diff --git a/.gitignore b/.gitignore index a85b177488a..1db9510e8be 100644 --- a/.gitignore +++ b/.gitignore @@ -1,5 +1,6 @@ # Exclude temporary and system files .DS_Store +*.swp # /flight/ /flight/*.pnproj diff --git a/Makefile b/Makefile index 4a216a226bb..f1ee0a101bd 100644 --- a/Makefile +++ b/Makefile @@ -839,9 +839,9 @@ endef # Start out assuming that we'll build fw, bl and bu for all boards FW_BOARDS := $(ALL_BOARDS) -BL_BOARDS := $(ALL_BOARDS) -BU_BOARDS := $(ALL_BOARDS) -EF_BOARDS := $(ALL_BOARDS) +BL_BOARDS := $(filter-out naze32, $(ALL_BOARDS)) +BU_BOARDS := $(BL_BOARDS) +EF_BOARDS := $(filter-out naze32, $(ALL_BOARDS)) # Sim targets are different for each host OS ifeq ($(UNAME), Linux) @@ -908,7 +908,7 @@ $(eval $(call SIM_TEMPLATE,simulation,Simulation,'sim ',posix,elf)) # ############################## -ALL_UNITTESTS := logfs i2c_vm misc_math sin_lookup coordinate_conversions error_correcting streamfs dsm timeutils +ALL_UNITTESTS := logfs i2c_vm misc_math coordinate_conversions error_correcting streamfs dsm timeutils ALL_PYTHON_UNITTESTS := python_ut_test UT_OUT_DIR := $(BUILD_DIR)/unit_tests diff --git a/flight/Libraries/frsky_packing.c b/flight/Libraries/frsky_packing.c new file mode 100644 index 00000000000..6570cbd708f --- /dev/null +++ b/flight/Libraries/frsky_packing.c @@ -0,0 +1,618 @@ +/** + ****************************************************************************** + * + * @file frsky_packing.c + * @author Tau Labs, http://taulabs.org, Copyright (C) 2015 + * @brief Packs UAVObjects into FrSKY Smart Port frames + * + * Since there is no public documentation of SmartPort protocol available, + * this was put together by studying OpenTx source code, reading + * tidbits of informations on the Internet and experimenting. + * @see https://github.com/opentx/opentx/tree/next/radio/src/telemetry + * @see https://code.google.com/p/telemetry-convert/wiki/FrSkySPortProtocol + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "frsky_packing.h" + +#include "modulesettings.h" +#include "misc_math.h" +#include "physical_constants.h" +#include "attitudeactual.h" +#include "baroaltitude.h" +#include "positionactual.h" +#include "velocityactual.h" +#include "flightbatterystate.h" +#include "flightbatterysettings.h" +#include "gpstime.h" +#include "homelocation.h" +#include "accels.h" +#include "flightstatus.h" +#include "airspeedactual.h" +#include "nedaccel.h" +#include "velocityactual.h" +#include "attitudeactual.h" +/** + * Encode baro altitude value + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_altitude(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (!frsky->use_baro_sensor || (PositionActualHandle() == NULL)) + return false; + + if (test_presence_only) + return true; + // instead of encoding baro altitude directly, we will use + // more accurate estimation in PositionActual UAVO + float down = 0; + PositionActualDownGet(&down); + int32_t alt = (int32_t)(-down * 100.0f); + *value = (uint32_t) alt; + return true; +} + +/** + * Encode heading value + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_gps_course(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (AttitudeActualHandle() == NULL) + return false; + + if (test_presence_only) + return true; + + AttitudeActualData attitude; + AttitudeActualGet(&attitude); + float hdg = (attitude.Yaw >= 0) ? attitude.Yaw : (attitude.Yaw + 360.0f); + *value = (uint32_t)(hdg * 100.0f); + + return true; +} + +/** + * Encode vertical speed value + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_vario(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (!frsky->use_baro_sensor || VelocityActualHandle() == NULL) + return false; + + if (test_presence_only) + return true; + + float down = 0; + VelocityActualDownGet(&down); + int32_t vspeed = (int32_t)(-down * 100.0f); + *value = (uint32_t) vspeed; + + return true; +} + +/** + * Encode battery current value + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_current(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (!frsky->use_current_sensor) + return false; + if (test_presence_only) + return true; + + float current = 0; + FlightBatteryStateCurrentGet(¤t); + int32_t current_frsky = (int32_t)(current * 10.0f); + *value = (uint32_t) current_frsky; + + return true; +} + +/** + * Encode battery cells voltage + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[], index of battery cell pair + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_cells(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if ((frsky->batt_cell_count == 0) || (frsky->batt_cell_count - 1) < (arg * 2)) + return false; + if (test_presence_only) + return true; + + float voltage = 0; + FlightBatteryStateVoltageGet(&voltage); + + uint32_t cell_voltage = (uint32_t)((voltage * 500.0f) / frsky->batt_cell_count); + *value = ((cell_voltage & 0xfff) << 8) | ((arg * 2) & 0x0f) | ((frsky->batt_cell_count << 4) & 0xf0); + if (((int16_t)frsky->batt_cell_count - 1) >= (arg * 2 + 1)) + *value |= ((cell_voltage & 0xfff) << 20); + + return true; +} + +/** + * Encode GPS status as T1 value + * Right-most two digits means visible satellite count, left-most digit has following meaning: + * 1 - no GPS connected + * 2 - no fix + * 3 - 2D fix + * 4 - 3D fix + * 5 - 3D fix and HomeLocation is SET - should be safe for navigation + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value successfully encoded or presence test passed + */ +bool frsky_encode_t1(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL) + return false; + + if (test_presence_only) + return true; + + uint8_t hl_set = HOMELOCATION_SET_FALSE; + + if (HomeLocationHandle()) + HomeLocationSetGet(&hl_set); + + int32_t t1 = 0; + switch (frsky->gps_position.Status) { + case GPSPOSITION_STATUS_NOGPS: + t1 = 100; + break; + case GPSPOSITION_STATUS_NOFIX: + t1 = 200; + break; + case GPSPOSITION_STATUS_FIX2D: + t1 = 300; + break; + case GPSPOSITION_STATUS_FIX3D: + case GPSPOSITION_STATUS_DIFF3D: + if (hl_set == HOMELOCATION_SET_TRUE) + t1 = 500; + else + t1 = 400; + break; + } + if (frsky->gps_position.Satellites > 0) + t1 += frsky->gps_position.Satellites; + + *value = (uint32_t)t1; + + return true; +} + +/** + * Encode GPS hDop and vDop as T2 + * Bits 0-7 = hDop * 100, max 255 (hDop = 2.55) + * Bits 8-15 = vDop * 100, max 255 (vDop = 2.55) + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value successfully encoded or presence test passed + */ +bool frsky_encode_t2(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL) + return false; + + if (test_presence_only) + return true; + + uint32_t hdop = (uint32_t)(frsky->gps_position.HDOP * 100.0f); + + if (hdop > 255) + hdop = 255; + + uint32_t vdop = (uint32_t)(frsky->gps_position.VDOP * 100.0f); + + if (vdop > 255) + vdop = 255; + + *value = 256 * vdop + hdop; + + return true; +} + +/** + * Encode consumed battery energy as fuel + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_fuel(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (!frsky->use_current_sensor) + return false; + if (test_presence_only) + return true; + + uint32_t capacity = frsky->battery_settings.Capacity; + float consumed_mahs = 0; + FlightBatteryStateConsumedEnergyGet(&consumed_mahs); + + float fuel = (uint32_t)(100.0f * (1.0f - consumed_mahs / capacity)); + fuel = bound_min_max(fuel, 0.0f, 100.0f); + *value = (uint32_t) fuel; + + return true; +} + +/** + * Encode configured values + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[]; 0=X, 1=Y, 2=Z + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_acc(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + uint8_t accelDataSettings; + ModuleSettingsFrskyAccelDataGet(&accelDataSettings); + + float acc = 0; + switch(accelDataSettings) { + case MODULESETTINGS_FRSKYACCELDATA_ACCELS: { + if (AccelsHandle() == NULL) + return false; + else if (test_presence_only) + return true; + + switch (arg) { + case 0: + AccelsxGet(&acc); + break; + case 1: + AccelsyGet(&acc); + break; + case 2: + AccelszGet(&acc); + break; + } + + acc /= GRAVITY; + acc *= 100.0f; + break; + } + + case MODULESETTINGS_FRSKYACCELDATA_NEDACCELS: { + if (NedAccelHandle() == NULL) + return false; + else if (test_presence_only) + return true; + + switch (arg) { + case 0: + NedAccelNorthGet(&acc); + break; + case 1: + NedAccelEastGet(&acc); + break; + case 2: + NedAccelDownGet(&acc); + break; + } + + acc /= GRAVITY; + acc *= 100.0f; + break; + } + + case MODULESETTINGS_FRSKYACCELDATA_NEDVELOCITY: { + if (VelocityActualHandle() == NULL) + return false; + else if (test_presence_only) + return true; + + switch (arg) { + case 0: + VelocityActualNorthGet(&acc); + break; + case 1: + VelocityActualEastGet(&acc); + break; + case 2: + VelocityActualDownGet(&acc); + break; + } + + acc *= 100.0f; + break; + } + + case MODULESETTINGS_FRSKYACCELDATA_ATTITUDEANGLES: { + if (AttitudeActualHandle() == NULL) + return false; + else if (test_presence_only) + return true; + + switch (arg) { + case 0: + AttitudeActualRollGet(&acc); + break; + case 1: + AttitudeActualPitchGet(&acc); + break; + case 2: + AttitudeActualYawGet(&acc); + break; + } + + acc *= 100.0f; + break; + } + } + + int32_t frsky_acc = (int32_t) acc; + *value = (uint32_t) frsky_acc; + + return true; +} + +/** + * Encode gps coordinates + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[]; 0=lattitude, 1=longitude + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_gps_coord(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL) + return false; + if (frsky->gps_position.Status == GPSPOSITION_STATUS_NOFIX + || frsky->gps_position.Status == GPSPOSITION_STATUS_NOGPS) + return false; + if (test_presence_only) + return true; + + uint32_t frsky_coord = 0; + int32_t coord = 0; + if (arg == 0) { + // lattitude + coord = frsky->gps_position.Latitude; + if (coord >= 0) + frsky_coord = 0; + else + frsky_coord = 1 << 30; + } else { + // longitude + coord = frsky->gps_position.Longitude; + if (coord >= 0) + frsky_coord = 2 << 30; + else + frsky_coord = 3 << 30; + } + coord = abs(coord); + frsky_coord |= (((uint64_t)coord * 6ull) / 100); + + *value = frsky_coord; + return true; +} + +/** + * Encode gps altitude + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_gps_alt(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL) + return false; + if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D + && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) + return false; + if (test_presence_only) + return true; + + int32_t frsky_gps_alt = (int32_t)(frsky->gps_position.Altitude * 100.0f); + *value = (uint32_t)frsky_gps_alt; + + return true; +} + +/** + * Encode gps speed + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_gps_speed(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL) + return false; + if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D + && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) + return false; + if (test_presence_only) + return true; + + int32_t frsky_speed = (int32_t)((frsky->gps_position.Groundspeed / KNOTS2M_PER_SECOND) * 1000); + *value = frsky_speed; + return true; +} + +/** + * Encode GPS UTC time + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[]; 0=date, 1=time + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_gps_time(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (GPSPositionHandle() == NULL || GPSTimeHandle() == NULL) + return false; + if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D + && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) + return false; + if (test_presence_only) + return true; + + GPSTimeData gps_time; + GPSTimeGet(&gps_time); + uint32_t frsky_time = 0; + + if (arg == 0) { + // encode date + frsky_time = 0x000000ff; + frsky_time |= gps_time.Day << 8; + frsky_time |= gps_time.Month << 16; + frsky_time |= (gps_time.Year % 100) << 24; + } else { + frsky_time = 0; + frsky_time |= gps_time.Second << 8; + frsky_time |= gps_time.Minute << 16; + frsky_time |= gps_time.Hour << 24; + } + *value = frsky_time; + return true; +} + +/** + * Encodes ARM status and flight mode number as RPM value + * Since there is no RPM information in any UAVO available, + * we will intentionaly misuse this item to encode another useful information. + * It will encode flight status as three-digit number as follow: + * most left digit encodes arm status (1=armed, 0=disarmed) + * two most right digits encodes flight mode number (see FlightStatus UAVO FlightMode enum) + * To work this propperly on Taranis, you have to set Blades to "1" in telemetry setting + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_rpm(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (FlightStatusHandle() == NULL) + return false; + if (test_presence_only) + return true; + + FlightStatusData flight_status; + FlightStatusGet(&flight_status); + + *value = (flight_status.Armed == FLIGHTSTATUS_ARMED_ARMED) ? 200 : 100; + *value += flight_status.FlightMode; + + return true; +} + +/** + * Encode true airspeed(TAS) + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +bool frsky_encode_airspeed(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + if (AirspeedActualHandle() == NULL) + return false; + if (test_presence_only) + return true; + + AirspeedActualData airspeed; + AirspeedActualGet(&airspeed); + int32_t frsky_speed = (int32_t)((airspeed.TrueAirspeed / KNOTS2M_PER_SECOND) * 10); + *value = (uint32_t)frsky_speed; + + return true; +} + +/** + * Performs byte stuffing and checksum calculation + * @param[out] obuff buffer where byte stuffed data will came in + * @param[in,out] chk checksum byte to update + * @param[in] byte + * @returns count of bytes inserted to obuff (1 or 2) + */ +uint8_t frsky_insert_byte(uint8_t *obuff, uint16_t *chk, uint8_t byte) +{ + /* checksum calculation is based on data before byte-stuffing */ + *chk += byte; + *chk += (*chk) >> 8; + *chk &= 0x00ff; + *chk += (*chk) >> 8; + *chk &= 0x00ff; + + if (byte == 0x7e || byte == 0x7d) { + obuff[0] = 0x7d; + obuff[1] = byte &= ~0x20; + return 2; + } + + obuff[0] = byte; + return 1; +} + +/** + * Send u32 value dataframe to FrSky SmartPort bus + * @param[in] id FrSky value ID + * @param[in] value value + */ +int32_t frsky_send_frame(uintptr_t com, enum frsky_value_id id, uint32_t value) +{ + /* each call of frsky_insert_byte can add 2 bytes to the buffer at maximum + * and therefore the worst-case is 15 bytes total (the first byte 0x10 won't be + * escaped) */ + uint8_t tx_data[15]; + uint16_t chk = 0; + uint8_t cnt = 0; + cnt += frsky_insert_byte(&tx_data[cnt], &chk, 0x10); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, (uint16_t)id & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, ((uint16_t)id >> 8) & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, value & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 8) & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 16) & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 24) & 0xff); + cnt += frsky_insert_byte(&tx_data[cnt], &chk, 0xff - chk); + + PIOS_COM_SendBuffer(com, tx_data, cnt); + + return cnt; +} + +/** + * @} + * @} + */ \ No newline at end of file diff --git a/flight/Libraries/inc/frsky_packing.h b/flight/Libraries/inc/frsky_packing.h new file mode 100644 index 00000000000..5ac1cec564f --- /dev/null +++ b/flight/Libraries/inc/frsky_packing.h @@ -0,0 +1,107 @@ +/** + ****************************************************************************** + * + * @file frsky_packing.h + * @author Tau Labs, http://taulabs.org, Copyright (C) 2015 + * @brief Packs UAVObjects into FrSKY Smart Port frames + * + * Since there is no public documentation of SmartPort protocol available, + * this was put together by studying OpenTx source code, reading + * tidbits of informations on the Internet and experimenting. + * @see https://github.com/opentx/opentx/tree/next/radio/src/telemetry + * @see https://code.google.com/p/telemetry-convert/wiki/FrSkySPortProtocol + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef FRSKY_PACKING_H +#define FRSKY_PACKING_H + +#include "pios.h" +#include "openpilot.h" + +#include "flightbatterysettings.h" +#include "gpsposition.h" + +struct frsky_settings { + bool use_current_sensor; + uint8_t batt_cell_count; + bool use_baro_sensor; + FlightBatterySettingsData battery_settings; + GPSPositionData gps_position; +}; + +enum frsky_value_id { + FRSKY_ALT_ID = 0x0100, + FRSKY_VARIO_ID = 0x110, + FRSKY_CURR_ID = 0x0200, + FRSKY_VFAS_ID = 0x0210, + FRSKY_CELLS_ID = 0x0300, + FRSKY_T1_ID = 0x0400, + FRSKY_T2_ID = 0x0410, + FRSKY_RPM_ID = 0x0500, + FRSKY_FUEL_ID = 0x0600, + FRSKY_ACCX_ID = 0x0700, + FRSKY_ACCY_ID = 0x0710, + FRSKY_ACCZ_ID = 0x0720, + FRSKY_GPS_LON_LAT_ID = 0x0800, + FRSKY_GPS_ALT_ID = 0x0820, + FRSKY_GPS_SPEED_ID = 0x0830, + FRSKY_GPS_COURSE_ID = 0x0840, + FRSKY_GPS_TIME_ID = 0x0850, + FRSKY_ADC3_ID = 0x0900, + FRSKY_ADC4_ID = 0x0910, + FRSKY_AIR_SPEED_ID = 0x0a00, + FRSKY_RSSI_ID = 0xf101, + FRSKY_ADC1_ID = 0xf102, + FRSKY_ADC2_ID = 0xf103, + FRSKY_BATT_ID = 0xf104, + FRSKY_SWR_ID = 0xf105, +}; + +struct frsky_value_item { + enum frsky_value_id id; + uint16_t period_ms; + bool (*encode_value)(struct frsky_settings *sport, uint32_t *value, bool test_presence_only, uint32_t arg); + uint32_t fn_arg; +}; + +bool frsky_encode_gps_course(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_altitude(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_vario(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_current(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_cells(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_t1(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_t2(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_fuel(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_acc(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_gps_coord(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_gps_alt(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_gps_speed(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_gps_time(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_rpm(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +bool frsky_encode_airspeed(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +uint8_t frsky_insert_byte(uint8_t *obuff, uint16_t *chk, uint8_t byte); +int32_t frsky_send_frame(uintptr_t com, enum frsky_value_id id, uint32_t value); + +#endif /* FRSKY_PACKING_H */ + +/** + * @} + * @} + */ diff --git a/flight/Libraries/inc/sanitycheck.h b/flight/Libraries/inc/sanitycheck.h index ff3a22de3f7..3454f91a014 100644 --- a/flight/Libraries/inc/sanitycheck.h +++ b/flight/Libraries/inc/sanitycheck.h @@ -27,10 +27,13 @@ #ifndef SANITYCHECK_H #define SANITYCHECK_H +#include "systemalarms.h" + extern int32_t configuration_check(); +void set_config_error(SystemAlarmsConfigErrorOptions error_code); #endif /* SANITYCHECK_H */ /** * @} - */ \ No newline at end of file + */ diff --git a/flight/Libraries/math/misc_math.c b/flight/Libraries/math/misc_math.c index 89021479ebe..f6687dfc108 100644 --- a/flight/Libraries/math/misc_math.c +++ b/flight/Libraries/math/misc_math.c @@ -28,6 +28,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include #include "misc_math.h" /* API declarations */ #include "physical_constants.h" @@ -113,6 +114,147 @@ float expo3(float x, int32_t g) return (x * ((100 - g) / 100.0f) + powf(x, 3) * (g / 100.0f)); } +/** + * Interpolate values (groundspeeds, altitudes) over flight legs + * @param[in] fraction how far we are through the leg + * @param[in] beginVal the configured value for the beginning of the leg + * @param[in] endVal the configured value for the end of the leg + * @returns the interpolated value + * + * Simple linear interpolation with clipping to ends (fraction>=0, <=1). + */ +float interpolate_value(const float fraction, const float beginVal, + const float endVal) { + return beginVal + (endVal - beginVal) * bound_min_max(fraction, 0, 1); +} + +/** + * Calculate pythagorean magnitude of a vector. + * @param[in] v pointer to a float array + * @param[in] n length of the amount to take the magnitude of + * @returns Root of sum of squares of the vector + * + * Note that sometimes we only take the magnitude of the first 2 elements + * of a 3-vector to get the horizontal component. + */ +float vectorn_magnitude(const float *v, int n) +{ + float sum=0; + + for (int i=0; i limit, vels=vels / mag(vels) * limit + */ +void vector2_clip(float *vels, float limit) +{ + float mag = vectorn_magnitude(vels, 2); // only horiz component + + if (mag > limit && mag != 0) { + float scale = limit / mag; + vels[0] *= scale; + vels[1] *= scale; + } +} + +/** + * Rotate a 2-vector by a specified angle. + * @param[in] original the input vector + * @param[out] out the rotated output vector + * @param[in] angle in degrees + */ +void vector2_rotate(const float *original, float *out, float angle) { + angle *= DEG2RAD; + + out[0] = original[0] * cosf(angle) - original[1] * sinf(angle); + out[1] = original[0] * sinf(angle) + original[1] * cosf(angle); +} + +/** + * Apply a "cubic deadband" to the input. + * @param[in] in the value to deadband + * @param[in] w deadband width + * @param[in] b slope of deadband at in=0 + * @param[in] m cubic weighting calculated by vtol_deadband_setup + * @param[in] r integrated response at in=w, calculated by vtol_deadband_setup + * + * "Real" deadbands are evil. Control systems end up fighting the edge. + * You don't teach your integrator about emerging drift. Discontinuities + * in your control inputs cause all kinds of neat stuff. As a result this + * calculates a cubic function within the deadband which has a low slope + * within the middle, but unity slope at the edge. + */ +float cubic_deadband(float in, float w, float b, float m, float r) +{ + // First get the nice linear bits -- outside the deadband-- out of + // the way. + if (in <= -w) { + return in+w-r; + } else if (in >= w) { + return in-w+r; + } + + return m * powf(in, 3) + b * in; +} + +/** + * Calculate the "cubic deadband" system parameters. + * @param[in] The width of the deadband + * @param[in] Slope of deadband at in=0, sane values between 0 and 1. + * @param[out] m cubic weighting of function + * @param[out] integrated response at in=w + */ +void cubic_deadband_setup(float w, float b, float *m, float *r) +{ + /* So basically.. we want the function to be tangent to the + ** linear sections-- have a slope of 1-- at -w and w. In the + ** middle we want a slope of b. So the cube here does all the + ** work b isn't doing. */ + *m = cbrtf((1-b)/(3*powf(w,2))); + + *r = *m * powf(w, 3) + b * w; +} + /** * @} diff --git a/flight/Libraries/math/misc_math.h b/flight/Libraries/math/misc_math.h index 815bcc06a0a..7a18a7088d0 100644 --- a/flight/Libraries/math/misc_math.h +++ b/flight/Libraries/math/misc_math.h @@ -31,7 +31,9 @@ #ifndef MISC_MATH_H #define MISC_MATH_H +#include #include "stdint.h" +#include "stdbool.h" // Max/Min macros. Taken from http://stackoverflow.com/questions/3437404/min-and-max-in-c #define MAX(a, b) ({ __typeof__ (a) _a = (a); __typeof__ (b) _b = (b); _a > _b ? _a : _b; }) @@ -53,6 +55,27 @@ float circular_modulus_rad(float err); //! Approximation an exponential scale curve float expo3(float x, int32_t g); +float interpolate_value(const float fraction, const float beginVal, + const float endVal); +float vectorn_magnitude(const float *v, int n); +float vector3_distances(const float *actual, + const float *desired, float *out, bool normalize); +void vector2_clip(float *vels, float limit); +void vector2_rotate(const float *original, float *out, float angle); +float cubic_deadband(float in, float w, float b, float m, float r); +void cubic_deadband_setup(float w, float b, float *m, float *r); + +/* Note--- current compiler chain has been verified to produce proper call + * to fpclassify even when compiling with -ffast-math / -ffinite-math. + * Previous attempts were made here to limit scope of disabling those + * optimizations to this function, but were infectious and increased + * stack usage across unrelated code because of compiler limitations. + * See TL issue #1879. + */ +static inline bool IS_NOT_FINITE(float x) { + return (!isfinite(x)); +} + #endif /* MISC_MATH_H */ /** diff --git a/flight/Libraries/math/sin_lookup.c b/flight/Libraries/math/sin_lookup.c deleted file mode 100644 index 78841e3bb34..00000000000 --- a/flight/Libraries/math/sin_lookup.c +++ /dev/null @@ -1,148 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsLibraries Tau Labs Libraries - * @{ - * @addtogroup TauLabsMath Tau Labs math support libraries - * @{ - * - * @file sin_lookup.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 - * @brief Fast lookup table based sin/cos functions - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "physical_constants.h" -#include "math.h" -#include "stdint.h" -#include "string.h" /* NULL */ - -#define FLASH_TABLE -#ifdef FLASH_TABLE - /** Version of the code which precomputes the lookup table in flash **/ - - // This is a precomputed sin lookup table over 90 degrees that - const float sin_table[] = { - 0.000000f,0.017452f,0.034899f,0.052336f,0.069756f,0.087156f,0.104528f,0.121869f,0.139173f,0.156434f, - 0.173648f,0.190809f,0.207912f,0.224951f,0.241922f,0.258819f,0.275637f,0.292372f,0.309017f,0.325568f, - 0.342020f,0.358368f,0.374607f,0.390731f,0.406737f,0.422618f,0.438371f,0.453990f,0.469472f,0.484810f, - 0.500000f,0.515038f,0.529919f,0.544639f,0.559193f,0.573576f,0.587785f,0.601815f,0.615661f,0.629320f, - 0.642788f,0.656059f,0.669131f,0.681998f,0.694658f,0.707107f,0.719340f,0.731354f,0.743145f,0.754710f, - 0.766044f,0.777146f,0.788011f,0.798636f,0.809017f,0.819152f,0.829038f,0.838671f,0.848048f,0.857167f, - 0.866025f,0.874620f,0.882948f,0.891007f,0.898794f,0.906308f,0.913545f,0.920505f,0.927184f,0.933580f, - 0.939693f,0.945519f,0.951057f,0.956305f,0.961262f,0.965926f,0.970296f,0.974370f,0.978148f,0.981627f, - 0.984808f,0.987688f,0.990268f,0.992546f,0.994522f,0.996195f,0.997564f,0.998630f,0.999391f,0.999848f, - 1.000000f,0.999848f,0.999391f,0.998630f,0.997564f,0.996195f,0.994522f,0.992546f,0.990268f,0.987688f, - 0.984808f,0.981627f,0.978148f,0.974370f,0.970296f,0.965926f,0.961262f,0.956305f,0.951057f,0.945519f, - 0.939693f,0.933580f,0.927184f,0.920505f,0.913545f,0.906308f,0.898794f,0.891007f,0.882948f,0.874620f, - 0.866025f,0.857167f,0.848048f,0.838671f,0.829038f,0.819152f,0.809017f,0.798636f,0.788011f,0.777146f, - 0.766044f,0.754710f,0.743145f,0.731354f,0.719340f,0.707107f,0.694658f,0.681998f,0.669131f,0.656059f, - 0.642788f,0.629320f,0.615661f,0.601815f,0.587785f,0.573576f,0.559193f,0.544639f,0.529919f,0.515038f, - 0.500000f,0.484810f,0.469472f,0.453990f,0.438371f,0.422618f,0.406737f,0.390731f,0.374607f,0.358368f, - 0.342020f,0.325568f,0.309017f,0.292372f,0.275637f,0.258819f,0.241922f,0.224951f,0.207912f,0.190809f, - 0.173648f,0.156434f,0.139173f,0.121869f,0.104528f,0.087156f,0.069756f,0.052336f,0.034899f,0.017452f - }; - -int sin_lookup_initialize() -{ - return 0; -} - -#else -/** Version of the code which allocates the lookup table in heap **/ - -const int SIN_RESOLUTION = 180; - -static float *sin_table; -int sin_lookup_initialize() -{ - // Previously initialized - if (sin_table) - return 0; - - sin_table = (float *) PIOS_malloc(sizeof(float) * SIN_RESOLUTION); - if (sin_table == NULL) - return -1; - - for(uint32_t i = 0; i < 180; i++) - sin_table[i] = sinf((float)i * DEG2RAD); - - return 0; -} - -#endif - -/** - * Use the lookup table to return sine(angle) where angle is in degrees - * @param[in] angle Angle in degrees - * @returns sin(angle) -*/ -float sin_lookup_deg(float angle) -{ -#ifndef SIM_POSIX - if (sin_table == NULL) - return 0; -#endif - - int i_ang = ((int32_t) angle) % 360; - if (i_ang >= 180) // for 180 to 360 deg - return -sin_table[i_ang - 180]; - else // for 0 to 179 deg - return sin_table[i_ang]; - - return 0; -} - -/** - * Get cos(angle) using the sine lookup table - * @param[in] angle Angle in degrees - * @returns cos(angle) - */ -float cos_lookup_deg(float angle) -{ - return sin_lookup_deg(angle + 90); -} - -/** - * Use the lookup table to return sine(angle) where angle is in radians - * @param[in] angle Angle in radians - * @returns sin(angle) - */ -float sin_lookup_rad(float angle) -{ - int degrees = angle * RAD2DEG; - return sin_lookup_deg(degrees); -} - -/** - * Use the lookup table to return sine(angle) where angle is in radians - * @param[in] angle Angle in radians - * @returns cos(angle) - */ -float cos_lookup_rad(float angle) -{ - int degrees = angle * RAD2DEG; - return cos_lookup_deg(degrees); -} - -/** - * @} - * @} - */ diff --git a/flight/Libraries/math/sin_lookup.h b/flight/Libraries/math/sin_lookup.h deleted file mode 100644 index 285d5ac2797..00000000000 --- a/flight/Libraries/math/sin_lookup.h +++ /dev/null @@ -1,46 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsLibraries Tau Labs Libraries - * @{ - * @addtogroup TauLabsMath Tau Labs math support libraries - * @{ - * - * @file sin_lookup.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Fast lookup table based sin/cos functions - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef SIN_LOOKUP_H -#define SIN_LOOKUP_H - -int sin_lookup_initialize(); -float sin_lookup_deg(float angle); -float cos_lookup_deg(float angle); -float sin_lookup_rad(float angle); -float cos_lookup_rad(float angle); - -#endif - -/** - * @} - * @} - */ \ No newline at end of file diff --git a/flight/Libraries/mavlink/v1.0/common/custom_types.h b/flight/Libraries/mavlink/v1.0/common/custom_types.h new file mode 100644 index 00000000000..15773a23d27 --- /dev/null +++ b/flight/Libraries/mavlink/v1.0/common/custom_types.h @@ -0,0 +1,22 @@ +/* Dervied from minimosd-extra code at https://github.com/diydrones/MinimOSD-Extra/blob/master/MinimOsd-Extra/OSD_Panels.ino (GPLv3) */ + + +#ifndef _CUSTOM_TYPES_H +#define _CUSTOM_TYPES_H + +#define CUSTOM_MODE_STAB 0 +#define CUSTOM_MODE_ACRO 1 +#define CUSTOM_MODE_ALTH 2 +#define CUSTOM_MODE_AUTO 3 +#define CUSTOM_MODE_GUIDED 4 +#define CUSTOM_MODE_LOITER 5 +#define CUSTOM_MODE_RTL 6 /* Return to "launch" */ +#define CUSTOM_MODE_CIRCLE 7 +#define CUSTOM_MODE_POSH 8 /* so posh. */ +#define CUSTOM_MODE_LAND 9 +#define CUSTOM_MODE_OFLOITER 10 /* whatever that is. */ +#define CUSTOM_MODE_DRIFT 11 +#define CUSTOM_MODE_SPORT 13 +#define CUSTOM_MODE_PHLD 16 /* The other position hold */ + +#endif diff --git a/flight/Libraries/sanitycheck.c b/flight/Libraries/sanitycheck.c index 1aa9f9de2bf..7922cc6f525 100644 --- a/flight/Libraries/sanitycheck.c +++ b/flight/Libraries/sanitycheck.c @@ -3,7 +3,7 @@ * @addtogroup TauLabsLibraries Tau Labs Libraries * @{ * @file sanitycheck.c - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief Utilities to validate a flight configuration * @see The GNU Public License (GPL) Version 3 * @@ -55,9 +55,6 @@ static int32_t check_stabilization_rates(); //! Check the system is safe for autonomous flight static int32_t check_safe_autonomous(); -//! Set the error code and alarm state -static void set_config_error(SystemAlarmsConfigErrorOptions error_code); - /** * Run a preflight check over the hardware configuration * and currently active modules @@ -114,6 +111,7 @@ int32_t configuration_check() } break; case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ACRO: + case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_ACROPLUS: case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_LEVELING: case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_MWRATE: case MANUALCONTROLSETTINGS_FLIGHTMODEPOSITION_HORIZON: @@ -266,6 +264,7 @@ static int32_t check_safe_to_arm() switch (flightStatus.FlightMode) { case FLIGHTSTATUS_FLIGHTMODE_MANUAL: case FLIGHTSTATUS_FLIGHTMODE_ACRO: + case FLIGHTSTATUS_FLIGHTMODE_ACROPLUS: case FLIGHTSTATUS_FLIGHTMODE_LEVELING: case FLIGHTSTATUS_FLIGHTMODE_MWRATE: case FLIGHTSTATUS_FLIGHTMODE_HORIZON: @@ -300,7 +299,7 @@ static int32_t check_safe_autonomous() // INSIndoor | INS (unsafe) -#if !defined(COPTERCONTROL) +#if !defined(SMALLF1) StateEstimationData stateEstimation; StateEstimationGet(&stateEstimation); @@ -342,28 +341,38 @@ static int32_t check_stabilization_rates() * Set the error code and alarm state * @param[in] error code */ -static void set_config_error(SystemAlarmsConfigErrorOptions error_code) +void set_config_error(SystemAlarmsConfigErrorOptions error_code) { // Get the severity of the alarm given the error code SystemAlarmsAlarmOptions severity; + + static bool sticky = false; + + /* Once a sticky error occurs, never change the error code */ + if (sticky) return; + switch (error_code) { case SYSTEMALARMS_CONFIGERROR_NONE: severity = SYSTEMALARMS_ALARM_OK; break; - case SYSTEMALARMS_CONFIGERROR_STABILIZATION: - case SYSTEMALARMS_CONFIGERROR_MULTIROTOR: + default: + error_code = SYSTEMALARMS_CONFIGERROR_UNDEFINED; + /* and fall through */ + + case SYSTEMALARMS_CONFIGERROR_DUPLICATEPORTCFG: + sticky = true; + /* and fall through */ case SYSTEMALARMS_CONFIGERROR_AUTOTUNE: case SYSTEMALARMS_CONFIGERROR_ALTITUDEHOLD: - case SYSTEMALARMS_CONFIGERROR_POSITIONHOLD: - case SYSTEMALARMS_CONFIGERROR_PATHPLANNER: + case SYSTEMALARMS_CONFIGERROR_MULTIROTOR: case SYSTEMALARMS_CONFIGERROR_NAVFILTER: + case SYSTEMALARMS_CONFIGERROR_PATHPLANNER: + case SYSTEMALARMS_CONFIGERROR_POSITIONHOLD: + case SYSTEMALARMS_CONFIGERROR_STABILIZATION: + case SYSTEMALARMS_CONFIGERROR_UNDEFINED: case SYSTEMALARMS_CONFIGERROR_UNSAFETOARM: severity = SYSTEMALARMS_ALARM_ERROR; break; - default: - severity = SYSTEMALARMS_ALARM_ERROR; - error_code = SYSTEMALARMS_CONFIGERROR_UNDEFINED; - break; } // Make sure not to set the error code if it didn't change diff --git a/flight/Libraries/timeutils.c b/flight/Libraries/timeutils.c index 35498c6bc41..9971728c47f 100644 --- a/flight/Libraries/timeutils.c +++ b/flight/Libraries/timeutils.c @@ -57,16 +57,7 @@ void date_from_timestamp(uint32_t timestamp, DateTimeT *date_time) days = timestamp / SECS_PER_DAY; rem = timestamp % SECS_PER_DAY; - while (rem < 0) - { - rem += SECS_PER_DAY; - --days; - } - while (rem >= SECS_PER_DAY) - { - rem -= SECS_PER_DAY; - ++days; - } + date_time->hour = rem / SECS_PER_HOUR; rem %= SECS_PER_HOUR; date_time->min = rem / 60; diff --git a/flight/Modules/Actuator/actuator.c b/flight/Modules/Actuator/actuator.c index 4709b7a00fe..336c89da8ef 100644 --- a/flight/Modules/Actuator/actuator.c +++ b/flight/Modules/Actuator/actuator.c @@ -78,7 +78,9 @@ static volatile bool mixer_settings_updated; static void actuatorTask(void* parameters); static float scaleChannel(float value, float max, float min, float neutral); static void setFailsafe(const ActuatorSettingsData * actuatorSettings, const MixerSettingsData * mixerSettings); -static float MixerCurve(const float throttle, const float* curve, uint8_t elements); +static float MixerCurve(const float input, const float* curve, uint8_t num_points, const float input_min, const float input_max); +static float ThrottleCurve(const float input, const float* curve, uint8_t num_points); +static float CollectiveCurve(const float input, const float* curve, uint8_t num_points); static bool set_channel(uint8_t mixer_channel, float value, const ActuatorSettingsData * actuatorSettings); static void actuator_update_rate_if_changed(const ActuatorSettingsData * actuatorSettings, bool force_update); static void MixerSettingsUpdatedCb(UAVObjEvent * ev); @@ -239,29 +241,27 @@ static void actuatorTask(void* parameters) bool positiveThrottle = desired.Throttle >= 0.00f; bool spinWhileArmed = actuatorSettings.MotorsSpinWhileArmed == ACTUATORSETTINGS_MOTORSSPINWHILEARMED_TRUE; - float curve1 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve1,MIXERSETTINGS_THROTTLECURVE1_NUMELEM); - + float curve1 = ThrottleCurve(desired.Throttle, mixerSettings.ThrottleCurve1, MIXERSETTINGS_THROTTLECURVE1_NUMELEM); + //The source for the secondary curve is selectable float curve2 = 0; AccessoryDesiredData accessory; switch(mixerSettings.Curve2Source) { case MIXERSETTINGS_CURVE2SOURCE_THROTTLE: - curve2 = MixerCurve(desired.Throttle,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(desired.Throttle, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_ROLL: - curve2 = MixerCurve(desired.Roll,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(desired.Roll, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_PITCH: - curve2 = MixerCurve(desired.Pitch,mixerSettings.ThrottleCurve2, - MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(desired.Pitch, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_YAW: - curve2 = MixerCurve(desired.Yaw,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(desired.Yaw, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_COLLECTIVE: ManualControlCommandCollectiveGet(&curve2); - curve2 = MixerCurve(curve2,mixerSettings.ThrottleCurve2, - MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(curve2, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); break; case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0: case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY1: @@ -270,7 +270,7 @@ static void actuatorTask(void* parameters) case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY4: case MIXERSETTINGS_CURVE2SOURCE_ACCESSORY5: if(AccessoryDesiredInstGet(mixerSettings.Curve2Source - MIXERSETTINGS_CURVE2SOURCE_ACCESSORY0,&accessory) == 0) - curve2 = MixerCurve(accessory.AccessoryVal,mixerSettings.ThrottleCurve2,MIXERSETTINGS_THROTTLECURVE2_NUMELEM); + curve2 = CollectiveCurve(accessory.AccessoryVal, mixerSettings.ThrottleCurve2, MIXERSETTINGS_THROTTLECURVE2_NUMELEM); else curve2 = 0; break; @@ -413,37 +413,74 @@ float ProcessMixer(const int index, const float curve1, const float curve2, return(result); } - /** - *Interpolate a throttle curve. Throttle input should be in the range 0 to 1. - *Output is in the range 0 to 1. + * Interpolate a mixer curve + * + * output range is defined by the curve vector + * curve is defined in N intervals connecting N+1 points + * + * @param input the input value, in [input_min,input_max] + * @param curve the array of points in the curve + * @param num_points the number of points in the curve + * @param input_min the lower range of the input values + * @param input_max the upper range of the input values + * @return the output value, in [0,1] */ -static float MixerCurve(const float throttle, const float* curve, uint8_t elements) +static float MixerCurve(float const input, float const * curve, uint8_t num_points, const float input_min, const float input_max) { - float scale = throttle * (float) (elements - 1); + // shift our input [min,max] into the typical range [0,1] + float scale = fmaxf( (input - input_min) / (input_max - input_min), 0.0f) * (float) (num_points - 1); + // select a starting bin via truncation int idx1 = scale; - scale -= (float)idx1; //remainder - if(curve[0] < -1) - { - return(throttle); - } - if (idx1 < 0) - { - idx1 = 0; //clamp to lowest entry in table - scale = 0; - } + // save the offset from the starting bin for linear interpolation + scale -= (float)idx1; + // select an ending bin (linear interpolation occurs between starting and ending bins) int idx2 = idx1 + 1; - if(idx2 >= elements) - { - idx2 = elements -1; //clamp to highest entry in table - if(idx1 >= elements) - { - idx1 = elements -1; + // if the ending bin bin is above the last bin + if (idx2 >= num_points) { + //clamp to highest entry in table + idx2 = num_points -1; + // if the starting bin is above the last bin + if (idx1 >= num_points) { + // we no longer do interpolation; instead, we just select the max point on the curve + return curve[num_points-1]; } } return curve[idx1] * (1.0f - scale) + curve[idx2] * scale; } +/** + * Interpolate a throttle curve + * + * throttle curve assumes input is [0,1] + * this means that the throttle channel neutral value is nearly the same as its min value + * this is convenient for throttle, since the neutral value is used as a failsafe and would thus shut off the motor + * + * @param input the input value, in [0,1] + * @param curve the array of points in the curve + * @param num_points the number of points in the curve + * @return the output value, in [0,1] + */ +static float ThrottleCurve(float const input, float const * curve, uint8_t num_points) +{ + return MixerCurve(input, curve, num_points, 0.0f, 1.0f); +} + +/** + * Interpolate a collective curve + * + * we need to accept input in [-1,1] so that the neutral point may be set arbitrarily within the typical channel input range, which is [-1,1] + * + * @param input The input value, in [-1,1] + * @param curve Array of points in the curve + * @param num_points Number of points in the curve + * @return the output value, in [-1,1] + */ +static float CollectiveCurve(float const input, float const * curve, uint8_t num_points) +{ + return MixerCurve(input, curve, num_points, -1.0f, 1.0f); +} + /** * Convert channel from -1/+1 to servo pulse duration in microseconds diff --git a/flight/Modules/AltitudeHold/altitudehold.c b/flight/Modules/AltitudeHold/altitudehold.c index 45b60a68883..ddcaf3f276f 100644 --- a/flight/Modules/AltitudeHold/altitudehold.c +++ b/flight/Modules/AltitudeHold/altitudehold.c @@ -59,7 +59,7 @@ // Private constants #define MAX_QUEUE_SIZE 4 -#define STACK_SIZE_BYTES 600 +#define STACK_SIZE_BYTES 648 #define TASK_PRIORITY PIOS_THREAD_PRIO_LOW // Private variables diff --git a/flight/Modules/Attitude/attitude.c b/flight/Modules/Attitude/attitude.c index 323a3ac7c1a..782dba84ac1 100644 --- a/flight/Modules/Attitude/attitude.c +++ b/flight/Modules/Attitude/attitude.c @@ -46,10 +46,16 @@ * simple filter to smooth the altitude. */ -#include "pios.h" #include "openpilot.h" +#include "pios.h" +#include "pios_thread.h" +#include "pios_queue.h" +#include "misc_math.h" #include "physical_constants.h" +#include "coordinate_conversions.h" +#include "WorldMagModel.h" +// UAVOs #include "accels.h" #include "attitudeactual.h" #include "attitudesettings.h" @@ -71,10 +77,6 @@ #include "stateestimation.h" #include "systemalarms.h" #include "velocityactual.h" -#include "coordinate_conversions.h" -#include "WorldMagModel.h" -#include "pios_thread.h" -#include "pios_queue.h" // Private constants #define STACK_SIZE_BYTES 2200 @@ -595,8 +597,9 @@ static int32_t updateAttitudeComplementary(bool first_run, bool secondary, bool MagnetometerData mag; MagnetometerGet(&mag); - // If the mag is producing bad data (NAN) don't use it (normally bad calibration) - if (mag.x == mag.x && mag.y == mag.y && mag.z == mag.z) { + // Only use the magnetometer data if it is good, i.e. not NAN. A NAN would + // normally only arise due to a bad magnetometer calibration. + if (!(IS_NOT_FINITE(mag.x) || IS_NOT_FINITE(mag.y) || IS_NOT_FINITE(mag.z))) { float bmag = 1.0f; float brot[3]; float Rbe[3][3]; @@ -676,9 +679,9 @@ static int32_t updateAttitudeComplementary(bool first_run, bool secondary, bool cf_q[2] = cf_q[2] / qmag; cf_q[3] = cf_q[3] / qmag; - // If quaternion has become inappropriately short or is nan reinit. + // If quaternion has become inappropriately short or has become Nan reinit. // THIS SHOULD NEVER ACTUALLY HAPPEN - if((fabsf(qmag) < 1.0e-3f) || (qmag != qmag)) { + if((fabsf(qmag) < 1.0e-3f) || IS_NOT_FINITE(qmag)) { cf_q[0] = 1; cf_q[1] = 0; cf_q[2] = 0; @@ -1015,14 +1018,14 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) GPSVelocityGet(&gpsVelData); // Discard mag if it has NAN (normally from bad calibration) - mag_updated &= (magData.x == magData.x && magData.y == magData.y && magData.z == magData.z); + mag_updated &= !(IS_NOT_FINITE(magData.x) || IS_NOT_FINITE(magData.y) || IS_NOT_FINITE(magData.z)); // Indoor mode will fall back to reasonable Be and that is ok. For outdoor make sure home // Be is set and a good value mag_updated &= !outdoor_mode || (homeLocation.Be[0] != 0 || homeLocation.Be[1] != 0 || homeLocation.Be[2]); // A more stringent requirement for GPS to initialize the filter - bool gps_init_usable = gps_updated & (gpsData.Satellites >= 7) && (gpsData.PDOP <= 3.5f) && (homeLocation.Set == HOMELOCATION_SET_TRUE); + bool gps_init_usable = gps_updated && (gpsData.Satellites >= 7) && (gpsData.PDOP <= 3.5f) && (homeLocation.Set == HOMELOCATION_SET_TRUE); // Set user-friendly alarms appropriately based on state if (ins_state == INS_INIT) { @@ -1057,6 +1060,8 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) INSSetAccelVar(insSettings.AccelVar); INSSetGyroVar(insSettings.GyroVar); INSSetBaroVar(insSettings.BaroVar); + /* This is more optimistic than in the actual flight loop, where + * ublox accuracy data is added. But that seems OK */ INSSetPosVelVar(insSettings.GpsVar[INSSETTINGS_GPSVAR_POS], insSettings.GpsVar[INSSETTINGS_GPSVAR_VEL], insSettings.GpsVar[INSSETTINGS_GPSVAR_VERTPOS]); // Initialize the gyro bias from the settings @@ -1208,6 +1213,32 @@ static int32_t updateAttitudeINSGPS(bool first_run, bool outdoor_mode) gps_vel_updated = false; } + // If either vel or pos is updated, update the variances. + if (gps_updated || gps_vel_updated) { + // Typical good pos 'accuracy' values are 2.5-3.5. Early + // flight is near 4.0. + // Typical bad pos 'accuracy' values are 10+ + // The values here are fudged. Basically, when GPS is + // "good" we'll have a lower variance than the nominal + // setting. But from there it will increase really quickly. + // sqrt(.5) / 3.5 =~ 0.181f + float pos_var = insSettings.GpsVar[INSSETTINGS_GPSVAR_POS] * + (0.6f + powf(gpsData.Accuracy * 0.180f, 2)); + + // A good value of speed accuracy in flight is 0.35-0.5. + // sqrt(.5) / .5 =~ 1.414 + float speed_var = insSettings.GpsVar[INSSETTINGS_GPSVAR_VEL] * + (0.5f + powf(gpsVelData.Accuracy * 1.414f, 2)); + + float v_pos_var = insSettings.GpsVar[INSSETTINGS_GPSVAR_VERTPOS] + + (0.7f + powf(gpsData.Accuracy * 0.167f, 3.0)); + + // We trust the vertical much less as accuracy gets worse. + // cuberoot(.3)/4.0 =~ .167 + + INSSetPosVelVar(pos_var, speed_var, v_pos_var); + } + // Update fake position at 10 hz static uint32_t indoor_pos_time; if (!outdoor_mode && PIOS_DELAY_DiffuS(indoor_pos_time) > 100000) { @@ -1429,6 +1460,7 @@ static void settingsUpdatedCb(UAVObjEvent * ev) INSSetAccelVar(insSettings.AccelVar); INSSetGyroVar(insSettings.GyroVar); INSSetBaroVar(insSettings.BaroVar); + /* Don't set GPS variance here, because the flight loop does */ } if(ev == NULL || ev->obj == HomeLocationHandle()) { uint8_t armed; diff --git a/flight/Modules/Attitude/coptercontrol/attitude.c b/flight/Modules/Attitude/smallf1/attitude.c similarity index 88% rename from flight/Modules/Attitude/coptercontrol/attitude.c rename to flight/Modules/Attitude/smallf1/attitude.c index 6f55efe9ae7..ff389a7db55 100644 --- a/flight/Modules/Attitude/coptercontrol/attitude.c +++ b/flight/Modules/Attitude/smallf1/attitude.c @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup TauLabsModules Tau Labs Modules * @{ - * @addtogroup AttitudeModuleCC Copter Control Attitude Estimation + * @addtogroup AttitudeModuleSmallF1 Attitude estimation for small F1 boards * @{ * @brief Minimal code for attitude estimation with integrated sensors * @@ -13,8 +13,8 @@ * * @file attitude.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 - * @brief Update attitude for CC(3D) + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 + * @brief Update attitude for F1 targets * * @see The GNU Public License (GPL) Version 3 * @@ -47,7 +47,6 @@ #include "manualcontrolcommand.h" #include "coordinate_conversions.h" #include -#include "pios_thread.h" #include "pios_queue.h" // Private constants @@ -73,15 +72,21 @@ static SensorSettingsData sensorSettings; static void AttitudeTask(void *parameters); static float gyro_correct_int[3] = {0,0,0}; + +#ifdef COPTERCONTROL static struct pios_queue *gyro_queue; static int32_t updateSensors(AccelsData *, GyrosData *); -static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData); +#define ADXL345_ACCEL_SCALE (GRAVITY * 0.004f) +/* 0.004f is gravity / LSB */ + +#endif + +static int32_t updateSensorsDigital(AccelsData * accelsData, GyrosData * gyrosData); static void updateAttitude(AccelsData *, GyrosData *); static void settingsUpdatedCb(UAVObjEvent * objEv); static void update_accels(struct pios_sensor_accel_data *accels, AccelsData * accelsData); static void update_gyros(struct pios_sensor_gyro_data *gyros, GyrosData * gyrosData); -static void update_trimming(AccelsData * accelsData); static void updateTemperatureComp(float temperature, float *temp_bias); //! Compute the mean gyro accumulated and assign the bias @@ -110,15 +115,6 @@ static bool accumulating_gyro = false; static uint32_t accumulated_gyro_samples = 0; static float accumulated_gyro[3]; -// For running trim flights -static volatile bool trim_requested = false; -static volatile int32_t trim_accels[3]; -static volatile int32_t trim_samples; -static int32_t const MAX_TRIM_FLIGHT_SAMPLES = 65535; - -#define ADXL345_ACCEL_SCALE (GRAVITY * 0.004f) -/* 0.004f is gravity / LSB */ - /** * Initialise the module, called on startup * \returns 0 on success or -1 if initialisation failed @@ -168,8 +164,6 @@ int32_t AttitudeInitialize(void) for(uint8_t j = 0; j < 3; j++) Rsb[i][j] = 0; - trim_requested = false; - AttitudeSettingsConnectCallback(&settingsUpdatedCb); SensorSettingsConnectCallback(&settingsUpdatedCb); @@ -184,15 +178,16 @@ MODULE_INITCALL(AttitudeInitialize, AttitudeStart) static void AttitudeTask(void *parameters) { AlarmsClear(SYSTEMALARMS_ALARM_ATTITUDE); - + +#ifdef COPTERCONTROL // Set critical error and wait until the accel is producing data while(PIOS_ADXL345_FifoElements() == 0) { AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_CRITICAL); PIOS_WDG_UpdateFlag(PIOS_WDG_ATTITUDE); } - + const struct pios_board_info * bdinfo = &pios_board_info_blob; - + bool cc3d = bdinfo->board_rev == 0x02; if (!cc3d) { @@ -205,7 +200,8 @@ static void AttitudeTask(void *parameters) PIOS_SENSORS_SetMaxGyro(500); #endif } - +#endif + // Force settings update to make sure rotation loaded settingsUpdatedCb(AttitudeSettingsHandle()); @@ -286,10 +282,14 @@ static void AttitudeTask(void *parameters) GyrosData gyros; int32_t retval = 0; +#ifdef COPTERCONTROL if (cc3d) - retval = updateSensorsCC3D(&accels, &gyros); + retval = updateSensorsDigital(&accels, &gyros); else retval = updateSensors(&accels, &gyros); +#else + retval = updateSensorsDigital(&accels, &gyros); +#endif // During power on set to angle from accel if (complimentary_filter_status == CF_POWERON) { @@ -314,6 +314,7 @@ static void AttitudeTask(void *parameters) } } +#ifdef COPTERCONTROL /** * Get an update from the sensors * @param[in] attitudeRaw Populate the UAVO instead of saving right here @@ -323,7 +324,7 @@ static int32_t updateSensors(AccelsData * accelsData, GyrosData * gyrosData) { struct pios_adxl345_data accel_data; float gyro[4]; - + // Only wait the time for two nominal updates before setting an alarm if (PIOS_Queue_Receive(gyro_queue, (void * const) gyro, PIOS_INTERNAL_ADC_UPDATE_RATE * 2) == false) { AlarmsSet(SYSTEMALARMS_ALARM_ATTITUDE, SYSTEMALARMS_ALARM_ERROR); @@ -337,14 +338,14 @@ static int32_t updateSensors(AccelsData * accelsData, GyrosData * gyrosData) // No accel data available if(PIOS_ADXL345_FifoElements() == 0) return -1; - + // Convert the ADC data into the standard normalized format struct pios_sensor_gyro_data gyros; gyros.temperature = gyro[0]; gyros.x = -(gyro[1] - GYRO_NEUTRAL) * IDG_GYRO_GAIN; gyros.y = (gyro[2] - GYRO_NEUTRAL) * IDG_GYRO_GAIN; gyros.z = -(gyro[3] - GYRO_NEUTRAL) * IDG_GYRO_GAIN; - + // Convert the ADXL345 data into the standard normalized format int32_t x = 0; int32_t y = 0; @@ -360,7 +361,7 @@ static int32_t updateSensors(AccelsData * accelsData, GyrosData * gyrosData) } while ( (i < 32) && (samples_remaining > 0) ); struct pios_sensor_accel_data accels; - + accels.x = ((float) x / i) * ADXL345_ACCEL_SCALE; accels.y = ((float) y / i) * ADXL345_ACCEL_SCALE; accels.z = ((float) z / i) * ADXL345_ACCEL_SCALE; @@ -368,23 +369,20 @@ static int32_t updateSensors(AccelsData * accelsData, GyrosData * gyrosData) // Apply rotation / calibration and assign to the UAVO update_gyros(&gyros, gyrosData); update_accels(&accels, accelsData); - - update_trimming(accelsData); - - GyrosSet(gyrosData); AccelsSet(accelsData); return 0; } +#endif /** * Get an update from the sensors * @param[in] attitudeRaw Populate the UAVO instead of saving right here * @return 0 if successfull, -1 if not */ -static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) +static int32_t updateSensorsDigital(AccelsData * accelsData, GyrosData * gyrosData) { struct pios_sensor_gyro_data gyros; struct pios_sensor_accel_data accels; @@ -408,8 +406,6 @@ static int32_t updateSensorsCC3D(AccelsData * accelsData, GyrosData * gyrosData) // the accels to be available first update_gyros(&gyros, gyrosData); - update_trimming(accelsData); - GyrosSet(gyrosData); AccelsSet(accelsData); @@ -542,31 +538,6 @@ static void accumulate_gyro(float gyros_out[3]) accumulated_gyro[2] += gyros_out[2]; } -/** - * @brief If requested accumulate accel values to calculate level - * @param[in] accelsData the scaled and normalized accels - */ -static void update_trimming(AccelsData * accelsData) -{ - if (trim_requested) { - if (trim_samples >= MAX_TRIM_FLIGHT_SAMPLES) { - trim_requested = false; - } else { - uint8_t armed; - float throttle; - FlightStatusArmedGet(&armed); - ManualControlCommandThrottleGet(&throttle); // Until flight status indicates airborne - if ((armed == FLIGHTSTATUS_ARMED_ARMED) && (throttle > 0)) { - trim_samples++; - // Store the digitally scaled version since that is what we use for bias - trim_accels[0] += accelsData->x; - trim_accels[1] += accelsData->y; - trim_accels[2] += accelsData->z; - } - } - } -} - static inline void apply_accel_filter(const float * raw, float * filtered) { if(accel_filter_enabled) { @@ -773,52 +744,6 @@ static void settingsUpdatedCb(UAVObjEvent * objEv) { Quaternion2R(rotationQuat, Rsb); rotate = 1; } - - if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_START) { - trim_accels[0] = 0; - trim_accels[1] = 0; - trim_accels[2] = 0; - trim_samples = 0; - trim_requested = true; - } else if (attitudeSettings.TrimFlight == ATTITUDESETTINGS_TRIMFLIGHT_LOAD) { - trim_requested = false; - - // Get sensor data mean - float a_body[3] = { trim_accels[0] / trim_samples, - trim_accels[1] / trim_samples, - trim_accels[2] / trim_samples - }; - - // Inverse rotation of sensor data, from body frame into sensor frame - float a_sensor[3]; - rot_mult(Rsb, a_body, a_sensor, false); - - // Temporary variables - float psi, theta, phi; - - psi = attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_YAW] * DEG2RAD / 100.0f; - - float cP = cosf(psi); - float sP = sinf(psi); - - // In case psi is too small, we have to use a different equation to solve for theta - if (fabsf(psi) > PI / 2) - theta = atanf((a_sensor[1] + cP * (sP * a_sensor[0] - - cP * a_sensor[1])) / (sP * a_sensor[2])); - else - theta = atanf((a_sensor[0] - sP * (sP * a_sensor[0] - - cP * a_sensor[1])) / (cP * a_sensor[2])); - - phi = atan2f((sP * a_sensor[0] - cP * a_sensor[1]) / GRAVITY, - (a_sensor[2] / cosf(theta) / GRAVITY)); - - attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_ROLL] = phi * RAD2DEG * 100.0f; - attitudeSettings.BoardRotation[ATTITUDESETTINGS_BOARDROTATION_PITCH] = theta * RAD2DEG * 100.0f; - - attitudeSettings.TrimFlight = ATTITUDESETTINGS_TRIMFLIGHT_NORMAL; - AttitudeSettingsSet(&attitudeSettings); - - } } /** * @} diff --git a/flight/Modules/ComUsbBridge/ComUsbBridge.c b/flight/Modules/ComUsbBridge/ComUsbBridge.c index 17c78134ab4..40bde7b8d42 100644 --- a/flight/Modules/ComUsbBridge/ComUsbBridge.c +++ b/flight/Modules/ComUsbBridge/ComUsbBridge.c @@ -50,7 +50,7 @@ static void updateSettings(); #if defined(PIOS_COMUSBBRIDGE_STACK_SIZE) #define STACK_SIZE_BYTES PIOS_COMUSBBRIDGE_STACK_SIZE #else -#define STACK_SIZE_BYTES 384 +#define STACK_SIZE_BYTES 480 #endif #define TASK_PRIORITY PIOS_THREAD_PRIO_LOW @@ -201,6 +201,7 @@ static void updateSettings() PIOS_COM_ChangeBaud(usart_port, 115200); break; } + } } diff --git a/flight/Modules/FirmwareIAP/inc/firmwareiap.h b/flight/Modules/FirmwareIAP/inc/firmwareiap.h index e3afcae18f4..92dc1f7148f 100644 --- a/flight/Modules/FirmwareIAP/inc/firmwareiap.h +++ b/flight/Modules/FirmwareIAP/inc/firmwareiap.h @@ -38,4 +38,4 @@ int32_t FirmwareIAPStart() {return 0;}; /** * @} * @} - */ \ No newline at end of file + */ diff --git a/flight/Modules/GPS/GPS.c b/flight/Modules/GPS/GPS.c index d0dae43b76a..2772fcad03d 100644 --- a/flight/Modules/GPS/GPS.c +++ b/flight/Modules/GPS/GPS.c @@ -100,7 +100,7 @@ int32_t GPSStart(void) return 0; } - AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_CRITICAL); + AlarmsSet(SYSTEMALARMS_ALARM_GPS, SYSTEMALARMS_ALARM_ERROR); } return -1; } @@ -127,30 +127,24 @@ int32_t GPSInitialize(void) } #endif -#if defined(REVOLUTION) - // These objects MUST be initialized for Revolution - // because the rest of the system expects to just - // attach to their queues - GPSPositionInitialize(); - GPSVelocityInitialize(); - GPSTimeInitialize(); - GPSSatellitesInitialize(); - HomeLocationInitialize(); - UBloxInfoInitialize(); - updateSettings(); - -#else + // These things are only conditional on small F1 targets. + // Expected to be always present otherwise. +#ifdef SMALLF1 if (gpsPort && module_enabled) { +#endif GPSPositionInitialize(); GPSVelocityInitialize(); #if !defined(PIOS_GPS_MINIMAL) GPSTimeInitialize(); GPSSatellitesInitialize(); + HomeLocationInitialize(); + UBloxInfoInitialize(); #endif #if defined(PIOS_GPS_PROVIDES_AIRSPEED) AirspeedActualInitialize(); #endif updateSettings(); +#ifdef SMALLF1 } #endif diff --git a/flight/Modules/ManualControl/geofence_control.c b/flight/Modules/ManualControl/geofence_control.c index e3160a11573..9fde1c1c95b 100644 --- a/flight/Modules/ManualControl/geofence_control.c +++ b/flight/Modules/ManualControl/geofence_control.c @@ -6,7 +6,7 @@ * @{ * * @file geofence_control.c - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 * @brief Geofence controller that is enabled when out of zone * * @see The GNU Public License (GPL) Version 3 @@ -103,7 +103,7 @@ int32_t geofence_control_select(bool reset_controller) //! Query if out of bounds and the geofence controller should take over bool geofence_control_activate() { -#if (!defined(COPTERCONTROL) && !defined(GIMBAL)) +#if (!defined(SMALLF1) && !defined(GIMBAL)) // Check if the module is running if (GeoFenceSettingsHandle()) { uint8_t alarm_status[SYSTEMALARMS_ALARM_NUMELEM]; diff --git a/flight/Modules/ManualControl/tablet_control.c b/flight/Modules/ManualControl/tablet_control.c index 764dbfad408..4ccdcd5bd1f 100644 --- a/flight/Modules/ManualControl/tablet_control.c +++ b/flight/Modules/ManualControl/tablet_control.c @@ -6,7 +6,7 @@ * @{ * * @file tablet_control.c - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 * @brief Use tablet for control source * * @see The GNU Public License (GPL) Version 3 @@ -43,7 +43,7 @@ #include "tabletinfo.h" #include "systemsettings.h" -#if !defined(COPTERCONTROL) +#if !defined(SMALLF1) //! Private methods static int32_t tabletInfo_to_ned(TabletInfoData *tabletInfo, float *NED); @@ -97,8 +97,9 @@ int32_t tablet_control_select(bool reset_controller) // Command to not move. This code is identical to that in manualcontrol LoiterCommandData loiterCommand; - loiterCommand.Forward = 0; - loiterCommand.Right = 0; + loiterCommand.Pitch = 0; + loiterCommand.Roll = 0; + loiterCommand.Throttle = 0.5f; loiterCommand.Frame = LOITERCOMMAND_FRAME_BODY; LoiterCommandSet(&loiterCommand); diff --git a/flight/Modules/ManualControl/transmitter_control.c b/flight/Modules/ManualControl/transmitter_control.c index 92243461d4c..162503fe41b 100644 --- a/flight/Modules/ManualControl/transmitter_control.c +++ b/flight/Modules/ManualControl/transmitter_control.c @@ -124,7 +124,7 @@ int32_t transmitter_control_initialize() ManualControlSettingsInitialize(); // Both the gimbal and coptercontrol do not support loitering -#if !defined(COPTERCONTROL) && !defined(GIMBAL) +#if !defined(SMALLF1) && !defined(GIMBAL) LoiterCommandInitialize(); #endif @@ -434,6 +434,7 @@ int32_t transmitter_control_select(bool reset_controller) update_actuator_desired(&cmd); break; case FLIGHTSTATUS_FLIGHTMODE_ACRO: + case FLIGHTSTATUS_FLIGHTMODE_ACROPLUS: case FLIGHTSTATUS_FLIGHTMODE_LEVELING: case FLIGHTSTATUS_FLIGHTMODE_VIRTUALBAR: case FLIGHTSTATUS_FLIGHTMODE_MWRATE: @@ -808,14 +809,8 @@ static bool updateRcvrActivityCompare(uintptr_t rcvr_id, struct rcvr_activity_fs case MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM: group = RECEIVERACTIVITY_ACTIVEGROUP_PPM; break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_DSMMAINPORT; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_DSMFLEXIPORT; - break; - case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT: - group = RECEIVERACTIVITY_ACTIVEGROUP_DSMRCVRPORT; + case MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM: + group = RECEIVERACTIVITY_ACTIVEGROUP_DSM; break; case MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS: group = RECEIVERACTIVITY_ACTIVEGROUP_SBUS; @@ -946,6 +941,9 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK, STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK, STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK}; + const uint8_t ACROPLUS_SETTINGS[3] = { STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS, + STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS, + STABILIZATIONDESIRED_STABILIZATIONMODE_RATE}; const uint8_t * stab_settings; @@ -956,6 +954,9 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC case FLIGHTSTATUS_FLIGHTMODE_ACRO: stab_settings = RATE_SETTINGS; break; + case FLIGHTSTATUS_FLIGHTMODE_ACROPLUS: + stab_settings = ACROPLUS_SETTINGS; + break; case FLIGHTSTATUS_FLIGHTMODE_LEVELING: stab_settings = ATTITUDE_SETTINGS; break; @@ -995,8 +996,9 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC stabilization.Roll = (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Roll : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? expo3(cmd->Roll, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_ROLL]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS) ? expo3(cmd->Roll, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_ROLL]) : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? expo3(cmd->Roll, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_ROLL]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL]: - (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Roll * stabSettings.RollMax : + (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? expo3(cmd->Roll, stabSettings.AttitudeExpo[STABILIZATIONSETTINGS_ATTITUDEEXPO_ROLL]) * stabSettings.RollMax : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? expo3(cmd->Roll, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_ROLL]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_ROLL] : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Roll : (stab_settings[0] == STABILIZATIONDESIRED_STABILIZATIONMODE_HORIZON) ? expo3(cmd->Roll, stabSettings.HorizonExpo[STABILIZATIONSETTINGS_HORIZONEXPO_ROLL]) : @@ -1007,8 +1009,9 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC stabilization.Pitch = (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Pitch : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? expo3(cmd->Pitch, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_PITCH]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS) ? expo3(cmd->Pitch, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_PITCH]) : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? expo3(cmd->Pitch, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_PITCH]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : - (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Pitch * stabSettings.PitchMax : + (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? expo3(cmd->Pitch, stabSettings.AttitudeExpo[STABILIZATIONSETTINGS_ATTITUDEEXPO_PITCH]) * stabSettings.PitchMax : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? expo3(cmd->Pitch, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_PITCH]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_PITCH] : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Pitch : (stab_settings[1] == STABILIZATIONDESIRED_STABILIZATIONMODE_HORIZON) ? expo3(cmd->Pitch, stabSettings.HorizonExpo[STABILIZATIONSETTINGS_HORIZONEXPO_PITCH]): @@ -1019,8 +1022,9 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC stabilization.Yaw = (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_NONE) ? cmd->Yaw : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_RATE) ? expo3(cmd->Yaw, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_YAW]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS) ? expo3(cmd->Yaw, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_YAW]) : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_WEAKLEVELING) ? expo3(cmd->Yaw, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_YAW]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : - (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? cmd->Yaw * stabSettings.YawMax : + (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE) ? expo3(cmd->Yaw, stabSettings.AttitudeExpo[STABILIZATIONSETTINGS_ATTITUDEEXPO_YAW]) * stabSettings.YawMax : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK) ? expo3(cmd->Yaw, stabSettings.RateExpo[STABILIZATIONSETTINGS_RATEEXPO_YAW]) * stabSettings.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_VIRTUALBAR) ? cmd->Yaw : (stab_settings[2] == STABILIZATIONDESIRED_STABILIZATIONMODE_HORIZON) ? expo3(cmd->Yaw, stabSettings.HorizonExpo[STABILIZATIONSETTINGS_HORIZONEXPO_YAW]) : @@ -1033,7 +1037,7 @@ static void update_stabilization_desired(ManualControlCommandData * cmd, ManualC StabilizationDesiredSet(&stabilization); } -#if !defined(COPTERCONTROL) && !defined(GIMBAL) +#if !defined(SMALLF1) && !defined(GIMBAL) /** * @brief Update the altitude desired to current altitude when @@ -1107,20 +1111,12 @@ static void altitude_hold_desired(ManualControlCommandData * cmd, bool flightMod static void set_loiter_command(ManualControlCommandData *cmd) { - const float CMD_THRESHOLD = 0.5f; - const float MAX_SPEED = 3.0f; // m/s - LoiterCommandData loiterCommand; - loiterCommand.Forward = (cmd->Pitch > CMD_THRESHOLD) ? cmd->Pitch - CMD_THRESHOLD : - (cmd->Pitch < -CMD_THRESHOLD) ? cmd->Pitch + CMD_THRESHOLD : - 0; - // Note the negative - forward pitch is negative - loiterCommand.Forward *= -MAX_SPEED / (1.0f - CMD_THRESHOLD); - loiterCommand.Right = (cmd->Roll > CMD_THRESHOLD) ? cmd->Roll - CMD_THRESHOLD : - (cmd->Roll < -CMD_THRESHOLD) ? cmd->Roll + CMD_THRESHOLD : - 0; - loiterCommand.Right *= MAX_SPEED / (1.0f - CMD_THRESHOLD); + loiterCommand.Pitch = cmd->Pitch; + loiterCommand.Roll = cmd->Roll; + + loiterCommand.Throttle = cmd->Throttle; loiterCommand.Frame = LOITERCOMMAND_FRAME_BODY; @@ -1139,7 +1135,7 @@ static void set_loiter_command(ManualControlCommandData *cmd) set_manual_control_error(SYSTEMALARMS_MANUALCONTROL_PATHFOLLOWER); } -#endif /* !defined(COPTERCONTROL) && !defined(GIMBAL) */ +#endif /* !defined(SMALLF1) && !defined(GIMBAL) */ /** * Convert channel from servo pulse duration (microseconds) to scaled -1/+1 range. diff --git a/flight/Modules/PathFollower/fixedwingpathfollower.c b/flight/Modules/PathFollower/fixedwingpathfollower.c deleted file mode 100644 index 2407b631c37..00000000000 --- a/flight/Modules/PathFollower/fixedwingpathfollower.c +++ /dev/null @@ -1,589 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file fixedwingpathfollower.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 - * @brief This module compared @ref PositionActual to @ref ActiveWaypoint - * and sets @ref StabilizationDesired. It only does this when the FlightMode field - * of @ref ManualControlCommand is Auto. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/** - * Input object: @ref PositionActual and @ref PathDesired - * Output object: @ref StabilizationDesired - * - * Computes the @ref StabilizationDesired that gets the UAV back on or keeps - * the UAV on the requested path - */ - -#include "openpilot.h" -#include "physical_constants.h" -#include "fixedwingpathfollower.h" -#include "fixedwingairspeeds.h" - -#include "positionactual.h" -#include "velocityactual.h" -#include "flightstatus.h" -#include "airspeedactual.h" -#include "stabilizationdesired.h" -#include "pathdesired.h" -#include "systemsettings.h" - -#include "coordinate_conversions.h" -#include "pios_thread.h" - -// Private constants -#define MAX_QUEUE_SIZE 4 -#define STACK_SIZE_BYTES 750 -#define TASK_PRIORITY PIOS_THREAD_PRIO_NORMAL -#define CRITICAL_ERROR_THRESHOLD_MS 5000 //Time in [ms] before an error becomes a critical error - -// Private types -static struct Integral { - float totalEnergyError; - float airspeedError; - - float lineError; - float circleError; -} *integral; - -// Private variables -extern bool flightStatusUpdate; -static bool homeOrbit = true; - -// Private functions -static uint8_t waypointFollowing(uint8_t flightMode, FixedWingPathFollowerSettingsCCData fixedwingpathfollowerSettings); -static float bound(float val, float min, float max); -static float followStraightLine(float r[3], float q[3], float p[3], - float heading, float chi_inf, float k_path, - float k_psi_int, float delT); -static float followOrbit(float c[3], float rho, bool direction, float p[3], - float phi, float k_orbit, float k_psi_int, float delT); - -void initializeFixedWingPathFollower() -{ - integral = (struct Integral *)PIOS_malloc(sizeof(struct Integral)); - memset(integral, 0, sizeof(struct Integral)); -} - -uint8_t updateFixedWingDesiredStabilization(uint8_t flightMode, FixedWingPathFollowerSettingsCCData fixedwingpathfollowerSettings) -{ - - // Compute path follower commands - switch (flightMode) { - case FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME: - case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: - waypointFollowing(flightMode, fixedwingpathfollowerSettings); - break; - default: - // Be cleaner and reset integrals - integral->totalEnergyError = 0; - integral->airspeedError = 0; - integral->lineError = 0; - integral->circleError = 0; - - break; - } - - return 0; - -} - -/** - * Compute desired attitude from the desired velocity - * - * Takes in @ref NedActual which has the acceleration in the - * NED frame as the feedback term and then compares the - * @ref VelocityActual against the @ref VelocityDesired - */ -uint8_t waypointFollowing(uint8_t flightMode, FixedWingPathFollowerSettingsCCData fixedwingpathfollowerSettings) -{ - float dT = fixedwingpathfollowerSettings.UpdatePeriod / 1000.0f; //Convert from [ms] to [s] - - VelocityActualData velocityActual; - StabilizationDesiredData stabDesired; - float trueAirspeed; - - float calibratedAirspeedActual; - float airspeedDesired; - float airspeedError; - - float pitchCommand; - - float powerCommand; - float headingError_R; - float rollCommand; - - //TODO: Move these out of the loop - FixedWingAirspeedsData fixedwingAirspeeds; - FixedWingAirspeedsGet(&fixedwingAirspeeds); - - VelocityActualGet(&velocityActual); - StabilizationDesiredGet(&stabDesired); - // TODO: Create UAVO that merges airspeed together - AirspeedActualTrueAirspeedGet(&trueAirspeed); - - PositionActualData positionActual; - PositionActualGet(&positionActual); - - PathDesiredData pathDesired; - PathDesiredGet(&pathDesired); - - if (flightStatusUpdate) { - - //Reset integrals - integral->totalEnergyError = 0; - integral->airspeedError = 0; - integral->lineError = 0; - integral->circleError = 0; - - if (flightMode == FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME) { - // Simple Return To Home mode: climb 10 meters and fly to home position - - pathDesired.Start[PATHDESIRED_START_NORTH] = - positionActual.North; - pathDesired.Start[PATHDESIRED_START_EAST] = - positionActual.East; - pathDesired.Start[PATHDESIRED_START_DOWN] = - positionActual.Down; - pathDesired.End[PATHDESIRED_END_NORTH] = 0; - pathDesired.End[PATHDESIRED_END_EAST] = 0; - pathDesired.End[PATHDESIRED_END_DOWN] = - positionActual.Down - 10; - pathDesired.StartingVelocity = - fixedwingAirspeeds.BestClimbRateSpeed; - pathDesired.EndingVelocity = - fixedwingAirspeeds.BestClimbRateSpeed; - pathDesired.Mode = PATHDESIRED_MODE_FLYVECTOR; - - homeOrbit = false; - } else if (flightMode == FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD) { - // Simple position hold: stay at present altitude and position - - //Offset by one so that the start and end points don't perfectly coincide - pathDesired.Start[PATHDESIRED_START_NORTH] = - positionActual.North - 1; - pathDesired.Start[PATHDESIRED_START_EAST] = - positionActual.East; - pathDesired.Start[PATHDESIRED_START_DOWN] = - positionActual.Down; - pathDesired.End[PATHDESIRED_END_NORTH] = - positionActual.North; - pathDesired.End[PATHDESIRED_END_EAST] = - positionActual.East; - pathDesired.End[PATHDESIRED_END_DOWN] = - positionActual.Down; - pathDesired.StartingVelocity = - fixedwingAirspeeds.BestClimbRateSpeed; - pathDesired.EndingVelocity = - fixedwingAirspeeds.BestClimbRateSpeed; - pathDesired.Mode = PATHDESIRED_MODE_FLYVECTOR; - } - PathDesiredSet(&pathDesired); - - flightStatusUpdate = false; - } - - /** - * Compute speed error (required for throttle and pitch) - */ - - // Current airspeed - calibratedAirspeedActual = trueAirspeed; //BOOOOOOOOOO!!! Where's the conversion from TAS to CAS? - - // Current heading - float headingActual_R = - atan2f(velocityActual.East, velocityActual.North); - - // Desired airspeed - airspeedDesired = pathDesired.EndingVelocity; - - // Airspeed error - airspeedError = airspeedDesired - calibratedAirspeedActual; - - /** - * Compute desired throttle command - */ - - //Proxy because instead of m*(1/2*v^2+g*h), it's v^2+2*gh. This saves processing power - float totalEnergyProxySetpoint = powf(pathDesired.EndingVelocity, - 2.0f) - - 2.0f * GRAVITY * pathDesired.End[2]; - float totalEnergyProxyActual = - powf(trueAirspeed, 2.0f) - 2.0f * GRAVITY * positionActual.Down; - float errorTotalEnergy = - totalEnergyProxySetpoint - totalEnergyProxyActual; - - float throttle_kp = - fixedwingpathfollowerSettings. - ThrottlePI[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLEPI_KP]; - float throttle_ki = fixedwingpathfollowerSettings.ThrottlePI[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLEPI_KI]; - float throttle_ilimit = fixedwingpathfollowerSettings.ThrottlePI[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLEPI_ILIMIT]; - - //Integrate with bound. Make integral leaky for better performance. Approximately 30s time constant. - if (throttle_ilimit > 0.0f) { - integral->totalEnergyError = - bound(integral->totalEnergyError + errorTotalEnergy * dT, - -throttle_ilimit / throttle_ki, - throttle_ilimit / throttle_ki) * (1.0f - - 1.0f / (1.0f + - 30.0f / - dT)); - } - - powerCommand = errorTotalEnergy * throttle_kp - + integral->totalEnergyError * throttle_ki; - - float throttlelimit_neutral = - fixedwingpathfollowerSettings. - ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLELIMIT_NEUTRAL]; - float throttlelimit_min = - fixedwingpathfollowerSettings. - ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLELIMIT_MIN]; - float throttlelimit_max = - fixedwingpathfollowerSettings. - ThrottleLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_THROTTLELIMIT_MAX]; - - // set throttle - stabDesired.Throttle = bound(powerCommand + throttlelimit_neutral, - throttlelimit_min, throttlelimit_max); - /** - * Compute desired pitch command - */ - - float airspeed_kp = - fixedwingpathfollowerSettings. - AirspeedPI[FIXEDWINGPATHFOLLOWERSETTINGSCC_AIRSPEEDPI_KP]; - float airspeed_ki = - fixedwingpathfollowerSettings. - AirspeedPI[FIXEDWINGPATHFOLLOWERSETTINGSCC_AIRSPEEDPI_KI]; - float airspeed_ilimit = - fixedwingpathfollowerSettings. - AirspeedPI[FIXEDWINGPATHFOLLOWERSETTINGSCC_AIRSPEEDPI_ILIMIT]; - - if (airspeed_ki > 0.0f) { - //Integrate with saturation - integral->airspeedError = - bound(integral->airspeedError + airspeedError * dT, - -airspeed_ilimit / airspeed_ki, - airspeed_ilimit / airspeed_ki); - } - //Compute the cross feed from altitude to pitch, with saturation - float pitchcrossfeed_kp = - fixedwingpathfollowerSettings. - VerticalToPitchCrossFeed - [FIXEDWINGPATHFOLLOWERSETTINGSCC_VERTICALTOPITCHCROSSFEED_KP]; - float pitchcrossfeed_min = - fixedwingpathfollowerSettings. - VerticalToPitchCrossFeed - [FIXEDWINGPATHFOLLOWERSETTINGSCC_VERTICALTOPITCHCROSSFEED_MAX]; - float pitchcrossfeed_max = - fixedwingpathfollowerSettings. - VerticalToPitchCrossFeed - [FIXEDWINGPATHFOLLOWERSETTINGSCC_VERTICALTOPITCHCROSSFEED_MAX]; - float alitudeError = -(pathDesired.End[2] - positionActual.Down); //Negative to convert from Down to altitude - float altitudeToPitchCommandComponent = - bound(alitudeError * pitchcrossfeed_kp, - -pitchcrossfeed_min, - pitchcrossfeed_max); - - //Compute the pitch command as err*Kp + errInt*Ki + X_feed. - pitchCommand = -(airspeedError * airspeed_kp - + integral->airspeedError * airspeed_ki) + - altitudeToPitchCommandComponent; - - //Saturate pitch command - float pitchlimit_neutral = - fixedwingpathfollowerSettings. - PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_PITCHLIMIT_NEUTRAL]; - float pitchlimit_min = - fixedwingpathfollowerSettings. - PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_PITCHLIMIT_MIN]; - float pitchlimit_max = - fixedwingpathfollowerSettings. - PitchLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_PITCHLIMIT_MAX]; - - stabDesired.Pitch = bound(pitchlimit_neutral + - pitchCommand, pitchlimit_min, pitchlimit_max); - - /** - * Compute desired roll command - */ - - float p[3] = - { positionActual.North, positionActual.East, positionActual.Down }; - float *c = pathDesired.End; - float *r = pathDesired.Start; - float q[3] = { pathDesired.End[0] - pathDesired.Start[0], - pathDesired.End[1] - pathDesired.Start[1], - pathDesired.End[2] - pathDesired.Start[2] - }; - - float k_path = fixedwingpathfollowerSettings.VectorFollowingGain / pathDesired.EndingVelocity; //Divide gain by airspeed so that the turn rate is independent of airspeed - float k_orbit = fixedwingpathfollowerSettings.OrbitFollowingGain / pathDesired.EndingVelocity; //Divide gain by airspeed so that the turn rate is independent of airspeed - float k_psi_int = fixedwingpathfollowerSettings.FollowerIntegralGain; -//======================================== - //SHOULD NOT BE HARD CODED - - bool direction; - - float chi_inf = PI / 4.0f; //THIS NEEDS TO BE A FUNCTION OF HOW LONG OUR PATH IS. - - //Saturate chi_inf. I.e., never approach the path at a steeper angle than 45 degrees - chi_inf = chi_inf < PI / 4.0f ? PI / 4.0f : chi_inf; -//======================================== - - float rho; - float headingCommand_R; - - float pncn = p[0] - c[0]; - float pece = p[1] - c[1]; - float d = sqrtf(pncn * pncn + pece * pece); - -//Assume that we want a 15 degree bank angle. This should yield a nice, non-agressive turn -#define ROLL_FOR_HOLDING_CIRCLE 15.0f - //Calculate radius, rho, using r*omega=v and omega = g/V_g * tan(phi) - //THIS SHOULD ONLY BE CALCULATED ONCE, INSTEAD OF EVERY TIME - rho = powf(pathDesired.EndingVelocity, - 2) / (GRAVITY * tanf(fabs(ROLL_FOR_HOLDING_CIRCLE * DEG2RAD))); - - typedef enum { - LINE, - ORBIT - } pathTypes_t; - - pathTypes_t pathType; - - //Determine if we should fly on a line or orbit path. - switch (flightMode) { - case FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME: - if (d < rho + 5.0f * pathDesired.EndingVelocity || homeOrbit == true) { //When approx five seconds from the circle, start integrating into it - pathType = ORBIT; - homeOrbit = true; - } else { - pathType = LINE; - } - break; - case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: - pathType = ORBIT; - break; - default: - pathType = LINE; - break; - } - - //Check to see if we've gone past our destination. Since the path follower - //is simply following a vector, it has no concept of where the vector ends. - //It will simply keep following it to infinity if we don't stop it. So while - //we don't know why the commutation to the next point failed, we don't know - //we don't want the plane flying off. - if (pathType == LINE) { - - //Compute the norm squared of the horizontal path length - //IT WOULD BE NICE TO ONLY DO THIS ONCE PER WAYPOINT UPDATE, INSTEAD OF - //EVERY LOOP - float pathLength2 = q[0] * q[0] + q[1] * q[1]; - - //Perform a quick vector math operation, |a| < a.b/|a| = |b|cos(theta), - //to test if we've gone past the waypoint. Add in a distance equal to 5s - //of flight time, for good measure to make sure we don't add jitter. - if (((p[0] - r[0]) * q[0] + (p[1] - r[1]) * q[1]) > - pathLength2 + 5.0f * pathDesired.EndingVelocity) { - //Whoops, we've really overflown our destination point, and haven't - //received any instructions. Start circling - //flightMode will reset the next time a waypoint changes, so there's - //no danger of it getting stuck in orbit mode. - flightMode = FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD; - pathType = ORBIT; - } - } - - switch (pathType) { - case ORBIT: - if (pathDesired.Mode == PATHDESIRED_MODE_FLYCIRCLELEFT) { - direction = false; - } else { - //In the case where the direction is undefined, always fly in a - //clockwise fashion - direction = true; - } - - headingCommand_R = - followOrbit(c, rho, direction, p, headingActual_R, k_orbit, - k_psi_int, dT); - break; - case LINE: - headingCommand_R = - followStraightLine(r, q, p, headingActual_R, chi_inf, - k_path, k_psi_int, dT); - break; - } - - //Calculate heading error - headingError_R = headingCommand_R - headingActual_R; - - //Wrap heading error around circle - if (headingError_R < -PI) - headingError_R += 2.0f * PI; - if (headingError_R > PI) - headingError_R -= 2.0f * PI; - - //GET RID OF THE RAD2DEG. IT CAN BE FACTORED INTO HeadingPI - float rolllimit_neutral = - fixedwingpathfollowerSettings. - RollLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_ROLLLIMIT_NEUTRAL]; - float rolllimit_min = - fixedwingpathfollowerSettings. - RollLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_ROLLLIMIT_MIN]; - float rolllimit_max = - fixedwingpathfollowerSettings. - RollLimit[FIXEDWINGPATHFOLLOWERSETTINGSCC_ROLLLIMIT_MAX]; - float headingpi_kp = - fixedwingpathfollowerSettings. - HeadingPI[FIXEDWINGPATHFOLLOWERSETTINGSCC_HEADINGPI_KP]; - rollCommand = (headingError_R * headingpi_kp) * RAD2DEG; - - //Turn heading - - stabDesired.Roll = bound(rolllimit_neutral + - rollCommand, rolllimit_min, rolllimit_max); - -#ifdef SIM_POSIX - fprintf(stderr, " headingError_R: %f, rollCommand: %f\n", - headingError_R, rollCommand); -#endif - - /** - * Compute desired yaw command - */ - // Coordinated flight, so we reset the desired yaw. - stabDesired.Yaw = 0; - - stabDesired. - StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = - STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired. - StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = - STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - stabDesired. - StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = - STABILIZATIONDESIRED_STABILIZATIONMODE_NONE; - - StabilizationDesiredSet(&stabDesired); - - //Stuff some debug variables into PathDesired, because right now these - //fields aren't being used. - pathDesired.ModeParameters[0] = pitchCommand; - pathDesired.ModeParameters[1] = airspeedError; - pathDesired.ModeParameters[2] = integral->airspeedError; - pathDesired.ModeParameters[3] = alitudeError; - pathDesired.UID = errorTotalEnergy; - - PathDesiredSet(&pathDesired); - - return 0; -} - -/** - * Calculate command for following simple vector based line. Taken from R. - * Beard at BYU. - */ -float followStraightLine(float r[3], float q[3], float p[3], float psi, - float chi_inf, float k_path, float k_psi_int, - float delT) -{ - float chi_q = atan2f(q[1], q[0]); - while (chi_q - psi < -PI) { - chi_q += 2.0f * PI; - } - while (chi_q - psi > PI) { - chi_q -= 2.0f * PI; - } - - float err_p = -sinf(chi_q) * (p[0] - r[0]) + cosf(chi_q) * (p[1] - r[1]); - integral->lineError += delT * err_p; - float psi_command = chi_q - chi_inf * 2.0f / PI * atanf(k_path * err_p) - - k_psi_int * integral->lineError; - - return psi_command; -} - -/** - * Calculate command for following simple vector based orbit. Taken from R. - * Beard at BYU. - */ -float followOrbit(float c[3], float rho, bool direction, float p[3], float psi, - float k_orbit, float k_psi_int, float delT) -{ - float pncn = p[0] - c[0]; - float pece = p[1] - c[1]; - float d = sqrtf(pncn * pncn + pece * pece); - - float err_orbit = d - rho; - integral->circleError += err_orbit * delT; - - float phi = atan2f(pece, pncn); - while (phi - psi < -PI) { - phi = phi + 2.0f * PI; - } - while (phi - psi > PI) { - phi = phi - 2.0f * PI; - } - - float psi_command = (direction == true) ? - phi + (PI / 2.0f + atanf(k_orbit * err_orbit) + - k_psi_int * integral->circleError) : phi - (PI / 2.0f + - atanf(k_orbit * - err_orbit) + - k_psi_int * - integral-> - circleError); - -#ifdef SIM_POSIX - fprintf(stderr, - "actual heading: %f, circle error: %f, circl integral: %f, heading command: %f", - psi, err_orbit, integral->circleError, psi_command); -#endif - return psi_command; -} - -/** - * Bound input value between limits - */ -static float bound(float val, float min, float max) -{ - if (val < min) { - val = min; - } else if (val > max) { - val = max; - } - return val; -} - -/** - * @} - * @} - */ diff --git a/flight/Modules/PathFollower/inc/dubinscartpathfollower.h b/flight/Modules/PathFollower/inc/dubinscartpathfollower.h deleted file mode 100644 index 0743b4ff52f..00000000000 --- a/flight/Modules/PathFollower/inc/dubinscartpathfollower.h +++ /dev/null @@ -1,46 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file dubinscartpathfollower.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * @brief Dubins cart path follower - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef DUBINSCARTPATHFOLLOWER_H -#define DUBINSCARTPATHFOLLOWER_H -#include "fixedwingpathfollowersettings.h" - -void initializeDubinsCartPathFollower(); -uint8_t updateDubinsCartDesiredStabilization(uint8_t flightMode, - FixedWingPathFollowerSettingsData - fixedwingpathfollowerSettings); - -#endif // DUBINSCARTPATHFOLLOWER_H - -/** - * @} - * @} - */ - \ No newline at end of file diff --git a/flight/Modules/PathFollower/inc/fixedwingpathfollower.h b/flight/Modules/PathFollower/inc/fixedwingpathfollower.h deleted file mode 100644 index f03a7f749bd..00000000000 --- a/flight/Modules/PathFollower/inc/fixedwingpathfollower.h +++ /dev/null @@ -1,44 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file fixedwingpathfollower.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * @brief Fixed wing path follower - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef FIXEDWINGPATHFOLLOWER_H -#define FIXEDWINGPATHFOLLOWER_H -#include "fixedwingpathfollowersettingscc.h" - -void initializeFixedWingPathFollower(); -uint8_t updateFixedWingDesiredStabilization(uint8_t flightMode, FixedWingPathFollowerSettingsCCData fixedwingpathfollowerSettingsCC); -#endif /* FIXEDWINGPATHFOLLOWER_H */ - -/** - * @} - * @} - */ - \ No newline at end of file diff --git a/flight/Modules/PathFollower/inc/helicopterpathfollower.h b/flight/Modules/PathFollower/inc/helicopterpathfollower.h deleted file mode 100644 index e796a5a785e..00000000000 --- a/flight/Modules/PathFollower/inc/helicopterpathfollower.h +++ /dev/null @@ -1,47 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file helicopterpathfollower.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * @brief Helicopter path follower - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef HELICOPTERPATHFOLLOWER_H -#define HELICOPTERPATHFOLLOWER_H -#include "fixedwingpathfollowersettings.h" - -void initializeHelicopterPathFollower(); -uint8_t updateHelicopterDesiredStabilization(uint8_t flightMode, - FixedWingPathFollowerSettingsData - fixedwingpathfollowerSettings); - -#endif /* HELICOPTERPATHFOLLOWER_H */ - -/** - * @} - * @} - */ - \ No newline at end of file diff --git a/flight/Modules/PathFollower/inc/multirotorpathfollower.h b/flight/Modules/PathFollower/inc/multirotorpathfollower.h deleted file mode 100644 index 2ee081b1755..00000000000 --- a/flight/Modules/PathFollower/inc/multirotorpathfollower.h +++ /dev/null @@ -1,47 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file multirotorpathfollower.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * @brief Path follower for multirotors - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef MULTIROTORPATHFOLLOWER_H -#define MULTIROTORPATHFOLLOWER_H -#include "fixedwingpathfollowersettings.h" - -void initializeMultirotorPathFollower(); -uint8_t updateMultirotorDesiredStabilization(uint8_t flightMode, - FixedWingPathFollowerSettingsData - fixedwingpathfollowerSettings); - -#endif /* MULTIROTORPATHFOLLOWER_H */ - -/** - * @} - * @} - */ - \ No newline at end of file diff --git a/flight/Modules/PathFollower/pathfollower.c b/flight/Modules/PathFollower/pathfollower.c deleted file mode 100644 index 97e46773c70..00000000000 --- a/flight/Modules/PathFollower/pathfollower.c +++ /dev/null @@ -1,247 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsModules Tau Labs Modules - * @{ - * @addtogroup PathFollowerModule Path Follower Module - * @{ - * - * @file pathfollower.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2014 - * @brief This module compared @ref PositionActuatl to @ref ActiveWaypoint - * and sets @ref AttitudeDesired. It only does this when the FlightMode field - * of @ref ManualControlCommand is Auto. - * - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/** - * Input object: @ref PathDesired and @ref PositionActual - * Output object: @ref StabilizationDesired - * - * Calculate the value of @ref StabilizationDesired to get on the desired path. - */ - -#include "openpilot.h" -#include "airspeedactual.h" -#include "fixedwingairspeeds.h" -#include "fixedwingpathfollowersettingscc.h" -#include "flightstatus.h" -#include "pathdesired.h" -#include "systemsettings.h" - -#include "fixedwingpathfollower.h" -#include "helicopterpathfollower.h" -#include "multirotorpathfollower.h" -#include "dubinscartpathfollower.h" - -#include "coordinate_conversions.h" -#include "pios_thread.h" - -// Private constants -#define MAX_QUEUE_SIZE 4 -#define STACK_SIZE_BYTES 750 -#define TASK_PRIORITY PIOS_THREAD_PRIO_NORMAL -#define CRITICAL_ERROR_THRESHOLD_MS 5000 //Time in [ms] before an error becomes a critical error - -enum pathFollowerTypes { - FIXEDWING, MULTIROTOR, HELICOPTER, DUBINSCART, HOLONOMIC, NONHOLONOMIC, - DISABLED -}; - -// Private variables -static struct pios_thread *PathFollowerTaskHandle; -static uint8_t flightMode = FLIGHTSTATUS_FLIGHTMODE_MANUAL; -static bool followerEnabled = false; -bool flightStatusUpdate = false; -static uint8_t pathFollowerType; - -// Private functions -static void PathFollowerTask(void *parameters); -static void FlightStatusUpdatedCb(UAVObjEvent * ev); - -/** - * Initialise the module, called on startup - * \returns 0 on success or -1 if initialisation failed - */ -int32_t PathFollowerStart() -{ - // Start main task - if (followerEnabled) { - // Start main task - PathFollowerTaskHandle = PIOS_Thread_Create(manualControlTask, "PathFollower", STACK_SIZE_BYTES, NULL, TASK_PRIORITY); - TaskMonitorAdd(TASKINFO_RUNNING_PATHFOLLOWER, - PathFollowerTaskHandle); - } - - return 0; -} - -/** - * Initialise the module, called on startup - * \returns 0 on success or -1 if initialisation failed - */ -int32_t PathFollowerInitialize() -{ - HwSettingsInitialize(); - uint8_t optionalModules[HWSETTINGS_OPTIONALMODULES_NUMELEM]; - HwSettingsOptionalModulesGet(optionalModules); - - // Select algorithm based on vehicle type - SystemSettingsInitialize(); - uint8_t systemSettingsAirframeType; - SystemSettingsAirframeTypeGet(&systemSettingsAirframeType); - switch(systemSettingsAirframeType) { - case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWING: - case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGELEVON: - case SYSTEMSETTINGS_AIRFRAMETYPE_FIXEDWINGVTAIL: - pathFollowerType = FIXEDWING; - break; - case SYSTEMSETTINGS_AIRFRAMETYPE_TRI: - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: - case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_HEXACOAX: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOV: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXP: - case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOCOAXX: - pathFollowerType = MULTIROTOR; - break; - case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLECAR: - case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEMOTORCYCLE: - pathFollowerType = DUBINSCART; - break; - case SYSTEMSETTINGS_AIRFRAMETYPE_GROUNDVEHICLEDIFFERENTIAL: - pathFollowerType = HOLONOMIC; - break; - case SYSTEMSETTINGS_AIRFRAMETYPE_HELICP: - pathFollowerType = HELICOPTER; - break; - case SYSTEMSETTINGS_AIRFRAMETYPE_VTOL: - pathFollowerType = HOLONOMIC; - break; - default: - // Cannot activate, prevent system arming - AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER, SYSTEMALARMS_ALARM_CRITICAL); - pathFollowerType = DISABLED; - return -1; - break; - } - - if (optionalModules[HWSETTINGS_OPTIONALMODULES_FIXEDWINGPATHFOLLOWER] == - HWSETTINGS_OPTIONALMODULES_ENABLED) { - FixedWingPathFollowerSettingsCCInitialize(); - FixedWingAirspeedsInitialize(); - AirspeedActualInitialize(); - PathDesiredInitialize(); - - // TODO: Index into array of functions - switch (pathFollowerType) { - case FIXEDWING: - initializeFixedWingPathFollower(); - break; - case MULTIROTOR: -// initializeMultirotorPathFollower(); - break; - case HELICOPTER: -// initializeHelicopterPathFollower(); - break; - case HOLONOMIC: - break; - case DUBINSCART: -// initializeDubinsCartPathFollower(); - break; - default: - PIOS_DEBUG_Assert(0); - return -1; - break; - } - - FlightStatusConnectCallback(FlightStatusUpdatedCb); - - followerEnabled = true; - return 0; - } - - return -1; -} - -MODULE_INITCALL(PathFollowerInitialize, PathFollowerStart) - -/** - * Module thread, should not return. - */ -static void PathFollowerTask(void *parameters) -{ - uint32_t lastUpdateTime; - FixedWingPathFollowerSettingsCCData fixedwingpathfollowerSettings; - - // Main task loop - lastUpdateTime = PIOS_Thread_Systime(); - while (1) { - // TODO: Refactor this into the fixed wing method as a callback - FixedWingPathFollowerSettingsCCGet(&fixedwingpathfollowerSettings); - - PIOS_Thread_Sleep_Until(&lastUpdateTime, fixedwingpathfollowerSettings.UpdatePeriod); - - if (flightStatusUpdate) - FlightStatusFlightModeGet(&flightMode); - - // Depending on vehicle type, call appropriate path follower - // TODO: Index into array of methods - switch (pathFollowerType) { - case FIXEDWING: - updateFixedWingDesiredStabilization(flightMode, fixedwingpathfollowerSettings); - break; -// case MULTIROTOR: -// // Set alarm, currently untested -// AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER, SYSTEMALARMS_ALARM_ERROR); -// updateMultirotorDesiredStabilization(flightMode, fixedwingpathfollowerSettings); -// break; -// case HELICOPTER: -// // Unready -// AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER, SYSTEMALARMS_ALARM_CRITICAL); -// //updateHelicopterDesiredStabilization(fixedwingpathfollowerSettings); -// case HOLONOMIC: -// // Unready -// AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER, SYSTEMALARMS_ALARM_CRITICAL); -// break; -// case DUBINSCART: -// updateDubinsCartDesiredStabilization(flightMode, fixedwingpathfollowerSettings); -// break; - default: - //Something has gone wrong, we shouldn't be able to get to this point - AlarmsSet(SYSTEMALARMS_ALARM_PATHFOLLOWER, SYSTEMALARMS_ALARM_CRITICAL); - break; - } - } -} - -// Triggered by changes in FlightStatus -static void FlightStatusUpdatedCb(UAVObjEvent * ev) -{ - flightStatusUpdate = true; -} - -/** - * @} - * @} - */ diff --git a/flight/Modules/PathPlanner/inc/path_saving.h b/flight/Modules/PathPlanner/inc/path_saving.h index 5190f4948fc..a9c57c64426 100644 --- a/flight/Modules/PathPlanner/inc/path_saving.h +++ b/flight/Modules/PathPlanner/inc/path_saving.h @@ -35,4 +35,4 @@ int32_t pathplanner_save_path(uint32_t path_id); /** * @} * @} - */ \ No newline at end of file + */ diff --git a/flight/Modules/PipXtreme/pipxtrememod.c b/flight/Modules/PipXtreme/pipxtrememod.c index 8e01ccfc38c..26dc17f4382 100644 --- a/flight/Modules/PipXtreme/pipxtrememod.c +++ b/flight/Modules/PipXtreme/pipxtrememod.c @@ -39,7 +39,6 @@ #include #include -#include #include "systemmod.h" #include "pios_thread.h" diff --git a/flight/Modules/RadioComBridge/RadioComBridge.c b/flight/Modules/RadioComBridge/RadioComBridge.c index 953a541f1b9..fa6a9475af7 100644 --- a/flight/Modules/RadioComBridge/RadioComBridge.c +++ b/flight/Modules/RadioComBridge/RadioComBridge.c @@ -45,6 +45,13 @@ #include #endif +// these objects are parsed locally for relaying to taranis +#include "flightbatterystate.h" +#include "flightstatus.h" +#include "positionactual.h" +#include "velocityactual.h" +#include "baroaltitude.h" + #include "pios_thread.h" #include "pios_queue.h" @@ -217,7 +224,6 @@ static int32_t RadioComBridgeInitialize(void) data->radioTxRetries = 0; data->parseUAVTalk = true; - PIOS_COM_RADIO = PIOS_COM_RFM22B; return 0; } @@ -379,10 +385,10 @@ static void radioRxTask( __attribute__ ((unused)) #ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_RADIORX); #endif - if (PIOS_COM_RADIO) { + if (PIOS_COM_RFM22B) { uint8_t serial_data[1]; uint16_t bytes_to_process = - PIOS_COM_ReceiveBuffer(PIOS_COM_RADIO, + PIOS_COM_ReceiveBuffer(PIOS_COM_RFM22B, serial_data, sizeof(serial_data), MAX_PORT_DELAY); @@ -505,7 +511,7 @@ static void serialRxTask( __attribute__ ((unused)) #ifdef PIOS_INCLUDE_WDG PIOS_WDG_UpdateFlag(PIOS_WDG_SERIALRX); #endif - if (inputPort && PIOS_COM_RADIO) { + if (inputPort && PIOS_COM_RFM22B) { // Receive some data. uint16_t bytes_to_process = PIOS_COM_ReceiveBuffer(inputPort, @@ -523,7 +529,7 @@ static void serialRxTask( __attribute__ ((unused)) while (count-- > 0 && ret < -1) { ret = PIOS_COM_SendBufferNonBlocking - (PIOS_COM_RADIO, + (PIOS_COM_RFM22B, data->serialRxBuf, bytes_to_process); } @@ -582,7 +588,7 @@ static int32_t RadioSendHandler(uint8_t * buf, int32_t length) if (!data->parseUAVTalk) { return length; } - uint32_t outputPort = PIOS_COM_RADIO; + uint32_t outputPort = PIOS_COM_RFM22B; // Don't send any data unless the radio port is available. if (outputPort && PIOS_COM_Available(outputPort)) { @@ -703,12 +709,25 @@ static void ProcessRadioStream(UAVTalkConnection inConnectionHandle, // some objects will send back a response to the remote modem UAVTalkReceiveObject(inConnectionHandle); break; + case FLIGHTBATTERYSTATE_OBJID: + case FLIGHTSTATUS_OBJID: + case POSITIONACTUAL_OBJID: + case VELOCITYACTUAL_OBJID: + case BAROALTITUDE_OBJID: + + // process the battery voltage locally for relaying to taranis + UAVTalkReceiveObject(inConnectionHandle); + UAVTalkRelayPacket(inConnectionHandle, outConnectionHandle); + break; case RFM22BSTATUS_OBJID: { uint32_t inst_id = UAVTalkGetPacketInstId(inConnectionHandle); if (inst_id == 0) { // instance 0 is from modem. do not pass this version } else { + // process the remote link state locally for relaying to taranis + UAVTalkReceiveObject(inConnectionHandle); + // for remote modem UAVTalkRelayPacket(inConnectionHandle, outConnectionHandle); } diff --git a/flight/Modules/Sensors/sensors.c b/flight/Modules/Sensors/sensors.c index 818dde685bd..64140d15c02 100644 --- a/flight/Modules/Sensors/sensors.c +++ b/flight/Modules/Sensors/sensors.c @@ -34,6 +34,7 @@ #include "physical_constants.h" #include "pios_thread.h" #include "pios_queue.h" +#include "misc_math.h" // UAVOs #include "accels.h" @@ -98,6 +99,10 @@ static float z_accel_offset = 0; static float Rsb[3][3] = {{0}}; //! Rotation matrix that transforms from the body frame to the sensor board frame static int8_t rotate = 0; +#if defined (AQ32) +// indicates whether the external mag works +extern bool external_mag_fail; +#endif //! Select the algorithm to try and null out the magnetometer bias error static enum mag_calibration_algo mag_calibration_algo = MAG_CALIBRATION_PRELEMARI; @@ -230,10 +235,15 @@ static void SensorsTask(void *parameters) } + #if defined(AQ32) + if ((good_runs > REQUIRED_GOOD_CYCLES) && !external_mag_fail) + #else if (good_runs > REQUIRED_GOOD_CYCLES) + #endif AlarmsClear(SYSTEMALARMS_ALARM_SENSORS); else good_runs++; + PIOS_WDG_UpdateFlag(PIOS_WDG_SENSORS); // Check total time to get the sensors wasn't over the limit @@ -383,7 +393,8 @@ static void update_mags(struct pios_sensor_mag_data *mag) */ static void update_baro(struct pios_sensor_baro_data *baro) { - if (isnan(baro->altitude) || isnan(baro->temperature) || isnan(baro->pressure)){ + // Check for Nan or infinity + if (IS_NOT_FINITE(baro->altitude) || IS_NOT_FINITE(baro->temperature) || IS_NOT_FINITE(baro->pressure)) { AlarmsSet(SYSTEMALARMS_ALARM_TEMPBARO, SYSTEMALARMS_ALARM_WARNING); return; } diff --git a/flight/Modules/Stabilization/inc/virtualflybar.h b/flight/Modules/Stabilization/inc/virtualflybar.h index 4440073a8f6..90043c516e7 100644 --- a/flight/Modules/Stabilization/inc/virtualflybar.h +++ b/flight/Modules/Stabilization/inc/virtualflybar.h @@ -43,4 +43,4 @@ int stabilization_virtual_flybar_pirocomp(float z_gyro, float dT); /** * @} * @} - */ \ No newline at end of file + */ diff --git a/flight/Modules/Stabilization/stabilization.c b/flight/Modules/Stabilization/stabilization.c index 443ac9360c3..5b34499bf65 100644 --- a/flight/Modules/Stabilization/stabilization.c +++ b/flight/Modules/Stabilization/stabilization.c @@ -59,7 +59,6 @@ // Math libraries #include "coordinate_conversions.h" #include "pid.h" -#include "sin_lookup.h" #include "misc_math.h" // Includes for various stabilization algorithms @@ -101,14 +100,12 @@ enum { PID_MAX }; - // Private variables static struct pios_thread *taskHandle; static MWRateSettingsData mwrate_settings; static StabilizationSettingsData settings; static TrimAnglesData trimAngles; static struct pios_queue *queue; -float gyro_alpha = 0; float axis_lock_accum[3] = {0,0,0}; uint8_t max_axis_lock = 0; uint8_t max_axislock_rate = 0; @@ -116,8 +113,11 @@ float weak_leveling_kp = 0; uint8_t weak_leveling_max = 0; bool lowThrottleZeroIntegral; float vbar_decay = 0.991f; +float gyro_alpha = 0.6; struct pid pids[PID_MAX]; +volatile bool gyro_filter_updated = false; + // Private functions static void stabilizationTask(void* parameters); static void zero_pids(void); @@ -164,9 +164,6 @@ int32_t StabilizationInitialize() RateDesiredInitialize(); #endif - // Code required for relay tuning - sin_lookup_initialize(); - return 0; } @@ -201,13 +198,13 @@ static void stabilizationTask(void* parameters) const uint32_t SYSTEM_IDENT_PERIOD = 75; uint32_t system_ident_timeval = PIOS_DELAY_GetRaw(); + float dT_filtered = 0; + // Main task loop zero_pids(); while(1) { iteration++; - float dT; - PIOS_WDG_UpdateFlag(PIOS_WDG_STABILIZATION); // Wait until the AttitudeRaw object is updated, if a timeout then go to failsafe @@ -217,12 +214,41 @@ static void stabilizationTask(void* parameters) continue; } - calculate_pids(); - dT = PIOS_DELAY_DiffuS(timeval) * 1.0e-6f; + float dT = PIOS_DELAY_DiffuS(timeval) * 1.0e-6f; timeval = PIOS_DELAY_GetRaw(); + // exponential moving averaging (EMA) of dT to reduce jitter; ~200points + // to have more or less equivalent noise reduction to a normal N point moving averaging: alpha = 2 / (N + 1) + // run it only at the beginning for the first samples, to reduce CPU load, and the value should converge to a constant value + + if (iteration < 100) { + dT_filtered = dT; + } else if (iteration < 2000) { + dT_filtered = 0.01f * dT + (1.0f - 0.01f) * dT_filtered; + } else if (iteration == 2000) { + gyro_filter_updated = true; + } + + if (gyro_filter_updated) { + if (settings.GyroCutoff < 1.0f) { + gyro_alpha = 0; + } else { + gyro_alpha = expf(-2.0f * (float)(M_PI) * + settings.GyroCutoff * dT_filtered); + } + + // Compute time constant for vbar decay term + if (settings.VbarTau < 0.001f) { + vbar_decay = 0; + } else { + vbar_decay = expf(-dT_filtered / settings.VbarTau); + } + + gyro_filter_updated = false; + } + FlightStatusGet(&flightStatus); StabilizationDesiredGet(&stabDesired); AttitudeActualGet(&attitudeActual); @@ -310,8 +336,9 @@ static void stabilizationTask(void* parameters) { // Check whether this axis mode needs to be reinitialized bool reinit = (stabDesired.StabilizationMode[i] != previous_mode[i]); + // The unscaled input (-1,1) + float *raw_input = &stabDesired.Roll; previous_mode[i] = stabDesired.StabilizationMode[i]; - // Apply the selected control law switch(stabDesired.StabilizationMode[i]) { @@ -328,7 +355,32 @@ static void stabilizationTask(void* parameters) break; - case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: + case STABILIZATIONDESIRED_STABILIZATIONMODE_ACROPLUS: + // this implementation is based on the Openpilot/Librepilot Acro+ flightmode + // and our existing rate & MWRate flightmodes + if(reinit) + pids[PID_RATE_ROLL + i].iAccumulator = 0; + + // The factor for gyro suppression / mixing raw stick input into the output; scaled by raw stick input + float factor = fabsf(raw_input[i]) * settings.AcroInsanityFactor / 100; + + // Store to rate desired variable for storing to UAVO + rateDesiredAxis[i] = bound_sym(raw_input[i] * settings.ManualRate[i], settings.ManualRate[i]); + + // Zero integral for aggressive maneuvers, like it is done for MWRate + if ((i < 2 && fabsf(gyro_filtered[i]) > 150.0f) || + (i == 0 && fabsf(raw_input[i]) > 0.2f)) { + pids[PID_RATE_ROLL + i].iAccumulator = 0; + pids[PID_RATE_ROLL + i].i = 0; + } + + // Compute the inner loop + actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i], gyro_filtered[i], dT); + actuatorDesiredAxis[i] = factor * raw_input[i] + (1.0f - factor) * actuatorDesiredAxis[i]; + actuatorDesiredAxis[i] = bound_sym(actuatorDesiredAxis[i], 1.0f); + + break; + case STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE: if(reinit) { pids[PID_ATT_ROLL + i].iAccumulator = 0; pids[PID_RATE_ROLL + i].iAccumulator = 0; @@ -371,18 +423,21 @@ static void stabilizationTask(void* parameters) if (reinit) pids[PID_RATE_ROLL + i].iAccumulator = 0; - if(fabs(stabDesiredAxis[i]) > max_axislock_rate) { + if (fabsf(stabDesiredAxis[i]) > max_axislock_rate) { // While getting strong commands act like rate mode - rateDesiredAxis[i] = stabDesiredAxis[i]; + rateDesiredAxis[i] = bound_sym(stabDesiredAxis[i], settings.ManualRate[i]); + + // Reset accumulator axis_lock_accum[i] = 0; } else { - // For weaker commands or no command simply attitude lock (almost) on no gyro change + // For weaker commands or no command simply lock (almost) on no gyro change axis_lock_accum[i] += (stabDesiredAxis[i] - gyro_filtered[i]) * dT; axis_lock_accum[i] = bound_sym(axis_lock_accum[i], max_axis_lock); - rateDesiredAxis[i] = pid_apply(&pids[PID_ATT_ROLL + i], axis_lock_accum[i], dT); - } - rateDesiredAxis[i] = bound_sym(rateDesiredAxis[i], settings.MaximumRate[i]); + // Compute the inner loop + float tmpRateDesired = pid_apply(&pids[PID_ATT_ROLL + i], axis_lock_accum[i], dT); + rateDesiredAxis[i] = bound_sym(tmpRateDesired, settings.MaximumRate[i]); + } actuatorDesiredAxis[i] = pid_apply_setpoint(&pids[PID_RATE_ROLL + i], rateDesiredAxis[i], gyro_filtered[i], dT); actuatorDesiredAxis[i] = bound_sym(actuatorDesiredAxis[i],1.0f); @@ -394,9 +449,6 @@ static void stabilizationTask(void* parameters) pids[PID_RATE_ROLL + i].iAccumulator = 0; } - // The unscaled input (-1,1) - float *raw_input = &stabDesired.Roll; - // Do not allow outer loop integral to wind up in this mode since the controller // is often disengaged. pids[PID_ATT_ROLL + i].iAccumulator = 0; @@ -942,19 +994,7 @@ static void SettingsUpdatedCb(UAVObjEvent * ev) // Whether to zero the PID integrals while throttle is low lowThrottleZeroIntegral = settings.LowThrottleZeroIntegral == STABILIZATIONSETTINGS_LOWTHROTTLEZEROINTEGRAL_TRUE; - // The dT has some jitter iteration to iteration that we don't want to - // make thie result unpredictable. Still, it's nicer to specify the constant - // based on a time (in ms) rather than a fixed multiplier. The error between - // update rates on OP (~300 Hz) and CC (~475 Hz) is negligible for this - // calculation - const float fakeDt = 0.0025f; - if(settings.GyroTau < 0.0001f) - gyro_alpha = 0; // not trusting this to resolve to 0 - else - gyro_alpha = expf(-fakeDt / settings.GyroTau); - - // Compute time constant for vbar decay term based on a tau - vbar_decay = expf(-fakeDt / settings.VbarTau); + gyro_filter_updated = true; } if (ev == NULL || ev->obj == MWRateSettingsHandle()) { diff --git a/flight/Modules/System/inc/systemmod.h b/flight/Modules/System/inc/systemmod.h index 765da2b3765..a3985b637bb 100644 --- a/flight/Modules/System/inc/systemmod.h +++ b/flight/Modules/System/inc/systemmod.h @@ -38,4 +38,4 @@ int32_t SystemModInitialize(void); /** * @} * @} - */ \ No newline at end of file + */ diff --git a/flight/Modules/System/systemmod.c b/flight/Modules/System/systemmod.c index 6dd3c40b814..15848dbea9d 100644 --- a/flight/Modules/System/systemmod.c +++ b/flight/Modules/System/systemmod.c @@ -7,7 +7,7 @@ * * @file systemmod.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 * @brief System module * * @see The GNU Public License (GPL) Version 3 @@ -84,7 +84,7 @@ static bool stackOverflow; // Private functions static void objectUpdatedCb(UAVObjEvent * ev); -#if (defined(COPTERCONTROL) || defined(REVOLUTION) || defined(SIM_OSX)) && ! (defined(SIM_POSIX)) +#ifndef NO_SENSORS static void configurationUpdatedCb(UAVObjEvent * ev); #endif @@ -169,7 +169,7 @@ static void systemTask(void *parameters) // Listen for SettingPersistance object updates, connect a callback function ObjectPersistenceConnectQueue(objectPersistenceQueue); -#if (defined(COPTERCONTROL) || defined(REVOLUTION) || defined(SIM_OSX)) && ! (defined(SIM_POSIX)) +#ifndef NO_SENSORS // Run this initially to make sure the configuration is checked configuration_check(); @@ -182,10 +182,10 @@ static void systemTask(void *parameters) ManualControlSettingsConnectCallback(configurationUpdatedCb); if (FlightStatusHandle()) FlightStatusConnectCallback(configurationUpdatedCb); -#endif -#if (defined(REVOLUTION) || defined(SIM_OSX)) && ! (defined(SIM_POSIX)) +#ifndef SMALLF1 if (StateEstimationHandle()) StateEstimationConnectCallback(configurationUpdatedCb); +#endif #endif // Main system loop @@ -332,10 +332,11 @@ static void objectUpdatedCb(UAVObjEvent * ev) } } +#ifndef NO_SENSORS /** * Called whenever a critical configuration component changes */ -#if (defined(COPTERCONTROL) || defined(REVOLUTION) || defined(SIM_OSX)) && ! (defined(SIM_POSIX)) + static void configurationUpdatedCb(UAVObjEvent * ev) { configuration_check(); diff --git a/flight/Modules/TxPID/txpid.c b/flight/Modules/TxPID/txpid.c index 090a5131b41..1d5fd3b7112 100644 --- a/flight/Modules/TxPID/txpid.c +++ b/flight/Modules/TxPID/txpid.c @@ -48,6 +48,10 @@ #include "accessorydesired.h" #include "manualcontrolcommand.h" #include "stabilizationsettings.h" +#ifdef UAVOBJ_INIT_vtolpathfollowersettings +#include "vtolpathfollowersettings.h" +#endif + #include "flightstatus.h" #include "modulesettings.h" @@ -70,7 +74,7 @@ // Private functions static void updatePIDs(UAVObjEvent* ev); -static uint8_t update(float *var, float val); +static bool update(float *var, float val); static float scale(float val, float inMin, float inMax, float outMin, float outMax); /** @@ -127,7 +131,7 @@ int32_t TxPIDInitialize(void) return -1; } -MODULE_INITCALL(TxPIDInitialize, NULL) +MODULE_INITCALL(TxPIDInitialize, NULL); /** * Update PIDs callback function @@ -151,9 +155,20 @@ static void updatePIDs(UAVObjEvent* ev) StabilizationSettingsData stab; StabilizationSettingsGet(&stab); + +#ifdef UAVOBJ_INIT_vtolpathfollowersettings + VtolPathFollowerSettingsData vtolPathFollowerSettingsData; + // Check to make sure the settings UAVObject has been instantiated + if (VtolPathFollowerSettingsHandle()) { + VtolPathFollowerSettingsGet(&vtolPathFollowerSettingsData); + } + + bool vtolPathFollowerSettingsNeedsUpdate = false; +#endif + AccessoryDesiredData accessory; - uint8_t needsUpdate = 0; + bool stabilizationSettingsNeedsUpdate = false; // Loop through every enabled instance for (uint8_t i = 0; i < TXPIDSETTINGS_PIDS_NUMELEM; i++) { @@ -174,159 +189,194 @@ static void updatePIDs(UAVObjEvent* ev) switch (inst.PIDs[i]) { case TXPIDSETTINGS_PIDS_ROLLRATEKP: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLRATEKI: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLRATEKD: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value); break; case TXPIDSETTINGS_PIDS_ROLLRATEILIMIT: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_ROLLATTITUDEKP: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLATTITUDEKI: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLATTITUDEILIMIT: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_PITCHRATEKP: - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value); break; case TXPIDSETTINGS_PIDS_PITCHRATEKI: - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value); break; case TXPIDSETTINGS_PIDS_PITCHRATEKD: - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value); break; case TXPIDSETTINGS_PIDS_PITCHRATEILIMIT: - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_PITCHATTITUDEKP: - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value); break; case TXPIDSETTINGS_PIDS_PITCHATTITUDEKI: - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value); break; case TXPIDSETTINGS_PIDS_PITCHATTITUDEILIMIT: - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKP: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value); - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKI: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value); - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHRATEKD: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value); - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_KD], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHRATEILIMIT: - needsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value); - needsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollRatePID[STABILIZATIONSETTINGS_ROLLRATEPID_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchRatePID[STABILIZATIONSETTINGS_PITCHRATEPID_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKP: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value); - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEKI: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value); - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHATTITUDEILIMIT: - needsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value); - needsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.RollPI[STABILIZATIONSETTINGS_ROLLPI_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.PitchPI[STABILIZATIONSETTINGS_PITCHPI_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_YAWRATEKP: - needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KP], value); break; case TXPIDSETTINGS_PIDS_YAWRATEKI: - needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KI], value); break; case TXPIDSETTINGS_PIDS_YAWRATEKD: - needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_KD], value); break; case TXPIDSETTINGS_PIDS_YAWRATEILIMIT: - needsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawRatePID[STABILIZATIONSETTINGS_YAWRATEPID_ILIMIT], value); break; case TXPIDSETTINGS_PIDS_YAWATTITUDEKP: - needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KP], value); break; case TXPIDSETTINGS_PIDS_YAWATTITUDEKI: - needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_KI], value); break; case TXPIDSETTINGS_PIDS_YAWATTITUDEILIMIT: - needsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value); + stabilizationSettingsNeedsUpdate |= update(&stab.YawPI[STABILIZATIONSETTINGS_YAWPI_ILIMIT], value); break; - case TXPIDSETTINGS_PIDS_GYROTAU: - needsUpdate |= update(&stab.GyroTau, value); + case TXPIDSETTINGS_PIDS_GYROCUTOFF: + stabilizationSettingsNeedsUpdate |= update(&stab.GyroCutoff, value); break; - case TXPIDSETTINGS_PIDS_ROLLVBARSENSITIVITY: - needsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_ROLL], value); + case TXPIDSETTINGS_PIDS_ROLLVBARSENSITIVITY: + stabilizationSettingsNeedsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_ROLL], value); break; case TXPIDSETTINGS_PIDS_PITCHVBARSENSITIVITY: - needsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_PITCH], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_PITCH], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHVBARSENSITIVITY: - needsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_ROLL], value); - needsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_PITCH], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_ROLL], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_PITCH], value); break; case TXPIDSETTINGS_PIDS_YAWVBARSENSITIVITY: - needsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_YAW], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarSensitivity[STABILIZATIONSETTINGS_VBARSENSITIVITY_YAW], value); break; case TXPIDSETTINGS_PIDS_ROLLVBARKP: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLVBARKI: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLVBARKD: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KD], value); break; case TXPIDSETTINGS_PIDS_PITCHVBARKP: - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KP], value); break; case TXPIDSETTINGS_PIDS_PITCHVBARKI: - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KI], value); break; case TXPIDSETTINGS_PIDS_PITCHVBARKD: - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KD], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHVBARKP: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KP], value); - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KP], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHVBARKI: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KI], value); - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KI], value); break; case TXPIDSETTINGS_PIDS_ROLLPITCHVBARKD: - needsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KD], value); - needsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarRollPID[STABILIZATIONSETTINGS_VBARROLLPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarPitchPID[STABILIZATIONSETTINGS_VBARPITCHPID_KD], value); break; case TXPIDSETTINGS_PIDS_YAWVBARKP: - needsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KP], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KP], value); break; case TXPIDSETTINGS_PIDS_YAWVBARKI: - needsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KI], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KI], value); break; case TXPIDSETTINGS_PIDS_YAWVBARKD: - needsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KD], value); + stabilizationSettingsNeedsUpdate |= update(&stab.VbarYawPID[STABILIZATIONSETTINGS_VBARYAWPID_KD], value); + break; +#ifdef UAVOBJ_INIT_vtolpathfollowersettings + case TXPIDSETTINGS_PIDS_HORIZONTALPOSKP: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KP], value); + break; + case TXPIDSETTINGS_PIDS_HORIZONTALPOSKI: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_KI], value); + break; + case TXPIDSETTINGS_PIDS_HORIZONTALPOSILIMIT: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalPosPI[VTOLPATHFOLLOWERSETTINGS_HORIZONTALPOSPI_ILIMIT], value); break; + case TXPIDSETTINGS_PIDS_HORIZONTALVELKP: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KP], value); + break; + case TXPIDSETTINGS_PIDS_HORIZONTALVELKI: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KI], value); + break; + case TXPIDSETTINGS_PIDS_HORIZONTALVELKD: + vtolPathFollowerSettingsNeedsUpdate |= update(&vtolPathFollowerSettingsData.HorizontalVelPID[VTOLPATHFOLLOWERSETTINGS_HORIZONTALVELPID_KD], value); + break; +#endif /* UAVOBJ_INIT_vtolpathfollowersettings */ default: - PIOS_Assert(0); + // Previously this would assert. But now the + // object may be missing and it's not worth a + // crash. + break; } } } - if (needsUpdate) + + // Update UAVOs, if necessary + if (stabilizationSettingsNeedsUpdate) { StabilizationSettingsSet(&stab); + } + +#ifdef UAVOBJ_INIT_vtolpathfollowersettings + if (vtolPathFollowerSettingsNeedsUpdate) { + // Check to make sure the settings UAVObject has been instantiated + if (VtolPathFollowerSettingsHandle()) { + VtolPathFollowerSettingsSet(&vtolPathFollowerSettingsData); + } + } +#endif } /** @@ -363,13 +413,13 @@ static float scale(float val, float inMin, float inMax, float outMin, float outM * Updates var using val if needed. * \returns 1 if updated, 0 otherwise */ -static uint8_t update(float *var, float val) +static bool update(float *var, float val) { if (*var != val) { *var = val; - return 1; + return true; } - return 0; + return false; } /** diff --git a/flight/Modules/UAVOFrSKYSPortBridge/UAVOFrSKYSPortBridge.c b/flight/Modules/UAVOFrSKYSPortBridge/UAVOFrSKYSPortBridge.c index f38aacc9a30..94c31835989 100644 --- a/flight/Modules/UAVOFrSKYSPortBridge/UAVOFrSKYSPortBridge.c +++ b/flight/Modules/UAVOFrSKYSPortBridge/UAVOFrSKYSPortBridge.c @@ -33,88 +33,27 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "pios.h" -#include "openpilot.h" -#include "modulesettings.h" -#include "misc_math.h" -#include "physical_constants.h" -#include "attitudeactual.h" +#include "frsky_packing.h" +#include "pios_thread.h" + #include "baroaltitude.h" -#include "positionactual.h" -#include "velocityactual.h" #include "flightbatterysettings.h" #include "flightbatterystate.h" #include "gpsposition.h" -#include "gpstime.h" -#include "homelocation.h" -#include "accels.h" -#include "flightstatus.h" -#include "airspeedactual.h" -#include "pios_thread.h" +#include "modulesettings.h" #if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) -static void uavoFrSKYSPortBridgeTask(void *parameters); -static bool frsky_encode_gps_course(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_altitude(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_vario(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_current(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_cells(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_t1(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_t2(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_fuel(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_acc(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_gps_coord(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_gps_alt(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_gps_speed(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_gps_time(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_rpm(uint32_t *value, bool test_presence_only, uint32_t arg); -static bool frsky_encode_airspeed(uint32_t *value, bool test_presence_only, uint32_t arg); - #define FRSKY_POLL_REQUEST 0x7e #define FRSKY_MINIMUM_POLL_INTERVAL 10000 -enum frsky_value_id { - FRSKY_ALT_ID = 0x0100, - FRSKY_VARIO_ID = 0x110, - FRSKY_CURR_ID = 0x0200, - FRSKY_VFAS_ID = 0x0210, - FRSKY_CELLS_ID = 0x0300, - FRSKY_T1_ID = 0x0400, - FRSKY_T2_ID = 0x0410, - FRSKY_RPM_ID = 0x0500, - FRSKY_FUEL_ID = 0x0600, - FRSKY_ACCX_ID = 0x0700, - FRSKY_ACCY_ID = 0x0710, - FRSKY_ACCZ_ID = 0x0720, - FRSKY_GPS_LON_LAT_ID = 0x0800, - FRSKY_GPS_ALT_ID = 0x0820, - FRSKY_GPS_SPEED_ID = 0x0830, - FRSKY_GPS_COURSE_ID = 0x0840, - FRSKY_GPS_TIME_ID = 0x0850, - FRSKY_ADC3_ID = 0x0900, - FRSKY_ADC4_ID = 0x0910, - FRSKY_AIR_SPEED_ID = 0x0a00, - FRSKY_RSSI_ID = 0xf101, - FRSKY_ADC1_ID = 0xf102, - FRSKY_ADC2_ID = 0xf103, - FRSKY_BATT_ID = 0xf104, - FRSKY_SWR_ID = 0xf105, -}; - enum frsky_state { FRSKY_STATE_WAIT_POLL_REQUEST, FRSKY_STATE_WAIT_SENSOR_ID, FRSKY_STATE_WAIT_TX_DONE, }; -struct frsky_value_item { - enum frsky_value_id id; - uint16_t period_ms; - bool (*encode_value)(uint32_t *value, bool test_presence_only, uint32_t arg); - uint32_t fn_arg; -}; - +// Set of objects sent by this module static const struct frsky_value_item frsky_value_items[] = { {FRSKY_GPS_COURSE_ID, 100, frsky_encode_gps_course, 0}, // attitude yaw estimate {FRSKY_ALT_ID, 100, frsky_encode_altitude, 0}, // altitude estimate @@ -129,9 +68,9 @@ static const struct frsky_value_item frsky_value_items[] = { {FRSKY_T1_ID, 2000, frsky_encode_t1, 0}, // baro temperature {FRSKY_T2_ID, 1500, frsky_encode_t2, 0}, // encodes GPS status! {FRSKY_FUEL_ID, 600, frsky_encode_fuel, 0}, // consumed battery energy - {FRSKY_ACCX_ID, 250, frsky_encode_acc, 0}, // accX - {FRSKY_ACCY_ID, 250, frsky_encode_acc, 1}, // accY - {FRSKY_ACCZ_ID, 250, frsky_encode_acc, 2}, // accZ + {FRSKY_ACCX_ID, 100, frsky_encode_acc, 0}, // accX + {FRSKY_ACCY_ID, 100, frsky_encode_acc, 1}, // accY + {FRSKY_ACCZ_ID, 100, frsky_encode_acc, 2}, // accZ {FRSKY_GPS_LON_LAT_ID, 100, frsky_encode_gps_coord, 0}, // lattitude {FRSKY_GPS_LON_LAT_ID, 100, frsky_encode_gps_coord, 1}, // longitude {FRSKY_GPS_ALT_ID, 750, frsky_encode_gps_alt, 0}, // gps altitude @@ -142,22 +81,18 @@ static const struct frsky_value_item frsky_value_items[] = { {FRSKY_AIR_SPEED_ID, 100, frsky_encode_airspeed, 0}, // airspeed }; -static const uint8_t frsky_sensor_ids[] = {0x1b, 0x0d, 0x34, 0x67}; struct frsky_sport_telemetry { - struct pios_thread *task; - uintptr_t com; - uint32_t item_last_triggered[NELEMENTS(frsky_value_items)]; - uint32_t last_poll_time; - uint8_t ignore_rx_chars; enum frsky_state state; int32_t scheduled_item; - bool use_current_sensor; - uint8_t batt_cell_count; - bool use_baro_sensor; - FlightBatterySettingsData battery_settings; - GPSPositionData gps_position; + uint32_t last_poll_time; + uint8_t ignore_rx_chars; + uintptr_t com; + struct frsky_settings frsky_settings; + uint32_t item_last_triggered[NELEMENTS(frsky_value_items)]; }; +static const uint8_t frsky_sensor_ids[] = {0x1b}; + #define FRSKY_SPORT_BAUDRATE 57600 #if defined(PIOS_FRSKY_SPORT_TELEMETRY_STACK_SIZE) @@ -169,481 +104,8 @@ struct frsky_sport_telemetry { static bool module_enabled; static struct frsky_sport_telemetry *frsky; - -/** - * Encode baro altitude value - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_altitude(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (!frsky->use_baro_sensor || (PositionActualHandle() == NULL)) - return false; - - if (test_presence_only) - return true; - // instead of encoding baro altitude directly, we will use - // more accurate estimation in PositionActual UAVO - float down = 0; - PositionActualDownGet(&down); - int32_t alt = (int32_t)(-down * 100.0f); - *value = (uint32_t) alt; - return true; -} - -/** - * Encode heading value - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_gps_course(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (AttitudeActualHandle() == NULL) - return false; - - if (test_presence_only) - return true; - - AttitudeActualData attitude; - AttitudeActualGet(&attitude); - float hdg = (attitude.Yaw >= 0) ? attitude.Yaw : (attitude.Yaw + 360.0f); - *value = (uint32_t)(hdg * 100.0f); - - return true; -} - -/** - * Encode vertical speed value - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_vario(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (!frsky->use_baro_sensor || VelocityActualHandle() == NULL) - return false; - - if (test_presence_only) - return true; - - float down = 0; - VelocityActualDownGet(&down); - int32_t vspeed = (int32_t)(-down * 100.0f); - *value = (uint32_t) vspeed; - - return true; -} - -/** - * Encode battery current value - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_current(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (!frsky->use_current_sensor) - return false; - if (test_presence_only) - return true; - - float current = 0; - FlightBatteryStateCurrentGet(¤t); - int32_t current_frsky = (int32_t)(current * 10.0f); - *value = (uint32_t) current_frsky; - - return true; -} - -/** - * Encode battery cells voltage - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[], index of battery cell pair - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_cells(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if ((frsky->batt_cell_count == 0) || (frsky->batt_cell_count - 1) < (arg * 2)) - return false; - if (test_presence_only) - return true; - - float voltage = 0; - FlightBatteryStateVoltageGet(&voltage); - - uint32_t cell_voltage = (uint32_t)((voltage * 500.0f) / frsky->batt_cell_count); - *value = ((cell_voltage & 0xfff) << 8) | ((arg * 2) & 0x0f) | ((frsky->batt_cell_count << 4) & 0xf0); - if (((int16_t)frsky->batt_cell_count - 1) >= (arg * 2 + 1)) - *value |= ((cell_voltage & 0xfff) << 20); - - return true; -} - -/** - * Encode temperature of barosensor as T1 - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_t1(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (!frsky->use_baro_sensor) - return false; - if (test_presence_only) - return true; - - float temp = 0; - BaroAltitudeTemperatureGet(&temp); - int32_t t1 = (int32_t)temp; - *value = (uint32_t)t1; - - return true; -} - -/** - * Encode GPS status as T2 value - * Right-most two digits means visible satellite count, left-most digit has following meaning: - * 0 - no GPS connected - * 1 - no fix - * 2 - 2D fix - * 3 - 3D fix - * 4 - 3D fix and HomeLocation is SET - should be safe for navigation - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_t2(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (GPSPositionHandle() == NULL) - return false; - if (test_presence_only) - return true; - uint8_t hl_set = HOMELOCATION_SET_FALSE; - if (HomeLocationHandle()) - HomeLocationSetGet(&hl_set); - - int32_t t2 = 0; - switch (frsky->gps_position.Status) { - case GPSPOSITION_STATUS_NOGPS: - t2 = 0; - break; - case GPSPOSITION_STATUS_NOFIX: - t2 = 100; - break; - case GPSPOSITION_STATUS_FIX2D: - t2 = 200; - break; - case GPSPOSITION_STATUS_FIX3D: - case GPSPOSITION_STATUS_DIFF3D: - if (hl_set == HOMELOCATION_SET_TRUE) - t2 = 400; - else - t2 = 300; - break; - } - if (frsky->gps_position.Satellites > 0) - t2 += frsky->gps_position.Satellites; - - *value = (uint32_t)t2; - - return true; -} - -/** - * Encode consumed battery energy as fuel - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_fuel(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (!frsky->use_current_sensor) - return false; - if (test_presence_only) - return true; - - uint32_t capacity = frsky->battery_settings.Capacity; - float consumed_mahs = 0; - FlightBatteryStateConsumedEnergyGet(&consumed_mahs); - - float fuel = (uint32_t)(100.0f * (1.0f - consumed_mahs / capacity)); - fuel = bound_min_max(fuel, 0.0f, 100.0f); - *value = (uint32_t) fuel; - - return true; -} - -/** - * Encode accelerometer values - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[]; 0=X, 1=Y, 2=Z - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_acc(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (AccelsHandle() == NULL) - return false; - if (test_presence_only) - return true; - - float acc = 0; - switch (arg) { - case 0: - AccelsxGet(&acc); - break; - case 1: - AccelsyGet(&acc); - break; - case 2: - AccelszGet(&acc); - break; - } - - acc /= GRAVITY; - acc *= 100.0f; - - int32_t frsky_acc = (int32_t) acc; - *value = (uint32_t) frsky_acc; - - return true; -} - -/** - * Encode gps coordinates - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[]; 0=lattitude, 1=longitude - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_gps_coord(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (GPSPositionHandle() == NULL) - return false; - if (frsky->gps_position.Status == GPSPOSITION_STATUS_NOFIX - || frsky->gps_position.Status == GPSPOSITION_STATUS_NOGPS) - return false; - if (test_presence_only) - return true; - - uint32_t frsky_coord = 0; - int32_t coord = 0; - if (arg == 0) { - // lattitude - coord = frsky->gps_position.Latitude; - if (coord >= 0) - frsky_coord = 0; - else - frsky_coord = 1 << 30; - } else { - // longitude - coord = frsky->gps_position.Longitude; - if (coord >= 0) - frsky_coord = 2 << 30; - else - frsky_coord = 3 << 30; - } - coord = abs(coord); - frsky_coord |= (((uint64_t)coord * 6ull) / 100); - - *value = frsky_coord; - return true; -} - -/** - * Encode gps altitude - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_gps_alt(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (GPSPositionHandle() == NULL) - return false; - if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D - && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) - return false; - if (test_presence_only) - return true; - - int32_t frsky_gps_alt = (int32_t)(frsky->gps_position.Altitude * 100.0f); - *value = (uint32_t)frsky_gps_alt; - - return true; -} - -/** - * Encode gps speed - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_gps_speed(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (GPSPositionHandle() == NULL) - return false; - if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D - && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) - return false; - if (test_presence_only) - return true; - - int32_t frsky_speed = (int32_t)((frsky->gps_position.Groundspeed / KNOTS2M_PER_SECOND) * 1000); - *value = frsky_speed; - return true; -} - -/** - * Encode GPS UTC time - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[]; 0=date, 1=time - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_gps_time(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (GPSPositionHandle() == NULL || GPSTimeHandle() == NULL) - return false; - if (frsky->gps_position.Status != GPSPOSITION_STATUS_FIX3D - && frsky->gps_position.Status != GPSPOSITION_STATUS_DIFF3D) - return false; - if (test_presence_only) - return true; - - GPSTimeData gps_time; - GPSTimeGet(&gps_time); - uint32_t frsky_time = 0; - - if (arg == 0) { - // encode date - frsky_time = 0x000000ff; - frsky_time |= gps_time.Day << 8; - frsky_time |= gps_time.Month << 16; - frsky_time |= (gps_time.Year % 100) << 24; - } else { - frsky_time = 0; - frsky_time |= gps_time.Second << 8; - frsky_time |= gps_time.Minute << 16; - frsky_time |= gps_time.Hour << 24; - } - *value = frsky_time; - return true; -} - -/** - * Encodes ARM status and flight mode number as RPM value - * Since there is no RPM information in any UAVO available, - * we will intentionaly misuse this item to encode another useful information. - * It will encode flight status as three-digit number as follow: - * most left digit encodes arm status (1=armed, 0=disarmed) - * two most right digits encodes flight mode number (see FlightStatus UAVO FlightMode enum) - * To work this propperly on Taranis, you have to set Blades to "1" in telemetry setting - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_rpm(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (FlightStatusHandle() == NULL) - return false; - if (test_presence_only) - return true; - - FlightStatusData flight_status; - FlightStatusGet(&flight_status); - - *value = (flight_status.Armed == FLIGHTSTATUS_ARMED_ARMED) ? 100 : 0; - *value += flight_status.FlightMode; - - return true; -} - -/** - * Encode true airspeed(TAS) - * @param[out] value encoded value - * @param[in] test_presence_only true when function should only test for availability of this value - * @param[in] arg argument specified in frsky_value_items[] - * @returns true when value succesfully encoded or presence test passed - */ -static bool frsky_encode_airspeed(uint32_t *value, bool test_presence_only, uint32_t arg) -{ - if (AirspeedActualHandle() == NULL) - return false; - if (test_presence_only) - return true; - - AirspeedActualData airspeed; - AirspeedActualGet(&airspeed); - int32_t frsky_speed = (int32_t)((airspeed.TrueAirspeed / KNOTS2M_PER_SECOND) * 10); - *value = (uint32_t)frsky_speed; - - return true; -} - -/** - * Performs byte stuffing and checksum calculation - * @param[out] obuff buffer where byte stuffed data will came in - * @param[in,out] chk checksum byte to update - * @param[in] byte - * @returns count of bytes inserted to obuff (1 or 2) - */ -static uint8_t frsky_insert_byte(uint8_t *obuff, uint16_t *chk, uint8_t byte) -{ - /* checksum calculation is based on data before byte-stuffing */ - *chk += byte; - *chk += (*chk) >> 8; - *chk &= 0x00ff; - *chk += (*chk) >> 8; - *chk &= 0x00ff; - - if (byte == 0x7e || byte == 0x7d) { - obuff[0] = 0x7d; - obuff[1] = byte &= ~0x20; - return 2; - } - - obuff[0] = byte; - return 1; -} -/** - * Send u32 value dataframe to FrSky SmartPort bus - * @param[in] id FrSky value ID - * @param[in] value value - */ -static void frsky_send_frame(enum frsky_value_id id, uint32_t value) -{ - /* each call of frsky_insert_byte can add 2 bytes to the buffer at maximum - * and therefore the worst-case is 15 bytes total (the first byte 0x10 won't be - * escaped) */ - uint8_t tx_data[15]; - uint16_t chk = 0; - uint8_t cnt = 0; - cnt += frsky_insert_byte(&tx_data[cnt], &chk, 0x10); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, (uint16_t)id & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, ((uint16_t)id >> 8) & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, value & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 8) & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 16) & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, (value >> 24) & 0xff); - cnt += frsky_insert_byte(&tx_data[cnt], &chk, 0xff - chk); - - PIOS_COM_SendBuffer(frsky->com, tx_data, cnt); - - frsky->ignore_rx_chars = cnt; -} +static int32_t uavoFrSKYSPortBridgeInitialize(void); +static void uavoFrSKYSPortBridgeTask(void *parameters); /** * Scan for value item with the longest expired time and schedule it to send in next poll turn @@ -655,7 +117,7 @@ static void frsky_schedule_next_item(void) int32_t max_exp_time = INT32_MIN; int32_t most_exp_item = -1; for (i = 0; i < NELEMENTS(frsky_value_items); i++) { - if (frsky_value_items[i].encode_value(0, true, frsky_value_items[i].fn_arg)) { + if (frsky_value_items[i].encode_value(&frsky->frsky_settings, 0, true, frsky_value_items[i].fn_arg)) { int32_t exp_time = PIOS_DELAY_GetuSSince(frsky->item_last_triggered[i]) - (frsky_value_items[i].period_ms * 1000); if (exp_time > max_exp_time) { @@ -676,9 +138,9 @@ static bool frsky_send_scheduled_item(void) if ((item >= 0) && (item < NELEMENTS(frsky_value_items))) { frsky->item_last_triggered[item] = PIOS_DELAY_GetuS(); uint32_t value = 0; - if (frsky_value_items[item].encode_value(&value, false, + if (frsky_value_items[item].encode_value(&frsky->frsky_settings, &value, false, frsky_value_items[item].fn_arg)) { - frsky_send_frame((uint16_t)(frsky_value_items[item].id), value); + frsky->ignore_rx_chars += frsky_send_frame(frsky->com, (uint16_t)(frsky_value_items[item].id), value); return true; } } @@ -718,7 +180,7 @@ static void frsky_receive_byte(uint8_t b) // get GPSPositionData once here to be more efficient, since // GPS position data are very often used by encode() handlers if (GPSPositionHandle() != NULL) - GPSPositionGet(&frsky->gps_position); + GPSPositionGet(&frsky->frsky_settings.gps_position); // send item previously scheduled if (frsky_send_scheduled_item() && frsky->ignore_rx_chars) frsky->state = FRSKY_STATE_WAIT_TX_DONE; @@ -745,19 +207,20 @@ static int32_t uavoFrSKYSPortBridgeStart(void) uint8_t currentPin; FlightBatterySettingsCurrentPinGet(¤tPin); if (currentPin != FLIGHTBATTERYSETTINGS_CURRENTPIN_NONE) - frsky->use_current_sensor = true; - FlightBatterySettingsGet(&frsky->battery_settings); - frsky->batt_cell_count = frsky->battery_settings.NbCells; + frsky->frsky_settings.use_current_sensor = true; + FlightBatterySettingsGet(&frsky->frsky_settings.battery_settings); + frsky->frsky_settings.batt_cell_count = frsky->frsky_settings.battery_settings.NbCells; } if (BaroAltitudeHandle() != NULL && PIOS_SENSORS_GetQueue(PIOS_SENSOR_BARO) != NULL) - frsky->use_baro_sensor = true; + frsky->frsky_settings.use_baro_sensor = true; - frsky->task = PIOS_Thread_Create( + struct pios_thread *task; + task = PIOS_Thread_Create( uavoFrSKYSPortBridgeTask, "uavoFrSKYSPortBridge", STACK_SIZE_BYTES, NULL, TASK_PRIORITY); TaskMonitorAdd(TASKINFO_RUNNING_UAVOFRSKYSPORTBRIDGE, - frsky->task); + task); return 0; } @@ -779,14 +242,14 @@ static int32_t uavoFrSKYSPortBridgeInitialize(void) if (frsky != NULL) { memset(frsky, 0x00, sizeof(struct frsky_sport_telemetry)); - frsky->com = sport_com; - frsky->ignore_rx_chars = 0; - frsky->last_poll_time = PIOS_DELAY_GetuS(); + frsky->frsky_settings.use_current_sensor = false; + frsky->frsky_settings.batt_cell_count = 0; + frsky->frsky_settings.use_baro_sensor = false; frsky->state = FRSKY_STATE_WAIT_POLL_REQUEST; + frsky->last_poll_time = PIOS_DELAY_GetuS(); + frsky->ignore_rx_chars = 0; frsky->scheduled_item = -1; - frsky->use_current_sensor = false; - frsky->batt_cell_count = 0; - frsky->use_baro_sensor = false; + frsky->com = sport_com; uint8_t i; for (i = 0; i < NELEMENTS(frsky_value_items); i++) diff --git a/flight/Modules/UAVOFrSKYSensorHubBridge/UAVOFrSKYSensorHubBridge.c b/flight/Modules/UAVOFrSKYSensorHubBridge/UAVOFrSKYSensorHubBridge.c index 1529493fa02..fb848234ca0 100644 --- a/flight/Modules/UAVOFrSKYSensorHubBridge/UAVOFrSKYSensorHubBridge.c +++ b/flight/Modules/UAVOFrSKYSensorHubBridge/UAVOFrSKYSensorHubBridge.c @@ -37,8 +37,12 @@ #include "gpsposition.h" #include "airspeedactual.h" #include "baroaltitude.h" +#include "homelocation.h" #include "accels.h" #include "flightstatus.h" +#include "nedaccel.h" +#include "velocityactual.h" +#include "attitudeactual.h" #include "pios_thread.h" #if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) @@ -51,8 +55,11 @@ static uint16_t frsky_pack_altitude( float altitude, uint8_t *serial_buf); -static uint16_t frsky_pack_temperature( +static uint16_t frsky_pack_temperature_01( float temperature_01, + uint8_t *serial_buf); + +static uint16_t frsky_pack_temperature_02( float temperature_02, uint8_t *serial_buf); @@ -248,8 +255,8 @@ static void uavoFrSKYSensorHubBridgeTask(void *parameters) FlightBatteryStateData batState; GPSPositionData gpsPosData; BaroAltitudeData baroAltitude; - AccelsData accels; FlightStatusData flightStatus; + float accX = 0, accY = 0, accZ = 0; if (FlightBatterySettingsHandle() != NULL ) FlightBatterySettingsGet(&batSettings); @@ -288,15 +295,6 @@ static void uavoFrSKYSensorHubBridgeTask(void *parameters) batState.Voltage = 0; } - if (AccelsHandle() != NULL ) - AccelsGet(&accels); - else { - accels.x = 0.0; - accels.y = 0.0; - accels.z = 0.0; - accels.temperature = 0.0; - } - uint8_t last_armed = FLIGHTSTATUS_ARMED_DISARMED; float altitude_offset = 0.0f; @@ -311,14 +309,56 @@ static void uavoFrSKYSensorHubBridgeTask(void *parameters) if (frame_trigger(FRSKY_FRAME_VARIO)) { msg_length = 0; - - if (AccelsHandle() != NULL) - AccelsGet(&accels); + + uint8_t accelDataSettings; + ModuleSettingsFrskyAccelDataGet(&accelDataSettings); + switch(accelDataSettings) { + case MODULESETTINGS_FRSKYACCELDATA_ACCELS: { + if (AccelsHandle() != NULL) { + AccelsxGet(&accX); + AccelsyGet(&accY); + AccelszGet(&accZ); + } + break; + } +#ifndef SMALLF1 + case MODULESETTINGS_FRSKYACCELDATA_NEDACCELS: { + if (NedAccelHandle() != NULL) { + NedAccelNorthGet(&accX); + NedAccelEastGet(&accY); + NedAccelDownGet(&accZ); + } + break; + } + case MODULESETTINGS_FRSKYACCELDATA_NEDVELOCITY: { + if (VelocityActualHandle() != NULL) { + VelocityActualNorthGet(&accX); + VelocityActualEastGet(&accY); + VelocityActualDownGet(&accZ); + accX *= GRAVITY / 10.0f; + accY *= GRAVITY / 10.0f; + accZ *= GRAVITY / 10.0f; + } + break; + } +#endif + case MODULESETTINGS_FRSKYACCELDATA_ATTITUDEANGLES: { + if (AttitudeActualHandle() != NULL) { + AttitudeActualRollGet(&accX); + AttitudeActualPitchGet(&accY); + AttitudeActualYawGet(&accZ); + accX *= GRAVITY / 10.0f; + accY *= GRAVITY / 10.0f; + accZ *= GRAVITY / 10.0f; + } + break; + } + } msg_length += frsky_pack_accel( - accels.x, - accels.y, - accels.z, + accX, + accY, + accZ, serial_buf + msg_length); if (BaroAltitudeHandle() != NULL) @@ -338,16 +378,6 @@ static void uavoFrSKYSensorHubBridgeTask(void *parameters) altitude, serial_buf + msg_length); - msg_length += frsky_pack_temperature( - baroAltitude.Temperature, - accels.temperature, - serial_buf + msg_length); - - // No idea what could be used as RPM - msg_length += frsky_pack_rpm( - 0, - serial_buf + msg_length); - msg_length += frsky_pack_stop(serial_buf + msg_length); PIOS_COM_SendBuffer(frsky_port, serial_buf, msg_length); @@ -400,9 +430,85 @@ static void uavoFrSKYSensorHubBridgeTask(void *parameters) if (frame_trigger(FRSKY_FRAME_GPS)) { msg_length = 0; - if (GPSPositionHandle() != NULL ) { + /** + * Encodes ARM status and flight mode number as RPM value + * Since there is no RPM information in any UAVO available, + * we will intentionally misuse this item to encode other useful information. + * It will encode flight status as three-digit number as follow: + * most left digit encodes arm status (200=armed, 100=disarmed) + * two most right digits encode flight mode number (see FlightStatus UAVO FlightMode enum) + * To work properly on Taranis, you have to set Blades to "60" in telemetry setting + */ + FlightStatusData flight_status; + FlightStatusGet(&flight_status); + + uint16_t status = 0; + float hdop, vdop; + + status = (flight_status.Armed == FLIGHTSTATUS_ARMED_ARMED) ? 200 : 100; + status += flight_status.FlightMode; + + msg_length += frsky_pack_rpm(status, serial_buf + msg_length); + + uint8_t hl_set = HOMELOCATION_SET_FALSE; + + if (GPSPositionHandle() != NULL) GPSPositionGet(&gpsPosData); + + if (HomeLocationHandle() != NULL) + HomeLocationSetGet(&hl_set); + + /** + * Encode GPS status and visible satellites as T1 value + * We will intentionally misuse this item to encode other useful information. + * Right-most two digits encode visible satellite count, left-most digit has following meaning: + * 1 - no GPS connected + * 2 - no fix + * 3 - 2D fix + * 4 - 3D fix + * 5 - 3D fix and HomeLocation is SET - should be safe for navigation + */ + switch (gpsPosData.Status) { + case GPSPOSITION_STATUS_NOGPS: + status = 100; + break; + case GPSPOSITION_STATUS_NOFIX: + status = 200; + break; + case GPSPOSITION_STATUS_FIX2D: + status = 300; + break; + case GPSPOSITION_STATUS_FIX3D: + case GPSPOSITION_STATUS_DIFF3D: + if (hl_set == HOMELOCATION_SET_TRUE) + status = 500; + else + status = 400; + break; } + + if (gpsPosData.Satellites > 0) + status += gpsPosData.Satellites; + + msg_length += frsky_pack_temperature_01((float)status, serial_buf + msg_length); + + /** + * Encode GPS HDOP and VDOP as T2 value + * We will intentionally misuse this item to encode other useful information. + * VDOP in the upper 16 bits, max 256 (2.56 * 100) + * HDOP in the lower 16 bits, max 256 (2.56 * 100) + */ + hdop = gpsPosData.HDOP * 100.0f; + + if (hdop > 255.0f) + hdop = 255.0f; + + vdop = gpsPosData.VDOP * 100.0f; + + if (vdop > 255.0f) + vdop = 255.0f; + + msg_length += frsky_pack_temperature_02((vdop * 256 + hdop), serial_buf + msg_length); if (gpsPosData.Status == GPSPOSITION_STATUS_FIX2D || gpsPosData.Status == GPSPOSITION_STATUS_FIX3D) { @@ -464,12 +570,11 @@ static uint16_t frsky_pack_altitude(float altitude, uint8_t *serial_buf) } /** - * Writes temperatures to buffer + * Writes baro temperature to buffer * \return number of bytes written to the buffer */ -static uint16_t frsky_pack_temperature( +static uint16_t frsky_pack_temperature_01( float temperature_01, - float temperature_02, uint8_t *serial_buf) { uint8_t index = 0; @@ -477,7 +582,20 @@ static uint16_t frsky_pack_temperature( int16_t temperature = lroundf(temperature_01); frsky_serialize_value(FRSKY_TEMPERATURE_1, (uint8_t*)&temperature, serial_buf, &index); - temperature = lroundf(temperature_02); + return index; +} + +/** + * Writes accel temperature to buffer + * \return number of bytes written to the buffer + */ +static uint16_t frsky_pack_temperature_02( + float temperature_02, + uint8_t *serial_buf) +{ + uint8_t index = 0; + + int16_t temperature = lroundf(temperature_02); frsky_serialize_value(FRSKY_TEMPERATURE_2, (uint8_t*)&temperature, serial_buf, &index); return index; @@ -555,9 +673,7 @@ static uint16_t frsky_pack_fas( * Writes rpm value to buffer * \return number of bytes written to the buffer */ -static uint16_t frsky_pack_rpm( - uint16_t rpm, - uint8_t *serial_buf) +static uint16_t frsky_pack_rpm(uint16_t rpm, uint8_t *serial_buf) { uint8_t index = 0; diff --git a/flight/Modules/UAVOHoTTBridge/inc/uavohottbridge.h b/flight/Modules/UAVOHoTTBridge/inc/uavohottbridge.h index 70597653284..76b23a86694 100644 --- a/flight/Modules/UAVOHoTTBridge/inc/uavohottbridge.h +++ b/flight/Modules/UAVOHoTTBridge/inc/uavohottbridge.h @@ -389,4 +389,4 @@ struct hott_text_message { /** * @} * @} - */ \ No newline at end of file + */ diff --git a/flight/Modules/UAVOMavlinkBridge/UAVOMavlinkBridge.c b/flight/Modules/UAVOMavlinkBridge/UAVOMavlinkBridge.c index 14524570274..9cca94bca81 100644 --- a/flight/Modules/UAVOMavlinkBridge/UAVOMavlinkBridge.c +++ b/flight/Modules/UAVOMavlinkBridge/UAVOMavlinkBridge.c @@ -45,6 +45,8 @@ #include "mavlink.h" #include "pios_thread.h" +#include "custom_types.h" + // **************** // Private functions @@ -57,7 +59,7 @@ static bool stream_trigger(enum MAV_DATA_STREAM stream_num); #if defined(PIOS_MAVLINK_STACK_SIZE) #define STACK_SIZE_BYTES PIOS_MAVLINK_STACK_SIZE #else -#define STACK_SIZE_BYTES 800 +#define STACK_SIZE_BYTES 696 #endif #define TASK_PRIORITY PIOS_THREAD_PRIO_LOW @@ -140,84 +142,27 @@ MODULE_INITCALL( uavoMavlinkBridgeInitialize, uavoMavlinkBridgeStart) */ static void uavoMavlinkBridgeTask(void *parameters) { - FlightBatterySettingsData batSettings; - FlightBatteryStateData batState; - GPSPositionData gpsPosData; - ManualControlCommandData manualState; - AttitudeActualData attActual; - AirspeedActualData airspeedActual; - ActuatorDesiredData actDesired; - FlightStatusData flightStatus; - SystemStatsData systemStats; - HomeLocationData homeLocation; - BaroAltitudeData baroAltitude; - - if (FlightBatterySettingsHandle() != NULL ) - FlightBatterySettingsGet(&batSettings); - else { - batSettings.Capacity = 0; - batSettings.SensorCalibrationFactor[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONFACTOR_CURRENT] = 0; - batSettings.SensorCalibrationFactor[FLIGHTBATTERYSETTINGS_SENSORCALIBRATIONFACTOR_VOLTAGE] = 0; - batSettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_WARNING] = 0; - batSettings.VoltageThresholds[FLIGHTBATTERYSETTINGS_VOLTAGETHRESHOLDS_ALARM] = 0; - batSettings.VoltagePin = FLIGHTBATTERYSETTINGS_VOLTAGEPIN_NONE; - batSettings.CurrentPin = FLIGHTBATTERYSETTINGS_CURRENTPIN_NONE; - } - - if (GPSPositionHandle() == NULL ){ - gpsPosData.Altitude = 0; - gpsPosData.GeoidSeparation = 0; - gpsPosData.Groundspeed = 0; - gpsPosData.HDOP = 0; - gpsPosData.Heading = 0; - gpsPosData.Latitude = 0; - gpsPosData.Longitude = 0; - gpsPosData.PDOP = 0; - gpsPosData.Satellites = 0; - gpsPosData.Status = 0; - gpsPosData.VDOP = 0; - } - - if (FlightBatteryStateHandle() == NULL ) { - batState.AvgCurrent = 0; - batState.BoardSupplyVoltage = 0; - batState.ConsumedEnergy = 0; - batState.Current = 0; - batState.EstimatedFlightTime = 0; - batState.PeakCurrent = 0; - batState.Voltage = 0; - } - - if (AirspeedActualHandle() == NULL ) { - airspeedActual.CalibratedAirspeed = 0; - airspeedActual.TrueAirspeed = 0; - airspeedActual.alpha = 0; - airspeedActual.beta = 0; - } - - if (HomeLocationHandle() == NULL ) { - homeLocation.Set=HOMELOCATION_SET_FALSE; - homeLocation.Latitude = 0; - homeLocation.Longitude = 0; - homeLocation.Altitude = 0; - homeLocation.Be[0] = 0; - homeLocation.Be[1] = 0; - homeLocation.Be[2] = 0; - homeLocation.GroundTemperature = (STANDARD_AIR_TEMPERATURE - CELSIUS2KELVIN) * 10; - homeLocation.SeaLevelPressure = STANDARD_AIR_SEA_LEVEL_PRESSURE/1000; - } - uint16_t msg_length; uint32_t lastSysTime; // Main task loop lastSysTime = PIOS_Thread_Systime(); + FlightBatterySettingsData batSettings = {}; + + if (FlightBatterySettingsHandle() != NULL ) + FlightBatterySettingsGet(&batSettings); + + SystemStatsData systemStats; + while (1) { PIOS_Thread_Sleep_Until(&lastSysTime, 1000 / TASK_RATE_HZ); if (stream_trigger(MAV_DATA_STREAM_EXTENDED_STATUS)) { + FlightBatteryStateData batState = {}; + if (FlightBatteryStateHandle() != NULL ) FlightBatteryStateGet(&batState); + SystemStatsGet(&systemStats); int8_t battery_remaining = 0; @@ -267,6 +212,9 @@ static void uavoMavlinkBridgeTask(void *parameters) { } if (stream_trigger(MAV_DATA_STREAM_RC_CHANNELS)) { + ManualControlCommandData manualState; + FlightStatusData flightStatus; + ManualControlCommandGet(&manualState); FlightStatusGet(&flightStatus); SystemStatsGet(&systemStats); @@ -300,6 +248,10 @@ static void uavoMavlinkBridgeTask(void *parameters) { } if (stream_trigger(MAV_DATA_STREAM_POSITION)) { + GPSPositionData gpsPosData = {}; + HomeLocationData homeLocation = {}; + SystemStatsGet(&systemStats); + if (GPSPositionHandle() != NULL ) GPSPositionGet(&gpsPosData); if (HomeLocationHandle() != NULL ) @@ -373,6 +325,9 @@ static void uavoMavlinkBridgeTask(void *parameters) { } if (stream_trigger(MAV_DATA_STREAM_EXTRA1)) { + AttitudeActualData attActual; + SystemStatsData systemStats; + AttitudeActualGet(&attActual); SystemStatsGet(&systemStats); @@ -396,6 +351,13 @@ static void uavoMavlinkBridgeTask(void *parameters) { } if (stream_trigger(MAV_DATA_STREAM_EXTRA2)) { + ActuatorDesiredData actDesired; + AttitudeActualData attActual; + AirspeedActualData airspeedActual = {}; + GPSPositionData gpsPosData = {}; + BaroAltitudeData baroAltitude = {}; + FlightStatusData flightStatus; + if (AirspeedActualHandle() != NULL ) AirspeedActualGet(&airspeedActual); if (GPSPositionHandle() != NULL ) @@ -404,6 +366,7 @@ static void uavoMavlinkBridgeTask(void *parameters) { BaroAltitudeGet(&baroAltitude); ActuatorDesiredGet(&actDesired); AttitudeActualGet(&attActual); + FlightStatusGet(&flightStatus); float altitude = 0; if (BaroAltitudeHandle() != NULL) @@ -436,6 +399,46 @@ static void uavoMavlinkBridgeTask(void *parameters) { if (flightStatus.Armed == FLIGHTSTATUS_ARMED_ARMED) armed_mode |= MAV_MODE_FLAG_SAFETY_ARMED; + uint8_t custom_mode = CUSTOM_MODE_STAB; + + switch (flightStatus.FlightMode) { + case FLIGHTSTATUS_FLIGHTMODE_MANUAL: + case FLIGHTSTATUS_FLIGHTMODE_MWRATE: + case FLIGHTSTATUS_FLIGHTMODE_VIRTUALBAR: + case FLIGHTSTATUS_FLIGHTMODE_HORIZON: + /* Kinda a catch all */ + custom_mode = CUSTOM_MODE_SPORT; + break; + case FLIGHTSTATUS_FLIGHTMODE_ACRO: + case FLIGHTSTATUS_FLIGHTMODE_AXISLOCK: + custom_mode = CUSTOM_MODE_ACRO; + break; + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED1: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED2: + case FLIGHTSTATUS_FLIGHTMODE_STABILIZED3: + /* May want these three to try and + * infer based on roll axis */ + case FLIGHTSTATUS_FLIGHTMODE_LEVELING: + custom_mode = CUSTOM_MODE_STAB; + break; + case FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE: + custom_mode = CUSTOM_MODE_DRIFT; + break; + case FLIGHTSTATUS_FLIGHTMODE_ALTITUDEHOLD: + custom_mode = CUSTOM_MODE_ALTH; + break; + case FLIGHTSTATUS_FLIGHTMODE_RETURNTOHOME: + custom_mode = CUSTOM_MODE_RTL; + break; + case FLIGHTSTATUS_FLIGHTMODE_TABLETCONTROL: + case FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD: + custom_mode = CUSTOM_MODE_POSH; + break; + case FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER: + custom_mode = CUSTOM_MODE_AUTO; + break; + } + mavlink_msg_heartbeat_pack(0, 200, &mavMsg, // type Type of the MAV (quadrotor, helicopter, etc., up to 15 types, defined in MAV_TYPE ENUM) MAV_TYPE_GENERIC, @@ -444,7 +447,7 @@ static void uavoMavlinkBridgeTask(void *parameters) { // base_mode System mode bitfield, see MAV_MODE_FLAGS ENUM in mavlink/include/mavlink_types.h armed_mode, // custom_mode A bitfield for use for autopilot-specific flags. - 0, + custom_mode, // system_status System status flag, see MAV_STATE ENUM 0); msg_length = mavlink_msg_to_send_buffer(serial_buf, &mavMsg); diff --git a/flight/Modules/UAVOTaranis/UAVOTaranis.c b/flight/Modules/UAVOTaranis/UAVOTaranis.c new file mode 100644 index 00000000000..1522e48524c --- /dev/null +++ b/flight/Modules/UAVOTaranis/UAVOTaranis.c @@ -0,0 +1,312 @@ +/** + ****************************************************************************** + * @addtogroup TauLabsModules TauLabs Modules + * @{ + * @addtogroup UAVOTaranis UAVO to Taranis S.PORT converter + * @{ + * + * @file uavoFrSKYSensorHubBridge.c + * @author Tau Labs, http://taulabs.org, Copyright (C) 2015 + * @brief Bridges selected UAVObjects to Taranis S.PORT + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* + * This module is derived from UAVOFrSKYSportPort but differs + * in a number of ways. Specifically the SPort code is expected + * to listen for sensor requests and respond appropriately. This + * code simply can spew data to the Taranis (since it is talking + * to different harware). The scheduling system is reused between + * the two, but duplicated because it isn't really part of the + * packing, and touches on the private state of the state machine + * code in the module + */ + +#include "frsky_packing.h" +#include "pios_thread.h" + +#include "openpilot.h" +#include "physical_constants.h" +#include "modulesettings.h" +#include "flightbatterysettings.h" +#include "flightbatterystate.h" +#include "gpsposition.h" +#include "airspeedactual.h" +#include "baroaltitude.h" +#include "accels.h" +#include "positionactual.h" +#include "velocityactual.h" +#include "flightstatus.h" +#include "rfm22bstatus.h" + +#if defined(PIOS_INCLUDE_TARANIS_SPORT) + +static void uavoTaranisTask(void *parameters); + +static bool frsky_encode_rssi(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +static bool frsky_encode_swr(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); +static bool frsky_encode_battery(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg); + +#define FRSKY_POLL_REQUEST 0x7e +#define FRSKY_MINIMUM_POLL_INTERVAL 10000 + +#define VOLT_RATIO (20) + +enum frsky_state { + FRSKY_STATE_WAIT_POLL_REQUEST, + FRSKY_STATE_WAIT_SENSOR_ID, + FRSKY_STATE_WAIT_TX_DONE, +}; + +static const struct frsky_value_item frsky_value_items[] = { + {FRSKY_CURR_ID, 300, frsky_encode_current, 0}, // battery current + {FRSKY_BATT_ID, 200, frsky_encode_battery, 0}, // send battery voltage + {FRSKY_FUEL_ID, 200, frsky_encode_fuel, 0}, // consumed battery energy + {FRSKY_RSSI_ID, 100, frsky_encode_rssi, 0}, // send RSSI information + {FRSKY_SWR_ID, 100, frsky_encode_swr, 0}, // send RSSI information + {FRSKY_ALT_ID, 100, frsky_encode_altitude, 0}, // altitude estimate + {FRSKY_VARIO_ID, 100, frsky_encode_vario, 0}, // vertical speed + {FRSKY_RPM_ID, 1500, frsky_encode_rpm, 0}, // encodes flight status! + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 0}, // battery cells 1-2 + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 1}, // battery cells 3-4 + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 2}, // battery cells 5-6 + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 3}, // battery cells 7-8 + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 4}, // battery cells 9-10 + {FRSKY_CELLS_ID, 850, frsky_encode_cells, 5}, // battery cells 11-12 +}; + +struct frsky_sport_telemetry { + enum frsky_state state; + int32_t scheduled_item; + uint32_t last_poll_time; + uint8_t ignore_rx_chars; + uintptr_t com; + struct frsky_settings frsky_settings; + uint32_t item_last_triggered[NELEMENTS(frsky_value_items)]; +}; + +#define FRSKY_SPORT_BAUDRATE 57600 + +#if defined(PIOS_FRSKY_SPORT_TELEMETRY_STACK_SIZE) +#define STACK_SIZE_BYTES PIOS_FRSKY_SPORT_TELEMETRY_STACK_SIZE +#else +#define STACK_SIZE_BYTES 672 +#endif +#define TASK_PRIORITY PIOS_THREAD_PRIO_LOW + +static struct pios_thread *uavoTaranisTaskHandle; +static bool module_enabled; +static struct frsky_sport_telemetry *frsky; + +/** + * Encode RSSI value + * @param[out] value encoded value + * @param[in] test_presence_only true when function should only test for availability of this value + * @param[in] arg argument specified in frsky_value_items[] + * @returns true when value succesfully encoded or presence test passed + */ +static bool frsky_encode_rssi(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + uint8_t local_link_quality, local_link_connected; + + RFM22BStatusLinkStateGet(&local_link_connected); + RFM22BStatusLinkQualityGet(&local_link_quality); + + RFM22BStatusData rfm22bStatus; + RFM22BStatusInstGet(1, &rfm22bStatus); + + if (local_link_connected == RFM22BSTATUS_LINKSTATE_CONNECTED) { + // report whichever link quality is worse + *value = (rfm22bStatus.LinkQuality < local_link_quality) ? rfm22bStatus.LinkQuality : local_link_quality; + + // Rescale to values that match Taranis + if (*value < 64) { + *value = 0; + } else { + *value = (*value - 64) * 100 / 64; + } + } else { + *value = 0; + } + + return true; +} + +static bool frsky_encode_swr(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + *value = 1; + return true; +} + +static bool frsky_encode_battery(struct frsky_settings *frsky, uint32_t *value, bool test_presence_only, uint32_t arg) +{ + float voltage = 0; + FlightBatteryStateVoltageGet(&voltage); + *value = (uint8_t) (voltage * VOLT_RATIO); + + return true; +} + + +/** + * Scan for value item with the longest expired time and schedule it to send in next poll turn + * + */ +static void frsky_schedule_next_item(void) +{ + uint32_t i = 0; + int32_t max_exp_time = INT32_MIN; + int32_t most_exp_item = -1; + for (i = 0; i < NELEMENTS(frsky_value_items); i++) { + if (frsky_value_items[i].encode_value(&frsky->frsky_settings, 0, true, frsky_value_items[i].fn_arg)) { + int32_t exp_time = PIOS_DELAY_GetuSSince(frsky->item_last_triggered[i]) - + (frsky_value_items[i].period_ms * 1000); + if (exp_time > max_exp_time) { + max_exp_time = exp_time; + most_exp_item = i; + } + } + } + frsky->scheduled_item = most_exp_item; +} +/** + * Send value item previously scheduled by frsky_schedule_next_itme() + * @returns true when item value was sended + */ +static bool frsky_send_scheduled_item(void) +{ + int32_t item = frsky->scheduled_item; + if ((item >= 0) && (item < NELEMENTS(frsky_value_items))) { + frsky->item_last_triggered[item] = PIOS_DELAY_GetuS(); + uint32_t value = 0; + if (frsky_value_items[item].encode_value(&frsky->frsky_settings, &value, false, + frsky_value_items[item].fn_arg)) { + frsky_send_frame(frsky->com, (uint16_t)(frsky_value_items[item].id), value); + return true; + } + } + + return false; +} + +/** + * Start the module + * \return -1 if start failed + * \return 0 on success + */ +static int32_t uavoTaranisStart(void) +{ + if (module_enabled) { + // Start tasks + uavoTaranisTaskHandle = PIOS_Thread_Create( + uavoTaranisTask, "uavoFrSKYSensorHubBridge", + STACK_SIZE_BYTES, NULL, TASK_PRIORITY); + TaskMonitorAdd(TASKINFO_RUNNING_UAVOFRSKYSBRIDGE, + uavoTaranisTaskHandle); + return 0; + } + return -1; +} + +/** + * Initialize the module + * \return -1 if initialization failed + * \return 0 on success + */ +static int32_t uavoTaranisInitialize(void) +{ + uint32_t sport_com = PIOS_COM_FRSKY_SPORT; + + if (sport_com) { + + + frsky = PIOS_malloc(sizeof(struct frsky_sport_telemetry)); + if (frsky != NULL) { + memset(frsky, 0x00, sizeof(struct frsky_sport_telemetry)); + + // These objects are registered on the TLM so it + // can intercept them from the telemetry stream + FlightBatteryStateInitialize(); + FlightStatusInitialize(); + PositionActualInitialize(); + VelocityActualInitialize(); + + frsky->frsky_settings.use_current_sensor = false; + frsky->frsky_settings.batt_cell_count = 0; + frsky->frsky_settings.use_baro_sensor = false; + frsky->state = FRSKY_STATE_WAIT_POLL_REQUEST; + frsky->last_poll_time = PIOS_DELAY_GetuS(); + frsky->ignore_rx_chars = 0; + frsky->scheduled_item = -1; + frsky->com = sport_com; + + uint8_t i; + for (i = 0; i < NELEMENTS(frsky_value_items); i++) + frsky->item_last_triggered[i] = PIOS_DELAY_GetuS(); + PIOS_COM_ChangeBaud(frsky->com, FRSKY_SPORT_BAUDRATE); + module_enabled = true; + return 0; + } + + module_enabled = true; + + return 0; + } + + module_enabled = false; + + return -1; +} +MODULE_INITCALL(uavoTaranisInitialize, uavoTaranisStart) + +/** + * Main task. It does not return. + */ +static void uavoTaranisTask(void *parameters) +{ + while(1) { + + if (true) { + + // for some reason, only first four messages are sent. + for (uint32_t i = 0; i < sizeof(frsky_value_items) / sizeof(frsky_value_items[0]); i++) { + frsky->scheduled_item = i; + frsky_send_scheduled_item(); + PIOS_Thread_Sleep(5); + } + + } + + if (false) { + + // fancier schedlued message sending. doesn't appear to work + // currently. + PIOS_Thread_Sleep(1); + frsky_schedule_next_item(); + frsky_send_scheduled_item(); + } + + } +} + +#endif /* PIOS_INCLUDE_TARANIS_SPORT */ +/** + * @} + * @} + */ diff --git a/flight/Modules/VtolPathFollower/vtol_follower_control.c b/flight/Modules/VtolPathFollower/vtol_follower_control.c index 296b43e0f23..0345d84148c 100644 --- a/flight/Modules/VtolPathFollower/vtol_follower_control.c +++ b/flight/Modules/VtolPathFollower/vtol_follower_control.c @@ -39,17 +39,15 @@ #include "altitudeholdsettings.h" #include "altitudeholdstate.h" #include "attitudeactual.h" +#include "loitercommand.h" #include "pathdesired.h" // object that will be updated by the module #include "positionactual.h" #include "manualcontrolcommand.h" #include "flightstatus.h" -#include "gpsvelocity.h" -#include "gpsposition.h" #include "nedaccel.h" #include "pathstatus.h" #include "stabilizationdesired.h" #include "stabilizationsettings.h" -#include "systemsettings.h" #include "velocitydesired.h" #include "velocityactual.h" #include "vtolpathfollowersettings.h" @@ -62,132 +60,11 @@ struct pid vtol_pids[VTOL_PID_NUM]; // Constants used in deadband calculation static float vtol_path_m=0, vtol_path_r=0, vtol_end_m=0, vtol_end_r=0; -static int32_t vtol_follower_control_simple(const float dT, - const float *hold_pos_ned, bool landing, bool update_status); +// Time constants converted to IIR parameter +static float loiter_brakealpha=0.96f, loiter_errordecayalpha=0.88f; -/** - * Interpolate values (groundspeeds, altitudes) over flight legs - * @param[in] fraction how far we are through the leg - * @param[in] beginVal the configured value for the beginning of the leg - * @param[in] endVal the configured value for the end of the leg - * @returns the interpolated value - * - * Simple linear interpolation with clipping to ends (fraction>=0, <=1). - */ -static float vtol_interpolate(const float fraction, const float beginVal, - const float endVal) { - return beginVal + (endVal - beginVal) * bound_min_max(fraction, 0, 1); -} - -/** - * Calculate pythagorean magnitude of a vector. - * @param[in] v pointer to a float array - * @param[in] n length of the amount to take the magnitude of - * @returns Root of sum of squares of the vector - * - * Note that sometimes we only take the magnitude of the first 2 elements - * of a 3-vector to get the horizontal component. - */ -static float vtol_magnitude(const float *v, int n) -{ - float sum=0; - - for (int i=0; i limit, vels=vels / mag(vels) * limit - */ -static void vtol_limit_velocity(float *vels, float limit) -{ - float mag = vtol_magnitude(vels, 2); // only horiz component - float scale = mag / limit; - - if (scale > 1) { - vels[0] /= mag; - vels[1] /= mag; - } -} - -/** - * Apply a "cubic deadband" to the input. - * @param[in] in the value to deadband - * @param[in] w deadband width - * @param[in] b slope of deadband at in=0 - * @param[in] m cubic weighting calculated by vtol_deadband_setup - * @param[in] r integrated response at in=w, calculated by vtol_deadband_setup - * - * "Real" deadbands are evil. Control systems end up fighting the edge. - * You don't teach your integrator about emerging drift. Discontinuities - * in your control inputs cause all kinds of neat stuff. As a result this - * calculates a cubic function within the deadband which has a low slope - * within the middle, but unity slope at the edge. - */ -static float vtol_deadband(float in, float w, float b, float m, float r) -{ - // First get the nice linear bits -- outside the deadband-- out of - // the way. - if (in <= -w) { - return in+w-r; - } else if (in >= w) { - return in-w+r; - } - - - return powf(m*in, 3)+b*in; -} - -/** - * Calculate the "cubic deadband" system parameters. - * @param[in] The width of the deadband - * @param[in] Slope of deadband at in=0, sane values between 0 and 1. - * @param[out] m cubic weighting of function - * @param[out] integrated response at in=w - */ -static void vtol_deadband_setup(float w, float b, float *m, float *r) -{ - /* So basically.. we want the function to be tangent to the - ** linear sections-- have a slope of 1-- at -w and w. In the - ** middle we want a slope of b. So the cube here does all the - ** work b isn't doing. */ - *m = cbrtf((1-b)/(3*powf(w,2))); - - *r = powf(*m*w, 3)+b*w; -} +static int32_t vtol_follower_control_impl(const float dT, + const float *hold_pos_ned, float alt_rate, bool update_status); /** * Compute desired velocity to follow the desired path from the current location. @@ -229,7 +106,7 @@ int32_t vtol_follower_control_path(const float dT, const PathDesiredData *pathDe pathStatus.Waypoint = pathDesired->Waypoint; // Figure out how low (high) we should be and the error - const float altitudeSetpoint = vtol_interpolate(progress->fractional_progress, + const float altitudeSetpoint = interpolate_value(progress->fractional_progress, pathDesired->Start[2], pathDesired->End[2]); const float downError = altitudeSetpoint - positionActual.Down; @@ -255,14 +132,15 @@ int32_t vtol_follower_control_path(const float dT, const PathDesiredData *pathDe } // Wait here for new path segment - return vtol_follower_control_simple(dT, pathDesired->End, false, false); + return vtol_follower_control_impl(dT, pathDesired->End, + 0, false); } // Interpolate desired velocity and altitude along the path - float groundspeed = vtol_interpolate(progress->fractional_progress, + float groundspeed = interpolate_value(progress->fractional_progress, pathDesired->StartingVelocity, pathDesired->EndingVelocity); - float error_speed = vtol_deadband(progress->error, + float error_speed = cubic_deadband(progress->error, guidanceSettings.PathDeadbandWidth, guidanceSettings.PathDeadbandCenterGain, vtol_path_m, vtol_path_r) * @@ -277,7 +155,7 @@ int32_t vtol_follower_control_path(const float dT, const PathDesiredData *pathDe progress->correction_direction[1] * error_speed; /* Limit the total velocity based on the configured value. */ - vtol_limit_velocity(commands_ned, guidanceSettings.HorizontalVelMax); + vector2_clip(commands_ned, guidanceSettings.HorizontalVelMax); commands_ned[2] = pid_apply_antiwindup(&vtol_pids[DOWN_POSITION], downError, -guidanceSettings.VerticalVelMax, guidanceSettings.VerticalVelMax, dT); @@ -299,11 +177,13 @@ int32_t vtol_follower_control_path(const float dT, const PathDesiredData *pathDe * Controller to maintain/seek a position and optionally descend. * @param[in] dT time since last eval * @param[in] hold_pos_ned a position to hold - * @param[in] landing whether to descend + * @param[in] alt_rate if not 0, a requested descent/climb rate that overrides + * hold_pos_ned * @param[in] update_status does this update path_status, or does somoene else? */ -static int32_t vtol_follower_control_simple(const float dT, - const float *hold_pos_ned, bool landing, bool update_status) { +static int32_t vtol_follower_control_impl(const float dT, + const float *hold_pos_ned, float alt_rate, bool update_status) +{ PositionActualData positionActual; VelocityDesiredData velocityDesired; @@ -325,9 +205,9 @@ static int32_t vtol_follower_control_simple(const float dT, /* Calculate the difference between where we want to be and the * above position */ - vtol_calculate_difference(cur_pos_ned, hold_pos_ned, errors_ned, false); + vector3_distances(cur_pos_ned, hold_pos_ned, errors_ned, false); - float horiz_error_mag = vtol_magnitude(errors_ned, 2); + float horiz_error_mag = vectorn_magnitude(errors_ned, 2); float scale_horiz_error_mag = 0; /* Apply a cubic deadband; if we are already really close don't work @@ -340,7 +220,7 @@ static int32_t vtol_follower_control_simple(const float dT, * attenuates that. */ if (horiz_error_mag > 0.00001f) { - scale_horiz_error_mag = vtol_deadband(horiz_error_mag, + scale_horiz_error_mag = cubic_deadband(horiz_error_mag, guidanceSettings.EndpointDeadbandWidth, guidanceSettings.EndpointDeadbandCenterGain, vtol_end_m, vtol_end_r) / horiz_error_mag; @@ -359,17 +239,17 @@ static int32_t vtol_follower_control_simple(const float dT, commands_ned[1] = pid_apply_antiwindup(&vtol_pids[EAST_POSITION], damped_ne[1], -guidanceSettings.HorizontalVelMax, guidanceSettings.HorizontalVelMax, dT); - if (!landing) { + if (fabsf(alt_rate) < 0.001f) { // Compute desired down comand velocity from the position difference commands_ned[2] = pid_apply_antiwindup(&vtol_pids[DOWN_POSITION], errors_ned[2], -guidanceSettings.VerticalVelMax, guidanceSettings.VerticalVelMax, dT); } else { - // Just use the landing rate. - commands_ned[2] = guidanceSettings.LandingRate; + // Just use the commanded rate + commands_ned[2] = alt_rate; } // Limit the maximum horizontal velocity any direction (not north and east separately) - vtol_limit_velocity(commands_ned, guidanceSettings.HorizontalVelMax); + vector2_clip(commands_ned, guidanceSettings.HorizontalVelMax); velocityDesired.North = commands_ned[0]; velocityDesired.East = commands_ned[1]; @@ -380,16 +260,18 @@ static int32_t vtol_follower_control_simple(const float dT, if (update_status) { uint8_t path_status = PATHSTATUS_STATUS_INPROGRESS; - if (!landing) { + if (fabsf(alt_rate) < 0.001f) { const bool criterion_altitude = (errors_ned[2]> -guidanceSettings.WaypointAltitudeTol) || (!guidanceSettings.ThrottleControl); // Indicate whether we are in radius of this endpoint // And at/above the altitude requested - if ((vtol_magnitude(errors_ned, 2) < guidanceSettings.EndpointRadius) && criterion_altitude) { + if ((vectorn_magnitude(errors_ned, 2) < guidanceSettings.EndpointRadius) && criterion_altitude) { path_status = PATHSTATUS_STATUS_COMPLETED; } - } // landing never terminates. + } + // Otherwise, we're not done-- we're in autoland or someone + // upstream is explicitly trimming our altitude PathStatusStatusSet(&path_status); } @@ -410,15 +292,14 @@ static int32_t vtol_follower_control_simple(const float dT, */ int32_t vtol_follower_control_endpoint(const float dT, const float *hold_pos_ned) { - return vtol_follower_control_simple(dT, hold_pos_ned, false, true); + return vtol_follower_control_impl(dT, hold_pos_ned, 0, true); } /** * Control algorithm to land at a fixed location * @param[in] dT the time since last evaluation - * @param[in] ned The position to attempt to land over (down ignored) - * @param[in] land_velocity The speed to descend - * @param[out] landed True once throttle low and velocity at zero + * @param[in] hold_pos_ned The position to attempt to land over (down ignored) + * @param[out] landed True once throttle low and velocity at zero (UNIMPL) * * Takes in @ref PositionActual and compares it to the hold position * and computes @ref VelocityDesired @@ -426,7 +307,22 @@ int32_t vtol_follower_control_endpoint(const float dT, const float *hold_pos_ned int32_t vtol_follower_control_land(const float dT, const float *hold_pos_ned, bool *landed) { - return vtol_follower_control_simple(dT, hold_pos_ned, false, true); + return vtol_follower_control_impl(dT, hold_pos_ned, + guidanceSettings.LandingRate, true); +} + +/** + * Control algorithm for loitering-- allow control of altitude rate. + * @param[in] dT time since last evaluation + * @param[in] hold_pos_ned The position to control for. + * @param[in] alt_adj If 0, holds at altitude in hold_pos_ned. Otherwise, + * a rate in meters per second to descend. + */ +int32_t vtol_follower_control_altrate(const float dT, + const float *hold_pos_ned, float alt_adj) +{ + return vtol_follower_control_impl(dT, hold_pos_ned, + alt_adj, true); } /** @@ -496,22 +392,69 @@ static int32_t vtol_follower_control_accel(float dT) return 0; } + +static float vtol_follower_control_altitude(float downCommand) { + AltitudeHoldStateData altitudeHoldState; + altitudeHoldState.VelocityDesired = downCommand; + altitudeHoldState.Integral = vtol_pids[DOWN_VELOCITY].iAccumulator / 1000.0f; + altitudeHoldState.AngleGain = 1.0f; + + if (altitudeHoldSettings.AttitudeComp > 0) { + // Throttle desired is at this point the mount desired in the up direction, we can + // account for the attitude if desired + AttitudeActualData attitudeActual; + AttitudeActualGet(&attitudeActual); + + // Project a unit vector pointing up into the body frame and + // get the z component + float fraction = attitudeActual.q1 * attitudeActual.q1 - + attitudeActual.q2 * attitudeActual.q2 - + attitudeActual.q3 * attitudeActual.q3 + + attitudeActual.q4 * attitudeActual.q4; + + // Add ability to scale up the amount of compensation to achieve + // level forward flight + fraction = powf(fraction, (float) altitudeHoldSettings.AttitudeComp / 100.0f); + + // Dividing by the fraction remaining in the vertical projection will + // attempt to compensate for tilt. This acts like the thrust is linear + // with the output which isn't really true. If the fraction is starting + // to go negative we are inverted and should shut off throttle + downCommand = (fraction > 0.1f) ? (downCommand / fraction) : 0.0f; + + altitudeHoldState.AngleGain = 1.0f / fraction; + } + + altitudeHoldState.Throttle = downCommand; + AltitudeHoldStateSet(&altitudeHoldState); + + return downCommand; +} + /** * Compute desired attitude from the desired velocity * @param[in] dT the time since last evaluation + * @param[in] att_adj an adjustment to the attitude for loiter mode * * Takes in @ref NedActual which has the acceleration in the * NED frame as the feedback term and then compares the * @ref VelocityActual against the @ref VelocityDesired */ -int32_t vtol_follower_control_attitude(float dT) +int32_t vtol_follower_control_attitude(float dT, const float *att_adj) { vtol_follower_control_accel(dT); + float default_adj[2] = {0,0}; + + if (!att_adj) { + att_adj = default_adj; + } + AccelDesiredData accelDesired; AccelDesiredGet(&accelDesired); - StabilizationDesiredData stabDesired; + StabilizationSettingsData stabSet; + StabilizationSettingsGet(&stabSet); float northCommand = accelDesired.North; float eastCommand = accelDesired.East; @@ -522,82 +465,46 @@ int32_t vtol_follower_control_attitude(float dT) float forward_accel_desired = -northCommand * cosf(yaw * DEG2RAD) + -eastCommand * sinf(yaw * DEG2RAD); float right_accel_desired = -northCommand * sinf(yaw * DEG2RAD) + eastCommand * cosf(yaw * DEG2RAD); + StabilizationDesiredData stabDesired; + // Set the angle that would achieve the desired acceleration given the thrust is enough for a hover - stabDesired.Pitch = bound_min_max(RAD2DEG * atanf(forward_accel_desired / GRAVITY), - -guidanceSettings.MaxRollPitch, guidanceSettings.MaxRollPitch); - stabDesired.Roll = bound_min_max(RAD2DEG * atanf(right_accel_desired / GRAVITY), - -guidanceSettings.MaxRollPitch, guidanceSettings.MaxRollPitch); + stabDesired.Pitch = bound_sym(RAD2DEG * atanf(forward_accel_desired / GRAVITY), guidanceSettings.MaxRollPitch) + att_adj[1]; + stabDesired.Roll = bound_sym(RAD2DEG * atanf(right_accel_desired / GRAVITY), guidanceSettings.MaxRollPitch) + att_adj[0]; + + // Re-bound based on maximum attitude settings + stabDesired.Pitch = bound_sym(stabDesired.Pitch, stabSet.PitchMax); + stabDesired.Roll = bound_sym(stabDesired.Roll, stabSet.RollMax); stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_ROLL] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_PITCH] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; - // Calculate the throttle setting or use pass through from transmitter if (guidanceSettings.ThrottleControl == VTOLPATHFOLLOWERSETTINGS_THROTTLECONTROL_FALSE) { ManualControlCommandThrottleGet(&stabDesired.Throttle); } else { - float downCommand = accelDesired.Down; - - AltitudeHoldStateData altitudeHoldState; - altitudeHoldState.VelocityDesired = downCommand; - altitudeHoldState.Integral = vtol_pids[DOWN_VELOCITY].iAccumulator / 1000.0f; - altitudeHoldState.AngleGain = 1.0f; - - if (altitudeHoldSettings.AttitudeComp > 0) { - // Throttle desired is at this point the mount desired in the up direction, we can - // account for the attitude if desired - AttitudeActualData attitudeActual; - AttitudeActualGet(&attitudeActual); - - // Project a unit vector pointing up into the body frame and - // get the z component - float fraction = attitudeActual.q1 * attitudeActual.q1 - - attitudeActual.q2 * attitudeActual.q2 - - attitudeActual.q3 * attitudeActual.q3 + - attitudeActual.q4 * attitudeActual.q4; - - // Add ability to scale up the amount of compensation to achieve - // level forward flight - fraction = powf(fraction, (float) altitudeHoldSettings.AttitudeComp / 100.0f); - - // Dividing by the fraction remaining in the vertical projection will - // attempt to compensate for tilt. This acts like the thrust is linear - // with the output which isn't really true. If the fraction is starting - // to go negative we are inverted and should shut off throttle - downCommand = (fraction > 0.1f) ? (downCommand / fraction) : 0.0f; - - altitudeHoldState.AngleGain = 1.0f / fraction; - } - - altitudeHoldState.Throttle = downCommand; - AltitudeHoldStateSet(&altitudeHoldState); + float downCommand = vtol_follower_control_altitude(accelDesired.Down); stabDesired.Throttle = bound_min_max(downCommand, 0, 1); } // Various ways to control the yaw that are essentially manual passthrough. However, because we do not have a fine // grained mechanism of manual setting the yaw as it normally would we need to duplicate that code here - float manual_rate[STABILIZATIONSETTINGS_MANUALRATE_NUMELEM]; switch(guidanceSettings.YawMode) { case VTOLPATHFOLLOWERSETTINGS_YAWMODE_RATE: /* This is awkward. This allows the transmitter to control the yaw while flying navigation */ ManualControlCommandYawGet(&yaw); - StabilizationSettingsManualRateGet(manual_rate); - stabDesired.Yaw = manual_rate[STABILIZATIONSETTINGS_MANUALRATE_YAW] * yaw; + stabDesired.Yaw = stabSet.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] * yaw; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_RATE; break; case VTOLPATHFOLLOWERSETTINGS_YAWMODE_AXISLOCK: ManualControlCommandYawGet(&yaw); - StabilizationSettingsManualRateGet(manual_rate); - stabDesired.Yaw = manual_rate[STABILIZATIONSETTINGS_MANUALRATE_YAW] * yaw; + stabDesired.Yaw = stabSet.ManualRate[STABILIZATIONSETTINGS_MANUALRATE_YAW] * yaw; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_AXISLOCK; break; case VTOLPATHFOLLOWERSETTINGS_YAWMODE_ATTITUDE: { - uint8_t yaw_max; - StabilizationSettingsYawMaxGet(&yaw_max); ManualControlCommandYawGet(&yaw); - stabDesired.Yaw = yaw_max * yaw; + stabDesired.Yaw = stabSet.YawMax * yaw; stabDesired.StabilizationMode[STABILIZATIONDESIRED_STABILIZATIONMODE_YAW] = STABILIZATIONDESIRED_STABILIZATIONMODE_ATTITUDE; } break; @@ -627,6 +534,175 @@ int32_t vtol_follower_control_attitude(float dT) return 0; } +static float loiter_deadband(float input, float threshold, float expoPercent) { + if (input > threshold) { + input -= threshold; + } else if (input < -threshold) { + input += threshold; + } else { + input = 0; + } + + input /= (1 - threshold); // Normalize to -1 to 1 range. + + /* Confine to desired range */ + if (input > 1.0f) { + input = 1.0f; + } else if (input < -1.0f) { + input = -1.0f; + } + + return expo3(input, expoPercent); +} + +/** + * Receives loiter commands and makes appropriate adjustments. The updated + * position and calculated attitude are used in later stages of the control + * process. + * @param[in] dT the time since last evaluation + * @param[in,out] hold_pos the hold position + * @param[out] att_adj an adjustment to be made to attitude for responsiveness. + * @param[out] alt_adj a requested descent (negative for climb) rate + */ + +bool vtol_follower_control_loiter(float dT, float *hold_pos, float *att_adj, + float *alt_adj) { + LoiterCommandData cmd; + LoiterCommandGet(&cmd); + + // XXX TODO reproject when we're not issuing body-centric commands + float commands_rp[2] = { + cmd.Roll, + cmd.Pitch + }; + + const float CMD_THRESHOLD = 0.2f; + + float command_mag = vectorn_magnitude(commands_rp, 2); + float deadband_mag = loiter_deadband(command_mag, CMD_THRESHOLD, 40); + + float down_cmd = 0; + + if (guidanceSettings.ThrottleControl && + guidanceSettings.LoiterAllowAltControl) { + // Inverted because we want units in "Down" frame + // Doubled to recenter to 1 to -1 scale from 0-1. + // loiter_deadband clips appropriately. + down_cmd = loiter_deadband(1 - (cmd.Throttle * 2), + altitudeHoldSettings.Deadband / 100.0f, + altitudeHoldSettings.Expo); + } + + // Peak detect and decay of the past command magnitude + static float historic_mag = 0.0f; + + // Initialize altitude command + *alt_adj = 0; + + // First reduce by decay constant + historic_mag *= loiter_brakealpha; + + // If our current magnitude is greater than the result, increase it. + if (deadband_mag > historic_mag) { + historic_mag = deadband_mag; + } + + // And if we haven't had any significant command lately, bug out and + // do nothing. + if ((historic_mag < 0.001f) && (fabsf(down_cmd) < 0.001f)) { + att_adj[0] = 0; att_adj[1] = 0; + return false; + } + + // Normalize our command magnitude. Command vectors from this + // point are normalized. + if (command_mag >= 0.001f) { + commands_rp[0] /= command_mag; + commands_rp[1] /= command_mag; + } else { + // Just pick a direction + commands_rp[0] = 0.0f; + commands_rp[1] = -1.0f; + } + + // Find our current position error + PositionActualData positionActual; + PositionActualGet(&positionActual); + + float cur_pos_ned[3] = { positionActual.North, + positionActual.East, positionActual.Down }; + + float total_poserr_ned[3]; + vector3_distances(cur_pos_ned, hold_pos, total_poserr_ned, false); + + if (deadband_mag >= 0.001f) { + float yaw; + AttitudeActualYawGet(&yaw); + + float commands_ne[2]; + // 90 degrees here compensates for the above being in roll-pitch + // order vs. north-east (and where yaw is defined). + vector2_rotate(commands_rp, commands_ne, 90 + yaw); + + VelocityActualData velocityActual; + VelocityActualGet(&velocityActual); + + // Come up with a target velocity for us to fly the command + // at, considering our current momentum in that direction. + float target_vel = guidanceSettings.LoiterInitialMaxVel * + deadband_mag; + + // Plus whatever current velocity we're making good in + // that direction.. + // find the portion of our current velocity vector parallel to + // cmd. + float parallel_sign = + velocityActual.North * commands_ne[0] + + velocityActual.East * commands_ne[1]; + + if (parallel_sign > 0) { + float parallel_mag = sqrtf( + powf(velocityActual.North * commands_ne[0], 2) + + powf(velocityActual.East * commands_ne[1], 2)); + + target_vel += deadband_mag * parallel_mag; + } + + // Feed the target velocity forward for our new desired position + hold_pos[0] = cur_pos_ned[0] + + commands_ne[0] * target_vel * + guidanceSettings.LoiterLookaheadTimeConstant; + hold_pos[1] = cur_pos_ned[1] + + commands_ne[1] * target_vel * + guidanceSettings.LoiterLookaheadTimeConstant; + } + + // Now put a portion of the error back in. At full stick + // deflection, decay error at specified time constant + float scaled_error_alpha = 1 - historic_mag * (1 - loiter_errordecayalpha); + hold_pos[0] -= scaled_error_alpha * total_poserr_ned[0]; + hold_pos[1] -= scaled_error_alpha * total_poserr_ned[1]; + + // Compute attitude feedforward + att_adj[0] = deadband_mag * commands_rp[0] * + guidanceSettings.LoiterAttitudeFeedthrough; + att_adj[1] = deadband_mag * commands_rp[1] * + guidanceSettings.LoiterAttitudeFeedthrough; + + // If we are being commanded to climb or descend... + if (fabsf(down_cmd) >= 0.001f) { + // Forgive all altitude error so when position controller comes + // back we do something sane + + hold_pos[2] = cur_pos_ned[2]; + + // and output an adjustment for velocity control use */ + *alt_adj = down_cmd * guidanceSettings.VerticalVelMax; + } + + return true; +} + void vtol_follower_control_settings_updated(UAVObjEvent * ev) { VtolPathFollowerSettingsGet(&guidanceSettings); @@ -663,14 +739,17 @@ void vtol_follower_control_settings_updated(UAVObjEvent * ev) 0, 1); // Note the ILimit here is 1 because we use this offset to set the throttle offset // Calculate the constants used in the deadband calculation - vtol_deadband_setup(guidanceSettings.EndpointDeadbandWidth, + cubic_deadband_setup(guidanceSettings.EndpointDeadbandWidth, guidanceSettings.EndpointDeadbandCenterGain, &vtol_end_m, &vtol_end_r); - vtol_deadband_setup(guidanceSettings.PathDeadbandWidth, + cubic_deadband_setup(guidanceSettings.PathDeadbandWidth, guidanceSettings.PathDeadbandCenterGain, &vtol_path_m, &vtol_path_r); + // calculate the loiter time constants. + loiter_brakealpha = expf(-(guidanceSettings.UpdatePeriod / 1000.0f) / guidanceSettings.LoiterBrakingTimeConstant); + loiter_errordecayalpha = expf(-(guidanceSettings.UpdatePeriod / 1000.0f) / guidanceSettings.LoiterErrorDecayConstant); } /** diff --git a/flight/Modules/VtolPathFollower/vtol_follower_fsm.c b/flight/Modules/VtolPathFollower/vtol_follower_fsm.c index 371a1646afb..fd2d3414b9a 100644 --- a/flight/Modules/VtolPathFollower/vtol_follower_fsm.c +++ b/flight/Modules/VtolPathFollower/vtol_follower_fsm.c @@ -51,16 +51,13 @@ #include "vtol_follower_priv.h" -#include "attitudeactual.h" -#include "loitercommand.h" #include "pathdesired.h" #include "positionactual.h" -#include "stabilizationdesired.h" #include "vtolpathfollowerstatus.h" // Various navigation constants const static float RTH_MIN_ALTITUDE = 15.f; //!< Hover at least 15 m above home */ -const static float RTH_VELOCITY = 2.5f; //!< Return home at 2.5 m/s */ +const static float RTH_VELOCITY = 3.0f; //!< Return home at 3.0 m/s */ const static float RTH_ALT_ERROR = 1.0f; //!< The altitude to come within for RTH */ const static float DT = 0.05f; // TODO: make the self monitored @@ -102,19 +99,6 @@ struct vtol_fsm_transition { enum vtol_fsm_state next_state[FSM_EVENT_NUM_EVENTS]; }; -/** - * Navigation modes that the states can enable. There is no one to one correspondence - * between states and these navigation modes as some FSM might have multiple hold states - * for example. When entering a hold state the FSM will configure the hold parameters and - * then set the navgiation mode - */ -enum vtol_nav_mode { - VTOL_NAV_HOLD, /*!< Hold at the configured location @ref do_land*/ - VTOL_NAV_PATH, /*!< Fly the configured path @ref do_path*/ - VTOL_NAV_LAND, /*!< Land at the desired location @ref do_land */ - VTOL_NAV_IDLE /*!< Nothing, no mode configured */ -}; - #define MILLI 1000 // State transition methods, typically enabling for certain actions @@ -127,7 +111,6 @@ static void go_enable_fly_home(void); static void go_enable_land_home(void); // Methods that actually achieve the desired nav mode -static int32_t do_default(void); static int32_t do_hold(void); static int32_t do_path(void); static int32_t do_requested_path(void); @@ -142,8 +125,7 @@ static void hold_position(float north, float east, float down); /** * The state machine for landing at home does the following: - * 1. enable holding at the current location - * 2 TODO: if it leaves the hold region enable a nav mode + * enable holding at the current location */ const static struct vtol_fsm_transition fsm_hold_position[FSM_STATE_NUM_STATES] = { [FSM_STATE_INIT] = { @@ -163,9 +145,7 @@ const static struct vtol_fsm_transition fsm_hold_position[FSM_STATE_NUM_STATES] /** * The state machine for following the Path Planner: - * 1. enable following path segment - * 2 TODO: the path planner should be able to utilize the goals of the - * follower so needs to be handled in the main module and not here. + * enable following path segment */ const static struct vtol_fsm_transition fsm_follow_path[FSM_STATE_NUM_STATES] = { [FSM_STATE_INIT] = { @@ -182,13 +162,14 @@ const static struct vtol_fsm_transition fsm_follow_path[FSM_STATE_NUM_STATES] = }, }, }; + /** * The state machine for landing at home does the following: * 1. holds where currently at for 10 seconds * 2. ascend to minimum altitude * 3. flies to home at 2 m/s at either current altitude or 15 m above home * 4. holds above home for 10 seconds - * 5. descends to ground + * 5. descends to ground (This step currently does not complete) * 6. disarms the system */ const static struct vtol_fsm_transition fsm_land_home[FSM_STATE_NUM_STATES] = { @@ -199,6 +180,7 @@ const static struct vtol_fsm_transition fsm_land_home[FSM_STATE_NUM_STATES] = { }, [FSM_STATE_PRE_RTH_HOLD] = { .entry_fn = go_enable_pause_10s_here, + .static_fn = do_hold, .timeout = 10 * MILLI, .next_state = { [FSM_EVENT_TIMEOUT] = FSM_STATE_PRE_RTH_RISE, @@ -218,12 +200,14 @@ const static struct vtol_fsm_transition fsm_land_home[FSM_STATE_NUM_STATES] = { }, [FSM_STATE_FLYING_PATH] = { .entry_fn = go_enable_fly_home, + .static_fn = do_path, .next_state = { [FSM_EVENT_HIT_TARGET] = FSM_STATE_POST_RTH_HOLD, }, }, [FSM_STATE_POST_RTH_HOLD] = { .entry_fn = go_enable_pause_home_10s, + .static_fn = do_hold, .timeout = 10 * MILLI, .next_state = { [FSM_EVENT_TIMEOUT] = FSM_STATE_LANDING, @@ -233,6 +217,7 @@ const static struct vtol_fsm_transition fsm_land_home[FSM_STATE_NUM_STATES] = { }, [FSM_STATE_LANDING] = { .entry_fn = go_enable_land_home, + .static_fn = do_land, .next_state = { [FSM_EVENT_HIT_TARGET] = FSM_STATE_DISARM, }, @@ -398,10 +383,6 @@ static int32_t vtol_fsm_static() // If the current state has a static function, call it if (current_goal[curr_state].static_fn) { current_goal[curr_state].static_fn(); - } else { - int32_t ret_val; - if ((ret_val = do_default()) < 0) - return ret_val; } if (vtol_fsm_timer_expired()) { @@ -420,31 +401,6 @@ static int32_t vtol_fsm_static() * @{ */ -//! The currently configured navigation mode. Used to sanity check configuration. -static enum vtol_nav_mode vtol_nav_mode; - -/** - * General methods which based on the selected @ref vtol_nav_mode calls the appropriate - * specific method - */ -static int32_t do_default() -{ - switch(vtol_nav_mode) { - case VTOL_NAV_HOLD: - return do_hold(); - case VTOL_NAV_PATH: - return do_path(); - case VTOL_NAV_LAND: - return do_land(); - break; - default: - // TODO: error? - break; - } - - return -1; -} - //! The setpoint for position hold relative to home in m static float vtol_hold_position_ned[3]; @@ -459,7 +415,7 @@ static float vtol_hold_position_ned[3]; static int32_t do_hold() { if (vtol_follower_control_endpoint(DT, vtol_hold_position_ned) == 0) { - if (vtol_follower_control_attitude(DT) == 0) { + if (vtol_follower_control_attitude(DT, NULL) == 0) { return 0; } } @@ -468,7 +424,9 @@ static int32_t do_hold() } //! The configured path desired. Uses the @ref PathDesired structure -static PathDesiredData vtol_fsm_path_desired; +static PathDesiredData vtol_fsm_path_desired = { + .Waypoint = 8000 // Unlikely to clash with pathplanner +}; /** * Update control values to fly along a path. @@ -482,7 +440,7 @@ static int32_t do_path() { struct path_status progress; if (vtol_follower_control_path(DT, &vtol_fsm_path_desired, &progress) == 0) { - if (vtol_follower_control_attitude(DT) == 0) { + if (vtol_follower_control_attitude(DT, NULL) == 0) { if (progress.fractional_progress >= 1.0f) { vtol_fsm_inject_event(FSM_EVENT_HIT_TARGET); @@ -533,7 +491,7 @@ static int32_t do_land() { bool landed; if (vtol_follower_control_land(DT, vtol_hold_position_ned, &landed) == 0) { - if (vtol_follower_control_attitude(DT) == 0) { + if (vtol_follower_control_attitude(DT, NULL) == 0) { return 0; } } @@ -546,46 +504,31 @@ static int32_t do_land() */ static int32_t do_loiter() { - const float LOITER_LEASH = 4; - - LoiterCommandData loiterCommand; - LoiterCommandGet(&loiterCommand); + float att_adj[2] = { 0, 0 }; + float hold_pos[3] = { + vtol_hold_position_ned[0], + vtol_hold_position_ned[1], + vtol_hold_position_ned[2] + }; - float yaw; - AttitudeActualYawGet(&yaw); - yaw *= DEG2RAD; + float alt_adj = 0; - float north_offset = 0; - float east_offset = 0; - float down_offset = 0; + if (vtol_follower_control_loiter(DT, hold_pos, att_adj, &alt_adj)) { + // If hold position changed, use it! + // We follow this conditional just to avoid unnecessarily + // spamming updates to the PositionDesired object. - if (loiterCommand.Frame == LOITERCOMMAND_FRAME_BODY) { - north_offset = (loiterCommand.Forward * cosf(yaw) - loiterCommand.Right * sinf(yaw)) * DT; - east_offset = (loiterCommand.Forward * sinf(yaw) + loiterCommand.Right * cosf(yaw)) * DT; - } else { - north_offset = loiterCommand.Forward * DT; - east_offset = loiterCommand.Right * DT; + hold_position(hold_pos[0], hold_pos[1], hold_pos[2]); } - float new_north = vtol_hold_position_ned[0] + north_offset; - float new_east = vtol_hold_position_ned[1] + east_offset; - PositionActualData positionActual; - PositionActualGet(&positionActual); - - const float cur_offset = sqrtf(powf(vtol_hold_position_ned[0] - positionActual.North, 2) + - powf(vtol_hold_position_ned[1] - positionActual.East, 2)); - const float new_offset = sqrtf(powf(new_north - positionActual.North, 2) + powf(new_east - positionActual.East, 2)); - if (new_offset < LOITER_LEASH || (new_offset < cur_offset)) { - // prevent moving set point too far from the current - // location. Ideally when there is a command input it would - // be added to the position controller instead of soley move - // the setpoint. - hold_position(vtol_hold_position_ned[0] + north_offset, - vtol_hold_position_ned[1] + east_offset, - vtol_hold_position_ned[2] + down_offset); + if (vtol_follower_control_altrate(DT, vtol_hold_position_ned, + alt_adj) == 0) { + if (vtol_follower_control_attitude(DT, att_adj) == 0) { + return 0; + } } - return do_hold(); + return -1; } /** @@ -626,8 +569,6 @@ static int32_t do_ph_climb() */ static void hold_position(float north, float east, float down) { - vtol_nav_mode = VTOL_NAV_HOLD; - vtol_hold_position_ned[0] = north; vtol_hold_position_ned[1] = east; vtol_hold_position_ned[2] = down; @@ -643,6 +584,9 @@ static void hold_position(float north, float east, float down) vtol_fsm_path_desired.EndingVelocity = 0; vtol_fsm_path_desired.Mode = PATHDESIRED_MODE_ENDPOINT; vtol_fsm_path_desired.ModeParameters = 0; + + vtol_fsm_path_desired.Waypoint++; + PathDesiredSet(&vtol_fsm_path_desired); } @@ -659,7 +603,6 @@ static void go_enable_hold_here() static void go_enable_fly_path() { - vtol_nav_mode = VTOL_NAV_HOLD; } /** @@ -678,7 +621,6 @@ static void go_enable_pause_10s_here() hold_position(positionActual.North, positionActual.East, positionActual.Down); } - /** * Stay at current location but rise to a minimal location. */ @@ -716,8 +658,6 @@ static void go_enable_pause_home_10s() */ static void go_enable_fly_home() { - vtol_nav_mode = VTOL_NAV_PATH; - PositionActualData positionActual; PositionActualGet(&positionActual); @@ -730,8 +670,11 @@ static void go_enable_fly_home() vtol_fsm_path_desired.End[0] = 0; vtol_fsm_path_desired.End[1] = 0; vtol_fsm_path_desired.End[2] = positionActual.Down; - if (vtol_fsm_path_desired.End[2] > -RTH_MIN_ALTITUDE) + + if (positionActual.Down > -RTH_MIN_ALTITUDE) { + vtol_fsm_path_desired.Start[2] = -RTH_MIN_ALTITUDE; vtol_fsm_path_desired.End[2] = -RTH_MIN_ALTITUDE; + } vtol_fsm_path_desired.StartingVelocity = RTH_VELOCITY; vtol_fsm_path_desired.EndingVelocity = RTH_VELOCITY; @@ -739,6 +682,13 @@ static void go_enable_fly_home() vtol_fsm_path_desired.Mode = PATHDESIRED_MODE_VECTOR; vtol_fsm_path_desired.ModeParameters = 0; + /* It's necessary that this increment so that we don't end up + * latching completion status. Wraparound, etc, is OK. + * This is for compatibility with the waypoint handshaking in the + * path planner. + */ + vtol_fsm_path_desired.Waypoint++; + PathDesiredSet(&vtol_fsm_path_desired); } @@ -747,11 +697,9 @@ static void go_enable_fly_home() */ static void go_enable_land_home() { - vtol_nav_mode = VTOL_NAV_LAND; - vtol_hold_position_ned[0] = 0; vtol_hold_position_ned[1] = 0; - vtol_hold_position_ned[2] = 0; // Has no affect + vtol_hold_position_ned[2] = 0; // Has no effect } //! @} diff --git a/flight/Modules/VtolPathFollower/vtol_follower_priv.h b/flight/Modules/VtolPathFollower/vtol_follower_priv.h index 5aafdc6ddc5..9eca7c2d43f 100644 --- a/flight/Modules/VtolPathFollower/vtol_follower_priv.h +++ b/flight/Modules/VtolPathFollower/vtol_follower_priv.h @@ -59,8 +59,12 @@ enum vtol_pid { // Control code public API methods int32_t vtol_follower_control_path(const float dT, const PathDesiredData *pathDesired, struct path_status *progress); int32_t vtol_follower_control_endpoint(const float dT, const float *hold_pos_ned); -int32_t vtol_follower_control_attitude(const float dT); +int32_t vtol_follower_control_altrate(const float dT, const float *hold_pos_ned, + float alt_adj); +int32_t vtol_follower_control_attitude(const float dT, const float *att_adj); int32_t vtol_follower_control_land(const float dT, const float *hold_pos_ned, bool *landed); +bool vtol_follower_control_loiter(float dT, float *hold_pos, float *att_adj, + float *alt_adj); void vtol_follower_control_settings_updated(UAVObjEvent * ev); // Follower FSM public API methods @@ -78,4 +82,4 @@ int32_t vtol_follower_fsm_activate_goal(enum vtol_goals new_goal); */ int32_t vtol_follower_fsm_update(); -#endif \ No newline at end of file +#endif diff --git a/flight/PiOS.posix/posix/library_chibios.mk b/flight/PiOS.posix/posix/library_chibios.mk index b77af150e64..912c63aeb41 100644 --- a/flight/PiOS.posix/posix/library_chibios.mk +++ b/flight/PiOS.posix/posix/library_chibios.mk @@ -1,7 +1,9 @@ # -# Rules to (help) build the F4xx device support. +# Rules to (help) build the Posix-targeted code. # +include $(MAKE_INC_DIR)/system-id.mk + # # Directory containing this makefile # @@ -21,4 +23,20 @@ PIOS_DEVLIB := $(dir $(lastword $(MAKEFILE_LIST))) # ARCHFLAGS += -DARCH_POSIX ARCHFLAGS += -D_GNU_SOURCE -ARCHFLAGS += -m32 + +# The posix code is not threaded but it is possibly re-entrant into the +# system libraries because of task switching. As a result, request the +# re-entrant libraries and -D_REENTRANT +ifdef MACOSX +# If we are building with clang, it doesn't like the pthread argument being +# passed at link time. Annoying. +CONLYFLAGS += -pthread +else +ARCHFLAGS += -pthread +endif + +# Build 32 bit code. +ifdef AMD64 +ARCHFLAGS += -m32 +endif + diff --git a/flight/PiOS.posix/posix/pios_iap.c b/flight/PiOS.posix/posix/pios_iap.c index 57ceeadc022..e55ba52d2cb 100644 --- a/flight/PiOS.posix/posix/pios_iap.c +++ b/flight/PiOS.posix/posix/pios_iap.c @@ -33,6 +33,7 @@ * Header files ****************************************************************************************/ #include +#include /*! * \brief PIOS_IAP_Init - performs required initializations for iap module. @@ -74,14 +75,17 @@ uint32_t PIOS_Boot_CheckRequest( void ) */ void PIOS_IAP_SetRequest1(void) { + printf("IAP SetRequest1\n"); } void PIOS_IAP_SetRequest2(void) { + printf("IAP SetRequest2\n"); } void PIOS_IAP_SetRequest3(void) { + printf("IAP SetRequest3\n"); } void PIOS_IAP_ClearRequest(void) diff --git a/flight/PiOS/Common/Libraries/ChibiOS/os/ports/GCC/SIMIA32/chcore.h b/flight/PiOS/Common/Libraries/ChibiOS/os/ports/GCC/SIMIA32/chcore.h index c1e8c2ba016..594c395d990 100644 --- a/flight/PiOS/Common/Libraries/ChibiOS/os/ports/GCC/SIMIA32/chcore.h +++ b/flight/PiOS/Common/Libraries/ChibiOS/os/ports/GCC/SIMIA32/chcore.h @@ -77,7 +77,7 @@ * @p extctx is known to be zero. */ #if !defined(PORT_INT_REQUIRED_STACK) || defined(__DOXYGEN__) -#define PORT_INT_REQUIRED_STACK 32768 +#define PORT_INT_REQUIRED_STACK 262144 #endif /** diff --git a/flight/PiOS/STM32F4xx/pios_dsm.c b/flight/PiOS/Common/pios_dsm.c similarity index 90% rename from flight/PiOS/STM32F4xx/pios_dsm.c rename to flight/PiOS/Common/pios_dsm.c index 5ebe6b86003..6571488c3e9 100644 --- a/flight/PiOS/STM32F4xx/pios_dsm.c +++ b/flight/PiOS/Common/pios_dsm.c @@ -8,7 +8,7 @@ * * @file pios_dsm.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2014-2015 * @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream * @see The GNU Public License (GPL) Version 3 * @@ -102,16 +102,20 @@ static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev) } /* Try to bind DSMx satellite using specified number of pulses */ -static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) +static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t num_pulses) { const struct pios_dsm_cfg *cfg = dsm_dev->cfg; GPIO_InitTypeDef GPIO_InitStructure = cfg->bind.init; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; +#ifdef SMALLF1 + GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; +#else + GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; +#endif /* just to limit bind pulses */ - if (bind > 10) - bind = 10; + if (num_pulses > 10) + num_pulses = 10; GPIO_Init(cfg->bind.gpio, (GPIO_InitTypeDef*)&cfg->bind.init); @@ -121,7 +125,7 @@ static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) /* on CC works up to 140ms, guess bind window is around 20-140ms after power up */ while (((float) PIOS_DELAY_GetRaw() / (float) PIOS_SYSCLK) < 0.02f); - for (int i = 0; i < bind ; i++) { + for (int i = 0; i < num_pulses ; i++) { /* RX line, drive low for 120us */ GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); PIOS_DELAY_WaituS(120); @@ -297,7 +301,7 @@ int32_t PIOS_DSM_Init(uintptr_t *dsm_id, const struct pios_dsm_cfg *cfg, const struct pios_com_driver *driver, uintptr_t lower_id, - uint8_t bind) + HwSharedDSMxModeOptions mode) { PIOS_DEBUG_Assert(dsm_id); PIOS_DEBUG_Assert(cfg); @@ -312,9 +316,40 @@ int32_t PIOS_DSM_Init(uintptr_t *dsm_id, /* Bind the configuration to the device instance */ dsm_dev->cfg = cfg; + uint8_t num_pulses = 0; + + // check user settings to determine which resolution mode to use + // if invalid mode selected, bail + if (mode > HWSHARED_DSMXMODE_BIND10PULSES) + return -1; + + // set resolution or bind mode depending on user selection + switch (mode) + { + case HWSHARED_DSMXMODE_AUTODETECT: + dsm_dev->resolution = DSM_UNKNOWN; + break; + case HWSHARED_DSMXMODE_FORCE10BIT: + dsm_dev->resolution = DSM_10BIT; + break; + case HWSHARED_DSMXMODE_FORCE11BIT: + dsm_dev->resolution = DSM_11BIT; + break; + case HWSHARED_DSMXMODE_BIND3PULSES: + case HWSHARED_DSMXMODE_BIND4PULSES: + case HWSHARED_DSMXMODE_BIND5PULSES: + case HWSHARED_DSMXMODE_BIND6PULSES: + case HWSHARED_DSMXMODE_BIND7PULSES: + case HWSHARED_DSMXMODE_BIND8PULSES: + case HWSHARED_DSMXMODE_BIND9PULSES: + case HWSHARED_DSMXMODE_BIND10PULSES: + num_pulses = 3 + mode - HWSHARED_DSMXMODE_BIND3PULSES; + break; + } + /* Bind the receiver if requested */ - if (bind) - PIOS_DSM_Bind(dsm_dev, bind); + if (num_pulses > 0) + PIOS_DSM_Bind(dsm_dev, num_pulses); PIOS_DSM_ResetState(dsm_dev); diff --git a/flight/PiOS/Common/pios_hal.c b/flight/PiOS/Common/pios_hal.c new file mode 100644 index 00000000000..2d42b31ff7e --- /dev/null +++ b/flight/PiOS/Common/pios_hal.c @@ -0,0 +1,796 @@ +/** + ****************************************************************************** + * @file pios_hal.c + * @author Tau Labs, http://taulabs.org, Copyright (C) 2015 + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_HAL Hardware abstraction layer files + * @{ + * @brief Code to initialize ports/devices for multiple targets + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#include +#include + +#include +#include +#include +#include +#include + +#include + +#include + +uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#if defined(PIOS_INCLUDE_RFM22B) +uint32_t pios_rfm22b_id; +uintptr_t pios_com_rf_id; +#endif + +uintptr_t pios_com_gps_id; +uintptr_t pios_com_bridge_id; + +#if defined(PIOS_INCLUDE_MAVLINK) +uintptr_t pios_com_mavlink_id; +#endif + +#if defined(PIOS_INCLUDE_HOTT) +uintptr_t pios_com_hott_id; +#endif + +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) +uintptr_t pios_com_frsky_sensor_hub_id; +#endif + +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) +uintptr_t pios_com_frsky_sport_id; +#endif + +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) +uintptr_t pios_com_lighttelemetry_id; +#endif + +#if defined(PIOS_INCLUDE_PICOC) +uintptr_t pios_com_picoc_id; +#endif + +#if defined(PIOS_INCLUDE_USB_HID) || defined(PIOS_INCLUDE_USB_CDC) +uintptr_t pios_com_telem_usb_id; +#endif + +#if defined(PIOS_INCLUDE_USB_CDC) +uintptr_t pios_com_vcp_id; +#endif + +uintptr_t pios_com_telem_serial_id; + +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 +uintptr_t pios_com_debug_id; +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + +#ifndef PIOS_COM_TELEM_RF_RX_BUF_LEN +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 +#endif + +#ifndef PIOS_COM_TELEM_RF_TX_BUF_LEN +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 +#endif + +#ifndef PIOS_COM_GPS_RX_BUF_LEN +#define PIOS_COM_GPS_RX_BUF_LEN 32 +#endif + +#ifndef PIOS_COM_GPS_TX_BUF_LEN +#define PIOS_COM_GPS_TX_BUF_LEN 16 +#endif + +#ifndef PIOS_COM_TELEM_USB_RX_BUF_LEN +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#endif + +#ifndef PIOS_COM_TELEM_USB_TX_BUF_LEN +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 +#endif + +#ifndef PIOS_COM_BRIDGE_RX_BUF_LEN +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#endif + +#ifndef PIOS_COM_BRIDGE_TX_BUF_LEN +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 +#endif + +#ifndef PIOS_COM_MAVLINK_TX_BUF_LEN +#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 +#endif + +#ifndef PIOS_COM_HOTT_RX_BUF_LEN +#define PIOS_COM_HOTT_RX_BUF_LEN 16 +#endif + +#ifndef PIOS_COM_HOTT_TX_BUF_LEN +#define PIOS_COM_HOTT_TX_BUF_LEN 16 +#endif + +#ifndef PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN +#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128 +#endif + +#ifndef PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN +#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 19 +#endif + +#ifndef PIOS_COM_PICOC_RX_BUF_LEN +#define PIOS_COM_PICOC_RX_BUF_LEN 128 +#endif + +#ifndef PIOS_COM_PICOC_TX_BUF_LEN +#define PIOS_COM_PICOC_TX_BUF_LEN 128 +#endif + +#ifndef PIOS_COM_FRSKYSPORT_TX_BUF_LEN +#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 +#endif + +#ifndef PIOS_COM_FRSKYSPORT_RX_BUF_LEN +#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 +#endif + +#ifndef PIOS_COM_RFM22B_RF_RX_BUF_LEN +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 +#endif + +#ifndef PIOS_COM_RFM22B_RF_TX_BUF_LEN +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 +#endif + +/** + * @brief Flash a blink code. + * @param[in] led_id The LED to blink + * @param[in] code Number of blinks to do in a row + */ +void PIOS_HAL_Panic(uint32_t led_id, int32_t code) { + while(1){ + for (int32_t i = 0; i < code; i++) { + PIOS_WDG_Clear(); + PIOS_LED_Toggle(led_id); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_LED_Toggle(led_id); + PIOS_DELAY_WaitmS(200); + } + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(100); + PIOS_WDG_Clear(); + } +} + +/** + * @brief Bind a device instance to a role. + * + * This allows us to check for duplicates and to eventually do something + * intelligent baout them here. + * + * @param[out] target place dedicated for this role to store device id + * @param[in] value handle of the device to store into this role. + */ +static void PIOS_HAL_SetTarget(uintptr_t *target, uintptr_t value) { + if (target) { +#ifndef PIOS_NO_ALARMS + if (*target) { + set_config_error(SYSTEMALARMS_CONFIGERROR_DUPLICATEPORTCFG); + } +#endif + + *target = value; + } +} + +/** + * @brief Assign a device instance into the receiver map + * + * @param[in] receiver_type the receiver type index from MANUALCONTROL + * @param[in] value handle of the device instance + */ +static void PIOS_HAL_SetReceiver(int receiver_type, uintptr_t value) { + PIOS_HAL_SetTarget(pios_rcvr_group_map + receiver_type, value); +} + +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) +/** + * @brief Configures USART and COM subsystems, allocates buffers. + * + * @param[in] usart_port_cfg USART configuration + * @param[in] rx_buf_len receive buffer size + * @param[in] tx_buf_len transmit buffer size + * @param[in] com_driver communications driver + * @param[out] com_id id of the PIOS_Com instance + */ +void PIOS_HAL_ConfigureCom(const struct pios_usart_cfg *usart_port_cfg, + size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uintptr_t *com_id) +{ + uintptr_t usart_id; + if (PIOS_USART_Init(&usart_id, usart_port_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer; + if (rx_buf_len > 0) { + rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); + PIOS_Assert(rx_buffer); + } else { + rx_buffer = NULL; + } + + uint8_t * tx_buffer; + if (tx_buf_len > 0) { + tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); + PIOS_Assert(tx_buffer); + } else { + tx_buffer = NULL; + } + + if (PIOS_COM_Init(com_id, com_driver, usart_id, + rx_buffer, rx_buf_len, + tx_buffer, tx_buf_len)) { + PIOS_Assert(0); + } +} +#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ + +#ifdef PIOS_INCLUDE_DSM +/** + * @brief Configures a DSM receiver + * + * @param[in] usart_dsm_cfg Configuration for the USART for DSM mode. + * @param[in] dsm_cfg Configuration for DSM on this target + * @param[in] usart_com_driver The COM driver for this USART + * @param[in] mode Mode in which to operate DSM driver; encapsulates binding + */ +static void PIOS_HAL_ConfigureDSM(const struct pios_usart_cfg *usart_dsm_cfg, + const struct pios_dsm_cfg *dsm_cfg, + const struct pios_com_driver *usart_com_driver, + HwSharedDSMxModeOptions mode) +{ + uintptr_t usart_dsm_id; + if (PIOS_USART_Init(&usart_dsm_id, usart_dsm_cfg)) { + PIOS_Assert(0); + } + + uintptr_t dsm_id; + if (PIOS_DSM_Init(&dsm_id, dsm_cfg, usart_com_driver, + usart_dsm_id, mode)) { + PIOS_Assert(0); + } + + uintptr_t dsm_rcvr_id; + if (PIOS_RCVR_Init(&dsm_rcvr_id, &pios_dsm_rcvr_driver, dsm_id)) { + PIOS_Assert(0); + } + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, dsm_rcvr_id); +} + +#endif + +#ifdef PIOS_INCLUDE_HSUM +/** + * @brief Configures a HSUM receiver + * + * @param[in] usart_hsum_cfg Configuration for the USART for DSM mode. + * @param[in] usart_com_driver The COM driver for this USART + * @param[in] proto SUMH/SUMD? + */ +static void PIOS_HAL_ConfigureHSUM(const struct pios_usart_cfg *usart_hsum_cfg, + const struct pios_com_driver *usart_com_driver, + enum pios_hsum_proto *proto) +{ + uintptr_t usart_hsum_id; + if (PIOS_USART_Init(&usart_hsum_id, usart_hsum_cfg)) { + PIOS_Assert(0); + } + + uintptr_t hsum_id; + if (PIOS_HSUM_Init(&hsum_id, usart_com_driver, + usart_hsum_id, *proto)) { + PIOS_Assert(0); + } + + uintptr_t hsum_rcvr_id; + if (PIOS_RCVR_Init(&hsum_rcvr_id, &pios_hsum_rcvr_driver, hsum_id)) { + PIOS_Assert(0); + } + + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM, + hsum_rcvr_id); +} +#endif + +/** @brief Configure a [flexi/main/rcvr/etc] port. + * + * Not all of these parameters will be defined for each port. Caller may pass + * NULL but is responsible for ensuring illegal modes also do not exist in the + * target's UAVO definition. + * + * Hopefully more of these can be inferred with time and the arg list can + * greatly decrease in size. + * + * @param[in] port_type protocol to speak on this port + * @param[in] usart_port_cfg serial configuration for most modes on this + * @param[in] com_driver communications driver for serial on this port + * @param[out] i2c_id ID of I2C peripheral if operated in I2C mode + * @param[in] i2c_Cfg Adapter configuration/registers for I2C mode + * @param[in] ppm_cfg Configuration/registers for PPM mode + * @param[in] led_id LED to blink when there's panics + * @param[in] usart_dsm_hsum_cfg usart configuration for DSM/HSUM modes + * @param[in] dsm_cfg DSM configuration for this port + * @param[in] dsm_mode Mode in which to operate DSM driver; encapsulates binding + * @param[in] sbus_rcvr_cfg usart configuration for SBUS modes + * @param[in] sbus_cfg SBUS configuration for this port + * @param[in] sbus_toggle Whether there is SBUS inverters to touch on this port + */ +void PIOS_HAL_ConfigurePort(HwSharedPortTypesOptions port_type, + const struct pios_usart_cfg *usart_port_cfg, + const struct pios_com_driver *com_driver, + uint32_t *i2c_id, + const struct pios_i2c_adapter_cfg *i2c_cfg, + const struct pios_ppm_cfg *ppm_cfg, + uint32_t led_id, +/* TODO: future work to factor most of these away */ + const struct pios_usart_cfg *usart_dsm_hsum_cfg, + const struct pios_dsm_cfg *dsm_cfg, + HwSharedDSMxModeOptions dsm_mode, + const struct pios_usart_cfg *sbus_rcvr_cfg, + const struct pios_sbus_cfg *sbus_cfg, + bool sbus_toggle + ) +{ + uintptr_t port_driver_id; + uintptr_t *target=NULL, *target2=NULL;; + + switch (port_type) { + case HWSHARED_PORTTYPES_I2C: +#if defined(PIOS_INCLUDE_I2C) + if (i2c_id && i2c_cfg) { + if (PIOS_I2C_Init(i2c_id, i2c_cfg)) { + PIOS_Assert(0); + } + if (PIOS_I2C_CheckClear(*i2c_id) != 0) + PIOS_HAL_Panic(led_id, 6); + } +#endif /* PIOS_INCLUDE_I2C */ + break; + case HWSHARED_PORTTYPES_PPM: +#if defined(PIOS_INCLUDE_PPM) + if (ppm_cfg) { + uintptr_t ppm_id; + PIOS_PPM_Init(&ppm_id, ppm_cfg); + + uintptr_t ppm_rcvr_id; + if (PIOS_RCVR_Init(&ppm_rcvr_id, &pios_ppm_rcvr_driver, ppm_id)) { + PIOS_Assert(0); + } + + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM, ppm_rcvr_id); + } +#endif /* PIOS_INCLUDE_PPM */ + break; + + case HWSHARED_PORTTYPES_DISABLED: + break; + case HWSHARED_PORTTYPES_TELEMETRY: + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_telem_serial_id; + break; + case HWSHARED_PORTTYPES_GPS: + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_gps_id; + break; + case HWSHARED_PORTTYPES_DSM: +#if defined(PIOS_INCLUDE_DSM) + if (dsm_cfg && usart_dsm_hsum_cfg) { + PIOS_HAL_ConfigureDSM(usart_dsm_hsum_cfg, dsm_cfg, com_driver, dsm_mode); + } +#endif /* PIOS_INCLUDE_DSM */ + break; + case HWSHARED_PORTTYPES_SBUS: +#if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) + if (sbus_cfg && sbus_rcvr_cfg) { + uintptr_t usart_sbus_id; + if (PIOS_USART_Init(&usart_sbus_id, sbus_rcvr_cfg)) { + PIOS_Assert(0); + } + uintptr_t sbus_id; + if (PIOS_SBus_Init(&sbus_id, sbus_cfg, com_driver, usart_sbus_id)) { + PIOS_Assert(0); + } + uintptr_t sbus_rcvr_id; + if (PIOS_RCVR_Init(&sbus_rcvr_id, &pios_sbus_rcvr_driver, sbus_id)) { + PIOS_Assert(0); + } + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS, sbus_rcvr_id); + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = sbus_rcvr_id; + } +#endif /* PIOS_INCLUDE_SBUS */ + break; + case HWSHARED_PORTTYPES_HOTTSUMD: + case HWSHARED_PORTTYPES_HOTTSUMH: +#if defined(PIOS_INCLUDE_HSUM) + if (usart_dsm_hsum_cfg) { + enum pios_hsum_proto proto; + switch (port_type) { + case HWSHARED_PORTTYPES_HOTTSUMD: + proto = PIOS_HSUM_PROTO_SUMD; + break; + case HWSHARED_PORTTYPES_HOTTSUMH: + proto = PIOS_HSUM_PROTO_SUMH; + break; + default: + PIOS_Assert(0); + break; + } + PIOS_HAL_ConfigureHSUM(usart_dsm_hsum_cfg, com_driver, &proto); + } +#endif /* PIOS_INCLUDE_HSUM */ + break; + case HWSHARED_PORTTYPES_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + PIOS_HAL_ConfigureCom(usart_port_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_debug_id; +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWSHARED_PORTTYPES_COMBRIDGE: + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_bridge_id; + break; + case HWSHARED_PORTTYPES_MAVLINKTX: +#if defined(PIOS_INCLUDE_MAVLINK) + PIOS_HAL_ConfigureCom(usart_port_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_mavlink_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWSHARED_PORTTYPES_MAVLINKTX_GPS_RX: +#if defined(PIOS_INCLUDE_MAVLINK) + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_mavlink_id; + target2 = &pios_com_gps_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWSHARED_PORTTYPES_HOTTTELEMETRY: +#if defined(PIOS_INCLUDE_HOTT) + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_hott_id; +#endif /* PIOS_INCLUDE_HOTT */ + break; + case HWSHARED_PORTTYPES_FRSKYSENSORHUB: +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) + PIOS_HAL_ConfigureCom(usart_port_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_frsky_sensor_hub_id; +#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ + break; + case HWSHARED_PORTTYPES_FRSKYSPORTTELEMETRY: +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_frsky_sport_id; +#endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ + break; + case HWSHARED_PORTTYPES_LIGHTTELEMETRYTX: +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) + PIOS_HAL_ConfigureCom(usart_port_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_lighttelemetry_id; +#endif + break; + case HWSHARED_PORTTYPES_PICOC: +#if defined(PIOS_INCLUDE_PICOC) + PIOS_HAL_ConfigureCom(usart_port_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, com_driver, &port_driver_id); + target = &pios_com_picoc_id; +#endif /* PIOS_INCLUDE_PICOC */ + break; + } /* port_type */ + + if (port_type != HWSHARED_PORTTYPES_SBUS && sbus_toggle) { + GPIO_Init(sbus_cfg->inv.gpio, (GPIO_InitTypeDef*)&sbus_cfg->inv.init); + GPIO_WriteBit(sbus_cfg->inv.gpio, sbus_cfg->inv.init.GPIO_Pin, sbus_cfg->gpio_inv_disable); + } + + PIOS_HAL_SetTarget(target, port_driver_id); + PIOS_HAL_SetTarget(target2, port_driver_id); +} + +#if defined(PIOS_INCLUDE_USB_CDC) +/** @brief Configure USB CDC. + * + * @param[in] port_type The service provided over USB CDC communications + * @param[in] usb_id ID of the USB device + * @param[in] cdc_cfg Platform-specific CDC configuration + */ +void PIOS_HAL_ConfigureCDC(HwSharedUSB_VCPPortOptions port_type, + uintptr_t usb_id, + const struct pios_usb_cdc_cfg *cdc_cfg) { + uintptr_t pios_usb_cdc_id; + + // TODO: Should we actually do this if disabled??? + if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, cdc_cfg, usb_id)) { + PIOS_Assert(0); + } + + switch (port_type) { + case HWSHARED_USB_VCPPORT_DISABLED: + break; + case HWSHARED_USB_VCPPORT_USBTELEMETRY: + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; + case HWSHARED_USB_VCPPORT_COMBRIDGE: + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, + tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; + case HWSHARED_USB_VCPPORT_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + { + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + NULL, 0, + tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWSHARED_USB_VCPPORT_PICOC: +#if defined(PIOS_INCLUDE_PICOC) + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, + tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_PICOC */ + break; + } +} +#endif + +#if defined(PIOS_INCLUDE_USB_HID) +/** @brief Configure USB HID. + * + * @param[in] port_type The service provided over USB HID communications + * @param[in] usb_id ID of the USB device + * @param[in] hid_cfg Platform-specific HID configuration + */ +void PIOS_HAL_ConfigureHID(HwSharedUSB_HIDPortOptions port_type, + uintptr_t usb_id, const struct pios_usb_hid_cfg *hid_cfg) { + uintptr_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, hid_cfg, usb_id)) { + PIOS_Assert(0); + } + + switch (port_type) { + case HWSHARED_USB_HIDPORT_DISABLED: + break; + case HWSHARED_USB_HIDPORT_USBTELEMETRY: + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } + break; + case HWSHARED_USB_HIDPORT_RCTRANSMITTER: +#if defined(PIOS_INCLUDE_USB_RCTX) + { + if (PIOS_USB_RCTX_Init(&pios_usb_rctx_id, &pios_usb_rctx_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_USB_RCTX */ + break; + + } +} +#endif /* PIOS_INCLUDE_USB_HID */ + + +#if defined(PIOS_INCLUDE_RFM22B) +/** @brief Configure RFM22B radio. + * + * @param[in] radio_type What goes over this radio link + * @param[in] board_type Target board type + * @param[in] board_rev Target board revision + * @param[in] max_power Maximum configured output power + * @param[in] max_speed Maximum configured speed + * @param[in] openlrs_cfg Configuration for radio in openlrs mode + * @param[in] rfm22b_cfg Configuration for radio in TauLink mode + * @param[in] min_chan Minimum channel id. + * @param[in] max_chan Maximum channel id + * @param[in] coord_id 0 if we are coordinator, else the coord's radio id. + * @param[in] status_inst Which instance number to save RFM22BStatus to + */ +void PIOS_HAL_ConfigureRFM22B(HwSharedRadioPortOptions radio_type, + uint8_t board_type, uint8_t board_rev, + HwSharedMaxRfPowerOptions max_power, + HwSharedMaxRfSpeedOptions max_speed, + const struct pios_openlrs_cfg *openlrs_cfg, + const struct pios_rfm22b_cfg *rfm22b_cfg, + uint8_t min_chan, uint8_t max_chan, uint32_t coord_id, + int status_inst) { + /* Initalize the RFM22B radio COM device. */ + RFM22BStatusInitialize(); + RFM22BStatusCreateInstance(); + + RFM22BStatusData rfm22bstatus; + RFM22BStatusGet(&rfm22bstatus); + RFM22BStatusInstSet(1,&rfm22bstatus); + + // Initialize out status object. + rfm22bstatus.BoardType = board_type; + rfm22bstatus.BoardRevision = board_rev; + + if (radio_type == HWSHARED_RADIOPORT_OPENLRS) { +#if defined(PIOS_INCLUDE_OPENLRS_RCVR) + uintptr_t openlrs_id; + + PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg); + + { + uintptr_t rfm22brcvr_id; + PIOS_OpenLRS_Rcvr_Init(&rfm22brcvr_id, openlrs_id); + uintptr_t rfm22brcvr_rcvr_id; + if (PIOS_RCVR_Init(&rfm22brcvr_rcvr_id, &pios_openlrs_rcvr_driver, rfm22brcvr_id)) { + PIOS_Assert(0); + } + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS, rfm22brcvr_rcvr_id); + } +#endif /* PIOS_INCLUDE_OPENLRS_RCVR */ + } else if (radio_type == HWSHARED_RADIOPORT_DISABLED || + max_power == HWSHARED_MAXRFPOWER_0) { + // When radio disabled, it is ok for init to fail. This allows + // boards without populating this component. + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg) == 0) { + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); + rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); + } else { + pios_rfm22b_id = 0; + } + + rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; + } else { + // always allow receiving PPM when radio is on + bool ppm_mode = radio_type == HWSHARED_RADIOPORT_TELEMPPM || + radio_type == HWSHARED_RADIOPORT_PPM; + bool ppm_only = radio_type == HWSHARED_RADIOPORT_PPM; + bool is_oneway = radio_type == HWSHARED_RADIOPORT_PPM; + // Sparky2 can only receive PPM only + + /* Configure the RFM22B device. */ + if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { + PIOS_Assert(0); + } + + rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); + rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); + + /* Configure the radio com interface */ + uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); + uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); + + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id, + rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, + tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { + PIOS_Assert(0); + } + +#ifndef PIOS_NO_TELEM_ON_RF + /* Set Telemetry to use RFM22b if no other telemetry is configured (USB always overrides anyway) */ + if (!pios_com_telem_serial_id) { + pios_com_telem_serial_id = pios_com_rf_id; + } +#endif + rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_ENABLED; + + /* Set the radio configuration parameters. */ + PIOS_RFM22B_Config(pios_rfm22b_id, max_speed, min_chan, max_chan, coord_id, is_oneway, ppm_mode, ppm_only); + + // XXX TODO: Factor these power switches out. + /* Set the modem Tx poer level */ + switch (max_power) { + case HWSHARED_MAXRFPOWER_125: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); + break; + case HWSHARED_MAXRFPOWER_16: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); + break; + case HWSHARED_MAXRFPOWER_316: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); + break; + case HWSHARED_MAXRFPOWER_63: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); + break; + case HWSHARED_MAXRFPOWER_126: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); + break; + case HWSHARED_MAXRFPOWER_25: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); + break; + case HWSHARED_MAXRFPOWER_50: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); + break; + case HWSHARED_MAXRFPOWER_100: + PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); + break; + default: + // do nothing + break; + } + + /* Reinitialize the modem. */ + PIOS_RFM22B_Reinit(pios_rfm22b_id); + +#if defined(PIOS_INCLUDE_RFM22B_RCVR) + { + uintptr_t rfm22brcvr_id; + PIOS_RFM22B_Rcvr_Init(&rfm22brcvr_id, pios_rfm22b_id); + uintptr_t rfm22brcvr_rcvr_id; + if (PIOS_RCVR_Init(&rfm22brcvr_rcvr_id, &pios_rfm22b_rcvr_driver, rfm22brcvr_id)) { + PIOS_Assert(0); + } + PIOS_HAL_SetReceiver(MANUALCONTROLSETTINGS_CHANNELGROUPS_RFM22B, rfm22brcvr_rcvr_id); + } +#endif /* PIOS_INCLUDE_RFM22B_RCVR */ + } + + RFM22BStatusInstSet(status_inst, &rfm22bstatus); +} +#endif /* PIOS_INCLUDE_RFM22B */ diff --git a/flight/PiOS/Common/pios_mpu6000.c b/flight/PiOS/Common/pios_mpu6000.c index 1c4d1aeaf40..fd36c365be5 100644 --- a/flight/PiOS/Common/pios_mpu6000.c +++ b/flight/PiOS/Common/pios_mpu6000.c @@ -44,6 +44,13 @@ #define MPU6000_TASK_PRIORITY PIOS_THREAD_PRIO_HIGHEST #define MPU6000_TASK_STACK 484 +#ifdef PIOS_MPU6000_SPI_HIGH_SPEED +#define MPU6000_SPI_HIGH_SPEED PIOS_MPU6000_SPI_HIGH_SPEED +#else +#define MPU6000_SPI_HIGH_SPEED 20000000 // should result in 10.5MHz clock on F4 targets like Quanton, and 18MHz on F1 targets like CC3D +#endif +#define MPU6000_SPI_LOW_SPEED 1000000 + /* Global Variables */ enum pios_mpu6000_dev_magic { @@ -76,8 +83,8 @@ static struct mpu6000_dev *pios_mpu6000_dev; static struct mpu6000_dev *PIOS_MPU6000_alloc(void); static int32_t PIOS_MPU6000_Validate(struct mpu6000_dev *dev); static void PIOS_MPU6000_Config(const struct pios_mpu60x0_cfg *cfg); -static int32_t PIOS_MPU6000_ClaimBus(); -static int32_t PIOS_MPU6000_ReleaseBus(); +static int32_t PIOS_MPU6000_ClaimBus(bool lowspeed); +static int32_t PIOS_MPU6000_ReleaseBus(bool lowspeed); static int32_t PIOS_MPU6000_SetReg(uint8_t address, uint8_t buffer); static int32_t PIOS_MPU6000_GetReg(uint8_t address); static void PIOS_MPU6000_Task(void *parameters); @@ -157,9 +164,9 @@ int32_t PIOS_MPU6000_Init(uint32_t spi_id, uint32_t slave_num, const struct pios pios_mpu6000_dev->cfg = cfg; /* Configure the MPU6000 Sensor */ - PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, 100000); + PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, MPU6000_SPI_LOW_SPEED); PIOS_MPU6000_Config(cfg); - PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, 3000000); + PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, MPU6000_SPI_HIGH_SPEED); pios_mpu6000_dev->threadp = PIOS_Thread_Create( PIOS_MPU6000_Task, "pios_mpu6000", MPU6000_TASK_STACK, NULL, MPU6000_TASK_PRIORITY); @@ -230,9 +237,9 @@ static void PIOS_MPU6000_Config(const struct pios_mpu60x0_cfg *cfg) * on all different targets. */ - PIOS_MPU6000_ClaimBus(); + PIOS_MPU6000_ClaimBus(true); PIOS_DELAY_WaitmS(1); - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(true); PIOS_DELAY_WaitmS(10); // Reset chip @@ -369,9 +376,10 @@ void PIOS_MPU6000_SetLPF(enum pios_mpu60x0_filter filter) /** * @brief Claim the SPI bus for the accel communications and select this chip + * \param[in] flag controls if low speed access for control registers should be used * @return 0 if successful, -1 for invalid device, -2 if unable to claim bus */ -static int32_t PIOS_MPU6000_ClaimBus() +static int32_t PIOS_MPU6000_ClaimBus(bool lowspeed) { if (PIOS_MPU6000_Validate(pios_mpu6000_dev) != 0) return -1; @@ -379,21 +387,28 @@ static int32_t PIOS_MPU6000_ClaimBus() if (PIOS_SPI_ClaimBus(pios_mpu6000_dev->spi_id) != 0) return -2; + if (lowspeed) + PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, MPU6000_SPI_LOW_SPEED); + PIOS_SPI_RC_PinSet(pios_mpu6000_dev->spi_id, pios_mpu6000_dev->slave_num, 0); return 0; } /** * @brief Release the SPI bus for the accel communications and end the transaction + * \param[in] must be true when bus was claimed in lowspeed mode * @return 0 if successful */ -static int32_t PIOS_MPU6000_ReleaseBus() +static int32_t PIOS_MPU6000_ReleaseBus(bool lowspeed) { if (PIOS_MPU6000_Validate(pios_mpu6000_dev) != 0) return -1; PIOS_SPI_RC_PinSet(pios_mpu6000_dev->spi_id, pios_mpu6000_dev->slave_num, 1); + if (lowspeed) + PIOS_SPI_SetClockSpeed(pios_mpu6000_dev->spi_id, MPU6000_SPI_HIGH_SPEED); + return PIOS_SPI_ReleaseBus(pios_mpu6000_dev->spi_id); } @@ -406,13 +421,13 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) { uint8_t data; - if (PIOS_MPU6000_ClaimBus() != 0) + if (PIOS_MPU6000_ClaimBus(true) != 0) return -1; PIOS_SPI_TransferByte(pios_mpu6000_dev->spi_id, (0x80 | reg)); // request byte data = PIOS_SPI_TransferByte(pios_mpu6000_dev->spi_id, 0); // receive response - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(true); return data; } @@ -426,20 +441,20 @@ static int32_t PIOS_MPU6000_GetReg(uint8_t reg) */ static int32_t PIOS_MPU6000_SetReg(uint8_t reg, uint8_t data) { - if (PIOS_MPU6000_ClaimBus() != 0) + if (PIOS_MPU6000_ClaimBus(true) != 0) return -1; if (PIOS_SPI_TransferByte(pios_mpu6000_dev->spi_id, 0x7f & reg) != 0) { - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(true); return -2; } if (PIOS_SPI_TransferByte(pios_mpu6000_dev->spi_id, data) != 0) { - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(true); return -3; } - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(true); return 0; } @@ -563,15 +578,16 @@ static void PIOS_MPU6000_Task(void *parameters) uint8_t mpu6000_send_buf[BUFFER_SIZE] = { PIOS_MPU60X0_ACCEL_X_OUT_MSB | 0x80, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0 }; uint8_t mpu6000_rec_buf[BUFFER_SIZE]; - if (PIOS_MPU6000_ClaimBus() != 0) + // claim bus in high speed mode + if (PIOS_MPU6000_ClaimBus(false) != 0) continue; if (PIOS_SPI_TransferBlock(pios_mpu6000_dev->spi_id, mpu6000_send_buf, mpu6000_rec_buf, sizeof(mpu6000_send_buf), NULL) < 0) { - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(false); continue; } - PIOS_MPU6000_ReleaseBus(); + PIOS_MPU6000_ReleaseBus(false); // Rotate the sensor to OP convention. The datasheet defines X as towards the right // and Y as forward. OP convention transposes this. Also the Z is defined negatively @@ -589,61 +605,61 @@ static void PIOS_MPU6000_Task(void *parameters) accel_data.x = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); gyro_data.y = (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_90DEG: - accel_data.y = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); accel_data.x = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_180DEG: - accel_data.y = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); - accel_data.x = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_270DEG: accel_data.y = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); - accel_data.x = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); gyro_data.y = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_0DEG: - accel_data.y = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); accel_data.x = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_90DEG: accel_data.y = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); - accel_data.x = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); gyro_data.y = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.z = (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_180DEG: accel_data.y = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); - accel_data.x = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); gyro_data.y = (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_270DEG: - accel_data.y = - (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_YOUT_L]); accel_data.x = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_XOUT_L]); - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.z = (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6000_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_ACCEL_ZOUT_L]); @@ -681,20 +697,20 @@ static void PIOS_MPU6000_Task(void *parameters) gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); break; case PIOS_MPU60X0_TOP_90DEG: - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.x = (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); break; case PIOS_MPU60X0_TOP_180DEG: - gyro_data.y = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); break; case PIOS_MPU60X0_TOP_270DEG: gyro_data.y = (int16_t)(mpu6000_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_XOUT_L]); break; } - gyro_data.z = - (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6000_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6000_rec_buf[IDX_GYRO_ZOUT_L]); int32_t raw_temp = (int16_t)(mpu6000_rec_buf[IDX_TEMP_OUT_H] << 8 | mpu6000_rec_buf[IDX_TEMP_OUT_L]); float temperature = 35.0f + ((float)raw_temp + 512.0f) / 340.0f; diff --git a/flight/PiOS/Common/pios_mpu6050.c b/flight/PiOS/Common/pios_mpu6050.c index ca241aa63ef..2f1c13871a7 100644 --- a/flight/PiOS/Common/pios_mpu6050.c +++ b/flight/PiOS/Common/pios_mpu6050.c @@ -638,37 +638,37 @@ static void PIOS_MPU6050_Task(void *parameters) accel_data.x = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_90DEG: - accel_data.y = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); accel_data.x = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_180DEG: - accel_data.y = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); - accel_data.x = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_TOP_270DEG: accel_data.y = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); - accel_data.x = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); - accel_data.z = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + accel_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_0DEG: - accel_data.y = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); accel_data.x = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); @@ -683,17 +683,17 @@ static void PIOS_MPU6050_Task(void *parameters) break; case PIOS_MPU60X0_BOTTOM_180DEG: accel_data.y = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); - accel_data.x = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_270DEG: - accel_data.y = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); - accel_data.x = - (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + accel_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_YOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_YOUT_L]); + accel_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_ACCEL_XOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_XOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); accel_data.z = (int16_t)(mpu6050_rec_buf[IDX_ACCEL_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_ACCEL_ZOUT_L]); break; @@ -728,25 +728,25 @@ static void PIOS_MPU6050_Task(void *parameters) case PIOS_MPU60X0_TOP_0DEG: gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; case PIOS_MPU60X0_TOP_90DEG: - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; case PIOS_MPU60X0_TOP_180DEG: - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; case PIOS_MPU60X0_TOP_270DEG: gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.z = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.z = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_0DEG: - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.x = (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; @@ -757,12 +757,12 @@ static void PIOS_MPU6050_Task(void *parameters) break; case PIOS_MPU60X0_BOTTOM_180DEG: gyro_data.y = (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; case PIOS_MPU60X0_BOTTOM_270DEG: - gyro_data.y = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); - gyro_data.x = - (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); + gyro_data.y = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_YOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_YOUT_L]); + gyro_data.x = -1.0f * (int16_t)(mpu6050_rec_buf[IDX_GYRO_XOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_XOUT_L]); gyro_data.z = (int16_t)(mpu6050_rec_buf[IDX_GYRO_ZOUT_H] << 8 | mpu6050_rec_buf[IDX_GYRO_ZOUT_L]); break; } diff --git a/flight/PiOS/Common/pios_mpu9150.c b/flight/PiOS/Common/pios_mpu9150.c index 2a676d473d7..356b7a4f149 100644 --- a/flight/PiOS/Common/pios_mpu9150.c +++ b/flight/PiOS/Common/pios_mpu9150.c @@ -775,38 +775,38 @@ static void PIOS_MPU9150_Task(void *parameters) break; case PIOS_MPU60X0_TOP_90DEG: mag_data.y = (int16_t) (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); - mag_data.x = (int16_t) -(mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); + mag_data.x = -1.0f * (int16_t)(mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); mag_data.z = (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_TOP_180DEG: - mag_data.x = (int16_t) -(mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); - mag_data.y = (int16_t) -(mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); + mag_data.x = -1.0f * (int16_t)(mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); + mag_data.y = -1.0f * (int16_t)(mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); mag_data.z = (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_TOP_270DEG: - mag_data.y = (int16_t) -(mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); + mag_data.y = -1.0f * (int16_t)(mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); mag_data.x = (int16_t) (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); mag_data.z = (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_BOTTOM_0DEG: mag_data.x = (int16_t) (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); - mag_data.y = (int16_t) - (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); - mag_data.z = (int16_t) - (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); + mag_data.y = -1.0f * (int16_t) (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); + mag_data.z = -1.0f * (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_BOTTOM_90DEG: - mag_data.y = (int16_t) - (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); - mag_data.x = (int16_t) - (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); - mag_data.z = (int16_t) - (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); + mag_data.y = -1.0f * (int16_t) (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); + mag_data.x = -1.0f * (int16_t) (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); + mag_data.z = -1.0f * (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_BOTTOM_180DEG: - mag_data.x = (int16_t) - (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); + mag_data.x = -1.0f * (int16_t) (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); mag_data.y = (int16_t) (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); - mag_data.z = (int16_t) - (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); + mag_data.z = -1.0f * (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; case PIOS_MPU60X0_BOTTOM_270DEG: mag_data.y = (int16_t) (mpu9150_mag_buffer[1] << 0x08 | mpu9150_mag_buffer[0]); mag_data.x = (int16_t) (mpu9150_mag_buffer[3] << 0x08 | mpu9150_mag_buffer[2]); - mag_data.z = (int16_t) - (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); + mag_data.z = -1.0f * (int16_t) (mpu9150_mag_buffer[5] << 0x08 | mpu9150_mag_buffer[4]); break; } diff --git a/flight/PiOS/Common/pios_mpu9250_spi.c b/flight/PiOS/Common/pios_mpu9250_spi.c index 94ee908caaf..5c69f87ff00 100644 --- a/flight/PiOS/Common/pios_mpu9250_spi.c +++ b/flight/PiOS/Common/pios_mpu9250_spi.c @@ -50,7 +50,7 @@ #ifdef PIOS_MPU9250_SPI_HIGH_SPEED #define MPU9250_SPI_HIGH_SPEED PIOS_MPU9250_SPI_HIGH_SPEED #else -#define MPU9250_SPI_HIGH_SPEED 20000000 +#define MPU9250_SPI_HIGH_SPEED 20000000 // should result in 10.5MHz clock on F4 targets like Sparky2 #endif #define MPU9250_SPI_LOW_SPEED 300000 diff --git a/flight/PiOS/Common/pios_ms5611.c b/flight/PiOS/Common/pios_ms5611.c index af080cd3f49..eb943d7edbe 100644 --- a/flight/PiOS/Common/pios_ms5611.c +++ b/flight/PiOS/Common/pios_ms5611.c @@ -45,7 +45,8 @@ #define MS5611_TASK_STACK_BYTES 512 /* MS5611 Addresses */ -#define MS5611_I2C_ADDR 0x77 +#define MS5611_I2C_ADDR_0x76 0x76 +#define MS5611_I2C_ADDR_0x77 0x77 #define MS5611_RESET 0x1E #define MS5611_CALIB_ADDR 0xA2 /* First sample is factory stuff */ #define MS5611_CALIB_LEN 16 @@ -55,6 +56,9 @@ #define MS5611_ADC_MSB 0xF6 #define MS5611_P0 101.3250f +/* Private Variables */ +uint8_t ms5611_i2c_addr; + /* Private methods */ static int32_t PIOS_MS5611_Read(uint8_t address, uint8_t * buffer, uint8_t len); static int32_t PIOS_MS5611_WriteCommand(uint8_t command); @@ -144,6 +148,12 @@ int32_t PIOS_MS5611_Init(const struct pios_ms5611_cfg *cfg, int32_t i2c_device) dev->i2c_id = i2c_device; dev->cfg = cfg; + /* Which I2C address is being used? */ + if (dev->cfg->use_0x76_address == true) + ms5611_i2c_addr = MS5611_I2C_ADDR_0x76; + else + ms5611_i2c_addr = MS5611_I2C_ADDR_0x77; + if (PIOS_MS5611_WriteCommand(MS5611_RESET) != 0) return -2; @@ -322,14 +332,14 @@ static int32_t PIOS_MS5611_Read(uint8_t address, uint8_t *buffer, uint8_t len) const struct pios_i2c_txn txn_list[] = { { .info = __func__, - .addr = MS5611_I2C_ADDR, + .addr = ms5611_i2c_addr, .rw = PIOS_I2C_TXN_WRITE, .len = 1, .buf = &address, }, { .info = __func__, - .addr = MS5611_I2C_ADDR, + .addr = ms5611_i2c_addr, .rw = PIOS_I2C_TXN_READ, .len = len, .buf = buffer, @@ -355,7 +365,7 @@ static int32_t PIOS_MS5611_WriteCommand(uint8_t command) const struct pios_i2c_txn txn_list[] = { { .info = __func__, - .addr = MS5611_I2C_ADDR, + .addr = ms5611_i2c_addr, .rw = PIOS_I2C_TXN_WRITE, .len = 1, .buf = &command, @@ -374,7 +384,6 @@ int32_t PIOS_MS5611_Test() if (PIOS_MS5611_Validate(dev) != 0) return -1; - PIOS_MS5611_ClaimDevice(); PIOS_MS5611_StartADC(TEMPERATURE_CONV); PIOS_DELAY_WaitmS(PIOS_MS5611_GetDelay()); @@ -394,7 +403,6 @@ int32_t PIOS_MS5611_Test() dev->pressure_unscaled > 120000) return -1; - return 0; } diff --git a/flight/PiOS/Common/pios_rfm22b.c b/flight/PiOS/Common/pios_rfm22b.c index a0d217fd307..c7076eeffd0 100644 --- a/flight/PiOS/Common/pios_rfm22b.c +++ b/flight/PiOS/Common/pios_rfm22b.c @@ -99,14 +99,14 @@ /* Local Defines */ #define STACK_SIZE_BYTES 800 #define TASK_PRIORITY PIOS_THREAD_PRIO_HIGHEST // flight control relevant device driver (ppm link) -#define RFM22B_DEFAULT_RX_DATARATE RFM22_datarate_9600 +#define RFM22B_DEFAULT_RX_DATARATE HWSHARED_MAXRFSPEED_9600 #define RFM22B_DEFAULT_TX_POWER RFM22_tx_pwr_txpow_0 #define RFM22B_NOMINAL_CARRIER_FREQUENCY 430000000 #define RFM22B_LINK_QUALITY_THRESHOLD 20 #define RFM22B_DEFAULT_MIN_CHANNEL 0 #define RFM22B_DEFAULT_MAX_CHANNEL 250 #define RFM22B_DEFAULT_CHANNEL_SET 24 -#define RFM22B_PPM_ONLY_DATARATE RFM22_datarate_9600 +#define RFM22B_PPM_ONLY_DATARATE HWSHARED_MAXRFSPEED_9600 #define RADIO_SYNC_PULSES_DISCONNECT 3 // The maximum amount of time without activity before initiating a reset. #define PIOS_RFM22B_SUPERVISOR_TIMEOUT 150 // ms @@ -611,7 +611,7 @@ void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, * @param[in] oneway Only the coordinator can send packets if true. */ void PIOS_RFM22B_Config(uint32_t rfm22b_id, - enum rfm22b_datarate datarate, + HwSharedMaxRfSpeedOptions datarate, uint8_t min_chan, uint8_t max_chan, uint32_t coordinator_id, bool oneway, bool ppm_mode, @@ -1362,7 +1362,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) break; } // Wait 1ms if not. - PIOS_DELAY_WaitmS(1); + PIOS_Thread_Sleep(1); } // **************** @@ -1407,6 +1407,9 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // incorrect RF module version return RADIO_EVENT_FATAL_ERROR; } + + PIOS_Thread_Sleep(1); + // calibrate our RF module to be exactly on frequency .. different for every module rfm22_write(rfm22b_dev, RFM22_xtal_osc_load_cap, OSC_LOAD_CAP); @@ -1446,6 +1449,8 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22_write(rfm22b_dev, RFM22_gpio2_config, RFM22_gpio2_config_drv3 | RFM22_gpio2_config_cca); + PIOS_Thread_Sleep(1); + // FIFO mode, GFSK modulation uint8_t fd_bit = rfm22_read(rfm22b_dev, @@ -1479,6 +1484,8 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) rfm22_write(rfm22b_dev, RFM22_rssi_threshold_clear_chan_indicator, (-90 + 122) * 2); + PIOS_Thread_Sleep(1); + // enable the internal Tx & Rx packet handlers (without CRC) rfm22_write(rfm22b_dev, RFM22_data_access_control, RFM22_dac_enpacrx | RFM22_dac_enpactx); @@ -1518,6 +1525,8 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) RFM22_header_cntl2_synclen_3210 | ((TX_PREAMBLE_NIBBLES >> 8) & 0x01)); + PIOS_Thread_Sleep(1); + // sync word rfm22_write(rfm22b_dev, RFM22_sync_word3, SYNC_BYTE_1); rfm22_write(rfm22b_dev, RFM22_sync_word2, SYNC_BYTE_2); @@ -1543,6 +1552,8 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) // Release the bus rfm22_releaseBus(rfm22b_dev); + PIOS_Thread_Sleep(1); + // Initialize the frequency and datarate to te default. rfm22_setNominalCarrierFrequency(rfm22b_dev, 0); pios_rfm22_setDatarate(rfm22b_dev); @@ -1565,7 +1576,7 @@ static enum pios_radio_event rfm22_init(struct pios_rfm22b_dev *rfm22b_dev) */ static void pios_rfm22_setDatarate(struct pios_rfm22b_dev *rfm22b_dev) { - enum rfm22b_datarate datarate = rfm22b_dev->datarate; + HwSharedMaxRfSpeedOptions datarate = rfm22b_dev->datarate; bool data_whitening = true; // Claim the SPI bus. diff --git a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c index 4b2ec1f1044..766f44030fb 100644 --- a/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c +++ b/flight/PiOS/STM32F10x/Libraries/STM32F10x_StdPeriph_Driver/src/stm32f10x_rcc.c @@ -192,6 +192,7 @@ static __I uint8_t APBAHBPrescTable[16] = {0, 0, 0, 0, 1, 2, 3, 4, 1, 2, 3, 4, 6, 7, 8, 9}; static __I uint8_t ADCPrescTable[4] = {2, 4, 6, 8}; +extern uint32_t hse_value; /** * @} @@ -926,7 +927,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) RCC_Clocks->SYSCLK_Frequency = HSI_VALUE; break; case 0x04: /* HSE used as system clock */ - RCC_Clocks->SYSCLK_Frequency = HSE_VALUE; + RCC_Clocks->SYSCLK_Frequency = hse_value; break; case 0x08: /* PLL used as system clock */ @@ -951,11 +952,11 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) /* HSE selected as PLL clock entry */ if ((RCC->CFGR & CFGR_PLLXTPRE_Mask) != (uint32_t)RESET) {/* HSE oscillator clock divided by 2 */ - RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE >> 1) * pllmull; + RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull; } else { - RCC_Clocks->SYSCLK_Frequency = HSE_VALUE * pllmull; + RCC_Clocks->SYSCLK_Frequency = hse_value * pllmull; } #endif } @@ -973,7 +974,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) if (pllsource == 0x00) {/* HSI oscillator clock divided by 2 selected as PLL clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSI_VALUE >> 1) * pllmull; + RCC_Clocks->SYSCLK_Frequency = (hse_value >> 1) * pllmull; } else {/* PREDIV1 selected as PLL clock entry */ @@ -984,7 +985,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) if (prediv1source == 0) { /* HSE oscillator clock selected as PREDIV1 clock entry */ - RCC_Clocks->SYSCLK_Frequency = (HSE_VALUE / prediv1factor) * pllmull; + RCC_Clocks->SYSCLK_Frequency = (hse_value / prediv1factor) * pllmull; } else {/* PLL2 clock selected as PREDIV1 clock entry */ @@ -992,7 +993,7 @@ void RCC_GetClocksFreq(RCC_ClocksTypeDef* RCC_Clocks) /* Get PREDIV2 division factor and PLL2 multiplication factor */ prediv2factor = ((RCC->CFGR2 & CFGR2_PREDIV2) >> 4) + 1; pll2mull = ((RCC->CFGR2 & CFGR2_PLL2MUL) >> 8 ) + 2; - RCC_Clocks->SYSCLK_Frequency = (((HSE_VALUE / prediv2factor) * pll2mull) / prediv1factor) * pllmull; + RCC_Clocks->SYSCLK_Frequency = (((hse_value / prediv2factor) * pll2mull) / prediv1factor) * pllmull; } } #endif /* STM32F10X_CL */ @@ -1467,4 +1468,4 @@ void RCC_ClearITPendingBit(uint8_t RCC_IT) * @} */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ +/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ \ No newline at end of file diff --git a/flight/PiOS/STM32F10x/inc/pios_i2c_priv.h b/flight/PiOS/STM32F10x/inc/pios_i2c_priv.h index fd9fa190f1c..e59e0adab94 100644 --- a/flight/PiOS/STM32F10x/inc/pios_i2c_priv.h +++ b/flight/PiOS/STM32F10x/inc/pios_i2c_priv.h @@ -3,7 +3,7 @@ * * @file pios_i2c_priv.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 * @brief I2C private definitions. * @see The GNU Public License (GPL) Version 3 * @@ -132,6 +132,7 @@ struct pios_i2c_adapter { struct pios_mutex *lock; struct pios_semaphore *sem_ready; + struct pios_semaphore *sem_busy; bool bus_error; bool nack; diff --git a/flight/PiOS/STM32F10x/pios_dsm.c b/flight/PiOS/STM32F10x/pios_dsm.c deleted file mode 100644 index 0415887a190..00000000000 --- a/flight/PiOS/STM32F10x/pios_dsm.c +++ /dev/null @@ -1,422 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions - * @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream - * @{ - * - * @file pios_dsm.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2014 - * @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Project Includes */ -#include "pios.h" -#include "pios_dsm_priv.h" - -#if defined(PIOS_INCLUDE_DSM) - -/* Forward Declarations */ -static int32_t PIOS_DSM_Get(uintptr_t rcvr_id, uint8_t channel); -static uint16_t PIOS_DSM_RxInCallback(uintptr_t context, - uint8_t *buf, - uint16_t buf_len, - uint16_t *headroom, - bool *need_yield); -static void PIOS_DSM_Supervisor(uintptr_t dsm_id); - -/* Local Variables */ -const struct pios_rcvr_driver pios_dsm_rcvr_driver = { - .read = PIOS_DSM_Get, -}; - -enum dsm_resolution { - DSM_UNKNOWN, DSM_10BIT, DSM_11BIT -}; - -enum pios_dsm_dev_magic { - PIOS_DSM_DEV_MAGIC = 0x44534d78, -}; - -struct pios_dsm_state { - uint16_t channel_data[PIOS_DSM_NUM_INPUTS]; - uint8_t received_data[DSM_FRAME_LENGTH]; - uint8_t receive_timer; - uint8_t failsafe_timer; - uint8_t frame_found; - uint8_t byte_count; -#ifdef DSM_LOST_FRAME_COUNTER - uint8_t frames_lost_last; - uint16_t frames_lost; -#endif -}; - -struct pios_dsm_dev { - enum pios_dsm_dev_magic magic; - const struct pios_dsm_cfg *cfg; - struct pios_dsm_state state; - enum dsm_resolution resolution; -}; - -/* Allocate DSM device descriptor */ -static struct pios_dsm_dev *PIOS_DSM_Alloc(void) -{ - struct pios_dsm_dev *dsm_dev; - - dsm_dev = (struct pios_dsm_dev *)PIOS_malloc(sizeof(*dsm_dev)); - if (!dsm_dev) - return NULL; - - dsm_dev->resolution = DSM_UNKNOWN; - dsm_dev->magic = PIOS_DSM_DEV_MAGIC; - return dsm_dev; -} - -/* Validate DSM device descriptor */ -static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev) -{ - return (dsm_dev->magic == PIOS_DSM_DEV_MAGIC); -} - -/* Try to bind DSMx satellite using specified number of pulses */ -static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) -{ - const struct pios_dsm_cfg *cfg = dsm_dev->cfg; - - GPIO_InitTypeDef GPIO_InitStructure; - GPIO_InitStructure.GPIO_Pin = cfg->bind.init.GPIO_Pin; - GPIO_InitStructure.GPIO_Speed = cfg->bind.init.GPIO_Speed; - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU; - - /* just to limit bind pulses */ - if (bind > 10) - bind = 10; - - GPIO_Init(cfg->bind.gpio, (GPIO_InitTypeDef*)&cfg->bind.init); - - /* RX line, set high */ - GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - - /* on CC works up to 140ms, guess bind window is around 20-140ms after power up */ - while (((float) PIOS_DELAY_GetRaw() / (float) PIOS_SYSCLK) < 0.02f); - - for (int i = 0; i < bind ; i++) { - /* RX line, drive low for 120us */ - GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - PIOS_DELAY_WaituS(120); - /* RX line, drive high for 120us */ - GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - PIOS_DELAY_WaituS(120); - } - /* RX line, set input and wait for data */ - GPIO_Init(cfg->bind.gpio, &GPIO_InitStructure); -} - -/* Reset channels in case of lost signal or explicit failsafe receiver flag */ -static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) { - state->channel_data[i] = PIOS_RCVR_TIMEOUT; - } -} - -/* Reset DSM receiver state */ -static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - state->receive_timer = 0; - state->failsafe_timer = 0; - state->frame_found = 0; -#ifdef DSM_LOST_FRAME_COUNTER - state->frames_lost_last = 0; - state->frames_lost = 0; -#endif - PIOS_DSM_ResetChannels(dsm_dev); -} - -/** - * DSM Resolution Detection: - * Satellite RX should be bound as master RX (Odd number of binding pulses), - * then transmitter information byte will be used to determine DSM resolution. - * If bound as slave RX, routine will fall back to looking at channel order to - * determine DSM resolution. It should be noted that the channel order method - * does not work with all Spektrum system configurations. - */ -enum dsm_resolution PIOS_DSM_DetectResolution(uint8_t *packet) -{ - uint8_t channel0, channel1; - uint16_t word0, word1; - bool bit_10, bit_11; - - // Form data words - word0 = ((uint16_t)packet[2] << 8) | packet[3]; - word1 = ((uint16_t)packet[4] << 8) | packet[5]; - - // Can't detect on the second data packet - if (word0 & DSM_2ND_FRAME_MASK) - return DSM_UNKNOWN; - - if (packet[1] != 0x00) // If transmitter information byte != 0, master satellite - { - if ((packet[1] & DSM_RESOLUTION_MASK) == 0x00) // Check resolution bit in transmitter information byte - return DSM_10BIT; // and set DSM resolution accordingly - else - return DSM_11BIT; - } - else // Else slave satellite - { - // Check for 10 bit - channel0 = (word0 >> 10) & 0x0f; - channel1 = (word1 >> 10) & 0x0f; - bit_10 = (channel0 == 1) && (channel1 == 5); - - // Check for 11 bit - channel0 = (word0 >> 11) & 0x0f; - channel1 = (word1 >> 11) & 0x0f; - bit_11 = (channel0 == 1) && (channel1 == 5); - - if (bit_10 && !bit_11) - return DSM_10BIT; - - if (bit_11 && !bit_10) - return DSM_11BIT; - - return DSM_UNKNOWN; - } -} - -/** - * This is the code from the PIOS_DSM layer - */ -int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - /* Fix resolution for detection. */ - -#ifdef DSM_LOST_FRAME_COUNTER - /* increment the lost frame counter */ - uint8_t frames_lost = state->received_data[0]; - state->frames_lost += (frames_lost - state->frames_lost_last); - state->frames_lost_last = frames_lost; -#endif - - // If no stream type has yet been detected, then try to probe for it - // this should only happen once per power cycle - if (dsm_dev->resolution == DSM_UNKNOWN) { - dsm_dev->resolution = PIOS_DSM_DetectResolution(state->received_data); - } - - /* Stream type still not detected */ - if (dsm_dev->resolution == DSM_UNKNOWN) { - return -2; - } - uint8_t resolution = (dsm_dev->resolution == DSM_10BIT) ? 10 : 11; - uint16_t mask = (dsm_dev->resolution == DSM_10BIT) ? 0x03ff : 0x07ff; - - /* unroll channels */ - uint8_t *s = &(state->received_data[2]); - - for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) { - uint16_t word = ((uint16_t)s[0] << 8) | s[1]; - s += 2; - - /* skip empty channel slot */ - if (word == 0xffff) - continue; - - /* minimal data validation */ - if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) { - /* invalid frame data, ignore rest of the frame */ - goto stream_error; - } - - /* extract and save the channel value */ - uint8_t channel_num = (word >> resolution) & 0x0f; - state->channel_data[channel_num] = (word & mask); - } - -#ifdef DSM_LOST_FRAME_COUNTER - /* put lost frames counter into the last channel for debugging */ - state->channel_data[PIOS_DSM_NUM_INPUTS-1] = state->frames_lost; -#endif - - /* all channels processed */ - return 0; - -stream_error: - /* either DSM2 selected with DSMX stream found, or vice-versa */ - return -1; -} - -/* Update decoder state processing input byte from the DSMx stream */ -static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - if (state->frame_found) { - /* receiving the data frame */ - if (state->byte_count < DSM_FRAME_LENGTH) { - /* store next byte */ - state->received_data[state->byte_count++] = byte; - if (state->byte_count == DSM_FRAME_LENGTH) { - /* full frame received - process and wait for new one */ - if (!PIOS_DSM_UnrollChannels(dsm_dev)) - /* data looking good */ - state->failsafe_timer = 0; - - /* prepare for the next frame */ - state->frame_found = 0; - } - } - } -} - -/* Initialise DSM receiver interface */ -int32_t PIOS_DSM_Init(uintptr_t *dsm_id, - const struct pios_dsm_cfg *cfg, - const struct pios_com_driver *driver, - uintptr_t lower_id, - uint8_t bind) -{ - PIOS_DEBUG_Assert(dsm_id); - PIOS_DEBUG_Assert(cfg); - PIOS_DEBUG_Assert(driver); - - struct pios_dsm_dev *dsm_dev; - - dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc(); - if (!dsm_dev) - return -1; - - /* Bind the configuration to the device instance */ - dsm_dev->cfg = cfg; - - /* Bind the receiver if requested */ - if (bind) - PIOS_DSM_Bind(dsm_dev, bind); - - PIOS_DSM_ResetState(dsm_dev); - - *dsm_id = (uintptr_t)dsm_dev; - - /* Set comm driver callback */ - (driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id); - - if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) { - PIOS_DEBUG_Assert(0); - } - - return 0; -} - -/* Comm byte received callback */ -static uint16_t PIOS_DSM_RxInCallback(uintptr_t context, - uint8_t *buf, - uint16_t buf_len, - uint16_t *headroom, - bool *need_yield) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context; - - bool valid = PIOS_DSM_Validate(dsm_dev); - PIOS_Assert(valid); - - /* process byte(s) and clear receive timer */ - for (uint8_t i = 0; i < buf_len; i++) { - PIOS_DSM_UpdateState(dsm_dev, buf[i]); - dsm_dev->state.receive_timer = 0; - } - - /* Always signal that we can accept another byte */ - if (headroom) - *headroom = DSM_FRAME_LENGTH; - - /* We never need a yield */ - *need_yield = false; - - /* Always indicate that all bytes were consumed */ - return buf_len; -} - -/** - * Get the value of an input channel - * \param[in] channel Number of the channel desired (zero based) - * \output PIOS_RCVR_INVALID channel not available - * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver - * \output >=0 channel value - */ -static int32_t PIOS_DSM_Get(uintptr_t rcvr_id, uint8_t channel) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id; - - if (!PIOS_DSM_Validate(dsm_dev)) - return PIOS_RCVR_INVALID; - - /* return error if channel is not available */ - if (channel >= PIOS_DSM_NUM_INPUTS) - return PIOS_RCVR_INVALID; - - /* may also be PIOS_RCVR_TIMEOUT set by other function */ - return dsm_dev->state.channel_data[channel]; -} - -/** - * Input data supervisor is called periodically and provides - * two functions: frame syncing and failsafe triggering. - * - * DSM frames come at 11ms or 22ms rate at 115200bps. - * RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives - * 8ms pause between frames which is good for both DSM frame rates. - * - * Data receive function must clear the receive_timer to confirm new - * data reception. If no new data received in 100ms, we must call the - * failsafe function which clears all channels. - */ -static void PIOS_DSM_Supervisor(uintptr_t dsm_id) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id; - - bool valid = PIOS_DSM_Validate(dsm_dev); - PIOS_Assert(valid); - - struct pios_dsm_state *state = &(dsm_dev->state); - - /* waiting for new frame if no bytes were received in 8ms */ - if (++state->receive_timer > 4) { - state->frame_found = 1; - state->byte_count = 0; - state->receive_timer = 0; - } - - /* activate failsafe if no frames have arrived in 102.4ms */ - if (++state->failsafe_timer > 64) { - PIOS_DSM_ResetChannels(dsm_dev); - state->failsafe_timer = 0; - } -} - -#endif /* PIOS_INCLUDE_DSM */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS/STM32F10x/pios_i2c_alt.c b/flight/PiOS/STM32F10x/pios_i2c_alt.c new file mode 100644 index 00000000000..08c15466bda --- /dev/null +++ b/flight/PiOS/STM32F10x/pios_i2c_alt.c @@ -0,0 +1,518 @@ +/** + ****************************************************************************** + * @addtogroup PIOS PIOS Core hardware abstraction layer + * @{ + * @addtogroup PIOS_I2C I2C Functions + * @brief STM32 Hardware dependent I2C functionality + * @{ + * + * @file pios_i2c.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 + * @brief I2C Enable/Disable routines + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +// Based on drv_i2c.c from baseflight - 32 bit fork of the MultiWii RC flight controller firmware + +/* + * == DO NOT USE FreeRTOS API in PIOS_I2C_EV_IRQ_Handler == + * + * Important STM32 Errata: + * + * See STM32F10xx8 and STM32F10xxB Errata sheet (Doc ID 14574 Rev 8), + * Section 2.11.1, 2.11.2. + * + * 2.11.1: + * When the EV7, EV7_1, EV6_1, EV6_3, EV2, EV8, and EV3 events are not + * managed before the current byte is being transferred, problems may be + * encountered such as receiving an extra byte, reading the same data twice + * or missing data. + * + * 2.11.2: + * In Master Receiver mode, when closing the communication using + * method 2, the content of the last read data can be corrupted. + * + * If the user software is not able to read the data N-1 before the STOP + * condition is generated on the bus, the content of the shift register + * (data N) will be corrupted. (data N is shifted 1-bit to the left). + * + * ---------------------------------------------------------------------- + * + * In order to ensure that events are not missed, the i2c interrupt must + * not be preempted. We set the i2c interrupt priority to be the highest + * interrupt in the system (priority level 0 / PIOS_IRQ_PRIO_EXTREME). + * + * Since priority level 0 is above configMAX_SYSCALL_INTERRUPT_PRIORITY, + * we cannot use any API functions in the I2C interrupt handlers (see FreeRTOS doc) + * + * As a result, we cannot use a semaphore (sem_ready) in PIOS_I2C_EV_IRQ_Handler + */ + +/* Project Includes */ +#include "pios.h" + +#if defined(PIOS_INCLUDE_I2C) + +//#define I2C_HALT_ON_ERRORS + +#define I2C_DEFAULT_TIMEOUT 30000 + +#include + +#define I2C_CR1_FLAG_SWRST ((uint32_t)0x10008000) +#define I2C_CR1_FLAG_ALERT ((uint32_t)0x10002000) +#define I2C_CR1_FLAG_PEC ((uint32_t)0x10001000) +#define I2C_CR1_FLAG_POS ((uint32_t)0x10000800) +#define I2C_CR1_FLAG_ACK ((uint32_t)0x10000400) +#define I2C_CR1_FLAG_STOP ((uint32_t)0x10000200) +#define I2C_CR1_FLAG_START ((uint32_t)0x10000100) + +struct i2c_internal_state { + volatile uint16_t error_count; + //-- + volatile bool busy; // See sem_ready note above + volatile uint8_t addr; + volatile uint8_t reg; + volatile uint8_t bytes; + volatile uint8_t dir; + volatile uint8_t* buf_p; + //-- + bool subaddress_sent; // flag to indicate if subaddess sent + bool final_stop; // flag to indicate final bus condition + int8_t index; // index is signed -1 == send the subaddress +}; + +/* + * + * + */ +static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter) +{ + GPIO_InitTypeDef scl_gpio_init; + GPIO_InitTypeDef sda_gpio_init; + + scl_gpio_init = i2c_adapter->cfg->scl.init; + scl_gpio_init.GPIO_Mode = GPIO_Mode_Out_OD; + GPIO_Init(i2c_adapter->cfg->scl.gpio, &scl_gpio_init); + + sda_gpio_init = i2c_adapter->cfg->sda.init; + sda_gpio_init.GPIO_Mode = GPIO_Mode_Out_OD; + GPIO_Init(i2c_adapter->cfg->sda.gpio, &sda_gpio_init); + + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); + GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); + + for (uint8_t i = 0; i < 8; i++) { + // Wait for any clock stretching to finish + while (!GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin)) { + PIOS_DELAY_WaituS(10); + } + + // Pull low + GPIO_ResetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); //Set bus low + PIOS_DELAY_WaituS(10); + // Release high again + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); //Set bus high + PIOS_DELAY_WaituS(10); + } + + // Generate a start then stop condition + GPIO_ResetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); // Set bus data low + PIOS_DELAY_WaituS(10); + GPIO_ResetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); // Set bus scl low + PIOS_DELAY_WaituS(10); + GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); // Set bus scl high + PIOS_DELAY_WaituS(10); + GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); // Set bus sda high + + // Init pins + GPIO_Init(i2c_adapter->cfg->scl.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->scl.init)); + GPIO_Init(i2c_adapter->cfg->sda.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->sda.init)); +} + +/* + * + * + */ +static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter) +{ + // Init pins + GPIO_Init(i2c_adapter->cfg->scl.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->scl.init)); + GPIO_Init(i2c_adapter->cfg->sda.gpio, (GPIO_InitTypeDef*)&(i2c_adapter->cfg->sda.init)); + + i2c_adapter_reset_bus(i2c_adapter); + i2c_adapter->curr_state = I2C_STATE_STOPPED; + + // Reset the I2C block + I2C_DeInit(i2c_adapter->cfg->regs); + // Disable EVT and ERR interrupts - they are enabled by the first request + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_ERR, DISABLE); + // Initialize the I2C block + I2C_Init(i2c_adapter->cfg->regs, (I2C_InitTypeDef*)&(i2c_adapter->cfg->init)); + // Enable I2C peripheral + I2C_Cmd(i2c_adapter->cfg->regs, ENABLE); +} + +/* + * + * + */ +static bool PIOS_I2C_validate(struct pios_i2c_adapter * i2c_adapter) +{ + return (i2c_adapter->magic == PIOS_I2C_DEV_MAGIC); +} + +/* + * + * + */ +static struct pios_i2c_adapter * PIOS_I2C_alloc(void) +{ + struct pios_i2c_adapter * i2c_adapter; + + i2c_adapter = (struct pios_i2c_adapter *)PIOS_malloc(sizeof(*i2c_adapter) + + sizeof(struct i2c_internal_state)); + if (!i2c_adapter) { + return(NULL); + } + + i2c_adapter->magic = PIOS_I2C_DEV_MAGIC; + i2c_adapter->active_txn = (const struct pios_i2c_txn *)(i2c_adapter+1); + ((struct i2c_internal_state*)i2c_adapter->active_txn)->error_count = 0; + return(i2c_adapter); +} + +/** +* Initializes IIC driver +* \param[in] mode currently only mode 0 supported +* \return < 0 if initialisation failed +*/ +int32_t PIOS_I2C_Init(uint32_t * i2c_id, const struct pios_i2c_adapter_cfg * cfg) +{ + PIOS_DEBUG_Assert(i2c_id); + PIOS_DEBUG_Assert(cfg); + + struct pios_i2c_adapter * i2c_adapter; + + i2c_adapter = (struct pios_i2c_adapter *) PIOS_I2C_alloc(); + if (!i2c_adapter) { + return(-1); + } + + /* Bind the configuration to the device instance */ + i2c_adapter->cfg = cfg; + + i2c_adapter->sem_busy = PIOS_Semaphore_Create(); + i2c_adapter->sem_ready = NULL; + + /* Enable the associated peripheral clock */ + switch ((uint32_t) i2c_adapter->cfg->regs) { + case (uint32_t) I2C1: + /* Enable I2C peripheral clock (APB1 == slow speed) */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE); + break; + case (uint32_t) I2C2: + /* Enable I2C peripheral clock (APB1 == slow speed) */ + RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE); + break; + } + + if (i2c_adapter->cfg->remap) { + GPIO_PinRemapConfig(i2c_adapter->cfg->remap, ENABLE); + } + + /* Initialize the state machine */ + i2c_adapter_fsm_init(i2c_adapter); + + *i2c_id = (uint32_t)i2c_adapter; + + /* Configure and enable I2C interrupts */ + NVIC_Init((NVIC_InitTypeDef*)&(i2c_adapter->cfg->event.init)); + NVIC_Init((NVIC_InitTypeDef*)&(i2c_adapter->cfg->error.init)); + + /* No error */ + return 0; +} + +/** + * @brief Perform a series of I2C transactions + * @returns 0 if success or error code + * @retval -1 for failed transaction + * @retval -2 for failure to get semaphore + */ +int32_t PIOS_I2C_Transfer(uint32_t i2c_id, const struct pios_i2c_txn txn_list[], uint32_t num_txns) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + + struct i2c_internal_state* state = (struct i2c_internal_state*)i2c_adapter->active_txn; + + PIOS_DEBUG_Assert(txn_list); + PIOS_DEBUG_Assert(num_txns); + + PIOS_DEBUG_Assert(num_txns == 1 || num_txns == 2); + if (num_txns < 1 || num_txns > 2) { + return -1; + } + + if (PIOS_Semaphore_Take(i2c_adapter->sem_busy, i2c_adapter->cfg->transfer_timeout_ms) == false) { +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(0); +#endif /*I2C_HALT_ON_ERRORS*/ + return -2; + } + + i2c_adapter->bus_error = false; + + state->addr = txn_list[0].addr << 1; + state->reg = txn_list[0].buf[0]; + + // Reading + if (num_txns == 2) { + state->dir = I2C_Direction_Receiver; + state->buf_p = txn_list[1].buf; // buf + state->bytes = txn_list[1].len; // len + } + // Writing + else if (num_txns == 1) { + state->dir = I2C_Direction_Transmitter; + state->buf_p = &(txn_list[0].buf[1]); // buf + state->bytes = txn_list[0].len - 1; // len + } + + state->busy = true; + + PIOS_DEBUG_Assert(!(i2c_adapter->cfg->regs->CR2 & I2C_IT_EVT)); + PIOS_DEBUG_Assert(!(i2c_adapter->cfg->regs->CR1 & 0x0100)); + + // wait for any stop to finish sending + while (i2c_adapter->cfg->regs->CR1 & 0x0200) { + PIOS_DELAY_WaituS(10); + } + + // send the start for the new job + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); + + // allow the interrupts to fire off again + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_ERR, ENABLE); + + uint32_t timeout = I2C_DEFAULT_TIMEOUT; + while (state->busy && --timeout > 0); + if (timeout == 0) { + state->error_count++; + // reinit peripheral + clock out garbage + i2c_adapter_fsm_init(i2c_adapter); +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(0); +#endif /*I2C_HALT_ON_ERRORS*/ + } + +#if defined(I2C_HALT_ON_ERRORS) + PIOS_DEBUG_Assert(!i2c_adapter->bus_error); +#endif + + PIOS_Semaphore_Give(i2c_adapter->sem_busy); + + return (timeout == 0) ? -2 : + i2c_adapter->bus_error ? -1 : + 0; +} + +/** + * @brief Check the I2C bus is clear and in a properly reset state + * @returns 0 Bus is clear + * @returns -1 Bus is in use + * @returns -2 Bus not clear + */ +int32_t PIOS_I2C_CheckClear(uint32_t i2c_id) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid) + + if (PIOS_Semaphore_Take(i2c_adapter->sem_busy, 0) == false) + return -1; + + PIOS_Semaphore_Give(i2c_adapter->sem_busy); + + return 0; +} +/* + * + * + */ +void PIOS_I2C_EV_IRQ_Handler(uint32_t i2c_id) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid); + + struct i2c_internal_state* state = (struct i2c_internal_state*)i2c_adapter->active_txn; + + uint8_t SReg_1 = i2c_adapter->cfg->regs->SR1; //read the status register here + + if (SReg_1 & 0x0001) { //we just sent a start - EV5 in ref manual + i2c_adapter->cfg->regs->CR1 &= ~0x0800; //reset the POS bit so ACK/NACK applied to the current byte + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, ENABLE); //make sure ACK is on + state->index = 0; //reset the index + if ((state->dir == I2C_Direction_Receiver) && (state->subaddress_sent || 0xFF == state->reg)) { //we have sent the subaddr + state->subaddress_sent = 1; //make sure this is set in case of no subaddress, so following code runs correctly + if (state->bytes == 2) + i2c_adapter->cfg->regs->CR1 |= 0x0800; //set the POS bit so NACK applied to the final byte in the two byte read + I2C_Send7bitAddress(i2c_adapter->cfg->regs, state->addr, I2C_Direction_Receiver); //send the address and set hardware mode + } else { //direction is Tx, or we havent sent the sub and rep start + I2C_Send7bitAddress(i2c_adapter->cfg->regs, state->addr, I2C_Direction_Transmitter); //send the address and set hardware mode + if (state->reg != 0xFF) //0xFF as subaddress means it will be ignored, in Tx or Rx mode + state->index = -1; //send a subaddress + } + } else if (SReg_1 & 0x0002) { //we just sent the address - EV6 in ref manual + // Read SR1,2 to clear ADDR + __DMB(); // memory fence to control hardware + if (state->bytes == 1 && (state->dir == I2C_Direction_Receiver) && state->subaddress_sent) { // we are receiving 1 byte - EV6_3 + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); // turn off ACK + __DMB(); + (void)i2c_adapter->cfg->regs->SR2; // clear ADDR after ACK is turned off + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); // program the stop + state->final_stop = true; + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, ENABLE); // allow us to have an EV7 + } else { // EV6 and EV6_1 + (void)i2c_adapter->cfg->regs->SR2; // clear the ADDR here + __DMB(); + if (state->bytes == 2 && (state->dir == I2C_Direction_Receiver) && state->subaddress_sent) { //rx 2 bytes - EV6_1 + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); //turn off ACK + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to fill + } else if (state->bytes == 3 && (state->dir == I2C_Direction_Receiver) && state->subaddress_sent) //rx 3 bytes + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); //make sure RXNE disabled so we get a BTF in two bytes time + else //receiving greater than three bytes, sending subaddress, or transmitting + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, ENABLE); + } + } else if (SReg_1 & 0x004) { //Byte transfer finished - EV7_2, EV7_3 or EV8_2 + state->final_stop = true; + if ((state->dir == I2C_Direction_Receiver) && state->subaddress_sent) { //EV7_2, EV7_3 + if (state->bytes > 2) { //EV7_2 + I2C_AcknowledgeConfig(i2c_adapter->cfg->regs, DISABLE); //turn off ACK + state->buf_p[state->index++] = I2C_ReceiveData(i2c_adapter->cfg->regs); //read data N-2 + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); //program the Stop + state->final_stop = true; //reuired to fix hardware + state->buf_p[state->index++] = I2C_ReceiveData(i2c_adapter->cfg->regs); //read data N-1 + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, ENABLE); //enable TXE to allow the final EV7 + } else { //EV7_3 + if (state->final_stop) + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); //program the Stop + else + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); //program a rep start + state->buf_p[state->index++] = I2C_ReceiveData(i2c_adapter->cfg->regs); //read data N-1 + state->buf_p[state->index++] = I2C_ReceiveData(i2c_adapter->cfg->regs); //read data N + state->index++; //to show job completed + } + } else { //EV8_2, which may be due to a subaddress sent or a write completion + if (state->subaddress_sent || ((state->dir == I2C_Direction_Transmitter))) { + if (state->final_stop) + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); //program the Stop + else + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); //program a rep start + state->index++; //to show that the job is complete + } else { //We need to send a subaddress + I2C_GenerateSTART(i2c_adapter->cfg->regs, ENABLE); //program the repeated Start + state->subaddress_sent = true; //this is set back to zero upon completion of the current task + } + } + //we must wait for the start to clear, otherwise we get constant BTF + while (i2c_adapter->cfg->regs->CR1 & 0x0100) { ; } + } else if (SReg_1 & 0x0040) { //Byte received - EV7 + state->buf_p[state->index++] = I2C_ReceiveData(i2c_adapter->cfg->regs); + if (state->bytes == (state->index + 3)) + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush so we can get an EV7_2 + if (state->bytes == state->index) //We have completed a final EV7 + state->index++; //to show job is complete + } else if (SReg_1 & 0x0080) { //Byte transmitted -EV8/EV8_1 + if (state->index != -1) { //we dont have a subaddress to send + I2C_SendData(i2c_adapter->cfg->regs, state->buf_p[state->index++]); + if (state->bytes == state->index) //we have sent all the data + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush + } else { + state->index++; + I2C_SendData(i2c_adapter->cfg->regs, state->reg); //send the subaddress + if ((state->dir == I2C_Direction_Receiver) || !state->bytes) //if receiving or sending 0 bytes, flush now + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); //disable TXE to allow the buffer to flush + } + } + if (state->index == state->bytes + 1) { //we have completed the current job + //Completion Tasks go here + //End of completion tasks + state->subaddress_sent = false; //reset this here + // i2c_adapter->cfg->regs->CR1 &= ~0x0800; //reset the POS bit so NACK applied to the current byte + if (state->final_stop) //If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_ERR, DISABLE); //Disable EVT and ERR interrupts while bus inactive + state->busy = false; + } +} + +/* + * + * + */ +void PIOS_I2C_ER_IRQ_Handler(uint32_t i2c_id) +{ + struct pios_i2c_adapter * i2c_adapter = (struct pios_i2c_adapter *)i2c_id; + + bool valid = PIOS_I2C_validate(i2c_adapter); + PIOS_Assert(valid); + + struct i2c_internal_state* state = (struct i2c_internal_state*)i2c_adapter->active_txn; + + volatile uint32_t SR1Register; + // Read the I2C1 status register + SR1Register = i2c_adapter->cfg->regs->SR1; + if (SR1Register & 0x0F00) { //an error + i2c_adapter->bus_error = true; + // I2C1error.error = ((SR1Register & 0x0F00) >> 8); //save error + // I2C1error.job = job; //the task + } + // If AF, BERR or ARLO, abandon the current job and commence new if there are jobs + if (SR1Register & 0x0700) { + (void)i2c_adapter->cfg->regs->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK) + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully) + if (!(SR1Register & 0x0200) && !(i2c_adapter->cfg->regs->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop + if (i2c_adapter->cfg->regs->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start,stop will hang the peripheral + while (i2c_adapter->cfg->regs->CR1 & 0x0100); // wait for any start to finish sending + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); // send stop to finalise bus transaction + while (i2c_adapter->cfg->regs->CR1 & 0x0200); // wait for stop to finish sending + i2c_adapter_fsm_init(i2c_adapter); // reset and configure the hardware + } else { + I2C_GenerateSTOP(i2c_adapter->cfg->regs, ENABLE); // stop to free up the bus + I2C_ITConfig(i2c_adapter->cfg->regs, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive + } + } + } + i2c_adapter->cfg->regs->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt + state->busy = false; +} + +#endif + +/** + * @} + * @} + */ diff --git a/flight/PiOS/STM32F10x/pios_tim.c b/flight/PiOS/STM32F10x/pios_tim.c index 283b026dab3..42498522704 100644 --- a/flight/PiOS/STM32F10x/pios_tim.c +++ b/flight/PiOS/STM32F10x/pios_tim.c @@ -137,7 +137,7 @@ int32_t PIOS_TIM_InitChannels(uintptr_t * tim_id, const struct pios_tim_channel RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); break; case (uint32_t) GPIOC: - RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOB, ENABLE); + RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOC, ENABLE); break; default: PIOS_Assert(0); diff --git a/flight/PiOS/STM32F10x/startup_stm32f10x_MD_NZ.S b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_NZ.S new file mode 100644 index 00000000000..fcf6ed3497a --- /dev/null +++ b/flight/PiOS/STM32F10x/startup_stm32f10x_MD_NZ.S @@ -0,0 +1,511 @@ +/** + ****************************************************************************** + * @file startup_stm32f10x_md.s + * @author MCD Application Team, Angus Peart, Michael Corcoran + * @version V3.5.0 + * @date 11-March-2011 + * @brief STM32F10x Medium Density Devices vector table for RIDE7 toolchain. + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Check backup registers and branch to ST bootloader if desired + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M3 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS + * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE + * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY + * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING + * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * + *

© COPYRIGHT 2011 STMicroelectronics

+ ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m3 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global xPortIncreaseHeapSize +.global Stack_Change + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss + +.equ BootRAM, 0xF108F85F +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + +.equ RCC_APB1ENR, 0x4002101C +.equ PWR_BKP_EN, 0x18000000 +.equ PWR_CR, 0x40007000 +.equ BKP_DR, 0x40006C04 +.equ MAGIC_1, 0x1122 +.equ MAGIC_2, 0xAA55 + +/* +* Check backup registers for magic values set by +* IAP module. If correct values are found, branch +* to STMicro bootloader (in ROM). +*/ + +/* Enable power and backup interface clocks */ + ldr r0, =RCC_APB1ENR + ldr r1, =PWR_BKP_EN + str r1, [r0] + +/* Enable backup register writes + reset value is 0 */ + ldr r0, =PWR_CR + mov r1, 0x0100 // DBP + str r1, [r0] + + mov r2, 0 // used to blank backup registers after read + ldr r3, =MAGIC_1 + ldr r4, =MAGIC_2 + +/* check (and clear) magic word 1 */ + ldr r0, =BKP_DR + ldr r1, [r0, #0] // BKP_DR1 + str r2, [r0, #0] // BKP_DR1 + cmp r1, r3 + bne InitStack + +/* check (and clear) magic word 2 */ + ldr r1, [r0, #4] // BKP_DR2 + str r2, [r0, #4] // BKP_DR2 + cmp r1, r4 + bne InitStack + +EnterDFU: + +.equ RCC_APB2ENR, 0x40021018 +.equ AFIO_MAPR, 0x40010004 +.equ GPIOB, 0x40010C00 +.equ GPIO_LED_CFG, 0x44422444 // PB 3 & 4 = O/P +.equ GPIO_LED_PINS,0x00000018 +.equ ST_BOOTLOADER,0x1FFFF000 + +/* + * First set the green and red LEDs on + * to indicate bootloader mode to user, + * then jump to STMicro bootloader +*/ + +/* enable GPIOB and AFIO clocks */ + ldr r0, =RCC_APB2ENR + mov r1, 0x00000009 + str r1, [r0] + +/* remap JTAG pins to GPIOs */ + ldr r0, =AFIO_MAPR + mov r1, 0x02000000 // JTAG disabled, SWD enabled + str r1, [r0] + +/* set LEDs as low outputs */ + ldr r0, =GPIOB + ldr r1, =GPIO_LED_CFG + str r1, [r0, #0] // GPIOB_CRL + ldr r1, =GPIO_LED_PINS + str r1, [r0, #20] // GPIOB_BRR + +/* branch to STMicro bootloader in ROM */ + ldr r0, =ST_BOOTLOADER + ldr sp, [r0, #0] + ldr r0, [r0, #4] + bx r0 + +InitStack: +/* + * From COrtex-M3 reference manual: + * - Handler IRQ always use SP_main + * - Process use SP_main or SP_process + * Here, we will use beginning of SRAM for IRQ (SP_main) + * and end of heap for initialization (SP_process). + * Once the schedule starts, all threads will use their own stack + * from heap and NOBOBY should use SP_process again. + */ + /* Do set/reset the stack pointers */ + LDR r0, =_irq_stack_top + MSR msp, r0 + LDR r2, =_init_stack_top + MSR psp, r2 + /* check if irq and init stack are the same */ + /* if they are, we don't do stack swap */ + /* and lets bypass the monitoring as well for now */ + cmp r0, r2 + beq SectionBssInit +/* DO + * - stay in thread process mode + * - stay in privilege level + * - use process stack + */ + movs r0, #2 + MSR control, r0 + ISB +/* Fill IRQ stack for watermark monitoring */ + ldr r2, =_irq_stack_end + b LoopFillIRQStack + +FillIRQStack: + movw r3, #0xA5A5 + str r3, [r2], #4 + +LoopFillIRQStack: + ldr r3, = _irq_stack_top + cmp r2, r3 + bcc FillIRQStack + +SectionBssInit: +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss +/* Call the application's entry point.*/ + bl main +/* will never return here */ + bx lr + +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that swaps stack (from end of heap to irq_stack). + * Also reclaim the heap that was used as a stack. + * @param None + * @retval : None +*/ + .section .text.Stack_Change + .weak Stack_Change + .type Stack_Change, %function +Stack_Change: + mov r4, lr +/* Switches stack back momentarily to MSP */ + movs r0, #0 + msr control, r0 +Heap_Reclaim: +/* add heap_post_rtos to the heap (if the capability/function exist) */ +/* Also claim the unused memory (between end of heap to end of memory */ +/* CAREFULL: the heap section must be the last section in RAM in order this to work */ + ldr r0, = _init_stack_size + ldr r1, = _eheap_post_rtos + ldr r2, = _eram + subs r2, r2, r1 + adds r0, r0, r2 + bl xPortIncreaseHeapSize + bx r4 + .size Stack_Change, .-Stack_Change + + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * + * @param None + * @retval : None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +******************************************************************************/ + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word _irq_stack_top + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word vPortSVCHandler + .word DebugMon_Handler + .word 0 + .word xPortPendSVHandler + .word xPortSysTickHandler + .word WWDG_IRQHandler + .word PVD_IRQHandler + .word TAMPER_IRQHandler + .word RTC_IRQHandler + .word FLASH_IRQHandler + .word RCC_IRQHandler + .word EXTI0_IRQHandler + .word EXTI1_IRQHandler + .word EXTI2_IRQHandler + .word EXTI3_IRQHandler + .word EXTI4_IRQHandler + .word DMA1_Channel1_IRQHandler + .word DMA1_Channel2_IRQHandler + .word DMA1_Channel3_IRQHandler + .word DMA1_Channel4_IRQHandler + .word DMA1_Channel5_IRQHandler + .word DMA1_Channel6_IRQHandler + .word DMA1_Channel7_IRQHandler + .word ADC1_2_IRQHandler + .word USB_HP_CAN1_TX_IRQHandler + .word USB_LP_CAN1_RX0_IRQHandler + .word CAN1_RX1_IRQHandler + .word CAN1_SCE_IRQHandler + .word EXTI9_5_IRQHandler + .word TIM1_BRK_IRQHandler + .word TIM1_UP_IRQHandler + .word TIM1_TRG_COM_IRQHandler + .word TIM1_CC_IRQHandler + .word TIM2_IRQHandler + .word TIM3_IRQHandler + .word TIM4_IRQHandler + .word I2C1_EV_IRQHandler + .word I2C1_ER_IRQHandler + .word I2C2_EV_IRQHandler + .word I2C2_ER_IRQHandler + .word SPI1_IRQHandler + .word SPI2_IRQHandler + .word USART1_IRQHandler + .word USART2_IRQHandler + .word USART3_IRQHandler + .word EXTI15_10_IRQHandler + .word RTCAlarm_IRQHandler + .word USBWakeUp_IRQHandler + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word 0 + .word BootRAM /* @0x108. This is for boot in RAM mode for + STM32F10x Medium Density devices. */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMPER_IRQHandler + .thumb_set TAMPER_IRQHandler,Default_Handler + + .weak RTC_IRQHandler + .thumb_set RTC_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Channel1_IRQHandler + .thumb_set DMA1_Channel1_IRQHandler,Default_Handler + + .weak DMA1_Channel2_IRQHandler + .thumb_set DMA1_Channel2_IRQHandler,Default_Handler + + .weak DMA1_Channel3_IRQHandler + .thumb_set DMA1_Channel3_IRQHandler,Default_Handler + + .weak DMA1_Channel4_IRQHandler + .thumb_set DMA1_Channel4_IRQHandler,Default_Handler + + .weak DMA1_Channel5_IRQHandler + .thumb_set DMA1_Channel5_IRQHandler,Default_Handler + + .weak DMA1_Channel6_IRQHandler + .thumb_set DMA1_Channel6_IRQHandler,Default_Handler + + .weak DMA1_Channel7_IRQHandler + .thumb_set DMA1_Channel7_IRQHandler,Default_Handler + + .weak ADC1_2_IRQHandler + .thumb_set ADC1_2_IRQHandler,Default_Handler + + .weak USB_HP_CAN1_TX_IRQHandler + .thumb_set USB_HP_CAN1_TX_IRQHandler,Default_Handler + + .weak USB_LP_CAN1_RX0_IRQHandler + .thumb_set USB_LP_CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_IRQHandler + .thumb_set TIM1_BRK_IRQHandler,Default_Handler + + .weak TIM1_UP_IRQHandler + .thumb_set TIM1_UP_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_IRQHandler + .thumb_set TIM1_TRG_COM_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTCAlarm_IRQHandler + .thumb_set RTCAlarm_IRQHandler,Default_Handler + + .weak USBWakeUp_IRQHandler + .thumb_set USBWakeUp_IRQHandler,Default_Handler + + diff --git a/flight/PiOS/STM32F30x/pios_brushless.c b/flight/PiOS/STM32F30x/pios_brushless.c index 4648330a7a2..639c5abd225 100644 --- a/flight/PiOS/STM32F30x/pios_brushless.c +++ b/flight/PiOS/STM32F30x/pios_brushless.c @@ -34,7 +34,6 @@ #include "pios_thread.h" #include "physical_constants.h" -#include "sin_lookup.h" #include "misc_math.h" /* Private Function Prototypes */ diff --git a/flight/PiOS/STM32F30x/pios_dsm.c b/flight/PiOS/STM32F30x/pios_dsm.c deleted file mode 100644 index f5c30388fdf..00000000000 --- a/flight/PiOS/STM32F30x/pios_dsm.c +++ /dev/null @@ -1,424 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup PIOS PIOS Core hardware abstraction layer - * @{ - * @addtogroup PIOS_DSM Spektrum/JR DSMx satellite receiver functions - * @brief Code to bind and read Spektrum/JR DSMx satellite receiver serial stream - * @{ - * - * @file pios_dsm.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 - * @brief Code bind and read Spektrum/JR DSMx satellite receiver serial stream - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Project Includes */ -#include "pios.h" -#include "pios_dsm_priv.h" - -#if defined(PIOS_INCLUDE_DSM) - -#if !defined(PIOS_INCLUDE_RTC) -#error PIOS_INCLUDE_RTC must be used to use DSM -#endif - -/* Forward Declarations */ -static int32_t PIOS_DSM_Get(uintptr_t rcvr_id, uint8_t channel); -static uint16_t PIOS_DSM_RxInCallback(uintptr_t context, - uint8_t *buf, - uint16_t buf_len, - uint16_t *headroom, - bool *need_yield); -static void PIOS_DSM_Supervisor(uintptr_t dsm_id); - -/* Local Variables */ -const struct pios_rcvr_driver pios_dsm_rcvr_driver = { - .read = PIOS_DSM_Get, -}; - -enum dsm_resolution { - DSM_UNKNOWN, DSM_10BIT, DSM_11BIT -}; - -enum pios_dsm_dev_magic { - PIOS_DSM_DEV_MAGIC = 0x44534d78, -}; - -struct pios_dsm_state { - uint16_t channel_data[PIOS_DSM_NUM_INPUTS]; - uint8_t received_data[DSM_FRAME_LENGTH]; - uint8_t receive_timer; - uint8_t failsafe_timer; - uint8_t frame_found; - uint8_t byte_count; -#ifdef DSM_LOST_FRAME_COUNTER - uint8_t frames_lost_last; - uint16_t frames_lost; -#endif -}; - -struct pios_dsm_dev { - enum pios_dsm_dev_magic magic; - const struct pios_dsm_cfg *cfg; - struct pios_dsm_state state; - enum dsm_resolution resolution; -}; - -/* Allocate DSM device descriptor */ -static struct pios_dsm_dev *PIOS_DSM_Alloc(void) -{ - struct pios_dsm_dev *dsm_dev; - - dsm_dev = (struct pios_dsm_dev *)PIOS_malloc(sizeof(*dsm_dev)); - if (!dsm_dev) - return NULL; - - dsm_dev->resolution = DSM_UNKNOWN; - dsm_dev->magic = PIOS_DSM_DEV_MAGIC; - return dsm_dev; -} - -/* Validate DSM device descriptor */ -static bool PIOS_DSM_Validate(struct pios_dsm_dev *dsm_dev) -{ - return (dsm_dev->magic == PIOS_DSM_DEV_MAGIC); -} - -/* Try to bind DSMx satellite using specified number of pulses */ -static void PIOS_DSM_Bind(struct pios_dsm_dev *dsm_dev, uint8_t bind) -{ - const struct pios_dsm_cfg *cfg = dsm_dev->cfg; - - GPIO_InitTypeDef GPIO_InitStructure = cfg->bind.init; - GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; - - /* just to limit bind pulses */ - if (bind > 10) - bind = 10; - - GPIO_Init(cfg->bind.gpio, (GPIO_InitTypeDef*)&cfg->bind.init); - - /* RX line, set high */ - GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - - /* on CC works up to 140ms, guess bind window is around 20-140ms after power up */ - while (((float) PIOS_DELAY_GetRaw() / (float) PIOS_SYSCLK) < 0.02f); - - for (int i = 0; i < bind ; i++) { - /* RX line, drive low for 120us */ - GPIO_ResetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - PIOS_DELAY_WaituS(120); - /* RX line, drive high for 120us */ - GPIO_SetBits(cfg->bind.gpio, cfg->bind.init.GPIO_Pin); - PIOS_DELAY_WaituS(120); - } - /* RX line, set input and wait for data */ - GPIO_Init((GPIO_TypeDef*)cfg->bind.gpio, &GPIO_InitStructure); -} - -/* Reset channels in case of lost signal or explicit failsafe receiver flag */ -static void PIOS_DSM_ResetChannels(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - for (int i = 0; i < PIOS_DSM_NUM_INPUTS; i++) { - state->channel_data[i] = PIOS_RCVR_TIMEOUT; - } -} - -/* Reset DSM receiver state */ -static void PIOS_DSM_ResetState(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - state->receive_timer = 0; - state->failsafe_timer = 0; - state->frame_found = 0; -#ifdef DSM_LOST_FRAME_COUNTER - state->frames_lost_last = 0; - state->frames_lost = 0; -#endif - PIOS_DSM_ResetChannels(dsm_dev); -} - -/** - * DSM Resolution Detection: - * Satellite RX should be bound as master RX (Odd number of binding pulses), - * then transmitter information byte will be used to determine DSM resolution. - * If bound as slave RX, routine will fall back to looking at channel order to - * determine DSM resolution. It should be noted that the channel order method - * does not work with all Spektrum system configurations. - */ -enum dsm_resolution PIOS_DSM_DetectResolution(uint8_t *packet) -{ - uint8_t channel0, channel1; - uint16_t word0, word1; - bool bit_10, bit_11; - - // Form data words - word0 = ((uint16_t)packet[2] << 8) | packet[3]; - word1 = ((uint16_t)packet[4] << 8) | packet[5]; - - // Can't detect on the second data packet - if (word0 & DSM_2ND_FRAME_MASK) - return DSM_UNKNOWN; - - if (packet[1] != 0x00) // If transmitter information byte != 0, master satellite - { - if ((packet[1] & DSM_RESOLUTION_MASK) == 0x00) // Check resolution bit in transmitter information byte - return DSM_10BIT; // and set DSM resolution accordingly - else - return DSM_11BIT; - } - else // Else slave satellite - { - // Check for 10 bit - channel0 = (word0 >> 10) & 0x0f; - channel1 = (word1 >> 10) & 0x0f; - bit_10 = (channel0 == 1) && (channel1 == 5); - - // Check for 11 bit - channel0 = (word0 >> 11) & 0x0f; - channel1 = (word1 >> 11) & 0x0f; - bit_11 = (channel0 == 1) && (channel1 == 5); - - if (bit_10 && !bit_11) - return DSM_10BIT; - - if (bit_11 && !bit_10) - return DSM_11BIT; - - return DSM_UNKNOWN; - } -} - -/** - * This is the code from the PIOS_DSM layer - */ -int PIOS_DSM_UnrollChannels(struct pios_dsm_dev *dsm_dev) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - /* Fix resolution for detection. */ - -#ifdef DSM_LOST_FRAME_COUNTER - /* increment the lost frame counter */ - uint8_t frames_lost = state->received_data[0]; - state->frames_lost += (frames_lost - state->frames_lost_last); - state->frames_lost_last = frames_lost; -#endif - - // If no stream type has yet been detected, then try to probe for it - // this should only happen once per power cycle - if (dsm_dev->resolution == DSM_UNKNOWN) { - dsm_dev->resolution = PIOS_DSM_DetectResolution(state->received_data); - } - - /* Stream type still not detected */ - if (dsm_dev->resolution == DSM_UNKNOWN) { - return -2; - } - uint8_t resolution = (dsm_dev->resolution == DSM_10BIT) ? 10 : 11; - uint16_t mask = (dsm_dev->resolution == DSM_10BIT) ? 0x03ff : 0x07ff; - - /* unroll channels */ - uint8_t *s = &(state->received_data[2]); - - for (int i = 0; i < DSM_CHANNELS_PER_FRAME; i++) { - uint16_t word = ((uint16_t)s[0] << 8) | s[1]; - s += 2; - - /* skip empty channel slot */ - if (word == 0xffff) - continue; - - /* minimal data validation */ - if ((i > 0) && (word & DSM_2ND_FRAME_MASK)) { - /* invalid frame data, ignore rest of the frame */ - goto stream_error; - } - - /* extract and save the channel value */ - uint8_t channel_num = (word >> resolution) & 0x0f; - state->channel_data[channel_num] = (word & mask); - } - -#ifdef DSM_LOST_FRAME_COUNTER - /* put lost frames counter into the last channel for debugging */ - state->channel_data[PIOS_DSM_NUM_INPUTS-1] = state->frames_lost; -#endif - - /* all channels processed */ - return 0; - -stream_error: - /* either DSM2 selected with DSMX stream found, or vice-versa */ - return -1; -} - -/* Update decoder state processing input byte from the DSMx stream */ -static void PIOS_DSM_UpdateState(struct pios_dsm_dev *dsm_dev, uint8_t byte) -{ - struct pios_dsm_state *state = &(dsm_dev->state); - if (state->frame_found) { - /* receiving the data frame */ - if (state->byte_count < DSM_FRAME_LENGTH) { - /* store next byte */ - state->received_data[state->byte_count++] = byte; - if (state->byte_count == DSM_FRAME_LENGTH) { - /* full frame received - process and wait for new one */ - if (!PIOS_DSM_UnrollChannels(dsm_dev)) - /* data looking good */ - state->failsafe_timer = 0; - - /* prepare for the next frame */ - state->frame_found = 0; - } - } - } -} - -/* Initialise DSM receiver interface */ -int32_t PIOS_DSM_Init(uintptr_t *dsm_id, - const struct pios_dsm_cfg *cfg, - const struct pios_com_driver *driver, - uintptr_t lower_id, - uint8_t bind) -{ - PIOS_DEBUG_Assert(dsm_id); - PIOS_DEBUG_Assert(cfg); - PIOS_DEBUG_Assert(driver); - - struct pios_dsm_dev *dsm_dev; - - dsm_dev = (struct pios_dsm_dev *)PIOS_DSM_Alloc(); - if (!dsm_dev) - return -1; - - /* Bind the configuration to the device instance */ - dsm_dev->cfg = cfg; - - /* Bind the receiver if requested */ - if (bind) - PIOS_DSM_Bind(dsm_dev, bind); - - PIOS_DSM_ResetState(dsm_dev); - - *dsm_id = (uintptr_t)dsm_dev; - - /* Set comm driver callback */ - (driver->bind_rx_cb)(lower_id, PIOS_DSM_RxInCallback, *dsm_id); - - if (!PIOS_RTC_RegisterTickCallback(PIOS_DSM_Supervisor, *dsm_id)) { - PIOS_DEBUG_Assert(0); - } - - return 0; -} - -/* Comm byte received callback */ -static uint16_t PIOS_DSM_RxInCallback(uintptr_t context, - uint8_t *buf, - uint16_t buf_len, - uint16_t *headroom, - bool *need_yield) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)context; - - bool valid = PIOS_DSM_Validate(dsm_dev); - PIOS_Assert(valid); - - /* process byte(s) and clear receive timer */ - for (uint8_t i = 0; i < buf_len; i++) { - PIOS_DSM_UpdateState(dsm_dev, buf[i]); - dsm_dev->state.receive_timer = 0; - } - - /* Always signal that we can accept another byte */ - if (headroom) - *headroom = DSM_FRAME_LENGTH; - - /* We never need a yield */ - *need_yield = false; - - /* Always indicate that all bytes were consumed */ - return buf_len; -} - -/** - * Get the value of an input channel - * \param[in] channel Number of the channel desired (zero based) - * \output PIOS_RCVR_INVALID channel not available - * \output PIOS_RCVR_TIMEOUT failsafe condition or missing receiver - * \output >=0 channel value - */ -static int32_t PIOS_DSM_Get(uintptr_t rcvr_id, uint8_t channel) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)rcvr_id; - - if (!PIOS_DSM_Validate(dsm_dev)) - return PIOS_RCVR_INVALID; - - /* return error if channel is not available */ - if (channel >= PIOS_DSM_NUM_INPUTS) - return PIOS_RCVR_INVALID; - - /* may also be PIOS_RCVR_TIMEOUT set by other function */ - return dsm_dev->state.channel_data[channel]; -} - -/** - * Input data supervisor is called periodically and provides - * two functions: frame syncing and failsafe triggering. - * - * DSM frames come at 11ms or 22ms rate at 115200bps. - * RTC timer is running at 625Hz (1.6ms). So with divider 5 it gives - * 8ms pause between frames which is good for both DSM frame rates. - * - * Data receive function must clear the receive_timer to confirm new - * data reception. If no new data received in 100ms, we must call the - * failsafe function which clears all channels. - */ -static void PIOS_DSM_Supervisor(uintptr_t dsm_id) -{ - struct pios_dsm_dev *dsm_dev = (struct pios_dsm_dev *)dsm_id; - - bool valid = PIOS_DSM_Validate(dsm_dev); - PIOS_Assert(valid); - - struct pios_dsm_state *state = &(dsm_dev->state); - - /* waiting for new frame if no bytes were received in 8ms */ - if (++state->receive_timer > 4) { - state->frame_found = 1; - state->byte_count = 0; - state->receive_timer = 0; - } - - /* activate failsafe if no frames have arrived in 102.4ms */ - if (++state->failsafe_timer > 64) { - PIOS_DSM_ResetChannels(dsm_dev); - state->failsafe_timer = 0; - } -} - -#endif /* PIOS_INCLUDE_DSM */ - -/** - * @} - * @} - */ diff --git a/flight/PiOS/STM32F30x/pios_i2c.c b/flight/PiOS/STM32F30x/pios_i2c.c index 560c4259fb7..45e45b5a802 100644 --- a/flight/PiOS/STM32F30x/pios_i2c.c +++ b/flight/PiOS/STM32F30x/pios_i2c.c @@ -293,6 +293,10 @@ static void i2c_adapter_fsm_init(struct pios_i2c_adapter *i2c_adapter) static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter) { + uint8_t retry_count = 0; + uint8_t retry_count_clk = 0; + static const uint8_t MAX_I2C_RETRY_COUNT = 10; + /* Reset the I2C block */ I2C_DeInit(i2c_adapter->cfg->regs); @@ -312,14 +316,17 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter) /* Check SDA line to determine if slave is asserting bus and clock out if so, this may */ /* have to be repeated (due to further bus errors) but better than clocking 0xFF into an */ /* ESC */ - //bool sda_hung = GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET; - while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET) { - + + retry_count_clk = 0; + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) == Bit_RESET && (retry_count_clk++ < MAX_I2C_RETRY_COUNT)) { + retry_count = 0; /* Set clock high and wait for any clock stretching to finish. */ GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); - while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET); + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) + PIOS_DELAY_WaituS(1); + PIOS_DELAY_WaituS(2); - + /* Set clock low */ GPIO_ResetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); PIOS_DELAY_WaituS(2); @@ -340,10 +347,15 @@ static void i2c_adapter_reset_bus(struct pios_i2c_adapter *i2c_adapter) /* Set data and clock high and wait for any clock stretching to finish. */ GPIO_SetBits(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin); GPIO_SetBits(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin); - while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET); + + retry_count = 0; + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->scl.gpio, i2c_adapter->cfg->scl.init.GPIO_Pin) == Bit_RESET && (retry_count++ < MAX_I2C_RETRY_COUNT)) + PIOS_DELAY_WaituS(1); + /* Wait for data to be high */ - while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET); - + retry_count = 0; + while (GPIO_ReadInputDataBit(i2c_adapter->cfg->sda.gpio, i2c_adapter->cfg->sda.init.GPIO_Pin) != Bit_SET && (retry_count++ < MAX_I2C_RETRY_COUNT)) + PIOS_DELAY_WaituS(1); /* Bus signals are guaranteed to be high (ie. free) after this point */ /* Initialize the GPIO pins to the peripheral function */ diff --git a/flight/PiOS/inc/pios_dsm_priv.h b/flight/PiOS/inc/pios_dsm_priv.h index 9a1f677def0..91fee9d5891 100644 --- a/flight/PiOS/inc/pios_dsm_priv.h +++ b/flight/PiOS/inc/pios_dsm_priv.h @@ -37,6 +37,10 @@ #include #include +// for HwSharedDSMxModeOptions +#include +#include + /* * Currently known DSMx (DSM2, DSMJ, DSMX) satellite serial port settings: * 115200bps serial stream, 8 bits, no parity, 1 stop bit @@ -122,7 +126,7 @@ extern int32_t PIOS_DSM_Init(uintptr_t *dsm_id, const struct pios_dsm_cfg *cfg, const struct pios_com_driver *driver, uintptr_t lower_id, - uint8_t bind); + HwSharedDSMxModeOptions mode); #endif /* PIOS_DSM_PRIV_H */ diff --git a/flight/PiOS/inc/pios_hal.h b/flight/PiOS/inc/pios_hal.h new file mode 100644 index 00000000000..3041bd0419b --- /dev/null +++ b/flight/PiOS/inc/pios_hal.h @@ -0,0 +1,73 @@ +#ifndef PIOS_HAL_H +#define PIOS_HAL_H + +#include /* XXX TODO */ +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +extern uintptr_t pios_rcvr_group_map[]; + +#if defined(PIOS_INCLUDE_SBUS) || defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_HOTT) || defined(PIOS_INCLUDE_GPS) || defined(PIOS_INCLUDE_RFM22B) || defined(PIOS_INCLUDE_USB_CDC) || defined(PIOS_INCLUDE_USB_HID) || defined(PIOS_INCLUDE_MAVLINK) + +#ifndef PIOS_INCLUDE_COM +#error Options defined that require PIOS_INCLUDE_COM! +#endif + +/* This one is a slight overreach; not all of the above requires this but close */ +#ifndef PIOS_INCLUDE_USART +#error Options defined that require PIOS_INCLUDE_USART! +#endif + +#endif + +void PIOS_HAL_ConfigureCom(const struct pios_usart_cfg *usart_port_cfg, + size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uintptr_t *com_id); + +void PIOS_HAL_Panic(uint32_t led_id, int32_t code); +void PIOS_HAL_ConfigurePort(HwSharedPortTypesOptions port_type, + const struct pios_usart_cfg *usart_port_cfg, + const struct pios_com_driver *com_driver, + uint32_t *i2c_id, + const struct pios_i2c_adapter_cfg *i2c_cfg, + const struct pios_ppm_cfg *ppm_cfg, + uint32_t led_id, + /* TODO: future work to factor most of these away */ + const struct pios_usart_cfg *usart_dsm_hsum_cfg, + const struct pios_dsm_cfg *dsm_cfg, + HwSharedDSMxModeOptions dsm_mode, + const struct pios_usart_cfg *sbus_rcvr_cfg, + const struct pios_sbus_cfg *sbus_cfg, + bool sbus_toggle + ); + +void PIOS_HAL_ConfigureCDC(HwSharedUSB_VCPPortOptions port_type, + uintptr_t usb_id, + const struct pios_usb_cdc_cfg *cdc_cfg); + +void PIOS_HAL_ConfigureHID(HwSharedUSB_HIDPortOptions port_type, + uintptr_t usb_id, + const struct pios_usb_hid_cfg *hid_cfg); + +void PIOS_HAL_ConfigureRFM22B(HwSharedRadioPortOptions radio_type, + uint8_t board_type, uint8_t board_rev, + HwSharedMaxRfPowerOptions max_power, + HwSharedMaxRfSpeedOptions max_speed, + const struct pios_openlrs_cfg *openlrs_cfg, + const struct pios_rfm22b_cfg *rfm22b_cfg, + uint8_t min_chan, uint8_t max_chan, uint32_t coord_id, + int status_inst); + +#endif diff --git a/flight/PiOS/inc/pios_mpu60x0.h b/flight/PiOS/inc/pios_mpu60x0.h index e5d7a6c3e9c..e0103897c63 100644 --- a/flight/PiOS/inc/pios_mpu60x0.h +++ b/flight/PiOS/inc/pios_mpu60x0.h @@ -8,7 +8,7 @@ * * @file PIOS_MPU60X0.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief MPU60X0 3-axis gyor function headers * @see The GNU Public License (GPL) Version 3 * @@ -88,6 +88,7 @@ #define PIOS_MPU60X0_INT_OPEN 0x40 #define PIOS_MPU60X0_INT_LATCH_EN 0x20 #define PIOS_MPU60X0_INT_CLR_ANYRD 0x10 +#define PIOS_MPU60X0_INT_I2C_BYPASS_EN 0x02 #define PIOS_MPU60X0_INTEN_OVERFLOW 0x10 #define PIOS_MPU60X0_INTEN_DATA_RDY 0x01 diff --git a/flight/PiOS/inc/pios_ms5611_priv.h b/flight/PiOS/inc/pios_ms5611_priv.h index d60d194e3d9..046119ee242 100644 --- a/flight/PiOS/inc/pios_ms5611_priv.h +++ b/flight/PiOS/inc/pios_ms5611_priv.h @@ -48,6 +48,9 @@ struct pios_ms5611_cfg { //! How many samples of pressure for each temperature measurement uint32_t temperature_interleaving; + + //! I2C address can either be 0x76 or 0x77 + uint8_t use_0x76_address; }; int32_t PIOS_MS5611_Init(const struct pios_ms5611_cfg * cfg, int32_t i2c_device); diff --git a/flight/PiOS/inc/pios_rfm22b.h b/flight/PiOS/inc/pios_rfm22b.h index 90f0a6c436e..e21e1d19742 100644 --- a/flight/PiOS/inc/pios_rfm22b.h +++ b/flight/PiOS/inc/pios_rfm22b.h @@ -33,6 +33,7 @@ #define PIOS_RFM22B_H #include +#include /* Constant definitions */ enum gpio_direction { GPIO0_TX_GPIO1_RX, GPIO0_RX_GPIO1_TX }; @@ -58,18 +59,6 @@ enum rfm22b_tx_power { RFM22_tx_pwr_txpow_7 = 0x07 // +20dBm .. 100mW }; -enum rfm22b_datarate { - RFM22_datarate_9600 = 0, - RFM22_datarate_19200 = 1, - RFM22_datarate_32000 = 2, - RFM22_datarate_57600 = 3, - RFM22_datarate_64000 = 4, - RFM22_datarate_100000 = 5, - RFM22_datarate_128000 = 6, - RFM22_datarate_192000 = 7, - RFM22_datarate_256000 = 8, -}; - typedef enum { PIOS_RFM22B_INT_FAILURE, PIOS_RFM22B_INT_SUCCESS, @@ -102,7 +91,7 @@ extern void PIOS_RFM22B_Reinit(uint32_t rfb22b_id); extern void PIOS_RFM22B_SetTxPower(uint32_t rfm22b_id, enum rfm22b_tx_power tx_pwr); extern void PIOS_RFM22B_Config(uint32_t rfm22b_id, - enum rfm22b_datarate datarate, + HwSharedMaxRfSpeedOptions datarate, uint8_t min_chan, uint8_t max_chan, uint32_t coordinator_id, bool oneway, diff --git a/flight/PiOS/inc/pios_sbus_priv.h b/flight/PiOS/inc/pios_sbus_priv.h index a2b2035958f..ed77bb6af8f 100644 --- a/flight/PiOS/inc/pios_sbus_priv.h +++ b/flight/PiOS/inc/pios_sbus_priv.h @@ -69,13 +69,6 @@ #define SBUS_R7008SB_EOF_COUNTER_MASK 0xCF #define SBUS_R7008SB_EOF_BYTE 0x04 -/* - * S.Bus protocol provides 16 proportional and 2 discrete channels. - * Do not change unless driver code is updated accordingly. - */ -#if (PIOS_SBUS_NUM_INPUTS != (16+2)) -#error "S.Bus protocol provides 16 proportional and 2 discrete channels" -#endif /* Discrete channels represented as bits, provide values for them */ #define SBUS_VALUE_MIN 352 @@ -92,6 +85,16 @@ struct pios_sbus_cfg { BitAction gpio_inv_disable; }; +/* + * S.Bus protocol provides 16 proportional and 2 discrete channels. + * Do not change unless driver code is updated accordingly. + */ +#ifdef PIOS_INCLUDE_SBUS + +#if (PIOS_SBUS_NUM_INPUTS != (16+2)) +#error "S.Bus protocol provides 16 proportional and 2 discrete channels" +#endif + extern const struct pios_rcvr_driver pios_sbus_rcvr_driver; extern int32_t PIOS_SBus_Init(uintptr_t *sbus_id, @@ -99,6 +102,9 @@ extern int32_t PIOS_SBus_Init(uintptr_t *sbus_id, const struct pios_com_driver *driver, uintptr_t lower_id); + +#endif /* PIOS_INCLUDE_SBUS */ + #endif /* PIOS_SBUS_PRIV_H */ /** diff --git a/flight/PiOS/inc/pios_usb_priv.h b/flight/PiOS/inc/pios_usb_priv.h index f345dfc4430..6e57d69f7eb 100644 --- a/flight/PiOS/inc/pios_usb_priv.h +++ b/flight/PiOS/inc/pios_usb_priv.h @@ -37,6 +37,7 @@ struct pios_usb_cfg { struct stm32_irq irq; struct stm32_gpio vsense; + struct stm32_gpio disconnect; }; extern int32_t PIOS_USB_Init(uintptr_t * usb_id, const struct pios_usb_cfg * cfg); diff --git a/flight/Project/Windows USB/TauLabs-CDC.inf b/flight/Project/Windows USB/TauLabs-CDC.inf index 3f7d078fa64..a71aeb205d4 100644 --- a/flight/Project/Windows USB/TauLabs-CDC.inf +++ b/flight/Project/Windows USB/TauLabs-CDC.inf @@ -18,6 +18,7 @@ DriverVer=10/15/2009,1.0.0.0 %Freedom%= DriverInstall,USB\VID_20A0&PID_41d0&MI_00 %Quanton%= DriverInstall,USB\VID_0fda&PID_0100&MI_00 %Sparky%= DriverInstall,USB\VID_20A0&PID_41d0&MI_00 +%AQ32%= DriverInstall,USB\VID_20A0&PID_4284&MI_00 [DeviceList.NTamd64] %CopterControl%= DriverInstall,USB\VID_20A0&PID_415b&MI_00 @@ -29,6 +30,7 @@ DriverVer=10/15/2009,1.0.0.0 %Freedom%= DriverInstall,USB\VID_20A0&PID_41d0&MI_00 %Quanton%= DriverInstall,USB\VID_0fda&PID_0100&MI_00 %Sparky%= DriverInstall,USB\VID_20A0&PID_41d0&MI_00 +%AQ32%= DriverInstall,USB\VID_20A0&PID_4284&MI_00 [DriverInstall] include=mdmcpq.inf @@ -54,3 +56,4 @@ FlyingF4 = "CDC Driver" Freedom = "CDC Driver" Quanton = "CDC Driver" Sparky = "CDC Driver" +AQ32 = "CDC Driver" diff --git a/flight/UAVObjects/inc/uavobjecttemplate.h b/flight/UAVObjects/inc/uavobjecttemplate.h index e9d113f3b23..7aa72ecc3b4 100644 --- a/flight/UAVObjects/inc/uavobjecttemplate.h +++ b/flight/UAVObjects/inc/uavobjecttemplate.h @@ -8,7 +8,7 @@ * * @file $(NAMELC).h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief Include files for the $(NAME) object. This file has been * automatically generated by the UAVObjectGenerator. * @@ -39,6 +39,7 @@ #define $(NAMEUC)_H #include "pios_queue.h" +$(PARENT_INCLUDES) // Object constants #define $(NAMEUC)_OBJID $(OBJIDHEX) diff --git a/flight/UAVObjects/uavobjecttemplate.c b/flight/UAVObjects/uavobjecttemplate.c index 76d67399867..ceaf3b36534 100644 --- a/flight/UAVObjects/uavobjecttemplate.c +++ b/flight/UAVObjects/uavobjecttemplate.c @@ -7,7 +7,7 @@ * * @file $(NAMELC).c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief Implementation of the $(NAME) object. This file has been * automatically generated by the UAVObjectGenerator. * @@ -74,7 +74,6 @@ int32_t $(NAME)Initialize(void) void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId) { $(NAME)Data data; - UAVObjMetadata metadata; // Initialize object fields to their default values UAVObjGetInstanceData(obj, instId, &data); @@ -83,17 +82,20 @@ void $(NAME)SetDefaults(UAVObjHandle obj, uint16_t instId) UAVObjSetInstanceData(obj, instId, &data); // Initialize object metadata to their default values - metadata.flags = - $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | - $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | - $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | - $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | - $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | - $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; - metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); - metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); - metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); - UAVObjSetMetadata(obj, &metadata); + if (instId == 0) { + UAVObjMetadata metadata; + metadata.flags = + $(FLIGHTACCESS) << UAVOBJ_ACCESS_SHIFT | + $(GCSACCESS) << UAVOBJ_GCS_ACCESS_SHIFT | + $(FLIGHTTELEM_ACKED) << UAVOBJ_TELEMETRY_ACKED_SHIFT | + $(GCSTELEM_ACKED) << UAVOBJ_GCS_TELEMETRY_ACKED_SHIFT | + $(FLIGHTTELEM_UPDATEMODE) << UAVOBJ_TELEMETRY_UPDATE_MODE_SHIFT | + $(GCSTELEM_UPDATEMODE) << UAVOBJ_GCS_TELEMETRY_UPDATE_MODE_SHIFT; + metadata.telemetryUpdatePeriod = $(FLIGHTTELEM_UPDATEPERIOD); + metadata.gcsTelemetryUpdatePeriod = $(GCSTELEM_UPDATEPERIOD); + metadata.loggingUpdatePeriod = $(LOGGING_UPDATEPERIOD); + UAVObjSetMetadata(obj, &metadata); + } } /** diff --git a/flight/targets/freedom/bl/pios_board.c b/flight/targets/aq32/bl/pios_board.c similarity index 84% rename from flight/targets/freedom/bl/pios_board.c rename to flight/targets/aq32/bl/pios_board.c index 0ea10b9285c..de62bae561a 100644 --- a/flight/targets/freedom/bl/pios_board.c +++ b/flight/targets/aq32/bl/pios_board.c @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup TauLabsBootloader Tau Labs Bootloaders * @{ - * @addtogroup FreedomBL Tau Labs Freedom bootloader + * @addtogroup Aq32BL Aq32 bootloader * @{ * * @file pios_board.c @@ -60,34 +60,26 @@ void PIOS_Board_Init() { PIOS_LED_On(PIOS_LED_HEARTBEAT); PIOS_LED_On(PIOS_LED_ALARM); - PIOS_LED_On(PIOS_LED_LINK); - -#if defined(PIOS_INCLUDE_SPI) - /* Set up the SPI interface to the flash and rfm22b */ - if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) { - PIOS_DEBUG_Assert(0); - } -#endif /* PIOS_INCLUDE_SPI */ #if defined(PIOS_INCLUDE_FLASH) - /* Inititialize all flash drivers */ + /* Initialize all flash drivers */ PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg); -#if defined(PIOS_INCLUDE_SPI) - PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_telem_flash_id, 1, &flash_m25p_cfg); -#endif /* PIOS_INCLUDE_SPI */ - /* Register the partition table */ PIOS_FLASH_register_partition_table(pios_flash_partition_table, NELEMENTS(pios_flash_partition_table)); #endif /* PIOS_INCLUDE_FLASH */ #if defined(PIOS_INCLUDE_USB) + /* Initialize USB disconnect GPIO */ + GPIO_Init(pios_usb_main_cfg.disconnect.gpio, (GPIO_InitTypeDef*)&pios_usb_main_cfg.disconnect.init); + GPIO_SetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + /* Initialize board specific USB data */ PIOS_USB_BOARD_DATA_Init(); /* Activate the HID-only USB configuration */ PIOS_USB_DESC_HID_ONLY_Init(); - + uintptr_t pios_usb_id; PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); @@ -102,11 +94,13 @@ void PIOS_Board_Init() { #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ PIOS_USBHOOK_Activate(); - + + /* Issue USB Disconnect Pulse */ + GPIO_ResetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + + PIOS_DELAY_WaitmS(200); + + GPIO_SetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + #endif /* PIOS_INCLUDE_USB */ } - -/** - * @} - * @} - */ diff --git a/flight/targets/revolution/bl/pios_config.h b/flight/targets/aq32/bl/pios_config.h similarity index 95% rename from flight/targets/revolution/bl/pios_config.h rename to flight/targets/aq32/bl/pios_config.h index 0140330ac61..32dacc0a2b1 100644 --- a/flight/targets/revolution/bl/pios_config.h +++ b/flight/targets/aq32/bl/pios_config.h @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup TauLabsBootloader Tau Labs Bootloaders * @{ - * @addtogroup RevolutionBL Revolution bootloader + * @addtogroup Aq32BL Aq32 bootloader * @{ * * @file pios_config.h @@ -45,4 +45,6 @@ #define PIOS_INCLUDE_FLASH_INTERNAL #define PIOS_INCLUDE_FLASH_JEDEC +#define BOOTLOADER_PAUSE_DELAY 2 + #endif /* PIOS_CONFIG_H */ diff --git a/flight/targets/freedom/bl/pios_usb_board_data.c b/flight/targets/aq32/bl/pios_usb_board_data.c similarity index 91% rename from flight/targets/freedom/bl/pios_usb_board_data.c rename to flight/targets/aq32/bl/pios_usb_board_data.c index 8619f57b631..7b0ec8c5945 100644 --- a/flight/targets/freedom/bl/pios_usb_board_data.c +++ b/flight/targets/aq32/bl/pios_usb_board_data.c @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup TauLabsBootloader Tau Labs Bootloaders * @{ - * @addtogroup FreedomBL Tau Labs Freedom bootloader + * @addtogroup Aq32BL Aq32 bootloader * @{ * * @file pios_usb_board_data.c @@ -33,16 +33,13 @@ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ #include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ -static const uint8_t usb_product_id[16] = { +static const uint8_t usb_product_id[10] = { sizeof(usb_product_id), USB_DESC_TYPE_STRING, - 'F', 0, - 'r', 0, - 'e', 0, - 'e', 0, - 'd', 0, - 'o', 0, - 'm', 0, + 'A', 0, + 'Q', 0, + '3', 0, + '2', 0, }; static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { @@ -56,20 +53,17 @@ static const struct usb_string_langid usb_lang_id = { .bLangID = htousbs(USB_LANGID_ENGLISH_US), }; -static const uint8_t usb_vendor_id[24] = { +static const uint8_t usb_vendor_id[18] = { sizeof(usb_vendor_id), USB_DESC_TYPE_STRING, - 'T', 0, - 'a', 0, + 'A', 0, + 'e', 0, + 'r', 0, + 'o', 0, + 'Q', 0, 'u', 0, - 'L', 0, 'a', 0, - 'b', 0, - 's', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0, + 'd', 0, }; int32_t PIOS_USB_BOARD_DATA_Init(void) @@ -91,8 +85,3 @@ int32_t PIOS_USB_BOARD_DATA_Init(void) return 0; } - -/** - * @} - * @} - */ diff --git a/flight/targets/revolution/bl/pios_usb_board_data.h b/flight/targets/aq32/bl/pios_usb_board_data.h similarity index 91% rename from flight/targets/revolution/bl/pios_usb_board_data.h rename to flight/targets/aq32/bl/pios_usb_board_data.h index 191d1d98929..f36899deb68 100644 --- a/flight/targets/revolution/bl/pios_usb_board_data.h +++ b/flight/targets/aq32/bl/pios_usb_board_data.h @@ -2,7 +2,7 @@ ****************************************************************************** * @addtogroup TauLabsBootloader Tau Labs Bootloaders * @{ - * @addtogroup RevolutionBL Revolution bootloader + * @addtogroup Aq32BL Aq32 bootloader * @{ * * @file pios_usb_board_data.h @@ -37,8 +37,8 @@ #include "pios_usb_defs.h" /* struct usb_* */ -#define PIOS_USB_BOARD_VENDOR_ID USB_VENDOR_ID_OPENPILOT -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION +#define PIOS_USB_BOARD_VENDOR_ID 0x20a0 +#define PIOS_USB_BOARD_PRODUCT_ID 0x4284 #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(0, USB_OP_BOARD_MODE_BL) #define PIOS_USB_BOARD_SN_SUFFIX "+BL" @@ -51,3 +51,5 @@ #define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE #endif /* PIOS_USB_BOARD_DATA_H */ + + diff --git a/flight/targets/revolution/board-info/board-info.mk b/flight/targets/aq32/board-info/board-info.mk similarity index 63% rename from flight/targets/revolution/board-info/board-info.mk rename to flight/targets/aq32/board-info/board-info.mk index 9c70953430f..fa3ff4c6108 100644 --- a/flight/targets/revolution/board-info/board-info.mk +++ b/flight/targets/aq32/board-info/board-info.mk @@ -1,12 +1,11 @@ -BOARD_TYPE := 0x7F -BOARD_REVISION := 0x02 -# Previous version was 0x081, 0x082 introduces partition extensions and forced boot from bkp registers -BOOTLOADER_VERSION := 0x82 +BOARD_TYPE := 0x94 +BOARD_REVISION := 0x01 +BOOTLOADER_VERSION := 0x84 HW_TYPE := 0x00 MCU := cortex-m4 -CHIP := STM32F405RGT -BOARD := STM32F4xx_OP +CHIP := STM32F407VGT6 +BOARD := STM32F4xx_AQ32 MODEL := HD MODEL_SUFFIX := @@ -18,9 +17,8 @@ BL_BANK_BASE := 0x08000000 # Start of bootloader flash BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region (32kb) # Leave the remaining 16KB and 64KB sectors for other uses - -FW_BANK_BASE := 0x08020000 # Start of firmware flash -FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE (256kb) +FW_BANK_BASE := 0x08020000 # Start of firmware flash (128kb) +FW_BANK_SIZE := 0x00060000 # Should include FW_DESC_SIZE (384kb) FW_DESC_SIZE := 0x00000064 @@ -28,7 +26,7 @@ EE_BANK_BASE := 0x00000000 EE_BANK_SIZE := 0x00000000 EF_BANK_BASE := 0x08000000 # Start of entire flash image (usually start of bootloader as well) -EF_BANK_SIZE := 0x00060000 # Size of the entire flash image (from bootloader until end of firmware) +EF_BANK_SIZE := 0x00080000 # Size of the entire flash image (from bootloader until end of firmware) OSCILLATOR_FREQ := 8000000 SYSCLK_FREQ := 168000000 diff --git a/flight/targets/revolution/board-info/board_hw_defs.c b/flight/targets/aq32/board-info/board_hw_defs.c similarity index 57% rename from flight/targets/revolution/board-info/board_hw_defs.c rename to flight/targets/aq32/board-info/board_hw_defs.c index a5f58754567..91f53c9fe49 100644 --- a/flight/targets/revolution/board-info/board_hw_defs.c +++ b/flight/targets/aq32/board-info/board_hw_defs.c @@ -1,33 +1,33 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Revolution OpenPilot Revolution support files + * @addtogroup Aq32 Aq32 support files * @{ * - * @file board_hw_defs.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 + * @file board_hw_defs.c + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 * @brief Defines board specific static initializers for hardware for the - * Revolution board. + * AQ32 board. * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + #include #include @@ -39,25 +39,29 @@ static const struct pios_led pios_leds[] = { .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL, }, }, + .remap = 0, + .active_high = true, }, [PIOS_LED_ALARM] = { .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL, }, }, + .remap = 0, + .active_high = true, }, }; @@ -75,16 +79,19 @@ const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revisio #if defined(PIOS_INCLUDE_SPI) #include + /* SPI1 Interface - * - Used for BMA180 accelerometer + * - Used for micro sd card communications */ -void PIOS_SPI_accel_irq_handler(void); -void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); -void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_accel_irq_handler"))); -static const struct pios_spi_cfg pios_spi_accel_cfg = { + +void PIOS_SPI_sdCard_irq_handler(void); + +void DMA2_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_sdCard_irq_handler"))); + +static const struct pios_spi_cfg pios_spi_sdCard_cfg = { .regs = SPI1, .remap = GPIO_AF_SPI1, - .init = { + .init = { .SPI_Mode = SPI_Mode_Master, .SPI_Direction = SPI_Direction_2Lines_FullDuplex, .SPI_DataSize = SPI_DataSize_8b, @@ -93,25 +100,26 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = { .SPI_CRCPolynomial = 7, .SPI_CPOL = SPI_CPOL_High, .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_16, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32, }, .use_crc = false, .dma = { .irq = { - .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), - .init = { + // Note this is the stream ID that triggers interrupts (in this case RX) + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), + .init = { .NVIC_IRQChannel = DMA2_Stream0_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, - + .rx = { .channel = DMA2_Stream0, - .init = { - .DMA_Channel = DMA_Channel_3, - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI1->DR), .DMA_DIR = DMA_DIR_PeripheralToMemory, .DMA_PeripheralInc = DMA_PeripheralInc_Disable, .DMA_MemoryInc = DMA_MemoryInc_Enable, @@ -120,27 +128,27 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = { .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_Medium, .DMA_FIFOMode = DMA_FIFOMode_Disable, - /* .DMA_FIFOThreshold */ - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, .tx = { - .channel = DMA2_Stream3, - .init = { - .DMA_Channel = DMA_Channel_3, - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), + .channel = DMA2_Stream5, + .init = { + .DMA_Channel = DMA_Channel_3, + .DMA_PeripheralBaseAddr = (uint32_t) & (SPI1->DR), .DMA_DIR = DMA_DIR_MemoryToPeripheral, .DMA_PeripheralInc = DMA_PeripheralInc_Disable, .DMA_MemoryInc = DMA_MemoryInc_Enable, .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_High, + .DMA_Priority = DMA_Priority_Medium, .DMA_FIFOMode = DMA_FIFOMode_Disable, - /* .DMA_FIFOThreshold */ - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, }, @@ -151,66 +159,61 @@ static const struct pios_spi_cfg pios_spi_accel_cfg = { .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource5, }, .miso = { .gpio = GPIOA, .init = { .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource6, }, .mosi = { .gpio = GPIOA, .init = { .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource7, }, - .slave_count = 2, + .slave_count = 1, .ssel = { { - .gpio = GPIOA, + .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, - { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, - } + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + } }, }; -static uint32_t pios_spi_accel_id; -void PIOS_SPI_accel_irq_handler(void) +uint32_t pios_spi_sdCard_id; +void PIOS_SPI_sdCard_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_accel_id); + PIOS_SPI_IRQ_Handler(pios_spi_sdCard_id); } - /* SPI2 Interface - * - Used for gyro communications + * - Used for external communications */ -void PIOS_SPI_GYRO_irq_handler(void); -void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); -void DMA1_Stream4_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); -static const struct pios_spi_cfg pios_spi_gyro_cfg = { + +void PIOS_SPI_external_irq_handler(void); + +void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_external_irq_handler"))); + +static const struct pios_spi_cfg pios_spi_external_cfg = { .regs = SPI2, .remap = GPIO_AF_SPI2, .init = { @@ -222,21 +225,21 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = { .SPI_CRCPolynomial = 7, .SPI_CPOL = SPI_CPOL_High, .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32, }, .use_crc = false, .dma = { .irq = { // Note this is the stream ID that triggers interrupts (in this case RX) - .flags = (DMA_IT_TCIF3 | DMA_IT_TEIF3 | DMA_IT_HTIF3), + .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), .init = { - .NVIC_IRQChannel = DMA1_Stream3_IRQn, + .NVIC_IRQChannel = DMA1_Stream3_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, - + .rx = { .channel = DMA1_Stream3, .init = { @@ -249,11 +252,10 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = { .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, .tx = { @@ -278,62 +280,65 @@ static const struct pios_spi_cfg pios_spi_gyro_cfg = { .sclk = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_13, + .GPIO_Pin = GPIO_Pin_13, .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource13, }, .miso = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource14, }, .mosi = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource15, }, .slave_count = 1, .ssel = { { - .gpio = GPIOB, + .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, } }, }; -uint32_t pios_spi_gyro_id; -void PIOS_SPI_gyro_irq_handler(void) +uint32_t pios_spi_external_id; +void PIOS_SPI_external_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_gyro_id); + PIOS_SPI_IRQ_Handler(pios_spi_external_id); } - -#if !defined(PIOS_FLASH_ON_ACCEL) /* SPI3 Interface - * - Used for flash communications + * - Used for gyro communications */ -void PIOS_SPI_flash_irq_handler(void); -void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); -void DMA1_Stream5_IRQHandler(void) __attribute__((alias("PIOS_SPI_flash_irq_handler"))); -static const struct pios_spi_cfg pios_spi_flash_cfg = { + +void PIOS_SPI_internal_irq_handler(void); + +void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_internal_irq_handler"))); + +static const struct pios_spi_cfg pios_spi_internal_cfg = { .regs = SPI3, .remap = GPIO_AF_SPI3, .init = { @@ -345,7 +350,7 @@ static const struct pios_spi_cfg pios_spi_flash_cfg = { .SPI_CRCPolynomial = 7, .SPI_CPOL = SPI_CPOL_High, .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_32, //@ APB2 PCLK1 82MHz / 32 == 2.6MHz }, .use_crc = false, .dma = { @@ -353,13 +358,13 @@ static const struct pios_spi_cfg pios_spi_flash_cfg = { // Note this is the stream ID that triggers interrupts (in this case RX) .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), .init = { - .NVIC_IRQChannel = DMA1_Stream0_IRQn, + .NVIC_IRQChannel = DMA1_Stream0_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, - + .rx = { .channel = DMA1_Stream0, .init = { @@ -372,11 +377,10 @@ static const struct pios_spi_cfg pios_spi_flash_cfg = { .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, .tx = { @@ -392,101 +396,241 @@ static const struct pios_spi_cfg pios_spi_flash_cfg = { .DMA_Mode = DMA_Mode_Normal, .DMA_Priority = DMA_Priority_Medium, .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, + .DMA_MemoryBurst = DMA_MemoryBurst_Single, + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, }, }, }, .sclk = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_10, + .GPIO_Pin = GPIO_Pin_10, .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource10, }, .miso = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource11, }, .mosi = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, + .pin_source = GPIO_PinSource12, }, .slave_count = 1, .ssel = { { - .gpio = GPIOD, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_100MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, } }, }; -uint32_t pios_spi_flash_id; -void PIOS_SPI_flash_irq_handler(void) +uint32_t pios_spi_internal_id; +void PIOS_SPI_internal_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_internal_id); +} + +#endif /* PIOS_INCLUDE_SPI */ + +#if defined(PIOS_INCLUDE_I2C) + +#include + +void PIOS_I2C_internal_ev_irq_handler(void); +void PIOS_I2C_internal_er_irq_handler(void); + +void I2C1_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_internal_ev_irq_handler"))); +void I2C1_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_internal_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_internal_cfg = { + .regs = I2C1, + .remap = GPIO_AF_I2C1, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_UP, + }, + .pin_source = GPIO_PinSource6, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_UP, + }, + .pin_source = GPIO_PinSource7, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C1_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_internal_id; +void PIOS_I2C_internal_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_internal_id); +} + +void PIOS_I2C_internal_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_internal_id); +} + +void PIOS_I2C_external_ev_irq_handler(void); +void PIOS_I2C_external_er_irq_handler(void); + +void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_external_ev_irq_handler"))); +void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_external_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_external_cfg = { + .regs = I2C2, + .remap = GPIO_AF_I2C2, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_UP, + }, + .pin_source = GPIO_PinSource10, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_UP, + }, + .pin_source = GPIO_PinSource11, + }, + .event = { + .flags = 0, /* FIXME: check this */ + . init = { + .NVIC_IRQChannel = I2C2_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_external_id; +void PIOS_I2C_external_ev_irq_handler(void) +{ +/* Call into the generic code to handle the IRQ for this specific device */ +PIOS_I2C_EV_IRQ_Handler(pios_i2c_external_id); +} + +void PIOS_I2C_external_er_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_flash_id); + PIOS_I2C_ER_IRQ_Handler(pios_i2c_external_id); } -#endif /* PIOS_FLASH_ON_ACCEL */ -#endif /* PIOS_INCLUDE_SPI */ +#endif /* PIOS_INCLUDE_I2C */ #if defined(PIOS_INCLUDE_FLASH) #include "pios_flashfs_logfs_priv.h" static const struct flashfs_logfs_cfg flashfs_settings_cfg = { - .fs_magic = 0x99abcedf, - .arena_size = 0x00010000, /* 256 * slot size */ + .fs_magic = 0x3b1b14cf, + .arena_size = 0x00004000, /* 64 * slot size = 16K bytes = 1 sector */ .slot_size = 0x00000100, /* 256 bytes */ }; static const struct flashfs_logfs_cfg flashfs_waypoints_cfg = { - .fs_magic = 0x99abcecf, - .arena_size = 0x00010000, /* 2048 * slot size */ - .slot_size = 0x00000040, /* 64 bytes */ -}; - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) -#include "pios_flash_jedec_priv.h" - -static const struct pios_flash_jedec_cfg flash_m25p_cfg = { - .expect_manufacturer = JEDEC_MANUFACTURER_ST, - .expect_memorytype = 0x20, - .expect_capacity = 0x15, - .sector_erase = 0xD8, + .fs_magic = 0x93a566a4, + .arena_size = 0x00020000, /* 2048 * slot size = 128K bytes = 1 sector */ + .slot_size = 0x00000040, /* 64 bytes */ }; -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) #include "pios_flash_internal_priv.h" static const struct pios_flash_internal_cfg flash_internal_cfg = { }; -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ #include "pios_flash_priv.h" -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) static const struct pios_flash_sector_range stm32f4_sectors[] = { { .base_sector = 0, @@ -514,72 +658,47 @@ static const struct pios_flash_chip pios_flash_chip_internal = { .sector_blocks = stm32f4_sectors, .num_blocks = NELEMENTS(stm32f4_sectors), }; -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) -static const struct pios_flash_sector_range m25p16_sectors[] = { - { - .base_sector = 0, - .last_sector = 31, - .sector_size = FLASH_SECTOR_64KB, - }, -}; - -uintptr_t pios_external_flash_id; -static const struct pios_flash_chip pios_flash_chip_external = { - .driver = &pios_jedec_flash_driver, - .chip_id = &pios_external_flash_id, - .page_size = 256, - .sector_blocks = m25p16_sectors, - .num_blocks = NELEMENTS(m25p16_sectors), -}; -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ static const struct pios_flash_partition pios_flash_partition_table[] = { -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) { .label = FLASH_PARTITION_LABEL_BL, .chip_desc = &pios_flash_chip_internal, .first_sector = 0, .last_sector = 1, - .chip_offset = 0, - .size = (1 - 0 + 1) * FLASH_SECTOR_16KB, + .chip_offset = 0, // 0x0800 0000 + .size = (1 - 0 + 1) * FLASH_SECTOR_16KB, // 32KB + }, + + { + .label = FLASH_PARTITION_LABEL_SETTINGS, + .chip_desc = &pios_flash_chip_internal, + .first_sector = 2, + .last_sector = 3, + .chip_offset = (2 * FLASH_SECTOR_16KB), // 0x0800 8000 + .size = (3 - 2 + 1) * FLASH_SECTOR_16KB, // 32KB }, - /* NOTE: sectors 2-4 of the internal flash are currently unallocated */ + /* NOTE: sector 4 of internal flash is currently unallocated */ { .label = FLASH_PARTITION_LABEL_FW, .chip_desc = &pios_flash_chip_internal, .first_sector = 5, - .last_sector = 6, - .chip_offset = (4 * FLASH_SECTOR_16KB) + (1 * FLASH_SECTOR_64KB), - .size = (6 - 5 + 1) * FLASH_SECTOR_128KB, - }, - - /* NOTE: sectors 7-11 of the internal flash are currently unallocated */ - -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) - { - .label = FLASH_PARTITION_LABEL_SETTINGS, - .chip_desc = &pios_flash_chip_external, - .first_sector = 0, - .last_sector = 15, - .chip_offset = 0, - .size = (15 - 0 + 1) * FLASH_SECTOR_64KB, + .last_sector = 7, + .chip_offset = (4 * FLASH_SECTOR_16KB) + (1 * FLASH_SECTOR_64KB), // 0x0802 0000 + .size = (7 - 5 + 1) * FLASH_SECTOR_128KB, // 384KB }, + /* NOTE: sectors 8-9 of the internal flash are currently unallocated */ + { .label = FLASH_PARTITION_LABEL_WAYPOINTS, - .chip_desc = &pios_flash_chip_external, - .first_sector = 16, - .last_sector = 31, - .chip_offset = (16 * FLASH_SECTOR_64KB), - .size = (31 - 16 + 1) * FLASH_SECTOR_64KB, - }, -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ + .chip_desc = &pios_flash_chip_internal, + .first_sector = 10, + .last_sector = 11, + .chip_offset = (4 * FLASH_SECTOR_16KB) + (1 * FLASH_SECTOR_64KB) + (5 * FLASH_SECTOR_128KB), // 0x080C 0000 + .size = (11 - 10 + 1) * FLASH_SECTOR_128KB, // 256KB + }, }; const struct pios_flash_partition * PIOS_BOARD_HW_DEFS_GetPartitionTable (uint32_t board_revision, uint32_t * num_partitions) @@ -592,494 +711,356 @@ const struct pios_flash_partition * PIOS_BOARD_HW_DEFS_GetPartitionTable (uint32 #endif /* PIOS_INCLUDE_FLASH */ -#if defined(PIOS_OVERO_SPI) -/* SPI3 Interface - * - Used for flash communications +#if defined(PIOS_INCLUDE_USART) + +#include "pios_usart_priv.h" + +#if defined(PIOS_INCLUDE_DSM) +/* + * Spektrum/JR DSM USART */ -#include -void PIOS_OVERO_irq_handler(void); -void DMA1_Stream7_IRQHandler(void) __attribute__((alias("PIOS_OVERO_irq_handler"))); -static const struct pios_overo_cfg pios_overo_cfg = { - .regs = SPI3, - .remap = GPIO_AF_SPI3, - .init = { - .SPI_Mode = SPI_Mode_Slave, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Hard, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case TX) - .flags = (DMA_IT_TCIF7), - .init = { - .NVIC_IRQChannel = DMA1_Stream7_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Stream0, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream7, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOC, +#include + +static const struct pios_dsm_cfg pios_usart4_dsm_aux_cfg = { + .bind = { + .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL + .GPIO_PuPd = GPIO_PuPd_NOPULL }, }, - .mosi = { +}; + +static const struct pios_dsm_cfg pios_usart6_dsm_aux_cfg = { + .bind = { .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - } }, + }, }; -uintptr_t pios_overo_id = 0; -void PIOS_OVERO_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_OVERO_DMA_irq_handler(pios_overo_id); -} -#else - -#endif /* PIOS_OVERO_SPI */ - - +#endif /* PIOS_INCLUDE_DSM */ +#if defined(PIOS_INCLUDE_HSUM) +/* + * Graupner HoTT SUMD/SUMH USART + */ +#include -#include +#endif /* PIOS_INCLUDE_HSUM */ -#ifdef PIOS_INCLUDE_COM_TELEM +#if (defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_HSUM)) /* - * Telemetry on main USART + * Spektrum/JR DSM or Graupner HoTT SUMD/SUMH USART */ -static const struct pios_usart_cfg pios_usart_telem_cfg = { - .regs = USART2, - .remap = GPIO_AF_USART2, + +static const struct pios_usart_cfg pios_usart3_dsm_hsum_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, }, .irq = { .init = { - .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannel = USART3_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_5, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource9, }, }; -#endif /* PIOS_COM_TELEM */ - -#ifdef PIOS_INCLUDE_GPS -/* - * GPS USART - */ -static const struct pios_usart_cfg pios_usart_gps_cfg = { - .regs = USART1, - .remap = GPIO_AF_USART1, +static const struct pios_usart_cfg pios_usart4_dsm_hsum_cfg = { + .regs = UART4, + .remap = GPIO_AF_UART4, .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, }, .irq = { .init = { - .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannel = UART4_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_10, + .GPIO_Pin = GPIO_Pin_1, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource1, }, - .tx = { - .gpio = GPIOA, +}; + +static const struct pios_usart_cfg pios_usart6_dsm_hsum_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { .init = { - .GPIO_Pin = GPIO_Pin_9, + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_7, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource7, }, }; -#endif /* PIOS_INCLUDE_GPS */ +#endif /* PIOS_INCLUDE_DSM || PIOS_INCLUDE_HSUM */ -#ifdef PIOS_INCLUDE_COM_AUX +#if defined(PIOS_INCLUDE_SBUS) /* - * AUX USART (UART label on rev2) + * S.Bus USART */ -static const struct pios_usart_cfg pios_usart_aux_cfg = { - .regs = USART6, - .remap = GPIO_AF_USART6, +#include + +static const struct pios_usart_cfg pios_usart3_sbus_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + .USART_BaudRate = 100000, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_Even, + .USART_StopBits = USART_StopBits_2, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, }, .irq = { .init = { - .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannel = USART3_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, }, .rx = { - .gpio = GPIOC, + .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_7, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource9, }, - .tx = { - .gpio = GPIOC, +}; + +static const struct pios_sbus_cfg pios_usart3_sbus_aux_cfg = { + /* Inverter configuration */ + .inv = { + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_6, + .GPIO_Pin = GPIO_Pin_12, .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, + .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, }, + .gpio_inv_enable = Bit_SET, }; -#endif /* PIOS_COM_AUX */ +#endif /* PIOS_INCLUDE_SBUS */ -#ifdef PIOS_INCLUDE_COM_AUXSBUS -/* - * AUX USART SBUS ( UART/ S Bus label on rev2) - */ -static const struct pios_usart_cfg pios_usart_auxsbus_cfg = { - .regs = UART4, - .remap = GPIO_AF_UART4, +static const struct pios_usart_cfg pios_usart1_cfg = { + .regs = USART1, + .remap = GPIO_AF_USART1, .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { .init = { - .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannel = USART1_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_1, + .GPIO_Pin = GPIO_Pin_10, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource10, }, .tx = { .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_0, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource9, }, }; -#endif /* PIOS_INCLUDE_COM_AUXSBUS */ - -#ifdef PIOS_INCLUDE_COM_FLEXI -/* - * FLEXI PORT - */ -static const struct pios_usart_cfg pios_usart_flexi_cfg = { - .regs = USART3, - .remap = GPIO_AF_USART3, +static const struct pios_usart_cfg pios_usart2_cfg = { + .regs = USART2, + .remap = GPIO_AF_USART2, .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { .init = { - .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannel = USART2_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { - .gpio = GPIOB, + .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_10, + .GPIO_Pin = GPIO_Pin_6, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource6, }, .tx = { - .gpio = GPIOB, + .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_11, + .GPIO_Pin = GPIO_Pin_5, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource5, }, }; -#endif /* PIOS_INCLUDE_COM_FLEXI */ - -#if defined(PIOS_INCLUDE_DSM) -/* - * Spektrum/JR DSM USART - */ -#include - -static const struct pios_dsm_cfg pios_dsm_aux_cfg = { - .bind = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_auxsbus_cfg = { - .bind = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_1, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { - .bind = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -#endif /* PIOS_INCLUDE_DSM */ - -#if defined(PIOS_INCLUDE_HSUM) -/* - * Graupner HoTT SUMD/SUMH USART - */ -#include - -#endif /* PIOS_INCLUDE_HSUM */ - -#if (defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_HSUM)) -/* - * Spektrum/JR DSM or Graupner HoTT SUMD/SUMH USART - */ - -static const struct pios_usart_cfg pios_usart_dsm_hsum_aux_cfg = { - .regs = USART6, - .remap = GPIO_AF_USART6, +static const struct pios_usart_cfg pios_usart3_cfg = { + .regs = USART3, + .remap = GPIO_AF_USART3, .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { .init = { - .NVIC_IRQChannel = USART6_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { - .gpio = GPIOC, + .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_7, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource9, }, .tx = { - .gpio = GPIOC, + .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_6, + .GPIO_Pin = GPIO_Pin_8, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource8, }, }; -static const struct pios_usart_cfg pios_usart_dsm_hsum_auxsbus_cfg = { +static const struct pios_usart_cfg pios_usart4_cfg = { .regs = UART4, .remap = GPIO_AF_UART4, .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { .init = { - .NVIC_IRQChannel = UART4_IRQn, + .NVIC_IRQChannel = UART4_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { @@ -1091,6 +1072,7 @@ static const struct pios_usart_cfg pios_usart_dsm_hsum_auxsbus_cfg = { .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource1, }, .tx = { .gpio = GPIOA, @@ -1101,343 +1083,60 @@ static const struct pios_usart_cfg pios_usart_dsm_hsum_auxsbus_cfg = { .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource0, }, }; -static const struct pios_usart_cfg pios_usart_dsm_hsum_flexi_cfg = { - .regs = USART3, - .remap = GPIO_AF_USART3, +static const struct pios_usart_cfg pios_usart6_cfg = { + .regs = USART6, + .remap = GPIO_AF_USART6, .init = { - .USART_BaudRate = 115200, + .USART_BaudRate = 57600, .USART_WordLength = USART_WordLength_8b, .USART_Parity = USART_Parity_No, .USART_StopBits = USART_StopBits_1, .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, }, .irq = { .init = { - .NVIC_IRQChannel = USART3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannel = USART6_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { - .gpio = GPIOB, + .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_11, + .GPIO_Pin = GPIO_Pin_7, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource7, }, .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -#endif /* PIOS_INCLUDE_DSM || PIOS_INCLUDE_HSUM */ - -#if defined(PIOS_INCLUDE_SBUS) -/* - * S.Bus USART - */ -#include - -static const struct pios_usart_cfg pios_usart_sbus_auxsbus_cfg = { - .regs = UART4, - .init = { - .USART_BaudRate = 100000, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_Even, - .USART_StopBits = USART_StopBits_2, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = UART4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, + .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_1, + .GPIO_Pin = GPIO_Pin_6, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, + .pin_source = GPIO_PinSource6, }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_sbus_cfg pios_sbus_cfg = { - /* Inverter configuration */ - .inv = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_Speed = GPIO_Speed_2MHz, - }, - }, - .gpio_clk_func = RCC_AHB1PeriphClockCmd, - .gpio_clk_periph = RCC_AHB1Periph_GPIOB, - .gpio_inv_enable = Bit_SET, }; -#endif /* PIOS_INCLUDE_SBUS */ +#endif /* PIOS_INCLUDE_USART */ #if defined(PIOS_INCLUDE_COM) -#include - -#endif /* PIOS_INCLUDE_COM */ - -#if defined(PIOS_INCLUDE_I2C) - -#include - -/* - * I2C Adapters - */ -void PIOS_I2C_mag_adapter_ev_irq_handler(void); -void PIOS_I2C_mag_adapter_er_irq_handler(void); -void I2C1_EV_IRQHandler() -__attribute__ ((alias("PIOS_I2C_mag_adapter_ev_irq_handler"))); -void I2C1_ER_IRQHandler() -__attribute__ ((alias("PIOS_I2C_mag_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_mag_adapter_cfg = { - .regs = I2C1, - .remap = GPIO_AF_I2C1, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_mag_adapter_id; -void PIOS_I2C_mag_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_adapter_id); -} - -void PIOS_I2C_mag_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_adapter_id); -} - - -void PIOS_I2C_flexiport_adapter_ev_irq_handler(void); -void PIOS_I2C_flexiport_adapter_er_irq_handler(void); -void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_ev_irq_handler"))); -void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = { - .regs = I2C2, - .remap = GPIO_AF_I2C2, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_flexiport_adapter_id; -void PIOS_I2C_flexiport_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexiport_adapter_id); -} - -void PIOS_I2C_flexiport_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexiport_adapter_id); -} - - -void PIOS_I2C_pressure_adapter_ev_irq_handler(void); -void PIOS_I2C_pressure_adapter_er_irq_handler(void); -void I2C3_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_ev_irq_handler"))); -void I2C3_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_pressure_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_pressure_adapter_cfg = { - .regs = I2C3, - .remap = GPIO_AF_I2C3, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C3_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C3_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_pressure_adapter_id; -void PIOS_I2C_pressure_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_pressure_adapter_id); -} +#include "pios_com_priv.h" -void PIOS_I2C_pressure_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_pressure_adapter_id); -} -#endif /* PIOS_INCLUDE_I2C */ +#endif /* PIOS_INCLUDE_COM */ #if defined(PIOS_INCLUDE_RTC) /* @@ -1448,9 +1147,9 @@ void PIOS_I2C_pressure_adapter_er_irq_handler(void) void PIOS_RTC_IRQ_Handler (void); void RTC_WKUP_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); static const struct pios_rtc_cfg pios_rtc_main_cfg = { - .clksrc = RCC_RTCCLKSource_HSE_Div16, // Divide 8 Mhz crystal down to 1 - // For some reason it's acting like crystal is 16 Mhz. This clock is then divided - // by another 16 to give a nominal 62.5 khz clock + .clksrc = RCC_RTCCLKSource_HSE_Div8, // Divide 8 MHz HSE by 8 = 1 MHz + // 1 MHz resulting clock is then divided + // by another 16 to give a nominal 62.5 kHz clock .prescaler = 100, // Every 100 cycles gives 625 Hz .irq = { .init = { @@ -1471,45 +1170,53 @@ void PIOS_RTC_IRQ_Handler (void) #include "pios_tim_priv.h" -static const TIM_TimeBaseInitTypeDef tim_2_3_5_time_base = { +//Timers used for inputs (4) + +// Set up timers that only have outputs on APB1 +static const TIM_TimeBaseInitTypeDef tim_4_time_base = { .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, .TIM_ClockDivision = TIM_CKD_DIV1, .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_Period = 0xFFFF, .TIM_RepetitionCounter = 0x0000, }; -static const TIM_TimeBaseInitTypeDef tim_9_10_11_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, }; -// Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_1_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, +// Timers used for outputs (1,2,3,8) + +// Set up timers that only have outputs on APB1 +static const TIM_TimeBaseInitTypeDef tim_2_3_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), .TIM_RepetitionCounter = 0x0000, }; -// Set up timers that only have inputs on APB2 -static const TIM_TimeBaseInitTypeDef tim_4_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, +// Set up timers that only have outputs on APB2 +static const TIM_TimeBaseInitTypeDef tim_1_8_time_base = { + .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), .TIM_RepetitionCounter = 0x0000, }; - - static const struct pios_tim_clock_cfg tim_2_cfg = { .timer = TIM2, - .time_base_init = &tim_2_3_5_time_base, + .time_base_init = &tim_2_3_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM2_IRQn, @@ -1520,10 +1227,9 @@ static const struct pios_tim_clock_cfg tim_2_cfg = { }, }; - static const struct pios_tim_clock_cfg tim_3_cfg = { .timer = TIM3, - .time_base_init = &tim_2_3_5_time_base, + .time_base_init = &tim_2_3_time_base, .irq = { .init = { .NVIC_IRQChannel = TIM3_IRQn, @@ -1534,13 +1240,12 @@ static const struct pios_tim_clock_cfg tim_3_cfg = { }, }; - -static const struct pios_tim_clock_cfg tim_5_cfg = { - .timer = TIM5, - .time_base_init = &tim_2_3_5_time_base, +static const struct pios_tim_clock_cfg tim_8_cfg = { + .timer = TIM8, + .time_base_init = &tim_1_8_time_base, .irq = { .init = { - .NVIC_IRQChannel = TIM5_IRQn, + .NVIC_IRQChannel = TIM8_CC_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, @@ -1548,25 +1253,14 @@ static const struct pios_tim_clock_cfg tim_5_cfg = { }, }; -static const struct pios_tim_clock_cfg tim_9_cfg = { - .timer = TIM9, - .time_base_init = &tim_9_10_11_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_BRK_TIM9_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; +// Timers used for inputs or outputs (1) -static const struct pios_tim_clock_cfg tim_10_cfg = { - .timer = TIM10, - .time_base_init = &tim_9_10_11_time_base, +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_8_time_base, .irq = { .init = { - .NVIC_IRQChannel = TIM1_UP_TIM10_IRQn, + .NVIC_IRQChannel = TIM1_CC_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, @@ -1574,366 +1268,483 @@ static const struct pios_tim_clock_cfg tim_10_cfg = { }, }; -static const struct pios_tim_clock_cfg tim_11_cfg = { - .timer = TIM11, - .time_base_init = &tim_9_10_11_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_TRG_COM_TIM11_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, +/** + * Pios servo configuration structures + */ + +/* + * Available outputs with PPM RX + 1: TIM8_CH4 (PC9) + 2: TIM8_CH3 (PC8) + 3: TIM2_CH1 (PA15) + 4: TIM2_CH2 (PB3) + 5: TIM3_CH1 (PB4) + 6: TIM3_CH2 (PB5) + 7: TIM1_CH1 (PE9) + 8: TIM1_CH2 (PE11) + 9: TIM1_CH3 (PE13) + 10: TIM1_CH4 (PE14) + */ +static const struct pios_tim_channel pios_tim_outputs_pins_ppm_rx[] = { + { + .timer = TIM8, + .timer_chan = TIM_Channel_4, + .remap = GPIO_AF_TIM8, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource9, }, }, -}; - -static const struct pios_tim_clock_cfg tim_1_cfg = { - .timer = TIM1, - .time_base_init = &tim_1_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + { + .timer = TIM8, + .timer_chan = TIM_Channel_3, + .remap = GPIO_AF_TIM8, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource8, }, }, -}; - -static const struct pios_tim_clock_cfg tim_4_cfg = { - .timer = TIM4, - .time_base_init = &tim_4_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource15, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource3, }, }, -}; - -/** - * Pios servo configuration structures - */ -#include -static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { { - .timer = TIM9, + .timer = TIM3, .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM3, .pin = { - .gpio = GPIOE, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_5, + .GPIO_Pin = GPIO_Pin_4, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource5, + .pin_source = GPIO_PinSource4, }, - .remap = GPIO_AF_TIM9, }, { - .timer = TIM9, + .timer = TIM3, .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM3, .pin = { - .gpio = GPIOE, + .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_6, + .GPIO_Pin = GPIO_Pin_5, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource6, + .pin_source = GPIO_PinSource5, }, - .remap = GPIO_AF_TIM9, }, { - .timer = TIM11, + .timer = TIM1, .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM1, .pin = { - .gpio = GPIOB, + .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_9, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, .pin_source = GPIO_PinSource9, }, - .remap = GPIO_AF_TIM11, }, { - .timer = TIM10, - .timer_chan = TIM_Channel_1, + .timer = TIM1, + .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM1, .pin = { - .gpio = GPIOB, + .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_8, + .GPIO_Pin = GPIO_Pin_11, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource8, + .pin_source = GPIO_PinSource11, }, - .remap = GPIO_AF_TIM10, }, { - .timer = TIM5, + .timer = TIM1, .timer_chan = TIM_Channel_3, + .remap = GPIO_AF_TIM1, .pin = { - .gpio = GPIOA, + .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_2, + .GPIO_Pin = GPIO_Pin_13, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource2, + .pin_source = GPIO_PinSource13, }, - .remap = GPIO_AF_TIM5, }, { - .timer = TIM5, + .timer = TIM1, .timer_chan = TIM_Channel_4, + .remap = GPIO_AF_TIM1, .pin = { - .gpio = GPIOA, + .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_3, + .GPIO_Pin = GPIO_Pin_14, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource3, + .pin_source = GPIO_PinSource14, }, - .remap = GPIO_AF_TIM5, }, +}; + +/* + * Available outputs with PWM RX + 1: TIM8_CH4 (PC9) + 2: TIM8_CH3 (PC8) + 3: TIM2_CH1 (PA15) + 4: TIM2_CH2 (PB3) + 5: TIM3_CH1 (PB4) + 6: TIM3_CH2 (PB5) + */ +static const struct pios_tim_channel pios_tim_outputs_pins_pwm_rx[] = { { - .timer = TIM3, + .timer = TIM8, + .timer_chan = TIM_Channel_4, + .remap = GPIO_AF_TIM8, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource9, + }, + }, + { + .timer = TIM8, .timer_chan = TIM_Channel_3, + .remap = GPIO_AF_TIM8, .pin = { - .gpio = GPIOB, + .gpio = GPIOC, .init = { - .GPIO_Pin = GPIO_Pin_0, + .GPIO_Pin = GPIO_Pin_8, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource0, + .pin_source = GPIO_PinSource8, }, - .remap = GPIO_AF_TIM3, }, { - .timer = TIM3, - .timer_chan = TIM_Channel_4, + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM2, .pin = { - .gpio = GPIOB, + .gpio = GPIOA, .init = { - .GPIO_Pin = GPIO_Pin_1, + .GPIO_Pin = GPIO_Pin_15, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, - .pin_source = GPIO_PinSource1, + .pin_source = GPIO_PinSource15, }, - .remap = GPIO_AF_TIM3, }, - // PB3 - TIM2 CH2 LED1 { .timer = TIM2, .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM2, .pin = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_3, + .GPIO_Pin = GPIO_Pin_3, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, .pin_source = GPIO_PinSource3, }, - .remap = GPIO_AF_TIM2, }, - // PB4 - TIM3 CH1 LED2 { .timer = TIM3, .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM3, .pin = { .gpio = GPIOB, .init = { - .GPIO_Pin = GPIO_Pin_4, + .GPIO_Pin = GPIO_Pin_4, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP + .GPIO_PuPd = GPIO_PuPd_NOPULL }, .pin_source = GPIO_PinSource4, }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_2, .remap = GPIO_AF_TIM3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_5, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF, + .GPIO_OType = GPIO_OType_PP, + .GPIO_PuPd = GPIO_PuPd_NOPULL + }, + .pin_source = GPIO_PinSource5, + }, }, }; -const struct pios_servo_cfg pios_servo_cfg = { +#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM) +/* + * Servo outputs + */ +#include + +const struct pios_servo_cfg pios_servo_cfg_ppm_rx = { .tim_oc_init = { - .TIM_OCMode = TIM_OCMode_PWM1, - .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, .TIM_OutputNState = TIM_OutputNState_Disable, - .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, - .TIM_OCPolarity = TIM_OCPolarity_High, - .TIM_OCNPolarity = TIM_OCPolarity_High, - .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, .TIM_OCNIdleState = TIM_OCNIdleState_Reset, }, - .channels = pios_tim_servoport_all_pins, - .num_channels = NELEMENTS(pios_tim_servoport_all_pins), + .channels = pios_tim_outputs_pins_ppm_rx, + .num_channels = NELEMENTS(pios_tim_outputs_pins_ppm_rx), }; +const struct pios_servo_cfg pios_servo_cfg_pwm_rx = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_outputs_pins_pwm_rx, + .num_channels = NELEMENTS(pios_tim_outputs_pins_pwm_rx), +}; +#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */ /* - * PWM Inputs + * PWM INPUTS + 1: TIM4_CH1 (PD12) + 2: TIM4_CH2 (PD13) + 3: TIM4_CH3 (PD14) + 4: TIM4_CH4 (PD15) + 5: TIM1_CH1 (PE9) + 6: TIM1_CH2 (PE11) + 7: TIM1_CH3 (PE13) + 8: TIM1_CH4 (PE14) */ -#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { +static const struct pios_tim_channel pios_tim_rcvrport_pwm[] = { { .timer = TIM4, - .timer_chan = TIM_Channel_4, + .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM4, .pin = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_15, + .GPIO_Pin = GPIO_Pin_12, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource15, + .pin_source = GPIO_PinSource12, }, - .remap = GPIO_AF_TIM4, }, { .timer = TIM4, - .timer_chan = TIM_Channel_3, + .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM4, .pin = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_14, + .GPIO_Pin = GPIO_Pin_13, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource14, + .pin_source = GPIO_PinSource13, }, - .remap = GPIO_AF_TIM4, }, { .timer = TIM4, - .timer_chan = TIM_Channel_2, + .timer_chan = TIM_Channel_3, + .remap = GPIO_AF_TIM4, .pin = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_13, + .GPIO_Pin = GPIO_Pin_14, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource13, + .pin_source = GPIO_PinSource14, }, - .remap = GPIO_AF_TIM4, }, { .timer = TIM4, - .timer_chan = TIM_Channel_1, + .timer_chan = TIM_Channel_4, + .remap = GPIO_AF_TIM4, .pin = { .gpio = GPIOD, .init = { - .GPIO_Pin = GPIO_Pin_12, + .GPIO_Pin = GPIO_Pin_15, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource12, + .pin_source = GPIO_PinSource15, }, - .remap = GPIO_AF_TIM4, }, { .timer = TIM1, - .timer_chan = TIM_Channel_4, + .timer_chan = TIM_Channel_1, + .remap = GPIO_AF_TIM1, .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_14, + .GPIO_Pin = GPIO_Pin_9, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource14, + .pin_source = GPIO_PinSource9, }, - .remap = GPIO_AF_TIM1, }, { .timer = TIM1, - .timer_chan = TIM_Channel_3, + .timer_chan = TIM_Channel_2, + .remap = GPIO_AF_TIM1, .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_13, + .GPIO_Pin = GPIO_Pin_11, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource13, + .pin_source = GPIO_PinSource11, }, - .remap = GPIO_AF_TIM1, }, { .timer = TIM1, - .timer_chan = TIM_Channel_2, + .timer_chan = TIM_Channel_3, + .remap = GPIO_AF_TIM1, .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_11, + .GPIO_Pin = GPIO_Pin_13, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource11, + .pin_source = GPIO_PinSource13, }, - .remap = GPIO_AF_TIM1, }, { .timer = TIM1, - .timer_chan = TIM_Channel_1, + .timer_chan = TIM_Channel_4, + .remap = GPIO_AF_TIM1, .pin = { .gpio = GPIOE, .init = { - .GPIO_Pin = GPIO_Pin_9, + .GPIO_Pin = GPIO_Pin_14, .GPIO_Speed = GPIO_Speed_2MHz, .GPIO_Mode = GPIO_Mode_AF, .GPIO_OType = GPIO_OType_PP, .GPIO_PuPd = GPIO_PuPd_UP }, - .pin_source = GPIO_PinSource9, + .pin_source = GPIO_PinSource14, }, - .remap = GPIO_AF_TIM1, }, }; +/* + * PWM Inputs + */ +#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) +#include +#include + +/* + * PWM Inputs + */ const struct pios_pwm_cfg pios_pwm_cfg = { .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, @@ -1941,30 +1752,27 @@ const struct pios_pwm_cfg pios_pwm_cfg = { .TIM_ICPrescaler = TIM_ICPSC_DIV1, .TIM_ICFilter = 0x0, }, - .channels = pios_tim_rcvrport_all_channels, - .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), + .channels = pios_tim_rcvrport_pwm, + .num_channels = NELEMENTS(pios_tim_rcvrport_pwm), }; -#endif /* * PPM Input */ -#if defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_ppm_cfg pios_ppm_cfg = { +const struct pios_ppm_cfg pios_ppm_cfg = { .tim_ic_init = { .TIM_ICPolarity = TIM_ICPolarity_Rising, .TIM_ICSelection = TIM_ICSelection_DirectTI, .TIM_ICPrescaler = TIM_ICPSC_DIV1, .TIM_ICFilter = 0x0, - .TIM_Channel = TIM_Channel_2, + .TIM_Channel = TIM_Channel_4, }, - /* Use only the first channel for ppm */ - .channels = &pios_tim_rcvrport_all_channels[0], + /* Channel 4 for PPM use */ + .channels = &pios_tim_rcvrport_pwm[3], .num_channels = 1, }; -#endif //PPM +#endif #if defined(PIOS_INCLUDE_GCSRCVR) #include "pios_gcsrcvr_priv.h" @@ -1982,21 +1790,30 @@ static const struct pios_usb_cfg pios_usb_main_cfg = { .init = { .NVIC_IRQChannel = OTG_FS_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 3, + .NVIC_IRQChannelSubPriority = 0, .NVIC_IRQChannelCmd = ENABLE, }, }, .vsense = { + .gpio = NULL, + }, + .disconnect = { .gpio = GPIOD, .init = { .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_25MHz, - .GPIO_Mode = GPIO_Mode_IN, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_OUT, .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, }, } }; +const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) +{ + return &pios_usb_main_cfg; +} + #include "pios_usb_board_data_priv.h" #include "pios_usb_desc_hid_cdc_priv.h" #include "pios_usb_desc_hid_only_priv.h" @@ -2042,40 +1859,44 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = { #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ #if defined(PIOS_INCLUDE_ADC) -#include "pios_internal_adc_priv.h" #include "pios_adc_priv.h" +#include "pios_internal_adc_priv.h" + +void PIOS_ADC_DMA_irq_handler(void); +void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMA_irq_handler"))); + struct pios_internal_adc_cfg pios_adc_cfg = { - .adc_dev_master = ADC1, .dma = { .irq = { - .flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4), - .init = { - .NVIC_IRQChannel = DMA2_Stream4_IRQn, + .flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4), + .init = { + .NVIC_IRQChannel = DMA2_Stream4_IRQn, .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, }, }, .rx = { .channel = DMA2_Stream4, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR + .init = { + .DMA_Channel = DMA_Channel_0, + .DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR }, } }, .half_flag = DMA_IT_HTIF4, .full_flag = DMA_IT_TCIF4, + .adc_dev_master = ADC1, + .adc_dev_slave = NULL, }; -void PIOS_ADC_DMA_irq_handler(void); -void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMA_irq_handler"))); void PIOS_ADC_DMA_irq_handler(void) { /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_INTERNAL_ADC_DMA_Handler(); + PIOS_INTERNAL_ADC_DMA_Handler(); } + #endif /* PIOS_INCLUDE_ADC */ /** diff --git a/flight/targets/freedom/board-info/cmsis_system.c b/flight/targets/aq32/board-info/cmsis_system.c similarity index 98% rename from flight/targets/freedom/board-info/cmsis_system.c rename to flight/targets/aq32/board-info/cmsis_system.c index e36abd80005..48129a20275 100644 --- a/flight/targets/freedom/board-info/cmsis_system.c +++ b/flight/targets/aq32/board-info/cmsis_system.c @@ -2,12 +2,12 @@ ****************************************************************************** * @file system_stm32f4xx.c * @author MCD Application Team - * @version V1.0.0 - * @date 30-September-2011 + * @version V1.0.1 + * @date 25-December-2014 * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. * This file contains the system clock configuration for STM32F4xx devices, * and is generated by the clock configuration tool - * stm32f4xx_Clock_Configuration_V1.0.0.xls + * stm32f4xx_Clock_Configuration_V1.0.1.xls * * 1. This file provides two functions and one global variable to be called from * user application: @@ -58,9 +58,9 @@ *----------------------------------------------------------------------------- * HSE Frequency(Hz) | 8000000 *----------------------------------------------------------------------------- - * PLL_M | 10 + * PLL_M | 8 *----------------------------------------------------------------------------- - * PLL_N | 420 + * PLL_N | 336 *----------------------------------------------------------------------------- * PLL_P | 2 *----------------------------------------------------------------------------- @@ -146,8 +146,8 @@ /************************* PLL Parameters *************************************/ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ -#define PLL_M 10 -#define PLL_N 420 +#define PLL_M 8 +#define PLL_N 336 /* SYSCLK = PLL_VCO / PLL_P */ #define PLL_P 2 @@ -211,7 +211,6 @@ void SystemInit(void) #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ #endif - /* Reset the RCC clock configuration to the default reset state ------------*/ /* Set HSION bit */ RCC->CR |= (uint32_t)0x00000001; @@ -407,9 +406,6 @@ static void SetSysClock(void) else { /* If HSE fails to start-up, the application will have wrong clock configuration. User can add here some code to deal with this error */ - - /* better to hang here than to start with a wrong clock */ - while (1); } } @@ -510,7 +506,7 @@ void SystemInit_ExtMemCtl(void) FSMC_Bank1->BTCR[2] = 0x00001015; FSMC_Bank1->BTCR[3] = 0x00010603; FSMC_Bank1E->BWTR[2] = 0x0fffffff; -/* + /* Bank1_SRAM2 is configured as follow: p.FSMC_AddressSetupTime = 3; @@ -536,8 +532,7 @@ void SystemInit_ExtMemCtl(void) FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; -*/ - +*/ } #endif /* DATA_IN_ExtSRAM */ @@ -554,3 +549,4 @@ void SystemInit_ExtMemCtl(void) * @} */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ + diff --git a/flight/targets/revolution/board-info/pios_board.h b/flight/targets/aq32/board-info/pios_board.h similarity index 64% rename from flight/targets/revolution/board-info/pios_board.h rename to flight/targets/aq32/board-info/pios_board.h index 5f9fe7c4d85..7c0ce87f3f7 100644 --- a/flight/targets/revolution/board-info/pios_board.h +++ b/flight/targets/aq32/board-info/pios_board.h @@ -1,16 +1,15 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Revolution OpenPilot Revolution support files + * @addtogroup Aq32 Aq32 support files * @{ * - * @file STM32Fxx_Revolution.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @file STM32F4xx_Aq32.c * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific defines for Revolution + * @brief Board specific defines for AQ32 * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -34,6 +33,13 @@ #include +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +#define DEBUG_LEVEL 0 +#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_debug_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_debug_id, __VA_ARGS__); }} +#else +#define DEBUG_PRINTF(level, ...) +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + //------------------------ // Timers and Channels Used //------------------------ @@ -70,33 +76,33 @@ TIM8 | | | | //------------------------ // BOOTLOADER_SETTINGS //------------------------ -#define BOARD_READABLE true -#define BOARD_WRITABLE true -#define MAX_DEL_RETRYS 3 +#define BOARD_READABLE true +#define BOARD_WRITABLE true +#define MAX_DEL_RETRYS 3 //------------------------ // PIOS_LED //------------------------ -#define PIOS_LED_HEARTBEAT 0 -#define PIOS_LED_ALARM 1 +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 //------------------------ // PIOS_WDG //------------------------ -#define PIOS_WATCHDOG_TIMEOUT 250 -#define PIOS_WDG_REGISTER RTC_BKP_DR4 +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER RTC_BKP_DR4 //------------------------ // PIOS_I2C // See also pios_board.c //------------------------ -#define PIOS_I2C_MAX_DEVS 3 -extern uint32_t pios_i2c_mag_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_adapter_id) -extern uint32_t pios_i2c_flexiport_adapter_id; -#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id) -#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER) +#define PIOS_I2C_MAX_DEVS 2 +extern uint32_t pios_i2c_internal_id; +extern uint32_t pios_i2c_external_id; +#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_internal_id) //this is dirty and should be removed in favor a cleaner sensor api + + //------------------------- // PIOS_COM @@ -110,6 +116,8 @@ extern uintptr_t pios_com_bridge_id; extern uintptr_t pios_com_vcp_id; extern uintptr_t pios_com_mavlink_id; extern uintptr_t pios_com_hott_id; +extern uintptr_t pios_com_frsky_sensor_hub_id; +extern uintptr_t pios_com_lighttelemetry_id; extern uintptr_t pios_com_picoc_id; extern uintptr_t pios_com_frsky_sport_id; @@ -118,119 +126,122 @@ extern uintptr_t pios_com_frsky_sport_id; #define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) -#define PIOS_COM_DEBUG (pios_com_debug_id) #define PIOS_COM_MAVLINK (pios_com_mavlink_id) #define PIOS_COM_HOTT (pios_com_hott_id) +#define PIOS_COM_FRSKY_SENSOR_HUB (pios_com_frsky_sensor_hub_id) +#define PIOS_COM_LIGHTTELEMETRY (pios_com_lighttelemetry_id) #define PIOS_COM_PICOC (pios_com_picoc_id) #define PIOS_COM_FRSKY_SPORT (pios_com_frsky_sport_id) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +extern uintptr_t pios_com_debug_id; +#define PIOS_COM_DEBUG (pios_com_debug_id) +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + + + //------------------------ -// TELEMETRY +// TELEMETRY //------------------------ -#define TELEM_QUEUE_SIZE 80 -#define PIOS_TELEM_STACK_SIZE 624 +#define TELEM_QUEUE_SIZE 80 +#define PIOS_TELEM_STACK_SIZE 624 -#define PIOS_SYSCLK 168000000 +#define PIOS_SYSCLK 168000000 // Peripherals that belongs to APB1 are: // DAC |PWR |CAN1,2 -// I2C1,2,3 |UART4,5 |USART3,2 -// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 +// I2C1,2,3 |UART4,5 |USART3,2 +// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 // I2S2Ext |IWDG |WWDG -// RTC/BKP reg +// RTC/BKP reg // TIM2,3,4,5,6,7,12,13,14 -// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) -// Default APB1 Prescaler = 4 -#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) +// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) +// Default APB1 Prescaler = 4 +#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) // Peripherals belonging to APB2 // SDIO |EXTI |SYSCFG |SPI1 -// ADC1,2,3 +// ADC1,2,3 // USART1,6 // TIM1,8,9,10,11 // // Default APB2 Prescaler = 2 // -#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK +#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK //------------------------- // Interrupt Priorities //------------------------- -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... + //------------------------ // PIOS_RCVR // See also pios_board.c //------------------------ -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_GCSRCVR_TIMEOUT_MS 100 +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 //------------------------- // Receiver PPM input //------------------------- -#define PIOS_PPM_NUM_INPUTS 12 +#define PIOS_PPM_NUM_INPUTS 12 //------------------------- // Receiver PWM input //------------------------- -#define PIOS_PWM_NUM_INPUTS 8 +#define PIOS_PWM_NUM_INPUTS 8 //------------------------- -// Receiver SPEKTRUM input +// Receiver DSM input //------------------------- -#define PIOS_SPEKTRUM_NUM_INPUTS 12 +#define PIOS_DSM_NUM_INPUTS 12 //------------------------- // Receiver HSUM input //------------------------- -#define PIOS_HSUM_MAX_DEVS 2 -#define PIOS_HSUM_NUM_INPUTS 32 +#define PIOS_HSUM_MAX_DEVS 2 +#define PIOS_HSUM_NUM_INPUTS 32 //------------------------- // Receiver S.Bus input //------------------------- -#define PIOS_SBUS_NUM_INPUTS (16+2) - -//------------------------- -// Receiver DSM input -//------------------------- -#define PIOS_DSM_NUM_INPUTS 12 +#define PIOS_SBUS_NUM_INPUTS (16+2) //------------------------- // Servo outputs //------------------------- -#define PIOS_SERVO_UPDATE_HZ 50 -#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ //-------------------------- // Timer controller settings //-------------------------- -#define PIOS_TIM_MAX_DEVS 6 +#define PIOS_TIM_MAX_DEVS 8 //------------------------- // ADC -// PIOS_ADC_PinGet(0) = Current sensor -// PIOS_ADC_PinGet(1) = Voltage sensor -// PIOS_ADC_PinGet(4) = VREF -// PIOS_ADC_PinGet(5) = Temperature sensor -//------------------------- -#define PIOS_DMA_PIN_CONFIG \ -{ \ - {GPIOC, GPIO_Pin_0, ADC_Channel_10}, \ - {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ - {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ - {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ - {GPIOC, GPIO_Pin_2, ADC_Channel_12} \ +//------------------------- +#define PIOS_ADC_SUB_DRIVER_MAX_INSTANCES 3 + +//------------------------- +#define PIOS_DMA_PIN_CONFIG \ +{ \ + { GPIOC, GPIO_Pin_0, ADC_Channel_10 }, /* Internal Voltage Monitor */ \ + { GPIOC, GPIO_Pin_4, ADC_Channel_14 }, /* External Voltage Monitor */ \ + { GPIOC, GPIO_Pin_5, ADC_Channel_15 }, /* External Current Monitor */ \ + { NULL, 0, ADC_Channel_Vrefint }, /* Voltage reference */ \ + { NULL, 0, ADC_Channel_TempSensor }, /* Temperature sensor */ \ } -/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ +/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_internal_adc.h */ /* which is annoying because this then determines the rate at which we generate buffer turnover events */ /* the objective here is to get enough buffer space to support 100Hz averaging rate */ -#define PIOS_ADC_NUM_CHANNELS 4 +#define PIOS_ADC_NUM_CHANNELS 5 #define PIOS_ADC_MAX_OVERSAMPLING 2 #define PIOS_ADC_USE_ADC2 0 @@ -239,12 +250,7 @@ extern uintptr_t pios_com_frsky_sport_id; //------------------------- // USB //------------------------- -#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ - -//------------------------- -// ADC -//------------------------- -#define PIOS_ADC_SUB_DRIVER_MAX_INSTANCES 3 +#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ #endif /* STM3210E_INS_H_ */ diff --git a/flight/targets/freedom/board-info/usb_conf.h b/flight/targets/aq32/board-info/usb_conf.h similarity index 100% rename from flight/targets/freedom/board-info/usb_conf.h rename to flight/targets/aq32/board-info/usb_conf.h diff --git a/flight/targets/freedom/fw/FreeRTOSConfig.h b/flight/targets/aq32/fw/FreeRTOSConfig.h similarity index 100% rename from flight/targets/freedom/fw/FreeRTOSConfig.h rename to flight/targets/aq32/fw/FreeRTOSConfig.h diff --git a/flight/targets/freedom/fw/Makefile b/flight/targets/aq32/fw/Makefile similarity index 72% rename from flight/targets/freedom/fw/Makefile rename to flight/targets/aq32/fw/Makefile index 77df58985a4..5ce0aa5b9f1 100644 --- a/flight/targets/freedom/fw/Makefile +++ b/flight/targets/aq32/fw/Makefile @@ -6,7 +6,7 @@ # @{ # @addtogroup # @{ -# @brief Makefile to build firmware for the Freedom board. +# @brief Makefile to build firmware for the Aq32 board. ############################################################################### # # This program is free software; you can redistribute it and/or modify @@ -27,13 +27,11 @@ include $(MAKE_INC_DIR)/firmware-defs.mk include $(BOARD_INFO_DIR)/board-info.mk -# @startgroup Compile Options -# @groupbrief Set developer code and compile options -# @optbrief Set to YES to compile for debugging +# Set developer code and compile options +# Set to YES for debugging DEBUG ?= NO ERASE_FLASH ?= NO -# @endgroup Compile Options # List of modules to include MODULES = Sensors MODULES += Attitude @@ -45,17 +43,16 @@ MODULES += Telemetry OPTMODULES += GPS OPTMODULES += AltitudeHold -OPTMODULES += PathPlanner OPTMODULES += VtolPathFollower OPTMODULES += FixedWingPathFollower OPTMODULES += GroundPathFollower +OPTMODULES += PathPlanner OPTMODULES += CameraStab -OPTMODULES += OveroSync OPTMODULES += Autotune OPTMODULES += TxPID -OPTMODULES += Battery OPTMODULES += VibrationAnalysis OPTMODULES += UAVOMavlinkBridge +OPTMODULES += Battery OPTMODULES += ComUsbBridge OPTMODULES += Airspeed/revolution OPTMODULES += UAVOHoTTBridge @@ -64,9 +61,7 @@ OPTMODULES += UAVOLighttelemetryBridge OPTMODULES += PicoC OPTMODULES += UAVOFrSKYSPortBridge OPTMODULES += Geofence - -PYMODULES = -#FlightPlan +#OPTMODULES += Logging # Paths OPUAVTALKINC = $(OPUAVTALK)/inc @@ -88,11 +83,12 @@ STMSPDINCDIR = $(STMSPDDIR)/inc DEBUG_CM3_DIR = $(PIOSCOMMONLIB)/Debug DEBUG_CM3_DIR_INC = $(DEBUG_CM3_DIR)/inc OPUAVOBJINC = $(OPUAVOBJ)/inc +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans MAVLINKINC = $(FLIGHTLIB)/mavlink/v1.0/common -SRC = # optional component libraries -include $(PIOSCOMMONLIB)/FreeRTOS/library.mk +include $(APPLIBDIR)/ChibiOS/library.mk #include $(PIOSCOMMONLIB)/dosfs/library.mk include $(FLIGHTLIB)/CMSIS3/DSP_Lib/library.mk @@ -105,6 +101,7 @@ SRC += ${foreach MOD, ${MODULES} ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/System/systemmod.c SRC += main.c +SRC += board.c SRC += pios_board.c SRC += pios_usb_board_data.c SRC += $(FLIGHTLIB)/alarms.c @@ -112,10 +109,14 @@ SRC += $(OPUAVTALK)/uavtalk.c SRC += $(OPUAVOBJ)/uavobjectmanager.c SRC += $(OPUAVOBJ)/eventdispatcher.c -#ifeq ($(DEBUG),YES) +ifeq ($(DEBUG),YES) SRC += $(DEBUG_CM3_DIR)/dcc_stdio.c SRC += $(DEBUG_CM3_DIR)/cm3_fault_handlers.c -#endif +endif + +ifeq ($(ERASE_FLASH), YES) +CDEFS += -DERASE_FLASH +endif SRC += $(FLIGHTLIB)/paths.c SRC += $(FLIGHTLIB)/fifo_buffer.c @@ -123,40 +124,32 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c -SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/atmospheric_math.c - -## For RFM22b -SRC += $(RSCODE)/berlekamp.c -SRC += $(RSCODE)/crcgen.c -SRC += $(RSCODE)/galois.c -SRC += $(RSCODE)/rs.c +SRC += $(MATHLIB)/pid.c ## PIOS Hardware (STM32F4xx) -include $(PIOS)/STM32F4xx/library_fw.mk +include $(PIOS)/STM32F4xx/library_chibios.mk ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_delay.c SRC += $(PIOSCOMMON)/pios_mpu6000.c -SRC += $(PIOSCOMMON)/pios_bma180.c -SRC += $(PIOSCOMMON)/pios_etasv3.c -SRC += $(PIOSCOMMON)/pios_mpxv5004.c -SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_gcsrcvr.c -SRC += $(PIOSCOMMON)/pios_l3gd20.c SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c + + + SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_rfm22b.c -SRC += $(PIOSCOMMON)/pios_rfm22b_com.c -SRC += $(PIOSCOMMON)/pios_rfm22b_rcvr.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c SRC += $(PIOSCOMMON)/pios_sensors.c +SRC += $(PIOSCOMMON)/pios_flash.c SRC += $(PIOSCOMMON)/pios_flash_jedec.c SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c SRC += $(PIOSCOMMON)/printf-stdarg.c @@ -164,69 +157,40 @@ SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c SRC += $(PIOSCOMMON)/pios_usb_util.c SRC += $(PIOSCOMMON)/pios_adc.c -SRC += $(PIOSCOMMON)/pios_flash.c SRC += $(PIOSCOMMON)/pios_heap.c SRC += $(PIOSCOMMON)/pios_semaphore.c SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c - - -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = +SRC += $(PIOSCOMMON)/pios_streamfs.c # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - -# List Assembler source files here. -# Make them always end in a capital .S. Files ending in a lowercase .s -# will not be considered source files but generated files (assembler -# output from the compiler), and will be deleted upon "make clean"! -# Even though the DOS/Win* filesystem matches both .s and .S the same, -# it will preserve the spelling of the filenames, and gcc itself does -# care about how the name is spelled on its command-line. - - -# List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = - # List any extra directories to look for include files here. # Each directory must be seperated by a space. -EXTRAINCDIRS += $(SHAREDAPIDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(OPUAVSYNTHDIR) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(MATHLIBINC) -EXTRAINCDIRS += $(RSCODEINC) -EXTRAINCDIRS += $(PIOSSTM32F4XX) -EXTRAINCDIRS += $(PIOSCOMMON) -EXTRAINCDIRS += $(BOARD_INFO_DIR) -EXTRAINCDIRS += $(STMSPDINCDIR) -EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(BOOTINC) -EXTRAINCDIRS += $(DEBUG_CM3_DIR_INC) -EXTRAINCDIRS += $(MAVLINKINC) - -# Generate intermediate code -gencode: ${OUTDIR}/pmlib_img.c ${OUTDIR}/pmlib_nat.c ${OUTDIR}/pmlibusr_img.c ${OUTDIR}/pmlibusr_nat.c ${OUTDIR}/pmfeatures.h - -EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${OPTMODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc +EXTRAINCDIRS += $(SHAREDAPIDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(MATHLIBINC) +EXTRAINCDIRS += $(RSCODEINC) +EXTRAINCDIRS += $(PIOSSTM32F4XX) +EXTRAINCDIRS += $(PIOSCOMMON) +EXTRAINCDIRS += $(BOARD_INFO_DIR) +EXTRAINCDIRS += $(STMSPDINCDIR) +EXTRAINCDIRS += $(CMSISDIR) +EXTRAINCDIRS += $(BOOTINC) +EXTRAINCDIRS += $(DEBUG_CM3_DIR_INC) +EXTRAINCDIRS += $(MAVLINKINC) + +EXTRAINCDIRS += ${foreach MOD, ${MODULES} ${OPTMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc # List any extra directories to look for library files here. # Also add directories where the linker should search for @@ -257,13 +221,10 @@ else CFLAGS += -Os endif -ifeq ($(ERASE_FLASH), YES) -CDEFS += -DERASE_FLASH -endif - + + # common architecture-specific flags from the device-specific library makefile CFLAGS += $(ARCHFLAGS) - CFLAGS += -DDIAGNOSTICS CFLAGS += -DDIAG_TASKS @@ -276,15 +237,7 @@ CDEFS += -DUNALIGNED_SUPPORT_DISABLE # This is not the best place for these. Really should abstract out # to the board file or something -CFLAGS += -DSTM32F4XX -CFLAGS += -DMEM_SIZE=1024000000 - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both +CDEFS += -DSTM32F40_41xxx # Debugging format. DEBUGF = dwarf-2 @@ -295,6 +248,10 @@ CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) +ifeq ($(ENABLE_DEBUG_CONSOLE), YES) +CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE +endif +CDEFS += -DCORTEX_VTOR_INIT='($(FW_BANK_BASE) - $(EF_BANK_BASE))' ifeq ($(ENABLE_DEBUG_CONSOLE), YES) CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE @@ -332,13 +289,10 @@ CSTANDARD = -std=gnu99 # Flags for C and C++ (arm-elf-gcc/arm-elf-g++) CFLAGS += -g$(DEBUGF) - CFLAGS += -ffast-math - CFLAGS += -mcpu=$(MCU) CFLAGS += $(CDEFS) CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - CFLAGS += -mapcs-frame CFLAGS += -fomit-frame-pointer CFLAGS += -ffunction-sections -fdata-sections @@ -362,23 +316,21 @@ ASFLAGS += $(ADEFS) ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -MATH_LIB = -lm - # Linker flags. # -Wl,...: tell GCC to pass this to linker. # -Map: create map file # --cref: add cross reference to map file LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc +LDFLAGS += -lc -lgcc -lm LDFLAGS += -Wl,--warn-common LDFLAGS += -Wl,--fatal-warnings -#Linker scripts -LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +# Linker scripts +LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) -include $(MAKE_INC_DIR)/firmware-common.mk +include ./UAVObjects.inc +UAVO_NAV = YES +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/tests/sin_lookup/Makefile b/flight/targets/aq32/fw/UAVObjects.inc similarity index 59% rename from flight/tests/sin_lookup/Makefile rename to flight/targets/aq32/fw/UAVObjects.inc index 759981df926..1c3538bb301 100644 --- a/flight/tests/sin_lookup/Makefile +++ b/flight/targets/aq32/fw/UAVObjects.inc @@ -1,11 +1,12 @@ ############################################################################### # @file Makefile -# @author Tau Labs, http://taulabs.org, Copyright (C) 2013 +# @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup # @{ -# @brief Makefile for unit test +# @brief Makefile to build UAVObject code for aq32 flight control. ############################################################################### # # This program is free software; you can redistribute it and/or modify @@ -23,20 +24,18 @@ # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA # -WHEREAMI := $(dir $(lastword $(MAKEFILE_LIST))) -TOP := $(realpath $(WHEREAMI)/../../../) -include $(TOP)/make/firmware-defs.mk +# These are the UAVObjects supposed to be build as part of the OpenPilot target +# (all architectures) -EXTRAINCDIRS += $(FLIGHTLIB)/math -EXTRAINCDIRS += $(SHAREDAPIDIR) +UAVOBJSRCFILENAMES = +UAVOBJSRCFILENAMES += acceldesired +UAVOBJSRCFILENAMES += geofencesettings +UAVOBJSRCFILENAMES += groundpathfollowersettings +UAVOBJSRCFILENAMES += hwaq32 +UAVOBJSRCFILENAMES += altitudeholdstate +UAVOBJSRCFILENAMES += hottsettings +UAVOBJSRCFILENAMES += picocsettings +UAVOBJSRCFILENAMES += picocstatus -CFLAGS += -O0 -CFLAGS += -Wall -Werror -CFLAGS += -g -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. -CONLYFLAGS += -std=gnu99 -SRC := $(FLIGHTLIB)/math/sin_lookup.c - -include $(TOP)/make/unittest.mk diff --git a/flight/targets/aq32/fw/board.c b/flight/targets/aq32/fw/board.c new file mode 100644 index 00000000000..04d968a6ed7 --- /dev/null +++ b/flight/targets/aq32/fw/board.c @@ -0,0 +1,36 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#include "ch.h" +#include "hal.h" + +/** + * @brief Early initialization code. + * @details This initialization must be performed just after stack setup + * and before any other initialization. + */ +void __early_init(void) +{ + stm32_clock_init(); +} + +/** + * @brief Board-specific initialization code. + */ +void boardInit(void) +{ +} + diff --git a/flight/targets/aq32/fw/board.h b/flight/targets/aq32/fw/board.h new file mode 100644 index 00000000000..8687e9863ab --- /dev/null +++ b/flight/targets/aq32/fw/board.h @@ -0,0 +1,69 @@ +/* + ChibiOS/RT - Copyright (C) 2006-20s13 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +#include "pios_chibios_transition_priv.h" + +/* + * Setup for STMicroelectronics STM32F4-Discovery board. + */ + +/* + * Board identifier. + */ +#define BOARD_AEROQUAD_AQ32 +#define BOARD_NAME "aeroquad flight control" + + +/* + * Board oscillators-related settings. + * NOTE: LSE not fitted. + */ +#if !defined(STM32_LSECLK) +#define STM32_LSECLK 0 +#endif + +#if !defined(STM32_HSECLK) +#define STM32_HSECLK 8000000 +#endif + +/* + * Board voltages. + * Required for performance limits calculation. + */ +#define STM32_VDD 330 + +/* + * MCU type as defined in the ST header. + */ +#if !defined(STM32F40_41xxx) +#define STM32F40_41xxx +#endif + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif + void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* _BOARD_H_ */ + diff --git a/flight/targets/revolution/fw/chconf.h b/flight/targets/aq32/fw/chconf.h similarity index 96% rename from flight/targets/revolution/fw/chconf.h rename to flight/targets/aq32/fw/chconf.h index a4042857b33..66359c7c5fa 100644 --- a/flight/targets/revolution/fw/chconf.h +++ b/flight/targets/aq32/fw/chconf.h @@ -299,7 +299,7 @@ * @note Mutexes are recommended. */ #if !defined(CH_USE_HEAP) || defined(__DOXYGEN__) -#define CH_USE_HEAP TRUE +#define CH_USE_HEAP FALSE #endif /** @@ -313,7 +313,7 @@ * appropriate documentation. */ #if !defined(CH_USE_MALLOC_HEAP) || defined(__DOXYGEN__) -#define CH_USE_MALLOC_HEAP TRUE +#define CH_USE_MALLOC_HEAP FALSE #endif /** @@ -357,7 +357,7 @@ * @note The default is @p FALSE. */ #if !defined(CH_DBG_SYSTEM_STATE_CHECK) || defined(__DOXYGEN__) -#define CH_DBG_SYSTEM_STATE_CHECK TRUE +#define CH_DBG_SYSTEM_STATE_CHECK FALSE #endif /** @@ -368,7 +368,7 @@ * @note The default is @p FALSE. */ #if !defined(CH_DBG_ENABLE_CHECKS) || defined(__DOXYGEN__) -#define CH_DBG_ENABLE_CHECKS TRUE +#define CH_DBG_ENABLE_CHECKS FALSE #endif /** @@ -380,7 +380,7 @@ * @note The default is @p FALSE. */ #if !defined(CH_DBG_ENABLE_ASSERTS) || defined(__DOXYGEN__) -#define CH_DBG_ENABLE_ASSERTS TRUE +#define CH_DBG_ENABLE_ASSERTS FALSE #endif /** @@ -405,7 +405,7 @@ * @p panic_msg variable set to @p NULL. */ #if !defined(CH_DBG_ENABLE_STACK_CHECK) || defined(__DOXYGEN__) -#define CH_DBG_ENABLE_STACK_CHECK FALSE +#define CH_DBG_ENABLE_STACK_CHECK TRUE #endif /** @@ -417,7 +417,7 @@ * @note The default is @p FALSE. */ #if !defined(CH_DBG_FILL_THREADS) || defined(__DOXYGEN__) -#define CH_DBG_FILL_THREADS FALSE +#define CH_DBG_FILL_THREADS TRUE #endif /** @@ -447,11 +447,7 @@ /** * @brief Type of the realtime free counter value. */ -#ifndef SIM_POSIX typedef uint32_t halrtcnt_t; -#else -#include "hal_lld.h" -#endif /** * @name Macro Functions @@ -470,7 +466,17 @@ typedef uint32_t halrtcnt_t; */ #define halGetCounterValue() hal_lld_get_counter_value() -halrtcnt_t hal_lld_get_counter_value(void); +/** + * @brief Returns the current value of the system free running counter. + * @note This service is implemented by returning the content of the + * DWT_CYCCNT register. + * + * @return The value of the system free running counter of + * type halrtcnt_t. + * + * @notapi + */ +#define hal_lld_get_counter_value() DWT_CYCCNT /** * @brief Threads descriptor structure extension. diff --git a/flight/targets/revolution/fw/halconf.h b/flight/targets/aq32/fw/halconf.h similarity index 93% rename from flight/targets/revolution/fw/halconf.h rename to flight/targets/aq32/fw/halconf.h index 48f3eb42ec5..51d5061d68b 100644 --- a/flight/targets/revolution/fw/halconf.h +++ b/flight/targets/aq32/fw/halconf.h @@ -28,10 +28,7 @@ #ifndef _HALCONF_H_ #define _HALCONF_H_ -#ifdef SIM_POSIX -// Hack -#include -#endif +#include "mcuconf.h" /** * @brief Enables the TM subsystem. @@ -290,21 +287,6 @@ #define SERIAL_BUFFERS_SIZE 16 #endif -/*===========================================================================*/ -/* SERIAL_USB driver related settings. */ -/*===========================================================================*/ - -/** - * @brief Serial over USB buffers size. - * @details Configuration parameter, the buffer size must be a multiple of - * the USB data endpoint maximum packet size. - * @note The default is 256 bytes for both the transmission and receive - * buffers. - */ -#if !defined(SERIAL_USB_BUFFERS_SIZE) || defined(__DOXYGEN__) -#define SERIAL_USB_BUFFERS_SIZE 256 -#endif - /*===========================================================================*/ /* SPI driver related settings. */ /*===========================================================================*/ diff --git a/flight/targets/freedom/fw/main.c b/flight/targets/aq32/fw/main.c similarity index 81% rename from flight/targets/freedom/fw/main.c rename to flight/targets/aq32/fw/main.c index 24fb53aeb40..7a875d49283 100644 --- a/flight/targets/freedom/fw/main.c +++ b/flight/targets/aq32/fw/main.c @@ -1,11 +1,11 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Freedom Tau Labs Freedom support files + * @addtogroup Aq32 Aq32 support files * @{ * - * @file freedom.c + * @file main.c * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 * @brief Start FreeRTOS and the Modules. * @see The GNU Public License (GPL) Version 3 @@ -51,32 +51,37 @@ static struct pios_thread *initTaskHandle; /* Function Prototypes */ static void initTask(void *parameters); -/* Prototype of generated InitModules() function */ -extern void InitModules(void); - /** - * Tau Labs Main function: - * - * Initialize PiOS
- * Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
- * Start FreeRTOS Scheduler (vTaskStartScheduler)
- * If something goes wrong, blink LED1 and LED2 every 100ms - * - */ +* Tau Labs Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ int main() { /* NOTE: Do NOT modify the following start-up sequence */ /* Any new initialization functions should be added in OpenPilotInit() */ PIOS_heap_initialize_blocks(); +#if defined(PIOS_INCLUDE_CHIBIOS) + halInit(); + chSysInit(); + + boardInit(); +#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ + /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); - + /* For Revolution we use a FreeRTOS task to bring up the system so we can */ /* always rely on FreeRTOS primitive */ initTaskHandle = PIOS_Thread_Create(initTask, "init", INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY); PIOS_Assert(initTaskHandle != NULL); - + +#if defined(PIOS_INCLUDE_FREERTOS) /* Start the FreeRTOS scheduler */ vTaskStartScheduler(); @@ -87,7 +92,9 @@ int main() PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ PIOS_DELAY_WaitmS(100); \ }; - +#elif defined(PIOS_INCLUDE_CHIBIOS) + PIOS_Thread_Sleep(PIOS_THREAD_TIMEOUT_MAX); +#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ return 0; } /** @@ -95,8 +102,7 @@ int main() * * Runs board and module initialisation, then terminates. */ -void -initTask(void *parameters) +void initTask(void *parameters) { /* board driver init */ PIOS_Board_Init(); diff --git a/flight/targets/aq32/fw/mcuconf.h b/flight/targets/aq32/fw/mcuconf.h new file mode 100644 index 00000000000..ab99333f86e --- /dev/null +++ b/flight/targets/aq32/fw/mcuconf.h @@ -0,0 +1,288 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + * STM32F4xx drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the whole + * driver is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +#define STM32F4xx_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_HSI_ENABLED TRUE +#define STM32_LSI_ENABLED TRUE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_CLOCK48_REQUIRED TRUE +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PLLM_VALUE 8 +#define STM32_PLLN_VALUE 336 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 7 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV4 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_RTCSEL STM32_RTCSEL_LSI +#define STM32_RTCPRE_VALUE 8 +#define STM32_MCO1SEL STM32_MCO1SEL_HSI +#define STM32_MCO1PRE STM32_MCO1PRE_DIV1 +#define STM32_MCO2SEL STM32_MCO2SEL_SYSCLK +#define STM32_MCO2PRE STM32_MCO2PRE_DIV5 +#define STM32_I2SSRC STM32_I2SSRC_CKIN +#define STM32_PLLI2SN_VALUE 192 +#define STM32_PLLI2SR_VALUE 5 +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 +#define STM32_BKPRAM_ENABLE FALSE + +/* + * ADC driver system settings. + */ +#define STM32_ADC_ADCPRE ADC_CCR_ADCPRE_DIV4 +#define STM32_ADC_USE_ADC1 FALSE +#define STM32_ADC_USE_ADC2 FALSE +#define STM32_ADC_USE_ADC3 FALSE +#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(2, 4) +#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 2) +#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 1) +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC2_DMA_PRIORITY 2 +#define STM32_ADC_ADC3_DMA_PRIORITY 2 +#define STM32_ADC_IRQ_PRIORITY 6 +#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 6 +#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 6 +#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 6 + +/* + * CAN driver system settings. + */ +#define STM32_CAN_USE_CAN1 FALSE +#define STM32_CAN_USE_CAN2 FALSE +#define STM32_CAN_CAN1_IRQ_PRIORITY 11 +#define STM32_CAN_CAN2_IRQ_PRIORITY 11 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 15 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI20_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI21_IRQ_PRIORITY 15 +#define STM32_EXT_EXTI22_IRQ_PRIORITY 15 + +/* + * GPT driver system settings. + */ +#define STM32_GPT_USE_TIM1 FALSE +#define STM32_GPT_USE_TIM2 FALSE +#define STM32_GPT_USE_TIM3 FALSE +#define STM32_GPT_USE_TIM4 FALSE +#define STM32_GPT_USE_TIM5 FALSE +#define STM32_GPT_USE_TIM6 FALSE +#define STM32_GPT_USE_TIM7 FALSE +#define STM32_GPT_USE_TIM8 FALSE +#define STM32_GPT_USE_TIM9 FALSE +#define STM32_GPT_USE_TIM11 FALSE +#define STM32_GPT_USE_TIM12 FALSE +#define STM32_GPT_USE_TIM14 FALSE +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM6_IRQ_PRIORITY 7 +#define STM32_GPT_TIM7_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 +#define STM32_GPT_TIM9_IRQ_PRIORITY 7 +#define STM32_GPT_TIM11_IRQ_PRIORITY 7 +#define STM32_GPT_TIM12_IRQ_PRIORITY 7 +#define STM32_GPT_TIM14_IRQ_PRIORITY 7 + +/* + * I2C driver system settings. + */ +#define STM32_I2C_USE_I2C1 FALSE +#define STM32_I2C_USE_I2C2 FALSE +#define STM32_I2C_USE_I2C3 FALSE +#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6) +#define STM32_I2C_I2C2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_I2C_I2C1_IRQ_PRIORITY 5 +#define STM32_I2C_I2C2_IRQ_PRIORITY 5 +#define STM32_I2C_I2C3_IRQ_PRIORITY 5 +#define STM32_I2C_I2C1_DMA_PRIORITY 3 +#define STM32_I2C_I2C2_DMA_PRIORITY 3 +#define STM32_I2C_I2C3_DMA_PRIORITY 3 +#define STM32_I2C_I2C1_DMA_ERROR_HOOK() chSysHalt() +#define STM32_I2C_I2C2_DMA_ERROR_HOOK() chSysHalt() +#define STM32_I2C_I2C3_DMA_ERROR_HOOK() chSysHalt() + +/* + * ICU driver system settings. + */ +#define STM32_ICU_USE_TIM1 FALSE +#define STM32_ICU_USE_TIM2 FALSE +#define STM32_ICU_USE_TIM3 FALSE +#define STM32_ICU_USE_TIM4 FALSE +#define STM32_ICU_USE_TIM5 FALSE +#define STM32_ICU_USE_TIM8 FALSE +#define STM32_ICU_USE_TIM9 FALSE +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 +#define STM32_ICU_TIM9_IRQ_PRIORITY 7 + +/* + * MAC driver system settings. + */ +#define STM32_MAC_TRANSMIT_BUFFERS 2 +#define STM32_MAC_RECEIVE_BUFFERS 4 +#define STM32_MAC_BUFFERS_SIZE 1522 +#define STM32_MAC_PHY_TIMEOUT 100 +#define STM32_MAC_ETH1_CHANGE_PHY_STATE TRUE +#define STM32_MAC_ETH1_IRQ_PRIORITY 13 +#define STM32_MAC_IP_CHECKSUM_OFFLOAD 0 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_ADVANCED FALSE +#define STM32_PWM_USE_TIM1 FALSE +#define STM32_PWM_USE_TIM2 FALSE +#define STM32_PWM_USE_TIM3 FALSE +#define STM32_PWM_USE_TIM4 FALSE +#define STM32_PWM_USE_TIM5 FALSE +#define STM32_PWM_USE_TIM8 FALSE +#define STM32_PWM_USE_TIM9 FALSE +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 +#define STM32_PWM_TIM9_IRQ_PRIORITY 7 + +/* + * SERIAL driver system settings. + */ +#define STM32_SERIAL_USE_USART1 FALSE +#define STM32_SERIAL_USE_USART2 FALSE +#define STM32_SERIAL_USE_USART3 FALSE +#define STM32_SERIAL_USE_UART4 FALSE +#define STM32_SERIAL_USE_UART5 FALSE +#define STM32_SERIAL_USE_USART6 FALSE +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 +#define STM32_SERIAL_UART4_PRIORITY 12 +#define STM32_SERIAL_UART5_PRIORITY 12 +#define STM32_SERIAL_USART6_PRIORITY 12 + +/* + * SPI driver system settings. + */ +#define STM32_SPI_USE_SPI1 FALSE +#define STM32_SPI_USE_SPI2 FALSE +#define STM32_SPI_USE_SPI3 FALSE +#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 0) +#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 3) +#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) +#define STM32_SPI_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_SPI_SPI3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_SPI_SPI3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_SPI3_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) chSysHalt() + +/* + * UART driver system settings. + */ +#define STM32_UART_USE_USART1 FALSE +#define STM32_UART_USE_USART2 FALSE +#define STM32_UART_USE_USART3 FALSE +#define STM32_UART_USE_UART4 FALSE +#define STM32_UART_USE_UART5 FALSE +#define STM32_UART_USE_USART6 FALSE +#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5) +#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7) +#define STM32_UART_USART2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5) +#define STM32_UART_USART2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6) +#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1) +#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) +#define STM32_UART_UART4_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_UART_UART4_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_UART_UART5_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_UART_UART5_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 2) +#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7) +#define STM32_UART_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_UART4_IRQ_PRIORITY 12 +#define STM32_UART_UART5_IRQ_PRIORITY 12 +#define STM32_UART_USART6_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_UART4_DMA_PRIORITY 0 +#define STM32_UART_UART5_DMA_PRIORITY 0 +#define STM32_UART_USART6_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) chSysHalt() + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_OTG1 FALSE +#define STM32_USB_USE_OTG2 FALSE +#define STM32_USB_OTG1_IRQ_PRIORITY 14 +#define STM32_USB_OTG2_IRQ_PRIORITY 14 +#define STM32_USB_OTG1_RX_FIFO_SIZE 512 +#define STM32_USB_OTG2_RX_FIFO_SIZE 1024 +#define STM32_USB_OTG_THREAD_PRIO LOWPRIO +#define STM32_USB_OTG_THREAD_STACK_SIZE 128 +#define STM32_USB_OTGFIFO_FILL_BASEPRI 0 diff --git a/flight/targets/aq32/fw/memory.ld b/flight/targets/aq32/fw/memory.ld new file mode 100644 index 00000000000..a7613805595 --- /dev/null +++ b/flight/targets/aq32/fw/memory.ld @@ -0,0 +1,10 @@ +__main_stack_size__ = 0x0400; +__process_stack_size__ = 0x0400; + +MEMORY +{ + bd_info (r) : org = 0x08008000 - 0x80, len = 0x000080 + flash : org = 0x08000000 + 128k, len = 384k + ram : org = 0x20000000, len = 128k + ccmram : org = 0x10000000, len = 64k +} diff --git a/flight/targets/aq32/fw/pios_board.c b/flight/targets/aq32/fw/pios_board.c new file mode 100644 index 00000000000..f6e01489486 --- /dev/null +++ b/flight/targets/aq32/fw/pios_board.c @@ -0,0 +1,1242 @@ +/** + ****************************************************************************** + * @addtogroup AeroQuadTargets AeroQuad Targets + * @{ + * @addtogroup AQ32 AQ32 support files + * @{ + * + * @file pios_board.c + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @brief The board specific initialization routines + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Pull in the board-specific static HW definitions. + * Including .c files is a bit ugly but this allows all of + * the HW definitions to be const and static to limit their + * scope. + * + * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE + */ + +#include "board_hw_defs.c" + +#include +#include +#include +#include "hwaq32.h" +#include "manualcontrolsettings.h" +#include "modulesettings.h" + +/** + * Configuration for the MPU6000 chip + */ +#if defined(PIOS_INCLUDE_MPU6000) +#include "pios_mpu6000.h" +static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { + .vector = PIOS_MPU6000_IRQHandler, + .line = EXTI_Line4, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line4, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_mpu60x0_cfg pios_mpu6000_cfg = { + .exti_cfg = &pios_exti_mpu6000_cfg, + .default_samplerate = 666, + .interrupt_cfg = PIOS_MPU60X0_INT_CLR_ANYRD, + .interrupt_en = PIOS_MPU60X0_INTEN_DATA_RDY, + .User_ctl = PIOS_MPU60X0_USERCTL_DIS_I2C, + .Pwr_mgmt_clk = PIOS_MPU60X0_PWRMGMT_PLL_Z_CLK, + .default_filter = PIOS_MPU60X0_LOWPASS_256_HZ, + .orientation = PIOS_MPU60X0_TOP_90DEG +}; +#endif /* PIOS_INCLUDE_MPU6000 */ + +/** + * Configuration for the HMC5883 chip + */ +#if defined(PIOS_INCLUDE_HMC5883) +#include "pios_hmc5883_priv.h" +static const struct pios_exti_cfg pios_exti_hmc5883_internal_cfg __exti_config = { + .vector = PIOS_HMC5883_IRQHandler, + .line = EXTI_Line2, + .pin = { + .gpio = GPIOE, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_100MHz, + .GPIO_Mode = GPIO_Mode_IN, + .GPIO_OType = GPIO_OType_OD, + .GPIO_PuPd = GPIO_PuPd_NOPULL, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line2, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_hmc5883_cfg pios_hmc5883_internal_cfg = { + .exti_cfg = &pios_exti_hmc5883_internal_cfg, + .M_ODR = PIOS_HMC5883_ODR_75, + .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, + .Gain = PIOS_HMC5883_GAIN_1_9, + .Mode = PIOS_HMC5883_MODE_CONTINUOUS, + .Default_Orientation = PIOS_HMC5883_TOP_270DEG, +}; + +static const struct pios_hmc5883_cfg pios_hmc5883_external_cfg = { + .M_ODR = PIOS_HMC5883_ODR_75, + .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, + .Gain = PIOS_HMC5883_GAIN_1_9, + .Mode = PIOS_HMC5883_MODE_SINGLE, + .Default_Orientation = PIOS_HMC5883_TOP_270DEG, +}; +#endif /* PIOS_INCLUDE_HMC5883 */ + +/** + * Configuration for the MS5611 chip + */ +#if defined(PIOS_INCLUDE_MS5611) +#include "pios_ms5611_priv.h" +static const struct pios_ms5611_cfg pios_ms5611_cfg = { + .oversampling = MS5611_OSR_4096, + .temperature_interleaving = 1, + .use_0x76_address = true, +}; +#endif /* PIOS_INCLUDE_MS5611 */ + +/* One slot per selectable receiver group. + * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS + * NOTE: No slot in this map for NONE. + */ +uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 + +#define PIOS_COM_GPS_RX_BUF_LEN 32 +#define PIOS_COM_GPS_TX_BUF_LEN 16 + +#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 +#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 + +#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 +#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 + +#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 + +#define PIOS_COM_HOTT_RX_BUF_LEN 16 +#define PIOS_COM_HOTT_TX_BUF_LEN 16 + +#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128 + +#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 19 + +#define PIOS_COM_PICOC_RX_BUF_LEN 128 +#define PIOS_COM_PICOC_TX_BUF_LEN 128 + +#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 +#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 + +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) +#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 +uintptr_t pios_com_debug_id; +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + +bool external_mag_fail; + +uintptr_t pios_com_gps_id; +uintptr_t pios_com_telem_usb_id; +uintptr_t pios_com_telem_rf_id; +uintptr_t pios_com_vcp_id; +uintptr_t pios_com_bridge_id; +uintptr_t pios_com_mavlink_id; +uintptr_t pios_com_hott_id; +uintptr_t pios_com_frsky_sensor_hub_id; +uintptr_t pios_com_lighttelemetry_id; +uintptr_t pios_com_picoc_id; +uintptr_t pios_uavo_settings_fs_id; +uintptr_t pios_waypoints_settings_fs_id; +uintptr_t pios_internal_adc_id; +uintptr_t pios_com_frsky_sport_id; + +/* + * Setup a com port based on the passed cfg, driver and buffer sizes. rx or tx size of 0 disables rx or tx + */ +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) +static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, + const struct pios_com_driver *com_driver, uintptr_t *pios_com_id) +{ + uintptr_t pios_usart_id; + if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { + PIOS_Assert(0); + } + + uint8_t * rx_buffer; + if (rx_buf_len > 0) { + rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); + PIOS_Assert(rx_buffer); + } else { + rx_buffer = NULL; + } + + uint8_t * tx_buffer; + if (tx_buf_len > 0) { + tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); + PIOS_Assert(tx_buffer); + } else { + tx_buffer = NULL; + } + + if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, + rx_buffer, rx_buf_len, + tx_buffer, tx_buf_len)) { + PIOS_Assert(0); + } +} +#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ + +#ifdef PIOS_INCLUDE_DSM +static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, + const struct pios_com_driver *pios_usart_com_driver, + ManualControlSettingsChannelGroupsOptions channelgroup,HwAQ32DSMxModeOptions *mode) +{ + uintptr_t pios_usart_dsm_id; + if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { + PIOS_Assert(0); + } + + uintptr_t pios_dsm_id; + if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, + pios_usart_dsm_id, *mode)) { + PIOS_Assert(0); + } + + uintptr_t pios_dsm_rcvr_id; + if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; +} +#endif + +#ifdef PIOS_INCLUDE_HSUM +static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hsum_cfg, + const struct pios_com_driver *pios_usart_com_driver,enum pios_hsum_proto *proto, + ManualControlSettingsChannelGroupsOptions channelgroup) +{ + uintptr_t pios_usart_hsum_id; + if (PIOS_USART_Init(&pios_usart_hsum_id, pios_usart_hsum_cfg)) { + PIOS_Assert(0); + } + + uintptr_t pios_hsum_id; + if (PIOS_HSUM_Init(&pios_hsum_id, pios_usart_com_driver, + pios_usart_hsum_id, *proto)) { + PIOS_Assert(0); + } + + uintptr_t pios_hsum_rcvr_id; + if (PIOS_RCVR_Init(&pios_hsum_rcvr_id, &pios_hsum_rcvr_driver, pios_hsum_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[channelgroup] = pios_hsum_rcvr_id; +} +#endif + +/** + * Indicate a target-specific error code when a component fails to initialize + * 1 pulse: Flash - PIOS_Flash_Internal_Init failed + * 2 pulses: Flash - PIOS_FLASHFS_Logfs_Init failed (settings) + * 3 pulses: Flash - PIOS_FLASHFS_Logfs_Init failed (waypoints) + * 4 pulse: MPU6000 - PIOS_MPU6000_Init failed + * 5 pulses: MPU6000 - PIOS_MPU6000_Test failed + * 6 pulses: HMC5883 - PIOS_HMC5883_Init failed (internal) + * 7 pulses: HMC5883 - PIOS_HMC5883_Test failed (internal) + * 8 pulses: I2C - Internal I2C bus locked + * 9 Not Used + * 10 Not Used + * 11 Not Used + * 12 pulses: MS5611 - PIOS_MS5611_Init failed + * 13 pulses: MS5611 - PIOS_MS5611_Test failed + * 14 pulses: ADC - PIOS_INTERNAL_ADC_Init failed + * 15 pulses: ADC - PIOS_ADC_Init failed + */ + +void panic(int32_t code) { + while(1){ + for (int32_t i = 0; i < code; i++) { + PIOS_WDG_Clear(); + PIOS_LED_Toggle(PIOS_LED_ALARM); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_LED_Toggle(PIOS_LED_ALARM); + PIOS_DELAY_WaitmS(200); + } + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(100); + } +} + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ + +#include + +void PIOS_Board_Init(void) { + /* Delay system */ + PIOS_DELAY_Init(); + + const struct pios_board_info * bdinfo = &pios_board_info_blob; + +#if defined(PIOS_INCLUDE_LED) + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_I2C) + if (PIOS_I2C_Init(&pios_i2c_internal_id, &pios_i2c_internal_cfg)) { + PIOS_DEBUG_Assert(0); + } + if (PIOS_I2C_CheckClear(pios_i2c_internal_id) != 0) + panic(8); +#endif + +#if defined(PIOS_INCLUDE_SPI) + if (PIOS_SPI_Init(&pios_spi_internal_id, &pios_spi_internal_cfg)) { + PIOS_Assert(0); + } + #endif + +#if defined(PIOS_INCLUDE_FLASH) + /* Initialize all flash drivers */ + if (PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg) != 0) + panic(1); + + /* Register the partition table */ + const struct pios_flash_partition * flash_partition_table; + uint32_t num_partitions; + flash_partition_table = PIOS_BOARD_HW_DEFS_GetPartitionTable(bdinfo->board_rev, &num_partitions); + PIOS_FLASH_register_partition_table(flash_partition_table, num_partitions); + + /* Mount all filesystems */ + if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS) != 0) + panic(2); + if (PIOS_FLASHFS_Logfs_Init(&pios_waypoints_settings_fs_id, &flashfs_waypoints_cfg, FLASH_PARTITION_LABEL_WAYPOINTS) != 0) + panic(3); +#endif /* PIOS_INCLUDE_FLASH */ + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + + /* Initialize the alarms library */ + AlarmsInitialize(); + + HwAQ32Initialize(); + ModuleSettingsInitialize(); + +#if defined(PIOS_INCLUDE_RTC) + /* Initialize the real-time clock and its associated tick */ + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif + +#ifndef ERASE_FLASH + /* Initialize watchdog as early as possible to catch faults during init + * but do it only if there is no debugger connected + */ + if ((CoreDebug->DHCSR & CoreDebug_DHCSR_C_DEBUGEN_Msk) == 0) { + PIOS_WDG_Init(); + } +#endif + + /* Set up pulse timers */ + + //Timers used for inputs (4) + PIOS_TIM_InitClock(&tim_4_cfg); + + // Timers used for outputs (2, 3, 8) + PIOS_TIM_InitClock(&tim_2_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_8_cfg); + + // Timers used for inputs or outputs (1) + // Configure TIM_Period (ARR) accordingly + + PIOS_TIM_InitClock(&tim_1_cfg); + + uint8_t hw_rcvrport; + HwAQ32RcvrPortGet(&hw_rcvrport); + + switch (hw_rcvrport) { + case HWAQ32_RCVRPORT_DISABLED: + case HWAQ32_RCVRPORT_PPM: + TIM1->ARR = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1); // Timer 1 configured for PWM outputs + break; + case HWAQ32_RCVRPORT_PWM: + TIM1->ARR = 0xFFFF; // Timer 1 configured for PWM inputs + break; + } + + /* IAP System Setup */ + PIOS_IAP_Init(); + uint16_t boot_count = PIOS_IAP_ReadBootCount(); + if (boot_count < 3) { + PIOS_IAP_WriteBootCount(++boot_count); + AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); + } else { + /* Too many failed boot attempts, force hw config to defaults */ + HwAQ32SetDefaults(HwAQ32Handle(), 0); + ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); + } + +#if defined(PIOS_INCLUDE_USB) + /* Initialize USB disconnect GPIO */ + GPIO_Init(pios_usb_main_cfg.disconnect.gpio, (GPIO_InitTypeDef*)&pios_usb_main_cfg.disconnect.init); + GPIO_SetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + + /* Initialize board specific USB data */ + PIOS_USB_BOARD_DATA_Init(); + + /* Flags to determine if various USB interfaces are advertised */ + bool usb_hid_present = false; + bool usb_cdc_present = false; + +#if defined(PIOS_INCLUDE_USB_CDC) + if (PIOS_USB_DESC_HID_CDC_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; + usb_cdc_present = true; +#else + if (PIOS_USB_DESC_HID_ONLY_Init()) { + PIOS_Assert(0); + } + usb_hid_present = true; +#endif + + uintptr_t pios_usb_id; + PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); + +#if defined(PIOS_INCLUDE_USB_CDC) + + uint8_t hw_usb_vcpport; + /* Configure the USB VCP port */ + HwAQ32USB_VCPPortGet(&hw_usb_vcpport); + + if (!usb_cdc_present) { + /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ + hw_usb_vcpport = HWAQ32_USB_VCPPORT_DISABLED; + } + + uintptr_t pios_usb_cdc_id; + if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + + switch (hw_usb_vcpport) { + case HWAQ32_USB_VCPPORT_DISABLED: + break; + case HWAQ32_USB_VCPPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + case HWAQ32_USB_VCPPORT_COMBRIDGE: +#if defined(PIOS_INCLUDE_COM) + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, + tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + case HWAQ32_USB_VCPPORT_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_COM) +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) + { + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + NULL, 0, + tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ +#endif /* PIOS_INCLUDE_COM */ + break; + case HWAQ32_USB_VCPPORT_PICOC: +#if defined(PIOS_INCLUDE_COM) + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, + rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, + tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } +#endif /* PIOS_INCLUDE_USB_CDC */ + +#if defined(PIOS_INCLUDE_USB_HID) + /* Configure the usb HID port */ + uint8_t hw_usb_hidport; + HwAQ32USB_HIDPortGet(&hw_usb_hidport); + + if (!usb_hid_present) { + /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ + hw_usb_hidport = HWAQ32_USB_HIDPORT_DISABLED; + } + + uintptr_t pios_usb_hid_id; + if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { + PIOS_Assert(0); + } + + switch (hw_usb_hidport) { + case HWAQ32_USB_HIDPORT_DISABLED: + break; + case HWAQ32_USB_HIDPORT_USBTELEMETRY: +#if defined(PIOS_INCLUDE_COM) + { + uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); + uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, + rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { + PIOS_Assert(0); + } + } +#endif /* PIOS_INCLUDE_COM */ + break; + } +#endif /* PIOS_INCLUDE_USB_HID */ + + if (usb_hid_present || usb_cdc_present) { + PIOS_USBHOOK_Activate(); + } + + /* Issue USB Disconnect Pulse */ + PIOS_WDG_Clear(); + + GPIO_ResetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + + PIOS_DELAY_WaitmS(200); + + GPIO_SetBits(pios_usb_main_cfg.disconnect.gpio, pios_usb_main_cfg.disconnect.init.GPIO_Pin); + + PIOS_WDG_Clear(); +#endif /* PIOS_INCLUDE_USB */ + + /* Configure the IO ports */ + HwAQ32DSMxModeOptions hw_DSMxMode; + HwAQ32DSMxModeGet(&hw_DSMxMode); + + /* init sensor queue registration */ + PIOS_SENSORS_Init(); + + /* UART1 Port */ + uint8_t hw_uart1; + + HwAQ32Uart1Get(&hw_uart1); + + switch (hw_uart1) { + case HWAQ32_UART1_DISABLED: + break; + case HWAQ32_UART1_TELEMETRY: +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + break; + case HWAQ32_UART1_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWAQ32_UART1_MAVLINKTX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) + PIOS_Board_configure_com(&pios_usart1_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART1_HOTTTELEMETRY: +#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); +#endif /* PIOS_INCLUDE_HOTT */ + break; + case HWAQ32_UART1_FRSKYSENSORHUB: +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); +#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ + break; + case HWAQ32_UART1_LIGHTTELEMETRYTX: +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) + PIOS_Board_configure_com(&pios_usart1_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); +#endif + break; + case HWAQ32_UART1_PICOC: +#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); +#endif /* PIOS_INCLUDE_PICOC */ + break; + case HWAQ32_UART1_FRSKYSPORTTELEMETRY: +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart1_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ + break; + } + + /* UART2 Port */ + uint8_t hw_uart2; + + HwAQ32Uart2Get(&hw_uart2); + + switch (hw_uart2) { + case HWAQ32_UART2_DISABLED: + break; + case HWAQ32_UART2_GPS: +#if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); +#endif + break; + case HWAQ32_UART2_MAVLINKTX_GPS_RX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) + PIOS_Board_configure_com(&pios_usart2_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + pios_com_mavlink_id = pios_com_gps_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + } + + /* UART3 Port */ + uint8_t hw_uart3; + + HwAQ32Uart3Get(&hw_uart3); + + GPIO_Init(pios_usart3_sbus_aux_cfg.inv.gpio, (GPIO_InitTypeDef*)&pios_usart3_sbus_aux_cfg.inv.init); + GPIO_WriteBit(pios_usart3_sbus_aux_cfg.inv.gpio, pios_usart3_sbus_aux_cfg.inv.init.GPIO_Pin, pios_usart3_sbus_aux_cfg.gpio_inv_disable); + + switch (hw_uart3) { + case HWAQ32_UART3_DISABLED: + break; + case HWAQ32_UART3_TELEMETRY: +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + break; + case HWAQ32_UART3_GPS: +#if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); +#endif + break; + case HWAQ32_UART3_SBUS: + //hardware signal inverter required +#if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) + { + uintptr_t pios_usart_sbus_id; + if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart3_sbus_cfg)) { + PIOS_Assert(0); + } + uintptr_t pios_sbus_id; + if (PIOS_SBus_Init(&pios_sbus_id, &pios_usart3_sbus_aux_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { + PIOS_Assert(0); + } + uintptr_t pios_sbus_rcvr_id; + if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; + } +#endif /* PIOS_INCLUDE_SBUS */ + break; + case HWAQ32_UART3_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWAQ32_UART3_COMBRIDGE: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); +#endif + break; + case HWAQ32_UART3_MAVLINKTX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) + PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART3_MAVLINKTX_GPS_RX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + pios_com_mavlink_id = pios_com_gps_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART3_HOTTSUMD: + case HWAQ32_UART3_HOTTSUMH: +#if defined(PIOS_INCLUDE_HSUM) + { + enum pios_hsum_proto proto; + switch (hw_uart3) { + case HWAQ32_UART3_HOTTSUMD: + proto = PIOS_HSUM_PROTO_SUMD; + break; + case HWAQ32_UART3_HOTTSUMH: + proto = PIOS_HSUM_PROTO_SUMH; + break; + default: + PIOS_Assert(0); + break; + } + PIOS_Board_configure_hsum(&pios_usart3_dsm_hsum_cfg, &pios_usart_com_driver, + &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); + } +#endif /* PIOS_INCLUDE_HSUM */ + break; + case HWAQ32_UART3_HOTTTELEMETRY: +#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); +#endif /* PIOS_INCLUDE_HOTT */ + break; + case HWAQ32_UART3_FRSKYSENSORHUB: +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + GPIO_WriteBit(pios_usart3_sbus_aux_cfg.inv.gpio, pios_usart3_sbus_aux_cfg.inv.init.GPIO_Pin, pios_usart3_sbus_aux_cfg.gpio_inv_enable); + PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); +#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ + break; + case HWAQ32_UART3_LIGHTTELEMETRYTX: +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) + PIOS_Board_configure_com(&pios_usart3_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); +#endif + break; + case HWAQ32_UART3_PICOC: +#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); +#endif /* PIOS_INCLUDE_PICOC */ + break; + case HWAQ32_UART3_FRSKYSPORTTELEMETRY: +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart3_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ + break; + } + + /* UART4 Port */ + uint8_t hw_uart4; + + HwAQ32Uart4Get(&hw_uart4); + + switch (hw_uart4) { + case HWAQ32_UART4_DISABLED: + break; + case HWAQ32_UART4_TELEMETRY: +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + break; + case HWAQ32_UART4_GPS: +#if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); +#endif + break; + case HWAQ32_UART4_DSM: +#if defined(PIOS_INCLUDE_DSM) + { + PIOS_Board_configure_dsm(&pios_usart4_dsm_hsum_cfg, &pios_usart4_dsm_aux_cfg, &pios_usart_com_driver, + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); + } +#endif /* PIOS_INCLUDE_DSM */ + break; + case HWAQ32_UART4_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWAQ32_UART4_COMBRIDGE: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); +#endif + break; + case HWAQ32_UART4_MAVLINKTX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) + PIOS_Board_configure_com(&pios_usart4_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART4_MAVLINKTX_GPS_RX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + pios_com_mavlink_id = pios_com_gps_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART4_HOTTSUMD: + case HWAQ32_UART4_HOTTSUMH: +#if defined(PIOS_INCLUDE_HSUM) + { + enum pios_hsum_proto proto; + switch (hw_uart4) { + case HWAQ32_UART4_HOTTSUMD: + proto = PIOS_HSUM_PROTO_SUMD; + break; + case HWAQ32_UART4_HOTTSUMH: + proto = PIOS_HSUM_PROTO_SUMH; + break; + default: + PIOS_Assert(0); + break; + } + PIOS_Board_configure_hsum(&pios_usart4_dsm_hsum_cfg, &pios_usart_com_driver, + &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); + } +#endif /* PIOS_INCLUDE_HSUM */ + break; + case HWAQ32_UART4_HOTTTELEMETRY: +#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); +#endif /* PIOS_INCLUDE_HOTT */ + break; + case HWAQ32_UART4_FRSKYSENSORHUB: +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); +#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ + break; + case HWAQ32_UART4_LIGHTTELEMETRYTX: +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) + PIOS_Board_configure_com(&pios_usart4_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); +#endif + break; + case HWAQ32_UART4_PICOC: +#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); +#endif /* PIOS_INCLUDE_PICOC */ + break; + case HWAQ32_UART4_FRSKYSPORTTELEMETRY: +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart4_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ + break; + } + + /* UART6 Port */ + uint8_t hw_uart6; + + HwAQ32Uart6Get(&hw_uart6); + + switch (hw_uart6) { + case HWAQ32_UART6_DISABLED: + break; + case HWAQ32_UART6_TELEMETRY: +#if defined(PIOS_INCLUDE_TELEMETRY_RF) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); +#endif /* PIOS_INCLUDE_TELEMETRY_RF */ + break; + case HWAQ32_UART6_GPS: +#if defined(PIOS_INCLUDE_GPS) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); +#endif + break; + case HWAQ32_UART6_DSM: +#if defined(PIOS_INCLUDE_DSM) + { + PIOS_Board_configure_dsm(&pios_usart6_dsm_hsum_cfg, &pios_usart6_dsm_aux_cfg, &pios_usart_com_driver, + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); + } +#endif /* PIOS_INCLUDE_DSM */ + break; + case HWAQ32_UART6_DEBUGCONSOLE: +#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); +#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ + break; + case HWAQ32_UART6_COMBRIDGE: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); +#endif + break; + case HWAQ32_UART6_MAVLINKTX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) + PIOS_Board_configure_com(&pios_usart6_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART6_MAVLINKTX_GPS_RX: +#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); + pios_com_mavlink_id = pios_com_gps_id; +#endif /* PIOS_INCLUDE_MAVLINK */ + break; + case HWAQ32_UART6_HOTTSUMD: + case HWAQ32_UART6_HOTTSUMH: +#if defined(PIOS_INCLUDE_HSUM) + { + enum pios_hsum_proto proto; + switch (hw_uart6) { + case HWAQ32_UART6_HOTTSUMD: + proto = PIOS_HSUM_PROTO_SUMD; + break; + case HWAQ32_UART6_HOTTSUMH: + proto = PIOS_HSUM_PROTO_SUMH; + break; + default: + PIOS_Assert(0); + break; + } + PIOS_Board_configure_hsum(&pios_usart6_dsm_hsum_cfg, &pios_usart_com_driver, + &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); + } +#endif /* PIOS_INCLUDE_HSUM */ + break; + case HWAQ32_UART6_HOTTTELEMETRY: +#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); +#endif /* PIOS_INCLUDE_HOTT */ + break; + case HWAQ32_UART6_FRSKYSENSORHUB: +#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); +#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ + break; + case HWAQ32_UART6_LIGHTTELEMETRYTX: +#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) + PIOS_Board_configure_com(&pios_usart6_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); +#endif + break; + case HWAQ32_UART6_PICOC: +#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); +#endif /* PIOS_INCLUDE_PICOC */ + break; + case HWAQ32_UART6_FRSKYSPORTTELEMETRY: +#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_Board_configure_com(&pios_usart6_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ + break; + } + + /* Configure the rcvr port */ + switch (hw_rcvrport) { + case HWAQ32_RCVRPORT_DISABLED: + break; + case HWAQ32_RCVRPORT_PPM: +#if defined(PIOS_INCLUDE_PPM) + {uintptr_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uintptr_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; +#endif /* PIOS_INCLUDE_PPM */ + } + break; + case HWAQ32_RCVRPORT_PWM: +#if defined(PIOS_INCLUDE_PWM) + { + uintptr_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uintptr_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + } + +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uintptr_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uintptr_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + +#if defined(PIOS_INCLUDE_TIM) && defined(PIOS_INCLUDE_SERVO) +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS + switch (hw_rcvrport) { + case HWAQ32_RCVRPORT_DISABLED: + case HWAQ32_RCVRPORT_PPM: + PIOS_Servo_Init(&pios_servo_cfg_ppm_rx); + break; + case HWAQ32_RCVRPORT_PWM: + PIOS_Servo_Init(&pios_servo_cfg_pwm_rx); + break; + } +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif +#endif + + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + +#if defined(PIOS_INCLUDE_MPU6000) + if (PIOS_MPU6000_Init(pios_spi_internal_id, 0, &pios_mpu6000_cfg) != 0) + panic(4); + if (PIOS_MPU6000_Test() != 0) + panic(5); + + // To be safe map from UAVO enum to driver enum + uint8_t hw_gyro_range; + HwAQ32GyroRangeGet(&hw_gyro_range); + switch(hw_gyro_range) { + case HWAQ32_GYRORANGE_250: + PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); + break; + case HWAQ32_GYRORANGE_500: + PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); + break; + case HWAQ32_GYRORANGE_1000: + PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); + break; + case HWAQ32_GYRORANGE_2000: + PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); + break; + } + + uint8_t hw_accel_range; + HwAQ32AccelRangeGet(&hw_accel_range); + switch(hw_accel_range) { + case HWAQ32_ACCELRANGE_2G: + PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); + break; + case HWAQ32_ACCELRANGE_4G: + PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); + break; + case HWAQ32_ACCELRANGE_8G: + PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); + break; + case HWAQ32_ACCELRANGE_16G: + PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); + break; + } + + // the filter has to be set before rate else divisor calculation will fail + uint8_t hw_mpu6000_dlpf; + HwAQ32MPU6000DLPFGet(&hw_mpu6000_dlpf); + enum pios_mpu60x0_filter mpu6000_dlpf = \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_256) ? PIOS_MPU60X0_LOWPASS_256_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_188) ? PIOS_MPU60X0_LOWPASS_188_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_98) ? PIOS_MPU60X0_LOWPASS_98_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_42) ? PIOS_MPU60X0_LOWPASS_42_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_20) ? PIOS_MPU60X0_LOWPASS_20_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_10) ? PIOS_MPU60X0_LOWPASS_10_HZ : \ + (hw_mpu6000_dlpf == HWAQ32_MPU6000DLPF_5) ? PIOS_MPU60X0_LOWPASS_5_HZ : \ + pios_mpu6000_cfg.default_filter; + PIOS_MPU6000_SetLPF(mpu6000_dlpf); + + uint8_t hw_mpu6000_samplerate; + HwAQ32MPU6000RateGet(&hw_mpu6000_samplerate); + uint16_t mpu6000_samplerate = \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_200) ? 200 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_333) ? 333 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_500) ? 500 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_666) ? 666 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_1000) ? 1000 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_2000) ? 2000 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_4000) ? 4000 : \ + (hw_mpu6000_samplerate == HWAQ32_MPU6000RATE_8000) ? 8000 : \ + pios_mpu6000_cfg.default_samplerate; + PIOS_MPU6000_SetSampleRate(mpu6000_samplerate); + +#endif + +#if defined(PIOS_INCLUDE_I2C) +#if defined(PIOS_INCLUDE_HMC5883) + PIOS_WDG_Clear(); + + uint8_t Magnetometer; + HwAQ32MagnetometerGet(&Magnetometer); + + external_mag_fail = false; + + if (Magnetometer == HWAQ32_MAGNETOMETER_EXTERNAL) + { + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_OK); + + if (PIOS_I2C_Init(&pios_i2c_external_id, &pios_i2c_external_cfg)) { + PIOS_DEBUG_Assert(0); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); + } + + if (PIOS_I2C_CheckClear(pios_i2c_external_id) != 0) + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL);; + + if (PIOS_HMC5883_Init(pios_i2c_external_id, &pios_hmc5883_external_cfg) == 0) { + if (PIOS_HMC5883_Test() == 0) { + // External mag configuration was successful + + // setup sensor orientation + uint8_t ExtMagOrientation; + HwAQ32ExtMagOrientationGet(&ExtMagOrientation); + + enum pios_hmc5883_orientation hmc5883_externalOrientation = \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_TOP0DEGCW) ? PIOS_HMC5883_TOP_0DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_TOP90DEGCW) ? PIOS_HMC5883_TOP_90DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_TOP180DEGCW) ? PIOS_HMC5883_TOP_180DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_TOP270DEGCW) ? PIOS_HMC5883_TOP_270DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_BOTTOM0DEGCW) ? PIOS_HMC5883_BOTTOM_0DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_BOTTOM90DEGCW) ? PIOS_HMC5883_BOTTOM_90DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_BOTTOM180DEGCW) ? PIOS_HMC5883_BOTTOM_180DEG : \ + (ExtMagOrientation == HWAQ32_EXTMAGORIENTATION_BOTTOM270DEGCW) ? PIOS_HMC5883_BOTTOM_270DEG : \ + pios_hmc5883_external_cfg.Default_Orientation; + PIOS_HMC5883_SetOrientation(hmc5883_externalOrientation); + } + else + external_mag_fail = true; // External HMC5883 Test Failed + } + else + external_mag_fail = true; // External HMC5883 Init Failed + } + + if (Magnetometer == HWAQ32_MAGNETOMETER_INTERNAL) + { + if (PIOS_HMC5883_Init(pios_i2c_internal_id, &pios_hmc5883_internal_cfg) != 0) + panic(6); + if (PIOS_HMC5883_Test() != 0) + panic(7); + } + +#endif + + //I2C is slow, sensor init as well, reset watchdog to prevent reset here + PIOS_WDG_Clear(); + +#if defined(PIOS_INCLUDE_MS5611) + if (PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_internal_id) != 0) + panic(12); + if (PIOS_MS5611_Test() != 0) + panic(13); +#endif + + //I2C is slow, sensor init as well, reset watchdog to prevent reset here + PIOS_WDG_Clear(); + +#endif /* PIOS_INCLUDE_I2C */ + +#if defined(PIOS_INCLUDE_GPIO) + PIOS_GPIO_Init(); +#endif + +#if defined(PIOS_INCLUDE_ADC) + /* Configure the adc port(s) */ + uint8_t hw_adcport; + + HwAQ32ADCInputsGet(&hw_adcport); + + switch (hw_adcport) { + case HWAQ32_ADCINPUTS_DISABLED: + break; + case HWAQ32_ADCINPUTS_ENABLED: + { + uint32_t internal_adc_id; + + if (PIOS_INTERNAL_ADC_Init(&internal_adc_id, &pios_adc_cfg) < 0) { + PIOS_Assert(0); + panic(14); + } + + if (PIOS_ADC_Init(&pios_internal_adc_id, &pios_internal_adc_driver, internal_adc_id) < 0) + panic(15); + } + break; + } +#endif + + /* Make sure we have at least one telemetry link configured or else fail initialization */ + PIOS_Assert(pios_com_telem_rf_id || pios_com_telem_usb_id); +} + +/** + * @} + */ diff --git a/flight/targets/freedom/fw/pios_config.h b/flight/targets/aq32/fw/pios_config.h similarity index 77% rename from flight/targets/freedom/fw/pios_config.h rename to flight/targets/aq32/fw/pios_config.h index 9528e5e98fe..3f35ef594a3 100644 --- a/flight/targets/freedom/fw/pios_config.h +++ b/flight/targets/aq32/fw/pios_config.h @@ -1,38 +1,37 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Freedom Tau Labs Freedom support files + * @addtogroup Aq32 Aq32 support files * @{ * - * @file pios_config.h + * @file pios_config.h * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 * @brief Board specific options that modify PiOS capabilities * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - #ifndef PIOS_CONFIG_H #define PIOS_CONFIG_H /* Major features */ -#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_CHIBIOS #define PIOS_INCLUDE_BL_HELPER /* Enable/Disable PiOS Modules */ @@ -43,6 +42,7 @@ #define PIOS_INCLUDE_IRQ #define PIOS_INCLUDE_LED #define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_TIM #define PIOS_INCLUDE_SERVO #define PIOS_INCLUDE_SPI #define PIOS_INCLUDE_SYS @@ -55,71 +55,62 @@ #define PIOS_INCLUDE_RTC #define PIOS_INCLUDE_WDG #define PIOS_INCLUDE_FASTHEAP +#define PIOS_INCLUDE_HPWM -/* Variables related to the RFM22B functionality */ -#define PIOS_INCLUDE_RFM22B -#define PIOS_INCLUDE_RFM22B_COM -#define RFM22_EXT_INT_USE - /* Select the sensors to include */ #define PIOS_INCLUDE_HMC5883 #define PIOS_INCLUDE_MPU6000 #define PIOS_MPU6000_ACCEL +#define PIOS_MPU6000_SIMPLE_INIT_SEQUENCE #define PIOS_INCLUDE_MS5611 -#define PIOS_INCLUDE_ETASV3 -#define PIOS_INCLUDE_MPXV5004 -#define PIOS_INCLUDE_MPXV7002 -//#define PIOS_INCLUDE_HCSR04 -//#define FLASH_FREERTOS +#define FLASH_FREERTOS + /* Com systems to include */ #define PIOS_INCLUDE_COM #define PIOS_INCLUDE_COM_TELEM +#define PIOS_INCLUDE_TELEMETRY_RF #define PIOS_INCLUDE_COM_FLEXI #define PIOS_INCLUDE_MAVLINK #define PIOS_INCLUDE_HOTT #define PIOS_INCLUDE_FRSKY_SENSOR_HUB #define PIOS_INCLUDE_SESSION_MANAGEMENT #define PIOS_INCLUDE_LIGHTTELEMETRY -//#define PIOS_INCLUDE_PICOC +#define PIOS_INCLUDE_PICOC #define PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY #define PIOS_INCLUDE_GPS #define PIOS_INCLUDE_GPS_NMEA_PARSER #define PIOS_INCLUDE_GPS_UBX_PARSER -#define PIOS_OVERO_SPI - /* Supported receiver interfaces */ #define PIOS_INCLUDE_RCVR #define PIOS_INCLUDE_DSM #define PIOS_INCLUDE_HSUM -//#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_SBUS #define PIOS_INCLUDE_PPM #define PIOS_INCLUDE_PWM #define PIOS_INCLUDE_GCSRCVR -#define PIOS_INCLUDE_RFM22B_RCVR - + #define PIOS_INCLUDE_FLASH #define PIOS_INCLUDE_LOGFS_SETTINGS #define PIOS_INCLUDE_FLASH_INTERNAL -#define PIOS_INCLUDE_FLASH_JEDEC -/* Flags that alter behaviors - mostly to lower resources for CC */ +/* Flags that alter behaviours - mostly to lower resources for CC */ #define PIOS_INCLUDE_INITCALL /* Include init call structures */ #define PIOS_TELEM_PRIORITY_QUEUE /* Enable a priority queue in telemetry */ #define CAMERASTAB_POI_MODE - + /* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 1000 -#define HEAP_LIMIT_CRITICAL 500 +#define HEAP_LIMIT_WARNING 1000 +#define HEAP_LIMIT_CRITICAL 500 #define IRQSTACK_LIMIT_WARNING 150 #define IRQSTACK_LIMIT_CRITICAL 80 #define CPULOAD_LIMIT_WARNING 80 #define CPULOAD_LIMIT_CRITICAL 95 /* - * This has been calibrated 2013/03/11 using next @ 6d21c7a590619ebbc074e60cab5e134e65c9d32b. + * This has been calibrated 2014/03/01 using chibios @ fbd194c026098076bddd9e45e147828000f39d89. * Calibration has been done by disabling the init task, breaking into debugger after * approximately after 60 seconds, then doing the following math: * @@ -129,9 +120,10 @@ * configuration like number of task priorities or similar changes. * A change in the cpu load calculation or the idle task handler will invalidate this as well. */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (9873737) #define REVOLUTION +#define AQ32 #endif /* PIOS_CONFIG_H */ /** diff --git a/flight/targets/freedom/fw/pios_usb_board_data.c b/flight/targets/aq32/fw/pios_usb_board_data.c similarity index 89% rename from flight/targets/freedom/fw/pios_usb_board_data.c rename to flight/targets/aq32/fw/pios_usb_board_data.c index 501b361177f..79b47e3be6d 100644 --- a/flight/targets/freedom/fw/pios_usb_board_data.c +++ b/flight/targets/aq32/fw/pios_usb_board_data.c @@ -1,15 +1,15 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Freedom Tau Labs Freedom support files + * @addtogroup Aq32 Aq32 support files * @{ * - * @file pios_usb_board_data.c + * @file pios_usb_board_data.c * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 * @brief Board specific USB specifications * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -26,22 +26,18 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - #include "pios_usb_board_data.h" /* struct usb_*, USB_* */ #include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ #include "pios_usbhook.h" /* PIOS_USBHOOK_* */ #include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ -static const uint8_t usb_product_id[16] = { +static const uint8_t usb_product_id[10] = { sizeof(usb_product_id), USB_DESC_TYPE_STRING, - 'F', 0, - 'r', 0, - 'e', 0, - 'e', 0, - 'd', 0, - 'o', 0, - 'm', 0, + 'A', 0, + 'Q', 0, + '3', 0, + '2', 0, }; static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { @@ -55,20 +51,17 @@ static const struct usb_string_langid usb_lang_id = { .bLangID = htousbs(USB_LANGID_ENGLISH_US), }; -static const uint8_t usb_vendor_id[24] = { +static const uint8_t usb_vendor_id[18] = { sizeof(usb_vendor_id), USB_DESC_TYPE_STRING, - 'T', 0, - 'a', 0, + 'A', 0, + 'e', 0, + 'r', 0, + 'o', 0, + 'Q', 0, 'u', 0, - 'L', 0, 'a', 0, - 'b', 0, - 's', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0, + 'd', 0, }; int32_t PIOS_USB_BOARD_DATA_Init(void) diff --git a/flight/targets/freedom/fw/pios_usb_board_data.h b/flight/targets/aq32/fw/pios_usb_board_data.h similarity index 87% rename from flight/targets/freedom/fw/pios_usb_board_data.h rename to flight/targets/aq32/fw/pios_usb_board_data.h index 714c9aba043..8e53420c502 100644 --- a/flight/targets/freedom/fw/pios_usb_board_data.h +++ b/flight/targets/aq32/fw/pios_usb_board_data.h @@ -1,15 +1,15 @@ /** ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets + * @addtogroup AeroQuadTargets AeroQuad Targets * @{ - * @addtogroup Freedom Tau Labs Freedom support files + * @addtogroup Aq32 Aq32 support files * @{ * * @file pios_usb_board_data.h * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 * @brief Defines for board specific usb information * @see The GNU Public License (GPL) Version 3 - * + * *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -38,9 +38,9 @@ #include "pios_usb_defs.h" /* USB_* macros */ -#define PIOS_USB_BOARD_VENDOR_ID USB_VENDOR_ID_CLAYLOGIC -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_FREEDOM +#define PIOS_USB_BOARD_VENDOR_ID 0x20a0 +#define PIOS_USB_BOARD_PRODUCT_ID 0x4284 #define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(0, USB_OP_BOARD_MODE_FW) #define PIOS_USB_BOARD_SN_SUFFIX "+FW" diff --git a/flight/targets/freedom/gdb/bl_freedom b/flight/targets/aq32/gdb/aq32 similarity index 55% rename from flight/targets/freedom/gdb/bl_freedom rename to flight/targets/aq32/gdb/aq32 index 5798ca8f460..8cb5ca56dc4 100644 --- a/flight/targets/freedom/gdb/bl_freedom +++ b/flight/targets/aq32/gdb/aq32 @@ -1,4 +1,4 @@ define connect target remote localhost:3333 - file ./build/bl_freedom/bl_freedom.elf + file ./build/fw_aq32/fw_aq32.elf end diff --git a/flight/targets/freedom/gdb/freedom b/flight/targets/aq32/gdb/bl_aq32 similarity index 55% rename from flight/targets/freedom/gdb/freedom rename to flight/targets/aq32/gdb/bl_aq32 index 198bee00be3..c60cfa61ad0 100644 --- a/flight/targets/freedom/gdb/freedom +++ b/flight/targets/aq32/gdb/bl_aq32 @@ -1,4 +1,4 @@ define connect target remote localhost:3333 - file ./build/fw_freedom/fw_freedom.elf + file ./build/bl_aq32/bl_aq32.elf end diff --git a/flight/targets/aq32/hw/AQ32_v2.brd b/flight/targets/aq32/hw/AQ32_v2.brd new file mode 100644 index 00000000000..bbbdc0e1c68 --- /dev/null +++ b/flight/targets/aq32/hw/AQ32_v2.brd @@ -0,0 +1,32082 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Special Thanks: +Krat, KirAsh4 +AeroQuad Forums +Motors +µSD input +X +Y +Z +3V3 +Honk, Ala42 +aadamson +U10 +U9 + + + + +S ++ +- +1 +2 +3 +4 +5 +6 +7 +8 +BM +GND +BOOT0 +U1 + + + + +SBUS +RSSI +1 +2 +3 +4 +5 +6 +7 +8 +RNG +1 +2 +3 +GPS + +5V +GND +I2C +SER +OSD +AQ32 +v2.0.2 +Camera +LED +1 +2 +3 +4 +5V +GND +AI2 +AI3 +AI4 +AI5 +SW +DIO +SW +CLK +MODEM ++ +- +3V3 ++ +- +GND + + + + + + + +<b>CAPACITOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>Name +>Value + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>NAME +>Value + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +>NAME +>VALUE + + +<b>USB Series Mini-B Surface Mounted</b> + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Chip Capacitor</b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b><p> + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + + + + + +LGA08 1.25mm x 2.2mm + + + + + + + + + + + + + + + + +>NAME + + +TO-223 + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +X +Y +Z + + + + + + + + +<b>SMT SC70-5</b><p> +SOT353 - Philips Semiconductors<br> +Source: http://www.semiconductors.philips.com/acrobat_download/datasheets/74HC_HCT1G66_3.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +<h3>SparkFun Electronics' preferred foot prints</h3> +In this library you'll find connectors and sockets- basically anything that can be plugged into or onto.<br><br> +We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. +<br><br> +<b>Licensing:</b> CC v3.0 Share-Alike You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>J.S.T. Connectors</b><p> +J.S.T Mfg Co.,Ltd.<p> +http://www.jst-mfg.com<p> +<author>Created by librarian@cadsoft.de</author> + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<h3>SparkFun Electronics' preferred foot prints</h3> +In this library you'll find resistors, capacitors, inductors, test points, jumper pads, etc.<br><br> +We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. +<br><br> +<b>Licensing:</b> CC v3.0 Share-Alike You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. + + +<b>CAPACITOR</b><p> +chip + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +<b>EAGLE Design Rules</b> +<p> +Die Standard-Design-Rules sind so gewählt, dass sie für +die meisten Anwendungen passen. Sollte ihre Platine +besondere Anforderungen haben, treffen Sie die erforderlichen +Einstellungen hier und speichern die Design Rules unter +einem neuen Namen ab. +<b>Laen's PCB Order Design Rules</b> +<p> +Please make sure your boards conform to these design rules. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Since Version 6.2.2 text objects can contain more than one line, +which will not be processed correctly with this version. + + + \ No newline at end of file diff --git a/flight/targets/aq32/hw/AQ32_v2.pdf b/flight/targets/aq32/hw/AQ32_v2.pdf new file mode 100644 index 00000000000..8974c0b265b Binary files /dev/null and b/flight/targets/aq32/hw/AQ32_v2.pdf differ diff --git a/flight/targets/aq32/hw/AQ32_v2.sch b/flight/targets/aq32/hw/AQ32_v2.sch new file mode 100644 index 00000000000..5c34bafc834 --- /dev/null +++ b/flight/targets/aq32/hw/AQ32_v2.sch @@ -0,0 +1,22302 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<B>LED</B><p> +5 mm, round + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>Name +>Value + + +<b>RESISTOR</b><p> +chip + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>Name +>Value + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package E</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +<B>LED</B><p> +3 mm, round + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + +>Name +>Value +>Value + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +1007 (2518 metric) package + + + + + + + + +>NAME +>VALUE + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +1.3x1.3mm 1.7mm between. Fits Sumida CDRH2D09, CDRH2D18 inductor + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>TO 92</b> + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>Name +>Value + + +<b>Diode</b><p> +Basic small signal diode good up to 200mA. SMB footprint. Common part #: BAS16 + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>SOT-23</b> + + + + + + + +>NAME +>VALUE + + + + + +<b>SOT-223</b> + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>OMRON SWITCH</b> + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + +>NAME +>Value + + + + + + + + + + + + + + + + + + + + + + +>NAME +>Value + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Sparkfun SKU# COM-08229 + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +>Value +>Name + + + + + + +>Name +>Value + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package G</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package E</b> + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>Value +>Name + + + + + + +>Value +>Name + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + +Type J2 package for SMD supercap PRT-10317 (p# EEC-EN0F204J2) + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<B>Diode</B><p> +Basic SMA packaged diode. Good for reverse polarization protection. Common part #: MBRA140 + + + + + + + + + +>NAME +>VALUE + + +<b>USB Series A Hole Mounted</b> + + + + + + + + + + + + + + + + + + + + + +>NAME +PCB Edge + + + + +<b>USB Series A Surface Mounted</b> + + + + + + + + + + + + + + + + +>NAME + + +<b>USB Series Mini-B Hole Mounted</b> + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + +USB Series B Surface Mounted + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + +<b>USB Series Mini-B Surface Mounted</b> + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + +<b>USB Series B Hole Mounted</b> + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +<b>USB Series Mini-B Surface Mounted</b> + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + +>Name +>Value + + +<b>USB Series B Hole Mounted</b> + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + + + + +>NAME + + +Micro USB Package + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +OLD Production Socket. DO NOT USE for production boards. + + + + + + + + + + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>VALUE + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + +>VALUE + + + + + + + + + + + + + + + + + + + + + + +Date: +>LAST_DATE_TIME +Sheet: +>SHEET +REV: +TITLE: +Document Number: +>DRAWING_NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + +>NAME +>VALUE + + + + + + + +USB + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>Schematic Frame</b><p> +Standard 8.5x11 US Letter frame + + + + + + + + + + + + + +<b>Resistor</b> +Basic schematic elements and footprints for 0603, 1206, and PTH 1/10th watt (small) resistors. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>LEDs</b> +Standard schematic elements and footprints for 5mm, 3mm, 1206, and 0603 sized LEDs. 5mm - Spark Fun Electronics SKU : COM-00529 (and others) + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Resonator</b> +Small SMD resonator. This is the itty bitty 10/20MHz resonators with built in caps. CSTCE10M0G55 and CSTCE20M0V53. Footprint has been reviewed closely but hasn't been tested yet. + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Capacitor</b> +Standard 0603 ceramic capacitor, and 0.1" leaded capacitor. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Inductors</b> +Basic Inductor/Choke - 0603 and 1206. Footprints are not proven and vary greatly between part numbers. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +3 Axis Digital Compass IC + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Transistor NPN</b> +BJT configuration in SOT23 package. MMBT2222 is the common NPN we use. Double check BCE configuration again layout. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Capacitor Polarized</b> +These are standard SMD and PTH capacitors. Normally 10uF, 47uF, and 100uF in electrolytic and tantalum varieties. Always verify the external diameter of the through hole cap, it varies with capacity, voltage, and manufacturer. The EIA devices should be standard. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Diode</b> +These are standard reverse protection diodes and small signal diodes. SMA package can handle up to about 1A. SOD-323 can handle about 200mA. What the SOD-323 package when ordering, there are some mfgs out there that are 5-pin packages. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>USB Connectors</b> +<p>USB-B-PTH is fully proven SKU : PRT-00139 +<p>USB-miniB is fully proven SKU : PRT-00587 +<p>USB-A-PCB is untested. +<p>USB-A-H is throughly reviewed, but untested. Spark Fun Electronics SKU : PRT-00437 +<p>USB-B-SMT is throughly reviewed, but untested. Needs silkscreen touching up. +<p>USB-A-S has not been used/tested +<p>USB-MB-H has not been used/tested + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>microSD Socket</b> +Push-push type uSD socket. Schematic element and footprint production proven. Spark Fun Electronics SKU : PRT-00127. tDoc lines correctly indicate media card edge positions when inserting (unlocked, locked, depressed). + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + +>NAME + + + + + + + + + + + + + + + +>NAME + + + + + + + + + + + +>NAME + + + + + + + +>VALUE +>NAME + + + + + + +STM32F101/103 100 pin LQFP + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>TANTALUM CAPACITOR</b> + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>TANTALUM CAPACITOR</b> + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>TANTALUM CAPACITOR</b> + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>TANTALUM CAPACITOR</b> + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +body 5 x 5 mm, rectangle, grid 2.54 mm + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +body 7.6 x 5 mm, rectangle, grid 5.08 mm + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +body 12.7 x 7.6 mm, rectangle, grid 10.16 mm + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +body 12.5 x 12.5 mm, rectangle, grid 10.16 mm + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 4 mm, grid 2.54 mm + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 4 mm, grid 2.54 mm + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 5 mm, grid 2.54 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 6 mm, grid 2.54 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 6 mm, grid 2.54 mm + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 7 mm, grid 2.54 mm + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 7 mm, grid 2.54 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 10 mm, grid 5.08 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 11 mm, grid 5.08 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 11 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 6 mm, grid 5.08 mm + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 6 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 7 mm, grid 5.08 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 7 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 9 mm, grid 5.08 mm + + + + + + + + + + + + +>NAME +>VALUE +TT + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 9 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +rectangle, grid 2.54 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +rectangle, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +rectangle, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +rectangle, grid 10.16 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +rectangle, grid 10.16 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 4.5 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 5.0 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 7.0 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 6.0 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 8.0 mm, grid 5.08 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 1.8 mm, diameter 4 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 15.24 mm, diameter 5 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 15.24 mm, diameter 6 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 15.24 mm, diameter 9 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 4 mm + + + + + + + + +>NAME +>VALUE + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 5 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 6 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 7 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 4 mm, + + + + + + + + +>NAME +>VALUE + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2 mm, diameter 4 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.032 mm, diameter 5 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 22.86 mm, diameter 10 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 22.86 mm, diameter 6 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 22.86 mm, diameter 9 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 3.5 mm, diameter 10 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 25.4 mm, diameter 10 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 25.4 mm, diameter 9 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 3.5 mm, diameter 8 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 10 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 12 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 16 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 35.56 mm, diameter 12 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 14 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 16 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 30.48 mm, diameter 18 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 45.72 mm, diameter 16 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 45.72 mm, diameter 18 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 45.72 mm, diameter 21 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 45.72 mm, diameter 22 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 45.72 mm, diameter 25 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 10.5 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 13 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.05 mm, diameter 4 mm + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 5 mm + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 6 mm + + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 8.5 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 50 mm, diameter 25 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 50 mm, diameter 30 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 55 mm, diameter 25 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 55 mm, diameter 30 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 5.08 mm, diameter 9 mm + + + + + + + + + +>NAME +>VALUE + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 7.62 mm, diameter 16 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 7.62 mm, diameter 18 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 10.16 mm, diameter 20 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 10.16 mm, diameter 22.5 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 10.16 mm, diameter 25 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 10.16 mm, diameter 30 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 10.16 mm, diameter 35 mm + + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>Aluminum electrolytic capacitors</b> reflow soldering<p> +SMD (Chip) Standard 085 CS<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> wave soldering<p> +SMD (Chip) Standard 085 CS<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> reflow soldering<p> +SMD (Chip) Standard 085 CS<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> wave soldering<p> +SMD (Chip) Standard 085 CS<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> reflow soldering<p> +SMD (Chip) Long Life 139 CLL<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> wave soldering<p> +SMD (Chip) Long Life 139 CLL<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> reflow soldering<p> +SMD (Chip) Long Life 139 CLL<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors</b> wave soldering<p> +SMD (Chip) Long Life 139 CLL<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, High temperature 140 CLH<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, High temperature 140 CLH<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, High temperature 140 CLH<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, very low impedance 150 CLZ<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, very low impedance 150 CLZ<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors SMD (Chip)</b><p> +Long life base plate, very low impedance 150 CLZ<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +SMD (Chip) Long Life Vertical 153 CLV<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +High Temperature solid electrolytic SMD 175 TMP<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Aluminum electrolytic capacitors</b><p> +High Temperature solid electrolytic SMD 175 TMP<p> +http://www.bccomponents.com/ + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Chip Capacitor Type KEMET A / EIA 3216-18 reflow solder</b><p>KEMET S / EIA 3216-12 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET A / EIA 3216-18 Wave solder</b><p> +KEMET S / EIA 3216-12 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET B / EIA 3528-21 reflow solder</b><p>KEMET T / EIA 3528-12 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET B / EIA 3528-21 Wave solder</b><p> +KEMET T / EIA 3528-12 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET C / EIA 6032-28 reflow solder</b><p>KEMET U / EIA 6032-15 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET C / EIA 6032-28 Wafe solder</b><p> +KEMET U / EIA 6032-15 + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET D / EIA 7343-21</b><p>KEMET V / EIA 7343-20, KEMET X / EIA 7343-43 reflow solder + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET D / EIA 7343-21</b><p> +KEMET V / EIA 7343-20, KEMET X / EIA 7343-43 Wafe solder + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET E / EIA 7260-38 reflow solder</b> + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET E / EIA 7260-38 Wafe solder</b> + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET R/EIA 2012-12 reflow solder</b> + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor Type KEMET R/EIA 2012-12 Wafe solder</b> + + + + + + +>NAME +>VALUE + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package A</b> + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package B</b> + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package C</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package D</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package E</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package F</b> + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +<b>Panasonic Aluminium Electrolytic Capacitor VS-Serie Package G</b> + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +diameter 5 mm, grid 2.54 mm + + + + + + + + + + + + + + + + + +>NAME +>VALUE +TT + + + + + + + +<b>ELECTROLYTIC CAPACITOR</b><p> +grid 2.54 mm, diameter 6 mm + + + + + + + + + + + + +>NAME +>VALUE + + + +<b>Chip Capacitor </b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194, B 45 197, B 45 198<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor</b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor</b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor </b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194, B 45 197, B 45 198<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor </b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194, B 45 197, B 45 198<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor </b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194, B 45 197, B 45 198<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>Chip Capacitor </b> Polar tantalum capacitors with solid electrolyte<p> +Siemens Matsushita Components B 45 194, B 45 197, B 45 198<br> +Source: www.farnell.com/datasheets/247.pdf + + + + + + +>NAME +>VALUE + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b><p> +Source: e_os_all.pdf + + + + +>NAME +>VALUE + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SANYO OSCON Capacitor</b> SMD type with conductive polymer electrolyte<p> +Source: e_os_all.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 10 x 10 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 4 x 5.8 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 5 x 5.8 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 6.3 x 5.8 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 6.3 x 7.7 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>ALUMINUM ELECTROLYTIC CAPACITORS</b> UD Series 8 x 10 mm<p> +Source: http://products.nichicon.co.jp/en/pdf/XJA043/e-ud.pdf + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +Source: http://download.siliconexpert.com/pdfs/2005/02/24/Semi_Ap/2/VSH/Resistor/dcrcwfre.pdf + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> wave soldering<p> +Source: http://download.siliconexpert.com/pdfs/2005/02/24/Semi_Ap/2/VSH/Resistor/dcrcwfre.pdf + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.10 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.12 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.10 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.12 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +type 0207, grid 10 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0207, grid 12 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0207, grid 15mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0207, grid 2.5 mm + + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type 0207, grid 5 mm + + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type 0207, grid 7.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0309, grid 10mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0309, grid 12.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 12.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 15 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 3.81 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0414, grid 15 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0414, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0617, grid 17.5 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0617, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0617, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0922, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0613, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0613, grid 15 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0817, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +0817 + + + + +<b>RESISTOR</b><p> +type 0817, grid 6.35 mm + + + + + + +>NAME +>VALUE +0817 + + + +<b>RESISTOR</b><p> +type V234, grid 12.5 mm + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type V235, grid 17.78 mm + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type V526-0, grid 2.5 mm + + + + + + + + + + +>NAME +>VALUE + + +<b>Mini MELF 0102 Axial</b> + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0922, grid 7.5 mm + + + + + + +>NAME +>VALUE +0922 + + + +<b>CECC Size RC2211</b> Reflow Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC2211</b> Wave Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC3715</b> Reflow Soldering<p> +source Beyschlag + + + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC3715</b> Wave Soldering<p> +source Beyschlag + + + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC6123</b> Reflow Soldering<p> +source Beyschlag + + + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC6123</b> Wave Soldering<p> +source Beyschlag + + + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type RDH, grid 15 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +RDH + + + + +<b>RESISTOR</b><p> +type 0309, grid 2.5 mm + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> chip<p> +Source: http://www.vishay.com/docs/20008/dcrcw.pdf + + +>NAME +>VALUE + + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RNC55<br> +Source: VISHAY .. vta56.pdf + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RNC60<br> +Source: VISHAY .. vta56.pdf + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RBR52<br> +Source: VISHAY .. vta56.pdf + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RBR53<br> +Source: VISHAY .. vta56.pdf + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RBR54<br> +Source: VISHAY .. vta56.pdf + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RBR55<br> +Source: VISHAY .. vta56.pdf + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Bulk Metal� Foil Technology</b>, Tubular Axial Lead Resistors, Meets or Exceeds MIL-R-39005 Requirements<p> +MIL SIZE RBR56<br> +Source: VISHAY .. vta56.pdf + + + + + + + + + + +>NAME +>VALUE + + + + +<b>Package 4527</b><p> +Source: http://www.vishay.com/docs/31059/wsrhigh.pdf + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + +>NAME +>VALUE + + +<b>Wirewound Resistors, Precision Power</b><p> +Source: VISHAY wscwsn.pdf + + + + + + +>NAME +>VALUE + + +<b>CRCW1218 Thick Film, Rectangular Chip Resistors</b><p> +Source: http://www.vishay.com .. dcrcw.pdf + + + + +>NAME +>VALUE + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 2.4 x 4.4 mm + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 2.5 x 5 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 3 x 5 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 4 x 5 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 5 x 5 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm, outline 6 x 5 mm + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 mm + 5 mm, outline 2.4 x 7 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 + 5 mm, outline 2.5 x 7.5 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 + 5 mm, outline 3.5 x 7.5 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 + 5 mm, outline 4.5 x 7.5 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 2.5 + 5 mm, outline 5.5 x 7.5 mm + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 2.4 x 4.4 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 2.5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 4.5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 3 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 5.5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 7.5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +Horizontal, grid 5 mm, outline 7.5 x 7.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>CAPACITOR</b><p> +grid 7.5 mm, outline 3.2 x 10.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 7.5 mm, outline 4.2 x 10.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 7.5 mm, outline 5.2 x 10.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 10.2 mm, outline 4.3 x 13.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 10.2 mm, outline 5.4 x 13.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 10.2 mm, outline 6.4 x 13.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 10.2 mm + 15.2 mm, outline 6.2 x 18.4 mm + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 15 mm, outline 5.4 x 18.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 15 mm, outline 6.4 x 18.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 15 mm, outline 7.2 x 18.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 15 mm, outline 8.4 x 18.3 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 15 mm, outline 9.1 x 18.2 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 22.5 mm, outline 6.2 x 26.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 22.5 mm, outline 7.4 x 26.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 22.5 mm, outline 8.7 x 26.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 22.5 mm, outline 10.8 x 26.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 22.5 mm, outline 11.3 x 26.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 9.3 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 11.3 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 13.4 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 20.5 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 32.5 mm, outline 13.7 x 37.4 mm + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 32.5 mm, outline 16.2 x 37.4 mm + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 32.5 mm, outline 18.2 x 37.4 mm + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 37.5 mm, outline 19.2 x 41.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 37.5 mm, outline 20.3 x 41.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 5 mm, outline 3.5 x 7.5 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 37.5 mm, outline 15.5 x 41.8 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 7.5 mm, outline 6.3 x 10.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 15.4 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>CAPACITOR</b><p> +grid 27.5 mm, outline 17.3 x 31.6 mm + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Ceramic Chip Capacitor KEMET 0204 reflow solder</b><p> +Metric Code Size 1005 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 0603 reflow solder</b><p> +Metric Code Size 1608 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 0805 reflow solder</b><p> +Metric Code Size 2012 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 1206 reflow solder</b><p> +Metric Code Size 3216 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 1210 reflow solder</b><p> +Metric Code Size 3225 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 1812 reflow solder</b><p> +Metric Code Size 4532 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 1825 reflow solder</b><p> +Metric Code Size 4564 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 2220 reflow solder</b><p>Metric Code Size 5650 + + + + +>NAME +>VALUE + + + + +<b>Ceramic Chip Capacitor KEMET 2225 reflow solder</b><p>Metric Code Size 5664 + + + + +>NAME +>VALUE + + + + +Source: http://www.avxcorp.com/docs/catalogs/cx5r.pdf + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b> wave soldering<p> + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +type 0204, grid 5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0204, grid 7.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0204, grid 2.5 mm + + + + + + +>NAME +>VALUE + + +<b>Chip Monolithic Ceramic Capacitors</b> Medium Voltage High Capacitance for General Use<p> +Source: http://www.murata.com .. GRM43DR72E224KW01.pdf + + + + + + +>NAME +>VALUE + + + + +<b>CAPACITOR</b><p> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b> + + + + + + + + +>NAME +>VALUE + + + + + +<b>CAPACITOR</b><p> +Source: AVX .. aphvc.pdf + + + + +>NAME +>VALUE + + + + +<b>CAPACITOR</b><p> +Source: AVX .. aphvc.pdf + + + + +>NAME +>VALUE + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME +>VALUE + + + + + + +<B>POLARIZED CAPACITOR</B>, American symbol + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<B>RESISTOR</B>, American symbol + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<B>CAPACITOR</B>, American symbol + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE + + + + + + +>VALUE + + + + +>VALUE + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +chip, wave soldering + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.10 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.12 W + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.10 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.12 W + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +MELF 0.25 W + + + + + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +type 0207, grid 10 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0207, grid 12 mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0207, grid 15mm + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0207, grid 2.5 mm + + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type 0207, grid 5 mm + + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type 0207, grid 7.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0309, grid 10mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0309, grid 12.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 12.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 15 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0411, grid 3.81 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0414, grid 15 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0414, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0617, grid 17.5 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0617, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0617, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0922, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<b>RESISTOR</b><p> +type 0613, grid 5 mm + + + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0613, grid 15 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0817, grid 22.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +0817 + + + + +<b>RESISTOR</b><p> +type 0817, grid 6.35 mm + + + + + + +>NAME +>VALUE +0817 + + + +<b>RESISTOR</b><p> +type V234, grid 12.5 mm + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type V235, grid 17.78 mm + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type V526-0, grid 2.5 mm + + + + + + + + + + +>NAME +>VALUE + + +<b>Mini MELF 0102 Axial</b> + + + + +>NAME +>VALUE + + + +<b>RESISTOR</b><p> +type 0922, grid 7.5 mm + + + + + + +>NAME +>VALUE +0922 + + + +<b>CECC Size RC2211</b> Reflow Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC2211</b> Wave Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC3715</b> Reflow Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC3715</b> Wave Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC6123</b> Reflow Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>CECC Size RC6123</b> Wave Soldering<p> +source Beyschlag + + + + + + +>NAME +>VALUE + + +<b>RESISTOR</b><p> +type RDH, grid 15 mm + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +RDH + + + + +<b>RESISTOR</b><p> +type 0309, grid 2.5 mm + + + + + + +>NAME +>VALUE + + + + + +<b>RESISTOR</b><p> +type 0204, grid 5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0204, grid 7.5 mm + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + +<b>RESISTOR</b><p> +type 0204, grid 2.5 mm + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + +<B>RESISTOR</B>, American symbol + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +LGA08 1.25mm x 2.2mm + + + + + + + + + + + + + + + + +>NAME + + +TO-223 + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +Pressure sensor 10cm + + + + + + + + + + + + + + + + + + + + + + +LOD Volt Reg + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE +X +Y +Z + + + + + + + + + + +ITG/MPU +>Value + + + + + + + + + + + + + + + + + + +ITG-3200 3-axis gyro, digital output, qfn24 package + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE + + + + + +<b>SUPPLY SYMBOL</b> + + + + + + + + + + + + + + + + +<b>Small Outline Transistor</b><p> +SOT753 - Philips Semiconductors<br> +Source: http://www.semiconductors.philips.com/acrobat_download/datasheets/74HC_HCT1G66_3.pdf + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + +<b>SMT SC70-5</b><p> +SOT353 - Philips Semiconductors<br> +Source: http://www.semiconductors.philips.com/acrobat_download/datasheets/74HC_HCT1G66_3.pdf + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +>NAME +GND +VCC + + + + + + +2-input <b>EXCLUSIV-OR</b> gate + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<h3>SparkFun Electronics' preferred foot prints</h3> +In this library you'll find connectors and sockets- basically anything that can be plugged into or onto.<br><br> +We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. +<br><br> +<b>Licensing:</b> CC v3.0 Share-Alike You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +JST crimp connector: 1mm pitch, top entry + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +2mm SMD side-entry connector. tDocu layer indicates the actual physical plastic housing. +/- indicate SparkFun standard batteries and wiring. + + + + + + + + + + + + + +>Name +>Value ++ +- + + + + + + + + + + + + + + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + +This footprint was designed to help hold the alignment of a through-hole component (i.e. 6-pin header) while soldering it into place. +You may notice that each hole has been shifted either up or down by 0.005 of an inch from it's more standard position (which is a perfectly straight line). +This slight alteration caused the pins (the squares in the middle) to touch the edges of the holes. Because they are alternating, it causes a "brace" +to hold the component in place. 0.005 has proven to be the perfect amount of "off-center" position when using our standard breakaway headers. +Although looks a little odd when you look at the bare footprint, once you have a header in there, the alteration is very hard to notice. Also, +if you push a header all the way into place, it is covered up entirely on the bottom side. This idea of altering the position of holes to aid alignment +will be further integrated into the Sparkfun Library for other footprints. It can help hold any component with 3 or more connection pins. + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>Name +>Value ++ +- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + +>Name +>Value ++ +- + + +<H3>JST-2-PTH-KIT</h3> +2-Pin JST, through-hole connector<br> +<br> +<b>Warning:</b> This is the KIT version of this package. This package has a smaller diameter top stop mask, which doesn't cover the diameter of the pad. This means only the bottom side of the pads' copper will be exposed. You'll only be able to solder to the bottom side. + + + + + + + + + +>Name +>Value ++ +- + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + + + + + + + + + + + +>VALUE +>NAME + + + + + + +<b>Header 12</b> +Standard 12-pin 0.1" header. Use with straight break away headers (SKU : PRT-00116), right angle break away headers (PRT-00553), swiss pins (PRT-00743), machine pins (PRT-00117), and female headers (PRT-00115). + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Header 9</b> +Standard 9-pin 0.1" header. Use with straight break away headers (SKU : PRT-00116), right angle break away headers (PRT-00553), swiss pins (PRT-00743), machine pins (PRT-00117), and female headers (PRT-00115). + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Header 8</b> +Standard 8-pin 0.1" header. Use with straight break away headers (SKU : PRT-00116), right angle break away headers (PRT-00553), swiss pins (PRT-00743), machine pins (PRT-00117), and female headers (PRT-00115). + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Header 2</b> +Standard 2-pin 0.1" header. Use with straight break away headers (SKU : PRT-00116), right angle break away headers (PRT-00553), swiss pins (PRT-00743), machine pins (PRT-00117), and female headers (PRT-00115). Molex polarized connector foot print use with SKU : PRT-08233 with associated crimp pins and housings. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>J.S.T. Connectors</b><p> +J.S.T Mfg Co.,Ltd.<p> +http://www.jst-mfg.com<p> +<author>Created by librarian@cadsoft.de</author> + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, top entry type</b> + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, top entry type</b> + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, side entry type</b> + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<b>Shrouded Header, top entry type</b> + + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + +>NAME +>VALUE + + + + +>NAME + + + + + +<b>Disconnectable Crimp style connector, 1.0mm pitch</b><br>4 contacts + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Disconnectable Crimp style connector, 1.0mm pitch</b><br>6 contacts + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<b>Disconnectable Crimp style connector, 1.0mm pitch</b><br>7 contacts + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +<h3>SparkFun Electronics' preferred foot prints</h3> +In this library you'll find resistors, capacitors, inductors, test points, jumper pads, etc.<br><br> +We've spent an enormous amount of time creating and checking these footprints and parts, but it is the end user's responsibility to ensure correctness and suitablity for a given componet or application. If you enjoy using this library, please buy one of our products at www.sparkfun.com. +<br><br> +<b>Licensing:</b> CC v3.0 Share-Alike You are welcome to use this library for commercial purposes. For attribution, we ask that when you begin to sell your device using our footprint, you email us with a link to the product being sold. We want bragging rights that we helped (in a very small part) to create your 8th world wonder. We would like the opportunity to feature your device on our homepage. + + +<b>CAPACITOR</b><p> +chip + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>Name +>Value + + + + + + + + + +>Name +>Value + + + + + + +>NAME +>VALUE + + + + + + + + +>Name +>Value + + + + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +>Name +>Value + + + + + + + + + + + + +>Name +>Value + + + + + + + + + + +>NAME +>VALUE + + + + + + + + + + +>NAME +>VALUE + + + + + +CTZ3 Series land pattern for variable capacitor - CTZ3E-50C-W1-PF + + + + + + + + + + + + + + + + + +>NAME +>VALUE + + +<h3>CAP-PTH-SMALL-KIT</h3> +Commonly used for small ceramic capacitors. Like our 0.1uF (http://www.sparkfun.com/products/8375) or 22pF caps (http://www.sparkfun.com/products/8571).<br> +<br> +<b>Warning:</b> This is the KIT version of this package. This package has a smaller diameter top stop mask, which doesn't cover the diameter of the pad. This means only the bottom side of the pads' copper will be exposed. You'll only be able to solder to the bottom side. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +This is the "EZ" version of the .1" spaced ceramic thru-hole cap.<br> +It has reduced top mask to make it harder to put the component on the wrong side of the board. + + + + + + + +>Name +>Value + + + + + + + + + + +>NAME +>VALUE + + + + + + + + +<b>Capacitor</b> +Standard 0603 ceramic capacitor, and 0.1" leaded capacitor. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Receiver: TIM1, TIM4 +Motor: TIM8, TIM2, TIM3 +Servo: TIM5 +USB Pull up +USB Disconnect +MPU6000 + + + + +Sensors +uSD + + + + +GPS + + + + +TIM8_CH4 +TIM8_CH1 +TIM8_CH3 +TIM8_CH2 +TIM5_CH2 +TIM5_CH1 +TIM5_CH3 ++5V +CS +DIN +SCK +DOUT +RESET +GND +DOUT +3.3V +DIN +GND +AI1 (Range Finder) + + + + +AI2 +AI3 +AI4 +AI5 +Do not install +R37 and R38 +if using SPI +For F1 use R54 0ohm +For F4 use C54 2.2uF +Licensed As: CC-BY-SA + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Since Version 6.2.2 text objects can contain more than one line, +which will not be processed correctly with this version. + + + diff --git a/flight/targets/aq32/hw/AQ32_v2_BOM.xlsx b/flight/targets/aq32/hw/AQ32_v2_BOM.xlsx new file mode 100644 index 00000000000..9b8797f6f80 Binary files /dev/null and b/flight/targets/aq32/hw/AQ32_v2_BOM.xlsx differ diff --git a/flight/targets/aq32/hw/aq32Taulabs.xlsx b/flight/targets/aq32/hw/aq32Taulabs.xlsx new file mode 100644 index 00000000000..509be41c7c3 Binary files /dev/null and b/flight/targets/aq32/hw/aq32Taulabs.xlsx differ diff --git a/flight/targets/aq32/hw/eagle.epf b/flight/targets/aq32/hw/eagle.epf new file mode 100644 index 00000000000..490245c455c --- /dev/null +++ b/flight/targets/aq32/hw/eagle.epf @@ -0,0 +1,361 @@ +[Eagle] +Version="06 04 00" +Platform="Windows" +Serial="6F13ACE5CA-LSR-WLM-1CS" +Globals="Globals" +Desktop="Desktop" + +[Globals] +AutoSaveProject=1 +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/19inch.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/40xx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/41xx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/45xx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74ac-logic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74ttl-din.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74xx-eu.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74xx-little-de.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74xx-little-us.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/74xx-us.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/751xx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SAMTEC-TSW-xxx-D-xx_By_element14_Batch_1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SAMTEC-TSW-xxx-D_By_element14_Batch_1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SAMTEC-TSW-xxx-Q-xx_By_element14_Batch_1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SAMTEC-TSW-xxx-T-xx_By_element14_Batch_1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SAMTEC-Txx_By_element14_Batch_1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/SparkFun-Connectors.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/advanced-test-technologies.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/agilent-technologies.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/allegro.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/altera-cyclone-II.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/altera-cyclone-III.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/altera-stratix-iv.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/altera.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/am29-memory.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/amd-mach.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/amd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/amis.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/analog-devices.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ase.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/atmel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/austriamicrosystems.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/avago.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/axis.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/battery.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/belton-engineering.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/burr-brown.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/busbar.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/buzzer.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/c-trimm.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/california-micro-devices.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/capacitor-wima.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/chipcard-siemens.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/cirrus-logic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-3m.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-4ucon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-champ.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-micromatch.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-mt.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-mt6.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-quick.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp-te.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-amphenol.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-avx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-berg.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-bosch.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-chipcard-iso7816.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-coax.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-commcon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-conrad.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-cpci.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-cui.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-cypressindustries.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-deutsch.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-dil.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-ebyelectro.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-elco.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-erni.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-faston.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-fci.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-friwo.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-garry.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-harting-h.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-harting-ml.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-harting-v.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-harting.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-hirose.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-hirschmann.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-jack.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-jae.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-jst.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-jst2.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-kycon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-kyocera-elco.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-lemo.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-leotronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-lsta.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-lstb.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-lumberg.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-ml.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-molex.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-neutrik_ag.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-omron.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-panasonic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-panduit.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-pc.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-pc104.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-254.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-3.81.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-350.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-500.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-508.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-762.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-me_max.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-mkds_5.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-phoenix-smkdsp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-ptr500.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-pulse.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-rib.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-samtec.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-shallin.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-shiua-chyuan.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-stewart.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-stocko.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-subd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-sullinselectronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-thomas-betts.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-tyco.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-tycoelectronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-vg.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-wago-500.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-wago-508.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-wago.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-wago255.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-weidmueller-sl35.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-wenzhou-yihua.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-xmultiple.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/con-yamaichi.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/crystal.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/csr.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/cypress.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/davicom.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/dc-dc-converter.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/dimensions.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/diode.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/discrete.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/display-hp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/display-kingbright.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/display-lcd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/docu-dummy.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/eagle-ltspice.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ecl.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/em-microelectronic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/etx-board.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/exar.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fairchild-semic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/farnell.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fiber-optic-hp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fiber-optic-siemens.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fifo.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/flexipanel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fox-electronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/frames.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/freescale.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ftdichip.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fujitsu.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/fuse.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/gennum.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/halo-electronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/heatsink.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/holes.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/holtek.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ic-package.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/inductor-coilcraft.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/inductor-neosid.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/inductor-nkl.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/inductors.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/infineon-tricore.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/infineon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/intersil-techwell.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/intersil.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ir.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/isd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/johanson-technology.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/jst-ph.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/jst_eph.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/jump-0r-smd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/jumper.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lantronix.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lattice.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lc-filter.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/led-7-segment.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/led-citizen-electronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/led-lumiled.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/led.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lem.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/linear-technology.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/linear.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/linx.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/logo.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lprs.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lsi-computer-systems.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/lumiled.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/marks.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/maxim.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/maxstream.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/melexis.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-hitachi.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-idt.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-micron.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-motorola-dram.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-nec.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-samsung.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory-sram.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/memory.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/mems.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micrel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-cyrod.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-fujitsu.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-harris.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-hitachi.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-infineon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-intel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-mc68000.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-motorola.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-philips.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-renesas.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-samsung.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micro-siemens.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/microchip.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micron.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/micronas.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/microphon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/microwave.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/midori-sensor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/minicircuits.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/mitsubishi-semiconductor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/motorola-sensor-driver.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/murata-filter.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/murata-sensor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/nanotec.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/national-instruments.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/national-semiconductor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/nec-lqfp100-pack.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/nec.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/nrj-semiconductor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/omnivision.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/on-semiconductor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-honeywell-3000.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-honeywell-4000.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-honeywell.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-micro-linear.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-trans-siemens.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-transmittter-hp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/opto-vishay.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/optocoupler.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pal.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/philips-semiconductors.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/photo-elements.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/piher.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pinhead.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/plcc-socket.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pld-intel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/plxtech.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pot-vitrohm.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pot-xicor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/pot.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ptc-ntc.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/quantum-research-group.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/rcl.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/recom-international.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/rectifier.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ref-packages-longpad.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/ref-packages.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/relay.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/renesas.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-bourns.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-dil.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-net.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-power.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-ruf.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-shunt.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor-sil.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/resistor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/rf-micro-devices.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/rf-solutions.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/rohm.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/semicon-smd-ipc.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sensor-comus-group.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sensor-heraeus.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sensor-infratec.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sharp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/silabs.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sim-technology.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/sipex.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/smd-ipc.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/smd-special.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/solomon-systech.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/solpad.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/special-drill.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/special.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/st-microelectronics.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/supertex.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/supply1.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/supply2.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-alps.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-coto.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-dil.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-misc.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-omron.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-raychem.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch-reed.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/switch.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/telcom.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/telecontrolli.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/telefunken.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/testpad.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/texas-sn55-sn75.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/texas.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/toshiba.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/traco-electronic.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trafo-bei.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trafo-hammondmfg.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trafo-siemens.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trafo-xicon.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trafo.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transformer-pulse.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-fet.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-neu-to92.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-npn.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-pnp.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-power.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor-small-signal.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/transistor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/triac.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/trimble.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/tripas.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/u-blox.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/uln-udn.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/v-reg-micrel.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/v-reg.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/varistor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/wafer-scale-psd.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/wirepad.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/xicor.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/xilinx-virtex-v5.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/xilinx-xc18v.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/xilinx-xc9.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/xilinx-xcv.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/zetex.lbr" +UsedLibrary="C:/Program Files (x86)/EAGLE-6.4.0/lbr/zilog.lbr" + +[Win_1] +Type="Control Panel" +Loc="136 179 985 706" +State=2 +Number=0 + +[Desktop] +Screen="1440 900" +Window="Win_1" \ No newline at end of file diff --git a/flight/targets/freedom/target-defs.mk b/flight/targets/aq32/target-defs.mk similarity index 78% rename from flight/targets/freedom/target-defs.mk rename to flight/targets/aq32/target-defs.mk index 54e8824088f..8a8ca1d2259 100644 --- a/flight/targets/freedom/target-defs.mk +++ b/flight/targets/aq32/target-defs.mk @@ -1,10 +1,10 @@ # Add this board to the list of buildable boards -ALL_BOARDS += freedom +ALL_BOARDS += aq32 # Set the cpu architecture here that matches your STM32 # Should be one of: f1,f3,f4 -freedom_cpuarch := f4 +aq32_cpuarch := f4 # Short name of this board (used to display board name in parallel builds) # Should be exactly 4 characters long. -freedom_short := 'free' +aq32_short := 'aq32' diff --git a/flight/targets/bu/f1/Makefile b/flight/targets/bu/f1/Makefile index 190135e32a4..950129560da 100644 --- a/flight/targets/bu/f1/Makefile +++ b/flight/targets/bu/f1/Makefile @@ -102,13 +102,20 @@ EXTRAINCDIRS += $(BUCOMMONDIR) # Path to Linker-Scripts LINKERSCRIPTPATH = $(PIOSSTM32F10X) + +PAYLOAD_FILE = $(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin + # Place project-specific -D (define) and/or # -U options for C here. +# +# This exists to prevent ccache from caching compilation results when the file +# has changed. md5sum is used on linux and Windows; cksum is used on mac. +CDEFS += -DBU_HASH=$(shell md5sum "$(PAYLOAD_FILE)" 2>/dev/null | cut -d ' ' -f 1 || cksum "$(PAYLOAD_FILE)" | cut -d ' ' -f 1) CDEFS = -DSTM32F10X_$(MODEL) #CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) CDEFS += -DUSE_STDPERIPH_DRIVER CDEFS += -DUSE_$(BOARD) -CDEFS += -DBU_PAYLOAD_FILE=$(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin +CDEFS += -DBU_PAYLOAD_FILE=$(PAYLOAD_FILE) # Place project-specific -D and/or -U options for # Assembler with preprocessor here. diff --git a/flight/targets/bu/f3/Makefile b/flight/targets/bu/f3/Makefile index bd86dbeb241..0c4abc279d9 100644 --- a/flight/targets/bu/f3/Makefile +++ b/flight/targets/bu/f3/Makefile @@ -82,11 +82,16 @@ EXTRAINCDIRS += $(BUBOARDDIR) EXTRAINCDIRS += $(BUARCHDIR) EXTRAINCDIRS += $(BUCOMMONDIR) +PAYLOAD_FILE = $(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin # Place project-specific -D (define) and/or # -U options for C here. CDEFS += -DMEM_SIZE=$(FW_BANK_SIZE) CDEFS += -DUSE_$(BOARD) -CDEFS += -DBU_PAYLOAD_FILE=$(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin +CDEFS += -DBU_PAYLOAD_FILE=$(PAYLOAD_FILE) + +# This exists to prevent ccache from caching compilation results when the file +# has changed. md5sum is used on linux and Windows; cksum is used on mac. +CDEFS += -DBU_HASH=$(shell md5sum "$(PAYLOAD_FILE)" 2>/dev/null | cut -d ' ' -f 1 || cksum "$(PAYLOAD_FILE)" | cut -d ' ' -f 1) # Place project-specific -D and/or -U options for # Assembler with preprocessor here. diff --git a/flight/targets/bu/f4/Makefile b/flight/targets/bu/f4/Makefile index cbb1721f749..c628c2ed173 100644 --- a/flight/targets/bu/f4/Makefile +++ b/flight/targets/bu/f4/Makefile @@ -81,11 +81,16 @@ EXTRAINCDIRS += $(BUBOARDDIR) EXTRAINCDIRS += $(BUARCHDIR) EXTRAINCDIRS += $(BUCOMMONDIR) +PAYLOAD_FILE = $(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin # Place project-specific -D (define) and/or # -U options for C here. CDEFS += -DMEM_SIZE=$(FW_BANK_SIZE) CDEFS += -DUSE_$(BOARD) -CDEFS += -DBU_PAYLOAD_FILE=$(ROOT_DIR)/build/bl_$(BOARD_NAME)/bl_$(BOARD_NAME).bin +CDEFS += -DBU_PAYLOAD_FILE=$(PAYLOAD_FILE) + +# This exists to prevent ccache from caching compilation results when the file +# has changed. md5sum is used on linux and Windows; cksum is used on mac. +CDEFS += -DBU_HASH=$(shell md5sum "$(PAYLOAD_FILE)" 2>/dev/null | cut -d ' ' -f 1 || cksum "$(PAYLOAD_FILE)" | cut -d ' ' -f 1) # Place project-specific -D and/or -U options for # Assembler with preprocessor here. diff --git a/flight/targets/colibri/fw/Makefile b/flight/targets/colibri/fw/Makefile index 93e65b8e15d..56662c2f5d7 100644 --- a/flight/targets/colibri/fw/Makefile +++ b/flight/targets/colibri/fw/Makefile @@ -118,7 +118,6 @@ SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(FLIGHTLIB)/timeutils.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/atmospheric_math.c SRC += $(MATHLIB)/pid.c @@ -134,6 +133,7 @@ SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c @@ -153,9 +153,6 @@ SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c SRC += $(PIOSCOMMON)/pios_streamfs.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -319,8 +316,11 @@ LDFLAGS += -lc -lgcc -lm LDFLAGS += -Wl,--warn-common LDFLAGS += -Wl,--fatal-warnings -#Linker scripts +# Linker scripts LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) -include $(MAKE_INC_DIR)/firmware-common.mk +include ./UAVObjects.inc + +UAVO_NAV = YES +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/colibri/fw/UAVObjects.inc b/flight/targets/colibri/fw/UAVObjects.inc index 796736f50a3..7a3497ffac5 100644 --- a/flight/targets/colibri/fw/UAVObjects.inc +++ b/flight/targets/colibri/fw/UAVObjects.inc @@ -1,7 +1,7 @@ ############################################################################### # @file Makefile # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup @@ -29,101 +29,15 @@ UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings UAVOBJSRCFILENAMES += loggingsettings UAVOBJSRCFILENAMES += loggingstats -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwcolibri -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += hottsettings UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/colibri/fw/pios_board.c b/flight/targets/colibri/fw/pios_board.c index 00ea31a5cc3..01b27a58977 100644 --- a/flight/targets/colibri/fw/pios_board.c +++ b/flight/targets/colibri/fw/pios_board.c @@ -200,7 +200,6 @@ uintptr_t pios_com_telem_usb_id; uintptr_t pios_com_telem_rf_id; uintptr_t pios_com_vcp_id; uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; uintptr_t pios_com_mavlink_id; uintptr_t pios_com_hott_id; uintptr_t pios_com_frsky_sensor_hub_id; @@ -259,7 +258,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg const struct pios_com_driver *pios_usart_com_driver, ManualControlSettingsChannelGroupsOptions - channelgroup, uint8_t * bind) + channelgroup, HwColibriDSMxModeOptions * mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -269,7 +268,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg uintptr_t pios_dsm_id; if (PIOS_DSM_Init (&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -653,8 +652,8 @@ void PIOS_Board_Init(void) #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwColibriDSMxBindGet(&hw_DSMxBind); + HwColibriDSMxModeOptions hw_DSMxMode; + HwColibriDSMxModeGet(&hw_DSMxMode); /* init sensor queue registration */ PIOS_SENSORS_Init(); @@ -720,8 +719,8 @@ void PIOS_Board_Init(void) PIOS_Board_configure_dsm(&pios_usart1_dsm_hsum_cfg, &pios_usart1_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, - &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, + &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -876,8 +875,8 @@ void PIOS_Board_Init(void) PIOS_Board_configure_dsm(&pios_usart2_dsm_hsum_cfg, &pios_usart2_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, - &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, + &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -1039,8 +1038,8 @@ void PIOS_Board_Init(void) PIOS_Board_configure_dsm(&pios_usart3_dsm_hsum_cfg, &pios_usart3_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, - &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, + &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -1168,8 +1167,8 @@ void PIOS_Board_Init(void) PIOS_Board_configure_dsm(&pios_usart4_dsm_hsum_cfg, &pios_usart4_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, - &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, + &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; diff --git a/flight/targets/colibri/fw/pios_config.h b/flight/targets/colibri/fw/pios_config.h index a65380dc3b2..a987508c710 100644 --- a/flight/targets/colibri/fw/pios_config.h +++ b/flight/targets/colibri/fw/pios_config.h @@ -124,8 +124,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (9873737) -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/targets/coptercontrol/board-info/board_hw_defs.c b/flight/targets/coptercontrol/board-info/board_hw_defs.c index 770785d474a..1e241e3eb8f 100644 --- a/flight/targets/coptercontrol/board-info/board_hw_defs.c +++ b/flight/targets/coptercontrol/board-info/board_hw_defs.c @@ -1334,6 +1334,17 @@ const struct pios_ppm_cfg pios_ppm_cfg = { .num_channels = 1, }; +const struct pios_ppm_cfg pios_ppm_pin8_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[5], + .num_channels = 1, +}; #endif /* PIOS_INCLUDE_PPM */ /* diff --git a/flight/targets/coptercontrol/board-info/cmsis_system.c b/flight/targets/coptercontrol/board-info/cmsis_system.c index 41805ec5674..4b747dd8e31 100644 --- a/flight/targets/coptercontrol/board-info/cmsis_system.c +++ b/flight/targets/coptercontrol/board-info/cmsis_system.c @@ -201,6 +201,10 @@ static void SetSysClock(void); * @{ */ +// this is required for the system_rcc code because +// of the clock rate switching in naze32 +uint32_t hse_value = 8000000; + /** * @brief Setup the microcontroller system * Initialize the Embedded Flash Interface, the PLL and update the diff --git a/flight/targets/coptercontrol/fw/Makefile b/flight/targets/coptercontrol/fw/Makefile index 6403780fcbe..4ac22a2935a 100644 --- a/flight/targets/coptercontrol/fw/Makefile +++ b/flight/targets/coptercontrol/fw/Makefile @@ -1,7 +1,7 @@ ############################################################################### # @file Makefile # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 # @addtogroup # @{ # @addtogroup @@ -53,8 +53,6 @@ ENABLE_AUX_UART ?= NO # @endgroup Compile Options -NAVIGATION ?= NO - # @startgroup Optional modules # @groupbrief Optional module and driver defaults USE_CAMERASTAB ?= YES @@ -64,7 +62,6 @@ USE_TXPID ?= YES USE_I2C ?= NO USE_ALTITUDE ?= NO USE_AUTOTUNE ?= YES -TEST_FAULTS ?= NO USE_UAVOMAVLINKBRIDGE ?= YES USE_UAVOLIGHTTELEMETRYBRIDGE ?= NO USE_UAVOFRSKYSENSORHUBBRIDGE ?= YES @@ -98,9 +95,6 @@ else $(error "Altitude module (USE_ALTITUDE=YES) requires i2c (USE_I2C=YES)") endif endif -ifeq ($(TEST_FAULTS), YES) -OPTMODULES += Fault -endif ifeq ($(USE_AUTOTUNE), YES) OPTMODULES += Autotune endif @@ -114,15 +108,8 @@ ifeq ($(USE_BATTERY), YES) OPTMODULES += Battery endif # List of mandatory modules to include -ifeq ($(NAVIGATION), YES) -MODULES += State/coptercontrol -MODULES += PathFollower -CFLAGS += -DNAVIGATION -else -MODULES += Attitude/coptercontrol -endif +MODULES += Attitude/smallf1 MODULES += Stabilization Actuator ManualControl FirmwareIAP -# MODULES += PathFollower/coptercontrol # Telemetry must be last to grab the optional modules (why?) MODULES += Telemetry @@ -178,67 +165,6 @@ SRC += $(OPTESTS)/test_common.c SRC += $(OPTESTS)/$(TESTAPP).c endif -## UAVOBJECTS -ifndef TESTAPP -SRC += $(OPUAVSYNTHDIR)/accessorydesired.c -SRC += $(OPUAVSYNTHDIR)/objectpersistence.c -SRC += $(OPUAVSYNTHDIR)/gcstelemetrystats.c -SRC += $(OPUAVSYNTHDIR)/flighttelemetrystats.c -SRC += $(OPUAVSYNTHDIR)/faultsettings.c -SRC += $(OPUAVSYNTHDIR)/flightstatus.c -SRC += $(OPUAVSYNTHDIR)/systemstats.c -SRC += $(OPUAVSYNTHDIR)/systemalarms.c -SRC += $(OPUAVSYNTHDIR)/systemsettings.c -SRC += $(OPUAVSYNTHDIR)/stabilizationdesired.c -SRC += $(OPUAVSYNTHDIR)/stabilizationsettings.c -SRC += $(OPUAVSYNTHDIR)/actuatorcommand.c -SRC += $(OPUAVSYNTHDIR)/actuatordesired.c -SRC += $(OPUAVSYNTHDIR)/actuatorsettings.c -SRC += $(OPUAVSYNTHDIR)/accels.c -SRC += $(OPUAVSYNTHDIR)/gyros.c -SRC += $(OPUAVSYNTHDIR)/attitudeactual.c -SRC += $(OPUAVSYNTHDIR)/manualcontrolcommand.c -SRC += $(OPUAVSYNTHDIR)/watchdogstatus.c -SRC += $(OPUAVSYNTHDIR)/manualcontrolsettings.c -SRC += $(OPUAVSYNTHDIR)/mixersettings.c -SRC += $(OPUAVSYNTHDIR)/firmwareiapobj.c -SRC += $(OPUAVSYNTHDIR)/attitudesettings.c -SRC += $(OPUAVSYNTHDIR)/camerastabsettings.c -SRC += $(OPUAVSYNTHDIR)/cameradesired.c -SRC += $(OPUAVSYNTHDIR)/gpsposition.c -SRC += $(OPUAVSYNTHDIR)/gpsvelocity.c -SRC += $(OPUAVSYNTHDIR)/hwcoptercontrol.c -SRC += $(OPUAVSYNTHDIR)/modulesettings.c -SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c -SRC += $(OPUAVSYNTHDIR)/receiveractivity.c -SRC += $(OPUAVSYNTHDIR)/systemident.c -SRC += $(OPUAVSYNTHDIR)/taskinfo.c -SRC += $(OPUAVSYNTHDIR)/mixerstatus.c -SRC += $(OPUAVSYNTHDIR)/mwratesettings.c -SRC += $(OPUAVSYNTHDIR)/ratedesired.c -SRC += $(OPUAVSYNTHDIR)/baroaltitude.c -SRC += $(OPUAVSYNTHDIR)/txpidsettings.c -SRC += $(OPUAVSYNTHDIR)/fixedwingairspeeds.c -SRC += $(OPUAVSYNTHDIR)/fixedwingpathfollowerstatus.c -SRC += $(OPUAVSYNTHDIR)/fixedwingpathfollowersettingscc.c -SRC += $(OPUAVSYNTHDIR)/pathstatus.c -SRC += $(OPUAVSYNTHDIR)/pathdesired.c -SRC += $(OPUAVSYNTHDIR)/homelocation.c -SRC += $(OPUAVSYNTHDIR)/poilocation.c -SRC += $(OPUAVSYNTHDIR)/positionactual.c -SRC += $(OPUAVSYNTHDIR)/tabletinfo.c -SRC += $(OPUAVSYNTHDIR)/velocityactual.c -SRC += $(OPUAVSYNTHDIR)/airspeedactual.c -SRC += $(OPUAVSYNTHDIR)/sensorsettings.c -SRC += $(OPUAVSYNTHDIR)/flightbatterystate.c -SRC += $(OPUAVSYNTHDIR)/flightbatterysettings.c -SRC += $(OPUAVSYNTHDIR)/trimanglessettings.c -SRC += $(OPUAVSYNTHDIR)/trimangles.c -SRC += $(OPUAVSYNTHDIR)/ubloxinfo.c -SRC += $(OPUAVSYNTHDIR)/sessionmanaging.c - -endif - ## PIOS Hardware (STM32F10x) SRC += $(PIOSSTM32F10X)/pios_sys.c SRC += $(PIOSSTM32F10X)/pios_led.c @@ -250,7 +176,6 @@ SRC += $(PIOSSTM32F10X)/pios_i2c.c SRC += $(PIOSSTM32F10X)/pios_spi.c SRC += $(PIOSSTM32F10X)/pios_ppm.c SRC += $(PIOSSTM32F10X)/pios_pwm.c -SRC += $(PIOSSTM32F10X)/pios_dsm.c SRC += $(PIOSSTM32F10X)/pios_debug.c SRC += $(PIOSSTM32F10X)/pios_gpio.c SRC += $(PIOSSTM32F10X)/pios_exti.c @@ -280,6 +205,7 @@ SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c SRC += $(PIOSCOMMON)/pios_flash_jedec.c SRC += $(PIOSCOMMON)/pios_adxl345.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_mpu6000.c SRC += $(PIOSCOMMON)/pios_com.c SRC += $(PIOSCOMMON)/pios_rcvr.c @@ -310,7 +236,6 @@ SRC += $(STATEESTIMATIONLIB)/premerlani_gps.c SRC += $(STATEESTIMATIONLIB)/premerlani_dcm.c endif SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c @@ -599,5 +524,6 @@ LDFLAGS += -Wl,--fatal-warnings LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld +include ./UAVObjects.inc include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/coptercontrol/fw/UAVObjects.inc b/flight/targets/coptercontrol/fw/UAVObjects.inc new file mode 100644 index 00000000000..f42cae73a3c --- /dev/null +++ b/flight/targets/coptercontrol/fw/UAVObjects.inc @@ -0,0 +1 @@ +UAVOBJSRCFILENAMES += hwcoptercontrol diff --git a/flight/targets/coptercontrol/fw/pios_board.c b/flight/targets/coptercontrol/fw/pios_board.c index 26652af7901..60a880805b2 100644 --- a/flight/targets/coptercontrol/fw/pios_board.c +++ b/flight/targets/coptercontrol/fw/pios_board.c @@ -47,7 +47,7 @@ /* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS + * eg. PWM, PPM, GCS, DSM, DSM, SBUS * NOTE: No slot in this map for NONE. */ uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; @@ -397,8 +397,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the main IO port */ - uint8_t hw_DSMxBind; - HwCopterControlDSMxBindGet(&hw_DSMxBind); + HwCopterControlDSMxModeOptions hw_DSMxMode; + HwCopterControlDSMxModeGet(&hw_DSMxMode); uint8_t hw_mainport; HwCopterControlMainPortGet(&hw_mainport); @@ -473,11 +473,15 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); } + if (hw_DSMxMode >= HWCOPTERCONTROL_DSMXMODE_BIND3PULSES) { + hw_DSMxMode = HWCOPTERCONTROL_DSMXMODE_AUTODETECT; /* Do not try to bind through XOR */ + } + uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, &pios_dsm_main_cfg, &pios_usart_com_driver, - pios_usart_dsm_id, 0)) { + pios_usart_dsm_id, hw_DSMxMode)) { PIOS_Assert(0); } @@ -485,7 +489,7 @@ void PIOS_Board_Init(void) { if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { PIOS_Assert(0); } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT] = pios_dsm_rcvr_id; + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM] = pios_dsm_rcvr_id; } #endif /* PIOS_INCLUDE_DSM */ break; @@ -704,7 +708,7 @@ void PIOS_Board_Init(void) { if (PIOS_DSM_Init(&pios_dsm_id, &pios_dsm_flexi_cfg, &pios_usart_com_driver, - pios_usart_dsm_id, hw_DSMxBind)) { + pios_usart_dsm_id, hw_DSMxMode)) { PIOS_Assert(0); } @@ -712,7 +716,7 @@ void PIOS_Board_Init(void) { if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { PIOS_Assert(0); } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT] = pios_dsm_rcvr_id; + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM] = pios_dsm_rcvr_id; } #endif /* PIOS_INCLUDE_DSM */ break; @@ -856,11 +860,13 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_PWM */ break; case HWCOPTERCONTROL_RCVRPORT_PPM: + case HWCOPTERCONTROL_RCVRPORT_PPMONPIN8: case HWCOPTERCONTROL_RCVRPORT_PPMOUTPUTS: #if defined(PIOS_INCLUDE_PPM) { uintptr_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + PIOS_PPM_Init(&pios_ppm_id, + (hw_rcvrport == HWCOPTERCONTROL_RCVRPORT_PPMONPIN8) ? &pios_ppm_pin8_cfg : &pios_ppm_cfg); uintptr_t pios_ppm_rcvr_id; if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { @@ -918,6 +924,7 @@ void PIOS_Board_Init(void) { case HWCOPTERCONTROL_RCVRPORT_DISABLED: case HWCOPTERCONTROL_RCVRPORT_PWM: case HWCOPTERCONTROL_RCVRPORT_PPM: + case HWCOPTERCONTROL_RCVRPORT_PPMONPIN8: case HWCOPTERCONTROL_RCVRPORT_PPMPWM: PIOS_Servo_Init(&pios_servo_cfg); break; diff --git a/flight/targets/coptercontrol/fw/pios_config.h b/flight/targets/coptercontrol/fw/pios_config.h index 97e18998512..b78c2504ac8 100644 --- a/flight/targets/coptercontrol/fw/pios_config.h +++ b/flight/targets/coptercontrol/fw/pios_config.h @@ -109,8 +109,8 @@ #define PIOS_STABILIZATION_STACK_SIZE 624 #define PIOS_TELEM_STACK_SIZE 500 #define PIOS_EVENTDISPATCHER_STACK_SIZE 720 -#define PIOS_MAVLINK_STACK_SIZE 600 -#define PIOS_COMUSBBRIDGE_STACK_SIZE 296 +#define PIOS_MAVLINK_STACK_SIZE 496 +#define PIOS_COMUSBBRIDGE_STACK_SIZE 480 #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 // This can't be too high to stop eventdispatcher thread overflowing @@ -119,11 +119,8 @@ /* PIOS Initcall infrastructure */ #define PIOS_INCLUDE_INITCALL +#define SMALLF1 #define COPTERCONTROL -// Conditional related to making CC run navigation -#if defined(NAVGIATION) -#define PIOS_GPS_PROVIDES_AIRSPEED -#endif #endif /* PIOS_CONFIG_H */ /** diff --git a/flight/targets/discoveryf4/fw/Makefile b/flight/targets/discoveryf4/fw/Makefile index e6a0df4b354..eb5b4bcaf93 100644 --- a/flight/targets/discoveryf4/fw/Makefile +++ b/flight/targets/discoveryf4/fw/Makefile @@ -106,9 +106,6 @@ SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List any extra directories to look for include files here. # Each directory must be seperated by a space. @@ -263,7 +260,11 @@ LDFLAGS += -lc -lgcc -lm LDFLAGS += -Wl,--warn-common LDFLAGS += -Wl,--fatal-warnings -#Linker scripts +# Linker scripts LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +UAVO_MINIMAL=YES + +include ./UAVObjects.inc include $(MAKE_INC_DIR)/firmware-common.mk + diff --git a/flight/targets/discoveryf4/fw/UAVObjects.inc b/flight/targets/discoveryf4/fw/UAVObjects.inc index 29cfff01048..2a3ca2942af 100644 --- a/flight/targets/discoveryf4/fw/UAVObjects.inc +++ b/flight/targets/discoveryf4/fw/UAVObjects.inc @@ -1,7 +1,7 @@ ############################################################################### # @file UAVObjects.inc # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup @@ -28,25 +28,4 @@ # (all architectures) UAVOBJSRCFILENAMES = -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus -UAVOBJSRCFILENAMES += modulesettings UAVOBJSRCFILENAMES += hwdiscoveryf4 -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += gcsreceiver -UAVOBJSRCFILENAMES += faultsettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/discoveryf4/fw/pios_board.c b/flight/targets/discoveryf4/fw/pios_board.c index 8b0ac946642..3a7f38b7691 100644 --- a/flight/targets/discoveryf4/fw/pios_board.c +++ b/flight/targets/discoveryf4/fw/pios_board.c @@ -44,7 +44,7 @@ #include "modulesettings.h" /* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, DSMMAINPORT, DSMFLEXIPORT, SBUS + * eg. PWM, PPM, GCS, DSM, DSM, SBUS * NOTE: No slot in this map for NONE. */ uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; diff --git a/flight/targets/discoveryf4/fw/pios_config.h b/flight/targets/discoveryf4/fw/pios_config.h index 5d7b23e0c03..06323c7445c 100644 --- a/flight/targets/discoveryf4/fw/pios_config.h +++ b/flight/targets/discoveryf4/fw/pios_config.h @@ -103,8 +103,7 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) -//This enables altitude hold in manualcontrol module -//#define REVOLUTION +#define NO_SENSORS #endif /* PIOS_CONFIG_H */ /** diff --git a/flight/targets/flyingf3/fw/Makefile b/flight/targets/flyingf3/fw/Makefile index 510956ef419..4dd50e7c33c 100644 --- a/flight/targets/flyingf3/fw/Makefile +++ b/flight/targets/flyingf3/fw/Makefile @@ -127,8 +127,8 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/atmospheric_math.c @@ -146,6 +146,7 @@ SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_bmp085.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c @@ -166,9 +167,6 @@ SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -327,5 +325,8 @@ LDFLAGS += -Wl,--fatal-warnings #Linker scripts LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) -include $(MAKE_INC_DIR)/firmware-common.mk +include ./UAVObjects.inc + +UAVO_NAV = YES +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/flyingf3/fw/UAVObjects.inc b/flight/targets/flyingf3/fw/UAVObjects.inc index 59b1f1a9c11..0deb28e9852 100644 --- a/flight/targets/flyingf3/fw/UAVObjects.inc +++ b/flight/targets/flyingf3/fw/UAVObjects.inc @@ -1,7 +1,7 @@ ############################################################################### # @file Makefile # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup @@ -29,98 +29,12 @@ UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwflyingf3 -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive UAVOBJSRCFILENAMES += groundpathfollowersettings UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += txpidsettings UAVOBJSRCFILENAMES += i2cvm UAVOBJSRCFILENAMES += i2cvmuserprogram -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/flyingf3/fw/pios_board.c b/flight/targets/flyingf3/fw/pios_board.c index 212032738bb..39b22d6c930 100644 --- a/flight/targets/flyingf3/fw/pios_board.c +++ b/flight/targets/flyingf3/fw/pios_board.c @@ -193,7 +193,6 @@ uintptr_t pios_com_mavlink_id; uintptr_t pios_com_hott_id; uintptr_t pios_com_frsky_sensor_hub_id; uintptr_t pios_com_lighttelemetry_id; -uintptr_t pios_com_overo_id; uintptr_t pios_com_can_id; uintptr_t pios_com_frsky_sport_id; @@ -241,7 +240,7 @@ static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cf #ifdef PIOS_INCLUDE_DSM static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) + ManualControlSettingsChannelGroupsOptions channelgroup,HwFlyingF3DSMxModeOptions *mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -250,7 +249,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -578,8 +577,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwFlyingF3DSMxBindGet(&hw_DSMxBind); + HwFlyingF3DSMxModeOptions hw_DSMxMode; + HwFlyingF3DSMxModeGet(&hw_DSMxMode); /* UART1 Port */ uint8_t hw_uart1; @@ -620,7 +619,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart1_dsm_hsum_cfg, &pios_usart1_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -729,7 +728,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart2_dsm_hsum_cfg, &pios_usart2_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -837,7 +836,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart3_dsm_hsum_cfg, &pios_usart3_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -945,7 +944,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart4_dsm_hsum_cfg, &pios_usart4_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -1053,7 +1052,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart5_dsm_hsum_cfg, &pios_usart5_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; diff --git a/flight/targets/flyingf3/fw/pios_config.h b/flight/targets/flyingf3/fw/pios_config.h index f38f9567549..16db6ccb3b1 100644 --- a/flight/targets/flyingf3/fw/pios_config.h +++ b/flight/targets/flyingf3/fw/pios_config.h @@ -126,8 +126,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (2175780) -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/targets/flyingf4/fw/Makefile b/flight/targets/flyingf4/fw/Makefile index 0694e3abfca..27af8a556ca 100644 --- a/flight/targets/flyingf4/fw/Makefile +++ b/flight/targets/flyingf4/fw/Makefile @@ -122,8 +122,8 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/atmospheric_math.c @@ -142,6 +142,7 @@ SRC += $(PIOSCOMMON)/pios_mpxv5004.c SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c @@ -161,9 +162,6 @@ SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -326,109 +324,11 @@ LDFLAGS += -lc -lgcc -lm LDFLAGS += -Wl,--warn-common LDFLAGS += -Wl,--fatal-warnings -#Linker scripts +# Linker scripts LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +include ./UAVObjects.inc -# Define programs and commands. -REMOVE = rm -f - -# List of all source files. -ALLSRC = $(ASRC) $(SRC) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) -# Define all listing files (used for make clean). -LSTFILES = $(addprefix $(OUTDIR)/, $(addsuffix .lst, $(ALLSRCBASE))) -# Define all depedency-files (used for make clean). -DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) - -# Default target. -all: gccversion build - -build: elf hex bin lss sym - -# Link: create ELF output file from object files. -$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) - -# Assemble: create object files from assembler source files. -$(foreach src, $(ASRC), $(eval $(call ASSEMBLE_TEMPLATE, $(src)))) - -# Compile: create object files from C source files. -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) - -# Compile: create object files from C++ source files. -$(foreach src, $(CPPSRC), $(eval $(call COMPILE_CPP_TEMPLATE, $(src)))) - -# Compile: create assembler files from C source files. ARM/Thumb -$(eval $(call PARTIAL_COMPILE_TEMPLATE, SRC)) - -$(OUTDIR)/$(TARGET).bin.o: $(OUTDIR)/$(TARGET).bin - -$(eval $(call TLFW_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(BOARD_TYPE),$(BOARD_REVISION))) - -# Add jtag targets (program and wipe) -$(eval $(call JTAG_TEMPLATE,$(OUTDIR)/$(TARGET).bin,$(FW_BANK_BASE),$(FW_BANK_SIZE),$(OPENOCD_JTAG_CONFIG),$(OPENOCD_CONFIG))) - -.PHONY: elf lss sym hex bin bino tlfw -elf: $(OUTDIR)/$(TARGET).elf -lss: $(OUTDIR)/$(TARGET).lss -sym: $(OUTDIR)/$(TARGET).sym -hex: $(OUTDIR)/$(TARGET).hex -bin: $(OUTDIR)/$(TARGET).bin -bino: $(OUTDIR)/$(TARGET).bin.o -tlfw: $(OUTDIR)/$(TARGET).tlfw - -# Display sizes of sections. -$(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) - -# Generate Doxygen documents -docs: - doxygen $(DOXYGENDIR)/doxygen.cfg - -# Install: install binary file with prefix/suffix into install directory -install: $(OUTDIR)/$(TARGET).tlfw -ifneq ($(INSTALL_DIR),) - @echo $(MSG_INSTALLING) $(call toprel, $<) - $(V1) mkdir -p $(INSTALL_DIR) - $(V1) $(INSTALL) $< $(INSTALL_DIR)/$(INSTALL_PFX)$(TARGET)$(INSTALL_SFX).tlfw -else - $(error INSTALL_DIR must be specified for $@) -endif - -# Target: clean project. -clean: clean_list - -clean_list : - @echo $(MSG_CLEANING) - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).map - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).elf - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).hex - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).sym - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).lss - $(V1) $(REMOVE) $(OUTDIR)/$(TARGET).bin.o - $(V1) $(REMOVE) $(ALLOBJ) - $(V1) $(REMOVE) $(LSTFILES) - $(V1) $(REMOVE) $(DEPFILES) - $(V1) $(REMOVE) $(SRC:.c=.s) - $(V1) $(REMOVE) $(CPPSRC:.cpp=.s) - -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -ifdef ComSpec -$(shell md $(subst /,\\,$(OUTDIR)) 2>NUL) -else -$(shell mkdir -p $(OUTDIR) 2>/dev/null) -endif - -# Include the dependency files. -ifdef ComSpec --include $(shell md $(subst /,\\,$(OUTDIR))\dep 2>NUL) $(wildcard $(OUTDIR)/dep/*) -else --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) -endif +UAVO_NAV = YES -# Listing of phony targets. -.PHONY : all build clean clean_list install docs +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/flyingf4/fw/UAVObjects.inc b/flight/targets/flyingf4/fw/UAVObjects.inc index 5292d6aa604..57b7e40cd3d 100644 --- a/flight/targets/flyingf4/fw/UAVObjects.inc +++ b/flight/targets/flyingf4/fw/UAVObjects.inc @@ -1,7 +1,7 @@ ############################################################################### # @file Makefile # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup @@ -29,100 +29,14 @@ UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus UAVOBJSRCFILENAMES += flightstats UAVOBJSRCFILENAMES += flightstatssettings -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwflyingf4 -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/flyingf4/fw/pios_board.c b/flight/targets/flyingf4/fw/pios_board.c index ee45b2415df..7306af61adc 100644 --- a/flight/targets/flyingf4/fw/pios_board.c +++ b/flight/targets/flyingf4/fw/pios_board.c @@ -164,7 +164,6 @@ uintptr_t pios_com_mavlink_id; uintptr_t pios_com_frsky_sensor_hub_id; uintptr_t pios_com_lighttelemetry_id; uintptr_t pios_com_picoc_id; -uintptr_t pios_com_overo_id; uintptr_t pios_com_frsky_sport_id; uintptr_t pios_uavo_settings_fs_id; @@ -211,7 +210,7 @@ static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cf #ifdef PIOS_INCLUDE_DSM static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) + ManualControlSettingsChannelGroupsOptions channelgroup,HwFlyingF4DSMxModeOptions *mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -220,7 +219,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -531,8 +530,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwFlyingF4DSMxBindGet(&hw_DSMxBind); + HwFlyingF4DSMxModeOptions hw_DSMxMode; + HwFlyingF4DSMxModeGet(&hw_DSMxMode); /* init sensor queue registration */ PIOS_SENSORS_Init(); @@ -572,7 +571,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart1_dsm_hsum_cfg, &pios_usart1_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -625,7 +624,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart2_dsm_hsum_cfg, &pios_usart2_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -715,7 +714,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart3_dsm_hsum_cfg, &pios_usart3_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ case HWFLYINGF4_UART3_HOTTSUMD: diff --git a/flight/targets/flyingf4/fw/pios_config.h b/flight/targets/flyingf4/fw/pios_config.h index dd634b5b867..2f697c623b5 100644 --- a/flight/targets/flyingf4/fw/pios_config.h +++ b/flight/targets/flyingf4/fw/pios_config.h @@ -124,8 +124,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/targets/freedom/bl/pios_config.h b/flight/targets/freedom/bl/pios_config.h deleted file mode 100644 index 1d131d886a5..00000000000 --- a/flight/targets/freedom/bl/pios_config.h +++ /dev/null @@ -1,53 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsBootloader Tau Labs Bootloaders - * @{ - * @addtogroup FreedomBL Tau Labs Freedom bootloader - * @{ - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific bootloader configuration file for PiOS - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_COM_MSG -#define PIOS_INCLUDE_FLASH -#define PIOS_INCLUDE_FLASH_INTERNAL -#define PIOS_INCLUDE_FLASH_JEDEC - -#endif /* PIOS_CONFIG_H */ - -/** - * @} - * @} - */ diff --git a/flight/targets/freedom/bl/pios_usb_board_data.h b/flight/targets/freedom/bl/pios_usb_board_data.h deleted file mode 100644 index de2ea8e9ade..00000000000 --- a/flight/targets/freedom/bl/pios_usb_board_data.h +++ /dev/null @@ -1,58 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsBootloader Tau Labs Bootloaders - * @{ - * @addtogroup FreedomBL Tau Labs Freedom bootloader - * @{ - * - * @file pios_usb_board_data.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific USB definitions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_USB_BOARD_DATA_H -#define PIOS_USB_BOARD_DATA_H - -#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 - -#define PIOS_USB_BOARD_EP_NUM 2 - -#include "pios_usb_defs.h" /* struct usb_* */ - -#define PIOS_USB_BOARD_VENDOR_ID USB_VENDOR_ID_CLAYLOGIC -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_FREEDOM -#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(0, USB_OP_BOARD_MODE_BL) -#define PIOS_USB_BOARD_SN_SUFFIX "+BL" - -/* - * The bootloader uses a simplified report structure - * BL: ... - * FW: ... - * This define changes the behaviour in pios_usb_hid.c - */ -#define PIOS_USB_BOARD_BL_HID_HAS_NO_LENGTH_BYTE - -#endif /* PIOS_USB_BOARD_DATA_H */ - -/** - * @} - * @} - */ diff --git a/flight/targets/freedom/board-info/board-info.mk b/flight/targets/freedom/board-info/board-info.mk deleted file mode 100644 index 9ab0ed84aea..00000000000 --- a/flight/targets/freedom/board-info/board-info.mk +++ /dev/null @@ -1,34 +0,0 @@ -BOARD_TYPE := 0x81 -BOARD_REVISION := 0x02 -# Previous version was 0x081, 0x082 introduces partition extensions and forced boot from bkp registers -BOOTLOADER_VERSION := 0x82 -HW_TYPE := 0x00 - -MCU := cortex-m4 -CHIP := STM32F405RGT -BOARD := STM32F4xx_FREEDOM -MODEL := HD -MODEL_SUFFIX := - -OPENOCD_JTAG_CONFIG := stlink-v2.cfg -OPENOCD_CONFIG := stm32f4xx.stlink.cfg - -# Note: These must match the values in link_$(BOARD)_memory.ld -BL_BANK_BASE := 0x08000000 # Start of bootloader flash -BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region (32kb) - -EE_BANK_BASE := 0x08008000 # EEPROM storage area -EE_BANK_SIZE := 0x00008000 # Size of EEPROM storage area - -# Leave the 64KB sector for other uses - -FW_BANK_BASE := 0x08020000 # Start of firmware flash -FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE (256kb) - -FW_DESC_SIZE := 0x00000064 - -EF_BANK_BASE := 0x08000000 # Start of entire flash image (usually start of bootloader as well) -EF_BANK_SIZE := 0x00060000 # Size of the entire flash image (from bootloader until end of firmware) - -OSCILLATOR_FREQ := 8000000 -SYSCLK_FREQ := 168000000 diff --git a/flight/targets/freedom/board-info/board_hw_defs.c b/flight/targets/freedom/board-info/board_hw_defs.c deleted file mode 100644 index 256bbeb169a..00000000000 --- a/flight/targets/freedom/board-info/board_hw_defs.c +++ /dev/null @@ -1,1631 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Freedom Tau Labs Freedom support files - * @{ - * - * @file board_hw_defs.c - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Defines board specific static initializers for hardware for the - * Freedom board. - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include -#include - -#if defined(PIOS_INCLUDE_LED) - -#include -static const struct pios_led pios_leds[] = { - [PIOS_LED_HEARTBEAT] = { - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - }, - [PIOS_LED_ALARM] = { - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - }, - [PIOS_LED_LINK] = { - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - }, -}; - -static const struct pios_led_cfg pios_led_cfg = { - .leds = pios_leds, - .num_leds = NELEMENTS(pios_leds), -}; - - -const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) -{ - return &pios_led_cfg; -} - -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_SPI) -#include - -/* SPI2 Interface - * - Used for gyro communications - */ -void PIOS_SPI_GYRO_irq_handler(void); -void DMA1_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_gyro_irq_handler"))); -static const struct pios_spi_cfg pios_spi_gyro_cfg = { - .regs = SPI2, - .remap = GPIO_AF_SPI2, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_High, - .SPI_CPHA = SPI_CPHA_2Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case RX) - .flags = (DMA_IT_TCIF3 | DMA_IT_TEIF3 | DMA_IT_HTIF3), - .init = { - .NVIC_IRQChannel = DMA1_Stream3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Stream3, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream4, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI2->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_13, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_14, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - } }, -}; - -uint32_t pios_spi_gyro_id; -void PIOS_SPI_gyro_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_gyro_id); -} - -#if defined(PIOS_OVERO_SPI) -/* - * SPI1 Interface - * Used for Overo - */ -#include -void PIOS_SPI_overo_irq_handler(void); -void DMA2_Stream3_IRQHandler(void) __attribute__((alias("PIOS_SPI_overo_irq_handler"))); -static const struct pios_overo_cfg pios_overo_cfg = { - .regs = SPI1, - .remap = GPIO_AF_SPI1, - .init = { - .SPI_Mode = SPI_Mode_Slave, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Hard, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_Low, - .SPI_CPHA = SPI_CPHA_1Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_2, - }, - .use_crc = false, - .dma = { - .irq = { - .flags = (DMA_IT_TCIF3), - .init = { - .NVIC_IRQChannel = DMA2_Stream3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA2_Stream0, - .init = { - .DMA_Channel = DMA_Channel_3, - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA2_Stream3, - .init = { - .DMA_Channel = DMA_Channel_3, - .DMA_PeripheralBaseAddr = (uint32_t)&(SPI1->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Circular, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_DOWN - }, - }, - .miso = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 1, - .ssel = { { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } } - } -}; - -uintptr_t pios_overo_id; -void PIOS_SPI_overo_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_OVERO_DMA_irq_handler(pios_overo_id); -} -#endif /* PIOS_OVERO_SPI */ - -/* - * SPI3 Interface - * Used for Flash and the RFM22B - */ -void PIOS_SPI_telem_flash_irq_handler(void); -void DMA1_Stream0_IRQHandler(void) __attribute__((alias("PIOS_SPI_telem_flash_irq_handler"))); -static const struct pios_spi_cfg pios_spi_telem_flash_cfg = { - .regs = SPI3, - .remap = GPIO_AF_SPI3, - .init = { - .SPI_Mode = SPI_Mode_Master, - .SPI_Direction = SPI_Direction_2Lines_FullDuplex, - .SPI_DataSize = SPI_DataSize_8b, - .SPI_NSS = SPI_NSS_Soft, - .SPI_FirstBit = SPI_FirstBit_MSB, - .SPI_CRCPolynomial = 7, - .SPI_CPOL = SPI_CPOL_Low, - .SPI_CPHA = SPI_CPHA_1Edge, - .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, - }, - .use_crc = false, - .dma = { - .irq = { - // Note this is the stream ID that triggers interrupts (in this case RX) - .flags = (DMA_IT_TCIF0 | DMA_IT_TEIF0 | DMA_IT_HTIF0), - .init = { - .NVIC_IRQChannel = DMA1_Stream0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - - .rx = { - .channel = DMA1_Stream0, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_PeripheralToMemory, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - //TODO: Enable FIFO - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - .tx = { - .channel = DMA1_Stream5, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & (SPI3->DR), - .DMA_DIR = DMA_DIR_MemoryToPeripheral, - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, - .DMA_MemoryInc = DMA_MemoryInc_Enable, - .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, - .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, - .DMA_Mode = DMA_Mode_Normal, - .DMA_Priority = DMA_Priority_Medium, - .DMA_FIFOMode = DMA_FIFOMode_Disable, - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, - .DMA_MemoryBurst = DMA_MemoryBurst_Single, - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, - }, - }, - }, - .sclk = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .miso = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .mosi = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_12, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, - .slave_count = 2, - .ssel = { - { // RFM22b - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, - { // Flash - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_15, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - } }, - }, -}; - -uint32_t pios_spi_telem_flash_id; -void PIOS_SPI_telem_flash_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_SPI_IRQ_Handler(pios_spi_telem_flash_id); -} - - -#if defined(PIOS_INCLUDE_RFM22B) -#include - -static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { - .vector = PIOS_RFM22_EXT_Int, - .line = EXTI_Line0, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_0, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI0_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line0, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Falling, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -const struct pios_rfm22b_cfg pios_rfm22b_freedom_cfg = { - .spi_cfg = &pios_spi_telem_flash_cfg, - .exti_cfg = &pios_exti_rfm22b_cfg, - .RFXtalCap = 0x7f, - .slave_num = 0, - .gpio_direction = GPIO0_TX_GPIO1_RX, -}; - -const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision) -{ - return &pios_rfm22b_freedom_cfg; -} - -#endif /* PIOS_INCLUDE_RFM22B */ - -#endif /* PIOS_INCLUDE_SPI */ - -#if defined(PIOS_INCLUDE_FLASH) -#include "pios_flashfs_logfs_priv.h" - -static const struct flashfs_logfs_cfg flashfs_settings_cfg = { - .fs_magic = 0x99abcedf, - .arena_size = 0x00010000, /* 256 * slot size */ - .slot_size = 0x00000100, /* 256 bytes */ -}; - -static const struct flashfs_logfs_cfg flashfs_waypoints_cfg = { - .fs_magic = 0x99abcecf, - .arena_size = 0x00010000, /* 2048 * slot size */ - .slot_size = 0x00000040, /* 64 bytes */ -}; - -static const struct flashfs_logfs_cfg flashfs_internal_cfg = { - .fs_magic = 0x99abcfef, - .arena_size = 0x00004000, /* 64 * slot size */ - .slot_size = 0x00000100, /* 256 bytes */ -}; - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) -#include "pios_flash_jedec_priv.h" - -static const struct pios_flash_jedec_cfg flash_m25p_cfg = { - .expect_manufacturer = JEDEC_MANUFACTURER_ST, - .expect_memorytype = 0x20, - .expect_capacity = 0x15, - .sector_erase = 0xD8, -}; -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ - -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) -#include "pios_flash_internal_priv.h" - -static const struct pios_flash_internal_cfg flash_internal_cfg = { -}; -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ - -#include "pios_flash_priv.h" - -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) -static const struct pios_flash_sector_range stm32f4_sectors[] = { - { - .base_sector = 0, - .last_sector = 3, - .sector_size = FLASH_SECTOR_16KB, - }, - { - .base_sector = 4, - .last_sector = 4, - .sector_size = FLASH_SECTOR_64KB, - }, - { - .base_sector = 5, - .last_sector = 11, - .sector_size = FLASH_SECTOR_128KB, - }, - -}; - -uintptr_t pios_internal_flash_id; -static const struct pios_flash_chip pios_flash_chip_internal = { - .driver = &pios_internal_flash_driver, - .chip_id = &pios_internal_flash_id, - .page_size = 16, /* 128-bit rows */ - .sector_blocks = stm32f4_sectors, - .num_blocks = NELEMENTS(stm32f4_sectors), -}; -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) -static const struct pios_flash_sector_range m25p16_sectors[] = { - { - .base_sector = 0, - .last_sector = 31, - .sector_size = FLASH_SECTOR_64KB, - }, -}; - -uintptr_t pios_external_flash_id; -static const struct pios_flash_chip pios_flash_chip_external = { - .driver = &pios_jedec_flash_driver, - .chip_id = &pios_external_flash_id, - .page_size = 256, - .sector_blocks = m25p16_sectors, - .num_blocks = NELEMENTS(m25p16_sectors), -}; -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ - -static const struct pios_flash_partition pios_flash_partition_table[] = { -#if defined(PIOS_INCLUDE_FLASH_INTERNAL) - { - .label = FLASH_PARTITION_LABEL_BL, - .chip_desc = &pios_flash_chip_internal, - .first_sector = 0, - .last_sector = 1, - .chip_offset = 0, - .size = (1 - 0 + 1) * FLASH_SECTOR_16KB, - }, - - /* NOTE: sectors 2-4 of the internal flash are currently unallocated */ - - { - .label = FLASH_PARTITION_LABEL_FW, - .chip_desc = &pios_flash_chip_internal, - .first_sector = 5, - .last_sector = 6, - .chip_offset = (4 * FLASH_SECTOR_16KB) + (1 * FLASH_SECTOR_64KB), - .size = (6 - 5 + 1) * FLASH_SECTOR_128KB, - }, - - /* NOTE: sectors 7-11 of the internal flash are currently unallocated */ - -#endif /* PIOS_INCLUDE_FLASH_INTERNAL */ - -#if defined(PIOS_INCLUDE_FLASH_JEDEC) - { - .label = FLASH_PARTITION_LABEL_SETTINGS, - .chip_desc = &pios_flash_chip_external, - .first_sector = 0, - .last_sector = 15, - .chip_offset = 0, - .size = (15 - 0 + 1) * FLASH_SECTOR_64KB, - }, - - { - .label = FLASH_PARTITION_LABEL_WAYPOINTS, - .chip_desc = &pios_flash_chip_external, - .first_sector = 16, - .last_sector = 31, - .chip_offset = (16 * FLASH_SECTOR_64KB), - .size = (31 - 16 + 1) * FLASH_SECTOR_64KB, - }, -#endif /* PIOS_INCLUDE_FLASH_JEDEC */ -}; - -const struct pios_flash_partition * PIOS_BOARD_HW_DEFS_GetPartitionTable (uint32_t board_revision, uint32_t * num_partitions) -{ - PIOS_Assert(num_partitions); - - *num_partitions = NELEMENTS(pios_flash_partition_table); - return pios_flash_partition_table; -} - -#endif /* PIOS_INCLUDE_FLASH */ - -#include - -#ifdef PIOS_INCLUDE_COM_TELEM -/* - * MAIN USART - */ -static const struct pios_usart_cfg pios_usart_flexi_cfg = { - .regs = USART1, - .remap = GPIO_AF_USART1, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource7, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource6, - }, -}; -#endif /* PIOS_INCLUDE_COM_TELEM */ - -#ifdef PIOS_INCLUDE_COM_FLEXI -/* - * Main PORT - */ -static const struct pios_usart_cfg pios_usart_main_cfg = { - .regs = USART2, - .remap = GPIO_AF_USART2, - .init = { - .USART_BaudRate = 57600, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = - USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -#endif /* PIOS_INCLUDE_COM_FLEXI */ - -#if defined(PIOS_INCLUDE_DSM) -/* - * Spektrum/JR DSM USART - */ -#include - -static const struct pios_dsm_cfg pios_dsm_flexi_cfg = { - .bind = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_NOPULL - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_main_cfg = { - .bind = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -static const struct pios_dsm_cfg pios_dsm_rcvr_cfg = { - .bind = { - .gpio = NULL, - }, -}; - -#endif /* PIOS_INCLUDE_DSM */ - -#if defined(PIOS_INCLUDE_HSUM) -/* - * Graupner HoTT SUMD/SUMH USART - */ -#include - -#endif /* PIOS_INCLUDE_HSUM */ - -#if (defined(PIOS_INCLUDE_DSM) || defined(PIOS_INCLUDE_HSUM)) -/* - * Spektrum/JR DSM or Graupner HoTT SUMD/SUMH USART - */ -static const struct pios_usart_cfg pios_usart_dsm_hsum_flexi_cfg = { - .regs = USART1, - .remap = GPIO_AF_USART1, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -static const struct pios_usart_cfg pios_usart_dsm_hsum_main_cfg = { - .regs = USART2, - .remap = GPIO_AF_USART2, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, -}; - -static const struct pios_usart_cfg pios_usart_dsm_hsum_rcvr_cfg = { - .regs = USART1, - .remap = GPIO_AF_USART1, - .init = { - .USART_BaudRate = 115200, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_No, - .USART_StopBits = USART_StopBits_1, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .tx = { - .gpio = NULL, - }, -}; - -#endif /* PIOS_INCLUDE_DSM || PIOS_INCLUDE_HSUM */ - -#include -#if defined(PIOS_INCLUDE_SBUS) -/* - * S.Bus USART - */ -static const struct pios_usart_cfg pios_usart_sbus_rcvr_cfg = { - .regs = USART1, - .init = { - .USART_BaudRate = 100000, - .USART_WordLength = USART_WordLength_8b, - .USART_Parity = USART_Parity_Even, - .USART_StopBits = USART_StopBits_2, - .USART_HardwareFlowControl = USART_HardwareFlowControl_None, - .USART_Mode = USART_Mode_Rx, - }, - .irq = { - .init = { - .NVIC_IRQChannel = USART1_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .gpio = GPIA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_IPU, - }, - }, - .tx = { - .gpio = NULL, - }, -}; - -#endif /* PIOS_INCLUDE_SBUS */ - -// Need this defined regardless to be able to turn it off -static const struct pios_sbus_cfg pios_sbus_cfg = { - /* Inverter configuration */ - .inv = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_2, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_OUT, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - }, - .gpio_inv_enable = Bit_SET, - .gpio_inv_disable = Bit_RESET, -}; - -#if defined(PIOS_INCLUDE_COM) - -#include - -#endif /* PIOS_INCLUDE_COM */ - -#if defined(PIOS_INCLUDE_I2C) - -#include - -/* - * I2C Adapters - */ -void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void); -void PIOS_I2C_mag_pressureadapter_er_irq_handler(void); -void I2C2_EV_IRQHandler() - __attribute__ ((alias("PIOS_I2C_mag_pressure_adapter_ev_irq_handler"))); -void I2C2_ER_IRQHandler() - __attribute__ ((alias("PIOS_I2C_mag_pressure_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_mag_pressure_adapter_cfg = { - .regs = I2C2, - .remap = GPIO_AF_I2C2, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_11, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C2_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_mag_pressure_adapter_id; -void PIOS_I2C_mag_pressure_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_mag_pressure_adapter_id); -} - -void PIOS_I2C_mag_pressure_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_mag_pressure_adapter_id); -} - - -void PIOS_I2C_flexiport_adapter_ev_irq_handler(void); -void PIOS_I2C_flexiport_adapter_er_irq_handler(void); -void I2C1_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_ev_irq_handler"))); -void I2C1_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_flexiport_adapter_er_irq_handler"))); - -static const struct pios_i2c_adapter_cfg pios_i2c_flexiport_adapter_cfg = { - .regs = I2C1, - .remap = GPIO_AF_I2C1, - .init = { - .I2C_Mode = I2C_Mode_I2C, - .I2C_OwnAddress1 = 0, - .I2C_Ack = I2C_Ack_Enable, - .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, - .I2C_DutyCycle = I2C_DutyCycle_2, - .I2C_ClockSpeed = 400000, /* bits/s */ - }, - .transfer_timeout_ms = 50, - .scl = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_6, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .sda = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_7, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_Speed = GPIO_Speed_50MHz, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .event = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_EV_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .error = { - .flags = 0, /* FIXME: check this */ - .init = { - .NVIC_IRQChannel = I2C1_ER_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -uint32_t pios_i2c_flexiport_adapter_id; -void PIOS_I2C_flexiport_adapter_ev_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_EV_IRQ_Handler(pios_i2c_flexiport_adapter_id); -} - -void PIOS_I2C_flexiport_adapter_er_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_I2C_ER_IRQ_Handler(pios_i2c_flexiport_adapter_id); -} - -#endif /* PIOS_INCLUDE_I2C */ - -#if defined(PIOS_INCLUDE_RTC) -/* - * Realtime Clock (RTC) - */ -#include - -void PIOS_RTC_IRQ_Handler (void); -void RTC_WKUP_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); -static const struct pios_rtc_cfg pios_rtc_main_cfg = { - .clksrc = RCC_RTCCLKSource_HSE_Div16, // Divide 8 Mhz crystal down to 1 - // For some reason it's acting like crystal is 16 Mhz. This clock is then divided - // by another 16 to give a nominal 62.5 khz clock - .prescaler = 100, // Every 100 cycles gives 625 Hz - .irq = { - .init = { - .NVIC_IRQChannel = RTC_WKUP_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -void PIOS_RTC_IRQ_Handler (void) -{ - PIOS_RTC_irq_handler (); -} - -#endif - -#include "pios_tim_priv.h" - -static const TIM_TimeBaseInitTypeDef tim_2_3_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, -}; -static const TIM_TimeBaseInitTypeDef tim_1_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), - .TIM_RepetitionCounter = 0x0000, -}; - - -static const struct pios_tim_clock_cfg tim_1_cfg = { - .timer = TIM1, - .time_base_init = &tim_1_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_2_cfg = { - .timer = TIM2, - .time_base_init = &tim_2_3_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM2_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_3_cfg = { - .timer = TIM3, - .time_base_init = &tim_2_3_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM3_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; -/* -static const struct pios_tim_clock_cfg tim_9_cfg = { - .timer = TIM9, - .time_base_init = &tim_9_10_11_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_BRK_TIM9_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_10_cfg = { - .timer = TIM10, - .time_base_init = &tim_9_10_11_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_UP_TIM10_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_11_cfg = { - .timer = TIM11, - .time_base_init = &tim_9_10_11_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_TRG_COM_TIM11_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -// Set up timers that only have inputs on APB1 -// TIM2,3,4,5,6,7,12,13,14 -static const TIM_TimeBaseInitTypeDef tim_apb1_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB1_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, -}; - - -// Set up timers that only have inputs on APB2 -// TIM1,8,9,10,11 -static const TIM_TimeBaseInitTypeDef tim_apb2_time_base = { - .TIM_Prescaler = (PIOS_PERIPHERAL_APB2_CLOCK / 1000000) - 1, - .TIM_ClockDivision = TIM_CKD_DIV1, - .TIM_CounterMode = TIM_CounterMode_Up, - .TIM_Period = 0xFFFF, - .TIM_RepetitionCounter = 0x0000, -}; - -static const struct pios_tim_clock_cfg tim_1_cfg = { - .timer = TIM1, - .time_base_init = &tim_apb2_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM1_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_4_cfg = { - .timer = TIM4, - .time_base_init = &tim_apb1_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; -static const struct pios_tim_clock_cfg tim_8_cfg = { - .timer = TIM8, - .time_base_init = &tim_apb2_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM8_CC_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; - -static const struct pios_tim_clock_cfg tim_12_cfg = { - .timer = TIM12, - .time_base_init = &tim_apb1_time_base, - .irq = { - .init = { - .NVIC_IRQChannel = TIM8_BRK_TIM12_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, -}; -*/ - -/** - * Pios servo configuration structures - * Using TIM1, TIM2, TIM3 - */ -#include -static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { - { // PWM1 TIM8_CH3 PC8 - .timer = TIM8, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource8, - }, - .remap = GPIO_AF_TIM8, - }, - { // PWM2 TIM8_CH4 PC9 - .timer = TIM8, - .timer_chan = TIM_Channel_4, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource9, - }, - .remap = GPIO_AF_TIM8, - }, - { // PWM3 TIM1_CH3 PA10 - .timer = TIM1, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource8, - }, - .remap = GPIO_AF_TIM1, - }, - { // PWM4 TIM3_CH2 PB5 - .timer = TIM3, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource5, - }, - .remap = GPIO_AF_TIM3, - }, - { // PWM5 TIM1_CH3 PB4 - .timer = TIM3, - .timer_chan = TIM_Channel_1, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource4, - }, - .remap = GPIO_AF_TIM3, - }, - { // PWM4 TIM3_CH2 PB3 - .timer = TIM2, - .timer_chan = TIM_Channel_2, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_3, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource3, - }, - .remap = GPIO_AF_TIM2, - }, -}; - -const struct pios_servo_cfg pios_servo_cfg = { - .tim_oc_init = { - .TIM_OCMode = TIM_OCMode_PWM1, - .TIM_OutputState = TIM_OutputState_Enable, - .TIM_OutputNState = TIM_OutputNState_Disable, - .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, - .TIM_OCPolarity = TIM_OCPolarity_High, - .TIM_OCNPolarity = TIM_OCPolarity_High, - .TIM_OCIdleState = TIM_OCIdleState_Reset, - .TIM_OCNIdleState = TIM_OCNIdleState_Reset, - }, - .channels = pios_tim_servoport_all_pins, - .num_channels = NELEMENTS(pios_tim_servoport_all_pins), -}; - - -/* - * PWM Inputs - * TIM1 - */ -#if defined(PIOS_INCLUDE_PWM) || defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { - { - .timer = TIM1, - .timer_chan = TIM_Channel_3, - .pin = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_10, - .GPIO_Speed = GPIO_Speed_2MHz, - .GPIO_Mode = GPIO_Mode_AF, - .GPIO_OType = GPIO_OType_PP, - .GPIO_PuPd = GPIO_PuPd_UP - }, - .pin_source = GPIO_PinSource10, - }, - .remap = GPIO_AF_TIM1, - }, -}; -#endif - -/* - * PPM Input - */ -#if defined(PIOS_INCLUDE_PPM) -#include -static const struct pios_ppm_cfg pios_ppm_cfg = { - .tim_ic_init = { - .TIM_ICPolarity = TIM_ICPolarity_Rising, - .TIM_ICSelection = TIM_ICSelection_DirectTI, - .TIM_ICPrescaler = TIM_ICPSC_DIV1, - .TIM_ICFilter = 0x0, - .TIM_Channel = TIM_Channel_2, - }, - /* Use only the first channel for ppm */ - .channels = &pios_tim_rcvrport_all_channels[0], - .num_channels = 1, -}; - -#endif //PPM - -#if defined(PIOS_INCLUDE_GCSRCVR) -#include "pios_gcsrcvr_priv.h" -#endif /* PIOS_INCLUDE_GCSRCVR */ - -#if defined(PIOS_INCLUDE_RCVR) -#include "pios_rcvr_priv.h" -#endif /* PIOS_INCLUDE_RCVR */ - -#if defined(PIOS_INCLUDE_USB) -#include "pios_usb_priv.h" - -static const struct pios_usb_cfg pios_usb_main_cfg = { - .irq = { - .init = { - .NVIC_IRQChannel = OTG_FS_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGHEST, - .NVIC_IRQChannelSubPriority = 3, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .vsense = { - .gpio = GPIOA, - .init = { - .GPIO_Pin = GPIO_Pin_9, - .GPIO_Speed = GPIO_Speed_25MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - }, - } -}; - -const struct pios_usb_cfg * PIOS_BOARD_HW_DEFS_GetUsbCfg (uint32_t board_revision) -{ - return &pios_usb_main_cfg; -} - -#include "pios_usb_board_data_priv.h" -#include "pios_usb_desc_hid_cdc_priv.h" -#include "pios_usb_desc_hid_only_priv.h" -#include "pios_usbhook.h" - -#endif /* PIOS_INCLUDE_USB */ - -#if defined(PIOS_INCLUDE_COM_MSG) - -#include - -#endif /* PIOS_INCLUDE_COM_MSG */ - -#if defined(PIOS_INCLUDE_USB_HID) && !defined(PIOS_INCLUDE_USB_CDC) -#include - -const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 0, - .data_rx_ep = 1, - .data_tx_ep = 1, -}; -#endif /* PIOS_INCLUDE_USB_HID && !PIOS_INCLUDE_USB_CDC */ - -#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_USB_CDC) -#include - -const struct pios_usb_cdc_cfg pios_usb_cdc_cfg = { - .ctrl_if = 0, - .ctrl_tx_ep = 2, - - .data_if = 1, - .data_rx_ep = 3, - .data_tx_ep = 3, -}; - -#include - -const struct pios_usb_hid_cfg pios_usb_hid_cfg = { - .data_if = 2, - .data_rx_ep = 1, - .data_tx_ep = 1, -}; -#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ - -#if defined(PIOS_INCLUDE_ADC) -#include "pios_adc_priv.h" -#include "pios_internal_adc_priv.h" -void PIOS_ADC_DMA_irq_handler(void); -void DMA2_Stream4_IRQHandler(void) __attribute__((alias("PIOS_ADC_DMA_irq_handler"))); -struct pios_internal_adc_cfg pios_adc_cfg = { - .adc_dev_master = ADC1, - .dma = { - .irq = { - .flags = (DMA_FLAG_TCIF4 | DMA_FLAG_TEIF4 | DMA_FLAG_HTIF4), - .init = { - .NVIC_IRQChannel = DMA2_Stream4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .rx = { - .channel = DMA2_Stream4, - .init = { - .DMA_Channel = DMA_Channel_0, - .DMA_PeripheralBaseAddr = (uint32_t) & ADC1->DR - }, - } - }, - .half_flag = DMA_IT_HTIF4, - .full_flag = DMA_IT_TCIF4, - -}; - -void PIOS_ADC_DMA_irq_handler(void) -{ - /* Call into the generic code to handle the IRQ for this specific device */ - PIOS_INTERNAL_ADC_DMA_Handler(); -} -#endif /* PIOS_INCLUDE_ADC */ - -/** - * @} - * @} - */ - diff --git a/flight/targets/freedom/board-info/pios_board.h b/flight/targets/freedom/board-info/pios_board.h deleted file mode 100644 index 728e13a7336..00000000000 --- a/flight/targets/freedom/board-info/pios_board.h +++ /dev/null @@ -1,299 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Freedom Tau Labs Freedom support files - * @{ - * - * @file STM32F4xx_Freedom.H - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific defines for Freedom - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef STM3210E_INS_H_ - -#include - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -#define DEBUG_LEVEL 0 -#define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_debug_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_debug_id, __VA_ARGS__); }} -#else -#define DEBUG_PRINTF(level, ...) -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -//------------------------ -// Timers and Channels Used -//------------------------ -/* -Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 -------+-----------+-----------+-----------+---------- -TIM1 | | | | -TIM2 | --------------- PIOS_DELAY ----------------- -TIM3 | | | | -TIM4 | | | | -TIM5 | | | | -TIM6 | | | | -TIM7 | | | | -TIM8 | | | | -------+-----------+-----------+-----------+---------- -*/ - -//------------------------ -// DMA Channels Used -//------------------------ -/* Channel 1 - */ -/* Channel 2 - SPI1 RX */ -/* Channel 3 - SPI1 TX */ -/* Channel 4 - SPI2 RX */ -/* Channel 5 - SPI2 TX */ -/* Channel 6 - */ -/* Channel 7 - */ -/* Channel 8 - */ -/* Channel 9 - */ -/* Channel 10 - */ -/* Channel 11 - */ -/* Channel 12 - */ - -//------------------------ -// BOOTLOADER_SETTINGS -//------------------------ -#define BOARD_READABLE true -#define BOARD_WRITABLE true -#define MAX_DEL_RETRYS 3 - - -//------------------------ -// PIOS_LED -//------------------------ -#define PIOS_LED_HEARTBEAT 0 -#define PIOS_LED_ALARM 1 -#define PIOS_LED_LINK 2 - -//------------------------ -// PIOS_WDG -//------------------------ -#define PIOS_WATCHDOG_TIMEOUT 250 -#define PIOS_WDG_REGISTER RTC_BKP_DR4 - -//------------------------ -// PIOS_I2C -// See also pios_board.c -//------------------------ -#define PIOS_I2C_MAX_DEVS 3 -extern uint32_t pios_i2c_mag_pressure_adapter_id; -#define PIOS_I2C_MAIN_ADAPTER (pios_i2c_mag_pressure_adapter_id) -extern uint32_t pios_i2c_flexiport_adapter_id; -#define PIOS_I2C_FLEXI_ADAPTER (pios_i2c_flexiport_adapter_id) -#define PIOS_I2C_ETASV3_ADAPTER (PIOS_I2C_FLEXI_ADAPTER) - -//------------------------- -// PIOS_COM -// -// See also pios_board.c -//------------------------- -extern uintptr_t pios_com_telem_rf_id; -extern uintptr_t pios_com_gps_id; -extern uintptr_t pios_com_telem_usb_id; -extern uintptr_t pios_com_bridge_id; -extern uintptr_t pios_com_vcp_id; -extern uintptr_t pios_com_mavlink_id; -extern uint32_t pios_rfm22b_id; -extern uintptr_t pios_com_hott_id; -extern uintptr_t pios_com_frsky_sensor_hub_id; -extern uintptr_t pios_com_lighttelemetry_id; -extern uintptr_t pios_com_picoc_id; -extern uintptr_t pios_com_frsky_sport_id; - -#define PIOS_COM_GPS (pios_com_gps_id) -#define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) -#define PIOS_COM_BRIDGE (pios_com_bridge_id) -#define PIOS_COM_VCP (pios_com_vcp_id) -#define PIOS_COM_MAVLINK (pios_com_mavlink_id) -#define PIOS_COM_HOTT (pios_com_hott_id) -#define PIOS_COM_FRSKY_SENSOR_HUB (pios_com_frsky_sensor_hub_id) -#define PIOS_COM_LIGHTTELEMETRY (pios_com_lighttelemetry_id) -#define PIOS_COM_PICOC (pios_com_picoc_id) -#define PIOS_COM_FRSKY_SPORT (pios_com_frsky_sport_id) - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -extern uintptr_t pios_com_debug_id; -#define PIOS_COM_DEBUG (pios_com_debug_id) -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -#if defined(PIOS_INCLUDE_RFM22B) -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 -extern uintptr_t pios_com_rfm22b_id; -#define PIOS_COM_RADIO (pios_com_rfm22b_id) -extern uint32_t pios_spi_telem_flash_id; -#define PIOS_RFM22_SPI_PORT (pios_spi_telem_flash_id) -#endif /* PIOS_INCLUDE_RFM22B */ - -#define LINK_LED_ON PIOS_LED_On(PIOS_LED_LINK) -#define LINK_LED_OFF PIOS_LED_Off(PIOS_LED_LINK) -#define LINK_LED_TOGGLE PIOS_LED_Toggle(PIOS_LED_LINK) - -#define RX_LED_ON -#define RX_LED_OFF -#define TX_LED_ON PIOS_LED_On(PIOS_LED_LINK) -#define TX_LED_OFF PIOS_LED_Off(PIOS_LED_LINK) -#define USB_LED_ON -#define USB_LED_OFF - -//------------------------- -// Packet Handler -//------------------------- -#define RS_ECC_NPARITY 4 -#define PIOS_PH_MAX_PACKET 255 -#define PIOS_PH_WIN_SIZE 3 -#define PIOS_PH_MAX_CONNECTIONS 1 -extern uint32_t pios_packet_handler; -#define PIOS_PACKET_HANDLER (pios_packet_handler) - -//------------------------ -// TELEMETRY -//------------------------ -#define TELEM_QUEUE_SIZE 80 -#define PIOS_TELEM_STACK_SIZE 624 - -#define PIOS_SYSCLK 168000000 -// Peripherals that belongs to APB1 are: -// DAC |PWR |CAN1,2 -// I2C1,2,3 |UART4,5 |USART3,2 -// I2S3Ext |SPI3/I2S3 |SPI2/I2S2 -// I2S2Ext |IWDG |WWDG -// RTC/BKP reg -// TIM2,3,4,5,6,7,12,13,14 - -// Calculated as SYSCLK / APBPresc * (APBPre == 1 ? 1 : 2) -// Default APB1 Prescaler = 4 -#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) - -// Peripherals belonging to APB2 -// SDIO |EXTI |SYSCFG |SPI1 -// ADC1,2,3 -// USART1,6 -// TIM1,8,9,10,11 -// -// Default APB2 Prescaler = 2 -// -#define PIOS_PERIPHERAL_APB2_CLOCK PIOS_SYSCLK - - -//------------------------- -// Interrupt Priorities -//------------------------- -#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS -#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS -#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... -#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... - -//------------------------ -// PIOS_RCVR -// See also pios_board.c -//------------------------ -#define PIOS_RCVR_MAX_CHANNELS 12 -#define PIOS_GCSRCVR_TIMEOUT_MS 100 - -//------------------------- -// Receiver PPM input -//------------------------- -#define PIOS_PPM_NUM_INPUTS 12 - -//------------------------- -// Receiver PWM input -//------------------------- -#define PIOS_PWM_NUM_INPUTS 8 - -//------------------------- -// Receiver SPEKTRUM input -//------------------------- -#define PIOS_SPEKTRUM_NUM_INPUTS 12 - -//------------------------- -// Receiver S.Bus input -//------------------------- -#define PIOS_SBUS_NUM_INPUTS (16+2) - -//------------------------- -// Receiver DSM input -//------------------------- -#define PIOS_DSM_NUM_INPUTS 12 - -//------------------------- -// Receiver HSUM input -//------------------------- -#define PIOS_HSUM_MAX_DEVS 2 -#define PIOS_HSUM_NUM_INPUTS 32 - -//------------------------- -// Servo outputs -//------------------------- -#define PIOS_SERVO_UPDATE_HZ 50 -#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ - -//-------------------------- -// Timer controller settings -//-------------------------- -#define PIOS_TIM_MAX_DEVS 6 - -//------------------------- -// ADC -// PIOS_ADC_PinGet(0) = Current sensor -// PIOS_ADC_PinGet(1) = Voltage sensor -// PIOS_ADC_PinGet(4) = VREF -// PIOS_ADC_PinGet(5) = Temperature sensor -//------------------------- -#define PIOS_DMA_PIN_CONFIG \ -{ \ - {GPIOC, GPIO_Pin_1, ADC_Channel_11}, \ - {GPIOC, GPIO_Pin_2, ADC_Channel_12}, \ - {NULL, 0, ADC_Channel_Vrefint}, /* Voltage reference */ \ - {NULL, 0, ADC_Channel_TempSensor}, /* Temperature sensor */ \ - {GPIOC, GPIO_Pin_3, ADC_Channel_13} \ -} - -/* we have to do all this to satisfy the PIOS_ADC_MAX_SAMPLES define in pios_adc.h */ -/* which is annoying because this then determines the rate at which we generate buffer turnover events */ -/* the objective here is to get enough buffer space to support 100Hz averaging rate */ -#define PIOS_ADC_NUM_CHANNELS 5 -#define PIOS_ADC_MAX_OVERSAMPLING 2 -#define PIOS_ADC_USE_ADC2 0 - -#define VREF_PLUS 3.3 - -//------------------------- -// USB -//------------------------- -#define PIOS_USB_ENABLED 1 /* Should remove all references to this */ - -//------------------------- -// ADC -//------------------------- -#define PIOS_ADC_SUB_DRIVER_MAX_INSTANCES 3 - -#endif /* STM3210E_INS_H_ */ - -/** - * @} - * @} - */ diff --git a/flight/targets/freedom/fw/UAVObjects.inc b/flight/targets/freedom/fw/UAVObjects.inc deleted file mode 100644 index 09912c14739..00000000000 --- a/flight/targets/freedom/fw/UAVObjects.inc +++ /dev/null @@ -1,126 +0,0 @@ -##### -# Project: Tau Labs -# -# Makefile for Tau Labs UAVObject code -# -# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -##### - -# These are the UAVObjects supposed to be build as part of the OpenPilot target -# (all architectures) - -UAVOBJSRCFILENAMES = -UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver -UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += groundpathfollowersettings -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += rfm22breceiver -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += rfm22bstatus -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus -UAVOBJSRCFILENAMES += hwfreedom -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo -UAVOBJSRCFILENAMES += picocsettings -UAVOBJSRCFILENAMES += picocstatus - -UAVOBJSRCFILENAMES += txpidsettings - -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings - -UAVOBJSRCFILENAMES += sessionmanaging - - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/freedom/fw/pios_board.c b/flight/targets/freedom/fw/pios_board.c deleted file mode 100644 index 405781c9980..00000000000 --- a/flight/targets/freedom/fw/pios_board.c +++ /dev/null @@ -1,1159 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Freedom Tau Labs Freedom support files - * @{ - * - * @file pios_board.c - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 - * @brief The board specific initialization routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include -#include -#include -#include "hwfreedom.h" -#include "modulesettings.h" -#include "manualcontrolsettings.h" -#include "rfm22bstatus.h" - -#include "pios_internal_adc_priv.h" -#include "pios_adc_priv.h" -#include "pios_rfm22b_priv.h" -#include "pios_rfm22b_rcvr_priv.h" - -/** - * Sensor configurations - */ - -#if defined(PIOS_INCLUDE_HMC5883) -#include "pios_hmc5883_priv.h" -static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { - .vector = PIOS_HMC5883_IRQHandler, - .line = EXTI_Line4, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line4, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { - .exti_cfg = &pios_exti_hmc5883_cfg, - .M_ODR = PIOS_HMC5883_ODR_75, - .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, - .Gain = PIOS_HMC5883_GAIN_1_9, - .Mode = PIOS_HMC5883_MODE_CONTINUOUS, - .Default_Orientation = PIOS_HMC5883_TOP_90DEG, - -}; -#endif /* PIOS_INCLUDE_HMC5883 */ - -/** - * Configuration for the MS5611 chip - */ -#if defined(PIOS_INCLUDE_MS5611) -#include "pios_ms5611_priv.h" -static const struct pios_ms5611_cfg pios_ms5611_cfg = { - .oversampling = MS5611_OSR_1024, - .temperature_interleaving = 1, -}; -#endif /* PIOS_INCLUDE_MS5611 */ - - -/** - * Configuration for the MPU6000 chip - */ -#if defined(PIOS_INCLUDE_MPU6000) -#include "pios_mpu6000.h" -static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { - .vector = PIOS_MPU6000_IRQHandler, - .line = EXTI_Line5, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line5, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_mpu60x0_cfg pios_mpu6000_cfg = { - .exti_cfg = &pios_exti_mpu6000_cfg, - .default_samplerate = 666, - .interrupt_cfg = PIOS_MPU60X0_INT_CLR_ANYRD, - .interrupt_en = PIOS_MPU60X0_INTEN_DATA_RDY, - .User_ctl = PIOS_MPU60X0_USERCTL_DIS_I2C, - .Pwr_mgmt_clk = PIOS_MPU60X0_PWRMGMT_PLL_Z_CLK, - .default_filter = PIOS_MPU60X0_LOWPASS_256_HZ, - .orientation = PIOS_MPU60X0_TOP_180DEG -}; -#endif /* PIOS_INCLUDE_MPU6000 */ - -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS - * NOTE: No slot in this map for NONE. - */ -uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 - -#define PIOS_COM_GPS_RX_BUF_LEN 32 -#define PIOS_COM_GPS_TX_BUF_LEN 16 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 - -#define PIOS_COM_HOTT_RX_BUF_LEN 16 -#define PIOS_COM_HOTT_TX_BUF_LEN 16 -#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 19 - -#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128 - -#define PIOS_COM_PICOC_RX_BUF_LEN 128 -#define PIOS_COM_PICOC_TX_BUF_LEN 128 - -#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 -#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 -uintptr_t pios_com_debug_id; -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -uintptr_t pios_com_gps_id; -uintptr_t pios_com_telem_usb_id; -uintptr_t pios_com_telem_rf_id; -uintptr_t pios_com_vcp_id; -uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; -uintptr_t pios_com_mavlink_id; -uintptr_t pios_com_rf_id; -uintptr_t pios_com_hott_id; -uintptr_t pios_com_frsky_sensor_hub_id; -uintptr_t pios_com_lighttelemetry_id; -uintptr_t pios_com_picoc_id; -uintptr_t pios_com_frsky_sport_id; -uintptr_t pios_internal_adc_id; -uint32_t pios_rfm22b_id; -uintptr_t pios_uavo_settings_fs_id; -uintptr_t pios_waypoints_settings_fs_id; - -/* - * Setup a com port based on the passed cfg, driver and buffer sizes. rx or tx size of 0 disables rx or tx - */ -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) -static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, - const struct pios_com_driver *com_driver, uintptr_t *pios_com_id) -{ - uintptr_t pios_usart_id; - if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer; - if (rx_buf_len > 0) { - rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); - PIOS_Assert(rx_buffer); - } else { - rx_buffer = NULL; - } - - uint8_t * tx_buffer; - if (tx_buf_len > 0) { - tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); - PIOS_Assert(tx_buffer); - } else { - tx_buffer = NULL; - } - - if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, - rx_buffer, rx_buf_len, - tx_buffer, tx_buf_len)) { - PIOS_Assert(0); - } -} -#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ - -#ifdef PIOS_INCLUDE_DSM -static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) -{ - uintptr_t pios_usart_dsm_id; - if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_rcvr_id; - if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; -} -#endif - -#ifdef PIOS_INCLUDE_HSUM -static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hsum_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_hsum_proto *proto, - ManualControlSettingsChannelGroupsOptions channelgroup) -{ - uintptr_t pios_usart_hsum_id; - if (PIOS_USART_Init(&pios_usart_hsum_id, pios_usart_hsum_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_id; - if (PIOS_HSUM_Init(&pios_hsum_id, pios_usart_com_driver, - pios_usart_hsum_id, *proto)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_rcvr_id; - if (PIOS_RCVR_Init(&pios_hsum_rcvr_id, &pios_hsum_rcvr_driver, pios_hsum_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_hsum_rcvr_id; -} -#endif - -/** - * Indicate a target-specific error code when a component fails to initialize - * 1 pulse - flash chip - * 2 pulses - MPU6000 - * 3 pulses - HMC5883 - * 4 pulses - MS5611 - * 5 pulses - I2C bus locked - */ -void panic(int32_t code) { - while(1){ - for (int32_t i = 0; i < code; i++) { - PIOS_LED_Toggle(PIOS_LED_ALARM); - PIOS_DELAY_WaitmS(200); - PIOS_WDG_Clear(); - PIOS_LED_Toggle(PIOS_LED_ALARM); - PIOS_DELAY_WaitmS(200); - PIOS_WDG_Clear(); - } - PIOS_DELAY_WaitmS(250); - PIOS_WDG_Clear(); - PIOS_DELAY_WaitmS(250); - PIOS_WDG_Clear(); - } -} - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ - -#include - -void PIOS_Board_Init(void) { - - /* Delay system */ - PIOS_DELAY_Init(); - - const struct pios_board_info * bdinfo = &pios_board_info_blob; - -#if defined(PIOS_INCLUDE_LED) - const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(bdinfo->board_rev); - PIOS_Assert(led_cfg); - PIOS_LED_Init(led_cfg); -#endif /* PIOS_INCLUDE_LED */ - - /* Set up the SPI interface to the gyro/acelerometer */ - if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { - PIOS_DEBUG_Assert(0); - } - - /* Set up the SPI interface to the flash and rfm22b */ - if (PIOS_SPI_Init(&pios_spi_telem_flash_id, &pios_spi_telem_flash_cfg)) { - PIOS_DEBUG_Assert(0); - } - -#if defined(PIOS_INCLUDE_FLASH) - /* Inititialize all flash drivers */ - if (PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_telem_flash_id, 1, &flash_m25p_cfg) != 0) - panic(1); - if (PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg) != 0) - panic(1); - - /* Register the partition table */ - const struct pios_flash_partition * flash_partition_table; - uint32_t num_partitions; - flash_partition_table = PIOS_BOARD_HW_DEFS_GetPartitionTable(bdinfo->board_rev, &num_partitions); - PIOS_FLASH_register_partition_table(flash_partition_table, num_partitions); - - /* Mount all filesystems */ - if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS) != 0) - panic(1); - if (PIOS_FLASHFS_Logfs_Init(&pios_waypoints_settings_fs_id, &flashfs_waypoints_cfg, FLASH_PARTITION_LABEL_WAYPOINTS) != 0) - panic(1); - -#if defined(ERASE_FLASH) - PIOS_FLASHFS_Format(pios_uavo_settings_fs_id); -#endif - -#endif /* PIOS_INCLUDE_FLASH */ - - /* Initialize the task monitor library */ - TaskMonitorInitialize(); - - /* Initialize UAVObject libraries */ - EventDispatcherInitialize(); - UAVObjInitialize(); - - /* Initialize the alarms library */ - AlarmsInitialize(); - - HwFreedomInitialize(); - ModuleSettingsInitialize(); - -#if defined(PIOS_INCLUDE_RTC) - PIOS_RTC_Init(&pios_rtc_main_cfg); -#endif - -#ifndef ERASE_FLASH - /* Initialize watchdog as early as possible to catch faults during init - * but do it only if there is no debugger connected - */ - if ((CoreDebug->DHCSR & CoreDebug_DHCSR_C_DEBUGEN_Msk) == 0) { - PIOS_WDG_Init(); - } -#endif - - // /* Set up pulse timers */ - PIOS_TIM_InitClock(&tim_1_cfg); - PIOS_TIM_InitClock(&tim_2_cfg); - PIOS_TIM_InitClock(&tim_3_cfg); - - /* IAP System Setup */ - PIOS_IAP_Init(); - uint16_t boot_count = PIOS_IAP_ReadBootCount(); - if (boot_count < 3) { - PIOS_IAP_WriteBootCount(++boot_count); - AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); - } else { - /* Too many failed boot attempts, force hw config to defaults */ - HwFreedomSetDefaults(HwFreedomHandle(), 0); - ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); - AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); - } - - - PIOS_IAP_Init(); - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - /* Flags to determine if various USB interfaces are advertised */ - bool usb_hid_present = false; - bool usb_cdc_present = false; - -#if defined(PIOS_INCLUDE_USB_CDC) - if (PIOS_USB_DESC_HID_CDC_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - usb_cdc_present = true; -#else - if (PIOS_USB_DESC_HID_ONLY_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; -#endif - - uintptr_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); - -#if defined(PIOS_INCLUDE_USB_CDC) - - uint8_t hw_usb_vcpport; - /* Configure the USB VCP port */ - HwFreedomUSB_VCPPortGet(&hw_usb_vcpport); - - if (!usb_cdc_present) { - /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ - hw_usb_vcpport = HWFREEDOM_USB_VCPPORT_DISABLED; - } - - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_vcpport) { - case HWFREEDOM_USB_VCPPORT_DISABLED: - break; - case HWFREEDOM_USB_VCPPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWFREEDOM_USB_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWFREEDOM_USB_VCPPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - NULL, 0, - tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -#endif /* PIOS_INCLUDE_COM */ - break; - case HWFREEDOM_USB_VCPPORT_PICOC: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, - tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } -#endif /* PIOS_INCLUDE_USB_CDC */ - -#if defined(PIOS_INCLUDE_USB_HID) - /* Configure the usb HID port */ - uint8_t hw_usb_hidport; - HwFreedomUSB_HIDPortGet(&hw_usb_hidport); - - if (!usb_hid_present) { - /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ - hw_usb_hidport = HWFREEDOM_USB_HIDPORT_DISABLED; - } - - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_hidport) { - case HWFREEDOM_USB_HIDPORT_DISABLED: - break; - case HWFREEDOM_USB_HIDPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } - -#endif /* PIOS_INCLUDE_USB_HID */ - - if (usb_hid_present || usb_cdc_present) { - PIOS_USBHOOK_Activate(); - } -#endif /* PIOS_INCLUDE_USB */ - - /* Configure IO ports */ - uint8_t hw_DSMxBind; - HwFreedomDSMxBindGet(&hw_DSMxBind); - - /* Configure FlexiPort */ - uint8_t hw_mainport; - HwFreedomMainPortGet(&hw_mainport); - switch (hw_mainport) { - case HWFREEDOM_MAINPORT_DISABLED: - break; - case HWFREEDOM_MAINPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWFREEDOM_MAINPORT_GPS: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_RX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWFREEDOM_MAINPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_main_cfg, &pios_dsm_main_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWFREEDOM_MAINPORT_HOTTSUMD: - case HWFREEDOM_MAINPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_mainport) { - case HWFREEDOM_MAINPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWFREEDOM_MAINPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_main_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWFREEDOM_MAINPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWFREEDOM_MAINPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWFREEDOM_MAINPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWFREEDOM_MAINPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_GPS) -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ -#endif /* PIOS_INCLUDE_GPS */ - break; - case HWFREEDOM_MAINPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWFREEDOM_MAINPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWFREEDOM_MAINPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - break; - case HWFREEDOM_MAINPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWFREEDOM_MAINPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ - break; - } /* hw_freedom_mainport */ - - /* Configure flexi USART port */ - uint8_t hw_flexiport; - HwFreedomFlexiPortGet(&hw_flexiport); - switch (hw_flexiport) { - case HWFREEDOM_FLEXIPORT_DISABLED: - break; - case HWFREEDOM_FLEXIPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWFREEDOM_FLEXIPORT_GPS: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_RX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWFREEDOM_FLEXIPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWFREEDOM_FLEXIPORT_HOTTSUMD: - case HWFREEDOM_FLEXIPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_flexiport) { - case HWFREEDOM_FLEXIPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWFREEDOM_FLEXIPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_flexi_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWFREEDOM_FLEXIPORT_I2C: -#if defined(PIOS_INCLUDE_I2C) - { - if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_I2C */ - break; - case HWFREEDOM_FLEXIPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWFREEDOM_FLEXIPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWFREEDOM_FLEXIPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWFREEDOM_FLEXIPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_GPS) -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ -#endif /* PIOS_INCLUDE_GPS */ - break; - case HWFREEDOM_FLEXIPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWFREEDOM_FLEXIPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWFREEDOM_FLEXIPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - break; - case HWFREEDOM_FLEXIPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWFREEDOM_FLEXIPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ - break; - } /* hw_freedom_flexiport */ - - - /* Initalize the RFM22B radio COM device. */ -#if defined(PIOS_INCLUDE_RFM22B) - RFM22BStatusInitialize(); - RFM22BStatusCreateInstance(); - - // Initialize out status object. - RFM22BStatusData rfm22bstatus; - RFM22BStatusGet(&rfm22bstatus); - RFM22BStatusInstSet(1,&rfm22bstatus); - - - HwFreedomData hwFreedom; - HwFreedomGet(&hwFreedom); - - // Initialize out status object. - rfm22bstatus.BoardType = bdinfo->board_type; - rfm22bstatus.BoardRevision = bdinfo->board_rev; - - if (hwFreedom.Radio == HWFREEDOM_RADIO_DISABLED || hwFreedom.MaxRfPower == HWFREEDOM_MAXRFPOWER_0) { - - // When radio disabled, it is ok for init to fail. This allows boards without populating - // this component. - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg) == 0) { - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - } else { - pios_rfm22b_id = 0; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; - - } else { - - // always allow receiving PPM when radio is on - bool ppm_mode = hwFreedom.Radio == HWFREEDOM_RADIO_TELEMPPM || hwFreedom.Radio == HWFREEDOM_RADIO_PPM; - bool ppm_only = hwFreedom.Radio == HWFREEDOM_RADIO_PPM; - bool is_oneway = hwFreedom.Radio == HWFREEDOM_RADIO_PPM; // Sparky2 can only receive PPM only - - /* Configure the RFM22B device. */ - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { - panic(6); - } - - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - - - /* Configure the radio com interface */ - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - panic(6); - } - - /* Set Telemetry to use RFM22b if no other telemetry is configured (USB always overrides anyway) */ - if (!pios_com_telem_rf_id) { - pios_com_telem_rf_id = pios_com_rf_id; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_ENABLED; - - enum rfm22b_datarate datarate = RFM22_datarate_64000; - switch (hwFreedom.MaxRfSpeed) { - case HWFREEDOM_MAXRFSPEED_9600: - datarate = RFM22_datarate_9600; - break; - case HWFREEDOM_MAXRFSPEED_19200: - datarate = RFM22_datarate_19200; - break; - case HWFREEDOM_MAXRFSPEED_32000: - datarate = RFM22_datarate_32000; - break; - case HWFREEDOM_MAXRFSPEED_64000: - datarate = RFM22_datarate_64000; - break; - case HWFREEDOM_MAXRFSPEED_100000: - datarate = RFM22_datarate_100000; - break; - case HWFREEDOM_MAXRFSPEED_192000: - datarate = RFM22_datarate_192000; - break; - } - - /* Set the radio configuration parameters. */ - PIOS_RFM22B_Config(pios_rfm22b_id, datarate, hwFreedom.MinChannel, hwFreedom.MaxChannel, hwFreedom.CoordID, is_oneway, ppm_mode, ppm_only); - - /* Set the modem Tx poer level */ - switch (hwFreedom.MaxRfPower) { - case HWFREEDOM_MAXRFPOWER_125: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - break; - case HWFREEDOM_MAXRFPOWER_16: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); - break; - case HWFREEDOM_MAXRFPOWER_316: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); - break; - case HWFREEDOM_MAXRFPOWER_63: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); - break; - case HWFREEDOM_MAXRFPOWER_126: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); - break; - case HWFREEDOM_MAXRFPOWER_25: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); - break; - case HWFREEDOM_MAXRFPOWER_50: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); - break; - case HWFREEDOM_MAXRFPOWER_100: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); - break; - default: - // do nothing - break; - } - - /* Reinitialize the modem. */ - PIOS_RFM22B_Reinit(pios_rfm22b_id); - -#if defined(PIOS_INCLUDE_RFM22B_RCVR) - { - uintptr_t pios_rfm22brcvr_id; - PIOS_RFM22B_Rcvr_Init(&pios_rfm22brcvr_id, pios_rfm22b_id); - uintptr_t pios_rfm22brcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_rfm22brcvr_rcvr_id, &pios_rfm22b_rcvr_driver, pios_rfm22brcvr_id)) { - panic(6); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_RFM22B] = pios_rfm22brcvr_rcvr_id; - } - } - - RFM22BStatusInstSet(1,&rfm22bstatus); -#endif /* PIOS_INCLUDE_RFM22B_RCVR */ - -#endif /* PIOS_INCLUDE_RFM22B */ - - PIOS_WDG_Clear(); - - /* Configure input receiver USART port */ - uint8_t hw_rcvrport; - HwFreedomRcvrPortGet(&hw_rcvrport); - switch (hw_rcvrport) { - case HWFREEDOM_RCVRPORT_DISABLED: - break; - case HWFREEDOM_RCVRPORT_PPM: - { - uintptr_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); - - uintptr_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; - } - break; - case HWFREEDOM_RCVRPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_rcvr_cfg, &pios_dsm_rcvr_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWFREEDOM_RCVRPORT_HOTTSUMD: - case HWFREEDOM_RCVRPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_rcvrport) { - case HWFREEDOM_RCVRPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWFREEDOM_RCVRPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_rcvr_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWFREEDOM_RCVRPORT_SBUS: -#if defined(PIOS_INCLUDE_SBUS) - { - uintptr_t pios_usart_sbus_id; - if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_rcvr_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_id; - if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; - } -#endif - - break; - } - - if (hw_rcvrport != HWFREEDOM_RCVRPORT_SBUS) { - GPIO_Init(pios_sbus_cfg.inv.gpio, (GPIO_InitTypeDef*)&pios_sbus_cfg.inv.init); - GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable); - } - - -#if defined(PIOS_OVERO_SPI) - /* Set up the SPI based PIOS_COM interface to the overo */ - { - bool overo_enabled = false; -#ifdef MODULE_OveroSync_BUILTIN - overo_enabled = true; -#else - uint8_t module_state[MODULESETTINGS_ADMINSTATE_NUMELEM]; - ModuleSettingsAdminStateGet(module_state); - if (module_state[MODULESETTINGS_ADMINSTATE_OVEROSYNC] == MODULESETTINGS_ADMINSTATE_ENABLED) { - overo_enabled = true; - } else { - overo_enabled = false; - } -#endif - if (overo_enabled) { - if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { - PIOS_DEBUG_Assert(0); - } - const uint32_t PACKET_SIZE = 1024; - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PACKET_SIZE); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PACKET_SIZE); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, - rx_buffer, PACKET_SIZE, - tx_buffer, PACKET_SIZE)) { - PIOS_Assert(0); - } - } - } -#endif - -#if defined(PIOS_INCLUDE_GCSRCVR) - GCSReceiverInitialize(); - uintptr_t pios_gcsrcvr_id; - PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); - uintptr_t pios_gcsrcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; -#endif /* PIOS_INCLUDE_GCSRCVR */ - -#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS - uint8_t hw_output_port; - HwFreedomOutputGet(&hw_output_port); - switch (hw_output_port) { - case HWFREEDOM_OUTPUT_DISABLED: - break; - case HWFREEDOM_OUTPUT_PWM: - /* Set up the servo outputs */ - PIOS_Servo_Init(&pios_servo_cfg); - break; - default: - break; - } -#else - PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); -#endif - - PIOS_DELAY_WaitmS(200); - - PIOS_SENSORS_Init(); - -#if defined(PIOS_INCLUDE_MPU6000) - if (PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg) != 0) - panic(2); - if (PIOS_MPU6000_Test() != 0) - panic(2); - - // To be safe map from UAVO enum to driver enum - uint8_t hw_gyro_range; - HwFreedomGyroRangeGet(&hw_gyro_range); - switch(hw_gyro_range) { - case HWFREEDOM_GYRORANGE_250: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); - break; - case HWFREEDOM_GYRORANGE_500: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); - break; - case HWFREEDOM_GYRORANGE_1000: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); - break; - case HWFREEDOM_GYRORANGE_2000: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); - break; - } - - uint8_t hw_accel_range; - HwFreedomAccelRangeGet(&hw_accel_range); - switch(hw_accel_range) { - case HWFREEDOM_ACCELRANGE_2G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); - break; - case HWFREEDOM_ACCELRANGE_4G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); - break; - case HWFREEDOM_ACCELRANGE_8G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); - break; - case HWFREEDOM_ACCELRANGE_16G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); - break; - } - - // the filter has to be set before rate else divisor calculation will fail - uint8_t hw_mpu6000_dlpf; - HwFreedomMPU6000DLPFGet(&hw_mpu6000_dlpf); - enum pios_mpu60x0_filter mpu6000_dlpf = \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_256) ? PIOS_MPU60X0_LOWPASS_256_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_188) ? PIOS_MPU60X0_LOWPASS_188_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_98) ? PIOS_MPU60X0_LOWPASS_98_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_42) ? PIOS_MPU60X0_LOWPASS_42_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_20) ? PIOS_MPU60X0_LOWPASS_20_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_10) ? PIOS_MPU60X0_LOWPASS_10_HZ : \ - (hw_mpu6000_dlpf == HWFREEDOM_MPU6000DLPF_5) ? PIOS_MPU60X0_LOWPASS_5_HZ : \ - pios_mpu6000_cfg.default_filter; - PIOS_MPU6000_SetLPF(mpu6000_dlpf); - - uint8_t hw_mpu6000_samplerate; - HwFreedomMPU6000RateGet(&hw_mpu6000_samplerate); - uint16_t mpu6000_samplerate = \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_200) ? 200 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_333) ? 333 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_500) ? 500 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_666) ? 666 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_1000) ? 1000 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_2000) ? 2000 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_4000) ? 4000 : \ - (hw_mpu6000_samplerate == HWFREEDOM_MPU6000RATE_8000) ? 8000 : \ - pios_mpu6000_cfg.default_samplerate; - PIOS_MPU6000_SetSampleRate(mpu6000_samplerate); -#endif - - if (PIOS_I2C_Init(&pios_i2c_mag_pressure_adapter_id, &pios_i2c_mag_pressure_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - if (PIOS_I2C_CheckClear(pios_i2c_mag_pressure_adapter_id) != 0) - panic(5); - - PIOS_DELAY_WaitmS(50); - -#if defined(PIOS_INCLUDE_ADC) - uint32_t internal_adc_id; - PIOS_INTERNAL_ADC_Init(&internal_adc_id, &pios_adc_cfg); - PIOS_ADC_Init(&pios_internal_adc_id, &pios_internal_adc_driver, internal_adc_id); -#endif - - PIOS_LED_On(0); -#if defined(PIOS_INCLUDE_HMC5883) - if (PIOS_HMC5883_Init(pios_i2c_mag_pressure_adapter_id, &pios_hmc5883_cfg) != 0) - panic(3); -#endif - PIOS_LED_On(1); - - -#if defined(PIOS_INCLUDE_MS5611) - if (PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_mag_pressure_adapter_id) != 0) - panic(4); -#endif - PIOS_LED_On(2); -} - -/** - * @} - * @} - */ - diff --git a/flight/targets/naze32/board-info/board-info.mk b/flight/targets/naze32/board-info/board-info.mk new file mode 100644 index 00000000000..239e1dab3da --- /dev/null +++ b/flight/targets/naze32/board-info/board-info.mk @@ -0,0 +1,25 @@ +BOARD_TYPE := 0xA0 +BOARD_REVISION := 0x01 +BOOTLOADER_VERSION := 0x80 +HW_TYPE := 0x01 + +MCU := cortex-m3 +CHIP := STM32F103CBT +BOARD := STM32103CB_Naze32 +MODEL := MD +MODEL_SUFFIX := _NZ + +OPENOCD_JTAG_CONFIG := stlink-v2-norst.cfg +OPENOCD_CONFIG := stm32f1xx.stlink.cfg + +# Note: These must match the values in link_$(BOARD)_memory.ld +FW_BANK_BASE := 0x08000000 # Start of firmware flash +FW_BANK_SIZE := 0x0001D000 # Should include FW_DESC_SIZE (116kB) + +FW_DESC_SIZE := 0x00000064 + +EE_BANK_BASE := 0x0801D000 # EEPROM storage area (@116kb) +EE_BANK_SIZE := 0x00003000 # Size of EEPROM storage area (12kb) + +EF_BANK_BASE := 0x08000000 # Start of entire flash image (usually start of bootloader as well) +EF_BANK_SIZE := 0x00020000 # Size of the entire flash image (from bootloader until end of firmware) diff --git a/flight/targets/naze32/board-info/board_hw_defs.c b/flight/targets/naze32/board-info/board_hw_defs.c new file mode 100644 index 00000000000..106a14d5163 --- /dev/null +++ b/flight/targets/naze32/board-info/board_hw_defs.c @@ -0,0 +1,991 @@ +/** + ****************************************************************************** + * @addtogroup TauLabsTargets Tau Labs Targets + * @{ + * @addtogroup Naze32 family support files + * @{ + * + * @file board_hw_defs.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 + * @brief Defines board specific static initializers for hardware for the + * Naze32 family of boards. + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include +#include + +#if defined(PIOS_INCLUDE_LED) + +#include +static const struct pios_led pios_leds[] = { + [PIOS_LED_HEARTBEAT] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + .remap = GPIO_Remap_SWJ_JTAGDisable, + }, + [PIOS_LED_ALARM] = { + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_4, + .GPIO_Mode = GPIO_Mode_Out_PP, + .GPIO_Speed = GPIO_Speed_50MHz, + }, + }, + }, +}; + +static const struct pios_led_cfg pios_led_cfg = { + .leds = pios_leds, + .num_leds = NELEMENTS(pios_leds), +}; + +const struct pios_led_cfg * PIOS_BOARD_HW_DEFS_GetLedCfg (uint32_t board_revision) +{ + return &pios_led_cfg; +} + +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_SPI) + +#include + +/* Flash/Accel Interface + * + * NOTE: Leave this declared as const data so that it ends up in the + * .rodata section (ie. Flash) rather than in the .bss section (RAM). + */ +void PIOS_SPI_generic_irq_handler(void); +void DMA1_Channel4_IRQHandler() __attribute__ ((alias ("PIOS_SPI_generic_irq_handler"))); +void DMA1_Channel5_IRQHandler() __attribute__ ((alias ("PIOS_SPI_generic_irq_handler"))); +static const struct pios_spi_cfg pios_spi_generic_cfg = { + .regs = SPI2, + .init = { + .SPI_Mode = SPI_Mode_Master, + .SPI_Direction = SPI_Direction_2Lines_FullDuplex, + .SPI_DataSize = SPI_DataSize_8b, + .SPI_NSS = SPI_NSS_Soft, + .SPI_FirstBit = SPI_FirstBit_MSB, + .SPI_CRCPolynomial = 7, + .SPI_CPOL = SPI_CPOL_High, + .SPI_CPHA = SPI_CPHA_2Edge, + .SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8, + }, + .use_crc = false, + .dma = { + .ahb_clk = RCC_AHBPeriph_DMA1, + + .irq = { + .flags = (DMA1_FLAG_TC4 | DMA1_FLAG_TE4 | DMA1_FLAG_HT4 | DMA1_FLAG_GL4), + .init = { + .NVIC_IRQChannel = DMA1_Channel4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + + .rx = { + .channel = DMA1_Channel4, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralSRC, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + .tx = { + .channel = DMA1_Channel5, + .init = { + .DMA_PeripheralBaseAddr = (uint32_t)&(SPI2->DR), + .DMA_DIR = DMA_DIR_PeripheralDST, + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, + .DMA_MemoryInc = DMA_MemoryInc_Enable, + .DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte, + .DMA_MemoryDataSize = DMA_MemoryDataSize_Byte, + .DMA_Mode = DMA_Mode_Normal, + .DMA_Priority = DMA_Priority_High, + .DMA_M2M = DMA_M2M_Disable, + }, + }, + }, + .sclk = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .miso = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .mosi = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_15, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, + .slave_count = 1, + .ssel = {{ + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_50MHz, + .GPIO_Mode = GPIO_Mode_Out_PP, + }, + }}, +}; + +static uint32_t pios_spi_generic_id; +void PIOS_SPI_generic_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_SPI_IRQ_Handler(pios_spi_generic_id); +} + +#endif /* PIOS_INCLUDE_SPI */ + +#if defined(PIOS_INCLUDE_FLASH) +#include "pios_flashfs_logfs_priv.h" + +static const struct flashfs_logfs_cfg flashfs_internal_settings_cfg = { + .fs_magic = 0x9ae1ee11, + .arena_size = 0x00001800, /* 32 * slot size = 8K bytes = 4 sectors */ + .slot_size = 0x00000100, /* 256 bytes */ +}; + +#include "pios_flash_internal_priv.h" + +static const struct pios_flash_internal_cfg flash_internal_cfg = { +}; + +#include "pios_flash_priv.h" + +static const struct pios_flash_sector_range stm32f1_sectors[] = { + { + .base_sector = 0, + .last_sector = 127, + .sector_size = FLASH_SECTOR_1KB, + }, +}; + +uintptr_t pios_internal_flash_id; +static const struct pios_flash_chip pios_flash_chip_internal = { + .driver = &pios_internal_flash_driver, + .chip_id = &pios_internal_flash_id, + .page_size = 8, + .sector_blocks = stm32f1_sectors, + .num_blocks = NELEMENTS(stm32f1_sectors), +}; + +static const struct pios_flash_partition pios_flash_partition_table[] = { + { + .label = FLASH_PARTITION_LABEL_SETTINGS, + .chip_desc = &pios_flash_chip_internal, + .first_sector = 116, // 0x0801D000 + .last_sector = 127, // 0x08020000 + .chip_offset = (116 * FLASH_SECTOR_1KB), + .size = 12 * FLASH_SECTOR_1KB, + }, +}; + +const struct pios_flash_partition * PIOS_BOARD_HW_DEFS_GetPartitionTable (uint32_t board_revision, uint32_t * num_partitions) +{ + PIOS_Assert(num_partitions); + + *num_partitions = NELEMENTS(pios_flash_partition_table); + return pios_flash_partition_table; +} + +#endif /* PIOS_INCLUDE_FLASH */ + +#include "pios_tim_priv.h" + +static const TIM_TimeBaseInitTypeDef tim_1_2_3_4_time_base = { + .TIM_Prescaler = (PIOS_SYSCLK / 1000000) - 1, + .TIM_ClockDivision = TIM_CKD_DIV1, + .TIM_CounterMode = TIM_CounterMode_Up, + .TIM_Period = ((1000000 / PIOS_SERVO_UPDATE_HZ) - 1), + .TIM_RepetitionCounter = 0x0000, +}; + +static const struct pios_tim_clock_cfg tim_1_cfg = { + .timer = TIM1, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM1_CC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_2_cfg = { + .timer = TIM2, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_3_cfg = { + .timer = TIM3, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_clock_cfg tim_4_cfg = { + .timer = TIM4, + .time_base_init = &tim_1_2_3_4_time_base, + .irq = { + .init = { + .NVIC_IRQChannel = TIM4_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_rcvrport_all_channels[] = { + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + +static const struct pios_tim_channel pios_tim_servoport_all_pins[] = { + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + + +static const struct pios_tim_channel pios_tim_servoport_rcvrport_pins[] = { + { + .timer = TIM1, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM1, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_8, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM4, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Mode = GPIO_Mode_AF_PP, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + + // Receiver port pins + // inputs are used as outputs in this case + { + .timer = TIM2, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM2, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_6, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_2, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_7, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_3, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_0, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, + { + .timer = TIM3, + .timer_chan = TIM_Channel_4, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IPD, + .GPIO_Speed = GPIO_Speed_2MHz, + }, + }, + }, +}; + +#if defined(PIOS_INCLUDE_USART) + +#include "pios_usart_priv.h" + +static const struct pios_usart_cfg pios_usart_main_cfg = { + .regs = USART1, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_9, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_rcvrserial_cfg = { + .regs = USART2, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + +static const struct pios_usart_cfg pios_usart_dsm_hsum_rcvrserial_cfg = { + .regs = USART2, + .init = { + .USART_BaudRate = 115200, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + +#if defined(PIOS_INCLUDE_DSM) +#include + +static const struct pios_dsm_cfg pios_dsm_rcvrserial_cfg = { + .bind = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_Out_PP + }, + }, +}; +#endif + +#endif /* PIOS_INCLUDE_USART */ + +#if defined(PIOS_INCLUDE_COM) + +#include "pios_com_priv.h" + +#endif /* PIOS_INCLUDE_COM */ + +#if defined(PIOS_INCLUDE_RTC) +/* + * Realtime Clock (RTC) + */ +#include + +void PIOS_RTC_IRQ_Handler (void); +void RTC_IRQHandler() __attribute__ ((alias ("PIOS_RTC_IRQ_Handler"))); +static const struct pios_rtc_cfg pios_rtc_main_cfg = { + .clksrc = RCC_RTCCLKSource_HSE_Div128, + .prescaler = 100, + .irq = { + .init = { + .NVIC_IRQChannel = RTC_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +void PIOS_RTC_IRQ_Handler (void) +{ + PIOS_RTC_irq_handler (); +} + +#endif + +#if defined(PIOS_INCLUDE_SERVO) && defined(PIOS_INCLUDE_TIM) +/* + * Servo outputs + */ +#include + +const struct pios_servo_cfg pios_servo_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_all_pins, + .num_channels = NELEMENTS(pios_tim_servoport_all_pins), +}; + +const struct pios_servo_cfg pios_servo_rcvr_cfg = { + .tim_oc_init = { + .TIM_OCMode = TIM_OCMode_PWM1, + .TIM_OutputState = TIM_OutputState_Enable, + .TIM_OutputNState = TIM_OutputNState_Disable, + .TIM_Pulse = PIOS_SERVOS_INITIAL_POSITION, + .TIM_OCPolarity = TIM_OCPolarity_High, + .TIM_OCNPolarity = TIM_OCPolarity_High, + .TIM_OCIdleState = TIM_OCIdleState_Reset, + .TIM_OCNIdleState = TIM_OCNIdleState_Reset, + }, + .channels = pios_tim_servoport_rcvrport_pins, + .num_channels = NELEMENTS(pios_tim_servoport_rcvrport_pins), +}; + +#endif /* PIOS_INCLUDE_SERVO && PIOS_INCLUDE_TIM */ + +/* + * PPM Inputs + */ +#if defined(PIOS_INCLUDE_PPM) +#include + +const struct pios_ppm_cfg pios_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + /* Use only the first channel for ppm */ + .channels = &pios_tim_rcvrport_all_channels[0], + .num_channels = 1, +}; + +#endif /* PIOS_INCLUDE_PPM */ + +/* + * PWM Inputs + */ +#if defined(PIOS_INCLUDE_PWM) +#include + +const struct pios_pwm_cfg pios_pwm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + .channels = pios_tim_rcvrport_all_channels, + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels), +}; + +const struct pios_pwm_cfg pios_pwm_with_ppm_cfg = { + .tim_ic_init = { + .TIM_ICPolarity = TIM_ICPolarity_Rising, + .TIM_ICSelection = TIM_ICSelection_DirectTI, + .TIM_ICPrescaler = TIM_ICPSC_DIV1, + .TIM_ICFilter = 0x0, + }, + /* Leave the first channel for PPM use and use the rest for PWM */ + .channels = &pios_tim_rcvrport_all_channels[1], + .num_channels = NELEMENTS(pios_tim_rcvrport_all_channels) - 1, +}; + +#endif + +#if defined(PIOS_INCLUDE_I2C) + +#include + +/* + * I2C Adapters + */ + +void PIOS_I2C_adapter_ev_irq_handler(void); +void PIOS_I2C_adapter_er_irq_handler(void); +void I2C2_EV_IRQHandler() __attribute__ ((alias ("PIOS_I2C_adapter_ev_irq_handler"))); +void I2C2_ER_IRQHandler() __attribute__ ((alias ("PIOS_I2C_adapter_er_irq_handler"))); + +static const struct pios_i2c_adapter_cfg pios_i2c_internal_cfg = { + .regs = I2C2, + .init = { + .I2C_Mode = I2C_Mode_I2C, + .I2C_OwnAddress1 = 0, + .I2C_Ack = I2C_Ack_Enable, + .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, + .I2C_DutyCycle = I2C_DutyCycle_2, + .I2C_ClockSpeed = 400000, /* bits/s */ + }, + .transfer_timeout_ms = 50, + .scl = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_OD, + }, + }, + .sda = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_11, + .GPIO_Speed = GPIO_Speed_10MHz, + .GPIO_Mode = GPIO_Mode_AF_OD, + }, + }, + .event = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_EV_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_EXTREME, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .error = { + .flags = 0, /* FIXME: check this */ + .init = { + .NVIC_IRQChannel = I2C2_ER_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_EXTREME, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, +}; + +uint32_t pios_i2c_internal_id; +void PIOS_I2C_adapter_ev_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_EV_IRQ_Handler(pios_i2c_internal_id); +} + +void PIOS_I2C_adapter_er_irq_handler(void) +{ + /* Call into the generic code to handle the IRQ for this specific device */ + PIOS_I2C_ER_IRQ_Handler(pios_i2c_internal_id); +} + +#endif /* PIOS_INCLUDE_I2C */ + +#if defined(PIOS_INCLUDE_GCSRCVR) +#include "pios_gcsrcvr_priv.h" +#endif /* PIOS_INCLUDE_GCSRCVR */ + +#if defined(PIOS_INCLUDE_RCVR) +#include "pios_rcvr_priv.h" + +#endif /* PIOS_INCLUDE_RCVR */ + +#if defined(PIOS_INCLUDE_COM_MSG) + +#include + +#endif /* PIOS_INCLUDE_COM_MSG */ diff --git a/flight/targets/naze32/board-info/pios_board.h b/flight/targets/naze32/board-info/pios_board.h new file mode 100644 index 00000000000..2e8206c00ae --- /dev/null +++ b/flight/targets/naze32/board-info/pios_board.h @@ -0,0 +1,189 @@ +/** + ****************************************************************************** + * @addtogroup TauLabsTargets Tau Labs Targets + * @{ + * @addtogroup Naze32 family support files + * @{ + * + * @file pios_board.h + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 + * @brief Board header file for Naze32 + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + + +#ifndef STM32103CB_NAZE32_H_ +#define STM32103CB_NAZE32_H_ + +#include + +//------------------------ +// Timers and Channels Used +//------------------------ +/* +Timer | Channel 1 | Channel 2 | Channel 3 | Channel 4 +------+-----------+-----------+-----------+---------- +TIM1 | Servo 1 | | | Servo 2 +TIM2 | RC In 1 | RC In 2 | RC In 3 | RC In 4 +TIM3 | RC In 5 | RC In 6 | RC In 7 | RC In 8 +TIM4 | Servo 3 | Servo 4 | Servo 5 | Servo 6 +------+-----------+-----------+-----------+---------- +*/ + +//------------------------ +// DMA Channels Used +//------------------------ +/* Channel 1 - */ +/* Channel 2 - */ +/* Channel 3 - */ +/* Channel 4 - */ +/* Channel 5 - */ +/* Channel 6 - */ +/* Channel 7 - */ +/* Channel 8 - */ +/* Channel 9 - */ +/* Channel 10 - */ +/* Channel 11 - */ +/* Channel 12 - */ + +//------------------------ +// BOOTLOADER_SETTINGS +//------------------------ +#define BOARD_READABLE true +#define BOARD_WRITABLE true +#define MAX_DEL_RETRYS 3 + + +//------------------------ +// PIOS_LED +//------------------------ +#define PIOS_LED_HEARTBEAT 0 +#define PIOS_LED_ALARM 1 + +//------------------------ +// PIOS_WDG +//------------------------ +#define PIOS_WATCHDOG_TIMEOUT 250 +#define PIOS_WDG_REGISTER BKP_DR4 + +//------------------------ +// PIOS_I2C +// See also pios_board.c +//------------------------ +#define PIOS_I2C_MAX_DEVS 1 + +//------------------------- +// PIOS_COM +// +// See also pios_board.c +//------------------------- +extern uintptr_t pios_com_telem_serial_id; +extern uintptr_t pios_com_gps_id; +extern uintptr_t pios_com_bridge_id; +extern uintptr_t pios_com_mavlink_id; + +#define PIOS_COM_GPS (pios_com_gps_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_serial_id) +#define PIOS_COM_BRIDGE (pios_com_bridge_id) +#define PIOS_COM_MAVLINK (pios_com_mavlink_id) + +//------------------------ +// TELEMETRY +//------------------------ +#define TELEM_QUEUE_SIZE 20 + +//------------------------- +// System Settings +// +// See also system_stm32f10x.c +//------------------------- +//These macros are deprecated + +#define PIOS_SYSCLK 72000000 +#define PIOS_PERIPHERAL_APB1_CLOCK (PIOS_SYSCLK / 2) +#define PIOS_PERIPHERAL_APB2_CLOCK (PIOS_SYSCLK / 1) + + +//------------------------- +// Interrupt Priorities +//------------------------- +#define PIOS_IRQ_PRIO_LOW 12 // lower than RTOS +#define PIOS_IRQ_PRIO_MID 8 // higher than RTOS +#define PIOS_IRQ_PRIO_HIGH 5 // for SPI, ADC, I2C etc... +#define PIOS_IRQ_PRIO_HIGHEST 4 // for USART etc... +#define PIOS_IRQ_PRIO_EXTREME 0 // for I2C + +//------------------------ +// PIOS_RCVR +// See also pios_board.c +//------------------------ +#define PIOS_RCVR_MAX_CHANNELS 12 +#define PIOS_GCSRCVR_TIMEOUT_MS 100 + +//------------------------- +// Receiver PPM input +//------------------------- +#define PIOS_PPM_NUM_INPUTS 8 + +//------------------------- +// Receiver PWM input +//------------------------- +#define PIOS_PWM_NUM_INPUTS 8 + +//------------------------- +// Receiver DSM input +//------------------------- +#define PIOS_DSM_NUM_INPUTS 12 + +//------------------------- +// Receiver HSUM input +//------------------------- +#define PIOS_HSUM_MAX_DEVS 2 +#define PIOS_HSUM_NUM_INPUTS 32 + + +//------------------------- +// Servo outputs +//------------------------- +#define PIOS_SERVO_UPDATE_HZ 50 +#define PIOS_SERVOS_INITIAL_POSITION 0 /* dont want to start motors, have no pulse till settings loaded */ + +//-------------------------- +// Timer controller settings +//-------------------------- +#define PIOS_TIM_MAX_DEVS 3 + +//------------------------- +// ADC +//------------------------- + +//------------------------- +// GPIO +//------------------------- +#define PIOS_GPIO_PORTS { } +#define PIOS_GPIO_PINS { } +#define PIOS_GPIO_CLKS { } +#define PIOS_GPIO_NUM 0 + +#endif /* STM32103CB_NAZE32_H_ */ + +/** + * @} + * @} + */ diff --git a/flight/targets/naze32/board-info/system_stm32f10x.c b/flight/targets/naze32/board-info/system_stm32f10x.c new file mode 100644 index 00000000000..f3442ced902 --- /dev/null +++ b/flight/targets/naze32/board-info/system_stm32f10x.c @@ -0,0 +1,176 @@ +#include "stm32f10x.h" + +#define SYSCLK_FREQ_72MHz 72000000 + +uint32_t SystemCoreClock = SYSCLK_FREQ_72MHz; /*!< System Clock Frequency (Core Clock) */ + +__I uint8_t AHBPrescTable[16] = { 0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9 }; + +uint32_t hse_value = 8000000; + +void SystemInit(void) +{ + /* Reset the RCC clock configuration to the default reset state(for debug purpose) */ + /* Set HSION bit */ + RCC->CR |= (uint32_t) 0x00000001; + + /* Reset SW, HPRE, PPRE1, PPRE2, ADCPRE and MCO bits */ + RCC->CFGR &= (uint32_t) 0xF8FF0000; + + /* Reset HSEON, CSSON and PLLON bits */ + RCC->CR &= (uint32_t) 0xFEF6FFFF; + + /* Reset HSEBYP bit */ + RCC->CR &= (uint32_t) 0xFFFBFFFF; + + /* Reset PLLSRC, PLLXTPRE, PLLMUL and USBPRE/OTGFSPRE bits */ + RCC->CFGR &= (uint32_t) 0xFF80FFFF; + + /* Disable all interrupts and clear pending bits */ + RCC->CIR = 0x009F0000; + + SCB->VTOR = FLASH_BASE; /* Vector Table Relocation in Internal FLASH. */ +} + +void SystemCoreClockUpdate(void) +{ + uint32_t tmp = 0, pllmull = 0, pllsource = 0; + + /* Get SYSCLK source ------------------------------------------------------- */ + tmp = RCC->CFGR & RCC_CFGR_SWS; + + switch (tmp) { + case 0x00: /* HSI used as system clock */ + SystemCoreClock = HSI_VALUE; + break; + case 0x04: /* HSE used as system clock */ + SystemCoreClock = hse_value; + break; + case 0x08: /* PLL used as system clock */ + + /* Get PLL clock source and multiplication factor ---------------------- */ + pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; + pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; + + pllmull = (pllmull >> 18) + 2; + + if (pllsource == 0x00) { + /* HSI oscillator clock divided by 2 selected as PLL clock entry */ + SystemCoreClock = (HSI_VALUE >> 1) * pllmull; + } else { + /* HSE selected as PLL clock entry */ + if ((RCC->CFGR & RCC_CFGR_PLLXTPRE) != (uint32_t) RESET) { /* HSE oscillator clock divided by 2 */ + SystemCoreClock = (hse_value >> 1) * pllmull; + } else { + SystemCoreClock = hse_value * pllmull; + } + } + break; + + default: + SystemCoreClock = HSI_VALUE; + break; + } + + /* Compute HCLK clock frequency ---------------- */ + /* Get HCLK prescaler */ + tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; + /* HCLK clock frequency */ + SystemCoreClock >>= tmp; +} + +enum { + SRC_NONE = 0, + SRC_HSI, + SRC_HSE +}; + +// Set system clock to 72 (HSE) or 64 (HSI) MHz +void SetSysClock(void) +{ + __IO uint32_t StartUpCounter = 0, status = 0, clocksrc = SRC_NONE; + __IO uint32_t *RCC_CRH = &GPIOC->CRH; + __IO uint32_t RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9; + + // First, try running off HSE + RCC->CR |= ((uint32_t)RCC_CR_HSEON); + RCC->APB2ENR |= RCC_CFGR_HPRE_0; + + // Wait till HSE is ready + do { + status = RCC->CR & RCC_CR_HSERDY; + StartUpCounter++; + } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + + if ((RCC->CR & RCC_CR_HSERDY) != RESET) { + // external xtal started up, we're good to go + clocksrc = SRC_HSE; + } else { + // If HSE fails to start-up, try to enable HSI and configure for 64MHz operation + RCC->CR |= ((uint32_t)RCC_CR_HSION); + StartUpCounter = 0; + do { + status = RCC->CR & RCC_CR_HSIRDY; + StartUpCounter++; + } while ((status == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); + if ((RCC->CR & RCC_CR_HSIRDY) != RESET) { + // we're on internal RC + clocksrc = SRC_HSI; + } else { + // We're fucked + while(1); + } + } + + // Enable Prefetch Buffer + FLASH->ACR |= FLASH_ACR_PRFTBE; + // Flash 2 wait state + FLASH->ACR &= (uint32_t)((uint32_t)~FLASH_ACR_LATENCY); + FLASH->ACR |= (uint32_t)FLASH_ACR_LATENCY_2; + // HCLK = SYSCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; + // PCLK2 = HCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; + // PCLK1 = HCLK + RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; + *RCC_CRH &= (uint32_t)~((uint32_t)0xF << (RCC_CFGR_PLLMULL9 >> 16)); + + // Configure PLL + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_PLLSRC | RCC_CFGR_PLLXTPRE | RCC_CFGR_PLLMULL)); + *RCC_CRH |= (uint32_t)0x8 << (RCC_CFGR_PLLMULL9 >> 16); + + GPIOC->ODR &= (uint32_t)~(GPIO_Pin_15); + uint32_t detect_12mhz = GPIOC->IDR & GPIO_Pin_15; + + // hardcode for my board + if (detect_12mhz) { + hse_value = 12000000; + RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL6; + } else { + hse_value = 8000000; + RCC_CFGR_PLLMUL = RCC_CFGR_PLLMULL9; + } + + switch (clocksrc) { + case SRC_HSE: + // PLL configuration: PLLCLK = HSE * 9 = 72 MHz + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSE | RCC_CFGR_PLLMUL); + break; + case SRC_HSI: + // PLL configuration: PLLCLK = HSI / 2 * 16 = 64 MHz + RCC->CFGR |= (uint32_t)(RCC_CFGR_PLLSRC_HSI_Div2 | RCC_CFGR_PLLMULL16); + break; + } + + // Enable PLL + RCC->CR |= RCC_CR_PLLON; + // Wait till PLL is ready + while ((RCC->CR & RCC_CR_PLLRDY) == 0); + // Select PLL as system clock source + RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); + RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; + // Wait till PLL is used as system clock source + while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS) != (uint32_t)0x08); + + SystemCoreClockUpdate(); +} diff --git a/flight/targets/naze32/fw/FreeRTOSConfig.h b/flight/targets/naze32/fw/FreeRTOSConfig.h new file mode 100644 index 00000000000..56a92d2084f --- /dev/null +++ b/flight/targets/naze32/fw/FreeRTOSConfig.h @@ -0,0 +1,103 @@ + +#ifndef FREERTOS_CONFIG_H +#define FREERTOS_CONFIG_H + +#if !defined(SIM_OSX) && !defined(SIM_POSIX) +#include +#endif + +/*----------------------------------------------------------- + * Application specific definitions. + * + * These definitions should be adjusted for your particular hardware and + * application requirements. + * + * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE + * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. + * + * See http://www.freertos.org/a00110.html. + *----------------------------------------------------------*/ + +/** + * @addtogroup PIOS PIOS + * @{ + * @addtogroup FreeRTOS FreeRTOS + * @{ + */ + +/* Notes: We use 5 task priorities */ + +#define configUSE_PREEMPTION 1 +#define configUSE_IDLE_HOOK 1 +#define configUSE_TICK_HOOK 0 +#define configUSE_MALLOC_FAILED_HOOK 1 +#define configCPU_CLOCK_HZ ( ( unsigned long ) 72000000 ) +#define configTICK_RATE_HZ ( ( portTickType ) 1000 ) +#define configMAX_PRIORITIES ( ( unsigned portBASE_TYPE ) 5 ) +#define configMINIMAL_STACK_SIZE ( ( unsigned short ) 48 ) +#define configTOTAL_HEAP_SIZE ( ( size_t ) ( 53 * 256) ) +#define configMAX_TASK_NAME_LEN ( 16 ) +#define configUSE_TRACE_FACILITY 0 +#define configUSE_16_BIT_TICKS 0 +#define configIDLE_SHOULD_YIELD 0 +#define configUSE_MUTEXES 1 +#define configUSE_RECURSIVE_MUTEXES 1 +#define configUSE_COUNTING_SEMAPHORES 0 +#define configUSE_ALTERNATIVE_API 0 +#define configQUEUE_REGISTRY_SIZE 0 + +/* Co-routine definitions. */ +#define configUSE_CO_ROUTINES 0 +#define configMAX_CO_ROUTINE_PRIORITIES ( 2 ) + +/* Set the following definitions to 1 to include the API function, or zero +to exclude the API function. */ + +#define INCLUDE_vTaskPrioritySet 1 +#define INCLUDE_uxTaskPriorityGet 1 +#define INCLUDE_vTaskDelete 1 +#define INCLUDE_vTaskCleanUpResources 0 +#define INCLUDE_vTaskSuspend 1 +#define INCLUDE_vTaskDelayUntil 1 +#define INCLUDE_vTaskDelay 1 +#define INCLUDE_xTaskGetSchedulerState 1 +#define INCLUDE_xTaskGetCurrentTaskHandle 1 +#define INCLUDE_uxTaskGetStackHighWaterMark 1 + +/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 +(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ +#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ +#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ + +/* This is the value being used as per the ST library which permits 16 +priority values, 0 to 15. This must correspond to the +configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest +NVIC value of 255. */ +#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 + +#if !defined(ARCH_POSIX) && !defined(ARCH_WIN32) +#define CHECK_IRQ_STACK +#endif + +/* Enable run time stats collection */ +#if defined(DIAG_TASKS) +#define configCHECK_FOR_STACK_OVERFLOW 2 + +#define configGENERATE_RUN_TIME_STATS 1 +#define INCLUDE_uxTaskGetRunTime 1 +#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS()\ +do {\ +(*(unsigned long *)0xe000edfc) |= (1<<24);/* DEMCR |= DEMCR_TRCENA */\ +(*(unsigned long *)0xe0001000) |= 1; /* DWT_CTRL |= DWT_CYCCNT_ENA */\ +} while(0) +#define portGET_RUN_TIME_COUNTER_VALUE() (*(unsigned long *)0xe0001004)/* DWT_CYCCNT */ +#else +#define configCHECK_FOR_STACK_OVERFLOW 1 +#endif + + +/** + * @} + */ + +#endif /* FREERTOS_CONFIG_H */ diff --git a/flight/targets/naze32/fw/Makefile b/flight/targets/naze32/fw/Makefile new file mode 100644 index 00000000000..16d9fd27b03 --- /dev/null +++ b/flight/targets/naze32/fw/Makefile @@ -0,0 +1,527 @@ +############################################################################### +# @file Makefile +# @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 +# @addtogroup +# @{ +# @addtogroup +# @{ +# @brief Makefile to build firmware for the Naze family of boards. +############################################################################### +# +# This program is free software; you can redistribute it and/or modify +# it under the terms of the GNU General Public License as published by +# the Free Software Foundation; either version 3 of the License, or +# (at your option) any later version. +# +# This program is distributed in the hope that it will be useful, but +# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +# for more details. +# +# You should have received a copy of the GNU General Public License along +# with this program; if not, write to the Free Software Foundation, Inc., +# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +# + +include $(MAKE_INC_DIR)/firmware-defs.mk +include $(BOARD_INFO_DIR)/board-info.mk + +# @startgroup Compile Options +# @groupbrief Set developer code and compile options +# @optbrief Set to YES to compile for debugging +DEBUG ?= NO + +# @optbrief Include objects that are just nice information to show +STACK_DIAGNOSTICS ?= NO +MIXERSTATUS_DIAGNOSTICS ?= NO +RATEDESIRED_DIAGNOSTICS ?= NO +WDG_STATS_DIAGNOSTICS ?= NO +DIAG_TASKS ?= NO + +#Or just turn on all the above diagnostics. WARNING: This consumes massive amounts of memory. +ALL_DIGNOSTICS ?=NO + +# @optbrief Set to YES to build a FW version that will erase all flash memory +ERASE_FLASH ?= NO + +# @optbrief Set to YES to use the Servo output pins for debugging via scope or logic analyser +ENABLE_DEBUG_PINS ?= NO + +# @optbrief Set to Yes to enable the AUX UART which is mapped on the S1 (Tx) and S2 (Rx) servo outputs +ENABLE_AUX_UART ?= NO + +# @endgroup Compile Options + +# @startgroup Optional modules +# @groupbrief Optional module and driver defaults +USE_CAMERASTAB ?= YES +USE_GPS ?= YES +USE_TXPID ?= YES +USE_ALTITUDE ?= NO +USE_AUTOTUNE ?= YES +USE_UAVOMAVLINKBRIDGE ?= YES +USE_UAVOLIGHTTELEMETRYBRIDGE ?= NO +USE_UAVOFRSKYSENSORHUBBRIDGE ?= YES +USE_BATTERY ?= NO +# @endgroup Optional modules + +# List of optional modules to include +OPTMODULES = +ifeq ($(USE_CAMERASTAB), YES) +OPTMODULES += CameraStab +endif +ifeq ($(USE_GPS), YES) +OPTMODULES += GPS +endif +ifeq ($(USE_TXPID), YES) +OPTMODULES += TxPID +endif +ifeq ($(USE_ALTITUDE), YES) +OPTMODULES += Altitude +endif +ifeq ($(USE_AUTOTUNE), YES) +OPTMODULES += Autotune +endif +ifeq ($(USE_UAVOMAVLINKBRIDGE), YES) +OPTMODULES += UAVOMavlinkBridge +endif +ifeq ($(USE_UAVOFRSKYSENSORHUBBRIDGE), YES) +OPTMODULES += UAVOFrSKYSensorHubBridge +endif +ifeq ($(USE_BATTERY), YES) +OPTMODULES += Battery +endif +# List of mandatory modules to include +MODULES += Attitude/smallf1 +MODULES += Stabilization Actuator ManualControl FirmwareIAP +# Telemetry must be last to grab the optional modules (why?) +MODULES += Telemetry + +# Paths +OPUAVTALKINC = $(OPUAVTALK)/inc +OPUAVOBJINC = $(OPUAVOBJ)/inc +OPTESTS = ./Tests +FLIGHTLIBINC = $(FLIGHTLIB)/inc +STATEESTIMATIONLIB = $(FLIGHTLIB)/StateEstimationFilters +STATEESTIMATIONLIBINC = $(STATEESTIMATIONLIB)/inc +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math +PIOSINC = $(PIOS)/inc +PIOSSTM32F10X = $(PIOS)/STM32F10x +PIOSCOMMON = $(PIOS)/Common +PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +APPLIBDIR = $(PIOSSTM32F10X)/Libraries +STMLIBDIR = $(APPLIBDIR) +STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver +STMUSBDIR = $(STMLIBDIR)/STM32_USB-FS-Device_Driver +STMSPDSRCDIR = $(STMSPDDIR)/src +STMSPDINCDIR = $(STMSPDDIR)/inc +STMUSBSRCDIR = $(STMUSBDIR)/src +STMUSBINCDIR = $(STMUSBDIR)/inc +CMSISDIR = $(STMLIBDIR)/CMSIS/Core/CM3 +DOSFSDIR = $(APPLIBDIR)/dosfs +MSDDIR = $(APPLIBDIR)/msd +RTOSDIR = $(PIOSCOMMON)/Libraries/FreeRTOS +RTOSSRCDIR = $(RTOSDIR)/Source +RTOSINCDIR = $(RTOSSRCDIR)/include +RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source +DOXYGENDIR = ../Doc/Doxygen +MAVLINKINC = $(FLIGHTLIB)/mavlink/v1.0/common +PYMITE = $(FLIGHTLIB)/PyMite +PYMITELIB = $(PYMITE)/lib +PYMITEPLAT = $(PYMITE)/platform/openpilot +PYMITETOOLS = $(PYMITE)/tools +PYMITEVM = $(PYMITE)/vm +PYMITEINC = $(PYMITEVM) +PYMITEINC += $(PYMITEPLAT) +PYMITEINC += $(OUTDIR) +FLIGHTPLANLIB = $(OPMODULEDIR)/FlightPlan/lib +FLIGHTPLANS = $(OPMODULEDIR)/FlightPlan/flightplans + +# List C source files here. (C dependencies are automatically generated.) +# use file-extension c for "c-only"-files + +ifndef TESTAPP +## MODULES +SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +## OPENPILOT CORE: +SRC += ${OPMODULEDIR}/System/systemmod.c +SRC += main.c +SRC += pios_board.c +SRC += $(FLIGHTLIB)/alarms.c +SRC += $(OPUAVTALK)/uavtalk.c +SRC += $(OPUAVOBJ)/uavobjectmanager.c +SRC += $(OPUAVOBJ)/eventdispatcher.c +else +## TESTCODE +SRC += $(OPTESTS)/test_common.c +SRC += $(OPTESTS)/$(TESTAPP).c +endif + + +## PIOS Hardware (STM32F10x) +SRC += $(PIOSSTM32F10X)/pios_sys.c +SRC += $(PIOSSTM32F10X)/pios_led.c +SRC += $(PIOSSTM32F10X)/pios_usart.c +SRC += $(PIOSSTM32F10X)/pios_irq.c +#SRC += $(PIOSSTM32F10X)/pios_internal_adc.c +SRC += $(PIOSSTM32F10X)/pios_servo.c +#SRC += $(PIOSSTM32F10X)/pios_i2c.c +SRC += $(PIOSSTM32F10X)/pios_i2c_alt.c +SRC += $(PIOSSTM32F10X)/pios_spi.c +SRC += $(PIOSSTM32F10X)/pios_ppm.c +SRC += $(PIOSSTM32F10X)/pios_pwm.c +SRC += $(PIOSSTM32F10X)/pios_debug.c +SRC += $(PIOSSTM32F10X)/pios_gpio.c +SRC += $(PIOSSTM32F10X)/pios_exti.c +SRC += $(PIOSSTM32F10X)/pios_rtc.c +SRC += $(PIOSSTM32F10X)/pios_wdg.c +SRC += $(PIOSSTM32F10X)/pios_iap.c +SRC += $(PIOSSTM32F10X)/pios_tim.c +SRC += $(PIOSSTM32F10X)/pios_bl_helper.c +SRC += $(PIOSSTM32F10X)/pios_flash_internal.c + +## PIOS Hardware (Common) +SRC += $(PIOSCOMMON)/pios_delay.c +SRC += $(PIOSCOMMON)/pios_crc.c +SRC += $(PIOSCOMMON)/pios_dsm.c +SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c +SRC += $(PIOSCOMMON)/pios_flash_jedec.c +SRC += $(PIOSCOMMON)/pios_ms5611.c +SRC += $(PIOSCOMMON)/pios_mpu6050.c +SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_rcvr.c +SRC += $(PIOSCOMMON)/pios_hsum.c +SRC += $(PIOSCOMMON)/pios_sensors.c +SRC += $(PIOSCOMMON)/pios_gcsrcvr.c +SRC += $(PIOSCOMMON)/printf-stdarg.c +#SRC += $(PIOSCOMMON)/pios_adc.c +SRC += $(PIOSCOMMON)/pios_flash.c +SRC += $(PIOSCOMMON)/pios_heap.c +SRC += $(PIOSCOMMON)/pios_semaphore.c +SRC += $(PIOSCOMMON)/pios_mutex.c +SRC += $(PIOSCOMMON)/pios_thread.c +SRC += $(PIOSCOMMON)/pios_queue.c +SRC += $(PIOSCOMMON)/pios_hal.c + +SRC += $(PIOSCOMMON)/pios_board_info.c + + +## Libraries for flight calculations +SRC += $(FLIGHTLIB)/fifo_buffer.c +SRC += $(FLIGHTLIB)/taskmonitor.c +SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(MATHLIB)/coordinate_conversions.c +SRC += $(MATHLIB)/misc_math.c +SRC += $(MATHLIB)/pid.c + +## CMSIS for STM32 +include $(PIOSCOMMONLIB)/CMSIS3/library.mk +#SRC += $(BOARD_INFO_DIR)/cmsis_system.c +SRC += $(BOARD_INFO_DIR)/system_stm32f10x.c + +## Used parts of the STM-Library +SRC += $(STMSPDSRCDIR)/stm32f10x_adc.c +SRC += $(STMSPDSRCDIR)/stm32f10x_bkp.c +SRC += $(STMSPDSRCDIR)/stm32f10x_crc.c +SRC += $(STMSPDSRCDIR)/stm32f10x_dac.c +SRC += $(STMSPDSRCDIR)/stm32f10x_dma.c +SRC += $(STMSPDSRCDIR)/stm32f10x_exti.c +SRC += $(STMSPDSRCDIR)/stm32f10x_flash.c +SRC += $(STMSPDSRCDIR)/stm32f10x_gpio.c +SRC += $(STMSPDSRCDIR)/stm32f10x_i2c.c +SRC += $(STMSPDSRCDIR)/stm32f10x_pwr.c +SRC += $(STMSPDSRCDIR)/stm32f10x_rcc.c +SRC += $(STMSPDSRCDIR)/stm32f10x_rtc.c +SRC += $(STMSPDSRCDIR)/stm32f10x_spi.c +SRC += $(STMSPDSRCDIR)/stm32f10x_tim.c +SRC += $(STMSPDSRCDIR)/stm32f10x_usart.c +SRC += $(STMSPDSRCDIR)/stm32f10x_iwdg.c +SRC += $(STMSPDSRCDIR)/stm32f10x_dbgmcu.c +SRC += $(STMSPDSRCDIR)/misc.c + +## RTOS +SRC += $(RTOSSRCDIR)/list.c +SRC += $(RTOSSRCDIR)/queue.c +SRC += $(RTOSSRCDIR)/tasks.c + +## RTOS Portable +SRC += $(RTOSPORTDIR)/portable/GCC/ARM_CM3/port.c + +## Dosfs file system +#SRC += $(DOSFSDIR)/dosfs.c +#SRC += $(DOSFSDIR)/dfs_sdcard.c + +## PyMite files +#SRC += $(wildcard ${PYMITEVM}/*.c) +#SRC += $(wildcard ${PYMITEPLAT}/*.c) +#SRC += $(OUTDIR)/pmlib_img.c +#SRC += $(OUTDIR)/pmlib_nat.c +#SRC += $(OUTDIR)/pmlibusr_img.c +#SRC += $(OUTDIR)/pmlibusr_nat.c + +## Mass Storage Device +#SRC += $(MSDDIR)/msd.c +#SRC += $(MSDDIR)/msd_bot.c +#SRC += $(MSDDIR)/msd_desc.c +#SRC += $(MSDDIR)/msd_memory.c +#SRC += $(MSDDIR)/msd_scsi.c +#SRC += $(MSDDIR)/msd_scsi_data.c + +# List C source files here which must be compiled in ARM-Mode (no -mthumb). +# use file-extension c for "c-only"-files +## just for testing, timer.c could be compiled in thumb-mode too +SRCARM = + +# List C++ source files here. +# use file-extension .cpp for C++-files (not .C) +CPPSRC = + +# List C++ source files here which must be compiled in ARM-Mode. +# use file-extension .cpp for C++-files (not .C) +#CPPSRCARM = $(TARGET).cpp +CPPSRCARM = + +# List Assembler source files here. +# Make them always end in a capital .S. Files ending in a lowercase .s +# will not be considered source files but generated files (assembler +# output from the compiler), and will be deleted upon "make clean"! +# Even though the DOS/Win* filesystem matches both .s and .S the same, +# it will preserve the spelling of the filenames, and gcc itself does +# care about how the name is spelled on its command-line. +ASRC = $(PIOSSTM32F10X)/startup_stm32f10x_$(MODEL)$(MODEL_SUFFIX).S + +# List Assembler source files here which must be assembled in ARM-Mode.. +ASRCARM = + +# List any extra directories to look for include files here. +# Each directory must be seperated by a space. +EXTRAINCDIRS += $(SHAREDAPIDIR) +EXTRAINCDIRS += $(OPUAVTALK) +EXTRAINCDIRS += $(OPUAVTALKINC) +EXTRAINCDIRS += $(OPUAVOBJ) +EXTRAINCDIRS += $(OPUAVOBJINC) +EXTRAINCDIRS += $(OPUAVSYNTHDIR) +EXTRAINCDIRS += $(PIOS) +EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(FLIGHTLIBINC) +EXTRAINCDIRS += $(STATEESTIMATIONLIBINC) +EXTRAINCDIRS += $(MATHLIBINC) +EXTRAINCDIRS += $(PIOSSTM32F10X) +EXTRAINCDIRS += $(PIOSSTM32F10X)/inc +EXTRAINCDIRS += $(PIOSCOMMON) +EXTRAINCDIRS += $(BOARD_INFO_DIR) +EXTRAINCDIRS += $(STMSPDINCDIR) +EXTRAINCDIRS += $(STMUSBINCDIR) +EXTRAINCDIRS += $(CMSISDIR) +EXTRAINCDIRS += $(DOSFSDIR) +EXTRAINCDIRS += $(MSDDIR) +EXTRAINCDIRS += $(RTOSINCDIR) +EXTRAINCDIRS += $(APPLIBDIR) +EXTRAINCDIRS += $(RTOSPORTDIR)/portable/GCC/ARM_CM3 +EXTRAINCDIRS += $(AHRSBOOTLOADERINC) +EXTRAINCDIRS += $(PYMITEINC) +EXTRAINCDIRS += $(MAVLINKINC) + +EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES}, ${OPMODULEDIR}/${MOD}/inc} ${OPMODULEDIR}/System/inc + + +# List any extra directories to look for library files here. +# Also add directories where the linker should search for +# includes from linker-script to the list +# Each directory must be seperated by a space. +EXTRA_LIBDIRS = + +# Extra Libraries +# Each library-name must be seperated by a space. +# i.e. to link with libxyz.a, libabc.a and libefsl.a: +# EXTRA_LIBS = xyz abc efsl +# for newlib-lpc (file: libnewlibc-lpc.a): +# EXTRA_LIBS = newlib-lpc +EXTRA_LIBS = + +# Path to Linker-Scripts +LINKERSCRIPTPATH = .. + +# Optimization level, can be [0, 1, 2, 3, s]. +# 0 = turn off optimization. s = optimize for size. +# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) + +ifeq ($(DEBUG),YES) +OPT = 1 +else +OPT = s +endif + +# Output format. (can be ihex or binary or both) +# binary to create a load-image in raw-binary format i.e. for SAM-BA, +# ihex to create a load-image in Intel hex format +#LOADFORMAT = ihex +#LOADFORMAT = binary +LOADFORMAT = both + +# Debugging format. +DEBUGF = dwarf-2 + +# Place project-specific -D (define) and/or +# -U options for C here. +CDEFS = -DSTM32F10X_$(MODEL) +CDEFS += -DUSE_STDPERIPH_DRIVER +CDEFS += -DUSE_$(BOARD) +ifeq ($(ENABLE_DEBUG_PINS), YES) +CDEFS += -DPIOS_ENABLE_DEBUG_PINS +endif +ifeq ($(ENABLE_DEBUG_CONSOLE), YES) +CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE +endif +ifeq ($(ERASE_FLASH), YES) +CDEFS += -DERASE_FLASH +endif + +ifneq ($(USE_GPS), NO) +CDEFS += -DUSE_GPS +endif + +ifeq ($(USE_I2C), YES) +CDEFS += -DUSE_I2C +endif + +ifeq ($(USE_PCF8591), YES) +CDEFS += -DUSE_PCF8591 +endif + +# Declare all non-optional modules as built-in to force inclusion, strip off any appended varieties of module +get_mod_name = $(shell echo $(1) | sed "s/\/[^\/]*$///") +BUILTIN_DEFS := ${foreach MOD, ${MODULES}, -DMODULE_$(call get_mod_name, $(MOD))_BUILTIN } +CDEFS += ${BUILTIN_DEFS} + +# Provide board-specific defines +CDEFS += -DBOARD_TYPE=$(BOARD_TYPE) +CDEFS += -DBOARD_REVISION=$(BOARD_REVISION) +CDEFS += -DHW_TYPE=$(HW_TYPE) +CDEFS += -DBOOTLOADER_VERSION=$(BOOTLOADER_VERSION) +CDEFS += -DFW_BANK_BASE=$(FW_BANK_BASE) +CDEFS += -DFW_BANK_SIZE=$(FW_BANK_SIZE) +CDEFS += -DFW_DESC_SIZE=$(FW_DESC_SIZE) +CDEFS += -DEE_BANK_BASE=$(EE_BANK_BASE) +CDEFS += -DEE_BANK_SIZE=$(EE_BANK_SIZE) + +# Place project-specific -D and/or -U options for +# Assembler with preprocessor here. +#ADEFS = -DUSE_IRQ_ASM_WRAPPER +ADEFS = -D__ASSEMBLY__ + +# Compiler flag to set the C Standard level. +# c89 - "ANSI" C +# gnu89 - c89 plus GCC extensions +# c99 - ISO C99 standard (not yet fully implemented) +# gnu99 - c99 plus GCC extensions +CSTANDARD = -std=gnu99 + +#----- + +# Compiler flags. + +# -g*: generate debugging information +# -O*: optimization level +# -f...: tuning, see GCC manual and avr-libc documentation +# -Wall...: warning level +# -Wa,...: tell GCC to pass this to the assembler. +# -adhlns...: create assembler listing +# +# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) + +ifeq ($(DEBUG),YES) +CFLAGS += -DDEBUG +endif + +#The following Makefile command, ifneq (, $(filter) $(A), $(B) $(C)) is equivalent +# to the pseudocode `if(A== B || A==C)` +ifneq (,$(filter YES,$(STACK_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DSTACK_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(MIXERSTATUS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DMIXERSTATUS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(RATEDESIRED_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DRATEDESIRED_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(WDG_STATS_DIAGNOSTICS) $(ALL_DIGNOSTICS))) +CFLAGS += -DWDG_STATS_DIAGNOSTICS +endif + +ifneq (,$(filter YES,$(DIAG_TASKS) $(ALL_DIGNOSTICS))) +CFLAGS += -DDIAG_TASKS +endif + +CFLAGS += -g$(DEBUGF) +CFLAGS += -O$(OPT) +CFLAGS += -mcpu=$(MCU) +CFLAGS += $(CDEFS) +CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. + +#CFLAGS += -fno-cprop-registers -fno-defer-pop -fno-guess-branch-probability -fno-section-anchors +#CFLAGS += -fno-if-conversion -fno-if-conversion2 -fno-ipa-pure-const -fno-ipa-reference -fno-merge-constants +#CFLAGS += -fno-split-wide-types -fno-tree-ccp -fno-tree-ch -fno-tree-copy-prop -fno-tree-copyrename +#CFLAGS += -fno-tree-dce -fno-tree-dominator-opts -fno-tree-dse -fno-tree-fre -fno-tree-sink -fno-tree-sra +#CFLAGS += -fno-tree-ter +#CFLAGS += -g$(DEBUGF) -DDEBUG + +CFLAGS += -mapcs-frame +CFLAGS += -fomit-frame-pointer + +CFLAGS += -Wall +CFLAGS += -Werror +CFLAGS += -ffunction-sections -fdata-sections +CFLAGS += -Wdouble-promotion +CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +# Compiler flags to generate dependency files: +CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d + +# flags only for C +#CONLYFLAGS += -Wnested-externs +CONLYFLAGS += $(CSTANDARD) + +# Assembler flags. +# -Wa,...: tell GCC to pass this to the assembler. +# -ahlns: create listing +ASFLAGS = -mcpu=$(MCU) -I. -x assembler-with-cpp +ASFLAGS += $(ADEFS) +ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) +ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) + +MATH_LIB = -lm + +# Linker flags. +# -Wl,...: tell GCC to pass this to linker. +# -Map: create map file +# --cref: add cross reference to map file +LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections +LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) +LDFLAGS += -lc +LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) +LDFLAGS += $(MATH_LIB) +LDFLAGS += -lc -lgcc +LDFLAGS += -Wl,--warn-common +LDFLAGS += -Wl,--fatal-warnings + +# Set linker-script name depending on selected submodel name +LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld +LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld + +include ./UAVObjects.inc +include $(MAKE_INC_DIR)/firmware-common.mk + +# Hack to place firmware info at correct location in flash +$(OUTDIR)/$(TARGET).padded.bin: FW_DESC_BASE := $(shell echo $$(($(FW_BANK_BASE)+$(FW_BANK_SIZE)-$(FW_DESC_SIZE)))) +$(OUTDIR)/$(TARGET).padded.bin: $(OUTDIR)/$(TARGET).elf + $(V1) $(OBJCOPY) --pad-to=$(FW_DESC_BASE) -O binary $< $@ + +$(OUTDIR)/$(TARGET).tlfw: $(OUTDIR)/$(TARGET).padded.bin $(OUTDIR)/$(TARGET).bin.firmwareinfo.bin + @echo $(MSG_TLFIRMWARE) $(call toprel, $@) + $(V1) cat $^ > $@ diff --git a/flight/targets/naze32/fw/UAVObjects.inc b/flight/targets/naze32/fw/UAVObjects.inc new file mode 100644 index 00000000000..692c47b48ed --- /dev/null +++ b/flight/targets/naze32/fw/UAVObjects.inc @@ -0,0 +1 @@ +UAVOBJSRCFILENAMES += hwnaze diff --git a/flight/targets/revolution/fw/main.c b/flight/targets/naze32/fw/main.c similarity index 62% rename from flight/targets/revolution/fw/main.c rename to flight/targets/naze32/fw/main.c index 16f58704d38..c87917da138 100644 --- a/flight/targets/revolution/fw/main.c +++ b/flight/targets/naze32/fw/main.c @@ -2,12 +2,12 @@ ****************************************************************************** * @addtogroup TauLabsTargets Tau Labs Targets * @{ - * @addtogroup Revolution OpenPilot Revolution support files + * @addtogroup Naze32 family support files * @{ * - * @file revolution.c + * @file main.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief Start FreeRTOS and the Modules. * @see The GNU Public License (GPL) Version 3 * @@ -28,69 +28,71 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ + /* OpenPilot Includes */ #include "openpilot.h" #include "uavobjectsinit.h" #include "systemmod.h" -#include "pios_thread.h" - -#if defined(PIOS_INCLUDE_FREERTOS) #include "FreeRTOS.h" #include "task.h" -#endif /* defined(PIOS_INCLUDE_FREERTOS) */ + +/* Task Priorities */ +#define PRIORITY_TASK_HOOKS (tskIDLE_PRIORITY + 3) + +/* Global Variables */ /* Prototype of PIOS_Board_Init() function */ extern void PIOS_Board_Init(void); extern void Stack_Change(void); /* Local Variables */ -#define INIT_TASK_PRIORITY PIOS_THREAD_PRIO_HIGHEST -#if defined(SIM_POSIX) -#define INIT_TASK_STACK 32768 -#else -#define INIT_TASK_STACK 1024 -#endif /* defined(SIM_POSIX) */ -static struct pios_thread *initTaskHandle; +#define INIT_TASK_PRIORITY (tskIDLE_PRIORITY + configMAX_PRIORITIES - 1) // max priority +#define INIT_TASK_STACK (640 / 4) +static xTaskHandle initTaskHandle; /* Function Prototypes */ static void initTask(void *parameters); +/* Prototype of generated InitModules() function */ +extern void InitModules(void); + +/* board-info/system_stm32f10x.c */ +extern void SetSysClock(void); + /** - * Tau Labs Main function: - * - * Initialize PiOS
- * Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
- * Start FreeRTOS Scheduler (vTaskStartScheduler)
- * If something goes wrong, blink LED1 and LED2 every 100ms - * - */ -#if defined(SIM_POSIX) -int main(int argc, char *argv[]) { - PIOS_SYS_Args(argc, argv); -#else +* Tau Labs Main function: +* +* Initialize PiOS
+* Create the "System" task (SystemModInitializein Modules/System/systemmod.c)
+* Start FreeRTOS Scheduler (vTaskStartScheduler)
+* If something goes wrong, blink LED1 and LED2 every 100ms +* +*/ int main() { -#endif + int result; + /* NOTE: Do NOT modify the following start-up sequence */ /* Any new initialization functions should be added in OpenPilotInit() */ - PIOS_heap_initialize_blocks(); - -#if defined(PIOS_INCLUDE_CHIBIOS) - halInit(); - chSysInit(); - - boardInit(); -#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ + vPortInitialiseBlocks(); /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); - /* For Revolution we use a FreeRTOS task to bring up the system so we can */ + // Configure the System clock frequency, HCLK, PCLK2 and PCLK1 prescalers + // Configure the Flash Latency cycles and enable prefetch buffer + SetSysClock(); + + /* use a FreeRTOS task to bring up the system so we can */ /* always rely on FreeRTOS primitive */ - initTaskHandle = PIOS_Thread_Create(initTask, "init", INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY); - PIOS_Assert(initTaskHandle != NULL); + result = xTaskCreate(initTask, (const signed char *)"init", + INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY, + &initTaskHandle); + PIOS_Assert(result == pdPASS); + + /* swap the stack to use the IRQ stack */ + Stack_Change(); -#if defined(PIOS_INCLUDE_FREERTOS) /* Start the FreeRTOS scheduler */ vTaskStartScheduler(); @@ -101,17 +103,16 @@ int main() PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ PIOS_DELAY_WaitmS(100); \ }; -#elif defined(PIOS_INCLUDE_CHIBIOS) - PIOS_Thread_Sleep(PIOS_THREAD_TIMEOUT_MAX); -#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ + return 0; } /** - * Initialization task. + * Initialisation task. * - * Runs board and module initialization, then terminates. + * Runs board and module initialisation, then terminates. */ -void initTask(void *parameters) +void +initTask(void *parameters) { /* board driver init */ PIOS_Board_Init(); @@ -120,10 +121,11 @@ void initTask(void *parameters) MODULE_INITIALISE_ALL(PIOS_WDG_Clear); /* terminate this task */ - PIOS_Thread_Delete(NULL); + vTaskDelete(NULL); } /** * @} * @} */ + diff --git a/flight/targets/naze32/fw/pios_board.c b/flight/targets/naze32/fw/pios_board.c new file mode 100644 index 00000000000..cb4adb7ed05 --- /dev/null +++ b/flight/targets/naze32/fw/pios_board.c @@ -0,0 +1,561 @@ +/** + ****************************************************************************** + * @addtogroup TauLabsTargets Tau Labs Targets + * @{ + * @addtogroup Naze family support files + * @{ + * + * @file pios_board.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 + * @brief The board specific initialization routines + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +/* Pull in the board-specific static HW definitions. + * Including .c files is a bit ugly but this allows all of + * the HW definitions to be const and static to limit their + * scope. + * + * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE + */ + +#include "board_hw_defs.c" + +#include +#include +#include +#include +#include "hwnaze.h" +#include "manualcontrolsettings.h" +#include "modulesettings.h" + +/** + * Configuration for the HMC5883L chip + */ +#if defined(PIOS_INCLUDE_HMC5883) +#include "pios_hmc5883_priv.h" +static struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { + // MAG_DRDY output on rev4 hardware (PB12) + .vector = PIOS_HMC5883_IRQHandler, + .line = EXTI_Line12, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_12, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line12, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static struct pios_exti_cfg pios_exti_hmc5883_cfg_v5 __exti_config = { + // MAG_DRDY output on rev5 hardware PC14 + .vector = PIOS_HMC5883_IRQHandler, + .line = EXTI_Line14, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_14, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line14, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static /*const*/ struct pios_hmc5883_cfg pios_hmc5883_cfg = { + .exti_cfg = &pios_exti_hmc5883_cfg, + .M_ODR = PIOS_HMC5883_ODR_75, + .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, + .Gain = PIOS_HMC5883_GAIN_1_9, + .Mode = PIOS_HMC5883_MODE_CONTINUOUS, + .Default_Orientation = PIOS_HMC5883_TOP_90DEG, // TODO: check & fix orientation +}; + +#endif /* PIOS_INCLUDE_HMC5883 */ + +/** + * Configuration for the MS5611 chip + */ +#if defined(PIOS_INCLUDE_MS5611) +#include "pios_ms5611_priv.h" +static const struct pios_ms5611_cfg pios_ms5611_cfg = { + .oversampling = MS5611_OSR_512, + .temperature_interleaving = 1, +}; +#endif /* PIOS_INCLUDE_MS5611 */ + +/** + * Configuration for the MPU6050 chip + */ +#if defined(PIOS_INCLUDE_MPU6050) +#include "pios_mpu6050.h" +//#define PIOS_MPU6050_I2C_ADDR PIOS_MPU6050_I2C_ADD_A0_HIGH +#define PIOS_MPU6050_I2C_ADDR PIOS_MPU6050_I2C_ADD_A0_LOW +static const struct pios_exti_cfg pios_exti_mpu6050_cfg __exti_config = { + // MPU_INT output on rev4 hardware (PB13) + .vector = PIOS_MPU6050_IRQHandler, + .line = EXTI_Line13, + .pin = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line13, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static const struct pios_exti_cfg pios_exti_mpu6050_cfg_v5 __exti_config = { + // MPU_INT output on rev5 hardware (PC13) + .vector = PIOS_MPU6050_IRQHandler, + .line = EXTI_Line13, + .pin = { + .gpio = GPIOC, + .init = { + .GPIO_Pin = GPIO_Pin_13, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI15_10_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line13, // matches above GPIO pin + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Rising, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +static /*const*/ struct pios_mpu60x0_cfg pios_mpu6050_cfg = { + .exti_cfg = &pios_exti_mpu6050_cfg, + .default_samplerate = 400, + .interrupt_cfg = PIOS_MPU60X0_INT_CLR_ANYRD | PIOS_MPU60X0_INT_I2C_BYPASS_EN, + .interrupt_en = PIOS_MPU60X0_INTEN_DATA_RDY, + .User_ctl = 0, + .Pwr_mgmt_clk = PIOS_MPU60X0_PWRMGMT_PLL_Z_CLK, + .default_filter = PIOS_MPU60X0_LOWPASS_256_HZ, + .orientation = PIOS_MPU60X0_TOP_90DEG +}; +#endif /* PIOS_INCLUDE_MPU6050 */ + +#define PIOS_COM_TELEM_RF_RX_BUF_LEN 32 +#define PIOS_COM_TELEM_RF_TX_BUF_LEN 12 + +uintptr_t pios_com_lighttelemetry_id; + +uintptr_t pios_uavo_settings_fs_id; + +uintptr_t pios_internal_adc_id; + +/** + * Indicate a target-specific error code when a component fails to initialize + * 1 pulse - MPU6050 - no irq + * 2 pulses - MPU6050 - failed configuration or task starting + * 3 pulses - internal I2C bus locked + * 4 pulses - ms5611 + * 5 pulses - flash + * 6 pulses - hmc5883l + */ +void panic(int32_t code) { + PIOS_HAL_Panic(PIOS_LED_ALARM, code); +} + +/** + * PIOS_Board_Init() + * initializes all the core subsystems on this specific hardware + * called from System/openpilot.c + */ + +//#include +//from flight/targets/naze32/board-info/system_stm32f10x.c +extern uint32_t hse_value; + +void PIOS_Board_Init(void) { + + /* Delay system */ + PIOS_DELAY_Init(); + + bool board_v5; + if (hse_value == 12000000) + board_v5 = true; + else + board_v5 = false; + + //TODO: Buzzer + //rev5 needs inverted beeper. + + //const struct pios_board_info * bdinfo = &pios_board_info_blob; + +#if defined(PIOS_INCLUDE_LED) + const struct pios_led_cfg * led_cfg = PIOS_BOARD_HW_DEFS_GetLedCfg(1); + PIOS_Assert(led_cfg); + PIOS_LED_Init(led_cfg); +#endif /* PIOS_INCLUDE_LED */ + +#if defined(PIOS_INCLUDE_SPI) + /* Set up the SPI interface to the serial flash */ + + if (PIOS_SPI_Init(&pios_spi_generic_id, &pios_spi_generic_cfg)) { + PIOS_Assert(0); + } +#endif + +#if defined(PIOS_INCLUDE_I2C) + if (PIOS_I2C_Init(&pios_i2c_internal_id, &pios_i2c_internal_cfg)) { + PIOS_DEBUG_Assert(0); + } + if (PIOS_I2C_CheckClear(pios_i2c_internal_id) != 0) + panic(3); +#endif + +#if defined(PIOS_INCLUDE_FLASH) + /* Inititialize all flash drivers */ + if (PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg) != 0) + panic(5); + + /* Register the partition table */ + const struct pios_flash_partition * flash_partition_table; + uint32_t num_partitions; + flash_partition_table = PIOS_BOARD_HW_DEFS_GetPartitionTable(1, &num_partitions); + PIOS_FLASH_register_partition_table(flash_partition_table, num_partitions); + + /* Mount all filesystems */ + if (PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_internal_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS) != 0) + panic(5); + +#endif /* PIOS_INCLUDE_FLASH */ + + /* Initialize UAVObject libraries */ + EventDispatcherInitialize(); + UAVObjInitialize(); + + HwNazeInitialize(); + ModuleSettingsInitialize(); + +#if defined(PIOS_INCLUDE_RTC) + /* Initialize the real-time clock and its associated tick */ + PIOS_RTC_Init(&pios_rtc_main_cfg); +#endif + +#ifndef ERASE_FLASH + /* Initialize watchdog as early as possible to catch faults during init + * but do it only if there is no debugger connected + */ + if ((CoreDebug->DHCSR & CoreDebug_DHCSR_C_DEBUGEN_Msk) == 0) { + PIOS_WDG_Init(); + } +#endif + + /* Initialize the alarms library */ + AlarmsInitialize(); + + /* Initialize the task monitor library */ + TaskMonitorInitialize(); + + /* Set up pulse timers */ + //inputs + + //outputs + PIOS_TIM_InitClock(&tim_1_cfg); + PIOS_TIM_InitClock(&tim_2_cfg); + PIOS_TIM_InitClock(&tim_3_cfg); + PIOS_TIM_InitClock(&tim_4_cfg); + + /* IAP System Setup */ + PIOS_IAP_Init(); + uint16_t boot_count = PIOS_IAP_ReadBootCount(); + if (boot_count < 3) { + PIOS_IAP_WriteBootCount(++boot_count); + AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); + } else { + /* Too many failed boot attempts, force hw config to defaults */ + HwNazeSetDefaults(HwNazeHandle(), 0); + ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); + AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); + } + + + /* UART1 Port */ +#if defined(PIOS_INCLUDE_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) + PIOS_HAL_ConfigureCom(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_serial_id); +#endif /* PIOS_INCLUDE_TELEMETRY */ + + /* Configure the rcvr port */ + uint8_t hw_rcvrport; + HwNazeRcvrPortGet(&hw_rcvrport); + + switch (hw_rcvrport) { + case HWNAZE_RCVRPORT_DISABLED: + break; + case HWNAZE_RCVRPORT_PWM: +#if defined(PIOS_INCLUDE_PWM) + { + uintptr_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); + + uintptr_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + case HWNAZE_RCVRPORT_PPMSERIAL: + { + uint8_t hw_rcvrserial; + HwNazeRcvrSerialGet(&hw_rcvrserial); + HwNazeDSMxModeOptions hw_DSMxMode; + HwNazeDSMxModeGet(&hw_DSMxMode); + PIOS_HAL_ConfigurePort(hw_rcvrserial, + &pios_usart_rcvrserial_cfg, + &pios_usart_com_driver, + NULL, NULL, NULL, + PIOS_LED_ALARM, + &pios_usart_dsm_hsum_rcvrserial_cfg, + &pios_dsm_rcvrserial_cfg, + hw_DSMxMode, + NULL, NULL, false); + } + + // Fall through to set up PPM. + + case HWNAZE_RCVRPORT_PPM: + case HWNAZE_RCVRPORT_PPMOUTPUTS: +#if defined(PIOS_INCLUDE_PPM) + { + uintptr_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uintptr_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PPM */ + break; + case HWNAZE_RCVRPORT_PPMPWM: + /* This is a combination of PPM and PWM inputs */ +#if defined(PIOS_INCLUDE_PPM) + { + uintptr_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + uintptr_t pios_ppm_rcvr_id; + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PPM */ +#if defined(PIOS_INCLUDE_PWM) + { + uintptr_t pios_pwm_id; + PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_with_ppm_cfg); + + uintptr_t pios_pwm_rcvr_id; + if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; + } +#endif /* PIOS_INCLUDE_PWM */ + break; + } + +#if defined(PIOS_INCLUDE_GCSRCVR) + GCSReceiverInitialize(); + uintptr_t pios_gcsrcvr_id; + PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); + uintptr_t pios_gcsrcvr_rcvr_id; + if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { + PIOS_Assert(0); + } + pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; +#endif /* PIOS_INCLUDE_GCSRCVR */ + + /* Remap AFIO pin for PB4 (Servo 5 Out)*/ + GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); + +#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS +#ifdef PIOS_INCLUDE_SERVO + switch (hw_rcvrport) { + case HWNAZE_RCVRPORT_DISABLED: + case HWNAZE_RCVRPORT_PWM: + case HWNAZE_RCVRPORT_PPM: + case HWNAZE_RCVRPORT_PPMPWM: + case HWNAZE_RCVRPORT_PPMSERIAL: + PIOS_Servo_Init(&pios_servo_cfg); + break; + case HWNAZE_RCVRPORT_PPMOUTPUTS: + case HWNAZE_RCVRPORT_OUTPUTS: + PIOS_Servo_Init(&pios_servo_rcvr_cfg); + break; + } +#endif +#else + PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); +#endif + +#if defined(PIOS_INCLUDE_ADC) +#error "Not yet implemented" +#endif /* PIOS_INCLUDE_ADC */ + PIOS_WDG_Clear(); + PIOS_DELAY_WaitmS(200); + PIOS_WDG_Clear(); + + PIOS_SENSORS_Init(); + + GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE); + +#if defined(PIOS_INCLUDE_MPU6050) + if(board_v5) { + // rev5 hardware use PC13 instead of PB13 for MPU_INT + pios_mpu6050_cfg.exti_cfg = &pios_exti_mpu6050_cfg_v5; + } + + if (PIOS_MPU6050_Init(pios_i2c_internal_id, PIOS_MPU6050_I2C_ADD_A0_LOW, &pios_mpu6050_cfg) != 0) + panic(2); + if (PIOS_MPU6050_Test() != 0) + panic(2); + + uint8_t hw_gyro_range; + HwNazeGyroRangeGet(&hw_gyro_range); + switch(hw_gyro_range) { + case HWNAZE_GYRORANGE_250: + PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); + break; + case HWNAZE_GYRORANGE_500: + PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); + break; + case HWNAZE_GYRORANGE_1000: + PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); + break; + case HWNAZE_GYRORANGE_2000: + PIOS_MPU6050_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); + break; + } + + uint8_t hw_accel_range; + HwNazeAccelRangeGet(&hw_accel_range); + switch(hw_accel_range) { + case HWNAZE_ACCELRANGE_2G: + PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); + break; + case HWNAZE_ACCELRANGE_4G: + PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); + break; + case HWNAZE_ACCELRANGE_8G: + PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); + break; + case HWNAZE_ACCELRANGE_16G: + PIOS_MPU6050_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); + break; + } + +#endif /* PIOS_INCLUDE_MPU6050 */ + + //I2C is slow, sensor init as well, reset watchdog to prevent reset here + PIOS_WDG_Clear(); + +#if defined(PIOS_INCLUDE_MS5611) + if (PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_internal_id) != 0) + panic(4); + if (PIOS_MS5611_Test() != 0) + panic(4); +#endif + +#if defined(PIOS_INCLUDE_HMC5883) + //TODO: if(board_v5) { /* use PC14 instead of PB12 for MAG_DRDY (exti) */ } + if (PIOS_HMC5883_Init(pios_i2c_internal_id, &pios_hmc5883_cfg) != 0) + panic(6); + if (PIOS_HMC5883_Test() != 0) + panic(6); +#endif + +#if defined(PIOS_INCLUDE_GPIO) + PIOS_GPIO_Init(); +#endif + + /* Make sure we have at least one telemetry link configured or else fail initialization */ + PIOS_Assert(pios_com_telem_serial_id); +} + +/** + * @} + */ diff --git a/flight/targets/naze32/fw/pios_config.h b/flight/targets/naze32/fw/pios_config.h new file mode 100644 index 00000000000..d2980d75298 --- /dev/null +++ b/flight/targets/naze32/fw/pios_config.h @@ -0,0 +1,121 @@ +/** + ****************************************************************************** + * @addtogroup TauLabsTargets Tau Labs Targets + * @{ + * @addtogroup Naze board family support files + * @{ + * + * @file pios_config.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 + * @brief Board specific options that modify PiOS capabilities + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +/* Enable/Disable PiOS Modules */ +//#define PIOS_INCLUDE_ADC +#define PIOS_INCLUDE_DELAY +#define PIOS_INCLUDE_I2C +//#define PIOS_INCLUDE_I2C_ESC +#define PIOS_INCLUDE_IRQ +#define PIOS_INCLUDE_LED +#define PIOS_INCLUDE_IAP +#define PIOS_INCLUDE_TIM +#define PIOS_INCLUDE_HPWM + +#define PIOS_INCLUDE_RCVR + +/* Supported receiver interfaces */ +#define PIOS_INCLUDE_DSM +#define PIOS_INCLUDE_HSUM +//#define PIOS_INCLUDE_SBUS +#define PIOS_INCLUDE_PPM +#define PIOS_INCLUDE_PWM +#define PIOS_INCLUDE_GCSRCVR + +/* Supported USART-based PIOS modules */ +#define PIOS_INCLUDE_TELEMETRY +#define PIOS_INCLUDE_GPS +#define PIOS_GPS_MINIMAL +#define PIOS_INCLUDE_GPS_NMEA_PARSER /* Include the NMEA protocol parser */ +#define PIOS_INCLUDE_GPS_UBX_PARSER /* Include the UBX protocol parser */ +#define PIOS_INCLUDE_MAVLINK + +#define PIOS_INCLUDE_SERVO +#define PIOS_INCLUDE_HPWM +//#define PIOS_INCLUDE_SPI +#define PIOS_INCLUDE_SYS +#define PIOS_INCLUDE_USART +#define PIOS_INCLUDE_COM +#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_GPIO +#define PIOS_INCLUDE_EXTI +#define PIOS_INCLUDE_RTC +//#define PIOS_INCLUDE_WDG +#define PIOS_INCLUDE_BL_HELPER + +//#define PIOS_INCLUDE_MS5611 +//#define PIOS_INCLUDE_HMC5883 +#define PIOS_INCLUDE_MPU6050 +#define PIOS_MPU6050_ACCEL + +#define PIOS_INCLUDE_LOGFS_SETTINGS + +#define PIOS_INCLUDE_FLASH +#define PIOS_INCLUDE_FLASH_SECTOR_SETTINGS +#define PIOS_INCLUDE_FLASH_INTERNAL + +#define PIOS_INCLUDE_SESSION_MANAGEMENT + + +/* Alarm Thresholds */ +#define HEAP_LIMIT_WARNING 220 +#define HEAP_LIMIT_CRITICAL 40 +#define IRQSTACK_LIMIT_WARNING 100 +#define IRQSTACK_LIMIT_CRITICAL 60 +#define CPULOAD_LIMIT_WARNING 85 +#define CPULOAD_LIMIT_CRITICAL 95 + +/* Task stack sizes */ +#define PIOS_ACTUATOR_STACK_SIZE 800 +#define PIOS_MANUAL_STACK_SIZE 700 +#define PIOS_SYSTEM_STACK_SIZE 660 +#define PIOS_STABILIZATION_STACK_SIZE 624 +#define PIOS_TELEM_STACK_SIZE 500 +#define PIOS_EVENTDISPATCHER_STACK_SIZE 720 +#define PIOS_MAVLINK_STACK_SIZE 496 +#define PIOS_COMUSBBRIDGE_STACK_SIZE 480 +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 1995998 + +// This can't be too high to stop eventdispatcher thread overflowing +#define PIOS_EVENTDISAPTCHER_QUEUE 10 + +/* PIOS Initcall infrastructure */ +#define PIOS_INCLUDE_INITCALL + +#define SMALLF1 + +#endif /* PIOS_CONFIG_H */ +/** + * @} + * @} + */ diff --git a/flight/targets/naze32/hw/OpenNaze.dch b/flight/targets/naze32/hw/OpenNaze.dch new file mode 100644 index 00000000000..d9caf7d0ee0 Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze.dch differ diff --git a/flight/targets/naze32/hw/OpenNaze.dip b/flight/targets/naze32/hw/OpenNaze.dip new file mode 100644 index 00000000000..4f4111650ae Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze.dip differ diff --git a/flight/targets/naze32/hw/OpenNaze.zip b/flight/targets/naze32/hw/OpenNaze.zip new file mode 100644 index 00000000000..ebc196a4a57 Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze.zip differ diff --git a/flight/targets/naze32/hw/OpenNaze_rev4-master.zip b/flight/targets/naze32/hw/OpenNaze_rev4-master.zip new file mode 100644 index 00000000000..5e99ae55c55 Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze_rev4-master.zip differ diff --git a/flight/targets/naze32/hw/OpenNaze_rev4.pdf b/flight/targets/naze32/hw/OpenNaze_rev4.pdf new file mode 100644 index 00000000000..debcfec020b Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze_rev4.pdf differ diff --git a/flight/targets/naze32/hw/OpenNaze_rev4.zip b/flight/targets/naze32/hw/OpenNaze_rev4.zip new file mode 100644 index 00000000000..fad5b1b4277 Binary files /dev/null and b/flight/targets/naze32/hw/OpenNaze_rev4.zip differ diff --git a/flight/targets/naze32/hw/README.md b/flight/targets/naze32/hw/README.md new file mode 100644 index 00000000000..22a03097e52 --- /dev/null +++ b/flight/targets/naze32/hw/README.md @@ -0,0 +1,8 @@ +OpenNaze_rev4 +============= +Creative Commons License
This work is licensed under a Creative Commons Attribution-NonCommercial-ShareAlike 4.0 International License. + +naze32_rev4 +=========== +This file was retrieved from https://code.google.com/p/afrodevices/downloads/detail?name=naze32_rev4.pdf , where it was released under CC-BY-NC-SA 3.0. + diff --git a/flight/targets/naze32/hw/naze32_rev4.pdf b/flight/targets/naze32/hw/naze32_rev4.pdf new file mode 100644 index 00000000000..f11a59a5256 Binary files /dev/null and b/flight/targets/naze32/hw/naze32_rev4.pdf differ diff --git a/flight/targets/naze32/link_STM32103CB_Naze32_memory.ld b/flight/targets/naze32/link_STM32103CB_Naze32_memory.ld new file mode 100644 index 00000000000..2d0c81f40aa --- /dev/null +++ b/flight/targets/naze32/link_STM32103CB_Naze32_memory.ld @@ -0,0 +1,9 @@ +MEMORY +{ + FLASH : ORIGIN = 0x08000000, LENGTH = 128K - 100 - 12K + /* FW_INFO should be filled when the tlfw is generated */ + FW_INFO : ORIGIN = 0x0801D000 - 100, LENGTH = 100 + /* Putting anything in EEPROM will overwrite saved settings */ + EEPROM : ORIGIN = 0x0801D000, LENGTH = 12K + SRAM : ORIGIN = 0x20000000, LENGTH = 20K +} diff --git a/flight/targets/naze32/link_STM32103CB_Naze32_sections.ld b/flight/targets/naze32/link_STM32103CB_Naze32_sections.ld new file mode 100644 index 00000000000..a3f737ef2bc --- /dev/null +++ b/flight/targets/naze32/link_STM32103CB_Naze32_sections.ld @@ -0,0 +1,166 @@ +/* This is the size of the stack for all FreeRTOS IRQs */ +_irq_stack_size = 0x240; +/* This is the size of the stack for early init: life span is until scheduler starts */ +_init_stack_size = 0x200; +/* This is the size of the pre-rtos heap */ +_init_heap_size = 53 * 256; + +/* Stub out these functions since we don't use them anyway */ +PROVIDE ( vPortSVCHandler = 0 ) ; +PROVIDE ( xPortPendSVHandler = 0 ) ; +PROVIDE ( xPortSysTickHandler = 0 ) ; + +/* Section Definitions */ +SECTIONS +{ + .text : + { + PROVIDE (pios_isr_vector_table_base = .); + KEEP(*(.isr_vector .isr_vector.*)) + *(.text .text.* .gnu.linkonce.t.*) + *(.glue_7t) *(.glue_7) + *(.rodata .rodata* .gnu.linkonce.r.*) + } > FLASH + + /* module sections */ + .initcallmodule.init : + { + . = ALIGN(4); + __module_initcall_start = .; + KEEP(*(.initcallmodule.init)) + . = ALIGN(4); + __module_initcall_end = .; + } >FLASH + + /* + * _exti section + */ + _exti : + { + . = ALIGN(4); + __start__exti = .; + KEEP(*(_exti)) + . = ALIGN(4); + __stop__exti = .; + } >FLASH + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } > FLASH + + .ARM.exidx : + { + *(.ARM.exidx* .gnu.linkonce.armexidx.*) + } > FLASH + + .boardinfo : + { + PROVIDE(pios_board_info_blob = .); + . = ALIGN(4); + KEEP(*(.boardinfo)) + . = ALIGN(4); + } > FLASH + + /* + * Markers for the end of the 'text' section and the in-flash start of + * non-constant data + */ + . = ALIGN(4); + _etext = .; + _sidata = .; + + /* + * This stack is used both as the initial sp during early init as well as ultimately + * being used as the STM32's MSP (Main Stack Pointer) which is the same stack that + * is used for _all_ interrupt handlers. The end of this stack should be placed + * against the lowest address in RAM so that a stack overrun results in a hard fault + * at the first access beyond the end of the stack. + */ + .irq_stack : + { + . = ALIGN(4); + _irq_stack_end = . ; + . = . + _irq_stack_size ; + . = ALIGN(4); + _irq_stack_top = . - 4 ; + . = ALIGN(4); + } > SRAM + + .data : AT (_etext) + { + _sdata = .; + *(.data .data.*) + . = ALIGN(4); + _edata = . ; + } > SRAM + + /* + * Uninitialised data (BSS + commons). + */ + .bss (NOLOAD) : + { + _sbss = . ; + *(.bss .bss.*) + *(COMMON) + _ebss = . ; + PROVIDE ( _end = _ebss ) ; + } > SRAM + + /* keep the heap section at the end of the SRAM + * this will allow to claim the remaining bytes not used + * at run time! (done by the reset vector). + */ + + .heap (NOLOAD) : + { + . = ALIGN(4); + _sheap = . ; + *(.heap) + . = ALIGN(4); + . = . + _init_heap_size ; + . = ALIGN(4); + _eheap = . ; + _init_stack_end = . ; + . = . + _init_stack_size ; + . = ALIGN(4); + _eheap_post_rtos = . ; + _init_stack_top = . - 4 ; + } > SRAM + + _eram = ORIGIN(SRAM) + LENGTH(SRAM) ; + + /* Stabs debugging sections. */ + .stab 0 : { *(.stab) } + .stabstr 0 : { *(.stabstr) } + .stab.excl 0 : { *(.stab.excl) } + .stab.exclstr 0 : { *(.stab.exclstr) } + .stab.index 0 : { *(.stab.index) } + .stab.indexstr 0 : { *(.stab.indexstr) } + .comment 0 : { *(.comment) } + /* DWARF debug sections. + Symbols in the DWARF debugging sections are relative to the beginning + of the section so we begin them at 0. */ + /* DWARF 1 */ + .debug 0 : { *(.debug) } + .line 0 : { *(.line) } + /* GNU DWARF 1 extensions */ + .debug_srcinfo 0 : { *(.debug_srcinfo) } + .debug_sfnames 0 : { *(.debug_sfnames) } + /* DWARF 1.1 and DWARF 2 */ + .debug_aranges 0 : { *(.debug_aranges) } + .debug_pubnames 0 : { *(.debug_pubnames) } + /* DWARF 2 */ + .debug_info 0 : { *(.debug_info .gnu.linkonce.wi.*) } + .debug_abbrev 0 : { *(.debug_abbrev) } + .debug_line 0 : { *(.debug_line) } + .debug_frame 0 : { *(.debug_frame) } + .debug_str 0 : { *(.debug_str) } + .debug_loc 0 : { *(.debug_loc) } + .debug_macinfo 0 : { *(.debug_macinfo) } + /* SGI/MIPS DWARF 2 extensions */ + .debug_weaknames 0 : { *(.debug_weaknames) } + .debug_funcnames 0 : { *(.debug_funcnames) } + .debug_typenames 0 : { *(.debug_typenames) } + .debug_varnames 0 : { *(.debug_varnames) } +} diff --git a/flight/targets/revolution/target-defs.mk b/flight/targets/naze32/target-defs.mk similarity index 76% rename from flight/targets/revolution/target-defs.mk rename to flight/targets/naze32/target-defs.mk index b159b3187ce..7bf75223928 100644 --- a/flight/targets/revolution/target-defs.mk +++ b/flight/targets/naze32/target-defs.mk @@ -1,10 +1,10 @@ # Add this board to the list of buildable boards -ALL_BOARDS += revolution +ALL_BOARDS += naze32 # Set the cpu architecture here that matches your STM32 # Should be one of: f1,f3,f4 -revolution_cpuarch := f4 +naze32_cpuarch := f1 # Short name of this board (used to display board name in parallel builds) # Should be exactly 4 characters long. -revolution_short := 'revo' +naze32_short := 'naze' diff --git a/flight/targets/pipxtreme/board-info/board-info.mk b/flight/targets/pipxtreme/board-info/board-info.mk index 0739a43cef6..fc587933143 100644 --- a/flight/targets/pipxtreme/board-info/board-info.mk +++ b/flight/targets/pipxtreme/board-info/board-info.mk @@ -1,5 +1,5 @@ BOARD_TYPE := 0x03 -BOARD_REVISION := 0x01 +BOARD_REVISION := 0x02 # Previous version was 0x080, 0x081 introduces forced boot from bkp registers BOOTLOADER_VERSION := 0x81 HW_TYPE := 0x01 diff --git a/flight/targets/pipxtreme/board-info/board_hw_defs.c b/flight/targets/pipxtreme/board-info/board_hw_defs.c index 7980c95fd29..36a5a707553 100644 --- a/flight/targets/pipxtreme/board-info/board_hw_defs.c +++ b/flight/targets/pipxtreme/board-info/board_hw_defs.c @@ -276,7 +276,7 @@ static const struct pios_exti_cfg pios_exti_rfm22b_cfg __exti_config = { #include -struct pios_rfm22b_cfg pios_rfm22b_pipx_cfg = { +struct pios_rfm22b_cfg pios_rfm22b_taulink_cfg = { .spi_cfg = &pios_spi_rfm22b_cfg, .exti_cfg = &pios_exti_rfm22b_cfg, .RFXtalCap = 0x7f, @@ -284,10 +284,50 @@ struct pios_rfm22b_cfg pios_rfm22b_pipx_cfg = { .gpio_direction = GPIO0_TX_GPIO1_RX, }; +static const struct pios_exti_cfg pios_exti_rfm22b_cfg_module __exti_config = { + .vector = PIOS_RFM22_EXT_Int, + .line = EXTI_Line1, + .pin = { + .gpio = GPIOA, + .init = { + .GPIO_Pin = GPIO_Pin_1, + .GPIO_Mode = GPIO_Mode_IN_FLOATING, + }, + }, + .irq = { + .init = { + .NVIC_IRQChannel = EXTI1_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .exti = { + .init = { + .EXTI_Line = EXTI_Line1, + .EXTI_Mode = EXTI_Mode_Interrupt, + .EXTI_Trigger = EXTI_Trigger_Falling, + .EXTI_LineCmd = ENABLE, + }, + }, +}; + +struct pios_rfm22b_cfg pios_rfm22b_taulinkmodule_cfg = { + .spi_cfg = &pios_spi_rfm22b_cfg, + .exti_cfg = &pios_exti_rfm22b_cfg_module, + .RFXtalCap = 0x7f, + .slave_num = 0, + .gpio_direction = GPIO0_TX_GPIO1_RX, +}; + //! Compatibility layer for various hardware revisions const struct pios_rfm22b_cfg * PIOS_BOARD_HW_DEFS_GetRfm22Cfg (uint32_t board_revision) { - return &pios_rfm22b_pipx_cfg; + if (board_revision == TAULINK_VERSION_STICK) + return &pios_rfm22b_taulink_cfg; + if (board_revision == TAULINK_VERSION_MODULE) + return &pios_rfm22b_taulinkmodule_cfg; + return NULL; } #endif /* PIOS_INCLUDE_RFM22B */ @@ -478,6 +518,50 @@ static const struct pios_usart_cfg pios_usart_serial_cfg = }, }; +static const struct pios_usart_cfg pios_usart_bluetooth_cfg = +{ + .regs = USART2, + .init = + { + .USART_BaudRate = 9600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Rx | USART_Mode_Tx, + }, + .irq = + { + .init = + { + .NVIC_IRQChannel = USART2_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .rx = + { + .gpio = GPIOA, + .init = + { + .GPIO_Pin = GPIO_Pin_3, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_IPU, + }, + }, + .tx = + { + .gpio = GPIOA, + .init = + { + .GPIO_Pin = GPIO_Pin_2, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = { .regs = USART3, .init = { @@ -514,6 +598,34 @@ static const struct pios_usart_cfg pios_usart_telem_flexi_cfg = { }, }; +static const struct pios_usart_cfg pios_usart_sport_cfg = { + .regs = USART3, + .init = { + .USART_BaudRate = 57600, + .USART_WordLength = USART_WordLength_8b, + .USART_Parity = USART_Parity_No, + .USART_StopBits = USART_StopBits_1, + .USART_HardwareFlowControl = USART_HardwareFlowControl_None, + .USART_Mode = USART_Mode_Tx, + }, + .irq = { + .init = { + .NVIC_IRQChannel = USART3_IRQn, + .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_MID, + .NVIC_IRQChannelSubPriority = 0, + .NVIC_IRQChannelCmd = ENABLE, + }, + }, + .tx = { + .gpio = GPIOB, + .init = { + .GPIO_Pin = GPIO_Pin_10, + .GPIO_Speed = GPIO_Speed_2MHz, + .GPIO_Mode = GPIO_Mode_AF_PP, + }, + }, +}; + #endif /* PIOS_INCLUDE_USART */ #if defined(PIOS_INCLUDE_COM) diff --git a/flight/targets/pipxtreme/board-info/cmsis_system.c b/flight/targets/pipxtreme/board-info/cmsis_system.c index 41805ec5674..dee096b07c4 100644 --- a/flight/targets/pipxtreme/board-info/cmsis_system.c +++ b/flight/targets/pipxtreme/board-info/cmsis_system.c @@ -175,6 +175,10 @@ __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9} static void SetSysClock(void); +// this is required for the system_rcc code because +// of the clock rate switching in naze32 +uint32_t hse_value = 8000000; + #ifdef SYSCLK_FREQ_HSE static void SetSysClockToHSE(void); #elif defined SYSCLK_FREQ_24MHz diff --git a/flight/targets/pipxtreme/board-info/pios_board.h b/flight/targets/pipxtreme/board-info/pios_board.h index 2fb49a78abf..3e9dc175727 100755 --- a/flight/targets/pipxtreme/board-info/pios_board.h +++ b/flight/targets/pipxtreme/board-info/pios_board.h @@ -31,6 +31,9 @@ #ifndef STM32103CB_PIPXTREME_H_ #define STM32103CB_PIPXTREME_H_ +#define TAULINK_VERSION_STICK 0x01 +#define TAULINK_VERSION_MODULE 0x02 + #define ADD_ONE_ADC //------------------------ @@ -165,24 +168,24 @@ extern uint32_t pios_i2c_flexi_adapter_id; // // See also pios_board.c //------------------------- -extern uintptr_t pios_com_telem_usb_id; -extern uintptr_t pios_com_telem_vcp_id; -extern uintptr_t pios_com_telem_uart_telem_id; -extern uintptr_t pios_com_telem_uart_main_id; -extern uintptr_t pios_com_telemetry_id; -extern uintptr_t pios_com_rfm22b_id; -extern uintptr_t pios_com_radio_id; +extern uintptr_t pios_com_telem_usb_id; +extern uintptr_t pios_com_vcp_id; +extern uintptr_t pios_com_radio_id; +extern uintptr_t pios_com_telem_serial_id; +extern uintptr_t pios_com_bridge_id; +extern uintptr_t pios_com_rf_id; +extern uintptr_t pios_com_telem_uart_telem_id; extern uintptr_t pios_ppm_rcvr_id; extern uintptr_t pios_com_debug_id; +extern uintptr_t pios_com_frsky_sport_id; #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_VCP (pios_com_telem_vcp_id) -#define PIOS_COM_TELEM_UART_FLEXI (pios_com_telem_uart_flexi_id) -#define PIOS_COM_TELEM_UART_TELEM (pios_com_telem_uart_main_id) -#define PIOS_COM_TELEMETRY (pios_com_telemetry_id) -#define PIOS_COM_RFM22B (pios_com_rfm22b_id) -#define PIOS_COM_RADIO (pios_com_radio_id) +#define PIOS_COM_VCP (pios_com_vcp_id) +#define PIOS_COM_TELEMETRY (pios_com_telem_serial_id) +#define PIOS_COM_BRIDGE (pios_com_bridge_id) +#define PIOS_COM_RFM22B (pios_com_rf_id) #define PIOS_PPM_RECEIVER (pios_ppm_rcvr_id) #define PIOS_COM_DEBUG (pios_com_debug_id) +#define PIOS_COM_FRSKY_SPORT (pios_com_frsky_sport_id) #define DEBUG_LEVEL 0 #define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && PIOS_COM_DEBUG > 0) { PIOS_COM_SendFormattedStringNonBlocking(PIOS_COM_DEBUG, __VA_ARGS__); }} diff --git a/flight/targets/pipxtreme/fw/Makefile b/flight/targets/pipxtreme/fw/Makefile index 22fbc5ba1b2..c5a3b84b726 100644 --- a/flight/targets/pipxtreme/fw/Makefile +++ b/flight/targets/pipxtreme/fw/Makefile @@ -53,8 +53,9 @@ USE_GPS ?= NO USE_I2C ?= YES # List of modules to include -OPTMODULES = -MODULES = RadioComBridge +MODULES += ComUsbBridge +MODULES += RadioComBridge +MODULES += UAVOTaranis # Paths OPUAVTALKINC = $(OPUAVTALK)/inc @@ -66,6 +67,8 @@ PIOSINC = $(PIOS)/inc PIOSSTM32F10X = $(PIOS)/STM32F10x PIOSCOMMON = $(PIOS)/Common PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries +MATHLIB = $(FLIGHTLIB)/math +MATHLIBINC = $(FLIGHTLIB)/math APPLIBDIR = $(PIOSSTM32F10X)/Libraries STMLIBDIR = $(APPLIBDIR) STMSPDDIR = $(STMLIBDIR)/STM32F10x_StdPeriph_Driver @@ -87,7 +90,7 @@ RTOSPORTDIR = $(APPLIBDIR)/FreeRTOS/Source ifndef TESTAPP ## MODULES -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} +SRC += ${foreach MOD, ${MODULES} ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/PipXtreme/pipxtrememod.c SRC += main.c @@ -107,8 +110,15 @@ SRC += $(OPUAVSYNTHDIR)/gcsreceiver.c SRC += $(OPUAVSYNTHDIR)/hwtaulink.c SRC += $(OPUAVSYNTHDIR)/rfm22bstatus.c SRC += $(OPUAVSYNTHDIR)/objectpersistence.c +SRC += $(OPUAVSYNTHDIR)/modulesettings.c SRC += $(OPUAVSYNTHDIR)/rfm22breceiver.c SRC += $(OPUAVSYNTHDIR)/radiocombridgestats.c + +SRC += $(OPUAVSYNTHDIR)/baroaltitude.c +SRC += $(OPUAVSYNTHDIR)/flightbatterystate.c +SRC += $(OPUAVSYNTHDIR)/flightstatus.c +SRC += $(OPUAVSYNTHDIR)/positionactual.c +SRC += $(OPUAVSYNTHDIR)/velocityactual.c endif ## PIOS Hardware (STM32F10x) @@ -156,6 +166,7 @@ SRC += $(PIOSCOMMON)/pios_semaphore.c SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c +SRC += $(PIOSCOMMON)/pios_hal.c ## Libraries for flight calculations @@ -166,6 +177,8 @@ SRC += $(FLIGHTLIB)/aes.c SRC += $(FLIGHTLIB)/rscode/rs.c SRC += $(FLIGHTLIB)/rscode/berlekamp.c SRC += $(FLIGHTLIB)/rscode/galois.c +SRC += $(FLIGHTLIB)/frsky_packing.c +SRC += $(MATHLIB)/misc_math.c ## CMSIS for STM32 include $(PIOSCOMMONLIB)/CMSIS3/library.mk @@ -242,6 +255,7 @@ EXTRAINCDIRS += $(OPUAVOBJINC) EXTRAINCDIRS += $(OPUAVSYNTHDIR) EXTRAINCDIRS += $(PIOS) EXTRAINCDIRS += $(PIOSINC) +EXTRAINCDIRS += $(MATHLIBINC) EXTRAINCDIRS += $(FLIGHTLIBINC) EXTRAINCDIRS += $(RSCODEINC) EXTRAINCDIRS += $(PIOSSTM32F10X) @@ -323,6 +337,9 @@ endif CDEFS += -DEE_BANK_BASE=$(EE_BANK_BASE) CDEFS += -DEE_BANK_SIZE=$(EE_BANK_SIZE) +CDEFS += -DPIOS_COM_TELEM_USB_RX_BUF_LEN=256 +CDEFS += -DPIOS_COM_TELEM_USB_TX_BUF_LEN=256 + # Declare all non-optional modules as built-in to force inclusion CDEFS += $(foreach MOD, $(notdir $(MODULES)), -DMODULE_$(MOD)_BUILTIN) @@ -429,5 +446,7 @@ LDFLAGS += -Wl,--fatal-warnings LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_memory.ld LDFLAGS += -T$(LINKERSCRIPTPATH)/link_$(BOARD)_sections.ld +NO_AUTO_UAVO=YES + include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/pipxtreme/fw/pios_board.c b/flight/targets/pipxtreme/fw/pios_board.c index 7a33038a93f..9b7a92207ec 100644 --- a/flight/targets/pipxtreme/fw/pios_board.c +++ b/flight/targets/pipxtreme/fw/pios_board.c @@ -7,7 +7,7 @@ * * @file pios_board.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief The board specific initialization routines * @see The GNU Public License (GPL) Version 3 * @@ -31,53 +31,24 @@ #include #include #include +#include #include +#include #include -#define PIOS_COM_TELEM_RX_BUF_LEN 256 -#define PIOS_COM_TELEM_TX_BUF_LEN 256 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 256 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 256 - -#define PIOS_COM_TELEM_VCP_RX_BUF_LEN 256 -#define PIOS_COM_TELEM_VCP_TX_BUF_LEN 256 - -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 - -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 -uintptr_t pios_com_debug_id; -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -uintptr_t pios_com_telem_usb_id; -uintptr_t pios_com_telem_vcp_id; -uintptr_t pios_com_vcp_id; -uintptr_t pios_com_telem_uart_main_id; -uintptr_t pios_com_telem_uart_flexi_id; -uintptr_t pios_com_telem_uart_telem_id; -uintptr_t pios_com_telemetry_id; +uintptr_t pios_com_telem_uart_bluetooth_id; #if defined(PIOS_INCLUDE_PPM) uintptr_t pios_ppm_rcvr_id; #endif -#if defined(PIOS_INCLUDE_RFM22B) -uint32_t pios_rfm22b_id; -uintptr_t pios_com_rfm22b_id; -uintptr_t pios_com_radio_id; -#endif - -uint8_t *pios_uart_rx_buffer; -uint8_t *pios_uart_tx_buffer; uintptr_t pios_uavo_settings_fs_id; +#define PIOS_COM_TELEM_RX_BUF_LEN 256 +#define PIOS_COM_TELEM_TX_BUF_LEN 256 +#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 256 +#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 256 +#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 + /** * PIOS_Board_Init() * initializes all the core subsystems on this specific hardware @@ -126,9 +97,9 @@ void PIOS_Board_Init(void) { PIOS_RTC_Init(&pios_rtc_main_cfg); #endif /* PIOS_INCLUDE_RTC */ + HwTauLinkInitialize(); #if defined(PIOS_INCLUDE_RFM22B) - HwTauLinkInitialize(); - RFM22BStatusInitialize(); + RFM22BStatusInitialize(); #endif /* PIOS_INCLUDE_RFM22B */ #if defined(PIOS_INCLUDE_LED) @@ -160,95 +131,177 @@ void PIOS_Board_Init(void) { } #endif + // Configure the main port + HwTauLinkData hwTauLink; + HwTauLinkGet(&hwTauLink); + /*Initialize the USB device */ uintptr_t pios_usb_id; PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); - /* Configure the USB HID port */ - { - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } + PIOS_HAL_ConfigureHID(HWSHARED_USB_HIDPORT_USBTELEMETRY, pios_usb_id, &pios_usb_hid_cfg); /* Configure the USB virtual com port (VCP) */ #if defined(PIOS_INCLUDE_USB_CDC) if (usb_cdc_present) { - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_VCP_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_VCP_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_VCP_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_VCP_TX_BUF_LEN)) { - PIOS_Assert(0); - } + PIOS_HAL_ConfigureCDC(hwTauLink.VCPPort, pios_usb_id, &pios_usb_cdc_cfg); } #endif - /* Allocate the uart buffers. */ - pios_uart_rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_RX_BUF_LEN); - pios_uart_tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_TX_BUF_LEN); - - // Configure the main port - HwTauLinkData hwTauLink; - HwTauLinkGet(&hwTauLink); - - bool is_oneway = hwTauLink.Radio == HWTAULINK_RADIO_PPM; - bool ppm_only = hwTauLink.Radio == HWTAULINK_RADIO_PPM; - bool ppm_mode = hwTauLink.Radio == HWTAULINK_RADIO_TELEMPPM || hwTauLink.Radio == HWTAULINK_RADIO_PPM; + PIOS_HAL_ConfigurePort(hwTauLink.MainPort, + &pios_usart_serial_cfg, &pios_usart_com_driver, + /* no I2C, DSM, HSUM, SBUS, etc. */ + NULL, NULL, NULL, PIOS_LED_ALARM, + NULL, NULL, 0, NULL, NULL, false); + + // Update the com baud rate. + uint32_t comBaud = 9600; + switch (hwTauLink.ComSpeed) { + case HWTAULINK_COMSPEED_4800: + comBaud = 4800; + break; + case HWTAULINK_COMSPEED_9600: + comBaud = 9600; + break; + case HWTAULINK_COMSPEED_19200: + comBaud = 19200; + break; + case HWTAULINK_COMSPEED_38400: + comBaud = 38400; + break; + case HWTAULINK_COMSPEED_57600: + comBaud = 57600; + break; + case HWTAULINK_COMSPEED_115200: + comBaud = 115200; + break; + } - // Configure the main serial port function - switch (hwTauLink.MainPort) { - case HWTAULINK_MAINPORT_TELEMETRY: - case HWTAULINK_MAINPORT_COMBRIDGE: - { - /* Configure the main port for uart serial */ -#ifndef PIOS_RFM22B_DEBUG_ON_TELEM - { - uintptr_t pios_usart1_id; - if (PIOS_USART_Init(&pios_usart1_id, &pios_usart_serial_cfg)) { - PIOS_Assert(0); + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + PIOS_HAL_ConfigureRFM22B(hwTauLink.Radio, bdinfo->board_type, + bdinfo->board_rev, hwTauLink.MaxRfPower, + hwTauLink.MaxRfSpeed, NULL, rfm22b_cfg, + hwTauLink.MinChannel, hwTauLink.MaxChannel, + hwTauLink.CoordID, 0); + + if (bdinfo->board_rev == TAULINK_VERSION_MODULE) { + // Configure the main serial port function + switch (hwTauLink.BTPort) { + case HWTAULINK_BTPORT_TELEMETRY: + { + // Note: if the main port is also on telemetry the bluetooth + // port will take precedence + uintptr_t pios_usart2_id; + if (PIOS_USART_Init(&pios_usart2_id, &pios_usart_bluetooth_cfg)) { + PIOS_Assert(0); + } + uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(128); + uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(256); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_uart_bluetooth_id, &pios_usart_com_driver, pios_usart2_id, + rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) { + PIOS_Assert(0); + } + + PIOS_COM_ChangeBaud(pios_com_telem_uart_bluetooth_id, 9600); + + // Note this doesn't actually send until RTOS is running + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+NAMETauLink"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+PIN:000000"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+MODE1"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+SHOW1"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+RESET"); + PIOS_COM_SendString(pios_com_telem_uart_bluetooth_id,"AT+BAUD4"); // 115200 + PIOS_COM_ChangeBaud(pios_com_telem_uart_bluetooth_id, 115200); + pios_com_telem_serial_id = pios_com_telem_uart_bluetooth_id; } - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_uart_telem_id, &pios_usart_com_driver, pios_usart1_id, - rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) { - PIOS_Assert(0); + break; + case HWTAULINK_BTPORT_COMBRIDGE: + { + // Note: if the main port is also on telemetry the bluetooth + // port will take precedence + uintptr_t pios_usart2_id; + if (PIOS_USART_Init(&pios_usart2_id, &pios_usart_bluetooth_cfg)) { + PIOS_Assert(0); + } + uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_RX_BUF_LEN); + uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_TELEM_TX_BUF_LEN); + PIOS_Assert(rx_buffer); + PIOS_Assert(tx_buffer); + if (PIOS_COM_Init(&pios_com_telem_uart_bluetooth_id, &pios_usart_com_driver, pios_usart2_id, + rx_buffer, PIOS_COM_TELEM_RX_BUF_LEN, + tx_buffer, PIOS_COM_TELEM_TX_BUF_LEN)) { + PIOS_Assert(0); + } + + // Since we don't expose the ModuleSettings object from TauLink to the GCS + // we just map the baud rate from HwTauLink into this object + ModuleSettingsInitialize(); + ModuleSettingsData moduleSettings; + ModuleSettingsGet(&moduleSettings); + switch(comBaud) { + case 4800: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_4800; + break; + case 9600: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_9600; + break; + case 19200: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_19200; + break; + case 38400: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_38400; + break; + case 57600: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_57600; + break; + case 115200: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_115200; + break; + default: + moduleSettings.ComUsbBridgeSpeed = MODULESETTINGS_COMUSBBRIDGESPEED_9600; + } + ModuleSettingsSet(&moduleSettings); + + PIOS_COM_ChangeBaud(pios_com_telem_uart_bluetooth_id, comBaud); + pios_com_bridge_id = pios_com_telem_uart_bluetooth_id; + } + break; + case HWTAULINK_MAINPORT_DISABLED: + break; } - - pios_com_telemetry_id = pios_com_telem_uart_telem_id; } -#endif - break; - } - case HWTAULINK_MAINPORT_DISABLED: - break; - } - // Configure the flexi port switch (hwTauLink.PPMPort) { case HWTAULINK_PPMPORT_PPM: { +#if defined(PIOS_INCLUDE_PPM) + /* PPM input is configured on the coordinator modem and sent in the RFM22BReceiver UAVO. */ + uintptr_t pios_ppm_id; + PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); + + if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { + PIOS_Assert(0); + } + +#endif /* PIOS_INCLUDE_PPM */ + break; + } + case HWTAULINK_PPMPORT_SPORT: +#if defined(PIOS_INCLUDE_TARANIS_SPORT) + PIOS_HAL_ConfigureCom(&pios_usart_sport_cfg, 0, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_TARANIS_SPORT */ + break; + case HWTAULINK_PPMPORT_PPMSPORT: + { +#if defined(PIOS_INCLUDE_TARANIS_SPORT) + PIOS_HAL_ConfigureCom(&pios_usart_sport_cfg, 0, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); +#endif /* PIOS_INCLUDE_TARANIS_SPORT */ #if defined(PIOS_INCLUDE_PPM) /* PPM input is configured on the coordinator modem and sent in the RFM22BReceiver UAVO. */ uintptr_t pios_ppm_id; @@ -266,174 +319,9 @@ void PIOS_Board_Init(void) { break; } - // Configure the USB VCP port - switch (hwTauLink.VCPPort) { - case HWTAULINK_VCPPORT_TELEMETRY: - PIOS_COM_TELEMETRY = pios_com_telem_vcp_id; - break; - case HWTAULINK_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWTAULINK_VCPPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - NULL, 0, - tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -#endif /* PIOS_INCLUDE_COM */ - case HWTAULINK_VCPPORT_DISABLED: - break; - } - - // Initialize out status object. - RFM22BStatusData rfm22bstatus; - RFM22BStatusGet(&rfm22bstatus); - - rfm22bstatus.BoardType = bdinfo->board_type; - rfm22bstatus.BoardRevision = bdinfo->board_rev; - - /* Initalize the RFM22B radio COM device. */ - if (hwTauLink.MaxRfPower != HWTAULINK_MAXRFPOWER_0) { - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_ENABLED; - - // Configure the RFM22B device - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { - PIOS_Assert(0); - } - - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - - // Configure the radio com interface - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rfm22b_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - - // Set the RF data rate on the modem to ~2X the selected buad rate because the modem is half duplex. - enum rfm22b_datarate datarate = RFM22_datarate_64000; - switch (hwTauLink.MaxRfSpeed) { - case HWTAULINK_MAXRFSPEED_9600: - datarate = RFM22_datarate_9600; - break; - case HWTAULINK_MAXRFSPEED_19200: - datarate = RFM22_datarate_19200; - break; - case HWTAULINK_MAXRFSPEED_32000: - datarate = RFM22_datarate_32000; - break; - case HWTAULINK_MAXRFSPEED_64000: - datarate = RFM22_datarate_64000; - break; - case HWTAULINK_MAXRFSPEED_100000: - datarate = RFM22_datarate_100000; - break; - case HWTAULINK_MAXRFSPEED_192000: - datarate = RFM22_datarate_192000; - break; - } - - /* Set the modem Tx poer level */ - switch (hwTauLink.MaxRfPower) { - case HWTAULINK_MAXRFPOWER_125: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - break; - case HWTAULINK_MAXRFPOWER_16: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); - break; - case HWTAULINK_MAXRFPOWER_316: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); - break; - case HWTAULINK_MAXRFPOWER_63: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); - break; - case HWTAULINK_MAXRFPOWER_126: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); - break; - case HWTAULINK_MAXRFPOWER_25: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); - break; - case HWTAULINK_MAXRFPOWER_50: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); - break; - case HWTAULINK_MAXRFPOWER_100: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); - break; - default: - // do nothing - break; - } - - // Set the radio configuration parameters. - PIOS_RFM22B_Config(pios_rfm22b_id, datarate, hwTauLink.MinChannel, hwTauLink.MaxChannel, hwTauLink.CoordID, is_oneway, ppm_mode, ppm_only); - - // Reinitilize the modem to affect te changes. - PIOS_RFM22B_Reinit(pios_rfm22b_id); - } else { - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; - } - - // Update the object - RFM22BStatusSet(&rfm22bstatus); - - // Update the com baud rate. - uint32_t comBaud = 9600; - switch (hwTauLink.ComSpeed) { - case HWTAULINK_COMSPEED_4800: - comBaud = 4800; - break; - case HWTAULINK_COMSPEED_9600: - comBaud = 9600; - break; - case HWTAULINK_COMSPEED_19200: - comBaud = 19200; - break; - case HWTAULINK_COMSPEED_38400: - comBaud = 38400; - break; - case HWTAULINK_COMSPEED_57600: - comBaud = 57600; - break; - case HWTAULINK_COMSPEED_115200: - comBaud = 115200; - break; - } - if (PIOS_COM_TELEMETRY) { - PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud); - } + if (PIOS_COM_TELEMETRY) { + PIOS_COM_ChangeBaud(PIOS_COM_TELEMETRY, comBaud); + } /* Remap AFIO pin */ GPIO_PinRemapConfig( GPIO_Remap_SWJ_NoJTRST, ENABLE); @@ -441,7 +329,7 @@ void PIOS_Board_Init(void) { #ifdef PIOS_INCLUDE_ADC PIOS_ADC_Init(); #endif - PIOS_GPIO_Init(); + PIOS_GPIO_Init(); } /** diff --git a/flight/targets/pipxtreme/fw/pios_config.h b/flight/targets/pipxtreme/fw/pios_config.h index f74b0f4ca99..75a4cea30e8 100755 --- a/flight/targets/pipxtreme/fw/pios_config.h +++ b/flight/targets/pipxtreme/fw/pios_config.h @@ -61,6 +61,9 @@ #define PIOS_INCLUDE_RFM22B #define PIOS_INCLUDE_PACKET_HANDLER +#define PIOS_INCLUDE_TARANIS_SPORT +#define PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY + #define PIOS_INCLUDE_FLASH #define PIOS_INCLUDE_FLASH_INTERNAL #define PIOS_INCLUDE_LOGFS_SETTINGS @@ -100,6 +103,9 @@ #define PIOS_INCLUDE_DEBUG_CONSOLE +#define PIOS_NO_TELEM_ON_RF +#define PIOS_NO_ALARMS + /* Turn on debugging signals on the telemetry port */ //#define PIOS_RFM22B_DEBUG_ON_TELEM diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/README.md b/flight/targets/pipxtreme/hw/TauLinkModule/README.md new file mode 100644 index 00000000000..c15c2c37be0 --- /dev/null +++ b/flight/targets/pipxtreme/hw/TauLinkModule/README.md @@ -0,0 +1,22 @@ +This is the TauLinkModule. It is inspired by the wonderful +work by pip a few years ago on the PipXtreme which was an +F1 processor with RFM22b module. This extends it to have +a layout that works in a JR module bay, has support for +injecting information into the Taranis, and has a bluetooth +module for relaying the telemetry to android. + +You can order PCBs directly from OSHPark here: + https://oshpark.com/shared_projects/gCTtwpcQ + +You can find a case for it here: + http://www.thingiverse.com/thing:747282 + +One thing that I don't love is the vertically mounted USB +connector that can be easily ripped off if one is not +careful, so be aware of that. + +The schematic calls for a HM-10 BLE module, however I think +there is a footprint compatible module that is not BLE which +might be a good alternative if you want to connect to the +computer. + diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Bottom v0.2.PDF b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Bottom v0.2.PDF new file mode 100644 index 00000000000..92556512ca9 Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Bottom v0.2.PDF differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Top v0.2.PDF b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Top v0.2.PDF new file mode 100644 index 00000000000..2095a7603fe Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule 3D Top v0.2.PDF differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule BOM v0.2.xls b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule BOM v0.2.xls new file mode 100644 index 00000000000..62525f8f6ef Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule BOM v0.2.xls differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule assembly v0.2.PDF b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule assembly v0.2.PDF new file mode 100644 index 00000000000..009a6947001 Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule assembly v0.2.PDF differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule gerbers v0.2.zip b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule gerbers v0.2.zip new file mode 100644 index 00000000000..3198d612375 Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule gerbers v0.2.zip differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule schematic v0.2.pdf b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule schematic v0.2.pdf new file mode 100644 index 00000000000..84c216971dd Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule schematic v0.2.pdf differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule stencil 0.2.zip b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule stencil 0.2.zip new file mode 100644 index 00000000000..1f59499c239 Binary files /dev/null and b/flight/targets/pipxtreme/hw/TauLinkModule/TauLinkModule stencil 0.2.zip differ diff --git a/flight/targets/pipxtreme/hw/TauLinkModule/license.txt b/flight/targets/pipxtreme/hw/TauLinkModule/license.txt new file mode 100644 index 00000000000..34ec65f344a --- /dev/null +++ b/flight/targets/pipxtreme/hw/TauLinkModule/license.txt @@ -0,0 +1,425 @@ +Attribution-ShareAlike 4.0 International + +======================================================================= + +Creative Commons Corporation ("Creative Commons") is not a law firm and +does not provide legal services or legal advice. Distribution of +Creative Commons public licenses does not create a lawyer-client or +other relationship. Creative Commons makes its licenses and related +information available on an "as-is" basis. Creative Commons gives no +warranties regarding its licenses, any material licensed under their +terms and conditions, or any related information. Creative Commons +disclaims all liability for damages resulting from their use to the +fullest extent possible. + +Using Creative Commons Public Licenses + +Creative Commons public licenses provide a standard set of terms and +conditions that creators and other rights holders may use to share +original works of authorship and other material subject to copyright +and certain other rights specified in the public license below. The +following considerations are for informational purposes only, are not +exhaustive, and do not form part of our licenses. + + Considerations for licensors: Our public licenses are + intended for use by those authorized to give the public + permission to use material in ways otherwise restricted by + copyright and certain other rights. Our licenses are + irrevocable. Licensors should read and understand the terms + and conditions of the license they choose before applying it. + Licensors should also secure all rights necessary before + applying our licenses so that the public can reuse the + material as expected. Licensors should clearly mark any + material not subject to the license. This includes other CC- + licensed material, or material used under an exception or + limitation to copyright. More considerations for licensors: + wiki.creativecommons.org/Considerations_for_licensors + + Considerations for the public: By using one of our public + licenses, a licensor grants the public permission to use the + licensed material under specified terms and conditions. If + the licensor's permission is not necessary for any reason--for + example, because of any applicable exception or limitation to + copyright--then that use is not regulated by the license. Our + licenses grant only permissions under copyright and certain + other rights that a licensor has authority to grant. Use of + the licensed material may still be restricted for other + reasons, including because others have copyright or other + rights in the material. A licensor may make special requests, + such as asking that all changes be marked or described. + Although not required by our licenses, you are encouraged to + respect those requests where reasonable. More_considerations + for the public: + wiki.creativecommons.org/Considerations_for_licensees + +======================================================================= + +Creative Commons Attribution-ShareAlike 4.0 International Public +License + +By exercising the Licensed Rights (defined below), You accept and agree +to be bound by the terms and conditions of this Creative Commons +Attribution-ShareAlike 4.0 International Public License ("Public +License"). To the extent this Public License may be interpreted as a +contract, You are granted the Licensed Rights in consideration of Your +acceptance of these terms and conditions, and the Licensor grants You +such rights in consideration of benefits the Licensor receives from +making the Licensed Material available under these terms and +conditions. + + +Section 1 -- Definitions. + + a. Adapted Material means material subject to Copyright and Similar + Rights that is derived from or based upon the Licensed Material + and in which the Licensed Material is translated, altered, + arranged, transformed, or otherwise modified in a manner requiring + permission under the Copyright and Similar Rights held by the + Licensor. For purposes of this Public License, where the Licensed + Material is a musical work, performance, or sound recording, + Adapted Material is always produced where the Licensed Material is + synched in timed relation with a moving image. + + b. Adapter's License means the license You apply to Your Copyright + and Similar Rights in Your contributions to Adapted Material in + accordance with the terms and conditions of this Public License. + + c. BY-SA Compatible License means a license listed at + creativecommons.org/compatiblelicenses, approved by Creative + Commons as essentially the equivalent of this Public License. + + d. Copyright and Similar Rights means copyright and/or similar rights + closely related to copyright including, without limitation, + performance, broadcast, sound recording, and Sui Generis Database + Rights, without regard to how the rights are labeled or + categorized. For purposes of this Public License, the rights + specified in Section 2(b)(1)-(2) are not Copyright and Similar + Rights. + + e. Effective Technological Measures means those measures that, in the + absence of proper authority, may not be circumvented under laws + fulfilling obligations under Article 11 of the WIPO Copyright + Treaty adopted on December 20, 1996, and/or similar international + agreements. + + f. Exceptions and Limitations means fair use, fair dealing, and/or + any other exception or limitation to Copyright and Similar Rights + that applies to Your use of the Licensed Material. + + g. License Elements means the license attributes listed in the name + of a Creative Commons Public License. The License Elements of this + Public License are Attribution and ShareAlike. + + h. Licensed Material means the artistic or literary work, database, + or other material to which the Licensor applied this Public + License. + + i. Licensed Rights means the rights granted to You subject to the + terms and conditions of this Public License, which are limited to + all Copyright and Similar Rights that apply to Your use of the + Licensed Material and that the Licensor has authority to license. + + j. Licensor means the individual(s) or entity(ies) granting rights + under this Public License. + + k. Share means to provide material to the public by any means or + process that requires permission under the Licensed Rights, such + as reproduction, public display, public performance, distribution, + dissemination, communication, or importation, and to make material + available to the public including in ways that members of the + public may access the material from a place and at a time + individually chosen by them. + + l. Sui Generis Database Rights means rights other than copyright + resulting from Directive 96/9/EC of the European Parliament and of + the Council of 11 March 1996 on the legal protection of databases, + as amended and/or succeeded, as well as other essentially + equivalent rights anywhere in the world. + + m. You means the individual or entity exercising the Licensed Rights + under this Public License. Your has a corresponding meaning. + + +Section 2 -- Scope. + + a. License grant. + + 1. Subject to the terms and conditions of this Public License, + the Licensor hereby grants You a worldwide, royalty-free, + non-sublicensable, non-exclusive, irrevocable license to + exercise the Licensed Rights in the Licensed Material to: + + a. reproduce and Share the Licensed Material, in whole or + in part; and + + b. produce, reproduce, and Share Adapted Material. + + 2. Exceptions and Limitations. For the avoidance of doubt, where + Exceptions and Limitations apply to Your use, this Public + License does not apply, and You do not need to comply with + its terms and conditions. + + 3. Term. The term of this Public License is specified in Section + 6(a). + + 4. Media and formats; technical modifications allowed. The + Licensor authorizes You to exercise the Licensed Rights in + all media and formats whether now known or hereafter created, + and to make technical modifications necessary to do so. The + Licensor waives and/or agrees not to assert any right or + authority to forbid You from making technical modifications + necessary to exercise the Licensed Rights, including + technical modifications necessary to circumvent Effective + Technological Measures. For purposes of this Public License, + simply making modifications authorized by this Section 2(a) + (4) never produces Adapted Material. + + 5. Downstream recipients. + + a. Offer from the Licensor -- Licensed Material. Every + recipient of the Licensed Material automatically + receives an offer from the Licensor to exercise the + Licensed Rights under the terms and conditions of this + Public License. + + b. Additional offer from the Licensor -- Adapted Material. + Every recipient of Adapted Material from You + automatically receives an offer from the Licensor to + exercise the Licensed Rights in the Adapted Material + under the conditions of the Adapter's License You apply. + + c. No downstream restrictions. You may not offer or impose + any additional or different terms or conditions on, or + apply any Effective Technological Measures to, the + Licensed Material if doing so restricts exercise of the + Licensed Rights by any recipient of the Licensed + Material. + + 6. No endorsement. Nothing in this Public License constitutes or + may be construed as permission to assert or imply that You + are, or that Your use of the Licensed Material is, connected + with, or sponsored, endorsed, or granted official status by, + the Licensor or others designated to receive attribution as + provided in Section 3(a)(1)(A)(i). + + b. Other rights. + + 1. Moral rights, such as the right of integrity, are not + licensed under this Public License, nor are publicity, + privacy, and/or other similar personality rights; however, to + the extent possible, the Licensor waives and/or agrees not to + assert any such rights held by the Licensor to the limited + extent necessary to allow You to exercise the Licensed + Rights, but not otherwise. + + 2. Patent and trademark rights are not licensed under this + Public License. + + 3. To the extent possible, the Licensor waives any right to + collect royalties from You for the exercise of the Licensed + Rights, whether directly or through a collecting society + under any voluntary or waivable statutory or compulsory + licensing scheme. In all other cases the Licensor expressly + reserves any right to collect such royalties. + + +Section 3 -- License Conditions. + +Your exercise of the Licensed Rights is expressly made subject to the +following conditions. + + a. Attribution. + + 1. If You Share the Licensed Material (including in modified + form), You must: + + a. retain the following if it is supplied by the Licensor + with the Licensed Material: + + i. identification of the creator(s) of the Licensed + Material and any others designated to receive + attribution, in any reasonable manner requested by + the Licensor (including by pseudonym if + designated); + + ii. a copyright notice; + + iii. a notice that refers to this Public License; + + iv. a notice that refers to the disclaimer of + warranties; + + v. a URI or hyperlink to the Licensed Material to the + extent reasonably practicable; + + b. indicate if You modified the Licensed Material and + retain an indication of any previous modifications; and + + c. indicate the Licensed Material is licensed under this + Public License, and include the text of, or the URI or + hyperlink to, this Public License. + + 2. You may satisfy the conditions in Section 3(a)(1) in any + reasonable manner based on the medium, means, and context in + which You Share the Licensed Material. For example, it may be + reasonable to satisfy the conditions by providing a URI or + hyperlink to a resource that includes the required + information. + + 3. If requested by the Licensor, You must remove any of the + information required by Section 3(a)(1)(A) to the extent + reasonably practicable. + + b. ShareAlike. + + In addition to the conditions in Section 3(a), if You Share + Adapted Material You produce, the following conditions also apply. + + 1. The Adapter's License You apply must be a Creative Commons + license with the same License Elements, this version or + later, or a BY-SA Compatible License. + + 2. You must include the text of, or the URI or hyperlink to, the + Adapter's License You apply. You may satisfy this condition + in any reasonable manner based on the medium, means, and + context in which You Share Adapted Material. + + 3. You may not offer or impose any additional or different terms + or conditions on, or apply any Effective Technological + Measures to, Adapted Material that restrict exercise of the + rights granted under the Adapter's License You apply. + + +Section 4 -- Sui Generis Database Rights. + +Where the Licensed Rights include Sui Generis Database Rights that +apply to Your use of the Licensed Material: + + a. for the avoidance of doubt, Section 2(a)(1) grants You the right + to extract, reuse, reproduce, and Share all or a substantial + portion of the contents of the database; + + b. if You include all or a substantial portion of the database + contents in a database in which You have Sui Generis Database + Rights, then the database in which You have Sui Generis Database + Rights (but not its individual contents) is Adapted Material, + + including for purposes of Section 3(b); and + c. You must comply with the conditions in Section 3(a) if You Share + all or a substantial portion of the contents of the database. + +For the avoidance of doubt, this Section 4 supplements and does not +replace Your obligations under this Public License where the Licensed +Rights include other Copyright and Similar Rights. + + +Section 5 -- Disclaimer of Warranties and Limitation of Liability. + + a. UNLESS OTHERWISE SEPARATELY UNDERTAKEN BY THE LICENSOR, TO THE + EXTENT POSSIBLE, THE LICENSOR OFFERS THE LICENSED MATERIAL AS-IS + AND AS-AVAILABLE, AND MAKES NO REPRESENTATIONS OR WARRANTIES OF + ANY KIND CONCERNING THE LICENSED MATERIAL, WHETHER EXPRESS, + IMPLIED, STATUTORY, OR OTHER. THIS INCLUDES, WITHOUT LIMITATION, + WARRANTIES OF TITLE, MERCHANTABILITY, FITNESS FOR A PARTICULAR + PURPOSE, NON-INFRINGEMENT, ABSENCE OF LATENT OR OTHER DEFECTS, + ACCURACY, OR THE PRESENCE OR ABSENCE OF ERRORS, WHETHER OR NOT + KNOWN OR DISCOVERABLE. WHERE DISCLAIMERS OF WARRANTIES ARE NOT + ALLOWED IN FULL OR IN PART, THIS DISCLAIMER MAY NOT APPLY TO YOU. + + b. TO THE EXTENT POSSIBLE, IN NO EVENT WILL THE LICENSOR BE LIABLE + TO YOU ON ANY LEGAL THEORY (INCLUDING, WITHOUT LIMITATION, + NEGLIGENCE) OR OTHERWISE FOR ANY DIRECT, SPECIAL, INDIRECT, + INCIDENTAL, CONSEQUENTIAL, PUNITIVE, EXEMPLARY, OR OTHER LOSSES, + COSTS, EXPENSES, OR DAMAGES ARISING OUT OF THIS PUBLIC LICENSE OR + USE OF THE LICENSED MATERIAL, EVEN IF THE LICENSOR HAS BEEN + ADVISED OF THE POSSIBILITY OF SUCH LOSSES, COSTS, EXPENSES, OR + DAMAGES. WHERE A LIMITATION OF LIABILITY IS NOT ALLOWED IN FULL OR + IN PART, THIS LIMITATION MAY NOT APPLY TO YOU. + + c. The disclaimer of warranties and limitation of liability provided + above shall be interpreted in a manner that, to the extent + possible, most closely approximates an absolute disclaimer and + waiver of all liability. + + +Section 6 -- Term and Termination. + + a. This Public License applies for the term of the Copyright and + Similar Rights licensed here. However, if You fail to comply with + this Public License, then Your rights under this Public License + terminate automatically. + + b. Where Your right to use the Licensed Material has terminated under + Section 6(a), it reinstates: + + 1. automatically as of the date the violation is cured, provided + it is cured within 30 days of Your discovery of the + violation; or + + 2. upon express reinstatement by the Licensor. + + For the avoidance of doubt, this Section 6(b) does not affect any + right the Licensor may have to seek remedies for Your violations + of this Public License. + + c. For the avoidance of doubt, the Licensor may also offer the + Licensed Material under separate terms or conditions or stop + distributing the Licensed Material at any time; however, doing so + will not terminate this Public License. + + d. Sections 1, 5, 6, 7, and 8 survive termination of this Public + License. + + +Section 7 -- Other Terms and Conditions. + + a. The Licensor shall not be bound by any additional or different + terms or conditions communicated by You unless expressly agreed. + + b. Any arrangements, understandings, or agreements regarding the + Licensed Material not stated herein are separate from and + independent of the terms and conditions of this Public License. + + +Section 8 -- Interpretation. + + a. For the avoidance of doubt, this Public License does not, and + shall not be interpreted to, reduce, limit, restrict, or impose + conditions on any use of the Licensed Material that could lawfully + be made without permission under this Public License. + + b. To the extent possible, if any provision of this Public License is + deemed unenforceable, it shall be automatically reformed to the + minimum extent necessary to make it enforceable. If the provision + cannot be reformed, it shall be severed from this Public License + without affecting the enforceability of the remaining terms and + conditions. + + c. No term or condition of this Public License will be waived and no + failure to comply consented to unless expressly agreed to by the + Licensor. + + d. Nothing in this Public License constitutes or may be interpreted + as a limitation upon, or waiver of, any privileges and immunities + that apply to the Licensor or You, including from the legal + processes of any jurisdiction or authority. + + +======================================================================= + +Creative Commons is not a party to its public licenses. +Notwithstanding, Creative Commons may elect to apply one of its public +licenses to material it publishes and in those instances will be +considered the "Licensor." Except for the limited purpose of indicating +that material is shared under a Creative Commons public license or as +otherwise permitted by the Creative Commons policies published at +creativecommons.org/policies, Creative Commons does not authorize the +use of the trademark "Creative Commons" or any other trademark or logo +of Creative Commons without its prior written consent including, +without limitation, in connection with any unauthorized modifications +to any of its public licenses or any other arrangements, +understandings, or agreements concerning use of licensed material. For +the avoidance of doubt, this paragraph does not form part of the public +licenses. + +Creative Commons may be contacted at creativecommons.org. diff --git a/flight/targets/quanton/fw/Makefile b/flight/targets/quanton/fw/Makefile index 537f1a5e69a..20a13d79a40 100644 --- a/flight/targets/quanton/fw/Makefile +++ b/flight/targets/quanton/fw/Makefile @@ -126,8 +126,8 @@ SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(FLIGHTLIB)/timeutils.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/atmospheric_math.c SRC += $(MATHLIB)/pid.c @@ -146,6 +146,7 @@ SRC += $(PIOSCOMMON)/pios_mpxv5004.c SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c @@ -165,9 +166,6 @@ SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c SRC += $(PIOSCOMMON)/pios_streamfs.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -334,4 +332,8 @@ LDFLAGS += -Wl,--fatal-warnings #Linker scripts LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) +include ./UAVObjects.inc + +UAVO_NAV = YES + include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/quanton/fw/UAVObjects.inc b/flight/targets/quanton/fw/UAVObjects.inc index 66e9cccda2b..db5452b37fa 100644 --- a/flight/targets/quanton/fw/UAVObjects.inc +++ b/flight/targets/quanton/fw/UAVObjects.inc @@ -1,7 +1,7 @@ ############################################################################### # @file Makefile # @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2012. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 # @addtogroup # @{ # @addtogroup @@ -29,103 +29,17 @@ UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus UAVOBJSRCFILENAMES += flightstats UAVOBJSRCFILENAMES += flightstatssettings -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings UAVOBJSRCFILENAMES += loggingsettings UAVOBJSRCFILENAMES += loggingstats -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwquanton -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += hottsettings UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/quanton/fw/pios_board.c b/flight/targets/quanton/fw/pios_board.c index a15bc8e1edc..c6a8d69006f 100644 --- a/flight/targets/quanton/fw/pios_board.c +++ b/flight/targets/quanton/fw/pios_board.c @@ -201,7 +201,6 @@ uintptr_t pios_com_telem_usb_id; uintptr_t pios_com_telem_rf_id; uintptr_t pios_com_vcp_id; uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; uintptr_t pios_com_mavlink_id; uintptr_t pios_com_hott_id; uintptr_t pios_com_frsky_sensor_hub_id; @@ -254,7 +253,7 @@ static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cf #ifdef PIOS_INCLUDE_DSM static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) + ManualControlSettingsChannelGroupsOptions channelgroup,HwQuantonDSMxModeOptions *mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -263,7 +262,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -595,8 +594,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwQuantonDSMxBindGet(&hw_DSMxBind); + HwQuantonDSMxModeOptions hw_DSMxMode; + HwQuantonDSMxModeGet(&hw_DSMxMode); /* init sensor queue registration */ PIOS_SENSORS_Init(); @@ -624,7 +623,7 @@ void PIOS_Board_Init(void) { } if (PIOS_I2C_CheckClear(pios_i2c_usart1_adapter_id) != 0) - panic(6); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); #if defined(PIOS_INCLUDE_HMC5883) { @@ -634,9 +633,9 @@ void PIOS_Board_Init(void) { if (Magnetometer == HWQUANTON_MAGNETOMETER_EXTERNALI2CUART1) { // init sensor if (PIOS_HMC5883_Init(pios_i2c_usart1_adapter_id, &pios_hmc5883_external_cfg) != 0) - panic(8); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); if (PIOS_HMC5883_Test() != 0) - panic(8); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); } } #endif /* PIOS_INCLUDE_HMC5883 */ @@ -646,7 +645,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart1_dsm_hsum_cfg, &pios_usart1_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -759,7 +758,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart2_dsm_hsum_cfg, &pios_usart2_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -859,7 +858,7 @@ void PIOS_Board_Init(void) { PIOS_Assert(0); } if (PIOS_I2C_CheckClear(pios_i2c_usart3_adapter_id) != 0) - panic(7); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); #if defined(PIOS_INCLUDE_HMC5883) { @@ -869,9 +868,9 @@ void PIOS_Board_Init(void) { if (Magnetometer == HWQUANTON_MAGNETOMETER_EXTERNALI2CUART3) { // init sensor if (PIOS_HMC5883_Init(pios_i2c_usart3_adapter_id, &pios_hmc5883_external_cfg) != 0) - panic(9); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); if (PIOS_HMC5883_Test() != 0) - panic(9); + AlarmsSet(SYSTEMALARMS_ALARM_I2C, SYSTEMALARMS_ALARM_CRITICAL); } } #endif /* PIOS_INCLUDE_HMC5883 */ @@ -881,7 +880,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart3_dsm_hsum_cfg, &pios_usart3_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -974,7 +973,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart4_dsm_hsum_cfg, &pios_usart4_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -1067,7 +1066,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_usart5_dsm_hsum_cfg, &pios_usart5_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; diff --git a/flight/targets/quanton/fw/pios_config.h b/flight/targets/quanton/fw/pios_config.h index 03268e1a531..c059976b35e 100644 --- a/flight/targets/quanton/fw/pios_config.h +++ b/flight/targets/quanton/fw/pios_config.h @@ -125,8 +125,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (9873737) -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/targets/revolution/bl/pios_board.c b/flight/targets/revolution/bl/pios_board.c deleted file mode 100644 index cc1065af0ba..00000000000 --- a/flight/targets/revolution/bl/pios_board.c +++ /dev/null @@ -1,101 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsBootloader Tau Labs Bootloaders - * @{ - * @addtogroup RevolutionBL Revolution bootloader - * @{ - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific initialization for the bootloader - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include -#include - -uintptr_t pios_com_telem_usb_id; - -void PIOS_Board_Init() -{ - /* Delay system */ - PIOS_DELAY_Init(); - -#if defined(PIOS_INCLUDE_LED) - PIOS_LED_Init(&pios_led_cfg); -#endif /* PIOS_INCLUDE_LED */ - -#if defined(PIOS_INCLUDE_FLASH) - -#if !defined(PIOS_FLASH_ON_ACCEL) - /* Set up the SPI interface to the flash */ - if (PIOS_SPI_Init(&pios_spi_flash_id, &pios_spi_flash_cfg)) { - PIOS_DEBUG_Assert(0); - } - /* Inititialize all flash drivers */ - PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_flash_id, 0, &flash_m25p_cfg); -#else - /* Set up the SPI interface to the accelerometer*/ - if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { - PIOS_DEBUG_Assert(0); - } - /* Inititialize all flash drivers */ - PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_accel_id, 1, &flash_m25p_cfg); -#endif - - PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg); - - /* Register the partition table */ - PIOS_FLASH_register_partition_table(pios_flash_partition_table, NELEMENTS(pios_flash_partition_table)); -#endif /* PIOS_INCLUDE_FLASH */ - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - /* Activate the HID-only USB configuration */ - PIOS_USB_DESC_HID_ONLY_Init(); - - uintptr_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); - -#if defined(PIOS_INCLUDE_USB_HID) && defined(PIOS_INCLUDE_COM_MSG) - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - if (PIOS_COM_MSG_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id)) { - PIOS_Assert(0); - } -#endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_COM_MSG */ - - PIOS_USBHOOK_Activate(); - -#endif /* PIOS_INCLUDE_USB */ -} diff --git a/flight/targets/revolution/bl/pios_usb_board_data.c b/flight/targets/revolution/bl/pios_usb_board_data.c deleted file mode 100644 index 1b8ab3d1977..00000000000 --- a/flight/targets/revolution/bl/pios_usb_board_data.c +++ /dev/null @@ -1,98 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsBootloader Tau Labs Bootloaders - * @{ - * @addtogroup RevolutionBL Revolution bootloader - * @{ - * - * @file pios_usb_board_data.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific USB definitions - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ -#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ - -static const uint8_t usb_product_id[22] = { - sizeof(usb_product_id), - USB_DESC_TYPE_STRING, - 'R', 0, - 'e', 0, - 'v', 0, - 'o', 0, - 'l', 0, - 'u', 0, - 't', 0, - 'i', 0, - 'o', 0, - 'n', 0, -}; - -static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { - sizeof(usb_serial_number), - USB_DESC_TYPE_STRING, -}; - -static const struct usb_string_langid usb_lang_id = { - .bLength = sizeof(usb_lang_id), - .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_US), -}; - -static const uint8_t usb_vendor_id[28] = { - sizeof(usb_vendor_id), - USB_DESC_TYPE_STRING, - 'o', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'p', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0 -}; - -int32_t PIOS_USB_BOARD_DATA_Init(void) -{ - /* Load device serial number into serial number string */ - uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; - PIOS_SYS_SerialNumberGet((char *)sn); - - /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ - uint8_t * utf8 = &(usb_serial_number[2]); - utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); - utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); - - return 0; -} diff --git a/flight/targets/revolution/board-info/cmsis_system.c b/flight/targets/revolution/board-info/cmsis_system.c deleted file mode 100644 index e36abd80005..00000000000 --- a/flight/targets/revolution/board-info/cmsis_system.c +++ /dev/null @@ -1,556 +0,0 @@ -/** - ****************************************************************************** - * @file system_stm32f4xx.c - * @author MCD Application Team - * @version V1.0.0 - * @date 30-September-2011 - * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File. - * This file contains the system clock configuration for STM32F4xx devices, - * and is generated by the clock configuration tool - * stm32f4xx_Clock_Configuration_V1.0.0.xls - * - * 1. This file provides two functions and one global variable to be called from - * user application: - * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier - * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and - * before branch to main program. This call is made inside - * the "startup_stm32f4xx.s" file. - * - * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick - * timer or configure other parameters. - * - * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must - * be called whenever the core clock is changed - * during program execution. - * - * 2. After each device reset the HSI (16 MHz) is used as system clock source. - * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to - * configure the system clock before to branch to main program. - * - * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and HSI still used as system clock source. User can - * add some code to deal with this issue inside the SetSysClock() function. - * - * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define - * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or - * through PLL, and you are using different crystal you have to adapt the HSE - * value to your own configuration. - * - * 5. This file configures the system clock as follows: - *============================================================================= - *============================================================================= - * Supported STM32F4xx device revision | Rev A - *----------------------------------------------------------------------------- - * System Clock source | PLL (HSE) - *----------------------------------------------------------------------------- - * SYSCLK(Hz) | 168000000 - *----------------------------------------------------------------------------- - * HCLK(Hz) | 168000000 - *----------------------------------------------------------------------------- - * AHB Prescaler | 1 - *----------------------------------------------------------------------------- - * APB1 Prescaler | 4 - *----------------------------------------------------------------------------- - * APB2 Prescaler | 2 - *----------------------------------------------------------------------------- - * HSE Frequency(Hz) | 8000000 - *----------------------------------------------------------------------------- - * PLL_M | 10 - *----------------------------------------------------------------------------- - * PLL_N | 420 - *----------------------------------------------------------------------------- - * PLL_P | 2 - *----------------------------------------------------------------------------- - * PLL_Q | 7 - *----------------------------------------------------------------------------- - * PLLI2S_N | NA - *----------------------------------------------------------------------------- - * PLLI2S_R | NA - *----------------------------------------------------------------------------- - * I2S input clock | NA - *----------------------------------------------------------------------------- - * VDD(V) | 3.3 - *----------------------------------------------------------------------------- - * Main regulator output voltage | Scale1 mode - *----------------------------------------------------------------------------- - * Flash Latency(WS) | 5 - *----------------------------------------------------------------------------- - * Prefetch Buffer | OFF - *----------------------------------------------------------------------------- - * Instruction cache | ON - *----------------------------------------------------------------------------- - * Data cache | ON - *----------------------------------------------------------------------------- - * Require 48MHz for USB OTG FS, | Enabled - * SDIO and RNG clock | - *----------------------------------------------------------------------------- - *============================================================================= - ****************************************************************************** - * @attention - * - * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS - * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE - * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY - * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING - * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. - * - *

© COPYRIGHT 2011 STMicroelectronics

- ****************************************************************************** - */ - -/** @addtogroup CMSIS - * @{ - */ - -/** @addtogroup stm32f4xx_system - * @{ - */ - -/** @addtogroup STM32F4xx_System_Private_Includes - * @{ - */ - -#include "stm32f4xx.h" - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_TypesDefinitions - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Defines - * @{ - */ - -/************************* Miscellaneous Configuration ************************/ -/*!< Uncomment the following line if you need to use external SRAM mounted - on STM324xG_EVAL board as data memory */ -/* #define DATA_IN_ExtSRAM */ - -/*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ -/* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ -/******************************************************************************/ - -/************************* PLL Parameters *************************************/ -/* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */ -#define PLL_M 10 -#define PLL_N 420 - -/* SYSCLK = PLL_VCO / PLL_P */ -#define PLL_P 2 - -/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */ -#define PLL_Q 7 - -/******************************************************************************/ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Macros - * @{ - */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Variables - * @{ - */ - - uint32_t SystemCoreClock = 168000000; - - __I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9}; - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes - * @{ - */ - -static void SetSysClock(void); -#ifdef DATA_IN_ExtSRAM - static void SystemInit_ExtMemCtl(void); -#endif /* DATA_IN_ExtSRAM */ - -/** - * @} - */ - -/** @addtogroup STM32F4xx_System_Private_Functions - * @{ - */ - -/** - * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the - * SystemFrequency variable. - * @param None - * @retval None - */ -void SystemInit(void) -{ - /* FPU settings ------------------------------------------------------------*/ - #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) - SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */ - #endif - - /* Reset the RCC clock configuration to the default reset state ------------*/ - /* Set HSION bit */ - RCC->CR |= (uint32_t)0x00000001; - - /* Reset CFGR register */ - RCC->CFGR = 0x00000000; - - /* Reset HSEON, CSSON and PLLON bits */ - RCC->CR &= (uint32_t)0xFEF6FFFF; - - /* Reset PLLCFGR register */ - RCC->PLLCFGR = 0x24003010; - - /* Reset HSEBYP bit */ - RCC->CR &= (uint32_t)0xFFFBFFFF; - - /* Disable all interrupts */ - RCC->CIR = 0x00000000; - -#ifdef DATA_IN_ExtSRAM - SystemInit_ExtMemCtl(); -#endif /* DATA_IN_ExtSRAM */ - - /* Configure the System clock source, PLL Multiplier and Divider factors, - AHB/APBx prescalers and Flash settings ----------------------------------*/ - SetSysClock(); - - /* Configure the Vector Table location add offset address ------------------*/ -#ifdef VECT_TAB_SRAM - SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */ -#else - SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */ -#endif -} - -/** - * @brief Update SystemCoreClock variable according to Clock Register Values. - * The SystemCoreClock variable contains the core clock (HCLK), it can - * be used by the user application to setup the SysTick timer or configure - * other parameters. - * - * @note Each time the core clock (HCLK) changes, this function must be called - * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined - * constant and the selected clock source: - * - * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) - * - * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) - * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) - * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * - * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value - * 16 MHz) but the real value may vary depending on the variations - * in voltage and temperature. - * - * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value - * 25 MHz), user has to ensure that HSE_VALUE is same as the real - * frequency of the crystal used. Otherwise, this function may - * have wrong result. - * - * - The result of this function could be not correct when using fractional - * value for HSE crystal. - * - * @param None - * @retval None - */ -void SystemCoreClockUpdate(void) -{ - uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2; - - /* Get SYSCLK source -------------------------------------------------------*/ - tmp = RCC->CFGR & RCC_CFGR_SWS; - - switch (tmp) - { - case 0x00: /* HSI used as system clock source */ - SystemCoreClock = HSI_VALUE; - break; - case 0x04: /* HSE used as system clock source */ - SystemCoreClock = HSE_VALUE; - break; - case 0x08: /* PLL used as system clock source */ - - /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N - SYSCLK = PLL_VCO / PLL_P - */ - pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22; - pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM; - - if (pllsource != 0) - { - /* HSE used as PLL clock source */ - pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - else - { - /* HSI used as PLL clock source */ - pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6); - } - - pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2; - SystemCoreClock = pllvco/pllp; - break; - default: - SystemCoreClock = HSI_VALUE; - break; - } - /* Compute HCLK frequency --------------------------------------------------*/ - /* Get HCLK prescaler */ - tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; - /* HCLK frequency */ - SystemCoreClock >>= tmp; -} - -/** - * @brief Configures the System clock source, PLL Multiplier and Divider factors, - * AHB/APBx prescalers and Flash settings - * @Note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). - * @param None - * @retval None - */ -static void SetSysClock(void) -{ -/******************************************************************************/ -/* PLL (clocked by HSE) used as System clock source */ -/******************************************************************************/ - __IO uint32_t StartUpCounter = 0, HSEStatus = 0; - - /* Enable HSE */ - RCC->CR |= ((uint32_t)RCC_CR_HSEON); - - /* Wait till HSE is ready and if Time out is reached exit */ - do - { - HSEStatus = RCC->CR & RCC_CR_HSERDY; - StartUpCounter++; - } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT)); - - if ((RCC->CR & RCC_CR_HSERDY) != RESET) - { - HSEStatus = (uint32_t)0x01; - } - else - { - HSEStatus = (uint32_t)0x00; - } - - if (HSEStatus == (uint32_t)0x01) - { - /* Select regulator voltage output Scale 1 mode, System frequency up to 168 MHz */ - RCC->APB1ENR |= RCC_APB1ENR_PWREN; - PWR->CR |= PWR_CR_VOS; - - /* HCLK = SYSCLK / 1*/ - RCC->CFGR |= RCC_CFGR_HPRE_DIV1; - - /* PCLK2 = HCLK / 2*/ - RCC->CFGR |= RCC_CFGR_PPRE2_DIV2; - - /* PCLK1 = HCLK / 4*/ - RCC->CFGR |= RCC_CFGR_PPRE1_DIV4; - - /* Configure the main PLL */ - RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | - (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24); - - /* Enable the main PLL */ - RCC->CR |= RCC_CR_PLLON; - - /* Wait till the main PLL is ready */ - while((RCC->CR & RCC_CR_PLLRDY) == 0) - { - } - - /* Configure Flash prefetch, Instruction cache, Data cache and wait state */ - FLASH->ACR = FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS; - - /* Select the main PLL as system clock source */ - RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); - RCC->CFGR |= RCC_CFGR_SW_PLL; - - /* Wait till the main PLL is used as system clock source */ - while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL); - { - } - } - else - { /* If HSE fails to start-up, the application will have wrong clock - configuration. User can add here some code to deal with this error */ - - /* better to hang here than to start with a wrong clock */ - while (1); - } - -} - -/** - * @brief Setup the external memory controller. Called in startup_stm32f4xx.s - * before jump to __main - * @param None - * @retval None - */ -#ifdef DATA_IN_ExtSRAM -/** - * @brief Setup the external memory controller. - * Called in startup_stm32f4xx.s before jump to main. - * This function configures the external SRAM mounted on STM324xG_EVAL board - * This SRAM will be used as program data memory (including heap and stack). - * @param None - * @retval None - */ -void SystemInit_ExtMemCtl(void) -{ -/*-- GPIOs Configuration -----------------------------------------------------*/ -/* - +-------------------+--------------------+------------------+------------------+ - + SRAM pins assignment + - +-------------------+--------------------+------------------+------------------+ - | PD0 <-> FSMC_D2 | PE0 <-> FSMC_NBL0 | PF0 <-> FSMC_A0 | PG0 <-> FSMC_A10 | - | PD1 <-> FSMC_D3 | PE1 <-> FSMC_NBL1 | PF1 <-> FSMC_A1 | PG1 <-> FSMC_A11 | - | PD4 <-> FSMC_NOE | PE3 <-> FSMC_A19 | PF2 <-> FSMC_A2 | PG2 <-> FSMC_A12 | - | PD5 <-> FSMC_NWE | PE4 <-> FSMC_A20 | PF3 <-> FSMC_A3 | PG3 <-> FSMC_A13 | - | PD8 <-> FSMC_D13 | PE7 <-> FSMC_D4 | PF4 <-> FSMC_A4 | PG4 <-> FSMC_A14 | - | PD9 <-> FSMC_D14 | PE8 <-> FSMC_D5 | PF5 <-> FSMC_A5 | PG5 <-> FSMC_A15 | - | PD10 <-> FSMC_D15 | PE9 <-> FSMC_D6 | PF12 <-> FSMC_A6 | PG9 <-> FSMC_NE2 | - | PD11 <-> FSMC_A16 | PE10 <-> FSMC_D7 | PF13 <-> FSMC_A7 |------------------+ - | PD12 <-> FSMC_A17 | PE11 <-> FSMC_D8 | PF14 <-> FSMC_A8 | - | PD13 <-> FSMC_A18 | PE12 <-> FSMC_D9 | PF15 <-> FSMC_A9 | - | PD14 <-> FSMC_D0 | PE13 <-> FSMC_D10 |------------------+ - | PD15 <-> FSMC_D1 | PE14 <-> FSMC_D11 | - | | PE15 <-> FSMC_D12 | - +-------------------+--------------------+ -*/ - /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */ - RCC->AHB1ENR = 0x00000078; - - /* Connect PDx pins to FSMC Alternate function */ - GPIOD->AFR[0] = 0x00cc00cc; - GPIOD->AFR[1] = 0xcc0ccccc; - /* Configure PDx pins in Alternate function mode */ - GPIOD->MODER = 0xaaaa0a0a; - /* Configure PDx pins speed to 100 MHz */ - GPIOD->OSPEEDR = 0xffff0f0f; - /* Configure PDx pins Output type to push-pull */ - GPIOD->OTYPER = 0x00000000; - /* No pull-up, pull-down for PDx pins */ - GPIOD->PUPDR = 0x00000000; - - /* Connect PEx pins to FSMC Alternate function */ - GPIOE->AFR[0] = 0xc00cc0cc; - GPIOE->AFR[1] = 0xcccccccc; - /* Configure PEx pins in Alternate function mode */ - GPIOE->MODER = 0xaaaa828a; - /* Configure PEx pins speed to 100 MHz */ - GPIOE->OSPEEDR = 0xffffc3cf; - /* Configure PEx pins Output type to push-pull */ - GPIOE->OTYPER = 0x00000000; - /* No pull-up, pull-down for PEx pins */ - GPIOE->PUPDR = 0x00000000; - - /* Connect PFx pins to FSMC Alternate function */ - GPIOF->AFR[0] = 0x00cccccc; - GPIOF->AFR[1] = 0xcccc0000; - /* Configure PFx pins in Alternate function mode */ - GPIOF->MODER = 0xaa000aaa; - /* Configure PFx pins speed to 100 MHz */ - GPIOF->OSPEEDR = 0xff000fff; - /* Configure PFx pins Output type to push-pull */ - GPIOF->OTYPER = 0x00000000; - /* No pull-up, pull-down for PFx pins */ - GPIOF->PUPDR = 0x00000000; - - /* Connect PGx pins to FSMC Alternate function */ - GPIOG->AFR[0] = 0x00cccccc; - GPIOG->AFR[1] = 0x000000c0; - /* Configure PGx pins in Alternate function mode */ - GPIOG->MODER = 0x00080aaa; - /* Configure PGx pins speed to 100 MHz */ - GPIOG->OSPEEDR = 0x000c0fff; - /* Configure PGx pins Output type to push-pull */ - GPIOG->OTYPER = 0x00000000; - /* No pull-up, pull-down for PGx pins */ - GPIOG->PUPDR = 0x00000000; - -/*-- FSMC Configuration ------------------------------------------------------*/ - /* Enable the FSMC interface clock */ - RCC->AHB3ENR = 0x00000001; - - /* Configure and enable Bank1_SRAM2 */ - FSMC_Bank1->BTCR[2] = 0x00001015; - FSMC_Bank1->BTCR[3] = 0x00010603; - FSMC_Bank1E->BWTR[2] = 0x0fffffff; -/* - Bank1_SRAM2 is configured as follow: - - p.FSMC_AddressSetupTime = 3; - p.FSMC_AddressHoldTime = 0; - p.FSMC_DataSetupTime = 6; - p.FSMC_BusTurnAroundDuration = 1; - p.FSMC_CLKDivision = 0; - p.FSMC_DataLatency = 0; - p.FSMC_AccessMode = FSMC_AccessMode_A; - - FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2; - FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable; - FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_PSRAM; - FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b; - FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low; - FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState; - FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable; - FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable; - FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable; - FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable; - FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &p; - FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &p; -*/ - -} -#endif /* DATA_IN_ExtSRAM */ - - -/** - * @} - */ - -/** - * @} - */ - -/** - * @} - */ -/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/flight/targets/revolution/board-info/usb_conf.h b/flight/targets/revolution/board-info/usb_conf.h deleted file mode 100644 index ee6c0efa2da..00000000000 --- a/flight/targets/revolution/board-info/usb_conf.h +++ /dev/null @@ -1,315 +0,0 @@ -/** - ****************************************************************************** - * @file usb_conf.h - * @author MCD Application Team - * @version V2.1.0 - * @date 19-March-2012 - * @brief General low level driver configuration - ****************************************************************************** - * @attention - * - *

© COPYRIGHT 2012 STMicroelectronics

- * - * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); - * You may not use this file except in compliance with the License. - * You may obtain a copy of the License at: - * - * http://www.st.com/software_license_agreement_liberty_v2 - * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, - * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. - * See the License for the specific language governing permissions and - * limitations under the License. - * - ****************************************************************************** - */ - -/* Define to prevent recursive inclusion -------------------------------------*/ -#ifndef __USB_CONF__H__ -#define __USB_CONF__H__ - -/* Includes ------------------------------------------------------------------*/ -#include "stm32f4xx.h" - - -/** @addtogroup USB_OTG_DRIVER - * @{ - */ - -/** @defgroup USB_CONF - * @brief USB low level driver configuration file - * @{ - */ - -/** @defgroup USB_CONF_Exported_Defines - * @{ - */ - -/* USB Core and PHY interface configuration. - Tip: To avoid modifying these defines each time you need to change the USB - configuration, you can declare the needed define in your toolchain - compiler preprocessor. - */ -/****************** USB OTG FS PHY CONFIGURATION ******************************* -* The USB OTG FS Core supports one on-chip Full Speed PHY. -* -* The USE_EMBEDDED_PHY symbol is defined in the project compiler preprocessor -* when FS core is used. -*******************************************************************************/ -#ifndef USE_USB_OTG_FS - #define USE_USB_OTG_FS -#endif /* USE_USB_OTG_FS */ - -#ifdef USE_USB_OTG_FS - #define USB_OTG_FS_CORE -#endif - -/****************** USB OTG HS PHY CONFIGURATION ******************************* -* The USB OTG HS Core supports two PHY interfaces: -* (i) An ULPI interface for the external High Speed PHY: the USB HS Core will -* operate in High speed mode -* (ii) An on-chip Full Speed PHY: the USB HS Core will operate in Full speed mode -* -* You can select the PHY to be used using one of these two defines: -* (i) USE_ULPI_PHY: if the USB OTG HS Core is to be used in High speed mode -* (ii) USE_EMBEDDED_PHY: if the USB OTG HS Core is to be used in Full speed mode -* -* Notes: -* - The USE_ULPI_PHY symbol is defined in the project compiler preprocessor as -* default PHY when HS core is used. -* - On STM322xG-EVAL and STM324xG-EVAL boards, only configuration(i) is available. -* Configuration (ii) need a different hardware, for more details refer to your -* STM32 device datasheet. -*******************************************************************************/ -#ifndef USE_USB_OTG_HS - //#define USE_USB_OTG_HS -#endif /* USE_USB_OTG_HS */ - -#ifndef USE_ULPI_PHY - //#define USE_ULPI_PHY -#endif /* USE_ULPI_PHY */ - -#ifndef USE_EMBEDDED_PHY - #define USE_EMBEDDED_PHY -#endif /* USE_EMBEDDED_PHY */ - -#ifdef USE_USB_OTG_FS - #define USB_OTG_FS_CORE -#endif - -#ifdef USE_USB_OTG_HS - #define USB_OTG_HS_CORE -#endif - -/******************************************************************************* -* FIFO Size Configuration in Device mode -* -* (i) Receive data FIFO size = RAM for setup packets + -* OUT endpoint control information + -* data OUT packets + miscellaneous -* Space = ONE 32-bits words -* --> RAM for setup packets = 10 spaces -* (n is the nbr of CTRL EPs the device core supports) -* --> OUT EP CTRL info = 1 space -* (one space for status information written to the FIFO along with each -* received packet) -* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces -* (MINIMUM to receive packets) -* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces -* (if high-bandwidth EP is enabled or multiple isochronous EPs) -* --> miscellaneous = 1 space per OUT EP -* (one space for transfer complete status information also pushed to the -* FIFO with each endpoint's last packet) -* -* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for -* that particular IN EP. More space allocated in the IN EP Tx FIFO results -* in a better performance on the USB and can hide latencies on the AHB. -* -* (iii) TXn min size = 16 words. (n : Transmit FIFO index) -* (iv) When a TxFIFO is not used, the Configuration should be as follows: -* case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) -* --> Txm can use the space allocated for Txn. -* case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) -* --> Txn should be configured with the minimum space of 16 words -* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top -* of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. -*******************************************************************************/ - -/******************************************************************************* -* FIFO Size Configuration in Host mode -* -* (i) Receive data FIFO size = (Largest Packet Size / 4) + 1 or -* 2x (Largest Packet Size / 4) + 1, If a -* high-bandwidth channel or multiple isochronous -* channels are enabled -* -* (ii) For the host nonperiodic Transmit FIFO is the largest maximum packet size -* for all supported nonperiodic OUT channels. Typically, a space -* corresponding to two Largest Packet Size is recommended. -* -* (iii) The minimum amount of RAM required for Host periodic Transmit FIFO is -* the largest maximum packet size for all supported periodic OUT channels. -* If there is at least one High Bandwidth Isochronous OUT endpoint, -* then the space must be at least two times the maximum packet size for -* that channel. -*******************************************************************************/ - -/****************** USB OTG HS CONFIGURATION **********************************/ -#ifdef USB_OTG_HS_CORE - #define RX_FIFO_HS_SIZE 512 - #define TX0_FIFO_HS_SIZE 512 - #define TX1_FIFO_HS_SIZE 512 - #define TX2_FIFO_HS_SIZE 0 - #define TX3_FIFO_HS_SIZE 0 - #define TX4_FIFO_HS_SIZE 0 - #define TX5_FIFO_HS_SIZE 0 - #define TXH_NP_HS_FIFOSIZ 96 - #define TXH_P_HS_FIFOSIZ 96 - -// #define USB_OTG_HS_LOW_PWR_MGMT_SUPPORT -// #define USB_OTG_HS_SOF_OUTPUT_ENABLED - -// #define USB_OTG_INTERNAL_VBUS_ENABLED - #define USB_OTG_EXTERNAL_VBUS_ENABLED - - #ifdef USE_ULPI_PHY - #define USB_OTG_ULPI_PHY_ENABLED - #endif - #ifdef USE_EMBEDDED_PHY - #define USB_OTG_EMBEDDED_PHY_ENABLED - #endif - #define USB_OTG_HS_INTERNAL_DMA_ENABLED - #define USB_OTG_HS_DEDICATED_EP1_ENABLED -#endif - -/****************** USB OTG FS CONFIGURATION **********************************/ -#ifdef USB_OTG_FS_CORE - #define RX_FIFO_FS_SIZE 128 - #define TX0_FIFO_FS_SIZE 64 - #define TX1_FIFO_FS_SIZE 32 - #define TX2_FIFO_FS_SIZE 32 - #define TX3_FIFO_FS_SIZE 64 - #define TXH_NP_HS_FIFOSIZ 96 - #define TXH_P_HS_FIFOSIZ 96 - -// #define USB_OTG_FS_LOW_PWR_MGMT_SUPPORT -// #define USB_OTG_FS_SOF_OUTPUT_ENABLED -#endif - -/****************** USB OTG MISC CONFIGURATION ********************************/ -//#define VBUS_SENSING_ENABLED - -/****************** USB OTG MODE CONFIGURATION ********************************/ -//#define USE_HOST_MODE -#define USE_DEVICE_MODE -//#define USE_OTG_MODE - -#ifndef USB_OTG_FS_CORE - #ifndef USB_OTG_HS_CORE - #error "USB_OTG_HS_CORE or USB_OTG_FS_CORE should be defined" - #endif -#endif - -#ifndef USE_DEVICE_MODE - #ifndef USE_HOST_MODE - #error "USE_DEVICE_MODE or USE_HOST_MODE should be defined" - #endif -#endif - -#ifndef USE_USB_OTG_HS - #ifndef USE_USB_OTG_FS - #error "USE_USB_OTG_HS or USE_USB_OTG_FS should be defined" - #endif -#else //USE_USB_OTG_HS - #ifndef USE_ULPI_PHY - #ifndef USE_EMBEDDED_PHY - #error "USE_ULPI_PHY or USE_EMBEDDED_PHY should be defined" - #endif - #endif -#endif - -/****************** C Compilers dependant keywords ****************************/ -/* In HS mode and when the DMA is used, all variables and data structures dealing - with the DMA during the transaction process should be 4-bytes aligned */ -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED - #if defined (__GNUC__) /* GNU Compiler */ - #define __ALIGN_END __attribute__ ((aligned (4))) - #define __ALIGN_BEGIN - #else - #define __ALIGN_END - #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #elif defined (__TASKING__) /* TASKING Compiler */ - #define __ALIGN_BEGIN __align(4) - #endif /* __CC_ARM */ - #endif /* __GNUC__ */ -#else - #define __ALIGN_BEGIN - #define __ALIGN_END -#endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ - -/* __packed keyword used to decrease the data type alignment to 1-byte */ -#if !defined(__packed) - -#if defined (__CC_ARM) /* ARM Compiler */ - #define __packed __packed -#elif defined (__ICCARM__) /* IAR Compiler */ - #define __packed __packed -#elif defined ( __GNUC__ ) /* GNU Compiler */ - #define __packed __attribute__ ((__packed__)) -#elif defined (__TASKING__) /* TASKING Compiler */ - #define __packed __unaligned -#endif /* __CC_ARM */ - -#endif /* __packed **/ - -/** - * @} - */ - - -/** @defgroup USB_CONF_Exported_Types - * @{ - */ -/** - * @} - */ - - -/** @defgroup USB_CONF_Exported_Macros - * @{ - */ -/** - * @} - */ - -/** @defgroup USB_CONF_Exported_Variables - * @{ - */ -/** - * @} - */ - -/** @defgroup USB_CONF_Exported_FunctionsPrototype - * @{ - */ -/** - * @} - */ - - -#endif //__USB_CONF__H__ - - -/** - * @} - */ - -/** - * @} - */ -/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ - diff --git a/flight/targets/revolution/fw/FreeRTOSConfig.h b/flight/targets/revolution/fw/FreeRTOSConfig.h deleted file mode 100644 index 0d0a9d3394e..00000000000 --- a/flight/targets/revolution/fw/FreeRTOSConfig.h +++ /dev/null @@ -1,98 +0,0 @@ - -#ifndef FREERTOS_CONFIG_H -#define FREERTOS_CONFIG_H - -#if !defined(SIM_OSX) && !defined(SIM_POSIX) -#include -#endif - -/*----------------------------------------------------------- - * Application specific definitions. - * - * These definitions should be adjusted for your particular hardware and - * application requirements. - * - * THESE PARAMETERS ARE DESCRIBED WITHIN THE 'CONFIGURATION' SECTION OF THE - * FreeRTOS API DOCUMENTATION AVAILABLE ON THE FreeRTOS.org WEB SITE. - * - * See http://www.freertos.org/a00110.html. - *----------------------------------------------------------*/ - -/** - * @addtogroup PIOS PIOS - * @{ - * @addtogroup FreeRTOS FreeRTOS - * @{ - */ - -/* Notes: We use 5 task priorities */ - -#define configCPU_CLOCK_HZ (SYSCLK_FREQ) // really the NVIC clock ... -#define configTICK_RATE_HZ ((portTickType )1000) -#define configMAX_PRIORITIES ((unsigned portBASE_TYPE)5) -#define configMINIMAL_STACK_SIZE ((unsigned short)512) -#define configMAX_TASK_NAME_LEN (16) - -#define configUSE_PREEMPTION 1 -#define configUSE_IDLE_HOOK 1 -#define configUSE_TICK_HOOK 0 -#define configUSE_TRACE_FACILITY 0 -#define configUSE_16_BIT_TICKS 0 -#define configIDLE_SHOULD_YIELD 0 -#define configUSE_MUTEXES 1 -#define configUSE_RECURSIVE_MUTEXES 1 -#define configUSE_COUNTING_SEMAPHORES 0 -#define configUSE_ALTERNATIVE_API 0 -#define configCHECK_FOR_STACK_OVERFLOW 2 -#define configQUEUE_REGISTRY_SIZE 0 - -#define configUSE_TIMERS 0 -#define configTIMER_TASK_PRIORITY (configMAX_PRIORITIES - 1) /* run timers at max priority */ -#define configTIMER_QUEUE_LENGTH 10 -#define configTIMER_TASK_STACK_DEPTH configMINIMAL_STACK_SIZE - -/* Co-routine definitions. */ -#define configUSE_CO_ROUTINES 0 -#define configMAX_CO_ROUTINE_PRIORITIES 0 - -/* Set the following definitions to 1 to include the API function, or zero -to exclude the API function. */ - -#define INCLUDE_vTaskPrioritySet 0 -#define INCLUDE_uxTaskPriorityGet 0 -#define INCLUDE_vTaskDelete 1 -#define INCLUDE_vTaskCleanUpResources 0 -#define INCLUDE_vTaskSuspend 0 -#define INCLUDE_vTaskDelayUntil 1 -#define INCLUDE_vTaskDelay 1 -#define INCLUDE_xTaskGetSchedulerState 0 -#define INCLUDE_xTaskGetCurrentTaskHandle 0 -#define INCLUDE_uxTaskGetStackHighWaterMark 1 - -/* This is the raw value as per the Cortex-M3 NVIC. Values can be 255 -(lowest) to 1 (highest maskable) to 0 (highest non-maskable). */ -#define configKERNEL_INTERRUPT_PRIORITY 15 << 4 /* equivalent to NVIC priority 15 */ -#define configMAX_SYSCALL_INTERRUPT_PRIORITY 3 << 4 /* equivalent to NVIC priority 3 */ - -/* This is the value being used as per the ST library which permits 16 -priority values, 0 to 15. This must correspond to the -configKERNEL_INTERRUPT_PRIORITY setting. Here 15 corresponds to the lowest -NVIC value of 255. */ -#define configLIBRARY_KERNEL_INTERRUPT_PRIORITY 15 - -/* Enable run time stats collection */ -#define configGENERATE_RUN_TIME_STATS 1 -#define INCLUDE_uxTaskGetRunTime 1 - -#define portCONFIGURE_TIMER_FOR_RUN_TIME_STATS() \ - do { \ - CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; \ - DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; \ - } while(0) -#define portGET_RUN_TIME_COUNTER_VALUE() DWT->CYCCNT - -/** - * @} - */ - -#endif /* FREERTOS_CONFIG_H */ diff --git a/flight/targets/revolution/fw/Makefile b/flight/targets/revolution/fw/Makefile deleted file mode 100644 index 983c57f0f71..00000000000 --- a/flight/targets/revolution/fw/Makefile +++ /dev/null @@ -1,382 +0,0 @@ -############################################################################### -# @file Makefile -# @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2009. -# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 -# @addtogroup -# @{ -# @addtogroup -# @{ -# @brief Makefile to build firmware for the Revolution board. -############################################################################### -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -# - -include $(MAKE_INC_DIR)/firmware-defs.mk -include $(BOARD_INFO_DIR)/board-info.mk - -# Set developer code and compile options -# Set to YES for debugging -DEBUG ?= NO - -# Optional module and driver defaults -USE_COMUSBBRIDGE ?= NO -USE_TXPID ?= NO -USE_I2C ?= NO -USE_ALTITUDE ?= NO -TEST_FAULTS ?= NO -USE_MAGBARO ?= NO - -# List of optional modules to include -OPTMODULES = -ifeq ($(USE_COMUSBBRIDGE), YES) -OPTMODULES += ComUsbBridge -endif -ifeq ($(USE_TXPID), YES) -OPTMODULES += TxPID -endif -ifeq ($(TEST_FAULTS), YES) -OPTMODULES += Fault -endif -ifeq ($(USE_MAGBARO), YES) -ifeq ($(USE_I2C), YES) -OPTMODULES += Extensions/MagBaro -else -$(error "MagBaro module (USE_MAGBARO=YES) requires i2c (USE_I2C=YES)") -endif -endif - -# List of modules to include -MODULES = Sensors -MODULES += Attitude -MODULES += ManualControl -MODULES += Stabilization -MODULES += Actuator -MODULES += FirmwareIAP -MODULES += Telemetry - -OPTMODULES += GPS -OPTMODULES += AltitudeHold -OPTMODULES += PathPlanner -OPTMODULES += VtolPathFollower -OPTMODULES += FixedWingPathFollower -OPTMODULES += CameraStab -OPTMODULES += OveroSync -OPTMODULES += Autotune -OPTMODULES += TxPID -OPTMODULES += UAVOMavlinkBridge -OPTMODULES += Battery -OPTMODULES += VibrationAnalysis -OPTMODULES += Airspeed/revolution -OPTMODULES += UAVOHoTTBridge -OPTMODULES += PicoC -OPTMODULES += UAVOFrSKYSPortBridge -OPTMODULES += Geofence - -PYMODULES = -#FlightPlan - -# Paths -OPUAVTALKINC = $(OPUAVTALK)/inc -OPUAVOBJINC = $(OPUAVOBJ)/inc -PIOSINC = $(PIOS)/inc -FLIGHTLIBINC = $(FLIGHTLIB)/inc -MATHLIB = $(FLIGHTLIB)/math -MATHLIBINC = $(FLIGHTLIB)/math -PIOSSTM32F4XX = $(PIOS)/STM32F4xx -PIOSCOMMON = $(PIOS)/Common -PIOSCOMMONLIB = $(PIOSCOMMON)/Libraries -APPLIBDIR = $(PIOSSTM32F4XX)/Libraries -STMLIBDIR = $(APPLIBDIR) -STMSPDDIR = $(STMLIBDIR)/STM32F4xx_StdPeriph_Driver -STMSPDSRCDIR = $(STMSPDDIR)/src -STMSPDINCDIR = $(STMSPDDIR)/inc -DEBUG_CM3_DIR = $(PIOSCOMMONLIB)/Debug -DEBUG_CM3_DIR_INC = $(DEBUG_CM3_DIR)/inc -OPUAVOBJINC = $(OPUAVOBJ)/inc -MAVLINKINC = $(FLIGHTLIB)/mavlink/v1.0/common - -SRC = -# optional component libraries -include $(PIOSCOMMONLIB)/FreeRTOS/library.mk -#include $(PIOSCOMMONLIB)/dosfs/library.mk -include $(FLIGHTLIB)/CMSIS3/DSP_Lib/library.mk - - -# List C source files here. (C dependencies are automatically generated.) -# use file-extension c for "c-only"-files - -## MODULES -SRC += ${foreach MOD, ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -SRC += ${foreach MOD, ${MODULES}, ${wildcard ${OPMODULEDIR}/${MOD}/*.c}} -## OPENPILOT CORE: -SRC += ${OPMODULEDIR}/System/systemmod.c -SRC += main.c -SRC += pios_board.c -SRC += pios_usb_board_data.c -SRC += $(FLIGHTLIB)/alarms.c -SRC += $(OPUAVTALK)/uavtalk.c -SRC += $(OPUAVOBJ)/uavobjectmanager.c -SRC += $(OPUAVOBJ)/eventdispatcher.c - -#ifeq ($(DEBUG),YES) -SRC += $(DEBUG_CM3_DIR)/dcc_stdio.c -SRC += $(DEBUG_CM3_DIR)/cm3_fault_handlers.c -#endif - -SRC += $(FLIGHTLIB)/paths.c -SRC += $(FLIGHTLIB)/fifo_buffer.c -SRC += $(FLIGHTLIB)/WorldMagModel.c -SRC += $(FLIGHTLIB)/insgps14state.c -SRC += $(FLIGHTLIB)/taskmonitor.c -SRC += $(FLIGHTLIB)/sanitycheck.c - -SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c -SRC += $(MATHLIB)/misc_math.c -SRC += $(MATHLIB)/pid.c -SRC += $(MATHLIB)/atmospheric_math.c - -## PIOS Hardware (STM32F4xx) -include $(PIOS)/STM32F4xx/library_fw.mk - -## PIOS Hardware (Common) -SRC += $(PIOSCOMMON)/pios_delay.c -SRC += $(PIOSCOMMON)/pios_mpu6000.c -SRC += $(PIOSCOMMON)/pios_bma180.c -SRC += $(PIOSCOMMON)/pios_etasv3.c -SRC += $(PIOSCOMMON)/pios_mpxv5004.c -SRC += $(PIOSCOMMON)/pios_mpxv7002.c -SRC += $(PIOSCOMMON)/pios_gcsrcvr.c -SRC += $(PIOSCOMMON)/pios_l3gd20.c -SRC += $(PIOSCOMMON)/pios_hmc5883.c -SRC += $(PIOSCOMMON)/pios_ms5611.c -SRC += $(PIOSCOMMON)/pios_crc.c -SRC += $(PIOSCOMMON)/pios_com.c -SRC += $(PIOSCOMMON)/pios_rcvr.c -SRC += $(PIOSCOMMON)/pios_hsum.c -SRC += $(PIOSCOMMON)/pios_sensors.c -SRC += $(PIOSCOMMON)/pios_flash.c -SRC += $(PIOSCOMMON)/pios_flash_jedec.c -SRC += $(PIOSCOMMON)/pios_flashfs_logfs.c -SRC += $(PIOSCOMMON)/printf-stdarg.c -SRC += $(PIOSCOMMON)/pios_usb_desc_hid_cdc.c -SRC += $(PIOSCOMMON)/pios_usb_desc_hid_only.c -SRC += $(PIOSCOMMON)/pios_usb_util.c -SRC += $(PIOSCOMMON)/pios_adc.c -SRC += $(PIOSCOMMON)/pios_heap.c -SRC += $(PIOSCOMMON)/pios_semaphore.c -SRC += $(PIOSCOMMON)/pios_mutex.c -SRC += $(PIOSCOMMON)/pios_thread.c -SRC += $(PIOSCOMMON)/pios_queue.c - -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - -# List C source files here which must be compiled in ARM-Mode (no -mthumb). -# use file-extension c for "c-only"-files -## just for testing, timer.c could be compiled in thumb-mode too -SRCARM = - -# List C++ source files here. -# use file-extension .cpp for C++-files (not .C) -CPPSRC = - -# List C++ source files here which must be compiled in ARM-Mode. -# use file-extension .cpp for C++-files (not .C) -#CPPSRCARM = $(TARGET).cpp -CPPSRCARM = - -# List Assembler source files here. -# Make them always end in a capital .S. Files ending in a lowercase .s -# will not be considered source files but generated files (assembler -# output from the compiler), and will be deleted upon "make clean"! -# Even though the DOS/Win* filesystem matches both .s and .S the same, -# it will preserve the spelling of the filenames, and gcc itself does -# care about how the name is spelled on its command-line. - - -# List Assembler source files here which must be assembled in ARM-Mode.. -ASRCARM = - -# List any extra directories to look for include files here. -# Each directory must be seperated by a space. -EXTRAINCDIRS += $(SHAREDAPIDIR) -EXTRAINCDIRS += $(PIOS) -EXTRAINCDIRS += $(PIOSINC) -EXTRAINCDIRS += $(OPUAVTALK) -EXTRAINCDIRS += $(OPUAVTALKINC) -EXTRAINCDIRS += $(OPUAVOBJ) -EXTRAINCDIRS += $(OPUAVOBJINC) -EXTRAINCDIRS += $(OPUAVSYNTHDIR) -EXTRAINCDIRS += $(FLIGHTLIBINC) -EXTRAINCDIRS += $(MATHLIBINC) -EXTRAINCDIRS += $(PIOSSTM32F4XX) -EXTRAINCDIRS += $(PIOSCOMMON) -EXTRAINCDIRS += $(BOARD_INFO_DIR) -EXTRAINCDIRS += $(STMSPDINCDIR) -EXTRAINCDIRS += $(CMSISDIR) -EXTRAINCDIRS += $(DEBUG_CM3_DIR_INC) -EXTRAINCDIRS += $(MAVLINKINC) - -EXTRAINCDIRS += ${foreach MOD, ${OPTMODULES} ${MODULES} ${PYMODULES}, $(OPMODULEDIR)/${MOD}/inc} ${OPMODULEDIR}/System/inc - -# List any extra directories to look for library files here. -# Also add directories where the linker should search for -# includes from linker-script to the list -# Each directory must be seperated by a space. -EXTRA_LIBDIRS = - -# Extra Libraries -# Each library-name must be seperated by a space. -# i.e. to link with libxyz.a, libabc.a and libefsl.a: -# EXTRA_LIBS = xyz abc efsl -# for newlib-lpc (file: libnewlibc-lpc.a): -# EXTRA_LIBS = newlib-lpc -EXTRA_LIBS = - -# Path to Linker-Scripts -LINKERSCRIPTPATH = $(PIOSSTM32F4XX) - -# Optimization level, can be [0, 1, 2, 3, s]. -# 0 = turn off optimization. s = optimize for size. -# (Note: 3 is not always the best optimization level. See avr-libc FAQ.) - -ifeq ($(DEBUG),YES) -CFLAGS += -O0 -CFLAGS += -DGENERAL_COV -CFLAGS += -finstrument-functions -ffixed-r10 -else -CFLAGS += -Os -endif - - - -# common architecture-specific flags from the device-specific library makefile -CFLAGS += $(ARCHFLAGS) - -CFLAGS += -DSTACK_DIAGNOSTICS -CFLAGS += -DMIXERSTATUS_DIAGNOSTICS -CFLAGS += -DRATEDESIRED_DIAGNOSTICS -CFLAGS += -DWDG_STATS_DIAGNOSTICS -CFLAGS += -DDIAG_TASKS - -# configure CMSIS DSP Library -CDEFS += -DARM_MATH_CM4 -CDEFS += -DARM_MATH_MATRIX_CHECK -CDEFS += -DARM_MATH_ROUNDING -CDEFS += -D__FPU_PRESENT=1 -CDEFS += -DUNALIGNED_SUPPORT_DISABLE - -# This is not the best place for these. Really should abstract out -# to the board file or something -CFLAGS += -DSTM32F4XX -CFLAGS += -DMEM_SIZE=1024000000 - -# Output format. (can be ihex or binary or both) -# binary to create a load-image in raw-binary format i.e. for SAM-BA, -# ihex to create a load-image in Intel hex format -#LOADFORMAT = ihex -#LOADFORMAT = binary -LOADFORMAT = both - -# Debugging format. -DEBUGF = dwarf-2 - -# Place project-specific -D (define) and/or -# -U options for C here. -CDEFS += -DHSE_VALUE=$(OSCILLATOR_FREQ) -CDEFS += -DSYSCLK_FREQ=$(SYSCLK_FREQ) -CDEFS += -DUSE_STDPERIPH_DRIVER -CDEFS += -DUSE_$(BOARD) - -# Declare all non-optional modules as built-in to force inclusion -CDEFS += $(foreach MOD, $(notdir $(MODULES)), -DMODULE_$(MOD)_BUILTIN) - -# Place project-specific -D and/or -U options for -# Assembler with preprocessor here. -#ADEFS = -DUSE_IRQ_ASM_WRAPPER -ADEFS = -D__ASSEMBLY__ - -# Compiler flag to set the C Standard level. -# c89 - "ANSI" C -# gnu89 - c89 plus GCC extensions -# c99 - ISO C99 standard (not yet fully implemented) -# gnu99 - c99 plus GCC extensions -CSTANDARD = -std=gnu99 - -#----- - -# Compiler flags. - -# -g*: generate debugging information -# -O*: optimization level -# -f...: tuning, see GCC manual and avr-libc documentation -# -Wall...: warning level -# -Wa,...: tell GCC to pass this to the assembler. -# -adhlns...: create assembler listing -# -# Flags for C and C++ (arm-elf-gcc/arm-elf-g++) - -CFLAGS += -g$(DEBUGF) - -CFLAGS += -ffast-math - -CFLAGS += -mcpu=$(MCU) -CFLAGS += $(CDEFS) -CFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) -I. - -CFLAGS += -mapcs-frame -CFLAGS += -fomit-frame-pointer -CFLAGS += -ffunction-sections -fdata-sections -CFLAGS += -Wdouble-promotion - -CFLAGS += -Wall -CFLAGS += -Werror -CFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -# Compiler flags to generate dependency files: -CFLAGS += -MD -MP -MF $(OUTDIR)/dep/$(@F).d - -# flags only for C -#CONLYFLAGS += -Wnested-externs -CONLYFLAGS += $(CSTANDARD) - -# Assembler flags. -# -Wa,...: tell GCC to pass this to the assembler. -# -ahlns: create listing -ASFLAGS = $(ARCHFLAGS) -mthumb -I. -x assembler-with-cpp -ASFLAGS += $(ADEFS) -ASFLAGS += -Wa,-adhlns=$(addprefix $(OUTDIR)/, $(notdir $(addsuffix .lst, $(basename $<)))) -ASFLAGS += $(patsubst %,-I%,$(EXTRAINCDIRS)) - -MATH_LIB = -lm - -# Linker flags. -# -Wl,...: tell GCC to pass this to linker. -# -Map: create map file -# --cref: add cross reference to map file -LDFLAGS = -nostartfiles -Wl,-Map=$(OUTDIR)/$(TARGET).map,--cref,--gc-sections -LDFLAGS += $(patsubst %,-L%,$(EXTRA_LIBDIRS)) -LDFLAGS += -lc -LDFLAGS += $(patsubst %,-l%,$(EXTRA_LIBS)) -LDFLAGS += $(MATH_LIB) -LDFLAGS += -lc -lgcc -LDFLAGS += -Wl,--warn-common -LDFLAGS += -Wl,--fatal-warnings - -#Linker scripts -LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) - -include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/revolution/fw/UAVObjects.inc b/flight/targets/revolution/fw/UAVObjects.inc deleted file mode 100644 index 18e5dd85a2e..00000000000 --- a/flight/targets/revolution/fw/UAVObjects.inc +++ /dev/null @@ -1,121 +0,0 @@ -##### -# Project: OpenPilot -# -# Makefile for OpenPilot UAVObject code -# -# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. -# -# This program is free software; you can redistribute it and/or modify -# it under the terms of the GNU General Public License as published by -# the Free Software Foundation; either version 3 of the License, or -# (at your option) any later version. -# -# This program is distributed in the hope that it will be useful, but -# WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY -# or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License -# for more details. -# -# You should have received a copy of the GNU General Public License along -# with this program; if not, write to the Free Software Foundation, Inc., -# 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -##### - -# These are the UAVObjects supposed to be build as part of the OpenPilot target -# (all architectures) - -UAVOBJSRCFILENAMES = -UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver -UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += groundpathfollowersettings -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus -UAVOBJSRCFILENAMES += hwrevolution -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo -UAVOBJSRCFILENAMES += picocsettings -UAVOBJSRCFILENAMES += picocstatus - -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/revolution/fw/board.c b/flight/targets/revolution/fw/board.c deleted file mode 100644 index 29f81022743..00000000000 --- a/flight/targets/revolution/fw/board.c +++ /dev/null @@ -1,38 +0,0 @@ -/* - ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, - 2011,2012 Giovanni Di Sirio. - - This file is part of ChibiOS/RT. - - ChibiOS/RT is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - ChibiOS/RT is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . - */ - -#include "ch.h" -#include "hal.h" - -/** - * @brief Early initialization code. - * @details This initialization must be performed just after stack setup - * and before any other initialization. - */ -void __early_init(void) -{ -} - -/** - * @brief Prepare all driver configurations - */ -void boardInit(void) -{ -} diff --git a/flight/targets/revolution/fw/board.h b/flight/targets/revolution/fw/board.h deleted file mode 100644 index 9a037d4c919..00000000000 --- a/flight/targets/revolution/fw/board.h +++ /dev/null @@ -1,38 +0,0 @@ -/* - ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010, - 2011,2012 Giovanni Di Sirio. - - This file is part of ChibiOS/RT. - - ChibiOS/RT is free software; you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation; either version 3 of the License, or - (at your option) any later version. - - ChibiOS/RT is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with this program. If not, see . -*/ - -#ifndef _BOARD_H_ -#define _BOARD_H_ - -/* - * Setup board. - */ - -#if !defined(_FROM_ASM_) -#ifdef __cplusplus -extern "C" { -#endif - void boardInit(void); -#ifdef __cplusplus -} -#endif -#endif /* _FROM_ASM_ */ - -#endif /* _BOARD_H_ */ diff --git a/flight/targets/revolution/fw/pios_board.c b/flight/targets/revolution/fw/pios_board.c deleted file mode 100644 index e5f2a116e77..00000000000 --- a/flight/targets/revolution/fw/pios_board.c +++ /dev/null @@ -1,1156 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Revolution OpenPilot revolution support files - * @{ - * - * @file pios_board.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 - * @brief The board specific initialization routines - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ - /* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* Pull in the board-specific static HW definitions. - * Including .c files is a bit ugly but this allows all of - * the HW definitions to be const and static to limit their - * scope. - * - * NOTE: THIS IS THE ONLY PLACE THAT SHOULD EVER INCLUDE THIS FILE - */ -#include "board_hw_defs.c" - -#include -#include -#include -#include "hwrevolution.h" -#include "modulesettings.h" -#include "manualcontrolsettings.h" - -/** - * Sensor configurations - */ - -#if defined(PIOS_INCLUDE_HMC5883) -#include "pios_hmc5883_priv.h" -static const struct pios_exti_cfg pios_exti_hmc5883_cfg __exti_config = { - .vector = PIOS_HMC5883_IRQHandler, - .line = EXTI_Line5, - .pin = { - .gpio = GPIOB, - .init = { - .GPIO_Pin = GPIO_Pin_5, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line5, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_hmc5883_cfg pios_hmc5883_cfg = { - .exti_cfg = &pios_exti_hmc5883_cfg, - .M_ODR = PIOS_HMC5883_ODR_75, - .Meas_Conf = PIOS_HMC5883_MEASCONF_NORMAL, - .Gain = PIOS_HMC5883_GAIN_1_9, - .Mode = PIOS_HMC5883_MODE_CONTINUOUS, - .Default_Orientation = PIOS_HMC5883_TOP_270DEG, -}; -#endif /* PIOS_INCLUDE_HMC5883 */ - -/** - * Configuration for the MS5611 chip - */ -#if defined(PIOS_INCLUDE_MS5611) -#include "pios_ms5611_priv.h" -static const struct pios_ms5611_cfg pios_ms5611_cfg = { - .oversampling = MS5611_OSR_1024, - .temperature_interleaving = 1, -}; -#endif /* PIOS_INCLUDE_MS5611 */ - -/** - * Configuration for the BMA180 chip - */ -#if defined(PIOS_INCLUDE_BMA180) -#include "pios_bma180.h" -static const struct pios_exti_cfg pios_exti_bma180_cfg __exti_config = { - .vector = PIOS_BMA180_IRQHandler, - .line = EXTI_Line4, - .pin = { - .gpio = GPIOC, - .init = { - .GPIO_Pin = GPIO_Pin_4, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI4_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_LOW, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line4, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; -static const struct pios_bma180_cfg pios_bma180_cfg = { - .exti_cfg = &pios_exti_bma180_cfg, - .bandwidth = BMA_BW_600HZ, - .range = BMA_RANGE_8G, -}; -#endif /* PIOS_INCLUDE_BMA180 */ - -/** - * Configuration for the MPU6000 chip - */ -#if defined(PIOS_INCLUDE_MPU6000) -#include "pios_mpu6000.h" -static const struct pios_exti_cfg pios_exti_mpu6000_cfg __exti_config = { - .vector = PIOS_MPU6000_IRQHandler, - .line = EXTI_Line8, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line8, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_mpu60x0_cfg pios_mpu6000_cfg = { - .exti_cfg = &pios_exti_mpu6000_cfg, - .default_samplerate = 666, - .interrupt_cfg = PIOS_MPU60X0_INT_CLR_ANYRD, - .interrupt_en = PIOS_MPU60X0_INTEN_DATA_RDY, - .User_ctl = PIOS_MPU60X0_USERCTL_DIS_I2C, - .Pwr_mgmt_clk = PIOS_MPU60X0_PWRMGMT_PLL_Z_CLK, - .default_filter = PIOS_MPU60X0_LOWPASS_256_HZ, - .orientation = PIOS_MPU60X0_TOP_0DEG -}; -#endif /* PIOS_INCLUDE_MPU6000 */ - -/** - * Configuration for L3GD20 chip - */ -#if defined(PIOS_INCLUDE_L3GD20) -#include "pios_l3gd20.h" -static const struct pios_exti_cfg pios_exti_l3gd20_cfg __exti_config = { - .vector = PIOS_L3GD20_IRQHandler, - .line = EXTI_Line8, - .pin = { - .gpio = GPIOD, - .init = { - .GPIO_Pin = GPIO_Pin_8, - .GPIO_Speed = GPIO_Speed_100MHz, - .GPIO_Mode = GPIO_Mode_IN, - .GPIO_OType = GPIO_OType_OD, - .GPIO_PuPd = GPIO_PuPd_NOPULL, - }, - }, - .irq = { - .init = { - .NVIC_IRQChannel = EXTI9_5_IRQn, - .NVIC_IRQChannelPreemptionPriority = PIOS_IRQ_PRIO_HIGH, - .NVIC_IRQChannelSubPriority = 0, - .NVIC_IRQChannelCmd = ENABLE, - }, - }, - .exti = { - .init = { - .EXTI_Line = EXTI_Line8, // matches above GPIO pin - .EXTI_Mode = EXTI_Mode_Interrupt, - .EXTI_Trigger = EXTI_Trigger_Rising, - .EXTI_LineCmd = ENABLE, - }, - }, -}; - -static const struct pios_l3gd20_cfg pios_l3gd20_cfg = { - .exti_cfg = &pios_exti_l3gd20_cfg, - .range = PIOS_L3GD20_SCALE_500_DEG, -}; -#endif /* PIOS_INCLUDE_L3GD20 */ - -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS - * NOTE: No slot in this map for NONE. - */ -uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 - -#define PIOS_COM_GPS_RX_BUF_LEN 32 -#define PIOS_COM_GPS_TX_BUF_LEN 16 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 - -#define PIOS_COM_HOTT_RX_BUF_LEN 16 -#define PIOS_COM_HOTT_TX_BUF_LEN 16 - -#define PIOS_COM_PICOC_RX_BUF_LEN 128 -#define PIOS_COM_PICOC_TX_BUF_LEN 128 - -#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 -#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 - -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 -uintptr_t pios_com_debug_id; -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -uintptr_t pios_com_gps_id; -uintptr_t pios_com_telem_usb_id; -uintptr_t pios_com_telem_rf_id; -uintptr_t pios_com_vcp_id; -uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; -uintptr_t pios_com_mavlink_id; -uintptr_t pios_com_hott_id; -uintptr_t pios_com_picoc_id; -uintptr_t pios_internal_adc_id = 0; -uintptr_t pios_uavo_settings_fs_id; -uintptr_t pios_waypoints_settings_fs_id; -uintptr_t pios_com_frsky_sport_id; - -/* - * Setup a com port based on the passed cfg, driver and buffer sizes. rx or tx size of 0 disables rx or tx - */ -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) -static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, - const struct pios_com_driver *com_driver, uintptr_t *pios_com_id) -{ - uintptr_t pios_usart_id; - if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer; - if (rx_buf_len > 0) { - rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); - PIOS_Assert(rx_buffer); - } else { - rx_buffer = NULL; - } - - uint8_t * tx_buffer; - if (tx_buf_len > 0) { - tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); - PIOS_Assert(tx_buffer); - } else { - tx_buffer = NULL; - } - - if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, - rx_buffer, rx_buf_len, - tx_buffer, tx_buf_len)) { - PIOS_Assert(0); - } -} -#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ - -#ifdef PIOS_INCLUDE_DSM -static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) -{ - uintptr_t pios_usart_dsm_id; - if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_rcvr_id; - if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; -} -#endif - -#ifdef PIOS_INCLUDE_HSUM -static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hsum_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_hsum_proto *proto, - ManualControlSettingsChannelGroupsOptions channelgroup) -{ - uintptr_t pios_usart_hsum_id; - if (PIOS_USART_Init(&pios_usart_hsum_id, pios_usart_hsum_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_id; - if (PIOS_HSUM_Init(&pios_hsum_id, pios_usart_com_driver, - pios_usart_hsum_id, *proto)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_rcvr_id; - if (PIOS_RCVR_Init(&pios_hsum_rcvr_id, &pios_hsum_rcvr_driver, pios_hsum_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_hsum_rcvr_id; -} -#endif - -/** - * PIOS_Board_Init() - * initializes all the core subsystems on this specific hardware - * called from System/openpilot.c - */ - -#include - -void PIOS_Board_Init(void) { - - const struct pios_board_info * bdinfo = &pios_board_info_blob; - - /* Delay system */ - PIOS_DELAY_Init(); - - PIOS_LED_Init(&pios_led_cfg); - - /* Set up the SPI interface to the accelerometer*/ - if (PIOS_SPI_Init(&pios_spi_accel_id, &pios_spi_accel_cfg)) { - PIOS_DEBUG_Assert(0); - } - - /* Set up the SPI interface to the gyro */ - if (PIOS_SPI_Init(&pios_spi_gyro_id, &pios_spi_gyro_cfg)) { - PIOS_DEBUG_Assert(0); - } - -#if !defined(PIOS_FLASH_ON_ACCEL) - /* Set up the SPI interface to the flash */ - if (PIOS_SPI_Init(&pios_spi_flash_id, &pios_spi_flash_cfg)) { - PIOS_DEBUG_Assert(0); - } - /* Inititialize all flash drivers */ - PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_flash_id, 0, &flash_m25p_cfg); -#else - /* Inititialize all flash drivers */ - PIOS_Flash_Jedec_Init(&pios_external_flash_id, pios_spi_accel_id, 1, &flash_m25p_cfg); -#endif - - PIOS_Flash_Internal_Init(&pios_internal_flash_id, &flash_internal_cfg); - - /* Register the partition table */ - const struct pios_flash_partition * flash_partition_table; - uint32_t num_partitions; - flash_partition_table = PIOS_BOARD_HW_DEFS_GetPartitionTable(bdinfo->board_rev, &num_partitions); - PIOS_FLASH_register_partition_table(flash_partition_table, num_partitions); - - /* Mount all filesystems */ - PIOS_FLASHFS_Logfs_Init(&pios_uavo_settings_fs_id, &flashfs_settings_cfg, FLASH_PARTITION_LABEL_SETTINGS); - PIOS_FLASHFS_Logfs_Init(&pios_waypoints_settings_fs_id, &flashfs_waypoints_cfg, FLASH_PARTITION_LABEL_WAYPOINTS); - - /* Initialize the task monitor library */ - TaskMonitorInitialize(); - - /* Initialize UAVObject libraries */ - EventDispatcherInitialize(); - UAVObjInitialize(); - - /* Initialize the alarms library */ - AlarmsInitialize(); - - HwRevolutionInitialize(); - ModuleSettingsInitialize(); - -#if defined(PIOS_INCLUDE_RTC) - PIOS_RTC_Init(&pios_rtc_main_cfg); -#endif - - /* Set up pulse timers */ - PIOS_TIM_InitClock(&tim_1_cfg); - PIOS_TIM_InitClock(&tim_2_cfg); - PIOS_TIM_InitClock(&tim_3_cfg); - PIOS_TIM_InitClock(&tim_4_cfg); - PIOS_TIM_InitClock(&tim_5_cfg); - PIOS_TIM_InitClock(&tim_9_cfg); - PIOS_TIM_InitClock(&tim_10_cfg); - PIOS_TIM_InitClock(&tim_11_cfg); - - /* IAP System Setup */ - PIOS_IAP_Init(); - uint16_t boot_count = PIOS_IAP_ReadBootCount(); - if (boot_count < 3) { - PIOS_IAP_WriteBootCount(++boot_count); - AlarmsClear(SYSTEMALARMS_ALARM_BOOTFAULT); - } else { - /* Too many failed boot attempts, force hw config to defaults */ - HwRevolutionSetDefaults(HwRevolutionHandle(), 0); - ModuleSettingsSetDefaults(ModuleSettingsHandle(),0); - AlarmsSet(SYSTEMALARMS_ALARM_BOOTFAULT, SYSTEMALARMS_ALARM_CRITICAL); - } - - - //PIOS_IAP_Init(); - -#if defined(PIOS_INCLUDE_USB) - /* Initialize board specific USB data */ - PIOS_USB_BOARD_DATA_Init(); - - /* Flags to determine if various USB interfaces are advertised */ - bool usb_hid_present = false; - bool usb_cdc_present = false; - -#if defined(PIOS_INCLUDE_USB_CDC) - if (PIOS_USB_DESC_HID_CDC_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; - usb_cdc_present = true; -#else - if (PIOS_USB_DESC_HID_ONLY_Init()) { - PIOS_Assert(0); - } - usb_hid_present = true; -#endif - - uintptr_t pios_usb_id; - PIOS_USB_Init(&pios_usb_id, &pios_usb_main_cfg); - -#if defined(PIOS_INCLUDE_USB_CDC) - - uint8_t hw_usb_vcpport; - /* Configure the USB VCP port */ - HwRevolutionUSB_VCPPortGet(&hw_usb_vcpport); - - if (!usb_cdc_present) { - /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ - hw_usb_vcpport = HWREVOLUTION_USB_VCPPORT_DISABLED; - } - - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_vcpport) { - case HWREVOLUTION_USB_VCPPORT_DISABLED: - break; - case HWREVOLUTION_USB_VCPPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOLUTION_USB_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOLUTION_USB_VCPPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - NULL, 0, - tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOLUTION_USB_VCPPORT_PICOC: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, - tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } -#endif /* PIOS_INCLUDE_USB_CDC */ - -#if defined(PIOS_INCLUDE_USB_HID) - /* Configure the usb HID port */ - uint8_t hw_usb_hidport; - HwRevolutionUSB_HIDPortGet(&hw_usb_hidport); - - if (!usb_hid_present) { - /* Force HID port function to disabled if we haven't advertised HID in our USB descriptor */ - hw_usb_hidport = HWREVOLUTION_USB_HIDPORT_DISABLED; - } - - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_hidport) { - case HWREVOLUTION_USB_HIDPORT_DISABLED: - break; - case HWREVOLUTION_USB_HIDPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } - -#endif /* PIOS_INCLUDE_USB_HID */ - - if (usb_hid_present || usb_cdc_present) { - PIOS_USBHOOK_Activate(); - } -#endif /* PIOS_INCLUDE_USB */ - - /* Configure IO ports */ - uint8_t hw_DSMxBind; - HwRevolutionDSMxBindGet(&hw_DSMxBind); - - /* Configure Telemetry port */ - uint8_t hw_telemetryport; - HwRevolutionTelemetryPortGet(&hw_telemetryport); - - switch (hw_telemetryport){ - case HWREVOLUTION_TELEMETRYPORT_DISABLED: - break; - case HWREVOLUTION_TELEMETRYPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWREVOLUTION_TELEMETRYPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - PIOS_Board_configure_com(&pios_usart_telem_cfg, 0, PIOS_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOLUTION_TELEMETRYPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_telem_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - - } /* hw_telemetryport */ - - /* Configure GPS port */ - uint8_t hw_gpsport; - HwRevolutionGPSPortGet(&hw_gpsport); - switch (hw_gpsport){ - case HWREVOLUTION_GPSPORT_DISABLED: - break; - - case HWREVOLUTION_GPSPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - - case HWREVOLUTION_GPSPORT_GPS: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_RX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - - case HWREVOLUTION_GPSPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - PIOS_Board_configure_com(&pios_usart_gps_cfg, 0, PIOS_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - - case HWREVOLUTION_GPSPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_gps_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - }/* hw_gpsport */ - - /* Configure AUXPort */ - uint8_t hw_auxport; - HwRevolutionAuxPortGet(&hw_auxport); - - switch (hw_auxport) { - case HWREVOLUTION_AUXPORT_DISABLED: - break; - - case HWREVOLUTION_AUXPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - - case HWREVOLUTION_AUXPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_aux_cfg, &pios_dsm_aux_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - - case HWREVOLUTION_AUXPORT_HOTTSUMD: - case HWREVOLUTION_AUXPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_auxport) { - case HWREVOLUTION_AUXPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWREVOLUTION_AUXPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_aux_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - - case HWREVOLUTION_AUXPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_aux_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_AUXPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_AUXPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - - case HWREVOLUTION_AUXPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - - case HWREVOLUTION_AUXPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - PIOS_Board_configure_com(&pios_usart_aux_cfg, 0, PIOS_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOLUTION_AUXPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWREVOLUTION_AUXPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_aux_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ - break; - } /* hw_auxport */ - /* Configure AUXSbusPort */ - //TODO: ensure that the serial invertion pin is setted correctly - uint8_t hw_auxsbusport; - HwRevolutionAuxSBusPortGet(&hw_auxsbusport); - - switch (hw_auxsbusport) { - case HWREVOLUTION_AUXSBUSPORT_DISABLED: - break; - case HWREVOLUTION_AUXSBUSPORT_SBUS: -#ifdef PIOS_INCLUDE_SBUS - { - uintptr_t pios_usart_sbus_id; - if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_auxsbus_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_id; - if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; - - } -#endif /* PIOS_INCLUDE_SBUS */ - break; - - case HWREVOLUTION_AUXSBUSPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_auxsbus_cfg, &pios_dsm_auxsbus_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - - case HWREVOLUTION_AUXSBUSPORT_HOTTSUMD: - case HWREVOLUTION_AUXSBUSPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_auxsbusport) { - case HWREVOLUTION_AUXSBUSPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWREVOLUTION_AUXSBUSPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_auxsbus_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - - case HWREVOLUTION_AUXSBUSPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_AUXSBUSPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_AUXSBUSPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, 0, PIOS_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOLUTION_AUXSBUSPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - - case HWREVOLUTION_AUXSBUSPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - - case HWREVOLUTION_AUXSBUSPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWREVOLUTION_AUXSBUSPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_auxsbus_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ - break; - } /* hw_auxport */ - - /* Configure FlexiPort */ - - uint8_t hw_flexiport; - HwRevolutionFlexiPortGet(&hw_flexiport); - - switch (hw_flexiport) { - case HWREVOLUTION_FLEXIPORT_DISABLED: - break; - case HWREVOLUTION_FLEXIPORT_I2C: -#if defined(PIOS_INCLUDE_I2C) - { - if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_I2C */ - break; - - case HWREVOLUTION_FLEXIPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - - case HWREVOLUTION_FLEXIPORT_HOTTSUMD: - case HWREVOLUTION_FLEXIPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_flexiport) { - case HWREVOLUTION_FLEXIPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWREVOLUTION_FLEXIPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_flexi_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - - case HWREVOLUTION_FLEXIPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_FLEXIPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) && defined(PIOS_INCLUDE_MAVLINK) && defined(PIOS_INCLUDE_GPS) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - - case HWREVOLUTION_FLEXIPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_aux_id); -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOLUTION_FLEXIPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWREVOLUTION_FLEXIPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - - case HWREVOLUTION_FLEXIPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWREVOLUTION_FLEXIPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKYSPORTTELEMETRY */ - break; - } /* hw_flexiport */ - - - /* Configure the receiver port*/ - uint8_t hw_rcvrport; - HwRevolutionRcvrPortGet(&hw_rcvrport); - // - switch (hw_rcvrport){ - case HWREVOLUTION_RCVRPORT_DISABLED: - break; - case HWREVOLUTION_RCVRPORT_PWM: -#if defined(PIOS_INCLUDE_PWM) - { - /* Set up the receiver port. Later this should be optional */ - uintptr_t pios_pwm_id; - PIOS_PWM_Init(&pios_pwm_id, &pios_pwm_cfg); - - uintptr_t pios_pwm_rcvr_id; - if (PIOS_RCVR_Init(&pios_pwm_rcvr_id, &pios_pwm_rcvr_driver, pios_pwm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PWM] = pios_pwm_rcvr_id; - } -#endif /* PIOS_INCLUDE_PWM */ - break; - case HWREVOLUTION_RCVRPORT_PPM: - case HWREVOLUTION_RCVRPORT_PPMOUTPUTS: -#if defined(PIOS_INCLUDE_PPM) - { - uintptr_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); - - uintptr_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; - } -#endif /* PIOS_INCLUDE_PPM */ - case HWREVOLUTION_RCVRPORT_OUTPUTS: - - break; - } - -#if defined(PIOS_OVERO_SPI) - /* Set up the SPI based PIOS_COM interface to the overo */ - { - bool overo_enabled = false; -#ifdef MODULE_OveroSync_BUILTIN - overo_enabled = true; -#else - uint8_t module_state[MODULESETTINGS_ADMINSTATE_NUMELEM]; - ModuleSettingsAdminStateGet(module_state); - if (module_state[MODULESETTINGS_ADMINSTATE_OVEROSYNC] == MODULESETTINGS_ADMINSTATE_ENABLED) { - overo_enabled = true; - } else { - overo_enabled = false; - } -#endif - if (overo_enabled) { - if (PIOS_OVERO_Init(&pios_overo_id, &pios_overo_cfg)) { - PIOS_DEBUG_Assert(0); - } - const uint32_t PACKET_SIZE = 1024; - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PACKET_SIZE); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PACKET_SIZE); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_overo_id, &pios_overo_com_driver, pios_overo_id, - rx_buffer, PACKET_SIZE, - tx_buffer, PACKET_SIZE)) { - PIOS_Assert(0); - } - } - } - -#endif - -#if defined(PIOS_INCLUDE_GCSRCVR) - GCSReceiverInitialize(); - uintptr_t pios_gcsrcvr_id; - PIOS_GCSRCVR_Init(&pios_gcsrcvr_id); - uintptr_t pios_gcsrcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_gcsrcvr_rcvr_id, &pios_gcsrcvr_rcvr_driver, pios_gcsrcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_GCS] = pios_gcsrcvr_rcvr_id; -#endif /* PIOS_INCLUDE_GCSRCVR */ - -#ifndef PIOS_DEBUG_ENABLE_DEBUG_PINS - switch (hw_rcvrport) { - case HWREVOLUTION_RCVRPORT_DISABLED: - case HWREVOLUTION_RCVRPORT_PWM: - case HWREVOLUTION_RCVRPORT_PPM: - /* Set up the servo outputs */ - PIOS_Servo_Init(&pios_servo_cfg); - break; - case HWREVOLUTION_RCVRPORT_PPMOUTPUTS: - case HWREVOLUTION_RCVRPORT_OUTPUTS: - //PIOS_Servo_Init(&pios_servo_rcvr_cfg); - //TODO: Prepare the configurations on board_hw_defs and handle here: - PIOS_Servo_Init(&pios_servo_cfg); - break; - } -#else - PIOS_DEBUG_Init(&pios_tim_servo_all_channels, NELEMENTS(pios_tim_servo_all_channels)); -#endif - - if (PIOS_I2C_Init(&pios_i2c_mag_adapter_id, &pios_i2c_mag_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - - if (PIOS_I2C_Init(&pios_i2c_pressure_adapter_id, &pios_i2c_pressure_adapter_cfg)) { - PIOS_DEBUG_Assert(0); - } - - PIOS_DELAY_WaitmS(50); - - PIOS_SENSORS_Init(); - -#if defined(PIOS_INCLUDE_ADC) - uint32_t internal_adc_id; - if(PIOS_INTERNAL_ADC_Init(&internal_adc_id, &pios_adc_cfg) < 0) - PIOS_Assert(0); - PIOS_ADC_Init(&pios_internal_adc_id, &pios_internal_adc_driver, internal_adc_id); -#endif - -#if defined(PIOS_INCLUDE_HMC5883) - PIOS_HMC5883_Init(PIOS_I2C_MAIN_ADAPTER, &pios_hmc5883_cfg); -#endif - -#if defined(PIOS_INCLUDE_MS5611) - PIOS_MS5611_Init(&pios_ms5611_cfg, pios_i2c_pressure_adapter_id); -#endif - - switch(bdinfo->board_rev) { - case 0x01: -#if defined(PIOS_INCLUDE_L3GD20) - PIOS_L3GD20_Init(pios_spi_gyro_id, 0, &pios_l3gd20_cfg); - PIOS_Assert(PIOS_L3GD20_Test() == 0); -#endif -#if defined(PIOS_INCLUDE_BMA180) - PIOS_BMA180_Init(pios_spi_accel_id, 0, &pios_bma180_cfg); - PIOS_Assert(PIOS_BMA180_Test() == 0); -#endif - break; - case 0x02: -#if defined(PIOS_INCLUDE_MPU6000) - PIOS_MPU6000_Init(pios_spi_gyro_id,0, &pios_mpu6000_cfg); - - // To be safe map from UAVO enum to driver enum - uint8_t hw_gyro_range; - HwRevolutionGyroRangeGet(&hw_gyro_range); - switch(hw_gyro_range) { - case HWREVOLUTION_GYRORANGE_250: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_250_DEG); - break; - case HWREVOLUTION_GYRORANGE_500: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_500_DEG); - break; - case HWREVOLUTION_GYRORANGE_1000: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_1000_DEG); - break; - case HWREVOLUTION_GYRORANGE_2000: - PIOS_MPU6000_SetGyroRange(PIOS_MPU60X0_SCALE_2000_DEG); - break; - } - - uint8_t hw_accel_range; - HwRevolutionAccelRangeGet(&hw_accel_range); - switch(hw_accel_range) { - case HWREVOLUTION_ACCELRANGE_2G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_2G); - break; - case HWREVOLUTION_ACCELRANGE_4G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_4G); - break; - case HWREVOLUTION_ACCELRANGE_8G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_8G); - break; - case HWREVOLUTION_ACCELRANGE_16G: - PIOS_MPU6000_SetAccelRange(PIOS_MPU60X0_ACCEL_16G); - break; - } - - // the filter has to be set before rate else divisor calculation will fail - uint8_t hw_mpu6000_dlpf; - HwRevolutionMPU6000DLPFGet(&hw_mpu6000_dlpf); - enum pios_mpu60x0_filter mpu6000_dlpf = \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_256) ? PIOS_MPU60X0_LOWPASS_256_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_188) ? PIOS_MPU60X0_LOWPASS_188_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_98) ? PIOS_MPU60X0_LOWPASS_98_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_42) ? PIOS_MPU60X0_LOWPASS_42_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_20) ? PIOS_MPU60X0_LOWPASS_20_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_10) ? PIOS_MPU60X0_LOWPASS_10_HZ : \ - (hw_mpu6000_dlpf == HWREVOLUTION_MPU6000DLPF_5) ? PIOS_MPU60X0_LOWPASS_5_HZ : \ - pios_mpu6000_cfg.default_filter; - PIOS_MPU6000_SetLPF(mpu6000_dlpf); - - uint8_t hw_mpu6000_samplerate; - HwRevolutionMPU6000RateGet(&hw_mpu6000_samplerate); - uint16_t mpu6000_samplerate = \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_200) ? 200 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_333) ? 333 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_500) ? 500 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_666) ? 666 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_1000) ? 1000 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_2000) ? 2000 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_4000) ? 4000 : \ - (hw_mpu6000_samplerate == HWREVOLUTION_MPU6000RATE_8000) ? 8000 : \ - pios_mpu6000_cfg.default_samplerate; - PIOS_MPU6000_SetSampleRate(mpu6000_samplerate); -#endif - break; - default: - PIOS_DEBUG_Assert(0); - } - -} - -/** - * @} - * @} - */ - diff --git a/flight/targets/revolution/fw/pios_config.h b/flight/targets/revolution/fw/pios_config.h deleted file mode 100644 index 4bd17638981..00000000000 --- a/flight/targets/revolution/fw/pios_config.h +++ /dev/null @@ -1,139 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Revolution OpenPilot Revolution support files - * @{ - * - * @file pios_config.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific options that modify PiOS capabilities - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#ifndef PIOS_CONFIG_H -#define PIOS_CONFIG_H - -/* Major features */ -#define PIOS_INCLUDE_FREERTOS -#define PIOS_INCLUDE_BL_HELPER - -/* Enable/Disable PiOS Modules */ -#define PIOS_INCLUDE_ADC -#define PIOS_INCLUDE_DELAY -#define PIOS_INCLUDE_I2C -#define PIOS_INCLUDE_IRQ -#define PIOS_INCLUDE_LED -#define PIOS_INCLUDE_IAP -#define PIOS_INCLUDE_SERVO -#define PIOS_INCLUDE_SPI -#define PIOS_INCLUDE_SYS -#define PIOS_INCLUDE_USART -#define PIOS_INCLUDE_USB -#define PIOS_INCLUDE_USB_HID -#define PIOS_INCLUDE_USB_CDC -//#define PIOS_INCLUDE_GPIO -#define PIOS_INCLUDE_EXTI -#define PIOS_INCLUDE_RTC -#define PIOS_INCLUDE_WDG -#define PIOS_INCLUDE_FASTHEAP - -/* Select the sensors to include */ -#define PIOS_INCLUDE_BMA180 -#define PIOS_INCLUDE_HMC5883 -#define PIOS_INCLUDE_MPU6000 -#define PIOS_MPU6000_ACCEL -#define PIOS_INCLUDE_L3GD20 -#define PIOS_INCLUDE_MS5611 -#define PIOS_INCLUDE_ETASV3 -#define PIOS_INCLUDE_MPXV5004 -#define PIOS_INCLUDE_MPXV7002 -//#define PIOS_INCLUDE_HCSR04 -#define PIOS_FLASH_ON_ACCEL /* true for second revo */ -#define FLASH_FREERTOS -/* Com systems to include */ -#define PIOS_INCLUDE_COM -#define PIOS_INCLUDE_COM_TELEM -#define PIOS_INCLUDE_COM_AUX -#define PIOS_INCLUDE_COM_AUXSBUS -#define PIOS_INCLUDE_COM_FLEXI -#define PIOS_INCLUDE_MAVLINK -#define PIOS_INCLUDE_HOTT -#define PIOS_INCLUDE_SESSION_MANAGEMENT -#define PIOS_INCLUDE_PICOC -#define PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY - -#define PIOS_INCLUDE_GPS -#define PIOS_INCLUDE_GPS_NMEA_PARSER -#define PIOS_INCLUDE_GPS_UBX_PARSER - -#define PIOS_OVERO_SPI -/* Supported receiver interfaces */ -#define PIOS_INCLUDE_RCVR -#define PIOS_INCLUDE_DSM -#define PIOS_INCLUDE_HSUM -//#define PIOS_INCLUDE_SBUS -#define PIOS_INCLUDE_PPM -#define PIOS_INCLUDE_PWM -#define PIOS_INCLUDE_GCSRCVR - -#define PIOS_INCLUDE_FLASH -#define PIOS_INCLUDE_FLASH_JEDEC -#define PIOS_INCLUDE_FLASH_INTERNAL -#define PIOS_INCLUDE_LOGFS_SETTINGS - -/* Flags that alter behaviors - mostly to lower resources for CC */ -#define PIOS_INCLUDE_INITCALL /* Include init call structures */ -#define PIOS_TELEM_PRIORITY_QUEUE /* Enable a priority queue in telemetry */ - -#define CAMERASTAB_POI_MODE - -/* Alarm Thresholds */ -#define HEAP_LIMIT_WARNING 1000 -#define HEAP_LIMIT_CRITICAL 500 -#define IRQSTACK_LIMIT_WARNING 150 -#define IRQSTACK_LIMIT_CRITICAL 80 -#define CPULOAD_LIMIT_WARNING 80 -#define CPULOAD_LIMIT_CRITICAL 95 - -/* - * This has been calibrated 2013/03/11 using next @ 6d21c7a590619ebbc074e60cab5e134e65c9d32b. - * Calibration has been done by disabling the init task, breaking into debugger after - * approximately after 60 seconds, then doing the following math: - * - * IDLE_COUNTS_PER_SEC_AT_NO_LOAD = (uint32_t)((double)idleCounter / xTickCount * 1000 + 0.5) - * - * This has to be redone every time the toolchain, toolchain flags or FreeRTOS - * configuration like number of task priorities or similar changes. - * A change in the cpu load calculation or the idle task handler will invalidate this as well. - */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) - -#define REVOLUTION - -// Enable POI tracking mode for camera stabilization -#define CAMERASTAB_POI_MODE - -#endif /* PIOS_CONFIG_H */ -/** - * @} - * @} - */ diff --git a/flight/targets/revolution/fw/pios_usb_board_data.c b/flight/targets/revolution/fw/pios_usb_board_data.c deleted file mode 100644 index f317940c86b..00000000000 --- a/flight/targets/revolution/fw/pios_usb_board_data.c +++ /dev/null @@ -1,98 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Revolution OpenPilot Revolution support files - * @{ - * - * @file pios_usb_board_data.c - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Board specific USB specifications - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pios_usb_board_data.h" /* struct usb_*, USB_* */ -#include "pios_sys.h" /* PIOS_SYS_SerialNumberGet */ -#include "pios_usbhook.h" /* PIOS_USBHOOK_* */ -#include "pios_usb_util.h" /* PIOS_USB_UTIL_AsciiToUtf8 */ - -static const uint8_t usb_product_id[22] = { - sizeof(usb_product_id), - USB_DESC_TYPE_STRING, - 'R', 0, - 'e', 0, - 'v', 0, - 'o', 0, - 'l', 0, - 'u', 0, - 't', 0, - 'i', 0, - 'o', 0, - 'n', 0, -}; - -static uint8_t usb_serial_number[2 + PIOS_SYS_SERIAL_NUM_ASCII_LEN*2 + (sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1)*2] = { - sizeof(usb_serial_number), - USB_DESC_TYPE_STRING, -}; - -static const struct usb_string_langid usb_lang_id = { - .bLength = sizeof(usb_lang_id), - .bDescriptorType = USB_DESC_TYPE_STRING, - .bLangID = htousbs(USB_LANGID_ENGLISH_US), -}; - -static const uint8_t usb_vendor_id[28] = { - sizeof(usb_vendor_id), - USB_DESC_TYPE_STRING, - 'o', 0, - 'p', 0, - 'e', 0, - 'n', 0, - 'p', 0, - 'i', 0, - 'l', 0, - 'o', 0, - 't', 0, - '.', 0, - 'o', 0, - 'r', 0, - 'g', 0 -}; - -int32_t PIOS_USB_BOARD_DATA_Init(void) -{ - /* Load device serial number into serial number string */ - uint8_t sn[PIOS_SYS_SERIAL_NUM_ASCII_LEN + 1]; - PIOS_SYS_SerialNumberGet((char *)sn); - - /* Concatenate the device serial number and the appropriate suffix ("+BL" or "+FW") into the USB serial number */ - uint8_t * utf8 = &(usb_serial_number[2]); - utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, sn, PIOS_SYS_SERIAL_NUM_ASCII_LEN); - utf8 = PIOS_USB_UTIL_AsciiToUtf8(utf8, (uint8_t *)PIOS_USB_BOARD_SN_SUFFIX, sizeof(PIOS_USB_BOARD_SN_SUFFIX)-1); - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_PRODUCT, (uint8_t *)&usb_product_id, sizeof(usb_product_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_SERIAL, (uint8_t *)&usb_serial_number, sizeof(usb_serial_number)); - - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_LANG, (uint8_t *)&usb_lang_id, sizeof(usb_lang_id)); - PIOS_USBHOOK_RegisterString(USB_STRING_DESC_VENDOR, (uint8_t *)&usb_vendor_id, sizeof(usb_vendor_id)); - - return 0; -} diff --git a/flight/targets/revolution/fw/pios_usb_board_data.h b/flight/targets/revolution/fw/pios_usb_board_data.h deleted file mode 100644 index 3ba45f70213..00000000000 --- a/flight/targets/revolution/fw/pios_usb_board_data.h +++ /dev/null @@ -1,47 +0,0 @@ -/** - ****************************************************************************** - * @addtogroup TauLabsTargets Tau Labs Targets - * @{ - * @addtogroup Revolution OpenPilot Revolution support files - * @{ - * - * @file pios_usb_board_data.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2013 - * @brief Defines for board specific usb information - * @see The GNU Public License (GPL) Version 3 - * - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef PIOS_USB_BOARD_DATA_H -#define PIOS_USB_BOARD_DATA_H - -#define PIOS_USB_BOARD_CDC_DATA_LENGTH 64 -#define PIOS_USB_BOARD_CDC_MGMT_LENGTH 32 -#define PIOS_USB_BOARD_HID_DATA_LENGTH 64 - -#define PIOS_USB_BOARD_EP_NUM 4 - -#include "pios_usb_defs.h" /* USB_* macros */ - -#define PIOS_USB_BOARD_VENDOR_ID USB_VENDOR_ID_OPENPILOT -#define PIOS_USB_BOARD_PRODUCT_ID USB_PRODUCT_ID_REVOLUTION -#define PIOS_USB_BOARD_DEVICE_VER USB_OP_DEVICE_VER(0, USB_OP_BOARD_MODE_FW) -#define PIOS_USB_BOARD_SN_SUFFIX "+FW" - -#endif /* PIOS_USB_BOARD_DATA_H */ diff --git a/flight/targets/revolution/gdb/bl_revolution b/flight/targets/revolution/gdb/bl_revolution deleted file mode 100644 index 362e273dcbc..00000000000 --- a/flight/targets/revolution/gdb/bl_revolution +++ /dev/null @@ -1,4 +0,0 @@ -define connect - target remote localhost:3333 - file ./build/bl_revolution/bl_revolution.elf -end diff --git a/flight/targets/revolution/gdb/revolution b/flight/targets/revolution/gdb/revolution deleted file mode 100644 index 058f43809f4..00000000000 --- a/flight/targets/revolution/gdb/revolution +++ /dev/null @@ -1,4 +0,0 @@ -define connect - target remote localhost:3333 - file ./build/fw_revolution/fw_revolution.elf -end diff --git a/flight/targets/revomini/board-info/board-info.mk b/flight/targets/revomini/board-info/board-info.mk index 17c859fe5ac..1a1ff9fd88c 100644 --- a/flight/targets/revomini/board-info/board-info.mk +++ b/flight/targets/revomini/board-info/board-info.mk @@ -1,7 +1,9 @@ BOARD_TYPE := 0x09 BOARD_REVISION := 0x03 -# Previous version was 0x081, 0x082 introduces partition extensions and forced boot from bkp registers -BOOTLOADER_VERSION := 0x83 +# Previous version was 0x081, 0x082 introduces partition extensions +# and forced boot from bkp registers; 0x83 changed bootdelay to 2ms for dsm bind +# 0x84 increases firmware to 384k +BOOTLOADER_VERSION := 0x84 HW_TYPE := 0x00 MCU := cortex-m4 @@ -20,7 +22,7 @@ BL_BANK_SIZE := 0x00008000 # Should include BD_INFO region (32kb) # Leave the remaining 16KB and 64KB sectors for other uses FW_BANK_BASE := 0x08020000 # Start of firmware flash -FW_BANK_SIZE := 0x00040000 # Should include FW_DESC_SIZE (256kb) +FW_BANK_SIZE := 0x00060000 # Should include FW_DESC_SIZE (384kb) FW_DESC_SIZE := 0x00000064 @@ -28,7 +30,7 @@ EE_BANK_BASE := 0x00000000 EE_BANK_SIZE := 0x00000000 EF_BANK_BASE := 0x08000000 # Start of entire flash image (usually start of bootloader as well) -EF_BANK_SIZE := 0x00060000 # Size of the entire flash image (from bootloader until end of firmware) +EF_BANK_SIZE := 0x00080000 # Size of the entire flash image (from bootloader until end of firmware) OSCILLATOR_FREQ := 8000000 SYSCLK_FREQ := 168000000 diff --git a/flight/targets/revomini/board-info/board_hw_defs.c b/flight/targets/revomini/board-info/board_hw_defs.c index 0c829fe05f6..b010a916782 100644 --- a/flight/targets/revomini/board-info/board_hw_defs.c +++ b/flight/targets/revomini/board-info/board_hw_defs.c @@ -594,12 +594,12 @@ static const struct pios_flash_partition pios_flash_partition_table[] = { .label = FLASH_PARTITION_LABEL_FW, .chip_desc = &pios_flash_chip_internal, .first_sector = 5, - .last_sector = 6, + .last_sector = 7, .chip_offset = (4 * FLASH_SECTOR_16KB) + (1 * FLASH_SECTOR_64KB), - .size = (6 - 5 + 1) * FLASH_SECTOR_128KB, + .size = (7 - 5 + 1) * FLASH_SECTOR_128KB, }, - /* NOTE: sectors 7-11 of the internal flash are currently unallocated */ + /* NOTE: sectors 8-11 of the internal flash are currently unallocated */ #endif /* PIOS_INCLUDE_FLASH_INTERNAL */ diff --git a/flight/targets/revomini/board-info/pios_board.h b/flight/targets/revomini/board-info/pios_board.h index 735075a7c8e..15a158a3d69 100644 --- a/flight/targets/revomini/board-info/pios_board.h +++ b/flight/targets/revomini/board-info/pios_board.h @@ -109,7 +109,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id; // // See also pios_board.c //------------------------- -extern uintptr_t pios_com_telem_rf_id; +extern uintptr_t pios_com_telem_serial_id; extern uintptr_t pios_com_gps_id; extern uintptr_t pios_com_telem_usb_id; extern uintptr_t pios_com_bridge_id; @@ -123,7 +123,7 @@ extern uintptr_t pios_com_frsky_sport_id; #define PIOS_COM_GPS (pios_com_gps_id) #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_serial_id) #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_MAVLINK (pios_com_mavlink_id) diff --git a/flight/targets/revomini/fw/Makefile b/flight/targets/revomini/fw/Makefile index dba03764908..f970e4c65ae 100644 --- a/flight/targets/revomini/fw/Makefile +++ b/flight/targets/revomini/fw/Makefile @@ -62,6 +62,7 @@ OPTMODULES += UAVOFrSKYSensorHubBridge OPTMODULES += PicoC OPTMODULES += UAVOFrSKYSPortBridge OPTMODULES += Geofence +OPTMODULES += ComUsbBridge # Paths OPUAVTALKINC = $(OPUAVTALK)/inc @@ -118,8 +119,8 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/atmospheric_math.c SRC += $(MATHLIB)/pid.c @@ -146,6 +147,7 @@ SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_openlrs.c SRC += $(PIOSCOMMON)/pios_openlrs_rcvr.c SRC += $(PIOSCOMMON)/pios_rfm22b.c @@ -168,11 +170,9 @@ SRC += $(PIOSCOMMON)/pios_semaphore.c SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c +SRC += $(PIOSCOMMON)/pios_hal.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files ## just for testing, timer.c could be compiled in thumb-mode too @@ -378,4 +378,8 @@ LDFLAGS += -Wl,--fatal-warnings #Linker scripts LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +include ./UAVObjects.inc + +UAVO_NAV = YES + include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/revomini/fw/UAVObjects.inc b/flight/targets/revomini/fw/UAVObjects.inc index 39c9e55ea67..8ef82dab400 100644 --- a/flight/targets/revomini/fw/UAVObjects.inc +++ b/flight/targets/revomini/fw/UAVObjects.inc @@ -1,10 +1,14 @@ -##### -# Project: OpenPilot +############################################################################### +# @file Makefile +# @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 +# @addtogroup +# @{ +# @addtogroup +# @{ +# @brief Makefile to build UAVObject code for RevoMini board. +############################################################################### # -# Makefile for OpenPilot UAVObject code -# -# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. -# # This program is free software; you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by # the Free Software Foundation; either version 3 of the License, or @@ -18,111 +22,24 @@ # You should have received a copy of the GNU General Public License along # with this program; if not, write to the Free Software Foundation, Inc., # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -##### # These are the UAVObjects supposed to be build as part of the OpenPilot target # (all architectures) UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired UAVOBJSRCFILENAMES += rfm22breceiver -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwrevomini -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging #Support for radio module on RM UAVOBJSRCFILENAMES += rfm22bstatus UAVOBJSRCFILENAMES += openlrs UAVOBJSRCFILENAMES += openlrsstatus - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/revomini/fw/pios_board.c b/flight/targets/revomini/fw/pios_board.c index 166dcd19ee2..f5f77941d27 100644 --- a/flight/targets/revomini/fw/pios_board.c +++ b/flight/targets/revomini/fw/pios_board.c @@ -7,7 +7,7 @@ * * @file pios_board.c * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2011. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014 + * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 * @brief The board specific initialization routines * @see The GNU Public License (GPL) Version 3 * @@ -38,6 +38,7 @@ #include "board_hw_defs.c" #include +#include #include #include #include "hwrevomini.h" @@ -154,150 +155,15 @@ static const struct pios_mpu60x0_cfg pios_mpu6000_cfg = { }; #endif /* PIOS_INCLUDE_MPU6000 */ -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS - * NOTE: No slot in this map for NONE. - */ -uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 - -#define PIOS_COM_GPS_RX_BUF_LEN 32 -#define PIOS_COM_GPS_TX_BUF_LEN 16 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 - -#define PIOS_COM_HOTT_RX_BUF_LEN 16 -#define PIOS_COM_HOTT_TX_BUF_LEN 16 - -#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128 - -#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 19 - -#define PIOS_COM_PICOC_RX_BUF_LEN 128 -#define PIOS_COM_PICOC_TX_BUF_LEN 128 - -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 - -#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 -#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 - #if defined(PIOS_INCLUDE_DEBUG_CONSOLE) #define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 uintptr_t pios_com_debug_id; #endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -uintptr_t pios_com_gps_id; -uintptr_t pios_com_telem_usb_id; -uintptr_t pios_com_telem_rf_id; -uintptr_t pios_com_vcp_id; -uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; -uintptr_t pios_com_mavlink_id; -uintptr_t pios_com_rf_id; -uintptr_t pios_com_hott_id; -uintptr_t pios_com_frsky_sensor_hub_id; -uintptr_t pios_com_lighttelemetry_id; -uintptr_t pios_com_picoc_id; -uintptr_t pios_com_frsky_sport_id; -uint32_t pios_rfm22b_id; uintptr_t pios_internal_adc_id = 0; uintptr_t pios_uavo_settings_fs_id; uintptr_t pios_waypoints_settings_fs_id; -/* - * Setup a com port based on the passed cfg, driver and buffer sizes. rx or tx size of 0 disables rx or tx - */ -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) -static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, - const struct pios_com_driver *com_driver, uintptr_t *pios_com_id) -{ - uintptr_t pios_usart_id; - if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer; - if (rx_buf_len > 0) { - rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); - PIOS_Assert(rx_buffer); - } else { - rx_buffer = NULL; - } - - uint8_t * tx_buffer; - if (tx_buf_len > 0) { - tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); - PIOS_Assert(tx_buffer); - } else { - tx_buffer = NULL; - } - - if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, - rx_buffer, rx_buf_len, - tx_buffer, tx_buf_len)) { - PIOS_Assert(0); - } -} -#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ - -#ifdef PIOS_INCLUDE_DSM -static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) -{ - uintptr_t pios_usart_dsm_id; - if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_rcvr_id; - if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; -} - -#endif - -#ifdef PIOS_INCLUDE_HSUM -static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hsum_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_hsum_proto *proto, - ManualControlSettingsChannelGroupsOptions channelgroup) -{ - uintptr_t pios_usart_hsum_id; - if (PIOS_USART_Init(&pios_usart_hsum_id, pios_usart_hsum_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_id; - if (PIOS_HSUM_Init(&pios_hsum_id, pios_usart_com_driver, - pios_usart_hsum_id, *proto)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_rcvr_id; - if (PIOS_RCVR_Init(&pios_hsum_rcvr_id, &pios_hsum_rcvr_driver, pios_hsum_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_hsum_rcvr_id; -} -#endif - /** * PIOS_Board_Init() * initializes all the core subsystems on this specific hardware @@ -427,85 +293,12 @@ void PIOS_Board_Init(void) { PIOS_USB_Init(&pios_usb_id, PIOS_BOARD_HW_DEFS_GetUsbCfg(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_USB_CDC) - uint8_t hw_usb_vcpport; /* Configure the USB VCP port */ HwRevoMiniUSB_VCPPortGet(&hw_usb_vcpport); - if (!usb_cdc_present) { - /* Force VCP port function to disabled if we haven't advertised VCP in our USB descriptor */ - hw_usb_vcpport = HWREVOMINI_USB_VCPPORT_DISABLED; - } - - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_vcpport) { - case HWREVOMINI_USB_VCPPORT_DISABLED: - break; - case HWREVOMINI_USB_VCPPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOMINI_USB_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOMINI_USB_VCPPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - NULL, 0, - tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -#endif /* PIOS_INCLUDE_COM */ - break; - case HWREVOMINI_USB_VCPPORT_PICOC: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, - tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } + PIOS_HAL_ConfigureCDC(hw_usb_vcpport, + pios_usb_id, &pios_usb_cdc_cfg); #endif /* PIOS_INCLUDE_USB_CDC */ #if defined(PIOS_INCLUDE_USB_HID) @@ -518,31 +311,7 @@ void PIOS_Board_Init(void) { hw_usb_hidport = HWREVOMINI_USB_HIDPORT_DISABLED; } - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_hidport) { - case HWREVOMINI_USB_HIDPORT_DISABLED: - break; - case HWREVOMINI_USB_HIDPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } - + PIOS_HAL_ConfigureHID(hw_usb_hidport, pios_usb_id, &pios_usb_hid_cfg); #endif /* PIOS_INCLUDE_USB_HID */ if (usb_hid_present || usb_cdc_present) { @@ -551,379 +320,41 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure IO ports */ - uint8_t hw_DSMxBind; - HwRevoMiniDSMxBindGet(&hw_DSMxBind); + HwRevoMiniDSMxModeOptions hw_DSMxMode; + HwRevoMiniDSMxModeGet(&hw_DSMxMode); /* Configure main USART port */ uint8_t hw_mainport; HwRevoMiniMainPortGet(&hw_mainport); - switch (hw_mainport) { - case HWREVOMINI_MAINPORT_DISABLED: - break; - case HWREVOMINI_MAINPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWREVOMINI_MAINPORT_GPS: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWREVOMINI_MAINPORT_SBUS: -#if defined(PIOS_INCLUDE_SBUS) - { - uintptr_t pios_usart_sbus_id; - if (PIOS_USART_Init(&pios_usart_sbus_id, &pios_usart_sbus_main_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_id; - if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { - PIOS_Assert(0); - } - - uintptr_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; - } -#endif - break; - case HWREVOMINI_MAINPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - // Force binding to zero on the main port - hw_DSMxBind = 0; - - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_main_cfg, &pios_dsm_main_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWREVOMINI_MAINPORT_HOTTSUMD: - case HWREVOMINI_MAINPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_mainport) { - case HWREVOMINI_MAINPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWREVOMINI_MAINPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_main_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWREVOMINI_MAINPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOMINI_MAINPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWREVOMINI_MAINPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWREVOMINI_MAINPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; - #endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWREVOMINI_MAINPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWREVOMINI_MAINPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWREVOMINI_MAINPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - break; - case HWREVOMINI_MAINPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWREVOMINI_MAINPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ - break; - } /* hw_mainport */ - - if (hw_mainport != HWREVOMINI_MAINPORT_SBUS) { - GPIO_Init(pios_sbus_cfg.inv.gpio, (GPIO_InitTypeDef*)&pios_sbus_cfg.inv.init); - GPIO_WriteBit(pios_sbus_cfg.inv.gpio, pios_sbus_cfg.inv.init.GPIO_Pin, pios_sbus_cfg.gpio_inv_disable); - } + + PIOS_HAL_ConfigurePort(hw_mainport, &pios_usart_main_cfg, + &pios_usart_com_driver, NULL, NULL, NULL, PIOS_LED_ALARM, + &pios_usart_dsm_hsum_main_cfg, &pios_dsm_main_cfg, + hw_DSMxMode >= HWREVOMINI_DSMXMODE_BIND3PULSES ? HWREVOMINI_DSMXMODE_AUTODETECT : hw_DSMxMode /* No bind on main port */, &pios_usart_sbus_main_cfg, + &pios_sbus_cfg, true); /* Configure FlexiPort */ uint8_t hw_flexiport; HwRevoMiniFlexiPortGet(&hw_flexiport); - switch (hw_flexiport) { - case HWREVOMINI_FLEXIPORT_DISABLED: - break; - case HWREVOMINI_FLEXIPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWREVOMINI_FLEXIPORT_I2C: -#if defined(PIOS_INCLUDE_I2C) - { - if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_I2C */ - break; - case HWREVOMINI_FLEXIPORT_GPS: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWREVOMINI_FLEXIPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - //TODO: Define the various Channelgroup for Revo dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT,&hw_DSMxBind); - } - break; -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWREVOMINI_FLEXIPORT_HOTTSUMD: - case HWREVOMINI_FLEXIPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_flexiport) { - case HWREVOMINI_FLEXIPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWREVOMINI_FLEXIPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_flexi_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWREVOMINI_FLEXIPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWREVOMINI_FLEXIPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWREVOMINI_FLEXIPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWREVOMINI_FLEXIPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWREVOMINI_FLEXIPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWREVOMINI_FLEXIPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWREVOMINI_FLEXIPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - case HWREVOMINI_FLEXIPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - case HWREVOMINI_FLEXIPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY */ - break; - } /* hwsettings_rv_flexiport */ - - // Initialize out status object. - RFM22BStatusInitialize(); - RFM22BStatusCreateInstance(); - - /* Initalize the RFM22B radio COM device. */ -#if defined(PIOS_INCLUDE_RFM22B) - RFM22BStatusData rfm22bstatus; - RFM22BStatusGet(&rfm22bstatus); + + PIOS_HAL_ConfigurePort(hw_flexiport, &pios_usart_flexi_cfg, + &pios_usart_com_driver, &pios_i2c_flexiport_adapter_id, + &pios_i2c_flexiport_adapter_cfg, NULL, PIOS_LED_ALARM, + &pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, + hw_DSMxMode, NULL, NULL, false); HwRevoMiniData hwRevoMini; HwRevoMiniGet(&hwRevoMini); - rfm22bstatus.BoardType = bdinfo->board_type; - rfm22bstatus.BoardRevision = bdinfo->board_rev; - - if (hwRevoMini.Radio == HWREVOMINI_RADIO_OPENLRS) { - uintptr_t openlrs_id; - - const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev); - PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg); - -#if defined(PIOS_INCLUDE_OPENLRS_RCVR) - { - uintptr_t pios_rfm22brcvr_id; - PIOS_OpenLRS_Rcvr_Init(&pios_rfm22brcvr_id, openlrs_id); - uintptr_t pios_rfm22brcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_rfm22brcvr_rcvr_id, &pios_openlrs_rcvr_driver, pios_rfm22brcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = pios_rfm22brcvr_rcvr_id; - } -#endif /* PIOS_INCLUDE_OPENLRS_RCVR */ - - } else if (hwRevoMini.Radio == HWREVOMINI_RADIO_DISABLED || hwRevoMini.MaxRfPower == HWREVOMINI_MAXRFPOWER_0) { - - // When radio disabled, it is ok for init to fail. This allows boards without populating - // this component. - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg) == 0) { - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - } else { - pios_rfm22b_id = 0; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; - - } else { - - // always allow receiving PPM when radio is on - bool ppm_mode = hwRevoMini.Radio == HWREVOMINI_RADIO_TELEMPPM || hwRevoMini.Radio == HWREVOMINI_RADIO_PPM; - bool ppm_only = hwRevoMini.Radio == HWREVOMINI_RADIO_PPM; - bool is_oneway = false; // does not matter for this side - - /* Configure the RFM22B device. */ - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { - PIOS_Assert(0); - } - - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - - /* Configure the radio com interface */ - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - /* Set Telemetry to use OPLinkMini if no other telemetry is configured (USB always overrides anyway) */ - if (!pios_com_telem_rf_id) { - pios_com_telem_rf_id = pios_com_rf_id; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_ENABLED; - - enum rfm22b_datarate datarate = RFM22_datarate_64000; - switch (hwRevoMini.MaxRfSpeed) { - case HWREVOMINI_MAXRFSPEED_9600: - datarate = RFM22_datarate_9600; - break; - case HWREVOMINI_MAXRFSPEED_19200: - datarate = RFM22_datarate_19200; - break; - case HWREVOMINI_MAXRFSPEED_32000: - datarate = RFM22_datarate_32000; - break; - case HWREVOMINI_MAXRFSPEED_64000: - datarate = RFM22_datarate_64000; - break; - case HWREVOMINI_MAXRFSPEED_100000: - datarate = RFM22_datarate_100000; - break; - case HWREVOMINI_MAXRFSPEED_192000: - datarate = RFM22_datarate_192000; - break; - } - - /* Set the radio configuration parameters. */ - PIOS_RFM22B_Config(pios_rfm22b_id, datarate, hwRevoMini.MinChannel, hwRevoMini.MaxChannel, hwRevoMini.CoordID, is_oneway, ppm_mode, ppm_only); - - /* Set the modem Tx poer level */ - switch (hwRevoMini.MaxRfPower) { - case HWREVOMINI_MAXRFPOWER_125: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - break; - case HWREVOMINI_MAXRFPOWER_16: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); - break; - case HWREVOMINI_MAXRFPOWER_316: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); - break; - case HWREVOMINI_MAXRFPOWER_63: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); - break; - case HWREVOMINI_MAXRFPOWER_126: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); - break; - case HWREVOMINI_MAXRFPOWER_25: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); - break; - case HWREVOMINI_MAXRFPOWER_50: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); - break; - case HWREVOMINI_MAXRFPOWER_100: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); - break; - default: - // do nothing - break; - } - - /* Reinitialize the modem. */ - PIOS_RFM22B_Reinit(pios_rfm22b_id); - -#if defined(PIOS_INCLUDE_RFM22B_RCVR) - { - uintptr_t pios_rfm22brcvr_id; - PIOS_RFM22B_Rcvr_Init(&pios_rfm22brcvr_id, pios_rfm22b_id); - uintptr_t pios_rfm22brcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_rfm22brcvr_rcvr_id, &pios_rfm22b_rcvr_driver, pios_rfm22brcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_RFM22B] = pios_rfm22brcvr_rcvr_id; - } - - } - RFM22BStatusInstSet(1,&rfm22bstatus); -#endif /* PIOS_INCLUDE_RFM22B_RCVR */ +#ifdef PIOS_INCLUDE_RFM22B + const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev); + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); + PIOS_HAL_ConfigureRFM22B(hwRevoMini.Radio, + bdinfo->board_type, bdinfo->board_rev, + hwRevoMini.MaxRfPower, hwRevoMini.MaxRfSpeed, + openlrs_cfg, rfm22b_cfg, hwRevoMini.MinChannel, + hwRevoMini.MaxChannel, hwRevoMini.CoordID, 1); #endif /* PIOS_INCLUDE_RFM22B */ /* Configure the receiver port*/ diff --git a/flight/targets/revomini/fw/pios_config.h b/flight/targets/revomini/fw/pios_config.h index ac4a67be8c8..23977ccc852 100644 --- a/flight/targets/revomini/fw/pios_config.h +++ b/flight/targets/revomini/fw/pios_config.h @@ -86,7 +86,7 @@ #define PIOS_INCLUDE_FRSKY_SENSOR_HUB #define PIOS_INCLUDE_SESSION_MANAGEMENT #define PIOS_INCLUDE_LIGHTTELEMETRY -//#define PIOS_INCLUDE_PICOC +#define PIOS_INCLUDE_PICOC #define PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY /* Supported receiver interfaces */ @@ -134,8 +134,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/targets/simulation/fw/Makefile.posix b/flight/targets/simulation/fw/Makefile.posix index 7242a60f4f7..3760ba5a379 100644 --- a/flight/targets/simulation/fw/Makefile.posix +++ b/flight/targets/simulation/fw/Makefile.posix @@ -155,7 +155,6 @@ SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(FLIGHTLIB)/paths.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c @@ -193,15 +192,6 @@ EXTRAINCDIRS += $(PIOSCOMMON)/inc ## PIOS Hardware (Common) SRC += $(PIOSPOSIX)/../../tests/logfs/pios_flash_posix.c -include ./UAVObjects.inc - -UAVOBJSRCFILENAMES += attitudesimulated -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) - -SRC += $(UAVOBJSRC) -CFLAGS_UAVOBJECTS = $(UAVOBJDEFINE) - # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files ## just for testing, timer.c could be compiled in thumb-mode too @@ -361,20 +351,9 @@ $(OUTDIR)/sim_firmwareinfo.c: $(ROOT_DIR)/make/templates/firmwareinfotemplate_si --revision=1 \ --uavodir=$(ROOT_DIR)/shared/uavobjectdefinition + # List of all source files. SRC += $(OUTDIR)/sim_firmwareinfo.c -ALLSRC = $(ASRCARM) $(ASRC) $(SRCARM) $(SRC) $(CPPSRCARM) $(CPPSRC) -# List of all source files without directory and file-extension. -ALLSRCBASE = $(notdir $(basename $(ALLSRC))) - -# Define all object files. -ALLOBJ = $(addprefix $(OUTDIR)/, $(addsuffix .o, $(ALLSRCBASE))) - -# Link: create ELF output file from object files. -$(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) - -# Compile: create object files from C source files. -$(foreach src, $(SRC), $(eval $(call COMPILE_C_TEMPLATE, $(src)))) .PHONY: elf elf: $(OUTDIR)/$(TARGET).elf @@ -382,14 +361,6 @@ elf: $(OUTDIR)/$(TARGET).elf # Display sizes of sections. $(eval $(call SIZE_TEMPLATE, $(OUTDIR)/$(TARGET).elf)) -# Create output files directory -# all known MS Windows OS define the ComSpec environment variable -$(shell mkdir -p $(OUTDIR) 2>/dev/null) - -# Include the dependency files. --include $(shell mkdir $(OUTDIR) 2>/dev/null) $(shell mkdir $(OUTDIR)/dep 2>/dev/null) $(wildcard $(OUTDIR)/dep/*) - -# Test if quotes are needed for the echo-command result = ${shell echo "test"} ifeq (${result}, test) quote = ' @@ -413,3 +384,9 @@ ${OUTDIR}/InitMods.c: Makefile.posix @echo ${quote}${foreach MOD, ${MOD_GEN}, ${MOD}Start();}${quote} >> ${OUTDIR}/InitMods.c @echo ${quote}}${quote} >> ${OUTDIR}/InitMods.c +include ./UAVObjects.inc + +BUILD_FWFILES=NO +UAVO_NAV = YES + +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/simulation/fw/UAVObjects.inc b/flight/targets/simulation/fw/UAVObjects.inc index 18e5dd85a2e..eccd84696e5 100644 --- a/flight/targets/simulation/fw/UAVObjects.inc +++ b/flight/targets/simulation/fw/UAVObjects.inc @@ -1,10 +1,14 @@ -##### -# Project: OpenPilot +############################################################################### +# @file Makefile +# @author The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 +# @addtogroup +# @{ +# @addtogroup +# @{ +# @brief Makefile to build UAVObject code for simulation. +############################################################################### # -# Makefile for OpenPilot UAVObject code -# -# The OpenPilot Team, http://www.openpilot.org, Copyright (C) 2011. -# # This program is free software; you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by # the Free Software Foundation; either version 3 of the License, or @@ -18,104 +22,23 @@ # You should have received a copy of the GNU General Public License along # with this program; if not, write to the Free Software Foundation, Inc., # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -##### - # These are the UAVObjects supposed to be build as part of the OpenPilot target # (all architectures) UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence UAVOBJSRCFILENAMES += overosyncstats UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus -UAVOBJSRCFILENAMES += hwrevolution -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) +# Include this in the simulator so that we can edit a representative inherited +# obj for dev test. +UAVOBJSRCFILENAMES += hwsparky + +UAVOBJSRCFILENAMES += attitudesimulated diff --git a/flight/targets/simulation/fw/main.c b/flight/targets/simulation/fw/main.c index 16f58704d38..867781d2ef1 100644 --- a/flight/targets/simulation/fw/main.c +++ b/flight/targets/simulation/fw/main.c @@ -45,11 +45,7 @@ extern void Stack_Change(void); /* Local Variables */ #define INIT_TASK_PRIORITY PIOS_THREAD_PRIO_HIGHEST -#if defined(SIM_POSIX) -#define INIT_TASK_STACK 32768 -#else -#define INIT_TASK_STACK 1024 -#endif /* defined(SIM_POSIX) */ +#define INIT_TASK_STACK 262144 static struct pios_thread *initTaskHandle; /* Function Prototypes */ diff --git a/flight/targets/simulation/fw/pios_board_sim.c b/flight/targets/simulation/fw/pios_board_sim.c index de0acf12332..4d9280d29ba 100644 --- a/flight/targets/simulation/fw/pios_board_sim.c +++ b/flight/targets/simulation/fw/pios_board_sim.c @@ -41,6 +41,7 @@ #include "gpsposition.h" #include "gyros.h" #include "gyrosbias.h" +#include "hwsparky.h" #include "magnetometer.h" #include "manualcontrolsettings.h" @@ -165,6 +166,9 @@ void PIOS_Board_Init(void) { GyrosInitialize(); GyrosBiasInitialize(); + /* Initialize the sparky object, because developers use this for dev + * test. */ + HwSparkyInitialize(); #if defined(PIOS_INCLUDE_COM) #if defined(PIOS_INCLUDE_TELEMETRY_RF) && 1 { diff --git a/flight/targets/simulation/fw/pios_config.h b/flight/targets/simulation/fw/pios_config.h index 00b71f9e774..8e4313f3605 100644 --- a/flight/targets/simulation/fw/pios_config.h +++ b/flight/targets/simulation/fw/pios_config.h @@ -130,8 +130,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) -#define REVOLUTION - // Enable POI tracking mode for camera stabilization #define CAMERASTAB_POI_MODE diff --git a/flight/targets/simulation/fw/pios_config_sim.h b/flight/targets/simulation/fw/pios_config_sim.h index 31fd6debb4b..bb7082c3668 100644 --- a/flight/targets/simulation/fw/pios_config_sim.h +++ b/flight/targets/simulation/fw/pios_config_sim.h @@ -80,8 +80,6 @@ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD 9959 -#define REVOLUTION - // Enable POI tracking mode for camera stabilization #define CAMERASTAB_POI_MODE diff --git a/flight/targets/sparky/fw/Makefile b/flight/targets/sparky/fw/Makefile index 8bdb86c7b1e..49a34f1af21 100644 --- a/flight/targets/sparky/fw/Makefile +++ b/flight/targets/sparky/fw/Makefile @@ -114,8 +114,8 @@ SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/atmospheric_math.c @@ -134,6 +134,7 @@ SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_hsum.c @@ -153,9 +154,6 @@ SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -324,5 +322,8 @@ LDFLAGS += -Wl,--fatal-warnings #Linker scripts LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) -include $(MAKE_INC_DIR)/firmware-common.mk +include ./UAVObjects.inc + +UAVO_NAV = YES +include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/sparky/fw/UAVObjects.inc b/flight/targets/sparky/fw/UAVObjects.inc index efee445bdfc..a21a2b975f5 100644 --- a/flight/targets/sparky/fw/UAVObjects.inc +++ b/flight/targets/sparky/fw/UAVObjects.inc @@ -1,6 +1,6 @@ ############################################################################### # @file Makefile -# @author Tau Labs, http://taulabs.org, Copyright (C) 2013 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 # @addtogroup # @{ # @addtogroup @@ -28,98 +28,12 @@ UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwsparky -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo -UAVOBJSRCFILENAMES += txpidsettings UAVOBJSRCFILENAMES += i2cvm UAVOBJSRCFILENAMES += i2cvmuserprogram -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/sparky/fw/pios_board.c b/flight/targets/sparky/fw/pios_board.c index 0cdc1c48c4a..438f07d0af8 100644 --- a/flight/targets/sparky/fw/pios_board.c +++ b/flight/targets/sparky/fw/pios_board.c @@ -263,7 +263,7 @@ static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cf #ifdef PIOS_INCLUDE_DSM static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) + ManualControlSettingsChannelGroupsOptions channelgroup,HwSparkyDSMxModeOptions *mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -272,7 +272,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -591,8 +591,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwSparkyDSMxBindGet(&hw_DSMxBind); + HwSparkyDSMxModeOptions hw_DSMxMode; + HwSparkyDSMxModeGet(&hw_DSMxMode); /* UART1 Port */ uint8_t hw_flexi; @@ -643,7 +643,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_flexi_dsm_hsum_cfg, &pios_flexi_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -731,7 +731,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_main_dsm_hsum_cfg, &pios_main_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -805,7 +805,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_rcvr_dsm_hsum_cfg, &pios_rcvr_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; diff --git a/flight/targets/sparky/fw/pios_config.h b/flight/targets/sparky/fw/pios_config.h index d3bf5ab897c..eb49351492c 100644 --- a/flight/targets/sparky/fw/pios_config.h +++ b/flight/targets/sparky/fw/pios_config.h @@ -126,8 +126,6 @@ */ #define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (2175780) -#define REVOLUTION - #define CAMERASTAB_POI_MODE #endif /* PIOS_CONFIG_H */ diff --git a/flight/targets/sparky2/board-info/pios_board.h b/flight/targets/sparky2/board-info/pios_board.h index ca2451db220..b230f236eee 100644 --- a/flight/targets/sparky2/board-info/pios_board.h +++ b/flight/targets/sparky2/board-info/pios_board.h @@ -104,7 +104,7 @@ extern uint32_t pios_i2c_flexiport_adapter_id; // // See also pios_board.c //------------------------- -extern uintptr_t pios_com_telem_rf_id; +extern uintptr_t pios_com_telem_serial_id; extern uintptr_t pios_com_gps_id; extern uintptr_t pios_com_telem_usb_id; extern uintptr_t pios_com_bridge_id; @@ -116,10 +116,11 @@ extern uintptr_t pios_com_lighttelemetry_id; extern uintptr_t pios_com_picoc_id; extern uintptr_t pios_com_debug_id; extern uintptr_t pios_com_logging_id; +extern uintptr_t pios_com_frsky_sport_id; #define PIOS_COM_GPS (pios_com_gps_id) #define PIOS_COM_TELEM_USB (pios_com_telem_usb_id) -#define PIOS_COM_TELEM_RF (pios_com_telem_rf_id) +#define PIOS_COM_TELEM_RF (pios_com_telem_serial_id) #define PIOS_COM_BRIDGE (pios_com_bridge_id) #define PIOS_COM_VCP (pios_com_vcp_id) #define PIOS_COM_MAVLINK (pios_com_mavlink_id) @@ -129,6 +130,7 @@ extern uintptr_t pios_com_logging_id; #define PIOS_COM_PICOC (pios_com_picoc_id) #define PIOS_COM_DEBUG (pios_com_debug_id) #define PIOS_COM_LOGGING (pios_com_logging_id) +#define PIOS_COM_FRSKY_SPORT (pios_com_frsky_sport_id) #define DEBUG_LEVEL 0 #define DEBUG_PRINTF(level, ...) {if(level <= DEBUG_LEVEL && pios_com_debug_id > 0) { PIOS_COM_SendFormattedStringNonBlocking(pios_com_debug_id, __VA_ARGS__); }} diff --git a/flight/targets/sparky2/fw/Makefile b/flight/targets/sparky2/fw/Makefile index c12eb4329b1..6e2505d22f9 100644 --- a/flight/targets/sparky2/fw/Makefile +++ b/flight/targets/sparky2/fw/Makefile @@ -60,6 +60,7 @@ OPTMODULES += UAVORelay OPTMODULES += Airspeed/revolution OPTMODULES += UAVOHoTTBridge OPTMODULES += UAVOFrSKYSensorHubBridge +OPTMODULES += UAVOFrSKYSPortBridge OPTMODULES += PicoC OPTMODULES += Logging OPTMODULES += FlightStats @@ -88,7 +89,7 @@ MAVLINKINC = $(FLIGHTLIB)/mavlink/v1.0/common SRC = # optional component libraries -include $(PIOSCOMMONLIB)/FreeRTOS/library.mk +include $(APPLIBDIR)/ChibiOS/library.mk #include $(PIOSCOMMONLIB)/dosfs/library.mk include $(FLIGHTLIB)/CMSIS3/DSP_Lib/library.mk @@ -101,6 +102,7 @@ SRC += ${foreach MOD, ${MODULES} ${OPTMODULES}, ${wildcard ${OPMODULEDIR}/${MOD} ## OPENPILOT CORE: SRC += ${OPMODULEDIR}/System/systemmod.c SRC += main.c +SRC += board.c SRC += pios_board.c SRC += pios_usb_board_data.c SRC += $(FLIGHTLIB)/alarms.c @@ -124,8 +126,8 @@ SRC += $(FLIGHTLIB)/insgps14state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(FLIGHTLIB)/timeutils.c +SRC += $(FLIGHTLIB)/frsky_packing.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/atmospheric_math.c SRC += $(MATHLIB)/pid.c @@ -137,7 +139,7 @@ SRC += $(RSCODE)/galois.c SRC += $(RSCODE)/rs.c ## PIOS Hardware (STM32F4xx) -include $(PIOS)/STM32F4xx/library_fw.mk +include $(PIOS)/STM32F4xx/library_chibios.mk ## PIOS Hardware (Common) SRC += $(PIOSCOMMON)/pios_delay.c @@ -152,6 +154,7 @@ SRC += $(PIOSCOMMON)/pios_hmc5883.c SRC += $(PIOSCOMMON)/pios_ms5611.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_openlrs.c SRC += $(PIOSCOMMON)/pios_openlrs_rcvr.c SRC += $(PIOSCOMMON)/pios_rfm22b.c @@ -175,9 +178,7 @@ SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_queue.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_streamfs.c - -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) +SRC += $(PIOSCOMMON)/pios_hal.c # List C source files here which must be compiled in ARM-Mode (no -mthumb). # use file-extension c for "c-only"-files @@ -277,7 +278,7 @@ CDEFS += -DUNALIGNED_SUPPORT_DISABLE # This is not the best place for these. Really should abstract out # to the board file or something -CFLAGS += -DSTM32F4XX +CDEFS += -DSTM32F40_41xxx CFLAGS += -DMEM_SIZE=1024000000 # Output format. (can be ihex or binary or both) @@ -299,6 +300,7 @@ CDEFS += -DUSE_$(BOARD) ifeq ($(ENABLE_DEBUG_CONSOLE), YES) CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE endif +CDEFS += -DCORTEX_VTOR_INIT='($(FW_BANK_BASE) - $(EF_BANK_BASE))' ifeq ($(ENABLE_DEBUG_CONSOLE), YES) CDEFS += -DPIOS_INCLUDE_DEBUG_CONSOLE @@ -381,6 +383,10 @@ LDFLAGS += -Wl,--warn-common LDFLAGS += -Wl,--fatal-warnings #Linker scripts -LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +LDFLAGS += -T memory.ld $(addprefix -T,$(LINKER_SCRIPTS_APP)) + +include ./UAVObjects.inc + +UAVO_NAV = YES include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/sparky2/fw/UAVObjects.inc b/flight/targets/sparky2/fw/UAVObjects.inc index 4d5d17376c9..15cc0aedac1 100644 --- a/flight/targets/sparky2/fw/UAVObjects.inc +++ b/flight/targets/sparky2/fw/UAVObjects.inc @@ -1,10 +1,13 @@ -##### -# Project: Sparky2 +############################################################################### +# @file Makefile +# @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 +# @addtogroup +# @{ +# @addtogroup +# @{ +# @brief Makefile to build UAVObject code for Sparky2 board. +############################################################################### # -# Makefile for Sparky2 UAVObject code -# -# Tau Labs, http://taulabs.org, Copyright (C) 2012-2015 -# # This program is free software; you can redistribute it and/or modify # it under the terms of the GNU General Public License as published by # the Free Software Foundation; either version 3 of the License, or @@ -18,116 +21,26 @@ # You should have received a copy of the GNU General Public License along # with this program; if not, write to the Free Software Foundation, Inc., # 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA -##### # These are the UAVObjects supposed to be build as part of the OpenPilot target # (all architectures) UAVOBJSRCFILENAMES = UAVOBJSRCFILENAMES += acceldesired -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus UAVOBJSRCFILENAMES += flightstats UAVOBJSRCFILENAMES += flightstatssettings -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver UAVOBJSRCFILENAMES += geofencesettings -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity UAVOBJSRCFILENAMES += groundpathfollowersettings UAVOBJSRCFILENAMES += loggingsettings UAVOBJSRCFILENAMES += loggingstats -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired UAVOBJSRCFILENAMES += rfm22breceiver -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo UAVOBJSRCFILENAMES += rfm22bstatus UAVOBJSRCFILENAMES += openlrs UAVOBJSRCFILENAMES += openlrsstatus -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwsparky2 -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings UAVOBJSRCFILENAMES += altitudeholdstate -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive UAVOBJSRCFILENAMES += hottsettings -UAVOBJSRCFILENAMES += ubloxinfo UAVOBJSRCFILENAMES += picocsettings UAVOBJSRCFILENAMES += picocstatus -UAVOBJSRCFILENAMES += txpidsettings -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings - -UAVOBJSRCFILENAMES += sessionmanaging - - - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/sparky2/fw/board.c b/flight/targets/sparky2/fw/board.c new file mode 100644 index 00000000000..f80bff024c1 --- /dev/null +++ b/flight/targets/sparky2/fw/board.c @@ -0,0 +1,37 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#include "ch.h" +#include "hal.h" + +/** + * @brief Early initialization code. + * @details This initialization must be performed just after stack setup + * and before any other initialization. + */ +void __early_init(void) +{ + stm32_clock_init(); +} + +/** + * @brief Board-specific initialization code. + * @todo Add your board-specific code, if any. + */ +void boardInit(void) +{ +} + diff --git a/flight/targets/sparky2/fw/board.h b/flight/targets/sparky2/fw/board.h new file mode 100644 index 00000000000..bc1bfe3a404 --- /dev/null +++ b/flight/targets/sparky2/fw/board.h @@ -0,0 +1,68 @@ +/* + ChibiOS/RT - Copyright (C) 2006-20s13 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +#include "pios_chibios_transition_priv.h" + +/* + * Setup for STMicroelectronics STM32F4 (sparky2) + */ + +/* + * Board identifier. + */ +#define BOARD_SPARKY2 +#define BOARD_NAME "sparky2 flight control" + + +/* + * Board oscillators-related settings. + * NOTE: LSE not fitted. + */ +#if !defined(STM32_LSECLK) +#define STM32_LSECLK 0 +#endif + +#if !defined(STM32_HSECLK) +#define STM32_HSECLK 16000000 +#endif + +/* + * Board voltages. + * Required for performance limits calculation. + */ +#define STM32_VDD 330 + +/* + * MCU type as defined in the ST header. + */ +#if !defined(STM32F40_41xxx) +#define STM32F40_41xxx +#endif + +#if !defined(_FROM_ASM_) +#ifdef __cplusplus +extern "C" { +#endif + void boardInit(void); +#ifdef __cplusplus +} +#endif +#endif /* _FROM_ASM_ */ + +#endif /* _BOARD_H_ */ diff --git a/flight/targets/sparky2/fw/chconf.h b/flight/targets/sparky2/fw/chconf.h new file mode 100644 index 00000000000..66359c7c5fa --- /dev/null +++ b/flight/targets/sparky2/fw/chconf.h @@ -0,0 +1,576 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file templates/chconf.h + * @brief Configuration file template. + * @details A copy of this file must be placed in each project directory, it + * contains the application specific kernel settings. + * + * @addtogroup config + * @details Kernel related settings and hooks. + * @{ + */ + +#ifndef _CHCONF_H_ +#define _CHCONF_H_ + +/*===========================================================================*/ +/** + * @name Kernel parameters and options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief System tick frequency. + * @details Frequency of the system timer that drives the system ticks. This + * setting also defines the system tick time unit. + */ +#if !defined(CH_FREQUENCY) || defined(__DOXYGEN__) +#define CH_FREQUENCY 1000 +#endif + +/** + * @brief Round robin interval. + * @details This constant is the number of system ticks allowed for the + * threads before preemption occurs. Setting this value to zero + * disables the preemption for threads with equal priority and the + * round robin becomes cooperative. Note that higher priority + * threads can still preempt, the kernel is always preemptive. + * + * @note Disabling the round robin preemption makes the kernel more compact + * and generally faster. + */ +#if !defined(CH_TIME_QUANTUM) || defined(__DOXYGEN__) +#define CH_TIME_QUANTUM 1 +#endif + +/** + * @brief Managed RAM size. + * @details Size of the RAM area to be managed by the OS. If set to zero + * then the whole available RAM is used. The core memory is made + * available to the heap allocator and/or can be used directly through + * the simplified core memory allocator. + * + * @note In order to let the OS manage the whole RAM the linker script must + * provide the @p __heap_base__ and @p __heap_end__ symbols. + * @note Requires @p CH_USE_MEMCORE. + */ +#if !defined(CH_MEMCORE_SIZE) || defined(__DOXYGEN__) +#define CH_MEMCORE_SIZE 0 +#endif + +/** + * @brief Idle thread automatic spawn suppression. + * @details When this option is activated the function @p chSysInit() + * does not spawn the idle thread automatically. The application has + * then the responsibility to do one of the following: + * - Spawn a custom idle thread at priority @p IDLEPRIO. + * - Change the main() thread priority to @p IDLEPRIO then enter + * an endless loop. In this scenario the @p main() thread acts as + * the idle thread. + * . + * @note Unless an idle thread is spawned the @p main() thread must not + * enter a sleep state. + */ +#if !defined(CH_NO_IDLE_THREAD) || defined(__DOXYGEN__) +#define CH_NO_IDLE_THREAD FALSE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Performance options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief OS optimization. + * @details If enabled then time efficient rather than space efficient code + * is used when two possible implementations exist. + * + * @note This is not related to the compiler optimization options. + * @note The default is @p TRUE. + */ +#if !defined(CH_OPTIMIZE_SPEED) || defined(__DOXYGEN__) +#define CH_OPTIMIZE_SPEED TRUE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Subsystem options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Threads registry APIs. + * @details If enabled then the registry APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_REGISTRY) || defined(__DOXYGEN__) +#define CH_USE_REGISTRY TRUE +#endif + +/** + * @brief Threads synchronization APIs. + * @details If enabled then the @p chThdWait() function is included in + * the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_WAITEXIT) || defined(__DOXYGEN__) +#define CH_USE_WAITEXIT TRUE +#endif + +/** + * @brief Semaphores APIs. + * @details If enabled then the Semaphores APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_SEMAPHORES) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES TRUE +#endif + +/** + * @brief Semaphores queuing mode. + * @details If enabled then the threads are enqueued on semaphores by + * priority rather than in FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMAPHORES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES_PRIORITY FALSE +#endif + +/** + * @brief Atomic semaphore API. + * @details If enabled then the semaphores the @p chSemSignalWait() API + * is included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMSW) || defined(__DOXYGEN__) +#define CH_USE_SEMSW TRUE +#endif + +/** + * @brief Mutexes APIs. + * @details If enabled then the mutexes APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MUTEXES) || defined(__DOXYGEN__) +#define CH_USE_MUTEXES TRUE +#endif + +/** + * @brief Conditional Variables APIs. + * @details If enabled then the conditional variables APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_MUTEXES. + */ +#if !defined(CH_USE_CONDVARS) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS FALSE +#endif + +/** + * @brief Conditional Variables APIs with timeout. + * @details If enabled then the conditional variables APIs with timeout + * specification are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_CONDVARS. + */ +#if !defined(CH_USE_CONDVARS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS_TIMEOUT FALSE +#endif + +/** + * @brief Events Flags APIs. + * @details If enabled then the event flags APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_EVENTS) || defined(__DOXYGEN__) +#define CH_USE_EVENTS FALSE +#endif + +/** + * @brief Events Flags APIs with timeout. + * @details If enabled then the events APIs with timeout specification + * are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_EVENTS. + */ +#if !defined(CH_USE_EVENTS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_EVENTS_TIMEOUT FALSE +#endif + +/** + * @brief Synchronous Messages APIs. + * @details If enabled then the synchronous messages APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MESSAGES) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES FALSE +#endif + +/** + * @brief Synchronous Messages queuing mode. + * @details If enabled then messages are served by priority rather than in + * FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_MESSAGES. + */ +#if !defined(CH_USE_MESSAGES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES_PRIORITY FALSE +#endif + +/** + * @brief Mailboxes APIs. + * @details If enabled then the asynchronous messages (mailboxes) APIs are + * included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_MAILBOXES) || defined(__DOXYGEN__) +#define CH_USE_MAILBOXES TRUE +#endif + +/** + * @brief I/O Queues APIs. + * @details If enabled then the I/O queues APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_QUEUES) || defined(__DOXYGEN__) +#define CH_USE_QUEUES FALSE +#endif + +/** + * @brief Core Memory Manager APIs. + * @details If enabled then the core memory manager APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMCORE) || defined(__DOXYGEN__) +#define CH_USE_MEMCORE FALSE +#endif + +/** + * @brief Heap Allocator APIs. + * @details If enabled then the memory heap allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_MEMCORE and either @p CH_USE_MUTEXES or + * @p CH_USE_SEMAPHORES. + * @note Mutexes are recommended. + */ +#if !defined(CH_USE_HEAP) || defined(__DOXYGEN__) +#define CH_USE_HEAP FALSE +#endif + +/** + * @brief C-runtime allocator. + * @details If enabled the the heap allocator APIs just wrap the C-runtime + * @p malloc() and @p free() functions. + * + * @note The default is @p FALSE. + * @note Requires @p CH_USE_HEAP. + * @note The C-runtime may or may not require @p CH_USE_MEMCORE, see the + * appropriate documentation. + */ +#if !defined(CH_USE_MALLOC_HEAP) || defined(__DOXYGEN__) +#define CH_USE_MALLOC_HEAP FALSE +#endif + +/** + * @brief Memory Pools Allocator APIs. + * @details If enabled then the memory pools allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMPOOLS) || defined(__DOXYGEN__) +#define CH_USE_MEMPOOLS TRUE +#endif + +/** + * @brief Dynamic Threads APIs. + * @details If enabled then the dynamic threads creation APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_WAITEXIT. + * @note Requires @p CH_USE_HEAP and/or @p CH_USE_MEMPOOLS. + */ +#if !defined(CH_USE_DYNAMIC) || defined(__DOXYGEN__) +#define CH_USE_DYNAMIC FALSE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Debug options + * @{ + */ +/*===========================================================================*/ + +/** + * @brief Debug option, system state check. + * @details If enabled the correct call protocol for system APIs is checked + * at runtime. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_SYSTEM_STATE_CHECK) || defined(__DOXYGEN__) +#define CH_DBG_SYSTEM_STATE_CHECK FALSE +#endif + +/** + * @brief Debug option, parameters checks. + * @details If enabled then the checks on the API functions input + * parameters are activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_CHECKS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_CHECKS FALSE +#endif + +/** + * @brief Debug option, consistency checks. + * @details If enabled then all the assertions in the kernel code are + * activated. This includes consistency checks inside the kernel, + * runtime anomalies and port-defined checks. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_ASSERTS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_ASSERTS FALSE +#endif + +/** + * @brief Debug option, trace buffer. + * @details If enabled then the context switch circular trace buffer is + * activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_TRACE) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_TRACE FALSE +#endif + +/** + * @brief Debug option, stack checks. + * @details If enabled then a runtime stack check is performed. + * + * @note The default is @p FALSE. + * @note The stack check is performed in a architecture/port dependent way. + * It may not be implemented or some ports. + * @note The default failure mode is to halt the system with the global + * @p panic_msg variable set to @p NULL. + */ +#if !defined(CH_DBG_ENABLE_STACK_CHECK) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_STACK_CHECK TRUE +#endif + +/** + * @brief Debug option, stacks initialization. + * @details If enabled then the threads working area is filled with a byte + * value when a thread is created. This can be useful for the + * runtime measurement of the used stack. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_FILL_THREADS) || defined(__DOXYGEN__) +#define CH_DBG_FILL_THREADS TRUE +#endif + +/** + * @brief Debug option, threads profiling. + * @details If enabled then a field is added to the @p Thread structure that + * counts the system ticks occurred while executing the thread. + * + * @note The default is @p TRUE. + * @note This debug option is defaulted to TRUE because it is required by + * some test cases into the test suite. + */ +#if !defined(CH_DBG_THREADS_PROFILING) || defined(__DOXYGEN__) +#define CH_DBG_THREADS_PROFILING FALSE +#endif + +/** @} */ + +/*===========================================================================*/ +/** + * @name Kernel hooks + * @{ + */ +/*===========================================================================*/ + +#include + +/** + * @brief Type of the realtime free counter value. + */ +typedef uint32_t halrtcnt_t; + +/** + * @name Macro Functions + * @{ + */ +/** + * @brief Returns the current value of the system free running counter. + * @note This is an optional service that could not be implemented in + * all HAL implementations. + * @note This function can be called from any context. + * + * @return The value of the system free running counter of + * type halrtcnt_t. + * + * @special + */ +#define halGetCounterValue() hal_lld_get_counter_value() + +/** + * @brief Returns the current value of the system free running counter. + * @note This service is implemented by returning the content of the + * DWT_CYCCNT register. + * + * @return The value of the system free running counter of + * type halrtcnt_t. + * + * @notapi + */ +#define hal_lld_get_counter_value() DWT_CYCCNT + +/** + * @brief Threads descriptor structure extension. + * @details User fields added to the end of the @p Thread structure. + */ +#if !defined(THREAD_EXT_FIELDS) || defined(__DOXYGEN__) +#define THREAD_EXT_FIELDS \ + halrtcnt_t ticks_switched_in; \ + halrtcnt_t ticks_total; \ + /* Add threads custom fields here.*/ +#endif + +/** + * @brief Threads initialization hook. + * @details User initialization code added to the @p chThdInit() API. + * + * @note It is invoked from within @p chThdInit() and implicitly from all + * the threads creation APIs. + */ +#if !defined(THREAD_EXT_INIT_HOOK) || defined(__DOXYGEN__) +#define THREAD_EXT_INIT_HOOK(tp) { \ + /* Add threads initialization code here.*/ \ +} +#endif + +/** + * @brief Threads finalization hook. + * @details User finalization code added to the @p chThdExit() API. + * + * @note It is inserted into lock zone. + * @note It is also invoked when the threads simply return in order to + * terminate. + */ +#if !defined(THREAD_EXT_EXIT_HOOK) || defined(__DOXYGEN__) +#define THREAD_EXT_EXIT_HOOK(tp) { \ + /* Add threads finalization code here.*/ \ +} +#endif + +/** + * @brief Context switch hook. + * @details This hook is invoked just before switching between threads. + */ +#if !defined(THREAD_CONTEXT_SWITCH_HOOK) || defined(__DOXYGEN__) +#define THREAD_CONTEXT_SWITCH_HOOK(ntp, otp) { \ + ntp->ticks_switched_in = halGetCounterValue(); \ + otp->ticks_total += ntp->ticks_switched_in - otp->ticks_switched_in; \ + /* System halt code here.*/ \ +} +#endif + +/** + * @brief Idle Loop hook. + * @details This hook is continuously invoked by the idle thread loop. + */ +#if !defined(IDLE_LOOP_HOOK) || defined(__DOXYGEN__) +#define IDLE_LOOP_HOOK() { \ + extern void vApplicationIdleHook(void); \ + vApplicationIdleHook(); \ +} +#endif + +/** + * @brief System tick event hook. + * @details This hook is invoked in the system tick handler immediately + * after processing the virtual timers queue. + */ +#if !defined(SYSTEM_TICK_EVENT_HOOK) || defined(__DOXYGEN__) +#define SYSTEM_TICK_EVENT_HOOK() { \ + /* System tick event code here.*/ \ +} +#endif + +/** + * @brief System halt hook. + * @details This hook is invoked in case to a system halting error before + * the system is halted. + */ +#if !defined(SYSTEM_HALT_HOOK) || defined(__DOXYGEN__) +#define SYSTEM_HALT_HOOK() { \ + /* System halt code here.*/ \ +} +#endif + +/** @} */ + +/*===========================================================================*/ +/* Port-specific settings (override port settings defaulted in chcore.h). */ +/*===========================================================================*/ + +/* NOTE: When changing this option you also have to enable or disable the FPU + in the project options.*/ +#define CORTEX_USE_FPU TRUE + +#endif /* _CHCONF_H_ */ + +/** @} */ diff --git a/flight/targets/sparky2/fw/halconf.h b/flight/targets/sparky2/fw/halconf.h new file mode 100644 index 00000000000..51d5061d68b --- /dev/null +++ b/flight/targets/sparky2/fw/halconf.h @@ -0,0 +1,312 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/** + * @file templates/halconf.h + * @brief HAL configuration header. + * @details HAL configuration file, this file allows to enable or disable the + * various device drivers from your application. You may also use + * this file in order to override the device drivers default settings. + * + * @addtogroup HAL_CONF + * @{ + */ + +#ifndef _HALCONF_H_ +#define _HALCONF_H_ + +#include "mcuconf.h" + +/** + * @brief Enables the TM subsystem. + */ +#if !defined(HAL_USE_TM) || defined(__DOXYGEN__) +#define HAL_USE_TM FALSE +#endif + +/** + * @brief Enables the PAL subsystem. + */ +#if !defined(HAL_USE_PAL) || defined(__DOXYGEN__) +#define HAL_USE_PAL FALSE +#endif + +/** + * @brief Enables the ADC subsystem. + */ +#if !defined(HAL_USE_ADC) || defined(__DOXYGEN__) +#define HAL_USE_ADC FALSE +#endif + +/** + * @brief Enables the CAN subsystem. + */ +#if !defined(HAL_USE_CAN) || defined(__DOXYGEN__) +#define HAL_USE_CAN FALSE +#endif + +/** + * @brief Enables the EXT subsystem. + */ +#if !defined(HAL_USE_EXT) || defined(__DOXYGEN__) +#define HAL_USE_EXT FALSE +#endif + +/** + * @brief Enables the GPT subsystem. + */ +#if !defined(HAL_USE_GPT) || defined(__DOXYGEN__) +#define HAL_USE_GPT FALSE +#endif + +/** + * @brief Enables the I2C subsystem. + */ +#if !defined(HAL_USE_I2C) || defined(__DOXYGEN__) +#define HAL_USE_I2C FALSE +#endif + +/** + * @brief Enables the ICU subsystem. + */ +#if !defined(HAL_USE_ICU) || defined(__DOXYGEN__) +#define HAL_USE_ICU FALSE +#endif + +/** + * @brief Enables the MAC subsystem. + */ +#if !defined(HAL_USE_MAC) || defined(__DOXYGEN__) +#define HAL_USE_MAC FALSE +#endif + +/** + * @brief Enables the MMC_SPI subsystem. + */ +#if !defined(HAL_USE_MMC_SPI) || defined(__DOXYGEN__) +#define HAL_USE_MMC_SPI FALSE +#endif + +/** + * @brief Enables the PWM subsystem. + */ +#if !defined(HAL_USE_PWM) || defined(__DOXYGEN__) +#define HAL_USE_PWM FALSE +#endif + +/** + * @brief Enables the RTC subsystem. + */ +#if !defined(HAL_USE_RTC) || defined(__DOXYGEN__) +#define HAL_USE_RTC FALSE +#endif + +/** + * @brief Enables the SDC subsystem. + */ +#if !defined(HAL_USE_SDC) || defined(__DOXYGEN__) +#define HAL_USE_SDC FALSE +#endif + +/** + * @brief Enables the SERIAL subsystem. + */ +#if !defined(HAL_USE_SERIAL) || defined(__DOXYGEN__) +#define HAL_USE_SERIAL FALSE +#endif + +/** + * @brief Enables the SERIAL over USB subsystem. + */ +#if !defined(HAL_USE_SERIAL_USB) || defined(__DOXYGEN__) +#define HAL_USE_SERIAL_USB FALSE +#endif + +/** + * @brief Enables the SPI subsystem. + */ +#if !defined(HAL_USE_SPI) || defined(__DOXYGEN__) +#define HAL_USE_SPI FALSE +#endif + +/** + * @brief Enables the UART subsystem. + */ +#if !defined(HAL_USE_UART) || defined(__DOXYGEN__) +#define HAL_USE_UART FALSE +#endif + +/** + * @brief Enables the USB subsystem. + */ +#if !defined(HAL_USE_USB) || defined(__DOXYGEN__) +#define HAL_USE_USB FALSE +#endif + +/*===========================================================================*/ +/* ADC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables synchronous APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(ADC_USE_WAIT) || defined(__DOXYGEN__) +#define ADC_USE_WAIT TRUE +#endif + +/** + * @brief Enables the @p adcAcquireBus() and @p adcReleaseBus() APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(ADC_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define ADC_USE_MUTUAL_EXCLUSION TRUE +#endif + +/*===========================================================================*/ +/* CAN driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Sleep mode related APIs inclusion switch. + */ +#if !defined(CAN_USE_SLEEP_MODE) || defined(__DOXYGEN__) +#define CAN_USE_SLEEP_MODE TRUE +#endif + +/*===========================================================================*/ +/* I2C driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the mutual exclusion APIs on the I2C bus. + */ +#if !defined(I2C_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define I2C_USE_MUTUAL_EXCLUSION TRUE +#endif + +/*===========================================================================*/ +/* MAC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables an event sources for incoming packets. + */ +#if !defined(MAC_USE_ZERO_COPY) || defined(__DOXYGEN__) +#define MAC_USE_ZERO_COPY FALSE +#endif + +/** + * @brief Enables an event sources for incoming packets. + */ +#if !defined(MAC_USE_EVENTS) || defined(__DOXYGEN__) +#define MAC_USE_EVENTS TRUE +#endif + +/*===========================================================================*/ +/* MMC_SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Delays insertions. + * @details If enabled this options inserts delays into the MMC waiting + * routines releasing some extra CPU time for the threads with + * lower priority, this may slow down the driver a bit however. + * This option is recommended also if the SPI driver does not + * use a DMA channel and heavily loads the CPU. + */ +#if !defined(MMC_NICE_WAITING) || defined(__DOXYGEN__) +#define MMC_NICE_WAITING TRUE +#endif + +/*===========================================================================*/ +/* SDC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Number of initialization attempts before rejecting the card. + * @note Attempts are performed at 10mS intervals. + */ +#if !defined(SDC_INIT_RETRY) || defined(__DOXYGEN__) +#define SDC_INIT_RETRY 100 +#endif + +/** + * @brief Include support for MMC cards. + * @note MMC support is not yet implemented so this option must be kept + * at @p FALSE. + */ +#if !defined(SDC_MMC_SUPPORT) || defined(__DOXYGEN__) +#define SDC_MMC_SUPPORT FALSE +#endif + +/** + * @brief Delays insertions. + * @details If enabled this options inserts delays into the MMC waiting + * routines releasing some extra CPU time for the threads with + * lower priority, this may slow down the driver a bit however. + */ +#if !defined(SDC_NICE_WAITING) || defined(__DOXYGEN__) +#define SDC_NICE_WAITING TRUE +#endif + +/*===========================================================================*/ +/* SERIAL driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Default bit rate. + * @details Configuration parameter, this is the baud rate selected for the + * default configuration. + */ +#if !defined(SERIAL_DEFAULT_BITRATE) || defined(__DOXYGEN__) +#define SERIAL_DEFAULT_BITRATE 38400 +#endif + +/** + * @brief Serial buffers size. + * @details Configuration parameter, you can change the depth of the queue + * buffers depending on the requirements of your application. + * @note The default is 64 bytes for both the transmission and receive + * buffers. + */ +#if !defined(SERIAL_BUFFERS_SIZE) || defined(__DOXYGEN__) +#define SERIAL_BUFFERS_SIZE 16 +#endif + +/*===========================================================================*/ +/* SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables synchronous APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(SPI_USE_WAIT) || defined(__DOXYGEN__) +#define SPI_USE_WAIT TRUE +#endif + +/** + * @brief Enables the @p spiAcquireBus() and @p spiReleaseBus() APIs. + * @note Disabling this option saves both code and data space. + */ +#if !defined(SPI_USE_MUTUAL_EXCLUSION) || defined(__DOXYGEN__) +#define SPI_USE_MUTUAL_EXCLUSION TRUE +#endif + +#endif /* _HALCONF_H_ */ + +/** @} */ diff --git a/flight/targets/sparky2/fw/main.c b/flight/targets/sparky2/fw/main.c index 1dc39a23a66..4538ed33cd9 100644 --- a/flight/targets/sparky2/fw/main.c +++ b/flight/targets/sparky2/fw/main.c @@ -51,9 +51,6 @@ static struct pios_thread *initTaskHandle; /* Function Prototypes */ static void initTask(void *parameters); -/* Prototype of generated InitModules() function */ -extern void InitModules(void); - /** * Tau Labs Main function: * @@ -69,6 +66,13 @@ int main() /* Any new initialization functions should be added in OpenPilotInit() */ PIOS_heap_initialize_blocks(); +#if defined(PIOS_INCLUDE_CHIBIOS) + halInit(); + chSysInit(); + + boardInit(); +#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ + /* Brings up System using CMSIS functions, enables the LEDs. */ PIOS_SYS_Init(); @@ -77,6 +81,7 @@ int main() initTaskHandle = PIOS_Thread_Create(initTask, "init", INIT_TASK_STACK, NULL, INIT_TASK_PRIORITY); PIOS_Assert(initTaskHandle != NULL); +#if defined(PIOS_INCLUDE_FREERTOS) /* Start the FreeRTOS scheduler */ vTaskStartScheduler(); @@ -87,6 +92,10 @@ int main() PIOS_LED_Toggle(PIOS_LED_HEARTBEAT); \ PIOS_DELAY_WaitmS(100); \ }; +#elif defined(PIOS_INCLUDE_CHIBIOS) + while(1) + PIOS_Thread_Sleep(PIOS_THREAD_TIMEOUT_MAX); +#endif /* defined(PIOS_INCLUDE_CHIBIOS) */ return 0; } diff --git a/flight/targets/sparky2/fw/mcuconf.h b/flight/targets/sparky2/fw/mcuconf.h new file mode 100644 index 00000000000..4f95cc46eb0 --- /dev/null +++ b/flight/targets/sparky2/fw/mcuconf.h @@ -0,0 +1,288 @@ +/* + ChibiOS/RT - Copyright (C) 2006-2013 Giovanni Di Sirio + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. +*/ + +/* + * STM32F4xx drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the whole + * driver is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +#define STM32F4xx_MCUCONF + +/* + * HAL driver system settings. + */ +#define STM32_NO_INIT FALSE +#define STM32_HSI_ENABLED TRUE +#define STM32_LSI_ENABLED TRUE +#define STM32_HSE_ENABLED TRUE +#define STM32_LSE_ENABLED FALSE +#define STM32_CLOCK48_REQUIRED TRUE +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_HSE +#define STM32_PLLM_VALUE 16 +#define STM32_PLLN_VALUE 336 +#define STM32_PLLP_VALUE 2 +#define STM32_PLLQ_VALUE 7 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV4 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_RTCSEL STM32_RTCSEL_LSI +#define STM32_RTCPRE_VALUE 8 +#define STM32_MCO1SEL STM32_MCO1SEL_HSI +#define STM32_MCO1PRE STM32_MCO1PRE_DIV1 +#define STM32_MCO2SEL STM32_MCO2SEL_SYSCLK +#define STM32_MCO2PRE STM32_MCO2PRE_DIV5 +#define STM32_I2SSRC STM32_I2SSRC_CKIN +#define STM32_PLLI2SN_VALUE 192 +#define STM32_PLLI2SR_VALUE 5 +#define STM32_PVD_ENABLE FALSE +#define STM32_PLS STM32_PLS_LEV0 +#define STM32_BKPRAM_ENABLE FALSE + +/* + * ADC driver system settings. + */ +#define STM32_ADC_ADCPRE ADC_CCR_ADCPRE_DIV4 +#define STM32_ADC_USE_ADC1 FALSE +#define STM32_ADC_USE_ADC2 FALSE +#define STM32_ADC_USE_ADC3 FALSE +#define STM32_ADC_ADC1_DMA_STREAM STM32_DMA_STREAM_ID(2, 4) +#define STM32_ADC_ADC2_DMA_STREAM STM32_DMA_STREAM_ID(2, 2) +#define STM32_ADC_ADC3_DMA_STREAM STM32_DMA_STREAM_ID(2, 1) +#define STM32_ADC_ADC1_DMA_PRIORITY 2 +#define STM32_ADC_ADC2_DMA_PRIORITY 2 +#define STM32_ADC_ADC3_DMA_PRIORITY 2 +#define STM32_ADC_IRQ_PRIORITY 6 +#define STM32_ADC_ADC1_DMA_IRQ_PRIORITY 6 +#define STM32_ADC_ADC2_DMA_IRQ_PRIORITY 6 +#define STM32_ADC_ADC3_DMA_IRQ_PRIORITY 6 + +/* + * CAN driver system settings. + */ +#define STM32_CAN_USE_CAN1 FALSE +#define STM32_CAN_USE_CAN2 FALSE +#define STM32_CAN_CAN1_IRQ_PRIORITY 11 +#define STM32_CAN_CAN2_IRQ_PRIORITY 11 + +/* + * EXT driver system settings. + */ +#define STM32_EXT_EXTI0_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI1_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI2_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI3_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI4_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI5_9_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI10_15_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI16_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI17_IRQ_PRIORITY 15 +#define STM32_EXT_EXTI18_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI19_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI20_IRQ_PRIORITY 6 +#define STM32_EXT_EXTI21_IRQ_PRIORITY 15 +#define STM32_EXT_EXTI22_IRQ_PRIORITY 15 + +/* + * GPT driver system settings. + */ +#define STM32_GPT_USE_TIM1 FALSE +#define STM32_GPT_USE_TIM2 FALSE +#define STM32_GPT_USE_TIM3 FALSE +#define STM32_GPT_USE_TIM4 FALSE +#define STM32_GPT_USE_TIM5 FALSE +#define STM32_GPT_USE_TIM6 FALSE +#define STM32_GPT_USE_TIM7 FALSE +#define STM32_GPT_USE_TIM8 FALSE +#define STM32_GPT_USE_TIM9 FALSE +#define STM32_GPT_USE_TIM11 FALSE +#define STM32_GPT_USE_TIM12 FALSE +#define STM32_GPT_USE_TIM14 FALSE +#define STM32_GPT_TIM1_IRQ_PRIORITY 7 +#define STM32_GPT_TIM2_IRQ_PRIORITY 7 +#define STM32_GPT_TIM3_IRQ_PRIORITY 7 +#define STM32_GPT_TIM4_IRQ_PRIORITY 7 +#define STM32_GPT_TIM5_IRQ_PRIORITY 7 +#define STM32_GPT_TIM6_IRQ_PRIORITY 7 +#define STM32_GPT_TIM7_IRQ_PRIORITY 7 +#define STM32_GPT_TIM8_IRQ_PRIORITY 7 +#define STM32_GPT_TIM9_IRQ_PRIORITY 7 +#define STM32_GPT_TIM11_IRQ_PRIORITY 7 +#define STM32_GPT_TIM12_IRQ_PRIORITY 7 +#define STM32_GPT_TIM14_IRQ_PRIORITY 7 + +/* + * I2C driver system settings. + */ +#define STM32_I2C_USE_I2C1 FALSE +#define STM32_I2C_USE_I2C2 FALSE +#define STM32_I2C_USE_I2C3 FALSE +#define STM32_I2C_I2C1_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_I2C_I2C1_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6) +#define STM32_I2C_I2C2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_I2C_I2C2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_I2C_I2C3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_I2C_I2C3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_I2C_I2C1_IRQ_PRIORITY 5 +#define STM32_I2C_I2C2_IRQ_PRIORITY 5 +#define STM32_I2C_I2C3_IRQ_PRIORITY 5 +#define STM32_I2C_I2C1_DMA_PRIORITY 3 +#define STM32_I2C_I2C2_DMA_PRIORITY 3 +#define STM32_I2C_I2C3_DMA_PRIORITY 3 +#define STM32_I2C_I2C1_DMA_ERROR_HOOK() chSysHalt() +#define STM32_I2C_I2C2_DMA_ERROR_HOOK() chSysHalt() +#define STM32_I2C_I2C3_DMA_ERROR_HOOK() chSysHalt() + +/* + * ICU driver system settings. + */ +#define STM32_ICU_USE_TIM1 FALSE +#define STM32_ICU_USE_TIM2 FALSE +#define STM32_ICU_USE_TIM3 FALSE +#define STM32_ICU_USE_TIM4 FALSE +#define STM32_ICU_USE_TIM5 FALSE +#define STM32_ICU_USE_TIM8 FALSE +#define STM32_ICU_USE_TIM9 FALSE +#define STM32_ICU_TIM1_IRQ_PRIORITY 7 +#define STM32_ICU_TIM2_IRQ_PRIORITY 7 +#define STM32_ICU_TIM3_IRQ_PRIORITY 7 +#define STM32_ICU_TIM4_IRQ_PRIORITY 7 +#define STM32_ICU_TIM5_IRQ_PRIORITY 7 +#define STM32_ICU_TIM8_IRQ_PRIORITY 7 +#define STM32_ICU_TIM9_IRQ_PRIORITY 7 + +/* + * MAC driver system settings. + */ +#define STM32_MAC_TRANSMIT_BUFFERS 2 +#define STM32_MAC_RECEIVE_BUFFERS 4 +#define STM32_MAC_BUFFERS_SIZE 1522 +#define STM32_MAC_PHY_TIMEOUT 100 +#define STM32_MAC_ETH1_CHANGE_PHY_STATE TRUE +#define STM32_MAC_ETH1_IRQ_PRIORITY 13 +#define STM32_MAC_IP_CHECKSUM_OFFLOAD 0 + +/* + * PWM driver system settings. + */ +#define STM32_PWM_USE_ADVANCED FALSE +#define STM32_PWM_USE_TIM1 FALSE +#define STM32_PWM_USE_TIM2 FALSE +#define STM32_PWM_USE_TIM3 FALSE +#define STM32_PWM_USE_TIM4 FALSE +#define STM32_PWM_USE_TIM5 FALSE +#define STM32_PWM_USE_TIM8 FALSE +#define STM32_PWM_USE_TIM9 FALSE +#define STM32_PWM_TIM1_IRQ_PRIORITY 7 +#define STM32_PWM_TIM2_IRQ_PRIORITY 7 +#define STM32_PWM_TIM3_IRQ_PRIORITY 7 +#define STM32_PWM_TIM4_IRQ_PRIORITY 7 +#define STM32_PWM_TIM5_IRQ_PRIORITY 7 +#define STM32_PWM_TIM8_IRQ_PRIORITY 7 +#define STM32_PWM_TIM9_IRQ_PRIORITY 7 + +/* + * SERIAL driver system settings. + */ +#define STM32_SERIAL_USE_USART1 FALSE +#define STM32_SERIAL_USE_USART2 FALSE +#define STM32_SERIAL_USE_USART3 FALSE +#define STM32_SERIAL_USE_UART4 FALSE +#define STM32_SERIAL_USE_UART5 FALSE +#define STM32_SERIAL_USE_USART6 FALSE +#define STM32_SERIAL_USART1_PRIORITY 12 +#define STM32_SERIAL_USART2_PRIORITY 12 +#define STM32_SERIAL_USART3_PRIORITY 12 +#define STM32_SERIAL_UART4_PRIORITY 12 +#define STM32_SERIAL_UART5_PRIORITY 12 +#define STM32_SERIAL_USART6_PRIORITY 12 + +/* + * SPI driver system settings. + */ +#define STM32_SPI_USE_SPI1 FALSE +#define STM32_SPI_USE_SPI2 FALSE +#define STM32_SPI_USE_SPI3 FALSE +#define STM32_SPI_SPI1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 0) +#define STM32_SPI_SPI1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 3) +#define STM32_SPI_SPI2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) +#define STM32_SPI_SPI2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_SPI_SPI3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_SPI_SPI3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_SPI_SPI1_DMA_PRIORITY 1 +#define STM32_SPI_SPI2_DMA_PRIORITY 1 +#define STM32_SPI_SPI3_DMA_PRIORITY 1 +#define STM32_SPI_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI_SPI3_IRQ_PRIORITY 10 +#define STM32_SPI_DMA_ERROR_HOOK(spip) chSysHalt() + +/* + * UART driver system settings. + */ +#define STM32_UART_USE_USART1 FALSE +#define STM32_UART_USE_USART2 FALSE +#define STM32_UART_USE_USART3 FALSE +#define STM32_UART_USE_UART4 FALSE +#define STM32_UART_USE_UART5 FALSE +#define STM32_UART_USE_USART6 FALSE +#define STM32_UART_USART1_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 5) +#define STM32_UART_USART1_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7) +#define STM32_UART_USART2_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 5) +#define STM32_UART_USART2_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 6) +#define STM32_UART_USART3_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 1) +#define STM32_UART_USART3_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 3) +#define STM32_UART_UART4_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 2) +#define STM32_UART_UART4_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 4) +#define STM32_UART_UART5_RX_DMA_STREAM STM32_DMA_STREAM_ID(1, 0) +#define STM32_UART_UART5_TX_DMA_STREAM STM32_DMA_STREAM_ID(1, 7) +#define STM32_UART_USART6_RX_DMA_STREAM STM32_DMA_STREAM_ID(2, 2) +#define STM32_UART_USART6_TX_DMA_STREAM STM32_DMA_STREAM_ID(2, 7) +#define STM32_UART_USART1_IRQ_PRIORITY 12 +#define STM32_UART_USART2_IRQ_PRIORITY 12 +#define STM32_UART_USART3_IRQ_PRIORITY 12 +#define STM32_UART_UART4_IRQ_PRIORITY 12 +#define STM32_UART_UART5_IRQ_PRIORITY 12 +#define STM32_UART_USART6_IRQ_PRIORITY 12 +#define STM32_UART_USART1_DMA_PRIORITY 0 +#define STM32_UART_USART2_DMA_PRIORITY 0 +#define STM32_UART_USART3_DMA_PRIORITY 0 +#define STM32_UART_UART4_DMA_PRIORITY 0 +#define STM32_UART_UART5_DMA_PRIORITY 0 +#define STM32_UART_USART6_DMA_PRIORITY 0 +#define STM32_UART_DMA_ERROR_HOOK(uartp) chSysHalt() + +/* + * USB driver system settings. + */ +#define STM32_USB_USE_OTG1 FALSE +#define STM32_USB_USE_OTG2 FALSE +#define STM32_USB_OTG1_IRQ_PRIORITY 14 +#define STM32_USB_OTG2_IRQ_PRIORITY 14 +#define STM32_USB_OTG1_RX_FIFO_SIZE 512 +#define STM32_USB_OTG2_RX_FIFO_SIZE 1024 +#define STM32_USB_OTG_THREAD_PRIO LOWPRIO +#define STM32_USB_OTG_THREAD_STACK_SIZE 128 +#define STM32_USB_OTGFIFO_FILL_BASEPRI 0 diff --git a/flight/targets/sparky2/fw/memory.ld b/flight/targets/sparky2/fw/memory.ld new file mode 100644 index 00000000000..a7613805595 --- /dev/null +++ b/flight/targets/sparky2/fw/memory.ld @@ -0,0 +1,10 @@ +__main_stack_size__ = 0x0400; +__process_stack_size__ = 0x0400; + +MEMORY +{ + bd_info (r) : org = 0x08008000 - 0x80, len = 0x000080 + flash : org = 0x08000000 + 128k, len = 384k + ram : org = 0x20000000, len = 128k + ccmram : org = 0x10000000, len = 64k +} diff --git a/flight/targets/sparky2/fw/pios_board.c b/flight/targets/sparky2/fw/pios_board.c index 2c9e6767e1f..15221c2ce48 100644 --- a/flight/targets/sparky2/fw/pios_board.c +++ b/flight/targets/sparky2/fw/pios_board.c @@ -37,6 +37,7 @@ #include "board_hw_defs.c" #include +#include #include #include #include "hwsparky2.h" @@ -126,66 +127,11 @@ static const struct pios_hmc5883_cfg pios_hmc5883_external_cfg = { }; #endif /* PIOS_INCLUDE_HMC5883 */ -/* One slot per selectable receiver group. - * eg. PWM, PPM, GCS, SPEKTRUM1, SPEKTRUM2, SBUS - * NOTE: No slot in this map for NONE. - */ -uintptr_t pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_NONE]; - -#define PIOS_COM_TELEM_RF_RX_BUF_LEN 512 -#define PIOS_COM_TELEM_RF_TX_BUF_LEN 512 - -#define PIOS_COM_GPS_RX_BUF_LEN 32 -#define PIOS_COM_GPS_TX_BUF_LEN 16 - -#define PIOS_COM_TELEM_USB_RX_BUF_LEN 65 -#define PIOS_COM_TELEM_USB_TX_BUF_LEN 65 - -#define PIOS_COM_BRIDGE_RX_BUF_LEN 65 -#define PIOS_COM_BRIDGE_TX_BUF_LEN 12 - -#define PIOS_COM_MAVLINK_TX_BUF_LEN 128 - -#define PIOS_COM_HOTT_RX_BUF_LEN 16 -#define PIOS_COM_HOTT_TX_BUF_LEN 16 - -#define PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN 128 - -#define PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN 19 - -#define PIOS_COM_PICOC_RX_BUF_LEN 128 -#define PIOS_COM_PICOC_TX_BUF_LEN 128 - -#define PIOS_COM_FRSKYSPORT_TX_BUF_LEN 16 -#define PIOS_COM_FRSKYSPORT_RX_BUF_LEN 16 - -#define PIOS_COM_RFM22B_RF_RX_BUF_LEN 512 -#define PIOS_COM_RFM22B_RF_TX_BUF_LEN 512 - #define PIOS_COM_CAN_RX_BUF_LEN 256 #define PIOS_COM_CAN_TX_BUF_LEN 256 -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) -#define PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN 40 -uintptr_t pios_com_debug_id; -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - -uintptr_t pios_com_gps_id; -uintptr_t pios_com_telem_usb_id; -uintptr_t pios_com_telem_rf_id; -uintptr_t pios_com_vcp_id; -uintptr_t pios_com_bridge_id; -uintptr_t pios_com_overo_id; -uintptr_t pios_com_mavlink_id; -uintptr_t pios_com_hott_id; -uintptr_t pios_com_frsky_sensor_hub_id; -uintptr_t pios_com_frsky_sport_id; -uintptr_t pios_com_lighttelemetry_id; -uintptr_t pios_com_picoc_id; uintptr_t pios_com_logging_id; -uintptr_t pios_com_rf_id; uintptr_t pios_com_can_id; -uint32_t pios_rfm22b_id; uintptr_t pios_internal_adc_id = 0; uintptr_t pios_uavo_settings_fs_id; uintptr_t pios_waypoints_settings_fs_id; @@ -194,92 +140,6 @@ uintptr_t pios_can_id; uintptr_t streamfs_id; -/* - * Setup a com port based on the passed cfg, driver and buffer sizes. rx or tx size of 0 disables rx or tx - */ -#if defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) -static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cfg, size_t rx_buf_len, size_t tx_buf_len, - const struct pios_com_driver *com_driver, uintptr_t *pios_com_id) -{ - uintptr_t pios_usart_id; - if (PIOS_USART_Init(&pios_usart_id, usart_port_cfg)) { - PIOS_Assert(0); - } - - uint8_t * rx_buffer; - if (rx_buf_len > 0) { - rx_buffer = (uint8_t *) PIOS_malloc(rx_buf_len); - PIOS_Assert(rx_buffer); - } else { - rx_buffer = NULL; - } - - uint8_t * tx_buffer; - if (tx_buf_len > 0) { - tx_buffer = (uint8_t *) PIOS_malloc(tx_buf_len); - PIOS_Assert(tx_buffer); - } else { - tx_buffer = NULL; - } - - if (PIOS_COM_Init(pios_com_id, com_driver, pios_usart_id, - rx_buffer, rx_buf_len, - tx_buffer, tx_buf_len)) { - PIOS_Assert(0); - } -} -#endif /* PIOS_INCLUDE_USART && PIOS_INCLUDE_COM */ - -#ifdef PIOS_INCLUDE_DSM -static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, - const struct pios_dsm_cfg *pios_dsm_cfg, - const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup, uint8_t *bind) -{ - uintptr_t pios_usart_dsm_id; - if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_id; - if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { - PIOS_Assert(0); - } - - uintptr_t pios_dsm_rcvr_id; - if (PIOS_RCVR_Init(&pios_dsm_rcvr_id, &pios_dsm_rcvr_driver, pios_dsm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_dsm_rcvr_id; -} - -#endif - -#ifdef PIOS_INCLUDE_HSUM -static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hsum_cfg, - const struct pios_com_driver *pios_usart_com_driver,enum pios_hsum_proto *proto, - ManualControlSettingsChannelGroupsOptions channelgroup) -{ - uintptr_t pios_usart_hsum_id; - if (PIOS_USART_Init(&pios_usart_hsum_id, pios_usart_hsum_cfg)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_id; - if (PIOS_HSUM_Init(&pios_hsum_id, pios_usart_com_driver, - pios_usart_hsum_id, *proto)) { - PIOS_Assert(0); - } - - uintptr_t pios_hsum_rcvr_id; - if (PIOS_RCVR_Init(&pios_hsum_rcvr_id, &pios_hsum_rcvr_driver, pios_hsum_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[channelgroup] = pios_hsum_rcvr_id; -} -#endif - /** * Indicate a target-specific error code when a component fails to initialize * 1 pulse - flash chip @@ -288,22 +148,7 @@ static void PIOS_Board_configure_hsum(const struct pios_usart_cfg *pios_usart_hs * 6 pulses - external mag */ static void panic(int32_t code) { - while(1){ - for (int32_t i = 0; i < code; i++) { - PIOS_WDG_Clear(); - PIOS_LED_Toggle(PIOS_LED_ALARM); - PIOS_DELAY_WaitmS(200); - PIOS_WDG_Clear(); - PIOS_LED_Toggle(PIOS_LED_ALARM); - PIOS_DELAY_WaitmS(200); - } - PIOS_DELAY_WaitmS(200); - PIOS_WDG_Clear(); - PIOS_DELAY_WaitmS(200); - PIOS_WDG_Clear(); - PIOS_DELAY_WaitmS(100); - PIOS_WDG_Clear(); - } + PIOS_HAL_Panic(PIOS_LED_ALARM, code); } void set_vtx_channel(HwSparky2VTX_ChOptions channel) @@ -557,75 +402,8 @@ void PIOS_Board_Init(void) { hw_usb_vcpport = HWSPARKY2_USB_VCPPORT_DISABLED; } - uintptr_t pios_usb_cdc_id; - if (PIOS_USB_CDC_Init(&pios_usb_cdc_id, &pios_usb_cdc_cfg, pios_usb_id)) { - PIOS_Assert(0); - } + PIOS_HAL_ConfigureCDC(hw_usb_vcpport, pios_usb_id, &pios_usb_cdc_cfg); - switch (hw_usb_vcpport) { - case HWSPARKY2_USB_VCPPORT_DISABLED: - break; - case HWSPARKY2_USB_VCPPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWSPARKY2_USB_VCPPORT_COMBRIDGE: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_BRIDGE_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_vcp_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_BRIDGE_RX_BUF_LEN, - tx_buffer, PIOS_COM_BRIDGE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - case HWSPARKY2_USB_VCPPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_COM) -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_debug_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - NULL, 0, - tx_buffer, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ -#endif /* PIOS_INCLUDE_COM */ - break; - case HWSPARKY2_USB_VCPPORT_PICOC: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_PICOC_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_picoc_id, &pios_usb_cdc_com_driver, pios_usb_cdc_id, - rx_buffer, PIOS_COM_PICOC_RX_BUF_LEN, - tx_buffer, PIOS_COM_PICOC_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } #endif /* PIOS_INCLUDE_USB_CDC */ #if defined(PIOS_INCLUDE_USB_HID) @@ -638,30 +416,7 @@ void PIOS_Board_Init(void) { hw_usb_hidport = HWSPARKY2_USB_HIDPORT_DISABLED; } - uintptr_t pios_usb_hid_id; - if (PIOS_USB_HID_Init(&pios_usb_hid_id, &pios_usb_hid_cfg, pios_usb_id)) { - PIOS_Assert(0); - } - - switch (hw_usb_hidport) { - case HWSPARKY2_USB_HIDPORT_DISABLED: - break; - case HWSPARKY2_USB_HIDPORT_USBTELEMETRY: -#if defined(PIOS_INCLUDE_COM) - { - uint8_t * rx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_RX_BUF_LEN); - uint8_t * tx_buffer = (uint8_t *) PIOS_malloc(PIOS_COM_TELEM_USB_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_telem_usb_id, &pios_usb_hid_com_driver, pios_usb_hid_id, - rx_buffer, PIOS_COM_TELEM_USB_RX_BUF_LEN, - tx_buffer, PIOS_COM_TELEM_USB_TX_BUF_LEN)) { - PIOS_Assert(0); - } - } -#endif /* PIOS_INCLUDE_COM */ - break; - } + PIOS_HAL_ConfigureHID(hw_usb_hidport, pios_usb_id, &pios_usb_hid_cfg); #endif /* PIOS_INCLUDE_USB_HID */ @@ -671,354 +426,45 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure IO ports */ - uint8_t hw_DSMxBind; - HwSparky2DSMxBindGet(&hw_DSMxBind); + HwSparky2DSMxModeOptions hw_DSMxMode; + HwSparky2DSMxModeGet(&hw_DSMxMode); /* Configure main USART port */ uint8_t hw_mainport; HwSparky2MainPortGet(&hw_mainport); - switch (hw_mainport) { - case HWSPARKY2_MAINPORT_DISABLED: - break; - case HWSPARKY2_MAINPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWSPARKY2_MAINPORT_GPS: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWSPARKY2_MAINPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - { - // Force binding to zero on the main port - hw_DSMxBind = 0; - - //TODO: Define the various Channelgroup for dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_main_cfg, &pios_dsm_main_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT,&hw_DSMxBind); - } -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWSPARKY2_MAINPORT_HOTTSUMD: - case HWSPARKY2_MAINPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_mainport) { - case HWSPARKY2_MAINPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWSPARKY2_MAINPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_main_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWSPARKY2_MAINPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWSPARKY2_MAINPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWSPARKY2_MAINPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWSPARKY2_MAINPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; - #endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWSPARKY2_MAINPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWSPARKY2_MAINPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWSPARKY2_MAINPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWSPARKY2_MAINPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - break; - case HWSPARKY2_MAINPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_main_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - } /* hw_mainport */ + + PIOS_HAL_ConfigurePort(hw_mainport, &pios_usart_main_cfg, + &pios_usart_com_driver, NULL, NULL, NULL, + PIOS_LED_ALARM, + &pios_usart_dsm_hsum_main_cfg, &pios_dsm_main_cfg, + hw_DSMxMode, NULL, NULL, false); /* Configure FlexiPort */ uint8_t hw_flexiport; HwSparky2FlexiPortGet(&hw_flexiport); - switch (hw_flexiport) { - case HWSPARKY2_FLEXIPORT_DISABLED: - break; - case HWSPARKY2_FLEXIPORT_TELEMETRY: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_TELEM_RF_RX_BUF_LEN, PIOS_COM_TELEM_RF_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_telem_rf_id); - break; - case HWSPARKY2_FLEXIPORT_I2C: -#if defined(PIOS_INCLUDE_I2C) - { - if (PIOS_I2C_Init(&pios_i2c_flexiport_adapter_id, &pios_i2c_flexiport_adapter_cfg)) { - PIOS_Assert(0); - } - if (PIOS_I2C_CheckClear(pios_i2c_flexiport_adapter_id) != 0) - panic(6); - } -#endif /* PIOS_INCLUDE_I2C */ - break; - case HWSPARKY2_FLEXIPORT_GPS: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_GPS_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - break; - case HWSPARKY2_FLEXIPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - //TODO: Define the various Channelgroup for dsm inputs and handle here - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, - &pios_usart_com_driver, MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT,&hw_DSMxBind); - break; -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWSPARKY2_FLEXIPORT_HOTTSUMD: - case HWSPARKY2_FLEXIPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_flexiport) { - case HWSPARKY2_FLEXIPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWSPARKY2_FLEXIPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_flexi_cfg, &pios_usart_com_driver, &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWSPARKY2_FLEXIPORT_DEBUGCONSOLE: -#if defined(PIOS_INCLUDE_DEBUG_CONSOLE) - { - PIOS_Board_configure_com(&pios_usart_main_cfg, 0, PIOS_COM_DEBUGCONSOLE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_debug_id); - } -#endif /* PIOS_INCLUDE_DEBUG_CONSOLE */ - break; - case HWSPARKY2_FLEXIPORT_COMBRIDGE: - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_BRIDGE_RX_BUF_LEN, PIOS_COM_BRIDGE_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_bridge_id); - break; - case HWSPARKY2_FLEXIPORT_MAVLINKTX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_mavlink_id); -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWSPARKY2_FLEXIPORT_MAVLINKTX_GPS_RX: -#if defined(PIOS_INCLUDE_MAVLINK) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_GPS_RX_BUF_LEN, PIOS_COM_MAVLINK_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_gps_id); - pios_com_mavlink_id = pios_com_gps_id; -#endif /* PIOS_INCLUDE_MAVLINK */ - break; - case HWSPARKY2_FLEXIPORT_HOTTTELEMETRY: -#if defined(PIOS_INCLUDE_HOTT) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_HOTT_RX_BUF_LEN, PIOS_COM_HOTT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_hott_id); -#endif /* PIOS_INCLUDE_HOTT */ - break; - case HWSPARKY2_FLEXIPORT_FRSKYSENSORHUB: -#if defined(PIOS_INCLUDE_FRSKY_SENSOR_HUB) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_FRSKYSENSORHUB_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sensor_hub_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWSPARKY2_FLEXIPORT_FRSKYSPORTTELEMETRY: -#if defined(PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_FRSKYSPORT_RX_BUF_LEN, PIOS_COM_FRSKYSPORT_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_frsky_sport_id); -#endif /* PIOS_INCLUDE_FRSKY_SENSOR_HUB */ - break; - case HWSPARKY2_FLEXIPORT_LIGHTTELEMETRYTX: -#if defined(PIOS_INCLUDE_LIGHTTELEMETRY) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, 0, PIOS_COM_LIGHTTELEMETRY_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_lighttelemetry_id); -#endif - case HWSPARKY2_FLEXIPORT_PICOC: -#if defined(PIOS_INCLUDE_PICOC) && defined(PIOS_INCLUDE_USART) && defined(PIOS_INCLUDE_COM) - PIOS_Board_configure_com(&pios_usart_flexi_cfg, PIOS_COM_PICOC_RX_BUF_LEN, PIOS_COM_PICOC_TX_BUF_LEN, &pios_usart_com_driver, &pios_com_picoc_id); -#endif /* PIOS_INCLUDE_PICOC */ - break; - } /* hwsettings_rv_flexiport */ + PIOS_HAL_ConfigurePort(hw_flexiport, &pios_usart_flexi_cfg, + &pios_usart_com_driver, + &pios_i2c_flexiport_adapter_id, + &pios_i2c_flexiport_adapter_cfg, NULL, + PIOS_LED_ALARM, + &pios_usart_dsm_hsum_flexi_cfg, &pios_dsm_flexi_cfg, + hw_DSMxMode, NULL, NULL, false); #if defined(PIOS_INCLUDE_RFM22B) - /* Initalize the RFM22B radio COM device. */ - RFM22BStatusInitialize(); - RFM22BStatusCreateInstance(); - - RFM22BStatusData rfm22bstatus; - RFM22BStatusGet(&rfm22bstatus); - RFM22BStatusInstSet(1,&rfm22bstatus); - - HwSparky2Data hwSparky2; HwSparky2Get(&hwSparky2); - // Initialize out status object. - rfm22bstatus.BoardType = bdinfo->board_type; - rfm22bstatus.BoardRevision = bdinfo->board_rev; - - if (hwSparky2.Radio == HWSPARKY2_RADIO_OPENLRS) { - uintptr_t openlrs_id; - - const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev); - PIOS_OpenLRS_Init(&openlrs_id, PIOS_RFM22_SPI_PORT, 0, openlrs_cfg); - -#if defined(PIOS_INCLUDE_OPENLRS_RCVR) - { - uintptr_t pios_rfm22brcvr_id; - PIOS_OpenLRS_Rcvr_Init(&pios_rfm22brcvr_id, openlrs_id); - uintptr_t pios_rfm22brcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_rfm22brcvr_rcvr_id, &pios_openlrs_rcvr_driver, pios_rfm22brcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_OPENLRS] = pios_rfm22brcvr_rcvr_id; - } -#endif /* PIOS_INCLUDE_OPENLRS_RCVR */ - } else if (hwSparky2.Radio == HWSPARKY2_RADIO_DISABLED || hwSparky2.MaxRfPower == HWSPARKY2_MAXRFPOWER_0) { - - // When radio disabled, it is ok for init to fail. This allows boards without populating - // this component. - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg) == 0) { - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - } else { - pios_rfm22b_id = 0; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_DISABLED; - - } else { - - // always allow receiving PPM when radio is on - bool ppm_mode = hwSparky2.Radio == HWSPARKY2_RADIO_TELEMPPM || hwSparky2.Radio == HWSPARKY2_RADIO_PPM; - bool ppm_only = hwSparky2.Radio == HWSPARKY2_RADIO_PPM; - bool is_oneway = hwSparky2.Radio == HWSPARKY2_RADIO_PPM; // Sparky2 can only receive PPM only + const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - /* Configure the RFM22B device. */ - const struct pios_rfm22b_cfg *rfm22b_cfg = PIOS_BOARD_HW_DEFS_GetRfm22Cfg(bdinfo->board_rev); - if (PIOS_RFM22B_Init(&pios_rfm22b_id, PIOS_RFM22_SPI_PORT, rfm22b_cfg->slave_num, rfm22b_cfg)) { - PIOS_Assert(0); - } + const struct pios_openlrs_cfg *openlrs_cfg = PIOS_BOARD_HW_DEFS_GetOpenLRSCfg(bdinfo->board_rev); - rfm22bstatus.DeviceID = PIOS_RFM22B_DeviceID(pios_rfm22b_id); - rfm22bstatus.BoardRevision = PIOS_RFM22B_ModuleVersion(pios_rfm22b_id); - - /* Configure the radio com interface */ - uint8_t *rx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_RX_BUF_LEN); - uint8_t *tx_buffer = (uint8_t *)PIOS_malloc(PIOS_COM_RFM22B_RF_TX_BUF_LEN); - PIOS_Assert(rx_buffer); - PIOS_Assert(tx_buffer); - if (PIOS_COM_Init(&pios_com_rf_id, &pios_rfm22b_com_driver, pios_rfm22b_id, - rx_buffer, PIOS_COM_RFM22B_RF_RX_BUF_LEN, - tx_buffer, PIOS_COM_RFM22B_RF_TX_BUF_LEN)) { - PIOS_Assert(0); - } - - /* Set Telemetry to use RFM22b if no other telemetry is configured (USB always overrides anyway) */ - if (!pios_com_telem_rf_id) { - pios_com_telem_rf_id = pios_com_rf_id; - } - rfm22bstatus.LinkState = RFM22BSTATUS_LINKSTATE_ENABLED; - - enum rfm22b_datarate datarate = RFM22_datarate_64000; - switch (hwSparky2.MaxRfSpeed) { - case HWSPARKY2_MAXRFSPEED_9600: - datarate = RFM22_datarate_9600; - break; - case HWSPARKY2_MAXRFSPEED_19200: - datarate = RFM22_datarate_19200; - break; - case HWSPARKY2_MAXRFSPEED_32000: - datarate = RFM22_datarate_32000; - break; - case HWSPARKY2_MAXRFSPEED_64000: - datarate = RFM22_datarate_64000; - break; - case HWSPARKY2_MAXRFSPEED_100000: - datarate = RFM22_datarate_100000; - break; - case HWSPARKY2_MAXRFSPEED_192000: - datarate = RFM22_datarate_192000; - break; - } - - /* Set the radio configuration parameters. */ - PIOS_RFM22B_Config(pios_rfm22b_id, datarate, hwSparky2.MinChannel, hwSparky2.MaxChannel, hwSparky2.CoordID, is_oneway, ppm_mode, ppm_only); - - /* Set the modem Tx poer level */ - switch (hwSparky2.MaxRfPower) { - case HWSPARKY2_MAXRFPOWER_125: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_0); - break; - case HWSPARKY2_MAXRFPOWER_16: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_1); - break; - case HWSPARKY2_MAXRFPOWER_316: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_2); - break; - case HWSPARKY2_MAXRFPOWER_63: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_3); - break; - case HWSPARKY2_MAXRFPOWER_126: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_4); - break; - case HWSPARKY2_MAXRFPOWER_25: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_5); - break; - case HWSPARKY2_MAXRFPOWER_50: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_6); - break; - case HWSPARKY2_MAXRFPOWER_100: - PIOS_RFM22B_SetTxPower(pios_rfm22b_id, RFM22_tx_pwr_txpow_7); - break; - default: - // do nothing - break; - } - - /* Reinitialize the modem. */ - PIOS_RFM22B_Reinit(pios_rfm22b_id); - -#if defined(PIOS_INCLUDE_RFM22B_RCVR) - { - uintptr_t pios_rfm22brcvr_id; - PIOS_RFM22B_Rcvr_Init(&pios_rfm22brcvr_id, pios_rfm22b_id); - uintptr_t pios_rfm22brcvr_rcvr_id; - if (PIOS_RCVR_Init(&pios_rfm22brcvr_rcvr_id, &pios_rfm22b_rcvr_driver, pios_rfm22brcvr_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_RFM22B] = pios_rfm22brcvr_rcvr_id; - } - } - - RFM22BStatusInstSet(1,&rfm22bstatus); -#endif /* PIOS_INCLUDE_RFM22B_RCVR */ + PIOS_HAL_ConfigureRFM22B(hwSparky2.Radio, + bdinfo->board_type, bdinfo->board_rev, + hwSparky2.MaxRfPower, hwSparky2.MaxRfSpeed, + openlrs_cfg, rfm22b_cfg, + hwSparky2.MinChannel, hwSparky2.MaxChannel, + hwSparky2.CoordID, 1); #endif /* PIOS_INCLUDE_RFM22B */ @@ -1026,88 +472,20 @@ void PIOS_Board_Init(void) { uint8_t hw_rcvrport; HwSparky2RcvrPortGet(&hw_rcvrport); - switch (hw_rcvrport){ - case HWSPARKY2_RCVRPORT_DISABLED: - break; - case HWSPARKY2_RCVRPORT_PPM: -#if defined(PIOS_INCLUDE_PPM) - { - uintptr_t pios_ppm_id; - PIOS_PPM_Init(&pios_ppm_id, &pios_ppm_cfg); - - uintptr_t pios_ppm_rcvr_id; - if (PIOS_RCVR_Init(&pios_ppm_rcvr_id, &pios_ppm_rcvr_driver, pios_ppm_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_PPM] = pios_ppm_rcvr_id; - } -#endif /* PIOS_INCLUDE_PPM */ - break; - case HWSPARKY2_RCVRPORT_DSM: -#if defined(PIOS_INCLUDE_DSM) - switch (bdinfo->board_rev) { - case BRUSHEDSPARKY_V0_2: - break; - default: - hw_DSMxBind = 0; // Do not attempt to bind pulse through XOR - break; - } - PIOS_Board_configure_dsm(&pios_usart_dsm_hsum_rcvr_cfg, &pios_dsm_rcvr_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMRCVRPORT, &hw_DSMxBind); - break; -#endif /* PIOS_INCLUDE_DSM */ - break; - case HWSPARKY2_RCVRPORT_HOTTSUMD: - case HWSPARKY2_RCVRPORT_HOTTSUMH: -#if defined(PIOS_INCLUDE_HSUM) - { - enum pios_hsum_proto proto; - switch (hw_rcvrport) { - case HWSPARKY2_RCVRPORT_HOTTSUMD: - proto = PIOS_HSUM_PROTO_SUMD; - break; - case HWSPARKY2_RCVRPORT_HOTTSUMH: - proto = PIOS_HSUM_PROTO_SUMH; - break; - default: - PIOS_Assert(0); - break; - } - PIOS_Board_configure_hsum(&pios_usart_dsm_hsum_rcvr_cfg, &pios_usart_com_driver, - &proto, MANUALCONTROLSETTINGS_CHANNELGROUPS_HOTTSUM); - } -#endif /* PIOS_INCLUDE_HSUM */ - break; - case HWSPARKY2_RCVRPORT_SBUS: -#if defined(PIOS_INCLUDE_SBUS) && defined(PIOS_INCLUDE_USART) - { - uintptr_t pios_usart_sbus_id; - if (PIOS_USART_Init(&pios_usart_sbus_id, get_sbus_rcvr_cfg(bdinfo->board_rev))) { - PIOS_Assert(0); - } - uintptr_t pios_sbus_id; - if (PIOS_SBus_Init(&pios_sbus_id, &pios_sbus_cfg, &pios_usart_com_driver, pios_usart_sbus_id)) { - PIOS_Assert(0); - } - uintptr_t pios_sbus_rcvr_id; - if (PIOS_RCVR_Init(&pios_sbus_rcvr_id, &pios_sbus_rcvr_driver, pios_sbus_id)) { - PIOS_Assert(0); - } - pios_rcvr_group_map[MANUALCONTROLSETTINGS_CHANNELGROUPS_SBUS] = pios_sbus_rcvr_id; - } -#endif /* PIOS_INCLUDE_SBUS */ - break; - default: - break; + if (bdinfo->board_rev != BRUSHEDSPARKY_V0_2 && hw_DSMxMode >= HWSPARKY2_DSMXMODE_BIND3PULSES) { + hw_DSMxMode = HWSPARKY2_DSMXMODE_AUTODETECT; /* Do not try to bind through XOR */ } - if (hw_rcvrport != HWSPARKY2_RCVRPORT_SBUS && get_sbus_toggle(bdinfo->board_rev)) { - const struct pios_sbus_cfg * sbus_cfg = get_sbus_toggle(bdinfo->board_rev); - GPIO_Init(sbus_cfg->inv.gpio, (GPIO_InitTypeDef*)&sbus_cfg->inv.init); - GPIO_WriteBit(sbus_cfg->inv.gpio, sbus_cfg->inv.init.GPIO_Pin, sbus_cfg->gpio_inv_disable); - } - - + PIOS_HAL_ConfigurePort(hw_rcvrport, + NULL, /* XXX TODO: fix as part of DSM refactor */ + &pios_usart_com_driver, + NULL, NULL, + &pios_ppm_cfg, + PIOS_LED_ALARM, + &pios_usart_dsm_hsum_rcvr_cfg, + &pios_dsm_rcvr_cfg, + hw_DSMxMode, get_sbus_rcvr_cfg(bdinfo->board_rev), + &pios_sbus_cfg, get_sbus_toggle(bdinfo->board_rev)); #if defined(PIOS_INCLUDE_GCSRCVR) GCSReceiverInitialize(); @@ -1145,7 +523,7 @@ void PIOS_Board_Init(void) { tx_buffer, PIOS_COM_CAN_TX_BUF_LEN)) panic(6); - pios_com_bridge_id = pios_com_can_id; + /* pios_com_bridge_id = pios_com_can_id; */ } #endif @@ -1219,7 +597,6 @@ void PIOS_Board_Init(void) { uint8_t hw_mpu9250_dlpf; HwSparky2MPU9250GyroLPFGet(&hw_mpu9250_dlpf); enum pios_mpu9250_gyro_filter mpu9250_gyro_lpf = \ - (hw_mpu9250_dlpf == HWSPARKY2_MPU9250GYROLPF_250) ? PIOS_MPU9250_GYRO_LOWPASS_250_HZ : \ (hw_mpu9250_dlpf == HWSPARKY2_MPU9250GYROLPF_184) ? PIOS_MPU9250_GYRO_LOWPASS_184_HZ : \ (hw_mpu9250_dlpf == HWSPARKY2_MPU9250GYROLPF_92) ? PIOS_MPU9250_GYRO_LOWPASS_92_HZ : \ (hw_mpu9250_dlpf == HWSPARKY2_MPU9250GYROLPF_41) ? PIOS_MPU9250_GYRO_LOWPASS_41_HZ : \ diff --git a/flight/targets/sparky2/fw/pios_config.h b/flight/targets/sparky2/fw/pios_config.h index d5fa9c741fc..a099ce4de85 100644 --- a/flight/targets/sparky2/fw/pios_config.h +++ b/flight/targets/sparky2/fw/pios_config.h @@ -32,7 +32,7 @@ #define PIOS_CONFIG_H /* Major features */ -#define PIOS_INCLUDE_FREERTOS +#define PIOS_INCLUDE_CHIBIOS #define PIOS_INCLUDE_BL_HELPER /* Enable/Disable PiOS Modules */ @@ -89,6 +89,7 @@ #define PIOS_INCLUDE_SESSION_MANAGEMENT //#define PIOS_INCLUDE_LIGHTTELEMETRY #define PIOS_INCLUDE_PICOC +#define PIOS_INCLUDE_FRSKY_SPORT_TELEMETRY /* Supported receiver interfaces */ #define PIOS_INCLUDE_RCVR @@ -133,9 +134,7 @@ * configuration like number of task priorities or similar changes. * A change in the cpu load calculation or the idle task handler will invalidate this as well. */ -#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (6984538) - -#define REVOLUTION +#define IDLE_COUNTS_PER_SEC_AT_NO_LOAD (9873737) #endif /* PIOS_CONFIG_H */ /** diff --git a/flight/targets/sparky2/hw/Sparky 2.0.stp b/flight/targets/sparky2/hw/Sparky 2.0.stp index 840763489ed..4fb5588ec71 100644 --- a/flight/targets/sparky2/hw/Sparky 2.0.stp +++ b/flight/targets/sparky2/hw/Sparky 2.0.stp @@ -1,7 +1,7 @@ ISO-10303-21; HEADER; FILE_DESCRIPTION(('Open CASCADE Model'),'2;1'); -FILE_NAME('Open CASCADE Shape Model','2015-04-30T10:39:21',('Author'),( +FILE_NAME('Open CASCADE Shape Model','2015-08-14T10:37:06',('Author'),( 'Open CASCADE'),'Open CASCADE STEP processor 6.2','Open CASCADE 6.2' ,'Unknown'); FILE_SCHEMA(('AUTOMOTIVE_DESIGN { 1 0 10303 214 1 1 1 1 }')); @@ -30,7 +30,7 @@ DATA; #13 = DIRECTION('',(0.E+000,0.E+000,1.)); #14 = DIRECTION('',(1.,0.E+000,0.E+000)); #15 = AXIS2_PLACEMENT_3D('',#16,#17,#18); -#16 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.27838)); +#16 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.6891)); #17 = DIRECTION('',(0.E+000,0.E+000,1.)); #18 = DIRECTION('',(1.,0.E+000,0.E+000)); #19 = AXIS2_PLACEMENT_3D('',#20,#21,#22); @@ -351,14 +351,16 @@ GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#331)) GLOBAL_UNIT_ASSIGNED_CONTEXT #331 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#328, 'distance_accuracy_value','confusion accuracy'); #332 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7)); -#333 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#334),#4642); +#333 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#334),#7034); #334 = MANIFOLD_SOLID_BREP('',#335); #335 = CLOSED_SHELL('',(#336,#456,#532,#608,#684,#760,#836,#912,#988, #1064,#1140,#1216,#1292,#1368,#1444,#1520,#1596,#1672,#1748,#1824, #1900,#1976,#2052,#2128,#2204,#2280,#2356,#2432,#2508,#2584,#2660, #2736,#2812,#2888,#2964,#3040,#3116,#3192,#3268,#3344,#3420,#3496, #3572,#3648,#3724,#3800,#3876,#3952,#4028,#4104,#4180,#4256,#4332, - #4408,#4479,#4526,#4584)); + #4408,#4479,#4526,#4612,#4698,#4784,#4870,#4956,#5042,#5128,#5214, + #5300,#5386,#5472,#5558,#5644,#5730,#5816,#5902,#5988,#6074,#6160, + #6246,#6332,#6418,#6504,#6590,#6676,#6762,#6898)); #336 = ADVANCED_FACE('',(#337),#351,.F.); #337 = FACE_BOUND('',#338,.F.); #338 = EDGE_LOOP('',(#339,#374,#402,#430)); @@ -367,7 +369,7 @@ GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#331)) GLOBAL_UNIT_ASSIGNED_CONTEXT #341 = VERTEX_POINT('',#342); #342 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,0.E+000)); #343 = VERTEX_POINT('',#344); -#344 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,2.29108)); +#344 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,1.7018)); #345 = SURFACE_CURVE('',#346,(#350,#362),.PCURVE_S1.); #346 = LINE('',#347,#348); #347 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,0.E+000)); @@ -404,16 +406,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #374 = ORIENTED_EDGE('',*,*,#375,.T.); #375 = EDGE_CURVE('',#343,#376,#378,.T.); #376 = VERTEX_POINT('',#377); -#377 = CARTESIAN_POINT('',(6.947916E-002,2.3624921,2.29108)); +#377 = CARTESIAN_POINT('',(6.947916E-002,2.3624921,1.7018)); #378 = SURFACE_CURVE('',#379,(#383,#390),.PCURVE_S1.); #379 = LINE('',#380,#381); -#380 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,2.29108)); +#380 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,1.7018)); #381 = VECTOR('',#382,1.); #382 = DIRECTION('',(7.846031821911E-002,-0.99691723752,0.E+000)); #383 = PCURVE('',#351,#384); #384 = DEFINITIONAL_REPRESENTATION('',(#385),#389); #385 = LINE('',#386,#387); -#386 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#386 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #387 = VECTOR('',#388,1.); #388 = DIRECTION('',(1.,0.E+000)); #389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -422,7 +424,7 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #390 = PCURVE('',#391,#396); #391 = PLANE('',#392); #392 = AXIS2_PLACEMENT_3D('',#393,#394,#395); -#393 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,2.29108)); +#393 = CARTESIAN_POINT('',(3.551682000001E-002,2.79401778,1.7018)); #394 = DIRECTION('',(0.E+000,0.E+000,-1.)); #395 = DIRECTION('',(-1.,0.E+000,0.E+000)); #396 = DEFINITIONAL_REPRESENTATION('',(#397),#401); @@ -502,16 +504,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #460 = ORIENTED_EDGE('',*,*,#461,.T.); #461 = EDGE_CURVE('',#376,#462,#464,.T.); #462 = VERTEX_POINT('',#463); -#463 = CARTESIAN_POINT('',(0.17052798,1.94159378,2.29108)); +#463 = CARTESIAN_POINT('',(0.17052798,1.94159378,1.7018)); #464 = SURFACE_CURVE('',#465,(#469,#476),.PCURVE_S1.); #465 = LINE('',#466,#467); -#466 = CARTESIAN_POINT('',(6.947916E-002,2.3624921,2.29108)); +#466 = CARTESIAN_POINT('',(6.947916E-002,2.3624921,1.7018)); #467 = VECTOR('',#468,1.); #468 = DIRECTION('',(0.2334455247,-0.972369881782,0.E+000)); #469 = PCURVE('',#419,#470); #470 = DEFINITIONAL_REPRESENTATION('',(#471),#475); #471 = LINE('',#472,#473); -#472 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#472 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #473 = VECTOR('',#474,1.); #474 = DIRECTION('',(1.,0.E+000)); #475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -590,16 +592,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #536 = ORIENTED_EDGE('',*,*,#537,.T.); #537 = EDGE_CURVE('',#462,#538,#540,.T.); #538 = VERTEX_POINT('',#539); -#539 = CARTESIAN_POINT('',(0.33617662,1.54168348,2.29108)); +#539 = CARTESIAN_POINT('',(0.33617662,1.54168348,1.7018)); #540 = SURFACE_CURVE('',#541,(#545,#552),.PCURVE_S1.); #541 = LINE('',#542,#543); -#542 = CARTESIAN_POINT('',(0.17052798,1.94159378,2.29108)); +#542 = CARTESIAN_POINT('',(0.17052798,1.94159378,1.7018)); #543 = VECTOR('',#544,1.); #544 = DIRECTION('',(0.38268416198,-0.923879230295,0.E+000)); #545 = PCURVE('',#500,#546); #546 = DEFINITIONAL_REPRESENTATION('',(#547),#551); #547 = LINE('',#548,#549); -#548 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#548 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #549 = VECTOR('',#550,1.); #550 = DIRECTION('',(1.,0.E+000)); #551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -678,16 +680,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #612 = ORIENTED_EDGE('',*,*,#613,.T.); #613 = EDGE_CURVE('',#538,#614,#616,.T.); #614 = VERTEX_POINT('',#615); -#615 = CARTESIAN_POINT('',(0.5623433,1.17261132,2.29108)); +#615 = CARTESIAN_POINT('',(0.5623433,1.17261132,1.7018)); #616 = SURFACE_CURVE('',#617,(#621,#628),.PCURVE_S1.); #617 = LINE('',#618,#619); -#618 = CARTESIAN_POINT('',(0.33617662,1.54168348,2.29108)); +#618 = CARTESIAN_POINT('',(0.33617662,1.54168348,1.7018)); #619 = VECTOR('',#620,1.); #620 = DIRECTION('',(0.522496833916,-0.852641224987,0.E+000)); #621 = PCURVE('',#576,#622); #622 = DEFINITIONAL_REPRESENTATION('',(#623),#627); #623 = LINE('',#624,#625); -#624 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#624 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #625 = VECTOR('',#626,1.); #626 = DIRECTION('',(1.,0.E+000)); #627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -766,16 +768,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #688 = ORIENTED_EDGE('',*,*,#689,.T.); #689 = EDGE_CURVE('',#614,#690,#692,.T.); #690 = VERTEX_POINT('',#691); -#691 = CARTESIAN_POINT('',(0.84346288,0.84346034,2.29108)); +#691 = CARTESIAN_POINT('',(0.84346288,0.84346034,1.7018)); #692 = SURFACE_CURVE('',#693,(#697,#704),.PCURVE_S1.); #693 = LINE('',#694,#695); -#694 = CARTESIAN_POINT('',(0.5623433,1.17261132,2.29108)); +#694 = CARTESIAN_POINT('',(0.5623433,1.17261132,1.7018)); #695 = VECTOR('',#696,1.); #696 = DIRECTION('',(0.649445490771,-0.760408149955,0.E+000)); #697 = PCURVE('',#652,#698); #698 = DEFINITIONAL_REPRESENTATION('',(#699),#703); #699 = LINE('',#700,#701); -#700 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#700 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #701 = VECTOR('',#702,1.); #702 = DIRECTION('',(1.,0.E+000)); #703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -854,16 +856,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #764 = ORIENTED_EDGE('',*,*,#765,.T.); #765 = EDGE_CURVE('',#690,#766,#768,.T.); #766 = VERTEX_POINT('',#767); -#767 = CARTESIAN_POINT('',(1.17261386,0.56234076,2.29108)); +#767 = CARTESIAN_POINT('',(1.17261386,0.56234076,1.7018)); #768 = SURFACE_CURVE('',#769,(#773,#780),.PCURVE_S1.); #769 = LINE('',#770,#771); -#770 = CARTESIAN_POINT('',(0.84346288,0.84346034,2.29108)); +#770 = CARTESIAN_POINT('',(0.84346288,0.84346034,1.7018)); #771 = VECTOR('',#772,1.); #772 = DIRECTION('',(0.760408149955,-0.649445490771,0.E+000)); #773 = PCURVE('',#728,#774); #774 = DEFINITIONAL_REPRESENTATION('',(#775),#779); #775 = LINE('',#776,#777); -#776 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#776 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #777 = VECTOR('',#778,1.); #778 = DIRECTION('',(1.,0.E+000)); #779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -942,16 +944,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #840 = ORIENTED_EDGE('',*,*,#841,.T.); #841 = EDGE_CURVE('',#766,#842,#844,.T.); #842 = VERTEX_POINT('',#843); -#843 = CARTESIAN_POINT('',(1.54168602,0.33617408,2.29108)); +#843 = CARTESIAN_POINT('',(1.54168602,0.33617408,1.7018)); #844 = SURFACE_CURVE('',#845,(#849,#856),.PCURVE_S1.); #845 = LINE('',#846,#847); -#846 = CARTESIAN_POINT('',(1.17261386,0.56234076,2.29108)); +#846 = CARTESIAN_POINT('',(1.17261386,0.56234076,1.7018)); #847 = VECTOR('',#848,1.); #848 = DIRECTION('',(0.852641224987,-0.522496833916,0.E+000)); #849 = PCURVE('',#804,#850); #850 = DEFINITIONAL_REPRESENTATION('',(#851),#855); #851 = LINE('',#852,#853); -#852 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#852 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #853 = VECTOR('',#854,1.); #854 = DIRECTION('',(1.,0.E+000)); #855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1030,16 +1032,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #916 = ORIENTED_EDGE('',*,*,#917,.T.); #917 = EDGE_CURVE('',#842,#918,#920,.T.); #918 = VERTEX_POINT('',#919); -#919 = CARTESIAN_POINT('',(1.94159632,0.17052544,2.29108)); +#919 = CARTESIAN_POINT('',(1.94159632,0.17052544,1.7018)); #920 = SURFACE_CURVE('',#921,(#925,#932),.PCURVE_S1.); #921 = LINE('',#922,#923); -#922 = CARTESIAN_POINT('',(1.54168602,0.33617408,2.29108)); +#922 = CARTESIAN_POINT('',(1.54168602,0.33617408,1.7018)); #923 = VECTOR('',#924,1.); #924 = DIRECTION('',(0.923879230295,-0.38268416198,0.E+000)); #925 = PCURVE('',#880,#926); #926 = DEFINITIONAL_REPRESENTATION('',(#927),#931); #927 = LINE('',#928,#929); -#928 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#928 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #929 = VECTOR('',#930,1.); #930 = DIRECTION('',(1.,0.E+000)); #931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1118,16 +1120,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #992 = ORIENTED_EDGE('',*,*,#993,.T.); #993 = EDGE_CURVE('',#918,#994,#996,.T.); #994 = VERTEX_POINT('',#995); -#995 = CARTESIAN_POINT('',(2.36249464,6.947662E-002,2.29108)); +#995 = CARTESIAN_POINT('',(2.36249464,6.947662E-002,1.7018)); #996 = SURFACE_CURVE('',#997,(#1001,#1008),.PCURVE_S1.); #997 = LINE('',#998,#999); -#998 = CARTESIAN_POINT('',(1.94159632,0.17052544,2.29108)); +#998 = CARTESIAN_POINT('',(1.94159632,0.17052544,1.7018)); #999 = VECTOR('',#1000,1.); #1000 = DIRECTION('',(0.972369881782,-0.2334455247,0.E+000)); #1001 = PCURVE('',#956,#1002); #1002 = DEFINITIONAL_REPRESENTATION('',(#1003),#1007); #1003 = LINE('',#1004,#1005); -#1004 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1004 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1005 = VECTOR('',#1006,1.); #1006 = DIRECTION('',(1.,0.E+000)); #1007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1206,16 +1208,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1068 = ORIENTED_EDGE('',*,*,#1069,.T.); #1069 = EDGE_CURVE('',#994,#1070,#1072,.T.); #1070 = VERTEX_POINT('',#1071); -#1071 = CARTESIAN_POINT('',(2.79402032,3.551428E-002,2.29108)); +#1071 = CARTESIAN_POINT('',(2.79402032,3.551428E-002,1.7018)); #1072 = SURFACE_CURVE('',#1073,(#1077,#1084),.PCURVE_S1.); #1073 = LINE('',#1074,#1075); -#1074 = CARTESIAN_POINT('',(2.36249464,6.947662E-002,2.29108)); +#1074 = CARTESIAN_POINT('',(2.36249464,6.947662E-002,1.7018)); #1075 = VECTOR('',#1076,1.); #1076 = DIRECTION('',(0.99691723752,-7.846031821913E-002,0.E+000)); #1077 = PCURVE('',#1032,#1078); #1078 = DEFINITIONAL_REPRESENTATION('',(#1079),#1083); #1079 = LINE('',#1080,#1081); -#1080 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1080 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1081 = VECTOR('',#1082,1.); #1082 = DIRECTION('',(1.,0.E+000)); #1083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1294,16 +1296,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1144 = ORIENTED_EDGE('',*,*,#1145,.T.); #1145 = EDGE_CURVE('',#1070,#1146,#1148,.T.); #1146 = VERTEX_POINT('',#1147); -#1147 = CARTESIAN_POINT('',(2.79402032,4.40182E-002,2.29108)); +#1147 = CARTESIAN_POINT('',(2.79402032,4.40182E-002,1.7018)); #1148 = SURFACE_CURVE('',#1149,(#1153,#1160),.PCURVE_S1.); #1149 = LINE('',#1150,#1151); -#1150 = CARTESIAN_POINT('',(2.79402032,3.551428E-002,2.29108)); +#1150 = CARTESIAN_POINT('',(2.79402032,3.551428E-002,1.7018)); #1151 = VECTOR('',#1152,1.); #1152 = DIRECTION('',(0.E+000,1.,0.E+000)); #1153 = PCURVE('',#1108,#1154); #1154 = DEFINITIONAL_REPRESENTATION('',(#1155),#1159); #1155 = LINE('',#1156,#1157); -#1156 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1156 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1157 = VECTOR('',#1158,1.); #1158 = DIRECTION('',(1.,0.E+000)); #1159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1382,16 +1384,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1220 = ORIENTED_EDGE('',*,*,#1221,.T.); #1221 = EDGE_CURVE('',#1146,#1222,#1224,.T.); #1222 = VERTEX_POINT('',#1223); -#1223 = CARTESIAN_POINT('',(2.794,4.40436E-002,2.29108)); +#1223 = CARTESIAN_POINT('',(2.794,4.40436E-002,1.7018)); #1224 = SURFACE_CURVE('',#1225,(#1229,#1236),.PCURVE_S1.); #1225 = LINE('',#1226,#1227); -#1226 = CARTESIAN_POINT('',(2.79402032,4.40182E-002,2.29108)); +#1226 = CARTESIAN_POINT('',(2.79402032,4.40182E-002,1.7018)); #1227 = VECTOR('',#1228,1.); #1228 = DIRECTION('',(-0.624695047661,0.780868809358,0.E+000)); #1229 = PCURVE('',#1184,#1230); #1230 = DEFINITIONAL_REPRESENTATION('',(#1231),#1235); #1231 = LINE('',#1232,#1233); -#1232 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1232 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1233 = VECTOR('',#1234,1.); #1234 = DIRECTION('',(1.,0.E+000)); #1235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1470,16 +1472,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1296 = ORIENTED_EDGE('',*,*,#1297,.T.); #1297 = EDGE_CURVE('',#1222,#1298,#1300,.T.); #1298 = VERTEX_POINT('',#1299); -#1299 = CARTESIAN_POINT('',(33.2940152,4.40436E-002,2.29108)); +#1299 = CARTESIAN_POINT('',(33.2940152,4.40436E-002,1.7018)); #1300 = SURFACE_CURVE('',#1301,(#1305,#1312),.PCURVE_S1.); #1301 = LINE('',#1302,#1303); -#1302 = CARTESIAN_POINT('',(2.794,4.40436E-002,2.29108)); +#1302 = CARTESIAN_POINT('',(2.794,4.40436E-002,1.7018)); #1303 = VECTOR('',#1304,1.); #1304 = DIRECTION('',(1.,0.E+000,0.E+000)); #1305 = PCURVE('',#1260,#1306); #1306 = DEFINITIONAL_REPRESENTATION('',(#1307),#1311); #1307 = LINE('',#1308,#1309); -#1308 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1308 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1309 = VECTOR('',#1310,1.); #1310 = DIRECTION('',(1.,0.E+000)); #1311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1558,16 +1560,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1372 = ORIENTED_EDGE('',*,*,#1373,.T.); #1373 = EDGE_CURVE('',#1298,#1374,#1376,.T.); #1374 = VERTEX_POINT('',#1375); -#1375 = CARTESIAN_POINT('',(33.29402028,3.551428E-002,2.29108)); +#1375 = CARTESIAN_POINT('',(33.29402028,3.551428E-002,1.7018)); #1376 = SURFACE_CURVE('',#1377,(#1381,#1388),.PCURVE_S1.); #1377 = LINE('',#1378,#1379); -#1378 = CARTESIAN_POINT('',(33.2940152,4.40436E-002,2.29108)); +#1378 = CARTESIAN_POINT('',(33.2940152,4.40436E-002,1.7018)); #1379 = VECTOR('',#1380,1.); #1380 = DIRECTION('',(5.955925083101E-004,-0.999999822635,0.E+000)); #1381 = PCURVE('',#1336,#1382); #1382 = DEFINITIONAL_REPRESENTATION('',(#1383),#1387); #1383 = LINE('',#1384,#1385); -#1384 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1384 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1385 = VECTOR('',#1386,1.); #1386 = DIRECTION('',(1.,0.E+000)); #1387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1646,16 +1648,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1448 = ORIENTED_EDGE('',*,*,#1449,.T.); #1449 = EDGE_CURVE('',#1374,#1450,#1452,.T.); #1450 = VERTEX_POINT('',#1451); -#1451 = CARTESIAN_POINT('',(33.72554596,6.947662E-002,2.29108)); +#1451 = CARTESIAN_POINT('',(33.72554596,6.947662E-002,1.7018)); #1452 = SURFACE_CURVE('',#1453,(#1457,#1464),.PCURVE_S1.); #1453 = LINE('',#1454,#1455); -#1454 = CARTESIAN_POINT('',(33.29402028,3.551428E-002,2.29108)); +#1454 = CARTESIAN_POINT('',(33.29402028,3.551428E-002,1.7018)); #1455 = VECTOR('',#1456,1.); #1456 = DIRECTION('',(0.99691723752,7.846031821912E-002,0.E+000)); #1457 = PCURVE('',#1412,#1458); #1458 = DEFINITIONAL_REPRESENTATION('',(#1459),#1463); #1459 = LINE('',#1460,#1461); -#1460 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1460 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1461 = VECTOR('',#1462,1.); #1462 = DIRECTION('',(1.,0.E+000)); #1463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1734,16 +1736,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1524 = ORIENTED_EDGE('',*,*,#1525,.T.); #1525 = EDGE_CURVE('',#1450,#1526,#1528,.T.); #1526 = VERTEX_POINT('',#1527); -#1527 = CARTESIAN_POINT('',(34.14644428,0.17052544,2.29108)); +#1527 = CARTESIAN_POINT('',(34.14644428,0.17052544,1.7018)); #1528 = SURFACE_CURVE('',#1529,(#1533,#1540),.PCURVE_S1.); #1529 = LINE('',#1530,#1531); -#1530 = CARTESIAN_POINT('',(33.72554596,6.947662E-002,2.29108)); +#1530 = CARTESIAN_POINT('',(33.72554596,6.947662E-002,1.7018)); #1531 = VECTOR('',#1532,1.); #1532 = DIRECTION('',(0.972369881782,0.2334455247,0.E+000)); #1533 = PCURVE('',#1488,#1534); #1534 = DEFINITIONAL_REPRESENTATION('',(#1535),#1539); #1535 = LINE('',#1536,#1537); -#1536 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1536 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1537 = VECTOR('',#1538,1.); #1538 = DIRECTION('',(1.,0.E+000)); #1539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1822,16 +1824,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1600 = ORIENTED_EDGE('',*,*,#1601,.T.); #1601 = EDGE_CURVE('',#1526,#1602,#1604,.T.); #1602 = VERTEX_POINT('',#1603); -#1603 = CARTESIAN_POINT('',(34.54635458,0.33617408,2.29108)); +#1603 = CARTESIAN_POINT('',(34.54635458,0.33617408,1.7018)); #1604 = SURFACE_CURVE('',#1605,(#1609,#1616),.PCURVE_S1.); #1605 = LINE('',#1606,#1607); -#1606 = CARTESIAN_POINT('',(34.14644428,0.17052544,2.29108)); +#1606 = CARTESIAN_POINT('',(34.14644428,0.17052544,1.7018)); #1607 = VECTOR('',#1608,1.); #1608 = DIRECTION('',(0.923879230295,0.38268416198,0.E+000)); #1609 = PCURVE('',#1564,#1610); #1610 = DEFINITIONAL_REPRESENTATION('',(#1611),#1615); #1611 = LINE('',#1612,#1613); -#1612 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1612 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1613 = VECTOR('',#1614,1.); #1614 = DIRECTION('',(1.,0.E+000)); #1615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1910,16 +1912,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1676 = ORIENTED_EDGE('',*,*,#1677,.T.); #1677 = EDGE_CURVE('',#1602,#1678,#1680,.T.); #1678 = VERTEX_POINT('',#1679); -#1679 = CARTESIAN_POINT('',(34.91542674,0.56234076,2.29108)); +#1679 = CARTESIAN_POINT('',(34.91542674,0.56234076,1.7018)); #1680 = SURFACE_CURVE('',#1681,(#1685,#1692),.PCURVE_S1.); #1681 = LINE('',#1682,#1683); -#1682 = CARTESIAN_POINT('',(34.54635458,0.33617408,2.29108)); +#1682 = CARTESIAN_POINT('',(34.54635458,0.33617408,1.7018)); #1683 = VECTOR('',#1684,1.); #1684 = DIRECTION('',(0.852641224987,0.522496833916,0.E+000)); #1685 = PCURVE('',#1640,#1686); #1686 = DEFINITIONAL_REPRESENTATION('',(#1687),#1691); #1687 = LINE('',#1688,#1689); -#1688 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1688 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1689 = VECTOR('',#1690,1.); #1690 = DIRECTION('',(1.,0.E+000)); #1691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -1998,16 +2000,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1752 = ORIENTED_EDGE('',*,*,#1753,.T.); #1753 = EDGE_CURVE('',#1678,#1754,#1756,.T.); #1754 = VERTEX_POINT('',#1755); -#1755 = CARTESIAN_POINT('',(35.24457772,0.84346034,2.29108)); +#1755 = CARTESIAN_POINT('',(35.24457772,0.84346034,1.7018)); #1756 = SURFACE_CURVE('',#1757,(#1761,#1768),.PCURVE_S1.); #1757 = LINE('',#1758,#1759); -#1758 = CARTESIAN_POINT('',(34.91542674,0.56234076,2.29108)); +#1758 = CARTESIAN_POINT('',(34.91542674,0.56234076,1.7018)); #1759 = VECTOR('',#1760,1.); #1760 = DIRECTION('',(0.760408149955,0.649445490771,0.E+000)); #1761 = PCURVE('',#1716,#1762); #1762 = DEFINITIONAL_REPRESENTATION('',(#1763),#1767); #1763 = LINE('',#1764,#1765); -#1764 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1764 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1765 = VECTOR('',#1766,1.); #1766 = DIRECTION('',(1.,0.E+000)); #1767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2086,16 +2088,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1828 = ORIENTED_EDGE('',*,*,#1829,.T.); #1829 = EDGE_CURVE('',#1754,#1830,#1832,.T.); #1830 = VERTEX_POINT('',#1831); -#1831 = CARTESIAN_POINT('',(35.5256973,1.17261132,2.29108)); +#1831 = CARTESIAN_POINT('',(35.5256973,1.17261132,1.7018)); #1832 = SURFACE_CURVE('',#1833,(#1837,#1844),.PCURVE_S1.); #1833 = LINE('',#1834,#1835); -#1834 = CARTESIAN_POINT('',(35.24457772,0.84346034,2.29108)); +#1834 = CARTESIAN_POINT('',(35.24457772,0.84346034,1.7018)); #1835 = VECTOR('',#1836,1.); #1836 = DIRECTION('',(0.649445490771,0.760408149955,0.E+000)); #1837 = PCURVE('',#1792,#1838); #1838 = DEFINITIONAL_REPRESENTATION('',(#1839),#1843); #1839 = LINE('',#1840,#1841); -#1840 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1840 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1841 = VECTOR('',#1842,1.); #1842 = DIRECTION('',(1.,0.E+000)); #1843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2174,16 +2176,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1904 = ORIENTED_EDGE('',*,*,#1905,.T.); #1905 = EDGE_CURVE('',#1830,#1906,#1908,.T.); #1906 = VERTEX_POINT('',#1907); -#1907 = CARTESIAN_POINT('',(35.75186398,1.54168348,2.29108)); +#1907 = CARTESIAN_POINT('',(35.75186398,1.54168348,1.7018)); #1908 = SURFACE_CURVE('',#1909,(#1913,#1920),.PCURVE_S1.); #1909 = LINE('',#1910,#1911); -#1910 = CARTESIAN_POINT('',(35.5256973,1.17261132,2.29108)); +#1910 = CARTESIAN_POINT('',(35.5256973,1.17261132,1.7018)); #1911 = VECTOR('',#1912,1.); #1912 = DIRECTION('',(0.522496833916,0.852641224987,0.E+000)); #1913 = PCURVE('',#1868,#1914); #1914 = DEFINITIONAL_REPRESENTATION('',(#1915),#1919); #1915 = LINE('',#1916,#1917); -#1916 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1916 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1917 = VECTOR('',#1918,1.); #1918 = DIRECTION('',(1.,0.E+000)); #1919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2262,16 +2264,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #1980 = ORIENTED_EDGE('',*,*,#1981,.T.); #1981 = EDGE_CURVE('',#1906,#1982,#1984,.T.); #1982 = VERTEX_POINT('',#1983); -#1983 = CARTESIAN_POINT('',(35.91751262,1.94159378,2.29108)); +#1983 = CARTESIAN_POINT('',(35.91751262,1.94159378,1.7018)); #1984 = SURFACE_CURVE('',#1985,(#1989,#1996),.PCURVE_S1.); #1985 = LINE('',#1986,#1987); -#1986 = CARTESIAN_POINT('',(35.75186398,1.54168348,2.29108)); +#1986 = CARTESIAN_POINT('',(35.75186398,1.54168348,1.7018)); #1987 = VECTOR('',#1988,1.); #1988 = DIRECTION('',(0.38268416198,0.923879230295,0.E+000)); #1989 = PCURVE('',#1944,#1990); #1990 = DEFINITIONAL_REPRESENTATION('',(#1991),#1995); #1991 = LINE('',#1992,#1993); -#1992 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#1992 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #1993 = VECTOR('',#1994,1.); #1994 = DIRECTION('',(1.,0.E+000)); #1995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2350,16 +2352,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2056 = ORIENTED_EDGE('',*,*,#2057,.T.); #2057 = EDGE_CURVE('',#1982,#2058,#2060,.T.); #2058 = VERTEX_POINT('',#2059); -#2059 = CARTESIAN_POINT('',(36.01856144,2.3624921,2.29108)); +#2059 = CARTESIAN_POINT('',(36.01856144,2.3624921,1.7018)); #2060 = SURFACE_CURVE('',#2061,(#2065,#2072),.PCURVE_S1.); #2061 = LINE('',#2062,#2063); -#2062 = CARTESIAN_POINT('',(35.91751262,1.94159378,2.29108)); +#2062 = CARTESIAN_POINT('',(35.91751262,1.94159378,1.7018)); #2063 = VECTOR('',#2064,1.); #2064 = DIRECTION('',(0.2334455247,0.972369881782,0.E+000)); #2065 = PCURVE('',#2020,#2066); #2066 = DEFINITIONAL_REPRESENTATION('',(#2067),#2071); #2067 = LINE('',#2068,#2069); -#2068 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2068 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2069 = VECTOR('',#2070,1.); #2070 = DIRECTION('',(1.,0.E+000)); #2071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2438,16 +2440,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2132 = ORIENTED_EDGE('',*,*,#2133,.T.); #2133 = EDGE_CURVE('',#2058,#2134,#2136,.T.); #2134 = VERTEX_POINT('',#2135); -#2135 = CARTESIAN_POINT('',(36.05252378,2.79401778,2.29108)); +#2135 = CARTESIAN_POINT('',(36.05252378,2.79401778,1.7018)); #2136 = SURFACE_CURVE('',#2137,(#2141,#2148),.PCURVE_S1.); #2137 = LINE('',#2138,#2139); -#2138 = CARTESIAN_POINT('',(36.01856144,2.3624921,2.29108)); +#2138 = CARTESIAN_POINT('',(36.01856144,2.3624921,1.7018)); #2139 = VECTOR('',#2140,1.); #2140 = DIRECTION('',(7.846031821913E-002,0.99691723752,0.E+000)); #2141 = PCURVE('',#2096,#2142); #2142 = DEFINITIONAL_REPRESENTATION('',(#2143),#2147); #2143 = LINE('',#2144,#2145); -#2144 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2144 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2145 = VECTOR('',#2146,1.); #2146 = DIRECTION('',(1.,0.E+000)); #2147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2526,16 +2528,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2208 = ORIENTED_EDGE('',*,*,#2209,.T.); #2209 = EDGE_CURVE('',#2134,#2210,#2212,.T.); #2210 = VERTEX_POINT('',#2211); -#2211 = CARTESIAN_POINT('',(36.04401986,2.79401778,2.29108)); +#2211 = CARTESIAN_POINT('',(36.04401986,2.79401778,1.7018)); #2212 = SURFACE_CURVE('',#2213,(#2217,#2224),.PCURVE_S1.); #2213 = LINE('',#2214,#2215); -#2214 = CARTESIAN_POINT('',(36.05252378,2.79401778,2.29108)); +#2214 = CARTESIAN_POINT('',(36.05252378,2.79401778,1.7018)); #2215 = VECTOR('',#2216,1.); #2216 = DIRECTION('',(-1.,0.E+000,0.E+000)); #2217 = PCURVE('',#2172,#2218); #2218 = DEFINITIONAL_REPRESENTATION('',(#2219),#2223); #2219 = LINE('',#2220,#2221); -#2220 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2220 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2221 = VECTOR('',#2222,1.); #2222 = DIRECTION('',(1.,0.E+000)); #2223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2614,16 +2616,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2284 = ORIENTED_EDGE('',*,*,#2285,.T.); #2285 = EDGE_CURVE('',#2210,#2286,#2288,.T.); #2286 = VERTEX_POINT('',#2287); -#2287 = CARTESIAN_POINT('',(36.0440224,2.7940508,2.29108)); +#2287 = CARTESIAN_POINT('',(36.0440224,2.7940508,1.7018)); #2288 = SURFACE_CURVE('',#2289,(#2293,#2300),.PCURVE_S1.); #2289 = LINE('',#2290,#2291); -#2290 = CARTESIAN_POINT('',(36.04401986,2.79401778,2.29108)); +#2290 = CARTESIAN_POINT('',(36.04401986,2.79401778,1.7018)); #2291 = VECTOR('',#2292,1.); #2292 = DIRECTION('',(7.66964987863E-002,0.997054485509,0.E+000)); #2293 = PCURVE('',#2248,#2294); #2294 = DEFINITIONAL_REPRESENTATION('',(#2295),#2299); #2295 = LINE('',#2296,#2297); -#2296 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2296 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2297 = VECTOR('',#2298,1.); #2298 = DIRECTION('',(1.,0.E+000)); #2299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2702,16 +2704,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2360 = ORIENTED_EDGE('',*,*,#2361,.T.); #2361 = EDGE_CURVE('',#2286,#2362,#2364,.T.); #2362 = VERTEX_POINT('',#2363); -#2363 = CARTESIAN_POINT('',(36.0440224,33.2940152,2.29108)); +#2363 = CARTESIAN_POINT('',(36.0440224,33.2940152,1.7018)); #2364 = SURFACE_CURVE('',#2365,(#2369,#2376),.PCURVE_S1.); #2365 = LINE('',#2366,#2367); -#2366 = CARTESIAN_POINT('',(36.0440224,2.7940508,2.29108)); +#2366 = CARTESIAN_POINT('',(36.0440224,2.7940508,1.7018)); #2367 = VECTOR('',#2368,1.); #2368 = DIRECTION('',(0.E+000,1.,0.E+000)); #2369 = PCURVE('',#2324,#2370); #2370 = DEFINITIONAL_REPRESENTATION('',(#2371),#2375); #2371 = LINE('',#2372,#2373); -#2372 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2372 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2373 = VECTOR('',#2374,1.); #2374 = DIRECTION('',(1.,0.E+000)); #2375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2790,16 +2792,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2436 = ORIENTED_EDGE('',*,*,#2437,.T.); #2437 = EDGE_CURVE('',#2362,#2438,#2440,.T.); #2438 = VERTEX_POINT('',#2439); -#2439 = CARTESIAN_POINT('',(36.05252378,33.29401774,2.29108)); +#2439 = CARTESIAN_POINT('',(36.05252378,33.29401774,1.7018)); #2440 = SURFACE_CURVE('',#2441,(#2445,#2452),.PCURVE_S1.); #2441 = LINE('',#2442,#2443); -#2442 = CARTESIAN_POINT('',(36.0440224,33.2940152,2.29108)); +#2442 = CARTESIAN_POINT('',(36.0440224,33.2940152,1.7018)); #2443 = VECTOR('',#2444,1.); #2444 = DIRECTION('',(0.999999955367,2.987750087197E-004,0.E+000)); #2445 = PCURVE('',#2400,#2446); #2446 = DEFINITIONAL_REPRESENTATION('',(#2447),#2451); #2447 = LINE('',#2448,#2449); -#2448 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2448 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2449 = VECTOR('',#2450,1.); #2450 = DIRECTION('',(1.,0.E+000)); #2451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2878,16 +2880,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2512 = ORIENTED_EDGE('',*,*,#2513,.T.); #2513 = EDGE_CURVE('',#2438,#2514,#2516,.T.); #2514 = VERTEX_POINT('',#2515); -#2515 = CARTESIAN_POINT('',(36.01856144,33.72554342,2.29108)); +#2515 = CARTESIAN_POINT('',(36.01856144,33.72554342,1.7018)); #2516 = SURFACE_CURVE('',#2517,(#2521,#2528),.PCURVE_S1.); #2517 = LINE('',#2518,#2519); -#2518 = CARTESIAN_POINT('',(36.05252378,33.29401774,2.29108)); +#2518 = CARTESIAN_POINT('',(36.05252378,33.29401774,1.7018)); #2519 = VECTOR('',#2520,1.); #2520 = DIRECTION('',(-7.846031821913E-002,0.99691723752,0.E+000)); #2521 = PCURVE('',#2476,#2522); #2522 = DEFINITIONAL_REPRESENTATION('',(#2523),#2527); #2523 = LINE('',#2524,#2525); -#2524 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2524 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2525 = VECTOR('',#2526,1.); #2526 = DIRECTION('',(1.,0.E+000)); #2527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -2966,16 +2968,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2588 = ORIENTED_EDGE('',*,*,#2589,.T.); #2589 = EDGE_CURVE('',#2514,#2590,#2592,.T.); #2590 = VERTEX_POINT('',#2591); -#2591 = CARTESIAN_POINT('',(35.91751262,34.14644174,2.29108)); +#2591 = CARTESIAN_POINT('',(35.91751262,34.14644174,1.7018)); #2592 = SURFACE_CURVE('',#2593,(#2597,#2604),.PCURVE_S1.); #2593 = LINE('',#2594,#2595); -#2594 = CARTESIAN_POINT('',(36.01856144,33.72554342,2.29108)); +#2594 = CARTESIAN_POINT('',(36.01856144,33.72554342,1.7018)); #2595 = VECTOR('',#2596,1.); #2596 = DIRECTION('',(-0.2334455247,0.972369881782,0.E+000)); #2597 = PCURVE('',#2552,#2598); #2598 = DEFINITIONAL_REPRESENTATION('',(#2599),#2603); #2599 = LINE('',#2600,#2601); -#2600 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2600 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2601 = VECTOR('',#2602,1.); #2602 = DIRECTION('',(1.,0.E+000)); #2603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3054,16 +3056,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2664 = ORIENTED_EDGE('',*,*,#2665,.T.); #2665 = EDGE_CURVE('',#2590,#2666,#2668,.T.); #2666 = VERTEX_POINT('',#2667); -#2667 = CARTESIAN_POINT('',(35.75186398,34.54635204,2.29108)); +#2667 = CARTESIAN_POINT('',(35.75186398,34.54635204,1.7018)); #2668 = SURFACE_CURVE('',#2669,(#2673,#2680),.PCURVE_S1.); #2669 = LINE('',#2670,#2671); -#2670 = CARTESIAN_POINT('',(35.91751262,34.14644174,2.29108)); +#2670 = CARTESIAN_POINT('',(35.91751262,34.14644174,1.7018)); #2671 = VECTOR('',#2672,1.); #2672 = DIRECTION('',(-0.38268416198,0.923879230295,0.E+000)); #2673 = PCURVE('',#2628,#2674); #2674 = DEFINITIONAL_REPRESENTATION('',(#2675),#2679); #2675 = LINE('',#2676,#2677); -#2676 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2676 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2677 = VECTOR('',#2678,1.); #2678 = DIRECTION('',(1.,0.E+000)); #2679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3142,16 +3144,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2740 = ORIENTED_EDGE('',*,*,#2741,.T.); #2741 = EDGE_CURVE('',#2666,#2742,#2744,.T.); #2742 = VERTEX_POINT('',#2743); -#2743 = CARTESIAN_POINT('',(35.5256973,34.9154242,2.29108)); +#2743 = CARTESIAN_POINT('',(35.5256973,34.9154242,1.7018)); #2744 = SURFACE_CURVE('',#2745,(#2749,#2756),.PCURVE_S1.); #2745 = LINE('',#2746,#2747); -#2746 = CARTESIAN_POINT('',(35.75186398,34.54635204,2.29108)); +#2746 = CARTESIAN_POINT('',(35.75186398,34.54635204,1.7018)); #2747 = VECTOR('',#2748,1.); #2748 = DIRECTION('',(-0.522496833916,0.852641224987,0.E+000)); #2749 = PCURVE('',#2704,#2750); #2750 = DEFINITIONAL_REPRESENTATION('',(#2751),#2755); #2751 = LINE('',#2752,#2753); -#2752 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2752 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2753 = VECTOR('',#2754,1.); #2754 = DIRECTION('',(1.,0.E+000)); #2755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3230,16 +3232,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2816 = ORIENTED_EDGE('',*,*,#2817,.T.); #2817 = EDGE_CURVE('',#2742,#2818,#2820,.T.); #2818 = VERTEX_POINT('',#2819); -#2819 = CARTESIAN_POINT('',(35.24457772,35.24457518,2.29108)); +#2819 = CARTESIAN_POINT('',(35.24457772,35.24457518,1.7018)); #2820 = SURFACE_CURVE('',#2821,(#2825,#2832),.PCURVE_S1.); #2821 = LINE('',#2822,#2823); -#2822 = CARTESIAN_POINT('',(35.5256973,34.9154242,2.29108)); +#2822 = CARTESIAN_POINT('',(35.5256973,34.9154242,1.7018)); #2823 = VECTOR('',#2824,1.); #2824 = DIRECTION('',(-0.649445490771,0.760408149955,0.E+000)); #2825 = PCURVE('',#2780,#2826); #2826 = DEFINITIONAL_REPRESENTATION('',(#2827),#2831); #2827 = LINE('',#2828,#2829); -#2828 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2828 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2829 = VECTOR('',#2830,1.); #2830 = DIRECTION('',(1.,0.E+000)); #2831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3318,16 +3320,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2892 = ORIENTED_EDGE('',*,*,#2893,.T.); #2893 = EDGE_CURVE('',#2818,#2894,#2896,.T.); #2894 = VERTEX_POINT('',#2895); -#2895 = CARTESIAN_POINT('',(34.91542674,35.52569476,2.29108)); +#2895 = CARTESIAN_POINT('',(34.91542674,35.52569476,1.7018)); #2896 = SURFACE_CURVE('',#2897,(#2901,#2908),.PCURVE_S1.); #2897 = LINE('',#2898,#2899); -#2898 = CARTESIAN_POINT('',(35.24457772,35.24457518,2.29108)); +#2898 = CARTESIAN_POINT('',(35.24457772,35.24457518,1.7018)); #2899 = VECTOR('',#2900,1.); #2900 = DIRECTION('',(-0.760408149955,0.649445490771,0.E+000)); #2901 = PCURVE('',#2856,#2902); #2902 = DEFINITIONAL_REPRESENTATION('',(#2903),#2907); #2903 = LINE('',#2904,#2905); -#2904 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2904 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2905 = VECTOR('',#2906,1.); #2906 = DIRECTION('',(1.,0.E+000)); #2907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3406,16 +3408,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #2968 = ORIENTED_EDGE('',*,*,#2969,.T.); #2969 = EDGE_CURVE('',#2894,#2970,#2972,.T.); #2970 = VERTEX_POINT('',#2971); -#2971 = CARTESIAN_POINT('',(34.54635458,35.75186144,2.29108)); +#2971 = CARTESIAN_POINT('',(34.54635458,35.75186144,1.7018)); #2972 = SURFACE_CURVE('',#2973,(#2977,#2984),.PCURVE_S1.); #2973 = LINE('',#2974,#2975); -#2974 = CARTESIAN_POINT('',(34.91542674,35.52569476,2.29108)); +#2974 = CARTESIAN_POINT('',(34.91542674,35.52569476,1.7018)); #2975 = VECTOR('',#2976,1.); #2976 = DIRECTION('',(-0.852641224987,0.522496833916,0.E+000)); #2977 = PCURVE('',#2932,#2978); #2978 = DEFINITIONAL_REPRESENTATION('',(#2979),#2983); #2979 = LINE('',#2980,#2981); -#2980 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#2980 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #2981 = VECTOR('',#2982,1.); #2982 = DIRECTION('',(1.,0.E+000)); #2983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3494,16 +3496,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3044 = ORIENTED_EDGE('',*,*,#3045,.T.); #3045 = EDGE_CURVE('',#2970,#3046,#3048,.T.); #3046 = VERTEX_POINT('',#3047); -#3047 = CARTESIAN_POINT('',(34.14644428,35.91751008,2.29108)); +#3047 = CARTESIAN_POINT('',(34.14644428,35.91751008,1.7018)); #3048 = SURFACE_CURVE('',#3049,(#3053,#3060),.PCURVE_S1.); #3049 = LINE('',#3050,#3051); -#3050 = CARTESIAN_POINT('',(34.54635458,35.75186144,2.29108)); +#3050 = CARTESIAN_POINT('',(34.54635458,35.75186144,1.7018)); #3051 = VECTOR('',#3052,1.); #3052 = DIRECTION('',(-0.923879230295,0.38268416198,0.E+000)); #3053 = PCURVE('',#3008,#3054); #3054 = DEFINITIONAL_REPRESENTATION('',(#3055),#3059); #3055 = LINE('',#3056,#3057); -#3056 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3056 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3057 = VECTOR('',#3058,1.); #3058 = DIRECTION('',(1.,0.E+000)); #3059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3582,16 +3584,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3120 = ORIENTED_EDGE('',*,*,#3121,.T.); #3121 = EDGE_CURVE('',#3046,#3122,#3124,.T.); #3122 = VERTEX_POINT('',#3123); -#3123 = CARTESIAN_POINT('',(33.72554596,36.0185589,2.29108)); +#3123 = CARTESIAN_POINT('',(33.72554596,36.0185589,1.7018)); #3124 = SURFACE_CURVE('',#3125,(#3129,#3136),.PCURVE_S1.); #3125 = LINE('',#3126,#3127); -#3126 = CARTESIAN_POINT('',(34.14644428,35.91751008,2.29108)); +#3126 = CARTESIAN_POINT('',(34.14644428,35.91751008,1.7018)); #3127 = VECTOR('',#3128,1.); #3128 = DIRECTION('',(-0.972369881782,0.2334455247,0.E+000)); #3129 = PCURVE('',#3084,#3130); #3130 = DEFINITIONAL_REPRESENTATION('',(#3131),#3135); #3131 = LINE('',#3132,#3133); -#3132 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3132 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3133 = VECTOR('',#3134,1.); #3134 = DIRECTION('',(1.,0.E+000)); #3135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3670,16 +3672,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3196 = ORIENTED_EDGE('',*,*,#3197,.T.); #3197 = EDGE_CURVE('',#3122,#3198,#3200,.T.); #3198 = VERTEX_POINT('',#3199); -#3199 = CARTESIAN_POINT('',(33.29402028,36.05252124,2.29108)); +#3199 = CARTESIAN_POINT('',(33.29402028,36.05252124,1.7018)); #3200 = SURFACE_CURVE('',#3201,(#3205,#3212),.PCURVE_S1.); #3201 = LINE('',#3202,#3203); -#3202 = CARTESIAN_POINT('',(33.72554596,36.0185589,2.29108)); +#3202 = CARTESIAN_POINT('',(33.72554596,36.0185589,1.7018)); #3203 = VECTOR('',#3204,1.); #3204 = DIRECTION('',(-0.99691723752,7.846031821912E-002,0.E+000)); #3205 = PCURVE('',#3160,#3206); #3206 = DEFINITIONAL_REPRESENTATION('',(#3207),#3211); #3207 = LINE('',#3208,#3209); -#3208 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3208 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3209 = VECTOR('',#3210,1.); #3210 = DIRECTION('',(1.,0.E+000)); #3211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3758,16 +3760,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3272 = ORIENTED_EDGE('',*,*,#3273,.T.); #3273 = EDGE_CURVE('',#3198,#3274,#3276,.T.); #3274 = VERTEX_POINT('',#3275); -#3275 = CARTESIAN_POINT('',(33.29402028,36.04401732,2.29108)); +#3275 = CARTESIAN_POINT('',(33.29402028,36.04401732,1.7018)); #3276 = SURFACE_CURVE('',#3277,(#3281,#3288),.PCURVE_S1.); #3277 = LINE('',#3278,#3279); -#3278 = CARTESIAN_POINT('',(33.29402028,36.05252124,2.29108)); +#3278 = CARTESIAN_POINT('',(33.29402028,36.05252124,1.7018)); #3279 = VECTOR('',#3280,1.); #3280 = DIRECTION('',(0.E+000,-1.,0.E+000)); #3281 = PCURVE('',#3236,#3282); #3282 = DEFINITIONAL_REPRESENTATION('',(#3283),#3287); #3283 = LINE('',#3284,#3285); -#3284 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3284 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3285 = VECTOR('',#3286,1.); #3286 = DIRECTION('',(1.,0.E+000)); #3287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3846,16 +3848,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3348 = ORIENTED_EDGE('',*,*,#3349,.T.); #3349 = EDGE_CURVE('',#3274,#3350,#3352,.T.); #3350 = VERTEX_POINT('',#3351); -#3351 = CARTESIAN_POINT('',(33.2940152,36.0440224,2.29108)); +#3351 = CARTESIAN_POINT('',(33.2940152,36.0440224,1.7018)); #3352 = SURFACE_CURVE('',#3353,(#3357,#3364),.PCURVE_S1.); #3353 = LINE('',#3354,#3355); -#3354 = CARTESIAN_POINT('',(33.29402028,36.04401732,2.29108)); +#3354 = CARTESIAN_POINT('',(33.29402028,36.04401732,1.7018)); #3355 = VECTOR('',#3356,1.); #3356 = DIRECTION('',(-0.707106780198,0.707106782176,0.E+000)); #3357 = PCURVE('',#3312,#3358); #3358 = DEFINITIONAL_REPRESENTATION('',(#3359),#3363); #3359 = LINE('',#3360,#3361); -#3360 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3360 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3361 = VECTOR('',#3362,1.); #3362 = DIRECTION('',(1.,0.E+000)); #3363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -3934,16 +3936,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3424 = ORIENTED_EDGE('',*,*,#3425,.T.); #3425 = EDGE_CURVE('',#3350,#3426,#3428,.T.); #3426 = VERTEX_POINT('',#3427); -#3427 = CARTESIAN_POINT('',(2.794,36.0440224,2.29108)); +#3427 = CARTESIAN_POINT('',(2.794,36.0440224,1.7018)); #3428 = SURFACE_CURVE('',#3429,(#3433,#3440),.PCURVE_S1.); #3429 = LINE('',#3430,#3431); -#3430 = CARTESIAN_POINT('',(33.2940152,36.0440224,2.29108)); +#3430 = CARTESIAN_POINT('',(33.2940152,36.0440224,1.7018)); #3431 = VECTOR('',#3432,1.); #3432 = DIRECTION('',(-1.,0.E+000,0.E+000)); #3433 = PCURVE('',#3388,#3434); #3434 = DEFINITIONAL_REPRESENTATION('',(#3435),#3439); #3435 = LINE('',#3436,#3437); -#3436 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3436 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3437 = VECTOR('',#3438,1.); #3438 = DIRECTION('',(1.,0.E+000)); #3439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4022,16 +4024,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3500 = ORIENTED_EDGE('',*,*,#3501,.T.); #3501 = EDGE_CURVE('',#3426,#3502,#3504,.T.); #3502 = VERTEX_POINT('',#3503); -#3503 = CARTESIAN_POINT('',(2.79402032,36.05252124,2.29108)); +#3503 = CARTESIAN_POINT('',(2.79402032,36.05252124,1.7018)); #3504 = SURFACE_CURVE('',#3505,(#3509,#3516),.PCURVE_S1.); #3505 = LINE('',#3506,#3507); -#3506 = CARTESIAN_POINT('',(2.794,36.0440224,2.29108)); +#3506 = CARTESIAN_POINT('',(2.794,36.0440224,1.7018)); #3507 = VECTOR('',#3508,1.); #3508 = DIRECTION('',(2.390907691554E-003,0.999997141776,0.E+000)); #3509 = PCURVE('',#3464,#3510); #3510 = DEFINITIONAL_REPRESENTATION('',(#3511),#3515); #3511 = LINE('',#3512,#3513); -#3512 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3512 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3513 = VECTOR('',#3514,1.); #3514 = DIRECTION('',(1.,0.E+000)); #3515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4110,16 +4112,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3576 = ORIENTED_EDGE('',*,*,#3577,.T.); #3577 = EDGE_CURVE('',#3502,#3578,#3580,.T.); #3578 = VERTEX_POINT('',#3579); -#3579 = CARTESIAN_POINT('',(2.36249464,36.0185589,2.29108)); +#3579 = CARTESIAN_POINT('',(2.36249464,36.0185589,1.7018)); #3580 = SURFACE_CURVE('',#3581,(#3585,#3592),.PCURVE_S1.); #3581 = LINE('',#3582,#3583); -#3582 = CARTESIAN_POINT('',(2.79402032,36.05252124,2.29108)); +#3582 = CARTESIAN_POINT('',(2.79402032,36.05252124,1.7018)); #3583 = VECTOR('',#3584,1.); #3584 = DIRECTION('',(-0.99691723752,-7.846031821913E-002,0.E+000)); #3585 = PCURVE('',#3540,#3586); #3586 = DEFINITIONAL_REPRESENTATION('',(#3587),#3591); #3587 = LINE('',#3588,#3589); -#3588 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3588 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3589 = VECTOR('',#3590,1.); #3590 = DIRECTION('',(1.,0.E+000)); #3591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4198,16 +4200,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3652 = ORIENTED_EDGE('',*,*,#3653,.T.); #3653 = EDGE_CURVE('',#3578,#3654,#3656,.T.); #3654 = VERTEX_POINT('',#3655); -#3655 = CARTESIAN_POINT('',(1.94159632,35.91751008,2.29108)); +#3655 = CARTESIAN_POINT('',(1.94159632,35.91751008,1.7018)); #3656 = SURFACE_CURVE('',#3657,(#3661,#3668),.PCURVE_S1.); #3657 = LINE('',#3658,#3659); -#3658 = CARTESIAN_POINT('',(2.36249464,36.0185589,2.29108)); +#3658 = CARTESIAN_POINT('',(2.36249464,36.0185589,1.7018)); #3659 = VECTOR('',#3660,1.); #3660 = DIRECTION('',(-0.972369881782,-0.2334455247,0.E+000)); #3661 = PCURVE('',#3616,#3662); #3662 = DEFINITIONAL_REPRESENTATION('',(#3663),#3667); #3663 = LINE('',#3664,#3665); -#3664 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3664 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3665 = VECTOR('',#3666,1.); #3666 = DIRECTION('',(1.,0.E+000)); #3667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4286,16 +4288,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3728 = ORIENTED_EDGE('',*,*,#3729,.T.); #3729 = EDGE_CURVE('',#3654,#3730,#3732,.T.); #3730 = VERTEX_POINT('',#3731); -#3731 = CARTESIAN_POINT('',(1.54168602,35.75186144,2.29108)); +#3731 = CARTESIAN_POINT('',(1.54168602,35.75186144,1.7018)); #3732 = SURFACE_CURVE('',#3733,(#3737,#3744),.PCURVE_S1.); #3733 = LINE('',#3734,#3735); -#3734 = CARTESIAN_POINT('',(1.94159632,35.91751008,2.29108)); +#3734 = CARTESIAN_POINT('',(1.94159632,35.91751008,1.7018)); #3735 = VECTOR('',#3736,1.); #3736 = DIRECTION('',(-0.923879230295,-0.38268416198,0.E+000)); #3737 = PCURVE('',#3692,#3738); #3738 = DEFINITIONAL_REPRESENTATION('',(#3739),#3743); #3739 = LINE('',#3740,#3741); -#3740 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3740 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3741 = VECTOR('',#3742,1.); #3742 = DIRECTION('',(1.,0.E+000)); #3743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4374,16 +4376,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3804 = ORIENTED_EDGE('',*,*,#3805,.T.); #3805 = EDGE_CURVE('',#3730,#3806,#3808,.T.); #3806 = VERTEX_POINT('',#3807); -#3807 = CARTESIAN_POINT('',(1.17261386,35.52569476,2.29108)); +#3807 = CARTESIAN_POINT('',(1.17261386,35.52569476,1.7018)); #3808 = SURFACE_CURVE('',#3809,(#3813,#3820),.PCURVE_S1.); #3809 = LINE('',#3810,#3811); -#3810 = CARTESIAN_POINT('',(1.54168602,35.75186144,2.29108)); +#3810 = CARTESIAN_POINT('',(1.54168602,35.75186144,1.7018)); #3811 = VECTOR('',#3812,1.); #3812 = DIRECTION('',(-0.852641224987,-0.522496833916,0.E+000)); #3813 = PCURVE('',#3768,#3814); #3814 = DEFINITIONAL_REPRESENTATION('',(#3815),#3819); #3815 = LINE('',#3816,#3817); -#3816 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3816 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3817 = VECTOR('',#3818,1.); #3818 = DIRECTION('',(1.,0.E+000)); #3819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4462,16 +4464,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3880 = ORIENTED_EDGE('',*,*,#3881,.T.); #3881 = EDGE_CURVE('',#3806,#3882,#3884,.T.); #3882 = VERTEX_POINT('',#3883); -#3883 = CARTESIAN_POINT('',(0.84346288,35.24457518,2.29108)); +#3883 = CARTESIAN_POINT('',(0.84346288,35.24457518,1.7018)); #3884 = SURFACE_CURVE('',#3885,(#3889,#3896),.PCURVE_S1.); #3885 = LINE('',#3886,#3887); -#3886 = CARTESIAN_POINT('',(1.17261386,35.52569476,2.29108)); +#3886 = CARTESIAN_POINT('',(1.17261386,35.52569476,1.7018)); #3887 = VECTOR('',#3888,1.); #3888 = DIRECTION('',(-0.760408149955,-0.649445490771,0.E+000)); #3889 = PCURVE('',#3844,#3890); #3890 = DEFINITIONAL_REPRESENTATION('',(#3891),#3895); #3891 = LINE('',#3892,#3893); -#3892 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3892 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3893 = VECTOR('',#3894,1.); #3894 = DIRECTION('',(1.,0.E+000)); #3895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4550,16 +4552,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #3956 = ORIENTED_EDGE('',*,*,#3957,.T.); #3957 = EDGE_CURVE('',#3882,#3958,#3960,.T.); #3958 = VERTEX_POINT('',#3959); -#3959 = CARTESIAN_POINT('',(0.5623433,34.9154242,2.29108)); +#3959 = CARTESIAN_POINT('',(0.5623433,34.9154242,1.7018)); #3960 = SURFACE_CURVE('',#3961,(#3965,#3972),.PCURVE_S1.); #3961 = LINE('',#3962,#3963); -#3962 = CARTESIAN_POINT('',(0.84346288,35.24457518,2.29108)); +#3962 = CARTESIAN_POINT('',(0.84346288,35.24457518,1.7018)); #3963 = VECTOR('',#3964,1.); #3964 = DIRECTION('',(-0.649445490771,-0.760408149955,0.E+000)); #3965 = PCURVE('',#3920,#3966); #3966 = DEFINITIONAL_REPRESENTATION('',(#3967),#3971); #3967 = LINE('',#3968,#3969); -#3968 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#3968 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #3969 = VECTOR('',#3970,1.); #3970 = DIRECTION('',(1.,0.E+000)); #3971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4638,16 +4640,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4032 = ORIENTED_EDGE('',*,*,#4033,.T.); #4033 = EDGE_CURVE('',#3958,#4034,#4036,.T.); #4034 = VERTEX_POINT('',#4035); -#4035 = CARTESIAN_POINT('',(0.33617662,34.54635204,2.29108)); +#4035 = CARTESIAN_POINT('',(0.33617662,34.54635204,1.7018)); #4036 = SURFACE_CURVE('',#4037,(#4041,#4048),.PCURVE_S1.); #4037 = LINE('',#4038,#4039); -#4038 = CARTESIAN_POINT('',(0.5623433,34.9154242,2.29108)); +#4038 = CARTESIAN_POINT('',(0.5623433,34.9154242,1.7018)); #4039 = VECTOR('',#4040,1.); #4040 = DIRECTION('',(-0.522496833916,-0.852641224987,0.E+000)); #4041 = PCURVE('',#3996,#4042); #4042 = DEFINITIONAL_REPRESENTATION('',(#4043),#4047); #4043 = LINE('',#4044,#4045); -#4044 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4044 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4045 = VECTOR('',#4046,1.); #4046 = DIRECTION('',(1.,0.E+000)); #4047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4726,16 +4728,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4108 = ORIENTED_EDGE('',*,*,#4109,.T.); #4109 = EDGE_CURVE('',#4034,#4110,#4112,.T.); #4110 = VERTEX_POINT('',#4111); -#4111 = CARTESIAN_POINT('',(0.17052798,34.14644174,2.29108)); +#4111 = CARTESIAN_POINT('',(0.17052798,34.14644174,1.7018)); #4112 = SURFACE_CURVE('',#4113,(#4117,#4124),.PCURVE_S1.); #4113 = LINE('',#4114,#4115); -#4114 = CARTESIAN_POINT('',(0.33617662,34.54635204,2.29108)); +#4114 = CARTESIAN_POINT('',(0.33617662,34.54635204,1.7018)); #4115 = VECTOR('',#4116,1.); #4116 = DIRECTION('',(-0.38268416198,-0.923879230295,0.E+000)); #4117 = PCURVE('',#4072,#4118); #4118 = DEFINITIONAL_REPRESENTATION('',(#4119),#4123); #4119 = LINE('',#4120,#4121); -#4120 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4120 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4121 = VECTOR('',#4122,1.); #4122 = DIRECTION('',(1.,0.E+000)); #4123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4814,16 +4816,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4184 = ORIENTED_EDGE('',*,*,#4185,.T.); #4185 = EDGE_CURVE('',#4110,#4186,#4188,.T.); #4186 = VERTEX_POINT('',#4187); -#4187 = CARTESIAN_POINT('',(6.947916E-002,33.72554342,2.29108)); +#4187 = CARTESIAN_POINT('',(6.947916E-002,33.72554342,1.7018)); #4188 = SURFACE_CURVE('',#4189,(#4193,#4200),.PCURVE_S1.); #4189 = LINE('',#4190,#4191); -#4190 = CARTESIAN_POINT('',(0.17052798,34.14644174,2.29108)); +#4190 = CARTESIAN_POINT('',(0.17052798,34.14644174,1.7018)); #4191 = VECTOR('',#4192,1.); #4192 = DIRECTION('',(-0.2334455247,-0.972369881782,0.E+000)); #4193 = PCURVE('',#4148,#4194); #4194 = DEFINITIONAL_REPRESENTATION('',(#4195),#4199); #4195 = LINE('',#4196,#4197); -#4196 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4196 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4197 = VECTOR('',#4198,1.); #4198 = DIRECTION('',(1.,0.E+000)); #4199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4902,16 +4904,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4260 = ORIENTED_EDGE('',*,*,#4261,.T.); #4261 = EDGE_CURVE('',#4186,#4262,#4264,.T.); #4262 = VERTEX_POINT('',#4263); -#4263 = CARTESIAN_POINT('',(3.551682000001E-002,33.29401774,2.29108)); +#4263 = CARTESIAN_POINT('',(3.551682000001E-002,33.29401774,1.7018)); #4264 = SURFACE_CURVE('',#4265,(#4269,#4276),.PCURVE_S1.); #4265 = LINE('',#4266,#4267); -#4266 = CARTESIAN_POINT('',(6.947916E-002,33.72554342,2.29108)); +#4266 = CARTESIAN_POINT('',(6.947916E-002,33.72554342,1.7018)); #4267 = VECTOR('',#4268,1.); #4268 = DIRECTION('',(-7.846031821911E-002,-0.99691723752,0.E+000)); #4269 = PCURVE('',#4224,#4270); #4270 = DEFINITIONAL_REPRESENTATION('',(#4271),#4275); #4271 = LINE('',#4272,#4273); -#4272 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4272 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4273 = VECTOR('',#4274,1.); #4274 = DIRECTION('',(1.,0.E+000)); #4275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -4990,16 +4992,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4336 = ORIENTED_EDGE('',*,*,#4337,.T.); #4337 = EDGE_CURVE('',#4262,#4338,#4340,.T.); #4338 = VERTEX_POINT('',#4339); -#4339 = CARTESIAN_POINT('',(4.402074E-002,33.29401774,2.29108)); +#4339 = CARTESIAN_POINT('',(4.402074E-002,33.29401774,1.7018)); #4340 = SURFACE_CURVE('',#4341,(#4345,#4352),.PCURVE_S1.); #4341 = LINE('',#4342,#4343); -#4342 = CARTESIAN_POINT('',(3.551682000001E-002,33.29401774,2.29108)); +#4342 = CARTESIAN_POINT('',(3.551682000001E-002,33.29401774,1.7018)); #4343 = VECTOR('',#4344,1.); #4344 = DIRECTION('',(1.,0.E+000,0.E+000)); #4345 = PCURVE('',#4300,#4346); #4346 = DEFINITIONAL_REPRESENTATION('',(#4347),#4351); #4347 = LINE('',#4348,#4349); -#4348 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4348 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4349 = VECTOR('',#4350,1.); #4350 = DIRECTION('',(1.,0.E+000)); #4351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -5078,16 +5080,16 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4412 = ORIENTED_EDGE('',*,*,#4413,.T.); #4413 = EDGE_CURVE('',#4338,#4414,#4416,.T.); #4414 = VERTEX_POINT('',#4415); -#4415 = CARTESIAN_POINT('',(4.40436E-002,33.2940152,2.29108)); +#4415 = CARTESIAN_POINT('',(4.40436E-002,33.2940152,1.7018)); #4416 = SURFACE_CURVE('',#4417,(#4421,#4428),.PCURVE_S1.); #4417 = LINE('',#4418,#4419); -#4418 = CARTESIAN_POINT('',(4.402074E-002,33.29401774,2.29108)); +#4418 = CARTESIAN_POINT('',(4.402074E-002,33.29401774,1.7018)); #4419 = VECTOR('',#4420,1.); #4420 = DIRECTION('',(0.993883734689,-0.110431525939,0.E+000)); #4421 = PCURVE('',#4376,#4422); #4422 = DEFINITIONAL_REPRESENTATION('',(#4423),#4427); #4423 = LINE('',#4424,#4425); -#4424 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4424 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4425 = VECTOR('',#4426,1.); #4426 = DIRECTION('',(1.,0.E+000)); #4427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -5162,13 +5164,13 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4484 = EDGE_CURVE('',#4414,#343,#4485,.T.); #4485 = SURFACE_CURVE('',#4486,(#4490,#4497),.PCURVE_S1.); #4486 = LINE('',#4487,#4488); -#4487 = CARTESIAN_POINT('',(4.40436E-002,33.2940152,2.29108)); +#4487 = CARTESIAN_POINT('',(4.40436E-002,33.2940152,1.7018)); #4488 = VECTOR('',#4489,1.); #4489 = DIRECTION('',(-2.795665701004E-004,-0.999999960921,0.E+000)); #4490 = PCURVE('',#363,#4491); #4491 = DEFINITIONAL_REPRESENTATION('',(#4492),#4496); #4492 = LINE('',#4493,#4494); -#4493 = CARTESIAN_POINT('',(0.E+000,-2.29108)); +#4493 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #4494 = VECTOR('',#4495,1.); #4495 = DIRECTION('',(1.,0.E+000)); #4496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) @@ -5209,6661 +5211,9648 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' #4525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#4526 = ADVANCED_FACE('',(#4527),#445,.T.); -#4527 = FACE_BOUND('',#4528,.F.); -#4528 = EDGE_LOOP('',(#4529,#4530,#4531,#4532,#4533,#4534,#4535,#4536, - #4537,#4538,#4539,#4540,#4541,#4542,#4543,#4544,#4545,#4546,#4547, - #4548,#4549,#4550,#4551,#4552,#4553,#4554,#4555,#4556,#4557,#4558, - #4559,#4560,#4561,#4562,#4563,#4564,#4565,#4566,#4567,#4568,#4569, - #4570,#4571,#4572,#4573,#4574,#4575,#4576,#4577,#4578,#4579,#4580, - #4581,#4582,#4583)); -#4529 = ORIENTED_EDGE('',*,*,#431,.T.); -#4530 = ORIENTED_EDGE('',*,*,#512,.T.); -#4531 = ORIENTED_EDGE('',*,*,#588,.T.); -#4532 = ORIENTED_EDGE('',*,*,#664,.T.); -#4533 = ORIENTED_EDGE('',*,*,#740,.T.); -#4534 = ORIENTED_EDGE('',*,*,#816,.T.); -#4535 = ORIENTED_EDGE('',*,*,#892,.T.); -#4536 = ORIENTED_EDGE('',*,*,#968,.T.); -#4537 = ORIENTED_EDGE('',*,*,#1044,.T.); -#4538 = ORIENTED_EDGE('',*,*,#1120,.T.); -#4539 = ORIENTED_EDGE('',*,*,#1196,.T.); -#4540 = ORIENTED_EDGE('',*,*,#1272,.T.); -#4541 = ORIENTED_EDGE('',*,*,#1348,.T.); -#4542 = ORIENTED_EDGE('',*,*,#1424,.T.); -#4543 = ORIENTED_EDGE('',*,*,#1500,.T.); -#4544 = ORIENTED_EDGE('',*,*,#1576,.T.); -#4545 = ORIENTED_EDGE('',*,*,#1652,.T.); -#4546 = ORIENTED_EDGE('',*,*,#1728,.T.); -#4547 = ORIENTED_EDGE('',*,*,#1804,.T.); -#4548 = ORIENTED_EDGE('',*,*,#1880,.T.); -#4549 = ORIENTED_EDGE('',*,*,#1956,.T.); -#4550 = ORIENTED_EDGE('',*,*,#2032,.T.); -#4551 = ORIENTED_EDGE('',*,*,#2108,.T.); -#4552 = ORIENTED_EDGE('',*,*,#2184,.T.); -#4553 = ORIENTED_EDGE('',*,*,#2260,.T.); -#4554 = ORIENTED_EDGE('',*,*,#2336,.T.); -#4555 = ORIENTED_EDGE('',*,*,#2412,.T.); -#4556 = ORIENTED_EDGE('',*,*,#2488,.T.); -#4557 = ORIENTED_EDGE('',*,*,#2564,.T.); -#4558 = ORIENTED_EDGE('',*,*,#2640,.T.); -#4559 = ORIENTED_EDGE('',*,*,#2716,.T.); -#4560 = ORIENTED_EDGE('',*,*,#2792,.T.); -#4561 = ORIENTED_EDGE('',*,*,#2868,.T.); -#4562 = ORIENTED_EDGE('',*,*,#2944,.T.); -#4563 = ORIENTED_EDGE('',*,*,#3020,.T.); -#4564 = ORIENTED_EDGE('',*,*,#3096,.T.); -#4565 = ORIENTED_EDGE('',*,*,#3172,.T.); -#4566 = ORIENTED_EDGE('',*,*,#3248,.T.); -#4567 = ORIENTED_EDGE('',*,*,#3324,.T.); -#4568 = ORIENTED_EDGE('',*,*,#3400,.T.); -#4569 = ORIENTED_EDGE('',*,*,#3476,.T.); -#4570 = ORIENTED_EDGE('',*,*,#3552,.T.); -#4571 = ORIENTED_EDGE('',*,*,#3628,.T.); -#4572 = ORIENTED_EDGE('',*,*,#3704,.T.); -#4573 = ORIENTED_EDGE('',*,*,#3780,.T.); -#4574 = ORIENTED_EDGE('',*,*,#3856,.T.); -#4575 = ORIENTED_EDGE('',*,*,#3932,.T.); -#4576 = ORIENTED_EDGE('',*,*,#4008,.T.); -#4577 = ORIENTED_EDGE('',*,*,#4084,.T.); -#4578 = ORIENTED_EDGE('',*,*,#4160,.T.); -#4579 = ORIENTED_EDGE('',*,*,#4236,.T.); -#4580 = ORIENTED_EDGE('',*,*,#4312,.T.); -#4581 = ORIENTED_EDGE('',*,*,#4388,.T.); -#4582 = ORIENTED_EDGE('',*,*,#4459,.T.); -#4583 = ORIENTED_EDGE('',*,*,#4506,.T.); -#4584 = ADVANCED_FACE('',(#4585),#391,.F.); -#4585 = FACE_BOUND('',#4586,.T.); -#4586 = EDGE_LOOP('',(#4587,#4588,#4589,#4590,#4591,#4592,#4593,#4594, - #4595,#4596,#4597,#4598,#4599,#4600,#4601,#4602,#4603,#4604,#4605, - #4606,#4607,#4608,#4609,#4610,#4611,#4612,#4613,#4614,#4615,#4616, - #4617,#4618,#4619,#4620,#4621,#4622,#4623,#4624,#4625,#4626,#4627, - #4628,#4629,#4630,#4631,#4632,#4633,#4634,#4635,#4636,#4637,#4638, - #4639,#4640,#4641)); -#4587 = ORIENTED_EDGE('',*,*,#375,.T.); -#4588 = ORIENTED_EDGE('',*,*,#461,.T.); -#4589 = ORIENTED_EDGE('',*,*,#537,.T.); -#4590 = ORIENTED_EDGE('',*,*,#613,.T.); -#4591 = ORIENTED_EDGE('',*,*,#689,.T.); -#4592 = ORIENTED_EDGE('',*,*,#765,.T.); -#4593 = ORIENTED_EDGE('',*,*,#841,.T.); -#4594 = ORIENTED_EDGE('',*,*,#917,.T.); -#4595 = ORIENTED_EDGE('',*,*,#993,.T.); -#4596 = ORIENTED_EDGE('',*,*,#1069,.T.); -#4597 = ORIENTED_EDGE('',*,*,#1145,.T.); -#4598 = ORIENTED_EDGE('',*,*,#1221,.T.); -#4599 = ORIENTED_EDGE('',*,*,#1297,.T.); -#4600 = ORIENTED_EDGE('',*,*,#1373,.T.); -#4601 = ORIENTED_EDGE('',*,*,#1449,.T.); -#4602 = ORIENTED_EDGE('',*,*,#1525,.T.); -#4603 = ORIENTED_EDGE('',*,*,#1601,.T.); -#4604 = ORIENTED_EDGE('',*,*,#1677,.T.); -#4605 = ORIENTED_EDGE('',*,*,#1753,.T.); -#4606 = ORIENTED_EDGE('',*,*,#1829,.T.); -#4607 = ORIENTED_EDGE('',*,*,#1905,.T.); -#4608 = ORIENTED_EDGE('',*,*,#1981,.T.); -#4609 = ORIENTED_EDGE('',*,*,#2057,.T.); -#4610 = ORIENTED_EDGE('',*,*,#2133,.T.); -#4611 = ORIENTED_EDGE('',*,*,#2209,.T.); -#4612 = ORIENTED_EDGE('',*,*,#2285,.T.); -#4613 = ORIENTED_EDGE('',*,*,#2361,.T.); -#4614 = ORIENTED_EDGE('',*,*,#2437,.T.); -#4615 = ORIENTED_EDGE('',*,*,#2513,.T.); -#4616 = ORIENTED_EDGE('',*,*,#2589,.T.); -#4617 = ORIENTED_EDGE('',*,*,#2665,.T.); -#4618 = ORIENTED_EDGE('',*,*,#2741,.T.); -#4619 = ORIENTED_EDGE('',*,*,#2817,.T.); -#4620 = ORIENTED_EDGE('',*,*,#2893,.T.); -#4621 = ORIENTED_EDGE('',*,*,#2969,.T.); -#4622 = ORIENTED_EDGE('',*,*,#3045,.T.); -#4623 = ORIENTED_EDGE('',*,*,#3121,.T.); -#4624 = ORIENTED_EDGE('',*,*,#3197,.T.); -#4625 = ORIENTED_EDGE('',*,*,#3273,.T.); -#4626 = ORIENTED_EDGE('',*,*,#3349,.T.); -#4627 = ORIENTED_EDGE('',*,*,#3425,.T.); -#4628 = ORIENTED_EDGE('',*,*,#3501,.T.); -#4629 = ORIENTED_EDGE('',*,*,#3577,.T.); -#4630 = ORIENTED_EDGE('',*,*,#3653,.T.); -#4631 = ORIENTED_EDGE('',*,*,#3729,.T.); -#4632 = ORIENTED_EDGE('',*,*,#3805,.T.); -#4633 = ORIENTED_EDGE('',*,*,#3881,.T.); -#4634 = ORIENTED_EDGE('',*,*,#3957,.T.); -#4635 = ORIENTED_EDGE('',*,*,#4033,.T.); -#4636 = ORIENTED_EDGE('',*,*,#4109,.T.); -#4637 = ORIENTED_EDGE('',*,*,#4185,.T.); -#4638 = ORIENTED_EDGE('',*,*,#4261,.T.); -#4639 = ORIENTED_EDGE('',*,*,#4337,.T.); -#4640 = ORIENTED_EDGE('',*,*,#4413,.T.); -#4641 = ORIENTED_EDGE('',*,*,#4484,.T.); -#4642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#4646)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#4643,#4644,#4645)) REPRESENTATION_CONTEXT -('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#4643 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#4644 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#4645 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#4646 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#4643, - 'distance_accuracy_value','confusion accuracy'); -#4647 = SHAPE_DEFINITION_REPRESENTATION(#4648,#333); -#4648 = PRODUCT_DEFINITION_SHAPE('','',#4649); -#4649 = PRODUCT_DEFINITION('design','',#4650,#4653); -#4650 = PRODUCT_DEFINITION_FORMATION('','',#4651); -#4651 = PRODUCT('Board','Board','',(#4652)); -#4652 = PRODUCT_CONTEXT('',#2,'mechanical'); -#4653 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#4654 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#4655,#4657); -#4655 = ( REPRESENTATION_RELATIONSHIP('','',#333,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#4656) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#4656 = ITEM_DEFINED_TRANSFORMATION('','',#11,#15); -#4657 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #4658); -#4658 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('133','=>[0:1:1:2]','',#5,#4649,$ - ); -#4659 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#4651)); -#4660 = SHAPE_DEFINITION_REPRESENTATION(#4661,#4667); -#4661 = PRODUCT_DEFINITION_SHAPE('','',#4662); -#4662 = PRODUCT_DEFINITION('design','',#4663,#4666); -#4663 = PRODUCT_DEFINITION_FORMATION('','',#4664); -#4664 = PRODUCT('FIL1','FIL1','',(#4665)); -#4665 = PRODUCT_CONTEXT('',#2,'mechanical'); -#4666 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#4667 = SHAPE_REPRESENTATION('',(#11,#4668),#4672); -#4668 = AXIS2_PLACEMENT_3D('',#4669,#4670,#4671); -#4669 = CARTESIAN_POINT('',(8.636,29.21,-3.21838066)); -#4670 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4671 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#4676)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#4673,#4674,#4675)) REPRESENTATION_CONTEXT -('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#4673 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#4674 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#4675 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#4676 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#4673, - 'distance_accuracy_value','confusion accuracy'); -#4677 = SHAPE_DEFINITION_REPRESENTATION(#4678,#4684); -#4678 = PRODUCT_DEFINITION_SHAPE('','',#4679); -#4679 = PRODUCT_DEFINITION('design','',#4680,#4683); -#4680 = PRODUCT_DEFINITION_FORMATION('','',#4681); -#4681 = PRODUCT('622931488','622931488','',(#4682)); -#4682 = PRODUCT_CONTEXT('',#2,'mechanical'); -#4683 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#4684 = SHAPE_REPRESENTATION('',(#11,#4685),#4689); -#4685 = AXIS2_PLACEMENT_3D('',#4686,#4687,#4688); -#4686 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#4687 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4688 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#4693)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#4690,#4691,#4692)) REPRESENTATION_CONTEXT -('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#4690 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#4691 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#4692 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#4693 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#4690, - 'distance_accuracy_value','confusion accuracy'); -#4694 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#4695),#5025); -#4695 = MANIFOLD_SOLID_BREP('',#4696); -#4696 = CLOSED_SHELL('',(#4697,#4817,#4893,#4964,#5011,#5018)); -#4697 = ADVANCED_FACE('',(#4698),#4712,.F.); -#4698 = FACE_BOUND('',#4699,.F.); -#4699 = EDGE_LOOP('',(#4700,#4735,#4763,#4791)); -#4700 = ORIENTED_EDGE('',*,*,#4701,.T.); -#4701 = EDGE_CURVE('',#4702,#4704,#4706,.T.); -#4702 = VERTEX_POINT('',#4703); -#4703 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); -#4704 = VERTEX_POINT('',#4705); -#4705 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); -#4706 = SURFACE_CURVE('',#4707,(#4711,#4723),.PCURVE_S1.); -#4707 = LINE('',#4708,#4709); -#4708 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); -#4709 = VECTOR('',#4710,1.); -#4710 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4711 = PCURVE('',#4712,#4717); -#4712 = PLANE('',#4713); -#4713 = AXIS2_PLACEMENT_3D('',#4714,#4715,#4716); -#4714 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); -#4715 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4716 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#4717 = DEFINITIONAL_REPRESENTATION('',(#4718),#4722); -#4718 = LINE('',#4719,#4720); -#4719 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4720 = VECTOR('',#4721,1.); -#4721 = DIRECTION('',(0.E+000,-1.)); -#4722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4723 = PCURVE('',#4724,#4729); -#4724 = PLANE('',#4725); -#4725 = AXIS2_PLACEMENT_3D('',#4726,#4727,#4728); -#4726 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); -#4727 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#4728 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#4729 = DEFINITIONAL_REPRESENTATION('',(#4730),#4734); -#4730 = LINE('',#4731,#4732); -#4731 = CARTESIAN_POINT('',(1.60000188,0.E+000)); -#4732 = VECTOR('',#4733,1.); -#4733 = DIRECTION('',(0.E+000,-1.)); -#4734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4735 = ORIENTED_EDGE('',*,*,#4736,.T.); -#4736 = EDGE_CURVE('',#4704,#4737,#4739,.T.); -#4737 = VERTEX_POINT('',#4738); -#4738 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.94)); -#4739 = SURFACE_CURVE('',#4740,(#4744,#4751),.PCURVE_S1.); -#4740 = LINE('',#4741,#4742); -#4741 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); -#4742 = VECTOR('',#4743,1.); -#4743 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#4744 = PCURVE('',#4712,#4745); -#4745 = DEFINITIONAL_REPRESENTATION('',(#4746),#4750); -#4746 = LINE('',#4747,#4748); -#4747 = CARTESIAN_POINT('',(0.E+000,-0.94)); -#4748 = VECTOR('',#4749,1.); -#4749 = DIRECTION('',(1.,0.E+000)); -#4750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4751 = PCURVE('',#4752,#4757); -#4752 = PLANE('',#4753); -#4753 = AXIS2_PLACEMENT_3D('',#4754,#4755,#4756); -#4754 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); -#4755 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#4756 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#4757 = DEFINITIONAL_REPRESENTATION('',(#4758),#4762); -#4758 = LINE('',#4759,#4760); -#4759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4760 = VECTOR('',#4761,1.); -#4761 = DIRECTION('',(0.E+000,-1.)); -#4762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4763 = ORIENTED_EDGE('',*,*,#4764,.F.); -#4764 = EDGE_CURVE('',#4765,#4737,#4767,.T.); -#4765 = VERTEX_POINT('',#4766); -#4766 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); -#4767 = SURFACE_CURVE('',#4768,(#4772,#4779),.PCURVE_S1.); +#4526 = ADVANCED_FACE('',(#4527),#4541,.F.); +#4527 = FACE_BOUND('',#4528,.T.); +#4528 = EDGE_LOOP('',(#4529,#4559,#4585,#4586)); +#4529 = ORIENTED_EDGE('',*,*,#4530,.T.); +#4530 = EDGE_CURVE('',#4531,#4533,#4535,.T.); +#4531 = VERTEX_POINT('',#4532); +#4532 = CARTESIAN_POINT('',(4.29399954,2.794,0.E+000)); +#4533 = VERTEX_POINT('',#4534); +#4534 = CARTESIAN_POINT('',(4.29399954,2.794,1.7018)); +#4535 = SEAM_CURVE('',#4536,(#4540,#4552),.PCURVE_S1.); +#4536 = LINE('',#4537,#4538); +#4537 = CARTESIAN_POINT('',(4.29399954,2.794,0.E+000)); +#4538 = VECTOR('',#4539,1.); +#4539 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4540 = PCURVE('',#4541,#4546); +#4541 = CYLINDRICAL_SURFACE('',#4542,1.49999954); +#4542 = AXIS2_PLACEMENT_3D('',#4543,#4544,#4545); +#4543 = CARTESIAN_POINT('',(2.794,2.794,0.E+000)); +#4544 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4545 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4546 = DEFINITIONAL_REPRESENTATION('',(#4547),#4551); +#4547 = LINE('',#4548,#4549); +#4548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4549 = VECTOR('',#4550,1.); +#4550 = DIRECTION('',(0.E+000,-1.)); +#4551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4552 = PCURVE('',#4541,#4553); +#4553 = DEFINITIONAL_REPRESENTATION('',(#4554),#4558); +#4554 = LINE('',#4555,#4556); +#4555 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#4556 = VECTOR('',#4557,1.); +#4557 = DIRECTION('',(0.E+000,-1.)); +#4558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4559 = ORIENTED_EDGE('',*,*,#4560,.T.); +#4560 = EDGE_CURVE('',#4533,#4533,#4561,.T.); +#4561 = SURFACE_CURVE('',#4562,(#4567,#4574),.PCURVE_S1.); +#4562 = CIRCLE('',#4563,1.49999954); +#4563 = AXIS2_PLACEMENT_3D('',#4564,#4565,#4566); +#4564 = CARTESIAN_POINT('',(2.794,2.794,1.7018)); +#4565 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4566 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4567 = PCURVE('',#4541,#4568); +#4568 = DEFINITIONAL_REPRESENTATION('',(#4569),#4573); +#4569 = LINE('',#4570,#4571); +#4570 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#4571 = VECTOR('',#4572,1.); +#4572 = DIRECTION('',(-1.,0.E+000)); +#4573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4574 = PCURVE('',#391,#4575); +#4575 = DEFINITIONAL_REPRESENTATION('',(#4576),#4584); +#4576 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4577,#4578,#4579,#4580, +#4581,#4582,#4583),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4577 = CARTESIAN_POINT('',(-4.25848272,-1.77800000003E-005)); +#4578 = CARTESIAN_POINT('',(-4.25848272,2.59805763461)); +#4579 = CARTESIAN_POINT('',(-2.00848341,1.299019927305)); +#4580 = CARTESIAN_POINT('',(0.2415159,-1.777999999927E-005)); +#4581 = CARTESIAN_POINT('',(-2.00848341,-1.299055487305)); +#4582 = CARTESIAN_POINT('',(-4.25848272,-2.59809319461)); +#4583 = CARTESIAN_POINT('',(-4.25848272,-1.77800000003E-005)); +#4584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4585 = ORIENTED_EDGE('',*,*,#4530,.F.); +#4586 = ORIENTED_EDGE('',*,*,#4587,.F.); +#4587 = EDGE_CURVE('',#4531,#4531,#4588,.T.); +#4588 = SURFACE_CURVE('',#4589,(#4594,#4601),.PCURVE_S1.); +#4589 = CIRCLE('',#4590,1.49999954); +#4590 = AXIS2_PLACEMENT_3D('',#4591,#4592,#4593); +#4591 = CARTESIAN_POINT('',(2.794,2.794,0.E+000)); +#4592 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4593 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4594 = PCURVE('',#4541,#4595); +#4595 = DEFINITIONAL_REPRESENTATION('',(#4596),#4600); +#4596 = LINE('',#4597,#4598); +#4597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4598 = VECTOR('',#4599,1.); +#4599 = DIRECTION('',(-1.,0.E+000)); +#4600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4601 = PCURVE('',#445,#4602); +#4602 = DEFINITIONAL_REPRESENTATION('',(#4603),#4611); +#4603 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4604,#4605,#4606,#4607, +#4608,#4609,#4610),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4604 = CARTESIAN_POINT('',(-4.25848272,-1.77800000003E-005)); +#4605 = CARTESIAN_POINT('',(-4.25848272,2.59805763461)); +#4606 = CARTESIAN_POINT('',(-2.00848341,1.299019927305)); +#4607 = CARTESIAN_POINT('',(0.2415159,-1.777999999927E-005)); +#4608 = CARTESIAN_POINT('',(-2.00848341,-1.299055487305)); +#4609 = CARTESIAN_POINT('',(-4.25848272,-2.59809319461)); +#4610 = CARTESIAN_POINT('',(-4.25848272,-1.77800000003E-005)); +#4611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4612 = ADVANCED_FACE('',(#4613),#4627,.F.); +#4613 = FACE_BOUND('',#4614,.T.); +#4614 = EDGE_LOOP('',(#4615,#4645,#4671,#4672)); +#4615 = ORIENTED_EDGE('',*,*,#4616,.T.); +#4616 = EDGE_CURVE('',#4617,#4619,#4621,.T.); +#4617 = VERTEX_POINT('',#4618); +#4618 = CARTESIAN_POINT('',(29.5080436,17.4938436,0.E+000)); +#4619 = VERTEX_POINT('',#4620); +#4620 = CARTESIAN_POINT('',(29.5080436,17.4938436,1.7018)); +#4621 = SEAM_CURVE('',#4622,(#4626,#4638),.PCURVE_S1.); +#4622 = LINE('',#4623,#4624); +#4623 = CARTESIAN_POINT('',(29.5080436,17.4938436,0.E+000)); +#4624 = VECTOR('',#4625,1.); +#4625 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4626 = PCURVE('',#4627,#4632); +#4627 = CYLINDRICAL_SURFACE('',#4628,0.508); +#4628 = AXIS2_PLACEMENT_3D('',#4629,#4630,#4631); +#4629 = CARTESIAN_POINT('',(29.0000436,17.4938436,0.E+000)); +#4630 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4631 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4632 = DEFINITIONAL_REPRESENTATION('',(#4633),#4637); +#4633 = LINE('',#4634,#4635); +#4634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4635 = VECTOR('',#4636,1.); +#4636 = DIRECTION('',(0.E+000,-1.)); +#4637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4638 = PCURVE('',#4627,#4639); +#4639 = DEFINITIONAL_REPRESENTATION('',(#4640),#4644); +#4640 = LINE('',#4641,#4642); +#4641 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#4642 = VECTOR('',#4643,1.); +#4643 = DIRECTION('',(0.E+000,-1.)); +#4644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4645 = ORIENTED_EDGE('',*,*,#4646,.T.); +#4646 = EDGE_CURVE('',#4619,#4619,#4647,.T.); +#4647 = SURFACE_CURVE('',#4648,(#4653,#4660),.PCURVE_S1.); +#4648 = CIRCLE('',#4649,0.508); +#4649 = AXIS2_PLACEMENT_3D('',#4650,#4651,#4652); +#4650 = CARTESIAN_POINT('',(29.0000436,17.4938436,1.7018)); +#4651 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4652 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4653 = PCURVE('',#4627,#4654); +#4654 = DEFINITIONAL_REPRESENTATION('',(#4655),#4659); +#4655 = LINE('',#4656,#4657); +#4656 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#4657 = VECTOR('',#4658,1.); +#4658 = DIRECTION('',(-1.,0.E+000)); +#4659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4660 = PCURVE('',#391,#4661); +#4661 = DEFINITIONAL_REPRESENTATION('',(#4662),#4670); +#4662 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4663,#4664,#4665,#4666, +#4667,#4668,#4669),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4663 = CARTESIAN_POINT('',(-29.47252678,14.69982582)); +#4664 = CARTESIAN_POINT('',(-29.47252678,15.579707630245)); +#4665 = CARTESIAN_POINT('',(-28.71052678,15.139766725122)); +#4666 = CARTESIAN_POINT('',(-27.94852678,14.69982582)); +#4667 = CARTESIAN_POINT('',(-28.71052678,14.259884914878)); +#4668 = CARTESIAN_POINT('',(-29.47252678,13.819944009755)); +#4669 = CARTESIAN_POINT('',(-29.47252678,14.69982582)); +#4670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4671 = ORIENTED_EDGE('',*,*,#4616,.F.); +#4672 = ORIENTED_EDGE('',*,*,#4673,.F.); +#4673 = EDGE_CURVE('',#4617,#4617,#4674,.T.); +#4674 = SURFACE_CURVE('',#4675,(#4680,#4687),.PCURVE_S1.); +#4675 = CIRCLE('',#4676,0.508); +#4676 = AXIS2_PLACEMENT_3D('',#4677,#4678,#4679); +#4677 = CARTESIAN_POINT('',(29.0000436,17.4938436,0.E+000)); +#4678 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4679 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4680 = PCURVE('',#4627,#4681); +#4681 = DEFINITIONAL_REPRESENTATION('',(#4682),#4686); +#4682 = LINE('',#4683,#4684); +#4683 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4684 = VECTOR('',#4685,1.); +#4685 = DIRECTION('',(-1.,0.E+000)); +#4686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4687 = PCURVE('',#445,#4688); +#4688 = DEFINITIONAL_REPRESENTATION('',(#4689),#4697); +#4689 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4690,#4691,#4692,#4693, +#4694,#4695,#4696),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4690 = CARTESIAN_POINT('',(-29.47252678,14.69982582)); +#4691 = CARTESIAN_POINT('',(-29.47252678,15.579707630245)); +#4692 = CARTESIAN_POINT('',(-28.71052678,15.139766725122)); +#4693 = CARTESIAN_POINT('',(-27.94852678,14.69982582)); +#4694 = CARTESIAN_POINT('',(-28.71052678,14.259884914878)); +#4695 = CARTESIAN_POINT('',(-29.47252678,13.819944009755)); +#4696 = CARTESIAN_POINT('',(-29.47252678,14.69982582)); +#4697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4698 = ADVANCED_FACE('',(#4699),#4713,.F.); +#4699 = FACE_BOUND('',#4700,.T.); +#4700 = EDGE_LOOP('',(#4701,#4731,#4757,#4758)); +#4701 = ORIENTED_EDGE('',*,*,#4702,.T.); +#4702 = EDGE_CURVE('',#4703,#4705,#4707,.T.); +#4703 = VERTEX_POINT('',#4704); +#4704 = CARTESIAN_POINT('',(29.5080436,14.9538436,0.E+000)); +#4705 = VERTEX_POINT('',#4706); +#4706 = CARTESIAN_POINT('',(29.5080436,14.9538436,1.7018)); +#4707 = SEAM_CURVE('',#4708,(#4712,#4724),.PCURVE_S1.); +#4708 = LINE('',#4709,#4710); +#4709 = CARTESIAN_POINT('',(29.5080436,14.9538436,0.E+000)); +#4710 = VECTOR('',#4711,1.); +#4711 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4712 = PCURVE('',#4713,#4718); +#4713 = CYLINDRICAL_SURFACE('',#4714,0.508); +#4714 = AXIS2_PLACEMENT_3D('',#4715,#4716,#4717); +#4715 = CARTESIAN_POINT('',(29.0000436,14.9538436,0.E+000)); +#4716 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4717 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4718 = DEFINITIONAL_REPRESENTATION('',(#4719),#4723); +#4719 = LINE('',#4720,#4721); +#4720 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4721 = VECTOR('',#4722,1.); +#4722 = DIRECTION('',(0.E+000,-1.)); +#4723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4724 = PCURVE('',#4713,#4725); +#4725 = DEFINITIONAL_REPRESENTATION('',(#4726),#4730); +#4726 = LINE('',#4727,#4728); +#4727 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#4728 = VECTOR('',#4729,1.); +#4729 = DIRECTION('',(0.E+000,-1.)); +#4730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4731 = ORIENTED_EDGE('',*,*,#4732,.T.); +#4732 = EDGE_CURVE('',#4705,#4705,#4733,.T.); +#4733 = SURFACE_CURVE('',#4734,(#4739,#4746),.PCURVE_S1.); +#4734 = CIRCLE('',#4735,0.508); +#4735 = AXIS2_PLACEMENT_3D('',#4736,#4737,#4738); +#4736 = CARTESIAN_POINT('',(29.0000436,14.9538436,1.7018)); +#4737 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4738 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4739 = PCURVE('',#4713,#4740); +#4740 = DEFINITIONAL_REPRESENTATION('',(#4741),#4745); +#4741 = LINE('',#4742,#4743); +#4742 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#4743 = VECTOR('',#4744,1.); +#4744 = DIRECTION('',(-1.,0.E+000)); +#4745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4746 = PCURVE('',#391,#4747); +#4747 = DEFINITIONAL_REPRESENTATION('',(#4748),#4756); +#4748 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4749,#4750,#4751,#4752, +#4753,#4754,#4755),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4749 = CARTESIAN_POINT('',(-29.47252678,12.15982582)); +#4750 = CARTESIAN_POINT('',(-29.47252678,13.039707630245)); +#4751 = CARTESIAN_POINT('',(-28.71052678,12.599766725122)); +#4752 = CARTESIAN_POINT('',(-27.94852678,12.15982582)); +#4753 = CARTESIAN_POINT('',(-28.71052678,11.719884914878)); +#4754 = CARTESIAN_POINT('',(-29.47252678,11.279944009755)); +#4755 = CARTESIAN_POINT('',(-29.47252678,12.15982582)); +#4756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4757 = ORIENTED_EDGE('',*,*,#4702,.F.); +#4758 = ORIENTED_EDGE('',*,*,#4759,.F.); +#4759 = EDGE_CURVE('',#4703,#4703,#4760,.T.); +#4760 = SURFACE_CURVE('',#4761,(#4766,#4773),.PCURVE_S1.); +#4761 = CIRCLE('',#4762,0.508); +#4762 = AXIS2_PLACEMENT_3D('',#4763,#4764,#4765); +#4763 = CARTESIAN_POINT('',(29.0000436,14.9538436,0.E+000)); +#4764 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4765 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4766 = PCURVE('',#4713,#4767); +#4767 = DEFINITIONAL_REPRESENTATION('',(#4768),#4772); #4768 = LINE('',#4769,#4770); -#4769 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); +#4769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #4770 = VECTOR('',#4771,1.); -#4771 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4772 = PCURVE('',#4712,#4773); -#4773 = DEFINITIONAL_REPRESENTATION('',(#4774),#4778); -#4774 = LINE('',#4775,#4776); -#4775 = CARTESIAN_POINT('',(3.19999868,0.E+000)); -#4776 = VECTOR('',#4777,1.); -#4777 = DIRECTION('',(0.E+000,-1.)); -#4778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4779 = PCURVE('',#4780,#4785); -#4780 = PLANE('',#4781); -#4781 = AXIS2_PLACEMENT_3D('',#4782,#4783,#4784); -#4782 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); -#4783 = DIRECTION('',(0.E+000,1.,0.E+000)); -#4784 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4785 = DEFINITIONAL_REPRESENTATION('',(#4786),#4790); -#4786 = LINE('',#4787,#4788); -#4787 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4788 = VECTOR('',#4789,1.); -#4789 = DIRECTION('',(0.E+000,-1.)); -#4790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4791 = ORIENTED_EDGE('',*,*,#4792,.F.); -#4792 = EDGE_CURVE('',#4702,#4765,#4793,.T.); -#4793 = SURFACE_CURVE('',#4794,(#4798,#4805),.PCURVE_S1.); +#4771 = DIRECTION('',(-1.,0.E+000)); +#4772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4773 = PCURVE('',#445,#4774); +#4774 = DEFINITIONAL_REPRESENTATION('',(#4775),#4783); +#4775 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4776,#4777,#4778,#4779, +#4780,#4781,#4782),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4776 = CARTESIAN_POINT('',(-29.47252678,12.15982582)); +#4777 = CARTESIAN_POINT('',(-29.47252678,13.039707630245)); +#4778 = CARTESIAN_POINT('',(-28.71052678,12.599766725122)); +#4779 = CARTESIAN_POINT('',(-27.94852678,12.15982582)); +#4780 = CARTESIAN_POINT('',(-28.71052678,11.719884914878)); +#4781 = CARTESIAN_POINT('',(-29.47252678,11.279944009755)); +#4782 = CARTESIAN_POINT('',(-29.47252678,12.15982582)); +#4783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4784 = ADVANCED_FACE('',(#4785),#4799,.F.); +#4785 = FACE_BOUND('',#4786,.T.); +#4786 = EDGE_LOOP('',(#4787,#4817,#4843,#4844)); +#4787 = ORIENTED_EDGE('',*,*,#4788,.T.); +#4788 = EDGE_CURVE('',#4789,#4791,#4793,.T.); +#4789 = VERTEX_POINT('',#4790); +#4790 = CARTESIAN_POINT('',(32.0480436,17.4938436,0.E+000)); +#4791 = VERTEX_POINT('',#4792); +#4792 = CARTESIAN_POINT('',(32.0480436,17.4938436,1.7018)); +#4793 = SEAM_CURVE('',#4794,(#4798,#4810),.PCURVE_S1.); #4794 = LINE('',#4795,#4796); -#4795 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#4795 = CARTESIAN_POINT('',(32.0480436,17.4938436,0.E+000)); #4796 = VECTOR('',#4797,1.); -#4797 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#4798 = PCURVE('',#4712,#4799); -#4799 = DEFINITIONAL_REPRESENTATION('',(#4800),#4804); -#4800 = LINE('',#4801,#4802); -#4801 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4802 = VECTOR('',#4803,1.); -#4803 = DIRECTION('',(1.,0.E+000)); -#4804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4805 = PCURVE('',#4806,#4811); -#4806 = PLANE('',#4807); -#4807 = AXIS2_PLACEMENT_3D('',#4808,#4809,#4810); -#4808 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); -#4809 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#4810 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#4797 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4798 = PCURVE('',#4799,#4804); +#4799 = CYLINDRICAL_SURFACE('',#4800,0.508); +#4800 = AXIS2_PLACEMENT_3D('',#4801,#4802,#4803); +#4801 = CARTESIAN_POINT('',(31.5400436,17.4938436,0.E+000)); +#4802 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4803 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4804 = DEFINITIONAL_REPRESENTATION('',(#4805),#4809); +#4805 = LINE('',#4806,#4807); +#4806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4807 = VECTOR('',#4808,1.); +#4808 = DIRECTION('',(0.E+000,-1.)); +#4809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4810 = PCURVE('',#4799,#4811); #4811 = DEFINITIONAL_REPRESENTATION('',(#4812),#4816); #4812 = LINE('',#4813,#4814); -#4813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4813 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); #4814 = VECTOR('',#4815,1.); #4815 = DIRECTION('',(0.E+000,-1.)); #4816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#4817 = ADVANCED_FACE('',(#4818),#4780,.F.); -#4818 = FACE_BOUND('',#4819,.F.); -#4819 = EDGE_LOOP('',(#4820,#4821,#4844,#4872)); -#4820 = ORIENTED_EDGE('',*,*,#4764,.T.); -#4821 = ORIENTED_EDGE('',*,*,#4822,.T.); -#4822 = EDGE_CURVE('',#4737,#4823,#4825,.T.); -#4823 = VERTEX_POINT('',#4824); -#4824 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.94)); -#4825 = SURFACE_CURVE('',#4826,(#4830,#4837),.PCURVE_S1.); -#4826 = LINE('',#4827,#4828); -#4827 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.94)); -#4828 = VECTOR('',#4829,1.); -#4829 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4830 = PCURVE('',#4780,#4831); -#4831 = DEFINITIONAL_REPRESENTATION('',(#4832),#4836); -#4832 = LINE('',#4833,#4834); -#4833 = CARTESIAN_POINT('',(0.E+000,-0.94)); -#4834 = VECTOR('',#4835,1.); -#4835 = DIRECTION('',(1.,0.E+000)); -#4836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4837 = PCURVE('',#4752,#4838); -#4838 = DEFINITIONAL_REPRESENTATION('',(#4839),#4843); -#4839 = LINE('',#4840,#4841); -#4840 = CARTESIAN_POINT('',(0.E+000,-3.19999868)); -#4841 = VECTOR('',#4842,1.); -#4842 = DIRECTION('',(-1.,0.E+000)); -#4843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#4817 = ORIENTED_EDGE('',*,*,#4818,.T.); +#4818 = EDGE_CURVE('',#4791,#4791,#4819,.T.); +#4819 = SURFACE_CURVE('',#4820,(#4825,#4832),.PCURVE_S1.); +#4820 = CIRCLE('',#4821,0.508); +#4821 = AXIS2_PLACEMENT_3D('',#4822,#4823,#4824); +#4822 = CARTESIAN_POINT('',(31.5400436,17.4938436,1.7018)); +#4823 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4824 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4825 = PCURVE('',#4799,#4826); +#4826 = DEFINITIONAL_REPRESENTATION('',(#4827),#4831); +#4827 = LINE('',#4828,#4829); +#4828 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#4829 = VECTOR('',#4830,1.); +#4830 = DIRECTION('',(-1.,0.E+000)); +#4831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4832 = PCURVE('',#391,#4833); +#4833 = DEFINITIONAL_REPRESENTATION('',(#4834),#4842); +#4834 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4835,#4836,#4837,#4838, +#4839,#4840,#4841),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4835 = CARTESIAN_POINT('',(-32.01252678,14.69982582)); +#4836 = CARTESIAN_POINT('',(-32.01252678,15.579707630245)); +#4837 = CARTESIAN_POINT('',(-31.25052678,15.139766725122)); +#4838 = CARTESIAN_POINT('',(-30.48852678,14.69982582)); +#4839 = CARTESIAN_POINT('',(-31.25052678,14.259884914877)); +#4840 = CARTESIAN_POINT('',(-32.01252678,13.819944009755)); +#4841 = CARTESIAN_POINT('',(-32.01252678,14.69982582)); +#4842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); +#4843 = ORIENTED_EDGE('',*,*,#4788,.F.); #4844 = ORIENTED_EDGE('',*,*,#4845,.F.); -#4845 = EDGE_CURVE('',#4846,#4823,#4848,.T.); -#4846 = VERTEX_POINT('',#4847); -#4847 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); -#4848 = SURFACE_CURVE('',#4849,(#4853,#4860),.PCURVE_S1.); -#4849 = LINE('',#4850,#4851); -#4850 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); -#4851 = VECTOR('',#4852,1.); -#4852 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4853 = PCURVE('',#4780,#4854); -#4854 = DEFINITIONAL_REPRESENTATION('',(#4855),#4859); -#4855 = LINE('',#4856,#4857); -#4856 = CARTESIAN_POINT('',(1.60000188,0.E+000)); -#4857 = VECTOR('',#4858,1.); -#4858 = DIRECTION('',(0.E+000,-1.)); -#4859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4860 = PCURVE('',#4861,#4866); -#4861 = PLANE('',#4862); -#4862 = AXIS2_PLACEMENT_3D('',#4863,#4864,#4865); -#4863 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); -#4864 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#4865 = DIRECTION('',(0.E+000,1.,0.E+000)); -#4866 = DEFINITIONAL_REPRESENTATION('',(#4867),#4871); -#4867 = LINE('',#4868,#4869); -#4868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4869 = VECTOR('',#4870,1.); -#4870 = DIRECTION('',(0.E+000,-1.)); -#4871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4872 = ORIENTED_EDGE('',*,*,#4873,.F.); -#4873 = EDGE_CURVE('',#4765,#4846,#4874,.T.); -#4874 = SURFACE_CURVE('',#4875,(#4879,#4886),.PCURVE_S1.); -#4875 = LINE('',#4876,#4877); -#4876 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); -#4877 = VECTOR('',#4878,1.); -#4878 = DIRECTION('',(1.,0.E+000,0.E+000)); -#4879 = PCURVE('',#4780,#4880); -#4880 = DEFINITIONAL_REPRESENTATION('',(#4881),#4885); -#4881 = LINE('',#4882,#4883); -#4882 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4883 = VECTOR('',#4884,1.); -#4884 = DIRECTION('',(1.,0.E+000)); -#4885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4886 = PCURVE('',#4806,#4887); -#4887 = DEFINITIONAL_REPRESENTATION('',(#4888),#4892); -#4888 = LINE('',#4889,#4890); -#4889 = CARTESIAN_POINT('',(0.E+000,-3.19999868)); -#4890 = VECTOR('',#4891,1.); -#4891 = DIRECTION('',(-1.,0.E+000)); -#4892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4893 = ADVANCED_FACE('',(#4894),#4861,.F.); -#4894 = FACE_BOUND('',#4895,.F.); -#4895 = EDGE_LOOP('',(#4896,#4897,#4920,#4943)); -#4896 = ORIENTED_EDGE('',*,*,#4845,.T.); -#4897 = ORIENTED_EDGE('',*,*,#4898,.T.); -#4898 = EDGE_CURVE('',#4823,#4899,#4901,.T.); -#4899 = VERTEX_POINT('',#4900); -#4900 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.94)); -#4901 = SURFACE_CURVE('',#4902,(#4906,#4913),.PCURVE_S1.); -#4902 = LINE('',#4903,#4904); -#4903 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.94)); -#4904 = VECTOR('',#4905,1.); -#4905 = DIRECTION('',(0.E+000,1.,0.E+000)); -#4906 = PCURVE('',#4861,#4907); -#4907 = DEFINITIONAL_REPRESENTATION('',(#4908),#4912); -#4908 = LINE('',#4909,#4910); -#4909 = CARTESIAN_POINT('',(0.E+000,-0.94)); -#4910 = VECTOR('',#4911,1.); -#4911 = DIRECTION('',(1.,0.E+000)); -#4912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4913 = PCURVE('',#4752,#4914); -#4914 = DEFINITIONAL_REPRESENTATION('',(#4915),#4919); -#4915 = LINE('',#4916,#4917); -#4916 = CARTESIAN_POINT('',(-1.60000188,-3.19999868)); -#4917 = VECTOR('',#4918,1.); -#4918 = DIRECTION('',(0.E+000,1.)); -#4919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4920 = ORIENTED_EDGE('',*,*,#4921,.F.); -#4921 = EDGE_CURVE('',#4922,#4899,#4924,.T.); -#4922 = VERTEX_POINT('',#4923); -#4923 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); -#4924 = SURFACE_CURVE('',#4925,(#4929,#4936),.PCURVE_S1.); -#4925 = LINE('',#4926,#4927); -#4926 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); -#4927 = VECTOR('',#4928,1.); -#4928 = DIRECTION('',(0.E+000,0.E+000,1.)); -#4929 = PCURVE('',#4861,#4930); -#4930 = DEFINITIONAL_REPRESENTATION('',(#4931),#4935); -#4931 = LINE('',#4932,#4933); -#4932 = CARTESIAN_POINT('',(3.19999868,0.E+000)); -#4933 = VECTOR('',#4934,1.); -#4934 = DIRECTION('',(0.E+000,-1.)); -#4935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4936 = PCURVE('',#4724,#4937); -#4937 = DEFINITIONAL_REPRESENTATION('',(#4938),#4942); -#4938 = LINE('',#4939,#4940); -#4939 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4940 = VECTOR('',#4941,1.); -#4941 = DIRECTION('',(0.E+000,-1.)); -#4942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4943 = ORIENTED_EDGE('',*,*,#4944,.F.); -#4944 = EDGE_CURVE('',#4846,#4922,#4945,.T.); -#4945 = SURFACE_CURVE('',#4946,(#4950,#4957),.PCURVE_S1.); -#4946 = LINE('',#4947,#4948); -#4947 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); -#4948 = VECTOR('',#4949,1.); -#4949 = DIRECTION('',(0.E+000,1.,0.E+000)); -#4950 = PCURVE('',#4861,#4951); -#4951 = DEFINITIONAL_REPRESENTATION('',(#4952),#4956); -#4952 = LINE('',#4953,#4954); -#4953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#4954 = VECTOR('',#4955,1.); -#4955 = DIRECTION('',(1.,0.E+000)); -#4956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4957 = PCURVE('',#4806,#4958); -#4958 = DEFINITIONAL_REPRESENTATION('',(#4959),#4963); -#4959 = LINE('',#4960,#4961); -#4960 = CARTESIAN_POINT('',(-1.60000188,-3.19999868)); -#4961 = VECTOR('',#4962,1.); -#4962 = DIRECTION('',(0.E+000,1.)); -#4963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#4964 = ADVANCED_FACE('',(#4965),#4724,.F.); -#4965 = FACE_BOUND('',#4966,.F.); -#4966 = EDGE_LOOP('',(#4967,#4968,#4989,#4990)); -#4967 = ORIENTED_EDGE('',*,*,#4921,.T.); -#4968 = ORIENTED_EDGE('',*,*,#4969,.T.); -#4969 = EDGE_CURVE('',#4899,#4704,#4970,.T.); -#4970 = SURFACE_CURVE('',#4971,(#4975,#4982),.PCURVE_S1.); -#4971 = LINE('',#4972,#4973); -#4972 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.94)); -#4973 = VECTOR('',#4974,1.); -#4974 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#4975 = PCURVE('',#4724,#4976); +#4845 = EDGE_CURVE('',#4789,#4789,#4846,.T.); +#4846 = SURFACE_CURVE('',#4847,(#4852,#4859),.PCURVE_S1.); +#4847 = CIRCLE('',#4848,0.508); +#4848 = AXIS2_PLACEMENT_3D('',#4849,#4850,#4851); +#4849 = CARTESIAN_POINT('',(31.5400436,17.4938436,0.E+000)); +#4850 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4851 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4852 = PCURVE('',#4799,#4853); +#4853 = DEFINITIONAL_REPRESENTATION('',(#4854),#4858); +#4854 = LINE('',#4855,#4856); +#4855 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4856 = VECTOR('',#4857,1.); +#4857 = DIRECTION('',(-1.,0.E+000)); +#4858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4859 = PCURVE('',#445,#4860); +#4860 = DEFINITIONAL_REPRESENTATION('',(#4861),#4869); +#4861 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4862,#4863,#4864,#4865, +#4866,#4867,#4868),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4862 = CARTESIAN_POINT('',(-32.01252678,14.69982582)); +#4863 = CARTESIAN_POINT('',(-32.01252678,15.579707630245)); +#4864 = CARTESIAN_POINT('',(-31.25052678,15.139766725122)); +#4865 = CARTESIAN_POINT('',(-30.48852678,14.69982582)); +#4866 = CARTESIAN_POINT('',(-31.25052678,14.259884914877)); +#4867 = CARTESIAN_POINT('',(-32.01252678,13.819944009755)); +#4868 = CARTESIAN_POINT('',(-32.01252678,14.69982582)); +#4869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4870 = ADVANCED_FACE('',(#4871),#4885,.F.); +#4871 = FACE_BOUND('',#4872,.T.); +#4872 = EDGE_LOOP('',(#4873,#4903,#4929,#4930)); +#4873 = ORIENTED_EDGE('',*,*,#4874,.T.); +#4874 = EDGE_CURVE('',#4875,#4877,#4879,.T.); +#4875 = VERTEX_POINT('',#4876); +#4876 = CARTESIAN_POINT('',(29.5080436,22.5738436,0.E+000)); +#4877 = VERTEX_POINT('',#4878); +#4878 = CARTESIAN_POINT('',(29.5080436,22.5738436,1.7018)); +#4879 = SEAM_CURVE('',#4880,(#4884,#4896),.PCURVE_S1.); +#4880 = LINE('',#4881,#4882); +#4881 = CARTESIAN_POINT('',(29.5080436,22.5738436,0.E+000)); +#4882 = VECTOR('',#4883,1.); +#4883 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4884 = PCURVE('',#4885,#4890); +#4885 = CYLINDRICAL_SURFACE('',#4886,0.508); +#4886 = AXIS2_PLACEMENT_3D('',#4887,#4888,#4889); +#4887 = CARTESIAN_POINT('',(29.0000436,22.5738436,0.E+000)); +#4888 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4889 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4890 = DEFINITIONAL_REPRESENTATION('',(#4891),#4895); +#4891 = LINE('',#4892,#4893); +#4892 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4893 = VECTOR('',#4894,1.); +#4894 = DIRECTION('',(0.E+000,-1.)); +#4895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4896 = PCURVE('',#4885,#4897); +#4897 = DEFINITIONAL_REPRESENTATION('',(#4898),#4902); +#4898 = LINE('',#4899,#4900); +#4899 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#4900 = VECTOR('',#4901,1.); +#4901 = DIRECTION('',(0.E+000,-1.)); +#4902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4903 = ORIENTED_EDGE('',*,*,#4904,.T.); +#4904 = EDGE_CURVE('',#4877,#4877,#4905,.T.); +#4905 = SURFACE_CURVE('',#4906,(#4911,#4918),.PCURVE_S1.); +#4906 = CIRCLE('',#4907,0.508); +#4907 = AXIS2_PLACEMENT_3D('',#4908,#4909,#4910); +#4908 = CARTESIAN_POINT('',(29.0000436,22.5738436,1.7018)); +#4909 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4910 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4911 = PCURVE('',#4885,#4912); +#4912 = DEFINITIONAL_REPRESENTATION('',(#4913),#4917); +#4913 = LINE('',#4914,#4915); +#4914 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#4915 = VECTOR('',#4916,1.); +#4916 = DIRECTION('',(-1.,0.E+000)); +#4917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4918 = PCURVE('',#391,#4919); +#4919 = DEFINITIONAL_REPRESENTATION('',(#4920),#4928); +#4920 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4921,#4922,#4923,#4924, +#4925,#4926,#4927),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4921 = CARTESIAN_POINT('',(-29.47252678,19.77982582)); +#4922 = CARTESIAN_POINT('',(-29.47252678,20.659707630245)); +#4923 = CARTESIAN_POINT('',(-28.71052678,20.219766725123)); +#4924 = CARTESIAN_POINT('',(-27.94852678,19.77982582)); +#4925 = CARTESIAN_POINT('',(-28.71052678,19.339884914878)); +#4926 = CARTESIAN_POINT('',(-29.47252678,18.899944009755)); +#4927 = CARTESIAN_POINT('',(-29.47252678,19.77982582)); +#4928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4929 = ORIENTED_EDGE('',*,*,#4874,.F.); +#4930 = ORIENTED_EDGE('',*,*,#4931,.F.); +#4931 = EDGE_CURVE('',#4875,#4875,#4932,.T.); +#4932 = SURFACE_CURVE('',#4933,(#4938,#4945),.PCURVE_S1.); +#4933 = CIRCLE('',#4934,0.508); +#4934 = AXIS2_PLACEMENT_3D('',#4935,#4936,#4937); +#4935 = CARTESIAN_POINT('',(29.0000436,22.5738436,0.E+000)); +#4936 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4937 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4938 = PCURVE('',#4885,#4939); +#4939 = DEFINITIONAL_REPRESENTATION('',(#4940),#4944); +#4940 = LINE('',#4941,#4942); +#4941 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#4942 = VECTOR('',#4943,1.); +#4943 = DIRECTION('',(-1.,0.E+000)); +#4944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4945 = PCURVE('',#445,#4946); +#4946 = DEFINITIONAL_REPRESENTATION('',(#4947),#4955); +#4947 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#4948,#4949,#4950,#4951, +#4952,#4953,#4954),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#4948 = CARTESIAN_POINT('',(-29.47252678,19.77982582)); +#4949 = CARTESIAN_POINT('',(-29.47252678,20.659707630245)); +#4950 = CARTESIAN_POINT('',(-28.71052678,20.219766725123)); +#4951 = CARTESIAN_POINT('',(-27.94852678,19.77982582)); +#4952 = CARTESIAN_POINT('',(-28.71052678,19.339884914878)); +#4953 = CARTESIAN_POINT('',(-29.47252678,18.899944009755)); +#4954 = CARTESIAN_POINT('',(-29.47252678,19.77982582)); +#4955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#4956 = ADVANCED_FACE('',(#4957),#4971,.F.); +#4957 = FACE_BOUND('',#4958,.T.); +#4958 = EDGE_LOOP('',(#4959,#4989,#5015,#5016)); +#4959 = ORIENTED_EDGE('',*,*,#4960,.T.); +#4960 = EDGE_CURVE('',#4961,#4963,#4965,.T.); +#4961 = VERTEX_POINT('',#4962); +#4962 = CARTESIAN_POINT('',(29.5080436,20.0338436,0.E+000)); +#4963 = VERTEX_POINT('',#4964); +#4964 = CARTESIAN_POINT('',(29.5080436,20.0338436,1.7018)); +#4965 = SEAM_CURVE('',#4966,(#4970,#4982),.PCURVE_S1.); +#4966 = LINE('',#4967,#4968); +#4967 = CARTESIAN_POINT('',(29.5080436,20.0338436,0.E+000)); +#4968 = VECTOR('',#4969,1.); +#4969 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4970 = PCURVE('',#4971,#4976); +#4971 = CYLINDRICAL_SURFACE('',#4972,0.508); +#4972 = AXIS2_PLACEMENT_3D('',#4973,#4974,#4975); +#4973 = CARTESIAN_POINT('',(29.0000436,20.0338436,0.E+000)); +#4974 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#4975 = DIRECTION('',(1.,0.E+000,0.E+000)); #4976 = DEFINITIONAL_REPRESENTATION('',(#4977),#4981); #4977 = LINE('',#4978,#4979); -#4978 = CARTESIAN_POINT('',(0.E+000,-0.94)); +#4978 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #4979 = VECTOR('',#4980,1.); -#4980 = DIRECTION('',(1.,0.E+000)); +#4980 = DIRECTION('',(0.E+000,-1.)); #4981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#4982 = PCURVE('',#4752,#4983); +#4982 = PCURVE('',#4971,#4983); #4983 = DEFINITIONAL_REPRESENTATION('',(#4984),#4988); #4984 = LINE('',#4985,#4986); -#4985 = CARTESIAN_POINT('',(-1.60000188,0.E+000)); +#4985 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); #4986 = VECTOR('',#4987,1.); -#4987 = DIRECTION('',(1.,0.E+000)); +#4987 = DIRECTION('',(0.E+000,-1.)); #4988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#4989 = ORIENTED_EDGE('',*,*,#4701,.F.); -#4990 = ORIENTED_EDGE('',*,*,#4991,.F.); -#4991 = EDGE_CURVE('',#4922,#4702,#4992,.T.); -#4992 = SURFACE_CURVE('',#4993,(#4997,#5004),.PCURVE_S1.); -#4993 = LINE('',#4994,#4995); -#4994 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); -#4995 = VECTOR('',#4996,1.); -#4996 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#4997 = PCURVE('',#4724,#4998); +#4989 = ORIENTED_EDGE('',*,*,#4990,.T.); +#4990 = EDGE_CURVE('',#4963,#4963,#4991,.T.); +#4991 = SURFACE_CURVE('',#4992,(#4997,#5004),.PCURVE_S1.); +#4992 = CIRCLE('',#4993,0.508); +#4993 = AXIS2_PLACEMENT_3D('',#4994,#4995,#4996); +#4994 = CARTESIAN_POINT('',(29.0000436,20.0338436,1.7018)); +#4995 = DIRECTION('',(0.E+000,0.E+000,1.)); +#4996 = DIRECTION('',(1.,0.E+000,0.E+000)); +#4997 = PCURVE('',#4971,#4998); #4998 = DEFINITIONAL_REPRESENTATION('',(#4999),#5003); #4999 = LINE('',#5000,#5001); -#5000 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5000 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #5001 = VECTOR('',#5002,1.); -#5002 = DIRECTION('',(1.,0.E+000)); +#5002 = DIRECTION('',(-1.,0.E+000)); #5003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5004 = PCURVE('',#4806,#5005); -#5005 = DEFINITIONAL_REPRESENTATION('',(#5006),#5010); -#5006 = LINE('',#5007,#5008); -#5007 = CARTESIAN_POINT('',(-1.60000188,0.E+000)); -#5008 = VECTOR('',#5009,1.); -#5009 = DIRECTION('',(1.,0.E+000)); -#5010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5011 = ADVANCED_FACE('',(#5012),#4806,.T.); -#5012 = FACE_BOUND('',#5013,.F.); -#5013 = EDGE_LOOP('',(#5014,#5015,#5016,#5017)); -#5014 = ORIENTED_EDGE('',*,*,#4792,.T.); -#5015 = ORIENTED_EDGE('',*,*,#4873,.T.); -#5016 = ORIENTED_EDGE('',*,*,#4944,.T.); -#5017 = ORIENTED_EDGE('',*,*,#4991,.T.); -#5018 = ADVANCED_FACE('',(#5019),#4752,.F.); -#5019 = FACE_BOUND('',#5020,.T.); -#5020 = EDGE_LOOP('',(#5021,#5022,#5023,#5024)); -#5021 = ORIENTED_EDGE('',*,*,#4736,.T.); -#5022 = ORIENTED_EDGE('',*,*,#4822,.T.); -#5023 = ORIENTED_EDGE('',*,*,#4898,.T.); -#5024 = ORIENTED_EDGE('',*,*,#4969,.T.); -#5025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#5029)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#5026,#5027,#5028)) REPRESENTATION_CONTEXT -('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#5026 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#5027 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#5028 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#5029 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#5026, - 'distance_accuracy_value','confusion accuracy'); -#5030 = SHAPE_DEFINITION_REPRESENTATION(#5031,#4694); -#5031 = PRODUCT_DEFINITION_SHAPE('','',#5032); -#5032 = PRODUCT_DEFINITION('design','',#5033,#5036); -#5033 = PRODUCT_DEFINITION_FORMATION('','',#5034); -#5034 = PRODUCT('Extruded','Extruded','',(#5035)); -#5035 = PRODUCT_CONTEXT('',#2,'mechanical'); -#5036 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#5037 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#5038,#5040); -#5038 = ( REPRESENTATION_RELATIONSHIP('','',#4694,#4684) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#5039) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#5039 = ITEM_DEFINED_TRANSFORMATION('','',#11,#4685); -#5040 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #5041); -#5041 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('134','=>[0:1:1:2]','',#4679, - #5032,$); -#5042 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#5034)); -#5043 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#5044,#5046); -#5044 = ( REPRESENTATION_RELATIONSHIP('','',#4684,#4667) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#5045) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#5045 = ITEM_DEFINED_TRANSFORMATION('','',#11,#4668); -#5046 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #5047); -#5047 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('135','=>[0:1:1:4]','',#4662, - #4679,$); -#5048 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#4681)); -#5049 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#5050,#5052); -#5050 = ( REPRESENTATION_RELATIONSHIP('','',#4667,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#5051) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#5051 = ITEM_DEFINED_TRANSFORMATION('','',#11,#19); -#5052 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #5053); -#5053 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('136','=>[0:1:1:3]','',#5,#4662,$ - ); -#5054 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#4664)); -#5055 = SHAPE_DEFINITION_REPRESENTATION(#5056,#5062); -#5056 = PRODUCT_DEFINITION_SHAPE('','',#5057); -#5057 = PRODUCT_DEFINITION('design','',#5058,#5061); -#5058 = PRODUCT_DEFINITION_FORMATION('','',#5059); -#5059 = PRODUCT('R8','R8','',(#5060)); -#5060 = PRODUCT_CONTEXT('',#2,'mechanical'); -#5061 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#5062 = SHAPE_REPRESENTATION('',(#11,#5063),#5067); -#5063 = AXIS2_PLACEMENT_3D('',#5064,#5065,#5066); -#5064 = CARTESIAN_POINT('',(14.6090005,6.35,-1.27E-002)); -#5065 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5066 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#5067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#5071)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#5068,#5069,#5070)) REPRESENTATION_CONTEXT -('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#5068 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#5069 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#5070 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#5071 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#5068, - 'distance_accuracy_value','confusion accuracy'); -#5072 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#5073),#7455); -#5073 = MANIFOLD_SOLID_BREP('',#5074); -#5074 = CLOSED_SHELL('',(#5075,#5195,#5305,#5481,#5647,#5704,#5780,#5851 - ,#6034,#6149,#6176,#6203,#6308,#6379,#6428,#6499,#6573,#6584,#6595, - #6666,#6737,#6764,#6791,#6862,#6940,#7016,#7087,#7161,#7172,#7183, - #7215,#7247,#7323,#7372,#7421,#7448)); -#5075 = ADVANCED_FACE('',(#5076),#5090,.T.); -#5076 = FACE_BOUND('',#5077,.T.); -#5077 = EDGE_LOOP('',(#5078,#5113,#5141,#5169)); -#5078 = ORIENTED_EDGE('',*,*,#5079,.T.); -#5079 = EDGE_CURVE('',#5080,#5082,#5084,.T.); -#5080 = VERTEX_POINT('',#5081); -#5081 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); -#5082 = VERTEX_POINT('',#5083); -#5083 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); -#5084 = SURFACE_CURVE('',#5085,(#5089,#5101),.PCURVE_S1.); +#5004 = PCURVE('',#391,#5005); +#5005 = DEFINITIONAL_REPRESENTATION('',(#5006),#5014); +#5006 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5007,#5008,#5009,#5010, +#5011,#5012,#5013),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5007 = CARTESIAN_POINT('',(-29.47252678,17.23982582)); +#5008 = CARTESIAN_POINT('',(-29.47252678,18.119707630245)); +#5009 = CARTESIAN_POINT('',(-28.71052678,17.679766725122)); +#5010 = CARTESIAN_POINT('',(-27.94852678,17.23982582)); +#5011 = CARTESIAN_POINT('',(-28.71052678,16.799884914878)); +#5012 = CARTESIAN_POINT('',(-29.47252678,16.359944009755)); +#5013 = CARTESIAN_POINT('',(-29.47252678,17.23982582)); +#5014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5015 = ORIENTED_EDGE('',*,*,#4960,.F.); +#5016 = ORIENTED_EDGE('',*,*,#5017,.F.); +#5017 = EDGE_CURVE('',#4961,#4961,#5018,.T.); +#5018 = SURFACE_CURVE('',#5019,(#5024,#5031),.PCURVE_S1.); +#5019 = CIRCLE('',#5020,0.508); +#5020 = AXIS2_PLACEMENT_3D('',#5021,#5022,#5023); +#5021 = CARTESIAN_POINT('',(29.0000436,20.0338436,0.E+000)); +#5022 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5023 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5024 = PCURVE('',#4971,#5025); +#5025 = DEFINITIONAL_REPRESENTATION('',(#5026),#5030); +#5026 = LINE('',#5027,#5028); +#5027 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5028 = VECTOR('',#5029,1.); +#5029 = DIRECTION('',(-1.,0.E+000)); +#5030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5031 = PCURVE('',#445,#5032); +#5032 = DEFINITIONAL_REPRESENTATION('',(#5033),#5041); +#5033 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5034,#5035,#5036,#5037, +#5038,#5039,#5040),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5034 = CARTESIAN_POINT('',(-29.47252678,17.23982582)); +#5035 = CARTESIAN_POINT('',(-29.47252678,18.119707630245)); +#5036 = CARTESIAN_POINT('',(-28.71052678,17.679766725122)); +#5037 = CARTESIAN_POINT('',(-27.94852678,17.23982582)); +#5038 = CARTESIAN_POINT('',(-28.71052678,16.799884914878)); +#5039 = CARTESIAN_POINT('',(-29.47252678,16.359944009755)); +#5040 = CARTESIAN_POINT('',(-29.47252678,17.23982582)); +#5041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5042 = ADVANCED_FACE('',(#5043),#5057,.F.); +#5043 = FACE_BOUND('',#5044,.T.); +#5044 = EDGE_LOOP('',(#5045,#5075,#5101,#5102)); +#5045 = ORIENTED_EDGE('',*,*,#5046,.T.); +#5046 = EDGE_CURVE('',#5047,#5049,#5051,.T.); +#5047 = VERTEX_POINT('',#5048); +#5048 = CARTESIAN_POINT('',(4.29399954,33.2940152,0.E+000)); +#5049 = VERTEX_POINT('',#5050); +#5050 = CARTESIAN_POINT('',(4.29399954,33.2940152,1.7018)); +#5051 = SEAM_CURVE('',#5052,(#5056,#5068),.PCURVE_S1.); +#5052 = LINE('',#5053,#5054); +#5053 = CARTESIAN_POINT('',(4.29399954,33.2940152,0.E+000)); +#5054 = VECTOR('',#5055,1.); +#5055 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5056 = PCURVE('',#5057,#5062); +#5057 = CYLINDRICAL_SURFACE('',#5058,1.49999954); +#5058 = AXIS2_PLACEMENT_3D('',#5059,#5060,#5061); +#5059 = CARTESIAN_POINT('',(2.794,33.2940152,0.E+000)); +#5060 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5061 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5062 = DEFINITIONAL_REPRESENTATION('',(#5063),#5067); +#5063 = LINE('',#5064,#5065); +#5064 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5065 = VECTOR('',#5066,1.); +#5066 = DIRECTION('',(0.E+000,-1.)); +#5067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5068 = PCURVE('',#5057,#5069); +#5069 = DEFINITIONAL_REPRESENTATION('',(#5070),#5074); +#5070 = LINE('',#5071,#5072); +#5071 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5072 = VECTOR('',#5073,1.); +#5073 = DIRECTION('',(0.E+000,-1.)); +#5074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5075 = ORIENTED_EDGE('',*,*,#5076,.T.); +#5076 = EDGE_CURVE('',#5049,#5049,#5077,.T.); +#5077 = SURFACE_CURVE('',#5078,(#5083,#5090),.PCURVE_S1.); +#5078 = CIRCLE('',#5079,1.49999954); +#5079 = AXIS2_PLACEMENT_3D('',#5080,#5081,#5082); +#5080 = CARTESIAN_POINT('',(2.794,33.2940152,1.7018)); +#5081 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5082 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5083 = PCURVE('',#5057,#5084); +#5084 = DEFINITIONAL_REPRESENTATION('',(#5085),#5089); #5085 = LINE('',#5086,#5087); -#5086 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); +#5086 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #5087 = VECTOR('',#5088,1.); -#5088 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5089 = PCURVE('',#5090,#5095); -#5090 = PLANE('',#5091); -#5091 = AXIS2_PLACEMENT_3D('',#5092,#5093,#5094); -#5092 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); -#5093 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5094 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5095 = DEFINITIONAL_REPRESENTATION('',(#5096),#5100); -#5096 = LINE('',#5097,#5098); -#5097 = CARTESIAN_POINT('',(4.E-002,5.E-003)); -#5098 = VECTOR('',#5099,1.); -#5099 = DIRECTION('',(-1.,0.E+000)); +#5088 = DIRECTION('',(-1.,0.E+000)); +#5089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5090 = PCURVE('',#391,#5091); +#5091 = DEFINITIONAL_REPRESENTATION('',(#5092),#5100); +#5092 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5093,#5094,#5095,#5096, +#5097,#5098,#5099),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5093 = CARTESIAN_POINT('',(-4.25848272,30.49999742)); +#5094 = CARTESIAN_POINT('',(-4.25848272,33.09807283461)); +#5095 = CARTESIAN_POINT('',(-2.00848341,31.799035127305)); +#5096 = CARTESIAN_POINT('',(0.2415159,30.49999742)); +#5097 = CARTESIAN_POINT('',(-2.00848341,29.200959712695)); +#5098 = CARTESIAN_POINT('',(-4.25848272,27.90192200539)); +#5099 = CARTESIAN_POINT('',(-4.25848272,30.49999742)); #5100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5101 = PCURVE('',#5102,#5107); -#5102 = PLANE('',#5103); -#5103 = AXIS2_PLACEMENT_3D('',#5104,#5105,#5106); -#5104 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); -#5105 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#5106 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5107 = DEFINITIONAL_REPRESENTATION('',(#5108),#5112); -#5108 = LINE('',#5109,#5110); -#5109 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5110 = VECTOR('',#5111,1.); -#5111 = DIRECTION('',(-1.,0.E+000)); -#5112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5113 = ORIENTED_EDGE('',*,*,#5114,.F.); -#5114 = EDGE_CURVE('',#5115,#5082,#5117,.T.); -#5115 = VERTEX_POINT('',#5116); -#5116 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); -#5117 = SURFACE_CURVE('',#5118,(#5122,#5129),.PCURVE_S1.); -#5118 = LINE('',#5119,#5120); -#5119 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); -#5120 = VECTOR('',#5121,1.); -#5121 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5122 = PCURVE('',#5090,#5123); -#5123 = DEFINITIONAL_REPRESENTATION('',(#5124),#5128); -#5124 = LINE('',#5125,#5126); -#5125 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5126 = VECTOR('',#5127,1.); -#5127 = DIRECTION('',(0.E+000,1.)); -#5128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5129 = PCURVE('',#5130,#5135); -#5130 = PLANE('',#5131); -#5131 = AXIS2_PLACEMENT_3D('',#5132,#5133,#5134); -#5132 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); -#5133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5134 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5135 = DEFINITIONAL_REPRESENTATION('',(#5136),#5140); -#5136 = LINE('',#5137,#5138); -#5137 = CARTESIAN_POINT('',(0.2,0.E+000)); -#5138 = VECTOR('',#5139,1.); -#5139 = DIRECTION('',(0.E+000,1.)); -#5140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5141 = ORIENTED_EDGE('',*,*,#5142,.T.); -#5142 = EDGE_CURVE('',#5115,#5143,#5145,.T.); -#5143 = VERTEX_POINT('',#5144); -#5144 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#5145 = SURFACE_CURVE('',#5146,(#5150,#5157),.PCURVE_S1.); -#5146 = LINE('',#5147,#5148); -#5147 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); -#5148 = VECTOR('',#5149,1.); -#5149 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5150 = PCURVE('',#5090,#5151); -#5151 = DEFINITIONAL_REPRESENTATION('',(#5152),#5156); -#5152 = LINE('',#5153,#5154); -#5153 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5154 = VECTOR('',#5155,1.); -#5155 = DIRECTION('',(1.,0.E+000)); -#5156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5157 = PCURVE('',#5158,#5163); -#5158 = PLANE('',#5159); -#5159 = AXIS2_PLACEMENT_3D('',#5160,#5161,#5162); -#5160 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); -#5161 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5162 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5163 = DEFINITIONAL_REPRESENTATION('',(#5164),#5168); -#5164 = LINE('',#5165,#5166); -#5165 = CARTESIAN_POINT('',(0.E+000,0.2)); -#5166 = VECTOR('',#5167,1.); -#5167 = DIRECTION('',(-1.,0.E+000)); -#5168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5169 = ORIENTED_EDGE('',*,*,#5170,.T.); -#5170 = EDGE_CURVE('',#5143,#5080,#5171,.T.); -#5171 = SURFACE_CURVE('',#5172,(#5176,#5183),.PCURVE_S1.); -#5172 = LINE('',#5173,#5174); -#5173 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#5174 = VECTOR('',#5175,1.); -#5175 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5176 = PCURVE('',#5090,#5177); -#5177 = DEFINITIONAL_REPRESENTATION('',(#5178),#5182); -#5178 = LINE('',#5179,#5180); -#5179 = CARTESIAN_POINT('',(4.E-002,0.E+000)); -#5180 = VECTOR('',#5181,1.); -#5181 = DIRECTION('',(0.E+000,1.)); -#5182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5183 = PCURVE('',#5184,#5189); -#5184 = PLANE('',#5185); -#5185 = AXIS2_PLACEMENT_3D('',#5186,#5187,#5188); -#5186 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#5187 = DIRECTION('',(-1.694065894509E-016,0.E+000,-1.)); -#5188 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); -#5189 = DEFINITIONAL_REPRESENTATION('',(#5190),#5194); -#5190 = LINE('',#5191,#5192); -#5191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5192 = VECTOR('',#5193,1.); -#5193 = DIRECTION('',(0.E+000,1.)); -#5194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5195 = ADVANCED_FACE('',(#5196),#5210,.T.); -#5196 = FACE_BOUND('',#5197,.T.); -#5197 = EDGE_LOOP('',(#5198,#5228,#5251,#5279)); -#5198 = ORIENTED_EDGE('',*,*,#5199,.F.); -#5199 = EDGE_CURVE('',#5200,#5202,#5204,.T.); -#5200 = VERTEX_POINT('',#5201); -#5201 = CARTESIAN_POINT('',(0.3,-0.245,0.24)); -#5202 = VERTEX_POINT('',#5203); -#5203 = CARTESIAN_POINT('',(0.3,-0.245,0.28)); -#5204 = SURFACE_CURVE('',#5205,(#5209,#5221),.PCURVE_S1.); -#5205 = LINE('',#5206,#5207); -#5206 = CARTESIAN_POINT('',(0.3,-0.245,0.24)); -#5207 = VECTOR('',#5208,1.); -#5208 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5209 = PCURVE('',#5210,#5215); -#5210 = PLANE('',#5211); -#5211 = AXIS2_PLACEMENT_3D('',#5212,#5213,#5214); -#5212 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#5213 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5214 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5215 = DEFINITIONAL_REPRESENTATION('',(#5216),#5220); -#5216 = LINE('',#5217,#5218); -#5217 = CARTESIAN_POINT('',(-4.E-002,5.E-003)); -#5218 = VECTOR('',#5219,1.); -#5219 = DIRECTION('',(1.,0.E+000)); -#5220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5221 = PCURVE('',#5102,#5222); -#5222 = DEFINITIONAL_REPRESENTATION('',(#5223),#5227); -#5223 = LINE('',#5224,#5225); -#5224 = CARTESIAN_POINT('',(0.E+000,0.6)); -#5225 = VECTOR('',#5226,1.); -#5226 = DIRECTION('',(-1.,0.E+000)); -#5227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5228 = ORIENTED_EDGE('',*,*,#5229,.F.); -#5229 = EDGE_CURVE('',#5230,#5200,#5232,.T.); -#5230 = VERTEX_POINT('',#5231); -#5231 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); -#5232 = SURFACE_CURVE('',#5233,(#5237,#5244),.PCURVE_S1.); -#5233 = LINE('',#5234,#5235); -#5234 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); -#5235 = VECTOR('',#5236,1.); -#5236 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5237 = PCURVE('',#5210,#5238); -#5238 = DEFINITIONAL_REPRESENTATION('',(#5239),#5243); -#5239 = LINE('',#5240,#5241); -#5240 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#5241 = VECTOR('',#5242,1.); -#5242 = DIRECTION('',(0.E+000,1.)); -#5243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5244 = PCURVE('',#5184,#5245); -#5245 = DEFINITIONAL_REPRESENTATION('',(#5246),#5250); -#5246 = LINE('',#5247,#5248); -#5247 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#5248 = VECTOR('',#5249,1.); -#5249 = DIRECTION('',(0.E+000,1.)); -#5250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5251 = ORIENTED_EDGE('',*,*,#5252,.T.); -#5252 = EDGE_CURVE('',#5230,#5253,#5255,.T.); -#5253 = VERTEX_POINT('',#5254); -#5254 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#5255 = SURFACE_CURVE('',#5256,(#5260,#5267),.PCURVE_S1.); -#5256 = LINE('',#5257,#5258); -#5257 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#5258 = VECTOR('',#5259,1.); -#5259 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5260 = PCURVE('',#5210,#5261); -#5261 = DEFINITIONAL_REPRESENTATION('',(#5262),#5266); -#5262 = LINE('',#5263,#5264); -#5263 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5264 = VECTOR('',#5265,1.); -#5265 = DIRECTION('',(1.,0.E+000)); -#5266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5267 = PCURVE('',#5268,#5273); -#5268 = PLANE('',#5269); -#5269 = AXIS2_PLACEMENT_3D('',#5270,#5271,#5272); -#5270 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); -#5271 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#5272 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5273 = DEFINITIONAL_REPRESENTATION('',(#5274),#5278); -#5274 = LINE('',#5275,#5276); -#5275 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#5276 = VECTOR('',#5277,1.); -#5277 = DIRECTION('',(-1.,0.E+000)); -#5278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5279 = ORIENTED_EDGE('',*,*,#5280,.T.); -#5280 = EDGE_CURVE('',#5253,#5202,#5281,.T.); -#5281 = SURFACE_CURVE('',#5282,(#5286,#5293),.PCURVE_S1.); -#5282 = LINE('',#5283,#5284); -#5283 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#5284 = VECTOR('',#5285,1.); -#5285 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5286 = PCURVE('',#5210,#5287); -#5287 = DEFINITIONAL_REPRESENTATION('',(#5288),#5292); -#5288 = LINE('',#5289,#5290); -#5289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5290 = VECTOR('',#5291,1.); -#5291 = DIRECTION('',(0.E+000,1.)); -#5292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5293 = PCURVE('',#5294,#5299); -#5294 = PLANE('',#5295); -#5295 = AXIS2_PLACEMENT_3D('',#5296,#5297,#5298); -#5296 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); -#5297 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5298 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5299 = DEFINITIONAL_REPRESENTATION('',(#5300),#5304); -#5300 = LINE('',#5301,#5302); -#5301 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#5302 = VECTOR('',#5303,1.); -#5303 = DIRECTION('',(0.E+000,1.)); -#5304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5305 = ADVANCED_FACE('',(#5306),#5320,.F.); -#5306 = FACE_BOUND('',#5307,.T.); -#5307 = EDGE_LOOP('',(#5308,#5343,#5371,#5399,#5427,#5455)); -#5308 = ORIENTED_EDGE('',*,*,#5309,.T.); -#5309 = EDGE_CURVE('',#5310,#5312,#5314,.T.); -#5310 = VERTEX_POINT('',#5311); -#5311 = CARTESIAN_POINT('',(0.46,0.24,4.E-002)); -#5312 = VERTEX_POINT('',#5313); -#5313 = CARTESIAN_POINT('',(0.3,0.24,4.E-002)); -#5314 = SURFACE_CURVE('',#5315,(#5319,#5331),.PCURVE_S1.); -#5315 = LINE('',#5316,#5317); -#5316 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); -#5317 = VECTOR('',#5318,1.); -#5318 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5319 = PCURVE('',#5320,#5325); -#5320 = PLANE('',#5321); -#5321 = AXIS2_PLACEMENT_3D('',#5322,#5323,#5324); -#5322 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); -#5323 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#5324 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5325 = DEFINITIONAL_REPRESENTATION('',(#5326),#5330); -#5326 = LINE('',#5327,#5328); -#5327 = CARTESIAN_POINT('',(0.2,0.E+000)); -#5328 = VECTOR('',#5329,1.); -#5329 = DIRECTION('',(0.E+000,-1.)); -#5330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5331 = PCURVE('',#5332,#5337); -#5332 = PLANE('',#5333); -#5333 = AXIS2_PLACEMENT_3D('',#5334,#5335,#5336); -#5334 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#5335 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5336 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5337 = DEFINITIONAL_REPRESENTATION('',(#5338),#5342); -#5338 = LINE('',#5339,#5340); -#5339 = CARTESIAN_POINT('',(-0.92,0.49)); -#5340 = VECTOR('',#5341,1.); -#5341 = DIRECTION('',(-1.,0.E+000)); -#5342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5343 = ORIENTED_EDGE('',*,*,#5344,.T.); -#5344 = EDGE_CURVE('',#5312,#5345,#5347,.T.); -#5345 = VERTEX_POINT('',#5346); -#5346 = CARTESIAN_POINT('',(-0.3,0.24,4.E-002)); -#5347 = SURFACE_CURVE('',#5348,(#5352,#5359),.PCURVE_S1.); -#5348 = LINE('',#5349,#5350); -#5349 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); -#5350 = VECTOR('',#5351,1.); -#5351 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5352 = PCURVE('',#5320,#5353); -#5353 = DEFINITIONAL_REPRESENTATION('',(#5354),#5358); -#5354 = LINE('',#5355,#5356); -#5355 = CARTESIAN_POINT('',(0.2,0.E+000)); -#5356 = VECTOR('',#5357,1.); -#5357 = DIRECTION('',(0.E+000,-1.)); +#5101 = ORIENTED_EDGE('',*,*,#5046,.F.); +#5102 = ORIENTED_EDGE('',*,*,#5103,.F.); +#5103 = EDGE_CURVE('',#5047,#5047,#5104,.T.); +#5104 = SURFACE_CURVE('',#5105,(#5110,#5117),.PCURVE_S1.); +#5105 = CIRCLE('',#5106,1.49999954); +#5106 = AXIS2_PLACEMENT_3D('',#5107,#5108,#5109); +#5107 = CARTESIAN_POINT('',(2.794,33.2940152,0.E+000)); +#5108 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5109 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5110 = PCURVE('',#5057,#5111); +#5111 = DEFINITIONAL_REPRESENTATION('',(#5112),#5116); +#5112 = LINE('',#5113,#5114); +#5113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5114 = VECTOR('',#5115,1.); +#5115 = DIRECTION('',(-1.,0.E+000)); +#5116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5117 = PCURVE('',#445,#5118); +#5118 = DEFINITIONAL_REPRESENTATION('',(#5119),#5127); +#5119 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5120,#5121,#5122,#5123, +#5124,#5125,#5126),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5120 = CARTESIAN_POINT('',(-4.25848272,30.49999742)); +#5121 = CARTESIAN_POINT('',(-4.25848272,33.09807283461)); +#5122 = CARTESIAN_POINT('',(-2.00848341,31.799035127305)); +#5123 = CARTESIAN_POINT('',(0.2415159,30.49999742)); +#5124 = CARTESIAN_POINT('',(-2.00848341,29.200959712695)); +#5125 = CARTESIAN_POINT('',(-4.25848272,27.90192200539)); +#5126 = CARTESIAN_POINT('',(-4.25848272,30.49999742)); +#5127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5128 = ADVANCED_FACE('',(#5129),#5143,.F.); +#5129 = FACE_BOUND('',#5130,.T.); +#5130 = EDGE_LOOP('',(#5131,#5161,#5187,#5188)); +#5131 = ORIENTED_EDGE('',*,*,#5132,.T.); +#5132 = EDGE_CURVE('',#5133,#5135,#5137,.T.); +#5133 = VERTEX_POINT('',#5134); +#5134 = CARTESIAN_POINT('',(18.034,34.671,0.E+000)); +#5135 = VERTEX_POINT('',#5136); +#5136 = CARTESIAN_POINT('',(18.034,34.671,1.7018)); +#5137 = SEAM_CURVE('',#5138,(#5142,#5154),.PCURVE_S1.); +#5138 = LINE('',#5139,#5140); +#5139 = CARTESIAN_POINT('',(18.034,34.671,0.E+000)); +#5140 = VECTOR('',#5141,1.); +#5141 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5142 = PCURVE('',#5143,#5148); +#5143 = CYLINDRICAL_SURFACE('',#5144,0.889); +#5144 = AXIS2_PLACEMENT_3D('',#5145,#5146,#5147); +#5145 = CARTESIAN_POINT('',(17.145,34.671,0.E+000)); +#5146 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5147 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5148 = DEFINITIONAL_REPRESENTATION('',(#5149),#5153); +#5149 = LINE('',#5150,#5151); +#5150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5151 = VECTOR('',#5152,1.); +#5152 = DIRECTION('',(0.E+000,-1.)); +#5153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5154 = PCURVE('',#5143,#5155); +#5155 = DEFINITIONAL_REPRESENTATION('',(#5156),#5160); +#5156 = LINE('',#5157,#5158); +#5157 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5158 = VECTOR('',#5159,1.); +#5159 = DIRECTION('',(0.E+000,-1.)); +#5160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5161 = ORIENTED_EDGE('',*,*,#5162,.T.); +#5162 = EDGE_CURVE('',#5135,#5135,#5163,.T.); +#5163 = SURFACE_CURVE('',#5164,(#5169,#5176),.PCURVE_S1.); +#5164 = CIRCLE('',#5165,0.889); +#5165 = AXIS2_PLACEMENT_3D('',#5166,#5167,#5168); +#5166 = CARTESIAN_POINT('',(17.145,34.671,1.7018)); +#5167 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5168 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5169 = PCURVE('',#5143,#5170); +#5170 = DEFINITIONAL_REPRESENTATION('',(#5171),#5175); +#5171 = LINE('',#5172,#5173); +#5172 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5173 = VECTOR('',#5174,1.); +#5174 = DIRECTION('',(-1.,0.E+000)); +#5175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5176 = PCURVE('',#391,#5177); +#5177 = DEFINITIONAL_REPRESENTATION('',(#5178),#5186); +#5178 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5179,#5180,#5181,#5182, +#5183,#5184,#5185),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5179 = CARTESIAN_POINT('',(-17.99848318,31.87698222)); +#5180 = CARTESIAN_POINT('',(-17.99848318,33.416775387929)); +#5181 = CARTESIAN_POINT('',(-16.66498318,32.646878803964)); +#5182 = CARTESIAN_POINT('',(-15.33148318,31.87698222)); +#5183 = CARTESIAN_POINT('',(-16.66498318,31.107085636036)); +#5184 = CARTESIAN_POINT('',(-17.99848318,30.337189052071)); +#5185 = CARTESIAN_POINT('',(-17.99848318,31.87698222)); +#5186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5187 = ORIENTED_EDGE('',*,*,#5132,.F.); +#5188 = ORIENTED_EDGE('',*,*,#5189,.F.); +#5189 = EDGE_CURVE('',#5133,#5133,#5190,.T.); +#5190 = SURFACE_CURVE('',#5191,(#5196,#5203),.PCURVE_S1.); +#5191 = CIRCLE('',#5192,0.889); +#5192 = AXIS2_PLACEMENT_3D('',#5193,#5194,#5195); +#5193 = CARTESIAN_POINT('',(17.145,34.671,0.E+000)); +#5194 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5195 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5196 = PCURVE('',#5143,#5197); +#5197 = DEFINITIONAL_REPRESENTATION('',(#5198),#5202); +#5198 = LINE('',#5199,#5200); +#5199 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5200 = VECTOR('',#5201,1.); +#5201 = DIRECTION('',(-1.,0.E+000)); +#5202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5203 = PCURVE('',#445,#5204); +#5204 = DEFINITIONAL_REPRESENTATION('',(#5205),#5213); +#5205 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5206,#5207,#5208,#5209, +#5210,#5211,#5212),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5206 = CARTESIAN_POINT('',(-17.99848318,31.87698222)); +#5207 = CARTESIAN_POINT('',(-17.99848318,33.416775387929)); +#5208 = CARTESIAN_POINT('',(-16.66498318,32.646878803964)); +#5209 = CARTESIAN_POINT('',(-15.33148318,31.87698222)); +#5210 = CARTESIAN_POINT('',(-16.66498318,31.107085636036)); +#5211 = CARTESIAN_POINT('',(-17.99848318,30.337189052071)); +#5212 = CARTESIAN_POINT('',(-17.99848318,31.87698222)); +#5213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5214 = ADVANCED_FACE('',(#5215),#5229,.F.); +#5215 = FACE_BOUND('',#5216,.T.); +#5216 = EDGE_LOOP('',(#5217,#5247,#5273,#5274)); +#5217 = ORIENTED_EDGE('',*,*,#5218,.T.); +#5218 = EDGE_CURVE('',#5219,#5221,#5223,.T.); +#5219 = VERTEX_POINT('',#5220); +#5220 = CARTESIAN_POINT('',(22.225,34.544,0.E+000)); +#5221 = VERTEX_POINT('',#5222); +#5222 = CARTESIAN_POINT('',(22.225,34.544,1.7018)); +#5223 = SEAM_CURVE('',#5224,(#5228,#5240),.PCURVE_S1.); +#5224 = LINE('',#5225,#5226); +#5225 = CARTESIAN_POINT('',(22.225,34.544,0.E+000)); +#5226 = VECTOR('',#5227,1.); +#5227 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5228 = PCURVE('',#5229,#5234); +#5229 = CYLINDRICAL_SURFACE('',#5230,0.508); +#5230 = AXIS2_PLACEMENT_3D('',#5231,#5232,#5233); +#5231 = CARTESIAN_POINT('',(21.717,34.544,0.E+000)); +#5232 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5233 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5234 = DEFINITIONAL_REPRESENTATION('',(#5235),#5239); +#5235 = LINE('',#5236,#5237); +#5236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5237 = VECTOR('',#5238,1.); +#5238 = DIRECTION('',(0.E+000,-1.)); +#5239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5240 = PCURVE('',#5229,#5241); +#5241 = DEFINITIONAL_REPRESENTATION('',(#5242),#5246); +#5242 = LINE('',#5243,#5244); +#5243 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5244 = VECTOR('',#5245,1.); +#5245 = DIRECTION('',(0.E+000,-1.)); +#5246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5247 = ORIENTED_EDGE('',*,*,#5248,.T.); +#5248 = EDGE_CURVE('',#5221,#5221,#5249,.T.); +#5249 = SURFACE_CURVE('',#5250,(#5255,#5262),.PCURVE_S1.); +#5250 = CIRCLE('',#5251,0.508); +#5251 = AXIS2_PLACEMENT_3D('',#5252,#5253,#5254); +#5252 = CARTESIAN_POINT('',(21.717,34.544,1.7018)); +#5253 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5254 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5255 = PCURVE('',#5229,#5256); +#5256 = DEFINITIONAL_REPRESENTATION('',(#5257),#5261); +#5257 = LINE('',#5258,#5259); +#5258 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5259 = VECTOR('',#5260,1.); +#5260 = DIRECTION('',(-1.,0.E+000)); +#5261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5262 = PCURVE('',#391,#5263); +#5263 = DEFINITIONAL_REPRESENTATION('',(#5264),#5272); +#5264 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5265,#5266,#5267,#5268, +#5269,#5270,#5271),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5265 = CARTESIAN_POINT('',(-22.18948318,31.74998222)); +#5266 = CARTESIAN_POINT('',(-22.18948318,32.629864030245)); +#5267 = CARTESIAN_POINT('',(-21.42748318,32.189923125122)); +#5268 = CARTESIAN_POINT('',(-20.66548318,31.74998222)); +#5269 = CARTESIAN_POINT('',(-21.42748318,31.310041314878)); +#5270 = CARTESIAN_POINT('',(-22.18948318,30.870100409755)); +#5271 = CARTESIAN_POINT('',(-22.18948318,31.74998222)); +#5272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5273 = ORIENTED_EDGE('',*,*,#5218,.F.); +#5274 = ORIENTED_EDGE('',*,*,#5275,.F.); +#5275 = EDGE_CURVE('',#5219,#5219,#5276,.T.); +#5276 = SURFACE_CURVE('',#5277,(#5282,#5289),.PCURVE_S1.); +#5277 = CIRCLE('',#5278,0.508); +#5278 = AXIS2_PLACEMENT_3D('',#5279,#5280,#5281); +#5279 = CARTESIAN_POINT('',(21.717,34.544,0.E+000)); +#5280 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5281 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5282 = PCURVE('',#5229,#5283); +#5283 = DEFINITIONAL_REPRESENTATION('',(#5284),#5288); +#5284 = LINE('',#5285,#5286); +#5285 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5286 = VECTOR('',#5287,1.); +#5287 = DIRECTION('',(-1.,0.E+000)); +#5288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5289 = PCURVE('',#445,#5290); +#5290 = DEFINITIONAL_REPRESENTATION('',(#5291),#5299); +#5291 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5292,#5293,#5294,#5295, +#5296,#5297,#5298),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5292 = CARTESIAN_POINT('',(-22.18948318,31.74998222)); +#5293 = CARTESIAN_POINT('',(-22.18948318,32.629864030245)); +#5294 = CARTESIAN_POINT('',(-21.42748318,32.189923125122)); +#5295 = CARTESIAN_POINT('',(-20.66548318,31.74998222)); +#5296 = CARTESIAN_POINT('',(-21.42748318,31.310041314878)); +#5297 = CARTESIAN_POINT('',(-22.18948318,30.870100409755)); +#5298 = CARTESIAN_POINT('',(-22.18948318,31.74998222)); +#5299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5300 = ADVANCED_FACE('',(#5301),#5315,.F.); +#5301 = FACE_BOUND('',#5302,.T.); +#5302 = EDGE_LOOP('',(#5303,#5333,#5359,#5360)); +#5303 = ORIENTED_EDGE('',*,*,#5304,.T.); +#5304 = EDGE_CURVE('',#5305,#5307,#5309,.T.); +#5305 = VERTEX_POINT('',#5306); +#5306 = CARTESIAN_POINT('',(29.5080436,27.6538436,0.E+000)); +#5307 = VERTEX_POINT('',#5308); +#5308 = CARTESIAN_POINT('',(29.5080436,27.6538436,1.7018)); +#5309 = SEAM_CURVE('',#5310,(#5314,#5326),.PCURVE_S1.); +#5310 = LINE('',#5311,#5312); +#5311 = CARTESIAN_POINT('',(29.5080436,27.6538436,0.E+000)); +#5312 = VECTOR('',#5313,1.); +#5313 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5314 = PCURVE('',#5315,#5320); +#5315 = CYLINDRICAL_SURFACE('',#5316,0.508); +#5316 = AXIS2_PLACEMENT_3D('',#5317,#5318,#5319); +#5317 = CARTESIAN_POINT('',(29.0000436,27.6538436,0.E+000)); +#5318 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5319 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5320 = DEFINITIONAL_REPRESENTATION('',(#5321),#5325); +#5321 = LINE('',#5322,#5323); +#5322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5323 = VECTOR('',#5324,1.); +#5324 = DIRECTION('',(0.E+000,-1.)); +#5325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5326 = PCURVE('',#5315,#5327); +#5327 = DEFINITIONAL_REPRESENTATION('',(#5328),#5332); +#5328 = LINE('',#5329,#5330); +#5329 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5330 = VECTOR('',#5331,1.); +#5331 = DIRECTION('',(0.E+000,-1.)); +#5332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5333 = ORIENTED_EDGE('',*,*,#5334,.T.); +#5334 = EDGE_CURVE('',#5307,#5307,#5335,.T.); +#5335 = SURFACE_CURVE('',#5336,(#5341,#5348),.PCURVE_S1.); +#5336 = CIRCLE('',#5337,0.508); +#5337 = AXIS2_PLACEMENT_3D('',#5338,#5339,#5340); +#5338 = CARTESIAN_POINT('',(29.0000436,27.6538436,1.7018)); +#5339 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5340 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5341 = PCURVE('',#5315,#5342); +#5342 = DEFINITIONAL_REPRESENTATION('',(#5343),#5347); +#5343 = LINE('',#5344,#5345); +#5344 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5345 = VECTOR('',#5346,1.); +#5346 = DIRECTION('',(-1.,0.E+000)); +#5347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5348 = PCURVE('',#391,#5349); +#5349 = DEFINITIONAL_REPRESENTATION('',(#5350),#5358); +#5350 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5351,#5352,#5353,#5354, +#5355,#5356,#5357),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5351 = CARTESIAN_POINT('',(-29.47252678,24.85982582)); +#5352 = CARTESIAN_POINT('',(-29.47252678,25.739707630245)); +#5353 = CARTESIAN_POINT('',(-28.71052678,25.299766725122)); +#5354 = CARTESIAN_POINT('',(-27.94852678,24.85982582)); +#5355 = CARTESIAN_POINT('',(-28.71052678,24.419884914878)); +#5356 = CARTESIAN_POINT('',(-29.47252678,23.979944009755)); +#5357 = CARTESIAN_POINT('',(-29.47252678,24.85982582)); #5358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5359 = PCURVE('',#5360,#5365); -#5360 = PLANE('',#5361); -#5361 = AXIS2_PLACEMENT_3D('',#5362,#5363,#5364); -#5362 = CARTESIAN_POINT('',(0.46,-0.24,4.E-002)); -#5363 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5364 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5365 = DEFINITIONAL_REPRESENTATION('',(#5366),#5370); -#5366 = LINE('',#5367,#5368); -#5367 = CARTESIAN_POINT('',(-0.92,0.48)); -#5368 = VECTOR('',#5369,1.); -#5369 = DIRECTION('',(-1.,0.E+000)); -#5370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5371 = ORIENTED_EDGE('',*,*,#5372,.T.); -#5372 = EDGE_CURVE('',#5345,#5373,#5375,.T.); -#5373 = VERTEX_POINT('',#5374); -#5374 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); -#5375 = SURFACE_CURVE('',#5376,(#5380,#5387),.PCURVE_S1.); -#5376 = LINE('',#5377,#5378); -#5377 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); -#5378 = VECTOR('',#5379,1.); -#5379 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5380 = PCURVE('',#5320,#5381); -#5381 = DEFINITIONAL_REPRESENTATION('',(#5382),#5386); -#5382 = LINE('',#5383,#5384); -#5383 = CARTESIAN_POINT('',(0.2,0.E+000)); -#5384 = VECTOR('',#5385,1.); -#5385 = DIRECTION('',(0.E+000,-1.)); -#5386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5387 = PCURVE('',#5388,#5393); -#5388 = PLANE('',#5389); -#5389 = AXIS2_PLACEMENT_3D('',#5390,#5391,#5392); -#5390 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5391 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5392 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5393 = DEFINITIONAL_REPRESENTATION('',(#5394),#5398); -#5394 = LINE('',#5395,#5396); -#5395 = CARTESIAN_POINT('',(0.E+000,0.49)); -#5396 = VECTOR('',#5397,1.); -#5397 = DIRECTION('',(-1.,0.E+000)); -#5398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5399 = ORIENTED_EDGE('',*,*,#5400,.F.); -#5400 = EDGE_CURVE('',#5401,#5373,#5403,.T.); -#5401 = VERTEX_POINT('',#5402); -#5402 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); -#5403 = SURFACE_CURVE('',#5404,(#5408,#5415),.PCURVE_S1.); -#5404 = LINE('',#5405,#5406); -#5405 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); -#5406 = VECTOR('',#5407,1.); -#5407 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5408 = PCURVE('',#5320,#5409); -#5409 = DEFINITIONAL_REPRESENTATION('',(#5410),#5414); -#5410 = LINE('',#5411,#5412); -#5411 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5412 = VECTOR('',#5413,1.); -#5413 = DIRECTION('',(1.,0.E+000)); -#5414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5415 = PCURVE('',#5416,#5421); -#5416 = PLANE('',#5417); -#5417 = AXIS2_PLACEMENT_3D('',#5418,#5419,#5420); -#5418 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5419 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5420 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5421 = DEFINITIONAL_REPRESENTATION('',(#5422),#5426); -#5422 = LINE('',#5423,#5424); -#5423 = CARTESIAN_POINT('',(-0.2,0.49)); -#5424 = VECTOR('',#5425,1.); -#5425 = DIRECTION('',(1.,0.E+000)); -#5426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5427 = ORIENTED_EDGE('',*,*,#5428,.F.); -#5428 = EDGE_CURVE('',#5429,#5401,#5431,.T.); -#5429 = VERTEX_POINT('',#5430); -#5430 = CARTESIAN_POINT('',(0.46,0.24,0.24)); -#5431 = SURFACE_CURVE('',#5432,(#5436,#5443),.PCURVE_S1.); -#5432 = LINE('',#5433,#5434); -#5433 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); -#5434 = VECTOR('',#5435,1.); -#5435 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5436 = PCURVE('',#5320,#5437); -#5437 = DEFINITIONAL_REPRESENTATION('',(#5438),#5442); -#5438 = LINE('',#5439,#5440); -#5439 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5440 = VECTOR('',#5441,1.); -#5441 = DIRECTION('',(0.E+000,-1.)); -#5442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5443 = PCURVE('',#5444,#5449); -#5444 = PLANE('',#5445); -#5445 = AXIS2_PLACEMENT_3D('',#5446,#5447,#5448); -#5446 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#5447 = DIRECTION('',(-1.694065894509E-016,0.E+000,-1.)); -#5448 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); -#5449 = DEFINITIONAL_REPRESENTATION('',(#5450),#5454); -#5450 = LINE('',#5451,#5452); -#5451 = CARTESIAN_POINT('',(0.16,0.49)); -#5452 = VECTOR('',#5453,1.); -#5453 = DIRECTION('',(1.,0.E+000)); -#5454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5455 = ORIENTED_EDGE('',*,*,#5456,.T.); -#5456 = EDGE_CURVE('',#5429,#5310,#5457,.T.); -#5457 = SURFACE_CURVE('',#5458,(#5462,#5469),.PCURVE_S1.); -#5458 = LINE('',#5459,#5460); -#5459 = CARTESIAN_POINT('',(0.46,0.24,0.24)); -#5460 = VECTOR('',#5461,1.); -#5461 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5462 = PCURVE('',#5320,#5463); -#5463 = DEFINITIONAL_REPRESENTATION('',(#5464),#5468); -#5464 = LINE('',#5465,#5466); -#5465 = CARTESIAN_POINT('',(0.E+000,0.92)); -#5466 = VECTOR('',#5467,1.); -#5467 = DIRECTION('',(1.,0.E+000)); -#5468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5469 = PCURVE('',#5470,#5475); -#5470 = PLANE('',#5471); -#5471 = AXIS2_PLACEMENT_3D('',#5472,#5473,#5474); -#5472 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#5473 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5474 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5475 = DEFINITIONAL_REPRESENTATION('',(#5476),#5480); -#5476 = LINE('',#5477,#5478); -#5477 = CARTESIAN_POINT('',(0.2,0.49)); -#5478 = VECTOR('',#5479,1.); -#5479 = DIRECTION('',(-1.,0.E+000)); -#5480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5481 = ADVANCED_FACE('',(#5482),#5496,.F.); -#5482 = FACE_BOUND('',#5483,.T.); -#5483 = EDGE_LOOP('',(#5484,#5519,#5542,#5570,#5598,#5621)); -#5484 = ORIENTED_EDGE('',*,*,#5485,.T.); -#5485 = EDGE_CURVE('',#5486,#5488,#5490,.T.); -#5486 = VERTEX_POINT('',#5487); -#5487 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); -#5488 = VERTEX_POINT('',#5489); -#5489 = CARTESIAN_POINT('',(-0.3,-0.24,4.E-002)); -#5490 = SURFACE_CURVE('',#5491,(#5495,#5507),.PCURVE_S1.); -#5491 = LINE('',#5492,#5493); -#5492 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); -#5493 = VECTOR('',#5494,1.); -#5494 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5495 = PCURVE('',#5496,#5501); -#5496 = PLANE('',#5497); -#5497 = AXIS2_PLACEMENT_3D('',#5498,#5499,#5500); -#5498 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); -#5499 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5500 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5501 = DEFINITIONAL_REPRESENTATION('',(#5502),#5506); -#5502 = LINE('',#5503,#5504); -#5503 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#5504 = VECTOR('',#5505,1.); -#5505 = DIRECTION('',(0.E+000,1.)); -#5506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5507 = PCURVE('',#5508,#5513); -#5508 = PLANE('',#5509); +#5359 = ORIENTED_EDGE('',*,*,#5304,.F.); +#5360 = ORIENTED_EDGE('',*,*,#5361,.F.); +#5361 = EDGE_CURVE('',#5305,#5305,#5362,.T.); +#5362 = SURFACE_CURVE('',#5363,(#5368,#5375),.PCURVE_S1.); +#5363 = CIRCLE('',#5364,0.508); +#5364 = AXIS2_PLACEMENT_3D('',#5365,#5366,#5367); +#5365 = CARTESIAN_POINT('',(29.0000436,27.6538436,0.E+000)); +#5366 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5367 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5368 = PCURVE('',#5315,#5369); +#5369 = DEFINITIONAL_REPRESENTATION('',(#5370),#5374); +#5370 = LINE('',#5371,#5372); +#5371 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5372 = VECTOR('',#5373,1.); +#5373 = DIRECTION('',(-1.,0.E+000)); +#5374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5375 = PCURVE('',#445,#5376); +#5376 = DEFINITIONAL_REPRESENTATION('',(#5377),#5385); +#5377 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5378,#5379,#5380,#5381, +#5382,#5383,#5384),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5378 = CARTESIAN_POINT('',(-29.47252678,24.85982582)); +#5379 = CARTESIAN_POINT('',(-29.47252678,25.739707630245)); +#5380 = CARTESIAN_POINT('',(-28.71052678,25.299766725122)); +#5381 = CARTESIAN_POINT('',(-27.94852678,24.85982582)); +#5382 = CARTESIAN_POINT('',(-28.71052678,24.419884914878)); +#5383 = CARTESIAN_POINT('',(-29.47252678,23.979944009755)); +#5384 = CARTESIAN_POINT('',(-29.47252678,24.85982582)); +#5385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5386 = ADVANCED_FACE('',(#5387),#5401,.F.); +#5387 = FACE_BOUND('',#5388,.T.); +#5388 = EDGE_LOOP('',(#5389,#5419,#5445,#5446)); +#5389 = ORIENTED_EDGE('',*,*,#5390,.T.); +#5390 = EDGE_CURVE('',#5391,#5393,#5395,.T.); +#5391 = VERTEX_POINT('',#5392); +#5392 = CARTESIAN_POINT('',(29.5080436,25.1138436,0.E+000)); +#5393 = VERTEX_POINT('',#5394); +#5394 = CARTESIAN_POINT('',(29.5080436,25.1138436,1.7018)); +#5395 = SEAM_CURVE('',#5396,(#5400,#5412),.PCURVE_S1.); +#5396 = LINE('',#5397,#5398); +#5397 = CARTESIAN_POINT('',(29.5080436,25.1138436,0.E+000)); +#5398 = VECTOR('',#5399,1.); +#5399 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5400 = PCURVE('',#5401,#5406); +#5401 = CYLINDRICAL_SURFACE('',#5402,0.508); +#5402 = AXIS2_PLACEMENT_3D('',#5403,#5404,#5405); +#5403 = CARTESIAN_POINT('',(29.0000436,25.1138436,0.E+000)); +#5404 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5405 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5406 = DEFINITIONAL_REPRESENTATION('',(#5407),#5411); +#5407 = LINE('',#5408,#5409); +#5408 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5409 = VECTOR('',#5410,1.); +#5410 = DIRECTION('',(0.E+000,-1.)); +#5411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5412 = PCURVE('',#5401,#5413); +#5413 = DEFINITIONAL_REPRESENTATION('',(#5414),#5418); +#5414 = LINE('',#5415,#5416); +#5415 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5416 = VECTOR('',#5417,1.); +#5417 = DIRECTION('',(0.E+000,-1.)); +#5418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5419 = ORIENTED_EDGE('',*,*,#5420,.T.); +#5420 = EDGE_CURVE('',#5393,#5393,#5421,.T.); +#5421 = SURFACE_CURVE('',#5422,(#5427,#5434),.PCURVE_S1.); +#5422 = CIRCLE('',#5423,0.508); +#5423 = AXIS2_PLACEMENT_3D('',#5424,#5425,#5426); +#5424 = CARTESIAN_POINT('',(29.0000436,25.1138436,1.7018)); +#5425 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5426 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5427 = PCURVE('',#5401,#5428); +#5428 = DEFINITIONAL_REPRESENTATION('',(#5429),#5433); +#5429 = LINE('',#5430,#5431); +#5430 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5431 = VECTOR('',#5432,1.); +#5432 = DIRECTION('',(-1.,0.E+000)); +#5433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5434 = PCURVE('',#391,#5435); +#5435 = DEFINITIONAL_REPRESENTATION('',(#5436),#5444); +#5436 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5437,#5438,#5439,#5440, +#5441,#5442,#5443),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5437 = CARTESIAN_POINT('',(-29.47252678,22.31982582)); +#5438 = CARTESIAN_POINT('',(-29.47252678,23.199707630245)); +#5439 = CARTESIAN_POINT('',(-28.71052678,22.759766725122)); +#5440 = CARTESIAN_POINT('',(-27.94852678,22.31982582)); +#5441 = CARTESIAN_POINT('',(-28.71052678,21.879884914878)); +#5442 = CARTESIAN_POINT('',(-29.47252678,21.439944009755)); +#5443 = CARTESIAN_POINT('',(-29.47252678,22.31982582)); +#5444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5445 = ORIENTED_EDGE('',*,*,#5390,.F.); +#5446 = ORIENTED_EDGE('',*,*,#5447,.F.); +#5447 = EDGE_CURVE('',#5391,#5391,#5448,.T.); +#5448 = SURFACE_CURVE('',#5449,(#5454,#5461),.PCURVE_S1.); +#5449 = CIRCLE('',#5450,0.508); +#5450 = AXIS2_PLACEMENT_3D('',#5451,#5452,#5453); +#5451 = CARTESIAN_POINT('',(29.0000436,25.1138436,0.E+000)); +#5452 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5453 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5454 = PCURVE('',#5401,#5455); +#5455 = DEFINITIONAL_REPRESENTATION('',(#5456),#5460); +#5456 = LINE('',#5457,#5458); +#5457 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5458 = VECTOR('',#5459,1.); +#5459 = DIRECTION('',(-1.,0.E+000)); +#5460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5461 = PCURVE('',#445,#5462); +#5462 = DEFINITIONAL_REPRESENTATION('',(#5463),#5471); +#5463 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5464,#5465,#5466,#5467, +#5468,#5469,#5470),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5464 = CARTESIAN_POINT('',(-29.47252678,22.31982582)); +#5465 = CARTESIAN_POINT('',(-29.47252678,23.199707630245)); +#5466 = CARTESIAN_POINT('',(-28.71052678,22.759766725122)); +#5467 = CARTESIAN_POINT('',(-27.94852678,22.31982582)); +#5468 = CARTESIAN_POINT('',(-28.71052678,21.879884914878)); +#5469 = CARTESIAN_POINT('',(-29.47252678,21.439944009755)); +#5470 = CARTESIAN_POINT('',(-29.47252678,22.31982582)); +#5471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5472 = ADVANCED_FACE('',(#5473),#5487,.F.); +#5473 = FACE_BOUND('',#5474,.T.); +#5474 = EDGE_LOOP('',(#5475,#5505,#5531,#5532)); +#5475 = ORIENTED_EDGE('',*,*,#5476,.T.); +#5476 = EDGE_CURVE('',#5477,#5479,#5481,.T.); +#5477 = VERTEX_POINT('',#5478); +#5478 = CARTESIAN_POINT('',(24.765,34.544,0.E+000)); +#5479 = VERTEX_POINT('',#5480); +#5480 = CARTESIAN_POINT('',(24.765,34.544,1.7018)); +#5481 = SEAM_CURVE('',#5482,(#5486,#5498),.PCURVE_S1.); +#5482 = LINE('',#5483,#5484); +#5483 = CARTESIAN_POINT('',(24.765,34.544,0.E+000)); +#5484 = VECTOR('',#5485,1.); +#5485 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5486 = PCURVE('',#5487,#5492); +#5487 = CYLINDRICAL_SURFACE('',#5488,0.508); +#5488 = AXIS2_PLACEMENT_3D('',#5489,#5490,#5491); +#5489 = CARTESIAN_POINT('',(24.257,34.544,0.E+000)); +#5490 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5491 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5492 = DEFINITIONAL_REPRESENTATION('',(#5493),#5497); +#5493 = LINE('',#5494,#5495); +#5494 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5495 = VECTOR('',#5496,1.); +#5496 = DIRECTION('',(0.E+000,-1.)); +#5497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5498 = PCURVE('',#5487,#5499); +#5499 = DEFINITIONAL_REPRESENTATION('',(#5500),#5504); +#5500 = LINE('',#5501,#5502); +#5501 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5502 = VECTOR('',#5503,1.); +#5503 = DIRECTION('',(0.E+000,-1.)); +#5504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5505 = ORIENTED_EDGE('',*,*,#5506,.T.); +#5506 = EDGE_CURVE('',#5479,#5479,#5507,.T.); +#5507 = SURFACE_CURVE('',#5508,(#5513,#5520),.PCURVE_S1.); +#5508 = CIRCLE('',#5509,0.508); #5509 = AXIS2_PLACEMENT_3D('',#5510,#5511,#5512); -#5510 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#5510 = CARTESIAN_POINT('',(24.257,34.544,1.7018)); #5511 = DIRECTION('',(0.E+000,0.E+000,1.)); #5512 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5513 = DEFINITIONAL_REPRESENTATION('',(#5514),#5518); -#5514 = LINE('',#5515,#5516); -#5515 = CARTESIAN_POINT('',(1.110223024625E-016,1.E-002)); -#5516 = VECTOR('',#5517,1.); -#5517 = DIRECTION('',(1.,0.E+000)); -#5518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5519 = ORIENTED_EDGE('',*,*,#5520,.T.); -#5520 = EDGE_CURVE('',#5488,#5521,#5523,.T.); -#5521 = VERTEX_POINT('',#5522); -#5522 = CARTESIAN_POINT('',(0.3,-0.24,4.E-002)); -#5523 = SURFACE_CURVE('',#5524,(#5528,#5535),.PCURVE_S1.); -#5524 = LINE('',#5525,#5526); -#5525 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); -#5526 = VECTOR('',#5527,1.); -#5527 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5528 = PCURVE('',#5496,#5529); -#5529 = DEFINITIONAL_REPRESENTATION('',(#5530),#5534); -#5530 = LINE('',#5531,#5532); -#5531 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#5532 = VECTOR('',#5533,1.); -#5533 = DIRECTION('',(0.E+000,1.)); -#5534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5535 = PCURVE('',#5360,#5536); -#5536 = DEFINITIONAL_REPRESENTATION('',(#5537),#5541); -#5537 = LINE('',#5538,#5539); -#5538 = CARTESIAN_POINT('',(-0.92,0.E+000)); -#5539 = VECTOR('',#5540,1.); -#5540 = DIRECTION('',(1.,0.E+000)); -#5541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5542 = ORIENTED_EDGE('',*,*,#5543,.T.); -#5543 = EDGE_CURVE('',#5521,#5544,#5546,.T.); -#5544 = VERTEX_POINT('',#5545); -#5545 = CARTESIAN_POINT('',(0.46,-0.24,4.E-002)); -#5546 = SURFACE_CURVE('',#5547,(#5551,#5558),.PCURVE_S1.); -#5547 = LINE('',#5548,#5549); -#5548 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); -#5549 = VECTOR('',#5550,1.); -#5550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5551 = PCURVE('',#5496,#5552); -#5552 = DEFINITIONAL_REPRESENTATION('',(#5553),#5557); -#5553 = LINE('',#5554,#5555); -#5554 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#5555 = VECTOR('',#5556,1.); -#5556 = DIRECTION('',(0.E+000,1.)); +#5513 = PCURVE('',#5487,#5514); +#5514 = DEFINITIONAL_REPRESENTATION('',(#5515),#5519); +#5515 = LINE('',#5516,#5517); +#5516 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5517 = VECTOR('',#5518,1.); +#5518 = DIRECTION('',(-1.,0.E+000)); +#5519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5520 = PCURVE('',#391,#5521); +#5521 = DEFINITIONAL_REPRESENTATION('',(#5522),#5530); +#5522 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5523,#5524,#5525,#5526, +#5527,#5528,#5529),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5523 = CARTESIAN_POINT('',(-24.72948318,31.74998222)); +#5524 = CARTESIAN_POINT('',(-24.72948318,32.629864030245)); +#5525 = CARTESIAN_POINT('',(-23.96748318,32.189923125122)); +#5526 = CARTESIAN_POINT('',(-23.20548318,31.74998222)); +#5527 = CARTESIAN_POINT('',(-23.96748318,31.310041314878)); +#5528 = CARTESIAN_POINT('',(-24.72948318,30.870100409755)); +#5529 = CARTESIAN_POINT('',(-24.72948318,31.74998222)); +#5530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5531 = ORIENTED_EDGE('',*,*,#5476,.F.); +#5532 = ORIENTED_EDGE('',*,*,#5533,.F.); +#5533 = EDGE_CURVE('',#5477,#5477,#5534,.T.); +#5534 = SURFACE_CURVE('',#5535,(#5540,#5547),.PCURVE_S1.); +#5535 = CIRCLE('',#5536,0.508); +#5536 = AXIS2_PLACEMENT_3D('',#5537,#5538,#5539); +#5537 = CARTESIAN_POINT('',(24.257,34.544,0.E+000)); +#5538 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5539 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5540 = PCURVE('',#5487,#5541); +#5541 = DEFINITIONAL_REPRESENTATION('',(#5542),#5546); +#5542 = LINE('',#5543,#5544); +#5543 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5544 = VECTOR('',#5545,1.); +#5545 = DIRECTION('',(-1.,0.E+000)); +#5546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5547 = PCURVE('',#445,#5548); +#5548 = DEFINITIONAL_REPRESENTATION('',(#5549),#5557); +#5549 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5550,#5551,#5552,#5553, +#5554,#5555,#5556),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5550 = CARTESIAN_POINT('',(-24.72948318,31.74998222)); +#5551 = CARTESIAN_POINT('',(-24.72948318,32.629864030245)); +#5552 = CARTESIAN_POINT('',(-23.96748318,32.189923125122)); +#5553 = CARTESIAN_POINT('',(-23.20548318,31.74998222)); +#5554 = CARTESIAN_POINT('',(-23.96748318,31.310041314878)); +#5555 = CARTESIAN_POINT('',(-24.72948318,30.870100409755)); +#5556 = CARTESIAN_POINT('',(-24.72948318,31.74998222)); #5557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5558 = PCURVE('',#5559,#5564); -#5559 = PLANE('',#5560); -#5560 = AXIS2_PLACEMENT_3D('',#5561,#5562,#5563); -#5561 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#5562 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5563 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5564 = DEFINITIONAL_REPRESENTATION('',(#5565),#5569); -#5565 = LINE('',#5566,#5567); -#5566 = CARTESIAN_POINT('',(-0.92,1.E-002)); -#5567 = VECTOR('',#5568,1.); -#5568 = DIRECTION('',(1.,0.E+000)); -#5569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5570 = ORIENTED_EDGE('',*,*,#5571,.F.); -#5571 = EDGE_CURVE('',#5572,#5544,#5574,.T.); -#5572 = VERTEX_POINT('',#5573); -#5573 = CARTESIAN_POINT('',(0.46,-0.24,0.24)); -#5574 = SURFACE_CURVE('',#5575,(#5579,#5586),.PCURVE_S1.); -#5575 = LINE('',#5576,#5577); -#5576 = CARTESIAN_POINT('',(0.46,-0.24,0.24)); -#5577 = VECTOR('',#5578,1.); -#5578 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5579 = PCURVE('',#5496,#5580); -#5580 = DEFINITIONAL_REPRESENTATION('',(#5581),#5585); -#5581 = LINE('',#5582,#5583); -#5582 = CARTESIAN_POINT('',(0.E+000,0.92)); -#5583 = VECTOR('',#5584,1.); -#5584 = DIRECTION('',(-1.,0.E+000)); -#5585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5586 = PCURVE('',#5587,#5592); -#5587 = PLANE('',#5588); -#5588 = AXIS2_PLACEMENT_3D('',#5589,#5590,#5591); -#5589 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#5590 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5591 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5592 = DEFINITIONAL_REPRESENTATION('',(#5593),#5597); -#5593 = LINE('',#5594,#5595); -#5594 = CARTESIAN_POINT('',(0.2,1.E-002)); -#5595 = VECTOR('',#5596,1.); -#5596 = DIRECTION('',(-1.,0.E+000)); -#5597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5598 = ORIENTED_EDGE('',*,*,#5599,.F.); -#5599 = EDGE_CURVE('',#5600,#5572,#5602,.T.); -#5600 = VERTEX_POINT('',#5601); -#5601 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); -#5602 = SURFACE_CURVE('',#5603,(#5607,#5614),.PCURVE_S1.); -#5603 = LINE('',#5604,#5605); -#5604 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); -#5605 = VECTOR('',#5606,1.); -#5606 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5607 = PCURVE('',#5496,#5608); -#5608 = DEFINITIONAL_REPRESENTATION('',(#5609),#5613); -#5609 = LINE('',#5610,#5611); -#5610 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5611 = VECTOR('',#5612,1.); -#5612 = DIRECTION('',(0.E+000,1.)); -#5613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5614 = PCURVE('',#5184,#5615); -#5615 = DEFINITIONAL_REPRESENTATION('',(#5616),#5620); -#5616 = LINE('',#5617,#5618); -#5617 = CARTESIAN_POINT('',(0.16,1.E-002)); -#5618 = VECTOR('',#5619,1.); -#5619 = DIRECTION('',(-1.,0.E+000)); -#5620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5621 = ORIENTED_EDGE('',*,*,#5622,.T.); -#5622 = EDGE_CURVE('',#5600,#5486,#5623,.T.); -#5623 = SURFACE_CURVE('',#5624,(#5628,#5635),.PCURVE_S1.); -#5624 = LINE('',#5625,#5626); -#5625 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); -#5626 = VECTOR('',#5627,1.); -#5627 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5628 = PCURVE('',#5496,#5629); -#5629 = DEFINITIONAL_REPRESENTATION('',(#5630),#5634); -#5630 = LINE('',#5631,#5632); -#5631 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5632 = VECTOR('',#5633,1.); -#5633 = DIRECTION('',(-1.,0.E+000)); -#5634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5635 = PCURVE('',#5636,#5641); -#5636 = PLANE('',#5637); -#5637 = AXIS2_PLACEMENT_3D('',#5638,#5639,#5640); -#5638 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5639 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5640 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5641 = DEFINITIONAL_REPRESENTATION('',(#5642),#5646); -#5642 = LINE('',#5643,#5644); -#5643 = CARTESIAN_POINT('',(-0.2,1.E-002)); -#5644 = VECTOR('',#5645,1.); -#5645 = DIRECTION('',(1.,0.E+000)); -#5646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5647 = ADVANCED_FACE('',(#5648),#5360,.F.); -#5648 = FACE_BOUND('',#5649,.T.); -#5649 = EDGE_LOOP('',(#5650,#5651,#5677,#5678)); -#5650 = ORIENTED_EDGE('',*,*,#5344,.F.); -#5651 = ORIENTED_EDGE('',*,*,#5652,.T.); -#5652 = EDGE_CURVE('',#5312,#5521,#5653,.T.); -#5653 = SURFACE_CURVE('',#5654,(#5658,#5665),.PCURVE_S1.); +#5558 = ADVANCED_FACE('',(#5559),#5573,.F.); +#5559 = FACE_BOUND('',#5560,.T.); +#5560 = EDGE_LOOP('',(#5561,#5591,#5617,#5618)); +#5561 = ORIENTED_EDGE('',*,*,#5562,.T.); +#5562 = EDGE_CURVE('',#5563,#5565,#5567,.T.); +#5563 = VERTEX_POINT('',#5564); +#5564 = CARTESIAN_POINT('',(27.305,34.544,0.E+000)); +#5565 = VERTEX_POINT('',#5566); +#5566 = CARTESIAN_POINT('',(27.305,34.544,1.7018)); +#5567 = SEAM_CURVE('',#5568,(#5572,#5584),.PCURVE_S1.); +#5568 = LINE('',#5569,#5570); +#5569 = CARTESIAN_POINT('',(27.305,34.544,0.E+000)); +#5570 = VECTOR('',#5571,1.); +#5571 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5572 = PCURVE('',#5573,#5578); +#5573 = CYLINDRICAL_SURFACE('',#5574,0.508); +#5574 = AXIS2_PLACEMENT_3D('',#5575,#5576,#5577); +#5575 = CARTESIAN_POINT('',(26.797,34.544,0.E+000)); +#5576 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5577 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5578 = DEFINITIONAL_REPRESENTATION('',(#5579),#5583); +#5579 = LINE('',#5580,#5581); +#5580 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5581 = VECTOR('',#5582,1.); +#5582 = DIRECTION('',(0.E+000,-1.)); +#5583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5584 = PCURVE('',#5573,#5585); +#5585 = DEFINITIONAL_REPRESENTATION('',(#5586),#5590); +#5586 = LINE('',#5587,#5588); +#5587 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5588 = VECTOR('',#5589,1.); +#5589 = DIRECTION('',(0.E+000,-1.)); +#5590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5591 = ORIENTED_EDGE('',*,*,#5592,.T.); +#5592 = EDGE_CURVE('',#5565,#5565,#5593,.T.); +#5593 = SURFACE_CURVE('',#5594,(#5599,#5606),.PCURVE_S1.); +#5594 = CIRCLE('',#5595,0.508); +#5595 = AXIS2_PLACEMENT_3D('',#5596,#5597,#5598); +#5596 = CARTESIAN_POINT('',(26.797,34.544,1.7018)); +#5597 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5599 = PCURVE('',#5573,#5600); +#5600 = DEFINITIONAL_REPRESENTATION('',(#5601),#5605); +#5601 = LINE('',#5602,#5603); +#5602 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5603 = VECTOR('',#5604,1.); +#5604 = DIRECTION('',(-1.,0.E+000)); +#5605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5606 = PCURVE('',#391,#5607); +#5607 = DEFINITIONAL_REPRESENTATION('',(#5608),#5616); +#5608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5609,#5610,#5611,#5612, +#5613,#5614,#5615),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5609 = CARTESIAN_POINT('',(-27.26948318,31.74998222)); +#5610 = CARTESIAN_POINT('',(-27.26948318,32.629864030245)); +#5611 = CARTESIAN_POINT('',(-26.50748318,32.189923125122)); +#5612 = CARTESIAN_POINT('',(-25.74548318,31.74998222)); +#5613 = CARTESIAN_POINT('',(-26.50748318,31.310041314878)); +#5614 = CARTESIAN_POINT('',(-27.26948318,30.870100409755)); +#5615 = CARTESIAN_POINT('',(-27.26948318,31.74998222)); +#5616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5617 = ORIENTED_EDGE('',*,*,#5562,.F.); +#5618 = ORIENTED_EDGE('',*,*,#5619,.F.); +#5619 = EDGE_CURVE('',#5563,#5563,#5620,.T.); +#5620 = SURFACE_CURVE('',#5621,(#5626,#5633),.PCURVE_S1.); +#5621 = CIRCLE('',#5622,0.508); +#5622 = AXIS2_PLACEMENT_3D('',#5623,#5624,#5625); +#5623 = CARTESIAN_POINT('',(26.797,34.544,0.E+000)); +#5624 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5625 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5626 = PCURVE('',#5573,#5627); +#5627 = DEFINITIONAL_REPRESENTATION('',(#5628),#5632); +#5628 = LINE('',#5629,#5630); +#5629 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5630 = VECTOR('',#5631,1.); +#5631 = DIRECTION('',(-1.,0.E+000)); +#5632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5633 = PCURVE('',#445,#5634); +#5634 = DEFINITIONAL_REPRESENTATION('',(#5635),#5643); +#5635 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5636,#5637,#5638,#5639, +#5640,#5641,#5642),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5636 = CARTESIAN_POINT('',(-27.26948318,31.74998222)); +#5637 = CARTESIAN_POINT('',(-27.26948318,32.629864030245)); +#5638 = CARTESIAN_POINT('',(-26.50748318,32.189923125122)); +#5639 = CARTESIAN_POINT('',(-25.74548318,31.74998222)); +#5640 = CARTESIAN_POINT('',(-26.50748318,31.310041314878)); +#5641 = CARTESIAN_POINT('',(-27.26948318,30.870100409755)); +#5642 = CARTESIAN_POINT('',(-27.26948318,31.74998222)); +#5643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5644 = ADVANCED_FACE('',(#5645),#5659,.F.); +#5645 = FACE_BOUND('',#5646,.T.); +#5646 = EDGE_LOOP('',(#5647,#5677,#5703,#5704)); +#5647 = ORIENTED_EDGE('',*,*,#5648,.T.); +#5648 = EDGE_CURVE('',#5649,#5651,#5653,.T.); +#5649 = VERTEX_POINT('',#5650); +#5650 = CARTESIAN_POINT('',(32.0480436,14.9538436,0.E+000)); +#5651 = VERTEX_POINT('',#5652); +#5652 = CARTESIAN_POINT('',(32.0480436,14.9538436,1.7018)); +#5653 = SEAM_CURVE('',#5654,(#5658,#5670),.PCURVE_S1.); #5654 = LINE('',#5655,#5656); -#5655 = CARTESIAN_POINT('',(0.3,-0.24,4.E-002)); +#5655 = CARTESIAN_POINT('',(32.0480436,14.9538436,0.E+000)); #5656 = VECTOR('',#5657,1.); -#5657 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#5658 = PCURVE('',#5360,#5659); -#5659 = DEFINITIONAL_REPRESENTATION('',(#5660),#5664); -#5660 = LINE('',#5661,#5662); -#5661 = CARTESIAN_POINT('',(-0.16,0.E+000)); -#5662 = VECTOR('',#5663,1.); -#5663 = DIRECTION('',(0.E+000,-1.)); -#5664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5665 = PCURVE('',#5666,#5671); -#5666 = PLANE('',#5667); -#5667 = AXIS2_PLACEMENT_3D('',#5668,#5669,#5670); -#5668 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); -#5669 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5670 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5657 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5658 = PCURVE('',#5659,#5664); +#5659 = CYLINDRICAL_SURFACE('',#5660,0.508); +#5660 = AXIS2_PLACEMENT_3D('',#5661,#5662,#5663); +#5661 = CARTESIAN_POINT('',(31.5400436,14.9538436,0.E+000)); +#5662 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5663 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5664 = DEFINITIONAL_REPRESENTATION('',(#5665),#5669); +#5665 = LINE('',#5666,#5667); +#5666 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5667 = VECTOR('',#5668,1.); +#5668 = DIRECTION('',(0.E+000,-1.)); +#5669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5670 = PCURVE('',#5659,#5671); #5671 = DEFINITIONAL_REPRESENTATION('',(#5672),#5676); #5672 = LINE('',#5673,#5674); -#5673 = CARTESIAN_POINT('',(4.E-002,1.E-002)); +#5673 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); #5674 = VECTOR('',#5675,1.); #5675 = DIRECTION('',(0.E+000,-1.)); #5676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5677 = ORIENTED_EDGE('',*,*,#5520,.F.); -#5678 = ORIENTED_EDGE('',*,*,#5679,.T.); -#5679 = EDGE_CURVE('',#5488,#5345,#5680,.T.); -#5680 = SURFACE_CURVE('',#5681,(#5685,#5692),.PCURVE_S1.); -#5681 = LINE('',#5682,#5683); -#5682 = CARTESIAN_POINT('',(-0.3,-0.24,4.E-002)); -#5683 = VECTOR('',#5684,1.); -#5684 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5685 = PCURVE('',#5360,#5686); +#5677 = ORIENTED_EDGE('',*,*,#5678,.T.); +#5678 = EDGE_CURVE('',#5651,#5651,#5679,.T.); +#5679 = SURFACE_CURVE('',#5680,(#5685,#5692),.PCURVE_S1.); +#5680 = CIRCLE('',#5681,0.508); +#5681 = AXIS2_PLACEMENT_3D('',#5682,#5683,#5684); +#5682 = CARTESIAN_POINT('',(31.5400436,14.9538436,1.7018)); +#5683 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5684 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5685 = PCURVE('',#5659,#5686); #5686 = DEFINITIONAL_REPRESENTATION('',(#5687),#5691); #5687 = LINE('',#5688,#5689); -#5688 = CARTESIAN_POINT('',(-0.76,0.E+000)); +#5688 = CARTESIAN_POINT('',(0.E+000,-1.7018)); #5689 = VECTOR('',#5690,1.); -#5690 = DIRECTION('',(0.E+000,1.)); +#5690 = DIRECTION('',(-1.,0.E+000)); #5691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#5692 = PCURVE('',#5693,#5698); -#5693 = PLANE('',#5694); -#5694 = AXIS2_PLACEMENT_3D('',#5695,#5696,#5697); -#5695 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); -#5696 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5697 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5698 = DEFINITIONAL_REPRESENTATION('',(#5699),#5703); -#5699 = LINE('',#5700,#5701); -#5700 = CARTESIAN_POINT('',(-4.E-002,1.E-002)); -#5701 = VECTOR('',#5702,1.); -#5702 = DIRECTION('',(0.E+000,1.)); -#5703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5704 = ADVANCED_FACE('',(#5705),#5388,.T.); -#5705 = FACE_BOUND('',#5706,.T.); -#5706 = EDGE_LOOP('',(#5707,#5708,#5731,#5759)); -#5707 = ORIENTED_EDGE('',*,*,#5372,.F.); -#5708 = ORIENTED_EDGE('',*,*,#5709,.T.); -#5709 = EDGE_CURVE('',#5345,#5710,#5712,.T.); -#5710 = VERTEX_POINT('',#5711); -#5711 = CARTESIAN_POINT('',(-0.3,0.25,4.E-002)); -#5712 = SURFACE_CURVE('',#5713,(#5717,#5724),.PCURVE_S1.); -#5713 = LINE('',#5714,#5715); -#5714 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); -#5715 = VECTOR('',#5716,1.); -#5716 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5717 = PCURVE('',#5388,#5718); -#5718 = DEFINITIONAL_REPRESENTATION('',(#5719),#5723); -#5719 = LINE('',#5720,#5721); -#5720 = CARTESIAN_POINT('',(0.16,0.E+000)); -#5721 = VECTOR('',#5722,1.); -#5722 = DIRECTION('',(0.E+000,1.)); -#5723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5724 = PCURVE('',#5693,#5725); -#5725 = DEFINITIONAL_REPRESENTATION('',(#5726),#5730); -#5726 = LINE('',#5727,#5728); -#5727 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#5728 = VECTOR('',#5729,1.); -#5729 = DIRECTION('',(0.E+000,1.)); -#5730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5731 = ORIENTED_EDGE('',*,*,#5732,.F.); -#5732 = EDGE_CURVE('',#5733,#5710,#5735,.T.); -#5733 = VERTEX_POINT('',#5734); -#5734 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); -#5735 = SURFACE_CURVE('',#5736,(#5740,#5747),.PCURVE_S1.); -#5736 = LINE('',#5737,#5738); -#5737 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); -#5738 = VECTOR('',#5739,1.); -#5739 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5740 = PCURVE('',#5388,#5741); -#5741 = DEFINITIONAL_REPRESENTATION('',(#5742),#5746); -#5742 = LINE('',#5743,#5744); -#5743 = CARTESIAN_POINT('',(0.E+000,0.5)); -#5744 = VECTOR('',#5745,1.); -#5745 = DIRECTION('',(1.,0.E+000)); -#5746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5747 = PCURVE('',#5748,#5753); -#5748 = PLANE('',#5749); -#5749 = AXIS2_PLACEMENT_3D('',#5750,#5751,#5752); -#5750 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); -#5751 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5752 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5753 = DEFINITIONAL_REPRESENTATION('',(#5754),#5758); -#5754 = LINE('',#5755,#5756); -#5755 = CARTESIAN_POINT('',(-0.24,4.E-002)); -#5756 = VECTOR('',#5757,1.); -#5757 = DIRECTION('',(0.E+000,1.)); -#5758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5759 = ORIENTED_EDGE('',*,*,#5760,.F.); -#5760 = EDGE_CURVE('',#5373,#5733,#5761,.T.); -#5761 = SURFACE_CURVE('',#5762,(#5766,#5773),.PCURVE_S1.); -#5762 = LINE('',#5763,#5764); -#5763 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5764 = VECTOR('',#5765,1.); -#5765 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5766 = PCURVE('',#5388,#5767); -#5767 = DEFINITIONAL_REPRESENTATION('',(#5768),#5772); -#5768 = LINE('',#5769,#5770); -#5769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5770 = VECTOR('',#5771,1.); -#5771 = DIRECTION('',(0.E+000,1.)); -#5772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5773 = PCURVE('',#5416,#5774); -#5774 = DEFINITIONAL_REPRESENTATION('',(#5775),#5779); -#5775 = LINE('',#5776,#5777); -#5776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5777 = VECTOR('',#5778,1.); -#5778 = DIRECTION('',(0.E+000,1.)); -#5779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5780 = ADVANCED_FACE('',(#5781),#5508,.T.); -#5781 = FACE_BOUND('',#5782,.T.); -#5782 = EDGE_LOOP('',(#5783,#5784,#5807,#5830)); -#5783 = ORIENTED_EDGE('',*,*,#5485,.F.); -#5784 = ORIENTED_EDGE('',*,*,#5785,.F.); -#5785 = EDGE_CURVE('',#5786,#5486,#5788,.T.); -#5786 = VERTEX_POINT('',#5787); -#5787 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5788 = SURFACE_CURVE('',#5789,(#5793,#5800),.PCURVE_S1.); -#5789 = LINE('',#5790,#5791); -#5790 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5791 = VECTOR('',#5792,1.); -#5792 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5793 = PCURVE('',#5508,#5794); -#5794 = DEFINITIONAL_REPRESENTATION('',(#5795),#5799); -#5795 = LINE('',#5796,#5797); -#5796 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5797 = VECTOR('',#5798,1.); -#5798 = DIRECTION('',(0.E+000,1.)); -#5799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5800 = PCURVE('',#5636,#5801); -#5801 = DEFINITIONAL_REPRESENTATION('',(#5802),#5806); -#5802 = LINE('',#5803,#5804); -#5803 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5804 = VECTOR('',#5805,1.); -#5805 = DIRECTION('',(0.E+000,1.)); -#5806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5807 = ORIENTED_EDGE('',*,*,#5808,.T.); -#5808 = EDGE_CURVE('',#5786,#5809,#5811,.T.); -#5809 = VERTEX_POINT('',#5810); -#5810 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); -#5811 = SURFACE_CURVE('',#5812,(#5816,#5823),.PCURVE_S1.); -#5812 = LINE('',#5813,#5814); -#5813 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#5814 = VECTOR('',#5815,1.); -#5815 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5816 = PCURVE('',#5508,#5817); -#5817 = DEFINITIONAL_REPRESENTATION('',(#5818),#5822); -#5818 = LINE('',#5819,#5820); -#5819 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5820 = VECTOR('',#5821,1.); -#5821 = DIRECTION('',(1.,0.E+000)); -#5822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5823 = PCURVE('',#5158,#5824); -#5824 = DEFINITIONAL_REPRESENTATION('',(#5825),#5829); -#5825 = LINE('',#5826,#5827); -#5826 = CARTESIAN_POINT('',(-0.24,4.E-002)); -#5827 = VECTOR('',#5828,1.); -#5828 = DIRECTION('',(0.E+000,1.)); -#5829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5830 = ORIENTED_EDGE('',*,*,#5831,.T.); -#5831 = EDGE_CURVE('',#5809,#5488,#5832,.T.); -#5832 = SURFACE_CURVE('',#5833,(#5837,#5844),.PCURVE_S1.); -#5833 = LINE('',#5834,#5835); -#5834 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); -#5835 = VECTOR('',#5836,1.); -#5836 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5837 = PCURVE('',#5508,#5838); -#5838 = DEFINITIONAL_REPRESENTATION('',(#5839),#5843); -#5839 = LINE('',#5840,#5841); -#5840 = CARTESIAN_POINT('',(0.16,0.E+000)); -#5841 = VECTOR('',#5842,1.); -#5842 = DIRECTION('',(0.E+000,1.)); -#5843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5844 = PCURVE('',#5693,#5845); -#5845 = DEFINITIONAL_REPRESENTATION('',(#5846),#5850); -#5846 = LINE('',#5847,#5848); -#5847 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#5848 = VECTOR('',#5849,1.); -#5849 = DIRECTION('',(0.E+000,1.)); -#5850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5851 = ADVANCED_FACE('',(#5852),#5444,.T.); -#5852 = FACE_BOUND('',#5853,.T.); -#5853 = EDGE_LOOP('',(#5854,#5855,#5878,#5901,#5929,#5957,#5985,#6013)); -#5854 = ORIENTED_EDGE('',*,*,#5428,.T.); -#5855 = ORIENTED_EDGE('',*,*,#5856,.T.); -#5856 = EDGE_CURVE('',#5401,#5857,#5859,.T.); -#5857 = VERTEX_POINT('',#5858); -#5858 = CARTESIAN_POINT('',(-0.46,0.25,0.24)); -#5859 = SURFACE_CURVE('',#5860,(#5864,#5871),.PCURVE_S1.); -#5860 = LINE('',#5861,#5862); -#5861 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); -#5862 = VECTOR('',#5863,1.); -#5863 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5864 = PCURVE('',#5444,#5865); -#5865 = DEFINITIONAL_REPRESENTATION('',(#5866),#5870); -#5866 = LINE('',#5867,#5868); -#5867 = CARTESIAN_POINT('',(0.16,0.E+000)); -#5868 = VECTOR('',#5869,1.); -#5869 = DIRECTION('',(0.E+000,1.)); -#5870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5871 = PCURVE('',#5416,#5872); -#5872 = DEFINITIONAL_REPRESENTATION('',(#5873),#5877); -#5873 = LINE('',#5874,#5875); -#5874 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#5875 = VECTOR('',#5876,1.); -#5876 = DIRECTION('',(0.E+000,1.)); -#5877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5878 = ORIENTED_EDGE('',*,*,#5879,.F.); -#5879 = EDGE_CURVE('',#5880,#5857,#5882,.T.); -#5880 = VERTEX_POINT('',#5881); -#5881 = CARTESIAN_POINT('',(-0.3,0.25,0.24)); -#5882 = SURFACE_CURVE('',#5883,(#5887,#5894),.PCURVE_S1.); -#5883 = LINE('',#5884,#5885); -#5884 = CARTESIAN_POINT('',(-0.3,0.25,0.24)); -#5885 = VECTOR('',#5886,1.); -#5886 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); -#5887 = PCURVE('',#5444,#5888); -#5888 = DEFINITIONAL_REPRESENTATION('',(#5889),#5893); -#5889 = LINE('',#5890,#5891); -#5890 = CARTESIAN_POINT('',(0.E+000,0.5)); -#5891 = VECTOR('',#5892,1.); -#5892 = DIRECTION('',(1.,0.E+000)); -#5893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5894 = PCURVE('',#5748,#5895); -#5895 = DEFINITIONAL_REPRESENTATION('',(#5896),#5900); -#5896 = LINE('',#5897,#5898); -#5897 = CARTESIAN_POINT('',(-4.E-002,0.2)); -#5898 = VECTOR('',#5899,1.); -#5899 = DIRECTION('',(1.694065894509E-016,-1.)); -#5900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5901 = ORIENTED_EDGE('',*,*,#5902,.F.); -#5902 = EDGE_CURVE('',#5903,#5880,#5905,.T.); -#5903 = VERTEX_POINT('',#5904); -#5904 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); -#5905 = SURFACE_CURVE('',#5906,(#5910,#5917),.PCURVE_S1.); -#5906 = LINE('',#5907,#5908); -#5907 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#5908 = VECTOR('',#5909,1.); -#5909 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5910 = PCURVE('',#5444,#5911); -#5911 = DEFINITIONAL_REPRESENTATION('',(#5912),#5916); +#5692 = PCURVE('',#391,#5693); +#5693 = DEFINITIONAL_REPRESENTATION('',(#5694),#5702); +#5694 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5695,#5696,#5697,#5698, +#5699,#5700,#5701),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5695 = CARTESIAN_POINT('',(-32.01252678,12.15982582)); +#5696 = CARTESIAN_POINT('',(-32.01252678,13.039707630245)); +#5697 = CARTESIAN_POINT('',(-31.25052678,12.599766725123)); +#5698 = CARTESIAN_POINT('',(-30.48852678,12.15982582)); +#5699 = CARTESIAN_POINT('',(-31.25052678,11.719884914878)); +#5700 = CARTESIAN_POINT('',(-32.01252678,11.279944009755)); +#5701 = CARTESIAN_POINT('',(-32.01252678,12.15982582)); +#5702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5703 = ORIENTED_EDGE('',*,*,#5648,.F.); +#5704 = ORIENTED_EDGE('',*,*,#5705,.F.); +#5705 = EDGE_CURVE('',#5649,#5649,#5706,.T.); +#5706 = SURFACE_CURVE('',#5707,(#5712,#5719),.PCURVE_S1.); +#5707 = CIRCLE('',#5708,0.508); +#5708 = AXIS2_PLACEMENT_3D('',#5709,#5710,#5711); +#5709 = CARTESIAN_POINT('',(31.5400436,14.9538436,0.E+000)); +#5710 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5711 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5712 = PCURVE('',#5659,#5713); +#5713 = DEFINITIONAL_REPRESENTATION('',(#5714),#5718); +#5714 = LINE('',#5715,#5716); +#5715 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5716 = VECTOR('',#5717,1.); +#5717 = DIRECTION('',(-1.,0.E+000)); +#5718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5719 = PCURVE('',#445,#5720); +#5720 = DEFINITIONAL_REPRESENTATION('',(#5721),#5729); +#5721 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5722,#5723,#5724,#5725, +#5726,#5727,#5728),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5722 = CARTESIAN_POINT('',(-32.01252678,12.15982582)); +#5723 = CARTESIAN_POINT('',(-32.01252678,13.039707630245)); +#5724 = CARTESIAN_POINT('',(-31.25052678,12.599766725123)); +#5725 = CARTESIAN_POINT('',(-30.48852678,12.15982582)); +#5726 = CARTESIAN_POINT('',(-31.25052678,11.719884914878)); +#5727 = CARTESIAN_POINT('',(-32.01252678,11.279944009755)); +#5728 = CARTESIAN_POINT('',(-32.01252678,12.15982582)); +#5729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5730 = ADVANCED_FACE('',(#5731),#5745,.F.); +#5731 = FACE_BOUND('',#5732,.T.); +#5732 = EDGE_LOOP('',(#5733,#5763,#5789,#5790)); +#5733 = ORIENTED_EDGE('',*,*,#5734,.T.); +#5734 = EDGE_CURVE('',#5735,#5737,#5739,.T.); +#5735 = VERTEX_POINT('',#5736); +#5736 = CARTESIAN_POINT('',(32.0480436,20.0338436,0.E+000)); +#5737 = VERTEX_POINT('',#5738); +#5738 = CARTESIAN_POINT('',(32.0480436,20.0338436,1.7018)); +#5739 = SEAM_CURVE('',#5740,(#5744,#5756),.PCURVE_S1.); +#5740 = LINE('',#5741,#5742); +#5741 = CARTESIAN_POINT('',(32.0480436,20.0338436,0.E+000)); +#5742 = VECTOR('',#5743,1.); +#5743 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5744 = PCURVE('',#5745,#5750); +#5745 = CYLINDRICAL_SURFACE('',#5746,0.508); +#5746 = AXIS2_PLACEMENT_3D('',#5747,#5748,#5749); +#5747 = CARTESIAN_POINT('',(31.5400436,20.0338436,0.E+000)); +#5748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5749 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5750 = DEFINITIONAL_REPRESENTATION('',(#5751),#5755); +#5751 = LINE('',#5752,#5753); +#5752 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5753 = VECTOR('',#5754,1.); +#5754 = DIRECTION('',(0.E+000,-1.)); +#5755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5756 = PCURVE('',#5745,#5757); +#5757 = DEFINITIONAL_REPRESENTATION('',(#5758),#5762); +#5758 = LINE('',#5759,#5760); +#5759 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5760 = VECTOR('',#5761,1.); +#5761 = DIRECTION('',(0.E+000,-1.)); +#5762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5763 = ORIENTED_EDGE('',*,*,#5764,.T.); +#5764 = EDGE_CURVE('',#5737,#5737,#5765,.T.); +#5765 = SURFACE_CURVE('',#5766,(#5771,#5778),.PCURVE_S1.); +#5766 = CIRCLE('',#5767,0.508); +#5767 = AXIS2_PLACEMENT_3D('',#5768,#5769,#5770); +#5768 = CARTESIAN_POINT('',(31.5400436,20.0338436,1.7018)); +#5769 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5770 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5771 = PCURVE('',#5745,#5772); +#5772 = DEFINITIONAL_REPRESENTATION('',(#5773),#5777); +#5773 = LINE('',#5774,#5775); +#5774 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5775 = VECTOR('',#5776,1.); +#5776 = DIRECTION('',(-1.,0.E+000)); +#5777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5778 = PCURVE('',#391,#5779); +#5779 = DEFINITIONAL_REPRESENTATION('',(#5780),#5788); +#5780 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5781,#5782,#5783,#5784, +#5785,#5786,#5787),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5781 = CARTESIAN_POINT('',(-32.01252678,17.23982582)); +#5782 = CARTESIAN_POINT('',(-32.01252678,18.119707630245)); +#5783 = CARTESIAN_POINT('',(-31.25052678,17.679766725122)); +#5784 = CARTESIAN_POINT('',(-30.48852678,17.23982582)); +#5785 = CARTESIAN_POINT('',(-31.25052678,16.799884914878)); +#5786 = CARTESIAN_POINT('',(-32.01252678,16.359944009755)); +#5787 = CARTESIAN_POINT('',(-32.01252678,17.23982582)); +#5788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5789 = ORIENTED_EDGE('',*,*,#5734,.F.); +#5790 = ORIENTED_EDGE('',*,*,#5791,.F.); +#5791 = EDGE_CURVE('',#5735,#5735,#5792,.T.); +#5792 = SURFACE_CURVE('',#5793,(#5798,#5805),.PCURVE_S1.); +#5793 = CIRCLE('',#5794,0.508); +#5794 = AXIS2_PLACEMENT_3D('',#5795,#5796,#5797); +#5795 = CARTESIAN_POINT('',(31.5400436,20.0338436,0.E+000)); +#5796 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5797 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5798 = PCURVE('',#5745,#5799); +#5799 = DEFINITIONAL_REPRESENTATION('',(#5800),#5804); +#5800 = LINE('',#5801,#5802); +#5801 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5802 = VECTOR('',#5803,1.); +#5803 = DIRECTION('',(-1.,0.E+000)); +#5804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5805 = PCURVE('',#445,#5806); +#5806 = DEFINITIONAL_REPRESENTATION('',(#5807),#5815); +#5807 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5808,#5809,#5810,#5811, +#5812,#5813,#5814),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5808 = CARTESIAN_POINT('',(-32.01252678,17.23982582)); +#5809 = CARTESIAN_POINT('',(-32.01252678,18.119707630245)); +#5810 = CARTESIAN_POINT('',(-31.25052678,17.679766725122)); +#5811 = CARTESIAN_POINT('',(-30.48852678,17.23982582)); +#5812 = CARTESIAN_POINT('',(-31.25052678,16.799884914878)); +#5813 = CARTESIAN_POINT('',(-32.01252678,16.359944009755)); +#5814 = CARTESIAN_POINT('',(-32.01252678,17.23982582)); +#5815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5816 = ADVANCED_FACE('',(#5817),#5831,.F.); +#5817 = FACE_BOUND('',#5818,.T.); +#5818 = EDGE_LOOP('',(#5819,#5849,#5875,#5876)); +#5819 = ORIENTED_EDGE('',*,*,#5820,.T.); +#5820 = EDGE_CURVE('',#5821,#5823,#5825,.T.); +#5821 = VERTEX_POINT('',#5822); +#5822 = CARTESIAN_POINT('',(34.5880436,14.9538436,0.E+000)); +#5823 = VERTEX_POINT('',#5824); +#5824 = CARTESIAN_POINT('',(34.5880436,14.9538436,1.7018)); +#5825 = SEAM_CURVE('',#5826,(#5830,#5842),.PCURVE_S1.); +#5826 = LINE('',#5827,#5828); +#5827 = CARTESIAN_POINT('',(34.5880436,14.9538436,0.E+000)); +#5828 = VECTOR('',#5829,1.); +#5829 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5830 = PCURVE('',#5831,#5836); +#5831 = CYLINDRICAL_SURFACE('',#5832,0.508); +#5832 = AXIS2_PLACEMENT_3D('',#5833,#5834,#5835); +#5833 = CARTESIAN_POINT('',(34.0800436,14.9538436,0.E+000)); +#5834 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#5835 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5836 = DEFINITIONAL_REPRESENTATION('',(#5837),#5841); +#5837 = LINE('',#5838,#5839); +#5838 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5839 = VECTOR('',#5840,1.); +#5840 = DIRECTION('',(0.E+000,-1.)); +#5841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5842 = PCURVE('',#5831,#5843); +#5843 = DEFINITIONAL_REPRESENTATION('',(#5844),#5848); +#5844 = LINE('',#5845,#5846); +#5845 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5846 = VECTOR('',#5847,1.); +#5847 = DIRECTION('',(0.E+000,-1.)); +#5848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5849 = ORIENTED_EDGE('',*,*,#5850,.T.); +#5850 = EDGE_CURVE('',#5823,#5823,#5851,.T.); +#5851 = SURFACE_CURVE('',#5852,(#5857,#5864),.PCURVE_S1.); +#5852 = CIRCLE('',#5853,0.508); +#5853 = AXIS2_PLACEMENT_3D('',#5854,#5855,#5856); +#5854 = CARTESIAN_POINT('',(34.0800436,14.9538436,1.7018)); +#5855 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5856 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5857 = PCURVE('',#5831,#5858); +#5858 = DEFINITIONAL_REPRESENTATION('',(#5859),#5863); +#5859 = LINE('',#5860,#5861); +#5860 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5861 = VECTOR('',#5862,1.); +#5862 = DIRECTION('',(-1.,0.E+000)); +#5863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5864 = PCURVE('',#391,#5865); +#5865 = DEFINITIONAL_REPRESENTATION('',(#5866),#5874); +#5866 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5867,#5868,#5869,#5870, +#5871,#5872,#5873),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5867 = CARTESIAN_POINT('',(-34.55252678,12.15982582)); +#5868 = CARTESIAN_POINT('',(-34.55252678,13.039707630245)); +#5869 = CARTESIAN_POINT('',(-33.79052678,12.599766725123)); +#5870 = CARTESIAN_POINT('',(-33.02852678,12.15982582)); +#5871 = CARTESIAN_POINT('',(-33.79052678,11.719884914878)); +#5872 = CARTESIAN_POINT('',(-34.55252678,11.279944009755)); +#5873 = CARTESIAN_POINT('',(-34.55252678,12.15982582)); +#5874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5875 = ORIENTED_EDGE('',*,*,#5820,.F.); +#5876 = ORIENTED_EDGE('',*,*,#5877,.F.); +#5877 = EDGE_CURVE('',#5821,#5821,#5878,.T.); +#5878 = SURFACE_CURVE('',#5879,(#5884,#5891),.PCURVE_S1.); +#5879 = CIRCLE('',#5880,0.508); +#5880 = AXIS2_PLACEMENT_3D('',#5881,#5882,#5883); +#5881 = CARTESIAN_POINT('',(34.0800436,14.9538436,0.E+000)); +#5882 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5883 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5884 = PCURVE('',#5831,#5885); +#5885 = DEFINITIONAL_REPRESENTATION('',(#5886),#5890); +#5886 = LINE('',#5887,#5888); +#5887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5888 = VECTOR('',#5889,1.); +#5889 = DIRECTION('',(-1.,0.E+000)); +#5890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5891 = PCURVE('',#445,#5892); +#5892 = DEFINITIONAL_REPRESENTATION('',(#5893),#5901); +#5893 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5894,#5895,#5896,#5897, +#5898,#5899,#5900),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5894 = CARTESIAN_POINT('',(-34.55252678,12.15982582)); +#5895 = CARTESIAN_POINT('',(-34.55252678,13.039707630245)); +#5896 = CARTESIAN_POINT('',(-33.79052678,12.599766725123)); +#5897 = CARTESIAN_POINT('',(-33.02852678,12.15982582)); +#5898 = CARTESIAN_POINT('',(-33.79052678,11.719884914878)); +#5899 = CARTESIAN_POINT('',(-34.55252678,11.279944009755)); +#5900 = CARTESIAN_POINT('',(-34.55252678,12.15982582)); +#5901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5902 = ADVANCED_FACE('',(#5903),#5917,.F.); +#5903 = FACE_BOUND('',#5904,.T.); +#5904 = EDGE_LOOP('',(#5905,#5935,#5961,#5962)); +#5905 = ORIENTED_EDGE('',*,*,#5906,.T.); +#5906 = EDGE_CURVE('',#5907,#5909,#5911,.T.); +#5907 = VERTEX_POINT('',#5908); +#5908 = CARTESIAN_POINT('',(34.79401474,2.794,0.E+000)); +#5909 = VERTEX_POINT('',#5910); +#5910 = CARTESIAN_POINT('',(34.79401474,2.794,1.7018)); +#5911 = SEAM_CURVE('',#5912,(#5916,#5928),.PCURVE_S1.); #5912 = LINE('',#5913,#5914); -#5913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5913 = CARTESIAN_POINT('',(34.79401474,2.794,0.E+000)); #5914 = VECTOR('',#5915,1.); -#5915 = DIRECTION('',(0.E+000,1.)); -#5916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5917 = PCURVE('',#5918,#5923); -#5918 = PLANE('',#5919); -#5919 = AXIS2_PLACEMENT_3D('',#5920,#5921,#5922); -#5920 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#5915 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5916 = PCURVE('',#5917,#5922); +#5917 = CYLINDRICAL_SURFACE('',#5918,1.49999954); +#5918 = AXIS2_PLACEMENT_3D('',#5919,#5920,#5921); +#5919 = CARTESIAN_POINT('',(33.2940152,2.794,0.E+000)); +#5920 = DIRECTION('',(0.E+000,0.E+000,-1.)); #5921 = DIRECTION('',(1.,0.E+000,0.E+000)); -#5922 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#5923 = DEFINITIONAL_REPRESENTATION('',(#5924),#5928); -#5924 = LINE('',#5925,#5926); -#5925 = CARTESIAN_POINT('',(4.E-002,0.E+000)); -#5926 = VECTOR('',#5927,1.); -#5927 = DIRECTION('',(0.E+000,1.)); -#5928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5929 = ORIENTED_EDGE('',*,*,#5930,.F.); -#5930 = EDGE_CURVE('',#5931,#5903,#5933,.T.); -#5931 = VERTEX_POINT('',#5932); -#5932 = CARTESIAN_POINT('',(0.3,0.245,0.24)); -#5933 = SURFACE_CURVE('',#5934,(#5938,#5945),.PCURVE_S1.); -#5934 = LINE('',#5935,#5936); -#5935 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); -#5936 = VECTOR('',#5937,1.); -#5937 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5938 = PCURVE('',#5444,#5939); -#5939 = DEFINITIONAL_REPRESENTATION('',(#5940),#5944); -#5940 = LINE('',#5941,#5942); -#5941 = CARTESIAN_POINT('',(0.E+000,0.495)); -#5942 = VECTOR('',#5943,1.); -#5943 = DIRECTION('',(1.,0.E+000)); -#5944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5945 = PCURVE('',#5946,#5951); -#5946 = PLANE('',#5947); -#5947 = AXIS2_PLACEMENT_3D('',#5948,#5949,#5950); -#5948 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); -#5949 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5950 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5951 = DEFINITIONAL_REPRESENTATION('',(#5952),#5956); -#5952 = LINE('',#5953,#5954); -#5953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#5954 = VECTOR('',#5955,1.); -#5955 = DIRECTION('',(0.E+000,-1.)); -#5956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5957 = ORIENTED_EDGE('',*,*,#5958,.T.); -#5958 = EDGE_CURVE('',#5931,#5959,#5961,.T.); -#5959 = VERTEX_POINT('',#5960); -#5960 = CARTESIAN_POINT('',(0.3,0.25,0.24)); -#5961 = SURFACE_CURVE('',#5962,(#5966,#5973),.PCURVE_S1.); -#5962 = LINE('',#5963,#5964); -#5963 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); -#5964 = VECTOR('',#5965,1.); -#5965 = DIRECTION('',(0.E+000,1.,0.E+000)); -#5966 = PCURVE('',#5444,#5967); -#5967 = DEFINITIONAL_REPRESENTATION('',(#5968),#5972); -#5968 = LINE('',#5969,#5970); -#5969 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#5970 = VECTOR('',#5971,1.); -#5971 = DIRECTION('',(0.E+000,1.)); -#5972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5973 = PCURVE('',#5974,#5979); -#5974 = PLANE('',#5975); -#5975 = AXIS2_PLACEMENT_3D('',#5976,#5977,#5978); -#5976 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#5977 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#5978 = DIRECTION('',(0.E+000,0.E+000,1.)); -#5979 = DEFINITIONAL_REPRESENTATION('',(#5980),#5984); -#5980 = LINE('',#5981,#5982); -#5981 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#5982 = VECTOR('',#5983,1.); -#5983 = DIRECTION('',(0.E+000,1.)); -#5984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#5985 = ORIENTED_EDGE('',*,*,#5986,.F.); -#5986 = EDGE_CURVE('',#5987,#5959,#5989,.T.); -#5987 = VERTEX_POINT('',#5988); -#5988 = CARTESIAN_POINT('',(0.46,0.25,0.24)); -#5989 = SURFACE_CURVE('',#5990,(#5994,#6001),.PCURVE_S1.); -#5990 = LINE('',#5991,#5992); -#5991 = CARTESIAN_POINT('',(0.3,0.25,0.24)); -#5992 = VECTOR('',#5993,1.); -#5993 = DIRECTION('',(-1.,0.E+000,-1.694065894509E-016)); -#5994 = PCURVE('',#5444,#5995); -#5995 = DEFINITIONAL_REPRESENTATION('',(#5996),#6000); -#5996 = LINE('',#5997,#5998); -#5997 = CARTESIAN_POINT('',(-0.6,0.5)); -#5998 = VECTOR('',#5999,1.); -#5999 = DIRECTION('',(1.,0.E+000)); -#6000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6001 = PCURVE('',#6002,#6007); -#6002 = PLANE('',#6003); -#6003 = AXIS2_PLACEMENT_3D('',#6004,#6005,#6006); -#6004 = CARTESIAN_POINT('',(0.3,0.25,0.24)); -#6005 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#5922 = DEFINITIONAL_REPRESENTATION('',(#5923),#5927); +#5923 = LINE('',#5924,#5925); +#5924 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5925 = VECTOR('',#5926,1.); +#5926 = DIRECTION('',(0.E+000,-1.)); +#5927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5928 = PCURVE('',#5917,#5929); +#5929 = DEFINITIONAL_REPRESENTATION('',(#5930),#5934); +#5930 = LINE('',#5931,#5932); +#5931 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#5932 = VECTOR('',#5933,1.); +#5933 = DIRECTION('',(0.E+000,-1.)); +#5934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5935 = ORIENTED_EDGE('',*,*,#5936,.T.); +#5936 = EDGE_CURVE('',#5909,#5909,#5937,.T.); +#5937 = SURFACE_CURVE('',#5938,(#5943,#5950),.PCURVE_S1.); +#5938 = CIRCLE('',#5939,1.49999954); +#5939 = AXIS2_PLACEMENT_3D('',#5940,#5941,#5942); +#5940 = CARTESIAN_POINT('',(33.2940152,2.794,1.7018)); +#5941 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5943 = PCURVE('',#5917,#5944); +#5944 = DEFINITIONAL_REPRESENTATION('',(#5945),#5949); +#5945 = LINE('',#5946,#5947); +#5946 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#5947 = VECTOR('',#5948,1.); +#5948 = DIRECTION('',(-1.,0.E+000)); +#5949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5950 = PCURVE('',#391,#5951); +#5951 = DEFINITIONAL_REPRESENTATION('',(#5952),#5960); +#5952 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5953,#5954,#5955,#5956, +#5957,#5958,#5959),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5953 = CARTESIAN_POINT('',(-34.75849792,-1.77800000003E-005)); +#5954 = CARTESIAN_POINT('',(-34.75849792,2.59805763461)); +#5955 = CARTESIAN_POINT('',(-32.50849861,1.299019927305)); +#5956 = CARTESIAN_POINT('',(-30.2584993,-1.777999999927E-005)); +#5957 = CARTESIAN_POINT('',(-32.50849861,-1.299055487305)); +#5958 = CARTESIAN_POINT('',(-34.75849792,-2.59809319461)); +#5959 = CARTESIAN_POINT('',(-34.75849792,-1.77800000003E-005)); +#5960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5961 = ORIENTED_EDGE('',*,*,#5906,.F.); +#5962 = ORIENTED_EDGE('',*,*,#5963,.F.); +#5963 = EDGE_CURVE('',#5907,#5907,#5964,.T.); +#5964 = SURFACE_CURVE('',#5965,(#5970,#5977),.PCURVE_S1.); +#5965 = CIRCLE('',#5966,1.49999954); +#5966 = AXIS2_PLACEMENT_3D('',#5967,#5968,#5969); +#5967 = CARTESIAN_POINT('',(33.2940152,2.794,0.E+000)); +#5968 = DIRECTION('',(0.E+000,0.E+000,1.)); +#5969 = DIRECTION('',(1.,0.E+000,0.E+000)); +#5970 = PCURVE('',#5917,#5971); +#5971 = DEFINITIONAL_REPRESENTATION('',(#5972),#5976); +#5972 = LINE('',#5973,#5974); +#5973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#5974 = VECTOR('',#5975,1.); +#5975 = DIRECTION('',(-1.,0.E+000)); +#5976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5977 = PCURVE('',#445,#5978); +#5978 = DEFINITIONAL_REPRESENTATION('',(#5979),#5987); +#5979 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#5980,#5981,#5982,#5983, +#5984,#5985,#5986),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#5980 = CARTESIAN_POINT('',(-34.75849792,-1.77800000003E-005)); +#5981 = CARTESIAN_POINT('',(-34.75849792,2.59805763461)); +#5982 = CARTESIAN_POINT('',(-32.50849861,1.299019927305)); +#5983 = CARTESIAN_POINT('',(-30.2584993,-1.777999999927E-005)); +#5984 = CARTESIAN_POINT('',(-32.50849861,-1.299055487305)); +#5985 = CARTESIAN_POINT('',(-34.75849792,-2.59809319461)); +#5986 = CARTESIAN_POINT('',(-34.75849792,-1.77800000003E-005)); +#5987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#5988 = ADVANCED_FACE('',(#5989),#6003,.F.); +#5989 = FACE_BOUND('',#5990,.T.); +#5990 = EDGE_LOOP('',(#5991,#6021,#6047,#6048)); +#5991 = ORIENTED_EDGE('',*,*,#5992,.T.); +#5992 = EDGE_CURVE('',#5993,#5995,#5997,.T.); +#5993 = VERTEX_POINT('',#5994); +#5994 = CARTESIAN_POINT('',(34.5880436,20.0338436,0.E+000)); +#5995 = VERTEX_POINT('',#5996); +#5996 = CARTESIAN_POINT('',(34.5880436,20.0338436,1.7018)); +#5997 = SEAM_CURVE('',#5998,(#6002,#6014),.PCURVE_S1.); +#5998 = LINE('',#5999,#6000); +#5999 = CARTESIAN_POINT('',(34.5880436,20.0338436,0.E+000)); +#6000 = VECTOR('',#6001,1.); +#6001 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6002 = PCURVE('',#6003,#6008); +#6003 = CYLINDRICAL_SURFACE('',#6004,0.508); +#6004 = AXIS2_PLACEMENT_3D('',#6005,#6006,#6007); +#6005 = CARTESIAN_POINT('',(34.0800436,20.0338436,0.E+000)); #6006 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6007 = DEFINITIONAL_REPRESENTATION('',(#6008),#6012); -#6008 = LINE('',#6009,#6010); -#6009 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6010 = VECTOR('',#6011,1.); -#6011 = DIRECTION('',(1.694065894509E-016,-1.)); -#6012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#6007 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6008 = DEFINITIONAL_REPRESENTATION('',(#6009),#6013); +#6009 = LINE('',#6010,#6011); +#6010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6011 = VECTOR('',#6012,1.); +#6012 = DIRECTION('',(0.E+000,-1.)); +#6013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6013 = ORIENTED_EDGE('',*,*,#6014,.F.); -#6014 = EDGE_CURVE('',#5429,#5987,#6015,.T.); -#6015 = SURFACE_CURVE('',#6016,(#6020,#6027),.PCURVE_S1.); +#6014 = PCURVE('',#6003,#6015); +#6015 = DEFINITIONAL_REPRESENTATION('',(#6016),#6020); #6016 = LINE('',#6017,#6018); -#6017 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); +#6017 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); #6018 = VECTOR('',#6019,1.); -#6019 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6020 = PCURVE('',#5444,#6021); -#6021 = DEFINITIONAL_REPRESENTATION('',(#6022),#6026); -#6022 = LINE('',#6023,#6024); -#6023 = CARTESIAN_POINT('',(-0.76,0.E+000)); -#6024 = VECTOR('',#6025,1.); -#6025 = DIRECTION('',(0.E+000,1.)); -#6026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6027 = PCURVE('',#5470,#6028); -#6028 = DEFINITIONAL_REPRESENTATION('',(#6029),#6033); -#6029 = LINE('',#6030,#6031); -#6030 = CARTESIAN_POINT('',(0.2,0.E+000)); -#6031 = VECTOR('',#6032,1.); -#6032 = DIRECTION('',(0.E+000,1.)); -#6033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6034 = ADVANCED_FACE('',(#6035),#5184,.T.); -#6035 = FACE_BOUND('',#6036,.T.); -#6036 = EDGE_LOOP('',(#6037,#6038,#6061,#6082,#6083,#6104,#6105,#6128)); -#6037 = ORIENTED_EDGE('',*,*,#5599,.T.); -#6038 = ORIENTED_EDGE('',*,*,#6039,.F.); -#6039 = EDGE_CURVE('',#6040,#5572,#6042,.T.); -#6040 = VERTEX_POINT('',#6041); -#6041 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); -#6042 = SURFACE_CURVE('',#6043,(#6047,#6054),.PCURVE_S1.); -#6043 = LINE('',#6044,#6045); -#6044 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); -#6045 = VECTOR('',#6046,1.); -#6046 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6047 = PCURVE('',#5184,#6048); -#6048 = DEFINITIONAL_REPRESENTATION('',(#6049),#6053); -#6049 = LINE('',#6050,#6051); -#6050 = CARTESIAN_POINT('',(-0.76,0.E+000)); -#6051 = VECTOR('',#6052,1.); -#6052 = DIRECTION('',(0.E+000,1.)); -#6053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6054 = PCURVE('',#5587,#6055); -#6055 = DEFINITIONAL_REPRESENTATION('',(#6056),#6060); -#6056 = LINE('',#6057,#6058); -#6057 = CARTESIAN_POINT('',(0.2,0.E+000)); -#6058 = VECTOR('',#6059,1.); -#6059 = DIRECTION('',(0.E+000,1.)); -#6060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6061 = ORIENTED_EDGE('',*,*,#6062,.T.); -#6062 = EDGE_CURVE('',#6040,#5230,#6063,.T.); -#6063 = SURFACE_CURVE('',#6064,(#6068,#6075),.PCURVE_S1.); -#6064 = LINE('',#6065,#6066); -#6065 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); -#6066 = VECTOR('',#6067,1.); -#6067 = DIRECTION('',(-1.,0.E+000,-1.694065894509E-016)); -#6068 = PCURVE('',#5184,#6069); -#6069 = DEFINITIONAL_REPRESENTATION('',(#6070),#6074); -#6070 = LINE('',#6071,#6072); -#6071 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#6072 = VECTOR('',#6073,1.); -#6073 = DIRECTION('',(1.,0.E+000)); -#6074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6075 = PCURVE('',#5268,#6076); -#6076 = DEFINITIONAL_REPRESENTATION('',(#6077),#6081); -#6077 = LINE('',#6078,#6079); -#6078 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6079 = VECTOR('',#6080,1.); -#6080 = DIRECTION('',(1.694065894509E-016,-1.)); -#6081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6082 = ORIENTED_EDGE('',*,*,#5229,.T.); -#6083 = ORIENTED_EDGE('',*,*,#6084,.F.); -#6084 = EDGE_CURVE('',#5080,#5200,#6085,.T.); -#6085 = SURFACE_CURVE('',#6086,(#6090,#6097),.PCURVE_S1.); -#6086 = LINE('',#6087,#6088); -#6087 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); -#6088 = VECTOR('',#6089,1.); -#6089 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6090 = PCURVE('',#5184,#6091); -#6091 = DEFINITIONAL_REPRESENTATION('',(#6092),#6096); -#6092 = LINE('',#6093,#6094); -#6093 = CARTESIAN_POINT('',(0.E+000,5.E-003)); -#6094 = VECTOR('',#6095,1.); -#6095 = DIRECTION('',(-1.,0.E+000)); -#6096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6097 = PCURVE('',#5102,#6098); -#6098 = DEFINITIONAL_REPRESENTATION('',(#6099),#6103); -#6099 = LINE('',#6100,#6101); -#6100 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6101 = VECTOR('',#6102,1.); -#6102 = DIRECTION('',(0.E+000,1.)); -#6103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6104 = ORIENTED_EDGE('',*,*,#5170,.F.); -#6105 = ORIENTED_EDGE('',*,*,#6106,.T.); -#6106 = EDGE_CURVE('',#5143,#6107,#6109,.T.); -#6107 = VERTEX_POINT('',#6108); -#6108 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); -#6109 = SURFACE_CURVE('',#6110,(#6114,#6121),.PCURVE_S1.); -#6110 = LINE('',#6111,#6112); -#6111 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); -#6112 = VECTOR('',#6113,1.); -#6113 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); -#6114 = PCURVE('',#5184,#6115); -#6115 = DEFINITIONAL_REPRESENTATION('',(#6116),#6120); -#6116 = LINE('',#6117,#6118); -#6117 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6118 = VECTOR('',#6119,1.); -#6119 = DIRECTION('',(1.,0.E+000)); -#6120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6121 = PCURVE('',#5158,#6122); -#6122 = DEFINITIONAL_REPRESENTATION('',(#6123),#6127); -#6123 = LINE('',#6124,#6125); -#6124 = CARTESIAN_POINT('',(-4.E-002,0.2)); -#6125 = VECTOR('',#6126,1.); -#6126 = DIRECTION('',(1.694065894509E-016,-1.)); -#6127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6128 = ORIENTED_EDGE('',*,*,#6129,.T.); -#6129 = EDGE_CURVE('',#6107,#5600,#6130,.T.); -#6130 = SURFACE_CURVE('',#6131,(#6135,#6142),.PCURVE_S1.); -#6131 = LINE('',#6132,#6133); -#6132 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); -#6133 = VECTOR('',#6134,1.); -#6134 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6135 = PCURVE('',#5184,#6136); -#6136 = DEFINITIONAL_REPRESENTATION('',(#6137),#6141); -#6137 = LINE('',#6138,#6139); -#6138 = CARTESIAN_POINT('',(0.16,0.E+000)); -#6139 = VECTOR('',#6140,1.); -#6140 = DIRECTION('',(0.E+000,1.)); -#6141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6142 = PCURVE('',#5636,#6143); +#6019 = DIRECTION('',(0.E+000,-1.)); +#6020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6021 = ORIENTED_EDGE('',*,*,#6022,.T.); +#6022 = EDGE_CURVE('',#5995,#5995,#6023,.T.); +#6023 = SURFACE_CURVE('',#6024,(#6029,#6036),.PCURVE_S1.); +#6024 = CIRCLE('',#6025,0.508); +#6025 = AXIS2_PLACEMENT_3D('',#6026,#6027,#6028); +#6026 = CARTESIAN_POINT('',(34.0800436,20.0338436,1.7018)); +#6027 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6028 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6029 = PCURVE('',#6003,#6030); +#6030 = DEFINITIONAL_REPRESENTATION('',(#6031),#6035); +#6031 = LINE('',#6032,#6033); +#6032 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6033 = VECTOR('',#6034,1.); +#6034 = DIRECTION('',(-1.,0.E+000)); +#6035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6036 = PCURVE('',#391,#6037); +#6037 = DEFINITIONAL_REPRESENTATION('',(#6038),#6046); +#6038 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6039,#6040,#6041,#6042, +#6043,#6044,#6045),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6039 = CARTESIAN_POINT('',(-34.55252678,17.23982582)); +#6040 = CARTESIAN_POINT('',(-34.55252678,18.119707630245)); +#6041 = CARTESIAN_POINT('',(-33.79052678,17.679766725122)); +#6042 = CARTESIAN_POINT('',(-33.02852678,17.23982582)); +#6043 = CARTESIAN_POINT('',(-33.79052678,16.799884914878)); +#6044 = CARTESIAN_POINT('',(-34.55252678,16.359944009755)); +#6045 = CARTESIAN_POINT('',(-34.55252678,17.23982582)); +#6046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6047 = ORIENTED_EDGE('',*,*,#5992,.F.); +#6048 = ORIENTED_EDGE('',*,*,#6049,.F.); +#6049 = EDGE_CURVE('',#5993,#5993,#6050,.T.); +#6050 = SURFACE_CURVE('',#6051,(#6056,#6063),.PCURVE_S1.); +#6051 = CIRCLE('',#6052,0.508); +#6052 = AXIS2_PLACEMENT_3D('',#6053,#6054,#6055); +#6053 = CARTESIAN_POINT('',(34.0800436,20.0338436,0.E+000)); +#6054 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6055 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6056 = PCURVE('',#6003,#6057); +#6057 = DEFINITIONAL_REPRESENTATION('',(#6058),#6062); +#6058 = LINE('',#6059,#6060); +#6059 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6060 = VECTOR('',#6061,1.); +#6061 = DIRECTION('',(-1.,0.E+000)); +#6062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6063 = PCURVE('',#445,#6064); +#6064 = DEFINITIONAL_REPRESENTATION('',(#6065),#6073); +#6065 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6066,#6067,#6068,#6069, +#6070,#6071,#6072),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6066 = CARTESIAN_POINT('',(-34.55252678,17.23982582)); +#6067 = CARTESIAN_POINT('',(-34.55252678,18.119707630245)); +#6068 = CARTESIAN_POINT('',(-33.79052678,17.679766725122)); +#6069 = CARTESIAN_POINT('',(-33.02852678,17.23982582)); +#6070 = CARTESIAN_POINT('',(-33.79052678,16.799884914878)); +#6071 = CARTESIAN_POINT('',(-34.55252678,16.359944009755)); +#6072 = CARTESIAN_POINT('',(-34.55252678,17.23982582)); +#6073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6074 = ADVANCED_FACE('',(#6075),#6089,.F.); +#6075 = FACE_BOUND('',#6076,.T.); +#6076 = EDGE_LOOP('',(#6077,#6107,#6133,#6134)); +#6077 = ORIENTED_EDGE('',*,*,#6078,.T.); +#6078 = EDGE_CURVE('',#6079,#6081,#6083,.T.); +#6079 = VERTEX_POINT('',#6080); +#6080 = CARTESIAN_POINT('',(34.5880436,17.4938436,0.E+000)); +#6081 = VERTEX_POINT('',#6082); +#6082 = CARTESIAN_POINT('',(34.5880436,17.4938436,1.7018)); +#6083 = SEAM_CURVE('',#6084,(#6088,#6100),.PCURVE_S1.); +#6084 = LINE('',#6085,#6086); +#6085 = CARTESIAN_POINT('',(34.5880436,17.4938436,0.E+000)); +#6086 = VECTOR('',#6087,1.); +#6087 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6088 = PCURVE('',#6089,#6094); +#6089 = CYLINDRICAL_SURFACE('',#6090,0.508); +#6090 = AXIS2_PLACEMENT_3D('',#6091,#6092,#6093); +#6091 = CARTESIAN_POINT('',(34.0800436,17.4938436,0.E+000)); +#6092 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6093 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6094 = DEFINITIONAL_REPRESENTATION('',(#6095),#6099); +#6095 = LINE('',#6096,#6097); +#6096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6097 = VECTOR('',#6098,1.); +#6098 = DIRECTION('',(0.E+000,-1.)); +#6099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6100 = PCURVE('',#6089,#6101); +#6101 = DEFINITIONAL_REPRESENTATION('',(#6102),#6106); +#6102 = LINE('',#6103,#6104); +#6103 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6104 = VECTOR('',#6105,1.); +#6105 = DIRECTION('',(0.E+000,-1.)); +#6106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6107 = ORIENTED_EDGE('',*,*,#6108,.T.); +#6108 = EDGE_CURVE('',#6081,#6081,#6109,.T.); +#6109 = SURFACE_CURVE('',#6110,(#6115,#6122),.PCURVE_S1.); +#6110 = CIRCLE('',#6111,0.508); +#6111 = AXIS2_PLACEMENT_3D('',#6112,#6113,#6114); +#6112 = CARTESIAN_POINT('',(34.0800436,17.4938436,1.7018)); +#6113 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6114 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6115 = PCURVE('',#6089,#6116); +#6116 = DEFINITIONAL_REPRESENTATION('',(#6117),#6121); +#6117 = LINE('',#6118,#6119); +#6118 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6119 = VECTOR('',#6120,1.); +#6120 = DIRECTION('',(-1.,0.E+000)); +#6121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6122 = PCURVE('',#391,#6123); +#6123 = DEFINITIONAL_REPRESENTATION('',(#6124),#6132); +#6124 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6125,#6126,#6127,#6128, +#6129,#6130,#6131),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6125 = CARTESIAN_POINT('',(-34.55252678,14.69982582)); +#6126 = CARTESIAN_POINT('',(-34.55252678,15.579707630245)); +#6127 = CARTESIAN_POINT('',(-33.79052678,15.139766725122)); +#6128 = CARTESIAN_POINT('',(-33.02852678,14.69982582)); +#6129 = CARTESIAN_POINT('',(-33.79052678,14.259884914877)); +#6130 = CARTESIAN_POINT('',(-34.55252678,13.819944009755)); +#6131 = CARTESIAN_POINT('',(-34.55252678,14.69982582)); +#6132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6133 = ORIENTED_EDGE('',*,*,#6078,.F.); +#6134 = ORIENTED_EDGE('',*,*,#6135,.F.); +#6135 = EDGE_CURVE('',#6079,#6079,#6136,.T.); +#6136 = SURFACE_CURVE('',#6137,(#6142,#6149),.PCURVE_S1.); +#6137 = CIRCLE('',#6138,0.508); +#6138 = AXIS2_PLACEMENT_3D('',#6139,#6140,#6141); +#6139 = CARTESIAN_POINT('',(34.0800436,17.4938436,0.E+000)); +#6140 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6141 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6142 = PCURVE('',#6089,#6143); #6143 = DEFINITIONAL_REPRESENTATION('',(#6144),#6148); #6144 = LINE('',#6145,#6146); -#6145 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#6145 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #6146 = VECTOR('',#6147,1.); -#6147 = DIRECTION('',(0.E+000,1.)); +#6147 = DIRECTION('',(-1.,0.E+000)); #6148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6149 = ADVANCED_FACE('',(#6150),#5416,.T.); -#6150 = FACE_BOUND('',#6151,.T.); -#6151 = EDGE_LOOP('',(#6152,#6153,#6154,#6175)); -#6152 = ORIENTED_EDGE('',*,*,#5400,.T.); -#6153 = ORIENTED_EDGE('',*,*,#5760,.T.); -#6154 = ORIENTED_EDGE('',*,*,#6155,.F.); -#6155 = EDGE_CURVE('',#5857,#5733,#6156,.T.); -#6156 = SURFACE_CURVE('',#6157,(#6161,#6168),.PCURVE_S1.); -#6157 = LINE('',#6158,#6159); -#6158 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); -#6159 = VECTOR('',#6160,1.); -#6160 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6161 = PCURVE('',#5416,#6162); -#6162 = DEFINITIONAL_REPRESENTATION('',(#6163),#6167); -#6163 = LINE('',#6164,#6165); -#6164 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6165 = VECTOR('',#6166,1.); -#6166 = DIRECTION('',(1.,0.E+000)); -#6167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6168 = PCURVE('',#5748,#6169); -#6169 = DEFINITIONAL_REPRESENTATION('',(#6170),#6174); +#6149 = PCURVE('',#445,#6150); +#6150 = DEFINITIONAL_REPRESENTATION('',(#6151),#6159); +#6151 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6152,#6153,#6154,#6155, +#6156,#6157,#6158),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6152 = CARTESIAN_POINT('',(-34.55252678,14.69982582)); +#6153 = CARTESIAN_POINT('',(-34.55252678,15.579707630245)); +#6154 = CARTESIAN_POINT('',(-33.79052678,15.139766725122)); +#6155 = CARTESIAN_POINT('',(-33.02852678,14.69982582)); +#6156 = CARTESIAN_POINT('',(-33.79052678,14.259884914877)); +#6157 = CARTESIAN_POINT('',(-34.55252678,13.819944009755)); +#6158 = CARTESIAN_POINT('',(-34.55252678,14.69982582)); +#6159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6160 = ADVANCED_FACE('',(#6161),#6175,.F.); +#6161 = FACE_BOUND('',#6162,.T.); +#6162 = EDGE_LOOP('',(#6163,#6193,#6219,#6220)); +#6163 = ORIENTED_EDGE('',*,*,#6164,.T.); +#6164 = EDGE_CURVE('',#6165,#6167,#6169,.T.); +#6165 = VERTEX_POINT('',#6166); +#6166 = CARTESIAN_POINT('',(32.0480436,22.5738436,0.E+000)); +#6167 = VERTEX_POINT('',#6168); +#6168 = CARTESIAN_POINT('',(32.0480436,22.5738436,1.7018)); +#6169 = SEAM_CURVE('',#6170,(#6174,#6186),.PCURVE_S1.); #6170 = LINE('',#6171,#6172); -#6171 = CARTESIAN_POINT('',(-0.24,4.E-002)); +#6171 = CARTESIAN_POINT('',(32.0480436,22.5738436,0.E+000)); #6172 = VECTOR('',#6173,1.); -#6173 = DIRECTION('',(-1.,0.E+000)); -#6174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6175 = ORIENTED_EDGE('',*,*,#5856,.F.); -#6176 = ADVANCED_FACE('',(#6177),#5636,.T.); -#6177 = FACE_BOUND('',#6178,.T.); -#6178 = EDGE_LOOP('',(#6179,#6180,#6181,#6202)); -#6179 = ORIENTED_EDGE('',*,*,#5622,.F.); -#6180 = ORIENTED_EDGE('',*,*,#6129,.F.); -#6181 = ORIENTED_EDGE('',*,*,#6182,.T.); -#6182 = EDGE_CURVE('',#6107,#5786,#6183,.T.); -#6183 = SURFACE_CURVE('',#6184,(#6188,#6195),.PCURVE_S1.); -#6184 = LINE('',#6185,#6186); -#6185 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); -#6186 = VECTOR('',#6187,1.); -#6187 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6188 = PCURVE('',#5636,#6189); -#6189 = DEFINITIONAL_REPRESENTATION('',(#6190),#6194); -#6190 = LINE('',#6191,#6192); -#6191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6192 = VECTOR('',#6193,1.); -#6193 = DIRECTION('',(1.,0.E+000)); -#6194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6195 = PCURVE('',#5158,#6196); -#6196 = DEFINITIONAL_REPRESENTATION('',(#6197),#6201); -#6197 = LINE('',#6198,#6199); -#6198 = CARTESIAN_POINT('',(-0.24,4.E-002)); -#6199 = VECTOR('',#6200,1.); -#6200 = DIRECTION('',(-1.,0.E+000)); -#6201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6202 = ORIENTED_EDGE('',*,*,#5785,.T.); -#6203 = ADVANCED_FACE('',(#6204),#6218,.T.); -#6204 = FACE_BOUND('',#6205,.T.); -#6205 = EDGE_LOOP('',(#6206,#6236,#6259,#6287)); -#6206 = ORIENTED_EDGE('',*,*,#6207,.T.); -#6207 = EDGE_CURVE('',#6208,#6210,#6212,.T.); -#6208 = VERTEX_POINT('',#6209); -#6209 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); -#6210 = VERTEX_POINT('',#6211); -#6211 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); -#6212 = SURFACE_CURVE('',#6213,(#6217,#6229),.PCURVE_S1.); -#6213 = LINE('',#6214,#6215); -#6214 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); -#6215 = VECTOR('',#6216,1.); -#6216 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6217 = PCURVE('',#6218,#6223); -#6218 = PLANE('',#6219); -#6219 = AXIS2_PLACEMENT_3D('',#6220,#6221,#6222); -#6220 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6221 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6222 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6223 = DEFINITIONAL_REPRESENTATION('',(#6224),#6228); -#6224 = LINE('',#6225,#6226); -#6225 = CARTESIAN_POINT('',(0.28,0.E+000)); -#6226 = VECTOR('',#6227,1.); -#6227 = DIRECTION('',(0.E+000,1.)); -#6228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6229 = PCURVE('',#5130,#6230); -#6230 = DEFINITIONAL_REPRESENTATION('',(#6231),#6235); -#6231 = LINE('',#6232,#6233); -#6232 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6233 = VECTOR('',#6234,1.); -#6234 = DIRECTION('',(0.E+000,1.)); -#6235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6236 = ORIENTED_EDGE('',*,*,#6237,.F.); -#6237 = EDGE_CURVE('',#6238,#6210,#6240,.T.); -#6238 = VERTEX_POINT('',#6239); -#6239 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); -#6240 = SURFACE_CURVE('',#6241,(#6245,#6252),.PCURVE_S1.); -#6241 = LINE('',#6242,#6243); -#6242 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); -#6243 = VECTOR('',#6244,1.); -#6244 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6245 = PCURVE('',#6218,#6246); -#6246 = DEFINITIONAL_REPRESENTATION('',(#6247),#6251); -#6247 = LINE('',#6248,#6249); -#6248 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6249 = VECTOR('',#6250,1.); -#6250 = DIRECTION('',(1.,0.E+000)); -#6251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6252 = PCURVE('',#5748,#6253); -#6253 = DEFINITIONAL_REPRESENTATION('',(#6254),#6258); -#6254 = LINE('',#6255,#6256); -#6255 = CARTESIAN_POINT('',(-0.28,0.E+000)); -#6256 = VECTOR('',#6257,1.); -#6257 = DIRECTION('',(1.,0.E+000)); -#6258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6259 = ORIENTED_EDGE('',*,*,#6260,.F.); -#6260 = EDGE_CURVE('',#6261,#6238,#6263,.T.); -#6261 = VERTEX_POINT('',#6262); -#6262 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6263 = SURFACE_CURVE('',#6264,(#6268,#6275),.PCURVE_S1.); -#6264 = LINE('',#6265,#6266); -#6265 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6266 = VECTOR('',#6267,1.); -#6267 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6268 = PCURVE('',#6218,#6269); -#6269 = DEFINITIONAL_REPRESENTATION('',(#6270),#6274); -#6270 = LINE('',#6271,#6272); -#6271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6272 = VECTOR('',#6273,1.); -#6273 = DIRECTION('',(0.E+000,1.)); -#6274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6275 = PCURVE('',#6276,#6281); -#6276 = PLANE('',#6277); -#6277 = AXIS2_PLACEMENT_3D('',#6278,#6279,#6280); -#6278 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6279 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6280 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6281 = DEFINITIONAL_REPRESENTATION('',(#6282),#6286); -#6282 = LINE('',#6283,#6284); -#6283 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6284 = VECTOR('',#6285,1.); -#6285 = DIRECTION('',(0.E+000,1.)); -#6286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6287 = ORIENTED_EDGE('',*,*,#6288,.T.); -#6288 = EDGE_CURVE('',#6261,#6208,#6289,.T.); -#6289 = SURFACE_CURVE('',#6290,(#6294,#6301),.PCURVE_S1.); -#6290 = LINE('',#6291,#6292); -#6291 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6292 = VECTOR('',#6293,1.); -#6293 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6294 = PCURVE('',#6218,#6295); -#6295 = DEFINITIONAL_REPRESENTATION('',(#6296),#6300); -#6296 = LINE('',#6297,#6298); -#6297 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6298 = VECTOR('',#6299,1.); -#6299 = DIRECTION('',(1.,0.E+000)); -#6300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6301 = PCURVE('',#5158,#6302); -#6302 = DEFINITIONAL_REPRESENTATION('',(#6303),#6307); -#6303 = LINE('',#6304,#6305); -#6304 = CARTESIAN_POINT('',(-0.28,0.E+000)); -#6305 = VECTOR('',#6306,1.); -#6306 = DIRECTION('',(1.,0.E+000)); -#6307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6308 = ADVANCED_FACE('',(#6309),#6276,.T.); -#6309 = FACE_BOUND('',#6310,.T.); -#6310 = EDGE_LOOP('',(#6311,#6312,#6335,#6358)); -#6311 = ORIENTED_EDGE('',*,*,#6260,.T.); -#6312 = ORIENTED_EDGE('',*,*,#6313,.F.); -#6313 = EDGE_CURVE('',#6314,#6238,#6316,.T.); -#6314 = VERTEX_POINT('',#6315); -#6315 = CARTESIAN_POINT('',(-0.3,0.25,0.E+000)); -#6316 = SURFACE_CURVE('',#6317,(#6321,#6328),.PCURVE_S1.); -#6317 = LINE('',#6318,#6319); -#6318 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); -#6319 = VECTOR('',#6320,1.); -#6320 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6321 = PCURVE('',#6276,#6322); -#6322 = DEFINITIONAL_REPRESENTATION('',(#6323),#6327); -#6323 = LINE('',#6324,#6325); -#6324 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6325 = VECTOR('',#6326,1.); -#6326 = DIRECTION('',(1.,0.E+000)); -#6327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6328 = PCURVE('',#5748,#6329); -#6329 = DEFINITIONAL_REPRESENTATION('',(#6330),#6334); -#6330 = LINE('',#6331,#6332); -#6331 = CARTESIAN_POINT('',(-0.28,0.E+000)); -#6332 = VECTOR('',#6333,1.); -#6333 = DIRECTION('',(0.E+000,-1.)); -#6334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6335 = ORIENTED_EDGE('',*,*,#6336,.F.); -#6336 = EDGE_CURVE('',#6337,#6314,#6339,.T.); +#6173 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6174 = PCURVE('',#6175,#6180); +#6175 = CYLINDRICAL_SURFACE('',#6176,0.508); +#6176 = AXIS2_PLACEMENT_3D('',#6177,#6178,#6179); +#6177 = CARTESIAN_POINT('',(31.5400436,22.5738436,0.E+000)); +#6178 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6179 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6180 = DEFINITIONAL_REPRESENTATION('',(#6181),#6185); +#6181 = LINE('',#6182,#6183); +#6182 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6183 = VECTOR('',#6184,1.); +#6184 = DIRECTION('',(0.E+000,-1.)); +#6185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6186 = PCURVE('',#6175,#6187); +#6187 = DEFINITIONAL_REPRESENTATION('',(#6188),#6192); +#6188 = LINE('',#6189,#6190); +#6189 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6190 = VECTOR('',#6191,1.); +#6191 = DIRECTION('',(0.E+000,-1.)); +#6192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6193 = ORIENTED_EDGE('',*,*,#6194,.T.); +#6194 = EDGE_CURVE('',#6167,#6167,#6195,.T.); +#6195 = SURFACE_CURVE('',#6196,(#6201,#6208),.PCURVE_S1.); +#6196 = CIRCLE('',#6197,0.508); +#6197 = AXIS2_PLACEMENT_3D('',#6198,#6199,#6200); +#6198 = CARTESIAN_POINT('',(31.5400436,22.5738436,1.7018)); +#6199 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6200 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6201 = PCURVE('',#6175,#6202); +#6202 = DEFINITIONAL_REPRESENTATION('',(#6203),#6207); +#6203 = LINE('',#6204,#6205); +#6204 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6205 = VECTOR('',#6206,1.); +#6206 = DIRECTION('',(-1.,0.E+000)); +#6207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6208 = PCURVE('',#391,#6209); +#6209 = DEFINITIONAL_REPRESENTATION('',(#6210),#6218); +#6210 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6211,#6212,#6213,#6214, +#6215,#6216,#6217),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6211 = CARTESIAN_POINT('',(-32.01252678,19.77982582)); +#6212 = CARTESIAN_POINT('',(-32.01252678,20.659707630245)); +#6213 = CARTESIAN_POINT('',(-31.25052678,20.219766725123)); +#6214 = CARTESIAN_POINT('',(-30.48852678,19.77982582)); +#6215 = CARTESIAN_POINT('',(-31.25052678,19.339884914878)); +#6216 = CARTESIAN_POINT('',(-32.01252678,18.899944009755)); +#6217 = CARTESIAN_POINT('',(-32.01252678,19.77982582)); +#6218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6219 = ORIENTED_EDGE('',*,*,#6164,.F.); +#6220 = ORIENTED_EDGE('',*,*,#6221,.F.); +#6221 = EDGE_CURVE('',#6165,#6165,#6222,.T.); +#6222 = SURFACE_CURVE('',#6223,(#6228,#6235),.PCURVE_S1.); +#6223 = CIRCLE('',#6224,0.508); +#6224 = AXIS2_PLACEMENT_3D('',#6225,#6226,#6227); +#6225 = CARTESIAN_POINT('',(31.5400436,22.5738436,0.E+000)); +#6226 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6227 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6228 = PCURVE('',#6175,#6229); +#6229 = DEFINITIONAL_REPRESENTATION('',(#6230),#6234); +#6230 = LINE('',#6231,#6232); +#6231 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6232 = VECTOR('',#6233,1.); +#6233 = DIRECTION('',(-1.,0.E+000)); +#6234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6235 = PCURVE('',#445,#6236); +#6236 = DEFINITIONAL_REPRESENTATION('',(#6237),#6245); +#6237 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6238,#6239,#6240,#6241, +#6242,#6243,#6244),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6238 = CARTESIAN_POINT('',(-32.01252678,19.77982582)); +#6239 = CARTESIAN_POINT('',(-32.01252678,20.659707630245)); +#6240 = CARTESIAN_POINT('',(-31.25052678,20.219766725123)); +#6241 = CARTESIAN_POINT('',(-30.48852678,19.77982582)); +#6242 = CARTESIAN_POINT('',(-31.25052678,19.339884914878)); +#6243 = CARTESIAN_POINT('',(-32.01252678,18.899944009755)); +#6244 = CARTESIAN_POINT('',(-32.01252678,19.77982582)); +#6245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6246 = ADVANCED_FACE('',(#6247),#6261,.F.); +#6247 = FACE_BOUND('',#6248,.T.); +#6248 = EDGE_LOOP('',(#6249,#6279,#6305,#6306)); +#6249 = ORIENTED_EDGE('',*,*,#6250,.T.); +#6250 = EDGE_CURVE('',#6251,#6253,#6255,.T.); +#6251 = VERTEX_POINT('',#6252); +#6252 = CARTESIAN_POINT('',(32.0480436,27.6538436,0.E+000)); +#6253 = VERTEX_POINT('',#6254); +#6254 = CARTESIAN_POINT('',(32.0480436,27.6538436,1.7018)); +#6255 = SEAM_CURVE('',#6256,(#6260,#6272),.PCURVE_S1.); +#6256 = LINE('',#6257,#6258); +#6257 = CARTESIAN_POINT('',(32.0480436,27.6538436,0.E+000)); +#6258 = VECTOR('',#6259,1.); +#6259 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6260 = PCURVE('',#6261,#6266); +#6261 = CYLINDRICAL_SURFACE('',#6262,0.508); +#6262 = AXIS2_PLACEMENT_3D('',#6263,#6264,#6265); +#6263 = CARTESIAN_POINT('',(31.5400436,27.6538436,0.E+000)); +#6264 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6265 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6266 = DEFINITIONAL_REPRESENTATION('',(#6267),#6271); +#6267 = LINE('',#6268,#6269); +#6268 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6269 = VECTOR('',#6270,1.); +#6270 = DIRECTION('',(0.E+000,-1.)); +#6271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6272 = PCURVE('',#6261,#6273); +#6273 = DEFINITIONAL_REPRESENTATION('',(#6274),#6278); +#6274 = LINE('',#6275,#6276); +#6275 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6276 = VECTOR('',#6277,1.); +#6277 = DIRECTION('',(0.E+000,-1.)); +#6278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6279 = ORIENTED_EDGE('',*,*,#6280,.T.); +#6280 = EDGE_CURVE('',#6253,#6253,#6281,.T.); +#6281 = SURFACE_CURVE('',#6282,(#6287,#6294),.PCURVE_S1.); +#6282 = CIRCLE('',#6283,0.508); +#6283 = AXIS2_PLACEMENT_3D('',#6284,#6285,#6286); +#6284 = CARTESIAN_POINT('',(31.5400436,27.6538436,1.7018)); +#6285 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6286 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6287 = PCURVE('',#6261,#6288); +#6288 = DEFINITIONAL_REPRESENTATION('',(#6289),#6293); +#6289 = LINE('',#6290,#6291); +#6290 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6291 = VECTOR('',#6292,1.); +#6292 = DIRECTION('',(-1.,0.E+000)); +#6293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6294 = PCURVE('',#391,#6295); +#6295 = DEFINITIONAL_REPRESENTATION('',(#6296),#6304); +#6296 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6297,#6298,#6299,#6300, +#6301,#6302,#6303),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6297 = CARTESIAN_POINT('',(-32.01252678,24.85982582)); +#6298 = CARTESIAN_POINT('',(-32.01252678,25.739707630245)); +#6299 = CARTESIAN_POINT('',(-31.25052678,25.299766725123)); +#6300 = CARTESIAN_POINT('',(-30.48852678,24.85982582)); +#6301 = CARTESIAN_POINT('',(-31.25052678,24.419884914878)); +#6302 = CARTESIAN_POINT('',(-32.01252678,23.979944009755)); +#6303 = CARTESIAN_POINT('',(-32.01252678,24.85982582)); +#6304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6305 = ORIENTED_EDGE('',*,*,#6250,.F.); +#6306 = ORIENTED_EDGE('',*,*,#6307,.F.); +#6307 = EDGE_CURVE('',#6251,#6251,#6308,.T.); +#6308 = SURFACE_CURVE('',#6309,(#6314,#6321),.PCURVE_S1.); +#6309 = CIRCLE('',#6310,0.508); +#6310 = AXIS2_PLACEMENT_3D('',#6311,#6312,#6313); +#6311 = CARTESIAN_POINT('',(31.5400436,27.6538436,0.E+000)); +#6312 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6313 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6314 = PCURVE('',#6261,#6315); +#6315 = DEFINITIONAL_REPRESENTATION('',(#6316),#6320); +#6316 = LINE('',#6317,#6318); +#6317 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6318 = VECTOR('',#6319,1.); +#6319 = DIRECTION('',(-1.,0.E+000)); +#6320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6321 = PCURVE('',#445,#6322); +#6322 = DEFINITIONAL_REPRESENTATION('',(#6323),#6331); +#6323 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6324,#6325,#6326,#6327, +#6328,#6329,#6330),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6324 = CARTESIAN_POINT('',(-32.01252678,24.85982582)); +#6325 = CARTESIAN_POINT('',(-32.01252678,25.739707630245)); +#6326 = CARTESIAN_POINT('',(-31.25052678,25.299766725123)); +#6327 = CARTESIAN_POINT('',(-30.48852678,24.85982582)); +#6328 = CARTESIAN_POINT('',(-31.25052678,24.419884914878)); +#6329 = CARTESIAN_POINT('',(-32.01252678,23.979944009755)); +#6330 = CARTESIAN_POINT('',(-32.01252678,24.85982582)); +#6331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6332 = ADVANCED_FACE('',(#6333),#6347,.F.); +#6333 = FACE_BOUND('',#6334,.T.); +#6334 = EDGE_LOOP('',(#6335,#6365,#6391,#6392)); +#6335 = ORIENTED_EDGE('',*,*,#6336,.T.); +#6336 = EDGE_CURVE('',#6337,#6339,#6341,.T.); #6337 = VERTEX_POINT('',#6338); -#6338 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); -#6339 = SURFACE_CURVE('',#6340,(#6344,#6351),.PCURVE_S1.); -#6340 = LINE('',#6341,#6342); -#6341 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); -#6342 = VECTOR('',#6343,1.); -#6343 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6344 = PCURVE('',#6276,#6345); -#6345 = DEFINITIONAL_REPRESENTATION('',(#6346),#6350); -#6346 = LINE('',#6347,#6348); -#6347 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#6348 = VECTOR('',#6349,1.); -#6349 = DIRECTION('',(0.E+000,1.)); -#6350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6351 = PCURVE('',#5693,#6352); +#6338 = CARTESIAN_POINT('',(32.0480436,25.1138436,0.E+000)); +#6339 = VERTEX_POINT('',#6340); +#6340 = CARTESIAN_POINT('',(32.0480436,25.1138436,1.7018)); +#6341 = SEAM_CURVE('',#6342,(#6346,#6358),.PCURVE_S1.); +#6342 = LINE('',#6343,#6344); +#6343 = CARTESIAN_POINT('',(32.0480436,25.1138436,0.E+000)); +#6344 = VECTOR('',#6345,1.); +#6345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6346 = PCURVE('',#6347,#6352); +#6347 = CYLINDRICAL_SURFACE('',#6348,0.508); +#6348 = AXIS2_PLACEMENT_3D('',#6349,#6350,#6351); +#6349 = CARTESIAN_POINT('',(31.5400436,25.1138436,0.E+000)); +#6350 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6351 = DIRECTION('',(1.,0.E+000,0.E+000)); #6352 = DEFINITIONAL_REPRESENTATION('',(#6353),#6357); #6353 = LINE('',#6354,#6355); #6354 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #6355 = VECTOR('',#6356,1.); -#6356 = DIRECTION('',(0.E+000,1.)); +#6356 = DIRECTION('',(0.E+000,-1.)); #6357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6358 = ORIENTED_EDGE('',*,*,#6359,.T.); -#6359 = EDGE_CURVE('',#6337,#6261,#6360,.T.); -#6360 = SURFACE_CURVE('',#6361,(#6365,#6372),.PCURVE_S1.); -#6361 = LINE('',#6362,#6363); -#6362 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); -#6363 = VECTOR('',#6364,1.); -#6364 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6365 = PCURVE('',#6276,#6366); -#6366 = DEFINITIONAL_REPRESENTATION('',(#6367),#6371); -#6367 = LINE('',#6368,#6369); -#6368 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6369 = VECTOR('',#6370,1.); -#6370 = DIRECTION('',(1.,0.E+000)); -#6371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6372 = PCURVE('',#5158,#6373); -#6373 = DEFINITIONAL_REPRESENTATION('',(#6374),#6378); -#6374 = LINE('',#6375,#6376); -#6375 = CARTESIAN_POINT('',(-0.28,0.E+000)); -#6376 = VECTOR('',#6377,1.); -#6377 = DIRECTION('',(0.E+000,-1.)); -#6378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6379 = ADVANCED_FACE('',(#6380),#5693,.T.); -#6380 = FACE_BOUND('',#6381,.T.); -#6381 = EDGE_LOOP('',(#6382,#6383,#6404,#6405,#6406,#6407)); -#6382 = ORIENTED_EDGE('',*,*,#6336,.T.); -#6383 = ORIENTED_EDGE('',*,*,#6384,.F.); -#6384 = EDGE_CURVE('',#5710,#6314,#6385,.T.); -#6385 = SURFACE_CURVE('',#6386,(#6390,#6397),.PCURVE_S1.); -#6386 = LINE('',#6387,#6388); -#6387 = CARTESIAN_POINT('',(-0.3,0.25,0.E+000)); -#6388 = VECTOR('',#6389,1.); -#6389 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6390 = PCURVE('',#5693,#6391); -#6391 = DEFINITIONAL_REPRESENTATION('',(#6392),#6396); -#6392 = LINE('',#6393,#6394); -#6393 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6394 = VECTOR('',#6395,1.); -#6395 = DIRECTION('',(1.,0.E+000)); -#6396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6397 = PCURVE('',#5748,#6398); -#6398 = DEFINITIONAL_REPRESENTATION('',(#6399),#6403); -#6399 = LINE('',#6400,#6401); -#6400 = CARTESIAN_POINT('',(-0.28,0.2)); -#6401 = VECTOR('',#6402,1.); -#6402 = DIRECTION('',(-1.,0.E+000)); -#6403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6404 = ORIENTED_EDGE('',*,*,#5709,.F.); -#6405 = ORIENTED_EDGE('',*,*,#5679,.F.); -#6406 = ORIENTED_EDGE('',*,*,#5831,.F.); -#6407 = ORIENTED_EDGE('',*,*,#6408,.T.); -#6408 = EDGE_CURVE('',#5809,#6337,#6409,.T.); -#6409 = SURFACE_CURVE('',#6410,(#6414,#6421),.PCURVE_S1.); -#6410 = LINE('',#6411,#6412); -#6411 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); -#6412 = VECTOR('',#6413,1.); -#6413 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6414 = PCURVE('',#5693,#6415); -#6415 = DEFINITIONAL_REPRESENTATION('',(#6416),#6420); -#6416 = LINE('',#6417,#6418); -#6417 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6418 = VECTOR('',#6419,1.); -#6419 = DIRECTION('',(1.,0.E+000)); -#6420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6421 = PCURVE('',#5158,#6422); -#6422 = DEFINITIONAL_REPRESENTATION('',(#6423),#6427); -#6423 = LINE('',#6424,#6425); -#6424 = CARTESIAN_POINT('',(-0.28,0.2)); -#6425 = VECTOR('',#6426,1.); -#6426 = DIRECTION('',(-1.,0.E+000)); -#6427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6428 = ADVANCED_FACE('',(#6429),#5918,.T.); -#6429 = FACE_BOUND('',#6430,.T.); -#6430 = EDGE_LOOP('',(#6431,#6454,#6455,#6478)); -#6431 = ORIENTED_EDGE('',*,*,#6432,.F.); -#6432 = EDGE_CURVE('',#5903,#6433,#6435,.T.); -#6433 = VERTEX_POINT('',#6434); -#6434 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#6435 = SURFACE_CURVE('',#6436,(#6440,#6447),.PCURVE_S1.); -#6436 = LINE('',#6437,#6438); -#6437 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); -#6438 = VECTOR('',#6439,1.); -#6439 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6440 = PCURVE('',#5918,#6441); -#6441 = DEFINITIONAL_REPRESENTATION('',(#6442),#6446); -#6442 = LINE('',#6443,#6444); -#6443 = CARTESIAN_POINT('',(4.E-002,0.495)); -#6444 = VECTOR('',#6445,1.); -#6445 = DIRECTION('',(-1.,0.E+000)); -#6446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6447 = PCURVE('',#5946,#6448); -#6448 = DEFINITIONAL_REPRESENTATION('',(#6449),#6453); -#6449 = LINE('',#6450,#6451); -#6450 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6451 = VECTOR('',#6452,1.); -#6452 = DIRECTION('',(1.,0.E+000)); -#6453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6454 = ORIENTED_EDGE('',*,*,#5902,.T.); -#6455 = ORIENTED_EDGE('',*,*,#6456,.F.); -#6456 = EDGE_CURVE('',#6457,#5880,#6459,.T.); -#6457 = VERTEX_POINT('',#6458); -#6458 = CARTESIAN_POINT('',(-0.3,0.25,0.28)); -#6459 = SURFACE_CURVE('',#6460,(#6464,#6471),.PCURVE_S1.); -#6460 = LINE('',#6461,#6462); -#6461 = CARTESIAN_POINT('',(-0.3,0.25,0.28)); -#6462 = VECTOR('',#6463,1.); -#6463 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6464 = PCURVE('',#5918,#6465); -#6465 = DEFINITIONAL_REPRESENTATION('',(#6466),#6470); -#6466 = LINE('',#6467,#6468); -#6467 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6468 = VECTOR('',#6469,1.); -#6469 = DIRECTION('',(1.,0.E+000)); -#6470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6471 = PCURVE('',#5748,#6472); -#6472 = DEFINITIONAL_REPRESENTATION('',(#6473),#6477); -#6473 = LINE('',#6474,#6475); -#6474 = CARTESIAN_POINT('',(0.E+000,0.2)); -#6475 = VECTOR('',#6476,1.); -#6476 = DIRECTION('',(-1.,0.E+000)); -#6477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#6358 = PCURVE('',#6347,#6359); +#6359 = DEFINITIONAL_REPRESENTATION('',(#6360),#6364); +#6360 = LINE('',#6361,#6362); +#6361 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6362 = VECTOR('',#6363,1.); +#6363 = DIRECTION('',(0.E+000,-1.)); +#6364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6365 = ORIENTED_EDGE('',*,*,#6366,.T.); +#6366 = EDGE_CURVE('',#6339,#6339,#6367,.T.); +#6367 = SURFACE_CURVE('',#6368,(#6373,#6380),.PCURVE_S1.); +#6368 = CIRCLE('',#6369,0.508); +#6369 = AXIS2_PLACEMENT_3D('',#6370,#6371,#6372); +#6370 = CARTESIAN_POINT('',(31.5400436,25.1138436,1.7018)); +#6371 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6372 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6373 = PCURVE('',#6347,#6374); +#6374 = DEFINITIONAL_REPRESENTATION('',(#6375),#6379); +#6375 = LINE('',#6376,#6377); +#6376 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6377 = VECTOR('',#6378,1.); +#6378 = DIRECTION('',(-1.,0.E+000)); +#6379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6380 = PCURVE('',#391,#6381); +#6381 = DEFINITIONAL_REPRESENTATION('',(#6382),#6390); +#6382 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6383,#6384,#6385,#6386, +#6387,#6388,#6389),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6383 = CARTESIAN_POINT('',(-32.01252678,22.31982582)); +#6384 = CARTESIAN_POINT('',(-32.01252678,23.199707630245)); +#6385 = CARTESIAN_POINT('',(-31.25052678,22.759766725122)); +#6386 = CARTESIAN_POINT('',(-30.48852678,22.31982582)); +#6387 = CARTESIAN_POINT('',(-31.25052678,21.879884914878)); +#6388 = CARTESIAN_POINT('',(-32.01252678,21.439944009755)); +#6389 = CARTESIAN_POINT('',(-32.01252678,22.31982582)); +#6390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6391 = ORIENTED_EDGE('',*,*,#6336,.F.); +#6392 = ORIENTED_EDGE('',*,*,#6393,.F.); +#6393 = EDGE_CURVE('',#6337,#6337,#6394,.T.); +#6394 = SURFACE_CURVE('',#6395,(#6400,#6407),.PCURVE_S1.); +#6395 = CIRCLE('',#6396,0.508); +#6396 = AXIS2_PLACEMENT_3D('',#6397,#6398,#6399); +#6397 = CARTESIAN_POINT('',(31.5400436,25.1138436,0.E+000)); +#6398 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6399 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6400 = PCURVE('',#6347,#6401); +#6401 = DEFINITIONAL_REPRESENTATION('',(#6402),#6406); +#6402 = LINE('',#6403,#6404); +#6403 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6404 = VECTOR('',#6405,1.); +#6405 = DIRECTION('',(-1.,0.E+000)); +#6406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6407 = PCURVE('',#445,#6408); +#6408 = DEFINITIONAL_REPRESENTATION('',(#6409),#6417); +#6409 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6410,#6411,#6412,#6413, +#6414,#6415,#6416),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6410 = CARTESIAN_POINT('',(-32.01252678,22.31982582)); +#6411 = CARTESIAN_POINT('',(-32.01252678,23.199707630245)); +#6412 = CARTESIAN_POINT('',(-31.25052678,22.759766725122)); +#6413 = CARTESIAN_POINT('',(-30.48852678,22.31982582)); +#6414 = CARTESIAN_POINT('',(-31.25052678,21.879884914878)); +#6415 = CARTESIAN_POINT('',(-32.01252678,21.439944009755)); +#6416 = CARTESIAN_POINT('',(-32.01252678,22.31982582)); +#6417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6418 = ADVANCED_FACE('',(#6419),#6433,.F.); +#6419 = FACE_BOUND('',#6420,.T.); +#6420 = EDGE_LOOP('',(#6421,#6451,#6477,#6478)); +#6421 = ORIENTED_EDGE('',*,*,#6422,.T.); +#6422 = EDGE_CURVE('',#6423,#6425,#6427,.T.); +#6423 = VERTEX_POINT('',#6424); +#6424 = CARTESIAN_POINT('',(34.5880436,25.1138436,0.E+000)); +#6425 = VERTEX_POINT('',#6426); +#6426 = CARTESIAN_POINT('',(34.5880436,25.1138436,1.7018)); +#6427 = SEAM_CURVE('',#6428,(#6432,#6444),.PCURVE_S1.); +#6428 = LINE('',#6429,#6430); +#6429 = CARTESIAN_POINT('',(34.5880436,25.1138436,0.E+000)); +#6430 = VECTOR('',#6431,1.); +#6431 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6432 = PCURVE('',#6433,#6438); +#6433 = CYLINDRICAL_SURFACE('',#6434,0.508); +#6434 = AXIS2_PLACEMENT_3D('',#6435,#6436,#6437); +#6435 = CARTESIAN_POINT('',(34.0800436,25.1138436,0.E+000)); +#6436 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6437 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6438 = DEFINITIONAL_REPRESENTATION('',(#6439),#6443); +#6439 = LINE('',#6440,#6441); +#6440 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6441 = VECTOR('',#6442,1.); +#6442 = DIRECTION('',(0.E+000,-1.)); +#6443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6444 = PCURVE('',#6433,#6445); +#6445 = DEFINITIONAL_REPRESENTATION('',(#6446),#6450); +#6446 = LINE('',#6447,#6448); +#6447 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6448 = VECTOR('',#6449,1.); +#6449 = DIRECTION('',(0.E+000,-1.)); +#6450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6451 = ORIENTED_EDGE('',*,*,#6452,.T.); +#6452 = EDGE_CURVE('',#6425,#6425,#6453,.T.); +#6453 = SURFACE_CURVE('',#6454,(#6459,#6466),.PCURVE_S1.); +#6454 = CIRCLE('',#6455,0.508); +#6455 = AXIS2_PLACEMENT_3D('',#6456,#6457,#6458); +#6456 = CARTESIAN_POINT('',(34.0800436,25.1138436,1.7018)); +#6457 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6458 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6459 = PCURVE('',#6433,#6460); +#6460 = DEFINITIONAL_REPRESENTATION('',(#6461),#6465); +#6461 = LINE('',#6462,#6463); +#6462 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6463 = VECTOR('',#6464,1.); +#6464 = DIRECTION('',(-1.,0.E+000)); +#6465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6466 = PCURVE('',#391,#6467); +#6467 = DEFINITIONAL_REPRESENTATION('',(#6468),#6476); +#6468 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6469,#6470,#6471,#6472, +#6473,#6474,#6475),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6469 = CARTESIAN_POINT('',(-34.55252678,22.31982582)); +#6470 = CARTESIAN_POINT('',(-34.55252678,23.199707630245)); +#6471 = CARTESIAN_POINT('',(-33.79052678,22.759766725122)); +#6472 = CARTESIAN_POINT('',(-33.02852678,22.31982582)); +#6473 = CARTESIAN_POINT('',(-33.79052678,21.879884914878)); +#6474 = CARTESIAN_POINT('',(-34.55252678,21.439944009755)); +#6475 = CARTESIAN_POINT('',(-34.55252678,22.31982582)); +#6476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6477 = ORIENTED_EDGE('',*,*,#6422,.F.); +#6478 = ORIENTED_EDGE('',*,*,#6479,.F.); +#6479 = EDGE_CURVE('',#6423,#6423,#6480,.T.); +#6480 = SURFACE_CURVE('',#6481,(#6486,#6493),.PCURVE_S1.); +#6481 = CIRCLE('',#6482,0.508); +#6482 = AXIS2_PLACEMENT_3D('',#6483,#6484,#6485); +#6483 = CARTESIAN_POINT('',(34.0800436,25.1138436,0.E+000)); +#6484 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6485 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6486 = PCURVE('',#6433,#6487); +#6487 = DEFINITIONAL_REPRESENTATION('',(#6488),#6492); +#6488 = LINE('',#6489,#6490); +#6489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6490 = VECTOR('',#6491,1.); +#6491 = DIRECTION('',(-1.,0.E+000)); +#6492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6493 = PCURVE('',#445,#6494); +#6494 = DEFINITIONAL_REPRESENTATION('',(#6495),#6503); +#6495 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6496,#6497,#6498,#6499, +#6500,#6501,#6502),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6496 = CARTESIAN_POINT('',(-34.55252678,22.31982582)); +#6497 = CARTESIAN_POINT('',(-34.55252678,23.199707630245)); +#6498 = CARTESIAN_POINT('',(-33.79052678,22.759766725122)); +#6499 = CARTESIAN_POINT('',(-33.02852678,22.31982582)); +#6500 = CARTESIAN_POINT('',(-33.79052678,21.879884914878)); +#6501 = CARTESIAN_POINT('',(-34.55252678,21.439944009755)); +#6502 = CARTESIAN_POINT('',(-34.55252678,22.31982582)); +#6503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6504 = ADVANCED_FACE('',(#6505),#6519,.F.); +#6505 = FACE_BOUND('',#6506,.T.); +#6506 = EDGE_LOOP('',(#6507,#6537,#6563,#6564)); +#6507 = ORIENTED_EDGE('',*,*,#6508,.T.); +#6508 = EDGE_CURVE('',#6509,#6511,#6513,.T.); +#6509 = VERTEX_POINT('',#6510); +#6510 = CARTESIAN_POINT('',(34.5880436,22.5738436,0.E+000)); +#6511 = VERTEX_POINT('',#6512); +#6512 = CARTESIAN_POINT('',(34.5880436,22.5738436,1.7018)); +#6513 = SEAM_CURVE('',#6514,(#6518,#6530),.PCURVE_S1.); +#6514 = LINE('',#6515,#6516); +#6515 = CARTESIAN_POINT('',(34.5880436,22.5738436,0.E+000)); +#6516 = VECTOR('',#6517,1.); +#6517 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6518 = PCURVE('',#6519,#6524); +#6519 = CYLINDRICAL_SURFACE('',#6520,0.508); +#6520 = AXIS2_PLACEMENT_3D('',#6521,#6522,#6523); +#6521 = CARTESIAN_POINT('',(34.0800436,22.5738436,0.E+000)); +#6522 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6523 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6524 = DEFINITIONAL_REPRESENTATION('',(#6525),#6529); +#6525 = LINE('',#6526,#6527); +#6526 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6527 = VECTOR('',#6528,1.); +#6528 = DIRECTION('',(0.E+000,-1.)); +#6529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6530 = PCURVE('',#6519,#6531); +#6531 = DEFINITIONAL_REPRESENTATION('',(#6532),#6536); +#6532 = LINE('',#6533,#6534); +#6533 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6534 = VECTOR('',#6535,1.); +#6535 = DIRECTION('',(0.E+000,-1.)); +#6536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6537 = ORIENTED_EDGE('',*,*,#6538,.T.); +#6538 = EDGE_CURVE('',#6511,#6511,#6539,.T.); +#6539 = SURFACE_CURVE('',#6540,(#6545,#6552),.PCURVE_S1.); +#6540 = CIRCLE('',#6541,0.508); +#6541 = AXIS2_PLACEMENT_3D('',#6542,#6543,#6544); +#6542 = CARTESIAN_POINT('',(34.0800436,22.5738436,1.7018)); +#6543 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6544 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6545 = PCURVE('',#6519,#6546); +#6546 = DEFINITIONAL_REPRESENTATION('',(#6547),#6551); +#6547 = LINE('',#6548,#6549); +#6548 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6549 = VECTOR('',#6550,1.); +#6550 = DIRECTION('',(-1.,0.E+000)); +#6551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6552 = PCURVE('',#391,#6553); +#6553 = DEFINITIONAL_REPRESENTATION('',(#6554),#6562); +#6554 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6555,#6556,#6557,#6558, +#6559,#6560,#6561),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6555 = CARTESIAN_POINT('',(-34.55252678,19.77982582)); +#6556 = CARTESIAN_POINT('',(-34.55252678,20.659707630245)); +#6557 = CARTESIAN_POINT('',(-33.79052678,20.219766725123)); +#6558 = CARTESIAN_POINT('',(-33.02852678,19.77982582)); +#6559 = CARTESIAN_POINT('',(-33.79052678,19.339884914878)); +#6560 = CARTESIAN_POINT('',(-34.55252678,18.899944009755)); +#6561 = CARTESIAN_POINT('',(-34.55252678,19.77982582)); +#6562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6563 = ORIENTED_EDGE('',*,*,#6508,.F.); +#6564 = ORIENTED_EDGE('',*,*,#6565,.F.); +#6565 = EDGE_CURVE('',#6509,#6509,#6566,.T.); +#6566 = SURFACE_CURVE('',#6567,(#6572,#6579),.PCURVE_S1.); +#6567 = CIRCLE('',#6568,0.508); +#6568 = AXIS2_PLACEMENT_3D('',#6569,#6570,#6571); +#6569 = CARTESIAN_POINT('',(34.0800436,22.5738436,0.E+000)); +#6570 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6571 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6572 = PCURVE('',#6519,#6573); +#6573 = DEFINITIONAL_REPRESENTATION('',(#6574),#6578); +#6574 = LINE('',#6575,#6576); +#6575 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6576 = VECTOR('',#6577,1.); +#6577 = DIRECTION('',(-1.,0.E+000)); +#6578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6579 = PCURVE('',#445,#6580); +#6580 = DEFINITIONAL_REPRESENTATION('',(#6581),#6589); +#6581 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6582,#6583,#6584,#6585, +#6586,#6587,#6588),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6582 = CARTESIAN_POINT('',(-34.55252678,19.77982582)); +#6583 = CARTESIAN_POINT('',(-34.55252678,20.659707630245)); +#6584 = CARTESIAN_POINT('',(-33.79052678,20.219766725123)); +#6585 = CARTESIAN_POINT('',(-33.02852678,19.77982582)); +#6586 = CARTESIAN_POINT('',(-33.79052678,19.339884914878)); +#6587 = CARTESIAN_POINT('',(-34.55252678,18.899944009755)); +#6588 = CARTESIAN_POINT('',(-34.55252678,19.77982582)); +#6589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6590 = ADVANCED_FACE('',(#6591),#6605,.F.); +#6591 = FACE_BOUND('',#6592,.T.); +#6592 = EDGE_LOOP('',(#6593,#6623,#6649,#6650)); +#6593 = ORIENTED_EDGE('',*,*,#6594,.T.); +#6594 = EDGE_CURVE('',#6595,#6597,#6599,.T.); +#6595 = VERTEX_POINT('',#6596); +#6596 = CARTESIAN_POINT('',(34.79401474,33.2940152,0.E+000)); +#6597 = VERTEX_POINT('',#6598); +#6598 = CARTESIAN_POINT('',(34.79401474,33.2940152,1.7018)); +#6599 = SEAM_CURVE('',#6600,(#6604,#6616),.PCURVE_S1.); +#6600 = LINE('',#6601,#6602); +#6601 = CARTESIAN_POINT('',(34.79401474,33.2940152,0.E+000)); +#6602 = VECTOR('',#6603,1.); +#6603 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6604 = PCURVE('',#6605,#6610); +#6605 = CYLINDRICAL_SURFACE('',#6606,1.49999954); +#6606 = AXIS2_PLACEMENT_3D('',#6607,#6608,#6609); +#6607 = CARTESIAN_POINT('',(33.2940152,33.2940152,0.E+000)); +#6608 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6609 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6610 = DEFINITIONAL_REPRESENTATION('',(#6611),#6615); +#6611 = LINE('',#6612,#6613); +#6612 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6613 = VECTOR('',#6614,1.); +#6614 = DIRECTION('',(0.E+000,-1.)); +#6615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6616 = PCURVE('',#6605,#6617); +#6617 = DEFINITIONAL_REPRESENTATION('',(#6618),#6622); +#6618 = LINE('',#6619,#6620); +#6619 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6620 = VECTOR('',#6621,1.); +#6621 = DIRECTION('',(0.E+000,-1.)); +#6622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6623 = ORIENTED_EDGE('',*,*,#6624,.T.); +#6624 = EDGE_CURVE('',#6597,#6597,#6625,.T.); +#6625 = SURFACE_CURVE('',#6626,(#6631,#6638),.PCURVE_S1.); +#6626 = CIRCLE('',#6627,1.49999954); +#6627 = AXIS2_PLACEMENT_3D('',#6628,#6629,#6630); +#6628 = CARTESIAN_POINT('',(33.2940152,33.2940152,1.7018)); +#6629 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6630 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6631 = PCURVE('',#6605,#6632); +#6632 = DEFINITIONAL_REPRESENTATION('',(#6633),#6637); +#6633 = LINE('',#6634,#6635); +#6634 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6635 = VECTOR('',#6636,1.); +#6636 = DIRECTION('',(-1.,0.E+000)); +#6637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6638 = PCURVE('',#391,#6639); +#6639 = DEFINITIONAL_REPRESENTATION('',(#6640),#6648); +#6640 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6641,#6642,#6643,#6644, +#6645,#6646,#6647),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6641 = CARTESIAN_POINT('',(-34.75849792,30.49999742)); +#6642 = CARTESIAN_POINT('',(-34.75849792,33.09807283461)); +#6643 = CARTESIAN_POINT('',(-32.50849861,31.799035127305)); +#6644 = CARTESIAN_POINT('',(-30.2584993,30.49999742)); +#6645 = CARTESIAN_POINT('',(-32.50849861,29.200959712695)); +#6646 = CARTESIAN_POINT('',(-34.75849792,27.90192200539)); +#6647 = CARTESIAN_POINT('',(-34.75849792,30.49999742)); +#6648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6649 = ORIENTED_EDGE('',*,*,#6594,.F.); +#6650 = ORIENTED_EDGE('',*,*,#6651,.F.); +#6651 = EDGE_CURVE('',#6595,#6595,#6652,.T.); +#6652 = SURFACE_CURVE('',#6653,(#6658,#6665),.PCURVE_S1.); +#6653 = CIRCLE('',#6654,1.49999954); +#6654 = AXIS2_PLACEMENT_3D('',#6655,#6656,#6657); +#6655 = CARTESIAN_POINT('',(33.2940152,33.2940152,0.E+000)); +#6656 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6657 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6658 = PCURVE('',#6605,#6659); +#6659 = DEFINITIONAL_REPRESENTATION('',(#6660),#6664); +#6660 = LINE('',#6661,#6662); +#6661 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6662 = VECTOR('',#6663,1.); +#6663 = DIRECTION('',(-1.,0.E+000)); +#6664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6665 = PCURVE('',#445,#6666); +#6666 = DEFINITIONAL_REPRESENTATION('',(#6667),#6675); +#6667 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6668,#6669,#6670,#6671, +#6672,#6673,#6674),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6668 = CARTESIAN_POINT('',(-34.75849792,30.49999742)); +#6669 = CARTESIAN_POINT('',(-34.75849792,33.09807283461)); +#6670 = CARTESIAN_POINT('',(-32.50849861,31.799035127305)); +#6671 = CARTESIAN_POINT('',(-30.2584993,30.49999742)); +#6672 = CARTESIAN_POINT('',(-32.50849861,29.200959712695)); +#6673 = CARTESIAN_POINT('',(-34.75849792,27.90192200539)); +#6674 = CARTESIAN_POINT('',(-34.75849792,30.49999742)); +#6675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6676 = ADVANCED_FACE('',(#6677),#6691,.F.); +#6677 = FACE_BOUND('',#6678,.T.); +#6678 = EDGE_LOOP('',(#6679,#6709,#6735,#6736)); +#6679 = ORIENTED_EDGE('',*,*,#6680,.T.); +#6680 = EDGE_CURVE('',#6681,#6683,#6685,.T.); +#6681 = VERTEX_POINT('',#6682); +#6682 = CARTESIAN_POINT('',(34.5880436,27.6538436,0.E+000)); +#6683 = VERTEX_POINT('',#6684); +#6684 = CARTESIAN_POINT('',(34.5880436,27.6538436,1.7018)); +#6685 = SEAM_CURVE('',#6686,(#6690,#6702),.PCURVE_S1.); +#6686 = LINE('',#6687,#6688); +#6687 = CARTESIAN_POINT('',(34.5880436,27.6538436,0.E+000)); +#6688 = VECTOR('',#6689,1.); +#6689 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6690 = PCURVE('',#6691,#6696); +#6691 = CYLINDRICAL_SURFACE('',#6692,0.508); +#6692 = AXIS2_PLACEMENT_3D('',#6693,#6694,#6695); +#6693 = CARTESIAN_POINT('',(34.0800436,27.6538436,0.E+000)); +#6694 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#6695 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6696 = DEFINITIONAL_REPRESENTATION('',(#6697),#6701); +#6697 = LINE('',#6698,#6699); +#6698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6699 = VECTOR('',#6700,1.); +#6700 = DIRECTION('',(0.E+000,-1.)); +#6701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6702 = PCURVE('',#6691,#6703); +#6703 = DEFINITIONAL_REPRESENTATION('',(#6704),#6708); +#6704 = LINE('',#6705,#6706); +#6705 = CARTESIAN_POINT('',(-6.28318530718,0.E+000)); +#6706 = VECTOR('',#6707,1.); +#6707 = DIRECTION('',(0.E+000,-1.)); +#6708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6709 = ORIENTED_EDGE('',*,*,#6710,.T.); +#6710 = EDGE_CURVE('',#6683,#6683,#6711,.T.); +#6711 = SURFACE_CURVE('',#6712,(#6717,#6724),.PCURVE_S1.); +#6712 = CIRCLE('',#6713,0.508); +#6713 = AXIS2_PLACEMENT_3D('',#6714,#6715,#6716); +#6714 = CARTESIAN_POINT('',(34.0800436,27.6538436,1.7018)); +#6715 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6716 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6717 = PCURVE('',#6691,#6718); +#6718 = DEFINITIONAL_REPRESENTATION('',(#6719),#6723); +#6719 = LINE('',#6720,#6721); +#6720 = CARTESIAN_POINT('',(0.E+000,-1.7018)); +#6721 = VECTOR('',#6722,1.); +#6722 = DIRECTION('',(-1.,0.E+000)); +#6723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6724 = PCURVE('',#391,#6725); +#6725 = DEFINITIONAL_REPRESENTATION('',(#6726),#6734); +#6726 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6727,#6728,#6729,#6730, +#6731,#6732,#6733),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6727 = CARTESIAN_POINT('',(-34.55252678,24.85982582)); +#6728 = CARTESIAN_POINT('',(-34.55252678,25.739707630245)); +#6729 = CARTESIAN_POINT('',(-33.79052678,25.299766725123)); +#6730 = CARTESIAN_POINT('',(-33.02852678,24.85982582)); +#6731 = CARTESIAN_POINT('',(-33.79052678,24.419884914878)); +#6732 = CARTESIAN_POINT('',(-34.55252678,23.979944009755)); +#6733 = CARTESIAN_POINT('',(-34.55252678,24.85982582)); +#6734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6735 = ORIENTED_EDGE('',*,*,#6680,.F.); +#6736 = ORIENTED_EDGE('',*,*,#6737,.F.); +#6737 = EDGE_CURVE('',#6681,#6681,#6738,.T.); +#6738 = SURFACE_CURVE('',#6739,(#6744,#6751),.PCURVE_S1.); +#6739 = CIRCLE('',#6740,0.508); +#6740 = AXIS2_PLACEMENT_3D('',#6741,#6742,#6743); +#6741 = CARTESIAN_POINT('',(34.0800436,27.6538436,0.E+000)); +#6742 = DIRECTION('',(0.E+000,0.E+000,1.)); +#6743 = DIRECTION('',(1.,0.E+000,0.E+000)); +#6744 = PCURVE('',#6691,#6745); +#6745 = DEFINITIONAL_REPRESENTATION('',(#6746),#6750); +#6746 = LINE('',#6747,#6748); +#6747 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#6748 = VECTOR('',#6749,1.); +#6749 = DIRECTION('',(-1.,0.E+000)); +#6750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6751 = PCURVE('',#445,#6752); +#6752 = DEFINITIONAL_REPRESENTATION('',(#6753),#6761); +#6753 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#6754,#6755,#6756,#6757, +#6758,#6759,#6760),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 + ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, +6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() +GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, +1.,0.5,1.)) REPRESENTATION_ITEM('') ); +#6754 = CARTESIAN_POINT('',(-34.55252678,24.85982582)); +#6755 = CARTESIAN_POINT('',(-34.55252678,25.739707630245)); +#6756 = CARTESIAN_POINT('',(-33.79052678,25.299766725123)); +#6757 = CARTESIAN_POINT('',(-33.02852678,24.85982582)); +#6758 = CARTESIAN_POINT('',(-33.79052678,24.419884914878)); +#6759 = CARTESIAN_POINT('',(-34.55252678,23.979944009755)); +#6760 = CARTESIAN_POINT('',(-34.55252678,24.85982582)); +#6761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#6762 = ADVANCED_FACE('',(#6763,#6820,#6823,#6826,#6829,#6832,#6835, + #6838,#6841,#6844,#6847,#6850,#6853,#6856,#6859,#6862,#6865,#6868, + #6871,#6874,#6877,#6880,#6883,#6886,#6889,#6892,#6895),#445,.T.); +#6763 = FACE_BOUND('',#6764,.F.); +#6764 = EDGE_LOOP('',(#6765,#6766,#6767,#6768,#6769,#6770,#6771,#6772, + #6773,#6774,#6775,#6776,#6777,#6778,#6779,#6780,#6781,#6782,#6783, + #6784,#6785,#6786,#6787,#6788,#6789,#6790,#6791,#6792,#6793,#6794, + #6795,#6796,#6797,#6798,#6799,#6800,#6801,#6802,#6803,#6804,#6805, + #6806,#6807,#6808,#6809,#6810,#6811,#6812,#6813,#6814,#6815,#6816, + #6817,#6818,#6819)); +#6765 = ORIENTED_EDGE('',*,*,#431,.T.); +#6766 = ORIENTED_EDGE('',*,*,#512,.T.); +#6767 = ORIENTED_EDGE('',*,*,#588,.T.); +#6768 = ORIENTED_EDGE('',*,*,#664,.T.); +#6769 = ORIENTED_EDGE('',*,*,#740,.T.); +#6770 = ORIENTED_EDGE('',*,*,#816,.T.); +#6771 = ORIENTED_EDGE('',*,*,#892,.T.); +#6772 = ORIENTED_EDGE('',*,*,#968,.T.); +#6773 = ORIENTED_EDGE('',*,*,#1044,.T.); +#6774 = ORIENTED_EDGE('',*,*,#1120,.T.); +#6775 = ORIENTED_EDGE('',*,*,#1196,.T.); +#6776 = ORIENTED_EDGE('',*,*,#1272,.T.); +#6777 = ORIENTED_EDGE('',*,*,#1348,.T.); +#6778 = ORIENTED_EDGE('',*,*,#1424,.T.); +#6779 = ORIENTED_EDGE('',*,*,#1500,.T.); +#6780 = ORIENTED_EDGE('',*,*,#1576,.T.); +#6781 = ORIENTED_EDGE('',*,*,#1652,.T.); +#6782 = ORIENTED_EDGE('',*,*,#1728,.T.); +#6783 = ORIENTED_EDGE('',*,*,#1804,.T.); +#6784 = ORIENTED_EDGE('',*,*,#1880,.T.); +#6785 = ORIENTED_EDGE('',*,*,#1956,.T.); +#6786 = ORIENTED_EDGE('',*,*,#2032,.T.); +#6787 = ORIENTED_EDGE('',*,*,#2108,.T.); +#6788 = ORIENTED_EDGE('',*,*,#2184,.T.); +#6789 = ORIENTED_EDGE('',*,*,#2260,.T.); +#6790 = ORIENTED_EDGE('',*,*,#2336,.T.); +#6791 = ORIENTED_EDGE('',*,*,#2412,.T.); +#6792 = ORIENTED_EDGE('',*,*,#2488,.T.); +#6793 = ORIENTED_EDGE('',*,*,#2564,.T.); +#6794 = ORIENTED_EDGE('',*,*,#2640,.T.); +#6795 = ORIENTED_EDGE('',*,*,#2716,.T.); +#6796 = ORIENTED_EDGE('',*,*,#2792,.T.); +#6797 = ORIENTED_EDGE('',*,*,#2868,.T.); +#6798 = ORIENTED_EDGE('',*,*,#2944,.T.); +#6799 = ORIENTED_EDGE('',*,*,#3020,.T.); +#6800 = ORIENTED_EDGE('',*,*,#3096,.T.); +#6801 = ORIENTED_EDGE('',*,*,#3172,.T.); +#6802 = ORIENTED_EDGE('',*,*,#3248,.T.); +#6803 = ORIENTED_EDGE('',*,*,#3324,.T.); +#6804 = ORIENTED_EDGE('',*,*,#3400,.T.); +#6805 = ORIENTED_EDGE('',*,*,#3476,.T.); +#6806 = ORIENTED_EDGE('',*,*,#3552,.T.); +#6807 = ORIENTED_EDGE('',*,*,#3628,.T.); +#6808 = ORIENTED_EDGE('',*,*,#3704,.T.); +#6809 = ORIENTED_EDGE('',*,*,#3780,.T.); +#6810 = ORIENTED_EDGE('',*,*,#3856,.T.); +#6811 = ORIENTED_EDGE('',*,*,#3932,.T.); +#6812 = ORIENTED_EDGE('',*,*,#4008,.T.); +#6813 = ORIENTED_EDGE('',*,*,#4084,.T.); +#6814 = ORIENTED_EDGE('',*,*,#4160,.T.); +#6815 = ORIENTED_EDGE('',*,*,#4236,.T.); +#6816 = ORIENTED_EDGE('',*,*,#4312,.T.); +#6817 = ORIENTED_EDGE('',*,*,#4388,.T.); +#6818 = ORIENTED_EDGE('',*,*,#4459,.T.); +#6819 = ORIENTED_EDGE('',*,*,#4506,.T.); +#6820 = FACE_BOUND('',#6821,.T.); +#6821 = EDGE_LOOP('',(#6822)); +#6822 = ORIENTED_EDGE('',*,*,#4587,.T.); +#6823 = FACE_BOUND('',#6824,.T.); +#6824 = EDGE_LOOP('',(#6825)); +#6825 = ORIENTED_EDGE('',*,*,#4673,.T.); +#6826 = FACE_BOUND('',#6827,.T.); +#6827 = EDGE_LOOP('',(#6828)); +#6828 = ORIENTED_EDGE('',*,*,#4759,.T.); +#6829 = FACE_BOUND('',#6830,.T.); +#6830 = EDGE_LOOP('',(#6831)); +#6831 = ORIENTED_EDGE('',*,*,#4845,.T.); +#6832 = FACE_BOUND('',#6833,.T.); +#6833 = EDGE_LOOP('',(#6834)); +#6834 = ORIENTED_EDGE('',*,*,#4931,.T.); +#6835 = FACE_BOUND('',#6836,.T.); +#6836 = EDGE_LOOP('',(#6837)); +#6837 = ORIENTED_EDGE('',*,*,#5017,.T.); +#6838 = FACE_BOUND('',#6839,.T.); +#6839 = EDGE_LOOP('',(#6840)); +#6840 = ORIENTED_EDGE('',*,*,#5103,.T.); +#6841 = FACE_BOUND('',#6842,.T.); +#6842 = EDGE_LOOP('',(#6843)); +#6843 = ORIENTED_EDGE('',*,*,#5189,.T.); +#6844 = FACE_BOUND('',#6845,.T.); +#6845 = EDGE_LOOP('',(#6846)); +#6846 = ORIENTED_EDGE('',*,*,#5275,.T.); +#6847 = FACE_BOUND('',#6848,.T.); +#6848 = EDGE_LOOP('',(#6849)); +#6849 = ORIENTED_EDGE('',*,*,#5361,.T.); +#6850 = FACE_BOUND('',#6851,.T.); +#6851 = EDGE_LOOP('',(#6852)); +#6852 = ORIENTED_EDGE('',*,*,#5447,.T.); +#6853 = FACE_BOUND('',#6854,.T.); +#6854 = EDGE_LOOP('',(#6855)); +#6855 = ORIENTED_EDGE('',*,*,#5533,.T.); +#6856 = FACE_BOUND('',#6857,.T.); +#6857 = EDGE_LOOP('',(#6858)); +#6858 = ORIENTED_EDGE('',*,*,#5619,.T.); +#6859 = FACE_BOUND('',#6860,.T.); +#6860 = EDGE_LOOP('',(#6861)); +#6861 = ORIENTED_EDGE('',*,*,#5705,.T.); +#6862 = FACE_BOUND('',#6863,.T.); +#6863 = EDGE_LOOP('',(#6864)); +#6864 = ORIENTED_EDGE('',*,*,#5791,.T.); +#6865 = FACE_BOUND('',#6866,.T.); +#6866 = EDGE_LOOP('',(#6867)); +#6867 = ORIENTED_EDGE('',*,*,#5877,.T.); +#6868 = FACE_BOUND('',#6869,.T.); +#6869 = EDGE_LOOP('',(#6870)); +#6870 = ORIENTED_EDGE('',*,*,#5963,.T.); +#6871 = FACE_BOUND('',#6872,.T.); +#6872 = EDGE_LOOP('',(#6873)); +#6873 = ORIENTED_EDGE('',*,*,#6049,.T.); +#6874 = FACE_BOUND('',#6875,.T.); +#6875 = EDGE_LOOP('',(#6876)); +#6876 = ORIENTED_EDGE('',*,*,#6135,.T.); +#6877 = FACE_BOUND('',#6878,.T.); +#6878 = EDGE_LOOP('',(#6879)); +#6879 = ORIENTED_EDGE('',*,*,#6221,.T.); +#6880 = FACE_BOUND('',#6881,.T.); +#6881 = EDGE_LOOP('',(#6882)); +#6882 = ORIENTED_EDGE('',*,*,#6307,.T.); +#6883 = FACE_BOUND('',#6884,.T.); +#6884 = EDGE_LOOP('',(#6885)); +#6885 = ORIENTED_EDGE('',*,*,#6393,.T.); +#6886 = FACE_BOUND('',#6887,.T.); +#6887 = EDGE_LOOP('',(#6888)); +#6888 = ORIENTED_EDGE('',*,*,#6479,.T.); +#6889 = FACE_BOUND('',#6890,.T.); +#6890 = EDGE_LOOP('',(#6891)); +#6891 = ORIENTED_EDGE('',*,*,#6565,.T.); +#6892 = FACE_BOUND('',#6893,.T.); +#6893 = EDGE_LOOP('',(#6894)); +#6894 = ORIENTED_EDGE('',*,*,#6651,.T.); +#6895 = FACE_BOUND('',#6896,.T.); +#6896 = EDGE_LOOP('',(#6897)); +#6897 = ORIENTED_EDGE('',*,*,#6737,.T.); +#6898 = ADVANCED_FACE('',(#6899,#6956,#6959,#6962,#6965,#6968,#6971, + #6974,#6977,#6980,#6983,#6986,#6989,#6992,#6995,#6998,#7001,#7004, + #7007,#7010,#7013,#7016,#7019,#7022,#7025,#7028,#7031),#391,.F.); +#6899 = FACE_BOUND('',#6900,.T.); +#6900 = EDGE_LOOP('',(#6901,#6902,#6903,#6904,#6905,#6906,#6907,#6908, + #6909,#6910,#6911,#6912,#6913,#6914,#6915,#6916,#6917,#6918,#6919, + #6920,#6921,#6922,#6923,#6924,#6925,#6926,#6927,#6928,#6929,#6930, + #6931,#6932,#6933,#6934,#6935,#6936,#6937,#6938,#6939,#6940,#6941, + #6942,#6943,#6944,#6945,#6946,#6947,#6948,#6949,#6950,#6951,#6952, + #6953,#6954,#6955)); +#6901 = ORIENTED_EDGE('',*,*,#375,.T.); +#6902 = ORIENTED_EDGE('',*,*,#461,.T.); +#6903 = ORIENTED_EDGE('',*,*,#537,.T.); +#6904 = ORIENTED_EDGE('',*,*,#613,.T.); +#6905 = ORIENTED_EDGE('',*,*,#689,.T.); +#6906 = ORIENTED_EDGE('',*,*,#765,.T.); +#6907 = ORIENTED_EDGE('',*,*,#841,.T.); +#6908 = ORIENTED_EDGE('',*,*,#917,.T.); +#6909 = ORIENTED_EDGE('',*,*,#993,.T.); +#6910 = ORIENTED_EDGE('',*,*,#1069,.T.); +#6911 = ORIENTED_EDGE('',*,*,#1145,.T.); +#6912 = ORIENTED_EDGE('',*,*,#1221,.T.); +#6913 = ORIENTED_EDGE('',*,*,#1297,.T.); +#6914 = ORIENTED_EDGE('',*,*,#1373,.T.); +#6915 = ORIENTED_EDGE('',*,*,#1449,.T.); +#6916 = ORIENTED_EDGE('',*,*,#1525,.T.); +#6917 = ORIENTED_EDGE('',*,*,#1601,.T.); +#6918 = ORIENTED_EDGE('',*,*,#1677,.T.); +#6919 = ORIENTED_EDGE('',*,*,#1753,.T.); +#6920 = ORIENTED_EDGE('',*,*,#1829,.T.); +#6921 = ORIENTED_EDGE('',*,*,#1905,.T.); +#6922 = ORIENTED_EDGE('',*,*,#1981,.T.); +#6923 = ORIENTED_EDGE('',*,*,#2057,.T.); +#6924 = ORIENTED_EDGE('',*,*,#2133,.T.); +#6925 = ORIENTED_EDGE('',*,*,#2209,.T.); +#6926 = ORIENTED_EDGE('',*,*,#2285,.T.); +#6927 = ORIENTED_EDGE('',*,*,#2361,.T.); +#6928 = ORIENTED_EDGE('',*,*,#2437,.T.); +#6929 = ORIENTED_EDGE('',*,*,#2513,.T.); +#6930 = ORIENTED_EDGE('',*,*,#2589,.T.); +#6931 = ORIENTED_EDGE('',*,*,#2665,.T.); +#6932 = ORIENTED_EDGE('',*,*,#2741,.T.); +#6933 = ORIENTED_EDGE('',*,*,#2817,.T.); +#6934 = ORIENTED_EDGE('',*,*,#2893,.T.); +#6935 = ORIENTED_EDGE('',*,*,#2969,.T.); +#6936 = ORIENTED_EDGE('',*,*,#3045,.T.); +#6937 = ORIENTED_EDGE('',*,*,#3121,.T.); +#6938 = ORIENTED_EDGE('',*,*,#3197,.T.); +#6939 = ORIENTED_EDGE('',*,*,#3273,.T.); +#6940 = ORIENTED_EDGE('',*,*,#3349,.T.); +#6941 = ORIENTED_EDGE('',*,*,#3425,.T.); +#6942 = ORIENTED_EDGE('',*,*,#3501,.T.); +#6943 = ORIENTED_EDGE('',*,*,#3577,.T.); +#6944 = ORIENTED_EDGE('',*,*,#3653,.T.); +#6945 = ORIENTED_EDGE('',*,*,#3729,.T.); +#6946 = ORIENTED_EDGE('',*,*,#3805,.T.); +#6947 = ORIENTED_EDGE('',*,*,#3881,.T.); +#6948 = ORIENTED_EDGE('',*,*,#3957,.T.); +#6949 = ORIENTED_EDGE('',*,*,#4033,.T.); +#6950 = ORIENTED_EDGE('',*,*,#4109,.T.); +#6951 = ORIENTED_EDGE('',*,*,#4185,.T.); +#6952 = ORIENTED_EDGE('',*,*,#4261,.T.); +#6953 = ORIENTED_EDGE('',*,*,#4337,.T.); +#6954 = ORIENTED_EDGE('',*,*,#4413,.T.); +#6955 = ORIENTED_EDGE('',*,*,#4484,.T.); +#6956 = FACE_BOUND('',#6957,.F.); +#6957 = EDGE_LOOP('',(#6958)); +#6958 = ORIENTED_EDGE('',*,*,#4560,.T.); +#6959 = FACE_BOUND('',#6960,.F.); +#6960 = EDGE_LOOP('',(#6961)); +#6961 = ORIENTED_EDGE('',*,*,#4646,.T.); +#6962 = FACE_BOUND('',#6963,.F.); +#6963 = EDGE_LOOP('',(#6964)); +#6964 = ORIENTED_EDGE('',*,*,#4732,.T.); +#6965 = FACE_BOUND('',#6966,.F.); +#6966 = EDGE_LOOP('',(#6967)); +#6967 = ORIENTED_EDGE('',*,*,#4818,.T.); +#6968 = FACE_BOUND('',#6969,.F.); +#6969 = EDGE_LOOP('',(#6970)); +#6970 = ORIENTED_EDGE('',*,*,#4904,.T.); +#6971 = FACE_BOUND('',#6972,.F.); +#6972 = EDGE_LOOP('',(#6973)); +#6973 = ORIENTED_EDGE('',*,*,#4990,.T.); +#6974 = FACE_BOUND('',#6975,.F.); +#6975 = EDGE_LOOP('',(#6976)); +#6976 = ORIENTED_EDGE('',*,*,#5076,.T.); +#6977 = FACE_BOUND('',#6978,.F.); +#6978 = EDGE_LOOP('',(#6979)); +#6979 = ORIENTED_EDGE('',*,*,#5162,.T.); +#6980 = FACE_BOUND('',#6981,.F.); +#6981 = EDGE_LOOP('',(#6982)); +#6982 = ORIENTED_EDGE('',*,*,#5248,.T.); +#6983 = FACE_BOUND('',#6984,.F.); +#6984 = EDGE_LOOP('',(#6985)); +#6985 = ORIENTED_EDGE('',*,*,#5334,.T.); +#6986 = FACE_BOUND('',#6987,.F.); +#6987 = EDGE_LOOP('',(#6988)); +#6988 = ORIENTED_EDGE('',*,*,#5420,.T.); +#6989 = FACE_BOUND('',#6990,.F.); +#6990 = EDGE_LOOP('',(#6991)); +#6991 = ORIENTED_EDGE('',*,*,#5506,.T.); +#6992 = FACE_BOUND('',#6993,.F.); +#6993 = EDGE_LOOP('',(#6994)); +#6994 = ORIENTED_EDGE('',*,*,#5592,.T.); +#6995 = FACE_BOUND('',#6996,.F.); +#6996 = EDGE_LOOP('',(#6997)); +#6997 = ORIENTED_EDGE('',*,*,#5678,.T.); +#6998 = FACE_BOUND('',#6999,.F.); +#6999 = EDGE_LOOP('',(#7000)); +#7000 = ORIENTED_EDGE('',*,*,#5764,.T.); +#7001 = FACE_BOUND('',#7002,.F.); +#7002 = EDGE_LOOP('',(#7003)); +#7003 = ORIENTED_EDGE('',*,*,#5850,.T.); +#7004 = FACE_BOUND('',#7005,.F.); +#7005 = EDGE_LOOP('',(#7006)); +#7006 = ORIENTED_EDGE('',*,*,#5936,.T.); +#7007 = FACE_BOUND('',#7008,.F.); +#7008 = EDGE_LOOP('',(#7009)); +#7009 = ORIENTED_EDGE('',*,*,#6022,.T.); +#7010 = FACE_BOUND('',#7011,.F.); +#7011 = EDGE_LOOP('',(#7012)); +#7012 = ORIENTED_EDGE('',*,*,#6108,.T.); +#7013 = FACE_BOUND('',#7014,.F.); +#7014 = EDGE_LOOP('',(#7015)); +#7015 = ORIENTED_EDGE('',*,*,#6194,.T.); +#7016 = FACE_BOUND('',#7017,.F.); +#7017 = EDGE_LOOP('',(#7018)); +#7018 = ORIENTED_EDGE('',*,*,#6280,.T.); +#7019 = FACE_BOUND('',#7020,.F.); +#7020 = EDGE_LOOP('',(#7021)); +#7021 = ORIENTED_EDGE('',*,*,#6366,.T.); +#7022 = FACE_BOUND('',#7023,.F.); +#7023 = EDGE_LOOP('',(#7024)); +#7024 = ORIENTED_EDGE('',*,*,#6452,.T.); +#7025 = FACE_BOUND('',#7026,.F.); +#7026 = EDGE_LOOP('',(#7027)); +#7027 = ORIENTED_EDGE('',*,*,#6538,.T.); +#7028 = FACE_BOUND('',#7029,.F.); +#7029 = EDGE_LOOP('',(#7030)); +#7030 = ORIENTED_EDGE('',*,*,#6624,.T.); +#7031 = FACE_BOUND('',#7032,.F.); +#7032 = EDGE_LOOP('',(#7033)); +#7033 = ORIENTED_EDGE('',*,*,#6710,.T.); +#7034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7038)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#7035,#7036,#7037)) REPRESENTATION_CONTEXT +('Context #1','3D Context with UNIT and UNCERTAINTY') ); +#7035 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#7036 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#7037 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#7038 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7035, + 'distance_accuracy_value','confusion accuracy'); +#7039 = SHAPE_DEFINITION_REPRESENTATION(#7040,#333); +#7040 = PRODUCT_DEFINITION_SHAPE('','',#7041); +#7041 = PRODUCT_DEFINITION('design','',#7042,#7045); +#7042 = PRODUCT_DEFINITION_FORMATION('','',#7043); +#7043 = PRODUCT('Board','Board','',(#7044)); +#7044 = PRODUCT_CONTEXT('',#2,'mechanical'); +#7045 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#7046 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7047,#7049); +#7047 = ( REPRESENTATION_RELATIONSHIP('','',#333,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7048) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#7048 = ITEM_DEFINED_TRANSFORMATION('','',#11,#15); +#7049 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #7050); +#7050 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('234','=>[0:1:1:2]','',#5,#7041,$ + ); +#7051 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7043)); +#7052 = SHAPE_DEFINITION_REPRESENTATION(#7053,#7059); +#7053 = PRODUCT_DEFINITION_SHAPE('','',#7054); +#7054 = PRODUCT_DEFINITION('design','',#7055,#7058); +#7055 = PRODUCT_DEFINITION_FORMATION('','',#7056); +#7056 = PRODUCT('FIL1','FIL1','',(#7057)); +#7057 = PRODUCT_CONTEXT('',#2,'mechanical'); +#7058 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#7059 = SHAPE_REPRESENTATION('',(#11,#7060),#7064); +#7060 = AXIS2_PLACEMENT_3D('',#7061,#7062,#7063); +#7061 = CARTESIAN_POINT('',(8.636,29.21,-2.62910066)); +#7062 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7063 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7068)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#7065,#7066,#7067)) REPRESENTATION_CONTEXT +('Context #1','3D Context with UNIT and UNCERTAINTY') ); +#7065 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#7066 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#7067 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#7068 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7065, + 'distance_accuracy_value','confusion accuracy'); +#7069 = SHAPE_DEFINITION_REPRESENTATION(#7070,#7076); +#7070 = PRODUCT_DEFINITION_SHAPE('','',#7071); +#7071 = PRODUCT_DEFINITION('design','',#7072,#7075); +#7072 = PRODUCT_DEFINITION_FORMATION('','',#7073); +#7073 = PRODUCT('549180064','549180064','',(#7074)); +#7074 = PRODUCT_CONTEXT('',#2,'mechanical'); +#7075 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#7076 = SHAPE_REPRESENTATION('',(#11,#7077),#7081); +#7077 = AXIS2_PLACEMENT_3D('',#7078,#7079,#7080); +#7078 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#7079 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7080 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7085)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#7082,#7083,#7084)) REPRESENTATION_CONTEXT +('Context #1','3D Context with UNIT and UNCERTAINTY') ); +#7082 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#7083 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#7084 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#7085 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7082, + 'distance_accuracy_value','confusion accuracy'); +#7086 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#7087),#7417); +#7087 = MANIFOLD_SOLID_BREP('',#7088); +#7088 = CLOSED_SHELL('',(#7089,#7209,#7285,#7356,#7403,#7410)); +#7089 = ADVANCED_FACE('',(#7090),#7104,.F.); +#7090 = FACE_BOUND('',#7091,.F.); +#7091 = EDGE_LOOP('',(#7092,#7127,#7155,#7183)); +#7092 = ORIENTED_EDGE('',*,*,#7093,.T.); +#7093 = EDGE_CURVE('',#7094,#7096,#7098,.T.); +#7094 = VERTEX_POINT('',#7095); +#7095 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#7096 = VERTEX_POINT('',#7097); +#7097 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); +#7098 = SURFACE_CURVE('',#7099,(#7103,#7115),.PCURVE_S1.); +#7099 = LINE('',#7100,#7101); +#7100 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#7101 = VECTOR('',#7102,1.); +#7102 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7103 = PCURVE('',#7104,#7109); +#7104 = PLANE('',#7105); +#7105 = AXIS2_PLACEMENT_3D('',#7106,#7107,#7108); +#7106 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#7107 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7108 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7109 = DEFINITIONAL_REPRESENTATION('',(#7110),#7114); +#7110 = LINE('',#7111,#7112); +#7111 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7112 = VECTOR('',#7113,1.); +#7113 = DIRECTION('',(0.E+000,-1.)); +#7114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7115 = PCURVE('',#7116,#7121); +#7116 = PLANE('',#7117); +#7117 = AXIS2_PLACEMENT_3D('',#7118,#7119,#7120); +#7118 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); +#7119 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7120 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7121 = DEFINITIONAL_REPRESENTATION('',(#7122),#7126); +#7122 = LINE('',#7123,#7124); +#7123 = CARTESIAN_POINT('',(1.60000188,0.E+000)); +#7124 = VECTOR('',#7125,1.); +#7125 = DIRECTION('',(0.E+000,-1.)); +#7126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7127 = ORIENTED_EDGE('',*,*,#7128,.T.); +#7128 = EDGE_CURVE('',#7096,#7129,#7131,.T.); +#7129 = VERTEX_POINT('',#7130); +#7130 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.94)); +#7131 = SURFACE_CURVE('',#7132,(#7136,#7143),.PCURVE_S1.); +#7132 = LINE('',#7133,#7134); +#7133 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); +#7134 = VECTOR('',#7135,1.); +#7135 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7136 = PCURVE('',#7104,#7137); +#7137 = DEFINITIONAL_REPRESENTATION('',(#7138),#7142); +#7138 = LINE('',#7139,#7140); +#7139 = CARTESIAN_POINT('',(0.E+000,-0.94)); +#7140 = VECTOR('',#7141,1.); +#7141 = DIRECTION('',(1.,0.E+000)); +#7142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7143 = PCURVE('',#7144,#7149); +#7144 = PLANE('',#7145); +#7145 = AXIS2_PLACEMENT_3D('',#7146,#7147,#7148); +#7146 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.94)); +#7147 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7148 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7149 = DEFINITIONAL_REPRESENTATION('',(#7150),#7154); +#7150 = LINE('',#7151,#7152); +#7151 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7152 = VECTOR('',#7153,1.); +#7153 = DIRECTION('',(0.E+000,-1.)); +#7154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7155 = ORIENTED_EDGE('',*,*,#7156,.F.); +#7156 = EDGE_CURVE('',#7157,#7129,#7159,.T.); +#7157 = VERTEX_POINT('',#7158); +#7158 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); +#7159 = SURFACE_CURVE('',#7160,(#7164,#7171),.PCURVE_S1.); +#7160 = LINE('',#7161,#7162); +#7161 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); +#7162 = VECTOR('',#7163,1.); +#7163 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7164 = PCURVE('',#7104,#7165); +#7165 = DEFINITIONAL_REPRESENTATION('',(#7166),#7170); +#7166 = LINE('',#7167,#7168); +#7167 = CARTESIAN_POINT('',(3.19999868,0.E+000)); +#7168 = VECTOR('',#7169,1.); +#7169 = DIRECTION('',(0.E+000,-1.)); +#7170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7171 = PCURVE('',#7172,#7177); +#7172 = PLANE('',#7173); +#7173 = AXIS2_PLACEMENT_3D('',#7174,#7175,#7176); +#7174 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); +#7175 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7176 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7177 = DEFINITIONAL_REPRESENTATION('',(#7178),#7182); +#7178 = LINE('',#7179,#7180); +#7179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7180 = VECTOR('',#7181,1.); +#7181 = DIRECTION('',(0.E+000,-1.)); +#7182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7183 = ORIENTED_EDGE('',*,*,#7184,.F.); +#7184 = EDGE_CURVE('',#7094,#7157,#7185,.T.); +#7185 = SURFACE_CURVE('',#7186,(#7190,#7197),.PCURVE_S1.); +#7186 = LINE('',#7187,#7188); +#7187 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#7188 = VECTOR('',#7189,1.); +#7189 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7190 = PCURVE('',#7104,#7191); +#7191 = DEFINITIONAL_REPRESENTATION('',(#7192),#7196); +#7192 = LINE('',#7193,#7194); +#7193 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7194 = VECTOR('',#7195,1.); +#7195 = DIRECTION('',(1.,0.E+000)); +#7196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7197 = PCURVE('',#7198,#7203); +#7198 = PLANE('',#7199); +#7199 = AXIS2_PLACEMENT_3D('',#7200,#7201,#7202); +#7200 = CARTESIAN_POINT('',(-0.80000094,1.59999934,0.E+000)); +#7201 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7202 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7203 = DEFINITIONAL_REPRESENTATION('',(#7204),#7208); +#7204 = LINE('',#7205,#7206); +#7205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7206 = VECTOR('',#7207,1.); +#7207 = DIRECTION('',(0.E+000,-1.)); +#7208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7209 = ADVANCED_FACE('',(#7210),#7172,.F.); +#7210 = FACE_BOUND('',#7211,.F.); +#7211 = EDGE_LOOP('',(#7212,#7213,#7236,#7264)); +#7212 = ORIENTED_EDGE('',*,*,#7156,.T.); +#7213 = ORIENTED_EDGE('',*,*,#7214,.T.); +#7214 = EDGE_CURVE('',#7129,#7215,#7217,.T.); +#7215 = VERTEX_POINT('',#7216); +#7216 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.94)); +#7217 = SURFACE_CURVE('',#7218,(#7222,#7229),.PCURVE_S1.); +#7218 = LINE('',#7219,#7220); +#7219 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.94)); +#7220 = VECTOR('',#7221,1.); +#7221 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7222 = PCURVE('',#7172,#7223); +#7223 = DEFINITIONAL_REPRESENTATION('',(#7224),#7228); +#7224 = LINE('',#7225,#7226); +#7225 = CARTESIAN_POINT('',(0.E+000,-0.94)); +#7226 = VECTOR('',#7227,1.); +#7227 = DIRECTION('',(1.,0.E+000)); +#7228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7229 = PCURVE('',#7144,#7230); +#7230 = DEFINITIONAL_REPRESENTATION('',(#7231),#7235); +#7231 = LINE('',#7232,#7233); +#7232 = CARTESIAN_POINT('',(0.E+000,-3.19999868)); +#7233 = VECTOR('',#7234,1.); +#7234 = DIRECTION('',(-1.,0.E+000)); +#7235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7236 = ORIENTED_EDGE('',*,*,#7237,.F.); +#7237 = EDGE_CURVE('',#7238,#7215,#7240,.T.); +#7238 = VERTEX_POINT('',#7239); +#7239 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); +#7240 = SURFACE_CURVE('',#7241,(#7245,#7252),.PCURVE_S1.); +#7241 = LINE('',#7242,#7243); +#7242 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); +#7243 = VECTOR('',#7244,1.); +#7244 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7245 = PCURVE('',#7172,#7246); +#7246 = DEFINITIONAL_REPRESENTATION('',(#7247),#7251); +#7247 = LINE('',#7248,#7249); +#7248 = CARTESIAN_POINT('',(1.60000188,0.E+000)); +#7249 = VECTOR('',#7250,1.); +#7250 = DIRECTION('',(0.E+000,-1.)); +#7251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7252 = PCURVE('',#7253,#7258); +#7253 = PLANE('',#7254); +#7254 = AXIS2_PLACEMENT_3D('',#7255,#7256,#7257); +#7255 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); +#7256 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7257 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7258 = DEFINITIONAL_REPRESENTATION('',(#7259),#7263); +#7259 = LINE('',#7260,#7261); +#7260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7261 = VECTOR('',#7262,1.); +#7262 = DIRECTION('',(0.E+000,-1.)); +#7263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7264 = ORIENTED_EDGE('',*,*,#7265,.F.); +#7265 = EDGE_CURVE('',#7157,#7238,#7266,.T.); +#7266 = SURFACE_CURVE('',#7267,(#7271,#7278),.PCURVE_S1.); +#7267 = LINE('',#7268,#7269); +#7268 = CARTESIAN_POINT('',(-0.80000094,-1.59999934,0.E+000)); +#7269 = VECTOR('',#7270,1.); +#7270 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7271 = PCURVE('',#7172,#7272); +#7272 = DEFINITIONAL_REPRESENTATION('',(#7273),#7277); +#7273 = LINE('',#7274,#7275); +#7274 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7275 = VECTOR('',#7276,1.); +#7276 = DIRECTION('',(1.,0.E+000)); +#7277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7278 = PCURVE('',#7198,#7279); +#7279 = DEFINITIONAL_REPRESENTATION('',(#7280),#7284); +#7280 = LINE('',#7281,#7282); +#7281 = CARTESIAN_POINT('',(0.E+000,-3.19999868)); +#7282 = VECTOR('',#7283,1.); +#7283 = DIRECTION('',(-1.,0.E+000)); +#7284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7285 = ADVANCED_FACE('',(#7286),#7253,.F.); +#7286 = FACE_BOUND('',#7287,.F.); +#7287 = EDGE_LOOP('',(#7288,#7289,#7312,#7335)); +#7288 = ORIENTED_EDGE('',*,*,#7237,.T.); +#7289 = ORIENTED_EDGE('',*,*,#7290,.T.); +#7290 = EDGE_CURVE('',#7215,#7291,#7293,.T.); +#7291 = VERTEX_POINT('',#7292); +#7292 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.94)); +#7293 = SURFACE_CURVE('',#7294,(#7298,#7305),.PCURVE_S1.); +#7294 = LINE('',#7295,#7296); +#7295 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.94)); +#7296 = VECTOR('',#7297,1.); +#7297 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7298 = PCURVE('',#7253,#7299); +#7299 = DEFINITIONAL_REPRESENTATION('',(#7300),#7304); +#7300 = LINE('',#7301,#7302); +#7301 = CARTESIAN_POINT('',(0.E+000,-0.94)); +#7302 = VECTOR('',#7303,1.); +#7303 = DIRECTION('',(1.,0.E+000)); +#7304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7305 = PCURVE('',#7144,#7306); +#7306 = DEFINITIONAL_REPRESENTATION('',(#7307),#7311); +#7307 = LINE('',#7308,#7309); +#7308 = CARTESIAN_POINT('',(-1.60000188,-3.19999868)); +#7309 = VECTOR('',#7310,1.); +#7310 = DIRECTION('',(0.E+000,1.)); +#7311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7312 = ORIENTED_EDGE('',*,*,#7313,.F.); +#7313 = EDGE_CURVE('',#7314,#7291,#7316,.T.); +#7314 = VERTEX_POINT('',#7315); +#7315 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); +#7316 = SURFACE_CURVE('',#7317,(#7321,#7328),.PCURVE_S1.); +#7317 = LINE('',#7318,#7319); +#7318 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); +#7319 = VECTOR('',#7320,1.); +#7320 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7321 = PCURVE('',#7253,#7322); +#7322 = DEFINITIONAL_REPRESENTATION('',(#7323),#7327); +#7323 = LINE('',#7324,#7325); +#7324 = CARTESIAN_POINT('',(3.19999868,0.E+000)); +#7325 = VECTOR('',#7326,1.); +#7326 = DIRECTION('',(0.E+000,-1.)); +#7327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7328 = PCURVE('',#7116,#7329); +#7329 = DEFINITIONAL_REPRESENTATION('',(#7330),#7334); +#7330 = LINE('',#7331,#7332); +#7331 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7332 = VECTOR('',#7333,1.); +#7333 = DIRECTION('',(0.E+000,-1.)); +#7334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7335 = ORIENTED_EDGE('',*,*,#7336,.F.); +#7336 = EDGE_CURVE('',#7238,#7314,#7337,.T.); +#7337 = SURFACE_CURVE('',#7338,(#7342,#7349),.PCURVE_S1.); +#7338 = LINE('',#7339,#7340); +#7339 = CARTESIAN_POINT('',(0.80000094,-1.59999934,0.E+000)); +#7340 = VECTOR('',#7341,1.); +#7341 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7342 = PCURVE('',#7253,#7343); +#7343 = DEFINITIONAL_REPRESENTATION('',(#7344),#7348); +#7344 = LINE('',#7345,#7346); +#7345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7346 = VECTOR('',#7347,1.); +#7347 = DIRECTION('',(1.,0.E+000)); +#7348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7349 = PCURVE('',#7198,#7350); +#7350 = DEFINITIONAL_REPRESENTATION('',(#7351),#7355); +#7351 = LINE('',#7352,#7353); +#7352 = CARTESIAN_POINT('',(-1.60000188,-3.19999868)); +#7353 = VECTOR('',#7354,1.); +#7354 = DIRECTION('',(0.E+000,1.)); +#7355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7356 = ADVANCED_FACE('',(#7357),#7116,.F.); +#7357 = FACE_BOUND('',#7358,.F.); +#7358 = EDGE_LOOP('',(#7359,#7360,#7381,#7382)); +#7359 = ORIENTED_EDGE('',*,*,#7313,.T.); +#7360 = ORIENTED_EDGE('',*,*,#7361,.T.); +#7361 = EDGE_CURVE('',#7291,#7096,#7362,.T.); +#7362 = SURFACE_CURVE('',#7363,(#7367,#7374),.PCURVE_S1.); +#7363 = LINE('',#7364,#7365); +#7364 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.94)); +#7365 = VECTOR('',#7366,1.); +#7366 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7367 = PCURVE('',#7116,#7368); +#7368 = DEFINITIONAL_REPRESENTATION('',(#7369),#7373); +#7369 = LINE('',#7370,#7371); +#7370 = CARTESIAN_POINT('',(0.E+000,-0.94)); +#7371 = VECTOR('',#7372,1.); +#7372 = DIRECTION('',(1.,0.E+000)); +#7373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7374 = PCURVE('',#7144,#7375); +#7375 = DEFINITIONAL_REPRESENTATION('',(#7376),#7380); +#7376 = LINE('',#7377,#7378); +#7377 = CARTESIAN_POINT('',(-1.60000188,0.E+000)); +#7378 = VECTOR('',#7379,1.); +#7379 = DIRECTION('',(1.,0.E+000)); +#7380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7381 = ORIENTED_EDGE('',*,*,#7093,.F.); +#7382 = ORIENTED_EDGE('',*,*,#7383,.F.); +#7383 = EDGE_CURVE('',#7314,#7094,#7384,.T.); +#7384 = SURFACE_CURVE('',#7385,(#7389,#7396),.PCURVE_S1.); +#7385 = LINE('',#7386,#7387); +#7386 = CARTESIAN_POINT('',(0.80000094,1.59999934,0.E+000)); +#7387 = VECTOR('',#7388,1.); +#7388 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7389 = PCURVE('',#7116,#7390); +#7390 = DEFINITIONAL_REPRESENTATION('',(#7391),#7395); +#7391 = LINE('',#7392,#7393); +#7392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7393 = VECTOR('',#7394,1.); +#7394 = DIRECTION('',(1.,0.E+000)); +#7395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7396 = PCURVE('',#7198,#7397); +#7397 = DEFINITIONAL_REPRESENTATION('',(#7398),#7402); +#7398 = LINE('',#7399,#7400); +#7399 = CARTESIAN_POINT('',(-1.60000188,0.E+000)); +#7400 = VECTOR('',#7401,1.); +#7401 = DIRECTION('',(1.,0.E+000)); +#7402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7403 = ADVANCED_FACE('',(#7404),#7198,.T.); +#7404 = FACE_BOUND('',#7405,.F.); +#7405 = EDGE_LOOP('',(#7406,#7407,#7408,#7409)); +#7406 = ORIENTED_EDGE('',*,*,#7184,.T.); +#7407 = ORIENTED_EDGE('',*,*,#7265,.T.); +#7408 = ORIENTED_EDGE('',*,*,#7336,.T.); +#7409 = ORIENTED_EDGE('',*,*,#7383,.T.); +#7410 = ADVANCED_FACE('',(#7411),#7144,.F.); +#7411 = FACE_BOUND('',#7412,.T.); +#7412 = EDGE_LOOP('',(#7413,#7414,#7415,#7416)); +#7413 = ORIENTED_EDGE('',*,*,#7128,.T.); +#7414 = ORIENTED_EDGE('',*,*,#7214,.T.); +#7415 = ORIENTED_EDGE('',*,*,#7290,.T.); +#7416 = ORIENTED_EDGE('',*,*,#7361,.T.); +#7417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7421)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#7418,#7419,#7420)) REPRESENTATION_CONTEXT +('Context #1','3D Context with UNIT and UNCERTAINTY') ); +#7418 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#7419 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#7420 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#7421 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7418, + 'distance_accuracy_value','confusion accuracy'); +#7422 = SHAPE_DEFINITION_REPRESENTATION(#7423,#7086); +#7423 = PRODUCT_DEFINITION_SHAPE('','',#7424); +#7424 = PRODUCT_DEFINITION('design','',#7425,#7428); +#7425 = PRODUCT_DEFINITION_FORMATION('','',#7426); +#7426 = PRODUCT('Extruded','Extruded','',(#7427)); +#7427 = PRODUCT_CONTEXT('',#2,'mechanical'); +#7428 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#7429 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7430,#7432); +#7430 = ( REPRESENTATION_RELATIONSHIP('','',#7086,#7076) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7431) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#7431 = ITEM_DEFINED_TRANSFORMATION('','',#11,#7077); +#7432 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #7433); +#7433 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('235','=>[0:1:1:2]','',#7071, + #7424,$); +#7434 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7426)); +#7435 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7436,#7438); +#7436 = ( REPRESENTATION_RELATIONSHIP('','',#7076,#7059) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7437) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#7437 = ITEM_DEFINED_TRANSFORMATION('','',#11,#7060); +#7438 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #7439); +#7439 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('236','=>[0:1:1:4]','',#7054, + #7071,$); +#7440 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7073)); +#7441 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7442,#7444); +#7442 = ( REPRESENTATION_RELATIONSHIP('','',#7059,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7443) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#7443 = ITEM_DEFINED_TRANSFORMATION('','',#11,#19); +#7444 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #7445); +#7445 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('237','=>[0:1:1:3]','',#5,#7054,$ + ); +#7446 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7056)); +#7447 = SHAPE_DEFINITION_REPRESENTATION(#7448,#7454); +#7448 = PRODUCT_DEFINITION_SHAPE('','',#7449); +#7449 = PRODUCT_DEFINITION('design','',#7450,#7453); +#7450 = PRODUCT_DEFINITION_FORMATION('','',#7451); +#7451 = PRODUCT('R8','R8','',(#7452)); +#7452 = PRODUCT_CONTEXT('',#2,'mechanical'); +#7453 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#7454 = SHAPE_REPRESENTATION('',(#11,#7455),#7459); +#7455 = AXIS2_PLACEMENT_3D('',#7456,#7457,#7458); +#7456 = CARTESIAN_POINT('',(14.6090005,6.35,-1.27E-002)); +#7457 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7458 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#7459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7463)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#7460,#7461,#7462)) REPRESENTATION_CONTEXT +('Context #1','3D Context with UNIT and UNCERTAINTY') ); +#7460 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#7461 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#7462 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#7463 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7460, + 'distance_accuracy_value','confusion accuracy'); +#7464 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#7465),#9847); +#7465 = MANIFOLD_SOLID_BREP('',#7466); +#7466 = CLOSED_SHELL('',(#7467,#7587,#7697,#7873,#8039,#8096,#8172,#8243 + ,#8426,#8541,#8568,#8595,#8700,#8771,#8820,#8891,#8965,#8976,#8987, + #9058,#9129,#9156,#9183,#9254,#9332,#9408,#9479,#9553,#9564,#9575, + #9607,#9639,#9715,#9764,#9813,#9840)); +#7467 = ADVANCED_FACE('',(#7468),#7482,.T.); +#7468 = FACE_BOUND('',#7469,.T.); +#7469 = EDGE_LOOP('',(#7470,#7505,#7533,#7561)); +#7470 = ORIENTED_EDGE('',*,*,#7471,.T.); +#7471 = EDGE_CURVE('',#7472,#7474,#7476,.T.); +#7472 = VERTEX_POINT('',#7473); +#7473 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); +#7474 = VERTEX_POINT('',#7475); +#7475 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); +#7476 = SURFACE_CURVE('',#7477,(#7481,#7493),.PCURVE_S1.); +#7477 = LINE('',#7478,#7479); +#7478 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); +#7479 = VECTOR('',#7480,1.); +#7480 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7481 = PCURVE('',#7482,#7487); +#7482 = PLANE('',#7483); +#7483 = AXIS2_PLACEMENT_3D('',#7484,#7485,#7486); +#7484 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#7485 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7486 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7487 = DEFINITIONAL_REPRESENTATION('',(#7488),#7492); +#7488 = LINE('',#7489,#7490); +#7489 = CARTESIAN_POINT('',(4.E-002,5.E-003)); +#7490 = VECTOR('',#7491,1.); +#7491 = DIRECTION('',(-1.,0.E+000)); +#7492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7493 = PCURVE('',#7494,#7499); +#7494 = PLANE('',#7495); +#7495 = AXIS2_PLACEMENT_3D('',#7496,#7497,#7498); +#7496 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); +#7497 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7498 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7499 = DEFINITIONAL_REPRESENTATION('',(#7500),#7504); +#7500 = LINE('',#7501,#7502); +#7501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7502 = VECTOR('',#7503,1.); +#7503 = DIRECTION('',(-1.,0.E+000)); +#7504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7505 = ORIENTED_EDGE('',*,*,#7506,.F.); +#7506 = EDGE_CURVE('',#7507,#7474,#7509,.T.); +#7507 = VERTEX_POINT('',#7508); +#7508 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#7509 = SURFACE_CURVE('',#7510,(#7514,#7521),.PCURVE_S1.); +#7510 = LINE('',#7511,#7512); +#7511 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#7512 = VECTOR('',#7513,1.); +#7513 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7514 = PCURVE('',#7482,#7515); +#7515 = DEFINITIONAL_REPRESENTATION('',(#7516),#7520); +#7516 = LINE('',#7517,#7518); +#7517 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7518 = VECTOR('',#7519,1.); +#7519 = DIRECTION('',(0.E+000,1.)); +#7520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7521 = PCURVE('',#7522,#7527); +#7522 = PLANE('',#7523); +#7523 = AXIS2_PLACEMENT_3D('',#7524,#7525,#7526); +#7524 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); +#7525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7526 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7527 = DEFINITIONAL_REPRESENTATION('',(#7528),#7532); +#7528 = LINE('',#7529,#7530); +#7529 = CARTESIAN_POINT('',(0.2,0.E+000)); +#7530 = VECTOR('',#7531,1.); +#7531 = DIRECTION('',(0.E+000,1.)); +#7532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7533 = ORIENTED_EDGE('',*,*,#7534,.T.); +#7534 = EDGE_CURVE('',#7507,#7535,#7537,.T.); +#7535 = VERTEX_POINT('',#7536); +#7536 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#7537 = SURFACE_CURVE('',#7538,(#7542,#7549),.PCURVE_S1.); +#7538 = LINE('',#7539,#7540); +#7539 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#7540 = VECTOR('',#7541,1.); +#7541 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7542 = PCURVE('',#7482,#7543); +#7543 = DEFINITIONAL_REPRESENTATION('',(#7544),#7548); +#7544 = LINE('',#7545,#7546); +#7545 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7546 = VECTOR('',#7547,1.); +#7547 = DIRECTION('',(1.,0.E+000)); +#7548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7549 = PCURVE('',#7550,#7555); +#7550 = PLANE('',#7551); +#7551 = AXIS2_PLACEMENT_3D('',#7552,#7553,#7554); +#7552 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); +#7553 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7554 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7555 = DEFINITIONAL_REPRESENTATION('',(#7556),#7560); +#7556 = LINE('',#7557,#7558); +#7557 = CARTESIAN_POINT('',(0.E+000,0.2)); +#7558 = VECTOR('',#7559,1.); +#7559 = DIRECTION('',(-1.,0.E+000)); +#7560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7561 = ORIENTED_EDGE('',*,*,#7562,.T.); +#7562 = EDGE_CURVE('',#7535,#7472,#7563,.T.); +#7563 = SURFACE_CURVE('',#7564,(#7568,#7575),.PCURVE_S1.); +#7564 = LINE('',#7565,#7566); +#7565 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#7566 = VECTOR('',#7567,1.); +#7567 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7568 = PCURVE('',#7482,#7569); +#7569 = DEFINITIONAL_REPRESENTATION('',(#7570),#7574); +#7570 = LINE('',#7571,#7572); +#7571 = CARTESIAN_POINT('',(4.E-002,0.E+000)); +#7572 = VECTOR('',#7573,1.); +#7573 = DIRECTION('',(0.E+000,1.)); +#7574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7575 = PCURVE('',#7576,#7581); +#7576 = PLANE('',#7577); +#7577 = AXIS2_PLACEMENT_3D('',#7578,#7579,#7580); +#7578 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#7579 = DIRECTION('',(-1.694065894509E-016,0.E+000,-1.)); +#7580 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); +#7581 = DEFINITIONAL_REPRESENTATION('',(#7582),#7586); +#7582 = LINE('',#7583,#7584); +#7583 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7584 = VECTOR('',#7585,1.); +#7585 = DIRECTION('',(0.E+000,1.)); +#7586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7587 = ADVANCED_FACE('',(#7588),#7602,.T.); +#7588 = FACE_BOUND('',#7589,.T.); +#7589 = EDGE_LOOP('',(#7590,#7620,#7643,#7671)); +#7590 = ORIENTED_EDGE('',*,*,#7591,.F.); +#7591 = EDGE_CURVE('',#7592,#7594,#7596,.T.); +#7592 = VERTEX_POINT('',#7593); +#7593 = CARTESIAN_POINT('',(0.3,-0.245,0.24)); +#7594 = VERTEX_POINT('',#7595); +#7595 = CARTESIAN_POINT('',(0.3,-0.245,0.28)); +#7596 = SURFACE_CURVE('',#7597,(#7601,#7613),.PCURVE_S1.); +#7597 = LINE('',#7598,#7599); +#7598 = CARTESIAN_POINT('',(0.3,-0.245,0.24)); +#7599 = VECTOR('',#7600,1.); +#7600 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7601 = PCURVE('',#7602,#7607); +#7602 = PLANE('',#7603); +#7603 = AXIS2_PLACEMENT_3D('',#7604,#7605,#7606); +#7604 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#7605 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7606 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7607 = DEFINITIONAL_REPRESENTATION('',(#7608),#7612); +#7608 = LINE('',#7609,#7610); +#7609 = CARTESIAN_POINT('',(-4.E-002,5.E-003)); +#7610 = VECTOR('',#7611,1.); +#7611 = DIRECTION('',(1.,0.E+000)); +#7612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7613 = PCURVE('',#7494,#7614); +#7614 = DEFINITIONAL_REPRESENTATION('',(#7615),#7619); +#7615 = LINE('',#7616,#7617); +#7616 = CARTESIAN_POINT('',(0.E+000,0.6)); +#7617 = VECTOR('',#7618,1.); +#7618 = DIRECTION('',(-1.,0.E+000)); +#7619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7620 = ORIENTED_EDGE('',*,*,#7621,.F.); +#7621 = EDGE_CURVE('',#7622,#7592,#7624,.T.); +#7622 = VERTEX_POINT('',#7623); +#7623 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); +#7624 = SURFACE_CURVE('',#7625,(#7629,#7636),.PCURVE_S1.); +#7625 = LINE('',#7626,#7627); +#7626 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); +#7627 = VECTOR('',#7628,1.); +#7628 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7629 = PCURVE('',#7602,#7630); +#7630 = DEFINITIONAL_REPRESENTATION('',(#7631),#7635); +#7631 = LINE('',#7632,#7633); +#7632 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#7633 = VECTOR('',#7634,1.); +#7634 = DIRECTION('',(0.E+000,1.)); +#7635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7636 = PCURVE('',#7576,#7637); +#7637 = DEFINITIONAL_REPRESENTATION('',(#7638),#7642); +#7638 = LINE('',#7639,#7640); +#7639 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#7640 = VECTOR('',#7641,1.); +#7641 = DIRECTION('',(0.E+000,1.)); +#7642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7643 = ORIENTED_EDGE('',*,*,#7644,.T.); +#7644 = EDGE_CURVE('',#7622,#7645,#7647,.T.); +#7645 = VERTEX_POINT('',#7646); +#7646 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#7647 = SURFACE_CURVE('',#7648,(#7652,#7659),.PCURVE_S1.); +#7648 = LINE('',#7649,#7650); +#7649 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#7650 = VECTOR('',#7651,1.); +#7651 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7652 = PCURVE('',#7602,#7653); +#7653 = DEFINITIONAL_REPRESENTATION('',(#7654),#7658); +#7654 = LINE('',#7655,#7656); +#7655 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7656 = VECTOR('',#7657,1.); +#7657 = DIRECTION('',(1.,0.E+000)); +#7658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7659 = PCURVE('',#7660,#7665); +#7660 = PLANE('',#7661); +#7661 = AXIS2_PLACEMENT_3D('',#7662,#7663,#7664); +#7662 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); +#7663 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7664 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7665 = DEFINITIONAL_REPRESENTATION('',(#7666),#7670); +#7666 = LINE('',#7667,#7668); +#7667 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#7668 = VECTOR('',#7669,1.); +#7669 = DIRECTION('',(-1.,0.E+000)); +#7670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7671 = ORIENTED_EDGE('',*,*,#7672,.T.); +#7672 = EDGE_CURVE('',#7645,#7594,#7673,.T.); +#7673 = SURFACE_CURVE('',#7674,(#7678,#7685),.PCURVE_S1.); +#7674 = LINE('',#7675,#7676); +#7675 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#7676 = VECTOR('',#7677,1.); +#7677 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7678 = PCURVE('',#7602,#7679); +#7679 = DEFINITIONAL_REPRESENTATION('',(#7680),#7684); +#7680 = LINE('',#7681,#7682); +#7681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7682 = VECTOR('',#7683,1.); +#7683 = DIRECTION('',(0.E+000,1.)); +#7684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7685 = PCURVE('',#7686,#7691); +#7686 = PLANE('',#7687); +#7687 = AXIS2_PLACEMENT_3D('',#7688,#7689,#7690); +#7688 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); +#7689 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7690 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7691 = DEFINITIONAL_REPRESENTATION('',(#7692),#7696); +#7692 = LINE('',#7693,#7694); +#7693 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#7694 = VECTOR('',#7695,1.); +#7695 = DIRECTION('',(0.E+000,1.)); +#7696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7697 = ADVANCED_FACE('',(#7698),#7712,.F.); +#7698 = FACE_BOUND('',#7699,.T.); +#7699 = EDGE_LOOP('',(#7700,#7735,#7763,#7791,#7819,#7847)); +#7700 = ORIENTED_EDGE('',*,*,#7701,.T.); +#7701 = EDGE_CURVE('',#7702,#7704,#7706,.T.); +#7702 = VERTEX_POINT('',#7703); +#7703 = CARTESIAN_POINT('',(0.46,0.24,4.E-002)); +#7704 = VERTEX_POINT('',#7705); +#7705 = CARTESIAN_POINT('',(0.3,0.24,4.E-002)); +#7706 = SURFACE_CURVE('',#7707,(#7711,#7723),.PCURVE_S1.); +#7707 = LINE('',#7708,#7709); +#7708 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); +#7709 = VECTOR('',#7710,1.); +#7710 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7711 = PCURVE('',#7712,#7717); +#7712 = PLANE('',#7713); +#7713 = AXIS2_PLACEMENT_3D('',#7714,#7715,#7716); +#7714 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); +#7715 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#7716 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7717 = DEFINITIONAL_REPRESENTATION('',(#7718),#7722); +#7718 = LINE('',#7719,#7720); +#7719 = CARTESIAN_POINT('',(0.2,0.E+000)); +#7720 = VECTOR('',#7721,1.); +#7721 = DIRECTION('',(0.E+000,-1.)); +#7722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7723 = PCURVE('',#7724,#7729); +#7724 = PLANE('',#7725); +#7725 = AXIS2_PLACEMENT_3D('',#7726,#7727,#7728); +#7726 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#7727 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7728 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7729 = DEFINITIONAL_REPRESENTATION('',(#7730),#7734); +#7730 = LINE('',#7731,#7732); +#7731 = CARTESIAN_POINT('',(-0.92,0.49)); +#7732 = VECTOR('',#7733,1.); +#7733 = DIRECTION('',(-1.,0.E+000)); +#7734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7735 = ORIENTED_EDGE('',*,*,#7736,.T.); +#7736 = EDGE_CURVE('',#7704,#7737,#7739,.T.); +#7737 = VERTEX_POINT('',#7738); +#7738 = CARTESIAN_POINT('',(-0.3,0.24,4.E-002)); +#7739 = SURFACE_CURVE('',#7740,(#7744,#7751),.PCURVE_S1.); +#7740 = LINE('',#7741,#7742); +#7741 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); +#7742 = VECTOR('',#7743,1.); +#7743 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7744 = PCURVE('',#7712,#7745); +#7745 = DEFINITIONAL_REPRESENTATION('',(#7746),#7750); +#7746 = LINE('',#7747,#7748); +#7747 = CARTESIAN_POINT('',(0.2,0.E+000)); +#7748 = VECTOR('',#7749,1.); +#7749 = DIRECTION('',(0.E+000,-1.)); +#7750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7751 = PCURVE('',#7752,#7757); +#7752 = PLANE('',#7753); +#7753 = AXIS2_PLACEMENT_3D('',#7754,#7755,#7756); +#7754 = CARTESIAN_POINT('',(0.46,-0.24,4.E-002)); +#7755 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7756 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7757 = DEFINITIONAL_REPRESENTATION('',(#7758),#7762); +#7758 = LINE('',#7759,#7760); +#7759 = CARTESIAN_POINT('',(-0.92,0.48)); +#7760 = VECTOR('',#7761,1.); +#7761 = DIRECTION('',(-1.,0.E+000)); +#7762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7763 = ORIENTED_EDGE('',*,*,#7764,.T.); +#7764 = EDGE_CURVE('',#7737,#7765,#7767,.T.); +#7765 = VERTEX_POINT('',#7766); +#7766 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); +#7767 = SURFACE_CURVE('',#7768,(#7772,#7779),.PCURVE_S1.); +#7768 = LINE('',#7769,#7770); +#7769 = CARTESIAN_POINT('',(-0.46,0.24,4.E-002)); +#7770 = VECTOR('',#7771,1.); +#7771 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7772 = PCURVE('',#7712,#7773); +#7773 = DEFINITIONAL_REPRESENTATION('',(#7774),#7778); +#7774 = LINE('',#7775,#7776); +#7775 = CARTESIAN_POINT('',(0.2,0.E+000)); +#7776 = VECTOR('',#7777,1.); +#7777 = DIRECTION('',(0.E+000,-1.)); +#7778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7779 = PCURVE('',#7780,#7785); +#7780 = PLANE('',#7781); +#7781 = AXIS2_PLACEMENT_3D('',#7782,#7783,#7784); +#7782 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#7783 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7784 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7785 = DEFINITIONAL_REPRESENTATION('',(#7786),#7790); +#7786 = LINE('',#7787,#7788); +#7787 = CARTESIAN_POINT('',(0.E+000,0.49)); +#7788 = VECTOR('',#7789,1.); +#7789 = DIRECTION('',(-1.,0.E+000)); +#7790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7791 = ORIENTED_EDGE('',*,*,#7792,.F.); +#7792 = EDGE_CURVE('',#7793,#7765,#7795,.T.); +#7793 = VERTEX_POINT('',#7794); +#7794 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); +#7795 = SURFACE_CURVE('',#7796,(#7800,#7807),.PCURVE_S1.); +#7796 = LINE('',#7797,#7798); +#7797 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); +#7798 = VECTOR('',#7799,1.); +#7799 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7800 = PCURVE('',#7712,#7801); +#7801 = DEFINITIONAL_REPRESENTATION('',(#7802),#7806); +#7802 = LINE('',#7803,#7804); +#7803 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7804 = VECTOR('',#7805,1.); +#7805 = DIRECTION('',(1.,0.E+000)); +#7806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7807 = PCURVE('',#7808,#7813); +#7808 = PLANE('',#7809); +#7809 = AXIS2_PLACEMENT_3D('',#7810,#7811,#7812); +#7810 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#7811 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7812 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7813 = DEFINITIONAL_REPRESENTATION('',(#7814),#7818); +#7814 = LINE('',#7815,#7816); +#7815 = CARTESIAN_POINT('',(-0.2,0.49)); +#7816 = VECTOR('',#7817,1.); +#7817 = DIRECTION('',(1.,0.E+000)); +#7818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7819 = ORIENTED_EDGE('',*,*,#7820,.F.); +#7820 = EDGE_CURVE('',#7821,#7793,#7823,.T.); +#7821 = VERTEX_POINT('',#7822); +#7822 = CARTESIAN_POINT('',(0.46,0.24,0.24)); +#7823 = SURFACE_CURVE('',#7824,(#7828,#7835),.PCURVE_S1.); +#7824 = LINE('',#7825,#7826); +#7825 = CARTESIAN_POINT('',(-0.46,0.24,0.24)); +#7826 = VECTOR('',#7827,1.); +#7827 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7828 = PCURVE('',#7712,#7829); +#7829 = DEFINITIONAL_REPRESENTATION('',(#7830),#7834); +#7830 = LINE('',#7831,#7832); +#7831 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#7832 = VECTOR('',#7833,1.); +#7833 = DIRECTION('',(0.E+000,-1.)); +#7834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7835 = PCURVE('',#7836,#7841); +#7836 = PLANE('',#7837); +#7837 = AXIS2_PLACEMENT_3D('',#7838,#7839,#7840); +#7838 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#7839 = DIRECTION('',(-1.694065894509E-016,0.E+000,-1.)); +#7840 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); +#7841 = DEFINITIONAL_REPRESENTATION('',(#7842),#7846); +#7842 = LINE('',#7843,#7844); +#7843 = CARTESIAN_POINT('',(0.16,0.49)); +#7844 = VECTOR('',#7845,1.); +#7845 = DIRECTION('',(1.,0.E+000)); +#7846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7847 = ORIENTED_EDGE('',*,*,#7848,.T.); +#7848 = EDGE_CURVE('',#7821,#7702,#7849,.T.); +#7849 = SURFACE_CURVE('',#7850,(#7854,#7861),.PCURVE_S1.); +#7850 = LINE('',#7851,#7852); +#7851 = CARTESIAN_POINT('',(0.46,0.24,0.24)); +#7852 = VECTOR('',#7853,1.); +#7853 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7854 = PCURVE('',#7712,#7855); +#7855 = DEFINITIONAL_REPRESENTATION('',(#7856),#7860); +#7856 = LINE('',#7857,#7858); +#7857 = CARTESIAN_POINT('',(0.E+000,0.92)); +#7858 = VECTOR('',#7859,1.); +#7859 = DIRECTION('',(1.,0.E+000)); +#7860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7861 = PCURVE('',#7862,#7867); +#7862 = PLANE('',#7863); +#7863 = AXIS2_PLACEMENT_3D('',#7864,#7865,#7866); +#7864 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#7865 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7866 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7867 = DEFINITIONAL_REPRESENTATION('',(#7868),#7872); +#7868 = LINE('',#7869,#7870); +#7869 = CARTESIAN_POINT('',(0.2,0.49)); +#7870 = VECTOR('',#7871,1.); +#7871 = DIRECTION('',(-1.,0.E+000)); +#7872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7873 = ADVANCED_FACE('',(#7874),#7888,.F.); +#7874 = FACE_BOUND('',#7875,.T.); +#7875 = EDGE_LOOP('',(#7876,#7911,#7934,#7962,#7990,#8013)); +#7876 = ORIENTED_EDGE('',*,*,#7877,.T.); +#7877 = EDGE_CURVE('',#7878,#7880,#7882,.T.); +#7878 = VERTEX_POINT('',#7879); +#7879 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); +#7880 = VERTEX_POINT('',#7881); +#7881 = CARTESIAN_POINT('',(-0.3,-0.24,4.E-002)); +#7882 = SURFACE_CURVE('',#7883,(#7887,#7899),.PCURVE_S1.); +#7883 = LINE('',#7884,#7885); +#7884 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); +#7885 = VECTOR('',#7886,1.); +#7886 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7887 = PCURVE('',#7888,#7893); +#7888 = PLANE('',#7889); +#7889 = AXIS2_PLACEMENT_3D('',#7890,#7891,#7892); +#7890 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); +#7891 = DIRECTION('',(0.E+000,1.,0.E+000)); +#7892 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7893 = DEFINITIONAL_REPRESENTATION('',(#7894),#7898); +#7894 = LINE('',#7895,#7896); +#7895 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#7896 = VECTOR('',#7897,1.); +#7897 = DIRECTION('',(0.E+000,1.)); +#7898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7899 = PCURVE('',#7900,#7905); +#7900 = PLANE('',#7901); +#7901 = AXIS2_PLACEMENT_3D('',#7902,#7903,#7904); +#7902 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#7903 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7904 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7905 = DEFINITIONAL_REPRESENTATION('',(#7906),#7910); +#7906 = LINE('',#7907,#7908); +#7907 = CARTESIAN_POINT('',(1.110223024625E-016,1.E-002)); +#7908 = VECTOR('',#7909,1.); +#7909 = DIRECTION('',(1.,0.E+000)); +#7910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7911 = ORIENTED_EDGE('',*,*,#7912,.T.); +#7912 = EDGE_CURVE('',#7880,#7913,#7915,.T.); +#7913 = VERTEX_POINT('',#7914); +#7914 = CARTESIAN_POINT('',(0.3,-0.24,4.E-002)); +#7915 = SURFACE_CURVE('',#7916,(#7920,#7927),.PCURVE_S1.); +#7916 = LINE('',#7917,#7918); +#7917 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); +#7918 = VECTOR('',#7919,1.); +#7919 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7920 = PCURVE('',#7888,#7921); +#7921 = DEFINITIONAL_REPRESENTATION('',(#7922),#7926); +#7922 = LINE('',#7923,#7924); +#7923 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#7924 = VECTOR('',#7925,1.); +#7925 = DIRECTION('',(0.E+000,1.)); +#7926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7927 = PCURVE('',#7752,#7928); +#7928 = DEFINITIONAL_REPRESENTATION('',(#7929),#7933); +#7929 = LINE('',#7930,#7931); +#7930 = CARTESIAN_POINT('',(-0.92,0.E+000)); +#7931 = VECTOR('',#7932,1.); +#7932 = DIRECTION('',(1.,0.E+000)); +#7933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7934 = ORIENTED_EDGE('',*,*,#7935,.T.); +#7935 = EDGE_CURVE('',#7913,#7936,#7938,.T.); +#7936 = VERTEX_POINT('',#7937); +#7937 = CARTESIAN_POINT('',(0.46,-0.24,4.E-002)); +#7938 = SURFACE_CURVE('',#7939,(#7943,#7950),.PCURVE_S1.); +#7939 = LINE('',#7940,#7941); +#7940 = CARTESIAN_POINT('',(-0.46,-0.24,4.E-002)); +#7941 = VECTOR('',#7942,1.); +#7942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7943 = PCURVE('',#7888,#7944); +#7944 = DEFINITIONAL_REPRESENTATION('',(#7945),#7949); +#7945 = LINE('',#7946,#7947); +#7946 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#7947 = VECTOR('',#7948,1.); +#7948 = DIRECTION('',(0.E+000,1.)); +#7949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7950 = PCURVE('',#7951,#7956); +#7951 = PLANE('',#7952); +#7952 = AXIS2_PLACEMENT_3D('',#7953,#7954,#7955); +#7953 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#7954 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7955 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7956 = DEFINITIONAL_REPRESENTATION('',(#7957),#7961); +#7957 = LINE('',#7958,#7959); +#7958 = CARTESIAN_POINT('',(-0.92,1.E-002)); +#7959 = VECTOR('',#7960,1.); +#7960 = DIRECTION('',(1.,0.E+000)); +#7961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7962 = ORIENTED_EDGE('',*,*,#7963,.F.); +#7963 = EDGE_CURVE('',#7964,#7936,#7966,.T.); +#7964 = VERTEX_POINT('',#7965); +#7965 = CARTESIAN_POINT('',(0.46,-0.24,0.24)); +#7966 = SURFACE_CURVE('',#7967,(#7971,#7978),.PCURVE_S1.); +#7967 = LINE('',#7968,#7969); +#7968 = CARTESIAN_POINT('',(0.46,-0.24,0.24)); +#7969 = VECTOR('',#7970,1.); +#7970 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#7971 = PCURVE('',#7888,#7972); +#7972 = DEFINITIONAL_REPRESENTATION('',(#7973),#7977); +#7973 = LINE('',#7974,#7975); +#7974 = CARTESIAN_POINT('',(0.E+000,0.92)); +#7975 = VECTOR('',#7976,1.); +#7976 = DIRECTION('',(-1.,0.E+000)); +#7977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7978 = PCURVE('',#7979,#7984); +#7979 = PLANE('',#7980); +#7980 = AXIS2_PLACEMENT_3D('',#7981,#7982,#7983); +#7981 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#7982 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#7983 = DIRECTION('',(0.E+000,0.E+000,1.)); +#7984 = DEFINITIONAL_REPRESENTATION('',(#7985),#7989); +#7985 = LINE('',#7986,#7987); +#7986 = CARTESIAN_POINT('',(0.2,1.E-002)); +#7987 = VECTOR('',#7988,1.); +#7988 = DIRECTION('',(-1.,0.E+000)); +#7989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#7990 = ORIENTED_EDGE('',*,*,#7991,.F.); +#7991 = EDGE_CURVE('',#7992,#7964,#7994,.T.); +#7992 = VERTEX_POINT('',#7993); +#7993 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); +#7994 = SURFACE_CURVE('',#7995,(#7999,#8006),.PCURVE_S1.); +#7995 = LINE('',#7996,#7997); +#7996 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); +#7997 = VECTOR('',#7998,1.); +#7998 = DIRECTION('',(1.,0.E+000,0.E+000)); +#7999 = PCURVE('',#7888,#8000); +#8000 = DEFINITIONAL_REPRESENTATION('',(#8001),#8005); +#8001 = LINE('',#8002,#8003); +#8002 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8003 = VECTOR('',#8004,1.); +#8004 = DIRECTION('',(0.E+000,1.)); +#8005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8006 = PCURVE('',#7576,#8007); +#8007 = DEFINITIONAL_REPRESENTATION('',(#8008),#8012); +#8008 = LINE('',#8009,#8010); +#8009 = CARTESIAN_POINT('',(0.16,1.E-002)); +#8010 = VECTOR('',#8011,1.); +#8011 = DIRECTION('',(-1.,0.E+000)); +#8012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8013 = ORIENTED_EDGE('',*,*,#8014,.T.); +#8014 = EDGE_CURVE('',#7992,#7878,#8015,.T.); +#8015 = SURFACE_CURVE('',#8016,(#8020,#8027),.PCURVE_S1.); +#8016 = LINE('',#8017,#8018); +#8017 = CARTESIAN_POINT('',(-0.46,-0.24,0.24)); +#8018 = VECTOR('',#8019,1.); +#8019 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8020 = PCURVE('',#7888,#8021); +#8021 = DEFINITIONAL_REPRESENTATION('',(#8022),#8026); +#8022 = LINE('',#8023,#8024); +#8023 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8024 = VECTOR('',#8025,1.); +#8025 = DIRECTION('',(-1.,0.E+000)); +#8026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8027 = PCURVE('',#8028,#8033); +#8028 = PLANE('',#8029); +#8029 = AXIS2_PLACEMENT_3D('',#8030,#8031,#8032); +#8030 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8031 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8032 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8033 = DEFINITIONAL_REPRESENTATION('',(#8034),#8038); +#8034 = LINE('',#8035,#8036); +#8035 = CARTESIAN_POINT('',(-0.2,1.E-002)); +#8036 = VECTOR('',#8037,1.); +#8037 = DIRECTION('',(1.,0.E+000)); +#8038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8039 = ADVANCED_FACE('',(#8040),#7752,.F.); +#8040 = FACE_BOUND('',#8041,.T.); +#8041 = EDGE_LOOP('',(#8042,#8043,#8069,#8070)); +#8042 = ORIENTED_EDGE('',*,*,#7736,.F.); +#8043 = ORIENTED_EDGE('',*,*,#8044,.T.); +#8044 = EDGE_CURVE('',#7704,#7913,#8045,.T.); +#8045 = SURFACE_CURVE('',#8046,(#8050,#8057),.PCURVE_S1.); +#8046 = LINE('',#8047,#8048); +#8047 = CARTESIAN_POINT('',(0.3,-0.24,4.E-002)); +#8048 = VECTOR('',#8049,1.); +#8049 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#8050 = PCURVE('',#7752,#8051); +#8051 = DEFINITIONAL_REPRESENTATION('',(#8052),#8056); +#8052 = LINE('',#8053,#8054); +#8053 = CARTESIAN_POINT('',(-0.16,0.E+000)); +#8054 = VECTOR('',#8055,1.); +#8055 = DIRECTION('',(0.E+000,-1.)); +#8056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8057 = PCURVE('',#8058,#8063); +#8058 = PLANE('',#8059); +#8059 = AXIS2_PLACEMENT_3D('',#8060,#8061,#8062); +#8060 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); +#8061 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8062 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8063 = DEFINITIONAL_REPRESENTATION('',(#8064),#8068); +#8064 = LINE('',#8065,#8066); +#8065 = CARTESIAN_POINT('',(4.E-002,1.E-002)); +#8066 = VECTOR('',#8067,1.); +#8067 = DIRECTION('',(0.E+000,-1.)); +#8068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8069 = ORIENTED_EDGE('',*,*,#7912,.F.); +#8070 = ORIENTED_EDGE('',*,*,#8071,.T.); +#8071 = EDGE_CURVE('',#7880,#7737,#8072,.T.); +#8072 = SURFACE_CURVE('',#8073,(#8077,#8084),.PCURVE_S1.); +#8073 = LINE('',#8074,#8075); +#8074 = CARTESIAN_POINT('',(-0.3,-0.24,4.E-002)); +#8075 = VECTOR('',#8076,1.); +#8076 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8077 = PCURVE('',#7752,#8078); +#8078 = DEFINITIONAL_REPRESENTATION('',(#8079),#8083); +#8079 = LINE('',#8080,#8081); +#8080 = CARTESIAN_POINT('',(-0.76,0.E+000)); +#8081 = VECTOR('',#8082,1.); +#8082 = DIRECTION('',(0.E+000,1.)); +#8083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8084 = PCURVE('',#8085,#8090); +#8085 = PLANE('',#8086); +#8086 = AXIS2_PLACEMENT_3D('',#8087,#8088,#8089); +#8087 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); +#8088 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8089 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8090 = DEFINITIONAL_REPRESENTATION('',(#8091),#8095); +#8091 = LINE('',#8092,#8093); +#8092 = CARTESIAN_POINT('',(-4.E-002,1.E-002)); +#8093 = VECTOR('',#8094,1.); +#8094 = DIRECTION('',(0.E+000,1.)); +#8095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8096 = ADVANCED_FACE('',(#8097),#7780,.T.); +#8097 = FACE_BOUND('',#8098,.T.); +#8098 = EDGE_LOOP('',(#8099,#8100,#8123,#8151)); +#8099 = ORIENTED_EDGE('',*,*,#7764,.F.); +#8100 = ORIENTED_EDGE('',*,*,#8101,.T.); +#8101 = EDGE_CURVE('',#7737,#8102,#8104,.T.); +#8102 = VERTEX_POINT('',#8103); +#8103 = CARTESIAN_POINT('',(-0.3,0.25,4.E-002)); +#8104 = SURFACE_CURVE('',#8105,(#8109,#8116),.PCURVE_S1.); +#8105 = LINE('',#8106,#8107); +#8106 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); +#8107 = VECTOR('',#8108,1.); +#8108 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8109 = PCURVE('',#7780,#8110); +#8110 = DEFINITIONAL_REPRESENTATION('',(#8111),#8115); +#8111 = LINE('',#8112,#8113); +#8112 = CARTESIAN_POINT('',(0.16,0.E+000)); +#8113 = VECTOR('',#8114,1.); +#8114 = DIRECTION('',(0.E+000,1.)); +#8115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8116 = PCURVE('',#8085,#8117); +#8117 = DEFINITIONAL_REPRESENTATION('',(#8118),#8122); +#8118 = LINE('',#8119,#8120); +#8119 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#8120 = VECTOR('',#8121,1.); +#8121 = DIRECTION('',(0.E+000,1.)); +#8122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8123 = ORIENTED_EDGE('',*,*,#8124,.F.); +#8124 = EDGE_CURVE('',#8125,#8102,#8127,.T.); +#8125 = VERTEX_POINT('',#8126); +#8126 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); +#8127 = SURFACE_CURVE('',#8128,(#8132,#8139),.PCURVE_S1.); +#8128 = LINE('',#8129,#8130); +#8129 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); +#8130 = VECTOR('',#8131,1.); +#8131 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8132 = PCURVE('',#7780,#8133); +#8133 = DEFINITIONAL_REPRESENTATION('',(#8134),#8138); +#8134 = LINE('',#8135,#8136); +#8135 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8136 = VECTOR('',#8137,1.); +#8137 = DIRECTION('',(1.,0.E+000)); +#8138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8139 = PCURVE('',#8140,#8145); +#8140 = PLANE('',#8141); +#8141 = AXIS2_PLACEMENT_3D('',#8142,#8143,#8144); +#8142 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); +#8143 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8144 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8145 = DEFINITIONAL_REPRESENTATION('',(#8146),#8150); +#8146 = LINE('',#8147,#8148); +#8147 = CARTESIAN_POINT('',(-0.24,4.E-002)); +#8148 = VECTOR('',#8149,1.); +#8149 = DIRECTION('',(0.E+000,1.)); +#8150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8151 = ORIENTED_EDGE('',*,*,#8152,.F.); +#8152 = EDGE_CURVE('',#7765,#8125,#8153,.T.); +#8153 = SURFACE_CURVE('',#8154,(#8158,#8165),.PCURVE_S1.); +#8154 = LINE('',#8155,#8156); +#8155 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8156 = VECTOR('',#8157,1.); +#8157 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8158 = PCURVE('',#7780,#8159); +#8159 = DEFINITIONAL_REPRESENTATION('',(#8160),#8164); +#8160 = LINE('',#8161,#8162); +#8161 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8162 = VECTOR('',#8163,1.); +#8163 = DIRECTION('',(0.E+000,1.)); +#8164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8165 = PCURVE('',#7808,#8166); +#8166 = DEFINITIONAL_REPRESENTATION('',(#8167),#8171); +#8167 = LINE('',#8168,#8169); +#8168 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8169 = VECTOR('',#8170,1.); +#8170 = DIRECTION('',(0.E+000,1.)); +#8171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8172 = ADVANCED_FACE('',(#8173),#7900,.T.); +#8173 = FACE_BOUND('',#8174,.T.); +#8174 = EDGE_LOOP('',(#8175,#8176,#8199,#8222)); +#8175 = ORIENTED_EDGE('',*,*,#7877,.F.); +#8176 = ORIENTED_EDGE('',*,*,#8177,.F.); +#8177 = EDGE_CURVE('',#8178,#7878,#8180,.T.); +#8178 = VERTEX_POINT('',#8179); +#8179 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8180 = SURFACE_CURVE('',#8181,(#8185,#8192),.PCURVE_S1.); +#8181 = LINE('',#8182,#8183); +#8182 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8183 = VECTOR('',#8184,1.); +#8184 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8185 = PCURVE('',#7900,#8186); +#8186 = DEFINITIONAL_REPRESENTATION('',(#8187),#8191); +#8187 = LINE('',#8188,#8189); +#8188 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8189 = VECTOR('',#8190,1.); +#8190 = DIRECTION('',(0.E+000,1.)); +#8191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8192 = PCURVE('',#8028,#8193); +#8193 = DEFINITIONAL_REPRESENTATION('',(#8194),#8198); +#8194 = LINE('',#8195,#8196); +#8195 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8196 = VECTOR('',#8197,1.); +#8197 = DIRECTION('',(0.E+000,1.)); +#8198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8199 = ORIENTED_EDGE('',*,*,#8200,.T.); +#8200 = EDGE_CURVE('',#8178,#8201,#8203,.T.); +#8201 = VERTEX_POINT('',#8202); +#8202 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); +#8203 = SURFACE_CURVE('',#8204,(#8208,#8215),.PCURVE_S1.); +#8204 = LINE('',#8205,#8206); +#8205 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8206 = VECTOR('',#8207,1.); +#8207 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8208 = PCURVE('',#7900,#8209); +#8209 = DEFINITIONAL_REPRESENTATION('',(#8210),#8214); +#8210 = LINE('',#8211,#8212); +#8211 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8212 = VECTOR('',#8213,1.); +#8213 = DIRECTION('',(1.,0.E+000)); +#8214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8215 = PCURVE('',#7550,#8216); +#8216 = DEFINITIONAL_REPRESENTATION('',(#8217),#8221); +#8217 = LINE('',#8218,#8219); +#8218 = CARTESIAN_POINT('',(-0.24,4.E-002)); +#8219 = VECTOR('',#8220,1.); +#8220 = DIRECTION('',(0.E+000,1.)); +#8221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8222 = ORIENTED_EDGE('',*,*,#8223,.T.); +#8223 = EDGE_CURVE('',#8201,#7880,#8224,.T.); +#8224 = SURFACE_CURVE('',#8225,(#8229,#8236),.PCURVE_S1.); +#8225 = LINE('',#8226,#8227); +#8226 = CARTESIAN_POINT('',(-0.3,-0.25,4.E-002)); +#8227 = VECTOR('',#8228,1.); +#8228 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8229 = PCURVE('',#7900,#8230); +#8230 = DEFINITIONAL_REPRESENTATION('',(#8231),#8235); +#8231 = LINE('',#8232,#8233); +#8232 = CARTESIAN_POINT('',(0.16,0.E+000)); +#8233 = VECTOR('',#8234,1.); +#8234 = DIRECTION('',(0.E+000,1.)); +#8235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8236 = PCURVE('',#8085,#8237); +#8237 = DEFINITIONAL_REPRESENTATION('',(#8238),#8242); +#8238 = LINE('',#8239,#8240); +#8239 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#8240 = VECTOR('',#8241,1.); +#8241 = DIRECTION('',(0.E+000,1.)); +#8242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8243 = ADVANCED_FACE('',(#8244),#7836,.T.); +#8244 = FACE_BOUND('',#8245,.T.); +#8245 = EDGE_LOOP('',(#8246,#8247,#8270,#8293,#8321,#8349,#8377,#8405)); +#8246 = ORIENTED_EDGE('',*,*,#7820,.T.); +#8247 = ORIENTED_EDGE('',*,*,#8248,.T.); +#8248 = EDGE_CURVE('',#7793,#8249,#8251,.T.); +#8249 = VERTEX_POINT('',#8250); +#8250 = CARTESIAN_POINT('',(-0.46,0.25,0.24)); +#8251 = SURFACE_CURVE('',#8252,(#8256,#8263),.PCURVE_S1.); +#8252 = LINE('',#8253,#8254); +#8253 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); +#8254 = VECTOR('',#8255,1.); +#8255 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8256 = PCURVE('',#7836,#8257); +#8257 = DEFINITIONAL_REPRESENTATION('',(#8258),#8262); +#8258 = LINE('',#8259,#8260); +#8259 = CARTESIAN_POINT('',(0.16,0.E+000)); +#8260 = VECTOR('',#8261,1.); +#8261 = DIRECTION('',(0.E+000,1.)); +#8262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8263 = PCURVE('',#7808,#8264); +#8264 = DEFINITIONAL_REPRESENTATION('',(#8265),#8269); +#8265 = LINE('',#8266,#8267); +#8266 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#8267 = VECTOR('',#8268,1.); +#8268 = DIRECTION('',(0.E+000,1.)); +#8269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8270 = ORIENTED_EDGE('',*,*,#8271,.F.); +#8271 = EDGE_CURVE('',#8272,#8249,#8274,.T.); +#8272 = VERTEX_POINT('',#8273); +#8273 = CARTESIAN_POINT('',(-0.3,0.25,0.24)); +#8274 = SURFACE_CURVE('',#8275,(#8279,#8286),.PCURVE_S1.); +#8275 = LINE('',#8276,#8277); +#8276 = CARTESIAN_POINT('',(-0.3,0.25,0.24)); +#8277 = VECTOR('',#8278,1.); +#8278 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); +#8279 = PCURVE('',#7836,#8280); +#8280 = DEFINITIONAL_REPRESENTATION('',(#8281),#8285); +#8281 = LINE('',#8282,#8283); +#8282 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8283 = VECTOR('',#8284,1.); +#8284 = DIRECTION('',(1.,0.E+000)); +#8285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8286 = PCURVE('',#8140,#8287); +#8287 = DEFINITIONAL_REPRESENTATION('',(#8288),#8292); +#8288 = LINE('',#8289,#8290); +#8289 = CARTESIAN_POINT('',(-4.E-002,0.2)); +#8290 = VECTOR('',#8291,1.); +#8291 = DIRECTION('',(1.694065894509E-016,-1.)); +#8292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8293 = ORIENTED_EDGE('',*,*,#8294,.F.); +#8294 = EDGE_CURVE('',#8295,#8272,#8297,.T.); +#8295 = VERTEX_POINT('',#8296); +#8296 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); +#8297 = SURFACE_CURVE('',#8298,(#8302,#8309),.PCURVE_S1.); +#8298 = LINE('',#8299,#8300); +#8299 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#8300 = VECTOR('',#8301,1.); +#8301 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8302 = PCURVE('',#7836,#8303); +#8303 = DEFINITIONAL_REPRESENTATION('',(#8304),#8308); +#8304 = LINE('',#8305,#8306); +#8305 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8306 = VECTOR('',#8307,1.); +#8307 = DIRECTION('',(0.E+000,1.)); +#8308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8309 = PCURVE('',#8310,#8315); +#8310 = PLANE('',#8311); +#8311 = AXIS2_PLACEMENT_3D('',#8312,#8313,#8314); +#8312 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#8313 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8314 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8315 = DEFINITIONAL_REPRESENTATION('',(#8316),#8320); +#8316 = LINE('',#8317,#8318); +#8317 = CARTESIAN_POINT('',(4.E-002,0.E+000)); +#8318 = VECTOR('',#8319,1.); +#8319 = DIRECTION('',(0.E+000,1.)); +#8320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8321 = ORIENTED_EDGE('',*,*,#8322,.F.); +#8322 = EDGE_CURVE('',#8323,#8295,#8325,.T.); +#8323 = VERTEX_POINT('',#8324); +#8324 = CARTESIAN_POINT('',(0.3,0.245,0.24)); +#8325 = SURFACE_CURVE('',#8326,(#8330,#8337),.PCURVE_S1.); +#8326 = LINE('',#8327,#8328); +#8327 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); +#8328 = VECTOR('',#8329,1.); +#8329 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8330 = PCURVE('',#7836,#8331); +#8331 = DEFINITIONAL_REPRESENTATION('',(#8332),#8336); +#8332 = LINE('',#8333,#8334); +#8333 = CARTESIAN_POINT('',(0.E+000,0.495)); +#8334 = VECTOR('',#8335,1.); +#8335 = DIRECTION('',(1.,0.E+000)); +#8336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8337 = PCURVE('',#8338,#8343); +#8338 = PLANE('',#8339); +#8339 = AXIS2_PLACEMENT_3D('',#8340,#8341,#8342); +#8340 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); +#8341 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8342 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8343 = DEFINITIONAL_REPRESENTATION('',(#8344),#8348); +#8344 = LINE('',#8345,#8346); +#8345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8346 = VECTOR('',#8347,1.); +#8347 = DIRECTION('',(0.E+000,-1.)); +#8348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8349 = ORIENTED_EDGE('',*,*,#8350,.T.); +#8350 = EDGE_CURVE('',#8323,#8351,#8353,.T.); +#8351 = VERTEX_POINT('',#8352); +#8352 = CARTESIAN_POINT('',(0.3,0.25,0.24)); +#8353 = SURFACE_CURVE('',#8354,(#8358,#8365),.PCURVE_S1.); +#8354 = LINE('',#8355,#8356); +#8355 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); +#8356 = VECTOR('',#8357,1.); +#8357 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8358 = PCURVE('',#7836,#8359); +#8359 = DEFINITIONAL_REPRESENTATION('',(#8360),#8364); +#8360 = LINE('',#8361,#8362); +#8361 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#8362 = VECTOR('',#8363,1.); +#8363 = DIRECTION('',(0.E+000,1.)); +#8364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8365 = PCURVE('',#8366,#8371); +#8366 = PLANE('',#8367); +#8367 = AXIS2_PLACEMENT_3D('',#8368,#8369,#8370); +#8368 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#8369 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8370 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8371 = DEFINITIONAL_REPRESENTATION('',(#8372),#8376); +#8372 = LINE('',#8373,#8374); +#8373 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#8374 = VECTOR('',#8375,1.); +#8375 = DIRECTION('',(0.E+000,1.)); +#8376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8377 = ORIENTED_EDGE('',*,*,#8378,.F.); +#8378 = EDGE_CURVE('',#8379,#8351,#8381,.T.); +#8379 = VERTEX_POINT('',#8380); +#8380 = CARTESIAN_POINT('',(0.46,0.25,0.24)); +#8381 = SURFACE_CURVE('',#8382,(#8386,#8393),.PCURVE_S1.); +#8382 = LINE('',#8383,#8384); +#8383 = CARTESIAN_POINT('',(0.3,0.25,0.24)); +#8384 = VECTOR('',#8385,1.); +#8385 = DIRECTION('',(-1.,0.E+000,-1.694065894509E-016)); +#8386 = PCURVE('',#7836,#8387); +#8387 = DEFINITIONAL_REPRESENTATION('',(#8388),#8392); +#8388 = LINE('',#8389,#8390); +#8389 = CARTESIAN_POINT('',(-0.6,0.5)); +#8390 = VECTOR('',#8391,1.); +#8391 = DIRECTION('',(1.,0.E+000)); +#8392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8393 = PCURVE('',#8394,#8399); +#8394 = PLANE('',#8395); +#8395 = AXIS2_PLACEMENT_3D('',#8396,#8397,#8398); +#8396 = CARTESIAN_POINT('',(0.3,0.25,0.24)); +#8397 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#8398 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8399 = DEFINITIONAL_REPRESENTATION('',(#8400),#8404); +#8400 = LINE('',#8401,#8402); +#8401 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8402 = VECTOR('',#8403,1.); +#8403 = DIRECTION('',(1.694065894509E-016,-1.)); +#8404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8405 = ORIENTED_EDGE('',*,*,#8406,.F.); +#8406 = EDGE_CURVE('',#7821,#8379,#8407,.T.); +#8407 = SURFACE_CURVE('',#8408,(#8412,#8419),.PCURVE_S1.); +#8408 = LINE('',#8409,#8410); +#8409 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); +#8410 = VECTOR('',#8411,1.); +#8411 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8412 = PCURVE('',#7836,#8413); +#8413 = DEFINITIONAL_REPRESENTATION('',(#8414),#8418); +#8414 = LINE('',#8415,#8416); +#8415 = CARTESIAN_POINT('',(-0.76,0.E+000)); +#8416 = VECTOR('',#8417,1.); +#8417 = DIRECTION('',(0.E+000,1.)); +#8418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8419 = PCURVE('',#7862,#8420); +#8420 = DEFINITIONAL_REPRESENTATION('',(#8421),#8425); +#8421 = LINE('',#8422,#8423); +#8422 = CARTESIAN_POINT('',(0.2,0.E+000)); +#8423 = VECTOR('',#8424,1.); +#8424 = DIRECTION('',(0.E+000,1.)); +#8425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8426 = ADVANCED_FACE('',(#8427),#7576,.T.); +#8427 = FACE_BOUND('',#8428,.T.); +#8428 = EDGE_LOOP('',(#8429,#8430,#8453,#8474,#8475,#8496,#8497,#8520)); +#8429 = ORIENTED_EDGE('',*,*,#7991,.T.); +#8430 = ORIENTED_EDGE('',*,*,#8431,.F.); +#8431 = EDGE_CURVE('',#8432,#7964,#8434,.T.); +#8432 = VERTEX_POINT('',#8433); +#8433 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); +#8434 = SURFACE_CURVE('',#8435,(#8439,#8446),.PCURVE_S1.); +#8435 = LINE('',#8436,#8437); +#8436 = CARTESIAN_POINT('',(0.46,-0.25,0.24)); +#8437 = VECTOR('',#8438,1.); +#8438 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8439 = PCURVE('',#7576,#8440); +#8440 = DEFINITIONAL_REPRESENTATION('',(#8441),#8445); +#8441 = LINE('',#8442,#8443); +#8442 = CARTESIAN_POINT('',(-0.76,0.E+000)); +#8443 = VECTOR('',#8444,1.); +#8444 = DIRECTION('',(0.E+000,1.)); +#8445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8446 = PCURVE('',#7979,#8447); +#8447 = DEFINITIONAL_REPRESENTATION('',(#8448),#8452); +#8448 = LINE('',#8449,#8450); +#8449 = CARTESIAN_POINT('',(0.2,0.E+000)); +#8450 = VECTOR('',#8451,1.); +#8451 = DIRECTION('',(0.E+000,1.)); +#8452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8453 = ORIENTED_EDGE('',*,*,#8454,.T.); +#8454 = EDGE_CURVE('',#8432,#7622,#8455,.T.); +#8455 = SURFACE_CURVE('',#8456,(#8460,#8467),.PCURVE_S1.); +#8456 = LINE('',#8457,#8458); +#8457 = CARTESIAN_POINT('',(0.3,-0.25,0.24)); +#8458 = VECTOR('',#8459,1.); +#8459 = DIRECTION('',(-1.,0.E+000,-1.694065894509E-016)); +#8460 = PCURVE('',#7576,#8461); +#8461 = DEFINITIONAL_REPRESENTATION('',(#8462),#8466); +#8462 = LINE('',#8463,#8464); +#8463 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#8464 = VECTOR('',#8465,1.); +#8465 = DIRECTION('',(1.,0.E+000)); +#8466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8467 = PCURVE('',#7660,#8468); +#8468 = DEFINITIONAL_REPRESENTATION('',(#8469),#8473); +#8469 = LINE('',#8470,#8471); +#8470 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8471 = VECTOR('',#8472,1.); +#8472 = DIRECTION('',(1.694065894509E-016,-1.)); +#8473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8474 = ORIENTED_EDGE('',*,*,#7621,.T.); +#8475 = ORIENTED_EDGE('',*,*,#8476,.F.); +#8476 = EDGE_CURVE('',#7472,#7592,#8477,.T.); +#8477 = SURFACE_CURVE('',#8478,(#8482,#8489),.PCURVE_S1.); +#8478 = LINE('',#8479,#8480); +#8479 = CARTESIAN_POINT('',(-0.3,-0.245,0.24)); +#8480 = VECTOR('',#8481,1.); +#8481 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8482 = PCURVE('',#7576,#8483); +#8483 = DEFINITIONAL_REPRESENTATION('',(#8484),#8488); +#8484 = LINE('',#8485,#8486); +#8485 = CARTESIAN_POINT('',(0.E+000,5.E-003)); +#8486 = VECTOR('',#8487,1.); +#8487 = DIRECTION('',(-1.,0.E+000)); +#8488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8489 = PCURVE('',#7494,#8490); +#8490 = DEFINITIONAL_REPRESENTATION('',(#8491),#8495); +#8491 = LINE('',#8492,#8493); +#8492 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8493 = VECTOR('',#8494,1.); +#8494 = DIRECTION('',(0.E+000,1.)); +#8495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8496 = ORIENTED_EDGE('',*,*,#7562,.F.); +#8497 = ORIENTED_EDGE('',*,*,#8498,.T.); +#8498 = EDGE_CURVE('',#7535,#8499,#8501,.T.); +#8499 = VERTEX_POINT('',#8500); +#8500 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); +#8501 = SURFACE_CURVE('',#8502,(#8506,#8513),.PCURVE_S1.); +#8502 = LINE('',#8503,#8504); +#8503 = CARTESIAN_POINT('',(-0.3,-0.25,0.24)); +#8504 = VECTOR('',#8505,1.); +#8505 = DIRECTION('',(-1.,0.E+000,1.694065894509E-016)); +#8506 = PCURVE('',#7576,#8507); +#8507 = DEFINITIONAL_REPRESENTATION('',(#8508),#8512); +#8508 = LINE('',#8509,#8510); +#8509 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8510 = VECTOR('',#8511,1.); +#8511 = DIRECTION('',(1.,0.E+000)); +#8512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8513 = PCURVE('',#7550,#8514); +#8514 = DEFINITIONAL_REPRESENTATION('',(#8515),#8519); +#8515 = LINE('',#8516,#8517); +#8516 = CARTESIAN_POINT('',(-4.E-002,0.2)); +#8517 = VECTOR('',#8518,1.); +#8518 = DIRECTION('',(1.694065894509E-016,-1.)); +#8519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8520 = ORIENTED_EDGE('',*,*,#8521,.T.); +#8521 = EDGE_CURVE('',#8499,#7992,#8522,.T.); +#8522 = SURFACE_CURVE('',#8523,(#8527,#8534),.PCURVE_S1.); +#8523 = LINE('',#8524,#8525); +#8524 = CARTESIAN_POINT('',(-0.46,-0.25,0.24)); +#8525 = VECTOR('',#8526,1.); +#8526 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8527 = PCURVE('',#7576,#8528); +#8528 = DEFINITIONAL_REPRESENTATION('',(#8529),#8533); +#8529 = LINE('',#8530,#8531); +#8530 = CARTESIAN_POINT('',(0.16,0.E+000)); +#8531 = VECTOR('',#8532,1.); +#8532 = DIRECTION('',(0.E+000,1.)); +#8533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8534 = PCURVE('',#8028,#8535); +#8535 = DEFINITIONAL_REPRESENTATION('',(#8536),#8540); +#8536 = LINE('',#8537,#8538); +#8537 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#8538 = VECTOR('',#8539,1.); +#8539 = DIRECTION('',(0.E+000,1.)); +#8540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8541 = ADVANCED_FACE('',(#8542),#7808,.T.); +#8542 = FACE_BOUND('',#8543,.T.); +#8543 = EDGE_LOOP('',(#8544,#8545,#8546,#8567)); +#8544 = ORIENTED_EDGE('',*,*,#7792,.T.); +#8545 = ORIENTED_EDGE('',*,*,#8152,.T.); +#8546 = ORIENTED_EDGE('',*,*,#8547,.F.); +#8547 = EDGE_CURVE('',#8249,#8125,#8548,.T.); +#8548 = SURFACE_CURVE('',#8549,(#8553,#8560),.PCURVE_S1.); +#8549 = LINE('',#8550,#8551); +#8550 = CARTESIAN_POINT('',(-0.46,0.25,4.E-002)); +#8551 = VECTOR('',#8552,1.); +#8552 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8553 = PCURVE('',#7808,#8554); +#8554 = DEFINITIONAL_REPRESENTATION('',(#8555),#8559); +#8555 = LINE('',#8556,#8557); +#8556 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8557 = VECTOR('',#8558,1.); +#8558 = DIRECTION('',(1.,0.E+000)); +#8559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8560 = PCURVE('',#8140,#8561); +#8561 = DEFINITIONAL_REPRESENTATION('',(#8562),#8566); +#8562 = LINE('',#8563,#8564); +#8563 = CARTESIAN_POINT('',(-0.24,4.E-002)); +#8564 = VECTOR('',#8565,1.); +#8565 = DIRECTION('',(-1.,0.E+000)); +#8566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8567 = ORIENTED_EDGE('',*,*,#8248,.F.); +#8568 = ADVANCED_FACE('',(#8569),#8028,.T.); +#8569 = FACE_BOUND('',#8570,.T.); +#8570 = EDGE_LOOP('',(#8571,#8572,#8573,#8594)); +#8571 = ORIENTED_EDGE('',*,*,#8014,.F.); +#8572 = ORIENTED_EDGE('',*,*,#8521,.F.); +#8573 = ORIENTED_EDGE('',*,*,#8574,.T.); +#8574 = EDGE_CURVE('',#8499,#8178,#8575,.T.); +#8575 = SURFACE_CURVE('',#8576,(#8580,#8587),.PCURVE_S1.); +#8576 = LINE('',#8577,#8578); +#8577 = CARTESIAN_POINT('',(-0.46,-0.25,4.E-002)); +#8578 = VECTOR('',#8579,1.); +#8579 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8580 = PCURVE('',#8028,#8581); +#8581 = DEFINITIONAL_REPRESENTATION('',(#8582),#8586); +#8582 = LINE('',#8583,#8584); +#8583 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8584 = VECTOR('',#8585,1.); +#8585 = DIRECTION('',(1.,0.E+000)); +#8586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8587 = PCURVE('',#7550,#8588); +#8588 = DEFINITIONAL_REPRESENTATION('',(#8589),#8593); +#8589 = LINE('',#8590,#8591); +#8590 = CARTESIAN_POINT('',(-0.24,4.E-002)); +#8591 = VECTOR('',#8592,1.); +#8592 = DIRECTION('',(-1.,0.E+000)); +#8593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8594 = ORIENTED_EDGE('',*,*,#8177,.T.); +#8595 = ADVANCED_FACE('',(#8596),#8610,.T.); +#8596 = FACE_BOUND('',#8597,.T.); +#8597 = EDGE_LOOP('',(#8598,#8628,#8651,#8679)); +#8598 = ORIENTED_EDGE('',*,*,#8599,.T.); +#8599 = EDGE_CURVE('',#8600,#8602,#8604,.T.); +#8600 = VERTEX_POINT('',#8601); +#8601 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); +#8602 = VERTEX_POINT('',#8603); +#8603 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); +#8604 = SURFACE_CURVE('',#8605,(#8609,#8621),.PCURVE_S1.); +#8605 = LINE('',#8606,#8607); +#8606 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); +#8607 = VECTOR('',#8608,1.); +#8608 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8609 = PCURVE('',#8610,#8615); +#8610 = PLANE('',#8611); +#8611 = AXIS2_PLACEMENT_3D('',#8612,#8613,#8614); +#8612 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8613 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8614 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8615 = DEFINITIONAL_REPRESENTATION('',(#8616),#8620); +#8616 = LINE('',#8617,#8618); +#8617 = CARTESIAN_POINT('',(0.28,0.E+000)); +#8618 = VECTOR('',#8619,1.); +#8619 = DIRECTION('',(0.E+000,1.)); +#8620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8621 = PCURVE('',#7522,#8622); +#8622 = DEFINITIONAL_REPRESENTATION('',(#8623),#8627); +#8623 = LINE('',#8624,#8625); +#8624 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8625 = VECTOR('',#8626,1.); +#8626 = DIRECTION('',(0.E+000,1.)); +#8627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8628 = ORIENTED_EDGE('',*,*,#8629,.F.); +#8629 = EDGE_CURVE('',#8630,#8602,#8632,.T.); +#8630 = VERTEX_POINT('',#8631); +#8631 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); +#8632 = SURFACE_CURVE('',#8633,(#8637,#8644),.PCURVE_S1.); +#8633 = LINE('',#8634,#8635); +#8634 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); +#8635 = VECTOR('',#8636,1.); +#8636 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8637 = PCURVE('',#8610,#8638); +#8638 = DEFINITIONAL_REPRESENTATION('',(#8639),#8643); +#8639 = LINE('',#8640,#8641); +#8640 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8641 = VECTOR('',#8642,1.); +#8642 = DIRECTION('',(1.,0.E+000)); +#8643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8644 = PCURVE('',#8140,#8645); +#8645 = DEFINITIONAL_REPRESENTATION('',(#8646),#8650); +#8646 = LINE('',#8647,#8648); +#8647 = CARTESIAN_POINT('',(-0.28,0.E+000)); +#8648 = VECTOR('',#8649,1.); +#8649 = DIRECTION('',(1.,0.E+000)); +#8650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8651 = ORIENTED_EDGE('',*,*,#8652,.F.); +#8652 = EDGE_CURVE('',#8653,#8630,#8655,.T.); +#8653 = VERTEX_POINT('',#8654); +#8654 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8655 = SURFACE_CURVE('',#8656,(#8660,#8667),.PCURVE_S1.); +#8656 = LINE('',#8657,#8658); +#8657 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8658 = VECTOR('',#8659,1.); +#8659 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8660 = PCURVE('',#8610,#8661); +#8661 = DEFINITIONAL_REPRESENTATION('',(#8662),#8666); +#8662 = LINE('',#8663,#8664); +#8663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8664 = VECTOR('',#8665,1.); +#8665 = DIRECTION('',(0.E+000,1.)); +#8666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8667 = PCURVE('',#8668,#8673); +#8668 = PLANE('',#8669); +#8669 = AXIS2_PLACEMENT_3D('',#8670,#8671,#8672); +#8670 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8671 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8672 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8673 = DEFINITIONAL_REPRESENTATION('',(#8674),#8678); +#8674 = LINE('',#8675,#8676); +#8675 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8676 = VECTOR('',#8677,1.); +#8677 = DIRECTION('',(0.E+000,1.)); +#8678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8679 = ORIENTED_EDGE('',*,*,#8680,.T.); +#8680 = EDGE_CURVE('',#8653,#8600,#8681,.T.); +#8681 = SURFACE_CURVE('',#8682,(#8686,#8693),.PCURVE_S1.); +#8682 = LINE('',#8683,#8684); +#8683 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8684 = VECTOR('',#8685,1.); +#8685 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8686 = PCURVE('',#8610,#8687); +#8687 = DEFINITIONAL_REPRESENTATION('',(#8688),#8692); +#8688 = LINE('',#8689,#8690); +#8689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8690 = VECTOR('',#8691,1.); +#8691 = DIRECTION('',(1.,0.E+000)); +#8692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8693 = PCURVE('',#7550,#8694); +#8694 = DEFINITIONAL_REPRESENTATION('',(#8695),#8699); +#8695 = LINE('',#8696,#8697); +#8696 = CARTESIAN_POINT('',(-0.28,0.E+000)); +#8697 = VECTOR('',#8698,1.); +#8698 = DIRECTION('',(1.,0.E+000)); +#8699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8700 = ADVANCED_FACE('',(#8701),#8668,.T.); +#8701 = FACE_BOUND('',#8702,.T.); +#8702 = EDGE_LOOP('',(#8703,#8704,#8727,#8750)); +#8703 = ORIENTED_EDGE('',*,*,#8652,.T.); +#8704 = ORIENTED_EDGE('',*,*,#8705,.F.); +#8705 = EDGE_CURVE('',#8706,#8630,#8708,.T.); +#8706 = VERTEX_POINT('',#8707); +#8707 = CARTESIAN_POINT('',(-0.3,0.25,0.E+000)); +#8708 = SURFACE_CURVE('',#8709,(#8713,#8720),.PCURVE_S1.); +#8709 = LINE('',#8710,#8711); +#8710 = CARTESIAN_POINT('',(-0.5,0.25,0.E+000)); +#8711 = VECTOR('',#8712,1.); +#8712 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8713 = PCURVE('',#8668,#8714); +#8714 = DEFINITIONAL_REPRESENTATION('',(#8715),#8719); +#8715 = LINE('',#8716,#8717); +#8716 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8717 = VECTOR('',#8718,1.); +#8718 = DIRECTION('',(1.,0.E+000)); +#8719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8720 = PCURVE('',#8140,#8721); +#8721 = DEFINITIONAL_REPRESENTATION('',(#8722),#8726); +#8722 = LINE('',#8723,#8724); +#8723 = CARTESIAN_POINT('',(-0.28,0.E+000)); +#8724 = VECTOR('',#8725,1.); +#8725 = DIRECTION('',(0.E+000,-1.)); +#8726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8727 = ORIENTED_EDGE('',*,*,#8728,.F.); +#8728 = EDGE_CURVE('',#8729,#8706,#8731,.T.); +#8729 = VERTEX_POINT('',#8730); +#8730 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); +#8731 = SURFACE_CURVE('',#8732,(#8736,#8743),.PCURVE_S1.); +#8732 = LINE('',#8733,#8734); +#8733 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); +#8734 = VECTOR('',#8735,1.); +#8735 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8736 = PCURVE('',#8668,#8737); +#8737 = DEFINITIONAL_REPRESENTATION('',(#8738),#8742); +#8738 = LINE('',#8739,#8740); +#8739 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#8740 = VECTOR('',#8741,1.); +#8741 = DIRECTION('',(0.E+000,1.)); +#8742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8743 = PCURVE('',#8085,#8744); +#8744 = DEFINITIONAL_REPRESENTATION('',(#8745),#8749); +#8745 = LINE('',#8746,#8747); +#8746 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8747 = VECTOR('',#8748,1.); +#8748 = DIRECTION('',(0.E+000,1.)); +#8749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8750 = ORIENTED_EDGE('',*,*,#8751,.T.); +#8751 = EDGE_CURVE('',#8729,#8653,#8752,.T.); +#8752 = SURFACE_CURVE('',#8753,(#8757,#8764),.PCURVE_S1.); +#8753 = LINE('',#8754,#8755); +#8754 = CARTESIAN_POINT('',(-0.5,-0.25,0.E+000)); +#8755 = VECTOR('',#8756,1.); +#8756 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#8757 = PCURVE('',#8668,#8758); +#8758 = DEFINITIONAL_REPRESENTATION('',(#8759),#8763); +#8759 = LINE('',#8760,#8761); +#8760 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8761 = VECTOR('',#8762,1.); +#8762 = DIRECTION('',(1.,0.E+000)); +#8763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8764 = PCURVE('',#7550,#8765); +#8765 = DEFINITIONAL_REPRESENTATION('',(#8766),#8770); +#8766 = LINE('',#8767,#8768); +#8767 = CARTESIAN_POINT('',(-0.28,0.E+000)); +#8768 = VECTOR('',#8769,1.); +#8769 = DIRECTION('',(0.E+000,-1.)); +#8770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8771 = ADVANCED_FACE('',(#8772),#8085,.T.); +#8772 = FACE_BOUND('',#8773,.T.); +#8773 = EDGE_LOOP('',(#8774,#8775,#8796,#8797,#8798,#8799)); +#8774 = ORIENTED_EDGE('',*,*,#8728,.T.); +#8775 = ORIENTED_EDGE('',*,*,#8776,.F.); +#8776 = EDGE_CURVE('',#8102,#8706,#8777,.T.); +#8777 = SURFACE_CURVE('',#8778,(#8782,#8789),.PCURVE_S1.); +#8778 = LINE('',#8779,#8780); +#8779 = CARTESIAN_POINT('',(-0.3,0.25,0.E+000)); +#8780 = VECTOR('',#8781,1.); +#8781 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8782 = PCURVE('',#8085,#8783); +#8783 = DEFINITIONAL_REPRESENTATION('',(#8784),#8788); +#8784 = LINE('',#8785,#8786); +#8785 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8786 = VECTOR('',#8787,1.); +#8787 = DIRECTION('',(1.,0.E+000)); +#8788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8789 = PCURVE('',#8140,#8790); +#8790 = DEFINITIONAL_REPRESENTATION('',(#8791),#8795); +#8791 = LINE('',#8792,#8793); +#8792 = CARTESIAN_POINT('',(-0.28,0.2)); +#8793 = VECTOR('',#8794,1.); +#8794 = DIRECTION('',(-1.,0.E+000)); +#8795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8796 = ORIENTED_EDGE('',*,*,#8101,.F.); +#8797 = ORIENTED_EDGE('',*,*,#8071,.F.); +#8798 = ORIENTED_EDGE('',*,*,#8223,.F.); +#8799 = ORIENTED_EDGE('',*,*,#8800,.T.); +#8800 = EDGE_CURVE('',#8201,#8729,#8801,.T.); +#8801 = SURFACE_CURVE('',#8802,(#8806,#8813),.PCURVE_S1.); +#8802 = LINE('',#8803,#8804); +#8803 = CARTESIAN_POINT('',(-0.3,-0.25,0.E+000)); +#8804 = VECTOR('',#8805,1.); +#8805 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8806 = PCURVE('',#8085,#8807); +#8807 = DEFINITIONAL_REPRESENTATION('',(#8808),#8812); +#8808 = LINE('',#8809,#8810); +#8809 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8810 = VECTOR('',#8811,1.); +#8811 = DIRECTION('',(1.,0.E+000)); +#8812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8813 = PCURVE('',#7550,#8814); +#8814 = DEFINITIONAL_REPRESENTATION('',(#8815),#8819); +#8815 = LINE('',#8816,#8817); +#8816 = CARTESIAN_POINT('',(-0.28,0.2)); +#8817 = VECTOR('',#8818,1.); +#8818 = DIRECTION('',(-1.,0.E+000)); +#8819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8820 = ADVANCED_FACE('',(#8821),#8310,.T.); +#8821 = FACE_BOUND('',#8822,.T.); +#8822 = EDGE_LOOP('',(#8823,#8846,#8847,#8870)); +#8823 = ORIENTED_EDGE('',*,*,#8824,.F.); +#8824 = EDGE_CURVE('',#8295,#8825,#8827,.T.); +#8825 = VERTEX_POINT('',#8826); +#8826 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#8827 = SURFACE_CURVE('',#8828,(#8832,#8839),.PCURVE_S1.); +#8828 = LINE('',#8829,#8830); +#8829 = CARTESIAN_POINT('',(-0.3,0.245,0.24)); +#8830 = VECTOR('',#8831,1.); +#8831 = DIRECTION('',(0.E+000,0.E+000,1.)); +#8832 = PCURVE('',#8310,#8833); +#8833 = DEFINITIONAL_REPRESENTATION('',(#8834),#8838); +#8834 = LINE('',#8835,#8836); +#8835 = CARTESIAN_POINT('',(4.E-002,0.495)); +#8836 = VECTOR('',#8837,1.); +#8837 = DIRECTION('',(-1.,0.E+000)); +#8838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8839 = PCURVE('',#8338,#8840); +#8840 = DEFINITIONAL_REPRESENTATION('',(#8841),#8845); +#8841 = LINE('',#8842,#8843); +#8842 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8843 = VECTOR('',#8844,1.); +#8844 = DIRECTION('',(1.,0.E+000)); +#8845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8846 = ORIENTED_EDGE('',*,*,#8294,.T.); +#8847 = ORIENTED_EDGE('',*,*,#8848,.F.); +#8848 = EDGE_CURVE('',#8849,#8272,#8851,.T.); +#8849 = VERTEX_POINT('',#8850); +#8850 = CARTESIAN_POINT('',(-0.3,0.25,0.28)); +#8851 = SURFACE_CURVE('',#8852,(#8856,#8863),.PCURVE_S1.); +#8852 = LINE('',#8853,#8854); +#8853 = CARTESIAN_POINT('',(-0.3,0.25,0.28)); +#8854 = VECTOR('',#8855,1.); +#8855 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#8856 = PCURVE('',#8310,#8857); +#8857 = DEFINITIONAL_REPRESENTATION('',(#8858),#8862); +#8858 = LINE('',#8859,#8860); +#8859 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8860 = VECTOR('',#8861,1.); +#8861 = DIRECTION('',(1.,0.E+000)); +#8862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8863 = PCURVE('',#8140,#8864); +#8864 = DEFINITIONAL_REPRESENTATION('',(#8865),#8869); +#8865 = LINE('',#8866,#8867); +#8866 = CARTESIAN_POINT('',(0.E+000,0.2)); +#8867 = VECTOR('',#8868,1.); +#8868 = DIRECTION('',(-1.,0.E+000)); +#8869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8870 = ORIENTED_EDGE('',*,*,#8871,.F.); +#8871 = EDGE_CURVE('',#8825,#8849,#8872,.T.); +#8872 = SURFACE_CURVE('',#8873,(#8877,#8884),.PCURVE_S1.); +#8873 = LINE('',#8874,#8875); +#8874 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); +#8875 = VECTOR('',#8876,1.); +#8876 = DIRECTION('',(0.E+000,1.,0.E+000)); +#8877 = PCURVE('',#8310,#8878); +#8878 = DEFINITIONAL_REPRESENTATION('',(#8879),#8883); +#8879 = LINE('',#8880,#8881); +#8880 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8881 = VECTOR('',#8882,1.); +#8882 = DIRECTION('',(0.E+000,1.)); +#8883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8884 = PCURVE('',#7522,#8885); +#8885 = DEFINITIONAL_REPRESENTATION('',(#8886),#8890); +#8886 = LINE('',#8887,#8888); +#8887 = CARTESIAN_POINT('',(0.2,0.E+000)); +#8888 = VECTOR('',#8889,1.); +#8889 = DIRECTION('',(0.E+000,1.)); +#8890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8891 = ADVANCED_FACE('',(#8892),#7522,.T.); +#8892 = FACE_BOUND('',#8893,.T.); +#8893 = EDGE_LOOP('',(#8894,#8895,#8921,#8922,#8943,#8944)); +#8894 = ORIENTED_EDGE('',*,*,#7506,.T.); +#8895 = ORIENTED_EDGE('',*,*,#8896,.F.); +#8896 = EDGE_CURVE('',#8825,#7474,#8897,.T.); +#8897 = SURFACE_CURVE('',#8898,(#8902,#8909),.PCURVE_S1.); +#8898 = LINE('',#8899,#8900); +#8899 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#8900 = VECTOR('',#8901,1.); +#8901 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#8902 = PCURVE('',#7522,#8903); +#8903 = DEFINITIONAL_REPRESENTATION('',(#8904),#8908); +#8904 = LINE('',#8905,#8906); +#8905 = CARTESIAN_POINT('',(0.2,0.495)); +#8906 = VECTOR('',#8907,1.); +#8907 = DIRECTION('',(0.E+000,-1.)); +#8908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8909 = PCURVE('',#8910,#8915); +#8910 = PLANE('',#8911); +#8911 = AXIS2_PLACEMENT_3D('',#8912,#8913,#8914); +#8912 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#8913 = DIRECTION('',(-0.866025403784,0.E+000,0.5)); +#8914 = DIRECTION('',(0.5,0.E+000,0.866025403784)); +#8915 = DEFINITIONAL_REPRESENTATION('',(#8916),#8920); +#8916 = LINE('',#8917,#8918); +#8917 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8918 = VECTOR('',#8919,1.); +#8919 = DIRECTION('',(0.E+000,-1.)); +#8920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8921 = ORIENTED_EDGE('',*,*,#8871,.T.); +#8922 = ORIENTED_EDGE('',*,*,#8923,.F.); +#8923 = EDGE_CURVE('',#8602,#8849,#8924,.T.); +#8924 = SURFACE_CURVE('',#8925,(#8929,#8936),.PCURVE_S1.); +#8925 = LINE('',#8926,#8927); +#8926 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); +#8927 = VECTOR('',#8928,1.); +#8928 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8929 = PCURVE('',#7522,#8930); +#8930 = DEFINITIONAL_REPRESENTATION('',(#8931),#8935); +#8931 = LINE('',#8932,#8933); +#8932 = CARTESIAN_POINT('',(0.E+000,0.5)); +#8933 = VECTOR('',#8934,1.); +#8934 = DIRECTION('',(1.,0.E+000)); +#8935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8936 = PCURVE('',#8140,#8937); +#8937 = DEFINITIONAL_REPRESENTATION('',(#8938),#8942); +#8938 = LINE('',#8939,#8940); +#8939 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8940 = VECTOR('',#8941,1.); +#8941 = DIRECTION('',(0.E+000,1.)); +#8942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8943 = ORIENTED_EDGE('',*,*,#8599,.F.); +#8944 = ORIENTED_EDGE('',*,*,#8945,.T.); +#8945 = EDGE_CURVE('',#8600,#7507,#8946,.T.); +#8946 = SURFACE_CURVE('',#8947,(#8951,#8958),.PCURVE_S1.); +#8947 = LINE('',#8948,#8949); +#8948 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); +#8949 = VECTOR('',#8950,1.); +#8950 = DIRECTION('',(1.,0.E+000,0.E+000)); +#8951 = PCURVE('',#7522,#8952); +#8952 = DEFINITIONAL_REPRESENTATION('',(#8953),#8957); +#8953 = LINE('',#8954,#8955); +#8954 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8955 = VECTOR('',#8956,1.); +#8956 = DIRECTION('',(1.,0.E+000)); +#8957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8958 = PCURVE('',#7550,#8959); +#8959 = DEFINITIONAL_REPRESENTATION('',(#8960),#8964); +#8960 = LINE('',#8961,#8962); +#8961 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#8962 = VECTOR('',#8963,1.); +#8963 = DIRECTION('',(0.E+000,1.)); +#8964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#8965 = ADVANCED_FACE('',(#8966),#7550,.F.); +#8966 = FACE_BOUND('',#8967,.T.); +#8967 = EDGE_LOOP('',(#8968,#8969,#8970,#8971,#8972,#8973,#8974,#8975)); +#8968 = ORIENTED_EDGE('',*,*,#8680,.F.); +#8969 = ORIENTED_EDGE('',*,*,#8751,.F.); +#8970 = ORIENTED_EDGE('',*,*,#8800,.F.); +#8971 = ORIENTED_EDGE('',*,*,#8200,.F.); +#8972 = ORIENTED_EDGE('',*,*,#8574,.F.); +#8973 = ORIENTED_EDGE('',*,*,#8498,.F.); +#8974 = ORIENTED_EDGE('',*,*,#7534,.F.); +#8975 = ORIENTED_EDGE('',*,*,#8945,.F.); +#8976 = ADVANCED_FACE('',(#8977),#8140,.T.); +#8977 = FACE_BOUND('',#8978,.T.); +#8978 = EDGE_LOOP('',(#8979,#8980,#8981,#8982,#8983,#8984,#8985,#8986)); +#8979 = ORIENTED_EDGE('',*,*,#8629,.T.); +#8980 = ORIENTED_EDGE('',*,*,#8923,.T.); +#8981 = ORIENTED_EDGE('',*,*,#8848,.T.); +#8982 = ORIENTED_EDGE('',*,*,#8271,.T.); +#8983 = ORIENTED_EDGE('',*,*,#8547,.T.); +#8984 = ORIENTED_EDGE('',*,*,#8124,.T.); +#8985 = ORIENTED_EDGE('',*,*,#8776,.T.); +#8986 = ORIENTED_EDGE('',*,*,#8705,.T.); +#8987 = ADVANCED_FACE('',(#8988),#7724,.T.); +#8988 = FACE_BOUND('',#8989,.T.); +#8989 = EDGE_LOOP('',(#8990,#8991,#9014,#9037)); +#8990 = ORIENTED_EDGE('',*,*,#7701,.F.); +#8991 = ORIENTED_EDGE('',*,*,#8992,.T.); +#8992 = EDGE_CURVE('',#7702,#8993,#8995,.T.); +#8993 = VERTEX_POINT('',#8994); +#8994 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); +#8995 = SURFACE_CURVE('',#8996,(#9000,#9007),.PCURVE_S1.); +#8996 = LINE('',#8997,#8998); +#8997 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#8998 = VECTOR('',#8999,1.); +#8999 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9000 = PCURVE('',#7724,#9001); +#9001 = DEFINITIONAL_REPRESENTATION('',(#9002),#9006); +#9002 = LINE('',#9003,#9004); +#9003 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9004 = VECTOR('',#9005,1.); +#9005 = DIRECTION('',(0.E+000,1.)); +#9006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9007 = PCURVE('',#7862,#9008); +#9008 = DEFINITIONAL_REPRESENTATION('',(#9009),#9013); +#9009 = LINE('',#9010,#9011); +#9010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9011 = VECTOR('',#9012,1.); +#9012 = DIRECTION('',(0.E+000,1.)); +#9013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9014 = ORIENTED_EDGE('',*,*,#9015,.F.); +#9015 = EDGE_CURVE('',#9016,#8993,#9018,.T.); +#9016 = VERTEX_POINT('',#9017); +#9017 = CARTESIAN_POINT('',(0.3,0.25,4.E-002)); +#9018 = SURFACE_CURVE('',#9019,(#9023,#9030),.PCURVE_S1.); +#9019 = LINE('',#9020,#9021); +#9020 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); +#9021 = VECTOR('',#9022,1.); +#9022 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9023 = PCURVE('',#7724,#9024); +#9024 = DEFINITIONAL_REPRESENTATION('',(#9025),#9029); +#9025 = LINE('',#9026,#9027); +#9026 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9027 = VECTOR('',#9028,1.); +#9028 = DIRECTION('',(1.,0.E+000)); +#9029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9030 = PCURVE('',#8394,#9031); +#9031 = DEFINITIONAL_REPRESENTATION('',(#9032),#9036); +#9032 = LINE('',#9033,#9034); +#9033 = CARTESIAN_POINT('',(0.2,0.16)); +#9034 = VECTOR('',#9035,1.); +#9035 = DIRECTION('',(0.E+000,1.)); +#9036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9037 = ORIENTED_EDGE('',*,*,#9038,.F.); +#9038 = EDGE_CURVE('',#7704,#9016,#9039,.T.); +#9039 = SURFACE_CURVE('',#9040,(#9044,#9051),.PCURVE_S1.); +#9040 = LINE('',#9041,#9042); +#9041 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); +#9042 = VECTOR('',#9043,1.); +#9043 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9044 = PCURVE('',#7724,#9045); +#9045 = DEFINITIONAL_REPRESENTATION('',(#9046),#9050); +#9046 = LINE('',#9047,#9048); +#9047 = CARTESIAN_POINT('',(-0.16,0.E+000)); +#9048 = VECTOR('',#9049,1.); +#9049 = DIRECTION('',(0.E+000,1.)); +#9050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9051 = PCURVE('',#8058,#9052); +#9052 = DEFINITIONAL_REPRESENTATION('',(#9053),#9057); +#9053 = LINE('',#9054,#9055); +#9054 = CARTESIAN_POINT('',(4.E-002,0.E+000)); +#9055 = VECTOR('',#9056,1.); +#9056 = DIRECTION('',(0.E+000,1.)); +#9057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9058 = ADVANCED_FACE('',(#9059),#7951,.T.); +#9059 = FACE_BOUND('',#9060,.T.); +#9060 = EDGE_LOOP('',(#9061,#9062,#9085,#9108)); +#9061 = ORIENTED_EDGE('',*,*,#7935,.F.); +#9062 = ORIENTED_EDGE('',*,*,#9063,.F.); +#9063 = EDGE_CURVE('',#9064,#7913,#9066,.T.); +#9064 = VERTEX_POINT('',#9065); +#9065 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); +#9066 = SURFACE_CURVE('',#9067,(#9071,#9078),.PCURVE_S1.); +#9067 = LINE('',#9068,#9069); +#9068 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); +#9069 = VECTOR('',#9070,1.); +#9070 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9071 = PCURVE('',#7951,#9072); +#9072 = DEFINITIONAL_REPRESENTATION('',(#9073),#9077); +#9073 = LINE('',#9074,#9075); +#9074 = CARTESIAN_POINT('',(-0.16,0.E+000)); +#9075 = VECTOR('',#9076,1.); +#9076 = DIRECTION('',(0.E+000,1.)); +#9077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6478 = ORIENTED_EDGE('',*,*,#6479,.F.); -#6479 = EDGE_CURVE('',#6433,#6457,#6480,.T.); -#6480 = SURFACE_CURVE('',#6481,(#6485,#6492),.PCURVE_S1.); -#6481 = LINE('',#6482,#6483); -#6482 = CARTESIAN_POINT('',(-0.3,-0.25,0.28)); -#6483 = VECTOR('',#6484,1.); -#6484 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6485 = PCURVE('',#5918,#6486); -#6486 = DEFINITIONAL_REPRESENTATION('',(#6487),#6491); -#6487 = LINE('',#6488,#6489); -#6488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6489 = VECTOR('',#6490,1.); -#6490 = DIRECTION('',(0.E+000,1.)); -#6491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6492 = PCURVE('',#5130,#6493); -#6493 = DEFINITIONAL_REPRESENTATION('',(#6494),#6498); -#6494 = LINE('',#6495,#6496); -#6495 = CARTESIAN_POINT('',(0.2,0.E+000)); -#6496 = VECTOR('',#6497,1.); -#6497 = DIRECTION('',(0.E+000,1.)); -#6498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6499 = ADVANCED_FACE('',(#6500),#5130,.T.); -#6500 = FACE_BOUND('',#6501,.T.); -#6501 = EDGE_LOOP('',(#6502,#6503,#6529,#6530,#6551,#6552)); -#6502 = ORIENTED_EDGE('',*,*,#5114,.T.); -#6503 = ORIENTED_EDGE('',*,*,#6504,.F.); -#6504 = EDGE_CURVE('',#6433,#5082,#6505,.T.); -#6505 = SURFACE_CURVE('',#6506,(#6510,#6517),.PCURVE_S1.); -#6506 = LINE('',#6507,#6508); -#6507 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#6508 = VECTOR('',#6509,1.); -#6509 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#6510 = PCURVE('',#5130,#6511); -#6511 = DEFINITIONAL_REPRESENTATION('',(#6512),#6516); -#6512 = LINE('',#6513,#6514); -#6513 = CARTESIAN_POINT('',(0.2,0.495)); -#6514 = VECTOR('',#6515,1.); -#6515 = DIRECTION('',(0.E+000,-1.)); -#6516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6517 = PCURVE('',#6518,#6523); -#6518 = PLANE('',#6519); -#6519 = AXIS2_PLACEMENT_3D('',#6520,#6521,#6522); -#6520 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#6521 = DIRECTION('',(-0.866025403784,0.E+000,0.5)); -#6522 = DIRECTION('',(0.5,0.E+000,0.866025403784)); -#6523 = DEFINITIONAL_REPRESENTATION('',(#6524),#6528); -#6524 = LINE('',#6525,#6526); -#6525 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6526 = VECTOR('',#6527,1.); -#6527 = DIRECTION('',(0.E+000,-1.)); -#6528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6529 = ORIENTED_EDGE('',*,*,#6479,.T.); -#6530 = ORIENTED_EDGE('',*,*,#6531,.F.); -#6531 = EDGE_CURVE('',#6210,#6457,#6532,.T.); -#6532 = SURFACE_CURVE('',#6533,(#6537,#6544),.PCURVE_S1.); -#6533 = LINE('',#6534,#6535); -#6534 = CARTESIAN_POINT('',(-0.5,0.25,0.28)); -#6535 = VECTOR('',#6536,1.); -#6536 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6537 = PCURVE('',#5130,#6538); -#6538 = DEFINITIONAL_REPRESENTATION('',(#6539),#6543); -#6539 = LINE('',#6540,#6541); -#6540 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6541 = VECTOR('',#6542,1.); -#6542 = DIRECTION('',(1.,0.E+000)); -#6543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6544 = PCURVE('',#5748,#6545); -#6545 = DEFINITIONAL_REPRESENTATION('',(#6546),#6550); -#6546 = LINE('',#6547,#6548); -#6547 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6548 = VECTOR('',#6549,1.); -#6549 = DIRECTION('',(0.E+000,1.)); -#6550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6551 = ORIENTED_EDGE('',*,*,#6207,.F.); -#6552 = ORIENTED_EDGE('',*,*,#6553,.T.); -#6553 = EDGE_CURVE('',#6208,#5115,#6554,.T.); -#6554 = SURFACE_CURVE('',#6555,(#6559,#6566),.PCURVE_S1.); -#6555 = LINE('',#6556,#6557); -#6556 = CARTESIAN_POINT('',(-0.5,-0.25,0.28)); -#6557 = VECTOR('',#6558,1.); -#6558 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6559 = PCURVE('',#5130,#6560); -#6560 = DEFINITIONAL_REPRESENTATION('',(#6561),#6565); -#6561 = LINE('',#6562,#6563); -#6562 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6563 = VECTOR('',#6564,1.); -#6564 = DIRECTION('',(1.,0.E+000)); -#6565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6566 = PCURVE('',#5158,#6567); -#6567 = DEFINITIONAL_REPRESENTATION('',(#6568),#6572); -#6568 = LINE('',#6569,#6570); -#6569 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6570 = VECTOR('',#6571,1.); -#6571 = DIRECTION('',(0.E+000,1.)); -#6572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6573 = ADVANCED_FACE('',(#6574),#5158,.F.); -#6574 = FACE_BOUND('',#6575,.T.); -#6575 = EDGE_LOOP('',(#6576,#6577,#6578,#6579,#6580,#6581,#6582,#6583)); -#6576 = ORIENTED_EDGE('',*,*,#6288,.F.); -#6577 = ORIENTED_EDGE('',*,*,#6359,.F.); -#6578 = ORIENTED_EDGE('',*,*,#6408,.F.); -#6579 = ORIENTED_EDGE('',*,*,#5808,.F.); -#6580 = ORIENTED_EDGE('',*,*,#6182,.F.); -#6581 = ORIENTED_EDGE('',*,*,#6106,.F.); -#6582 = ORIENTED_EDGE('',*,*,#5142,.F.); -#6583 = ORIENTED_EDGE('',*,*,#6553,.F.); -#6584 = ADVANCED_FACE('',(#6585),#5748,.T.); -#6585 = FACE_BOUND('',#6586,.T.); -#6586 = EDGE_LOOP('',(#6587,#6588,#6589,#6590,#6591,#6592,#6593,#6594)); -#6587 = ORIENTED_EDGE('',*,*,#6237,.T.); -#6588 = ORIENTED_EDGE('',*,*,#6531,.T.); -#6589 = ORIENTED_EDGE('',*,*,#6456,.T.); -#6590 = ORIENTED_EDGE('',*,*,#5879,.T.); -#6591 = ORIENTED_EDGE('',*,*,#6155,.T.); -#6592 = ORIENTED_EDGE('',*,*,#5732,.T.); -#6593 = ORIENTED_EDGE('',*,*,#6384,.T.); -#6594 = ORIENTED_EDGE('',*,*,#6313,.T.); -#6595 = ADVANCED_FACE('',(#6596),#5332,.T.); -#6596 = FACE_BOUND('',#6597,.T.); -#6597 = EDGE_LOOP('',(#6598,#6599,#6622,#6645)); -#6598 = ORIENTED_EDGE('',*,*,#5309,.F.); -#6599 = ORIENTED_EDGE('',*,*,#6600,.T.); -#6600 = EDGE_CURVE('',#5310,#6601,#6603,.T.); -#6601 = VERTEX_POINT('',#6602); -#6602 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); -#6603 = SURFACE_CURVE('',#6604,(#6608,#6615),.PCURVE_S1.); -#6604 = LINE('',#6605,#6606); -#6605 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#6606 = VECTOR('',#6607,1.); -#6607 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6608 = PCURVE('',#5332,#6609); -#6609 = DEFINITIONAL_REPRESENTATION('',(#6610),#6614); -#6610 = LINE('',#6611,#6612); -#6611 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6612 = VECTOR('',#6613,1.); -#6613 = DIRECTION('',(0.E+000,1.)); -#6614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6615 = PCURVE('',#5470,#6616); -#6616 = DEFINITIONAL_REPRESENTATION('',(#6617),#6621); -#6617 = LINE('',#6618,#6619); -#6618 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6619 = VECTOR('',#6620,1.); -#6620 = DIRECTION('',(0.E+000,1.)); -#6621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6622 = ORIENTED_EDGE('',*,*,#6623,.F.); -#6623 = EDGE_CURVE('',#6624,#6601,#6626,.T.); -#6624 = VERTEX_POINT('',#6625); -#6625 = CARTESIAN_POINT('',(0.3,0.25,4.E-002)); -#6626 = SURFACE_CURVE('',#6627,(#6631,#6638),.PCURVE_S1.); -#6627 = LINE('',#6628,#6629); -#6628 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); -#6629 = VECTOR('',#6630,1.); -#6630 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6631 = PCURVE('',#5332,#6632); -#6632 = DEFINITIONAL_REPRESENTATION('',(#6633),#6637); -#6633 = LINE('',#6634,#6635); -#6634 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6635 = VECTOR('',#6636,1.); -#6636 = DIRECTION('',(1.,0.E+000)); -#6637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#9078 = PCURVE('',#8058,#9079); +#9079 = DEFINITIONAL_REPRESENTATION('',(#9080),#9084); +#9080 = LINE('',#9081,#9082); +#9081 = CARTESIAN_POINT('',(4.E-002,0.E+000)); +#9082 = VECTOR('',#9083,1.); +#9083 = DIRECTION('',(0.E+000,1.)); +#9084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9085 = ORIENTED_EDGE('',*,*,#9086,.T.); +#9086 = EDGE_CURVE('',#9064,#9087,#9089,.T.); +#9087 = VERTEX_POINT('',#9088); +#9088 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#9089 = SURFACE_CURVE('',#9090,(#9094,#9101),.PCURVE_S1.); +#9090 = LINE('',#9091,#9092); +#9091 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#9092 = VECTOR('',#9093,1.); +#9093 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9094 = PCURVE('',#7951,#9095); +#9095 = DEFINITIONAL_REPRESENTATION('',(#9096),#9100); +#9096 = LINE('',#9097,#9098); +#9097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9098 = VECTOR('',#9099,1.); +#9099 = DIRECTION('',(1.,0.E+000)); +#9100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9101 = PCURVE('',#7660,#9102); +#9102 = DEFINITIONAL_REPRESENTATION('',(#9103),#9107); +#9103 = LINE('',#9104,#9105); +#9104 = CARTESIAN_POINT('',(0.2,0.16)); +#9105 = VECTOR('',#9106,1.); +#9106 = DIRECTION('',(0.E+000,1.)); +#9107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9108 = ORIENTED_EDGE('',*,*,#9109,.T.); +#9109 = EDGE_CURVE('',#9087,#7936,#9110,.T.); +#9110 = SURFACE_CURVE('',#9111,(#9115,#9122),.PCURVE_S1.); +#9111 = LINE('',#9112,#9113); +#9112 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#9113 = VECTOR('',#9114,1.); +#9114 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9115 = PCURVE('',#7951,#9116); +#9116 = DEFINITIONAL_REPRESENTATION('',(#9117),#9121); +#9117 = LINE('',#9118,#9119); +#9118 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9119 = VECTOR('',#9120,1.); +#9120 = DIRECTION('',(0.E+000,1.)); +#9121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9122 = PCURVE('',#7979,#9123); +#9123 = DEFINITIONAL_REPRESENTATION('',(#9124),#9128); +#9124 = LINE('',#9125,#9126); +#9125 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9126 = VECTOR('',#9127,1.); +#9127 = DIRECTION('',(0.E+000,1.)); +#9128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9129 = ADVANCED_FACE('',(#9130),#7862,.T.); +#9130 = FACE_BOUND('',#9131,.T.); +#9131 = EDGE_LOOP('',(#9132,#9133,#9134,#9155)); +#9132 = ORIENTED_EDGE('',*,*,#7848,.F.); +#9133 = ORIENTED_EDGE('',*,*,#8406,.T.); +#9134 = ORIENTED_EDGE('',*,*,#9135,.F.); +#9135 = EDGE_CURVE('',#8993,#8379,#9136,.T.); +#9136 = SURFACE_CURVE('',#9137,(#9141,#9148),.PCURVE_S1.); +#9137 = LINE('',#9138,#9139); +#9138 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); +#9139 = VECTOR('',#9140,1.); +#9140 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9141 = PCURVE('',#7862,#9142); +#9142 = DEFINITIONAL_REPRESENTATION('',(#9143),#9147); +#9143 = LINE('',#9144,#9145); +#9144 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9145 = VECTOR('',#9146,1.); +#9146 = DIRECTION('',(1.,0.E+000)); +#9147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9148 = PCURVE('',#8394,#9149); +#9149 = DEFINITIONAL_REPRESENTATION('',(#9150),#9154); +#9150 = LINE('',#9151,#9152); +#9151 = CARTESIAN_POINT('',(0.2,0.16)); +#9152 = VECTOR('',#9153,1.); +#9153 = DIRECTION('',(-1.,0.E+000)); +#9154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9155 = ORIENTED_EDGE('',*,*,#8992,.F.); +#9156 = ADVANCED_FACE('',(#9157),#7979,.T.); +#9157 = FACE_BOUND('',#9158,.T.); +#9158 = EDGE_LOOP('',(#9159,#9160,#9161,#9182)); +#9159 = ORIENTED_EDGE('',*,*,#7963,.T.); +#9160 = ORIENTED_EDGE('',*,*,#9109,.F.); +#9161 = ORIENTED_EDGE('',*,*,#9162,.T.); +#9162 = EDGE_CURVE('',#9087,#8432,#9163,.T.); +#9163 = SURFACE_CURVE('',#9164,(#9168,#9175),.PCURVE_S1.); +#9164 = LINE('',#9165,#9166); +#9165 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); +#9166 = VECTOR('',#9167,1.); +#9167 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9168 = PCURVE('',#7979,#9169); +#9169 = DEFINITIONAL_REPRESENTATION('',(#9170),#9174); +#9170 = LINE('',#9171,#9172); +#9171 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9172 = VECTOR('',#9173,1.); +#9173 = DIRECTION('',(1.,0.E+000)); +#9174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9175 = PCURVE('',#7660,#9176); +#9176 = DEFINITIONAL_REPRESENTATION('',(#9177),#9181); +#9177 = LINE('',#9178,#9179); +#9178 = CARTESIAN_POINT('',(0.2,0.16)); +#9179 = VECTOR('',#9180,1.); +#9180 = DIRECTION('',(-1.,0.E+000)); +#9181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9182 = ORIENTED_EDGE('',*,*,#8431,.T.); +#9183 = ADVANCED_FACE('',(#9184),#8366,.T.); +#9184 = FACE_BOUND('',#9185,.T.); +#9185 = EDGE_LOOP('',(#9186,#9209,#9232,#9253)); +#9186 = ORIENTED_EDGE('',*,*,#9187,.T.); +#9187 = EDGE_CURVE('',#8323,#9188,#9190,.T.); +#9188 = VERTEX_POINT('',#9189); +#9189 = CARTESIAN_POINT('',(0.3,0.245,0.28)); +#9190 = SURFACE_CURVE('',#9191,(#9195,#9202),.PCURVE_S1.); +#9191 = LINE('',#9192,#9193); +#9192 = CARTESIAN_POINT('',(0.3,0.245,0.24)); +#9193 = VECTOR('',#9194,1.); +#9194 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9195 = PCURVE('',#8366,#9196); +#9196 = DEFINITIONAL_REPRESENTATION('',(#9197),#9201); +#9197 = LINE('',#9198,#9199); +#9198 = CARTESIAN_POINT('',(-4.E-002,0.495)); +#9199 = VECTOR('',#9200,1.); +#9200 = DIRECTION('',(1.,0.E+000)); +#9201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9202 = PCURVE('',#8338,#9203); +#9203 = DEFINITIONAL_REPRESENTATION('',(#9204),#9208); +#9204 = LINE('',#9205,#9206); +#9205 = CARTESIAN_POINT('',(0.E+000,0.6)); +#9206 = VECTOR('',#9207,1.); +#9207 = DIRECTION('',(1.,0.E+000)); +#9208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9209 = ORIENTED_EDGE('',*,*,#9210,.T.); +#9210 = EDGE_CURVE('',#9188,#9211,#9213,.T.); +#9211 = VERTEX_POINT('',#9212); +#9212 = CARTESIAN_POINT('',(0.3,0.25,0.28)); +#9213 = SURFACE_CURVE('',#9214,(#9218,#9225),.PCURVE_S1.); +#9214 = LINE('',#9215,#9216); +#9215 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); +#9216 = VECTOR('',#9217,1.); +#9217 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9218 = PCURVE('',#8366,#9219); +#9219 = DEFINITIONAL_REPRESENTATION('',(#9220),#9224); +#9220 = LINE('',#9221,#9222); +#9221 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9222 = VECTOR('',#9223,1.); +#9223 = DIRECTION('',(0.E+000,1.)); +#9224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9225 = PCURVE('',#7686,#9226); +#9226 = DEFINITIONAL_REPRESENTATION('',(#9227),#9231); +#9227 = LINE('',#9228,#9229); +#9228 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#9229 = VECTOR('',#9230,1.); +#9230 = DIRECTION('',(0.E+000,1.)); +#9231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9232 = ORIENTED_EDGE('',*,*,#9233,.F.); +#9233 = EDGE_CURVE('',#8351,#9211,#9234,.T.); +#9234 = SURFACE_CURVE('',#9235,(#9239,#9246),.PCURVE_S1.); +#9235 = LINE('',#9236,#9237); +#9236 = CARTESIAN_POINT('',(0.3,0.25,0.28)); +#9237 = VECTOR('',#9238,1.); +#9238 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9239 = PCURVE('',#8366,#9240); +#9240 = DEFINITIONAL_REPRESENTATION('',(#9241),#9245); +#9241 = LINE('',#9242,#9243); +#9242 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9243 = VECTOR('',#9244,1.); +#9244 = DIRECTION('',(1.,0.E+000)); +#9245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9246 = PCURVE('',#8394,#9247); +#9247 = DEFINITIONAL_REPRESENTATION('',(#9248),#9252); +#9248 = LINE('',#9249,#9250); +#9249 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#9250 = VECTOR('',#9251,1.); +#9251 = DIRECTION('',(-1.,0.E+000)); +#9252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9253 = ORIENTED_EDGE('',*,*,#8350,.F.); +#9254 = ADVANCED_FACE('',(#9255),#8058,.T.); +#9255 = FACE_BOUND('',#9256,.T.); +#9256 = EDGE_LOOP('',(#9257,#9258,#9259,#9260,#9283,#9311)); +#9257 = ORIENTED_EDGE('',*,*,#9063,.T.); +#9258 = ORIENTED_EDGE('',*,*,#8044,.F.); +#9259 = ORIENTED_EDGE('',*,*,#9038,.T.); +#9260 = ORIENTED_EDGE('',*,*,#9261,.F.); +#9261 = EDGE_CURVE('',#9262,#9016,#9264,.T.); +#9262 = VERTEX_POINT('',#9263); +#9263 = CARTESIAN_POINT('',(0.3,0.25,0.E+000)); +#9264 = SURFACE_CURVE('',#9265,(#9269,#9276),.PCURVE_S1.); +#9265 = LINE('',#9266,#9267); +#9266 = CARTESIAN_POINT('',(0.3,0.25,0.E+000)); +#9267 = VECTOR('',#9268,1.); +#9268 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9269 = PCURVE('',#8058,#9270); +#9270 = DEFINITIONAL_REPRESENTATION('',(#9271),#9275); +#9271 = LINE('',#9272,#9273); +#9272 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9273 = VECTOR('',#9274,1.); +#9274 = DIRECTION('',(1.,0.E+000)); +#9275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9276 = PCURVE('',#8394,#9277); +#9277 = DEFINITIONAL_REPRESENTATION('',(#9278),#9282); +#9278 = LINE('',#9279,#9280); +#9279 = CARTESIAN_POINT('',(0.24,0.E+000)); +#9280 = VECTOR('',#9281,1.); +#9281 = DIRECTION('',(-1.,0.E+000)); +#9282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9283 = ORIENTED_EDGE('',*,*,#9284,.F.); +#9284 = EDGE_CURVE('',#9285,#9262,#9287,.T.); +#9285 = VERTEX_POINT('',#9286); +#9286 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); +#9287 = SURFACE_CURVE('',#9288,(#9292,#9299),.PCURVE_S1.); +#9288 = LINE('',#9289,#9290); +#9289 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); +#9290 = VECTOR('',#9291,1.); +#9291 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9292 = PCURVE('',#8058,#9293); +#9293 = DEFINITIONAL_REPRESENTATION('',(#9294),#9298); +#9294 = LINE('',#9295,#9296); +#9295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9296 = VECTOR('',#9297,1.); +#9297 = DIRECTION('',(0.E+000,1.)); +#9298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9299 = PCURVE('',#9300,#9305); +#9300 = PLANE('',#9301); +#9301 = AXIS2_PLACEMENT_3D('',#9302,#9303,#9304); +#9302 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9303 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#9304 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9305 = DEFINITIONAL_REPRESENTATION('',(#9306),#9310); +#9306 = LINE('',#9307,#9308); +#9307 = CARTESIAN_POINT('',(0.2,0.E+000)); +#9308 = VECTOR('',#9309,1.); +#9309 = DIRECTION('',(0.E+000,1.)); +#9310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9311 = ORIENTED_EDGE('',*,*,#9312,.T.); +#9312 = EDGE_CURVE('',#9285,#9064,#9313,.T.); +#9313 = SURFACE_CURVE('',#9314,(#9318,#9325),.PCURVE_S1.); +#9314 = LINE('',#9315,#9316); +#9315 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); +#9316 = VECTOR('',#9317,1.); +#9317 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9318 = PCURVE('',#8058,#9319); +#9319 = DEFINITIONAL_REPRESENTATION('',(#9320),#9324); +#9320 = LINE('',#9321,#9322); +#9321 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9322 = VECTOR('',#9323,1.); +#9323 = DIRECTION('',(1.,0.E+000)); +#9324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9325 = PCURVE('',#7660,#9326); +#9326 = DEFINITIONAL_REPRESENTATION('',(#9327),#9331); +#9327 = LINE('',#9328,#9329); +#9328 = CARTESIAN_POINT('',(0.24,0.E+000)); +#9329 = VECTOR('',#9330,1.); +#9330 = DIRECTION('',(-1.,0.E+000)); +#9331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9332 = ADVANCED_FACE('',(#9333),#9300,.T.); +#9333 = FACE_BOUND('',#9334,.T.); +#9334 = EDGE_LOOP('',(#9335,#9336,#9359,#9387)); +#9335 = ORIENTED_EDGE('',*,*,#9284,.T.); +#9336 = ORIENTED_EDGE('',*,*,#9337,.F.); +#9337 = EDGE_CURVE('',#9338,#9262,#9340,.T.); +#9338 = VERTEX_POINT('',#9339); +#9339 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); +#9340 = SURFACE_CURVE('',#9341,(#9345,#9352),.PCURVE_S1.); +#9341 = LINE('',#9342,#9343); +#9342 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); +#9343 = VECTOR('',#9344,1.); +#9344 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9345 = PCURVE('',#9300,#9346); +#9346 = DEFINITIONAL_REPRESENTATION('',(#9347),#9351); +#9347 = LINE('',#9348,#9349); +#9348 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9349 = VECTOR('',#9350,1.); +#9350 = DIRECTION('',(1.,0.E+000)); +#9351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9352 = PCURVE('',#8394,#9353); +#9353 = DEFINITIONAL_REPRESENTATION('',(#9354),#9358); +#9354 = LINE('',#9355,#9356); +#9355 = CARTESIAN_POINT('',(0.24,0.2)); +#9356 = VECTOR('',#9357,1.); +#9357 = DIRECTION('',(0.E+000,-1.)); +#9358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9359 = ORIENTED_EDGE('',*,*,#9360,.F.); +#9360 = EDGE_CURVE('',#9361,#9338,#9363,.T.); +#9361 = VERTEX_POINT('',#9362); +#9362 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9363 = SURFACE_CURVE('',#9364,(#9368,#9375),.PCURVE_S1.); +#9364 = LINE('',#9365,#9366); +#9365 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9366 = VECTOR('',#9367,1.); +#9367 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9368 = PCURVE('',#9300,#9369); +#9369 = DEFINITIONAL_REPRESENTATION('',(#9370),#9374); +#9370 = LINE('',#9371,#9372); +#9371 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9372 = VECTOR('',#9373,1.); +#9373 = DIRECTION('',(0.E+000,1.)); +#9374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9375 = PCURVE('',#9376,#9381); +#9376 = PLANE('',#9377); +#9377 = AXIS2_PLACEMENT_3D('',#9378,#9379,#9380); +#9378 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9379 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9380 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#9381 = DEFINITIONAL_REPRESENTATION('',(#9382),#9386); +#9382 = LINE('',#9383,#9384); +#9383 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9384 = VECTOR('',#9385,1.); +#9385 = DIRECTION('',(0.E+000,1.)); +#9386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9387 = ORIENTED_EDGE('',*,*,#9388,.T.); +#9388 = EDGE_CURVE('',#9361,#9285,#9389,.T.); +#9389 = SURFACE_CURVE('',#9390,(#9394,#9401),.PCURVE_S1.); +#9390 = LINE('',#9391,#9392); +#9391 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9392 = VECTOR('',#9393,1.); +#9393 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9394 = PCURVE('',#9300,#9395); +#9395 = DEFINITIONAL_REPRESENTATION('',(#9396),#9400); +#9396 = LINE('',#9397,#9398); +#9397 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9398 = VECTOR('',#9399,1.); +#9399 = DIRECTION('',(1.,0.E+000)); +#9400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9401 = PCURVE('',#7660,#9402); +#9402 = DEFINITIONAL_REPRESENTATION('',(#9403),#9407); +#9403 = LINE('',#9404,#9405); +#9404 = CARTESIAN_POINT('',(0.24,0.2)); +#9405 = VECTOR('',#9406,1.); +#9406 = DIRECTION('',(0.E+000,-1.)); +#9407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9408 = ADVANCED_FACE('',(#9409),#9376,.T.); +#9409 = FACE_BOUND('',#9410,.T.); +#9410 = EDGE_LOOP('',(#9411,#9412,#9435,#9458)); +#9411 = ORIENTED_EDGE('',*,*,#9360,.T.); +#9412 = ORIENTED_EDGE('',*,*,#9413,.F.); +#9413 = EDGE_CURVE('',#9414,#9338,#9416,.T.); +#9414 = VERTEX_POINT('',#9415); +#9415 = CARTESIAN_POINT('',(0.5,0.25,0.28)); +#9416 = SURFACE_CURVE('',#9417,(#9421,#9428),.PCURVE_S1.); +#9417 = LINE('',#9418,#9419); +#9418 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); +#9419 = VECTOR('',#9420,1.); +#9420 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#9421 = PCURVE('',#9376,#9422); +#9422 = DEFINITIONAL_REPRESENTATION('',(#9423),#9427); +#9423 = LINE('',#9424,#9425); +#9424 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9425 = VECTOR('',#9426,1.); +#9426 = DIRECTION('',(1.,0.E+000)); +#9427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9428 = PCURVE('',#8394,#9429); +#9429 = DEFINITIONAL_REPRESENTATION('',(#9430),#9434); +#9430 = LINE('',#9431,#9432); +#9431 = CARTESIAN_POINT('',(0.24,0.2)); +#9432 = VECTOR('',#9433,1.); +#9433 = DIRECTION('',(1.,0.E+000)); +#9434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9435 = ORIENTED_EDGE('',*,*,#9436,.F.); +#9436 = EDGE_CURVE('',#9437,#9414,#9439,.T.); +#9437 = VERTEX_POINT('',#9438); +#9438 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); +#9439 = SURFACE_CURVE('',#9440,(#9444,#9451),.PCURVE_S1.); +#9440 = LINE('',#9441,#9442); +#9441 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); +#9442 = VECTOR('',#9443,1.); +#9443 = DIRECTION('',(0.E+000,1.,0.E+000)); +#9444 = PCURVE('',#9376,#9445); +#9445 = DEFINITIONAL_REPRESENTATION('',(#9446),#9450); +#9446 = LINE('',#9447,#9448); +#9447 = CARTESIAN_POINT('',(-0.28,0.E+000)); +#9448 = VECTOR('',#9449,1.); +#9449 = DIRECTION('',(0.E+000,1.)); +#9450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9451 = PCURVE('',#7686,#9452); +#9452 = DEFINITIONAL_REPRESENTATION('',(#9453),#9457); +#9453 = LINE('',#9454,#9455); +#9454 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9455 = VECTOR('',#9456,1.); +#9456 = DIRECTION('',(0.E+000,1.)); +#9457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9458 = ORIENTED_EDGE('',*,*,#9459,.T.); +#9459 = EDGE_CURVE('',#9437,#9361,#9460,.T.); +#9460 = SURFACE_CURVE('',#9461,(#9465,#9472),.PCURVE_S1.); +#9461 = LINE('',#9462,#9463); +#9462 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); +#9463 = VECTOR('',#9464,1.); +#9464 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#9465 = PCURVE('',#9376,#9466); +#9466 = DEFINITIONAL_REPRESENTATION('',(#9467),#9471); +#9467 = LINE('',#9468,#9469); +#9468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9469 = VECTOR('',#9470,1.); +#9470 = DIRECTION('',(1.,0.E+000)); +#9471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9472 = PCURVE('',#7660,#9473); +#9473 = DEFINITIONAL_REPRESENTATION('',(#9474),#9478); +#9474 = LINE('',#9475,#9476); +#9475 = CARTESIAN_POINT('',(0.24,0.2)); +#9476 = VECTOR('',#9477,1.); +#9477 = DIRECTION('',(1.,0.E+000)); +#9478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9479 = ADVANCED_FACE('',(#9480),#7686,.T.); +#9480 = FACE_BOUND('',#9481,.T.); +#9481 = EDGE_LOOP('',(#9482,#9483,#9504,#9505,#9531,#9532)); +#9482 = ORIENTED_EDGE('',*,*,#9436,.T.); +#9483 = ORIENTED_EDGE('',*,*,#9484,.F.); +#9484 = EDGE_CURVE('',#9211,#9414,#9485,.T.); +#9485 = SURFACE_CURVE('',#9486,(#9490,#9497),.PCURVE_S1.); +#9486 = LINE('',#9487,#9488); +#9487 = CARTESIAN_POINT('',(0.5,0.25,0.28)); +#9488 = VECTOR('',#9489,1.); +#9489 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9490 = PCURVE('',#7686,#9491); +#9491 = DEFINITIONAL_REPRESENTATION('',(#9492),#9496); +#9492 = LINE('',#9493,#9494); +#9493 = CARTESIAN_POINT('',(0.E+000,0.5)); +#9494 = VECTOR('',#9495,1.); +#9495 = DIRECTION('',(1.,0.E+000)); +#9496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9497 = PCURVE('',#8394,#9498); +#9498 = DEFINITIONAL_REPRESENTATION('',(#9499),#9503); +#9499 = LINE('',#9500,#9501); +#9500 = CARTESIAN_POINT('',(-4.E-002,0.2)); +#9501 = VECTOR('',#9502,1.); +#9502 = DIRECTION('',(0.E+000,1.)); +#9503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9504 = ORIENTED_EDGE('',*,*,#9210,.F.); +#9505 = ORIENTED_EDGE('',*,*,#9506,.F.); +#9506 = EDGE_CURVE('',#7594,#9188,#9507,.T.); +#9507 = SURFACE_CURVE('',#9508,(#9512,#9519),.PCURVE_S1.); +#9508 = LINE('',#9509,#9510); +#9509 = CARTESIAN_POINT('',(0.3,0.245,0.28)); +#9510 = VECTOR('',#9511,1.); +#9511 = DIRECTION('',(1.106328747434E-016,1.,0.E+000)); +#9512 = PCURVE('',#7686,#9513); +#9513 = DEFINITIONAL_REPRESENTATION('',(#9514),#9518); +#9514 = LINE('',#9515,#9516); +#9515 = CARTESIAN_POINT('',(-0.2,0.495)); +#9516 = VECTOR('',#9517,1.); +#9517 = DIRECTION('',(1.106328747434E-016,1.)); +#9518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9519 = PCURVE('',#9520,#9525); +#9520 = PLANE('',#9521); +#9521 = AXIS2_PLACEMENT_3D('',#9522,#9523,#9524); +#9522 = CARTESIAN_POINT('',(0.3,0.245,0.28)); +#9523 = DIRECTION('',(0.866025403784,-9.58108800215E-017,0.5)); +#9524 = DIRECTION('',(0.5,3.111580566401E-033,-0.866025403784)); +#9525 = DEFINITIONAL_REPRESENTATION('',(#9526),#9530); +#9526 = LINE('',#9527,#9528); +#9527 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9528 = VECTOR('',#9529,1.); +#9529 = DIRECTION('',(5.531643737171E-017,1.)); +#9530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9531 = ORIENTED_EDGE('',*,*,#7672,.F.); +#9532 = ORIENTED_EDGE('',*,*,#9533,.T.); +#9533 = EDGE_CURVE('',#7645,#9437,#9534,.T.); +#9534 = SURFACE_CURVE('',#9535,(#9539,#9546),.PCURVE_S1.); +#9535 = LINE('',#9536,#9537); +#9536 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); +#9537 = VECTOR('',#9538,1.); +#9538 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9539 = PCURVE('',#7686,#9540); +#9540 = DEFINITIONAL_REPRESENTATION('',(#9541),#9545); +#9541 = LINE('',#9542,#9543); +#9542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9543 = VECTOR('',#9544,1.); +#9544 = DIRECTION('',(1.,0.E+000)); +#9545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9546 = PCURVE('',#7660,#9547); +#9547 = DEFINITIONAL_REPRESENTATION('',(#9548),#9552); +#9548 = LINE('',#9549,#9550); +#9549 = CARTESIAN_POINT('',(-4.E-002,0.2)); +#9550 = VECTOR('',#9551,1.); +#9551 = DIRECTION('',(0.E+000,1.)); +#9552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9553 = ADVANCED_FACE('',(#9554),#7660,.T.); +#9554 = FACE_BOUND('',#9555,.T.); +#9555 = EDGE_LOOP('',(#9556,#9557,#9558,#9559,#9560,#9561,#9562,#9563)); +#9556 = ORIENTED_EDGE('',*,*,#7644,.F.); +#9557 = ORIENTED_EDGE('',*,*,#8454,.F.); +#9558 = ORIENTED_EDGE('',*,*,#9162,.F.); +#9559 = ORIENTED_EDGE('',*,*,#9086,.F.); +#9560 = ORIENTED_EDGE('',*,*,#9312,.F.); +#9561 = ORIENTED_EDGE('',*,*,#9388,.F.); +#9562 = ORIENTED_EDGE('',*,*,#9459,.F.); +#9563 = ORIENTED_EDGE('',*,*,#9533,.F.); +#9564 = ADVANCED_FACE('',(#9565),#8394,.F.); +#9565 = FACE_BOUND('',#9566,.T.); +#9566 = EDGE_LOOP('',(#9567,#9568,#9569,#9570,#9571,#9572,#9573,#9574)); +#9567 = ORIENTED_EDGE('',*,*,#9233,.T.); +#9568 = ORIENTED_EDGE('',*,*,#9484,.T.); +#9569 = ORIENTED_EDGE('',*,*,#9413,.T.); +#9570 = ORIENTED_EDGE('',*,*,#9337,.T.); +#9571 = ORIENTED_EDGE('',*,*,#9261,.T.); +#9572 = ORIENTED_EDGE('',*,*,#9015,.T.); +#9573 = ORIENTED_EDGE('',*,*,#9135,.T.); +#9574 = ORIENTED_EDGE('',*,*,#8378,.T.); +#9575 = ADVANCED_FACE('',(#9576),#7494,.T.); +#9576 = FACE_BOUND('',#9577,.T.); +#9577 = EDGE_LOOP('',(#9578,#9604,#9605,#9606)); +#9578 = ORIENTED_EDGE('',*,*,#9579,.F.); +#9579 = EDGE_CURVE('',#7474,#7594,#9580,.T.); +#9580 = SURFACE_CURVE('',#9581,(#9585,#9592),.PCURVE_S1.); +#9581 = LINE('',#9582,#9583); +#9582 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); +#9583 = VECTOR('',#9584,1.); +#9584 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9585 = PCURVE('',#7494,#9586); +#9586 = DEFINITIONAL_REPRESENTATION('',(#9587),#9591); +#9587 = LINE('',#9588,#9589); +#9588 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); +#9589 = VECTOR('',#9590,1.); +#9590 = DIRECTION('',(0.E+000,1.)); +#9591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9592 = PCURVE('',#9593,#9598); +#9593 = PLANE('',#9594); +#9594 = AXIS2_PLACEMENT_3D('',#9595,#9596,#9597); +#9595 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); +#9596 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#9597 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#9598 = DEFINITIONAL_REPRESENTATION('',(#9599),#9603); +#9599 = LINE('',#9600,#9601); +#9600 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9601 = VECTOR('',#9602,1.); +#9602 = DIRECTION('',(0.E+000,1.)); +#9603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9604 = ORIENTED_EDGE('',*,*,#7471,.F.); +#9605 = ORIENTED_EDGE('',*,*,#8476,.T.); +#9606 = ORIENTED_EDGE('',*,*,#7591,.T.); +#9607 = ADVANCED_FACE('',(#9608),#8338,.T.); +#9608 = FACE_BOUND('',#9609,.T.); +#9609 = EDGE_LOOP('',(#9610,#9636,#9637,#9638)); +#9610 = ORIENTED_EDGE('',*,*,#9611,.F.); +#9611 = EDGE_CURVE('',#9188,#8825,#9612,.T.); +#9612 = SURFACE_CURVE('',#9613,(#9617,#9624),.PCURVE_S1.); +#9613 = LINE('',#9614,#9615); +#9614 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#9615 = VECTOR('',#9616,1.); +#9616 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9617 = PCURVE('',#8338,#9618); +#9618 = DEFINITIONAL_REPRESENTATION('',(#9619),#9623); +#9619 = LINE('',#9620,#9621); +#9620 = CARTESIAN_POINT('',(4.E-002,0.E+000)); +#9621 = VECTOR('',#9622,1.); +#9622 = DIRECTION('',(0.E+000,-1.)); +#9623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9624 = PCURVE('',#9625,#9630); +#9625 = PLANE('',#9626); +#9626 = AXIS2_PLACEMENT_3D('',#9627,#9628,#9629); +#9627 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#9628 = DIRECTION('',(0.E+000,0.866025403784,0.5)); +#9629 = DIRECTION('',(0.E+000,-0.5,0.866025403784)); +#9630 = DEFINITIONAL_REPRESENTATION('',(#9631),#9635); +#9631 = LINE('',#9632,#9633); +#9632 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9633 = VECTOR('',#9634,1.); +#9634 = DIRECTION('',(0.E+000,-1.)); +#9635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6638 = PCURVE('',#6002,#6639); -#6639 = DEFINITIONAL_REPRESENTATION('',(#6640),#6644); -#6640 = LINE('',#6641,#6642); -#6641 = CARTESIAN_POINT('',(0.2,0.16)); -#6642 = VECTOR('',#6643,1.); -#6643 = DIRECTION('',(0.E+000,1.)); -#6644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6645 = ORIENTED_EDGE('',*,*,#6646,.F.); -#6646 = EDGE_CURVE('',#5312,#6624,#6647,.T.); -#6647 = SURFACE_CURVE('',#6648,(#6652,#6659),.PCURVE_S1.); -#6648 = LINE('',#6649,#6650); -#6649 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); -#6650 = VECTOR('',#6651,1.); -#6651 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6652 = PCURVE('',#5332,#6653); -#6653 = DEFINITIONAL_REPRESENTATION('',(#6654),#6658); -#6654 = LINE('',#6655,#6656); -#6655 = CARTESIAN_POINT('',(-0.16,0.E+000)); -#6656 = VECTOR('',#6657,1.); -#6657 = DIRECTION('',(0.E+000,1.)); -#6658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6659 = PCURVE('',#5666,#6660); -#6660 = DEFINITIONAL_REPRESENTATION('',(#6661),#6665); -#6661 = LINE('',#6662,#6663); -#6662 = CARTESIAN_POINT('',(4.E-002,0.E+000)); -#6663 = VECTOR('',#6664,1.); -#6664 = DIRECTION('',(0.E+000,1.)); -#6665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6666 = ADVANCED_FACE('',(#6667),#5559,.T.); -#6667 = FACE_BOUND('',#6668,.T.); -#6668 = EDGE_LOOP('',(#6669,#6670,#6693,#6716)); -#6669 = ORIENTED_EDGE('',*,*,#5543,.F.); -#6670 = ORIENTED_EDGE('',*,*,#6671,.F.); -#6671 = EDGE_CURVE('',#6672,#5521,#6674,.T.); -#6672 = VERTEX_POINT('',#6673); -#6673 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); -#6674 = SURFACE_CURVE('',#6675,(#6679,#6686),.PCURVE_S1.); -#6675 = LINE('',#6676,#6677); -#6676 = CARTESIAN_POINT('',(0.3,-0.25,4.E-002)); -#6677 = VECTOR('',#6678,1.); -#6678 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6679 = PCURVE('',#5559,#6680); -#6680 = DEFINITIONAL_REPRESENTATION('',(#6681),#6685); -#6681 = LINE('',#6682,#6683); -#6682 = CARTESIAN_POINT('',(-0.16,0.E+000)); -#6683 = VECTOR('',#6684,1.); -#6684 = DIRECTION('',(0.E+000,1.)); -#6685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6686 = PCURVE('',#5666,#6687); -#6687 = DEFINITIONAL_REPRESENTATION('',(#6688),#6692); -#6688 = LINE('',#6689,#6690); -#6689 = CARTESIAN_POINT('',(4.E-002,0.E+000)); -#6690 = VECTOR('',#6691,1.); -#6691 = DIRECTION('',(0.E+000,1.)); -#6692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6693 = ORIENTED_EDGE('',*,*,#6694,.T.); -#6694 = EDGE_CURVE('',#6672,#6695,#6697,.T.); -#6695 = VERTEX_POINT('',#6696); -#6696 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#6697 = SURFACE_CURVE('',#6698,(#6702,#6709),.PCURVE_S1.); -#6698 = LINE('',#6699,#6700); -#6699 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#6700 = VECTOR('',#6701,1.); -#6701 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6702 = PCURVE('',#5559,#6703); -#6703 = DEFINITIONAL_REPRESENTATION('',(#6704),#6708); -#6704 = LINE('',#6705,#6706); -#6705 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6706 = VECTOR('',#6707,1.); -#6707 = DIRECTION('',(1.,0.E+000)); -#6708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#9636 = ORIENTED_EDGE('',*,*,#9187,.F.); +#9637 = ORIENTED_EDGE('',*,*,#8322,.T.); +#9638 = ORIENTED_EDGE('',*,*,#8824,.T.); +#9639 = ADVANCED_FACE('',(#9640),#9520,.T.); +#9640 = FACE_BOUND('',#9641,.T.); +#9641 = EDGE_LOOP('',(#9642,#9643,#9666,#9694)); +#9642 = ORIENTED_EDGE('',*,*,#9506,.T.); +#9643 = ORIENTED_EDGE('',*,*,#9644,.F.); +#9644 = EDGE_CURVE('',#9645,#9188,#9647,.T.); +#9645 = VERTEX_POINT('',#9646); +#9646 = CARTESIAN_POINT('',(0.288452994616,0.233452994616,0.3)); +#9647 = SURFACE_CURVE('',#9648,(#9652,#9659),.PCURVE_S1.); +#9648 = LINE('',#9649,#9650); +#9649 = CARTESIAN_POINT('',(0.18,0.125,0.487846096908)); +#9650 = VECTOR('',#9651,1.); +#9651 = DIRECTION('',(0.4472135955,0.4472135955,-0.774596669241)); +#9652 = PCURVE('',#9520,#9653); +#9653 = DEFINITIONAL_REPRESENTATION('',(#9654),#9658); +#9654 = LINE('',#9655,#9656); +#9655 = CARTESIAN_POINT('',(-0.24,-0.12)); +#9656 = VECTOR('',#9657,1.); +#9657 = DIRECTION('',(0.894427191,0.4472135955)); +#9658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9659 = PCURVE('',#9625,#9660); +#9660 = DEFINITIONAL_REPRESENTATION('',(#9661),#9665); +#9661 = LINE('',#9662,#9663); +#9662 = CARTESIAN_POINT('',(0.24,0.48)); +#9663 = VECTOR('',#9664,1.); +#9664 = DIRECTION('',(-0.894427191,0.4472135955)); +#9665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9666 = ORIENTED_EDGE('',*,*,#9667,.F.); +#9667 = EDGE_CURVE('',#9668,#9645,#9670,.T.); +#9668 = VERTEX_POINT('',#9669); +#9669 = CARTESIAN_POINT('',(0.288452994616,-0.233452994616,0.3)); +#9670 = SURFACE_CURVE('',#9671,(#9675,#9682),.PCURVE_S1.); +#9671 = LINE('',#9672,#9673); +#9672 = CARTESIAN_POINT('',(0.288452994616,0.245,0.3)); +#9673 = VECTOR('',#9674,1.); +#9674 = DIRECTION('',(1.106328747434E-016,1.,0.E+000)); +#9675 = PCURVE('',#9520,#9676); +#9676 = DEFINITIONAL_REPRESENTATION('',(#9677),#9681); +#9677 = LINE('',#9678,#9679); +#9678 = CARTESIAN_POINT('',(-2.309401076759E-002,4.132097742011E-034)); +#9679 = VECTOR('',#9680,1.); +#9680 = DIRECTION('',(5.531643737171E-017,1.)); +#9681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9682 = PCURVE('',#9683,#9688); +#9683 = PLANE('',#9684); +#9684 = AXIS2_PLACEMENT_3D('',#9685,#9686,#9687); +#9685 = CARTESIAN_POINT('',(0.3,-0.245,0.3)); +#9686 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9687 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9688 = DEFINITIONAL_REPRESENTATION('',(#9689),#9693); +#9689 = LINE('',#9690,#9691); +#9690 = CARTESIAN_POINT('',(-1.154700538379E-002,0.49)); +#9691 = VECTOR('',#9692,1.); +#9692 = DIRECTION('',(1.106328747434E-016,1.)); +#9693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9694 = ORIENTED_EDGE('',*,*,#9695,.T.); +#9695 = EDGE_CURVE('',#9668,#7594,#9696,.T.); +#9696 = SURFACE_CURVE('',#9697,(#9701,#9708),.PCURVE_S1.); +#9697 = LINE('',#9698,#9699); +#9698 = CARTESIAN_POINT('',(0.202,-0.147,0.449740979142)); +#9699 = VECTOR('',#9700,1.); +#9700 = DIRECTION('',(0.4472135955,-0.4472135955,-0.774596669241)); +#9701 = PCURVE('',#9520,#9702); +#9702 = DEFINITIONAL_REPRESENTATION('',(#9703),#9707); +#9703 = LINE('',#9704,#9705); +#9704 = CARTESIAN_POINT('',(-0.196,-0.392)); +#9705 = VECTOR('',#9706,1.); +#9706 = DIRECTION('',(0.894427191,-0.4472135955)); +#9707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9708 = PCURVE('',#9593,#9709); +#9709 = DEFINITIONAL_REPRESENTATION('',(#9710),#9714); +#9710 = LINE('',#9711,#9712); +#9711 = CARTESIAN_POINT('',(-0.196,0.502)); +#9712 = VECTOR('',#9713,1.); +#9713 = DIRECTION('',(0.894427191,0.4472135955)); +#9714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9715 = ADVANCED_FACE('',(#9716),#9625,.T.); +#9716 = FACE_BOUND('',#9717,.T.); +#9717 = EDGE_LOOP('',(#9718,#9719,#9742,#9763)); +#9718 = ORIENTED_EDGE('',*,*,#9611,.T.); +#9719 = ORIENTED_EDGE('',*,*,#9720,.F.); +#9720 = EDGE_CURVE('',#9721,#8825,#9723,.T.); +#9721 = VERTEX_POINT('',#9722); +#9722 = CARTESIAN_POINT('',(-0.288452994616,0.233452994616,0.3)); +#9723 = SURFACE_CURVE('',#9724,(#9728,#9735),.PCURVE_S1.); +#9724 = LINE('',#9725,#9726); +#9725 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); +#9726 = VECTOR('',#9727,1.); +#9727 = DIRECTION('',(-0.4472135955,0.4472135955,-0.774596669241)); +#9728 = PCURVE('',#9625,#9729); +#9729 = DEFINITIONAL_REPRESENTATION('',(#9730),#9734); +#9730 = LINE('',#9731,#9732); +#9731 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9732 = VECTOR('',#9733,1.); +#9733 = DIRECTION('',(-0.894427191,-0.4472135955)); +#9734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9735 = PCURVE('',#8910,#9736); +#9736 = DEFINITIONAL_REPRESENTATION('',(#9737),#9741); +#9737 = LINE('',#9738,#9739); +#9738 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9739 = VECTOR('',#9740,1.); +#9740 = DIRECTION('',(-0.894427191,0.4472135955)); +#9741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9742 = ORIENTED_EDGE('',*,*,#9743,.F.); +#9743 = EDGE_CURVE('',#9645,#9721,#9744,.T.); +#9744 = SURFACE_CURVE('',#9745,(#9749,#9756),.PCURVE_S1.); +#9745 = LINE('',#9746,#9747); +#9746 = CARTESIAN_POINT('',(-0.3,0.233452994616,0.3)); +#9747 = VECTOR('',#9748,1.); +#9748 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9749 = PCURVE('',#9625,#9750); +#9750 = DEFINITIONAL_REPRESENTATION('',(#9751),#9755); +#9751 = LINE('',#9752,#9753); +#9752 = CARTESIAN_POINT('',(2.309401076759E-002,0.E+000)); +#9753 = VECTOR('',#9754,1.); +#9754 = DIRECTION('',(0.E+000,-1.)); +#9755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9756 = PCURVE('',#9683,#9757); +#9757 = DEFINITIONAL_REPRESENTATION('',(#9758),#9762); +#9758 = LINE('',#9759,#9760); +#9759 = CARTESIAN_POINT('',(-0.6,0.478452994616)); +#9760 = VECTOR('',#9761,1.); +#9761 = DIRECTION('',(-1.,0.E+000)); +#9762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9763 = ORIENTED_EDGE('',*,*,#9644,.T.); +#9764 = ADVANCED_FACE('',(#9765),#8910,.T.); +#9765 = FACE_BOUND('',#9766,.T.); +#9766 = EDGE_LOOP('',(#9767,#9768,#9791,#9812)); +#9767 = ORIENTED_EDGE('',*,*,#8896,.T.); +#9768 = ORIENTED_EDGE('',*,*,#9769,.F.); +#9769 = EDGE_CURVE('',#9770,#7474,#9772,.T.); +#9770 = VERTEX_POINT('',#9771); +#9771 = CARTESIAN_POINT('',(-0.288452994616,-0.233452994616,0.3)); +#9772 = SURFACE_CURVE('',#9773,(#9777,#9784),.PCURVE_S1.); +#9773 = LINE('',#9774,#9775); +#9774 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); +#9775 = VECTOR('',#9776,1.); +#9776 = DIRECTION('',(-0.4472135955,-0.4472135955,-0.774596669241)); +#9777 = PCURVE('',#8910,#9778); +#9778 = DEFINITIONAL_REPRESENTATION('',(#9779),#9783); +#9779 = LINE('',#9780,#9781); +#9780 = CARTESIAN_POINT('',(0.E+000,-0.49)); +#9781 = VECTOR('',#9782,1.); +#9782 = DIRECTION('',(-0.894427191,-0.4472135955)); +#9783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9784 = PCURVE('',#9593,#9785); +#9785 = DEFINITIONAL_REPRESENTATION('',(#9786),#9790); +#9786 = LINE('',#9787,#9788); +#9787 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#9788 = VECTOR('',#9789,1.); +#9789 = DIRECTION('',(0.894427191,-0.4472135955)); +#9790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6709 = PCURVE('',#5268,#6710); -#6710 = DEFINITIONAL_REPRESENTATION('',(#6711),#6715); -#6711 = LINE('',#6712,#6713); -#6712 = CARTESIAN_POINT('',(0.2,0.16)); -#6713 = VECTOR('',#6714,1.); -#6714 = DIRECTION('',(0.E+000,1.)); -#6715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#9791 = ORIENTED_EDGE('',*,*,#9792,.F.); +#9792 = EDGE_CURVE('',#9721,#9770,#9793,.T.); +#9793 = SURFACE_CURVE('',#9794,(#9798,#9805),.PCURVE_S1.); +#9794 = LINE('',#9795,#9796); +#9795 = CARTESIAN_POINT('',(-0.288452994616,0.245,0.3)); +#9796 = VECTOR('',#9797,1.); +#9797 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#9798 = PCURVE('',#8910,#9799); +#9799 = DEFINITIONAL_REPRESENTATION('',(#9800),#9804); +#9800 = LINE('',#9801,#9802); +#9801 = CARTESIAN_POINT('',(2.309401076759E-002,0.E+000)); +#9802 = VECTOR('',#9803,1.); +#9803 = DIRECTION('',(0.E+000,-1.)); +#9804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#6716 = ORIENTED_EDGE('',*,*,#6717,.T.); -#6717 = EDGE_CURVE('',#6695,#5544,#6718,.T.); -#6718 = SURFACE_CURVE('',#6719,(#6723,#6730),.PCURVE_S1.); -#6719 = LINE('',#6720,#6721); -#6720 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#6721 = VECTOR('',#6722,1.); -#6722 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6723 = PCURVE('',#5559,#6724); -#6724 = DEFINITIONAL_REPRESENTATION('',(#6725),#6729); -#6725 = LINE('',#6726,#6727); -#6726 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6727 = VECTOR('',#6728,1.); -#6728 = DIRECTION('',(0.E+000,1.)); -#6729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6730 = PCURVE('',#5587,#6731); -#6731 = DEFINITIONAL_REPRESENTATION('',(#6732),#6736); -#6732 = LINE('',#6733,#6734); -#6733 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6734 = VECTOR('',#6735,1.); -#6735 = DIRECTION('',(0.E+000,1.)); -#6736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6737 = ADVANCED_FACE('',(#6738),#5470,.T.); -#6738 = FACE_BOUND('',#6739,.T.); -#6739 = EDGE_LOOP('',(#6740,#6741,#6742,#6763)); -#6740 = ORIENTED_EDGE('',*,*,#5456,.F.); -#6741 = ORIENTED_EDGE('',*,*,#6014,.T.); -#6742 = ORIENTED_EDGE('',*,*,#6743,.F.); -#6743 = EDGE_CURVE('',#6601,#5987,#6744,.T.); -#6744 = SURFACE_CURVE('',#6745,(#6749,#6756),.PCURVE_S1.); -#6745 = LINE('',#6746,#6747); -#6746 = CARTESIAN_POINT('',(0.46,0.25,4.E-002)); -#6747 = VECTOR('',#6748,1.); -#6748 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6749 = PCURVE('',#5470,#6750); -#6750 = DEFINITIONAL_REPRESENTATION('',(#6751),#6755); -#6751 = LINE('',#6752,#6753); -#6752 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6753 = VECTOR('',#6754,1.); -#6754 = DIRECTION('',(1.,0.E+000)); -#6755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6756 = PCURVE('',#6002,#6757); -#6757 = DEFINITIONAL_REPRESENTATION('',(#6758),#6762); -#6758 = LINE('',#6759,#6760); -#6759 = CARTESIAN_POINT('',(0.2,0.16)); -#6760 = VECTOR('',#6761,1.); -#6761 = DIRECTION('',(-1.,0.E+000)); -#6762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6763 = ORIENTED_EDGE('',*,*,#6600,.F.); -#6764 = ADVANCED_FACE('',(#6765),#5587,.T.); -#6765 = FACE_BOUND('',#6766,.T.); -#6766 = EDGE_LOOP('',(#6767,#6768,#6769,#6790)); -#6767 = ORIENTED_EDGE('',*,*,#5571,.T.); -#6768 = ORIENTED_EDGE('',*,*,#6717,.F.); -#6769 = ORIENTED_EDGE('',*,*,#6770,.T.); -#6770 = EDGE_CURVE('',#6695,#6040,#6771,.T.); -#6771 = SURFACE_CURVE('',#6772,(#6776,#6783),.PCURVE_S1.); -#6772 = LINE('',#6773,#6774); -#6773 = CARTESIAN_POINT('',(0.46,-0.25,4.E-002)); -#6774 = VECTOR('',#6775,1.); -#6775 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6776 = PCURVE('',#5587,#6777); -#6777 = DEFINITIONAL_REPRESENTATION('',(#6778),#6782); -#6778 = LINE('',#6779,#6780); -#6779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6780 = VECTOR('',#6781,1.); -#6781 = DIRECTION('',(1.,0.E+000)); -#6782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6783 = PCURVE('',#5268,#6784); -#6784 = DEFINITIONAL_REPRESENTATION('',(#6785),#6789); -#6785 = LINE('',#6786,#6787); -#6786 = CARTESIAN_POINT('',(0.2,0.16)); -#6787 = VECTOR('',#6788,1.); -#6788 = DIRECTION('',(-1.,0.E+000)); -#6789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6790 = ORIENTED_EDGE('',*,*,#6039,.T.); -#6791 = ADVANCED_FACE('',(#6792),#5974,.T.); -#6792 = FACE_BOUND('',#6793,.T.); -#6793 = EDGE_LOOP('',(#6794,#6817,#6840,#6861)); -#6794 = ORIENTED_EDGE('',*,*,#6795,.T.); -#6795 = EDGE_CURVE('',#5931,#6796,#6798,.T.); -#6796 = VERTEX_POINT('',#6797); -#6797 = CARTESIAN_POINT('',(0.3,0.245,0.28)); -#6798 = SURFACE_CURVE('',#6799,(#6803,#6810),.PCURVE_S1.); -#6799 = LINE('',#6800,#6801); -#6800 = CARTESIAN_POINT('',(0.3,0.245,0.24)); -#6801 = VECTOR('',#6802,1.); -#6802 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6803 = PCURVE('',#5974,#6804); -#6804 = DEFINITIONAL_REPRESENTATION('',(#6805),#6809); -#6805 = LINE('',#6806,#6807); -#6806 = CARTESIAN_POINT('',(-4.E-002,0.495)); -#6807 = VECTOR('',#6808,1.); -#6808 = DIRECTION('',(1.,0.E+000)); -#6809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6810 = PCURVE('',#5946,#6811); -#6811 = DEFINITIONAL_REPRESENTATION('',(#6812),#6816); -#6812 = LINE('',#6813,#6814); -#6813 = CARTESIAN_POINT('',(0.E+000,0.6)); -#6814 = VECTOR('',#6815,1.); -#6815 = DIRECTION('',(1.,0.E+000)); -#6816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6817 = ORIENTED_EDGE('',*,*,#6818,.T.); -#6818 = EDGE_CURVE('',#6796,#6819,#6821,.T.); -#6819 = VERTEX_POINT('',#6820); -#6820 = CARTESIAN_POINT('',(0.3,0.25,0.28)); -#6821 = SURFACE_CURVE('',#6822,(#6826,#6833),.PCURVE_S1.); -#6822 = LINE('',#6823,#6824); -#6823 = CARTESIAN_POINT('',(0.3,-0.25,0.28)); -#6824 = VECTOR('',#6825,1.); -#6825 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6826 = PCURVE('',#5974,#6827); -#6827 = DEFINITIONAL_REPRESENTATION('',(#6828),#6832); -#6828 = LINE('',#6829,#6830); -#6829 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6830 = VECTOR('',#6831,1.); -#6831 = DIRECTION('',(0.E+000,1.)); -#6832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6833 = PCURVE('',#5294,#6834); -#6834 = DEFINITIONAL_REPRESENTATION('',(#6835),#6839); -#6835 = LINE('',#6836,#6837); -#6836 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#6837 = VECTOR('',#6838,1.); -#6838 = DIRECTION('',(0.E+000,1.)); -#6839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6840 = ORIENTED_EDGE('',*,*,#6841,.F.); -#6841 = EDGE_CURVE('',#5959,#6819,#6842,.T.); -#6842 = SURFACE_CURVE('',#6843,(#6847,#6854),.PCURVE_S1.); -#6843 = LINE('',#6844,#6845); -#6844 = CARTESIAN_POINT('',(0.3,0.25,0.28)); -#6845 = VECTOR('',#6846,1.); -#6846 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6847 = PCURVE('',#5974,#6848); -#6848 = DEFINITIONAL_REPRESENTATION('',(#6849),#6853); -#6849 = LINE('',#6850,#6851); -#6850 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6851 = VECTOR('',#6852,1.); -#6852 = DIRECTION('',(1.,0.E+000)); -#6853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6854 = PCURVE('',#6002,#6855); -#6855 = DEFINITIONAL_REPRESENTATION('',(#6856),#6860); -#6856 = LINE('',#6857,#6858); -#6857 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#6858 = VECTOR('',#6859,1.); -#6859 = DIRECTION('',(-1.,0.E+000)); -#6860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6861 = ORIENTED_EDGE('',*,*,#5958,.F.); -#6862 = ADVANCED_FACE('',(#6863),#5666,.T.); -#6863 = FACE_BOUND('',#6864,.T.); -#6864 = EDGE_LOOP('',(#6865,#6866,#6867,#6868,#6891,#6919)); -#6865 = ORIENTED_EDGE('',*,*,#6671,.T.); -#6866 = ORIENTED_EDGE('',*,*,#5652,.F.); -#6867 = ORIENTED_EDGE('',*,*,#6646,.T.); -#6868 = ORIENTED_EDGE('',*,*,#6869,.F.); -#6869 = EDGE_CURVE('',#6870,#6624,#6872,.T.); -#6870 = VERTEX_POINT('',#6871); -#6871 = CARTESIAN_POINT('',(0.3,0.25,0.E+000)); -#6872 = SURFACE_CURVE('',#6873,(#6877,#6884),.PCURVE_S1.); -#6873 = LINE('',#6874,#6875); -#6874 = CARTESIAN_POINT('',(0.3,0.25,0.E+000)); -#6875 = VECTOR('',#6876,1.); -#6876 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6877 = PCURVE('',#5666,#6878); -#6878 = DEFINITIONAL_REPRESENTATION('',(#6879),#6883); -#6879 = LINE('',#6880,#6881); -#6880 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6881 = VECTOR('',#6882,1.); -#6882 = DIRECTION('',(1.,0.E+000)); -#6883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6884 = PCURVE('',#6002,#6885); -#6885 = DEFINITIONAL_REPRESENTATION('',(#6886),#6890); -#6886 = LINE('',#6887,#6888); -#6887 = CARTESIAN_POINT('',(0.24,0.E+000)); -#6888 = VECTOR('',#6889,1.); -#6889 = DIRECTION('',(-1.,0.E+000)); -#6890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6891 = ORIENTED_EDGE('',*,*,#6892,.F.); -#6892 = EDGE_CURVE('',#6893,#6870,#6895,.T.); -#6893 = VERTEX_POINT('',#6894); -#6894 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); -#6895 = SURFACE_CURVE('',#6896,(#6900,#6907),.PCURVE_S1.); -#6896 = LINE('',#6897,#6898); -#6897 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); -#6898 = VECTOR('',#6899,1.); -#6899 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6900 = PCURVE('',#5666,#6901); -#6901 = DEFINITIONAL_REPRESENTATION('',(#6902),#6906); -#6902 = LINE('',#6903,#6904); -#6903 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6904 = VECTOR('',#6905,1.); -#6905 = DIRECTION('',(0.E+000,1.)); -#6906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6907 = PCURVE('',#6908,#6913); -#6908 = PLANE('',#6909); -#6909 = AXIS2_PLACEMENT_3D('',#6910,#6911,#6912); -#6910 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#6911 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6912 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6913 = DEFINITIONAL_REPRESENTATION('',(#6914),#6918); -#6914 = LINE('',#6915,#6916); -#6915 = CARTESIAN_POINT('',(0.2,0.E+000)); -#6916 = VECTOR('',#6917,1.); -#6917 = DIRECTION('',(0.E+000,1.)); -#6918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6919 = ORIENTED_EDGE('',*,*,#6920,.T.); -#6920 = EDGE_CURVE('',#6893,#6672,#6921,.T.); -#6921 = SURFACE_CURVE('',#6922,(#6926,#6933),.PCURVE_S1.); -#6922 = LINE('',#6923,#6924); -#6923 = CARTESIAN_POINT('',(0.3,-0.25,0.E+000)); -#6924 = VECTOR('',#6925,1.); -#6925 = DIRECTION('',(0.E+000,0.E+000,1.)); -#6926 = PCURVE('',#5666,#6927); -#6927 = DEFINITIONAL_REPRESENTATION('',(#6928),#6932); -#6928 = LINE('',#6929,#6930); -#6929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6930 = VECTOR('',#6931,1.); -#6931 = DIRECTION('',(1.,0.E+000)); -#6932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6933 = PCURVE('',#5268,#6934); -#6934 = DEFINITIONAL_REPRESENTATION('',(#6935),#6939); -#6935 = LINE('',#6936,#6937); -#6936 = CARTESIAN_POINT('',(0.24,0.E+000)); -#6937 = VECTOR('',#6938,1.); -#6938 = DIRECTION('',(-1.,0.E+000)); -#6939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6940 = ADVANCED_FACE('',(#6941),#6908,.T.); -#6941 = FACE_BOUND('',#6942,.T.); -#6942 = EDGE_LOOP('',(#6943,#6944,#6967,#6995)); -#6943 = ORIENTED_EDGE('',*,*,#6892,.T.); -#6944 = ORIENTED_EDGE('',*,*,#6945,.F.); -#6945 = EDGE_CURVE('',#6946,#6870,#6948,.T.); -#6946 = VERTEX_POINT('',#6947); -#6947 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); -#6948 = SURFACE_CURVE('',#6949,(#6953,#6960),.PCURVE_S1.); -#6949 = LINE('',#6950,#6951); -#6950 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); -#6951 = VECTOR('',#6952,1.); -#6952 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#6953 = PCURVE('',#6908,#6954); -#6954 = DEFINITIONAL_REPRESENTATION('',(#6955),#6959); -#6955 = LINE('',#6956,#6957); -#6956 = CARTESIAN_POINT('',(0.E+000,0.5)); -#6957 = VECTOR('',#6958,1.); -#6958 = DIRECTION('',(1.,0.E+000)); -#6959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6960 = PCURVE('',#6002,#6961); -#6961 = DEFINITIONAL_REPRESENTATION('',(#6962),#6966); -#6962 = LINE('',#6963,#6964); -#6963 = CARTESIAN_POINT('',(0.24,0.2)); -#6964 = VECTOR('',#6965,1.); -#6965 = DIRECTION('',(0.E+000,-1.)); -#6966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6967 = ORIENTED_EDGE('',*,*,#6968,.F.); -#6968 = EDGE_CURVE('',#6969,#6946,#6971,.T.); -#6969 = VERTEX_POINT('',#6970); -#6970 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#6971 = SURFACE_CURVE('',#6972,(#6976,#6983),.PCURVE_S1.); -#6972 = LINE('',#6973,#6974); -#6973 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#6974 = VECTOR('',#6975,1.); -#6975 = DIRECTION('',(0.E+000,1.,0.E+000)); -#6976 = PCURVE('',#6908,#6977); -#6977 = DEFINITIONAL_REPRESENTATION('',(#6978),#6982); -#6978 = LINE('',#6979,#6980); -#6979 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6980 = VECTOR('',#6981,1.); -#6981 = DIRECTION('',(0.E+000,1.)); -#6982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6983 = PCURVE('',#6984,#6989); -#6984 = PLANE('',#6985); -#6985 = AXIS2_PLACEMENT_3D('',#6986,#6987,#6988); -#6986 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#6987 = DIRECTION('',(1.,0.E+000,0.E+000)); -#6988 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#6989 = DEFINITIONAL_REPRESENTATION('',(#6990),#6994); -#6990 = LINE('',#6991,#6992); -#6991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#6992 = VECTOR('',#6993,1.); -#6993 = DIRECTION('',(0.E+000,1.)); -#6994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#6995 = ORIENTED_EDGE('',*,*,#6996,.T.); -#6996 = EDGE_CURVE('',#6969,#6893,#6997,.T.); -#6997 = SURFACE_CURVE('',#6998,(#7002,#7009),.PCURVE_S1.); -#6998 = LINE('',#6999,#7000); -#6999 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#7000 = VECTOR('',#7001,1.); -#7001 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7002 = PCURVE('',#6908,#7003); -#7003 = DEFINITIONAL_REPRESENTATION('',(#7004),#7008); -#7004 = LINE('',#7005,#7006); -#7005 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7006 = VECTOR('',#7007,1.); -#7007 = DIRECTION('',(1.,0.E+000)); -#7008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7009 = PCURVE('',#5268,#7010); -#7010 = DEFINITIONAL_REPRESENTATION('',(#7011),#7015); -#7011 = LINE('',#7012,#7013); -#7012 = CARTESIAN_POINT('',(0.24,0.2)); -#7013 = VECTOR('',#7014,1.); -#7014 = DIRECTION('',(0.E+000,-1.)); -#7015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7016 = ADVANCED_FACE('',(#7017),#6984,.T.); -#7017 = FACE_BOUND('',#7018,.T.); -#7018 = EDGE_LOOP('',(#7019,#7020,#7043,#7066)); -#7019 = ORIENTED_EDGE('',*,*,#6968,.T.); -#7020 = ORIENTED_EDGE('',*,*,#7021,.F.); -#7021 = EDGE_CURVE('',#7022,#6946,#7024,.T.); -#7022 = VERTEX_POINT('',#7023); -#7023 = CARTESIAN_POINT('',(0.5,0.25,0.28)); -#7024 = SURFACE_CURVE('',#7025,(#7029,#7036),.PCURVE_S1.); -#7025 = LINE('',#7026,#7027); -#7026 = CARTESIAN_POINT('',(0.5,0.25,0.E+000)); -#7027 = VECTOR('',#7028,1.); -#7028 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7029 = PCURVE('',#6984,#7030); -#7030 = DEFINITIONAL_REPRESENTATION('',(#7031),#7035); -#7031 = LINE('',#7032,#7033); -#7032 = CARTESIAN_POINT('',(0.E+000,0.5)); -#7033 = VECTOR('',#7034,1.); -#7034 = DIRECTION('',(1.,0.E+000)); -#7035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7036 = PCURVE('',#6002,#7037); -#7037 = DEFINITIONAL_REPRESENTATION('',(#7038),#7042); -#7038 = LINE('',#7039,#7040); -#7039 = CARTESIAN_POINT('',(0.24,0.2)); -#7040 = VECTOR('',#7041,1.); -#7041 = DIRECTION('',(1.,0.E+000)); -#7042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7043 = ORIENTED_EDGE('',*,*,#7044,.F.); -#7044 = EDGE_CURVE('',#7045,#7022,#7047,.T.); -#7045 = VERTEX_POINT('',#7046); -#7046 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); -#7047 = SURFACE_CURVE('',#7048,(#7052,#7059),.PCURVE_S1.); -#7048 = LINE('',#7049,#7050); -#7049 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); -#7050 = VECTOR('',#7051,1.); -#7051 = DIRECTION('',(0.E+000,1.,0.E+000)); -#7052 = PCURVE('',#6984,#7053); -#7053 = DEFINITIONAL_REPRESENTATION('',(#7054),#7058); -#7054 = LINE('',#7055,#7056); -#7055 = CARTESIAN_POINT('',(-0.28,0.E+000)); -#7056 = VECTOR('',#7057,1.); -#7057 = DIRECTION('',(0.E+000,1.)); -#7058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7059 = PCURVE('',#5294,#7060); -#7060 = DEFINITIONAL_REPRESENTATION('',(#7061),#7065); -#7061 = LINE('',#7062,#7063); -#7062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7063 = VECTOR('',#7064,1.); -#7064 = DIRECTION('',(0.E+000,1.)); -#7065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7066 = ORIENTED_EDGE('',*,*,#7067,.T.); -#7067 = EDGE_CURVE('',#7045,#6969,#7068,.T.); -#7068 = SURFACE_CURVE('',#7069,(#7073,#7080),.PCURVE_S1.); -#7069 = LINE('',#7070,#7071); -#7070 = CARTESIAN_POINT('',(0.5,-0.25,0.E+000)); -#7071 = VECTOR('',#7072,1.); -#7072 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7073 = PCURVE('',#6984,#7074); -#7074 = DEFINITIONAL_REPRESENTATION('',(#7075),#7079); -#7075 = LINE('',#7076,#7077); -#7076 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7077 = VECTOR('',#7078,1.); -#7078 = DIRECTION('',(1.,0.E+000)); -#7079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7080 = PCURVE('',#5268,#7081); -#7081 = DEFINITIONAL_REPRESENTATION('',(#7082),#7086); -#7082 = LINE('',#7083,#7084); -#7083 = CARTESIAN_POINT('',(0.24,0.2)); -#7084 = VECTOR('',#7085,1.); -#7085 = DIRECTION('',(1.,0.E+000)); -#7086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7087 = ADVANCED_FACE('',(#7088),#5294,.T.); -#7088 = FACE_BOUND('',#7089,.T.); -#7089 = EDGE_LOOP('',(#7090,#7091,#7112,#7113,#7139,#7140)); -#7090 = ORIENTED_EDGE('',*,*,#7044,.T.); -#7091 = ORIENTED_EDGE('',*,*,#7092,.F.); -#7092 = EDGE_CURVE('',#6819,#7022,#7093,.T.); -#7093 = SURFACE_CURVE('',#7094,(#7098,#7105),.PCURVE_S1.); -#7094 = LINE('',#7095,#7096); -#7095 = CARTESIAN_POINT('',(0.5,0.25,0.28)); -#7096 = VECTOR('',#7097,1.); -#7097 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7098 = PCURVE('',#5294,#7099); -#7099 = DEFINITIONAL_REPRESENTATION('',(#7100),#7104); -#7100 = LINE('',#7101,#7102); -#7101 = CARTESIAN_POINT('',(0.E+000,0.5)); -#7102 = VECTOR('',#7103,1.); -#7103 = DIRECTION('',(1.,0.E+000)); -#7104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7105 = PCURVE('',#6002,#7106); -#7106 = DEFINITIONAL_REPRESENTATION('',(#7107),#7111); -#7107 = LINE('',#7108,#7109); -#7108 = CARTESIAN_POINT('',(-4.E-002,0.2)); -#7109 = VECTOR('',#7110,1.); -#7110 = DIRECTION('',(0.E+000,1.)); -#7111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7112 = ORIENTED_EDGE('',*,*,#6818,.F.); -#7113 = ORIENTED_EDGE('',*,*,#7114,.F.); -#7114 = EDGE_CURVE('',#5202,#6796,#7115,.T.); -#7115 = SURFACE_CURVE('',#7116,(#7120,#7127),.PCURVE_S1.); -#7116 = LINE('',#7117,#7118); -#7117 = CARTESIAN_POINT('',(0.3,0.245,0.28)); -#7118 = VECTOR('',#7119,1.); -#7119 = DIRECTION('',(1.106328747434E-016,1.,0.E+000)); -#7120 = PCURVE('',#5294,#7121); -#7121 = DEFINITIONAL_REPRESENTATION('',(#7122),#7126); -#7122 = LINE('',#7123,#7124); -#7123 = CARTESIAN_POINT('',(-0.2,0.495)); -#7124 = VECTOR('',#7125,1.); -#7125 = DIRECTION('',(1.106328747434E-016,1.)); -#7126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#9805 = PCURVE('',#9683,#9806); +#9806 = DEFINITIONAL_REPRESENTATION('',(#9807),#9811); +#9807 = LINE('',#9808,#9809); +#9808 = CARTESIAN_POINT('',(-0.588452994616,0.49)); +#9809 = VECTOR('',#9810,1.); +#9810 = DIRECTION('',(0.E+000,-1.)); +#9811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#7127 = PCURVE('',#7128,#7133); -#7128 = PLANE('',#7129); -#7129 = AXIS2_PLACEMENT_3D('',#7130,#7131,#7132); -#7130 = CARTESIAN_POINT('',(0.3,0.245,0.28)); -#7131 = DIRECTION('',(0.866025403784,-9.58108800215E-017,0.5)); -#7132 = DIRECTION('',(0.5,3.111580566401E-033,-0.866025403784)); -#7133 = DEFINITIONAL_REPRESENTATION('',(#7134),#7138); -#7134 = LINE('',#7135,#7136); -#7135 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7136 = VECTOR('',#7137,1.); -#7137 = DIRECTION('',(5.531643737171E-017,1.)); -#7138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7139 = ORIENTED_EDGE('',*,*,#5280,.F.); -#7140 = ORIENTED_EDGE('',*,*,#7141,.T.); -#7141 = EDGE_CURVE('',#5253,#7045,#7142,.T.); -#7142 = SURFACE_CURVE('',#7143,(#7147,#7154),.PCURVE_S1.); -#7143 = LINE('',#7144,#7145); -#7144 = CARTESIAN_POINT('',(0.5,-0.25,0.28)); -#7145 = VECTOR('',#7146,1.); -#7146 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7147 = PCURVE('',#5294,#7148); -#7148 = DEFINITIONAL_REPRESENTATION('',(#7149),#7153); -#7149 = LINE('',#7150,#7151); -#7150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7151 = VECTOR('',#7152,1.); -#7152 = DIRECTION('',(1.,0.E+000)); -#7153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7154 = PCURVE('',#5268,#7155); -#7155 = DEFINITIONAL_REPRESENTATION('',(#7156),#7160); -#7156 = LINE('',#7157,#7158); -#7157 = CARTESIAN_POINT('',(-4.E-002,0.2)); -#7158 = VECTOR('',#7159,1.); -#7159 = DIRECTION('',(0.E+000,1.)); -#7160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7161 = ADVANCED_FACE('',(#7162),#5268,.T.); -#7162 = FACE_BOUND('',#7163,.T.); -#7163 = EDGE_LOOP('',(#7164,#7165,#7166,#7167,#7168,#7169,#7170,#7171)); -#7164 = ORIENTED_EDGE('',*,*,#5252,.F.); -#7165 = ORIENTED_EDGE('',*,*,#6062,.F.); -#7166 = ORIENTED_EDGE('',*,*,#6770,.F.); -#7167 = ORIENTED_EDGE('',*,*,#6694,.F.); -#7168 = ORIENTED_EDGE('',*,*,#6920,.F.); -#7169 = ORIENTED_EDGE('',*,*,#6996,.F.); -#7170 = ORIENTED_EDGE('',*,*,#7067,.F.); -#7171 = ORIENTED_EDGE('',*,*,#7141,.F.); -#7172 = ADVANCED_FACE('',(#7173),#6002,.F.); -#7173 = FACE_BOUND('',#7174,.T.); -#7174 = EDGE_LOOP('',(#7175,#7176,#7177,#7178,#7179,#7180,#7181,#7182)); -#7175 = ORIENTED_EDGE('',*,*,#6841,.T.); -#7176 = ORIENTED_EDGE('',*,*,#7092,.T.); -#7177 = ORIENTED_EDGE('',*,*,#7021,.T.); -#7178 = ORIENTED_EDGE('',*,*,#6945,.T.); -#7179 = ORIENTED_EDGE('',*,*,#6869,.T.); -#7180 = ORIENTED_EDGE('',*,*,#6623,.T.); -#7181 = ORIENTED_EDGE('',*,*,#6743,.T.); -#7182 = ORIENTED_EDGE('',*,*,#5986,.T.); -#7183 = ADVANCED_FACE('',(#7184),#5102,.T.); -#7184 = FACE_BOUND('',#7185,.T.); -#7185 = EDGE_LOOP('',(#7186,#7212,#7213,#7214)); -#7186 = ORIENTED_EDGE('',*,*,#7187,.F.); -#7187 = EDGE_CURVE('',#5082,#5202,#7188,.T.); -#7188 = SURFACE_CURVE('',#7189,(#7193,#7200),.PCURVE_S1.); -#7189 = LINE('',#7190,#7191); -#7190 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); -#7191 = VECTOR('',#7192,1.); -#7192 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7193 = PCURVE('',#5102,#7194); -#7194 = DEFINITIONAL_REPRESENTATION('',(#7195),#7199); -#7195 = LINE('',#7196,#7197); -#7196 = CARTESIAN_POINT('',(-4.E-002,0.E+000)); -#7197 = VECTOR('',#7198,1.); -#7198 = DIRECTION('',(0.E+000,1.)); -#7199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7200 = PCURVE('',#7201,#7206); -#7201 = PLANE('',#7202); -#7202 = AXIS2_PLACEMENT_3D('',#7203,#7204,#7205); -#7203 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); -#7204 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#7205 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#7206 = DEFINITIONAL_REPRESENTATION('',(#7207),#7211); -#7207 = LINE('',#7208,#7209); -#7208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7209 = VECTOR('',#7210,1.); -#7210 = DIRECTION('',(0.E+000,1.)); -#7211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7212 = ORIENTED_EDGE('',*,*,#5079,.F.); -#7213 = ORIENTED_EDGE('',*,*,#6084,.T.); -#7214 = ORIENTED_EDGE('',*,*,#5199,.T.); -#7215 = ADVANCED_FACE('',(#7216),#5946,.T.); -#7216 = FACE_BOUND('',#7217,.T.); -#7217 = EDGE_LOOP('',(#7218,#7244,#7245,#7246)); -#7218 = ORIENTED_EDGE('',*,*,#7219,.F.); -#7219 = EDGE_CURVE('',#6796,#6433,#7220,.T.); -#7220 = SURFACE_CURVE('',#7221,(#7225,#7232),.PCURVE_S1.); -#7221 = LINE('',#7222,#7223); -#7222 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#7223 = VECTOR('',#7224,1.); -#7224 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7225 = PCURVE('',#5946,#7226); -#7226 = DEFINITIONAL_REPRESENTATION('',(#7227),#7231); -#7227 = LINE('',#7228,#7229); -#7228 = CARTESIAN_POINT('',(4.E-002,0.E+000)); -#7229 = VECTOR('',#7230,1.); -#7230 = DIRECTION('',(0.E+000,-1.)); -#7231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7232 = PCURVE('',#7233,#7238); -#7233 = PLANE('',#7234); -#7234 = AXIS2_PLACEMENT_3D('',#7235,#7236,#7237); -#7235 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#7236 = DIRECTION('',(0.E+000,0.866025403784,0.5)); -#7237 = DIRECTION('',(0.E+000,-0.5,0.866025403784)); -#7238 = DEFINITIONAL_REPRESENTATION('',(#7239),#7243); -#7239 = LINE('',#7240,#7241); -#7240 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7241 = VECTOR('',#7242,1.); -#7242 = DIRECTION('',(0.E+000,-1.)); -#7243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7244 = ORIENTED_EDGE('',*,*,#6795,.F.); -#7245 = ORIENTED_EDGE('',*,*,#5930,.T.); -#7246 = ORIENTED_EDGE('',*,*,#6432,.T.); -#7247 = ADVANCED_FACE('',(#7248),#7128,.T.); -#7248 = FACE_BOUND('',#7249,.T.); -#7249 = EDGE_LOOP('',(#7250,#7251,#7274,#7302)); -#7250 = ORIENTED_EDGE('',*,*,#7114,.T.); -#7251 = ORIENTED_EDGE('',*,*,#7252,.F.); -#7252 = EDGE_CURVE('',#7253,#6796,#7255,.T.); -#7253 = VERTEX_POINT('',#7254); -#7254 = CARTESIAN_POINT('',(0.288452994616,0.233452994616,0.3)); -#7255 = SURFACE_CURVE('',#7256,(#7260,#7267),.PCURVE_S1.); -#7256 = LINE('',#7257,#7258); -#7257 = CARTESIAN_POINT('',(0.18,0.125,0.487846096908)); -#7258 = VECTOR('',#7259,1.); -#7259 = DIRECTION('',(0.4472135955,0.4472135955,-0.774596669241)); -#7260 = PCURVE('',#7128,#7261); -#7261 = DEFINITIONAL_REPRESENTATION('',(#7262),#7266); -#7262 = LINE('',#7263,#7264); -#7263 = CARTESIAN_POINT('',(-0.24,-0.12)); -#7264 = VECTOR('',#7265,1.); -#7265 = DIRECTION('',(0.894427191,0.4472135955)); -#7266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7267 = PCURVE('',#7233,#7268); -#7268 = DEFINITIONAL_REPRESENTATION('',(#7269),#7273); -#7269 = LINE('',#7270,#7271); -#7270 = CARTESIAN_POINT('',(0.24,0.48)); -#7271 = VECTOR('',#7272,1.); -#7272 = DIRECTION('',(-0.894427191,0.4472135955)); -#7273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7274 = ORIENTED_EDGE('',*,*,#7275,.F.); -#7275 = EDGE_CURVE('',#7276,#7253,#7278,.T.); -#7276 = VERTEX_POINT('',#7277); -#7277 = CARTESIAN_POINT('',(0.288452994616,-0.233452994616,0.3)); -#7278 = SURFACE_CURVE('',#7279,(#7283,#7290),.PCURVE_S1.); -#7279 = LINE('',#7280,#7281); -#7280 = CARTESIAN_POINT('',(0.288452994616,0.245,0.3)); -#7281 = VECTOR('',#7282,1.); -#7282 = DIRECTION('',(1.106328747434E-016,1.,0.E+000)); -#7283 = PCURVE('',#7128,#7284); -#7284 = DEFINITIONAL_REPRESENTATION('',(#7285),#7289); -#7285 = LINE('',#7286,#7287); -#7286 = CARTESIAN_POINT('',(-2.309401076759E-002,4.132097742011E-034)); -#7287 = VECTOR('',#7288,1.); -#7288 = DIRECTION('',(5.531643737171E-017,1.)); -#7289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7290 = PCURVE('',#7291,#7296); -#7291 = PLANE('',#7292); -#7292 = AXIS2_PLACEMENT_3D('',#7293,#7294,#7295); -#7293 = CARTESIAN_POINT('',(0.3,-0.245,0.3)); -#7294 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7295 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7296 = DEFINITIONAL_REPRESENTATION('',(#7297),#7301); -#7297 = LINE('',#7298,#7299); -#7298 = CARTESIAN_POINT('',(-1.154700538379E-002,0.49)); -#7299 = VECTOR('',#7300,1.); -#7300 = DIRECTION('',(1.106328747434E-016,1.)); -#7301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7302 = ORIENTED_EDGE('',*,*,#7303,.T.); -#7303 = EDGE_CURVE('',#7276,#5202,#7304,.T.); -#7304 = SURFACE_CURVE('',#7305,(#7309,#7316),.PCURVE_S1.); -#7305 = LINE('',#7306,#7307); -#7306 = CARTESIAN_POINT('',(0.202,-0.147,0.449740979142)); -#7307 = VECTOR('',#7308,1.); -#7308 = DIRECTION('',(0.4472135955,-0.4472135955,-0.774596669241)); -#7309 = PCURVE('',#7128,#7310); -#7310 = DEFINITIONAL_REPRESENTATION('',(#7311),#7315); -#7311 = LINE('',#7312,#7313); -#7312 = CARTESIAN_POINT('',(-0.196,-0.392)); -#7313 = VECTOR('',#7314,1.); -#7314 = DIRECTION('',(0.894427191,-0.4472135955)); -#7315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7316 = PCURVE('',#7201,#7317); -#7317 = DEFINITIONAL_REPRESENTATION('',(#7318),#7322); -#7318 = LINE('',#7319,#7320); -#7319 = CARTESIAN_POINT('',(-0.196,0.502)); -#7320 = VECTOR('',#7321,1.); -#7321 = DIRECTION('',(0.894427191,0.4472135955)); -#7322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7323 = ADVANCED_FACE('',(#7324),#7233,.T.); -#7324 = FACE_BOUND('',#7325,.T.); -#7325 = EDGE_LOOP('',(#7326,#7327,#7350,#7371)); -#7326 = ORIENTED_EDGE('',*,*,#7219,.T.); -#7327 = ORIENTED_EDGE('',*,*,#7328,.F.); -#7328 = EDGE_CURVE('',#7329,#6433,#7331,.T.); -#7329 = VERTEX_POINT('',#7330); -#7330 = CARTESIAN_POINT('',(-0.288452994616,0.233452994616,0.3)); -#7331 = SURFACE_CURVE('',#7332,(#7336,#7343),.PCURVE_S1.); -#7332 = LINE('',#7333,#7334); -#7333 = CARTESIAN_POINT('',(-0.3,0.245,0.28)); -#7334 = VECTOR('',#7335,1.); -#7335 = DIRECTION('',(-0.4472135955,0.4472135955,-0.774596669241)); -#7336 = PCURVE('',#7233,#7337); -#7337 = DEFINITIONAL_REPRESENTATION('',(#7338),#7342); -#7338 = LINE('',#7339,#7340); -#7339 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7340 = VECTOR('',#7341,1.); -#7341 = DIRECTION('',(-0.894427191,-0.4472135955)); -#7342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7343 = PCURVE('',#6518,#7344); -#7344 = DEFINITIONAL_REPRESENTATION('',(#7345),#7349); -#7345 = LINE('',#7346,#7347); -#7346 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7347 = VECTOR('',#7348,1.); -#7348 = DIRECTION('',(-0.894427191,0.4472135955)); -#7349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7350 = ORIENTED_EDGE('',*,*,#7351,.F.); -#7351 = EDGE_CURVE('',#7253,#7329,#7352,.T.); -#7352 = SURFACE_CURVE('',#7353,(#7357,#7364),.PCURVE_S1.); -#7353 = LINE('',#7354,#7355); -#7354 = CARTESIAN_POINT('',(-0.3,0.233452994616,0.3)); -#7355 = VECTOR('',#7356,1.); -#7356 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7357 = PCURVE('',#7233,#7358); -#7358 = DEFINITIONAL_REPRESENTATION('',(#7359),#7363); -#7359 = LINE('',#7360,#7361); -#7360 = CARTESIAN_POINT('',(2.309401076759E-002,0.E+000)); -#7361 = VECTOR('',#7362,1.); -#7362 = DIRECTION('',(0.E+000,-1.)); -#7363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7364 = PCURVE('',#7291,#7365); -#7365 = DEFINITIONAL_REPRESENTATION('',(#7366),#7370); -#7366 = LINE('',#7367,#7368); -#7367 = CARTESIAN_POINT('',(-0.6,0.478452994616)); -#7368 = VECTOR('',#7369,1.); -#7369 = DIRECTION('',(-1.,0.E+000)); -#7370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7371 = ORIENTED_EDGE('',*,*,#7252,.T.); -#7372 = ADVANCED_FACE('',(#7373),#6518,.T.); -#7373 = FACE_BOUND('',#7374,.T.); -#7374 = EDGE_LOOP('',(#7375,#7376,#7399,#7420)); -#7375 = ORIENTED_EDGE('',*,*,#6504,.T.); -#7376 = ORIENTED_EDGE('',*,*,#7377,.F.); -#7377 = EDGE_CURVE('',#7378,#5082,#7380,.T.); -#7378 = VERTEX_POINT('',#7379); -#7379 = CARTESIAN_POINT('',(-0.288452994616,-0.233452994616,0.3)); -#7380 = SURFACE_CURVE('',#7381,(#7385,#7392),.PCURVE_S1.); -#7381 = LINE('',#7382,#7383); -#7382 = CARTESIAN_POINT('',(-0.3,-0.245,0.28)); -#7383 = VECTOR('',#7384,1.); -#7384 = DIRECTION('',(-0.4472135955,-0.4472135955,-0.774596669241)); -#7385 = PCURVE('',#6518,#7386); -#7386 = DEFINITIONAL_REPRESENTATION('',(#7387),#7391); -#7387 = LINE('',#7388,#7389); -#7388 = CARTESIAN_POINT('',(0.E+000,-0.49)); -#7389 = VECTOR('',#7390,1.); -#7390 = DIRECTION('',(-0.894427191,-0.4472135955)); -#7391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7392 = PCURVE('',#7201,#7393); -#7393 = DEFINITIONAL_REPRESENTATION('',(#7394),#7398); -#7394 = LINE('',#7395,#7396); -#7395 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7396 = VECTOR('',#7397,1.); -#7397 = DIRECTION('',(0.894427191,-0.4472135955)); -#7398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7399 = ORIENTED_EDGE('',*,*,#7400,.F.); -#7400 = EDGE_CURVE('',#7329,#7378,#7401,.T.); -#7401 = SURFACE_CURVE('',#7402,(#7406,#7413),.PCURVE_S1.); -#7402 = LINE('',#7403,#7404); -#7403 = CARTESIAN_POINT('',(-0.288452994616,0.245,0.3)); -#7404 = VECTOR('',#7405,1.); -#7405 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#7406 = PCURVE('',#6518,#7407); -#7407 = DEFINITIONAL_REPRESENTATION('',(#7408),#7412); -#7408 = LINE('',#7409,#7410); -#7409 = CARTESIAN_POINT('',(2.309401076759E-002,0.E+000)); -#7410 = VECTOR('',#7411,1.); -#7411 = DIRECTION('',(0.E+000,-1.)); -#7412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7413 = PCURVE('',#7291,#7414); -#7414 = DEFINITIONAL_REPRESENTATION('',(#7415),#7419); -#7415 = LINE('',#7416,#7417); -#7416 = CARTESIAN_POINT('',(-0.588452994616,0.49)); -#7417 = VECTOR('',#7418,1.); -#7418 = DIRECTION('',(0.E+000,-1.)); -#7419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7420 = ORIENTED_EDGE('',*,*,#7328,.T.); -#7421 = ADVANCED_FACE('',(#7422),#7201,.T.); -#7422 = FACE_BOUND('',#7423,.T.); -#7423 = EDGE_LOOP('',(#7424,#7425,#7426,#7447)); -#7424 = ORIENTED_EDGE('',*,*,#7187,.T.); -#7425 = ORIENTED_EDGE('',*,*,#7303,.F.); -#7426 = ORIENTED_EDGE('',*,*,#7427,.F.); -#7427 = EDGE_CURVE('',#7378,#7276,#7428,.T.); -#7428 = SURFACE_CURVE('',#7429,(#7433,#7440),.PCURVE_S1.); -#7429 = LINE('',#7430,#7431); -#7430 = CARTESIAN_POINT('',(-0.3,-0.233452994616,0.3)); -#7431 = VECTOR('',#7432,1.); -#7432 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7433 = PCURVE('',#7201,#7434); -#7434 = DEFINITIONAL_REPRESENTATION('',(#7435),#7439); -#7435 = LINE('',#7436,#7437); -#7436 = CARTESIAN_POINT('',(-2.309401076759E-002,0.E+000)); -#7437 = VECTOR('',#7438,1.); -#7438 = DIRECTION('',(0.E+000,1.)); -#7439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7440 = PCURVE('',#7291,#7441); -#7441 = DEFINITIONAL_REPRESENTATION('',(#7442),#7446); -#7442 = LINE('',#7443,#7444); -#7443 = CARTESIAN_POINT('',(-0.6,1.154700538379E-002)); -#7444 = VECTOR('',#7445,1.); -#7445 = DIRECTION('',(1.,0.E+000)); -#7446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7447 = ORIENTED_EDGE('',*,*,#7377,.T.); -#7448 = ADVANCED_FACE('',(#7449),#7291,.T.); -#7449 = FACE_BOUND('',#7450,.T.); -#7450 = EDGE_LOOP('',(#7451,#7452,#7453,#7454)); -#7451 = ORIENTED_EDGE('',*,*,#7275,.T.); -#7452 = ORIENTED_EDGE('',*,*,#7351,.T.); -#7453 = ORIENTED_EDGE('',*,*,#7400,.T.); -#7454 = ORIENTED_EDGE('',*,*,#7427,.T.); -#7455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7459)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#7456,#7457,#7458)) REPRESENTATION_CONTEXT +#9812 = ORIENTED_EDGE('',*,*,#9720,.T.); +#9813 = ADVANCED_FACE('',(#9814),#9593,.T.); +#9814 = FACE_BOUND('',#9815,.T.); +#9815 = EDGE_LOOP('',(#9816,#9817,#9818,#9839)); +#9816 = ORIENTED_EDGE('',*,*,#9579,.T.); +#9817 = ORIENTED_EDGE('',*,*,#9695,.F.); +#9818 = ORIENTED_EDGE('',*,*,#9819,.F.); +#9819 = EDGE_CURVE('',#9770,#9668,#9820,.T.); +#9820 = SURFACE_CURVE('',#9821,(#9825,#9832),.PCURVE_S1.); +#9821 = LINE('',#9822,#9823); +#9822 = CARTESIAN_POINT('',(-0.3,-0.233452994616,0.3)); +#9823 = VECTOR('',#9824,1.); +#9824 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9825 = PCURVE('',#9593,#9826); +#9826 = DEFINITIONAL_REPRESENTATION('',(#9827),#9831); +#9827 = LINE('',#9828,#9829); +#9828 = CARTESIAN_POINT('',(-2.309401076759E-002,0.E+000)); +#9829 = VECTOR('',#9830,1.); +#9830 = DIRECTION('',(0.E+000,1.)); +#9831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9832 = PCURVE('',#9683,#9833); +#9833 = DEFINITIONAL_REPRESENTATION('',(#9834),#9838); +#9834 = LINE('',#9835,#9836); +#9835 = CARTESIAN_POINT('',(-0.6,1.154700538379E-002)); +#9836 = VECTOR('',#9837,1.); +#9837 = DIRECTION('',(1.,0.E+000)); +#9838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9839 = ORIENTED_EDGE('',*,*,#9769,.T.); +#9840 = ADVANCED_FACE('',(#9841),#9683,.T.); +#9841 = FACE_BOUND('',#9842,.T.); +#9842 = EDGE_LOOP('',(#9843,#9844,#9845,#9846)); +#9843 = ORIENTED_EDGE('',*,*,#9667,.T.); +#9844 = ORIENTED_EDGE('',*,*,#9743,.T.); +#9845 = ORIENTED_EDGE('',*,*,#9792,.T.); +#9846 = ORIENTED_EDGE('',*,*,#9819,.T.); +#9847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#9851)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#9848,#9849,#9850)) REPRESENTATION_CONTEXT ('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#7456 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#7457 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#7458 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#7459 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7456, +#9848 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#9849 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#9850 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#9851 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#9848, 'distance_accuracy_value','confusion accuracy'); -#7460 = SHAPE_DEFINITION_REPRESENTATION(#7461,#5072); -#7461 = PRODUCT_DEFINITION_SHAPE('','',#7462); -#7462 = PRODUCT_DEFINITION('design','',#7463,#7466); -#7463 = PRODUCT_DEFINITION_FORMATION('','',#7464); -#7464 = PRODUCT('res0402','res0402','',(#7465)); -#7465 = PRODUCT_CONTEXT('',#2,'mechanical'); -#7466 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#7467 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7468,#7470); -#7468 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#5062) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7469) +#9852 = SHAPE_DEFINITION_REPRESENTATION(#9853,#7464); +#9853 = PRODUCT_DEFINITION_SHAPE('','',#9854); +#9854 = PRODUCT_DEFINITION('design','',#9855,#9858); +#9855 = PRODUCT_DEFINITION_FORMATION('','',#9856); +#9856 = PRODUCT('res0402','res0402','',(#9857)); +#9857 = PRODUCT_CONTEXT('',#2,'mechanical'); +#9858 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#9859 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#9860,#9862); +#9860 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#7454) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#9861) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#7469 = ITEM_DEFINED_TRANSFORMATION('','',#11,#5063); -#7470 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #7471); -#7471 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('137','=>[0:1:1:7]','',#5057, - #7462,$); -#7472 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7464)); -#7473 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7474,#7476); -#7474 = ( REPRESENTATION_RELATIONSHIP('','',#5062,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7475) +#9861 = ITEM_DEFINED_TRANSFORMATION('','',#11,#7455); +#9862 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #9863); +#9863 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('238','=>[0:1:1:7]','',#7449, + #9854,$); +#9864 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#9856)); +#9865 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#9866,#9868); +#9866 = ( REPRESENTATION_RELATIONSHIP('','',#7454,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#9867) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#7475 = ITEM_DEFINED_TRANSFORMATION('','',#11,#23); -#7476 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #7477); -#7477 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('138','=>[0:1:1:6]','',#5,#5057,$ - ); -#7478 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#5059)); -#7479 = SHAPE_DEFINITION_REPRESENTATION(#7480,#7486); -#7480 = PRODUCT_DEFINITION_SHAPE('','',#7481); -#7481 = PRODUCT_DEFINITION('design','',#7482,#7485); -#7482 = PRODUCT_DEFINITION_FORMATION('','',#7483); -#7483 = PRODUCT('R3','R3','',(#7484)); -#7484 = PRODUCT_CONTEXT('',#2,'mechanical'); -#7485 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#7486 = SHAPE_REPRESENTATION('',(#11,#7487),#7491); -#7487 = AXIS2_PLACEMENT_3D('',#7488,#7489,#7490); -#7488 = CARTESIAN_POINT('',(21.0860005,6.096,-1.27E-002)); -#7489 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7490 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#7491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7495)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#7492,#7493,#7494)) REPRESENTATION_CONTEXT +#9867 = ITEM_DEFINED_TRANSFORMATION('','',#11,#23); +#9868 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #9869); +#9869 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('239','=>[0:1:1:6]','',#5,#7449,$ + ); +#9870 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7451)); +#9871 = SHAPE_DEFINITION_REPRESENTATION(#9872,#9878); +#9872 = PRODUCT_DEFINITION_SHAPE('','',#9873); +#9873 = PRODUCT_DEFINITION('design','',#9874,#9877); +#9874 = PRODUCT_DEFINITION_FORMATION('','',#9875); +#9875 = PRODUCT('R3','R3','',(#9876)); +#9876 = PRODUCT_CONTEXT('',#2,'mechanical'); +#9877 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#9878 = SHAPE_REPRESENTATION('',(#11,#9879),#9883); +#9879 = AXIS2_PLACEMENT_3D('',#9880,#9881,#9882); +#9880 = CARTESIAN_POINT('',(21.0860005,6.096,-1.27E-002)); +#9881 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9882 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#9883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#9887)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#9884,#9885,#9886)) REPRESENTATION_CONTEXT ('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#7492 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#7493 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#7494 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#7495 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7492, +#9884 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#9885 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#9886 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#9887 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#9884, 'distance_accuracy_value','confusion accuracy'); -#7496 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7497,#7499); -#7497 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#7486) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7498) +#9888 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#9889,#9891); +#9889 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#9878) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#9890) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#7498 = ITEM_DEFINED_TRANSFORMATION('','',#11,#7487); -#7499 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #7500); -#7500 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('139','=>[0:1:1:7]','',#7481, - #7462,$); -#7501 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#7502,#7504); -#7502 = ( REPRESENTATION_RELATIONSHIP('','',#7486,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#7503) +#9890 = ITEM_DEFINED_TRANSFORMATION('','',#11,#9879); +#9891 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #9892); +#9892 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('240','=>[0:1:1:7]','',#9873, + #9854,$); +#9893 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#9894,#9896); +#9894 = ( REPRESENTATION_RELATIONSHIP('','',#9878,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#9895) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#7503 = ITEM_DEFINED_TRANSFORMATION('','',#11,#27); -#7504 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #7505); -#7505 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('140','=>[0:1:1:8]','',#5,#7481,$ - ); -#7506 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7483)); -#7507 = SHAPE_DEFINITION_REPRESENTATION(#7508,#7514); -#7508 = PRODUCT_DEFINITION_SHAPE('','',#7509); -#7509 = PRODUCT_DEFINITION('design','',#7510,#7513); -#7510 = PRODUCT_DEFINITION_FORMATION('','',#7511); -#7511 = PRODUCT('D4','D4','',(#7512)); -#7512 = PRODUCT_CONTEXT('',#2,'mechanical'); -#7513 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#7514 = SHAPE_REPRESENTATION('',(#11,#7515),#7519); -#7515 = AXIS2_PLACEMENT_3D('',#7516,#7517,#7518); -#7516 = CARTESIAN_POINT('',(14.4648428,4.04644098,1.27E-002)); -#7517 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7518 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#7519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#7523)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#7520,#7521,#7522)) REPRESENTATION_CONTEXT +#9895 = ITEM_DEFINED_TRANSFORMATION('','',#11,#27); +#9896 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #9897); +#9897 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('241','=>[0:1:1:8]','',#5,#9873,$ + ); +#9898 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#9875)); +#9899 = SHAPE_DEFINITION_REPRESENTATION(#9900,#9906); +#9900 = PRODUCT_DEFINITION_SHAPE('','',#9901); +#9901 = PRODUCT_DEFINITION('design','',#9902,#9905); +#9902 = PRODUCT_DEFINITION_FORMATION('','',#9903); +#9903 = PRODUCT('D4','D4','',(#9904)); +#9904 = PRODUCT_CONTEXT('',#2,'mechanical'); +#9905 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#9906 = SHAPE_REPRESENTATION('',(#11,#9907),#9911); +#9907 = AXIS2_PLACEMENT_3D('',#9908,#9909,#9910); +#9908 = CARTESIAN_POINT('',(14.4648428,4.04644098,1.27E-002)); +#9909 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9910 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#9911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#9915)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#9912,#9913,#9914)) REPRESENTATION_CONTEXT ('Context #1','3D Context with UNIT and UNCERTAINTY') ); -#7520 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#7521 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#7522 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#7523 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#7520, +#9912 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#9913 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#9914 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#9915 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#9912, 'distance_accuracy_value','confusion accuracy'); -#7524 = SHAPE_REPRESENTATION('',(#11,#7525,#8171,#8501,#8831,#9912), - #11016); -#7525 = MANIFOLD_SOLID_BREP('',#7526); -#7526 = CLOSED_SHELL('',(#7527,#7759,#7837,#7886,#7935,#7983,#8035,#8084 - ,#8133,#8160)); -#7527 = ADVANCED_FACE('',(#7528),#7543,.F.); -#7528 = FACE_BOUND('',#7529,.T.); -#7529 = EDGE_LOOP('',(#7530,#7565,#7593,#7621,#7649,#7677,#7705,#7733)); -#7530 = ORIENTED_EDGE('',*,*,#7531,.T.); -#7531 = EDGE_CURVE('',#7532,#7534,#7536,.T.); -#7532 = VERTEX_POINT('',#7533); -#7533 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, +#9916 = SHAPE_REPRESENTATION('',(#11,#9917,#10563,#10893,#11223,#12304), + #13408); +#9917 = MANIFOLD_SOLID_BREP('',#9918); +#9918 = CLOSED_SHELL('',(#9919,#10151,#10229,#10278,#10327,#10375,#10427 + ,#10476,#10525,#10552)); +#9919 = ADVANCED_FACE('',(#9920),#9935,.F.); +#9920 = FACE_BOUND('',#9921,.T.); +#9921 = EDGE_LOOP('',(#9922,#9957,#9985,#10013,#10041,#10069,#10097, + #10125)); +#9922 = ORIENTED_EDGE('',*,*,#9923,.T.); +#9923 = EDGE_CURVE('',#9924,#9926,#9928,.T.); +#9924 = VERTEX_POINT('',#9925); +#9925 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 2.976642100057E-002)); -#7534 = VERTEX_POINT('',#7535); -#7535 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, +#9926 = VERTEX_POINT('',#9927); +#9927 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, 2.976642100057E-002)); -#7536 = SURFACE_CURVE('',#7537,(#7542,#7554),.PCURVE_S1.); -#7537 = CIRCLE('',#7538,0.15); -#7538 = AXIS2_PLACEMENT_3D('',#7539,#7540,#7541); -#7539 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, +#9928 = SURFACE_CURVE('',#9929,(#9934,#9946),.PCURVE_S1.); +#9929 = CIRCLE('',#9930,0.15); +#9930 = AXIS2_PLACEMENT_3D('',#9931,#9932,#9933); +#9931 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, 2.976642100057E-002)); -#7540 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7541 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7542 = PCURVE('',#7543,#7548); -#7543 = PLANE('',#7544); -#7544 = AXIS2_PLACEMENT_3D('',#7545,#7546,#7547); -#7545 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, +#9932 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9933 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9934 = PCURVE('',#9935,#9940); +#9935 = PLANE('',#9936); +#9936 = AXIS2_PLACEMENT_3D('',#9937,#9938,#9939); +#9937 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, 2.976642100057E-002)); -#7546 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7547 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7548 = DEFINITIONAL_REPRESENTATION('',(#7549),#7553); -#7549 = CIRCLE('',#7550,0.15); -#7550 = AXIS2_PLACEMENT_2D('',#7551,#7552); -#7551 = CARTESIAN_POINT('',(-8.348356728138E-014,0.825)); -#7552 = DIRECTION('',(-1.,0.E+000)); -#7553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7554 = PCURVE('',#7555,#7560); -#7555 = CYLINDRICAL_SURFACE('',#7556,0.15); -#7556 = AXIS2_PLACEMENT_3D('',#7557,#7558,#7559); -#7557 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, +#9938 = DIRECTION('',(0.E+000,0.E+000,1.)); +#9939 = DIRECTION('',(1.,0.E+000,0.E+000)); +#9940 = DEFINITIONAL_REPRESENTATION('',(#9941),#9945); +#9941 = CIRCLE('',#9942,0.15); +#9942 = AXIS2_PLACEMENT_2D('',#9943,#9944); +#9943 = CARTESIAN_POINT('',(-8.348356728138E-014,0.825)); +#9944 = DIRECTION('',(-1.,0.E+000)); +#9945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9946 = PCURVE('',#9947,#9952); +#9947 = CYLINDRICAL_SURFACE('',#9948,0.15); +#9948 = AXIS2_PLACEMENT_3D('',#9949,#9950,#9951); +#9949 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, -0.221407354483)); -#7558 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7559 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7560 = DEFINITIONAL_REPRESENTATION('',(#7561),#7564); -#7561 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7562,#7563),.UNSPECIFIED.,.F., +#9950 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#9951 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#9952 = DEFINITIONAL_REPRESENTATION('',(#9953),#9956); +#9953 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#9954,#9955),.UNSPECIFIED.,.F., .F.,(2,2),(0.16744807922,2.97414457437),.PIECEWISE_BEZIER_KNOTS.); -#7562 = CARTESIAN_POINT('',(6.11573722796,-0.251173775483)); -#7563 = CARTESIAN_POINT('',(3.309040732809,-0.251173775483)); -#7564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#9954 = CARTESIAN_POINT('',(6.11573722796,-0.251173775483)); +#9955 = CARTESIAN_POINT('',(3.309040732809,-0.251173775483)); +#9956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#7565 = ORIENTED_EDGE('',*,*,#7566,.F.); -#7566 = EDGE_CURVE('',#7567,#7534,#7569,.T.); -#7567 = VERTEX_POINT('',#7568); -#7568 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#9957 = ORIENTED_EDGE('',*,*,#9958,.F.); +#9958 = EDGE_CURVE('',#9959,#9926,#9961,.T.); +#9959 = VERTEX_POINT('',#9960); +#9960 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, 2.976642100057E-002)); -#7569 = SURFACE_CURVE('',#7570,(#7574,#7581),.PCURVE_S1.); -#7570 = LINE('',#7571,#7572); -#7571 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#9961 = SURFACE_CURVE('',#9962,(#9966,#9973),.PCURVE_S1.); +#9962 = LINE('',#9963,#9964); +#9963 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, 2.976642100057E-002)); -#7572 = VECTOR('',#7573,1.); -#7573 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#7574 = PCURVE('',#7543,#7575); -#7575 = DEFINITIONAL_REPRESENTATION('',(#7576),#7580); -#7576 = LINE('',#7577,#7578); -#7577 = CARTESIAN_POINT('',(0.3625,0.8)); -#7578 = VECTOR('',#7579,1.); -#7579 = DIRECTION('',(-1.,-1.011968286946E-013)); -#7580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7581 = PCURVE('',#7582,#7587); -#7582 = PLANE('',#7583); -#7583 = AXIS2_PLACEMENT_3D('',#7584,#7585,#7586); -#7584 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#9964 = VECTOR('',#9965,1.); +#9965 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#9966 = PCURVE('',#9935,#9967); +#9967 = DEFINITIONAL_REPRESENTATION('',(#9968),#9972); +#9968 = LINE('',#9969,#9970); +#9969 = CARTESIAN_POINT('',(0.3625,0.8)); +#9970 = VECTOR('',#9971,1.); +#9971 = DIRECTION('',(-1.,-1.011968286946E-013)); +#9972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9973 = PCURVE('',#9974,#9979); +#9974 = PLANE('',#9975); +#9975 = AXIS2_PLACEMENT_3D('',#9976,#9977,#9978); +#9976 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, 2.976642100057E-002)); -#7585 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#7586 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#7587 = DEFINITIONAL_REPRESENTATION('',(#7588),#7592); -#7588 = LINE('',#7589,#7590); -#7589 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); -#7590 = VECTOR('',#7591,1.); -#7591 = DIRECTION('',(1.,0.E+000)); -#7592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7593 = ORIENTED_EDGE('',*,*,#7594,.F.); -#7594 = EDGE_CURVE('',#7595,#7567,#7597,.T.); -#7595 = VERTEX_POINT('',#7596); -#7596 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#9977 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#9978 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#9979 = DEFINITIONAL_REPRESENTATION('',(#9980),#9984); +#9980 = LINE('',#9981,#9982); +#9981 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); +#9982 = VECTOR('',#9983,1.); +#9983 = DIRECTION('',(1.,0.E+000)); +#9984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#9985 = ORIENTED_EDGE('',*,*,#9986,.F.); +#9986 = EDGE_CURVE('',#9987,#9959,#9989,.T.); +#9987 = VERTEX_POINT('',#9988); +#9988 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7597 = SURFACE_CURVE('',#7598,(#7602,#7609),.PCURVE_S1.); -#7598 = LINE('',#7599,#7600); -#7599 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#9989 = SURFACE_CURVE('',#9990,(#9994,#10001),.PCURVE_S1.); +#9990 = LINE('',#9991,#9992); +#9991 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7600 = VECTOR('',#7601,1.); -#7601 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#7602 = PCURVE('',#7543,#7603); -#7603 = DEFINITIONAL_REPRESENTATION('',(#7604),#7608); -#7604 = LINE('',#7605,#7606); -#7605 = CARTESIAN_POINT('',(0.3625,-0.8)); -#7606 = VECTOR('',#7607,1.); -#7607 = DIRECTION('',(-1.011968286946E-013,1.)); -#7608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7609 = PCURVE('',#7610,#7615); -#7610 = PLANE('',#7611); -#7611 = AXIS2_PLACEMENT_3D('',#7612,#7613,#7614); -#7612 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#9992 = VECTOR('',#9993,1.); +#9993 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#9994 = PCURVE('',#9935,#9995); +#9995 = DEFINITIONAL_REPRESENTATION('',(#9996),#10000); +#9996 = LINE('',#9997,#9998); +#9997 = CARTESIAN_POINT('',(0.3625,-0.8)); +#9998 = VECTOR('',#9999,1.); +#9999 = DIRECTION('',(-1.011968286946E-013,1.)); +#10000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10001 = PCURVE('',#10002,#10007); +#10002 = PLANE('',#10003); +#10003 = AXIS2_PLACEMENT_3D('',#10004,#10005,#10006); +#10004 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7613 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#7614 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#7615 = DEFINITIONAL_REPRESENTATION('',(#7616),#7620); -#7616 = LINE('',#7617,#7618); -#7617 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); -#7618 = VECTOR('',#7619,1.); -#7619 = DIRECTION('',(1.,0.E+000)); -#7620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7621 = ORIENTED_EDGE('',*,*,#7622,.F.); -#7622 = EDGE_CURVE('',#7623,#7595,#7625,.T.); -#7623 = VERTEX_POINT('',#7624); -#7624 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, +#10005 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10006 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10007 = DEFINITIONAL_REPRESENTATION('',(#10008),#10012); +#10008 = LINE('',#10009,#10010); +#10009 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); +#10010 = VECTOR('',#10011,1.); +#10011 = DIRECTION('',(1.,0.E+000)); +#10012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10013 = ORIENTED_EDGE('',*,*,#10014,.F.); +#10014 = EDGE_CURVE('',#10015,#9987,#10017,.T.); +#10015 = VERTEX_POINT('',#10016); +#10016 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 2.976642100057E-002)); -#7625 = SURFACE_CURVE('',#7626,(#7630,#7637),.PCURVE_S1.); -#7626 = LINE('',#7627,#7628); -#7627 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#10017 = SURFACE_CURVE('',#10018,(#10022,#10029),.PCURVE_S1.); +#10018 = LINE('',#10019,#10020); +#10019 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7628 = VECTOR('',#7629,1.); -#7629 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#7630 = PCURVE('',#7543,#7631); -#7631 = DEFINITIONAL_REPRESENTATION('',(#7632),#7636); -#7632 = LINE('',#7633,#7634); -#7633 = CARTESIAN_POINT('',(0.3625,-0.8)); -#7634 = VECTOR('',#7635,1.); -#7635 = DIRECTION('',(1.,1.011968286946E-013)); -#7636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7637 = PCURVE('',#7638,#7643); -#7638 = PLANE('',#7639); -#7639 = AXIS2_PLACEMENT_3D('',#7640,#7641,#7642); -#7640 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#10020 = VECTOR('',#10021,1.); +#10021 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10022 = PCURVE('',#9935,#10023); +#10023 = DEFINITIONAL_REPRESENTATION('',(#10024),#10028); +#10024 = LINE('',#10025,#10026); +#10025 = CARTESIAN_POINT('',(0.3625,-0.8)); +#10026 = VECTOR('',#10027,1.); +#10027 = DIRECTION('',(1.,1.011968286946E-013)); +#10028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10029 = PCURVE('',#10030,#10035); +#10030 = PLANE('',#10031); +#10031 = AXIS2_PLACEMENT_3D('',#10032,#10033,#10034); +#10032 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7641 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#7642 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#7643 = DEFINITIONAL_REPRESENTATION('',(#7644),#7648); -#7644 = LINE('',#7645,#7646); -#7645 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7646 = VECTOR('',#7647,1.); -#7647 = DIRECTION('',(1.,0.E+000)); -#7648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7649 = ORIENTED_EDGE('',*,*,#7650,.T.); -#7650 = EDGE_CURVE('',#7623,#7651,#7653,.T.); -#7651 = VERTEX_POINT('',#7652); -#7652 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, +#10033 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10034 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10035 = DEFINITIONAL_REPRESENTATION('',(#10036),#10040); +#10036 = LINE('',#10037,#10038); +#10037 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#10038 = VECTOR('',#10039,1.); +#10039 = DIRECTION('',(1.,0.E+000)); +#10040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10041 = ORIENTED_EDGE('',*,*,#10042,.T.); +#10042 = EDGE_CURVE('',#10015,#10043,#10045,.T.); +#10043 = VERTEX_POINT('',#10044); +#10044 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, 2.976642100057E-002)); -#7653 = SURFACE_CURVE('',#7654,(#7659,#7666),.PCURVE_S1.); -#7654 = CIRCLE('',#7655,0.15); -#7655 = AXIS2_PLACEMENT_3D('',#7656,#7657,#7658); -#7656 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, +#10045 = SURFACE_CURVE('',#10046,(#10051,#10058),.PCURVE_S1.); +#10046 = CIRCLE('',#10047,0.15); +#10047 = AXIS2_PLACEMENT_3D('',#10048,#10049,#10050); +#10048 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, 2.976642100057E-002)); -#7657 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7658 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7659 = PCURVE('',#7543,#7660); -#7660 = DEFINITIONAL_REPRESENTATION('',(#7661),#7665); -#7661 = CIRCLE('',#7662,0.15); -#7662 = AXIS2_PLACEMENT_2D('',#7663,#7664); -#7663 = CARTESIAN_POINT('',(8.348356728138E-014,-0.825)); -#7664 = DIRECTION('',(1.,0.E+000)); -#7665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7666 = PCURVE('',#7667,#7672); -#7667 = CYLINDRICAL_SURFACE('',#7668,0.15); -#7668 = AXIS2_PLACEMENT_3D('',#7669,#7670,#7671); -#7669 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, +#10049 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10050 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10051 = PCURVE('',#9935,#10052); +#10052 = DEFINITIONAL_REPRESENTATION('',(#10053),#10057); +#10053 = CIRCLE('',#10054,0.15); +#10054 = AXIS2_PLACEMENT_2D('',#10055,#10056); +#10055 = CARTESIAN_POINT('',(8.348356728138E-014,-0.825)); +#10056 = DIRECTION('',(1.,0.E+000)); +#10057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10058 = PCURVE('',#10059,#10064); +#10059 = CYLINDRICAL_SURFACE('',#10060,0.15); +#10060 = AXIS2_PLACEMENT_3D('',#10061,#10062,#10063); +#10061 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, -0.221407354483)); -#7670 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7671 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7672 = DEFINITIONAL_REPRESENTATION('',(#7673),#7676); -#7673 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7674,#7675),.UNSPECIFIED.,.F., - .F.,(2,2),(0.16744807922,2.97414457437),.PIECEWISE_BEZIER_KNOTS.); -#7674 = CARTESIAN_POINT('',(0.16744807922,0.251173775483)); -#7675 = CARTESIAN_POINT('',(2.97414457437,0.251173775483)); -#7676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7677 = ORIENTED_EDGE('',*,*,#7678,.F.); -#7678 = EDGE_CURVE('',#7679,#7651,#7681,.T.); -#7679 = VERTEX_POINT('',#7680); -#7680 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056, +#10062 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10063 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10064 = DEFINITIONAL_REPRESENTATION('',(#10065),#10068); +#10065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10066,#10067),.UNSPECIFIED., + .F.,.F.,(2,2),(0.16744807922,2.97414457437),.PIECEWISE_BEZIER_KNOTS.); +#10066 = CARTESIAN_POINT('',(0.16744807922,0.251173775483)); +#10067 = CARTESIAN_POINT('',(2.97414457437,0.251173775483)); +#10068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10069 = ORIENTED_EDGE('',*,*,#10070,.F.); +#10070 = EDGE_CURVE('',#10071,#10043,#10073,.T.); +#10071 = VERTEX_POINT('',#10072); +#10072 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056, 2.976642100057E-002)); -#7681 = SURFACE_CURVE('',#7682,(#7686,#7693),.PCURVE_S1.); -#7682 = LINE('',#7683,#7684); -#7683 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, +#10073 = SURFACE_CURVE('',#10074,(#10078,#10085),.PCURVE_S1.); +#10074 = LINE('',#10075,#10076); +#10075 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, 2.976642100057E-002)); -#7684 = VECTOR('',#7685,1.); -#7685 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7686 = PCURVE('',#7543,#7687); -#7687 = DEFINITIONAL_REPRESENTATION('',(#7688),#7692); -#7688 = LINE('',#7689,#7690); -#7689 = CARTESIAN_POINT('',(0.E+000,-0.8)); -#7690 = VECTOR('',#7691,1.); -#7691 = DIRECTION('',(1.,0.E+000)); -#7692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7693 = PCURVE('',#7694,#7699); -#7694 = PLANE('',#7695); -#7695 = AXIS2_PLACEMENT_3D('',#7696,#7697,#7698); -#7696 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#10076 = VECTOR('',#10077,1.); +#10077 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10078 = PCURVE('',#9935,#10079); +#10079 = DEFINITIONAL_REPRESENTATION('',(#10080),#10084); +#10080 = LINE('',#10081,#10082); +#10081 = CARTESIAN_POINT('',(0.E+000,-0.8)); +#10082 = VECTOR('',#10083,1.); +#10083 = DIRECTION('',(1.,0.E+000)); +#10084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10085 = PCURVE('',#10086,#10091); +#10086 = PLANE('',#10087); +#10087 = AXIS2_PLACEMENT_3D('',#10088,#10089,#10090); +#10088 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7697 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#7698 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#7699 = DEFINITIONAL_REPRESENTATION('',(#7700),#7704); -#7700 = LINE('',#7701,#7702); -#7701 = CARTESIAN_POINT('',(-0.3625,0.E+000)); -#7702 = VECTOR('',#7703,1.); -#7703 = DIRECTION('',(1.,0.E+000)); -#7704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7705 = ORIENTED_EDGE('',*,*,#7706,.F.); -#7706 = EDGE_CURVE('',#7707,#7679,#7709,.T.); -#7707 = VERTEX_POINT('',#7708); -#7708 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, +#10089 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10090 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10091 = DEFINITIONAL_REPRESENTATION('',(#10092),#10096); +#10092 = LINE('',#10093,#10094); +#10093 = CARTESIAN_POINT('',(-0.3625,0.E+000)); +#10094 = VECTOR('',#10095,1.); +#10095 = DIRECTION('',(1.,0.E+000)); +#10096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10097 = ORIENTED_EDGE('',*,*,#10098,.F.); +#10098 = EDGE_CURVE('',#10099,#10071,#10101,.T.); +#10099 = VERTEX_POINT('',#10100); +#10100 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, 2.976642100057E-002)); -#7709 = SURFACE_CURVE('',#7710,(#7714,#7721),.PCURVE_S1.); -#7710 = LINE('',#7711,#7712); -#7711 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, +#10101 = SURFACE_CURVE('',#10102,(#10106,#10113),.PCURVE_S1.); +#10102 = LINE('',#10103,#10104); +#10103 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, 2.976642100057E-002)); -#7712 = VECTOR('',#7713,1.); -#7713 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#7714 = PCURVE('',#7543,#7715); -#7715 = DEFINITIONAL_REPRESENTATION('',(#7716),#7720); -#7716 = LINE('',#7717,#7718); -#7717 = CARTESIAN_POINT('',(-0.3625,0.8)); -#7718 = VECTOR('',#7719,1.); -#7719 = DIRECTION('',(1.011968286946E-013,-1.)); -#7720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7721 = PCURVE('',#7722,#7727); -#7722 = PLANE('',#7723); -#7723 = AXIS2_PLACEMENT_3D('',#7724,#7725,#7726); -#7724 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, +#10104 = VECTOR('',#10105,1.); +#10105 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10106 = PCURVE('',#9935,#10107); +#10107 = DEFINITIONAL_REPRESENTATION('',(#10108),#10112); +#10108 = LINE('',#10109,#10110); +#10109 = CARTESIAN_POINT('',(-0.3625,0.8)); +#10110 = VECTOR('',#10111,1.); +#10111 = DIRECTION('',(1.011968286946E-013,-1.)); +#10112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10113 = PCURVE('',#10114,#10119); +#10114 = PLANE('',#10115); +#10115 = AXIS2_PLACEMENT_3D('',#10116,#10117,#10118); +#10116 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, 2.976642100057E-002)); -#7725 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#7726 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#7727 = DEFINITIONAL_REPRESENTATION('',(#7728),#7732); -#7728 = LINE('',#7729,#7730); -#7729 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); -#7730 = VECTOR('',#7731,1.); -#7731 = DIRECTION('',(1.,0.E+000)); -#7732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7733 = ORIENTED_EDGE('',*,*,#7734,.F.); -#7734 = EDGE_CURVE('',#7532,#7707,#7735,.T.); -#7735 = SURFACE_CURVE('',#7736,(#7740,#7747),.PCURVE_S1.); -#7736 = LINE('',#7737,#7738); -#7737 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#10117 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10118 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10119 = DEFINITIONAL_REPRESENTATION('',(#10120),#10124); +#10120 = LINE('',#10121,#10122); +#10121 = CARTESIAN_POINT('',(0.E+000,5.20417042793E-017)); +#10122 = VECTOR('',#10123,1.); +#10123 = DIRECTION('',(1.,0.E+000)); +#10124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10125 = ORIENTED_EDGE('',*,*,#10126,.F.); +#10126 = EDGE_CURVE('',#9924,#10099,#10127,.T.); +#10127 = SURFACE_CURVE('',#10128,(#10132,#10139),.PCURVE_S1.); +#10128 = LINE('',#10129,#10130); +#10129 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, 2.976642100057E-002)); -#7738 = VECTOR('',#7739,1.); -#7739 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#7740 = PCURVE('',#7543,#7741); -#7741 = DEFINITIONAL_REPRESENTATION('',(#7742),#7746); -#7742 = LINE('',#7743,#7744); -#7743 = CARTESIAN_POINT('',(0.3625,0.8)); -#7744 = VECTOR('',#7745,1.); -#7745 = DIRECTION('',(-1.,-1.011968286946E-013)); -#7746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7747 = PCURVE('',#7748,#7753); -#7748 = PLANE('',#7749); -#7749 = AXIS2_PLACEMENT_3D('',#7750,#7751,#7752); -#7750 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#10130 = VECTOR('',#10131,1.); +#10131 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10132 = PCURVE('',#9935,#10133); +#10133 = DEFINITIONAL_REPRESENTATION('',(#10134),#10138); +#10134 = LINE('',#10135,#10136); +#10135 = CARTESIAN_POINT('',(0.3625,0.8)); +#10136 = VECTOR('',#10137,1.); +#10137 = DIRECTION('',(-1.,-1.011968286946E-013)); +#10138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10139 = PCURVE('',#10140,#10145); +#10140 = PLANE('',#10141); +#10141 = AXIS2_PLACEMENT_3D('',#10142,#10143,#10144); +#10142 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, 2.976642100057E-002)); -#7751 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#7752 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#7753 = DEFINITIONAL_REPRESENTATION('',(#7754),#7758); -#7754 = LINE('',#7755,#7756); -#7755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7756 = VECTOR('',#7757,1.); -#7757 = DIRECTION('',(1.,0.E+000)); -#7758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7759 = ADVANCED_FACE('',(#7760),#7667,.F.); -#7760 = FACE_BOUND('',#7761,.F.); -#7761 = EDGE_LOOP('',(#7762,#7763,#7785,#7817)); -#7762 = ORIENTED_EDGE('',*,*,#7650,.T.); -#7763 = ORIENTED_EDGE('',*,*,#7764,.T.); -#7764 = EDGE_CURVE('',#7651,#7765,#7767,.T.); -#7765 = VERTEX_POINT('',#7766); -#7766 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, +#10143 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10144 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10145 = DEFINITIONAL_REPRESENTATION('',(#10146),#10150); +#10146 = LINE('',#10147,#10148); +#10147 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#10148 = VECTOR('',#10149,1.); +#10149 = DIRECTION('',(1.,0.E+000)); +#10150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10151 = ADVANCED_FACE('',(#10152),#10059,.F.); +#10152 = FACE_BOUND('',#10153,.F.); +#10153 = EDGE_LOOP('',(#10154,#10155,#10177,#10209)); +#10154 = ORIENTED_EDGE('',*,*,#10042,.T.); +#10155 = ORIENTED_EDGE('',*,*,#10156,.T.); +#10156 = EDGE_CURVE('',#10043,#10157,#10159,.T.); +#10157 = VERTEX_POINT('',#10158); +#10158 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, 0.329766421001)); -#7767 = SURFACE_CURVE('',#7768,(#7772,#7778),.PCURVE_S1.); -#7768 = LINE('',#7769,#7770); -#7769 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, +#10159 = SURFACE_CURVE('',#10160,(#10164,#10170),.PCURVE_S1.); +#10160 = LINE('',#10161,#10162); +#10161 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, 2.976642100057E-002)); -#7770 = VECTOR('',#7771,1.); -#7771 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7772 = PCURVE('',#7667,#7773); -#7773 = DEFINITIONAL_REPRESENTATION('',(#7774),#7777); -#7774 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7775,#7776),.UNSPECIFIED.,.F., - .F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#7775 = CARTESIAN_POINT('',(2.97414457437,0.251173775483)); -#7776 = CARTESIAN_POINT('',(2.97414457437,0.551173775483)); -#7777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7778 = PCURVE('',#7694,#7779); -#7779 = DEFINITIONAL_REPRESENTATION('',(#7780),#7784); -#7780 = LINE('',#7781,#7782); -#7781 = CARTESIAN_POINT('',(-0.510401994578,0.E+000)); -#7782 = VECTOR('',#7783,1.); -#7783 = DIRECTION('',(0.E+000,1.)); -#7784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7785 = ORIENTED_EDGE('',*,*,#7786,.T.); -#7786 = EDGE_CURVE('',#7765,#7787,#7789,.T.); -#7787 = VERTEX_POINT('',#7788); -#7788 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, +#10162 = VECTOR('',#10163,1.); +#10163 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10164 = PCURVE('',#10059,#10165); +#10165 = DEFINITIONAL_REPRESENTATION('',(#10166),#10169); +#10166 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10167,#10168),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#10167 = CARTESIAN_POINT('',(2.97414457437,0.251173775483)); +#10168 = CARTESIAN_POINT('',(2.97414457437,0.551173775483)); +#10169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10170 = PCURVE('',#10086,#10171); +#10171 = DEFINITIONAL_REPRESENTATION('',(#10172),#10176); +#10172 = LINE('',#10173,#10174); +#10173 = CARTESIAN_POINT('',(-0.510401994578,0.E+000)); +#10174 = VECTOR('',#10175,1.); +#10175 = DIRECTION('',(0.E+000,1.)); +#10176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10177 = ORIENTED_EDGE('',*,*,#10178,.T.); +#10178 = EDGE_CURVE('',#10157,#10179,#10181,.T.); +#10179 = VERTEX_POINT('',#10180); +#10180 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 0.329766421001)); -#7789 = SURFACE_CURVE('',#7790,(#7795,#7801),.PCURVE_S1.); -#7790 = CIRCLE('',#7791,0.15); -#7791 = AXIS2_PLACEMENT_3D('',#7792,#7793,#7794); -#7792 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, +#10181 = SURFACE_CURVE('',#10182,(#10187,#10193),.PCURVE_S1.); +#10182 = CIRCLE('',#10183,0.15); +#10183 = AXIS2_PLACEMENT_3D('',#10184,#10185,#10186); +#10184 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, 0.329766421001)); -#7793 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7794 = DIRECTION('',(1.,1.445602896647E-015,0.E+000)); -#7795 = PCURVE('',#7667,#7796); -#7796 = DEFINITIONAL_REPRESENTATION('',(#7797),#7800); -#7797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7798,#7799),.UNSPECIFIED.,.F., - .F.,(2,2),(3.309040732809,6.11573722796),.PIECEWISE_BEZIER_KNOTS.); -#7798 = CARTESIAN_POINT('',(2.97414457437,0.551173775483)); -#7799 = CARTESIAN_POINT('',(0.16744807922,0.551173775483)); -#7800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7801 = PCURVE('',#7802,#7807); -#7802 = PLANE('',#7803); -#7803 = AXIS2_PLACEMENT_3D('',#7804,#7805,#7806); -#7804 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, +#10185 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10186 = DIRECTION('',(1.,1.445602896647E-015,0.E+000)); +#10187 = PCURVE('',#10059,#10188); +#10188 = DEFINITIONAL_REPRESENTATION('',(#10189),#10192); +#10189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10190,#10191),.UNSPECIFIED., + .F.,.F.,(2,2),(3.309040732809,6.11573722796), + .PIECEWISE_BEZIER_KNOTS.); +#10190 = CARTESIAN_POINT('',(2.97414457437,0.551173775483)); +#10191 = CARTESIAN_POINT('',(0.16744807922,0.551173775483)); +#10192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10193 = PCURVE('',#10194,#10199); +#10194 = PLANE('',#10195); +#10195 = AXIS2_PLACEMENT_3D('',#10196,#10197,#10198); +#10196 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, 0.329766421001)); -#7805 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7806 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7807 = DEFINITIONAL_REPRESENTATION('',(#7808),#7816); -#7808 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#7809,#7810,#7811,#7812, -#7813,#7814,#7815),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#7809 = CARTESIAN_POINT('',(0.15,-0.825)); -#7810 = CARTESIAN_POINT('',(0.15,-1.084807621135)); -#7811 = CARTESIAN_POINT('',(-7.499999999993E-002,-0.954903810568)); -#7812 = CARTESIAN_POINT('',(-0.3,-0.825)); -#7813 = CARTESIAN_POINT('',(-7.499999999993E-002,-0.695096189432)); -#7814 = CARTESIAN_POINT('',(0.15,-0.565192378865)); -#7815 = CARTESIAN_POINT('',(0.15,-0.825)); -#7816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7817 = ORIENTED_EDGE('',*,*,#7818,.T.); -#7818 = EDGE_CURVE('',#7787,#7623,#7819,.T.); -#7819 = SURFACE_CURVE('',#7820,(#7824,#7830),.PCURVE_S1.); -#7820 = LINE('',#7821,#7822); -#7821 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, - 2.976642100057E-002)); -#7822 = VECTOR('',#7823,1.); -#7823 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7824 = PCURVE('',#7667,#7825); -#7825 = DEFINITIONAL_REPRESENTATION('',(#7826),#7829); -#7826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7827,#7828),.UNSPECIFIED.,.F., - .F.,(2,2),(-0.3,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#7827 = CARTESIAN_POINT('',(0.16744807922,0.551173775483)); -#7828 = CARTESIAN_POINT('',(0.16744807922,0.251173775483)); -#7829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7830 = PCURVE('',#7638,#7831); -#7831 = DEFINITIONAL_REPRESENTATION('',(#7832),#7836); -#7832 = LINE('',#7833,#7834); -#7833 = CARTESIAN_POINT('',(-0.214598005422,0.E+000)); -#7834 = VECTOR('',#7835,1.); -#7835 = DIRECTION('',(0.E+000,-1.)); -#7836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7837 = ADVANCED_FACE('',(#7838),#7638,.T.); -#7838 = FACE_BOUND('',#7839,.T.); -#7839 = EDGE_LOOP('',(#7840,#7841,#7842,#7865)); -#7840 = ORIENTED_EDGE('',*,*,#7818,.T.); -#7841 = ORIENTED_EDGE('',*,*,#7622,.T.); -#7842 = ORIENTED_EDGE('',*,*,#7843,.F.); -#7843 = EDGE_CURVE('',#7844,#7595,#7846,.T.); -#7844 = VERTEX_POINT('',#7845); -#7845 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056,0.329766421001) - ); -#7846 = SURFACE_CURVE('',#7847,(#7851,#7858),.PCURVE_S1.); -#7847 = LINE('',#7848,#7849); -#7848 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, +#10197 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10198 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10199 = DEFINITIONAL_REPRESENTATION('',(#10200),#10208); +#10200 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#10201,#10202,#10203,#10204 + ,#10205,#10206,#10207),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#10201 = CARTESIAN_POINT('',(0.15,-0.825)); +#10202 = CARTESIAN_POINT('',(0.15,-1.084807621135)); +#10203 = CARTESIAN_POINT('',(-7.499999999993E-002,-0.954903810568)); +#10204 = CARTESIAN_POINT('',(-0.3,-0.825)); +#10205 = CARTESIAN_POINT('',(-7.499999999993E-002,-0.695096189432)); +#10206 = CARTESIAN_POINT('',(0.15,-0.565192378865)); +#10207 = CARTESIAN_POINT('',(0.15,-0.825)); +#10208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10209 = ORIENTED_EDGE('',*,*,#10210,.T.); +#10210 = EDGE_CURVE('',#10179,#10015,#10211,.T.); +#10211 = SURFACE_CURVE('',#10212,(#10216,#10222),.PCURVE_S1.); +#10212 = LINE('',#10213,#10214); +#10213 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 2.976642100057E-002)); -#7849 = VECTOR('',#7850,1.); -#7850 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7851 = PCURVE('',#7638,#7852); -#7852 = DEFINITIONAL_REPRESENTATION('',(#7853),#7857); -#7853 = LINE('',#7854,#7855); -#7854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7855 = VECTOR('',#7856,1.); -#7856 = DIRECTION('',(0.E+000,-1.)); -#7857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7858 = PCURVE('',#7610,#7859); -#7859 = DEFINITIONAL_REPRESENTATION('',(#7860),#7864); -#7860 = LINE('',#7861,#7862); -#7861 = CARTESIAN_POINT('',(2.84217094304E-014,0.E+000)); -#7862 = VECTOR('',#7863,1.); -#7863 = DIRECTION('',(0.E+000,-1.)); -#7864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7865 = ORIENTED_EDGE('',*,*,#7866,.F.); -#7866 = EDGE_CURVE('',#7787,#7844,#7867,.T.); -#7867 = SURFACE_CURVE('',#7868,(#7872,#7879),.PCURVE_S1.); -#7868 = LINE('',#7869,#7870); -#7869 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, - 0.329766421001)); -#7870 = VECTOR('',#7871,1.); -#7871 = DIRECTION('',(1.,0.E+000,0.E+000)); -#7872 = PCURVE('',#7638,#7873); -#7873 = DEFINITIONAL_REPRESENTATION('',(#7874),#7878); -#7874 = LINE('',#7875,#7876); -#7875 = CARTESIAN_POINT('',(-0.3625,0.3)); -#7876 = VECTOR('',#7877,1.); -#7877 = DIRECTION('',(1.,0.E+000)); -#7878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7879 = PCURVE('',#7802,#7880); -#7880 = DEFINITIONAL_REPRESENTATION('',(#7881),#7885); -#7881 = LINE('',#7882,#7883); -#7882 = CARTESIAN_POINT('',(0.E+000,-0.8)); -#7883 = VECTOR('',#7884,1.); -#7884 = DIRECTION('',(1.,0.E+000)); -#7885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7886 = ADVANCED_FACE('',(#7887),#7610,.T.); -#7887 = FACE_BOUND('',#7888,.T.); -#7888 = EDGE_LOOP('',(#7889,#7890,#7913,#7934)); -#7889 = ORIENTED_EDGE('',*,*,#7594,.T.); -#7890 = ORIENTED_EDGE('',*,*,#7891,.F.); -#7891 = EDGE_CURVE('',#7892,#7567,#7894,.T.); -#7892 = VERTEX_POINT('',#7893); -#7893 = CARTESIAN_POINT('',(0.3571564998,0.182558409944,0.329766421001) - ); -#7894 = SURFACE_CURVE('',#7895,(#7899,#7906),.PCURVE_S1.); -#7895 = LINE('',#7896,#7897); -#7896 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, +#10214 = VECTOR('',#10215,1.); +#10215 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10216 = PCURVE('',#10059,#10217); +#10217 = DEFINITIONAL_REPRESENTATION('',(#10218),#10221); +#10218 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10219,#10220),.UNSPECIFIED., + .F.,.F.,(2,2),(-0.3,0.E+000),.PIECEWISE_BEZIER_KNOTS.); +#10219 = CARTESIAN_POINT('',(0.16744807922,0.551173775483)); +#10220 = CARTESIAN_POINT('',(0.16744807922,0.251173775483)); +#10221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10222 = PCURVE('',#10030,#10223); +#10223 = DEFINITIONAL_REPRESENTATION('',(#10224),#10228); +#10224 = LINE('',#10225,#10226); +#10225 = CARTESIAN_POINT('',(-0.214598005422,0.E+000)); +#10226 = VECTOR('',#10227,1.); +#10227 = DIRECTION('',(0.E+000,-1.)); +#10228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10229 = ADVANCED_FACE('',(#10230),#10030,.T.); +#10230 = FACE_BOUND('',#10231,.T.); +#10231 = EDGE_LOOP('',(#10232,#10233,#10234,#10257)); +#10232 = ORIENTED_EDGE('',*,*,#10210,.T.); +#10233 = ORIENTED_EDGE('',*,*,#10014,.T.); +#10234 = ORIENTED_EDGE('',*,*,#10235,.F.); +#10235 = EDGE_CURVE('',#10236,#9987,#10238,.T.); +#10236 = VERTEX_POINT('',#10237); +#10237 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056,0.329766421001 + )); +#10238 = SURFACE_CURVE('',#10239,(#10243,#10250),.PCURVE_S1.); +#10239 = LINE('',#10240,#10241); +#10240 = CARTESIAN_POINT('',(0.3571564998,-1.417441590056, 2.976642100057E-002)); -#7897 = VECTOR('',#7898,1.); -#7898 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7899 = PCURVE('',#7610,#7900); -#7900 = DEFINITIONAL_REPRESENTATION('',(#7901),#7905); -#7901 = LINE('',#7902,#7903); -#7902 = CARTESIAN_POINT('',(1.6,0.E+000)); -#7903 = VECTOR('',#7904,1.); -#7904 = DIRECTION('',(0.E+000,-1.)); -#7905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7906 = PCURVE('',#7582,#7907); -#7907 = DEFINITIONAL_REPRESENTATION('',(#7908),#7912); -#7908 = LINE('',#7909,#7910); -#7909 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#7910 = VECTOR('',#7911,1.); -#7911 = DIRECTION('',(0.E+000,-1.)); -#7912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7913 = ORIENTED_EDGE('',*,*,#7914,.F.); -#7914 = EDGE_CURVE('',#7844,#7892,#7915,.T.); -#7915 = SURFACE_CURVE('',#7916,(#7920,#7927),.PCURVE_S1.); -#7916 = LINE('',#7917,#7918); -#7917 = CARTESIAN_POINT('',(0.3571564998,-0.617441590056,0.329766421001) - ); -#7918 = VECTOR('',#7919,1.); -#7919 = DIRECTION('',(0.E+000,1.,0.E+000)); -#7920 = PCURVE('',#7610,#7921); -#7921 = DEFINITIONAL_REPRESENTATION('',(#7922),#7926); -#7922 = LINE('',#7923,#7924); -#7923 = CARTESIAN_POINT('',(0.8,0.3)); -#7924 = VECTOR('',#7925,1.); -#7925 = DIRECTION('',(1.,0.E+000)); -#7926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#10241 = VECTOR('',#10242,1.); +#10242 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10243 = PCURVE('',#10030,#10244); +#10244 = DEFINITIONAL_REPRESENTATION('',(#10245),#10249); +#10245 = LINE('',#10246,#10247); +#10246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#10247 = VECTOR('',#10248,1.); +#10248 = DIRECTION('',(0.E+000,-1.)); +#10249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10250 = PCURVE('',#10002,#10251); +#10251 = DEFINITIONAL_REPRESENTATION('',(#10252),#10256); +#10252 = LINE('',#10253,#10254); +#10253 = CARTESIAN_POINT('',(2.84217094304E-014,0.E+000)); +#10254 = VECTOR('',#10255,1.); +#10255 = DIRECTION('',(0.E+000,-1.)); +#10256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#7927 = PCURVE('',#7802,#7928); -#7928 = DEFINITIONAL_REPRESENTATION('',(#7929),#7933); -#7929 = LINE('',#7930,#7931); -#7930 = CARTESIAN_POINT('',(0.3625,0.E+000)); -#7931 = VECTOR('',#7932,1.); -#7932 = DIRECTION('',(0.E+000,1.)); -#7933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#10257 = ORIENTED_EDGE('',*,*,#10258,.F.); +#10258 = EDGE_CURVE('',#10179,#10236,#10259,.T.); +#10259 = SURFACE_CURVE('',#10260,(#10264,#10271),.PCURVE_S1.); +#10260 = LINE('',#10261,#10262); +#10261 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, + 0.329766421001)); +#10262 = VECTOR('',#10263,1.); +#10263 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10264 = PCURVE('',#10030,#10265); +#10265 = DEFINITIONAL_REPRESENTATION('',(#10266),#10270); +#10266 = LINE('',#10267,#10268); +#10267 = CARTESIAN_POINT('',(-0.3625,0.3)); +#10268 = VECTOR('',#10269,1.); +#10269 = DIRECTION('',(1.,0.E+000)); +#10270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10271 = PCURVE('',#10194,#10272); +#10272 = DEFINITIONAL_REPRESENTATION('',(#10273),#10277); +#10273 = LINE('',#10274,#10275); +#10274 = CARTESIAN_POINT('',(0.E+000,-0.8)); +#10275 = VECTOR('',#10276,1.); +#10276 = DIRECTION('',(1.,0.E+000)); +#10277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10278 = ADVANCED_FACE('',(#10279),#10002,.T.); +#10279 = FACE_BOUND('',#10280,.T.); +#10280 = EDGE_LOOP('',(#10281,#10282,#10305,#10326)); +#10281 = ORIENTED_EDGE('',*,*,#9986,.T.); +#10282 = ORIENTED_EDGE('',*,*,#10283,.F.); +#10283 = EDGE_CURVE('',#10284,#9959,#10286,.T.); +#10284 = VERTEX_POINT('',#10285); +#10285 = CARTESIAN_POINT('',(0.3571564998,0.182558409944,0.329766421001) + ); +#10286 = SURFACE_CURVE('',#10287,(#10291,#10298),.PCURVE_S1.); +#10287 = LINE('',#10288,#10289); +#10288 = CARTESIAN_POINT('',(0.3571564998,0.182558409944, + 2.976642100057E-002)); +#10289 = VECTOR('',#10290,1.); +#10290 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10291 = PCURVE('',#10002,#10292); +#10292 = DEFINITIONAL_REPRESENTATION('',(#10293),#10297); +#10293 = LINE('',#10294,#10295); +#10294 = CARTESIAN_POINT('',(1.6,0.E+000)); +#10295 = VECTOR('',#10296,1.); +#10296 = DIRECTION('',(0.E+000,-1.)); +#10297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10298 = PCURVE('',#9974,#10299); +#10299 = DEFINITIONAL_REPRESENTATION('',(#10300),#10304); +#10300 = LINE('',#10301,#10302); +#10301 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#10302 = VECTOR('',#10303,1.); +#10303 = DIRECTION('',(0.E+000,-1.)); +#10304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#7934 = ORIENTED_EDGE('',*,*,#7843,.T.); -#7935 = ADVANCED_FACE('',(#7936),#7582,.T.); -#7936 = FACE_BOUND('',#7937,.T.); -#7937 = EDGE_LOOP('',(#7938,#7960,#7981,#7982)); -#7938 = ORIENTED_EDGE('',*,*,#7939,.T.); -#7939 = EDGE_CURVE('',#7534,#7940,#7942,.T.); -#7940 = VERTEX_POINT('',#7941); -#7941 = CARTESIAN_POINT('',(0.142558494378,0.182558409944,0.329766421001 +#10305 = ORIENTED_EDGE('',*,*,#10306,.F.); +#10306 = EDGE_CURVE('',#10236,#10284,#10307,.T.); +#10307 = SURFACE_CURVE('',#10308,(#10312,#10319),.PCURVE_S1.); +#10308 = LINE('',#10309,#10310); +#10309 = CARTESIAN_POINT('',(0.3571564998,-0.617441590056,0.329766421001 )); -#7942 = SURFACE_CURVE('',#7943,(#7947,#7954),.PCURVE_S1.); -#7943 = LINE('',#7944,#7945); -#7944 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, - -0.221407354483)); -#7945 = VECTOR('',#7946,1.); -#7946 = DIRECTION('',(0.E+000,0.E+000,1.)); -#7947 = PCURVE('',#7582,#7948); -#7948 = DEFINITIONAL_REPRESENTATION('',(#7949),#7953); -#7949 = LINE('',#7950,#7951); -#7950 = CARTESIAN_POINT('',(0.214598005422,-0.251173775483)); -#7951 = VECTOR('',#7952,1.); -#7952 = DIRECTION('',(0.E+000,1.)); -#7953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7954 = PCURVE('',#7555,#7955); -#7955 = DEFINITIONAL_REPRESENTATION('',(#7956),#7959); -#7956 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7957,#7958),.UNSPECIFIED.,.F., - .F.,(2,2),(0.251173775483,0.551173775483),.PIECEWISE_BEZIER_KNOTS.); -#7957 = CARTESIAN_POINT('',(3.309040732809,-0.251173775483)); -#7958 = CARTESIAN_POINT('',(3.309040732809,-0.551173775483)); -#7959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7960 = ORIENTED_EDGE('',*,*,#7961,.F.); -#7961 = EDGE_CURVE('',#7892,#7940,#7962,.T.); -#7962 = SURFACE_CURVE('',#7963,(#7967,#7974),.PCURVE_S1.); -#7963 = LINE('',#7964,#7965); -#7964 = CARTESIAN_POINT('',(-5.343500199819E-003,0.182558409944, +#10310 = VECTOR('',#10311,1.); +#10311 = DIRECTION('',(0.E+000,1.,0.E+000)); +#10312 = PCURVE('',#10002,#10313); +#10313 = DEFINITIONAL_REPRESENTATION('',(#10314),#10318); +#10314 = LINE('',#10315,#10316); +#10315 = CARTESIAN_POINT('',(0.8,0.3)); +#10316 = VECTOR('',#10317,1.); +#10317 = DIRECTION('',(1.,0.E+000)); +#10318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10319 = PCURVE('',#10194,#10320); +#10320 = DEFINITIONAL_REPRESENTATION('',(#10321),#10325); +#10321 = LINE('',#10322,#10323); +#10322 = CARTESIAN_POINT('',(0.3625,0.E+000)); +#10323 = VECTOR('',#10324,1.); +#10324 = DIRECTION('',(0.E+000,1.)); +#10325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10326 = ORIENTED_EDGE('',*,*,#10235,.T.); +#10327 = ADVANCED_FACE('',(#10328),#9974,.T.); +#10328 = FACE_BOUND('',#10329,.T.); +#10329 = EDGE_LOOP('',(#10330,#10352,#10373,#10374)); +#10330 = ORIENTED_EDGE('',*,*,#10331,.T.); +#10331 = EDGE_CURVE('',#9926,#10332,#10334,.T.); +#10332 = VERTEX_POINT('',#10333); +#10333 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, 0.329766421001)); -#7965 = VECTOR('',#7966,1.); -#7966 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#7967 = PCURVE('',#7582,#7968); -#7968 = DEFINITIONAL_REPRESENTATION('',(#7969),#7973); -#7969 = LINE('',#7970,#7971); -#7970 = CARTESIAN_POINT('',(0.3625,0.3)); -#7971 = VECTOR('',#7972,1.); -#7972 = DIRECTION('',(1.,0.E+000)); -#7973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7974 = PCURVE('',#7802,#7975); -#7975 = DEFINITIONAL_REPRESENTATION('',(#7976),#7980); -#7976 = LINE('',#7977,#7978); -#7977 = CARTESIAN_POINT('',(0.E+000,0.8)); -#7978 = VECTOR('',#7979,1.); -#7979 = DIRECTION('',(-1.,0.E+000)); -#7980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#7981 = ORIENTED_EDGE('',*,*,#7891,.T.); -#7982 = ORIENTED_EDGE('',*,*,#7566,.T.); -#7983 = ADVANCED_FACE('',(#7984),#7555,.F.); -#7984 = FACE_BOUND('',#7985,.F.); -#7985 = EDGE_LOOP('',(#7986,#8008,#8009,#8010)); -#7986 = ORIENTED_EDGE('',*,*,#7987,.T.); -#7987 = EDGE_CURVE('',#7988,#7532,#7990,.T.); -#7988 = VERTEX_POINT('',#7989); -#7989 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, +#10334 = SURFACE_CURVE('',#10335,(#10339,#10346),.PCURVE_S1.); +#10335 = LINE('',#10336,#10337); +#10336 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, + -0.221407354483)); +#10337 = VECTOR('',#10338,1.); +#10338 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10339 = PCURVE('',#9974,#10340); +#10340 = DEFINITIONAL_REPRESENTATION('',(#10341),#10345); +#10341 = LINE('',#10342,#10343); +#10342 = CARTESIAN_POINT('',(0.214598005422,-0.251173775483)); +#10343 = VECTOR('',#10344,1.); +#10344 = DIRECTION('',(0.E+000,1.)); +#10345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10346 = PCURVE('',#9947,#10347); +#10347 = DEFINITIONAL_REPRESENTATION('',(#10348),#10351); +#10348 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10349,#10350),.UNSPECIFIED., + .F.,.F.,(2,2),(0.251173775483,0.551173775483), + .PIECEWISE_BEZIER_KNOTS.); +#10349 = CARTESIAN_POINT('',(3.309040732809,-0.251173775483)); +#10350 = CARTESIAN_POINT('',(3.309040732809,-0.551173775483)); +#10351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10352 = ORIENTED_EDGE('',*,*,#10353,.F.); +#10353 = EDGE_CURVE('',#10284,#10332,#10354,.T.); +#10354 = SURFACE_CURVE('',#10355,(#10359,#10366),.PCURVE_S1.); +#10355 = LINE('',#10356,#10357); +#10356 = CARTESIAN_POINT('',(-5.343500199819E-003,0.182558409944, 0.329766421001)); -#7990 = SURFACE_CURVE('',#7991,(#7995,#8001),.PCURVE_S1.); -#7991 = LINE('',#7992,#7993); -#7992 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, - 2.976642100057E-002)); -#7993 = VECTOR('',#7994,1.); -#7994 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#7995 = PCURVE('',#7555,#7996); -#7996 = DEFINITIONAL_REPRESENTATION('',(#7997),#8000); -#7997 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#7998,#7999),.UNSPECIFIED.,.F., - .F.,(2,2),(-0.3,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#7998 = CARTESIAN_POINT('',(6.11573722796,-0.551173775483)); -#7999 = CARTESIAN_POINT('',(6.11573722796,-0.251173775483)); -#8000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8001 = PCURVE('',#7748,#8002); -#8002 = DEFINITIONAL_REPRESENTATION('',(#8003),#8007); -#8003 = LINE('',#8004,#8005); -#8004 = CARTESIAN_POINT('',(0.510401994578,0.E+000)); -#8005 = VECTOR('',#8006,1.); -#8006 = DIRECTION('',(0.E+000,-1.)); -#8007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8008 = ORIENTED_EDGE('',*,*,#7531,.T.); -#8009 = ORIENTED_EDGE('',*,*,#7939,.T.); -#8010 = ORIENTED_EDGE('',*,*,#8011,.T.); -#8011 = EDGE_CURVE('',#7940,#7988,#8012,.T.); -#8012 = SURFACE_CURVE('',#8013,(#8018,#8024),.PCURVE_S1.); -#8013 = CIRCLE('',#8014,0.15); -#8014 = AXIS2_PLACEMENT_3D('',#8015,#8016,#8017); -#8015 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, +#10357 = VECTOR('',#10358,1.); +#10358 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#10359 = PCURVE('',#9974,#10360); +#10360 = DEFINITIONAL_REPRESENTATION('',(#10361),#10365); +#10361 = LINE('',#10362,#10363); +#10362 = CARTESIAN_POINT('',(0.3625,0.3)); +#10363 = VECTOR('',#10364,1.); +#10364 = DIRECTION('',(1.,0.E+000)); +#10365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10366 = PCURVE('',#10194,#10367); +#10367 = DEFINITIONAL_REPRESENTATION('',(#10368),#10372); +#10368 = LINE('',#10369,#10370); +#10369 = CARTESIAN_POINT('',(0.E+000,0.8)); +#10370 = VECTOR('',#10371,1.); +#10371 = DIRECTION('',(-1.,0.E+000)); +#10372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10373 = ORIENTED_EDGE('',*,*,#10283,.T.); +#10374 = ORIENTED_EDGE('',*,*,#9958,.T.); +#10375 = ADVANCED_FACE('',(#10376),#9947,.F.); +#10376 = FACE_BOUND('',#10377,.F.); +#10377 = EDGE_LOOP('',(#10378,#10400,#10401,#10402)); +#10378 = ORIENTED_EDGE('',*,*,#10379,.T.); +#10379 = EDGE_CURVE('',#10380,#9924,#10382,.T.); +#10380 = VERTEX_POINT('',#10381); +#10381 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 0.329766421001)); -#8016 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8017 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#8018 = PCURVE('',#7555,#8019); -#8019 = DEFINITIONAL_REPRESENTATION('',(#8020),#8023); -#8020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#8021,#8022),.UNSPECIFIED.,.F., - .F.,(2,2),(3.309040732809,6.11573722796),.PIECEWISE_BEZIER_KNOTS.); -#8021 = CARTESIAN_POINT('',(3.309040732809,-0.551173775483)); -#8022 = CARTESIAN_POINT('',(6.11573722796,-0.551173775483)); -#8023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8024 = PCURVE('',#7802,#8025); -#8025 = DEFINITIONAL_REPRESENTATION('',(#8026),#8034); -#8026 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#8027,#8028,#8029,#8030, -#8031,#8032,#8033),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#8027 = CARTESIAN_POINT('',(-0.15,0.825)); -#8028 = CARTESIAN_POINT('',(-0.15,1.084807621135)); -#8029 = CARTESIAN_POINT('',(7.499999999993E-002,0.954903810568)); -#8030 = CARTESIAN_POINT('',(0.3,0.825)); -#8031 = CARTESIAN_POINT('',(7.499999999993E-002,0.695096189432)); -#8032 = CARTESIAN_POINT('',(-0.15,0.565192378865)); -#8033 = CARTESIAN_POINT('',(-0.15,0.825)); -#8034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8035 = ADVANCED_FACE('',(#8036),#7748,.T.); -#8036 = FACE_BOUND('',#8037,.T.); -#8037 = EDGE_LOOP('',(#8038,#8039,#8040,#8063)); -#8038 = ORIENTED_EDGE('',*,*,#7987,.T.); -#8039 = ORIENTED_EDGE('',*,*,#7734,.T.); -#8040 = ORIENTED_EDGE('',*,*,#8041,.F.); -#8041 = EDGE_CURVE('',#8042,#7707,#8044,.T.); -#8042 = VERTEX_POINT('',#8043); -#8043 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944,0.329766421001) - ); -#8044 = SURFACE_CURVE('',#8045,(#8049,#8056),.PCURVE_S1.); -#8045 = LINE('',#8046,#8047); -#8046 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, +#10382 = SURFACE_CURVE('',#10383,(#10387,#10393),.PCURVE_S1.); +#10383 = LINE('',#10384,#10385); +#10384 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 2.976642100057E-002)); -#8047 = VECTOR('',#8048,1.); -#8048 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8049 = PCURVE('',#7748,#8050); -#8050 = DEFINITIONAL_REPRESENTATION('',(#8051),#8055); -#8051 = LINE('',#8052,#8053); -#8052 = CARTESIAN_POINT('',(0.725,0.E+000)); -#8053 = VECTOR('',#8054,1.); -#8054 = DIRECTION('',(0.E+000,-1.)); -#8055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8056 = PCURVE('',#7722,#8057); -#8057 = DEFINITIONAL_REPRESENTATION('',(#8058),#8062); -#8058 = LINE('',#8059,#8060); -#8059 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#8060 = VECTOR('',#8061,1.); -#8061 = DIRECTION('',(0.E+000,-1.)); -#8062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8063 = ORIENTED_EDGE('',*,*,#8064,.F.); -#8064 = EDGE_CURVE('',#7988,#8042,#8065,.T.); -#8065 = SURFACE_CURVE('',#8066,(#8070,#8077),.PCURVE_S1.); -#8066 = LINE('',#8067,#8068); -#8067 = CARTESIAN_POINT('',(-5.343500199819E-003,0.182558409944, +#10385 = VECTOR('',#10386,1.); +#10386 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10387 = PCURVE('',#9947,#10388); +#10388 = DEFINITIONAL_REPRESENTATION('',(#10389),#10392); +#10389 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10390,#10391),.UNSPECIFIED., + .F.,.F.,(2,2),(-0.3,0.E+000),.PIECEWISE_BEZIER_KNOTS.); +#10390 = CARTESIAN_POINT('',(6.11573722796,-0.551173775483)); +#10391 = CARTESIAN_POINT('',(6.11573722796,-0.251173775483)); +#10392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10393 = PCURVE('',#10140,#10394); +#10394 = DEFINITIONAL_REPRESENTATION('',(#10395),#10399); +#10395 = LINE('',#10396,#10397); +#10396 = CARTESIAN_POINT('',(0.510401994578,0.E+000)); +#10397 = VECTOR('',#10398,1.); +#10398 = DIRECTION('',(0.E+000,-1.)); +#10399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10400 = ORIENTED_EDGE('',*,*,#9923,.T.); +#10401 = ORIENTED_EDGE('',*,*,#10331,.T.); +#10402 = ORIENTED_EDGE('',*,*,#10403,.T.); +#10403 = EDGE_CURVE('',#10332,#10380,#10404,.T.); +#10404 = SURFACE_CURVE('',#10405,(#10410,#10416),.PCURVE_S1.); +#10405 = CIRCLE('',#10406,0.15); +#10406 = AXIS2_PLACEMENT_3D('',#10407,#10408,#10409); +#10407 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, 0.329766421001)); -#8068 = VECTOR('',#8069,1.); -#8069 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#8070 = PCURVE('',#7748,#8071); -#8071 = DEFINITIONAL_REPRESENTATION('',(#8072),#8076); -#8072 = LINE('',#8073,#8074); -#8073 = CARTESIAN_POINT('',(0.3625,0.3)); -#8074 = VECTOR('',#8075,1.); -#8075 = DIRECTION('',(1.,0.E+000)); -#8076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8077 = PCURVE('',#7802,#8078); -#8078 = DEFINITIONAL_REPRESENTATION('',(#8079),#8083); -#8079 = LINE('',#8080,#8081); -#8080 = CARTESIAN_POINT('',(0.E+000,0.8)); -#8081 = VECTOR('',#8082,1.); -#8082 = DIRECTION('',(-1.,0.E+000)); -#8083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#10408 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10409 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#10410 = PCURVE('',#9947,#10411); +#10411 = DEFINITIONAL_REPRESENTATION('',(#10412),#10415); +#10412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10413,#10414),.UNSPECIFIED., + .F.,.F.,(2,2),(3.309040732809,6.11573722796), + .PIECEWISE_BEZIER_KNOTS.); +#10413 = CARTESIAN_POINT('',(3.309040732809,-0.551173775483)); +#10414 = CARTESIAN_POINT('',(6.11573722796,-0.551173775483)); +#10415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#8084 = ADVANCED_FACE('',(#8085),#7722,.T.); -#8085 = FACE_BOUND('',#8086,.T.); -#8086 = EDGE_LOOP('',(#8087,#8110,#8111,#8112)); -#8087 = ORIENTED_EDGE('',*,*,#8088,.F.); -#8088 = EDGE_CURVE('',#8042,#8089,#8091,.T.); -#8089 = VERTEX_POINT('',#8090); -#8090 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056,0.329766421001 - )); -#8091 = SURFACE_CURVE('',#8092,(#8096,#8103),.PCURVE_S1.); -#8092 = LINE('',#8093,#8094); -#8093 = CARTESIAN_POINT('',(-0.3678435002,-0.617441590056,0.329766421001 +#10416 = PCURVE('',#10194,#10417); +#10417 = DEFINITIONAL_REPRESENTATION('',(#10418),#10426); +#10418 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#10419,#10420,#10421,#10422 + ,#10423,#10424,#10425),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#10419 = CARTESIAN_POINT('',(-0.15,0.825)); +#10420 = CARTESIAN_POINT('',(-0.15,1.084807621135)); +#10421 = CARTESIAN_POINT('',(7.499999999993E-002,0.954903810568)); +#10422 = CARTESIAN_POINT('',(0.3,0.825)); +#10423 = CARTESIAN_POINT('',(7.499999999993E-002,0.695096189432)); +#10424 = CARTESIAN_POINT('',(-0.15,0.565192378865)); +#10425 = CARTESIAN_POINT('',(-0.15,0.825)); +#10426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10427 = ADVANCED_FACE('',(#10428),#10140,.T.); +#10428 = FACE_BOUND('',#10429,.T.); +#10429 = EDGE_LOOP('',(#10430,#10431,#10432,#10455)); +#10430 = ORIENTED_EDGE('',*,*,#10379,.T.); +#10431 = ORIENTED_EDGE('',*,*,#10126,.T.); +#10432 = ORIENTED_EDGE('',*,*,#10433,.F.); +#10433 = EDGE_CURVE('',#10434,#10099,#10436,.T.); +#10434 = VERTEX_POINT('',#10435); +#10435 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944,0.329766421001 )); -#8094 = VECTOR('',#8095,1.); -#8095 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#8096 = PCURVE('',#7722,#8097); -#8097 = DEFINITIONAL_REPRESENTATION('',(#8098),#8102); -#8098 = LINE('',#8099,#8100); -#8099 = CARTESIAN_POINT('',(0.8,0.3)); -#8100 = VECTOR('',#8101,1.); -#8101 = DIRECTION('',(1.,0.E+000)); -#8102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8103 = PCURVE('',#7802,#8104); -#8104 = DEFINITIONAL_REPRESENTATION('',(#8105),#8109); -#8105 = LINE('',#8106,#8107); -#8106 = CARTESIAN_POINT('',(-0.3625,0.E+000)); -#8107 = VECTOR('',#8108,1.); -#8108 = DIRECTION('',(0.E+000,-1.)); -#8109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8110 = ORIENTED_EDGE('',*,*,#8041,.T.); -#8111 = ORIENTED_EDGE('',*,*,#7706,.T.); -#8112 = ORIENTED_EDGE('',*,*,#8113,.F.); -#8113 = EDGE_CURVE('',#8089,#7679,#8114,.T.); -#8114 = SURFACE_CURVE('',#8115,(#8119,#8126),.PCURVE_S1.); -#8115 = LINE('',#8116,#8117); -#8116 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056, +#10436 = SURFACE_CURVE('',#10437,(#10441,#10448),.PCURVE_S1.); +#10437 = LINE('',#10438,#10439); +#10438 = CARTESIAN_POINT('',(-0.3678435002,0.182558409944, 2.976642100057E-002)); -#8117 = VECTOR('',#8118,1.); -#8118 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8119 = PCURVE('',#7722,#8120); -#8120 = DEFINITIONAL_REPRESENTATION('',(#8121),#8125); -#8121 = LINE('',#8122,#8123); -#8122 = CARTESIAN_POINT('',(1.6,0.E+000)); -#8123 = VECTOR('',#8124,1.); -#8124 = DIRECTION('',(0.E+000,-1.)); -#8125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8126 = PCURVE('',#7694,#8127); -#8127 = DEFINITIONAL_REPRESENTATION('',(#8128),#8132); -#8128 = LINE('',#8129,#8130); -#8129 = CARTESIAN_POINT('',(-0.725,0.E+000)); -#8130 = VECTOR('',#8131,1.); -#8131 = DIRECTION('',(0.E+000,-1.)); -#8132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8133 = ADVANCED_FACE('',(#8134),#7694,.T.); -#8134 = FACE_BOUND('',#8135,.T.); -#8135 = EDGE_LOOP('',(#8136,#8137,#8158,#8159)); -#8136 = ORIENTED_EDGE('',*,*,#7764,.T.); -#8137 = ORIENTED_EDGE('',*,*,#8138,.F.); -#8138 = EDGE_CURVE('',#8089,#7765,#8139,.T.); -#8139 = SURFACE_CURVE('',#8140,(#8144,#8151),.PCURVE_S1.); -#8140 = LINE('',#8141,#8142); -#8141 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, +#10439 = VECTOR('',#10440,1.); +#10440 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10441 = PCURVE('',#10140,#10442); +#10442 = DEFINITIONAL_REPRESENTATION('',(#10443),#10447); +#10443 = LINE('',#10444,#10445); +#10444 = CARTESIAN_POINT('',(0.725,0.E+000)); +#10445 = VECTOR('',#10446,1.); +#10446 = DIRECTION('',(0.E+000,-1.)); +#10447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10448 = PCURVE('',#10114,#10449); +#10449 = DEFINITIONAL_REPRESENTATION('',(#10450),#10454); +#10450 = LINE('',#10451,#10452); +#10451 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#10452 = VECTOR('',#10453,1.); +#10453 = DIRECTION('',(0.E+000,-1.)); +#10454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10455 = ORIENTED_EDGE('',*,*,#10456,.F.); +#10456 = EDGE_CURVE('',#10380,#10434,#10457,.T.); +#10457 = SURFACE_CURVE('',#10458,(#10462,#10469),.PCURVE_S1.); +#10458 = LINE('',#10459,#10460); +#10459 = CARTESIAN_POINT('',(-5.343500199819E-003,0.182558409944, 0.329766421001)); -#8142 = VECTOR('',#8143,1.); -#8143 = DIRECTION('',(1.,0.E+000,0.E+000)); -#8144 = PCURVE('',#7694,#8145); -#8145 = DEFINITIONAL_REPRESENTATION('',(#8146),#8150); -#8146 = LINE('',#8147,#8148); -#8147 = CARTESIAN_POINT('',(-0.3625,0.3)); -#8148 = VECTOR('',#8149,1.); -#8149 = DIRECTION('',(1.,0.E+000)); -#8150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8151 = PCURVE('',#7802,#8152); -#8152 = DEFINITIONAL_REPRESENTATION('',(#8153),#8157); -#8153 = LINE('',#8154,#8155); -#8154 = CARTESIAN_POINT('',(0.E+000,-0.8)); -#8155 = VECTOR('',#8156,1.); -#8156 = DIRECTION('',(1.,0.E+000)); -#8157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8158 = ORIENTED_EDGE('',*,*,#8113,.T.); -#8159 = ORIENTED_EDGE('',*,*,#7678,.T.); -#8160 = ADVANCED_FACE('',(#8161),#7802,.T.); -#8161 = FACE_BOUND('',#8162,.T.); -#8162 = EDGE_LOOP('',(#8163,#8164,#8165,#8166,#8167,#8168,#8169,#8170)); -#8163 = ORIENTED_EDGE('',*,*,#8088,.T.); -#8164 = ORIENTED_EDGE('',*,*,#8138,.T.); -#8165 = ORIENTED_EDGE('',*,*,#7786,.T.); -#8166 = ORIENTED_EDGE('',*,*,#7866,.T.); -#8167 = ORIENTED_EDGE('',*,*,#7914,.T.); -#8168 = ORIENTED_EDGE('',*,*,#7961,.T.); -#8169 = ORIENTED_EDGE('',*,*,#8011,.T.); -#8170 = ORIENTED_EDGE('',*,*,#8064,.T.); -#8171 = MANIFOLD_SOLID_BREP('',#8172); -#8172 = CLOSED_SHELL('',(#8173,#8293,#8369,#8418,#8467,#8494)); -#8173 = ADVANCED_FACE('',(#8174),#8188,.T.); -#8174 = FACE_BOUND('',#8175,.T.); -#8175 = EDGE_LOOP('',(#8176,#8211,#8239,#8267)); -#8176 = ORIENTED_EDGE('',*,*,#8177,.F.); -#8177 = EDGE_CURVE('',#8178,#8180,#8182,.T.); -#8178 = VERTEX_POINT('',#8179); -#8179 = CARTESIAN_POINT('',(0.3571564998,-0.163641806703,0.679766421001) - ); -#8180 = VERTEX_POINT('',#8181); -#8181 = CARTESIAN_POINT('',(0.3571564998,-1.071241373408,0.679766421001) - ); -#8182 = SURFACE_CURVE('',#8183,(#8187,#8199),.PCURVE_S1.); -#8183 = LINE('',#8184,#8185); -#8184 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.679766421001) - ); -#8185 = VECTOR('',#8186,1.); -#8186 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#8187 = PCURVE('',#8188,#8193); -#8188 = PLANE('',#8189); -#8189 = AXIS2_PLACEMENT_3D('',#8190,#8191,#8192); -#8190 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, +#10460 = VECTOR('',#10461,1.); +#10461 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#10462 = PCURVE('',#10140,#10463); +#10463 = DEFINITIONAL_REPRESENTATION('',(#10464),#10468); +#10464 = LINE('',#10465,#10466); +#10465 = CARTESIAN_POINT('',(0.3625,0.3)); +#10466 = VECTOR('',#10467,1.); +#10467 = DIRECTION('',(1.,0.E+000)); +#10468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10469 = PCURVE('',#10194,#10470); +#10470 = DEFINITIONAL_REPRESENTATION('',(#10471),#10475); +#10471 = LINE('',#10472,#10473); +#10472 = CARTESIAN_POINT('',(0.E+000,0.8)); +#10473 = VECTOR('',#10474,1.); +#10474 = DIRECTION('',(-1.,0.E+000)); +#10475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10476 = ADVANCED_FACE('',(#10477),#10114,.T.); +#10477 = FACE_BOUND('',#10478,.T.); +#10478 = EDGE_LOOP('',(#10479,#10502,#10503,#10504)); +#10479 = ORIENTED_EDGE('',*,*,#10480,.F.); +#10480 = EDGE_CURVE('',#10434,#10481,#10483,.T.); +#10481 = VERTEX_POINT('',#10482); +#10482 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056, + 0.329766421001)); +#10483 = SURFACE_CURVE('',#10484,(#10488,#10495),.PCURVE_S1.); +#10484 = LINE('',#10485,#10486); +#10485 = CARTESIAN_POINT('',(-0.3678435002,-0.617441590056, + 0.329766421001)); +#10486 = VECTOR('',#10487,1.); +#10487 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#10488 = PCURVE('',#10114,#10489); +#10489 = DEFINITIONAL_REPRESENTATION('',(#10490),#10494); +#10490 = LINE('',#10491,#10492); +#10491 = CARTESIAN_POINT('',(0.8,0.3)); +#10492 = VECTOR('',#10493,1.); +#10493 = DIRECTION('',(1.,0.E+000)); +#10494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10495 = PCURVE('',#10194,#10496); +#10496 = DEFINITIONAL_REPRESENTATION('',(#10497),#10501); +#10497 = LINE('',#10498,#10499); +#10498 = CARTESIAN_POINT('',(-0.3625,0.E+000)); +#10499 = VECTOR('',#10500,1.); +#10500 = DIRECTION('',(0.E+000,-1.)); +#10501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10502 = ORIENTED_EDGE('',*,*,#10433,.T.); +#10503 = ORIENTED_EDGE('',*,*,#10098,.T.); +#10504 = ORIENTED_EDGE('',*,*,#10505,.F.); +#10505 = EDGE_CURVE('',#10481,#10071,#10506,.T.); +#10506 = SURFACE_CURVE('',#10507,(#10511,#10518),.PCURVE_S1.); +#10507 = LINE('',#10508,#10509); +#10508 = CARTESIAN_POINT('',(-0.3678435002,-1.417441590056, + 2.976642100057E-002)); +#10509 = VECTOR('',#10510,1.); +#10510 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#10511 = PCURVE('',#10114,#10512); +#10512 = DEFINITIONAL_REPRESENTATION('',(#10513),#10517); +#10513 = LINE('',#10514,#10515); +#10514 = CARTESIAN_POINT('',(1.6,0.E+000)); +#10515 = VECTOR('',#10516,1.); +#10516 = DIRECTION('',(0.E+000,-1.)); +#10517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10518 = PCURVE('',#10086,#10519); +#10519 = DEFINITIONAL_REPRESENTATION('',(#10520),#10524); +#10520 = LINE('',#10521,#10522); +#10521 = CARTESIAN_POINT('',(-0.725,0.E+000)); +#10522 = VECTOR('',#10523,1.); +#10523 = DIRECTION('',(0.E+000,-1.)); +#10524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10525 = ADVANCED_FACE('',(#10526),#10086,.T.); +#10526 = FACE_BOUND('',#10527,.T.); +#10527 = EDGE_LOOP('',(#10528,#10529,#10550,#10551)); +#10528 = ORIENTED_EDGE('',*,*,#10156,.T.); +#10529 = ORIENTED_EDGE('',*,*,#10530,.F.); +#10530 = EDGE_CURVE('',#10481,#10157,#10531,.T.); +#10531 = SURFACE_CURVE('',#10532,(#10536,#10543),.PCURVE_S1.); +#10532 = LINE('',#10533,#10534); +#10533 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.417441590056, + 0.329766421001)); +#10534 = VECTOR('',#10535,1.); +#10535 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10536 = PCURVE('',#10086,#10537); +#10537 = DEFINITIONAL_REPRESENTATION('',(#10538),#10542); +#10538 = LINE('',#10539,#10540); +#10539 = CARTESIAN_POINT('',(-0.3625,0.3)); +#10540 = VECTOR('',#10541,1.); +#10541 = DIRECTION('',(1.,0.E+000)); +#10542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10543 = PCURVE('',#10194,#10544); +#10544 = DEFINITIONAL_REPRESENTATION('',(#10545),#10549); +#10545 = LINE('',#10546,#10547); +#10546 = CARTESIAN_POINT('',(0.E+000,-0.8)); +#10547 = VECTOR('',#10548,1.); +#10548 = DIRECTION('',(1.,0.E+000)); +#10549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10550 = ORIENTED_EDGE('',*,*,#10505,.T.); +#10551 = ORIENTED_EDGE('',*,*,#10070,.T.); +#10552 = ADVANCED_FACE('',(#10553),#10194,.T.); +#10553 = FACE_BOUND('',#10554,.T.); +#10554 = EDGE_LOOP('',(#10555,#10556,#10557,#10558,#10559,#10560,#10561, + #10562)); +#10555 = ORIENTED_EDGE('',*,*,#10480,.T.); +#10556 = ORIENTED_EDGE('',*,*,#10530,.T.); +#10557 = ORIENTED_EDGE('',*,*,#10178,.T.); +#10558 = ORIENTED_EDGE('',*,*,#10258,.T.); +#10559 = ORIENTED_EDGE('',*,*,#10306,.T.); +#10560 = ORIENTED_EDGE('',*,*,#10353,.T.); +#10561 = ORIENTED_EDGE('',*,*,#10403,.T.); +#10562 = ORIENTED_EDGE('',*,*,#10456,.T.); +#10563 = MANIFOLD_SOLID_BREP('',#10564); +#10564 = CLOSED_SHELL('',(#10565,#10685,#10761,#10810,#10859,#10886)); +#10565 = ADVANCED_FACE('',(#10566),#10580,.T.); +#10566 = FACE_BOUND('',#10567,.T.); +#10567 = EDGE_LOOP('',(#10568,#10603,#10631,#10659)); +#10568 = ORIENTED_EDGE('',*,*,#10569,.F.); +#10569 = EDGE_CURVE('',#10570,#10572,#10574,.T.); +#10570 = VERTEX_POINT('',#10571); +#10571 = CARTESIAN_POINT('',(0.3571564998,-0.163641806703,0.679766421001 + )); +#10572 = VERTEX_POINT('',#10573); +#10573 = CARTESIAN_POINT('',(0.3571564998,-1.071241373408,0.679766421001 + )); +#10574 = SURFACE_CURVE('',#10575,(#10579,#10591),.PCURVE_S1.); +#10575 = LINE('',#10576,#10577); +#10576 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.679766421001 + )); +#10577 = VECTOR('',#10578,1.); +#10578 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10579 = PCURVE('',#10580,#10585); +#10580 = PLANE('',#10581); +#10581 = AXIS2_PLACEMENT_3D('',#10582,#10583,#10584); +#10582 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, 0.679766421001)); -#8191 = DIRECTION('',(0.E+000,0.E+000,1.)); -#8192 = DIRECTION('',(1.,0.E+000,0.E+000)); -#8193 = DEFINITIONAL_REPRESENTATION('',(#8194),#8198); -#8194 = LINE('',#8195,#8196); -#8195 = CARTESIAN_POINT('',(0.3625,-0.5)); -#8196 = VECTOR('',#8197,1.); -#8197 = DIRECTION('',(1.011968286946E-013,-1.)); -#8198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8199 = PCURVE('',#8200,#8205); -#8200 = PLANE('',#8201); -#8201 = AXIS2_PLACEMENT_3D('',#8202,#8203,#8204); -#8202 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.329766421001) - ); -#8203 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#8204 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8205 = DEFINITIONAL_REPRESENTATION('',(#8206),#8210); -#8206 = LINE('',#8207,#8208); -#8207 = CARTESIAN_POINT('',(0.E+000,0.35)); -#8208 = VECTOR('',#8209,1.); -#8209 = DIRECTION('',(-1.,0.E+000)); -#8210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8211 = ORIENTED_EDGE('',*,*,#8212,.F.); -#8212 = EDGE_CURVE('',#8213,#8178,#8215,.T.); -#8213 = VERTEX_POINT('',#8214); -#8214 = CARTESIAN_POINT('',(-0.3678435002,-0.163641806703,0.679766421001 +#10583 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10584 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10585 = DEFINITIONAL_REPRESENTATION('',(#10586),#10590); +#10586 = LINE('',#10587,#10588); +#10587 = CARTESIAN_POINT('',(0.3625,-0.5)); +#10588 = VECTOR('',#10589,1.); +#10589 = DIRECTION('',(1.011968286946E-013,-1.)); +#10590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10591 = PCURVE('',#10592,#10597); +#10592 = PLANE('',#10593); +#10593 = AXIS2_PLACEMENT_3D('',#10594,#10595,#10596); +#10594 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.329766421001 )); -#8215 = SURFACE_CURVE('',#8216,(#8220,#8227),.PCURVE_S1.); -#8216 = LINE('',#8217,#8218); -#8217 = CARTESIAN_POINT('',(0.1759064998,-0.163641806703,0.679766421001) - ); -#8218 = VECTOR('',#8219,1.); -#8219 = DIRECTION('',(1.,9.946375595696E-014,1.31292773537E-014)); -#8220 = PCURVE('',#8188,#8221); -#8221 = DEFINITIONAL_REPRESENTATION('',(#8222),#8226); -#8222 = LINE('',#8223,#8224); -#8223 = CARTESIAN_POINT('',(0.18125,0.453799783352)); -#8224 = VECTOR('',#8225,1.); -#8225 = DIRECTION('',(1.,9.946375595696E-014)); -#8226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8227 = PCURVE('',#8228,#8233); -#8228 = PLANE('',#8229); -#8229 = AXIS2_PLACEMENT_3D('',#8230,#8231,#8232); -#8230 = CARTESIAN_POINT('',(0.1759064998,-0.14054169838,0.504766421001) - ); -#8231 = DIRECTION('',(-1.003265501894E-013,0.991400140533,0.13086543222) - ); -#8232 = DIRECTION('',(4.606824426974E-031,-0.13086543222,0.991400140533) - ); -#8233 = DEFINITIONAL_REPRESENTATION('',(#8234),#8238); -#8234 = LINE('',#8235,#8236); -#8235 = CARTESIAN_POINT('',(0.176518030253,-6.278531618702E-031)); -#8236 = VECTOR('',#8237,1.); -#8237 = DIRECTION('',(-7.403274706225E-031,1.)); -#8238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8239 = ORIENTED_EDGE('',*,*,#8240,.F.); -#8240 = EDGE_CURVE('',#8241,#8213,#8243,.T.); -#8241 = VERTEX_POINT('',#8242); -#8242 = CARTESIAN_POINT('',(-0.3678435002,-1.071241373408,0.679766421001 +#10595 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10596 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10597 = DEFINITIONAL_REPRESENTATION('',(#10598),#10602); +#10598 = LINE('',#10599,#10600); +#10599 = CARTESIAN_POINT('',(0.E+000,0.35)); +#10600 = VECTOR('',#10601,1.); +#10601 = DIRECTION('',(-1.,0.E+000)); +#10602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10603 = ORIENTED_EDGE('',*,*,#10604,.F.); +#10604 = EDGE_CURVE('',#10605,#10570,#10607,.T.); +#10605 = VERTEX_POINT('',#10606); +#10606 = CARTESIAN_POINT('',(-0.3678435002,-0.163641806703, + 0.679766421001)); +#10607 = SURFACE_CURVE('',#10608,(#10612,#10619),.PCURVE_S1.); +#10608 = LINE('',#10609,#10610); +#10609 = CARTESIAN_POINT('',(0.1759064998,-0.163641806703,0.679766421001 )); -#8243 = SURFACE_CURVE('',#8244,(#8248,#8255),.PCURVE_S1.); -#8244 = LINE('',#8245,#8246); -#8245 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056,0.679766421001 +#10610 = VECTOR('',#10611,1.); +#10611 = DIRECTION('',(1.,9.946375595696E-014,1.31292773537E-014)); +#10612 = PCURVE('',#10580,#10613); +#10613 = DEFINITIONAL_REPRESENTATION('',(#10614),#10618); +#10614 = LINE('',#10615,#10616); +#10615 = CARTESIAN_POINT('',(0.18125,0.453799783352)); +#10616 = VECTOR('',#10617,1.); +#10617 = DIRECTION('',(1.,9.946375595696E-014)); +#10618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10619 = PCURVE('',#10620,#10625); +#10620 = PLANE('',#10621); +#10621 = AXIS2_PLACEMENT_3D('',#10622,#10623,#10624); +#10622 = CARTESIAN_POINT('',(0.1759064998,-0.14054169838,0.504766421001) + ); +#10623 = DIRECTION('',(-1.003265501894E-013,0.991400140533,0.13086543222 )); -#8246 = VECTOR('',#8247,1.); -#8247 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8248 = PCURVE('',#8188,#8249); -#8249 = DEFINITIONAL_REPRESENTATION('',(#8250),#8254); -#8250 = LINE('',#8251,#8252); -#8251 = CARTESIAN_POINT('',(-0.3625,0.5)); -#8252 = VECTOR('',#8253,1.); -#8253 = DIRECTION('',(-1.011968286946E-013,1.)); -#8254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8255 = PCURVE('',#8256,#8261); -#8256 = PLANE('',#8257); -#8257 = AXIS2_PLACEMENT_3D('',#8258,#8259,#8260); -#8258 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056,0.329766421001 +#10624 = DIRECTION('',(4.606824426974E-031,-0.13086543222,0.991400140533 )); -#8259 = DIRECTION('',(-1.,-1.011968286946E-013,3.231174267785E-027)); -#8260 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#8261 = DEFINITIONAL_REPRESENTATION('',(#8262),#8266); -#8262 = LINE('',#8263,#8264); -#8263 = CARTESIAN_POINT('',(0.E+000,0.35)); -#8264 = VECTOR('',#8265,1.); -#8265 = DIRECTION('',(-1.,0.E+000)); -#8266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8267 = ORIENTED_EDGE('',*,*,#8268,.F.); -#8268 = EDGE_CURVE('',#8180,#8241,#8269,.T.); -#8269 = SURFACE_CURVE('',#8270,(#8274,#8281),.PCURVE_S1.); -#8270 = LINE('',#8271,#8272); -#8271 = CARTESIAN_POINT('',(0.1759064998,-1.071241373408,0.679766421001) - ); -#8272 = VECTOR('',#8273,1.); -#8273 = DIRECTION('',(-1.,-9.946375595696E-014,1.31292773537E-014)); -#8274 = PCURVE('',#8188,#8275); -#8275 = DEFINITIONAL_REPRESENTATION('',(#8276),#8280); -#8276 = LINE('',#8277,#8278); -#8277 = CARTESIAN_POINT('',(0.18125,-0.453799783352)); -#8278 = VECTOR('',#8279,1.); -#8279 = DIRECTION('',(-1.,-9.946375595696E-014)); -#8280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8281 = PCURVE('',#8282,#8287); -#8282 = PLANE('',#8283); -#8283 = AXIS2_PLACEMENT_3D('',#8284,#8285,#8286); -#8284 = CARTESIAN_POINT('',(0.1759064998,-1.094341481732,0.504766421001) - ); -#8285 = DIRECTION('',(1.003265501894E-013,-0.991400140533,0.13086543222) - ); -#8286 = DIRECTION('',(4.606824426974E-031,-0.13086543222,-0.991400140533 +#10625 = DEFINITIONAL_REPRESENTATION('',(#10626),#10630); +#10626 = LINE('',#10627,#10628); +#10627 = CARTESIAN_POINT('',(0.176518030253,-6.278531618702E-031)); +#10628 = VECTOR('',#10629,1.); +#10629 = DIRECTION('',(-7.403274706225E-031,1.)); +#10630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10631 = ORIENTED_EDGE('',*,*,#10632,.F.); +#10632 = EDGE_CURVE('',#10633,#10605,#10635,.T.); +#10633 = VERTEX_POINT('',#10634); +#10634 = CARTESIAN_POINT('',(-0.3678435002,-1.071241373408, + 0.679766421001)); +#10635 = SURFACE_CURVE('',#10636,(#10640,#10647),.PCURVE_S1.); +#10636 = LINE('',#10637,#10638); +#10637 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056, + 0.679766421001)); +#10638 = VECTOR('',#10639,1.); +#10639 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10640 = PCURVE('',#10580,#10641); +#10641 = DEFINITIONAL_REPRESENTATION('',(#10642),#10646); +#10642 = LINE('',#10643,#10644); +#10643 = CARTESIAN_POINT('',(-0.3625,0.5)); +#10644 = VECTOR('',#10645,1.); +#10645 = DIRECTION('',(-1.011968286946E-013,1.)); +#10646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10647 = PCURVE('',#10648,#10653); +#10648 = PLANE('',#10649); +#10649 = AXIS2_PLACEMENT_3D('',#10650,#10651,#10652); +#10650 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056, + 0.329766421001)); +#10651 = DIRECTION('',(-1.,-1.011968286946E-013,3.231174267785E-027)); +#10652 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10653 = DEFINITIONAL_REPRESENTATION('',(#10654),#10658); +#10654 = LINE('',#10655,#10656); +#10655 = CARTESIAN_POINT('',(0.E+000,0.35)); +#10656 = VECTOR('',#10657,1.); +#10657 = DIRECTION('',(-1.,0.E+000)); +#10658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10659 = ORIENTED_EDGE('',*,*,#10660,.F.); +#10660 = EDGE_CURVE('',#10572,#10633,#10661,.T.); +#10661 = SURFACE_CURVE('',#10662,(#10666,#10673),.PCURVE_S1.); +#10662 = LINE('',#10663,#10664); +#10663 = CARTESIAN_POINT('',(0.1759064998,-1.071241373408,0.679766421001 )); -#8287 = DEFINITIONAL_REPRESENTATION('',(#8288),#8292); -#8288 = LINE('',#8289,#8290); -#8289 = CARTESIAN_POINT('',(-0.176518030253,-8.471010267393E-030)); -#8290 = VECTOR('',#8291,1.); -#8291 = DIRECTION('',(7.403274706225E-031,-1.)); -#8292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8293 = ADVANCED_FACE('',(#8294),#8256,.T.); -#8294 = FACE_BOUND('',#8295,.T.); -#8295 = EDGE_LOOP('',(#8296,#8297,#8320,#8348)); -#8296 = ORIENTED_EDGE('',*,*,#8240,.T.); -#8297 = ORIENTED_EDGE('',*,*,#8298,.F.); -#8298 = EDGE_CURVE('',#8299,#8213,#8301,.T.); -#8299 = VERTEX_POINT('',#8300); -#8300 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056,0.329766421001 +#10664 = VECTOR('',#10665,1.); +#10665 = DIRECTION('',(-1.,-9.946375595696E-014,1.31292773537E-014)); +#10666 = PCURVE('',#10580,#10667); +#10667 = DEFINITIONAL_REPRESENTATION('',(#10668),#10672); +#10668 = LINE('',#10669,#10670); +#10669 = CARTESIAN_POINT('',(0.18125,-0.453799783352)); +#10670 = VECTOR('',#10671,1.); +#10671 = DIRECTION('',(-1.,-9.946375595696E-014)); +#10672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10673 = PCURVE('',#10674,#10679); +#10674 = PLANE('',#10675); +#10675 = AXIS2_PLACEMENT_3D('',#10676,#10677,#10678); +#10676 = CARTESIAN_POINT('',(0.1759064998,-1.094341481732,0.504766421001 )); -#8301 = SURFACE_CURVE('',#8302,(#8306,#8313),.PCURVE_S1.); -#8302 = LINE('',#8303,#8304); -#8303 = CARTESIAN_POINT('',(-0.3678435002,-0.14054169838,0.504766421001) - ); -#8304 = VECTOR('',#8305,1.); -#8305 = DIRECTION('',(0.E+000,-0.13086543222,0.991400140533)); -#8306 = PCURVE('',#8256,#8307); -#8307 = DEFINITIONAL_REPRESENTATION('',(#8308),#8312); -#8308 = LINE('',#8309,#8310); -#8309 = CARTESIAN_POINT('',(2.31001083238E-002,0.175)); -#8310 = VECTOR('',#8311,1.); -#8311 = DIRECTION('',(0.13086543222,0.991400140533)); -#8312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8313 = PCURVE('',#8228,#8314); -#8314 = DEFINITIONAL_REPRESENTATION('',(#8315),#8319); -#8315 = LINE('',#8316,#8317); -#8316 = CARTESIAN_POINT('',(3.492460267773E-017,-0.54375)); -#8317 = VECTOR('',#8318,1.); -#8318 = DIRECTION('',(1.,2.08739454662E-031)); -#8319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8320 = ORIENTED_EDGE('',*,*,#8321,.T.); -#8321 = EDGE_CURVE('',#8299,#8322,#8324,.T.); -#8322 = VERTEX_POINT('',#8323); -#8323 = CARTESIAN_POINT('',(-0.3678435002,-1.117441590056,0.329766421001 +#10677 = DIRECTION('',(1.003265501894E-013,-0.991400140533,0.13086543222 )); -#8324 = SURFACE_CURVE('',#8325,(#8329,#8336),.PCURVE_S1.); -#8325 = LINE('',#8326,#8327); -#8326 = CARTESIAN_POINT('',(-0.3678435002,-0.617441590056,0.329766421001 +#10678 = DIRECTION('',(4.606824426974E-031,-0.13086543222, + -0.991400140533)); +#10679 = DEFINITIONAL_REPRESENTATION('',(#10680),#10684); +#10680 = LINE('',#10681,#10682); +#10681 = CARTESIAN_POINT('',(-0.176518030253,-8.471010267393E-030)); +#10682 = VECTOR('',#10683,1.); +#10683 = DIRECTION('',(7.403274706225E-031,-1.)); +#10684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10685 = ADVANCED_FACE('',(#10686),#10648,.T.); +#10686 = FACE_BOUND('',#10687,.T.); +#10687 = EDGE_LOOP('',(#10688,#10689,#10712,#10740)); +#10688 = ORIENTED_EDGE('',*,*,#10632,.T.); +#10689 = ORIENTED_EDGE('',*,*,#10690,.F.); +#10690 = EDGE_CURVE('',#10691,#10605,#10693,.T.); +#10691 = VERTEX_POINT('',#10692); +#10692 = CARTESIAN_POINT('',(-0.3678435002,-0.117441590056, + 0.329766421001)); +#10693 = SURFACE_CURVE('',#10694,(#10698,#10705),.PCURVE_S1.); +#10694 = LINE('',#10695,#10696); +#10695 = CARTESIAN_POINT('',(-0.3678435002,-0.14054169838,0.504766421001 )); -#8327 = VECTOR('',#8328,1.); -#8328 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#8329 = PCURVE('',#8256,#8330); -#8330 = DEFINITIONAL_REPRESENTATION('',(#8331),#8335); -#8331 = LINE('',#8332,#8333); -#8332 = CARTESIAN_POINT('',(0.5,-8.968310171402E-044)); -#8333 = VECTOR('',#8334,1.); -#8334 = DIRECTION('',(1.,-3.269845888594E-040)); -#8335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8336 = PCURVE('',#8337,#8342); -#8337 = PLANE('',#8338); -#8338 = AXIS2_PLACEMENT_3D('',#8339,#8340,#8341); -#8339 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, +#10696 = VECTOR('',#10697,1.); +#10697 = DIRECTION('',(0.E+000,-0.13086543222,0.991400140533)); +#10698 = PCURVE('',#10648,#10699); +#10699 = DEFINITIONAL_REPRESENTATION('',(#10700),#10704); +#10700 = LINE('',#10701,#10702); +#10701 = CARTESIAN_POINT('',(2.31001083238E-002,0.175)); +#10702 = VECTOR('',#10703,1.); +#10703 = DIRECTION('',(0.13086543222,0.991400140533)); +#10704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10705 = PCURVE('',#10620,#10706); +#10706 = DEFINITIONAL_REPRESENTATION('',(#10707),#10711); +#10707 = LINE('',#10708,#10709); +#10708 = CARTESIAN_POINT('',(3.492460267773E-017,-0.54375)); +#10709 = VECTOR('',#10710,1.); +#10710 = DIRECTION('',(1.,2.08739454662E-031)); +#10711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10712 = ORIENTED_EDGE('',*,*,#10713,.T.); +#10713 = EDGE_CURVE('',#10691,#10714,#10716,.T.); +#10714 = VERTEX_POINT('',#10715); +#10715 = CARTESIAN_POINT('',(-0.3678435002,-1.117441590056, + 0.329766421001)); +#10716 = SURFACE_CURVE('',#10717,(#10721,#10728),.PCURVE_S1.); +#10717 = LINE('',#10718,#10719); +#10718 = CARTESIAN_POINT('',(-0.3678435002,-0.617441590056, 0.329766421001)); -#8340 = DIRECTION('',(0.E+000,0.E+000,1.)); -#8341 = DIRECTION('',(1.,0.E+000,0.E+000)); -#8342 = DEFINITIONAL_REPRESENTATION('',(#8343),#8347); -#8343 = LINE('',#8344,#8345); -#8344 = CARTESIAN_POINT('',(-0.3625,0.E+000)); -#8345 = VECTOR('',#8346,1.); -#8346 = DIRECTION('',(0.E+000,-1.)); -#8347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8348 = ORIENTED_EDGE('',*,*,#8349,.F.); -#8349 = EDGE_CURVE('',#8241,#8322,#8350,.T.); -#8350 = SURFACE_CURVE('',#8351,(#8355,#8362),.PCURVE_S1.); -#8351 = LINE('',#8352,#8353); -#8352 = CARTESIAN_POINT('',(-0.3678435002,-1.094341481732,0.504766421001 +#10719 = VECTOR('',#10720,1.); +#10720 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#10721 = PCURVE('',#10648,#10722); +#10722 = DEFINITIONAL_REPRESENTATION('',(#10723),#10727); +#10723 = LINE('',#10724,#10725); +#10724 = CARTESIAN_POINT('',(0.5,-8.968310171402E-044)); +#10725 = VECTOR('',#10726,1.); +#10726 = DIRECTION('',(1.,-3.269845888594E-040)); +#10727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10728 = PCURVE('',#10729,#10734); +#10729 = PLANE('',#10730); +#10730 = AXIS2_PLACEMENT_3D('',#10731,#10732,#10733); +#10731 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.617441590056, + 0.329766421001)); +#10732 = DIRECTION('',(0.E+000,0.E+000,1.)); +#10733 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10734 = DEFINITIONAL_REPRESENTATION('',(#10735),#10739); +#10735 = LINE('',#10736,#10737); +#10736 = CARTESIAN_POINT('',(-0.3625,0.E+000)); +#10737 = VECTOR('',#10738,1.); +#10738 = DIRECTION('',(0.E+000,-1.)); +#10739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10740 = ORIENTED_EDGE('',*,*,#10741,.F.); +#10741 = EDGE_CURVE('',#10633,#10714,#10742,.T.); +#10742 = SURFACE_CURVE('',#10743,(#10747,#10754),.PCURVE_S1.); +#10743 = LINE('',#10744,#10745); +#10744 = CARTESIAN_POINT('',(-0.3678435002,-1.094341481732, + 0.504766421001)); +#10745 = VECTOR('',#10746,1.); +#10746 = DIRECTION('',(0.E+000,-0.13086543222,-0.991400140533)); +#10747 = PCURVE('',#10648,#10748); +#10748 = DEFINITIONAL_REPRESENTATION('',(#10749),#10753); +#10749 = LINE('',#10750,#10751); +#10750 = CARTESIAN_POINT('',(0.976899891676,0.175)); +#10751 = VECTOR('',#10752,1.); +#10752 = DIRECTION('',(0.13086543222,-0.991400140533)); +#10753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10754 = PCURVE('',#10674,#10755); +#10755 = DEFINITIONAL_REPRESENTATION('',(#10756),#10760); +#10756 = LINE('',#10757,#10758); +#10757 = CARTESIAN_POINT('',(-6.424618738757E-017,-0.54375)); +#10758 = VECTOR('',#10759,1.); +#10759 = DIRECTION('',(1.,2.08739454662E-031)); +#10760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10761 = ADVANCED_FACE('',(#10762),#10674,.T.); +#10762 = FACE_BOUND('',#10763,.T.); +#10763 = EDGE_LOOP('',(#10764,#10765,#10788,#10809)); +#10764 = ORIENTED_EDGE('',*,*,#10741,.T.); +#10765 = ORIENTED_EDGE('',*,*,#10766,.T.); +#10766 = EDGE_CURVE('',#10714,#10767,#10769,.T.); +#10767 = VERTEX_POINT('',#10768); +#10768 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.329766421001 )); -#8353 = VECTOR('',#8354,1.); -#8354 = DIRECTION('',(0.E+000,-0.13086543222,-0.991400140533)); -#8355 = PCURVE('',#8256,#8356); -#8356 = DEFINITIONAL_REPRESENTATION('',(#8357),#8361); -#8357 = LINE('',#8358,#8359); -#8358 = CARTESIAN_POINT('',(0.976899891676,0.175)); -#8359 = VECTOR('',#8360,1.); -#8360 = DIRECTION('',(0.13086543222,-0.991400140533)); -#8361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8362 = PCURVE('',#8282,#8363); -#8363 = DEFINITIONAL_REPRESENTATION('',(#8364),#8368); -#8364 = LINE('',#8365,#8366); -#8365 = CARTESIAN_POINT('',(-6.424618738757E-017,-0.54375)); -#8366 = VECTOR('',#8367,1.); -#8367 = DIRECTION('',(1.,2.08739454662E-031)); -#8368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8369 = ADVANCED_FACE('',(#8370),#8282,.T.); -#8370 = FACE_BOUND('',#8371,.T.); -#8371 = EDGE_LOOP('',(#8372,#8373,#8396,#8417)); -#8372 = ORIENTED_EDGE('',*,*,#8349,.T.); -#8373 = ORIENTED_EDGE('',*,*,#8374,.T.); -#8374 = EDGE_CURVE('',#8322,#8375,#8377,.T.); -#8375 = VERTEX_POINT('',#8376); -#8376 = CARTESIAN_POINT('',(0.3571564998,-1.117441590056,0.329766421001) - ); -#8377 = SURFACE_CURVE('',#8378,(#8382,#8389),.PCURVE_S1.); -#8378 = LINE('',#8379,#8380); -#8379 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.117441590056, +#10769 = SURFACE_CURVE('',#10770,(#10774,#10781),.PCURVE_S1.); +#10770 = LINE('',#10771,#10772); +#10771 = CARTESIAN_POINT('',(-5.343500199819E-003,-1.117441590056, 0.329766421001)); -#8380 = VECTOR('',#8381,1.); -#8381 = DIRECTION('',(1.,0.E+000,0.E+000)); -#8382 = PCURVE('',#8282,#8383); -#8383 = DEFINITIONAL_REPRESENTATION('',(#8384),#8388); -#8384 = LINE('',#8385,#8386); -#8385 = CARTESIAN_POINT('',(0.176518030253,-0.18125)); -#8386 = VECTOR('',#8387,1.); -#8387 = DIRECTION('',(8.2352764422E-031,1.)); -#8388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8389 = PCURVE('',#8337,#8390); -#8390 = DEFINITIONAL_REPRESENTATION('',(#8391),#8395); -#8391 = LINE('',#8392,#8393); -#8392 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#8393 = VECTOR('',#8394,1.); -#8394 = DIRECTION('',(1.,0.E+000)); -#8395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8396 = ORIENTED_EDGE('',*,*,#8397,.F.); -#8397 = EDGE_CURVE('',#8180,#8375,#8398,.T.); -#8398 = SURFACE_CURVE('',#8399,(#8403,#8410),.PCURVE_S1.); -#8399 = LINE('',#8400,#8401); -#8400 = CARTESIAN_POINT('',(0.3571564998,-1.071241373408,0.679766421001) - ); -#8401 = VECTOR('',#8402,1.); -#8402 = DIRECTION('',(1.320564628722E-014,-0.13086543222,-0.991400140533 +#10772 = VECTOR('',#10773,1.); +#10773 = DIRECTION('',(1.,0.E+000,0.E+000)); +#10774 = PCURVE('',#10674,#10775); +#10775 = DEFINITIONAL_REPRESENTATION('',(#10776),#10780); +#10776 = LINE('',#10777,#10778); +#10777 = CARTESIAN_POINT('',(0.176518030253,-0.18125)); +#10778 = VECTOR('',#10779,1.); +#10779 = DIRECTION('',(8.2352764422E-031,1.)); +#10780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10781 = PCURVE('',#10729,#10782); +#10782 = DEFINITIONAL_REPRESENTATION('',(#10783),#10787); +#10783 = LINE('',#10784,#10785); +#10784 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#10785 = VECTOR('',#10786,1.); +#10786 = DIRECTION('',(1.,0.E+000)); +#10787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10788 = ORIENTED_EDGE('',*,*,#10789,.F.); +#10789 = EDGE_CURVE('',#10572,#10767,#10790,.T.); +#10790 = SURFACE_CURVE('',#10791,(#10795,#10802),.PCURVE_S1.); +#10791 = LINE('',#10792,#10793); +#10792 = CARTESIAN_POINT('',(0.3571564998,-1.071241373408,0.679766421001 + )); +#10793 = VECTOR('',#10794,1.); +#10794 = DIRECTION('',(1.320564628722E-014,-0.13086543222, + -0.991400140533)); +#10795 = PCURVE('',#10674,#10796); +#10796 = DEFINITIONAL_REPRESENTATION('',(#10797),#10801); +#10797 = LINE('',#10798,#10799); +#10798 = CARTESIAN_POINT('',(-0.176518030253,0.18125)); +#10799 = VECTOR('',#10800,1.); +#10800 = DIRECTION('',(1.,1.320564628722E-014)); +#10801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10802 = PCURVE('',#10592,#10803); +#10803 = DEFINITIONAL_REPRESENTATION('',(#10804),#10808); +#10804 = LINE('',#10805,#10806); +#10805 = CARTESIAN_POINT('',(4.62002166476E-002,0.35)); +#10806 = VECTOR('',#10807,1.); +#10807 = DIRECTION('',(-0.13086543222,-0.991400140533)); +#10808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10809 = ORIENTED_EDGE('',*,*,#10660,.T.); +#10810 = ADVANCED_FACE('',(#10811),#10592,.T.); +#10811 = FACE_BOUND('',#10812,.T.); +#10812 = EDGE_LOOP('',(#10813,#10836,#10857,#10858)); +#10813 = ORIENTED_EDGE('',*,*,#10814,.T.); +#10814 = EDGE_CURVE('',#10767,#10815,#10817,.T.); +#10815 = VERTEX_POINT('',#10816); +#10816 = CARTESIAN_POINT('',(0.3571564998,-0.117441590056,0.329766421001 )); -#8403 = PCURVE('',#8282,#8404); -#8404 = DEFINITIONAL_REPRESENTATION('',(#8405),#8409); -#8405 = LINE('',#8406,#8407); -#8406 = CARTESIAN_POINT('',(-0.176518030253,0.18125)); -#8407 = VECTOR('',#8408,1.); -#8408 = DIRECTION('',(1.,1.320564628722E-014)); -#8409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8410 = PCURVE('',#8200,#8411); -#8411 = DEFINITIONAL_REPRESENTATION('',(#8412),#8416); -#8412 = LINE('',#8413,#8414); -#8413 = CARTESIAN_POINT('',(4.62002166476E-002,0.35)); -#8414 = VECTOR('',#8415,1.); -#8415 = DIRECTION('',(-0.13086543222,-0.991400140533)); -#8416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8417 = ORIENTED_EDGE('',*,*,#8268,.T.); -#8418 = ADVANCED_FACE('',(#8419),#8200,.T.); -#8419 = FACE_BOUND('',#8420,.T.); -#8420 = EDGE_LOOP('',(#8421,#8444,#8465,#8466)); -#8421 = ORIENTED_EDGE('',*,*,#8422,.T.); -#8422 = EDGE_CURVE('',#8375,#8423,#8425,.T.); -#8423 = VERTEX_POINT('',#8424); -#8424 = CARTESIAN_POINT('',(0.3571564998,-0.117441590056,0.329766421001) - ); -#8425 = SURFACE_CURVE('',#8426,(#8430,#8437),.PCURVE_S1.); -#8426 = LINE('',#8427,#8428); -#8427 = CARTESIAN_POINT('',(0.3571564998,-0.617441590056,0.329766421001) - ); -#8428 = VECTOR('',#8429,1.); -#8429 = DIRECTION('',(0.E+000,1.,0.E+000)); -#8430 = PCURVE('',#8200,#8431); -#8431 = DEFINITIONAL_REPRESENTATION('',(#8432),#8436); -#8432 = LINE('',#8433,#8434); -#8433 = CARTESIAN_POINT('',(0.5,0.E+000)); -#8434 = VECTOR('',#8435,1.); -#8435 = DIRECTION('',(1.,0.E+000)); -#8436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8437 = PCURVE('',#8337,#8438); -#8438 = DEFINITIONAL_REPRESENTATION('',(#8439),#8443); -#8439 = LINE('',#8440,#8441); -#8440 = CARTESIAN_POINT('',(0.3625,0.E+000)); -#8441 = VECTOR('',#8442,1.); -#8442 = DIRECTION('',(0.E+000,1.)); -#8443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8444 = ORIENTED_EDGE('',*,*,#8445,.F.); -#8445 = EDGE_CURVE('',#8178,#8423,#8446,.T.); -#8446 = SURFACE_CURVE('',#8447,(#8451,#8458),.PCURVE_S1.); -#8447 = LINE('',#8448,#8449); -#8448 = CARTESIAN_POINT('',(0.3571564998,-0.14054169838,0.504766421001) - ); -#8449 = VECTOR('',#8450,1.); -#8450 = DIRECTION('',(0.E+000,0.13086543222,-0.991400140533)); -#8451 = PCURVE('',#8200,#8452); -#8452 = DEFINITIONAL_REPRESENTATION('',(#8453),#8457); -#8453 = LINE('',#8454,#8455); -#8454 = CARTESIAN_POINT('',(0.976899891676,0.175)); -#8455 = VECTOR('',#8456,1.); -#8456 = DIRECTION('',(0.13086543222,-0.991400140533)); -#8457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8458 = PCURVE('',#8228,#8459); -#8459 = DEFINITIONAL_REPRESENTATION('',(#8460),#8464); -#8460 = LINE('',#8461,#8462); -#8461 = CARTESIAN_POINT('',(6.415831354952E-017,0.18125)); -#8462 = VECTOR('',#8463,1.); -#8463 = DIRECTION('',(-1.,-2.08739454662E-031)); -#8464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8465 = ORIENTED_EDGE('',*,*,#8177,.T.); -#8466 = ORIENTED_EDGE('',*,*,#8397,.T.); -#8467 = ADVANCED_FACE('',(#8468),#8228,.T.); -#8468 = FACE_BOUND('',#8469,.T.); -#8469 = EDGE_LOOP('',(#8470,#8471,#8472,#8473)); -#8470 = ORIENTED_EDGE('',*,*,#8298,.T.); -#8471 = ORIENTED_EDGE('',*,*,#8212,.T.); -#8472 = ORIENTED_EDGE('',*,*,#8445,.T.); -#8473 = ORIENTED_EDGE('',*,*,#8474,.T.); -#8474 = EDGE_CURVE('',#8423,#8299,#8475,.T.); -#8475 = SURFACE_CURVE('',#8476,(#8480,#8487),.PCURVE_S1.); -#8476 = LINE('',#8477,#8478); -#8477 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.117441590056, +#10817 = SURFACE_CURVE('',#10818,(#10822,#10829),.PCURVE_S1.); +#10818 = LINE('',#10819,#10820); +#10819 = CARTESIAN_POINT('',(0.3571564998,-0.617441590056,0.329766421001 + )); +#10820 = VECTOR('',#10821,1.); +#10821 = DIRECTION('',(0.E+000,1.,0.E+000)); +#10822 = PCURVE('',#10592,#10823); +#10823 = DEFINITIONAL_REPRESENTATION('',(#10824),#10828); +#10824 = LINE('',#10825,#10826); +#10825 = CARTESIAN_POINT('',(0.5,0.E+000)); +#10826 = VECTOR('',#10827,1.); +#10827 = DIRECTION('',(1.,0.E+000)); +#10828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10829 = PCURVE('',#10729,#10830); +#10830 = DEFINITIONAL_REPRESENTATION('',(#10831),#10835); +#10831 = LINE('',#10832,#10833); +#10832 = CARTESIAN_POINT('',(0.3625,0.E+000)); +#10833 = VECTOR('',#10834,1.); +#10834 = DIRECTION('',(0.E+000,1.)); +#10835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10836 = ORIENTED_EDGE('',*,*,#10837,.F.); +#10837 = EDGE_CURVE('',#10570,#10815,#10838,.T.); +#10838 = SURFACE_CURVE('',#10839,(#10843,#10850),.PCURVE_S1.); +#10839 = LINE('',#10840,#10841); +#10840 = CARTESIAN_POINT('',(0.3571564998,-0.14054169838,0.504766421001) + ); +#10841 = VECTOR('',#10842,1.); +#10842 = DIRECTION('',(0.E+000,0.13086543222,-0.991400140533)); +#10843 = PCURVE('',#10592,#10844); +#10844 = DEFINITIONAL_REPRESENTATION('',(#10845),#10849); +#10845 = LINE('',#10846,#10847); +#10846 = CARTESIAN_POINT('',(0.976899891676,0.175)); +#10847 = VECTOR('',#10848,1.); +#10848 = DIRECTION('',(0.13086543222,-0.991400140533)); +#10849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10850 = PCURVE('',#10620,#10851); +#10851 = DEFINITIONAL_REPRESENTATION('',(#10852),#10856); +#10852 = LINE('',#10853,#10854); +#10853 = CARTESIAN_POINT('',(6.415831354952E-017,0.18125)); +#10854 = VECTOR('',#10855,1.); +#10855 = DIRECTION('',(-1.,-2.08739454662E-031)); +#10856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10857 = ORIENTED_EDGE('',*,*,#10569,.T.); +#10858 = ORIENTED_EDGE('',*,*,#10789,.T.); +#10859 = ADVANCED_FACE('',(#10860),#10620,.T.); +#10860 = FACE_BOUND('',#10861,.T.); +#10861 = EDGE_LOOP('',(#10862,#10863,#10864,#10865)); +#10862 = ORIENTED_EDGE('',*,*,#10690,.T.); +#10863 = ORIENTED_EDGE('',*,*,#10604,.T.); +#10864 = ORIENTED_EDGE('',*,*,#10837,.T.); +#10865 = ORIENTED_EDGE('',*,*,#10866,.T.); +#10866 = EDGE_CURVE('',#10815,#10691,#10867,.T.); +#10867 = SURFACE_CURVE('',#10868,(#10872,#10879),.PCURVE_S1.); +#10868 = LINE('',#10869,#10870); +#10869 = CARTESIAN_POINT('',(-5.343500199819E-003,-0.117441590056, 0.329766421001)); -#8478 = VECTOR('',#8479,1.); -#8479 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#8480 = PCURVE('',#8228,#8481); -#8481 = DEFINITIONAL_REPRESENTATION('',(#8482),#8486); -#8482 = LINE('',#8483,#8484); -#8483 = CARTESIAN_POINT('',(-0.176518030253,-0.18125)); -#8484 = VECTOR('',#8485,1.); -#8485 = DIRECTION('',(-8.2352764422E-031,-1.)); -#8486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8487 = PCURVE('',#8337,#8488); -#8488 = DEFINITIONAL_REPRESENTATION('',(#8489),#8493); -#8489 = LINE('',#8490,#8491); -#8490 = CARTESIAN_POINT('',(0.E+000,0.5)); -#8491 = VECTOR('',#8492,1.); -#8492 = DIRECTION('',(-1.,0.E+000)); -#8493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8494 = ADVANCED_FACE('',(#8495),#8337,.F.); -#8495 = FACE_BOUND('',#8496,.T.); -#8496 = EDGE_LOOP('',(#8497,#8498,#8499,#8500)); -#8497 = ORIENTED_EDGE('',*,*,#8422,.F.); -#8498 = ORIENTED_EDGE('',*,*,#8374,.F.); -#8499 = ORIENTED_EDGE('',*,*,#8321,.F.); -#8500 = ORIENTED_EDGE('',*,*,#8474,.F.); -#8501 = MANIFOLD_SOLID_BREP('',#8502); -#8502 = CLOSED_SHELL('',(#8503,#8623,#8699,#8748,#8797,#8824)); -#8503 = ADVANCED_FACE('',(#8504),#8518,.T.); -#8504 = FACE_BOUND('',#8505,.T.); -#8505 = EDGE_LOOP('',(#8506,#8541,#8569,#8597)); -#8506 = ORIENTED_EDGE('',*,*,#8507,.F.); -#8507 = EDGE_CURVE('',#8508,#8510,#8512,.T.); -#8508 = VERTEX_POINT('',#8509); -#8509 = CARTESIAN_POINT('',(6.909329470559E-002,-0.537412988595, +#10870 = VECTOR('',#10871,1.); +#10871 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#10872 = PCURVE('',#10620,#10873); +#10873 = DEFINITIONAL_REPRESENTATION('',(#10874),#10878); +#10874 = LINE('',#10875,#10876); +#10875 = CARTESIAN_POINT('',(-0.176518030253,-0.18125)); +#10876 = VECTOR('',#10877,1.); +#10877 = DIRECTION('',(-8.2352764422E-031,-1.)); +#10878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10879 = PCURVE('',#10729,#10880); +#10880 = DEFINITIONAL_REPRESENTATION('',(#10881),#10885); +#10881 = LINE('',#10882,#10883); +#10882 = CARTESIAN_POINT('',(0.E+000,0.5)); +#10883 = VECTOR('',#10884,1.); +#10884 = DIRECTION('',(-1.,0.E+000)); +#10885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10886 = ADVANCED_FACE('',(#10887),#10729,.F.); +#10887 = FACE_BOUND('',#10888,.T.); +#10888 = EDGE_LOOP('',(#10889,#10890,#10891,#10892)); +#10889 = ORIENTED_EDGE('',*,*,#10814,.F.); +#10890 = ORIENTED_EDGE('',*,*,#10766,.F.); +#10891 = ORIENTED_EDGE('',*,*,#10713,.F.); +#10892 = ORIENTED_EDGE('',*,*,#10866,.F.); +#10893 = MANIFOLD_SOLID_BREP('',#10894); +#10894 = CLOSED_SHELL('',(#10895,#11015,#11091,#11140,#11189,#11216)); +#10895 = ADVANCED_FACE('',(#10896),#10910,.T.); +#10896 = FACE_BOUND('',#10897,.T.); +#10897 = EDGE_LOOP('',(#10898,#10933,#10961,#10989)); +#10898 = ORIENTED_EDGE('',*,*,#10899,.F.); +#10899 = EDGE_CURVE('',#10900,#10902,#10904,.T.); +#10900 = VERTEX_POINT('',#10901); +#10901 = CARTESIAN_POINT('',(6.909329470559E-002,-0.537412988595, 0.404766421001)); -#8510 = VERTEX_POINT('',#8511); -#8511 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#10902 = VERTEX_POINT('',#10903); +#10903 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.404766421001)); -#8512 = SURFACE_CURVE('',#8513,(#8517,#8529),.PCURVE_S1.); -#8513 = LINE('',#8514,#8515); -#8514 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#10904 = SURFACE_CURVE('',#10905,(#10909,#10921),.PCURVE_S1.); +#10905 = LINE('',#10906,#10907); +#10906 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.404766421001)); -#8515 = VECTOR('',#8516,1.); -#8516 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#8517 = PCURVE('',#8518,#8523); -#8518 = PLANE('',#8519); -#8519 = AXIS2_PLACEMENT_3D('',#8520,#8521,#8522); -#8520 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.617441590056, +#10907 = VECTOR('',#10908,1.); +#10908 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10909 = PCURVE('',#10910,#10915); +#10910 = PLANE('',#10911); +#10911 = AXIS2_PLACEMENT_3D('',#10912,#10913,#10914); +#10912 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.617441590056, 0.404766421001)); -#8521 = DIRECTION('',(-6.311124536681E-027,-6.386657886087E-040,1.)); -#8522 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); -#8523 = DEFINITIONAL_REPRESENTATION('',(#8524),#8528); -#8524 = LINE('',#8525,#8526); -#8525 = CARTESIAN_POINT('',(7.443679490547E-002,-8.002860146083E-002)); -#8526 = VECTOR('',#8527,1.); -#8527 = DIRECTION('',(1.011968286946E-013,-1.)); -#8528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8529 = PCURVE('',#8530,#8535); -#8530 = PLANE('',#8531); -#8531 = AXIS2_PLACEMENT_3D('',#8532,#8533,#8534); -#8532 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#10913 = DIRECTION('',(-6.311124536681E-027,-6.386657886087E-040,1.)); +#10914 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); +#10915 = DEFINITIONAL_REPRESENTATION('',(#10916),#10920); +#10916 = LINE('',#10917,#10918); +#10917 = CARTESIAN_POINT('',(7.443679490547E-002,-8.002860146083E-002)); +#10918 = VECTOR('',#10919,1.); +#10919 = DIRECTION('',(1.011968286946E-013,-1.)); +#10920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10921 = PCURVE('',#10922,#10927); +#10922 = PLANE('',#10923); +#10923 = AXIS2_PLACEMENT_3D('',#10924,#10925,#10926); +#10924 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.379766421001)); -#8533 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#8534 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8535 = DEFINITIONAL_REPRESENTATION('',(#8536),#8540); -#8536 = LINE('',#8537,#8538); -#8537 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#8538 = VECTOR('',#8539,1.); -#8539 = DIRECTION('',(-1.,0.E+000)); -#8540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#10925 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10926 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10927 = DEFINITIONAL_REPRESENTATION('',(#10928),#10932); +#10928 = LINE('',#10929,#10930); +#10929 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#10930 = VECTOR('',#10931,1.); +#10931 = DIRECTION('',(-1.,0.E+000)); +#10932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#8541 = ORIENTED_EDGE('',*,*,#8542,.F.); -#8542 = EDGE_CURVE('',#8543,#8508,#8545,.T.); -#8543 = VERTEX_POINT('',#8544); -#8544 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, +#10933 = ORIENTED_EDGE('',*,*,#10934,.F.); +#10934 = EDGE_CURVE('',#10935,#10900,#10937,.T.); +#10935 = VERTEX_POINT('',#10936); +#10936 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, 0.404766421001)); -#8545 = SURFACE_CURVE('',#8546,(#8550,#8557),.PCURVE_S1.); -#8546 = LINE('',#8547,#8548); -#8547 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, +#10937 = SURFACE_CURVE('',#10938,(#10942,#10949),.PCURVE_S1.); +#10938 = LINE('',#10939,#10940); +#10939 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, 0.404766421001)); -#8548 = VECTOR('',#8549,1.); -#8549 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#8550 = PCURVE('',#8518,#8551); -#8551 = DEFINITIONAL_REPRESENTATION('',(#8552),#8556); -#8552 = LINE('',#8553,#8554); -#8553 = CARTESIAN_POINT('',(7.443679490546E-002,8.00286014609E-002)); -#8554 = VECTOR('',#8555,1.); -#8555 = DIRECTION('',(1.,1.011968286946E-013)); -#8556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8557 = PCURVE('',#8558,#8563); -#8558 = PLANE('',#8559); -#8559 = AXIS2_PLACEMENT_3D('',#8560,#8561,#8562); -#8560 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, +#10940 = VECTOR('',#10941,1.); +#10941 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#10942 = PCURVE('',#10910,#10943); +#10943 = DEFINITIONAL_REPRESENTATION('',(#10944),#10948); +#10944 = LINE('',#10945,#10946); +#10945 = CARTESIAN_POINT('',(7.443679490546E-002,8.00286014609E-002)); +#10946 = VECTOR('',#10947,1.); +#10947 = DIRECTION('',(1.,1.011968286946E-013)); +#10948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10949 = PCURVE('',#10950,#10955); +#10950 = PLANE('',#10951); +#10951 = AXIS2_PLACEMENT_3D('',#10952,#10953,#10954); +#10952 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, 0.379766421001)); -#8561 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8562 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#8563 = DEFINITIONAL_REPRESENTATION('',(#8564),#8568); -#8564 = LINE('',#8565,#8566); -#8565 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#8566 = VECTOR('',#8567,1.); -#8567 = DIRECTION('',(-1.,0.E+000)); -#8568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8569 = ORIENTED_EDGE('',*,*,#8570,.F.); -#8570 = EDGE_CURVE('',#8571,#8543,#8573,.T.); -#8571 = VERTEX_POINT('',#8572); -#8572 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.697470191517, +#10953 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10954 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10955 = DEFINITIONAL_REPRESENTATION('',(#10956),#10960); +#10956 = LINE('',#10957,#10958); +#10957 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#10958 = VECTOR('',#10959,1.); +#10959 = DIRECTION('',(-1.,0.E+000)); +#10960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10961 = ORIENTED_EDGE('',*,*,#10962,.F.); +#10962 = EDGE_CURVE('',#10963,#10935,#10965,.T.); +#10963 = VERTEX_POINT('',#10964); +#10964 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.697470191517, 0.404766421001)); -#8573 = SURFACE_CURVE('',#8574,(#8578,#8585),.PCURVE_S1.); -#8574 = LINE('',#8575,#8576); -#8575 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, +#10965 = SURFACE_CURVE('',#10966,(#10970,#10977),.PCURVE_S1.); +#10966 = LINE('',#10967,#10968); +#10967 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, 0.404766421001)); -#8576 = VECTOR('',#8577,1.); -#8577 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8578 = PCURVE('',#8518,#8579); -#8579 = DEFINITIONAL_REPRESENTATION('',(#8580),#8584); -#8580 = LINE('',#8581,#8582); -#8581 = CARTESIAN_POINT('',(-7.443679490542E-002,8.002860146089E-002)); -#8582 = VECTOR('',#8583,1.); -#8583 = DIRECTION('',(-1.011968286946E-013,1.)); -#8584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8585 = PCURVE('',#8586,#8591); -#8586 = PLANE('',#8587); -#8587 = AXIS2_PLACEMENT_3D('',#8588,#8589,#8590); -#8588 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, +#10968 = VECTOR('',#10969,1.); +#10969 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#10970 = PCURVE('',#10910,#10971); +#10971 = DEFINITIONAL_REPRESENTATION('',(#10972),#10976); +#10972 = LINE('',#10973,#10974); +#10973 = CARTESIAN_POINT('',(-7.443679490542E-002,8.002860146089E-002)); +#10974 = VECTOR('',#10975,1.); +#10975 = DIRECTION('',(-1.011968286946E-013,1.)); +#10976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10977 = PCURVE('',#10978,#10983); +#10978 = PLANE('',#10979); +#10979 = AXIS2_PLACEMENT_3D('',#10980,#10981,#10982); +#10980 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, 0.379766421001)); -#8589 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#8590 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#8591 = DEFINITIONAL_REPRESENTATION('',(#8592),#8596); -#8592 = LINE('',#8593,#8594); -#8593 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#8594 = VECTOR('',#8595,1.); -#8595 = DIRECTION('',(-1.,0.E+000)); -#8596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8597 = ORIENTED_EDGE('',*,*,#8598,.F.); -#8598 = EDGE_CURVE('',#8510,#8571,#8599,.T.); -#8599 = SURFACE_CURVE('',#8600,(#8604,#8611),.PCURVE_S1.); -#8600 = LINE('',#8601,#8602); -#8601 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#10981 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10982 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#10983 = DEFINITIONAL_REPRESENTATION('',(#10984),#10988); +#10984 = LINE('',#10985,#10986); +#10985 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#10986 = VECTOR('',#10987,1.); +#10987 = DIRECTION('',(-1.,0.E+000)); +#10988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#10989 = ORIENTED_EDGE('',*,*,#10990,.F.); +#10990 = EDGE_CURVE('',#10902,#10963,#10991,.T.); +#10991 = SURFACE_CURVE('',#10992,(#10996,#11003),.PCURVE_S1.); +#10992 = LINE('',#10993,#10994); +#10993 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.404766421001)); -#8602 = VECTOR('',#8603,1.); -#8603 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#8604 = PCURVE('',#8518,#8605); -#8605 = DEFINITIONAL_REPRESENTATION('',(#8606),#8610); -#8606 = LINE('',#8607,#8608); -#8607 = CARTESIAN_POINT('',(7.443679490547E-002,-8.002860146083E-002)); -#8608 = VECTOR('',#8609,1.); -#8609 = DIRECTION('',(-1.,-1.011968286946E-013)); -#8610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8611 = PCURVE('',#8612,#8617); -#8612 = PLANE('',#8613); -#8613 = AXIS2_PLACEMENT_3D('',#8614,#8615,#8616); -#8614 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#10994 = VECTOR('',#10995,1.); +#10995 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#10996 = PCURVE('',#10910,#10997); +#10997 = DEFINITIONAL_REPRESENTATION('',(#10998),#11002); +#10998 = LINE('',#10999,#11000); +#10999 = CARTESIAN_POINT('',(7.443679490547E-002,-8.002860146083E-002)); +#11000 = VECTOR('',#11001,1.); +#11001 = DIRECTION('',(-1.,-1.011968286946E-013)); +#11002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11003 = PCURVE('',#11004,#11009); +#11004 = PLANE('',#11005); +#11005 = AXIS2_PLACEMENT_3D('',#11006,#11007,#11008); +#11006 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.379766421001)); -#8615 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#8616 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#8617 = DEFINITIONAL_REPRESENTATION('',(#8618),#8622); -#8618 = LINE('',#8619,#8620); -#8619 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#8620 = VECTOR('',#8621,1.); -#8621 = DIRECTION('',(-1.,0.E+000)); -#8622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8623 = ADVANCED_FACE('',(#8624),#8586,.T.); -#8624 = FACE_BOUND('',#8625,.T.); -#8625 = EDGE_LOOP('',(#8626,#8627,#8650,#8678)); -#8626 = ORIENTED_EDGE('',*,*,#8570,.T.); -#8627 = ORIENTED_EDGE('',*,*,#8628,.F.); -#8628 = EDGE_CURVE('',#8629,#8543,#8631,.T.); -#8629 = VERTEX_POINT('',#8630); -#8630 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, +#11007 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11008 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11009 = DEFINITIONAL_REPRESENTATION('',(#11010),#11014); +#11010 = LINE('',#11011,#11012); +#11011 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#11012 = VECTOR('',#11013,1.); +#11013 = DIRECTION('',(-1.,0.E+000)); +#11014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11015 = ADVANCED_FACE('',(#11016),#10978,.T.); +#11016 = FACE_BOUND('',#11017,.T.); +#11017 = EDGE_LOOP('',(#11018,#11019,#11042,#11070)); +#11018 = ORIENTED_EDGE('',*,*,#10962,.T.); +#11019 = ORIENTED_EDGE('',*,*,#11020,.F.); +#11020 = EDGE_CURVE('',#11021,#10935,#11023,.T.); +#11021 = VERTEX_POINT('',#11022); +#11022 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, 0.329766421001)); -#8631 = SURFACE_CURVE('',#8632,(#8636,#8643),.PCURVE_S1.); -#8632 = LINE('',#8633,#8634); -#8633 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, +#11023 = SURFACE_CURVE('',#11024,(#11028,#11035),.PCURVE_S1.); +#11024 = LINE('',#11025,#11026); +#11025 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.537412988595, 0.379766421001)); -#8634 = VECTOR('',#8635,1.); -#8635 = DIRECTION('',(0.E+000,0.E+000,1.)); -#8636 = PCURVE('',#8586,#8637); -#8637 = DEFINITIONAL_REPRESENTATION('',(#8638),#8642); -#8638 = LINE('',#8639,#8640); -#8639 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#8640 = VECTOR('',#8641,1.); -#8641 = DIRECTION('',(0.E+000,1.)); -#8642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8643 = PCURVE('',#8558,#8644); -#8644 = DEFINITIONAL_REPRESENTATION('',(#8645),#8649); -#8645 = LINE('',#8646,#8647); -#8646 = CARTESIAN_POINT('',(0.148873589811,0.E+000)); -#8647 = VECTOR('',#8648,1.); -#8648 = DIRECTION('',(0.E+000,1.)); -#8649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8650 = ORIENTED_EDGE('',*,*,#8651,.T.); -#8651 = EDGE_CURVE('',#8629,#8652,#8654,.T.); -#8652 = VERTEX_POINT('',#8653); -#8653 = CARTESIAN_POINT('',(-7.978029510528E-002,-0.697470191517, +#11026 = VECTOR('',#11027,1.); +#11027 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11028 = PCURVE('',#10978,#11029); +#11029 = DEFINITIONAL_REPRESENTATION('',(#11030),#11034); +#11030 = LINE('',#11031,#11032); +#11031 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#11032 = VECTOR('',#11033,1.); +#11033 = DIRECTION('',(0.E+000,1.)); +#11034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11035 = PCURVE('',#10950,#11036); +#11036 = DEFINITIONAL_REPRESENTATION('',(#11037),#11041); +#11037 = LINE('',#11038,#11039); +#11038 = CARTESIAN_POINT('',(0.148873589811,0.E+000)); +#11039 = VECTOR('',#11040,1.); +#11040 = DIRECTION('',(0.E+000,1.)); +#11041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11042 = ORIENTED_EDGE('',*,*,#11043,.T.); +#11043 = EDGE_CURVE('',#11021,#11044,#11046,.T.); +#11044 = VERTEX_POINT('',#11045); +#11045 = CARTESIAN_POINT('',(-7.978029510528E-002,-0.697470191517, 0.329766421001)); -#8654 = SURFACE_CURVE('',#8655,(#8659,#8666),.PCURVE_S1.); -#8655 = LINE('',#8656,#8657); -#8656 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.617441590056, +#11046 = SURFACE_CURVE('',#11047,(#11051,#11058),.PCURVE_S1.); +#11047 = LINE('',#11048,#11049); +#11048 = CARTESIAN_POINT('',(-7.978029510529E-002,-0.617441590056, 0.329766421001)); -#8657 = VECTOR('',#8658,1.); -#8658 = DIRECTION('',(4.030699329227E-066,-1.,-6.386657886087E-040)); -#8659 = PCURVE('',#8586,#8660); -#8660 = DEFINITIONAL_REPRESENTATION('',(#8661),#8665); -#8661 = LINE('',#8662,#8663); -#8662 = CARTESIAN_POINT('',(8.002860146089E-002,-5.E-002)); -#8663 = VECTOR('',#8664,1.); -#8664 = DIRECTION('',(1.,-6.386657886087E-040)); -#8665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8666 = PCURVE('',#8667,#8672); -#8667 = PLANE('',#8668); -#8668 = AXIS2_PLACEMENT_3D('',#8669,#8670,#8671); -#8669 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.617441590056, +#11049 = VECTOR('',#11050,1.); +#11050 = DIRECTION('',(4.030699329227E-066,-1.,-6.386657886087E-040)); +#11051 = PCURVE('',#10978,#11052); +#11052 = DEFINITIONAL_REPRESENTATION('',(#11053),#11057); +#11053 = LINE('',#11054,#11055); +#11054 = CARTESIAN_POINT('',(8.002860146089E-002,-5.E-002)); +#11055 = VECTOR('',#11056,1.); +#11056 = DIRECTION('',(1.,-6.386657886087E-040)); +#11057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11058 = PCURVE('',#11059,#11064); +#11059 = PLANE('',#11060); +#11060 = AXIS2_PLACEMENT_3D('',#11061,#11062,#11063); +#11061 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.617441590056, 0.329766421001)); -#8670 = DIRECTION('',(-6.311124536681E-027,-6.386657886087E-040,1.)); -#8671 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); -#8672 = DEFINITIONAL_REPRESENTATION('',(#8673),#8677); -#8673 = LINE('',#8674,#8675); -#8674 = CARTESIAN_POINT('',(-7.443679490542E-002,3.000323392951E-067)); -#8675 = VECTOR('',#8676,1.); -#8676 = DIRECTION('',(2.944402941176E-082,-1.)); -#8677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8678 = ORIENTED_EDGE('',*,*,#8679,.F.); -#8679 = EDGE_CURVE('',#8571,#8652,#8680,.T.); -#8680 = SURFACE_CURVE('',#8681,(#8685,#8692),.PCURVE_S1.); -#8681 = LINE('',#8682,#8683); -#8682 = CARTESIAN_POINT('',(-7.978029510528E-002,-0.697470191517, +#11062 = DIRECTION('',(-6.311124536681E-027,-6.386657886087E-040,1.)); +#11063 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); +#11064 = DEFINITIONAL_REPRESENTATION('',(#11065),#11069); +#11065 = LINE('',#11066,#11067); +#11066 = CARTESIAN_POINT('',(-7.443679490542E-002,3.000323392951E-067)); +#11067 = VECTOR('',#11068,1.); +#11068 = DIRECTION('',(2.944402941176E-082,-1.)); +#11069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11070 = ORIENTED_EDGE('',*,*,#11071,.F.); +#11071 = EDGE_CURVE('',#10963,#11044,#11072,.T.); +#11072 = SURFACE_CURVE('',#11073,(#11077,#11084),.PCURVE_S1.); +#11073 = LINE('',#11074,#11075); +#11074 = CARTESIAN_POINT('',(-7.978029510528E-002,-0.697470191517, 0.379766421001)); -#8683 = VECTOR('',#8684,1.); -#8684 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8685 = PCURVE('',#8586,#8686); -#8686 = DEFINITIONAL_REPRESENTATION('',(#8687),#8691); -#8687 = LINE('',#8688,#8689); -#8688 = CARTESIAN_POINT('',(0.160057202922,0.E+000)); -#8689 = VECTOR('',#8690,1.); -#8690 = DIRECTION('',(0.E+000,-1.)); -#8691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8692 = PCURVE('',#8612,#8693); -#8693 = DEFINITIONAL_REPRESENTATION('',(#8694),#8698); -#8694 = LINE('',#8695,#8696); -#8695 = CARTESIAN_POINT('',(-0.148873589811,0.E+000)); -#8696 = VECTOR('',#8697,1.); -#8697 = DIRECTION('',(0.E+000,-1.)); -#8698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8699 = ADVANCED_FACE('',(#8700),#8612,.T.); -#8700 = FACE_BOUND('',#8701,.T.); -#8701 = EDGE_LOOP('',(#8702,#8703,#8704,#8727)); -#8702 = ORIENTED_EDGE('',*,*,#8598,.T.); -#8703 = ORIENTED_EDGE('',*,*,#8679,.T.); -#8704 = ORIENTED_EDGE('',*,*,#8705,.T.); -#8705 = EDGE_CURVE('',#8652,#8706,#8708,.T.); -#8706 = VERTEX_POINT('',#8707); -#8707 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#11075 = VECTOR('',#11076,1.); +#11076 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11077 = PCURVE('',#10978,#11078); +#11078 = DEFINITIONAL_REPRESENTATION('',(#11079),#11083); +#11079 = LINE('',#11080,#11081); +#11080 = CARTESIAN_POINT('',(0.160057202922,0.E+000)); +#11081 = VECTOR('',#11082,1.); +#11082 = DIRECTION('',(0.E+000,-1.)); +#11083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11084 = PCURVE('',#11004,#11085); +#11085 = DEFINITIONAL_REPRESENTATION('',(#11086),#11090); +#11086 = LINE('',#11087,#11088); +#11087 = CARTESIAN_POINT('',(-0.148873589811,0.E+000)); +#11088 = VECTOR('',#11089,1.); +#11089 = DIRECTION('',(0.E+000,-1.)); +#11090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11091 = ADVANCED_FACE('',(#11092),#11004,.T.); +#11092 = FACE_BOUND('',#11093,.T.); +#11093 = EDGE_LOOP('',(#11094,#11095,#11096,#11119)); +#11094 = ORIENTED_EDGE('',*,*,#10990,.T.); +#11095 = ORIENTED_EDGE('',*,*,#11071,.T.); +#11096 = ORIENTED_EDGE('',*,*,#11097,.T.); +#11097 = EDGE_CURVE('',#11044,#11098,#11100,.T.); +#11098 = VERTEX_POINT('',#11099); +#11099 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.329766421001)); -#8708 = SURFACE_CURVE('',#8709,(#8713,#8720),.PCURVE_S1.); -#8709 = LINE('',#8710,#8711); -#8710 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.697470191517, +#11100 = SURFACE_CURVE('',#11101,(#11105,#11112),.PCURVE_S1.); +#11101 = LINE('',#11102,#11103); +#11102 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.697470191517, 0.329766421001)); -#8711 = VECTOR('',#8712,1.); -#8712 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); -#8713 = PCURVE('',#8612,#8714); -#8714 = DEFINITIONAL_REPRESENTATION('',(#8715),#8719); -#8715 = LINE('',#8716,#8717); -#8716 = CARTESIAN_POINT('',(-7.443679490547E-002,-5.E-002)); -#8717 = VECTOR('',#8718,1.); -#8718 = DIRECTION('',(1.,6.311124536681E-027)); -#8719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8720 = PCURVE('',#8667,#8721); -#8721 = DEFINITIONAL_REPRESENTATION('',(#8722),#8726); -#8722 = LINE('',#8723,#8724); -#8723 = CARTESIAN_POINT('',(0.E+000,-8.002860146085E-002)); -#8724 = VECTOR('',#8725,1.); -#8725 = DIRECTION('',(1.,2.32669603044E-082)); -#8726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8727 = ORIENTED_EDGE('',*,*,#8728,.F.); -#8728 = EDGE_CURVE('',#8510,#8706,#8729,.T.); -#8729 = SURFACE_CURVE('',#8730,(#8734,#8741),.PCURVE_S1.); -#8730 = LINE('',#8731,#8732); -#8731 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, +#11103 = VECTOR('',#11104,1.); +#11104 = DIRECTION('',(1.,0.E+000,6.311124536681E-027)); +#11105 = PCURVE('',#11004,#11106); +#11106 = DEFINITIONAL_REPRESENTATION('',(#11107),#11111); +#11107 = LINE('',#11108,#11109); +#11108 = CARTESIAN_POINT('',(-7.443679490547E-002,-5.E-002)); +#11109 = VECTOR('',#11110,1.); +#11110 = DIRECTION('',(1.,6.311124536681E-027)); +#11111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11112 = PCURVE('',#11059,#11113); +#11113 = DEFINITIONAL_REPRESENTATION('',(#11114),#11118); +#11114 = LINE('',#11115,#11116); +#11115 = CARTESIAN_POINT('',(0.E+000,-8.002860146085E-002)); +#11116 = VECTOR('',#11117,1.); +#11117 = DIRECTION('',(1.,2.32669603044E-082)); +#11118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11119 = ORIENTED_EDGE('',*,*,#11120,.F.); +#11120 = EDGE_CURVE('',#10902,#11098,#11121,.T.); +#11121 = SURFACE_CURVE('',#11122,(#11126,#11133),.PCURVE_S1.); +#11122 = LINE('',#11123,#11124); +#11123 = CARTESIAN_POINT('',(6.90932947056E-002,-0.697470191517, 0.379766421001)); -#8732 = VECTOR('',#8733,1.); -#8733 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8734 = PCURVE('',#8612,#8735); -#8735 = DEFINITIONAL_REPRESENTATION('',(#8736),#8740); -#8736 = LINE('',#8737,#8738); -#8737 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#8738 = VECTOR('',#8739,1.); -#8739 = DIRECTION('',(0.E+000,-1.)); -#8740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8741 = PCURVE('',#8530,#8742); -#8742 = DEFINITIONAL_REPRESENTATION('',(#8743),#8747); -#8743 = LINE('',#8744,#8745); -#8744 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#8745 = VECTOR('',#8746,1.); -#8746 = DIRECTION('',(0.E+000,-1.)); -#8747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8748 = ADVANCED_FACE('',(#8749),#8530,.T.); -#8749 = FACE_BOUND('',#8750,.T.); -#8750 = EDGE_LOOP('',(#8751,#8774,#8795,#8796)); -#8751 = ORIENTED_EDGE('',*,*,#8752,.T.); -#8752 = EDGE_CURVE('',#8706,#8753,#8755,.T.); -#8753 = VERTEX_POINT('',#8754); -#8754 = CARTESIAN_POINT('',(6.909329470559E-002,-0.537412988595, +#11124 = VECTOR('',#11125,1.); +#11125 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11126 = PCURVE('',#11004,#11127); +#11127 = DEFINITIONAL_REPRESENTATION('',(#11128),#11132); +#11128 = LINE('',#11129,#11130); +#11129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11130 = VECTOR('',#11131,1.); +#11131 = DIRECTION('',(0.E+000,-1.)); +#11132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11133 = PCURVE('',#10922,#11134); +#11134 = DEFINITIONAL_REPRESENTATION('',(#11135),#11139); +#11135 = LINE('',#11136,#11137); +#11136 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11137 = VECTOR('',#11138,1.); +#11138 = DIRECTION('',(0.E+000,-1.)); +#11139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11140 = ADVANCED_FACE('',(#11141),#10922,.T.); +#11141 = FACE_BOUND('',#11142,.T.); +#11142 = EDGE_LOOP('',(#11143,#11166,#11187,#11188)); +#11143 = ORIENTED_EDGE('',*,*,#11144,.T.); +#11144 = EDGE_CURVE('',#11098,#11145,#11147,.T.); +#11145 = VERTEX_POINT('',#11146); +#11146 = CARTESIAN_POINT('',(6.909329470559E-002,-0.537412988595, 0.329766421001)); -#8755 = SURFACE_CURVE('',#8756,(#8760,#8767),.PCURVE_S1.); -#8756 = LINE('',#8757,#8758); -#8757 = CARTESIAN_POINT('',(6.90932947056E-002,-0.617441590056, +#11147 = SURFACE_CURVE('',#11148,(#11152,#11159),.PCURVE_S1.); +#11148 = LINE('',#11149,#11150); +#11149 = CARTESIAN_POINT('',(6.90932947056E-002,-0.617441590056, 0.329766421001)); -#8758 = VECTOR('',#8759,1.); -#8759 = DIRECTION('',(-4.030699329227E-066,1.,6.386657886087E-040)); -#8760 = PCURVE('',#8530,#8761); -#8761 = DEFINITIONAL_REPRESENTATION('',(#8762),#8766); -#8762 = LINE('',#8763,#8764); -#8763 = CARTESIAN_POINT('',(8.002860146083E-002,-5.E-002)); -#8764 = VECTOR('',#8765,1.); -#8765 = DIRECTION('',(1.,6.386657886087E-040)); -#8766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8767 = PCURVE('',#8667,#8768); -#8768 = DEFINITIONAL_REPRESENTATION('',(#8769),#8773); -#8769 = LINE('',#8770,#8771); -#8770 = CARTESIAN_POINT('',(7.443679490547E-002,-3.000323392953E-067)); -#8771 = VECTOR('',#8772,1.); -#8772 = DIRECTION('',(-2.944402941176E-082,1.)); -#8773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8774 = ORIENTED_EDGE('',*,*,#8775,.F.); -#8775 = EDGE_CURVE('',#8508,#8753,#8776,.T.); -#8776 = SURFACE_CURVE('',#8777,(#8781,#8788),.PCURVE_S1.); -#8777 = LINE('',#8778,#8779); -#8778 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, +#11150 = VECTOR('',#11151,1.); +#11151 = DIRECTION('',(-4.030699329227E-066,1.,6.386657886087E-040)); +#11152 = PCURVE('',#10922,#11153); +#11153 = DEFINITIONAL_REPRESENTATION('',(#11154),#11158); +#11154 = LINE('',#11155,#11156); +#11155 = CARTESIAN_POINT('',(8.002860146083E-002,-5.E-002)); +#11156 = VECTOR('',#11157,1.); +#11157 = DIRECTION('',(1.,6.386657886087E-040)); +#11158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11159 = PCURVE('',#11059,#11160); +#11160 = DEFINITIONAL_REPRESENTATION('',(#11161),#11165); +#11161 = LINE('',#11162,#11163); +#11162 = CARTESIAN_POINT('',(7.443679490547E-002,-3.000323392953E-067)); +#11163 = VECTOR('',#11164,1.); +#11164 = DIRECTION('',(-2.944402941176E-082,1.)); +#11165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11166 = ORIENTED_EDGE('',*,*,#11167,.F.); +#11167 = EDGE_CURVE('',#10900,#11145,#11168,.T.); +#11168 = SURFACE_CURVE('',#11169,(#11173,#11180),.PCURVE_S1.); +#11169 = LINE('',#11170,#11171); +#11170 = CARTESIAN_POINT('',(6.909329470558E-002,-0.537412988595, 0.379766421001)); -#8779 = VECTOR('',#8780,1.); -#8780 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8781 = PCURVE('',#8530,#8782); -#8782 = DEFINITIONAL_REPRESENTATION('',(#8783),#8787); -#8783 = LINE('',#8784,#8785); -#8784 = CARTESIAN_POINT('',(0.160057202922,0.E+000)); -#8785 = VECTOR('',#8786,1.); -#8786 = DIRECTION('',(0.E+000,-1.)); -#8787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8788 = PCURVE('',#8558,#8789); -#8789 = DEFINITIONAL_REPRESENTATION('',(#8790),#8794); -#8790 = LINE('',#8791,#8792); -#8791 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#8792 = VECTOR('',#8793,1.); -#8793 = DIRECTION('',(0.E+000,-1.)); -#8794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8795 = ORIENTED_EDGE('',*,*,#8507,.T.); -#8796 = ORIENTED_EDGE('',*,*,#8728,.T.); -#8797 = ADVANCED_FACE('',(#8798),#8558,.T.); -#8798 = FACE_BOUND('',#8799,.T.); -#8799 = EDGE_LOOP('',(#8800,#8801,#8802,#8823)); -#8800 = ORIENTED_EDGE('',*,*,#8542,.T.); -#8801 = ORIENTED_EDGE('',*,*,#8775,.T.); -#8802 = ORIENTED_EDGE('',*,*,#8803,.T.); -#8803 = EDGE_CURVE('',#8753,#8629,#8804,.T.); -#8804 = SURFACE_CURVE('',#8805,(#8809,#8816),.PCURVE_S1.); -#8805 = LINE('',#8806,#8807); -#8806 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.537412988595, +#11171 = VECTOR('',#11172,1.); +#11172 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11173 = PCURVE('',#10922,#11174); +#11174 = DEFINITIONAL_REPRESENTATION('',(#11175),#11179); +#11175 = LINE('',#11176,#11177); +#11176 = CARTESIAN_POINT('',(0.160057202922,0.E+000)); +#11177 = VECTOR('',#11178,1.); +#11178 = DIRECTION('',(0.E+000,-1.)); +#11179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11180 = PCURVE('',#10950,#11181); +#11181 = DEFINITIONAL_REPRESENTATION('',(#11182),#11186); +#11182 = LINE('',#11183,#11184); +#11183 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11184 = VECTOR('',#11185,1.); +#11185 = DIRECTION('',(0.E+000,-1.)); +#11186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11187 = ORIENTED_EDGE('',*,*,#10899,.T.); +#11188 = ORIENTED_EDGE('',*,*,#11120,.T.); +#11189 = ADVANCED_FACE('',(#11190),#10950,.T.); +#11190 = FACE_BOUND('',#11191,.T.); +#11191 = EDGE_LOOP('',(#11192,#11193,#11194,#11215)); +#11192 = ORIENTED_EDGE('',*,*,#10934,.T.); +#11193 = ORIENTED_EDGE('',*,*,#11167,.T.); +#11194 = ORIENTED_EDGE('',*,*,#11195,.T.); +#11195 = EDGE_CURVE('',#11145,#11021,#11196,.T.); +#11196 = SURFACE_CURVE('',#11197,(#11201,#11208),.PCURVE_S1.); +#11197 = LINE('',#11198,#11199); +#11198 = CARTESIAN_POINT('',(-5.343500199876E-003,-0.537412988595, 0.329766421001)); -#8807 = VECTOR('',#8808,1.); -#8808 = DIRECTION('',(-1.,0.E+000,-6.311124536681E-027)); -#8809 = PCURVE('',#8558,#8810); -#8810 = DEFINITIONAL_REPRESENTATION('',(#8811),#8815); -#8811 = LINE('',#8812,#8813); -#8812 = CARTESIAN_POINT('',(7.443679490546E-002,-5.E-002)); -#8813 = VECTOR('',#8814,1.); -#8814 = DIRECTION('',(1.,-6.311124536681E-027)); -#8815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8816 = PCURVE('',#8667,#8817); -#8817 = DEFINITIONAL_REPRESENTATION('',(#8818),#8822); -#8818 = LINE('',#8819,#8820); -#8819 = CARTESIAN_POINT('',(0.E+000,8.00286014609E-002)); -#8820 = VECTOR('',#8821,1.); -#8821 = DIRECTION('',(-1.,-2.32669603044E-082)); -#8822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8823 = ORIENTED_EDGE('',*,*,#8628,.T.); -#8824 = ADVANCED_FACE('',(#8825),#8667,.F.); -#8825 = FACE_BOUND('',#8826,.T.); -#8826 = EDGE_LOOP('',(#8827,#8828,#8829,#8830)); -#8827 = ORIENTED_EDGE('',*,*,#8752,.F.); -#8828 = ORIENTED_EDGE('',*,*,#8705,.F.); -#8829 = ORIENTED_EDGE('',*,*,#8651,.F.); -#8830 = ORIENTED_EDGE('',*,*,#8803,.F.); -#8831 = MANIFOLD_SOLID_BREP('',#8832); -#8832 = CLOSED_SHELL('',(#8833,#9051,#9127,#9237,#9308,#9357,#9435,#9594 - ,#9669,#9722,#9771,#9824,#9872,#9903)); -#8833 = ADVANCED_FACE('',(#8834),#8849,.T.); -#8834 = FACE_BOUND('',#8835,.T.); -#8835 = EDGE_LOOP('',(#8836,#8898,#8948,#9003)); -#8836 = ORIENTED_EDGE('',*,*,#8837,.F.); -#8837 = EDGE_CURVE('',#8838,#8840,#8842,.T.); -#8838 = VERTEX_POINT('',#8839); -#8839 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, +#11199 = VECTOR('',#11200,1.); +#11200 = DIRECTION('',(-1.,0.E+000,-6.311124536681E-027)); +#11201 = PCURVE('',#10950,#11202); +#11202 = DEFINITIONAL_REPRESENTATION('',(#11203),#11207); +#11203 = LINE('',#11204,#11205); +#11204 = CARTESIAN_POINT('',(7.443679490546E-002,-5.E-002)); +#11205 = VECTOR('',#11206,1.); +#11206 = DIRECTION('',(1.,-6.311124536681E-027)); +#11207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11208 = PCURVE('',#11059,#11209); +#11209 = DEFINITIONAL_REPRESENTATION('',(#11210),#11214); +#11210 = LINE('',#11211,#11212); +#11211 = CARTESIAN_POINT('',(0.E+000,8.00286014609E-002)); +#11212 = VECTOR('',#11213,1.); +#11213 = DIRECTION('',(-1.,-2.32669603044E-082)); +#11214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11215 = ORIENTED_EDGE('',*,*,#11020,.T.); +#11216 = ADVANCED_FACE('',(#11217),#11059,.F.); +#11217 = FACE_BOUND('',#11218,.T.); +#11218 = EDGE_LOOP('',(#11219,#11220,#11221,#11222)); +#11219 = ORIENTED_EDGE('',*,*,#11144,.F.); +#11220 = ORIENTED_EDGE('',*,*,#11097,.F.); +#11221 = ORIENTED_EDGE('',*,*,#11043,.F.); +#11222 = ORIENTED_EDGE('',*,*,#11195,.F.); +#11223 = MANIFOLD_SOLID_BREP('',#11224); +#11224 = CLOSED_SHELL('',(#11225,#11443,#11519,#11629,#11700,#11749, + #11827,#11986,#12061,#12114,#12163,#12216,#12264,#12295)); +#11225 = ADVANCED_FACE('',(#11226),#11241,.T.); +#11226 = FACE_BOUND('',#11227,.T.); +#11227 = EDGE_LOOP('',(#11228,#11290,#11340,#11395)); +#11228 = ORIENTED_EDGE('',*,*,#11229,.F.); +#11229 = EDGE_CURVE('',#11230,#11232,#11234,.T.); +#11230 = VERTEX_POINT('',#11231); +#11231 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 0.329766421001)); -#8840 = VERTEX_POINT('',#8841); -#8841 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, +#11232 = VERTEX_POINT('',#11233); +#11233 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, 0.329766421001)); -#8842 = SURFACE_CURVE('',#8843,(#8848,#8882),.PCURVE_S1.); -#8843 = CIRCLE('',#8844,0.15); -#8844 = AXIS2_PLACEMENT_3D('',#8845,#8846,#8847); -#8845 = CARTESIAN_POINT('',(-5.343500199845E-003,-1.442441590056, +#11234 = SURFACE_CURVE('',#11235,(#11240,#11274),.PCURVE_S1.); +#11235 = CIRCLE('',#11236,0.15); +#11236 = AXIS2_PLACEMENT_3D('',#11237,#11238,#11239); +#11237 = CARTESIAN_POINT('',(-5.343500199845E-003,-1.442441590056, 0.329766421001)); -#8846 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#8847 = DIRECTION('',(1.,-2.314804904035E-042,1.624097681737E-013)); -#8848 = PCURVE('',#8849,#8854); -#8849 = CYLINDRICAL_SURFACE('',#8850,0.15); -#8850 = AXIS2_PLACEMENT_3D('',#8851,#8852,#8853); -#8851 = CARTESIAN_POINT('',(-5.343500199793E-003,-1.442441590056, +#11238 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#11239 = DIRECTION('',(1.,-2.314804904035E-042,1.624097681737E-013)); +#11240 = PCURVE('',#11241,#11246); +#11241 = CYLINDRICAL_SURFACE('',#11242,0.15); +#11242 = AXIS2_PLACEMENT_3D('',#11243,#11244,#11245); +#11243 = CARTESIAN_POINT('',(-5.343500199793E-003,-1.442441590056, 4.766421000566E-003)); -#8852 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#8853 = DIRECTION('',(1.,5.409413345169E-045,1.624097681737E-013)); -#8854 = DEFINITIONAL_REPRESENTATION('',(#8855),#8881); -#8855 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#8856,#8857,#8858,#8859,#8860, - #8861,#8862,#8863,#8864,#8865,#8866,#8867,#8868,#8869,#8870,#8871, - #8872,#8873,#8874,#8875,#8876,#8877,#8878,#8879,#8880), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (0.16744807922,0.295025192636,0.422602306052,0.550179419467, - 0.677756532883,0.805333646299,0.932910759715,1.060487873131, - 1.188064986547,1.315642099963,1.443219213379,1.570796326795, - 1.698373440211,1.825950553627,1.953527667043,2.081104780459, - 2.208681893875,2.336259007291,2.463836120707,2.591413234123, - 2.718990347538,2.846567460954,2.97414457437),.QUASI_UNIFORM_KNOTS.); -#8856 = CARTESIAN_POINT('',(0.16744807922,0.325)); -#8857 = CARTESIAN_POINT('',(0.209973783692,0.325)); -#8858 = CARTESIAN_POINT('',(0.295025192636,0.325)); -#8859 = CARTESIAN_POINT('',(0.422602306052,0.325)); -#8860 = CARTESIAN_POINT('',(0.550179419467,0.325)); -#8861 = CARTESIAN_POINT('',(0.677756532883,0.325)); -#8862 = CARTESIAN_POINT('',(0.805333646299,0.325)); -#8863 = CARTESIAN_POINT('',(0.932910759715,0.325)); -#8864 = CARTESIAN_POINT('',(1.060487873131,0.325)); -#8865 = CARTESIAN_POINT('',(1.188064986547,0.325)); -#8866 = CARTESIAN_POINT('',(1.315642099963,0.325)); -#8867 = CARTESIAN_POINT('',(1.443219213379,0.325)); -#8868 = CARTESIAN_POINT('',(1.570796326795,0.325)); -#8869 = CARTESIAN_POINT('',(1.698373440211,0.325)); -#8870 = CARTESIAN_POINT('',(1.825950553627,0.325)); -#8871 = CARTESIAN_POINT('',(1.953527667043,0.325)); -#8872 = CARTESIAN_POINT('',(2.081104780459,0.325)); -#8873 = CARTESIAN_POINT('',(2.208681893875,0.325)); -#8874 = CARTESIAN_POINT('',(2.336259007291,0.325)); -#8875 = CARTESIAN_POINT('',(2.463836120707,0.325)); -#8876 = CARTESIAN_POINT('',(2.591413234123,0.325)); -#8877 = CARTESIAN_POINT('',(2.718990347538,0.325)); -#8878 = CARTESIAN_POINT('',(2.846567460954,0.325)); -#8879 = CARTESIAN_POINT('',(2.931618869898,0.325)); -#8880 = CARTESIAN_POINT('',(2.97414457437,0.325)); -#8881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8882 = PCURVE('',#8883,#8888); -#8883 = PLANE('',#8884); -#8884 = AXIS2_PLACEMENT_3D('',#8885,#8886,#8887); -#8885 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.329766421001) - ); -#8886 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#8887 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#8888 = DEFINITIONAL_REPRESENTATION('',(#8889),#8897); -#8889 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#8890,#8891,#8892,#8893, -#8894,#8895,#8896),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#8890 = CARTESIAN_POINT('',(0.175,-0.275)); -#8891 = CARTESIAN_POINT('',(0.175,-1.519237886462E-002)); -#8892 = CARTESIAN_POINT('',(0.4,-0.145096189432)); -#8893 = CARTESIAN_POINT('',(0.625,-0.275)); -#8894 = CARTESIAN_POINT('',(0.4,-0.404903810568)); -#8895 = CARTESIAN_POINT('',(0.175,-0.534807621135)); -#8896 = CARTESIAN_POINT('',(0.175,-0.275)); -#8897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8898 = ORIENTED_EDGE('',*,*,#8899,.F.); -#8899 = EDGE_CURVE('',#8900,#8838,#8902,.T.); -#8900 = VERTEX_POINT('',#8901); -#8901 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, +#11244 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#11245 = DIRECTION('',(1.,5.409413345169E-045,1.624097681737E-013)); +#11246 = DEFINITIONAL_REPRESENTATION('',(#11247),#11273); +#11247 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#11248,#11249,#11250,#11251, + #11252,#11253,#11254,#11255,#11256,#11257,#11258,#11259,#11260, + #11261,#11262,#11263,#11264,#11265,#11266,#11267,#11268,#11269, + #11270,#11271,#11272),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(0.16744807922,0.295025192636,0.422602306052 + ,0.550179419467,0.677756532883,0.805333646299,0.932910759715, + 1.060487873131,1.188064986547,1.315642099963,1.443219213379, + 1.570796326795,1.698373440211,1.825950553627,1.953527667043, + 2.081104780459,2.208681893875,2.336259007291,2.463836120707, + 2.591413234123,2.718990347538,2.846567460954,2.97414457437), + .QUASI_UNIFORM_KNOTS.); +#11248 = CARTESIAN_POINT('',(0.16744807922,0.325)); +#11249 = CARTESIAN_POINT('',(0.209973783692,0.325)); +#11250 = CARTESIAN_POINT('',(0.295025192636,0.325)); +#11251 = CARTESIAN_POINT('',(0.422602306052,0.325)); +#11252 = CARTESIAN_POINT('',(0.550179419467,0.325)); +#11253 = CARTESIAN_POINT('',(0.677756532883,0.325)); +#11254 = CARTESIAN_POINT('',(0.805333646299,0.325)); +#11255 = CARTESIAN_POINT('',(0.932910759715,0.325)); +#11256 = CARTESIAN_POINT('',(1.060487873131,0.325)); +#11257 = CARTESIAN_POINT('',(1.188064986547,0.325)); +#11258 = CARTESIAN_POINT('',(1.315642099963,0.325)); +#11259 = CARTESIAN_POINT('',(1.443219213379,0.325)); +#11260 = CARTESIAN_POINT('',(1.570796326795,0.325)); +#11261 = CARTESIAN_POINT('',(1.698373440211,0.325)); +#11262 = CARTESIAN_POINT('',(1.825950553627,0.325)); +#11263 = CARTESIAN_POINT('',(1.953527667043,0.325)); +#11264 = CARTESIAN_POINT('',(2.081104780459,0.325)); +#11265 = CARTESIAN_POINT('',(2.208681893875,0.325)); +#11266 = CARTESIAN_POINT('',(2.336259007291,0.325)); +#11267 = CARTESIAN_POINT('',(2.463836120707,0.325)); +#11268 = CARTESIAN_POINT('',(2.591413234123,0.325)); +#11269 = CARTESIAN_POINT('',(2.718990347538,0.325)); +#11270 = CARTESIAN_POINT('',(2.846567460954,0.325)); +#11271 = CARTESIAN_POINT('',(2.931618869898,0.325)); +#11272 = CARTESIAN_POINT('',(2.97414457437,0.325)); +#11273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11274 = PCURVE('',#11275,#11280); +#11275 = PLANE('',#11276); +#11276 = AXIS2_PLACEMENT_3D('',#11277,#11278,#11279); +#11277 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.329766421001 + )); +#11278 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11279 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#11280 = DEFINITIONAL_REPRESENTATION('',(#11281),#11289); +#11281 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#11282,#11283,#11284,#11285 + ,#11286,#11287,#11288),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#11282 = CARTESIAN_POINT('',(0.175,-0.275)); +#11283 = CARTESIAN_POINT('',(0.175,-1.519237886462E-002)); +#11284 = CARTESIAN_POINT('',(0.4,-0.145096189432)); +#11285 = CARTESIAN_POINT('',(0.625,-0.275)); +#11286 = CARTESIAN_POINT('',(0.4,-0.404903810568)); +#11287 = CARTESIAN_POINT('',(0.175,-0.534807621135)); +#11288 = CARTESIAN_POINT('',(0.175,-0.275)); +#11289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11290 = ORIENTED_EDGE('',*,*,#11291,.F.); +#11291 = EDGE_CURVE('',#11292,#11230,#11294,.T.); +#11292 = VERTEX_POINT('',#11293); +#11293 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 2.976642100055E-002)); -#8902 = SURFACE_CURVE('',#8903,(#8907,#8936),.PCURVE_S1.); -#8903 = LINE('',#8904,#8905); -#8904 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, - 0.329766421001)); -#8905 = VECTOR('',#8906,1.); -#8906 = DIRECTION('',(0.E+000,0.E+000,1.)); -#8907 = PCURVE('',#8849,#8908); -#8908 = DEFINITIONAL_REPRESENTATION('',(#8909),#8935); -#8909 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#8910,#8911,#8912,#8913,#8914, - #8915,#8916,#8917,#8918,#8919,#8920,#8921,#8922,#8923,#8924,#8925, - #8926,#8927,#8928,#8929,#8930,#8931,#8932,#8933,#8934), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (-0.3,-0.286363636364,-0.272727272727,-0.259090909091,-0.245454545455, - -0.231818181818,-0.218181818182,-0.204545454545,-0.190909090909, - -0.177272727273,-0.163636363636,-0.15,-0.136363636364, - -0.122727272727,-0.109090909091,-9.545454545454E-002, - -8.181818181817E-002,-6.818181818181E-002,-5.454545454544E-002, - -4.090909090908E-002,-2.727272727271E-002,-1.363636363635E-002, - 1.804112415016E-014),.UNSPECIFIED.); -#8910 = CARTESIAN_POINT('',(0.16744807922,2.499999999996E-002)); -#8911 = CARTESIAN_POINT('',(0.16744807922,2.954545454541E-002)); -#8912 = CARTESIAN_POINT('',(0.16744807922,3.863636363632E-002)); -#8913 = CARTESIAN_POINT('',(0.16744807922,5.227272727269E-002)); -#8914 = CARTESIAN_POINT('',(0.16744807922,6.590909090905E-002)); -#8915 = CARTESIAN_POINT('',(0.16744807922,7.954545454542E-002)); -#8916 = CARTESIAN_POINT('',(0.16744807922,9.318181818178E-002)); -#8917 = CARTESIAN_POINT('',(0.16744807922,0.106818181818)); -#8918 = CARTESIAN_POINT('',(0.16744807922,0.120454545455)); -#8919 = CARTESIAN_POINT('',(0.16744807922,0.134090909091)); -#8920 = CARTESIAN_POINT('',(0.16744807922,0.147727272727)); -#8921 = CARTESIAN_POINT('',(0.16744807922,0.161363636364)); -#8922 = CARTESIAN_POINT('',(0.16744807922,0.175)); -#8923 = CARTESIAN_POINT('',(0.16744807922,0.188636363636)); -#8924 = CARTESIAN_POINT('',(0.16744807922,0.202272727273)); -#8925 = CARTESIAN_POINT('',(0.16744807922,0.215909090909)); -#8926 = CARTESIAN_POINT('',(0.16744807922,0.229545454545)); -#8927 = CARTESIAN_POINT('',(0.16744807922,0.243181818182)); -#8928 = CARTESIAN_POINT('',(0.16744807922,0.256818181818)); -#8929 = CARTESIAN_POINT('',(0.16744807922,0.270454545455)); -#8930 = CARTESIAN_POINT('',(0.16744807922,0.284090909091)); -#8931 = CARTESIAN_POINT('',(0.16744807922,0.297727272727)); -#8932 = CARTESIAN_POINT('',(0.16744807922,0.311363636364)); -#8933 = CARTESIAN_POINT('',(0.16744807922,0.320454545455)); -#8934 = CARTESIAN_POINT('',(0.16744807922,0.325)); -#8935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8936 = PCURVE('',#8937,#8942); -#8937 = PLANE('',#8938); -#8938 = AXIS2_PLACEMENT_3D('',#8939,#8940,#8941); -#8939 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001) - ); -#8940 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#8941 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#8942 = DEFINITIONAL_REPRESENTATION('',(#8943),#8947); -#8943 = LINE('',#8944,#8945); -#8944 = CARTESIAN_POINT('',(0.177098005422,0.E+000)); -#8945 = VECTOR('',#8946,1.); -#8946 = DIRECTION('',(0.E+000,1.)); -#8947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8948 = ORIENTED_EDGE('',*,*,#8949,.F.); -#8949 = EDGE_CURVE('',#8950,#8900,#8952,.T.); -#8950 = VERTEX_POINT('',#8951); -#8951 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, - 2.976642100054E-002)); -#8952 = SURFACE_CURVE('',#8953,(#8958,#8987),.PCURVE_S1.); -#8953 = CIRCLE('',#8954,0.15); -#8954 = AXIS2_PLACEMENT_3D('',#8955,#8956,#8957); -#8955 = CARTESIAN_POINT('',(-5.343500199797E-003,-1.442441590056, - 2.976642100053E-002)); -#8956 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#8957 = DIRECTION('',(1.,1.445602896647E-015,1.624097681737E-013)); -#8958 = PCURVE('',#8849,#8959); -#8959 = DEFINITIONAL_REPRESENTATION('',(#8960),#8986); -#8960 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#8961,#8962,#8963,#8964,#8965, - #8966,#8967,#8968,#8969,#8970,#8971,#8972,#8973,#8974,#8975,#8976, - #8977,#8978,#8979,#8980,#8981,#8982,#8983,#8984,#8985), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (3.309040732809,3.436617846225,3.564194959641,3.691772073057, - 3.819349186473,3.946926299889,4.074503413305,4.202080526721, - 4.329657640137,4.457234753553,4.584811866969,4.712388980385, - 4.839966093801,4.967543207216,5.095120320632,5.222697434048, - 5.350274547464,5.47785166088,5.605428774296,5.733005887712, - 5.860583001128,5.988160114544,6.11573722796),.QUASI_UNIFORM_KNOTS.); -#8961 = CARTESIAN_POINT('',(2.97414457437,2.499999999996E-002)); -#8962 = CARTESIAN_POINT('',(2.931618869898,2.499999999996E-002)); -#8963 = CARTESIAN_POINT('',(2.846567460954,2.499999999996E-002)); -#8964 = CARTESIAN_POINT('',(2.718990347539,2.499999999996E-002)); -#8965 = CARTESIAN_POINT('',(2.591413234123,2.499999999996E-002)); -#8966 = CARTESIAN_POINT('',(2.463836120707,2.499999999996E-002)); -#8967 = CARTESIAN_POINT('',(2.336259007291,2.499999999996E-002)); -#8968 = CARTESIAN_POINT('',(2.208681893875,2.499999999996E-002)); -#8969 = CARTESIAN_POINT('',(2.081104780459,2.499999999996E-002)); -#8970 = CARTESIAN_POINT('',(1.953527667043,2.499999999996E-002)); -#8971 = CARTESIAN_POINT('',(1.825950553627,2.499999999996E-002)); -#8972 = CARTESIAN_POINT('',(1.698373440211,2.499999999996E-002)); -#8973 = CARTESIAN_POINT('',(1.570796326795,2.499999999996E-002)); -#8974 = CARTESIAN_POINT('',(1.443219213379,2.499999999996E-002)); -#8975 = CARTESIAN_POINT('',(1.315642099963,2.499999999996E-002)); -#8976 = CARTESIAN_POINT('',(1.188064986547,2.499999999996E-002)); -#8977 = CARTESIAN_POINT('',(1.060487873131,2.499999999996E-002)); -#8978 = CARTESIAN_POINT('',(0.932910759715,2.499999999996E-002)); -#8979 = CARTESIAN_POINT('',(0.805333646299,2.499999999996E-002)); -#8980 = CARTESIAN_POINT('',(0.677756532883,2.499999999996E-002)); -#8981 = CARTESIAN_POINT('',(0.550179419467,2.499999999996E-002)); -#8982 = CARTESIAN_POINT('',(0.422602306051,2.499999999996E-002)); -#8983 = CARTESIAN_POINT('',(0.295025192636,2.499999999996E-002)); -#8984 = CARTESIAN_POINT('',(0.209973783692,2.499999999996E-002)); -#8985 = CARTESIAN_POINT('',(0.16744807922,2.499999999996E-002)); -#8986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#8987 = PCURVE('',#8988,#8993); -#8988 = PLANE('',#8989); -#8989 = AXIS2_PLACEMENT_3D('',#8990,#8991,#8992); -#8990 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.292441590056, - 2.976642100057E-002)); -#8991 = DIRECTION('',(0.E+000,0.E+000,1.)); -#8992 = DIRECTION('',(1.,0.E+000,0.E+000)); -#8993 = DEFINITIONAL_REPRESENTATION('',(#8994),#9002); -#8994 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#8995,#8996,#8997,#8998, -#8999,#9000,#9001),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#8995 = CARTESIAN_POINT('',(0.15,-0.15)); -#8996 = CARTESIAN_POINT('',(0.15,-0.409807621135)); -#8997 = CARTESIAN_POINT('',(-7.500000000006E-002,-0.279903810568)); -#8998 = CARTESIAN_POINT('',(-0.3,-0.15)); -#8999 = CARTESIAN_POINT('',(-7.500000000006E-002,-2.009618943225E-002)); -#9000 = CARTESIAN_POINT('',(0.15,0.109807621135)); -#9001 = CARTESIAN_POINT('',(0.15,-0.15)); -#9002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9003 = ORIENTED_EDGE('',*,*,#9004,.F.); -#9004 = EDGE_CURVE('',#8840,#8950,#9005,.T.); -#9005 = SURFACE_CURVE('',#9006,(#9010,#9039),.PCURVE_S1.); -#9006 = LINE('',#9007,#9008); -#9007 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, +#11294 = SURFACE_CURVE('',#11295,(#11299,#11328),.PCURVE_S1.); +#11295 = LINE('',#11296,#11297); +#11296 = CARTESIAN_POINT('',(0.142558494378,-1.417441590056, 0.329766421001)); -#9008 = VECTOR('',#9009,1.); -#9009 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9010 = PCURVE('',#8849,#9011); -#9011 = DEFINITIONAL_REPRESENTATION('',(#9012),#9038); -#9012 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#9013,#9014,#9015,#9016,#9017, - #9018,#9019,#9020,#9021,#9022,#9023,#9024,#9025,#9026,#9027,#9028, - #9029,#9030,#9031,#9032,#9033,#9034,#9035,#9036,#9037), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (-1.804112415016E-014,1.363636363635E-002,2.727272727271E-002, - 4.090909090908E-002,5.454545454545E-002,6.818181818181E-002, - 8.181818181818E-002,9.545454545454E-002,0.109090909091, - 0.122727272727,0.136363636364,0.15,0.163636363636,0.177272727273, - 0.190909090909,0.204545454545,0.218181818182,0.231818181818, - 0.245454545455,0.259090909091,0.272727272727,0.286363636364,0.3), - .UNSPECIFIED.); -#9013 = CARTESIAN_POINT('',(2.97414457437,0.325)); -#9014 = CARTESIAN_POINT('',(2.97414457437,0.320454545455)); -#9015 = CARTESIAN_POINT('',(2.97414457437,0.311363636364)); -#9016 = CARTESIAN_POINT('',(2.97414457437,0.297727272727)); -#9017 = CARTESIAN_POINT('',(2.97414457437,0.284090909091)); -#9018 = CARTESIAN_POINT('',(2.97414457437,0.270454545455)); -#9019 = CARTESIAN_POINT('',(2.97414457437,0.256818181818)); -#9020 = CARTESIAN_POINT('',(2.97414457437,0.243181818182)); -#9021 = CARTESIAN_POINT('',(2.97414457437,0.229545454545)); -#9022 = CARTESIAN_POINT('',(2.97414457437,0.215909090909)); -#9023 = CARTESIAN_POINT('',(2.97414457437,0.202272727273)); -#9024 = CARTESIAN_POINT('',(2.97414457437,0.188636363636)); -#9025 = CARTESIAN_POINT('',(2.97414457437,0.175)); -#9026 = CARTESIAN_POINT('',(2.97414457437,0.161363636364)); -#9027 = CARTESIAN_POINT('',(2.97414457437,0.147727272727)); -#9028 = CARTESIAN_POINT('',(2.97414457437,0.134090909091)); -#9029 = CARTESIAN_POINT('',(2.97414457437,0.120454545455)); -#9030 = CARTESIAN_POINT('',(2.97414457437,0.106818181818)); -#9031 = CARTESIAN_POINT('',(2.97414457437,9.318181818182E-002)); -#9032 = CARTESIAN_POINT('',(2.97414457437,7.954545454546E-002)); -#9033 = CARTESIAN_POINT('',(2.97414457437,6.590909090909E-002)); -#9034 = CARTESIAN_POINT('',(2.97414457437,5.227272727273E-002)); -#9035 = CARTESIAN_POINT('',(2.97414457437,3.863636363636E-002)); -#9036 = CARTESIAN_POINT('',(2.97414457437,2.954545454545E-002)); -#9037 = CARTESIAN_POINT('',(2.97414457437,2.499999999999E-002)); -#9038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9039 = PCURVE('',#9040,#9045); -#9040 = PLANE('',#9041); -#9041 = AXIS2_PLACEMENT_3D('',#9042,#9043,#9044); -#9042 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001) - ); -#9043 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#9044 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#9045 = DEFINITIONAL_REPRESENTATION('',(#9046),#9050); -#9046 = LINE('',#9047,#9048); -#9047 = CARTESIAN_POINT('',(0.472901994578,0.E+000)); -#9048 = VECTOR('',#9049,1.); -#9049 = DIRECTION('',(0.E+000,-1.)); -#9050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9051 = ADVANCED_FACE('',(#9052),#8937,.T.); -#9052 = FACE_BOUND('',#9053,.T.); -#9053 = EDGE_LOOP('',(#9054,#9055,#9078,#9106)); -#9054 = ORIENTED_EDGE('',*,*,#8899,.T.); -#9055 = ORIENTED_EDGE('',*,*,#9056,.F.); -#9056 = EDGE_CURVE('',#9057,#8838,#9059,.T.); -#9057 = VERTEX_POINT('',#9058); -#9058 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001) - ); -#9059 = SURFACE_CURVE('',#9060,(#9064,#9071),.PCURVE_S1.); -#9060 = LINE('',#9061,#9062); -#9061 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001) - ); -#9062 = VECTOR('',#9063,1.); -#9063 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#9064 = PCURVE('',#8937,#9065); -#9065 = DEFINITIONAL_REPRESENTATION('',(#9066),#9070); -#9066 = LINE('',#9067,#9068); -#9067 = CARTESIAN_POINT('',(2.531308496145E-014,0.E+000)); -#9068 = VECTOR('',#9069,1.); -#9069 = DIRECTION('',(1.,0.E+000)); -#9070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#11297 = VECTOR('',#11298,1.); +#11298 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11299 = PCURVE('',#11241,#11300); +#11300 = DEFINITIONAL_REPRESENTATION('',(#11301),#11327); +#11301 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#11302,#11303,#11304,#11305, + #11306,#11307,#11308,#11309,#11310,#11311,#11312,#11313,#11314, + #11315,#11316,#11317,#11318,#11319,#11320,#11321,#11322,#11323, + #11324,#11325,#11326),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(-0.3,-0.286363636364,-0.272727272727, + -0.259090909091,-0.245454545455,-0.231818181818,-0.218181818182, + -0.204545454545,-0.190909090909,-0.177272727273,-0.163636363636, + -0.15,-0.136363636364,-0.122727272727,-0.109090909091, + -9.545454545454E-002,-8.181818181817E-002,-6.818181818181E-002, + -5.454545454544E-002,-4.090909090908E-002,-2.727272727271E-002, + -1.363636363635E-002,1.804112415016E-014),.UNSPECIFIED.); +#11302 = CARTESIAN_POINT('',(0.16744807922,2.499999999996E-002)); +#11303 = CARTESIAN_POINT('',(0.16744807922,2.954545454541E-002)); +#11304 = CARTESIAN_POINT('',(0.16744807922,3.863636363632E-002)); +#11305 = CARTESIAN_POINT('',(0.16744807922,5.227272727269E-002)); +#11306 = CARTESIAN_POINT('',(0.16744807922,6.590909090905E-002)); +#11307 = CARTESIAN_POINT('',(0.16744807922,7.954545454542E-002)); +#11308 = CARTESIAN_POINT('',(0.16744807922,9.318181818178E-002)); +#11309 = CARTESIAN_POINT('',(0.16744807922,0.106818181818)); +#11310 = CARTESIAN_POINT('',(0.16744807922,0.120454545455)); +#11311 = CARTESIAN_POINT('',(0.16744807922,0.134090909091)); +#11312 = CARTESIAN_POINT('',(0.16744807922,0.147727272727)); +#11313 = CARTESIAN_POINT('',(0.16744807922,0.161363636364)); +#11314 = CARTESIAN_POINT('',(0.16744807922,0.175)); +#11315 = CARTESIAN_POINT('',(0.16744807922,0.188636363636)); +#11316 = CARTESIAN_POINT('',(0.16744807922,0.202272727273)); +#11317 = CARTESIAN_POINT('',(0.16744807922,0.215909090909)); +#11318 = CARTESIAN_POINT('',(0.16744807922,0.229545454545)); +#11319 = CARTESIAN_POINT('',(0.16744807922,0.243181818182)); +#11320 = CARTESIAN_POINT('',(0.16744807922,0.256818181818)); +#11321 = CARTESIAN_POINT('',(0.16744807922,0.270454545455)); +#11322 = CARTESIAN_POINT('',(0.16744807922,0.284090909091)); +#11323 = CARTESIAN_POINT('',(0.16744807922,0.297727272727)); +#11324 = CARTESIAN_POINT('',(0.16744807922,0.311363636364)); +#11325 = CARTESIAN_POINT('',(0.16744807922,0.320454545455)); +#11326 = CARTESIAN_POINT('',(0.16744807922,0.325)); +#11327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11328 = PCURVE('',#11329,#11334); +#11329 = PLANE('',#11330); +#11330 = AXIS2_PLACEMENT_3D('',#11331,#11332,#11333); +#11331 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001 + )); +#11332 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11333 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#11334 = DEFINITIONAL_REPRESENTATION('',(#11335),#11339); +#11335 = LINE('',#11336,#11337); +#11336 = CARTESIAN_POINT('',(0.177098005422,0.E+000)); +#11337 = VECTOR('',#11338,1.); +#11338 = DIRECTION('',(0.E+000,1.)); +#11339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#9071 = PCURVE('',#8883,#9072); -#9072 = DEFINITIONAL_REPRESENTATION('',(#9073),#9077); -#9073 = LINE('',#9074,#9075); -#9074 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#9075 = VECTOR('',#9076,1.); -#9076 = DIRECTION('',(1.,0.E+000)); -#9077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#11340 = ORIENTED_EDGE('',*,*,#11341,.F.); +#11341 = EDGE_CURVE('',#11342,#11292,#11344,.T.); +#11342 = VERTEX_POINT('',#11343); +#11343 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, + 2.976642100054E-002)); +#11344 = SURFACE_CURVE('',#11345,(#11350,#11379),.PCURVE_S1.); +#11345 = CIRCLE('',#11346,0.15); +#11346 = AXIS2_PLACEMENT_3D('',#11347,#11348,#11349); +#11347 = CARTESIAN_POINT('',(-5.343500199797E-003,-1.442441590056, + 2.976642100053E-002)); +#11348 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#11349 = DIRECTION('',(1.,1.445602896647E-015,1.624097681737E-013)); +#11350 = PCURVE('',#11241,#11351); +#11351 = DEFINITIONAL_REPRESENTATION('',(#11352),#11378); +#11352 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#11353,#11354,#11355,#11356, + #11357,#11358,#11359,#11360,#11361,#11362,#11363,#11364,#11365, + #11366,#11367,#11368,#11369,#11370,#11371,#11372,#11373,#11374, + #11375,#11376,#11377),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(3.309040732809,3.436617846225, + 3.564194959641,3.691772073057,3.819349186473,3.946926299889, + 4.074503413305,4.202080526721,4.329657640137,4.457234753553, + 4.584811866969,4.712388980385,4.839966093801,4.967543207216, + 5.095120320632,5.222697434048,5.350274547464,5.47785166088, + 5.605428774296,5.733005887712,5.860583001128,5.988160114544, + 6.11573722796),.QUASI_UNIFORM_KNOTS.); +#11353 = CARTESIAN_POINT('',(2.97414457437,2.499999999996E-002)); +#11354 = CARTESIAN_POINT('',(2.931618869898,2.499999999996E-002)); +#11355 = CARTESIAN_POINT('',(2.846567460954,2.499999999996E-002)); +#11356 = CARTESIAN_POINT('',(2.718990347539,2.499999999996E-002)); +#11357 = CARTESIAN_POINT('',(2.591413234123,2.499999999996E-002)); +#11358 = CARTESIAN_POINT('',(2.463836120707,2.499999999996E-002)); +#11359 = CARTESIAN_POINT('',(2.336259007291,2.499999999996E-002)); +#11360 = CARTESIAN_POINT('',(2.208681893875,2.499999999996E-002)); +#11361 = CARTESIAN_POINT('',(2.081104780459,2.499999999996E-002)); +#11362 = CARTESIAN_POINT('',(1.953527667043,2.499999999996E-002)); +#11363 = CARTESIAN_POINT('',(1.825950553627,2.499999999996E-002)); +#11364 = CARTESIAN_POINT('',(1.698373440211,2.499999999996E-002)); +#11365 = CARTESIAN_POINT('',(1.570796326795,2.499999999996E-002)); +#11366 = CARTESIAN_POINT('',(1.443219213379,2.499999999996E-002)); +#11367 = CARTESIAN_POINT('',(1.315642099963,2.499999999996E-002)); +#11368 = CARTESIAN_POINT('',(1.188064986547,2.499999999996E-002)); +#11369 = CARTESIAN_POINT('',(1.060487873131,2.499999999996E-002)); +#11370 = CARTESIAN_POINT('',(0.932910759715,2.499999999996E-002)); +#11371 = CARTESIAN_POINT('',(0.805333646299,2.499999999996E-002)); +#11372 = CARTESIAN_POINT('',(0.677756532883,2.499999999996E-002)); +#11373 = CARTESIAN_POINT('',(0.550179419467,2.499999999996E-002)); +#11374 = CARTESIAN_POINT('',(0.422602306051,2.499999999996E-002)); +#11375 = CARTESIAN_POINT('',(0.295025192636,2.499999999996E-002)); +#11376 = CARTESIAN_POINT('',(0.209973783692,2.499999999996E-002)); +#11377 = CARTESIAN_POINT('',(0.16744807922,2.499999999996E-002)); +#11378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11379 = PCURVE('',#11380,#11385); +#11380 = PLANE('',#11381); +#11381 = AXIS2_PLACEMENT_3D('',#11382,#11383,#11384); +#11382 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.292441590056, + 2.976642100057E-002)); +#11383 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11384 = DIRECTION('',(1.,0.E+000,0.E+000)); +#11385 = DEFINITIONAL_REPRESENTATION('',(#11386),#11394); +#11386 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#11387,#11388,#11389,#11390 + ,#11391,#11392,#11393),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#11387 = CARTESIAN_POINT('',(0.15,-0.15)); +#11388 = CARTESIAN_POINT('',(0.15,-0.409807621135)); +#11389 = CARTESIAN_POINT('',(-7.500000000006E-002,-0.279903810568)); +#11390 = CARTESIAN_POINT('',(-0.3,-0.15)); +#11391 = CARTESIAN_POINT('',(-7.500000000006E-002,-2.009618943225E-002) + ); +#11392 = CARTESIAN_POINT('',(0.15,0.109807621135)); +#11393 = CARTESIAN_POINT('',(0.15,-0.15)); +#11394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11395 = ORIENTED_EDGE('',*,*,#11396,.F.); +#11396 = EDGE_CURVE('',#11232,#11342,#11397,.T.); +#11397 = SURFACE_CURVE('',#11398,(#11402,#11431),.PCURVE_S1.); +#11398 = LINE('',#11399,#11400); +#11399 = CARTESIAN_POINT('',(-0.153245494777,-1.417441590056, + 0.329766421001)); +#11400 = VECTOR('',#11401,1.); +#11401 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11402 = PCURVE('',#11241,#11403); +#11403 = DEFINITIONAL_REPRESENTATION('',(#11404),#11430); +#11404 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#11405,#11406,#11407,#11408, + #11409,#11410,#11411,#11412,#11413,#11414,#11415,#11416,#11417, + #11418,#11419,#11420,#11421,#11422,#11423,#11424,#11425,#11426, + #11427,#11428,#11429),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(-1.804112415016E-014,1.363636363635E-002, + 2.727272727271E-002,4.090909090908E-002,5.454545454545E-002, + 6.818181818181E-002,8.181818181818E-002,9.545454545454E-002, + 0.109090909091,0.122727272727,0.136363636364,0.15,0.163636363636, + 0.177272727273,0.190909090909,0.204545454545,0.218181818182, + 0.231818181818,0.245454545455,0.259090909091,0.272727272727, + 0.286363636364,0.3),.UNSPECIFIED.); +#11405 = CARTESIAN_POINT('',(2.97414457437,0.325)); +#11406 = CARTESIAN_POINT('',(2.97414457437,0.320454545455)); +#11407 = CARTESIAN_POINT('',(2.97414457437,0.311363636364)); +#11408 = CARTESIAN_POINT('',(2.97414457437,0.297727272727)); +#11409 = CARTESIAN_POINT('',(2.97414457437,0.284090909091)); +#11410 = CARTESIAN_POINT('',(2.97414457437,0.270454545455)); +#11411 = CARTESIAN_POINT('',(2.97414457437,0.256818181818)); +#11412 = CARTESIAN_POINT('',(2.97414457437,0.243181818182)); +#11413 = CARTESIAN_POINT('',(2.97414457437,0.229545454545)); +#11414 = CARTESIAN_POINT('',(2.97414457437,0.215909090909)); +#11415 = CARTESIAN_POINT('',(2.97414457437,0.202272727273)); +#11416 = CARTESIAN_POINT('',(2.97414457437,0.188636363636)); +#11417 = CARTESIAN_POINT('',(2.97414457437,0.175)); +#11418 = CARTESIAN_POINT('',(2.97414457437,0.161363636364)); +#11419 = CARTESIAN_POINT('',(2.97414457437,0.147727272727)); +#11420 = CARTESIAN_POINT('',(2.97414457437,0.134090909091)); +#11421 = CARTESIAN_POINT('',(2.97414457437,0.120454545455)); +#11422 = CARTESIAN_POINT('',(2.97414457437,0.106818181818)); +#11423 = CARTESIAN_POINT('',(2.97414457437,9.318181818182E-002)); +#11424 = CARTESIAN_POINT('',(2.97414457437,7.954545454546E-002)); +#11425 = CARTESIAN_POINT('',(2.97414457437,6.590909090909E-002)); +#11426 = CARTESIAN_POINT('',(2.97414457437,5.227272727273E-002)); +#11427 = CARTESIAN_POINT('',(2.97414457437,3.863636363636E-002)); +#11428 = CARTESIAN_POINT('',(2.97414457437,2.954545454545E-002)); +#11429 = CARTESIAN_POINT('',(2.97414457437,2.499999999999E-002)); +#11430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#9078 = ORIENTED_EDGE('',*,*,#9079,.F.); -#9079 = EDGE_CURVE('',#9080,#9057,#9082,.T.); -#9080 = VERTEX_POINT('',#9081); -#9081 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056, - 2.976642100057E-002)); -#9082 = SURFACE_CURVE('',#9083,(#9087,#9094),.PCURVE_S1.); -#9083 = LINE('',#9084,#9085); -#9084 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.354766421001) - ); -#9085 = VECTOR('',#9086,1.); -#9086 = DIRECTION('',(0.E+000,0.E+000,1.)); -#9087 = PCURVE('',#8937,#9088); -#9088 = DEFINITIONAL_REPRESENTATION('',(#9089),#9093); -#9089 = LINE('',#9090,#9091); -#9090 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#9091 = VECTOR('',#9092,1.); -#9092 = DIRECTION('',(0.E+000,1.)); -#9093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9094 = PCURVE('',#9095,#9100); -#9095 = PLANE('',#9096); -#9096 = AXIS2_PLACEMENT_3D('',#9097,#9098,#9099); -#9097 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.354766421001) - ); -#9098 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#9099 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#9100 = DEFINITIONAL_REPRESENTATION('',(#9101),#9105); -#9101 = LINE('',#9102,#9103); -#9102 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#9103 = VECTOR('',#9104,1.); -#9104 = DIRECTION('',(0.E+000,1.)); -#9105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9106 = ORIENTED_EDGE('',*,*,#9107,.F.); -#9107 = EDGE_CURVE('',#8900,#9080,#9108,.T.); -#9108 = SURFACE_CURVE('',#9109,(#9113,#9120),.PCURVE_S1.); -#9109 = LINE('',#9110,#9111); -#9110 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.417441590056, +#11431 = PCURVE('',#11432,#11437); +#11432 = PLANE('',#11433); +#11433 = AXIS2_PLACEMENT_3D('',#11434,#11435,#11436); +#11434 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001 + )); +#11435 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11436 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#11437 = DEFINITIONAL_REPRESENTATION('',(#11438),#11442); +#11438 = LINE('',#11439,#11440); +#11439 = CARTESIAN_POINT('',(0.472901994578,0.E+000)); +#11440 = VECTOR('',#11441,1.); +#11441 = DIRECTION('',(0.E+000,-1.)); +#11442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11443 = ADVANCED_FACE('',(#11444),#11329,.T.); +#11444 = FACE_BOUND('',#11445,.T.); +#11445 = EDGE_LOOP('',(#11446,#11447,#11470,#11498)); +#11446 = ORIENTED_EDGE('',*,*,#11291,.T.); +#11447 = ORIENTED_EDGE('',*,*,#11448,.F.); +#11448 = EDGE_CURVE('',#11449,#11230,#11451,.T.); +#11449 = VERTEX_POINT('',#11450); +#11450 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001 + )); +#11451 = SURFACE_CURVE('',#11452,(#11456,#11463),.PCURVE_S1.); +#11452 = LINE('',#11453,#11454); +#11453 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001 + )); +#11454 = VECTOR('',#11455,1.); +#11455 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#11456 = PCURVE('',#11329,#11457); +#11457 = DEFINITIONAL_REPRESENTATION('',(#11458),#11462); +#11458 = LINE('',#11459,#11460); +#11459 = CARTESIAN_POINT('',(2.531308496145E-014,0.E+000)); +#11460 = VECTOR('',#11461,1.); +#11461 = DIRECTION('',(1.,0.E+000)); +#11462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11463 = PCURVE('',#11275,#11464); +#11464 = DEFINITIONAL_REPRESENTATION('',(#11465),#11469); +#11465 = LINE('',#11466,#11467); +#11466 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#11467 = VECTOR('',#11468,1.); +#11468 = DIRECTION('',(1.,0.E+000)); +#11469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11470 = ORIENTED_EDGE('',*,*,#11471,.F.); +#11471 = EDGE_CURVE('',#11472,#11449,#11474,.T.); +#11472 = VERTEX_POINT('',#11473); +#11473 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056, 2.976642100057E-002)); -#9111 = VECTOR('',#9112,1.); -#9112 = DIRECTION('',(1.,0.E+000,0.E+000)); -#9113 = PCURVE('',#8937,#9114); -#9114 = DEFINITIONAL_REPRESENTATION('',(#9115),#9119); -#9115 = LINE('',#9116,#9117); -#9116 = CARTESIAN_POINT('',(0.325,-0.3)); -#9117 = VECTOR('',#9118,1.); -#9118 = DIRECTION('',(-1.,0.E+000)); -#9119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9120 = PCURVE('',#8988,#9121); -#9121 = DEFINITIONAL_REPRESENTATION('',(#9122),#9126); -#9122 = LINE('',#9123,#9124); -#9123 = CARTESIAN_POINT('',(0.E+000,-0.125)); -#9124 = VECTOR('',#9125,1.); -#9125 = DIRECTION('',(1.,0.E+000)); -#9126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9127 = ADVANCED_FACE('',(#9128),#9142,.T.); -#9128 = FACE_BOUND('',#9129,.T.); -#9129 = EDGE_LOOP('',(#9130,#9160,#9188,#9216)); -#9130 = ORIENTED_EDGE('',*,*,#9131,.F.); -#9131 = EDGE_CURVE('',#9132,#9134,#9136,.T.); -#9132 = VERTEX_POINT('',#9133); -#9133 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056,0.329766421001 +#11474 = SURFACE_CURVE('',#11475,(#11479,#11486),.PCURVE_S1.); +#11475 = LINE('',#11476,#11477); +#11476 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.354766421001 )); -#9134 = VERTEX_POINT('',#9135); -#9135 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.329766421001) - ); -#9136 = SURFACE_CURVE('',#9137,(#9141,#9153),.PCURVE_S1.); -#9137 = LINE('',#9138,#9139); -#9138 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.329766421001) - ); -#9139 = VECTOR('',#9140,1.); -#9140 = DIRECTION('',(1.,0.E+000,0.E+000)); -#9141 = PCURVE('',#9142,#9147); -#9142 = PLANE('',#9143); -#9143 = AXIS2_PLACEMENT_3D('',#9144,#9145,#9146); -#9144 = CARTESIAN_POINT('',(-5.343500199815E-003,-1.217441590056, - 0.342266421001)); -#9145 = DIRECTION('',(-1.011968286941E-013,1.,1.376209188377E-049)); -#9146 = DIRECTION('',(-1.,-1.011968286941E-013,1.05105713494E-078)); -#9147 = DEFINITIONAL_REPRESENTATION('',(#9148),#9152); -#9148 = LINE('',#9149,#9150); -#9149 = CARTESIAN_POINT('',(-0.325,-1.25E-002)); -#9150 = VECTOR('',#9151,1.); -#9151 = DIRECTION('',(-1.,1.392680054835E-062)); -#9152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9153 = PCURVE('',#8883,#9154); -#9154 = DEFINITIONAL_REPRESENTATION('',(#9155),#9159); -#9155 = LINE('',#9156,#9157); -#9156 = CARTESIAN_POINT('',(0.E+000,-5.000000000008E-002)); -#9157 = VECTOR('',#9158,1.); -#9158 = DIRECTION('',(-1.,0.E+000)); -#9159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9160 = ORIENTED_EDGE('',*,*,#9161,.F.); -#9161 = EDGE_CURVE('',#9162,#9132,#9164,.T.); -#9162 = VERTEX_POINT('',#9163); -#9163 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056,0.354766421001 +#11477 = VECTOR('',#11478,1.); +#11478 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11479 = PCURVE('',#11329,#11480); +#11480 = DEFINITIONAL_REPRESENTATION('',(#11481),#11485); +#11481 = LINE('',#11482,#11483); +#11482 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#11483 = VECTOR('',#11484,1.); +#11484 = DIRECTION('',(0.E+000,1.)); +#11485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11486 = PCURVE('',#11487,#11492); +#11487 = PLANE('',#11488); +#11488 = AXIS2_PLACEMENT_3D('',#11489,#11490,#11491); +#11489 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.354766421001 )); -#9164 = SURFACE_CURVE('',#9165,(#9169,#9176),.PCURVE_S1.); -#9165 = LINE('',#9166,#9167); -#9166 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056,0.329766421001 +#11490 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11491 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11492 = DEFINITIONAL_REPRESENTATION('',(#11493),#11497); +#11493 = LINE('',#11494,#11495); +#11494 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#11495 = VECTOR('',#11496,1.); +#11496 = DIRECTION('',(0.E+000,1.)); +#11497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11498 = ORIENTED_EDGE('',*,*,#11499,.F.); +#11499 = EDGE_CURVE('',#11292,#11472,#11500,.T.); +#11500 = SURFACE_CURVE('',#11501,(#11505,#11512),.PCURVE_S1.); +#11501 = LINE('',#11502,#11503); +#11502 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.417441590056, + 2.976642100057E-002)); +#11503 = VECTOR('',#11504,1.); +#11504 = DIRECTION('',(1.,0.E+000,0.E+000)); +#11505 = PCURVE('',#11329,#11506); +#11506 = DEFINITIONAL_REPRESENTATION('',(#11507),#11511); +#11507 = LINE('',#11508,#11509); +#11508 = CARTESIAN_POINT('',(0.325,-0.3)); +#11509 = VECTOR('',#11510,1.); +#11510 = DIRECTION('',(-1.,0.E+000)); +#11511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11512 = PCURVE('',#11380,#11513); +#11513 = DEFINITIONAL_REPRESENTATION('',(#11514),#11518); +#11514 = LINE('',#11515,#11516); +#11515 = CARTESIAN_POINT('',(0.E+000,-0.125)); +#11516 = VECTOR('',#11517,1.); +#11517 = DIRECTION('',(1.,0.E+000)); +#11518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11519 = ADVANCED_FACE('',(#11520),#11534,.T.); +#11520 = FACE_BOUND('',#11521,.T.); +#11521 = EDGE_LOOP('',(#11522,#11552,#11580,#11608)); +#11522 = ORIENTED_EDGE('',*,*,#11523,.F.); +#11523 = EDGE_CURVE('',#11524,#11526,#11528,.T.); +#11524 = VERTEX_POINT('',#11525); +#11525 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056, + 0.329766421001)); +#11526 = VERTEX_POINT('',#11527); +#11527 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.329766421001 )); -#9167 = VECTOR('',#9168,1.); -#9168 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9169 = PCURVE('',#9142,#9170); -#9170 = DEFINITIONAL_REPRESENTATION('',(#9171),#9175); -#9171 = LINE('',#9172,#9173); -#9172 = CARTESIAN_POINT('',(0.325,-1.25E-002)); -#9173 = VECTOR('',#9174,1.); -#9174 = DIRECTION('',(0.E+000,-1.)); -#9175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9176 = PCURVE('',#9177,#9182); -#9177 = PLANE('',#9178); -#9178 = AXIS2_PLACEMENT_3D('',#9179,#9180,#9181); -#9179 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056,0.329766421001 +#11528 = SURFACE_CURVE('',#11529,(#11533,#11545),.PCURVE_S1.); +#11529 = LINE('',#11530,#11531); +#11530 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.329766421001 )); -#9180 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#9181 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9182 = DEFINITIONAL_REPRESENTATION('',(#9183),#9187); -#9183 = LINE('',#9184,#9185); -#9184 = CARTESIAN_POINT('',(5.000000000001E-002,0.E+000)); -#9185 = VECTOR('',#9186,1.); -#9186 = DIRECTION('',(0.E+000,-1.)); -#9187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9188 = ORIENTED_EDGE('',*,*,#9189,.F.); -#9189 = EDGE_CURVE('',#9190,#9162,#9192,.T.); -#9190 = VERTEX_POINT('',#9191); -#9191 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.354766421001) - ); -#9192 = SURFACE_CURVE('',#9193,(#9197,#9204),.PCURVE_S1.); -#9193 = LINE('',#9194,#9195); -#9194 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056,0.354766421001 +#11531 = VECTOR('',#11532,1.); +#11532 = DIRECTION('',(1.,0.E+000,0.E+000)); +#11533 = PCURVE('',#11534,#11539); +#11534 = PLANE('',#11535); +#11535 = AXIS2_PLACEMENT_3D('',#11536,#11537,#11538); +#11536 = CARTESIAN_POINT('',(-5.343500199815E-003,-1.217441590056, + 0.342266421001)); +#11537 = DIRECTION('',(-1.011968286941E-013,1.,1.376209188377E-049)); +#11538 = DIRECTION('',(-1.,-1.011968286941E-013,1.05105713494E-078)); +#11539 = DEFINITIONAL_REPRESENTATION('',(#11540),#11544); +#11540 = LINE('',#11541,#11542); +#11541 = CARTESIAN_POINT('',(-0.325,-1.25E-002)); +#11542 = VECTOR('',#11543,1.); +#11543 = DIRECTION('',(-1.,1.392680054835E-062)); +#11544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11545 = PCURVE('',#11275,#11546); +#11546 = DEFINITIONAL_REPRESENTATION('',(#11547),#11551); +#11547 = LINE('',#11548,#11549); +#11548 = CARTESIAN_POINT('',(0.E+000,-5.000000000008E-002)); +#11549 = VECTOR('',#11550,1.); +#11550 = DIRECTION('',(-1.,0.E+000)); +#11551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11552 = ORIENTED_EDGE('',*,*,#11553,.F.); +#11553 = EDGE_CURVE('',#11554,#11524,#11556,.T.); +#11554 = VERTEX_POINT('',#11555); +#11555 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056, + 0.354766421001)); +#11556 = SURFACE_CURVE('',#11557,(#11561,#11568),.PCURVE_S1.); +#11557 = LINE('',#11558,#11559); +#11558 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056, + 0.329766421001)); +#11559 = VECTOR('',#11560,1.); +#11560 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11561 = PCURVE('',#11534,#11562); +#11562 = DEFINITIONAL_REPRESENTATION('',(#11563),#11567); +#11563 = LINE('',#11564,#11565); +#11564 = CARTESIAN_POINT('',(0.325,-1.25E-002)); +#11565 = VECTOR('',#11566,1.); +#11566 = DIRECTION('',(0.E+000,-1.)); +#11567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11568 = PCURVE('',#11569,#11574); +#11569 = PLANE('',#11570); +#11570 = AXIS2_PLACEMENT_3D('',#11571,#11572,#11573); +#11571 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, + 0.329766421001)); +#11572 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#11573 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11574 = DEFINITIONAL_REPRESENTATION('',(#11575),#11579); +#11575 = LINE('',#11576,#11577); +#11576 = CARTESIAN_POINT('',(5.000000000001E-002,0.E+000)); +#11577 = VECTOR('',#11578,1.); +#11578 = DIRECTION('',(0.E+000,-1.)); +#11579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11580 = ORIENTED_EDGE('',*,*,#11581,.F.); +#11581 = EDGE_CURVE('',#11582,#11554,#11584,.T.); +#11582 = VERTEX_POINT('',#11583); +#11583 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.354766421001 )); -#9195 = VECTOR('',#9196,1.); -#9196 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#9197 = PCURVE('',#9142,#9198); -#9198 = DEFINITIONAL_REPRESENTATION('',(#9199),#9203); -#9199 = LINE('',#9200,#9201); -#9200 = CARTESIAN_POINT('',(0.325,1.25E-002)); -#9201 = VECTOR('',#9202,1.); -#9202 = DIRECTION('',(1.,-1.392680054835E-062)); -#9203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9204 = PCURVE('',#9205,#9210); -#9205 = PLANE('',#9206); -#9206 = AXIS2_PLACEMENT_3D('',#9207,#9208,#9209); -#9207 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056,0.354766421001 +#11584 = SURFACE_CURVE('',#11585,(#11589,#11596),.PCURVE_S1.); +#11585 = LINE('',#11586,#11587); +#11586 = CARTESIAN_POINT('',(-0.3303435002,-1.217441590056, + 0.354766421001)); +#11587 = VECTOR('',#11588,1.); +#11588 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#11589 = PCURVE('',#11534,#11590); +#11590 = DEFINITIONAL_REPRESENTATION('',(#11591),#11595); +#11591 = LINE('',#11592,#11593); +#11592 = CARTESIAN_POINT('',(0.325,1.25E-002)); +#11593 = VECTOR('',#11594,1.); +#11594 = DIRECTION('',(1.,-1.392680054835E-062)); +#11595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11596 = PCURVE('',#11597,#11602); +#11597 = PLANE('',#11598); +#11598 = AXIS2_PLACEMENT_3D('',#11599,#11600,#11601); +#11599 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, + 0.354766421001)); +#11600 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11601 = DIRECTION('',(1.,0.E+000,0.E+000)); +#11602 = DEFINITIONAL_REPRESENTATION('',(#11603),#11607); +#11603 = LINE('',#11604,#11605); +#11604 = CARTESIAN_POINT('',(0.E+000,-4.999999999995E-002)); +#11605 = VECTOR('',#11606,1.); +#11606 = DIRECTION('',(-1.,0.E+000)); +#11607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11608 = ORIENTED_EDGE('',*,*,#11609,.F.); +#11609 = EDGE_CURVE('',#11526,#11582,#11610,.T.); +#11610 = SURFACE_CURVE('',#11611,(#11615,#11622),.PCURVE_S1.); +#11611 = LINE('',#11612,#11613); +#11612 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.354766421001 )); -#9208 = DIRECTION('',(0.E+000,0.E+000,1.)); -#9209 = DIRECTION('',(1.,0.E+000,0.E+000)); -#9210 = DEFINITIONAL_REPRESENTATION('',(#9211),#9215); -#9211 = LINE('',#9212,#9213); -#9212 = CARTESIAN_POINT('',(0.E+000,-4.999999999995E-002)); -#9213 = VECTOR('',#9214,1.); -#9214 = DIRECTION('',(-1.,0.E+000)); -#9215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9216 = ORIENTED_EDGE('',*,*,#9217,.F.); -#9217 = EDGE_CURVE('',#9134,#9190,#9218,.T.); -#9218 = SURFACE_CURVE('',#9219,(#9223,#9230),.PCURVE_S1.); -#9219 = LINE('',#9220,#9221); -#9220 = CARTESIAN_POINT('',(0.3196564998,-1.217441590056,0.354766421001) - ); -#9221 = VECTOR('',#9222,1.); -#9222 = DIRECTION('',(0.E+000,0.E+000,1.)); -#9223 = PCURVE('',#9142,#9224); -#9224 = DEFINITIONAL_REPRESENTATION('',(#9225),#9229); -#9225 = LINE('',#9226,#9227); -#9226 = CARTESIAN_POINT('',(-0.325,1.25E-002)); -#9227 = VECTOR('',#9228,1.); -#9228 = DIRECTION('',(0.E+000,1.)); -#9229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9230 = PCURVE('',#9095,#9231); -#9231 = DEFINITIONAL_REPRESENTATION('',(#9232),#9236); -#9232 = LINE('',#9233,#9234); -#9233 = CARTESIAN_POINT('',(-5.000000000001E-002,0.E+000)); -#9234 = VECTOR('',#9235,1.); -#9235 = DIRECTION('',(0.E+000,1.)); -#9236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9237 = ADVANCED_FACE('',(#9238),#8883,.T.); -#9238 = FACE_BOUND('',#9239,.T.); -#9239 = EDGE_LOOP('',(#9240,#9241,#9242,#9265,#9286,#9287)); -#9240 = ORIENTED_EDGE('',*,*,#9056,.T.); -#9241 = ORIENTED_EDGE('',*,*,#8837,.T.); -#9242 = ORIENTED_EDGE('',*,*,#9243,.F.); -#9243 = EDGE_CURVE('',#9244,#8840,#9246,.T.); -#9244 = VERTEX_POINT('',#9245); -#9245 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056,0.329766421001 +#11613 = VECTOR('',#11614,1.); +#11614 = DIRECTION('',(0.E+000,0.E+000,1.)); +#11615 = PCURVE('',#11534,#11616); +#11616 = DEFINITIONAL_REPRESENTATION('',(#11617),#11621); +#11617 = LINE('',#11618,#11619); +#11618 = CARTESIAN_POINT('',(-0.325,1.25E-002)); +#11619 = VECTOR('',#11620,1.); +#11620 = DIRECTION('',(0.E+000,1.)); +#11621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11622 = PCURVE('',#11487,#11623); +#11623 = DEFINITIONAL_REPRESENTATION('',(#11624),#11628); +#11624 = LINE('',#11625,#11626); +#11625 = CARTESIAN_POINT('',(-5.000000000001E-002,0.E+000)); +#11626 = VECTOR('',#11627,1.); +#11627 = DIRECTION('',(0.E+000,1.)); +#11628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11629 = ADVANCED_FACE('',(#11630),#11275,.T.); +#11630 = FACE_BOUND('',#11631,.T.); +#11631 = EDGE_LOOP('',(#11632,#11633,#11634,#11657,#11678,#11679)); +#11632 = ORIENTED_EDGE('',*,*,#11448,.T.); +#11633 = ORIENTED_EDGE('',*,*,#11229,.T.); +#11634 = ORIENTED_EDGE('',*,*,#11635,.F.); +#11635 = EDGE_CURVE('',#11636,#11232,#11638,.T.); +#11636 = VERTEX_POINT('',#11637); +#11637 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056, + 0.329766421001)); +#11638 = SURFACE_CURVE('',#11639,(#11643,#11650),.PCURVE_S1.); +#11639 = LINE('',#11640,#11641); +#11640 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001 )); -#9246 = SURFACE_CURVE('',#9247,(#9251,#9258),.PCURVE_S1.); -#9247 = LINE('',#9248,#9249); -#9248 = CARTESIAN_POINT('',(0.3196564998,-1.417441590056,0.329766421001) - ); -#9249 = VECTOR('',#9250,1.); -#9250 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#9251 = PCURVE('',#8883,#9252); -#9252 = DEFINITIONAL_REPRESENTATION('',(#9253),#9257); -#9253 = LINE('',#9254,#9255); -#9254 = CARTESIAN_POINT('',(-2.531308496145E-014,-0.25)); -#9255 = VECTOR('',#9256,1.); -#9256 = DIRECTION('',(-1.,1.011968286946E-013)); -#9257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9258 = PCURVE('',#9040,#9259); -#9259 = DEFINITIONAL_REPRESENTATION('',(#9260),#9264); -#9260 = LINE('',#9261,#9262); -#9261 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#9262 = VECTOR('',#9263,1.); -#9263 = DIRECTION('',(-1.,0.E+000)); -#9264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9265 = ORIENTED_EDGE('',*,*,#9266,.F.); -#9266 = EDGE_CURVE('',#9132,#9244,#9267,.T.); -#9267 = SURFACE_CURVE('',#9268,(#9272,#9279),.PCURVE_S1.); -#9268 = LINE('',#9269,#9270); -#9269 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056,0.329766421001 +#11641 = VECTOR('',#11642,1.); +#11642 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11643 = PCURVE('',#11275,#11644); +#11644 = DEFINITIONAL_REPRESENTATION('',(#11645),#11649); +#11645 = LINE('',#11646,#11647); +#11646 = CARTESIAN_POINT('',(-2.531308496145E-014,-0.25)); +#11647 = VECTOR('',#11648,1.); +#11648 = DIRECTION('',(-1.,1.011968286946E-013)); +#11649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11650 = PCURVE('',#11432,#11651); +#11651 = DEFINITIONAL_REPRESENTATION('',(#11652),#11656); +#11652 = LINE('',#11653,#11654); +#11653 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11654 = VECTOR('',#11655,1.); +#11655 = DIRECTION('',(-1.,0.E+000)); +#11656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11657 = ORIENTED_EDGE('',*,*,#11658,.F.); +#11658 = EDGE_CURVE('',#11524,#11636,#11659,.T.); +#11659 = SURFACE_CURVE('',#11660,(#11664,#11671),.PCURVE_S1.); +#11660 = LINE('',#11661,#11662); +#11661 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, + 0.329766421001)); +#11662 = VECTOR('',#11663,1.); +#11663 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11664 = PCURVE('',#11275,#11665); +#11665 = DEFINITIONAL_REPRESENTATION('',(#11666),#11670); +#11666 = LINE('',#11667,#11668); +#11667 = CARTESIAN_POINT('',(0.65,-6.572520305781E-014)); +#11668 = VECTOR('',#11669,1.); +#11669 = DIRECTION('',(-1.011968286946E-013,-1.)); +#11670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11671 = PCURVE('',#11569,#11672); +#11672 = DEFINITIONAL_REPRESENTATION('',(#11673),#11677); +#11673 = LINE('',#11674,#11675); +#11674 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11675 = VECTOR('',#11676,1.); +#11676 = DIRECTION('',(1.,0.E+000)); +#11677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11678 = ORIENTED_EDGE('',*,*,#11523,.T.); +#11679 = ORIENTED_EDGE('',*,*,#11680,.F.); +#11680 = EDGE_CURVE('',#11449,#11526,#11681,.T.); +#11681 = SURFACE_CURVE('',#11682,(#11686,#11693),.PCURVE_S1.); +#11682 = LINE('',#11683,#11684); +#11683 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.329766421001 )); -#9270 = VECTOR('',#9271,1.); -#9271 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9272 = PCURVE('',#8883,#9273); -#9273 = DEFINITIONAL_REPRESENTATION('',(#9274),#9278); -#9274 = LINE('',#9275,#9276); -#9275 = CARTESIAN_POINT('',(0.65,-6.572520305781E-014)); -#9276 = VECTOR('',#9277,1.); -#9277 = DIRECTION('',(-1.011968286946E-013,-1.)); -#9278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9279 = PCURVE('',#9177,#9280); -#9280 = DEFINITIONAL_REPRESENTATION('',(#9281),#9285); -#9281 = LINE('',#9282,#9283); -#9282 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#9283 = VECTOR('',#9284,1.); -#9284 = DIRECTION('',(1.,0.E+000)); -#9285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9286 = ORIENTED_EDGE('',*,*,#9131,.T.); -#9287 = ORIENTED_EDGE('',*,*,#9288,.F.); -#9288 = EDGE_CURVE('',#9057,#9134,#9289,.T.); -#9289 = SURFACE_CURVE('',#9290,(#9294,#9301),.PCURVE_S1.); -#9290 = LINE('',#9291,#9292); -#9291 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.329766421001) - ); -#9292 = VECTOR('',#9293,1.); -#9293 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#9294 = PCURVE('',#8883,#9295); -#9295 = DEFINITIONAL_REPRESENTATION('',(#9296),#9300); -#9296 = LINE('',#9297,#9298); -#9297 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#9298 = VECTOR('',#9299,1.); -#9299 = DIRECTION('',(1.011968286946E-013,1.)); -#9300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9301 = PCURVE('',#9095,#9302); -#9302 = DEFINITIONAL_REPRESENTATION('',(#9303),#9307); -#9303 = LINE('',#9304,#9305); -#9304 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#9305 = VECTOR('',#9306,1.); -#9306 = DIRECTION('',(1.,0.E+000)); -#9307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9308 = ADVANCED_FACE('',(#9309),#9040,.T.); -#9309 = FACE_BOUND('',#9310,.T.); -#9310 = EDGE_LOOP('',(#9311,#9312,#9335,#9356)); -#9311 = ORIENTED_EDGE('',*,*,#9004,.T.); -#9312 = ORIENTED_EDGE('',*,*,#9313,.F.); -#9313 = EDGE_CURVE('',#9314,#8950,#9316,.T.); -#9314 = VERTEX_POINT('',#9315); -#9315 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056, +#11684 = VECTOR('',#11685,1.); +#11685 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11686 = PCURVE('',#11275,#11687); +#11687 = DEFINITIONAL_REPRESENTATION('',(#11688),#11692); +#11688 = LINE('',#11689,#11690); +#11689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11690 = VECTOR('',#11691,1.); +#11691 = DIRECTION('',(1.011968286946E-013,1.)); +#11692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11693 = PCURVE('',#11487,#11694); +#11694 = DEFINITIONAL_REPRESENTATION('',(#11695),#11699); +#11695 = LINE('',#11696,#11697); +#11696 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#11697 = VECTOR('',#11698,1.); +#11698 = DIRECTION('',(1.,0.E+000)); +#11699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11700 = ADVANCED_FACE('',(#11701),#11432,.T.); +#11701 = FACE_BOUND('',#11702,.T.); +#11702 = EDGE_LOOP('',(#11703,#11704,#11727,#11748)); +#11703 = ORIENTED_EDGE('',*,*,#11396,.T.); +#11704 = ORIENTED_EDGE('',*,*,#11705,.F.); +#11705 = EDGE_CURVE('',#11706,#11342,#11708,.T.); +#11706 = VERTEX_POINT('',#11707); +#11707 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056, 2.976642100057E-002)); -#9316 = SURFACE_CURVE('',#9317,(#9321,#9328),.PCURVE_S1.); -#9317 = LINE('',#9318,#9319); -#9318 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.417441590056, +#11708 = SURFACE_CURVE('',#11709,(#11713,#11720),.PCURVE_S1.); +#11709 = LINE('',#11710,#11711); +#11710 = CARTESIAN_POINT('',(-5.343500199751E-003,-1.417441590056, 2.976642100057E-002)); -#9319 = VECTOR('',#9320,1.); -#9320 = DIRECTION('',(1.,0.E+000,0.E+000)); -#9321 = PCURVE('',#9040,#9322); -#9322 = DEFINITIONAL_REPRESENTATION('',(#9323),#9327); -#9323 = LINE('',#9324,#9325); -#9324 = CARTESIAN_POINT('',(0.325,-0.3)); -#9325 = VECTOR('',#9326,1.); -#9326 = DIRECTION('',(-1.,0.E+000)); -#9327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9328 = PCURVE('',#8988,#9329); -#9329 = DEFINITIONAL_REPRESENTATION('',(#9330),#9334); -#9330 = LINE('',#9331,#9332); -#9331 = CARTESIAN_POINT('',(0.E+000,-0.125)); -#9332 = VECTOR('',#9333,1.); -#9333 = DIRECTION('',(1.,0.E+000)); -#9334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9335 = ORIENTED_EDGE('',*,*,#9336,.F.); -#9336 = EDGE_CURVE('',#9244,#9314,#9337,.T.); -#9337 = SURFACE_CURVE('',#9338,(#9342,#9349),.PCURVE_S1.); -#9338 = LINE('',#9339,#9340); -#9339 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056,0.329766421001 - )); -#9340 = VECTOR('',#9341,1.); -#9341 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9342 = PCURVE('',#9040,#9343); -#9343 = DEFINITIONAL_REPRESENTATION('',(#9344),#9348); -#9344 = LINE('',#9345,#9346); -#9345 = CARTESIAN_POINT('',(0.65,0.E+000)); -#9346 = VECTOR('',#9347,1.); -#9347 = DIRECTION('',(0.E+000,-1.)); -#9348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9349 = PCURVE('',#9177,#9350); -#9350 = DEFINITIONAL_REPRESENTATION('',(#9351),#9355); -#9351 = LINE('',#9352,#9353); -#9352 = CARTESIAN_POINT('',(0.25,0.E+000)); -#9353 = VECTOR('',#9354,1.); -#9354 = DIRECTION('',(0.E+000,-1.)); -#9355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9356 = ORIENTED_EDGE('',*,*,#9243,.T.); -#9357 = ADVANCED_FACE('',(#9358),#8988,.T.); -#9358 = FACE_BOUND('',#9359,.T.); -#9359 = EDGE_LOOP('',(#9360,#9383,#9411,#9432,#9433,#9434)); -#9360 = ORIENTED_EDGE('',*,*,#9361,.F.); -#9361 = EDGE_CURVE('',#9362,#9080,#9364,.T.); -#9362 = VERTEX_POINT('',#9363); -#9363 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, +#11711 = VECTOR('',#11712,1.); +#11712 = DIRECTION('',(1.,0.E+000,0.E+000)); +#11713 = PCURVE('',#11432,#11714); +#11714 = DEFINITIONAL_REPRESENTATION('',(#11715),#11719); +#11715 = LINE('',#11716,#11717); +#11716 = CARTESIAN_POINT('',(0.325,-0.3)); +#11717 = VECTOR('',#11718,1.); +#11718 = DIRECTION('',(-1.,0.E+000)); +#11719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11720 = PCURVE('',#11380,#11721); +#11721 = DEFINITIONAL_REPRESENTATION('',(#11722),#11726); +#11722 = LINE('',#11723,#11724); +#11723 = CARTESIAN_POINT('',(0.E+000,-0.125)); +#11724 = VECTOR('',#11725,1.); +#11725 = DIRECTION('',(1.,0.E+000)); +#11726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11727 = ORIENTED_EDGE('',*,*,#11728,.F.); +#11728 = EDGE_CURVE('',#11636,#11706,#11729,.T.); +#11729 = SURFACE_CURVE('',#11730,(#11734,#11741),.PCURVE_S1.); +#11730 = LINE('',#11731,#11732); +#11731 = CARTESIAN_POINT('',(-0.3303435002,-1.417441590056, + 0.329766421001)); +#11732 = VECTOR('',#11733,1.); +#11733 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#11734 = PCURVE('',#11432,#11735); +#11735 = DEFINITIONAL_REPRESENTATION('',(#11736),#11740); +#11736 = LINE('',#11737,#11738); +#11737 = CARTESIAN_POINT('',(0.65,0.E+000)); +#11738 = VECTOR('',#11739,1.); +#11739 = DIRECTION('',(0.E+000,-1.)); +#11740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11741 = PCURVE('',#11569,#11742); +#11742 = DEFINITIONAL_REPRESENTATION('',(#11743),#11747); +#11743 = LINE('',#11744,#11745); +#11744 = CARTESIAN_POINT('',(0.25,0.E+000)); +#11745 = VECTOR('',#11746,1.); +#11746 = DIRECTION('',(0.E+000,-1.)); +#11747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11748 = ORIENTED_EDGE('',*,*,#11635,.T.); +#11749 = ADVANCED_FACE('',(#11750),#11380,.T.); +#11750 = FACE_BOUND('',#11751,.T.); +#11751 = EDGE_LOOP('',(#11752,#11775,#11803,#11824,#11825,#11826)); +#11752 = ORIENTED_EDGE('',*,*,#11753,.F.); +#11753 = EDGE_CURVE('',#11754,#11472,#11756,.T.); +#11754 = VERTEX_POINT('',#11755); +#11755 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, 2.976642100057E-002)); -#9364 = SURFACE_CURVE('',#9365,(#9369,#9376),.PCURVE_S1.); -#9365 = LINE('',#9366,#9367); -#9366 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, +#11756 = SURFACE_CURVE('',#11757,(#11761,#11768),.PCURVE_S1.); +#11757 = LINE('',#11758,#11759); +#11758 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, 2.976642100057E-002)); -#9367 = VECTOR('',#9368,1.); -#9368 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9369 = PCURVE('',#8988,#9370); -#9370 = DEFINITIONAL_REPRESENTATION('',(#9371),#9375); -#9371 = LINE('',#9372,#9373); -#9372 = CARTESIAN_POINT('',(0.325,0.125)); -#9373 = VECTOR('',#9374,1.); -#9374 = DIRECTION('',(1.011968286946E-013,-1.)); -#9375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9376 = PCURVE('',#9095,#9377); -#9377 = DEFINITIONAL_REPRESENTATION('',(#9378),#9382); -#9378 = LINE('',#9379,#9380); -#9379 = CARTESIAN_POINT('',(0.E+000,-0.325)); -#9380 = VECTOR('',#9381,1.); -#9381 = DIRECTION('',(-1.,0.E+000)); -#9382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9383 = ORIENTED_EDGE('',*,*,#9384,.F.); -#9384 = EDGE_CURVE('',#9385,#9362,#9387,.T.); -#9385 = VERTEX_POINT('',#9386); -#9386 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, +#11759 = VECTOR('',#11760,1.); +#11760 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11761 = PCURVE('',#11380,#11762); +#11762 = DEFINITIONAL_REPRESENTATION('',(#11763),#11767); +#11763 = LINE('',#11764,#11765); +#11764 = CARTESIAN_POINT('',(0.325,0.125)); +#11765 = VECTOR('',#11766,1.); +#11766 = DIRECTION('',(1.011968286946E-013,-1.)); +#11767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11768 = PCURVE('',#11487,#11769); +#11769 = DEFINITIONAL_REPRESENTATION('',(#11770),#11774); +#11770 = LINE('',#11771,#11772); +#11771 = CARTESIAN_POINT('',(0.E+000,-0.325)); +#11772 = VECTOR('',#11773,1.); +#11773 = DIRECTION('',(-1.,0.E+000)); +#11774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11775 = ORIENTED_EDGE('',*,*,#11776,.F.); +#11776 = EDGE_CURVE('',#11777,#11754,#11779,.T.); +#11777 = VERTEX_POINT('',#11778); +#11778 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, 2.976642100057E-002)); -#9387 = SURFACE_CURVE('',#9388,(#9392,#9399),.PCURVE_S1.); -#9388 = LINE('',#9389,#9390); -#9389 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, +#11779 = SURFACE_CURVE('',#11780,(#11784,#11791),.PCURVE_S1.); +#11780 = LINE('',#11781,#11782); +#11781 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, 2.976642100057E-002)); -#9390 = VECTOR('',#9391,1.); -#9391 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#9392 = PCURVE('',#8988,#9393); -#9393 = DEFINITIONAL_REPRESENTATION('',(#9394),#9398); -#9394 = LINE('',#9395,#9396); -#9395 = CARTESIAN_POINT('',(-0.325,0.125)); -#9396 = VECTOR('',#9397,1.); -#9397 = DIRECTION('',(1.,1.011968286946E-013)); -#9398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9399 = PCURVE('',#9400,#9405); -#9400 = PLANE('',#9401); -#9401 = AXIS2_PLACEMENT_3D('',#9402,#9403,#9404); -#9402 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, +#11782 = VECTOR('',#11783,1.); +#11783 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11784 = PCURVE('',#11380,#11785); +#11785 = DEFINITIONAL_REPRESENTATION('',(#11786),#11790); +#11786 = LINE('',#11787,#11788); +#11787 = CARTESIAN_POINT('',(-0.325,0.125)); +#11788 = VECTOR('',#11789,1.); +#11789 = DIRECTION('',(1.,1.011968286946E-013)); +#11790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11791 = PCURVE('',#11792,#11797); +#11792 = PLANE('',#11793); +#11793 = AXIS2_PLACEMENT_3D('',#11794,#11795,#11796); +#11794 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, 4.766421000566E-003)); -#9403 = DIRECTION('',(-1.011968286946E-013,1.,1.91193743656E-027)); -#9404 = DIRECTION('',(-1.,-1.011968286946E-013,-1.712573804467E-057)); -#9405 = DEFINITIONAL_REPRESENTATION('',(#9406),#9410); -#9406 = LINE('',#9407,#9408); -#9407 = CARTESIAN_POINT('',(-4.281434511168E-059,2.5E-002)); -#9408 = VECTOR('',#9409,1.); -#9409 = DIRECTION('',(-1.,-1.712573804467E-057)); -#9410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9411 = ORIENTED_EDGE('',*,*,#9412,.F.); -#9412 = EDGE_CURVE('',#9314,#9385,#9413,.T.); -#9413 = SURFACE_CURVE('',#9414,(#9418,#9425),.PCURVE_S1.); -#9414 = LINE('',#9415,#9416); -#9415 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, +#11795 = DIRECTION('',(-1.011968286946E-013,1.,1.91193743656E-027)); +#11796 = DIRECTION('',(-1.,-1.011968286946E-013,-1.712573804467E-057)); +#11797 = DEFINITIONAL_REPRESENTATION('',(#11798),#11802); +#11798 = LINE('',#11799,#11800); +#11799 = CARTESIAN_POINT('',(-4.281434511168E-059,2.5E-002)); +#11800 = VECTOR('',#11801,1.); +#11801 = DIRECTION('',(-1.,-1.712573804467E-057)); +#11802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11803 = ORIENTED_EDGE('',*,*,#11804,.F.); +#11804 = EDGE_CURVE('',#11706,#11777,#11805,.T.); +#11805 = SURFACE_CURVE('',#11806,(#11810,#11817),.PCURVE_S1.); +#11806 = LINE('',#11807,#11808); +#11807 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, 2.976642100057E-002)); -#9416 = VECTOR('',#9417,1.); -#9417 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#9418 = PCURVE('',#8988,#9419); -#9419 = DEFINITIONAL_REPRESENTATION('',(#9420),#9424); -#9420 = LINE('',#9421,#9422); -#9421 = CARTESIAN_POINT('',(-0.325,0.125)); -#9422 = VECTOR('',#9423,1.); -#9423 = DIRECTION('',(-1.011968286946E-013,1.)); -#9424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9425 = PCURVE('',#9177,#9426); -#9426 = DEFINITIONAL_REPRESENTATION('',(#9427),#9431); -#9427 = LINE('',#9428,#9429); -#9428 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#9429 = VECTOR('',#9430,1.); -#9430 = DIRECTION('',(-1.,0.E+000)); -#9431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9432 = ORIENTED_EDGE('',*,*,#9313,.T.); -#9433 = ORIENTED_EDGE('',*,*,#8949,.T.); -#9434 = ORIENTED_EDGE('',*,*,#9107,.T.); -#9435 = ADVANCED_FACE('',(#9436),#9205,.T.); -#9436 = FACE_BOUND('',#9437,.T.); -#9437 = EDGE_LOOP('',(#9438,#9468,#9523,#9551,#9572,#9573)); -#9438 = ORIENTED_EDGE('',*,*,#9439,.F.); -#9439 = EDGE_CURVE('',#9440,#9442,#9444,.T.); -#9440 = VERTEX_POINT('',#9441); -#9441 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056,0.354766421001 - )); -#9442 = VERTEX_POINT('',#9443); -#9443 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056,0.354766421001 - )); -#9444 = SURFACE_CURVE('',#9445,(#9449,#9456),.PCURVE_S1.); -#9445 = LINE('',#9446,#9447); -#9446 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056,0.354766421001 - )); -#9447 = VECTOR('',#9448,1.); -#9448 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#9449 = PCURVE('',#9205,#9450); -#9450 = DEFINITIONAL_REPRESENTATION('',(#9451),#9455); -#9451 = LINE('',#9452,#9453); -#9452 = CARTESIAN_POINT('',(0.2,-0.275)); -#9453 = VECTOR('',#9454,1.); -#9454 = DIRECTION('',(-1.,-1.011968286946E-013)); -#9455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9456 = PCURVE('',#9457,#9462); -#9457 = PLANE('',#9458); -#9458 = AXIS2_PLACEMENT_3D('',#9459,#9460,#9461); -#9459 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, +#11808 = VECTOR('',#11809,1.); +#11809 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11810 = PCURVE('',#11380,#11811); +#11811 = DEFINITIONAL_REPRESENTATION('',(#11812),#11816); +#11812 = LINE('',#11813,#11814); +#11813 = CARTESIAN_POINT('',(-0.325,0.125)); +#11814 = VECTOR('',#11815,1.); +#11815 = DIRECTION('',(-1.011968286946E-013,1.)); +#11816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11817 = PCURVE('',#11569,#11818); +#11818 = DEFINITIONAL_REPRESENTATION('',(#11819),#11823); +#11819 = LINE('',#11820,#11821); +#11820 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#11821 = VECTOR('',#11822,1.); +#11822 = DIRECTION('',(-1.,0.E+000)); +#11823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11824 = ORIENTED_EDGE('',*,*,#11705,.T.); +#11825 = ORIENTED_EDGE('',*,*,#11341,.T.); +#11826 = ORIENTED_EDGE('',*,*,#11499,.T.); +#11827 = ADVANCED_FACE('',(#11828),#11597,.T.); +#11828 = FACE_BOUND('',#11829,.T.); +#11829 = EDGE_LOOP('',(#11830,#11860,#11915,#11943,#11964,#11965)); +#11830 = ORIENTED_EDGE('',*,*,#11831,.F.); +#11831 = EDGE_CURVE('',#11832,#11834,#11836,.T.); +#11832 = VERTEX_POINT('',#11833); +#11833 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, + 0.354766421001)); +#11834 = VERTEX_POINT('',#11835); +#11835 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056, + 0.354766421001)); +#11836 = SURFACE_CURVE('',#11837,(#11841,#11848),.PCURVE_S1.); +#11837 = LINE('',#11838,#11839); +#11838 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, + 0.354766421001)); +#11839 = VECTOR('',#11840,1.); +#11840 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#11841 = PCURVE('',#11597,#11842); +#11842 = DEFINITIONAL_REPRESENTATION('',(#11843),#11847); +#11843 = LINE('',#11844,#11845); +#11844 = CARTESIAN_POINT('',(0.2,-0.275)); +#11845 = VECTOR('',#11846,1.); +#11846 = DIRECTION('',(-1.,-1.011968286946E-013)); +#11847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11848 = PCURVE('',#11849,#11854); +#11849 = PLANE('',#11850); +#11850 = AXIS2_PLACEMENT_3D('',#11851,#11852,#11853); +#11851 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, 4.766421000566E-003)); -#9460 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9461 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#9462 = DEFINITIONAL_REPRESENTATION('',(#9463),#9467); -#9463 = LINE('',#9464,#9465); -#9464 = CARTESIAN_POINT('',(0.E+000,0.35)); -#9465 = VECTOR('',#9466,1.); -#9466 = DIRECTION('',(-1.,0.E+000)); -#9467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9468 = ORIENTED_EDGE('',*,*,#9469,.T.); -#9469 = EDGE_CURVE('',#9440,#9470,#9472,.T.); -#9470 = VERTEX_POINT('',#9471); -#9471 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056,0.354766421001) - ); -#9472 = SURFACE_CURVE('',#9473,(#9478,#9489),.PCURVE_S1.); -#9473 = CIRCLE('',#9474,0.125); -#9474 = AXIS2_PLACEMENT_3D('',#9475,#9476,#9477); -#9475 = CARTESIAN_POINT('',(-5.343500199793E-003,-1.442441590056, +#11852 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11853 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11854 = DEFINITIONAL_REPRESENTATION('',(#11855),#11859); +#11855 = LINE('',#11856,#11857); +#11856 = CARTESIAN_POINT('',(0.E+000,0.35)); +#11857 = VECTOR('',#11858,1.); +#11858 = DIRECTION('',(-1.,0.E+000)); +#11859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11860 = ORIENTED_EDGE('',*,*,#11861,.T.); +#11861 = EDGE_CURVE('',#11832,#11862,#11864,.T.); +#11862 = VERTEX_POINT('',#11863); +#11863 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056,0.354766421001 + )); +#11864 = SURFACE_CURVE('',#11865,(#11870,#11881),.PCURVE_S1.); +#11865 = CIRCLE('',#11866,0.125); +#11866 = AXIS2_PLACEMENT_3D('',#11867,#11868,#11869); +#11867 = CARTESIAN_POINT('',(-5.343500199793E-003,-1.442441590056, 0.354766421001)); -#9476 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#9477 = DIRECTION('',(1.,-3.502754633927E-042,1.624097681737E-013)); -#9478 = PCURVE('',#9205,#9479); -#9479 = DEFINITIONAL_REPRESENTATION('',(#9480),#9488); -#9480 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#9481,#9482,#9483,#9484, -#9485,#9486,#9487),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#9481 = CARTESIAN_POINT('',(0.45,-0.275)); -#9482 = CARTESIAN_POINT('',(0.45,-0.491506350946)); -#9483 = CARTESIAN_POINT('',(0.2625,-0.383253175473)); -#9484 = CARTESIAN_POINT('',(7.499999999996E-002,-0.275)); -#9485 = CARTESIAN_POINT('',(0.2625,-0.166746824527)); -#9486 = CARTESIAN_POINT('',(0.45,-5.849364905389E-002)); -#9487 = CARTESIAN_POINT('',(0.45,-0.275)); -#9488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9489 = PCURVE('',#9490,#9495); -#9490 = CYLINDRICAL_SURFACE('',#9491,0.125); -#9491 = AXIS2_PLACEMENT_3D('',#9492,#9493,#9494); -#9492 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, +#11868 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#11869 = DIRECTION('',(1.,-3.502754633927E-042,1.624097681737E-013)); +#11870 = PCURVE('',#11597,#11871); +#11871 = DEFINITIONAL_REPRESENTATION('',(#11872),#11880); +#11872 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#11873,#11874,#11875,#11876 + ,#11877,#11878,#11879),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#11873 = CARTESIAN_POINT('',(0.45,-0.275)); +#11874 = CARTESIAN_POINT('',(0.45,-0.491506350946)); +#11875 = CARTESIAN_POINT('',(0.2625,-0.383253175473)); +#11876 = CARTESIAN_POINT('',(7.499999999996E-002,-0.275)); +#11877 = CARTESIAN_POINT('',(0.2625,-0.166746824527)); +#11878 = CARTESIAN_POINT('',(0.45,-5.849364905389E-002)); +#11879 = CARTESIAN_POINT('',(0.45,-0.275)); +#11880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11881 = PCURVE('',#11882,#11887); +#11882 = CYLINDRICAL_SURFACE('',#11883,0.125); +#11883 = AXIS2_PLACEMENT_3D('',#11884,#11885,#11886); +#11884 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, 4.766421000587E-003)); -#9493 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#9494 = DIRECTION('',(1.,-5.027572966497E-044,1.624097681737E-013)); -#9495 = DEFINITIONAL_REPRESENTATION('',(#9496),#9522); -#9496 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#9497,#9498,#9499,#9500,#9501, - #9502,#9503,#9504,#9505,#9506,#9507,#9508,#9509,#9510,#9511,#9512, - #9513,#9514,#9515,#9516,#9517,#9518,#9519,#9520,#9521), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (3.14159265359,3.284392319662,3.427191985734,3.569991651807, - 3.712791317879,3.855590983951,3.998390650023,4.141190316096, - 4.283989982168,4.42678964824,4.569589314312,4.712388980385, - 4.855188646457,4.997988312529,5.140787978602,5.283587644674, - 5.426387310746,5.569186976818,5.711986642891,5.854786308963, - 5.997585975035,6.140385641107,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#9497 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#9498 = CARTESIAN_POINT('',(3.093992764899,0.35)); -#9499 = CARTESIAN_POINT('',(2.998792987517,0.35)); -#9500 = CARTESIAN_POINT('',(2.855993321445,0.35)); -#9501 = CARTESIAN_POINT('',(2.713193655373,0.35)); -#9502 = CARTESIAN_POINT('',(2.570393989301,0.35)); -#9503 = CARTESIAN_POINT('',(2.427594323228,0.35)); -#9504 = CARTESIAN_POINT('',(2.284794657156,0.35)); -#9505 = CARTESIAN_POINT('',(2.141994991084,0.35)); -#9506 = CARTESIAN_POINT('',(1.999195325012,0.35)); -#9507 = CARTESIAN_POINT('',(1.856395658939,0.35)); -#9508 = CARTESIAN_POINT('',(1.713595992867,0.35)); -#9509 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#9510 = CARTESIAN_POINT('',(1.427996660723,0.35)); -#9511 = CARTESIAN_POINT('',(1.28519699465,0.35)); -#9512 = CARTESIAN_POINT('',(1.142397328578,0.35)); -#9513 = CARTESIAN_POINT('',(0.999597662506,0.35)); -#9514 = CARTESIAN_POINT('',(0.856797996434,0.35)); -#9515 = CARTESIAN_POINT('',(0.713998330361,0.35)); -#9516 = CARTESIAN_POINT('',(0.571198664289,0.35)); -#9517 = CARTESIAN_POINT('',(0.428398998217,0.35)); -#9518 = CARTESIAN_POINT('',(0.285599332145,0.35)); -#9519 = CARTESIAN_POINT('',(0.142799666072,0.35)); -#9520 = CARTESIAN_POINT('',(4.759988869075E-002,0.35)); -#9521 = CARTESIAN_POINT('',(0.E+000,0.35)); -#9522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9523 = ORIENTED_EDGE('',*,*,#9524,.F.); -#9524 = EDGE_CURVE('',#9525,#9470,#9527,.T.); -#9525 = VERTEX_POINT('',#9526); -#9526 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056,0.354766421001) - ); -#9527 = SURFACE_CURVE('',#9528,(#9532,#9539),.PCURVE_S1.); -#9528 = LINE('',#9529,#9530); -#9529 = CARTESIAN_POINT('',(0.1446564998,-1.442441590056,0.354766421001) - ); -#9530 = VECTOR('',#9531,1.); -#9531 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#9532 = PCURVE('',#9205,#9533); -#9533 = DEFINITIONAL_REPRESENTATION('',(#9534),#9538); -#9534 = LINE('',#9535,#9536); -#9535 = CARTESIAN_POINT('',(0.475,-0.275)); -#9536 = VECTOR('',#9537,1.); -#9537 = DIRECTION('',(-1.,-1.011968286946E-013)); -#9538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9539 = PCURVE('',#9540,#9545); -#9540 = PLANE('',#9541); -#9541 = AXIS2_PLACEMENT_3D('',#9542,#9543,#9544); -#9542 = CARTESIAN_POINT('',(0.1446564998,-1.442441590056, +#11885 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#11886 = DIRECTION('',(1.,-5.027572966497E-044,1.624097681737E-013)); +#11887 = DEFINITIONAL_REPRESENTATION('',(#11888),#11914); +#11888 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#11889,#11890,#11891,#11892, + #11893,#11894,#11895,#11896,#11897,#11898,#11899,#11900,#11901, + #11902,#11903,#11904,#11905,#11906,#11907,#11908,#11909,#11910, + #11911,#11912,#11913),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 + ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, + 4.141190316096,4.283989982168,4.42678964824,4.569589314312, + 4.712388980385,4.855188646457,4.997988312529,5.140787978602, + 5.283587644674,5.426387310746,5.569186976818,5.711986642891, + 5.854786308963,5.997585975035,6.140385641107,6.28318530718), + .QUASI_UNIFORM_KNOTS.); +#11889 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#11890 = CARTESIAN_POINT('',(3.093992764899,0.35)); +#11891 = CARTESIAN_POINT('',(2.998792987517,0.35)); +#11892 = CARTESIAN_POINT('',(2.855993321445,0.35)); +#11893 = CARTESIAN_POINT('',(2.713193655373,0.35)); +#11894 = CARTESIAN_POINT('',(2.570393989301,0.35)); +#11895 = CARTESIAN_POINT('',(2.427594323228,0.35)); +#11896 = CARTESIAN_POINT('',(2.284794657156,0.35)); +#11897 = CARTESIAN_POINT('',(2.141994991084,0.35)); +#11898 = CARTESIAN_POINT('',(1.999195325012,0.35)); +#11899 = CARTESIAN_POINT('',(1.856395658939,0.35)); +#11900 = CARTESIAN_POINT('',(1.713595992867,0.35)); +#11901 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#11902 = CARTESIAN_POINT('',(1.427996660723,0.35)); +#11903 = CARTESIAN_POINT('',(1.28519699465,0.35)); +#11904 = CARTESIAN_POINT('',(1.142397328578,0.35)); +#11905 = CARTESIAN_POINT('',(0.999597662506,0.35)); +#11906 = CARTESIAN_POINT('',(0.856797996434,0.35)); +#11907 = CARTESIAN_POINT('',(0.713998330361,0.35)); +#11908 = CARTESIAN_POINT('',(0.571198664289,0.35)); +#11909 = CARTESIAN_POINT('',(0.428398998217,0.35)); +#11910 = CARTESIAN_POINT('',(0.285599332145,0.35)); +#11911 = CARTESIAN_POINT('',(0.142799666072,0.35)); +#11912 = CARTESIAN_POINT('',(4.759988869075E-002,0.35)); +#11913 = CARTESIAN_POINT('',(0.E+000,0.35)); +#11914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11915 = ORIENTED_EDGE('',*,*,#11916,.F.); +#11916 = EDGE_CURVE('',#11917,#11862,#11919,.T.); +#11917 = VERTEX_POINT('',#11918); +#11918 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056,0.354766421001 + )); +#11919 = SURFACE_CURVE('',#11920,(#11924,#11931),.PCURVE_S1.); +#11920 = LINE('',#11921,#11922); +#11921 = CARTESIAN_POINT('',(0.1446564998,-1.442441590056,0.354766421001 + )); +#11922 = VECTOR('',#11923,1.); +#11923 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#11924 = PCURVE('',#11597,#11925); +#11925 = DEFINITIONAL_REPRESENTATION('',(#11926),#11930); +#11926 = LINE('',#11927,#11928); +#11927 = CARTESIAN_POINT('',(0.475,-0.275)); +#11928 = VECTOR('',#11929,1.); +#11929 = DIRECTION('',(-1.,-1.011968286946E-013)); +#11930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11931 = PCURVE('',#11932,#11937); +#11932 = PLANE('',#11933); +#11933 = AXIS2_PLACEMENT_3D('',#11934,#11935,#11936); +#11934 = CARTESIAN_POINT('',(0.1446564998,-1.442441590056, 4.766421000566E-003)); -#9543 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9544 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#9545 = DEFINITIONAL_REPRESENTATION('',(#9546),#9550); -#9546 = LINE('',#9547,#9548); -#9547 = CARTESIAN_POINT('',(0.E+000,0.35)); -#9548 = VECTOR('',#9549,1.); -#9549 = DIRECTION('',(-1.,0.E+000)); -#9550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9551 = ORIENTED_EDGE('',*,*,#9552,.F.); -#9552 = EDGE_CURVE('',#9190,#9525,#9553,.T.); -#9553 = SURFACE_CURVE('',#9554,(#9558,#9565),.PCURVE_S1.); -#9554 = LINE('',#9555,#9556); -#9555 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.354766421001) - ); -#9556 = VECTOR('',#9557,1.); -#9557 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#9558 = PCURVE('',#9205,#9559); -#9559 = DEFINITIONAL_REPRESENTATION('',(#9560),#9564); -#9560 = LINE('',#9561,#9562); -#9561 = CARTESIAN_POINT('',(0.65,6.572520305781E-014)); -#9562 = VECTOR('',#9563,1.); -#9563 = DIRECTION('',(1.011968286946E-013,-1.)); -#9564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9565 = PCURVE('',#9095,#9566); -#9566 = DEFINITIONAL_REPRESENTATION('',(#9567),#9571); -#9567 = LINE('',#9568,#9569); -#9568 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#9569 = VECTOR('',#9570,1.); -#9570 = DIRECTION('',(-1.,0.E+000)); -#9571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9572 = ORIENTED_EDGE('',*,*,#9189,.T.); -#9573 = ORIENTED_EDGE('',*,*,#9574,.F.); -#9574 = EDGE_CURVE('',#9442,#9162,#9575,.T.); -#9575 = SURFACE_CURVE('',#9576,(#9580,#9587),.PCURVE_S1.); -#9576 = LINE('',#9577,#9578); -#9577 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056,0.354766421001 +#11935 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11936 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#11937 = DEFINITIONAL_REPRESENTATION('',(#11938),#11942); +#11938 = LINE('',#11939,#11940); +#11939 = CARTESIAN_POINT('',(0.E+000,0.35)); +#11940 = VECTOR('',#11941,1.); +#11941 = DIRECTION('',(-1.,0.E+000)); +#11942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11943 = ORIENTED_EDGE('',*,*,#11944,.F.); +#11944 = EDGE_CURVE('',#11582,#11917,#11945,.T.); +#11945 = SURFACE_CURVE('',#11946,(#11950,#11957),.PCURVE_S1.); +#11946 = LINE('',#11947,#11948); +#11947 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056,0.354766421001 )); -#9578 = VECTOR('',#9579,1.); -#9579 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#9580 = PCURVE('',#9205,#9581); -#9581 = DEFINITIONAL_REPRESENTATION('',(#9582),#9586); -#9582 = LINE('',#9583,#9584); -#9583 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#9584 = VECTOR('',#9585,1.); -#9585 = DIRECTION('',(-1.011968286946E-013,1.)); -#9586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9587 = PCURVE('',#9177,#9588); -#9588 = DEFINITIONAL_REPRESENTATION('',(#9589),#9593); -#9589 = LINE('',#9590,#9591); -#9590 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#9591 = VECTOR('',#9592,1.); -#9592 = DIRECTION('',(-1.,0.E+000)); -#9593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9594 = ADVANCED_FACE('',(#9595),#9540,.T.); -#9595 = FACE_BOUND('',#9596,.T.); -#9596 = EDGE_LOOP('',(#9597,#9598,#9620,#9648)); -#9597 = ORIENTED_EDGE('',*,*,#9524,.T.); -#9598 = ORIENTED_EDGE('',*,*,#9599,.T.); -#9599 = EDGE_CURVE('',#9470,#9600,#9602,.T.); -#9600 = VERTEX_POINT('',#9601); -#9601 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056, +#11948 = VECTOR('',#11949,1.); +#11949 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#11950 = PCURVE('',#11597,#11951); +#11951 = DEFINITIONAL_REPRESENTATION('',(#11952),#11956); +#11952 = LINE('',#11953,#11954); +#11953 = CARTESIAN_POINT('',(0.65,6.572520305781E-014)); +#11954 = VECTOR('',#11955,1.); +#11955 = DIRECTION('',(1.011968286946E-013,-1.)); +#11956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11957 = PCURVE('',#11487,#11958); +#11958 = DEFINITIONAL_REPRESENTATION('',(#11959),#11963); +#11959 = LINE('',#11960,#11961); +#11960 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11961 = VECTOR('',#11962,1.); +#11962 = DIRECTION('',(-1.,0.E+000)); +#11963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11964 = ORIENTED_EDGE('',*,*,#11581,.T.); +#11965 = ORIENTED_EDGE('',*,*,#11966,.F.); +#11966 = EDGE_CURVE('',#11834,#11554,#11967,.T.); +#11967 = SURFACE_CURVE('',#11968,(#11972,#11979),.PCURVE_S1.); +#11968 = LINE('',#11969,#11970); +#11969 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, + 0.354766421001)); +#11970 = VECTOR('',#11971,1.); +#11971 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#11972 = PCURVE('',#11597,#11973); +#11973 = DEFINITIONAL_REPRESENTATION('',(#11974),#11978); +#11974 = LINE('',#11975,#11976); +#11975 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#11976 = VECTOR('',#11977,1.); +#11977 = DIRECTION('',(-1.011968286946E-013,1.)); +#11978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11979 = PCURVE('',#11569,#11980); +#11980 = DEFINITIONAL_REPRESENTATION('',(#11981),#11985); +#11981 = LINE('',#11982,#11983); +#11982 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#11983 = VECTOR('',#11984,1.); +#11984 = DIRECTION('',(-1.,0.E+000)); +#11985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#11986 = ADVANCED_FACE('',(#11987),#11932,.T.); +#11987 = FACE_BOUND('',#11988,.T.); +#11988 = EDGE_LOOP('',(#11989,#11990,#12012,#12040)); +#11989 = ORIENTED_EDGE('',*,*,#11916,.T.); +#11990 = ORIENTED_EDGE('',*,*,#11991,.T.); +#11991 = EDGE_CURVE('',#11862,#11992,#11994,.T.); +#11992 = VERTEX_POINT('',#11993); +#11993 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056, 4.766421000566E-003)); -#9602 = SURFACE_CURVE('',#9603,(#9607,#9614),.PCURVE_S1.); -#9603 = LINE('',#9604,#9605); -#9604 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056, +#11994 = SURFACE_CURVE('',#11995,(#11999,#12006),.PCURVE_S1.); +#11995 = LINE('',#11996,#11997); +#11996 = CARTESIAN_POINT('',(0.1196564998,-1.442441590056, 4.766421000607E-003)); -#9605 = VECTOR('',#9606,1.); -#9606 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#9607 = PCURVE('',#9540,#9608); -#9608 = DEFINITIONAL_REPRESENTATION('',(#9609),#9613); -#9609 = LINE('',#9610,#9611); -#9610 = CARTESIAN_POINT('',(-2.499999999998E-002,4.05751821031E-014)); -#9611 = VECTOR('',#9612,1.); -#9612 = DIRECTION('',(1.624097681737E-013,-1.)); -#9613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9614 = PCURVE('',#9490,#9615); -#9615 = DEFINITIONAL_REPRESENTATION('',(#9616),#9619); -#9616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#9617,#9618),.UNSPECIFIED.,.F., - .F.,(2,2),(-0.35,4.058732516743E-014),.PIECEWISE_BEZIER_KNOTS.); -#9617 = CARTESIAN_POINT('',(0.E+000,0.35)); -#9618 = CARTESIAN_POINT('',(0.E+000,-4.058732516743E-014)); -#9619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9620 = ORIENTED_EDGE('',*,*,#9621,.T.); -#9621 = EDGE_CURVE('',#9600,#9622,#9624,.T.); -#9622 = VERTEX_POINT('',#9623); -#9623 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056, +#11997 = VECTOR('',#11998,1.); +#11998 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#11999 = PCURVE('',#11932,#12000); +#12000 = DEFINITIONAL_REPRESENTATION('',(#12001),#12005); +#12001 = LINE('',#12002,#12003); +#12002 = CARTESIAN_POINT('',(-2.499999999998E-002,4.05751821031E-014)); +#12003 = VECTOR('',#12004,1.); +#12004 = DIRECTION('',(1.624097681737E-013,-1.)); +#12005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12006 = PCURVE('',#11882,#12007); +#12007 = DEFINITIONAL_REPRESENTATION('',(#12008),#12011); +#12008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12009,#12010),.UNSPECIFIED., + .F.,.F.,(2,2),(-0.35,4.058732516743E-014),.PIECEWISE_BEZIER_KNOTS.); +#12009 = CARTESIAN_POINT('',(0.E+000,0.35)); +#12010 = CARTESIAN_POINT('',(0.E+000,-4.058732516743E-014)); +#12011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12012 = ORIENTED_EDGE('',*,*,#12013,.T.); +#12013 = EDGE_CURVE('',#11992,#12014,#12016,.T.); +#12014 = VERTEX_POINT('',#12015); +#12015 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056, 4.766421000566E-003)); -#9624 = SURFACE_CURVE('',#9625,(#9629,#9636),.PCURVE_S1.); -#9625 = LINE('',#9626,#9627); -#9626 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.442441590056, +#12016 = SURFACE_CURVE('',#12017,(#12021,#12028),.PCURVE_S1.); +#12017 = LINE('',#12018,#12019); +#12018 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.442441590056, 4.766421000566E-003)); -#9627 = VECTOR('',#9628,1.); -#9628 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); -#9629 = PCURVE('',#9540,#9630); -#9630 = DEFINITIONAL_REPRESENTATION('',(#9631),#9635); -#9631 = LINE('',#9632,#9633); -#9632 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#9633 = VECTOR('',#9634,1.); -#9634 = DIRECTION('',(1.,-8.306531413975E-029)); -#9635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#12019 = VECTOR('',#12020,1.); +#12020 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); +#12021 = PCURVE('',#11932,#12022); +#12022 = DEFINITIONAL_REPRESENTATION('',(#12023),#12027); +#12023 = LINE('',#12024,#12025); +#12024 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#12025 = VECTOR('',#12026,1.); +#12026 = DIRECTION('',(1.,-8.306531413975E-029)); +#12027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#9636 = PCURVE('',#9637,#9642); -#9637 = PLANE('',#9638); -#9638 = AXIS2_PLACEMENT_3D('',#9639,#9640,#9641); -#9639 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.367220815637, +#12028 = PCURVE('',#12029,#12034); +#12029 = PLANE('',#12030); +#12030 = AXIS2_PLACEMENT_3D('',#12031,#12032,#12033); +#12031 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.367220815637, 4.766421000566E-003)); -#9640 = DIRECTION('',(8.306531413975E-029,8.405946365462E-042,1.)); -#9641 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); -#9642 = DEFINITIONAL_REPRESENTATION('',(#9643),#9647); -#9643 = LINE('',#9644,#9645); -#9644 = CARTESIAN_POINT('',(0.E+000,-7.522077441907E-002)); -#9645 = VECTOR('',#9646,1.); -#9646 = DIRECTION('',(1.,1.295058128893E-085)); -#9647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9648 = ORIENTED_EDGE('',*,*,#9649,.F.); -#9649 = EDGE_CURVE('',#9525,#9622,#9650,.T.); -#9650 = SURFACE_CURVE('',#9651,(#9655,#9662),.PCURVE_S1.); -#9651 = LINE('',#9652,#9653); -#9652 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056,0.354766421001) - ); -#9653 = VECTOR('',#9654,1.); -#9654 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9655 = PCURVE('',#9540,#9656); -#9656 = DEFINITIONAL_REPRESENTATION('',(#9657),#9661); -#9657 = LINE('',#9658,#9659); -#9658 = CARTESIAN_POINT('',(0.175,0.35)); -#9659 = VECTOR('',#9660,1.); -#9660 = DIRECTION('',(0.E+000,-1.)); -#9661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9662 = PCURVE('',#9095,#9663); -#9663 = DEFINITIONAL_REPRESENTATION('',(#9664),#9668); -#9664 = LINE('',#9665,#9666); -#9665 = CARTESIAN_POINT('',(-0.275,0.E+000)); -#9666 = VECTOR('',#9667,1.); -#9667 = DIRECTION('',(0.E+000,-1.)); -#9668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9669 = ADVANCED_FACE('',(#9670),#9095,.T.); -#9670 = FACE_BOUND('',#9671,.T.); -#9671 = EDGE_LOOP('',(#9672,#9695,#9696,#9697,#9698,#9699,#9700,#9701)); -#9672 = ORIENTED_EDGE('',*,*,#9673,.F.); -#9673 = EDGE_CURVE('',#9362,#9674,#9676,.T.); -#9674 = VERTEX_POINT('',#9675); -#9675 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, +#12032 = DIRECTION('',(8.306531413975E-029,8.405946365462E-042,1.)); +#12033 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); +#12034 = DEFINITIONAL_REPRESENTATION('',(#12035),#12039); +#12035 = LINE('',#12036,#12037); +#12036 = CARTESIAN_POINT('',(0.E+000,-7.522077441907E-002)); +#12037 = VECTOR('',#12038,1.); +#12038 = DIRECTION('',(1.,1.295058128893E-085)); +#12039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12040 = ORIENTED_EDGE('',*,*,#12041,.F.); +#12041 = EDGE_CURVE('',#11917,#12014,#12042,.T.); +#12042 = SURFACE_CURVE('',#12043,(#12047,#12054),.PCURVE_S1.); +#12043 = LINE('',#12044,#12045); +#12044 = CARTESIAN_POINT('',(0.3196564998,-1.442441590056,0.354766421001 + )); +#12045 = VECTOR('',#12046,1.); +#12046 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12047 = PCURVE('',#11932,#12048); +#12048 = DEFINITIONAL_REPRESENTATION('',(#12049),#12053); +#12049 = LINE('',#12050,#12051); +#12050 = CARTESIAN_POINT('',(0.175,0.35)); +#12051 = VECTOR('',#12052,1.); +#12052 = DIRECTION('',(0.E+000,-1.)); +#12053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12054 = PCURVE('',#11487,#12055); +#12055 = DEFINITIONAL_REPRESENTATION('',(#12056),#12060); +#12056 = LINE('',#12057,#12058); +#12057 = CARTESIAN_POINT('',(-0.275,0.E+000)); +#12058 = VECTOR('',#12059,1.); +#12059 = DIRECTION('',(0.E+000,-1.)); +#12060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12061 = ADVANCED_FACE('',(#12062),#11487,.T.); +#12062 = FACE_BOUND('',#12063,.T.); +#12063 = EDGE_LOOP('',(#12064,#12087,#12088,#12089,#12090,#12091,#12092, + #12093)); +#12064 = ORIENTED_EDGE('',*,*,#12065,.F.); +#12065 = EDGE_CURVE('',#11754,#12066,#12068,.T.); +#12066 = VERTEX_POINT('',#12067); +#12067 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, 4.766421000566E-003)); -#9676 = SURFACE_CURVE('',#9677,(#9681,#9688),.PCURVE_S1.); -#9677 = LINE('',#9678,#9679); -#9678 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, +#12068 = SURFACE_CURVE('',#12069,(#12073,#12080),.PCURVE_S1.); +#12069 = LINE('',#12070,#12071); +#12070 = CARTESIAN_POINT('',(0.3196564998,-1.167441590056, 4.766421000566E-003)); -#9679 = VECTOR('',#9680,1.); -#9680 = DIRECTION('',(-1.934820052423E-040,1.91193743656E-027,-1.)); -#9681 = PCURVE('',#9095,#9682); -#9682 = DEFINITIONAL_REPRESENTATION('',(#9683),#9687); -#9683 = LINE('',#9684,#9685); -#9684 = CARTESIAN_POINT('',(-2.84217094304E-014,-0.35)); -#9685 = VECTOR('',#9686,1.); -#9686 = DIRECTION('',(1.91193743656E-027,-1.)); -#9687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9688 = PCURVE('',#9400,#9689); -#9689 = DEFINITIONAL_REPRESENTATION('',(#9690),#9694); -#9690 = LINE('',#9691,#9692); -#9691 = CARTESIAN_POINT('',(-0.65,1.008271557608E-043)); -#9692 = VECTOR('',#9693,1.); -#9693 = DIRECTION('',(-8.156630584998E-056,-1.)); -#9694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9695 = ORIENTED_EDGE('',*,*,#9361,.T.); -#9696 = ORIENTED_EDGE('',*,*,#9079,.T.); -#9697 = ORIENTED_EDGE('',*,*,#9288,.T.); -#9698 = ORIENTED_EDGE('',*,*,#9217,.T.); -#9699 = ORIENTED_EDGE('',*,*,#9552,.T.); -#9700 = ORIENTED_EDGE('',*,*,#9649,.T.); -#9701 = ORIENTED_EDGE('',*,*,#9702,.T.); -#9702 = EDGE_CURVE('',#9622,#9674,#9703,.T.); -#9703 = SURFACE_CURVE('',#9704,(#9708,#9715),.PCURVE_S1.); -#9704 = LINE('',#9705,#9706); -#9705 = CARTESIAN_POINT('',(0.3196564998,-1.367220815637, +#12071 = VECTOR('',#12072,1.); +#12072 = DIRECTION('',(-1.934820052423E-040,1.91193743656E-027,-1.)); +#12073 = PCURVE('',#11487,#12074); +#12074 = DEFINITIONAL_REPRESENTATION('',(#12075),#12079); +#12075 = LINE('',#12076,#12077); +#12076 = CARTESIAN_POINT('',(-2.84217094304E-014,-0.35)); +#12077 = VECTOR('',#12078,1.); +#12078 = DIRECTION('',(1.91193743656E-027,-1.)); +#12079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12080 = PCURVE('',#11792,#12081); +#12081 = DEFINITIONAL_REPRESENTATION('',(#12082),#12086); +#12082 = LINE('',#12083,#12084); +#12083 = CARTESIAN_POINT('',(-0.65,1.008271557608E-043)); +#12084 = VECTOR('',#12085,1.); +#12085 = DIRECTION('',(-8.156630584998E-056,-1.)); +#12086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12087 = ORIENTED_EDGE('',*,*,#11753,.T.); +#12088 = ORIENTED_EDGE('',*,*,#11471,.T.); +#12089 = ORIENTED_EDGE('',*,*,#11680,.T.); +#12090 = ORIENTED_EDGE('',*,*,#11609,.T.); +#12091 = ORIENTED_EDGE('',*,*,#11944,.T.); +#12092 = ORIENTED_EDGE('',*,*,#12041,.T.); +#12093 = ORIENTED_EDGE('',*,*,#12094,.T.); +#12094 = EDGE_CURVE('',#12014,#12066,#12095,.T.); +#12095 = SURFACE_CURVE('',#12096,(#12100,#12107),.PCURVE_S1.); +#12096 = LINE('',#12097,#12098); +#12097 = CARTESIAN_POINT('',(0.3196564998,-1.367220815637, 4.766421000566E-003)); -#9706 = VECTOR('',#9707,1.); -#9707 = DIRECTION('',(-6.982425754889E-070,1.,-8.405946365462E-042)); -#9708 = PCURVE('',#9095,#9709); -#9709 = DEFINITIONAL_REPRESENTATION('',(#9710),#9714); -#9710 = LINE('',#9711,#9712); -#9711 = CARTESIAN_POINT('',(-0.199779225581,-0.35)); -#9712 = VECTOR('',#9713,1.); -#9713 = DIRECTION('',(1.,-8.405946365462E-042)); -#9714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9715 = PCURVE('',#9637,#9716); -#9716 = DEFINITIONAL_REPRESENTATION('',(#9717),#9721); -#9717 = LINE('',#9718,#9719); -#9718 = CARTESIAN_POINT('',(0.325,-2.269288370339E-070)); -#9719 = VECTOR('',#9720,1.); -#9720 = DIRECTION('',(3.525121835561E-086,1.)); -#9721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9722 = ADVANCED_FACE('',(#9723),#9400,.T.); -#9723 = FACE_BOUND('',#9724,.T.); -#9724 = EDGE_LOOP('',(#9725,#9726,#9727,#9750)); -#9725 = ORIENTED_EDGE('',*,*,#9384,.T.); -#9726 = ORIENTED_EDGE('',*,*,#9673,.T.); -#9727 = ORIENTED_EDGE('',*,*,#9728,.T.); -#9728 = EDGE_CURVE('',#9674,#9729,#9731,.T.); -#9729 = VERTEX_POINT('',#9730); -#9730 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, +#12098 = VECTOR('',#12099,1.); +#12099 = DIRECTION('',(-6.982425754889E-070,1.,-8.405946365462E-042)); +#12100 = PCURVE('',#11487,#12101); +#12101 = DEFINITIONAL_REPRESENTATION('',(#12102),#12106); +#12102 = LINE('',#12103,#12104); +#12103 = CARTESIAN_POINT('',(-0.199779225581,-0.35)); +#12104 = VECTOR('',#12105,1.); +#12105 = DIRECTION('',(1.,-8.405946365462E-042)); +#12106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12107 = PCURVE('',#12029,#12108); +#12108 = DEFINITIONAL_REPRESENTATION('',(#12109),#12113); +#12109 = LINE('',#12110,#12111); +#12110 = CARTESIAN_POINT('',(0.325,-2.269288370339E-070)); +#12111 = VECTOR('',#12112,1.); +#12112 = DIRECTION('',(3.525121835561E-086,1.)); +#12113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12114 = ADVANCED_FACE('',(#12115),#11792,.T.); +#12115 = FACE_BOUND('',#12116,.T.); +#12116 = EDGE_LOOP('',(#12117,#12118,#12119,#12142)); +#12117 = ORIENTED_EDGE('',*,*,#11776,.T.); +#12118 = ORIENTED_EDGE('',*,*,#12065,.T.); +#12119 = ORIENTED_EDGE('',*,*,#12120,.T.); +#12120 = EDGE_CURVE('',#12066,#12121,#12123,.T.); +#12121 = VERTEX_POINT('',#12122); +#12122 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, 4.766421000566E-003)); -#9731 = SURFACE_CURVE('',#9732,(#9736,#9743),.PCURVE_S1.); -#9732 = LINE('',#9733,#9734); -#9733 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.167441590056, +#12123 = SURFACE_CURVE('',#12124,(#12128,#12135),.PCURVE_S1.); +#12124 = LINE('',#12125,#12126); +#12125 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.167441590056, 4.766421000566E-003)); -#9734 = VECTOR('',#9735,1.); -#9735 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); -#9736 = PCURVE('',#9400,#9737); -#9737 = DEFINITIONAL_REPRESENTATION('',(#9738),#9742); -#9738 = LINE('',#9739,#9740); -#9739 = CARTESIAN_POINT('',(-0.325,-5.377642775528E-017)); -#9740 = VECTOR('',#9741,1.); -#9741 = DIRECTION('',(1.,8.306531413955E-029)); -#9742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9743 = PCURVE('',#9637,#9744); -#9744 = DEFINITIONAL_REPRESENTATION('',(#9745),#9749); -#9745 = LINE('',#9746,#9747); -#9746 = CARTESIAN_POINT('',(0.E+000,0.199779225581)); -#9747 = VECTOR('',#9748,1.); -#9748 = DIRECTION('',(-1.,-1.295058128893E-085)); -#9749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9750 = ORIENTED_EDGE('',*,*,#9751,.F.); -#9751 = EDGE_CURVE('',#9385,#9729,#9752,.T.); -#9752 = SURFACE_CURVE('',#9753,(#9757,#9764),.PCURVE_S1.); -#9753 = LINE('',#9754,#9755); -#9754 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056,0.329766421001 - )); -#9755 = VECTOR('',#9756,1.); -#9756 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9757 = PCURVE('',#9400,#9758); -#9758 = DEFINITIONAL_REPRESENTATION('',(#9759),#9763); -#9759 = LINE('',#9760,#9761); -#9760 = CARTESIAN_POINT('',(5.689893001204E-014,0.325)); -#9761 = VECTOR('',#9762,1.); -#9762 = DIRECTION('',(0.E+000,-1.)); -#9763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9764 = PCURVE('',#9177,#9765); -#9765 = DEFINITIONAL_REPRESENTATION('',(#9766),#9770); -#9766 = LINE('',#9767,#9768); -#9767 = CARTESIAN_POINT('',(2.84217094304E-014,0.E+000)); -#9768 = VECTOR('',#9769,1.); -#9769 = DIRECTION('',(0.E+000,-1.)); -#9770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9771 = ADVANCED_FACE('',(#9772),#9177,.T.); -#9772 = FACE_BOUND('',#9773,.T.); -#9773 = EDGE_LOOP('',(#9774,#9775,#9798,#9819,#9820,#9821,#9822,#9823)); -#9774 = ORIENTED_EDGE('',*,*,#9751,.T.); -#9775 = ORIENTED_EDGE('',*,*,#9776,.T.); -#9776 = EDGE_CURVE('',#9729,#9777,#9779,.T.); -#9777 = VERTEX_POINT('',#9778); -#9778 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056, +#12126 = VECTOR('',#12127,1.); +#12127 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); +#12128 = PCURVE('',#11792,#12129); +#12129 = DEFINITIONAL_REPRESENTATION('',(#12130),#12134); +#12130 = LINE('',#12131,#12132); +#12131 = CARTESIAN_POINT('',(-0.325,-5.377642775528E-017)); +#12132 = VECTOR('',#12133,1.); +#12133 = DIRECTION('',(1.,8.306531413955E-029)); +#12134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12135 = PCURVE('',#12029,#12136); +#12136 = DEFINITIONAL_REPRESENTATION('',(#12137),#12141); +#12137 = LINE('',#12138,#12139); +#12138 = CARTESIAN_POINT('',(0.E+000,0.199779225581)); +#12139 = VECTOR('',#12140,1.); +#12140 = DIRECTION('',(-1.,-1.295058128893E-085)); +#12141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12142 = ORIENTED_EDGE('',*,*,#12143,.F.); +#12143 = EDGE_CURVE('',#11777,#12121,#12144,.T.); +#12144 = SURFACE_CURVE('',#12145,(#12149,#12156),.PCURVE_S1.); +#12145 = LINE('',#12146,#12147); +#12146 = CARTESIAN_POINT('',(-0.3303435002,-1.167441590056, + 0.329766421001)); +#12147 = VECTOR('',#12148,1.); +#12148 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12149 = PCURVE('',#11792,#12150); +#12150 = DEFINITIONAL_REPRESENTATION('',(#12151),#12155); +#12151 = LINE('',#12152,#12153); +#12152 = CARTESIAN_POINT('',(5.689893001204E-014,0.325)); +#12153 = VECTOR('',#12154,1.); +#12154 = DIRECTION('',(0.E+000,-1.)); +#12155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12156 = PCURVE('',#11569,#12157); +#12157 = DEFINITIONAL_REPRESENTATION('',(#12158),#12162); +#12158 = LINE('',#12159,#12160); +#12159 = CARTESIAN_POINT('',(2.84217094304E-014,0.E+000)); +#12160 = VECTOR('',#12161,1.); +#12161 = DIRECTION('',(0.E+000,-1.)); +#12162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12163 = ADVANCED_FACE('',(#12164),#11569,.T.); +#12164 = FACE_BOUND('',#12165,.T.); +#12165 = EDGE_LOOP('',(#12166,#12167,#12190,#12211,#12212,#12213,#12214, + #12215)); +#12166 = ORIENTED_EDGE('',*,*,#12143,.T.); +#12167 = ORIENTED_EDGE('',*,*,#12168,.T.); +#12168 = EDGE_CURVE('',#12121,#12169,#12171,.T.); +#12169 = VERTEX_POINT('',#12170); +#12170 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056, 4.766421000566E-003)); -#9779 = SURFACE_CURVE('',#9780,(#9784,#9791),.PCURVE_S1.); -#9780 = LINE('',#9781,#9782); -#9781 = CARTESIAN_POINT('',(-0.3303435002,-1.367220815637, +#12171 = SURFACE_CURVE('',#12172,(#12176,#12183),.PCURVE_S1.); +#12172 = LINE('',#12173,#12174); +#12173 = CARTESIAN_POINT('',(-0.3303435002,-1.367220815637, 4.766421000566E-003)); -#9782 = VECTOR('',#9783,1.); -#9783 = DIRECTION('',(6.982425754889E-070,-1.,8.405946365462E-042)); -#9784 = PCURVE('',#9177,#9785); -#9785 = DEFINITIONAL_REPRESENTATION('',(#9786),#9790); -#9786 = LINE('',#9787,#9788); -#9787 = CARTESIAN_POINT('',(0.199779225581,-0.325)); -#9788 = VECTOR('',#9789,1.); -#9789 = DIRECTION('',(1.,8.405946365462E-042)); -#9790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9791 = PCURVE('',#9637,#9792); -#9792 = DEFINITIONAL_REPRESENTATION('',(#9793),#9797); -#9793 = LINE('',#9794,#9795); -#9794 = CARTESIAN_POINT('',(-0.325,2.269288370339E-070)); -#9795 = VECTOR('',#9796,1.); -#9796 = DIRECTION('',(-3.525121835561E-086,-1.)); -#9797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#12174 = VECTOR('',#12175,1.); +#12175 = DIRECTION('',(6.982425754889E-070,-1.,8.405946365462E-042)); +#12176 = PCURVE('',#11569,#12177); +#12177 = DEFINITIONAL_REPRESENTATION('',(#12178),#12182); +#12178 = LINE('',#12179,#12180); +#12179 = CARTESIAN_POINT('',(0.199779225581,-0.325)); +#12180 = VECTOR('',#12181,1.); +#12181 = DIRECTION('',(1.,8.405946365462E-042)); +#12182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12183 = PCURVE('',#12029,#12184); +#12184 = DEFINITIONAL_REPRESENTATION('',(#12185),#12189); +#12185 = LINE('',#12186,#12187); +#12186 = CARTESIAN_POINT('',(-0.325,2.269288370339E-070)); +#12187 = VECTOR('',#12188,1.); +#12188 = DIRECTION('',(-3.525121835561E-086,-1.)); +#12189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#9798 = ORIENTED_EDGE('',*,*,#9799,.F.); -#9799 = EDGE_CURVE('',#9442,#9777,#9800,.T.); -#9800 = SURFACE_CURVE('',#9801,(#9805,#9812),.PCURVE_S1.); -#9801 = LINE('',#9802,#9803); -#9802 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056, +#12190 = ORIENTED_EDGE('',*,*,#12191,.F.); +#12191 = EDGE_CURVE('',#11834,#12169,#12192,.T.); +#12192 = SURFACE_CURVE('',#12193,(#12197,#12204),.PCURVE_S1.); +#12193 = LINE('',#12194,#12195); +#12194 = CARTESIAN_POINT('',(-0.3303435002,-1.442441590056, 4.766421000566E-003)); -#9803 = VECTOR('',#9804,1.); -#9804 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9805 = PCURVE('',#9177,#9806); -#9806 = DEFINITIONAL_REPRESENTATION('',(#9807),#9811); -#9807 = LINE('',#9808,#9809); -#9808 = CARTESIAN_POINT('',(0.275,-0.325)); -#9809 = VECTOR('',#9810,1.); -#9810 = DIRECTION('',(0.E+000,-1.)); -#9811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9812 = PCURVE('',#9457,#9813); -#9813 = DEFINITIONAL_REPRESENTATION('',(#9814),#9818); -#9814 = LINE('',#9815,#9816); -#9815 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#9816 = VECTOR('',#9817,1.); -#9817 = DIRECTION('',(0.E+000,-1.)); -#9818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9819 = ORIENTED_EDGE('',*,*,#9574,.T.); -#9820 = ORIENTED_EDGE('',*,*,#9161,.T.); -#9821 = ORIENTED_EDGE('',*,*,#9266,.T.); -#9822 = ORIENTED_EDGE('',*,*,#9336,.T.); -#9823 = ORIENTED_EDGE('',*,*,#9412,.T.); -#9824 = ADVANCED_FACE('',(#9825),#9457,.T.); -#9825 = FACE_BOUND('',#9826,.T.); -#9826 = EDGE_LOOP('',(#9827,#9828,#9829,#9852)); -#9827 = ORIENTED_EDGE('',*,*,#9439,.T.); -#9828 = ORIENTED_EDGE('',*,*,#9799,.T.); -#9829 = ORIENTED_EDGE('',*,*,#9830,.T.); -#9830 = EDGE_CURVE('',#9777,#9831,#9833,.T.); -#9831 = VERTEX_POINT('',#9832); -#9832 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, +#12195 = VECTOR('',#12196,1.); +#12196 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12197 = PCURVE('',#11569,#12198); +#12198 = DEFINITIONAL_REPRESENTATION('',(#12199),#12203); +#12199 = LINE('',#12200,#12201); +#12200 = CARTESIAN_POINT('',(0.275,-0.325)); +#12201 = VECTOR('',#12202,1.); +#12202 = DIRECTION('',(0.E+000,-1.)); +#12203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12204 = PCURVE('',#11849,#12205); +#12205 = DEFINITIONAL_REPRESENTATION('',(#12206),#12210); +#12206 = LINE('',#12207,#12208); +#12207 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#12208 = VECTOR('',#12209,1.); +#12209 = DIRECTION('',(0.E+000,-1.)); +#12210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12211 = ORIENTED_EDGE('',*,*,#11966,.T.); +#12212 = ORIENTED_EDGE('',*,*,#11553,.T.); +#12213 = ORIENTED_EDGE('',*,*,#11658,.T.); +#12214 = ORIENTED_EDGE('',*,*,#11728,.T.); +#12215 = ORIENTED_EDGE('',*,*,#11804,.T.); +#12216 = ADVANCED_FACE('',(#12217),#11849,.T.); +#12217 = FACE_BOUND('',#12218,.T.); +#12218 = EDGE_LOOP('',(#12219,#12220,#12221,#12244)); +#12219 = ORIENTED_EDGE('',*,*,#11831,.T.); +#12220 = ORIENTED_EDGE('',*,*,#12191,.T.); +#12221 = ORIENTED_EDGE('',*,*,#12222,.T.); +#12222 = EDGE_CURVE('',#12169,#12223,#12225,.T.); +#12223 = VERTEX_POINT('',#12224); +#12224 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, 4.766421000551E-003)); -#9833 = SURFACE_CURVE('',#9834,(#9838,#9845),.PCURVE_S1.); -#9834 = LINE('',#9835,#9836); -#9835 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.442441590056, +#12225 = SURFACE_CURVE('',#12226,(#12230,#12237),.PCURVE_S1.); +#12226 = LINE('',#12227,#12228); +#12227 = CARTESIAN_POINT('',(-5.343500199743E-003,-1.442441590056, 4.766421000566E-003)); -#9836 = VECTOR('',#9837,1.); -#9837 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); -#9838 = PCURVE('',#9457,#9839); -#9839 = DEFINITIONAL_REPRESENTATION('',(#9840),#9844); -#9840 = LINE('',#9841,#9842); -#9841 = CARTESIAN_POINT('',(0.125,0.E+000)); -#9842 = VECTOR('',#9843,1.); -#9843 = DIRECTION('',(1.,-8.306531413975E-029)); -#9844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9845 = PCURVE('',#9637,#9846); -#9846 = DEFINITIONAL_REPRESENTATION('',(#9847),#9851); -#9847 = LINE('',#9848,#9849); -#9848 = CARTESIAN_POINT('',(0.E+000,-7.522077441911E-002)); -#9849 = VECTOR('',#9850,1.); -#9850 = DIRECTION('',(1.,1.295058128893E-085)); -#9851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9852 = ORIENTED_EDGE('',*,*,#9853,.T.); -#9853 = EDGE_CURVE('',#9831,#9440,#9854,.T.); -#9854 = SURFACE_CURVE('',#9855,(#9859,#9866),.PCURVE_S1.); -#9855 = LINE('',#9856,#9857); -#9856 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, +#12228 = VECTOR('',#12229,1.); +#12229 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); +#12230 = PCURVE('',#11849,#12231); +#12231 = DEFINITIONAL_REPRESENTATION('',(#12232),#12236); +#12232 = LINE('',#12233,#12234); +#12233 = CARTESIAN_POINT('',(0.125,0.E+000)); +#12234 = VECTOR('',#12235,1.); +#12235 = DIRECTION('',(1.,-8.306531413975E-029)); +#12236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12237 = PCURVE('',#12029,#12238); +#12238 = DEFINITIONAL_REPRESENTATION('',(#12239),#12243); +#12239 = LINE('',#12240,#12241); +#12240 = CARTESIAN_POINT('',(0.E+000,-7.522077441911E-002)); +#12241 = VECTOR('',#12242,1.); +#12242 = DIRECTION('',(1.,1.295058128893E-085)); +#12243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12244 = ORIENTED_EDGE('',*,*,#12245,.T.); +#12245 = EDGE_CURVE('',#12223,#11832,#12246,.T.); +#12246 = SURFACE_CURVE('',#12247,(#12251,#12258),.PCURVE_S1.); +#12247 = LINE('',#12248,#12249); +#12248 = CARTESIAN_POINT('',(-0.1303435002,-1.442441590056, 4.766421000566E-003)); -#9857 = VECTOR('',#9858,1.); -#9858 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#9859 = PCURVE('',#9457,#9860); -#9860 = DEFINITIONAL_REPRESENTATION('',(#9861),#9865); -#9861 = LINE('',#9862,#9863); -#9862 = CARTESIAN_POINT('',(0.E+000,-2.602085213965E-017)); -#9863 = VECTOR('',#9864,1.); -#9864 = DIRECTION('',(-1.624097681737E-013,1.)); -#9865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9866 = PCURVE('',#9490,#9867); -#9867 = DEFINITIONAL_REPRESENTATION('',(#9868),#9871); -#9868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#9869,#9870),.UNSPECIFIED.,.F., - .F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#9869 = CARTESIAN_POINT('',(3.14159265359,-1.520571862867E-014)); -#9870 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#9871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9872 = ADVANCED_FACE('',(#9873),#9490,.F.); -#9873 = FACE_BOUND('',#9874,.F.); -#9874 = EDGE_LOOP('',(#9875,#9876,#9901,#9902)); -#9875 = ORIENTED_EDGE('',*,*,#9599,.T.); -#9876 = ORIENTED_EDGE('',*,*,#9877,.F.); -#9877 = EDGE_CURVE('',#9831,#9600,#9878,.T.); -#9878 = SURFACE_CURVE('',#9879,(#9884,#9890),.PCURVE_S1.); -#9879 = CIRCLE('',#9880,0.125); -#9880 = AXIS2_PLACEMENT_3D('',#9881,#9882,#9883); -#9881 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, +#12249 = VECTOR('',#12250,1.); +#12250 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#12251 = PCURVE('',#11849,#12252); +#12252 = DEFINITIONAL_REPRESENTATION('',(#12253),#12257); +#12253 = LINE('',#12254,#12255); +#12254 = CARTESIAN_POINT('',(0.E+000,-2.602085213965E-017)); +#12255 = VECTOR('',#12256,1.); +#12256 = DIRECTION('',(-1.624097681737E-013,1.)); +#12257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12258 = PCURVE('',#11882,#12259); +#12259 = DEFINITIONAL_REPRESENTATION('',(#12260),#12263); +#12260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12261,#12262),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); +#12261 = CARTESIAN_POINT('',(3.14159265359,-1.520571862867E-014)); +#12262 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#12263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12264 = ADVANCED_FACE('',(#12265),#11882,.F.); +#12265 = FACE_BOUND('',#12266,.F.); +#12266 = EDGE_LOOP('',(#12267,#12268,#12293,#12294)); +#12267 = ORIENTED_EDGE('',*,*,#11991,.T.); +#12268 = ORIENTED_EDGE('',*,*,#12269,.F.); +#12269 = EDGE_CURVE('',#12223,#11992,#12270,.T.); +#12270 = SURFACE_CURVE('',#12271,(#12276,#12282),.PCURVE_S1.); +#12271 = CIRCLE('',#12272,0.125); +#12272 = AXIS2_PLACEMENT_3D('',#12273,#12274,#12275); +#12273 = CARTESIAN_POINT('',(-5.343500199736E-003,-1.442441590056, 4.766421000556E-003)); -#9882 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#9883 = DIRECTION('',(1.,-5.027572966497E-044,1.624097681737E-013)); -#9884 = PCURVE('',#9490,#9885); -#9885 = DEFINITIONAL_REPRESENTATION('',(#9886),#9889); -#9886 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#9887,#9888),.UNSPECIFIED.,.F., - .F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#9887 = CARTESIAN_POINT('',(3.14159265359,-3.043832547123E-014)); -#9888 = CARTESIAN_POINT('',(0.E+000,-3.043745810949E-014)); -#9889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9890 = PCURVE('',#9637,#9891); -#9891 = DEFINITIONAL_REPRESENTATION('',(#9892),#9900); -#9892 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#9893,#9894,#9895,#9896, -#9897,#9898,#9899),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#9893 = CARTESIAN_POINT('',(0.125,-7.522077441911E-002)); -#9894 = CARTESIAN_POINT('',(0.125,-0.291727125365)); -#9895 = CARTESIAN_POINT('',(-6.249999999999E-002,-0.183473949892)); -#9896 = CARTESIAN_POINT('',(-0.25,-7.522077441911E-002)); -#9897 = CARTESIAN_POINT('',(-6.249999999999E-002,3.303240105395E-002)); -#9898 = CARTESIAN_POINT('',(0.125,0.141285576527)); -#9899 = CARTESIAN_POINT('',(0.125,-7.522077441911E-002)); -#9900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9901 = ORIENTED_EDGE('',*,*,#9853,.T.); -#9902 = ORIENTED_EDGE('',*,*,#9469,.T.); -#9903 = ADVANCED_FACE('',(#9904),#9637,.F.); -#9904 = FACE_BOUND('',#9905,.T.); -#9905 = EDGE_LOOP('',(#9906,#9907,#9908,#9909,#9910,#9911)); -#9906 = ORIENTED_EDGE('',*,*,#9830,.F.); -#9907 = ORIENTED_EDGE('',*,*,#9776,.F.); -#9908 = ORIENTED_EDGE('',*,*,#9728,.F.); -#9909 = ORIENTED_EDGE('',*,*,#9702,.F.); -#9910 = ORIENTED_EDGE('',*,*,#9621,.F.); -#9911 = ORIENTED_EDGE('',*,*,#9877,.F.); -#9912 = MANIFOLD_SOLID_BREP('',#9913); -#9913 = CLOSED_SHELL('',(#9914,#10132,#10208,#10318,#10389,#10438,#10516 - ,#10675,#10750,#10803,#10852,#10905,#10953,#11007)); -#9914 = ADVANCED_FACE('',(#9915),#9930,.T.); -#9915 = FACE_BOUND('',#9916,.T.); -#9916 = EDGE_LOOP('',(#9917,#9979,#10029,#10084)); -#9917 = ORIENTED_EDGE('',*,*,#9918,.F.); -#9918 = EDGE_CURVE('',#9919,#9921,#9923,.T.); -#9919 = VERTEX_POINT('',#9920); -#9920 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, +#12274 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#12275 = DIRECTION('',(1.,-5.027572966497E-044,1.624097681737E-013)); +#12276 = PCURVE('',#11882,#12277); +#12277 = DEFINITIONAL_REPRESENTATION('',(#12278),#12281); +#12278 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12279,#12280),.UNSPECIFIED., + .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); +#12279 = CARTESIAN_POINT('',(3.14159265359,-3.043832547123E-014)); +#12280 = CARTESIAN_POINT('',(0.E+000,-3.043745810949E-014)); +#12281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12282 = PCURVE('',#12029,#12283); +#12283 = DEFINITIONAL_REPRESENTATION('',(#12284),#12292); +#12284 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#12285,#12286,#12287,#12288 + ,#12289,#12290,#12291),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#12285 = CARTESIAN_POINT('',(0.125,-7.522077441911E-002)); +#12286 = CARTESIAN_POINT('',(0.125,-0.291727125365)); +#12287 = CARTESIAN_POINT('',(-6.249999999999E-002,-0.183473949892)); +#12288 = CARTESIAN_POINT('',(-0.25,-7.522077441911E-002)); +#12289 = CARTESIAN_POINT('',(-6.249999999999E-002,3.303240105395E-002)); +#12290 = CARTESIAN_POINT('',(0.125,0.141285576527)); +#12291 = CARTESIAN_POINT('',(0.125,-7.522077441911E-002)); +#12292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12293 = ORIENTED_EDGE('',*,*,#12245,.T.); +#12294 = ORIENTED_EDGE('',*,*,#11861,.T.); +#12295 = ADVANCED_FACE('',(#12296),#12029,.F.); +#12296 = FACE_BOUND('',#12297,.T.); +#12297 = EDGE_LOOP('',(#12298,#12299,#12300,#12301,#12302,#12303)); +#12298 = ORIENTED_EDGE('',*,*,#12222,.F.); +#12299 = ORIENTED_EDGE('',*,*,#12168,.F.); +#12300 = ORIENTED_EDGE('',*,*,#12120,.F.); +#12301 = ORIENTED_EDGE('',*,*,#12094,.F.); +#12302 = ORIENTED_EDGE('',*,*,#12013,.F.); +#12303 = ORIENTED_EDGE('',*,*,#12269,.F.); +#12304 = MANIFOLD_SOLID_BREP('',#12305); +#12305 = CLOSED_SHELL('',(#12306,#12524,#12600,#12710,#12781,#12830, + #12908,#13067,#13142,#13195,#13244,#13297,#13345,#13399)); +#12306 = ADVANCED_FACE('',(#12307),#12322,.T.); +#12307 = FACE_BOUND('',#12308,.T.); +#12308 = EDGE_LOOP('',(#12309,#12371,#12421,#12476)); +#12309 = ORIENTED_EDGE('',*,*,#12310,.F.); +#12310 = EDGE_CURVE('',#12311,#12313,#12315,.T.); +#12311 = VERTEX_POINT('',#12312); +#12312 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 0.329766421001)); -#9921 = VERTEX_POINT('',#9922); -#9922 = CARTESIAN_POINT('',(0.142558494378,0.182558409944,0.329766421001 - )); -#9923 = SURFACE_CURVE('',#9924,(#9929,#9963),.PCURVE_S1.); -#9924 = CIRCLE('',#9925,0.15); -#9925 = AXIS2_PLACEMENT_3D('',#9926,#9927,#9928); -#9926 = CARTESIAN_POINT('',(-5.343500200012E-003,0.207558409944, +#12313 = VERTEX_POINT('',#12314); +#12314 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, + 0.329766421001)); +#12315 = SURFACE_CURVE('',#12316,(#12321,#12355),.PCURVE_S1.); +#12316 = CIRCLE('',#12317,0.15); +#12317 = AXIS2_PLACEMENT_3D('',#12318,#12319,#12320); +#12318 = CARTESIAN_POINT('',(-5.343500200012E-003,0.207558409944, 0.329766421001)); -#9927 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#9928 = DIRECTION('',(-1.,2.314804904035E-042,-1.624097681737E-013)); -#9929 = PCURVE('',#9930,#9935); -#9930 = CYLINDRICAL_SURFACE('',#9931,0.15); -#9931 = AXIS2_PLACEMENT_3D('',#9932,#9933,#9934); -#9932 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, +#12319 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#12320 = DIRECTION('',(-1.,2.314804904035E-042,-1.624097681737E-013)); +#12321 = PCURVE('',#12322,#12327); +#12322 = CYLINDRICAL_SURFACE('',#12323,0.15); +#12323 = AXIS2_PLACEMENT_3D('',#12324,#12325,#12326); +#12324 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, 4.766421000566E-003)); -#9933 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#9934 = DIRECTION('',(-1.,-5.409413345169E-045,-1.624097681737E-013)); -#9935 = DEFINITIONAL_REPRESENTATION('',(#9936),#9962); -#9936 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#9937,#9938,#9939,#9940,#9941, - #9942,#9943,#9944,#9945,#9946,#9947,#9948,#9949,#9950,#9951,#9952, - #9953,#9954,#9955,#9956,#9957,#9958,#9959,#9960,#9961), - .UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4), - (0.16744807922,0.295025192636,0.422602306052,0.550179419468, - 0.677756532883,0.805333646299,0.932910759715,1.060487873131, - 1.188064986547,1.315642099963,1.443219213379,1.570796326795, - 1.698373440211,1.825950553627,1.953527667043,2.081104780459, - 2.208681893875,2.336259007291,2.463836120707,2.591413234123, - 2.718990347539,2.846567460954,2.97414457437),.QUASI_UNIFORM_KNOTS.); -#9937 = CARTESIAN_POINT('',(6.11573722796,-0.325)); -#9938 = CARTESIAN_POINT('',(6.073211523488,-0.325)); -#9939 = CARTESIAN_POINT('',(5.988160114544,-0.325)); -#9940 = CARTESIAN_POINT('',(5.860583001128,-0.325)); -#9941 = CARTESIAN_POINT('',(5.733005887712,-0.325)); -#9942 = CARTESIAN_POINT('',(5.605428774296,-0.325)); -#9943 = CARTESIAN_POINT('',(5.47785166088,-0.325)); -#9944 = CARTESIAN_POINT('',(5.350274547464,-0.325)); -#9945 = CARTESIAN_POINT('',(5.222697434048,-0.325)); -#9946 = CARTESIAN_POINT('',(5.095120320632,-0.325)); -#9947 = CARTESIAN_POINT('',(4.967543207216,-0.325)); -#9948 = CARTESIAN_POINT('',(4.8399660938,-0.325)); -#9949 = CARTESIAN_POINT('',(4.712388980385,-0.325)); -#9950 = CARTESIAN_POINT('',(4.584811866969,-0.325)); -#9951 = CARTESIAN_POINT('',(4.457234753553,-0.325)); -#9952 = CARTESIAN_POINT('',(4.329657640137,-0.325)); -#9953 = CARTESIAN_POINT('',(4.202080526721,-0.325)); -#9954 = CARTESIAN_POINT('',(4.074503413305,-0.325)); -#9955 = CARTESIAN_POINT('',(3.946926299889,-0.325)); -#9956 = CARTESIAN_POINT('',(3.819349186473,-0.325)); -#9957 = CARTESIAN_POINT('',(3.691772073057,-0.325)); -#9958 = CARTESIAN_POINT('',(3.564194959641,-0.325)); -#9959 = CARTESIAN_POINT('',(3.436617846225,-0.325)); -#9960 = CARTESIAN_POINT('',(3.351566437281,-0.325)); -#9961 = CARTESIAN_POINT('',(3.309040732809,-0.325)); -#9962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9963 = PCURVE('',#9964,#9969); -#9964 = PLANE('',#9965); -#9965 = AXIS2_PLACEMENT_3D('',#9966,#9967,#9968); -#9966 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#12325 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#12326 = DIRECTION('',(-1.,-5.409413345169E-045,-1.624097681737E-013)); +#12327 = DEFINITIONAL_REPRESENTATION('',(#12328),#12354); +#12328 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12329,#12330,#12331,#12332, + #12333,#12334,#12335,#12336,#12337,#12338,#12339,#12340,#12341, + #12342,#12343,#12344,#12345,#12346,#12347,#12348,#12349,#12350, + #12351,#12352,#12353),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(0.16744807922,0.295025192636,0.422602306052 + ,0.550179419468,0.677756532883,0.805333646299,0.932910759715, + 1.060487873131,1.188064986547,1.315642099963,1.443219213379, + 1.570796326795,1.698373440211,1.825950553627,1.953527667043, + 2.081104780459,2.208681893875,2.336259007291,2.463836120707, + 2.591413234123,2.718990347539,2.846567460954,2.97414457437), + .QUASI_UNIFORM_KNOTS.); +#12329 = CARTESIAN_POINT('',(6.11573722796,-0.325)); +#12330 = CARTESIAN_POINT('',(6.073211523488,-0.325)); +#12331 = CARTESIAN_POINT('',(5.988160114544,-0.325)); +#12332 = CARTESIAN_POINT('',(5.860583001128,-0.325)); +#12333 = CARTESIAN_POINT('',(5.733005887712,-0.325)); +#12334 = CARTESIAN_POINT('',(5.605428774296,-0.325)); +#12335 = CARTESIAN_POINT('',(5.47785166088,-0.325)); +#12336 = CARTESIAN_POINT('',(5.350274547464,-0.325)); +#12337 = CARTESIAN_POINT('',(5.222697434048,-0.325)); +#12338 = CARTESIAN_POINT('',(5.095120320632,-0.325)); +#12339 = CARTESIAN_POINT('',(4.967543207216,-0.325)); +#12340 = CARTESIAN_POINT('',(4.8399660938,-0.325)); +#12341 = CARTESIAN_POINT('',(4.712388980385,-0.325)); +#12342 = CARTESIAN_POINT('',(4.584811866969,-0.325)); +#12343 = CARTESIAN_POINT('',(4.457234753553,-0.325)); +#12344 = CARTESIAN_POINT('',(4.329657640137,-0.325)); +#12345 = CARTESIAN_POINT('',(4.202080526721,-0.325)); +#12346 = CARTESIAN_POINT('',(4.074503413305,-0.325)); +#12347 = CARTESIAN_POINT('',(3.946926299889,-0.325)); +#12348 = CARTESIAN_POINT('',(3.819349186473,-0.325)); +#12349 = CARTESIAN_POINT('',(3.691772073057,-0.325)); +#12350 = CARTESIAN_POINT('',(3.564194959641,-0.325)); +#12351 = CARTESIAN_POINT('',(3.436617846225,-0.325)); +#12352 = CARTESIAN_POINT('',(3.351566437281,-0.325)); +#12353 = CARTESIAN_POINT('',(3.309040732809,-0.325)); +#12354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12355 = PCURVE('',#12356,#12361); +#12356 = PLANE('',#12357); +#12357 = AXIS2_PLACEMENT_3D('',#12358,#12359,#12360); +#12358 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 0.329766421001)); -#9967 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#9968 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#9969 = DEFINITIONAL_REPRESENTATION('',(#9970),#9978); -#9970 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#9971,#9972,#9973,#9974, -#9975,#9976,#9977),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2 - ,2,2,2,1),(-2.094395102393,0.E+000,2.094395102393,4.188790204786, -6.28318530718,8.377580409573),.UNSPECIFIED.) CURVE() -GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5, -1.,0.5,1.)) REPRESENTATION_ITEM('') ); -#9971 = CARTESIAN_POINT('',(0.475,0.275)); -#9972 = CARTESIAN_POINT('',(0.475,1.519237886455E-002)); -#9973 = CARTESIAN_POINT('',(0.25,0.145096189432)); -#9974 = CARTESIAN_POINT('',(2.500000000006E-002,0.275)); -#9975 = CARTESIAN_POINT('',(0.25,0.404903810568)); -#9976 = CARTESIAN_POINT('',(0.475,0.534807621135)); -#9977 = CARTESIAN_POINT('',(0.475,0.275)); -#9978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#9979 = ORIENTED_EDGE('',*,*,#9980,.F.); -#9980 = EDGE_CURVE('',#9981,#9919,#9983,.T.); -#9981 = VERTEX_POINT('',#9982); -#9982 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, +#12359 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12360 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#12361 = DEFINITIONAL_REPRESENTATION('',(#12362),#12370); +#12362 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#12363,#12364,#12365,#12366 + ,#12367,#12368,#12369),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#12363 = CARTESIAN_POINT('',(0.475,0.275)); +#12364 = CARTESIAN_POINT('',(0.475,1.519237886455E-002)); +#12365 = CARTESIAN_POINT('',(0.25,0.145096189432)); +#12366 = CARTESIAN_POINT('',(2.500000000006E-002,0.275)); +#12367 = CARTESIAN_POINT('',(0.25,0.404903810568)); +#12368 = CARTESIAN_POINT('',(0.475,0.534807621135)); +#12369 = CARTESIAN_POINT('',(0.475,0.275)); +#12370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12371 = ORIENTED_EDGE('',*,*,#12372,.F.); +#12372 = EDGE_CURVE('',#12373,#12311,#12375,.T.); +#12373 = VERTEX_POINT('',#12374); +#12374 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 2.976642100058E-002)); -#9983 = SURFACE_CURVE('',#9984,(#9988,#10017),.PCURVE_S1.); -#9984 = LINE('',#9985,#9986); -#9985 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, +#12375 = SURFACE_CURVE('',#12376,(#12380,#12409),.PCURVE_S1.); +#12376 = LINE('',#12377,#12378); +#12377 = CARTESIAN_POINT('',(-0.153245494777,0.182558409944, 0.329766421001)); -#9986 = VECTOR('',#9987,1.); -#9987 = DIRECTION('',(0.E+000,0.E+000,1.)); -#9988 = PCURVE('',#9930,#9989); -#9989 = DEFINITIONAL_REPRESENTATION('',(#9990),#10016); -#9990 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#9991,#9992,#9993,#9994,#9995, - #9996,#9997,#9998,#9999,#10000,#10001,#10002,#10003,#10004,#10005, - #10006,#10007,#10008,#10009,#10010,#10011,#10012,#10013,#10014, - #10015),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 - ,1,1,1,4),(-0.3,-0.286363636364,-0.272727272727,-0.259090909091, - -0.245454545455,-0.231818181818,-0.218181818182,-0.204545454545, - -0.190909090909,-0.177272727273,-0.163636363636,-0.15, - -0.136363636364,-0.122727272727,-0.109090909091,-9.545454545455E-002 - ,-8.181818181819E-002,-6.818181818183E-002,-5.454545454547E-002, - -4.09090909091E-002,-2.727272727274E-002,-1.363636363638E-002, - -1.809663530139E-014),.UNSPECIFIED.); -#9991 = CARTESIAN_POINT('',(6.11573722796,-2.500000000004E-002)); -#9992 = CARTESIAN_POINT('',(6.11573722796,-2.95454545455E-002)); -#9993 = CARTESIAN_POINT('',(6.11573722796,-3.86363636364E-002)); -#9994 = CARTESIAN_POINT('',(6.11573722796,-5.227272727277E-002)); -#9995 = CARTESIAN_POINT('',(6.11573722796,-6.590909090913E-002)); -#9996 = CARTESIAN_POINT('',(6.11573722796,-7.954545454549E-002)); -#9997 = CARTESIAN_POINT('',(6.11573722796,-9.318181818185E-002)); -#9998 = CARTESIAN_POINT('',(6.11573722796,-0.106818181818)); -#9999 = CARTESIAN_POINT('',(6.11573722796,-0.120454545455)); -#10000 = CARTESIAN_POINT('',(6.11573722796,-0.134090909091)); -#10001 = CARTESIAN_POINT('',(6.11573722796,-0.147727272727)); -#10002 = CARTESIAN_POINT('',(6.11573722796,-0.161363636364)); -#10003 = CARTESIAN_POINT('',(6.11573722796,-0.175)); -#10004 = CARTESIAN_POINT('',(6.11573722796,-0.188636363636)); -#10005 = CARTESIAN_POINT('',(6.11573722796,-0.202272727273)); -#10006 = CARTESIAN_POINT('',(6.11573722796,-0.215909090909)); -#10007 = CARTESIAN_POINT('',(6.11573722796,-0.229545454545)); -#10008 = CARTESIAN_POINT('',(6.11573722796,-0.243181818182)); -#10009 = CARTESIAN_POINT('',(6.11573722796,-0.256818181818)); -#10010 = CARTESIAN_POINT('',(6.11573722796,-0.270454545455)); -#10011 = CARTESIAN_POINT('',(6.11573722796,-0.284090909091)); -#10012 = CARTESIAN_POINT('',(6.11573722796,-0.297727272727)); -#10013 = CARTESIAN_POINT('',(6.11573722796,-0.311363636364)); -#10014 = CARTESIAN_POINT('',(6.11573722796,-0.320454545455)); -#10015 = CARTESIAN_POINT('',(6.11573722796,-0.325)); -#10016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10017 = PCURVE('',#10018,#10023); -#10018 = PLANE('',#10019); -#10019 = AXIS2_PLACEMENT_3D('',#10020,#10021,#10022); -#10020 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) - ); -#10021 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10022 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#10023 = DEFINITIONAL_REPRESENTATION('',(#10024),#10028); -#10024 = LINE('',#10025,#10026); -#10025 = CARTESIAN_POINT('',(-0.472901994578,0.E+000)); -#10026 = VECTOR('',#10027,1.); -#10027 = DIRECTION('',(0.E+000,1.)); -#10028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10029 = ORIENTED_EDGE('',*,*,#10030,.F.); -#10030 = EDGE_CURVE('',#10031,#9981,#10033,.T.); -#10031 = VERTEX_POINT('',#10032); -#10032 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, +#12378 = VECTOR('',#12379,1.); +#12379 = DIRECTION('',(0.E+000,0.E+000,1.)); +#12380 = PCURVE('',#12322,#12381); +#12381 = DEFINITIONAL_REPRESENTATION('',(#12382),#12408); +#12382 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12383,#12384,#12385,#12386, + #12387,#12388,#12389,#12390,#12391,#12392,#12393,#12394,#12395, + #12396,#12397,#12398,#12399,#12400,#12401,#12402,#12403,#12404, + #12405,#12406,#12407),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 + ,1,1,1,1,1,1,1,1,1,1,4),(-0.3,-0.286363636364,-0.272727272727, + -0.259090909091,-0.245454545455,-0.231818181818,-0.218181818182, + -0.204545454545,-0.190909090909,-0.177272727273,-0.163636363636, + -0.15,-0.136363636364,-0.122727272727,-0.109090909091, + -9.545454545455E-002,-8.181818181819E-002,-6.818181818183E-002, + -5.454545454547E-002,-4.09090909091E-002,-2.727272727274E-002, + -1.363636363638E-002,-1.809663530139E-014),.UNSPECIFIED.); +#12383 = CARTESIAN_POINT('',(6.11573722796,-2.500000000004E-002)); +#12384 = CARTESIAN_POINT('',(6.11573722796,-2.95454545455E-002)); +#12385 = CARTESIAN_POINT('',(6.11573722796,-3.86363636364E-002)); +#12386 = CARTESIAN_POINT('',(6.11573722796,-5.227272727277E-002)); +#12387 = CARTESIAN_POINT('',(6.11573722796,-6.590909090913E-002)); +#12388 = CARTESIAN_POINT('',(6.11573722796,-7.954545454549E-002)); +#12389 = CARTESIAN_POINT('',(6.11573722796,-9.318181818185E-002)); +#12390 = CARTESIAN_POINT('',(6.11573722796,-0.106818181818)); +#12391 = CARTESIAN_POINT('',(6.11573722796,-0.120454545455)); +#12392 = CARTESIAN_POINT('',(6.11573722796,-0.134090909091)); +#12393 = CARTESIAN_POINT('',(6.11573722796,-0.147727272727)); +#12394 = CARTESIAN_POINT('',(6.11573722796,-0.161363636364)); +#12395 = CARTESIAN_POINT('',(6.11573722796,-0.175)); +#12396 = CARTESIAN_POINT('',(6.11573722796,-0.188636363636)); +#12397 = CARTESIAN_POINT('',(6.11573722796,-0.202272727273)); +#12398 = CARTESIAN_POINT('',(6.11573722796,-0.215909090909)); +#12399 = CARTESIAN_POINT('',(6.11573722796,-0.229545454545)); +#12400 = CARTESIAN_POINT('',(6.11573722796,-0.243181818182)); +#12401 = CARTESIAN_POINT('',(6.11573722796,-0.256818181818)); +#12402 = CARTESIAN_POINT('',(6.11573722796,-0.270454545455)); +#12403 = CARTESIAN_POINT('',(6.11573722796,-0.284090909091)); +#12404 = CARTESIAN_POINT('',(6.11573722796,-0.297727272727)); +#12405 = CARTESIAN_POINT('',(6.11573722796,-0.311363636364)); +#12406 = CARTESIAN_POINT('',(6.11573722796,-0.320454545455)); +#12407 = CARTESIAN_POINT('',(6.11573722796,-0.325)); +#12408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12409 = PCURVE('',#12410,#12415); +#12410 = PLANE('',#12411); +#12411 = AXIS2_PLACEMENT_3D('',#12412,#12413,#12414); +#12412 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) + ); +#12413 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#12414 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#12415 = DEFINITIONAL_REPRESENTATION('',(#12416),#12420); +#12416 = LINE('',#12417,#12418); +#12417 = CARTESIAN_POINT('',(-0.472901994578,0.E+000)); +#12418 = VECTOR('',#12419,1.); +#12419 = DIRECTION('',(0.E+000,1.)); +#12420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12421 = ORIENTED_EDGE('',*,*,#12422,.F.); +#12422 = EDGE_CURVE('',#12423,#12373,#12425,.T.); +#12423 = VERTEX_POINT('',#12424); +#12424 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, 2.97664210006E-002)); -#10033 = SURFACE_CURVE('',#10034,(#10039,#10068),.PCURVE_S1.); -#10034 = CIRCLE('',#10035,0.15); -#10035 = AXIS2_PLACEMENT_3D('',#10036,#10037,#10038); -#10036 = CARTESIAN_POINT('',(-5.343500199964E-003,0.207558409944, +#12425 = SURFACE_CURVE('',#12426,(#12431,#12460),.PCURVE_S1.); +#12426 = CIRCLE('',#12427,0.15); +#12427 = AXIS2_PLACEMENT_3D('',#12428,#12429,#12430); +#12428 = CARTESIAN_POINT('',(-5.343500199964E-003,0.207558409944, 2.97664210006E-002)); -#10037 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#10038 = DIRECTION('',(-1.,8.739915935031E-044,-1.624097681737E-013)); -#10039 = PCURVE('',#9930,#10040); -#10040 = DEFINITIONAL_REPRESENTATION('',(#10041),#10067); -#10041 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#10042,#10043,#10044,#10045, - #10046,#10047,#10048,#10049,#10050,#10051,#10052,#10053,#10054, - #10055,#10056,#10057,#10058,#10059,#10060,#10061,#10062,#10063, - #10064,#10065,#10066),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#12429 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#12430 = DIRECTION('',(-1.,8.739915935031E-044,-1.624097681737E-013)); +#12431 = PCURVE('',#12322,#12432); +#12432 = DEFINITIONAL_REPRESENTATION('',(#12433),#12459); +#12433 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12434,#12435,#12436,#12437, + #12438,#12439,#12440,#12441,#12442,#12443,#12444,#12445,#12446, + #12447,#12448,#12449,#12450,#12451,#12452,#12453,#12454,#12455, + #12456,#12457,#12458),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.309040732809,3.436617846225, 3.564194959641,3.691772073057,3.819349186473,3.946926299889, 4.074503413305,4.202080526721,4.329657640137,4.457234753553, @@ -11871,73 +14860,73 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.095120320632,5.222697434048,5.350274547464,5.47785166088, 5.605428774296,5.733005887712,5.860583001128,5.988160114544, 6.11573722796),.QUASI_UNIFORM_KNOTS.); -#10042 = CARTESIAN_POINT('',(3.309040732809,-2.500000000004E-002)); -#10043 = CARTESIAN_POINT('',(3.351566437281,-2.500000000004E-002)); -#10044 = CARTESIAN_POINT('',(3.436617846225,-2.500000000004E-002)); -#10045 = CARTESIAN_POINT('',(3.564194959641,-2.500000000004E-002)); -#10046 = CARTESIAN_POINT('',(3.691772073057,-2.500000000004E-002)); -#10047 = CARTESIAN_POINT('',(3.819349186473,-2.500000000004E-002)); -#10048 = CARTESIAN_POINT('',(3.946926299889,-2.500000000004E-002)); -#10049 = CARTESIAN_POINT('',(4.074503413305,-2.500000000004E-002)); -#10050 = CARTESIAN_POINT('',(4.202080526721,-2.500000000004E-002)); -#10051 = CARTESIAN_POINT('',(4.329657640137,-2.500000000004E-002)); -#10052 = CARTESIAN_POINT('',(4.457234753553,-2.500000000004E-002)); -#10053 = CARTESIAN_POINT('',(4.584811866969,-2.500000000004E-002)); -#10054 = CARTESIAN_POINT('',(4.712388980385,-2.500000000004E-002)); -#10055 = CARTESIAN_POINT('',(4.839966093801,-2.500000000004E-002)); -#10056 = CARTESIAN_POINT('',(4.967543207216,-2.500000000004E-002)); -#10057 = CARTESIAN_POINT('',(5.095120320632,-2.500000000004E-002)); -#10058 = CARTESIAN_POINT('',(5.222697434048,-2.500000000004E-002)); -#10059 = CARTESIAN_POINT('',(5.350274547464,-2.500000000004E-002)); -#10060 = CARTESIAN_POINT('',(5.47785166088,-2.500000000004E-002)); -#10061 = CARTESIAN_POINT('',(5.605428774296,-2.500000000004E-002)); -#10062 = CARTESIAN_POINT('',(5.733005887712,-2.500000000004E-002)); -#10063 = CARTESIAN_POINT('',(5.860583001128,-2.500000000004E-002)); -#10064 = CARTESIAN_POINT('',(5.988160114544,-2.500000000004E-002)); -#10065 = CARTESIAN_POINT('',(6.073211523488,-2.500000000004E-002)); -#10066 = CARTESIAN_POINT('',(6.11573722796,-2.500000000004E-002)); -#10067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10068 = PCURVE('',#10069,#10074); -#10069 = PLANE('',#10070); -#10070 = AXIS2_PLACEMENT_3D('',#10071,#10072,#10073); -#10071 = CARTESIAN_POINT('',(-5.343500199887E-003,5.755840994421E-002, +#12434 = CARTESIAN_POINT('',(3.309040732809,-2.500000000004E-002)); +#12435 = CARTESIAN_POINT('',(3.351566437281,-2.500000000004E-002)); +#12436 = CARTESIAN_POINT('',(3.436617846225,-2.500000000004E-002)); +#12437 = CARTESIAN_POINT('',(3.564194959641,-2.500000000004E-002)); +#12438 = CARTESIAN_POINT('',(3.691772073057,-2.500000000004E-002)); +#12439 = CARTESIAN_POINT('',(3.819349186473,-2.500000000004E-002)); +#12440 = CARTESIAN_POINT('',(3.946926299889,-2.500000000004E-002)); +#12441 = CARTESIAN_POINT('',(4.074503413305,-2.500000000004E-002)); +#12442 = CARTESIAN_POINT('',(4.202080526721,-2.500000000004E-002)); +#12443 = CARTESIAN_POINT('',(4.329657640137,-2.500000000004E-002)); +#12444 = CARTESIAN_POINT('',(4.457234753553,-2.500000000004E-002)); +#12445 = CARTESIAN_POINT('',(4.584811866969,-2.500000000004E-002)); +#12446 = CARTESIAN_POINT('',(4.712388980385,-2.500000000004E-002)); +#12447 = CARTESIAN_POINT('',(4.839966093801,-2.500000000004E-002)); +#12448 = CARTESIAN_POINT('',(4.967543207216,-2.500000000004E-002)); +#12449 = CARTESIAN_POINT('',(5.095120320632,-2.500000000004E-002)); +#12450 = CARTESIAN_POINT('',(5.222697434048,-2.500000000004E-002)); +#12451 = CARTESIAN_POINT('',(5.350274547464,-2.500000000004E-002)); +#12452 = CARTESIAN_POINT('',(5.47785166088,-2.500000000004E-002)); +#12453 = CARTESIAN_POINT('',(5.605428774296,-2.500000000004E-002)); +#12454 = CARTESIAN_POINT('',(5.733005887712,-2.500000000004E-002)); +#12455 = CARTESIAN_POINT('',(5.860583001128,-2.500000000004E-002)); +#12456 = CARTESIAN_POINT('',(5.988160114544,-2.500000000004E-002)); +#12457 = CARTESIAN_POINT('',(6.073211523488,-2.500000000004E-002)); +#12458 = CARTESIAN_POINT('',(6.11573722796,-2.500000000004E-002)); +#12459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12460 = PCURVE('',#12461,#12466); +#12461 = PLANE('',#12462); +#12462 = AXIS2_PLACEMENT_3D('',#12463,#12464,#12465); +#12463 = CARTESIAN_POINT('',(-5.343500199887E-003,5.755840994421E-002, 2.976642100057E-002)); -#10072 = DIRECTION('',(0.E+000,0.E+000,1.)); -#10073 = DIRECTION('',(1.,0.E+000,0.E+000)); -#10074 = DEFINITIONAL_REPRESENTATION('',(#10075),#10083); -#10075 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#10076,#10077,#10078,#10079 - ,#10080,#10081,#10082),.UNSPECIFIED.,.F.,.F.) +#12464 = DIRECTION('',(0.E+000,0.E+000,1.)); +#12465 = DIRECTION('',(1.,0.E+000,0.E+000)); +#12466 = DEFINITIONAL_REPRESENTATION('',(#12467),#12475); +#12467 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#12468,#12469,#12470,#12471 + ,#12472,#12473,#12474),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#10076 = CARTESIAN_POINT('',(-0.15,0.15)); -#10077 = CARTESIAN_POINT('',(-0.15,0.409807621135)); -#10078 = CARTESIAN_POINT('',(7.499999999994E-002,0.279903810568)); -#10079 = CARTESIAN_POINT('',(0.3,0.15)); -#10080 = CARTESIAN_POINT('',(7.499999999994E-002,2.009618943225E-002)); -#10081 = CARTESIAN_POINT('',(-0.15,-0.109807621135)); -#10082 = CARTESIAN_POINT('',(-0.15,0.15)); -#10083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10084 = ORIENTED_EDGE('',*,*,#10085,.F.); -#10085 = EDGE_CURVE('',#9921,#10031,#10086,.T.); -#10086 = SURFACE_CURVE('',#10087,(#10091,#10120),.PCURVE_S1.); -#10087 = LINE('',#10088,#10089); -#10088 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, +#12468 = CARTESIAN_POINT('',(-0.15,0.15)); +#12469 = CARTESIAN_POINT('',(-0.15,0.409807621135)); +#12470 = CARTESIAN_POINT('',(7.499999999994E-002,0.279903810568)); +#12471 = CARTESIAN_POINT('',(0.3,0.15)); +#12472 = CARTESIAN_POINT('',(7.499999999994E-002,2.009618943225E-002)); +#12473 = CARTESIAN_POINT('',(-0.15,-0.109807621135)); +#12474 = CARTESIAN_POINT('',(-0.15,0.15)); +#12475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12476 = ORIENTED_EDGE('',*,*,#12477,.F.); +#12477 = EDGE_CURVE('',#12313,#12423,#12478,.T.); +#12478 = SURFACE_CURVE('',#12479,(#12483,#12512),.PCURVE_S1.); +#12479 = LINE('',#12480,#12481); +#12480 = CARTESIAN_POINT('',(0.142558494378,0.182558409944, 0.329766421001)); -#10089 = VECTOR('',#10090,1.); -#10090 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10091 = PCURVE('',#9930,#10092); -#10092 = DEFINITIONAL_REPRESENTATION('',(#10093),#10119); -#10093 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#10094,#10095,#10096,#10097, - #10098,#10099,#10100,#10101,#10102,#10103,#10104,#10105,#10106, - #10107,#10108,#10109,#10110,#10111,#10112,#10113,#10114,#10115, - #10116,#10117,#10118),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#12481 = VECTOR('',#12482,1.); +#12482 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12483 = PCURVE('',#12322,#12484); +#12484 = DEFINITIONAL_REPRESENTATION('',(#12485),#12511); +#12485 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12486,#12487,#12488,#12489, + #12490,#12491,#12492,#12493,#12494,#12495,#12496,#12497,#12498, + #12499,#12500,#12501,#12502,#12503,#12504,#12505,#12506,#12507, + #12508,#12509,#12510),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.809663530139E-014,1.363636363638E-002, 2.727272727274E-002,4.09090909091E-002,5.454545454546E-002, 6.818181818183E-002,8.181818181819E-002,9.545454545455E-002, @@ -11945,607 +14934,607 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#10094 = CARTESIAN_POINT('',(3.309040732809,-0.325)); -#10095 = CARTESIAN_POINT('',(3.309040732809,-0.320454545455)); -#10096 = CARTESIAN_POINT('',(3.309040732809,-0.311363636364)); -#10097 = CARTESIAN_POINT('',(3.309040732809,-0.297727272727)); -#10098 = CARTESIAN_POINT('',(3.309040732809,-0.284090909091)); -#10099 = CARTESIAN_POINT('',(3.309040732809,-0.270454545455)); -#10100 = CARTESIAN_POINT('',(3.309040732809,-0.256818181818)); -#10101 = CARTESIAN_POINT('',(3.309040732809,-0.243181818182)); -#10102 = CARTESIAN_POINT('',(3.309040732809,-0.229545454545)); -#10103 = CARTESIAN_POINT('',(3.309040732809,-0.215909090909)); -#10104 = CARTESIAN_POINT('',(3.309040732809,-0.202272727273)); -#10105 = CARTESIAN_POINT('',(3.309040732809,-0.188636363636)); -#10106 = CARTESIAN_POINT('',(3.309040732809,-0.175)); -#10107 = CARTESIAN_POINT('',(3.309040732809,-0.161363636364)); -#10108 = CARTESIAN_POINT('',(3.309040732809,-0.147727272727)); -#10109 = CARTESIAN_POINT('',(3.309040732809,-0.134090909091)); -#10110 = CARTESIAN_POINT('',(3.309040732809,-0.120454545455)); -#10111 = CARTESIAN_POINT('',(3.309040732809,-0.106818181818)); -#10112 = CARTESIAN_POINT('',(3.309040732809,-9.318181818181E-002)); -#10113 = CARTESIAN_POINT('',(3.309040732809,-7.954545454545E-002)); -#10114 = CARTESIAN_POINT('',(3.309040732809,-6.590909090909E-002)); -#10115 = CARTESIAN_POINT('',(3.309040732809,-5.227272727273E-002)); -#10116 = CARTESIAN_POINT('',(3.309040732809,-3.863636363637E-002)); -#10117 = CARTESIAN_POINT('',(3.309040732809,-2.954545454546E-002)); -#10118 = CARTESIAN_POINT('',(3.309040732809,-2.500000000001E-002)); -#10119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10120 = PCURVE('',#10121,#10126); -#10121 = PLANE('',#10122); -#10122 = AXIS2_PLACEMENT_3D('',#10123,#10124,#10125); -#10123 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) - ); -#10124 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10125 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#10126 = DEFINITIONAL_REPRESENTATION('',(#10127),#10131); -#10127 = LINE('',#10128,#10129); -#10128 = CARTESIAN_POINT('',(-0.177098005423,0.E+000)); -#10129 = VECTOR('',#10130,1.); -#10130 = DIRECTION('',(0.E+000,-1.)); -#10131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10132 = ADVANCED_FACE('',(#10133),#10018,.T.); -#10133 = FACE_BOUND('',#10134,.T.); -#10134 = EDGE_LOOP('',(#10135,#10136,#10159,#10187)); -#10135 = ORIENTED_EDGE('',*,*,#9980,.T.); -#10136 = ORIENTED_EDGE('',*,*,#10137,.F.); -#10137 = EDGE_CURVE('',#10138,#9919,#10140,.T.); -#10138 = VERTEX_POINT('',#10139); -#10139 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944,0.329766421001 +#12486 = CARTESIAN_POINT('',(3.309040732809,-0.325)); +#12487 = CARTESIAN_POINT('',(3.309040732809,-0.320454545455)); +#12488 = CARTESIAN_POINT('',(3.309040732809,-0.311363636364)); +#12489 = CARTESIAN_POINT('',(3.309040732809,-0.297727272727)); +#12490 = CARTESIAN_POINT('',(3.309040732809,-0.284090909091)); +#12491 = CARTESIAN_POINT('',(3.309040732809,-0.270454545455)); +#12492 = CARTESIAN_POINT('',(3.309040732809,-0.256818181818)); +#12493 = CARTESIAN_POINT('',(3.309040732809,-0.243181818182)); +#12494 = CARTESIAN_POINT('',(3.309040732809,-0.229545454545)); +#12495 = CARTESIAN_POINT('',(3.309040732809,-0.215909090909)); +#12496 = CARTESIAN_POINT('',(3.309040732809,-0.202272727273)); +#12497 = CARTESIAN_POINT('',(3.309040732809,-0.188636363636)); +#12498 = CARTESIAN_POINT('',(3.309040732809,-0.175)); +#12499 = CARTESIAN_POINT('',(3.309040732809,-0.161363636364)); +#12500 = CARTESIAN_POINT('',(3.309040732809,-0.147727272727)); +#12501 = CARTESIAN_POINT('',(3.309040732809,-0.134090909091)); +#12502 = CARTESIAN_POINT('',(3.309040732809,-0.120454545455)); +#12503 = CARTESIAN_POINT('',(3.309040732809,-0.106818181818)); +#12504 = CARTESIAN_POINT('',(3.309040732809,-9.318181818181E-002)); +#12505 = CARTESIAN_POINT('',(3.309040732809,-7.954545454545E-002)); +#12506 = CARTESIAN_POINT('',(3.309040732809,-6.590909090909E-002)); +#12507 = CARTESIAN_POINT('',(3.309040732809,-5.227272727273E-002)); +#12508 = CARTESIAN_POINT('',(3.309040732809,-3.863636363637E-002)); +#12509 = CARTESIAN_POINT('',(3.309040732809,-2.954545454546E-002)); +#12510 = CARTESIAN_POINT('',(3.309040732809,-2.500000000001E-002)); +#12511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12512 = PCURVE('',#12513,#12518); +#12513 = PLANE('',#12514); +#12514 = AXIS2_PLACEMENT_3D('',#12515,#12516,#12517); +#12515 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) + ); +#12516 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#12517 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#12518 = DEFINITIONAL_REPRESENTATION('',(#12519),#12523); +#12519 = LINE('',#12520,#12521); +#12520 = CARTESIAN_POINT('',(-0.177098005423,0.E+000)); +#12521 = VECTOR('',#12522,1.); +#12522 = DIRECTION('',(0.E+000,-1.)); +#12523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12524 = ADVANCED_FACE('',(#12525),#12410,.T.); +#12525 = FACE_BOUND('',#12526,.T.); +#12526 = EDGE_LOOP('',(#12527,#12528,#12551,#12579)); +#12527 = ORIENTED_EDGE('',*,*,#12372,.T.); +#12528 = ORIENTED_EDGE('',*,*,#12529,.F.); +#12529 = EDGE_CURVE('',#12530,#12311,#12532,.T.); +#12530 = VERTEX_POINT('',#12531); +#12531 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944,0.329766421001 )); -#10140 = SURFACE_CURVE('',#10141,(#10145,#10152),.PCURVE_S1.); -#10141 = LINE('',#10142,#10143); -#10142 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) - ); -#10143 = VECTOR('',#10144,1.); -#10144 = DIRECTION('',(1.,0.E+000,0.E+000)); -#10145 = PCURVE('',#10018,#10146); -#10146 = DEFINITIONAL_REPRESENTATION('',(#10147),#10151); -#10147 = LINE('',#10148,#10149); -#10148 = CARTESIAN_POINT('',(2.531308496145E-014,0.E+000)); -#10149 = VECTOR('',#10150,1.); -#10150 = DIRECTION('',(1.,0.E+000)); -#10151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10152 = PCURVE('',#9964,#10153); -#10153 = DEFINITIONAL_REPRESENTATION('',(#10154),#10158); -#10154 = LINE('',#10155,#10156); -#10155 = CARTESIAN_POINT('',(0.E+000,0.25)); -#10156 = VECTOR('',#10157,1.); -#10157 = DIRECTION('',(-1.,0.E+000)); -#10158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10159 = ORIENTED_EDGE('',*,*,#10160,.F.); -#10160 = EDGE_CURVE('',#10161,#10138,#10163,.T.); -#10161 = VERTEX_POINT('',#10162); -#10162 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944, +#12532 = SURFACE_CURVE('',#12533,(#12537,#12544),.PCURVE_S1.); +#12533 = LINE('',#12534,#12535); +#12534 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) + ); +#12535 = VECTOR('',#12536,1.); +#12536 = DIRECTION('',(1.,0.E+000,0.E+000)); +#12537 = PCURVE('',#12410,#12538); +#12538 = DEFINITIONAL_REPRESENTATION('',(#12539),#12543); +#12539 = LINE('',#12540,#12541); +#12540 = CARTESIAN_POINT('',(2.531308496145E-014,0.E+000)); +#12541 = VECTOR('',#12542,1.); +#12542 = DIRECTION('',(1.,0.E+000)); +#12543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12544 = PCURVE('',#12356,#12545); +#12545 = DEFINITIONAL_REPRESENTATION('',(#12546),#12550); +#12546 = LINE('',#12547,#12548); +#12547 = CARTESIAN_POINT('',(0.E+000,0.25)); +#12548 = VECTOR('',#12549,1.); +#12549 = DIRECTION('',(-1.,0.E+000)); +#12550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12551 = ORIENTED_EDGE('',*,*,#12552,.F.); +#12552 = EDGE_CURVE('',#12553,#12530,#12555,.T.); +#12553 = VERTEX_POINT('',#12554); +#12554 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944, 2.976642100057E-002)); -#10163 = SURFACE_CURVE('',#10164,(#10168,#10175),.PCURVE_S1.); -#10164 = LINE('',#10165,#10166); -#10165 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944,0.329766421001 +#12555 = SURFACE_CURVE('',#12556,(#12560,#12567),.PCURVE_S1.); +#12556 = LINE('',#12557,#12558); +#12557 = CARTESIAN_POINT('',(-0.3303435002,0.182558409944,0.329766421001 )); -#10166 = VECTOR('',#10167,1.); -#10167 = DIRECTION('',(0.E+000,0.E+000,1.)); -#10168 = PCURVE('',#10018,#10169); -#10169 = DEFINITIONAL_REPRESENTATION('',(#10170),#10174); -#10170 = LINE('',#10171,#10172); -#10171 = CARTESIAN_POINT('',(-0.65,0.E+000)); -#10172 = VECTOR('',#10173,1.); -#10173 = DIRECTION('',(0.E+000,1.)); -#10174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10175 = PCURVE('',#10176,#10181); -#10176 = PLANE('',#10177); -#10177 = AXIS2_PLACEMENT_3D('',#10178,#10179,#10180); -#10178 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, +#12558 = VECTOR('',#12559,1.); +#12559 = DIRECTION('',(0.E+000,0.E+000,1.)); +#12560 = PCURVE('',#12410,#12561); +#12561 = DEFINITIONAL_REPRESENTATION('',(#12562),#12566); +#12562 = LINE('',#12563,#12564); +#12563 = CARTESIAN_POINT('',(-0.65,0.E+000)); +#12564 = VECTOR('',#12565,1.); +#12565 = DIRECTION('',(0.E+000,1.)); +#12566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12567 = PCURVE('',#12568,#12573); +#12568 = PLANE('',#12569); +#12569 = AXIS2_PLACEMENT_3D('',#12570,#12571,#12572); +#12570 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, 0.329766421001)); -#10179 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#10180 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10181 = DEFINITIONAL_REPRESENTATION('',(#10182),#10186); -#10182 = LINE('',#10183,#10184); -#10183 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#10184 = VECTOR('',#10185,1.); -#10185 = DIRECTION('',(0.E+000,1.)); -#10186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10187 = ORIENTED_EDGE('',*,*,#10188,.F.); -#10188 = EDGE_CURVE('',#9981,#10161,#10189,.T.); -#10189 = SURFACE_CURVE('',#10190,(#10194,#10201),.PCURVE_S1.); -#10190 = LINE('',#10191,#10192); -#10191 = CARTESIAN_POINT('',(-5.343500199887E-003,0.182558409944, +#12571 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#12572 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#12573 = DEFINITIONAL_REPRESENTATION('',(#12574),#12578); +#12574 = LINE('',#12575,#12576); +#12575 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#12576 = VECTOR('',#12577,1.); +#12577 = DIRECTION('',(0.E+000,1.)); +#12578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12579 = ORIENTED_EDGE('',*,*,#12580,.F.); +#12580 = EDGE_CURVE('',#12373,#12553,#12581,.T.); +#12581 = SURFACE_CURVE('',#12582,(#12586,#12593),.PCURVE_S1.); +#12582 = LINE('',#12583,#12584); +#12583 = CARTESIAN_POINT('',(-5.343500199887E-003,0.182558409944, 2.976642100057E-002)); -#10192 = VECTOR('',#10193,1.); -#10193 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#10194 = PCURVE('',#10018,#10195); -#10195 = DEFINITIONAL_REPRESENTATION('',(#10196),#10200); -#10196 = LINE('',#10197,#10198); -#10197 = CARTESIAN_POINT('',(-0.325,-0.3)); -#10198 = VECTOR('',#10199,1.); -#10199 = DIRECTION('',(-1.,0.E+000)); -#10200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10201 = PCURVE('',#10069,#10202); -#10202 = DEFINITIONAL_REPRESENTATION('',(#10203),#10207); -#10203 = LINE('',#10204,#10205); -#10204 = CARTESIAN_POINT('',(0.E+000,0.125)); -#10205 = VECTOR('',#10206,1.); -#10206 = DIRECTION('',(-1.,0.E+000)); -#10207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10208 = ADVANCED_FACE('',(#10209),#10223,.T.); -#10209 = FACE_BOUND('',#10210,.T.); -#10210 = EDGE_LOOP('',(#10211,#10241,#10269,#10297)); -#10211 = ORIENTED_EDGE('',*,*,#10212,.F.); -#10212 = EDGE_CURVE('',#10213,#10215,#10217,.T.); -#10213 = VERTEX_POINT('',#10214); -#10214 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, +#12584 = VECTOR('',#12585,1.); +#12585 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#12586 = PCURVE('',#12410,#12587); +#12587 = DEFINITIONAL_REPRESENTATION('',(#12588),#12592); +#12588 = LINE('',#12589,#12590); +#12589 = CARTESIAN_POINT('',(-0.325,-0.3)); +#12590 = VECTOR('',#12591,1.); +#12591 = DIRECTION('',(-1.,0.E+000)); +#12592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12593 = PCURVE('',#12461,#12594); +#12594 = DEFINITIONAL_REPRESENTATION('',(#12595),#12599); +#12595 = LINE('',#12596,#12597); +#12596 = CARTESIAN_POINT('',(0.E+000,0.125)); +#12597 = VECTOR('',#12598,1.); +#12598 = DIRECTION('',(-1.,0.E+000)); +#12599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12600 = ADVANCED_FACE('',(#12601),#12615,.T.); +#12601 = FACE_BOUND('',#12602,.T.); +#12602 = EDGE_LOOP('',(#12603,#12633,#12661,#12689)); +#12603 = ORIENTED_EDGE('',*,*,#12604,.F.); +#12604 = EDGE_CURVE('',#12605,#12607,#12609,.T.); +#12605 = VERTEX_POINT('',#12606); +#12606 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, 0.329766421001)); -#10215 = VERTEX_POINT('',#10216); -#10216 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005582E-002, +#12607 = VERTEX_POINT('',#12608); +#12608 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005582E-002, 0.329766421001)); -#10217 = SURFACE_CURVE('',#10218,(#10222,#10234),.PCURVE_S1.); -#10218 = LINE('',#10219,#10220); -#10219 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, +#12609 = SURFACE_CURVE('',#12610,(#12614,#12626),.PCURVE_S1.); +#12610 = LINE('',#12611,#12612); +#12611 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, 0.329766421001)); -#10220 = VECTOR('',#10221,1.); -#10221 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#10222 = PCURVE('',#10223,#10228); -#10223 = PLANE('',#10224); -#10224 = AXIS2_PLACEMENT_3D('',#10225,#10226,#10227); -#10225 = CARTESIAN_POINT('',(-5.343500199937E-003,-1.744159005581E-002, +#12612 = VECTOR('',#12613,1.); +#12613 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#12614 = PCURVE('',#12615,#12620); +#12615 = PLANE('',#12616); +#12616 = AXIS2_PLACEMENT_3D('',#12617,#12618,#12619); +#12617 = CARTESIAN_POINT('',(-5.343500199937E-003,-1.744159005581E-002, 0.342266421001)); -#10226 = DIRECTION('',(1.01196828695E-013,-1.,-3.014155100546E-025)); -#10227 = DIRECTION('',(1.,1.01196828695E-013,-2.57443652839E-055)); -#10228 = DEFINITIONAL_REPRESENTATION('',(#10229),#10233); -#10229 = LINE('',#10230,#10231); -#10230 = CARTESIAN_POINT('',(0.325,-1.25E-002)); -#10231 = VECTOR('',#10232,1.); -#10232 = DIRECTION('',(-1.,-3.050229373702E-038)); -#10233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10234 = PCURVE('',#9964,#10235); -#10235 = DEFINITIONAL_REPRESENTATION('',(#10236),#10240); -#10236 = LINE('',#10237,#10238); -#10237 = CARTESIAN_POINT('',(0.E+000,5.000000000001E-002)); -#10238 = VECTOR('',#10239,1.); -#10239 = DIRECTION('',(1.,0.E+000)); -#10240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10241 = ORIENTED_EDGE('',*,*,#10242,.F.); -#10242 = EDGE_CURVE('',#10243,#10213,#10245,.T.); -#10243 = VERTEX_POINT('',#10244); -#10244 = CARTESIAN_POINT('',(0.3196564998,-1.74415900558E-002, - 0.354766421001)); -#10245 = SURFACE_CURVE('',#10246,(#10250,#10257),.PCURVE_S1.); -#10246 = LINE('',#10247,#10248); -#10247 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, +#12618 = DIRECTION('',(1.01196828695E-013,-1.,-3.014155100546E-025)); +#12619 = DIRECTION('',(1.,1.01196828695E-013,-2.57443652839E-055)); +#12620 = DEFINITIONAL_REPRESENTATION('',(#12621),#12625); +#12621 = LINE('',#12622,#12623); +#12622 = CARTESIAN_POINT('',(0.325,-1.25E-002)); +#12623 = VECTOR('',#12624,1.); +#12624 = DIRECTION('',(-1.,-3.050229373702E-038)); +#12625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12626 = PCURVE('',#12356,#12627); +#12627 = DEFINITIONAL_REPRESENTATION('',(#12628),#12632); +#12628 = LINE('',#12629,#12630); +#12629 = CARTESIAN_POINT('',(0.E+000,5.000000000001E-002)); +#12630 = VECTOR('',#12631,1.); +#12631 = DIRECTION('',(1.,0.E+000)); +#12632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12633 = ORIENTED_EDGE('',*,*,#12634,.F.); +#12634 = EDGE_CURVE('',#12635,#12605,#12637,.T.); +#12635 = VERTEX_POINT('',#12636); +#12636 = CARTESIAN_POINT('',(0.3196564998,-1.74415900558E-002, 0.354766421001)); -#10248 = VECTOR('',#10249,1.); -#10249 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10250 = PCURVE('',#10223,#10251); -#10251 = DEFINITIONAL_REPRESENTATION('',(#10252),#10256); -#10252 = LINE('',#10253,#10254); -#10253 = CARTESIAN_POINT('',(0.325,1.25E-002)); -#10254 = VECTOR('',#10255,1.); -#10255 = DIRECTION('',(0.E+000,-1.)); -#10256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10257 = PCURVE('',#10258,#10263); -#10258 = PLANE('',#10259); -#10259 = AXIS2_PLACEMENT_3D('',#10260,#10261,#10262); -#10260 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#12637 = SURFACE_CURVE('',#12638,(#12642,#12649),.PCURVE_S1.); +#12638 = LINE('',#12639,#12640); +#12639 = CARTESIAN_POINT('',(0.3196564998,-1.744159005578E-002, 0.354766421001)); -#10261 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#10262 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10263 = DEFINITIONAL_REPRESENTATION('',(#10264),#10268); -#10264 = LINE('',#10265,#10266); -#10265 = CARTESIAN_POINT('',(5.000000000001E-002,0.E+000)); -#10266 = VECTOR('',#10267,1.); -#10267 = DIRECTION('',(0.E+000,-1.)); -#10268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10269 = ORIENTED_EDGE('',*,*,#10270,.F.); -#10270 = EDGE_CURVE('',#10271,#10243,#10273,.T.); -#10271 = VERTEX_POINT('',#10272); -#10272 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, +#12640 = VECTOR('',#12641,1.); +#12641 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12642 = PCURVE('',#12615,#12643); +#12643 = DEFINITIONAL_REPRESENTATION('',(#12644),#12648); +#12644 = LINE('',#12645,#12646); +#12645 = CARTESIAN_POINT('',(0.325,1.25E-002)); +#12646 = VECTOR('',#12647,1.); +#12647 = DIRECTION('',(0.E+000,-1.)); +#12648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12649 = PCURVE('',#12650,#12655); +#12650 = PLANE('',#12651); +#12651 = AXIS2_PLACEMENT_3D('',#12652,#12653,#12654); +#12652 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 0.354766421001)); -#10273 = SURFACE_CURVE('',#10274,(#10278,#10285),.PCURVE_S1.); -#10274 = LINE('',#10275,#10276); -#10275 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, +#12653 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#12654 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#12655 = DEFINITIONAL_REPRESENTATION('',(#12656),#12660); +#12656 = LINE('',#12657,#12658); +#12657 = CARTESIAN_POINT('',(5.000000000001E-002,0.E+000)); +#12658 = VECTOR('',#12659,1.); +#12659 = DIRECTION('',(0.E+000,-1.)); +#12660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12661 = ORIENTED_EDGE('',*,*,#12662,.F.); +#12662 = EDGE_CURVE('',#12663,#12635,#12665,.T.); +#12663 = VERTEX_POINT('',#12664); +#12664 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, 0.354766421001)); -#10276 = VECTOR('',#10277,1.); -#10277 = DIRECTION('',(1.,0.E+000,0.E+000)); -#10278 = PCURVE('',#10223,#10279); -#10279 = DEFINITIONAL_REPRESENTATION('',(#10280),#10284); -#10280 = LINE('',#10281,#10282); -#10281 = CARTESIAN_POINT('',(-0.325,1.25E-002)); -#10282 = VECTOR('',#10283,1.); -#10283 = DIRECTION('',(1.,3.050229373702E-038)); -#10284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10285 = PCURVE('',#10286,#10291); -#10286 = PLANE('',#10287); -#10287 = AXIS2_PLACEMENT_3D('',#10288,#10289,#10290); -#10288 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, +#12665 = SURFACE_CURVE('',#12666,(#12670,#12677),.PCURVE_S1.); +#12666 = LINE('',#12667,#12668); +#12667 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, 0.354766421001)); -#10289 = DIRECTION('',(0.E+000,0.E+000,1.)); -#10290 = DIRECTION('',(1.,0.E+000,0.E+000)); -#10291 = DEFINITIONAL_REPRESENTATION('',(#10292),#10296); -#10292 = LINE('',#10293,#10294); -#10293 = CARTESIAN_POINT('',(0.E+000,5.000000000001E-002)); -#10294 = VECTOR('',#10295,1.); -#10295 = DIRECTION('',(1.,0.E+000)); -#10296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10297 = ORIENTED_EDGE('',*,*,#10298,.F.); -#10298 = EDGE_CURVE('',#10215,#10271,#10299,.T.); -#10299 = SURFACE_CURVE('',#10300,(#10304,#10311),.PCURVE_S1.); -#10300 = LINE('',#10301,#10302); -#10301 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, - 0.329766421001)); -#10302 = VECTOR('',#10303,1.); -#10303 = DIRECTION('',(0.E+000,0.E+000,1.)); -#10304 = PCURVE('',#10223,#10305); -#10305 = DEFINITIONAL_REPRESENTATION('',(#10306),#10310); -#10306 = LINE('',#10307,#10308); -#10307 = CARTESIAN_POINT('',(-0.325,-1.25E-002)); -#10308 = VECTOR('',#10309,1.); -#10309 = DIRECTION('',(0.E+000,1.)); -#10310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10311 = PCURVE('',#10176,#10312); -#10312 = DEFINITIONAL_REPRESENTATION('',(#10313),#10317); -#10313 = LINE('',#10314,#10315); -#10314 = CARTESIAN_POINT('',(-5.000000000001E-002,0.E+000)); -#10315 = VECTOR('',#10316,1.); -#10316 = DIRECTION('',(0.E+000,1.)); -#10317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10318 = ADVANCED_FACE('',(#10319),#9964,.T.); -#10319 = FACE_BOUND('',#10320,.T.); -#10320 = EDGE_LOOP('',(#10321,#10322,#10323,#10346,#10367,#10368)); -#10321 = ORIENTED_EDGE('',*,*,#10137,.T.); -#10322 = ORIENTED_EDGE('',*,*,#9918,.T.); -#10323 = ORIENTED_EDGE('',*,*,#10324,.F.); -#10324 = EDGE_CURVE('',#10325,#9921,#10327,.T.); -#10325 = VERTEX_POINT('',#10326); -#10326 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) - ); -#10327 = SURFACE_CURVE('',#10328,(#10332,#10339),.PCURVE_S1.); -#10328 = LINE('',#10329,#10330); -#10329 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) - ); -#10330 = VECTOR('',#10331,1.); -#10331 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#10332 = PCURVE('',#9964,#10333); -#10333 = DEFINITIONAL_REPRESENTATION('',(#10334),#10338); -#10334 = LINE('',#10335,#10336); -#10335 = CARTESIAN_POINT('',(2.531308496145E-014,0.25)); -#10336 = VECTOR('',#10337,1.); -#10337 = DIRECTION('',(1.,-1.011968286946E-013)); -#10338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10339 = PCURVE('',#10121,#10340); -#10340 = DEFINITIONAL_REPRESENTATION('',(#10341),#10345); -#10341 = LINE('',#10342,#10343); -#10342 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#10343 = VECTOR('',#10344,1.); -#10344 = DIRECTION('',(-1.,0.E+000)); -#10345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#12668 = VECTOR('',#12669,1.); +#12669 = DIRECTION('',(1.,0.E+000,0.E+000)); +#12670 = PCURVE('',#12615,#12671); +#12671 = DEFINITIONAL_REPRESENTATION('',(#12672),#12676); +#12672 = LINE('',#12673,#12674); +#12673 = CARTESIAN_POINT('',(-0.325,1.25E-002)); +#12674 = VECTOR('',#12675,1.); +#12675 = DIRECTION('',(1.,3.050229373702E-038)); +#12676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#10346 = ORIENTED_EDGE('',*,*,#10347,.F.); -#10347 = EDGE_CURVE('',#10213,#10325,#10348,.T.); -#10348 = SURFACE_CURVE('',#10349,(#10353,#10360),.PCURVE_S1.); -#10349 = LINE('',#10350,#10351); -#10350 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#12677 = PCURVE('',#12678,#12683); +#12678 = PLANE('',#12679); +#12679 = AXIS2_PLACEMENT_3D('',#12680,#12681,#12682); +#12680 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, + 0.354766421001)); +#12681 = DIRECTION('',(0.E+000,0.E+000,1.)); +#12682 = DIRECTION('',(1.,0.E+000,0.E+000)); +#12683 = DEFINITIONAL_REPRESENTATION('',(#12684),#12688); +#12684 = LINE('',#12685,#12686); +#12685 = CARTESIAN_POINT('',(0.E+000,5.000000000001E-002)); +#12686 = VECTOR('',#12687,1.); +#12687 = DIRECTION('',(1.,0.E+000)); +#12688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12689 = ORIENTED_EDGE('',*,*,#12690,.F.); +#12690 = EDGE_CURVE('',#12607,#12663,#12691,.T.); +#12691 = SURFACE_CURVE('',#12692,(#12696,#12703),.PCURVE_S1.); +#12692 = LINE('',#12693,#12694); +#12693 = CARTESIAN_POINT('',(-0.3303435002,-1.744159005584E-002, 0.329766421001)); -#10351 = VECTOR('',#10352,1.); -#10352 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10353 = PCURVE('',#9964,#10354); -#10354 = DEFINITIONAL_REPRESENTATION('',(#10355),#10359); -#10355 = LINE('',#10356,#10357); -#10356 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#10357 = VECTOR('',#10358,1.); -#10358 = DIRECTION('',(1.011968286946E-013,1.)); -#10359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10360 = PCURVE('',#10258,#10361); -#10361 = DEFINITIONAL_REPRESENTATION('',(#10362),#10366); -#10362 = LINE('',#10363,#10364); -#10363 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#10364 = VECTOR('',#10365,1.); -#10365 = DIRECTION('',(1.,0.E+000)); -#10366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10367 = ORIENTED_EDGE('',*,*,#10212,.T.); -#10368 = ORIENTED_EDGE('',*,*,#10369,.F.); -#10369 = EDGE_CURVE('',#10138,#10215,#10370,.T.); -#10370 = SURFACE_CURVE('',#10371,(#10375,#10382),.PCURVE_S1.); -#10371 = LINE('',#10372,#10373); -#10372 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, +#12694 = VECTOR('',#12695,1.); +#12695 = DIRECTION('',(0.E+000,0.E+000,1.)); +#12696 = PCURVE('',#12615,#12697); +#12697 = DEFINITIONAL_REPRESENTATION('',(#12698),#12702); +#12698 = LINE('',#12699,#12700); +#12699 = CARTESIAN_POINT('',(-0.325,-1.25E-002)); +#12700 = VECTOR('',#12701,1.); +#12701 = DIRECTION('',(0.E+000,1.)); +#12702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12703 = PCURVE('',#12568,#12704); +#12704 = DEFINITIONAL_REPRESENTATION('',(#12705),#12709); +#12705 = LINE('',#12706,#12707); +#12706 = CARTESIAN_POINT('',(-5.000000000001E-002,0.E+000)); +#12707 = VECTOR('',#12708,1.); +#12708 = DIRECTION('',(0.E+000,1.)); +#12709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12710 = ADVANCED_FACE('',(#12711),#12356,.T.); +#12711 = FACE_BOUND('',#12712,.T.); +#12712 = EDGE_LOOP('',(#12713,#12714,#12715,#12738,#12759,#12760)); +#12713 = ORIENTED_EDGE('',*,*,#12529,.T.); +#12714 = ORIENTED_EDGE('',*,*,#12310,.T.); +#12715 = ORIENTED_EDGE('',*,*,#12716,.F.); +#12716 = EDGE_CURVE('',#12717,#12313,#12719,.T.); +#12717 = VERTEX_POINT('',#12718); +#12718 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) + ); +#12719 = SURFACE_CURVE('',#12720,(#12724,#12731),.PCURVE_S1.); +#12720 = LINE('',#12721,#12722); +#12721 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.329766421001) + ); +#12722 = VECTOR('',#12723,1.); +#12723 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#12724 = PCURVE('',#12356,#12725); +#12725 = DEFINITIONAL_REPRESENTATION('',(#12726),#12730); +#12726 = LINE('',#12727,#12728); +#12727 = CARTESIAN_POINT('',(2.531308496145E-014,0.25)); +#12728 = VECTOR('',#12729,1.); +#12729 = DIRECTION('',(1.,-1.011968286946E-013)); +#12730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12731 = PCURVE('',#12513,#12732); +#12732 = DEFINITIONAL_REPRESENTATION('',(#12733),#12737); +#12733 = LINE('',#12734,#12735); +#12734 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#12735 = VECTOR('',#12736,1.); +#12736 = DIRECTION('',(-1.,0.E+000)); +#12737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12738 = ORIENTED_EDGE('',*,*,#12739,.F.); +#12739 = EDGE_CURVE('',#12605,#12717,#12740,.T.); +#12740 = SURFACE_CURVE('',#12741,(#12745,#12752),.PCURVE_S1.); +#12741 = LINE('',#12742,#12743); +#12742 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 0.329766421001)); -#10373 = VECTOR('',#10374,1.); -#10374 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10375 = PCURVE('',#9964,#10376); -#10376 = DEFINITIONAL_REPRESENTATION('',(#10377),#10381); -#10377 = LINE('',#10378,#10379); -#10378 = CARTESIAN_POINT('',(0.65,-6.571132527E-014)); -#10379 = VECTOR('',#10380,1.); -#10380 = DIRECTION('',(-1.011968286946E-013,-1.)); -#10381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10382 = PCURVE('',#10176,#10383); -#10383 = DEFINITIONAL_REPRESENTATION('',(#10384),#10388); -#10384 = LINE('',#10385,#10386); -#10385 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#10386 = VECTOR('',#10387,1.); -#10387 = DIRECTION('',(1.,0.E+000)); -#10388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10389 = ADVANCED_FACE('',(#10390),#10121,.T.); -#10390 = FACE_BOUND('',#10391,.T.); -#10391 = EDGE_LOOP('',(#10392,#10393,#10416,#10437)); -#10392 = ORIENTED_EDGE('',*,*,#10085,.T.); -#10393 = ORIENTED_EDGE('',*,*,#10394,.F.); -#10394 = EDGE_CURVE('',#10395,#10031,#10397,.T.); -#10395 = VERTEX_POINT('',#10396); -#10396 = CARTESIAN_POINT('',(0.3196564998,0.182558409944, +#12743 = VECTOR('',#12744,1.); +#12744 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#12745 = PCURVE('',#12356,#12746); +#12746 = DEFINITIONAL_REPRESENTATION('',(#12747),#12751); +#12747 = LINE('',#12748,#12749); +#12748 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#12749 = VECTOR('',#12750,1.); +#12750 = DIRECTION('',(1.011968286946E-013,1.)); +#12751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12752 = PCURVE('',#12650,#12753); +#12753 = DEFINITIONAL_REPRESENTATION('',(#12754),#12758); +#12754 = LINE('',#12755,#12756); +#12755 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#12756 = VECTOR('',#12757,1.); +#12757 = DIRECTION('',(1.,0.E+000)); +#12758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12759 = ORIENTED_EDGE('',*,*,#12604,.T.); +#12760 = ORIENTED_EDGE('',*,*,#12761,.F.); +#12761 = EDGE_CURVE('',#12530,#12607,#12762,.T.); +#12762 = SURFACE_CURVE('',#12763,(#12767,#12774),.PCURVE_S1.); +#12763 = LINE('',#12764,#12765); +#12764 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, + 0.329766421001)); +#12765 = VECTOR('',#12766,1.); +#12766 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#12767 = PCURVE('',#12356,#12768); +#12768 = DEFINITIONAL_REPRESENTATION('',(#12769),#12773); +#12769 = LINE('',#12770,#12771); +#12770 = CARTESIAN_POINT('',(0.65,-6.571132527E-014)); +#12771 = VECTOR('',#12772,1.); +#12772 = DIRECTION('',(-1.011968286946E-013,-1.)); +#12773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12774 = PCURVE('',#12568,#12775); +#12775 = DEFINITIONAL_REPRESENTATION('',(#12776),#12780); +#12776 = LINE('',#12777,#12778); +#12777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#12778 = VECTOR('',#12779,1.); +#12779 = DIRECTION('',(1.,0.E+000)); +#12780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12781 = ADVANCED_FACE('',(#12782),#12513,.T.); +#12782 = FACE_BOUND('',#12783,.T.); +#12783 = EDGE_LOOP('',(#12784,#12785,#12808,#12829)); +#12784 = ORIENTED_EDGE('',*,*,#12477,.T.); +#12785 = ORIENTED_EDGE('',*,*,#12786,.F.); +#12786 = EDGE_CURVE('',#12787,#12423,#12789,.T.); +#12787 = VERTEX_POINT('',#12788); +#12788 = CARTESIAN_POINT('',(0.3196564998,0.182558409944, 2.976642100057E-002)); -#10397 = SURFACE_CURVE('',#10398,(#10402,#10409),.PCURVE_S1.); -#10398 = LINE('',#10399,#10400); -#10399 = CARTESIAN_POINT('',(-5.343500199887E-003,0.182558409944, +#12789 = SURFACE_CURVE('',#12790,(#12794,#12801),.PCURVE_S1.); +#12790 = LINE('',#12791,#12792); +#12791 = CARTESIAN_POINT('',(-5.343500199887E-003,0.182558409944, 2.976642100057E-002)); -#10400 = VECTOR('',#10401,1.); -#10401 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#10402 = PCURVE('',#10121,#10403); -#10403 = DEFINITIONAL_REPRESENTATION('',(#10404),#10408); -#10404 = LINE('',#10405,#10406); -#10405 = CARTESIAN_POINT('',(-0.325,-0.3)); -#10406 = VECTOR('',#10407,1.); -#10407 = DIRECTION('',(-1.,0.E+000)); -#10408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10409 = PCURVE('',#10069,#10410); -#10410 = DEFINITIONAL_REPRESENTATION('',(#10411),#10415); -#10411 = LINE('',#10412,#10413); -#10412 = CARTESIAN_POINT('',(0.E+000,0.125)); -#10413 = VECTOR('',#10414,1.); -#10414 = DIRECTION('',(-1.,0.E+000)); -#10415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#12792 = VECTOR('',#12793,1.); +#12793 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#12794 = PCURVE('',#12513,#12795); +#12795 = DEFINITIONAL_REPRESENTATION('',(#12796),#12800); +#12796 = LINE('',#12797,#12798); +#12797 = CARTESIAN_POINT('',(-0.325,-0.3)); +#12798 = VECTOR('',#12799,1.); +#12799 = DIRECTION('',(-1.,0.E+000)); +#12800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12801 = PCURVE('',#12461,#12802); +#12802 = DEFINITIONAL_REPRESENTATION('',(#12803),#12807); +#12803 = LINE('',#12804,#12805); +#12804 = CARTESIAN_POINT('',(0.E+000,0.125)); +#12805 = VECTOR('',#12806,1.); +#12806 = DIRECTION('',(-1.,0.E+000)); +#12807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12808 = ORIENTED_EDGE('',*,*,#12809,.F.); +#12809 = EDGE_CURVE('',#12717,#12787,#12810,.T.); +#12810 = SURFACE_CURVE('',#12811,(#12815,#12822),.PCURVE_S1.); +#12811 = LINE('',#12812,#12813); +#12812 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.354766421001) + ); +#12813 = VECTOR('',#12814,1.); +#12814 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#12815 = PCURVE('',#12513,#12816); +#12816 = DEFINITIONAL_REPRESENTATION('',(#12817),#12821); +#12817 = LINE('',#12818,#12819); +#12818 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#12819 = VECTOR('',#12820,1.); +#12820 = DIRECTION('',(0.E+000,-1.)); +#12821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12822 = PCURVE('',#12650,#12823); +#12823 = DEFINITIONAL_REPRESENTATION('',(#12824),#12828); +#12824 = LINE('',#12825,#12826); +#12825 = CARTESIAN_POINT('',(0.25,0.E+000)); +#12826 = VECTOR('',#12827,1.); +#12827 = DIRECTION('',(0.E+000,-1.)); +#12828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#10416 = ORIENTED_EDGE('',*,*,#10417,.F.); -#10417 = EDGE_CURVE('',#10325,#10395,#10418,.T.); -#10418 = SURFACE_CURVE('',#10419,(#10423,#10430),.PCURVE_S1.); -#10419 = LINE('',#10420,#10421); -#10420 = CARTESIAN_POINT('',(0.3196564998,0.182558409944,0.354766421001) - ); -#10421 = VECTOR('',#10422,1.); -#10422 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10423 = PCURVE('',#10121,#10424); -#10424 = DEFINITIONAL_REPRESENTATION('',(#10425),#10429); -#10425 = LINE('',#10426,#10427); -#10426 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#10427 = VECTOR('',#10428,1.); -#10428 = DIRECTION('',(0.E+000,-1.)); -#10429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10430 = PCURVE('',#10258,#10431); -#10431 = DEFINITIONAL_REPRESENTATION('',(#10432),#10436); -#10432 = LINE('',#10433,#10434); -#10433 = CARTESIAN_POINT('',(0.25,0.E+000)); -#10434 = VECTOR('',#10435,1.); -#10435 = DIRECTION('',(0.E+000,-1.)); -#10436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10437 = ORIENTED_EDGE('',*,*,#10324,.T.); -#10438 = ADVANCED_FACE('',(#10439),#10069,.T.); -#10439 = FACE_BOUND('',#10440,.T.); -#10440 = EDGE_LOOP('',(#10441,#10464,#10492,#10513,#10514,#10515)); -#10441 = ORIENTED_EDGE('',*,*,#10442,.F.); -#10442 = EDGE_CURVE('',#10443,#10161,#10445,.T.); -#10443 = VERTEX_POINT('',#10444); -#10444 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, +#12829 = ORIENTED_EDGE('',*,*,#12716,.T.); +#12830 = ADVANCED_FACE('',(#12831),#12461,.T.); +#12831 = FACE_BOUND('',#12832,.T.); +#12832 = EDGE_LOOP('',(#12833,#12856,#12884,#12905,#12906,#12907)); +#12833 = ORIENTED_EDGE('',*,*,#12834,.F.); +#12834 = EDGE_CURVE('',#12835,#12553,#12837,.T.); +#12835 = VERTEX_POINT('',#12836); +#12836 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, 2.976642100057E-002)); -#10445 = SURFACE_CURVE('',#10446,(#10450,#10457),.PCURVE_S1.); -#10446 = LINE('',#10447,#10448); -#10447 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, +#12837 = SURFACE_CURVE('',#12838,(#12842,#12849),.PCURVE_S1.); +#12838 = LINE('',#12839,#12840); +#12839 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, 2.976642100057E-002)); -#10448 = VECTOR('',#10449,1.); -#10449 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10450 = PCURVE('',#10069,#10451); -#10451 = DEFINITIONAL_REPRESENTATION('',(#10452),#10456); -#10452 = LINE('',#10453,#10454); -#10453 = CARTESIAN_POINT('',(-0.325,-0.125)); -#10454 = VECTOR('',#10455,1.); -#10455 = DIRECTION('',(-1.011968286946E-013,1.)); -#10456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10457 = PCURVE('',#10176,#10458); -#10458 = DEFINITIONAL_REPRESENTATION('',(#10459),#10463); -#10459 = LINE('',#10460,#10461); -#10460 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#10461 = VECTOR('',#10462,1.); -#10462 = DIRECTION('',(-1.,0.E+000)); -#10463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10464 = ORIENTED_EDGE('',*,*,#10465,.F.); -#10465 = EDGE_CURVE('',#10466,#10443,#10468,.T.); -#10466 = VERTEX_POINT('',#10467); -#10467 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#12840 = VECTOR('',#12841,1.); +#12841 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#12842 = PCURVE('',#12461,#12843); +#12843 = DEFINITIONAL_REPRESENTATION('',(#12844),#12848); +#12844 = LINE('',#12845,#12846); +#12845 = CARTESIAN_POINT('',(-0.325,-0.125)); +#12846 = VECTOR('',#12847,1.); +#12847 = DIRECTION('',(-1.011968286946E-013,1.)); +#12848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12849 = PCURVE('',#12568,#12850); +#12850 = DEFINITIONAL_REPRESENTATION('',(#12851),#12855); +#12851 = LINE('',#12852,#12853); +#12852 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#12853 = VECTOR('',#12854,1.); +#12854 = DIRECTION('',(-1.,0.E+000)); +#12855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12856 = ORIENTED_EDGE('',*,*,#12857,.F.); +#12857 = EDGE_CURVE('',#12858,#12835,#12860,.T.); +#12858 = VERTEX_POINT('',#12859); +#12859 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 2.976642100057E-002)); -#10468 = SURFACE_CURVE('',#10469,(#10473,#10480),.PCURVE_S1.); -#10469 = LINE('',#10470,#10471); -#10470 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, +#12860 = SURFACE_CURVE('',#12861,(#12865,#12872),.PCURVE_S1.); +#12861 = LINE('',#12862,#12863); +#12862 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, 2.976642100057E-002)); -#10471 = VECTOR('',#10472,1.); -#10472 = DIRECTION('',(-1.,-5.747112187857E-014,0.E+000)); -#10473 = PCURVE('',#10069,#10474); -#10474 = DEFINITIONAL_REPRESENTATION('',(#10475),#10479); -#10475 = LINE('',#10476,#10477); -#10476 = CARTESIAN_POINT('',(-0.325,-0.125)); -#10477 = VECTOR('',#10478,1.); -#10478 = DIRECTION('',(-1.,-5.747112187857E-014)); -#10479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10480 = PCURVE('',#10481,#10486); -#10481 = PLANE('',#10482); -#10482 = AXIS2_PLACEMENT_3D('',#10483,#10484,#10485); -#10483 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, +#12863 = VECTOR('',#12864,1.); +#12864 = DIRECTION('',(-1.,-5.747112187857E-014,0.E+000)); +#12865 = PCURVE('',#12461,#12866); +#12866 = DEFINITIONAL_REPRESENTATION('',(#12867),#12871); +#12867 = LINE('',#12868,#12869); +#12868 = CARTESIAN_POINT('',(-0.325,-0.125)); +#12869 = VECTOR('',#12870,1.); +#12870 = DIRECTION('',(-1.,-5.747112187857E-014)); +#12871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12872 = PCURVE('',#12873,#12878); +#12873 = PLANE('',#12874); +#12874 = AXIS2_PLACEMENT_3D('',#12875,#12876,#12877); +#12875 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, 4.766421000566E-003)); -#10484 = DIRECTION('',(5.747112187857E-014,-1.,0.E+000)); -#10485 = DIRECTION('',(1.,5.747112187857E-014,0.E+000)); -#10486 = DEFINITIONAL_REPRESENTATION('',(#10487),#10491); -#10487 = LINE('',#10488,#10489); -#10488 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#10489 = VECTOR('',#10490,1.); -#10490 = DIRECTION('',(-1.,0.E+000)); -#10491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10492 = ORIENTED_EDGE('',*,*,#10493,.F.); -#10493 = EDGE_CURVE('',#10395,#10466,#10494,.T.); -#10494 = SURFACE_CURVE('',#10495,(#10499,#10506),.PCURVE_S1.); -#10495 = LINE('',#10496,#10497); -#10496 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#12876 = DIRECTION('',(5.747112187857E-014,-1.,0.E+000)); +#12877 = DIRECTION('',(1.,5.747112187857E-014,0.E+000)); +#12878 = DEFINITIONAL_REPRESENTATION('',(#12879),#12883); +#12879 = LINE('',#12880,#12881); +#12880 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#12881 = VECTOR('',#12882,1.); +#12882 = DIRECTION('',(-1.,0.E+000)); +#12883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12884 = ORIENTED_EDGE('',*,*,#12885,.F.); +#12885 = EDGE_CURVE('',#12787,#12858,#12886,.T.); +#12886 = SURFACE_CURVE('',#12887,(#12891,#12898),.PCURVE_S1.); +#12887 = LINE('',#12888,#12889); +#12888 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 2.976642100057E-002)); -#10497 = VECTOR('',#10498,1.); -#10498 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10499 = PCURVE('',#10069,#10500); -#10500 = DEFINITIONAL_REPRESENTATION('',(#10501),#10505); -#10501 = LINE('',#10502,#10503); -#10502 = CARTESIAN_POINT('',(0.325,-0.125)); -#10503 = VECTOR('',#10504,1.); -#10504 = DIRECTION('',(1.011968286946E-013,-1.)); -#10505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10506 = PCURVE('',#10258,#10507); -#10507 = DEFINITIONAL_REPRESENTATION('',(#10508),#10512); -#10508 = LINE('',#10509,#10510); -#10509 = CARTESIAN_POINT('',(0.E+000,-0.325)); -#10510 = VECTOR('',#10511,1.); -#10511 = DIRECTION('',(-1.,0.E+000)); -#10512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10513 = ORIENTED_EDGE('',*,*,#10394,.T.); -#10514 = ORIENTED_EDGE('',*,*,#10030,.T.); -#10515 = ORIENTED_EDGE('',*,*,#10188,.T.); -#10516 = ADVANCED_FACE('',(#10517),#10286,.T.); -#10517 = FACE_BOUND('',#10518,.T.); -#10518 = EDGE_LOOP('',(#10519,#10549,#10604,#10632,#10653,#10654)); -#10519 = ORIENTED_EDGE('',*,*,#10520,.F.); -#10520 = EDGE_CURVE('',#10521,#10523,#10525,.T.); -#10521 = VERTEX_POINT('',#10522); -#10522 = CARTESIAN_POINT('',(0.1196564998,0.207558409944,0.354766421001) - ); -#10523 = VERTEX_POINT('',#10524); -#10524 = CARTESIAN_POINT('',(0.3196564998,0.207558409944,0.354766421001) - ); -#10525 = SURFACE_CURVE('',#10526,(#10530,#10537),.PCURVE_S1.); -#10526 = LINE('',#10527,#10528); -#10527 = CARTESIAN_POINT('',(0.1446564998,0.207558409944,0.354766421001) - ); -#10528 = VECTOR('',#10529,1.); -#10529 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#10530 = PCURVE('',#10286,#10531); -#10531 = DEFINITIONAL_REPRESENTATION('',(#10532),#10536); -#10532 = LINE('',#10533,#10534); -#10533 = CARTESIAN_POINT('',(0.475,0.275)); -#10534 = VECTOR('',#10535,1.); -#10535 = DIRECTION('',(1.,1.011968286946E-013)); -#10536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10537 = PCURVE('',#10538,#10543); -#10538 = PLANE('',#10539); -#10539 = AXIS2_PLACEMENT_3D('',#10540,#10541,#10542); -#10540 = CARTESIAN_POINT('',(0.1446564998,0.207558409944, +#12889 = VECTOR('',#12890,1.); +#12890 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#12891 = PCURVE('',#12461,#12892); +#12892 = DEFINITIONAL_REPRESENTATION('',(#12893),#12897); +#12893 = LINE('',#12894,#12895); +#12894 = CARTESIAN_POINT('',(0.325,-0.125)); +#12895 = VECTOR('',#12896,1.); +#12896 = DIRECTION('',(1.011968286946E-013,-1.)); +#12897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12898 = PCURVE('',#12650,#12899); +#12899 = DEFINITIONAL_REPRESENTATION('',(#12900),#12904); +#12900 = LINE('',#12901,#12902); +#12901 = CARTESIAN_POINT('',(0.E+000,-0.325)); +#12902 = VECTOR('',#12903,1.); +#12903 = DIRECTION('',(-1.,0.E+000)); +#12904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12905 = ORIENTED_EDGE('',*,*,#12786,.T.); +#12906 = ORIENTED_EDGE('',*,*,#12422,.T.); +#12907 = ORIENTED_EDGE('',*,*,#12580,.T.); +#12908 = ADVANCED_FACE('',(#12909),#12678,.T.); +#12909 = FACE_BOUND('',#12910,.T.); +#12910 = EDGE_LOOP('',(#12911,#12941,#12996,#13024,#13045,#13046)); +#12911 = ORIENTED_EDGE('',*,*,#12912,.F.); +#12912 = EDGE_CURVE('',#12913,#12915,#12917,.T.); +#12913 = VERTEX_POINT('',#12914); +#12914 = CARTESIAN_POINT('',(0.1196564998,0.207558409944,0.354766421001) + ); +#12915 = VERTEX_POINT('',#12916); +#12916 = CARTESIAN_POINT('',(0.3196564998,0.207558409944,0.354766421001) + ); +#12917 = SURFACE_CURVE('',#12918,(#12922,#12929),.PCURVE_S1.); +#12918 = LINE('',#12919,#12920); +#12919 = CARTESIAN_POINT('',(0.1446564998,0.207558409944,0.354766421001) + ); +#12920 = VECTOR('',#12921,1.); +#12921 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#12922 = PCURVE('',#12678,#12923); +#12923 = DEFINITIONAL_REPRESENTATION('',(#12924),#12928); +#12924 = LINE('',#12925,#12926); +#12925 = CARTESIAN_POINT('',(0.475,0.275)); +#12926 = VECTOR('',#12927,1.); +#12927 = DIRECTION('',(1.,1.011968286946E-013)); +#12928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12929 = PCURVE('',#12930,#12935); +#12930 = PLANE('',#12931); +#12931 = AXIS2_PLACEMENT_3D('',#12932,#12933,#12934); +#12932 = CARTESIAN_POINT('',(0.1446564998,0.207558409944, 4.766421000566E-003)); -#10541 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10542 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#10543 = DEFINITIONAL_REPRESENTATION('',(#10544),#10548); -#10544 = LINE('',#10545,#10546); -#10545 = CARTESIAN_POINT('',(0.E+000,0.35)); -#10546 = VECTOR('',#10547,1.); -#10547 = DIRECTION('',(-1.,0.E+000)); -#10548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10549 = ORIENTED_EDGE('',*,*,#10550,.T.); -#10550 = EDGE_CURVE('',#10521,#10551,#10553,.T.); -#10551 = VERTEX_POINT('',#10552); -#10552 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 +#12933 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#12934 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#12935 = DEFINITIONAL_REPRESENTATION('',(#12936),#12940); +#12936 = LINE('',#12937,#12938); +#12937 = CARTESIAN_POINT('',(0.E+000,0.35)); +#12938 = VECTOR('',#12939,1.); +#12939 = DIRECTION('',(-1.,0.E+000)); +#12940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12941 = ORIENTED_EDGE('',*,*,#12942,.T.); +#12942 = EDGE_CURVE('',#12913,#12943,#12945,.T.); +#12943 = VERTEX_POINT('',#12944); +#12944 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 )); -#10553 = SURFACE_CURVE('',#10554,(#10559,#10570),.PCURVE_S1.); -#10554 = CIRCLE('',#10555,0.125); -#10555 = AXIS2_PLACEMENT_3D('',#10556,#10557,#10558); -#10556 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, +#12945 = SURFACE_CURVE('',#12946,(#12951,#12962),.PCURVE_S1.); +#12946 = CIRCLE('',#12947,0.125); +#12947 = AXIS2_PLACEMENT_3D('',#12948,#12949,#12950); +#12948 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, 0.354766421001)); -#10557 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#10558 = DIRECTION('',(-1.,3.502754633927E-042,-1.624097681737E-013)); -#10559 = PCURVE('',#10286,#10560); -#10560 = DEFINITIONAL_REPRESENTATION('',(#10561),#10569); -#10561 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#10562,#10563,#10564,#10565 - ,#10566,#10567,#10568),.UNSPECIFIED.,.F.,.F.) +#12949 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#12950 = DIRECTION('',(-1.,3.502754633927E-042,-1.624097681737E-013)); +#12951 = PCURVE('',#12678,#12952); +#12952 = DEFINITIONAL_REPRESENTATION('',(#12953),#12961); +#12953 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#12954,#12955,#12956,#12957 + ,#12958,#12959,#12960),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#10562 = CARTESIAN_POINT('',(0.2,0.275)); -#10563 = CARTESIAN_POINT('',(0.2,0.491506350946)); -#10564 = CARTESIAN_POINT('',(0.3875,0.383253175473)); -#10565 = CARTESIAN_POINT('',(0.575,0.275)); -#10566 = CARTESIAN_POINT('',(0.3875,0.166746824527)); -#10567 = CARTESIAN_POINT('',(0.2,5.849364905396E-002)); -#10568 = CARTESIAN_POINT('',(0.2,0.275)); -#10569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10570 = PCURVE('',#10571,#10576); -#10571 = CYLINDRICAL_SURFACE('',#10572,0.125); -#10572 = AXIS2_PLACEMENT_3D('',#10573,#10574,#10575); -#10573 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, +#12954 = CARTESIAN_POINT('',(0.2,0.275)); +#12955 = CARTESIAN_POINT('',(0.2,0.491506350946)); +#12956 = CARTESIAN_POINT('',(0.3875,0.383253175473)); +#12957 = CARTESIAN_POINT('',(0.575,0.275)); +#12958 = CARTESIAN_POINT('',(0.3875,0.166746824527)); +#12959 = CARTESIAN_POINT('',(0.2,5.849364905396E-002)); +#12960 = CARTESIAN_POINT('',(0.2,0.275)); +#12961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12962 = PCURVE('',#12963,#12968); +#12963 = CYLINDRICAL_SURFACE('',#12964,0.125); +#12964 = AXIS2_PLACEMENT_3D('',#12965,#12966,#12967); +#12965 = CARTESIAN_POINT('',(-5.34350019996E-003,0.207558409944, 0.354766421001)); -#10574 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#10575 = DIRECTION('',(-1.,3.502754633927E-042,-1.624097681737E-013)); -#10576 = DEFINITIONAL_REPRESENTATION('',(#10577),#10603); -#10577 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#10578,#10579,#10580,#10581, - #10582,#10583,#10584,#10585,#10586,#10587,#10588,#10589,#10590, - #10591,#10592,#10593,#10594,#10595,#10596,#10597,#10598,#10599, - #10600,#10601,#10602),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#12966 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#12967 = DIRECTION('',(-1.,3.502754633927E-042,-1.624097681737E-013)); +#12968 = DEFINITIONAL_REPRESENTATION('',(#12969),#12995); +#12969 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12970,#12971,#12972,#12973, + #12974,#12975,#12976,#12977,#12978,#12979,#12980,#12981,#12982, + #12983,#12984,#12985,#12986,#12987,#12988,#12989,#12990,#12991, + #12992,#12993,#12994),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -12553,485 +15542,485 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#10578 = CARTESIAN_POINT('',(3.14159265359,2.031708135064E-014)); -#10579 = CARTESIAN_POINT('',(3.189192542281,2.031708135064E-014)); -#10580 = CARTESIAN_POINT('',(3.284392319662,2.031747022155E-014)); -#10581 = CARTESIAN_POINT('',(3.427191985734,2.031572030246E-014)); -#10582 = CARTESIAN_POINT('',(3.569991651807,2.032213667246E-014)); -#10583 = CARTESIAN_POINT('',(3.712791317879,2.029822111156E-014)); -#10584 = CARTESIAN_POINT('',(3.855590983951,2.038746698514E-014)); -#10585 = CARTESIAN_POINT('',(3.998390650023,2.038746595912E-014)); -#10586 = CARTESIAN_POINT('',(4.141190316096,2.029822418961E-014)); -#10587 = CARTESIAN_POINT('',(4.283989982168,2.032212538627E-014)); -#10588 = CARTESIAN_POINT('',(4.42678964824,2.031576236914E-014)); -#10589 = CARTESIAN_POINT('',(4.569589314312,2.031731324101E-014)); -#10590 = CARTESIAN_POINT('',(4.712388980385,2.031747277066E-014)); -#10591 = CARTESIAN_POINT('',(4.855188646457,2.03152837802E-014)); -#10592 = CARTESIAN_POINT('',(4.997988312529,2.032388021237E-014)); -#10593 = CARTESIAN_POINT('',(5.140787978602,2.029168347415E-014)); -#10594 = CARTESIAN_POINT('',(5.283587644674,2.041187399485E-014)); -#10595 = CARTESIAN_POINT('',(5.426387310746,2.029637555766E-014)); -#10596 = CARTESIAN_POINT('',(5.569186976818,2.030511187834E-014)); -#10597 = CARTESIAN_POINT('',(5.711986642891,2.038566503284E-014)); -#10598 = CARTESIAN_POINT('',(5.854786308963,2.038778300155E-014)); -#10599 = CARTESIAN_POINT('',(5.997585975035,2.029875797221E-014)); -#10600 = CARTESIAN_POINT('',(6.140385641107,2.031967321347E-014)); -#10601 = CARTESIAN_POINT('',(6.235585418489,2.032324925633E-014)); -#10602 = CARTESIAN_POINT('',(6.28318530718,2.031708135064E-014)); -#10603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10604 = ORIENTED_EDGE('',*,*,#10605,.F.); -#10605 = EDGE_CURVE('',#10606,#10551,#10608,.T.); -#10606 = VERTEX_POINT('',#10607); -#10607 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944,0.354766421001 +#12970 = CARTESIAN_POINT('',(3.14159265359,2.031708135064E-014)); +#12971 = CARTESIAN_POINT('',(3.189192542281,2.031708135064E-014)); +#12972 = CARTESIAN_POINT('',(3.284392319662,2.031747022155E-014)); +#12973 = CARTESIAN_POINT('',(3.427191985734,2.031572030246E-014)); +#12974 = CARTESIAN_POINT('',(3.569991651807,2.032213667246E-014)); +#12975 = CARTESIAN_POINT('',(3.712791317879,2.029822111156E-014)); +#12976 = CARTESIAN_POINT('',(3.855590983951,2.038746698514E-014)); +#12977 = CARTESIAN_POINT('',(3.998390650023,2.038746595912E-014)); +#12978 = CARTESIAN_POINT('',(4.141190316096,2.029822418961E-014)); +#12979 = CARTESIAN_POINT('',(4.283989982168,2.032212538627E-014)); +#12980 = CARTESIAN_POINT('',(4.42678964824,2.031576236914E-014)); +#12981 = CARTESIAN_POINT('',(4.569589314312,2.031731324101E-014)); +#12982 = CARTESIAN_POINT('',(4.712388980385,2.031747277066E-014)); +#12983 = CARTESIAN_POINT('',(4.855188646457,2.03152837802E-014)); +#12984 = CARTESIAN_POINT('',(4.997988312529,2.032388021237E-014)); +#12985 = CARTESIAN_POINT('',(5.140787978602,2.029168347415E-014)); +#12986 = CARTESIAN_POINT('',(5.283587644674,2.041187399485E-014)); +#12987 = CARTESIAN_POINT('',(5.426387310746,2.029637555766E-014)); +#12988 = CARTESIAN_POINT('',(5.569186976818,2.030511187834E-014)); +#12989 = CARTESIAN_POINT('',(5.711986642891,2.038566503284E-014)); +#12990 = CARTESIAN_POINT('',(5.854786308963,2.038778300155E-014)); +#12991 = CARTESIAN_POINT('',(5.997585975035,2.029875797221E-014)); +#12992 = CARTESIAN_POINT('',(6.140385641107,2.031967321347E-014)); +#12993 = CARTESIAN_POINT('',(6.235585418489,2.032324925633E-014)); +#12994 = CARTESIAN_POINT('',(6.28318530718,2.031708135064E-014)); +#12995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#12996 = ORIENTED_EDGE('',*,*,#12997,.F.); +#12997 = EDGE_CURVE('',#12998,#12943,#13000,.T.); +#12998 = VERTEX_POINT('',#12999); +#12999 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944,0.354766421001 )); -#10608 = SURFACE_CURVE('',#10609,(#10613,#10620),.PCURVE_S1.); -#10609 = LINE('',#10610,#10611); -#10610 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 +#13000 = SURFACE_CURVE('',#13001,(#13005,#13012),.PCURVE_S1.); +#13001 = LINE('',#13002,#13003); +#13002 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 )); -#10611 = VECTOR('',#10612,1.); -#10612 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); -#10613 = PCURVE('',#10286,#10614); -#10614 = DEFINITIONAL_REPRESENTATION('',(#10615),#10619); -#10615 = LINE('',#10616,#10617); -#10616 = CARTESIAN_POINT('',(0.2,0.275)); -#10617 = VECTOR('',#10618,1.); -#10618 = DIRECTION('',(1.,1.011968286946E-013)); -#10619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10620 = PCURVE('',#10621,#10626); -#10621 = PLANE('',#10622); -#10622 = AXIS2_PLACEMENT_3D('',#10623,#10624,#10625); -#10623 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944, +#13003 = VECTOR('',#13004,1.); +#13004 = DIRECTION('',(1.,1.011968286946E-013,0.E+000)); +#13005 = PCURVE('',#12678,#13006); +#13006 = DEFINITIONAL_REPRESENTATION('',(#13007),#13011); +#13007 = LINE('',#13008,#13009); +#13008 = CARTESIAN_POINT('',(0.2,0.275)); +#13009 = VECTOR('',#13010,1.); +#13010 = DIRECTION('',(1.,1.011968286946E-013)); +#13011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13012 = PCURVE('',#13013,#13018); +#13013 = PLANE('',#13014); +#13014 = AXIS2_PLACEMENT_3D('',#13015,#13016,#13017); +#13015 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944, 4.766421000566E-003)); -#10624 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10625 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); -#10626 = DEFINITIONAL_REPRESENTATION('',(#10627),#10631); -#10627 = LINE('',#10628,#10629); -#10628 = CARTESIAN_POINT('',(0.E+000,0.35)); -#10629 = VECTOR('',#10630,1.); -#10630 = DIRECTION('',(-1.,0.E+000)); -#10631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10632 = ORIENTED_EDGE('',*,*,#10633,.F.); -#10633 = EDGE_CURVE('',#10271,#10606,#10634,.T.); -#10634 = SURFACE_CURVE('',#10635,(#10639,#10646),.PCURVE_S1.); -#10635 = LINE('',#10636,#10637); -#10636 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, +#13016 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#13017 = DIRECTION('',(-1.,-1.011968286946E-013,0.E+000)); +#13018 = DEFINITIONAL_REPRESENTATION('',(#13019),#13023); +#13019 = LINE('',#13020,#13021); +#13020 = CARTESIAN_POINT('',(0.E+000,0.35)); +#13021 = VECTOR('',#13022,1.); +#13022 = DIRECTION('',(-1.,0.E+000)); +#13023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13024 = ORIENTED_EDGE('',*,*,#13025,.F.); +#13025 = EDGE_CURVE('',#12663,#12998,#13026,.T.); +#13026 = SURFACE_CURVE('',#13027,(#13031,#13038),.PCURVE_S1.); +#13027 = LINE('',#13028,#13029); +#13028 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005585E-002, 0.354766421001)); -#10637 = VECTOR('',#10638,1.); -#10638 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); -#10639 = PCURVE('',#10286,#10640); -#10640 = DEFINITIONAL_REPRESENTATION('',(#10641),#10645); -#10641 = LINE('',#10642,#10643); -#10642 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#10643 = VECTOR('',#10644,1.); -#10644 = DIRECTION('',(-1.011968286946E-013,1.)); -#10645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10646 = PCURVE('',#10176,#10647); -#10647 = DEFINITIONAL_REPRESENTATION('',(#10648),#10652); -#10648 = LINE('',#10649,#10650); -#10649 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#10650 = VECTOR('',#10651,1.); -#10651 = DIRECTION('',(-1.,0.E+000)); -#10652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10653 = ORIENTED_EDGE('',*,*,#10270,.T.); -#10654 = ORIENTED_EDGE('',*,*,#10655,.F.); -#10655 = EDGE_CURVE('',#10523,#10243,#10656,.T.); -#10656 = SURFACE_CURVE('',#10657,(#10661,#10668),.PCURVE_S1.); -#10657 = LINE('',#10658,#10659); -#10658 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#13029 = VECTOR('',#13030,1.); +#13030 = DIRECTION('',(-1.011968286946E-013,1.,0.E+000)); +#13031 = PCURVE('',#12678,#13032); +#13032 = DEFINITIONAL_REPRESENTATION('',(#13033),#13037); +#13033 = LINE('',#13034,#13035); +#13034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13035 = VECTOR('',#13036,1.); +#13036 = DIRECTION('',(-1.011968286946E-013,1.)); +#13037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13038 = PCURVE('',#12568,#13039); +#13039 = DEFINITIONAL_REPRESENTATION('',(#13040),#13044); +#13040 = LINE('',#13041,#13042); +#13041 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#13042 = VECTOR('',#13043,1.); +#13043 = DIRECTION('',(-1.,0.E+000)); +#13044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13045 = ORIENTED_EDGE('',*,*,#12662,.T.); +#13046 = ORIENTED_EDGE('',*,*,#13047,.F.); +#13047 = EDGE_CURVE('',#12915,#12635,#13048,.T.); +#13048 = SURFACE_CURVE('',#13049,(#13053,#13060),.PCURVE_S1.); +#13049 = LINE('',#13050,#13051); +#13050 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 0.354766421001)); -#10659 = VECTOR('',#10660,1.); -#10660 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); -#10661 = PCURVE('',#10286,#10662); -#10662 = DEFINITIONAL_REPRESENTATION('',(#10663),#10667); -#10663 = LINE('',#10664,#10665); -#10664 = CARTESIAN_POINT('',(0.65,6.571132527E-014)); -#10665 = VECTOR('',#10666,1.); -#10666 = DIRECTION('',(1.011968286946E-013,-1.)); -#10667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10668 = PCURVE('',#10258,#10669); -#10669 = DEFINITIONAL_REPRESENTATION('',(#10670),#10674); -#10670 = LINE('',#10671,#10672); -#10671 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); -#10672 = VECTOR('',#10673,1.); -#10673 = DIRECTION('',(-1.,0.E+000)); -#10674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10675 = ADVANCED_FACE('',(#10676),#10621,.T.); -#10676 = FACE_BOUND('',#10677,.T.); -#10677 = EDGE_LOOP('',(#10678,#10679,#10701,#10729)); -#10678 = ORIENTED_EDGE('',*,*,#10605,.T.); -#10679 = ORIENTED_EDGE('',*,*,#10680,.T.); -#10680 = EDGE_CURVE('',#10551,#10681,#10683,.T.); -#10681 = VERTEX_POINT('',#10682); -#10682 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944, +#13051 = VECTOR('',#13052,1.); +#13052 = DIRECTION('',(1.011968286946E-013,-1.,0.E+000)); +#13053 = PCURVE('',#12678,#13054); +#13054 = DEFINITIONAL_REPRESENTATION('',(#13055),#13059); +#13055 = LINE('',#13056,#13057); +#13056 = CARTESIAN_POINT('',(0.65,6.571132527E-014)); +#13057 = VECTOR('',#13058,1.); +#13058 = DIRECTION('',(1.011968286946E-013,-1.)); +#13059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13060 = PCURVE('',#12650,#13061); +#13061 = DEFINITIONAL_REPRESENTATION('',(#13062),#13066); +#13062 = LINE('',#13063,#13064); +#13063 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); +#13064 = VECTOR('',#13065,1.); +#13065 = DIRECTION('',(-1.,0.E+000)); +#13066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13067 = ADVANCED_FACE('',(#13068),#13013,.T.); +#13068 = FACE_BOUND('',#13069,.T.); +#13069 = EDGE_LOOP('',(#13070,#13071,#13093,#13121)); +#13070 = ORIENTED_EDGE('',*,*,#12997,.T.); +#13071 = ORIENTED_EDGE('',*,*,#13072,.T.); +#13072 = EDGE_CURVE('',#12943,#13073,#13075,.T.); +#13073 = VERTEX_POINT('',#13074); +#13074 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944, 4.766421000566E-003)); -#10683 = SURFACE_CURVE('',#10684,(#10688,#10695),.PCURVE_S1.); -#10684 = LINE('',#10685,#10686); -#10685 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 +#13075 = SURFACE_CURVE('',#13076,(#13080,#13087),.PCURVE_S1.); +#13076 = LINE('',#13077,#13078); +#13077 = CARTESIAN_POINT('',(-0.1303435002,0.207558409944,0.354766421001 )); -#10686 = VECTOR('',#10687,1.); -#10687 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#10688 = PCURVE('',#10621,#10689); -#10689 = DEFINITIONAL_REPRESENTATION('',(#10690),#10694); -#10690 = LINE('',#10691,#10692); -#10691 = CARTESIAN_POINT('',(5.692668558765E-014,0.35)); -#10692 = VECTOR('',#10693,1.); -#10693 = DIRECTION('',(-1.624097681737E-013,-1.)); -#10694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10695 = PCURVE('',#10571,#10696); -#10696 = DEFINITIONAL_REPRESENTATION('',(#10697),#10700); -#10697 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10698,#10699),.UNSPECIFIED., +#13078 = VECTOR('',#13079,1.); +#13079 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#13080 = PCURVE('',#13013,#13081); +#13081 = DEFINITIONAL_REPRESENTATION('',(#13082),#13086); +#13082 = LINE('',#13083,#13084); +#13083 = CARTESIAN_POINT('',(5.692668558765E-014,0.35)); +#13084 = VECTOR('',#13085,1.); +#13085 = DIRECTION('',(-1.624097681737E-013,-1.)); +#13086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13087 = PCURVE('',#12963,#13088); +#13088 = DEFINITIONAL_REPRESENTATION('',(#13089),#13092); +#13089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13090,#13091),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#10698 = CARTESIAN_POINT('',(6.28318530718,1.010302952409E-014)); -#10699 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#10700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#13090 = CARTESIAN_POINT('',(6.28318530718,1.010302952409E-014)); +#13091 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#13092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#10701 = ORIENTED_EDGE('',*,*,#10702,.T.); -#10702 = EDGE_CURVE('',#10681,#10703,#10705,.T.); -#10703 = VERTEX_POINT('',#10704); -#10704 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944, +#13093 = ORIENTED_EDGE('',*,*,#13094,.T.); +#13094 = EDGE_CURVE('',#13073,#13095,#13097,.T.); +#13095 = VERTEX_POINT('',#13096); +#13096 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944, 4.766421000566E-003)); -#10705 = SURFACE_CURVE('',#10706,(#10710,#10717),.PCURVE_S1.); -#10706 = LINE('',#10707,#10708); -#10707 = CARTESIAN_POINT('',(-5.343500199895E-003,0.207558409944, +#13097 = SURFACE_CURVE('',#13098,(#13102,#13109),.PCURVE_S1.); +#13098 = LINE('',#13099,#13100); +#13099 = CARTESIAN_POINT('',(-5.343500199895E-003,0.207558409944, 4.766421000566E-003)); -#10708 = VECTOR('',#10709,1.); -#10709 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); -#10710 = PCURVE('',#10621,#10711); -#10711 = DEFINITIONAL_REPRESENTATION('',(#10712),#10716); -#10712 = LINE('',#10713,#10714); -#10713 = CARTESIAN_POINT('',(-0.125,0.E+000)); -#10714 = VECTOR('',#10715,1.); -#10715 = DIRECTION('',(1.,8.306531413975E-029)); -#10716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10717 = PCURVE('',#10718,#10723); -#10718 = PLANE('',#10719); -#10719 = AXIS2_PLACEMENT_3D('',#10720,#10721,#10722); -#10720 = CARTESIAN_POINT('',(-5.343500199895E-003,0.132337635525, +#13100 = VECTOR('',#13101,1.); +#13101 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); +#13102 = PCURVE('',#13013,#13103); +#13103 = DEFINITIONAL_REPRESENTATION('',(#13104),#13108); +#13104 = LINE('',#13105,#13106); +#13105 = CARTESIAN_POINT('',(-0.125,0.E+000)); +#13106 = VECTOR('',#13107,1.); +#13107 = DIRECTION('',(1.,8.306531413975E-029)); +#13108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13109 = PCURVE('',#13110,#13115); +#13110 = PLANE('',#13111); +#13111 = AXIS2_PLACEMENT_3D('',#13112,#13113,#13114); +#13112 = CARTESIAN_POINT('',(-5.343500199895E-003,0.132337635525, 4.766421000566E-003)); -#10721 = DIRECTION('',(8.306531413975E-029,8.405946365462E-042,1.)); -#10722 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); -#10723 = DEFINITIONAL_REPRESENTATION('',(#10724),#10728); -#10724 = LINE('',#10725,#10726); -#10725 = CARTESIAN_POINT('',(0.E+000,7.522077441907E-002)); -#10726 = VECTOR('',#10727,1.); -#10727 = DIRECTION('',(-1.,-1.090839840737E-085)); -#10728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10729 = ORIENTED_EDGE('',*,*,#10730,.F.); -#10730 = EDGE_CURVE('',#10606,#10703,#10731,.T.); -#10731 = SURFACE_CURVE('',#10732,(#10736,#10743),.PCURVE_S1.); -#10732 = LINE('',#10733,#10734); -#10733 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944,0.329766421001 +#13113 = DIRECTION('',(8.306531413975E-029,8.405946365462E-042,1.)); +#13114 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); +#13115 = DEFINITIONAL_REPRESENTATION('',(#13116),#13120); +#13116 = LINE('',#13117,#13118); +#13117 = CARTESIAN_POINT('',(0.E+000,7.522077441907E-002)); +#13118 = VECTOR('',#13119,1.); +#13119 = DIRECTION('',(-1.,-1.090839840737E-085)); +#13120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13121 = ORIENTED_EDGE('',*,*,#13122,.F.); +#13122 = EDGE_CURVE('',#12998,#13095,#13123,.T.); +#13123 = SURFACE_CURVE('',#13124,(#13128,#13135),.PCURVE_S1.); +#13124 = LINE('',#13125,#13126); +#13125 = CARTESIAN_POINT('',(-0.3303435002,0.207558409944,0.329766421001 )); -#10734 = VECTOR('',#10735,1.); -#10735 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10736 = PCURVE('',#10621,#10737); -#10737 = DEFINITIONAL_REPRESENTATION('',(#10738),#10742); -#10738 = LINE('',#10739,#10740); -#10739 = CARTESIAN_POINT('',(0.2,0.325)); -#10740 = VECTOR('',#10741,1.); -#10741 = DIRECTION('',(0.E+000,-1.)); -#10742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10743 = PCURVE('',#10176,#10744); -#10744 = DEFINITIONAL_REPRESENTATION('',(#10745),#10749); -#10745 = LINE('',#10746,#10747); -#10746 = CARTESIAN_POINT('',(-0.275,0.E+000)); -#10747 = VECTOR('',#10748,1.); -#10748 = DIRECTION('',(0.E+000,-1.)); -#10749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10750 = ADVANCED_FACE('',(#10751),#10176,.T.); -#10751 = FACE_BOUND('',#10752,.T.); -#10752 = EDGE_LOOP('',(#10753,#10776,#10777,#10778,#10779,#10780,#10781, - #10782)); -#10753 = ORIENTED_EDGE('',*,*,#10754,.F.); -#10754 = EDGE_CURVE('',#10443,#10755,#10757,.T.); -#10755 = VERTEX_POINT('',#10756); -#10756 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, +#13126 = VECTOR('',#13127,1.); +#13127 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#13128 = PCURVE('',#13013,#13129); +#13129 = DEFINITIONAL_REPRESENTATION('',(#13130),#13134); +#13130 = LINE('',#13131,#13132); +#13131 = CARTESIAN_POINT('',(0.2,0.325)); +#13132 = VECTOR('',#13133,1.); +#13133 = DIRECTION('',(0.E+000,-1.)); +#13134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13135 = PCURVE('',#12568,#13136); +#13136 = DEFINITIONAL_REPRESENTATION('',(#13137),#13141); +#13137 = LINE('',#13138,#13139); +#13138 = CARTESIAN_POINT('',(-0.275,0.E+000)); +#13139 = VECTOR('',#13140,1.); +#13140 = DIRECTION('',(0.E+000,-1.)); +#13141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13142 = ADVANCED_FACE('',(#13143),#12568,.T.); +#13143 = FACE_BOUND('',#13144,.T.); +#13144 = EDGE_LOOP('',(#13145,#13168,#13169,#13170,#13171,#13172,#13173, + #13174)); +#13145 = ORIENTED_EDGE('',*,*,#13146,.F.); +#13146 = EDGE_CURVE('',#12835,#13147,#13149,.T.); +#13147 = VERTEX_POINT('',#13148); +#13148 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, 4.766421000566E-003)); -#10757 = SURFACE_CURVE('',#10758,(#10762,#10769),.PCURVE_S1.); -#10758 = LINE('',#10759,#10760); -#10759 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, +#13149 = SURFACE_CURVE('',#13150,(#13154,#13161),.PCURVE_S1.); +#13150 = LINE('',#13151,#13152); +#13151 = CARTESIAN_POINT('',(-0.3303435002,-6.744159005582E-002, 4.766421000566E-003)); -#10760 = VECTOR('',#10761,1.); -#10761 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10762 = PCURVE('',#10176,#10763); -#10763 = DEFINITIONAL_REPRESENTATION('',(#10764),#10768); -#10764 = LINE('',#10765,#10766); -#10765 = CARTESIAN_POINT('',(-2.84078316426E-014,-0.325)); -#10766 = VECTOR('',#10767,1.); -#10767 = DIRECTION('',(0.E+000,-1.)); -#10768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10769 = PCURVE('',#10481,#10770); -#10770 = DEFINITIONAL_REPRESENTATION('',(#10771),#10775); -#10771 = LINE('',#10772,#10773); -#10772 = CARTESIAN_POINT('',(-1.898481372109E-014,0.E+000)); -#10773 = VECTOR('',#10774,1.); -#10774 = DIRECTION('',(0.E+000,-1.)); -#10775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10776 = ORIENTED_EDGE('',*,*,#10442,.T.); -#10777 = ORIENTED_EDGE('',*,*,#10160,.T.); -#10778 = ORIENTED_EDGE('',*,*,#10369,.T.); -#10779 = ORIENTED_EDGE('',*,*,#10298,.T.); -#10780 = ORIENTED_EDGE('',*,*,#10633,.T.); -#10781 = ORIENTED_EDGE('',*,*,#10730,.T.); -#10782 = ORIENTED_EDGE('',*,*,#10783,.T.); -#10783 = EDGE_CURVE('',#10703,#10755,#10784,.T.); -#10784 = SURFACE_CURVE('',#10785,(#10789,#10796),.PCURVE_S1.); -#10785 = LINE('',#10786,#10787); -#10786 = CARTESIAN_POINT('',(-0.3303435002,0.132337635525, +#13152 = VECTOR('',#13153,1.); +#13153 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#13154 = PCURVE('',#12568,#13155); +#13155 = DEFINITIONAL_REPRESENTATION('',(#13156),#13160); +#13156 = LINE('',#13157,#13158); +#13157 = CARTESIAN_POINT('',(-2.84078316426E-014,-0.325)); +#13158 = VECTOR('',#13159,1.); +#13159 = DIRECTION('',(0.E+000,-1.)); +#13160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13161 = PCURVE('',#12873,#13162); +#13162 = DEFINITIONAL_REPRESENTATION('',(#13163),#13167); +#13163 = LINE('',#13164,#13165); +#13164 = CARTESIAN_POINT('',(-1.898481372109E-014,0.E+000)); +#13165 = VECTOR('',#13166,1.); +#13166 = DIRECTION('',(0.E+000,-1.)); +#13167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13168 = ORIENTED_EDGE('',*,*,#12834,.T.); +#13169 = ORIENTED_EDGE('',*,*,#12552,.T.); +#13170 = ORIENTED_EDGE('',*,*,#12761,.T.); +#13171 = ORIENTED_EDGE('',*,*,#12690,.T.); +#13172 = ORIENTED_EDGE('',*,*,#13025,.T.); +#13173 = ORIENTED_EDGE('',*,*,#13122,.T.); +#13174 = ORIENTED_EDGE('',*,*,#13175,.T.); +#13175 = EDGE_CURVE('',#13095,#13147,#13176,.T.); +#13176 = SURFACE_CURVE('',#13177,(#13181,#13188),.PCURVE_S1.); +#13177 = LINE('',#13178,#13179); +#13178 = CARTESIAN_POINT('',(-0.3303435002,0.132337635525, 4.766421000566E-003)); -#10787 = VECTOR('',#10788,1.); -#10788 = DIRECTION('',(6.982425754889E-070,-1.,8.405946365462E-042)); -#10789 = PCURVE('',#10176,#10790); -#10790 = DEFINITIONAL_REPRESENTATION('',(#10791),#10795); -#10791 = LINE('',#10792,#10793); -#10792 = CARTESIAN_POINT('',(-0.199779225581,-0.325)); -#10793 = VECTOR('',#10794,1.); -#10794 = DIRECTION('',(1.,8.405946365462E-042)); -#10795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10796 = PCURVE('',#10718,#10797); -#10797 = DEFINITIONAL_REPRESENTATION('',(#10798),#10802); -#10798 = LINE('',#10799,#10800); -#10799 = CARTESIAN_POINT('',(-0.325,2.269288370339E-070)); -#10800 = VECTOR('',#10801,1.); -#10801 = DIRECTION('',(-1.435183292767E-085,-1.)); -#10802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10803 = ADVANCED_FACE('',(#10804),#10481,.T.); -#10804 = FACE_BOUND('',#10805,.T.); -#10805 = EDGE_LOOP('',(#10806,#10807,#10808,#10831)); -#10806 = ORIENTED_EDGE('',*,*,#10465,.T.); -#10807 = ORIENTED_EDGE('',*,*,#10754,.T.); -#10808 = ORIENTED_EDGE('',*,*,#10809,.T.); -#10809 = EDGE_CURVE('',#10755,#10810,#10812,.T.); -#10810 = VERTEX_POINT('',#10811); -#10811 = CARTESIAN_POINT('',(0.3196564998,-6.744159005581E-002, +#13179 = VECTOR('',#13180,1.); +#13180 = DIRECTION('',(6.982425754889E-070,-1.,8.405946365462E-042)); +#13181 = PCURVE('',#12568,#13182); +#13182 = DEFINITIONAL_REPRESENTATION('',(#13183),#13187); +#13183 = LINE('',#13184,#13185); +#13184 = CARTESIAN_POINT('',(-0.199779225581,-0.325)); +#13185 = VECTOR('',#13186,1.); +#13186 = DIRECTION('',(1.,8.405946365462E-042)); +#13187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13188 = PCURVE('',#13110,#13189); +#13189 = DEFINITIONAL_REPRESENTATION('',(#13190),#13194); +#13190 = LINE('',#13191,#13192); +#13191 = CARTESIAN_POINT('',(-0.325,2.269288370339E-070)); +#13192 = VECTOR('',#13193,1.); +#13193 = DIRECTION('',(-1.435183292767E-085,-1.)); +#13194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13195 = ADVANCED_FACE('',(#13196),#12873,.T.); +#13196 = FACE_BOUND('',#13197,.T.); +#13197 = EDGE_LOOP('',(#13198,#13199,#13200,#13223)); +#13198 = ORIENTED_EDGE('',*,*,#12857,.T.); +#13199 = ORIENTED_EDGE('',*,*,#13146,.T.); +#13200 = ORIENTED_EDGE('',*,*,#13201,.T.); +#13201 = EDGE_CURVE('',#13147,#13202,#13204,.T.); +#13202 = VERTEX_POINT('',#13203); +#13203 = CARTESIAN_POINT('',(0.3196564998,-6.744159005581E-002, 4.766421000566E-003)); -#10812 = SURFACE_CURVE('',#10813,(#10817,#10824),.PCURVE_S1.); -#10813 = LINE('',#10814,#10815); -#10814 = CARTESIAN_POINT('',(-5.343500199895E-003,-6.744159005582E-002, +#13204 = SURFACE_CURVE('',#13205,(#13209,#13216),.PCURVE_S1.); +#13205 = LINE('',#13206,#13207); +#13206 = CARTESIAN_POINT('',(-5.343500199895E-003,-6.744159005582E-002, 4.766421000566E-003)); -#10815 = VECTOR('',#10816,1.); -#10816 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); -#10817 = PCURVE('',#10481,#10818); -#10818 = DEFINITIONAL_REPRESENTATION('',(#10819),#10823); -#10819 = LINE('',#10820,#10821); -#10820 = CARTESIAN_POINT('',(0.325,-5.377642775528E-017)); -#10821 = VECTOR('',#10822,1.); -#10822 = DIRECTION('',(1.,-8.306531413975E-029)); -#10823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10824 = PCURVE('',#10718,#10825); -#10825 = DEFINITIONAL_REPRESENTATION('',(#10826),#10830); -#10826 = LINE('',#10827,#10828); -#10827 = CARTESIAN_POINT('',(0.E+000,-0.199779225581)); -#10828 = VECTOR('',#10829,1.); -#10829 = DIRECTION('',(1.,1.090839840737E-085)); -#10830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10831 = ORIENTED_EDGE('',*,*,#10832,.F.); -#10832 = EDGE_CURVE('',#10466,#10810,#10833,.T.); -#10833 = SURFACE_CURVE('',#10834,(#10838,#10845),.PCURVE_S1.); -#10834 = LINE('',#10835,#10836); -#10835 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, +#13207 = VECTOR('',#13208,1.); +#13208 = DIRECTION('',(1.,0.E+000,-8.306531413975E-029)); +#13209 = PCURVE('',#12873,#13210); +#13210 = DEFINITIONAL_REPRESENTATION('',(#13211),#13215); +#13211 = LINE('',#13212,#13213); +#13212 = CARTESIAN_POINT('',(0.325,-5.377642775528E-017)); +#13213 = VECTOR('',#13214,1.); +#13214 = DIRECTION('',(1.,-8.306531413975E-029)); +#13215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13216 = PCURVE('',#13110,#13217); +#13217 = DEFINITIONAL_REPRESENTATION('',(#13218),#13222); +#13218 = LINE('',#13219,#13220); +#13219 = CARTESIAN_POINT('',(0.E+000,-0.199779225581)); +#13220 = VECTOR('',#13221,1.); +#13221 = DIRECTION('',(1.,1.090839840737E-085)); +#13222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13223 = ORIENTED_EDGE('',*,*,#13224,.F.); +#13224 = EDGE_CURVE('',#12858,#13202,#13225,.T.); +#13225 = SURFACE_CURVE('',#13226,(#13230,#13237),.PCURVE_S1.); +#13226 = LINE('',#13227,#13228); +#13227 = CARTESIAN_POINT('',(0.3196564998,-6.744159005579E-002, 0.354766421001)); -#10836 = VECTOR('',#10837,1.); -#10837 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10838 = PCURVE('',#10481,#10839); -#10839 = DEFINITIONAL_REPRESENTATION('',(#10840),#10844); -#10840 = LINE('',#10841,#10842); -#10841 = CARTESIAN_POINT('',(0.65,0.35)); -#10842 = VECTOR('',#10843,1.); -#10843 = DIRECTION('',(0.E+000,-1.)); -#10844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10845 = PCURVE('',#10258,#10846); -#10846 = DEFINITIONAL_REPRESENTATION('',(#10847),#10851); -#10847 = LINE('',#10848,#10849); -#10848 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#10849 = VECTOR('',#10850,1.); -#10850 = DIRECTION('',(0.E+000,-1.)); -#10851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10852 = ADVANCED_FACE('',(#10853),#10258,.T.); -#10853 = FACE_BOUND('',#10854,.T.); -#10854 = EDGE_LOOP('',(#10855,#10856,#10879,#10900,#10901,#10902,#10903, - #10904)); -#10855 = ORIENTED_EDGE('',*,*,#10832,.T.); -#10856 = ORIENTED_EDGE('',*,*,#10857,.T.); -#10857 = EDGE_CURVE('',#10810,#10858,#10860,.T.); -#10858 = VERTEX_POINT('',#10859); -#10859 = CARTESIAN_POINT('',(0.3196564998,0.207558409944, +#13228 = VECTOR('',#13229,1.); +#13229 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#13230 = PCURVE('',#12873,#13231); +#13231 = DEFINITIONAL_REPRESENTATION('',(#13232),#13236); +#13232 = LINE('',#13233,#13234); +#13233 = CARTESIAN_POINT('',(0.65,0.35)); +#13234 = VECTOR('',#13235,1.); +#13235 = DIRECTION('',(0.E+000,-1.)); +#13236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13237 = PCURVE('',#12650,#13238); +#13238 = DEFINITIONAL_REPRESENTATION('',(#13239),#13243); +#13239 = LINE('',#13240,#13241); +#13240 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13241 = VECTOR('',#13242,1.); +#13242 = DIRECTION('',(0.E+000,-1.)); +#13243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13244 = ADVANCED_FACE('',(#13245),#12650,.T.); +#13245 = FACE_BOUND('',#13246,.T.); +#13246 = EDGE_LOOP('',(#13247,#13248,#13271,#13292,#13293,#13294,#13295, + #13296)); +#13247 = ORIENTED_EDGE('',*,*,#13224,.T.); +#13248 = ORIENTED_EDGE('',*,*,#13249,.T.); +#13249 = EDGE_CURVE('',#13202,#13250,#13252,.T.); +#13250 = VERTEX_POINT('',#13251); +#13251 = CARTESIAN_POINT('',(0.3196564998,0.207558409944, 4.766421000566E-003)); -#10860 = SURFACE_CURVE('',#10861,(#10865,#10872),.PCURVE_S1.); -#10861 = LINE('',#10862,#10863); -#10862 = CARTESIAN_POINT('',(0.3196564998,0.132337635525, +#13252 = SURFACE_CURVE('',#13253,(#13257,#13264),.PCURVE_S1.); +#13253 = LINE('',#13254,#13255); +#13254 = CARTESIAN_POINT('',(0.3196564998,0.132337635525, 4.766421000566E-003)); -#10863 = VECTOR('',#10864,1.); -#10864 = DIRECTION('',(-6.982425754889E-070,1.,-8.405946365462E-042)); -#10865 = PCURVE('',#10258,#10866); -#10866 = DEFINITIONAL_REPRESENTATION('',(#10867),#10871); -#10867 = LINE('',#10868,#10869); -#10868 = CARTESIAN_POINT('',(0.199779225581,-0.35)); -#10869 = VECTOR('',#10870,1.); -#10870 = DIRECTION('',(1.,-8.405946365462E-042)); -#10871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10872 = PCURVE('',#10718,#10873); -#10873 = DEFINITIONAL_REPRESENTATION('',(#10874),#10878); -#10874 = LINE('',#10875,#10876); -#10875 = CARTESIAN_POINT('',(0.325,-2.269288370339E-070)); -#10876 = VECTOR('',#10877,1.); -#10877 = DIRECTION('',(1.435183292767E-085,1.)); -#10878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10879 = ORIENTED_EDGE('',*,*,#10880,.F.); -#10880 = EDGE_CURVE('',#10523,#10858,#10881,.T.); -#10881 = SURFACE_CURVE('',#10882,(#10886,#10893),.PCURVE_S1.); -#10882 = LINE('',#10883,#10884); -#10883 = CARTESIAN_POINT('',(0.3196564998,0.207558409944, +#13255 = VECTOR('',#13256,1.); +#13256 = DIRECTION('',(-6.982425754889E-070,1.,-8.405946365462E-042)); +#13257 = PCURVE('',#12650,#13258); +#13258 = DEFINITIONAL_REPRESENTATION('',(#13259),#13263); +#13259 = LINE('',#13260,#13261); +#13260 = CARTESIAN_POINT('',(0.199779225581,-0.35)); +#13261 = VECTOR('',#13262,1.); +#13262 = DIRECTION('',(1.,-8.405946365462E-042)); +#13263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13264 = PCURVE('',#13110,#13265); +#13265 = DEFINITIONAL_REPRESENTATION('',(#13266),#13270); +#13266 = LINE('',#13267,#13268); +#13267 = CARTESIAN_POINT('',(0.325,-2.269288370339E-070)); +#13268 = VECTOR('',#13269,1.); +#13269 = DIRECTION('',(1.435183292767E-085,1.)); +#13270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13271 = ORIENTED_EDGE('',*,*,#13272,.F.); +#13272 = EDGE_CURVE('',#12915,#13250,#13273,.T.); +#13273 = SURFACE_CURVE('',#13274,(#13278,#13285),.PCURVE_S1.); +#13274 = LINE('',#13275,#13276); +#13275 = CARTESIAN_POINT('',(0.3196564998,0.207558409944, 4.766421000566E-003)); -#10884 = VECTOR('',#10885,1.); -#10885 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#10886 = PCURVE('',#10258,#10887); -#10887 = DEFINITIONAL_REPRESENTATION('',(#10888),#10892); -#10888 = LINE('',#10889,#10890); -#10889 = CARTESIAN_POINT('',(0.275,-0.35)); -#10890 = VECTOR('',#10891,1.); -#10891 = DIRECTION('',(0.E+000,-1.)); -#10892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10893 = PCURVE('',#10538,#10894); -#10894 = DEFINITIONAL_REPRESENTATION('',(#10895),#10899); -#10895 = LINE('',#10896,#10897); -#10896 = CARTESIAN_POINT('',(-0.175,0.E+000)); -#10897 = VECTOR('',#10898,1.); -#10898 = DIRECTION('',(0.E+000,-1.)); -#10899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10900 = ORIENTED_EDGE('',*,*,#10655,.T.); -#10901 = ORIENTED_EDGE('',*,*,#10242,.T.); -#10902 = ORIENTED_EDGE('',*,*,#10347,.T.); -#10903 = ORIENTED_EDGE('',*,*,#10417,.T.); -#10904 = ORIENTED_EDGE('',*,*,#10493,.T.); -#10905 = ADVANCED_FACE('',(#10906),#10538,.T.); -#10906 = FACE_BOUND('',#10907,.T.); -#10907 = EDGE_LOOP('',(#10908,#10909,#10910,#10933)); -#10908 = ORIENTED_EDGE('',*,*,#10520,.T.); -#10909 = ORIENTED_EDGE('',*,*,#10880,.T.); -#10910 = ORIENTED_EDGE('',*,*,#10911,.T.); -#10911 = EDGE_CURVE('',#10858,#10912,#10914,.T.); -#10912 = VERTEX_POINT('',#10913); -#10913 = CARTESIAN_POINT('',(0.1196564998,0.207558409944, +#13276 = VECTOR('',#13277,1.); +#13277 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#13278 = PCURVE('',#12650,#13279); +#13279 = DEFINITIONAL_REPRESENTATION('',(#13280),#13284); +#13280 = LINE('',#13281,#13282); +#13281 = CARTESIAN_POINT('',(0.275,-0.35)); +#13282 = VECTOR('',#13283,1.); +#13283 = DIRECTION('',(0.E+000,-1.)); +#13284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13285 = PCURVE('',#12930,#13286); +#13286 = DEFINITIONAL_REPRESENTATION('',(#13287),#13291); +#13287 = LINE('',#13288,#13289); +#13288 = CARTESIAN_POINT('',(-0.175,0.E+000)); +#13289 = VECTOR('',#13290,1.); +#13290 = DIRECTION('',(0.E+000,-1.)); +#13291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13292 = ORIENTED_EDGE('',*,*,#13047,.T.); +#13293 = ORIENTED_EDGE('',*,*,#12634,.T.); +#13294 = ORIENTED_EDGE('',*,*,#12739,.T.); +#13295 = ORIENTED_EDGE('',*,*,#12809,.T.); +#13296 = ORIENTED_EDGE('',*,*,#12885,.T.); +#13297 = ADVANCED_FACE('',(#13298),#12930,.T.); +#13298 = FACE_BOUND('',#13299,.T.); +#13299 = EDGE_LOOP('',(#13300,#13301,#13302,#13325)); +#13300 = ORIENTED_EDGE('',*,*,#12912,.T.); +#13301 = ORIENTED_EDGE('',*,*,#13272,.T.); +#13302 = ORIENTED_EDGE('',*,*,#13303,.T.); +#13303 = EDGE_CURVE('',#13250,#13304,#13306,.T.); +#13304 = VERTEX_POINT('',#13305); +#13305 = CARTESIAN_POINT('',(0.1196564998,0.207558409944, 4.766421000581E-003)); -#10914 = SURFACE_CURVE('',#10915,(#10919,#10926),.PCURVE_S1.); -#10915 = LINE('',#10916,#10917); -#10916 = CARTESIAN_POINT('',(-5.343500199895E-003,0.207558409944, +#13306 = SURFACE_CURVE('',#13307,(#13311,#13318),.PCURVE_S1.); +#13307 = LINE('',#13308,#13309); +#13308 = CARTESIAN_POINT('',(-5.343500199895E-003,0.207558409944, 4.766421000566E-003)); -#10917 = VECTOR('',#10918,1.); -#10918 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); -#10919 = PCURVE('',#10538,#10920); -#10920 = DEFINITIONAL_REPRESENTATION('',(#10921),#10925); -#10921 = LINE('',#10922,#10923); -#10922 = CARTESIAN_POINT('',(0.15,0.E+000)); -#10923 = VECTOR('',#10924,1.); -#10924 = DIRECTION('',(1.,8.306531413975E-029)); -#10925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10926 = PCURVE('',#10718,#10927); -#10927 = DEFINITIONAL_REPRESENTATION('',(#10928),#10932); -#10928 = LINE('',#10929,#10930); -#10929 = CARTESIAN_POINT('',(0.E+000,7.522077441911E-002)); -#10930 = VECTOR('',#10931,1.); -#10931 = DIRECTION('',(-1.,-1.090839840737E-085)); -#10932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10933 = ORIENTED_EDGE('',*,*,#10934,.T.); -#10934 = EDGE_CURVE('',#10912,#10521,#10935,.T.); -#10935 = SURFACE_CURVE('',#10936,(#10940,#10947),.PCURVE_S1.); -#10936 = LINE('',#10937,#10938); -#10937 = CARTESIAN_POINT('',(0.1196564998,0.207558409944,0.354766421001) - ); -#10938 = VECTOR('',#10939,1.); -#10939 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); -#10940 = PCURVE('',#10538,#10941); -#10941 = DEFINITIONAL_REPRESENTATION('',(#10942),#10946); -#10942 = LINE('',#10943,#10944); -#10943 = CARTESIAN_POINT('',(2.500000000003E-002,0.35)); -#10944 = VECTOR('',#10945,1.); -#10945 = DIRECTION('',(1.624097681737E-013,1.)); -#10946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10947 = PCURVE('',#10571,#10948); -#10948 = DEFINITIONAL_REPRESENTATION('',(#10949),#10952); -#10949 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#10950,#10951),.UNSPECIFIED., +#13309 = VECTOR('',#13310,1.); +#13310 = DIRECTION('',(-1.,0.E+000,8.306531413975E-029)); +#13311 = PCURVE('',#12930,#13312); +#13312 = DEFINITIONAL_REPRESENTATION('',(#13313),#13317); +#13313 = LINE('',#13314,#13315); +#13314 = CARTESIAN_POINT('',(0.15,0.E+000)); +#13315 = VECTOR('',#13316,1.); +#13316 = DIRECTION('',(1.,8.306531413975E-029)); +#13317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13318 = PCURVE('',#13110,#13319); +#13319 = DEFINITIONAL_REPRESENTATION('',(#13320),#13324); +#13320 = LINE('',#13321,#13322); +#13321 = CARTESIAN_POINT('',(0.E+000,7.522077441911E-002)); +#13322 = VECTOR('',#13323,1.); +#13323 = DIRECTION('',(-1.,-1.090839840737E-085)); +#13324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13325 = ORIENTED_EDGE('',*,*,#13326,.T.); +#13326 = EDGE_CURVE('',#13304,#12913,#13327,.T.); +#13327 = SURFACE_CURVE('',#13328,(#13332,#13339),.PCURVE_S1.); +#13328 = LINE('',#13329,#13330); +#13329 = CARTESIAN_POINT('',(0.1196564998,0.207558409944,0.354766421001) + ); +#13330 = VECTOR('',#13331,1.); +#13331 = DIRECTION('',(-1.624097681737E-013,-1.64353534882E-026,1.)); +#13332 = PCURVE('',#12930,#13333); +#13333 = DEFINITIONAL_REPRESENTATION('',(#13334),#13338); +#13334 = LINE('',#13335,#13336); +#13335 = CARTESIAN_POINT('',(2.500000000003E-002,0.35)); +#13336 = VECTOR('',#13337,1.); +#13337 = DIRECTION('',(1.624097681737E-013,1.)); +#13338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13339 = PCURVE('',#12963,#13340); +#13340 = DEFINITIONAL_REPRESENTATION('',(#13341),#13344); +#13341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13342,#13343),.UNSPECIFIED., .F.,.F.,(2,2),(-0.35,-3.042011087473E-014),.PIECEWISE_BEZIER_KNOTS.); -#10950 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#10951 = CARTESIAN_POINT('',(3.14159265359,3.047562202596E-014)); -#10952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10953 = ADVANCED_FACE('',(#10954),#10571,.F.); -#10954 = FACE_BOUND('',#10955,.F.); -#10955 = EDGE_LOOP('',(#10956,#10957,#11005,#11006)); -#10956 = ORIENTED_EDGE('',*,*,#10680,.T.); -#10957 = ORIENTED_EDGE('',*,*,#10958,.F.); -#10958 = EDGE_CURVE('',#10912,#10681,#10959,.T.); -#10959 = SURFACE_CURVE('',#10960,(#10965,#10994),.PCURVE_S1.); -#10960 = CIRCLE('',#10961,0.125); -#10961 = AXIS2_PLACEMENT_3D('',#10962,#10963,#10964); -#10962 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, +#13342 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#13343 = CARTESIAN_POINT('',(3.14159265359,3.047562202596E-014)); +#13344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13345 = ADVANCED_FACE('',(#13346),#12963,.F.); +#13346 = FACE_BOUND('',#13347,.F.); +#13347 = EDGE_LOOP('',(#13348,#13349,#13397,#13398)); +#13348 = ORIENTED_EDGE('',*,*,#13072,.T.); +#13349 = ORIENTED_EDGE('',*,*,#13350,.F.); +#13350 = EDGE_CURVE('',#13304,#13073,#13351,.T.); +#13351 = SURFACE_CURVE('',#13352,(#13357,#13386),.PCURVE_S1.); +#13352 = CIRCLE('',#13353,0.125); +#13353 = AXIS2_PLACEMENT_3D('',#13354,#13355,#13356); +#13354 = CARTESIAN_POINT('',(-5.343500199903E-003,0.207558409944, 4.766421000576E-003)); -#10963 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); -#10964 = DIRECTION('',(-1.,5.027572966497E-044,-1.624097681737E-013)); -#10965 = PCURVE('',#10571,#10966); -#10966 = DEFINITIONAL_REPRESENTATION('',(#10967),#10993); -#10967 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#10968,#10969,#10970,#10971, - #10972,#10973,#10974,#10975,#10976,#10977,#10978,#10979,#10980, - #10981,#10982,#10983,#10984,#10985,#10986,#10987,#10988,#10989, - #10990,#10991,#10992),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#13355 = DIRECTION('',(1.624097681737E-013,1.64353534882E-026,-1.)); +#13356 = DIRECTION('',(-1.,5.027572966497E-044,-1.624097681737E-013)); +#13357 = PCURVE('',#12963,#13358); +#13358 = DEFINITIONAL_REPRESENTATION('',(#13359),#13385); +#13359 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13360,#13361,#13362,#13363, + #13364,#13365,#13366,#13367,#13368,#13369,#13370,#13371,#13372, + #13373,#13374,#13375,#13376,#13377,#13378,#13379,#13380,#13381, + #13382,#13383,#13384),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -13039,1438 +16028,1438 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#10968 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#10969 = CARTESIAN_POINT('',(3.189192542281,0.35)); -#10970 = CARTESIAN_POINT('',(3.284392319662,0.35)); -#10971 = CARTESIAN_POINT('',(3.427191985734,0.35)); -#10972 = CARTESIAN_POINT('',(3.569991651807,0.35)); -#10973 = CARTESIAN_POINT('',(3.712791317879,0.35)); -#10974 = CARTESIAN_POINT('',(3.855590983951,0.35)); -#10975 = CARTESIAN_POINT('',(3.998390650023,0.35)); -#10976 = CARTESIAN_POINT('',(4.141190316096,0.35)); -#10977 = CARTESIAN_POINT('',(4.283989982168,0.35)); -#10978 = CARTESIAN_POINT('',(4.42678964824,0.35)); -#10979 = CARTESIAN_POINT('',(4.569589314312,0.35)); -#10980 = CARTESIAN_POINT('',(4.712388980385,0.35)); -#10981 = CARTESIAN_POINT('',(4.855188646457,0.35)); -#10982 = CARTESIAN_POINT('',(4.997988312529,0.35)); -#10983 = CARTESIAN_POINT('',(5.140787978602,0.35)); -#10984 = CARTESIAN_POINT('',(5.283587644674,0.35)); -#10985 = CARTESIAN_POINT('',(5.426387310746,0.35)); -#10986 = CARTESIAN_POINT('',(5.569186976818,0.35)); -#10987 = CARTESIAN_POINT('',(5.711986642891,0.35)); -#10988 = CARTESIAN_POINT('',(5.854786308963,0.35)); -#10989 = CARTESIAN_POINT('',(5.997585975035,0.35)); -#10990 = CARTESIAN_POINT('',(6.140385641107,0.35)); -#10991 = CARTESIAN_POINT('',(6.235585418489,0.35)); -#10992 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#10993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#10994 = PCURVE('',#10718,#10995); -#10995 = DEFINITIONAL_REPRESENTATION('',(#10996),#11004); -#10996 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#10997,#10998,#10999,#11000 - ,#11001,#11002,#11003),.UNSPECIFIED.,.T.,.F.) +#13360 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#13361 = CARTESIAN_POINT('',(3.189192542281,0.35)); +#13362 = CARTESIAN_POINT('',(3.284392319662,0.35)); +#13363 = CARTESIAN_POINT('',(3.427191985734,0.35)); +#13364 = CARTESIAN_POINT('',(3.569991651807,0.35)); +#13365 = CARTESIAN_POINT('',(3.712791317879,0.35)); +#13366 = CARTESIAN_POINT('',(3.855590983951,0.35)); +#13367 = CARTESIAN_POINT('',(3.998390650023,0.35)); +#13368 = CARTESIAN_POINT('',(4.141190316096,0.35)); +#13369 = CARTESIAN_POINT('',(4.283989982168,0.35)); +#13370 = CARTESIAN_POINT('',(4.42678964824,0.35)); +#13371 = CARTESIAN_POINT('',(4.569589314312,0.35)); +#13372 = CARTESIAN_POINT('',(4.712388980385,0.35)); +#13373 = CARTESIAN_POINT('',(4.855188646457,0.35)); +#13374 = CARTESIAN_POINT('',(4.997988312529,0.35)); +#13375 = CARTESIAN_POINT('',(5.140787978602,0.35)); +#13376 = CARTESIAN_POINT('',(5.283587644674,0.35)); +#13377 = CARTESIAN_POINT('',(5.426387310746,0.35)); +#13378 = CARTESIAN_POINT('',(5.569186976818,0.35)); +#13379 = CARTESIAN_POINT('',(5.711986642891,0.35)); +#13380 = CARTESIAN_POINT('',(5.854786308963,0.35)); +#13381 = CARTESIAN_POINT('',(5.997585975035,0.35)); +#13382 = CARTESIAN_POINT('',(6.140385641107,0.35)); +#13383 = CARTESIAN_POINT('',(6.235585418489,0.35)); +#13384 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#13385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13386 = PCURVE('',#13110,#13387); +#13387 = DEFINITIONAL_REPRESENTATION('',(#13388),#13396); +#13388 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#13389,#13390,#13391,#13392 + ,#13393,#13394,#13395),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#10997 = CARTESIAN_POINT('',(-0.125,7.522077441911E-002)); -#10998 = CARTESIAN_POINT('',(-0.125,0.291727125365)); -#10999 = CARTESIAN_POINT('',(6.249999999999E-002,0.183473949892)); -#11000 = CARTESIAN_POINT('',(0.25,7.522077441911E-002)); -#11001 = CARTESIAN_POINT('',(6.249999999999E-002,-3.303240105395E-002)); -#11002 = CARTESIAN_POINT('',(-0.125,-0.141285576527)); -#11003 = CARTESIAN_POINT('',(-0.125,7.522077441911E-002)); -#11004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11005 = ORIENTED_EDGE('',*,*,#10934,.T.); -#11006 = ORIENTED_EDGE('',*,*,#10550,.T.); -#11007 = ADVANCED_FACE('',(#11008),#10718,.F.); -#11008 = FACE_BOUND('',#11009,.T.); -#11009 = EDGE_LOOP('',(#11010,#11011,#11012,#11013,#11014,#11015)); -#11010 = ORIENTED_EDGE('',*,*,#10911,.F.); -#11011 = ORIENTED_EDGE('',*,*,#10857,.F.); -#11012 = ORIENTED_EDGE('',*,*,#10809,.F.); -#11013 = ORIENTED_EDGE('',*,*,#10783,.F.); -#11014 = ORIENTED_EDGE('',*,*,#10702,.F.); -#11015 = ORIENTED_EDGE('',*,*,#10958,.F.); -#11016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11020)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11017,#11018,#11019)) +#13389 = CARTESIAN_POINT('',(-0.125,7.522077441911E-002)); +#13390 = CARTESIAN_POINT('',(-0.125,0.291727125365)); +#13391 = CARTESIAN_POINT('',(6.249999999999E-002,0.183473949892)); +#13392 = CARTESIAN_POINT('',(0.25,7.522077441911E-002)); +#13393 = CARTESIAN_POINT('',(6.249999999999E-002,-3.303240105395E-002)); +#13394 = CARTESIAN_POINT('',(-0.125,-0.141285576527)); +#13395 = CARTESIAN_POINT('',(-0.125,7.522077441911E-002)); +#13396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13397 = ORIENTED_EDGE('',*,*,#13326,.T.); +#13398 = ORIENTED_EDGE('',*,*,#12942,.T.); +#13399 = ADVANCED_FACE('',(#13400),#13110,.F.); +#13400 = FACE_BOUND('',#13401,.T.); +#13401 = EDGE_LOOP('',(#13402,#13403,#13404,#13405,#13406,#13407)); +#13402 = ORIENTED_EDGE('',*,*,#13303,.F.); +#13403 = ORIENTED_EDGE('',*,*,#13249,.F.); +#13404 = ORIENTED_EDGE('',*,*,#13201,.F.); +#13405 = ORIENTED_EDGE('',*,*,#13175,.F.); +#13406 = ORIENTED_EDGE('',*,*,#13094,.F.); +#13407 = ORIENTED_EDGE('',*,*,#13350,.F.); +#13408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13412)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13409,#13410,#13411)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11017 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11018 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11019 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11020 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11017, +#13409 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13410 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13411 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13412 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13409, 'distance_accuracy_value','confusion accuracy'); -#11021 = SHAPE_DEFINITION_REPRESENTATION(#11022,#7524); -#11022 = PRODUCT_DEFINITION_SHAPE('','',#11023); -#11023 = PRODUCT_DEFINITION('design','',#11024,#11027); -#11024 = PRODUCT_DEFINITION_FORMATION('','',#11025); -#11025 = PRODUCT('LED_SMD0603','LED_SMD0603','',(#11026)); -#11026 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11027 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11028 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11029,#11031); -#11029 = ( REPRESENTATION_RELATIONSHIP('','',#7524,#7514) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11030) +#13413 = SHAPE_DEFINITION_REPRESENTATION(#13414,#9916); +#13414 = PRODUCT_DEFINITION_SHAPE('','',#13415); +#13415 = PRODUCT_DEFINITION('design','',#13416,#13419); +#13416 = PRODUCT_DEFINITION_FORMATION('','',#13417); +#13417 = PRODUCT('LED_SMD0603','LED_SMD0603','',(#13418)); +#13418 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13419 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13420 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13421,#13423); +#13421 = ( REPRESENTATION_RELATIONSHIP('','',#9916,#9906) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13422) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11030 = ITEM_DEFINED_TRANSFORMATION('','',#11,#7515); -#11031 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11032); -#11032 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('141','=>[0:1:1:10]','',#7509, - #11023,$); -#11033 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11025)); -#11034 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11035,#11037); -#11035 = ( REPRESENTATION_RELATIONSHIP('','',#7514,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11036) +#13422 = ITEM_DEFINED_TRANSFORMATION('','',#11,#9907); +#13423 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13424); +#13424 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('242','=>[0:1:1:10]','',#9901, + #13415,$); +#13425 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13417)); +#13426 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13427,#13429); +#13427 = ( REPRESENTATION_RELATIONSHIP('','',#9906,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13428) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11036 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31); -#11037 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11038); -#11038 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('142','=>[0:1:1:9]','',#5,#7509, +#13428 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31); +#13429 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13430); +#13430 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('243','=>[0:1:1:9]','',#5,#9901, $); -#11039 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#7511)); -#11040 = SHAPE_DEFINITION_REPRESENTATION(#11041,#11047); -#11041 = PRODUCT_DEFINITION_SHAPE('','',#11042); -#11042 = PRODUCT_DEFINITION('design','',#11043,#11046); -#11043 = PRODUCT_DEFINITION_FORMATION('','',#11044); -#11044 = PRODUCT('R1','R1','',(#11045)); -#11045 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11046 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11047 = SHAPE_REPRESENTATION('',(#11,#11048),#11052); -#11048 = AXIS2_PLACEMENT_3D('',#11049,#11050,#11051); -#11049 = CARTESIAN_POINT('',(7.1079995,16.51,-1.27E-002)); -#11050 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11051 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#11052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11056)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11053,#11054,#11055)) -REPRESENTATION_CONTEXT('Context #1', - '3D Context with UNIT and UNCERTAINTY') ); -#11053 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11054 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11055 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11056 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11053, - 'distance_accuracy_value','confusion accuracy'); -#11057 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11058,#11060); -#11058 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#11047) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11059) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11059 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11048); -#11060 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11061); -#11061 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('143','=>[0:1:1:7]','',#11042, - #7462,$); -#11062 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11063,#11065); -#11063 = ( REPRESENTATION_RELATIONSHIP('','',#11047,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11064) -SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11064 = ITEM_DEFINED_TRANSFORMATION('','',#11,#35); -#11065 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11066); -#11066 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('144','=>[0:1:1:11]','',#5, - #11042,$); -#11067 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11044)); -#11068 = SHAPE_DEFINITION_REPRESENTATION(#11069,#11075); -#11069 = PRODUCT_DEFINITION_SHAPE('','',#11070); -#11070 = PRODUCT_DEFINITION('design','',#11071,#11074); -#11071 = PRODUCT_DEFINITION_FORMATION('','',#11072); -#11072 = PRODUCT('JP10','JP10','',(#11073)); -#11073 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11074 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11075 = SHAPE_REPRESENTATION('',(#11,#11076,#11080,#11084,#11088), - #11092); -#11076 = AXIS2_PLACEMENT_3D('',#11077,#11078,#11079); -#11077 = CARTESIAN_POINT('',(26.81699996,34.544,-2.48730008)); -#11078 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11079 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11080 = AXIS2_PLACEMENT_3D('',#11081,#11082,#11083); -#11081 = CARTESIAN_POINT('',(21.717,34.544,-2.48730008)); -#11082 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11083 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11084 = AXIS2_PLACEMENT_3D('',#11085,#11086,#11087); -#11085 = CARTESIAN_POINT('',(24.26699998,34.544,1.27E-002)); -#11086 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11087 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11088 = AXIS2_PLACEMENT_3D('',#11089,#11090,#11091); -#11089 = CARTESIAN_POINT('',(24.26699998,34.544,-2.48730008)); -#11090 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11091 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11096)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11093,#11094,#11095)) -REPRESENTATION_CONTEXT('Context #1', - '3D Context with UNIT and UNCERTAINTY') ); -#11093 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11094 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11095 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11096 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11093, - 'distance_accuracy_value','confusion accuracy'); -#11097 = SHAPE_DEFINITION_REPRESENTATION(#11098,#11104); -#11098 = PRODUCT_DEFINITION_SHAPE('','',#11099); -#11099 = PRODUCT_DEFINITION('design','',#11100,#11103); -#11100 = PRODUCT_DEFINITION_FORMATION('','',#11101); -#11101 = PRODUCT('622893856','622893856','',(#11102)); -#11102 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11103 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11104 = SHAPE_REPRESENTATION('',(#11,#11105),#11109); -#11105 = AXIS2_PLACEMENT_3D('',#11106,#11107,#11108); -#11106 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#11107 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11108 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11113)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11110,#11111,#11112)) +#13431 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#9903)); +#13432 = SHAPE_DEFINITION_REPRESENTATION(#13433,#13439); +#13433 = PRODUCT_DEFINITION_SHAPE('','',#13434); +#13434 = PRODUCT_DEFINITION('design','',#13435,#13438); +#13435 = PRODUCT_DEFINITION_FORMATION('','',#13436); +#13436 = PRODUCT('R1','R1','',(#13437)); +#13437 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13438 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13439 = SHAPE_REPRESENTATION('',(#11,#13440),#13444); +#13440 = AXIS2_PLACEMENT_3D('',#13441,#13442,#13443); +#13441 = CARTESIAN_POINT('',(7.1079995,16.51,-1.27E-002)); +#13442 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13443 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#13444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13448)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13445,#13446,#13447)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11110 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11111 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11112 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11113 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11110, +#13445 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13446 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13447 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13448 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13445, 'distance_accuracy_value','confusion accuracy'); -#11114 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#11115),#11445); -#11115 = MANIFOLD_SOLID_BREP('',#11116); -#11116 = CLOSED_SHELL('',(#11117,#11237,#11313,#11384,#11431,#11438)); -#11117 = ADVANCED_FACE('',(#11118),#11132,.T.); -#11118 = FACE_BOUND('',#11119,.T.); -#11119 = EDGE_LOOP('',(#11120,#11155,#11183,#11211)); -#11120 = ORIENTED_EDGE('',*,*,#11121,.T.); -#11121 = EDGE_CURVE('',#11122,#11124,#11126,.T.); -#11122 = VERTEX_POINT('',#11123); -#11123 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); -#11124 = VERTEX_POINT('',#11125); -#11125 = CARTESIAN_POINT('',(-0.2499995,0.2499995,12.5)); -#11126 = SURFACE_CURVE('',#11127,(#11131,#11143),.PCURVE_S1.); -#11127 = LINE('',#11128,#11129); -#11128 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); -#11129 = VECTOR('',#11130,1.); -#11130 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11131 = PCURVE('',#11132,#11137); -#11132 = PLANE('',#11133); -#11133 = AXIS2_PLACEMENT_3D('',#11134,#11135,#11136); -#11134 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); -#11135 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11136 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11137 = DEFINITIONAL_REPRESENTATION('',(#11138),#11142); -#11138 = LINE('',#11139,#11140); -#11139 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11140 = VECTOR('',#11141,1.); -#11141 = DIRECTION('',(0.E+000,-1.)); -#11142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11143 = PCURVE('',#11144,#11149); -#11144 = PLANE('',#11145); -#11145 = AXIS2_PLACEMENT_3D('',#11146,#11147,#11148); -#11146 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); -#11147 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11148 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11149 = DEFINITIONAL_REPRESENTATION('',(#11150),#11154); -#11150 = LINE('',#11151,#11152); -#11151 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11152 = VECTOR('',#11153,1.); -#11153 = DIRECTION('',(0.E+000,-1.)); -#11154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11155 = ORIENTED_EDGE('',*,*,#11156,.T.); -#11156 = EDGE_CURVE('',#11124,#11157,#11159,.T.); -#11157 = VERTEX_POINT('',#11158); -#11158 = CARTESIAN_POINT('',(0.2499995,0.2499995,12.5)); -#11159 = SURFACE_CURVE('',#11160,(#11164,#11171),.PCURVE_S1.); -#11160 = LINE('',#11161,#11162); -#11161 = CARTESIAN_POINT('',(-0.2499995,0.2499995,12.5)); -#11162 = VECTOR('',#11163,1.); -#11163 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11164 = PCURVE('',#11132,#11165); -#11165 = DEFINITIONAL_REPRESENTATION('',(#11166),#11170); -#11166 = LINE('',#11167,#11168); -#11167 = CARTESIAN_POINT('',(0.E+000,-12.5)); -#11168 = VECTOR('',#11169,1.); -#11169 = DIRECTION('',(1.,0.E+000)); -#11170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11171 = PCURVE('',#11172,#11177); -#11172 = PLANE('',#11173); -#11173 = AXIS2_PLACEMENT_3D('',#11174,#11175,#11176); -#11174 = CARTESIAN_POINT('',(-0.2499995,0.2499995,12.5)); -#11175 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11176 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11177 = DEFINITIONAL_REPRESENTATION('',(#11178),#11182); -#11178 = LINE('',#11179,#11180); -#11179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11180 = VECTOR('',#11181,1.); -#11181 = DIRECTION('',(1.,0.E+000)); -#11182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11183 = ORIENTED_EDGE('',*,*,#11184,.F.); -#11184 = EDGE_CURVE('',#11185,#11157,#11187,.T.); -#11185 = VERTEX_POINT('',#11186); -#11186 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); -#11187 = SURFACE_CURVE('',#11188,(#11192,#11199),.PCURVE_S1.); -#11188 = LINE('',#11189,#11190); -#11189 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); -#11190 = VECTOR('',#11191,1.); -#11191 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11192 = PCURVE('',#11132,#11193); -#11193 = DEFINITIONAL_REPRESENTATION('',(#11194),#11198); -#11194 = LINE('',#11195,#11196); -#11195 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11196 = VECTOR('',#11197,1.); -#11197 = DIRECTION('',(0.E+000,-1.)); -#11198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11199 = PCURVE('',#11200,#11205); -#11200 = PLANE('',#11201); -#11201 = AXIS2_PLACEMENT_3D('',#11202,#11203,#11204); -#11202 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); -#11203 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11204 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11205 = DEFINITIONAL_REPRESENTATION('',(#11206),#11210); -#11206 = LINE('',#11207,#11208); -#11207 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11208 = VECTOR('',#11209,1.); -#11209 = DIRECTION('',(0.E+000,-1.)); -#11210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11211 = ORIENTED_EDGE('',*,*,#11212,.F.); -#11212 = EDGE_CURVE('',#11122,#11185,#11213,.T.); -#11213 = SURFACE_CURVE('',#11214,(#11218,#11225),.PCURVE_S1.); -#11214 = LINE('',#11215,#11216); -#11215 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); -#11216 = VECTOR('',#11217,1.); -#11217 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11218 = PCURVE('',#11132,#11219); -#11219 = DEFINITIONAL_REPRESENTATION('',(#11220),#11224); -#11220 = LINE('',#11221,#11222); -#11221 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11222 = VECTOR('',#11223,1.); -#11223 = DIRECTION('',(1.,0.E+000)); -#11224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11225 = PCURVE('',#11226,#11231); -#11226 = PLANE('',#11227); -#11227 = AXIS2_PLACEMENT_3D('',#11228,#11229,#11230); -#11228 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); -#11229 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11230 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11231 = DEFINITIONAL_REPRESENTATION('',(#11232),#11236); -#11232 = LINE('',#11233,#11234); -#11233 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11234 = VECTOR('',#11235,1.); -#11235 = DIRECTION('',(1.,0.E+000)); -#11236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11237 = ADVANCED_FACE('',(#11238),#11200,.T.); -#11238 = FACE_BOUND('',#11239,.T.); -#11239 = EDGE_LOOP('',(#11240,#11241,#11264,#11292)); -#11240 = ORIENTED_EDGE('',*,*,#11184,.T.); -#11241 = ORIENTED_EDGE('',*,*,#11242,.T.); -#11242 = EDGE_CURVE('',#11157,#11243,#11245,.T.); -#11243 = VERTEX_POINT('',#11244); -#11244 = CARTESIAN_POINT('',(0.2499995,-0.2499995,12.5)); -#11245 = SURFACE_CURVE('',#11246,(#11250,#11257),.PCURVE_S1.); -#11246 = LINE('',#11247,#11248); -#11247 = CARTESIAN_POINT('',(0.2499995,0.2499995,12.5)); -#11248 = VECTOR('',#11249,1.); -#11249 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11250 = PCURVE('',#11200,#11251); -#11251 = DEFINITIONAL_REPRESENTATION('',(#11252),#11256); -#11252 = LINE('',#11253,#11254); -#11253 = CARTESIAN_POINT('',(0.E+000,-12.5)); -#11254 = VECTOR('',#11255,1.); -#11255 = DIRECTION('',(1.,0.E+000)); -#11256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11257 = PCURVE('',#11172,#11258); -#11258 = DEFINITIONAL_REPRESENTATION('',(#11259),#11263); -#11259 = LINE('',#11260,#11261); -#11260 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11261 = VECTOR('',#11262,1.); -#11262 = DIRECTION('',(0.E+000,-1.)); -#11263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11264 = ORIENTED_EDGE('',*,*,#11265,.F.); -#11265 = EDGE_CURVE('',#11266,#11243,#11268,.T.); -#11266 = VERTEX_POINT('',#11267); -#11267 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); -#11268 = SURFACE_CURVE('',#11269,(#11273,#11280),.PCURVE_S1.); -#11269 = LINE('',#11270,#11271); -#11270 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); -#11271 = VECTOR('',#11272,1.); -#11272 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11273 = PCURVE('',#11200,#11274); -#11274 = DEFINITIONAL_REPRESENTATION('',(#11275),#11279); -#11275 = LINE('',#11276,#11277); -#11276 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11277 = VECTOR('',#11278,1.); -#11278 = DIRECTION('',(0.E+000,-1.)); -#11279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11280 = PCURVE('',#11281,#11286); -#11281 = PLANE('',#11282); -#11282 = AXIS2_PLACEMENT_3D('',#11283,#11284,#11285); -#11283 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); -#11284 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11285 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11286 = DEFINITIONAL_REPRESENTATION('',(#11287),#11291); -#11287 = LINE('',#11288,#11289); -#11288 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11289 = VECTOR('',#11290,1.); -#11290 = DIRECTION('',(0.E+000,-1.)); -#11291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11292 = ORIENTED_EDGE('',*,*,#11293,.F.); -#11293 = EDGE_CURVE('',#11185,#11266,#11294,.T.); -#11294 = SURFACE_CURVE('',#11295,(#11299,#11306),.PCURVE_S1.); -#11295 = LINE('',#11296,#11297); -#11296 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); -#11297 = VECTOR('',#11298,1.); -#11298 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11299 = PCURVE('',#11200,#11300); -#11300 = DEFINITIONAL_REPRESENTATION('',(#11301),#11305); -#11301 = LINE('',#11302,#11303); -#11302 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11303 = VECTOR('',#11304,1.); -#11304 = DIRECTION('',(1.,0.E+000)); -#11305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11306 = PCURVE('',#11226,#11307); -#11307 = DEFINITIONAL_REPRESENTATION('',(#11308),#11312); -#11308 = LINE('',#11309,#11310); -#11309 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11310 = VECTOR('',#11311,1.); -#11311 = DIRECTION('',(0.E+000,-1.)); -#11312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11313 = ADVANCED_FACE('',(#11314),#11281,.T.); -#11314 = FACE_BOUND('',#11315,.T.); -#11315 = EDGE_LOOP('',(#11316,#11317,#11340,#11363)); -#11316 = ORIENTED_EDGE('',*,*,#11265,.T.); -#11317 = ORIENTED_EDGE('',*,*,#11318,.T.); -#11318 = EDGE_CURVE('',#11243,#11319,#11321,.T.); -#11319 = VERTEX_POINT('',#11320); -#11320 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,12.5)); -#11321 = SURFACE_CURVE('',#11322,(#11326,#11333),.PCURVE_S1.); -#11322 = LINE('',#11323,#11324); -#11323 = CARTESIAN_POINT('',(0.2499995,-0.2499995,12.5)); -#11324 = VECTOR('',#11325,1.); -#11325 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11326 = PCURVE('',#11281,#11327); -#11327 = DEFINITIONAL_REPRESENTATION('',(#11328),#11332); -#11328 = LINE('',#11329,#11330); -#11329 = CARTESIAN_POINT('',(0.E+000,-12.5)); -#11330 = VECTOR('',#11331,1.); -#11331 = DIRECTION('',(1.,0.E+000)); -#11332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11333 = PCURVE('',#11172,#11334); -#11334 = DEFINITIONAL_REPRESENTATION('',(#11335),#11339); -#11335 = LINE('',#11336,#11337); -#11336 = CARTESIAN_POINT('',(0.499999,-0.499999)); -#11337 = VECTOR('',#11338,1.); -#11338 = DIRECTION('',(-1.,0.E+000)); -#11339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11340 = ORIENTED_EDGE('',*,*,#11341,.F.); -#11341 = EDGE_CURVE('',#11342,#11319,#11344,.T.); -#11342 = VERTEX_POINT('',#11343); -#11343 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); -#11344 = SURFACE_CURVE('',#11345,(#11349,#11356),.PCURVE_S1.); -#11345 = LINE('',#11346,#11347); -#11346 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); -#11347 = VECTOR('',#11348,1.); -#11348 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11349 = PCURVE('',#11281,#11350); -#11350 = DEFINITIONAL_REPRESENTATION('',(#11351),#11355); -#11351 = LINE('',#11352,#11353); -#11352 = CARTESIAN_POINT('',(0.499999,0.E+000)); -#11353 = VECTOR('',#11354,1.); -#11354 = DIRECTION('',(0.E+000,-1.)); -#11355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11356 = PCURVE('',#11144,#11357); -#11357 = DEFINITIONAL_REPRESENTATION('',(#11358),#11362); -#11358 = LINE('',#11359,#11360); -#11359 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11360 = VECTOR('',#11361,1.); -#11361 = DIRECTION('',(0.E+000,-1.)); -#11362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11363 = ORIENTED_EDGE('',*,*,#11364,.F.); -#11364 = EDGE_CURVE('',#11266,#11342,#11365,.T.); -#11365 = SURFACE_CURVE('',#11366,(#11370,#11377),.PCURVE_S1.); -#11366 = LINE('',#11367,#11368); -#11367 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); -#11368 = VECTOR('',#11369,1.); -#11369 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11370 = PCURVE('',#11281,#11371); -#11371 = DEFINITIONAL_REPRESENTATION('',(#11372),#11376); -#11372 = LINE('',#11373,#11374); -#11373 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11374 = VECTOR('',#11375,1.); -#11375 = DIRECTION('',(1.,0.E+000)); -#11376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11377 = PCURVE('',#11226,#11378); -#11378 = DEFINITIONAL_REPRESENTATION('',(#11379),#11383); -#11379 = LINE('',#11380,#11381); -#11380 = CARTESIAN_POINT('',(0.499999,-0.499999)); -#11381 = VECTOR('',#11382,1.); -#11382 = DIRECTION('',(-1.,0.E+000)); -#11383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11384 = ADVANCED_FACE('',(#11385),#11144,.T.); -#11385 = FACE_BOUND('',#11386,.T.); -#11386 = EDGE_LOOP('',(#11387,#11388,#11409,#11410)); -#11387 = ORIENTED_EDGE('',*,*,#11341,.T.); -#11388 = ORIENTED_EDGE('',*,*,#11389,.T.); -#11389 = EDGE_CURVE('',#11319,#11124,#11390,.T.); -#11390 = SURFACE_CURVE('',#11391,(#11395,#11402),.PCURVE_S1.); -#11391 = LINE('',#11392,#11393); -#11392 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,12.5)); -#11393 = VECTOR('',#11394,1.); -#11394 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11395 = PCURVE('',#11144,#11396); -#11396 = DEFINITIONAL_REPRESENTATION('',(#11397),#11401); -#11397 = LINE('',#11398,#11399); -#11398 = CARTESIAN_POINT('',(0.E+000,-12.5)); -#11399 = VECTOR('',#11400,1.); -#11400 = DIRECTION('',(1.,0.E+000)); -#11401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11402 = PCURVE('',#11172,#11403); -#11403 = DEFINITIONAL_REPRESENTATION('',(#11404),#11408); -#11404 = LINE('',#11405,#11406); -#11405 = CARTESIAN_POINT('',(0.E+000,-0.499999)); -#11406 = VECTOR('',#11407,1.); -#11407 = DIRECTION('',(0.E+000,1.)); -#11408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11409 = ORIENTED_EDGE('',*,*,#11121,.F.); -#11410 = ORIENTED_EDGE('',*,*,#11411,.F.); -#11411 = EDGE_CURVE('',#11342,#11122,#11412,.T.); -#11412 = SURFACE_CURVE('',#11413,(#11417,#11424),.PCURVE_S1.); -#11413 = LINE('',#11414,#11415); -#11414 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); -#11415 = VECTOR('',#11416,1.); -#11416 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11417 = PCURVE('',#11144,#11418); -#11418 = DEFINITIONAL_REPRESENTATION('',(#11419),#11423); -#11419 = LINE('',#11420,#11421); -#11420 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11421 = VECTOR('',#11422,1.); -#11422 = DIRECTION('',(1.,0.E+000)); -#11423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11424 = PCURVE('',#11226,#11425); -#11425 = DEFINITIONAL_REPRESENTATION('',(#11426),#11430); -#11426 = LINE('',#11427,#11428); -#11427 = CARTESIAN_POINT('',(0.E+000,-0.499999)); -#11428 = VECTOR('',#11429,1.); -#11429 = DIRECTION('',(0.E+000,1.)); -#11430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#13449 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13450,#13452); +#13450 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#13439) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13451) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#13451 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13440); +#13452 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13453); +#13453 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('244','=>[0:1:1:7]','',#13434, + #9854,$); +#13454 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13455,#13457); +#13455 = ( REPRESENTATION_RELATIONSHIP('','',#13439,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13456) +SHAPE_REPRESENTATION_RELATIONSHIP() ); +#13456 = ITEM_DEFINED_TRANSFORMATION('','',#11,#35); +#13457 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13458); +#13458 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('245','=>[0:1:1:11]','',#5, + #13434,$); +#13459 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13436)); +#13460 = SHAPE_DEFINITION_REPRESENTATION(#13461,#13467); +#13461 = PRODUCT_DEFINITION_SHAPE('','',#13462); +#13462 = PRODUCT_DEFINITION('design','',#13463,#13466); +#13463 = PRODUCT_DEFINITION_FORMATION('','',#13464); +#13464 = PRODUCT('JP10','JP10','',(#13465)); +#13465 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13466 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13467 = SHAPE_REPRESENTATION('',(#11,#13468,#13472,#13476,#13480), + #13484); +#13468 = AXIS2_PLACEMENT_3D('',#13469,#13470,#13471); +#13469 = CARTESIAN_POINT('',(26.81699996,34.544,-2.48730008)); +#13470 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13471 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13472 = AXIS2_PLACEMENT_3D('',#13473,#13474,#13475); +#13473 = CARTESIAN_POINT('',(21.717,34.544,-2.48730008)); +#13474 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13475 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13476 = AXIS2_PLACEMENT_3D('',#13477,#13478,#13479); +#13477 = CARTESIAN_POINT('',(24.26699998,34.544,1.27E-002)); +#13478 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13479 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13480 = AXIS2_PLACEMENT_3D('',#13481,#13482,#13483); +#13481 = CARTESIAN_POINT('',(24.26699998,34.544,-2.48730008)); +#13482 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13483 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13488)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13485,#13486,#13487)) +REPRESENTATION_CONTEXT('Context #1', + '3D Context with UNIT and UNCERTAINTY') ); +#13485 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13486 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13487 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13488 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13485, + 'distance_accuracy_value','confusion accuracy'); +#13489 = SHAPE_DEFINITION_REPRESENTATION(#13490,#13496); +#13490 = PRODUCT_DEFINITION_SHAPE('','',#13491); +#13491 = PRODUCT_DEFINITION('design','',#13492,#13495); +#13492 = PRODUCT_DEFINITION_FORMATION('','',#13493); +#13493 = PRODUCT('549160096','549160096','',(#13494)); +#13494 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13495 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13496 = SHAPE_REPRESENTATION('',(#11,#13497),#13501); +#13497 = AXIS2_PLACEMENT_3D('',#13498,#13499,#13500); +#13498 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#13499 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13500 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13505)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13502,#13503,#13504)) +REPRESENTATION_CONTEXT('Context #1', + '3D Context with UNIT and UNCERTAINTY') ); +#13502 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13503 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13504 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13505 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13502, + 'distance_accuracy_value','confusion accuracy'); +#13506 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#13507),#13837); +#13507 = MANIFOLD_SOLID_BREP('',#13508); +#13508 = CLOSED_SHELL('',(#13509,#13629,#13705,#13776,#13823,#13830)); +#13509 = ADVANCED_FACE('',(#13510),#13524,.T.); +#13510 = FACE_BOUND('',#13511,.T.); +#13511 = EDGE_LOOP('',(#13512,#13547,#13575,#13603)); +#13512 = ORIENTED_EDGE('',*,*,#13513,.T.); +#13513 = EDGE_CURVE('',#13514,#13516,#13518,.T.); +#13514 = VERTEX_POINT('',#13515); +#13515 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); +#13516 = VERTEX_POINT('',#13517); +#13517 = CARTESIAN_POINT('',(0.2499995,-0.2499995,12.5)); +#13518 = SURFACE_CURVE('',#13519,(#13523,#13535),.PCURVE_S1.); +#13519 = LINE('',#13520,#13521); +#13520 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); +#13521 = VECTOR('',#13522,1.); +#13522 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13523 = PCURVE('',#13524,#13529); +#13524 = PLANE('',#13525); +#13525 = AXIS2_PLACEMENT_3D('',#13526,#13527,#13528); +#13526 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); +#13527 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13528 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13529 = DEFINITIONAL_REPRESENTATION('',(#13530),#13534); +#13530 = LINE('',#13531,#13532); +#13531 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13532 = VECTOR('',#13533,1.); +#13533 = DIRECTION('',(0.E+000,-1.)); +#13534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13535 = PCURVE('',#13536,#13541); +#13536 = PLANE('',#13537); +#13537 = AXIS2_PLACEMENT_3D('',#13538,#13539,#13540); +#13538 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); +#13539 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13540 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13541 = DEFINITIONAL_REPRESENTATION('',(#13542),#13546); +#13542 = LINE('',#13543,#13544); +#13543 = CARTESIAN_POINT('',(0.499999,0.E+000)); +#13544 = VECTOR('',#13545,1.); +#13545 = DIRECTION('',(0.E+000,-1.)); +#13546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13547 = ORIENTED_EDGE('',*,*,#13548,.T.); +#13548 = EDGE_CURVE('',#13516,#13549,#13551,.T.); +#13549 = VERTEX_POINT('',#13550); +#13550 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,12.5)); +#13551 = SURFACE_CURVE('',#13552,(#13556,#13563),.PCURVE_S1.); +#13552 = LINE('',#13553,#13554); +#13553 = CARTESIAN_POINT('',(0.2499995,-0.2499995,12.5)); +#13554 = VECTOR('',#13555,1.); +#13555 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13556 = PCURVE('',#13524,#13557); +#13557 = DEFINITIONAL_REPRESENTATION('',(#13558),#13562); +#13558 = LINE('',#13559,#13560); +#13559 = CARTESIAN_POINT('',(0.E+000,-12.5)); +#13560 = VECTOR('',#13561,1.); +#13561 = DIRECTION('',(1.,0.E+000)); +#13562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13563 = PCURVE('',#13564,#13569); +#13564 = PLANE('',#13565); +#13565 = AXIS2_PLACEMENT_3D('',#13566,#13567,#13568); +#13566 = CARTESIAN_POINT('',(0.2499995,-0.2499995,12.5)); +#13567 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13568 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13569 = DEFINITIONAL_REPRESENTATION('',(#13570),#13574); +#13570 = LINE('',#13571,#13572); +#13571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13572 = VECTOR('',#13573,1.); +#13573 = DIRECTION('',(-1.,0.E+000)); +#13574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13575 = ORIENTED_EDGE('',*,*,#13576,.F.); +#13576 = EDGE_CURVE('',#13577,#13549,#13579,.T.); +#13577 = VERTEX_POINT('',#13578); +#13578 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); +#13579 = SURFACE_CURVE('',#13580,(#13584,#13591),.PCURVE_S1.); +#13580 = LINE('',#13581,#13582); +#13581 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); +#13582 = VECTOR('',#13583,1.); +#13583 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13584 = PCURVE('',#13524,#13585); +#13585 = DEFINITIONAL_REPRESENTATION('',(#13586),#13590); +#13586 = LINE('',#13587,#13588); +#13587 = CARTESIAN_POINT('',(0.499999,0.E+000)); +#13588 = VECTOR('',#13589,1.); +#13589 = DIRECTION('',(0.E+000,-1.)); +#13590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13591 = PCURVE('',#13592,#13597); +#13592 = PLANE('',#13593); +#13593 = AXIS2_PLACEMENT_3D('',#13594,#13595,#13596); +#13594 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); +#13595 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13596 = DIRECTION('',(0.E+000,1.,0.E+000)); +#13597 = DEFINITIONAL_REPRESENTATION('',(#13598),#13602); +#13598 = LINE('',#13599,#13600); +#13599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13600 = VECTOR('',#13601,1.); +#13601 = DIRECTION('',(0.E+000,-1.)); +#13602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#11431 = ADVANCED_FACE('',(#11432),#11226,.F.); -#11432 = FACE_BOUND('',#11433,.T.); -#11433 = EDGE_LOOP('',(#11434,#11435,#11436,#11437)); -#11434 = ORIENTED_EDGE('',*,*,#11212,.T.); -#11435 = ORIENTED_EDGE('',*,*,#11293,.T.); -#11436 = ORIENTED_EDGE('',*,*,#11364,.T.); -#11437 = ORIENTED_EDGE('',*,*,#11411,.T.); -#11438 = ADVANCED_FACE('',(#11439),#11172,.T.); -#11439 = FACE_BOUND('',#11440,.F.); -#11440 = EDGE_LOOP('',(#11441,#11442,#11443,#11444)); -#11441 = ORIENTED_EDGE('',*,*,#11156,.T.); -#11442 = ORIENTED_EDGE('',*,*,#11242,.T.); -#11443 = ORIENTED_EDGE('',*,*,#11318,.T.); -#11444 = ORIENTED_EDGE('',*,*,#11389,.T.); -#11445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11449)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11446,#11447,#11448)) +#13603 = ORIENTED_EDGE('',*,*,#13604,.F.); +#13604 = EDGE_CURVE('',#13514,#13577,#13605,.T.); +#13605 = SURFACE_CURVE('',#13606,(#13610,#13617),.PCURVE_S1.); +#13606 = LINE('',#13607,#13608); +#13607 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); +#13608 = VECTOR('',#13609,1.); +#13609 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13610 = PCURVE('',#13524,#13611); +#13611 = DEFINITIONAL_REPRESENTATION('',(#13612),#13616); +#13612 = LINE('',#13613,#13614); +#13613 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13614 = VECTOR('',#13615,1.); +#13615 = DIRECTION('',(1.,0.E+000)); +#13616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13617 = PCURVE('',#13618,#13623); +#13618 = PLANE('',#13619); +#13619 = AXIS2_PLACEMENT_3D('',#13620,#13621,#13622); +#13620 = CARTESIAN_POINT('',(0.2499995,-0.2499995,0.E+000)); +#13621 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13622 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13623 = DEFINITIONAL_REPRESENTATION('',(#13624),#13628); +#13624 = LINE('',#13625,#13626); +#13625 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13626 = VECTOR('',#13627,1.); +#13627 = DIRECTION('',(-1.,0.E+000)); +#13628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13629 = ADVANCED_FACE('',(#13630),#13592,.T.); +#13630 = FACE_BOUND('',#13631,.T.); +#13631 = EDGE_LOOP('',(#13632,#13633,#13656,#13684)); +#13632 = ORIENTED_EDGE('',*,*,#13576,.T.); +#13633 = ORIENTED_EDGE('',*,*,#13634,.T.); +#13634 = EDGE_CURVE('',#13549,#13635,#13637,.T.); +#13635 = VERTEX_POINT('',#13636); +#13636 = CARTESIAN_POINT('',(-0.2499995,0.2499995,12.5)); +#13637 = SURFACE_CURVE('',#13638,(#13642,#13649),.PCURVE_S1.); +#13638 = LINE('',#13639,#13640); +#13639 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,12.5)); +#13640 = VECTOR('',#13641,1.); +#13641 = DIRECTION('',(0.E+000,1.,0.E+000)); +#13642 = PCURVE('',#13592,#13643); +#13643 = DEFINITIONAL_REPRESENTATION('',(#13644),#13648); +#13644 = LINE('',#13645,#13646); +#13645 = CARTESIAN_POINT('',(0.E+000,-12.5)); +#13646 = VECTOR('',#13647,1.); +#13647 = DIRECTION('',(1.,0.E+000)); +#13648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13649 = PCURVE('',#13564,#13650); +#13650 = DEFINITIONAL_REPRESENTATION('',(#13651),#13655); +#13651 = LINE('',#13652,#13653); +#13652 = CARTESIAN_POINT('',(-0.499999,0.E+000)); +#13653 = VECTOR('',#13654,1.); +#13654 = DIRECTION('',(0.E+000,1.)); +#13655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13656 = ORIENTED_EDGE('',*,*,#13657,.F.); +#13657 = EDGE_CURVE('',#13658,#13635,#13660,.T.); +#13658 = VERTEX_POINT('',#13659); +#13659 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); +#13660 = SURFACE_CURVE('',#13661,(#13665,#13672),.PCURVE_S1.); +#13661 = LINE('',#13662,#13663); +#13662 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); +#13663 = VECTOR('',#13664,1.); +#13664 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13665 = PCURVE('',#13592,#13666); +#13666 = DEFINITIONAL_REPRESENTATION('',(#13667),#13671); +#13667 = LINE('',#13668,#13669); +#13668 = CARTESIAN_POINT('',(0.499999,0.E+000)); +#13669 = VECTOR('',#13670,1.); +#13670 = DIRECTION('',(0.E+000,-1.)); +#13671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13672 = PCURVE('',#13673,#13678); +#13673 = PLANE('',#13674); +#13674 = AXIS2_PLACEMENT_3D('',#13675,#13676,#13677); +#13675 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); +#13676 = DIRECTION('',(0.E+000,1.,0.E+000)); +#13677 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13678 = DEFINITIONAL_REPRESENTATION('',(#13679),#13683); +#13679 = LINE('',#13680,#13681); +#13680 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13681 = VECTOR('',#13682,1.); +#13682 = DIRECTION('',(0.E+000,-1.)); +#13683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13684 = ORIENTED_EDGE('',*,*,#13685,.F.); +#13685 = EDGE_CURVE('',#13577,#13658,#13686,.T.); +#13686 = SURFACE_CURVE('',#13687,(#13691,#13698),.PCURVE_S1.); +#13687 = LINE('',#13688,#13689); +#13688 = CARTESIAN_POINT('',(-0.2499995,-0.2499995,0.E+000)); +#13689 = VECTOR('',#13690,1.); +#13690 = DIRECTION('',(0.E+000,1.,0.E+000)); +#13691 = PCURVE('',#13592,#13692); +#13692 = DEFINITIONAL_REPRESENTATION('',(#13693),#13697); +#13693 = LINE('',#13694,#13695); +#13694 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13695 = VECTOR('',#13696,1.); +#13696 = DIRECTION('',(1.,0.E+000)); +#13697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13698 = PCURVE('',#13618,#13699); +#13699 = DEFINITIONAL_REPRESENTATION('',(#13700),#13704); +#13700 = LINE('',#13701,#13702); +#13701 = CARTESIAN_POINT('',(-0.499999,0.E+000)); +#13702 = VECTOR('',#13703,1.); +#13703 = DIRECTION('',(0.E+000,1.)); +#13704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13705 = ADVANCED_FACE('',(#13706),#13673,.T.); +#13706 = FACE_BOUND('',#13707,.T.); +#13707 = EDGE_LOOP('',(#13708,#13709,#13732,#13755)); +#13708 = ORIENTED_EDGE('',*,*,#13657,.T.); +#13709 = ORIENTED_EDGE('',*,*,#13710,.T.); +#13710 = EDGE_CURVE('',#13635,#13711,#13713,.T.); +#13711 = VERTEX_POINT('',#13712); +#13712 = CARTESIAN_POINT('',(0.2499995,0.2499995,12.5)); +#13713 = SURFACE_CURVE('',#13714,(#13718,#13725),.PCURVE_S1.); +#13714 = LINE('',#13715,#13716); +#13715 = CARTESIAN_POINT('',(-0.2499995,0.2499995,12.5)); +#13716 = VECTOR('',#13717,1.); +#13717 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13718 = PCURVE('',#13673,#13719); +#13719 = DEFINITIONAL_REPRESENTATION('',(#13720),#13724); +#13720 = LINE('',#13721,#13722); +#13721 = CARTESIAN_POINT('',(0.E+000,-12.5)); +#13722 = VECTOR('',#13723,1.); +#13723 = DIRECTION('',(1.,0.E+000)); +#13724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13725 = PCURVE('',#13564,#13726); +#13726 = DEFINITIONAL_REPRESENTATION('',(#13727),#13731); +#13727 = LINE('',#13728,#13729); +#13728 = CARTESIAN_POINT('',(-0.499999,0.499999)); +#13729 = VECTOR('',#13730,1.); +#13730 = DIRECTION('',(1.,0.E+000)); +#13731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13732 = ORIENTED_EDGE('',*,*,#13733,.F.); +#13733 = EDGE_CURVE('',#13734,#13711,#13736,.T.); +#13734 = VERTEX_POINT('',#13735); +#13735 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); +#13736 = SURFACE_CURVE('',#13737,(#13741,#13748),.PCURVE_S1.); +#13737 = LINE('',#13738,#13739); +#13738 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); +#13739 = VECTOR('',#13740,1.); +#13740 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13741 = PCURVE('',#13673,#13742); +#13742 = DEFINITIONAL_REPRESENTATION('',(#13743),#13747); +#13743 = LINE('',#13744,#13745); +#13744 = CARTESIAN_POINT('',(0.499999,0.E+000)); +#13745 = VECTOR('',#13746,1.); +#13746 = DIRECTION('',(0.E+000,-1.)); +#13747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13748 = PCURVE('',#13536,#13749); +#13749 = DEFINITIONAL_REPRESENTATION('',(#13750),#13754); +#13750 = LINE('',#13751,#13752); +#13751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13752 = VECTOR('',#13753,1.); +#13753 = DIRECTION('',(0.E+000,-1.)); +#13754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13755 = ORIENTED_EDGE('',*,*,#13756,.F.); +#13756 = EDGE_CURVE('',#13658,#13734,#13757,.T.); +#13757 = SURFACE_CURVE('',#13758,(#13762,#13769),.PCURVE_S1.); +#13758 = LINE('',#13759,#13760); +#13759 = CARTESIAN_POINT('',(-0.2499995,0.2499995,0.E+000)); +#13760 = VECTOR('',#13761,1.); +#13761 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13762 = PCURVE('',#13673,#13763); +#13763 = DEFINITIONAL_REPRESENTATION('',(#13764),#13768); +#13764 = LINE('',#13765,#13766); +#13765 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13766 = VECTOR('',#13767,1.); +#13767 = DIRECTION('',(1.,0.E+000)); +#13768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13769 = PCURVE('',#13618,#13770); +#13770 = DEFINITIONAL_REPRESENTATION('',(#13771),#13775); +#13771 = LINE('',#13772,#13773); +#13772 = CARTESIAN_POINT('',(-0.499999,0.499999)); +#13773 = VECTOR('',#13774,1.); +#13774 = DIRECTION('',(1.,0.E+000)); +#13775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13776 = ADVANCED_FACE('',(#13777),#13536,.T.); +#13777 = FACE_BOUND('',#13778,.T.); +#13778 = EDGE_LOOP('',(#13779,#13780,#13801,#13802)); +#13779 = ORIENTED_EDGE('',*,*,#13733,.T.); +#13780 = ORIENTED_EDGE('',*,*,#13781,.T.); +#13781 = EDGE_CURVE('',#13711,#13516,#13782,.T.); +#13782 = SURFACE_CURVE('',#13783,(#13787,#13794),.PCURVE_S1.); +#13783 = LINE('',#13784,#13785); +#13784 = CARTESIAN_POINT('',(0.2499995,0.2499995,12.5)); +#13785 = VECTOR('',#13786,1.); +#13786 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13787 = PCURVE('',#13536,#13788); +#13788 = DEFINITIONAL_REPRESENTATION('',(#13789),#13793); +#13789 = LINE('',#13790,#13791); +#13790 = CARTESIAN_POINT('',(0.E+000,-12.5)); +#13791 = VECTOR('',#13792,1.); +#13792 = DIRECTION('',(1.,0.E+000)); +#13793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13794 = PCURVE('',#13564,#13795); +#13795 = DEFINITIONAL_REPRESENTATION('',(#13796),#13800); +#13796 = LINE('',#13797,#13798); +#13797 = CARTESIAN_POINT('',(0.E+000,0.499999)); +#13798 = VECTOR('',#13799,1.); +#13799 = DIRECTION('',(0.E+000,-1.)); +#13800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13801 = ORIENTED_EDGE('',*,*,#13513,.F.); +#13802 = ORIENTED_EDGE('',*,*,#13803,.F.); +#13803 = EDGE_CURVE('',#13734,#13514,#13804,.T.); +#13804 = SURFACE_CURVE('',#13805,(#13809,#13816),.PCURVE_S1.); +#13805 = LINE('',#13806,#13807); +#13806 = CARTESIAN_POINT('',(0.2499995,0.2499995,0.E+000)); +#13807 = VECTOR('',#13808,1.); +#13808 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13809 = PCURVE('',#13536,#13810); +#13810 = DEFINITIONAL_REPRESENTATION('',(#13811),#13815); +#13811 = LINE('',#13812,#13813); +#13812 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13813 = VECTOR('',#13814,1.); +#13814 = DIRECTION('',(1.,0.E+000)); +#13815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13816 = PCURVE('',#13618,#13817); +#13817 = DEFINITIONAL_REPRESENTATION('',(#13818),#13822); +#13818 = LINE('',#13819,#13820); +#13819 = CARTESIAN_POINT('',(0.E+000,0.499999)); +#13820 = VECTOR('',#13821,1.); +#13821 = DIRECTION('',(0.E+000,-1.)); +#13822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13823 = ADVANCED_FACE('',(#13824),#13618,.F.); +#13824 = FACE_BOUND('',#13825,.T.); +#13825 = EDGE_LOOP('',(#13826,#13827,#13828,#13829)); +#13826 = ORIENTED_EDGE('',*,*,#13604,.T.); +#13827 = ORIENTED_EDGE('',*,*,#13685,.T.); +#13828 = ORIENTED_EDGE('',*,*,#13756,.T.); +#13829 = ORIENTED_EDGE('',*,*,#13803,.T.); +#13830 = ADVANCED_FACE('',(#13831),#13564,.T.); +#13831 = FACE_BOUND('',#13832,.F.); +#13832 = EDGE_LOOP('',(#13833,#13834,#13835,#13836)); +#13833 = ORIENTED_EDGE('',*,*,#13548,.T.); +#13834 = ORIENTED_EDGE('',*,*,#13634,.T.); +#13835 = ORIENTED_EDGE('',*,*,#13710,.T.); +#13836 = ORIENTED_EDGE('',*,*,#13781,.T.); +#13837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13841)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13838,#13839,#13840)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11446 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11447 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11448 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11449 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11446, +#13838 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13839 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13840 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13841 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13838, 'distance_accuracy_value','confusion accuracy'); -#11450 = SHAPE_DEFINITION_REPRESENTATION(#11451,#11114); -#11451 = PRODUCT_DEFINITION_SHAPE('','',#11452); -#11452 = PRODUCT_DEFINITION('design','',#11453,#11456); -#11453 = PRODUCT_DEFINITION_FORMATION('','',#11454); -#11454 = PRODUCT('Extruded','Extruded','',(#11455)); -#11455 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11456 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11457 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11458,#11460); -#11458 = ( REPRESENTATION_RELATIONSHIP('','',#11114,#11104) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11459) +#13842 = SHAPE_DEFINITION_REPRESENTATION(#13843,#13506); +#13843 = PRODUCT_DEFINITION_SHAPE('','',#13844); +#13844 = PRODUCT_DEFINITION('design','',#13845,#13848); +#13845 = PRODUCT_DEFINITION_FORMATION('','',#13846); +#13846 = PRODUCT('Extruded','Extruded','',(#13847)); +#13847 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13848 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13849 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13850,#13852); +#13850 = ( REPRESENTATION_RELATIONSHIP('','',#13506,#13496) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13851) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11459 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11105); -#11460 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11461); -#11461 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('145','=>[0:1:1:2]','',#11099, - #11452,$); -#11462 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11454)); -#11463 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11464,#11466); -#11464 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#11075) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11465) +#13851 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13497); +#13852 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13853); +#13853 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('246','=>[0:1:1:2]','',#13491, + #13844,$); +#13854 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13846)); +#13855 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13856,#13858); +#13856 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#13467) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13857) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11465 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11076); -#11466 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11467); -#11467 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('146','=>[0:1:1:13]','',#11070, - #11099,$); -#11468 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11101)); -#11469 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11470,#11472); -#11470 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#11075) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11471) +#13857 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13468); +#13858 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13859); +#13859 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('247','=>[0:1:1:13]','',#13462, + #13491,$); +#13860 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13493)); +#13861 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#13862,#13864); +#13862 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#13467) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#13863) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11471 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11080); -#11472 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11473); -#11473 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('147','=>[0:1:1:13]','',#11070, - #11099,$); -#11474 = SHAPE_DEFINITION_REPRESENTATION(#11475,#11481); -#11475 = PRODUCT_DEFINITION_SHAPE('','',#11476); -#11476 = PRODUCT_DEFINITION('design','',#11477,#11480); -#11477 = PRODUCT_DEFINITION_FORMATION('','',#11478); -#11478 = PRODUCT('622893984','622893984','',(#11479)); -#11479 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11480 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11481 = SHAPE_REPRESENTATION('',(#11,#11482),#11486); -#11482 = AXIS2_PLACEMENT_3D('',#11483,#11484,#11485); -#11483 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#11484 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11485 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11490)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11487,#11488,#11489)) +#13863 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13472); +#13864 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #13865); +#13865 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('248','=>[0:1:1:13]','',#13462, + #13491,$); +#13866 = SHAPE_DEFINITION_REPRESENTATION(#13867,#13873); +#13867 = PRODUCT_DEFINITION_SHAPE('','',#13868); +#13868 = PRODUCT_DEFINITION('design','',#13869,#13872); +#13869 = PRODUCT_DEFINITION_FORMATION('','',#13870); +#13870 = PRODUCT('549161376','549161376','',(#13871)); +#13871 = PRODUCT_CONTEXT('',#2,'mechanical'); +#13872 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#13873 = SHAPE_REPRESENTATION('',(#11,#13874),#13878); +#13874 = AXIS2_PLACEMENT_3D('',#13875,#13876,#13877); +#13875 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#13876 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13877 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#13882)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#13879,#13880,#13881)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11487 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11488 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11489 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11490 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11487, +#13879 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#13880 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#13881 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#13882 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#13879, 'distance_accuracy_value','confusion accuracy'); -#11491 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#11492),#11822); -#11492 = MANIFOLD_SOLID_BREP('',#11493); -#11493 = CLOSED_SHELL('',(#11494,#11614,#11690,#11761,#11808,#11815)); -#11494 = ADVANCED_FACE('',(#11495),#11509,.T.); -#11495 = FACE_BOUND('',#11496,.T.); -#11496 = EDGE_LOOP('',(#11497,#11532,#11560,#11588)); -#11497 = ORIENTED_EDGE('',*,*,#11498,.T.); -#11498 = EDGE_CURVE('',#11499,#11501,#11503,.T.); -#11499 = VERTEX_POINT('',#11500); -#11500 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); -#11501 = VERTEX_POINT('',#11502); -#11502 = CARTESIAN_POINT('',(-3.75000012,1.20000014,2.5)); -#11503 = SURFACE_CURVE('',#11504,(#11508,#11520),.PCURVE_S1.); -#11504 = LINE('',#11505,#11506); -#11505 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); -#11506 = VECTOR('',#11507,1.); -#11507 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11508 = PCURVE('',#11509,#11514); -#11509 = PLANE('',#11510); -#11510 = AXIS2_PLACEMENT_3D('',#11511,#11512,#11513); -#11511 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); -#11512 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11513 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11514 = DEFINITIONAL_REPRESENTATION('',(#11515),#11519); -#11515 = LINE('',#11516,#11517); -#11516 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11517 = VECTOR('',#11518,1.); -#11518 = DIRECTION('',(0.E+000,-1.)); -#11519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11520 = PCURVE('',#11521,#11526); -#11521 = PLANE('',#11522); -#11522 = AXIS2_PLACEMENT_3D('',#11523,#11524,#11525); -#11523 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); -#11524 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11525 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11526 = DEFINITIONAL_REPRESENTATION('',(#11527),#11531); -#11527 = LINE('',#11528,#11529); -#11528 = CARTESIAN_POINT('',(2.40000028,0.E+000)); -#11529 = VECTOR('',#11530,1.); -#11530 = DIRECTION('',(0.E+000,-1.)); -#11531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11532 = ORIENTED_EDGE('',*,*,#11533,.T.); -#11533 = EDGE_CURVE('',#11501,#11534,#11536,.T.); -#11534 = VERTEX_POINT('',#11535); -#11535 = CARTESIAN_POINT('',(3.75000012,1.20000014,2.5)); -#11536 = SURFACE_CURVE('',#11537,(#11541,#11548),.PCURVE_S1.); -#11537 = LINE('',#11538,#11539); -#11538 = CARTESIAN_POINT('',(-3.75000012,1.20000014,2.5)); -#11539 = VECTOR('',#11540,1.); -#11540 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11541 = PCURVE('',#11509,#11542); -#11542 = DEFINITIONAL_REPRESENTATION('',(#11543),#11547); -#11543 = LINE('',#11544,#11545); -#11544 = CARTESIAN_POINT('',(0.E+000,-2.5)); -#11545 = VECTOR('',#11546,1.); -#11546 = DIRECTION('',(1.,0.E+000)); -#11547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11548 = PCURVE('',#11549,#11554); -#11549 = PLANE('',#11550); -#11550 = AXIS2_PLACEMENT_3D('',#11551,#11552,#11553); -#11551 = CARTESIAN_POINT('',(-3.75000012,1.20000014,2.5)); -#11552 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11553 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11554 = DEFINITIONAL_REPRESENTATION('',(#11555),#11559); -#11555 = LINE('',#11556,#11557); -#11556 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11557 = VECTOR('',#11558,1.); -#11558 = DIRECTION('',(1.,0.E+000)); -#11559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11560 = ORIENTED_EDGE('',*,*,#11561,.F.); -#11561 = EDGE_CURVE('',#11562,#11534,#11564,.T.); -#11562 = VERTEX_POINT('',#11563); -#11563 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); -#11564 = SURFACE_CURVE('',#11565,(#11569,#11576),.PCURVE_S1.); -#11565 = LINE('',#11566,#11567); -#11566 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); -#11567 = VECTOR('',#11568,1.); -#11568 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11569 = PCURVE('',#11509,#11570); -#11570 = DEFINITIONAL_REPRESENTATION('',(#11571),#11575); -#11571 = LINE('',#11572,#11573); -#11572 = CARTESIAN_POINT('',(7.50000024,0.E+000)); -#11573 = VECTOR('',#11574,1.); -#11574 = DIRECTION('',(0.E+000,-1.)); -#11575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11576 = PCURVE('',#11577,#11582); -#11577 = PLANE('',#11578); -#11578 = AXIS2_PLACEMENT_3D('',#11579,#11580,#11581); -#11579 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); -#11580 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11581 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11582 = DEFINITIONAL_REPRESENTATION('',(#11583),#11587); -#11583 = LINE('',#11584,#11585); -#11584 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11585 = VECTOR('',#11586,1.); -#11586 = DIRECTION('',(0.E+000,-1.)); -#11587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11588 = ORIENTED_EDGE('',*,*,#11589,.F.); -#11589 = EDGE_CURVE('',#11499,#11562,#11590,.T.); -#11590 = SURFACE_CURVE('',#11591,(#11595,#11602),.PCURVE_S1.); -#11591 = LINE('',#11592,#11593); -#11592 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); -#11593 = VECTOR('',#11594,1.); -#11594 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11595 = PCURVE('',#11509,#11596); -#11596 = DEFINITIONAL_REPRESENTATION('',(#11597),#11601); -#11597 = LINE('',#11598,#11599); -#11598 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11599 = VECTOR('',#11600,1.); -#11600 = DIRECTION('',(1.,0.E+000)); -#11601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11602 = PCURVE('',#11603,#11608); -#11603 = PLANE('',#11604); -#11604 = AXIS2_PLACEMENT_3D('',#11605,#11606,#11607); -#11605 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); -#11606 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11607 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11608 = DEFINITIONAL_REPRESENTATION('',(#11609),#11613); -#11609 = LINE('',#11610,#11611); -#11610 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11611 = VECTOR('',#11612,1.); -#11612 = DIRECTION('',(1.,0.E+000)); -#11613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11614 = ADVANCED_FACE('',(#11615),#11577,.T.); -#11615 = FACE_BOUND('',#11616,.T.); -#11616 = EDGE_LOOP('',(#11617,#11618,#11641,#11669)); -#11617 = ORIENTED_EDGE('',*,*,#11561,.T.); -#11618 = ORIENTED_EDGE('',*,*,#11619,.T.); -#11619 = EDGE_CURVE('',#11534,#11620,#11622,.T.); -#11620 = VERTEX_POINT('',#11621); -#11621 = CARTESIAN_POINT('',(3.75000012,-1.20000014,2.5)); -#11622 = SURFACE_CURVE('',#11623,(#11627,#11634),.PCURVE_S1.); -#11623 = LINE('',#11624,#11625); -#11624 = CARTESIAN_POINT('',(3.75000012,1.20000014,2.5)); -#11625 = VECTOR('',#11626,1.); -#11626 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11627 = PCURVE('',#11577,#11628); -#11628 = DEFINITIONAL_REPRESENTATION('',(#11629),#11633); -#11629 = LINE('',#11630,#11631); -#11630 = CARTESIAN_POINT('',(0.E+000,-2.5)); -#11631 = VECTOR('',#11632,1.); -#11632 = DIRECTION('',(1.,0.E+000)); -#11633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11634 = PCURVE('',#11549,#11635); -#11635 = DEFINITIONAL_REPRESENTATION('',(#11636),#11640); -#11636 = LINE('',#11637,#11638); -#11637 = CARTESIAN_POINT('',(7.50000024,0.E+000)); -#11638 = VECTOR('',#11639,1.); -#11639 = DIRECTION('',(0.E+000,-1.)); -#11640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11641 = ORIENTED_EDGE('',*,*,#11642,.F.); -#11642 = EDGE_CURVE('',#11643,#11620,#11645,.T.); -#11643 = VERTEX_POINT('',#11644); -#11644 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); -#11645 = SURFACE_CURVE('',#11646,(#11650,#11657),.PCURVE_S1.); -#11646 = LINE('',#11647,#11648); -#11647 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); -#11648 = VECTOR('',#11649,1.); -#11649 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11650 = PCURVE('',#11577,#11651); -#11651 = DEFINITIONAL_REPRESENTATION('',(#11652),#11656); -#11652 = LINE('',#11653,#11654); -#11653 = CARTESIAN_POINT('',(2.40000028,0.E+000)); -#11654 = VECTOR('',#11655,1.); -#11655 = DIRECTION('',(0.E+000,-1.)); -#11656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#13883 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#13884),#14214); +#13884 = MANIFOLD_SOLID_BREP('',#13885); +#13885 = CLOSED_SHELL('',(#13886,#14006,#14082,#14153,#14200,#14207)); +#13886 = ADVANCED_FACE('',(#13887),#13901,.T.); +#13887 = FACE_BOUND('',#13888,.T.); +#13888 = EDGE_LOOP('',(#13889,#13924,#13952,#13980)); +#13889 = ORIENTED_EDGE('',*,*,#13890,.T.); +#13890 = EDGE_CURVE('',#13891,#13893,#13895,.T.); +#13891 = VERTEX_POINT('',#13892); +#13892 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); +#13893 = VERTEX_POINT('',#13894); +#13894 = CARTESIAN_POINT('',(3.75000012,-1.20000014,2.5)); +#13895 = SURFACE_CURVE('',#13896,(#13900,#13912),.PCURVE_S1.); +#13896 = LINE('',#13897,#13898); +#13897 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); +#13898 = VECTOR('',#13899,1.); +#13899 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13900 = PCURVE('',#13901,#13906); +#13901 = PLANE('',#13902); +#13902 = AXIS2_PLACEMENT_3D('',#13903,#13904,#13905); +#13903 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); +#13904 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13905 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13906 = DEFINITIONAL_REPRESENTATION('',(#13907),#13911); +#13907 = LINE('',#13908,#13909); +#13908 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13909 = VECTOR('',#13910,1.); +#13910 = DIRECTION('',(0.E+000,-1.)); +#13911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13912 = PCURVE('',#13913,#13918); +#13913 = PLANE('',#13914); +#13914 = AXIS2_PLACEMENT_3D('',#13915,#13916,#13917); +#13915 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); +#13916 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13917 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#13918 = DEFINITIONAL_REPRESENTATION('',(#13919),#13923); +#13919 = LINE('',#13920,#13921); +#13920 = CARTESIAN_POINT('',(2.40000028,0.E+000)); +#13921 = VECTOR('',#13922,1.); +#13922 = DIRECTION('',(0.E+000,-1.)); +#13923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13924 = ORIENTED_EDGE('',*,*,#13925,.T.); +#13925 = EDGE_CURVE('',#13893,#13926,#13928,.T.); +#13926 = VERTEX_POINT('',#13927); +#13927 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,2.5)); +#13928 = SURFACE_CURVE('',#13929,(#13933,#13940),.PCURVE_S1.); +#13929 = LINE('',#13930,#13931); +#13930 = CARTESIAN_POINT('',(3.75000012,-1.20000014,2.5)); +#13931 = VECTOR('',#13932,1.); +#13932 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13933 = PCURVE('',#13901,#13934); +#13934 = DEFINITIONAL_REPRESENTATION('',(#13935),#13939); +#13935 = LINE('',#13936,#13937); +#13936 = CARTESIAN_POINT('',(0.E+000,-2.5)); +#13937 = VECTOR('',#13938,1.); +#13938 = DIRECTION('',(1.,0.E+000)); +#13939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13940 = PCURVE('',#13941,#13946); +#13941 = PLANE('',#13942); +#13942 = AXIS2_PLACEMENT_3D('',#13943,#13944,#13945); +#13943 = CARTESIAN_POINT('',(3.75000012,-1.20000014,2.5)); +#13944 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13945 = DIRECTION('',(1.,0.E+000,0.E+000)); +#13946 = DEFINITIONAL_REPRESENTATION('',(#13947),#13951); +#13947 = LINE('',#13948,#13949); +#13948 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13949 = VECTOR('',#13950,1.); +#13950 = DIRECTION('',(-1.,0.E+000)); +#13951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13952 = ORIENTED_EDGE('',*,*,#13953,.F.); +#13953 = EDGE_CURVE('',#13954,#13926,#13956,.T.); +#13954 = VERTEX_POINT('',#13955); +#13955 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); +#13956 = SURFACE_CURVE('',#13957,(#13961,#13968),.PCURVE_S1.); +#13957 = LINE('',#13958,#13959); +#13958 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); +#13959 = VECTOR('',#13960,1.); +#13960 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13961 = PCURVE('',#13901,#13962); +#13962 = DEFINITIONAL_REPRESENTATION('',(#13963),#13967); +#13963 = LINE('',#13964,#13965); +#13964 = CARTESIAN_POINT('',(7.50000024,0.E+000)); +#13965 = VECTOR('',#13966,1.); +#13966 = DIRECTION('',(0.E+000,-1.)); +#13967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13968 = PCURVE('',#13969,#13974); +#13969 = PLANE('',#13970); +#13970 = AXIS2_PLACEMENT_3D('',#13971,#13972,#13973); +#13971 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); +#13972 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13973 = DIRECTION('',(0.E+000,1.,0.E+000)); +#13974 = DEFINITIONAL_REPRESENTATION('',(#13975),#13979); +#13975 = LINE('',#13976,#13977); +#13976 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13977 = VECTOR('',#13978,1.); +#13978 = DIRECTION('',(0.E+000,-1.)); +#13979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#11657 = PCURVE('',#11658,#11663); -#11658 = PLANE('',#11659); -#11659 = AXIS2_PLACEMENT_3D('',#11660,#11661,#11662); -#11660 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); -#11661 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11662 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11663 = DEFINITIONAL_REPRESENTATION('',(#11664),#11668); -#11664 = LINE('',#11665,#11666); -#11665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11666 = VECTOR('',#11667,1.); -#11667 = DIRECTION('',(0.E+000,-1.)); -#11668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11669 = ORIENTED_EDGE('',*,*,#11670,.F.); -#11670 = EDGE_CURVE('',#11562,#11643,#11671,.T.); -#11671 = SURFACE_CURVE('',#11672,(#11676,#11683),.PCURVE_S1.); -#11672 = LINE('',#11673,#11674); -#11673 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); -#11674 = VECTOR('',#11675,1.); -#11675 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#11676 = PCURVE('',#11577,#11677); -#11677 = DEFINITIONAL_REPRESENTATION('',(#11678),#11682); -#11678 = LINE('',#11679,#11680); -#11679 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11680 = VECTOR('',#11681,1.); -#11681 = DIRECTION('',(1.,0.E+000)); -#11682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11683 = PCURVE('',#11603,#11684); -#11684 = DEFINITIONAL_REPRESENTATION('',(#11685),#11689); -#11685 = LINE('',#11686,#11687); -#11686 = CARTESIAN_POINT('',(7.50000024,0.E+000)); -#11687 = VECTOR('',#11688,1.); -#11688 = DIRECTION('',(0.E+000,-1.)); -#11689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11690 = ADVANCED_FACE('',(#11691),#11658,.T.); -#11691 = FACE_BOUND('',#11692,.T.); -#11692 = EDGE_LOOP('',(#11693,#11694,#11717,#11740)); -#11693 = ORIENTED_EDGE('',*,*,#11642,.T.); -#11694 = ORIENTED_EDGE('',*,*,#11695,.T.); -#11695 = EDGE_CURVE('',#11620,#11696,#11698,.T.); -#11696 = VERTEX_POINT('',#11697); -#11697 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,2.5)); -#11698 = SURFACE_CURVE('',#11699,(#11703,#11710),.PCURVE_S1.); -#11699 = LINE('',#11700,#11701); -#11700 = CARTESIAN_POINT('',(3.75000012,-1.20000014,2.5)); -#11701 = VECTOR('',#11702,1.); -#11702 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11703 = PCURVE('',#11658,#11704); -#11704 = DEFINITIONAL_REPRESENTATION('',(#11705),#11709); -#11705 = LINE('',#11706,#11707); -#11706 = CARTESIAN_POINT('',(0.E+000,-2.5)); -#11707 = VECTOR('',#11708,1.); -#11708 = DIRECTION('',(1.,0.E+000)); -#11709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11710 = PCURVE('',#11549,#11711); -#11711 = DEFINITIONAL_REPRESENTATION('',(#11712),#11716); -#11712 = LINE('',#11713,#11714); -#11713 = CARTESIAN_POINT('',(7.50000024,-2.40000028)); -#11714 = VECTOR('',#11715,1.); -#11715 = DIRECTION('',(-1.,0.E+000)); -#11716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11717 = ORIENTED_EDGE('',*,*,#11718,.F.); -#11718 = EDGE_CURVE('',#11719,#11696,#11721,.T.); -#11719 = VERTEX_POINT('',#11720); -#11720 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); -#11721 = SURFACE_CURVE('',#11722,(#11726,#11733),.PCURVE_S1.); -#11722 = LINE('',#11723,#11724); -#11723 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); -#11724 = VECTOR('',#11725,1.); -#11725 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11726 = PCURVE('',#11658,#11727); -#11727 = DEFINITIONAL_REPRESENTATION('',(#11728),#11732); -#11728 = LINE('',#11729,#11730); -#11729 = CARTESIAN_POINT('',(7.50000024,0.E+000)); -#11730 = VECTOR('',#11731,1.); -#11731 = DIRECTION('',(0.E+000,-1.)); -#11732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11733 = PCURVE('',#11521,#11734); -#11734 = DEFINITIONAL_REPRESENTATION('',(#11735),#11739); -#11735 = LINE('',#11736,#11737); -#11736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11737 = VECTOR('',#11738,1.); -#11738 = DIRECTION('',(0.E+000,-1.)); -#11739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11740 = ORIENTED_EDGE('',*,*,#11741,.F.); -#11741 = EDGE_CURVE('',#11643,#11719,#11742,.T.); -#11742 = SURFACE_CURVE('',#11743,(#11747,#11754),.PCURVE_S1.); -#11743 = LINE('',#11744,#11745); -#11744 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); -#11745 = VECTOR('',#11746,1.); -#11746 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11747 = PCURVE('',#11658,#11748); -#11748 = DEFINITIONAL_REPRESENTATION('',(#11749),#11753); -#11749 = LINE('',#11750,#11751); -#11750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11751 = VECTOR('',#11752,1.); -#11752 = DIRECTION('',(1.,0.E+000)); -#11753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11754 = PCURVE('',#11603,#11755); -#11755 = DEFINITIONAL_REPRESENTATION('',(#11756),#11760); -#11756 = LINE('',#11757,#11758); -#11757 = CARTESIAN_POINT('',(7.50000024,-2.40000028)); -#11758 = VECTOR('',#11759,1.); -#11759 = DIRECTION('',(-1.,0.E+000)); -#11760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11761 = ADVANCED_FACE('',(#11762),#11521,.T.); -#11762 = FACE_BOUND('',#11763,.T.); -#11763 = EDGE_LOOP('',(#11764,#11765,#11786,#11787)); -#11764 = ORIENTED_EDGE('',*,*,#11718,.T.); -#11765 = ORIENTED_EDGE('',*,*,#11766,.T.); -#11766 = EDGE_CURVE('',#11696,#11501,#11767,.T.); -#11767 = SURFACE_CURVE('',#11768,(#11772,#11779),.PCURVE_S1.); -#11768 = LINE('',#11769,#11770); -#11769 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,2.5)); -#11770 = VECTOR('',#11771,1.); -#11771 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11772 = PCURVE('',#11521,#11773); -#11773 = DEFINITIONAL_REPRESENTATION('',(#11774),#11778); -#11774 = LINE('',#11775,#11776); -#11775 = CARTESIAN_POINT('',(0.E+000,-2.5)); -#11776 = VECTOR('',#11777,1.); -#11777 = DIRECTION('',(1.,0.E+000)); -#11778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11779 = PCURVE('',#11549,#11780); -#11780 = DEFINITIONAL_REPRESENTATION('',(#11781),#11785); -#11781 = LINE('',#11782,#11783); -#11782 = CARTESIAN_POINT('',(0.E+000,-2.40000028)); -#11783 = VECTOR('',#11784,1.); -#11784 = DIRECTION('',(0.E+000,1.)); -#11785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11786 = ORIENTED_EDGE('',*,*,#11498,.F.); -#11787 = ORIENTED_EDGE('',*,*,#11788,.F.); -#11788 = EDGE_CURVE('',#11719,#11499,#11789,.T.); -#11789 = SURFACE_CURVE('',#11790,(#11794,#11801),.PCURVE_S1.); -#11790 = LINE('',#11791,#11792); -#11791 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); -#11792 = VECTOR('',#11793,1.); -#11793 = DIRECTION('',(0.E+000,1.,0.E+000)); -#11794 = PCURVE('',#11521,#11795); -#11795 = DEFINITIONAL_REPRESENTATION('',(#11796),#11800); -#11796 = LINE('',#11797,#11798); -#11797 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#11798 = VECTOR('',#11799,1.); -#11799 = DIRECTION('',(1.,0.E+000)); -#11800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11801 = PCURVE('',#11603,#11802); -#11802 = DEFINITIONAL_REPRESENTATION('',(#11803),#11807); -#11803 = LINE('',#11804,#11805); -#11804 = CARTESIAN_POINT('',(0.E+000,-2.40000028)); -#11805 = VECTOR('',#11806,1.); -#11806 = DIRECTION('',(0.E+000,1.)); -#11807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11808 = ADVANCED_FACE('',(#11809),#11603,.F.); -#11809 = FACE_BOUND('',#11810,.T.); -#11810 = EDGE_LOOP('',(#11811,#11812,#11813,#11814)); -#11811 = ORIENTED_EDGE('',*,*,#11589,.T.); -#11812 = ORIENTED_EDGE('',*,*,#11670,.T.); -#11813 = ORIENTED_EDGE('',*,*,#11741,.T.); -#11814 = ORIENTED_EDGE('',*,*,#11788,.T.); -#11815 = ADVANCED_FACE('',(#11816),#11549,.T.); -#11816 = FACE_BOUND('',#11817,.F.); -#11817 = EDGE_LOOP('',(#11818,#11819,#11820,#11821)); -#11818 = ORIENTED_EDGE('',*,*,#11533,.T.); -#11819 = ORIENTED_EDGE('',*,*,#11619,.T.); -#11820 = ORIENTED_EDGE('',*,*,#11695,.T.); -#11821 = ORIENTED_EDGE('',*,*,#11766,.T.); -#11822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11826)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11823,#11824,#11825)) +#13980 = ORIENTED_EDGE('',*,*,#13981,.F.); +#13981 = EDGE_CURVE('',#13891,#13954,#13982,.T.); +#13982 = SURFACE_CURVE('',#13983,(#13987,#13994),.PCURVE_S1.); +#13983 = LINE('',#13984,#13985); +#13984 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); +#13985 = VECTOR('',#13986,1.); +#13986 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#13987 = PCURVE('',#13901,#13988); +#13988 = DEFINITIONAL_REPRESENTATION('',(#13989),#13993); +#13989 = LINE('',#13990,#13991); +#13990 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#13991 = VECTOR('',#13992,1.); +#13992 = DIRECTION('',(1.,0.E+000)); +#13993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#13994 = PCURVE('',#13995,#14000); +#13995 = PLANE('',#13996); +#13996 = AXIS2_PLACEMENT_3D('',#13997,#13998,#13999); +#13997 = CARTESIAN_POINT('',(3.75000012,-1.20000014,0.E+000)); +#13998 = DIRECTION('',(0.E+000,0.E+000,1.)); +#13999 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14000 = DEFINITIONAL_REPRESENTATION('',(#14001),#14005); +#14001 = LINE('',#14002,#14003); +#14002 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14003 = VECTOR('',#14004,1.); +#14004 = DIRECTION('',(-1.,0.E+000)); +#14005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14006 = ADVANCED_FACE('',(#14007),#13969,.T.); +#14007 = FACE_BOUND('',#14008,.T.); +#14008 = EDGE_LOOP('',(#14009,#14010,#14033,#14061)); +#14009 = ORIENTED_EDGE('',*,*,#13953,.T.); +#14010 = ORIENTED_EDGE('',*,*,#14011,.T.); +#14011 = EDGE_CURVE('',#13926,#14012,#14014,.T.); +#14012 = VERTEX_POINT('',#14013); +#14013 = CARTESIAN_POINT('',(-3.75000012,1.20000014,2.5)); +#14014 = SURFACE_CURVE('',#14015,(#14019,#14026),.PCURVE_S1.); +#14015 = LINE('',#14016,#14017); +#14016 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,2.5)); +#14017 = VECTOR('',#14018,1.); +#14018 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14019 = PCURVE('',#13969,#14020); +#14020 = DEFINITIONAL_REPRESENTATION('',(#14021),#14025); +#14021 = LINE('',#14022,#14023); +#14022 = CARTESIAN_POINT('',(0.E+000,-2.5)); +#14023 = VECTOR('',#14024,1.); +#14024 = DIRECTION('',(1.,0.E+000)); +#14025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14026 = PCURVE('',#13941,#14027); +#14027 = DEFINITIONAL_REPRESENTATION('',(#14028),#14032); +#14028 = LINE('',#14029,#14030); +#14029 = CARTESIAN_POINT('',(-7.50000024,0.E+000)); +#14030 = VECTOR('',#14031,1.); +#14031 = DIRECTION('',(0.E+000,1.)); +#14032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14033 = ORIENTED_EDGE('',*,*,#14034,.F.); +#14034 = EDGE_CURVE('',#14035,#14012,#14037,.T.); +#14035 = VERTEX_POINT('',#14036); +#14036 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); +#14037 = SURFACE_CURVE('',#14038,(#14042,#14049),.PCURVE_S1.); +#14038 = LINE('',#14039,#14040); +#14039 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); +#14040 = VECTOR('',#14041,1.); +#14041 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14042 = PCURVE('',#13969,#14043); +#14043 = DEFINITIONAL_REPRESENTATION('',(#14044),#14048); +#14044 = LINE('',#14045,#14046); +#14045 = CARTESIAN_POINT('',(2.40000028,0.E+000)); +#14046 = VECTOR('',#14047,1.); +#14047 = DIRECTION('',(0.E+000,-1.)); +#14048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14049 = PCURVE('',#14050,#14055); +#14050 = PLANE('',#14051); +#14051 = AXIS2_PLACEMENT_3D('',#14052,#14053,#14054); +#14052 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); +#14053 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14054 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14055 = DEFINITIONAL_REPRESENTATION('',(#14056),#14060); +#14056 = LINE('',#14057,#14058); +#14057 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14058 = VECTOR('',#14059,1.); +#14059 = DIRECTION('',(0.E+000,-1.)); +#14060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14061 = ORIENTED_EDGE('',*,*,#14062,.F.); +#14062 = EDGE_CURVE('',#13954,#14035,#14063,.T.); +#14063 = SURFACE_CURVE('',#14064,(#14068,#14075),.PCURVE_S1.); +#14064 = LINE('',#14065,#14066); +#14065 = CARTESIAN_POINT('',(-3.75000012,-1.20000014,0.E+000)); +#14066 = VECTOR('',#14067,1.); +#14067 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14068 = PCURVE('',#13969,#14069); +#14069 = DEFINITIONAL_REPRESENTATION('',(#14070),#14074); +#14070 = LINE('',#14071,#14072); +#14071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14072 = VECTOR('',#14073,1.); +#14073 = DIRECTION('',(1.,0.E+000)); +#14074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14075 = PCURVE('',#13995,#14076); +#14076 = DEFINITIONAL_REPRESENTATION('',(#14077),#14081); +#14077 = LINE('',#14078,#14079); +#14078 = CARTESIAN_POINT('',(-7.50000024,0.E+000)); +#14079 = VECTOR('',#14080,1.); +#14080 = DIRECTION('',(0.E+000,1.)); +#14081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14082 = ADVANCED_FACE('',(#14083),#14050,.T.); +#14083 = FACE_BOUND('',#14084,.T.); +#14084 = EDGE_LOOP('',(#14085,#14086,#14109,#14132)); +#14085 = ORIENTED_EDGE('',*,*,#14034,.T.); +#14086 = ORIENTED_EDGE('',*,*,#14087,.T.); +#14087 = EDGE_CURVE('',#14012,#14088,#14090,.T.); +#14088 = VERTEX_POINT('',#14089); +#14089 = CARTESIAN_POINT('',(3.75000012,1.20000014,2.5)); +#14090 = SURFACE_CURVE('',#14091,(#14095,#14102),.PCURVE_S1.); +#14091 = LINE('',#14092,#14093); +#14092 = CARTESIAN_POINT('',(-3.75000012,1.20000014,2.5)); +#14093 = VECTOR('',#14094,1.); +#14094 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14095 = PCURVE('',#14050,#14096); +#14096 = DEFINITIONAL_REPRESENTATION('',(#14097),#14101); +#14097 = LINE('',#14098,#14099); +#14098 = CARTESIAN_POINT('',(0.E+000,-2.5)); +#14099 = VECTOR('',#14100,1.); +#14100 = DIRECTION('',(1.,0.E+000)); +#14101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14102 = PCURVE('',#13941,#14103); +#14103 = DEFINITIONAL_REPRESENTATION('',(#14104),#14108); +#14104 = LINE('',#14105,#14106); +#14105 = CARTESIAN_POINT('',(-7.50000024,2.40000028)); +#14106 = VECTOR('',#14107,1.); +#14107 = DIRECTION('',(1.,0.E+000)); +#14108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14109 = ORIENTED_EDGE('',*,*,#14110,.F.); +#14110 = EDGE_CURVE('',#14111,#14088,#14113,.T.); +#14111 = VERTEX_POINT('',#14112); +#14112 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); +#14113 = SURFACE_CURVE('',#14114,(#14118,#14125),.PCURVE_S1.); +#14114 = LINE('',#14115,#14116); +#14115 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); +#14116 = VECTOR('',#14117,1.); +#14117 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14118 = PCURVE('',#14050,#14119); +#14119 = DEFINITIONAL_REPRESENTATION('',(#14120),#14124); +#14120 = LINE('',#14121,#14122); +#14121 = CARTESIAN_POINT('',(7.50000024,0.E+000)); +#14122 = VECTOR('',#14123,1.); +#14123 = DIRECTION('',(0.E+000,-1.)); +#14124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14125 = PCURVE('',#13913,#14126); +#14126 = DEFINITIONAL_REPRESENTATION('',(#14127),#14131); +#14127 = LINE('',#14128,#14129); +#14128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14129 = VECTOR('',#14130,1.); +#14130 = DIRECTION('',(0.E+000,-1.)); +#14131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14132 = ORIENTED_EDGE('',*,*,#14133,.F.); +#14133 = EDGE_CURVE('',#14035,#14111,#14134,.T.); +#14134 = SURFACE_CURVE('',#14135,(#14139,#14146),.PCURVE_S1.); +#14135 = LINE('',#14136,#14137); +#14136 = CARTESIAN_POINT('',(-3.75000012,1.20000014,0.E+000)); +#14137 = VECTOR('',#14138,1.); +#14138 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14139 = PCURVE('',#14050,#14140); +#14140 = DEFINITIONAL_REPRESENTATION('',(#14141),#14145); +#14141 = LINE('',#14142,#14143); +#14142 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14143 = VECTOR('',#14144,1.); +#14144 = DIRECTION('',(1.,0.E+000)); +#14145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14146 = PCURVE('',#13995,#14147); +#14147 = DEFINITIONAL_REPRESENTATION('',(#14148),#14152); +#14148 = LINE('',#14149,#14150); +#14149 = CARTESIAN_POINT('',(-7.50000024,2.40000028)); +#14150 = VECTOR('',#14151,1.); +#14151 = DIRECTION('',(1.,0.E+000)); +#14152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14153 = ADVANCED_FACE('',(#14154),#13913,.T.); +#14154 = FACE_BOUND('',#14155,.T.); +#14155 = EDGE_LOOP('',(#14156,#14157,#14178,#14179)); +#14156 = ORIENTED_EDGE('',*,*,#14110,.T.); +#14157 = ORIENTED_EDGE('',*,*,#14158,.T.); +#14158 = EDGE_CURVE('',#14088,#13893,#14159,.T.); +#14159 = SURFACE_CURVE('',#14160,(#14164,#14171),.PCURVE_S1.); +#14160 = LINE('',#14161,#14162); +#14161 = CARTESIAN_POINT('',(3.75000012,1.20000014,2.5)); +#14162 = VECTOR('',#14163,1.); +#14163 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#14164 = PCURVE('',#13913,#14165); +#14165 = DEFINITIONAL_REPRESENTATION('',(#14166),#14170); +#14166 = LINE('',#14167,#14168); +#14167 = CARTESIAN_POINT('',(0.E+000,-2.5)); +#14168 = VECTOR('',#14169,1.); +#14169 = DIRECTION('',(1.,0.E+000)); +#14170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14171 = PCURVE('',#13941,#14172); +#14172 = DEFINITIONAL_REPRESENTATION('',(#14173),#14177); +#14173 = LINE('',#14174,#14175); +#14174 = CARTESIAN_POINT('',(0.E+000,2.40000028)); +#14175 = VECTOR('',#14176,1.); +#14176 = DIRECTION('',(0.E+000,-1.)); +#14177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14178 = ORIENTED_EDGE('',*,*,#13890,.F.); +#14179 = ORIENTED_EDGE('',*,*,#14180,.F.); +#14180 = EDGE_CURVE('',#14111,#13891,#14181,.T.); +#14181 = SURFACE_CURVE('',#14182,(#14186,#14193),.PCURVE_S1.); +#14182 = LINE('',#14183,#14184); +#14183 = CARTESIAN_POINT('',(3.75000012,1.20000014,0.E+000)); +#14184 = VECTOR('',#14185,1.); +#14185 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#14186 = PCURVE('',#13913,#14187); +#14187 = DEFINITIONAL_REPRESENTATION('',(#14188),#14192); +#14188 = LINE('',#14189,#14190); +#14189 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14190 = VECTOR('',#14191,1.); +#14191 = DIRECTION('',(1.,0.E+000)); +#14192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14193 = PCURVE('',#13995,#14194); +#14194 = DEFINITIONAL_REPRESENTATION('',(#14195),#14199); +#14195 = LINE('',#14196,#14197); +#14196 = CARTESIAN_POINT('',(0.E+000,2.40000028)); +#14197 = VECTOR('',#14198,1.); +#14198 = DIRECTION('',(0.E+000,-1.)); +#14199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14200 = ADVANCED_FACE('',(#14201),#13995,.F.); +#14201 = FACE_BOUND('',#14202,.T.); +#14202 = EDGE_LOOP('',(#14203,#14204,#14205,#14206)); +#14203 = ORIENTED_EDGE('',*,*,#13981,.T.); +#14204 = ORIENTED_EDGE('',*,*,#14062,.T.); +#14205 = ORIENTED_EDGE('',*,*,#14133,.T.); +#14206 = ORIENTED_EDGE('',*,*,#14180,.T.); +#14207 = ADVANCED_FACE('',(#14208),#13941,.T.); +#14208 = FACE_BOUND('',#14209,.F.); +#14209 = EDGE_LOOP('',(#14210,#14211,#14212,#14213)); +#14210 = ORIENTED_EDGE('',*,*,#13925,.T.); +#14211 = ORIENTED_EDGE('',*,*,#14011,.T.); +#14212 = ORIENTED_EDGE('',*,*,#14087,.T.); +#14213 = ORIENTED_EDGE('',*,*,#14158,.T.); +#14214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#14218)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#14215,#14216,#14217)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11823 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11824 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11825 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11826 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#11823, +#14215 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#14216 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#14217 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#14218 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#14215, 'distance_accuracy_value','confusion accuracy'); -#11827 = SHAPE_DEFINITION_REPRESENTATION(#11828,#11491); -#11828 = PRODUCT_DEFINITION_SHAPE('','',#11829); -#11829 = PRODUCT_DEFINITION('design','',#11830,#11833); -#11830 = PRODUCT_DEFINITION_FORMATION('','',#11831); -#11831 = PRODUCT('Extruded','Extruded','',(#11832)); -#11832 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11833 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11834 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11835,#11837); -#11835 = ( REPRESENTATION_RELATIONSHIP('','',#11491,#11481) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11836) +#14219 = SHAPE_DEFINITION_REPRESENTATION(#14220,#13883); +#14220 = PRODUCT_DEFINITION_SHAPE('','',#14221); +#14221 = PRODUCT_DEFINITION('design','',#14222,#14225); +#14222 = PRODUCT_DEFINITION_FORMATION('','',#14223); +#14223 = PRODUCT('Extruded','Extruded','',(#14224)); +#14224 = PRODUCT_CONTEXT('',#2,'mechanical'); +#14225 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#14226 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#14227,#14229); +#14227 = ( REPRESENTATION_RELATIONSHIP('','',#13883,#13873) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#14228) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11836 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11482); -#11837 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11838); -#11838 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('148','=>[0:1:1:2]','',#11476, - #11829,$); -#11839 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11831)); -#11840 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11841,#11843); -#11841 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#11075) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11842) +#14228 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13874); +#14229 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #14230); +#14230 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('249','=>[0:1:1:2]','',#13868, + #14221,$); +#14231 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#14223)); +#14232 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#14233,#14235); +#14233 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#13467) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#14234) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11842 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11084); -#11843 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11844); -#11844 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('149','=>[0:1:1:15]','',#11070, - #11476,$); -#11845 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11478)); -#11846 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11847,#11849); -#11847 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#11075) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11848) +#14234 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13476); +#14235 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #14236); +#14236 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('250','=>[0:1:1:15]','',#13462, + #13868,$); +#14237 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13870)); +#14238 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#14239,#14241); +#14239 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#13467) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#14240) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11848 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11088); -#11849 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11850); -#11850 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('150','=>[0:1:1:13]','',#11070, - #11099,$); -#11851 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#11852,#11854); -#11852 = ( REPRESENTATION_RELATIONSHIP('','',#11075,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#11853) +#14240 = ITEM_DEFINED_TRANSFORMATION('','',#11,#13480); +#14241 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #14242); +#14242 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('251','=>[0:1:1:13]','',#13462, + #13491,$); +#14243 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#14244,#14246); +#14244 = ( REPRESENTATION_RELATIONSHIP('','',#13467,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#14245) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#11853 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39); -#11854 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #11855); -#11855 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('151','=>[0:1:1:12]','',#5, - #11070,$); -#11856 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11072)); -#11857 = SHAPE_DEFINITION_REPRESENTATION(#11858,#11864); -#11858 = PRODUCT_DEFINITION_SHAPE('','',#11859); -#11859 = PRODUCT_DEFINITION('design','',#11860,#11863); -#11860 = PRODUCT_DEFINITION_FORMATION('','',#11861); -#11861 = PRODUCT('C12','C12','',(#11862)); -#11862 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11863 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11864 = SHAPE_REPRESENTATION('',(#11,#11865),#11869); -#11865 = AXIS2_PLACEMENT_3D('',#11866,#11867,#11868); -#11866 = CARTESIAN_POINT('',(16.63691872,31.3689365,1.27E-002)); -#11867 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11868 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#11869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11873)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11870,#11871,#11872)) +#14245 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39); +#14246 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #14247); +#14247 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('252','=>[0:1:1:12]','',#5, + #13462,$); +#14248 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#13464)); +#14249 = SHAPE_DEFINITION_REPRESENTATION(#14250,#14256); +#14250 = PRODUCT_DEFINITION_SHAPE('','',#14251); +#14251 = PRODUCT_DEFINITION('design','',#14252,#14255); +#14252 = PRODUCT_DEFINITION_FORMATION('','',#14253); +#14253 = PRODUCT('C12','C12','',(#14254)); +#14254 = PRODUCT_CONTEXT('',#2,'mechanical'); +#14255 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#14256 = SHAPE_REPRESENTATION('',(#11,#14257),#14261); +#14257 = AXIS2_PLACEMENT_3D('',#14258,#14259,#14260); +#14258 = CARTESIAN_POINT('',(16.63691872,31.3689365,1.27E-002)); +#14259 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14260 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#14261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#14265)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#14262,#14263,#14264)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11870 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11871 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11872 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11873 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#11870, +#14262 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#14263 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#14264 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#14265 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#14262, 'distance_accuracy_value','confusion accuracy'); -#11874 = SHAPE_DEFINITION_REPRESENTATION(#11875,#11881); -#11875 = PRODUCT_DEFINITION_SHAPE('','',#11876); -#11876 = PRODUCT_DEFINITION('design','',#11877,#11880); -#11877 = PRODUCT_DEFINITION_FORMATION('','',#11878); -#11878 = PRODUCT('0402HD','0402HD','',(#11879)); -#11879 = PRODUCT_CONTEXT('',#2,'mechanical'); -#11880 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#11881 = SHAPE_REPRESENTATION('',(#11,#11882,#11886),#11890); -#11882 = AXIS2_PLACEMENT_3D('',#11883,#11884,#11885); -#11883 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#11884 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11885 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11886 = AXIS2_PLACEMENT_3D('',#11887,#11888,#11889); -#11887 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#11888 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11889 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#11894)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#11891,#11892,#11893)) +#14266 = SHAPE_DEFINITION_REPRESENTATION(#14267,#14273); +#14267 = PRODUCT_DEFINITION_SHAPE('','',#14268); +#14268 = PRODUCT_DEFINITION('design','',#14269,#14272); +#14269 = PRODUCT_DEFINITION_FORMATION('','',#14270); +#14270 = PRODUCT('0402HD','0402HD','',(#14271)); +#14271 = PRODUCT_CONTEXT('',#2,'mechanical'); +#14272 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#14273 = SHAPE_REPRESENTATION('',(#11,#14274,#14278),#14282); +#14274 = AXIS2_PLACEMENT_3D('',#14275,#14276,#14277); +#14275 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#14276 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14277 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14278 = AXIS2_PLACEMENT_3D('',#14279,#14280,#14281); +#14279 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#14280 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14281 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#14286)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#14283,#14284,#14285)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#11891 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#11892 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#11893 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#11894 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#11891, +#14283 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#14284 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#14285 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#14286 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#14283, 'distance_accuracy_value','confusion accuracy'); -#11895 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#11896),#16362); -#11896 = MANIFOLD_SOLID_BREP('',#11897); -#11897 = CLOSED_SHELL('',(#11898,#12013,#12129,#12287,#12402,#12499, - #12591,#12688,#12780,#12877,#12908,#13016,#13068,#13155,#13207, - #13317,#13369,#13456,#13487,#13603,#13742,#13812,#13907,#13977, - #14072,#14142,#14237,#14263,#14421,#14513,#14610,#14702,#14799, - #14891,#14988,#15019,#15054,#15162,#15214,#15301,#15353,#15463, - #15515,#15625,#15656,#15687,#15826,#15896,#15991,#16061,#16156, - #16226,#16321,#16347)); -#11898 = ADVANCED_FACE('',(#11899),#11914,.T.); -#11899 = FACE_BOUND('',#11900,.T.); -#11900 = EDGE_LOOP('',(#11901,#11936,#11962,#11994)); -#11901 = ORIENTED_EDGE('',*,*,#11902,.T.); -#11902 = EDGE_CURVE('',#11903,#11905,#11907,.T.); -#11903 = VERTEX_POINT('',#11904); -#11904 = CARTESIAN_POINT('',(-0.25,0.E+000,0.221740556244)); -#11905 = VERTEX_POINT('',#11906); -#11906 = CARTESIAN_POINT('',(-0.25,9.584017729891E-018,0.378259443756)); -#11907 = SURFACE_CURVE('',#11908,(#11913,#11924),.PCURVE_S1.); -#11908 = CIRCLE('',#11909,7.825944375606E-002); -#11909 = AXIS2_PLACEMENT_3D('',#11910,#11911,#11912); -#11910 = CARTESIAN_POINT('',(-0.25,0.E+000,0.3)); -#11911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#11913 = PCURVE('',#11914,#11919); -#11914 = CYLINDRICAL_SURFACE('',#11915,7.825944375606E-002); -#11915 = AXIS2_PLACEMENT_3D('',#11916,#11917,#11918); -#11916 = CARTESIAN_POINT('',(-0.35,0.E+000,0.3)); -#11917 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11918 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#11919 = DEFINITIONAL_REPRESENTATION('',(#11920),#11923); -#11920 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#11921,#11922),.UNSPECIFIED., +#14287 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#14288),#18754); +#14288 = MANIFOLD_SOLID_BREP('',#14289); +#14289 = CLOSED_SHELL('',(#14290,#14405,#14521,#14679,#14794,#14891, + #14983,#15080,#15172,#15269,#15300,#15408,#15460,#15547,#15599, + #15709,#15761,#15848,#15879,#15995,#16134,#16204,#16299,#16369, + #16464,#16534,#16629,#16655,#16813,#16905,#17002,#17094,#17191, + #17283,#17380,#17411,#17446,#17554,#17606,#17693,#17745,#17855, + #17907,#18017,#18048,#18079,#18218,#18288,#18383,#18453,#18548, + #18618,#18713,#18739)); +#14290 = ADVANCED_FACE('',(#14291),#14306,.T.); +#14291 = FACE_BOUND('',#14292,.T.); +#14292 = EDGE_LOOP('',(#14293,#14328,#14354,#14386)); +#14293 = ORIENTED_EDGE('',*,*,#14294,.T.); +#14294 = EDGE_CURVE('',#14295,#14297,#14299,.T.); +#14295 = VERTEX_POINT('',#14296); +#14296 = CARTESIAN_POINT('',(-0.25,0.E+000,0.221740556244)); +#14297 = VERTEX_POINT('',#14298); +#14298 = CARTESIAN_POINT('',(-0.25,9.584017729891E-018,0.378259443756)); +#14299 = SURFACE_CURVE('',#14300,(#14305,#14316),.PCURVE_S1.); +#14300 = CIRCLE('',#14301,7.825944375606E-002); +#14301 = AXIS2_PLACEMENT_3D('',#14302,#14303,#14304); +#14302 = CARTESIAN_POINT('',(-0.25,0.E+000,0.3)); +#14303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#14305 = PCURVE('',#14306,#14311); +#14306 = CYLINDRICAL_SURFACE('',#14307,7.825944375606E-002); +#14307 = AXIS2_PLACEMENT_3D('',#14308,#14309,#14310); +#14308 = CARTESIAN_POINT('',(-0.35,0.E+000,0.3)); +#14309 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14310 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#14311 = DEFINITIONAL_REPRESENTATION('',(#14312),#14315); +#14312 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14313,#14314),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#11921 = CARTESIAN_POINT('',(0.E+000,0.1)); -#11922 = CARTESIAN_POINT('',(3.14159265359,0.1)); -#11923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11924 = PCURVE('',#11925,#11930); -#11925 = PLANE('',#11926); -#11926 = AXIS2_PLACEMENT_3D('',#11927,#11928,#11929); -#11927 = CARTESIAN_POINT('',(-0.25,-0.25,0.3)); -#11928 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11929 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#11930 = DEFINITIONAL_REPRESENTATION('',(#11931),#11935); -#11931 = CIRCLE('',#11932,7.825944375606E-002); -#11932 = AXIS2_PLACEMENT_2D('',#11933,#11934); -#11933 = CARTESIAN_POINT('',(0.E+000,0.25)); -#11934 = DIRECTION('',(1.,0.E+000)); -#11935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11936 = ORIENTED_EDGE('',*,*,#11937,.T.); -#11937 = EDGE_CURVE('',#11905,#11938,#11940,.T.); -#11938 = VERTEX_POINT('',#11939); -#11939 = CARTESIAN_POINT('',(0.25,9.584017729891E-018,0.378259443756)); -#11940 = SURFACE_CURVE('',#11941,(#11945,#11951),.PCURVE_S1.); -#11941 = LINE('',#11942,#11943); -#11942 = CARTESIAN_POINT('',(-0.35,9.584017729891E-018,0.378259443756)); -#11943 = VECTOR('',#11944,1.); -#11944 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11945 = PCURVE('',#11914,#11946); -#11946 = DEFINITIONAL_REPRESENTATION('',(#11947),#11950); -#11947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#11948,#11949),.UNSPECIFIED., +#14313 = CARTESIAN_POINT('',(0.E+000,0.1)); +#14314 = CARTESIAN_POINT('',(3.14159265359,0.1)); +#14315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14316 = PCURVE('',#14317,#14322); +#14317 = PLANE('',#14318); +#14318 = AXIS2_PLACEMENT_3D('',#14319,#14320,#14321); +#14319 = CARTESIAN_POINT('',(-0.25,-0.25,0.3)); +#14320 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14321 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#14322 = DEFINITIONAL_REPRESENTATION('',(#14323),#14327); +#14323 = CIRCLE('',#14324,7.825944375606E-002); +#14324 = AXIS2_PLACEMENT_2D('',#14325,#14326); +#14325 = CARTESIAN_POINT('',(0.E+000,0.25)); +#14326 = DIRECTION('',(1.,0.E+000)); +#14327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14328 = ORIENTED_EDGE('',*,*,#14329,.T.); +#14329 = EDGE_CURVE('',#14297,#14330,#14332,.T.); +#14330 = VERTEX_POINT('',#14331); +#14331 = CARTESIAN_POINT('',(0.25,9.584017729891E-018,0.378259443756)); +#14332 = SURFACE_CURVE('',#14333,(#14337,#14343),.PCURVE_S1.); +#14333 = LINE('',#14334,#14335); +#14334 = CARTESIAN_POINT('',(-0.35,9.584017729891E-018,0.378259443756)); +#14335 = VECTOR('',#14336,1.); +#14336 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14337 = PCURVE('',#14306,#14338); +#14338 = DEFINITIONAL_REPRESENTATION('',(#14339),#14342); +#14339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14340,#14341),.UNSPECIFIED., .F.,.F.,(2,2),(0.1,0.6),.PIECEWISE_BEZIER_KNOTS.); -#11948 = CARTESIAN_POINT('',(3.14159265359,0.1)); -#11949 = CARTESIAN_POINT('',(3.14159265359,0.6)); -#11950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11951 = PCURVE('',#11952,#11957); -#11952 = CYLINDRICAL_SURFACE('',#11953,7.825944375606E-002); -#11953 = AXIS2_PLACEMENT_3D('',#11954,#11955,#11956); -#11954 = CARTESIAN_POINT('',(-0.35,0.E+000,0.3)); -#11955 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11956 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#11957 = DEFINITIONAL_REPRESENTATION('',(#11958),#11961); -#11958 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#11959,#11960),.UNSPECIFIED., +#14340 = CARTESIAN_POINT('',(3.14159265359,0.1)); +#14341 = CARTESIAN_POINT('',(3.14159265359,0.6)); +#14342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14343 = PCURVE('',#14344,#14349); +#14344 = CYLINDRICAL_SURFACE('',#14345,7.825944375606E-002); +#14345 = AXIS2_PLACEMENT_3D('',#14346,#14347,#14348); +#14346 = CARTESIAN_POINT('',(-0.35,0.E+000,0.3)); +#14347 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14348 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#14349 = DEFINITIONAL_REPRESENTATION('',(#14350),#14353); +#14350 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14351,#14352),.UNSPECIFIED., .F.,.F.,(2,2),(0.1,0.6),.PIECEWISE_BEZIER_KNOTS.); -#11959 = CARTESIAN_POINT('',(3.14159265359,0.1)); -#11960 = CARTESIAN_POINT('',(3.14159265359,0.6)); -#11961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11962 = ORIENTED_EDGE('',*,*,#11963,.F.); -#11963 = EDGE_CURVE('',#11964,#11938,#11966,.T.); -#11964 = VERTEX_POINT('',#11965); -#11965 = CARTESIAN_POINT('',(0.25,0.E+000,0.221740556244)); -#11966 = SURFACE_CURVE('',#11967,(#11972,#11978),.PCURVE_S1.); -#11967 = CIRCLE('',#11968,7.825944375606E-002); -#11968 = AXIS2_PLACEMENT_3D('',#11969,#11970,#11971); -#11969 = CARTESIAN_POINT('',(0.25,0.E+000,0.3)); -#11970 = DIRECTION('',(1.,0.E+000,0.E+000)); -#11971 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#11972 = PCURVE('',#11914,#11973); -#11973 = DEFINITIONAL_REPRESENTATION('',(#11974),#11977); -#11974 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#11975,#11976),.UNSPECIFIED., +#14351 = CARTESIAN_POINT('',(3.14159265359,0.1)); +#14352 = CARTESIAN_POINT('',(3.14159265359,0.6)); +#14353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14354 = ORIENTED_EDGE('',*,*,#14355,.F.); +#14355 = EDGE_CURVE('',#14356,#14330,#14358,.T.); +#14356 = VERTEX_POINT('',#14357); +#14357 = CARTESIAN_POINT('',(0.25,0.E+000,0.221740556244)); +#14358 = SURFACE_CURVE('',#14359,(#14364,#14370),.PCURVE_S1.); +#14359 = CIRCLE('',#14360,7.825944375606E-002); +#14360 = AXIS2_PLACEMENT_3D('',#14361,#14362,#14363); +#14361 = CARTESIAN_POINT('',(0.25,0.E+000,0.3)); +#14362 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14363 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#14364 = PCURVE('',#14306,#14365); +#14365 = DEFINITIONAL_REPRESENTATION('',(#14366),#14369); +#14366 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14367,#14368),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#11975 = CARTESIAN_POINT('',(0.E+000,0.6)); -#11976 = CARTESIAN_POINT('',(3.14159265359,0.6)); -#11977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11978 = PCURVE('',#11979,#11984); -#11979 = PLANE('',#11980); -#11980 = AXIS2_PLACEMENT_3D('',#11981,#11982,#11983); -#11981 = CARTESIAN_POINT('',(0.25,-0.25,0.3)); -#11982 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#11983 = DIRECTION('',(0.E+000,0.E+000,1.)); -#11984 = DEFINITIONAL_REPRESENTATION('',(#11985),#11993); -#11985 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#11986,#11987,#11988,#11989 - ,#11990,#11991,#11992),.UNSPECIFIED.,.T.,.F.) +#14367 = CARTESIAN_POINT('',(0.E+000,0.6)); +#14368 = CARTESIAN_POINT('',(3.14159265359,0.6)); +#14369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14370 = PCURVE('',#14371,#14376); +#14371 = PLANE('',#14372); +#14372 = AXIS2_PLACEMENT_3D('',#14373,#14374,#14375); +#14373 = CARTESIAN_POINT('',(0.25,-0.25,0.3)); +#14374 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#14375 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14376 = DEFINITIONAL_REPRESENTATION('',(#14377),#14385); +#14377 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#14378,#14379,#14380,#14381 + ,#14382,#14383,#14384),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#11986 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); -#11987 = CARTESIAN_POINT('',(-7.825944375606E-002,0.385549332758)); -#11988 = CARTESIAN_POINT('',(3.912972187803E-002,0.317774666379)); -#11989 = CARTESIAN_POINT('',(0.156518887512,0.25)); -#11990 = CARTESIAN_POINT('',(3.912972187803E-002,0.182225333621)); -#11991 = CARTESIAN_POINT('',(-7.825944375606E-002,0.114450667242)); -#11992 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); -#11993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#11994 = ORIENTED_EDGE('',*,*,#11995,.F.); -#11995 = EDGE_CURVE('',#11903,#11964,#11996,.T.); -#11996 = SURFACE_CURVE('',#11997,(#12001,#12007),.PCURVE_S1.); -#11997 = LINE('',#11998,#11999); -#11998 = CARTESIAN_POINT('',(-0.35,0.E+000,0.221740556244)); -#11999 = VECTOR('',#12000,1.); -#12000 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12001 = PCURVE('',#11914,#12002); -#12002 = DEFINITIONAL_REPRESENTATION('',(#12003),#12006); -#12003 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12004,#12005),.UNSPECIFIED., +#14378 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); +#14379 = CARTESIAN_POINT('',(-7.825944375606E-002,0.385549332758)); +#14380 = CARTESIAN_POINT('',(3.912972187803E-002,0.317774666379)); +#14381 = CARTESIAN_POINT('',(0.156518887512,0.25)); +#14382 = CARTESIAN_POINT('',(3.912972187803E-002,0.182225333621)); +#14383 = CARTESIAN_POINT('',(-7.825944375606E-002,0.114450667242)); +#14384 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); +#14385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14386 = ORIENTED_EDGE('',*,*,#14387,.F.); +#14387 = EDGE_CURVE('',#14295,#14356,#14388,.T.); +#14388 = SURFACE_CURVE('',#14389,(#14393,#14399),.PCURVE_S1.); +#14389 = LINE('',#14390,#14391); +#14390 = CARTESIAN_POINT('',(-0.35,0.E+000,0.221740556244)); +#14391 = VECTOR('',#14392,1.); +#14392 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14393 = PCURVE('',#14306,#14394); +#14394 = DEFINITIONAL_REPRESENTATION('',(#14395),#14398); +#14395 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14396,#14397),.UNSPECIFIED., .F.,.F.,(2,2),(0.1,0.6),.PIECEWISE_BEZIER_KNOTS.); -#12004 = CARTESIAN_POINT('',(0.E+000,0.1)); -#12005 = CARTESIAN_POINT('',(0.E+000,0.6)); -#12006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#14396 = CARTESIAN_POINT('',(0.E+000,0.1)); +#14397 = CARTESIAN_POINT('',(0.E+000,0.6)); +#14398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12007 = PCURVE('',#11952,#12008); -#12008 = DEFINITIONAL_REPRESENTATION('',(#12009),#12012); -#12009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12010,#12011),.UNSPECIFIED., +#14399 = PCURVE('',#14344,#14400); +#14400 = DEFINITIONAL_REPRESENTATION('',(#14401),#14404); +#14401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14402,#14403),.UNSPECIFIED., .F.,.F.,(2,2),(0.1,0.6),.PIECEWISE_BEZIER_KNOTS.); -#12010 = CARTESIAN_POINT('',(6.28318530718,0.1)); -#12011 = CARTESIAN_POINT('',(6.28318530718,0.6)); -#12012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12013 = ADVANCED_FACE('',(#12014),#12028,.T.); -#12014 = FACE_BOUND('',#12015,.T.); -#12015 = EDGE_LOOP('',(#12016,#12050,#12077,#12104)); -#12016 = ORIENTED_EDGE('',*,*,#12017,.F.); -#12017 = EDGE_CURVE('',#12018,#12020,#12022,.T.); -#12018 = VERTEX_POINT('',#12019); -#12019 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); -#12020 = VERTEX_POINT('',#12021); -#12021 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); -#12022 = SURFACE_CURVE('',#12023,(#12027,#12039),.PCURVE_S1.); -#12023 = LINE('',#12024,#12025); -#12024 = CARTESIAN_POINT('',(-0.5,-0.25,5.E-002)); -#12025 = VECTOR('',#12026,1.); -#12026 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12027 = PCURVE('',#12028,#12033); -#12028 = PLANE('',#12029); -#12029 = AXIS2_PLACEMENT_3D('',#12030,#12031,#12032); -#12030 = CARTESIAN_POINT('',(-0.5,-0.25,0.3)); -#12031 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#12032 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12033 = DEFINITIONAL_REPRESENTATION('',(#12034),#12038); -#12034 = LINE('',#12035,#12036); -#12035 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#12036 = VECTOR('',#12037,1.); -#12037 = DIRECTION('',(0.E+000,1.)); -#12038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12039 = PCURVE('',#12040,#12045); -#12040 = CYLINDRICAL_SURFACE('',#12041,5.E-002); -#12041 = AXIS2_PLACEMENT_3D('',#12042,#12043,#12044); -#12042 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); -#12043 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12044 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12045 = DEFINITIONAL_REPRESENTATION('',(#12046),#12049); -#12046 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12047,#12048),.UNSPECIFIED., +#14402 = CARTESIAN_POINT('',(6.28318530718,0.1)); +#14403 = CARTESIAN_POINT('',(6.28318530718,0.6)); +#14404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14405 = ADVANCED_FACE('',(#14406),#14420,.T.); +#14406 = FACE_BOUND('',#14407,.T.); +#14407 = EDGE_LOOP('',(#14408,#14442,#14469,#14496)); +#14408 = ORIENTED_EDGE('',*,*,#14409,.F.); +#14409 = EDGE_CURVE('',#14410,#14412,#14414,.T.); +#14410 = VERTEX_POINT('',#14411); +#14411 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); +#14412 = VERTEX_POINT('',#14413); +#14413 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); +#14414 = SURFACE_CURVE('',#14415,(#14419,#14431),.PCURVE_S1.); +#14415 = LINE('',#14416,#14417); +#14416 = CARTESIAN_POINT('',(-0.5,-0.25,5.E-002)); +#14417 = VECTOR('',#14418,1.); +#14418 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14419 = PCURVE('',#14420,#14425); +#14420 = PLANE('',#14421); +#14421 = AXIS2_PLACEMENT_3D('',#14422,#14423,#14424); +#14422 = CARTESIAN_POINT('',(-0.5,-0.25,0.3)); +#14423 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#14424 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14425 = DEFINITIONAL_REPRESENTATION('',(#14426),#14430); +#14426 = LINE('',#14427,#14428); +#14427 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#14428 = VECTOR('',#14429,1.); +#14429 = DIRECTION('',(0.E+000,1.)); +#14430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14431 = PCURVE('',#14432,#14437); +#14432 = CYLINDRICAL_SURFACE('',#14433,5.E-002); +#14433 = AXIS2_PLACEMENT_3D('',#14434,#14435,#14436); +#14434 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); +#14435 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14436 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14437 = DEFINITIONAL_REPRESENTATION('',(#14438),#14441); +#14438 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14439,#14440),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#12047 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#12048 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#12049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12050 = ORIENTED_EDGE('',*,*,#12051,.F.); -#12051 = EDGE_CURVE('',#12052,#12018,#12054,.T.); -#12052 = VERTEX_POINT('',#12053); -#12053 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); -#12054 = SURFACE_CURVE('',#12055,(#12059,#12066),.PCURVE_S1.); -#12055 = LINE('',#12056,#12057); -#12056 = CARTESIAN_POINT('',(-0.5,-0.2,0.3)); -#12057 = VECTOR('',#12058,1.); -#12058 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#12059 = PCURVE('',#12028,#12060); -#12060 = DEFINITIONAL_REPRESENTATION('',(#12061),#12065); -#12061 = LINE('',#12062,#12063); -#12062 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#12063 = VECTOR('',#12064,1.); -#12064 = DIRECTION('',(-1.,2.595054858731E-031)); -#12065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12066 = PCURVE('',#12067,#12072); -#12067 = CYLINDRICAL_SURFACE('',#12068,5.E-002); -#12068 = AXIS2_PLACEMENT_3D('',#12069,#12070,#12071); -#12069 = CARTESIAN_POINT('',(-0.45,-0.2,0.3)); -#12070 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#12071 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); -#12072 = DEFINITIONAL_REPRESENTATION('',(#12073),#12076); -#12073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12074,#12075),.UNSPECIFIED., - .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#12074 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#12075 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#12076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#14439 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#14440 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#14441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12077 = ORIENTED_EDGE('',*,*,#12078,.F.); -#12078 = EDGE_CURVE('',#12079,#12052,#12081,.T.); -#12079 = VERTEX_POINT('',#12080); -#12080 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); -#12081 = SURFACE_CURVE('',#12082,(#12086,#12093),.PCURVE_S1.); -#12082 = LINE('',#12083,#12084); -#12083 = CARTESIAN_POINT('',(-0.5,-0.25,0.55)); -#12084 = VECTOR('',#12085,1.); -#12085 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#12086 = PCURVE('',#12028,#12087); -#12087 = DEFINITIONAL_REPRESENTATION('',(#12088),#12092); -#12088 = LINE('',#12089,#12090); -#12089 = CARTESIAN_POINT('',(0.25,0.E+000)); -#12090 = VECTOR('',#12091,1.); -#12091 = DIRECTION('',(0.E+000,-1.)); -#12092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12093 = PCURVE('',#12094,#12099); -#12094 = CYLINDRICAL_SURFACE('',#12095,5.E-002); -#12095 = AXIS2_PLACEMENT_3D('',#12096,#12097,#12098); -#12096 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); -#12097 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12098 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12099 = DEFINITIONAL_REPRESENTATION('',(#12100),#12103); -#12100 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12101,#12102),.UNSPECIFIED., +#14442 = ORIENTED_EDGE('',*,*,#14443,.F.); +#14443 = EDGE_CURVE('',#14444,#14410,#14446,.T.); +#14444 = VERTEX_POINT('',#14445); +#14445 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); +#14446 = SURFACE_CURVE('',#14447,(#14451,#14458),.PCURVE_S1.); +#14447 = LINE('',#14448,#14449); +#14448 = CARTESIAN_POINT('',(-0.5,-0.2,0.3)); +#14449 = VECTOR('',#14450,1.); +#14450 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#14451 = PCURVE('',#14420,#14452); +#14452 = DEFINITIONAL_REPRESENTATION('',(#14453),#14457); +#14453 = LINE('',#14454,#14455); +#14454 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#14455 = VECTOR('',#14456,1.); +#14456 = DIRECTION('',(-1.,2.595054858731E-031)); +#14457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14458 = PCURVE('',#14459,#14464); +#14459 = CYLINDRICAL_SURFACE('',#14460,5.E-002); +#14460 = AXIS2_PLACEMENT_3D('',#14461,#14462,#14463); +#14461 = CARTESIAN_POINT('',(-0.45,-0.2,0.3)); +#14462 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#14463 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); +#14464 = DEFINITIONAL_REPRESENTATION('',(#14465),#14468); +#14465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14466,#14467),.UNSPECIFIED., + .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); +#14466 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#14467 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#14468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14469 = ORIENTED_EDGE('',*,*,#14470,.F.); +#14470 = EDGE_CURVE('',#14471,#14444,#14473,.T.); +#14471 = VERTEX_POINT('',#14472); +#14472 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); +#14473 = SURFACE_CURVE('',#14474,(#14478,#14485),.PCURVE_S1.); +#14474 = LINE('',#14475,#14476); +#14475 = CARTESIAN_POINT('',(-0.5,-0.25,0.55)); +#14476 = VECTOR('',#14477,1.); +#14477 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#14478 = PCURVE('',#14420,#14479); +#14479 = DEFINITIONAL_REPRESENTATION('',(#14480),#14484); +#14480 = LINE('',#14481,#14482); +#14481 = CARTESIAN_POINT('',(0.25,0.E+000)); +#14482 = VECTOR('',#14483,1.); +#14483 = DIRECTION('',(0.E+000,-1.)); +#14484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14485 = PCURVE('',#14486,#14491); +#14486 = CYLINDRICAL_SURFACE('',#14487,5.E-002); +#14487 = AXIS2_PLACEMENT_3D('',#14488,#14489,#14490); +#14488 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); +#14489 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14490 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14491 = DEFINITIONAL_REPRESENTATION('',(#14492),#14495); +#14492 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14493,#14494),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#12101 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#12102 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#12103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12104 = ORIENTED_EDGE('',*,*,#12105,.F.); -#12105 = EDGE_CURVE('',#12020,#12079,#12106,.T.); -#12106 = SURFACE_CURVE('',#12107,(#12111,#12118),.PCURVE_S1.); -#12107 = LINE('',#12108,#12109); -#12108 = CARTESIAN_POINT('',(-0.5,0.2,0.3)); -#12109 = VECTOR('',#12110,1.); -#12110 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#12111 = PCURVE('',#12028,#12112); -#12112 = DEFINITIONAL_REPRESENTATION('',(#12113),#12117); -#12113 = LINE('',#12114,#12115); -#12114 = CARTESIAN_POINT('',(0.E+000,0.45)); -#12115 = VECTOR('',#12116,1.); -#12116 = DIRECTION('',(1.,-2.595054858731E-031)); -#12117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12118 = PCURVE('',#12119,#12124); -#12119 = CYLINDRICAL_SURFACE('',#12120,5.E-002); -#12120 = AXIS2_PLACEMENT_3D('',#12121,#12122,#12123); -#12121 = CARTESIAN_POINT('',(-0.45,0.2,0.3)); -#12122 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#12123 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); -#12124 = DEFINITIONAL_REPRESENTATION('',(#12125),#12128); -#12125 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12126,#12127),.UNSPECIFIED., +#14493 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#14494 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#14495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14496 = ORIENTED_EDGE('',*,*,#14497,.F.); +#14497 = EDGE_CURVE('',#14412,#14471,#14498,.T.); +#14498 = SURFACE_CURVE('',#14499,(#14503,#14510),.PCURVE_S1.); +#14499 = LINE('',#14500,#14501); +#14500 = CARTESIAN_POINT('',(-0.5,0.2,0.3)); +#14501 = VECTOR('',#14502,1.); +#14502 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#14503 = PCURVE('',#14420,#14504); +#14504 = DEFINITIONAL_REPRESENTATION('',(#14505),#14509); +#14505 = LINE('',#14506,#14507); +#14506 = CARTESIAN_POINT('',(0.E+000,0.45)); +#14507 = VECTOR('',#14508,1.); +#14508 = DIRECTION('',(1.,-2.595054858731E-031)); +#14509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14510 = PCURVE('',#14511,#14516); +#14511 = CYLINDRICAL_SURFACE('',#14512,5.E-002); +#14512 = AXIS2_PLACEMENT_3D('',#14513,#14514,#14515); +#14513 = CARTESIAN_POINT('',(-0.45,0.2,0.3)); +#14514 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#14515 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); +#14516 = DEFINITIONAL_REPRESENTATION('',(#14517),#14520); +#14517 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14518,#14519),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#12126 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#12127 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#12128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12129 = ADVANCED_FACE('',(#12130),#12145,.T.); -#12130 = FACE_BOUND('',#12131,.T.); -#12131 = EDGE_LOOP('',(#12132,#12201,#12244)); -#12132 = ORIENTED_EDGE('',*,*,#12133,.F.); -#12133 = EDGE_CURVE('',#12134,#12136,#12138,.T.); -#12134 = VERTEX_POINT('',#12135); -#12135 = CARTESIAN_POINT('',(-0.45,-0.2,0.6)); -#12136 = VERTEX_POINT('',#12137); -#12137 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); -#12138 = SURFACE_CURVE('',#12139,(#12144,#12190),.PCURVE_S1.); -#12139 = CIRCLE('',#12140,5.E-002); -#12140 = AXIS2_PLACEMENT_3D('',#12141,#12142,#12143); -#12141 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); -#12142 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); -#12143 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); -#12144 = PCURVE('',#12145,#12162); -#12145 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#12146,#12147,#12148,#12149) - ,(#12150,#12151,#12152,#12153) - ,(#12154,#12155,#12156,#12157) - ,(#12158,#12159,#12160,#12161 +#14518 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#14519 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#14520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14521 = ADVANCED_FACE('',(#14522),#14537,.T.); +#14522 = FACE_BOUND('',#14523,.T.); +#14523 = EDGE_LOOP('',(#14524,#14593,#14636)); +#14524 = ORIENTED_EDGE('',*,*,#14525,.F.); +#14525 = EDGE_CURVE('',#14526,#14528,#14530,.T.); +#14526 = VERTEX_POINT('',#14527); +#14527 = CARTESIAN_POINT('',(-0.45,-0.2,0.6)); +#14528 = VERTEX_POINT('',#14529); +#14529 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); +#14530 = SURFACE_CURVE('',#14531,(#14536,#14582),.PCURVE_S1.); +#14531 = CIRCLE('',#14532,5.E-002); +#14532 = AXIS2_PLACEMENT_3D('',#14533,#14534,#14535); +#14533 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); +#14534 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); +#14535 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); +#14536 = PCURVE('',#14537,#14554); +#14537 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#14538,#14539,#14540,#14541) + ,(#14542,#14543,#14544,#14545) + ,(#14546,#14547,#14548,#14549) + ,(#14550,#14551,#14552,#14553 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -14479,27 +17468,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#12146 = CARTESIAN_POINT('',(-0.45,-0.2,0.6)); -#12147 = CARTESIAN_POINT('',(-0.45,-0.229289321881,0.6)); -#12148 = CARTESIAN_POINT('',(-0.45,-0.25,0.579289321881)); -#12149 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); -#12150 = CARTESIAN_POINT('',(-0.479289321881,-0.2,0.6)); -#12151 = CARTESIAN_POINT('',(-0.479289321881,-0.229289321881,0.6)); -#12152 = CARTESIAN_POINT('',(-0.479289321881,-0.25,0.579289321881)); -#12153 = CARTESIAN_POINT('',(-0.479289321881,-0.25,0.55)); -#12154 = CARTESIAN_POINT('',(-0.5,-0.2,0.579289321881)); -#12155 = CARTESIAN_POINT('',(-0.5,-0.217157287525,0.579289321881)); -#12156 = CARTESIAN_POINT('',(-0.5,-0.229289321881,0.567157287525)); -#12157 = CARTESIAN_POINT('',(-0.5,-0.229289321881,0.55)); -#12158 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); -#12159 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); -#12160 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); -#12161 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); -#12162 = DEFINITIONAL_REPRESENTATION('',(#12163),#12189); -#12163 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12164,#12165,#12166,#12167, - #12168,#12169,#12170,#12171,#12172,#12173,#12174,#12175,#12176, - #12177,#12178,#12179,#12180,#12181,#12182,#12183,#12184,#12185, - #12186,#12187,#12188),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14538 = CARTESIAN_POINT('',(-0.45,-0.2,0.6)); +#14539 = CARTESIAN_POINT('',(-0.45,-0.229289321881,0.6)); +#14540 = CARTESIAN_POINT('',(-0.45,-0.25,0.579289321881)); +#14541 = CARTESIAN_POINT('',(-0.45,-0.25,0.55)); +#14542 = CARTESIAN_POINT('',(-0.479289321881,-0.2,0.6)); +#14543 = CARTESIAN_POINT('',(-0.479289321881,-0.229289321881,0.6)); +#14544 = CARTESIAN_POINT('',(-0.479289321881,-0.25,0.579289321881)); +#14545 = CARTESIAN_POINT('',(-0.479289321881,-0.25,0.55)); +#14546 = CARTESIAN_POINT('',(-0.5,-0.2,0.579289321881)); +#14547 = CARTESIAN_POINT('',(-0.5,-0.217157287525,0.579289321881)); +#14548 = CARTESIAN_POINT('',(-0.5,-0.229289321881,0.567157287525)); +#14549 = CARTESIAN_POINT('',(-0.5,-0.229289321881,0.55)); +#14550 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); +#14551 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); +#14552 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); +#14553 = CARTESIAN_POINT('',(-0.5,-0.2,0.55)); +#14554 = DEFINITIONAL_REPRESENTATION('',(#14555),#14581); +#14555 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14556,#14557,#14558,#14559, + #14560,#14561,#14562,#14563,#14564,#14565,#14566,#14567,#14568, + #14569,#14570,#14571,#14572,#14573,#14574,#14575,#14576,#14577, + #14578,#14579,#14580),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -14507,63 +17496,63 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#12164 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12165 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); -#12166 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#12167 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#12168 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#12169 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#12170 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#12171 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#12172 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#12173 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#12174 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#12175 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#12176 = CARTESIAN_POINT('',(0.E+000,0.5)); -#12177 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#12178 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#12179 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#12180 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#12181 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#12182 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#12183 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#12184 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#12185 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#12186 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#12187 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#12188 = CARTESIAN_POINT('',(0.E+000,1.)); -#12189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12190 = PCURVE('',#12191,#12196); -#12191 = CYLINDRICAL_SURFACE('',#12192,5.E-002); -#12192 = AXIS2_PLACEMENT_3D('',#12193,#12194,#12195); -#12193 = CARTESIAN_POINT('',(-0.375,-0.2,0.55)); -#12194 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); -#12195 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); -#12196 = DEFINITIONAL_REPRESENTATION('',(#12197),#12200); -#12197 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12198,#12199),.UNSPECIFIED., +#14556 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14557 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); +#14558 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#14559 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#14560 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#14561 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#14562 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#14563 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#14564 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#14565 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#14566 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#14567 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#14568 = CARTESIAN_POINT('',(0.E+000,0.5)); +#14569 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#14570 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#14571 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#14572 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#14573 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#14574 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#14575 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#14576 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#14577 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#14578 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#14579 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#14580 = CARTESIAN_POINT('',(0.E+000,1.)); +#14581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14582 = PCURVE('',#14583,#14588); +#14583 = CYLINDRICAL_SURFACE('',#14584,5.E-002); +#14584 = AXIS2_PLACEMENT_3D('',#14585,#14586,#14587); +#14585 = CARTESIAN_POINT('',(-0.375,-0.2,0.55)); +#14586 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); +#14587 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); +#14588 = DEFINITIONAL_REPRESENTATION('',(#14589),#14592); +#14589 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14590,#14591),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#12198 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#12199 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); -#12200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12201 = ORIENTED_EDGE('',*,*,#12202,.F.); -#12202 = EDGE_CURVE('',#12052,#12134,#12203,.T.); -#12203 = SURFACE_CURVE('',#12204,(#12209,#12238),.PCURVE_S1.); -#12204 = CIRCLE('',#12205,5.E-002); -#12205 = AXIS2_PLACEMENT_3D('',#12206,#12207,#12208); -#12206 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); -#12207 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12208 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12209 = PCURVE('',#12145,#12210); -#12210 = DEFINITIONAL_REPRESENTATION('',(#12211),#12237); -#12211 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12212,#12213,#12214,#12215, - #12216,#12217,#12218,#12219,#12220,#12221,#12222,#12223,#12224, - #12225,#12226,#12227,#12228,#12229,#12230,#12231,#12232,#12233, - #12234,#12235,#12236),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14590 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#14591 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); +#14592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14593 = ORIENTED_EDGE('',*,*,#14594,.F.); +#14594 = EDGE_CURVE('',#14444,#14526,#14595,.T.); +#14595 = SURFACE_CURVE('',#14596,(#14601,#14630),.PCURVE_S1.); +#14596 = CIRCLE('',#14597,5.E-002); +#14597 = AXIS2_PLACEMENT_3D('',#14598,#14599,#14600); +#14598 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); +#14599 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14600 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14601 = PCURVE('',#14537,#14602); +#14602 = DEFINITIONAL_REPRESENTATION('',(#14603),#14629); +#14603 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14604,#14605,#14606,#14607, + #14608,#14609,#14610,#14611,#14612,#14613,#14614,#14615,#14616, + #14617,#14618,#14619,#14620,#14621,#14622,#14623,#14624,#14625, + #14626,#14627,#14628),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -14571,58 +17560,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#12212 = CARTESIAN_POINT('',(1.,0.E+000)); -#12213 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#12214 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#12215 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#12216 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#12217 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#12218 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#12219 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#12220 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#12221 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#12222 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#12223 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#12224 = CARTESIAN_POINT('',(0.5,0.E+000)); -#12225 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#12226 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#12227 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#12228 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#12229 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#12230 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#12231 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#12232 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#12233 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#12234 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#12235 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#12236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12238 = PCURVE('',#12094,#12239); -#12239 = DEFINITIONAL_REPRESENTATION('',(#12240),#12243); -#12240 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12241,#12242),.UNSPECIFIED., +#14604 = CARTESIAN_POINT('',(1.,0.E+000)); +#14605 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#14606 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#14607 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#14608 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#14609 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#14610 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#14611 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#14612 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#14613 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#14614 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#14615 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#14616 = CARTESIAN_POINT('',(0.5,0.E+000)); +#14617 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#14618 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#14619 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#14620 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#14621 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#14622 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#14623 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#14624 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#14625 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#14626 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#14627 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#14628 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14630 = PCURVE('',#14486,#14631); +#14631 = DEFINITIONAL_REPRESENTATION('',(#14632),#14635); +#14632 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14633,#14634),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#12241 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#12242 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#12243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12244 = ORIENTED_EDGE('',*,*,#12245,.F.); -#12245 = EDGE_CURVE('',#12136,#12052,#12246,.T.); -#12246 = SURFACE_CURVE('',#12247,(#12252,#12281),.PCURVE_S1.); -#12247 = CIRCLE('',#12248,5.E-002); -#12248 = AXIS2_PLACEMENT_3D('',#12249,#12250,#12251); -#12249 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); -#12250 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#12251 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); -#12252 = PCURVE('',#12145,#12253); -#12253 = DEFINITIONAL_REPRESENTATION('',(#12254),#12280); -#12254 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12255,#12256,#12257,#12258, - #12259,#12260,#12261,#12262,#12263,#12264,#12265,#12266,#12267, - #12268,#12269,#12270,#12271,#12272,#12273,#12274,#12275,#12276, - #12277,#12278,#12279),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14633 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#14634 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#14635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14636 = ORIENTED_EDGE('',*,*,#14637,.F.); +#14637 = EDGE_CURVE('',#14528,#14444,#14638,.T.); +#14638 = SURFACE_CURVE('',#14639,(#14644,#14673),.PCURVE_S1.); +#14639 = CIRCLE('',#14640,5.E-002); +#14640 = AXIS2_PLACEMENT_3D('',#14641,#14642,#14643); +#14641 = CARTESIAN_POINT('',(-0.45,-0.2,0.55)); +#14642 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#14643 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); +#14644 = PCURVE('',#14537,#14645); +#14645 = DEFINITIONAL_REPRESENTATION('',(#14646),#14672); +#14646 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14647,#14648,#14649,#14650, + #14651,#14652,#14653,#14654,#14655,#14656,#14657,#14658,#14659, + #14660,#14661,#14662,#14663,#14664,#14665,#14666,#14667,#14668, + #14669,#14670,#14671),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -14630,65 +17619,65 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#12255 = CARTESIAN_POINT('',(0.E+000,1.)); -#12256 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#12257 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#12258 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#12259 = CARTESIAN_POINT('',(0.145724913075,1.)); -#12260 = CARTESIAN_POINT('',(0.192043637223,1.)); -#12261 = CARTESIAN_POINT('',(0.237526724423,1.)); -#12262 = CARTESIAN_POINT('',(0.282309422539,1.)); -#12263 = CARTESIAN_POINT('',(0.326519436214,1.)); -#12264 = CARTESIAN_POINT('',(0.370278310591,1.)); -#12265 = CARTESIAN_POINT('',(0.413702852292,1.)); -#12266 = CARTESIAN_POINT('',(0.456906394885,1.)); -#12267 = CARTESIAN_POINT('',(0.5,1.)); -#12268 = CARTESIAN_POINT('',(0.543093605115,1.)); -#12269 = CARTESIAN_POINT('',(0.586297147708,1.)); -#12270 = CARTESIAN_POINT('',(0.629721689409,1.)); -#12271 = CARTESIAN_POINT('',(0.673480563786,1.)); -#12272 = CARTESIAN_POINT('',(0.717690577461,1.)); -#12273 = CARTESIAN_POINT('',(0.762473275577,1.)); -#12274 = CARTESIAN_POINT('',(0.807956362777,1.)); -#12275 = CARTESIAN_POINT('',(0.854275086925,1.)); -#12276 = CARTESIAN_POINT('',(0.901574474096,1.)); -#12277 = CARTESIAN_POINT('',(0.950009297011,1.)); -#12278 = CARTESIAN_POINT('',(0.983172198663,1.)); -#12279 = CARTESIAN_POINT('',(1.,1.)); -#12280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12281 = PCURVE('',#12067,#12282); -#12282 = DEFINITIONAL_REPRESENTATION('',(#12283),#12286); -#12283 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12284,#12285),.UNSPECIFIED., +#14647 = CARTESIAN_POINT('',(0.E+000,1.)); +#14648 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#14649 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#14650 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#14651 = CARTESIAN_POINT('',(0.145724913075,1.)); +#14652 = CARTESIAN_POINT('',(0.192043637223,1.)); +#14653 = CARTESIAN_POINT('',(0.237526724423,1.)); +#14654 = CARTESIAN_POINT('',(0.282309422539,1.)); +#14655 = CARTESIAN_POINT('',(0.326519436214,1.)); +#14656 = CARTESIAN_POINT('',(0.370278310591,1.)); +#14657 = CARTESIAN_POINT('',(0.413702852292,1.)); +#14658 = CARTESIAN_POINT('',(0.456906394885,1.)); +#14659 = CARTESIAN_POINT('',(0.5,1.)); +#14660 = CARTESIAN_POINT('',(0.543093605115,1.)); +#14661 = CARTESIAN_POINT('',(0.586297147708,1.)); +#14662 = CARTESIAN_POINT('',(0.629721689409,1.)); +#14663 = CARTESIAN_POINT('',(0.673480563786,1.)); +#14664 = CARTESIAN_POINT('',(0.717690577461,1.)); +#14665 = CARTESIAN_POINT('',(0.762473275577,1.)); +#14666 = CARTESIAN_POINT('',(0.807956362777,1.)); +#14667 = CARTESIAN_POINT('',(0.854275086925,1.)); +#14668 = CARTESIAN_POINT('',(0.901574474096,1.)); +#14669 = CARTESIAN_POINT('',(0.950009297011,1.)); +#14670 = CARTESIAN_POINT('',(0.983172198663,1.)); +#14671 = CARTESIAN_POINT('',(1.,1.)); +#14672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14673 = PCURVE('',#14459,#14674); +#14674 = DEFINITIONAL_REPRESENTATION('',(#14675),#14678); +#14675 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14676,#14677),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#12284 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#12285 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#12286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12287 = ADVANCED_FACE('',(#12288),#12067,.T.); -#12288 = FACE_BOUND('',#12289,.T.); -#12289 = EDGE_LOOP('',(#12290,#12291,#12292,#12377)); -#12290 = ORIENTED_EDGE('',*,*,#12245,.T.); -#12291 = ORIENTED_EDGE('',*,*,#12051,.T.); -#12292 = ORIENTED_EDGE('',*,*,#12293,.F.); -#12293 = EDGE_CURVE('',#12294,#12018,#12296,.T.); -#12294 = VERTEX_POINT('',#12295); -#12295 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); -#12296 = SURFACE_CURVE('',#12297,(#12302,#12331),.PCURVE_S1.); -#12297 = CIRCLE('',#12298,5.E-002); -#12298 = AXIS2_PLACEMENT_3D('',#12299,#12300,#12301); -#12299 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); -#12300 = DIRECTION('',(0.E+000,-1.224646799147E-016,-1.)); -#12301 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12302 = PCURVE('',#12067,#12303); -#12303 = DEFINITIONAL_REPRESENTATION('',(#12304),#12330); -#12304 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12305,#12306,#12307,#12308, - #12309,#12310,#12311,#12312,#12313,#12314,#12315,#12316,#12317, - #12318,#12319,#12320,#12321,#12322,#12323,#12324,#12325,#12326, - #12327,#12328,#12329),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14676 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#14677 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#14678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14679 = ADVANCED_FACE('',(#14680),#14459,.T.); +#14680 = FACE_BOUND('',#14681,.T.); +#14681 = EDGE_LOOP('',(#14682,#14683,#14684,#14769)); +#14682 = ORIENTED_EDGE('',*,*,#14637,.T.); +#14683 = ORIENTED_EDGE('',*,*,#14443,.T.); +#14684 = ORIENTED_EDGE('',*,*,#14685,.F.); +#14685 = EDGE_CURVE('',#14686,#14410,#14688,.T.); +#14686 = VERTEX_POINT('',#14687); +#14687 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); +#14688 = SURFACE_CURVE('',#14689,(#14694,#14723),.PCURVE_S1.); +#14689 = CIRCLE('',#14690,5.E-002); +#14690 = AXIS2_PLACEMENT_3D('',#14691,#14692,#14693); +#14691 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); +#14692 = DIRECTION('',(0.E+000,-1.224646799147E-016,-1.)); +#14693 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14694 = PCURVE('',#14459,#14695); +#14695 = DEFINITIONAL_REPRESENTATION('',(#14696),#14722); +#14696 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14697,#14698,#14699,#14700, + #14701,#14702,#14703,#14704,#14705,#14706,#14707,#14708,#14709, + #14710,#14711,#14712,#14713,#14714,#14715,#14716,#14717,#14718, + #14719,#14720,#14721),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -14696,40 +17685,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#12305 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#12306 = CARTESIAN_POINT('',(3.165392597935,0.25)); -#12307 = CARTESIAN_POINT('',(3.212992486626,0.25)); -#12308 = CARTESIAN_POINT('',(3.284392319662,0.25)); -#12309 = CARTESIAN_POINT('',(3.355792152698,0.25)); -#12310 = CARTESIAN_POINT('',(3.427191985734,0.25)); -#12311 = CARTESIAN_POINT('',(3.49859181877,0.25)); -#12312 = CARTESIAN_POINT('',(3.569991651807,0.25)); -#12313 = CARTESIAN_POINT('',(3.641391484843,0.25)); -#12314 = CARTESIAN_POINT('',(3.712791317879,0.25)); -#12315 = CARTESIAN_POINT('',(3.784191150915,0.25)); -#12316 = CARTESIAN_POINT('',(3.855590983951,0.25)); -#12317 = CARTESIAN_POINT('',(3.926990816987,0.25)); -#12318 = CARTESIAN_POINT('',(3.998390650023,0.25)); -#12319 = CARTESIAN_POINT('',(4.06979048306,0.25)); -#12320 = CARTESIAN_POINT('',(4.141190316096,0.25)); -#12321 = CARTESIAN_POINT('',(4.212590149132,0.25)); -#12322 = CARTESIAN_POINT('',(4.283989982168,0.25)); -#12323 = CARTESIAN_POINT('',(4.355389815204,0.25)); -#12324 = CARTESIAN_POINT('',(4.42678964824,0.25)); -#12325 = CARTESIAN_POINT('',(4.498189481276,0.25)); -#12326 = CARTESIAN_POINT('',(4.569589314312,0.25)); -#12327 = CARTESIAN_POINT('',(4.640989147349,0.25)); -#12328 = CARTESIAN_POINT('',(4.688589036039,0.25)); -#12329 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#12330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12331 = PCURVE('',#12332,#12349); -#12332 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#12333,#12334,#12335,#12336) - ,(#12337,#12338,#12339,#12340) - ,(#12341,#12342,#12343,#12344) - ,(#12345,#12346,#12347,#12348 +#14697 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#14698 = CARTESIAN_POINT('',(3.165392597935,0.25)); +#14699 = CARTESIAN_POINT('',(3.212992486626,0.25)); +#14700 = CARTESIAN_POINT('',(3.284392319662,0.25)); +#14701 = CARTESIAN_POINT('',(3.355792152698,0.25)); +#14702 = CARTESIAN_POINT('',(3.427191985734,0.25)); +#14703 = CARTESIAN_POINT('',(3.49859181877,0.25)); +#14704 = CARTESIAN_POINT('',(3.569991651807,0.25)); +#14705 = CARTESIAN_POINT('',(3.641391484843,0.25)); +#14706 = CARTESIAN_POINT('',(3.712791317879,0.25)); +#14707 = CARTESIAN_POINT('',(3.784191150915,0.25)); +#14708 = CARTESIAN_POINT('',(3.855590983951,0.25)); +#14709 = CARTESIAN_POINT('',(3.926990816987,0.25)); +#14710 = CARTESIAN_POINT('',(3.998390650023,0.25)); +#14711 = CARTESIAN_POINT('',(4.06979048306,0.25)); +#14712 = CARTESIAN_POINT('',(4.141190316096,0.25)); +#14713 = CARTESIAN_POINT('',(4.212590149132,0.25)); +#14714 = CARTESIAN_POINT('',(4.283989982168,0.25)); +#14715 = CARTESIAN_POINT('',(4.355389815204,0.25)); +#14716 = CARTESIAN_POINT('',(4.42678964824,0.25)); +#14717 = CARTESIAN_POINT('',(4.498189481276,0.25)); +#14718 = CARTESIAN_POINT('',(4.569589314312,0.25)); +#14719 = CARTESIAN_POINT('',(4.640989147349,0.25)); +#14720 = CARTESIAN_POINT('',(4.688589036039,0.25)); +#14721 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#14722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14723 = PCURVE('',#14724,#14741); +#14724 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#14725,#14726,#14727,#14728) + ,(#14729,#14730,#14731,#14732) + ,(#14733,#14734,#14735,#14736) + ,(#14737,#14738,#14739,#14740 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -14738,28 +17727,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#12333 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); -#12334 = CARTESIAN_POINT('',(-0.45,-0.25,2.071067811865E-002)); -#12335 = CARTESIAN_POINT('',(-0.45,-0.229289321881,0.E+000)); -#12336 = CARTESIAN_POINT('',(-0.45,-0.2,0.E+000)); -#12337 = CARTESIAN_POINT('',(-0.479289321881,-0.25,5.E-002)); -#12338 = CARTESIAN_POINT('',(-0.479289321881,-0.25,2.071067811865E-002) - ); -#12339 = CARTESIAN_POINT('',(-0.479289321881,-0.229289321881,0.E+000)); -#12340 = CARTESIAN_POINT('',(-0.479289321881,-0.2,0.E+000)); -#12341 = CARTESIAN_POINT('',(-0.5,-0.229289321881,5.E-002)); -#12342 = CARTESIAN_POINT('',(-0.5,-0.229289321881,3.284271247462E-002)); -#12343 = CARTESIAN_POINT('',(-0.5,-0.217157287525,2.071067811865E-002)); -#12344 = CARTESIAN_POINT('',(-0.5,-0.2,2.071067811865E-002)); -#12345 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); -#12346 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); -#12347 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); -#12348 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); -#12349 = DEFINITIONAL_REPRESENTATION('',(#12350),#12376); -#12350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12351,#12352,#12353,#12354, - #12355,#12356,#12357,#12358,#12359,#12360,#12361,#12362,#12363, - #12364,#12365,#12366,#12367,#12368,#12369,#12370,#12371,#12372, - #12373,#12374,#12375),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14725 = CARTESIAN_POINT('',(-0.45,-0.25,5.E-002)); +#14726 = CARTESIAN_POINT('',(-0.45,-0.25,2.071067811865E-002)); +#14727 = CARTESIAN_POINT('',(-0.45,-0.229289321881,0.E+000)); +#14728 = CARTESIAN_POINT('',(-0.45,-0.2,0.E+000)); +#14729 = CARTESIAN_POINT('',(-0.479289321881,-0.25,5.E-002)); +#14730 = CARTESIAN_POINT('',(-0.479289321881,-0.25,2.071067811865E-002) + ); +#14731 = CARTESIAN_POINT('',(-0.479289321881,-0.229289321881,0.E+000)); +#14732 = CARTESIAN_POINT('',(-0.479289321881,-0.2,0.E+000)); +#14733 = CARTESIAN_POINT('',(-0.5,-0.229289321881,5.E-002)); +#14734 = CARTESIAN_POINT('',(-0.5,-0.229289321881,3.284271247462E-002)); +#14735 = CARTESIAN_POINT('',(-0.5,-0.217157287525,2.071067811865E-002)); +#14736 = CARTESIAN_POINT('',(-0.5,-0.2,2.071067811865E-002)); +#14737 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); +#14738 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); +#14739 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); +#14740 = CARTESIAN_POINT('',(-0.5,-0.2,5.E-002)); +#14741 = DEFINITIONAL_REPRESENTATION('',(#14742),#14768); +#14742 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14743,#14744,#14745,#14746, + #14747,#14748,#14749,#14750,#14751,#14752,#14753,#14754,#14755, + #14756,#14757,#14758,#14759,#14760,#14761,#14762,#14763,#14764, + #14765,#14766,#14767),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -14767,84 +17756,84 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#12351 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12352 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#12353 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#12354 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#12355 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#12356 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#12357 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#12358 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#12359 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#12360 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#12361 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#12362 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#12363 = CARTESIAN_POINT('',(0.5,0.E+000)); -#12364 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#12365 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#12366 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#12367 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#12368 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#12369 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#12370 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#12371 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#12372 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#12373 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#12374 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#12375 = CARTESIAN_POINT('',(1.,0.E+000)); -#12376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12377 = ORIENTED_EDGE('',*,*,#12378,.T.); -#12378 = EDGE_CURVE('',#12294,#12136,#12379,.T.); -#12379 = SURFACE_CURVE('',#12380,(#12384,#12390),.PCURVE_S1.); -#12380 = LINE('',#12381,#12382); -#12381 = CARTESIAN_POINT('',(-0.45,-0.25,0.3)); -#12382 = VECTOR('',#12383,1.); -#12383 = DIRECTION('',(4.259399095405E-061,-2.595054858731E-031,1.)); -#12384 = PCURVE('',#12067,#12385); -#12385 = DEFINITIONAL_REPRESENTATION('',(#12386),#12389); -#12386 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12387,#12388),.UNSPECIFIED., +#14743 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14744 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#14745 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#14746 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#14747 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#14748 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#14749 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#14750 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#14751 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#14752 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#14753 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#14754 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#14755 = CARTESIAN_POINT('',(0.5,0.E+000)); +#14756 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#14757 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#14758 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#14759 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#14760 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#14761 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#14762 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#14763 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#14764 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#14765 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#14766 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#14767 = CARTESIAN_POINT('',(1.,0.E+000)); +#14768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14769 = ORIENTED_EDGE('',*,*,#14770,.T.); +#14770 = EDGE_CURVE('',#14686,#14528,#14771,.T.); +#14771 = SURFACE_CURVE('',#14772,(#14776,#14782),.PCURVE_S1.); +#14772 = LINE('',#14773,#14774); +#14773 = CARTESIAN_POINT('',(-0.45,-0.25,0.3)); +#14774 = VECTOR('',#14775,1.); +#14775 = DIRECTION('',(4.259399095405E-061,-2.595054858731E-031,1.)); +#14776 = PCURVE('',#14459,#14777); +#14777 = DEFINITIONAL_REPRESENTATION('',(#14778),#14781); +#14778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14779,#14780),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#12387 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#12388 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#12389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12390 = PCURVE('',#12391,#12396); -#12391 = PLANE('',#12392); -#12392 = AXIS2_PLACEMENT_3D('',#12393,#12394,#12395); -#12393 = CARTESIAN_POINT('',(-0.375,-0.25,0.3)); -#12394 = DIRECTION('',(-1.641352236187E-030,1.,2.595054858731E-031)); -#12395 = DIRECTION('',(-1.,-1.641352236187E-030,1.106509096121E-077)); -#12396 = DEFINITIONAL_REPRESENTATION('',(#12397),#12401); -#12397 = LINE('',#12398,#12399); -#12398 = CARTESIAN_POINT('',(7.5E-002,-3.194549321554E-062)); -#12399 = VECTOR('',#12400,1.); -#12400 = DIRECTION('',(6.908934844076E-077,1.)); -#12401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12402 = ADVANCED_FACE('',(#12403),#12332,.T.); -#12403 = FACE_BOUND('',#12404,.T.); -#12404 = EDGE_LOOP('',(#12405,#12406,#12451)); -#12405 = ORIENTED_EDGE('',*,*,#12293,.T.); -#12406 = ORIENTED_EDGE('',*,*,#12407,.F.); -#12407 = EDGE_CURVE('',#12408,#12018,#12410,.T.); -#12408 = VERTEX_POINT('',#12409); -#12409 = CARTESIAN_POINT('',(-0.45,-0.2,1.055240209696E-017)); -#12410 = SURFACE_CURVE('',#12411,(#12416,#12445),.PCURVE_S1.); -#12411 = CIRCLE('',#12412,5.E-002); -#12412 = AXIS2_PLACEMENT_3D('',#12413,#12414,#12415); -#12413 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); -#12414 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12415 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12416 = PCURVE('',#12332,#12417); -#12417 = DEFINITIONAL_REPRESENTATION('',(#12418),#12444); -#12418 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12419,#12420,#12421,#12422, - #12423,#12424,#12425,#12426,#12427,#12428,#12429,#12430,#12431, - #12432,#12433,#12434,#12435,#12436,#12437,#12438,#12439,#12440, - #12441,#12442,#12443),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14779 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#14780 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#14781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14782 = PCURVE('',#14783,#14788); +#14783 = PLANE('',#14784); +#14784 = AXIS2_PLACEMENT_3D('',#14785,#14786,#14787); +#14785 = CARTESIAN_POINT('',(-0.375,-0.25,0.3)); +#14786 = DIRECTION('',(-1.641352236187E-030,1.,2.595054858731E-031)); +#14787 = DIRECTION('',(-1.,-1.641352236187E-030,1.106509096121E-077)); +#14788 = DEFINITIONAL_REPRESENTATION('',(#14789),#14793); +#14789 = LINE('',#14790,#14791); +#14790 = CARTESIAN_POINT('',(7.5E-002,-3.194549321554E-062)); +#14791 = VECTOR('',#14792,1.); +#14792 = DIRECTION('',(6.908934844076E-077,1.)); +#14793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14794 = ADVANCED_FACE('',(#14795),#14724,.T.); +#14795 = FACE_BOUND('',#14796,.T.); +#14796 = EDGE_LOOP('',(#14797,#14798,#14843)); +#14797 = ORIENTED_EDGE('',*,*,#14685,.T.); +#14798 = ORIENTED_EDGE('',*,*,#14799,.F.); +#14799 = EDGE_CURVE('',#14800,#14410,#14802,.T.); +#14800 = VERTEX_POINT('',#14801); +#14801 = CARTESIAN_POINT('',(-0.45,-0.2,1.055240209696E-017)); +#14802 = SURFACE_CURVE('',#14803,(#14808,#14837),.PCURVE_S1.); +#14803 = CIRCLE('',#14804,5.E-002); +#14804 = AXIS2_PLACEMENT_3D('',#14805,#14806,#14807); +#14805 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); +#14806 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14807 = DIRECTION('',(0.E+000,0.E+000,1.)); +#14808 = PCURVE('',#14724,#14809); +#14809 = DEFINITIONAL_REPRESENTATION('',(#14810),#14836); +#14810 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14811,#14812,#14813,#14814, + #14815,#14816,#14817,#14818,#14819,#14820,#14821,#14822,#14823, + #14824,#14825,#14826,#14827,#14828,#14829,#14830,#14831,#14832, + #14833,#14834,#14835),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -14852,58 +17841,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#12419 = CARTESIAN_POINT('',(0.E+000,1.)); -#12420 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#12421 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#12422 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#12423 = CARTESIAN_POINT('',(0.145724913075,1.)); -#12424 = CARTESIAN_POINT('',(0.192043637223,1.)); -#12425 = CARTESIAN_POINT('',(0.237526724423,1.)); -#12426 = CARTESIAN_POINT('',(0.282309422539,1.)); -#12427 = CARTESIAN_POINT('',(0.326519436214,1.)); -#12428 = CARTESIAN_POINT('',(0.370278310591,1.)); -#12429 = CARTESIAN_POINT('',(0.413702852292,1.)); -#12430 = CARTESIAN_POINT('',(0.456906394885,1.)); -#12431 = CARTESIAN_POINT('',(0.5,1.)); -#12432 = CARTESIAN_POINT('',(0.543093605115,1.)); -#12433 = CARTESIAN_POINT('',(0.586297147708,1.)); -#12434 = CARTESIAN_POINT('',(0.629721689409,1.)); -#12435 = CARTESIAN_POINT('',(0.673480563786,1.)); -#12436 = CARTESIAN_POINT('',(0.717690577461,1.)); -#12437 = CARTESIAN_POINT('',(0.762473275577,1.)); -#12438 = CARTESIAN_POINT('',(0.807956362777,1.)); -#12439 = CARTESIAN_POINT('',(0.854275086925,1.)); -#12440 = CARTESIAN_POINT('',(0.901574474096,1.)); -#12441 = CARTESIAN_POINT('',(0.950009297011,1.)); -#12442 = CARTESIAN_POINT('',(0.983172198663,1.)); -#12443 = CARTESIAN_POINT('',(1.,1.)); -#12444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12445 = PCURVE('',#12040,#12446); -#12446 = DEFINITIONAL_REPRESENTATION('',(#12447),#12450); -#12447 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12448,#12449),.UNSPECIFIED., +#14811 = CARTESIAN_POINT('',(0.E+000,1.)); +#14812 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#14813 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#14814 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#14815 = CARTESIAN_POINT('',(0.145724913075,1.)); +#14816 = CARTESIAN_POINT('',(0.192043637223,1.)); +#14817 = CARTESIAN_POINT('',(0.237526724423,1.)); +#14818 = CARTESIAN_POINT('',(0.282309422539,1.)); +#14819 = CARTESIAN_POINT('',(0.326519436214,1.)); +#14820 = CARTESIAN_POINT('',(0.370278310591,1.)); +#14821 = CARTESIAN_POINT('',(0.413702852292,1.)); +#14822 = CARTESIAN_POINT('',(0.456906394885,1.)); +#14823 = CARTESIAN_POINT('',(0.5,1.)); +#14824 = CARTESIAN_POINT('',(0.543093605115,1.)); +#14825 = CARTESIAN_POINT('',(0.586297147708,1.)); +#14826 = CARTESIAN_POINT('',(0.629721689409,1.)); +#14827 = CARTESIAN_POINT('',(0.673480563786,1.)); +#14828 = CARTESIAN_POINT('',(0.717690577461,1.)); +#14829 = CARTESIAN_POINT('',(0.762473275577,1.)); +#14830 = CARTESIAN_POINT('',(0.807956362777,1.)); +#14831 = CARTESIAN_POINT('',(0.854275086925,1.)); +#14832 = CARTESIAN_POINT('',(0.901574474096,1.)); +#14833 = CARTESIAN_POINT('',(0.950009297011,1.)); +#14834 = CARTESIAN_POINT('',(0.983172198663,1.)); +#14835 = CARTESIAN_POINT('',(1.,1.)); +#14836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14837 = PCURVE('',#14432,#14838); +#14838 = DEFINITIONAL_REPRESENTATION('',(#14839),#14842); +#14839 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14840,#14841),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#12448 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#12449 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#12450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12451 = ORIENTED_EDGE('',*,*,#12452,.F.); -#12452 = EDGE_CURVE('',#12294,#12408,#12453,.T.); -#12453 = SURFACE_CURVE('',#12454,(#12459,#12488),.PCURVE_S1.); -#12454 = CIRCLE('',#12455,5.E-002); -#12455 = AXIS2_PLACEMENT_3D('',#12456,#12457,#12458); -#12456 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); -#12457 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); -#12458 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); -#12459 = PCURVE('',#12332,#12460); -#12460 = DEFINITIONAL_REPRESENTATION('',(#12461),#12487); -#12461 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12462,#12463,#12464,#12465, - #12466,#12467,#12468,#12469,#12470,#12471,#12472,#12473,#12474, - #12475,#12476,#12477,#12478,#12479,#12480,#12481,#12482,#12483, - #12484,#12485,#12486),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14840 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#14841 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#14842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14843 = ORIENTED_EDGE('',*,*,#14844,.F.); +#14844 = EDGE_CURVE('',#14686,#14800,#14845,.T.); +#14845 = SURFACE_CURVE('',#14846,(#14851,#14880),.PCURVE_S1.); +#14846 = CIRCLE('',#14847,5.E-002); +#14847 = AXIS2_PLACEMENT_3D('',#14848,#14849,#14850); +#14848 = CARTESIAN_POINT('',(-0.45,-0.2,5.E-002)); +#14849 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); +#14850 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); +#14851 = PCURVE('',#14724,#14852); +#14852 = DEFINITIONAL_REPRESENTATION('',(#14853),#14879); +#14853 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14854,#14855,#14856,#14857, + #14858,#14859,#14860,#14861,#14862,#14863,#14864,#14865,#14866, + #14867,#14868,#14869,#14870,#14871,#14872,#14873,#14874,#14875, + #14876,#14877,#14878),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -14911,80 +17900,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#12462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12463 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#12464 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#12465 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#12466 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#12467 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#12468 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#12469 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#12470 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#12471 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#12472 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#12473 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#12474 = CARTESIAN_POINT('',(0.E+000,0.5)); -#12475 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#12476 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#12477 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#12478 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#12479 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#12480 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#12481 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#12482 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#12483 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#12484 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#12485 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#12486 = CARTESIAN_POINT('',(0.E+000,1.)); -#12487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12488 = PCURVE('',#12489,#12494); -#12489 = CYLINDRICAL_SURFACE('',#12490,5.E-002); -#12490 = AXIS2_PLACEMENT_3D('',#12491,#12492,#12493); -#12491 = CARTESIAN_POINT('',(-0.375,-0.2,5.E-002)); -#12492 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); -#12493 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); -#12494 = DEFINITIONAL_REPRESENTATION('',(#12495),#12498); -#12495 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12496,#12497),.UNSPECIFIED., +#14854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14855 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#14856 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#14857 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#14858 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#14859 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#14860 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#14861 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#14862 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#14863 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#14864 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#14865 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#14866 = CARTESIAN_POINT('',(0.E+000,0.5)); +#14867 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#14868 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#14869 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#14870 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#14871 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#14872 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#14873 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#14874 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#14875 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#14876 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#14877 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#14878 = CARTESIAN_POINT('',(0.E+000,1.)); +#14879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14880 = PCURVE('',#14881,#14886); +#14881 = CYLINDRICAL_SURFACE('',#14882,5.E-002); +#14882 = AXIS2_PLACEMENT_3D('',#14883,#14884,#14885); +#14883 = CARTESIAN_POINT('',(-0.375,-0.2,5.E-002)); +#14884 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); +#14885 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); +#14886 = DEFINITIONAL_REPRESENTATION('',(#14887),#14890); +#14887 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14888,#14889),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#12496 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); -#12497 = CARTESIAN_POINT('',(6.28318530718,-7.5E-002)); -#12498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12499 = ADVANCED_FACE('',(#12500),#12040,.T.); -#12500 = FACE_BOUND('',#12501,.T.); -#12501 = EDGE_LOOP('',(#12502,#12503,#12504,#12566)); -#12502 = ORIENTED_EDGE('',*,*,#12407,.T.); -#12503 = ORIENTED_EDGE('',*,*,#12017,.T.); -#12504 = ORIENTED_EDGE('',*,*,#12505,.F.); -#12505 = EDGE_CURVE('',#12506,#12020,#12508,.T.); -#12506 = VERTEX_POINT('',#12507); -#12507 = CARTESIAN_POINT('',(-0.45,0.2,3.337249060612E-018)); -#12508 = SURFACE_CURVE('',#12509,(#12514,#12520),.PCURVE_S1.); -#12509 = CIRCLE('',#12510,5.E-002); -#12510 = AXIS2_PLACEMENT_3D('',#12511,#12512,#12513); -#12511 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); -#12512 = DIRECTION('',(0.E+000,1.,-1.836970198721E-016)); -#12513 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12514 = PCURVE('',#12040,#12515); -#12515 = DEFINITIONAL_REPRESENTATION('',(#12516),#12519); -#12516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12517,#12518),.UNSPECIFIED., +#14888 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); +#14889 = CARTESIAN_POINT('',(6.28318530718,-7.5E-002)); +#14890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14891 = ADVANCED_FACE('',(#14892),#14432,.T.); +#14892 = FACE_BOUND('',#14893,.T.); +#14893 = EDGE_LOOP('',(#14894,#14895,#14896,#14958)); +#14894 = ORIENTED_EDGE('',*,*,#14799,.T.); +#14895 = ORIENTED_EDGE('',*,*,#14409,.T.); +#14896 = ORIENTED_EDGE('',*,*,#14897,.F.); +#14897 = EDGE_CURVE('',#14898,#14412,#14900,.T.); +#14898 = VERTEX_POINT('',#14899); +#14899 = CARTESIAN_POINT('',(-0.45,0.2,3.337249060612E-018)); +#14900 = SURFACE_CURVE('',#14901,(#14906,#14912),.PCURVE_S1.); +#14901 = CIRCLE('',#14902,5.E-002); +#14902 = AXIS2_PLACEMENT_3D('',#14903,#14904,#14905); +#14903 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); +#14904 = DIRECTION('',(0.E+000,1.,-1.836970198721E-016)); +#14905 = DIRECTION('',(1.,0.E+000,0.E+000)); +#14906 = PCURVE('',#14432,#14907); +#14907 = DEFINITIONAL_REPRESENTATION('',(#14908),#14911); +#14908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14909,#14910),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#12517 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#12518 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#12519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#14909 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#14910 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#14911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12520 = PCURVE('',#12521,#12538); -#12521 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#12522,#12523,#12524,#12525) - ,(#12526,#12527,#12528,#12529) - ,(#12530,#12531,#12532,#12533) - ,(#12534,#12535,#12536,#12537 +#14912 = PCURVE('',#14913,#14930); +#14913 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#14914,#14915,#14916,#14917) + ,(#14918,#14919,#14920,#14921) + ,(#14922,#14923,#14924,#14925) + ,(#14926,#14927,#14928,#14929 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -14993,28 +17982,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#12522 = CARTESIAN_POINT('',(-0.45,0.2,-6.776263578034E-018)); -#12523 = CARTESIAN_POINT('',(-0.45,0.229289321881,9.101509629156E-018)); -#12524 = CARTESIAN_POINT('',(-0.45,0.25,2.071067811865E-002)); -#12525 = CARTESIAN_POINT('',(-0.45,0.25,5.E-002)); -#12526 = CARTESIAN_POINT('',(-0.479289321881,0.2,-8.569717292594E-018)); -#12527 = CARTESIAN_POINT('',(-0.479289321881,0.229289321881, +#14914 = CARTESIAN_POINT('',(-0.45,0.2,-6.776263578034E-018)); +#14915 = CARTESIAN_POINT('',(-0.45,0.229289321881,9.101509629156E-018)); +#14916 = CARTESIAN_POINT('',(-0.45,0.25,2.071067811865E-002)); +#14917 = CARTESIAN_POINT('',(-0.45,0.25,5.E-002)); +#14918 = CARTESIAN_POINT('',(-0.479289321881,0.2,-8.569717292594E-018)); +#14919 = CARTESIAN_POINT('',(-0.479289321881,0.229289321881, -8.569717292594E-018)); -#12528 = CARTESIAN_POINT('',(-0.479289321881,0.25,2.071067811865E-002)); -#12529 = CARTESIAN_POINT('',(-0.479289321881,0.25,5.E-002)); -#12530 = CARTESIAN_POINT('',(-0.5,0.2,2.071067811865E-002)); -#12531 = CARTESIAN_POINT('',(-0.5,0.217157287525,2.071067811865E-002)); -#12532 = CARTESIAN_POINT('',(-0.5,0.229289321881,3.284271247462E-002)); -#12533 = CARTESIAN_POINT('',(-0.5,0.229289321881,5.E-002)); -#12534 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); -#12535 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); -#12536 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); -#12537 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); -#12538 = DEFINITIONAL_REPRESENTATION('',(#12539),#12565); -#12539 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12540,#12541,#12542,#12543, - #12544,#12545,#12546,#12547,#12548,#12549,#12550,#12551,#12552, - #12553,#12554,#12555,#12556,#12557,#12558,#12559,#12560,#12561, - #12562,#12563,#12564),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14920 = CARTESIAN_POINT('',(-0.479289321881,0.25,2.071067811865E-002)); +#14921 = CARTESIAN_POINT('',(-0.479289321881,0.25,5.E-002)); +#14922 = CARTESIAN_POINT('',(-0.5,0.2,2.071067811865E-002)); +#14923 = CARTESIAN_POINT('',(-0.5,0.217157287525,2.071067811865E-002)); +#14924 = CARTESIAN_POINT('',(-0.5,0.229289321881,3.284271247462E-002)); +#14925 = CARTESIAN_POINT('',(-0.5,0.229289321881,5.E-002)); +#14926 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); +#14927 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); +#14928 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); +#14929 = CARTESIAN_POINT('',(-0.5,0.2,5.E-002)); +#14930 = DEFINITIONAL_REPRESENTATION('',(#14931),#14957); +#14931 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14932,#14933,#14934,#14935, + #14936,#14937,#14938,#14939,#14940,#14941,#14942,#14943,#14944, + #14945,#14946,#14947,#14948,#14949,#14950,#14951,#14952,#14953, + #14954,#14955,#14956),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -15022,84 +18011,84 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#12540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12541 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#12542 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#12543 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#12544 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#12545 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#12546 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#12547 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#12548 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#12549 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#12550 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#12551 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#12552 = CARTESIAN_POINT('',(0.5,0.E+000)); -#12553 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#12554 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#12555 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#12556 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#12557 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#12558 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#12559 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#12560 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#12561 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#12562 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#12563 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#12564 = CARTESIAN_POINT('',(1.,0.E+000)); -#12565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12566 = ORIENTED_EDGE('',*,*,#12567,.F.); -#12567 = EDGE_CURVE('',#12408,#12506,#12568,.T.); -#12568 = SURFACE_CURVE('',#12569,(#12573,#12579),.PCURVE_S1.); -#12569 = LINE('',#12570,#12571); -#12570 = CARTESIAN_POINT('',(-0.45,-0.25,2.449293598295E-017)); -#12571 = VECTOR('',#12572,1.); -#12572 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12573 = PCURVE('',#12040,#12574); -#12574 = DEFINITIONAL_REPRESENTATION('',(#12575),#12578); -#12575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12576,#12577),.UNSPECIFIED., +#14932 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#14933 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#14934 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#14935 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#14936 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#14937 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#14938 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#14939 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#14940 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#14941 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#14942 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#14943 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#14944 = CARTESIAN_POINT('',(0.5,0.E+000)); +#14945 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#14946 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#14947 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#14948 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#14949 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#14950 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#14951 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#14952 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#14953 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#14954 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#14955 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#14956 = CARTESIAN_POINT('',(1.,0.E+000)); +#14957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14958 = ORIENTED_EDGE('',*,*,#14959,.F.); +#14959 = EDGE_CURVE('',#14800,#14898,#14960,.T.); +#14960 = SURFACE_CURVE('',#14961,(#14965,#14971),.PCURVE_S1.); +#14961 = LINE('',#14962,#14963); +#14962 = CARTESIAN_POINT('',(-0.45,-0.25,2.449293598295E-017)); +#14963 = VECTOR('',#14964,1.); +#14964 = DIRECTION('',(0.E+000,1.,0.E+000)); +#14965 = PCURVE('',#14432,#14966); +#14966 = DEFINITIONAL_REPRESENTATION('',(#14967),#14970); +#14967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14968,#14969),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#12576 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#12577 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#12578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12579 = PCURVE('',#12580,#12585); -#12580 = PLANE('',#12581); -#12581 = AXIS2_PLACEMENT_3D('',#12582,#12583,#12584); -#12582 = CARTESIAN_POINT('',(-0.375,-0.25,1.530808498934E-017)); -#12583 = DIRECTION('',(-1.224646799147E-016,0.E+000,-1.)); -#12584 = DIRECTION('',(-1.,0.E+000,1.224646799147E-016)); -#12585 = DEFINITIONAL_REPRESENTATION('',(#12586),#12590); -#12586 = LINE('',#12587,#12588); -#12587 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); -#12588 = VECTOR('',#12589,1.); -#12589 = DIRECTION('',(0.E+000,1.)); -#12590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12591 = ADVANCED_FACE('',(#12592),#12521,.T.); -#12592 = FACE_BOUND('',#12593,.T.); -#12593 = EDGE_LOOP('',(#12594,#12595,#12640)); -#12594 = ORIENTED_EDGE('',*,*,#12505,.T.); -#12595 = ORIENTED_EDGE('',*,*,#12596,.F.); -#12596 = EDGE_CURVE('',#12597,#12020,#12599,.T.); -#12597 = VERTEX_POINT('',#12598); -#12598 = CARTESIAN_POINT('',(-0.45,0.25,5.E-002)); -#12599 = SURFACE_CURVE('',#12600,(#12605,#12634),.PCURVE_S1.); -#12600 = CIRCLE('',#12601,5.E-002); -#12601 = AXIS2_PLACEMENT_3D('',#12602,#12603,#12604); -#12602 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); -#12603 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#12604 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); -#12605 = PCURVE('',#12521,#12606); -#12606 = DEFINITIONAL_REPRESENTATION('',(#12607),#12633); -#12607 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12608,#12609,#12610,#12611, - #12612,#12613,#12614,#12615,#12616,#12617,#12618,#12619,#12620, - #12621,#12622,#12623,#12624,#12625,#12626,#12627,#12628,#12629, - #12630,#12631,#12632),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#14968 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#14969 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#14970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14971 = PCURVE('',#14972,#14977); +#14972 = PLANE('',#14973); +#14973 = AXIS2_PLACEMENT_3D('',#14974,#14975,#14976); +#14974 = CARTESIAN_POINT('',(-0.375,-0.25,1.530808498934E-017)); +#14975 = DIRECTION('',(-1.224646799147E-016,0.E+000,-1.)); +#14976 = DIRECTION('',(-1.,0.E+000,1.224646799147E-016)); +#14977 = DEFINITIONAL_REPRESENTATION('',(#14978),#14982); +#14978 = LINE('',#14979,#14980); +#14979 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); +#14980 = VECTOR('',#14981,1.); +#14981 = DIRECTION('',(0.E+000,1.)); +#14982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#14983 = ADVANCED_FACE('',(#14984),#14913,.T.); +#14984 = FACE_BOUND('',#14985,.T.); +#14985 = EDGE_LOOP('',(#14986,#14987,#15032)); +#14986 = ORIENTED_EDGE('',*,*,#14897,.T.); +#14987 = ORIENTED_EDGE('',*,*,#14988,.F.); +#14988 = EDGE_CURVE('',#14989,#14412,#14991,.T.); +#14989 = VERTEX_POINT('',#14990); +#14990 = CARTESIAN_POINT('',(-0.45,0.25,5.E-002)); +#14991 = SURFACE_CURVE('',#14992,(#14997,#15026),.PCURVE_S1.); +#14992 = CIRCLE('',#14993,5.E-002); +#14993 = AXIS2_PLACEMENT_3D('',#14994,#14995,#14996); +#14994 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); +#14995 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#14996 = DIRECTION('',(0.E+000,1.,2.595054858731E-031)); +#14997 = PCURVE('',#14913,#14998); +#14998 = DEFINITIONAL_REPRESENTATION('',(#14999),#15025); +#14999 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15000,#15001,#15002,#15003, + #15004,#15005,#15006,#15007,#15008,#15009,#15010,#15011,#15012, + #15013,#15014,#15015,#15016,#15017,#15018,#15019,#15020,#15021, + #15022,#15023,#15024),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -15107,57 +18096,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#12608 = CARTESIAN_POINT('',(0.E+000,1.)); -#12609 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#12610 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#12611 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#12612 = CARTESIAN_POINT('',(0.145724913075,1.)); -#12613 = CARTESIAN_POINT('',(0.192043637223,1.)); -#12614 = CARTESIAN_POINT('',(0.237526724423,1.)); -#12615 = CARTESIAN_POINT('',(0.282309422539,1.)); -#12616 = CARTESIAN_POINT('',(0.326519436214,1.)); -#12617 = CARTESIAN_POINT('',(0.370278310591,1.)); -#12618 = CARTESIAN_POINT('',(0.413702852292,1.)); -#12619 = CARTESIAN_POINT('',(0.456906394885,1.)); -#12620 = CARTESIAN_POINT('',(0.5,1.)); -#12621 = CARTESIAN_POINT('',(0.543093605115,1.)); -#12622 = CARTESIAN_POINT('',(0.586297147708,1.)); -#12623 = CARTESIAN_POINT('',(0.629721689409,1.)); -#12624 = CARTESIAN_POINT('',(0.673480563786,1.)); -#12625 = CARTESIAN_POINT('',(0.717690577461,1.)); -#12626 = CARTESIAN_POINT('',(0.762473275577,1.)); -#12627 = CARTESIAN_POINT('',(0.807956362777,1.)); -#12628 = CARTESIAN_POINT('',(0.854275086925,1.)); -#12629 = CARTESIAN_POINT('',(0.901574474096,1.)); -#12630 = CARTESIAN_POINT('',(0.950009297011,1.)); -#12631 = CARTESIAN_POINT('',(0.983172198663,1.)); -#12632 = CARTESIAN_POINT('',(1.,1.)); -#12633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12634 = PCURVE('',#12119,#12635); -#12635 = DEFINITIONAL_REPRESENTATION('',(#12636),#12639); -#12636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12637,#12638),.UNSPECIFIED., +#15000 = CARTESIAN_POINT('',(0.E+000,1.)); +#15001 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#15002 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#15003 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#15004 = CARTESIAN_POINT('',(0.145724913075,1.)); +#15005 = CARTESIAN_POINT('',(0.192043637223,1.)); +#15006 = CARTESIAN_POINT('',(0.237526724423,1.)); +#15007 = CARTESIAN_POINT('',(0.282309422539,1.)); +#15008 = CARTESIAN_POINT('',(0.326519436214,1.)); +#15009 = CARTESIAN_POINT('',(0.370278310591,1.)); +#15010 = CARTESIAN_POINT('',(0.413702852292,1.)); +#15011 = CARTESIAN_POINT('',(0.456906394885,1.)); +#15012 = CARTESIAN_POINT('',(0.5,1.)); +#15013 = CARTESIAN_POINT('',(0.543093605115,1.)); +#15014 = CARTESIAN_POINT('',(0.586297147708,1.)); +#15015 = CARTESIAN_POINT('',(0.629721689409,1.)); +#15016 = CARTESIAN_POINT('',(0.673480563786,1.)); +#15017 = CARTESIAN_POINT('',(0.717690577461,1.)); +#15018 = CARTESIAN_POINT('',(0.762473275577,1.)); +#15019 = CARTESIAN_POINT('',(0.807956362777,1.)); +#15020 = CARTESIAN_POINT('',(0.854275086925,1.)); +#15021 = CARTESIAN_POINT('',(0.901574474096,1.)); +#15022 = CARTESIAN_POINT('',(0.950009297011,1.)); +#15023 = CARTESIAN_POINT('',(0.983172198663,1.)); +#15024 = CARTESIAN_POINT('',(1.,1.)); +#15025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15026 = PCURVE('',#14511,#15027); +#15027 = DEFINITIONAL_REPRESENTATION('',(#15028),#15031); +#15028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15029,#15030),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#12637 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#12638 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#12639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12640 = ORIENTED_EDGE('',*,*,#12641,.F.); -#12641 = EDGE_CURVE('',#12506,#12597,#12642,.T.); -#12642 = SURFACE_CURVE('',#12643,(#12648,#12677),.PCURVE_S1.); -#12643 = CIRCLE('',#12644,5.E-002); -#12644 = AXIS2_PLACEMENT_3D('',#12645,#12646,#12647); -#12645 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); -#12646 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); -#12647 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); -#12648 = PCURVE('',#12521,#12649); -#12649 = DEFINITIONAL_REPRESENTATION('',(#12650),#12676); -#12650 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12651,#12652,#12653,#12654, - #12655,#12656,#12657,#12658,#12659,#12660,#12661,#12662,#12663, - #12664,#12665,#12666,#12667,#12668,#12669,#12670,#12671,#12672, - #12673,#12674,#12675),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15029 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#15030 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#15031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15032 = ORIENTED_EDGE('',*,*,#15033,.F.); +#15033 = EDGE_CURVE('',#14898,#14989,#15034,.T.); +#15034 = SURFACE_CURVE('',#15035,(#15040,#15069),.PCURVE_S1.); +#15035 = CIRCLE('',#15036,5.E-002); +#15036 = AXIS2_PLACEMENT_3D('',#15037,#15038,#15039); +#15037 = CARTESIAN_POINT('',(-0.45,0.2,5.E-002)); +#15038 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); +#15039 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); +#15040 = PCURVE('',#14913,#15041); +#15041 = DEFINITIONAL_REPRESENTATION('',(#15042),#15068); +#15042 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15043,#15044,#15045,#15046, + #15047,#15048,#15049,#15050,#15051,#15052,#15053,#15054,#15055, + #15056,#15057,#15058,#15059,#15060,#15061,#15062,#15063,#15064, + #15065,#15066,#15067),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -15165,77 +18154,77 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#12651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12652 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#12653 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#12654 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#12655 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#12656 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#12657 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#12658 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#12659 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#12660 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#12661 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#12662 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#12663 = CARTESIAN_POINT('',(0.E+000,0.5)); -#12664 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#12665 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#12666 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#12667 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#12668 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#12669 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#12670 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#12671 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#12672 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#12673 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#12674 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#12675 = CARTESIAN_POINT('',(0.E+000,1.)); -#12676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15044 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#15045 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15046 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15047 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15048 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15049 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15050 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15051 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15052 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15053 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15054 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15055 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15056 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15057 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15058 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15059 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15060 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15061 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15062 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15063 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15064 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15065 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15066 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15067 = CARTESIAN_POINT('',(0.E+000,1.)); +#15068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15069 = PCURVE('',#15070,#15075); +#15070 = CYLINDRICAL_SURFACE('',#15071,5.E-002); +#15071 = AXIS2_PLACEMENT_3D('',#15072,#15073,#15074); +#15072 = CARTESIAN_POINT('',(-0.375,0.2,5.E-002)); +#15073 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); +#15074 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); +#15075 = DEFINITIONAL_REPRESENTATION('',(#15076),#15079); +#15076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15077,#15078),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#15077 = CARTESIAN_POINT('',(0.E+000,-7.5E-002)); +#15078 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); +#15079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12677 = PCURVE('',#12678,#12683); -#12678 = CYLINDRICAL_SURFACE('',#12679,5.E-002); -#12679 = AXIS2_PLACEMENT_3D('',#12680,#12681,#12682); -#12680 = CARTESIAN_POINT('',(-0.375,0.2,5.E-002)); -#12681 = DIRECTION('',(1.,1.641352236187E-030,-1.224646799147E-016)); -#12682 = DIRECTION('',(-1.224646799147E-016,-2.010076762319E-046,-1.)); -#12683 = DEFINITIONAL_REPRESENTATION('',(#12684),#12687); -#12684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12685,#12686),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#12685 = CARTESIAN_POINT('',(0.E+000,-7.5E-002)); -#12686 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); -#12687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12688 = ADVANCED_FACE('',(#12689),#12119,.T.); -#12689 = FACE_BOUND('',#12690,.T.); -#12690 = EDGE_LOOP('',(#12691,#12753,#12778,#12779)); -#12691 = ORIENTED_EDGE('',*,*,#12692,.F.); -#12692 = EDGE_CURVE('',#12693,#12079,#12695,.T.); -#12693 = VERTEX_POINT('',#12694); -#12694 = CARTESIAN_POINT('',(-0.45,0.25,0.55)); -#12695 = SURFACE_CURVE('',#12696,(#12701,#12707),.PCURVE_S1.); -#12696 = CIRCLE('',#12697,5.E-002); -#12697 = AXIS2_PLACEMENT_3D('',#12698,#12699,#12700); -#12698 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); -#12699 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12700 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12701 = PCURVE('',#12119,#12702); -#12702 = DEFINITIONAL_REPRESENTATION('',(#12703),#12706); -#12703 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12704,#12705),.UNSPECIFIED., +#15080 = ADVANCED_FACE('',(#15081),#14511,.T.); +#15081 = FACE_BOUND('',#15082,.T.); +#15082 = EDGE_LOOP('',(#15083,#15145,#15170,#15171)); +#15083 = ORIENTED_EDGE('',*,*,#15084,.F.); +#15084 = EDGE_CURVE('',#15085,#14471,#15087,.T.); +#15085 = VERTEX_POINT('',#15086); +#15086 = CARTESIAN_POINT('',(-0.45,0.25,0.55)); +#15087 = SURFACE_CURVE('',#15088,(#15093,#15099),.PCURVE_S1.); +#15088 = CIRCLE('',#15089,5.E-002); +#15089 = AXIS2_PLACEMENT_3D('',#15090,#15091,#15092); +#15090 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); +#15091 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15092 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15093 = PCURVE('',#14511,#15094); +#15094 = DEFINITIONAL_REPRESENTATION('',(#15095),#15098); +#15095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15096,#15097),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#12704 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#12705 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#12706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15096 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#15097 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#15098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12707 = PCURVE('',#12708,#12725); -#12708 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#12709,#12710,#12711,#12712) - ,(#12713,#12714,#12715,#12716) - ,(#12717,#12718,#12719,#12720) - ,(#12721,#12722,#12723,#12724 +#15099 = PCURVE('',#15100,#15117); +#15100 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#15101,#15102,#15103,#15104) + ,(#15105,#15106,#15107,#15108) + ,(#15109,#15110,#15111,#15112) + ,(#15113,#15114,#15115,#15116 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -15244,27 +18233,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#12709 = CARTESIAN_POINT('',(-0.45,0.25,0.55)); -#12710 = CARTESIAN_POINT('',(-0.45,0.25,0.579289321881)); -#12711 = CARTESIAN_POINT('',(-0.45,0.229289321881,0.6)); -#12712 = CARTESIAN_POINT('',(-0.45,0.2,0.6)); -#12713 = CARTESIAN_POINT('',(-0.479289321881,0.25,0.55)); -#12714 = CARTESIAN_POINT('',(-0.479289321881,0.25,0.579289321881)); -#12715 = CARTESIAN_POINT('',(-0.479289321881,0.229289321881,0.6)); -#12716 = CARTESIAN_POINT('',(-0.479289321881,0.2,0.6)); -#12717 = CARTESIAN_POINT('',(-0.5,0.229289321881,0.55)); -#12718 = CARTESIAN_POINT('',(-0.5,0.229289321881,0.567157287525)); -#12719 = CARTESIAN_POINT('',(-0.5,0.217157287525,0.579289321881)); -#12720 = CARTESIAN_POINT('',(-0.5,0.2,0.579289321881)); -#12721 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); -#12722 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); -#12723 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); -#12724 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); -#12725 = DEFINITIONAL_REPRESENTATION('',(#12726),#12752); -#12726 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12727,#12728,#12729,#12730, - #12731,#12732,#12733,#12734,#12735,#12736,#12737,#12738,#12739, - #12740,#12741,#12742,#12743,#12744,#12745,#12746,#12747,#12748, - #12749,#12750,#12751),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15101 = CARTESIAN_POINT('',(-0.45,0.25,0.55)); +#15102 = CARTESIAN_POINT('',(-0.45,0.25,0.579289321881)); +#15103 = CARTESIAN_POINT('',(-0.45,0.229289321881,0.6)); +#15104 = CARTESIAN_POINT('',(-0.45,0.2,0.6)); +#15105 = CARTESIAN_POINT('',(-0.479289321881,0.25,0.55)); +#15106 = CARTESIAN_POINT('',(-0.479289321881,0.25,0.579289321881)); +#15107 = CARTESIAN_POINT('',(-0.479289321881,0.229289321881,0.6)); +#15108 = CARTESIAN_POINT('',(-0.479289321881,0.2,0.6)); +#15109 = CARTESIAN_POINT('',(-0.5,0.229289321881,0.55)); +#15110 = CARTESIAN_POINT('',(-0.5,0.229289321881,0.567157287525)); +#15111 = CARTESIAN_POINT('',(-0.5,0.217157287525,0.579289321881)); +#15112 = CARTESIAN_POINT('',(-0.5,0.2,0.579289321881)); +#15113 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); +#15114 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); +#15115 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); +#15116 = CARTESIAN_POINT('',(-0.5,0.2,0.55)); +#15117 = DEFINITIONAL_REPRESENTATION('',(#15118),#15144); +#15118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15119,#15120,#15121,#15122, + #15123,#15124,#15125,#15126,#15127,#15128,#15129,#15130,#15131, + #15132,#15133,#15134,#15135,#15136,#15137,#15138,#15139,#15140, + #15141,#15142,#15143),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -15272,85 +18261,85 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#12727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12728 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#12729 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#12730 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#12731 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#12732 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#12733 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#12734 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#12735 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#12736 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#12737 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#12738 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#12739 = CARTESIAN_POINT('',(0.5,0.E+000)); -#12740 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#12741 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#12742 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#12743 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#12744 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#12745 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#12746 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#12747 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#12748 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#12749 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#12750 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#12751 = CARTESIAN_POINT('',(1.,0.E+000)); -#12752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12753 = ORIENTED_EDGE('',*,*,#12754,.F.); -#12754 = EDGE_CURVE('',#12597,#12693,#12755,.T.); -#12755 = SURFACE_CURVE('',#12756,(#12760,#12766),.PCURVE_S1.); -#12756 = LINE('',#12757,#12758); -#12757 = CARTESIAN_POINT('',(-0.45,0.25,0.3)); -#12758 = VECTOR('',#12759,1.); -#12759 = DIRECTION('',(4.259399095405E-061,-2.595054858731E-031,1.)); -#12760 = PCURVE('',#12119,#12761); -#12761 = DEFINITIONAL_REPRESENTATION('',(#12762),#12765); -#12762 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12763,#12764),.UNSPECIFIED., +#15119 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15120 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#15121 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#15122 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#15123 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#15124 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#15125 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#15126 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#15127 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#15128 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#15129 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#15130 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#15131 = CARTESIAN_POINT('',(0.5,0.E+000)); +#15132 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#15133 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#15134 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#15135 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#15136 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#15137 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#15138 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#15139 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#15140 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#15141 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#15142 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#15143 = CARTESIAN_POINT('',(1.,0.E+000)); +#15144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15145 = ORIENTED_EDGE('',*,*,#15146,.F.); +#15146 = EDGE_CURVE('',#14989,#15085,#15147,.T.); +#15147 = SURFACE_CURVE('',#15148,(#15152,#15158),.PCURVE_S1.); +#15148 = LINE('',#15149,#15150); +#15149 = CARTESIAN_POINT('',(-0.45,0.25,0.3)); +#15150 = VECTOR('',#15151,1.); +#15151 = DIRECTION('',(4.259399095405E-061,-2.595054858731E-031,1.)); +#15152 = PCURVE('',#14511,#15153); +#15153 = DEFINITIONAL_REPRESENTATION('',(#15154),#15157); +#15154 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15155,#15156),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#12763 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#12764 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#12765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12766 = PCURVE('',#12767,#12772); -#12767 = PLANE('',#12768); -#12768 = AXIS2_PLACEMENT_3D('',#12769,#12770,#12771); -#12769 = CARTESIAN_POINT('',(-0.375,0.25,0.3)); -#12770 = DIRECTION('',(-1.641352236187E-030,1.,2.595054858731E-031)); -#12771 = DIRECTION('',(-1.,-1.641352236187E-030,1.106509096121E-077)); -#12772 = DEFINITIONAL_REPRESENTATION('',(#12773),#12777); -#12773 = LINE('',#12774,#12775); -#12774 = CARTESIAN_POINT('',(7.5E-002,-3.194549321554E-062)); -#12775 = VECTOR('',#12776,1.); -#12776 = DIRECTION('',(6.908934844076E-077,1.)); -#12777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12778 = ORIENTED_EDGE('',*,*,#12596,.T.); -#12779 = ORIENTED_EDGE('',*,*,#12105,.T.); -#12780 = ADVANCED_FACE('',(#12781),#12708,.T.); -#12781 = FACE_BOUND('',#12782,.T.); -#12782 = EDGE_LOOP('',(#12783,#12828,#12876)); -#12783 = ORIENTED_EDGE('',*,*,#12784,.F.); -#12784 = EDGE_CURVE('',#12785,#12079,#12787,.T.); -#12785 = VERTEX_POINT('',#12786); -#12786 = CARTESIAN_POINT('',(-0.45,0.2,0.6)); -#12787 = SURFACE_CURVE('',#12788,(#12793,#12822),.PCURVE_S1.); -#12788 = CIRCLE('',#12789,5.E-002); -#12789 = AXIS2_PLACEMENT_3D('',#12790,#12791,#12792); -#12790 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); -#12791 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#12792 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12793 = PCURVE('',#12708,#12794); -#12794 = DEFINITIONAL_REPRESENTATION('',(#12795),#12821); -#12795 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12796,#12797,#12798,#12799, - #12800,#12801,#12802,#12803,#12804,#12805,#12806,#12807,#12808, - #12809,#12810,#12811,#12812,#12813,#12814,#12815,#12816,#12817, - #12818,#12819,#12820),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15155 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#15156 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#15157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15158 = PCURVE('',#15159,#15164); +#15159 = PLANE('',#15160); +#15160 = AXIS2_PLACEMENT_3D('',#15161,#15162,#15163); +#15161 = CARTESIAN_POINT('',(-0.375,0.25,0.3)); +#15162 = DIRECTION('',(-1.641352236187E-030,1.,2.595054858731E-031)); +#15163 = DIRECTION('',(-1.,-1.641352236187E-030,1.106509096121E-077)); +#15164 = DEFINITIONAL_REPRESENTATION('',(#15165),#15169); +#15165 = LINE('',#15166,#15167); +#15166 = CARTESIAN_POINT('',(7.5E-002,-3.194549321554E-062)); +#15167 = VECTOR('',#15168,1.); +#15168 = DIRECTION('',(6.908934844076E-077,1.)); +#15169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15170 = ORIENTED_EDGE('',*,*,#14988,.T.); +#15171 = ORIENTED_EDGE('',*,*,#14497,.T.); +#15172 = ADVANCED_FACE('',(#15173),#15100,.T.); +#15173 = FACE_BOUND('',#15174,.T.); +#15174 = EDGE_LOOP('',(#15175,#15220,#15268)); +#15175 = ORIENTED_EDGE('',*,*,#15176,.F.); +#15176 = EDGE_CURVE('',#15177,#14471,#15179,.T.); +#15177 = VERTEX_POINT('',#15178); +#15178 = CARTESIAN_POINT('',(-0.45,0.2,0.6)); +#15179 = SURFACE_CURVE('',#15180,(#15185,#15214),.PCURVE_S1.); +#15180 = CIRCLE('',#15181,5.E-002); +#15181 = AXIS2_PLACEMENT_3D('',#15182,#15183,#15184); +#15182 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); +#15183 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#15184 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15185 = PCURVE('',#15100,#15186); +#15186 = DEFINITIONAL_REPRESENTATION('',(#15187),#15213); +#15187 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15188,#15189,#15190,#15191, + #15192,#15193,#15194,#15195,#15196,#15197,#15198,#15199,#15200, + #15201,#15202,#15203,#15204,#15205,#15206,#15207,#15208,#15209, + #15210,#15211,#15212),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -15358,57 +18347,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#12796 = CARTESIAN_POINT('',(0.E+000,1.)); -#12797 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#12798 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#12799 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#12800 = CARTESIAN_POINT('',(0.145724913075,1.)); -#12801 = CARTESIAN_POINT('',(0.192043637223,1.)); -#12802 = CARTESIAN_POINT('',(0.237526724423,1.)); -#12803 = CARTESIAN_POINT('',(0.282309422539,1.)); -#12804 = CARTESIAN_POINT('',(0.326519436214,1.)); -#12805 = CARTESIAN_POINT('',(0.370278310591,1.)); -#12806 = CARTESIAN_POINT('',(0.413702852292,1.)); -#12807 = CARTESIAN_POINT('',(0.456906394885,1.)); -#12808 = CARTESIAN_POINT('',(0.5,1.)); -#12809 = CARTESIAN_POINT('',(0.543093605115,1.)); -#12810 = CARTESIAN_POINT('',(0.586297147708,1.)); -#12811 = CARTESIAN_POINT('',(0.629721689409,1.)); -#12812 = CARTESIAN_POINT('',(0.673480563786,1.)); -#12813 = CARTESIAN_POINT('',(0.717690577461,1.)); -#12814 = CARTESIAN_POINT('',(0.762473275577,1.)); -#12815 = CARTESIAN_POINT('',(0.807956362777,1.)); -#12816 = CARTESIAN_POINT('',(0.854275086925,1.)); -#12817 = CARTESIAN_POINT('',(0.901574474096,1.)); -#12818 = CARTESIAN_POINT('',(0.950009297011,1.)); -#12819 = CARTESIAN_POINT('',(0.983172198663,1.)); -#12820 = CARTESIAN_POINT('',(1.,1.)); -#12821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12822 = PCURVE('',#12094,#12823); -#12823 = DEFINITIONAL_REPRESENTATION('',(#12824),#12827); -#12824 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12825,#12826),.UNSPECIFIED., +#15188 = CARTESIAN_POINT('',(0.E+000,1.)); +#15189 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#15190 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#15191 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#15192 = CARTESIAN_POINT('',(0.145724913075,1.)); +#15193 = CARTESIAN_POINT('',(0.192043637223,1.)); +#15194 = CARTESIAN_POINT('',(0.237526724423,1.)); +#15195 = CARTESIAN_POINT('',(0.282309422539,1.)); +#15196 = CARTESIAN_POINT('',(0.326519436214,1.)); +#15197 = CARTESIAN_POINT('',(0.370278310591,1.)); +#15198 = CARTESIAN_POINT('',(0.413702852292,1.)); +#15199 = CARTESIAN_POINT('',(0.456906394885,1.)); +#15200 = CARTESIAN_POINT('',(0.5,1.)); +#15201 = CARTESIAN_POINT('',(0.543093605115,1.)); +#15202 = CARTESIAN_POINT('',(0.586297147708,1.)); +#15203 = CARTESIAN_POINT('',(0.629721689409,1.)); +#15204 = CARTESIAN_POINT('',(0.673480563786,1.)); +#15205 = CARTESIAN_POINT('',(0.717690577461,1.)); +#15206 = CARTESIAN_POINT('',(0.762473275577,1.)); +#15207 = CARTESIAN_POINT('',(0.807956362777,1.)); +#15208 = CARTESIAN_POINT('',(0.854275086925,1.)); +#15209 = CARTESIAN_POINT('',(0.901574474096,1.)); +#15210 = CARTESIAN_POINT('',(0.950009297011,1.)); +#15211 = CARTESIAN_POINT('',(0.983172198663,1.)); +#15212 = CARTESIAN_POINT('',(1.,1.)); +#15213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15214 = PCURVE('',#14486,#15215); +#15215 = DEFINITIONAL_REPRESENTATION('',(#15216),#15219); +#15216 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15217,#15218),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#12825 = CARTESIAN_POINT('',(6.28318530718,0.45)); -#12826 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#12827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12828 = ORIENTED_EDGE('',*,*,#12829,.F.); -#12829 = EDGE_CURVE('',#12693,#12785,#12830,.T.); -#12830 = SURFACE_CURVE('',#12831,(#12836,#12865),.PCURVE_S1.); -#12831 = CIRCLE('',#12832,5.E-002); -#12832 = AXIS2_PLACEMENT_3D('',#12833,#12834,#12835); -#12833 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); -#12834 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); -#12835 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); -#12836 = PCURVE('',#12708,#12837); -#12837 = DEFINITIONAL_REPRESENTATION('',(#12838),#12864); -#12838 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12839,#12840,#12841,#12842, - #12843,#12844,#12845,#12846,#12847,#12848,#12849,#12850,#12851, - #12852,#12853,#12854,#12855,#12856,#12857,#12858,#12859,#12860, - #12861,#12862,#12863),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15217 = CARTESIAN_POINT('',(6.28318530718,0.45)); +#15218 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#15219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15220 = ORIENTED_EDGE('',*,*,#15221,.F.); +#15221 = EDGE_CURVE('',#15085,#15177,#15222,.T.); +#15222 = SURFACE_CURVE('',#15223,(#15228,#15257),.PCURVE_S1.); +#15223 = CIRCLE('',#15224,5.E-002); +#15224 = AXIS2_PLACEMENT_3D('',#15225,#15226,#15227); +#15225 = CARTESIAN_POINT('',(-0.45,0.2,0.55)); +#15226 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); +#15227 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); +#15228 = PCURVE('',#15100,#15229); +#15229 = DEFINITIONAL_REPRESENTATION('',(#15230),#15256); +#15230 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15231,#15232,#15233,#15234, + #15235,#15236,#15237,#15238,#15239,#15240,#15241,#15242,#15243, + #15244,#15245,#15246,#15247,#15248,#15249,#15250,#15251,#15252, + #15253,#15254,#15255),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -15416,143 +18405,143 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#12839 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12840 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); -#12841 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#12842 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#12843 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#12844 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#12845 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#12846 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#12847 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#12848 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#12849 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#12850 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#12851 = CARTESIAN_POINT('',(0.E+000,0.5)); -#12852 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#12853 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#12854 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#12855 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#12856 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#12857 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#12858 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#12859 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#12860 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#12861 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#12862 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#12863 = CARTESIAN_POINT('',(0.E+000,1.)); -#12864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12865 = PCURVE('',#12866,#12871); -#12866 = CYLINDRICAL_SURFACE('',#12867,5.E-002); -#12867 = AXIS2_PLACEMENT_3D('',#12868,#12869,#12870); -#12868 = CARTESIAN_POINT('',(-0.375,0.2,0.55)); -#12869 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); -#12870 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); -#12871 = DEFINITIONAL_REPRESENTATION('',(#12872),#12875); -#12872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12873,#12874),.UNSPECIFIED., +#15231 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15232 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); +#15233 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15234 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15235 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15236 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15237 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15238 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15239 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15240 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15241 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15242 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15243 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15244 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15245 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15246 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15247 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15248 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15249 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15250 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15251 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15252 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15253 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15254 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15255 = CARTESIAN_POINT('',(0.E+000,1.)); +#15256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15257 = PCURVE('',#15258,#15263); +#15258 = CYLINDRICAL_SURFACE('',#15259,5.E-002); +#15259 = AXIS2_PLACEMENT_3D('',#15260,#15261,#15262); +#15260 = CARTESIAN_POINT('',(-0.375,0.2,0.55)); +#15261 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); +#15262 = DIRECTION('',(1.641352236187E-030,-1.,0.E+000)); +#15263 = DEFINITIONAL_REPRESENTATION('',(#15264),#15267); +#15264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15265,#15266),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#12873 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); -#12874 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#12875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12876 = ORIENTED_EDGE('',*,*,#12692,.T.); -#12877 = ADVANCED_FACE('',(#12878),#12094,.T.); -#12878 = FACE_BOUND('',#12879,.T.); -#12879 = EDGE_LOOP('',(#12880,#12881,#12906,#12907)); -#12880 = ORIENTED_EDGE('',*,*,#12202,.T.); -#12881 = ORIENTED_EDGE('',*,*,#12882,.F.); -#12882 = EDGE_CURVE('',#12785,#12134,#12883,.T.); -#12883 = SURFACE_CURVE('',#12884,(#12888,#12894),.PCURVE_S1.); -#12884 = LINE('',#12885,#12886); -#12885 = CARTESIAN_POINT('',(-0.45,-0.25,0.6)); -#12886 = VECTOR('',#12887,1.); -#12887 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#12888 = PCURVE('',#12094,#12889); -#12889 = DEFINITIONAL_REPRESENTATION('',(#12890),#12893); -#12890 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12891,#12892),.UNSPECIFIED., +#15265 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); +#15266 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#15267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15268 = ORIENTED_EDGE('',*,*,#15084,.T.); +#15269 = ADVANCED_FACE('',(#15270),#14486,.T.); +#15270 = FACE_BOUND('',#15271,.T.); +#15271 = EDGE_LOOP('',(#15272,#15273,#15298,#15299)); +#15272 = ORIENTED_EDGE('',*,*,#14594,.T.); +#15273 = ORIENTED_EDGE('',*,*,#15274,.F.); +#15274 = EDGE_CURVE('',#15177,#14526,#15275,.T.); +#15275 = SURFACE_CURVE('',#15276,(#15280,#15286),.PCURVE_S1.); +#15276 = LINE('',#15277,#15278); +#15277 = CARTESIAN_POINT('',(-0.45,-0.25,0.6)); +#15278 = VECTOR('',#15279,1.); +#15279 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#15280 = PCURVE('',#14486,#15281); +#15281 = DEFINITIONAL_REPRESENTATION('',(#15282),#15285); +#15282 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15283,#15284),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#12891 = CARTESIAN_POINT('',(6.28318530718,0.45)); -#12892 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#12893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12894 = PCURVE('',#12895,#12900); -#12895 = PLANE('',#12896); -#12896 = AXIS2_PLACEMENT_3D('',#12897,#12898,#12899); -#12897 = CARTESIAN_POINT('',(-0.375,-0.25,0.6)); -#12898 = DIRECTION('',(0.E+000,0.E+000,1.)); -#12899 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12900 = DEFINITIONAL_REPRESENTATION('',(#12901),#12905); -#12901 = LINE('',#12902,#12903); -#12902 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); -#12903 = VECTOR('',#12904,1.); -#12904 = DIRECTION('',(0.E+000,-1.)); -#12905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12906 = ORIENTED_EDGE('',*,*,#12784,.T.); -#12907 = ORIENTED_EDGE('',*,*,#12078,.T.); -#12908 = ADVANCED_FACE('',(#12909),#12191,.T.); -#12909 = FACE_BOUND('',#12910,.T.); -#12910 = EDGE_LOOP('',(#12911,#12912,#12934,#12996)); -#12911 = ORIENTED_EDGE('',*,*,#12133,.T.); -#12912 = ORIENTED_EDGE('',*,*,#12913,.T.); -#12913 = EDGE_CURVE('',#12136,#12914,#12916,.T.); -#12914 = VERTEX_POINT('',#12915); -#12915 = CARTESIAN_POINT('',(-0.26,-0.25,0.55)); -#12916 = SURFACE_CURVE('',#12917,(#12921,#12927),.PCURVE_S1.); -#12917 = LINE('',#12918,#12919); -#12918 = CARTESIAN_POINT('',(-0.375,-0.25,0.55)); -#12919 = VECTOR('',#12920,1.); -#12920 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); -#12921 = PCURVE('',#12191,#12922); -#12922 = DEFINITIONAL_REPRESENTATION('',(#12923),#12926); -#12923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12924,#12925),.UNSPECIFIED., +#15283 = CARTESIAN_POINT('',(6.28318530718,0.45)); +#15284 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#15285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15286 = PCURVE('',#15287,#15292); +#15287 = PLANE('',#15288); +#15288 = AXIS2_PLACEMENT_3D('',#15289,#15290,#15291); +#15289 = CARTESIAN_POINT('',(-0.375,-0.25,0.6)); +#15290 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15291 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15292 = DEFINITIONAL_REPRESENTATION('',(#15293),#15297); +#15293 = LINE('',#15294,#15295); +#15294 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); +#15295 = VECTOR('',#15296,1.); +#15296 = DIRECTION('',(0.E+000,-1.)); +#15297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15298 = ORIENTED_EDGE('',*,*,#15176,.T.); +#15299 = ORIENTED_EDGE('',*,*,#14470,.T.); +#15300 = ADVANCED_FACE('',(#15301),#14583,.T.); +#15301 = FACE_BOUND('',#15302,.T.); +#15302 = EDGE_LOOP('',(#15303,#15304,#15326,#15388)); +#15303 = ORIENTED_EDGE('',*,*,#14525,.T.); +#15304 = ORIENTED_EDGE('',*,*,#15305,.T.); +#15305 = EDGE_CURVE('',#14528,#15306,#15308,.T.); +#15306 = VERTEX_POINT('',#15307); +#15307 = CARTESIAN_POINT('',(-0.26,-0.25,0.55)); +#15308 = SURFACE_CURVE('',#15309,(#15313,#15319),.PCURVE_S1.); +#15309 = LINE('',#15310,#15311); +#15310 = CARTESIAN_POINT('',(-0.375,-0.25,0.55)); +#15311 = VECTOR('',#15312,1.); +#15312 = DIRECTION('',(1.,1.641352236187E-030,0.E+000)); +#15313 = PCURVE('',#14583,#15314); +#15314 = DEFINITIONAL_REPRESENTATION('',(#15315),#15318); +#15315 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15316,#15317),.UNSPECIFIED., .F.,.F.,(2,2),(-7.5E-002,0.115),.PIECEWISE_BEZIER_KNOTS.); -#12924 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); -#12925 = CARTESIAN_POINT('',(0.E+000,-0.115)); -#12926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12927 = PCURVE('',#12391,#12928); -#12928 = DEFINITIONAL_REPRESENTATION('',(#12929),#12933); -#12929 = LINE('',#12930,#12931); -#12930 = CARTESIAN_POINT('',(2.766272740304E-078,0.25)); -#12931 = VECTOR('',#12932,1.); -#12932 = DIRECTION('',(-1.,1.106509096121E-077)); -#12933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12934 = ORIENTED_EDGE('',*,*,#12935,.F.); -#12935 = EDGE_CURVE('',#12936,#12914,#12938,.T.); -#12936 = VERTEX_POINT('',#12937); -#12937 = CARTESIAN_POINT('',(-0.26,-0.2,0.6)); -#12938 = SURFACE_CURVE('',#12939,(#12944,#12950),.PCURVE_S1.); -#12939 = CIRCLE('',#12940,5.E-002); -#12940 = AXIS2_PLACEMENT_3D('',#12941,#12942,#12943); -#12941 = CARTESIAN_POINT('',(-0.26,-0.2,0.55)); -#12942 = DIRECTION('',(1.,0.E+000,0.E+000)); -#12943 = DIRECTION('',(0.E+000,1.,0.E+000)); -#12944 = PCURVE('',#12191,#12945); -#12945 = DEFINITIONAL_REPRESENTATION('',(#12946),#12949); -#12946 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#12947,#12948),.UNSPECIFIED., +#15316 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); +#15317 = CARTESIAN_POINT('',(0.E+000,-0.115)); +#15318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15319 = PCURVE('',#14783,#15320); +#15320 = DEFINITIONAL_REPRESENTATION('',(#15321),#15325); +#15321 = LINE('',#15322,#15323); +#15322 = CARTESIAN_POINT('',(2.766272740304E-078,0.25)); +#15323 = VECTOR('',#15324,1.); +#15324 = DIRECTION('',(-1.,1.106509096121E-077)); +#15325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15326 = ORIENTED_EDGE('',*,*,#15327,.F.); +#15327 = EDGE_CURVE('',#15328,#15306,#15330,.T.); +#15328 = VERTEX_POINT('',#15329); +#15329 = CARTESIAN_POINT('',(-0.26,-0.2,0.6)); +#15330 = SURFACE_CURVE('',#15331,(#15336,#15342),.PCURVE_S1.); +#15331 = CIRCLE('',#15332,5.E-002); +#15332 = AXIS2_PLACEMENT_3D('',#15333,#15334,#15335); +#15333 = CARTESIAN_POINT('',(-0.26,-0.2,0.55)); +#15334 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15335 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15336 = PCURVE('',#14583,#15337); +#15337 = DEFINITIONAL_REPRESENTATION('',(#15338),#15341); +#15338 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15339,#15340),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#12947 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#12948 = CARTESIAN_POINT('',(0.E+000,-0.115)); -#12949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15339 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#15340 = CARTESIAN_POINT('',(0.E+000,-0.115)); +#15341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#12950 = PCURVE('',#12951,#12968); -#12951 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#12952,#12953,#12954,#12955) - ,(#12956,#12957,#12958,#12959) - ,(#12960,#12961,#12962,#12963) - ,(#12964,#12965,#12966,#12967 +#15342 = PCURVE('',#15343,#15360); +#15343 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#15344,#15345,#15346,#15347) + ,(#15348,#15349,#15350,#15351) + ,(#15352,#15353,#15354,#15355) + ,(#15356,#15357,#15358,#15359 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -15561,27 +18550,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#12952 = CARTESIAN_POINT('',(-0.26,-0.25,0.55)); -#12953 = CARTESIAN_POINT('',(-0.26,-0.25,0.579289321881)); -#12954 = CARTESIAN_POINT('',(-0.26,-0.229289321881,0.6)); -#12955 = CARTESIAN_POINT('',(-0.26,-0.2,0.6)); -#12956 = CARTESIAN_POINT('',(-0.254142135624,-0.25,0.55)); -#12957 = CARTESIAN_POINT('',(-0.254142135624,-0.25,0.579289321881)); -#12958 = CARTESIAN_POINT('',(-0.254142135624,-0.229289321881,0.6)); -#12959 = CARTESIAN_POINT('',(-0.254142135624,-0.2,0.6)); -#12960 = CARTESIAN_POINT('',(-0.25,-0.245857864376,0.55)); -#12961 = CARTESIAN_POINT('',(-0.25,-0.245857864376,0.57686291501)); -#12962 = CARTESIAN_POINT('',(-0.25,-0.22686291501,0.595857864376)); -#12963 = CARTESIAN_POINT('',(-0.25,-0.2,0.595857864376)); -#12964 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); -#12965 = CARTESIAN_POINT('',(-0.25,-0.24,0.573431457505)); -#12966 = CARTESIAN_POINT('',(-0.25,-0.223431457505,0.59)); -#12967 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); -#12968 = DEFINITIONAL_REPRESENTATION('',(#12969),#12995); -#12969 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#12970,#12971,#12972,#12973, - #12974,#12975,#12976,#12977,#12978,#12979,#12980,#12981,#12982, - #12983,#12984,#12985,#12986,#12987,#12988,#12989,#12990,#12991, - #12992,#12993,#12994),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15344 = CARTESIAN_POINT('',(-0.26,-0.25,0.55)); +#15345 = CARTESIAN_POINT('',(-0.26,-0.25,0.579289321881)); +#15346 = CARTESIAN_POINT('',(-0.26,-0.229289321881,0.6)); +#15347 = CARTESIAN_POINT('',(-0.26,-0.2,0.6)); +#15348 = CARTESIAN_POINT('',(-0.254142135624,-0.25,0.55)); +#15349 = CARTESIAN_POINT('',(-0.254142135624,-0.25,0.579289321881)); +#15350 = CARTESIAN_POINT('',(-0.254142135624,-0.229289321881,0.6)); +#15351 = CARTESIAN_POINT('',(-0.254142135624,-0.2,0.6)); +#15352 = CARTESIAN_POINT('',(-0.25,-0.245857864376,0.55)); +#15353 = CARTESIAN_POINT('',(-0.25,-0.245857864376,0.57686291501)); +#15354 = CARTESIAN_POINT('',(-0.25,-0.22686291501,0.595857864376)); +#15355 = CARTESIAN_POINT('',(-0.25,-0.2,0.595857864376)); +#15356 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); +#15357 = CARTESIAN_POINT('',(-0.25,-0.24,0.573431457505)); +#15358 = CARTESIAN_POINT('',(-0.25,-0.223431457505,0.59)); +#15359 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); +#15360 = DEFINITIONAL_REPRESENTATION('',(#15361),#15387); +#15361 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15362,#15363,#15364,#15365, + #15366,#15367,#15368,#15369,#15370,#15371,#15372,#15373,#15374, + #15375,#15376,#15377,#15378,#15379,#15380,#15381,#15382,#15383, + #15384,#15385,#15386),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -15589,176 +18578,176 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#12970 = CARTESIAN_POINT('',(0.E+000,1.)); -#12971 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#12972 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#12973 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#12974 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#12975 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#12976 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#12977 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#12978 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#12979 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#12980 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#12981 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#12982 = CARTESIAN_POINT('',(0.E+000,0.5)); -#12983 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#12984 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#12985 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#12986 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#12987 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#12988 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#12989 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#12990 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#12991 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#12992 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#12993 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#12994 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#12995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#12996 = ORIENTED_EDGE('',*,*,#12997,.F.); -#12997 = EDGE_CURVE('',#12134,#12936,#12998,.T.); -#12998 = SURFACE_CURVE('',#12999,(#13003,#13009),.PCURVE_S1.); -#12999 = LINE('',#13000,#13001); -#13000 = CARTESIAN_POINT('',(-0.375,-0.2,0.6)); -#13001 = VECTOR('',#13002,1.); -#13002 = DIRECTION('',(1.,0.E+000,0.E+000)); -#13003 = PCURVE('',#12191,#13004); -#13004 = DEFINITIONAL_REPRESENTATION('',(#13005),#13008); -#13005 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13006,#13007),.UNSPECIFIED., +#15362 = CARTESIAN_POINT('',(0.E+000,1.)); +#15363 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15364 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15365 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15366 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15367 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15368 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15369 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15370 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15371 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15372 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15373 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15374 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15375 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15376 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15377 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15378 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15379 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15380 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15381 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15382 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15383 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15384 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15385 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#15386 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15388 = ORIENTED_EDGE('',*,*,#15389,.F.); +#15389 = EDGE_CURVE('',#14526,#15328,#15390,.T.); +#15390 = SURFACE_CURVE('',#15391,(#15395,#15401),.PCURVE_S1.); +#15391 = LINE('',#15392,#15393); +#15392 = CARTESIAN_POINT('',(-0.375,-0.2,0.6)); +#15393 = VECTOR('',#15394,1.); +#15394 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15395 = PCURVE('',#14583,#15396); +#15396 = DEFINITIONAL_REPRESENTATION('',(#15397),#15400); +#15397 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15398,#15399),.UNSPECIFIED., .F.,.F.,(2,2),(-7.5E-002,0.115),.PIECEWISE_BEZIER_KNOTS.); -#13006 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#13007 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#13008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13009 = PCURVE('',#12895,#13010); -#13010 = DEFINITIONAL_REPRESENTATION('',(#13011),#13015); -#13011 = LINE('',#13012,#13013); -#13012 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#13013 = VECTOR('',#13014,1.); -#13014 = DIRECTION('',(1.,0.E+000)); -#13015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13016 = ADVANCED_FACE('',(#13017),#12391,.F.); -#13017 = FACE_BOUND('',#13018,.T.); -#13018 = EDGE_LOOP('',(#13019,#13020,#13021,#13043)); -#13019 = ORIENTED_EDGE('',*,*,#12913,.F.); -#13020 = ORIENTED_EDGE('',*,*,#12378,.F.); -#13021 = ORIENTED_EDGE('',*,*,#13022,.F.); -#13022 = EDGE_CURVE('',#13023,#12294,#13025,.T.); -#13023 = VERTEX_POINT('',#13024); -#13024 = CARTESIAN_POINT('',(-0.26,-0.25,5.E-002)); -#13025 = SURFACE_CURVE('',#13026,(#13030,#13037),.PCURVE_S1.); -#13026 = LINE('',#13027,#13028); -#13027 = CARTESIAN_POINT('',(-0.375,-0.25,5.E-002)); -#13028 = VECTOR('',#13029,1.); -#13029 = DIRECTION('',(-1.,-1.641352236187E-030,1.224646799147E-016)); -#13030 = PCURVE('',#12391,#13031); -#13031 = DEFINITIONAL_REPRESENTATION('',(#13032),#13036); -#13032 = LINE('',#13033,#13034); -#13033 = CARTESIAN_POINT('',(-2.766272740304E-078,-0.25)); -#13034 = VECTOR('',#13035,1.); -#13035 = DIRECTION('',(1.,1.224646799147E-016)); -#13036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13037 = PCURVE('',#12489,#13038); -#13038 = DEFINITIONAL_REPRESENTATION('',(#13039),#13042); -#13039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13040,#13041),.UNSPECIFIED., +#15398 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#15399 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#15400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15401 = PCURVE('',#15287,#15402); +#15402 = DEFINITIONAL_REPRESENTATION('',(#15403),#15407); +#15403 = LINE('',#15404,#15405); +#15404 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#15405 = VECTOR('',#15406,1.); +#15406 = DIRECTION('',(1.,0.E+000)); +#15407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15408 = ADVANCED_FACE('',(#15409),#14783,.F.); +#15409 = FACE_BOUND('',#15410,.T.); +#15410 = EDGE_LOOP('',(#15411,#15412,#15413,#15435)); +#15411 = ORIENTED_EDGE('',*,*,#15305,.F.); +#15412 = ORIENTED_EDGE('',*,*,#14770,.F.); +#15413 = ORIENTED_EDGE('',*,*,#15414,.F.); +#15414 = EDGE_CURVE('',#15415,#14686,#15417,.T.); +#15415 = VERTEX_POINT('',#15416); +#15416 = CARTESIAN_POINT('',(-0.26,-0.25,5.E-002)); +#15417 = SURFACE_CURVE('',#15418,(#15422,#15429),.PCURVE_S1.); +#15418 = LINE('',#15419,#15420); +#15419 = CARTESIAN_POINT('',(-0.375,-0.25,5.E-002)); +#15420 = VECTOR('',#15421,1.); +#15421 = DIRECTION('',(-1.,-1.641352236187E-030,1.224646799147E-016)); +#15422 = PCURVE('',#14783,#15423); +#15423 = DEFINITIONAL_REPRESENTATION('',(#15424),#15428); +#15424 = LINE('',#15425,#15426); +#15425 = CARTESIAN_POINT('',(-2.766272740304E-078,-0.25)); +#15426 = VECTOR('',#15427,1.); +#15427 = DIRECTION('',(1.,1.224646799147E-016)); +#15428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15429 = PCURVE('',#14881,#15430); +#15430 = DEFINITIONAL_REPRESENTATION('',(#15431),#15434); +#15431 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15432,#15433),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#13040 = CARTESIAN_POINT('',(4.712388980385,0.115)); -#13041 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); -#13042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13043 = ORIENTED_EDGE('',*,*,#13044,.F.); -#13044 = EDGE_CURVE('',#12914,#13023,#13045,.T.); -#13045 = SURFACE_CURVE('',#13046,(#13050,#13057),.PCURVE_S1.); -#13046 = LINE('',#13047,#13048); -#13047 = CARTESIAN_POINT('',(-0.26,-0.25,0.3)); -#13048 = VECTOR('',#13049,1.); -#13049 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#13050 = PCURVE('',#12391,#13051); -#13051 = DEFINITIONAL_REPRESENTATION('',(#13052),#13056); -#13052 = LINE('',#13053,#13054); -#13053 = CARTESIAN_POINT('',(-0.115,4.898308959716E-062)); -#13054 = VECTOR('',#13055,1.); -#13055 = DIRECTION('',(-4.259399095405E-061,-1.)); -#13056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13057 = PCURVE('',#13058,#13063); -#13058 = CYLINDRICAL_SURFACE('',#13059,1.E-002); -#13059 = AXIS2_PLACEMENT_3D('',#13060,#13061,#13062); -#13060 = CARTESIAN_POINT('',(-0.26,-0.24,0.3)); -#13061 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#13062 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); -#13063 = DEFINITIONAL_REPRESENTATION('',(#13064),#13067); -#13064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13065,#13066),.UNSPECIFIED., +#15432 = CARTESIAN_POINT('',(4.712388980385,0.115)); +#15433 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); +#15434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15435 = ORIENTED_EDGE('',*,*,#15436,.F.); +#15436 = EDGE_CURVE('',#15306,#15415,#15437,.T.); +#15437 = SURFACE_CURVE('',#15438,(#15442,#15449),.PCURVE_S1.); +#15438 = LINE('',#15439,#15440); +#15439 = CARTESIAN_POINT('',(-0.26,-0.25,0.3)); +#15440 = VECTOR('',#15441,1.); +#15441 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#15442 = PCURVE('',#14783,#15443); +#15443 = DEFINITIONAL_REPRESENTATION('',(#15444),#15448); +#15444 = LINE('',#15445,#15446); +#15445 = CARTESIAN_POINT('',(-0.115,4.898308959716E-062)); +#15446 = VECTOR('',#15447,1.); +#15447 = DIRECTION('',(-4.259399095405E-061,-1.)); +#15448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15449 = PCURVE('',#15450,#15455); +#15450 = CYLINDRICAL_SURFACE('',#15451,1.E-002); +#15451 = AXIS2_PLACEMENT_3D('',#15452,#15453,#15454); +#15452 = CARTESIAN_POINT('',(-0.26,-0.24,0.3)); +#15453 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#15454 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); +#15455 = DEFINITIONAL_REPRESENTATION('',(#15456),#15459); +#15456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15457,#15458),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#13065 = CARTESIAN_POINT('',(0.E+000,0.25)); -#13066 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#13067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13068 = ADVANCED_FACE('',(#13069),#12489,.T.); -#13069 = FACE_BOUND('',#13070,.T.); -#13070 = EDGE_LOOP('',(#13071,#13072,#13094,#13154)); -#13071 = ORIENTED_EDGE('',*,*,#12452,.T.); -#13072 = ORIENTED_EDGE('',*,*,#13073,.F.); -#13073 = EDGE_CURVE('',#13074,#12408,#13076,.T.); -#13074 = VERTEX_POINT('',#13075); -#13075 = CARTESIAN_POINT('',(-0.26,-0.2,2.000227594295E-018)); -#13076 = SURFACE_CURVE('',#13077,(#13081,#13087),.PCURVE_S1.); -#13077 = LINE('',#13078,#13079); -#13078 = CARTESIAN_POINT('',(-0.375,-0.2,1.530808498934E-017)); -#13079 = VECTOR('',#13080,1.); -#13080 = DIRECTION('',(-1.,0.E+000,1.224646799147E-016)); -#13081 = PCURVE('',#12489,#13082); -#13082 = DEFINITIONAL_REPRESENTATION('',(#13083),#13086); -#13083 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13084,#13085),.UNSPECIFIED., +#15457 = CARTESIAN_POINT('',(0.E+000,0.25)); +#15458 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#15459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15460 = ADVANCED_FACE('',(#15461),#14881,.T.); +#15461 = FACE_BOUND('',#15462,.T.); +#15462 = EDGE_LOOP('',(#15463,#15464,#15486,#15546)); +#15463 = ORIENTED_EDGE('',*,*,#14844,.T.); +#15464 = ORIENTED_EDGE('',*,*,#15465,.F.); +#15465 = EDGE_CURVE('',#15466,#14800,#15468,.T.); +#15466 = VERTEX_POINT('',#15467); +#15467 = CARTESIAN_POINT('',(-0.26,-0.2,2.000227594295E-018)); +#15468 = SURFACE_CURVE('',#15469,(#15473,#15479),.PCURVE_S1.); +#15469 = LINE('',#15470,#15471); +#15470 = CARTESIAN_POINT('',(-0.375,-0.2,1.530808498934E-017)); +#15471 = VECTOR('',#15472,1.); +#15472 = DIRECTION('',(-1.,0.E+000,1.224646799147E-016)); +#15473 = PCURVE('',#14881,#15474); +#15474 = DEFINITIONAL_REPRESENTATION('',(#15475),#15478); +#15475 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15476,#15477),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#13084 = CARTESIAN_POINT('',(6.28318530718,0.115)); -#13085 = CARTESIAN_POINT('',(6.28318530718,-7.5E-002)); -#13086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13087 = PCURVE('',#12580,#13088); -#13088 = DEFINITIONAL_REPRESENTATION('',(#13089),#13093); -#13089 = LINE('',#13090,#13091); -#13090 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#13091 = VECTOR('',#13092,1.); -#13092 = DIRECTION('',(1.,0.E+000)); -#13093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13094 = ORIENTED_EDGE('',*,*,#13095,.F.); -#13095 = EDGE_CURVE('',#13023,#13074,#13096,.T.); -#13096 = SURFACE_CURVE('',#13097,(#13102,#13108),.PCURVE_S1.); -#13097 = CIRCLE('',#13098,5.E-002); -#13098 = AXIS2_PLACEMENT_3D('',#13099,#13100,#13101); -#13099 = CARTESIAN_POINT('',(-0.26,-0.2,5.E-002)); -#13100 = DIRECTION('',(1.,0.E+000,0.E+000)); -#13101 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13102 = PCURVE('',#12489,#13103); -#13103 = DEFINITIONAL_REPRESENTATION('',(#13104),#13107); -#13104 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13105,#13106),.UNSPECIFIED., +#15476 = CARTESIAN_POINT('',(6.28318530718,0.115)); +#15477 = CARTESIAN_POINT('',(6.28318530718,-7.5E-002)); +#15478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15479 = PCURVE('',#14972,#15480); +#15480 = DEFINITIONAL_REPRESENTATION('',(#15481),#15485); +#15481 = LINE('',#15482,#15483); +#15482 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#15483 = VECTOR('',#15484,1.); +#15484 = DIRECTION('',(1.,0.E+000)); +#15485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15486 = ORIENTED_EDGE('',*,*,#15487,.F.); +#15487 = EDGE_CURVE('',#15415,#15466,#15488,.T.); +#15488 = SURFACE_CURVE('',#15489,(#15494,#15500),.PCURVE_S1.); +#15489 = CIRCLE('',#15490,5.E-002); +#15490 = AXIS2_PLACEMENT_3D('',#15491,#15492,#15493); +#15491 = CARTESIAN_POINT('',(-0.26,-0.2,5.E-002)); +#15492 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15493 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15494 = PCURVE('',#14881,#15495); +#15495 = DEFINITIONAL_REPRESENTATION('',(#15496),#15499); +#15496 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15497,#15498),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#13105 = CARTESIAN_POINT('',(4.712388980385,0.115)); -#13106 = CARTESIAN_POINT('',(6.28318530718,0.115)); -#13107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15497 = CARTESIAN_POINT('',(4.712388980385,0.115)); +#15498 = CARTESIAN_POINT('',(6.28318530718,0.115)); +#15499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13108 = PCURVE('',#13109,#13126); -#13109 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#13110,#13111,#13112,#13113) - ,(#13114,#13115,#13116,#13117) - ,(#13118,#13119,#13120,#13121) - ,(#13122,#13123,#13124,#13125 +#15500 = PCURVE('',#15501,#15518); +#15501 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#15502,#15503,#15504,#15505) + ,(#15506,#15507,#15508,#15509) + ,(#15510,#15511,#15512,#15513) + ,(#15514,#15515,#15516,#15517 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -15767,32 +18756,32 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#13110 = CARTESIAN_POINT('',(-0.26,-0.2,-1.694065894509E-018)); -#13111 = CARTESIAN_POINT('',(-0.26,-0.229289321881,-1.694065894509E-018) +#15502 = CARTESIAN_POINT('',(-0.26,-0.2,-1.694065894509E-018)); +#15503 = CARTESIAN_POINT('',(-0.26,-0.229289321881,-1.694065894509E-018) ); -#13112 = CARTESIAN_POINT('',(-0.26,-0.25,2.071067811865E-002)); -#13113 = CARTESIAN_POINT('',(-0.26,-0.25,5.E-002)); -#13114 = CARTESIAN_POINT('',(-0.254142135624,-0.2,-1.694065894509E-018) +#15504 = CARTESIAN_POINT('',(-0.26,-0.25,2.071067811865E-002)); +#15505 = CARTESIAN_POINT('',(-0.26,-0.25,5.E-002)); +#15506 = CARTESIAN_POINT('',(-0.254142135624,-0.2,-1.694065894509E-018) ); -#13115 = CARTESIAN_POINT('',(-0.254142135624,-0.229289321881, +#15507 = CARTESIAN_POINT('',(-0.254142135624,-0.229289321881, -1.694065894509E-018)); -#13116 = CARTESIAN_POINT('',(-0.254142135624,-0.25,2.071067811865E-002) - ); -#13117 = CARTESIAN_POINT('',(-0.254142135624,-0.25,5.E-002)); -#13118 = CARTESIAN_POINT('',(-0.25,-0.2,4.142135623731E-003)); -#13119 = CARTESIAN_POINT('',(-0.25,-0.22686291501,4.142135623731E-003)); -#13120 = CARTESIAN_POINT('',(-0.25,-0.245857864376,2.313708498985E-002) - ); -#13121 = CARTESIAN_POINT('',(-0.25,-0.245857864376,5.E-002)); -#13122 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); -#13123 = CARTESIAN_POINT('',(-0.25,-0.223431457505,1.E-002)); -#13124 = CARTESIAN_POINT('',(-0.25,-0.24,2.656854249492E-002)); -#13125 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); -#13126 = DEFINITIONAL_REPRESENTATION('',(#13127),#13153); -#13127 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13128,#13129,#13130,#13131, - #13132,#13133,#13134,#13135,#13136,#13137,#13138,#13139,#13140, - #13141,#13142,#13143,#13144,#13145,#13146,#13147,#13148,#13149, - #13150,#13151,#13152),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15508 = CARTESIAN_POINT('',(-0.254142135624,-0.25,2.071067811865E-002) + ); +#15509 = CARTESIAN_POINT('',(-0.254142135624,-0.25,5.E-002)); +#15510 = CARTESIAN_POINT('',(-0.25,-0.2,4.142135623731E-003)); +#15511 = CARTESIAN_POINT('',(-0.25,-0.22686291501,4.142135623731E-003)); +#15512 = CARTESIAN_POINT('',(-0.25,-0.245857864376,2.313708498985E-002) + ); +#15513 = CARTESIAN_POINT('',(-0.25,-0.245857864376,5.E-002)); +#15514 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); +#15515 = CARTESIAN_POINT('',(-0.25,-0.223431457505,1.E-002)); +#15516 = CARTESIAN_POINT('',(-0.25,-0.24,2.656854249492E-002)); +#15517 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); +#15518 = DEFINITIONAL_REPRESENTATION('',(#15519),#15545); +#15519 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15520,#15521,#15522,#15523, + #15524,#15525,#15526,#15527,#15528,#15529,#15530,#15531,#15532, + #15533,#15534,#15535,#15536,#15537,#15538,#15539,#15540,#15541, + #15542,#15543,#15544),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -15800,116 +18789,116 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#13128 = CARTESIAN_POINT('',(0.E+000,1.)); -#13129 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#13130 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#13131 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#13132 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#13133 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#13134 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#13135 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#13136 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#13137 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#13138 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#13139 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#13140 = CARTESIAN_POINT('',(0.E+000,0.5)); -#13141 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#13142 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#13143 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#13144 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#13145 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#13146 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#13147 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#13148 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#13149 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#13150 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#13151 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#13152 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#13153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13154 = ORIENTED_EDGE('',*,*,#13022,.T.); -#13155 = ADVANCED_FACE('',(#13156),#12580,.T.); -#13156 = FACE_BOUND('',#13157,.T.); -#13157 = EDGE_LOOP('',(#13158,#13159,#13181,#13206)); -#13158 = ORIENTED_EDGE('',*,*,#12567,.T.); -#13159 = ORIENTED_EDGE('',*,*,#13160,.F.); -#13160 = EDGE_CURVE('',#13161,#12506,#13163,.T.); -#13161 = VERTEX_POINT('',#13162); -#13162 = CARTESIAN_POINT('',(-0.26,0.2,-3.944376021176E-018)); -#13163 = SURFACE_CURVE('',#13164,(#13168,#13175),.PCURVE_S1.); -#13164 = LINE('',#13165,#13166); -#13165 = CARTESIAN_POINT('',(-0.375,0.2,-6.776263578034E-018)); -#13166 = VECTOR('',#13167,1.); -#13167 = DIRECTION('',(-1.,-1.641352236187E-030,1.224646799147E-016)); -#13168 = PCURVE('',#12580,#13169); -#13169 = DEFINITIONAL_REPRESENTATION('',(#13170),#13174); -#13170 = LINE('',#13171,#13172); -#13171 = CARTESIAN_POINT('',(0.E+000,0.45)); -#13172 = VECTOR('',#13173,1.); -#13173 = DIRECTION('',(1.,-1.641352236187E-030)); -#13174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13175 = PCURVE('',#12678,#13176); -#13176 = DEFINITIONAL_REPRESENTATION('',(#13177),#13180); -#13177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13178,#13179),.UNSPECIFIED., +#15520 = CARTESIAN_POINT('',(0.E+000,1.)); +#15521 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15522 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15523 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15524 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15525 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15526 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15527 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15528 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15529 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15530 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15531 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15532 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15533 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15534 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15535 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15536 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15537 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15538 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15539 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15540 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15541 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15542 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15543 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#15544 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15546 = ORIENTED_EDGE('',*,*,#15414,.T.); +#15547 = ADVANCED_FACE('',(#15548),#14972,.T.); +#15548 = FACE_BOUND('',#15549,.T.); +#15549 = EDGE_LOOP('',(#15550,#15551,#15573,#15598)); +#15550 = ORIENTED_EDGE('',*,*,#14959,.T.); +#15551 = ORIENTED_EDGE('',*,*,#15552,.F.); +#15552 = EDGE_CURVE('',#15553,#14898,#15555,.T.); +#15553 = VERTEX_POINT('',#15554); +#15554 = CARTESIAN_POINT('',(-0.26,0.2,-3.944376021176E-018)); +#15555 = SURFACE_CURVE('',#15556,(#15560,#15567),.PCURVE_S1.); +#15556 = LINE('',#15557,#15558); +#15557 = CARTESIAN_POINT('',(-0.375,0.2,-6.776263578034E-018)); +#15558 = VECTOR('',#15559,1.); +#15559 = DIRECTION('',(-1.,-1.641352236187E-030,1.224646799147E-016)); +#15560 = PCURVE('',#14972,#15561); +#15561 = DEFINITIONAL_REPRESENTATION('',(#15562),#15566); +#15562 = LINE('',#15563,#15564); +#15563 = CARTESIAN_POINT('',(0.E+000,0.45)); +#15564 = VECTOR('',#15565,1.); +#15565 = DIRECTION('',(1.,-1.641352236187E-030)); +#15566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15567 = PCURVE('',#15070,#15568); +#15568 = DEFINITIONAL_REPRESENTATION('',(#15569),#15572); +#15569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15570,#15571),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#13178 = CARTESIAN_POINT('',(0.E+000,0.115)); -#13179 = CARTESIAN_POINT('',(0.E+000,-7.5E-002)); -#13180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13181 = ORIENTED_EDGE('',*,*,#13182,.F.); -#13182 = EDGE_CURVE('',#13074,#13161,#13183,.T.); -#13183 = SURFACE_CURVE('',#13184,(#13188,#13195),.PCURVE_S1.); -#13184 = LINE('',#13185,#13186); -#13185 = CARTESIAN_POINT('',(-0.26,-0.25,0.E+000)); -#13186 = VECTOR('',#13187,1.); -#13187 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13188 = PCURVE('',#12580,#13189); -#13189 = DEFINITIONAL_REPRESENTATION('',(#13190),#13194); -#13190 = LINE('',#13191,#13192); -#13191 = CARTESIAN_POINT('',(-0.115,0.E+000)); -#13192 = VECTOR('',#13193,1.); -#13193 = DIRECTION('',(0.E+000,1.)); -#13194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13195 = PCURVE('',#13196,#13201); -#13196 = CYLINDRICAL_SURFACE('',#13197,1.E-002); -#13197 = AXIS2_PLACEMENT_3D('',#13198,#13199,#13200); -#13198 = CARTESIAN_POINT('',(-0.26,-0.25,1.E-002)); -#13199 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13200 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13201 = DEFINITIONAL_REPRESENTATION('',(#13202),#13205); -#13202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13203,#13204),.UNSPECIFIED., +#15570 = CARTESIAN_POINT('',(0.E+000,0.115)); +#15571 = CARTESIAN_POINT('',(0.E+000,-7.5E-002)); +#15572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15573 = ORIENTED_EDGE('',*,*,#15574,.F.); +#15574 = EDGE_CURVE('',#15466,#15553,#15575,.T.); +#15575 = SURFACE_CURVE('',#15576,(#15580,#15587),.PCURVE_S1.); +#15576 = LINE('',#15577,#15578); +#15577 = CARTESIAN_POINT('',(-0.26,-0.25,0.E+000)); +#15578 = VECTOR('',#15579,1.); +#15579 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15580 = PCURVE('',#14972,#15581); +#15581 = DEFINITIONAL_REPRESENTATION('',(#15582),#15586); +#15582 = LINE('',#15583,#15584); +#15583 = CARTESIAN_POINT('',(-0.115,0.E+000)); +#15584 = VECTOR('',#15585,1.); +#15585 = DIRECTION('',(0.E+000,1.)); +#15586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15587 = PCURVE('',#15588,#15593); +#15588 = CYLINDRICAL_SURFACE('',#15589,1.E-002); +#15589 = AXIS2_PLACEMENT_3D('',#15590,#15591,#15592); +#15590 = CARTESIAN_POINT('',(-0.26,-0.25,1.E-002)); +#15591 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15592 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15593 = DEFINITIONAL_REPRESENTATION('',(#15594),#15597); +#15594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15595,#15596),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#13203 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#13204 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#13205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13206 = ORIENTED_EDGE('',*,*,#13073,.T.); -#13207 = ADVANCED_FACE('',(#13208),#12678,.T.); -#13208 = FACE_BOUND('',#13209,.T.); -#13209 = EDGE_LOOP('',(#13210,#13211,#13256,#13316)); -#13210 = ORIENTED_EDGE('',*,*,#12641,.T.); -#13211 = ORIENTED_EDGE('',*,*,#13212,.F.); -#13212 = EDGE_CURVE('',#13213,#12597,#13215,.T.); -#13213 = VERTEX_POINT('',#13214); -#13214 = CARTESIAN_POINT('',(-0.26,0.25,5.E-002)); -#13215 = SURFACE_CURVE('',#13216,(#13220,#13249),.PCURVE_S1.); -#13216 = LINE('',#13217,#13218); -#13217 = CARTESIAN_POINT('',(-0.375,0.25,5.E-002)); -#13218 = VECTOR('',#13219,1.); -#13219 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); -#13220 = PCURVE('',#12678,#13221); -#13221 = DEFINITIONAL_REPRESENTATION('',(#13222),#13248); -#13222 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13223,#13224,#13225,#13226, - #13227,#13228,#13229,#13230,#13231,#13232,#13233,#13234,#13235, - #13236,#13237,#13238,#13239,#13240,#13241,#13242,#13243,#13244, - #13245,#13246,#13247),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15595 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#15596 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#15597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15598 = ORIENTED_EDGE('',*,*,#15465,.T.); +#15599 = ADVANCED_FACE('',(#15600),#15070,.T.); +#15600 = FACE_BOUND('',#15601,.T.); +#15601 = EDGE_LOOP('',(#15602,#15603,#15648,#15708)); +#15602 = ORIENTED_EDGE('',*,*,#15033,.T.); +#15603 = ORIENTED_EDGE('',*,*,#15604,.F.); +#15604 = EDGE_CURVE('',#15605,#14989,#15607,.T.); +#15605 = VERTEX_POINT('',#15606); +#15606 = CARTESIAN_POINT('',(-0.26,0.25,5.E-002)); +#15607 = SURFACE_CURVE('',#15608,(#15612,#15641),.PCURVE_S1.); +#15608 = LINE('',#15609,#15610); +#15609 = CARTESIAN_POINT('',(-0.375,0.25,5.E-002)); +#15610 = VECTOR('',#15611,1.); +#15611 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); +#15612 = PCURVE('',#15070,#15613); +#15613 = DEFINITIONAL_REPRESENTATION('',(#15614),#15640); +#15614 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15615,#15616,#15617,#15618, + #15619,#15620,#15621,#15622,#15623,#15624,#15625,#15626,#15627, + #15628,#15629,#15630,#15631,#15632,#15633,#15634,#15635,#15636, + #15637,#15638,#15639),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.115,-0.106363636364,-9.772727272727E-002 ,-8.909090909091E-002,-8.045454545455E-002,-7.181818181818E-002, -6.318181818182E-002,-5.454545454545E-002,-4.590909090909E-002, @@ -15918,67 +18907,67 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.454545454545E-002,2.318181818182E-002,3.181818181818E-002, 4.045454545455E-002,4.909090909091E-002,5.772727272727E-002, 6.636363636364E-002,7.5E-002),.UNSPECIFIED.); -#13223 = CARTESIAN_POINT('',(1.570796326795,0.115)); -#13224 = CARTESIAN_POINT('',(1.570796326795,0.112121212121)); -#13225 = CARTESIAN_POINT('',(1.570796326795,0.106363636364)); -#13226 = CARTESIAN_POINT('',(1.570796326795,9.772727272727E-002)); -#13227 = CARTESIAN_POINT('',(1.570796326795,8.909090909091E-002)); -#13228 = CARTESIAN_POINT('',(1.570796326795,8.045454545455E-002)); -#13229 = CARTESIAN_POINT('',(1.570796326795,7.181818181818E-002)); -#13230 = CARTESIAN_POINT('',(1.570796326795,6.318181818182E-002)); -#13231 = CARTESIAN_POINT('',(1.570796326795,5.454545454545E-002)); -#13232 = CARTESIAN_POINT('',(1.570796326795,4.590909090909E-002)); -#13233 = CARTESIAN_POINT('',(1.570796326795,3.727272727273E-002)); -#13234 = CARTESIAN_POINT('',(1.570796326795,2.863636363636E-002)); -#13235 = CARTESIAN_POINT('',(1.570796326795,2.E-002)); -#13236 = CARTESIAN_POINT('',(1.570796326795,1.136363636364E-002)); -#13237 = CARTESIAN_POINT('',(1.570796326795,2.727272727273E-003)); -#13238 = CARTESIAN_POINT('',(1.570796326795,-5.909090909091E-003)); -#13239 = CARTESIAN_POINT('',(1.570796326795,-1.454545454545E-002)); -#13240 = CARTESIAN_POINT('',(1.570796326795,-2.318181818182E-002)); -#13241 = CARTESIAN_POINT('',(1.570796326795,-3.181818181818E-002)); -#13242 = CARTESIAN_POINT('',(1.570796326795,-4.045454545455E-002)); -#13243 = CARTESIAN_POINT('',(1.570796326795,-4.909090909091E-002)); -#13244 = CARTESIAN_POINT('',(1.570796326795,-5.772727272727E-002)); -#13245 = CARTESIAN_POINT('',(1.570796326795,-6.636363636364E-002)); -#13246 = CARTESIAN_POINT('',(1.570796326795,-7.212121212121E-002)); -#13247 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); -#13248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13249 = PCURVE('',#12767,#13250); -#13250 = DEFINITIONAL_REPRESENTATION('',(#13251),#13255); -#13251 = LINE('',#13252,#13253); -#13252 = CARTESIAN_POINT('',(-2.766272740304E-078,-0.25)); -#13253 = VECTOR('',#13254,1.); -#13254 = DIRECTION('',(1.,-1.106509096121E-077)); -#13255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13256 = ORIENTED_EDGE('',*,*,#13257,.F.); -#13257 = EDGE_CURVE('',#13161,#13213,#13258,.T.); -#13258 = SURFACE_CURVE('',#13259,(#13264,#13270),.PCURVE_S1.); -#13259 = CIRCLE('',#13260,5.E-002); -#13260 = AXIS2_PLACEMENT_3D('',#13261,#13262,#13263); -#13261 = CARTESIAN_POINT('',(-0.26,0.2,5.E-002)); -#13262 = DIRECTION('',(1.,0.E+000,0.E+000)); -#13263 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13264 = PCURVE('',#12678,#13265); -#13265 = DEFINITIONAL_REPRESENTATION('',(#13266),#13269); -#13266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13267,#13268),.UNSPECIFIED., +#15615 = CARTESIAN_POINT('',(1.570796326795,0.115)); +#15616 = CARTESIAN_POINT('',(1.570796326795,0.112121212121)); +#15617 = CARTESIAN_POINT('',(1.570796326795,0.106363636364)); +#15618 = CARTESIAN_POINT('',(1.570796326795,9.772727272727E-002)); +#15619 = CARTESIAN_POINT('',(1.570796326795,8.909090909091E-002)); +#15620 = CARTESIAN_POINT('',(1.570796326795,8.045454545455E-002)); +#15621 = CARTESIAN_POINT('',(1.570796326795,7.181818181818E-002)); +#15622 = CARTESIAN_POINT('',(1.570796326795,6.318181818182E-002)); +#15623 = CARTESIAN_POINT('',(1.570796326795,5.454545454545E-002)); +#15624 = CARTESIAN_POINT('',(1.570796326795,4.590909090909E-002)); +#15625 = CARTESIAN_POINT('',(1.570796326795,3.727272727273E-002)); +#15626 = CARTESIAN_POINT('',(1.570796326795,2.863636363636E-002)); +#15627 = CARTESIAN_POINT('',(1.570796326795,2.E-002)); +#15628 = CARTESIAN_POINT('',(1.570796326795,1.136363636364E-002)); +#15629 = CARTESIAN_POINT('',(1.570796326795,2.727272727273E-003)); +#15630 = CARTESIAN_POINT('',(1.570796326795,-5.909090909091E-003)); +#15631 = CARTESIAN_POINT('',(1.570796326795,-1.454545454545E-002)); +#15632 = CARTESIAN_POINT('',(1.570796326795,-2.318181818182E-002)); +#15633 = CARTESIAN_POINT('',(1.570796326795,-3.181818181818E-002)); +#15634 = CARTESIAN_POINT('',(1.570796326795,-4.045454545455E-002)); +#15635 = CARTESIAN_POINT('',(1.570796326795,-4.909090909091E-002)); +#15636 = CARTESIAN_POINT('',(1.570796326795,-5.772727272727E-002)); +#15637 = CARTESIAN_POINT('',(1.570796326795,-6.636363636364E-002)); +#15638 = CARTESIAN_POINT('',(1.570796326795,-7.212121212121E-002)); +#15639 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); +#15640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15641 = PCURVE('',#15159,#15642); +#15642 = DEFINITIONAL_REPRESENTATION('',(#15643),#15647); +#15643 = LINE('',#15644,#15645); +#15644 = CARTESIAN_POINT('',(-2.766272740304E-078,-0.25)); +#15645 = VECTOR('',#15646,1.); +#15646 = DIRECTION('',(1.,-1.106509096121E-077)); +#15647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15648 = ORIENTED_EDGE('',*,*,#15649,.F.); +#15649 = EDGE_CURVE('',#15553,#15605,#15650,.T.); +#15650 = SURFACE_CURVE('',#15651,(#15656,#15662),.PCURVE_S1.); +#15651 = CIRCLE('',#15652,5.E-002); +#15652 = AXIS2_PLACEMENT_3D('',#15653,#15654,#15655); +#15653 = CARTESIAN_POINT('',(-0.26,0.2,5.E-002)); +#15654 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15655 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15656 = PCURVE('',#15070,#15657); +#15657 = DEFINITIONAL_REPRESENTATION('',(#15658),#15661); +#15658 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15659,#15660),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#13267 = CARTESIAN_POINT('',(0.E+000,0.115)); -#13268 = CARTESIAN_POINT('',(1.570796326795,0.115)); -#13269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15659 = CARTESIAN_POINT('',(0.E+000,0.115)); +#15660 = CARTESIAN_POINT('',(1.570796326795,0.115)); +#15661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13270 = PCURVE('',#13271,#13288); -#13271 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#13272,#13273,#13274,#13275) - ,(#13276,#13277,#13278,#13279) - ,(#13280,#13281,#13282,#13283) - ,(#13284,#13285,#13286,#13287 +#15662 = PCURVE('',#15663,#15680); +#15663 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#15664,#15665,#15666,#15667) + ,(#15668,#15669,#15670,#15671) + ,(#15672,#15673,#15674,#15675) + ,(#15676,#15677,#15678,#15679 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -15987,28 +18976,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#13272 = CARTESIAN_POINT('',(-0.26,0.25,5.E-002)); -#13273 = CARTESIAN_POINT('',(-0.26,0.25,2.071067811865E-002)); -#13274 = CARTESIAN_POINT('',(-0.26,0.229289321881,1.587777320719E-017)); -#13275 = CARTESIAN_POINT('',(-0.26,0.2,0.E+000)); -#13276 = CARTESIAN_POINT('',(-0.254142135624,0.25,5.E-002)); -#13277 = CARTESIAN_POINT('',(-0.254142135624,0.25,2.071067811865E-002)); -#13278 = CARTESIAN_POINT('',(-0.254142135624,0.229289321881, +#15664 = CARTESIAN_POINT('',(-0.26,0.25,5.E-002)); +#15665 = CARTESIAN_POINT('',(-0.26,0.25,2.071067811865E-002)); +#15666 = CARTESIAN_POINT('',(-0.26,0.229289321881,1.587777320719E-017)); +#15667 = CARTESIAN_POINT('',(-0.26,0.2,0.E+000)); +#15668 = CARTESIAN_POINT('',(-0.254142135624,0.25,5.E-002)); +#15669 = CARTESIAN_POINT('',(-0.254142135624,0.25,2.071067811865E-002)); +#15670 = CARTESIAN_POINT('',(-0.254142135624,0.229289321881, 1.587777320719E-017)); -#13279 = CARTESIAN_POINT('',(-0.254142135624,0.2,0.E+000)); -#13280 = CARTESIAN_POINT('',(-0.25,0.245857864376,5.E-002)); -#13281 = CARTESIAN_POINT('',(-0.25,0.245857864376,2.313708498985E-002)); -#13282 = CARTESIAN_POINT('',(-0.25,0.22686291501,4.142135623731E-003)); -#13283 = CARTESIAN_POINT('',(-0.25,0.2,4.142135623731E-003)); -#13284 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); -#13285 = CARTESIAN_POINT('',(-0.25,0.24,2.656854249492E-002)); -#13286 = CARTESIAN_POINT('',(-0.25,0.223431457505,1.E-002)); -#13287 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); -#13288 = DEFINITIONAL_REPRESENTATION('',(#13289),#13315); -#13289 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13290,#13291,#13292,#13293, - #13294,#13295,#13296,#13297,#13298,#13299,#13300,#13301,#13302, - #13303,#13304,#13305,#13306,#13307,#13308,#13309,#13310,#13311, - #13312,#13313,#13314),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15671 = CARTESIAN_POINT('',(-0.254142135624,0.2,0.E+000)); +#15672 = CARTESIAN_POINT('',(-0.25,0.245857864376,5.E-002)); +#15673 = CARTESIAN_POINT('',(-0.25,0.245857864376,2.313708498985E-002)); +#15674 = CARTESIAN_POINT('',(-0.25,0.22686291501,4.142135623731E-003)); +#15675 = CARTESIAN_POINT('',(-0.25,0.2,4.142135623731E-003)); +#15676 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); +#15677 = CARTESIAN_POINT('',(-0.25,0.24,2.656854249492E-002)); +#15678 = CARTESIAN_POINT('',(-0.25,0.223431457505,1.E-002)); +#15679 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); +#15680 = DEFINITIONAL_REPRESENTATION('',(#15681),#15707); +#15681 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15682,#15683,#15684,#15685, + #15686,#15687,#15688,#15689,#15690,#15691,#15692,#15693,#15694, + #15695,#15696,#15697,#15698,#15699,#15700,#15701,#15702,#15703, + #15704,#15705,#15706),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -16016,151 +19005,151 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#13290 = CARTESIAN_POINT('',(0.E+000,1.)); -#13291 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#13292 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#13293 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#13294 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#13295 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#13296 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#13297 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#13298 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#13299 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#13300 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#13301 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#13302 = CARTESIAN_POINT('',(0.E+000,0.5)); -#13303 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#13304 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#13305 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#13306 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#13307 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#13308 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#13309 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#13310 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#13311 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#13312 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#13313 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); -#13314 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#13315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13316 = ORIENTED_EDGE('',*,*,#13160,.T.); -#13317 = ADVANCED_FACE('',(#13318),#12767,.T.); -#13318 = FACE_BOUND('',#13319,.T.); -#13319 = EDGE_LOOP('',(#13320,#13321,#13343,#13368)); -#13320 = ORIENTED_EDGE('',*,*,#12754,.T.); -#13321 = ORIENTED_EDGE('',*,*,#13322,.F.); -#13322 = EDGE_CURVE('',#13323,#12693,#13325,.T.); -#13323 = VERTEX_POINT('',#13324); -#13324 = CARTESIAN_POINT('',(-0.26,0.25,0.55)); -#13325 = SURFACE_CURVE('',#13326,(#13330,#13337),.PCURVE_S1.); -#13326 = LINE('',#13327,#13328); -#13327 = CARTESIAN_POINT('',(-0.375,0.25,0.55)); -#13328 = VECTOR('',#13329,1.); -#13329 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); -#13330 = PCURVE('',#12767,#13331); -#13331 = DEFINITIONAL_REPRESENTATION('',(#13332),#13336); -#13332 = LINE('',#13333,#13334); -#13333 = CARTESIAN_POINT('',(2.766272740304E-078,0.25)); -#13334 = VECTOR('',#13335,1.); -#13335 = DIRECTION('',(1.,-1.106509096121E-077)); -#13336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13337 = PCURVE('',#12866,#13338); -#13338 = DEFINITIONAL_REPRESENTATION('',(#13339),#13342); -#13339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13340,#13341),.UNSPECIFIED., +#15682 = CARTESIAN_POINT('',(0.E+000,1.)); +#15683 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15684 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15685 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15686 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15687 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15688 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15689 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15690 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15691 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15692 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15693 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15694 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15695 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15696 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15697 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15698 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15699 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15700 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15701 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15702 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15703 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15704 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15705 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); +#15706 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15708 = ORIENTED_EDGE('',*,*,#15552,.T.); +#15709 = ADVANCED_FACE('',(#15710),#15159,.T.); +#15710 = FACE_BOUND('',#15711,.T.); +#15711 = EDGE_LOOP('',(#15712,#15713,#15735,#15760)); +#15712 = ORIENTED_EDGE('',*,*,#15146,.T.); +#15713 = ORIENTED_EDGE('',*,*,#15714,.F.); +#15714 = EDGE_CURVE('',#15715,#15085,#15717,.T.); +#15715 = VERTEX_POINT('',#15716); +#15716 = CARTESIAN_POINT('',(-0.26,0.25,0.55)); +#15717 = SURFACE_CURVE('',#15718,(#15722,#15729),.PCURVE_S1.); +#15718 = LINE('',#15719,#15720); +#15719 = CARTESIAN_POINT('',(-0.375,0.25,0.55)); +#15720 = VECTOR('',#15721,1.); +#15721 = DIRECTION('',(-1.,-1.641352236187E-030,0.E+000)); +#15722 = PCURVE('',#15159,#15723); +#15723 = DEFINITIONAL_REPRESENTATION('',(#15724),#15728); +#15724 = LINE('',#15725,#15726); +#15725 = CARTESIAN_POINT('',(2.766272740304E-078,0.25)); +#15726 = VECTOR('',#15727,1.); +#15727 = DIRECTION('',(1.,-1.106509096121E-077)); +#15728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15729 = PCURVE('',#15258,#15730); +#15730 = DEFINITIONAL_REPRESENTATION('',(#15731),#15734); +#15731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15732,#15733),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#13340 = CARTESIAN_POINT('',(3.14159265359,-0.115)); -#13341 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); -#13342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13343 = ORIENTED_EDGE('',*,*,#13344,.F.); -#13344 = EDGE_CURVE('',#13213,#13323,#13345,.T.); -#13345 = SURFACE_CURVE('',#13346,(#13350,#13357),.PCURVE_S1.); -#13346 = LINE('',#13347,#13348); -#13347 = CARTESIAN_POINT('',(-0.26,0.25,0.3)); -#13348 = VECTOR('',#13349,1.); -#13349 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#13350 = PCURVE('',#12767,#13351); -#13351 = DEFINITIONAL_REPRESENTATION('',(#13352),#13356); -#13352 = LINE('',#13353,#13354); -#13353 = CARTESIAN_POINT('',(-0.115,4.898308959716E-062)); -#13354 = VECTOR('',#13355,1.); -#13355 = DIRECTION('',(4.259399095405E-061,1.)); -#13356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13357 = PCURVE('',#13358,#13363); -#13358 = CYLINDRICAL_SURFACE('',#13359,1.E-002); -#13359 = AXIS2_PLACEMENT_3D('',#13360,#13361,#13362); -#13360 = CARTESIAN_POINT('',(-0.26,0.24,0.3)); -#13361 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#13362 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); -#13363 = DEFINITIONAL_REPRESENTATION('',(#13364),#13367); -#13364 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13365,#13366),.UNSPECIFIED., +#15732 = CARTESIAN_POINT('',(3.14159265359,-0.115)); +#15733 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); +#15734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15735 = ORIENTED_EDGE('',*,*,#15736,.F.); +#15736 = EDGE_CURVE('',#15605,#15715,#15737,.T.); +#15737 = SURFACE_CURVE('',#15738,(#15742,#15749),.PCURVE_S1.); +#15738 = LINE('',#15739,#15740); +#15739 = CARTESIAN_POINT('',(-0.26,0.25,0.3)); +#15740 = VECTOR('',#15741,1.); +#15741 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#15742 = PCURVE('',#15159,#15743); +#15743 = DEFINITIONAL_REPRESENTATION('',(#15744),#15748); +#15744 = LINE('',#15745,#15746); +#15745 = CARTESIAN_POINT('',(-0.115,4.898308959716E-062)); +#15746 = VECTOR('',#15747,1.); +#15747 = DIRECTION('',(4.259399095405E-061,1.)); +#15748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15749 = PCURVE('',#15750,#15755); +#15750 = CYLINDRICAL_SURFACE('',#15751,1.E-002); +#15751 = AXIS2_PLACEMENT_3D('',#15752,#15753,#15754); +#15752 = CARTESIAN_POINT('',(-0.26,0.24,0.3)); +#15753 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#15754 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); +#15755 = DEFINITIONAL_REPRESENTATION('',(#15756),#15759); +#15756 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15757,#15758),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#13365 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#13366 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#13367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13368 = ORIENTED_EDGE('',*,*,#13212,.T.); -#13369 = ADVANCED_FACE('',(#13370),#12866,.T.); -#13370 = FACE_BOUND('',#13371,.T.); -#13371 = EDGE_LOOP('',(#13372,#13373,#13395,#13455)); -#13372 = ORIENTED_EDGE('',*,*,#12829,.T.); -#13373 = ORIENTED_EDGE('',*,*,#13374,.F.); -#13374 = EDGE_CURVE('',#13375,#12785,#13377,.T.); -#13375 = VERTEX_POINT('',#13376); -#13376 = CARTESIAN_POINT('',(-0.26,0.2,0.6)); -#13377 = SURFACE_CURVE('',#13378,(#13382,#13388),.PCURVE_S1.); -#13378 = LINE('',#13379,#13380); -#13379 = CARTESIAN_POINT('',(-0.375,0.2,0.6)); -#13380 = VECTOR('',#13381,1.); -#13381 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#13382 = PCURVE('',#12866,#13383); -#13383 = DEFINITIONAL_REPRESENTATION('',(#13384),#13387); -#13384 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13385,#13386),.UNSPECIFIED., +#15757 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#15758 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#15759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15760 = ORIENTED_EDGE('',*,*,#15604,.T.); +#15761 = ADVANCED_FACE('',(#15762),#15258,.T.); +#15762 = FACE_BOUND('',#15763,.T.); +#15763 = EDGE_LOOP('',(#15764,#15765,#15787,#15847)); +#15764 = ORIENTED_EDGE('',*,*,#15221,.T.); +#15765 = ORIENTED_EDGE('',*,*,#15766,.F.); +#15766 = EDGE_CURVE('',#15767,#15177,#15769,.T.); +#15767 = VERTEX_POINT('',#15768); +#15768 = CARTESIAN_POINT('',(-0.26,0.2,0.6)); +#15769 = SURFACE_CURVE('',#15770,(#15774,#15780),.PCURVE_S1.); +#15770 = LINE('',#15771,#15772); +#15771 = CARTESIAN_POINT('',(-0.375,0.2,0.6)); +#15772 = VECTOR('',#15773,1.); +#15773 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#15774 = PCURVE('',#15258,#15775); +#15775 = DEFINITIONAL_REPRESENTATION('',(#15776),#15779); +#15776 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15777,#15778),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#13385 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#13386 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#13387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13388 = PCURVE('',#12895,#13389); -#13389 = DEFINITIONAL_REPRESENTATION('',(#13390),#13394); -#13390 = LINE('',#13391,#13392); -#13391 = CARTESIAN_POINT('',(0.E+000,0.45)); -#13392 = VECTOR('',#13393,1.); -#13393 = DIRECTION('',(-1.,0.E+000)); -#13394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13395 = ORIENTED_EDGE('',*,*,#13396,.F.); -#13396 = EDGE_CURVE('',#13323,#13375,#13397,.T.); -#13397 = SURFACE_CURVE('',#13398,(#13403,#13409),.PCURVE_S1.); -#13398 = CIRCLE('',#13399,5.E-002); -#13399 = AXIS2_PLACEMENT_3D('',#13400,#13401,#13402); -#13400 = CARTESIAN_POINT('',(-0.26,0.2,0.55)); -#13401 = DIRECTION('',(1.,0.E+000,0.E+000)); -#13402 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13403 = PCURVE('',#12866,#13404); -#13404 = DEFINITIONAL_REPRESENTATION('',(#13405),#13408); -#13405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13406,#13407),.UNSPECIFIED., +#15777 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#15778 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#15779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15780 = PCURVE('',#15287,#15781); +#15781 = DEFINITIONAL_REPRESENTATION('',(#15782),#15786); +#15782 = LINE('',#15783,#15784); +#15783 = CARTESIAN_POINT('',(0.E+000,0.45)); +#15784 = VECTOR('',#15785,1.); +#15785 = DIRECTION('',(-1.,0.E+000)); +#15786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15787 = ORIENTED_EDGE('',*,*,#15788,.F.); +#15788 = EDGE_CURVE('',#15715,#15767,#15789,.T.); +#15789 = SURFACE_CURVE('',#15790,(#15795,#15801),.PCURVE_S1.); +#15790 = CIRCLE('',#15791,5.E-002); +#15791 = AXIS2_PLACEMENT_3D('',#15792,#15793,#15794); +#15792 = CARTESIAN_POINT('',(-0.26,0.2,0.55)); +#15793 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15794 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15795 = PCURVE('',#15258,#15796); +#15796 = DEFINITIONAL_REPRESENTATION('',(#15797),#15800); +#15797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15798,#15799),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#13406 = CARTESIAN_POINT('',(3.14159265359,-0.115)); -#13407 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#13408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#15798 = CARTESIAN_POINT('',(3.14159265359,-0.115)); +#15799 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#15800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13409 = PCURVE('',#13410,#13427); -#13410 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#13411,#13412,#13413,#13414) - ,(#13415,#13416,#13417,#13418) - ,(#13419,#13420,#13421,#13422) - ,(#13423,#13424,#13425,#13426 +#15801 = PCURVE('',#15802,#15819); +#15802 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#15803,#15804,#15805,#15806) + ,(#15807,#15808,#15809,#15810) + ,(#15811,#15812,#15813,#15814) + ,(#15815,#15816,#15817,#15818 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -16169,27 +19158,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#13411 = CARTESIAN_POINT('',(-0.26,0.2,0.6)); -#13412 = CARTESIAN_POINT('',(-0.26,0.229289321881,0.6)); -#13413 = CARTESIAN_POINT('',(-0.26,0.25,0.579289321881)); -#13414 = CARTESIAN_POINT('',(-0.26,0.25,0.55)); -#13415 = CARTESIAN_POINT('',(-0.254142135624,0.2,0.6)); -#13416 = CARTESIAN_POINT('',(-0.254142135624,0.229289321881,0.6)); -#13417 = CARTESIAN_POINT('',(-0.254142135624,0.25,0.579289321881)); -#13418 = CARTESIAN_POINT('',(-0.254142135624,0.25,0.55)); -#13419 = CARTESIAN_POINT('',(-0.25,0.2,0.595857864376)); -#13420 = CARTESIAN_POINT('',(-0.25,0.22686291501,0.595857864376)); -#13421 = CARTESIAN_POINT('',(-0.25,0.245857864376,0.57686291501)); -#13422 = CARTESIAN_POINT('',(-0.25,0.245857864376,0.55)); -#13423 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); -#13424 = CARTESIAN_POINT('',(-0.25,0.223431457505,0.59)); -#13425 = CARTESIAN_POINT('',(-0.25,0.24,0.573431457505)); -#13426 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); -#13427 = DEFINITIONAL_REPRESENTATION('',(#13428),#13454); -#13428 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13429,#13430,#13431,#13432, - #13433,#13434,#13435,#13436,#13437,#13438,#13439,#13440,#13441, - #13442,#13443,#13444,#13445,#13446,#13447,#13448,#13449,#13450, - #13451,#13452,#13453),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15803 = CARTESIAN_POINT('',(-0.26,0.2,0.6)); +#15804 = CARTESIAN_POINT('',(-0.26,0.229289321881,0.6)); +#15805 = CARTESIAN_POINT('',(-0.26,0.25,0.579289321881)); +#15806 = CARTESIAN_POINT('',(-0.26,0.25,0.55)); +#15807 = CARTESIAN_POINT('',(-0.254142135624,0.2,0.6)); +#15808 = CARTESIAN_POINT('',(-0.254142135624,0.229289321881,0.6)); +#15809 = CARTESIAN_POINT('',(-0.254142135624,0.25,0.579289321881)); +#15810 = CARTESIAN_POINT('',(-0.254142135624,0.25,0.55)); +#15811 = CARTESIAN_POINT('',(-0.25,0.2,0.595857864376)); +#15812 = CARTESIAN_POINT('',(-0.25,0.22686291501,0.595857864376)); +#15813 = CARTESIAN_POINT('',(-0.25,0.245857864376,0.57686291501)); +#15814 = CARTESIAN_POINT('',(-0.25,0.245857864376,0.55)); +#15815 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); +#15816 = CARTESIAN_POINT('',(-0.25,0.223431457505,0.59)); +#15817 = CARTESIAN_POINT('',(-0.25,0.24,0.573431457505)); +#15818 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); +#15819 = DEFINITIONAL_REPRESENTATION('',(#15820),#15846); +#15820 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15821,#15822,#15823,#15824, + #15825,#15826,#15827,#15828,#15829,#15830,#15831,#15832,#15833, + #15834,#15835,#15836,#15837,#15838,#15839,#15840,#15841,#15842, + #15843,#15844,#15845),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -16197,226 +19186,226 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#13429 = CARTESIAN_POINT('',(0.E+000,1.)); -#13430 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#13431 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#13432 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#13433 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#13434 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#13435 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#13436 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#13437 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#13438 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#13439 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#13440 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#13441 = CARTESIAN_POINT('',(0.E+000,0.5)); -#13442 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#13443 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#13444 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#13445 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#13446 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#13447 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#13448 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#13449 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#13450 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#13451 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#13452 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#13453 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#13454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13455 = ORIENTED_EDGE('',*,*,#13322,.T.); -#13456 = ADVANCED_FACE('',(#13457),#12895,.T.); -#13457 = FACE_BOUND('',#13458,.T.); -#13458 = EDGE_LOOP('',(#13459,#13460,#13461,#13486)); -#13459 = ORIENTED_EDGE('',*,*,#12882,.T.); -#13460 = ORIENTED_EDGE('',*,*,#12997,.T.); -#13461 = ORIENTED_EDGE('',*,*,#13462,.F.); -#13462 = EDGE_CURVE('',#13375,#12936,#13463,.T.); -#13463 = SURFACE_CURVE('',#13464,(#13468,#13475),.PCURVE_S1.); -#13464 = LINE('',#13465,#13466); -#13465 = CARTESIAN_POINT('',(-0.26,-0.25,0.6)); -#13466 = VECTOR('',#13467,1.); -#13467 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#13468 = PCURVE('',#12895,#13469); -#13469 = DEFINITIONAL_REPRESENTATION('',(#13470),#13474); -#13470 = LINE('',#13471,#13472); -#13471 = CARTESIAN_POINT('',(0.115,0.E+000)); -#13472 = VECTOR('',#13473,1.); -#13473 = DIRECTION('',(0.E+000,-1.)); -#13474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13475 = PCURVE('',#13476,#13481); -#13476 = CYLINDRICAL_SURFACE('',#13477,1.E-002); -#13477 = AXIS2_PLACEMENT_3D('',#13478,#13479,#13480); -#13478 = CARTESIAN_POINT('',(-0.26,-0.25,0.59)); -#13479 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13480 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13481 = DEFINITIONAL_REPRESENTATION('',(#13482),#13485); -#13482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13483,#13484),.UNSPECIFIED., +#15821 = CARTESIAN_POINT('',(0.E+000,1.)); +#15822 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#15823 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#15824 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#15825 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#15826 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#15827 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#15828 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#15829 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#15830 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#15831 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#15832 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#15833 = CARTESIAN_POINT('',(0.E+000,0.5)); +#15834 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#15835 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#15836 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#15837 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#15838 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#15839 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#15840 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#15841 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#15842 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#15843 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#15844 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#15845 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#15846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15847 = ORIENTED_EDGE('',*,*,#15714,.T.); +#15848 = ADVANCED_FACE('',(#15849),#15287,.T.); +#15849 = FACE_BOUND('',#15850,.T.); +#15850 = EDGE_LOOP('',(#15851,#15852,#15853,#15878)); +#15851 = ORIENTED_EDGE('',*,*,#15274,.T.); +#15852 = ORIENTED_EDGE('',*,*,#15389,.T.); +#15853 = ORIENTED_EDGE('',*,*,#15854,.F.); +#15854 = EDGE_CURVE('',#15767,#15328,#15855,.T.); +#15855 = SURFACE_CURVE('',#15856,(#15860,#15867),.PCURVE_S1.); +#15856 = LINE('',#15857,#15858); +#15857 = CARTESIAN_POINT('',(-0.26,-0.25,0.6)); +#15858 = VECTOR('',#15859,1.); +#15859 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#15860 = PCURVE('',#15287,#15861); +#15861 = DEFINITIONAL_REPRESENTATION('',(#15862),#15866); +#15862 = LINE('',#15863,#15864); +#15863 = CARTESIAN_POINT('',(0.115,0.E+000)); +#15864 = VECTOR('',#15865,1.); +#15865 = DIRECTION('',(0.E+000,-1.)); +#15866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15867 = PCURVE('',#15868,#15873); +#15868 = CYLINDRICAL_SURFACE('',#15869,1.E-002); +#15869 = AXIS2_PLACEMENT_3D('',#15870,#15871,#15872); +#15870 = CARTESIAN_POINT('',(-0.26,-0.25,0.59)); +#15871 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15872 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15873 = DEFINITIONAL_REPRESENTATION('',(#15874),#15877); +#15874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15875,#15876),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#13483 = CARTESIAN_POINT('',(0.E+000,0.45)); -#13484 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#13485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13486 = ORIENTED_EDGE('',*,*,#13374,.T.); -#13487 = ADVANCED_FACE('',(#13488),#13502,.T.); -#13488 = FACE_BOUND('',#13489,.T.); -#13489 = EDGE_LOOP('',(#13490,#13524,#13551,#13578)); -#13490 = ORIENTED_EDGE('',*,*,#13491,.F.); -#13491 = EDGE_CURVE('',#13492,#13494,#13496,.T.); -#13492 = VERTEX_POINT('',#13493); -#13493 = CARTESIAN_POINT('',(0.5,0.2,0.55)); -#13494 = VERTEX_POINT('',#13495); -#13495 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); -#13496 = SURFACE_CURVE('',#13497,(#13501,#13513),.PCURVE_S1.); -#13497 = LINE('',#13498,#13499); -#13498 = CARTESIAN_POINT('',(0.5,0.2,0.3)); -#13499 = VECTOR('',#13500,1.); -#13500 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#13501 = PCURVE('',#13502,#13507); -#13502 = PLANE('',#13503); -#13503 = AXIS2_PLACEMENT_3D('',#13504,#13505,#13506); -#13504 = CARTESIAN_POINT('',(0.5,-0.25,0.3)); -#13505 = DIRECTION('',(1.,0.E+000,0.E+000)); -#13506 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#13507 = DEFINITIONAL_REPRESENTATION('',(#13508),#13512); -#13508 = LINE('',#13509,#13510); -#13509 = CARTESIAN_POINT('',(0.E+000,0.45)); -#13510 = VECTOR('',#13511,1.); -#13511 = DIRECTION('',(1.,2.69486466099E-031)); -#13512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13513 = PCURVE('',#13514,#13519); -#13514 = CYLINDRICAL_SURFACE('',#13515,5.E-002); -#13515 = AXIS2_PLACEMENT_3D('',#13516,#13517,#13518); -#13516 = CARTESIAN_POINT('',(0.45,0.2,0.3)); -#13517 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#13518 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); -#13519 = DEFINITIONAL_REPRESENTATION('',(#13520),#13523); -#13520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13521,#13522),.UNSPECIFIED., +#15875 = CARTESIAN_POINT('',(0.E+000,0.45)); +#15876 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#15877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15878 = ORIENTED_EDGE('',*,*,#15766,.T.); +#15879 = ADVANCED_FACE('',(#15880),#15894,.T.); +#15880 = FACE_BOUND('',#15881,.T.); +#15881 = EDGE_LOOP('',(#15882,#15916,#15943,#15970)); +#15882 = ORIENTED_EDGE('',*,*,#15883,.F.); +#15883 = EDGE_CURVE('',#15884,#15886,#15888,.T.); +#15884 = VERTEX_POINT('',#15885); +#15885 = CARTESIAN_POINT('',(0.5,0.2,0.55)); +#15886 = VERTEX_POINT('',#15887); +#15887 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); +#15888 = SURFACE_CURVE('',#15889,(#15893,#15905),.PCURVE_S1.); +#15889 = LINE('',#15890,#15891); +#15890 = CARTESIAN_POINT('',(0.5,0.2,0.3)); +#15891 = VECTOR('',#15892,1.); +#15892 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#15893 = PCURVE('',#15894,#15899); +#15894 = PLANE('',#15895); +#15895 = AXIS2_PLACEMENT_3D('',#15896,#15897,#15898); +#15896 = CARTESIAN_POINT('',(0.5,-0.25,0.3)); +#15897 = DIRECTION('',(1.,0.E+000,0.E+000)); +#15898 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#15899 = DEFINITIONAL_REPRESENTATION('',(#15900),#15904); +#15900 = LINE('',#15901,#15902); +#15901 = CARTESIAN_POINT('',(0.E+000,0.45)); +#15902 = VECTOR('',#15903,1.); +#15903 = DIRECTION('',(1.,2.69486466099E-031)); +#15904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15905 = PCURVE('',#15906,#15911); +#15906 = CYLINDRICAL_SURFACE('',#15907,5.E-002); +#15907 = AXIS2_PLACEMENT_3D('',#15908,#15909,#15910); +#15908 = CARTESIAN_POINT('',(0.45,0.2,0.3)); +#15909 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#15910 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); +#15911 = DEFINITIONAL_REPRESENTATION('',(#15912),#15915); +#15912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15913,#15914),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#13521 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#13522 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#13523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13524 = ORIENTED_EDGE('',*,*,#13525,.F.); -#13525 = EDGE_CURVE('',#13526,#13492,#13528,.T.); -#13526 = VERTEX_POINT('',#13527); -#13527 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); -#13528 = SURFACE_CURVE('',#13529,(#13533,#13540),.PCURVE_S1.); -#13529 = LINE('',#13530,#13531); -#13530 = CARTESIAN_POINT('',(0.5,-0.25,0.55)); -#13531 = VECTOR('',#13532,1.); -#13532 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13533 = PCURVE('',#13502,#13534); -#13534 = DEFINITIONAL_REPRESENTATION('',(#13535),#13539); -#13535 = LINE('',#13536,#13537); -#13536 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#13537 = VECTOR('',#13538,1.); -#13538 = DIRECTION('',(0.E+000,1.)); -#13539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13540 = PCURVE('',#13541,#13546); -#13541 = CYLINDRICAL_SURFACE('',#13542,5.E-002); -#13542 = AXIS2_PLACEMENT_3D('',#13543,#13544,#13545); -#13543 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); -#13544 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13545 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13546 = DEFINITIONAL_REPRESENTATION('',(#13547),#13550); -#13547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13548,#13549),.UNSPECIFIED., +#15913 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#15914 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#15915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15916 = ORIENTED_EDGE('',*,*,#15917,.F.); +#15917 = EDGE_CURVE('',#15918,#15884,#15920,.T.); +#15918 = VERTEX_POINT('',#15919); +#15919 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); +#15920 = SURFACE_CURVE('',#15921,(#15925,#15932),.PCURVE_S1.); +#15921 = LINE('',#15922,#15923); +#15922 = CARTESIAN_POINT('',(0.5,-0.25,0.55)); +#15923 = VECTOR('',#15924,1.); +#15924 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15925 = PCURVE('',#15894,#15926); +#15926 = DEFINITIONAL_REPRESENTATION('',(#15927),#15931); +#15927 = LINE('',#15928,#15929); +#15928 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#15929 = VECTOR('',#15930,1.); +#15930 = DIRECTION('',(0.E+000,1.)); +#15931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15932 = PCURVE('',#15933,#15938); +#15933 = CYLINDRICAL_SURFACE('',#15934,5.E-002); +#15934 = AXIS2_PLACEMENT_3D('',#15935,#15936,#15937); +#15935 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); +#15936 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15937 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15938 = DEFINITIONAL_REPRESENTATION('',(#15939),#15942); +#15939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15940,#15941),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#13548 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#13549 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#13550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13551 = ORIENTED_EDGE('',*,*,#13552,.F.); -#13552 = EDGE_CURVE('',#13553,#13526,#13555,.T.); -#13553 = VERTEX_POINT('',#13554); -#13554 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); -#13555 = SURFACE_CURVE('',#13556,(#13560,#13567),.PCURVE_S1.); -#13556 = LINE('',#13557,#13558); -#13557 = CARTESIAN_POINT('',(0.5,-0.2,0.3)); -#13558 = VECTOR('',#13559,1.); -#13559 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#13560 = PCURVE('',#13502,#13561); -#13561 = DEFINITIONAL_REPRESENTATION('',(#13562),#13566); -#13562 = LINE('',#13563,#13564); -#13563 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#13564 = VECTOR('',#13565,1.); -#13565 = DIRECTION('',(-1.,-2.69486466099E-031)); -#13566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13567 = PCURVE('',#13568,#13573); -#13568 = CYLINDRICAL_SURFACE('',#13569,5.E-002); -#13569 = AXIS2_PLACEMENT_3D('',#13570,#13571,#13572); -#13570 = CARTESIAN_POINT('',(0.45,-0.2,0.3)); -#13571 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#13572 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); -#13573 = DEFINITIONAL_REPRESENTATION('',(#13574),#13577); -#13574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13575,#13576),.UNSPECIFIED., +#15940 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#15941 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#15942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15943 = ORIENTED_EDGE('',*,*,#15944,.F.); +#15944 = EDGE_CURVE('',#15945,#15918,#15947,.T.); +#15945 = VERTEX_POINT('',#15946); +#15946 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); +#15947 = SURFACE_CURVE('',#15948,(#15952,#15959),.PCURVE_S1.); +#15948 = LINE('',#15949,#15950); +#15949 = CARTESIAN_POINT('',(0.5,-0.2,0.3)); +#15950 = VECTOR('',#15951,1.); +#15951 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#15952 = PCURVE('',#15894,#15953); +#15953 = DEFINITIONAL_REPRESENTATION('',(#15954),#15958); +#15954 = LINE('',#15955,#15956); +#15955 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#15956 = VECTOR('',#15957,1.); +#15957 = DIRECTION('',(-1.,-2.69486466099E-031)); +#15958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15959 = PCURVE('',#15960,#15965); +#15960 = CYLINDRICAL_SURFACE('',#15961,5.E-002); +#15961 = AXIS2_PLACEMENT_3D('',#15962,#15963,#15964); +#15962 = CARTESIAN_POINT('',(0.45,-0.2,0.3)); +#15963 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#15964 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); +#15965 = DEFINITIONAL_REPRESENTATION('',(#15966),#15969); +#15966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15967,#15968),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#13575 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#13576 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#13577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13578 = ORIENTED_EDGE('',*,*,#13579,.F.); -#13579 = EDGE_CURVE('',#13494,#13553,#13580,.T.); -#13580 = SURFACE_CURVE('',#13581,(#13585,#13592),.PCURVE_S1.); -#13581 = LINE('',#13582,#13583); -#13582 = CARTESIAN_POINT('',(0.5,-0.25,5.E-002)); -#13583 = VECTOR('',#13584,1.); -#13584 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#13585 = PCURVE('',#13502,#13586); -#13586 = DEFINITIONAL_REPRESENTATION('',(#13587),#13591); -#13587 = LINE('',#13588,#13589); -#13588 = CARTESIAN_POINT('',(0.25,0.E+000)); -#13589 = VECTOR('',#13590,1.); -#13590 = DIRECTION('',(0.E+000,-1.)); -#13591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13592 = PCURVE('',#13593,#13598); -#13593 = CYLINDRICAL_SURFACE('',#13594,5.E-002); -#13594 = AXIS2_PLACEMENT_3D('',#13595,#13596,#13597); -#13595 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); -#13596 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13597 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13598 = DEFINITIONAL_REPRESENTATION('',(#13599),#13602); -#13599 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13600,#13601),.UNSPECIFIED., +#15967 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#15968 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#15969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15970 = ORIENTED_EDGE('',*,*,#15971,.F.); +#15971 = EDGE_CURVE('',#15886,#15945,#15972,.T.); +#15972 = SURFACE_CURVE('',#15973,(#15977,#15984),.PCURVE_S1.); +#15973 = LINE('',#15974,#15975); +#15974 = CARTESIAN_POINT('',(0.5,-0.25,5.E-002)); +#15975 = VECTOR('',#15976,1.); +#15976 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#15977 = PCURVE('',#15894,#15978); +#15978 = DEFINITIONAL_REPRESENTATION('',(#15979),#15983); +#15979 = LINE('',#15980,#15981); +#15980 = CARTESIAN_POINT('',(0.25,0.E+000)); +#15981 = VECTOR('',#15982,1.); +#15982 = DIRECTION('',(0.E+000,-1.)); +#15983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15984 = PCURVE('',#15985,#15990); +#15985 = CYLINDRICAL_SURFACE('',#15986,5.E-002); +#15986 = AXIS2_PLACEMENT_3D('',#15987,#15988,#15989); +#15987 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); +#15988 = DIRECTION('',(0.E+000,1.,0.E+000)); +#15989 = DIRECTION('',(0.E+000,0.E+000,1.)); +#15990 = DEFINITIONAL_REPRESENTATION('',(#15991),#15994); +#15991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15992,#15993),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#13600 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#13601 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#13602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13603 = ADVANCED_FACE('',(#13604),#12951,.T.); -#13604 = FACE_BOUND('',#13605,.T.); -#13605 = EDGE_LOOP('',(#13606,#13651,#13652,#13697)); -#13606 = ORIENTED_EDGE('',*,*,#13607,.F.); -#13607 = EDGE_CURVE('',#12936,#13608,#13610,.T.); -#13608 = VERTEX_POINT('',#13609); -#13609 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); -#13610 = SURFACE_CURVE('',#13611,(#13616,#13645),.PCURVE_S1.); -#13611 = CIRCLE('',#13612,1.E-002); -#13612 = AXIS2_PLACEMENT_3D('',#13613,#13614,#13615); -#13613 = CARTESIAN_POINT('',(-0.26,-0.2,0.59)); -#13614 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13615 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13616 = PCURVE('',#12951,#13617); -#13617 = DEFINITIONAL_REPRESENTATION('',(#13618),#13644); -#13618 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13619,#13620,#13621,#13622, - #13623,#13624,#13625,#13626,#13627,#13628,#13629,#13630,#13631, - #13632,#13633,#13634,#13635,#13636,#13637,#13638,#13639,#13640, - #13641,#13642,#13643),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#15992 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#15993 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#15994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#15995 = ADVANCED_FACE('',(#15996),#15343,.T.); +#15996 = FACE_BOUND('',#15997,.T.); +#15997 = EDGE_LOOP('',(#15998,#16043,#16044,#16089)); +#15998 = ORIENTED_EDGE('',*,*,#15999,.F.); +#15999 = EDGE_CURVE('',#15328,#16000,#16002,.T.); +#16000 = VERTEX_POINT('',#16001); +#16001 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); +#16002 = SURFACE_CURVE('',#16003,(#16008,#16037),.PCURVE_S1.); +#16003 = CIRCLE('',#16004,1.E-002); +#16004 = AXIS2_PLACEMENT_3D('',#16005,#16006,#16007); +#16005 = CARTESIAN_POINT('',(-0.26,-0.2,0.59)); +#16006 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16007 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16008 = PCURVE('',#15343,#16009); +#16009 = DEFINITIONAL_REPRESENTATION('',(#16010),#16036); +#16010 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16011,#16012,#16013,#16014, + #16015,#16016,#16017,#16018,#16019,#16020,#16021,#16022,#16023, + #16024,#16025,#16026,#16027,#16028,#16029,#16030,#16031,#16032, + #16033,#16034,#16035),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -16424,60 +19413,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#13619 = CARTESIAN_POINT('',(0.E+000,1.)); -#13620 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#13621 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#13622 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#13623 = CARTESIAN_POINT('',(0.145724913075,1.)); -#13624 = CARTESIAN_POINT('',(0.192043637223,1.)); -#13625 = CARTESIAN_POINT('',(0.237526724423,1.)); -#13626 = CARTESIAN_POINT('',(0.282309422539,1.)); -#13627 = CARTESIAN_POINT('',(0.326519436214,1.)); -#13628 = CARTESIAN_POINT('',(0.370278310591,1.)); -#13629 = CARTESIAN_POINT('',(0.413702852292,1.)); -#13630 = CARTESIAN_POINT('',(0.456906394885,1.)); -#13631 = CARTESIAN_POINT('',(0.5,1.)); -#13632 = CARTESIAN_POINT('',(0.543093605115,1.)); -#13633 = CARTESIAN_POINT('',(0.586297147708,1.)); -#13634 = CARTESIAN_POINT('',(0.629721689409,1.)); -#13635 = CARTESIAN_POINT('',(0.673480563786,1.)); -#13636 = CARTESIAN_POINT('',(0.717690577461,1.)); -#13637 = CARTESIAN_POINT('',(0.762473275577,1.)); -#13638 = CARTESIAN_POINT('',(0.807956362777,1.)); -#13639 = CARTESIAN_POINT('',(0.854275086925,1.)); -#13640 = CARTESIAN_POINT('',(0.901574474096,1.)); -#13641 = CARTESIAN_POINT('',(0.950009297011,1.)); -#13642 = CARTESIAN_POINT('',(0.983172198663,1.)); -#13643 = CARTESIAN_POINT('',(1.,1.)); -#13644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13645 = PCURVE('',#13476,#13646); -#13646 = DEFINITIONAL_REPRESENTATION('',(#13647),#13650); -#13647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13648,#13649),.UNSPECIFIED., +#16011 = CARTESIAN_POINT('',(0.E+000,1.)); +#16012 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#16013 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#16014 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16015 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16016 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16017 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16018 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16019 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16020 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16021 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16022 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16023 = CARTESIAN_POINT('',(0.5,1.)); +#16024 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16025 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16026 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16027 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16028 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16029 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16030 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16031 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16032 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16033 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16034 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16035 = CARTESIAN_POINT('',(1.,1.)); +#16036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16037 = PCURVE('',#15868,#16038); +#16038 = DEFINITIONAL_REPRESENTATION('',(#16039),#16042); +#16039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16040,#16041),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#13648 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#13649 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#13650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13651 = ORIENTED_EDGE('',*,*,#12935,.T.); -#13652 = ORIENTED_EDGE('',*,*,#13653,.F.); -#13653 = EDGE_CURVE('',#13654,#12914,#13656,.T.); -#13654 = VERTEX_POINT('',#13655); -#13655 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); -#13656 = SURFACE_CURVE('',#13657,(#13662,#13691),.PCURVE_S1.); -#13657 = CIRCLE('',#13658,1.E-002); -#13658 = AXIS2_PLACEMENT_3D('',#13659,#13660,#13661); -#13659 = CARTESIAN_POINT('',(-0.26,-0.24,0.55)); -#13660 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); -#13661 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); -#13662 = PCURVE('',#12951,#13663); -#13663 = DEFINITIONAL_REPRESENTATION('',(#13664),#13690); -#13664 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13665,#13666,#13667,#13668, - #13669,#13670,#13671,#13672,#13673,#13674,#13675,#13676,#13677, - #13678,#13679,#13680,#13681,#13682,#13683,#13684,#13685,#13686, - #13687,#13688,#13689),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16040 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#16041 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#16042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16043 = ORIENTED_EDGE('',*,*,#15327,.T.); +#16044 = ORIENTED_EDGE('',*,*,#16045,.F.); +#16045 = EDGE_CURVE('',#16046,#15306,#16048,.T.); +#16046 = VERTEX_POINT('',#16047); +#16047 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); +#16048 = SURFACE_CURVE('',#16049,(#16054,#16083),.PCURVE_S1.); +#16049 = CIRCLE('',#16050,1.E-002); +#16050 = AXIS2_PLACEMENT_3D('',#16051,#16052,#16053); +#16051 = CARTESIAN_POINT('',(-0.26,-0.24,0.55)); +#16052 = DIRECTION('',(0.E+000,2.595054858731E-031,-1.)); +#16053 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); +#16054 = PCURVE('',#15343,#16055); +#16055 = DEFINITIONAL_REPRESENTATION('',(#16056),#16082); +#16056 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16057,#16058,#16059,#16060, + #16061,#16062,#16063,#16064,#16065,#16066,#16067,#16068,#16069, + #16070,#16071,#16072,#16073,#16074,#16075,#16076,#16077,#16078, + #16079,#16080,#16081),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -16485,59 +19474,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#13665 = CARTESIAN_POINT('',(1.,0.E+000)); -#13666 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#13667 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#13668 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#13669 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#13670 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#13671 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#13672 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#13673 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#13674 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#13675 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#13676 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#13677 = CARTESIAN_POINT('',(0.5,0.E+000)); -#13678 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#13679 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#13680 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#13681 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#13682 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#13683 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#13684 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#13685 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#13686 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#13687 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); -#13688 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#13689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#13690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13691 = PCURVE('',#13058,#13692); -#13692 = DEFINITIONAL_REPRESENTATION('',(#13693),#13696); -#13693 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13694,#13695),.UNSPECIFIED., +#16057 = CARTESIAN_POINT('',(1.,0.E+000)); +#16058 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16059 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16060 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16061 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16062 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16063 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16064 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16065 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16066 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16067 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16068 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16069 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16070 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16071 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16072 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16073 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16074 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16075 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16076 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16077 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16078 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16079 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); +#16080 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#16081 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16083 = PCURVE('',#15450,#16084); +#16084 = DEFINITIONAL_REPRESENTATION('',(#16085),#16088); +#16085 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16086,#16087),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#13694 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#13695 = CARTESIAN_POINT('',(0.E+000,0.25)); -#13696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16086 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#16087 = CARTESIAN_POINT('',(0.E+000,0.25)); +#16088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13697 = ORIENTED_EDGE('',*,*,#13698,.F.); -#13698 = EDGE_CURVE('',#13608,#13654,#13699,.T.); -#13699 = SURFACE_CURVE('',#13700,(#13705,#13734),.PCURVE_S1.); -#13700 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13701,#13702,#13703,#13704), +#16089 = ORIENTED_EDGE('',*,*,#16090,.F.); +#16090 = EDGE_CURVE('',#16000,#16046,#16091,.T.); +#16091 = SURFACE_CURVE('',#16092,(#16097,#16126),.PCURVE_S1.); +#16092 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16093,#16094,#16095,#16096), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#13701 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); -#13702 = CARTESIAN_POINT('',(-0.25,-0.222012399811,0.589675836708)); -#13703 = CARTESIAN_POINT('',(-0.25,-0.239663944536,0.572819941129)); -#13704 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); -#13705 = PCURVE('',#12951,#13706); -#13706 = DEFINITIONAL_REPRESENTATION('',(#13707),#13733); -#13707 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13708,#13709,#13710,#13711, - #13712,#13713,#13714,#13715,#13716,#13717,#13718,#13719,#13720, - #13721,#13722,#13723,#13724,#13725,#13726,#13727,#13728,#13729, - #13730,#13731,#13732),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16093 = CARTESIAN_POINT('',(-0.25,-0.2,0.59)); +#16094 = CARTESIAN_POINT('',(-0.25,-0.222012399811,0.589675836708)); +#16095 = CARTESIAN_POINT('',(-0.25,-0.239663944536,0.572819941129)); +#16096 = CARTESIAN_POINT('',(-0.25,-0.24,0.55)); +#16097 = PCURVE('',#15343,#16098); +#16098 = DEFINITIONAL_REPRESENTATION('',(#16099),#16125); +#16099 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16100,#16101,#16102,#16103, + #16104,#16105,#16106,#16107,#16108,#16109,#16110,#16111,#16112, + #16113,#16114,#16115,#16116,#16117,#16118,#16119,#16120,#16121, + #16122,#16123,#16124),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -16545,76 +19534,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#13708 = CARTESIAN_POINT('',(1.,1.)); -#13709 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#13710 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#13711 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#13712 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); -#13713 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); -#13714 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#13715 = CARTESIAN_POINT('',(1.000601540492,0.714599645879)); -#13716 = CARTESIAN_POINT('',(1.000600014196,0.67137508889)); -#13717 = CARTESIAN_POINT('',(1.000606368831,0.628804305407)); -#13718 = CARTESIAN_POINT('',(1.000582476584,0.586710614182)); -#13719 = CARTESIAN_POINT('',(1.000671690938,0.544924984711)); -#13720 = CARTESIAN_POINT('',(1.000081825934,0.503282378115)); -#13721 = CARTESIAN_POINT('',(0.999949652391,0.461618222946)); -#13722 = CARTESIAN_POINT('',(0.999980640293,0.419764925537)); -#13723 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#13724 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#13725 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#13726 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#13727 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#13728 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#13729 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#13730 = CARTESIAN_POINT('',(1.000709884619,5.402886517653E-002)); -#13731 = CARTESIAN_POINT('',(1.000367478029,1.83320056513E-002)); -#13732 = CARTESIAN_POINT('',(1.,0.E+000)); -#13733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13734 = PCURVE('',#11925,#13735); -#13735 = DEFINITIONAL_REPRESENTATION('',(#13736),#13741); -#13736 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13737,#13738,#13739,#13740), +#16100 = CARTESIAN_POINT('',(1.,1.)); +#16101 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#16102 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#16103 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#16104 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); +#16105 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); +#16106 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#16107 = CARTESIAN_POINT('',(1.000601540492,0.714599645879)); +#16108 = CARTESIAN_POINT('',(1.000600014196,0.67137508889)); +#16109 = CARTESIAN_POINT('',(1.000606368831,0.628804305407)); +#16110 = CARTESIAN_POINT('',(1.000582476584,0.586710614182)); +#16111 = CARTESIAN_POINT('',(1.000671690938,0.544924984711)); +#16112 = CARTESIAN_POINT('',(1.000081825934,0.503282378115)); +#16113 = CARTESIAN_POINT('',(0.999949652391,0.461618222946)); +#16114 = CARTESIAN_POINT('',(0.999980640293,0.419764925537)); +#16115 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#16116 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#16117 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#16118 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#16119 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#16120 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#16121 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#16122 = CARTESIAN_POINT('',(1.000709884619,5.402886517653E-002)); +#16123 = CARTESIAN_POINT('',(1.000367478029,1.83320056513E-002)); +#16124 = CARTESIAN_POINT('',(1.,0.E+000)); +#16125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16126 = PCURVE('',#14317,#16127); +#16127 = DEFINITIONAL_REPRESENTATION('',(#16128),#16133); +#16128 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16129,#16130,#16131,#16132), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#13737 = CARTESIAN_POINT('',(-0.29,5.E-002)); -#13738 = CARTESIAN_POINT('',(-0.289675836708,2.79876001892E-002)); -#13739 = CARTESIAN_POINT('',(-0.272819941129,1.033605546414E-002)); -#13740 = CARTESIAN_POINT('',(-0.25,1.E-002)); -#13741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13742 = ADVANCED_FACE('',(#13743),#13058,.T.); -#13743 = FACE_BOUND('',#13744,.T.); -#13744 = EDGE_LOOP('',(#13745,#13746,#13747,#13792)); -#13745 = ORIENTED_EDGE('',*,*,#13653,.T.); -#13746 = ORIENTED_EDGE('',*,*,#13044,.T.); -#13747 = ORIENTED_EDGE('',*,*,#13748,.F.); -#13748 = EDGE_CURVE('',#13749,#13023,#13751,.T.); -#13749 = VERTEX_POINT('',#13750); -#13750 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); -#13751 = SURFACE_CURVE('',#13752,(#13757,#13763),.PCURVE_S1.); -#13752 = CIRCLE('',#13753,1.E-002); -#13753 = AXIS2_PLACEMENT_3D('',#13754,#13755,#13756); -#13754 = CARTESIAN_POINT('',(-0.26,-0.24,5.E-002)); -#13755 = DIRECTION('',(0.E+000,1.224646799147E-016,-1.)); -#13756 = DIRECTION('',(0.E+000,-1.,-1.224646799147E-016)); -#13757 = PCURVE('',#13058,#13758); -#13758 = DEFINITIONAL_REPRESENTATION('',(#13759),#13762); -#13759 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13760,#13761),.UNSPECIFIED., +#16129 = CARTESIAN_POINT('',(-0.29,5.E-002)); +#16130 = CARTESIAN_POINT('',(-0.289675836708,2.79876001892E-002)); +#16131 = CARTESIAN_POINT('',(-0.272819941129,1.033605546414E-002)); +#16132 = CARTESIAN_POINT('',(-0.25,1.E-002)); +#16133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16134 = ADVANCED_FACE('',(#16135),#15450,.T.); +#16135 = FACE_BOUND('',#16136,.T.); +#16136 = EDGE_LOOP('',(#16137,#16138,#16139,#16184)); +#16137 = ORIENTED_EDGE('',*,*,#16045,.T.); +#16138 = ORIENTED_EDGE('',*,*,#15436,.T.); +#16139 = ORIENTED_EDGE('',*,*,#16140,.F.); +#16140 = EDGE_CURVE('',#16141,#15415,#16143,.T.); +#16141 = VERTEX_POINT('',#16142); +#16142 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); +#16143 = SURFACE_CURVE('',#16144,(#16149,#16155),.PCURVE_S1.); +#16144 = CIRCLE('',#16145,1.E-002); +#16145 = AXIS2_PLACEMENT_3D('',#16146,#16147,#16148); +#16146 = CARTESIAN_POINT('',(-0.26,-0.24,5.E-002)); +#16147 = DIRECTION('',(0.E+000,1.224646799147E-016,-1.)); +#16148 = DIRECTION('',(0.E+000,-1.,-1.224646799147E-016)); +#16149 = PCURVE('',#15450,#16150); +#16150 = DEFINITIONAL_REPRESENTATION('',(#16151),#16154); +#16151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16152,#16153),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#13760 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#13761 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#13762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16152 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#16153 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#16154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13763 = PCURVE('',#13109,#13764); -#13764 = DEFINITIONAL_REPRESENTATION('',(#13765),#13791); -#13765 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13766,#13767,#13768,#13769, - #13770,#13771,#13772,#13773,#13774,#13775,#13776,#13777,#13778, - #13779,#13780,#13781,#13782,#13783,#13784,#13785,#13786,#13787, - #13788,#13789,#13790),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16155 = PCURVE('',#15501,#16156); +#16156 = DEFINITIONAL_REPRESENTATION('',(#16157),#16183); +#16157 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16158,#16159,#16160,#16161, + #16162,#16163,#16164,#16165,#16166,#16167,#16168,#16169,#16170, + #16171,#16172,#16173,#16174,#16175,#16176,#16177,#16178,#16179, + #16180,#16181,#16182),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -16622,80 +19611,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#13766 = CARTESIAN_POINT('',(1.,1.)); -#13767 = CARTESIAN_POINT('',(0.983172198663,1.)); -#13768 = CARTESIAN_POINT('',(0.950009297011,1.)); -#13769 = CARTESIAN_POINT('',(0.901574474096,1.)); -#13770 = CARTESIAN_POINT('',(0.854275086925,1.)); -#13771 = CARTESIAN_POINT('',(0.807956362777,1.)); -#13772 = CARTESIAN_POINT('',(0.762473275577,1.)); -#13773 = CARTESIAN_POINT('',(0.717690577461,1.)); -#13774 = CARTESIAN_POINT('',(0.673480563786,1.)); -#13775 = CARTESIAN_POINT('',(0.629721689409,1.)); -#13776 = CARTESIAN_POINT('',(0.586297147708,1.)); -#13777 = CARTESIAN_POINT('',(0.543093605115,1.)); -#13778 = CARTESIAN_POINT('',(0.5,1.)); -#13779 = CARTESIAN_POINT('',(0.456906394885,1.)); -#13780 = CARTESIAN_POINT('',(0.413702852292,1.)); -#13781 = CARTESIAN_POINT('',(0.370278310591,1.)); -#13782 = CARTESIAN_POINT('',(0.326519436214,1.)); -#13783 = CARTESIAN_POINT('',(0.282309422539,1.)); -#13784 = CARTESIAN_POINT('',(0.237526724423,1.)); -#13785 = CARTESIAN_POINT('',(0.192043637223,1.)); -#13786 = CARTESIAN_POINT('',(0.145724913075,1.)); -#13787 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#13788 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#13789 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#13790 = CARTESIAN_POINT('',(0.E+000,1.)); -#13791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13792 = ORIENTED_EDGE('',*,*,#13793,.F.); -#13793 = EDGE_CURVE('',#13654,#13749,#13794,.T.); -#13794 = SURFACE_CURVE('',#13795,(#13799,#13805),.PCURVE_S1.); -#13795 = LINE('',#13796,#13797); -#13796 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); -#13797 = VECTOR('',#13798,1.); -#13798 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#13799 = PCURVE('',#13058,#13800); -#13800 = DEFINITIONAL_REPRESENTATION('',(#13801),#13804); -#13801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13802,#13803),.UNSPECIFIED., +#16158 = CARTESIAN_POINT('',(1.,1.)); +#16159 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16160 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16161 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16162 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16163 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16164 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16165 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16166 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16167 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16168 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16169 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16170 = CARTESIAN_POINT('',(0.5,1.)); +#16171 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16172 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16173 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16174 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16175 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16176 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16177 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16178 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16179 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16180 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#16181 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#16182 = CARTESIAN_POINT('',(0.E+000,1.)); +#16183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16184 = ORIENTED_EDGE('',*,*,#16185,.F.); +#16185 = EDGE_CURVE('',#16046,#16141,#16186,.T.); +#16186 = SURFACE_CURVE('',#16187,(#16191,#16197),.PCURVE_S1.); +#16187 = LINE('',#16188,#16189); +#16188 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); +#16189 = VECTOR('',#16190,1.); +#16190 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#16191 = PCURVE('',#15450,#16192); +#16192 = DEFINITIONAL_REPRESENTATION('',(#16193),#16196); +#16193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16194,#16195),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#13802 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#13803 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#13804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13805 = PCURVE('',#11925,#13806); -#13806 = DEFINITIONAL_REPRESENTATION('',(#13807),#13811); -#13807 = LINE('',#13808,#13809); -#13808 = CARTESIAN_POINT('',(0.E+000,1.E-002)); -#13809 = VECTOR('',#13810,1.); -#13810 = DIRECTION('',(1.,0.E+000)); -#13811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13812 = ADVANCED_FACE('',(#13813),#13109,.T.); -#13813 = FACE_BOUND('',#13814,.T.); -#13814 = EDGE_LOOP('',(#13815,#13816,#13817,#13862)); -#13815 = ORIENTED_EDGE('',*,*,#13748,.T.); -#13816 = ORIENTED_EDGE('',*,*,#13095,.T.); -#13817 = ORIENTED_EDGE('',*,*,#13818,.F.); -#13818 = EDGE_CURVE('',#13819,#13074,#13821,.T.); -#13819 = VERTEX_POINT('',#13820); -#13820 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); -#13821 = SURFACE_CURVE('',#13822,(#13827,#13856),.PCURVE_S1.); -#13822 = CIRCLE('',#13823,1.E-002); -#13823 = AXIS2_PLACEMENT_3D('',#13824,#13825,#13826); -#13824 = CARTESIAN_POINT('',(-0.26,-0.2,1.E-002)); -#13825 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13826 = DIRECTION('',(0.E+000,0.E+000,1.)); -#13827 = PCURVE('',#13109,#13828); -#13828 = DEFINITIONAL_REPRESENTATION('',(#13829),#13855); -#13829 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13830,#13831,#13832,#13833, - #13834,#13835,#13836,#13837,#13838,#13839,#13840,#13841,#13842, - #13843,#13844,#13845,#13846,#13847,#13848,#13849,#13850,#13851, - #13852,#13853,#13854),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16194 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#16195 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#16196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16197 = PCURVE('',#14317,#16198); +#16198 = DEFINITIONAL_REPRESENTATION('',(#16199),#16203); +#16199 = LINE('',#16200,#16201); +#16200 = CARTESIAN_POINT('',(0.E+000,1.E-002)); +#16201 = VECTOR('',#16202,1.); +#16202 = DIRECTION('',(1.,0.E+000)); +#16203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16204 = ADVANCED_FACE('',(#16205),#15501,.T.); +#16205 = FACE_BOUND('',#16206,.T.); +#16206 = EDGE_LOOP('',(#16207,#16208,#16209,#16254)); +#16207 = ORIENTED_EDGE('',*,*,#16140,.T.); +#16208 = ORIENTED_EDGE('',*,*,#15487,.T.); +#16209 = ORIENTED_EDGE('',*,*,#16210,.F.); +#16210 = EDGE_CURVE('',#16211,#15466,#16213,.T.); +#16211 = VERTEX_POINT('',#16212); +#16212 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); +#16213 = SURFACE_CURVE('',#16214,(#16219,#16248),.PCURVE_S1.); +#16214 = CIRCLE('',#16215,1.E-002); +#16215 = AXIS2_PLACEMENT_3D('',#16216,#16217,#16218); +#16216 = CARTESIAN_POINT('',(-0.26,-0.2,1.E-002)); +#16217 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16218 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16219 = PCURVE('',#15501,#16220); +#16220 = DEFINITIONAL_REPRESENTATION('',(#16221),#16247); +#16221 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16222,#16223,#16224,#16225, + #16226,#16227,#16228,#16229,#16230,#16231,#16232,#16233,#16234, + #16235,#16236,#16237,#16238,#16239,#16240,#16241,#16242,#16243, + #16244,#16245,#16246),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -16703,60 +19692,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#13830 = CARTESIAN_POINT('',(1.,0.E+000)); -#13831 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#13832 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#13833 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#13834 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#13835 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#13836 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#13837 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#13838 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#13839 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#13840 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#13841 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#13842 = CARTESIAN_POINT('',(0.5,0.E+000)); -#13843 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#13844 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#13845 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#13846 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#13847 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#13848 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#13849 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#13850 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#13851 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#13852 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#13853 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#13854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#13855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13856 = PCURVE('',#13196,#13857); -#13857 = DEFINITIONAL_REPRESENTATION('',(#13858),#13861); -#13858 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13859,#13860),.UNSPECIFIED., +#16222 = CARTESIAN_POINT('',(1.,0.E+000)); +#16223 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16224 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16225 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16226 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16227 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16228 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16229 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16230 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16231 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16232 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16233 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16234 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16235 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16236 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16237 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16238 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16239 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16240 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16241 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16242 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16243 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16244 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#16245 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#16246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16248 = PCURVE('',#15588,#16249); +#16249 = DEFINITIONAL_REPRESENTATION('',(#16250),#16253); +#16250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16251,#16252),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#13859 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#13860 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#13861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16251 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#16252 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#16253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13862 = ORIENTED_EDGE('',*,*,#13863,.F.); -#13863 = EDGE_CURVE('',#13749,#13819,#13864,.T.); -#13864 = SURFACE_CURVE('',#13865,(#13870,#13899),.PCURVE_S1.); -#13865 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13866,#13867,#13868,#13869), +#16254 = ORIENTED_EDGE('',*,*,#16255,.F.); +#16255 = EDGE_CURVE('',#16141,#16211,#16256,.T.); +#16256 = SURFACE_CURVE('',#16257,(#16262,#16291),.PCURVE_S1.); +#16257 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16258,#16259,#16260,#16261), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#13866 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); -#13867 = CARTESIAN_POINT('',(-0.25,-0.239675836708,2.79876001892E-002)); -#13868 = CARTESIAN_POINT('',(-0.25,-0.222819941129,1.033605546414E-002) - ); -#13869 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); -#13870 = PCURVE('',#13109,#13871); -#13871 = DEFINITIONAL_REPRESENTATION('',(#13872),#13898); -#13872 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13873,#13874,#13875,#13876, - #13877,#13878,#13879,#13880,#13881,#13882,#13883,#13884,#13885, - #13886,#13887,#13888,#13889,#13890,#13891,#13892,#13893,#13894, - #13895,#13896,#13897),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16258 = CARTESIAN_POINT('',(-0.25,-0.24,5.E-002)); +#16259 = CARTESIAN_POINT('',(-0.25,-0.239675836708,2.79876001892E-002)); +#16260 = CARTESIAN_POINT('',(-0.25,-0.222819941129,1.033605546414E-002) + ); +#16261 = CARTESIAN_POINT('',(-0.25,-0.2,1.E-002)); +#16262 = PCURVE('',#15501,#16263); +#16263 = DEFINITIONAL_REPRESENTATION('',(#16264),#16290); +#16264 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16265,#16266,#16267,#16268, + #16269,#16270,#16271,#16272,#16273,#16274,#16275,#16276,#16277, + #16278,#16279,#16280,#16281,#16282,#16283,#16284,#16285,#16286, + #16287,#16288,#16289),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -16764,76 +19753,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#13873 = CARTESIAN_POINT('',(1.,1.)); -#13874 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#13875 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#13876 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#13877 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); -#13878 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); -#13879 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#13880 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); -#13881 = CARTESIAN_POINT('',(1.000600014196,0.671375088893)); -#13882 = CARTESIAN_POINT('',(1.000606368831,0.628804305396)); -#13883 = CARTESIAN_POINT('',(1.000582476584,0.586710614224)); -#13884 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); -#13885 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); -#13886 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); -#13887 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#13888 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#13889 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#13890 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#13891 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#13892 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#13893 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#13894 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#13895 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); -#13896 = CARTESIAN_POINT('',(1.000367478029,1.833200565131E-002)); -#13897 = CARTESIAN_POINT('',(1.,0.E+000)); -#13898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13899 = PCURVE('',#11925,#13900); -#13900 = DEFINITIONAL_REPRESENTATION('',(#13901),#13906); -#13901 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13902,#13903,#13904,#13905), +#16265 = CARTESIAN_POINT('',(1.,1.)); +#16266 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#16267 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#16268 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#16269 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); +#16270 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); +#16271 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#16272 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); +#16273 = CARTESIAN_POINT('',(1.000600014196,0.671375088893)); +#16274 = CARTESIAN_POINT('',(1.000606368831,0.628804305396)); +#16275 = CARTESIAN_POINT('',(1.000582476584,0.586710614224)); +#16276 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); +#16277 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); +#16278 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); +#16279 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#16280 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#16281 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#16282 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#16283 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#16284 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#16285 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#16286 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#16287 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); +#16288 = CARTESIAN_POINT('',(1.000367478029,1.833200565131E-002)); +#16289 = CARTESIAN_POINT('',(1.,0.E+000)); +#16290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16291 = PCURVE('',#14317,#16292); +#16292 = DEFINITIONAL_REPRESENTATION('',(#16293),#16298); +#16293 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16294,#16295,#16296,#16297), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#13902 = CARTESIAN_POINT('',(0.25,1.E-002)); -#13903 = CARTESIAN_POINT('',(0.272012399811,1.032416329181E-002)); -#13904 = CARTESIAN_POINT('',(0.289663944536,2.718005887099E-002)); -#13905 = CARTESIAN_POINT('',(0.29,5.E-002)); -#13906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13907 = ADVANCED_FACE('',(#13908),#13196,.T.); -#13908 = FACE_BOUND('',#13909,.T.); -#13909 = EDGE_LOOP('',(#13910,#13911,#13912,#13957)); -#13910 = ORIENTED_EDGE('',*,*,#13818,.T.); -#13911 = ORIENTED_EDGE('',*,*,#13182,.T.); -#13912 = ORIENTED_EDGE('',*,*,#13913,.F.); -#13913 = EDGE_CURVE('',#13914,#13161,#13916,.T.); -#13914 = VERTEX_POINT('',#13915); -#13915 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); -#13916 = SURFACE_CURVE('',#13917,(#13922,#13928),.PCURVE_S1.); -#13917 = CIRCLE('',#13918,1.E-002); -#13918 = AXIS2_PLACEMENT_3D('',#13919,#13920,#13921); -#13919 = CARTESIAN_POINT('',(-0.26,0.2,1.E-002)); -#13920 = DIRECTION('',(0.E+000,1.,6.123233995737E-017)); -#13921 = DIRECTION('',(0.E+000,6.123233995737E-017,-1.)); -#13922 = PCURVE('',#13196,#13923); -#13923 = DEFINITIONAL_REPRESENTATION('',(#13924),#13927); -#13924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13925,#13926),.UNSPECIFIED., +#16294 = CARTESIAN_POINT('',(0.25,1.E-002)); +#16295 = CARTESIAN_POINT('',(0.272012399811,1.032416329181E-002)); +#16296 = CARTESIAN_POINT('',(0.289663944536,2.718005887099E-002)); +#16297 = CARTESIAN_POINT('',(0.29,5.E-002)); +#16298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16299 = ADVANCED_FACE('',(#16300),#15588,.T.); +#16300 = FACE_BOUND('',#16301,.T.); +#16301 = EDGE_LOOP('',(#16302,#16303,#16304,#16349)); +#16302 = ORIENTED_EDGE('',*,*,#16210,.T.); +#16303 = ORIENTED_EDGE('',*,*,#15574,.T.); +#16304 = ORIENTED_EDGE('',*,*,#16305,.F.); +#16305 = EDGE_CURVE('',#16306,#15553,#16308,.T.); +#16306 = VERTEX_POINT('',#16307); +#16307 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); +#16308 = SURFACE_CURVE('',#16309,(#16314,#16320),.PCURVE_S1.); +#16309 = CIRCLE('',#16310,1.E-002); +#16310 = AXIS2_PLACEMENT_3D('',#16311,#16312,#16313); +#16311 = CARTESIAN_POINT('',(-0.26,0.2,1.E-002)); +#16312 = DIRECTION('',(0.E+000,1.,6.123233995737E-017)); +#16313 = DIRECTION('',(0.E+000,6.123233995737E-017,-1.)); +#16314 = PCURVE('',#15588,#16315); +#16315 = DEFINITIONAL_REPRESENTATION('',(#16316),#16319); +#16316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16317,#16318),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#13925 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#13926 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#13927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16317 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#16318 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#16319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#13928 = PCURVE('',#13271,#13929); -#13929 = DEFINITIONAL_REPRESENTATION('',(#13930),#13956); -#13930 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13931,#13932,#13933,#13934, - #13935,#13936,#13937,#13938,#13939,#13940,#13941,#13942,#13943, - #13944,#13945,#13946,#13947,#13948,#13949,#13950,#13951,#13952, - #13953,#13954,#13955),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16320 = PCURVE('',#15663,#16321); +#16321 = DEFINITIONAL_REPRESENTATION('',(#16322),#16348); +#16322 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16323,#16324,#16325,#16326, + #16327,#16328,#16329,#16330,#16331,#16332,#16333,#16334,#16335, + #16336,#16337,#16338,#16339,#16340,#16341,#16342,#16343,#16344, + #16345,#16346,#16347),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -16841,78 +19830,78 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#13931 = CARTESIAN_POINT('',(1.,1.)); -#13932 = CARTESIAN_POINT('',(0.983172198663,1.)); -#13933 = CARTESIAN_POINT('',(0.950009297011,1.)); -#13934 = CARTESIAN_POINT('',(0.901574474096,1.)); -#13935 = CARTESIAN_POINT('',(0.854275086925,1.)); -#13936 = CARTESIAN_POINT('',(0.807956362777,1.)); -#13937 = CARTESIAN_POINT('',(0.762473275577,1.)); -#13938 = CARTESIAN_POINT('',(0.717690577461,1.)); -#13939 = CARTESIAN_POINT('',(0.673480563786,1.)); -#13940 = CARTESIAN_POINT('',(0.629721689409,1.)); -#13941 = CARTESIAN_POINT('',(0.586297147708,1.)); -#13942 = CARTESIAN_POINT('',(0.543093605115,1.)); -#13943 = CARTESIAN_POINT('',(0.5,1.)); -#13944 = CARTESIAN_POINT('',(0.456906394885,1.)); -#13945 = CARTESIAN_POINT('',(0.413702852292,1.)); -#13946 = CARTESIAN_POINT('',(0.370278310591,1.)); -#13947 = CARTESIAN_POINT('',(0.326519436214,1.)); -#13948 = CARTESIAN_POINT('',(0.282309422539,1.)); -#13949 = CARTESIAN_POINT('',(0.237526724423,1.)); -#13950 = CARTESIAN_POINT('',(0.192043637223,1.)); -#13951 = CARTESIAN_POINT('',(0.145724913075,1.)); -#13952 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#13953 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#13954 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#13955 = CARTESIAN_POINT('',(0.E+000,1.)); -#13956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13957 = ORIENTED_EDGE('',*,*,#13958,.F.); -#13958 = EDGE_CURVE('',#13819,#13914,#13959,.T.); -#13959 = SURFACE_CURVE('',#13960,(#13964,#13970),.PCURVE_S1.); -#13960 = LINE('',#13961,#13962); -#13961 = CARTESIAN_POINT('',(-0.25,-0.25,1.E-002)); -#13962 = VECTOR('',#13963,1.); -#13963 = DIRECTION('',(0.E+000,1.,0.E+000)); -#13964 = PCURVE('',#13196,#13965); -#13965 = DEFINITIONAL_REPRESENTATION('',(#13966),#13969); -#13966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#13967,#13968),.UNSPECIFIED., +#16323 = CARTESIAN_POINT('',(1.,1.)); +#16324 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16325 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16326 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16327 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16328 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16329 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16330 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16331 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16332 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16333 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16334 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16335 = CARTESIAN_POINT('',(0.5,1.)); +#16336 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16337 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16338 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16339 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16340 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16341 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16342 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16343 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16344 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16345 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#16346 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#16347 = CARTESIAN_POINT('',(0.E+000,1.)); +#16348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16349 = ORIENTED_EDGE('',*,*,#16350,.F.); +#16350 = EDGE_CURVE('',#16211,#16306,#16351,.T.); +#16351 = SURFACE_CURVE('',#16352,(#16356,#16362),.PCURVE_S1.); +#16352 = LINE('',#16353,#16354); +#16353 = CARTESIAN_POINT('',(-0.25,-0.25,1.E-002)); +#16354 = VECTOR('',#16355,1.); +#16355 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16356 = PCURVE('',#15588,#16357); +#16357 = DEFINITIONAL_REPRESENTATION('',(#16358),#16361); +#16358 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16359,#16360),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#13967 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#13968 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#13969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13970 = PCURVE('',#11925,#13971); -#13971 = DEFINITIONAL_REPRESENTATION('',(#13972),#13976); -#13972 = LINE('',#13973,#13974); -#13973 = CARTESIAN_POINT('',(0.29,0.E+000)); -#13974 = VECTOR('',#13975,1.); -#13975 = DIRECTION('',(0.E+000,1.)); -#13976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#13977 = ADVANCED_FACE('',(#13978),#13271,.T.); -#13978 = FACE_BOUND('',#13979,.T.); -#13979 = EDGE_LOOP('',(#13980,#14025,#14070,#14071)); -#13980 = ORIENTED_EDGE('',*,*,#13981,.F.); -#13981 = EDGE_CURVE('',#13982,#13213,#13984,.T.); -#13982 = VERTEX_POINT('',#13983); -#13983 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); -#13984 = SURFACE_CURVE('',#13985,(#13990,#14019),.PCURVE_S1.); -#13985 = CIRCLE('',#13986,1.E-002); -#13986 = AXIS2_PLACEMENT_3D('',#13987,#13988,#13989); -#13987 = CARTESIAN_POINT('',(-0.26,0.24,5.E-002)); -#13988 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); -#13989 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); -#13990 = PCURVE('',#13271,#13991); -#13991 = DEFINITIONAL_REPRESENTATION('',(#13992),#14018); -#13992 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#13993,#13994,#13995,#13996, - #13997,#13998,#13999,#14000,#14001,#14002,#14003,#14004,#14005, - #14006,#14007,#14008,#14009,#14010,#14011,#14012,#14013,#14014, - #14015,#14016,#14017),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16359 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#16360 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#16361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16362 = PCURVE('',#14317,#16363); +#16363 = DEFINITIONAL_REPRESENTATION('',(#16364),#16368); +#16364 = LINE('',#16365,#16366); +#16365 = CARTESIAN_POINT('',(0.29,0.E+000)); +#16366 = VECTOR('',#16367,1.); +#16367 = DIRECTION('',(0.E+000,1.)); +#16368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16369 = ADVANCED_FACE('',(#16370),#15663,.T.); +#16370 = FACE_BOUND('',#16371,.T.); +#16371 = EDGE_LOOP('',(#16372,#16417,#16462,#16463)); +#16372 = ORIENTED_EDGE('',*,*,#16373,.F.); +#16373 = EDGE_CURVE('',#16374,#15605,#16376,.T.); +#16374 = VERTEX_POINT('',#16375); +#16375 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); +#16376 = SURFACE_CURVE('',#16377,(#16382,#16411),.PCURVE_S1.); +#16377 = CIRCLE('',#16378,1.E-002); +#16378 = AXIS2_PLACEMENT_3D('',#16379,#16380,#16381); +#16379 = CARTESIAN_POINT('',(-0.26,0.24,5.E-002)); +#16380 = DIRECTION('',(0.E+000,-2.595054858731E-031,1.)); +#16381 = DIRECTION('',(0.E+000,-1.,-2.595054858731E-031)); +#16382 = PCURVE('',#15663,#16383); +#16383 = DEFINITIONAL_REPRESENTATION('',(#16384),#16410); +#16384 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16385,#16386,#16387,#16388, + #16389,#16390,#16391,#16392,#16393,#16394,#16395,#16396,#16397, + #16398,#16399,#16400,#16401,#16402,#16403,#16404,#16405,#16406, + #16407,#16408,#16409),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -16920,59 +19909,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#13993 = CARTESIAN_POINT('',(1.,0.E+000)); -#13994 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#13995 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#13996 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#13997 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#13998 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#13999 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14000 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14001 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14002 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14003 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14004 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14005 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14006 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14007 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14008 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14009 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14010 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14011 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14012 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14013 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14014 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14015 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#14016 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#14017 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14019 = PCURVE('',#13358,#14020); -#14020 = DEFINITIONAL_REPRESENTATION('',(#14021),#14024); -#14021 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14022,#14023),.UNSPECIFIED., +#16385 = CARTESIAN_POINT('',(1.,0.E+000)); +#16386 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16387 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16388 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16389 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16390 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16391 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16392 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16393 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16394 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16395 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16396 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16397 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16398 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16399 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16400 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16401 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16402 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16403 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16404 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16405 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16406 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16407 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#16408 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#16409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16411 = PCURVE('',#15750,#16412); +#16412 = DEFINITIONAL_REPRESENTATION('',(#16413),#16416); +#16413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16414,#16415),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#14022 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#14023 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#14024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16414 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#16415 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#16416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14025 = ORIENTED_EDGE('',*,*,#14026,.F.); -#14026 = EDGE_CURVE('',#13914,#13982,#14027,.T.); -#14027 = SURFACE_CURVE('',#14028,(#14033,#14062),.PCURVE_S1.); -#14028 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14029,#14030,#14031,#14032), +#16417 = ORIENTED_EDGE('',*,*,#16418,.F.); +#16418 = EDGE_CURVE('',#16306,#16374,#16419,.T.); +#16419 = SURFACE_CURVE('',#16420,(#16425,#16454),.PCURVE_S1.); +#16420 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16421,#16422,#16423,#16424), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#14029 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); -#14030 = CARTESIAN_POINT('',(-0.25,0.222012399811,1.032416329181E-002)); -#14031 = CARTESIAN_POINT('',(-0.25,0.239663944536,2.718005887099E-002)); -#14032 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); -#14033 = PCURVE('',#13271,#14034); -#14034 = DEFINITIONAL_REPRESENTATION('',(#14035),#14061); -#14035 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14036,#14037,#14038,#14039, - #14040,#14041,#14042,#14043,#14044,#14045,#14046,#14047,#14048, - #14049,#14050,#14051,#14052,#14053,#14054,#14055,#14056,#14057, - #14058,#14059,#14060),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16421 = CARTESIAN_POINT('',(-0.25,0.2,1.E-002)); +#16422 = CARTESIAN_POINT('',(-0.25,0.222012399811,1.032416329181E-002)); +#16423 = CARTESIAN_POINT('',(-0.25,0.239663944536,2.718005887099E-002)); +#16424 = CARTESIAN_POINT('',(-0.25,0.24,5.E-002)); +#16425 = PCURVE('',#15663,#16426); +#16426 = DEFINITIONAL_REPRESENTATION('',(#16427),#16453); +#16427 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16428,#16429,#16430,#16431, + #16432,#16433,#16434,#16435,#16436,#16437,#16438,#16439,#16440, + #16441,#16442,#16443,#16444,#16445,#16446,#16447,#16448,#16449, + #16450,#16451,#16452),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -16980,76 +19969,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#14036 = CARTESIAN_POINT('',(1.,1.)); -#14037 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#14038 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#14039 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#14040 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); -#14041 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); -#14042 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#14043 = CARTESIAN_POINT('',(1.000601540492,0.714599645877)); -#14044 = CARTESIAN_POINT('',(1.000600014196,0.671375088896)); -#14045 = CARTESIAN_POINT('',(1.000606368831,0.628804305385)); -#14046 = CARTESIAN_POINT('',(1.000582476584,0.586710614266)); -#14047 = CARTESIAN_POINT('',(1.000671690938,0.544924984689)); -#14048 = CARTESIAN_POINT('',(1.000081825934,0.503282378121)); -#14049 = CARTESIAN_POINT('',(0.999949652391,0.461618222944)); -#14050 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#14051 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#14052 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#14053 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#14054 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#14055 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#14056 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#14057 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#14058 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); -#14059 = CARTESIAN_POINT('',(1.000367478029,1.833200565132E-002)); -#14060 = CARTESIAN_POINT('',(1.,0.E+000)); -#14061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14062 = PCURVE('',#11925,#14063); -#14063 = DEFINITIONAL_REPRESENTATION('',(#14064),#14069); -#14064 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14065,#14066,#14067,#14068), +#16428 = CARTESIAN_POINT('',(1.,1.)); +#16429 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#16430 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#16431 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#16432 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); +#16433 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); +#16434 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#16435 = CARTESIAN_POINT('',(1.000601540492,0.714599645877)); +#16436 = CARTESIAN_POINT('',(1.000600014196,0.671375088896)); +#16437 = CARTESIAN_POINT('',(1.000606368831,0.628804305385)); +#16438 = CARTESIAN_POINT('',(1.000582476584,0.586710614266)); +#16439 = CARTESIAN_POINT('',(1.000671690938,0.544924984689)); +#16440 = CARTESIAN_POINT('',(1.000081825934,0.503282378121)); +#16441 = CARTESIAN_POINT('',(0.999949652391,0.461618222944)); +#16442 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#16443 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#16444 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#16445 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#16446 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#16447 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#16448 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#16449 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#16450 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); +#16451 = CARTESIAN_POINT('',(1.000367478029,1.833200565132E-002)); +#16452 = CARTESIAN_POINT('',(1.,0.E+000)); +#16453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16454 = PCURVE('',#14317,#16455); +#16455 = DEFINITIONAL_REPRESENTATION('',(#16456),#16461); +#16456 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16457,#16458,#16459,#16460), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#14065 = CARTESIAN_POINT('',(0.29,0.45)); -#14066 = CARTESIAN_POINT('',(0.289675836708,0.472012399811)); -#14067 = CARTESIAN_POINT('',(0.272819941129,0.489663944536)); -#14068 = CARTESIAN_POINT('',(0.25,0.49)); -#14069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14070 = ORIENTED_EDGE('',*,*,#13913,.T.); -#14071 = ORIENTED_EDGE('',*,*,#13257,.T.); -#14072 = ADVANCED_FACE('',(#14073),#13358,.T.); -#14073 = FACE_BOUND('',#14074,.T.); -#14074 = EDGE_LOOP('',(#14075,#14120,#14140,#14141)); -#14075 = ORIENTED_EDGE('',*,*,#14076,.F.); -#14076 = EDGE_CURVE('',#14077,#13323,#14079,.T.); -#14077 = VERTEX_POINT('',#14078); -#14078 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); -#14079 = SURFACE_CURVE('',#14080,(#14085,#14091),.PCURVE_S1.); -#14080 = CIRCLE('',#14081,1.E-002); -#14081 = AXIS2_PLACEMENT_3D('',#14082,#14083,#14084); -#14082 = CARTESIAN_POINT('',(-0.26,0.24,0.55)); -#14083 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14084 = DIRECTION('',(0.E+000,1.,0.E+000)); -#14085 = PCURVE('',#13358,#14086); -#14086 = DEFINITIONAL_REPRESENTATION('',(#14087),#14090); -#14087 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14088,#14089),.UNSPECIFIED., +#16457 = CARTESIAN_POINT('',(0.29,0.45)); +#16458 = CARTESIAN_POINT('',(0.289675836708,0.472012399811)); +#16459 = CARTESIAN_POINT('',(0.272819941129,0.489663944536)); +#16460 = CARTESIAN_POINT('',(0.25,0.49)); +#16461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16462 = ORIENTED_EDGE('',*,*,#16305,.T.); +#16463 = ORIENTED_EDGE('',*,*,#15649,.T.); +#16464 = ADVANCED_FACE('',(#16465),#15750,.T.); +#16465 = FACE_BOUND('',#16466,.T.); +#16466 = EDGE_LOOP('',(#16467,#16512,#16532,#16533)); +#16467 = ORIENTED_EDGE('',*,*,#16468,.F.); +#16468 = EDGE_CURVE('',#16469,#15715,#16471,.T.); +#16469 = VERTEX_POINT('',#16470); +#16470 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); +#16471 = SURFACE_CURVE('',#16472,(#16477,#16483),.PCURVE_S1.); +#16472 = CIRCLE('',#16473,1.E-002); +#16473 = AXIS2_PLACEMENT_3D('',#16474,#16475,#16476); +#16474 = CARTESIAN_POINT('',(-0.26,0.24,0.55)); +#16475 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16476 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16477 = PCURVE('',#15750,#16478); +#16478 = DEFINITIONAL_REPRESENTATION('',(#16479),#16482); +#16479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16480,#16481),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14088 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#14089 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#14090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16480 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#16481 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#16482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14091 = PCURVE('',#13410,#14092); -#14092 = DEFINITIONAL_REPRESENTATION('',(#14093),#14119); -#14093 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14094,#14095,#14096,#14097, - #14098,#14099,#14100,#14101,#14102,#14103,#14104,#14105,#14106, - #14107,#14108,#14109,#14110,#14111,#14112,#14113,#14114,#14115, - #14116,#14117,#14118),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16483 = PCURVE('',#15802,#16484); +#16484 = DEFINITIONAL_REPRESENTATION('',(#16485),#16511); +#16485 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16486,#16487,#16488,#16489, + #16490,#16491,#16492,#16493,#16494,#16495,#16496,#16497,#16498, + #16499,#16500,#16501,#16502,#16503,#16504,#16505,#16506,#16507, + #16508,#16509,#16510),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -17057,80 +20046,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14094 = CARTESIAN_POINT('',(1.,1.)); -#14095 = CARTESIAN_POINT('',(0.983172198663,1.)); -#14096 = CARTESIAN_POINT('',(0.950009297011,1.)); -#14097 = CARTESIAN_POINT('',(0.901574474096,1.)); -#14098 = CARTESIAN_POINT('',(0.854275086925,1.)); -#14099 = CARTESIAN_POINT('',(0.807956362777,1.)); -#14100 = CARTESIAN_POINT('',(0.762473275577,1.)); -#14101 = CARTESIAN_POINT('',(0.717690577461,1.)); -#14102 = CARTESIAN_POINT('',(0.673480563786,1.)); -#14103 = CARTESIAN_POINT('',(0.629721689409,1.)); -#14104 = CARTESIAN_POINT('',(0.586297147708,1.)); -#14105 = CARTESIAN_POINT('',(0.543093605115,1.)); -#14106 = CARTESIAN_POINT('',(0.5,1.)); -#14107 = CARTESIAN_POINT('',(0.456906394885,1.)); -#14108 = CARTESIAN_POINT('',(0.413702852292,1.)); -#14109 = CARTESIAN_POINT('',(0.370278310591,1.)); -#14110 = CARTESIAN_POINT('',(0.326519436214,1.)); -#14111 = CARTESIAN_POINT('',(0.282309422539,1.)); -#14112 = CARTESIAN_POINT('',(0.237526724423,1.)); -#14113 = CARTESIAN_POINT('',(0.192043637223,1.)); -#14114 = CARTESIAN_POINT('',(0.145724913075,1.)); -#14115 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#14116 = CARTESIAN_POINT('',(4.99907029888E-002,1.)); -#14117 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#14118 = CARTESIAN_POINT('',(0.E+000,1.)); -#14119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14120 = ORIENTED_EDGE('',*,*,#14121,.F.); -#14121 = EDGE_CURVE('',#13982,#14077,#14122,.T.); -#14122 = SURFACE_CURVE('',#14123,(#14127,#14133),.PCURVE_S1.); -#14123 = LINE('',#14124,#14125); -#14124 = CARTESIAN_POINT('',(-0.25,0.24,0.3)); -#14125 = VECTOR('',#14126,1.); -#14126 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14127 = PCURVE('',#13358,#14128); -#14128 = DEFINITIONAL_REPRESENTATION('',(#14129),#14132); -#14129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14130,#14131),.UNSPECIFIED., +#16486 = CARTESIAN_POINT('',(1.,1.)); +#16487 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16488 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16489 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16490 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16491 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16492 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16493 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16494 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16495 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16496 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16497 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16498 = CARTESIAN_POINT('',(0.5,1.)); +#16499 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16500 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16501 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16502 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16503 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16504 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16505 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16506 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16507 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16508 = CARTESIAN_POINT('',(4.99907029888E-002,1.)); +#16509 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#16510 = CARTESIAN_POINT('',(0.E+000,1.)); +#16511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16512 = ORIENTED_EDGE('',*,*,#16513,.F.); +#16513 = EDGE_CURVE('',#16374,#16469,#16514,.T.); +#16514 = SURFACE_CURVE('',#16515,(#16519,#16525),.PCURVE_S1.); +#16515 = LINE('',#16516,#16517); +#16516 = CARTESIAN_POINT('',(-0.25,0.24,0.3)); +#16517 = VECTOR('',#16518,1.); +#16518 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16519 = PCURVE('',#15750,#16520); +#16520 = DEFINITIONAL_REPRESENTATION('',(#16521),#16524); +#16521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16522,#16523),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#14130 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#14131 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#14132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14133 = PCURVE('',#11925,#14134); -#14134 = DEFINITIONAL_REPRESENTATION('',(#14135),#14139); -#14135 = LINE('',#14136,#14137); -#14136 = CARTESIAN_POINT('',(0.E+000,0.49)); -#14137 = VECTOR('',#14138,1.); -#14138 = DIRECTION('',(-1.,0.E+000)); -#14139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14140 = ORIENTED_EDGE('',*,*,#13981,.T.); -#14141 = ORIENTED_EDGE('',*,*,#13344,.T.); -#14142 = ADVANCED_FACE('',(#14143),#13410,.T.); -#14143 = FACE_BOUND('',#14144,.T.); -#14144 = EDGE_LOOP('',(#14145,#14190,#14235,#14236)); -#14145 = ORIENTED_EDGE('',*,*,#14146,.F.); -#14146 = EDGE_CURVE('',#14147,#13375,#14149,.T.); -#14147 = VERTEX_POINT('',#14148); -#14148 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); -#14149 = SURFACE_CURVE('',#14150,(#14155,#14184),.PCURVE_S1.); -#14150 = CIRCLE('',#14151,1.E-002); -#14151 = AXIS2_PLACEMENT_3D('',#14152,#14153,#14154); -#14152 = CARTESIAN_POINT('',(-0.26,0.2,0.59)); -#14153 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#14154 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14155 = PCURVE('',#13410,#14156); -#14156 = DEFINITIONAL_REPRESENTATION('',(#14157),#14183); -#14157 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14158,#14159,#14160,#14161, - #14162,#14163,#14164,#14165,#14166,#14167,#14168,#14169,#14170, - #14171,#14172,#14173,#14174,#14175,#14176,#14177,#14178,#14179, - #14180,#14181,#14182),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16522 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#16523 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#16524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16525 = PCURVE('',#14317,#16526); +#16526 = DEFINITIONAL_REPRESENTATION('',(#16527),#16531); +#16527 = LINE('',#16528,#16529); +#16528 = CARTESIAN_POINT('',(0.E+000,0.49)); +#16529 = VECTOR('',#16530,1.); +#16530 = DIRECTION('',(-1.,0.E+000)); +#16531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16532 = ORIENTED_EDGE('',*,*,#16373,.T.); +#16533 = ORIENTED_EDGE('',*,*,#15736,.T.); +#16534 = ADVANCED_FACE('',(#16535),#15802,.T.); +#16535 = FACE_BOUND('',#16536,.T.); +#16536 = EDGE_LOOP('',(#16537,#16582,#16627,#16628)); +#16537 = ORIENTED_EDGE('',*,*,#16538,.F.); +#16538 = EDGE_CURVE('',#16539,#15767,#16541,.T.); +#16539 = VERTEX_POINT('',#16540); +#16540 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); +#16541 = SURFACE_CURVE('',#16542,(#16547,#16576),.PCURVE_S1.); +#16542 = CIRCLE('',#16543,1.E-002); +#16543 = AXIS2_PLACEMENT_3D('',#16544,#16545,#16546); +#16544 = CARTESIAN_POINT('',(-0.26,0.2,0.59)); +#16545 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#16546 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16547 = PCURVE('',#15802,#16548); +#16548 = DEFINITIONAL_REPRESENTATION('',(#16549),#16575); +#16549 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16550,#16551,#16552,#16553, + #16554,#16555,#16556,#16557,#16558,#16559,#16560,#16561,#16562, + #16563,#16564,#16565,#16566,#16567,#16568,#16569,#16570,#16571, + #16572,#16573,#16574),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -17138,59 +20127,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14158 = CARTESIAN_POINT('',(1.,0.E+000)); -#14159 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#14160 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#14161 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#14162 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#14163 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#14164 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14165 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14166 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14167 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14168 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14169 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14170 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14171 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14172 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14173 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14174 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14175 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14176 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14177 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14178 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14179 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14180 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); -#14181 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#14182 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14184 = PCURVE('',#13476,#14185); -#14185 = DEFINITIONAL_REPRESENTATION('',(#14186),#14189); -#14186 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14187,#14188),.UNSPECIFIED., +#16550 = CARTESIAN_POINT('',(1.,0.E+000)); +#16551 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16552 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16553 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16554 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16555 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16556 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16557 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16558 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16559 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16560 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16561 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16562 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16563 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16564 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16565 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16566 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16567 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16568 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16569 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16570 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16571 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16572 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); +#16573 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#16574 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16576 = PCURVE('',#15868,#16577); +#16577 = DEFINITIONAL_REPRESENTATION('',(#16578),#16581); +#16578 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16579,#16580),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14187 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#14188 = CARTESIAN_POINT('',(0.E+000,0.45)); -#14189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16579 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#16580 = CARTESIAN_POINT('',(0.E+000,0.45)); +#16581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14190 = ORIENTED_EDGE('',*,*,#14191,.F.); -#14191 = EDGE_CURVE('',#14077,#14147,#14192,.T.); -#14192 = SURFACE_CURVE('',#14193,(#14198,#14227),.PCURVE_S1.); -#14193 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14194,#14195,#14196,#14197), +#16582 = ORIENTED_EDGE('',*,*,#16583,.F.); +#16583 = EDGE_CURVE('',#16469,#16539,#16584,.T.); +#16584 = SURFACE_CURVE('',#16585,(#16590,#16619),.PCURVE_S1.); +#16585 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16586,#16587,#16588,#16589), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#14194 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); -#14195 = CARTESIAN_POINT('',(-0.25,0.239675836708,0.572012399811)); -#14196 = CARTESIAN_POINT('',(-0.25,0.222819941129,0.589663944536)); -#14197 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); -#14198 = PCURVE('',#13410,#14199); -#14199 = DEFINITIONAL_REPRESENTATION('',(#14200),#14226); -#14200 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14201,#14202,#14203,#14204, - #14205,#14206,#14207,#14208,#14209,#14210,#14211,#14212,#14213, - #14214,#14215,#14216,#14217,#14218,#14219,#14220,#14221,#14222, - #14223,#14224,#14225),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16586 = CARTESIAN_POINT('',(-0.25,0.24,0.55)); +#16587 = CARTESIAN_POINT('',(-0.25,0.239675836708,0.572012399811)); +#16588 = CARTESIAN_POINT('',(-0.25,0.222819941129,0.589663944536)); +#16589 = CARTESIAN_POINT('',(-0.25,0.2,0.59)); +#16590 = PCURVE('',#15802,#16591); +#16591 = DEFINITIONAL_REPRESENTATION('',(#16592),#16618); +#16592 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16593,#16594,#16595,#16596, + #16597,#16598,#16599,#16600,#16601,#16602,#16603,#16604,#16605, + #16606,#16607,#16608,#16609,#16610,#16611,#16612,#16613,#16614, + #16615,#16616,#16617),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -17198,99 +20187,99 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#14201 = CARTESIAN_POINT('',(1.,1.)); -#14202 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#14203 = CARTESIAN_POINT('',(1.00070985715,0.947763200665)); -#14204 = CARTESIAN_POINT('',(1.000572249037,0.898063133831)); -#14205 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); -#14206 = CARTESIAN_POINT('',(1.000599265839,0.803778523426)); -#14207 = CARTESIAN_POINT('',(1.000601789944,0.758666144519)); -#14208 = CARTESIAN_POINT('',(1.000601540492,0.714599645832)); -#14209 = CARTESIAN_POINT('',(1.000600014196,0.671375089064)); -#14210 = CARTESIAN_POINT('',(1.000606368831,0.628804305345)); -#14211 = CARTESIAN_POINT('',(1.000582476584,0.586710614276)); -#14212 = CARTESIAN_POINT('',(1.000671690938,0.544924984686)); -#14213 = CARTESIAN_POINT('',(1.000081825934,0.503282378122)); -#14214 = CARTESIAN_POINT('',(0.999949652391,0.461618222944)); -#14215 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#14216 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#14217 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#14218 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#14219 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#14220 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#14221 = CARTESIAN_POINT('',(1.000609469903,0.15397779537)); -#14222 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#14223 = CARTESIAN_POINT('',(1.000709884619,5.402886517647E-002)); -#14224 = CARTESIAN_POINT('',(1.000367478029,1.83320056512E-002)); -#14225 = CARTESIAN_POINT('',(1.,0.E+000)); -#14226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14227 = PCURVE('',#11925,#14228); -#14228 = DEFINITIONAL_REPRESENTATION('',(#14229),#14234); -#14229 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14230,#14231,#14232,#14233), +#16593 = CARTESIAN_POINT('',(1.,1.)); +#16594 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#16595 = CARTESIAN_POINT('',(1.00070985715,0.947763200665)); +#16596 = CARTESIAN_POINT('',(1.000572249037,0.898063133831)); +#16597 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); +#16598 = CARTESIAN_POINT('',(1.000599265839,0.803778523426)); +#16599 = CARTESIAN_POINT('',(1.000601789944,0.758666144519)); +#16600 = CARTESIAN_POINT('',(1.000601540492,0.714599645832)); +#16601 = CARTESIAN_POINT('',(1.000600014196,0.671375089064)); +#16602 = CARTESIAN_POINT('',(1.000606368831,0.628804305345)); +#16603 = CARTESIAN_POINT('',(1.000582476584,0.586710614276)); +#16604 = CARTESIAN_POINT('',(1.000671690938,0.544924984686)); +#16605 = CARTESIAN_POINT('',(1.000081825934,0.503282378122)); +#16606 = CARTESIAN_POINT('',(0.999949652391,0.461618222944)); +#16607 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#16608 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#16609 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#16610 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#16611 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#16612 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#16613 = CARTESIAN_POINT('',(1.000609469903,0.15397779537)); +#16614 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#16615 = CARTESIAN_POINT('',(1.000709884619,5.402886517647E-002)); +#16616 = CARTESIAN_POINT('',(1.000367478029,1.83320056512E-002)); +#16617 = CARTESIAN_POINT('',(1.,0.E+000)); +#16618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16619 = PCURVE('',#14317,#16620); +#16620 = DEFINITIONAL_REPRESENTATION('',(#16621),#16626); +#16621 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16622,#16623,#16624,#16625), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#14230 = CARTESIAN_POINT('',(-0.25,0.49)); -#14231 = CARTESIAN_POINT('',(-0.272012399811,0.489675836708)); -#14232 = CARTESIAN_POINT('',(-0.289663944536,0.472819941129)); -#14233 = CARTESIAN_POINT('',(-0.29,0.45)); -#14234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14235 = ORIENTED_EDGE('',*,*,#14076,.T.); -#14236 = ORIENTED_EDGE('',*,*,#13396,.T.); -#14237 = ADVANCED_FACE('',(#14238),#13476,.T.); -#14238 = FACE_BOUND('',#14239,.T.); -#14239 = EDGE_LOOP('',(#14240,#14241,#14261,#14262)); -#14240 = ORIENTED_EDGE('',*,*,#13607,.T.); -#14241 = ORIENTED_EDGE('',*,*,#14242,.F.); -#14242 = EDGE_CURVE('',#14147,#13608,#14243,.T.); -#14243 = SURFACE_CURVE('',#14244,(#14248,#14254),.PCURVE_S1.); -#14244 = LINE('',#14245,#14246); -#14245 = CARTESIAN_POINT('',(-0.25,-0.25,0.59)); -#14246 = VECTOR('',#14247,1.); -#14247 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#14248 = PCURVE('',#13476,#14249); -#14249 = DEFINITIONAL_REPRESENTATION('',(#14250),#14253); -#14250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14251,#14252),.UNSPECIFIED., +#16622 = CARTESIAN_POINT('',(-0.25,0.49)); +#16623 = CARTESIAN_POINT('',(-0.272012399811,0.489675836708)); +#16624 = CARTESIAN_POINT('',(-0.289663944536,0.472819941129)); +#16625 = CARTESIAN_POINT('',(-0.29,0.45)); +#16626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16627 = ORIENTED_EDGE('',*,*,#16468,.T.); +#16628 = ORIENTED_EDGE('',*,*,#15788,.T.); +#16629 = ADVANCED_FACE('',(#16630),#15868,.T.); +#16630 = FACE_BOUND('',#16631,.T.); +#16631 = EDGE_LOOP('',(#16632,#16633,#16653,#16654)); +#16632 = ORIENTED_EDGE('',*,*,#15999,.T.); +#16633 = ORIENTED_EDGE('',*,*,#16634,.F.); +#16634 = EDGE_CURVE('',#16539,#16000,#16635,.T.); +#16635 = SURFACE_CURVE('',#16636,(#16640,#16646),.PCURVE_S1.); +#16636 = LINE('',#16637,#16638); +#16637 = CARTESIAN_POINT('',(-0.25,-0.25,0.59)); +#16638 = VECTOR('',#16639,1.); +#16639 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#16640 = PCURVE('',#15868,#16641); +#16641 = DEFINITIONAL_REPRESENTATION('',(#16642),#16645); +#16642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16643,#16644),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#14251 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#14252 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#14253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14254 = PCURVE('',#11925,#14255); -#14255 = DEFINITIONAL_REPRESENTATION('',(#14256),#14260); -#14256 = LINE('',#14257,#14258); -#14257 = CARTESIAN_POINT('',(-0.29,0.E+000)); -#14258 = VECTOR('',#14259,1.); -#14259 = DIRECTION('',(0.E+000,-1.)); -#14260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14261 = ORIENTED_EDGE('',*,*,#14146,.T.); -#14262 = ORIENTED_EDGE('',*,*,#13462,.T.); -#14263 = ADVANCED_FACE('',(#14264),#14279,.T.); -#14264 = FACE_BOUND('',#14265,.T.); -#14265 = EDGE_LOOP('',(#14266,#14335,#14378)); -#14266 = ORIENTED_EDGE('',*,*,#14267,.F.); -#14267 = EDGE_CURVE('',#14268,#14270,#14272,.T.); -#14268 = VERTEX_POINT('',#14269); -#14269 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); -#14270 = VERTEX_POINT('',#14271); -#14271 = CARTESIAN_POINT('',(0.45,-0.2,0.6)); -#14272 = SURFACE_CURVE('',#14273,(#14278,#14324),.PCURVE_S1.); -#14273 = CIRCLE('',#14274,5.E-002); -#14274 = AXIS2_PLACEMENT_3D('',#14275,#14276,#14277); -#14275 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); -#14276 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); -#14277 = DIRECTION('',(-9.773375837189E-031,1.,0.E+000)); -#14278 = PCURVE('',#14279,#14296); -#14279 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#14280,#14281,#14282,#14283) - ,(#14284,#14285,#14286,#14287) - ,(#14288,#14289,#14290,#14291) - ,(#14292,#14293,#14294,#14295 +#16643 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#16644 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#16645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16646 = PCURVE('',#14317,#16647); +#16647 = DEFINITIONAL_REPRESENTATION('',(#16648),#16652); +#16648 = LINE('',#16649,#16650); +#16649 = CARTESIAN_POINT('',(-0.29,0.E+000)); +#16650 = VECTOR('',#16651,1.); +#16651 = DIRECTION('',(0.E+000,-1.)); +#16652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16653 = ORIENTED_EDGE('',*,*,#16538,.T.); +#16654 = ORIENTED_EDGE('',*,*,#15854,.T.); +#16655 = ADVANCED_FACE('',(#16656),#16671,.T.); +#16656 = FACE_BOUND('',#16657,.T.); +#16657 = EDGE_LOOP('',(#16658,#16727,#16770)); +#16658 = ORIENTED_EDGE('',*,*,#16659,.F.); +#16659 = EDGE_CURVE('',#16660,#16662,#16664,.T.); +#16660 = VERTEX_POINT('',#16661); +#16661 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); +#16662 = VERTEX_POINT('',#16663); +#16663 = CARTESIAN_POINT('',(0.45,-0.2,0.6)); +#16664 = SURFACE_CURVE('',#16665,(#16670,#16716),.PCURVE_S1.); +#16665 = CIRCLE('',#16666,5.E-002); +#16666 = AXIS2_PLACEMENT_3D('',#16667,#16668,#16669); +#16667 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); +#16668 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); +#16669 = DIRECTION('',(-9.773375837189E-031,1.,0.E+000)); +#16670 = PCURVE('',#16671,#16688); +#16671 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#16672,#16673,#16674,#16675) + ,(#16676,#16677,#16678,#16679) + ,(#16680,#16681,#16682,#16683) + ,(#16684,#16685,#16686,#16687 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -17299,27 +20288,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#14280 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); -#14281 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); -#14282 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); -#14283 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); -#14284 = CARTESIAN_POINT('',(0.5,-0.2,0.579289321881)); -#14285 = CARTESIAN_POINT('',(0.5,-0.217157287525,0.579289321881)); -#14286 = CARTESIAN_POINT('',(0.5,-0.229289321881,0.567157287525)); -#14287 = CARTESIAN_POINT('',(0.5,-0.229289321881,0.55)); -#14288 = CARTESIAN_POINT('',(0.479289321881,-0.2,0.6)); -#14289 = CARTESIAN_POINT('',(0.479289321881,-0.229289321881,0.6)); -#14290 = CARTESIAN_POINT('',(0.479289321881,-0.25,0.579289321881)); -#14291 = CARTESIAN_POINT('',(0.479289321881,-0.25,0.55)); -#14292 = CARTESIAN_POINT('',(0.45,-0.2,0.6)); -#14293 = CARTESIAN_POINT('',(0.45,-0.229289321881,0.6)); -#14294 = CARTESIAN_POINT('',(0.45,-0.25,0.579289321881)); -#14295 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); -#14296 = DEFINITIONAL_REPRESENTATION('',(#14297),#14323); -#14297 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14298,#14299,#14300,#14301, - #14302,#14303,#14304,#14305,#14306,#14307,#14308,#14309,#14310, - #14311,#14312,#14313,#14314,#14315,#14316,#14317,#14318,#14319, - #14320,#14321,#14322),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16672 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); +#16673 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); +#16674 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); +#16675 = CARTESIAN_POINT('',(0.5,-0.2,0.55)); +#16676 = CARTESIAN_POINT('',(0.5,-0.2,0.579289321881)); +#16677 = CARTESIAN_POINT('',(0.5,-0.217157287525,0.579289321881)); +#16678 = CARTESIAN_POINT('',(0.5,-0.229289321881,0.567157287525)); +#16679 = CARTESIAN_POINT('',(0.5,-0.229289321881,0.55)); +#16680 = CARTESIAN_POINT('',(0.479289321881,-0.2,0.6)); +#16681 = CARTESIAN_POINT('',(0.479289321881,-0.229289321881,0.6)); +#16682 = CARTESIAN_POINT('',(0.479289321881,-0.25,0.579289321881)); +#16683 = CARTESIAN_POINT('',(0.479289321881,-0.25,0.55)); +#16684 = CARTESIAN_POINT('',(0.45,-0.2,0.6)); +#16685 = CARTESIAN_POINT('',(0.45,-0.229289321881,0.6)); +#16686 = CARTESIAN_POINT('',(0.45,-0.25,0.579289321881)); +#16687 = CARTESIAN_POINT('',(0.45,-0.25,0.55)); +#16688 = DEFINITIONAL_REPRESENTATION('',(#16689),#16715); +#16689 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16690,#16691,#16692,#16693, + #16694,#16695,#16696,#16697,#16698,#16699,#16700,#16701,#16702, + #16703,#16704,#16705,#16706,#16707,#16708,#16709,#16710,#16711, + #16712,#16713,#16714),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -17327,63 +20316,63 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#14298 = CARTESIAN_POINT('',(1.,1.)); -#14299 = CARTESIAN_POINT('',(1.,0.983172198663)); -#14300 = CARTESIAN_POINT('',(1.,0.950009297011)); -#14301 = CARTESIAN_POINT('',(1.,0.901574474096)); -#14302 = CARTESIAN_POINT('',(1.,0.854275086925)); -#14303 = CARTESIAN_POINT('',(1.,0.807956362777)); -#14304 = CARTESIAN_POINT('',(1.,0.762473275577)); -#14305 = CARTESIAN_POINT('',(1.,0.717690577461)); -#14306 = CARTESIAN_POINT('',(1.,0.673480563786)); -#14307 = CARTESIAN_POINT('',(1.,0.629721689409)); -#14308 = CARTESIAN_POINT('',(1.,0.586297147708)); -#14309 = CARTESIAN_POINT('',(1.,0.543093605115)); -#14310 = CARTESIAN_POINT('',(1.,0.5)); -#14311 = CARTESIAN_POINT('',(1.,0.456906394885)); -#14312 = CARTESIAN_POINT('',(1.,0.413702852292)); -#14313 = CARTESIAN_POINT('',(1.,0.370278310591)); -#14314 = CARTESIAN_POINT('',(1.,0.326519436214)); -#14315 = CARTESIAN_POINT('',(1.,0.282309422539)); -#14316 = CARTESIAN_POINT('',(1.,0.237526724423)); -#14317 = CARTESIAN_POINT('',(1.,0.192043637223)); -#14318 = CARTESIAN_POINT('',(1.,0.145724913075)); -#14319 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); -#14320 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); -#14321 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); -#14322 = CARTESIAN_POINT('',(1.,0.E+000)); -#14323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14324 = PCURVE('',#14325,#14330); -#14325 = CYLINDRICAL_SURFACE('',#14326,5.E-002); -#14326 = AXIS2_PLACEMENT_3D('',#14327,#14328,#14329); -#14327 = CARTESIAN_POINT('',(0.375,-0.2,0.55)); -#14328 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); -#14329 = DIRECTION('',(-9.773375837189E-031,1.,0.E+000)); -#14330 = DEFINITIONAL_REPRESENTATION('',(#14331),#14334); -#14331 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14332,#14333),.UNSPECIFIED., +#16690 = CARTESIAN_POINT('',(1.,1.)); +#16691 = CARTESIAN_POINT('',(1.,0.983172198663)); +#16692 = CARTESIAN_POINT('',(1.,0.950009297011)); +#16693 = CARTESIAN_POINT('',(1.,0.901574474096)); +#16694 = CARTESIAN_POINT('',(1.,0.854275086925)); +#16695 = CARTESIAN_POINT('',(1.,0.807956362777)); +#16696 = CARTESIAN_POINT('',(1.,0.762473275577)); +#16697 = CARTESIAN_POINT('',(1.,0.717690577461)); +#16698 = CARTESIAN_POINT('',(1.,0.673480563786)); +#16699 = CARTESIAN_POINT('',(1.,0.629721689409)); +#16700 = CARTESIAN_POINT('',(1.,0.586297147708)); +#16701 = CARTESIAN_POINT('',(1.,0.543093605115)); +#16702 = CARTESIAN_POINT('',(1.,0.5)); +#16703 = CARTESIAN_POINT('',(1.,0.456906394885)); +#16704 = CARTESIAN_POINT('',(1.,0.413702852292)); +#16705 = CARTESIAN_POINT('',(1.,0.370278310591)); +#16706 = CARTESIAN_POINT('',(1.,0.326519436214)); +#16707 = CARTESIAN_POINT('',(1.,0.282309422539)); +#16708 = CARTESIAN_POINT('',(1.,0.237526724423)); +#16709 = CARTESIAN_POINT('',(1.,0.192043637223)); +#16710 = CARTESIAN_POINT('',(1.,0.145724913075)); +#16711 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); +#16712 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); +#16713 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); +#16714 = CARTESIAN_POINT('',(1.,0.E+000)); +#16715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16716 = PCURVE('',#16717,#16722); +#16717 = CYLINDRICAL_SURFACE('',#16718,5.E-002); +#16718 = AXIS2_PLACEMENT_3D('',#16719,#16720,#16721); +#16719 = CARTESIAN_POINT('',(0.375,-0.2,0.55)); +#16720 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); +#16721 = DIRECTION('',(-9.773375837189E-031,1.,0.E+000)); +#16722 = DEFINITIONAL_REPRESENTATION('',(#16723),#16726); +#16723 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16724,#16725),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#14332 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); -#14333 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#14334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14335 = ORIENTED_EDGE('',*,*,#14336,.F.); -#14336 = EDGE_CURVE('',#13526,#14268,#14337,.T.); -#14337 = SURFACE_CURVE('',#14338,(#14343,#14372),.PCURVE_S1.); -#14338 = CIRCLE('',#14339,5.E-002); -#14339 = AXIS2_PLACEMENT_3D('',#14340,#14341,#14342); -#14340 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); -#14341 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#14342 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); -#14343 = PCURVE('',#14279,#14344); -#14344 = DEFINITIONAL_REPRESENTATION('',(#14345),#14371); -#14345 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14346,#14347,#14348,#14349, - #14350,#14351,#14352,#14353,#14354,#14355,#14356,#14357,#14358, - #14359,#14360,#14361,#14362,#14363,#14364,#14365,#14366,#14367, - #14368,#14369,#14370),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16724 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); +#16725 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#16726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16727 = ORIENTED_EDGE('',*,*,#16728,.F.); +#16728 = EDGE_CURVE('',#15918,#16660,#16729,.T.); +#16729 = SURFACE_CURVE('',#16730,(#16735,#16764),.PCURVE_S1.); +#16730 = CIRCLE('',#16731,5.E-002); +#16731 = AXIS2_PLACEMENT_3D('',#16732,#16733,#16734); +#16732 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); +#16733 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#16734 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); +#16735 = PCURVE('',#16671,#16736); +#16736 = DEFINITIONAL_REPRESENTATION('',(#16737),#16763); +#16737 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16738,#16739,#16740,#16741, + #16742,#16743,#16744,#16745,#16746,#16747,#16748,#16749,#16750, + #16751,#16752,#16753,#16754,#16755,#16756,#16757,#16758,#16759, + #16760,#16761,#16762),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -17391,58 +20380,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#14346 = CARTESIAN_POINT('',(0.E+000,1.)); -#14347 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#14348 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#14349 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#14350 = CARTESIAN_POINT('',(0.145724913075,1.)); -#14351 = CARTESIAN_POINT('',(0.192043637223,1.)); -#14352 = CARTESIAN_POINT('',(0.237526724423,1.)); -#14353 = CARTESIAN_POINT('',(0.282309422539,1.)); -#14354 = CARTESIAN_POINT('',(0.326519436214,1.)); -#14355 = CARTESIAN_POINT('',(0.370278310591,1.)); -#14356 = CARTESIAN_POINT('',(0.413702852292,1.)); -#14357 = CARTESIAN_POINT('',(0.456906394885,1.)); -#14358 = CARTESIAN_POINT('',(0.5,1.)); -#14359 = CARTESIAN_POINT('',(0.543093605115,1.)); -#14360 = CARTESIAN_POINT('',(0.586297147708,1.)); -#14361 = CARTESIAN_POINT('',(0.629721689409,1.)); -#14362 = CARTESIAN_POINT('',(0.673480563786,1.)); -#14363 = CARTESIAN_POINT('',(0.717690577461,1.)); -#14364 = CARTESIAN_POINT('',(0.762473275577,1.)); -#14365 = CARTESIAN_POINT('',(0.807956362777,1.)); -#14366 = CARTESIAN_POINT('',(0.854275086925,1.)); -#14367 = CARTESIAN_POINT('',(0.901574474096,1.)); -#14368 = CARTESIAN_POINT('',(0.950009297011,1.)); -#14369 = CARTESIAN_POINT('',(0.983172198663,1.)); -#14370 = CARTESIAN_POINT('',(1.,1.)); -#14371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14372 = PCURVE('',#13568,#14373); -#14373 = DEFINITIONAL_REPRESENTATION('',(#14374),#14377); -#14374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14375,#14376),.UNSPECIFIED., +#16738 = CARTESIAN_POINT('',(0.E+000,1.)); +#16739 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#16740 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#16741 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16742 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16743 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16744 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16745 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16746 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16747 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16748 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16749 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16750 = CARTESIAN_POINT('',(0.5,1.)); +#16751 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16752 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16753 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16754 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16755 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16756 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16757 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16758 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16759 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16760 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16761 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16762 = CARTESIAN_POINT('',(1.,1.)); +#16763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16764 = PCURVE('',#15960,#16765); +#16765 = DEFINITIONAL_REPRESENTATION('',(#16766),#16769); +#16766 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16767,#16768),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#14375 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#14376 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#14377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14378 = ORIENTED_EDGE('',*,*,#14379,.F.); -#14379 = EDGE_CURVE('',#14270,#13526,#14380,.T.); -#14380 = SURFACE_CURVE('',#14381,(#14386,#14415),.PCURVE_S1.); -#14381 = CIRCLE('',#14382,5.E-002); -#14382 = AXIS2_PLACEMENT_3D('',#14383,#14384,#14385); -#14383 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); -#14384 = DIRECTION('',(0.E+000,1.,0.E+000)); -#14385 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14386 = PCURVE('',#14279,#14387); -#14387 = DEFINITIONAL_REPRESENTATION('',(#14388),#14414); -#14388 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14389,#14390,#14391,#14392, - #14393,#14394,#14395,#14396,#14397,#14398,#14399,#14400,#14401, - #14402,#14403,#14404,#14405,#14406,#14407,#14408,#14409,#14410, - #14411,#14412,#14413),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16767 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#16768 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#16769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16770 = ORIENTED_EDGE('',*,*,#16771,.F.); +#16771 = EDGE_CURVE('',#16662,#15918,#16772,.T.); +#16772 = SURFACE_CURVE('',#16773,(#16778,#16807),.PCURVE_S1.); +#16773 = CIRCLE('',#16774,5.E-002); +#16774 = AXIS2_PLACEMENT_3D('',#16775,#16776,#16777); +#16775 = CARTESIAN_POINT('',(0.45,-0.2,0.55)); +#16776 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16777 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16778 = PCURVE('',#16671,#16779); +#16779 = DEFINITIONAL_REPRESENTATION('',(#16780),#16806); +#16780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16781,#16782,#16783,#16784, + #16785,#16786,#16787,#16788,#16789,#16790,#16791,#16792,#16793, + #16794,#16795,#16796,#16797,#16798,#16799,#16800,#16801,#16802, + #16803,#16804,#16805),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -17450,74 +20439,74 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#14389 = CARTESIAN_POINT('',(1.,0.E+000)); -#14390 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#14391 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#14392 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#14393 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#14394 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#14395 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14396 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14397 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14398 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14399 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14400 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14401 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14402 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14403 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14404 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14405 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14406 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14407 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14408 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14409 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14410 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14411 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#14412 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#14413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14415 = PCURVE('',#13541,#14416); -#14416 = DEFINITIONAL_REPRESENTATION('',(#14417),#14420); -#14417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14418,#14419),.UNSPECIFIED., +#16781 = CARTESIAN_POINT('',(1.,0.E+000)); +#16782 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16783 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16784 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16785 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16786 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16787 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16788 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16789 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16790 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16791 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16792 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16793 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16794 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16795 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16796 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16797 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16798 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16799 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16800 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16801 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16802 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16803 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#16804 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#16805 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16807 = PCURVE('',#15933,#16808); +#16808 = DEFINITIONAL_REPRESENTATION('',(#16809),#16812); +#16809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16810,#16811),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#14418 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#14419 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#14420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14421 = ADVANCED_FACE('',(#14422),#13541,.T.); -#14422 = FACE_BOUND('',#14423,.T.); -#14423 = EDGE_LOOP('',(#14424,#14425,#14426,#14488)); -#14424 = ORIENTED_EDGE('',*,*,#14379,.T.); -#14425 = ORIENTED_EDGE('',*,*,#13525,.T.); -#14426 = ORIENTED_EDGE('',*,*,#14427,.F.); -#14427 = EDGE_CURVE('',#14428,#13492,#14430,.T.); -#14428 = VERTEX_POINT('',#14429); -#14429 = CARTESIAN_POINT('',(0.45,0.2,0.6)); -#14430 = SURFACE_CURVE('',#14431,(#14436,#14442),.PCURVE_S1.); -#14431 = CIRCLE('',#14432,5.E-002); -#14432 = AXIS2_PLACEMENT_3D('',#14433,#14434,#14435); -#14433 = CARTESIAN_POINT('',(0.45,0.2,0.55)); -#14434 = DIRECTION('',(0.E+000,1.,-6.123233995737E-017)); -#14435 = DIRECTION('',(1.,0.E+000,0.E+000)); -#14436 = PCURVE('',#13541,#14437); -#14437 = DEFINITIONAL_REPRESENTATION('',(#14438),#14441); -#14438 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14439,#14440),.UNSPECIFIED., +#16810 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#16811 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#16812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16813 = ADVANCED_FACE('',(#16814),#15933,.T.); +#16814 = FACE_BOUND('',#16815,.T.); +#16815 = EDGE_LOOP('',(#16816,#16817,#16818,#16880)); +#16816 = ORIENTED_EDGE('',*,*,#16771,.T.); +#16817 = ORIENTED_EDGE('',*,*,#15917,.T.); +#16818 = ORIENTED_EDGE('',*,*,#16819,.F.); +#16819 = EDGE_CURVE('',#16820,#15884,#16822,.T.); +#16820 = VERTEX_POINT('',#16821); +#16821 = CARTESIAN_POINT('',(0.45,0.2,0.6)); +#16822 = SURFACE_CURVE('',#16823,(#16828,#16834),.PCURVE_S1.); +#16823 = CIRCLE('',#16824,5.E-002); +#16824 = AXIS2_PLACEMENT_3D('',#16825,#16826,#16827); +#16825 = CARTESIAN_POINT('',(0.45,0.2,0.55)); +#16826 = DIRECTION('',(0.E+000,1.,-6.123233995737E-017)); +#16827 = DIRECTION('',(1.,0.E+000,0.E+000)); +#16828 = PCURVE('',#15933,#16829); +#16829 = DEFINITIONAL_REPRESENTATION('',(#16830),#16833); +#16830 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16831,#16832),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14439 = CARTESIAN_POINT('',(0.E+000,0.45)); -#14440 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#14441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#16831 = CARTESIAN_POINT('',(0.E+000,0.45)); +#16832 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#16833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14442 = PCURVE('',#14443,#14460); -#14443 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#14444,#14445,#14446,#14447) - ,(#14448,#14449,#14450,#14451) - ,(#14452,#14453,#14454,#14455) - ,(#14456,#14457,#14458,#14459 +#16834 = PCURVE('',#16835,#16852); +#16835 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#16836,#16837,#16838,#16839) + ,(#16840,#16841,#16842,#16843) + ,(#16844,#16845,#16846,#16847) + ,(#16848,#16849,#16850,#16851 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -17526,27 +20515,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#14444 = CARTESIAN_POINT('',(0.5,0.2,0.55)); -#14445 = CARTESIAN_POINT('',(0.5,0.2,0.55)); -#14446 = CARTESIAN_POINT('',(0.5,0.2,0.55)); -#14447 = CARTESIAN_POINT('',(0.5,0.2,0.55)); -#14448 = CARTESIAN_POINT('',(0.5,0.229289321881,0.55)); -#14449 = CARTESIAN_POINT('',(0.5,0.229289321881,0.567157287525)); -#14450 = CARTESIAN_POINT('',(0.5,0.217157287525,0.579289321881)); -#14451 = CARTESIAN_POINT('',(0.5,0.2,0.579289321881)); -#14452 = CARTESIAN_POINT('',(0.479289321881,0.25,0.55)); -#14453 = CARTESIAN_POINT('',(0.479289321881,0.25,0.579289321881)); -#14454 = CARTESIAN_POINT('',(0.479289321881,0.229289321881,0.6)); -#14455 = CARTESIAN_POINT('',(0.479289321881,0.2,0.6)); -#14456 = CARTESIAN_POINT('',(0.45,0.25,0.55)); -#14457 = CARTESIAN_POINT('',(0.45,0.25,0.579289321881)); -#14458 = CARTESIAN_POINT('',(0.45,0.229289321881,0.6)); -#14459 = CARTESIAN_POINT('',(0.45,0.2,0.6)); -#14460 = DEFINITIONAL_REPRESENTATION('',(#14461),#14487); -#14461 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14462,#14463,#14464,#14465, - #14466,#14467,#14468,#14469,#14470,#14471,#14472,#14473,#14474, - #14475,#14476,#14477,#14478,#14479,#14480,#14481,#14482,#14483, - #14484,#14485,#14486),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16836 = CARTESIAN_POINT('',(0.5,0.2,0.55)); +#16837 = CARTESIAN_POINT('',(0.5,0.2,0.55)); +#16838 = CARTESIAN_POINT('',(0.5,0.2,0.55)); +#16839 = CARTESIAN_POINT('',(0.5,0.2,0.55)); +#16840 = CARTESIAN_POINT('',(0.5,0.229289321881,0.55)); +#16841 = CARTESIAN_POINT('',(0.5,0.229289321881,0.567157287525)); +#16842 = CARTESIAN_POINT('',(0.5,0.217157287525,0.579289321881)); +#16843 = CARTESIAN_POINT('',(0.5,0.2,0.579289321881)); +#16844 = CARTESIAN_POINT('',(0.479289321881,0.25,0.55)); +#16845 = CARTESIAN_POINT('',(0.479289321881,0.25,0.579289321881)); +#16846 = CARTESIAN_POINT('',(0.479289321881,0.229289321881,0.6)); +#16847 = CARTESIAN_POINT('',(0.479289321881,0.2,0.6)); +#16848 = CARTESIAN_POINT('',(0.45,0.25,0.55)); +#16849 = CARTESIAN_POINT('',(0.45,0.25,0.579289321881)); +#16850 = CARTESIAN_POINT('',(0.45,0.229289321881,0.6)); +#16851 = CARTESIAN_POINT('',(0.45,0.2,0.6)); +#16852 = DEFINITIONAL_REPRESENTATION('',(#16853),#16879); +#16853 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16854,#16855,#16856,#16857, + #16858,#16859,#16860,#16861,#16862,#16863,#16864,#16865,#16866, + #16867,#16868,#16869,#16870,#16871,#16872,#16873,#16874,#16875, + #16876,#16877,#16878),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -17554,84 +20543,84 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14462 = CARTESIAN_POINT('',(1.,1.)); -#14463 = CARTESIAN_POINT('',(0.983172198663,1.)); -#14464 = CARTESIAN_POINT('',(0.950009297011,1.)); -#14465 = CARTESIAN_POINT('',(0.901574474096,1.)); -#14466 = CARTESIAN_POINT('',(0.854275086925,1.)); -#14467 = CARTESIAN_POINT('',(0.807956362777,1.)); -#14468 = CARTESIAN_POINT('',(0.762473275577,1.)); -#14469 = CARTESIAN_POINT('',(0.717690577461,1.)); -#14470 = CARTESIAN_POINT('',(0.673480563786,1.)); -#14471 = CARTESIAN_POINT('',(0.629721689409,1.)); -#14472 = CARTESIAN_POINT('',(0.586297147708,1.)); -#14473 = CARTESIAN_POINT('',(0.543093605115,1.)); -#14474 = CARTESIAN_POINT('',(0.5,1.)); -#14475 = CARTESIAN_POINT('',(0.456906394885,1.)); -#14476 = CARTESIAN_POINT('',(0.413702852292,1.)); -#14477 = CARTESIAN_POINT('',(0.370278310591,1.)); -#14478 = CARTESIAN_POINT('',(0.326519436214,1.)); -#14479 = CARTESIAN_POINT('',(0.282309422539,1.)); -#14480 = CARTESIAN_POINT('',(0.237526724423,1.)); -#14481 = CARTESIAN_POINT('',(0.192043637223,1.)); -#14482 = CARTESIAN_POINT('',(0.145724913075,1.)); -#14483 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#14484 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#14485 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#14486 = CARTESIAN_POINT('',(0.E+000,1.)); -#14487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14488 = ORIENTED_EDGE('',*,*,#14489,.F.); -#14489 = EDGE_CURVE('',#14270,#14428,#14490,.T.); -#14490 = SURFACE_CURVE('',#14491,(#14495,#14501),.PCURVE_S1.); -#14491 = LINE('',#14492,#14493); -#14492 = CARTESIAN_POINT('',(0.45,-0.25,0.6)); -#14493 = VECTOR('',#14494,1.); -#14494 = DIRECTION('',(0.E+000,1.,0.E+000)); -#14495 = PCURVE('',#13541,#14496); -#14496 = DEFINITIONAL_REPRESENTATION('',(#14497),#14500); -#14497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14498,#14499),.UNSPECIFIED., +#16854 = CARTESIAN_POINT('',(1.,1.)); +#16855 = CARTESIAN_POINT('',(0.983172198663,1.)); +#16856 = CARTESIAN_POINT('',(0.950009297011,1.)); +#16857 = CARTESIAN_POINT('',(0.901574474096,1.)); +#16858 = CARTESIAN_POINT('',(0.854275086925,1.)); +#16859 = CARTESIAN_POINT('',(0.807956362777,1.)); +#16860 = CARTESIAN_POINT('',(0.762473275577,1.)); +#16861 = CARTESIAN_POINT('',(0.717690577461,1.)); +#16862 = CARTESIAN_POINT('',(0.673480563786,1.)); +#16863 = CARTESIAN_POINT('',(0.629721689409,1.)); +#16864 = CARTESIAN_POINT('',(0.586297147708,1.)); +#16865 = CARTESIAN_POINT('',(0.543093605115,1.)); +#16866 = CARTESIAN_POINT('',(0.5,1.)); +#16867 = CARTESIAN_POINT('',(0.456906394885,1.)); +#16868 = CARTESIAN_POINT('',(0.413702852292,1.)); +#16869 = CARTESIAN_POINT('',(0.370278310591,1.)); +#16870 = CARTESIAN_POINT('',(0.326519436214,1.)); +#16871 = CARTESIAN_POINT('',(0.282309422539,1.)); +#16872 = CARTESIAN_POINT('',(0.237526724423,1.)); +#16873 = CARTESIAN_POINT('',(0.192043637223,1.)); +#16874 = CARTESIAN_POINT('',(0.145724913075,1.)); +#16875 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#16876 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#16877 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#16878 = CARTESIAN_POINT('',(0.E+000,1.)); +#16879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16880 = ORIENTED_EDGE('',*,*,#16881,.F.); +#16881 = EDGE_CURVE('',#16662,#16820,#16882,.T.); +#16882 = SURFACE_CURVE('',#16883,(#16887,#16893),.PCURVE_S1.); +#16883 = LINE('',#16884,#16885); +#16884 = CARTESIAN_POINT('',(0.45,-0.25,0.6)); +#16885 = VECTOR('',#16886,1.); +#16886 = DIRECTION('',(0.E+000,1.,0.E+000)); +#16887 = PCURVE('',#15933,#16888); +#16888 = DEFINITIONAL_REPRESENTATION('',(#16889),#16892); +#16889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16890,#16891),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#14498 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#14499 = CARTESIAN_POINT('',(0.E+000,0.45)); -#14500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14501 = PCURVE('',#14502,#14507); -#14502 = PLANE('',#14503); -#14503 = AXIS2_PLACEMENT_3D('',#14504,#14505,#14506); -#14504 = CARTESIAN_POINT('',(0.375,-0.25,0.6)); -#14505 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14506 = DIRECTION('',(1.,0.E+000,0.E+000)); -#14507 = DEFINITIONAL_REPRESENTATION('',(#14508),#14512); -#14508 = LINE('',#14509,#14510); -#14509 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); -#14510 = VECTOR('',#14511,1.); -#14511 = DIRECTION('',(0.E+000,1.)); -#14512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14513 = ADVANCED_FACE('',(#14514),#14443,.T.); -#14514 = FACE_BOUND('',#14515,.T.); -#14515 = EDGE_LOOP('',(#14516,#14517,#14562)); -#14516 = ORIENTED_EDGE('',*,*,#14427,.T.); -#14517 = ORIENTED_EDGE('',*,*,#14518,.F.); -#14518 = EDGE_CURVE('',#14519,#13492,#14521,.T.); -#14519 = VERTEX_POINT('',#14520); -#14520 = CARTESIAN_POINT('',(0.45,0.25,0.55)); -#14521 = SURFACE_CURVE('',#14522,(#14527,#14556),.PCURVE_S1.); -#14522 = CIRCLE('',#14523,5.E-002); -#14523 = AXIS2_PLACEMENT_3D('',#14524,#14525,#14526); -#14524 = CARTESIAN_POINT('',(0.45,0.2,0.55)); -#14525 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#14526 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); -#14527 = PCURVE('',#14443,#14528); -#14528 = DEFINITIONAL_REPRESENTATION('',(#14529),#14555); -#14529 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14530,#14531,#14532,#14533, - #14534,#14535,#14536,#14537,#14538,#14539,#14540,#14541,#14542, - #14543,#14544,#14545,#14546,#14547,#14548,#14549,#14550,#14551, - #14552,#14553,#14554),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16890 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#16891 = CARTESIAN_POINT('',(0.E+000,0.45)); +#16892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16893 = PCURVE('',#16894,#16899); +#16894 = PLANE('',#16895); +#16895 = AXIS2_PLACEMENT_3D('',#16896,#16897,#16898); +#16896 = CARTESIAN_POINT('',(0.375,-0.25,0.6)); +#16897 = DIRECTION('',(0.E+000,0.E+000,1.)); +#16898 = DIRECTION('',(1.,0.E+000,0.E+000)); +#16899 = DEFINITIONAL_REPRESENTATION('',(#16900),#16904); +#16900 = LINE('',#16901,#16902); +#16901 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); +#16902 = VECTOR('',#16903,1.); +#16903 = DIRECTION('',(0.E+000,1.)); +#16904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16905 = ADVANCED_FACE('',(#16906),#16835,.T.); +#16906 = FACE_BOUND('',#16907,.T.); +#16907 = EDGE_LOOP('',(#16908,#16909,#16954)); +#16908 = ORIENTED_EDGE('',*,*,#16819,.T.); +#16909 = ORIENTED_EDGE('',*,*,#16910,.F.); +#16910 = EDGE_CURVE('',#16911,#15884,#16913,.T.); +#16911 = VERTEX_POINT('',#16912); +#16912 = CARTESIAN_POINT('',(0.45,0.25,0.55)); +#16913 = SURFACE_CURVE('',#16914,(#16919,#16948),.PCURVE_S1.); +#16914 = CIRCLE('',#16915,5.E-002); +#16915 = AXIS2_PLACEMENT_3D('',#16916,#16917,#16918); +#16916 = CARTESIAN_POINT('',(0.45,0.2,0.55)); +#16917 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#16918 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); +#16919 = PCURVE('',#16835,#16920); +#16920 = DEFINITIONAL_REPRESENTATION('',(#16921),#16947); +#16921 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16922,#16923,#16924,#16925, + #16926,#16927,#16928,#16929,#16930,#16931,#16932,#16933,#16934, + #16935,#16936,#16937,#16938,#16939,#16940,#16941,#16942,#16943, + #16944,#16945,#16946),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -17639,58 +20628,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#14530 = CARTESIAN_POINT('',(1.,0.E+000)); -#14531 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#14532 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#14533 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#14534 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#14535 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#14536 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14537 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14538 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14539 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14540 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14541 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14542 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14543 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14544 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14545 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14546 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14547 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14548 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14549 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14550 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14551 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14552 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#14553 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#14554 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14556 = PCURVE('',#13514,#14557); -#14557 = DEFINITIONAL_REPRESENTATION('',(#14558),#14561); -#14558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14559,#14560),.UNSPECIFIED., +#16922 = CARTESIAN_POINT('',(1.,0.E+000)); +#16923 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#16924 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#16925 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#16926 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#16927 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#16928 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#16929 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#16930 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#16931 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#16932 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#16933 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#16934 = CARTESIAN_POINT('',(0.5,0.E+000)); +#16935 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#16936 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#16937 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#16938 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#16939 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#16940 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#16941 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#16942 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#16943 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#16944 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#16945 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#16946 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#16947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16948 = PCURVE('',#15906,#16949); +#16949 = DEFINITIONAL_REPRESENTATION('',(#16950),#16953); +#16950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16951,#16952),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#14559 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#14560 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#14561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14562 = ORIENTED_EDGE('',*,*,#14563,.F.); -#14563 = EDGE_CURVE('',#14428,#14519,#14564,.T.); -#14564 = SURFACE_CURVE('',#14565,(#14570,#14599),.PCURVE_S1.); -#14565 = CIRCLE('',#14566,5.E-002); -#14566 = AXIS2_PLACEMENT_3D('',#14567,#14568,#14569); -#14567 = CARTESIAN_POINT('',(0.45,0.2,0.55)); -#14568 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); -#14569 = DIRECTION('',(9.773375837189E-031,-1.,0.E+000)); -#14570 = PCURVE('',#14443,#14571); -#14571 = DEFINITIONAL_REPRESENTATION('',(#14572),#14598); -#14572 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14573,#14574,#14575,#14576, - #14577,#14578,#14579,#14580,#14581,#14582,#14583,#14584,#14585, - #14586,#14587,#14588,#14589,#14590,#14591,#14592,#14593,#14594, - #14595,#14596,#14597),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#16951 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#16952 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#16953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16954 = ORIENTED_EDGE('',*,*,#16955,.F.); +#16955 = EDGE_CURVE('',#16820,#16911,#16956,.T.); +#16956 = SURFACE_CURVE('',#16957,(#16962,#16991),.PCURVE_S1.); +#16957 = CIRCLE('',#16958,5.E-002); +#16958 = AXIS2_PLACEMENT_3D('',#16959,#16960,#16961); +#16959 = CARTESIAN_POINT('',(0.45,0.2,0.55)); +#16960 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); +#16961 = DIRECTION('',(9.773375837189E-031,-1.,0.E+000)); +#16962 = PCURVE('',#16835,#16963); +#16963 = DEFINITIONAL_REPRESENTATION('',(#16964),#16990); +#16964 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16965,#16966,#16967,#16968, + #16969,#16970,#16971,#16972,#16973,#16974,#16975,#16976,#16977, + #16978,#16979,#16980,#16981,#16982,#16983,#16984,#16985,#16986, + #16987,#16988,#16989),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -17698,78 +20687,78 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#14573 = CARTESIAN_POINT('',(1.,1.)); -#14574 = CARTESIAN_POINT('',(1.,0.983172198663)); -#14575 = CARTESIAN_POINT('',(1.,0.950009297011)); -#14576 = CARTESIAN_POINT('',(1.,0.901574474096)); -#14577 = CARTESIAN_POINT('',(1.,0.854275086925)); -#14578 = CARTESIAN_POINT('',(1.,0.807956362777)); -#14579 = CARTESIAN_POINT('',(1.,0.762473275577)); -#14580 = CARTESIAN_POINT('',(1.,0.717690577461)); -#14581 = CARTESIAN_POINT('',(1.,0.673480563786)); -#14582 = CARTESIAN_POINT('',(1.,0.629721689409)); -#14583 = CARTESIAN_POINT('',(1.,0.586297147708)); -#14584 = CARTESIAN_POINT('',(1.,0.543093605115)); -#14585 = CARTESIAN_POINT('',(1.,0.5)); -#14586 = CARTESIAN_POINT('',(1.,0.456906394885)); -#14587 = CARTESIAN_POINT('',(1.,0.413702852292)); -#14588 = CARTESIAN_POINT('',(1.,0.370278310591)); -#14589 = CARTESIAN_POINT('',(1.,0.326519436214)); -#14590 = CARTESIAN_POINT('',(1.,0.282309422539)); -#14591 = CARTESIAN_POINT('',(1.,0.237526724423)); -#14592 = CARTESIAN_POINT('',(1.,0.192043637223)); -#14593 = CARTESIAN_POINT('',(1.,0.145724913075)); -#14594 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); -#14595 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); -#14596 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); -#14597 = CARTESIAN_POINT('',(1.,0.E+000)); -#14598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14599 = PCURVE('',#14600,#14605); -#14600 = CYLINDRICAL_SURFACE('',#14601,5.E-002); -#14601 = AXIS2_PLACEMENT_3D('',#14602,#14603,#14604); -#14602 = CARTESIAN_POINT('',(0.375,0.2,0.55)); -#14603 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); -#14604 = DIRECTION('',(9.773375837189E-031,-1.,0.E+000)); -#14605 = DEFINITIONAL_REPRESENTATION('',(#14606),#14609); -#14606 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14607,#14608),.UNSPECIFIED., +#16965 = CARTESIAN_POINT('',(1.,1.)); +#16966 = CARTESIAN_POINT('',(1.,0.983172198663)); +#16967 = CARTESIAN_POINT('',(1.,0.950009297011)); +#16968 = CARTESIAN_POINT('',(1.,0.901574474096)); +#16969 = CARTESIAN_POINT('',(1.,0.854275086925)); +#16970 = CARTESIAN_POINT('',(1.,0.807956362777)); +#16971 = CARTESIAN_POINT('',(1.,0.762473275577)); +#16972 = CARTESIAN_POINT('',(1.,0.717690577461)); +#16973 = CARTESIAN_POINT('',(1.,0.673480563786)); +#16974 = CARTESIAN_POINT('',(1.,0.629721689409)); +#16975 = CARTESIAN_POINT('',(1.,0.586297147708)); +#16976 = CARTESIAN_POINT('',(1.,0.543093605115)); +#16977 = CARTESIAN_POINT('',(1.,0.5)); +#16978 = CARTESIAN_POINT('',(1.,0.456906394885)); +#16979 = CARTESIAN_POINT('',(1.,0.413702852292)); +#16980 = CARTESIAN_POINT('',(1.,0.370278310591)); +#16981 = CARTESIAN_POINT('',(1.,0.326519436214)); +#16982 = CARTESIAN_POINT('',(1.,0.282309422539)); +#16983 = CARTESIAN_POINT('',(1.,0.237526724423)); +#16984 = CARTESIAN_POINT('',(1.,0.192043637223)); +#16985 = CARTESIAN_POINT('',(1.,0.145724913075)); +#16986 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); +#16987 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); +#16988 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); +#16989 = CARTESIAN_POINT('',(1.,0.E+000)); +#16990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#16991 = PCURVE('',#16992,#16997); +#16992 = CYLINDRICAL_SURFACE('',#16993,5.E-002); +#16993 = AXIS2_PLACEMENT_3D('',#16994,#16995,#16996); +#16994 = CARTESIAN_POINT('',(0.375,0.2,0.55)); +#16995 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); +#16996 = DIRECTION('',(9.773375837189E-031,-1.,0.E+000)); +#16997 = DEFINITIONAL_REPRESENTATION('',(#16998),#17001); +#16998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16999,#17000),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#14607 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); -#14608 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); -#14609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14610 = ADVANCED_FACE('',(#14611),#13514,.T.); -#14611 = FACE_BOUND('',#14612,.T.); -#14612 = EDGE_LOOP('',(#14613,#14675,#14700,#14701)); -#14613 = ORIENTED_EDGE('',*,*,#14614,.F.); -#14614 = EDGE_CURVE('',#14615,#13494,#14617,.T.); -#14615 = VERTEX_POINT('',#14616); -#14616 = CARTESIAN_POINT('',(0.45,0.25,5.E-002)); -#14617 = SURFACE_CURVE('',#14618,(#14623,#14629),.PCURVE_S1.); -#14618 = CIRCLE('',#14619,5.E-002); -#14619 = AXIS2_PLACEMENT_3D('',#14620,#14621,#14622); -#14620 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); -#14621 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#14622 = DIRECTION('',(1.,0.E+000,0.E+000)); -#14623 = PCURVE('',#13514,#14624); -#14624 = DEFINITIONAL_REPRESENTATION('',(#14625),#14628); -#14625 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14626,#14627),.UNSPECIFIED., +#16999 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); +#17000 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); +#17001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17002 = ADVANCED_FACE('',(#17003),#15906,.T.); +#17003 = FACE_BOUND('',#17004,.T.); +#17004 = EDGE_LOOP('',(#17005,#17067,#17092,#17093)); +#17005 = ORIENTED_EDGE('',*,*,#17006,.F.); +#17006 = EDGE_CURVE('',#17007,#15886,#17009,.T.); +#17007 = VERTEX_POINT('',#17008); +#17008 = CARTESIAN_POINT('',(0.45,0.25,5.E-002)); +#17009 = SURFACE_CURVE('',#17010,(#17015,#17021),.PCURVE_S1.); +#17010 = CIRCLE('',#17011,5.E-002); +#17011 = AXIS2_PLACEMENT_3D('',#17012,#17013,#17014); +#17012 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); +#17013 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#17014 = DIRECTION('',(1.,0.E+000,0.E+000)); +#17015 = PCURVE('',#15906,#17016); +#17016 = DEFINITIONAL_REPRESENTATION('',(#17017),#17020); +#17017 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17018,#17019),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14626 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#14627 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#14628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17018 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#17019 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#17020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14629 = PCURVE('',#14630,#14647); -#14630 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#14631,#14632,#14633,#14634) - ,(#14635,#14636,#14637,#14638) - ,(#14639,#14640,#14641,#14642) - ,(#14643,#14644,#14645,#14646 +#17021 = PCURVE('',#17022,#17039); +#17022 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17023,#17024,#17025,#17026) + ,(#17027,#17028,#17029,#17030) + ,(#17031,#17032,#17033,#17034) + ,(#17035,#17036,#17037,#17038 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -17778,28 +20767,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#14631 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); -#14632 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); -#14633 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); -#14634 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); -#14635 = CARTESIAN_POINT('',(0.5,0.2,2.071067811865E-002)); -#14636 = CARTESIAN_POINT('',(0.5,0.217157287525,2.071067811865E-002)); -#14637 = CARTESIAN_POINT('',(0.5,0.229289321881,3.284271247462E-002)); -#14638 = CARTESIAN_POINT('',(0.5,0.229289321881,5.E-002)); -#14639 = CARTESIAN_POINT('',(0.479289321881,0.2,-4.982809863475E-018)); -#14640 = CARTESIAN_POINT('',(0.479289321881,0.229289321881, +#17023 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); +#17024 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); +#17025 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); +#17026 = CARTESIAN_POINT('',(0.5,0.2,5.E-002)); +#17027 = CARTESIAN_POINT('',(0.5,0.2,2.071067811865E-002)); +#17028 = CARTESIAN_POINT('',(0.5,0.217157287525,2.071067811865E-002)); +#17029 = CARTESIAN_POINT('',(0.5,0.229289321881,3.284271247462E-002)); +#17030 = CARTESIAN_POINT('',(0.5,0.229289321881,5.E-002)); +#17031 = CARTESIAN_POINT('',(0.479289321881,0.2,-4.982809863475E-018)); +#17032 = CARTESIAN_POINT('',(0.479289321881,0.229289321881, -5.261612948505E-017)); -#14641 = CARTESIAN_POINT('',(0.479289321881,0.25,2.071067811865E-002)); -#14642 = CARTESIAN_POINT('',(0.479289321881,0.25,5.E-002)); -#14643 = CARTESIAN_POINT('',(0.45,0.2,-6.776263578034E-018)); -#14644 = CARTESIAN_POINT('',(0.45,0.229289321881,-5.440958319961E-017)); -#14645 = CARTESIAN_POINT('',(0.45,0.25,2.071067811865E-002)); -#14646 = CARTESIAN_POINT('',(0.45,0.25,5.E-002)); -#14647 = DEFINITIONAL_REPRESENTATION('',(#14648),#14674); -#14648 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14649,#14650,#14651,#14652, - #14653,#14654,#14655,#14656,#14657,#14658,#14659,#14660,#14661, - #14662,#14663,#14664,#14665,#14666,#14667,#14668,#14669,#14670, - #14671,#14672,#14673),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17033 = CARTESIAN_POINT('',(0.479289321881,0.25,2.071067811865E-002)); +#17034 = CARTESIAN_POINT('',(0.479289321881,0.25,5.E-002)); +#17035 = CARTESIAN_POINT('',(0.45,0.2,-6.776263578034E-018)); +#17036 = CARTESIAN_POINT('',(0.45,0.229289321881,-5.440958319961E-017)); +#17037 = CARTESIAN_POINT('',(0.45,0.25,2.071067811865E-002)); +#17038 = CARTESIAN_POINT('',(0.45,0.25,5.E-002)); +#17039 = DEFINITIONAL_REPRESENTATION('',(#17040),#17066); +#17040 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17041,#17042,#17043,#17044, + #17045,#17046,#17047,#17048,#17049,#17050,#17051,#17052,#17053, + #17054,#17055,#17056,#17057,#17058,#17059,#17060,#17061,#17062, + #17063,#17064,#17065),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -17807,85 +20796,85 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14649 = CARTESIAN_POINT('',(1.,1.)); -#14650 = CARTESIAN_POINT('',(0.983172198663,1.)); -#14651 = CARTESIAN_POINT('',(0.950009297011,1.)); -#14652 = CARTESIAN_POINT('',(0.901574474096,1.)); -#14653 = CARTESIAN_POINT('',(0.854275086925,1.)); -#14654 = CARTESIAN_POINT('',(0.807956362777,1.)); -#14655 = CARTESIAN_POINT('',(0.762473275577,1.)); -#14656 = CARTESIAN_POINT('',(0.717690577461,1.)); -#14657 = CARTESIAN_POINT('',(0.673480563786,1.)); -#14658 = CARTESIAN_POINT('',(0.629721689409,1.)); -#14659 = CARTESIAN_POINT('',(0.586297147708,1.)); -#14660 = CARTESIAN_POINT('',(0.543093605115,1.)); -#14661 = CARTESIAN_POINT('',(0.5,1.)); -#14662 = CARTESIAN_POINT('',(0.456906394885,1.)); -#14663 = CARTESIAN_POINT('',(0.413702852292,1.)); -#14664 = CARTESIAN_POINT('',(0.370278310591,1.)); -#14665 = CARTESIAN_POINT('',(0.326519436214,1.)); -#14666 = CARTESIAN_POINT('',(0.282309422539,1.)); -#14667 = CARTESIAN_POINT('',(0.237526724423,1.)); -#14668 = CARTESIAN_POINT('',(0.192043637223,1.)); -#14669 = CARTESIAN_POINT('',(0.145724913075,1.)); -#14670 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#14671 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#14672 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#14673 = CARTESIAN_POINT('',(0.E+000,1.)); -#14674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14675 = ORIENTED_EDGE('',*,*,#14676,.F.); -#14676 = EDGE_CURVE('',#14519,#14615,#14677,.T.); -#14677 = SURFACE_CURVE('',#14678,(#14682,#14688),.PCURVE_S1.); -#14678 = LINE('',#14679,#14680); -#14679 = CARTESIAN_POINT('',(0.45,0.25,0.3)); -#14680 = VECTOR('',#14681,1.); -#14681 = DIRECTION('',(-2.633792516221E-061,2.69486466099E-031,-1.)); -#14682 = PCURVE('',#13514,#14683); -#14683 = DEFINITIONAL_REPRESENTATION('',(#14684),#14687); -#14684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14685,#14686),.UNSPECIFIED., +#17041 = CARTESIAN_POINT('',(1.,1.)); +#17042 = CARTESIAN_POINT('',(0.983172198663,1.)); +#17043 = CARTESIAN_POINT('',(0.950009297011,1.)); +#17044 = CARTESIAN_POINT('',(0.901574474096,1.)); +#17045 = CARTESIAN_POINT('',(0.854275086925,1.)); +#17046 = CARTESIAN_POINT('',(0.807956362777,1.)); +#17047 = CARTESIAN_POINT('',(0.762473275577,1.)); +#17048 = CARTESIAN_POINT('',(0.717690577461,1.)); +#17049 = CARTESIAN_POINT('',(0.673480563786,1.)); +#17050 = CARTESIAN_POINT('',(0.629721689409,1.)); +#17051 = CARTESIAN_POINT('',(0.586297147708,1.)); +#17052 = CARTESIAN_POINT('',(0.543093605115,1.)); +#17053 = CARTESIAN_POINT('',(0.5,1.)); +#17054 = CARTESIAN_POINT('',(0.456906394885,1.)); +#17055 = CARTESIAN_POINT('',(0.413702852292,1.)); +#17056 = CARTESIAN_POINT('',(0.370278310591,1.)); +#17057 = CARTESIAN_POINT('',(0.326519436214,1.)); +#17058 = CARTESIAN_POINT('',(0.282309422539,1.)); +#17059 = CARTESIAN_POINT('',(0.237526724423,1.)); +#17060 = CARTESIAN_POINT('',(0.192043637223,1.)); +#17061 = CARTESIAN_POINT('',(0.145724913075,1.)); +#17062 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#17063 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#17064 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#17065 = CARTESIAN_POINT('',(0.E+000,1.)); +#17066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17067 = ORIENTED_EDGE('',*,*,#17068,.F.); +#17068 = EDGE_CURVE('',#16911,#17007,#17069,.T.); +#17069 = SURFACE_CURVE('',#17070,(#17074,#17080),.PCURVE_S1.); +#17070 = LINE('',#17071,#17072); +#17071 = CARTESIAN_POINT('',(0.45,0.25,0.3)); +#17072 = VECTOR('',#17073,1.); +#17073 = DIRECTION('',(-2.633792516221E-061,2.69486466099E-031,-1.)); +#17074 = PCURVE('',#15906,#17075); +#17075 = DEFINITIONAL_REPRESENTATION('',(#17076),#17079); +#17076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17077,#17078),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#14685 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#14686 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#14687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14688 = PCURVE('',#14689,#14694); -#14689 = PLANE('',#14690); -#14690 = AXIS2_PLACEMENT_3D('',#14691,#14692,#14693); -#14691 = CARTESIAN_POINT('',(0.375,0.25,0.3)); -#14692 = DIRECTION('',(-9.773375837189E-031,1.,2.69486466099E-031)); -#14693 = DIRECTION('',(-1.,-9.773375837189E-031,-1.359521846759E-077)); -#14694 = DEFINITIONAL_REPRESENTATION('',(#14695),#14699); -#14695 = LINE('',#14696,#14697); -#14696 = CARTESIAN_POINT('',(-7.5E-002,1.975344387166E-062)); -#14697 = VECTOR('',#14698,1.); -#14698 = DIRECTION('',(-3.454467422038E-077,-1.)); -#14699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14700 = ORIENTED_EDGE('',*,*,#14518,.T.); -#14701 = ORIENTED_EDGE('',*,*,#13491,.T.); -#14702 = ADVANCED_FACE('',(#14703),#14630,.T.); -#14703 = FACE_BOUND('',#14704,.T.); -#14704 = EDGE_LOOP('',(#14705,#14750,#14798)); -#14705 = ORIENTED_EDGE('',*,*,#14706,.F.); -#14706 = EDGE_CURVE('',#14707,#13494,#14709,.T.); -#14707 = VERTEX_POINT('',#14708); -#14708 = CARTESIAN_POINT('',(0.45,0.2,1.055240209696E-017)); -#14709 = SURFACE_CURVE('',#14710,(#14715,#14744),.PCURVE_S1.); -#14710 = CIRCLE('',#14711,5.E-002); -#14711 = AXIS2_PLACEMENT_3D('',#14712,#14713,#14714); -#14712 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); -#14713 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#14714 = DIRECTION('',(0.E+000,0.E+000,1.)); -#14715 = PCURVE('',#14630,#14716); -#14716 = DEFINITIONAL_REPRESENTATION('',(#14717),#14743); -#14717 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14718,#14719,#14720,#14721, - #14722,#14723,#14724,#14725,#14726,#14727,#14728,#14729,#14730, - #14731,#14732,#14733,#14734,#14735,#14736,#14737,#14738,#14739, - #14740,#14741,#14742),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17077 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#17078 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#17079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17080 = PCURVE('',#17081,#17086); +#17081 = PLANE('',#17082); +#17082 = AXIS2_PLACEMENT_3D('',#17083,#17084,#17085); +#17083 = CARTESIAN_POINT('',(0.375,0.25,0.3)); +#17084 = DIRECTION('',(-9.773375837189E-031,1.,2.69486466099E-031)); +#17085 = DIRECTION('',(-1.,-9.773375837189E-031,-1.359521846759E-077)); +#17086 = DEFINITIONAL_REPRESENTATION('',(#17087),#17091); +#17087 = LINE('',#17088,#17089); +#17088 = CARTESIAN_POINT('',(-7.5E-002,1.975344387166E-062)); +#17089 = VECTOR('',#17090,1.); +#17090 = DIRECTION('',(-3.454467422038E-077,-1.)); +#17091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17092 = ORIENTED_EDGE('',*,*,#16910,.T.); +#17093 = ORIENTED_EDGE('',*,*,#15883,.T.); +#17094 = ADVANCED_FACE('',(#17095),#17022,.T.); +#17095 = FACE_BOUND('',#17096,.T.); +#17096 = EDGE_LOOP('',(#17097,#17142,#17190)); +#17097 = ORIENTED_EDGE('',*,*,#17098,.F.); +#17098 = EDGE_CURVE('',#17099,#15886,#17101,.T.); +#17099 = VERTEX_POINT('',#17100); +#17100 = CARTESIAN_POINT('',(0.45,0.2,1.055240209696E-017)); +#17101 = SURFACE_CURVE('',#17102,(#17107,#17136),.PCURVE_S1.); +#17102 = CIRCLE('',#17103,5.E-002); +#17103 = AXIS2_PLACEMENT_3D('',#17104,#17105,#17106); +#17104 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); +#17105 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#17106 = DIRECTION('',(0.E+000,0.E+000,1.)); +#17107 = PCURVE('',#17022,#17108); +#17108 = DEFINITIONAL_REPRESENTATION('',(#17109),#17135); +#17109 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17110,#17111,#17112,#17113, + #17114,#17115,#17116,#17117,#17118,#17119,#17120,#17121,#17122, + #17123,#17124,#17125,#17126,#17127,#17128,#17129,#17130,#17131, + #17132,#17133,#17134),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -17893,58 +20882,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#14718 = CARTESIAN_POINT('',(1.,0.E+000)); -#14719 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#14720 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#14721 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#14722 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#14723 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#14724 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14725 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14726 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14727 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14728 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14729 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14730 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14731 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14732 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14733 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14734 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14735 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14736 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14737 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14738 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14739 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14740 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#14741 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#14742 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14744 = PCURVE('',#13593,#14745); -#14745 = DEFINITIONAL_REPRESENTATION('',(#14746),#14749); -#14746 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14747,#14748),.UNSPECIFIED., +#17110 = CARTESIAN_POINT('',(1.,0.E+000)); +#17111 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#17112 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#17113 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#17114 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#17115 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#17116 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#17117 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#17118 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#17119 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#17120 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#17121 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#17122 = CARTESIAN_POINT('',(0.5,0.E+000)); +#17123 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#17124 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#17125 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#17126 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#17127 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#17128 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#17129 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#17130 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#17131 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#17132 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#17133 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#17134 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#17135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17136 = PCURVE('',#15985,#17137); +#17137 = DEFINITIONAL_REPRESENTATION('',(#17138),#17141); +#17138 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17139,#17140),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#14747 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#14748 = CARTESIAN_POINT('',(1.570796326795,0.45)); -#14749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14750 = ORIENTED_EDGE('',*,*,#14751,.F.); -#14751 = EDGE_CURVE('',#14615,#14707,#14752,.T.); -#14752 = SURFACE_CURVE('',#14753,(#14758,#14787),.PCURVE_S1.); -#14753 = CIRCLE('',#14754,5.E-002); -#14754 = AXIS2_PLACEMENT_3D('',#14755,#14756,#14757); -#14755 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); -#14756 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); -#14757 = DIRECTION('',(1.224646799147E-016,1.626303258728E-015,-1.)); -#14758 = PCURVE('',#14630,#14759); -#14759 = DEFINITIONAL_REPRESENTATION('',(#14760),#14786); -#14760 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14761,#14762,#14763,#14764, - #14765,#14766,#14767,#14768,#14769,#14770,#14771,#14772,#14773, - #14774,#14775,#14776,#14777,#14778,#14779,#14780,#14781,#14782, - #14783,#14784,#14785),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17139 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#17140 = CARTESIAN_POINT('',(1.570796326795,0.45)); +#17141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17142 = ORIENTED_EDGE('',*,*,#17143,.F.); +#17143 = EDGE_CURVE('',#17007,#17099,#17144,.T.); +#17144 = SURFACE_CURVE('',#17145,(#17150,#17179),.PCURVE_S1.); +#17145 = CIRCLE('',#17146,5.E-002); +#17146 = AXIS2_PLACEMENT_3D('',#17147,#17148,#17149); +#17147 = CARTESIAN_POINT('',(0.45,0.2,5.E-002)); +#17148 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); +#17149 = DIRECTION('',(1.224646799147E-016,1.626303258728E-015,-1.)); +#17150 = PCURVE('',#17022,#17151); +#17151 = DEFINITIONAL_REPRESENTATION('',(#17152),#17178); +#17152 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17153,#17154,#17155,#17156, + #17157,#17158,#17159,#17160,#17161,#17162,#17163,#17164,#17165, + #17166,#17167,#17168,#17169,#17170,#17171,#17172,#17173,#17174, + #17175,#17176,#17177),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -17952,79 +20941,79 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14761 = CARTESIAN_POINT('',(1.,1.)); -#14762 = CARTESIAN_POINT('',(1.,0.983172198663)); -#14763 = CARTESIAN_POINT('',(1.,0.950009297011)); -#14764 = CARTESIAN_POINT('',(1.,0.901574474096)); -#14765 = CARTESIAN_POINT('',(1.,0.854275086925)); -#14766 = CARTESIAN_POINT('',(1.,0.807956362777)); -#14767 = CARTESIAN_POINT('',(1.,0.762473275577)); -#14768 = CARTESIAN_POINT('',(1.,0.717690577461)); -#14769 = CARTESIAN_POINT('',(1.,0.673480563786)); -#14770 = CARTESIAN_POINT('',(1.,0.629721689409)); -#14771 = CARTESIAN_POINT('',(1.,0.586297147708)); -#14772 = CARTESIAN_POINT('',(1.,0.543093605115)); -#14773 = CARTESIAN_POINT('',(1.,0.5)); -#14774 = CARTESIAN_POINT('',(1.,0.456906394885)); -#14775 = CARTESIAN_POINT('',(1.,0.413702852292)); -#14776 = CARTESIAN_POINT('',(1.,0.370278310591)); -#14777 = CARTESIAN_POINT('',(1.,0.326519436214)); -#14778 = CARTESIAN_POINT('',(1.,0.282309422539)); -#14779 = CARTESIAN_POINT('',(1.,0.237526724423)); -#14780 = CARTESIAN_POINT('',(1.,0.192043637223)); -#14781 = CARTESIAN_POINT('',(1.,0.145724913075)); -#14782 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); -#14783 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); -#14784 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); -#14785 = CARTESIAN_POINT('',(1.,0.E+000)); -#14786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14787 = PCURVE('',#14788,#14793); -#14788 = CYLINDRICAL_SURFACE('',#14789,5.E-002); -#14789 = AXIS2_PLACEMENT_3D('',#14790,#14791,#14792); -#14790 = CARTESIAN_POINT('',(0.375,0.2,5.E-002)); -#14791 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); -#14792 = DIRECTION('',(1.224646799147E-016,1.196893343588E-046,-1.)); -#14793 = DEFINITIONAL_REPRESENTATION('',(#14794),#14797); -#14794 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14795,#14796),.UNSPECIFIED., +#17153 = CARTESIAN_POINT('',(1.,1.)); +#17154 = CARTESIAN_POINT('',(1.,0.983172198663)); +#17155 = CARTESIAN_POINT('',(1.,0.950009297011)); +#17156 = CARTESIAN_POINT('',(1.,0.901574474096)); +#17157 = CARTESIAN_POINT('',(1.,0.854275086925)); +#17158 = CARTESIAN_POINT('',(1.,0.807956362777)); +#17159 = CARTESIAN_POINT('',(1.,0.762473275577)); +#17160 = CARTESIAN_POINT('',(1.,0.717690577461)); +#17161 = CARTESIAN_POINT('',(1.,0.673480563786)); +#17162 = CARTESIAN_POINT('',(1.,0.629721689409)); +#17163 = CARTESIAN_POINT('',(1.,0.586297147708)); +#17164 = CARTESIAN_POINT('',(1.,0.543093605115)); +#17165 = CARTESIAN_POINT('',(1.,0.5)); +#17166 = CARTESIAN_POINT('',(1.,0.456906394885)); +#17167 = CARTESIAN_POINT('',(1.,0.413702852292)); +#17168 = CARTESIAN_POINT('',(1.,0.370278310591)); +#17169 = CARTESIAN_POINT('',(1.,0.326519436214)); +#17170 = CARTESIAN_POINT('',(1.,0.282309422539)); +#17171 = CARTESIAN_POINT('',(1.,0.237526724423)); +#17172 = CARTESIAN_POINT('',(1.,0.192043637223)); +#17173 = CARTESIAN_POINT('',(1.,0.145724913075)); +#17174 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); +#17175 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); +#17176 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); +#17177 = CARTESIAN_POINT('',(1.,0.E+000)); +#17178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17179 = PCURVE('',#17180,#17185); +#17180 = CYLINDRICAL_SURFACE('',#17181,5.E-002); +#17181 = AXIS2_PLACEMENT_3D('',#17182,#17183,#17184); +#17182 = CARTESIAN_POINT('',(0.375,0.2,5.E-002)); +#17183 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); +#17184 = DIRECTION('',(1.224646799147E-016,1.196893343588E-046,-1.)); +#17185 = DEFINITIONAL_REPRESENTATION('',(#17186),#17189); +#17186 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17187,#17188),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14795 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#14796 = CARTESIAN_POINT('',(1.7763568394E-015,7.5E-002)); -#14797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14798 = ORIENTED_EDGE('',*,*,#14614,.T.); -#14799 = ADVANCED_FACE('',(#14800),#13593,.T.); -#14800 = FACE_BOUND('',#14801,.T.); -#14801 = EDGE_LOOP('',(#14802,#14864,#14889,#14890)); -#14802 = ORIENTED_EDGE('',*,*,#14803,.F.); -#14803 = EDGE_CURVE('',#14804,#13553,#14806,.T.); -#14804 = VERTEX_POINT('',#14805); -#14805 = CARTESIAN_POINT('',(0.45,-0.2,1.180757853316E-017)); -#14806 = SURFACE_CURVE('',#14807,(#14812,#14818),.PCURVE_S1.); -#14807 = CIRCLE('',#14808,5.E-002); -#14808 = AXIS2_PLACEMENT_3D('',#14809,#14810,#14811); -#14809 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); -#14810 = DIRECTION('',(-6.820895540155E-048,-1.,1.836970198721E-016)); -#14811 = DIRECTION('',(1.,-3.236426505397E-031,-1.761828530289E-015)); -#14812 = PCURVE('',#13593,#14813); -#14813 = DEFINITIONAL_REPRESENTATION('',(#14814),#14817); -#14814 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14815,#14816),.UNSPECIFIED., +#17187 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#17188 = CARTESIAN_POINT('',(1.7763568394E-015,7.5E-002)); +#17189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17190 = ORIENTED_EDGE('',*,*,#17006,.T.); +#17191 = ADVANCED_FACE('',(#17192),#15985,.T.); +#17192 = FACE_BOUND('',#17193,.T.); +#17193 = EDGE_LOOP('',(#17194,#17256,#17281,#17282)); +#17194 = ORIENTED_EDGE('',*,*,#17195,.F.); +#17195 = EDGE_CURVE('',#17196,#15945,#17198,.T.); +#17196 = VERTEX_POINT('',#17197); +#17197 = CARTESIAN_POINT('',(0.45,-0.2,1.180757853316E-017)); +#17198 = SURFACE_CURVE('',#17199,(#17204,#17210),.PCURVE_S1.); +#17199 = CIRCLE('',#17200,5.E-002); +#17200 = AXIS2_PLACEMENT_3D('',#17201,#17202,#17203); +#17201 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); +#17202 = DIRECTION('',(-6.820895540155E-048,-1.,1.836970198721E-016)); +#17203 = DIRECTION('',(1.,-3.236426505397E-031,-1.761828530289E-015)); +#17204 = PCURVE('',#15985,#17205); +#17205 = DEFINITIONAL_REPRESENTATION('',(#17206),#17209); +#17206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17207,#17208),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#14815 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#14816 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); -#14817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17207 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#17208 = CARTESIAN_POINT('',(1.570796326795,5.E-002)); +#17209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#14818 = PCURVE('',#14819,#14836); -#14819 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#14820,#14821,#14822,#14823) - ,(#14824,#14825,#14826,#14827) - ,(#14828,#14829,#14830,#14831) - ,(#14832,#14833,#14834,#14835 +#17210 = PCURVE('',#17211,#17228); +#17211 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17212,#17213,#17214,#17215) + ,(#17216,#17217,#17218,#17219) + ,(#17220,#17221,#17222,#17223) + ,(#17224,#17225,#17226,#17227 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -18033,28 +21022,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#14820 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); -#14821 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); -#14822 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); -#14823 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); -#14824 = CARTESIAN_POINT('',(0.5,-0.229289321881,5.E-002)); -#14825 = CARTESIAN_POINT('',(0.5,-0.229289321881,3.284271247462E-002)); -#14826 = CARTESIAN_POINT('',(0.5,-0.217157287525,2.071067811865E-002)); -#14827 = CARTESIAN_POINT('',(0.5,-0.2,2.071067811865E-002)); -#14828 = CARTESIAN_POINT('',(0.479289321881,-0.25,5.E-002)); -#14829 = CARTESIAN_POINT('',(0.479289321881,-0.25,2.071067811865E-002)); -#14830 = CARTESIAN_POINT('',(0.479289321881,-0.229289321881, +#17212 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); +#17213 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); +#17214 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); +#17215 = CARTESIAN_POINT('',(0.5,-0.2,5.E-002)); +#17216 = CARTESIAN_POINT('',(0.5,-0.229289321881,5.E-002)); +#17217 = CARTESIAN_POINT('',(0.5,-0.229289321881,3.284271247462E-002)); +#17218 = CARTESIAN_POINT('',(0.5,-0.217157287525,2.071067811865E-002)); +#17219 = CARTESIAN_POINT('',(0.5,-0.2,2.071067811865E-002)); +#17220 = CARTESIAN_POINT('',(0.479289321881,-0.25,5.E-002)); +#17221 = CARTESIAN_POINT('',(0.479289321881,-0.25,2.071067811865E-002)); +#17222 = CARTESIAN_POINT('',(0.479289321881,-0.229289321881, 1.587777320719E-017)); -#14831 = CARTESIAN_POINT('',(0.479289321881,-0.2,0.E+000)); -#14832 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); -#14833 = CARTESIAN_POINT('',(0.45,-0.25,2.071067811865E-002)); -#14834 = CARTESIAN_POINT('',(0.45,-0.229289321881,1.587777320719E-017)); -#14835 = CARTESIAN_POINT('',(0.45,-0.2,0.E+000)); -#14836 = DEFINITIONAL_REPRESENTATION('',(#14837),#14863); -#14837 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14838,#14839,#14840,#14841, - #14842,#14843,#14844,#14845,#14846,#14847,#14848,#14849,#14850, - #14851,#14852,#14853,#14854,#14855,#14856,#14857,#14858,#14859, - #14860,#14861,#14862),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17223 = CARTESIAN_POINT('',(0.479289321881,-0.2,0.E+000)); +#17224 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); +#17225 = CARTESIAN_POINT('',(0.45,-0.25,2.071067811865E-002)); +#17226 = CARTESIAN_POINT('',(0.45,-0.229289321881,1.587777320719E-017)); +#17227 = CARTESIAN_POINT('',(0.45,-0.2,0.E+000)); +#17228 = DEFINITIONAL_REPRESENTATION('',(#17229),#17255); +#17229 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17230,#17231,#17232,#17233, + #17234,#17235,#17236,#17237,#17238,#17239,#17240,#17241,#17242, + #17243,#17244,#17245,#17246,#17247,#17248,#17249,#17250,#17251, + #17252,#17253,#17254),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -18062,85 +21051,85 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#14838 = CARTESIAN_POINT('',(1.,1.)); -#14839 = CARTESIAN_POINT('',(0.983172198663,1.)); -#14840 = CARTESIAN_POINT('',(0.950009297011,1.)); -#14841 = CARTESIAN_POINT('',(0.901574474096,1.)); -#14842 = CARTESIAN_POINT('',(0.854275086925,1.)); -#14843 = CARTESIAN_POINT('',(0.807956362777,1.)); -#14844 = CARTESIAN_POINT('',(0.762473275577,1.)); -#14845 = CARTESIAN_POINT('',(0.717690577461,1.)); -#14846 = CARTESIAN_POINT('',(0.673480563786,1.)); -#14847 = CARTESIAN_POINT('',(0.629721689409,1.)); -#14848 = CARTESIAN_POINT('',(0.586297147708,1.)); -#14849 = CARTESIAN_POINT('',(0.543093605115,1.)); -#14850 = CARTESIAN_POINT('',(0.5,1.)); -#14851 = CARTESIAN_POINT('',(0.456906394885,1.)); -#14852 = CARTESIAN_POINT('',(0.413702852292,1.)); -#14853 = CARTESIAN_POINT('',(0.370278310591,1.)); -#14854 = CARTESIAN_POINT('',(0.326519436214,1.)); -#14855 = CARTESIAN_POINT('',(0.282309422539,1.)); -#14856 = CARTESIAN_POINT('',(0.237526724423,1.)); -#14857 = CARTESIAN_POINT('',(0.192043637223,1.)); -#14858 = CARTESIAN_POINT('',(0.145724913075,1.)); -#14859 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#14860 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#14861 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#14862 = CARTESIAN_POINT('',(0.E+000,1.)); -#14863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14864 = ORIENTED_EDGE('',*,*,#14865,.F.); -#14865 = EDGE_CURVE('',#14707,#14804,#14866,.T.); -#14866 = SURFACE_CURVE('',#14867,(#14871,#14877),.PCURVE_S1.); -#14867 = LINE('',#14868,#14869); -#14868 = CARTESIAN_POINT('',(0.45,-0.25,2.449293598295E-017)); -#14869 = VECTOR('',#14870,1.); -#14870 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#14871 = PCURVE('',#13593,#14872); -#14872 = DEFINITIONAL_REPRESENTATION('',(#14873),#14876); -#14873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14874,#14875),.UNSPECIFIED., +#17230 = CARTESIAN_POINT('',(1.,1.)); +#17231 = CARTESIAN_POINT('',(0.983172198663,1.)); +#17232 = CARTESIAN_POINT('',(0.950009297011,1.)); +#17233 = CARTESIAN_POINT('',(0.901574474096,1.)); +#17234 = CARTESIAN_POINT('',(0.854275086925,1.)); +#17235 = CARTESIAN_POINT('',(0.807956362777,1.)); +#17236 = CARTESIAN_POINT('',(0.762473275577,1.)); +#17237 = CARTESIAN_POINT('',(0.717690577461,1.)); +#17238 = CARTESIAN_POINT('',(0.673480563786,1.)); +#17239 = CARTESIAN_POINT('',(0.629721689409,1.)); +#17240 = CARTESIAN_POINT('',(0.586297147708,1.)); +#17241 = CARTESIAN_POINT('',(0.543093605115,1.)); +#17242 = CARTESIAN_POINT('',(0.5,1.)); +#17243 = CARTESIAN_POINT('',(0.456906394885,1.)); +#17244 = CARTESIAN_POINT('',(0.413702852292,1.)); +#17245 = CARTESIAN_POINT('',(0.370278310591,1.)); +#17246 = CARTESIAN_POINT('',(0.326519436214,1.)); +#17247 = CARTESIAN_POINT('',(0.282309422539,1.)); +#17248 = CARTESIAN_POINT('',(0.237526724423,1.)); +#17249 = CARTESIAN_POINT('',(0.192043637223,1.)); +#17250 = CARTESIAN_POINT('',(0.145724913075,1.)); +#17251 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#17252 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#17253 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#17254 = CARTESIAN_POINT('',(0.E+000,1.)); +#17255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17256 = ORIENTED_EDGE('',*,*,#17257,.F.); +#17257 = EDGE_CURVE('',#17099,#17196,#17258,.T.); +#17258 = SURFACE_CURVE('',#17259,(#17263,#17269),.PCURVE_S1.); +#17259 = LINE('',#17260,#17261); +#17260 = CARTESIAN_POINT('',(0.45,-0.25,2.449293598295E-017)); +#17261 = VECTOR('',#17262,1.); +#17262 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#17263 = PCURVE('',#15985,#17264); +#17264 = DEFINITIONAL_REPRESENTATION('',(#17265),#17268); +#17265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17266,#17267),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#14874 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#14875 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#14876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14877 = PCURVE('',#14878,#14883); -#14878 = PLANE('',#14879); -#14879 = AXIS2_PLACEMENT_3D('',#14880,#14881,#14882); -#14880 = CARTESIAN_POINT('',(0.375,-0.25,1.530808498934E-017)); -#14881 = DIRECTION('',(1.224646799147E-016,0.E+000,-1.)); -#14882 = DIRECTION('',(-1.,0.E+000,-1.224646799147E-016)); -#14883 = DEFINITIONAL_REPRESENTATION('',(#14884),#14888); -#14884 = LINE('',#14885,#14886); -#14885 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); -#14886 = VECTOR('',#14887,1.); -#14887 = DIRECTION('',(0.E+000,-1.)); -#14888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14889 = ORIENTED_EDGE('',*,*,#14706,.T.); -#14890 = ORIENTED_EDGE('',*,*,#13579,.T.); -#14891 = ADVANCED_FACE('',(#14892),#14819,.T.); -#14892 = FACE_BOUND('',#14893,.T.); -#14893 = EDGE_LOOP('',(#14894,#14939,#14987)); -#14894 = ORIENTED_EDGE('',*,*,#14895,.F.); -#14895 = EDGE_CURVE('',#14896,#13553,#14898,.T.); -#14896 = VERTEX_POINT('',#14897); -#14897 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); -#14898 = SURFACE_CURVE('',#14899,(#14904,#14933),.PCURVE_S1.); -#14899 = CIRCLE('',#14900,5.E-002); -#14900 = AXIS2_PLACEMENT_3D('',#14901,#14902,#14903); -#14901 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); -#14902 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#14903 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); -#14904 = PCURVE('',#14819,#14905); -#14905 = DEFINITIONAL_REPRESENTATION('',(#14906),#14932); -#14906 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14907,#14908,#14909,#14910, - #14911,#14912,#14913,#14914,#14915,#14916,#14917,#14918,#14919, - #14920,#14921,#14922,#14923,#14924,#14925,#14926,#14927,#14928, - #14929,#14930,#14931),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17266 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#17267 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#17268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17269 = PCURVE('',#17270,#17275); +#17270 = PLANE('',#17271); +#17271 = AXIS2_PLACEMENT_3D('',#17272,#17273,#17274); +#17272 = CARTESIAN_POINT('',(0.375,-0.25,1.530808498934E-017)); +#17273 = DIRECTION('',(1.224646799147E-016,0.E+000,-1.)); +#17274 = DIRECTION('',(-1.,0.E+000,-1.224646799147E-016)); +#17275 = DEFINITIONAL_REPRESENTATION('',(#17276),#17280); +#17276 = LINE('',#17277,#17278); +#17277 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); +#17278 = VECTOR('',#17279,1.); +#17279 = DIRECTION('',(0.E+000,-1.)); +#17280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17281 = ORIENTED_EDGE('',*,*,#17098,.T.); +#17282 = ORIENTED_EDGE('',*,*,#15971,.T.); +#17283 = ADVANCED_FACE('',(#17284),#17211,.T.); +#17284 = FACE_BOUND('',#17285,.T.); +#17285 = EDGE_LOOP('',(#17286,#17331,#17379)); +#17286 = ORIENTED_EDGE('',*,*,#17287,.F.); +#17287 = EDGE_CURVE('',#17288,#15945,#17290,.T.); +#17288 = VERTEX_POINT('',#17289); +#17289 = CARTESIAN_POINT('',(0.45,-0.25,5.E-002)); +#17290 = SURFACE_CURVE('',#17291,(#17296,#17325),.PCURVE_S1.); +#17291 = CIRCLE('',#17292,5.E-002); +#17292 = AXIS2_PLACEMENT_3D('',#17293,#17294,#17295); +#17293 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); +#17294 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#17295 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); +#17296 = PCURVE('',#17211,#17297); +#17297 = DEFINITIONAL_REPRESENTATION('',(#17298),#17324); +#17298 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17299,#17300,#17301,#17302, + #17303,#17304,#17305,#17306,#17307,#17308,#17309,#17310,#17311, + #17312,#17313,#17314,#17315,#17316,#17317,#17318,#17319,#17320, + #17321,#17322,#17323),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -18148,58 +21137,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#14907 = CARTESIAN_POINT('',(1.,0.E+000)); -#14908 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#14909 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#14910 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#14911 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#14912 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#14913 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#14914 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#14915 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#14916 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#14917 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#14918 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#14919 = CARTESIAN_POINT('',(0.5,0.E+000)); -#14920 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#14921 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#14922 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#14923 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#14924 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#14925 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#14926 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#14927 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#14928 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#14929 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#14930 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#14931 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#14932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14933 = PCURVE('',#13568,#14934); -#14934 = DEFINITIONAL_REPRESENTATION('',(#14935),#14938); -#14935 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14936,#14937),.UNSPECIFIED., +#17299 = CARTESIAN_POINT('',(1.,0.E+000)); +#17300 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#17301 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#17302 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#17303 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#17304 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#17305 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#17306 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#17307 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#17308 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#17309 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#17310 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#17311 = CARTESIAN_POINT('',(0.5,0.E+000)); +#17312 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#17313 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#17314 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#17315 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#17316 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#17317 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#17318 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#17319 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#17320 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#17321 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#17322 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#17323 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#17324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17325 = PCURVE('',#15960,#17326); +#17326 = DEFINITIONAL_REPRESENTATION('',(#17327),#17330); +#17327 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17328,#17329),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#14936 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#14937 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#14938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14939 = ORIENTED_EDGE('',*,*,#14940,.F.); -#14940 = EDGE_CURVE('',#14804,#14896,#14941,.T.); -#14941 = SURFACE_CURVE('',#14942,(#14947,#14976),.PCURVE_S1.); -#14942 = CIRCLE('',#14943,5.E-002); -#14943 = AXIS2_PLACEMENT_3D('',#14944,#14945,#14946); -#14944 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); -#14945 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); -#14946 = DIRECTION('',(-1.224646799147E-016,-1.196893343588E-046,1.)); -#14947 = PCURVE('',#14819,#14948); -#14948 = DEFINITIONAL_REPRESENTATION('',(#14949),#14975); -#14949 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#14950,#14951,#14952,#14953, - #14954,#14955,#14956,#14957,#14958,#14959,#14960,#14961,#14962, - #14963,#14964,#14965,#14966,#14967,#14968,#14969,#14970,#14971, - #14972,#14973,#14974),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17328 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#17329 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#17330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17331 = ORIENTED_EDGE('',*,*,#17332,.F.); +#17332 = EDGE_CURVE('',#17196,#17288,#17333,.T.); +#17333 = SURFACE_CURVE('',#17334,(#17339,#17368),.PCURVE_S1.); +#17334 = CIRCLE('',#17335,5.E-002); +#17335 = AXIS2_PLACEMENT_3D('',#17336,#17337,#17338); +#17336 = CARTESIAN_POINT('',(0.45,-0.2,5.E-002)); +#17337 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); +#17338 = DIRECTION('',(-1.224646799147E-016,-1.196893343588E-046,1.)); +#17339 = PCURVE('',#17211,#17340); +#17340 = DEFINITIONAL_REPRESENTATION('',(#17341),#17367); +#17341 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17342,#17343,#17344,#17345, + #17346,#17347,#17348,#17349,#17350,#17351,#17352,#17353,#17354, + #17355,#17356,#17357,#17358,#17359,#17360,#17361,#17362,#17363, + #17364,#17365,#17366),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -18207,184 +21196,184 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#14950 = CARTESIAN_POINT('',(1.,1.)); -#14951 = CARTESIAN_POINT('',(1.,0.983172198663)); -#14952 = CARTESIAN_POINT('',(1.,0.950009297011)); -#14953 = CARTESIAN_POINT('',(1.,0.901574474096)); -#14954 = CARTESIAN_POINT('',(1.,0.854275086925)); -#14955 = CARTESIAN_POINT('',(1.,0.807956362777)); -#14956 = CARTESIAN_POINT('',(1.,0.762473275577)); -#14957 = CARTESIAN_POINT('',(1.,0.717690577461)); -#14958 = CARTESIAN_POINT('',(1.,0.673480563786)); -#14959 = CARTESIAN_POINT('',(1.,0.629721689409)); -#14960 = CARTESIAN_POINT('',(1.,0.586297147708)); -#14961 = CARTESIAN_POINT('',(1.,0.543093605115)); -#14962 = CARTESIAN_POINT('',(1.,0.5)); -#14963 = CARTESIAN_POINT('',(1.,0.456906394885)); -#14964 = CARTESIAN_POINT('',(1.,0.413702852292)); -#14965 = CARTESIAN_POINT('',(1.,0.370278310591)); -#14966 = CARTESIAN_POINT('',(1.,0.326519436214)); -#14967 = CARTESIAN_POINT('',(1.,0.282309422539)); -#14968 = CARTESIAN_POINT('',(1.,0.237526724423)); -#14969 = CARTESIAN_POINT('',(1.,0.192043637223)); -#14970 = CARTESIAN_POINT('',(1.,0.145724913075)); -#14971 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); -#14972 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); -#14973 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); -#14974 = CARTESIAN_POINT('',(1.,0.E+000)); -#14975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14976 = PCURVE('',#14977,#14982); -#14977 = CYLINDRICAL_SURFACE('',#14978,5.E-002); -#14978 = AXIS2_PLACEMENT_3D('',#14979,#14980,#14981); -#14979 = CARTESIAN_POINT('',(0.375,-0.2,5.E-002)); -#14980 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); -#14981 = DIRECTION('',(-1.224646799147E-016,-1.196893343588E-046,1.)); -#14982 = DEFINITIONAL_REPRESENTATION('',(#14983),#14986); -#14983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#14984,#14985),.UNSPECIFIED., +#17342 = CARTESIAN_POINT('',(1.,1.)); +#17343 = CARTESIAN_POINT('',(1.,0.983172198663)); +#17344 = CARTESIAN_POINT('',(1.,0.950009297011)); +#17345 = CARTESIAN_POINT('',(1.,0.901574474096)); +#17346 = CARTESIAN_POINT('',(1.,0.854275086925)); +#17347 = CARTESIAN_POINT('',(1.,0.807956362777)); +#17348 = CARTESIAN_POINT('',(1.,0.762473275577)); +#17349 = CARTESIAN_POINT('',(1.,0.717690577461)); +#17350 = CARTESIAN_POINT('',(1.,0.673480563786)); +#17351 = CARTESIAN_POINT('',(1.,0.629721689409)); +#17352 = CARTESIAN_POINT('',(1.,0.586297147708)); +#17353 = CARTESIAN_POINT('',(1.,0.543093605115)); +#17354 = CARTESIAN_POINT('',(1.,0.5)); +#17355 = CARTESIAN_POINT('',(1.,0.456906394885)); +#17356 = CARTESIAN_POINT('',(1.,0.413702852292)); +#17357 = CARTESIAN_POINT('',(1.,0.370278310591)); +#17358 = CARTESIAN_POINT('',(1.,0.326519436214)); +#17359 = CARTESIAN_POINT('',(1.,0.282309422539)); +#17360 = CARTESIAN_POINT('',(1.,0.237526724423)); +#17361 = CARTESIAN_POINT('',(1.,0.192043637223)); +#17362 = CARTESIAN_POINT('',(1.,0.145724913075)); +#17363 = CARTESIAN_POINT('',(1.,9.842552590405E-002)); +#17364 = CARTESIAN_POINT('',(1.,4.999070298881E-002)); +#17365 = CARTESIAN_POINT('',(1.,1.682780133706E-002)); +#17366 = CARTESIAN_POINT('',(1.,0.E+000)); +#17367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17368 = PCURVE('',#17369,#17374); +#17369 = CYLINDRICAL_SURFACE('',#17370,5.E-002); +#17370 = AXIS2_PLACEMENT_3D('',#17371,#17372,#17373); +#17371 = CARTESIAN_POINT('',(0.375,-0.2,5.E-002)); +#17372 = DIRECTION('',(-1.,-9.773375837189E-031,-1.224646799147E-016)); +#17373 = DIRECTION('',(-1.224646799147E-016,-1.196893343588E-046,1.)); +#17374 = DEFINITIONAL_REPRESENTATION('',(#17375),#17378); +#17375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17376,#17377),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#14984 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); -#14985 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); -#14986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#14987 = ORIENTED_EDGE('',*,*,#14803,.T.); -#14988 = ADVANCED_FACE('',(#14989),#13568,.T.); -#14989 = FACE_BOUND('',#14990,.T.); -#14990 = EDGE_LOOP('',(#14991,#14992,#15017,#15018)); -#14991 = ORIENTED_EDGE('',*,*,#14336,.T.); -#14992 = ORIENTED_EDGE('',*,*,#14993,.T.); -#14993 = EDGE_CURVE('',#14268,#14896,#14994,.T.); -#14994 = SURFACE_CURVE('',#14995,(#14999,#15005),.PCURVE_S1.); -#14995 = LINE('',#14996,#14997); -#14996 = CARTESIAN_POINT('',(0.45,-0.25,0.3)); -#14997 = VECTOR('',#14998,1.); -#14998 = DIRECTION('',(-2.633792516221E-061,2.69486466099E-031,-1.)); -#14999 = PCURVE('',#13568,#15000); -#15000 = DEFINITIONAL_REPRESENTATION('',(#15001),#15004); -#15001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15002,#15003),.UNSPECIFIED., +#17376 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); +#17377 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); +#17378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17379 = ORIENTED_EDGE('',*,*,#17195,.T.); +#17380 = ADVANCED_FACE('',(#17381),#15960,.T.); +#17381 = FACE_BOUND('',#17382,.T.); +#17382 = EDGE_LOOP('',(#17383,#17384,#17409,#17410)); +#17383 = ORIENTED_EDGE('',*,*,#16728,.T.); +#17384 = ORIENTED_EDGE('',*,*,#17385,.T.); +#17385 = EDGE_CURVE('',#16660,#17288,#17386,.T.); +#17386 = SURFACE_CURVE('',#17387,(#17391,#17397),.PCURVE_S1.); +#17387 = LINE('',#17388,#17389); +#17388 = CARTESIAN_POINT('',(0.45,-0.25,0.3)); +#17389 = VECTOR('',#17390,1.); +#17390 = DIRECTION('',(-2.633792516221E-061,2.69486466099E-031,-1.)); +#17391 = PCURVE('',#15960,#17392); +#17392 = DEFINITIONAL_REPRESENTATION('',(#17393),#17396); +#17393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17394,#17395),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#15002 = CARTESIAN_POINT('',(3.14159265359,-0.25)); -#15003 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#15004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15005 = PCURVE('',#15006,#15011); -#15006 = PLANE('',#15007); -#15007 = AXIS2_PLACEMENT_3D('',#15008,#15009,#15010); -#15008 = CARTESIAN_POINT('',(0.375,-0.25,0.3)); -#15009 = DIRECTION('',(-9.773375837189E-031,1.,2.69486466099E-031)); -#15010 = DIRECTION('',(-1.,-9.773375837189E-031,-1.359521846759E-077)); -#15011 = DEFINITIONAL_REPRESENTATION('',(#15012),#15016); -#15012 = LINE('',#15013,#15014); -#15013 = CARTESIAN_POINT('',(-7.5E-002,1.975344387166E-062)); -#15014 = VECTOR('',#15015,1.); -#15015 = DIRECTION('',(-3.454467422038E-077,-1.)); -#15016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15017 = ORIENTED_EDGE('',*,*,#14895,.T.); -#15018 = ORIENTED_EDGE('',*,*,#13552,.T.); -#15019 = ADVANCED_FACE('',(#15020,#15030),#11925,.T.); -#15020 = FACE_BOUND('',#15021,.T.); -#15021 = EDGE_LOOP('',(#15022,#15023,#15024,#15025,#15026,#15027,#15028, - #15029)); -#15022 = ORIENTED_EDGE('',*,*,#14191,.T.); -#15023 = ORIENTED_EDGE('',*,*,#14242,.T.); -#15024 = ORIENTED_EDGE('',*,*,#13698,.T.); -#15025 = ORIENTED_EDGE('',*,*,#13793,.T.); -#15026 = ORIENTED_EDGE('',*,*,#13863,.T.); -#15027 = ORIENTED_EDGE('',*,*,#13958,.T.); -#15028 = ORIENTED_EDGE('',*,*,#14026,.T.); -#15029 = ORIENTED_EDGE('',*,*,#14121,.T.); -#15030 = FACE_BOUND('',#15031,.T.); -#15031 = EDGE_LOOP('',(#15032,#15033)); -#15032 = ORIENTED_EDGE('',*,*,#11902,.F.); -#15033 = ORIENTED_EDGE('',*,*,#15034,.F.); -#15034 = EDGE_CURVE('',#11905,#11903,#15035,.T.); -#15035 = SURFACE_CURVE('',#15036,(#15041,#15048),.PCURVE_S1.); -#15036 = CIRCLE('',#15037,7.825944375606E-002); -#15037 = AXIS2_PLACEMENT_3D('',#15038,#15039,#15040); -#15038 = CARTESIAN_POINT('',(-0.25,0.E+000,0.3)); -#15039 = DIRECTION('',(1.,0.E+000,0.E+000)); -#15040 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#15041 = PCURVE('',#11925,#15042); -#15042 = DEFINITIONAL_REPRESENTATION('',(#15043),#15047); -#15043 = CIRCLE('',#15044,7.825944375606E-002); -#15044 = AXIS2_PLACEMENT_2D('',#15045,#15046); -#15045 = CARTESIAN_POINT('',(0.E+000,0.25)); -#15046 = DIRECTION('',(1.,0.E+000)); -#15047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15048 = PCURVE('',#11952,#15049); -#15049 = DEFINITIONAL_REPRESENTATION('',(#15050),#15053); -#15050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15051,#15052),.UNSPECIFIED., +#17394 = CARTESIAN_POINT('',(3.14159265359,-0.25)); +#17395 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#17396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17397 = PCURVE('',#17398,#17403); +#17398 = PLANE('',#17399); +#17399 = AXIS2_PLACEMENT_3D('',#17400,#17401,#17402); +#17400 = CARTESIAN_POINT('',(0.375,-0.25,0.3)); +#17401 = DIRECTION('',(-9.773375837189E-031,1.,2.69486466099E-031)); +#17402 = DIRECTION('',(-1.,-9.773375837189E-031,-1.359521846759E-077)); +#17403 = DEFINITIONAL_REPRESENTATION('',(#17404),#17408); +#17404 = LINE('',#17405,#17406); +#17405 = CARTESIAN_POINT('',(-7.5E-002,1.975344387166E-062)); +#17406 = VECTOR('',#17407,1.); +#17407 = DIRECTION('',(-3.454467422038E-077,-1.)); +#17408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17409 = ORIENTED_EDGE('',*,*,#17287,.T.); +#17410 = ORIENTED_EDGE('',*,*,#15944,.T.); +#17411 = ADVANCED_FACE('',(#17412,#17422),#14317,.T.); +#17412 = FACE_BOUND('',#17413,.T.); +#17413 = EDGE_LOOP('',(#17414,#17415,#17416,#17417,#17418,#17419,#17420, + #17421)); +#17414 = ORIENTED_EDGE('',*,*,#16583,.T.); +#17415 = ORIENTED_EDGE('',*,*,#16634,.T.); +#17416 = ORIENTED_EDGE('',*,*,#16090,.T.); +#17417 = ORIENTED_EDGE('',*,*,#16185,.T.); +#17418 = ORIENTED_EDGE('',*,*,#16255,.T.); +#17419 = ORIENTED_EDGE('',*,*,#16350,.T.); +#17420 = ORIENTED_EDGE('',*,*,#16418,.T.); +#17421 = ORIENTED_EDGE('',*,*,#16513,.T.); +#17422 = FACE_BOUND('',#17423,.T.); +#17423 = EDGE_LOOP('',(#17424,#17425)); +#17424 = ORIENTED_EDGE('',*,*,#14294,.F.); +#17425 = ORIENTED_EDGE('',*,*,#17426,.F.); +#17426 = EDGE_CURVE('',#14297,#14295,#17427,.T.); +#17427 = SURFACE_CURVE('',#17428,(#17433,#17440),.PCURVE_S1.); +#17428 = CIRCLE('',#17429,7.825944375606E-002); +#17429 = AXIS2_PLACEMENT_3D('',#17430,#17431,#17432); +#17430 = CARTESIAN_POINT('',(-0.25,0.E+000,0.3)); +#17431 = DIRECTION('',(1.,0.E+000,0.E+000)); +#17432 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#17433 = PCURVE('',#14317,#17434); +#17434 = DEFINITIONAL_REPRESENTATION('',(#17435),#17439); +#17435 = CIRCLE('',#17436,7.825944375606E-002); +#17436 = AXIS2_PLACEMENT_2D('',#17437,#17438); +#17437 = CARTESIAN_POINT('',(0.E+000,0.25)); +#17438 = DIRECTION('',(1.,0.E+000)); +#17439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17440 = PCURVE('',#14344,#17441); +#17441 = DEFINITIONAL_REPRESENTATION('',(#17442),#17445); +#17442 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17443,#17444),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#15051 = CARTESIAN_POINT('',(3.14159265359,0.1)); -#15052 = CARTESIAN_POINT('',(6.28318530718,0.1)); -#15053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15054 = ADVANCED_FACE('',(#15055),#14325,.T.); -#15055 = FACE_BOUND('',#15056,.T.); -#15056 = EDGE_LOOP('',(#15057,#15058,#15080,#15142)); -#15057 = ORIENTED_EDGE('',*,*,#14267,.T.); -#15058 = ORIENTED_EDGE('',*,*,#15059,.F.); -#15059 = EDGE_CURVE('',#15060,#14270,#15062,.T.); -#15060 = VERTEX_POINT('',#15061); -#15061 = CARTESIAN_POINT('',(0.26,-0.2,0.6)); -#15062 = SURFACE_CURVE('',#15063,(#15067,#15073),.PCURVE_S1.); -#15063 = LINE('',#15064,#15065); -#15064 = CARTESIAN_POINT('',(0.375,-0.2,0.6)); -#15065 = VECTOR('',#15066,1.); -#15066 = DIRECTION('',(1.,0.E+000,0.E+000)); -#15067 = PCURVE('',#14325,#15068); -#15068 = DEFINITIONAL_REPRESENTATION('',(#15069),#15072); -#15069 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15070,#15071),.UNSPECIFIED., +#17443 = CARTESIAN_POINT('',(3.14159265359,0.1)); +#17444 = CARTESIAN_POINT('',(6.28318530718,0.1)); +#17445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17446 = ADVANCED_FACE('',(#17447),#16717,.T.); +#17447 = FACE_BOUND('',#17448,.T.); +#17448 = EDGE_LOOP('',(#17449,#17450,#17472,#17534)); +#17449 = ORIENTED_EDGE('',*,*,#16659,.T.); +#17450 = ORIENTED_EDGE('',*,*,#17451,.F.); +#17451 = EDGE_CURVE('',#17452,#16662,#17454,.T.); +#17452 = VERTEX_POINT('',#17453); +#17453 = CARTESIAN_POINT('',(0.26,-0.2,0.6)); +#17454 = SURFACE_CURVE('',#17455,(#17459,#17465),.PCURVE_S1.); +#17455 = LINE('',#17456,#17457); +#17456 = CARTESIAN_POINT('',(0.375,-0.2,0.6)); +#17457 = VECTOR('',#17458,1.); +#17458 = DIRECTION('',(1.,0.E+000,0.E+000)); +#17459 = PCURVE('',#16717,#17460); +#17460 = DEFINITIONAL_REPRESENTATION('',(#17461),#17464); +#17461 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17462,#17463),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15070 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#15071 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#15072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15073 = PCURVE('',#14502,#15074); -#15074 = DEFINITIONAL_REPRESENTATION('',(#15075),#15079); -#15075 = LINE('',#15076,#15077); -#15076 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#15077 = VECTOR('',#15078,1.); -#15078 = DIRECTION('',(1.,0.E+000)); -#15079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15080 = ORIENTED_EDGE('',*,*,#15081,.F.); -#15081 = EDGE_CURVE('',#15082,#15060,#15084,.T.); -#15082 = VERTEX_POINT('',#15083); -#15083 = CARTESIAN_POINT('',(0.26,-0.25,0.55)); -#15084 = SURFACE_CURVE('',#15085,(#15090,#15096),.PCURVE_S1.); -#15085 = CIRCLE('',#15086,5.E-002); -#15086 = AXIS2_PLACEMENT_3D('',#15087,#15088,#15089); -#15087 = CARTESIAN_POINT('',(0.26,-0.2,0.55)); -#15088 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#15089 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15090 = PCURVE('',#14325,#15091); -#15091 = DEFINITIONAL_REPRESENTATION('',(#15092),#15095); -#15092 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15093,#15094),.UNSPECIFIED., +#17462 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#17463 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#17464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17465 = PCURVE('',#16894,#17466); +#17466 = DEFINITIONAL_REPRESENTATION('',(#17467),#17471); +#17467 = LINE('',#17468,#17469); +#17468 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#17469 = VECTOR('',#17470,1.); +#17470 = DIRECTION('',(1.,0.E+000)); +#17471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17472 = ORIENTED_EDGE('',*,*,#17473,.F.); +#17473 = EDGE_CURVE('',#17474,#17452,#17476,.T.); +#17474 = VERTEX_POINT('',#17475); +#17475 = CARTESIAN_POINT('',(0.26,-0.25,0.55)); +#17476 = SURFACE_CURVE('',#17477,(#17482,#17488),.PCURVE_S1.); +#17477 = CIRCLE('',#17478,5.E-002); +#17478 = AXIS2_PLACEMENT_3D('',#17479,#17480,#17481); +#17479 = CARTESIAN_POINT('',(0.26,-0.2,0.55)); +#17480 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#17481 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17482 = PCURVE('',#16717,#17483); +#17483 = DEFINITIONAL_REPRESENTATION('',(#17484),#17487); +#17484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17485,#17486),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#15093 = CARTESIAN_POINT('',(3.14159265359,-0.115)); -#15094 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#15095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17485 = CARTESIAN_POINT('',(3.14159265359,-0.115)); +#17486 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#17487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15096 = PCURVE('',#15097,#15114); -#15097 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#15098,#15099,#15100,#15101) - ,(#15102,#15103,#15104,#15105) - ,(#15106,#15107,#15108,#15109) - ,(#15110,#15111,#15112,#15113 +#17488 = PCURVE('',#17489,#17506); +#17489 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17490,#17491,#17492,#17493) + ,(#17494,#17495,#17496,#17497) + ,(#17498,#17499,#17500,#17501) + ,(#17502,#17503,#17504,#17505 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -18393,27 +21382,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#15098 = CARTESIAN_POINT('',(0.26,-0.2,0.6)); -#15099 = CARTESIAN_POINT('',(0.26,-0.229289321881,0.6)); -#15100 = CARTESIAN_POINT('',(0.26,-0.25,0.579289321881)); -#15101 = CARTESIAN_POINT('',(0.26,-0.25,0.55)); -#15102 = CARTESIAN_POINT('',(0.254142135624,-0.2,0.6)); -#15103 = CARTESIAN_POINT('',(0.254142135624,-0.229289321881,0.6)); -#15104 = CARTESIAN_POINT('',(0.254142135624,-0.25,0.579289321881)); -#15105 = CARTESIAN_POINT('',(0.254142135624,-0.25,0.55)); -#15106 = CARTESIAN_POINT('',(0.25,-0.2,0.595857864376)); -#15107 = CARTESIAN_POINT('',(0.25,-0.22686291501,0.595857864376)); -#15108 = CARTESIAN_POINT('',(0.25,-0.245857864376,0.57686291501)); -#15109 = CARTESIAN_POINT('',(0.25,-0.245857864376,0.55)); -#15110 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); -#15111 = CARTESIAN_POINT('',(0.25,-0.223431457505,0.59)); -#15112 = CARTESIAN_POINT('',(0.25,-0.24,0.573431457505)); -#15113 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); -#15114 = DEFINITIONAL_REPRESENTATION('',(#15115),#15141); -#15115 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15116,#15117,#15118,#15119, - #15120,#15121,#15122,#15123,#15124,#15125,#15126,#15127,#15128, - #15129,#15130,#15131,#15132,#15133,#15134,#15135,#15136,#15137, - #15138,#15139,#15140),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17490 = CARTESIAN_POINT('',(0.26,-0.2,0.6)); +#17491 = CARTESIAN_POINT('',(0.26,-0.229289321881,0.6)); +#17492 = CARTESIAN_POINT('',(0.26,-0.25,0.579289321881)); +#17493 = CARTESIAN_POINT('',(0.26,-0.25,0.55)); +#17494 = CARTESIAN_POINT('',(0.254142135624,-0.2,0.6)); +#17495 = CARTESIAN_POINT('',(0.254142135624,-0.229289321881,0.6)); +#17496 = CARTESIAN_POINT('',(0.254142135624,-0.25,0.579289321881)); +#17497 = CARTESIAN_POINT('',(0.254142135624,-0.25,0.55)); +#17498 = CARTESIAN_POINT('',(0.25,-0.2,0.595857864376)); +#17499 = CARTESIAN_POINT('',(0.25,-0.22686291501,0.595857864376)); +#17500 = CARTESIAN_POINT('',(0.25,-0.245857864376,0.57686291501)); +#17501 = CARTESIAN_POINT('',(0.25,-0.245857864376,0.55)); +#17502 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); +#17503 = CARTESIAN_POINT('',(0.25,-0.223431457505,0.59)); +#17504 = CARTESIAN_POINT('',(0.25,-0.24,0.573431457505)); +#17505 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); +#17506 = DEFINITIONAL_REPRESENTATION('',(#17507),#17533); +#17507 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17508,#17509,#17510,#17511, + #17512,#17513,#17514,#17515,#17516,#17517,#17518,#17519,#17520, + #17521,#17522,#17523,#17524,#17525,#17526,#17527,#17528,#17529, + #17530,#17531,#17532),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -18421,176 +21410,176 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#15116 = CARTESIAN_POINT('',(0.E+000,1.)); -#15117 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#15118 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#15119 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#15120 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#15121 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#15122 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#15123 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#15124 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#15125 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#15126 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#15127 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#15128 = CARTESIAN_POINT('',(0.E+000,0.5)); -#15129 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#15130 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#15131 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#15132 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#15133 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#15134 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#15135 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#15136 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#15137 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#15138 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#15139 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#15140 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15142 = ORIENTED_EDGE('',*,*,#15143,.T.); -#15143 = EDGE_CURVE('',#15082,#14268,#15144,.T.); -#15144 = SURFACE_CURVE('',#15145,(#15149,#15155),.PCURVE_S1.); -#15145 = LINE('',#15146,#15147); -#15146 = CARTESIAN_POINT('',(0.375,-0.25,0.55)); -#15147 = VECTOR('',#15148,1.); -#15148 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); -#15149 = PCURVE('',#14325,#15150); -#15150 = DEFINITIONAL_REPRESENTATION('',(#15151),#15154); -#15151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15152,#15153),.UNSPECIFIED., +#17508 = CARTESIAN_POINT('',(0.E+000,1.)); +#17509 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#17510 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#17511 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#17512 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#17513 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#17514 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#17515 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#17516 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#17517 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#17518 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#17519 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#17520 = CARTESIAN_POINT('',(0.E+000,0.5)); +#17521 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#17522 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#17523 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#17524 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#17525 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#17526 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#17527 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#17528 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#17529 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#17530 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#17531 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#17532 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#17533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17534 = ORIENTED_EDGE('',*,*,#17535,.T.); +#17535 = EDGE_CURVE('',#17474,#16660,#17536,.T.); +#17536 = SURFACE_CURVE('',#17537,(#17541,#17547),.PCURVE_S1.); +#17537 = LINE('',#17538,#17539); +#17538 = CARTESIAN_POINT('',(0.375,-0.25,0.55)); +#17539 = VECTOR('',#17540,1.); +#17540 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); +#17541 = PCURVE('',#16717,#17542); +#17542 = DEFINITIONAL_REPRESENTATION('',(#17543),#17546); +#17543 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17544,#17545),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15152 = CARTESIAN_POINT('',(3.14159265359,-0.115)); -#15153 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); -#15154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15155 = PCURVE('',#15006,#15156); -#15156 = DEFINITIONAL_REPRESENTATION('',(#15157),#15161); -#15157 = LINE('',#15158,#15159); -#15158 = CARTESIAN_POINT('',(-3.398804616898E-078,0.25)); -#15159 = VECTOR('',#15160,1.); -#15160 = DIRECTION('',(-1.,-1.359521846759E-077)); -#15161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15162 = ADVANCED_FACE('',(#15163),#14502,.T.); -#15163 = FACE_BOUND('',#15164,.T.); -#15164 = EDGE_LOOP('',(#15165,#15166,#15188,#15213)); -#15165 = ORIENTED_EDGE('',*,*,#14489,.T.); -#15166 = ORIENTED_EDGE('',*,*,#15167,.F.); -#15167 = EDGE_CURVE('',#15168,#14428,#15170,.T.); -#15168 = VERTEX_POINT('',#15169); -#15169 = CARTESIAN_POINT('',(0.26,0.2,0.6)); -#15170 = SURFACE_CURVE('',#15171,(#15175,#15182),.PCURVE_S1.); -#15171 = LINE('',#15172,#15173); -#15172 = CARTESIAN_POINT('',(0.375,0.2,0.6)); -#15173 = VECTOR('',#15174,1.); -#15174 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); -#15175 = PCURVE('',#14502,#15176); -#15176 = DEFINITIONAL_REPRESENTATION('',(#15177),#15181); -#15177 = LINE('',#15178,#15179); -#15178 = CARTESIAN_POINT('',(0.E+000,0.45)); -#15179 = VECTOR('',#15180,1.); -#15180 = DIRECTION('',(1.,9.773375837189E-031)); -#15181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15182 = PCURVE('',#14600,#15183); -#15183 = DEFINITIONAL_REPRESENTATION('',(#15184),#15187); -#15184 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15185,#15186),.UNSPECIFIED., +#17544 = CARTESIAN_POINT('',(3.14159265359,-0.115)); +#17545 = CARTESIAN_POINT('',(3.14159265359,7.5E-002)); +#17546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17547 = PCURVE('',#17398,#17548); +#17548 = DEFINITIONAL_REPRESENTATION('',(#17549),#17553); +#17549 = LINE('',#17550,#17551); +#17550 = CARTESIAN_POINT('',(-3.398804616898E-078,0.25)); +#17551 = VECTOR('',#17552,1.); +#17552 = DIRECTION('',(-1.,-1.359521846759E-077)); +#17553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17554 = ADVANCED_FACE('',(#17555),#16894,.T.); +#17555 = FACE_BOUND('',#17556,.T.); +#17556 = EDGE_LOOP('',(#17557,#17558,#17580,#17605)); +#17557 = ORIENTED_EDGE('',*,*,#16881,.T.); +#17558 = ORIENTED_EDGE('',*,*,#17559,.F.); +#17559 = EDGE_CURVE('',#17560,#16820,#17562,.T.); +#17560 = VERTEX_POINT('',#17561); +#17561 = CARTESIAN_POINT('',(0.26,0.2,0.6)); +#17562 = SURFACE_CURVE('',#17563,(#17567,#17574),.PCURVE_S1.); +#17563 = LINE('',#17564,#17565); +#17564 = CARTESIAN_POINT('',(0.375,0.2,0.6)); +#17565 = VECTOR('',#17566,1.); +#17566 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); +#17567 = PCURVE('',#16894,#17568); +#17568 = DEFINITIONAL_REPRESENTATION('',(#17569),#17573); +#17569 = LINE('',#17570,#17571); +#17570 = CARTESIAN_POINT('',(0.E+000,0.45)); +#17571 = VECTOR('',#17572,1.); +#17572 = DIRECTION('',(1.,9.773375837189E-031)); +#17573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17574 = PCURVE('',#16992,#17575); +#17575 = DEFINITIONAL_REPRESENTATION('',(#17576),#17579); +#17576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17577,#17578),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15185 = CARTESIAN_POINT('',(1.570796326795,0.115)); -#15186 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); -#15187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15188 = ORIENTED_EDGE('',*,*,#15189,.F.); -#15189 = EDGE_CURVE('',#15060,#15168,#15190,.T.); -#15190 = SURFACE_CURVE('',#15191,(#15195,#15202),.PCURVE_S1.); -#15191 = LINE('',#15192,#15193); -#15192 = CARTESIAN_POINT('',(0.26,-0.25,0.6)); -#15193 = VECTOR('',#15194,1.); -#15194 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15195 = PCURVE('',#14502,#15196); -#15196 = DEFINITIONAL_REPRESENTATION('',(#15197),#15201); -#15197 = LINE('',#15198,#15199); -#15198 = CARTESIAN_POINT('',(-0.115,0.E+000)); -#15199 = VECTOR('',#15200,1.); -#15200 = DIRECTION('',(0.E+000,1.)); -#15201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15202 = PCURVE('',#15203,#15208); -#15203 = CYLINDRICAL_SURFACE('',#15204,1.E-002); -#15204 = AXIS2_PLACEMENT_3D('',#15205,#15206,#15207); -#15205 = CARTESIAN_POINT('',(0.26,-0.25,0.59)); -#15206 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15207 = DIRECTION('',(0.E+000,0.E+000,1.)); -#15208 = DEFINITIONAL_REPRESENTATION('',(#15209),#15212); -#15209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15210,#15211),.UNSPECIFIED., +#17577 = CARTESIAN_POINT('',(1.570796326795,0.115)); +#17578 = CARTESIAN_POINT('',(1.570796326795,-7.5E-002)); +#17579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17580 = ORIENTED_EDGE('',*,*,#17581,.F.); +#17581 = EDGE_CURVE('',#17452,#17560,#17582,.T.); +#17582 = SURFACE_CURVE('',#17583,(#17587,#17594),.PCURVE_S1.); +#17583 = LINE('',#17584,#17585); +#17584 = CARTESIAN_POINT('',(0.26,-0.25,0.6)); +#17585 = VECTOR('',#17586,1.); +#17586 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17587 = PCURVE('',#16894,#17588); +#17588 = DEFINITIONAL_REPRESENTATION('',(#17589),#17593); +#17589 = LINE('',#17590,#17591); +#17590 = CARTESIAN_POINT('',(-0.115,0.E+000)); +#17591 = VECTOR('',#17592,1.); +#17592 = DIRECTION('',(0.E+000,1.)); +#17593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17594 = PCURVE('',#17595,#17600); +#17595 = CYLINDRICAL_SURFACE('',#17596,1.E-002); +#17596 = AXIS2_PLACEMENT_3D('',#17597,#17598,#17599); +#17597 = CARTESIAN_POINT('',(0.26,-0.25,0.59)); +#17598 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17599 = DIRECTION('',(0.E+000,0.E+000,1.)); +#17600 = DEFINITIONAL_REPRESENTATION('',(#17601),#17604); +#17601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17602,#17603),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#15210 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#15211 = CARTESIAN_POINT('',(6.28318530718,0.45)); -#15212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15213 = ORIENTED_EDGE('',*,*,#15059,.T.); -#15214 = ADVANCED_FACE('',(#15215),#14600,.T.); -#15215 = FACE_BOUND('',#15216,.T.); -#15216 = EDGE_LOOP('',(#15217,#15218,#15240,#15300)); -#15217 = ORIENTED_EDGE('',*,*,#14563,.T.); -#15218 = ORIENTED_EDGE('',*,*,#15219,.F.); -#15219 = EDGE_CURVE('',#15220,#14519,#15222,.T.); -#15220 = VERTEX_POINT('',#15221); -#15221 = CARTESIAN_POINT('',(0.26,0.25,0.55)); -#15222 = SURFACE_CURVE('',#15223,(#15227,#15233),.PCURVE_S1.); -#15223 = LINE('',#15224,#15225); -#15224 = CARTESIAN_POINT('',(0.375,0.25,0.55)); -#15225 = VECTOR('',#15226,1.); -#15226 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); -#15227 = PCURVE('',#14600,#15228); -#15228 = DEFINITIONAL_REPRESENTATION('',(#15229),#15232); -#15229 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15230,#15231),.UNSPECIFIED., +#17602 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#17603 = CARTESIAN_POINT('',(6.28318530718,0.45)); +#17604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17605 = ORIENTED_EDGE('',*,*,#17451,.T.); +#17606 = ADVANCED_FACE('',(#17607),#16992,.T.); +#17607 = FACE_BOUND('',#17608,.T.); +#17608 = EDGE_LOOP('',(#17609,#17610,#17632,#17692)); +#17609 = ORIENTED_EDGE('',*,*,#16955,.T.); +#17610 = ORIENTED_EDGE('',*,*,#17611,.F.); +#17611 = EDGE_CURVE('',#17612,#16911,#17614,.T.); +#17612 = VERTEX_POINT('',#17613); +#17613 = CARTESIAN_POINT('',(0.26,0.25,0.55)); +#17614 = SURFACE_CURVE('',#17615,(#17619,#17625),.PCURVE_S1.); +#17615 = LINE('',#17616,#17617); +#17616 = CARTESIAN_POINT('',(0.375,0.25,0.55)); +#17617 = VECTOR('',#17618,1.); +#17618 = DIRECTION('',(1.,9.773375837189E-031,0.E+000)); +#17619 = PCURVE('',#16992,#17620); +#17620 = DEFINITIONAL_REPRESENTATION('',(#17621),#17624); +#17621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17622,#17623),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15230 = CARTESIAN_POINT('',(3.14159265359,0.115)); -#15231 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); -#15232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15233 = PCURVE('',#14689,#15234); -#15234 = DEFINITIONAL_REPRESENTATION('',(#15235),#15239); -#15235 = LINE('',#15236,#15237); -#15236 = CARTESIAN_POINT('',(-3.398804616898E-078,0.25)); -#15237 = VECTOR('',#15238,1.); -#15238 = DIRECTION('',(-1.,-1.359521846759E-077)); -#15239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15240 = ORIENTED_EDGE('',*,*,#15241,.F.); -#15241 = EDGE_CURVE('',#15168,#15220,#15242,.T.); -#15242 = SURFACE_CURVE('',#15243,(#15248,#15254),.PCURVE_S1.); -#15243 = CIRCLE('',#15244,5.E-002); -#15244 = AXIS2_PLACEMENT_3D('',#15245,#15246,#15247); -#15245 = CARTESIAN_POINT('',(0.26,0.2,0.55)); -#15246 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#15247 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15248 = PCURVE('',#14600,#15249); -#15249 = DEFINITIONAL_REPRESENTATION('',(#15250),#15253); -#15250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15251,#15252),.UNSPECIFIED., +#17622 = CARTESIAN_POINT('',(3.14159265359,0.115)); +#17623 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); +#17624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17625 = PCURVE('',#17081,#17626); +#17626 = DEFINITIONAL_REPRESENTATION('',(#17627),#17631); +#17627 = LINE('',#17628,#17629); +#17628 = CARTESIAN_POINT('',(-3.398804616898E-078,0.25)); +#17629 = VECTOR('',#17630,1.); +#17630 = DIRECTION('',(-1.,-1.359521846759E-077)); +#17631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17632 = ORIENTED_EDGE('',*,*,#17633,.F.); +#17633 = EDGE_CURVE('',#17560,#17612,#17634,.T.); +#17634 = SURFACE_CURVE('',#17635,(#17640,#17646),.PCURVE_S1.); +#17635 = CIRCLE('',#17636,5.E-002); +#17636 = AXIS2_PLACEMENT_3D('',#17637,#17638,#17639); +#17637 = CARTESIAN_POINT('',(0.26,0.2,0.55)); +#17638 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#17639 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17640 = PCURVE('',#16992,#17641); +#17641 = DEFINITIONAL_REPRESENTATION('',(#17642),#17645); +#17642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17643,#17644),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#15251 = CARTESIAN_POINT('',(1.570796326795,0.115)); -#15252 = CARTESIAN_POINT('',(3.14159265359,0.115)); -#15253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17643 = CARTESIAN_POINT('',(1.570796326795,0.115)); +#17644 = CARTESIAN_POINT('',(3.14159265359,0.115)); +#17645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15254 = PCURVE('',#15255,#15272); -#15255 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#15256,#15257,#15258,#15259) - ,(#15260,#15261,#15262,#15263) - ,(#15264,#15265,#15266,#15267) - ,(#15268,#15269,#15270,#15271 +#17646 = PCURVE('',#17647,#17664); +#17647 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17648,#17649,#17650,#17651) + ,(#17652,#17653,#17654,#17655) + ,(#17656,#17657,#17658,#17659) + ,(#17660,#17661,#17662,#17663 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -18599,27 +21588,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#15256 = CARTESIAN_POINT('',(0.26,0.25,0.55)); -#15257 = CARTESIAN_POINT('',(0.26,0.25,0.579289321881)); -#15258 = CARTESIAN_POINT('',(0.26,0.229289321881,0.6)); -#15259 = CARTESIAN_POINT('',(0.26,0.2,0.6)); -#15260 = CARTESIAN_POINT('',(0.254142135624,0.25,0.55)); -#15261 = CARTESIAN_POINT('',(0.254142135624,0.25,0.579289321881)); -#15262 = CARTESIAN_POINT('',(0.254142135624,0.229289321881,0.6)); -#15263 = CARTESIAN_POINT('',(0.254142135624,0.2,0.6)); -#15264 = CARTESIAN_POINT('',(0.25,0.245857864376,0.55)); -#15265 = CARTESIAN_POINT('',(0.25,0.245857864376,0.57686291501)); -#15266 = CARTESIAN_POINT('',(0.25,0.22686291501,0.595857864376)); -#15267 = CARTESIAN_POINT('',(0.25,0.2,0.595857864376)); -#15268 = CARTESIAN_POINT('',(0.25,0.24,0.55)); -#15269 = CARTESIAN_POINT('',(0.25,0.24,0.573431457505)); -#15270 = CARTESIAN_POINT('',(0.25,0.223431457505,0.59)); -#15271 = CARTESIAN_POINT('',(0.25,0.2,0.59)); -#15272 = DEFINITIONAL_REPRESENTATION('',(#15273),#15299); -#15273 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15274,#15275,#15276,#15277, - #15278,#15279,#15280,#15281,#15282,#15283,#15284,#15285,#15286, - #15287,#15288,#15289,#15290,#15291,#15292,#15293,#15294,#15295, - #15296,#15297,#15298),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17648 = CARTESIAN_POINT('',(0.26,0.25,0.55)); +#17649 = CARTESIAN_POINT('',(0.26,0.25,0.579289321881)); +#17650 = CARTESIAN_POINT('',(0.26,0.229289321881,0.6)); +#17651 = CARTESIAN_POINT('',(0.26,0.2,0.6)); +#17652 = CARTESIAN_POINT('',(0.254142135624,0.25,0.55)); +#17653 = CARTESIAN_POINT('',(0.254142135624,0.25,0.579289321881)); +#17654 = CARTESIAN_POINT('',(0.254142135624,0.229289321881,0.6)); +#17655 = CARTESIAN_POINT('',(0.254142135624,0.2,0.6)); +#17656 = CARTESIAN_POINT('',(0.25,0.245857864376,0.55)); +#17657 = CARTESIAN_POINT('',(0.25,0.245857864376,0.57686291501)); +#17658 = CARTESIAN_POINT('',(0.25,0.22686291501,0.595857864376)); +#17659 = CARTESIAN_POINT('',(0.25,0.2,0.595857864376)); +#17660 = CARTESIAN_POINT('',(0.25,0.24,0.55)); +#17661 = CARTESIAN_POINT('',(0.25,0.24,0.573431457505)); +#17662 = CARTESIAN_POINT('',(0.25,0.223431457505,0.59)); +#17663 = CARTESIAN_POINT('',(0.25,0.2,0.59)); +#17664 = DEFINITIONAL_REPRESENTATION('',(#17665),#17691); +#17665 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17666,#17667,#17668,#17669, + #17670,#17671,#17672,#17673,#17674,#17675,#17676,#17677,#17678, + #17679,#17680,#17681,#17682,#17683,#17684,#17685,#17686,#17687, + #17688,#17689,#17690),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -18627,116 +21616,116 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#15274 = CARTESIAN_POINT('',(0.E+000,1.)); -#15275 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#15276 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#15277 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#15278 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#15279 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#15280 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#15281 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#15282 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#15283 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#15284 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#15285 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#15286 = CARTESIAN_POINT('',(0.E+000,0.5)); -#15287 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#15288 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#15289 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#15290 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#15291 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#15292 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#15293 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#15294 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#15295 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#15296 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#15297 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); -#15298 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15300 = ORIENTED_EDGE('',*,*,#15167,.T.); -#15301 = ADVANCED_FACE('',(#15302),#14689,.T.); -#15302 = FACE_BOUND('',#15303,.T.); -#15303 = EDGE_LOOP('',(#15304,#15305,#15327,#15352)); -#15304 = ORIENTED_EDGE('',*,*,#14676,.T.); -#15305 = ORIENTED_EDGE('',*,*,#15306,.F.); -#15306 = EDGE_CURVE('',#15307,#14615,#15309,.T.); -#15307 = VERTEX_POINT('',#15308); -#15308 = CARTESIAN_POINT('',(0.26,0.25,5.E-002)); -#15309 = SURFACE_CURVE('',#15310,(#15314,#15321),.PCURVE_S1.); -#15310 = LINE('',#15311,#15312); -#15311 = CARTESIAN_POINT('',(0.375,0.25,5.E-002)); -#15312 = VECTOR('',#15313,1.); -#15313 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); -#15314 = PCURVE('',#14689,#15315); -#15315 = DEFINITIONAL_REPRESENTATION('',(#15316),#15320); -#15316 = LINE('',#15317,#15318); -#15317 = CARTESIAN_POINT('',(3.398804616898E-078,-0.25)); -#15318 = VECTOR('',#15319,1.); -#15319 = DIRECTION('',(-1.,1.224646799147E-016)); -#15320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15321 = PCURVE('',#14788,#15322); -#15322 = DEFINITIONAL_REPRESENTATION('',(#15323),#15326); -#15323 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15324,#15325),.UNSPECIFIED., +#17666 = CARTESIAN_POINT('',(0.E+000,1.)); +#17667 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#17668 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#17669 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#17670 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#17671 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#17672 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#17673 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#17674 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#17675 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#17676 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#17677 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#17678 = CARTESIAN_POINT('',(0.E+000,0.5)); +#17679 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#17680 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#17681 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#17682 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#17683 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#17684 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#17685 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#17686 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#17687 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#17688 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#17689 = CARTESIAN_POINT('',(0.E+000,1.682780133706E-002)); +#17690 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#17691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17692 = ORIENTED_EDGE('',*,*,#17559,.T.); +#17693 = ADVANCED_FACE('',(#17694),#17081,.T.); +#17694 = FACE_BOUND('',#17695,.T.); +#17695 = EDGE_LOOP('',(#17696,#17697,#17719,#17744)); +#17696 = ORIENTED_EDGE('',*,*,#17068,.T.); +#17697 = ORIENTED_EDGE('',*,*,#17698,.F.); +#17698 = EDGE_CURVE('',#17699,#17007,#17701,.T.); +#17699 = VERTEX_POINT('',#17700); +#17700 = CARTESIAN_POINT('',(0.26,0.25,5.E-002)); +#17701 = SURFACE_CURVE('',#17702,(#17706,#17713),.PCURVE_S1.); +#17702 = LINE('',#17703,#17704); +#17703 = CARTESIAN_POINT('',(0.375,0.25,5.E-002)); +#17704 = VECTOR('',#17705,1.); +#17705 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); +#17706 = PCURVE('',#17081,#17707); +#17707 = DEFINITIONAL_REPRESENTATION('',(#17708),#17712); +#17708 = LINE('',#17709,#17710); +#17709 = CARTESIAN_POINT('',(3.398804616898E-078,-0.25)); +#17710 = VECTOR('',#17711,1.); +#17711 = DIRECTION('',(-1.,1.224646799147E-016)); +#17712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17713 = PCURVE('',#17180,#17714); +#17714 = DEFINITIONAL_REPRESENTATION('',(#17715),#17718); +#17715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17716,#17717),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15324 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#15325 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); -#15326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15327 = ORIENTED_EDGE('',*,*,#15328,.F.); -#15328 = EDGE_CURVE('',#15220,#15307,#15329,.T.); -#15329 = SURFACE_CURVE('',#15330,(#15334,#15341),.PCURVE_S1.); -#15330 = LINE('',#15331,#15332); -#15331 = CARTESIAN_POINT('',(0.26,0.25,0.3)); -#15332 = VECTOR('',#15333,1.); -#15333 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#15334 = PCURVE('',#14689,#15335); -#15335 = DEFINITIONAL_REPRESENTATION('',(#15336),#15340); -#15336 = LINE('',#15337,#15338); -#15337 = CARTESIAN_POINT('',(0.115,-3.028861393654E-062)); -#15338 = VECTOR('',#15339,1.); -#15339 = DIRECTION('',(-2.633792516221E-061,-1.)); -#15340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15341 = PCURVE('',#15342,#15347); -#15342 = CYLINDRICAL_SURFACE('',#15343,1.E-002); -#15343 = AXIS2_PLACEMENT_3D('',#15344,#15345,#15346); -#15344 = CARTESIAN_POINT('',(0.26,0.24,0.3)); -#15345 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#15346 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); -#15347 = DEFINITIONAL_REPRESENTATION('',(#15348),#15351); -#15348 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15349,#15350),.UNSPECIFIED., +#17716 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#17717 = CARTESIAN_POINT('',(1.570796326795,7.5E-002)); +#17718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17719 = ORIENTED_EDGE('',*,*,#17720,.F.); +#17720 = EDGE_CURVE('',#17612,#17699,#17721,.T.); +#17721 = SURFACE_CURVE('',#17722,(#17726,#17733),.PCURVE_S1.); +#17722 = LINE('',#17723,#17724); +#17723 = CARTESIAN_POINT('',(0.26,0.25,0.3)); +#17724 = VECTOR('',#17725,1.); +#17725 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#17726 = PCURVE('',#17081,#17727); +#17727 = DEFINITIONAL_REPRESENTATION('',(#17728),#17732); +#17728 = LINE('',#17729,#17730); +#17729 = CARTESIAN_POINT('',(0.115,-3.028861393654E-062)); +#17730 = VECTOR('',#17731,1.); +#17731 = DIRECTION('',(-2.633792516221E-061,-1.)); +#17732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17733 = PCURVE('',#17734,#17739); +#17734 = CYLINDRICAL_SURFACE('',#17735,1.E-002); +#17735 = AXIS2_PLACEMENT_3D('',#17736,#17737,#17738); +#17736 = CARTESIAN_POINT('',(0.26,0.24,0.3)); +#17737 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#17738 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); +#17739 = DEFINITIONAL_REPRESENTATION('',(#17740),#17743); +#17740 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17741,#17742),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#15349 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#15350 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#15351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15352 = ORIENTED_EDGE('',*,*,#15219,.T.); -#15353 = ADVANCED_FACE('',(#15354),#14788,.T.); -#15354 = FACE_BOUND('',#15355,.T.); -#15355 = EDGE_LOOP('',(#15356,#15357,#15402,#15462)); -#15356 = ORIENTED_EDGE('',*,*,#14751,.T.); -#15357 = ORIENTED_EDGE('',*,*,#15358,.F.); -#15358 = EDGE_CURVE('',#15359,#14707,#15361,.T.); -#15359 = VERTEX_POINT('',#15360); -#15360 = CARTESIAN_POINT('',(0.26,0.2,2.000227594295E-018)); -#15361 = SURFACE_CURVE('',#15362,(#15366,#15395),.PCURVE_S1.); -#15362 = LINE('',#15363,#15364); -#15363 = CARTESIAN_POINT('',(0.375,0.2,1.530808498934E-017)); -#15364 = VECTOR('',#15365,1.); -#15365 = DIRECTION('',(1.,0.E+000,1.224646799147E-016)); -#15366 = PCURVE('',#14788,#15367); -#15367 = DEFINITIONAL_REPRESENTATION('',(#15368),#15394); -#15368 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15369,#15370,#15371,#15372, - #15373,#15374,#15375,#15376,#15377,#15378,#15379,#15380,#15381, - #15382,#15383,#15384,#15385,#15386,#15387,#15388,#15389,#15390, - #15391,#15392,#15393),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17741 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#17742 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#17743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17744 = ORIENTED_EDGE('',*,*,#17611,.T.); +#17745 = ADVANCED_FACE('',(#17746),#17180,.T.); +#17746 = FACE_BOUND('',#17747,.T.); +#17747 = EDGE_LOOP('',(#17748,#17749,#17794,#17854)); +#17748 = ORIENTED_EDGE('',*,*,#17143,.T.); +#17749 = ORIENTED_EDGE('',*,*,#17750,.F.); +#17750 = EDGE_CURVE('',#17751,#17099,#17753,.T.); +#17751 = VERTEX_POINT('',#17752); +#17752 = CARTESIAN_POINT('',(0.26,0.2,2.000227594295E-018)); +#17753 = SURFACE_CURVE('',#17754,(#17758,#17787),.PCURVE_S1.); +#17754 = LINE('',#17755,#17756); +#17755 = CARTESIAN_POINT('',(0.375,0.2,1.530808498934E-017)); +#17756 = VECTOR('',#17757,1.); +#17757 = DIRECTION('',(1.,0.E+000,1.224646799147E-016)); +#17758 = PCURVE('',#17180,#17759); +#17759 = DEFINITIONAL_REPRESENTATION('',(#17760),#17786); +#17760 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17761,#17762,#17763,#17764, + #17765,#17766,#17767,#17768,#17769,#17770,#17771,#17772,#17773, + #17774,#17775,#17776,#17777,#17778,#17779,#17780,#17781,#17782, + #17783,#17784,#17785),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.115,-0.106363636364,-9.772727272727E-002 ,-8.909090909091E-002,-8.045454545455E-002,-7.181818181818E-002, -6.318181818182E-002,-5.454545454545E-002,-4.590909090909E-002, @@ -18745,70 +21734,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.454545454545E-002,2.318181818182E-002,3.181818181818E-002, 4.045454545455E-002,4.909090909091E-002,5.772727272727E-002, 6.636363636364E-002,7.5E-002),.UNSPECIFIED.); -#15369 = CARTESIAN_POINT('',(0.E+000,-0.115)); -#15370 = CARTESIAN_POINT('',(0.E+000,-0.112121212121)); -#15371 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.106363636364)); -#15372 = CARTESIAN_POINT('',(0.E+000,-9.772727272727E-002)); -#15373 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.909090909091E-002) - ); -#15374 = CARTESIAN_POINT('',(-1.7763568394E-015,-8.045454545455E-002)); -#15375 = CARTESIAN_POINT('',(0.E+000,-7.181818181818E-002)); -#15376 = CARTESIAN_POINT('',(0.E+000,-6.318181818182E-002)); -#15377 = CARTESIAN_POINT('',(-1.7763568394E-015,-5.454545454545E-002)); -#15378 = CARTESIAN_POINT('',(0.E+000,-4.590909090909E-002)); -#15379 = CARTESIAN_POINT('',(-1.7763568394E-015,-3.727272727273E-002)); -#15380 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.863636363636E-002) - ); -#15381 = CARTESIAN_POINT('',(-1.7763568394E-015,-2.E-002)); -#15382 = CARTESIAN_POINT('',(-8.881784197001E-016,-1.136363636364E-002) - ); -#15383 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.727272727273E-003) - ); -#15384 = CARTESIAN_POINT('',(-1.7763568394E-015,5.909090909091E-003)); -#15385 = CARTESIAN_POINT('',(0.E+000,1.454545454545E-002)); -#15386 = CARTESIAN_POINT('',(-8.881784197001E-016,2.318181818182E-002)); -#15387 = CARTESIAN_POINT('',(-8.881784197001E-016,3.181818181818E-002)); -#15388 = CARTESIAN_POINT('',(-1.7763568394E-015,4.045454545455E-002)); -#15389 = CARTESIAN_POINT('',(-1.7763568394E-015,4.909090909091E-002)); -#15390 = CARTESIAN_POINT('',(-8.881784197001E-016,5.772727272727E-002)); -#15391 = CARTESIAN_POINT('',(0.E+000,6.636363636364E-002)); -#15392 = CARTESIAN_POINT('',(0.E+000,7.212121212121E-002)); -#15393 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); -#15394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15395 = PCURVE('',#14878,#15396); -#15396 = DEFINITIONAL_REPRESENTATION('',(#15397),#15401); -#15397 = LINE('',#15398,#15399); -#15398 = CARTESIAN_POINT('',(0.E+000,0.45)); -#15399 = VECTOR('',#15400,1.); -#15400 = DIRECTION('',(-1.,0.E+000)); -#15401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15402 = ORIENTED_EDGE('',*,*,#15403,.F.); -#15403 = EDGE_CURVE('',#15307,#15359,#15404,.T.); -#15404 = SURFACE_CURVE('',#15405,(#15410,#15416),.PCURVE_S1.); -#15405 = CIRCLE('',#15406,5.E-002); -#15406 = AXIS2_PLACEMENT_3D('',#15407,#15408,#15409); -#15407 = CARTESIAN_POINT('',(0.26,0.2,5.E-002)); -#15408 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#15409 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15410 = PCURVE('',#14788,#15411); -#15411 = DEFINITIONAL_REPRESENTATION('',(#15412),#15415); -#15412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15413,#15414),.UNSPECIFIED., +#17761 = CARTESIAN_POINT('',(0.E+000,-0.115)); +#17762 = CARTESIAN_POINT('',(0.E+000,-0.112121212121)); +#17763 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.106363636364)); +#17764 = CARTESIAN_POINT('',(0.E+000,-9.772727272727E-002)); +#17765 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.909090909091E-002) + ); +#17766 = CARTESIAN_POINT('',(-1.7763568394E-015,-8.045454545455E-002)); +#17767 = CARTESIAN_POINT('',(0.E+000,-7.181818181818E-002)); +#17768 = CARTESIAN_POINT('',(0.E+000,-6.318181818182E-002)); +#17769 = CARTESIAN_POINT('',(-1.7763568394E-015,-5.454545454545E-002)); +#17770 = CARTESIAN_POINT('',(0.E+000,-4.590909090909E-002)); +#17771 = CARTESIAN_POINT('',(-1.7763568394E-015,-3.727272727273E-002)); +#17772 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.863636363636E-002) + ); +#17773 = CARTESIAN_POINT('',(-1.7763568394E-015,-2.E-002)); +#17774 = CARTESIAN_POINT('',(-8.881784197001E-016,-1.136363636364E-002) + ); +#17775 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.727272727273E-003) + ); +#17776 = CARTESIAN_POINT('',(-1.7763568394E-015,5.909090909091E-003)); +#17777 = CARTESIAN_POINT('',(0.E+000,1.454545454545E-002)); +#17778 = CARTESIAN_POINT('',(-8.881784197001E-016,2.318181818182E-002)); +#17779 = CARTESIAN_POINT('',(-8.881784197001E-016,3.181818181818E-002)); +#17780 = CARTESIAN_POINT('',(-1.7763568394E-015,4.045454545455E-002)); +#17781 = CARTESIAN_POINT('',(-1.7763568394E-015,4.909090909091E-002)); +#17782 = CARTESIAN_POINT('',(-8.881784197001E-016,5.772727272727E-002)); +#17783 = CARTESIAN_POINT('',(0.E+000,6.636363636364E-002)); +#17784 = CARTESIAN_POINT('',(0.E+000,7.212121212121E-002)); +#17785 = CARTESIAN_POINT('',(0.E+000,7.5E-002)); +#17786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17787 = PCURVE('',#17270,#17788); +#17788 = DEFINITIONAL_REPRESENTATION('',(#17789),#17793); +#17789 = LINE('',#17790,#17791); +#17790 = CARTESIAN_POINT('',(0.E+000,0.45)); +#17791 = VECTOR('',#17792,1.); +#17792 = DIRECTION('',(-1.,0.E+000)); +#17793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17794 = ORIENTED_EDGE('',*,*,#17795,.F.); +#17795 = EDGE_CURVE('',#17699,#17751,#17796,.T.); +#17796 = SURFACE_CURVE('',#17797,(#17802,#17808),.PCURVE_S1.); +#17797 = CIRCLE('',#17798,5.E-002); +#17798 = AXIS2_PLACEMENT_3D('',#17799,#17800,#17801); +#17799 = CARTESIAN_POINT('',(0.26,0.2,5.E-002)); +#17800 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#17801 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17802 = PCURVE('',#17180,#17803); +#17803 = DEFINITIONAL_REPRESENTATION('',(#17804),#17807); +#17804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17805,#17806),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#15413 = CARTESIAN_POINT('',(1.570796326795,-0.115)); -#15414 = CARTESIAN_POINT('',(0.E+000,-0.115)); -#15415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17805 = CARTESIAN_POINT('',(1.570796326795,-0.115)); +#17806 = CARTESIAN_POINT('',(0.E+000,-0.115)); +#17807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15416 = PCURVE('',#15417,#15434); -#15417 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#15418,#15419,#15420,#15421) - ,(#15422,#15423,#15424,#15425) - ,(#15426,#15427,#15428,#15429) - ,(#15430,#15431,#15432,#15433 +#17808 = PCURVE('',#17809,#17826); +#17809 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17810,#17811,#17812,#17813) + ,(#17814,#17815,#17816,#17817) + ,(#17818,#17819,#17820,#17821) + ,(#17822,#17823,#17824,#17825 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -18817,28 +21806,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#15418 = CARTESIAN_POINT('',(0.26,0.2,-1.694065894509E-018)); -#15419 = CARTESIAN_POINT('',(0.26,0.229289321881,-4.932738551608E-017)); -#15420 = CARTESIAN_POINT('',(0.26,0.25,2.071067811865E-002)); -#15421 = CARTESIAN_POINT('',(0.26,0.25,5.E-002)); -#15422 = CARTESIAN_POINT('',(0.254142135624,0.2,-1.694065894509E-018)); -#15423 = CARTESIAN_POINT('',(0.254142135624,0.229289321881, +#17810 = CARTESIAN_POINT('',(0.26,0.2,-1.694065894509E-018)); +#17811 = CARTESIAN_POINT('',(0.26,0.229289321881,-4.932738551608E-017)); +#17812 = CARTESIAN_POINT('',(0.26,0.25,2.071067811865E-002)); +#17813 = CARTESIAN_POINT('',(0.26,0.25,5.E-002)); +#17814 = CARTESIAN_POINT('',(0.254142135624,0.2,-1.694065894509E-018)); +#17815 = CARTESIAN_POINT('',(0.254142135624,0.229289321881, -4.932738551608E-017)); -#15424 = CARTESIAN_POINT('',(0.254142135624,0.25,2.071067811865E-002)); -#15425 = CARTESIAN_POINT('',(0.254142135624,0.25,5.E-002)); -#15426 = CARTESIAN_POINT('',(0.25,0.2,4.142135623731E-003)); -#15427 = CARTESIAN_POINT('',(0.25,0.22686291501,4.142135623731E-003)); -#15428 = CARTESIAN_POINT('',(0.25,0.245857864376,2.313708498985E-002)); -#15429 = CARTESIAN_POINT('',(0.25,0.245857864376,5.E-002)); -#15430 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); -#15431 = CARTESIAN_POINT('',(0.25,0.223431457505,1.E-002)); -#15432 = CARTESIAN_POINT('',(0.25,0.24,2.656854249492E-002)); -#15433 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); -#15434 = DEFINITIONAL_REPRESENTATION('',(#15435),#15461); -#15435 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15436,#15437,#15438,#15439, - #15440,#15441,#15442,#15443,#15444,#15445,#15446,#15447,#15448, - #15449,#15450,#15451,#15452,#15453,#15454,#15455,#15456,#15457, - #15458,#15459,#15460),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17816 = CARTESIAN_POINT('',(0.254142135624,0.25,2.071067811865E-002)); +#17817 = CARTESIAN_POINT('',(0.254142135624,0.25,5.E-002)); +#17818 = CARTESIAN_POINT('',(0.25,0.2,4.142135623731E-003)); +#17819 = CARTESIAN_POINT('',(0.25,0.22686291501,4.142135623731E-003)); +#17820 = CARTESIAN_POINT('',(0.25,0.245857864376,2.313708498985E-002)); +#17821 = CARTESIAN_POINT('',(0.25,0.245857864376,5.E-002)); +#17822 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); +#17823 = CARTESIAN_POINT('',(0.25,0.223431457505,1.E-002)); +#17824 = CARTESIAN_POINT('',(0.25,0.24,2.656854249492E-002)); +#17825 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); +#17826 = DEFINITIONAL_REPRESENTATION('',(#17827),#17853); +#17827 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17828,#17829,#17830,#17831, + #17832,#17833,#17834,#17835,#17836,#17837,#17838,#17839,#17840, + #17841,#17842,#17843,#17844,#17845,#17846,#17847,#17848,#17849, + #17850,#17851,#17852),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -18846,116 +21835,116 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#15436 = CARTESIAN_POINT('',(0.E+000,1.)); -#15437 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#15438 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#15439 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#15440 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#15441 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#15442 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#15443 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#15444 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#15445 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#15446 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#15447 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#15448 = CARTESIAN_POINT('',(0.E+000,0.5)); -#15449 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#15450 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#15451 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#15452 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#15453 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#15454 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#15455 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#15456 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#15457 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#15458 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#15459 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#15460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15462 = ORIENTED_EDGE('',*,*,#15306,.T.); -#15463 = ADVANCED_FACE('',(#15464),#14878,.T.); -#15464 = FACE_BOUND('',#15465,.T.); -#15465 = EDGE_LOOP('',(#15466,#15467,#15489,#15514)); -#15466 = ORIENTED_EDGE('',*,*,#14865,.T.); -#15467 = ORIENTED_EDGE('',*,*,#15468,.F.); -#15468 = EDGE_CURVE('',#15469,#14804,#15471,.T.); -#15469 = VERTEX_POINT('',#15470); -#15470 = CARTESIAN_POINT('',(0.26,-0.2,2.831887556859E-018)); -#15471 = SURFACE_CURVE('',#15472,(#15476,#15483),.PCURVE_S1.); -#15472 = LINE('',#15473,#15474); -#15473 = CARTESIAN_POINT('',(0.375,-0.2,-6.776263578034E-018)); -#15474 = VECTOR('',#15475,1.); -#15475 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); -#15476 = PCURVE('',#14878,#15477); -#15477 = DEFINITIONAL_REPRESENTATION('',(#15478),#15482); -#15478 = LINE('',#15479,#15480); -#15479 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#15480 = VECTOR('',#15481,1.); -#15481 = DIRECTION('',(-1.,9.773375837189E-031)); -#15482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15483 = PCURVE('',#14977,#15484); -#15484 = DEFINITIONAL_REPRESENTATION('',(#15485),#15488); -#15485 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15486,#15487),.UNSPECIFIED., +#17828 = CARTESIAN_POINT('',(0.E+000,1.)); +#17829 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#17830 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#17831 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#17832 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#17833 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#17834 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#17835 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#17836 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#17837 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#17838 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#17839 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#17840 = CARTESIAN_POINT('',(0.E+000,0.5)); +#17841 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#17842 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#17843 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#17844 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#17845 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#17846 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#17847 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#17848 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#17849 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#17850 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#17851 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#17852 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#17853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17854 = ORIENTED_EDGE('',*,*,#17698,.T.); +#17855 = ADVANCED_FACE('',(#17856),#17270,.T.); +#17856 = FACE_BOUND('',#17857,.T.); +#17857 = EDGE_LOOP('',(#17858,#17859,#17881,#17906)); +#17858 = ORIENTED_EDGE('',*,*,#17257,.T.); +#17859 = ORIENTED_EDGE('',*,*,#17860,.F.); +#17860 = EDGE_CURVE('',#17861,#17196,#17863,.T.); +#17861 = VERTEX_POINT('',#17862); +#17862 = CARTESIAN_POINT('',(0.26,-0.2,2.831887556859E-018)); +#17863 = SURFACE_CURVE('',#17864,(#17868,#17875),.PCURVE_S1.); +#17864 = LINE('',#17865,#17866); +#17865 = CARTESIAN_POINT('',(0.375,-0.2,-6.776263578034E-018)); +#17866 = VECTOR('',#17867,1.); +#17867 = DIRECTION('',(1.,9.773375837189E-031,1.224646799147E-016)); +#17868 = PCURVE('',#17270,#17869); +#17869 = DEFINITIONAL_REPRESENTATION('',(#17870),#17874); +#17870 = LINE('',#17871,#17872); +#17871 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#17872 = VECTOR('',#17873,1.); +#17873 = DIRECTION('',(-1.,9.773375837189E-031)); +#17874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17875 = PCURVE('',#17369,#17876); +#17876 = DEFINITIONAL_REPRESENTATION('',(#17877),#17880); +#17877 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17878,#17879),.UNSPECIFIED., .F.,.F.,(2,2),(-0.115,7.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#15486 = CARTESIAN_POINT('',(3.14159265359,0.115)); -#15487 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); -#15488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15489 = ORIENTED_EDGE('',*,*,#15490,.F.); -#15490 = EDGE_CURVE('',#15359,#15469,#15491,.T.); -#15491 = SURFACE_CURVE('',#15492,(#15496,#15503),.PCURVE_S1.); -#15492 = LINE('',#15493,#15494); -#15493 = CARTESIAN_POINT('',(0.26,-0.25,0.E+000)); -#15494 = VECTOR('',#15495,1.); -#15495 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#15496 = PCURVE('',#14878,#15497); -#15497 = DEFINITIONAL_REPRESENTATION('',(#15498),#15502); -#15498 = LINE('',#15499,#15500); -#15499 = CARTESIAN_POINT('',(0.115,0.E+000)); -#15500 = VECTOR('',#15501,1.); -#15501 = DIRECTION('',(0.E+000,-1.)); -#15502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15503 = PCURVE('',#15504,#15509); -#15504 = CYLINDRICAL_SURFACE('',#15505,1.E-002); -#15505 = AXIS2_PLACEMENT_3D('',#15506,#15507,#15508); -#15506 = CARTESIAN_POINT('',(0.26,-0.25,1.E-002)); -#15507 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15508 = DIRECTION('',(0.E+000,0.E+000,1.)); -#15509 = DEFINITIONAL_REPRESENTATION('',(#15510),#15513); -#15510 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15511,#15512),.UNSPECIFIED., +#17878 = CARTESIAN_POINT('',(3.14159265359,0.115)); +#17879 = CARTESIAN_POINT('',(3.14159265359,-7.5E-002)); +#17880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17881 = ORIENTED_EDGE('',*,*,#17882,.F.); +#17882 = EDGE_CURVE('',#17751,#17861,#17883,.T.); +#17883 = SURFACE_CURVE('',#17884,(#17888,#17895),.PCURVE_S1.); +#17884 = LINE('',#17885,#17886); +#17885 = CARTESIAN_POINT('',(0.26,-0.25,0.E+000)); +#17886 = VECTOR('',#17887,1.); +#17887 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#17888 = PCURVE('',#17270,#17889); +#17889 = DEFINITIONAL_REPRESENTATION('',(#17890),#17894); +#17890 = LINE('',#17891,#17892); +#17891 = CARTESIAN_POINT('',(0.115,0.E+000)); +#17892 = VECTOR('',#17893,1.); +#17893 = DIRECTION('',(0.E+000,-1.)); +#17894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17895 = PCURVE('',#17896,#17901); +#17896 = CYLINDRICAL_SURFACE('',#17897,1.E-002); +#17897 = AXIS2_PLACEMENT_3D('',#17898,#17899,#17900); +#17898 = CARTESIAN_POINT('',(0.26,-0.25,1.E-002)); +#17899 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17900 = DIRECTION('',(0.E+000,0.E+000,1.)); +#17901 = DEFINITIONAL_REPRESENTATION('',(#17902),#17905); +#17902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17903,#17904),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#15511 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#15512 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#15513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15514 = ORIENTED_EDGE('',*,*,#15358,.T.); -#15515 = ADVANCED_FACE('',(#15516),#14977,.T.); -#15516 = FACE_BOUND('',#15517,.T.); -#15517 = EDGE_LOOP('',(#15518,#15519,#15564,#15624)); -#15518 = ORIENTED_EDGE('',*,*,#14940,.T.); -#15519 = ORIENTED_EDGE('',*,*,#15520,.T.); -#15520 = EDGE_CURVE('',#14896,#15521,#15523,.T.); -#15521 = VERTEX_POINT('',#15522); -#15522 = CARTESIAN_POINT('',(0.26,-0.25,5.E-002)); -#15523 = SURFACE_CURVE('',#15524,(#15528,#15557),.PCURVE_S1.); -#15524 = LINE('',#15525,#15526); -#15525 = CARTESIAN_POINT('',(0.375,-0.25,5.E-002)); -#15526 = VECTOR('',#15527,1.); -#15527 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); -#15528 = PCURVE('',#14977,#15529); -#15529 = DEFINITIONAL_REPRESENTATION('',(#15530),#15556); -#15530 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15531,#15532,#15533,#15534, - #15535,#15536,#15537,#15538,#15539,#15540,#15541,#15542,#15543, - #15544,#15545,#15546,#15547,#15548,#15549,#15550,#15551,#15552, - #15553,#15554,#15555),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17903 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#17904 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#17905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17906 = ORIENTED_EDGE('',*,*,#17750,.T.); +#17907 = ADVANCED_FACE('',(#17908),#17369,.T.); +#17908 = FACE_BOUND('',#17909,.T.); +#17909 = EDGE_LOOP('',(#17910,#17911,#17956,#18016)); +#17910 = ORIENTED_EDGE('',*,*,#17332,.T.); +#17911 = ORIENTED_EDGE('',*,*,#17912,.T.); +#17912 = EDGE_CURVE('',#17288,#17913,#17915,.T.); +#17913 = VERTEX_POINT('',#17914); +#17914 = CARTESIAN_POINT('',(0.26,-0.25,5.E-002)); +#17915 = SURFACE_CURVE('',#17916,(#17920,#17949),.PCURVE_S1.); +#17916 = LINE('',#17917,#17918); +#17917 = CARTESIAN_POINT('',(0.375,-0.25,5.E-002)); +#17918 = VECTOR('',#17919,1.); +#17919 = DIRECTION('',(-1.,-9.773375837189E-031,0.E+000)); +#17920 = PCURVE('',#17369,#17921); +#17921 = DEFINITIONAL_REPRESENTATION('',(#17922),#17948); +#17922 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17923,#17924,#17925,#17926, + #17927,#17928,#17929,#17930,#17931,#17932,#17933,#17934,#17935, + #17936,#17937,#17938,#17939,#17940,#17941,#17942,#17943,#17944, + #17945,#17946,#17947),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-7.5E-002,-6.636363636364E-002, -5.772727272727E-002,-4.909090909091E-002,-4.045454545455E-002, -3.181818181818E-002,-2.318181818182E-002,-1.454545454545E-002, @@ -18964,67 +21953,67 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.454545454545E-002,6.318181818182E-002,7.181818181818E-002, 8.045454545455E-002,8.909090909091E-002,9.772727272727E-002, 0.106363636364,0.115),.UNSPECIFIED.); -#15531 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); -#15532 = CARTESIAN_POINT('',(4.712388980385,-7.212121212121E-002)); -#15533 = CARTESIAN_POINT('',(4.712388980385,-6.636363636364E-002)); -#15534 = CARTESIAN_POINT('',(4.712388980385,-5.772727272727E-002)); -#15535 = CARTESIAN_POINT('',(4.712388980385,-4.909090909091E-002)); -#15536 = CARTESIAN_POINT('',(4.712388980385,-4.045454545455E-002)); -#15537 = CARTESIAN_POINT('',(4.712388980385,-3.181818181818E-002)); -#15538 = CARTESIAN_POINT('',(4.712388980385,-2.318181818182E-002)); -#15539 = CARTESIAN_POINT('',(4.712388980385,-1.454545454545E-002)); -#15540 = CARTESIAN_POINT('',(4.712388980385,-5.909090909091E-003)); -#15541 = CARTESIAN_POINT('',(4.712388980385,2.727272727273E-003)); -#15542 = CARTESIAN_POINT('',(4.712388980385,1.136363636364E-002)); -#15543 = CARTESIAN_POINT('',(4.712388980385,2.E-002)); -#15544 = CARTESIAN_POINT('',(4.712388980385,2.863636363636E-002)); -#15545 = CARTESIAN_POINT('',(4.712388980385,3.727272727273E-002)); -#15546 = CARTESIAN_POINT('',(4.712388980385,4.590909090909E-002)); -#15547 = CARTESIAN_POINT('',(4.712388980385,5.454545454545E-002)); -#15548 = CARTESIAN_POINT('',(4.712388980385,6.318181818182E-002)); -#15549 = CARTESIAN_POINT('',(4.712388980385,7.181818181818E-002)); -#15550 = CARTESIAN_POINT('',(4.712388980385,8.045454545455E-002)); -#15551 = CARTESIAN_POINT('',(4.712388980385,8.909090909091E-002)); -#15552 = CARTESIAN_POINT('',(4.712388980385,9.772727272727E-002)); -#15553 = CARTESIAN_POINT('',(4.712388980385,0.106363636364)); -#15554 = CARTESIAN_POINT('',(4.712388980385,0.112121212121)); -#15555 = CARTESIAN_POINT('',(4.712388980385,0.115)); -#15556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15557 = PCURVE('',#15006,#15558); -#15558 = DEFINITIONAL_REPRESENTATION('',(#15559),#15563); -#15559 = LINE('',#15560,#15561); -#15560 = CARTESIAN_POINT('',(3.398804616898E-078,-0.25)); -#15561 = VECTOR('',#15562,1.); -#15562 = DIRECTION('',(1.,1.359521846759E-077)); -#15563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15564 = ORIENTED_EDGE('',*,*,#15565,.F.); -#15565 = EDGE_CURVE('',#15469,#15521,#15566,.T.); -#15566 = SURFACE_CURVE('',#15567,(#15572,#15578),.PCURVE_S1.); -#15567 = CIRCLE('',#15568,5.E-002); -#15568 = AXIS2_PLACEMENT_3D('',#15569,#15570,#15571); -#15569 = CARTESIAN_POINT('',(0.26,-0.2,5.E-002)); -#15570 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#15571 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15572 = PCURVE('',#14977,#15573); -#15573 = DEFINITIONAL_REPRESENTATION('',(#15574),#15577); -#15574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15575,#15576),.UNSPECIFIED., +#17923 = CARTESIAN_POINT('',(4.712388980385,-7.5E-002)); +#17924 = CARTESIAN_POINT('',(4.712388980385,-7.212121212121E-002)); +#17925 = CARTESIAN_POINT('',(4.712388980385,-6.636363636364E-002)); +#17926 = CARTESIAN_POINT('',(4.712388980385,-5.772727272727E-002)); +#17927 = CARTESIAN_POINT('',(4.712388980385,-4.909090909091E-002)); +#17928 = CARTESIAN_POINT('',(4.712388980385,-4.045454545455E-002)); +#17929 = CARTESIAN_POINT('',(4.712388980385,-3.181818181818E-002)); +#17930 = CARTESIAN_POINT('',(4.712388980385,-2.318181818182E-002)); +#17931 = CARTESIAN_POINT('',(4.712388980385,-1.454545454545E-002)); +#17932 = CARTESIAN_POINT('',(4.712388980385,-5.909090909091E-003)); +#17933 = CARTESIAN_POINT('',(4.712388980385,2.727272727273E-003)); +#17934 = CARTESIAN_POINT('',(4.712388980385,1.136363636364E-002)); +#17935 = CARTESIAN_POINT('',(4.712388980385,2.E-002)); +#17936 = CARTESIAN_POINT('',(4.712388980385,2.863636363636E-002)); +#17937 = CARTESIAN_POINT('',(4.712388980385,3.727272727273E-002)); +#17938 = CARTESIAN_POINT('',(4.712388980385,4.590909090909E-002)); +#17939 = CARTESIAN_POINT('',(4.712388980385,5.454545454545E-002)); +#17940 = CARTESIAN_POINT('',(4.712388980385,6.318181818182E-002)); +#17941 = CARTESIAN_POINT('',(4.712388980385,7.181818181818E-002)); +#17942 = CARTESIAN_POINT('',(4.712388980385,8.045454545455E-002)); +#17943 = CARTESIAN_POINT('',(4.712388980385,8.909090909091E-002)); +#17944 = CARTESIAN_POINT('',(4.712388980385,9.772727272727E-002)); +#17945 = CARTESIAN_POINT('',(4.712388980385,0.106363636364)); +#17946 = CARTESIAN_POINT('',(4.712388980385,0.112121212121)); +#17947 = CARTESIAN_POINT('',(4.712388980385,0.115)); +#17948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17949 = PCURVE('',#17398,#17950); +#17950 = DEFINITIONAL_REPRESENTATION('',(#17951),#17955); +#17951 = LINE('',#17952,#17953); +#17952 = CARTESIAN_POINT('',(3.398804616898E-078,-0.25)); +#17953 = VECTOR('',#17954,1.); +#17954 = DIRECTION('',(1.,1.359521846759E-077)); +#17955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#17956 = ORIENTED_EDGE('',*,*,#17957,.F.); +#17957 = EDGE_CURVE('',#17861,#17913,#17958,.T.); +#17958 = SURFACE_CURVE('',#17959,(#17964,#17970),.PCURVE_S1.); +#17959 = CIRCLE('',#17960,5.E-002); +#17960 = AXIS2_PLACEMENT_3D('',#17961,#17962,#17963); +#17961 = CARTESIAN_POINT('',(0.26,-0.2,5.E-002)); +#17962 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#17963 = DIRECTION('',(0.E+000,1.,0.E+000)); +#17964 = PCURVE('',#17369,#17965); +#17965 = DEFINITIONAL_REPRESENTATION('',(#17966),#17969); +#17966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17967,#17968),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#15575 = CARTESIAN_POINT('',(3.14159265359,0.115)); -#15576 = CARTESIAN_POINT('',(4.712388980385,0.115)); -#15577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#17967 = CARTESIAN_POINT('',(3.14159265359,0.115)); +#17968 = CARTESIAN_POINT('',(4.712388980385,0.115)); +#17969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15578 = PCURVE('',#15579,#15596); -#15579 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#15580,#15581,#15582,#15583) - ,(#15584,#15585,#15586,#15587) - ,(#15588,#15589,#15590,#15591) - ,(#15592,#15593,#15594,#15595 +#17970 = PCURVE('',#17971,#17988); +#17971 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#17972,#17973,#17974,#17975) + ,(#17976,#17977,#17978,#17979) + ,(#17980,#17981,#17982,#17983) + ,(#17984,#17985,#17986,#17987 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -19033,28 +22022,28 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.647603013861,0.647603013861,0.804737854124) ,(1.,0.804737854124,0.804737854124,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#15580 = CARTESIAN_POINT('',(0.26,-0.25,5.E-002)); -#15581 = CARTESIAN_POINT('',(0.26,-0.25,2.071067811865E-002)); -#15582 = CARTESIAN_POINT('',(0.26,-0.229289321881,3.175554641438E-017)); -#15583 = CARTESIAN_POINT('',(0.26,-0.2,0.E+000)); -#15584 = CARTESIAN_POINT('',(0.254142135624,-0.25,5.E-002)); -#15585 = CARTESIAN_POINT('',(0.254142135624,-0.25,2.071067811865E-002)); -#15586 = CARTESIAN_POINT('',(0.254142135624,-0.229289321881, +#17972 = CARTESIAN_POINT('',(0.26,-0.25,5.E-002)); +#17973 = CARTESIAN_POINT('',(0.26,-0.25,2.071067811865E-002)); +#17974 = CARTESIAN_POINT('',(0.26,-0.229289321881,3.175554641438E-017)); +#17975 = CARTESIAN_POINT('',(0.26,-0.2,0.E+000)); +#17976 = CARTESIAN_POINT('',(0.254142135624,-0.25,5.E-002)); +#17977 = CARTESIAN_POINT('',(0.254142135624,-0.25,2.071067811865E-002)); +#17978 = CARTESIAN_POINT('',(0.254142135624,-0.229289321881, 3.175554641438E-017)); -#15587 = CARTESIAN_POINT('',(0.254142135624,-0.2,0.E+000)); -#15588 = CARTESIAN_POINT('',(0.25,-0.245857864376,5.E-002)); -#15589 = CARTESIAN_POINT('',(0.25,-0.245857864376,2.313708498985E-002)); -#15590 = CARTESIAN_POINT('',(0.25,-0.22686291501,4.142135623731E-003)); -#15591 = CARTESIAN_POINT('',(0.25,-0.2,4.142135623731E-003)); -#15592 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); -#15593 = CARTESIAN_POINT('',(0.25,-0.24,2.656854249492E-002)); -#15594 = CARTESIAN_POINT('',(0.25,-0.223431457505,1.E-002)); -#15595 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); -#15596 = DEFINITIONAL_REPRESENTATION('',(#15597),#15623); -#15597 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15598,#15599,#15600,#15601, - #15602,#15603,#15604,#15605,#15606,#15607,#15608,#15609,#15610, - #15611,#15612,#15613,#15614,#15615,#15616,#15617,#15618,#15619, - #15620,#15621,#15622),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#17979 = CARTESIAN_POINT('',(0.254142135624,-0.2,0.E+000)); +#17980 = CARTESIAN_POINT('',(0.25,-0.245857864376,5.E-002)); +#17981 = CARTESIAN_POINT('',(0.25,-0.245857864376,2.313708498985E-002)); +#17982 = CARTESIAN_POINT('',(0.25,-0.22686291501,4.142135623731E-003)); +#17983 = CARTESIAN_POINT('',(0.25,-0.2,4.142135623731E-003)); +#17984 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); +#17985 = CARTESIAN_POINT('',(0.25,-0.24,2.656854249492E-002)); +#17986 = CARTESIAN_POINT('',(0.25,-0.223431457505,1.E-002)); +#17987 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); +#17988 = DEFINITIONAL_REPRESENTATION('',(#17989),#18015); +#17989 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17990,#17991,#17992,#17993, + #17994,#17995,#17996,#17997,#17998,#17999,#18000,#18001,#18002, + #18003,#18004,#18005,#18006,#18007,#18008,#18009,#18010,#18011, + #18012,#18013,#18014),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -19062,132 +22051,132 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#15598 = CARTESIAN_POINT('',(0.E+000,1.)); -#15599 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); -#15600 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); -#15601 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); -#15602 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); -#15603 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); -#15604 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); -#15605 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); -#15606 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); -#15607 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); -#15608 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); -#15609 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); -#15610 = CARTESIAN_POINT('',(0.E+000,0.5)); -#15611 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); -#15612 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); -#15613 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); -#15614 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); -#15615 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); -#15616 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); -#15617 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); -#15618 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); -#15619 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); -#15620 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); -#15621 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); -#15622 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15624 = ORIENTED_EDGE('',*,*,#15468,.T.); -#15625 = ADVANCED_FACE('',(#15626),#15006,.F.); -#15626 = FACE_BOUND('',#15627,.T.); -#15627 = EDGE_LOOP('',(#15628,#15629,#15630,#15631)); -#15628 = ORIENTED_EDGE('',*,*,#15520,.F.); -#15629 = ORIENTED_EDGE('',*,*,#14993,.F.); -#15630 = ORIENTED_EDGE('',*,*,#15143,.F.); -#15631 = ORIENTED_EDGE('',*,*,#15632,.F.); -#15632 = EDGE_CURVE('',#15521,#15082,#15633,.T.); -#15633 = SURFACE_CURVE('',#15634,(#15638,#15645),.PCURVE_S1.); -#15634 = LINE('',#15635,#15636); -#15635 = CARTESIAN_POINT('',(0.26,-0.25,0.3)); -#15636 = VECTOR('',#15637,1.); -#15637 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#15638 = PCURVE('',#15006,#15639); -#15639 = DEFINITIONAL_REPRESENTATION('',(#15640),#15644); -#15640 = LINE('',#15641,#15642); -#15641 = CARTESIAN_POINT('',(0.115,-3.028861393654E-062)); -#15642 = VECTOR('',#15643,1.); -#15643 = DIRECTION('',(2.633792516221E-061,1.)); -#15644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15645 = PCURVE('',#15646,#15651); -#15646 = CYLINDRICAL_SURFACE('',#15647,1.E-002); -#15647 = AXIS2_PLACEMENT_3D('',#15648,#15649,#15650); -#15648 = CARTESIAN_POINT('',(0.26,-0.24,0.3)); -#15649 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#15650 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); -#15651 = DEFINITIONAL_REPRESENTATION('',(#15652),#15655); -#15652 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15653,#15654),.UNSPECIFIED., +#17990 = CARTESIAN_POINT('',(0.E+000,1.)); +#17991 = CARTESIAN_POINT('',(0.E+000,0.983172198663)); +#17992 = CARTESIAN_POINT('',(0.E+000,0.950009297011)); +#17993 = CARTESIAN_POINT('',(0.E+000,0.901574474096)); +#17994 = CARTESIAN_POINT('',(0.E+000,0.854275086925)); +#17995 = CARTESIAN_POINT('',(0.E+000,0.807956362777)); +#17996 = CARTESIAN_POINT('',(0.E+000,0.762473275577)); +#17997 = CARTESIAN_POINT('',(0.E+000,0.717690577461)); +#17998 = CARTESIAN_POINT('',(0.E+000,0.673480563786)); +#17999 = CARTESIAN_POINT('',(0.E+000,0.629721689409)); +#18000 = CARTESIAN_POINT('',(0.E+000,0.586297147708)); +#18001 = CARTESIAN_POINT('',(0.E+000,0.543093605115)); +#18002 = CARTESIAN_POINT('',(0.E+000,0.5)); +#18003 = CARTESIAN_POINT('',(0.E+000,0.456906394885)); +#18004 = CARTESIAN_POINT('',(0.E+000,0.413702852292)); +#18005 = CARTESIAN_POINT('',(0.E+000,0.370278310591)); +#18006 = CARTESIAN_POINT('',(0.E+000,0.326519436214)); +#18007 = CARTESIAN_POINT('',(0.E+000,0.282309422539)); +#18008 = CARTESIAN_POINT('',(0.E+000,0.237526724423)); +#18009 = CARTESIAN_POINT('',(0.E+000,0.192043637223)); +#18010 = CARTESIAN_POINT('',(0.E+000,0.145724913075)); +#18011 = CARTESIAN_POINT('',(0.E+000,9.842552590405E-002)); +#18012 = CARTESIAN_POINT('',(0.E+000,4.999070298881E-002)); +#18013 = CARTESIAN_POINT('',(0.E+000,1.682780133705E-002)); +#18014 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#18015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18016 = ORIENTED_EDGE('',*,*,#17860,.T.); +#18017 = ADVANCED_FACE('',(#18018),#17398,.F.); +#18018 = FACE_BOUND('',#18019,.T.); +#18019 = EDGE_LOOP('',(#18020,#18021,#18022,#18023)); +#18020 = ORIENTED_EDGE('',*,*,#17912,.F.); +#18021 = ORIENTED_EDGE('',*,*,#17385,.F.); +#18022 = ORIENTED_EDGE('',*,*,#17535,.F.); +#18023 = ORIENTED_EDGE('',*,*,#18024,.F.); +#18024 = EDGE_CURVE('',#17913,#17474,#18025,.T.); +#18025 = SURFACE_CURVE('',#18026,(#18030,#18037),.PCURVE_S1.); +#18026 = LINE('',#18027,#18028); +#18027 = CARTESIAN_POINT('',(0.26,-0.25,0.3)); +#18028 = VECTOR('',#18029,1.); +#18029 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#18030 = PCURVE('',#17398,#18031); +#18031 = DEFINITIONAL_REPRESENTATION('',(#18032),#18036); +#18032 = LINE('',#18033,#18034); +#18033 = CARTESIAN_POINT('',(0.115,-3.028861393654E-062)); +#18034 = VECTOR('',#18035,1.); +#18035 = DIRECTION('',(2.633792516221E-061,1.)); +#18036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18037 = PCURVE('',#18038,#18043); +#18038 = CYLINDRICAL_SURFACE('',#18039,1.E-002); +#18039 = AXIS2_PLACEMENT_3D('',#18040,#18041,#18042); +#18040 = CARTESIAN_POINT('',(0.26,-0.24,0.3)); +#18041 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#18042 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); +#18043 = DEFINITIONAL_REPRESENTATION('',(#18044),#18047); +#18044 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18045,#18046),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#15653 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#15654 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#15655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15656 = ADVANCED_FACE('',(#15657),#11952,.T.); -#15657 = FACE_BOUND('',#15658,.T.); -#15658 = EDGE_LOOP('',(#15659,#15660,#15661,#15662)); -#15659 = ORIENTED_EDGE('',*,*,#11937,.F.); -#15660 = ORIENTED_EDGE('',*,*,#15034,.T.); -#15661 = ORIENTED_EDGE('',*,*,#11995,.T.); -#15662 = ORIENTED_EDGE('',*,*,#15663,.F.); -#15663 = EDGE_CURVE('',#11938,#11964,#15664,.T.); -#15664 = SURFACE_CURVE('',#15665,(#15670,#15676),.PCURVE_S1.); -#15665 = CIRCLE('',#15666,7.825944375606E-002); -#15666 = AXIS2_PLACEMENT_3D('',#15667,#15668,#15669); -#15667 = CARTESIAN_POINT('',(0.25,0.E+000,0.3)); -#15668 = DIRECTION('',(1.,0.E+000,0.E+000)); -#15669 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#15670 = PCURVE('',#11952,#15671); -#15671 = DEFINITIONAL_REPRESENTATION('',(#15672),#15675); -#15672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15673,#15674),.UNSPECIFIED., +#18045 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#18046 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#18047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18048 = ADVANCED_FACE('',(#18049),#14344,.T.); +#18049 = FACE_BOUND('',#18050,.T.); +#18050 = EDGE_LOOP('',(#18051,#18052,#18053,#18054)); +#18051 = ORIENTED_EDGE('',*,*,#14329,.F.); +#18052 = ORIENTED_EDGE('',*,*,#17426,.T.); +#18053 = ORIENTED_EDGE('',*,*,#14387,.T.); +#18054 = ORIENTED_EDGE('',*,*,#18055,.F.); +#18055 = EDGE_CURVE('',#14330,#14356,#18056,.T.); +#18056 = SURFACE_CURVE('',#18057,(#18062,#18068),.PCURVE_S1.); +#18057 = CIRCLE('',#18058,7.825944375606E-002); +#18058 = AXIS2_PLACEMENT_3D('',#18059,#18060,#18061); +#18059 = CARTESIAN_POINT('',(0.25,0.E+000,0.3)); +#18060 = DIRECTION('',(1.,0.E+000,0.E+000)); +#18061 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#18062 = PCURVE('',#14344,#18063); +#18063 = DEFINITIONAL_REPRESENTATION('',(#18064),#18067); +#18064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18065,#18066),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#15673 = CARTESIAN_POINT('',(3.14159265359,0.6)); -#15674 = CARTESIAN_POINT('',(6.28318530718,0.6)); -#15675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18065 = CARTESIAN_POINT('',(3.14159265359,0.6)); +#18066 = CARTESIAN_POINT('',(6.28318530718,0.6)); +#18067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15676 = PCURVE('',#11979,#15677); -#15677 = DEFINITIONAL_REPRESENTATION('',(#15678),#15686); -#15678 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#15679,#15680,#15681,#15682 - ,#15683,#15684,#15685),.UNSPECIFIED.,.T.,.F.) +#18068 = PCURVE('',#14371,#18069); +#18069 = DEFINITIONAL_REPRESENTATION('',(#18070),#18078); +#18070 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18071,#18072,#18073,#18074 + ,#18075,#18076,#18077),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#15679 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); -#15680 = CARTESIAN_POINT('',(-7.825944375606E-002,0.385549332758)); -#15681 = CARTESIAN_POINT('',(3.912972187803E-002,0.317774666379)); -#15682 = CARTESIAN_POINT('',(0.156518887512,0.25)); -#15683 = CARTESIAN_POINT('',(3.912972187803E-002,0.182225333621)); -#15684 = CARTESIAN_POINT('',(-7.825944375606E-002,0.114450667242)); -#15685 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); -#15686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15687 = ADVANCED_FACE('',(#15688),#15097,.T.); -#15688 = FACE_BOUND('',#15689,.T.); -#15689 = EDGE_LOOP('',(#15690,#15735,#15736,#15781)); -#15690 = ORIENTED_EDGE('',*,*,#15691,.F.); -#15691 = EDGE_CURVE('',#15082,#15692,#15694,.T.); -#15692 = VERTEX_POINT('',#15693); -#15693 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); -#15694 = SURFACE_CURVE('',#15695,(#15700,#15729),.PCURVE_S1.); -#15695 = CIRCLE('',#15696,1.E-002); -#15696 = AXIS2_PLACEMENT_3D('',#15697,#15698,#15699); -#15697 = CARTESIAN_POINT('',(0.26,-0.24,0.55)); -#15698 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#15699 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); -#15700 = PCURVE('',#15097,#15701); -#15701 = DEFINITIONAL_REPRESENTATION('',(#15702),#15728); -#15702 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15703,#15704,#15705,#15706, - #15707,#15708,#15709,#15710,#15711,#15712,#15713,#15714,#15715, - #15716,#15717,#15718,#15719,#15720,#15721,#15722,#15723,#15724, - #15725,#15726,#15727),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18071 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); +#18072 = CARTESIAN_POINT('',(-7.825944375606E-002,0.385549332758)); +#18073 = CARTESIAN_POINT('',(3.912972187803E-002,0.317774666379)); +#18074 = CARTESIAN_POINT('',(0.156518887512,0.25)); +#18075 = CARTESIAN_POINT('',(3.912972187803E-002,0.182225333621)); +#18076 = CARTESIAN_POINT('',(-7.825944375606E-002,0.114450667242)); +#18077 = CARTESIAN_POINT('',(-7.825944375606E-002,0.25)); +#18078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18079 = ADVANCED_FACE('',(#18080),#17489,.T.); +#18080 = FACE_BOUND('',#18081,.T.); +#18081 = EDGE_LOOP('',(#18082,#18127,#18128,#18173)); +#18082 = ORIENTED_EDGE('',*,*,#18083,.F.); +#18083 = EDGE_CURVE('',#17474,#18084,#18086,.T.); +#18084 = VERTEX_POINT('',#18085); +#18085 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); +#18086 = SURFACE_CURVE('',#18087,(#18092,#18121),.PCURVE_S1.); +#18087 = CIRCLE('',#18088,1.E-002); +#18088 = AXIS2_PLACEMENT_3D('',#18089,#18090,#18091); +#18089 = CARTESIAN_POINT('',(0.26,-0.24,0.55)); +#18090 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#18091 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); +#18092 = PCURVE('',#17489,#18093); +#18093 = DEFINITIONAL_REPRESENTATION('',(#18094),#18120); +#18094 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18095,#18096,#18097,#18098, + #18099,#18100,#18101,#18102,#18103,#18104,#18105,#18106,#18107, + #18108,#18109,#18110,#18111,#18112,#18113,#18114,#18115,#18116, + #18117,#18118,#18119),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -19195,60 +22184,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#15703 = CARTESIAN_POINT('',(0.E+000,1.)); -#15704 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#15705 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#15706 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#15707 = CARTESIAN_POINT('',(0.145724913075,1.)); -#15708 = CARTESIAN_POINT('',(0.192043637223,1.)); -#15709 = CARTESIAN_POINT('',(0.237526724423,1.)); -#15710 = CARTESIAN_POINT('',(0.282309422539,1.)); -#15711 = CARTESIAN_POINT('',(0.326519436214,1.)); -#15712 = CARTESIAN_POINT('',(0.370278310591,1.)); -#15713 = CARTESIAN_POINT('',(0.413702852292,1.)); -#15714 = CARTESIAN_POINT('',(0.456906394885,1.)); -#15715 = CARTESIAN_POINT('',(0.5,1.)); -#15716 = CARTESIAN_POINT('',(0.543093605115,1.)); -#15717 = CARTESIAN_POINT('',(0.586297147708,1.)); -#15718 = CARTESIAN_POINT('',(0.629721689409,1.)); -#15719 = CARTESIAN_POINT('',(0.673480563786,1.)); -#15720 = CARTESIAN_POINT('',(0.717690577461,1.)); -#15721 = CARTESIAN_POINT('',(0.762473275577,1.)); -#15722 = CARTESIAN_POINT('',(0.807956362777,1.)); -#15723 = CARTESIAN_POINT('',(0.854275086925,1.)); -#15724 = CARTESIAN_POINT('',(0.901574474096,1.)); -#15725 = CARTESIAN_POINT('',(0.950009297011,1.)); -#15726 = CARTESIAN_POINT('',(0.983172198663,1.)); -#15727 = CARTESIAN_POINT('',(1.,1.)); -#15728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15729 = PCURVE('',#15646,#15730); -#15730 = DEFINITIONAL_REPRESENTATION('',(#15731),#15734); -#15731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15732,#15733),.UNSPECIFIED., +#18095 = CARTESIAN_POINT('',(0.E+000,1.)); +#18096 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#18097 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#18098 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#18099 = CARTESIAN_POINT('',(0.145724913075,1.)); +#18100 = CARTESIAN_POINT('',(0.192043637223,1.)); +#18101 = CARTESIAN_POINT('',(0.237526724423,1.)); +#18102 = CARTESIAN_POINT('',(0.282309422539,1.)); +#18103 = CARTESIAN_POINT('',(0.326519436214,1.)); +#18104 = CARTESIAN_POINT('',(0.370278310591,1.)); +#18105 = CARTESIAN_POINT('',(0.413702852292,1.)); +#18106 = CARTESIAN_POINT('',(0.456906394885,1.)); +#18107 = CARTESIAN_POINT('',(0.5,1.)); +#18108 = CARTESIAN_POINT('',(0.543093605115,1.)); +#18109 = CARTESIAN_POINT('',(0.586297147708,1.)); +#18110 = CARTESIAN_POINT('',(0.629721689409,1.)); +#18111 = CARTESIAN_POINT('',(0.673480563786,1.)); +#18112 = CARTESIAN_POINT('',(0.717690577461,1.)); +#18113 = CARTESIAN_POINT('',(0.762473275577,1.)); +#18114 = CARTESIAN_POINT('',(0.807956362777,1.)); +#18115 = CARTESIAN_POINT('',(0.854275086925,1.)); +#18116 = CARTESIAN_POINT('',(0.901574474096,1.)); +#18117 = CARTESIAN_POINT('',(0.950009297011,1.)); +#18118 = CARTESIAN_POINT('',(0.983172198663,1.)); +#18119 = CARTESIAN_POINT('',(1.,1.)); +#18120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18121 = PCURVE('',#18038,#18122); +#18122 = DEFINITIONAL_REPRESENTATION('',(#18123),#18126); +#18123 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18124,#18125),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#15732 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#15733 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#15734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15735 = ORIENTED_EDGE('',*,*,#15081,.T.); -#15736 = ORIENTED_EDGE('',*,*,#15737,.F.); -#15737 = EDGE_CURVE('',#15738,#15060,#15740,.T.); -#15738 = VERTEX_POINT('',#15739); -#15739 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); -#15740 = SURFACE_CURVE('',#15741,(#15746,#15775),.PCURVE_S1.); -#15741 = CIRCLE('',#15742,1.E-002); -#15742 = AXIS2_PLACEMENT_3D('',#15743,#15744,#15745); -#15743 = CARTESIAN_POINT('',(0.26,-0.2,0.59)); -#15744 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15745 = DIRECTION('',(0.E+000,0.E+000,1.)); -#15746 = PCURVE('',#15097,#15747); -#15747 = DEFINITIONAL_REPRESENTATION('',(#15748),#15774); -#15748 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15749,#15750,#15751,#15752, - #15753,#15754,#15755,#15756,#15757,#15758,#15759,#15760,#15761, - #15762,#15763,#15764,#15765,#15766,#15767,#15768,#15769,#15770, - #15771,#15772,#15773),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18124 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#18125 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#18126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18127 = ORIENTED_EDGE('',*,*,#17473,.T.); +#18128 = ORIENTED_EDGE('',*,*,#18129,.F.); +#18129 = EDGE_CURVE('',#18130,#17452,#18132,.T.); +#18130 = VERTEX_POINT('',#18131); +#18131 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); +#18132 = SURFACE_CURVE('',#18133,(#18138,#18167),.PCURVE_S1.); +#18133 = CIRCLE('',#18134,1.E-002); +#18134 = AXIS2_PLACEMENT_3D('',#18135,#18136,#18137); +#18135 = CARTESIAN_POINT('',(0.26,-0.2,0.59)); +#18136 = DIRECTION('',(0.E+000,1.,0.E+000)); +#18137 = DIRECTION('',(0.E+000,0.E+000,1.)); +#18138 = PCURVE('',#17489,#18139); +#18139 = DEFINITIONAL_REPRESENTATION('',(#18140),#18166); +#18140 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18141,#18142,#18143,#18144, + #18145,#18146,#18147,#18148,#18149,#18150,#18151,#18152,#18153, + #18154,#18155,#18156,#18157,#18158,#18159,#18160,#18161,#18162, + #18163,#18164,#18165),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19256,59 +22245,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#15749 = CARTESIAN_POINT('',(1.,0.E+000)); -#15750 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#15751 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#15752 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#15753 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#15754 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#15755 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#15756 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#15757 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#15758 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#15759 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#15760 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#15761 = CARTESIAN_POINT('',(0.5,0.E+000)); -#15762 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#15763 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#15764 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#15765 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#15766 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#15767 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#15768 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#15769 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#15770 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#15771 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#15772 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#15773 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15775 = PCURVE('',#15203,#15776); -#15776 = DEFINITIONAL_REPRESENTATION('',(#15777),#15780); -#15777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15778,#15779),.UNSPECIFIED., +#18141 = CARTESIAN_POINT('',(1.,0.E+000)); +#18142 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#18143 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#18144 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#18145 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#18146 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#18147 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#18148 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#18149 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#18150 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#18151 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#18152 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#18153 = CARTESIAN_POINT('',(0.5,0.E+000)); +#18154 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#18155 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#18156 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#18157 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#18158 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#18159 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#18160 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#18161 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#18162 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#18163 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#18164 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#18165 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#18166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18167 = PCURVE('',#17595,#18168); +#18168 = DEFINITIONAL_REPRESENTATION('',(#18169),#18172); +#18169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18170,#18171),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#15778 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#15779 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#15780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18170 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#18171 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#18172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15781 = ORIENTED_EDGE('',*,*,#15782,.F.); -#15782 = EDGE_CURVE('',#15692,#15738,#15783,.T.); -#15783 = SURFACE_CURVE('',#15784,(#15789,#15818),.PCURVE_S1.); -#15784 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15785,#15786,#15787,#15788), +#18173 = ORIENTED_EDGE('',*,*,#18174,.F.); +#18174 = EDGE_CURVE('',#18084,#18130,#18175,.T.); +#18175 = SURFACE_CURVE('',#18176,(#18181,#18210),.PCURVE_S1.); +#18176 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18177,#18178,#18179,#18180), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#15785 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); -#15786 = CARTESIAN_POINT('',(0.25,-0.239675836708,0.572012399811)); -#15787 = CARTESIAN_POINT('',(0.25,-0.222819941129,0.589663944536)); -#15788 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); -#15789 = PCURVE('',#15097,#15790); -#15790 = DEFINITIONAL_REPRESENTATION('',(#15791),#15817); -#15791 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15792,#15793,#15794,#15795, - #15796,#15797,#15798,#15799,#15800,#15801,#15802,#15803,#15804, - #15805,#15806,#15807,#15808,#15809,#15810,#15811,#15812,#15813, - #15814,#15815,#15816),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18177 = CARTESIAN_POINT('',(0.25,-0.24,0.55)); +#18178 = CARTESIAN_POINT('',(0.25,-0.239675836708,0.572012399811)); +#18179 = CARTESIAN_POINT('',(0.25,-0.222819941129,0.589663944536)); +#18180 = CARTESIAN_POINT('',(0.25,-0.2,0.59)); +#18181 = PCURVE('',#17489,#18182); +#18182 = DEFINITIONAL_REPRESENTATION('',(#18183),#18209); +#18183 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18184,#18185,#18186,#18187, + #18188,#18189,#18190,#18191,#18192,#18193,#18194,#18195,#18196, + #18197,#18198,#18199,#18200,#18201,#18202,#18203,#18204,#18205, + #18206,#18207,#18208),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -19316,76 +22305,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#15792 = CARTESIAN_POINT('',(1.,1.)); -#15793 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#15794 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#15795 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#15796 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); -#15797 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); -#15798 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#15799 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); -#15800 = CARTESIAN_POINT('',(1.000600014196,0.671375088892)); -#15801 = CARTESIAN_POINT('',(1.000606368831,0.628804305402)); -#15802 = CARTESIAN_POINT('',(1.000582476584,0.586710614222)); -#15803 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); -#15804 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); -#15805 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); -#15806 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#15807 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#15808 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#15809 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#15810 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#15811 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#15812 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#15813 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#15814 = CARTESIAN_POINT('',(1.000709884619,5.40288651765E-002)); -#15815 = CARTESIAN_POINT('',(1.000367478029,1.833200565126E-002)); -#15816 = CARTESIAN_POINT('',(1.,0.E+000)); -#15817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15818 = PCURVE('',#11979,#15819); -#15819 = DEFINITIONAL_REPRESENTATION('',(#15820),#15825); -#15820 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15821,#15822,#15823,#15824), +#18184 = CARTESIAN_POINT('',(1.,1.)); +#18185 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#18186 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#18187 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#18188 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); +#18189 = CARTESIAN_POINT('',(1.000599265839,0.80377852343)); +#18190 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#18191 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); +#18192 = CARTESIAN_POINT('',(1.000600014196,0.671375088892)); +#18193 = CARTESIAN_POINT('',(1.000606368831,0.628804305402)); +#18194 = CARTESIAN_POINT('',(1.000582476584,0.586710614222)); +#18195 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); +#18196 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); +#18197 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); +#18198 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#18199 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#18200 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#18201 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#18202 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#18203 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#18204 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#18205 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#18206 = CARTESIAN_POINT('',(1.000709884619,5.40288651765E-002)); +#18207 = CARTESIAN_POINT('',(1.000367478029,1.833200565126E-002)); +#18208 = CARTESIAN_POINT('',(1.,0.E+000)); +#18209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18210 = PCURVE('',#14371,#18211); +#18211 = DEFINITIONAL_REPRESENTATION('',(#18212),#18217); +#18212 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18213,#18214,#18215,#18216), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#15821 = CARTESIAN_POINT('',(0.25,1.E-002)); -#15822 = CARTESIAN_POINT('',(0.272012399811,1.032416329181E-002)); -#15823 = CARTESIAN_POINT('',(0.289663944536,2.718005887099E-002)); -#15824 = CARTESIAN_POINT('',(0.29,5.E-002)); -#15825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15826 = ADVANCED_FACE('',(#15827),#15203,.T.); -#15827 = FACE_BOUND('',#15828,.T.); -#15828 = EDGE_LOOP('',(#15829,#15830,#15831,#15876)); -#15829 = ORIENTED_EDGE('',*,*,#15737,.T.); -#15830 = ORIENTED_EDGE('',*,*,#15189,.T.); -#15831 = ORIENTED_EDGE('',*,*,#15832,.F.); -#15832 = EDGE_CURVE('',#15833,#15168,#15835,.T.); -#15833 = VERTEX_POINT('',#15834); -#15834 = CARTESIAN_POINT('',(0.25,0.2,0.59)); -#15835 = SURFACE_CURVE('',#15836,(#15841,#15847),.PCURVE_S1.); -#15836 = CIRCLE('',#15837,1.E-002); -#15837 = AXIS2_PLACEMENT_3D('',#15838,#15839,#15840); -#15838 = CARTESIAN_POINT('',(0.26,0.2,0.59)); -#15839 = DIRECTION('',(0.E+000,1.,-6.123233995737E-017)); -#15840 = DIRECTION('',(0.E+000,6.123233995737E-017,1.)); -#15841 = PCURVE('',#15203,#15842); -#15842 = DEFINITIONAL_REPRESENTATION('',(#15843),#15846); -#15843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15844,#15845),.UNSPECIFIED., +#18213 = CARTESIAN_POINT('',(0.25,1.E-002)); +#18214 = CARTESIAN_POINT('',(0.272012399811,1.032416329181E-002)); +#18215 = CARTESIAN_POINT('',(0.289663944536,2.718005887099E-002)); +#18216 = CARTESIAN_POINT('',(0.29,5.E-002)); +#18217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18218 = ADVANCED_FACE('',(#18219),#17595,.T.); +#18219 = FACE_BOUND('',#18220,.T.); +#18220 = EDGE_LOOP('',(#18221,#18222,#18223,#18268)); +#18221 = ORIENTED_EDGE('',*,*,#18129,.T.); +#18222 = ORIENTED_EDGE('',*,*,#17581,.T.); +#18223 = ORIENTED_EDGE('',*,*,#18224,.F.); +#18224 = EDGE_CURVE('',#18225,#17560,#18227,.T.); +#18225 = VERTEX_POINT('',#18226); +#18226 = CARTESIAN_POINT('',(0.25,0.2,0.59)); +#18227 = SURFACE_CURVE('',#18228,(#18233,#18239),.PCURVE_S1.); +#18228 = CIRCLE('',#18229,1.E-002); +#18229 = AXIS2_PLACEMENT_3D('',#18230,#18231,#18232); +#18230 = CARTESIAN_POINT('',(0.26,0.2,0.59)); +#18231 = DIRECTION('',(0.E+000,1.,-6.123233995737E-017)); +#18232 = DIRECTION('',(0.E+000,6.123233995737E-017,1.)); +#18233 = PCURVE('',#17595,#18234); +#18234 = DEFINITIONAL_REPRESENTATION('',(#18235),#18238); +#18235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18236,#18237),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#15844 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#15845 = CARTESIAN_POINT('',(6.28318530718,0.45)); -#15846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18236 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#18237 = CARTESIAN_POINT('',(6.28318530718,0.45)); +#18238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15847 = PCURVE('',#15255,#15848); -#15848 = DEFINITIONAL_REPRESENTATION('',(#15849),#15875); -#15849 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15850,#15851,#15852,#15853, - #15854,#15855,#15856,#15857,#15858,#15859,#15860,#15861,#15862, - #15863,#15864,#15865,#15866,#15867,#15868,#15869,#15870,#15871, - #15872,#15873,#15874),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18239 = PCURVE('',#17647,#18240); +#18240 = DEFINITIONAL_REPRESENTATION('',(#18241),#18267); +#18241 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18242,#18243,#18244,#18245, + #18246,#18247,#18248,#18249,#18250,#18251,#18252,#18253,#18254, + #18255,#18256,#18257,#18258,#18259,#18260,#18261,#18262,#18263, + #18264,#18265,#18266),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19393,80 +22382,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#15850 = CARTESIAN_POINT('',(1.,1.)); -#15851 = CARTESIAN_POINT('',(0.983172198663,1.)); -#15852 = CARTESIAN_POINT('',(0.950009297011,1.)); -#15853 = CARTESIAN_POINT('',(0.901574474096,1.)); -#15854 = CARTESIAN_POINT('',(0.854275086925,1.)); -#15855 = CARTESIAN_POINT('',(0.807956362777,1.)); -#15856 = CARTESIAN_POINT('',(0.762473275577,1.)); -#15857 = CARTESIAN_POINT('',(0.717690577461,1.)); -#15858 = CARTESIAN_POINT('',(0.673480563786,1.)); -#15859 = CARTESIAN_POINT('',(0.629721689409,1.)); -#15860 = CARTESIAN_POINT('',(0.586297147708,1.)); -#15861 = CARTESIAN_POINT('',(0.543093605115,1.)); -#15862 = CARTESIAN_POINT('',(0.5,1.)); -#15863 = CARTESIAN_POINT('',(0.456906394885,1.)); -#15864 = CARTESIAN_POINT('',(0.413702852292,1.)); -#15865 = CARTESIAN_POINT('',(0.370278310591,1.)); -#15866 = CARTESIAN_POINT('',(0.326519436214,1.)); -#15867 = CARTESIAN_POINT('',(0.282309422539,1.)); -#15868 = CARTESIAN_POINT('',(0.237526724423,1.)); -#15869 = CARTESIAN_POINT('',(0.192043637223,1.)); -#15870 = CARTESIAN_POINT('',(0.145724913075,1.)); -#15871 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#15872 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#15873 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#15874 = CARTESIAN_POINT('',(0.E+000,1.)); -#15875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15876 = ORIENTED_EDGE('',*,*,#15877,.F.); -#15877 = EDGE_CURVE('',#15738,#15833,#15878,.T.); -#15878 = SURFACE_CURVE('',#15879,(#15883,#15889),.PCURVE_S1.); -#15879 = LINE('',#15880,#15881); -#15880 = CARTESIAN_POINT('',(0.25,-0.25,0.59)); -#15881 = VECTOR('',#15882,1.); -#15882 = DIRECTION('',(0.E+000,1.,0.E+000)); -#15883 = PCURVE('',#15203,#15884); -#15884 = DEFINITIONAL_REPRESENTATION('',(#15885),#15888); -#15885 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15886,#15887),.UNSPECIFIED., +#18242 = CARTESIAN_POINT('',(1.,1.)); +#18243 = CARTESIAN_POINT('',(0.983172198663,1.)); +#18244 = CARTESIAN_POINT('',(0.950009297011,1.)); +#18245 = CARTESIAN_POINT('',(0.901574474096,1.)); +#18246 = CARTESIAN_POINT('',(0.854275086925,1.)); +#18247 = CARTESIAN_POINT('',(0.807956362777,1.)); +#18248 = CARTESIAN_POINT('',(0.762473275577,1.)); +#18249 = CARTESIAN_POINT('',(0.717690577461,1.)); +#18250 = CARTESIAN_POINT('',(0.673480563786,1.)); +#18251 = CARTESIAN_POINT('',(0.629721689409,1.)); +#18252 = CARTESIAN_POINT('',(0.586297147708,1.)); +#18253 = CARTESIAN_POINT('',(0.543093605115,1.)); +#18254 = CARTESIAN_POINT('',(0.5,1.)); +#18255 = CARTESIAN_POINT('',(0.456906394885,1.)); +#18256 = CARTESIAN_POINT('',(0.413702852292,1.)); +#18257 = CARTESIAN_POINT('',(0.370278310591,1.)); +#18258 = CARTESIAN_POINT('',(0.326519436214,1.)); +#18259 = CARTESIAN_POINT('',(0.282309422539,1.)); +#18260 = CARTESIAN_POINT('',(0.237526724423,1.)); +#18261 = CARTESIAN_POINT('',(0.192043637223,1.)); +#18262 = CARTESIAN_POINT('',(0.145724913075,1.)); +#18263 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#18264 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#18265 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#18266 = CARTESIAN_POINT('',(0.E+000,1.)); +#18267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18268 = ORIENTED_EDGE('',*,*,#18269,.F.); +#18269 = EDGE_CURVE('',#18130,#18225,#18270,.T.); +#18270 = SURFACE_CURVE('',#18271,(#18275,#18281),.PCURVE_S1.); +#18271 = LINE('',#18272,#18273); +#18272 = CARTESIAN_POINT('',(0.25,-0.25,0.59)); +#18273 = VECTOR('',#18274,1.); +#18274 = DIRECTION('',(0.E+000,1.,0.E+000)); +#18275 = PCURVE('',#17595,#18276); +#18276 = DEFINITIONAL_REPRESENTATION('',(#18277),#18280); +#18277 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18278,#18279),.UNSPECIFIED., .F.,.F.,(2,2),(5.E-002,0.45),.PIECEWISE_BEZIER_KNOTS.); -#15886 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#15887 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#15888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15889 = PCURVE('',#11979,#15890); -#15890 = DEFINITIONAL_REPRESENTATION('',(#15891),#15895); -#15891 = LINE('',#15892,#15893); -#15892 = CARTESIAN_POINT('',(0.29,0.E+000)); -#15893 = VECTOR('',#15894,1.); -#15894 = DIRECTION('',(0.E+000,1.)); -#15895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15896 = ADVANCED_FACE('',(#15897),#15255,.T.); -#15897 = FACE_BOUND('',#15898,.T.); -#15898 = EDGE_LOOP('',(#15899,#15900,#15901,#15946)); -#15899 = ORIENTED_EDGE('',*,*,#15832,.T.); -#15900 = ORIENTED_EDGE('',*,*,#15241,.T.); -#15901 = ORIENTED_EDGE('',*,*,#15902,.F.); -#15902 = EDGE_CURVE('',#15903,#15220,#15905,.T.); -#15903 = VERTEX_POINT('',#15904); -#15904 = CARTESIAN_POINT('',(0.25,0.24,0.55)); -#15905 = SURFACE_CURVE('',#15906,(#15911,#15940),.PCURVE_S1.); -#15906 = CIRCLE('',#15907,1.E-002); -#15907 = AXIS2_PLACEMENT_3D('',#15908,#15909,#15910); -#15908 = CARTESIAN_POINT('',(0.26,0.24,0.55)); -#15909 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); -#15910 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); -#15911 = PCURVE('',#15255,#15912); -#15912 = DEFINITIONAL_REPRESENTATION('',(#15913),#15939); -#15913 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15914,#15915,#15916,#15917, - #15918,#15919,#15920,#15921,#15922,#15923,#15924,#15925,#15926, - #15927,#15928,#15929,#15930,#15931,#15932,#15933,#15934,#15935, - #15936,#15937,#15938),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18278 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#18279 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#18280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18281 = PCURVE('',#14371,#18282); +#18282 = DEFINITIONAL_REPRESENTATION('',(#18283),#18287); +#18283 = LINE('',#18284,#18285); +#18284 = CARTESIAN_POINT('',(0.29,0.E+000)); +#18285 = VECTOR('',#18286,1.); +#18286 = DIRECTION('',(0.E+000,1.)); +#18287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18288 = ADVANCED_FACE('',(#18289),#17647,.T.); +#18289 = FACE_BOUND('',#18290,.T.); +#18290 = EDGE_LOOP('',(#18291,#18292,#18293,#18338)); +#18291 = ORIENTED_EDGE('',*,*,#18224,.T.); +#18292 = ORIENTED_EDGE('',*,*,#17633,.T.); +#18293 = ORIENTED_EDGE('',*,*,#18294,.F.); +#18294 = EDGE_CURVE('',#18295,#17612,#18297,.T.); +#18295 = VERTEX_POINT('',#18296); +#18296 = CARTESIAN_POINT('',(0.25,0.24,0.55)); +#18297 = SURFACE_CURVE('',#18298,(#18303,#18332),.PCURVE_S1.); +#18298 = CIRCLE('',#18299,1.E-002); +#18299 = AXIS2_PLACEMENT_3D('',#18300,#18301,#18302); +#18300 = CARTESIAN_POINT('',(0.26,0.24,0.55)); +#18301 = DIRECTION('',(0.E+000,2.69486466099E-031,-1.)); +#18302 = DIRECTION('',(0.E+000,1.,2.69486466099E-031)); +#18303 = PCURVE('',#17647,#18304); +#18304 = DEFINITIONAL_REPRESENTATION('',(#18305),#18331); +#18305 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18306,#18307,#18308,#18309, + #18310,#18311,#18312,#18313,#18314,#18315,#18316,#18317,#18318, + #18319,#18320,#18321,#18322,#18323,#18324,#18325,#18326,#18327, + #18328,#18329,#18330),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19474,59 +22463,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#15914 = CARTESIAN_POINT('',(1.,0.E+000)); -#15915 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#15916 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#15917 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#15918 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#15919 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#15920 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#15921 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#15922 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#15923 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#15924 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#15925 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#15926 = CARTESIAN_POINT('',(0.5,0.E+000)); -#15927 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#15928 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#15929 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#15930 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#15931 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#15932 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#15933 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#15934 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#15935 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#15936 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); -#15937 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#15938 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#15939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15940 = PCURVE('',#15342,#15941); -#15941 = DEFINITIONAL_REPRESENTATION('',(#15942),#15945); -#15942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#15943,#15944),.UNSPECIFIED., +#18306 = CARTESIAN_POINT('',(1.,0.E+000)); +#18307 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#18308 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#18309 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#18310 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#18311 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#18312 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#18313 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#18314 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#18315 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#18316 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#18317 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#18318 = CARTESIAN_POINT('',(0.5,0.E+000)); +#18319 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#18320 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#18321 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#18322 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#18323 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#18324 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#18325 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#18326 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#18327 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#18328 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); +#18329 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#18330 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#18331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18332 = PCURVE('',#17734,#18333); +#18333 = DEFINITIONAL_REPRESENTATION('',(#18334),#18337); +#18334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18335,#18336),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#15943 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#15944 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#15945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18335 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#18336 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#18337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#15946 = ORIENTED_EDGE('',*,*,#15947,.F.); -#15947 = EDGE_CURVE('',#15833,#15903,#15948,.T.); -#15948 = SURFACE_CURVE('',#15949,(#15954,#15983),.PCURVE_S1.); -#15949 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15950,#15951,#15952,#15953), +#18338 = ORIENTED_EDGE('',*,*,#18339,.F.); +#18339 = EDGE_CURVE('',#18225,#18295,#18340,.T.); +#18340 = SURFACE_CURVE('',#18341,(#18346,#18375),.PCURVE_S1.); +#18341 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18342,#18343,#18344,#18345), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#15950 = CARTESIAN_POINT('',(0.25,0.2,0.59)); -#15951 = CARTESIAN_POINT('',(0.25,0.222012399811,0.589675836708)); -#15952 = CARTESIAN_POINT('',(0.25,0.239663944536,0.572819941129)); -#15953 = CARTESIAN_POINT('',(0.25,0.24,0.55)); -#15954 = PCURVE('',#15255,#15955); -#15955 = DEFINITIONAL_REPRESENTATION('',(#15956),#15982); -#15956 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15957,#15958,#15959,#15960, - #15961,#15962,#15963,#15964,#15965,#15966,#15967,#15968,#15969, - #15970,#15971,#15972,#15973,#15974,#15975,#15976,#15977,#15978, - #15979,#15980,#15981),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18342 = CARTESIAN_POINT('',(0.25,0.2,0.59)); +#18343 = CARTESIAN_POINT('',(0.25,0.222012399811,0.589675836708)); +#18344 = CARTESIAN_POINT('',(0.25,0.239663944536,0.572819941129)); +#18345 = CARTESIAN_POINT('',(0.25,0.24,0.55)); +#18346 = PCURVE('',#17647,#18347); +#18347 = DEFINITIONAL_REPRESENTATION('',(#18348),#18374); +#18348 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18349,#18350,#18351,#18352, + #18353,#18354,#18355,#18356,#18357,#18358,#18359,#18360,#18361, + #18362,#18363,#18364,#18365,#18366,#18367,#18368,#18369,#18370, + #18371,#18372,#18373),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -19534,76 +22523,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#15957 = CARTESIAN_POINT('',(1.,1.)); -#15958 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#15959 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#15960 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#15961 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); -#15962 = CARTESIAN_POINT('',(1.000599265839,0.803778523426)); -#15963 = CARTESIAN_POINT('',(1.000601789944,0.758666144519)); -#15964 = CARTESIAN_POINT('',(1.000601540492,0.714599645833)); -#15965 = CARTESIAN_POINT('',(1.000600014196,0.671375089061)); -#15966 = CARTESIAN_POINT('',(1.000606368831,0.628804305357)); -#15967 = CARTESIAN_POINT('',(1.000582476584,0.586710614234)); -#15968 = CARTESIAN_POINT('',(1.000671690938,0.544924984697)); -#15969 = CARTESIAN_POINT('',(1.000081825934,0.503282378119)); -#15970 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); -#15971 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#15972 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#15973 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#15974 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#15975 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#15976 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#15977 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#15978 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#15979 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); -#15980 = CARTESIAN_POINT('',(1.000367478029,1.833200565131E-002)); -#15981 = CARTESIAN_POINT('',(1.,0.E+000)); -#15982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15983 = PCURVE('',#11979,#15984); -#15984 = DEFINITIONAL_REPRESENTATION('',(#15985),#15990); -#15985 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#15986,#15987,#15988,#15989), +#18349 = CARTESIAN_POINT('',(1.,1.)); +#18350 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#18351 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#18352 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#18353 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); +#18354 = CARTESIAN_POINT('',(1.000599265839,0.803778523426)); +#18355 = CARTESIAN_POINT('',(1.000601789944,0.758666144519)); +#18356 = CARTESIAN_POINT('',(1.000601540492,0.714599645833)); +#18357 = CARTESIAN_POINT('',(1.000600014196,0.671375089061)); +#18358 = CARTESIAN_POINT('',(1.000606368831,0.628804305357)); +#18359 = CARTESIAN_POINT('',(1.000582476584,0.586710614234)); +#18360 = CARTESIAN_POINT('',(1.000671690938,0.544924984697)); +#18361 = CARTESIAN_POINT('',(1.000081825934,0.503282378119)); +#18362 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); +#18363 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#18364 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#18365 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#18366 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#18367 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#18368 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#18369 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#18370 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#18371 = CARTESIAN_POINT('',(1.000709884619,5.402886517654E-002)); +#18372 = CARTESIAN_POINT('',(1.000367478029,1.833200565131E-002)); +#18373 = CARTESIAN_POINT('',(1.,0.E+000)); +#18374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18375 = PCURVE('',#14371,#18376); +#18376 = DEFINITIONAL_REPRESENTATION('',(#18377),#18382); +#18377 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18378,#18379,#18380,#18381), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#15986 = CARTESIAN_POINT('',(0.29,0.45)); -#15987 = CARTESIAN_POINT('',(0.289675836708,0.472012399811)); -#15988 = CARTESIAN_POINT('',(0.272819941129,0.489663944536)); -#15989 = CARTESIAN_POINT('',(0.25,0.49)); -#15990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#15991 = ADVANCED_FACE('',(#15992),#15342,.T.); -#15992 = FACE_BOUND('',#15993,.T.); -#15993 = EDGE_LOOP('',(#15994,#15995,#15996,#16041)); -#15994 = ORIENTED_EDGE('',*,*,#15902,.T.); -#15995 = ORIENTED_EDGE('',*,*,#15328,.T.); -#15996 = ORIENTED_EDGE('',*,*,#15997,.F.); -#15997 = EDGE_CURVE('',#15998,#15307,#16000,.T.); -#15998 = VERTEX_POINT('',#15999); -#15999 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); -#16000 = SURFACE_CURVE('',#16001,(#16006,#16012),.PCURVE_S1.); -#16001 = CIRCLE('',#16002,1.E-002); -#16002 = AXIS2_PLACEMENT_3D('',#16003,#16004,#16005); -#16003 = CARTESIAN_POINT('',(0.26,0.24,5.E-002)); -#16004 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#16005 = DIRECTION('',(0.E+000,1.,0.E+000)); -#16006 = PCURVE('',#15342,#16007); -#16007 = DEFINITIONAL_REPRESENTATION('',(#16008),#16011); -#16008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16009,#16010),.UNSPECIFIED., +#18378 = CARTESIAN_POINT('',(0.29,0.45)); +#18379 = CARTESIAN_POINT('',(0.289675836708,0.472012399811)); +#18380 = CARTESIAN_POINT('',(0.272819941129,0.489663944536)); +#18381 = CARTESIAN_POINT('',(0.25,0.49)); +#18382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18383 = ADVANCED_FACE('',(#18384),#17734,.T.); +#18384 = FACE_BOUND('',#18385,.T.); +#18385 = EDGE_LOOP('',(#18386,#18387,#18388,#18433)); +#18386 = ORIENTED_EDGE('',*,*,#18294,.T.); +#18387 = ORIENTED_EDGE('',*,*,#17720,.T.); +#18388 = ORIENTED_EDGE('',*,*,#18389,.F.); +#18389 = EDGE_CURVE('',#18390,#17699,#18392,.T.); +#18390 = VERTEX_POINT('',#18391); +#18391 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); +#18392 = SURFACE_CURVE('',#18393,(#18398,#18404),.PCURVE_S1.); +#18393 = CIRCLE('',#18394,1.E-002); +#18394 = AXIS2_PLACEMENT_3D('',#18395,#18396,#18397); +#18395 = CARTESIAN_POINT('',(0.26,0.24,5.E-002)); +#18396 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#18397 = DIRECTION('',(0.E+000,1.,0.E+000)); +#18398 = PCURVE('',#17734,#18399); +#18399 = DEFINITIONAL_REPRESENTATION('',(#18400),#18403); +#18400 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18401,#18402),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#16009 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16010 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#16011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18401 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#18402 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#18403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#16012 = PCURVE('',#15417,#16013); -#16013 = DEFINITIONAL_REPRESENTATION('',(#16014),#16040); -#16014 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16015,#16016,#16017,#16018, - #16019,#16020,#16021,#16022,#16023,#16024,#16025,#16026,#16027, - #16028,#16029,#16030,#16031,#16032,#16033,#16034,#16035,#16036, - #16037,#16038,#16039),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18404 = PCURVE('',#17809,#18405); +#18405 = DEFINITIONAL_REPRESENTATION('',(#18406),#18432); +#18406 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18407,#18408,#18409,#18410, + #18411,#18412,#18413,#18414,#18415,#18416,#18417,#18418,#18419, + #18420,#18421,#18422,#18423,#18424,#18425,#18426,#18427,#18428, + #18429,#18430,#18431),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19611,78 +22600,78 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#16015 = CARTESIAN_POINT('',(1.,1.)); -#16016 = CARTESIAN_POINT('',(0.983172198663,1.)); -#16017 = CARTESIAN_POINT('',(0.950009297011,1.)); -#16018 = CARTESIAN_POINT('',(0.901574474096,1.)); -#16019 = CARTESIAN_POINT('',(0.854275086925,1.)); -#16020 = CARTESIAN_POINT('',(0.807956362777,1.)); -#16021 = CARTESIAN_POINT('',(0.762473275577,1.)); -#16022 = CARTESIAN_POINT('',(0.717690577461,1.)); -#16023 = CARTESIAN_POINT('',(0.673480563786,1.)); -#16024 = CARTESIAN_POINT('',(0.629721689409,1.)); -#16025 = CARTESIAN_POINT('',(0.586297147708,1.)); -#16026 = CARTESIAN_POINT('',(0.543093605115,1.)); -#16027 = CARTESIAN_POINT('',(0.5,1.)); -#16028 = CARTESIAN_POINT('',(0.456906394885,1.)); -#16029 = CARTESIAN_POINT('',(0.413702852292,1.)); -#16030 = CARTESIAN_POINT('',(0.370278310591,1.)); -#16031 = CARTESIAN_POINT('',(0.326519436214,1.)); -#16032 = CARTESIAN_POINT('',(0.282309422539,1.)); -#16033 = CARTESIAN_POINT('',(0.237526724423,1.)); -#16034 = CARTESIAN_POINT('',(0.192043637223,1.)); -#16035 = CARTESIAN_POINT('',(0.145724913075,1.)); -#16036 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#16037 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#16038 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#16039 = CARTESIAN_POINT('',(0.E+000,1.)); -#16040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16041 = ORIENTED_EDGE('',*,*,#16042,.F.); -#16042 = EDGE_CURVE('',#15903,#15998,#16043,.T.); -#16043 = SURFACE_CURVE('',#16044,(#16048,#16054),.PCURVE_S1.); -#16044 = LINE('',#16045,#16046); -#16045 = CARTESIAN_POINT('',(0.25,0.24,0.3)); -#16046 = VECTOR('',#16047,1.); -#16047 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#16048 = PCURVE('',#15342,#16049); -#16049 = DEFINITIONAL_REPRESENTATION('',(#16050),#16053); -#16050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16051,#16052),.UNSPECIFIED., +#18407 = CARTESIAN_POINT('',(1.,1.)); +#18408 = CARTESIAN_POINT('',(0.983172198663,1.)); +#18409 = CARTESIAN_POINT('',(0.950009297011,1.)); +#18410 = CARTESIAN_POINT('',(0.901574474096,1.)); +#18411 = CARTESIAN_POINT('',(0.854275086925,1.)); +#18412 = CARTESIAN_POINT('',(0.807956362777,1.)); +#18413 = CARTESIAN_POINT('',(0.762473275577,1.)); +#18414 = CARTESIAN_POINT('',(0.717690577461,1.)); +#18415 = CARTESIAN_POINT('',(0.673480563786,1.)); +#18416 = CARTESIAN_POINT('',(0.629721689409,1.)); +#18417 = CARTESIAN_POINT('',(0.586297147708,1.)); +#18418 = CARTESIAN_POINT('',(0.543093605115,1.)); +#18419 = CARTESIAN_POINT('',(0.5,1.)); +#18420 = CARTESIAN_POINT('',(0.456906394885,1.)); +#18421 = CARTESIAN_POINT('',(0.413702852292,1.)); +#18422 = CARTESIAN_POINT('',(0.370278310591,1.)); +#18423 = CARTESIAN_POINT('',(0.326519436214,1.)); +#18424 = CARTESIAN_POINT('',(0.282309422539,1.)); +#18425 = CARTESIAN_POINT('',(0.237526724423,1.)); +#18426 = CARTESIAN_POINT('',(0.192043637223,1.)); +#18427 = CARTESIAN_POINT('',(0.145724913075,1.)); +#18428 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#18429 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#18430 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#18431 = CARTESIAN_POINT('',(0.E+000,1.)); +#18432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18433 = ORIENTED_EDGE('',*,*,#18434,.F.); +#18434 = EDGE_CURVE('',#18295,#18390,#18435,.T.); +#18435 = SURFACE_CURVE('',#18436,(#18440,#18446),.PCURVE_S1.); +#18436 = LINE('',#18437,#18438); +#18437 = CARTESIAN_POINT('',(0.25,0.24,0.3)); +#18438 = VECTOR('',#18439,1.); +#18439 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#18440 = PCURVE('',#17734,#18441); +#18441 = DEFINITIONAL_REPRESENTATION('',(#18442),#18445); +#18442 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18443,#18444),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16051 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16052 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16054 = PCURVE('',#11979,#16055); -#16055 = DEFINITIONAL_REPRESENTATION('',(#16056),#16060); -#16056 = LINE('',#16057,#16058); -#16057 = CARTESIAN_POINT('',(0.E+000,0.49)); -#16058 = VECTOR('',#16059,1.); -#16059 = DIRECTION('',(-1.,0.E+000)); -#16060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16061 = ADVANCED_FACE('',(#16062),#15417,.T.); -#16062 = FACE_BOUND('',#16063,.T.); -#16063 = EDGE_LOOP('',(#16064,#16109,#16154,#16155)); -#16064 = ORIENTED_EDGE('',*,*,#16065,.F.); -#16065 = EDGE_CURVE('',#16066,#15359,#16068,.T.); -#16066 = VERTEX_POINT('',#16067); -#16067 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); -#16068 = SURFACE_CURVE('',#16069,(#16074,#16103),.PCURVE_S1.); -#16069 = CIRCLE('',#16070,1.E-002); -#16070 = AXIS2_PLACEMENT_3D('',#16071,#16072,#16073); -#16071 = CARTESIAN_POINT('',(0.26,0.2,1.E-002)); -#16072 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#16073 = DIRECTION('',(0.E+000,0.E+000,1.)); -#16074 = PCURVE('',#15417,#16075); -#16075 = DEFINITIONAL_REPRESENTATION('',(#16076),#16102); -#16076 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16077,#16078,#16079,#16080, - #16081,#16082,#16083,#16084,#16085,#16086,#16087,#16088,#16089, - #16090,#16091,#16092,#16093,#16094,#16095,#16096,#16097,#16098, - #16099,#16100,#16101),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18443 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#18444 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#18445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18446 = PCURVE('',#14371,#18447); +#18447 = DEFINITIONAL_REPRESENTATION('',(#18448),#18452); +#18448 = LINE('',#18449,#18450); +#18449 = CARTESIAN_POINT('',(0.E+000,0.49)); +#18450 = VECTOR('',#18451,1.); +#18451 = DIRECTION('',(-1.,0.E+000)); +#18452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18453 = ADVANCED_FACE('',(#18454),#17809,.T.); +#18454 = FACE_BOUND('',#18455,.T.); +#18455 = EDGE_LOOP('',(#18456,#18501,#18546,#18547)); +#18456 = ORIENTED_EDGE('',*,*,#18457,.F.); +#18457 = EDGE_CURVE('',#18458,#17751,#18460,.T.); +#18458 = VERTEX_POINT('',#18459); +#18459 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); +#18460 = SURFACE_CURVE('',#18461,(#18466,#18495),.PCURVE_S1.); +#18461 = CIRCLE('',#18462,1.E-002); +#18462 = AXIS2_PLACEMENT_3D('',#18463,#18464,#18465); +#18463 = CARTESIAN_POINT('',(0.26,0.2,1.E-002)); +#18464 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#18465 = DIRECTION('',(0.E+000,0.E+000,1.)); +#18466 = PCURVE('',#17809,#18467); +#18467 = DEFINITIONAL_REPRESENTATION('',(#18468),#18494); +#18468 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18469,#18470,#18471,#18472, + #18473,#18474,#18475,#18476,#18477,#18478,#18479,#18480,#18481, + #18482,#18483,#18484,#18485,#18486,#18487,#18488,#18489,#18490, + #18491,#18492,#18493),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -19690,59 +22679,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#16077 = CARTESIAN_POINT('',(1.,0.E+000)); -#16078 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#16079 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#16080 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#16081 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#16082 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#16083 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#16084 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#16085 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#16086 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#16087 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#16088 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#16089 = CARTESIAN_POINT('',(0.5,0.E+000)); -#16090 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#16091 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#16092 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#16093 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#16094 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#16095 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#16096 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#16097 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#16098 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#16099 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#16100 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#16101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#16102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16103 = PCURVE('',#15504,#16104); -#16104 = DEFINITIONAL_REPRESENTATION('',(#16105),#16108); -#16105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16106,#16107),.UNSPECIFIED., +#18469 = CARTESIAN_POINT('',(1.,0.E+000)); +#18470 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#18471 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#18472 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#18473 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#18474 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#18475 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#18476 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#18477 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#18478 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#18479 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#18480 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#18481 = CARTESIAN_POINT('',(0.5,0.E+000)); +#18482 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#18483 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#18484 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#18485 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#18486 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#18487 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#18488 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#18489 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#18490 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#18491 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#18492 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#18493 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#18494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18495 = PCURVE('',#17896,#18496); +#18496 = DEFINITIONAL_REPRESENTATION('',(#18497),#18500); +#18497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18498,#18499),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#16106 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#16107 = CARTESIAN_POINT('',(3.14159265359,0.45)); -#16108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18498 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#18499 = CARTESIAN_POINT('',(3.14159265359,0.45)); +#18500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#16109 = ORIENTED_EDGE('',*,*,#16110,.F.); -#16110 = EDGE_CURVE('',#15998,#16066,#16111,.T.); -#16111 = SURFACE_CURVE('',#16112,(#16117,#16146),.PCURVE_S1.); -#16112 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16113,#16114,#16115,#16116), +#18501 = ORIENTED_EDGE('',*,*,#18502,.F.); +#18502 = EDGE_CURVE('',#18390,#18458,#18503,.T.); +#18503 = SURFACE_CURVE('',#18504,(#18509,#18538),.PCURVE_S1.); +#18504 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18505,#18506,#18507,#18508), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#16113 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); -#16114 = CARTESIAN_POINT('',(0.25,0.239675836708,2.79876001892E-002)); -#16115 = CARTESIAN_POINT('',(0.25,0.222819941129,1.033605546414E-002)); -#16116 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); -#16117 = PCURVE('',#15417,#16118); -#16118 = DEFINITIONAL_REPRESENTATION('',(#16119),#16145); -#16119 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16120,#16121,#16122,#16123, - #16124,#16125,#16126,#16127,#16128,#16129,#16130,#16131,#16132, - #16133,#16134,#16135,#16136,#16137,#16138,#16139,#16140,#16141, - #16142,#16143,#16144),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18505 = CARTESIAN_POINT('',(0.25,0.24,5.E-002)); +#18506 = CARTESIAN_POINT('',(0.25,0.239675836708,2.79876001892E-002)); +#18507 = CARTESIAN_POINT('',(0.25,0.222819941129,1.033605546414E-002)); +#18508 = CARTESIAN_POINT('',(0.25,0.2,1.E-002)); +#18509 = PCURVE('',#17809,#18510); +#18510 = DEFINITIONAL_REPRESENTATION('',(#18511),#18537); +#18511 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18512,#18513,#18514,#18515, + #18516,#18517,#18518,#18519,#18520,#18521,#18522,#18523,#18524, + #18525,#18526,#18527,#18528,#18529,#18530,#18531,#18532,#18533, + #18534,#18535,#18536),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -19750,76 +22739,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#16120 = CARTESIAN_POINT('',(1.,1.)); -#16121 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#16122 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#16123 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#16124 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); -#16125 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); -#16126 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#16127 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); -#16128 = CARTESIAN_POINT('',(1.000600014196,0.671375088893)); -#16129 = CARTESIAN_POINT('',(1.000606368831,0.628804305396)); -#16130 = CARTESIAN_POINT('',(1.000582476584,0.586710614224)); -#16131 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); -#16132 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); -#16133 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); -#16134 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#16135 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#16136 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#16137 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#16138 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#16139 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#16140 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#16141 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#16142 = CARTESIAN_POINT('',(1.000709884619,5.402886517652E-002)); -#16143 = CARTESIAN_POINT('',(1.000367478029,1.833200565127E-002)); -#16144 = CARTESIAN_POINT('',(1.,0.E+000)); -#16145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16146 = PCURVE('',#11979,#16147); -#16147 = DEFINITIONAL_REPRESENTATION('',(#16148),#16153); -#16148 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16149,#16150,#16151,#16152), +#18512 = CARTESIAN_POINT('',(1.,1.)); +#18513 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#18514 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#18515 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#18516 = CARTESIAN_POINT('',(1.000609112807,0.850160688084)); +#18517 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); +#18518 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#18519 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); +#18520 = CARTESIAN_POINT('',(1.000600014196,0.671375088893)); +#18521 = CARTESIAN_POINT('',(1.000606368831,0.628804305396)); +#18522 = CARTESIAN_POINT('',(1.000582476584,0.586710614224)); +#18523 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); +#18524 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); +#18525 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); +#18526 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#18527 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#18528 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#18529 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#18530 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#18531 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#18532 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#18533 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#18534 = CARTESIAN_POINT('',(1.000709884619,5.402886517652E-002)); +#18535 = CARTESIAN_POINT('',(1.000367478029,1.833200565127E-002)); +#18536 = CARTESIAN_POINT('',(1.,0.E+000)); +#18537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18538 = PCURVE('',#14371,#18539); +#18539 = DEFINITIONAL_REPRESENTATION('',(#18540),#18545); +#18540 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18541,#18542,#18543,#18544), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#16149 = CARTESIAN_POINT('',(-0.25,0.49)); -#16150 = CARTESIAN_POINT('',(-0.272012399811,0.489675836708)); -#16151 = CARTESIAN_POINT('',(-0.289663944536,0.472819941129)); -#16152 = CARTESIAN_POINT('',(-0.29,0.45)); -#16153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16154 = ORIENTED_EDGE('',*,*,#15997,.T.); -#16155 = ORIENTED_EDGE('',*,*,#15403,.T.); -#16156 = ADVANCED_FACE('',(#16157),#15504,.T.); -#16157 = FACE_BOUND('',#16158,.T.); -#16158 = EDGE_LOOP('',(#16159,#16204,#16224,#16225)); -#16159 = ORIENTED_EDGE('',*,*,#16160,.F.); -#16160 = EDGE_CURVE('',#16161,#15469,#16163,.T.); -#16161 = VERTEX_POINT('',#16162); -#16162 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); -#16163 = SURFACE_CURVE('',#16164,(#16169,#16175),.PCURVE_S1.); -#16164 = CIRCLE('',#16165,1.E-002); -#16165 = AXIS2_PLACEMENT_3D('',#16166,#16167,#16168); -#16166 = CARTESIAN_POINT('',(0.26,-0.2,1.E-002)); -#16167 = DIRECTION('',(0.E+000,-1.,1.836970198721E-016)); -#16168 = DIRECTION('',(0.E+000,-1.836970198721E-016,-1.)); -#16169 = PCURVE('',#15504,#16170); -#16170 = DEFINITIONAL_REPRESENTATION('',(#16171),#16174); -#16171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16172,#16173),.UNSPECIFIED., +#18541 = CARTESIAN_POINT('',(-0.25,0.49)); +#18542 = CARTESIAN_POINT('',(-0.272012399811,0.489675836708)); +#18543 = CARTESIAN_POINT('',(-0.289663944536,0.472819941129)); +#18544 = CARTESIAN_POINT('',(-0.29,0.45)); +#18545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18546 = ORIENTED_EDGE('',*,*,#18389,.T.); +#18547 = ORIENTED_EDGE('',*,*,#17795,.T.); +#18548 = ADVANCED_FACE('',(#18549),#17896,.T.); +#18549 = FACE_BOUND('',#18550,.T.); +#18550 = EDGE_LOOP('',(#18551,#18596,#18616,#18617)); +#18551 = ORIENTED_EDGE('',*,*,#18552,.F.); +#18552 = EDGE_CURVE('',#18553,#17861,#18555,.T.); +#18553 = VERTEX_POINT('',#18554); +#18554 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); +#18555 = SURFACE_CURVE('',#18556,(#18561,#18567),.PCURVE_S1.); +#18556 = CIRCLE('',#18557,1.E-002); +#18557 = AXIS2_PLACEMENT_3D('',#18558,#18559,#18560); +#18558 = CARTESIAN_POINT('',(0.26,-0.2,1.E-002)); +#18559 = DIRECTION('',(0.E+000,-1.,1.836970198721E-016)); +#18560 = DIRECTION('',(0.E+000,-1.836970198721E-016,-1.)); +#18561 = PCURVE('',#17896,#18562); +#18562 = DEFINITIONAL_REPRESENTATION('',(#18563),#18566); +#18563 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18564,#18565),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#16172 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#16173 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#16174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18564 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#18565 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#18566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#16175 = PCURVE('',#15579,#16176); -#16176 = DEFINITIONAL_REPRESENTATION('',(#16177),#16203); -#16177 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16178,#16179,#16180,#16181, - #16182,#16183,#16184,#16185,#16186,#16187,#16188,#16189,#16190, - #16191,#16192,#16193,#16194,#16195,#16196,#16197,#16198,#16199, - #16200,#16201,#16202),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18567 = PCURVE('',#17971,#18568); +#18568 = DEFINITIONAL_REPRESENTATION('',(#18569),#18595); +#18569 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18570,#18571,#18572,#18573, + #18574,#18575,#18576,#18577,#18578,#18579,#18580,#18581,#18582, + #18583,#18584,#18585,#18586,#18587,#18588,#18589,#18590,#18591, + #18592,#18593,#18594),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19827,80 +22816,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#16178 = CARTESIAN_POINT('',(1.,1.)); -#16179 = CARTESIAN_POINT('',(0.983172198663,1.)); -#16180 = CARTESIAN_POINT('',(0.950009297011,1.)); -#16181 = CARTESIAN_POINT('',(0.901574474096,1.)); -#16182 = CARTESIAN_POINT('',(0.854275086925,1.)); -#16183 = CARTESIAN_POINT('',(0.807956362777,1.)); -#16184 = CARTESIAN_POINT('',(0.762473275577,1.)); -#16185 = CARTESIAN_POINT('',(0.717690577461,1.)); -#16186 = CARTESIAN_POINT('',(0.673480563786,1.)); -#16187 = CARTESIAN_POINT('',(0.629721689409,1.)); -#16188 = CARTESIAN_POINT('',(0.586297147708,1.)); -#16189 = CARTESIAN_POINT('',(0.543093605115,1.)); -#16190 = CARTESIAN_POINT('',(0.5,1.)); -#16191 = CARTESIAN_POINT('',(0.456906394885,1.)); -#16192 = CARTESIAN_POINT('',(0.413702852292,1.)); -#16193 = CARTESIAN_POINT('',(0.370278310591,1.)); -#16194 = CARTESIAN_POINT('',(0.326519436214,1.)); -#16195 = CARTESIAN_POINT('',(0.282309422539,1.)); -#16196 = CARTESIAN_POINT('',(0.237526724423,1.)); -#16197 = CARTESIAN_POINT('',(0.192043637223,1.)); -#16198 = CARTESIAN_POINT('',(0.145724913075,1.)); -#16199 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#16200 = CARTESIAN_POINT('',(4.99907029888E-002,1.)); -#16201 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); -#16202 = CARTESIAN_POINT('',(0.E+000,1.)); -#16203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16204 = ORIENTED_EDGE('',*,*,#16205,.F.); -#16205 = EDGE_CURVE('',#16066,#16161,#16206,.T.); -#16206 = SURFACE_CURVE('',#16207,(#16211,#16217),.PCURVE_S1.); -#16207 = LINE('',#16208,#16209); -#16208 = CARTESIAN_POINT('',(0.25,-0.25,1.E-002)); -#16209 = VECTOR('',#16210,1.); -#16210 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#16211 = PCURVE('',#15504,#16212); -#16212 = DEFINITIONAL_REPRESENTATION('',(#16213),#16216); -#16213 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16214,#16215),.UNSPECIFIED., +#18570 = CARTESIAN_POINT('',(1.,1.)); +#18571 = CARTESIAN_POINT('',(0.983172198663,1.)); +#18572 = CARTESIAN_POINT('',(0.950009297011,1.)); +#18573 = CARTESIAN_POINT('',(0.901574474096,1.)); +#18574 = CARTESIAN_POINT('',(0.854275086925,1.)); +#18575 = CARTESIAN_POINT('',(0.807956362777,1.)); +#18576 = CARTESIAN_POINT('',(0.762473275577,1.)); +#18577 = CARTESIAN_POINT('',(0.717690577461,1.)); +#18578 = CARTESIAN_POINT('',(0.673480563786,1.)); +#18579 = CARTESIAN_POINT('',(0.629721689409,1.)); +#18580 = CARTESIAN_POINT('',(0.586297147708,1.)); +#18581 = CARTESIAN_POINT('',(0.543093605115,1.)); +#18582 = CARTESIAN_POINT('',(0.5,1.)); +#18583 = CARTESIAN_POINT('',(0.456906394885,1.)); +#18584 = CARTESIAN_POINT('',(0.413702852292,1.)); +#18585 = CARTESIAN_POINT('',(0.370278310591,1.)); +#18586 = CARTESIAN_POINT('',(0.326519436214,1.)); +#18587 = CARTESIAN_POINT('',(0.282309422539,1.)); +#18588 = CARTESIAN_POINT('',(0.237526724423,1.)); +#18589 = CARTESIAN_POINT('',(0.192043637223,1.)); +#18590 = CARTESIAN_POINT('',(0.145724913075,1.)); +#18591 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#18592 = CARTESIAN_POINT('',(4.99907029888E-002,1.)); +#18593 = CARTESIAN_POINT('',(1.682780133705E-002,1.)); +#18594 = CARTESIAN_POINT('',(0.E+000,1.)); +#18595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18596 = ORIENTED_EDGE('',*,*,#18597,.F.); +#18597 = EDGE_CURVE('',#18458,#18553,#18598,.T.); +#18598 = SURFACE_CURVE('',#18599,(#18603,#18609),.PCURVE_S1.); +#18599 = LINE('',#18600,#18601); +#18600 = CARTESIAN_POINT('',(0.25,-0.25,1.E-002)); +#18601 = VECTOR('',#18602,1.); +#18602 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#18603 = PCURVE('',#17896,#18604); +#18604 = DEFINITIONAL_REPRESENTATION('',(#18605),#18608); +#18605 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18606,#18607),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#16214 = CARTESIAN_POINT('',(4.712388980385,0.45)); -#16215 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); -#16216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16217 = PCURVE('',#11979,#16218); -#16218 = DEFINITIONAL_REPRESENTATION('',(#16219),#16223); -#16219 = LINE('',#16220,#16221); -#16220 = CARTESIAN_POINT('',(-0.29,0.E+000)); -#16221 = VECTOR('',#16222,1.); -#16222 = DIRECTION('',(0.E+000,-1.)); -#16223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16224 = ORIENTED_EDGE('',*,*,#16065,.T.); -#16225 = ORIENTED_EDGE('',*,*,#15490,.T.); -#16226 = ADVANCED_FACE('',(#16227),#15579,.T.); -#16227 = FACE_BOUND('',#16228,.T.); -#16228 = EDGE_LOOP('',(#16229,#16274,#16319,#16320)); -#16229 = ORIENTED_EDGE('',*,*,#16230,.F.); -#16230 = EDGE_CURVE('',#16231,#15521,#16233,.T.); -#16231 = VERTEX_POINT('',#16232); -#16232 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); -#16233 = SURFACE_CURVE('',#16234,(#16239,#16268),.PCURVE_S1.); -#16234 = CIRCLE('',#16235,1.E-002); -#16235 = AXIS2_PLACEMENT_3D('',#16236,#16237,#16238); -#16236 = CARTESIAN_POINT('',(0.26,-0.24,5.E-002)); -#16237 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); -#16238 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); -#16239 = PCURVE('',#15579,#16240); -#16240 = DEFINITIONAL_REPRESENTATION('',(#16241),#16267); -#16241 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16242,#16243,#16244,#16245, - #16246,#16247,#16248,#16249,#16250,#16251,#16252,#16253,#16254, - #16255,#16256,#16257,#16258,#16259,#16260,#16261,#16262,#16263, - #16264,#16265,#16266),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18606 = CARTESIAN_POINT('',(4.712388980385,0.45)); +#18607 = CARTESIAN_POINT('',(4.712388980385,5.E-002)); +#18608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18609 = PCURVE('',#14371,#18610); +#18610 = DEFINITIONAL_REPRESENTATION('',(#18611),#18615); +#18611 = LINE('',#18612,#18613); +#18612 = CARTESIAN_POINT('',(-0.29,0.E+000)); +#18613 = VECTOR('',#18614,1.); +#18614 = DIRECTION('',(0.E+000,-1.)); +#18615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18616 = ORIENTED_EDGE('',*,*,#18457,.T.); +#18617 = ORIENTED_EDGE('',*,*,#17882,.T.); +#18618 = ADVANCED_FACE('',(#18619),#17971,.T.); +#18619 = FACE_BOUND('',#18620,.T.); +#18620 = EDGE_LOOP('',(#18621,#18666,#18711,#18712)); +#18621 = ORIENTED_EDGE('',*,*,#18622,.F.); +#18622 = EDGE_CURVE('',#18623,#17913,#18625,.T.); +#18623 = VERTEX_POINT('',#18624); +#18624 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); +#18625 = SURFACE_CURVE('',#18626,(#18631,#18660),.PCURVE_S1.); +#18626 = CIRCLE('',#18627,1.E-002); +#18627 = AXIS2_PLACEMENT_3D('',#18628,#18629,#18630); +#18628 = CARTESIAN_POINT('',(0.26,-0.24,5.E-002)); +#18629 = DIRECTION('',(0.E+000,-2.69486466099E-031,1.)); +#18630 = DIRECTION('',(0.E+000,-1.,-2.69486466099E-031)); +#18631 = PCURVE('',#17971,#18632); +#18632 = DEFINITIONAL_REPRESENTATION('',(#18633),#18659); +#18633 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18634,#18635,#18636,#18637, + #18638,#18639,#18640,#18641,#18642,#18643,#18644,#18645,#18646, + #18647,#18648,#18649,#18650,#18651,#18652,#18653,#18654,#18655, + #18656,#18657,#18658),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -19908,59 +22897,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#16242 = CARTESIAN_POINT('',(1.,0.E+000)); -#16243 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#16244 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#16245 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#16246 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#16247 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#16248 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#16249 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#16250 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#16251 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#16252 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#16253 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#16254 = CARTESIAN_POINT('',(0.5,0.E+000)); -#16255 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#16256 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#16257 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#16258 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#16259 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#16260 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#16261 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#16262 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#16263 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#16264 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); -#16265 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); -#16266 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#16267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16268 = PCURVE('',#15646,#16269); -#16269 = DEFINITIONAL_REPRESENTATION('',(#16270),#16273); -#16270 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16271,#16272),.UNSPECIFIED., +#18634 = CARTESIAN_POINT('',(1.,0.E+000)); +#18635 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#18636 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#18637 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#18638 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#18639 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#18640 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#18641 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#18642 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#18643 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#18644 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#18645 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#18646 = CARTESIAN_POINT('',(0.5,0.E+000)); +#18647 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#18648 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#18649 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#18650 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#18651 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#18652 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#18653 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#18654 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#18655 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#18656 = CARTESIAN_POINT('',(4.99907029888E-002,0.E+000)); +#18657 = CARTESIAN_POINT('',(1.682780133705E-002,0.E+000)); +#18658 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#18659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18660 = PCURVE('',#18038,#18661); +#18661 = DEFINITIONAL_REPRESENTATION('',(#18662),#18665); +#18662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18663,#18664),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#16271 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16272 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#16273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#18663 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#18664 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#18665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#16274 = ORIENTED_EDGE('',*,*,#16275,.F.); -#16275 = EDGE_CURVE('',#16161,#16231,#16276,.T.); -#16276 = SURFACE_CURVE('',#16277,(#16282,#16311),.PCURVE_S1.); -#16277 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16278,#16279,#16280,#16281), +#18666 = ORIENTED_EDGE('',*,*,#18667,.F.); +#18667 = EDGE_CURVE('',#18553,#18623,#18668,.T.); +#18668 = SURFACE_CURVE('',#18669,(#18674,#18703),.PCURVE_S1.); +#18669 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18670,#18671,#18672,#18673), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#16278 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); -#16279 = CARTESIAN_POINT('',(0.25,-0.222012399811,1.032416329181E-002)); -#16280 = CARTESIAN_POINT('',(0.25,-0.239663944536,2.718005887099E-002)); -#16281 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); -#16282 = PCURVE('',#15579,#16283); -#16283 = DEFINITIONAL_REPRESENTATION('',(#16284),#16310); -#16284 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16285,#16286,#16287,#16288, - #16289,#16290,#16291,#16292,#16293,#16294,#16295,#16296,#16297, - #16298,#16299,#16300,#16301,#16302,#16303,#16304,#16305,#16306, - #16307,#16308,#16309),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18670 = CARTESIAN_POINT('',(0.25,-0.2,1.E-002)); +#18671 = CARTESIAN_POINT('',(0.25,-0.222012399811,1.032416329181E-002)); +#18672 = CARTESIAN_POINT('',(0.25,-0.239663944536,2.718005887099E-002)); +#18673 = CARTESIAN_POINT('',(0.25,-0.24,5.E-002)); +#18674 = PCURVE('',#17971,#18675); +#18675 = DEFINITIONAL_REPRESENTATION('',(#18676),#18702); +#18676 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18677,#18678,#18679,#18680, + #18681,#18682,#18683,#18684,#18685,#18686,#18687,#18688,#18689, + #18690,#18691,#18692,#18693,#18694,#18695,#18696,#18697,#18698, + #18699,#18700,#18701),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -19968,176 +22957,176 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#16285 = CARTESIAN_POINT('',(1.,1.)); -#16286 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); -#16287 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); -#16288 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); -#16289 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); -#16290 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); -#16291 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); -#16292 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); -#16293 = CARTESIAN_POINT('',(1.000600014196,0.671375088892)); -#16294 = CARTESIAN_POINT('',(1.000606368831,0.628804305402)); -#16295 = CARTESIAN_POINT('',(1.000582476584,0.586710614222)); -#16296 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); -#16297 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); -#16298 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); -#16299 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); -#16300 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); -#16301 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); -#16302 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); -#16303 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); -#16304 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); -#16305 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); -#16306 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); -#16307 = CARTESIAN_POINT('',(1.000709884619,5.402886517655E-002)); -#16308 = CARTESIAN_POINT('',(1.000367478029,1.833200565132E-002)); -#16309 = CARTESIAN_POINT('',(1.,0.E+000)); -#16310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16311 = PCURVE('',#11979,#16312); -#16312 = DEFINITIONAL_REPRESENTATION('',(#16313),#16318); -#16313 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16314,#16315,#16316,#16317), +#18677 = CARTESIAN_POINT('',(1.,1.)); +#18678 = CARTESIAN_POINT('',(1.000367478029,0.982316037696)); +#18679 = CARTESIAN_POINT('',(1.00070985715,0.947763200664)); +#18680 = CARTESIAN_POINT('',(1.000572249037,0.898063133832)); +#18681 = CARTESIAN_POINT('',(1.000609112807,0.850160688083)); +#18682 = CARTESIAN_POINT('',(1.000599265839,0.803778523429)); +#18683 = CARTESIAN_POINT('',(1.000601789944,0.758666144507)); +#18684 = CARTESIAN_POINT('',(1.000601540492,0.714599645878)); +#18685 = CARTESIAN_POINT('',(1.000600014196,0.671375088892)); +#18686 = CARTESIAN_POINT('',(1.000606368831,0.628804305402)); +#18687 = CARTESIAN_POINT('',(1.000582476584,0.586710614222)); +#18688 = CARTESIAN_POINT('',(1.000671690938,0.5449249847)); +#18689 = CARTESIAN_POINT('',(1.000081825934,0.503282378118)); +#18690 = CARTESIAN_POINT('',(0.999949652391,0.461618222945)); +#18691 = CARTESIAN_POINT('',(0.999980640293,0.419764925538)); +#18692 = CARTESIAN_POINT('',(1.000347927659,0.377548333973)); +#18693 = CARTESIAN_POINT('',(1.0006692633,0.334784072813)); +#18694 = CARTESIAN_POINT('',(1.000582985248,0.291273645863)); +#18695 = CARTESIAN_POINT('',(1.000606761815,0.246800271467)); +#18696 = CARTESIAN_POINT('',(1.000597933597,0.201124142094)); +#18697 = CARTESIAN_POINT('',(1.000609469903,0.153977795371)); +#18698 = CARTESIAN_POINT('',(1.000572152896,0.105058546912)); +#18699 = CARTESIAN_POINT('',(1.000709884619,5.402886517655E-002)); +#18700 = CARTESIAN_POINT('',(1.000367478029,1.833200565132E-002)); +#18701 = CARTESIAN_POINT('',(1.,0.E+000)); +#18702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18703 = PCURVE('',#14371,#18704); +#18704 = DEFINITIONAL_REPRESENTATION('',(#18705),#18710); +#18705 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18706,#18707,#18708,#18709), .UNSPECIFIED.,.F.,.F.,(4,4),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#16314 = CARTESIAN_POINT('',(-0.29,5.E-002)); -#16315 = CARTESIAN_POINT('',(-0.289675836708,2.79876001892E-002)); -#16316 = CARTESIAN_POINT('',(-0.272819941129,1.033605546414E-002)); -#16317 = CARTESIAN_POINT('',(-0.25,1.E-002)); -#16318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16319 = ORIENTED_EDGE('',*,*,#16160,.T.); -#16320 = ORIENTED_EDGE('',*,*,#15565,.T.); -#16321 = ADVANCED_FACE('',(#16322),#15646,.T.); -#16322 = FACE_BOUND('',#16323,.T.); -#16323 = EDGE_LOOP('',(#16324,#16325,#16345,#16346)); -#16324 = ORIENTED_EDGE('',*,*,#15691,.T.); -#16325 = ORIENTED_EDGE('',*,*,#16326,.F.); -#16326 = EDGE_CURVE('',#16231,#15692,#16327,.T.); -#16327 = SURFACE_CURVE('',#16328,(#16332,#16338),.PCURVE_S1.); -#16328 = LINE('',#16329,#16330); -#16329 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); -#16330 = VECTOR('',#16331,1.); -#16331 = DIRECTION('',(0.E+000,0.E+000,1.)); -#16332 = PCURVE('',#15646,#16333); -#16333 = DEFINITIONAL_REPRESENTATION('',(#16334),#16337); -#16334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16335,#16336),.UNSPECIFIED., +#18706 = CARTESIAN_POINT('',(-0.29,5.E-002)); +#18707 = CARTESIAN_POINT('',(-0.289675836708,2.79876001892E-002)); +#18708 = CARTESIAN_POINT('',(-0.272819941129,1.033605546414E-002)); +#18709 = CARTESIAN_POINT('',(-0.25,1.E-002)); +#18710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18711 = ORIENTED_EDGE('',*,*,#18552,.T.); +#18712 = ORIENTED_EDGE('',*,*,#17957,.T.); +#18713 = ADVANCED_FACE('',(#18714),#18038,.T.); +#18714 = FACE_BOUND('',#18715,.T.); +#18715 = EDGE_LOOP('',(#18716,#18717,#18737,#18738)); +#18716 = ORIENTED_EDGE('',*,*,#18083,.T.); +#18717 = ORIENTED_EDGE('',*,*,#18718,.F.); +#18718 = EDGE_CURVE('',#18623,#18084,#18719,.T.); +#18719 = SURFACE_CURVE('',#18720,(#18724,#18730),.PCURVE_S1.); +#18720 = LINE('',#18721,#18722); +#18721 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); +#18722 = VECTOR('',#18723,1.); +#18723 = DIRECTION('',(0.E+000,0.E+000,1.)); +#18724 = PCURVE('',#18038,#18725); +#18725 = DEFINITIONAL_REPRESENTATION('',(#18726),#18729); +#18726 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18727,#18728),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16335 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16336 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16338 = PCURVE('',#11979,#16339); -#16339 = DEFINITIONAL_REPRESENTATION('',(#16340),#16344); -#16340 = LINE('',#16341,#16342); -#16341 = CARTESIAN_POINT('',(0.E+000,1.E-002)); -#16342 = VECTOR('',#16343,1.); -#16343 = DIRECTION('',(1.,0.E+000)); -#16344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16345 = ORIENTED_EDGE('',*,*,#16230,.T.); -#16346 = ORIENTED_EDGE('',*,*,#15632,.T.); -#16347 = ADVANCED_FACE('',(#16348,#16358),#11979,.T.); -#16348 = FACE_BOUND('',#16349,.T.); -#16349 = EDGE_LOOP('',(#16350,#16351,#16352,#16353,#16354,#16355,#16356, - #16357)); -#16350 = ORIENTED_EDGE('',*,*,#16275,.T.); -#16351 = ORIENTED_EDGE('',*,*,#16326,.T.); -#16352 = ORIENTED_EDGE('',*,*,#15782,.T.); -#16353 = ORIENTED_EDGE('',*,*,#15877,.T.); -#16354 = ORIENTED_EDGE('',*,*,#15947,.T.); -#16355 = ORIENTED_EDGE('',*,*,#16042,.T.); -#16356 = ORIENTED_EDGE('',*,*,#16110,.T.); -#16357 = ORIENTED_EDGE('',*,*,#16205,.T.); -#16358 = FACE_BOUND('',#16359,.T.); -#16359 = EDGE_LOOP('',(#16360,#16361)); -#16360 = ORIENTED_EDGE('',*,*,#11963,.T.); -#16361 = ORIENTED_EDGE('',*,*,#15663,.T.); -#16362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#16366)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#16363,#16364,#16365)) +#18727 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#18728 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#18729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18730 = PCURVE('',#14371,#18731); +#18731 = DEFINITIONAL_REPRESENTATION('',(#18732),#18736); +#18732 = LINE('',#18733,#18734); +#18733 = CARTESIAN_POINT('',(0.E+000,1.E-002)); +#18734 = VECTOR('',#18735,1.); +#18735 = DIRECTION('',(1.,0.E+000)); +#18736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18737 = ORIENTED_EDGE('',*,*,#18622,.T.); +#18738 = ORIENTED_EDGE('',*,*,#18024,.T.); +#18739 = ADVANCED_FACE('',(#18740,#18750),#14371,.T.); +#18740 = FACE_BOUND('',#18741,.T.); +#18741 = EDGE_LOOP('',(#18742,#18743,#18744,#18745,#18746,#18747,#18748, + #18749)); +#18742 = ORIENTED_EDGE('',*,*,#18667,.T.); +#18743 = ORIENTED_EDGE('',*,*,#18718,.T.); +#18744 = ORIENTED_EDGE('',*,*,#18174,.T.); +#18745 = ORIENTED_EDGE('',*,*,#18269,.T.); +#18746 = ORIENTED_EDGE('',*,*,#18339,.T.); +#18747 = ORIENTED_EDGE('',*,*,#18434,.T.); +#18748 = ORIENTED_EDGE('',*,*,#18502,.T.); +#18749 = ORIENTED_EDGE('',*,*,#18597,.T.); +#18750 = FACE_BOUND('',#18751,.T.); +#18751 = EDGE_LOOP('',(#18752,#18753)); +#18752 = ORIENTED_EDGE('',*,*,#14355,.T.); +#18753 = ORIENTED_EDGE('',*,*,#18055,.T.); +#18754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#18758)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#18755,#18756,#18757)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#16363 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#16364 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#16365 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#16366 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#16363, +#18755 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#18756 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#18757 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#18758 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#18755, 'distance_accuracy_value','confusion accuracy'); -#16367 = SHAPE_DEFINITION_REPRESENTATION(#16368,#11895); -#16368 = PRODUCT_DEFINITION_SHAPE('','',#16369); -#16369 = PRODUCT_DEFINITION('design','',#16370,#16373); -#16370 = PRODUCT_DEFINITION_FORMATION('','',#16371); -#16371 = PRODUCT('User_Library-V0402HD_Anschl_X_FCsse_1', - 'User_Library-V0402HD_Anschl_X_FCsse_1','',(#16372)); -#16372 = PRODUCT_CONTEXT('',#2,'mechanical'); -#16373 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#16374 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#16375,#16377); -#16375 = ( REPRESENTATION_RELATIONSHIP('','',#11895,#11881) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#16376) +#18759 = SHAPE_DEFINITION_REPRESENTATION(#18760,#14287); +#18760 = PRODUCT_DEFINITION_SHAPE('','',#18761); +#18761 = PRODUCT_DEFINITION('design','',#18762,#18765); +#18762 = PRODUCT_DEFINITION_FORMATION('','',#18763); +#18763 = PRODUCT('User_Library-V0402HD_Anschl_X_FCsse_1', + 'User_Library-V0402HD_Anschl_X_FCsse_1','',(#18764)); +#18764 = PRODUCT_CONTEXT('',#2,'mechanical'); +#18765 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#18766 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#18767,#18769); +#18767 = ( REPRESENTATION_RELATIONSHIP('','',#14287,#14273) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#18768) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#16376 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11882); -#16377 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #16378); -#16378 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('152','','',#11876,#16369,$); -#16379 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#16371)); -#16380 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#16381),#17215); -#16381 = MANIFOLD_SOLID_BREP('',#16382); -#16382 = CLOSED_SHELL('',(#16383,#16677,#16797,#16845,#16893,#16941, - #17035,#17083,#17177,#17204)); -#16383 = ADVANCED_FACE('',(#16384),#16399,.T.); -#16384 = FACE_BOUND('',#16385,.T.); -#16385 = EDGE_LOOP('',(#16386,#16448,#16476,#16508,#16536,#16568,#16596, - #16651)); -#16386 = ORIENTED_EDGE('',*,*,#16387,.F.); -#16387 = EDGE_CURVE('',#16388,#16390,#16392,.T.); -#16388 = VERTEX_POINT('',#16389); -#16389 = CARTESIAN_POINT('',(0.25,-0.24,0.54)); -#16390 = VERTEX_POINT('',#16391); -#16391 = CARTESIAN_POINT('',(0.25,-0.19,0.59)); -#16392 = SURFACE_CURVE('',#16393,(#16398,#16414),.PCURVE_S1.); -#16393 = CIRCLE('',#16394,5.E-002); -#16394 = AXIS2_PLACEMENT_3D('',#16395,#16396,#16397); -#16395 = CARTESIAN_POINT('',(0.25,-0.19,0.54)); -#16396 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16397 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); -#16398 = PCURVE('',#16399,#16404); -#16399 = PLANE('',#16400); -#16400 = AXIS2_PLACEMENT_3D('',#16401,#16402,#16403); -#16401 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); -#16402 = DIRECTION('',(1.,0.E+000,5.024716275243E-015)); -#16403 = DIRECTION('',(5.024716275243E-015,0.E+000,-1.)); -#16404 = DEFINITIONAL_REPRESENTATION('',(#16405),#16413); -#16405 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#16406,#16407,#16408,#16409 - ,#16410,#16411,#16412),.UNSPECIFIED.,.F.,.F.) +#18768 = ITEM_DEFINED_TRANSFORMATION('','',#11,#14274); +#18769 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #18770); +#18770 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('253','','',#14268,#18761,$); +#18771 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#18763)); +#18772 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#18773),#19607); +#18773 = MANIFOLD_SOLID_BREP('',#18774); +#18774 = CLOSED_SHELL('',(#18775,#19069,#19189,#19237,#19285,#19333, + #19427,#19475,#19569,#19596)); +#18775 = ADVANCED_FACE('',(#18776),#18791,.T.); +#18776 = FACE_BOUND('',#18777,.T.); +#18777 = EDGE_LOOP('',(#18778,#18840,#18868,#18900,#18928,#18960,#18988, + #19043)); +#18778 = ORIENTED_EDGE('',*,*,#18779,.F.); +#18779 = EDGE_CURVE('',#18780,#18782,#18784,.T.); +#18780 = VERTEX_POINT('',#18781); +#18781 = CARTESIAN_POINT('',(0.25,-0.24,0.54)); +#18782 = VERTEX_POINT('',#18783); +#18783 = CARTESIAN_POINT('',(0.25,-0.19,0.59)); +#18784 = SURFACE_CURVE('',#18785,(#18790,#18806),.PCURVE_S1.); +#18785 = CIRCLE('',#18786,5.E-002); +#18786 = AXIS2_PLACEMENT_3D('',#18787,#18788,#18789); +#18787 = CARTESIAN_POINT('',(0.25,-0.19,0.54)); +#18788 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#18789 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); +#18790 = PCURVE('',#18791,#18796); +#18791 = PLANE('',#18792); +#18792 = AXIS2_PLACEMENT_3D('',#18793,#18794,#18795); +#18793 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); +#18794 = DIRECTION('',(1.,0.E+000,5.024716275243E-015)); +#18795 = DIRECTION('',(5.024716275243E-015,0.E+000,-1.)); +#18796 = DEFINITIONAL_REPRESENTATION('',(#18797),#18805); +#18797 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18798,#18799,#18800,#18801 + ,#18802,#18803,#18804),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#16406 = CARTESIAN_POINT('',(-0.29,5.E-002)); -#16407 = CARTESIAN_POINT('',(-0.29,0.136602540378)); -#16408 = CARTESIAN_POINT('',(-0.215,9.330127018922E-002)); -#16409 = CARTESIAN_POINT('',(-0.14,5.E-002)); -#16410 = CARTESIAN_POINT('',(-0.215,6.698729810778E-003)); -#16411 = CARTESIAN_POINT('',(-0.29,-3.660254037844E-002)); -#16412 = CARTESIAN_POINT('',(-0.29,5.E-002)); -#16413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16414 = PCURVE('',#16415,#16420); -#16415 = CYLINDRICAL_SURFACE('',#16416,5.E-002); -#16416 = AXIS2_PLACEMENT_3D('',#16417,#16418,#16419); -#16417 = CARTESIAN_POINT('',(6.02018435103E-015,-0.19,0.54)); -#16418 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16419 = DIRECTION('',(5.551115123126E-016,2.746118192074E-062,1.)); -#16420 = DEFINITIONAL_REPRESENTATION('',(#16421),#16447); -#16421 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16422,#16423,#16424,#16425, - #16426,#16427,#16428,#16429,#16430,#16431,#16432,#16433,#16434, - #16435,#16436,#16437,#16438,#16439,#16440,#16441,#16442,#16443, - #16444,#16445,#16446),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#18798 = CARTESIAN_POINT('',(-0.29,5.E-002)); +#18799 = CARTESIAN_POINT('',(-0.29,0.136602540378)); +#18800 = CARTESIAN_POINT('',(-0.215,9.330127018922E-002)); +#18801 = CARTESIAN_POINT('',(-0.14,5.E-002)); +#18802 = CARTESIAN_POINT('',(-0.215,6.698729810778E-003)); +#18803 = CARTESIAN_POINT('',(-0.29,-3.660254037844E-002)); +#18804 = CARTESIAN_POINT('',(-0.29,5.E-002)); +#18805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18806 = PCURVE('',#18807,#18812); +#18807 = CYLINDRICAL_SURFACE('',#18808,5.E-002); +#18808 = AXIS2_PLACEMENT_3D('',#18809,#18810,#18811); +#18809 = CARTESIAN_POINT('',(6.02018435103E-015,-0.19,0.54)); +#18810 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#18811 = DIRECTION('',(5.551115123126E-016,2.746118192074E-062,1.)); +#18812 = DEFINITIONAL_REPRESENTATION('',(#18813),#18839); +#18813 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#18814,#18815,#18816,#18817, + #18818,#18819,#18820,#18821,#18822,#18823,#18824,#18825,#18826, + #18827,#18828,#18829,#18830,#18831,#18832,#18833,#18834,#18835, + #18836,#18837,#18838),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -20145,260 +23134,260 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#16422 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16423 = CARTESIAN_POINT('',(4.73618892473,-0.25)); -#16424 = CARTESIAN_POINT('',(4.783788813421,-0.25)); -#16425 = CARTESIAN_POINT('',(4.855188646457,-0.25)); -#16426 = CARTESIAN_POINT('',(4.926588479493,-0.25)); -#16427 = CARTESIAN_POINT('',(4.997988312529,-0.25)); -#16428 = CARTESIAN_POINT('',(5.069388145565,-0.25)); -#16429 = CARTESIAN_POINT('',(5.140787978601,-0.25)); -#16430 = CARTESIAN_POINT('',(5.212187811638,-0.25)); -#16431 = CARTESIAN_POINT('',(5.283587644674,-0.25)); -#16432 = CARTESIAN_POINT('',(5.35498747771,-0.25)); -#16433 = CARTESIAN_POINT('',(5.426387310746,-0.25)); -#16434 = CARTESIAN_POINT('',(5.497787143782,-0.25)); -#16435 = CARTESIAN_POINT('',(5.569186976818,-0.25)); -#16436 = CARTESIAN_POINT('',(5.640586809854,-0.25)); -#16437 = CARTESIAN_POINT('',(5.711986642891,-0.25)); -#16438 = CARTESIAN_POINT('',(5.783386475927,-0.25)); -#16439 = CARTESIAN_POINT('',(5.854786308963,-0.25)); -#16440 = CARTESIAN_POINT('',(5.926186141999,-0.25)); -#16441 = CARTESIAN_POINT('',(5.997585975035,-0.25)); -#16442 = CARTESIAN_POINT('',(6.068985808071,-0.25)); -#16443 = CARTESIAN_POINT('',(6.140385641107,-0.25)); -#16444 = CARTESIAN_POINT('',(6.211785474143,-0.25)); -#16445 = CARTESIAN_POINT('',(6.259385362834,-0.25)); -#16446 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#16447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16448 = ORIENTED_EDGE('',*,*,#16449,.T.); -#16449 = EDGE_CURVE('',#16388,#16450,#16452,.T.); -#16450 = VERTEX_POINT('',#16451); -#16451 = CARTESIAN_POINT('',(0.25,-0.24,5.999999999999E-002)); -#16452 = SURFACE_CURVE('',#16453,(#16457,#16464),.PCURVE_S1.); -#16453 = LINE('',#16454,#16455); -#16454 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); -#16455 = VECTOR('',#16456,1.); -#16456 = DIRECTION('',(0.E+000,2.221687869544E-031,-1.)); -#16457 = PCURVE('',#16399,#16458); -#16458 = DEFINITIONAL_REPRESENTATION('',(#16459),#16463); -#16459 = LINE('',#16460,#16461); -#16460 = CARTESIAN_POINT('',(1.054711873394E-015,0.E+000)); -#16461 = VECTOR('',#16462,1.); -#16462 = DIRECTION('',(1.,2.221687869544E-031)); -#16463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16464 = PCURVE('',#16465,#16470); -#16465 = PLANE('',#16466); -#16466 = AXIS2_PLACEMENT_3D('',#16467,#16468,#16469); -#16467 = CARTESIAN_POINT('',(6.314393452556E-015,-0.24,0.3)); -#16468 = DIRECTION('',(5.1741401491E-032,1.,2.221687869544E-031)); -#16469 = DIRECTION('',(-6.873513058986E-079,-2.221687869544E-031,1.)); -#16470 = DEFINITIONAL_REPRESENTATION('',(#16471),#16475); -#16471 = LINE('',#16472,#16473); -#16472 = CARTESIAN_POINT('',(-1.718378264747E-079,0.25)); -#16473 = VECTOR('',#16474,1.); -#16474 = DIRECTION('',(-1.,-6.873513058986E-079)); -#16475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16476 = ORIENTED_EDGE('',*,*,#16477,.F.); -#16477 = EDGE_CURVE('',#16478,#16450,#16480,.T.); -#16478 = VERTEX_POINT('',#16479); -#16479 = CARTESIAN_POINT('',(0.25,-0.19,9.999999999993E-003)); -#16480 = SURFACE_CURVE('',#16481,(#16486,#16497),.PCURVE_S1.); -#16481 = CIRCLE('',#16482,5.E-002); -#16482 = AXIS2_PLACEMENT_3D('',#16483,#16484,#16485); -#16483 = CARTESIAN_POINT('',(0.25,-0.19,5.999999999999E-002)); -#16484 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); -#16485 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); -#16486 = PCURVE('',#16399,#16487); -#16487 = DEFINITIONAL_REPRESENTATION('',(#16488),#16496); -#16488 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#16489,#16490,#16491,#16492 - ,#16493,#16494,#16495),.UNSPECIFIED.,.T.,.F.) +#18814 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#18815 = CARTESIAN_POINT('',(4.73618892473,-0.25)); +#18816 = CARTESIAN_POINT('',(4.783788813421,-0.25)); +#18817 = CARTESIAN_POINT('',(4.855188646457,-0.25)); +#18818 = CARTESIAN_POINT('',(4.926588479493,-0.25)); +#18819 = CARTESIAN_POINT('',(4.997988312529,-0.25)); +#18820 = CARTESIAN_POINT('',(5.069388145565,-0.25)); +#18821 = CARTESIAN_POINT('',(5.140787978601,-0.25)); +#18822 = CARTESIAN_POINT('',(5.212187811638,-0.25)); +#18823 = CARTESIAN_POINT('',(5.283587644674,-0.25)); +#18824 = CARTESIAN_POINT('',(5.35498747771,-0.25)); +#18825 = CARTESIAN_POINT('',(5.426387310746,-0.25)); +#18826 = CARTESIAN_POINT('',(5.497787143782,-0.25)); +#18827 = CARTESIAN_POINT('',(5.569186976818,-0.25)); +#18828 = CARTESIAN_POINT('',(5.640586809854,-0.25)); +#18829 = CARTESIAN_POINT('',(5.711986642891,-0.25)); +#18830 = CARTESIAN_POINT('',(5.783386475927,-0.25)); +#18831 = CARTESIAN_POINT('',(5.854786308963,-0.25)); +#18832 = CARTESIAN_POINT('',(5.926186141999,-0.25)); +#18833 = CARTESIAN_POINT('',(5.997585975035,-0.25)); +#18834 = CARTESIAN_POINT('',(6.068985808071,-0.25)); +#18835 = CARTESIAN_POINT('',(6.140385641107,-0.25)); +#18836 = CARTESIAN_POINT('',(6.211785474143,-0.25)); +#18837 = CARTESIAN_POINT('',(6.259385362834,-0.25)); +#18838 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#18839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18840 = ORIENTED_EDGE('',*,*,#18841,.T.); +#18841 = EDGE_CURVE('',#18780,#18842,#18844,.T.); +#18842 = VERTEX_POINT('',#18843); +#18843 = CARTESIAN_POINT('',(0.25,-0.24,5.999999999999E-002)); +#18844 = SURFACE_CURVE('',#18845,(#18849,#18856),.PCURVE_S1.); +#18845 = LINE('',#18846,#18847); +#18846 = CARTESIAN_POINT('',(0.25,-0.24,0.3)); +#18847 = VECTOR('',#18848,1.); +#18848 = DIRECTION('',(0.E+000,2.221687869544E-031,-1.)); +#18849 = PCURVE('',#18791,#18850); +#18850 = DEFINITIONAL_REPRESENTATION('',(#18851),#18855); +#18851 = LINE('',#18852,#18853); +#18852 = CARTESIAN_POINT('',(1.054711873394E-015,0.E+000)); +#18853 = VECTOR('',#18854,1.); +#18854 = DIRECTION('',(1.,2.221687869544E-031)); +#18855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18856 = PCURVE('',#18857,#18862); +#18857 = PLANE('',#18858); +#18858 = AXIS2_PLACEMENT_3D('',#18859,#18860,#18861); +#18859 = CARTESIAN_POINT('',(6.314393452556E-015,-0.24,0.3)); +#18860 = DIRECTION('',(5.1741401491E-032,1.,2.221687869544E-031)); +#18861 = DIRECTION('',(-6.873513058986E-079,-2.221687869544E-031,1.)); +#18862 = DEFINITIONAL_REPRESENTATION('',(#18863),#18867); +#18863 = LINE('',#18864,#18865); +#18864 = CARTESIAN_POINT('',(-1.718378264747E-079,0.25)); +#18865 = VECTOR('',#18866,1.); +#18866 = DIRECTION('',(-1.,-6.873513058986E-079)); +#18867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18868 = ORIENTED_EDGE('',*,*,#18869,.F.); +#18869 = EDGE_CURVE('',#18870,#18842,#18872,.T.); +#18870 = VERTEX_POINT('',#18871); +#18871 = CARTESIAN_POINT('',(0.25,-0.19,9.999999999993E-003)); +#18872 = SURFACE_CURVE('',#18873,(#18878,#18889),.PCURVE_S1.); +#18873 = CIRCLE('',#18874,5.E-002); +#18874 = AXIS2_PLACEMENT_3D('',#18875,#18876,#18877); +#18875 = CARTESIAN_POINT('',(0.25,-0.19,5.999999999999E-002)); +#18876 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); +#18877 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); +#18878 = PCURVE('',#18791,#18879); +#18879 = DEFINITIONAL_REPRESENTATION('',(#18880),#18888); +#18880 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18881,#18882,#18883,#18884 + ,#18885,#18886,#18887),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#16489 = CARTESIAN_POINT('',(0.29,5.E-002)); -#16490 = CARTESIAN_POINT('',(0.29,-3.660254037844E-002)); -#16491 = CARTESIAN_POINT('',(0.215,6.698729810778E-003)); -#16492 = CARTESIAN_POINT('',(0.14,5.E-002)); -#16493 = CARTESIAN_POINT('',(0.215,9.330127018922E-002)); -#16494 = CARTESIAN_POINT('',(0.29,0.136602540378)); -#16495 = CARTESIAN_POINT('',(0.29,5.E-002)); -#16496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16497 = PCURVE('',#16498,#16503); -#16498 = CYLINDRICAL_SURFACE('',#16499,5.E-002); -#16499 = AXIS2_PLACEMENT_3D('',#16500,#16501,#16502); -#16500 = CARTESIAN_POINT('',(6.72940436014E-015,-0.19, +#18881 = CARTESIAN_POINT('',(0.29,5.E-002)); +#18882 = CARTESIAN_POINT('',(0.29,-3.660254037844E-002)); +#18883 = CARTESIAN_POINT('',(0.215,6.698729810778E-003)); +#18884 = CARTESIAN_POINT('',(0.14,5.E-002)); +#18885 = CARTESIAN_POINT('',(0.215,9.330127018922E-002)); +#18886 = CARTESIAN_POINT('',(0.29,0.136602540378)); +#18887 = CARTESIAN_POINT('',(0.29,5.E-002)); +#18888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18889 = PCURVE('',#18890,#18895); +#18890 = CYLINDRICAL_SURFACE('',#18891,5.E-002); +#18891 = AXIS2_PLACEMENT_3D('',#18892,#18893,#18894); +#18892 = CARTESIAN_POINT('',(6.72940436014E-015,-0.19, 5.999999999999E-002)); -#16501 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); -#16502 = DIRECTION('',(3.512815038853E-016,1.394068039674E-062,-1.)); -#16503 = DEFINITIONAL_REPRESENTATION('',(#16504),#16507); -#16504 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16505,#16506),.UNSPECIFIED., +#18893 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); +#18894 = DIRECTION('',(3.512815038853E-016,1.394068039674E-062,-1.)); +#18895 = DEFINITIONAL_REPRESENTATION('',(#18896),#18899); +#18896 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18897,#18898),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#16505 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#16506 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16508 = ORIENTED_EDGE('',*,*,#16509,.F.); -#16509 = EDGE_CURVE('',#16510,#16478,#16512,.T.); -#16510 = VERTEX_POINT('',#16511); -#16511 = CARTESIAN_POINT('',(0.25,0.19,9.999999999993E-003)); -#16512 = SURFACE_CURVE('',#16513,(#16517,#16524),.PCURVE_S1.); -#16513 = LINE('',#16514,#16515); -#16514 = CARTESIAN_POINT('',(0.25,-0.24,9.999999999993E-003)); -#16515 = VECTOR('',#16516,1.); -#16516 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#16517 = PCURVE('',#16399,#16518); -#16518 = DEFINITIONAL_REPRESENTATION('',(#16519),#16523); -#16519 = LINE('',#16520,#16521); -#16520 = CARTESIAN_POINT('',(0.29,0.E+000)); -#16521 = VECTOR('',#16522,1.); -#16522 = DIRECTION('',(0.E+000,-1.)); -#16523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16524 = PCURVE('',#16525,#16530); -#16525 = PLANE('',#16526); -#16526 = AXIS2_PLACEMENT_3D('',#16527,#16528,#16529); -#16527 = CARTESIAN_POINT('',(7.077671781985E-015,-0.24, +#18897 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#18898 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#18899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18900 = ORIENTED_EDGE('',*,*,#18901,.F.); +#18901 = EDGE_CURVE('',#18902,#18870,#18904,.T.); +#18902 = VERTEX_POINT('',#18903); +#18903 = CARTESIAN_POINT('',(0.25,0.19,9.999999999993E-003)); +#18904 = SURFACE_CURVE('',#18905,(#18909,#18916),.PCURVE_S1.); +#18905 = LINE('',#18906,#18907); +#18906 = CARTESIAN_POINT('',(0.25,-0.24,9.999999999993E-003)); +#18907 = VECTOR('',#18908,1.); +#18908 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#18909 = PCURVE('',#18791,#18910); +#18910 = DEFINITIONAL_REPRESENTATION('',(#18911),#18915); +#18911 = LINE('',#18912,#18913); +#18912 = CARTESIAN_POINT('',(0.29,0.E+000)); +#18913 = VECTOR('',#18914,1.); +#18914 = DIRECTION('',(0.E+000,-1.)); +#18915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18916 = PCURVE('',#18917,#18922); +#18917 = PLANE('',#18918); +#18918 = AXIS2_PLACEMENT_3D('',#18919,#18920,#18921); +#18919 = CARTESIAN_POINT('',(7.077671781985E-015,-0.24, 9.999999999993E-003)); -#16528 = DIRECTION('',(3.512815038853E-016,0.E+000,-1.)); -#16529 = DIRECTION('',(-1.,0.E+000,-3.512815038853E-016)); -#16530 = DEFINITIONAL_REPRESENTATION('',(#16531),#16535); -#16531 = LINE('',#16532,#16533); -#16532 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#16533 = VECTOR('',#16534,1.); -#16534 = DIRECTION('',(0.E+000,-1.)); -#16535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16536 = ORIENTED_EDGE('',*,*,#16537,.F.); -#16537 = EDGE_CURVE('',#16538,#16510,#16540,.T.); -#16538 = VERTEX_POINT('',#16539); -#16539 = CARTESIAN_POINT('',(0.25,0.24,5.999999999999E-002)); -#16540 = SURFACE_CURVE('',#16541,(#16546,#16557),.PCURVE_S1.); -#16541 = CIRCLE('',#16542,5.E-002); -#16542 = AXIS2_PLACEMENT_3D('',#16543,#16544,#16545); -#16543 = CARTESIAN_POINT('',(0.25,0.19,5.999999999999E-002)); -#16544 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); -#16545 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); -#16546 = PCURVE('',#16399,#16547); -#16547 = DEFINITIONAL_REPRESENTATION('',(#16548),#16556); -#16548 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#16549,#16550,#16551,#16552 - ,#16553,#16554,#16555),.UNSPECIFIED.,.T.,.F.) +#18920 = DIRECTION('',(3.512815038853E-016,0.E+000,-1.)); +#18921 = DIRECTION('',(-1.,0.E+000,-3.512815038853E-016)); +#18922 = DEFINITIONAL_REPRESENTATION('',(#18923),#18927); +#18923 = LINE('',#18924,#18925); +#18924 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#18925 = VECTOR('',#18926,1.); +#18926 = DIRECTION('',(0.E+000,-1.)); +#18927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18928 = ORIENTED_EDGE('',*,*,#18929,.F.); +#18929 = EDGE_CURVE('',#18930,#18902,#18932,.T.); +#18930 = VERTEX_POINT('',#18931); +#18931 = CARTESIAN_POINT('',(0.25,0.24,5.999999999999E-002)); +#18932 = SURFACE_CURVE('',#18933,(#18938,#18949),.PCURVE_S1.); +#18933 = CIRCLE('',#18934,5.E-002); +#18934 = AXIS2_PLACEMENT_3D('',#18935,#18936,#18937); +#18935 = CARTESIAN_POINT('',(0.25,0.19,5.999999999999E-002)); +#18936 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); +#18937 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); +#18938 = PCURVE('',#18791,#18939); +#18939 = DEFINITIONAL_REPRESENTATION('',(#18940),#18948); +#18940 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18941,#18942,#18943,#18944 + ,#18945,#18946,#18947),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#16549 = CARTESIAN_POINT('',(0.29,0.43)); -#16550 = CARTESIAN_POINT('',(0.29,0.343397459622)); -#16551 = CARTESIAN_POINT('',(0.215,0.386698729811)); -#16552 = CARTESIAN_POINT('',(0.14,0.43)); -#16553 = CARTESIAN_POINT('',(0.215,0.473301270189)); -#16554 = CARTESIAN_POINT('',(0.29,0.516602540378)); -#16555 = CARTESIAN_POINT('',(0.29,0.43)); -#16556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16557 = PCURVE('',#16558,#16563); -#16558 = CYLINDRICAL_SURFACE('',#16559,5.E-002); -#16559 = AXIS2_PLACEMENT_3D('',#16560,#16561,#16562); -#16560 = CARTESIAN_POINT('',(6.72940436014E-015,0.19,5.999999999999E-002 +#18941 = CARTESIAN_POINT('',(0.29,0.43)); +#18942 = CARTESIAN_POINT('',(0.29,0.343397459622)); +#18943 = CARTESIAN_POINT('',(0.215,0.386698729811)); +#18944 = CARTESIAN_POINT('',(0.14,0.43)); +#18945 = CARTESIAN_POINT('',(0.215,0.473301270189)); +#18946 = CARTESIAN_POINT('',(0.29,0.516602540378)); +#18947 = CARTESIAN_POINT('',(0.29,0.43)); +#18948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18949 = PCURVE('',#18950,#18955); +#18950 = CYLINDRICAL_SURFACE('',#18951,5.E-002); +#18951 = AXIS2_PLACEMENT_3D('',#18952,#18953,#18954); +#18952 = CARTESIAN_POINT('',(6.72940436014E-015,0.19,5.999999999999E-002 )); -#16561 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); -#16562 = DIRECTION('',(3.512815038853E-016,1.394068039674E-062,-1.)); -#16563 = DEFINITIONAL_REPRESENTATION('',(#16564),#16567); -#16564 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16565,#16566),.UNSPECIFIED., +#18953 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); +#18954 = DIRECTION('',(3.512815038853E-016,1.394068039674E-062,-1.)); +#18955 = DEFINITIONAL_REPRESENTATION('',(#18956),#18959); +#18956 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18957,#18958),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#16565 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#16566 = CARTESIAN_POINT('',(0.E+000,0.25)); -#16567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16568 = ORIENTED_EDGE('',*,*,#16569,.F.); -#16569 = EDGE_CURVE('',#16570,#16538,#16572,.T.); -#16570 = VERTEX_POINT('',#16571); -#16571 = CARTESIAN_POINT('',(0.25,0.24,0.54)); -#16572 = SURFACE_CURVE('',#16573,(#16577,#16584),.PCURVE_S1.); -#16573 = LINE('',#16574,#16575); -#16574 = CARTESIAN_POINT('',(0.25,0.24,0.3)); -#16575 = VECTOR('',#16576,1.); -#16576 = DIRECTION('',(0.E+000,2.221687869544E-031,-1.)); -#16577 = PCURVE('',#16399,#16578); -#16578 = DEFINITIONAL_REPRESENTATION('',(#16579),#16583); -#16579 = LINE('',#16580,#16581); -#16580 = CARTESIAN_POINT('',(1.054711873394E-015,0.48)); -#16581 = VECTOR('',#16582,1.); -#16582 = DIRECTION('',(1.,2.221687869544E-031)); -#16583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16584 = PCURVE('',#16585,#16590); -#16585 = PLANE('',#16586); -#16586 = AXIS2_PLACEMENT_3D('',#16587,#16588,#16589); -#16587 = CARTESIAN_POINT('',(6.314393452556E-015,0.24,0.3)); -#16588 = DIRECTION('',(5.1741401491E-032,1.,2.221687869544E-031)); -#16589 = DIRECTION('',(-6.873513058986E-079,-2.221687869544E-031,1.)); -#16590 = DEFINITIONAL_REPRESENTATION('',(#16591),#16595); -#16591 = LINE('',#16592,#16593); -#16592 = CARTESIAN_POINT('',(-1.718378264747E-079,0.25)); -#16593 = VECTOR('',#16594,1.); -#16594 = DIRECTION('',(-1.,-6.873513058986E-079)); -#16595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16596 = ORIENTED_EDGE('',*,*,#16597,.F.); -#16597 = EDGE_CURVE('',#16598,#16570,#16600,.T.); -#16598 = VERTEX_POINT('',#16599); -#16599 = CARTESIAN_POINT('',(0.25,0.19,0.59)); -#16600 = SURFACE_CURVE('',#16601,(#16606,#16617),.PCURVE_S1.); -#16601 = CIRCLE('',#16602,5.E-002); -#16602 = AXIS2_PLACEMENT_3D('',#16603,#16604,#16605); -#16603 = CARTESIAN_POINT('',(0.25,0.19,0.54)); -#16604 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16605 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); -#16606 = PCURVE('',#16399,#16607); -#16607 = DEFINITIONAL_REPRESENTATION('',(#16608),#16616); -#16608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#16609,#16610,#16611,#16612 - ,#16613,#16614,#16615),.UNSPECIFIED.,.T.,.F.) +#18957 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#18958 = CARTESIAN_POINT('',(0.E+000,0.25)); +#18959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18960 = ORIENTED_EDGE('',*,*,#18961,.F.); +#18961 = EDGE_CURVE('',#18962,#18930,#18964,.T.); +#18962 = VERTEX_POINT('',#18963); +#18963 = CARTESIAN_POINT('',(0.25,0.24,0.54)); +#18964 = SURFACE_CURVE('',#18965,(#18969,#18976),.PCURVE_S1.); +#18965 = LINE('',#18966,#18967); +#18966 = CARTESIAN_POINT('',(0.25,0.24,0.3)); +#18967 = VECTOR('',#18968,1.); +#18968 = DIRECTION('',(0.E+000,2.221687869544E-031,-1.)); +#18969 = PCURVE('',#18791,#18970); +#18970 = DEFINITIONAL_REPRESENTATION('',(#18971),#18975); +#18971 = LINE('',#18972,#18973); +#18972 = CARTESIAN_POINT('',(1.054711873394E-015,0.48)); +#18973 = VECTOR('',#18974,1.); +#18974 = DIRECTION('',(1.,2.221687869544E-031)); +#18975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18976 = PCURVE('',#18977,#18982); +#18977 = PLANE('',#18978); +#18978 = AXIS2_PLACEMENT_3D('',#18979,#18980,#18981); +#18979 = CARTESIAN_POINT('',(6.314393452556E-015,0.24,0.3)); +#18980 = DIRECTION('',(5.1741401491E-032,1.,2.221687869544E-031)); +#18981 = DIRECTION('',(-6.873513058986E-079,-2.221687869544E-031,1.)); +#18982 = DEFINITIONAL_REPRESENTATION('',(#18983),#18987); +#18983 = LINE('',#18984,#18985); +#18984 = CARTESIAN_POINT('',(-1.718378264747E-079,0.25)); +#18985 = VECTOR('',#18986,1.); +#18986 = DIRECTION('',(-1.,-6.873513058986E-079)); +#18987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#18988 = ORIENTED_EDGE('',*,*,#18989,.F.); +#18989 = EDGE_CURVE('',#18990,#18962,#18992,.T.); +#18990 = VERTEX_POINT('',#18991); +#18991 = CARTESIAN_POINT('',(0.25,0.19,0.59)); +#18992 = SURFACE_CURVE('',#18993,(#18998,#19009),.PCURVE_S1.); +#18993 = CIRCLE('',#18994,5.E-002); +#18994 = AXIS2_PLACEMENT_3D('',#18995,#18996,#18997); +#18995 = CARTESIAN_POINT('',(0.25,0.19,0.54)); +#18996 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#18997 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); +#18998 = PCURVE('',#18791,#18999); +#18999 = DEFINITIONAL_REPRESENTATION('',(#19000),#19008); +#19000 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#19001,#19002,#19003,#19004 + ,#19005,#19006,#19007),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#16609 = CARTESIAN_POINT('',(-0.29,0.43)); -#16610 = CARTESIAN_POINT('',(-0.29,0.516602540378)); -#16611 = CARTESIAN_POINT('',(-0.215,0.473301270189)); -#16612 = CARTESIAN_POINT('',(-0.14,0.43)); -#16613 = CARTESIAN_POINT('',(-0.215,0.386698729811)); -#16614 = CARTESIAN_POINT('',(-0.29,0.343397459622)); -#16615 = CARTESIAN_POINT('',(-0.29,0.43)); -#16616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16617 = PCURVE('',#16618,#16623); -#16618 = CYLINDRICAL_SURFACE('',#16619,5.E-002); -#16619 = AXIS2_PLACEMENT_3D('',#16620,#16621,#16622); -#16620 = CARTESIAN_POINT('',(6.02018435103E-015,0.19,0.54)); -#16621 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16622 = DIRECTION('',(5.551115123126E-016,2.746118192074E-062,1.)); -#16623 = DEFINITIONAL_REPRESENTATION('',(#16624),#16650); -#16624 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16625,#16626,#16627,#16628, - #16629,#16630,#16631,#16632,#16633,#16634,#16635,#16636,#16637, - #16638,#16639,#16640,#16641,#16642,#16643,#16644,#16645,#16646, - #16647,#16648,#16649),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19001 = CARTESIAN_POINT('',(-0.29,0.43)); +#19002 = CARTESIAN_POINT('',(-0.29,0.516602540378)); +#19003 = CARTESIAN_POINT('',(-0.215,0.473301270189)); +#19004 = CARTESIAN_POINT('',(-0.14,0.43)); +#19005 = CARTESIAN_POINT('',(-0.215,0.386698729811)); +#19006 = CARTESIAN_POINT('',(-0.29,0.343397459622)); +#19007 = CARTESIAN_POINT('',(-0.29,0.43)); +#19008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19009 = PCURVE('',#19010,#19015); +#19010 = CYLINDRICAL_SURFACE('',#19011,5.E-002); +#19011 = AXIS2_PLACEMENT_3D('',#19012,#19013,#19014); +#19012 = CARTESIAN_POINT('',(6.02018435103E-015,0.19,0.54)); +#19013 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#19014 = DIRECTION('',(5.551115123126E-016,2.746118192074E-062,1.)); +#19015 = DEFINITIONAL_REPRESENTATION('',(#19016),#19042); +#19016 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19017,#19018,#19019,#19020, + #19021,#19022,#19023,#19024,#19025,#19026,#19027,#19028,#19029, + #19030,#19031,#19032,#19033,#19034,#19035,#19036,#19037,#19038, + #19039,#19040,#19041),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -20406,85 +23395,85 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827686,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#16625 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#16626 = CARTESIAN_POINT('',(2.379994434538E-002,-0.25)); -#16627 = CARTESIAN_POINT('',(7.139983303613E-002,-0.25)); -#16628 = CARTESIAN_POINT('',(0.142799666072,-0.25)); -#16629 = CARTESIAN_POINT('',(0.214199499108,-0.25)); -#16630 = CARTESIAN_POINT('',(0.285599332145,-0.25)); -#16631 = CARTESIAN_POINT('',(0.356999165181,-0.25)); -#16632 = CARTESIAN_POINT('',(0.428398998217,-0.25)); -#16633 = CARTESIAN_POINT('',(0.499798831253,-0.25)); -#16634 = CARTESIAN_POINT('',(0.571198664289,-0.25)); -#16635 = CARTESIAN_POINT('',(0.642598497325,-0.25)); -#16636 = CARTESIAN_POINT('',(0.713998330361,-0.25)); -#16637 = CARTESIAN_POINT('',(0.785398163397,-0.25)); -#16638 = CARTESIAN_POINT('',(0.856797996434,-0.25)); -#16639 = CARTESIAN_POINT('',(0.92819782947,-0.25)); -#16640 = CARTESIAN_POINT('',(0.999597662506,-0.25)); -#16641 = CARTESIAN_POINT('',(1.070997495542,-0.25)); -#16642 = CARTESIAN_POINT('',(1.142397328578,-0.25)); -#16643 = CARTESIAN_POINT('',(1.213797161614,-0.25)); -#16644 = CARTESIAN_POINT('',(1.28519699465,-0.25)); -#16645 = CARTESIAN_POINT('',(1.356596827686,-0.25)); -#16646 = CARTESIAN_POINT('',(1.427996660723,-0.25)); -#16647 = CARTESIAN_POINT('',(1.499396493759,-0.25)); -#16648 = CARTESIAN_POINT('',(1.54699638245,-0.25)); -#16649 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#16650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16651 = ORIENTED_EDGE('',*,*,#16652,.F.); -#16652 = EDGE_CURVE('',#16390,#16598,#16653,.T.); -#16653 = SURFACE_CURVE('',#16654,(#16658,#16665),.PCURVE_S1.); -#16654 = LINE('',#16655,#16656); -#16655 = CARTESIAN_POINT('',(0.25,-0.24,0.59)); -#16656 = VECTOR('',#16657,1.); -#16657 = DIRECTION('',(0.E+000,1.,0.E+000)); -#16658 = PCURVE('',#16399,#16659); -#16659 = DEFINITIONAL_REPRESENTATION('',(#16660),#16664); -#16660 = LINE('',#16661,#16662); -#16661 = CARTESIAN_POINT('',(-0.29,0.E+000)); -#16662 = VECTOR('',#16663,1.); -#16663 = DIRECTION('',(0.E+000,1.)); -#16664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16665 = PCURVE('',#16666,#16671); -#16666 = PLANE('',#16667); -#16667 = AXIS2_PLACEMENT_3D('',#16668,#16669,#16670); -#16668 = CARTESIAN_POINT('',(5.620504062165E-015,-0.24,0.59)); -#16669 = DIRECTION('',(5.551115123126E-016,0.E+000,1.)); -#16670 = DIRECTION('',(1.,0.E+000,-5.551115123126E-016)); -#16671 = DEFINITIONAL_REPRESENTATION('',(#16672),#16676); -#16672 = LINE('',#16673,#16674); -#16673 = CARTESIAN_POINT('',(0.25,0.E+000)); -#16674 = VECTOR('',#16675,1.); -#16675 = DIRECTION('',(0.E+000,1.)); -#16676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16677 = ADVANCED_FACE('',(#16678),#16498,.T.); -#16678 = FACE_BOUND('',#16679,.T.); -#16679 = EDGE_LOOP('',(#16680,#16733,#16753,#16754)); -#16680 = ORIENTED_EDGE('',*,*,#16681,.F.); -#16681 = EDGE_CURVE('',#16682,#16684,#16686,.T.); -#16682 = VERTEX_POINT('',#16683); -#16683 = CARTESIAN_POINT('',(-0.25,-0.19,9.999999999993E-003)); -#16684 = VERTEX_POINT('',#16685); -#16685 = CARTESIAN_POINT('',(-0.25,-0.24,5.999999999999E-002)); -#16686 = SURFACE_CURVE('',#16687,(#16692,#16721),.PCURVE_S1.); -#16687 = CIRCLE('',#16688,5.E-002); -#16688 = AXIS2_PLACEMENT_3D('',#16689,#16690,#16691); -#16689 = CARTESIAN_POINT('',(-0.25,-0.19,5.999999999999E-002)); -#16690 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); -#16691 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); -#16692 = PCURVE('',#16498,#16693); -#16693 = DEFINITIONAL_REPRESENTATION('',(#16694),#16720); -#16694 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16695,#16696,#16697,#16698, - #16699,#16700,#16701,#16702,#16703,#16704,#16705,#16706,#16707, - #16708,#16709,#16710,#16711,#16712,#16713,#16714,#16715,#16716, - #16717,#16718,#16719),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19017 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#19018 = CARTESIAN_POINT('',(2.379994434538E-002,-0.25)); +#19019 = CARTESIAN_POINT('',(7.139983303613E-002,-0.25)); +#19020 = CARTESIAN_POINT('',(0.142799666072,-0.25)); +#19021 = CARTESIAN_POINT('',(0.214199499108,-0.25)); +#19022 = CARTESIAN_POINT('',(0.285599332145,-0.25)); +#19023 = CARTESIAN_POINT('',(0.356999165181,-0.25)); +#19024 = CARTESIAN_POINT('',(0.428398998217,-0.25)); +#19025 = CARTESIAN_POINT('',(0.499798831253,-0.25)); +#19026 = CARTESIAN_POINT('',(0.571198664289,-0.25)); +#19027 = CARTESIAN_POINT('',(0.642598497325,-0.25)); +#19028 = CARTESIAN_POINT('',(0.713998330361,-0.25)); +#19029 = CARTESIAN_POINT('',(0.785398163397,-0.25)); +#19030 = CARTESIAN_POINT('',(0.856797996434,-0.25)); +#19031 = CARTESIAN_POINT('',(0.92819782947,-0.25)); +#19032 = CARTESIAN_POINT('',(0.999597662506,-0.25)); +#19033 = CARTESIAN_POINT('',(1.070997495542,-0.25)); +#19034 = CARTESIAN_POINT('',(1.142397328578,-0.25)); +#19035 = CARTESIAN_POINT('',(1.213797161614,-0.25)); +#19036 = CARTESIAN_POINT('',(1.28519699465,-0.25)); +#19037 = CARTESIAN_POINT('',(1.356596827686,-0.25)); +#19038 = CARTESIAN_POINT('',(1.427996660723,-0.25)); +#19039 = CARTESIAN_POINT('',(1.499396493759,-0.25)); +#19040 = CARTESIAN_POINT('',(1.54699638245,-0.25)); +#19041 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#19042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19043 = ORIENTED_EDGE('',*,*,#19044,.F.); +#19044 = EDGE_CURVE('',#18782,#18990,#19045,.T.); +#19045 = SURFACE_CURVE('',#19046,(#19050,#19057),.PCURVE_S1.); +#19046 = LINE('',#19047,#19048); +#19047 = CARTESIAN_POINT('',(0.25,-0.24,0.59)); +#19048 = VECTOR('',#19049,1.); +#19049 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19050 = PCURVE('',#18791,#19051); +#19051 = DEFINITIONAL_REPRESENTATION('',(#19052),#19056); +#19052 = LINE('',#19053,#19054); +#19053 = CARTESIAN_POINT('',(-0.29,0.E+000)); +#19054 = VECTOR('',#19055,1.); +#19055 = DIRECTION('',(0.E+000,1.)); +#19056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19057 = PCURVE('',#19058,#19063); +#19058 = PLANE('',#19059); +#19059 = AXIS2_PLACEMENT_3D('',#19060,#19061,#19062); +#19060 = CARTESIAN_POINT('',(5.620504062165E-015,-0.24,0.59)); +#19061 = DIRECTION('',(5.551115123126E-016,0.E+000,1.)); +#19062 = DIRECTION('',(1.,0.E+000,-5.551115123126E-016)); +#19063 = DEFINITIONAL_REPRESENTATION('',(#19064),#19068); +#19064 = LINE('',#19065,#19066); +#19065 = CARTESIAN_POINT('',(0.25,0.E+000)); +#19066 = VECTOR('',#19067,1.); +#19067 = DIRECTION('',(0.E+000,1.)); +#19068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19069 = ADVANCED_FACE('',(#19070),#18890,.T.); +#19070 = FACE_BOUND('',#19071,.T.); +#19071 = EDGE_LOOP('',(#19072,#19125,#19145,#19146)); +#19072 = ORIENTED_EDGE('',*,*,#19073,.F.); +#19073 = EDGE_CURVE('',#19074,#19076,#19078,.T.); +#19074 = VERTEX_POINT('',#19075); +#19075 = CARTESIAN_POINT('',(-0.25,-0.19,9.999999999993E-003)); +#19076 = VERTEX_POINT('',#19077); +#19077 = CARTESIAN_POINT('',(-0.25,-0.24,5.999999999999E-002)); +#19078 = SURFACE_CURVE('',#19079,(#19084,#19113),.PCURVE_S1.); +#19079 = CIRCLE('',#19080,5.E-002); +#19080 = AXIS2_PLACEMENT_3D('',#19081,#19082,#19083); +#19081 = CARTESIAN_POINT('',(-0.25,-0.19,5.999999999999E-002)); +#19082 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); +#19083 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); +#19084 = PCURVE('',#18890,#19085); +#19085 = DEFINITIONAL_REPRESENTATION('',(#19086),#19112); +#19086 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19087,#19088,#19089,#19090, + #19091,#19092,#19093,#19094,#19095,#19096,#19097,#19098,#19099, + #19100,#19101,#19102,#19103,#19104,#19105,#19106,#19107,#19108, + #19109,#19110,#19111),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -20492,89 +23481,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#16695 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#16696 = CARTESIAN_POINT('',(6.259385362834,-0.25)); -#16697 = CARTESIAN_POINT('',(6.211785474143,-0.25)); -#16698 = CARTESIAN_POINT('',(6.140385641107,-0.25)); -#16699 = CARTESIAN_POINT('',(6.068985808071,-0.25)); -#16700 = CARTESIAN_POINT('',(5.997585975035,-0.25)); -#16701 = CARTESIAN_POINT('',(5.926186141999,-0.25)); -#16702 = CARTESIAN_POINT('',(5.854786308963,-0.25)); -#16703 = CARTESIAN_POINT('',(5.783386475927,-0.25)); -#16704 = CARTESIAN_POINT('',(5.711986642891,-0.25)); -#16705 = CARTESIAN_POINT('',(5.640586809854,-0.25)); -#16706 = CARTESIAN_POINT('',(5.569186976818,-0.25)); -#16707 = CARTESIAN_POINT('',(5.497787143782,-0.25)); -#16708 = CARTESIAN_POINT('',(5.426387310746,-0.25)); -#16709 = CARTESIAN_POINT('',(5.35498747771,-0.25)); -#16710 = CARTESIAN_POINT('',(5.283587644674,-0.25)); -#16711 = CARTESIAN_POINT('',(5.212187811638,-0.25)); -#16712 = CARTESIAN_POINT('',(5.140787978601,-0.25)); -#16713 = CARTESIAN_POINT('',(5.069388145565,-0.25)); -#16714 = CARTESIAN_POINT('',(4.997988312529,-0.25)); -#16715 = CARTESIAN_POINT('',(4.926588479493,-0.25)); -#16716 = CARTESIAN_POINT('',(4.855188646457,-0.25)); -#16717 = CARTESIAN_POINT('',(4.783788813421,-0.25)); -#16718 = CARTESIAN_POINT('',(4.73618892473,-0.25)); -#16719 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16721 = PCURVE('',#16722,#16727); -#16722 = PLANE('',#16723); -#16723 = AXIS2_PLACEMENT_3D('',#16724,#16725,#16726); -#16724 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); -#16725 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#16726 = DIRECTION('',(0.E+000,0.E+000,1.)); -#16727 = DEFINITIONAL_REPRESENTATION('',(#16728),#16732); -#16728 = CIRCLE('',#16729,5.E-002); -#16729 = AXIS2_PLACEMENT_2D('',#16730,#16731); -#16730 = CARTESIAN_POINT('',(-0.24,5.E-002)); -#16731 = DIRECTION('',(-1.,-1.817579732889E-047)); -#16732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16733 = ORIENTED_EDGE('',*,*,#16734,.F.); -#16734 = EDGE_CURVE('',#16478,#16682,#16735,.T.); -#16735 = SURFACE_CURVE('',#16736,(#16740,#16746),.PCURVE_S1.); -#16736 = LINE('',#16737,#16738); -#16737 = CARTESIAN_POINT('',(7.077671781985E-015,-0.19, +#19087 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#19088 = CARTESIAN_POINT('',(6.259385362834,-0.25)); +#19089 = CARTESIAN_POINT('',(6.211785474143,-0.25)); +#19090 = CARTESIAN_POINT('',(6.140385641107,-0.25)); +#19091 = CARTESIAN_POINT('',(6.068985808071,-0.25)); +#19092 = CARTESIAN_POINT('',(5.997585975035,-0.25)); +#19093 = CARTESIAN_POINT('',(5.926186141999,-0.25)); +#19094 = CARTESIAN_POINT('',(5.854786308963,-0.25)); +#19095 = CARTESIAN_POINT('',(5.783386475927,-0.25)); +#19096 = CARTESIAN_POINT('',(5.711986642891,-0.25)); +#19097 = CARTESIAN_POINT('',(5.640586809854,-0.25)); +#19098 = CARTESIAN_POINT('',(5.569186976818,-0.25)); +#19099 = CARTESIAN_POINT('',(5.497787143782,-0.25)); +#19100 = CARTESIAN_POINT('',(5.426387310746,-0.25)); +#19101 = CARTESIAN_POINT('',(5.35498747771,-0.25)); +#19102 = CARTESIAN_POINT('',(5.283587644674,-0.25)); +#19103 = CARTESIAN_POINT('',(5.212187811638,-0.25)); +#19104 = CARTESIAN_POINT('',(5.140787978601,-0.25)); +#19105 = CARTESIAN_POINT('',(5.069388145565,-0.25)); +#19106 = CARTESIAN_POINT('',(4.997988312529,-0.25)); +#19107 = CARTESIAN_POINT('',(4.926588479493,-0.25)); +#19108 = CARTESIAN_POINT('',(4.855188646457,-0.25)); +#19109 = CARTESIAN_POINT('',(4.783788813421,-0.25)); +#19110 = CARTESIAN_POINT('',(4.73618892473,-0.25)); +#19111 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#19112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19113 = PCURVE('',#19114,#19119); +#19114 = PLANE('',#19115); +#19115 = AXIS2_PLACEMENT_3D('',#19116,#19117,#19118); +#19116 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); +#19117 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#19118 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19119 = DEFINITIONAL_REPRESENTATION('',(#19120),#19124); +#19120 = CIRCLE('',#19121,5.E-002); +#19121 = AXIS2_PLACEMENT_2D('',#19122,#19123); +#19122 = CARTESIAN_POINT('',(-0.24,5.E-002)); +#19123 = DIRECTION('',(-1.,-1.817579732889E-047)); +#19124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19125 = ORIENTED_EDGE('',*,*,#19126,.F.); +#19126 = EDGE_CURVE('',#18870,#19074,#19127,.T.); +#19127 = SURFACE_CURVE('',#19128,(#19132,#19138),.PCURVE_S1.); +#19128 = LINE('',#19129,#19130); +#19129 = CARTESIAN_POINT('',(7.077671781985E-015,-0.19, 9.999999999993E-003)); -#16738 = VECTOR('',#16739,1.); -#16739 = DIRECTION('',(-1.,0.E+000,-3.512815038853E-016)); -#16740 = PCURVE('',#16498,#16741); -#16741 = DEFINITIONAL_REPRESENTATION('',(#16742),#16745); -#16742 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16743,#16744),.UNSPECIFIED., +#19130 = VECTOR('',#19131,1.); +#19131 = DIRECTION('',(-1.,0.E+000,-3.512815038853E-016)); +#19132 = PCURVE('',#18890,#19133); +#19133 = DEFINITIONAL_REPRESENTATION('',(#19134),#19137); +#19134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19135,#19136),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16743 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#16744 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#16745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16746 = PCURVE('',#16525,#16747); -#16747 = DEFINITIONAL_REPRESENTATION('',(#16748),#16752); -#16748 = LINE('',#16749,#16750); -#16749 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#16750 = VECTOR('',#16751,1.); -#16751 = DIRECTION('',(1.,0.E+000)); -#16752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16753 = ORIENTED_EDGE('',*,*,#16477,.T.); -#16754 = ORIENTED_EDGE('',*,*,#16755,.T.); -#16755 = EDGE_CURVE('',#16450,#16684,#16756,.T.); -#16756 = SURFACE_CURVE('',#16757,(#16761,#16790),.PCURVE_S1.); -#16757 = LINE('',#16758,#16759); -#16758 = CARTESIAN_POINT('',(6.314393452556E-015,-0.24, +#19135 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#19136 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#19137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19138 = PCURVE('',#18917,#19139); +#19139 = DEFINITIONAL_REPRESENTATION('',(#19140),#19144); +#19140 = LINE('',#19141,#19142); +#19141 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#19142 = VECTOR('',#19143,1.); +#19143 = DIRECTION('',(1.,0.E+000)); +#19144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19145 = ORIENTED_EDGE('',*,*,#18869,.T.); +#19146 = ORIENTED_EDGE('',*,*,#19147,.T.); +#19147 = EDGE_CURVE('',#18842,#19076,#19148,.T.); +#19148 = SURFACE_CURVE('',#19149,(#19153,#19182),.PCURVE_S1.); +#19149 = LINE('',#19150,#19151); +#19150 = CARTESIAN_POINT('',(6.314393452556E-015,-0.24, 5.999999999999E-002)); -#16759 = VECTOR('',#16760,1.); -#16760 = DIRECTION('',(-1.,5.1741401491E-032,1.149532440457E-062)); -#16761 = PCURVE('',#16498,#16762); -#16762 = DEFINITIONAL_REPRESENTATION('',(#16763),#16789); -#16763 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16764,#16765,#16766,#16767, - #16768,#16769,#16770,#16771,#16772,#16773,#16774,#16775,#16776, - #16777,#16778,#16779,#16780,#16781,#16782,#16783,#16784,#16785, - #16786,#16787,#16788),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19151 = VECTOR('',#19152,1.); +#19152 = DIRECTION('',(-1.,5.1741401491E-032,1.149532440457E-062)); +#19153 = PCURVE('',#18890,#19154); +#19154 = DEFINITIONAL_REPRESENTATION('',(#19155),#19181); +#19155 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19156,#19157,#19158,#19159, + #19160,#19161,#19162,#19163,#19164,#19165,#19166,#19167,#19168, + #19169,#19170,#19171,#19172,#19173,#19174,#19175,#19176,#19177, + #19178,#19179,#19180),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.25,-0.227272727273,-0.204545454545, -0.181818181818,-0.159090909091,-0.136363636364,-0.113636363636, -9.090909090909E-002,-6.818181818182E-002,-4.545454545455E-002, @@ -20582,235 +23571,235 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.545454545455E-002,6.818181818182E-002,9.090909090909E-002, 0.113636363636,0.136363636364,0.159090909091,0.181818181818, 0.204545454545,0.227272727273,0.25),.UNSPECIFIED.); -#16764 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16765 = CARTESIAN_POINT('',(4.712388980385,0.242424242424)); -#16766 = CARTESIAN_POINT('',(4.712388980385,0.227272727273)); -#16767 = CARTESIAN_POINT('',(4.712388980385,0.204545454545)); -#16768 = CARTESIAN_POINT('',(4.712388980385,0.181818181818)); -#16769 = CARTESIAN_POINT('',(4.712388980385,0.159090909091)); -#16770 = CARTESIAN_POINT('',(4.712388980385,0.136363636364)); -#16771 = CARTESIAN_POINT('',(4.712388980385,0.113636363636)); -#16772 = CARTESIAN_POINT('',(4.712388980385,9.090909090909E-002)); -#16773 = CARTESIAN_POINT('',(4.712388980385,6.818181818182E-002)); -#16774 = CARTESIAN_POINT('',(4.712388980385,4.545454545455E-002)); -#16775 = CARTESIAN_POINT('',(4.712388980385,2.272727272727E-002)); -#16776 = CARTESIAN_POINT('',(4.712388980385,-1.939570100698E-017)); -#16777 = CARTESIAN_POINT('',(4.712388980385,-2.272727272727E-002)); -#16778 = CARTESIAN_POINT('',(4.712388980385,-4.545454545455E-002)); -#16779 = CARTESIAN_POINT('',(4.712388980385,-6.818181818182E-002)); -#16780 = CARTESIAN_POINT('',(4.712388980385,-9.090909090909E-002)); -#16781 = CARTESIAN_POINT('',(4.712388980385,-0.113636363636)); -#16782 = CARTESIAN_POINT('',(4.712388980385,-0.136363636364)); -#16783 = CARTESIAN_POINT('',(4.712388980385,-0.159090909091)); -#16784 = CARTESIAN_POINT('',(4.712388980385,-0.181818181818)); -#16785 = CARTESIAN_POINT('',(4.712388980385,-0.204545454545)); -#16786 = CARTESIAN_POINT('',(4.712388980385,-0.227272727273)); -#16787 = CARTESIAN_POINT('',(4.712388980385,-0.242424242424)); -#16788 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16790 = PCURVE('',#16465,#16791); -#16791 = DEFINITIONAL_REPRESENTATION('',(#16792),#16796); -#16792 = LINE('',#16793,#16794); -#16793 = CARTESIAN_POINT('',(-0.24,2.758877857098E-063)); -#16794 = VECTOR('',#16795,1.); -#16795 = DIRECTION('',(0.E+000,-1.)); -#16796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16797 = ADVANCED_FACE('',(#16798),#16465,.F.); -#16798 = FACE_BOUND('',#16799,.T.); -#16799 = EDGE_LOOP('',(#16800,#16801,#16823,#16844)); -#16800 = ORIENTED_EDGE('',*,*,#16449,.F.); -#16801 = ORIENTED_EDGE('',*,*,#16802,.F.); -#16802 = EDGE_CURVE('',#16803,#16388,#16805,.T.); -#16803 = VERTEX_POINT('',#16804); -#16804 = CARTESIAN_POINT('',(-0.25,-0.24,0.54)); -#16805 = SURFACE_CURVE('',#16806,(#16810,#16817),.PCURVE_S1.); -#16806 = LINE('',#16807,#16808); -#16807 = CARTESIAN_POINT('',(6.02018435103E-015,-0.24,0.54)); -#16808 = VECTOR('',#16809,1.); -#16809 = DIRECTION('',(1.,-5.1741401491E-032,-5.551115123126E-016)); -#16810 = PCURVE('',#16465,#16811); -#16811 = DEFINITIONAL_REPRESENTATION('',(#16812),#16816); -#16812 = LINE('',#16813,#16814); -#16813 = CARTESIAN_POINT('',(0.24,-2.942091015257E-016)); -#16814 = VECTOR('',#16815,1.); -#16815 = DIRECTION('',(-5.551115123126E-016,1.)); -#16816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16817 = PCURVE('',#16415,#16818); -#16818 = DEFINITIONAL_REPRESENTATION('',(#16819),#16822); -#16819 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16820,#16821),.UNSPECIFIED., +#19156 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#19157 = CARTESIAN_POINT('',(4.712388980385,0.242424242424)); +#19158 = CARTESIAN_POINT('',(4.712388980385,0.227272727273)); +#19159 = CARTESIAN_POINT('',(4.712388980385,0.204545454545)); +#19160 = CARTESIAN_POINT('',(4.712388980385,0.181818181818)); +#19161 = CARTESIAN_POINT('',(4.712388980385,0.159090909091)); +#19162 = CARTESIAN_POINT('',(4.712388980385,0.136363636364)); +#19163 = CARTESIAN_POINT('',(4.712388980385,0.113636363636)); +#19164 = CARTESIAN_POINT('',(4.712388980385,9.090909090909E-002)); +#19165 = CARTESIAN_POINT('',(4.712388980385,6.818181818182E-002)); +#19166 = CARTESIAN_POINT('',(4.712388980385,4.545454545455E-002)); +#19167 = CARTESIAN_POINT('',(4.712388980385,2.272727272727E-002)); +#19168 = CARTESIAN_POINT('',(4.712388980385,-1.939570100698E-017)); +#19169 = CARTESIAN_POINT('',(4.712388980385,-2.272727272727E-002)); +#19170 = CARTESIAN_POINT('',(4.712388980385,-4.545454545455E-002)); +#19171 = CARTESIAN_POINT('',(4.712388980385,-6.818181818182E-002)); +#19172 = CARTESIAN_POINT('',(4.712388980385,-9.090909090909E-002)); +#19173 = CARTESIAN_POINT('',(4.712388980385,-0.113636363636)); +#19174 = CARTESIAN_POINT('',(4.712388980385,-0.136363636364)); +#19175 = CARTESIAN_POINT('',(4.712388980385,-0.159090909091)); +#19176 = CARTESIAN_POINT('',(4.712388980385,-0.181818181818)); +#19177 = CARTESIAN_POINT('',(4.712388980385,-0.204545454545)); +#19178 = CARTESIAN_POINT('',(4.712388980385,-0.227272727273)); +#19179 = CARTESIAN_POINT('',(4.712388980385,-0.242424242424)); +#19180 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#19181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19182 = PCURVE('',#18857,#19183); +#19183 = DEFINITIONAL_REPRESENTATION('',(#19184),#19188); +#19184 = LINE('',#19185,#19186); +#19185 = CARTESIAN_POINT('',(-0.24,2.758877857098E-063)); +#19186 = VECTOR('',#19187,1.); +#19187 = DIRECTION('',(0.E+000,-1.)); +#19188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19189 = ADVANCED_FACE('',(#19190),#18857,.F.); +#19190 = FACE_BOUND('',#19191,.T.); +#19191 = EDGE_LOOP('',(#19192,#19193,#19215,#19236)); +#19192 = ORIENTED_EDGE('',*,*,#18841,.F.); +#19193 = ORIENTED_EDGE('',*,*,#19194,.F.); +#19194 = EDGE_CURVE('',#19195,#18780,#19197,.T.); +#19195 = VERTEX_POINT('',#19196); +#19196 = CARTESIAN_POINT('',(-0.25,-0.24,0.54)); +#19197 = SURFACE_CURVE('',#19198,(#19202,#19209),.PCURVE_S1.); +#19198 = LINE('',#19199,#19200); +#19199 = CARTESIAN_POINT('',(6.02018435103E-015,-0.24,0.54)); +#19200 = VECTOR('',#19201,1.); +#19201 = DIRECTION('',(1.,-5.1741401491E-032,-5.551115123126E-016)); +#19202 = PCURVE('',#18857,#19203); +#19203 = DEFINITIONAL_REPRESENTATION('',(#19204),#19208); +#19204 = LINE('',#19205,#19206); +#19205 = CARTESIAN_POINT('',(0.24,-2.942091015257E-016)); +#19206 = VECTOR('',#19207,1.); +#19207 = DIRECTION('',(-5.551115123126E-016,1.)); +#19208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19209 = PCURVE('',#18807,#19210); +#19210 = DEFINITIONAL_REPRESENTATION('',(#19211),#19214); +#19211 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19212,#19213),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16820 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16821 = CARTESIAN_POINT('',(4.712388980385,-0.25)); -#16822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16823 = ORIENTED_EDGE('',*,*,#16824,.F.); -#16824 = EDGE_CURVE('',#16684,#16803,#16825,.T.); -#16825 = SURFACE_CURVE('',#16826,(#16830,#16837),.PCURVE_S1.); -#16826 = LINE('',#16827,#16828); -#16827 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); -#16828 = VECTOR('',#16829,1.); -#16829 = DIRECTION('',(0.E+000,0.E+000,1.)); -#16830 = PCURVE('',#16465,#16831); -#16831 = DEFINITIONAL_REPRESENTATION('',(#16832),#16836); -#16832 = LINE('',#16833,#16834); -#16833 = CARTESIAN_POINT('',(1.054711873394E-015,-0.25)); -#16834 = VECTOR('',#16835,1.); -#16835 = DIRECTION('',(1.,-1.149532440457E-062)); -#16836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16837 = PCURVE('',#16722,#16838); -#16838 = DEFINITIONAL_REPRESENTATION('',(#16839),#16843); -#16839 = LINE('',#16840,#16841); -#16840 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#16841 = VECTOR('',#16842,1.); -#16842 = DIRECTION('',(1.,0.E+000)); -#16843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16844 = ORIENTED_EDGE('',*,*,#16755,.F.); -#16845 = ADVANCED_FACE('',(#16846),#16415,.T.); -#16846 = FACE_BOUND('',#16847,.T.); -#16847 = EDGE_LOOP('',(#16848,#16849,#16871,#16892)); -#16848 = ORIENTED_EDGE('',*,*,#16387,.T.); -#16849 = ORIENTED_EDGE('',*,*,#16850,.F.); -#16850 = EDGE_CURVE('',#16851,#16390,#16853,.T.); -#16851 = VERTEX_POINT('',#16852); -#16852 = CARTESIAN_POINT('',(-0.25,-0.19,0.59)); -#16853 = SURFACE_CURVE('',#16854,(#16858,#16864),.PCURVE_S1.); -#16854 = LINE('',#16855,#16856); -#16855 = CARTESIAN_POINT('',(5.620504062165E-015,-0.19,0.59)); -#16856 = VECTOR('',#16857,1.); -#16857 = DIRECTION('',(1.,0.E+000,-5.551115123126E-016)); -#16858 = PCURVE('',#16415,#16859); -#16859 = DEFINITIONAL_REPRESENTATION('',(#16860),#16863); -#16860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16861,#16862),.UNSPECIFIED., +#19212 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#19213 = CARTESIAN_POINT('',(4.712388980385,-0.25)); +#19214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19215 = ORIENTED_EDGE('',*,*,#19216,.F.); +#19216 = EDGE_CURVE('',#19076,#19195,#19217,.T.); +#19217 = SURFACE_CURVE('',#19218,(#19222,#19229),.PCURVE_S1.); +#19218 = LINE('',#19219,#19220); +#19219 = CARTESIAN_POINT('',(-0.25,-0.24,0.3)); +#19220 = VECTOR('',#19221,1.); +#19221 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19222 = PCURVE('',#18857,#19223); +#19223 = DEFINITIONAL_REPRESENTATION('',(#19224),#19228); +#19224 = LINE('',#19225,#19226); +#19225 = CARTESIAN_POINT('',(1.054711873394E-015,-0.25)); +#19226 = VECTOR('',#19227,1.); +#19227 = DIRECTION('',(1.,-1.149532440457E-062)); +#19228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19229 = PCURVE('',#19114,#19230); +#19230 = DEFINITIONAL_REPRESENTATION('',(#19231),#19235); +#19231 = LINE('',#19232,#19233); +#19232 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19233 = VECTOR('',#19234,1.); +#19234 = DIRECTION('',(1.,0.E+000)); +#19235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19236 = ORIENTED_EDGE('',*,*,#19147,.F.); +#19237 = ADVANCED_FACE('',(#19238),#18807,.T.); +#19238 = FACE_BOUND('',#19239,.T.); +#19239 = EDGE_LOOP('',(#19240,#19241,#19263,#19284)); +#19240 = ORIENTED_EDGE('',*,*,#18779,.T.); +#19241 = ORIENTED_EDGE('',*,*,#19242,.F.); +#19242 = EDGE_CURVE('',#19243,#18782,#19245,.T.); +#19243 = VERTEX_POINT('',#19244); +#19244 = CARTESIAN_POINT('',(-0.25,-0.19,0.59)); +#19245 = SURFACE_CURVE('',#19246,(#19250,#19256),.PCURVE_S1.); +#19246 = LINE('',#19247,#19248); +#19247 = CARTESIAN_POINT('',(5.620504062165E-015,-0.19,0.59)); +#19248 = VECTOR('',#19249,1.); +#19249 = DIRECTION('',(1.,0.E+000,-5.551115123126E-016)); +#19250 = PCURVE('',#18807,#19251); +#19251 = DEFINITIONAL_REPRESENTATION('',(#19252),#19255); +#19252 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19253,#19254),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16861 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#16862 = CARTESIAN_POINT('',(6.28318530718,-0.25)); -#16863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16864 = PCURVE('',#16666,#16865); -#16865 = DEFINITIONAL_REPRESENTATION('',(#16866),#16870); -#16866 = LINE('',#16867,#16868); -#16867 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#16868 = VECTOR('',#16869,1.); -#16869 = DIRECTION('',(1.,0.E+000)); -#16870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16871 = ORIENTED_EDGE('',*,*,#16872,.F.); -#16872 = EDGE_CURVE('',#16803,#16851,#16873,.T.); -#16873 = SURFACE_CURVE('',#16874,(#16879,#16885),.PCURVE_S1.); -#16874 = CIRCLE('',#16875,5.E-002); -#16875 = AXIS2_PLACEMENT_3D('',#16876,#16877,#16878); -#16876 = CARTESIAN_POINT('',(-0.25,-0.19,0.54)); -#16877 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16878 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); -#16879 = PCURVE('',#16415,#16880); -#16880 = DEFINITIONAL_REPRESENTATION('',(#16881),#16884); -#16881 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16882,#16883),.UNSPECIFIED., +#19253 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#19254 = CARTESIAN_POINT('',(6.28318530718,-0.25)); +#19255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19256 = PCURVE('',#19058,#19257); +#19257 = DEFINITIONAL_REPRESENTATION('',(#19258),#19262); +#19258 = LINE('',#19259,#19260); +#19259 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#19260 = VECTOR('',#19261,1.); +#19261 = DIRECTION('',(1.,0.E+000)); +#19262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19263 = ORIENTED_EDGE('',*,*,#19264,.F.); +#19264 = EDGE_CURVE('',#19195,#19243,#19265,.T.); +#19265 = SURFACE_CURVE('',#19266,(#19271,#19277),.PCURVE_S1.); +#19266 = CIRCLE('',#19267,5.E-002); +#19267 = AXIS2_PLACEMENT_3D('',#19268,#19269,#19270); +#19268 = CARTESIAN_POINT('',(-0.25,-0.19,0.54)); +#19269 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#19270 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); +#19271 = PCURVE('',#18807,#19272); +#19272 = DEFINITIONAL_REPRESENTATION('',(#19273),#19276); +#19273 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19274,#19275),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#16882 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#16883 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#16884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16885 = PCURVE('',#16722,#16886); -#16886 = DEFINITIONAL_REPRESENTATION('',(#16887),#16891); -#16887 = CIRCLE('',#16888,5.E-002); -#16888 = AXIS2_PLACEMENT_2D('',#16889,#16890); -#16889 = CARTESIAN_POINT('',(0.24,5.E-002)); -#16890 = DIRECTION('',(1.,2.737589227315E-047)); -#16891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16892 = ORIENTED_EDGE('',*,*,#16802,.T.); -#16893 = ADVANCED_FACE('',(#16894),#16666,.T.); -#16894 = FACE_BOUND('',#16895,.T.); -#16895 = EDGE_LOOP('',(#16896,#16897,#16898,#16920)); -#16896 = ORIENTED_EDGE('',*,*,#16850,.T.); -#16897 = ORIENTED_EDGE('',*,*,#16652,.T.); -#16898 = ORIENTED_EDGE('',*,*,#16899,.F.); -#16899 = EDGE_CURVE('',#16900,#16598,#16902,.T.); -#16900 = VERTEX_POINT('',#16901); -#16901 = CARTESIAN_POINT('',(-0.25,0.19,0.59)); -#16902 = SURFACE_CURVE('',#16903,(#16907,#16914),.PCURVE_S1.); -#16903 = LINE('',#16904,#16905); -#16904 = CARTESIAN_POINT('',(6.047939926646E-015,0.19,0.59)); -#16905 = VECTOR('',#16906,1.); -#16906 = DIRECTION('',(1.,-5.1741401491E-032,-5.551115123126E-016)); -#16907 = PCURVE('',#16666,#16908); -#16908 = DEFINITIONAL_REPRESENTATION('',(#16909),#16913); -#16909 = LINE('',#16910,#16911); -#16910 = CARTESIAN_POINT('',(4.274358644807E-016,0.43)); -#16911 = VECTOR('',#16912,1.); -#16912 = DIRECTION('',(1.,-5.1741401491E-032)); -#16913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16914 = PCURVE('',#16618,#16915); -#16915 = DEFINITIONAL_REPRESENTATION('',(#16916),#16919); -#16916 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#16917,#16918),.UNSPECIFIED., +#19274 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#19275 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#19276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19277 = PCURVE('',#19114,#19278); +#19278 = DEFINITIONAL_REPRESENTATION('',(#19279),#19283); +#19279 = CIRCLE('',#19280,5.E-002); +#19280 = AXIS2_PLACEMENT_2D('',#19281,#19282); +#19281 = CARTESIAN_POINT('',(0.24,5.E-002)); +#19282 = DIRECTION('',(1.,2.737589227315E-047)); +#19283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19284 = ORIENTED_EDGE('',*,*,#19194,.T.); +#19285 = ADVANCED_FACE('',(#19286),#19058,.T.); +#19286 = FACE_BOUND('',#19287,.T.); +#19287 = EDGE_LOOP('',(#19288,#19289,#19290,#19312)); +#19288 = ORIENTED_EDGE('',*,*,#19242,.T.); +#19289 = ORIENTED_EDGE('',*,*,#19044,.T.); +#19290 = ORIENTED_EDGE('',*,*,#19291,.F.); +#19291 = EDGE_CURVE('',#19292,#18990,#19294,.T.); +#19292 = VERTEX_POINT('',#19293); +#19293 = CARTESIAN_POINT('',(-0.25,0.19,0.59)); +#19294 = SURFACE_CURVE('',#19295,(#19299,#19306),.PCURVE_S1.); +#19295 = LINE('',#19296,#19297); +#19296 = CARTESIAN_POINT('',(6.047939926646E-015,0.19,0.59)); +#19297 = VECTOR('',#19298,1.); +#19298 = DIRECTION('',(1.,-5.1741401491E-032,-5.551115123126E-016)); +#19299 = PCURVE('',#19058,#19300); +#19300 = DEFINITIONAL_REPRESENTATION('',(#19301),#19305); +#19301 = LINE('',#19302,#19303); +#19302 = CARTESIAN_POINT('',(4.274358644807E-016,0.43)); +#19303 = VECTOR('',#19304,1.); +#19304 = DIRECTION('',(1.,-5.1741401491E-032)); +#19305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19306 = PCURVE('',#19010,#19307); +#19307 = DEFINITIONAL_REPRESENTATION('',(#19308),#19311); +#19308 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19309,#19310),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#16917 = CARTESIAN_POINT('',(0.E+000,0.25)); -#16918 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#16919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16920 = ORIENTED_EDGE('',*,*,#16921,.F.); -#16921 = EDGE_CURVE('',#16851,#16900,#16922,.T.); -#16922 = SURFACE_CURVE('',#16923,(#16927,#16934),.PCURVE_S1.); -#16923 = LINE('',#16924,#16925); -#16924 = CARTESIAN_POINT('',(-0.25,-0.24,0.59)); -#16925 = VECTOR('',#16926,1.); -#16926 = DIRECTION('',(0.E+000,1.,0.E+000)); -#16927 = PCURVE('',#16666,#16928); -#16928 = DEFINITIONAL_REPRESENTATION('',(#16929),#16933); -#16929 = LINE('',#16930,#16931); -#16930 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#16931 = VECTOR('',#16932,1.); -#16932 = DIRECTION('',(0.E+000,1.)); -#16933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16934 = PCURVE('',#16722,#16935); -#16935 = DEFINITIONAL_REPRESENTATION('',(#16936),#16940); -#16936 = LINE('',#16937,#16938); -#16937 = CARTESIAN_POINT('',(0.29,0.E+000)); -#16938 = VECTOR('',#16939,1.); -#16939 = DIRECTION('',(0.E+000,1.)); -#16940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16941 = ADVANCED_FACE('',(#16942),#16618,.T.); -#16942 = FACE_BOUND('',#16943,.T.); -#16943 = EDGE_LOOP('',(#16944,#16945,#16990,#17034)); -#16944 = ORIENTED_EDGE('',*,*,#16597,.T.); -#16945 = ORIENTED_EDGE('',*,*,#16946,.F.); -#16946 = EDGE_CURVE('',#16947,#16570,#16949,.T.); -#16947 = VERTEX_POINT('',#16948); -#16948 = CARTESIAN_POINT('',(-0.25,0.24,0.54)); -#16949 = SURFACE_CURVE('',#16950,(#16954,#16983),.PCURVE_S1.); -#16950 = LINE('',#16951,#16952); -#16951 = CARTESIAN_POINT('',(6.314393452556E-015,0.24,0.54)); -#16952 = VECTOR('',#16953,1.); -#16953 = DIRECTION('',(1.,-5.1741401491E-032,-1.149532440457E-062)); -#16954 = PCURVE('',#16618,#16955); -#16955 = DEFINITIONAL_REPRESENTATION('',(#16956),#16982); -#16956 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#16957,#16958,#16959,#16960, - #16961,#16962,#16963,#16964,#16965,#16966,#16967,#16968,#16969, - #16970,#16971,#16972,#16973,#16974,#16975,#16976,#16977,#16978, - #16979,#16980,#16981),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19309 = CARTESIAN_POINT('',(0.E+000,0.25)); +#19310 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#19311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19312 = ORIENTED_EDGE('',*,*,#19313,.F.); +#19313 = EDGE_CURVE('',#19243,#19292,#19314,.T.); +#19314 = SURFACE_CURVE('',#19315,(#19319,#19326),.PCURVE_S1.); +#19315 = LINE('',#19316,#19317); +#19316 = CARTESIAN_POINT('',(-0.25,-0.24,0.59)); +#19317 = VECTOR('',#19318,1.); +#19318 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19319 = PCURVE('',#19058,#19320); +#19320 = DEFINITIONAL_REPRESENTATION('',(#19321),#19325); +#19321 = LINE('',#19322,#19323); +#19322 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#19323 = VECTOR('',#19324,1.); +#19324 = DIRECTION('',(0.E+000,1.)); +#19325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19326 = PCURVE('',#19114,#19327); +#19327 = DEFINITIONAL_REPRESENTATION('',(#19328),#19332); +#19328 = LINE('',#19329,#19330); +#19329 = CARTESIAN_POINT('',(0.29,0.E+000)); +#19330 = VECTOR('',#19331,1.); +#19331 = DIRECTION('',(0.E+000,1.)); +#19332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19333 = ADVANCED_FACE('',(#19334),#19010,.T.); +#19334 = FACE_BOUND('',#19335,.T.); +#19335 = EDGE_LOOP('',(#19336,#19337,#19382,#19426)); +#19336 = ORIENTED_EDGE('',*,*,#18989,.T.); +#19337 = ORIENTED_EDGE('',*,*,#19338,.F.); +#19338 = EDGE_CURVE('',#19339,#18962,#19341,.T.); +#19339 = VERTEX_POINT('',#19340); +#19340 = CARTESIAN_POINT('',(-0.25,0.24,0.54)); +#19341 = SURFACE_CURVE('',#19342,(#19346,#19375),.PCURVE_S1.); +#19342 = LINE('',#19343,#19344); +#19343 = CARTESIAN_POINT('',(6.314393452556E-015,0.24,0.54)); +#19344 = VECTOR('',#19345,1.); +#19345 = DIRECTION('',(1.,-5.1741401491E-032,-1.149532440457E-062)); +#19346 = PCURVE('',#19010,#19347); +#19347 = DEFINITIONAL_REPRESENTATION('',(#19348),#19374); +#19348 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19349,#19350,#19351,#19352, + #19353,#19354,#19355,#19356,#19357,#19358,#19359,#19360,#19361, + #19362,#19363,#19364,#19365,#19366,#19367,#19368,#19369,#19370, + #19371,#19372,#19373),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.25,-0.227272727273,-0.204545454545, -0.181818181818,-0.159090909091,-0.136363636364,-0.113636363636, -9.090909090909E-002,-6.818181818182E-002,-4.545454545455E-002, @@ -20818,57 +23807,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.545454545455E-002,6.818181818182E-002,9.090909090909E-002, 0.113636363636,0.136363636364,0.159090909091,0.181818181818, 0.204545454545,0.227272727273,0.25),.UNSPECIFIED.); -#16957 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#16958 = CARTESIAN_POINT('',(1.570796326795,0.242424242424)); -#16959 = CARTESIAN_POINT('',(1.570796326795,0.227272727273)); -#16960 = CARTESIAN_POINT('',(1.570796326795,0.204545454545)); -#16961 = CARTESIAN_POINT('',(1.570796326795,0.181818181818)); -#16962 = CARTESIAN_POINT('',(1.570796326795,0.159090909091)); -#16963 = CARTESIAN_POINT('',(1.570796326795,0.136363636364)); -#16964 = CARTESIAN_POINT('',(1.570796326795,0.113636363636)); -#16965 = CARTESIAN_POINT('',(1.570796326795,9.090909090909E-002)); -#16966 = CARTESIAN_POINT('',(1.570796326795,6.818181818182E-002)); -#16967 = CARTESIAN_POINT('',(1.570796326795,4.545454545455E-002)); -#16968 = CARTESIAN_POINT('',(1.570796326795,2.272727272727E-002)); -#16969 = CARTESIAN_POINT('',(1.570796326795,4.846780462791E-017)); -#16970 = CARTESIAN_POINT('',(1.570796326795,-2.272727272727E-002)); -#16971 = CARTESIAN_POINT('',(1.570796326795,-4.545454545455E-002)); -#16972 = CARTESIAN_POINT('',(1.570796326795,-6.818181818182E-002)); -#16973 = CARTESIAN_POINT('',(1.570796326795,-9.090909090909E-002)); -#16974 = CARTESIAN_POINT('',(1.570796326795,-0.113636363636)); -#16975 = CARTESIAN_POINT('',(1.570796326795,-0.136363636364)); -#16976 = CARTESIAN_POINT('',(1.570796326795,-0.159090909091)); -#16977 = CARTESIAN_POINT('',(1.570796326795,-0.181818181818)); -#16978 = CARTESIAN_POINT('',(1.570796326795,-0.204545454545)); -#16979 = CARTESIAN_POINT('',(1.570796326795,-0.227272727273)); -#16980 = CARTESIAN_POINT('',(1.570796326795,-0.242424242424)); -#16981 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#16982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16983 = PCURVE('',#16585,#16984); -#16984 = DEFINITIONAL_REPRESENTATION('',(#16985),#16989); -#16985 = LINE('',#16986,#16987); -#16986 = CARTESIAN_POINT('',(0.24,-2.758877857098E-063)); -#16987 = VECTOR('',#16988,1.); -#16988 = DIRECTION('',(0.E+000,1.)); -#16989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#16990 = ORIENTED_EDGE('',*,*,#16991,.F.); -#16991 = EDGE_CURVE('',#16900,#16947,#16992,.T.); -#16992 = SURFACE_CURVE('',#16993,(#16998,#17027),.PCURVE_S1.); -#16993 = CIRCLE('',#16994,5.E-002); -#16994 = AXIS2_PLACEMENT_3D('',#16995,#16996,#16997); -#16995 = CARTESIAN_POINT('',(-0.25,0.19,0.54)); -#16996 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); -#16997 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); -#16998 = PCURVE('',#16618,#16999); -#16999 = DEFINITIONAL_REPRESENTATION('',(#17000),#17026); -#17000 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17001,#17002,#17003,#17004, - #17005,#17006,#17007,#17008,#17009,#17010,#17011,#17012,#17013, - #17014,#17015,#17016,#17017,#17018,#17019,#17020,#17021,#17022, - #17023,#17024,#17025),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19349 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#19350 = CARTESIAN_POINT('',(1.570796326795,0.242424242424)); +#19351 = CARTESIAN_POINT('',(1.570796326795,0.227272727273)); +#19352 = CARTESIAN_POINT('',(1.570796326795,0.204545454545)); +#19353 = CARTESIAN_POINT('',(1.570796326795,0.181818181818)); +#19354 = CARTESIAN_POINT('',(1.570796326795,0.159090909091)); +#19355 = CARTESIAN_POINT('',(1.570796326795,0.136363636364)); +#19356 = CARTESIAN_POINT('',(1.570796326795,0.113636363636)); +#19357 = CARTESIAN_POINT('',(1.570796326795,9.090909090909E-002)); +#19358 = CARTESIAN_POINT('',(1.570796326795,6.818181818182E-002)); +#19359 = CARTESIAN_POINT('',(1.570796326795,4.545454545455E-002)); +#19360 = CARTESIAN_POINT('',(1.570796326795,2.272727272727E-002)); +#19361 = CARTESIAN_POINT('',(1.570796326795,4.846780462791E-017)); +#19362 = CARTESIAN_POINT('',(1.570796326795,-2.272727272727E-002)); +#19363 = CARTESIAN_POINT('',(1.570796326795,-4.545454545455E-002)); +#19364 = CARTESIAN_POINT('',(1.570796326795,-6.818181818182E-002)); +#19365 = CARTESIAN_POINT('',(1.570796326795,-9.090909090909E-002)); +#19366 = CARTESIAN_POINT('',(1.570796326795,-0.113636363636)); +#19367 = CARTESIAN_POINT('',(1.570796326795,-0.136363636364)); +#19368 = CARTESIAN_POINT('',(1.570796326795,-0.159090909091)); +#19369 = CARTESIAN_POINT('',(1.570796326795,-0.181818181818)); +#19370 = CARTESIAN_POINT('',(1.570796326795,-0.204545454545)); +#19371 = CARTESIAN_POINT('',(1.570796326795,-0.227272727273)); +#19372 = CARTESIAN_POINT('',(1.570796326795,-0.242424242424)); +#19373 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#19374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19375 = PCURVE('',#18977,#19376); +#19376 = DEFINITIONAL_REPRESENTATION('',(#19377),#19381); +#19377 = LINE('',#19378,#19379); +#19378 = CARTESIAN_POINT('',(0.24,-2.758877857098E-063)); +#19379 = VECTOR('',#19380,1.); +#19380 = DIRECTION('',(0.E+000,1.)); +#19381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19382 = ORIENTED_EDGE('',*,*,#19383,.F.); +#19383 = EDGE_CURVE('',#19292,#19339,#19384,.T.); +#19384 = SURFACE_CURVE('',#19385,(#19390,#19419),.PCURVE_S1.); +#19385 = CIRCLE('',#19386,5.E-002); +#19386 = AXIS2_PLACEMENT_3D('',#19387,#19388,#19389); +#19387 = CARTESIAN_POINT('',(-0.25,0.19,0.54)); +#19388 = DIRECTION('',(-1.,5.1741401491E-032,5.551115123126E-016)); +#19389 = DIRECTION('',(5.551115123126E-016,2.737589227315E-047,1.)); +#19390 = PCURVE('',#19010,#19391); +#19391 = DEFINITIONAL_REPRESENTATION('',(#19392),#19418); +#19392 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19393,#19394,#19395,#19396, + #19397,#19398,#19399,#19400,#19401,#19402,#19403,#19404,#19405, + #19406,#19407,#19408,#19409,#19410,#19411,#19412,#19413,#19414, + #19415,#19416,#19417),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -20876,121 +23865,121 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#17001 = CARTESIAN_POINT('',(0.E+000,0.25)); -#17002 = CARTESIAN_POINT('',(2.379994434538E-002,0.25)); -#17003 = CARTESIAN_POINT('',(7.139983303613E-002,0.25)); -#17004 = CARTESIAN_POINT('',(0.142799666072,0.25)); -#17005 = CARTESIAN_POINT('',(0.214199499108,0.25)); -#17006 = CARTESIAN_POINT('',(0.285599332145,0.25)); -#17007 = CARTESIAN_POINT('',(0.356999165181,0.25)); -#17008 = CARTESIAN_POINT('',(0.428398998217,0.25)); -#17009 = CARTESIAN_POINT('',(0.499798831253,0.25)); -#17010 = CARTESIAN_POINT('',(0.571198664289,0.25)); -#17011 = CARTESIAN_POINT('',(0.642598497325,0.25)); -#17012 = CARTESIAN_POINT('',(0.713998330361,0.25)); -#17013 = CARTESIAN_POINT('',(0.785398163397,0.25)); -#17014 = CARTESIAN_POINT('',(0.856797996434,0.25)); -#17015 = CARTESIAN_POINT('',(0.92819782947,0.25)); -#17016 = CARTESIAN_POINT('',(0.999597662506,0.25)); -#17017 = CARTESIAN_POINT('',(1.070997495542,0.25)); -#17018 = CARTESIAN_POINT('',(1.142397328578,0.25)); -#17019 = CARTESIAN_POINT('',(1.213797161614,0.25)); -#17020 = CARTESIAN_POINT('',(1.28519699465,0.25)); -#17021 = CARTESIAN_POINT('',(1.356596827687,0.25)); -#17022 = CARTESIAN_POINT('',(1.427996660723,0.25)); -#17023 = CARTESIAN_POINT('',(1.499396493759,0.25)); -#17024 = CARTESIAN_POINT('',(1.54699638245,0.25)); -#17025 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#17026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17027 = PCURVE('',#16722,#17028); -#17028 = DEFINITIONAL_REPRESENTATION('',(#17029),#17033); -#17029 = CIRCLE('',#17030,5.E-002); -#17030 = AXIS2_PLACEMENT_2D('',#17031,#17032); -#17031 = CARTESIAN_POINT('',(0.24,0.43)); -#17032 = DIRECTION('',(1.,2.737589227315E-047)); -#17033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17034 = ORIENTED_EDGE('',*,*,#16899,.T.); -#17035 = ADVANCED_FACE('',(#17036),#16585,.T.); -#17036 = FACE_BOUND('',#17037,.T.); -#17037 = EDGE_LOOP('',(#17038,#17039,#17040,#17062)); -#17038 = ORIENTED_EDGE('',*,*,#16946,.T.); -#17039 = ORIENTED_EDGE('',*,*,#16569,.T.); -#17040 = ORIENTED_EDGE('',*,*,#17041,.F.); -#17041 = EDGE_CURVE('',#17042,#16538,#17044,.T.); -#17042 = VERTEX_POINT('',#17043); -#17043 = CARTESIAN_POINT('',(-0.25,0.24,5.999999999999E-002)); -#17044 = SURFACE_CURVE('',#17045,(#17049,#17056),.PCURVE_S1.); -#17045 = LINE('',#17046,#17047); -#17046 = CARTESIAN_POINT('',(6.72940436014E-015,0.24,5.999999999999E-002 +#19393 = CARTESIAN_POINT('',(0.E+000,0.25)); +#19394 = CARTESIAN_POINT('',(2.379994434538E-002,0.25)); +#19395 = CARTESIAN_POINT('',(7.139983303613E-002,0.25)); +#19396 = CARTESIAN_POINT('',(0.142799666072,0.25)); +#19397 = CARTESIAN_POINT('',(0.214199499108,0.25)); +#19398 = CARTESIAN_POINT('',(0.285599332145,0.25)); +#19399 = CARTESIAN_POINT('',(0.356999165181,0.25)); +#19400 = CARTESIAN_POINT('',(0.428398998217,0.25)); +#19401 = CARTESIAN_POINT('',(0.499798831253,0.25)); +#19402 = CARTESIAN_POINT('',(0.571198664289,0.25)); +#19403 = CARTESIAN_POINT('',(0.642598497325,0.25)); +#19404 = CARTESIAN_POINT('',(0.713998330361,0.25)); +#19405 = CARTESIAN_POINT('',(0.785398163397,0.25)); +#19406 = CARTESIAN_POINT('',(0.856797996434,0.25)); +#19407 = CARTESIAN_POINT('',(0.92819782947,0.25)); +#19408 = CARTESIAN_POINT('',(0.999597662506,0.25)); +#19409 = CARTESIAN_POINT('',(1.070997495542,0.25)); +#19410 = CARTESIAN_POINT('',(1.142397328578,0.25)); +#19411 = CARTESIAN_POINT('',(1.213797161614,0.25)); +#19412 = CARTESIAN_POINT('',(1.28519699465,0.25)); +#19413 = CARTESIAN_POINT('',(1.356596827687,0.25)); +#19414 = CARTESIAN_POINT('',(1.427996660723,0.25)); +#19415 = CARTESIAN_POINT('',(1.499396493759,0.25)); +#19416 = CARTESIAN_POINT('',(1.54699638245,0.25)); +#19417 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#19418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19419 = PCURVE('',#19114,#19420); +#19420 = DEFINITIONAL_REPRESENTATION('',(#19421),#19425); +#19421 = CIRCLE('',#19422,5.E-002); +#19422 = AXIS2_PLACEMENT_2D('',#19423,#19424); +#19423 = CARTESIAN_POINT('',(0.24,0.43)); +#19424 = DIRECTION('',(1.,2.737589227315E-047)); +#19425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19426 = ORIENTED_EDGE('',*,*,#19291,.T.); +#19427 = ADVANCED_FACE('',(#19428),#18977,.T.); +#19428 = FACE_BOUND('',#19429,.T.); +#19429 = EDGE_LOOP('',(#19430,#19431,#19432,#19454)); +#19430 = ORIENTED_EDGE('',*,*,#19338,.T.); +#19431 = ORIENTED_EDGE('',*,*,#18961,.T.); +#19432 = ORIENTED_EDGE('',*,*,#19433,.F.); +#19433 = EDGE_CURVE('',#19434,#18930,#19436,.T.); +#19434 = VERTEX_POINT('',#19435); +#19435 = CARTESIAN_POINT('',(-0.25,0.24,5.999999999999E-002)); +#19436 = SURFACE_CURVE('',#19437,(#19441,#19448),.PCURVE_S1.); +#19437 = LINE('',#19438,#19439); +#19438 = CARTESIAN_POINT('',(6.72940436014E-015,0.24,5.999999999999E-002 )); -#17047 = VECTOR('',#17048,1.); -#17048 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); -#17049 = PCURVE('',#16585,#17050); -#17050 = DEFINITIONAL_REPRESENTATION('',(#17051),#17055); -#17051 = LINE('',#17052,#17053); -#17052 = CARTESIAN_POINT('',(-0.24,4.15010907584E-016)); -#17053 = VECTOR('',#17054,1.); -#17054 = DIRECTION('',(3.512815038853E-016,1.)); -#17055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17056 = PCURVE('',#16558,#17057); -#17057 = DEFINITIONAL_REPRESENTATION('',(#17058),#17061); -#17058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17059,#17060),.UNSPECIFIED., +#19439 = VECTOR('',#19440,1.); +#19440 = DIRECTION('',(1.,-5.1741401491E-032,3.512815038853E-016)); +#19441 = PCURVE('',#18977,#19442); +#19442 = DEFINITIONAL_REPRESENTATION('',(#19443),#19447); +#19443 = LINE('',#19444,#19445); +#19444 = CARTESIAN_POINT('',(-0.24,4.15010907584E-016)); +#19445 = VECTOR('',#19446,1.); +#19446 = DIRECTION('',(3.512815038853E-016,1.)); +#19447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19448 = PCURVE('',#18950,#19449); +#19449 = DEFINITIONAL_REPRESENTATION('',(#19450),#19453); +#19450 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19451,#19452),.UNSPECIFIED., .F.,.F.,(2,2),(-0.25,0.25),.PIECEWISE_BEZIER_KNOTS.); -#17059 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#17060 = CARTESIAN_POINT('',(1.570796326795,0.25)); -#17061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17062 = ORIENTED_EDGE('',*,*,#17063,.F.); -#17063 = EDGE_CURVE('',#16947,#17042,#17064,.T.); -#17064 = SURFACE_CURVE('',#17065,(#17069,#17076),.PCURVE_S1.); -#17065 = LINE('',#17066,#17067); -#17066 = CARTESIAN_POINT('',(-0.25,0.24,0.3)); -#17067 = VECTOR('',#17068,1.); -#17068 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#17069 = PCURVE('',#16585,#17070); -#17070 = DEFINITIONAL_REPRESENTATION('',(#17071),#17075); -#17071 = LINE('',#17072,#17073); -#17072 = CARTESIAN_POINT('',(1.054711873394E-015,-0.25)); -#17073 = VECTOR('',#17074,1.); -#17074 = DIRECTION('',(-1.,1.149532440457E-062)); -#17075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17076 = PCURVE('',#16722,#17077); -#17077 = DEFINITIONAL_REPRESENTATION('',(#17078),#17082); -#17078 = LINE('',#17079,#17080); -#17079 = CARTESIAN_POINT('',(0.E+000,0.48)); -#17080 = VECTOR('',#17081,1.); -#17081 = DIRECTION('',(-1.,0.E+000)); -#17082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17083 = ADVANCED_FACE('',(#17084),#16558,.T.); -#17084 = FACE_BOUND('',#17085,.T.); -#17085 = EDGE_LOOP('',(#17086,#17132,#17133,#17134)); -#17086 = ORIENTED_EDGE('',*,*,#17087,.F.); -#17087 = EDGE_CURVE('',#17042,#17088,#17090,.T.); -#17088 = VERTEX_POINT('',#17089); -#17089 = CARTESIAN_POINT('',(-0.25,0.19,9.999999999993E-003)); -#17090 = SURFACE_CURVE('',#17091,(#17096,#17125),.PCURVE_S1.); -#17091 = CIRCLE('',#17092,5.E-002); -#17092 = AXIS2_PLACEMENT_3D('',#17093,#17094,#17095); -#17093 = CARTESIAN_POINT('',(-0.25,0.19,5.999999999999E-002)); -#17094 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); -#17095 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); -#17096 = PCURVE('',#16558,#17097); -#17097 = DEFINITIONAL_REPRESENTATION('',(#17098),#17124); -#17098 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17099,#17100,#17101,#17102, - #17103,#17104,#17105,#17106,#17107,#17108,#17109,#17110,#17111, - #17112,#17113,#17114,#17115,#17116,#17117,#17118,#17119,#17120, - #17121,#17122,#17123),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19451 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#19452 = CARTESIAN_POINT('',(1.570796326795,0.25)); +#19453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19454 = ORIENTED_EDGE('',*,*,#19455,.F.); +#19455 = EDGE_CURVE('',#19339,#19434,#19456,.T.); +#19456 = SURFACE_CURVE('',#19457,(#19461,#19468),.PCURVE_S1.); +#19457 = LINE('',#19458,#19459); +#19458 = CARTESIAN_POINT('',(-0.25,0.24,0.3)); +#19459 = VECTOR('',#19460,1.); +#19460 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#19461 = PCURVE('',#18977,#19462); +#19462 = DEFINITIONAL_REPRESENTATION('',(#19463),#19467); +#19463 = LINE('',#19464,#19465); +#19464 = CARTESIAN_POINT('',(1.054711873394E-015,-0.25)); +#19465 = VECTOR('',#19466,1.); +#19466 = DIRECTION('',(-1.,1.149532440457E-062)); +#19467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19468 = PCURVE('',#19114,#19469); +#19469 = DEFINITIONAL_REPRESENTATION('',(#19470),#19474); +#19470 = LINE('',#19471,#19472); +#19471 = CARTESIAN_POINT('',(0.E+000,0.48)); +#19472 = VECTOR('',#19473,1.); +#19473 = DIRECTION('',(-1.,0.E+000)); +#19474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19475 = ADVANCED_FACE('',(#19476),#18950,.T.); +#19476 = FACE_BOUND('',#19477,.T.); +#19477 = EDGE_LOOP('',(#19478,#19524,#19525,#19526)); +#19478 = ORIENTED_EDGE('',*,*,#19479,.F.); +#19479 = EDGE_CURVE('',#19434,#19480,#19482,.T.); +#19480 = VERTEX_POINT('',#19481); +#19481 = CARTESIAN_POINT('',(-0.25,0.19,9.999999999993E-003)); +#19482 = SURFACE_CURVE('',#19483,(#19488,#19517),.PCURVE_S1.); +#19483 = CIRCLE('',#19484,5.E-002); +#19484 = AXIS2_PLACEMENT_3D('',#19485,#19486,#19487); +#19485 = CARTESIAN_POINT('',(-0.25,0.19,5.999999999999E-002)); +#19486 = DIRECTION('',(-1.,5.1741401491E-032,-3.512815038853E-016)); +#19487 = DIRECTION('',(3.512815038853E-016,-1.817579732889E-047,-1.)); +#19488 = PCURVE('',#18950,#19489); +#19489 = DEFINITIONAL_REPRESENTATION('',(#19490),#19516); +#19490 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19491,#19492,#19493,#19494, + #19495,#19496,#19497,#19498,#19499,#19500,#19501,#19502,#19503, + #19504,#19505,#19506,#19507,#19508,#19509,#19510,#19511,#19512, + #19513,#19514,#19515),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.783788813421, 4.855188646457,4.926588479493,4.997988312529,5.069388145565, 5.140787978601,5.212187811638,5.283587644674,5.35498747771, @@ -20998,59 +23987,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.711986642891,5.783386475927,5.854786308963,5.926186141999, 5.997585975035,6.068985808071,6.140385641107,6.211785474143, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#17099 = CARTESIAN_POINT('',(1.570796326795,-0.25)); -#17100 = CARTESIAN_POINT('',(1.54699638245,-0.25)); -#17101 = CARTESIAN_POINT('',(1.499396493759,-0.25)); -#17102 = CARTESIAN_POINT('',(1.427996660723,-0.25)); -#17103 = CARTESIAN_POINT('',(1.356596827687,-0.25)); -#17104 = CARTESIAN_POINT('',(1.28519699465,-0.25)); -#17105 = CARTESIAN_POINT('',(1.213797161614,-0.25)); -#17106 = CARTESIAN_POINT('',(1.142397328578,-0.25)); -#17107 = CARTESIAN_POINT('',(1.070997495542,-0.25)); -#17108 = CARTESIAN_POINT('',(0.999597662506,-0.25)); -#17109 = CARTESIAN_POINT('',(0.92819782947,-0.25)); -#17110 = CARTESIAN_POINT('',(0.856797996434,-0.25)); -#17111 = CARTESIAN_POINT('',(0.785398163397,-0.25)); -#17112 = CARTESIAN_POINT('',(0.713998330361,-0.25)); -#17113 = CARTESIAN_POINT('',(0.642598497325,-0.25)); -#17114 = CARTESIAN_POINT('',(0.571198664289,-0.25)); -#17115 = CARTESIAN_POINT('',(0.499798831253,-0.25)); -#17116 = CARTESIAN_POINT('',(0.428398998217,-0.25)); -#17117 = CARTESIAN_POINT('',(0.356999165181,-0.25)); -#17118 = CARTESIAN_POINT('',(0.285599332145,-0.25)); -#17119 = CARTESIAN_POINT('',(0.214199499108,-0.25)); -#17120 = CARTESIAN_POINT('',(0.142799666072,-0.25)); -#17121 = CARTESIAN_POINT('',(7.139983303613E-002,-0.25)); -#17122 = CARTESIAN_POINT('',(2.379994434538E-002,-0.25)); -#17123 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#17124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17125 = PCURVE('',#16722,#17126); -#17126 = DEFINITIONAL_REPRESENTATION('',(#17127),#17131); -#17127 = CIRCLE('',#17128,5.E-002); -#17128 = AXIS2_PLACEMENT_2D('',#17129,#17130); -#17129 = CARTESIAN_POINT('',(-0.24,0.43)); -#17130 = DIRECTION('',(-1.,-1.817579732889E-047)); -#17131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17132 = ORIENTED_EDGE('',*,*,#17041,.T.); -#17133 = ORIENTED_EDGE('',*,*,#16537,.T.); -#17134 = ORIENTED_EDGE('',*,*,#17135,.F.); -#17135 = EDGE_CURVE('',#17088,#16510,#17136,.T.); -#17136 = SURFACE_CURVE('',#17137,(#17141,#17170),.PCURVE_S1.); -#17137 = LINE('',#17138,#17139); -#17138 = CARTESIAN_POINT('',(7.077671781985E-015,0.19, +#19491 = CARTESIAN_POINT('',(1.570796326795,-0.25)); +#19492 = CARTESIAN_POINT('',(1.54699638245,-0.25)); +#19493 = CARTESIAN_POINT('',(1.499396493759,-0.25)); +#19494 = CARTESIAN_POINT('',(1.427996660723,-0.25)); +#19495 = CARTESIAN_POINT('',(1.356596827687,-0.25)); +#19496 = CARTESIAN_POINT('',(1.28519699465,-0.25)); +#19497 = CARTESIAN_POINT('',(1.213797161614,-0.25)); +#19498 = CARTESIAN_POINT('',(1.142397328578,-0.25)); +#19499 = CARTESIAN_POINT('',(1.070997495542,-0.25)); +#19500 = CARTESIAN_POINT('',(0.999597662506,-0.25)); +#19501 = CARTESIAN_POINT('',(0.92819782947,-0.25)); +#19502 = CARTESIAN_POINT('',(0.856797996434,-0.25)); +#19503 = CARTESIAN_POINT('',(0.785398163397,-0.25)); +#19504 = CARTESIAN_POINT('',(0.713998330361,-0.25)); +#19505 = CARTESIAN_POINT('',(0.642598497325,-0.25)); +#19506 = CARTESIAN_POINT('',(0.571198664289,-0.25)); +#19507 = CARTESIAN_POINT('',(0.499798831253,-0.25)); +#19508 = CARTESIAN_POINT('',(0.428398998217,-0.25)); +#19509 = CARTESIAN_POINT('',(0.356999165181,-0.25)); +#19510 = CARTESIAN_POINT('',(0.285599332145,-0.25)); +#19511 = CARTESIAN_POINT('',(0.214199499108,-0.25)); +#19512 = CARTESIAN_POINT('',(0.142799666072,-0.25)); +#19513 = CARTESIAN_POINT('',(7.139983303613E-002,-0.25)); +#19514 = CARTESIAN_POINT('',(2.379994434538E-002,-0.25)); +#19515 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#19516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19517 = PCURVE('',#19114,#19518); +#19518 = DEFINITIONAL_REPRESENTATION('',(#19519),#19523); +#19519 = CIRCLE('',#19520,5.E-002); +#19520 = AXIS2_PLACEMENT_2D('',#19521,#19522); +#19521 = CARTESIAN_POINT('',(-0.24,0.43)); +#19522 = DIRECTION('',(-1.,-1.817579732889E-047)); +#19523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19524 = ORIENTED_EDGE('',*,*,#19433,.T.); +#19525 = ORIENTED_EDGE('',*,*,#18929,.T.); +#19526 = ORIENTED_EDGE('',*,*,#19527,.F.); +#19527 = EDGE_CURVE('',#19480,#18902,#19528,.T.); +#19528 = SURFACE_CURVE('',#19529,(#19533,#19562),.PCURVE_S1.); +#19529 = LINE('',#19530,#19531); +#19530 = CARTESIAN_POINT('',(7.077671781985E-015,0.19, 9.999999999993E-003)); -#17139 = VECTOR('',#17140,1.); -#17140 = DIRECTION('',(1.,0.E+000,3.512815038853E-016)); -#17141 = PCURVE('',#16558,#17142); -#17142 = DEFINITIONAL_REPRESENTATION('',(#17143),#17169); -#17143 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#17144,#17145,#17146,#17147, - #17148,#17149,#17150,#17151,#17152,#17153,#17154,#17155,#17156, - #17157,#17158,#17159,#17160,#17161,#17162,#17163,#17164,#17165, - #17166,#17167,#17168),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#19531 = VECTOR('',#19532,1.); +#19532 = DIRECTION('',(1.,0.E+000,3.512815038853E-016)); +#19533 = PCURVE('',#18950,#19534); +#19534 = DEFINITIONAL_REPRESENTATION('',(#19535),#19561); +#19535 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19536,#19537,#19538,#19539, + #19540,#19541,#19542,#19543,#19544,#19545,#19546,#19547,#19548, + #19549,#19550,#19551,#19552,#19553,#19554,#19555,#19556,#19557, + #19558,#19559,#19560),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.25,-0.227272727273,-0.204545454545, -0.181818181818,-0.159090909091,-0.136363636364,-0.113636363636, -9.090909090909E-002,-6.818181818182E-002,-4.545454545455E-002, @@ -21058,2866 +24047,2866 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.545454545455E-002,6.818181818182E-002,9.090909090909E-002, 0.113636363636,0.136363636364,0.159090909091,0.181818181818, 0.204545454545,0.227272727273,0.25),.UNSPECIFIED.); -#17144 = CARTESIAN_POINT('',(0.E+000,-0.25)); -#17145 = CARTESIAN_POINT('',(3.392348130799E-016,-0.242424242424)); -#17146 = CARTESIAN_POINT('',(6.553002370975E-016,-0.227272727273)); -#17147 = CARTESIAN_POINT('',(5.282660244145E-016,-0.204545454545)); -#17148 = CARTESIAN_POINT('',(5.6230473912E-016,-0.181818181818)); -#17149 = CARTESIAN_POINT('',(5.53184092981E-016,-0.159090909091)); -#17150 = CARTESIAN_POINT('',(5.556279628316E-016,-0.136363636364)); -#17151 = CARTESIAN_POINT('',(5.54973129568E-016,-0.113636363636)); -#17152 = CARTESIAN_POINT('',(5.551485927718E-016,-9.090909090909E-002)); -#17153 = CARTESIAN_POINT('',(5.551015732204E-016,-6.818181818182E-002)); -#17154 = CARTESIAN_POINT('',(5.55114188222E-016,-4.545454545455E-002)); -#17155 = CARTESIAN_POINT('',(5.55110747767E-016,-2.272727272727E-002)); -#17156 = CARTESIAN_POINT('',(5.551118945854E-016,4.890939284275E-016)); -#17157 = CARTESIAN_POINT('',(5.55110747767E-016,2.272727272727E-002)); -#17158 = CARTESIAN_POINT('',(5.55114188222E-016,4.545454545455E-002)); -#17159 = CARTESIAN_POINT('',(5.551015732204E-016,6.818181818182E-002)); -#17160 = CARTESIAN_POINT('',(5.551485927718E-016,9.090909090909E-002)); -#17161 = CARTESIAN_POINT('',(5.54973129568E-016,0.113636363636)); -#17162 = CARTESIAN_POINT('',(5.556279628316E-016,0.136363636364)); -#17163 = CARTESIAN_POINT('',(5.53184092981E-016,0.159090909091)); -#17164 = CARTESIAN_POINT('',(5.6230473912E-016,0.181818181818)); -#17165 = CARTESIAN_POINT('',(5.282660244145E-016,0.204545454545)); -#17166 = CARTESIAN_POINT('',(6.553002370975E-016,0.227272727273)); -#17167 = CARTESIAN_POINT('',(3.392348130799E-016,0.242424242424)); -#17168 = CARTESIAN_POINT('',(0.E+000,0.25)); -#17169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17170 = PCURVE('',#16525,#17171); -#17171 = DEFINITIONAL_REPRESENTATION('',(#17172),#17176); -#17172 = LINE('',#17173,#17174); -#17173 = CARTESIAN_POINT('',(0.E+000,0.43)); -#17174 = VECTOR('',#17175,1.); -#17175 = DIRECTION('',(-1.,0.E+000)); -#17176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17177 = ADVANCED_FACE('',(#17178),#16525,.T.); -#17178 = FACE_BOUND('',#17179,.T.); -#17179 = EDGE_LOOP('',(#17180,#17181,#17182,#17183)); -#17180 = ORIENTED_EDGE('',*,*,#17135,.T.); -#17181 = ORIENTED_EDGE('',*,*,#16509,.T.); -#17182 = ORIENTED_EDGE('',*,*,#16734,.T.); -#17183 = ORIENTED_EDGE('',*,*,#17184,.F.); -#17184 = EDGE_CURVE('',#17088,#16682,#17185,.T.); -#17185 = SURFACE_CURVE('',#17186,(#17190,#17197),.PCURVE_S1.); -#17186 = LINE('',#17187,#17188); -#17187 = CARTESIAN_POINT('',(-0.25,-0.24,9.999999999993E-003)); -#17188 = VECTOR('',#17189,1.); -#17189 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17190 = PCURVE('',#16525,#17191); -#17191 = DEFINITIONAL_REPRESENTATION('',(#17192),#17196); -#17192 = LINE('',#17193,#17194); -#17193 = CARTESIAN_POINT('',(0.25,0.E+000)); -#17194 = VECTOR('',#17195,1.); -#17195 = DIRECTION('',(0.E+000,-1.)); -#17196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17197 = PCURVE('',#16722,#17198); -#17198 = DEFINITIONAL_REPRESENTATION('',(#17199),#17203); -#17199 = LINE('',#17200,#17201); -#17200 = CARTESIAN_POINT('',(-0.29,0.E+000)); -#17201 = VECTOR('',#17202,1.); -#17202 = DIRECTION('',(0.E+000,-1.)); -#17203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17204 = ADVANCED_FACE('',(#17205),#16722,.T.); -#17205 = FACE_BOUND('',#17206,.T.); -#17206 = EDGE_LOOP('',(#17207,#17208,#17209,#17210,#17211,#17212,#17213, - #17214)); -#17207 = ORIENTED_EDGE('',*,*,#17087,.T.); -#17208 = ORIENTED_EDGE('',*,*,#17184,.T.); -#17209 = ORIENTED_EDGE('',*,*,#16681,.T.); -#17210 = ORIENTED_EDGE('',*,*,#16824,.T.); -#17211 = ORIENTED_EDGE('',*,*,#16872,.T.); -#17212 = ORIENTED_EDGE('',*,*,#16921,.T.); -#17213 = ORIENTED_EDGE('',*,*,#16991,.T.); -#17214 = ORIENTED_EDGE('',*,*,#17063,.T.); -#17215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#17219)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#17216,#17217,#17218)) +#19536 = CARTESIAN_POINT('',(0.E+000,-0.25)); +#19537 = CARTESIAN_POINT('',(3.392348130799E-016,-0.242424242424)); +#19538 = CARTESIAN_POINT('',(6.553002370975E-016,-0.227272727273)); +#19539 = CARTESIAN_POINT('',(5.282660244145E-016,-0.204545454545)); +#19540 = CARTESIAN_POINT('',(5.6230473912E-016,-0.181818181818)); +#19541 = CARTESIAN_POINT('',(5.53184092981E-016,-0.159090909091)); +#19542 = CARTESIAN_POINT('',(5.556279628316E-016,-0.136363636364)); +#19543 = CARTESIAN_POINT('',(5.54973129568E-016,-0.113636363636)); +#19544 = CARTESIAN_POINT('',(5.551485927718E-016,-9.090909090909E-002)); +#19545 = CARTESIAN_POINT('',(5.551015732204E-016,-6.818181818182E-002)); +#19546 = CARTESIAN_POINT('',(5.55114188222E-016,-4.545454545455E-002)); +#19547 = CARTESIAN_POINT('',(5.55110747767E-016,-2.272727272727E-002)); +#19548 = CARTESIAN_POINT('',(5.551118945854E-016,4.890939284275E-016)); +#19549 = CARTESIAN_POINT('',(5.55110747767E-016,2.272727272727E-002)); +#19550 = CARTESIAN_POINT('',(5.55114188222E-016,4.545454545455E-002)); +#19551 = CARTESIAN_POINT('',(5.551015732204E-016,6.818181818182E-002)); +#19552 = CARTESIAN_POINT('',(5.551485927718E-016,9.090909090909E-002)); +#19553 = CARTESIAN_POINT('',(5.54973129568E-016,0.113636363636)); +#19554 = CARTESIAN_POINT('',(5.556279628316E-016,0.136363636364)); +#19555 = CARTESIAN_POINT('',(5.53184092981E-016,0.159090909091)); +#19556 = CARTESIAN_POINT('',(5.6230473912E-016,0.181818181818)); +#19557 = CARTESIAN_POINT('',(5.282660244145E-016,0.204545454545)); +#19558 = CARTESIAN_POINT('',(6.553002370975E-016,0.227272727273)); +#19559 = CARTESIAN_POINT('',(3.392348130799E-016,0.242424242424)); +#19560 = CARTESIAN_POINT('',(0.E+000,0.25)); +#19561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19562 = PCURVE('',#18917,#19563); +#19563 = DEFINITIONAL_REPRESENTATION('',(#19564),#19568); +#19564 = LINE('',#19565,#19566); +#19565 = CARTESIAN_POINT('',(0.E+000,0.43)); +#19566 = VECTOR('',#19567,1.); +#19567 = DIRECTION('',(-1.,0.E+000)); +#19568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19569 = ADVANCED_FACE('',(#19570),#18917,.T.); +#19570 = FACE_BOUND('',#19571,.T.); +#19571 = EDGE_LOOP('',(#19572,#19573,#19574,#19575)); +#19572 = ORIENTED_EDGE('',*,*,#19527,.T.); +#19573 = ORIENTED_EDGE('',*,*,#18901,.T.); +#19574 = ORIENTED_EDGE('',*,*,#19126,.T.); +#19575 = ORIENTED_EDGE('',*,*,#19576,.F.); +#19576 = EDGE_CURVE('',#19480,#19074,#19577,.T.); +#19577 = SURFACE_CURVE('',#19578,(#19582,#19589),.PCURVE_S1.); +#19578 = LINE('',#19579,#19580); +#19579 = CARTESIAN_POINT('',(-0.25,-0.24,9.999999999993E-003)); +#19580 = VECTOR('',#19581,1.); +#19581 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#19582 = PCURVE('',#18917,#19583); +#19583 = DEFINITIONAL_REPRESENTATION('',(#19584),#19588); +#19584 = LINE('',#19585,#19586); +#19585 = CARTESIAN_POINT('',(0.25,0.E+000)); +#19586 = VECTOR('',#19587,1.); +#19587 = DIRECTION('',(0.E+000,-1.)); +#19588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19589 = PCURVE('',#19114,#19590); +#19590 = DEFINITIONAL_REPRESENTATION('',(#19591),#19595); +#19591 = LINE('',#19592,#19593); +#19592 = CARTESIAN_POINT('',(-0.29,0.E+000)); +#19593 = VECTOR('',#19594,1.); +#19594 = DIRECTION('',(0.E+000,-1.)); +#19595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19596 = ADVANCED_FACE('',(#19597),#19114,.T.); +#19597 = FACE_BOUND('',#19598,.T.); +#19598 = EDGE_LOOP('',(#19599,#19600,#19601,#19602,#19603,#19604,#19605, + #19606)); +#19599 = ORIENTED_EDGE('',*,*,#19479,.T.); +#19600 = ORIENTED_EDGE('',*,*,#19576,.T.); +#19601 = ORIENTED_EDGE('',*,*,#19073,.T.); +#19602 = ORIENTED_EDGE('',*,*,#19216,.T.); +#19603 = ORIENTED_EDGE('',*,*,#19264,.T.); +#19604 = ORIENTED_EDGE('',*,*,#19313,.T.); +#19605 = ORIENTED_EDGE('',*,*,#19383,.T.); +#19606 = ORIENTED_EDGE('',*,*,#19455,.T.); +#19607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#19611)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#19608,#19609,#19610)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#17216 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#17217 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#17218 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#17219 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#17216, +#19608 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#19609 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#19610 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#19611 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#19608, 'distance_accuracy_value','confusion accuracy'); -#17220 = SHAPE_DEFINITION_REPRESENTATION(#17221,#16380); -#17221 = PRODUCT_DEFINITION_SHAPE('','',#17222); -#17222 = PRODUCT_DEFINITION('design','',#17223,#17226); -#17223 = PRODUCT_DEFINITION_FORMATION('','',#17224); -#17224 = PRODUCT('User_Library-V0402HD_K_X_F6rper_1', - 'User_Library-V0402HD_K_X_F6rper_1','',(#17225)); -#17225 = PRODUCT_CONTEXT('',#2,'mechanical'); -#17226 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#17227 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17228,#17230); -#17228 = ( REPRESENTATION_RELATIONSHIP('','',#16380,#11881) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17229) +#19612 = SHAPE_DEFINITION_REPRESENTATION(#19613,#18772); +#19613 = PRODUCT_DEFINITION_SHAPE('','',#19614); +#19614 = PRODUCT_DEFINITION('design','',#19615,#19618); +#19615 = PRODUCT_DEFINITION_FORMATION('','',#19616); +#19616 = PRODUCT('User_Library-V0402HD_K_X_F6rper_1', + 'User_Library-V0402HD_K_X_F6rper_1','',(#19617)); +#19617 = PRODUCT_CONTEXT('',#2,'mechanical'); +#19618 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#19619 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#19620,#19622); +#19620 = ( REPRESENTATION_RELATIONSHIP('','',#18772,#14273) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#19621) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17229 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11886); -#17230 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17231); -#17231 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('153','','',#11876,#17222,$); -#17232 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#17224)); -#17233 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17234,#17236); -#17234 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#11864) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17235) +#19621 = ITEM_DEFINED_TRANSFORMATION('','',#11,#14278); +#19622 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #19623); +#19623 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('254','','',#14268,#19614,$); +#19624 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#19616)); +#19625 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#19626,#19628); +#19626 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#14256) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#19627) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17235 = ITEM_DEFINED_TRANSFORMATION('','',#11,#11865); -#17236 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17237); -#17237 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('154','=>[0:1:1:18]','',#11859, - #11876,$); -#17238 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11878)); -#17239 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17240,#17242); -#17240 = ( REPRESENTATION_RELATIONSHIP('','',#11864,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17241) +#19627 = ITEM_DEFINED_TRANSFORMATION('','',#11,#14257); +#19628 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #19629); +#19629 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('255','=>[0:1:1:18]','',#14251, + #14268,$); +#19630 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#14270)); +#19631 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#19632,#19634); +#19632 = ( REPRESENTATION_RELATIONSHIP('','',#14256,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#19633) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17241 = ITEM_DEFINED_TRANSFORMATION('','',#11,#43); -#17242 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17243); -#17243 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('155','=>[0:1:1:17]','',#5, - #11859,$); -#17244 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#11861)); -#17245 = SHAPE_DEFINITION_REPRESENTATION(#17246,#17252); -#17246 = PRODUCT_DEFINITION_SHAPE('','',#17247); -#17247 = PRODUCT_DEFINITION('design','',#17248,#17251); -#17248 = PRODUCT_DEFINITION_FORMATION('','',#17249); -#17249 = PRODUCT('X1','X1','',(#17250)); -#17250 = PRODUCT_CONTEXT('',#2,'mechanical'); -#17251 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#17252 = SHAPE_REPRESENTATION('',(#11,#17253,#17257),#17261); -#17253 = AXIS2_PLACEMENT_3D('',#17254,#17255,#17256); -#17254 = CARTESIAN_POINT('',(25.019,15.621,1.27E-002)); -#17255 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17256 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17257 = AXIS2_PLACEMENT_3D('',#17258,#17259,#17260); -#17258 = CARTESIAN_POINT('',(25.019,15.621,1.27E-002)); -#17259 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17260 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#17265)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#17262,#17263,#17264)) +#19633 = ITEM_DEFINED_TRANSFORMATION('','',#11,#43); +#19634 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #19635); +#19635 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('256','=>[0:1:1:17]','',#5, + #14251,$); +#19636 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#14253)); +#19637 = SHAPE_DEFINITION_REPRESENTATION(#19638,#19644); +#19638 = PRODUCT_DEFINITION_SHAPE('','',#19639); +#19639 = PRODUCT_DEFINITION('design','',#19640,#19643); +#19640 = PRODUCT_DEFINITION_FORMATION('','',#19641); +#19641 = PRODUCT('X1','X1','',(#19642)); +#19642 = PRODUCT_CONTEXT('',#2,'mechanical'); +#19643 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#19644 = SHAPE_REPRESENTATION('',(#11,#19645,#19649),#19653); +#19645 = AXIS2_PLACEMENT_3D('',#19646,#19647,#19648); +#19646 = CARTESIAN_POINT('',(25.019,15.621,1.27E-002)); +#19647 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19648 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19649 = AXIS2_PLACEMENT_3D('',#19650,#19651,#19652); +#19650 = CARTESIAN_POINT('',(25.019,15.621,1.27E-002)); +#19651 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19652 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#19657)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#19654,#19655,#19656)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#17262 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#17263 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#17264 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#17265 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#17262, +#19654 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#19655 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#19656 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#19657 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#19654, 'distance_accuracy_value','confusion accuracy'); -#17266 = SHAPE_DEFINITION_REPRESENTATION(#17267,#17273); -#17267 = PRODUCT_DEFINITION_SHAPE('','',#17268); -#17268 = PRODUCT_DEFINITION('design','',#17269,#17272); -#17269 = PRODUCT_DEFINITION_FORMATION('','',#17270); -#17270 = PRODUCT('622926752','622926752','',(#17271)); -#17271 = PRODUCT_CONTEXT('',#2,'mechanical'); -#17272 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#17273 = SHAPE_REPRESENTATION('',(#11,#17274),#17278); -#17274 = AXIS2_PLACEMENT_3D('',#17275,#17276,#17277); -#17275 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#17276 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17277 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#17282)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#17279,#17280,#17281)) +#19658 = SHAPE_DEFINITION_REPRESENTATION(#19659,#19665); +#19659 = PRODUCT_DEFINITION_SHAPE('','',#19660); +#19660 = PRODUCT_DEFINITION('design','',#19661,#19664); +#19661 = PRODUCT_DEFINITION_FORMATION('','',#19662); +#19662 = PRODUCT('549162144','549162144','',(#19663)); +#19663 = PRODUCT_CONTEXT('',#2,'mechanical'); +#19664 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#19665 = SHAPE_REPRESENTATION('',(#11,#19666),#19670); +#19666 = AXIS2_PLACEMENT_3D('',#19667,#19668,#19669); +#19667 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#19668 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19669 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#19674)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#19671,#19672,#19673)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#17279 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#17280 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#17281 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#17282 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#17279, +#19671 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#19672 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#19673 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#19674 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#19671, 'distance_accuracy_value','confusion accuracy'); -#17283 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#17284),#17614); -#17284 = MANIFOLD_SOLID_BREP('',#17285); -#17285 = CLOSED_SHELL('',(#17286,#17406,#17482,#17553,#17600,#17607)); -#17286 = ADVANCED_FACE('',(#17287),#17301,.T.); -#17287 = FACE_BOUND('',#17288,.T.); -#17288 = EDGE_LOOP('',(#17289,#17324,#17352,#17380)); -#17289 = ORIENTED_EDGE('',*,*,#17290,.T.); -#17290 = EDGE_CURVE('',#17291,#17293,#17295,.T.); -#17291 = VERTEX_POINT('',#17292); -#17292 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); -#17293 = VERTEX_POINT('',#17294); -#17294 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); -#17295 = SURFACE_CURVE('',#17296,(#17300,#17312),.PCURVE_S1.); -#17296 = LINE('',#17297,#17298); -#17297 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); -#17298 = VECTOR('',#17299,1.); -#17299 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17300 = PCURVE('',#17301,#17306); -#17301 = PLANE('',#17302); -#17302 = AXIS2_PLACEMENT_3D('',#17303,#17304,#17305); -#17303 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); -#17304 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17305 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17306 = DEFINITIONAL_REPRESENTATION('',(#17307),#17311); -#17307 = LINE('',#17308,#17309); -#17308 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17309 = VECTOR('',#17310,1.); -#17310 = DIRECTION('',(0.E+000,-1.)); -#17311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17312 = PCURVE('',#17313,#17318); -#17313 = PLANE('',#17314); -#17314 = AXIS2_PLACEMENT_3D('',#17315,#17316,#17317); -#17315 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); -#17316 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17317 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17318 = DEFINITIONAL_REPRESENTATION('',(#17319),#17323); -#17319 = LINE('',#17320,#17321); -#17320 = CARTESIAN_POINT('',(3.2004,0.E+000)); -#17321 = VECTOR('',#17322,1.); -#17322 = DIRECTION('',(0.E+000,-1.)); -#17323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17324 = ORIENTED_EDGE('',*,*,#17325,.T.); -#17325 = EDGE_CURVE('',#17293,#17326,#17328,.T.); -#17326 = VERTEX_POINT('',#17327); -#17327 = CARTESIAN_POINT('',(0.6604,1.6002,0.6)); -#17328 = SURFACE_CURVE('',#17329,(#17333,#17340),.PCURVE_S1.); -#17329 = LINE('',#17330,#17331); -#17330 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); -#17331 = VECTOR('',#17332,1.); -#17332 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17333 = PCURVE('',#17301,#17334); -#17334 = DEFINITIONAL_REPRESENTATION('',(#17335),#17339); -#17335 = LINE('',#17336,#17337); -#17336 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#17337 = VECTOR('',#17338,1.); -#17338 = DIRECTION('',(1.,0.E+000)); -#17339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17340 = PCURVE('',#17341,#17346); -#17341 = PLANE('',#17342); -#17342 = AXIS2_PLACEMENT_3D('',#17343,#17344,#17345); -#17343 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); -#17344 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17345 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17346 = DEFINITIONAL_REPRESENTATION('',(#17347),#17351); -#17347 = LINE('',#17348,#17349); -#17348 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17349 = VECTOR('',#17350,1.); -#17350 = DIRECTION('',(1.,0.E+000)); -#17351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17352 = ORIENTED_EDGE('',*,*,#17353,.F.); -#17353 = EDGE_CURVE('',#17354,#17326,#17356,.T.); -#17354 = VERTEX_POINT('',#17355); -#17355 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); -#17356 = SURFACE_CURVE('',#17357,(#17361,#17368),.PCURVE_S1.); -#17357 = LINE('',#17358,#17359); -#17358 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); -#17359 = VECTOR('',#17360,1.); -#17360 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17361 = PCURVE('',#17301,#17362); -#17362 = DEFINITIONAL_REPRESENTATION('',(#17363),#17367); -#17363 = LINE('',#17364,#17365); -#17364 = CARTESIAN_POINT('',(1.3208,0.E+000)); -#17365 = VECTOR('',#17366,1.); -#17366 = DIRECTION('',(0.E+000,-1.)); -#17367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#19675 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#19676),#20006); +#19676 = MANIFOLD_SOLID_BREP('',#19677); +#19677 = CLOSED_SHELL('',(#19678,#19798,#19874,#19945,#19992,#19999)); +#19678 = ADVANCED_FACE('',(#19679),#19693,.T.); +#19679 = FACE_BOUND('',#19680,.T.); +#19680 = EDGE_LOOP('',(#19681,#19716,#19744,#19772)); +#19681 = ORIENTED_EDGE('',*,*,#19682,.T.); +#19682 = EDGE_CURVE('',#19683,#19685,#19687,.T.); +#19683 = VERTEX_POINT('',#19684); +#19684 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); +#19685 = VERTEX_POINT('',#19686); +#19686 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); +#19687 = SURFACE_CURVE('',#19688,(#19692,#19704),.PCURVE_S1.); +#19688 = LINE('',#19689,#19690); +#19689 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); +#19690 = VECTOR('',#19691,1.); +#19691 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19692 = PCURVE('',#19693,#19698); +#19693 = PLANE('',#19694); +#19694 = AXIS2_PLACEMENT_3D('',#19695,#19696,#19697); +#19695 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); +#19696 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19697 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19698 = DEFINITIONAL_REPRESENTATION('',(#19699),#19703); +#19699 = LINE('',#19700,#19701); +#19700 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19701 = VECTOR('',#19702,1.); +#19702 = DIRECTION('',(0.E+000,-1.)); +#19703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19704 = PCURVE('',#19705,#19710); +#19705 = PLANE('',#19706); +#19706 = AXIS2_PLACEMENT_3D('',#19707,#19708,#19709); +#19707 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); +#19708 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#19709 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19710 = DEFINITIONAL_REPRESENTATION('',(#19711),#19715); +#19711 = LINE('',#19712,#19713); +#19712 = CARTESIAN_POINT('',(3.2004,0.E+000)); +#19713 = VECTOR('',#19714,1.); +#19714 = DIRECTION('',(0.E+000,-1.)); +#19715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19716 = ORIENTED_EDGE('',*,*,#19717,.T.); +#19717 = EDGE_CURVE('',#19685,#19718,#19720,.T.); +#19718 = VERTEX_POINT('',#19719); +#19719 = CARTESIAN_POINT('',(0.6604,1.6002,0.6)); +#19720 = SURFACE_CURVE('',#19721,(#19725,#19732),.PCURVE_S1.); +#19721 = LINE('',#19722,#19723); +#19722 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); +#19723 = VECTOR('',#19724,1.); +#19724 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19725 = PCURVE('',#19693,#19726); +#19726 = DEFINITIONAL_REPRESENTATION('',(#19727),#19731); +#19727 = LINE('',#19728,#19729); +#19728 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#19729 = VECTOR('',#19730,1.); +#19730 = DIRECTION('',(1.,0.E+000)); +#19731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19732 = PCURVE('',#19733,#19738); +#19733 = PLANE('',#19734); +#19734 = AXIS2_PLACEMENT_3D('',#19735,#19736,#19737); +#19735 = CARTESIAN_POINT('',(-0.6604,1.6002,0.6)); +#19736 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19737 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19738 = DEFINITIONAL_REPRESENTATION('',(#19739),#19743); +#19739 = LINE('',#19740,#19741); +#19740 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19741 = VECTOR('',#19742,1.); +#19742 = DIRECTION('',(1.,0.E+000)); +#19743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19744 = ORIENTED_EDGE('',*,*,#19745,.F.); +#19745 = EDGE_CURVE('',#19746,#19718,#19748,.T.); +#19746 = VERTEX_POINT('',#19747); +#19747 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); +#19748 = SURFACE_CURVE('',#19749,(#19753,#19760),.PCURVE_S1.); +#19749 = LINE('',#19750,#19751); +#19750 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); +#19751 = VECTOR('',#19752,1.); +#19752 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19753 = PCURVE('',#19693,#19754); +#19754 = DEFINITIONAL_REPRESENTATION('',(#19755),#19759); +#19755 = LINE('',#19756,#19757); +#19756 = CARTESIAN_POINT('',(1.3208,0.E+000)); +#19757 = VECTOR('',#19758,1.); +#19758 = DIRECTION('',(0.E+000,-1.)); +#19759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19760 = PCURVE('',#19761,#19766); +#19761 = PLANE('',#19762); +#19762 = AXIS2_PLACEMENT_3D('',#19763,#19764,#19765); +#19763 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); +#19764 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19765 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#19766 = DEFINITIONAL_REPRESENTATION('',(#19767),#19771); +#19767 = LINE('',#19768,#19769); +#19768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19769 = VECTOR('',#19770,1.); +#19770 = DIRECTION('',(0.E+000,-1.)); +#19771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19772 = ORIENTED_EDGE('',*,*,#19773,.F.); +#19773 = EDGE_CURVE('',#19683,#19746,#19774,.T.); +#19774 = SURFACE_CURVE('',#19775,(#19779,#19786),.PCURVE_S1.); +#19775 = LINE('',#19776,#19777); +#19776 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); +#19777 = VECTOR('',#19778,1.); +#19778 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19779 = PCURVE('',#19693,#19780); +#19780 = DEFINITIONAL_REPRESENTATION('',(#19781),#19785); +#19781 = LINE('',#19782,#19783); +#19782 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19783 = VECTOR('',#19784,1.); +#19784 = DIRECTION('',(1.,0.E+000)); +#19785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19786 = PCURVE('',#19787,#19792); +#19787 = PLANE('',#19788); +#19788 = AXIS2_PLACEMENT_3D('',#19789,#19790,#19791); +#19789 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); +#19790 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19791 = DIRECTION('',(1.,0.E+000,0.E+000)); +#19792 = DEFINITIONAL_REPRESENTATION('',(#19793),#19797); +#19793 = LINE('',#19794,#19795); +#19794 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19795 = VECTOR('',#19796,1.); +#19796 = DIRECTION('',(1.,0.E+000)); +#19797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19798 = ADVANCED_FACE('',(#19799),#19761,.T.); +#19799 = FACE_BOUND('',#19800,.T.); +#19800 = EDGE_LOOP('',(#19801,#19802,#19825,#19853)); +#19801 = ORIENTED_EDGE('',*,*,#19745,.T.); +#19802 = ORIENTED_EDGE('',*,*,#19803,.T.); +#19803 = EDGE_CURVE('',#19718,#19804,#19806,.T.); +#19804 = VERTEX_POINT('',#19805); +#19805 = CARTESIAN_POINT('',(0.6604,-1.6002,0.6)); +#19806 = SURFACE_CURVE('',#19807,(#19811,#19818),.PCURVE_S1.); +#19807 = LINE('',#19808,#19809); +#19808 = CARTESIAN_POINT('',(0.6604,1.6002,0.6)); +#19809 = VECTOR('',#19810,1.); +#19810 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#19811 = PCURVE('',#19761,#19812); +#19812 = DEFINITIONAL_REPRESENTATION('',(#19813),#19817); +#19813 = LINE('',#19814,#19815); +#19814 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#19815 = VECTOR('',#19816,1.); +#19816 = DIRECTION('',(1.,0.E+000)); +#19817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19818 = PCURVE('',#19733,#19819); +#19819 = DEFINITIONAL_REPRESENTATION('',(#19820),#19824); +#19820 = LINE('',#19821,#19822); +#19821 = CARTESIAN_POINT('',(1.3208,0.E+000)); +#19822 = VECTOR('',#19823,1.); +#19823 = DIRECTION('',(0.E+000,-1.)); +#19824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19825 = ORIENTED_EDGE('',*,*,#19826,.F.); +#19826 = EDGE_CURVE('',#19827,#19804,#19829,.T.); +#19827 = VERTEX_POINT('',#19828); +#19828 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); +#19829 = SURFACE_CURVE('',#19830,(#19834,#19841),.PCURVE_S1.); +#19830 = LINE('',#19831,#19832); +#19831 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); +#19832 = VECTOR('',#19833,1.); +#19833 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19834 = PCURVE('',#19761,#19835); +#19835 = DEFINITIONAL_REPRESENTATION('',(#19836),#19840); +#19836 = LINE('',#19837,#19838); +#19837 = CARTESIAN_POINT('',(3.2004,0.E+000)); +#19838 = VECTOR('',#19839,1.); +#19839 = DIRECTION('',(0.E+000,-1.)); +#19840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19841 = PCURVE('',#19842,#19847); +#19842 = PLANE('',#19843); +#19843 = AXIS2_PLACEMENT_3D('',#19844,#19845,#19846); +#19844 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); +#19845 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#19846 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#19847 = DEFINITIONAL_REPRESENTATION('',(#19848),#19852); +#19848 = LINE('',#19849,#19850); +#19849 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19850 = VECTOR('',#19851,1.); +#19851 = DIRECTION('',(0.E+000,-1.)); +#19852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19853 = ORIENTED_EDGE('',*,*,#19854,.F.); +#19854 = EDGE_CURVE('',#19746,#19827,#19855,.T.); +#19855 = SURFACE_CURVE('',#19856,(#19860,#19867),.PCURVE_S1.); +#19856 = LINE('',#19857,#19858); +#19857 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); +#19858 = VECTOR('',#19859,1.); +#19859 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#19860 = PCURVE('',#19761,#19861); +#19861 = DEFINITIONAL_REPRESENTATION('',(#19862),#19866); +#19862 = LINE('',#19863,#19864); +#19863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19864 = VECTOR('',#19865,1.); +#19865 = DIRECTION('',(1.,0.E+000)); +#19866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19867 = PCURVE('',#19787,#19868); +#19868 = DEFINITIONAL_REPRESENTATION('',(#19869),#19873); +#19869 = LINE('',#19870,#19871); +#19870 = CARTESIAN_POINT('',(1.3208,0.E+000)); +#19871 = VECTOR('',#19872,1.); +#19872 = DIRECTION('',(0.E+000,-1.)); +#19873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19874 = ADVANCED_FACE('',(#19875),#19842,.T.); +#19875 = FACE_BOUND('',#19876,.T.); +#19876 = EDGE_LOOP('',(#19877,#19878,#19901,#19924)); +#19877 = ORIENTED_EDGE('',*,*,#19826,.T.); +#19878 = ORIENTED_EDGE('',*,*,#19879,.T.); +#19879 = EDGE_CURVE('',#19804,#19880,#19882,.T.); +#19880 = VERTEX_POINT('',#19881); +#19881 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.6)); +#19882 = SURFACE_CURVE('',#19883,(#19887,#19894),.PCURVE_S1.); +#19883 = LINE('',#19884,#19885); +#19884 = CARTESIAN_POINT('',(0.6604,-1.6002,0.6)); +#19885 = VECTOR('',#19886,1.); +#19886 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#19887 = PCURVE('',#19842,#19888); +#19888 = DEFINITIONAL_REPRESENTATION('',(#19889),#19893); +#19889 = LINE('',#19890,#19891); +#19890 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#19891 = VECTOR('',#19892,1.); +#19892 = DIRECTION('',(1.,0.E+000)); +#19893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19894 = PCURVE('',#19733,#19895); +#19895 = DEFINITIONAL_REPRESENTATION('',(#19896),#19900); +#19896 = LINE('',#19897,#19898); +#19897 = CARTESIAN_POINT('',(1.3208,-3.2004)); +#19898 = VECTOR('',#19899,1.); +#19899 = DIRECTION('',(-1.,0.E+000)); +#19900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#17368 = PCURVE('',#17369,#17374); -#17369 = PLANE('',#17370); -#17370 = AXIS2_PLACEMENT_3D('',#17371,#17372,#17373); -#17371 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); -#17372 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17373 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17374 = DEFINITIONAL_REPRESENTATION('',(#17375),#17379); -#17375 = LINE('',#17376,#17377); -#17376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17377 = VECTOR('',#17378,1.); -#17378 = DIRECTION('',(0.E+000,-1.)); -#17379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17380 = ORIENTED_EDGE('',*,*,#17381,.F.); -#17381 = EDGE_CURVE('',#17291,#17354,#17382,.T.); -#17382 = SURFACE_CURVE('',#17383,(#17387,#17394),.PCURVE_S1.); -#17383 = LINE('',#17384,#17385); -#17384 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); -#17385 = VECTOR('',#17386,1.); -#17386 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17387 = PCURVE('',#17301,#17388); -#17388 = DEFINITIONAL_REPRESENTATION('',(#17389),#17393); -#17389 = LINE('',#17390,#17391); -#17390 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17391 = VECTOR('',#17392,1.); -#17392 = DIRECTION('',(1.,0.E+000)); -#17393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17394 = PCURVE('',#17395,#17400); -#17395 = PLANE('',#17396); -#17396 = AXIS2_PLACEMENT_3D('',#17397,#17398,#17399); -#17397 = CARTESIAN_POINT('',(-0.6604,1.6002,0.E+000)); -#17398 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17399 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17400 = DEFINITIONAL_REPRESENTATION('',(#17401),#17405); -#17401 = LINE('',#17402,#17403); -#17402 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17403 = VECTOR('',#17404,1.); -#17404 = DIRECTION('',(1.,0.E+000)); -#17405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17406 = ADVANCED_FACE('',(#17407),#17369,.T.); -#17407 = FACE_BOUND('',#17408,.T.); -#17408 = EDGE_LOOP('',(#17409,#17410,#17433,#17461)); -#17409 = ORIENTED_EDGE('',*,*,#17353,.T.); -#17410 = ORIENTED_EDGE('',*,*,#17411,.T.); -#17411 = EDGE_CURVE('',#17326,#17412,#17414,.T.); -#17412 = VERTEX_POINT('',#17413); -#17413 = CARTESIAN_POINT('',(0.6604,-1.6002,0.6)); -#17414 = SURFACE_CURVE('',#17415,(#17419,#17426),.PCURVE_S1.); -#17415 = LINE('',#17416,#17417); -#17416 = CARTESIAN_POINT('',(0.6604,1.6002,0.6)); -#17417 = VECTOR('',#17418,1.); -#17418 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17419 = PCURVE('',#17369,#17420); -#17420 = DEFINITIONAL_REPRESENTATION('',(#17421),#17425); -#17421 = LINE('',#17422,#17423); -#17422 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#17423 = VECTOR('',#17424,1.); -#17424 = DIRECTION('',(1.,0.E+000)); -#17425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17426 = PCURVE('',#17341,#17427); -#17427 = DEFINITIONAL_REPRESENTATION('',(#17428),#17432); -#17428 = LINE('',#17429,#17430); -#17429 = CARTESIAN_POINT('',(1.3208,0.E+000)); -#17430 = VECTOR('',#17431,1.); -#17431 = DIRECTION('',(0.E+000,-1.)); -#17432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17433 = ORIENTED_EDGE('',*,*,#17434,.F.); -#17434 = EDGE_CURVE('',#17435,#17412,#17437,.T.); -#17435 = VERTEX_POINT('',#17436); -#17436 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); -#17437 = SURFACE_CURVE('',#17438,(#17442,#17449),.PCURVE_S1.); -#17438 = LINE('',#17439,#17440); -#17439 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); -#17440 = VECTOR('',#17441,1.); -#17441 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17442 = PCURVE('',#17369,#17443); -#17443 = DEFINITIONAL_REPRESENTATION('',(#17444),#17448); -#17444 = LINE('',#17445,#17446); -#17445 = CARTESIAN_POINT('',(3.2004,0.E+000)); -#17446 = VECTOR('',#17447,1.); -#17447 = DIRECTION('',(0.E+000,-1.)); -#17448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17449 = PCURVE('',#17450,#17455); -#17450 = PLANE('',#17451); -#17451 = AXIS2_PLACEMENT_3D('',#17452,#17453,#17454); -#17452 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); -#17453 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17454 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17455 = DEFINITIONAL_REPRESENTATION('',(#17456),#17460); -#17456 = LINE('',#17457,#17458); -#17457 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17458 = VECTOR('',#17459,1.); -#17459 = DIRECTION('',(0.E+000,-1.)); -#17460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17461 = ORIENTED_EDGE('',*,*,#17462,.F.); -#17462 = EDGE_CURVE('',#17354,#17435,#17463,.T.); -#17463 = SURFACE_CURVE('',#17464,(#17468,#17475),.PCURVE_S1.); -#17464 = LINE('',#17465,#17466); -#17465 = CARTESIAN_POINT('',(0.6604,1.6002,0.E+000)); -#17466 = VECTOR('',#17467,1.); -#17467 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17468 = PCURVE('',#17369,#17469); -#17469 = DEFINITIONAL_REPRESENTATION('',(#17470),#17474); -#17470 = LINE('',#17471,#17472); -#17471 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17472 = VECTOR('',#17473,1.); -#17473 = DIRECTION('',(1.,0.E+000)); -#17474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17475 = PCURVE('',#17395,#17476); -#17476 = DEFINITIONAL_REPRESENTATION('',(#17477),#17481); -#17477 = LINE('',#17478,#17479); -#17478 = CARTESIAN_POINT('',(1.3208,0.E+000)); -#17479 = VECTOR('',#17480,1.); -#17480 = DIRECTION('',(0.E+000,-1.)); -#17481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17482 = ADVANCED_FACE('',(#17483),#17450,.T.); -#17483 = FACE_BOUND('',#17484,.T.); -#17484 = EDGE_LOOP('',(#17485,#17486,#17509,#17532)); -#17485 = ORIENTED_EDGE('',*,*,#17434,.T.); -#17486 = ORIENTED_EDGE('',*,*,#17487,.T.); -#17487 = EDGE_CURVE('',#17412,#17488,#17490,.T.); -#17488 = VERTEX_POINT('',#17489); -#17489 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.6)); -#17490 = SURFACE_CURVE('',#17491,(#17495,#17502),.PCURVE_S1.); -#17491 = LINE('',#17492,#17493); -#17492 = CARTESIAN_POINT('',(0.6604,-1.6002,0.6)); -#17493 = VECTOR('',#17494,1.); -#17494 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17495 = PCURVE('',#17450,#17496); -#17496 = DEFINITIONAL_REPRESENTATION('',(#17497),#17501); -#17497 = LINE('',#17498,#17499); -#17498 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#17499 = VECTOR('',#17500,1.); -#17500 = DIRECTION('',(1.,0.E+000)); -#17501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17502 = PCURVE('',#17341,#17503); -#17503 = DEFINITIONAL_REPRESENTATION('',(#17504),#17508); -#17504 = LINE('',#17505,#17506); -#17505 = CARTESIAN_POINT('',(1.3208,-3.2004)); -#17506 = VECTOR('',#17507,1.); -#17507 = DIRECTION('',(-1.,0.E+000)); -#17508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17509 = ORIENTED_EDGE('',*,*,#17510,.F.); -#17510 = EDGE_CURVE('',#17511,#17488,#17513,.T.); -#17511 = VERTEX_POINT('',#17512); -#17512 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); -#17513 = SURFACE_CURVE('',#17514,(#17518,#17525),.PCURVE_S1.); -#17514 = LINE('',#17515,#17516); -#17515 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); -#17516 = VECTOR('',#17517,1.); -#17517 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17518 = PCURVE('',#17450,#17519); -#17519 = DEFINITIONAL_REPRESENTATION('',(#17520),#17524); -#17520 = LINE('',#17521,#17522); -#17521 = CARTESIAN_POINT('',(1.3208,0.E+000)); -#17522 = VECTOR('',#17523,1.); -#17523 = DIRECTION('',(0.E+000,-1.)); -#17524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17525 = PCURVE('',#17313,#17526); -#17526 = DEFINITIONAL_REPRESENTATION('',(#17527),#17531); -#17527 = LINE('',#17528,#17529); -#17528 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17529 = VECTOR('',#17530,1.); -#17530 = DIRECTION('',(0.E+000,-1.)); -#17531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17532 = ORIENTED_EDGE('',*,*,#17533,.F.); -#17533 = EDGE_CURVE('',#17435,#17511,#17534,.T.); -#17534 = SURFACE_CURVE('',#17535,(#17539,#17546),.PCURVE_S1.); -#17535 = LINE('',#17536,#17537); -#17536 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); -#17537 = VECTOR('',#17538,1.); -#17538 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17539 = PCURVE('',#17450,#17540); -#17540 = DEFINITIONAL_REPRESENTATION('',(#17541),#17545); -#17541 = LINE('',#17542,#17543); -#17542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17543 = VECTOR('',#17544,1.); -#17544 = DIRECTION('',(1.,0.E+000)); -#17545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17546 = PCURVE('',#17395,#17547); -#17547 = DEFINITIONAL_REPRESENTATION('',(#17548),#17552); -#17548 = LINE('',#17549,#17550); -#17549 = CARTESIAN_POINT('',(1.3208,-3.2004)); -#17550 = VECTOR('',#17551,1.); -#17551 = DIRECTION('',(-1.,0.E+000)); -#17552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17553 = ADVANCED_FACE('',(#17554),#17313,.T.); -#17554 = FACE_BOUND('',#17555,.T.); -#17555 = EDGE_LOOP('',(#17556,#17557,#17578,#17579)); -#17556 = ORIENTED_EDGE('',*,*,#17510,.T.); -#17557 = ORIENTED_EDGE('',*,*,#17558,.T.); -#17558 = EDGE_CURVE('',#17488,#17293,#17559,.T.); -#17559 = SURFACE_CURVE('',#17560,(#17564,#17571),.PCURVE_S1.); -#17560 = LINE('',#17561,#17562); -#17561 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.6)); -#17562 = VECTOR('',#17563,1.); -#17563 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17564 = PCURVE('',#17313,#17565); -#17565 = DEFINITIONAL_REPRESENTATION('',(#17566),#17570); -#17566 = LINE('',#17567,#17568); -#17567 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#17568 = VECTOR('',#17569,1.); -#17569 = DIRECTION('',(1.,0.E+000)); -#17570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17571 = PCURVE('',#17341,#17572); -#17572 = DEFINITIONAL_REPRESENTATION('',(#17573),#17577); -#17573 = LINE('',#17574,#17575); -#17574 = CARTESIAN_POINT('',(0.E+000,-3.2004)); -#17575 = VECTOR('',#17576,1.); -#17576 = DIRECTION('',(0.E+000,1.)); -#17577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17578 = ORIENTED_EDGE('',*,*,#17290,.F.); -#17579 = ORIENTED_EDGE('',*,*,#17580,.F.); -#17580 = EDGE_CURVE('',#17511,#17291,#17581,.T.); -#17581 = SURFACE_CURVE('',#17582,(#17586,#17593),.PCURVE_S1.); -#17582 = LINE('',#17583,#17584); -#17583 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); -#17584 = VECTOR('',#17585,1.); -#17585 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17586 = PCURVE('',#17313,#17587); -#17587 = DEFINITIONAL_REPRESENTATION('',(#17588),#17592); -#17588 = LINE('',#17589,#17590); -#17589 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17590 = VECTOR('',#17591,1.); -#17591 = DIRECTION('',(1.,0.E+000)); -#17592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17593 = PCURVE('',#17395,#17594); -#17594 = DEFINITIONAL_REPRESENTATION('',(#17595),#17599); -#17595 = LINE('',#17596,#17597); -#17596 = CARTESIAN_POINT('',(0.E+000,-3.2004)); -#17597 = VECTOR('',#17598,1.); -#17598 = DIRECTION('',(0.E+000,1.)); -#17599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17600 = ADVANCED_FACE('',(#17601),#17395,.F.); -#17601 = FACE_BOUND('',#17602,.T.); -#17602 = EDGE_LOOP('',(#17603,#17604,#17605,#17606)); -#17603 = ORIENTED_EDGE('',*,*,#17381,.T.); -#17604 = ORIENTED_EDGE('',*,*,#17462,.T.); -#17605 = ORIENTED_EDGE('',*,*,#17533,.T.); -#17606 = ORIENTED_EDGE('',*,*,#17580,.T.); -#17607 = ADVANCED_FACE('',(#17608),#17341,.T.); -#17608 = FACE_BOUND('',#17609,.F.); -#17609 = EDGE_LOOP('',(#17610,#17611,#17612,#17613)); -#17610 = ORIENTED_EDGE('',*,*,#17325,.T.); -#17611 = ORIENTED_EDGE('',*,*,#17411,.T.); -#17612 = ORIENTED_EDGE('',*,*,#17487,.T.); -#17613 = ORIENTED_EDGE('',*,*,#17558,.T.); -#17614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#17618)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#17615,#17616,#17617)) +#19901 = ORIENTED_EDGE('',*,*,#19902,.F.); +#19902 = EDGE_CURVE('',#19903,#19880,#19905,.T.); +#19903 = VERTEX_POINT('',#19904); +#19904 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); +#19905 = SURFACE_CURVE('',#19906,(#19910,#19917),.PCURVE_S1.); +#19906 = LINE('',#19907,#19908); +#19907 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); +#19908 = VECTOR('',#19909,1.); +#19909 = DIRECTION('',(0.E+000,0.E+000,1.)); +#19910 = PCURVE('',#19842,#19911); +#19911 = DEFINITIONAL_REPRESENTATION('',(#19912),#19916); +#19912 = LINE('',#19913,#19914); +#19913 = CARTESIAN_POINT('',(1.3208,0.E+000)); +#19914 = VECTOR('',#19915,1.); +#19915 = DIRECTION('',(0.E+000,-1.)); +#19916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19917 = PCURVE('',#19705,#19918); +#19918 = DEFINITIONAL_REPRESENTATION('',(#19919),#19923); +#19919 = LINE('',#19920,#19921); +#19920 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19921 = VECTOR('',#19922,1.); +#19922 = DIRECTION('',(0.E+000,-1.)); +#19923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19924 = ORIENTED_EDGE('',*,*,#19925,.F.); +#19925 = EDGE_CURVE('',#19827,#19903,#19926,.T.); +#19926 = SURFACE_CURVE('',#19927,(#19931,#19938),.PCURVE_S1.); +#19927 = LINE('',#19928,#19929); +#19928 = CARTESIAN_POINT('',(0.6604,-1.6002,0.E+000)); +#19929 = VECTOR('',#19930,1.); +#19930 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#19931 = PCURVE('',#19842,#19932); +#19932 = DEFINITIONAL_REPRESENTATION('',(#19933),#19937); +#19933 = LINE('',#19934,#19935); +#19934 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19935 = VECTOR('',#19936,1.); +#19936 = DIRECTION('',(1.,0.E+000)); +#19937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19938 = PCURVE('',#19787,#19939); +#19939 = DEFINITIONAL_REPRESENTATION('',(#19940),#19944); +#19940 = LINE('',#19941,#19942); +#19941 = CARTESIAN_POINT('',(1.3208,-3.2004)); +#19942 = VECTOR('',#19943,1.); +#19943 = DIRECTION('',(-1.,0.E+000)); +#19944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19945 = ADVANCED_FACE('',(#19946),#19705,.T.); +#19946 = FACE_BOUND('',#19947,.T.); +#19947 = EDGE_LOOP('',(#19948,#19949,#19970,#19971)); +#19948 = ORIENTED_EDGE('',*,*,#19902,.T.); +#19949 = ORIENTED_EDGE('',*,*,#19950,.T.); +#19950 = EDGE_CURVE('',#19880,#19685,#19951,.T.); +#19951 = SURFACE_CURVE('',#19952,(#19956,#19963),.PCURVE_S1.); +#19952 = LINE('',#19953,#19954); +#19953 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.6)); +#19954 = VECTOR('',#19955,1.); +#19955 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19956 = PCURVE('',#19705,#19957); +#19957 = DEFINITIONAL_REPRESENTATION('',(#19958),#19962); +#19958 = LINE('',#19959,#19960); +#19959 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#19960 = VECTOR('',#19961,1.); +#19961 = DIRECTION('',(1.,0.E+000)); +#19962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19963 = PCURVE('',#19733,#19964); +#19964 = DEFINITIONAL_REPRESENTATION('',(#19965),#19969); +#19965 = LINE('',#19966,#19967); +#19966 = CARTESIAN_POINT('',(0.E+000,-3.2004)); +#19967 = VECTOR('',#19968,1.); +#19968 = DIRECTION('',(0.E+000,1.)); +#19969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19970 = ORIENTED_EDGE('',*,*,#19682,.F.); +#19971 = ORIENTED_EDGE('',*,*,#19972,.F.); +#19972 = EDGE_CURVE('',#19903,#19683,#19973,.T.); +#19973 = SURFACE_CURVE('',#19974,(#19978,#19985),.PCURVE_S1.); +#19974 = LINE('',#19975,#19976); +#19975 = CARTESIAN_POINT('',(-0.6604,-1.6002,0.E+000)); +#19976 = VECTOR('',#19977,1.); +#19977 = DIRECTION('',(0.E+000,1.,0.E+000)); +#19978 = PCURVE('',#19705,#19979); +#19979 = DEFINITIONAL_REPRESENTATION('',(#19980),#19984); +#19980 = LINE('',#19981,#19982); +#19981 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#19982 = VECTOR('',#19983,1.); +#19983 = DIRECTION('',(1.,0.E+000)); +#19984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19985 = PCURVE('',#19787,#19986); +#19986 = DEFINITIONAL_REPRESENTATION('',(#19987),#19991); +#19987 = LINE('',#19988,#19989); +#19988 = CARTESIAN_POINT('',(0.E+000,-3.2004)); +#19989 = VECTOR('',#19990,1.); +#19990 = DIRECTION('',(0.E+000,1.)); +#19991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#19992 = ADVANCED_FACE('',(#19993),#19787,.F.); +#19993 = FACE_BOUND('',#19994,.T.); +#19994 = EDGE_LOOP('',(#19995,#19996,#19997,#19998)); +#19995 = ORIENTED_EDGE('',*,*,#19773,.T.); +#19996 = ORIENTED_EDGE('',*,*,#19854,.T.); +#19997 = ORIENTED_EDGE('',*,*,#19925,.T.); +#19998 = ORIENTED_EDGE('',*,*,#19972,.T.); +#19999 = ADVANCED_FACE('',(#20000),#19733,.T.); +#20000 = FACE_BOUND('',#20001,.F.); +#20001 = EDGE_LOOP('',(#20002,#20003,#20004,#20005)); +#20002 = ORIENTED_EDGE('',*,*,#19717,.T.); +#20003 = ORIENTED_EDGE('',*,*,#19803,.T.); +#20004 = ORIENTED_EDGE('',*,*,#19879,.T.); +#20005 = ORIENTED_EDGE('',*,*,#19950,.T.); +#20006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#20010)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#20007,#20008,#20009)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#17615 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#17616 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#17617 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#17618 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#17615, +#20007 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#20008 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#20009 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#20010 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#20007, 'distance_accuracy_value','confusion accuracy'); -#17619 = SHAPE_DEFINITION_REPRESENTATION(#17620,#17283); -#17620 = PRODUCT_DEFINITION_SHAPE('','',#17621); -#17621 = PRODUCT_DEFINITION('design','',#17622,#17625); -#17622 = PRODUCT_DEFINITION_FORMATION('','',#17623); -#17623 = PRODUCT('Extruded','Extruded','',(#17624)); -#17624 = PRODUCT_CONTEXT('',#2,'mechanical'); -#17625 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#17626 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17627,#17629); -#17627 = ( REPRESENTATION_RELATIONSHIP('','',#17283,#17273) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17628) +#20011 = SHAPE_DEFINITION_REPRESENTATION(#20012,#19675); +#20012 = PRODUCT_DEFINITION_SHAPE('','',#20013); +#20013 = PRODUCT_DEFINITION('design','',#20014,#20017); +#20014 = PRODUCT_DEFINITION_FORMATION('','',#20015); +#20015 = PRODUCT('Extruded','Extruded','',(#20016)); +#20016 = PRODUCT_CONTEXT('',#2,'mechanical'); +#20017 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#20018 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#20019,#20021); +#20019 = ( REPRESENTATION_RELATIONSHIP('','',#19675,#19665) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#20020) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17628 = ITEM_DEFINED_TRANSFORMATION('','',#11,#17274); -#17629 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17630); -#17630 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('156','=>[0:1:1:2]','',#17268, - #17621,$); -#17631 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#17623)); -#17632 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17633,#17635); -#17633 = ( REPRESENTATION_RELATIONSHIP('','',#17273,#17252) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17634) +#20020 = ITEM_DEFINED_TRANSFORMATION('','',#11,#19666); +#20021 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #20022); +#20022 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('257','=>[0:1:1:2]','',#19660, + #20013,$); +#20023 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#20015)); +#20024 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#20025,#20027); +#20025 = ( REPRESENTATION_RELATIONSHIP('','',#19665,#19644) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#20026) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17634 = ITEM_DEFINED_TRANSFORMATION('','',#11,#17253); -#17635 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17636); -#17636 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('157','=>[0:1:1:22]','',#17247, - #17268,$); -#17637 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#17270)); -#17638 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17639,#17641); -#17639 = ( REPRESENTATION_RELATIONSHIP('','',#17273,#17252) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17640) +#20026 = ITEM_DEFINED_TRANSFORMATION('','',#11,#19645); +#20027 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #20028); +#20028 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('258','=>[0:1:1:22]','',#19639, + #19660,$); +#20029 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#19662)); +#20030 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#20031,#20033); +#20031 = ( REPRESENTATION_RELATIONSHIP('','',#19665,#19644) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#20032) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17640 = ITEM_DEFINED_TRANSFORMATION('','',#11,#17257); -#17641 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17642); -#17642 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('158','=>[0:1:1:22]','',#17247, - #17268,$); -#17643 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#17644,#17646); -#17644 = ( REPRESENTATION_RELATIONSHIP('','',#17252,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#17645) +#20032 = ITEM_DEFINED_TRANSFORMATION('','',#11,#19649); +#20033 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #20034); +#20034 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('259','=>[0:1:1:22]','',#19639, + #19660,$); +#20035 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#20036,#20038); +#20036 = ( REPRESENTATION_RELATIONSHIP('','',#19644,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#20037) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#17645 = ITEM_DEFINED_TRANSFORMATION('','',#11,#47); -#17646 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #17647); -#17647 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('159','=>[0:1:1:21]','',#5, - #17247,$); -#17648 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#17249)); -#17649 = SHAPE_DEFINITION_REPRESENTATION(#17650,#17656); -#17650 = PRODUCT_DEFINITION_SHAPE('','',#17651); -#17651 = PRODUCT_DEFINITION('design','',#17652,#17655); -#17652 = PRODUCT_DEFINITION_FORMATION('','',#17653); -#17653 = PRODUCT('SKT1','SKT1','',(#17654)); -#17654 = PRODUCT_CONTEXT('',#2,'mechanical'); -#17655 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#17656 = SHAPE_REPRESENTATION('',(#11,#17657),#17661); -#17657 = AXIS2_PLACEMENT_3D('',#17658,#17659,#17660); -#17658 = CARTESIAN_POINT('',(66.28790146,31.6919991,-24.77838072)); -#17659 = DIRECTION('',(-1.224606353822E-016,1.,-2.334829378448E-016)); -#17660 = DIRECTION('',(-1.,-1.224606353822E-016,1.499660721822E-032)); -#17661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#17665)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#17662,#17663,#17664)) +#20037 = ITEM_DEFINED_TRANSFORMATION('','',#11,#47); +#20038 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #20039); +#20039 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('260','=>[0:1:1:21]','',#5, + #19639,$); +#20040 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#19641)); +#20041 = SHAPE_DEFINITION_REPRESENTATION(#20042,#20048); +#20042 = PRODUCT_DEFINITION_SHAPE('','',#20043); +#20043 = PRODUCT_DEFINITION('design','',#20044,#20047); +#20044 = PRODUCT_DEFINITION_FORMATION('','',#20045); +#20045 = PRODUCT('SKT1','SKT1','',(#20046)); +#20046 = PRODUCT_CONTEXT('',#2,'mechanical'); +#20047 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#20048 = SHAPE_REPRESENTATION('',(#11,#20049),#20053); +#20049 = AXIS2_PLACEMENT_3D('',#20050,#20051,#20052); +#20050 = CARTESIAN_POINT('',(66.28790146,31.6919991,-24.18910072)); +#20051 = DIRECTION('',(-1.224606353822E-016,1.,-2.334829378448E-016)); +#20052 = DIRECTION('',(-1.,-1.224606353822E-016,1.499660721822E-032)); +#20053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#20057)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#20054,#20055,#20056)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#17662 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#17663 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#17664 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#17665 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#17662, +#20054 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#20055 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#20056 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#20057 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#20054, 'distance_accuracy_value','confusion accuracy'); -#17666 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#17667),#21885); -#17667 = MANIFOLD_SOLID_BREP('',#17668); -#17668 = CLOSED_SHELL('',(#17669,#17894,#18104,#18314,#18519,#18639, - #18875,#18951,#19051,#19098,#19129,#19205,#19254,#19285,#19316, - #19347,#19374,#19494,#19610,#19709,#19808,#19907,#20006,#20106, - #20202,#20340,#20389,#20438,#20465,#20543,#20643,#20690,#20699, - #20726,#20855,#20946,#20953,#21044,#21051,#21057,#21106,#21199, - #21206,#21405,#21431,#21457,#21464,#21490,#21516,#21523,#21550, - #21557,#21658,#21767,#21815,#21864,#21871,#21878)); -#17669 = ADVANCED_FACE('',(#17670),#17684,.T.); -#17670 = FACE_BOUND('',#17671,.T.); -#17671 = EDGE_LOOP('',(#17672,#17706,#17734,#17762,#17790,#17818,#17841, - #17868)); -#17672 = ORIENTED_EDGE('',*,*,#17673,.F.); -#17673 = EDGE_CURVE('',#17674,#17676,#17678,.T.); -#17674 = VERTEX_POINT('',#17675); -#17675 = CARTESIAN_POINT('',(56.538908,22.495721,1.E-001)); -#17676 = VERTEX_POINT('',#17677); -#17677 = CARTESIAN_POINT('',(56.538908,22.145721,1.E-001)); -#17678 = SURFACE_CURVE('',#17679,(#17683,#17695),.PCURVE_S1.); -#17679 = LINE('',#17680,#17681); -#17680 = CARTESIAN_POINT('',(56.538908,22.495721,1.E-001)); -#17681 = VECTOR('',#17682,1.); -#17682 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17683 = PCURVE('',#17684,#17689); -#17684 = PLANE('',#17685); -#17685 = AXIS2_PLACEMENT_3D('',#17686,#17687,#17688); -#17686 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); -#17687 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17688 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17689 = DEFINITIONAL_REPRESENTATION('',(#17690),#17694); -#17690 = LINE('',#17691,#17692); -#17691 = CARTESIAN_POINT('',(-2.3,0.E+000)); -#17692 = VECTOR('',#17693,1.); -#17693 = DIRECTION('',(0.E+000,1.)); -#17694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17695 = PCURVE('',#17696,#17701); -#17696 = CYLINDRICAL_SURFACE('',#17697,0.3); -#17697 = AXIS2_PLACEMENT_3D('',#17698,#17699,#17700); -#17698 = CARTESIAN_POINT('',(56.238908,22.495721,1.E-001)); -#17699 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17700 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17701 = DEFINITIONAL_REPRESENTATION('',(#17702),#17705); -#17702 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17703,#17704),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#17703 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#17704 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#17705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17706 = ORIENTED_EDGE('',*,*,#17707,.T.); -#17707 = EDGE_CURVE('',#17674,#17708,#17710,.T.); -#17708 = VERTEX_POINT('',#17709); -#17709 = CARTESIAN_POINT('',(56.538908,22.495721,0.2)); -#17710 = SURFACE_CURVE('',#17711,(#17715,#17722),.PCURVE_S1.); -#17711 = LINE('',#17712,#17713); -#17712 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); -#17713 = VECTOR('',#17714,1.); -#17714 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17715 = PCURVE('',#17684,#17716); -#17716 = DEFINITIONAL_REPRESENTATION('',(#17717),#17721); -#17717 = LINE('',#17718,#17719); -#17718 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#17719 = VECTOR('',#17720,1.); -#17720 = DIRECTION('',(1.,0.E+000)); -#17721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17722 = PCURVE('',#17723,#17728); -#17723 = PLANE('',#17724); -#17724 = AXIS2_PLACEMENT_3D('',#17725,#17726,#17727); -#17725 = CARTESIAN_POINT('',(50.919956733961,22.495721,0.899011437739)); -#17726 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17727 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17728 = DEFINITIONAL_REPRESENTATION('',(#17729),#17733); -#17729 = LINE('',#17730,#17731); -#17730 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); -#17731 = VECTOR('',#17732,1.); -#17732 = DIRECTION('',(0.E+000,1.)); -#17733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17734 = ORIENTED_EDGE('',*,*,#17735,.F.); -#17735 = EDGE_CURVE('',#17736,#17708,#17738,.T.); -#17736 = VERTEX_POINT('',#17737); -#17737 = CARTESIAN_POINT('',(56.538908,22.345721,0.2)); -#17738 = SURFACE_CURVE('',#17739,(#17743,#17750),.PCURVE_S1.); -#17739 = LINE('',#17740,#17741); -#17740 = CARTESIAN_POINT('',(56.538908,22.495721,0.2)); -#17741 = VECTOR('',#17742,1.); -#17742 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17743 = PCURVE('',#17684,#17744); -#17744 = DEFINITIONAL_REPRESENTATION('',(#17745),#17749); -#17745 = LINE('',#17746,#17747); -#17746 = CARTESIAN_POINT('',(-2.2,0.E+000)); -#17747 = VECTOR('',#17748,1.); -#17748 = DIRECTION('',(0.E+000,-1.)); -#17749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17750 = PCURVE('',#17751,#17756); -#17751 = PLANE('',#17752); -#17752 = AXIS2_PLACEMENT_3D('',#17753,#17754,#17755); -#17753 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); -#17754 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#17755 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17756 = DEFINITIONAL_REPRESENTATION('',(#17757),#17761); -#17757 = LINE('',#17758,#17759); -#17758 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#17759 = VECTOR('',#17760,1.); -#17760 = DIRECTION('',(0.E+000,-1.)); -#17761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17762 = ORIENTED_EDGE('',*,*,#17763,.T.); -#17763 = EDGE_CURVE('',#17736,#17764,#17766,.T.); -#17764 = VERTEX_POINT('',#17765); -#17765 = CARTESIAN_POINT('',(56.538908,22.345721,2.)); -#17766 = SURFACE_CURVE('',#17767,(#17771,#17778),.PCURVE_S1.); -#17767 = LINE('',#17768,#17769); -#17768 = CARTESIAN_POINT('',(56.538908,22.345721,0.899011437739)); -#17769 = VECTOR('',#17770,1.); -#17770 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17771 = PCURVE('',#17684,#17772); -#17772 = DEFINITIONAL_REPRESENTATION('',(#17773),#17777); -#17773 = LINE('',#17774,#17775); -#17774 = CARTESIAN_POINT('',(-1.500988562261,0.15)); -#17775 = VECTOR('',#17776,1.); -#17776 = DIRECTION('',(1.,0.E+000)); -#17777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17778 = PCURVE('',#17779,#17784); -#17779 = PLANE('',#17780); -#17780 = AXIS2_PLACEMENT_3D('',#17781,#17782,#17783); -#17781 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); -#17782 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17783 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17784 = DEFINITIONAL_REPRESENTATION('',(#17785),#17789); -#17785 = LINE('',#17786,#17787); -#17786 = CARTESIAN_POINT('',(-5.618951266039,0.E+000)); -#17787 = VECTOR('',#17788,1.); -#17788 = DIRECTION('',(0.E+000,1.)); -#17789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17790 = ORIENTED_EDGE('',*,*,#17791,.F.); -#17791 = EDGE_CURVE('',#17792,#17764,#17794,.T.); -#17792 = VERTEX_POINT('',#17793); -#17793 = CARTESIAN_POINT('',(56.538908,22.495721,2.)); -#17794 = SURFACE_CURVE('',#17795,(#17799,#17806),.PCURVE_S1.); -#17795 = LINE('',#17796,#17797); -#17796 = CARTESIAN_POINT('',(56.538908,22.495721,2.)); -#17797 = VECTOR('',#17798,1.); -#17798 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17799 = PCURVE('',#17684,#17800); -#17800 = DEFINITIONAL_REPRESENTATION('',(#17801),#17805); -#17801 = LINE('',#17802,#17803); -#17802 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#17803 = VECTOR('',#17804,1.); -#17804 = DIRECTION('',(0.E+000,1.)); -#17805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17806 = PCURVE('',#17807,#17812); -#17807 = PLANE('',#17808); -#17808 = AXIS2_PLACEMENT_3D('',#17809,#17810,#17811); -#17809 = CARTESIAN_POINT('',(56.288908,22.495721,2.)); -#17810 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17811 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17812 = DEFINITIONAL_REPRESENTATION('',(#17813),#17817); -#17813 = LINE('',#17814,#17815); -#17814 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#17815 = VECTOR('',#17816,1.); -#17816 = DIRECTION('',(0.E+000,1.)); -#17817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17818 = ORIENTED_EDGE('',*,*,#17819,.T.); -#17819 = EDGE_CURVE('',#17792,#17820,#17822,.T.); -#17820 = VERTEX_POINT('',#17821); -#17821 = CARTESIAN_POINT('',(56.538908,22.495721,2.1)); -#17822 = SURFACE_CURVE('',#17823,(#17827,#17834),.PCURVE_S1.); -#17823 = LINE('',#17824,#17825); -#17824 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); -#17825 = VECTOR('',#17826,1.); -#17826 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17827 = PCURVE('',#17684,#17828); -#17828 = DEFINITIONAL_REPRESENTATION('',(#17829),#17833); -#17829 = LINE('',#17830,#17831); -#17830 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#17831 = VECTOR('',#17832,1.); -#17832 = DIRECTION('',(1.,0.E+000)); -#17833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17834 = PCURVE('',#17723,#17835); -#17835 = DEFINITIONAL_REPRESENTATION('',(#17836),#17840); -#17836 = LINE('',#17837,#17838); -#17837 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); -#17838 = VECTOR('',#17839,1.); -#17839 = DIRECTION('',(0.E+000,1.)); -#17840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17841 = ORIENTED_EDGE('',*,*,#17842,.T.); -#17842 = EDGE_CURVE('',#17820,#17843,#17845,.T.); -#17843 = VERTEX_POINT('',#17844); -#17844 = CARTESIAN_POINT('',(56.538908,22.145721,2.1)); -#17845 = SURFACE_CURVE('',#17846,(#17850,#17857),.PCURVE_S1.); -#17846 = LINE('',#17847,#17848); -#17847 = CARTESIAN_POINT('',(56.538908,22.495721,2.1)); -#17848 = VECTOR('',#17849,1.); -#17849 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17850 = PCURVE('',#17684,#17851); -#17851 = DEFINITIONAL_REPRESENTATION('',(#17852),#17856); -#17852 = LINE('',#17853,#17854); -#17853 = CARTESIAN_POINT('',(-0.3,0.E+000)); -#17854 = VECTOR('',#17855,1.); -#17855 = DIRECTION('',(0.E+000,1.)); -#17856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17857 = PCURVE('',#17858,#17863); -#17858 = CYLINDRICAL_SURFACE('',#17859,0.3); -#17859 = AXIS2_PLACEMENT_3D('',#17860,#17861,#17862); -#17860 = CARTESIAN_POINT('',(56.238908,22.495721,2.1)); -#17861 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17862 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17863 = DEFINITIONAL_REPRESENTATION('',(#17864),#17867); -#17864 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17865,#17866),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#17865 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#17866 = CARTESIAN_POINT('',(0.E+000,0.35)); -#17867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17868 = ORIENTED_EDGE('',*,*,#17869,.F.); -#17869 = EDGE_CURVE('',#17676,#17843,#17870,.T.); -#17870 = SURFACE_CURVE('',#17871,(#17875,#17882),.PCURVE_S1.); -#17871 = LINE('',#17872,#17873); -#17872 = CARTESIAN_POINT('',(56.538908,22.145721,-0.2)); -#17873 = VECTOR('',#17874,1.); -#17874 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17875 = PCURVE('',#17684,#17876); -#17876 = DEFINITIONAL_REPRESENTATION('',(#17877),#17881); -#17877 = LINE('',#17878,#17879); -#17878 = CARTESIAN_POINT('',(-2.6,0.35)); -#17879 = VECTOR('',#17880,1.); -#17880 = DIRECTION('',(1.,0.E+000)); -#17881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17882 = PCURVE('',#17883,#17888); -#17883 = PLANE('',#17884); -#17884 = AXIS2_PLACEMENT_3D('',#17885,#17886,#17887); -#17885 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); -#17886 = DIRECTION('',(0.E+000,1.,0.E+000)); -#17887 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17888 = DEFINITIONAL_REPRESENTATION('',(#17889),#17893); -#17889 = LINE('',#17890,#17891); -#17890 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); -#17891 = VECTOR('',#17892,1.); -#17892 = DIRECTION('',(0.E+000,1.)); -#17893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17894 = ADVANCED_FACE('',(#17895),#17909,.T.); -#17895 = FACE_BOUND('',#17896,.T.); -#17896 = EDGE_LOOP('',(#17897,#17931,#17954,#17976,#17999,#18027,#18055, - #18083)); -#17897 = ORIENTED_EDGE('',*,*,#17898,.T.); -#17898 = EDGE_CURVE('',#17899,#17901,#17903,.T.); -#17899 = VERTEX_POINT('',#17900); -#17900 = CARTESIAN_POINT('',(54.238908,22.495721,2.4)); -#17901 = VERTEX_POINT('',#17902); -#17902 = CARTESIAN_POINT('',(54.238908,22.145721,2.4)); -#17903 = SURFACE_CURVE('',#17904,(#17908,#17920),.PCURVE_S1.); -#17904 = LINE('',#17905,#17906); -#17905 = CARTESIAN_POINT('',(54.238908,22.495721,2.4)); -#17906 = VECTOR('',#17907,1.); -#17907 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17908 = PCURVE('',#17909,#17914); -#17909 = PLANE('',#17910); -#17910 = AXIS2_PLACEMENT_3D('',#17911,#17912,#17913); -#17911 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); -#17912 = DIRECTION('',(0.E+000,0.E+000,1.)); -#17913 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17914 = DEFINITIONAL_REPRESENTATION('',(#17915),#17919); -#17915 = LINE('',#17916,#17917); -#17916 = CARTESIAN_POINT('',(-0.3,0.E+000)); -#17917 = VECTOR('',#17918,1.); -#17918 = DIRECTION('',(0.E+000,1.)); -#17919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17920 = PCURVE('',#17921,#17926); -#17921 = CYLINDRICAL_SURFACE('',#17922,0.3); -#17922 = AXIS2_PLACEMENT_3D('',#17923,#17924,#17925); -#17923 = CARTESIAN_POINT('',(54.238908,22.495721,2.1)); -#17924 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17925 = DIRECTION('',(1.,0.E+000,0.E+000)); -#17926 = DEFINITIONAL_REPRESENTATION('',(#17927),#17930); -#17927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17928,#17929),.UNSPECIFIED., +#20058 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#20059),#24277); +#20059 = MANIFOLD_SOLID_BREP('',#20060); +#20060 = CLOSED_SHELL('',(#20061,#20286,#20496,#20706,#20911,#21031, + #21267,#21343,#21443,#21490,#21521,#21597,#21646,#21677,#21708, + #21739,#21766,#21886,#22002,#22101,#22200,#22299,#22398,#22498, + #22594,#22732,#22781,#22830,#22857,#22935,#23035,#23082,#23091, + #23118,#23247,#23338,#23345,#23436,#23443,#23449,#23498,#23591, + #23598,#23797,#23823,#23849,#23856,#23882,#23908,#23915,#23942, + #23949,#24050,#24159,#24207,#24256,#24263,#24270)); +#20061 = ADVANCED_FACE('',(#20062),#20076,.T.); +#20062 = FACE_BOUND('',#20063,.T.); +#20063 = EDGE_LOOP('',(#20064,#20098,#20126,#20154,#20182,#20210,#20233, + #20260)); +#20064 = ORIENTED_EDGE('',*,*,#20065,.F.); +#20065 = EDGE_CURVE('',#20066,#20068,#20070,.T.); +#20066 = VERTEX_POINT('',#20067); +#20067 = CARTESIAN_POINT('',(56.538908,22.495721,1.E-001)); +#20068 = VERTEX_POINT('',#20069); +#20069 = CARTESIAN_POINT('',(56.538908,22.145721,1.E-001)); +#20070 = SURFACE_CURVE('',#20071,(#20075,#20087),.PCURVE_S1.); +#20071 = LINE('',#20072,#20073); +#20072 = CARTESIAN_POINT('',(56.538908,22.495721,1.E-001)); +#20073 = VECTOR('',#20074,1.); +#20074 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20075 = PCURVE('',#20076,#20081); +#20076 = PLANE('',#20077); +#20077 = AXIS2_PLACEMENT_3D('',#20078,#20079,#20080); +#20078 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); +#20079 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20080 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20081 = DEFINITIONAL_REPRESENTATION('',(#20082),#20086); +#20082 = LINE('',#20083,#20084); +#20083 = CARTESIAN_POINT('',(-2.3,0.E+000)); +#20084 = VECTOR('',#20085,1.); +#20085 = DIRECTION('',(0.E+000,1.)); +#20086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20087 = PCURVE('',#20088,#20093); +#20088 = CYLINDRICAL_SURFACE('',#20089,0.3); +#20089 = AXIS2_PLACEMENT_3D('',#20090,#20091,#20092); +#20090 = CARTESIAN_POINT('',(56.238908,22.495721,1.E-001)); +#20091 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20092 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20093 = DEFINITIONAL_REPRESENTATION('',(#20094),#20097); +#20094 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20095,#20096),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#17928 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#17929 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#17930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17931 = ORIENTED_EDGE('',*,*,#17932,.F.); -#17932 = EDGE_CURVE('',#17933,#17901,#17935,.T.); -#17933 = VERTEX_POINT('',#17934); -#17934 = CARTESIAN_POINT('',(56.238908,22.145721,2.4)); -#17935 = SURFACE_CURVE('',#17936,(#17940,#17947),.PCURVE_S1.); -#17936 = LINE('',#17937,#17938); -#17937 = CARTESIAN_POINT('',(56.538908,22.145721,2.4)); -#17938 = VECTOR('',#17939,1.); -#17939 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17940 = PCURVE('',#17909,#17941); -#17941 = DEFINITIONAL_REPRESENTATION('',(#17942),#17946); -#17942 = LINE('',#17943,#17944); -#17943 = CARTESIAN_POINT('',(-2.6,0.35)); -#17944 = VECTOR('',#17945,1.); -#17945 = DIRECTION('',(1.,0.E+000)); -#17946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17947 = PCURVE('',#17883,#17948); -#17948 = DEFINITIONAL_REPRESENTATION('',(#17949),#17953); -#17949 = LINE('',#17950,#17951); -#17950 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); -#17951 = VECTOR('',#17952,1.); -#17952 = DIRECTION('',(1.,0.E+000)); -#17953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17954 = ORIENTED_EDGE('',*,*,#17955,.F.); -#17955 = EDGE_CURVE('',#17956,#17933,#17958,.T.); -#17956 = VERTEX_POINT('',#17957); -#17957 = CARTESIAN_POINT('',(56.238908,22.495721,2.4)); -#17958 = SURFACE_CURVE('',#17959,(#17963,#17970),.PCURVE_S1.); -#17959 = LINE('',#17960,#17961); -#17960 = CARTESIAN_POINT('',(56.238908,22.495721,2.4)); -#17961 = VECTOR('',#17962,1.); -#17962 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#17963 = PCURVE('',#17909,#17964); -#17964 = DEFINITIONAL_REPRESENTATION('',(#17965),#17969); -#17965 = LINE('',#17966,#17967); -#17966 = CARTESIAN_POINT('',(-2.3,0.E+000)); -#17967 = VECTOR('',#17968,1.); -#17968 = DIRECTION('',(0.E+000,1.)); -#17969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#20095 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#20096 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#20097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20098 = ORIENTED_EDGE('',*,*,#20099,.T.); +#20099 = EDGE_CURVE('',#20066,#20100,#20102,.T.); +#20100 = VERTEX_POINT('',#20101); +#20101 = CARTESIAN_POINT('',(56.538908,22.495721,0.2)); +#20102 = SURFACE_CURVE('',#20103,(#20107,#20114),.PCURVE_S1.); +#20103 = LINE('',#20104,#20105); +#20104 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); +#20105 = VECTOR('',#20106,1.); +#20106 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20107 = PCURVE('',#20076,#20108); +#20108 = DEFINITIONAL_REPRESENTATION('',(#20109),#20113); +#20109 = LINE('',#20110,#20111); +#20110 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20111 = VECTOR('',#20112,1.); +#20112 = DIRECTION('',(1.,0.E+000)); +#20113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20114 = PCURVE('',#20115,#20120); +#20115 = PLANE('',#20116); +#20116 = AXIS2_PLACEMENT_3D('',#20117,#20118,#20119); +#20117 = CARTESIAN_POINT('',(50.919956733961,22.495721,0.899011437739)); +#20118 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20119 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20120 = DEFINITIONAL_REPRESENTATION('',(#20121),#20125); +#20121 = LINE('',#20122,#20123); +#20122 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); +#20123 = VECTOR('',#20124,1.); +#20124 = DIRECTION('',(0.E+000,1.)); +#20125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20126 = ORIENTED_EDGE('',*,*,#20127,.F.); +#20127 = EDGE_CURVE('',#20128,#20100,#20130,.T.); +#20128 = VERTEX_POINT('',#20129); +#20129 = CARTESIAN_POINT('',(56.538908,22.345721,0.2)); +#20130 = SURFACE_CURVE('',#20131,(#20135,#20142),.PCURVE_S1.); +#20131 = LINE('',#20132,#20133); +#20132 = CARTESIAN_POINT('',(56.538908,22.495721,0.2)); +#20133 = VECTOR('',#20134,1.); +#20134 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20135 = PCURVE('',#20076,#20136); +#20136 = DEFINITIONAL_REPRESENTATION('',(#20137),#20141); +#20137 = LINE('',#20138,#20139); +#20138 = CARTESIAN_POINT('',(-2.2,0.E+000)); +#20139 = VECTOR('',#20140,1.); +#20140 = DIRECTION('',(0.E+000,-1.)); +#20141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20142 = PCURVE('',#20143,#20148); +#20143 = PLANE('',#20144); +#20144 = AXIS2_PLACEMENT_3D('',#20145,#20146,#20147); +#20145 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); +#20146 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20147 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20148 = DEFINITIONAL_REPRESENTATION('',(#20149),#20153); +#20149 = LINE('',#20150,#20151); +#20150 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#20151 = VECTOR('',#20152,1.); +#20152 = DIRECTION('',(0.E+000,-1.)); +#20153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#17970 = PCURVE('',#17858,#17971); -#17971 = DEFINITIONAL_REPRESENTATION('',(#17972),#17975); -#17972 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#17973,#17974),.UNSPECIFIED., +#20154 = ORIENTED_EDGE('',*,*,#20155,.T.); +#20155 = EDGE_CURVE('',#20128,#20156,#20158,.T.); +#20156 = VERTEX_POINT('',#20157); +#20157 = CARTESIAN_POINT('',(56.538908,22.345721,2.)); +#20158 = SURFACE_CURVE('',#20159,(#20163,#20170),.PCURVE_S1.); +#20159 = LINE('',#20160,#20161); +#20160 = CARTESIAN_POINT('',(56.538908,22.345721,0.899011437739)); +#20161 = VECTOR('',#20162,1.); +#20162 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20163 = PCURVE('',#20076,#20164); +#20164 = DEFINITIONAL_REPRESENTATION('',(#20165),#20169); +#20165 = LINE('',#20166,#20167); +#20166 = CARTESIAN_POINT('',(-1.500988562261,0.15)); +#20167 = VECTOR('',#20168,1.); +#20168 = DIRECTION('',(1.,0.E+000)); +#20169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20170 = PCURVE('',#20171,#20176); +#20171 = PLANE('',#20172); +#20172 = AXIS2_PLACEMENT_3D('',#20173,#20174,#20175); +#20173 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); +#20174 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20175 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20176 = DEFINITIONAL_REPRESENTATION('',(#20177),#20181); +#20177 = LINE('',#20178,#20179); +#20178 = CARTESIAN_POINT('',(-5.618951266039,0.E+000)); +#20179 = VECTOR('',#20180,1.); +#20180 = DIRECTION('',(0.E+000,1.)); +#20181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20182 = ORIENTED_EDGE('',*,*,#20183,.F.); +#20183 = EDGE_CURVE('',#20184,#20156,#20186,.T.); +#20184 = VERTEX_POINT('',#20185); +#20185 = CARTESIAN_POINT('',(56.538908,22.495721,2.)); +#20186 = SURFACE_CURVE('',#20187,(#20191,#20198),.PCURVE_S1.); +#20187 = LINE('',#20188,#20189); +#20188 = CARTESIAN_POINT('',(56.538908,22.495721,2.)); +#20189 = VECTOR('',#20190,1.); +#20190 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20191 = PCURVE('',#20076,#20192); +#20192 = DEFINITIONAL_REPRESENTATION('',(#20193),#20197); +#20193 = LINE('',#20194,#20195); +#20194 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#20195 = VECTOR('',#20196,1.); +#20196 = DIRECTION('',(0.E+000,1.)); +#20197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20198 = PCURVE('',#20199,#20204); +#20199 = PLANE('',#20200); +#20200 = AXIS2_PLACEMENT_3D('',#20201,#20202,#20203); +#20201 = CARTESIAN_POINT('',(56.288908,22.495721,2.)); +#20202 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20203 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20204 = DEFINITIONAL_REPRESENTATION('',(#20205),#20209); +#20205 = LINE('',#20206,#20207); +#20206 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#20207 = VECTOR('',#20208,1.); +#20208 = DIRECTION('',(0.E+000,1.)); +#20209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20210 = ORIENTED_EDGE('',*,*,#20211,.T.); +#20211 = EDGE_CURVE('',#20184,#20212,#20214,.T.); +#20212 = VERTEX_POINT('',#20213); +#20213 = CARTESIAN_POINT('',(56.538908,22.495721,2.1)); +#20214 = SURFACE_CURVE('',#20215,(#20219,#20226),.PCURVE_S1.); +#20215 = LINE('',#20216,#20217); +#20216 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); +#20217 = VECTOR('',#20218,1.); +#20218 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20219 = PCURVE('',#20076,#20220); +#20220 = DEFINITIONAL_REPRESENTATION('',(#20221),#20225); +#20221 = LINE('',#20222,#20223); +#20222 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20223 = VECTOR('',#20224,1.); +#20224 = DIRECTION('',(1.,0.E+000)); +#20225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20226 = PCURVE('',#20115,#20227); +#20227 = DEFINITIONAL_REPRESENTATION('',(#20228),#20232); +#20228 = LINE('',#20229,#20230); +#20229 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); +#20230 = VECTOR('',#20231,1.); +#20231 = DIRECTION('',(0.E+000,1.)); +#20232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20233 = ORIENTED_EDGE('',*,*,#20234,.T.); +#20234 = EDGE_CURVE('',#20212,#20235,#20237,.T.); +#20235 = VERTEX_POINT('',#20236); +#20236 = CARTESIAN_POINT('',(56.538908,22.145721,2.1)); +#20237 = SURFACE_CURVE('',#20238,(#20242,#20249),.PCURVE_S1.); +#20238 = LINE('',#20239,#20240); +#20239 = CARTESIAN_POINT('',(56.538908,22.495721,2.1)); +#20240 = VECTOR('',#20241,1.); +#20241 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20242 = PCURVE('',#20076,#20243); +#20243 = DEFINITIONAL_REPRESENTATION('',(#20244),#20248); +#20244 = LINE('',#20245,#20246); +#20245 = CARTESIAN_POINT('',(-0.3,0.E+000)); +#20246 = VECTOR('',#20247,1.); +#20247 = DIRECTION('',(0.E+000,1.)); +#20248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20249 = PCURVE('',#20250,#20255); +#20250 = CYLINDRICAL_SURFACE('',#20251,0.3); +#20251 = AXIS2_PLACEMENT_3D('',#20252,#20253,#20254); +#20252 = CARTESIAN_POINT('',(56.238908,22.495721,2.1)); +#20253 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20254 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20255 = DEFINITIONAL_REPRESENTATION('',(#20256),#20259); +#20256 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20257,#20258),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#17973 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#17974 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#17975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17976 = ORIENTED_EDGE('',*,*,#17977,.T.); -#17977 = EDGE_CURVE('',#17956,#17978,#17980,.T.); -#17978 = VERTEX_POINT('',#17979); -#17979 = CARTESIAN_POINT('',(55.538908,22.495721,2.4)); -#17980 = SURFACE_CURVE('',#17981,(#17985,#17992),.PCURVE_S1.); -#17981 = LINE('',#17982,#17983); -#17982 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); -#17983 = VECTOR('',#17984,1.); -#17984 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#17985 = PCURVE('',#17909,#17986); -#17986 = DEFINITIONAL_REPRESENTATION('',(#17987),#17991); -#17987 = LINE('',#17988,#17989); -#17988 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#17989 = VECTOR('',#17990,1.); -#17990 = DIRECTION('',(1.,0.E+000)); -#17991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17992 = PCURVE('',#17723,#17993); -#17993 = DEFINITIONAL_REPRESENTATION('',(#17994),#17998); -#17994 = LINE('',#17995,#17996); -#17995 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); -#17996 = VECTOR('',#17997,1.); -#17997 = DIRECTION('',(1.,0.E+000)); -#17998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#17999 = ORIENTED_EDGE('',*,*,#18000,.F.); -#18000 = EDGE_CURVE('',#18001,#17978,#18003,.T.); -#18001 = VERTEX_POINT('',#18002); -#18002 = CARTESIAN_POINT('',(55.538908,22.345721,2.4)); -#18003 = SURFACE_CURVE('',#18004,(#18008,#18015),.PCURVE_S1.); -#18004 = LINE('',#18005,#18006); -#18005 = CARTESIAN_POINT('',(55.538908,22.495721,2.4)); -#18006 = VECTOR('',#18007,1.); -#18007 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18008 = PCURVE('',#17909,#18009); -#18009 = DEFINITIONAL_REPRESENTATION('',(#18010),#18014); -#18010 = LINE('',#18011,#18012); -#18011 = CARTESIAN_POINT('',(-1.6,0.E+000)); -#18012 = VECTOR('',#18013,1.); -#18013 = DIRECTION('',(0.E+000,-1.)); -#18014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18015 = PCURVE('',#18016,#18021); -#18016 = PLANE('',#18017); -#18017 = AXIS2_PLACEMENT_3D('',#18018,#18019,#18020); -#18018 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); -#18019 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18020 = DIRECTION('',(0.E+000,0.E+000,1.)); -#18021 = DEFINITIONAL_REPRESENTATION('',(#18022),#18026); -#18022 = LINE('',#18023,#18024); -#18023 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#18024 = VECTOR('',#18025,1.); -#18025 = DIRECTION('',(0.E+000,-1.)); -#18026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18027 = ORIENTED_EDGE('',*,*,#18028,.T.); -#18028 = EDGE_CURVE('',#18001,#18029,#18031,.T.); -#18029 = VERTEX_POINT('',#18030); -#18030 = CARTESIAN_POINT('',(54.938908,22.345721,2.4)); -#18031 = SURFACE_CURVE('',#18032,(#18036,#18043),.PCURVE_S1.); -#18032 = LINE('',#18033,#18034); -#18033 = CARTESIAN_POINT('',(50.919956733961,22.345721,2.4)); -#18034 = VECTOR('',#18035,1.); -#18035 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18036 = PCURVE('',#17909,#18037); -#18037 = DEFINITIONAL_REPRESENTATION('',(#18038),#18042); -#18038 = LINE('',#18039,#18040); -#18039 = CARTESIAN_POINT('',(3.018951266039,0.15)); -#18040 = VECTOR('',#18041,1.); -#18041 = DIRECTION('',(1.,0.E+000)); -#18042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18043 = PCURVE('',#18044,#18049); -#18044 = PLANE('',#18045); -#18045 = AXIS2_PLACEMENT_3D('',#18046,#18047,#18048); -#18046 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); -#18047 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18048 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18049 = DEFINITIONAL_REPRESENTATION('',(#18050),#18054); -#18050 = LINE('',#18051,#18052); -#18051 = CARTESIAN_POINT('',(0.E+000,1.500988562261)); -#18052 = VECTOR('',#18053,1.); -#18053 = DIRECTION('',(1.,0.E+000)); -#18054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18055 = ORIENTED_EDGE('',*,*,#18056,.F.); -#18056 = EDGE_CURVE('',#18057,#18029,#18059,.T.); -#18057 = VERTEX_POINT('',#18058); -#18058 = CARTESIAN_POINT('',(54.938908,22.495721,2.4)); -#18059 = SURFACE_CURVE('',#18060,(#18064,#18071),.PCURVE_S1.); -#18060 = LINE('',#18061,#18062); -#18061 = CARTESIAN_POINT('',(54.938908,22.495721,2.4)); -#18062 = VECTOR('',#18063,1.); -#18063 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18064 = PCURVE('',#17909,#18065); -#18065 = DEFINITIONAL_REPRESENTATION('',(#18066),#18070); -#18066 = LINE('',#18067,#18068); -#18067 = CARTESIAN_POINT('',(-1.,0.E+000)); -#18068 = VECTOR('',#18069,1.); -#18069 = DIRECTION('',(0.E+000,1.)); -#18070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18071 = PCURVE('',#18072,#18077); -#18072 = PLANE('',#18073); -#18073 = AXIS2_PLACEMENT_3D('',#18074,#18075,#18076); -#18074 = CARTESIAN_POINT('',(54.938908,22.495721,1.5)); -#18075 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18076 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18077 = DEFINITIONAL_REPRESENTATION('',(#18078),#18082); -#18078 = LINE('',#18079,#18080); -#18079 = CARTESIAN_POINT('',(-0.9,0.E+000)); -#18080 = VECTOR('',#18081,1.); -#18081 = DIRECTION('',(0.E+000,1.)); -#18082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18083 = ORIENTED_EDGE('',*,*,#18084,.T.); -#18084 = EDGE_CURVE('',#18057,#17899,#18085,.T.); -#18085 = SURFACE_CURVE('',#18086,(#18090,#18097),.PCURVE_S1.); -#18086 = LINE('',#18087,#18088); -#18087 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); -#18088 = VECTOR('',#18089,1.); -#18089 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18090 = PCURVE('',#17909,#18091); -#18091 = DEFINITIONAL_REPRESENTATION('',(#18092),#18096); -#18092 = LINE('',#18093,#18094); -#18093 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#18094 = VECTOR('',#18095,1.); -#18095 = DIRECTION('',(1.,0.E+000)); -#18096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18097 = PCURVE('',#17723,#18098); -#18098 = DEFINITIONAL_REPRESENTATION('',(#18099),#18103); -#18099 = LINE('',#18100,#18101); -#18100 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); -#18101 = VECTOR('',#18102,1.); -#18102 = DIRECTION('',(1.,0.E+000)); -#18103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18104 = ADVANCED_FACE('',(#18105),#18119,.T.); -#18105 = FACE_BOUND('',#18106,.T.); -#18106 = EDGE_LOOP('',(#18107,#18141,#18164,#18186,#18209,#18237,#18265, - #18293)); -#18107 = ORIENTED_EDGE('',*,*,#18108,.T.); -#18108 = EDGE_CURVE('',#18109,#18111,#18113,.T.); -#18109 = VERTEX_POINT('',#18110); -#18110 = CARTESIAN_POINT('',(53.938908,22.495721,1.E-001)); -#18111 = VERTEX_POINT('',#18112); -#18112 = CARTESIAN_POINT('',(53.938908,22.145721,1.E-001)); -#18113 = SURFACE_CURVE('',#18114,(#18118,#18130),.PCURVE_S1.); -#18114 = LINE('',#18115,#18116); -#18115 = CARTESIAN_POINT('',(53.938908,22.495721,1.E-001)); -#18116 = VECTOR('',#18117,1.); -#18117 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18118 = PCURVE('',#18119,#18124); -#18119 = PLANE('',#18120); -#18120 = AXIS2_PLACEMENT_3D('',#18121,#18122,#18123); -#18121 = CARTESIAN_POINT('',(53.938908,22.495721,-0.2)); -#18122 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18123 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18124 = DEFINITIONAL_REPRESENTATION('',(#18125),#18129); -#18125 = LINE('',#18126,#18127); -#18126 = CARTESIAN_POINT('',(-0.3,0.E+000)); -#18127 = VECTOR('',#18128,1.); -#18128 = DIRECTION('',(0.E+000,1.)); -#18129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18130 = PCURVE('',#18131,#18136); -#18131 = CYLINDRICAL_SURFACE('',#18132,0.3); -#18132 = AXIS2_PLACEMENT_3D('',#18133,#18134,#18135); -#18133 = CARTESIAN_POINT('',(54.238908,22.495721,1.E-001)); -#18134 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18135 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18136 = DEFINITIONAL_REPRESENTATION('',(#18137),#18140); -#18137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18138,#18139),.UNSPECIFIED., +#20257 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#20258 = CARTESIAN_POINT('',(0.E+000,0.35)); +#20259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20260 = ORIENTED_EDGE('',*,*,#20261,.F.); +#20261 = EDGE_CURVE('',#20068,#20235,#20262,.T.); +#20262 = SURFACE_CURVE('',#20263,(#20267,#20274),.PCURVE_S1.); +#20263 = LINE('',#20264,#20265); +#20264 = CARTESIAN_POINT('',(56.538908,22.145721,-0.2)); +#20265 = VECTOR('',#20266,1.); +#20266 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20267 = PCURVE('',#20076,#20268); +#20268 = DEFINITIONAL_REPRESENTATION('',(#20269),#20273); +#20269 = LINE('',#20270,#20271); +#20270 = CARTESIAN_POINT('',(-2.6,0.35)); +#20271 = VECTOR('',#20272,1.); +#20272 = DIRECTION('',(1.,0.E+000)); +#20273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20274 = PCURVE('',#20275,#20280); +#20275 = PLANE('',#20276); +#20276 = AXIS2_PLACEMENT_3D('',#20277,#20278,#20279); +#20277 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); +#20278 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20279 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20280 = DEFINITIONAL_REPRESENTATION('',(#20281),#20285); +#20281 = LINE('',#20282,#20283); +#20282 = CARTESIAN_POINT('',(-5.618951266039,-1.099011437739)); +#20283 = VECTOR('',#20284,1.); +#20284 = DIRECTION('',(0.E+000,1.)); +#20285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20286 = ADVANCED_FACE('',(#20287),#20301,.T.); +#20287 = FACE_BOUND('',#20288,.T.); +#20288 = EDGE_LOOP('',(#20289,#20323,#20346,#20368,#20391,#20419,#20447, + #20475)); +#20289 = ORIENTED_EDGE('',*,*,#20290,.T.); +#20290 = EDGE_CURVE('',#20291,#20293,#20295,.T.); +#20291 = VERTEX_POINT('',#20292); +#20292 = CARTESIAN_POINT('',(54.238908,22.495721,2.4)); +#20293 = VERTEX_POINT('',#20294); +#20294 = CARTESIAN_POINT('',(54.238908,22.145721,2.4)); +#20295 = SURFACE_CURVE('',#20296,(#20300,#20312),.PCURVE_S1.); +#20296 = LINE('',#20297,#20298); +#20297 = CARTESIAN_POINT('',(54.238908,22.495721,2.4)); +#20298 = VECTOR('',#20299,1.); +#20299 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20300 = PCURVE('',#20301,#20306); +#20301 = PLANE('',#20302); +#20302 = AXIS2_PLACEMENT_3D('',#20303,#20304,#20305); +#20303 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); +#20304 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20305 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20306 = DEFINITIONAL_REPRESENTATION('',(#20307),#20311); +#20307 = LINE('',#20308,#20309); +#20308 = CARTESIAN_POINT('',(-0.3,0.E+000)); +#20309 = VECTOR('',#20310,1.); +#20310 = DIRECTION('',(0.E+000,1.)); +#20311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20312 = PCURVE('',#20313,#20318); +#20313 = CYLINDRICAL_SURFACE('',#20314,0.3); +#20314 = AXIS2_PLACEMENT_3D('',#20315,#20316,#20317); +#20315 = CARTESIAN_POINT('',(54.238908,22.495721,2.1)); +#20316 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20317 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20318 = DEFINITIONAL_REPRESENTATION('',(#20319),#20322); +#20319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20320,#20321),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#18138 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#18139 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#18140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18141 = ORIENTED_EDGE('',*,*,#18142,.F.); -#18142 = EDGE_CURVE('',#18143,#18111,#18145,.T.); -#18143 = VERTEX_POINT('',#18144); -#18144 = CARTESIAN_POINT('',(53.938908,22.145721,2.1)); -#18145 = SURFACE_CURVE('',#18146,(#18150,#18157),.PCURVE_S1.); -#18146 = LINE('',#18147,#18148); -#18147 = CARTESIAN_POINT('',(53.938908,22.145721,2.4)); -#18148 = VECTOR('',#18149,1.); -#18149 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18150 = PCURVE('',#18119,#18151); -#18151 = DEFINITIONAL_REPRESENTATION('',(#18152),#18156); -#18152 = LINE('',#18153,#18154); -#18153 = CARTESIAN_POINT('',(-2.6,0.35)); -#18154 = VECTOR('',#18155,1.); -#18155 = DIRECTION('',(1.,0.E+000)); -#18156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18157 = PCURVE('',#17883,#18158); -#18158 = DEFINITIONAL_REPRESENTATION('',(#18159),#18163); -#18159 = LINE('',#18160,#18161); -#18160 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); -#18161 = VECTOR('',#18162,1.); -#18162 = DIRECTION('',(0.E+000,-1.)); -#18163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18164 = ORIENTED_EDGE('',*,*,#18165,.F.); -#18165 = EDGE_CURVE('',#18166,#18143,#18168,.T.); -#18166 = VERTEX_POINT('',#18167); -#18167 = CARTESIAN_POINT('',(53.938908,22.495721,2.1)); -#18168 = SURFACE_CURVE('',#18169,(#18173,#18180),.PCURVE_S1.); -#18169 = LINE('',#18170,#18171); -#18170 = CARTESIAN_POINT('',(53.938908,22.495721,2.1)); -#18171 = VECTOR('',#18172,1.); -#18172 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18173 = PCURVE('',#18119,#18174); -#18174 = DEFINITIONAL_REPRESENTATION('',(#18175),#18179); -#18175 = LINE('',#18176,#18177); -#18176 = CARTESIAN_POINT('',(-2.3,0.E+000)); -#18177 = VECTOR('',#18178,1.); -#18178 = DIRECTION('',(0.E+000,1.)); -#18179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18180 = PCURVE('',#17921,#18181); -#18181 = DEFINITIONAL_REPRESENTATION('',(#18182),#18185); -#18182 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18183,#18184),.UNSPECIFIED., +#20320 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#20321 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#20322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20323 = ORIENTED_EDGE('',*,*,#20324,.F.); +#20324 = EDGE_CURVE('',#20325,#20293,#20327,.T.); +#20325 = VERTEX_POINT('',#20326); +#20326 = CARTESIAN_POINT('',(56.238908,22.145721,2.4)); +#20327 = SURFACE_CURVE('',#20328,(#20332,#20339),.PCURVE_S1.); +#20328 = LINE('',#20329,#20330); +#20329 = CARTESIAN_POINT('',(56.538908,22.145721,2.4)); +#20330 = VECTOR('',#20331,1.); +#20331 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20332 = PCURVE('',#20301,#20333); +#20333 = DEFINITIONAL_REPRESENTATION('',(#20334),#20338); +#20334 = LINE('',#20335,#20336); +#20335 = CARTESIAN_POINT('',(-2.6,0.35)); +#20336 = VECTOR('',#20337,1.); +#20337 = DIRECTION('',(1.,0.E+000)); +#20338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20339 = PCURVE('',#20275,#20340); +#20340 = DEFINITIONAL_REPRESENTATION('',(#20341),#20345); +#20341 = LINE('',#20342,#20343); +#20342 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); +#20343 = VECTOR('',#20344,1.); +#20344 = DIRECTION('',(1.,0.E+000)); +#20345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20346 = ORIENTED_EDGE('',*,*,#20347,.F.); +#20347 = EDGE_CURVE('',#20348,#20325,#20350,.T.); +#20348 = VERTEX_POINT('',#20349); +#20349 = CARTESIAN_POINT('',(56.238908,22.495721,2.4)); +#20350 = SURFACE_CURVE('',#20351,(#20355,#20362),.PCURVE_S1.); +#20351 = LINE('',#20352,#20353); +#20352 = CARTESIAN_POINT('',(56.238908,22.495721,2.4)); +#20353 = VECTOR('',#20354,1.); +#20354 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20355 = PCURVE('',#20301,#20356); +#20356 = DEFINITIONAL_REPRESENTATION('',(#20357),#20361); +#20357 = LINE('',#20358,#20359); +#20358 = CARTESIAN_POINT('',(-2.3,0.E+000)); +#20359 = VECTOR('',#20360,1.); +#20360 = DIRECTION('',(0.E+000,1.)); +#20361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20362 = PCURVE('',#20250,#20363); +#20363 = DEFINITIONAL_REPRESENTATION('',(#20364),#20367); +#20364 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20365,#20366),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#18183 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#18184 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#18185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18186 = ORIENTED_EDGE('',*,*,#18187,.T.); -#18187 = EDGE_CURVE('',#18166,#18188,#18190,.T.); -#18188 = VERTEX_POINT('',#18189); -#18189 = CARTESIAN_POINT('',(53.938908,22.495721,2.)); -#18190 = SURFACE_CURVE('',#18191,(#18195,#18202),.PCURVE_S1.); -#18191 = LINE('',#18192,#18193); -#18192 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); -#18193 = VECTOR('',#18194,1.); -#18194 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18195 = PCURVE('',#18119,#18196); -#18196 = DEFINITIONAL_REPRESENTATION('',(#18197),#18201); -#18197 = LINE('',#18198,#18199); -#18198 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#18199 = VECTOR('',#18200,1.); -#18200 = DIRECTION('',(1.,0.E+000)); -#18201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18202 = PCURVE('',#17723,#18203); -#18203 = DEFINITIONAL_REPRESENTATION('',(#18204),#18208); -#18204 = LINE('',#18205,#18206); -#18205 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); -#18206 = VECTOR('',#18207,1.); -#18207 = DIRECTION('',(0.E+000,-1.)); -#18208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18209 = ORIENTED_EDGE('',*,*,#18210,.F.); -#18210 = EDGE_CURVE('',#18211,#18188,#18213,.T.); -#18211 = VERTEX_POINT('',#18212); -#18212 = CARTESIAN_POINT('',(53.938908,22.345721,2.)); -#18213 = SURFACE_CURVE('',#18214,(#18218,#18225),.PCURVE_S1.); -#18214 = LINE('',#18215,#18216); -#18215 = CARTESIAN_POINT('',(53.938908,22.495721,2.)); -#18216 = VECTOR('',#18217,1.); -#18217 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18218 = PCURVE('',#18119,#18219); -#18219 = DEFINITIONAL_REPRESENTATION('',(#18220),#18224); -#18220 = LINE('',#18221,#18222); -#18221 = CARTESIAN_POINT('',(-2.2,0.E+000)); -#18222 = VECTOR('',#18223,1.); -#18223 = DIRECTION('',(0.E+000,-1.)); -#18224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18225 = PCURVE('',#18226,#18231); -#18226 = PLANE('',#18227); -#18227 = AXIS2_PLACEMENT_3D('',#18228,#18229,#18230); -#18228 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); -#18229 = DIRECTION('',(0.E+000,0.E+000,1.)); -#18230 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18231 = DEFINITIONAL_REPRESENTATION('',(#18232),#18236); -#18232 = LINE('',#18233,#18234); -#18233 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#18234 = VECTOR('',#18235,1.); -#18235 = DIRECTION('',(0.E+000,-1.)); -#18236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18237 = ORIENTED_EDGE('',*,*,#18238,.T.); -#18238 = EDGE_CURVE('',#18211,#18239,#18241,.T.); -#18239 = VERTEX_POINT('',#18240); -#18240 = CARTESIAN_POINT('',(53.938908,22.345721,0.2)); -#18241 = SURFACE_CURVE('',#18242,(#18246,#18253),.PCURVE_S1.); -#18242 = LINE('',#18243,#18244); -#18243 = CARTESIAN_POINT('',(53.938908,22.345721,0.899011437739)); -#18244 = VECTOR('',#18245,1.); -#18245 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18246 = PCURVE('',#18119,#18247); -#18247 = DEFINITIONAL_REPRESENTATION('',(#18248),#18252); -#18248 = LINE('',#18249,#18250); -#18249 = CARTESIAN_POINT('',(-1.099011437739,0.15)); -#18250 = VECTOR('',#18251,1.); -#18251 = DIRECTION('',(1.,0.E+000)); -#18252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18253 = PCURVE('',#18254,#18259); -#18254 = PLANE('',#18255); -#18255 = AXIS2_PLACEMENT_3D('',#18256,#18257,#18258); -#18256 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); -#18257 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18258 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18259 = DEFINITIONAL_REPRESENTATION('',(#18260),#18264); -#18260 = LINE('',#18261,#18262); -#18261 = CARTESIAN_POINT('',(-3.018951266039,0.E+000)); -#18262 = VECTOR('',#18263,1.); -#18263 = DIRECTION('',(0.E+000,-1.)); -#18264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18265 = ORIENTED_EDGE('',*,*,#18266,.F.); -#18266 = EDGE_CURVE('',#18267,#18239,#18269,.T.); -#18267 = VERTEX_POINT('',#18268); -#18268 = CARTESIAN_POINT('',(53.938908,22.495721,0.2)); -#18269 = SURFACE_CURVE('',#18270,(#18274,#18281),.PCURVE_S1.); -#18270 = LINE('',#18271,#18272); -#18271 = CARTESIAN_POINT('',(53.938908,22.495721,0.2)); -#18272 = VECTOR('',#18273,1.); -#18273 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18274 = PCURVE('',#18119,#18275); -#18275 = DEFINITIONAL_REPRESENTATION('',(#18276),#18280); -#18276 = LINE('',#18277,#18278); -#18277 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#18278 = VECTOR('',#18279,1.); -#18279 = DIRECTION('',(0.E+000,1.)); -#18280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#20365 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#20366 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#20367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#18281 = PCURVE('',#18282,#18287); -#18282 = PLANE('',#18283); -#18283 = AXIS2_PLACEMENT_3D('',#18284,#18285,#18286); -#18284 = CARTESIAN_POINT('',(54.188908,22.495721,0.2)); -#18285 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18286 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18287 = DEFINITIONAL_REPRESENTATION('',(#18288),#18292); -#18288 = LINE('',#18289,#18290); -#18289 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#18290 = VECTOR('',#18291,1.); -#18291 = DIRECTION('',(0.E+000,1.)); -#18292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18293 = ORIENTED_EDGE('',*,*,#18294,.T.); -#18294 = EDGE_CURVE('',#18267,#18109,#18295,.T.); -#18295 = SURFACE_CURVE('',#18296,(#18300,#18307),.PCURVE_S1.); -#18296 = LINE('',#18297,#18298); -#18297 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); -#18298 = VECTOR('',#18299,1.); -#18299 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18300 = PCURVE('',#18119,#18301); -#18301 = DEFINITIONAL_REPRESENTATION('',(#18302),#18306); -#18302 = LINE('',#18303,#18304); -#18303 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#18304 = VECTOR('',#18305,1.); -#18305 = DIRECTION('',(1.,0.E+000)); -#18306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18307 = PCURVE('',#17723,#18308); -#18308 = DEFINITIONAL_REPRESENTATION('',(#18309),#18313); -#18309 = LINE('',#18310,#18311); -#18310 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); -#18311 = VECTOR('',#18312,1.); -#18312 = DIRECTION('',(0.E+000,-1.)); -#18313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18314 = ADVANCED_FACE('',(#18315),#18329,.T.); -#18315 = FACE_BOUND('',#18316,.T.); -#18316 = EDGE_LOOP('',(#18317,#18347,#18369,#18392,#18420,#18448,#18476, - #18499)); -#18317 = ORIENTED_EDGE('',*,*,#18318,.T.); -#18318 = EDGE_CURVE('',#18319,#18321,#18323,.T.); -#18319 = VERTEX_POINT('',#18320); -#18320 = CARTESIAN_POINT('',(54.238908,22.495721,-0.2)); -#18321 = VERTEX_POINT('',#18322); -#18322 = CARTESIAN_POINT('',(56.238908,22.495721,-0.2)); -#18323 = SURFACE_CURVE('',#18324,(#18328,#18340),.PCURVE_S1.); -#18324 = LINE('',#18325,#18326); -#18325 = CARTESIAN_POINT('',(53.938908,22.495721,-0.2)); -#18326 = VECTOR('',#18327,1.); -#18327 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18328 = PCURVE('',#18329,#18334); -#18329 = PLANE('',#18330); -#18330 = AXIS2_PLACEMENT_3D('',#18331,#18332,#18333); -#18331 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); -#18332 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18333 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18334 = DEFINITIONAL_REPRESENTATION('',(#18335),#18339); -#18335 = LINE('',#18336,#18337); -#18336 = CARTESIAN_POINT('',(-2.6,0.E+000)); -#18337 = VECTOR('',#18338,1.); -#18338 = DIRECTION('',(1.,0.E+000)); -#18339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18340 = PCURVE('',#17723,#18341); -#18341 = DEFINITIONAL_REPRESENTATION('',(#18342),#18346); -#18342 = LINE('',#18343,#18344); -#18343 = CARTESIAN_POINT('',(-3.018951266039,-1.099011437739)); -#18344 = VECTOR('',#18345,1.); -#18345 = DIRECTION('',(-1.,0.E+000)); -#18346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18347 = ORIENTED_EDGE('',*,*,#18348,.T.); -#18348 = EDGE_CURVE('',#18321,#18349,#18351,.T.); -#18349 = VERTEX_POINT('',#18350); -#18350 = CARTESIAN_POINT('',(56.238908,22.145721,-0.2)); -#18351 = SURFACE_CURVE('',#18352,(#18356,#18363),.PCURVE_S1.); -#18352 = LINE('',#18353,#18354); -#18353 = CARTESIAN_POINT('',(56.238908,22.495721,-0.2)); -#18354 = VECTOR('',#18355,1.); -#18355 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18356 = PCURVE('',#18329,#18357); -#18357 = DEFINITIONAL_REPRESENTATION('',(#18358),#18362); -#18358 = LINE('',#18359,#18360); -#18359 = CARTESIAN_POINT('',(-0.3,0.E+000)); -#18360 = VECTOR('',#18361,1.); -#18361 = DIRECTION('',(0.E+000,1.)); -#18362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18363 = PCURVE('',#17696,#18364); -#18364 = DEFINITIONAL_REPRESENTATION('',(#18365),#18368); -#18365 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18366,#18367),.UNSPECIFIED., +#20368 = ORIENTED_EDGE('',*,*,#20369,.T.); +#20369 = EDGE_CURVE('',#20348,#20370,#20372,.T.); +#20370 = VERTEX_POINT('',#20371); +#20371 = CARTESIAN_POINT('',(55.538908,22.495721,2.4)); +#20372 = SURFACE_CURVE('',#20373,(#20377,#20384),.PCURVE_S1.); +#20373 = LINE('',#20374,#20375); +#20374 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); +#20375 = VECTOR('',#20376,1.); +#20376 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20377 = PCURVE('',#20301,#20378); +#20378 = DEFINITIONAL_REPRESENTATION('',(#20379),#20383); +#20379 = LINE('',#20380,#20381); +#20380 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20381 = VECTOR('',#20382,1.); +#20382 = DIRECTION('',(1.,0.E+000)); +#20383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20384 = PCURVE('',#20115,#20385); +#20385 = DEFINITIONAL_REPRESENTATION('',(#20386),#20390); +#20386 = LINE('',#20387,#20388); +#20387 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); +#20388 = VECTOR('',#20389,1.); +#20389 = DIRECTION('',(1.,0.E+000)); +#20390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20391 = ORIENTED_EDGE('',*,*,#20392,.F.); +#20392 = EDGE_CURVE('',#20393,#20370,#20395,.T.); +#20393 = VERTEX_POINT('',#20394); +#20394 = CARTESIAN_POINT('',(55.538908,22.345721,2.4)); +#20395 = SURFACE_CURVE('',#20396,(#20400,#20407),.PCURVE_S1.); +#20396 = LINE('',#20397,#20398); +#20397 = CARTESIAN_POINT('',(55.538908,22.495721,2.4)); +#20398 = VECTOR('',#20399,1.); +#20399 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20400 = PCURVE('',#20301,#20401); +#20401 = DEFINITIONAL_REPRESENTATION('',(#20402),#20406); +#20402 = LINE('',#20403,#20404); +#20403 = CARTESIAN_POINT('',(-1.6,0.E+000)); +#20404 = VECTOR('',#20405,1.); +#20405 = DIRECTION('',(0.E+000,-1.)); +#20406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20407 = PCURVE('',#20408,#20413); +#20408 = PLANE('',#20409); +#20409 = AXIS2_PLACEMENT_3D('',#20410,#20411,#20412); +#20410 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); +#20411 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20412 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20413 = DEFINITIONAL_REPRESENTATION('',(#20414),#20418); +#20414 = LINE('',#20415,#20416); +#20415 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#20416 = VECTOR('',#20417,1.); +#20417 = DIRECTION('',(0.E+000,-1.)); +#20418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20419 = ORIENTED_EDGE('',*,*,#20420,.T.); +#20420 = EDGE_CURVE('',#20393,#20421,#20423,.T.); +#20421 = VERTEX_POINT('',#20422); +#20422 = CARTESIAN_POINT('',(54.938908,22.345721,2.4)); +#20423 = SURFACE_CURVE('',#20424,(#20428,#20435),.PCURVE_S1.); +#20424 = LINE('',#20425,#20426); +#20425 = CARTESIAN_POINT('',(50.919956733961,22.345721,2.4)); +#20426 = VECTOR('',#20427,1.); +#20427 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20428 = PCURVE('',#20301,#20429); +#20429 = DEFINITIONAL_REPRESENTATION('',(#20430),#20434); +#20430 = LINE('',#20431,#20432); +#20431 = CARTESIAN_POINT('',(3.018951266039,0.15)); +#20432 = VECTOR('',#20433,1.); +#20433 = DIRECTION('',(1.,0.E+000)); +#20434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20435 = PCURVE('',#20436,#20441); +#20436 = PLANE('',#20437); +#20437 = AXIS2_PLACEMENT_3D('',#20438,#20439,#20440); +#20438 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); +#20439 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20440 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20441 = DEFINITIONAL_REPRESENTATION('',(#20442),#20446); +#20442 = LINE('',#20443,#20444); +#20443 = CARTESIAN_POINT('',(0.E+000,1.500988562261)); +#20444 = VECTOR('',#20445,1.); +#20445 = DIRECTION('',(1.,0.E+000)); +#20446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20447 = ORIENTED_EDGE('',*,*,#20448,.F.); +#20448 = EDGE_CURVE('',#20449,#20421,#20451,.T.); +#20449 = VERTEX_POINT('',#20450); +#20450 = CARTESIAN_POINT('',(54.938908,22.495721,2.4)); +#20451 = SURFACE_CURVE('',#20452,(#20456,#20463),.PCURVE_S1.); +#20452 = LINE('',#20453,#20454); +#20453 = CARTESIAN_POINT('',(54.938908,22.495721,2.4)); +#20454 = VECTOR('',#20455,1.); +#20455 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20456 = PCURVE('',#20301,#20457); +#20457 = DEFINITIONAL_REPRESENTATION('',(#20458),#20462); +#20458 = LINE('',#20459,#20460); +#20459 = CARTESIAN_POINT('',(-1.,0.E+000)); +#20460 = VECTOR('',#20461,1.); +#20461 = DIRECTION('',(0.E+000,1.)); +#20462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20463 = PCURVE('',#20464,#20469); +#20464 = PLANE('',#20465); +#20465 = AXIS2_PLACEMENT_3D('',#20466,#20467,#20468); +#20466 = CARTESIAN_POINT('',(54.938908,22.495721,1.5)); +#20467 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20468 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20469 = DEFINITIONAL_REPRESENTATION('',(#20470),#20474); +#20470 = LINE('',#20471,#20472); +#20471 = CARTESIAN_POINT('',(-0.9,0.E+000)); +#20472 = VECTOR('',#20473,1.); +#20473 = DIRECTION('',(0.E+000,1.)); +#20474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20475 = ORIENTED_EDGE('',*,*,#20476,.T.); +#20476 = EDGE_CURVE('',#20449,#20291,#20477,.T.); +#20477 = SURFACE_CURVE('',#20478,(#20482,#20489),.PCURVE_S1.); +#20478 = LINE('',#20479,#20480); +#20479 = CARTESIAN_POINT('',(56.538908,22.495721,2.4)); +#20480 = VECTOR('',#20481,1.); +#20481 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20482 = PCURVE('',#20301,#20483); +#20483 = DEFINITIONAL_REPRESENTATION('',(#20484),#20488); +#20484 = LINE('',#20485,#20486); +#20485 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20486 = VECTOR('',#20487,1.); +#20487 = DIRECTION('',(1.,0.E+000)); +#20488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20489 = PCURVE('',#20115,#20490); +#20490 = DEFINITIONAL_REPRESENTATION('',(#20491),#20495); +#20491 = LINE('',#20492,#20493); +#20492 = CARTESIAN_POINT('',(-5.618951266039,1.500988562261)); +#20493 = VECTOR('',#20494,1.); +#20494 = DIRECTION('',(1.,0.E+000)); +#20495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20496 = ADVANCED_FACE('',(#20497),#20511,.T.); +#20497 = FACE_BOUND('',#20498,.T.); +#20498 = EDGE_LOOP('',(#20499,#20533,#20556,#20578,#20601,#20629,#20657, + #20685)); +#20499 = ORIENTED_EDGE('',*,*,#20500,.T.); +#20500 = EDGE_CURVE('',#20501,#20503,#20505,.T.); +#20501 = VERTEX_POINT('',#20502); +#20502 = CARTESIAN_POINT('',(53.938908,22.495721,1.E-001)); +#20503 = VERTEX_POINT('',#20504); +#20504 = CARTESIAN_POINT('',(53.938908,22.145721,1.E-001)); +#20505 = SURFACE_CURVE('',#20506,(#20510,#20522),.PCURVE_S1.); +#20506 = LINE('',#20507,#20508); +#20507 = CARTESIAN_POINT('',(53.938908,22.495721,1.E-001)); +#20508 = VECTOR('',#20509,1.); +#20509 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20510 = PCURVE('',#20511,#20516); +#20511 = PLANE('',#20512); +#20512 = AXIS2_PLACEMENT_3D('',#20513,#20514,#20515); +#20513 = CARTESIAN_POINT('',(53.938908,22.495721,-0.2)); +#20514 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20515 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20516 = DEFINITIONAL_REPRESENTATION('',(#20517),#20521); +#20517 = LINE('',#20518,#20519); +#20518 = CARTESIAN_POINT('',(-0.3,0.E+000)); +#20519 = VECTOR('',#20520,1.); +#20520 = DIRECTION('',(0.E+000,1.)); +#20521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20522 = PCURVE('',#20523,#20528); +#20523 = CYLINDRICAL_SURFACE('',#20524,0.3); +#20524 = AXIS2_PLACEMENT_3D('',#20525,#20526,#20527); +#20525 = CARTESIAN_POINT('',(54.238908,22.495721,1.E-001)); +#20526 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20527 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20528 = DEFINITIONAL_REPRESENTATION('',(#20529),#20532); +#20529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20530,#20531),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#18366 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#18367 = CARTESIAN_POINT('',(4.712388980385,0.35)); -#18368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18369 = ORIENTED_EDGE('',*,*,#18370,.F.); -#18370 = EDGE_CURVE('',#18371,#18349,#18373,.T.); -#18371 = VERTEX_POINT('',#18372); -#18372 = CARTESIAN_POINT('',(55.538908,22.145721,-0.2)); -#18373 = SURFACE_CURVE('',#18374,(#18378,#18385),.PCURVE_S1.); -#18374 = LINE('',#18375,#18376); -#18375 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.2)); -#18376 = VECTOR('',#18377,1.); -#18377 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18378 = PCURVE('',#18329,#18379); -#18379 = DEFINITIONAL_REPRESENTATION('',(#18380),#18384); -#18380 = LINE('',#18381,#18382); -#18381 = CARTESIAN_POINT('',(-5.618951266039,0.35)); -#18382 = VECTOR('',#18383,1.); -#18383 = DIRECTION('',(1.,0.E+000)); -#18384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18385 = PCURVE('',#17883,#18386); -#18386 = DEFINITIONAL_REPRESENTATION('',(#18387),#18391); -#18387 = LINE('',#18388,#18389); -#18388 = CARTESIAN_POINT('',(0.E+000,-1.099011437739)); -#18389 = VECTOR('',#18390,1.); -#18390 = DIRECTION('',(-1.,0.E+000)); -#18391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18392 = ORIENTED_EDGE('',*,*,#18393,.T.); -#18393 = EDGE_CURVE('',#18371,#18394,#18396,.T.); -#18394 = VERTEX_POINT('',#18395); -#18395 = CARTESIAN_POINT('',(55.538908,22.295721,-0.2)); -#18396 = SURFACE_CURVE('',#18397,(#18401,#18408),.PCURVE_S1.); -#18397 = LINE('',#18398,#18399); -#18398 = CARTESIAN_POINT('',(55.538908,22.495721,-0.2)); -#18399 = VECTOR('',#18400,1.); -#18400 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18401 = PCURVE('',#18329,#18402); -#18402 = DEFINITIONAL_REPRESENTATION('',(#18403),#18407); -#18403 = LINE('',#18404,#18405); -#18404 = CARTESIAN_POINT('',(-1.,0.E+000)); -#18405 = VECTOR('',#18406,1.); -#18406 = DIRECTION('',(0.E+000,-1.)); -#18407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18408 = PCURVE('',#18409,#18414); -#18409 = PLANE('',#18410); -#18410 = AXIS2_PLACEMENT_3D('',#18411,#18412,#18413); -#18411 = CARTESIAN_POINT('',(55.538908,22.495721,0.146060798583)); -#18412 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18413 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18414 = DEFINITIONAL_REPRESENTATION('',(#18415),#18419); -#18415 = LINE('',#18416,#18417); -#18416 = CARTESIAN_POINT('',(0.346060798583,0.E+000)); -#18417 = VECTOR('',#18418,1.); -#18418 = DIRECTION('',(0.E+000,-1.)); -#18419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18420 = ORIENTED_EDGE('',*,*,#18421,.F.); -#18421 = EDGE_CURVE('',#18422,#18394,#18424,.T.); -#18422 = VERTEX_POINT('',#18423); -#18423 = CARTESIAN_POINT('',(54.938908,22.295721,-0.2)); -#18424 = SURFACE_CURVE('',#18425,(#18429,#18436),.PCURVE_S1.); -#18425 = LINE('',#18426,#18427); -#18426 = CARTESIAN_POINT('',(0.E+000,22.295721,-0.2)); -#18427 = VECTOR('',#18428,1.); -#18428 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18429 = PCURVE('',#18329,#18430); -#18430 = DEFINITIONAL_REPRESENTATION('',(#18431),#18435); -#18431 = LINE('',#18432,#18433); -#18432 = CARTESIAN_POINT('',(-56.538908,0.2)); -#18433 = VECTOR('',#18434,1.); -#18434 = DIRECTION('',(1.,0.E+000)); -#18435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18436 = PCURVE('',#18437,#18442); -#18437 = PLANE('',#18438); -#18438 = AXIS2_PLACEMENT_3D('',#18439,#18440,#18441); -#18439 = CARTESIAN_POINT('',(55.538908,22.295721,-0.45)); -#18440 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18441 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18442 = DEFINITIONAL_REPRESENTATION('',(#18443),#18447); -#18443 = LINE('',#18444,#18445); -#18444 = CARTESIAN_POINT('',(-55.538908,0.25)); -#18445 = VECTOR('',#18446,1.); -#18446 = DIRECTION('',(1.,0.E+000)); -#18447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18448 = ORIENTED_EDGE('',*,*,#18449,.F.); -#18449 = EDGE_CURVE('',#18450,#18422,#18452,.T.); -#18450 = VERTEX_POINT('',#18451); -#18451 = CARTESIAN_POINT('',(54.938908,22.145721,-0.2)); -#18452 = SURFACE_CURVE('',#18453,(#18457,#18464),.PCURVE_S1.); -#18453 = LINE('',#18454,#18455); -#18454 = CARTESIAN_POINT('',(54.938908,22.495721,-0.2)); -#18455 = VECTOR('',#18456,1.); -#18456 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18457 = PCURVE('',#18329,#18458); -#18458 = DEFINITIONAL_REPRESENTATION('',(#18459),#18463); -#18459 = LINE('',#18460,#18461); -#18460 = CARTESIAN_POINT('',(-1.6,0.E+000)); -#18461 = VECTOR('',#18462,1.); -#18462 = DIRECTION('',(0.E+000,-1.)); -#18463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18464 = PCURVE('',#18465,#18470); -#18465 = PLANE('',#18466); -#18466 = AXIS2_PLACEMENT_3D('',#18467,#18468,#18469); -#18467 = CARTESIAN_POINT('',(54.938908,22.495721,-0.45)); -#18468 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18469 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18470 = DEFINITIONAL_REPRESENTATION('',(#18471),#18475); -#18471 = LINE('',#18472,#18473); -#18472 = CARTESIAN_POINT('',(-0.25,0.E+000)); -#18473 = VECTOR('',#18474,1.); -#18474 = DIRECTION('',(0.E+000,-1.)); -#18475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18476 = ORIENTED_EDGE('',*,*,#18477,.F.); -#18477 = EDGE_CURVE('',#18478,#18450,#18480,.T.); -#18478 = VERTEX_POINT('',#18479); -#18479 = CARTESIAN_POINT('',(54.238908,22.145721,-0.2)); -#18480 = SURFACE_CURVE('',#18481,(#18485,#18492),.PCURVE_S1.); -#18481 = LINE('',#18482,#18483); -#18482 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.2)); -#18483 = VECTOR('',#18484,1.); -#18484 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18485 = PCURVE('',#18329,#18486); -#18486 = DEFINITIONAL_REPRESENTATION('',(#18487),#18491); -#18487 = LINE('',#18488,#18489); -#18488 = CARTESIAN_POINT('',(-5.618951266039,0.35)); -#18489 = VECTOR('',#18490,1.); -#18490 = DIRECTION('',(1.,0.E+000)); -#18491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18492 = PCURVE('',#17883,#18493); -#18493 = DEFINITIONAL_REPRESENTATION('',(#18494),#18498); -#18494 = LINE('',#18495,#18496); -#18495 = CARTESIAN_POINT('',(0.E+000,-1.099011437739)); -#18496 = VECTOR('',#18497,1.); -#18497 = DIRECTION('',(-1.,0.E+000)); -#18498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18499 = ORIENTED_EDGE('',*,*,#18500,.F.); -#18500 = EDGE_CURVE('',#18319,#18478,#18501,.T.); -#18501 = SURFACE_CURVE('',#18502,(#18506,#18513),.PCURVE_S1.); -#18502 = LINE('',#18503,#18504); -#18503 = CARTESIAN_POINT('',(54.238908,22.495721,-0.2)); -#18504 = VECTOR('',#18505,1.); -#18505 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18506 = PCURVE('',#18329,#18507); -#18507 = DEFINITIONAL_REPRESENTATION('',(#18508),#18512); -#18508 = LINE('',#18509,#18510); -#18509 = CARTESIAN_POINT('',(-2.3,0.E+000)); -#18510 = VECTOR('',#18511,1.); -#18511 = DIRECTION('',(0.E+000,1.)); -#18512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18513 = PCURVE('',#18131,#18514); -#18514 = DEFINITIONAL_REPRESENTATION('',(#18515),#18518); -#18515 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18516,#18517),.UNSPECIFIED., +#20530 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#20531 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#20532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20533 = ORIENTED_EDGE('',*,*,#20534,.F.); +#20534 = EDGE_CURVE('',#20535,#20503,#20537,.T.); +#20535 = VERTEX_POINT('',#20536); +#20536 = CARTESIAN_POINT('',(53.938908,22.145721,2.1)); +#20537 = SURFACE_CURVE('',#20538,(#20542,#20549),.PCURVE_S1.); +#20538 = LINE('',#20539,#20540); +#20539 = CARTESIAN_POINT('',(53.938908,22.145721,2.4)); +#20540 = VECTOR('',#20541,1.); +#20541 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20542 = PCURVE('',#20511,#20543); +#20543 = DEFINITIONAL_REPRESENTATION('',(#20544),#20548); +#20544 = LINE('',#20545,#20546); +#20545 = CARTESIAN_POINT('',(-2.6,0.35)); +#20546 = VECTOR('',#20547,1.); +#20547 = DIRECTION('',(1.,0.E+000)); +#20548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20549 = PCURVE('',#20275,#20550); +#20550 = DEFINITIONAL_REPRESENTATION('',(#20551),#20555); +#20551 = LINE('',#20552,#20553); +#20552 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); +#20553 = VECTOR('',#20554,1.); +#20554 = DIRECTION('',(0.E+000,-1.)); +#20555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20556 = ORIENTED_EDGE('',*,*,#20557,.F.); +#20557 = EDGE_CURVE('',#20558,#20535,#20560,.T.); +#20558 = VERTEX_POINT('',#20559); +#20559 = CARTESIAN_POINT('',(53.938908,22.495721,2.1)); +#20560 = SURFACE_CURVE('',#20561,(#20565,#20572),.PCURVE_S1.); +#20561 = LINE('',#20562,#20563); +#20562 = CARTESIAN_POINT('',(53.938908,22.495721,2.1)); +#20563 = VECTOR('',#20564,1.); +#20564 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20565 = PCURVE('',#20511,#20566); +#20566 = DEFINITIONAL_REPRESENTATION('',(#20567),#20571); +#20567 = LINE('',#20568,#20569); +#20568 = CARTESIAN_POINT('',(-2.3,0.E+000)); +#20569 = VECTOR('',#20570,1.); +#20570 = DIRECTION('',(0.E+000,1.)); +#20571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20572 = PCURVE('',#20313,#20573); +#20573 = DEFINITIONAL_REPRESENTATION('',(#20574),#20577); +#20574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20575,#20576),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#18516 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#18517 = CARTESIAN_POINT('',(4.712388980385,0.35)); -#18518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18519 = ADVANCED_FACE('',(#18520),#18535,.F.); -#18520 = FACE_BOUND('',#18521,.T.); -#18521 = EDGE_LOOP('',(#18522,#18557,#18585,#18613)); -#18522 = ORIENTED_EDGE('',*,*,#18523,.F.); -#18523 = EDGE_CURVE('',#18524,#18526,#18528,.T.); -#18524 = VERTEX_POINT('',#18525); -#18525 = CARTESIAN_POINT('',(54.464311330758,22.145721,1.45)); -#18526 = VERTEX_POINT('',#18527); -#18527 = CARTESIAN_POINT('',(56.013504669241,22.145721,1.45)); -#18528 = SURFACE_CURVE('',#18529,(#18534,#18546),.PCURVE_S1.); -#18529 = CIRCLE('',#18530,0.85); -#18530 = AXIS2_PLACEMENT_3D('',#18531,#18532,#18533); -#18531 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18532 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18533 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18534 = PCURVE('',#18535,#18540); -#18535 = PLANE('',#18536); -#18536 = AXIS2_PLACEMENT_3D('',#18537,#18538,#18539); -#18537 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); -#18538 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18539 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18540 = DEFINITIONAL_REPRESENTATION('',(#18541),#18545); -#18541 = CIRCLE('',#18542,0.85); -#18542 = AXIS2_PLACEMENT_2D('',#18543,#18544); -#18543 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#18544 = DIRECTION('',(1.,0.E+000)); -#18545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#20575 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#20576 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#20577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20578 = ORIENTED_EDGE('',*,*,#20579,.T.); +#20579 = EDGE_CURVE('',#20558,#20580,#20582,.T.); +#20580 = VERTEX_POINT('',#20581); +#20581 = CARTESIAN_POINT('',(53.938908,22.495721,2.)); +#20582 = SURFACE_CURVE('',#20583,(#20587,#20594),.PCURVE_S1.); +#20583 = LINE('',#20584,#20585); +#20584 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); +#20585 = VECTOR('',#20586,1.); +#20586 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20587 = PCURVE('',#20511,#20588); +#20588 = DEFINITIONAL_REPRESENTATION('',(#20589),#20593); +#20589 = LINE('',#20590,#20591); +#20590 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20591 = VECTOR('',#20592,1.); +#20592 = DIRECTION('',(1.,0.E+000)); +#20593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20594 = PCURVE('',#20115,#20595); +#20595 = DEFINITIONAL_REPRESENTATION('',(#20596),#20600); +#20596 = LINE('',#20597,#20598); +#20597 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); +#20598 = VECTOR('',#20599,1.); +#20599 = DIRECTION('',(0.E+000,-1.)); +#20600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20601 = ORIENTED_EDGE('',*,*,#20602,.F.); +#20602 = EDGE_CURVE('',#20603,#20580,#20605,.T.); +#20603 = VERTEX_POINT('',#20604); +#20604 = CARTESIAN_POINT('',(53.938908,22.345721,2.)); +#20605 = SURFACE_CURVE('',#20606,(#20610,#20617),.PCURVE_S1.); +#20606 = LINE('',#20607,#20608); +#20607 = CARTESIAN_POINT('',(53.938908,22.495721,2.)); +#20608 = VECTOR('',#20609,1.); +#20609 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20610 = PCURVE('',#20511,#20611); +#20611 = DEFINITIONAL_REPRESENTATION('',(#20612),#20616); +#20612 = LINE('',#20613,#20614); +#20613 = CARTESIAN_POINT('',(-2.2,0.E+000)); +#20614 = VECTOR('',#20615,1.); +#20615 = DIRECTION('',(0.E+000,-1.)); +#20616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20617 = PCURVE('',#20618,#20623); +#20618 = PLANE('',#20619); +#20619 = AXIS2_PLACEMENT_3D('',#20620,#20621,#20622); +#20620 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); +#20621 = DIRECTION('',(0.E+000,0.E+000,1.)); +#20622 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20623 = DEFINITIONAL_REPRESENTATION('',(#20624),#20628); +#20624 = LINE('',#20625,#20626); +#20625 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#20626 = VECTOR('',#20627,1.); +#20627 = DIRECTION('',(0.E+000,-1.)); +#20628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20629 = ORIENTED_EDGE('',*,*,#20630,.T.); +#20630 = EDGE_CURVE('',#20603,#20631,#20633,.T.); +#20631 = VERTEX_POINT('',#20632); +#20632 = CARTESIAN_POINT('',(53.938908,22.345721,0.2)); +#20633 = SURFACE_CURVE('',#20634,(#20638,#20645),.PCURVE_S1.); +#20634 = LINE('',#20635,#20636); +#20635 = CARTESIAN_POINT('',(53.938908,22.345721,0.899011437739)); +#20636 = VECTOR('',#20637,1.); +#20637 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20638 = PCURVE('',#20511,#20639); +#20639 = DEFINITIONAL_REPRESENTATION('',(#20640),#20644); +#20640 = LINE('',#20641,#20642); +#20641 = CARTESIAN_POINT('',(-1.099011437739,0.15)); +#20642 = VECTOR('',#20643,1.); +#20643 = DIRECTION('',(1.,0.E+000)); +#20644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20645 = PCURVE('',#20646,#20651); +#20646 = PLANE('',#20647); +#20647 = AXIS2_PLACEMENT_3D('',#20648,#20649,#20650); +#20648 = CARTESIAN_POINT('',(50.919956733961,22.345721,0.899011437739)); +#20649 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20650 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20651 = DEFINITIONAL_REPRESENTATION('',(#20652),#20656); +#20652 = LINE('',#20653,#20654); +#20653 = CARTESIAN_POINT('',(-3.018951266039,0.E+000)); +#20654 = VECTOR('',#20655,1.); +#20655 = DIRECTION('',(0.E+000,-1.)); +#20656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20657 = ORIENTED_EDGE('',*,*,#20658,.F.); +#20658 = EDGE_CURVE('',#20659,#20631,#20661,.T.); +#20659 = VERTEX_POINT('',#20660); +#20660 = CARTESIAN_POINT('',(53.938908,22.495721,0.2)); +#20661 = SURFACE_CURVE('',#20662,(#20666,#20673),.PCURVE_S1.); +#20662 = LINE('',#20663,#20664); +#20663 = CARTESIAN_POINT('',(53.938908,22.495721,0.2)); +#20664 = VECTOR('',#20665,1.); +#20665 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20666 = PCURVE('',#20511,#20667); +#20667 = DEFINITIONAL_REPRESENTATION('',(#20668),#20672); +#20668 = LINE('',#20669,#20670); +#20669 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#20670 = VECTOR('',#20671,1.); +#20671 = DIRECTION('',(0.E+000,1.)); +#20672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20673 = PCURVE('',#20674,#20679); +#20674 = PLANE('',#20675); +#20675 = AXIS2_PLACEMENT_3D('',#20676,#20677,#20678); +#20676 = CARTESIAN_POINT('',(54.188908,22.495721,0.2)); +#20677 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20678 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20679 = DEFINITIONAL_REPRESENTATION('',(#20680),#20684); +#20680 = LINE('',#20681,#20682); +#20681 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#20682 = VECTOR('',#20683,1.); +#20683 = DIRECTION('',(0.E+000,1.)); +#20684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20685 = ORIENTED_EDGE('',*,*,#20686,.T.); +#20686 = EDGE_CURVE('',#20659,#20501,#20687,.T.); +#20687 = SURFACE_CURVE('',#20688,(#20692,#20699),.PCURVE_S1.); +#20688 = LINE('',#20689,#20690); +#20689 = CARTESIAN_POINT('',(53.938908,22.495721,2.4)); +#20690 = VECTOR('',#20691,1.); +#20691 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20692 = PCURVE('',#20511,#20693); +#20693 = DEFINITIONAL_REPRESENTATION('',(#20694),#20698); +#20694 = LINE('',#20695,#20696); +#20695 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20696 = VECTOR('',#20697,1.); +#20697 = DIRECTION('',(1.,0.E+000)); +#20698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20699 = PCURVE('',#20115,#20700); +#20700 = DEFINITIONAL_REPRESENTATION('',(#20701),#20705); +#20701 = LINE('',#20702,#20703); +#20702 = CARTESIAN_POINT('',(-3.018951266039,1.500988562261)); +#20703 = VECTOR('',#20704,1.); +#20704 = DIRECTION('',(0.E+000,-1.)); +#20705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20706 = ADVANCED_FACE('',(#20707),#20721,.T.); +#20707 = FACE_BOUND('',#20708,.T.); +#20708 = EDGE_LOOP('',(#20709,#20739,#20761,#20784,#20812,#20840,#20868, + #20891)); +#20709 = ORIENTED_EDGE('',*,*,#20710,.T.); +#20710 = EDGE_CURVE('',#20711,#20713,#20715,.T.); +#20711 = VERTEX_POINT('',#20712); +#20712 = CARTESIAN_POINT('',(54.238908,22.495721,-0.2)); +#20713 = VERTEX_POINT('',#20714); +#20714 = CARTESIAN_POINT('',(56.238908,22.495721,-0.2)); +#20715 = SURFACE_CURVE('',#20716,(#20720,#20732),.PCURVE_S1.); +#20716 = LINE('',#20717,#20718); +#20717 = CARTESIAN_POINT('',(53.938908,22.495721,-0.2)); +#20718 = VECTOR('',#20719,1.); +#20719 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20720 = PCURVE('',#20721,#20726); +#20721 = PLANE('',#20722); +#20722 = AXIS2_PLACEMENT_3D('',#20723,#20724,#20725); +#20723 = CARTESIAN_POINT('',(56.538908,22.495721,-0.2)); +#20724 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20725 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20726 = DEFINITIONAL_REPRESENTATION('',(#20727),#20731); +#20727 = LINE('',#20728,#20729); +#20728 = CARTESIAN_POINT('',(-2.6,0.E+000)); +#20729 = VECTOR('',#20730,1.); +#20730 = DIRECTION('',(1.,0.E+000)); +#20731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20732 = PCURVE('',#20115,#20733); +#20733 = DEFINITIONAL_REPRESENTATION('',(#20734),#20738); +#20734 = LINE('',#20735,#20736); +#20735 = CARTESIAN_POINT('',(-3.018951266039,-1.099011437739)); +#20736 = VECTOR('',#20737,1.); +#20737 = DIRECTION('',(-1.,0.E+000)); +#20738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20739 = ORIENTED_EDGE('',*,*,#20740,.T.); +#20740 = EDGE_CURVE('',#20713,#20741,#20743,.T.); +#20741 = VERTEX_POINT('',#20742); +#20742 = CARTESIAN_POINT('',(56.238908,22.145721,-0.2)); +#20743 = SURFACE_CURVE('',#20744,(#20748,#20755),.PCURVE_S1.); +#20744 = LINE('',#20745,#20746); +#20745 = CARTESIAN_POINT('',(56.238908,22.495721,-0.2)); +#20746 = VECTOR('',#20747,1.); +#20747 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20748 = PCURVE('',#20721,#20749); +#20749 = DEFINITIONAL_REPRESENTATION('',(#20750),#20754); +#20750 = LINE('',#20751,#20752); +#20751 = CARTESIAN_POINT('',(-0.3,0.E+000)); +#20752 = VECTOR('',#20753,1.); +#20753 = DIRECTION('',(0.E+000,1.)); +#20754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20755 = PCURVE('',#20088,#20756); +#20756 = DEFINITIONAL_REPRESENTATION('',(#20757),#20760); +#20757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20758,#20759),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); +#20758 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#20759 = CARTESIAN_POINT('',(4.712388980385,0.35)); +#20760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20761 = ORIENTED_EDGE('',*,*,#20762,.F.); +#20762 = EDGE_CURVE('',#20763,#20741,#20765,.T.); +#20763 = VERTEX_POINT('',#20764); +#20764 = CARTESIAN_POINT('',(55.538908,22.145721,-0.2)); +#20765 = SURFACE_CURVE('',#20766,(#20770,#20777),.PCURVE_S1.); +#20766 = LINE('',#20767,#20768); +#20767 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.2)); +#20768 = VECTOR('',#20769,1.); +#20769 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20770 = PCURVE('',#20721,#20771); +#20771 = DEFINITIONAL_REPRESENTATION('',(#20772),#20776); +#20772 = LINE('',#20773,#20774); +#20773 = CARTESIAN_POINT('',(-5.618951266039,0.35)); +#20774 = VECTOR('',#20775,1.); +#20775 = DIRECTION('',(1.,0.E+000)); +#20776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#18546 = PCURVE('',#18547,#18552); -#18547 = CYLINDRICAL_SURFACE('',#18548,0.85); -#18548 = AXIS2_PLACEMENT_3D('',#18549,#18550,#18551); -#18549 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#18550 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18551 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18552 = DEFINITIONAL_REPRESENTATION('',(#18553),#18556); -#18553 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18554,#18555),.UNSPECIFIED., +#20777 = PCURVE('',#20275,#20778); +#20778 = DEFINITIONAL_REPRESENTATION('',(#20779),#20783); +#20779 = LINE('',#20780,#20781); +#20780 = CARTESIAN_POINT('',(0.E+000,-1.099011437739)); +#20781 = VECTOR('',#20782,1.); +#20782 = DIRECTION('',(-1.,0.E+000)); +#20783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20784 = ORIENTED_EDGE('',*,*,#20785,.T.); +#20785 = EDGE_CURVE('',#20763,#20786,#20788,.T.); +#20786 = VERTEX_POINT('',#20787); +#20787 = CARTESIAN_POINT('',(55.538908,22.295721,-0.2)); +#20788 = SURFACE_CURVE('',#20789,(#20793,#20800),.PCURVE_S1.); +#20789 = LINE('',#20790,#20791); +#20790 = CARTESIAN_POINT('',(55.538908,22.495721,-0.2)); +#20791 = VECTOR('',#20792,1.); +#20792 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20793 = PCURVE('',#20721,#20794); +#20794 = DEFINITIONAL_REPRESENTATION('',(#20795),#20799); +#20795 = LINE('',#20796,#20797); +#20796 = CARTESIAN_POINT('',(-1.,0.E+000)); +#20797 = VECTOR('',#20798,1.); +#20798 = DIRECTION('',(0.E+000,-1.)); +#20799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20800 = PCURVE('',#20801,#20806); +#20801 = PLANE('',#20802); +#20802 = AXIS2_PLACEMENT_3D('',#20803,#20804,#20805); +#20803 = CARTESIAN_POINT('',(55.538908,22.495721,0.146060798583)); +#20804 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20805 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20806 = DEFINITIONAL_REPRESENTATION('',(#20807),#20811); +#20807 = LINE('',#20808,#20809); +#20808 = CARTESIAN_POINT('',(0.346060798583,0.E+000)); +#20809 = VECTOR('',#20810,1.); +#20810 = DIRECTION('',(0.E+000,-1.)); +#20811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20812 = ORIENTED_EDGE('',*,*,#20813,.F.); +#20813 = EDGE_CURVE('',#20814,#20786,#20816,.T.); +#20814 = VERTEX_POINT('',#20815); +#20815 = CARTESIAN_POINT('',(54.938908,22.295721,-0.2)); +#20816 = SURFACE_CURVE('',#20817,(#20821,#20828),.PCURVE_S1.); +#20817 = LINE('',#20818,#20819); +#20818 = CARTESIAN_POINT('',(0.E+000,22.295721,-0.2)); +#20819 = VECTOR('',#20820,1.); +#20820 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20821 = PCURVE('',#20721,#20822); +#20822 = DEFINITIONAL_REPRESENTATION('',(#20823),#20827); +#20823 = LINE('',#20824,#20825); +#20824 = CARTESIAN_POINT('',(-56.538908,0.2)); +#20825 = VECTOR('',#20826,1.); +#20826 = DIRECTION('',(1.,0.E+000)); +#20827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20828 = PCURVE('',#20829,#20834); +#20829 = PLANE('',#20830); +#20830 = AXIS2_PLACEMENT_3D('',#20831,#20832,#20833); +#20831 = CARTESIAN_POINT('',(55.538908,22.295721,-0.45)); +#20832 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20833 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20834 = DEFINITIONAL_REPRESENTATION('',(#20835),#20839); +#20835 = LINE('',#20836,#20837); +#20836 = CARTESIAN_POINT('',(-55.538908,0.25)); +#20837 = VECTOR('',#20838,1.); +#20838 = DIRECTION('',(1.,0.E+000)); +#20839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20840 = ORIENTED_EDGE('',*,*,#20841,.F.); +#20841 = EDGE_CURVE('',#20842,#20814,#20844,.T.); +#20842 = VERTEX_POINT('',#20843); +#20843 = CARTESIAN_POINT('',(54.938908,22.145721,-0.2)); +#20844 = SURFACE_CURVE('',#20845,(#20849,#20856),.PCURVE_S1.); +#20845 = LINE('',#20846,#20847); +#20846 = CARTESIAN_POINT('',(54.938908,22.495721,-0.2)); +#20847 = VECTOR('',#20848,1.); +#20848 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20849 = PCURVE('',#20721,#20850); +#20850 = DEFINITIONAL_REPRESENTATION('',(#20851),#20855); +#20851 = LINE('',#20852,#20853); +#20852 = CARTESIAN_POINT('',(-1.6,0.E+000)); +#20853 = VECTOR('',#20854,1.); +#20854 = DIRECTION('',(0.E+000,-1.)); +#20855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20856 = PCURVE('',#20857,#20862); +#20857 = PLANE('',#20858); +#20858 = AXIS2_PLACEMENT_3D('',#20859,#20860,#20861); +#20859 = CARTESIAN_POINT('',(54.938908,22.495721,-0.45)); +#20860 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20861 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#20862 = DEFINITIONAL_REPRESENTATION('',(#20863),#20867); +#20863 = LINE('',#20864,#20865); +#20864 = CARTESIAN_POINT('',(-0.25,0.E+000)); +#20865 = VECTOR('',#20866,1.); +#20866 = DIRECTION('',(0.E+000,-1.)); +#20867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20868 = ORIENTED_EDGE('',*,*,#20869,.F.); +#20869 = EDGE_CURVE('',#20870,#20842,#20872,.T.); +#20870 = VERTEX_POINT('',#20871); +#20871 = CARTESIAN_POINT('',(54.238908,22.145721,-0.2)); +#20872 = SURFACE_CURVE('',#20873,(#20877,#20884),.PCURVE_S1.); +#20873 = LINE('',#20874,#20875); +#20874 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.2)); +#20875 = VECTOR('',#20876,1.); +#20876 = DIRECTION('',(1.,0.E+000,0.E+000)); +#20877 = PCURVE('',#20721,#20878); +#20878 = DEFINITIONAL_REPRESENTATION('',(#20879),#20883); +#20879 = LINE('',#20880,#20881); +#20880 = CARTESIAN_POINT('',(-5.618951266039,0.35)); +#20881 = VECTOR('',#20882,1.); +#20882 = DIRECTION('',(1.,0.E+000)); +#20883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20884 = PCURVE('',#20275,#20885); +#20885 = DEFINITIONAL_REPRESENTATION('',(#20886),#20890); +#20886 = LINE('',#20887,#20888); +#20887 = CARTESIAN_POINT('',(0.E+000,-1.099011437739)); +#20888 = VECTOR('',#20889,1.); +#20889 = DIRECTION('',(-1.,0.E+000)); +#20890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20891 = ORIENTED_EDGE('',*,*,#20892,.F.); +#20892 = EDGE_CURVE('',#20711,#20870,#20893,.T.); +#20893 = SURFACE_CURVE('',#20894,(#20898,#20905),.PCURVE_S1.); +#20894 = LINE('',#20895,#20896); +#20895 = CARTESIAN_POINT('',(54.238908,22.495721,-0.2)); +#20896 = VECTOR('',#20897,1.); +#20897 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#20898 = PCURVE('',#20721,#20899); +#20899 = DEFINITIONAL_REPRESENTATION('',(#20900),#20904); +#20900 = LINE('',#20901,#20902); +#20901 = CARTESIAN_POINT('',(-2.3,0.E+000)); +#20902 = VECTOR('',#20903,1.); +#20903 = DIRECTION('',(0.E+000,1.)); +#20904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20905 = PCURVE('',#20523,#20906); +#20906 = DEFINITIONAL_REPRESENTATION('',(#20907),#20910); +#20907 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20908,#20909),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); +#20908 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#20909 = CARTESIAN_POINT('',(4.712388980385,0.35)); +#20910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20911 = ADVANCED_FACE('',(#20912),#20927,.F.); +#20912 = FACE_BOUND('',#20913,.T.); +#20913 = EDGE_LOOP('',(#20914,#20949,#20977,#21005)); +#20914 = ORIENTED_EDGE('',*,*,#20915,.F.); +#20915 = EDGE_CURVE('',#20916,#20918,#20920,.T.); +#20916 = VERTEX_POINT('',#20917); +#20917 = CARTESIAN_POINT('',(54.464311330758,22.145721,1.45)); +#20918 = VERTEX_POINT('',#20919); +#20919 = CARTESIAN_POINT('',(56.013504669241,22.145721,1.45)); +#20920 = SURFACE_CURVE('',#20921,(#20926,#20938),.PCURVE_S1.); +#20921 = CIRCLE('',#20922,0.85); +#20922 = AXIS2_PLACEMENT_3D('',#20923,#20924,#20925); +#20923 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#20924 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20925 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20926 = PCURVE('',#20927,#20932); +#20927 = PLANE('',#20928); +#20928 = AXIS2_PLACEMENT_3D('',#20929,#20930,#20931); +#20929 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); +#20930 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20931 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20932 = DEFINITIONAL_REPRESENTATION('',(#20933),#20937); +#20933 = CIRCLE('',#20934,0.85); +#20934 = AXIS2_PLACEMENT_2D('',#20935,#20936); +#20935 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#20936 = DIRECTION('',(1.,0.E+000)); +#20937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20938 = PCURVE('',#20939,#20944); +#20939 = CYLINDRICAL_SURFACE('',#20940,0.85); +#20940 = AXIS2_PLACEMENT_3D('',#20941,#20942,#20943); +#20941 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#20942 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20943 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20944 = DEFINITIONAL_REPRESENTATION('',(#20945),#20948); +#20945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20946,#20947),.UNSPECIFIED., .F.,.F.,(2,2),(0.424389708593,2.717202944997), .PIECEWISE_BEZIER_KNOTS.); -#18554 = CARTESIAN_POINT('',(0.424389708593,-0.35)); -#18555 = CARTESIAN_POINT('',(2.717202944997,-0.35)); -#18556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18557 = ORIENTED_EDGE('',*,*,#18558,.T.); -#18558 = EDGE_CURVE('',#18524,#18559,#18561,.T.); -#18559 = VERTEX_POINT('',#18560); -#18560 = CARTESIAN_POINT('',(54.814643931288,22.145721,1.45)); -#18561 = SURFACE_CURVE('',#18562,(#18566,#18573),.PCURVE_S1.); -#18562 = LINE('',#18563,#18564); -#18563 = CARTESIAN_POINT('',(50.919956733961,22.145721,1.45)); -#18564 = VECTOR('',#18565,1.); -#18565 = DIRECTION('',(1.,0.E+000,1.110223024625E-016)); -#18566 = PCURVE('',#18535,#18567); -#18567 = DEFINITIONAL_REPRESENTATION('',(#18568),#18572); -#18568 = LINE('',#18569,#18570); -#18569 = CARTESIAN_POINT('',(0.E+000,0.550988562261)); -#18570 = VECTOR('',#18571,1.); -#18571 = DIRECTION('',(-1.,1.110223024625E-016)); -#18572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18573 = PCURVE('',#18574,#18579); -#18574 = PLANE('',#18575); -#18575 = AXIS2_PLACEMENT_3D('',#18576,#18577,#18578); -#18576 = CARTESIAN_POINT('',(54.464311330758,22.145721,1.45)); -#18577 = DIRECTION('',(-1.110223024625E-016,0.E+000,1.)); -#18578 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); -#18579 = DEFINITIONAL_REPRESENTATION('',(#18580),#18584); -#18580 = LINE('',#18581,#18582); -#18581 = CARTESIAN_POINT('',(3.544354596797,0.E+000)); -#18582 = VECTOR('',#18583,1.); -#18583 = DIRECTION('',(-1.,0.E+000)); -#18584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18585 = ORIENTED_EDGE('',*,*,#18586,.T.); -#18586 = EDGE_CURVE('',#18559,#18587,#18589,.T.); -#18587 = VERTEX_POINT('',#18588); -#18588 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); -#18589 = SURFACE_CURVE('',#18590,(#18595,#18602),.PCURVE_S1.); -#18590 = CIRCLE('',#18591,0.55); -#18591 = AXIS2_PLACEMENT_3D('',#18592,#18593,#18594); -#18592 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18593 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18594 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18595 = PCURVE('',#18535,#18596); -#18596 = DEFINITIONAL_REPRESENTATION('',(#18597),#18601); -#18597 = CIRCLE('',#18598,0.55); -#18598 = AXIS2_PLACEMENT_2D('',#18599,#18600); -#18599 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#18600 = DIRECTION('',(1.,0.E+000)); -#18601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18602 = PCURVE('',#18603,#18608); -#18603 = CYLINDRICAL_SURFACE('',#18604,0.55); -#18604 = AXIS2_PLACEMENT_3D('',#18605,#18606,#18607); -#18605 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18606 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18607 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18608 = DEFINITIONAL_REPRESENTATION('',(#18609),#18612); -#18609 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18610,#18611),.UNSPECIFIED., +#20946 = CARTESIAN_POINT('',(0.424389708593,-0.35)); +#20947 = CARTESIAN_POINT('',(2.717202944997,-0.35)); +#20948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20949 = ORIENTED_EDGE('',*,*,#20950,.T.); +#20950 = EDGE_CURVE('',#20916,#20951,#20953,.T.); +#20951 = VERTEX_POINT('',#20952); +#20952 = CARTESIAN_POINT('',(54.814643931288,22.145721,1.45)); +#20953 = SURFACE_CURVE('',#20954,(#20958,#20965),.PCURVE_S1.); +#20954 = LINE('',#20955,#20956); +#20955 = CARTESIAN_POINT('',(50.919956733961,22.145721,1.45)); +#20956 = VECTOR('',#20957,1.); +#20957 = DIRECTION('',(1.,0.E+000,1.110223024625E-016)); +#20958 = PCURVE('',#20927,#20959); +#20959 = DEFINITIONAL_REPRESENTATION('',(#20960),#20964); +#20960 = LINE('',#20961,#20962); +#20961 = CARTESIAN_POINT('',(0.E+000,0.550988562261)); +#20962 = VECTOR('',#20963,1.); +#20963 = DIRECTION('',(-1.,1.110223024625E-016)); +#20964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20965 = PCURVE('',#20966,#20971); +#20966 = PLANE('',#20967); +#20967 = AXIS2_PLACEMENT_3D('',#20968,#20969,#20970); +#20968 = CARTESIAN_POINT('',(54.464311330758,22.145721,1.45)); +#20969 = DIRECTION('',(-1.110223024625E-016,0.E+000,1.)); +#20970 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); +#20971 = DEFINITIONAL_REPRESENTATION('',(#20972),#20976); +#20972 = LINE('',#20973,#20974); +#20973 = CARTESIAN_POINT('',(3.544354596797,0.E+000)); +#20974 = VECTOR('',#20975,1.); +#20975 = DIRECTION('',(-1.,0.E+000)); +#20976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20977 = ORIENTED_EDGE('',*,*,#20978,.T.); +#20978 = EDGE_CURVE('',#20951,#20979,#20981,.T.); +#20979 = VERTEX_POINT('',#20980); +#20980 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); +#20981 = SURFACE_CURVE('',#20982,(#20987,#20994),.PCURVE_S1.); +#20982 = CIRCLE('',#20983,0.55); +#20983 = AXIS2_PLACEMENT_3D('',#20984,#20985,#20986); +#20984 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#20985 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20986 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#20987 = PCURVE('',#20927,#20988); +#20988 = DEFINITIONAL_REPRESENTATION('',(#20989),#20993); +#20989 = CIRCLE('',#20990,0.55); +#20990 = AXIS2_PLACEMENT_2D('',#20991,#20992); +#20991 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#20992 = DIRECTION('',(1.,0.E+000)); +#20993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#20994 = PCURVE('',#20995,#21000); +#20995 = CYLINDRICAL_SURFACE('',#20996,0.55); +#20996 = AXIS2_PLACEMENT_3D('',#20997,#20998,#20999); +#20997 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#20998 = DIRECTION('',(0.E+000,1.,0.E+000)); +#20999 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21000 = DEFINITIONAL_REPRESENTATION('',(#21001),#21004); +#21001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21002,#21003),.UNSPECIFIED., .F.,.F.,(2,2),(0.689775000786,2.451817652804), .PIECEWISE_BEZIER_KNOTS.); -#18610 = CARTESIAN_POINT('',(0.689775000786,0.E+000)); -#18611 = CARTESIAN_POINT('',(2.451817652804,0.E+000)); -#18612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18613 = ORIENTED_EDGE('',*,*,#18614,.T.); -#18614 = EDGE_CURVE('',#18587,#18526,#18615,.T.); -#18615 = SURFACE_CURVE('',#18616,(#18620,#18627),.PCURVE_S1.); -#18616 = LINE('',#18617,#18618); -#18617 = CARTESIAN_POINT('',(50.919956733961,22.145721,1.45)); -#18618 = VECTOR('',#18619,1.); -#18619 = DIRECTION('',(1.,0.E+000,1.110223024625E-016)); -#18620 = PCURVE('',#18535,#18621); -#18621 = DEFINITIONAL_REPRESENTATION('',(#18622),#18626); -#18622 = LINE('',#18623,#18624); -#18623 = CARTESIAN_POINT('',(0.E+000,0.550988562261)); -#18624 = VECTOR('',#18625,1.); -#18625 = DIRECTION('',(-1.,1.110223024625E-016)); -#18626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18627 = PCURVE('',#18628,#18633); -#18628 = PLANE('',#18629); -#18629 = AXIS2_PLACEMENT_3D('',#18630,#18631,#18632); -#18630 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); -#18631 = DIRECTION('',(-1.110223024625E-016,0.E+000,1.)); -#18632 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); -#18633 = DEFINITIONAL_REPRESENTATION('',(#18634),#18638); -#18634 = LINE('',#18635,#18636); -#18635 = CARTESIAN_POINT('',(4.743215334751,0.E+000)); -#18636 = VECTOR('',#18637,1.); -#18637 = DIRECTION('',(-1.,0.E+000)); -#18638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18639 = ADVANCED_FACE('',(#18640),#17883,.F.); -#18640 = FACE_BOUND('',#18641,.T.); -#18641 = EDGE_LOOP('',(#18642,#18643,#18668,#18669,#18694,#18695,#18720, - #18721,#18746,#18747,#18775,#18803,#18831,#18854)); -#18642 = ORIENTED_EDGE('',*,*,#18370,.T.); -#18643 = ORIENTED_EDGE('',*,*,#18644,.T.); -#18644 = EDGE_CURVE('',#18349,#17676,#18645,.T.); -#18645 = SURFACE_CURVE('',#18646,(#18651,#18662),.PCURVE_S1.); -#18646 = CIRCLE('',#18647,0.3); -#18647 = AXIS2_PLACEMENT_3D('',#18648,#18649,#18650); -#18648 = CARTESIAN_POINT('',(56.238908,22.145721,1.E-001)); -#18649 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18650 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18651 = PCURVE('',#17883,#18652); -#18652 = DEFINITIONAL_REPRESENTATION('',(#18653),#18661); -#18653 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18654,#18655,#18656,#18657 - ,#18658,#18659,#18660),.UNSPECIFIED.,.T.,.F.) +#21002 = CARTESIAN_POINT('',(0.689775000786,0.E+000)); +#21003 = CARTESIAN_POINT('',(2.451817652804,0.E+000)); +#21004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21005 = ORIENTED_EDGE('',*,*,#21006,.T.); +#21006 = EDGE_CURVE('',#20979,#20918,#21007,.T.); +#21007 = SURFACE_CURVE('',#21008,(#21012,#21019),.PCURVE_S1.); +#21008 = LINE('',#21009,#21010); +#21009 = CARTESIAN_POINT('',(50.919956733961,22.145721,1.45)); +#21010 = VECTOR('',#21011,1.); +#21011 = DIRECTION('',(1.,0.E+000,1.110223024625E-016)); +#21012 = PCURVE('',#20927,#21013); +#21013 = DEFINITIONAL_REPRESENTATION('',(#21014),#21018); +#21014 = LINE('',#21015,#21016); +#21015 = CARTESIAN_POINT('',(0.E+000,0.550988562261)); +#21016 = VECTOR('',#21017,1.); +#21017 = DIRECTION('',(-1.,1.110223024625E-016)); +#21018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21019 = PCURVE('',#21020,#21025); +#21020 = PLANE('',#21021); +#21021 = AXIS2_PLACEMENT_3D('',#21022,#21023,#21024); +#21022 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); +#21023 = DIRECTION('',(-1.110223024625E-016,0.E+000,1.)); +#21024 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); +#21025 = DEFINITIONAL_REPRESENTATION('',(#21026),#21030); +#21026 = LINE('',#21027,#21028); +#21027 = CARTESIAN_POINT('',(4.743215334751,0.E+000)); +#21028 = VECTOR('',#21029,1.); +#21029 = DIRECTION('',(-1.,0.E+000)); +#21030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21031 = ADVANCED_FACE('',(#21032),#20275,.F.); +#21032 = FACE_BOUND('',#21033,.T.); +#21033 = EDGE_LOOP('',(#21034,#21035,#21060,#21061,#21086,#21087,#21112, + #21113,#21138,#21139,#21167,#21195,#21223,#21246)); +#21034 = ORIENTED_EDGE('',*,*,#20762,.T.); +#21035 = ORIENTED_EDGE('',*,*,#21036,.T.); +#21036 = EDGE_CURVE('',#20741,#20068,#21037,.T.); +#21037 = SURFACE_CURVE('',#21038,(#21043,#21054),.PCURVE_S1.); +#21038 = CIRCLE('',#21039,0.3); +#21039 = AXIS2_PLACEMENT_3D('',#21040,#21041,#21042); +#21040 = CARTESIAN_POINT('',(56.238908,22.145721,1.E-001)); +#21041 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21042 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21043 = PCURVE('',#20275,#21044); +#21044 = DEFINITIONAL_REPRESENTATION('',(#21045),#21053); +#21045 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21046,#21047,#21048,#21049 + ,#21050,#21051,#21052),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#18654 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); -#18655 = CARTESIAN_POINT('',(-5.618951266039,-0.279396195469)); -#18656 = CARTESIAN_POINT('',(-5.168951266039,-0.539203816604)); -#18657 = CARTESIAN_POINT('',(-4.718951266039,-0.799011437739)); -#18658 = CARTESIAN_POINT('',(-5.168951266039,-1.058819058875)); -#18659 = CARTESIAN_POINT('',(-5.618951266039,-1.31862668001)); -#18660 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); -#18661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18662 = PCURVE('',#17696,#18663); -#18663 = DEFINITIONAL_REPRESENTATION('',(#18664),#18667); -#18664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18665,#18666),.UNSPECIFIED., +#21046 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); +#21047 = CARTESIAN_POINT('',(-5.618951266039,-0.279396195469)); +#21048 = CARTESIAN_POINT('',(-5.168951266039,-0.539203816604)); +#21049 = CARTESIAN_POINT('',(-4.718951266039,-0.799011437739)); +#21050 = CARTESIAN_POINT('',(-5.168951266039,-1.058819058875)); +#21051 = CARTESIAN_POINT('',(-5.618951266039,-1.31862668001)); +#21052 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); +#21053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21054 = PCURVE('',#20088,#21055); +#21055 = DEFINITIONAL_REPRESENTATION('',(#21056),#21059); +#21056 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21057,#21058),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#18665 = CARTESIAN_POINT('',(4.712388980385,0.35)); -#18666 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#18667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18668 = ORIENTED_EDGE('',*,*,#17869,.T.); -#18669 = ORIENTED_EDGE('',*,*,#18670,.T.); -#18670 = EDGE_CURVE('',#17843,#17933,#18671,.T.); -#18671 = SURFACE_CURVE('',#18672,(#18677,#18688),.PCURVE_S1.); -#18672 = CIRCLE('',#18673,0.3); -#18673 = AXIS2_PLACEMENT_3D('',#18674,#18675,#18676); -#18674 = CARTESIAN_POINT('',(56.238908,22.145721,2.1)); -#18675 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18676 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18677 = PCURVE('',#17883,#18678); -#18678 = DEFINITIONAL_REPRESENTATION('',(#18679),#18687); -#18679 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18680,#18681,#18682,#18683 - ,#18684,#18685,#18686),.UNSPECIFIED.,.T.,.F.) +#21057 = CARTESIAN_POINT('',(4.712388980385,0.35)); +#21058 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#21059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21060 = ORIENTED_EDGE('',*,*,#20261,.T.); +#21061 = ORIENTED_EDGE('',*,*,#21062,.T.); +#21062 = EDGE_CURVE('',#20235,#20325,#21063,.T.); +#21063 = SURFACE_CURVE('',#21064,(#21069,#21080),.PCURVE_S1.); +#21064 = CIRCLE('',#21065,0.3); +#21065 = AXIS2_PLACEMENT_3D('',#21066,#21067,#21068); +#21066 = CARTESIAN_POINT('',(56.238908,22.145721,2.1)); +#21067 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21068 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21069 = PCURVE('',#20275,#21070); +#21070 = DEFINITIONAL_REPRESENTATION('',(#21071),#21079); +#21071 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21072,#21073,#21074,#21075 + ,#21076,#21077,#21078),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#18680 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); -#18681 = CARTESIAN_POINT('',(-5.618951266039,1.720603804531)); -#18682 = CARTESIAN_POINT('',(-5.168951266039,1.460796183396)); -#18683 = CARTESIAN_POINT('',(-4.718951266039,1.200988562261)); -#18684 = CARTESIAN_POINT('',(-5.168951266039,0.941180941125)); -#18685 = CARTESIAN_POINT('',(-5.618951266039,0.68137331999)); -#18686 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); -#18687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18688 = PCURVE('',#17858,#18689); -#18689 = DEFINITIONAL_REPRESENTATION('',(#18690),#18693); -#18690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18691,#18692),.UNSPECIFIED., +#21072 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); +#21073 = CARTESIAN_POINT('',(-5.618951266039,1.720603804531)); +#21074 = CARTESIAN_POINT('',(-5.168951266039,1.460796183396)); +#21075 = CARTESIAN_POINT('',(-4.718951266039,1.200988562261)); +#21076 = CARTESIAN_POINT('',(-5.168951266039,0.941180941125)); +#21077 = CARTESIAN_POINT('',(-5.618951266039,0.68137331999)); +#21078 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); +#21079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21080 = PCURVE('',#20250,#21081); +#21081 = DEFINITIONAL_REPRESENTATION('',(#21082),#21085); +#21082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21083,#21084),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#18691 = CARTESIAN_POINT('',(0.E+000,0.35)); -#18692 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#18693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18694 = ORIENTED_EDGE('',*,*,#17932,.T.); -#18695 = ORIENTED_EDGE('',*,*,#18696,.T.); -#18696 = EDGE_CURVE('',#17901,#18143,#18697,.T.); -#18697 = SURFACE_CURVE('',#18698,(#18703,#18714),.PCURVE_S1.); -#18698 = CIRCLE('',#18699,0.3); -#18699 = AXIS2_PLACEMENT_3D('',#18700,#18701,#18702); -#18700 = CARTESIAN_POINT('',(54.238908,22.145721,2.1)); -#18701 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18702 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18703 = PCURVE('',#17883,#18704); -#18704 = DEFINITIONAL_REPRESENTATION('',(#18705),#18713); -#18705 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18706,#18707,#18708,#18709 - ,#18710,#18711,#18712),.UNSPECIFIED.,.T.,.F.) +#21083 = CARTESIAN_POINT('',(0.E+000,0.35)); +#21084 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#21085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21086 = ORIENTED_EDGE('',*,*,#20324,.T.); +#21087 = ORIENTED_EDGE('',*,*,#21088,.T.); +#21088 = EDGE_CURVE('',#20293,#20535,#21089,.T.); +#21089 = SURFACE_CURVE('',#21090,(#21095,#21106),.PCURVE_S1.); +#21090 = CIRCLE('',#21091,0.3); +#21091 = AXIS2_PLACEMENT_3D('',#21092,#21093,#21094); +#21092 = CARTESIAN_POINT('',(54.238908,22.145721,2.1)); +#21093 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21094 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21095 = PCURVE('',#20275,#21096); +#21096 = DEFINITIONAL_REPRESENTATION('',(#21097),#21105); +#21097 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21098,#21099,#21100,#21101 + ,#21102,#21103,#21104),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#18706 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); -#18707 = CARTESIAN_POINT('',(-3.618951266039,1.720603804531)); -#18708 = CARTESIAN_POINT('',(-3.168951266039,1.460796183396)); -#18709 = CARTESIAN_POINT('',(-2.718951266039,1.200988562261)); -#18710 = CARTESIAN_POINT('',(-3.168951266039,0.941180941125)); -#18711 = CARTESIAN_POINT('',(-3.618951266039,0.68137331999)); -#18712 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); -#18713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18714 = PCURVE('',#17921,#18715); -#18715 = DEFINITIONAL_REPRESENTATION('',(#18716),#18719); -#18716 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18717,#18718),.UNSPECIFIED., +#21098 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); +#21099 = CARTESIAN_POINT('',(-3.618951266039,1.720603804531)); +#21100 = CARTESIAN_POINT('',(-3.168951266039,1.460796183396)); +#21101 = CARTESIAN_POINT('',(-2.718951266039,1.200988562261)); +#21102 = CARTESIAN_POINT('',(-3.168951266039,0.941180941125)); +#21103 = CARTESIAN_POINT('',(-3.618951266039,0.68137331999)); +#21104 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); +#21105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21106 = PCURVE('',#20313,#21107); +#21107 = DEFINITIONAL_REPRESENTATION('',(#21108),#21111); +#21108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21109,#21110),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#18717 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#18718 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#18719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18720 = ORIENTED_EDGE('',*,*,#18142,.T.); -#18721 = ORIENTED_EDGE('',*,*,#18722,.T.); -#18722 = EDGE_CURVE('',#18111,#18478,#18723,.T.); -#18723 = SURFACE_CURVE('',#18724,(#18729,#18740),.PCURVE_S1.); -#18724 = CIRCLE('',#18725,0.3); -#18725 = AXIS2_PLACEMENT_3D('',#18726,#18727,#18728); -#18726 = CARTESIAN_POINT('',(54.238908,22.145721,1.E-001)); -#18727 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18728 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18729 = PCURVE('',#17883,#18730); -#18730 = DEFINITIONAL_REPRESENTATION('',(#18731),#18739); -#18731 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#18732,#18733,#18734,#18735 - ,#18736,#18737,#18738),.UNSPECIFIED.,.T.,.F.) +#21109 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#21110 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#21111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21112 = ORIENTED_EDGE('',*,*,#20534,.T.); +#21113 = ORIENTED_EDGE('',*,*,#21114,.T.); +#21114 = EDGE_CURVE('',#20503,#20870,#21115,.T.); +#21115 = SURFACE_CURVE('',#21116,(#21121,#21132),.PCURVE_S1.); +#21116 = CIRCLE('',#21117,0.3); +#21117 = AXIS2_PLACEMENT_3D('',#21118,#21119,#21120); +#21118 = CARTESIAN_POINT('',(54.238908,22.145721,1.E-001)); +#21119 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21120 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21121 = PCURVE('',#20275,#21122); +#21122 = DEFINITIONAL_REPRESENTATION('',(#21123),#21131); +#21123 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21124,#21125,#21126,#21127 + ,#21128,#21129,#21130),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#18732 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); -#18733 = CARTESIAN_POINT('',(-3.618951266039,-0.279396195469)); -#18734 = CARTESIAN_POINT('',(-3.168951266039,-0.539203816604)); -#18735 = CARTESIAN_POINT('',(-2.718951266039,-0.799011437739)); -#18736 = CARTESIAN_POINT('',(-3.168951266039,-1.058819058875)); -#18737 = CARTESIAN_POINT('',(-3.618951266039,-1.31862668001)); -#18738 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); -#18739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18740 = PCURVE('',#18131,#18741); -#18741 = DEFINITIONAL_REPRESENTATION('',(#18742),#18745); -#18742 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18743,#18744),.UNSPECIFIED., +#21124 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); +#21125 = CARTESIAN_POINT('',(-3.618951266039,-0.279396195469)); +#21126 = CARTESIAN_POINT('',(-3.168951266039,-0.539203816604)); +#21127 = CARTESIAN_POINT('',(-2.718951266039,-0.799011437739)); +#21128 = CARTESIAN_POINT('',(-3.168951266039,-1.058819058875)); +#21129 = CARTESIAN_POINT('',(-3.618951266039,-1.31862668001)); +#21130 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); +#21131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21132 = PCURVE('',#20523,#21133); +#21133 = DEFINITIONAL_REPRESENTATION('',(#21134),#21137); +#21134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21135,#21136),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#18743 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#18744 = CARTESIAN_POINT('',(4.712388980385,0.35)); -#18745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18746 = ORIENTED_EDGE('',*,*,#18477,.T.); -#18747 = ORIENTED_EDGE('',*,*,#18748,.F.); -#18748 = EDGE_CURVE('',#18749,#18450,#18751,.T.); -#18749 = VERTEX_POINT('',#18750); -#18750 = CARTESIAN_POINT('',(54.938908,22.145721,0.146060798583)); -#18751 = SURFACE_CURVE('',#18752,(#18756,#18763),.PCURVE_S1.); -#18752 = LINE('',#18753,#18754); -#18753 = CARTESIAN_POINT('',(54.938908,22.145721,0.899011437739)); -#18754 = VECTOR('',#18755,1.); -#18755 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18756 = PCURVE('',#17883,#18757); -#18757 = DEFINITIONAL_REPRESENTATION('',(#18758),#18762); -#18758 = LINE('',#18759,#18760); -#18759 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); -#18760 = VECTOR('',#18761,1.); -#18761 = DIRECTION('',(0.E+000,-1.)); -#18762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18763 = PCURVE('',#18764,#18769); -#18764 = PLANE('',#18765); -#18765 = AXIS2_PLACEMENT_3D('',#18766,#18767,#18768); -#18766 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); -#18767 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18768 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18769 = DEFINITIONAL_REPRESENTATION('',(#18770),#18774); -#18770 = LINE('',#18771,#18772); -#18771 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); -#18772 = VECTOR('',#18773,1.); -#18773 = DIRECTION('',(0.E+000,-1.)); -#18774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18775 = ORIENTED_EDGE('',*,*,#18776,.T.); -#18776 = EDGE_CURVE('',#18749,#18777,#18779,.T.); -#18777 = VERTEX_POINT('',#18778); -#18778 = CARTESIAN_POINT('',(54.238908,22.145721,1.1)); -#18779 = SURFACE_CURVE('',#18780,(#18785,#18792),.PCURVE_S1.); -#18780 = CIRCLE('',#18781,1.); -#18781 = AXIS2_PLACEMENT_3D('',#18782,#18783,#18784); -#18782 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18783 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18784 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18785 = PCURVE('',#17883,#18786); -#18786 = DEFINITIONAL_REPRESENTATION('',(#18787),#18791); -#18787 = CIRCLE('',#18788,1.); -#18788 = AXIS2_PLACEMENT_2D('',#18789,#18790); -#18789 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#18790 = DIRECTION('',(1.,0.E+000)); -#18791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18792 = PCURVE('',#18793,#18798); -#18793 = CYLINDRICAL_SURFACE('',#18794,1.); -#18794 = AXIS2_PLACEMENT_3D('',#18795,#18796,#18797); -#18795 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#18796 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18797 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18798 = DEFINITIONAL_REPRESENTATION('',(#18799),#18802); -#18799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18800,#18801),.UNSPECIFIED., +#21135 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#21136 = CARTESIAN_POINT('',(4.712388980385,0.35)); +#21137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21138 = ORIENTED_EDGE('',*,*,#20869,.T.); +#21139 = ORIENTED_EDGE('',*,*,#21140,.F.); +#21140 = EDGE_CURVE('',#21141,#20842,#21143,.T.); +#21141 = VERTEX_POINT('',#21142); +#21142 = CARTESIAN_POINT('',(54.938908,22.145721,0.146060798583)); +#21143 = SURFACE_CURVE('',#21144,(#21148,#21155),.PCURVE_S1.); +#21144 = LINE('',#21145,#21146); +#21145 = CARTESIAN_POINT('',(54.938908,22.145721,0.899011437739)); +#21146 = VECTOR('',#21147,1.); +#21147 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21148 = PCURVE('',#20275,#21149); +#21149 = DEFINITIONAL_REPRESENTATION('',(#21150),#21154); +#21150 = LINE('',#21151,#21152); +#21151 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); +#21152 = VECTOR('',#21153,1.); +#21153 = DIRECTION('',(0.E+000,-1.)); +#21154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21155 = PCURVE('',#21156,#21161); +#21156 = PLANE('',#21157); +#21157 = AXIS2_PLACEMENT_3D('',#21158,#21159,#21160); +#21158 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); +#21159 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21160 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21161 = DEFINITIONAL_REPRESENTATION('',(#21162),#21166); +#21162 = LINE('',#21163,#21164); +#21163 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); +#21164 = VECTOR('',#21165,1.); +#21165 = DIRECTION('',(0.E+000,-1.)); +#21166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21167 = ORIENTED_EDGE('',*,*,#21168,.T.); +#21168 = EDGE_CURVE('',#21141,#21169,#21171,.T.); +#21169 = VERTEX_POINT('',#21170); +#21170 = CARTESIAN_POINT('',(54.238908,22.145721,1.1)); +#21171 = SURFACE_CURVE('',#21172,(#21177,#21184),.PCURVE_S1.); +#21172 = CIRCLE('',#21173,1.); +#21173 = AXIS2_PLACEMENT_3D('',#21174,#21175,#21176); +#21174 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21175 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21176 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21177 = PCURVE('',#20275,#21178); +#21178 = DEFINITIONAL_REPRESENTATION('',(#21179),#21183); +#21179 = CIRCLE('',#21180,1.); +#21180 = AXIS2_PLACEMENT_2D('',#21181,#21182); +#21181 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21182 = DIRECTION('',(1.,0.E+000)); +#21183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21184 = PCURVE('',#21185,#21190); +#21185 = CYLINDRICAL_SURFACE('',#21186,1.); +#21186 = AXIS2_PLACEMENT_3D('',#21187,#21188,#21189); +#21187 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#21188 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21189 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21190 = DEFINITIONAL_REPRESENTATION('',(#21191),#21194); +#21191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21192,#21193),.UNSPECIFIED., .F.,.F.,(2,2),(5.0170816344,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#18800 = CARTESIAN_POINT('',(5.0170816344,-0.35)); -#18801 = CARTESIAN_POINT('',(6.28318530718,-0.35)); -#18802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18803 = ORIENTED_EDGE('',*,*,#18804,.T.); -#18804 = EDGE_CURVE('',#18777,#18805,#18807,.T.); -#18805 = VERTEX_POINT('',#18806); -#18806 = CARTESIAN_POINT('',(56.238908,22.145721,1.1)); -#18807 = SURFACE_CURVE('',#18808,(#18813,#18820),.PCURVE_S1.); -#18808 = CIRCLE('',#18809,1.); -#18809 = AXIS2_PLACEMENT_3D('',#18810,#18811,#18812); -#18810 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18811 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18812 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18813 = PCURVE('',#17883,#18814); -#18814 = DEFINITIONAL_REPRESENTATION('',(#18815),#18819); -#18815 = CIRCLE('',#18816,1.); -#18816 = AXIS2_PLACEMENT_2D('',#18817,#18818); -#18817 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#18818 = DIRECTION('',(1.,0.E+000)); -#18819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18820 = PCURVE('',#18821,#18826); -#18821 = CYLINDRICAL_SURFACE('',#18822,1.); -#18822 = AXIS2_PLACEMENT_3D('',#18823,#18824,#18825); -#18823 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#18824 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18825 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18826 = DEFINITIONAL_REPRESENTATION('',(#18827),#18830); -#18827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18828,#18829),.UNSPECIFIED., +#21192 = CARTESIAN_POINT('',(5.0170816344,-0.35)); +#21193 = CARTESIAN_POINT('',(6.28318530718,-0.35)); +#21194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21195 = ORIENTED_EDGE('',*,*,#21196,.T.); +#21196 = EDGE_CURVE('',#21169,#21197,#21199,.T.); +#21197 = VERTEX_POINT('',#21198); +#21198 = CARTESIAN_POINT('',(56.238908,22.145721,1.1)); +#21199 = SURFACE_CURVE('',#21200,(#21205,#21212),.PCURVE_S1.); +#21200 = CIRCLE('',#21201,1.); +#21201 = AXIS2_PLACEMENT_3D('',#21202,#21203,#21204); +#21202 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21203 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21204 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21205 = PCURVE('',#20275,#21206); +#21206 = DEFINITIONAL_REPRESENTATION('',(#21207),#21211); +#21207 = CIRCLE('',#21208,1.); +#21208 = AXIS2_PLACEMENT_2D('',#21209,#21210); +#21209 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21210 = DIRECTION('',(1.,0.E+000)); +#21211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21212 = PCURVE('',#21213,#21218); +#21213 = CYLINDRICAL_SURFACE('',#21214,1.); +#21214 = AXIS2_PLACEMENT_3D('',#21215,#21216,#21217); +#21215 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#21216 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21217 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21218 = DEFINITIONAL_REPRESENTATION('',(#21219),#21222); +#21219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21220,#21221),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#18828 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#18829 = CARTESIAN_POINT('',(3.14159265359,-0.35)); -#18830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18831 = ORIENTED_EDGE('',*,*,#18832,.T.); -#18832 = EDGE_CURVE('',#18805,#18833,#18835,.T.); -#18833 = VERTEX_POINT('',#18834); -#18834 = CARTESIAN_POINT('',(55.538908,22.145721,0.146060798583)); -#18835 = SURFACE_CURVE('',#18836,(#18841,#18848),.PCURVE_S1.); -#18836 = CIRCLE('',#18837,1.); -#18837 = AXIS2_PLACEMENT_3D('',#18838,#18839,#18840); -#18838 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#18839 = DIRECTION('',(0.E+000,1.,0.E+000)); -#18840 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18841 = PCURVE('',#17883,#18842); -#18842 = DEFINITIONAL_REPRESENTATION('',(#18843),#18847); -#18843 = CIRCLE('',#18844,1.); -#18844 = AXIS2_PLACEMENT_2D('',#18845,#18846); -#18845 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#18846 = DIRECTION('',(1.,0.E+000)); -#18847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18848 = PCURVE('',#18793,#18849); -#18849 = DEFINITIONAL_REPRESENTATION('',(#18850),#18853); -#18850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#18851,#18852),.UNSPECIFIED., +#21220 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#21221 = CARTESIAN_POINT('',(3.14159265359,-0.35)); +#21222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21223 = ORIENTED_EDGE('',*,*,#21224,.T.); +#21224 = EDGE_CURVE('',#21197,#21225,#21227,.T.); +#21225 = VERTEX_POINT('',#21226); +#21226 = CARTESIAN_POINT('',(55.538908,22.145721,0.146060798583)); +#21227 = SURFACE_CURVE('',#21228,(#21233,#21240),.PCURVE_S1.); +#21228 = CIRCLE('',#21229,1.); +#21229 = AXIS2_PLACEMENT_3D('',#21230,#21231,#21232); +#21230 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21231 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21232 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21233 = PCURVE('',#20275,#21234); +#21234 = DEFINITIONAL_REPRESENTATION('',(#21235),#21239); +#21235 = CIRCLE('',#21236,1.); +#21236 = AXIS2_PLACEMENT_2D('',#21237,#21238); +#21237 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21238 = DIRECTION('',(1.,0.E+000)); +#21239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21240 = PCURVE('',#21185,#21241); +#21241 = DEFINITIONAL_REPRESENTATION('',(#21242),#21245); +#21242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21243,#21244),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.407696326369), .PIECEWISE_BEZIER_KNOTS.); -#18851 = CARTESIAN_POINT('',(3.14159265359,-0.35)); -#18852 = CARTESIAN_POINT('',(4.407696326369,-0.35)); -#18853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18854 = ORIENTED_EDGE('',*,*,#18855,.T.); -#18855 = EDGE_CURVE('',#18833,#18371,#18856,.T.); -#18856 = SURFACE_CURVE('',#18857,(#18861,#18868),.PCURVE_S1.); -#18857 = LINE('',#18858,#18859); -#18858 = CARTESIAN_POINT('',(55.538908,22.145721,0.899011437739)); -#18859 = VECTOR('',#18860,1.); -#18860 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18861 = PCURVE('',#17883,#18862); -#18862 = DEFINITIONAL_REPRESENTATION('',(#18863),#18867); -#18863 = LINE('',#18864,#18865); -#18864 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); -#18865 = VECTOR('',#18866,1.); -#18866 = DIRECTION('',(0.E+000,-1.)); -#18867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21243 = CARTESIAN_POINT('',(3.14159265359,-0.35)); +#21244 = CARTESIAN_POINT('',(4.407696326369,-0.35)); +#21245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21246 = ORIENTED_EDGE('',*,*,#21247,.T.); +#21247 = EDGE_CURVE('',#21225,#20763,#21248,.T.); +#21248 = SURFACE_CURVE('',#21249,(#21253,#21260),.PCURVE_S1.); +#21249 = LINE('',#21250,#21251); +#21250 = CARTESIAN_POINT('',(55.538908,22.145721,0.899011437739)); +#21251 = VECTOR('',#21252,1.); +#21252 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21253 = PCURVE('',#20275,#21254); +#21254 = DEFINITIONAL_REPRESENTATION('',(#21255),#21259); +#21255 = LINE('',#21256,#21257); +#21256 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); +#21257 = VECTOR('',#21258,1.); +#21258 = DIRECTION('',(0.E+000,-1.)); +#21259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21260 = PCURVE('',#21156,#21261); +#21261 = DEFINITIONAL_REPRESENTATION('',(#21262),#21266); +#21262 = LINE('',#21263,#21264); +#21263 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); +#21264 = VECTOR('',#21265,1.); +#21265 = DIRECTION('',(0.E+000,-1.)); +#21266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21267 = ADVANCED_FACE('',(#21268),#20829,.F.); +#21268 = FACE_BOUND('',#21269,.T.); +#21269 = EDGE_LOOP('',(#21270,#21293,#21294,#21317)); +#21270 = ORIENTED_EDGE('',*,*,#21271,.T.); +#21271 = EDGE_CURVE('',#21272,#20814,#21274,.T.); +#21272 = VERTEX_POINT('',#21273); +#21273 = CARTESIAN_POINT('',(54.938908,22.295721,-0.45)); +#21274 = SURFACE_CURVE('',#21275,(#21279,#21286),.PCURVE_S1.); +#21275 = LINE('',#21276,#21277); +#21276 = CARTESIAN_POINT('',(54.938908,22.295721,0.899011437739)); +#21277 = VECTOR('',#21278,1.); +#21278 = DIRECTION('',(0.E+000,0.E+000,1.)); +#21279 = PCURVE('',#20829,#21280); +#21280 = DEFINITIONAL_REPRESENTATION('',(#21281),#21285); +#21281 = LINE('',#21282,#21283); +#21282 = CARTESIAN_POINT('',(-0.6,1.349011437739)); +#21283 = VECTOR('',#21284,1.); +#21284 = DIRECTION('',(0.E+000,1.)); +#21285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21286 = PCURVE('',#20857,#21287); +#21287 = DEFINITIONAL_REPRESENTATION('',(#21288),#21292); +#21288 = LINE('',#21289,#21290); +#21289 = CARTESIAN_POINT('',(-1.349011437739,0.2)); +#21290 = VECTOR('',#21291,1.); +#21291 = DIRECTION('',(-1.,0.E+000)); +#21292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21293 = ORIENTED_EDGE('',*,*,#20813,.T.); +#21294 = ORIENTED_EDGE('',*,*,#21295,.F.); +#21295 = EDGE_CURVE('',#21296,#20786,#21298,.T.); +#21296 = VERTEX_POINT('',#21297); +#21297 = CARTESIAN_POINT('',(55.538908,22.295721,-0.45)); +#21298 = SURFACE_CURVE('',#21299,(#21303,#21310),.PCURVE_S1.); +#21299 = LINE('',#21300,#21301); +#21300 = CARTESIAN_POINT('',(55.538908,22.295721,0.899011437739)); +#21301 = VECTOR('',#21302,1.); +#21302 = DIRECTION('',(0.E+000,0.E+000,1.)); +#21303 = PCURVE('',#20829,#21304); +#21304 = DEFINITIONAL_REPRESENTATION('',(#21305),#21309); +#21305 = LINE('',#21306,#21307); +#21306 = CARTESIAN_POINT('',(0.E+000,1.349011437739)); +#21307 = VECTOR('',#21308,1.); +#21308 = DIRECTION('',(0.E+000,1.)); +#21309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21310 = PCURVE('',#20801,#21311); +#21311 = DEFINITIONAL_REPRESENTATION('',(#21312),#21316); +#21312 = LINE('',#21313,#21314); +#21313 = CARTESIAN_POINT('',(-0.752950639156,0.2)); +#21314 = VECTOR('',#21315,1.); +#21315 = DIRECTION('',(-1.,0.E+000)); +#21316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21317 = ORIENTED_EDGE('',*,*,#21318,.T.); +#21318 = EDGE_CURVE('',#21296,#21272,#21319,.T.); +#21319 = SURFACE_CURVE('',#21320,(#21324,#21331),.PCURVE_S1.); +#21320 = LINE('',#21321,#21322); +#21321 = CARTESIAN_POINT('',(50.919956733961,22.295721,-0.45)); +#21322 = VECTOR('',#21323,1.); +#21323 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21324 = PCURVE('',#20829,#21325); +#21325 = DEFINITIONAL_REPRESENTATION('',(#21326),#21330); +#21326 = LINE('',#21327,#21328); +#21327 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); +#21328 = VECTOR('',#21329,1.); +#21329 = DIRECTION('',(-1.,0.E+000)); +#21330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21331 = PCURVE('',#21332,#21337); +#21332 = PLANE('',#21333); +#21333 = AXIS2_PLACEMENT_3D('',#21334,#21335,#21336); +#21334 = CARTESIAN_POINT('',(55.538908,22.495721,-0.45)); +#21335 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21336 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21337 = DEFINITIONAL_REPRESENTATION('',(#21338),#21342); +#21338 = LINE('',#21339,#21340); +#21339 = CARTESIAN_POINT('',(-4.618951266039,0.2)); +#21340 = VECTOR('',#21341,1.); +#21341 = DIRECTION('',(-1.,0.E+000)); +#21342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21343 = ADVANCED_FACE('',(#21344),#21358,.T.); +#21344 = FACE_BOUND('',#21345,.T.); +#21345 = EDGE_LOOP('',(#21346,#21376,#21399,#21422)); +#21346 = ORIENTED_EDGE('',*,*,#21347,.F.); +#21347 = EDGE_CURVE('',#21348,#21350,#21352,.T.); +#21348 = VERTEX_POINT('',#21349); +#21349 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); +#21350 = VERTEX_POINT('',#21351); +#21351 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); +#21352 = SURFACE_CURVE('',#21353,(#21357,#21369),.PCURVE_S1.); +#21353 = LINE('',#21354,#21355); +#21354 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); +#21355 = VECTOR('',#21356,1.); +#21356 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21357 = PCURVE('',#21358,#21363); +#21358 = PLANE('',#21359); +#21359 = AXIS2_PLACEMENT_3D('',#21360,#21361,#21362); +#21360 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); +#21361 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21362 = DIRECTION('',(0.E+000,0.E+000,1.)); +#21363 = DEFINITIONAL_REPRESENTATION('',(#21364),#21368); +#21364 = LINE('',#21365,#21366); +#21365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#21366 = VECTOR('',#21367,1.); +#21367 = DIRECTION('',(-1.,0.E+000)); +#21368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21369 = PCURVE('',#20115,#21370); +#21370 = DEFINITIONAL_REPRESENTATION('',(#21371),#21375); +#21371 = LINE('',#21372,#21373); +#21372 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); +#21373 = VECTOR('',#21374,1.); +#21374 = DIRECTION('',(0.E+000,-1.)); +#21375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21376 = ORIENTED_EDGE('',*,*,#21377,.T.); +#21377 = EDGE_CURVE('',#21348,#21378,#21380,.T.); +#21378 = VERTEX_POINT('',#21379); +#21379 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); +#21380 = SURFACE_CURVE('',#21381,(#21385,#21392),.PCURVE_S1.); +#21381 = LINE('',#21382,#21383); +#21382 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); +#21383 = VECTOR('',#21384,1.); +#21384 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21385 = PCURVE('',#21358,#21386); +#21386 = DEFINITIONAL_REPRESENTATION('',(#21387),#21391); +#21387 = LINE('',#21388,#21389); +#21388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#21389 = VECTOR('',#21390,1.); +#21390 = DIRECTION('',(0.E+000,1.)); +#21391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21392 = PCURVE('',#20199,#21393); +#21393 = DEFINITIONAL_REPRESENTATION('',(#21394),#21398); +#21394 = LINE('',#21395,#21396); +#21395 = CARTESIAN_POINT('',(-0.45,0.E+000)); +#21396 = VECTOR('',#21397,1.); +#21397 = DIRECTION('',(0.E+000,1.)); +#21398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21399 = ORIENTED_EDGE('',*,*,#21400,.T.); +#21400 = EDGE_CURVE('',#21378,#21401,#21403,.T.); +#21401 = VERTEX_POINT('',#21402); +#21402 = CARTESIAN_POINT('',(56.738908,22.345721,0.2)); +#21403 = SURFACE_CURVE('',#21404,(#21408,#21415),.PCURVE_S1.); +#21404 = LINE('',#21405,#21406); +#21405 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); +#21406 = VECTOR('',#21407,1.); +#21407 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21408 = PCURVE('',#21358,#21409); +#21409 = DEFINITIONAL_REPRESENTATION('',(#21410),#21414); +#21410 = LINE('',#21411,#21412); +#21411 = CARTESIAN_POINT('',(0.E+000,0.15)); +#21412 = VECTOR('',#21413,1.); +#21413 = DIRECTION('',(-1.,0.E+000)); +#21414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21415 = PCURVE('',#20171,#21416); +#21416 = DEFINITIONAL_REPRESENTATION('',(#21417),#21421); +#21417 = LINE('',#21418,#21419); +#21418 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); +#21419 = VECTOR('',#21420,1.); +#21420 = DIRECTION('',(0.E+000,-1.)); +#21421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21422 = ORIENTED_EDGE('',*,*,#21423,.F.); +#21423 = EDGE_CURVE('',#21350,#21401,#21424,.T.); +#21424 = SURFACE_CURVE('',#21425,(#21429,#21436),.PCURVE_S1.); +#21425 = LINE('',#21426,#21427); +#21426 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); +#21427 = VECTOR('',#21428,1.); +#21428 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21429 = PCURVE('',#21358,#21430); +#21430 = DEFINITIONAL_REPRESENTATION('',(#21431),#21435); +#21431 = LINE('',#21432,#21433); +#21432 = CARTESIAN_POINT('',(-1.8,0.E+000)); +#21433 = VECTOR('',#21434,1.); +#21434 = DIRECTION('',(0.E+000,1.)); +#21435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21436 = PCURVE('',#20143,#21437); +#21437 = DEFINITIONAL_REPRESENTATION('',(#21438),#21442); +#21438 = LINE('',#21439,#21440); +#21439 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#21440 = VECTOR('',#21441,1.); +#21441 = DIRECTION('',(0.E+000,1.)); +#21442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#18868 = PCURVE('',#18764,#18869); -#18869 = DEFINITIONAL_REPRESENTATION('',(#18870),#18874); -#18870 = LINE('',#18871,#18872); -#18871 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); -#18872 = VECTOR('',#18873,1.); -#18873 = DIRECTION('',(0.E+000,-1.)); -#18874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18875 = ADVANCED_FACE('',(#18876),#18437,.F.); -#18876 = FACE_BOUND('',#18877,.T.); -#18877 = EDGE_LOOP('',(#18878,#18901,#18902,#18925)); -#18878 = ORIENTED_EDGE('',*,*,#18879,.T.); -#18879 = EDGE_CURVE('',#18880,#18422,#18882,.T.); -#18880 = VERTEX_POINT('',#18881); -#18881 = CARTESIAN_POINT('',(54.938908,22.295721,-0.45)); -#18882 = SURFACE_CURVE('',#18883,(#18887,#18894),.PCURVE_S1.); -#18883 = LINE('',#18884,#18885); -#18884 = CARTESIAN_POINT('',(54.938908,22.295721,0.899011437739)); -#18885 = VECTOR('',#18886,1.); -#18886 = DIRECTION('',(0.E+000,0.E+000,1.)); -#18887 = PCURVE('',#18437,#18888); -#18888 = DEFINITIONAL_REPRESENTATION('',(#18889),#18893); -#18889 = LINE('',#18890,#18891); -#18890 = CARTESIAN_POINT('',(-0.6,1.349011437739)); -#18891 = VECTOR('',#18892,1.); -#18892 = DIRECTION('',(0.E+000,1.)); -#18893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18894 = PCURVE('',#18465,#18895); -#18895 = DEFINITIONAL_REPRESENTATION('',(#18896),#18900); -#18896 = LINE('',#18897,#18898); -#18897 = CARTESIAN_POINT('',(-1.349011437739,0.2)); -#18898 = VECTOR('',#18899,1.); -#18899 = DIRECTION('',(-1.,0.E+000)); -#18900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18901 = ORIENTED_EDGE('',*,*,#18421,.T.); -#18902 = ORIENTED_EDGE('',*,*,#18903,.F.); -#18903 = EDGE_CURVE('',#18904,#18394,#18906,.T.); -#18904 = VERTEX_POINT('',#18905); -#18905 = CARTESIAN_POINT('',(55.538908,22.295721,-0.45)); -#18906 = SURFACE_CURVE('',#18907,(#18911,#18918),.PCURVE_S1.); -#18907 = LINE('',#18908,#18909); -#18908 = CARTESIAN_POINT('',(55.538908,22.295721,0.899011437739)); -#18909 = VECTOR('',#18910,1.); -#18910 = DIRECTION('',(0.E+000,0.E+000,1.)); -#18911 = PCURVE('',#18437,#18912); -#18912 = DEFINITIONAL_REPRESENTATION('',(#18913),#18917); -#18913 = LINE('',#18914,#18915); -#18914 = CARTESIAN_POINT('',(0.E+000,1.349011437739)); -#18915 = VECTOR('',#18916,1.); -#18916 = DIRECTION('',(0.E+000,1.)); -#18917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18918 = PCURVE('',#18409,#18919); -#18919 = DEFINITIONAL_REPRESENTATION('',(#18920),#18924); -#18920 = LINE('',#18921,#18922); -#18921 = CARTESIAN_POINT('',(-0.752950639156,0.2)); -#18922 = VECTOR('',#18923,1.); -#18923 = DIRECTION('',(-1.,0.E+000)); -#18924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18925 = ORIENTED_EDGE('',*,*,#18926,.T.); -#18926 = EDGE_CURVE('',#18904,#18880,#18927,.T.); -#18927 = SURFACE_CURVE('',#18928,(#18932,#18939),.PCURVE_S1.); -#18928 = LINE('',#18929,#18930); -#18929 = CARTESIAN_POINT('',(50.919956733961,22.295721,-0.45)); -#18930 = VECTOR('',#18931,1.); -#18931 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#18932 = PCURVE('',#18437,#18933); -#18933 = DEFINITIONAL_REPRESENTATION('',(#18934),#18938); -#18934 = LINE('',#18935,#18936); -#18935 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); -#18936 = VECTOR('',#18937,1.); -#18937 = DIRECTION('',(-1.,0.E+000)); -#18938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18939 = PCURVE('',#18940,#18945); -#18940 = PLANE('',#18941); -#18941 = AXIS2_PLACEMENT_3D('',#18942,#18943,#18944); -#18942 = CARTESIAN_POINT('',(55.538908,22.495721,-0.45)); -#18943 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18944 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18945 = DEFINITIONAL_REPRESENTATION('',(#18946),#18950); -#18946 = LINE('',#18947,#18948); -#18947 = CARTESIAN_POINT('',(-4.618951266039,0.2)); -#18948 = VECTOR('',#18949,1.); -#18949 = DIRECTION('',(-1.,0.E+000)); -#18950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18951 = ADVANCED_FACE('',(#18952),#18966,.T.); -#18952 = FACE_BOUND('',#18953,.T.); -#18953 = EDGE_LOOP('',(#18954,#18984,#19007,#19030)); -#18954 = ORIENTED_EDGE('',*,*,#18955,.F.); -#18955 = EDGE_CURVE('',#18956,#18958,#18960,.T.); -#18956 = VERTEX_POINT('',#18957); -#18957 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); -#18958 = VERTEX_POINT('',#18959); -#18959 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); -#18960 = SURFACE_CURVE('',#18961,(#18965,#18977),.PCURVE_S1.); -#18961 = LINE('',#18962,#18963); -#18962 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); -#18963 = VECTOR('',#18964,1.); -#18964 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#18965 = PCURVE('',#18966,#18971); -#18966 = PLANE('',#18967); -#18967 = AXIS2_PLACEMENT_3D('',#18968,#18969,#18970); -#18968 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); -#18969 = DIRECTION('',(1.,0.E+000,0.E+000)); -#18970 = DIRECTION('',(0.E+000,0.E+000,1.)); -#18971 = DEFINITIONAL_REPRESENTATION('',(#18972),#18976); -#18972 = LINE('',#18973,#18974); -#18973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#18974 = VECTOR('',#18975,1.); -#18975 = DIRECTION('',(-1.,0.E+000)); -#18976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18977 = PCURVE('',#17723,#18978); -#18978 = DEFINITIONAL_REPRESENTATION('',(#18979),#18983); -#18979 = LINE('',#18980,#18981); -#18980 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); -#18981 = VECTOR('',#18982,1.); -#18982 = DIRECTION('',(0.E+000,-1.)); -#18983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#18984 = ORIENTED_EDGE('',*,*,#18985,.T.); -#18985 = EDGE_CURVE('',#18956,#18986,#18988,.T.); -#18986 = VERTEX_POINT('',#18987); -#18987 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); -#18988 = SURFACE_CURVE('',#18989,(#18993,#19000),.PCURVE_S1.); -#18989 = LINE('',#18990,#18991); -#18990 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); -#18991 = VECTOR('',#18992,1.); -#18992 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#18993 = PCURVE('',#18966,#18994); -#18994 = DEFINITIONAL_REPRESENTATION('',(#18995),#18999); -#18995 = LINE('',#18996,#18997); -#18996 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#18997 = VECTOR('',#18998,1.); -#18998 = DIRECTION('',(0.E+000,1.)); -#18999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19000 = PCURVE('',#17807,#19001); -#19001 = DEFINITIONAL_REPRESENTATION('',(#19002),#19006); -#19002 = LINE('',#19003,#19004); -#19003 = CARTESIAN_POINT('',(-0.45,0.E+000)); -#19004 = VECTOR('',#19005,1.); -#19005 = DIRECTION('',(0.E+000,1.)); -#19006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19007 = ORIENTED_EDGE('',*,*,#19008,.T.); -#19008 = EDGE_CURVE('',#18986,#19009,#19011,.T.); -#19009 = VERTEX_POINT('',#19010); -#19010 = CARTESIAN_POINT('',(56.738908,22.345721,0.2)); -#19011 = SURFACE_CURVE('',#19012,(#19016,#19023),.PCURVE_S1.); -#19012 = LINE('',#19013,#19014); -#19013 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); -#19014 = VECTOR('',#19015,1.); -#19015 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#19016 = PCURVE('',#18966,#19017); -#19017 = DEFINITIONAL_REPRESENTATION('',(#19018),#19022); -#19018 = LINE('',#19019,#19020); -#19019 = CARTESIAN_POINT('',(0.E+000,0.15)); -#19020 = VECTOR('',#19021,1.); -#19021 = DIRECTION('',(-1.,0.E+000)); -#19022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19023 = PCURVE('',#17779,#19024); -#19024 = DEFINITIONAL_REPRESENTATION('',(#19025),#19029); -#19025 = LINE('',#19026,#19027); -#19026 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); -#19027 = VECTOR('',#19028,1.); -#19028 = DIRECTION('',(0.E+000,-1.)); -#19029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19030 = ORIENTED_EDGE('',*,*,#19031,.F.); -#19031 = EDGE_CURVE('',#18958,#19009,#19032,.T.); -#19032 = SURFACE_CURVE('',#19033,(#19037,#19044),.PCURVE_S1.); -#19033 = LINE('',#19034,#19035); -#19034 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); -#19035 = VECTOR('',#19036,1.); -#19036 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19037 = PCURVE('',#18966,#19038); -#19038 = DEFINITIONAL_REPRESENTATION('',(#19039),#19043); -#19039 = LINE('',#19040,#19041); -#19040 = CARTESIAN_POINT('',(-1.8,0.E+000)); -#19041 = VECTOR('',#19042,1.); -#19042 = DIRECTION('',(0.E+000,1.)); -#19043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19044 = PCURVE('',#17751,#19045); -#19045 = DEFINITIONAL_REPRESENTATION('',(#19046),#19050); -#19046 = LINE('',#19047,#19048); -#19047 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19048 = VECTOR('',#19049,1.); -#19049 = DIRECTION('',(0.E+000,1.)); -#19050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19051 = ADVANCED_FACE('',(#19052),#17807,.T.); -#19052 = FACE_BOUND('',#19053,.T.); -#19053 = EDGE_LOOP('',(#19054,#19055,#19076,#19077)); -#19054 = ORIENTED_EDGE('',*,*,#17791,.T.); -#19055 = ORIENTED_EDGE('',*,*,#19056,.F.); -#19056 = EDGE_CURVE('',#18986,#17764,#19057,.T.); -#19057 = SURFACE_CURVE('',#19058,(#19062,#19069),.PCURVE_S1.); -#19058 = LINE('',#19059,#19060); -#19059 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); -#19060 = VECTOR('',#19061,1.); -#19061 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19062 = PCURVE('',#17807,#19063); -#19063 = DEFINITIONAL_REPRESENTATION('',(#19064),#19068); -#19064 = LINE('',#19065,#19066); -#19065 = CARTESIAN_POINT('',(-0.45,0.15)); -#19066 = VECTOR('',#19067,1.); -#19067 = DIRECTION('',(1.,0.E+000)); -#19068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21443 = ADVANCED_FACE('',(#21444),#20199,.T.); +#21444 = FACE_BOUND('',#21445,.T.); +#21445 = EDGE_LOOP('',(#21446,#21447,#21468,#21469)); +#21446 = ORIENTED_EDGE('',*,*,#20183,.T.); +#21447 = ORIENTED_EDGE('',*,*,#21448,.F.); +#21448 = EDGE_CURVE('',#21378,#20156,#21449,.T.); +#21449 = SURFACE_CURVE('',#21450,(#21454,#21461),.PCURVE_S1.); +#21450 = LINE('',#21451,#21452); +#21451 = CARTESIAN_POINT('',(56.738908,22.345721,2.)); +#21452 = VECTOR('',#21453,1.); +#21453 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21454 = PCURVE('',#20199,#21455); +#21455 = DEFINITIONAL_REPRESENTATION('',(#21456),#21460); +#21456 = LINE('',#21457,#21458); +#21457 = CARTESIAN_POINT('',(-0.45,0.15)); +#21458 = VECTOR('',#21459,1.); +#21459 = DIRECTION('',(1.,0.E+000)); +#21460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21461 = PCURVE('',#20171,#21462); +#21462 = DEFINITIONAL_REPRESENTATION('',(#21463),#21467); +#21463 = LINE('',#21464,#21465); +#21464 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); +#21465 = VECTOR('',#21466,1.); +#21466 = DIRECTION('',(1.,0.E+000)); +#21467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21468 = ORIENTED_EDGE('',*,*,#21377,.F.); +#21469 = ORIENTED_EDGE('',*,*,#21470,.T.); +#21470 = EDGE_CURVE('',#21348,#20184,#21471,.T.); +#21471 = SURFACE_CURVE('',#21472,(#21476,#21483),.PCURVE_S1.); +#21472 = LINE('',#21473,#21474); +#21473 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); +#21474 = VECTOR('',#21475,1.); +#21475 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21476 = PCURVE('',#20199,#21477); +#21477 = DEFINITIONAL_REPRESENTATION('',(#21478),#21482); +#21478 = LINE('',#21479,#21480); +#21479 = CARTESIAN_POINT('',(-0.45,0.E+000)); +#21480 = VECTOR('',#21481,1.); +#21481 = DIRECTION('',(1.,0.E+000)); +#21482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21483 = PCURVE('',#20115,#21484); +#21484 = DEFINITIONAL_REPRESENTATION('',(#21485),#21489); +#21485 = LINE('',#21486,#21487); +#21486 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); +#21487 = VECTOR('',#21488,1.); +#21488 = DIRECTION('',(1.,0.E+000)); +#21489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19069 = PCURVE('',#17779,#19070); -#19070 = DEFINITIONAL_REPRESENTATION('',(#19071),#19075); -#19071 = LINE('',#19072,#19073); -#19072 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); -#19073 = VECTOR('',#19074,1.); -#19074 = DIRECTION('',(1.,0.E+000)); -#19075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19076 = ORIENTED_EDGE('',*,*,#18985,.F.); -#19077 = ORIENTED_EDGE('',*,*,#19078,.T.); -#19078 = EDGE_CURVE('',#18956,#17792,#19079,.T.); -#19079 = SURFACE_CURVE('',#19080,(#19084,#19091),.PCURVE_S1.); -#19080 = LINE('',#19081,#19082); -#19081 = CARTESIAN_POINT('',(56.738908,22.495721,2.)); -#19082 = VECTOR('',#19083,1.); -#19083 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19084 = PCURVE('',#17807,#19085); -#19085 = DEFINITIONAL_REPRESENTATION('',(#19086),#19090); -#19086 = LINE('',#19087,#19088); -#19087 = CARTESIAN_POINT('',(-0.45,0.E+000)); -#19088 = VECTOR('',#19089,1.); -#19089 = DIRECTION('',(1.,0.E+000)); -#19090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19091 = PCURVE('',#17723,#19092); -#19092 = DEFINITIONAL_REPRESENTATION('',(#19093),#19097); -#19093 = LINE('',#19094,#19095); -#19094 = CARTESIAN_POINT('',(-5.818951266039,1.100988562261)); -#19095 = VECTOR('',#19096,1.); -#19096 = DIRECTION('',(1.,0.E+000)); -#19097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19098 = ADVANCED_FACE('',(#19099),#17696,.T.); -#19099 = FACE_BOUND('',#19100,.T.); -#19100 = EDGE_LOOP('',(#19101,#19102,#19103,#19104)); -#19101 = ORIENTED_EDGE('',*,*,#17673,.T.); -#19102 = ORIENTED_EDGE('',*,*,#18644,.F.); -#19103 = ORIENTED_EDGE('',*,*,#18348,.F.); -#19104 = ORIENTED_EDGE('',*,*,#19105,.T.); -#19105 = EDGE_CURVE('',#18321,#17674,#19106,.T.); -#19106 = SURFACE_CURVE('',#19107,(#19112,#19118),.PCURVE_S1.); -#19107 = CIRCLE('',#19108,0.3); -#19108 = AXIS2_PLACEMENT_3D('',#19109,#19110,#19111); -#19109 = CARTESIAN_POINT('',(56.238908,22.495721,1.E-001)); -#19110 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19111 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19112 = PCURVE('',#17696,#19113); -#19113 = DEFINITIONAL_REPRESENTATION('',(#19114),#19117); -#19114 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19115,#19116),.UNSPECIFIED., +#21490 = ADVANCED_FACE('',(#21491),#20088,.T.); +#21491 = FACE_BOUND('',#21492,.T.); +#21492 = EDGE_LOOP('',(#21493,#21494,#21495,#21496)); +#21493 = ORIENTED_EDGE('',*,*,#20065,.T.); +#21494 = ORIENTED_EDGE('',*,*,#21036,.F.); +#21495 = ORIENTED_EDGE('',*,*,#20740,.F.); +#21496 = ORIENTED_EDGE('',*,*,#21497,.T.); +#21497 = EDGE_CURVE('',#20713,#20066,#21498,.T.); +#21498 = SURFACE_CURVE('',#21499,(#21504,#21510),.PCURVE_S1.); +#21499 = CIRCLE('',#21500,0.3); +#21500 = AXIS2_PLACEMENT_3D('',#21501,#21502,#21503); +#21501 = CARTESIAN_POINT('',(56.238908,22.495721,1.E-001)); +#21502 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21503 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21504 = PCURVE('',#20088,#21505); +#21505 = DEFINITIONAL_REPRESENTATION('',(#21506),#21509); +#21506 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21507,#21508),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#19115 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#19116 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#19117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21507 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#21508 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#21509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19118 = PCURVE('',#17723,#19119); -#19119 = DEFINITIONAL_REPRESENTATION('',(#19120),#19128); -#19120 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#19121,#19122,#19123,#19124 - ,#19125,#19126,#19127),.UNSPECIFIED.,.T.,.F.) +#21510 = PCURVE('',#20115,#21511); +#21511 = DEFINITIONAL_REPRESENTATION('',(#21512),#21520); +#21512 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21513,#21514,#21515,#21516 + ,#21517,#21518,#21519),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#19121 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); -#19122 = CARTESIAN_POINT('',(-5.618951266039,-0.279396195469)); -#19123 = CARTESIAN_POINT('',(-5.168951266039,-0.539203816604)); -#19124 = CARTESIAN_POINT('',(-4.718951266039,-0.799011437739)); -#19125 = CARTESIAN_POINT('',(-5.168951266039,-1.058819058875)); -#19126 = CARTESIAN_POINT('',(-5.618951266039,-1.31862668001)); -#19127 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); -#19128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19129 = ADVANCED_FACE('',(#19130),#18254,.F.); -#19130 = FACE_BOUND('',#19131,.T.); -#19131 = EDGE_LOOP('',(#19132,#19133,#19156,#19184)); -#19132 = ORIENTED_EDGE('',*,*,#18238,.F.); -#19133 = ORIENTED_EDGE('',*,*,#19134,.T.); -#19134 = EDGE_CURVE('',#18211,#19135,#19137,.T.); -#19135 = VERTEX_POINT('',#19136); -#19136 = CARTESIAN_POINT('',(53.738908,22.345721,2.)); -#19137 = SURFACE_CURVE('',#19138,(#19142,#19149),.PCURVE_S1.); -#19138 = LINE('',#19139,#19140); -#19139 = CARTESIAN_POINT('',(54.188908,22.345721,2.)); -#19140 = VECTOR('',#19141,1.); -#19141 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19142 = PCURVE('',#18254,#19143); -#19143 = DEFINITIONAL_REPRESENTATION('',(#19144),#19148); -#19144 = LINE('',#19145,#19146); -#19145 = CARTESIAN_POINT('',(-3.268951266039,1.100988562261)); -#19146 = VECTOR('',#19147,1.); -#19147 = DIRECTION('',(1.,0.E+000)); -#19148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19149 = PCURVE('',#18226,#19150); -#19150 = DEFINITIONAL_REPRESENTATION('',(#19151),#19155); -#19151 = LINE('',#19152,#19153); -#19152 = CARTESIAN_POINT('',(-0.45,0.15)); -#19153 = VECTOR('',#19154,1.); -#19154 = DIRECTION('',(1.,0.E+000)); -#19155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19156 = ORIENTED_EDGE('',*,*,#19157,.T.); -#19157 = EDGE_CURVE('',#19135,#19158,#19160,.T.); -#19158 = VERTEX_POINT('',#19159); -#19159 = CARTESIAN_POINT('',(53.738908,22.345721,0.2)); -#19160 = SURFACE_CURVE('',#19161,(#19165,#19172),.PCURVE_S1.); -#19161 = LINE('',#19162,#19163); -#19162 = CARTESIAN_POINT('',(53.738908,22.345721,2.)); -#19163 = VECTOR('',#19164,1.); -#19164 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#19165 = PCURVE('',#18254,#19166); -#19166 = DEFINITIONAL_REPRESENTATION('',(#19167),#19171); -#19167 = LINE('',#19168,#19169); -#19168 = CARTESIAN_POINT('',(-2.818951266039,1.100988562261)); -#19169 = VECTOR('',#19170,1.); -#19170 = DIRECTION('',(0.E+000,-1.)); -#19171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19172 = PCURVE('',#19173,#19178); -#19173 = PLANE('',#19174); -#19174 = AXIS2_PLACEMENT_3D('',#19175,#19176,#19177); -#19175 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); -#19176 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19177 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#19178 = DEFINITIONAL_REPRESENTATION('',(#19179),#19183); -#19179 = LINE('',#19180,#19181); -#19180 = CARTESIAN_POINT('',(-1.8,0.15)); -#19181 = VECTOR('',#19182,1.); -#19182 = DIRECTION('',(1.,0.E+000)); -#19183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19184 = ORIENTED_EDGE('',*,*,#19185,.T.); -#19185 = EDGE_CURVE('',#19158,#18239,#19186,.T.); -#19186 = SURFACE_CURVE('',#19187,(#19191,#19198),.PCURVE_S1.); -#19187 = LINE('',#19188,#19189); -#19188 = CARTESIAN_POINT('',(53.738908,22.345721,0.2)); -#19189 = VECTOR('',#19190,1.); -#19190 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19191 = PCURVE('',#18254,#19192); -#19192 = DEFINITIONAL_REPRESENTATION('',(#19193),#19197); -#19193 = LINE('',#19194,#19195); -#19194 = CARTESIAN_POINT('',(-2.818951266039,-0.699011437739)); -#19195 = VECTOR('',#19196,1.); -#19196 = DIRECTION('',(-1.,0.E+000)); -#19197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19198 = PCURVE('',#18282,#19199); -#19199 = DEFINITIONAL_REPRESENTATION('',(#19200),#19204); -#19200 = LINE('',#19201,#19202); -#19201 = CARTESIAN_POINT('',(-0.45,0.15)); -#19202 = VECTOR('',#19203,1.); -#19203 = DIRECTION('',(1.,0.E+000)); -#19204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19205 = ADVANCED_FACE('',(#19206),#18282,.T.); -#19206 = FACE_BOUND('',#19207,.T.); -#19207 = EDGE_LOOP('',(#19208,#19209,#19210,#19233)); -#19208 = ORIENTED_EDGE('',*,*,#18266,.T.); -#19209 = ORIENTED_EDGE('',*,*,#19185,.F.); -#19210 = ORIENTED_EDGE('',*,*,#19211,.F.); -#19211 = EDGE_CURVE('',#19212,#19158,#19214,.T.); -#19212 = VERTEX_POINT('',#19213); -#19213 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); -#19214 = SURFACE_CURVE('',#19215,(#19219,#19226),.PCURVE_S1.); -#19215 = LINE('',#19216,#19217); -#19216 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); -#19217 = VECTOR('',#19218,1.); -#19218 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19219 = PCURVE('',#18282,#19220); -#19220 = DEFINITIONAL_REPRESENTATION('',(#19221),#19225); -#19221 = LINE('',#19222,#19223); -#19222 = CARTESIAN_POINT('',(-0.45,0.E+000)); -#19223 = VECTOR('',#19224,1.); -#19224 = DIRECTION('',(0.E+000,1.)); -#19225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19226 = PCURVE('',#19173,#19227); -#19227 = DEFINITIONAL_REPRESENTATION('',(#19228),#19232); -#19228 = LINE('',#19229,#19230); -#19229 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19230 = VECTOR('',#19231,1.); -#19231 = DIRECTION('',(0.E+000,1.)); -#19232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19233 = ORIENTED_EDGE('',*,*,#19234,.T.); -#19234 = EDGE_CURVE('',#19212,#18267,#19235,.T.); -#19235 = SURFACE_CURVE('',#19236,(#19240,#19247),.PCURVE_S1.); -#19236 = LINE('',#19237,#19238); -#19237 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); -#19238 = VECTOR('',#19239,1.); -#19239 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19240 = PCURVE('',#18282,#19241); -#19241 = DEFINITIONAL_REPRESENTATION('',(#19242),#19246); -#19242 = LINE('',#19243,#19244); -#19243 = CARTESIAN_POINT('',(-0.45,0.E+000)); -#19244 = VECTOR('',#19245,1.); -#19245 = DIRECTION('',(1.,0.E+000)); -#19246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19247 = PCURVE('',#17723,#19248); -#19248 = DEFINITIONAL_REPRESENTATION('',(#19249),#19253); -#19249 = LINE('',#19250,#19251); -#19250 = CARTESIAN_POINT('',(-2.818951266039,-0.699011437739)); -#19251 = VECTOR('',#19252,1.); -#19252 = DIRECTION('',(-1.,0.E+000)); -#19253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19254 = ADVANCED_FACE('',(#19255),#17858,.T.); -#19255 = FACE_BOUND('',#19256,.T.); -#19256 = EDGE_LOOP('',(#19257,#19258,#19283,#19284)); -#19257 = ORIENTED_EDGE('',*,*,#17842,.F.); -#19258 = ORIENTED_EDGE('',*,*,#19259,.T.); -#19259 = EDGE_CURVE('',#17820,#17956,#19260,.T.); -#19260 = SURFACE_CURVE('',#19261,(#19266,#19272),.PCURVE_S1.); -#19261 = CIRCLE('',#19262,0.3); -#19262 = AXIS2_PLACEMENT_3D('',#19263,#19264,#19265); -#19263 = CARTESIAN_POINT('',(56.238908,22.495721,2.1)); -#19264 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19265 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19266 = PCURVE('',#17858,#19267); -#19267 = DEFINITIONAL_REPRESENTATION('',(#19268),#19271); -#19268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19269,#19270),.UNSPECIFIED., +#21513 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); +#21514 = CARTESIAN_POINT('',(-5.618951266039,-0.279396195469)); +#21515 = CARTESIAN_POINT('',(-5.168951266039,-0.539203816604)); +#21516 = CARTESIAN_POINT('',(-4.718951266039,-0.799011437739)); +#21517 = CARTESIAN_POINT('',(-5.168951266039,-1.058819058875)); +#21518 = CARTESIAN_POINT('',(-5.618951266039,-1.31862668001)); +#21519 = CARTESIAN_POINT('',(-5.618951266039,-0.799011437739)); +#21520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21521 = ADVANCED_FACE('',(#21522),#20646,.F.); +#21522 = FACE_BOUND('',#21523,.T.); +#21523 = EDGE_LOOP('',(#21524,#21525,#21548,#21576)); +#21524 = ORIENTED_EDGE('',*,*,#20630,.F.); +#21525 = ORIENTED_EDGE('',*,*,#21526,.T.); +#21526 = EDGE_CURVE('',#20603,#21527,#21529,.T.); +#21527 = VERTEX_POINT('',#21528); +#21528 = CARTESIAN_POINT('',(53.738908,22.345721,2.)); +#21529 = SURFACE_CURVE('',#21530,(#21534,#21541),.PCURVE_S1.); +#21530 = LINE('',#21531,#21532); +#21531 = CARTESIAN_POINT('',(54.188908,22.345721,2.)); +#21532 = VECTOR('',#21533,1.); +#21533 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21534 = PCURVE('',#20646,#21535); +#21535 = DEFINITIONAL_REPRESENTATION('',(#21536),#21540); +#21536 = LINE('',#21537,#21538); +#21537 = CARTESIAN_POINT('',(-3.268951266039,1.100988562261)); +#21538 = VECTOR('',#21539,1.); +#21539 = DIRECTION('',(1.,0.E+000)); +#21540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21541 = PCURVE('',#20618,#21542); +#21542 = DEFINITIONAL_REPRESENTATION('',(#21543),#21547); +#21543 = LINE('',#21544,#21545); +#21544 = CARTESIAN_POINT('',(-0.45,0.15)); +#21545 = VECTOR('',#21546,1.); +#21546 = DIRECTION('',(1.,0.E+000)); +#21547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21548 = ORIENTED_EDGE('',*,*,#21549,.T.); +#21549 = EDGE_CURVE('',#21527,#21550,#21552,.T.); +#21550 = VERTEX_POINT('',#21551); +#21551 = CARTESIAN_POINT('',(53.738908,22.345721,0.2)); +#21552 = SURFACE_CURVE('',#21553,(#21557,#21564),.PCURVE_S1.); +#21553 = LINE('',#21554,#21555); +#21554 = CARTESIAN_POINT('',(53.738908,22.345721,2.)); +#21555 = VECTOR('',#21556,1.); +#21556 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21557 = PCURVE('',#20646,#21558); +#21558 = DEFINITIONAL_REPRESENTATION('',(#21559),#21563); +#21559 = LINE('',#21560,#21561); +#21560 = CARTESIAN_POINT('',(-2.818951266039,1.100988562261)); +#21561 = VECTOR('',#21562,1.); +#21562 = DIRECTION('',(0.E+000,-1.)); +#21563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21564 = PCURVE('',#21565,#21570); +#21565 = PLANE('',#21566); +#21566 = AXIS2_PLACEMENT_3D('',#21567,#21568,#21569); +#21567 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); +#21568 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21569 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#21570 = DEFINITIONAL_REPRESENTATION('',(#21571),#21575); +#21571 = LINE('',#21572,#21573); +#21572 = CARTESIAN_POINT('',(-1.8,0.15)); +#21573 = VECTOR('',#21574,1.); +#21574 = DIRECTION('',(1.,0.E+000)); +#21575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21576 = ORIENTED_EDGE('',*,*,#21577,.T.); +#21577 = EDGE_CURVE('',#21550,#20631,#21578,.T.); +#21578 = SURFACE_CURVE('',#21579,(#21583,#21590),.PCURVE_S1.); +#21579 = LINE('',#21580,#21581); +#21580 = CARTESIAN_POINT('',(53.738908,22.345721,0.2)); +#21581 = VECTOR('',#21582,1.); +#21582 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21583 = PCURVE('',#20646,#21584); +#21584 = DEFINITIONAL_REPRESENTATION('',(#21585),#21589); +#21585 = LINE('',#21586,#21587); +#21586 = CARTESIAN_POINT('',(-2.818951266039,-0.699011437739)); +#21587 = VECTOR('',#21588,1.); +#21588 = DIRECTION('',(-1.,0.E+000)); +#21589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21590 = PCURVE('',#20674,#21591); +#21591 = DEFINITIONAL_REPRESENTATION('',(#21592),#21596); +#21592 = LINE('',#21593,#21594); +#21593 = CARTESIAN_POINT('',(-0.45,0.15)); +#21594 = VECTOR('',#21595,1.); +#21595 = DIRECTION('',(1.,0.E+000)); +#21596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21597 = ADVANCED_FACE('',(#21598),#20674,.T.); +#21598 = FACE_BOUND('',#21599,.T.); +#21599 = EDGE_LOOP('',(#21600,#21601,#21602,#21625)); +#21600 = ORIENTED_EDGE('',*,*,#20658,.T.); +#21601 = ORIENTED_EDGE('',*,*,#21577,.F.); +#21602 = ORIENTED_EDGE('',*,*,#21603,.F.); +#21603 = EDGE_CURVE('',#21604,#21550,#21606,.T.); +#21604 = VERTEX_POINT('',#21605); +#21605 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); +#21606 = SURFACE_CURVE('',#21607,(#21611,#21618),.PCURVE_S1.); +#21607 = LINE('',#21608,#21609); +#21608 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); +#21609 = VECTOR('',#21610,1.); +#21610 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21611 = PCURVE('',#20674,#21612); +#21612 = DEFINITIONAL_REPRESENTATION('',(#21613),#21617); +#21613 = LINE('',#21614,#21615); +#21614 = CARTESIAN_POINT('',(-0.45,0.E+000)); +#21615 = VECTOR('',#21616,1.); +#21616 = DIRECTION('',(0.E+000,1.)); +#21617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21618 = PCURVE('',#21565,#21619); +#21619 = DEFINITIONAL_REPRESENTATION('',(#21620),#21624); +#21620 = LINE('',#21621,#21622); +#21621 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#21622 = VECTOR('',#21623,1.); +#21623 = DIRECTION('',(0.E+000,1.)); +#21624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21625 = ORIENTED_EDGE('',*,*,#21626,.T.); +#21626 = EDGE_CURVE('',#21604,#20659,#21627,.T.); +#21627 = SURFACE_CURVE('',#21628,(#21632,#21639),.PCURVE_S1.); +#21628 = LINE('',#21629,#21630); +#21629 = CARTESIAN_POINT('',(53.738908,22.495721,0.2)); +#21630 = VECTOR('',#21631,1.); +#21631 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21632 = PCURVE('',#20674,#21633); +#21633 = DEFINITIONAL_REPRESENTATION('',(#21634),#21638); +#21634 = LINE('',#21635,#21636); +#21635 = CARTESIAN_POINT('',(-0.45,0.E+000)); +#21636 = VECTOR('',#21637,1.); +#21637 = DIRECTION('',(1.,0.E+000)); +#21638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21639 = PCURVE('',#20115,#21640); +#21640 = DEFINITIONAL_REPRESENTATION('',(#21641),#21645); +#21641 = LINE('',#21642,#21643); +#21642 = CARTESIAN_POINT('',(-2.818951266039,-0.699011437739)); +#21643 = VECTOR('',#21644,1.); +#21644 = DIRECTION('',(-1.,0.E+000)); +#21645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21646 = ADVANCED_FACE('',(#21647),#20250,.T.); +#21647 = FACE_BOUND('',#21648,.T.); +#21648 = EDGE_LOOP('',(#21649,#21650,#21675,#21676)); +#21649 = ORIENTED_EDGE('',*,*,#20234,.F.); +#21650 = ORIENTED_EDGE('',*,*,#21651,.T.); +#21651 = EDGE_CURVE('',#20212,#20348,#21652,.T.); +#21652 = SURFACE_CURVE('',#21653,(#21658,#21664),.PCURVE_S1.); +#21653 = CIRCLE('',#21654,0.3); +#21654 = AXIS2_PLACEMENT_3D('',#21655,#21656,#21657); +#21655 = CARTESIAN_POINT('',(56.238908,22.495721,2.1)); +#21656 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21657 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21658 = PCURVE('',#20250,#21659); +#21659 = DEFINITIONAL_REPRESENTATION('',(#21660),#21663); +#21660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21661,#21662),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#19269 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19270 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#19271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21661 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#21662 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#21663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19272 = PCURVE('',#17723,#19273); -#19273 = DEFINITIONAL_REPRESENTATION('',(#19274),#19282); -#19274 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#19275,#19276,#19277,#19278 - ,#19279,#19280,#19281),.UNSPECIFIED.,.T.,.F.) +#21664 = PCURVE('',#20115,#21665); +#21665 = DEFINITIONAL_REPRESENTATION('',(#21666),#21674); +#21666 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21667,#21668,#21669,#21670 + ,#21671,#21672,#21673),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#19275 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); -#19276 = CARTESIAN_POINT('',(-5.618951266039,1.720603804531)); -#19277 = CARTESIAN_POINT('',(-5.168951266039,1.460796183396)); -#19278 = CARTESIAN_POINT('',(-4.718951266039,1.200988562261)); -#19279 = CARTESIAN_POINT('',(-5.168951266039,0.941180941125)); -#19280 = CARTESIAN_POINT('',(-5.618951266039,0.68137331999)); -#19281 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); -#19282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19283 = ORIENTED_EDGE('',*,*,#17955,.T.); -#19284 = ORIENTED_EDGE('',*,*,#18670,.F.); -#19285 = ADVANCED_FACE('',(#19286),#17921,.T.); -#19286 = FACE_BOUND('',#19287,.T.); -#19287 = EDGE_LOOP('',(#19288,#19289,#19314,#19315)); -#19288 = ORIENTED_EDGE('',*,*,#17898,.F.); -#19289 = ORIENTED_EDGE('',*,*,#19290,.T.); -#19290 = EDGE_CURVE('',#17899,#18166,#19291,.T.); -#19291 = SURFACE_CURVE('',#19292,(#19297,#19303),.PCURVE_S1.); -#19292 = CIRCLE('',#19293,0.3); -#19293 = AXIS2_PLACEMENT_3D('',#19294,#19295,#19296); -#19294 = CARTESIAN_POINT('',(54.238908,22.495721,2.1)); -#19295 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19296 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19297 = PCURVE('',#17921,#19298); -#19298 = DEFINITIONAL_REPRESENTATION('',(#19299),#19302); -#19299 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19300,#19301),.UNSPECIFIED., +#21667 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); +#21668 = CARTESIAN_POINT('',(-5.618951266039,1.720603804531)); +#21669 = CARTESIAN_POINT('',(-5.168951266039,1.460796183396)); +#21670 = CARTESIAN_POINT('',(-4.718951266039,1.200988562261)); +#21671 = CARTESIAN_POINT('',(-5.168951266039,0.941180941125)); +#21672 = CARTESIAN_POINT('',(-5.618951266039,0.68137331999)); +#21673 = CARTESIAN_POINT('',(-5.618951266039,1.200988562261)); +#21674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21675 = ORIENTED_EDGE('',*,*,#20347,.T.); +#21676 = ORIENTED_EDGE('',*,*,#21062,.F.); +#21677 = ADVANCED_FACE('',(#21678),#20313,.T.); +#21678 = FACE_BOUND('',#21679,.T.); +#21679 = EDGE_LOOP('',(#21680,#21681,#21706,#21707)); +#21680 = ORIENTED_EDGE('',*,*,#20290,.F.); +#21681 = ORIENTED_EDGE('',*,*,#21682,.T.); +#21682 = EDGE_CURVE('',#20291,#20558,#21683,.T.); +#21683 = SURFACE_CURVE('',#21684,(#21689,#21695),.PCURVE_S1.); +#21684 = CIRCLE('',#21685,0.3); +#21685 = AXIS2_PLACEMENT_3D('',#21686,#21687,#21688); +#21686 = CARTESIAN_POINT('',(54.238908,22.495721,2.1)); +#21687 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21688 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21689 = PCURVE('',#20313,#21690); +#21690 = DEFINITIONAL_REPRESENTATION('',(#21691),#21694); +#21691 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21692,#21693),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#19300 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#19301 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#19302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21692 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#21693 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#21694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19303 = PCURVE('',#17723,#19304); -#19304 = DEFINITIONAL_REPRESENTATION('',(#19305),#19313); -#19305 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#19306,#19307,#19308,#19309 - ,#19310,#19311,#19312),.UNSPECIFIED.,.T.,.F.) +#21695 = PCURVE('',#20115,#21696); +#21696 = DEFINITIONAL_REPRESENTATION('',(#21697),#21705); +#21697 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21698,#21699,#21700,#21701 + ,#21702,#21703,#21704),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#19306 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); -#19307 = CARTESIAN_POINT('',(-3.618951266039,1.720603804531)); -#19308 = CARTESIAN_POINT('',(-3.168951266039,1.460796183396)); -#19309 = CARTESIAN_POINT('',(-2.718951266039,1.200988562261)); -#19310 = CARTESIAN_POINT('',(-3.168951266039,0.941180941125)); -#19311 = CARTESIAN_POINT('',(-3.618951266039,0.68137331999)); -#19312 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); -#19313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19314 = ORIENTED_EDGE('',*,*,#18165,.T.); -#19315 = ORIENTED_EDGE('',*,*,#18696,.F.); -#19316 = ADVANCED_FACE('',(#19317),#18131,.T.); -#19317 = FACE_BOUND('',#19318,.T.); -#19318 = EDGE_LOOP('',(#19319,#19320,#19345,#19346)); -#19319 = ORIENTED_EDGE('',*,*,#18108,.F.); -#19320 = ORIENTED_EDGE('',*,*,#19321,.T.); -#19321 = EDGE_CURVE('',#18109,#18319,#19322,.T.); -#19322 = SURFACE_CURVE('',#19323,(#19328,#19334),.PCURVE_S1.); -#19323 = CIRCLE('',#19324,0.3); -#19324 = AXIS2_PLACEMENT_3D('',#19325,#19326,#19327); -#19325 = CARTESIAN_POINT('',(54.238908,22.495721,1.E-001)); -#19326 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19327 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19328 = PCURVE('',#18131,#19329); -#19329 = DEFINITIONAL_REPRESENTATION('',(#19330),#19333); -#19330 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19331,#19332),.UNSPECIFIED., +#21698 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); +#21699 = CARTESIAN_POINT('',(-3.618951266039,1.720603804531)); +#21700 = CARTESIAN_POINT('',(-3.168951266039,1.460796183396)); +#21701 = CARTESIAN_POINT('',(-2.718951266039,1.200988562261)); +#21702 = CARTESIAN_POINT('',(-3.168951266039,0.941180941125)); +#21703 = CARTESIAN_POINT('',(-3.618951266039,0.68137331999)); +#21704 = CARTESIAN_POINT('',(-3.618951266039,1.200988562261)); +#21705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21706 = ORIENTED_EDGE('',*,*,#20557,.T.); +#21707 = ORIENTED_EDGE('',*,*,#21088,.F.); +#21708 = ADVANCED_FACE('',(#21709),#20523,.T.); +#21709 = FACE_BOUND('',#21710,.T.); +#21710 = EDGE_LOOP('',(#21711,#21712,#21737,#21738)); +#21711 = ORIENTED_EDGE('',*,*,#20500,.F.); +#21712 = ORIENTED_EDGE('',*,*,#21713,.T.); +#21713 = EDGE_CURVE('',#20501,#20711,#21714,.T.); +#21714 = SURFACE_CURVE('',#21715,(#21720,#21726),.PCURVE_S1.); +#21715 = CIRCLE('',#21716,0.3); +#21716 = AXIS2_PLACEMENT_3D('',#21717,#21718,#21719); +#21717 = CARTESIAN_POINT('',(54.238908,22.495721,1.E-001)); +#21718 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#21719 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21720 = PCURVE('',#20523,#21721); +#21721 = DEFINITIONAL_REPRESENTATION('',(#21722),#21725); +#21722 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21723,#21724),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#19331 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#19332 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#19333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21723 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#21724 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#21725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19334 = PCURVE('',#17723,#19335); -#19335 = DEFINITIONAL_REPRESENTATION('',(#19336),#19344); -#19336 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#19337,#19338,#19339,#19340 - ,#19341,#19342,#19343),.UNSPECIFIED.,.T.,.F.) +#21726 = PCURVE('',#20115,#21727); +#21727 = DEFINITIONAL_REPRESENTATION('',(#21728),#21736); +#21728 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#21729,#21730,#21731,#21732 + ,#21733,#21734,#21735),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#19337 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); -#19338 = CARTESIAN_POINT('',(-3.618951266039,-0.279396195469)); -#19339 = CARTESIAN_POINT('',(-3.168951266039,-0.539203816604)); -#19340 = CARTESIAN_POINT('',(-2.718951266039,-0.799011437739)); -#19341 = CARTESIAN_POINT('',(-3.168951266039,-1.058819058875)); -#19342 = CARTESIAN_POINT('',(-3.618951266039,-1.31862668001)); -#19343 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); -#19344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19345 = ORIENTED_EDGE('',*,*,#18500,.T.); -#19346 = ORIENTED_EDGE('',*,*,#18722,.F.); -#19347 = ADVANCED_FACE('',(#19348),#17779,.F.); -#19348 = FACE_BOUND('',#19349,.T.); -#19349 = EDGE_LOOP('',(#19350,#19351,#19372,#19373)); -#19350 = ORIENTED_EDGE('',*,*,#17763,.F.); -#19351 = ORIENTED_EDGE('',*,*,#19352,.F.); -#19352 = EDGE_CURVE('',#19009,#17736,#19353,.T.); -#19353 = SURFACE_CURVE('',#19354,(#19358,#19365),.PCURVE_S1.); -#19354 = LINE('',#19355,#19356); -#19355 = CARTESIAN_POINT('',(56.738908,22.345721,0.2)); -#19356 = VECTOR('',#19357,1.); -#19357 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19358 = PCURVE('',#17779,#19359); -#19359 = DEFINITIONAL_REPRESENTATION('',(#19360),#19364); -#19360 = LINE('',#19361,#19362); -#19361 = CARTESIAN_POINT('',(-5.818951266039,-0.699011437739)); -#19362 = VECTOR('',#19363,1.); -#19363 = DIRECTION('',(1.,0.E+000)); -#19364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19365 = PCURVE('',#17751,#19366); -#19366 = DEFINITIONAL_REPRESENTATION('',(#19367),#19371); -#19367 = LINE('',#19368,#19369); -#19368 = CARTESIAN_POINT('',(0.E+000,0.15)); -#19369 = VECTOR('',#19370,1.); -#19370 = DIRECTION('',(-1.,0.E+000)); -#19371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19372 = ORIENTED_EDGE('',*,*,#19008,.F.); -#19373 = ORIENTED_EDGE('',*,*,#19056,.T.); -#19374 = ADVANCED_FACE('',(#19375),#19390,.F.); -#19375 = FACE_BOUND('',#19376,.T.); -#19376 = EDGE_LOOP('',(#19377,#19412,#19440,#19468)); -#19377 = ORIENTED_EDGE('',*,*,#19378,.F.); -#19378 = EDGE_CURVE('',#19379,#19381,#19383,.T.); -#19379 = VERTEX_POINT('',#19380); -#19380 = CARTESIAN_POINT('',(56.013504669241,22.145721,0.75)); -#19381 = VERTEX_POINT('',#19382); -#19382 = CARTESIAN_POINT('',(54.464311330758,22.145721,0.75)); -#19383 = SURFACE_CURVE('',#19384,(#19389,#19401),.PCURVE_S1.); -#19384 = CIRCLE('',#19385,0.85); -#19385 = AXIS2_PLACEMENT_3D('',#19386,#19387,#19388); -#19386 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#19387 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19388 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19389 = PCURVE('',#19390,#19395); -#19390 = PLANE('',#19391); -#19391 = AXIS2_PLACEMENT_3D('',#19392,#19393,#19394); -#19392 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); -#19393 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19394 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19395 = DEFINITIONAL_REPRESENTATION('',(#19396),#19400); -#19396 = CIRCLE('',#19397,0.85); -#19397 = AXIS2_PLACEMENT_2D('',#19398,#19399); -#19398 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#19399 = DIRECTION('',(1.,0.E+000)); -#19400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19401 = PCURVE('',#19402,#19407); -#19402 = CYLINDRICAL_SURFACE('',#19403,0.85); -#19403 = AXIS2_PLACEMENT_3D('',#19404,#19405,#19406); -#19404 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#19405 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19406 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19407 = DEFINITIONAL_REPRESENTATION('',(#19408),#19411); -#19408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19409,#19410),.UNSPECIFIED., +#21729 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); +#21730 = CARTESIAN_POINT('',(-3.618951266039,-0.279396195469)); +#21731 = CARTESIAN_POINT('',(-3.168951266039,-0.539203816604)); +#21732 = CARTESIAN_POINT('',(-2.718951266039,-0.799011437739)); +#21733 = CARTESIAN_POINT('',(-3.168951266039,-1.058819058875)); +#21734 = CARTESIAN_POINT('',(-3.618951266039,-1.31862668001)); +#21735 = CARTESIAN_POINT('',(-3.618951266039,-0.799011437739)); +#21736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21737 = ORIENTED_EDGE('',*,*,#20892,.T.); +#21738 = ORIENTED_EDGE('',*,*,#21114,.F.); +#21739 = ADVANCED_FACE('',(#21740),#20171,.F.); +#21740 = FACE_BOUND('',#21741,.T.); +#21741 = EDGE_LOOP('',(#21742,#21743,#21764,#21765)); +#21742 = ORIENTED_EDGE('',*,*,#20155,.F.); +#21743 = ORIENTED_EDGE('',*,*,#21744,.F.); +#21744 = EDGE_CURVE('',#21401,#20128,#21745,.T.); +#21745 = SURFACE_CURVE('',#21746,(#21750,#21757),.PCURVE_S1.); +#21746 = LINE('',#21747,#21748); +#21747 = CARTESIAN_POINT('',(56.738908,22.345721,0.2)); +#21748 = VECTOR('',#21749,1.); +#21749 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21750 = PCURVE('',#20171,#21751); +#21751 = DEFINITIONAL_REPRESENTATION('',(#21752),#21756); +#21752 = LINE('',#21753,#21754); +#21753 = CARTESIAN_POINT('',(-5.818951266039,-0.699011437739)); +#21754 = VECTOR('',#21755,1.); +#21755 = DIRECTION('',(1.,0.E+000)); +#21756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21757 = PCURVE('',#20143,#21758); +#21758 = DEFINITIONAL_REPRESENTATION('',(#21759),#21763); +#21759 = LINE('',#21760,#21761); +#21760 = CARTESIAN_POINT('',(0.E+000,0.15)); +#21761 = VECTOR('',#21762,1.); +#21762 = DIRECTION('',(-1.,0.E+000)); +#21763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21764 = ORIENTED_EDGE('',*,*,#21400,.F.); +#21765 = ORIENTED_EDGE('',*,*,#21448,.T.); +#21766 = ADVANCED_FACE('',(#21767),#21782,.F.); +#21767 = FACE_BOUND('',#21768,.T.); +#21768 = EDGE_LOOP('',(#21769,#21804,#21832,#21860)); +#21769 = ORIENTED_EDGE('',*,*,#21770,.F.); +#21770 = EDGE_CURVE('',#21771,#21773,#21775,.T.); +#21771 = VERTEX_POINT('',#21772); +#21772 = CARTESIAN_POINT('',(56.013504669241,22.145721,0.75)); +#21773 = VERTEX_POINT('',#21774); +#21774 = CARTESIAN_POINT('',(54.464311330758,22.145721,0.75)); +#21775 = SURFACE_CURVE('',#21776,(#21781,#21793),.PCURVE_S1.); +#21776 = CIRCLE('',#21777,0.85); +#21777 = AXIS2_PLACEMENT_3D('',#21778,#21779,#21780); +#21778 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21779 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21780 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21781 = PCURVE('',#21782,#21787); +#21782 = PLANE('',#21783); +#21783 = AXIS2_PLACEMENT_3D('',#21784,#21785,#21786); +#21784 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.899011437739)); +#21785 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21786 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21787 = DEFINITIONAL_REPRESENTATION('',(#21788),#21792); +#21788 = CIRCLE('',#21789,0.85); +#21789 = AXIS2_PLACEMENT_2D('',#21790,#21791); +#21790 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21791 = DIRECTION('',(1.,0.E+000)); +#21792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21793 = PCURVE('',#21794,#21799); +#21794 = CYLINDRICAL_SURFACE('',#21795,0.85); +#21795 = AXIS2_PLACEMENT_3D('',#21796,#21797,#21798); +#21796 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#21797 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21798 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21799 = DEFINITIONAL_REPRESENTATION('',(#21800),#21803); +#21800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21801,#21802),.UNSPECIFIED., .F.,.F.,(2,2),(3.565982362183,5.858795598586), .PIECEWISE_BEZIER_KNOTS.); -#19409 = CARTESIAN_POINT('',(3.565982362183,-0.35)); -#19410 = CARTESIAN_POINT('',(5.858795598586,-0.35)); -#19411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19412 = ORIENTED_EDGE('',*,*,#19413,.T.); -#19413 = EDGE_CURVE('',#19379,#19414,#19416,.T.); -#19414 = VERTEX_POINT('',#19415); -#19415 = CARTESIAN_POINT('',(55.663172068712,22.145721,0.75)); -#19416 = SURFACE_CURVE('',#19417,(#19421,#19428),.PCURVE_S1.); -#19417 = LINE('',#19418,#19419); -#19418 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.75)); -#19419 = VECTOR('',#19420,1.); -#19420 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); -#19421 = PCURVE('',#19390,#19422); -#19422 = DEFINITIONAL_REPRESENTATION('',(#19423),#19427); -#19423 = LINE('',#19424,#19425); -#19424 = CARTESIAN_POINT('',(0.E+000,-0.149011437739)); -#19425 = VECTOR('',#19426,1.); -#19426 = DIRECTION('',(1.,-2.22044604925E-016)); -#19427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19428 = PCURVE('',#19429,#19434); -#19429 = PLANE('',#19430); -#19430 = AXIS2_PLACEMENT_3D('',#19431,#19432,#19433); -#19431 = CARTESIAN_POINT('',(56.013504669241,22.145721,0.75)); -#19432 = DIRECTION('',(2.22044604925E-016,0.E+000,-1.)); -#19433 = DIRECTION('',(1.,0.E+000,2.22044604925E-016)); -#19434 = DEFINITIONAL_REPRESENTATION('',(#19435),#19439); -#19435 = LINE('',#19436,#19437); -#19436 = CARTESIAN_POINT('',(-5.09354793528,0.E+000)); -#19437 = VECTOR('',#19438,1.); -#19438 = DIRECTION('',(-1.,0.E+000)); -#19439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19440 = ORIENTED_EDGE('',*,*,#19441,.T.); -#19441 = EDGE_CURVE('',#19414,#19442,#19444,.T.); -#19442 = VERTEX_POINT('',#19443); -#19443 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); -#19444 = SURFACE_CURVE('',#19445,(#19450,#19457),.PCURVE_S1.); -#19445 = CIRCLE('',#19446,0.55); -#19446 = AXIS2_PLACEMENT_3D('',#19447,#19448,#19449); -#19447 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#19448 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19449 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19450 = PCURVE('',#19390,#19451); -#19451 = DEFINITIONAL_REPRESENTATION('',(#19452),#19456); -#19452 = CIRCLE('',#19453,0.55); -#19453 = AXIS2_PLACEMENT_2D('',#19454,#19455); -#19454 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#19455 = DIRECTION('',(1.,0.E+000)); -#19456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19457 = PCURVE('',#19458,#19463); -#19458 = CYLINDRICAL_SURFACE('',#19459,0.55); -#19459 = AXIS2_PLACEMENT_3D('',#19460,#19461,#19462); -#19460 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#19461 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19462 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19463 = DEFINITIONAL_REPRESENTATION('',(#19464),#19467); -#19464 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19465,#19466),.UNSPECIFIED., +#21801 = CARTESIAN_POINT('',(3.565982362183,-0.35)); +#21802 = CARTESIAN_POINT('',(5.858795598586,-0.35)); +#21803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21804 = ORIENTED_EDGE('',*,*,#21805,.T.); +#21805 = EDGE_CURVE('',#21771,#21806,#21808,.T.); +#21806 = VERTEX_POINT('',#21807); +#21807 = CARTESIAN_POINT('',(55.663172068712,22.145721,0.75)); +#21808 = SURFACE_CURVE('',#21809,(#21813,#21820),.PCURVE_S1.); +#21809 = LINE('',#21810,#21811); +#21810 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.75)); +#21811 = VECTOR('',#21812,1.); +#21812 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); +#21813 = PCURVE('',#21782,#21814); +#21814 = DEFINITIONAL_REPRESENTATION('',(#21815),#21819); +#21815 = LINE('',#21816,#21817); +#21816 = CARTESIAN_POINT('',(0.E+000,-0.149011437739)); +#21817 = VECTOR('',#21818,1.); +#21818 = DIRECTION('',(1.,-2.22044604925E-016)); +#21819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21820 = PCURVE('',#21821,#21826); +#21821 = PLANE('',#21822); +#21822 = AXIS2_PLACEMENT_3D('',#21823,#21824,#21825); +#21823 = CARTESIAN_POINT('',(56.013504669241,22.145721,0.75)); +#21824 = DIRECTION('',(2.22044604925E-016,0.E+000,-1.)); +#21825 = DIRECTION('',(1.,0.E+000,2.22044604925E-016)); +#21826 = DEFINITIONAL_REPRESENTATION('',(#21827),#21831); +#21827 = LINE('',#21828,#21829); +#21828 = CARTESIAN_POINT('',(-5.09354793528,0.E+000)); +#21829 = VECTOR('',#21830,1.); +#21830 = DIRECTION('',(-1.,0.E+000)); +#21831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21832 = ORIENTED_EDGE('',*,*,#21833,.T.); +#21833 = EDGE_CURVE('',#21806,#21834,#21836,.T.); +#21834 = VERTEX_POINT('',#21835); +#21835 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); +#21836 = SURFACE_CURVE('',#21837,(#21842,#21849),.PCURVE_S1.); +#21837 = CIRCLE('',#21838,0.55); +#21838 = AXIS2_PLACEMENT_3D('',#21839,#21840,#21841); +#21839 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21840 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21841 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21842 = PCURVE('',#21782,#21843); +#21843 = DEFINITIONAL_REPRESENTATION('',(#21844),#21848); +#21844 = CIRCLE('',#21845,0.55); +#21845 = AXIS2_PLACEMENT_2D('',#21846,#21847); +#21846 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21847 = DIRECTION('',(1.,0.E+000)); +#21848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21849 = PCURVE('',#21850,#21855); +#21850 = CYLINDRICAL_SURFACE('',#21851,0.55); +#21851 = AXIS2_PLACEMENT_3D('',#21852,#21853,#21854); +#21852 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21853 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21854 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21855 = DEFINITIONAL_REPRESENTATION('',(#21856),#21859); +#21856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21857,#21858),.UNSPECIFIED., .F.,.F.,(2,2),(3.831367654375,5.593410306394), .PIECEWISE_BEZIER_KNOTS.); -#19465 = CARTESIAN_POINT('',(3.831367654375,0.E+000)); -#19466 = CARTESIAN_POINT('',(5.593410306394,0.E+000)); -#19467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19468 = ORIENTED_EDGE('',*,*,#19469,.T.); -#19469 = EDGE_CURVE('',#19442,#19381,#19470,.T.); -#19470 = SURFACE_CURVE('',#19471,(#19475,#19482),.PCURVE_S1.); -#19471 = LINE('',#19472,#19473); -#19472 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.75)); -#19473 = VECTOR('',#19474,1.); -#19474 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); -#19475 = PCURVE('',#19390,#19476); -#19476 = DEFINITIONAL_REPRESENTATION('',(#19477),#19481); -#19477 = LINE('',#19478,#19479); -#19478 = CARTESIAN_POINT('',(0.E+000,-0.149011437739)); -#19479 = VECTOR('',#19480,1.); -#19480 = DIRECTION('',(1.,-2.22044604925E-016)); -#19481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19482 = PCURVE('',#19483,#19488); -#19483 = PLANE('',#19484); -#19484 = AXIS2_PLACEMENT_3D('',#19485,#19486,#19487); -#19485 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); -#19486 = DIRECTION('',(2.22044604925E-016,0.E+000,-1.)); -#19487 = DIRECTION('',(1.,0.E+000,2.22044604925E-016)); -#19488 = DEFINITIONAL_REPRESENTATION('',(#19489),#19493); -#19489 = LINE('',#19490,#19491); -#19490 = CARTESIAN_POINT('',(-3.894687197327,0.E+000)); -#19491 = VECTOR('',#19492,1.); -#19492 = DIRECTION('',(-1.,0.E+000)); -#19493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19494 = ADVANCED_FACE('',(#19495),#18793,.T.); -#19495 = FACE_BOUND('',#19496,.T.); -#19496 = EDGE_LOOP('',(#19497,#19549,#19568,#19569,#19590,#19591)); -#19497 = ORIENTED_EDGE('',*,*,#19498,.T.); -#19498 = EDGE_CURVE('',#19499,#19501,#19503,.T.); -#19499 = VERTEX_POINT('',#19500); -#19500 = CARTESIAN_POINT('',(56.238908,22.015721,1.1)); -#19501 = VERTEX_POINT('',#19502); -#19502 = CARTESIAN_POINT('',(54.238908,22.015721,1.1)); -#19503 = SURFACE_CURVE('',#19504,(#19509,#19515),.PCURVE_S1.); -#19504 = CIRCLE('',#19505,1.); -#19505 = AXIS2_PLACEMENT_3D('',#19506,#19507,#19508); -#19506 = CARTESIAN_POINT('',(55.238908,22.015721,1.1)); -#19507 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19508 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19509 = PCURVE('',#18793,#19510); -#19510 = DEFINITIONAL_REPRESENTATION('',(#19511),#19514); -#19511 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19512,#19513),.UNSPECIFIED., +#21857 = CARTESIAN_POINT('',(3.831367654375,0.E+000)); +#21858 = CARTESIAN_POINT('',(5.593410306394,0.E+000)); +#21859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21860 = ORIENTED_EDGE('',*,*,#21861,.T.); +#21861 = EDGE_CURVE('',#21834,#21773,#21862,.T.); +#21862 = SURFACE_CURVE('',#21863,(#21867,#21874),.PCURVE_S1.); +#21863 = LINE('',#21864,#21865); +#21864 = CARTESIAN_POINT('',(50.919956733961,22.145721,0.75)); +#21865 = VECTOR('',#21866,1.); +#21866 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); +#21867 = PCURVE('',#21782,#21868); +#21868 = DEFINITIONAL_REPRESENTATION('',(#21869),#21873); +#21869 = LINE('',#21870,#21871); +#21870 = CARTESIAN_POINT('',(0.E+000,-0.149011437739)); +#21871 = VECTOR('',#21872,1.); +#21872 = DIRECTION('',(1.,-2.22044604925E-016)); +#21873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21874 = PCURVE('',#21875,#21880); +#21875 = PLANE('',#21876); +#21876 = AXIS2_PLACEMENT_3D('',#21877,#21878,#21879); +#21877 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); +#21878 = DIRECTION('',(2.22044604925E-016,0.E+000,-1.)); +#21879 = DIRECTION('',(1.,0.E+000,2.22044604925E-016)); +#21880 = DEFINITIONAL_REPRESENTATION('',(#21881),#21885); +#21881 = LINE('',#21882,#21883); +#21882 = CARTESIAN_POINT('',(-3.894687197327,0.E+000)); +#21883 = VECTOR('',#21884,1.); +#21884 = DIRECTION('',(-1.,0.E+000)); +#21885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21886 = ADVANCED_FACE('',(#21887),#21185,.T.); +#21887 = FACE_BOUND('',#21888,.T.); +#21888 = EDGE_LOOP('',(#21889,#21941,#21960,#21961,#21982,#21983)); +#21889 = ORIENTED_EDGE('',*,*,#21890,.T.); +#21890 = EDGE_CURVE('',#21891,#21893,#21895,.T.); +#21891 = VERTEX_POINT('',#21892); +#21892 = CARTESIAN_POINT('',(56.238908,22.015721,1.1)); +#21893 = VERTEX_POINT('',#21894); +#21894 = CARTESIAN_POINT('',(54.238908,22.015721,1.1)); +#21895 = SURFACE_CURVE('',#21896,(#21901,#21907),.PCURVE_S1.); +#21896 = CIRCLE('',#21897,1.); +#21897 = AXIS2_PLACEMENT_3D('',#21898,#21899,#21900); +#21898 = CARTESIAN_POINT('',(55.238908,22.015721,1.1)); +#21899 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21900 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21901 = PCURVE('',#21185,#21902); +#21902 = DEFINITIONAL_REPRESENTATION('',(#21903),#21906); +#21903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21904,#21905),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#19512 = CARTESIAN_POINT('',(3.14159265359,-0.48)); -#19513 = CARTESIAN_POINT('',(6.28318530718,-0.48)); -#19514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19515 = PCURVE('',#19516,#19521); -#19516 = CONICAL_SURFACE('',#19517,0.93,0.785398163397); -#19517 = AXIS2_PLACEMENT_3D('',#19518,#19519,#19520); -#19518 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); -#19519 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19520 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19521 = DEFINITIONAL_REPRESENTATION('',(#19522),#19548); -#19522 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19523,#19524,#19525,#19526, - #19527,#19528,#19529,#19530,#19531,#19532,#19533,#19534,#19535, - #19536,#19537,#19538,#19539,#19540,#19541,#19542,#19543,#19544, - #19545,#19546,#19547),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#21904 = CARTESIAN_POINT('',(3.14159265359,-0.48)); +#21905 = CARTESIAN_POINT('',(6.28318530718,-0.48)); +#21906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21907 = PCURVE('',#21908,#21913); +#21908 = CONICAL_SURFACE('',#21909,0.93,0.785398163397); +#21909 = AXIS2_PLACEMENT_3D('',#21910,#21911,#21912); +#21910 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); +#21911 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21912 = DIRECTION('',(1.,0.E+000,0.E+000)); +#21913 = DEFINITIONAL_REPRESENTATION('',(#21914),#21940); +#21914 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21915,#21916,#21917,#21918, + #21919,#21920,#21921,#21922,#21923,#21924,#21925,#21926,#21927, + #21928,#21929,#21930,#21931,#21932,#21933,#21934,#21935,#21936, + #21937,#21938,#21939),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -23925,164 +26914,164 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#19523 = CARTESIAN_POINT('',(0.E+000,7.E-002)); -#19524 = CARTESIAN_POINT('',(4.759988869075E-002,7.E-002)); -#19525 = CARTESIAN_POINT('',(0.142799666072,7.E-002)); -#19526 = CARTESIAN_POINT('',(0.285599332145,7.E-002)); -#19527 = CARTESIAN_POINT('',(0.428398998217,7.E-002)); -#19528 = CARTESIAN_POINT('',(0.571198664289,7.E-002)); -#19529 = CARTESIAN_POINT('',(0.713998330361,7.E-002)); -#19530 = CARTESIAN_POINT('',(0.856797996434,7.E-002)); -#19531 = CARTESIAN_POINT('',(0.999597662506,7.E-002)); -#19532 = CARTESIAN_POINT('',(1.142397328578,7.E-002)); -#19533 = CARTESIAN_POINT('',(1.28519699465,7.E-002)); -#19534 = CARTESIAN_POINT('',(1.427996660723,7.E-002)); -#19535 = CARTESIAN_POINT('',(1.570796326795,7.E-002)); -#19536 = CARTESIAN_POINT('',(1.713595992867,7.E-002)); -#19537 = CARTESIAN_POINT('',(1.856395658939,7.E-002)); -#19538 = CARTESIAN_POINT('',(1.999195325012,7.E-002)); -#19539 = CARTESIAN_POINT('',(2.141994991084,7.E-002)); -#19540 = CARTESIAN_POINT('',(2.284794657156,7.E-002)); -#19541 = CARTESIAN_POINT('',(2.427594323228,7.E-002)); -#19542 = CARTESIAN_POINT('',(2.570393989301,7.E-002)); -#19543 = CARTESIAN_POINT('',(2.713193655373,7.E-002)); -#19544 = CARTESIAN_POINT('',(2.855993321445,7.E-002)); -#19545 = CARTESIAN_POINT('',(2.998792987518,7.E-002)); -#19546 = CARTESIAN_POINT('',(3.093992764899,7.E-002)); -#19547 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#19548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19549 = ORIENTED_EDGE('',*,*,#19550,.T.); -#19550 = EDGE_CURVE('',#19501,#18777,#19551,.T.); -#19551 = SURFACE_CURVE('',#19552,(#19556,#19562),.PCURVE_S1.); -#19552 = LINE('',#19553,#19554); -#19553 = CARTESIAN_POINT('',(54.238908,22.495721,1.1)); -#19554 = VECTOR('',#19555,1.); -#19555 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19556 = PCURVE('',#18793,#19557); -#19557 = DEFINITIONAL_REPRESENTATION('',(#19558),#19561); -#19558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19559,#19560),.UNSPECIFIED., +#21915 = CARTESIAN_POINT('',(0.E+000,7.E-002)); +#21916 = CARTESIAN_POINT('',(4.759988869075E-002,7.E-002)); +#21917 = CARTESIAN_POINT('',(0.142799666072,7.E-002)); +#21918 = CARTESIAN_POINT('',(0.285599332145,7.E-002)); +#21919 = CARTESIAN_POINT('',(0.428398998217,7.E-002)); +#21920 = CARTESIAN_POINT('',(0.571198664289,7.E-002)); +#21921 = CARTESIAN_POINT('',(0.713998330361,7.E-002)); +#21922 = CARTESIAN_POINT('',(0.856797996434,7.E-002)); +#21923 = CARTESIAN_POINT('',(0.999597662506,7.E-002)); +#21924 = CARTESIAN_POINT('',(1.142397328578,7.E-002)); +#21925 = CARTESIAN_POINT('',(1.28519699465,7.E-002)); +#21926 = CARTESIAN_POINT('',(1.427996660723,7.E-002)); +#21927 = CARTESIAN_POINT('',(1.570796326795,7.E-002)); +#21928 = CARTESIAN_POINT('',(1.713595992867,7.E-002)); +#21929 = CARTESIAN_POINT('',(1.856395658939,7.E-002)); +#21930 = CARTESIAN_POINT('',(1.999195325012,7.E-002)); +#21931 = CARTESIAN_POINT('',(2.141994991084,7.E-002)); +#21932 = CARTESIAN_POINT('',(2.284794657156,7.E-002)); +#21933 = CARTESIAN_POINT('',(2.427594323228,7.E-002)); +#21934 = CARTESIAN_POINT('',(2.570393989301,7.E-002)); +#21935 = CARTESIAN_POINT('',(2.713193655373,7.E-002)); +#21936 = CARTESIAN_POINT('',(2.855993321445,7.E-002)); +#21937 = CARTESIAN_POINT('',(2.998792987518,7.E-002)); +#21938 = CARTESIAN_POINT('',(3.093992764899,7.E-002)); +#21939 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#21940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21941 = ORIENTED_EDGE('',*,*,#21942,.T.); +#21942 = EDGE_CURVE('',#21893,#21169,#21943,.T.); +#21943 = SURFACE_CURVE('',#21944,(#21948,#21954),.PCURVE_S1.); +#21944 = LINE('',#21945,#21946); +#21945 = CARTESIAN_POINT('',(54.238908,22.495721,1.1)); +#21946 = VECTOR('',#21947,1.); +#21947 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21948 = PCURVE('',#21185,#21949); +#21949 = DEFINITIONAL_REPRESENTATION('',(#21950),#21953); +#21950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21951,#21952),.UNSPECIFIED., .F.,.F.,(2,2),(-0.48,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#19559 = CARTESIAN_POINT('',(6.28318530718,-0.48)); -#19560 = CARTESIAN_POINT('',(6.28318530718,-0.35)); -#19561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21951 = CARTESIAN_POINT('',(6.28318530718,-0.48)); +#21952 = CARTESIAN_POINT('',(6.28318530718,-0.35)); +#21953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19562 = PCURVE('',#18821,#19563); -#19563 = DEFINITIONAL_REPRESENTATION('',(#19564),#19567); -#19564 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19565,#19566),.UNSPECIFIED., +#21954 = PCURVE('',#21213,#21955); +#21955 = DEFINITIONAL_REPRESENTATION('',(#21956),#21959); +#21956 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21957,#21958),.UNSPECIFIED., .F.,.F.,(2,2),(-0.48,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#19565 = CARTESIAN_POINT('',(0.E+000,-0.48)); -#19566 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#19567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19568 = ORIENTED_EDGE('',*,*,#18776,.F.); -#19569 = ORIENTED_EDGE('',*,*,#19570,.F.); -#19570 = EDGE_CURVE('',#18833,#18749,#19571,.T.); -#19571 = SURFACE_CURVE('',#19572,(#19577,#19583),.PCURVE_S1.); -#19572 = CIRCLE('',#19573,1.); -#19573 = AXIS2_PLACEMENT_3D('',#19574,#19575,#19576); -#19574 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); -#19575 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19576 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19577 = PCURVE('',#18793,#19578); -#19578 = DEFINITIONAL_REPRESENTATION('',(#19579),#19582); -#19579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19580,#19581),.UNSPECIFIED., +#21957 = CARTESIAN_POINT('',(0.E+000,-0.48)); +#21958 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#21959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21960 = ORIENTED_EDGE('',*,*,#21168,.F.); +#21961 = ORIENTED_EDGE('',*,*,#21962,.F.); +#21962 = EDGE_CURVE('',#21225,#21141,#21963,.T.); +#21963 = SURFACE_CURVE('',#21964,(#21969,#21975),.PCURVE_S1.); +#21964 = CIRCLE('',#21965,1.); +#21965 = AXIS2_PLACEMENT_3D('',#21966,#21967,#21968); +#21966 = CARTESIAN_POINT('',(55.238908,22.145721,1.1)); +#21967 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21968 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#21969 = PCURVE('',#21185,#21970); +#21970 = DEFINITIONAL_REPRESENTATION('',(#21971),#21974); +#21971 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21972,#21973),.UNSPECIFIED., .F.,.F.,(2,2),(4.407696326369,5.0170816344),.PIECEWISE_BEZIER_KNOTS.); -#19580 = CARTESIAN_POINT('',(4.407696326369,-0.35)); -#19581 = CARTESIAN_POINT('',(5.0170816344,-0.35)); -#19582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19583 = PCURVE('',#18764,#19584); -#19584 = DEFINITIONAL_REPRESENTATION('',(#19585),#19589); -#19585 = CIRCLE('',#19586,1.); -#19586 = AXIS2_PLACEMENT_2D('',#19587,#19588); -#19587 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#19588 = DIRECTION('',(1.,0.E+000)); -#19589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19590 = ORIENTED_EDGE('',*,*,#18832,.F.); -#19591 = ORIENTED_EDGE('',*,*,#19592,.F.); -#19592 = EDGE_CURVE('',#19499,#18805,#19593,.T.); -#19593 = SURFACE_CURVE('',#19594,(#19598,#19604),.PCURVE_S1.); -#19594 = LINE('',#19595,#19596); -#19595 = CARTESIAN_POINT('',(56.238908,22.495721,1.1)); -#19596 = VECTOR('',#19597,1.); -#19597 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19598 = PCURVE('',#18793,#19599); -#19599 = DEFINITIONAL_REPRESENTATION('',(#19600),#19603); -#19600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19601,#19602),.UNSPECIFIED., +#21972 = CARTESIAN_POINT('',(4.407696326369,-0.35)); +#21973 = CARTESIAN_POINT('',(5.0170816344,-0.35)); +#21974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21975 = PCURVE('',#21156,#21976); +#21976 = DEFINITIONAL_REPRESENTATION('',(#21977),#21981); +#21977 = CIRCLE('',#21978,1.); +#21978 = AXIS2_PLACEMENT_2D('',#21979,#21980); +#21979 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#21980 = DIRECTION('',(1.,0.E+000)); +#21981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#21982 = ORIENTED_EDGE('',*,*,#21224,.F.); +#21983 = ORIENTED_EDGE('',*,*,#21984,.F.); +#21984 = EDGE_CURVE('',#21891,#21197,#21985,.T.); +#21985 = SURFACE_CURVE('',#21986,(#21990,#21996),.PCURVE_S1.); +#21986 = LINE('',#21987,#21988); +#21987 = CARTESIAN_POINT('',(56.238908,22.495721,1.1)); +#21988 = VECTOR('',#21989,1.); +#21989 = DIRECTION('',(0.E+000,1.,0.E+000)); +#21990 = PCURVE('',#21185,#21991); +#21991 = DEFINITIONAL_REPRESENTATION('',(#21992),#21995); +#21992 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21993,#21994),.UNSPECIFIED., .F.,.F.,(2,2),(-0.48,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#19601 = CARTESIAN_POINT('',(3.14159265359,-0.48)); -#19602 = CARTESIAN_POINT('',(3.14159265359,-0.35)); -#19603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#21993 = CARTESIAN_POINT('',(3.14159265359,-0.48)); +#21994 = CARTESIAN_POINT('',(3.14159265359,-0.35)); +#21995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19604 = PCURVE('',#18821,#19605); -#19605 = DEFINITIONAL_REPRESENTATION('',(#19606),#19609); -#19606 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19607,#19608),.UNSPECIFIED., +#21996 = PCURVE('',#21213,#21997); +#21997 = DEFINITIONAL_REPRESENTATION('',(#21998),#22001); +#21998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21999,#22000),.UNSPECIFIED., .F.,.F.,(2,2),(-0.48,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#19607 = CARTESIAN_POINT('',(3.14159265359,-0.48)); -#19608 = CARTESIAN_POINT('',(3.14159265359,-0.35)); -#19609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19610 = ADVANCED_FACE('',(#19611),#19516,.T.); -#19611 = FACE_BOUND('',#19612,.T.); -#19612 = EDGE_LOOP('',(#19613,#19614,#19640,#19690)); -#19613 = ORIENTED_EDGE('',*,*,#19498,.F.); -#19614 = ORIENTED_EDGE('',*,*,#19615,.F.); -#19615 = EDGE_CURVE('',#19616,#19499,#19618,.T.); -#19616 = VERTEX_POINT('',#19617); -#19617 = CARTESIAN_POINT('',(56.168908,21.945721,1.1)); -#19618 = SURFACE_CURVE('',#19619,(#19623,#19629),.PCURVE_S1.); -#19619 = LINE('',#19620,#19621); -#19620 = CARTESIAN_POINT('',(56.168908,21.945721,1.1)); -#19621 = VECTOR('',#19622,1.); -#19622 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#19623 = PCURVE('',#19516,#19624); -#19624 = DEFINITIONAL_REPRESENTATION('',(#19625),#19628); -#19625 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19626,#19627),.UNSPECIFIED., +#21999 = CARTESIAN_POINT('',(3.14159265359,-0.48)); +#22000 = CARTESIAN_POINT('',(3.14159265359,-0.35)); +#22001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22002 = ADVANCED_FACE('',(#22003),#21908,.T.); +#22003 = FACE_BOUND('',#22004,.T.); +#22004 = EDGE_LOOP('',(#22005,#22006,#22032,#22082)); +#22005 = ORIENTED_EDGE('',*,*,#21890,.F.); +#22006 = ORIENTED_EDGE('',*,*,#22007,.F.); +#22007 = EDGE_CURVE('',#22008,#21891,#22010,.T.); +#22008 = VERTEX_POINT('',#22009); +#22009 = CARTESIAN_POINT('',(56.168908,21.945721,1.1)); +#22010 = SURFACE_CURVE('',#22011,(#22015,#22021),.PCURVE_S1.); +#22011 = LINE('',#22012,#22013); +#22012 = CARTESIAN_POINT('',(56.168908,21.945721,1.1)); +#22013 = VECTOR('',#22014,1.); +#22014 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#22015 = PCURVE('',#21908,#22016); +#22016 = DEFINITIONAL_REPRESENTATION('',(#22017),#22020); +#22017 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22018,#22019),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#19626 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19627 = CARTESIAN_POINT('',(0.E+000,7.E-002)); -#19628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19629 = PCURVE('',#19630,#19635); -#19630 = CONICAL_SURFACE('',#19631,0.93,0.785398163397); -#19631 = AXIS2_PLACEMENT_3D('',#19632,#19633,#19634); -#19632 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); -#19633 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19634 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19635 = DEFINITIONAL_REPRESENTATION('',(#19636),#19639); -#19636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19637,#19638),.UNSPECIFIED., +#22018 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22019 = CARTESIAN_POINT('',(0.E+000,7.E-002)); +#22020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22021 = PCURVE('',#22022,#22027); +#22022 = CONICAL_SURFACE('',#22023,0.93,0.785398163397); +#22023 = AXIS2_PLACEMENT_3D('',#22024,#22025,#22026); +#22024 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); +#22025 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22026 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22027 = DEFINITIONAL_REPRESENTATION('',(#22028),#22031); +#22028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22029,#22030),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#19637 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#19638 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); -#19639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19640 = ORIENTED_EDGE('',*,*,#19641,.T.); -#19641 = EDGE_CURVE('',#19616,#19642,#19644,.T.); -#19642 = VERTEX_POINT('',#19643); -#19643 = CARTESIAN_POINT('',(54.308908,21.945721,1.1)); -#19644 = SURFACE_CURVE('',#19645,(#19650,#19679),.PCURVE_S1.); -#19645 = CIRCLE('',#19646,0.93); -#19646 = AXIS2_PLACEMENT_3D('',#19647,#19648,#19649); -#19647 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); -#19648 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19649 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19650 = PCURVE('',#19516,#19651); -#19651 = DEFINITIONAL_REPRESENTATION('',(#19652),#19678); -#19652 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19653,#19654,#19655,#19656, - #19657,#19658,#19659,#19660,#19661,#19662,#19663,#19664,#19665, - #19666,#19667,#19668,#19669,#19670,#19671,#19672,#19673,#19674, - #19675,#19676,#19677),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22029 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#22030 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); +#22031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22032 = ORIENTED_EDGE('',*,*,#22033,.T.); +#22033 = EDGE_CURVE('',#22008,#22034,#22036,.T.); +#22034 = VERTEX_POINT('',#22035); +#22035 = CARTESIAN_POINT('',(54.308908,21.945721,1.1)); +#22036 = SURFACE_CURVE('',#22037,(#22042,#22071),.PCURVE_S1.); +#22037 = CIRCLE('',#22038,0.93); +#22038 = AXIS2_PLACEMENT_3D('',#22039,#22040,#22041); +#22039 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); +#22040 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22041 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22042 = PCURVE('',#21908,#22043); +#22043 = DEFINITIONAL_REPRESENTATION('',(#22044),#22070); +#22044 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22045,#22046,#22047,#22048, + #22049,#22050,#22051,#22052,#22053,#22054,#22055,#22056,#22057, + #22058,#22059,#22060,#22061,#22062,#22063,#22064,#22065,#22066, + #22067,#22068,#22069),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -24090,140 +27079,140 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#19653 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19654 = CARTESIAN_POINT('',(4.759988869075E-002,9.865035100538E-016)); -#19655 = CARTESIAN_POINT('',(0.142799666072,1.361780904012E-015)); -#19656 = CARTESIAN_POINT('',(0.285599332145,-5.363629483806E-016)); -#19657 = CARTESIAN_POINT('',(0.428398998217,-1.716282479807E-015)); -#19658 = CARTESIAN_POINT('',(0.571198664289,-1.963737078103E-015)); -#19659 = CARTESIAN_POINT('',(0.713998330361,1.947934266932E-015)); -#19660 = CARTESIAN_POINT('',(0.856797996434,-7.227087998241E-016)); -#19661 = CARTESIAN_POINT('',(0.999597662506,-3.617195417872E-016)); -#19662 = CARTESIAN_POINT('',(1.142397328578,9.511605655338E-016)); -#19663 = CARTESIAN_POINT('',(1.28519699465,-7.609860163792E-016)); -#19664 = CARTESIAN_POINT('',(1.427996660723,-2.346190935829E-016)); -#19665 = CARTESIAN_POINT('',(1.570796326795,1.003183964032E-016)); -#19666 = CARTESIAN_POINT('',(1.713595992867,-1.666544920301E-016)); -#19667 = CARTESIAN_POINT('',(1.856395658939,-7.031927520461E-016)); -#19668 = CARTESIAN_POINT('',(1.999195325012,9.715914969886E-016)); -#19669 = CARTESIAN_POINT('',(2.141994991084,-1.982562348385E-016)); -#19670 = CARTESIAN_POINT('',(2.284794657156,-8.365688561161E-016)); -#19671 = CARTESIAN_POINT('',(2.427594323228,1.9881594407E-015)); -#19672 = CARTESIAN_POINT('',(2.570393989301,-2.010452456232E-015)); -#19673 = CARTESIAN_POINT('',(2.713193655373,-1.7496779118E-015)); -#19674 = CARTESIAN_POINT('',(2.855993321445,-4.94626879923E-016)); -#19675 = CARTESIAN_POINT('',(2.998792987518,1.415907458233E-015)); -#19676 = CARTESIAN_POINT('',(3.093992764899,9.272518613274E-016)); -#19677 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#19678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19679 = PCURVE('',#19680,#19685); -#19680 = CYLINDRICAL_SURFACE('',#19681,0.93); -#19681 = AXIS2_PLACEMENT_3D('',#19682,#19683,#19684); -#19682 = CARTESIAN_POINT('',(55.238908,21.895721,1.1)); -#19683 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19684 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19685 = DEFINITIONAL_REPRESENTATION('',(#19686),#19689); -#19686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19687,#19688),.UNSPECIFIED., +#22045 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22046 = CARTESIAN_POINT('',(4.759988869075E-002,9.865035100538E-016)); +#22047 = CARTESIAN_POINT('',(0.142799666072,1.361780904012E-015)); +#22048 = CARTESIAN_POINT('',(0.285599332145,-5.363629483806E-016)); +#22049 = CARTESIAN_POINT('',(0.428398998217,-1.716282479807E-015)); +#22050 = CARTESIAN_POINT('',(0.571198664289,-1.963737078103E-015)); +#22051 = CARTESIAN_POINT('',(0.713998330361,1.947934266932E-015)); +#22052 = CARTESIAN_POINT('',(0.856797996434,-7.227087998241E-016)); +#22053 = CARTESIAN_POINT('',(0.999597662506,-3.617195417872E-016)); +#22054 = CARTESIAN_POINT('',(1.142397328578,9.511605655338E-016)); +#22055 = CARTESIAN_POINT('',(1.28519699465,-7.609860163792E-016)); +#22056 = CARTESIAN_POINT('',(1.427996660723,-2.346190935829E-016)); +#22057 = CARTESIAN_POINT('',(1.570796326795,1.003183964032E-016)); +#22058 = CARTESIAN_POINT('',(1.713595992867,-1.666544920301E-016)); +#22059 = CARTESIAN_POINT('',(1.856395658939,-7.031927520461E-016)); +#22060 = CARTESIAN_POINT('',(1.999195325012,9.715914969886E-016)); +#22061 = CARTESIAN_POINT('',(2.141994991084,-1.982562348385E-016)); +#22062 = CARTESIAN_POINT('',(2.284794657156,-8.365688561161E-016)); +#22063 = CARTESIAN_POINT('',(2.427594323228,1.9881594407E-015)); +#22064 = CARTESIAN_POINT('',(2.570393989301,-2.010452456232E-015)); +#22065 = CARTESIAN_POINT('',(2.713193655373,-1.7496779118E-015)); +#22066 = CARTESIAN_POINT('',(2.855993321445,-4.94626879923E-016)); +#22067 = CARTESIAN_POINT('',(2.998792987518,1.415907458233E-015)); +#22068 = CARTESIAN_POINT('',(3.093992764899,9.272518613274E-016)); +#22069 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22071 = PCURVE('',#22072,#22077); +#22072 = CYLINDRICAL_SURFACE('',#22073,0.93); +#22073 = AXIS2_PLACEMENT_3D('',#22074,#22075,#22076); +#22074 = CARTESIAN_POINT('',(55.238908,21.895721,1.1)); +#22075 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22076 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22077 = DEFINITIONAL_REPRESENTATION('',(#22078),#22081); +#22078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22079,#22080),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#19687 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#19688 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#19689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19690 = ORIENTED_EDGE('',*,*,#19691,.T.); -#19691 = EDGE_CURVE('',#19642,#19501,#19692,.T.); -#19692 = SURFACE_CURVE('',#19693,(#19697,#19703),.PCURVE_S1.); -#19693 = LINE('',#19694,#19695); -#19694 = CARTESIAN_POINT('',(54.308908,21.945721,1.1)); -#19695 = VECTOR('',#19696,1.); -#19696 = DIRECTION('',(-0.707106781187,0.707106781187, +#22079 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#22080 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#22081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22082 = ORIENTED_EDGE('',*,*,#22083,.T.); +#22083 = EDGE_CURVE('',#22034,#21893,#22084,.T.); +#22084 = SURFACE_CURVE('',#22085,(#22089,#22095),.PCURVE_S1.); +#22085 = LINE('',#22086,#22087); +#22086 = CARTESIAN_POINT('',(54.308908,21.945721,1.1)); +#22087 = VECTOR('',#22088,1.); +#22088 = DIRECTION('',(-0.707106781187,0.707106781187, -1.68827146095E-016)); -#19697 = PCURVE('',#19516,#19698); -#19698 = DEFINITIONAL_REPRESENTATION('',(#19699),#19702); -#19699 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19700,#19701),.UNSPECIFIED., +#22089 = PCURVE('',#21908,#22090); +#22090 = DEFINITIONAL_REPRESENTATION('',(#22091),#22094); +#22091 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22092,#22093),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#19700 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#19701 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#19702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22092 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22093 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#22094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19703 = PCURVE('',#19630,#19704); -#19704 = DEFINITIONAL_REPRESENTATION('',(#19705),#19708); -#19705 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19706,#19707),.UNSPECIFIED., +#22095 = PCURVE('',#22022,#22096); +#22096 = DEFINITIONAL_REPRESENTATION('',(#22097),#22100); +#22097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22098,#22099),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#19706 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#19707 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#19708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19709 = ADVANCED_FACE('',(#19710),#19680,.T.); -#19710 = FACE_BOUND('',#19711,.T.); -#19711 = EDGE_LOOP('',(#19712,#19713,#19739,#19789)); -#19712 = ORIENTED_EDGE('',*,*,#19641,.F.); -#19713 = ORIENTED_EDGE('',*,*,#19714,.F.); -#19714 = EDGE_CURVE('',#19715,#19616,#19717,.T.); -#19715 = VERTEX_POINT('',#19716); -#19716 = CARTESIAN_POINT('',(56.168908,21.845721,1.1)); -#19717 = SURFACE_CURVE('',#19718,(#19722,#19728),.PCURVE_S1.); -#19718 = LINE('',#19719,#19720); -#19719 = CARTESIAN_POINT('',(56.168908,21.895721,1.1)); -#19720 = VECTOR('',#19721,1.); -#19721 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19722 = PCURVE('',#19680,#19723); -#19723 = DEFINITIONAL_REPRESENTATION('',(#19724),#19727); -#19724 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19725,#19726),.UNSPECIFIED., +#22098 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22099 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#22100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22101 = ADVANCED_FACE('',(#22102),#22072,.T.); +#22102 = FACE_BOUND('',#22103,.T.); +#22103 = EDGE_LOOP('',(#22104,#22105,#22131,#22181)); +#22104 = ORIENTED_EDGE('',*,*,#22033,.F.); +#22105 = ORIENTED_EDGE('',*,*,#22106,.F.); +#22106 = EDGE_CURVE('',#22107,#22008,#22109,.T.); +#22107 = VERTEX_POINT('',#22108); +#22108 = CARTESIAN_POINT('',(56.168908,21.845721,1.1)); +#22109 = SURFACE_CURVE('',#22110,(#22114,#22120),.PCURVE_S1.); +#22110 = LINE('',#22111,#22112); +#22111 = CARTESIAN_POINT('',(56.168908,21.895721,1.1)); +#22112 = VECTOR('',#22113,1.); +#22113 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22114 = PCURVE('',#22072,#22115); +#22115 = DEFINITIONAL_REPRESENTATION('',(#22116),#22119); +#22116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22117,#22118),.UNSPECIFIED., .F.,.F.,(2,2),(-5.E-002,5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#19725 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#19726 = CARTESIAN_POINT('',(0.E+000,5.E-002)); -#19727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19728 = PCURVE('',#19729,#19734); -#19729 = CYLINDRICAL_SURFACE('',#19730,0.93); -#19730 = AXIS2_PLACEMENT_3D('',#19731,#19732,#19733); -#19731 = CARTESIAN_POINT('',(55.238908,21.895721,1.1)); -#19732 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19733 = DIRECTION('',(1.,0.E+000,0.E+000)); -#19734 = DEFINITIONAL_REPRESENTATION('',(#19735),#19738); -#19735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19736,#19737),.UNSPECIFIED., +#22117 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#22118 = CARTESIAN_POINT('',(0.E+000,5.E-002)); +#22119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22120 = PCURVE('',#22121,#22126); +#22121 = CYLINDRICAL_SURFACE('',#22122,0.93); +#22122 = AXIS2_PLACEMENT_3D('',#22123,#22124,#22125); +#22123 = CARTESIAN_POINT('',(55.238908,21.895721,1.1)); +#22124 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22125 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22126 = DEFINITIONAL_REPRESENTATION('',(#22127),#22130); +#22127 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22128,#22129),.UNSPECIFIED., .F.,.F.,(2,2),(-5.E-002,5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#19736 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#19737 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#19738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19739 = ORIENTED_EDGE('',*,*,#19740,.T.); -#19740 = EDGE_CURVE('',#19715,#19741,#19743,.T.); -#19741 = VERTEX_POINT('',#19742); -#19742 = CARTESIAN_POINT('',(54.308908,21.845721,1.1)); -#19743 = SURFACE_CURVE('',#19744,(#19749,#19755),.PCURVE_S1.); -#19744 = CIRCLE('',#19745,0.93); -#19745 = AXIS2_PLACEMENT_3D('',#19746,#19747,#19748); -#19746 = CARTESIAN_POINT('',(55.238908,21.845721,1.1)); -#19747 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19748 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19749 = PCURVE('',#19680,#19750); -#19750 = DEFINITIONAL_REPRESENTATION('',(#19751),#19754); -#19751 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19752,#19753),.UNSPECIFIED., +#22128 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#22129 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#22130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22131 = ORIENTED_EDGE('',*,*,#22132,.T.); +#22132 = EDGE_CURVE('',#22107,#22133,#22135,.T.); +#22133 = VERTEX_POINT('',#22134); +#22134 = CARTESIAN_POINT('',(54.308908,21.845721,1.1)); +#22135 = SURFACE_CURVE('',#22136,(#22141,#22147),.PCURVE_S1.); +#22136 = CIRCLE('',#22137,0.93); +#22137 = AXIS2_PLACEMENT_3D('',#22138,#22139,#22140); +#22138 = CARTESIAN_POINT('',(55.238908,21.845721,1.1)); +#22139 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22140 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22141 = PCURVE('',#22072,#22142); +#22142 = DEFINITIONAL_REPRESENTATION('',(#22143),#22146); +#22143 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22144,#22145),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#19752 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#19753 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#19754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19755 = PCURVE('',#19756,#19761); -#19756 = CONICAL_SURFACE('',#19757,1.,0.785398163397); -#19757 = AXIS2_PLACEMENT_3D('',#19758,#19759,#19760); -#19758 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); -#19759 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19760 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19761 = DEFINITIONAL_REPRESENTATION('',(#19762),#19788); -#19762 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19763,#19764,#19765,#19766, - #19767,#19768,#19769,#19770,#19771,#19772,#19773,#19774,#19775, - #19776,#19777,#19778,#19779,#19780,#19781,#19782,#19783,#19784, - #19785,#19786,#19787),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22144 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#22145 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#22146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22147 = PCURVE('',#22148,#22153); +#22148 = CONICAL_SURFACE('',#22149,1.,0.785398163397); +#22149 = AXIS2_PLACEMENT_3D('',#22150,#22151,#22152); +#22150 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); +#22151 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#22152 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22153 = DEFINITIONAL_REPRESENTATION('',(#22154),#22180); +#22154 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22155,#22156,#22157,#22158, + #22159,#22160,#22161,#22162,#22163,#22164,#22165,#22166,#22167, + #22168,#22169,#22170,#22171,#22172,#22173,#22174,#22175,#22176, + #22177,#22178,#22179),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -24231,114 +27220,114 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#19763 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); -#19764 = CARTESIAN_POINT('',(3.093992764899,-7.E-002)); -#19765 = CARTESIAN_POINT('',(2.998792987518,-7.E-002)); -#19766 = CARTESIAN_POINT('',(2.855993321445,-7.E-002)); -#19767 = CARTESIAN_POINT('',(2.713193655373,-7.E-002)); -#19768 = CARTESIAN_POINT('',(2.570393989301,-7.E-002)); -#19769 = CARTESIAN_POINT('',(2.427594323228,-7.E-002)); -#19770 = CARTESIAN_POINT('',(2.284794657156,-7.E-002)); -#19771 = CARTESIAN_POINT('',(2.141994991084,-7.E-002)); -#19772 = CARTESIAN_POINT('',(1.999195325012,-7.E-002)); -#19773 = CARTESIAN_POINT('',(1.856395658939,-7.E-002)); -#19774 = CARTESIAN_POINT('',(1.713595992867,-7.E-002)); -#19775 = CARTESIAN_POINT('',(1.570796326795,-7.E-002)); -#19776 = CARTESIAN_POINT('',(1.427996660723,-7.E-002)); -#19777 = CARTESIAN_POINT('',(1.28519699465,-7.E-002)); -#19778 = CARTESIAN_POINT('',(1.142397328578,-7.E-002)); -#19779 = CARTESIAN_POINT('',(0.999597662506,-7.E-002)); -#19780 = CARTESIAN_POINT('',(0.856797996434,-7.E-002)); -#19781 = CARTESIAN_POINT('',(0.713998330361,-7.E-002)); -#19782 = CARTESIAN_POINT('',(0.571198664289,-7.E-002)); -#19783 = CARTESIAN_POINT('',(0.428398998217,-7.E-002)); -#19784 = CARTESIAN_POINT('',(0.285599332145,-7.E-002)); -#19785 = CARTESIAN_POINT('',(0.142799666072,-7.E-002)); -#19786 = CARTESIAN_POINT('',(4.759988869075E-002,-7.E-002)); -#19787 = CARTESIAN_POINT('',(0.E+000,-7.E-002)); -#19788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19789 = ORIENTED_EDGE('',*,*,#19790,.T.); -#19790 = EDGE_CURVE('',#19741,#19642,#19791,.T.); -#19791 = SURFACE_CURVE('',#19792,(#19796,#19802),.PCURVE_S1.); -#19792 = LINE('',#19793,#19794); -#19793 = CARTESIAN_POINT('',(54.308908,21.895721,1.1)); -#19794 = VECTOR('',#19795,1.); -#19795 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19796 = PCURVE('',#19680,#19797); -#19797 = DEFINITIONAL_REPRESENTATION('',(#19798),#19801); -#19798 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19799,#19800),.UNSPECIFIED., +#22155 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); +#22156 = CARTESIAN_POINT('',(3.093992764899,-7.E-002)); +#22157 = CARTESIAN_POINT('',(2.998792987518,-7.E-002)); +#22158 = CARTESIAN_POINT('',(2.855993321445,-7.E-002)); +#22159 = CARTESIAN_POINT('',(2.713193655373,-7.E-002)); +#22160 = CARTESIAN_POINT('',(2.570393989301,-7.E-002)); +#22161 = CARTESIAN_POINT('',(2.427594323228,-7.E-002)); +#22162 = CARTESIAN_POINT('',(2.284794657156,-7.E-002)); +#22163 = CARTESIAN_POINT('',(2.141994991084,-7.E-002)); +#22164 = CARTESIAN_POINT('',(1.999195325012,-7.E-002)); +#22165 = CARTESIAN_POINT('',(1.856395658939,-7.E-002)); +#22166 = CARTESIAN_POINT('',(1.713595992867,-7.E-002)); +#22167 = CARTESIAN_POINT('',(1.570796326795,-7.E-002)); +#22168 = CARTESIAN_POINT('',(1.427996660723,-7.E-002)); +#22169 = CARTESIAN_POINT('',(1.28519699465,-7.E-002)); +#22170 = CARTESIAN_POINT('',(1.142397328578,-7.E-002)); +#22171 = CARTESIAN_POINT('',(0.999597662506,-7.E-002)); +#22172 = CARTESIAN_POINT('',(0.856797996434,-7.E-002)); +#22173 = CARTESIAN_POINT('',(0.713998330361,-7.E-002)); +#22174 = CARTESIAN_POINT('',(0.571198664289,-7.E-002)); +#22175 = CARTESIAN_POINT('',(0.428398998217,-7.E-002)); +#22176 = CARTESIAN_POINT('',(0.285599332145,-7.E-002)); +#22177 = CARTESIAN_POINT('',(0.142799666072,-7.E-002)); +#22178 = CARTESIAN_POINT('',(4.759988869075E-002,-7.E-002)); +#22179 = CARTESIAN_POINT('',(0.E+000,-7.E-002)); +#22180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22181 = ORIENTED_EDGE('',*,*,#22182,.T.); +#22182 = EDGE_CURVE('',#22133,#22034,#22183,.T.); +#22183 = SURFACE_CURVE('',#22184,(#22188,#22194),.PCURVE_S1.); +#22184 = LINE('',#22185,#22186); +#22185 = CARTESIAN_POINT('',(54.308908,21.895721,1.1)); +#22186 = VECTOR('',#22187,1.); +#22187 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22188 = PCURVE('',#22072,#22189); +#22189 = DEFINITIONAL_REPRESENTATION('',(#22190),#22193); +#22190 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22191,#22192),.UNSPECIFIED., .F.,.F.,(2,2),(-5.E-002,5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#19799 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#19800 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#19801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22191 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#22192 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#22193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19802 = PCURVE('',#19729,#19803); -#19803 = DEFINITIONAL_REPRESENTATION('',(#19804),#19807); -#19804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19805,#19806),.UNSPECIFIED., +#22194 = PCURVE('',#22121,#22195); +#22195 = DEFINITIONAL_REPRESENTATION('',(#22196),#22199); +#22196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22197,#22198),.UNSPECIFIED., .F.,.F.,(2,2),(-5.E-002,5.E-002),.PIECEWISE_BEZIER_KNOTS.); -#19805 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#19806 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#19807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19808 = ADVANCED_FACE('',(#19809),#19756,.T.); -#19809 = FACE_BOUND('',#19810,.T.); -#19810 = EDGE_LOOP('',(#19811,#19812,#19838,#19888)); -#19811 = ORIENTED_EDGE('',*,*,#19740,.F.); -#19812 = ORIENTED_EDGE('',*,*,#19813,.T.); -#19813 = EDGE_CURVE('',#19715,#19814,#19816,.T.); -#19814 = VERTEX_POINT('',#19815); -#19815 = CARTESIAN_POINT('',(56.238908,21.775721,1.1)); -#19816 = SURFACE_CURVE('',#19817,(#19821,#19827),.PCURVE_S1.); -#19817 = LINE('',#19818,#19819); -#19818 = CARTESIAN_POINT('',(56.238908,21.775721,1.1)); -#19819 = VECTOR('',#19820,1.); -#19820 = DIRECTION('',(0.707106781187,-0.707106781187, +#22197 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#22198 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#22199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22200 = ADVANCED_FACE('',(#22201),#22148,.T.); +#22201 = FACE_BOUND('',#22202,.T.); +#22202 = EDGE_LOOP('',(#22203,#22204,#22230,#22280)); +#22203 = ORIENTED_EDGE('',*,*,#22132,.F.); +#22204 = ORIENTED_EDGE('',*,*,#22205,.T.); +#22205 = EDGE_CURVE('',#22107,#22206,#22208,.T.); +#22206 = VERTEX_POINT('',#22207); +#22207 = CARTESIAN_POINT('',(56.238908,21.775721,1.1)); +#22208 = SURFACE_CURVE('',#22209,(#22213,#22219),.PCURVE_S1.); +#22209 = LINE('',#22210,#22211); +#22210 = CARTESIAN_POINT('',(56.238908,21.775721,1.1)); +#22211 = VECTOR('',#22212,1.); +#22212 = DIRECTION('',(0.707106781187,-0.707106781187, -1.570092458684E-016)); -#19821 = PCURVE('',#19756,#19822); -#19822 = DEFINITIONAL_REPRESENTATION('',(#19823),#19826); -#19823 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19824,#19825),.UNSPECIFIED., +#22213 = PCURVE('',#22148,#22214); +#22214 = DEFINITIONAL_REPRESENTATION('',(#22215),#22218); +#22215 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22216,#22217),.UNSPECIFIED., .F.,.F.,(2,2),(-9.899494936612E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#19824 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); -#19825 = CARTESIAN_POINT('',(3.14159265359,9.813077866774E-018)); -#19826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22216 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); +#22217 = CARTESIAN_POINT('',(3.14159265359,9.813077866774E-018)); +#22218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19827 = PCURVE('',#19828,#19833); -#19828 = CONICAL_SURFACE('',#19829,1.,0.785398163397); -#19829 = AXIS2_PLACEMENT_3D('',#19830,#19831,#19832); -#19830 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); -#19831 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#19832 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19833 = DEFINITIONAL_REPRESENTATION('',(#19834),#19837); -#19834 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19835,#19836),.UNSPECIFIED., +#22219 = PCURVE('',#22220,#22225); +#22220 = CONICAL_SURFACE('',#22221,1.,0.785398163397); +#22221 = AXIS2_PLACEMENT_3D('',#22222,#22223,#22224); +#22222 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); +#22223 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#22224 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22225 = DEFINITIONAL_REPRESENTATION('',(#22226),#22229); +#22226 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22227,#22228),.UNSPECIFIED., .F.,.F.,(2,2),(-9.899494936612E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#19835 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); -#19836 = CARTESIAN_POINT('',(3.14159265359,9.813077866774E-018)); -#19837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19838 = ORIENTED_EDGE('',*,*,#19839,.T.); -#19839 = EDGE_CURVE('',#19814,#19840,#19842,.T.); -#19840 = VERTEX_POINT('',#19841); -#19841 = CARTESIAN_POINT('',(54.238908,21.775721,1.1)); -#19842 = SURFACE_CURVE('',#19843,(#19848,#19877),.PCURVE_S1.); -#19843 = CIRCLE('',#19844,1.); -#19844 = AXIS2_PLACEMENT_3D('',#19845,#19846,#19847); -#19845 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); -#19846 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19847 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19848 = PCURVE('',#19756,#19849); -#19849 = DEFINITIONAL_REPRESENTATION('',(#19850),#19876); -#19850 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19851,#19852,#19853,#19854, - #19855,#19856,#19857,#19858,#19859,#19860,#19861,#19862,#19863, - #19864,#19865,#19866,#19867,#19868,#19869,#19870,#19871,#19872, - #19873,#19874,#19875),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22227 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); +#22228 = CARTESIAN_POINT('',(3.14159265359,9.813077866774E-018)); +#22229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22230 = ORIENTED_EDGE('',*,*,#22231,.T.); +#22231 = EDGE_CURVE('',#22206,#22232,#22234,.T.); +#22232 = VERTEX_POINT('',#22233); +#22233 = CARTESIAN_POINT('',(54.238908,21.775721,1.1)); +#22234 = SURFACE_CURVE('',#22235,(#22240,#22269),.PCURVE_S1.); +#22235 = CIRCLE('',#22236,1.); +#22236 = AXIS2_PLACEMENT_3D('',#22237,#22238,#22239); +#22237 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); +#22238 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22239 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22240 = PCURVE('',#22148,#22241); +#22241 = DEFINITIONAL_REPRESENTATION('',(#22242),#22268); +#22242 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22243,#22244,#22245,#22246, + #22247,#22248,#22249,#22250,#22251,#22252,#22253,#22254,#22255, + #22256,#22257,#22258,#22259,#22260,#22261,#22262,#22263,#22264, + #22265,#22266,#22267),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -24346,110 +27335,110 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#19851 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#19852 = CARTESIAN_POINT('',(3.093992764899,1.427225669824E-015)); -#19853 = CARTESIAN_POINT('',(2.998792987518,1.510256676895E-015)); -#19854 = CARTESIAN_POINT('',(2.855993321445,-2.046925693997E-015)); -#19855 = CARTESIAN_POINT('',(2.713193655373,-9.912242871167E-016)); -#19856 = CARTESIAN_POINT('',(2.570393989301,1.546916561533E-016)); -#19857 = CARTESIAN_POINT('',(2.427594323228,2.10284432979E-015)); -#19858 = CARTESIAN_POINT('',(2.284794657156,-9.429350803516E-016)); -#19859 = CARTESIAN_POINT('',(2.141994991084,-7.157375587484E-017)); -#19860 = CARTESIAN_POINT('',(1.999195325012,-7.021676462147E-016)); -#19861 = CARTESIAN_POINT('',(1.856395658939,-6.533873798311E-016)); -#19862 = CARTESIAN_POINT('',(1.713595992867,2.763190053018E-016)); -#19863 = CARTESIAN_POINT('',(1.570796326795,-1.552509269843E-016)); -#19864 = CARTESIAN_POINT('',(1.427996660723,3.446847026352E-016)); -#19865 = CARTESIAN_POINT('',(1.28519699465,-5.970358682943E-016)); -#19866 = CARTESIAN_POINT('',(1.142397328578,-6.76533429681E-016)); -#19867 = CARTESIAN_POINT('',(0.999597662506,7.25181635547E-017)); -#19868 = CARTESIAN_POINT('',(0.856797996434,-9.846755019716E-016)); -#19869 = CARTESIAN_POINT('',(0.713998330361,2.125714096841E-015)); -#19870 = CARTESIAN_POINT('',(0.571198664289,1.049530095722E-016)); -#19871 = CARTESIAN_POINT('',(0.428398998217,-9.953338689097E-016)); -#19872 = CARTESIAN_POINT('',(0.285599332145,-1.980911350569E-015)); -#19873 = CARTESIAN_POINT('',(0.142799666072,1.53198460939E-015)); -#19874 = CARTESIAN_POINT('',(4.759988869075E-002,1.427493708694E-015)); -#19875 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#19876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19877 = PCURVE('',#19878,#19883); -#19878 = CYLINDRICAL_SURFACE('',#19879,1.); -#19879 = AXIS2_PLACEMENT_3D('',#19880,#19881,#19882); -#19880 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#19881 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19882 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19883 = DEFINITIONAL_REPRESENTATION('',(#19884),#19887); -#19884 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19885,#19886),.UNSPECIFIED., +#22243 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#22244 = CARTESIAN_POINT('',(3.093992764899,1.427225669824E-015)); +#22245 = CARTESIAN_POINT('',(2.998792987518,1.510256676895E-015)); +#22246 = CARTESIAN_POINT('',(2.855993321445,-2.046925693997E-015)); +#22247 = CARTESIAN_POINT('',(2.713193655373,-9.912242871167E-016)); +#22248 = CARTESIAN_POINT('',(2.570393989301,1.546916561533E-016)); +#22249 = CARTESIAN_POINT('',(2.427594323228,2.10284432979E-015)); +#22250 = CARTESIAN_POINT('',(2.284794657156,-9.429350803516E-016)); +#22251 = CARTESIAN_POINT('',(2.141994991084,-7.157375587484E-017)); +#22252 = CARTESIAN_POINT('',(1.999195325012,-7.021676462147E-016)); +#22253 = CARTESIAN_POINT('',(1.856395658939,-6.533873798311E-016)); +#22254 = CARTESIAN_POINT('',(1.713595992867,2.763190053018E-016)); +#22255 = CARTESIAN_POINT('',(1.570796326795,-1.552509269843E-016)); +#22256 = CARTESIAN_POINT('',(1.427996660723,3.446847026352E-016)); +#22257 = CARTESIAN_POINT('',(1.28519699465,-5.970358682943E-016)); +#22258 = CARTESIAN_POINT('',(1.142397328578,-6.76533429681E-016)); +#22259 = CARTESIAN_POINT('',(0.999597662506,7.25181635547E-017)); +#22260 = CARTESIAN_POINT('',(0.856797996434,-9.846755019716E-016)); +#22261 = CARTESIAN_POINT('',(0.713998330361,2.125714096841E-015)); +#22262 = CARTESIAN_POINT('',(0.571198664289,1.049530095722E-016)); +#22263 = CARTESIAN_POINT('',(0.428398998217,-9.953338689097E-016)); +#22264 = CARTESIAN_POINT('',(0.285599332145,-1.980911350569E-015)); +#22265 = CARTESIAN_POINT('',(0.142799666072,1.53198460939E-015)); +#22266 = CARTESIAN_POINT('',(4.759988869075E-002,1.427493708694E-015)); +#22267 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22269 = PCURVE('',#22270,#22275); +#22270 = CYLINDRICAL_SURFACE('',#22271,1.); +#22271 = AXIS2_PLACEMENT_3D('',#22272,#22273,#22274); +#22272 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#22273 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22274 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22275 = DEFINITIONAL_REPRESENTATION('',(#22276),#22279); +#22276 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22277,#22278),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#19885 = CARTESIAN_POINT('',(3.14159265359,-0.72)); -#19886 = CARTESIAN_POINT('',(6.28318530718,-0.72)); -#19887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19888 = ORIENTED_EDGE('',*,*,#19889,.F.); -#19889 = EDGE_CURVE('',#19741,#19840,#19890,.T.); -#19890 = SURFACE_CURVE('',#19891,(#19895,#19901),.PCURVE_S1.); -#19891 = LINE('',#19892,#19893); -#19892 = CARTESIAN_POINT('',(54.238908,21.775721,1.1)); -#19893 = VECTOR('',#19894,1.); -#19894 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#19895 = PCURVE('',#19756,#19896); -#19896 = DEFINITIONAL_REPRESENTATION('',(#19897),#19900); -#19897 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19898,#19899),.UNSPECIFIED., +#22277 = CARTESIAN_POINT('',(3.14159265359,-0.72)); +#22278 = CARTESIAN_POINT('',(6.28318530718,-0.72)); +#22279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22280 = ORIENTED_EDGE('',*,*,#22281,.F.); +#22281 = EDGE_CURVE('',#22133,#22232,#22282,.T.); +#22282 = SURFACE_CURVE('',#22283,(#22287,#22293),.PCURVE_S1.); +#22283 = LINE('',#22284,#22285); +#22284 = CARTESIAN_POINT('',(54.238908,21.775721,1.1)); +#22285 = VECTOR('',#22286,1.); +#22286 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#22287 = PCURVE('',#22148,#22288); +#22288 = DEFINITIONAL_REPRESENTATION('',(#22289),#22292); +#22289 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22290,#22291),.UNSPECIFIED., .F.,.F.,(2,2),(-9.899494936612E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#19898 = CARTESIAN_POINT('',(0.E+000,-7.E-002)); -#19899 = CARTESIAN_POINT('',(0.E+000,9.813077866774E-018)); -#19900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22290 = CARTESIAN_POINT('',(0.E+000,-7.E-002)); +#22291 = CARTESIAN_POINT('',(0.E+000,9.813077866774E-018)); +#22292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#19901 = PCURVE('',#19828,#19902); -#19902 = DEFINITIONAL_REPRESENTATION('',(#19903),#19906); -#19903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19904,#19905),.UNSPECIFIED., +#22293 = PCURVE('',#22220,#22294); +#22294 = DEFINITIONAL_REPRESENTATION('',(#22295),#22298); +#22295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22296,#22297),.UNSPECIFIED., .F.,.F.,(2,2),(-9.899494936612E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#19904 = CARTESIAN_POINT('',(6.28318530718,-7.E-002)); -#19905 = CARTESIAN_POINT('',(6.28318530718,9.813077866774E-018)); -#19906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19907 = ADVANCED_FACE('',(#19908),#19878,.T.); -#19908 = FACE_BOUND('',#19909,.T.); -#19909 = EDGE_LOOP('',(#19910,#19962,#19986,#19987)); -#19910 = ORIENTED_EDGE('',*,*,#19911,.T.); -#19911 = EDGE_CURVE('',#19912,#19914,#19916,.T.); -#19912 = VERTEX_POINT('',#19913); -#19913 = CARTESIAN_POINT('',(56.238908,21.315721,1.1)); -#19914 = VERTEX_POINT('',#19915); -#19915 = CARTESIAN_POINT('',(54.238908,21.315721,1.1)); -#19916 = SURFACE_CURVE('',#19917,(#19922,#19928),.PCURVE_S1.); -#19917 = CIRCLE('',#19918,1.); -#19918 = AXIS2_PLACEMENT_3D('',#19919,#19920,#19921); -#19919 = CARTESIAN_POINT('',(55.238908,21.315721,1.1)); -#19920 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19921 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19922 = PCURVE('',#19878,#19923); -#19923 = DEFINITIONAL_REPRESENTATION('',(#19924),#19927); -#19924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19925,#19926),.UNSPECIFIED., +#22296 = CARTESIAN_POINT('',(6.28318530718,-7.E-002)); +#22297 = CARTESIAN_POINT('',(6.28318530718,9.813077866774E-018)); +#22298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22299 = ADVANCED_FACE('',(#22300),#22270,.T.); +#22300 = FACE_BOUND('',#22301,.T.); +#22301 = EDGE_LOOP('',(#22302,#22354,#22378,#22379)); +#22302 = ORIENTED_EDGE('',*,*,#22303,.T.); +#22303 = EDGE_CURVE('',#22304,#22306,#22308,.T.); +#22304 = VERTEX_POINT('',#22305); +#22305 = CARTESIAN_POINT('',(56.238908,21.315721,1.1)); +#22306 = VERTEX_POINT('',#22307); +#22307 = CARTESIAN_POINT('',(54.238908,21.315721,1.1)); +#22308 = SURFACE_CURVE('',#22309,(#22314,#22320),.PCURVE_S1.); +#22309 = CIRCLE('',#22310,1.); +#22310 = AXIS2_PLACEMENT_3D('',#22311,#22312,#22313); +#22311 = CARTESIAN_POINT('',(55.238908,21.315721,1.1)); +#22312 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22313 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22314 = PCURVE('',#22270,#22315); +#22315 = DEFINITIONAL_REPRESENTATION('',(#22316),#22319); +#22316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22317,#22318),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#19925 = CARTESIAN_POINT('',(3.14159265359,-1.18)); -#19926 = CARTESIAN_POINT('',(6.28318530718,-1.18)); -#19927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19928 = PCURVE('',#19929,#19934); -#19929 = CONICAL_SURFACE('',#19930,0.93,0.785398163397); -#19930 = AXIS2_PLACEMENT_3D('',#19931,#19932,#19933); -#19931 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#19932 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19933 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19934 = DEFINITIONAL_REPRESENTATION('',(#19935),#19961); -#19935 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#19936,#19937,#19938,#19939, - #19940,#19941,#19942,#19943,#19944,#19945,#19946,#19947,#19948, - #19949,#19950,#19951,#19952,#19953,#19954,#19955,#19956,#19957, - #19958,#19959,#19960),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22317 = CARTESIAN_POINT('',(3.14159265359,-1.18)); +#22318 = CARTESIAN_POINT('',(6.28318530718,-1.18)); +#22319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22320 = PCURVE('',#22321,#22326); +#22321 = CONICAL_SURFACE('',#22322,0.93,0.785398163397); +#22322 = AXIS2_PLACEMENT_3D('',#22323,#22324,#22325); +#22323 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22324 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22325 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22326 = DEFINITIONAL_REPRESENTATION('',(#22327),#22353); +#22327 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22328,#22329,#22330,#22331, + #22332,#22333,#22334,#22335,#22336,#22337,#22338,#22339,#22340, + #22341,#22342,#22343,#22344,#22345,#22346,#22347,#22348,#22349, + #22350,#22351,#22352),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -24457,111 +27446,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#19936 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#19937 = CARTESIAN_POINT('',(3.189192542281,7.E-002)); -#19938 = CARTESIAN_POINT('',(3.284392319662,7.E-002)); -#19939 = CARTESIAN_POINT('',(3.427191985734,7.E-002)); -#19940 = CARTESIAN_POINT('',(3.569991651807,7.E-002)); -#19941 = CARTESIAN_POINT('',(3.712791317879,7.E-002)); -#19942 = CARTESIAN_POINT('',(3.855590983951,7.E-002)); -#19943 = CARTESIAN_POINT('',(3.998390650023,7.E-002)); -#19944 = CARTESIAN_POINT('',(4.141190316096,7.E-002)); -#19945 = CARTESIAN_POINT('',(4.283989982168,7.E-002)); -#19946 = CARTESIAN_POINT('',(4.42678964824,7.E-002)); -#19947 = CARTESIAN_POINT('',(4.569589314312,7.E-002)); -#19948 = CARTESIAN_POINT('',(4.712388980385,7.E-002)); -#19949 = CARTESIAN_POINT('',(4.855188646457,7.E-002)); -#19950 = CARTESIAN_POINT('',(4.997988312529,7.E-002)); -#19951 = CARTESIAN_POINT('',(5.140787978601,7.E-002)); -#19952 = CARTESIAN_POINT('',(5.283587644674,7.E-002)); -#19953 = CARTESIAN_POINT('',(5.426387310746,7.E-002)); -#19954 = CARTESIAN_POINT('',(5.569186976818,7.E-002)); -#19955 = CARTESIAN_POINT('',(5.711986642891,7.E-002)); -#19956 = CARTESIAN_POINT('',(5.854786308963,7.E-002)); -#19957 = CARTESIAN_POINT('',(5.997585975035,7.E-002)); -#19958 = CARTESIAN_POINT('',(6.140385641107,7.E-002)); -#19959 = CARTESIAN_POINT('',(6.235585418489,7.E-002)); -#19960 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); -#19961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19962 = ORIENTED_EDGE('',*,*,#19963,.T.); -#19963 = EDGE_CURVE('',#19914,#19840,#19964,.T.); -#19964 = SURFACE_CURVE('',#19965,(#19969,#19975),.PCURVE_S1.); -#19965 = LINE('',#19966,#19967); -#19966 = CARTESIAN_POINT('',(54.238908,22.495721,1.1)); -#19967 = VECTOR('',#19968,1.); -#19968 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19969 = PCURVE('',#19878,#19970); -#19970 = DEFINITIONAL_REPRESENTATION('',(#19971),#19974); -#19971 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19972,#19973),.UNSPECIFIED., +#22328 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#22329 = CARTESIAN_POINT('',(3.189192542281,7.E-002)); +#22330 = CARTESIAN_POINT('',(3.284392319662,7.E-002)); +#22331 = CARTESIAN_POINT('',(3.427191985734,7.E-002)); +#22332 = CARTESIAN_POINT('',(3.569991651807,7.E-002)); +#22333 = CARTESIAN_POINT('',(3.712791317879,7.E-002)); +#22334 = CARTESIAN_POINT('',(3.855590983951,7.E-002)); +#22335 = CARTESIAN_POINT('',(3.998390650023,7.E-002)); +#22336 = CARTESIAN_POINT('',(4.141190316096,7.E-002)); +#22337 = CARTESIAN_POINT('',(4.283989982168,7.E-002)); +#22338 = CARTESIAN_POINT('',(4.42678964824,7.E-002)); +#22339 = CARTESIAN_POINT('',(4.569589314312,7.E-002)); +#22340 = CARTESIAN_POINT('',(4.712388980385,7.E-002)); +#22341 = CARTESIAN_POINT('',(4.855188646457,7.E-002)); +#22342 = CARTESIAN_POINT('',(4.997988312529,7.E-002)); +#22343 = CARTESIAN_POINT('',(5.140787978601,7.E-002)); +#22344 = CARTESIAN_POINT('',(5.283587644674,7.E-002)); +#22345 = CARTESIAN_POINT('',(5.426387310746,7.E-002)); +#22346 = CARTESIAN_POINT('',(5.569186976818,7.E-002)); +#22347 = CARTESIAN_POINT('',(5.711986642891,7.E-002)); +#22348 = CARTESIAN_POINT('',(5.854786308963,7.E-002)); +#22349 = CARTESIAN_POINT('',(5.997585975035,7.E-002)); +#22350 = CARTESIAN_POINT('',(6.140385641107,7.E-002)); +#22351 = CARTESIAN_POINT('',(6.235585418489,7.E-002)); +#22352 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); +#22353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22354 = ORIENTED_EDGE('',*,*,#22355,.T.); +#22355 = EDGE_CURVE('',#22306,#22232,#22356,.T.); +#22356 = SURFACE_CURVE('',#22357,(#22361,#22367),.PCURVE_S1.); +#22357 = LINE('',#22358,#22359); +#22358 = CARTESIAN_POINT('',(54.238908,22.495721,1.1)); +#22359 = VECTOR('',#22360,1.); +#22360 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22361 = PCURVE('',#22270,#22362); +#22362 = DEFINITIONAL_REPRESENTATION('',(#22363),#22366); +#22363 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22364,#22365),.UNSPECIFIED., .F.,.F.,(2,2),(-1.18,-0.72),.PIECEWISE_BEZIER_KNOTS.); -#19972 = CARTESIAN_POINT('',(6.28318530718,-1.18)); -#19973 = CARTESIAN_POINT('',(6.28318530718,-0.72)); -#19974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19975 = PCURVE('',#19976,#19981); -#19976 = CYLINDRICAL_SURFACE('',#19977,1.); -#19977 = AXIS2_PLACEMENT_3D('',#19978,#19979,#19980); -#19978 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#19979 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19980 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#19981 = DEFINITIONAL_REPRESENTATION('',(#19982),#19985); -#19982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19983,#19984),.UNSPECIFIED., +#22364 = CARTESIAN_POINT('',(6.28318530718,-1.18)); +#22365 = CARTESIAN_POINT('',(6.28318530718,-0.72)); +#22366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22367 = PCURVE('',#22368,#22373); +#22368 = CYLINDRICAL_SURFACE('',#22369,1.); +#22369 = AXIS2_PLACEMENT_3D('',#22370,#22371,#22372); +#22370 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#22371 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22372 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22373 = DEFINITIONAL_REPRESENTATION('',(#22374),#22377); +#22374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22375,#22376),.UNSPECIFIED., .F.,.F.,(2,2),(-1.18,-0.72),.PIECEWISE_BEZIER_KNOTS.); -#19983 = CARTESIAN_POINT('',(0.E+000,-1.18)); -#19984 = CARTESIAN_POINT('',(0.E+000,-0.72)); -#19985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#19986 = ORIENTED_EDGE('',*,*,#19839,.F.); -#19987 = ORIENTED_EDGE('',*,*,#19988,.F.); -#19988 = EDGE_CURVE('',#19912,#19814,#19989,.T.); -#19989 = SURFACE_CURVE('',#19990,(#19994,#20000),.PCURVE_S1.); -#19990 = LINE('',#19991,#19992); -#19991 = CARTESIAN_POINT('',(56.238908,22.495721,1.1)); -#19992 = VECTOR('',#19993,1.); -#19993 = DIRECTION('',(0.E+000,1.,0.E+000)); -#19994 = PCURVE('',#19878,#19995); -#19995 = DEFINITIONAL_REPRESENTATION('',(#19996),#19999); -#19996 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#19997,#19998),.UNSPECIFIED., +#22375 = CARTESIAN_POINT('',(0.E+000,-1.18)); +#22376 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#22377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22378 = ORIENTED_EDGE('',*,*,#22231,.F.); +#22379 = ORIENTED_EDGE('',*,*,#22380,.F.); +#22380 = EDGE_CURVE('',#22304,#22206,#22381,.T.); +#22381 = SURFACE_CURVE('',#22382,(#22386,#22392),.PCURVE_S1.); +#22382 = LINE('',#22383,#22384); +#22383 = CARTESIAN_POINT('',(56.238908,22.495721,1.1)); +#22384 = VECTOR('',#22385,1.); +#22385 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22386 = PCURVE('',#22270,#22387); +#22387 = DEFINITIONAL_REPRESENTATION('',(#22388),#22391); +#22388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22389,#22390),.UNSPECIFIED., .F.,.F.,(2,2),(-1.18,-0.72),.PIECEWISE_BEZIER_KNOTS.); -#19997 = CARTESIAN_POINT('',(3.14159265359,-1.18)); -#19998 = CARTESIAN_POINT('',(3.14159265359,-0.72)); -#19999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22389 = CARTESIAN_POINT('',(3.14159265359,-1.18)); +#22390 = CARTESIAN_POINT('',(3.14159265359,-0.72)); +#22391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20000 = PCURVE('',#19976,#20001); -#20001 = DEFINITIONAL_REPRESENTATION('',(#20002),#20005); -#20002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20003,#20004),.UNSPECIFIED., +#22392 = PCURVE('',#22368,#22393); +#22393 = DEFINITIONAL_REPRESENTATION('',(#22394),#22397); +#22394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22395,#22396),.UNSPECIFIED., .F.,.F.,(2,2),(-1.18,-0.72),.PIECEWISE_BEZIER_KNOTS.); -#20003 = CARTESIAN_POINT('',(3.14159265359,-1.18)); -#20004 = CARTESIAN_POINT('',(3.14159265359,-0.72)); -#20005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20006 = ADVANCED_FACE('',(#20007),#19929,.T.); -#20007 = FACE_BOUND('',#20008,.T.); -#20008 = EDGE_LOOP('',(#20009,#20062,#20086,#20087)); -#20009 = ORIENTED_EDGE('',*,*,#20010,.T.); -#20010 = EDGE_CURVE('',#20011,#20013,#20015,.T.); -#20011 = VERTEX_POINT('',#20012); -#20012 = CARTESIAN_POINT('',(56.168908,21.245721,1.1)); -#20013 = VERTEX_POINT('',#20014); -#20014 = CARTESIAN_POINT('',(54.308908,21.245721,1.1)); -#20015 = SURFACE_CURVE('',#20016,(#20021,#20050),.PCURVE_S1.); -#20016 = CIRCLE('',#20017,0.93); -#20017 = AXIS2_PLACEMENT_3D('',#20018,#20019,#20020); -#20018 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20019 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20020 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20021 = PCURVE('',#19929,#20022); -#20022 = DEFINITIONAL_REPRESENTATION('',(#20023),#20049); -#20023 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#20024,#20025,#20026,#20027, - #20028,#20029,#20030,#20031,#20032,#20033,#20034,#20035,#20036, - #20037,#20038,#20039,#20040,#20041,#20042,#20043,#20044,#20045, - #20046,#20047,#20048),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22395 = CARTESIAN_POINT('',(3.14159265359,-1.18)); +#22396 = CARTESIAN_POINT('',(3.14159265359,-0.72)); +#22397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22398 = ADVANCED_FACE('',(#22399),#22321,.T.); +#22399 = FACE_BOUND('',#22400,.T.); +#22400 = EDGE_LOOP('',(#22401,#22454,#22478,#22479)); +#22401 = ORIENTED_EDGE('',*,*,#22402,.T.); +#22402 = EDGE_CURVE('',#22403,#22405,#22407,.T.); +#22403 = VERTEX_POINT('',#22404); +#22404 = CARTESIAN_POINT('',(56.168908,21.245721,1.1)); +#22405 = VERTEX_POINT('',#22406); +#22406 = CARTESIAN_POINT('',(54.308908,21.245721,1.1)); +#22407 = SURFACE_CURVE('',#22408,(#22413,#22442),.PCURVE_S1.); +#22408 = CIRCLE('',#22409,0.93); +#22409 = AXIS2_PLACEMENT_3D('',#22410,#22411,#22412); +#22410 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22411 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22412 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22413 = PCURVE('',#22321,#22414); +#22414 = DEFINITIONAL_REPRESENTATION('',(#22415),#22441); +#22415 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22416,#22417,#22418,#22419, + #22420,#22421,#22422,#22423,#22424,#22425,#22426,#22427,#22428, + #22429,#22430,#22431,#22432,#22433,#22434,#22435,#22436,#22437, + #22438,#22439,#22440),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -24569,132 +27558,132 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#20024 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#20025 = CARTESIAN_POINT('',(3.189192542281,9.217540528111E-016)); -#20026 = CARTESIAN_POINT('',(3.284392319662,1.391846012591E-015)); -#20027 = CARTESIAN_POINT('',(3.427191985734,-5.44466642543E-016)); -#20028 = CARTESIAN_POINT('',(3.569991651807,-1.714095442062E-015)); -#20029 = CARTESIAN_POINT('',(3.712791317879,-1.964381534921E-015)); -#20030 = CARTESIAN_POINT('',(3.855590983951,1.948162426132E-015)); -#20031 = CARTESIAN_POINT('',(3.998390650023,-7.228143494822E-016)); -#20032 = CARTESIAN_POINT('',(4.141190316096,-3.61688132681E-016)); -#20033 = CARTESIAN_POINT('',(4.283989982168,9.511404787669E-016)); -#20034 = CARTESIAN_POINT('',(4.42678964824,-7.609370784178E-016)); -#20035 = CARTESIAN_POINT('',(4.569589314312,-2.346321283359E-016)); -#20036 = CARTESIAN_POINT('',(4.712388980385,1.003215974538E-016)); -#20037 = CARTESIAN_POINT('',(4.855188646457,-1.666542614792E-016)); -#20038 = CARTESIAN_POINT('',(4.997988312529,-7.031968753003E-016)); -#20039 = CARTESIAN_POINT('',(5.140787978601,9.716077594545E-016)); -#20040 = CARTESIAN_POINT('',(5.283587644674,-1.98317161448E-016)); -#20041 = CARTESIAN_POINT('',(5.426387310746,-8.365040424699E-016)); -#20042 = CARTESIAN_POINT('',(5.569186976818,1.987961112725E-015)); -#20043 = CARTESIAN_POINT('',(5.711986642891,-2.009886588303E-015)); -#20044 = CARTESIAN_POINT('',(5.854786308963,-1.751743055543E-015)); -#20045 = CARTESIAN_POINT('',(5.997585975035,-4.866069122285E-016)); -#20046 = CARTESIAN_POINT('',(6.140385641107,1.385892731197E-015)); -#20047 = CARTESIAN_POINT('',(6.235585418489,9.920479994969E-016)); -#20048 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#20049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20050 = PCURVE('',#20051,#20056); -#20051 = PLANE('',#20052); -#20052 = AXIS2_PLACEMENT_3D('',#20053,#20054,#20055); -#20053 = CARTESIAN_POINT('',(50.919956733961,21.245721,0.899011437739)); -#20054 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20055 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20056 = DEFINITIONAL_REPRESENTATION('',(#20057),#20061); -#20057 = CIRCLE('',#20058,0.93); -#20058 = AXIS2_PLACEMENT_2D('',#20059,#20060); -#20059 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20060 = DIRECTION('',(1.,0.E+000)); -#20061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20062 = ORIENTED_EDGE('',*,*,#20063,.T.); -#20063 = EDGE_CURVE('',#20013,#19914,#20064,.T.); -#20064 = SURFACE_CURVE('',#20065,(#20069,#20075),.PCURVE_S1.); -#20065 = LINE('',#20066,#20067); -#20066 = CARTESIAN_POINT('',(54.308908,21.245721,1.1)); -#20067 = VECTOR('',#20068,1.); -#20068 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#20069 = PCURVE('',#19929,#20070); -#20070 = DEFINITIONAL_REPRESENTATION('',(#20071),#20074); -#20071 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20072,#20073),.UNSPECIFIED., +#22416 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22417 = CARTESIAN_POINT('',(3.189192542281,9.217540528111E-016)); +#22418 = CARTESIAN_POINT('',(3.284392319662,1.391846012591E-015)); +#22419 = CARTESIAN_POINT('',(3.427191985734,-5.44466642543E-016)); +#22420 = CARTESIAN_POINT('',(3.569991651807,-1.714095442062E-015)); +#22421 = CARTESIAN_POINT('',(3.712791317879,-1.964381534921E-015)); +#22422 = CARTESIAN_POINT('',(3.855590983951,1.948162426132E-015)); +#22423 = CARTESIAN_POINT('',(3.998390650023,-7.228143494822E-016)); +#22424 = CARTESIAN_POINT('',(4.141190316096,-3.61688132681E-016)); +#22425 = CARTESIAN_POINT('',(4.283989982168,9.511404787669E-016)); +#22426 = CARTESIAN_POINT('',(4.42678964824,-7.609370784178E-016)); +#22427 = CARTESIAN_POINT('',(4.569589314312,-2.346321283359E-016)); +#22428 = CARTESIAN_POINT('',(4.712388980385,1.003215974538E-016)); +#22429 = CARTESIAN_POINT('',(4.855188646457,-1.666542614792E-016)); +#22430 = CARTESIAN_POINT('',(4.997988312529,-7.031968753003E-016)); +#22431 = CARTESIAN_POINT('',(5.140787978601,9.716077594545E-016)); +#22432 = CARTESIAN_POINT('',(5.283587644674,-1.98317161448E-016)); +#22433 = CARTESIAN_POINT('',(5.426387310746,-8.365040424699E-016)); +#22434 = CARTESIAN_POINT('',(5.569186976818,1.987961112725E-015)); +#22435 = CARTESIAN_POINT('',(5.711986642891,-2.009886588303E-015)); +#22436 = CARTESIAN_POINT('',(5.854786308963,-1.751743055543E-015)); +#22437 = CARTESIAN_POINT('',(5.997585975035,-4.866069122285E-016)); +#22438 = CARTESIAN_POINT('',(6.140385641107,1.385892731197E-015)); +#22439 = CARTESIAN_POINT('',(6.235585418489,9.920479994969E-016)); +#22440 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#22441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22442 = PCURVE('',#22443,#22448); +#22443 = PLANE('',#22444); +#22444 = AXIS2_PLACEMENT_3D('',#22445,#22446,#22447); +#22445 = CARTESIAN_POINT('',(50.919956733961,21.245721,0.899011437739)); +#22446 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22447 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22448 = DEFINITIONAL_REPRESENTATION('',(#22449),#22453); +#22449 = CIRCLE('',#22450,0.93); +#22450 = AXIS2_PLACEMENT_2D('',#22451,#22452); +#22451 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#22452 = DIRECTION('',(1.,0.E+000)); +#22453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22454 = ORIENTED_EDGE('',*,*,#22455,.T.); +#22455 = EDGE_CURVE('',#22405,#22306,#22456,.T.); +#22456 = SURFACE_CURVE('',#22457,(#22461,#22467),.PCURVE_S1.); +#22457 = LINE('',#22458,#22459); +#22458 = CARTESIAN_POINT('',(54.308908,21.245721,1.1)); +#22459 = VECTOR('',#22460,1.); +#22460 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#22461 = PCURVE('',#22321,#22462); +#22462 = DEFINITIONAL_REPRESENTATION('',(#22463),#22466); +#22463 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22464,#22465),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#20072 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#20073 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); -#20074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20075 = PCURVE('',#20076,#20081); -#20076 = CONICAL_SURFACE('',#20077,0.93,0.785398163397); -#20077 = AXIS2_PLACEMENT_3D('',#20078,#20079,#20080); -#20078 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20079 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20080 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20081 = DEFINITIONAL_REPRESENTATION('',(#20082),#20085); -#20082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20083,#20084),.UNSPECIFIED., +#22464 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#22465 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); +#22466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22467 = PCURVE('',#22468,#22473); +#22468 = CONICAL_SURFACE('',#22469,0.93,0.785398163397); +#22469 = AXIS2_PLACEMENT_3D('',#22470,#22471,#22472); +#22470 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22471 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22472 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22473 = DEFINITIONAL_REPRESENTATION('',(#22474),#22477); +#22474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22475,#22476),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#20083 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20084 = CARTESIAN_POINT('',(0.E+000,7.E-002)); -#20085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20086 = ORIENTED_EDGE('',*,*,#19911,.F.); -#20087 = ORIENTED_EDGE('',*,*,#20088,.F.); -#20088 = EDGE_CURVE('',#20011,#19912,#20089,.T.); -#20089 = SURFACE_CURVE('',#20090,(#20094,#20100),.PCURVE_S1.); -#20090 = LINE('',#20091,#20092); -#20091 = CARTESIAN_POINT('',(56.168908,21.245721,1.1)); -#20092 = VECTOR('',#20093,1.); -#20093 = DIRECTION('',(0.707106781187,0.707106781187,1.68827146095E-016) - ); -#20094 = PCURVE('',#19929,#20095); -#20095 = DEFINITIONAL_REPRESENTATION('',(#20096),#20099); -#20096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20097,#20098),.UNSPECIFIED., +#22475 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22476 = CARTESIAN_POINT('',(0.E+000,7.E-002)); +#22477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22478 = ORIENTED_EDGE('',*,*,#22303,.F.); +#22479 = ORIENTED_EDGE('',*,*,#22480,.F.); +#22480 = EDGE_CURVE('',#22403,#22304,#22481,.T.); +#22481 = SURFACE_CURVE('',#22482,(#22486,#22492),.PCURVE_S1.); +#22482 = LINE('',#22483,#22484); +#22483 = CARTESIAN_POINT('',(56.168908,21.245721,1.1)); +#22484 = VECTOR('',#22485,1.); +#22485 = DIRECTION('',(0.707106781187,0.707106781187,1.68827146095E-016) + ); +#22486 = PCURVE('',#22321,#22487); +#22487 = DEFINITIONAL_REPRESENTATION('',(#22488),#22491); +#22488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22489,#22490),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#20097 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#20098 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#20099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22489 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22490 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#22491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20100 = PCURVE('',#20076,#20101); -#20101 = DEFINITIONAL_REPRESENTATION('',(#20102),#20105); -#20102 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20103,#20104),.UNSPECIFIED., +#22492 = PCURVE('',#22468,#22493); +#22493 = DEFINITIONAL_REPRESENTATION('',(#22494),#22497); +#22494 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22495,#22496),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,9.899494936612E-002),.PIECEWISE_BEZIER_KNOTS.); -#20103 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#20104 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#20105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20106 = ADVANCED_FACE('',(#20107,#20154),#20051,.F.); -#20107 = FACE_BOUND('',#20108,.T.); -#20108 = EDGE_LOOP('',(#20109,#20110)); -#20109 = ORIENTED_EDGE('',*,*,#20010,.F.); -#20110 = ORIENTED_EDGE('',*,*,#20111,.F.); -#20111 = EDGE_CURVE('',#20013,#20011,#20112,.T.); -#20112 = SURFACE_CURVE('',#20113,(#20118,#20125),.PCURVE_S1.); -#20113 = CIRCLE('',#20114,0.93); -#20114 = AXIS2_PLACEMENT_3D('',#20115,#20116,#20117); -#20115 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20116 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20117 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20118 = PCURVE('',#20051,#20119); -#20119 = DEFINITIONAL_REPRESENTATION('',(#20120),#20124); -#20120 = CIRCLE('',#20121,0.93); -#20121 = AXIS2_PLACEMENT_2D('',#20122,#20123); -#20122 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20123 = DIRECTION('',(1.,0.E+000)); -#20124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20125 = PCURVE('',#20076,#20126); -#20126 = DEFINITIONAL_REPRESENTATION('',(#20127),#20153); -#20127 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#20128,#20129,#20130,#20131, - #20132,#20133,#20134,#20135,#20136,#20137,#20138,#20139,#20140, - #20141,#20142,#20143,#20144,#20145,#20146,#20147,#20148,#20149, - #20150,#20151,#20152),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#22495 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22496 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#22497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22498 = ADVANCED_FACE('',(#22499,#22546),#22443,.F.); +#22499 = FACE_BOUND('',#22500,.T.); +#22500 = EDGE_LOOP('',(#22501,#22502)); +#22501 = ORIENTED_EDGE('',*,*,#22402,.F.); +#22502 = ORIENTED_EDGE('',*,*,#22503,.F.); +#22503 = EDGE_CURVE('',#22405,#22403,#22504,.T.); +#22504 = SURFACE_CURVE('',#22505,(#22510,#22517),.PCURVE_S1.); +#22505 = CIRCLE('',#22506,0.93); +#22506 = AXIS2_PLACEMENT_3D('',#22507,#22508,#22509); +#22507 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22508 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22509 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22510 = PCURVE('',#22443,#22511); +#22511 = DEFINITIONAL_REPRESENTATION('',(#22512),#22516); +#22512 = CIRCLE('',#22513,0.93); +#22513 = AXIS2_PLACEMENT_2D('',#22514,#22515); +#22514 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#22515 = DIRECTION('',(1.,0.E+000)); +#22516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22517 = PCURVE('',#22468,#22518); +#22518 = DEFINITIONAL_REPRESENTATION('',(#22519),#22545); +#22519 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#22520,#22521,#22522,#22523, + #22524,#22525,#22526,#22527,#22528,#22529,#22530,#22531,#22532, + #22533,#22534,#22535,#22536,#22537,#22538,#22539,#22540,#22541, + #22542,#22543,#22544),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -24702,892 +27691,892 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#20128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20129 = CARTESIAN_POINT('',(4.759988869075E-002,9.76245752833E-016)); -#20130 = CARTESIAN_POINT('',(0.142799666072,1.363288249944E-015)); -#20131 = CARTESIAN_POINT('',(0.285599332145,-4.786013378299E-016)); -#20132 = CARTESIAN_POINT('',(0.428398998217,-1.761160871884E-015)); -#20133 = CARTESIAN_POINT('',(0.571198664289,-1.980220897338E-015)); -#20134 = CARTESIAN_POINT('',(0.713998330361,2.058747935946E-015)); -#20135 = CARTESIAN_POINT('',(0.856797996434,-7.129798620028E-016)); -#20136 = CARTESIAN_POINT('',(0.999597662506,-5.114489620861E-016)); -#20137 = CARTESIAN_POINT('',(1.142397328578,9.797625756245E-016)); -#20138 = CARTESIAN_POINT('',(1.28519699465,-7.256646364429E-016)); -#20139 = CARTESIAN_POINT('',(1.427996660723,-8.493803307859E-017)); -#20140 = CARTESIAN_POINT('',(1.570796326795,1.257387458641E-016)); -#20141 = CARTESIAN_POINT('',(1.713595992867,-8.495004299031E-017)); -#20142 = CARTESIAN_POINT('',(1.856395658939,-7.257792271219E-016)); -#20143 = CARTESIAN_POINT('',(1.999195325012,9.802329482521E-016)); -#20144 = CARTESIAN_POINT('',(2.141994991084,-5.133784922436E-016)); -#20145 = CARTESIAN_POINT('',(2.284794657156,-7.055694836745E-016)); -#20146 = CARTESIAN_POINT('',(2.427594323228,2.03103595279E-015)); -#20147 = CARTESIAN_POINT('',(2.570393989301,-1.876783343043E-015)); -#20148 = CARTESIAN_POINT('',(2.713193655373,-1.786972934098E-015)); -#20149 = CARTESIAN_POINT('',(2.855993321445,-4.791159039207E-016)); -#20150 = CARTESIAN_POINT('',(2.998792987518,1.391158576521E-015)); -#20151 = CARTESIAN_POINT('',(3.093992764899,9.114496146634E-016)); -#20152 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#20153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22520 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22521 = CARTESIAN_POINT('',(4.759988869075E-002,9.76245752833E-016)); +#22522 = CARTESIAN_POINT('',(0.142799666072,1.363288249944E-015)); +#22523 = CARTESIAN_POINT('',(0.285599332145,-4.786013378299E-016)); +#22524 = CARTESIAN_POINT('',(0.428398998217,-1.761160871884E-015)); +#22525 = CARTESIAN_POINT('',(0.571198664289,-1.980220897338E-015)); +#22526 = CARTESIAN_POINT('',(0.713998330361,2.058747935946E-015)); +#22527 = CARTESIAN_POINT('',(0.856797996434,-7.129798620028E-016)); +#22528 = CARTESIAN_POINT('',(0.999597662506,-5.114489620861E-016)); +#22529 = CARTESIAN_POINT('',(1.142397328578,9.797625756245E-016)); +#22530 = CARTESIAN_POINT('',(1.28519699465,-7.256646364429E-016)); +#22531 = CARTESIAN_POINT('',(1.427996660723,-8.493803307859E-017)); +#22532 = CARTESIAN_POINT('',(1.570796326795,1.257387458641E-016)); +#22533 = CARTESIAN_POINT('',(1.713595992867,-8.495004299031E-017)); +#22534 = CARTESIAN_POINT('',(1.856395658939,-7.257792271219E-016)); +#22535 = CARTESIAN_POINT('',(1.999195325012,9.802329482521E-016)); +#22536 = CARTESIAN_POINT('',(2.141994991084,-5.133784922436E-016)); +#22537 = CARTESIAN_POINT('',(2.284794657156,-7.055694836745E-016)); +#22538 = CARTESIAN_POINT('',(2.427594323228,2.03103595279E-015)); +#22539 = CARTESIAN_POINT('',(2.570393989301,-1.876783343043E-015)); +#22540 = CARTESIAN_POINT('',(2.713193655373,-1.786972934098E-015)); +#22541 = CARTESIAN_POINT('',(2.855993321445,-4.791159039207E-016)); +#22542 = CARTESIAN_POINT('',(2.998792987518,1.391158576521E-015)); +#22543 = CARTESIAN_POINT('',(3.093992764899,9.114496146634E-016)); +#22544 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#22545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20154 = FACE_BOUND('',#20155,.T.); -#20155 = EDGE_LOOP('',(#20156,#20181)); -#20156 = ORIENTED_EDGE('',*,*,#20157,.T.); -#20157 = EDGE_CURVE('',#20158,#20160,#20162,.T.); -#20158 = VERTEX_POINT('',#20159); -#20159 = CARTESIAN_POINT('',(56.088908,21.245721,1.1)); -#20160 = VERTEX_POINT('',#20161); -#20161 = CARTESIAN_POINT('',(54.388908,21.245721,1.1)); -#20162 = SURFACE_CURVE('',#20163,(#20168,#20175),.PCURVE_S1.); -#20163 = CIRCLE('',#20164,0.85); -#20164 = AXIS2_PLACEMENT_3D('',#20165,#20166,#20167); -#20165 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20166 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20167 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20168 = PCURVE('',#20051,#20169); -#20169 = DEFINITIONAL_REPRESENTATION('',(#20170),#20174); -#20170 = CIRCLE('',#20171,0.85); -#20171 = AXIS2_PLACEMENT_2D('',#20172,#20173); -#20172 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20173 = DIRECTION('',(1.,0.E+000)); -#20174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20175 = PCURVE('',#19402,#20176); -#20176 = DEFINITIONAL_REPRESENTATION('',(#20177),#20180); -#20177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20178,#20179),.UNSPECIFIED., +#22546 = FACE_BOUND('',#22547,.T.); +#22547 = EDGE_LOOP('',(#22548,#22573)); +#22548 = ORIENTED_EDGE('',*,*,#22549,.T.); +#22549 = EDGE_CURVE('',#22550,#22552,#22554,.T.); +#22550 = VERTEX_POINT('',#22551); +#22551 = CARTESIAN_POINT('',(56.088908,21.245721,1.1)); +#22552 = VERTEX_POINT('',#22553); +#22553 = CARTESIAN_POINT('',(54.388908,21.245721,1.1)); +#22554 = SURFACE_CURVE('',#22555,(#22560,#22567),.PCURVE_S1.); +#22555 = CIRCLE('',#22556,0.85); +#22556 = AXIS2_PLACEMENT_3D('',#22557,#22558,#22559); +#22557 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22558 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22559 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22560 = PCURVE('',#22443,#22561); +#22561 = DEFINITIONAL_REPRESENTATION('',(#22562),#22566); +#22562 = CIRCLE('',#22563,0.85); +#22563 = AXIS2_PLACEMENT_2D('',#22564,#22565); +#22564 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#22565 = DIRECTION('',(1.,0.E+000)); +#22566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22567 = PCURVE('',#21794,#22568); +#22568 = DEFINITIONAL_REPRESENTATION('',(#22569),#22572); +#22569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22570,#22571),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#20178 = CARTESIAN_POINT('',(3.14159265359,-1.25)); -#20179 = CARTESIAN_POINT('',(6.28318530718,-1.25)); -#20180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20181 = ORIENTED_EDGE('',*,*,#20182,.T.); -#20182 = EDGE_CURVE('',#20160,#20158,#20183,.T.); -#20183 = SURFACE_CURVE('',#20184,(#20189,#20196),.PCURVE_S1.); -#20184 = CIRCLE('',#20185,0.85); -#20185 = AXIS2_PLACEMENT_3D('',#20186,#20187,#20188); -#20186 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20187 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20188 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20189 = PCURVE('',#20051,#20190); -#20190 = DEFINITIONAL_REPRESENTATION('',(#20191),#20195); -#20191 = CIRCLE('',#20192,0.85); -#20192 = AXIS2_PLACEMENT_2D('',#20193,#20194); -#20193 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20194 = DIRECTION('',(1.,0.E+000)); -#20195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20196 = PCURVE('',#18547,#20197); -#20197 = DEFINITIONAL_REPRESENTATION('',(#20198),#20201); -#20198 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20199,#20200),.UNSPECIFIED., +#22570 = CARTESIAN_POINT('',(3.14159265359,-1.25)); +#22571 = CARTESIAN_POINT('',(6.28318530718,-1.25)); +#22572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22573 = ORIENTED_EDGE('',*,*,#22574,.T.); +#22574 = EDGE_CURVE('',#22552,#22550,#22575,.T.); +#22575 = SURFACE_CURVE('',#22576,(#22581,#22588),.PCURVE_S1.); +#22576 = CIRCLE('',#22577,0.85); +#22577 = AXIS2_PLACEMENT_3D('',#22578,#22579,#22580); +#22578 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22579 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22580 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22581 = PCURVE('',#22443,#22582); +#22582 = DEFINITIONAL_REPRESENTATION('',(#22583),#22587); +#22583 = CIRCLE('',#22584,0.85); +#22584 = AXIS2_PLACEMENT_2D('',#22585,#22586); +#22585 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#22586 = DIRECTION('',(1.,0.E+000)); +#22587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22588 = PCURVE('',#20939,#22589); +#22589 = DEFINITIONAL_REPRESENTATION('',(#22590),#22593); +#22590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22591,#22592),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#20199 = CARTESIAN_POINT('',(0.E+000,-1.25)); -#20200 = CARTESIAN_POINT('',(3.14159265359,-1.25)); -#20201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20202 = ADVANCED_FACE('',(#20203),#19402,.F.); -#20203 = FACE_BOUND('',#20204,.F.); -#20204 = EDGE_LOOP('',(#20205,#20227,#20228,#20250,#20278,#20297,#20298, - #20319)); -#20205 = ORIENTED_EDGE('',*,*,#20206,.T.); -#20206 = EDGE_CURVE('',#20207,#19381,#20209,.T.); -#20207 = VERTEX_POINT('',#20208); -#20208 = CARTESIAN_POINT('',(54.464311330758,22.045721,0.75)); -#20209 = SURFACE_CURVE('',#20210,(#20214,#20220),.PCURVE_S1.); -#20210 = LINE('',#20211,#20212); -#20211 = CARTESIAN_POINT('',(54.464311330758,22.495721,0.75)); -#20212 = VECTOR('',#20213,1.); -#20213 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20214 = PCURVE('',#19402,#20215); -#20215 = DEFINITIONAL_REPRESENTATION('',(#20216),#20219); -#20216 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20217,#20218),.UNSPECIFIED., +#22591 = CARTESIAN_POINT('',(0.E+000,-1.25)); +#22592 = CARTESIAN_POINT('',(3.14159265359,-1.25)); +#22593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22594 = ADVANCED_FACE('',(#22595),#21794,.F.); +#22595 = FACE_BOUND('',#22596,.F.); +#22596 = EDGE_LOOP('',(#22597,#22619,#22620,#22642,#22670,#22689,#22690, + #22711)); +#22597 = ORIENTED_EDGE('',*,*,#22598,.T.); +#22598 = EDGE_CURVE('',#22599,#21773,#22601,.T.); +#22599 = VERTEX_POINT('',#22600); +#22600 = CARTESIAN_POINT('',(54.464311330758,22.045721,0.75)); +#22601 = SURFACE_CURVE('',#22602,(#22606,#22612),.PCURVE_S1.); +#22602 = LINE('',#22603,#22604); +#22603 = CARTESIAN_POINT('',(54.464311330758,22.495721,0.75)); +#22604 = VECTOR('',#22605,1.); +#22605 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22606 = PCURVE('',#21794,#22607); +#22607 = DEFINITIONAL_REPRESENTATION('',(#22608),#22611); +#22608 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22609,#22610),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#20217 = CARTESIAN_POINT('',(5.858795598586,-0.45)); -#20218 = CARTESIAN_POINT('',(5.858795598586,-0.35)); -#20219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20220 = PCURVE('',#19483,#20221); -#20221 = DEFINITIONAL_REPRESENTATION('',(#20222),#20226); -#20222 = LINE('',#20223,#20224); -#20223 = CARTESIAN_POINT('',(-0.35033260053,-0.35)); -#20224 = VECTOR('',#20225,1.); -#20225 = DIRECTION('',(0.E+000,-1.)); -#20226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20227 = ORIENTED_EDGE('',*,*,#19378,.F.); -#20228 = ORIENTED_EDGE('',*,*,#20229,.F.); -#20229 = EDGE_CURVE('',#20230,#19379,#20232,.T.); -#20230 = VERTEX_POINT('',#20231); -#20231 = CARTESIAN_POINT('',(56.013504669241,22.045721,0.75)); -#20232 = SURFACE_CURVE('',#20233,(#20237,#20243),.PCURVE_S1.); -#20233 = LINE('',#20234,#20235); -#20234 = CARTESIAN_POINT('',(56.013504669241,22.495721,0.75)); -#20235 = VECTOR('',#20236,1.); -#20236 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20237 = PCURVE('',#19402,#20238); -#20238 = DEFINITIONAL_REPRESENTATION('',(#20239),#20242); -#20239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20240,#20241),.UNSPECIFIED., +#22609 = CARTESIAN_POINT('',(5.858795598586,-0.45)); +#22610 = CARTESIAN_POINT('',(5.858795598586,-0.35)); +#22611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22612 = PCURVE('',#21875,#22613); +#22613 = DEFINITIONAL_REPRESENTATION('',(#22614),#22618); +#22614 = LINE('',#22615,#22616); +#22615 = CARTESIAN_POINT('',(-0.35033260053,-0.35)); +#22616 = VECTOR('',#22617,1.); +#22617 = DIRECTION('',(0.E+000,-1.)); +#22618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22619 = ORIENTED_EDGE('',*,*,#21770,.F.); +#22620 = ORIENTED_EDGE('',*,*,#22621,.F.); +#22621 = EDGE_CURVE('',#22622,#21771,#22624,.T.); +#22622 = VERTEX_POINT('',#22623); +#22623 = CARTESIAN_POINT('',(56.013504669241,22.045721,0.75)); +#22624 = SURFACE_CURVE('',#22625,(#22629,#22635),.PCURVE_S1.); +#22625 = LINE('',#22626,#22627); +#22626 = CARTESIAN_POINT('',(56.013504669241,22.495721,0.75)); +#22627 = VECTOR('',#22628,1.); +#22628 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22629 = PCURVE('',#21794,#22630); +#22630 = DEFINITIONAL_REPRESENTATION('',(#22631),#22634); +#22631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22632,#22633),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#20240 = CARTESIAN_POINT('',(3.565982362183,-0.45)); -#20241 = CARTESIAN_POINT('',(3.565982362183,-0.35)); -#20242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20243 = PCURVE('',#19429,#20244); -#20244 = DEFINITIONAL_REPRESENTATION('',(#20245),#20249); -#20245 = LINE('',#20246,#20247); -#20246 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#20247 = VECTOR('',#20248,1.); -#20248 = DIRECTION('',(0.E+000,-1.)); -#20249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20250 = ORIENTED_EDGE('',*,*,#20251,.F.); -#20251 = EDGE_CURVE('',#20252,#20230,#20254,.T.); -#20252 = VERTEX_POINT('',#20253); -#20253 = CARTESIAN_POINT('',(56.088908,22.045721,1.1)); -#20254 = SURFACE_CURVE('',#20255,(#20260,#20266),.PCURVE_S1.); -#20255 = CIRCLE('',#20256,0.85); -#20256 = AXIS2_PLACEMENT_3D('',#20257,#20258,#20259); -#20257 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#20258 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20259 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20260 = PCURVE('',#19402,#20261); -#20261 = DEFINITIONAL_REPRESENTATION('',(#20262),#20265); -#20262 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20263,#20264),.UNSPECIFIED., - .F.,.F.,(2,2),(3.14159265359,3.565982362183), - .PIECEWISE_BEZIER_KNOTS.); -#20263 = CARTESIAN_POINT('',(3.14159265359,-0.45)); -#20264 = CARTESIAN_POINT('',(3.565982362183,-0.45)); -#20265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20266 = PCURVE('',#20267,#20272); -#20267 = PLANE('',#20268); -#20268 = AXIS2_PLACEMENT_3D('',#20269,#20270,#20271); -#20269 = CARTESIAN_POINT('',(55.266410442306,22.045721,2.01366055628)); -#20270 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20271 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20272 = DEFINITIONAL_REPRESENTATION('',(#20273),#20277); -#20273 = CIRCLE('',#20274,0.85); -#20274 = AXIS2_PLACEMENT_2D('',#20275,#20276); -#20275 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#20276 = DIRECTION('',(1.,0.E+000)); -#20277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22632 = CARTESIAN_POINT('',(3.565982362183,-0.45)); +#22633 = CARTESIAN_POINT('',(3.565982362183,-0.35)); +#22634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20278 = ORIENTED_EDGE('',*,*,#20279,.F.); -#20279 = EDGE_CURVE('',#20158,#20252,#20280,.T.); -#20280 = SURFACE_CURVE('',#20281,(#20285,#20291),.PCURVE_S1.); -#20281 = LINE('',#20282,#20283); -#20282 = CARTESIAN_POINT('',(56.088908,22.495721,1.1)); -#20283 = VECTOR('',#20284,1.); -#20284 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20285 = PCURVE('',#19402,#20286); -#20286 = DEFINITIONAL_REPRESENTATION('',(#20287),#20290); -#20287 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20288,#20289),.UNSPECIFIED., +#22635 = PCURVE('',#21821,#22636); +#22636 = DEFINITIONAL_REPRESENTATION('',(#22637),#22641); +#22637 = LINE('',#22638,#22639); +#22638 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#22639 = VECTOR('',#22640,1.); +#22640 = DIRECTION('',(0.E+000,-1.)); +#22641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22642 = ORIENTED_EDGE('',*,*,#22643,.F.); +#22643 = EDGE_CURVE('',#22644,#22622,#22646,.T.); +#22644 = VERTEX_POINT('',#22645); +#22645 = CARTESIAN_POINT('',(56.088908,22.045721,1.1)); +#22646 = SURFACE_CURVE('',#22647,(#22652,#22658),.PCURVE_S1.); +#22647 = CIRCLE('',#22648,0.85); +#22648 = AXIS2_PLACEMENT_3D('',#22649,#22650,#22651); +#22649 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#22650 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22651 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22652 = PCURVE('',#21794,#22653); +#22653 = DEFINITIONAL_REPRESENTATION('',(#22654),#22657); +#22654 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22655,#22656),.UNSPECIFIED., + .F.,.F.,(2,2),(3.14159265359,3.565982362183), + .PIECEWISE_BEZIER_KNOTS.); +#22655 = CARTESIAN_POINT('',(3.14159265359,-0.45)); +#22656 = CARTESIAN_POINT('',(3.565982362183,-0.45)); +#22657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22658 = PCURVE('',#22659,#22664); +#22659 = PLANE('',#22660); +#22660 = AXIS2_PLACEMENT_3D('',#22661,#22662,#22663); +#22661 = CARTESIAN_POINT('',(55.266410442306,22.045721,2.01366055628)); +#22662 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22663 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22664 = DEFINITIONAL_REPRESENTATION('',(#22665),#22669); +#22665 = CIRCLE('',#22666,0.85); +#22666 = AXIS2_PLACEMENT_2D('',#22667,#22668); +#22667 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#22668 = DIRECTION('',(1.,0.E+000)); +#22669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22670 = ORIENTED_EDGE('',*,*,#22671,.F.); +#22671 = EDGE_CURVE('',#22550,#22644,#22672,.T.); +#22672 = SURFACE_CURVE('',#22673,(#22677,#22683),.PCURVE_S1.); +#22673 = LINE('',#22674,#22675); +#22674 = CARTESIAN_POINT('',(56.088908,22.495721,1.1)); +#22675 = VECTOR('',#22676,1.); +#22676 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22677 = PCURVE('',#21794,#22678); +#22678 = DEFINITIONAL_REPRESENTATION('',(#22679),#22682); +#22679 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22680,#22681),.UNSPECIFIED., .F.,.F.,(2,2),(-1.25,-0.45),.PIECEWISE_BEZIER_KNOTS.); -#20288 = CARTESIAN_POINT('',(3.14159265359,-1.25)); -#20289 = CARTESIAN_POINT('',(3.14159265359,-0.45)); -#20290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22680 = CARTESIAN_POINT('',(3.14159265359,-1.25)); +#22681 = CARTESIAN_POINT('',(3.14159265359,-0.45)); +#22682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20291 = PCURVE('',#18547,#20292); -#20292 = DEFINITIONAL_REPRESENTATION('',(#20293),#20296); -#20293 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20294,#20295),.UNSPECIFIED., +#22683 = PCURVE('',#20939,#22684); +#22684 = DEFINITIONAL_REPRESENTATION('',(#22685),#22688); +#22685 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22686,#22687),.UNSPECIFIED., .F.,.F.,(2,2),(-1.25,-0.45),.PIECEWISE_BEZIER_KNOTS.); -#20294 = CARTESIAN_POINT('',(3.14159265359,-1.25)); -#20295 = CARTESIAN_POINT('',(3.14159265359,-0.45)); -#20296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20297 = ORIENTED_EDGE('',*,*,#20157,.T.); -#20298 = ORIENTED_EDGE('',*,*,#20299,.T.); -#20299 = EDGE_CURVE('',#20160,#20300,#20302,.T.); -#20300 = VERTEX_POINT('',#20301); -#20301 = CARTESIAN_POINT('',(54.388908,22.045721,1.1)); -#20302 = SURFACE_CURVE('',#20303,(#20307,#20313),.PCURVE_S1.); -#20303 = LINE('',#20304,#20305); -#20304 = CARTESIAN_POINT('',(54.388908,22.495721,1.1)); -#20305 = VECTOR('',#20306,1.); -#20306 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20307 = PCURVE('',#19402,#20308); -#20308 = DEFINITIONAL_REPRESENTATION('',(#20309),#20312); -#20309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20310,#20311),.UNSPECIFIED., +#22686 = CARTESIAN_POINT('',(3.14159265359,-1.25)); +#22687 = CARTESIAN_POINT('',(3.14159265359,-0.45)); +#22688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22689 = ORIENTED_EDGE('',*,*,#22549,.T.); +#22690 = ORIENTED_EDGE('',*,*,#22691,.T.); +#22691 = EDGE_CURVE('',#22552,#22692,#22694,.T.); +#22692 = VERTEX_POINT('',#22693); +#22693 = CARTESIAN_POINT('',(54.388908,22.045721,1.1)); +#22694 = SURFACE_CURVE('',#22695,(#22699,#22705),.PCURVE_S1.); +#22695 = LINE('',#22696,#22697); +#22696 = CARTESIAN_POINT('',(54.388908,22.495721,1.1)); +#22697 = VECTOR('',#22698,1.); +#22698 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22699 = PCURVE('',#21794,#22700); +#22700 = DEFINITIONAL_REPRESENTATION('',(#22701),#22704); +#22701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22702,#22703),.UNSPECIFIED., .F.,.F.,(2,2),(-1.25,-0.45),.PIECEWISE_BEZIER_KNOTS.); -#20310 = CARTESIAN_POINT('',(6.28318530718,-1.25)); -#20311 = CARTESIAN_POINT('',(6.28318530718,-0.45)); -#20312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22702 = CARTESIAN_POINT('',(6.28318530718,-1.25)); +#22703 = CARTESIAN_POINT('',(6.28318530718,-0.45)); +#22704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20313 = PCURVE('',#18547,#20314); -#20314 = DEFINITIONAL_REPRESENTATION('',(#20315),#20318); -#20315 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20316,#20317),.UNSPECIFIED., +#22705 = PCURVE('',#20939,#22706); +#22706 = DEFINITIONAL_REPRESENTATION('',(#22707),#22710); +#22707 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22708,#22709),.UNSPECIFIED., .F.,.F.,(2,2),(-1.25,-0.45),.PIECEWISE_BEZIER_KNOTS.); -#20316 = CARTESIAN_POINT('',(0.E+000,-1.25)); -#20317 = CARTESIAN_POINT('',(0.E+000,-0.45)); -#20318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20319 = ORIENTED_EDGE('',*,*,#20320,.F.); -#20320 = EDGE_CURVE('',#20207,#20300,#20321,.T.); -#20321 = SURFACE_CURVE('',#20322,(#20327,#20333),.PCURVE_S1.); -#20322 = CIRCLE('',#20323,0.85); -#20323 = AXIS2_PLACEMENT_3D('',#20324,#20325,#20326); -#20324 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#20325 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20326 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20327 = PCURVE('',#19402,#20328); -#20328 = DEFINITIONAL_REPRESENTATION('',(#20329),#20332); -#20329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20330,#20331),.UNSPECIFIED., +#22708 = CARTESIAN_POINT('',(0.E+000,-1.25)); +#22709 = CARTESIAN_POINT('',(0.E+000,-0.45)); +#22710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22711 = ORIENTED_EDGE('',*,*,#22712,.F.); +#22712 = EDGE_CURVE('',#22599,#22692,#22713,.T.); +#22713 = SURFACE_CURVE('',#22714,(#22719,#22725),.PCURVE_S1.); +#22714 = CIRCLE('',#22715,0.85); +#22715 = AXIS2_PLACEMENT_3D('',#22716,#22717,#22718); +#22716 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#22717 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22718 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22719 = PCURVE('',#21794,#22720); +#22720 = DEFINITIONAL_REPRESENTATION('',(#22721),#22724); +#22721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22722,#22723),.UNSPECIFIED., .F.,.F.,(2,2),(5.858795598586,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#20330 = CARTESIAN_POINT('',(5.858795598586,-0.45)); -#20331 = CARTESIAN_POINT('',(6.28318530718,-0.45)); -#20332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20333 = PCURVE('',#20267,#20334); -#20334 = DEFINITIONAL_REPRESENTATION('',(#20335),#20339); -#20335 = CIRCLE('',#20336,0.85); -#20336 = AXIS2_PLACEMENT_2D('',#20337,#20338); -#20337 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#20338 = DIRECTION('',(1.,0.E+000)); -#20339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20340 = ADVANCED_FACE('',(#20341),#18409,.F.); -#20341 = FACE_BOUND('',#20342,.T.); -#20342 = EDGE_LOOP('',(#20343,#20344,#20345,#20368)); -#20343 = ORIENTED_EDGE('',*,*,#18903,.T.); -#20344 = ORIENTED_EDGE('',*,*,#18393,.F.); -#20345 = ORIENTED_EDGE('',*,*,#20346,.T.); -#20346 = EDGE_CURVE('',#18371,#20347,#20349,.T.); -#20347 = VERTEX_POINT('',#20348); -#20348 = CARTESIAN_POINT('',(55.538908,22.145721,-0.45)); -#20349 = SURFACE_CURVE('',#20350,(#20354,#20361),.PCURVE_S1.); -#20350 = LINE('',#20351,#20352); -#20351 = CARTESIAN_POINT('',(55.538908,22.145721,0.899011437739)); -#20352 = VECTOR('',#20353,1.); -#20353 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#20354 = PCURVE('',#18409,#20355); -#20355 = DEFINITIONAL_REPRESENTATION('',(#20356),#20360); -#20356 = LINE('',#20357,#20358); -#20357 = CARTESIAN_POINT('',(-0.752950639156,0.35)); -#20358 = VECTOR('',#20359,1.); -#20359 = DIRECTION('',(1.,0.E+000)); -#20360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20361 = PCURVE('',#18764,#20362); -#20362 = DEFINITIONAL_REPRESENTATION('',(#20363),#20367); -#20363 = LINE('',#20364,#20365); -#20364 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); -#20365 = VECTOR('',#20366,1.); -#20366 = DIRECTION('',(0.E+000,-1.)); -#20367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20368 = ORIENTED_EDGE('',*,*,#20369,.F.); -#20369 = EDGE_CURVE('',#18904,#20347,#20370,.T.); -#20370 = SURFACE_CURVE('',#20371,(#20375,#20382),.PCURVE_S1.); -#20371 = LINE('',#20372,#20373); -#20372 = CARTESIAN_POINT('',(55.538908,22.495721,-0.45)); -#20373 = VECTOR('',#20374,1.); -#20374 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#20375 = PCURVE('',#18409,#20376); -#20376 = DEFINITIONAL_REPRESENTATION('',(#20377),#20381); -#20377 = LINE('',#20378,#20379); -#20378 = CARTESIAN_POINT('',(0.596060798583,0.E+000)); -#20379 = VECTOR('',#20380,1.); -#20380 = DIRECTION('',(0.E+000,1.)); -#20381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20382 = PCURVE('',#18940,#20383); -#20383 = DEFINITIONAL_REPRESENTATION('',(#20384),#20388); -#20384 = LINE('',#20385,#20386); -#20385 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20386 = VECTOR('',#20387,1.); -#20387 = DIRECTION('',(0.E+000,1.)); -#20388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20389 = ADVANCED_FACE('',(#20390),#18465,.T.); -#20390 = FACE_BOUND('',#20391,.T.); -#20391 = EDGE_LOOP('',(#20392,#20393,#20416,#20437)); -#20392 = ORIENTED_EDGE('',*,*,#18879,.F.); -#20393 = ORIENTED_EDGE('',*,*,#20394,.T.); -#20394 = EDGE_CURVE('',#18880,#20395,#20397,.T.); -#20395 = VERTEX_POINT('',#20396); -#20396 = CARTESIAN_POINT('',(54.938908,22.145721,-0.45)); -#20397 = SURFACE_CURVE('',#20398,(#20402,#20409),.PCURVE_S1.); -#20398 = LINE('',#20399,#20400); -#20399 = CARTESIAN_POINT('',(54.938908,22.495721,-0.45)); -#20400 = VECTOR('',#20401,1.); -#20401 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#20402 = PCURVE('',#18465,#20403); -#20403 = DEFINITIONAL_REPRESENTATION('',(#20404),#20408); -#20404 = LINE('',#20405,#20406); -#20405 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20406 = VECTOR('',#20407,1.); -#20407 = DIRECTION('',(0.E+000,1.)); -#20408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20409 = PCURVE('',#18940,#20410); -#20410 = DEFINITIONAL_REPRESENTATION('',(#20411),#20415); -#20411 = LINE('',#20412,#20413); -#20412 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#20413 = VECTOR('',#20414,1.); -#20414 = DIRECTION('',(0.E+000,1.)); -#20415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20416 = ORIENTED_EDGE('',*,*,#20417,.F.); -#20417 = EDGE_CURVE('',#18450,#20395,#20418,.T.); -#20418 = SURFACE_CURVE('',#20419,(#20423,#20430),.PCURVE_S1.); -#20419 = LINE('',#20420,#20421); -#20420 = CARTESIAN_POINT('',(54.938908,22.145721,0.899011437739)); -#20421 = VECTOR('',#20422,1.); -#20422 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#20423 = PCURVE('',#18465,#20424); -#20424 = DEFINITIONAL_REPRESENTATION('',(#20425),#20429); -#20425 = LINE('',#20426,#20427); -#20426 = CARTESIAN_POINT('',(-1.349011437739,0.35)); -#20427 = VECTOR('',#20428,1.); -#20428 = DIRECTION('',(1.,0.E+000)); -#20429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20430 = PCURVE('',#18764,#20431); -#20431 = DEFINITIONAL_REPRESENTATION('',(#20432),#20436); -#20432 = LINE('',#20433,#20434); -#20433 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); -#20434 = VECTOR('',#20435,1.); -#20435 = DIRECTION('',(0.E+000,-1.)); -#20436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20437 = ORIENTED_EDGE('',*,*,#18449,.T.); -#20438 = ADVANCED_FACE('',(#20439),#18940,.T.); -#20439 = FACE_BOUND('',#20440,.T.); -#20440 = EDGE_LOOP('',(#20441,#20442,#20443,#20464)); -#20441 = ORIENTED_EDGE('',*,*,#18926,.F.); -#20442 = ORIENTED_EDGE('',*,*,#20369,.T.); -#20443 = ORIENTED_EDGE('',*,*,#20444,.F.); -#20444 = EDGE_CURVE('',#20395,#20347,#20445,.T.); -#20445 = SURFACE_CURVE('',#20446,(#20450,#20457),.PCURVE_S1.); -#20446 = LINE('',#20447,#20448); -#20447 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.45)); -#20448 = VECTOR('',#20449,1.); -#20449 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20450 = PCURVE('',#18940,#20451); -#20451 = DEFINITIONAL_REPRESENTATION('',(#20452),#20456); -#20452 = LINE('',#20453,#20454); -#20453 = CARTESIAN_POINT('',(-4.618951266039,0.35)); -#20454 = VECTOR('',#20455,1.); -#20455 = DIRECTION('',(1.,0.E+000)); -#20456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20457 = PCURVE('',#18764,#20458); -#20458 = DEFINITIONAL_REPRESENTATION('',(#20459),#20463); -#20459 = LINE('',#20460,#20461); -#20460 = CARTESIAN_POINT('',(0.E+000,-1.349011437739)); -#20461 = VECTOR('',#20462,1.); -#20462 = DIRECTION('',(-1.,0.E+000)); -#20463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20464 = ORIENTED_EDGE('',*,*,#20394,.F.); -#20465 = ADVANCED_FACE('',(#20466),#20481,.F.); -#20466 = FACE_BOUND('',#20467,.F.); -#20467 = EDGE_LOOP('',(#20468,#20498,#20524)); -#20468 = ORIENTED_EDGE('',*,*,#20469,.F.); -#20469 = EDGE_CURVE('',#20470,#20472,#20474,.T.); -#20470 = VERTEX_POINT('',#20471); -#20471 = CARTESIAN_POINT('',(55.238400174819,22.495721,1.1)); -#20472 = VERTEX_POINT('',#20473); -#20473 = CARTESIAN_POINT('',(55.239415825181,22.495721,1.1)); -#20474 = SURFACE_CURVE('',#20475,(#20480,#20491),.PCURVE_S1.); -#20475 = CIRCLE('',#20476,5.078251810705E-004); -#20476 = AXIS2_PLACEMENT_3D('',#20477,#20478,#20479); -#20477 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#20478 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20479 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20480 = PCURVE('',#20481,#20486); -#20481 = CONICAL_SURFACE('',#20482,6.116265326384E-005, +#22722 = CARTESIAN_POINT('',(5.858795598586,-0.45)); +#22723 = CARTESIAN_POINT('',(6.28318530718,-0.45)); +#22724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22725 = PCURVE('',#22659,#22726); +#22726 = DEFINITIONAL_REPRESENTATION('',(#22727),#22731); +#22727 = CIRCLE('',#22728,0.85); +#22728 = AXIS2_PLACEMENT_2D('',#22729,#22730); +#22729 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#22730 = DIRECTION('',(1.,0.E+000)); +#22731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22732 = ADVANCED_FACE('',(#22733),#20801,.F.); +#22733 = FACE_BOUND('',#22734,.T.); +#22734 = EDGE_LOOP('',(#22735,#22736,#22737,#22760)); +#22735 = ORIENTED_EDGE('',*,*,#21295,.T.); +#22736 = ORIENTED_EDGE('',*,*,#20785,.F.); +#22737 = ORIENTED_EDGE('',*,*,#22738,.T.); +#22738 = EDGE_CURVE('',#20763,#22739,#22741,.T.); +#22739 = VERTEX_POINT('',#22740); +#22740 = CARTESIAN_POINT('',(55.538908,22.145721,-0.45)); +#22741 = SURFACE_CURVE('',#22742,(#22746,#22753),.PCURVE_S1.); +#22742 = LINE('',#22743,#22744); +#22743 = CARTESIAN_POINT('',(55.538908,22.145721,0.899011437739)); +#22744 = VECTOR('',#22745,1.); +#22745 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#22746 = PCURVE('',#20801,#22747); +#22747 = DEFINITIONAL_REPRESENTATION('',(#22748),#22752); +#22748 = LINE('',#22749,#22750); +#22749 = CARTESIAN_POINT('',(-0.752950639156,0.35)); +#22750 = VECTOR('',#22751,1.); +#22751 = DIRECTION('',(1.,0.E+000)); +#22752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22753 = PCURVE('',#21156,#22754); +#22754 = DEFINITIONAL_REPRESENTATION('',(#22755),#22759); +#22755 = LINE('',#22756,#22757); +#22756 = CARTESIAN_POINT('',(-4.618951266039,0.E+000)); +#22757 = VECTOR('',#22758,1.); +#22758 = DIRECTION('',(0.E+000,-1.)); +#22759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22760 = ORIENTED_EDGE('',*,*,#22761,.F.); +#22761 = EDGE_CURVE('',#21296,#22739,#22762,.T.); +#22762 = SURFACE_CURVE('',#22763,(#22767,#22774),.PCURVE_S1.); +#22763 = LINE('',#22764,#22765); +#22764 = CARTESIAN_POINT('',(55.538908,22.495721,-0.45)); +#22765 = VECTOR('',#22766,1.); +#22766 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#22767 = PCURVE('',#20801,#22768); +#22768 = DEFINITIONAL_REPRESENTATION('',(#22769),#22773); +#22769 = LINE('',#22770,#22771); +#22770 = CARTESIAN_POINT('',(0.596060798583,0.E+000)); +#22771 = VECTOR('',#22772,1.); +#22772 = DIRECTION('',(0.E+000,1.)); +#22773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22774 = PCURVE('',#21332,#22775); +#22775 = DEFINITIONAL_REPRESENTATION('',(#22776),#22780); +#22776 = LINE('',#22777,#22778); +#22777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22778 = VECTOR('',#22779,1.); +#22779 = DIRECTION('',(0.E+000,1.)); +#22780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22781 = ADVANCED_FACE('',(#22782),#20857,.T.); +#22782 = FACE_BOUND('',#22783,.T.); +#22783 = EDGE_LOOP('',(#22784,#22785,#22808,#22829)); +#22784 = ORIENTED_EDGE('',*,*,#21271,.F.); +#22785 = ORIENTED_EDGE('',*,*,#22786,.T.); +#22786 = EDGE_CURVE('',#21272,#22787,#22789,.T.); +#22787 = VERTEX_POINT('',#22788); +#22788 = CARTESIAN_POINT('',(54.938908,22.145721,-0.45)); +#22789 = SURFACE_CURVE('',#22790,(#22794,#22801),.PCURVE_S1.); +#22790 = LINE('',#22791,#22792); +#22791 = CARTESIAN_POINT('',(54.938908,22.495721,-0.45)); +#22792 = VECTOR('',#22793,1.); +#22793 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#22794 = PCURVE('',#20857,#22795); +#22795 = DEFINITIONAL_REPRESENTATION('',(#22796),#22800); +#22796 = LINE('',#22797,#22798); +#22797 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22798 = VECTOR('',#22799,1.); +#22799 = DIRECTION('',(0.E+000,1.)); +#22800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22801 = PCURVE('',#21332,#22802); +#22802 = DEFINITIONAL_REPRESENTATION('',(#22803),#22807); +#22803 = LINE('',#22804,#22805); +#22804 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#22805 = VECTOR('',#22806,1.); +#22806 = DIRECTION('',(0.E+000,1.)); +#22807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22808 = ORIENTED_EDGE('',*,*,#22809,.F.); +#22809 = EDGE_CURVE('',#20842,#22787,#22810,.T.); +#22810 = SURFACE_CURVE('',#22811,(#22815,#22822),.PCURVE_S1.); +#22811 = LINE('',#22812,#22813); +#22812 = CARTESIAN_POINT('',(54.938908,22.145721,0.899011437739)); +#22813 = VECTOR('',#22814,1.); +#22814 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#22815 = PCURVE('',#20857,#22816); +#22816 = DEFINITIONAL_REPRESENTATION('',(#22817),#22821); +#22817 = LINE('',#22818,#22819); +#22818 = CARTESIAN_POINT('',(-1.349011437739,0.35)); +#22819 = VECTOR('',#22820,1.); +#22820 = DIRECTION('',(1.,0.E+000)); +#22821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22822 = PCURVE('',#21156,#22823); +#22823 = DEFINITIONAL_REPRESENTATION('',(#22824),#22828); +#22824 = LINE('',#22825,#22826); +#22825 = CARTESIAN_POINT('',(-4.018951266039,0.E+000)); +#22826 = VECTOR('',#22827,1.); +#22827 = DIRECTION('',(0.E+000,-1.)); +#22828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22829 = ORIENTED_EDGE('',*,*,#20841,.T.); +#22830 = ADVANCED_FACE('',(#22831),#21332,.T.); +#22831 = FACE_BOUND('',#22832,.T.); +#22832 = EDGE_LOOP('',(#22833,#22834,#22835,#22856)); +#22833 = ORIENTED_EDGE('',*,*,#21318,.F.); +#22834 = ORIENTED_EDGE('',*,*,#22761,.T.); +#22835 = ORIENTED_EDGE('',*,*,#22836,.F.); +#22836 = EDGE_CURVE('',#22787,#22739,#22837,.T.); +#22837 = SURFACE_CURVE('',#22838,(#22842,#22849),.PCURVE_S1.); +#22838 = LINE('',#22839,#22840); +#22839 = CARTESIAN_POINT('',(50.919956733961,22.145721,-0.45)); +#22840 = VECTOR('',#22841,1.); +#22841 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22842 = PCURVE('',#21332,#22843); +#22843 = DEFINITIONAL_REPRESENTATION('',(#22844),#22848); +#22844 = LINE('',#22845,#22846); +#22845 = CARTESIAN_POINT('',(-4.618951266039,0.35)); +#22846 = VECTOR('',#22847,1.); +#22847 = DIRECTION('',(1.,0.E+000)); +#22848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22849 = PCURVE('',#21156,#22850); +#22850 = DEFINITIONAL_REPRESENTATION('',(#22851),#22855); +#22851 = LINE('',#22852,#22853); +#22852 = CARTESIAN_POINT('',(0.E+000,-1.349011437739)); +#22853 = VECTOR('',#22854,1.); +#22854 = DIRECTION('',(-1.,0.E+000)); +#22855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22856 = ORIENTED_EDGE('',*,*,#22786,.F.); +#22857 = ADVANCED_FACE('',(#22858),#22873,.F.); +#22858 = FACE_BOUND('',#22859,.F.); +#22859 = EDGE_LOOP('',(#22860,#22890,#22916)); +#22860 = ORIENTED_EDGE('',*,*,#22861,.F.); +#22861 = EDGE_CURVE('',#22862,#22864,#22866,.T.); +#22862 = VERTEX_POINT('',#22863); +#22863 = CARTESIAN_POINT('',(55.238400174819,22.495721,1.1)); +#22864 = VERTEX_POINT('',#22865); +#22865 = CARTESIAN_POINT('',(55.239415825181,22.495721,1.1)); +#22866 = SURFACE_CURVE('',#22867,(#22872,#22883),.PCURVE_S1.); +#22867 = CIRCLE('',#22868,5.078251810705E-004); +#22868 = AXIS2_PLACEMENT_3D('',#22869,#22870,#22871); +#22869 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#22870 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22871 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22872 = PCURVE('',#22873,#22878); +#22873 = CONICAL_SURFACE('',#22874,6.116265326384E-005, 4.062601225057E-004); -#20482 = AXIS2_PLACEMENT_3D('',#20483,#20484,#20485); -#20483 = CARTESIAN_POINT('',(55.238908,21.396271463879,1.1)); -#20484 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20485 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20486 = DEFINITIONAL_REPRESENTATION('',(#20487),#20490); -#20487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20488,#20489),.UNSPECIFIED., +#22874 = AXIS2_PLACEMENT_3D('',#22875,#22876,#22877); +#22875 = CARTESIAN_POINT('',(55.238908,21.396271463879,1.1)); +#22876 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22877 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22878 = DEFINITIONAL_REPRESENTATION('',(#22879),#22882); +#22879 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22880,#22881),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#20488 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); -#20489 = CARTESIAN_POINT('',(6.28318530718,1.099449536121)); -#20490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20491 = PCURVE('',#17723,#20492); -#20492 = DEFINITIONAL_REPRESENTATION('',(#20493),#20497); -#20493 = CIRCLE('',#20494,5.078251810673E-004); -#20494 = AXIS2_PLACEMENT_2D('',#20495,#20496); -#20495 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20496 = DIRECTION('',(-1.,0.E+000)); -#20497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20498 = ORIENTED_EDGE('',*,*,#20499,.F.); -#20499 = EDGE_CURVE('',#20500,#20470,#20502,.T.); -#20500 = VERTEX_POINT('',#20501); -#20501 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#20502 = SURFACE_CURVE('',#20503,(#20507,#20513),.PCURVE_S1.); -#20503 = LINE('',#20504,#20505); -#20504 = CARTESIAN_POINT('',(55.238846837347,21.396271463879,1.1)); -#20505 = VECTOR('',#20506,1.); -#20506 = DIRECTION('',(-4.062601113068E-004,0.999999917476,0.E+000)); -#20507 = PCURVE('',#20481,#20508); -#20508 = DEFINITIONAL_REPRESENTATION('',(#20509),#20512); -#20509 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20510,#20511),.UNSPECIFIED., +#22880 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); +#22881 = CARTESIAN_POINT('',(6.28318530718,1.099449536121)); +#22882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22883 = PCURVE('',#20115,#22884); +#22884 = DEFINITIONAL_REPRESENTATION('',(#22885),#22889); +#22885 = CIRCLE('',#22886,5.078251810673E-004); +#22886 = AXIS2_PLACEMENT_2D('',#22887,#22888); +#22887 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#22888 = DIRECTION('',(-1.,0.E+000)); +#22889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22890 = ORIENTED_EDGE('',*,*,#22891,.F.); +#22891 = EDGE_CURVE('',#22892,#22862,#22894,.T.); +#22892 = VERTEX_POINT('',#22893); +#22893 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#22894 = SURFACE_CURVE('',#22895,(#22899,#22905),.PCURVE_S1.); +#22895 = LINE('',#22896,#22897); +#22896 = CARTESIAN_POINT('',(55.238846837347,21.396271463879,1.1)); +#22897 = VECTOR('',#22898,1.); +#22898 = DIRECTION('',(-4.062601113068E-004,0.999999917476,0.E+000)); +#22899 = PCURVE('',#22873,#22900); +#22900 = DEFINITIONAL_REPRESENTATION('',(#22901),#22904); +#22901 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22902,#22903),.UNSPECIFIED., .F.,.F.,(2,2),(-0.150550476303,1.099449626851), .PIECEWISE_BEZIER_KNOTS.); -#20510 = CARTESIAN_POINT('',(3.14159265359,-0.150550463879)); -#20511 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); -#20512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22902 = CARTESIAN_POINT('',(3.14159265359,-0.150550463879)); +#22903 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); +#22904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20513 = PCURVE('',#20514,#20519); -#20514 = CONICAL_SURFACE('',#20515,6.116265326384E-005, +#22905 = PCURVE('',#22906,#22911); +#22906 = CONICAL_SURFACE('',#22907,6.116265326384E-005, 4.062601225057E-004); -#20515 = AXIS2_PLACEMENT_3D('',#20516,#20517,#20518); -#20516 = CARTESIAN_POINT('',(55.238908,21.396271463879,1.1)); -#20517 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20518 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20519 = DEFINITIONAL_REPRESENTATION('',(#20520),#20523); -#20520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20521,#20522),.UNSPECIFIED., +#22907 = AXIS2_PLACEMENT_3D('',#22908,#22909,#22910); +#22908 = CARTESIAN_POINT('',(55.238908,21.396271463879,1.1)); +#22909 = DIRECTION('',(0.E+000,1.,0.E+000)); +#22910 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22911 = DEFINITIONAL_REPRESENTATION('',(#22912),#22915); +#22912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22913,#22914),.UNSPECIFIED., .F.,.F.,(2,2),(-0.150550476303,1.099449626851), .PIECEWISE_BEZIER_KNOTS.); -#20521 = CARTESIAN_POINT('',(3.14159265359,-0.150550463879)); -#20522 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); -#20523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20524 = ORIENTED_EDGE('',*,*,#20525,.T.); -#20525 = EDGE_CURVE('',#20500,#20472,#20526,.T.); -#20526 = SURFACE_CURVE('',#20527,(#20531,#20537),.PCURVE_S1.); -#20527 = LINE('',#20528,#20529); -#20528 = CARTESIAN_POINT('',(55.238969162653,21.396271463879,1.1)); -#20529 = VECTOR('',#20530,1.); -#20530 = DIRECTION('',(4.062601113068E-004,0.999999917476,0.E+000)); -#20531 = PCURVE('',#20481,#20532); -#20532 = DEFINITIONAL_REPRESENTATION('',(#20533),#20536); -#20533 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20534,#20535),.UNSPECIFIED., +#22913 = CARTESIAN_POINT('',(3.14159265359,-0.150550463879)); +#22914 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); +#22915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22916 = ORIENTED_EDGE('',*,*,#22917,.T.); +#22917 = EDGE_CURVE('',#22892,#22864,#22918,.T.); +#22918 = SURFACE_CURVE('',#22919,(#22923,#22929),.PCURVE_S1.); +#22919 = LINE('',#22920,#22921); +#22920 = CARTESIAN_POINT('',(55.238969162653,21.396271463879,1.1)); +#22921 = VECTOR('',#22922,1.); +#22922 = DIRECTION('',(4.062601113068E-004,0.999999917476,0.E+000)); +#22923 = PCURVE('',#22873,#22924); +#22924 = DEFINITIONAL_REPRESENTATION('',(#22925),#22928); +#22925 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22926,#22927),.UNSPECIFIED., .F.,.F.,(2,2),(-0.150550476303,1.099449626851), .PIECEWISE_BEZIER_KNOTS.); -#20534 = CARTESIAN_POINT('',(6.28318530718,-0.150550463879)); -#20535 = CARTESIAN_POINT('',(6.28318530718,1.099449536121)); -#20536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22926 = CARTESIAN_POINT('',(6.28318530718,-0.150550463879)); +#22927 = CARTESIAN_POINT('',(6.28318530718,1.099449536121)); +#22928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20537 = PCURVE('',#20514,#20538); -#20538 = DEFINITIONAL_REPRESENTATION('',(#20539),#20542); -#20539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20540,#20541),.UNSPECIFIED., +#22929 = PCURVE('',#22906,#22930); +#22930 = DEFINITIONAL_REPRESENTATION('',(#22931),#22934); +#22931 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#22932,#22933),.UNSPECIFIED., .F.,.F.,(2,2),(-0.150550476303,1.099449626851), .PIECEWISE_BEZIER_KNOTS.); -#20540 = CARTESIAN_POINT('',(0.E+000,-0.150550463879)); -#20541 = CARTESIAN_POINT('',(0.E+000,1.099449536121)); -#20542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20543 = ADVANCED_FACE('',(#20544),#20558,.T.); -#20544 = FACE_BOUND('',#20545,.T.); -#20545 = EDGE_LOOP('',(#20546,#20576,#20599,#20622)); -#20546 = ORIENTED_EDGE('',*,*,#20547,.F.); -#20547 = EDGE_CURVE('',#20548,#20550,#20552,.T.); -#20548 = VERTEX_POINT('',#20549); -#20549 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); -#20550 = VERTEX_POINT('',#20551); -#20551 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); -#20552 = SURFACE_CURVE('',#20553,(#20557,#20569),.PCURVE_S1.); -#20553 = LINE('',#20554,#20555); -#20554 = CARTESIAN_POINT('',(52.448908,22.495721,2.65)); -#20555 = VECTOR('',#20556,1.); -#20556 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20557 = PCURVE('',#20558,#20563); -#20558 = PLANE('',#20559); -#20559 = AXIS2_PLACEMENT_3D('',#20560,#20561,#20562); -#20560 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); -#20561 = DIRECTION('',(0.E+000,0.E+000,1.)); -#20562 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20563 = DEFINITIONAL_REPRESENTATION('',(#20564),#20568); -#20564 = LINE('',#20565,#20566); -#20565 = CARTESIAN_POINT('',(2.49,0.E+000)); -#20566 = VECTOR('',#20567,1.); -#20567 = DIRECTION('',(-1.,0.E+000)); -#20568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20569 = PCURVE('',#17723,#20570); -#20570 = DEFINITIONAL_REPRESENTATION('',(#20571),#20575); -#20571 = LINE('',#20572,#20573); -#20572 = CARTESIAN_POINT('',(-1.528951266039,1.750988562261)); -#20573 = VECTOR('',#20574,1.); -#20574 = DIRECTION('',(-1.,0.E+000)); -#20575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20576 = ORIENTED_EDGE('',*,*,#20577,.T.); -#20577 = EDGE_CURVE('',#20548,#20578,#20580,.T.); -#20578 = VERTEX_POINT('',#20579); -#20579 = CARTESIAN_POINT('',(54.938908,22.345721,2.65)); -#20580 = SURFACE_CURVE('',#20581,(#20585,#20592),.PCURVE_S1.); -#20581 = LINE('',#20582,#20583); -#20582 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); -#20583 = VECTOR('',#20584,1.); -#20584 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#20585 = PCURVE('',#20558,#20586); -#20586 = DEFINITIONAL_REPRESENTATION('',(#20587),#20591); -#20587 = LINE('',#20588,#20589); -#20588 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20589 = VECTOR('',#20590,1.); -#20590 = DIRECTION('',(0.E+000,1.)); -#20591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20592 = PCURVE('',#18072,#20593); -#20593 = DEFINITIONAL_REPRESENTATION('',(#20594),#20598); -#20594 = LINE('',#20595,#20596); -#20595 = CARTESIAN_POINT('',(-1.15,0.E+000)); -#20596 = VECTOR('',#20597,1.); -#20597 = DIRECTION('',(0.E+000,1.)); -#20598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20599 = ORIENTED_EDGE('',*,*,#20600,.T.); -#20600 = EDGE_CURVE('',#20578,#20601,#20603,.T.); -#20601 = VERTEX_POINT('',#20602); -#20602 = CARTESIAN_POINT('',(55.538908,22.345721,2.65)); -#20603 = SURFACE_CURVE('',#20604,(#20608,#20615),.PCURVE_S1.); -#20604 = LINE('',#20605,#20606); -#20605 = CARTESIAN_POINT('',(52.448908,22.345721,2.65)); -#20606 = VECTOR('',#20607,1.); -#20607 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20608 = PCURVE('',#20558,#20609); -#20609 = DEFINITIONAL_REPRESENTATION('',(#20610),#20614); -#20610 = LINE('',#20611,#20612); -#20611 = CARTESIAN_POINT('',(2.49,0.15)); -#20612 = VECTOR('',#20613,1.); -#20613 = DIRECTION('',(-1.,0.E+000)); -#20614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20615 = PCURVE('',#18044,#20616); -#20616 = DEFINITIONAL_REPRESENTATION('',(#20617),#20621); -#20617 = LINE('',#20618,#20619); -#20618 = CARTESIAN_POINT('',(-1.528951266039,1.750988562261)); -#20619 = VECTOR('',#20620,1.); -#20620 = DIRECTION('',(-1.,0.E+000)); -#20621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20622 = ORIENTED_EDGE('',*,*,#20623,.F.); -#20623 = EDGE_CURVE('',#20550,#20601,#20624,.T.); -#20624 = SURFACE_CURVE('',#20625,(#20629,#20636),.PCURVE_S1.); -#20625 = LINE('',#20626,#20627); -#20626 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); -#20627 = VECTOR('',#20628,1.); -#20628 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#20629 = PCURVE('',#20558,#20630); -#20630 = DEFINITIONAL_REPRESENTATION('',(#20631),#20635); -#20631 = LINE('',#20632,#20633); -#20632 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#20633 = VECTOR('',#20634,1.); -#20634 = DIRECTION('',(0.E+000,1.)); -#20635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20636 = PCURVE('',#18016,#20637); -#20637 = DEFINITIONAL_REPRESENTATION('',(#20638),#20642); -#20638 = LINE('',#20639,#20640); -#20639 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20640 = VECTOR('',#20641,1.); -#20641 = DIRECTION('',(0.E+000,1.)); -#20642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20643 = ADVANCED_FACE('',(#20644),#18044,.F.); -#20644 = FACE_BOUND('',#20645,.T.); -#20645 = EDGE_LOOP('',(#20646,#20667,#20668,#20689)); -#20646 = ORIENTED_EDGE('',*,*,#20647,.F.); -#20647 = EDGE_CURVE('',#18029,#20578,#20648,.T.); -#20648 = SURFACE_CURVE('',#20649,(#20653,#20660),.PCURVE_S1.); -#20649 = LINE('',#20650,#20651); -#20650 = CARTESIAN_POINT('',(54.938908,22.345721,0.45)); -#20651 = VECTOR('',#20652,1.); -#20652 = DIRECTION('',(0.E+000,0.E+000,1.)); -#20653 = PCURVE('',#18044,#20654); -#20654 = DEFINITIONAL_REPRESENTATION('',(#20655),#20659); -#20655 = LINE('',#20656,#20657); -#20656 = CARTESIAN_POINT('',(-4.018951266039,-0.449011437739)); -#20657 = VECTOR('',#20658,1.); -#20658 = DIRECTION('',(0.E+000,1.)); -#20659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20660 = PCURVE('',#18072,#20661); -#20661 = DEFINITIONAL_REPRESENTATION('',(#20662),#20666); -#20662 = LINE('',#20663,#20664); -#20663 = CARTESIAN_POINT('',(1.05,0.15)); -#20664 = VECTOR('',#20665,1.); -#20665 = DIRECTION('',(-1.,0.E+000)); -#20666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20667 = ORIENTED_EDGE('',*,*,#18028,.F.); -#20668 = ORIENTED_EDGE('',*,*,#20669,.T.); -#20669 = EDGE_CURVE('',#18001,#20601,#20670,.T.); -#20670 = SURFACE_CURVE('',#20671,(#20675,#20682),.PCURVE_S1.); -#20671 = LINE('',#20672,#20673); -#20672 = CARTESIAN_POINT('',(55.538908,22.345721,0.45)); -#20673 = VECTOR('',#20674,1.); -#20674 = DIRECTION('',(0.E+000,0.E+000,1.)); -#20675 = PCURVE('',#18044,#20676); -#20676 = DEFINITIONAL_REPRESENTATION('',(#20677),#20681); -#20677 = LINE('',#20678,#20679); -#20678 = CARTESIAN_POINT('',(-4.618951266039,-0.449011437739)); -#20679 = VECTOR('',#20680,1.); -#20680 = DIRECTION('',(0.E+000,1.)); -#20681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20682 = PCURVE('',#18016,#20683); -#20683 = DEFINITIONAL_REPRESENTATION('',(#20684),#20688); -#20684 = LINE('',#20685,#20686); -#20685 = CARTESIAN_POINT('',(-2.2,0.15)); -#20686 = VECTOR('',#20687,1.); -#20687 = DIRECTION('',(1.,0.E+000)); -#20688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20689 = ORIENTED_EDGE('',*,*,#20600,.F.); -#20690 = ADVANCED_FACE('',(#20691),#18764,.F.); -#20691 = FACE_BOUND('',#20692,.T.); -#20692 = EDGE_LOOP('',(#20693,#20694,#20695,#20696,#20697,#20698)); -#20693 = ORIENTED_EDGE('',*,*,#18748,.T.); -#20694 = ORIENTED_EDGE('',*,*,#20417,.T.); -#20695 = ORIENTED_EDGE('',*,*,#20444,.T.); -#20696 = ORIENTED_EDGE('',*,*,#20346,.F.); -#20697 = ORIENTED_EDGE('',*,*,#18855,.F.); -#20698 = ORIENTED_EDGE('',*,*,#19570,.T.); -#20699 = ADVANCED_FACE('',(#20700),#18072,.T.); -#20700 = FACE_BOUND('',#20701,.T.); -#20701 = EDGE_LOOP('',(#20702,#20723,#20724,#20725)); -#20702 = ORIENTED_EDGE('',*,*,#20703,.F.); -#20703 = EDGE_CURVE('',#18057,#20548,#20704,.T.); -#20704 = SURFACE_CURVE('',#20705,(#20709,#20716),.PCURVE_S1.); -#20705 = LINE('',#20706,#20707); -#20706 = CARTESIAN_POINT('',(54.938908,22.495721,0.45)); -#20707 = VECTOR('',#20708,1.); -#20708 = DIRECTION('',(0.E+000,0.E+000,1.)); -#20709 = PCURVE('',#18072,#20710); -#20710 = DEFINITIONAL_REPRESENTATION('',(#20711),#20715); -#20711 = LINE('',#20712,#20713); -#20712 = CARTESIAN_POINT('',(1.05,0.E+000)); -#20713 = VECTOR('',#20714,1.); -#20714 = DIRECTION('',(-1.,0.E+000)); -#20715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20716 = PCURVE('',#17723,#20717); -#20717 = DEFINITIONAL_REPRESENTATION('',(#20718),#20722); -#20718 = LINE('',#20719,#20720); -#20719 = CARTESIAN_POINT('',(-4.018951266039,-0.449011437739)); -#20720 = VECTOR('',#20721,1.); -#20721 = DIRECTION('',(0.E+000,1.)); -#20722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20723 = ORIENTED_EDGE('',*,*,#18056,.T.); -#20724 = ORIENTED_EDGE('',*,*,#20647,.T.); -#20725 = ORIENTED_EDGE('',*,*,#20577,.F.); -#20726 = ADVANCED_FACE('',(#20727,#20751),#17723,.T.); -#20727 = FACE_BOUND('',#20728,.T.); -#20728 = EDGE_LOOP('',(#20729,#20730)); -#20729 = ORIENTED_EDGE('',*,*,#20469,.F.); -#20730 = ORIENTED_EDGE('',*,*,#20731,.F.); -#20731 = EDGE_CURVE('',#20472,#20470,#20732,.T.); -#20732 = SURFACE_CURVE('',#20733,(#20738,#20745),.PCURVE_S1.); -#20733 = CIRCLE('',#20734,5.078251810705E-004); -#20734 = AXIS2_PLACEMENT_3D('',#20735,#20736,#20737); -#20735 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); -#20736 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20737 = DIRECTION('',(1.,0.E+000,0.E+000)); -#20738 = PCURVE('',#17723,#20739); -#20739 = DEFINITIONAL_REPRESENTATION('',(#20740),#20744); -#20740 = CIRCLE('',#20741,5.078251810673E-004); -#20741 = AXIS2_PLACEMENT_2D('',#20742,#20743); -#20742 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); -#20743 = DIRECTION('',(-1.,0.E+000)); -#20744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20745 = PCURVE('',#20514,#20746); -#20746 = DEFINITIONAL_REPRESENTATION('',(#20747),#20750); -#20747 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20748,#20749),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#20748 = CARTESIAN_POINT('',(0.E+000,1.099449536121)); -#20749 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); -#20750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20751 = FACE_BOUND('',#20752,.T.); -#20752 = EDGE_LOOP('',(#20753,#20754,#20755,#20756,#20777,#20778,#20779, - #20780,#20781,#20782,#20803,#20804,#20805,#20806,#20807,#20808, - #20809,#20832,#20853,#20854)); -#20753 = ORIENTED_EDGE('',*,*,#18084,.F.); -#20754 = ORIENTED_EDGE('',*,*,#20703,.T.); -#20755 = ORIENTED_EDGE('',*,*,#20547,.T.); -#20756 = ORIENTED_EDGE('',*,*,#20757,.F.); -#20757 = EDGE_CURVE('',#17978,#20550,#20758,.T.); -#20758 = SURFACE_CURVE('',#20759,(#20763,#20770),.PCURVE_S1.); -#20759 = LINE('',#20760,#20761); -#20760 = CARTESIAN_POINT('',(55.538908,22.495721,0.45)); -#20761 = VECTOR('',#20762,1.); -#20762 = DIRECTION('',(0.E+000,0.E+000,1.)); -#20763 = PCURVE('',#17723,#20764); -#20764 = DEFINITIONAL_REPRESENTATION('',(#20765),#20769); -#20765 = LINE('',#20766,#20767); -#20766 = CARTESIAN_POINT('',(-4.618951266039,-0.449011437739)); -#20767 = VECTOR('',#20768,1.); -#20768 = DIRECTION('',(0.E+000,1.)); -#20769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20770 = PCURVE('',#18016,#20771); -#20771 = DEFINITIONAL_REPRESENTATION('',(#20772),#20776); -#20772 = LINE('',#20773,#20774); -#20773 = CARTESIAN_POINT('',(-2.2,0.E+000)); -#20774 = VECTOR('',#20775,1.); -#20775 = DIRECTION('',(1.,0.E+000)); -#20776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#22932 = CARTESIAN_POINT('',(0.E+000,-0.150550463879)); +#22933 = CARTESIAN_POINT('',(0.E+000,1.099449536121)); +#22934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22935 = ADVANCED_FACE('',(#22936),#22950,.T.); +#22936 = FACE_BOUND('',#22937,.T.); +#22937 = EDGE_LOOP('',(#22938,#22968,#22991,#23014)); +#22938 = ORIENTED_EDGE('',*,*,#22939,.F.); +#22939 = EDGE_CURVE('',#22940,#22942,#22944,.T.); +#22940 = VERTEX_POINT('',#22941); +#22941 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); +#22942 = VERTEX_POINT('',#22943); +#22943 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); +#22944 = SURFACE_CURVE('',#22945,(#22949,#22961),.PCURVE_S1.); +#22945 = LINE('',#22946,#22947); +#22946 = CARTESIAN_POINT('',(52.448908,22.495721,2.65)); +#22947 = VECTOR('',#22948,1.); +#22948 = DIRECTION('',(1.,0.E+000,0.E+000)); +#22949 = PCURVE('',#22950,#22955); +#22950 = PLANE('',#22951); +#22951 = AXIS2_PLACEMENT_3D('',#22952,#22953,#22954); +#22952 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); +#22953 = DIRECTION('',(0.E+000,0.E+000,1.)); +#22954 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#22955 = DEFINITIONAL_REPRESENTATION('',(#22956),#22960); +#22956 = LINE('',#22957,#22958); +#22957 = CARTESIAN_POINT('',(2.49,0.E+000)); +#22958 = VECTOR('',#22959,1.); +#22959 = DIRECTION('',(-1.,0.E+000)); +#22960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22961 = PCURVE('',#20115,#22962); +#22962 = DEFINITIONAL_REPRESENTATION('',(#22963),#22967); +#22963 = LINE('',#22964,#22965); +#22964 = CARTESIAN_POINT('',(-1.528951266039,1.750988562261)); +#22965 = VECTOR('',#22966,1.); +#22966 = DIRECTION('',(-1.,0.E+000)); +#22967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22968 = ORIENTED_EDGE('',*,*,#22969,.T.); +#22969 = EDGE_CURVE('',#22940,#22970,#22972,.T.); +#22970 = VERTEX_POINT('',#22971); +#22971 = CARTESIAN_POINT('',(54.938908,22.345721,2.65)); +#22972 = SURFACE_CURVE('',#22973,(#22977,#22984),.PCURVE_S1.); +#22973 = LINE('',#22974,#22975); +#22974 = CARTESIAN_POINT('',(54.938908,22.495721,2.65)); +#22975 = VECTOR('',#22976,1.); +#22976 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#22977 = PCURVE('',#22950,#22978); +#22978 = DEFINITIONAL_REPRESENTATION('',(#22979),#22983); +#22979 = LINE('',#22980,#22981); +#22980 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#22981 = VECTOR('',#22982,1.); +#22982 = DIRECTION('',(0.E+000,1.)); +#22983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22984 = PCURVE('',#20464,#22985); +#22985 = DEFINITIONAL_REPRESENTATION('',(#22986),#22990); +#22986 = LINE('',#22987,#22988); +#22987 = CARTESIAN_POINT('',(-1.15,0.E+000)); +#22988 = VECTOR('',#22989,1.); +#22989 = DIRECTION('',(0.E+000,1.)); +#22990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#22991 = ORIENTED_EDGE('',*,*,#22992,.T.); +#22992 = EDGE_CURVE('',#22970,#22993,#22995,.T.); +#22993 = VERTEX_POINT('',#22994); +#22994 = CARTESIAN_POINT('',(55.538908,22.345721,2.65)); +#22995 = SURFACE_CURVE('',#22996,(#23000,#23007),.PCURVE_S1.); +#22996 = LINE('',#22997,#22998); +#22997 = CARTESIAN_POINT('',(52.448908,22.345721,2.65)); +#22998 = VECTOR('',#22999,1.); +#22999 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23000 = PCURVE('',#22950,#23001); +#23001 = DEFINITIONAL_REPRESENTATION('',(#23002),#23006); +#23002 = LINE('',#23003,#23004); +#23003 = CARTESIAN_POINT('',(2.49,0.15)); +#23004 = VECTOR('',#23005,1.); +#23005 = DIRECTION('',(-1.,0.E+000)); +#23006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23007 = PCURVE('',#20436,#23008); +#23008 = DEFINITIONAL_REPRESENTATION('',(#23009),#23013); +#23009 = LINE('',#23010,#23011); +#23010 = CARTESIAN_POINT('',(-1.528951266039,1.750988562261)); +#23011 = VECTOR('',#23012,1.); +#23012 = DIRECTION('',(-1.,0.E+000)); +#23013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23014 = ORIENTED_EDGE('',*,*,#23015,.F.); +#23015 = EDGE_CURVE('',#22942,#22993,#23016,.T.); +#23016 = SURFACE_CURVE('',#23017,(#23021,#23028),.PCURVE_S1.); +#23017 = LINE('',#23018,#23019); +#23018 = CARTESIAN_POINT('',(55.538908,22.495721,2.65)); +#23019 = VECTOR('',#23020,1.); +#23020 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23021 = PCURVE('',#22950,#23022); +#23022 = DEFINITIONAL_REPRESENTATION('',(#23023),#23027); +#23023 = LINE('',#23024,#23025); +#23024 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#23025 = VECTOR('',#23026,1.); +#23026 = DIRECTION('',(0.E+000,1.)); +#23027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23028 = PCURVE('',#20408,#23029); +#23029 = DEFINITIONAL_REPRESENTATION('',(#23030),#23034); +#23030 = LINE('',#23031,#23032); +#23031 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#23032 = VECTOR('',#23033,1.); +#23033 = DIRECTION('',(0.E+000,1.)); +#23034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23035 = ADVANCED_FACE('',(#23036),#20436,.F.); +#23036 = FACE_BOUND('',#23037,.T.); +#23037 = EDGE_LOOP('',(#23038,#23059,#23060,#23081)); +#23038 = ORIENTED_EDGE('',*,*,#23039,.F.); +#23039 = EDGE_CURVE('',#20421,#22970,#23040,.T.); +#23040 = SURFACE_CURVE('',#23041,(#23045,#23052),.PCURVE_S1.); +#23041 = LINE('',#23042,#23043); +#23042 = CARTESIAN_POINT('',(54.938908,22.345721,0.45)); +#23043 = VECTOR('',#23044,1.); +#23044 = DIRECTION('',(0.E+000,0.E+000,1.)); +#23045 = PCURVE('',#20436,#23046); +#23046 = DEFINITIONAL_REPRESENTATION('',(#23047),#23051); +#23047 = LINE('',#23048,#23049); +#23048 = CARTESIAN_POINT('',(-4.018951266039,-0.449011437739)); +#23049 = VECTOR('',#23050,1.); +#23050 = DIRECTION('',(0.E+000,1.)); +#23051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20777 = ORIENTED_EDGE('',*,*,#17977,.F.); -#20778 = ORIENTED_EDGE('',*,*,#19259,.F.); -#20779 = ORIENTED_EDGE('',*,*,#17819,.F.); -#20780 = ORIENTED_EDGE('',*,*,#19078,.F.); -#20781 = ORIENTED_EDGE('',*,*,#18955,.T.); -#20782 = ORIENTED_EDGE('',*,*,#20783,.T.); -#20783 = EDGE_CURVE('',#18958,#17708,#20784,.T.); -#20784 = SURFACE_CURVE('',#20785,(#20789,#20796),.PCURVE_S1.); -#20785 = LINE('',#20786,#20787); -#20786 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); -#20787 = VECTOR('',#20788,1.); -#20788 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20789 = PCURVE('',#17723,#20790); -#20790 = DEFINITIONAL_REPRESENTATION('',(#20791),#20795); -#20791 = LINE('',#20792,#20793); -#20792 = CARTESIAN_POINT('',(-5.818951266039,-0.699011437739)); -#20793 = VECTOR('',#20794,1.); -#20794 = DIRECTION('',(1.,0.E+000)); -#20795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20796 = PCURVE('',#17751,#20797); -#20797 = DEFINITIONAL_REPRESENTATION('',(#20798),#20802); -#20798 = LINE('',#20799,#20800); -#20799 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#20800 = VECTOR('',#20801,1.); -#20801 = DIRECTION('',(-1.,0.E+000)); -#20802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20803 = ORIENTED_EDGE('',*,*,#17707,.F.); -#20804 = ORIENTED_EDGE('',*,*,#19105,.F.); -#20805 = ORIENTED_EDGE('',*,*,#18318,.F.); -#20806 = ORIENTED_EDGE('',*,*,#19321,.F.); -#20807 = ORIENTED_EDGE('',*,*,#18294,.F.); -#20808 = ORIENTED_EDGE('',*,*,#19234,.F.); -#20809 = ORIENTED_EDGE('',*,*,#20810,.F.); -#20810 = EDGE_CURVE('',#20811,#19212,#20813,.T.); -#20811 = VERTEX_POINT('',#20812); -#20812 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); -#20813 = SURFACE_CURVE('',#20814,(#20818,#20825),.PCURVE_S1.); -#20814 = LINE('',#20815,#20816); -#20815 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); -#20816 = VECTOR('',#20817,1.); -#20817 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#20818 = PCURVE('',#17723,#20819); -#20819 = DEFINITIONAL_REPRESENTATION('',(#20820),#20824); -#20820 = LINE('',#20821,#20822); -#20821 = CARTESIAN_POINT('',(-2.818951266039,1.100988562261)); -#20822 = VECTOR('',#20823,1.); -#20823 = DIRECTION('',(0.E+000,-1.)); -#20824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20825 = PCURVE('',#19173,#20826); -#20826 = DEFINITIONAL_REPRESENTATION('',(#20827),#20831); -#20827 = LINE('',#20828,#20829); -#20828 = CARTESIAN_POINT('',(-1.8,0.E+000)); -#20829 = VECTOR('',#20830,1.); -#20830 = DIRECTION('',(1.,0.E+000)); -#20831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20832 = ORIENTED_EDGE('',*,*,#20833,.F.); -#20833 = EDGE_CURVE('',#18188,#20811,#20834,.T.); -#20834 = SURFACE_CURVE('',#20835,(#20839,#20846),.PCURVE_S1.); -#20835 = LINE('',#20836,#20837); -#20836 = CARTESIAN_POINT('',(54.188908,22.495721,2.)); -#20837 = VECTOR('',#20838,1.); -#20838 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20839 = PCURVE('',#17723,#20840); -#20840 = DEFINITIONAL_REPRESENTATION('',(#20841),#20845); -#20841 = LINE('',#20842,#20843); -#20842 = CARTESIAN_POINT('',(-3.268951266039,1.100988562261)); -#20843 = VECTOR('',#20844,1.); -#20844 = DIRECTION('',(1.,0.E+000)); -#20845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20846 = PCURVE('',#18226,#20847); -#20847 = DEFINITIONAL_REPRESENTATION('',(#20848),#20852); -#20848 = LINE('',#20849,#20850); -#20849 = CARTESIAN_POINT('',(-0.45,0.E+000)); -#20850 = VECTOR('',#20851,1.); -#20851 = DIRECTION('',(1.,0.E+000)); -#20852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20853 = ORIENTED_EDGE('',*,*,#18187,.F.); -#20854 = ORIENTED_EDGE('',*,*,#19290,.F.); -#20855 = ADVANCED_FACE('',(#20856),#19630,.T.); -#20856 = FACE_BOUND('',#20857,.T.); -#20857 = EDGE_LOOP('',(#20858,#20859,#20902,#20903)); -#20858 = ORIENTED_EDGE('',*,*,#19615,.T.); -#20859 = ORIENTED_EDGE('',*,*,#20860,.F.); -#20860 = EDGE_CURVE('',#19501,#19499,#20861,.T.); -#20861 = SURFACE_CURVE('',#20862,(#20867,#20896),.PCURVE_S1.); -#20862 = CIRCLE('',#20863,1.); -#20863 = AXIS2_PLACEMENT_3D('',#20864,#20865,#20866); -#20864 = CARTESIAN_POINT('',(55.238908,22.015721,1.1)); -#20865 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20866 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20867 = PCURVE('',#19630,#20868); -#20868 = DEFINITIONAL_REPRESENTATION('',(#20869),#20895); -#20869 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#20870,#20871,#20872,#20873, - #20874,#20875,#20876,#20877,#20878,#20879,#20880,#20881,#20882, - #20883,#20884,#20885,#20886,#20887,#20888,#20889,#20890,#20891, - #20892,#20893,#20894),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23052 = PCURVE('',#20464,#23053); +#23053 = DEFINITIONAL_REPRESENTATION('',(#23054),#23058); +#23054 = LINE('',#23055,#23056); +#23055 = CARTESIAN_POINT('',(1.05,0.15)); +#23056 = VECTOR('',#23057,1.); +#23057 = DIRECTION('',(-1.,0.E+000)); +#23058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23059 = ORIENTED_EDGE('',*,*,#20420,.F.); +#23060 = ORIENTED_EDGE('',*,*,#23061,.T.); +#23061 = EDGE_CURVE('',#20393,#22993,#23062,.T.); +#23062 = SURFACE_CURVE('',#23063,(#23067,#23074),.PCURVE_S1.); +#23063 = LINE('',#23064,#23065); +#23064 = CARTESIAN_POINT('',(55.538908,22.345721,0.45)); +#23065 = VECTOR('',#23066,1.); +#23066 = DIRECTION('',(0.E+000,0.E+000,1.)); +#23067 = PCURVE('',#20436,#23068); +#23068 = DEFINITIONAL_REPRESENTATION('',(#23069),#23073); +#23069 = LINE('',#23070,#23071); +#23070 = CARTESIAN_POINT('',(-4.618951266039,-0.449011437739)); +#23071 = VECTOR('',#23072,1.); +#23072 = DIRECTION('',(0.E+000,1.)); +#23073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23074 = PCURVE('',#20408,#23075); +#23075 = DEFINITIONAL_REPRESENTATION('',(#23076),#23080); +#23076 = LINE('',#23077,#23078); +#23077 = CARTESIAN_POINT('',(-2.2,0.15)); +#23078 = VECTOR('',#23079,1.); +#23079 = DIRECTION('',(1.,0.E+000)); +#23080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23081 = ORIENTED_EDGE('',*,*,#22992,.F.); +#23082 = ADVANCED_FACE('',(#23083),#21156,.F.); +#23083 = FACE_BOUND('',#23084,.T.); +#23084 = EDGE_LOOP('',(#23085,#23086,#23087,#23088,#23089,#23090)); +#23085 = ORIENTED_EDGE('',*,*,#21140,.T.); +#23086 = ORIENTED_EDGE('',*,*,#22809,.T.); +#23087 = ORIENTED_EDGE('',*,*,#22836,.T.); +#23088 = ORIENTED_EDGE('',*,*,#22738,.F.); +#23089 = ORIENTED_EDGE('',*,*,#21247,.F.); +#23090 = ORIENTED_EDGE('',*,*,#21962,.T.); +#23091 = ADVANCED_FACE('',(#23092),#20464,.T.); +#23092 = FACE_BOUND('',#23093,.T.); +#23093 = EDGE_LOOP('',(#23094,#23115,#23116,#23117)); +#23094 = ORIENTED_EDGE('',*,*,#23095,.F.); +#23095 = EDGE_CURVE('',#20449,#22940,#23096,.T.); +#23096 = SURFACE_CURVE('',#23097,(#23101,#23108),.PCURVE_S1.); +#23097 = LINE('',#23098,#23099); +#23098 = CARTESIAN_POINT('',(54.938908,22.495721,0.45)); +#23099 = VECTOR('',#23100,1.); +#23100 = DIRECTION('',(0.E+000,0.E+000,1.)); +#23101 = PCURVE('',#20464,#23102); +#23102 = DEFINITIONAL_REPRESENTATION('',(#23103),#23107); +#23103 = LINE('',#23104,#23105); +#23104 = CARTESIAN_POINT('',(1.05,0.E+000)); +#23105 = VECTOR('',#23106,1.); +#23106 = DIRECTION('',(-1.,0.E+000)); +#23107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23108 = PCURVE('',#20115,#23109); +#23109 = DEFINITIONAL_REPRESENTATION('',(#23110),#23114); +#23110 = LINE('',#23111,#23112); +#23111 = CARTESIAN_POINT('',(-4.018951266039,-0.449011437739)); +#23112 = VECTOR('',#23113,1.); +#23113 = DIRECTION('',(0.E+000,1.)); +#23114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23115 = ORIENTED_EDGE('',*,*,#20448,.T.); +#23116 = ORIENTED_EDGE('',*,*,#23039,.T.); +#23117 = ORIENTED_EDGE('',*,*,#22969,.F.); +#23118 = ADVANCED_FACE('',(#23119,#23143),#20115,.T.); +#23119 = FACE_BOUND('',#23120,.T.); +#23120 = EDGE_LOOP('',(#23121,#23122)); +#23121 = ORIENTED_EDGE('',*,*,#22861,.F.); +#23122 = ORIENTED_EDGE('',*,*,#23123,.F.); +#23123 = EDGE_CURVE('',#22864,#22862,#23124,.T.); +#23124 = SURFACE_CURVE('',#23125,(#23130,#23137),.PCURVE_S1.); +#23125 = CIRCLE('',#23126,5.078251810705E-004); +#23126 = AXIS2_PLACEMENT_3D('',#23127,#23128,#23129); +#23127 = CARTESIAN_POINT('',(55.238908,22.495721,1.1)); +#23128 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23129 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23130 = PCURVE('',#20115,#23131); +#23131 = DEFINITIONAL_REPRESENTATION('',(#23132),#23136); +#23132 = CIRCLE('',#23133,5.078251810673E-004); +#23133 = AXIS2_PLACEMENT_2D('',#23134,#23135); +#23134 = CARTESIAN_POINT('',(-4.318951266039,0.200988562261)); +#23135 = DIRECTION('',(-1.,0.E+000)); +#23136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23137 = PCURVE('',#22906,#23138); +#23138 = DEFINITIONAL_REPRESENTATION('',(#23139),#23142); +#23139 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23140,#23141),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); +#23140 = CARTESIAN_POINT('',(0.E+000,1.099449536121)); +#23141 = CARTESIAN_POINT('',(3.14159265359,1.099449536121)); +#23142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23143 = FACE_BOUND('',#23144,.T.); +#23144 = EDGE_LOOP('',(#23145,#23146,#23147,#23148,#23169,#23170,#23171, + #23172,#23173,#23174,#23195,#23196,#23197,#23198,#23199,#23200, + #23201,#23224,#23245,#23246)); +#23145 = ORIENTED_EDGE('',*,*,#20476,.F.); +#23146 = ORIENTED_EDGE('',*,*,#23095,.T.); +#23147 = ORIENTED_EDGE('',*,*,#22939,.T.); +#23148 = ORIENTED_EDGE('',*,*,#23149,.F.); +#23149 = EDGE_CURVE('',#20370,#22942,#23150,.T.); +#23150 = SURFACE_CURVE('',#23151,(#23155,#23162),.PCURVE_S1.); +#23151 = LINE('',#23152,#23153); +#23152 = CARTESIAN_POINT('',(55.538908,22.495721,0.45)); +#23153 = VECTOR('',#23154,1.); +#23154 = DIRECTION('',(0.E+000,0.E+000,1.)); +#23155 = PCURVE('',#20115,#23156); +#23156 = DEFINITIONAL_REPRESENTATION('',(#23157),#23161); +#23157 = LINE('',#23158,#23159); +#23158 = CARTESIAN_POINT('',(-4.618951266039,-0.449011437739)); +#23159 = VECTOR('',#23160,1.); +#23160 = DIRECTION('',(0.E+000,1.)); +#23161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23162 = PCURVE('',#20408,#23163); +#23163 = DEFINITIONAL_REPRESENTATION('',(#23164),#23168); +#23164 = LINE('',#23165,#23166); +#23165 = CARTESIAN_POINT('',(-2.2,0.E+000)); +#23166 = VECTOR('',#23167,1.); +#23167 = DIRECTION('',(1.,0.E+000)); +#23168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23169 = ORIENTED_EDGE('',*,*,#20369,.F.); +#23170 = ORIENTED_EDGE('',*,*,#21651,.F.); +#23171 = ORIENTED_EDGE('',*,*,#20211,.F.); +#23172 = ORIENTED_EDGE('',*,*,#21470,.F.); +#23173 = ORIENTED_EDGE('',*,*,#21347,.T.); +#23174 = ORIENTED_EDGE('',*,*,#23175,.T.); +#23175 = EDGE_CURVE('',#21350,#20100,#23176,.T.); +#23176 = SURFACE_CURVE('',#23177,(#23181,#23188),.PCURVE_S1.); +#23177 = LINE('',#23178,#23179); +#23178 = CARTESIAN_POINT('',(56.738908,22.495721,0.2)); +#23179 = VECTOR('',#23180,1.); +#23180 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23181 = PCURVE('',#20115,#23182); +#23182 = DEFINITIONAL_REPRESENTATION('',(#23183),#23187); +#23183 = LINE('',#23184,#23185); +#23184 = CARTESIAN_POINT('',(-5.818951266039,-0.699011437739)); +#23185 = VECTOR('',#23186,1.); +#23186 = DIRECTION('',(1.,0.E+000)); +#23187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23188 = PCURVE('',#20143,#23189); +#23189 = DEFINITIONAL_REPRESENTATION('',(#23190),#23194); +#23190 = LINE('',#23191,#23192); +#23191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#23192 = VECTOR('',#23193,1.); +#23193 = DIRECTION('',(-1.,0.E+000)); +#23194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23195 = ORIENTED_EDGE('',*,*,#20099,.F.); +#23196 = ORIENTED_EDGE('',*,*,#21497,.F.); +#23197 = ORIENTED_EDGE('',*,*,#20710,.F.); +#23198 = ORIENTED_EDGE('',*,*,#21713,.F.); +#23199 = ORIENTED_EDGE('',*,*,#20686,.F.); +#23200 = ORIENTED_EDGE('',*,*,#21626,.F.); +#23201 = ORIENTED_EDGE('',*,*,#23202,.F.); +#23202 = EDGE_CURVE('',#23203,#21604,#23205,.T.); +#23203 = VERTEX_POINT('',#23204); +#23204 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); +#23205 = SURFACE_CURVE('',#23206,(#23210,#23217),.PCURVE_S1.); +#23206 = LINE('',#23207,#23208); +#23207 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); +#23208 = VECTOR('',#23209,1.); +#23209 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#23210 = PCURVE('',#20115,#23211); +#23211 = DEFINITIONAL_REPRESENTATION('',(#23212),#23216); +#23212 = LINE('',#23213,#23214); +#23213 = CARTESIAN_POINT('',(-2.818951266039,1.100988562261)); +#23214 = VECTOR('',#23215,1.); +#23215 = DIRECTION('',(0.E+000,-1.)); +#23216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23217 = PCURVE('',#21565,#23218); +#23218 = DEFINITIONAL_REPRESENTATION('',(#23219),#23223); +#23219 = LINE('',#23220,#23221); +#23220 = CARTESIAN_POINT('',(-1.8,0.E+000)); +#23221 = VECTOR('',#23222,1.); +#23222 = DIRECTION('',(1.,0.E+000)); +#23223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23224 = ORIENTED_EDGE('',*,*,#23225,.F.); +#23225 = EDGE_CURVE('',#20580,#23203,#23226,.T.); +#23226 = SURFACE_CURVE('',#23227,(#23231,#23238),.PCURVE_S1.); +#23227 = LINE('',#23228,#23229); +#23228 = CARTESIAN_POINT('',(54.188908,22.495721,2.)); +#23229 = VECTOR('',#23230,1.); +#23230 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23231 = PCURVE('',#20115,#23232); +#23232 = DEFINITIONAL_REPRESENTATION('',(#23233),#23237); +#23233 = LINE('',#23234,#23235); +#23234 = CARTESIAN_POINT('',(-3.268951266039,1.100988562261)); +#23235 = VECTOR('',#23236,1.); +#23236 = DIRECTION('',(1.,0.E+000)); +#23237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23238 = PCURVE('',#20618,#23239); +#23239 = DEFINITIONAL_REPRESENTATION('',(#23240),#23244); +#23240 = LINE('',#23241,#23242); +#23241 = CARTESIAN_POINT('',(-0.45,0.E+000)); +#23242 = VECTOR('',#23243,1.); +#23243 = DIRECTION('',(1.,0.E+000)); +#23244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23245 = ORIENTED_EDGE('',*,*,#20579,.F.); +#23246 = ORIENTED_EDGE('',*,*,#21682,.F.); +#23247 = ADVANCED_FACE('',(#23248),#22022,.T.); +#23248 = FACE_BOUND('',#23249,.T.); +#23249 = EDGE_LOOP('',(#23250,#23251,#23294,#23295)); +#23250 = ORIENTED_EDGE('',*,*,#22007,.T.); +#23251 = ORIENTED_EDGE('',*,*,#23252,.F.); +#23252 = EDGE_CURVE('',#21893,#21891,#23253,.T.); +#23253 = SURFACE_CURVE('',#23254,(#23259,#23288),.PCURVE_S1.); +#23254 = CIRCLE('',#23255,1.); +#23255 = AXIS2_PLACEMENT_3D('',#23256,#23257,#23258); +#23256 = CARTESIAN_POINT('',(55.238908,22.015721,1.1)); +#23257 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23258 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23259 = PCURVE('',#22022,#23260); +#23260 = DEFINITIONAL_REPRESENTATION('',(#23261),#23287); +#23261 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23262,#23263,#23264,#23265, + #23266,#23267,#23268,#23269,#23270,#23271,#23272,#23273,#23274, + #23275,#23276,#23277,#23278,#23279,#23280,#23281,#23282,#23283, + #23284,#23285,#23286),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -25595,58 +28584,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#20870 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#20871 = CARTESIAN_POINT('',(3.189192542281,7.E-002)); -#20872 = CARTESIAN_POINT('',(3.284392319662,7.E-002)); -#20873 = CARTESIAN_POINT('',(3.427191985734,7.E-002)); -#20874 = CARTESIAN_POINT('',(3.569991651807,7.E-002)); -#20875 = CARTESIAN_POINT('',(3.712791317879,7.E-002)); -#20876 = CARTESIAN_POINT('',(3.855590983951,7.E-002)); -#20877 = CARTESIAN_POINT('',(3.998390650023,7.E-002)); -#20878 = CARTESIAN_POINT('',(4.141190316096,7.E-002)); -#20879 = CARTESIAN_POINT('',(4.283989982168,7.E-002)); -#20880 = CARTESIAN_POINT('',(4.42678964824,7.E-002)); -#20881 = CARTESIAN_POINT('',(4.569589314312,7.E-002)); -#20882 = CARTESIAN_POINT('',(4.712388980385,7.E-002)); -#20883 = CARTESIAN_POINT('',(4.855188646457,7.E-002)); -#20884 = CARTESIAN_POINT('',(4.997988312529,7.E-002)); -#20885 = CARTESIAN_POINT('',(5.140787978601,7.E-002)); -#20886 = CARTESIAN_POINT('',(5.283587644674,7.E-002)); -#20887 = CARTESIAN_POINT('',(5.426387310746,7.E-002)); -#20888 = CARTESIAN_POINT('',(5.569186976818,7.E-002)); -#20889 = CARTESIAN_POINT('',(5.711986642891,7.E-002)); -#20890 = CARTESIAN_POINT('',(5.854786308963,7.E-002)); -#20891 = CARTESIAN_POINT('',(5.997585975035,7.E-002)); -#20892 = CARTESIAN_POINT('',(6.140385641107,7.E-002)); -#20893 = CARTESIAN_POINT('',(6.235585418489,7.E-002)); -#20894 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); -#20895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20896 = PCURVE('',#18821,#20897); -#20897 = DEFINITIONAL_REPRESENTATION('',(#20898),#20901); -#20898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20899,#20900),.UNSPECIFIED., +#23262 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#23263 = CARTESIAN_POINT('',(3.189192542281,7.E-002)); +#23264 = CARTESIAN_POINT('',(3.284392319662,7.E-002)); +#23265 = CARTESIAN_POINT('',(3.427191985734,7.E-002)); +#23266 = CARTESIAN_POINT('',(3.569991651807,7.E-002)); +#23267 = CARTESIAN_POINT('',(3.712791317879,7.E-002)); +#23268 = CARTESIAN_POINT('',(3.855590983951,7.E-002)); +#23269 = CARTESIAN_POINT('',(3.998390650023,7.E-002)); +#23270 = CARTESIAN_POINT('',(4.141190316096,7.E-002)); +#23271 = CARTESIAN_POINT('',(4.283989982168,7.E-002)); +#23272 = CARTESIAN_POINT('',(4.42678964824,7.E-002)); +#23273 = CARTESIAN_POINT('',(4.569589314312,7.E-002)); +#23274 = CARTESIAN_POINT('',(4.712388980385,7.E-002)); +#23275 = CARTESIAN_POINT('',(4.855188646457,7.E-002)); +#23276 = CARTESIAN_POINT('',(4.997988312529,7.E-002)); +#23277 = CARTESIAN_POINT('',(5.140787978601,7.E-002)); +#23278 = CARTESIAN_POINT('',(5.283587644674,7.E-002)); +#23279 = CARTESIAN_POINT('',(5.426387310746,7.E-002)); +#23280 = CARTESIAN_POINT('',(5.569186976818,7.E-002)); +#23281 = CARTESIAN_POINT('',(5.711986642891,7.E-002)); +#23282 = CARTESIAN_POINT('',(5.854786308963,7.E-002)); +#23283 = CARTESIAN_POINT('',(5.997585975035,7.E-002)); +#23284 = CARTESIAN_POINT('',(6.140385641107,7.E-002)); +#23285 = CARTESIAN_POINT('',(6.235585418489,7.E-002)); +#23286 = CARTESIAN_POINT('',(6.28318530718,7.E-002)); +#23287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23288 = PCURVE('',#21213,#23289); +#23289 = DEFINITIONAL_REPRESENTATION('',(#23290),#23293); +#23290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23291,#23292),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#20899 = CARTESIAN_POINT('',(0.E+000,-0.48)); -#20900 = CARTESIAN_POINT('',(3.14159265359,-0.48)); -#20901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20902 = ORIENTED_EDGE('',*,*,#19691,.F.); -#20903 = ORIENTED_EDGE('',*,*,#20904,.T.); -#20904 = EDGE_CURVE('',#19642,#19616,#20905,.T.); -#20905 = SURFACE_CURVE('',#20906,(#20911,#20940),.PCURVE_S1.); -#20906 = CIRCLE('',#20907,0.93); -#20907 = AXIS2_PLACEMENT_3D('',#20908,#20909,#20910); -#20908 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); -#20909 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20910 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20911 = PCURVE('',#19630,#20912); -#20912 = DEFINITIONAL_REPRESENTATION('',(#20913),#20939); -#20913 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#20914,#20915,#20916,#20917, - #20918,#20919,#20920,#20921,#20922,#20923,#20924,#20925,#20926, - #20927,#20928,#20929,#20930,#20931,#20932,#20933,#20934,#20935, - #20936,#20937,#20938),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23291 = CARTESIAN_POINT('',(0.E+000,-0.48)); +#23292 = CARTESIAN_POINT('',(3.14159265359,-0.48)); +#23293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23294 = ORIENTED_EDGE('',*,*,#22083,.F.); +#23295 = ORIENTED_EDGE('',*,*,#23296,.T.); +#23296 = EDGE_CURVE('',#22034,#22008,#23297,.T.); +#23297 = SURFACE_CURVE('',#23298,(#23303,#23332),.PCURVE_S1.); +#23298 = CIRCLE('',#23299,0.93); +#23299 = AXIS2_PLACEMENT_3D('',#23300,#23301,#23302); +#23300 = CARTESIAN_POINT('',(55.238908,21.945721,1.1)); +#23301 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23302 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23303 = PCURVE('',#22022,#23304); +#23304 = DEFINITIONAL_REPRESENTATION('',(#23305),#23331); +#23305 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23306,#23307,#23308,#23309, + #23310,#23311,#23312,#23313,#23314,#23315,#23316,#23317,#23318, + #23319,#23320,#23321,#23322,#23323,#23324,#23325,#23326,#23327, + #23328,#23329,#23330),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -25654,77 +28643,77 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#20914 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); -#20915 = CARTESIAN_POINT('',(3.189192542281,9.114526263361E-016)); -#20916 = CARTESIAN_POINT('',(3.284392319662,1.393305971736E-015)); -#20917 = CARTESIAN_POINT('',(3.427191985734,-4.866363046809E-016)); -#20918 = CARTESIAN_POINT('',(3.569991651807,-1.759038726272E-015)); -#20919 = CARTESIAN_POINT('',(3.712791317879,-1.980837143263E-015)); -#20920 = CARTESIAN_POINT('',(3.855590983951,2.058928143707E-015)); -#20921 = CARTESIAN_POINT('',(3.998390650023,-7.130844471248E-016)); -#20922 = CARTESIAN_POINT('',(4.141190316096,-5.113734596861E-016)); -#20923 = CARTESIAN_POINT('',(4.283989982168,9.797277814721E-016)); -#20924 = CARTESIAN_POINT('',(4.42678964824,-7.256009622334E-016)); -#20925 = CARTESIAN_POINT('',(4.569589314312,-8.499530543832E-017)); -#20926 = CARTESIAN_POINT('',(4.712388980385,1.257415307677E-016)); -#20927 = CARTESIAN_POINT('',(4.855188646457,-8.490391024483E-017)); -#20928 = CARTESIAN_POINT('',(4.997988312529,-7.258039126815E-016)); -#20929 = CARTESIAN_POINT('',(5.140787978601,9.802855577451E-016)); -#20930 = CARTESIAN_POINT('',(5.283587644674,-5.1340161433E-016)); -#20931 = CARTESIAN_POINT('',(5.426387310746,-7.055296048221E-016)); -#20932 = CARTESIAN_POINT('',(5.569186976818,2.030899559467E-015)); -#20933 = CARTESIAN_POINT('',(5.711986642891,-1.876277648602E-015)); -#20934 = CARTESIAN_POINT('',(5.854786308963,-1.789021948865E-015)); -#20935 = CARTESIAN_POINT('',(5.997585975035,-4.711002786428E-016)); -#20936 = CARTESIAN_POINT('',(6.140385641107,1.361145090176E-015)); -#20937 = CARTESIAN_POINT('',(6.235585418489,9.76245752833E-016)); -#20938 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#20939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20940 = PCURVE('',#19729,#20941); -#20941 = DEFINITIONAL_REPRESENTATION('',(#20942),#20945); -#20942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20943,#20944),.UNSPECIFIED., +#23306 = CARTESIAN_POINT('',(3.14159265359,-1.665334536938E-016)); +#23307 = CARTESIAN_POINT('',(3.189192542281,9.114526263361E-016)); +#23308 = CARTESIAN_POINT('',(3.284392319662,1.393305971736E-015)); +#23309 = CARTESIAN_POINT('',(3.427191985734,-4.866363046809E-016)); +#23310 = CARTESIAN_POINT('',(3.569991651807,-1.759038726272E-015)); +#23311 = CARTESIAN_POINT('',(3.712791317879,-1.980837143263E-015)); +#23312 = CARTESIAN_POINT('',(3.855590983951,2.058928143707E-015)); +#23313 = CARTESIAN_POINT('',(3.998390650023,-7.130844471248E-016)); +#23314 = CARTESIAN_POINT('',(4.141190316096,-5.113734596861E-016)); +#23315 = CARTESIAN_POINT('',(4.283989982168,9.797277814721E-016)); +#23316 = CARTESIAN_POINT('',(4.42678964824,-7.256009622334E-016)); +#23317 = CARTESIAN_POINT('',(4.569589314312,-8.499530543832E-017)); +#23318 = CARTESIAN_POINT('',(4.712388980385,1.257415307677E-016)); +#23319 = CARTESIAN_POINT('',(4.855188646457,-8.490391024483E-017)); +#23320 = CARTESIAN_POINT('',(4.997988312529,-7.258039126815E-016)); +#23321 = CARTESIAN_POINT('',(5.140787978601,9.802855577451E-016)); +#23322 = CARTESIAN_POINT('',(5.283587644674,-5.1340161433E-016)); +#23323 = CARTESIAN_POINT('',(5.426387310746,-7.055296048221E-016)); +#23324 = CARTESIAN_POINT('',(5.569186976818,2.030899559467E-015)); +#23325 = CARTESIAN_POINT('',(5.711986642891,-1.876277648602E-015)); +#23326 = CARTESIAN_POINT('',(5.854786308963,-1.789021948865E-015)); +#23327 = CARTESIAN_POINT('',(5.997585975035,-4.711002786428E-016)); +#23328 = CARTESIAN_POINT('',(6.140385641107,1.361145090176E-015)); +#23329 = CARTESIAN_POINT('',(6.235585418489,9.76245752833E-016)); +#23330 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#23331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23332 = PCURVE('',#22121,#23333); +#23333 = DEFINITIONAL_REPRESENTATION('',(#23334),#23337); +#23334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23335,#23336),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#20943 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); -#20944 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); -#20945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#20946 = ADVANCED_FACE('',(#20947),#18821,.T.); -#20947 = FACE_BOUND('',#20948,.T.); -#20948 = EDGE_LOOP('',(#20949,#20950,#20951,#20952)); -#20949 = ORIENTED_EDGE('',*,*,#19592,.T.); -#20950 = ORIENTED_EDGE('',*,*,#18804,.F.); -#20951 = ORIENTED_EDGE('',*,*,#19550,.F.); -#20952 = ORIENTED_EDGE('',*,*,#20860,.T.); -#20953 = ADVANCED_FACE('',(#20954),#19976,.T.); -#20954 = FACE_BOUND('',#20955,.T.); -#20955 = EDGE_LOOP('',(#20956,#20957,#21000,#21001)); -#20956 = ORIENTED_EDGE('',*,*,#19963,.F.); -#20957 = ORIENTED_EDGE('',*,*,#20958,.T.); -#20958 = EDGE_CURVE('',#19914,#19912,#20959,.T.); -#20959 = SURFACE_CURVE('',#20960,(#20965,#20971),.PCURVE_S1.); -#20960 = CIRCLE('',#20961,1.); -#20961 = AXIS2_PLACEMENT_3D('',#20962,#20963,#20964); -#20962 = CARTESIAN_POINT('',(55.238908,21.315721,1.1)); -#20963 = DIRECTION('',(0.E+000,1.,0.E+000)); -#20964 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#20965 = PCURVE('',#19976,#20966); -#20966 = DEFINITIONAL_REPRESENTATION('',(#20967),#20970); -#20967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#20968,#20969),.UNSPECIFIED., +#23335 = CARTESIAN_POINT('',(3.14159265359,5.E-002)); +#23336 = CARTESIAN_POINT('',(6.28318530718,5.E-002)); +#23337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23338 = ADVANCED_FACE('',(#23339),#21213,.T.); +#23339 = FACE_BOUND('',#23340,.T.); +#23340 = EDGE_LOOP('',(#23341,#23342,#23343,#23344)); +#23341 = ORIENTED_EDGE('',*,*,#21984,.T.); +#23342 = ORIENTED_EDGE('',*,*,#21196,.F.); +#23343 = ORIENTED_EDGE('',*,*,#21942,.F.); +#23344 = ORIENTED_EDGE('',*,*,#23252,.T.); +#23345 = ADVANCED_FACE('',(#23346),#22368,.T.); +#23346 = FACE_BOUND('',#23347,.T.); +#23347 = EDGE_LOOP('',(#23348,#23349,#23392,#23393)); +#23348 = ORIENTED_EDGE('',*,*,#22355,.F.); +#23349 = ORIENTED_EDGE('',*,*,#23350,.T.); +#23350 = EDGE_CURVE('',#22306,#22304,#23351,.T.); +#23351 = SURFACE_CURVE('',#23352,(#23357,#23363),.PCURVE_S1.); +#23352 = CIRCLE('',#23353,1.); +#23353 = AXIS2_PLACEMENT_3D('',#23354,#23355,#23356); +#23354 = CARTESIAN_POINT('',(55.238908,21.315721,1.1)); +#23355 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23356 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23357 = PCURVE('',#22368,#23358); +#23358 = DEFINITIONAL_REPRESENTATION('',(#23359),#23362); +#23359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23360,#23361),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#20968 = CARTESIAN_POINT('',(0.E+000,-1.18)); -#20969 = CARTESIAN_POINT('',(3.14159265359,-1.18)); -#20970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#23360 = CARTESIAN_POINT('',(0.E+000,-1.18)); +#23361 = CARTESIAN_POINT('',(3.14159265359,-1.18)); +#23362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#20971 = PCURVE('',#20076,#20972); -#20972 = DEFINITIONAL_REPRESENTATION('',(#20973),#20999); -#20973 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#20974,#20975,#20976,#20977, - #20978,#20979,#20980,#20981,#20982,#20983,#20984,#20985,#20986, - #20987,#20988,#20989,#20990,#20991,#20992,#20993,#20994,#20995, - #20996,#20997,#20998),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23363 = PCURVE('',#22468,#23364); +#23364 = DEFINITIONAL_REPRESENTATION('',(#23365),#23391); +#23365 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23366,#23367,#23368,#23369, + #23370,#23371,#23372,#23373,#23374,#23375,#23376,#23377,#23378, + #23379,#23380,#23381,#23382,#23383,#23384,#23385,#23386,#23387, + #23388,#23389,#23390),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -25732,58 +28721,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#20974 = CARTESIAN_POINT('',(0.E+000,7.E-002)); -#20975 = CARTESIAN_POINT('',(4.759988869075E-002,7.E-002)); -#20976 = CARTESIAN_POINT('',(0.142799666072,7.E-002)); -#20977 = CARTESIAN_POINT('',(0.285599332145,7.E-002)); -#20978 = CARTESIAN_POINT('',(0.428398998217,7.E-002)); -#20979 = CARTESIAN_POINT('',(0.571198664289,7.E-002)); -#20980 = CARTESIAN_POINT('',(0.713998330361,7.E-002)); -#20981 = CARTESIAN_POINT('',(0.856797996434,7.E-002)); -#20982 = CARTESIAN_POINT('',(0.999597662506,7.E-002)); -#20983 = CARTESIAN_POINT('',(1.142397328578,7.E-002)); -#20984 = CARTESIAN_POINT('',(1.28519699465,7.E-002)); -#20985 = CARTESIAN_POINT('',(1.427996660723,7.E-002)); -#20986 = CARTESIAN_POINT('',(1.570796326795,7.E-002)); -#20987 = CARTESIAN_POINT('',(1.713595992867,7.E-002)); -#20988 = CARTESIAN_POINT('',(1.856395658939,7.E-002)); -#20989 = CARTESIAN_POINT('',(1.999195325012,7.E-002)); -#20990 = CARTESIAN_POINT('',(2.141994991084,7.E-002)); -#20991 = CARTESIAN_POINT('',(2.284794657156,7.E-002)); -#20992 = CARTESIAN_POINT('',(2.427594323228,7.E-002)); -#20993 = CARTESIAN_POINT('',(2.570393989301,7.E-002)); -#20994 = CARTESIAN_POINT('',(2.713193655373,7.E-002)); -#20995 = CARTESIAN_POINT('',(2.855993321445,7.E-002)); -#20996 = CARTESIAN_POINT('',(2.998792987518,7.E-002)); -#20997 = CARTESIAN_POINT('',(3.093992764899,7.E-002)); -#20998 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); -#20999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21000 = ORIENTED_EDGE('',*,*,#19988,.T.); -#21001 = ORIENTED_EDGE('',*,*,#21002,.F.); -#21002 = EDGE_CURVE('',#19840,#19814,#21003,.T.); -#21003 = SURFACE_CURVE('',#21004,(#21009,#21015),.PCURVE_S1.); -#21004 = CIRCLE('',#21005,1.); -#21005 = AXIS2_PLACEMENT_3D('',#21006,#21007,#21008); -#21006 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); -#21007 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21008 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21009 = PCURVE('',#19976,#21010); -#21010 = DEFINITIONAL_REPRESENTATION('',(#21011),#21014); -#21011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21012,#21013),.UNSPECIFIED., +#23366 = CARTESIAN_POINT('',(0.E+000,7.E-002)); +#23367 = CARTESIAN_POINT('',(4.759988869075E-002,7.E-002)); +#23368 = CARTESIAN_POINT('',(0.142799666072,7.E-002)); +#23369 = CARTESIAN_POINT('',(0.285599332145,7.E-002)); +#23370 = CARTESIAN_POINT('',(0.428398998217,7.E-002)); +#23371 = CARTESIAN_POINT('',(0.571198664289,7.E-002)); +#23372 = CARTESIAN_POINT('',(0.713998330361,7.E-002)); +#23373 = CARTESIAN_POINT('',(0.856797996434,7.E-002)); +#23374 = CARTESIAN_POINT('',(0.999597662506,7.E-002)); +#23375 = CARTESIAN_POINT('',(1.142397328578,7.E-002)); +#23376 = CARTESIAN_POINT('',(1.28519699465,7.E-002)); +#23377 = CARTESIAN_POINT('',(1.427996660723,7.E-002)); +#23378 = CARTESIAN_POINT('',(1.570796326795,7.E-002)); +#23379 = CARTESIAN_POINT('',(1.713595992867,7.E-002)); +#23380 = CARTESIAN_POINT('',(1.856395658939,7.E-002)); +#23381 = CARTESIAN_POINT('',(1.999195325012,7.E-002)); +#23382 = CARTESIAN_POINT('',(2.141994991084,7.E-002)); +#23383 = CARTESIAN_POINT('',(2.284794657156,7.E-002)); +#23384 = CARTESIAN_POINT('',(2.427594323228,7.E-002)); +#23385 = CARTESIAN_POINT('',(2.570393989301,7.E-002)); +#23386 = CARTESIAN_POINT('',(2.713193655373,7.E-002)); +#23387 = CARTESIAN_POINT('',(2.855993321445,7.E-002)); +#23388 = CARTESIAN_POINT('',(2.998792987518,7.E-002)); +#23389 = CARTESIAN_POINT('',(3.093992764899,7.E-002)); +#23390 = CARTESIAN_POINT('',(3.14159265359,7.E-002)); +#23391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23392 = ORIENTED_EDGE('',*,*,#22380,.T.); +#23393 = ORIENTED_EDGE('',*,*,#23394,.F.); +#23394 = EDGE_CURVE('',#22232,#22206,#23395,.T.); +#23395 = SURFACE_CURVE('',#23396,(#23401,#23407),.PCURVE_S1.); +#23396 = CIRCLE('',#23397,1.); +#23397 = AXIS2_PLACEMENT_3D('',#23398,#23399,#23400); +#23398 = CARTESIAN_POINT('',(55.238908,21.775721,1.1)); +#23399 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23400 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23401 = PCURVE('',#22368,#23402); +#23402 = DEFINITIONAL_REPRESENTATION('',(#23403),#23406); +#23403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23404,#23405),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#21012 = CARTESIAN_POINT('',(0.E+000,-0.72)); -#21013 = CARTESIAN_POINT('',(3.14159265359,-0.72)); -#21014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#23404 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#23405 = CARTESIAN_POINT('',(3.14159265359,-0.72)); +#23406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21015 = PCURVE('',#19828,#21016); -#21016 = DEFINITIONAL_REPRESENTATION('',(#21017),#21043); -#21017 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21018,#21019,#21020,#21021, - #21022,#21023,#21024,#21025,#21026,#21027,#21028,#21029,#21030, - #21031,#21032,#21033,#21034,#21035,#21036,#21037,#21038,#21039, - #21040,#21041,#21042),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23407 = PCURVE('',#22220,#23408); +#23408 = DEFINITIONAL_REPRESENTATION('',(#23409),#23435); +#23409 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23410,#23411,#23412,#23413, + #23414,#23415,#23416,#23417,#23418,#23419,#23420,#23421,#23422, + #23423,#23424,#23425,#23426,#23427,#23428,#23429,#23430,#23431, + #23432,#23433,#23434),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -25791,76 +28780,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#21018 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#21019 = CARTESIAN_POINT('',(6.235585418489,1.409117987707E-015)); -#21020 = CARTESIAN_POINT('',(6.140385641107,1.505919086625E-015)); -#21021 = CARTESIAN_POINT('',(5.997585975035,-1.957094549721E-015)); -#21022 = CARTESIAN_POINT('',(5.854786308963,-1.064698179864E-015)); -#21023 = CARTESIAN_POINT('',(5.711986642891,2.203576755492E-016)); -#21024 = CARTESIAN_POINT('',(5.569186976818,2.093848546021E-015)); -#21025 = CARTESIAN_POINT('',(5.426387310746,-9.726179646718E-016)); -#21026 = CARTESIAN_POINT('',(5.283587644674,5.631619550075E-017)); -#21027 = CARTESIAN_POINT('',(5.140787978601,-1.184207197723E-015)); -#21028 = CARTESIAN_POINT('',(4.997988312529,1.146880874825E-015)); -#21029 = CARTESIAN_POINT('',(4.855188646457,-1.178584582964E-016)); -#21030 = CARTESIAN_POINT('',(4.712388980385,-4.899502637784E-017)); -#21031 = CARTESIAN_POINT('',(4.569589314312,3.138385638077E-016)); -#21032 = CARTESIAN_POINT('',(4.42678964824,-5.79907213591E-016)); -#21033 = CARTESIAN_POINT('',(4.283989982168,-7.140392793409E-016)); -#21034 = CARTESIAN_POINT('',(4.141190316096,-9.740475928441E-017)); -#21035 = CARTESIAN_POINT('',(3.998390650023,-8.27902063913E-016)); -#21036 = CARTESIAN_POINT('',(3.855590983951,2.172046756348E-015)); -#21037 = CARTESIAN_POINT('',(3.712791317879,1.990234674754E-016)); -#21038 = CARTESIAN_POINT('',(3.569991651807,-1.057559557895E-015)); -#21039 = CARTESIAN_POINT('',(3.427191985734,-1.964477459847E-015)); -#21040 = CARTESIAN_POINT('',(3.284392319662,1.528312105162E-015)); -#21041 = CARTESIAN_POINT('',(3.189192542281,1.424890117644E-015)); -#21042 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#21043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21044 = ADVANCED_FACE('',(#21045),#20076,.T.); -#21045 = FACE_BOUND('',#21046,.T.); -#21046 = EDGE_LOOP('',(#21047,#21048,#21049,#21050)); -#21047 = ORIENTED_EDGE('',*,*,#20063,.F.); -#21048 = ORIENTED_EDGE('',*,*,#20111,.T.); -#21049 = ORIENTED_EDGE('',*,*,#20088,.T.); -#21050 = ORIENTED_EDGE('',*,*,#20958,.F.); -#21051 = ADVANCED_FACE('',(#21052),#20514,.F.); -#21052 = FACE_BOUND('',#21053,.F.); -#21053 = EDGE_LOOP('',(#21054,#21055,#21056)); -#21054 = ORIENTED_EDGE('',*,*,#20499,.T.); -#21055 = ORIENTED_EDGE('',*,*,#20731,.F.); -#21056 = ORIENTED_EDGE('',*,*,#20525,.F.); -#21057 = ADVANCED_FACE('',(#21058),#19729,.T.); -#21058 = FACE_BOUND('',#21059,.T.); -#21059 = EDGE_LOOP('',(#21060,#21061,#21062,#21063)); -#21060 = ORIENTED_EDGE('',*,*,#19714,.T.); -#21061 = ORIENTED_EDGE('',*,*,#20904,.F.); -#21062 = ORIENTED_EDGE('',*,*,#19790,.F.); -#21063 = ORIENTED_EDGE('',*,*,#21064,.T.); -#21064 = EDGE_CURVE('',#19741,#19715,#21065,.T.); -#21065 = SURFACE_CURVE('',#21066,(#21071,#21077),.PCURVE_S1.); -#21066 = CIRCLE('',#21067,0.93); -#21067 = AXIS2_PLACEMENT_3D('',#21068,#21069,#21070); -#21068 = CARTESIAN_POINT('',(55.238908,21.845721,1.1)); -#21069 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21070 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21071 = PCURVE('',#19729,#21072); -#21072 = DEFINITIONAL_REPRESENTATION('',(#21073),#21076); -#21073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21074,#21075),.UNSPECIFIED., +#23410 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#23411 = CARTESIAN_POINT('',(6.235585418489,1.409117987707E-015)); +#23412 = CARTESIAN_POINT('',(6.140385641107,1.505919086625E-015)); +#23413 = CARTESIAN_POINT('',(5.997585975035,-1.957094549721E-015)); +#23414 = CARTESIAN_POINT('',(5.854786308963,-1.064698179864E-015)); +#23415 = CARTESIAN_POINT('',(5.711986642891,2.203576755492E-016)); +#23416 = CARTESIAN_POINT('',(5.569186976818,2.093848546021E-015)); +#23417 = CARTESIAN_POINT('',(5.426387310746,-9.726179646718E-016)); +#23418 = CARTESIAN_POINT('',(5.283587644674,5.631619550075E-017)); +#23419 = CARTESIAN_POINT('',(5.140787978601,-1.184207197723E-015)); +#23420 = CARTESIAN_POINT('',(4.997988312529,1.146880874825E-015)); +#23421 = CARTESIAN_POINT('',(4.855188646457,-1.178584582964E-016)); +#23422 = CARTESIAN_POINT('',(4.712388980385,-4.899502637784E-017)); +#23423 = CARTESIAN_POINT('',(4.569589314312,3.138385638077E-016)); +#23424 = CARTESIAN_POINT('',(4.42678964824,-5.79907213591E-016)); +#23425 = CARTESIAN_POINT('',(4.283989982168,-7.140392793409E-016)); +#23426 = CARTESIAN_POINT('',(4.141190316096,-9.740475928441E-017)); +#23427 = CARTESIAN_POINT('',(3.998390650023,-8.27902063913E-016)); +#23428 = CARTESIAN_POINT('',(3.855590983951,2.172046756348E-015)); +#23429 = CARTESIAN_POINT('',(3.712791317879,1.990234674754E-016)); +#23430 = CARTESIAN_POINT('',(3.569991651807,-1.057559557895E-015)); +#23431 = CARTESIAN_POINT('',(3.427191985734,-1.964477459847E-015)); +#23432 = CARTESIAN_POINT('',(3.284392319662,1.528312105162E-015)); +#23433 = CARTESIAN_POINT('',(3.189192542281,1.424890117644E-015)); +#23434 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#23435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23436 = ADVANCED_FACE('',(#23437),#22468,.T.); +#23437 = FACE_BOUND('',#23438,.T.); +#23438 = EDGE_LOOP('',(#23439,#23440,#23441,#23442)); +#23439 = ORIENTED_EDGE('',*,*,#22455,.F.); +#23440 = ORIENTED_EDGE('',*,*,#22503,.T.); +#23441 = ORIENTED_EDGE('',*,*,#22480,.T.); +#23442 = ORIENTED_EDGE('',*,*,#23350,.F.); +#23443 = ADVANCED_FACE('',(#23444),#22906,.F.); +#23444 = FACE_BOUND('',#23445,.F.); +#23445 = EDGE_LOOP('',(#23446,#23447,#23448)); +#23446 = ORIENTED_EDGE('',*,*,#22891,.T.); +#23447 = ORIENTED_EDGE('',*,*,#23123,.F.); +#23448 = ORIENTED_EDGE('',*,*,#22917,.F.); +#23449 = ADVANCED_FACE('',(#23450),#22121,.T.); +#23450 = FACE_BOUND('',#23451,.T.); +#23451 = EDGE_LOOP('',(#23452,#23453,#23454,#23455)); +#23452 = ORIENTED_EDGE('',*,*,#22106,.T.); +#23453 = ORIENTED_EDGE('',*,*,#23296,.F.); +#23454 = ORIENTED_EDGE('',*,*,#22182,.F.); +#23455 = ORIENTED_EDGE('',*,*,#23456,.T.); +#23456 = EDGE_CURVE('',#22133,#22107,#23457,.T.); +#23457 = SURFACE_CURVE('',#23458,(#23463,#23469),.PCURVE_S1.); +#23458 = CIRCLE('',#23459,0.93); +#23459 = AXIS2_PLACEMENT_3D('',#23460,#23461,#23462); +#23460 = CARTESIAN_POINT('',(55.238908,21.845721,1.1)); +#23461 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23462 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23463 = PCURVE('',#22121,#23464); +#23464 = DEFINITIONAL_REPRESENTATION('',(#23465),#23468); +#23465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23466,#23467),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#21074 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#21075 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#21076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#23466 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#23467 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#23468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21077 = PCURVE('',#19828,#21078); -#21078 = DEFINITIONAL_REPRESENTATION('',(#21079),#21105); -#21079 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21080,#21081,#21082,#21083, - #21084,#21085,#21086,#21087,#21088,#21089,#21090,#21091,#21092, - #21093,#21094,#21095,#21096,#21097,#21098,#21099,#21100,#21101, - #21102,#21103,#21104),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23469 = PCURVE('',#22220,#23470); +#23470 = DEFINITIONAL_REPRESENTATION('',(#23471),#23497); +#23471 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23472,#23473,#23474,#23475, + #23476,#23477,#23478,#23479,#23480,#23481,#23482,#23483,#23484, + #23485,#23486,#23487,#23488,#23489,#23490,#23491,#23492,#23493, + #23494,#23495,#23496),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -25868,614 +28857,614 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#21080 = CARTESIAN_POINT('',(6.28318530718,-7.E-002)); -#21081 = CARTESIAN_POINT('',(6.235585418489,-7.E-002)); -#21082 = CARTESIAN_POINT('',(6.140385641107,-7.E-002)); -#21083 = CARTESIAN_POINT('',(5.997585975035,-7.E-002)); -#21084 = CARTESIAN_POINT('',(5.854786308963,-7.E-002)); -#21085 = CARTESIAN_POINT('',(5.711986642891,-7.E-002)); -#21086 = CARTESIAN_POINT('',(5.569186976818,-7.E-002)); -#21087 = CARTESIAN_POINT('',(5.426387310746,-7.E-002)); -#21088 = CARTESIAN_POINT('',(5.283587644674,-7.E-002)); -#21089 = CARTESIAN_POINT('',(5.140787978601,-7.E-002)); -#21090 = CARTESIAN_POINT('',(4.997988312529,-7.E-002)); -#21091 = CARTESIAN_POINT('',(4.855188646457,-7.E-002)); -#21092 = CARTESIAN_POINT('',(4.712388980385,-7.E-002)); -#21093 = CARTESIAN_POINT('',(4.569589314312,-7.E-002)); -#21094 = CARTESIAN_POINT('',(4.42678964824,-7.E-002)); -#21095 = CARTESIAN_POINT('',(4.283989982168,-7.E-002)); -#21096 = CARTESIAN_POINT('',(4.141190316096,-7.E-002)); -#21097 = CARTESIAN_POINT('',(3.998390650023,-7.E-002)); -#21098 = CARTESIAN_POINT('',(3.855590983951,-7.E-002)); -#21099 = CARTESIAN_POINT('',(3.712791317879,-7.E-002)); -#21100 = CARTESIAN_POINT('',(3.569991651807,-7.E-002)); -#21101 = CARTESIAN_POINT('',(3.427191985734,-7.E-002)); -#21102 = CARTESIAN_POINT('',(3.284392319662,-7.E-002)); -#21103 = CARTESIAN_POINT('',(3.189192542281,-7.E-002)); -#21104 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); -#21105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21106 = ADVANCED_FACE('',(#21107),#18547,.F.); -#21107 = FACE_BOUND('',#21108,.F.); -#21108 = EDGE_LOOP('',(#21109,#21110,#21111,#21112,#21135,#21155,#21156, - #21178)); -#21109 = ORIENTED_EDGE('',*,*,#20299,.F.); -#21110 = ORIENTED_EDGE('',*,*,#20182,.T.); -#21111 = ORIENTED_EDGE('',*,*,#20279,.T.); -#21112 = ORIENTED_EDGE('',*,*,#21113,.F.); -#21113 = EDGE_CURVE('',#21114,#20252,#21116,.T.); -#21114 = VERTEX_POINT('',#21115); -#21115 = CARTESIAN_POINT('',(56.013504669241,22.045721,1.45)); -#21116 = SURFACE_CURVE('',#21117,(#21122,#21128),.PCURVE_S1.); -#21117 = CIRCLE('',#21118,0.85); -#21118 = AXIS2_PLACEMENT_3D('',#21119,#21120,#21121); -#21119 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21120 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21121 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21122 = PCURVE('',#18547,#21123); -#21123 = DEFINITIONAL_REPRESENTATION('',(#21124),#21127); -#21124 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21125,#21126),.UNSPECIFIED., +#23472 = CARTESIAN_POINT('',(6.28318530718,-7.E-002)); +#23473 = CARTESIAN_POINT('',(6.235585418489,-7.E-002)); +#23474 = CARTESIAN_POINT('',(6.140385641107,-7.E-002)); +#23475 = CARTESIAN_POINT('',(5.997585975035,-7.E-002)); +#23476 = CARTESIAN_POINT('',(5.854786308963,-7.E-002)); +#23477 = CARTESIAN_POINT('',(5.711986642891,-7.E-002)); +#23478 = CARTESIAN_POINT('',(5.569186976818,-7.E-002)); +#23479 = CARTESIAN_POINT('',(5.426387310746,-7.E-002)); +#23480 = CARTESIAN_POINT('',(5.283587644674,-7.E-002)); +#23481 = CARTESIAN_POINT('',(5.140787978601,-7.E-002)); +#23482 = CARTESIAN_POINT('',(4.997988312529,-7.E-002)); +#23483 = CARTESIAN_POINT('',(4.855188646457,-7.E-002)); +#23484 = CARTESIAN_POINT('',(4.712388980385,-7.E-002)); +#23485 = CARTESIAN_POINT('',(4.569589314312,-7.E-002)); +#23486 = CARTESIAN_POINT('',(4.42678964824,-7.E-002)); +#23487 = CARTESIAN_POINT('',(4.283989982168,-7.E-002)); +#23488 = CARTESIAN_POINT('',(4.141190316096,-7.E-002)); +#23489 = CARTESIAN_POINT('',(3.998390650023,-7.E-002)); +#23490 = CARTESIAN_POINT('',(3.855590983951,-7.E-002)); +#23491 = CARTESIAN_POINT('',(3.712791317879,-7.E-002)); +#23492 = CARTESIAN_POINT('',(3.569991651807,-7.E-002)); +#23493 = CARTESIAN_POINT('',(3.427191985734,-7.E-002)); +#23494 = CARTESIAN_POINT('',(3.284392319662,-7.E-002)); +#23495 = CARTESIAN_POINT('',(3.189192542281,-7.E-002)); +#23496 = CARTESIAN_POINT('',(3.14159265359,-7.E-002)); +#23497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23498 = ADVANCED_FACE('',(#23499),#20939,.F.); +#23499 = FACE_BOUND('',#23500,.F.); +#23500 = EDGE_LOOP('',(#23501,#23502,#23503,#23504,#23527,#23547,#23548, + #23570)); +#23501 = ORIENTED_EDGE('',*,*,#22691,.F.); +#23502 = ORIENTED_EDGE('',*,*,#22574,.T.); +#23503 = ORIENTED_EDGE('',*,*,#22671,.T.); +#23504 = ORIENTED_EDGE('',*,*,#23505,.F.); +#23505 = EDGE_CURVE('',#23506,#22644,#23508,.T.); +#23506 = VERTEX_POINT('',#23507); +#23507 = CARTESIAN_POINT('',(56.013504669241,22.045721,1.45)); +#23508 = SURFACE_CURVE('',#23509,(#23514,#23520),.PCURVE_S1.); +#23509 = CIRCLE('',#23510,0.85); +#23510 = AXIS2_PLACEMENT_3D('',#23511,#23512,#23513); +#23511 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23512 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23513 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23514 = PCURVE('',#20939,#23515); +#23515 = DEFINITIONAL_REPRESENTATION('',(#23516),#23519); +#23516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23517,#23518),.UNSPECIFIED., .F.,.F.,(2,2),(2.717202944997,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#21125 = CARTESIAN_POINT('',(2.717202944997,-0.45)); -#21126 = CARTESIAN_POINT('',(3.14159265359,-0.45)); -#21127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21128 = PCURVE('',#20267,#21129); -#21129 = DEFINITIONAL_REPRESENTATION('',(#21130),#21134); -#21130 = CIRCLE('',#21131,0.85); -#21131 = AXIS2_PLACEMENT_2D('',#21132,#21133); -#21132 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21133 = DIRECTION('',(1.,0.E+000)); -#21134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21135 = ORIENTED_EDGE('',*,*,#21136,.T.); -#21136 = EDGE_CURVE('',#21114,#18526,#21137,.T.); -#21137 = SURFACE_CURVE('',#21138,(#21142,#21148),.PCURVE_S1.); -#21138 = LINE('',#21139,#21140); -#21139 = CARTESIAN_POINT('',(56.013504669241,22.495721,1.45)); -#21140 = VECTOR('',#21141,1.); -#21141 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21142 = PCURVE('',#18547,#21143); -#21143 = DEFINITIONAL_REPRESENTATION('',(#21144),#21147); -#21144 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21145,#21146),.UNSPECIFIED., +#23517 = CARTESIAN_POINT('',(2.717202944997,-0.45)); +#23518 = CARTESIAN_POINT('',(3.14159265359,-0.45)); +#23519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23520 = PCURVE('',#22659,#23521); +#23521 = DEFINITIONAL_REPRESENTATION('',(#23522),#23526); +#23522 = CIRCLE('',#23523,0.85); +#23523 = AXIS2_PLACEMENT_2D('',#23524,#23525); +#23524 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23525 = DIRECTION('',(1.,0.E+000)); +#23526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23527 = ORIENTED_EDGE('',*,*,#23528,.T.); +#23528 = EDGE_CURVE('',#23506,#20918,#23529,.T.); +#23529 = SURFACE_CURVE('',#23530,(#23534,#23540),.PCURVE_S1.); +#23530 = LINE('',#23531,#23532); +#23531 = CARTESIAN_POINT('',(56.013504669241,22.495721,1.45)); +#23532 = VECTOR('',#23533,1.); +#23533 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23534 = PCURVE('',#20939,#23535); +#23535 = DEFINITIONAL_REPRESENTATION('',(#23536),#23539); +#23536 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23537,#23538),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#21145 = CARTESIAN_POINT('',(2.717202944997,-0.45)); -#21146 = CARTESIAN_POINT('',(2.717202944997,-0.35)); -#21147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21148 = PCURVE('',#18628,#21149); -#21149 = DEFINITIONAL_REPRESENTATION('',(#21150),#21154); -#21150 = LINE('',#21151,#21152); -#21151 = CARTESIAN_POINT('',(-0.35033260053,-0.35)); -#21152 = VECTOR('',#21153,1.); -#21153 = DIRECTION('',(0.E+000,-1.)); -#21154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21155 = ORIENTED_EDGE('',*,*,#18523,.F.); -#21156 = ORIENTED_EDGE('',*,*,#21157,.F.); -#21157 = EDGE_CURVE('',#21158,#18524,#21160,.T.); -#21158 = VERTEX_POINT('',#21159); -#21159 = CARTESIAN_POINT('',(54.464311330758,22.045721,1.45)); -#21160 = SURFACE_CURVE('',#21161,(#21165,#21171),.PCURVE_S1.); -#21161 = LINE('',#21162,#21163); -#21162 = CARTESIAN_POINT('',(54.464311330758,22.495721,1.45)); -#21163 = VECTOR('',#21164,1.); -#21164 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21165 = PCURVE('',#18547,#21166); -#21166 = DEFINITIONAL_REPRESENTATION('',(#21167),#21170); -#21167 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21168,#21169),.UNSPECIFIED., +#23537 = CARTESIAN_POINT('',(2.717202944997,-0.45)); +#23538 = CARTESIAN_POINT('',(2.717202944997,-0.35)); +#23539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23540 = PCURVE('',#21020,#23541); +#23541 = DEFINITIONAL_REPRESENTATION('',(#23542),#23546); +#23542 = LINE('',#23543,#23544); +#23543 = CARTESIAN_POINT('',(-0.35033260053,-0.35)); +#23544 = VECTOR('',#23545,1.); +#23545 = DIRECTION('',(0.E+000,-1.)); +#23546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23547 = ORIENTED_EDGE('',*,*,#20915,.F.); +#23548 = ORIENTED_EDGE('',*,*,#23549,.F.); +#23549 = EDGE_CURVE('',#23550,#20916,#23552,.T.); +#23550 = VERTEX_POINT('',#23551); +#23551 = CARTESIAN_POINT('',(54.464311330758,22.045721,1.45)); +#23552 = SURFACE_CURVE('',#23553,(#23557,#23563),.PCURVE_S1.); +#23553 = LINE('',#23554,#23555); +#23554 = CARTESIAN_POINT('',(54.464311330758,22.495721,1.45)); +#23555 = VECTOR('',#23556,1.); +#23556 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23557 = PCURVE('',#20939,#23558); +#23558 = DEFINITIONAL_REPRESENTATION('',(#23559),#23562); +#23559 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23560,#23561),.UNSPECIFIED., .F.,.F.,(2,2),(-0.45,-0.35),.PIECEWISE_BEZIER_KNOTS.); -#21168 = CARTESIAN_POINT('',(0.424389708593,-0.45)); -#21169 = CARTESIAN_POINT('',(0.424389708593,-0.35)); -#21170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21171 = PCURVE('',#18574,#21172); -#21172 = DEFINITIONAL_REPRESENTATION('',(#21173),#21177); -#21173 = LINE('',#21174,#21175); -#21174 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#21175 = VECTOR('',#21176,1.); -#21176 = DIRECTION('',(0.E+000,-1.)); -#21177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21178 = ORIENTED_EDGE('',*,*,#21179,.F.); -#21179 = EDGE_CURVE('',#20300,#21158,#21180,.T.); -#21180 = SURFACE_CURVE('',#21181,(#21186,#21192),.PCURVE_S1.); -#21181 = CIRCLE('',#21182,0.85); -#21182 = AXIS2_PLACEMENT_3D('',#21183,#21184,#21185); -#21183 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21184 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21185 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21186 = PCURVE('',#18547,#21187); -#21187 = DEFINITIONAL_REPRESENTATION('',(#21188),#21191); -#21188 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21189,#21190),.UNSPECIFIED., +#23560 = CARTESIAN_POINT('',(0.424389708593,-0.45)); +#23561 = CARTESIAN_POINT('',(0.424389708593,-0.35)); +#23562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23563 = PCURVE('',#20966,#23564); +#23564 = DEFINITIONAL_REPRESENTATION('',(#23565),#23569); +#23565 = LINE('',#23566,#23567); +#23566 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#23567 = VECTOR('',#23568,1.); +#23568 = DIRECTION('',(0.E+000,-1.)); +#23569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23570 = ORIENTED_EDGE('',*,*,#23571,.F.); +#23571 = EDGE_CURVE('',#22692,#23550,#23572,.T.); +#23572 = SURFACE_CURVE('',#23573,(#23578,#23584),.PCURVE_S1.); +#23573 = CIRCLE('',#23574,0.85); +#23574 = AXIS2_PLACEMENT_3D('',#23575,#23576,#23577); +#23575 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23576 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23577 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23578 = PCURVE('',#20939,#23579); +#23579 = DEFINITIONAL_REPRESENTATION('',(#23580),#23583); +#23580 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23581,#23582),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424389708593),.PIECEWISE_BEZIER_KNOTS.); -#21189 = CARTESIAN_POINT('',(0.E+000,-0.45)); -#21190 = CARTESIAN_POINT('',(0.424389708593,-0.45)); -#21191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21192 = PCURVE('',#20267,#21193); -#21193 = DEFINITIONAL_REPRESENTATION('',(#21194),#21198); -#21194 = CIRCLE('',#21195,0.85); -#21195 = AXIS2_PLACEMENT_2D('',#21196,#21197); -#21196 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21197 = DIRECTION('',(1.,0.E+000)); -#21198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21199 = ADVANCED_FACE('',(#21200),#19828,.T.); -#21200 = FACE_BOUND('',#21201,.T.); -#21201 = EDGE_LOOP('',(#21202,#21203,#21204,#21205)); -#21202 = ORIENTED_EDGE('',*,*,#19889,.T.); -#21203 = ORIENTED_EDGE('',*,*,#21002,.T.); -#21204 = ORIENTED_EDGE('',*,*,#19813,.F.); -#21205 = ORIENTED_EDGE('',*,*,#21064,.F.); -#21206 = ADVANCED_FACE('',(#21207,#21347),#20267,.F.); -#21207 = FACE_BOUND('',#21208,.T.); -#21208 = EDGE_LOOP('',(#21209,#21232,#21255,#21276,#21277,#21278,#21301, - #21324,#21345,#21346)); -#21209 = ORIENTED_EDGE('',*,*,#21210,.F.); -#21210 = EDGE_CURVE('',#21211,#20207,#21213,.T.); -#21211 = VERTEX_POINT('',#21212); -#21212 = CARTESIAN_POINT('',(54.814643931288,22.045721,0.75)); -#21213 = SURFACE_CURVE('',#21214,(#21218,#21225),.PCURVE_S1.); -#21214 = LINE('',#21215,#21216); -#21215 = CARTESIAN_POINT('',(54.322392861009,22.045721,0.75)); -#21216 = VECTOR('',#21217,1.); -#21217 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); -#21218 = PCURVE('',#20267,#21219); -#21219 = DEFINITIONAL_REPRESENTATION('',(#21220),#21224); -#21220 = LINE('',#21221,#21222); -#21221 = CARTESIAN_POINT('',(0.944017581298,-1.26366055628)); -#21222 = VECTOR('',#21223,1.); -#21223 = DIRECTION('',(1.,-2.22044604925E-016)); -#21224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21225 = PCURVE('',#19483,#21226); -#21226 = DEFINITIONAL_REPRESENTATION('',(#21227),#21231); -#21227 = LINE('',#21228,#21229); -#21228 = CARTESIAN_POINT('',(-0.492251070279,0.1)); -#21229 = VECTOR('',#21230,1.); -#21230 = DIRECTION('',(-1.,0.E+000)); -#21231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21232 = ORIENTED_EDGE('',*,*,#21233,.F.); -#21233 = EDGE_CURVE('',#21234,#21211,#21236,.T.); -#21234 = VERTEX_POINT('',#21235); -#21235 = CARTESIAN_POINT('',(55.663172068712,22.045721,0.75)); -#21236 = SURFACE_CURVE('',#21237,(#21242,#21249),.PCURVE_S1.); -#21237 = CIRCLE('',#21238,0.55); -#21238 = AXIS2_PLACEMENT_3D('',#21239,#21240,#21241); -#21239 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21240 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21241 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21242 = PCURVE('',#20267,#21243); -#21243 = DEFINITIONAL_REPRESENTATION('',(#21244),#21248); -#21244 = CIRCLE('',#21245,0.55); -#21245 = AXIS2_PLACEMENT_2D('',#21246,#21247); -#21246 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21247 = DIRECTION('',(1.,0.E+000)); -#21248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21249 = PCURVE('',#19458,#21250); -#21250 = DEFINITIONAL_REPRESENTATION('',(#21251),#21254); -#21251 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21252,#21253),.UNSPECIFIED., +#23581 = CARTESIAN_POINT('',(0.E+000,-0.45)); +#23582 = CARTESIAN_POINT('',(0.424389708593,-0.45)); +#23583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23584 = PCURVE('',#22659,#23585); +#23585 = DEFINITIONAL_REPRESENTATION('',(#23586),#23590); +#23586 = CIRCLE('',#23587,0.85); +#23587 = AXIS2_PLACEMENT_2D('',#23588,#23589); +#23588 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23589 = DIRECTION('',(1.,0.E+000)); +#23590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23591 = ADVANCED_FACE('',(#23592),#22220,.T.); +#23592 = FACE_BOUND('',#23593,.T.); +#23593 = EDGE_LOOP('',(#23594,#23595,#23596,#23597)); +#23594 = ORIENTED_EDGE('',*,*,#22281,.T.); +#23595 = ORIENTED_EDGE('',*,*,#23394,.T.); +#23596 = ORIENTED_EDGE('',*,*,#22205,.F.); +#23597 = ORIENTED_EDGE('',*,*,#23456,.F.); +#23598 = ADVANCED_FACE('',(#23599,#23739),#22659,.F.); +#23599 = FACE_BOUND('',#23600,.T.); +#23600 = EDGE_LOOP('',(#23601,#23624,#23647,#23668,#23669,#23670,#23693, + #23716,#23737,#23738)); +#23601 = ORIENTED_EDGE('',*,*,#23602,.F.); +#23602 = EDGE_CURVE('',#23603,#22599,#23605,.T.); +#23603 = VERTEX_POINT('',#23604); +#23604 = CARTESIAN_POINT('',(54.814643931288,22.045721,0.75)); +#23605 = SURFACE_CURVE('',#23606,(#23610,#23617),.PCURVE_S1.); +#23606 = LINE('',#23607,#23608); +#23607 = CARTESIAN_POINT('',(54.322392861009,22.045721,0.75)); +#23608 = VECTOR('',#23609,1.); +#23609 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); +#23610 = PCURVE('',#22659,#23611); +#23611 = DEFINITIONAL_REPRESENTATION('',(#23612),#23616); +#23612 = LINE('',#23613,#23614); +#23613 = CARTESIAN_POINT('',(0.944017581298,-1.26366055628)); +#23614 = VECTOR('',#23615,1.); +#23615 = DIRECTION('',(1.,-2.22044604925E-016)); +#23616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23617 = PCURVE('',#21875,#23618); +#23618 = DEFINITIONAL_REPRESENTATION('',(#23619),#23623); +#23619 = LINE('',#23620,#23621); +#23620 = CARTESIAN_POINT('',(-0.492251070279,0.1)); +#23621 = VECTOR('',#23622,1.); +#23622 = DIRECTION('',(-1.,0.E+000)); +#23623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23624 = ORIENTED_EDGE('',*,*,#23625,.F.); +#23625 = EDGE_CURVE('',#23626,#23603,#23628,.T.); +#23626 = VERTEX_POINT('',#23627); +#23627 = CARTESIAN_POINT('',(55.663172068712,22.045721,0.75)); +#23628 = SURFACE_CURVE('',#23629,(#23634,#23641),.PCURVE_S1.); +#23629 = CIRCLE('',#23630,0.55); +#23630 = AXIS2_PLACEMENT_3D('',#23631,#23632,#23633); +#23631 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23632 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23633 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23634 = PCURVE('',#22659,#23635); +#23635 = DEFINITIONAL_REPRESENTATION('',(#23636),#23640); +#23636 = CIRCLE('',#23637,0.55); +#23637 = AXIS2_PLACEMENT_2D('',#23638,#23639); +#23638 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23639 = DIRECTION('',(1.,0.E+000)); +#23640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23641 = PCURVE('',#21850,#23642); +#23642 = DEFINITIONAL_REPRESENTATION('',(#23643),#23646); +#23643 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23644,#23645),.UNSPECIFIED., .F.,.F.,(2,2),(3.831367654375,5.593410306394), .PIECEWISE_BEZIER_KNOTS.); -#21252 = CARTESIAN_POINT('',(3.831367654375,-0.1)); -#21253 = CARTESIAN_POINT('',(5.593410306394,-0.1)); -#21254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21255 = ORIENTED_EDGE('',*,*,#21256,.F.); -#21256 = EDGE_CURVE('',#20230,#21234,#21257,.T.); -#21257 = SURFACE_CURVE('',#21258,(#21262,#21269),.PCURVE_S1.); -#21258 = LINE('',#21259,#21260); -#21259 = CARTESIAN_POINT('',(54.322392861009,22.045721,0.75)); -#21260 = VECTOR('',#21261,1.); -#21261 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); -#21262 = PCURVE('',#20267,#21263); -#21263 = DEFINITIONAL_REPRESENTATION('',(#21264),#21268); -#21264 = LINE('',#21265,#21266); -#21265 = CARTESIAN_POINT('',(0.944017581298,-1.26366055628)); -#21266 = VECTOR('',#21267,1.); -#21267 = DIRECTION('',(1.,-2.22044604925E-016)); -#21268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21269 = PCURVE('',#19429,#21270); -#21270 = DEFINITIONAL_REPRESENTATION('',(#21271),#21275); -#21271 = LINE('',#21272,#21273); -#21272 = CARTESIAN_POINT('',(-1.691111808233,0.1)); -#21273 = VECTOR('',#21274,1.); -#21274 = DIRECTION('',(-1.,0.E+000)); -#21275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21276 = ORIENTED_EDGE('',*,*,#20251,.F.); -#21277 = ORIENTED_EDGE('',*,*,#21113,.F.); -#21278 = ORIENTED_EDGE('',*,*,#21279,.T.); -#21279 = EDGE_CURVE('',#21114,#21280,#21282,.T.); -#21280 = VERTEX_POINT('',#21281); -#21281 = CARTESIAN_POINT('',(55.663172068712,22.045721,1.45)); -#21282 = SURFACE_CURVE('',#21283,(#21287,#21294),.PCURVE_S1.); -#21283 = LINE('',#21284,#21285); -#21284 = CARTESIAN_POINT('',(54.322392861009,22.045721,1.45)); -#21285 = VECTOR('',#21286,1.); -#21286 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); -#21287 = PCURVE('',#20267,#21288); -#21288 = DEFINITIONAL_REPRESENTATION('',(#21289),#21293); -#21289 = LINE('',#21290,#21291); -#21290 = CARTESIAN_POINT('',(0.944017581298,-0.56366055628)); -#21291 = VECTOR('',#21292,1.); -#21292 = DIRECTION('',(1.,-1.110223024625E-016)); -#21293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21294 = PCURVE('',#18628,#21295); -#21295 = DEFINITIONAL_REPRESENTATION('',(#21296),#21300); -#21296 = LINE('',#21297,#21298); -#21297 = CARTESIAN_POINT('',(1.340779207703,0.1)); -#21298 = VECTOR('',#21299,1.); -#21299 = DIRECTION('',(1.,0.E+000)); -#21300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21301 = ORIENTED_EDGE('',*,*,#21302,.F.); -#21302 = EDGE_CURVE('',#21303,#21280,#21305,.T.); -#21303 = VERTEX_POINT('',#21304); -#21304 = CARTESIAN_POINT('',(54.814643931288,22.045721,1.45)); -#21305 = SURFACE_CURVE('',#21306,(#21311,#21318),.PCURVE_S1.); -#21306 = CIRCLE('',#21307,0.55); -#21307 = AXIS2_PLACEMENT_3D('',#21308,#21309,#21310); -#21308 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21309 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21310 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21311 = PCURVE('',#20267,#21312); -#21312 = DEFINITIONAL_REPRESENTATION('',(#21313),#21317); -#21313 = CIRCLE('',#21314,0.55); -#21314 = AXIS2_PLACEMENT_2D('',#21315,#21316); -#21315 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21316 = DIRECTION('',(1.,0.E+000)); -#21317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21318 = PCURVE('',#18603,#21319); -#21319 = DEFINITIONAL_REPRESENTATION('',(#21320),#21323); -#21320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21321,#21322),.UNSPECIFIED., +#23644 = CARTESIAN_POINT('',(3.831367654375,-0.1)); +#23645 = CARTESIAN_POINT('',(5.593410306394,-0.1)); +#23646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23647 = ORIENTED_EDGE('',*,*,#23648,.F.); +#23648 = EDGE_CURVE('',#22622,#23626,#23649,.T.); +#23649 = SURFACE_CURVE('',#23650,(#23654,#23661),.PCURVE_S1.); +#23650 = LINE('',#23651,#23652); +#23651 = CARTESIAN_POINT('',(54.322392861009,22.045721,0.75)); +#23652 = VECTOR('',#23653,1.); +#23653 = DIRECTION('',(-1.,0.E+000,-2.22044604925E-016)); +#23654 = PCURVE('',#22659,#23655); +#23655 = DEFINITIONAL_REPRESENTATION('',(#23656),#23660); +#23656 = LINE('',#23657,#23658); +#23657 = CARTESIAN_POINT('',(0.944017581298,-1.26366055628)); +#23658 = VECTOR('',#23659,1.); +#23659 = DIRECTION('',(1.,-2.22044604925E-016)); +#23660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23661 = PCURVE('',#21821,#23662); +#23662 = DEFINITIONAL_REPRESENTATION('',(#23663),#23667); +#23663 = LINE('',#23664,#23665); +#23664 = CARTESIAN_POINT('',(-1.691111808233,0.1)); +#23665 = VECTOR('',#23666,1.); +#23666 = DIRECTION('',(-1.,0.E+000)); +#23667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23668 = ORIENTED_EDGE('',*,*,#22643,.F.); +#23669 = ORIENTED_EDGE('',*,*,#23505,.F.); +#23670 = ORIENTED_EDGE('',*,*,#23671,.T.); +#23671 = EDGE_CURVE('',#23506,#23672,#23674,.T.); +#23672 = VERTEX_POINT('',#23673); +#23673 = CARTESIAN_POINT('',(55.663172068712,22.045721,1.45)); +#23674 = SURFACE_CURVE('',#23675,(#23679,#23686),.PCURVE_S1.); +#23675 = LINE('',#23676,#23677); +#23676 = CARTESIAN_POINT('',(54.322392861009,22.045721,1.45)); +#23677 = VECTOR('',#23678,1.); +#23678 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); +#23679 = PCURVE('',#22659,#23680); +#23680 = DEFINITIONAL_REPRESENTATION('',(#23681),#23685); +#23681 = LINE('',#23682,#23683); +#23682 = CARTESIAN_POINT('',(0.944017581298,-0.56366055628)); +#23683 = VECTOR('',#23684,1.); +#23684 = DIRECTION('',(1.,-1.110223024625E-016)); +#23685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23686 = PCURVE('',#21020,#23687); +#23687 = DEFINITIONAL_REPRESENTATION('',(#23688),#23692); +#23688 = LINE('',#23689,#23690); +#23689 = CARTESIAN_POINT('',(1.340779207703,0.1)); +#23690 = VECTOR('',#23691,1.); +#23691 = DIRECTION('',(1.,0.E+000)); +#23692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23693 = ORIENTED_EDGE('',*,*,#23694,.F.); +#23694 = EDGE_CURVE('',#23695,#23672,#23697,.T.); +#23695 = VERTEX_POINT('',#23696); +#23696 = CARTESIAN_POINT('',(54.814643931288,22.045721,1.45)); +#23697 = SURFACE_CURVE('',#23698,(#23703,#23710),.PCURVE_S1.); +#23698 = CIRCLE('',#23699,0.55); +#23699 = AXIS2_PLACEMENT_3D('',#23700,#23701,#23702); +#23700 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23701 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23702 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#23703 = PCURVE('',#22659,#23704); +#23704 = DEFINITIONAL_REPRESENTATION('',(#23705),#23709); +#23705 = CIRCLE('',#23706,0.55); +#23706 = AXIS2_PLACEMENT_2D('',#23707,#23708); +#23707 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23708 = DIRECTION('',(1.,0.E+000)); +#23709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23710 = PCURVE('',#20995,#23711); +#23711 = DEFINITIONAL_REPRESENTATION('',(#23712),#23715); +#23712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23713,#23714),.UNSPECIFIED., .F.,.F.,(2,2),(0.689775000786,2.451817652804), .PIECEWISE_BEZIER_KNOTS.); -#21321 = CARTESIAN_POINT('',(0.689775000786,-0.1)); -#21322 = CARTESIAN_POINT('',(2.451817652804,-0.1)); -#21323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21324 = ORIENTED_EDGE('',*,*,#21325,.T.); -#21325 = EDGE_CURVE('',#21303,#21158,#21326,.T.); -#21326 = SURFACE_CURVE('',#21327,(#21331,#21338),.PCURVE_S1.); -#21327 = LINE('',#21328,#21329); -#21328 = CARTESIAN_POINT('',(54.322392861009,22.045721,1.45)); -#21329 = VECTOR('',#21330,1.); -#21330 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); -#21331 = PCURVE('',#20267,#21332); -#21332 = DEFINITIONAL_REPRESENTATION('',(#21333),#21337); -#21333 = LINE('',#21334,#21335); -#21334 = CARTESIAN_POINT('',(0.944017581298,-0.56366055628)); -#21335 = VECTOR('',#21336,1.); -#21336 = DIRECTION('',(1.,-1.110223024625E-016)); -#21337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21338 = PCURVE('',#18574,#21339); -#21339 = DEFINITIONAL_REPRESENTATION('',(#21340),#21344); -#21340 = LINE('',#21341,#21342); -#21341 = CARTESIAN_POINT('',(0.14191846975,0.1)); -#21342 = VECTOR('',#21343,1.); -#21343 = DIRECTION('',(1.,0.E+000)); -#21344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21345 = ORIENTED_EDGE('',*,*,#21179,.F.); -#21346 = ORIENTED_EDGE('',*,*,#20320,.F.); -#21347 = FACE_BOUND('',#21348,.T.); -#21348 = EDGE_LOOP('',(#21349,#21379)); -#21349 = ORIENTED_EDGE('',*,*,#21350,.T.); -#21350 = EDGE_CURVE('',#21351,#21353,#21355,.T.); -#21351 = VERTEX_POINT('',#21352); -#21352 = CARTESIAN_POINT('',(54.988908,22.045721,1.1)); -#21353 = VERTEX_POINT('',#21354); -#21354 = CARTESIAN_POINT('',(55.488908,22.045721,1.1)); -#21355 = SURFACE_CURVE('',#21356,(#21361,#21368),.PCURVE_S1.); -#21356 = CIRCLE('',#21357,0.25); -#21357 = AXIS2_PLACEMENT_3D('',#21358,#21359,#21360); -#21358 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21359 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21360 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21361 = PCURVE('',#20267,#21362); -#21362 = DEFINITIONAL_REPRESENTATION('',(#21363),#21367); -#21363 = CIRCLE('',#21364,0.25); -#21364 = AXIS2_PLACEMENT_2D('',#21365,#21366); -#21365 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21366 = DIRECTION('',(-1.,0.E+000)); -#21367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21368 = PCURVE('',#21369,#21374); -#21369 = CYLINDRICAL_SURFACE('',#21370,0.25); -#21370 = AXIS2_PLACEMENT_3D('',#21371,#21372,#21373); -#21371 = CARTESIAN_POINT('',(55.238908,21.795721,1.1)); -#21372 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21373 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21374 = DEFINITIONAL_REPRESENTATION('',(#21375),#21378); -#21375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21376,#21377),.UNSPECIFIED., +#23713 = CARTESIAN_POINT('',(0.689775000786,-0.1)); +#23714 = CARTESIAN_POINT('',(2.451817652804,-0.1)); +#23715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23716 = ORIENTED_EDGE('',*,*,#23717,.T.); +#23717 = EDGE_CURVE('',#23695,#23550,#23718,.T.); +#23718 = SURFACE_CURVE('',#23719,(#23723,#23730),.PCURVE_S1.); +#23719 = LINE('',#23720,#23721); +#23720 = CARTESIAN_POINT('',(54.322392861009,22.045721,1.45)); +#23721 = VECTOR('',#23722,1.); +#23722 = DIRECTION('',(-1.,0.E+000,-1.110223024625E-016)); +#23723 = PCURVE('',#22659,#23724); +#23724 = DEFINITIONAL_REPRESENTATION('',(#23725),#23729); +#23725 = LINE('',#23726,#23727); +#23726 = CARTESIAN_POINT('',(0.944017581298,-0.56366055628)); +#23727 = VECTOR('',#23728,1.); +#23728 = DIRECTION('',(1.,-1.110223024625E-016)); +#23729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23730 = PCURVE('',#20966,#23731); +#23731 = DEFINITIONAL_REPRESENTATION('',(#23732),#23736); +#23732 = LINE('',#23733,#23734); +#23733 = CARTESIAN_POINT('',(0.14191846975,0.1)); +#23734 = VECTOR('',#23735,1.); +#23735 = DIRECTION('',(1.,0.E+000)); +#23736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23737 = ORIENTED_EDGE('',*,*,#23571,.F.); +#23738 = ORIENTED_EDGE('',*,*,#22712,.F.); +#23739 = FACE_BOUND('',#23740,.T.); +#23740 = EDGE_LOOP('',(#23741,#23771)); +#23741 = ORIENTED_EDGE('',*,*,#23742,.T.); +#23742 = EDGE_CURVE('',#23743,#23745,#23747,.T.); +#23743 = VERTEX_POINT('',#23744); +#23744 = CARTESIAN_POINT('',(54.988908,22.045721,1.1)); +#23745 = VERTEX_POINT('',#23746); +#23746 = CARTESIAN_POINT('',(55.488908,22.045721,1.1)); +#23747 = SURFACE_CURVE('',#23748,(#23753,#23760),.PCURVE_S1.); +#23748 = CIRCLE('',#23749,0.25); +#23749 = AXIS2_PLACEMENT_3D('',#23750,#23751,#23752); +#23750 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23751 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23752 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23753 = PCURVE('',#22659,#23754); +#23754 = DEFINITIONAL_REPRESENTATION('',(#23755),#23759); +#23755 = CIRCLE('',#23756,0.25); +#23756 = AXIS2_PLACEMENT_2D('',#23757,#23758); +#23757 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23758 = DIRECTION('',(-1.,0.E+000)); +#23759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23760 = PCURVE('',#23761,#23766); +#23761 = CYLINDRICAL_SURFACE('',#23762,0.25); +#23762 = AXIS2_PLACEMENT_3D('',#23763,#23764,#23765); +#23763 = CARTESIAN_POINT('',(55.238908,21.795721,1.1)); +#23764 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23765 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23766 = DEFINITIONAL_REPRESENTATION('',(#23767),#23770); +#23767 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23768,#23769),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#21376 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#21377 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#21378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21379 = ORIENTED_EDGE('',*,*,#21380,.T.); -#21380 = EDGE_CURVE('',#21353,#21351,#21381,.T.); -#21381 = SURFACE_CURVE('',#21382,(#21387,#21394),.PCURVE_S1.); -#21382 = CIRCLE('',#21383,0.25); -#21383 = AXIS2_PLACEMENT_3D('',#21384,#21385,#21386); -#21384 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); -#21385 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21386 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21387 = PCURVE('',#20267,#21388); -#21388 = DEFINITIONAL_REPRESENTATION('',(#21389),#21393); -#21389 = CIRCLE('',#21390,0.25); -#21390 = AXIS2_PLACEMENT_2D('',#21391,#21392); -#21391 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); -#21392 = DIRECTION('',(-1.,0.E+000)); -#21393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21394 = PCURVE('',#21395,#21400); -#21395 = CYLINDRICAL_SURFACE('',#21396,0.25); -#21396 = AXIS2_PLACEMENT_3D('',#21397,#21398,#21399); -#21397 = CARTESIAN_POINT('',(55.238908,21.795721,1.1)); -#21398 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21399 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21400 = DEFINITIONAL_REPRESENTATION('',(#21401),#21404); -#21401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21402,#21403),.UNSPECIFIED., +#23768 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#23769 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#23770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23771 = ORIENTED_EDGE('',*,*,#23772,.T.); +#23772 = EDGE_CURVE('',#23745,#23743,#23773,.T.); +#23773 = SURFACE_CURVE('',#23774,(#23779,#23786),.PCURVE_S1.); +#23774 = CIRCLE('',#23775,0.25); +#23775 = AXIS2_PLACEMENT_3D('',#23776,#23777,#23778); +#23776 = CARTESIAN_POINT('',(55.238908,22.045721,1.1)); +#23777 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23778 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23779 = PCURVE('',#22659,#23780); +#23780 = DEFINITIONAL_REPRESENTATION('',(#23781),#23785); +#23781 = CIRCLE('',#23782,0.25); +#23782 = AXIS2_PLACEMENT_2D('',#23783,#23784); +#23783 = CARTESIAN_POINT('',(2.75024423064E-002,-0.91366055628)); +#23784 = DIRECTION('',(-1.,0.E+000)); +#23785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23786 = PCURVE('',#23787,#23792); +#23787 = CYLINDRICAL_SURFACE('',#23788,0.25); +#23788 = AXIS2_PLACEMENT_3D('',#23789,#23790,#23791); +#23789 = CARTESIAN_POINT('',(55.238908,21.795721,1.1)); +#23790 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23791 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23792 = DEFINITIONAL_REPRESENTATION('',(#23793),#23796); +#23793 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23794,#23795),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#21402 = CARTESIAN_POINT('',(0.E+000,0.25)); -#21403 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#21404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21405 = ADVANCED_FACE('',(#21406),#18628,.T.); -#21406 = FACE_BOUND('',#21407,.T.); -#21407 = EDGE_LOOP('',(#21408,#21409,#21429,#21430)); -#21408 = ORIENTED_EDGE('',*,*,#18614,.F.); -#21409 = ORIENTED_EDGE('',*,*,#21410,.T.); -#21410 = EDGE_CURVE('',#18587,#21280,#21411,.T.); -#21411 = SURFACE_CURVE('',#21412,(#21416,#21423),.PCURVE_S1.); -#21412 = LINE('',#21413,#21414); -#21413 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); -#21414 = VECTOR('',#21415,1.); -#21415 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#21416 = PCURVE('',#18628,#21417); -#21417 = DEFINITIONAL_REPRESENTATION('',(#21418),#21422); -#21418 = LINE('',#21419,#21420); -#21419 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#21420 = VECTOR('',#21421,1.); -#21421 = DIRECTION('',(0.E+000,1.)); -#21422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21423 = PCURVE('',#18603,#21424); -#21424 = DEFINITIONAL_REPRESENTATION('',(#21425),#21428); -#21425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21426,#21427),.UNSPECIFIED., +#23794 = CARTESIAN_POINT('',(0.E+000,0.25)); +#23795 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#23796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23797 = ADVANCED_FACE('',(#23798),#21020,.T.); +#23798 = FACE_BOUND('',#23799,.T.); +#23799 = EDGE_LOOP('',(#23800,#23801,#23821,#23822)); +#23800 = ORIENTED_EDGE('',*,*,#21006,.F.); +#23801 = ORIENTED_EDGE('',*,*,#23802,.T.); +#23802 = EDGE_CURVE('',#20979,#23672,#23803,.T.); +#23803 = SURFACE_CURVE('',#23804,(#23808,#23815),.PCURVE_S1.); +#23804 = LINE('',#23805,#23806); +#23805 = CARTESIAN_POINT('',(55.663172068712,22.145721,1.45)); +#23806 = VECTOR('',#23807,1.); +#23807 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23808 = PCURVE('',#21020,#23809); +#23809 = DEFINITIONAL_REPRESENTATION('',(#23810),#23814); +#23810 = LINE('',#23811,#23812); +#23811 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#23812 = VECTOR('',#23813,1.); +#23813 = DIRECTION('',(0.E+000,1.)); +#23814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23815 = PCURVE('',#20995,#23816); +#23816 = DEFINITIONAL_REPRESENTATION('',(#23817),#23820); +#23817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23818,#23819),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.1),.PIECEWISE_BEZIER_KNOTS.); -#21426 = CARTESIAN_POINT('',(2.451817652804,0.E+000)); -#21427 = CARTESIAN_POINT('',(2.451817652804,-0.1)); -#21428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21429 = ORIENTED_EDGE('',*,*,#21279,.F.); -#21430 = ORIENTED_EDGE('',*,*,#21136,.T.); -#21431 = ADVANCED_FACE('',(#21432),#18603,.T.); -#21432 = FACE_BOUND('',#21433,.T.); -#21433 = EDGE_LOOP('',(#21434,#21435,#21455,#21456)); -#21434 = ORIENTED_EDGE('',*,*,#18586,.F.); -#21435 = ORIENTED_EDGE('',*,*,#21436,.T.); -#21436 = EDGE_CURVE('',#18559,#21303,#21437,.T.); -#21437 = SURFACE_CURVE('',#21438,(#21442,#21448),.PCURVE_S1.); -#21438 = LINE('',#21439,#21440); -#21439 = CARTESIAN_POINT('',(54.814643931288,22.145721,1.45)); -#21440 = VECTOR('',#21441,1.); -#21441 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#21442 = PCURVE('',#18603,#21443); -#21443 = DEFINITIONAL_REPRESENTATION('',(#21444),#21447); -#21444 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21445,#21446),.UNSPECIFIED., +#23818 = CARTESIAN_POINT('',(2.451817652804,0.E+000)); +#23819 = CARTESIAN_POINT('',(2.451817652804,-0.1)); +#23820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23821 = ORIENTED_EDGE('',*,*,#23671,.F.); +#23822 = ORIENTED_EDGE('',*,*,#23528,.T.); +#23823 = ADVANCED_FACE('',(#23824),#20995,.T.); +#23824 = FACE_BOUND('',#23825,.T.); +#23825 = EDGE_LOOP('',(#23826,#23827,#23847,#23848)); +#23826 = ORIENTED_EDGE('',*,*,#20978,.F.); +#23827 = ORIENTED_EDGE('',*,*,#23828,.T.); +#23828 = EDGE_CURVE('',#20951,#23695,#23829,.T.); +#23829 = SURFACE_CURVE('',#23830,(#23834,#23840),.PCURVE_S1.); +#23830 = LINE('',#23831,#23832); +#23831 = CARTESIAN_POINT('',(54.814643931288,22.145721,1.45)); +#23832 = VECTOR('',#23833,1.); +#23833 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23834 = PCURVE('',#20995,#23835); +#23835 = DEFINITIONAL_REPRESENTATION('',(#23836),#23839); +#23836 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23837,#23838),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.1),.PIECEWISE_BEZIER_KNOTS.); -#21445 = CARTESIAN_POINT('',(0.689775000786,0.E+000)); -#21446 = CARTESIAN_POINT('',(0.689775000786,-0.1)); -#21447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#23837 = CARTESIAN_POINT('',(0.689775000786,0.E+000)); +#23838 = CARTESIAN_POINT('',(0.689775000786,-0.1)); +#23839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23840 = PCURVE('',#20966,#23841); +#23841 = DEFINITIONAL_REPRESENTATION('',(#23842),#23846); +#23842 = LINE('',#23843,#23844); +#23843 = CARTESIAN_POINT('',(-0.35033260053,0.E+000)); +#23844 = VECTOR('',#23845,1.); +#23845 = DIRECTION('',(0.E+000,1.)); +#23846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23847 = ORIENTED_EDGE('',*,*,#23694,.T.); +#23848 = ORIENTED_EDGE('',*,*,#23802,.F.); +#23849 = ADVANCED_FACE('',(#23850),#20966,.T.); +#23850 = FACE_BOUND('',#23851,.T.); +#23851 = EDGE_LOOP('',(#23852,#23853,#23854,#23855)); +#23852 = ORIENTED_EDGE('',*,*,#20950,.F.); +#23853 = ORIENTED_EDGE('',*,*,#23549,.F.); +#23854 = ORIENTED_EDGE('',*,*,#23717,.F.); +#23855 = ORIENTED_EDGE('',*,*,#23828,.F.); +#23856 = ADVANCED_FACE('',(#23857),#21821,.T.); +#23857 = FACE_BOUND('',#23858,.T.); +#23858 = EDGE_LOOP('',(#23859,#23860,#23861,#23862)); +#23859 = ORIENTED_EDGE('',*,*,#21805,.F.); +#23860 = ORIENTED_EDGE('',*,*,#22621,.F.); +#23861 = ORIENTED_EDGE('',*,*,#23648,.T.); +#23862 = ORIENTED_EDGE('',*,*,#23863,.F.); +#23863 = EDGE_CURVE('',#21806,#23626,#23864,.T.); +#23864 = SURFACE_CURVE('',#23865,(#23869,#23876),.PCURVE_S1.); +#23865 = LINE('',#23866,#23867); +#23866 = CARTESIAN_POINT('',(55.663172068712,22.145721,0.75)); +#23867 = VECTOR('',#23868,1.); +#23868 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23869 = PCURVE('',#21821,#23870); +#23870 = DEFINITIONAL_REPRESENTATION('',(#23871),#23875); +#23871 = LINE('',#23872,#23873); +#23872 = CARTESIAN_POINT('',(-0.35033260053,0.E+000)); +#23873 = VECTOR('',#23874,1.); +#23874 = DIRECTION('',(0.E+000,1.)); +#23875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21448 = PCURVE('',#18574,#21449); -#21449 = DEFINITIONAL_REPRESENTATION('',(#21450),#21454); -#21450 = LINE('',#21451,#21452); -#21451 = CARTESIAN_POINT('',(-0.35033260053,0.E+000)); -#21452 = VECTOR('',#21453,1.); -#21453 = DIRECTION('',(0.E+000,1.)); -#21454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21455 = ORIENTED_EDGE('',*,*,#21302,.T.); -#21456 = ORIENTED_EDGE('',*,*,#21410,.F.); -#21457 = ADVANCED_FACE('',(#21458),#18574,.T.); -#21458 = FACE_BOUND('',#21459,.T.); -#21459 = EDGE_LOOP('',(#21460,#21461,#21462,#21463)); -#21460 = ORIENTED_EDGE('',*,*,#18558,.F.); -#21461 = ORIENTED_EDGE('',*,*,#21157,.F.); -#21462 = ORIENTED_EDGE('',*,*,#21325,.F.); -#21463 = ORIENTED_EDGE('',*,*,#21436,.F.); -#21464 = ADVANCED_FACE('',(#21465),#19429,.T.); -#21465 = FACE_BOUND('',#21466,.T.); -#21466 = EDGE_LOOP('',(#21467,#21468,#21469,#21470)); -#21467 = ORIENTED_EDGE('',*,*,#19413,.F.); -#21468 = ORIENTED_EDGE('',*,*,#20229,.F.); -#21469 = ORIENTED_EDGE('',*,*,#21256,.T.); -#21470 = ORIENTED_EDGE('',*,*,#21471,.F.); -#21471 = EDGE_CURVE('',#19414,#21234,#21472,.T.); -#21472 = SURFACE_CURVE('',#21473,(#21477,#21484),.PCURVE_S1.); -#21473 = LINE('',#21474,#21475); -#21474 = CARTESIAN_POINT('',(55.663172068712,22.145721,0.75)); -#21475 = VECTOR('',#21476,1.); -#21476 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#21477 = PCURVE('',#19429,#21478); -#21478 = DEFINITIONAL_REPRESENTATION('',(#21479),#21483); -#21479 = LINE('',#21480,#21481); -#21480 = CARTESIAN_POINT('',(-0.35033260053,0.E+000)); -#21481 = VECTOR('',#21482,1.); -#21482 = DIRECTION('',(0.E+000,1.)); -#21483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21484 = PCURVE('',#19458,#21485); -#21485 = DEFINITIONAL_REPRESENTATION('',(#21486),#21489); -#21486 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21487,#21488),.UNSPECIFIED., +#23876 = PCURVE('',#21850,#23877); +#23877 = DEFINITIONAL_REPRESENTATION('',(#23878),#23881); +#23878 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23879,#23880),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.1),.PIECEWISE_BEZIER_KNOTS.); -#21487 = CARTESIAN_POINT('',(3.831367654375,0.E+000)); -#21488 = CARTESIAN_POINT('',(3.831367654375,-0.1)); -#21489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21490 = ADVANCED_FACE('',(#21491),#19483,.T.); -#21491 = FACE_BOUND('',#21492,.T.); -#21492 = EDGE_LOOP('',(#21493,#21494,#21514,#21515)); -#21493 = ORIENTED_EDGE('',*,*,#19469,.F.); -#21494 = ORIENTED_EDGE('',*,*,#21495,.T.); -#21495 = EDGE_CURVE('',#19442,#21211,#21496,.T.); -#21496 = SURFACE_CURVE('',#21497,(#21501,#21508),.PCURVE_S1.); -#21497 = LINE('',#21498,#21499); -#21498 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); -#21499 = VECTOR('',#21500,1.); -#21500 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#21501 = PCURVE('',#19483,#21502); -#21502 = DEFINITIONAL_REPRESENTATION('',(#21503),#21507); -#21503 = LINE('',#21504,#21505); -#21504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#21505 = VECTOR('',#21506,1.); -#21506 = DIRECTION('',(0.E+000,1.)); -#21507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21508 = PCURVE('',#19458,#21509); -#21509 = DEFINITIONAL_REPRESENTATION('',(#21510),#21513); -#21510 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21511,#21512),.UNSPECIFIED., +#23879 = CARTESIAN_POINT('',(3.831367654375,0.E+000)); +#23880 = CARTESIAN_POINT('',(3.831367654375,-0.1)); +#23881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23882 = ADVANCED_FACE('',(#23883),#21875,.T.); +#23883 = FACE_BOUND('',#23884,.T.); +#23884 = EDGE_LOOP('',(#23885,#23886,#23906,#23907)); +#23885 = ORIENTED_EDGE('',*,*,#21861,.F.); +#23886 = ORIENTED_EDGE('',*,*,#23887,.T.); +#23887 = EDGE_CURVE('',#21834,#23603,#23888,.T.); +#23888 = SURFACE_CURVE('',#23889,(#23893,#23900),.PCURVE_S1.); +#23889 = LINE('',#23890,#23891); +#23890 = CARTESIAN_POINT('',(54.814643931288,22.145721,0.75)); +#23891 = VECTOR('',#23892,1.); +#23892 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23893 = PCURVE('',#21875,#23894); +#23894 = DEFINITIONAL_REPRESENTATION('',(#23895),#23899); +#23895 = LINE('',#23896,#23897); +#23896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#23897 = VECTOR('',#23898,1.); +#23898 = DIRECTION('',(0.E+000,1.)); +#23899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23900 = PCURVE('',#21850,#23901); +#23901 = DEFINITIONAL_REPRESENTATION('',(#23902),#23905); +#23902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23903,#23904),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.1),.PIECEWISE_BEZIER_KNOTS.); -#21511 = CARTESIAN_POINT('',(5.593410306394,0.E+000)); -#21512 = CARTESIAN_POINT('',(5.593410306394,-0.1)); -#21513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21514 = ORIENTED_EDGE('',*,*,#21210,.T.); -#21515 = ORIENTED_EDGE('',*,*,#20206,.T.); -#21516 = ADVANCED_FACE('',(#21517),#19458,.T.); -#21517 = FACE_BOUND('',#21518,.T.); -#21518 = EDGE_LOOP('',(#21519,#21520,#21521,#21522)); -#21519 = ORIENTED_EDGE('',*,*,#19441,.F.); -#21520 = ORIENTED_EDGE('',*,*,#21471,.T.); -#21521 = ORIENTED_EDGE('',*,*,#21233,.T.); -#21522 = ORIENTED_EDGE('',*,*,#21495,.F.); -#21523 = ADVANCED_FACE('',(#21524),#18226,.T.); -#21524 = FACE_BOUND('',#21525,.T.); -#21525 = EDGE_LOOP('',(#21526,#21527,#21548,#21549)); -#21526 = ORIENTED_EDGE('',*,*,#20833,.T.); -#21527 = ORIENTED_EDGE('',*,*,#21528,.T.); -#21528 = EDGE_CURVE('',#20811,#19135,#21529,.T.); -#21529 = SURFACE_CURVE('',#21530,(#21534,#21541),.PCURVE_S1.); -#21530 = LINE('',#21531,#21532); -#21531 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); -#21532 = VECTOR('',#21533,1.); -#21533 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#21534 = PCURVE('',#18226,#21535); -#21535 = DEFINITIONAL_REPRESENTATION('',(#21536),#21540); -#21536 = LINE('',#21537,#21538); -#21537 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#21538 = VECTOR('',#21539,1.); -#21539 = DIRECTION('',(0.E+000,1.)); -#21540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21541 = PCURVE('',#19173,#21542); -#21542 = DEFINITIONAL_REPRESENTATION('',(#21543),#21547); -#21543 = LINE('',#21544,#21545); -#21544 = CARTESIAN_POINT('',(-1.8,0.E+000)); -#21545 = VECTOR('',#21546,1.); -#21546 = DIRECTION('',(0.E+000,1.)); -#21547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21548 = ORIENTED_EDGE('',*,*,#19134,.F.); -#21549 = ORIENTED_EDGE('',*,*,#18210,.T.); -#21550 = ADVANCED_FACE('',(#21551),#19173,.T.); -#21551 = FACE_BOUND('',#21552,.T.); -#21552 = EDGE_LOOP('',(#21553,#21554,#21555,#21556)); -#21553 = ORIENTED_EDGE('',*,*,#20810,.T.); -#21554 = ORIENTED_EDGE('',*,*,#19211,.T.); -#21555 = ORIENTED_EDGE('',*,*,#19157,.F.); -#21556 = ORIENTED_EDGE('',*,*,#21528,.F.); -#21557 = ADVANCED_FACE('',(#21558),#21369,.T.); -#21558 = FACE_BOUND('',#21559,.T.); -#21559 = EDGE_LOOP('',(#21560,#21619,#21638,#21639)); -#21560 = ORIENTED_EDGE('',*,*,#21561,.T.); -#21561 = EDGE_CURVE('',#21562,#21564,#21566,.T.); -#21562 = VERTEX_POINT('',#21563); -#21563 = CARTESIAN_POINT('',(54.988908,21.465721,1.1)); -#21564 = VERTEX_POINT('',#21565); -#21565 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); -#21566 = SURFACE_CURVE('',#21567,(#21572,#21578),.PCURVE_S1.); -#21567 = CIRCLE('',#21568,0.25); -#21568 = AXIS2_PLACEMENT_3D('',#21569,#21570,#21571); -#21569 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); -#21570 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21571 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21572 = PCURVE('',#21369,#21573); -#21573 = DEFINITIONAL_REPRESENTATION('',(#21574),#21577); -#21574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21575,#21576),.UNSPECIFIED., +#23903 = CARTESIAN_POINT('',(5.593410306394,0.E+000)); +#23904 = CARTESIAN_POINT('',(5.593410306394,-0.1)); +#23905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23906 = ORIENTED_EDGE('',*,*,#23602,.T.); +#23907 = ORIENTED_EDGE('',*,*,#22598,.T.); +#23908 = ADVANCED_FACE('',(#23909),#21850,.T.); +#23909 = FACE_BOUND('',#23910,.T.); +#23910 = EDGE_LOOP('',(#23911,#23912,#23913,#23914)); +#23911 = ORIENTED_EDGE('',*,*,#21833,.F.); +#23912 = ORIENTED_EDGE('',*,*,#23863,.T.); +#23913 = ORIENTED_EDGE('',*,*,#23625,.T.); +#23914 = ORIENTED_EDGE('',*,*,#23887,.F.); +#23915 = ADVANCED_FACE('',(#23916),#20618,.T.); +#23916 = FACE_BOUND('',#23917,.T.); +#23917 = EDGE_LOOP('',(#23918,#23919,#23940,#23941)); +#23918 = ORIENTED_EDGE('',*,*,#23225,.T.); +#23919 = ORIENTED_EDGE('',*,*,#23920,.T.); +#23920 = EDGE_CURVE('',#23203,#21527,#23921,.T.); +#23921 = SURFACE_CURVE('',#23922,(#23926,#23933),.PCURVE_S1.); +#23922 = LINE('',#23923,#23924); +#23923 = CARTESIAN_POINT('',(53.738908,22.495721,2.)); +#23924 = VECTOR('',#23925,1.); +#23925 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#23926 = PCURVE('',#20618,#23927); +#23927 = DEFINITIONAL_REPRESENTATION('',(#23928),#23932); +#23928 = LINE('',#23929,#23930); +#23929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#23930 = VECTOR('',#23931,1.); +#23931 = DIRECTION('',(0.E+000,1.)); +#23932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23933 = PCURVE('',#21565,#23934); +#23934 = DEFINITIONAL_REPRESENTATION('',(#23935),#23939); +#23935 = LINE('',#23936,#23937); +#23936 = CARTESIAN_POINT('',(-1.8,0.E+000)); +#23937 = VECTOR('',#23938,1.); +#23938 = DIRECTION('',(0.E+000,1.)); +#23939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#23940 = ORIENTED_EDGE('',*,*,#21526,.F.); +#23941 = ORIENTED_EDGE('',*,*,#20602,.T.); +#23942 = ADVANCED_FACE('',(#23943),#21565,.T.); +#23943 = FACE_BOUND('',#23944,.T.); +#23944 = EDGE_LOOP('',(#23945,#23946,#23947,#23948)); +#23945 = ORIENTED_EDGE('',*,*,#23202,.T.); +#23946 = ORIENTED_EDGE('',*,*,#21603,.T.); +#23947 = ORIENTED_EDGE('',*,*,#21549,.F.); +#23948 = ORIENTED_EDGE('',*,*,#23920,.F.); +#23949 = ADVANCED_FACE('',(#23950),#23761,.T.); +#23950 = FACE_BOUND('',#23951,.T.); +#23951 = EDGE_LOOP('',(#23952,#24011,#24030,#24031)); +#23952 = ORIENTED_EDGE('',*,*,#23953,.T.); +#23953 = EDGE_CURVE('',#23954,#23956,#23958,.T.); +#23954 = VERTEX_POINT('',#23955); +#23955 = CARTESIAN_POINT('',(54.988908,21.465721,1.1)); +#23956 = VERTEX_POINT('',#23957); +#23957 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); +#23958 = SURFACE_CURVE('',#23959,(#23964,#23970),.PCURVE_S1.); +#23959 = CIRCLE('',#23960,0.25); +#23960 = AXIS2_PLACEMENT_3D('',#23961,#23962,#23963); +#23961 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); +#23962 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23963 = DIRECTION('',(1.,0.E+000,0.E+000)); +#23964 = PCURVE('',#23761,#23965); +#23965 = DEFINITIONAL_REPRESENTATION('',(#23966),#23969); +#23966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#23967,#23968),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#21575 = CARTESIAN_POINT('',(3.14159265359,-0.33)); -#21576 = CARTESIAN_POINT('',(6.28318530718,-0.33)); -#21577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#23967 = CARTESIAN_POINT('',(3.14159265359,-0.33)); +#23968 = CARTESIAN_POINT('',(6.28318530718,-0.33)); +#23969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21578 = PCURVE('',#21579,#21591); -#21579 = SURFACE_OF_REVOLUTION('',#21580,#21588); -#21580 = B_SPLINE_CURVE_WITH_KNOTS('',6,(#21581,#21582,#21583,#21584, - #21585,#21586,#21587),.UNSPECIFIED.,.F.,.F.,(7,7),(4.712388980385, +#23970 = PCURVE('',#23971,#23983); +#23971 = SURFACE_OF_REVOLUTION('',#23972,#23980); +#23972 = B_SPLINE_CURVE_WITH_KNOTS('',6,(#23973,#23974,#23975,#23976, + #23977,#23978,#23979),.UNSPECIFIED.,.F.,.F.,(7,7),(4.712388980385, 6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#21581 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); -#21582 = CARTESIAN_POINT('',(55.326503865316,21.245721,1.1)); -#21583 = CARTESIAN_POINT('',(55.384094830155,21.263811090924,1.1)); -#21584 = CARTESIAN_POINT('',(55.434609832921,21.300019167079,1.1)); -#21585 = CARTESIAN_POINT('',(55.470817909075,21.350534169845,1.1)); -#21586 = CARTESIAN_POINT('',(55.488908,21.408125134684,1.1)); -#21587 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); -#21588 = AXIS1_PLACEMENT('',#21589,#21590); -#21589 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); -#21590 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21591 = DEFINITIONAL_REPRESENTATION('',(#21592),#21618); -#21592 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21593,#21594,#21595,#21596, - #21597,#21598,#21599,#21600,#21601,#21602,#21603,#21604,#21605, - #21606,#21607,#21608,#21609,#21610,#21611,#21612,#21613,#21614, - #21615,#21616,#21617),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#23973 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); +#23974 = CARTESIAN_POINT('',(55.326503865316,21.245721,1.1)); +#23975 = CARTESIAN_POINT('',(55.384094830155,21.263811090924,1.1)); +#23976 = CARTESIAN_POINT('',(55.434609832921,21.300019167079,1.1)); +#23977 = CARTESIAN_POINT('',(55.470817909075,21.350534169845,1.1)); +#23978 = CARTESIAN_POINT('',(55.488908,21.408125134684,1.1)); +#23979 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); +#23980 = AXIS1_PLACEMENT('',#23981,#23982); +#23981 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); +#23982 = DIRECTION('',(0.E+000,1.,0.E+000)); +#23983 = DEFINITIONAL_REPRESENTATION('',(#23984),#24010); +#23984 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#23985,#23986,#23987,#23988, + #23989,#23990,#23991,#23992,#23993,#23994,#23995,#23996,#23997, + #23998,#23999,#24000,#24001,#24002,#24003,#24004,#24005,#24006, + #24007,#24008,#24009),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -26483,149 +29472,149 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#21593 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); -#21594 = CARTESIAN_POINT('',(3.189192542281,6.28318530718)); -#21595 = CARTESIAN_POINT('',(3.284392319662,6.28318530718)); -#21596 = CARTESIAN_POINT('',(3.427191985734,6.28318530718)); -#21597 = CARTESIAN_POINT('',(3.569991651807,6.28318530718)); -#21598 = CARTESIAN_POINT('',(3.712791317879,6.28318530718)); -#21599 = CARTESIAN_POINT('',(3.855590983951,6.28318530718)); -#21600 = CARTESIAN_POINT('',(3.998390650023,6.28318530718)); -#21601 = CARTESIAN_POINT('',(4.141190316096,6.28318530718)); -#21602 = CARTESIAN_POINT('',(4.283989982168,6.28318530718)); -#21603 = CARTESIAN_POINT('',(4.42678964824,6.28318530718)); -#21604 = CARTESIAN_POINT('',(4.569589314312,6.28318530718)); -#21605 = CARTESIAN_POINT('',(4.712388980385,6.28318530718)); -#21606 = CARTESIAN_POINT('',(4.855188646457,6.28318530718)); -#21607 = CARTESIAN_POINT('',(4.997988312529,6.28318530718)); -#21608 = CARTESIAN_POINT('',(5.140787978601,6.28318530718)); -#21609 = CARTESIAN_POINT('',(5.283587644674,6.28318530718)); -#21610 = CARTESIAN_POINT('',(5.426387310746,6.28318530718)); -#21611 = CARTESIAN_POINT('',(5.569186976818,6.28318530718)); -#21612 = CARTESIAN_POINT('',(5.711986642891,6.28318530718)); -#21613 = CARTESIAN_POINT('',(5.854786308963,6.28318530718)); -#21614 = CARTESIAN_POINT('',(5.997585975035,6.28318530718)); -#21615 = CARTESIAN_POINT('',(6.140385641107,6.28318530718)); -#21616 = CARTESIAN_POINT('',(6.235585418489,6.28318530718)); -#21617 = CARTESIAN_POINT('',(6.28318530718,6.28318530718)); -#21618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21619 = ORIENTED_EDGE('',*,*,#21620,.T.); -#21620 = EDGE_CURVE('',#21564,#21353,#21621,.T.); -#21621 = SURFACE_CURVE('',#21622,(#21626,#21632),.PCURVE_S1.); -#21622 = LINE('',#21623,#21624); -#21623 = CARTESIAN_POINT('',(55.488908,21.795721,1.1)); -#21624 = VECTOR('',#21625,1.); -#21625 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21626 = PCURVE('',#21369,#21627); -#21627 = DEFINITIONAL_REPRESENTATION('',(#21628),#21631); -#21628 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21629,#21630),.UNSPECIFIED., +#23985 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); +#23986 = CARTESIAN_POINT('',(3.189192542281,6.28318530718)); +#23987 = CARTESIAN_POINT('',(3.284392319662,6.28318530718)); +#23988 = CARTESIAN_POINT('',(3.427191985734,6.28318530718)); +#23989 = CARTESIAN_POINT('',(3.569991651807,6.28318530718)); +#23990 = CARTESIAN_POINT('',(3.712791317879,6.28318530718)); +#23991 = CARTESIAN_POINT('',(3.855590983951,6.28318530718)); +#23992 = CARTESIAN_POINT('',(3.998390650023,6.28318530718)); +#23993 = CARTESIAN_POINT('',(4.141190316096,6.28318530718)); +#23994 = CARTESIAN_POINT('',(4.283989982168,6.28318530718)); +#23995 = CARTESIAN_POINT('',(4.42678964824,6.28318530718)); +#23996 = CARTESIAN_POINT('',(4.569589314312,6.28318530718)); +#23997 = CARTESIAN_POINT('',(4.712388980385,6.28318530718)); +#23998 = CARTESIAN_POINT('',(4.855188646457,6.28318530718)); +#23999 = CARTESIAN_POINT('',(4.997988312529,6.28318530718)); +#24000 = CARTESIAN_POINT('',(5.140787978601,6.28318530718)); +#24001 = CARTESIAN_POINT('',(5.283587644674,6.28318530718)); +#24002 = CARTESIAN_POINT('',(5.426387310746,6.28318530718)); +#24003 = CARTESIAN_POINT('',(5.569186976818,6.28318530718)); +#24004 = CARTESIAN_POINT('',(5.711986642891,6.28318530718)); +#24005 = CARTESIAN_POINT('',(5.854786308963,6.28318530718)); +#24006 = CARTESIAN_POINT('',(5.997585975035,6.28318530718)); +#24007 = CARTESIAN_POINT('',(6.140385641107,6.28318530718)); +#24008 = CARTESIAN_POINT('',(6.235585418489,6.28318530718)); +#24009 = CARTESIAN_POINT('',(6.28318530718,6.28318530718)); +#24010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24011 = ORIENTED_EDGE('',*,*,#24012,.T.); +#24012 = EDGE_CURVE('',#23956,#23745,#24013,.T.); +#24013 = SURFACE_CURVE('',#24014,(#24018,#24024),.PCURVE_S1.); +#24014 = LINE('',#24015,#24016); +#24015 = CARTESIAN_POINT('',(55.488908,21.795721,1.1)); +#24016 = VECTOR('',#24017,1.); +#24017 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24018 = PCURVE('',#23761,#24019); +#24019 = DEFINITIONAL_REPRESENTATION('',(#24020),#24023); +#24020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24021,#24022),.UNSPECIFIED., .F.,.F.,(2,2),(-0.33,0.25),.PIECEWISE_BEZIER_KNOTS.); -#21629 = CARTESIAN_POINT('',(6.28318530718,-0.33)); -#21630 = CARTESIAN_POINT('',(6.28318530718,0.25)); -#21631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24021 = CARTESIAN_POINT('',(6.28318530718,-0.33)); +#24022 = CARTESIAN_POINT('',(6.28318530718,0.25)); +#24023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21632 = PCURVE('',#21395,#21633); -#21633 = DEFINITIONAL_REPRESENTATION('',(#21634),#21637); -#21634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21635,#21636),.UNSPECIFIED., +#24024 = PCURVE('',#23787,#24025); +#24025 = DEFINITIONAL_REPRESENTATION('',(#24026),#24029); +#24026 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24027,#24028),.UNSPECIFIED., .F.,.F.,(2,2),(-0.33,0.25),.PIECEWISE_BEZIER_KNOTS.); -#21635 = CARTESIAN_POINT('',(0.E+000,-0.33)); -#21636 = CARTESIAN_POINT('',(0.E+000,0.25)); -#21637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21638 = ORIENTED_EDGE('',*,*,#21350,.F.); -#21639 = ORIENTED_EDGE('',*,*,#21640,.F.); -#21640 = EDGE_CURVE('',#21562,#21351,#21641,.T.); -#21641 = SURFACE_CURVE('',#21642,(#21646,#21652),.PCURVE_S1.); -#21642 = LINE('',#21643,#21644); -#21643 = CARTESIAN_POINT('',(54.988908,21.795721,1.1)); -#21644 = VECTOR('',#21645,1.); -#21645 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21646 = PCURVE('',#21369,#21647); -#21647 = DEFINITIONAL_REPRESENTATION('',(#21648),#21651); -#21648 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21649,#21650),.UNSPECIFIED., +#24027 = CARTESIAN_POINT('',(0.E+000,-0.33)); +#24028 = CARTESIAN_POINT('',(0.E+000,0.25)); +#24029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24030 = ORIENTED_EDGE('',*,*,#23742,.F.); +#24031 = ORIENTED_EDGE('',*,*,#24032,.F.); +#24032 = EDGE_CURVE('',#23954,#23743,#24033,.T.); +#24033 = SURFACE_CURVE('',#24034,(#24038,#24044),.PCURVE_S1.); +#24034 = LINE('',#24035,#24036); +#24035 = CARTESIAN_POINT('',(54.988908,21.795721,1.1)); +#24036 = VECTOR('',#24037,1.); +#24037 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24038 = PCURVE('',#23761,#24039); +#24039 = DEFINITIONAL_REPRESENTATION('',(#24040),#24043); +#24040 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24041,#24042),.UNSPECIFIED., .F.,.F.,(2,2),(-0.33,0.25),.PIECEWISE_BEZIER_KNOTS.); -#21649 = CARTESIAN_POINT('',(3.14159265359,-0.33)); -#21650 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#21651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24041 = CARTESIAN_POINT('',(3.14159265359,-0.33)); +#24042 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#24043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21652 = PCURVE('',#21395,#21653); -#21653 = DEFINITIONAL_REPRESENTATION('',(#21654),#21657); -#21654 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21655,#21656),.UNSPECIFIED., +#24044 = PCURVE('',#23787,#24045); +#24045 = DEFINITIONAL_REPRESENTATION('',(#24046),#24049); +#24046 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24047,#24048),.UNSPECIFIED., .F.,.F.,(2,2),(-0.33,0.25),.PIECEWISE_BEZIER_KNOTS.); -#21655 = CARTESIAN_POINT('',(3.14159265359,-0.33)); -#21656 = CARTESIAN_POINT('',(3.14159265359,0.25)); -#21657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21658 = ADVANCED_FACE('',(#21659),#21579,.T.); -#21659 = FACE_BOUND('',#21660,.T.); -#21660 = EDGE_LOOP('',(#21661,#21662,#21696,#21747)); -#21661 = ORIENTED_EDGE('',*,*,#21561,.F.); -#21662 = ORIENTED_EDGE('',*,*,#21663,.T.); -#21663 = EDGE_CURVE('',#21562,#21664,#21666,.T.); -#21664 = VERTEX_POINT('',#21665); -#21665 = CARTESIAN_POINT('',(55.208908,21.245721,1.1)); -#21666 = SURFACE_CURVE('',#21667,(#21672,#21678),.PCURVE_S1.); -#21667 = CIRCLE('',#21668,0.22); -#21668 = AXIS2_PLACEMENT_3D('',#21669,#21670,#21671); -#21669 = CARTESIAN_POINT('',(55.208908,21.465721,1.1)); -#21670 = DIRECTION('',(0.E+000,0.E+000,1.)); -#21671 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21672 = PCURVE('',#21579,#21673); -#21673 = DEFINITIONAL_REPRESENTATION('',(#21674),#21677); -#21674 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21675,#21676),.UNSPECIFIED., +#24047 = CARTESIAN_POINT('',(3.14159265359,-0.33)); +#24048 = CARTESIAN_POINT('',(3.14159265359,0.25)); +#24049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24050 = ADVANCED_FACE('',(#24051),#23971,.T.); +#24051 = FACE_BOUND('',#24052,.T.); +#24052 = EDGE_LOOP('',(#24053,#24054,#24088,#24139)); +#24053 = ORIENTED_EDGE('',*,*,#23953,.F.); +#24054 = ORIENTED_EDGE('',*,*,#24055,.T.); +#24055 = EDGE_CURVE('',#23954,#24056,#24058,.T.); +#24056 = VERTEX_POINT('',#24057); +#24057 = CARTESIAN_POINT('',(55.208908,21.245721,1.1)); +#24058 = SURFACE_CURVE('',#24059,(#24064,#24070),.PCURVE_S1.); +#24059 = CIRCLE('',#24060,0.22); +#24060 = AXIS2_PLACEMENT_3D('',#24061,#24062,#24063); +#24061 = CARTESIAN_POINT('',(55.208908,21.465721,1.1)); +#24062 = DIRECTION('',(0.E+000,0.E+000,1.)); +#24063 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24064 = PCURVE('',#23971,#24065); +#24065 = DEFINITIONAL_REPRESENTATION('',(#24066),#24069); +#24066 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24067,#24068),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#21675 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); -#21676 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); -#21677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24067 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); +#24068 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); +#24069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21678 = PCURVE('',#21679,#21691); -#21679 = SURFACE_OF_REVOLUTION('',#21680,#21688); -#21680 = B_SPLINE_CURVE_WITH_KNOTS('',6,(#21681,#21682,#21683,#21684, - #21685,#21686,#21687),.UNSPECIFIED.,.F.,.F.,(7,7),(4.712388980385, +#24070 = PCURVE('',#24071,#24083); +#24071 = SURFACE_OF_REVOLUTION('',#24072,#24080); +#24072 = B_SPLINE_CURVE_WITH_KNOTS('',6,(#24073,#24074,#24075,#24076, + #24077,#24078,#24079),.UNSPECIFIED.,.F.,.F.,(7,7),(4.712388980385, 6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#21681 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); -#21682 = CARTESIAN_POINT('',(55.326503865316,21.245721,1.1)); -#21683 = CARTESIAN_POINT('',(55.384094830155,21.263811090924,1.1)); -#21684 = CARTESIAN_POINT('',(55.43460983292,21.300019167079,1.1)); -#21685 = CARTESIAN_POINT('',(55.470817909076,21.350534169845,1.1)); -#21686 = CARTESIAN_POINT('',(55.488908,21.408125134684,1.1)); -#21687 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); -#21688 = AXIS1_PLACEMENT('',#21689,#21690); -#21689 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); -#21690 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21691 = DEFINITIONAL_REPRESENTATION('',(#21692),#21695); -#21692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21693,#21694),.UNSPECIFIED., +#24073 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); +#24074 = CARTESIAN_POINT('',(55.326503865316,21.245721,1.1)); +#24075 = CARTESIAN_POINT('',(55.384094830155,21.263811090924,1.1)); +#24076 = CARTESIAN_POINT('',(55.43460983292,21.300019167079,1.1)); +#24077 = CARTESIAN_POINT('',(55.470817909076,21.350534169845,1.1)); +#24078 = CARTESIAN_POINT('',(55.488908,21.408125134684,1.1)); +#24079 = CARTESIAN_POINT('',(55.488908,21.465721,1.1)); +#24080 = AXIS1_PLACEMENT('',#24081,#24082); +#24081 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); +#24082 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24083 = DEFINITIONAL_REPRESENTATION('',(#24084),#24087); +#24084 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24085,#24086),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#21693 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); -#21694 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); -#21695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21696 = ORIENTED_EDGE('',*,*,#21697,.T.); -#21697 = EDGE_CURVE('',#21664,#21698,#21700,.T.); -#21698 = VERTEX_POINT('',#21699); -#21699 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); -#21700 = SURFACE_CURVE('',#21701,(#21706,#21735),.PCURVE_S1.); -#21701 = CIRCLE('',#21702,3.E-002); -#21702 = AXIS2_PLACEMENT_3D('',#21703,#21704,#21705); -#21703 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#21704 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21705 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21706 = PCURVE('',#21579,#21707); -#21707 = DEFINITIONAL_REPRESENTATION('',(#21708),#21734); -#21708 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21709,#21710,#21711,#21712, - #21713,#21714,#21715,#21716,#21717,#21718,#21719,#21720,#21721, - #21722,#21723,#21724,#21725,#21726,#21727,#21728,#21729,#21730, - #21731,#21732,#21733),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#24085 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); +#24086 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); +#24087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24088 = ORIENTED_EDGE('',*,*,#24089,.T.); +#24089 = EDGE_CURVE('',#24056,#24090,#24092,.T.); +#24090 = VERTEX_POINT('',#24091); +#24091 = CARTESIAN_POINT('',(55.268908,21.245721,1.1)); +#24092 = SURFACE_CURVE('',#24093,(#24098,#24127),.PCURVE_S1.); +#24093 = CIRCLE('',#24094,3.E-002); +#24094 = AXIS2_PLACEMENT_3D('',#24095,#24096,#24097); +#24095 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#24096 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24097 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24098 = PCURVE('',#23971,#24099); +#24099 = DEFINITIONAL_REPRESENTATION('',(#24100),#24126); +#24100 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#24101,#24102,#24103,#24104, + #24105,#24106,#24107,#24108,#24109,#24110,#24111,#24112,#24113, + #24114,#24115,#24116,#24117,#24118,#24119,#24120,#24121,#24122, + #24123,#24124,#24125),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.284392319662,3.427191985734 ,3.569991651807,3.712791317879,3.855590983951,3.998390650023, 4.141190316096,4.283989982168,4.42678964824,4.569589314312, @@ -26633,102 +29622,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.283587644674,5.426387310746,5.569186976818,5.711986642891, 5.854786308963,5.997585975035,6.140385641107,6.28318530718), .QUASI_UNIFORM_KNOTS.); -#21709 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); -#21710 = CARTESIAN_POINT('',(3.189192542281,4.712388980385)); -#21711 = CARTESIAN_POINT('',(3.284392319662,4.712388980385)); -#21712 = CARTESIAN_POINT('',(3.427191985734,4.712388980385)); -#21713 = CARTESIAN_POINT('',(3.569991651807,4.712388980385)); -#21714 = CARTESIAN_POINT('',(3.712791317879,4.712388980385)); -#21715 = CARTESIAN_POINT('',(3.855590983951,4.712388980385)); -#21716 = CARTESIAN_POINT('',(3.998390650023,4.712388980385)); -#21717 = CARTESIAN_POINT('',(4.141190316096,4.712388980385)); -#21718 = CARTESIAN_POINT('',(4.283989982168,4.712388980385)); -#21719 = CARTESIAN_POINT('',(4.42678964824,4.712388980385)); -#21720 = CARTESIAN_POINT('',(4.569589314313,4.712388980385)); -#21721 = CARTESIAN_POINT('',(4.712388980385,4.712388980385)); -#21722 = CARTESIAN_POINT('',(4.855188646457,4.712388980385)); -#21723 = CARTESIAN_POINT('',(4.997988312529,4.712388980385)); -#21724 = CARTESIAN_POINT('',(5.140787978601,4.712388980385)); -#21725 = CARTESIAN_POINT('',(5.283587644674,4.712388980385)); -#21726 = CARTESIAN_POINT('',(5.426387310746,4.712388980385)); -#21727 = CARTESIAN_POINT('',(5.569186976818,4.712388980385)); -#21728 = CARTESIAN_POINT('',(5.71198664289,4.712388980385)); -#21729 = CARTESIAN_POINT('',(5.854786308963,4.712388980385)); -#21730 = CARTESIAN_POINT('',(5.997585975035,4.712388980385)); -#21731 = CARTESIAN_POINT('',(6.140385641107,4.712388980385)); -#21732 = CARTESIAN_POINT('',(6.235585418489,4.712388980385)); -#21733 = CARTESIAN_POINT('',(6.28318530718,4.712388980385)); -#21734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21735 = PCURVE('',#21736,#21741); -#21736 = PLANE('',#21737); -#21737 = AXIS2_PLACEMENT_3D('',#21738,#21739,#21740); -#21738 = CARTESIAN_POINT('',(55.113908,21.245721,1.1)); -#21739 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21740 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21741 = DEFINITIONAL_REPRESENTATION('',(#21742),#21746); -#21742 = CIRCLE('',#21743,3.E-002); -#21743 = AXIS2_PLACEMENT_2D('',#21744,#21745); -#21744 = CARTESIAN_POINT('',(0.125,0.E+000)); -#21745 = DIRECTION('',(1.,0.E+000)); -#21746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21747 = ORIENTED_EDGE('',*,*,#21748,.F.); -#21748 = EDGE_CURVE('',#21564,#21698,#21749,.T.); -#21749 = SURFACE_CURVE('',#21750,(#21755,#21761),.PCURVE_S1.); -#21750 = CIRCLE('',#21751,0.22); -#21751 = AXIS2_PLACEMENT_3D('',#21752,#21753,#21754); -#21752 = CARTESIAN_POINT('',(55.268908,21.465721,1.1)); -#21753 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#21754 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#21755 = PCURVE('',#21579,#21756); -#21756 = DEFINITIONAL_REPRESENTATION('',(#21757),#21760); -#21757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21758,#21759),.UNSPECIFIED., +#24101 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); +#24102 = CARTESIAN_POINT('',(3.189192542281,4.712388980385)); +#24103 = CARTESIAN_POINT('',(3.284392319662,4.712388980385)); +#24104 = CARTESIAN_POINT('',(3.427191985734,4.712388980385)); +#24105 = CARTESIAN_POINT('',(3.569991651807,4.712388980385)); +#24106 = CARTESIAN_POINT('',(3.712791317879,4.712388980385)); +#24107 = CARTESIAN_POINT('',(3.855590983951,4.712388980385)); +#24108 = CARTESIAN_POINT('',(3.998390650023,4.712388980385)); +#24109 = CARTESIAN_POINT('',(4.141190316096,4.712388980385)); +#24110 = CARTESIAN_POINT('',(4.283989982168,4.712388980385)); +#24111 = CARTESIAN_POINT('',(4.42678964824,4.712388980385)); +#24112 = CARTESIAN_POINT('',(4.569589314313,4.712388980385)); +#24113 = CARTESIAN_POINT('',(4.712388980385,4.712388980385)); +#24114 = CARTESIAN_POINT('',(4.855188646457,4.712388980385)); +#24115 = CARTESIAN_POINT('',(4.997988312529,4.712388980385)); +#24116 = CARTESIAN_POINT('',(5.140787978601,4.712388980385)); +#24117 = CARTESIAN_POINT('',(5.283587644674,4.712388980385)); +#24118 = CARTESIAN_POINT('',(5.426387310746,4.712388980385)); +#24119 = CARTESIAN_POINT('',(5.569186976818,4.712388980385)); +#24120 = CARTESIAN_POINT('',(5.71198664289,4.712388980385)); +#24121 = CARTESIAN_POINT('',(5.854786308963,4.712388980385)); +#24122 = CARTESIAN_POINT('',(5.997585975035,4.712388980385)); +#24123 = CARTESIAN_POINT('',(6.140385641107,4.712388980385)); +#24124 = CARTESIAN_POINT('',(6.235585418489,4.712388980385)); +#24125 = CARTESIAN_POINT('',(6.28318530718,4.712388980385)); +#24126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24127 = PCURVE('',#24128,#24133); +#24128 = PLANE('',#24129); +#24129 = AXIS2_PLACEMENT_3D('',#24130,#24131,#24132); +#24130 = CARTESIAN_POINT('',(55.113908,21.245721,1.1)); +#24131 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24132 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24133 = DEFINITIONAL_REPRESENTATION('',(#24134),#24138); +#24134 = CIRCLE('',#24135,3.E-002); +#24135 = AXIS2_PLACEMENT_2D('',#24136,#24137); +#24136 = CARTESIAN_POINT('',(0.125,0.E+000)); +#24137 = DIRECTION('',(1.,0.E+000)); +#24138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24139 = ORIENTED_EDGE('',*,*,#24140,.F.); +#24140 = EDGE_CURVE('',#23956,#24090,#24141,.T.); +#24141 = SURFACE_CURVE('',#24142,(#24147,#24153),.PCURVE_S1.); +#24142 = CIRCLE('',#24143,0.22); +#24143 = AXIS2_PLACEMENT_3D('',#24144,#24145,#24146); +#24144 = CARTESIAN_POINT('',(55.268908,21.465721,1.1)); +#24145 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#24146 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#24147 = PCURVE('',#23971,#24148); +#24148 = DEFINITIONAL_REPRESENTATION('',(#24149),#24152); +#24149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24150,#24151),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#21758 = CARTESIAN_POINT('',(6.28318530718,6.28318530718)); -#21759 = CARTESIAN_POINT('',(6.28318530718,4.712388980385)); -#21760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24150 = CARTESIAN_POINT('',(6.28318530718,6.28318530718)); +#24151 = CARTESIAN_POINT('',(6.28318530718,4.712388980385)); +#24152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21761 = PCURVE('',#21679,#21762); -#21762 = DEFINITIONAL_REPRESENTATION('',(#21763),#21766); -#21763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21764,#21765),.UNSPECIFIED., +#24153 = PCURVE('',#24071,#24154); +#24154 = DEFINITIONAL_REPRESENTATION('',(#24155),#24158); +#24155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24156,#24157),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#21764 = CARTESIAN_POINT('',(0.E+000,6.28318530718)); -#21765 = CARTESIAN_POINT('',(0.E+000,4.712388980385)); -#21766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21767 = ADVANCED_FACE('',(#21768),#21736,.F.); -#21768 = FACE_BOUND('',#21769,.T.); -#21769 = EDGE_LOOP('',(#21770,#21814)); -#21770 = ORIENTED_EDGE('',*,*,#21771,.F.); -#21771 = EDGE_CURVE('',#21698,#21664,#21772,.T.); -#21772 = SURFACE_CURVE('',#21773,(#21778,#21785),.PCURVE_S1.); -#21773 = CIRCLE('',#21774,3.E-002); -#21774 = AXIS2_PLACEMENT_3D('',#21775,#21776,#21777); -#21775 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); -#21776 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21777 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21778 = PCURVE('',#21736,#21779); -#21779 = DEFINITIONAL_REPRESENTATION('',(#21780),#21784); -#21780 = CIRCLE('',#21781,3.E-002); -#21781 = AXIS2_PLACEMENT_2D('',#21782,#21783); -#21782 = CARTESIAN_POINT('',(0.125,0.E+000)); -#21783 = DIRECTION('',(1.,0.E+000)); -#21784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21785 = PCURVE('',#21679,#21786); -#21786 = DEFINITIONAL_REPRESENTATION('',(#21787),#21813); -#21787 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21788,#21789,#21790,#21791, - #21792,#21793,#21794,#21795,#21796,#21797,#21798,#21799,#21800, - #21801,#21802,#21803,#21804,#21805,#21806,#21807,#21808,#21809, - #21810,#21811,#21812),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#24156 = CARTESIAN_POINT('',(0.E+000,6.28318530718)); +#24157 = CARTESIAN_POINT('',(0.E+000,4.712388980385)); +#24158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24159 = ADVANCED_FACE('',(#24160),#24128,.F.); +#24160 = FACE_BOUND('',#24161,.T.); +#24161 = EDGE_LOOP('',(#24162,#24206)); +#24162 = ORIENTED_EDGE('',*,*,#24163,.F.); +#24163 = EDGE_CURVE('',#24090,#24056,#24164,.T.); +#24164 = SURFACE_CURVE('',#24165,(#24170,#24177),.PCURVE_S1.); +#24165 = CIRCLE('',#24166,3.E-002); +#24166 = AXIS2_PLACEMENT_3D('',#24167,#24168,#24169); +#24167 = CARTESIAN_POINT('',(55.238908,21.245721,1.1)); +#24168 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24169 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24170 = PCURVE('',#24128,#24171); +#24171 = DEFINITIONAL_REPRESENTATION('',(#24172),#24176); +#24172 = CIRCLE('',#24173,3.E-002); +#24173 = AXIS2_PLACEMENT_2D('',#24174,#24175); +#24174 = CARTESIAN_POINT('',(0.125,0.E+000)); +#24175 = DIRECTION('',(1.,0.E+000)); +#24176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24177 = PCURVE('',#24071,#24178); +#24178 = DEFINITIONAL_REPRESENTATION('',(#24179),#24205); +#24179 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#24180,#24181,#24182,#24183, + #24184,#24185,#24186,#24187,#24188,#24189,#24190,#24191,#24192, + #24193,#24194,#24195,#24196,#24197,#24198,#24199,#24200,#24201, + #24202,#24203,#24204),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -26736,62 +29725,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#21788 = CARTESIAN_POINT('',(0.E+000,4.712388980385)); -#21789 = CARTESIAN_POINT('',(4.759988869077E-002,4.712388980385)); -#21790 = CARTESIAN_POINT('',(0.142799666072,4.712388980385)); -#21791 = CARTESIAN_POINT('',(0.285599332144,4.712388980385)); -#21792 = CARTESIAN_POINT('',(0.428398998217,4.712388980385)); -#21793 = CARTESIAN_POINT('',(0.571198664289,4.712388980385)); -#21794 = CARTESIAN_POINT('',(0.713998330361,4.712388980385)); -#21795 = CARTESIAN_POINT('',(0.856797996433,4.712388980385)); -#21796 = CARTESIAN_POINT('',(0.999597662506,4.712388980385)); -#21797 = CARTESIAN_POINT('',(1.142397328578,4.712388980385)); -#21798 = CARTESIAN_POINT('',(1.28519699465,4.712388980385)); -#21799 = CARTESIAN_POINT('',(1.427996660723,4.712388980385)); -#21800 = CARTESIAN_POINT('',(1.570796326795,4.712388980385)); -#21801 = CARTESIAN_POINT('',(1.713595992867,4.712388980385)); -#21802 = CARTESIAN_POINT('',(1.85639565894,4.712388980385)); -#21803 = CARTESIAN_POINT('',(1.999195325011,4.712388980385)); -#21804 = CARTESIAN_POINT('',(2.141994991084,4.712388980385)); -#21805 = CARTESIAN_POINT('',(2.284794657156,4.712388980385)); -#21806 = CARTESIAN_POINT('',(2.427594323229,4.712388980385)); -#21807 = CARTESIAN_POINT('',(2.570393989301,4.712388980385)); -#21808 = CARTESIAN_POINT('',(2.713193655373,4.712388980385)); -#21809 = CARTESIAN_POINT('',(2.855993321445,4.712388980385)); -#21810 = CARTESIAN_POINT('',(2.998792987518,4.712388980385)); -#21811 = CARTESIAN_POINT('',(3.093992764899,4.712388980385)); -#21812 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); -#21813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21814 = ORIENTED_EDGE('',*,*,#21697,.F.); -#21815 = ADVANCED_FACE('',(#21816),#21395,.T.); -#21816 = FACE_BOUND('',#21817,.T.); -#21817 = EDGE_LOOP('',(#21818,#21819,#21862,#21863)); -#21818 = ORIENTED_EDGE('',*,*,#21620,.F.); -#21819 = ORIENTED_EDGE('',*,*,#21820,.T.); -#21820 = EDGE_CURVE('',#21564,#21562,#21821,.T.); -#21821 = SURFACE_CURVE('',#21822,(#21827,#21833),.PCURVE_S1.); -#21822 = CIRCLE('',#21823,0.25); -#21823 = AXIS2_PLACEMENT_3D('',#21824,#21825,#21826); -#21824 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); -#21825 = DIRECTION('',(0.E+000,1.,0.E+000)); -#21826 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21827 = PCURVE('',#21395,#21828); -#21828 = DEFINITIONAL_REPRESENTATION('',(#21829),#21832); -#21829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#21830,#21831),.UNSPECIFIED., +#24180 = CARTESIAN_POINT('',(0.E+000,4.712388980385)); +#24181 = CARTESIAN_POINT('',(4.759988869077E-002,4.712388980385)); +#24182 = CARTESIAN_POINT('',(0.142799666072,4.712388980385)); +#24183 = CARTESIAN_POINT('',(0.285599332144,4.712388980385)); +#24184 = CARTESIAN_POINT('',(0.428398998217,4.712388980385)); +#24185 = CARTESIAN_POINT('',(0.571198664289,4.712388980385)); +#24186 = CARTESIAN_POINT('',(0.713998330361,4.712388980385)); +#24187 = CARTESIAN_POINT('',(0.856797996433,4.712388980385)); +#24188 = CARTESIAN_POINT('',(0.999597662506,4.712388980385)); +#24189 = CARTESIAN_POINT('',(1.142397328578,4.712388980385)); +#24190 = CARTESIAN_POINT('',(1.28519699465,4.712388980385)); +#24191 = CARTESIAN_POINT('',(1.427996660723,4.712388980385)); +#24192 = CARTESIAN_POINT('',(1.570796326795,4.712388980385)); +#24193 = CARTESIAN_POINT('',(1.713595992867,4.712388980385)); +#24194 = CARTESIAN_POINT('',(1.85639565894,4.712388980385)); +#24195 = CARTESIAN_POINT('',(1.999195325011,4.712388980385)); +#24196 = CARTESIAN_POINT('',(2.141994991084,4.712388980385)); +#24197 = CARTESIAN_POINT('',(2.284794657156,4.712388980385)); +#24198 = CARTESIAN_POINT('',(2.427594323229,4.712388980385)); +#24199 = CARTESIAN_POINT('',(2.570393989301,4.712388980385)); +#24200 = CARTESIAN_POINT('',(2.713193655373,4.712388980385)); +#24201 = CARTESIAN_POINT('',(2.855993321445,4.712388980385)); +#24202 = CARTESIAN_POINT('',(2.998792987518,4.712388980385)); +#24203 = CARTESIAN_POINT('',(3.093992764899,4.712388980385)); +#24204 = CARTESIAN_POINT('',(3.14159265359,4.712388980385)); +#24205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24206 = ORIENTED_EDGE('',*,*,#24089,.F.); +#24207 = ADVANCED_FACE('',(#24208),#23787,.T.); +#24208 = FACE_BOUND('',#24209,.T.); +#24209 = EDGE_LOOP('',(#24210,#24211,#24254,#24255)); +#24210 = ORIENTED_EDGE('',*,*,#24012,.F.); +#24211 = ORIENTED_EDGE('',*,*,#24212,.T.); +#24212 = EDGE_CURVE('',#23956,#23954,#24213,.T.); +#24213 = SURFACE_CURVE('',#24214,(#24219,#24225),.PCURVE_S1.); +#24214 = CIRCLE('',#24215,0.25); +#24215 = AXIS2_PLACEMENT_3D('',#24216,#24217,#24218); +#24216 = CARTESIAN_POINT('',(55.238908,21.465721,1.1)); +#24217 = DIRECTION('',(0.E+000,1.,0.E+000)); +#24218 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24219 = PCURVE('',#23787,#24220); +#24220 = DEFINITIONAL_REPRESENTATION('',(#24221),#24224); +#24221 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#24222,#24223),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#21830 = CARTESIAN_POINT('',(0.E+000,-0.33)); -#21831 = CARTESIAN_POINT('',(3.14159265359,-0.33)); -#21832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24222 = CARTESIAN_POINT('',(0.E+000,-0.33)); +#24223 = CARTESIAN_POINT('',(3.14159265359,-0.33)); +#24224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#21833 = PCURVE('',#21679,#21834); -#21834 = DEFINITIONAL_REPRESENTATION('',(#21835),#21861); -#21835 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#21836,#21837,#21838,#21839, - #21840,#21841,#21842,#21843,#21844,#21845,#21846,#21847,#21848, - #21849,#21850,#21851,#21852,#21853,#21854,#21855,#21856,#21857, - #21858,#21859,#21860),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#24225 = PCURVE('',#24071,#24226); +#24226 = DEFINITIONAL_REPRESENTATION('',(#24227),#24253); +#24227 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#24228,#24229,#24230,#24231, + #24232,#24233,#24234,#24235,#24236,#24237,#24238,#24239,#24240, + #24241,#24242,#24243,#24244,#24245,#24246,#24247,#24248,#24249, + #24250,#24251,#24252),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.142799666072,0.285599332145, 0.428398998217,0.571198664289,0.713998330361,0.856797996434, 0.999597662506,1.142397328578,1.28519699465,1.427996660723, @@ -26799,9676 +29788,9676 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.141994991084,2.284794657156,2.427594323228,2.570393989301, 2.713193655373,2.855993321445,2.998792987518,3.14159265359), .QUASI_UNIFORM_KNOTS.); -#21836 = CARTESIAN_POINT('',(0.E+000,6.28318530718)); -#21837 = CARTESIAN_POINT('',(4.759988869075E-002,6.28318530718)); -#21838 = CARTESIAN_POINT('',(0.142799666072,6.28318530718)); -#21839 = CARTESIAN_POINT('',(0.285599332145,6.28318530718)); -#21840 = CARTESIAN_POINT('',(0.428398998217,6.28318530718)); -#21841 = CARTESIAN_POINT('',(0.571198664289,6.28318530718)); -#21842 = CARTESIAN_POINT('',(0.713998330361,6.28318530718)); -#21843 = CARTESIAN_POINT('',(0.856797996434,6.28318530718)); -#21844 = CARTESIAN_POINT('',(0.999597662506,6.28318530718)); -#21845 = CARTESIAN_POINT('',(1.142397328578,6.28318530718)); -#21846 = CARTESIAN_POINT('',(1.28519699465,6.28318530718)); -#21847 = CARTESIAN_POINT('',(1.427996660723,6.28318530718)); -#21848 = CARTESIAN_POINT('',(1.570796326795,6.28318530718)); -#21849 = CARTESIAN_POINT('',(1.713595992867,6.28318530718)); -#21850 = CARTESIAN_POINT('',(1.856395658939,6.28318530718)); -#21851 = CARTESIAN_POINT('',(1.999195325012,6.28318530718)); -#21852 = CARTESIAN_POINT('',(2.141994991084,6.28318530718)); -#21853 = CARTESIAN_POINT('',(2.284794657156,6.28318530718)); -#21854 = CARTESIAN_POINT('',(2.427594323228,6.28318530718)); -#21855 = CARTESIAN_POINT('',(2.570393989301,6.28318530718)); -#21856 = CARTESIAN_POINT('',(2.713193655373,6.28318530718)); -#21857 = CARTESIAN_POINT('',(2.855993321445,6.28318530718)); -#21858 = CARTESIAN_POINT('',(2.998792987518,6.28318530718)); -#21859 = CARTESIAN_POINT('',(3.093992764899,6.28318530718)); -#21860 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); -#21861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#21862 = ORIENTED_EDGE('',*,*,#21640,.T.); -#21863 = ORIENTED_EDGE('',*,*,#21380,.F.); -#21864 = ADVANCED_FACE('',(#21865),#21679,.T.); -#21865 = FACE_BOUND('',#21866,.T.); -#21866 = EDGE_LOOP('',(#21867,#21868,#21869,#21870)); -#21867 = ORIENTED_EDGE('',*,*,#21771,.T.); -#21868 = ORIENTED_EDGE('',*,*,#21663,.F.); -#21869 = ORIENTED_EDGE('',*,*,#21820,.F.); -#21870 = ORIENTED_EDGE('',*,*,#21748,.T.); -#21871 = ADVANCED_FACE('',(#21872),#17751,.T.); -#21872 = FACE_BOUND('',#21873,.T.); -#21873 = EDGE_LOOP('',(#21874,#21875,#21876,#21877)); -#21874 = ORIENTED_EDGE('',*,*,#17735,.T.); -#21875 = ORIENTED_EDGE('',*,*,#20783,.F.); -#21876 = ORIENTED_EDGE('',*,*,#19031,.T.); -#21877 = ORIENTED_EDGE('',*,*,#19352,.T.); -#21878 = ADVANCED_FACE('',(#21879),#18016,.T.); -#21879 = FACE_BOUND('',#21880,.T.); -#21880 = EDGE_LOOP('',(#21881,#21882,#21883,#21884)); -#21881 = ORIENTED_EDGE('',*,*,#20757,.T.); -#21882 = ORIENTED_EDGE('',*,*,#20623,.T.); -#21883 = ORIENTED_EDGE('',*,*,#20669,.F.); -#21884 = ORIENTED_EDGE('',*,*,#18000,.T.); -#21885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#21889)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#21886,#21887,#21888)) +#24228 = CARTESIAN_POINT('',(0.E+000,6.28318530718)); +#24229 = CARTESIAN_POINT('',(4.759988869075E-002,6.28318530718)); +#24230 = CARTESIAN_POINT('',(0.142799666072,6.28318530718)); +#24231 = CARTESIAN_POINT('',(0.285599332145,6.28318530718)); +#24232 = CARTESIAN_POINT('',(0.428398998217,6.28318530718)); +#24233 = CARTESIAN_POINT('',(0.571198664289,6.28318530718)); +#24234 = CARTESIAN_POINT('',(0.713998330361,6.28318530718)); +#24235 = CARTESIAN_POINT('',(0.856797996434,6.28318530718)); +#24236 = CARTESIAN_POINT('',(0.999597662506,6.28318530718)); +#24237 = CARTESIAN_POINT('',(1.142397328578,6.28318530718)); +#24238 = CARTESIAN_POINT('',(1.28519699465,6.28318530718)); +#24239 = CARTESIAN_POINT('',(1.427996660723,6.28318530718)); +#24240 = CARTESIAN_POINT('',(1.570796326795,6.28318530718)); +#24241 = CARTESIAN_POINT('',(1.713595992867,6.28318530718)); +#24242 = CARTESIAN_POINT('',(1.856395658939,6.28318530718)); +#24243 = CARTESIAN_POINT('',(1.999195325012,6.28318530718)); +#24244 = CARTESIAN_POINT('',(2.141994991084,6.28318530718)); +#24245 = CARTESIAN_POINT('',(2.284794657156,6.28318530718)); +#24246 = CARTESIAN_POINT('',(2.427594323228,6.28318530718)); +#24247 = CARTESIAN_POINT('',(2.570393989301,6.28318530718)); +#24248 = CARTESIAN_POINT('',(2.713193655373,6.28318530718)); +#24249 = CARTESIAN_POINT('',(2.855993321445,6.28318530718)); +#24250 = CARTESIAN_POINT('',(2.998792987518,6.28318530718)); +#24251 = CARTESIAN_POINT('',(3.093992764899,6.28318530718)); +#24252 = CARTESIAN_POINT('',(3.14159265359,6.28318530718)); +#24253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24254 = ORIENTED_EDGE('',*,*,#24032,.T.); +#24255 = ORIENTED_EDGE('',*,*,#23772,.F.); +#24256 = ADVANCED_FACE('',(#24257),#24071,.T.); +#24257 = FACE_BOUND('',#24258,.T.); +#24258 = EDGE_LOOP('',(#24259,#24260,#24261,#24262)); +#24259 = ORIENTED_EDGE('',*,*,#24163,.T.); +#24260 = ORIENTED_EDGE('',*,*,#24055,.F.); +#24261 = ORIENTED_EDGE('',*,*,#24212,.F.); +#24262 = ORIENTED_EDGE('',*,*,#24140,.T.); +#24263 = ADVANCED_FACE('',(#24264),#20143,.T.); +#24264 = FACE_BOUND('',#24265,.T.); +#24265 = EDGE_LOOP('',(#24266,#24267,#24268,#24269)); +#24266 = ORIENTED_EDGE('',*,*,#20127,.T.); +#24267 = ORIENTED_EDGE('',*,*,#23175,.F.); +#24268 = ORIENTED_EDGE('',*,*,#21423,.T.); +#24269 = ORIENTED_EDGE('',*,*,#21744,.T.); +#24270 = ADVANCED_FACE('',(#24271),#20408,.T.); +#24271 = FACE_BOUND('',#24272,.T.); +#24272 = EDGE_LOOP('',(#24273,#24274,#24275,#24276)); +#24273 = ORIENTED_EDGE('',*,*,#23149,.T.); +#24274 = ORIENTED_EDGE('',*,*,#23015,.T.); +#24275 = ORIENTED_EDGE('',*,*,#23061,.F.); +#24276 = ORIENTED_EDGE('',*,*,#20392,.T.); +#24277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24281)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24278,#24279,#24280)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#21886 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#21887 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#21888 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#21889 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#21886, +#24278 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24279 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24280 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24281 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#24278, 'distance_accuracy_value','confusion accuracy'); -#21890 = SHAPE_DEFINITION_REPRESENTATION(#21891,#17666); -#21891 = PRODUCT_DEFINITION_SHAPE('','',#21892); -#21892 = PRODUCT_DEFINITION('design','',#21893,#21896); -#21893 = PRODUCT_DEFINITION_FORMATION('','',#21894); -#21894 = PRODUCT('U.FL-R-SMT-1','U.FL-R-SMT-1','',(#21895)); -#21895 = PRODUCT_CONTEXT('',#2,'mechanical'); -#21896 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#21897 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21898,#21900); -#21898 = ( REPRESENTATION_RELATIONSHIP('','',#17666,#17656) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21899) +#24282 = SHAPE_DEFINITION_REPRESENTATION(#24283,#20058); +#24283 = PRODUCT_DEFINITION_SHAPE('','',#24284); +#24284 = PRODUCT_DEFINITION('design','',#24285,#24288); +#24285 = PRODUCT_DEFINITION_FORMATION('','',#24286); +#24286 = PRODUCT('U.FL-R-SMT-1','U.FL-R-SMT-1','',(#24287)); +#24287 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24288 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24289 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24290,#24292); +#24290 = ( REPRESENTATION_RELATIONSHIP('','',#20058,#20048) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24291) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21899 = ITEM_DEFINED_TRANSFORMATION('','',#11,#17657); -#21900 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21901); -#21901 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('160','=>[0:1:1:25]','',#17651, - #21892,$); -#21902 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#21894)); -#21903 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21904,#21906); -#21904 = ( REPRESENTATION_RELATIONSHIP('','',#17656,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21905) +#24291 = ITEM_DEFINED_TRANSFORMATION('','',#11,#20049); +#24292 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24293); +#24293 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('261','=>[0:1:1:25]','',#20043, + #24284,$); +#24294 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24286)); +#24295 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24296,#24298); +#24296 = ( REPRESENTATION_RELATIONSHIP('','',#20048,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24297) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21905 = ITEM_DEFINED_TRANSFORMATION('','',#11,#51); -#21906 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21907); -#21907 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('161','=>[0:1:1:24]','',#5, - #17651,$); -#21908 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#17653)); -#21909 = SHAPE_DEFINITION_REPRESENTATION(#21910,#21916); -#21910 = PRODUCT_DEFINITION_SHAPE('','',#21911); -#21911 = PRODUCT_DEFINITION('design','',#21912,#21915); -#21912 = PRODUCT_DEFINITION_FORMATION('','',#21913); -#21913 = PRODUCT('R7','R7','',(#21914)); -#21914 = PRODUCT_CONTEXT('',#2,'mechanical'); -#21915 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#21916 = SHAPE_REPRESENTATION('',(#11,#21917),#21921); -#21917 = AXIS2_PLACEMENT_3D('',#21918,#21919,#21920); -#21918 = CARTESIAN_POINT('',(17.4030005,6.35,-1.27E-002)); -#21919 = DIRECTION('',(0.E+000,0.E+000,1.)); -#21920 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#21921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#21925)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#21922,#21923,#21924)) +#24297 = ITEM_DEFINED_TRANSFORMATION('','',#11,#51); +#24298 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24299); +#24299 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('262','=>[0:1:1:24]','',#5, + #20043,$); +#24300 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#20045)); +#24301 = SHAPE_DEFINITION_REPRESENTATION(#24302,#24308); +#24302 = PRODUCT_DEFINITION_SHAPE('','',#24303); +#24303 = PRODUCT_DEFINITION('design','',#24304,#24307); +#24304 = PRODUCT_DEFINITION_FORMATION('','',#24305); +#24305 = PRODUCT('R7','R7','',(#24306)); +#24306 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24307 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24308 = SHAPE_REPRESENTATION('',(#11,#24309),#24313); +#24309 = AXIS2_PLACEMENT_3D('',#24310,#24311,#24312); +#24310 = CARTESIAN_POINT('',(17.4030005,6.35,-1.27E-002)); +#24311 = DIRECTION('',(0.E+000,0.E+000,1.)); +#24312 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#24313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24317)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24314,#24315,#24316)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#21922 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#21923 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#21924 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#21925 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#21922, +#24314 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24315 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24316 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24317 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#24314, 'distance_accuracy_value','confusion accuracy'); -#21926 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21927,#21929); -#21927 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#21916) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21928) +#24318 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24319,#24321); +#24319 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#24308) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24320) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21928 = ITEM_DEFINED_TRANSFORMATION('','',#11,#21917); -#21929 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21930); -#21930 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('162','=>[0:1:1:7]','',#21911, - #7462,$); -#21931 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21932,#21934); -#21932 = ( REPRESENTATION_RELATIONSHIP('','',#21916,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21933) +#24320 = ITEM_DEFINED_TRANSFORMATION('','',#11,#24309); +#24321 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24322); +#24322 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('263','=>[0:1:1:7]','',#24303, + #9854,$); +#24323 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24324,#24326); +#24324 = ( REPRESENTATION_RELATIONSHIP('','',#24308,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24325) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21933 = ITEM_DEFINED_TRANSFORMATION('','',#11,#55); -#21934 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21935); -#21935 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('163','=>[0:1:1:26]','',#5, - #21911,$); -#21936 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#21913)); -#21937 = SHAPE_DEFINITION_REPRESENTATION(#21938,#21944); -#21938 = PRODUCT_DEFINITION_SHAPE('','',#21939); -#21939 = PRODUCT_DEFINITION('design','',#21940,#21943); -#21940 = PRODUCT_DEFINITION_FORMATION('','',#21941); -#21941 = PRODUCT('D3','D3','',(#21942)); -#21942 = PRODUCT_CONTEXT('',#2,'mechanical'); -#21943 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#21944 = SHAPE_REPRESENTATION('',(#11,#21945),#21949); -#21945 = AXIS2_PLACEMENT_3D('',#21946,#21947,#21948); -#21946 = CARTESIAN_POINT('',(18.7828428,4.04644098,1.27E-002)); -#21947 = DIRECTION('',(0.E+000,0.E+000,1.)); -#21948 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#21949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#21953)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#21950,#21951,#21952)) +#24325 = ITEM_DEFINED_TRANSFORMATION('','',#11,#55); +#24326 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24327); +#24327 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('264','=>[0:1:1:26]','',#5, + #24303,$); +#24328 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24305)); +#24329 = SHAPE_DEFINITION_REPRESENTATION(#24330,#24336); +#24330 = PRODUCT_DEFINITION_SHAPE('','',#24331); +#24331 = PRODUCT_DEFINITION('design','',#24332,#24335); +#24332 = PRODUCT_DEFINITION_FORMATION('','',#24333); +#24333 = PRODUCT('D3','D3','',(#24334)); +#24334 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24335 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24336 = SHAPE_REPRESENTATION('',(#11,#24337),#24341); +#24337 = AXIS2_PLACEMENT_3D('',#24338,#24339,#24340); +#24338 = CARTESIAN_POINT('',(18.7828428,4.04644098,1.27E-002)); +#24339 = DIRECTION('',(0.E+000,0.E+000,1.)); +#24340 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#24341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24345)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24342,#24343,#24344)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#21950 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#21951 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#21952 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#21953 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#21950, +#24342 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24343 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24344 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24345 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#24342, 'distance_accuracy_value','confusion accuracy'); -#21954 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21955,#21957); -#21955 = ( REPRESENTATION_RELATIONSHIP('','',#7524,#21944) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21956) +#24346 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24347,#24349); +#24347 = ( REPRESENTATION_RELATIONSHIP('','',#9916,#24336) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24348) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21956 = ITEM_DEFINED_TRANSFORMATION('','',#11,#21945); -#21957 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21958); -#21958 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('164','=>[0:1:1:10]','',#21939, - #11023,$); -#21959 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21960,#21962); -#21960 = ( REPRESENTATION_RELATIONSHIP('','',#21944,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21961) +#24348 = ITEM_DEFINED_TRANSFORMATION('','',#11,#24337); +#24349 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24350); +#24350 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('265','=>[0:1:1:10]','',#24331, + #13415,$); +#24351 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24352,#24354); +#24352 = ( REPRESENTATION_RELATIONSHIP('','',#24336,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24353) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21961 = ITEM_DEFINED_TRANSFORMATION('','',#11,#59); -#21962 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21963); -#21963 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('165','=>[0:1:1:27]','',#5, - #21939,$); -#21964 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#21941)); -#21965 = SHAPE_DEFINITION_REPRESENTATION(#21966,#21972); -#21966 = PRODUCT_DEFINITION_SHAPE('','',#21967); -#21967 = PRODUCT_DEFINITION('design','',#21968,#21971); -#21968 = PRODUCT_DEFINITION_FORMATION('','',#21969); -#21969 = PRODUCT('C49','C49','',(#21970)); -#21970 = PRODUCT_CONTEXT('',#2,'mechanical'); -#21971 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#21972 = SHAPE_REPRESENTATION('',(#11,#21973),#21977); -#21973 = AXIS2_PLACEMENT_3D('',#21974,#21975,#21976); -#21974 = CARTESIAN_POINT('',(18.03408128,31.6229365,-2.27838)); -#21975 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#21976 = DIRECTION('',(1.,0.E+000,0.E+000)); -#21977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#21981)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#21978,#21979,#21980)) +#24353 = ITEM_DEFINED_TRANSFORMATION('','',#11,#59); +#24354 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24355); +#24355 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('266','=>[0:1:1:27]','',#5, + #24331,$); +#24356 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24333)); +#24357 = SHAPE_DEFINITION_REPRESENTATION(#24358,#24364); +#24358 = PRODUCT_DEFINITION_SHAPE('','',#24359); +#24359 = PRODUCT_DEFINITION('design','',#24360,#24363); +#24360 = PRODUCT_DEFINITION_FORMATION('','',#24361); +#24361 = PRODUCT('C49','C49','',(#24362)); +#24362 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24363 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24364 = SHAPE_REPRESENTATION('',(#11,#24365),#24369); +#24365 = AXIS2_PLACEMENT_3D('',#24366,#24367,#24368); +#24366 = CARTESIAN_POINT('',(18.03408128,31.6229365,-1.6891)); +#24367 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#24368 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24373)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24370,#24371,#24372)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#21978 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#21979 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#21980 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#21981 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#21978, +#24370 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24371 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24372 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24373 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#24370, 'distance_accuracy_value','confusion accuracy'); -#21982 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21983,#21985); -#21983 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#21972) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21984) +#24374 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24375,#24377); +#24375 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#24364) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24376) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21984 = ITEM_DEFINED_TRANSFORMATION('','',#11,#21973); -#21985 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21986); -#21986 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('166','=>[0:1:1:18]','',#21967, - #11876,$); -#21987 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#21988,#21990); -#21988 = ( REPRESENTATION_RELATIONSHIP('','',#21972,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#21989) +#24376 = ITEM_DEFINED_TRANSFORMATION('','',#11,#24365); +#24377 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24378); +#24378 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('267','=>[0:1:1:18]','',#24359, + #14268,$); +#24379 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24380,#24382); +#24380 = ( REPRESENTATION_RELATIONSHIP('','',#24364,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24381) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#21989 = ITEM_DEFINED_TRANSFORMATION('','',#11,#63); -#21990 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #21991); -#21991 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('167','=>[0:1:1:28]','',#5, - #21967,$); -#21992 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#21969)); -#21993 = SHAPE_DEFINITION_REPRESENTATION(#21994,#22000); -#21994 = PRODUCT_DEFINITION_SHAPE('','',#21995); -#21995 = PRODUCT_DEFINITION('design','',#21996,#21999); -#21996 = PRODUCT_DEFINITION_FORMATION('','',#21997); -#21997 = PRODUCT('C48','C48','',(#21998)); -#21998 = PRODUCT_CONTEXT('',#2,'mechanical'); -#21999 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#22000 = SHAPE_REPRESENTATION('',(#11,#22001),#22005); -#22001 = AXIS2_PLACEMENT_3D('',#22002,#22003,#22004); -#22002 = CARTESIAN_POINT('',(18.03408128,30.2259365,-2.27838)); -#22003 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#22004 = DIRECTION('',(1.,0.E+000,0.E+000)); -#22005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#22009)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#22006,#22007,#22008)) +#24381 = ITEM_DEFINED_TRANSFORMATION('','',#11,#63); +#24382 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24383); +#24383 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('268','=>[0:1:1:28]','',#5, + #24359,$); +#24384 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24361)); +#24385 = SHAPE_DEFINITION_REPRESENTATION(#24386,#24392); +#24386 = PRODUCT_DEFINITION_SHAPE('','',#24387); +#24387 = PRODUCT_DEFINITION('design','',#24388,#24391); +#24388 = PRODUCT_DEFINITION_FORMATION('','',#24389); +#24389 = PRODUCT('C48','C48','',(#24390)); +#24390 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24391 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24392 = SHAPE_REPRESENTATION('',(#11,#24393),#24397); +#24393 = AXIS2_PLACEMENT_3D('',#24394,#24395,#24396); +#24394 = CARTESIAN_POINT('',(18.03408128,30.2259365,-1.6891)); +#24395 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#24396 = DIRECTION('',(1.,0.E+000,0.E+000)); +#24397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24401)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24398,#24399,#24400)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#22006 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#22007 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#22008 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#22009 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#22006, +#24398 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24399 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24400 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24401 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#24398, 'distance_accuracy_value','confusion accuracy'); -#22010 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#22011,#22013); -#22011 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#22000) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#22012) +#24402 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24403,#24405); +#24403 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#24392) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24404) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#22012 = ITEM_DEFINED_TRANSFORMATION('','',#11,#22001); -#22013 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #22014); -#22014 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('168','=>[0:1:1:18]','',#21995, - #11876,$); -#22015 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#22016,#22018); -#22016 = ( REPRESENTATION_RELATIONSHIP('','',#22000,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#22017) +#24404 = ITEM_DEFINED_TRANSFORMATION('','',#11,#24393); +#24405 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24406); +#24406 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('269','=>[0:1:1:18]','',#24387, + #14268,$); +#24407 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#24408,#24410); +#24408 = ( REPRESENTATION_RELATIONSHIP('','',#24392,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#24409) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#22017 = ITEM_DEFINED_TRANSFORMATION('','',#11,#67); -#22018 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #22019); -#22019 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('169','=>[0:1:1:29]','',#5, - #21995,$); -#22020 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#21997)); -#22021 = SHAPE_DEFINITION_REPRESENTATION(#22022,#22028); -#22022 = PRODUCT_DEFINITION_SHAPE('','',#22023); -#22023 = PRODUCT_DEFINITION('design','',#22024,#22027); -#22024 = PRODUCT_DEFINITION_FORMATION('','',#22025); -#22025 = PRODUCT('CONN5','CONN5','',(#22026)); -#22026 = PRODUCT_CONTEXT('',#2,'mechanical'); -#22027 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#22028 = SHAPE_REPRESENTATION('',(#11,#22029),#22033); -#22029 = AXIS2_PLACEMENT_3D('',#22030,#22031,#22032); -#22030 = CARTESIAN_POINT('',(31.54059986,9.694799,-0.3175)); -#22031 = DIRECTION('',(1.,-1.110223024625E-016,1.110223024625E-016)); -#22032 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#22033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#22037)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#22034,#22035,#22036)) +#24409 = ITEM_DEFINED_TRANSFORMATION('','',#11,#67); +#24410 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #24411); +#24411 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('270','=>[0:1:1:29]','',#5, + #24387,$); +#24412 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24389)); +#24413 = SHAPE_DEFINITION_REPRESENTATION(#24414,#24420); +#24414 = PRODUCT_DEFINITION_SHAPE('','',#24415); +#24415 = PRODUCT_DEFINITION('design','',#24416,#24419); +#24416 = PRODUCT_DEFINITION_FORMATION('','',#24417); +#24417 = PRODUCT('CONN5','CONN5','',(#24418)); +#24418 = PRODUCT_CONTEXT('',#2,'mechanical'); +#24419 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#24420 = SHAPE_REPRESENTATION('',(#11,#24421),#24425); +#24421 = AXIS2_PLACEMENT_3D('',#24422,#24423,#24424); +#24422 = CARTESIAN_POINT('',(31.54059986,9.694799,-0.3175)); +#24423 = DIRECTION('',(1.,-1.110223024625E-016,1.110223024625E-016)); +#24424 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#24425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#24429)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#24426,#24427,#24428)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#22034 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#22035 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#22036 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#22037 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#22034, +#24426 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#24427 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#24428 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#24429 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#24426, 'distance_accuracy_value','confusion accuracy'); -#22038 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#22039),#28455); -#22039 = MANIFOLD_SOLID_BREP('',#22040); -#22040 = CLOSED_SHELL('',(#22041,#22161,#22237,#22742,#22791,#22818, - #22825,#22901,#22977,#23133,#23209,#23285,#23334,#23383,#23454, - #23525,#23574,#23601,#23735,#23762,#23789,#23816,#23843,#24334, - #24341,#24412,#24439,#24466,#24473,#24480,#24551,#24578,#24605, - #24681,#24688,#24764,#25059,#25655,#25704,#25830,#25946,#26102, - #26129,#26353,#26360,#26387,#26414,#26421,#26428,#26499,#26548, - #26575,#26962,#27009,#27036,#27043,#27050,#27155,#27260,#27287, - #27392,#27487,#27592,#27619,#27714,#27741,#27836,#27863,#27958, - #27985,#28012,#28019,#28114,#28123,#28150,#28177,#28204,#28211, - #28238,#28265,#28292,#28319,#28346,#28353,#28380,#28387,#28414, - #28421,#28448)); -#22041 = ADVANCED_FACE('',(#22042),#22056,.F.); -#22042 = FACE_BOUND('',#22043,.T.); -#22043 = EDGE_LOOP('',(#22044,#22079,#22107,#22135)); -#22044 = ORIENTED_EDGE('',*,*,#22045,.F.); -#22045 = EDGE_CURVE('',#22046,#22048,#22050,.T.); -#22046 = VERTEX_POINT('',#22047); -#22047 = CARTESIAN_POINT('',(1.6,1.955,0.895)); -#22048 = VERTEX_POINT('',#22049); -#22049 = CARTESIAN_POINT('',(1.6,2.085,2.645)); -#22050 = SURFACE_CURVE('',#22051,(#22055,#22067),.PCURVE_S1.); -#22051 = LINE('',#22052,#22053); -#22052 = CARTESIAN_POINT('',(1.6,2.085,2.645)); -#22053 = VECTOR('',#22054,1.); -#22054 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#22055 = PCURVE('',#22056,#22061); -#22056 = PLANE('',#22057); -#22057 = AXIS2_PLACEMENT_3D('',#22058,#22059,#22060); -#22058 = CARTESIAN_POINT('',(1.6,0.445,0.195)); -#22059 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22060 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22061 = DEFINITIONAL_REPRESENTATION('',(#22062),#22066); -#22062 = LINE('',#22063,#22064); -#22063 = CARTESIAN_POINT('',(-1.64,2.45)); -#22064 = VECTOR('',#22065,1.); -#22065 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#22066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22067 = PCURVE('',#22068,#22073); -#22068 = PLANE('',#22069); -#22069 = AXIS2_PLACEMENT_3D('',#22070,#22071,#22072); -#22070 = CARTESIAN_POINT('',(1.4,2.085,2.645)); -#22071 = DIRECTION('',(-5.173092832126E-016,0.997252183706, - -7.408159078957E-002)); -#22072 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, - -0.997252183706)); -#22073 = DEFINITIONAL_REPRESENTATION('',(#22074),#22078); -#22074 = LINE('',#22075,#22076); -#22075 = CARTESIAN_POINT('',(-6.414895964605E-017,-0.2)); -#22076 = VECTOR('',#22077,1.); -#22077 = DIRECTION('',(-1.,4.74549138297E-031)); -#22078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22079 = ORIENTED_EDGE('',*,*,#22080,.T.); -#22080 = EDGE_CURVE('',#22046,#22081,#22083,.T.); -#22081 = VERTEX_POINT('',#22082); -#22082 = CARTESIAN_POINT('',(1.6,2.435,0.895)); -#22083 = SURFACE_CURVE('',#22084,(#22088,#22095),.PCURVE_S1.); -#22084 = LINE('',#22085,#22086); -#22085 = CARTESIAN_POINT('',(1.6,0.755,0.895)); -#22086 = VECTOR('',#22087,1.); -#22087 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22088 = PCURVE('',#22056,#22089); -#22089 = DEFINITIONAL_REPRESENTATION('',(#22090),#22094); -#22090 = LINE('',#22091,#22092); -#22091 = CARTESIAN_POINT('',(-0.31,0.7)); -#22092 = VECTOR('',#22093,1.); -#22093 = DIRECTION('',(-1.,1.702510980039E-043)); -#22094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22095 = PCURVE('',#22096,#22101); -#22096 = PLANE('',#22097); -#22097 = AXIS2_PLACEMENT_3D('',#22098,#22099,#22100); -#22098 = CARTESIAN_POINT('',(2.2,0.755,0.895)); -#22099 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#22100 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22101 = DEFINITIONAL_REPRESENTATION('',(#22102),#22106); -#22102 = LINE('',#22103,#22104); -#22103 = CARTESIAN_POINT('',(-1.014885537928E-031,0.6)); -#22104 = VECTOR('',#22105,1.); -#22105 = DIRECTION('',(-1.,0.E+000)); -#22106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22107 = ORIENTED_EDGE('',*,*,#22108,.F.); -#22108 = EDGE_CURVE('',#22109,#22081,#22111,.T.); -#22109 = VERTEX_POINT('',#22110); -#22110 = CARTESIAN_POINT('',(1.6,2.435,2.645)); -#22111 = SURFACE_CURVE('',#22112,(#22116,#22123),.PCURVE_S1.); -#22112 = LINE('',#22113,#22114); -#22113 = CARTESIAN_POINT('',(1.6,2.435,2.645)); -#22114 = VECTOR('',#22115,1.); -#22115 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#22116 = PCURVE('',#22056,#22117); -#22117 = DEFINITIONAL_REPRESENTATION('',(#22118),#22122); -#22118 = LINE('',#22119,#22120); -#22119 = CARTESIAN_POINT('',(-1.99,2.45)); -#22120 = VECTOR('',#22121,1.); -#22121 = DIRECTION('',(-1.770125995895E-016,-1.)); -#22122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22123 = PCURVE('',#22124,#22129); -#22124 = PLANE('',#22125); -#22125 = AXIS2_PLACEMENT_3D('',#22126,#22127,#22128); -#22126 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22127 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); -#22128 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); -#22129 = DEFINITIONAL_REPRESENTATION('',(#22130),#22134); -#22130 = LINE('',#22131,#22132); -#22131 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); -#22132 = VECTOR('',#22133,1.); -#22133 = DIRECTION('',(-1.,0.E+000)); -#22134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22135 = ORIENTED_EDGE('',*,*,#22136,.F.); -#22136 = EDGE_CURVE('',#22048,#22109,#22137,.T.); -#22137 = SURFACE_CURVE('',#22138,(#22142,#22149),.PCURVE_S1.); -#22138 = LINE('',#22139,#22140); -#22139 = CARTESIAN_POINT('',(1.6,2.435,2.645)); -#22140 = VECTOR('',#22141,1.); -#22141 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22142 = PCURVE('',#22056,#22143); -#22143 = DEFINITIONAL_REPRESENTATION('',(#22144),#22148); -#22144 = LINE('',#22145,#22146); -#22145 = CARTESIAN_POINT('',(-1.99,2.45)); -#22146 = VECTOR('',#22147,1.); -#22147 = DIRECTION('',(-1.,1.702510980039E-043)); -#22148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22149 = PCURVE('',#22150,#22155); -#22150 = PLANE('',#22151); -#22151 = AXIS2_PLACEMENT_3D('',#22152,#22153,#22154); -#22152 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22153 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#22154 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22155 = DEFINITIONAL_REPRESENTATION('',(#22156),#22160); -#22156 = LINE('',#22157,#22158); -#22157 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); -#22158 = VECTOR('',#22159,1.); -#22159 = DIRECTION('',(-1.,0.E+000)); -#22160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22161 = ADVANCED_FACE('',(#22162),#22124,.F.); -#22162 = FACE_BOUND('',#22163,.T.); -#22163 = EDGE_LOOP('',(#22164,#22165,#22188,#22216)); -#22164 = ORIENTED_EDGE('',*,*,#22108,.T.); -#22165 = ORIENTED_EDGE('',*,*,#22166,.T.); -#22166 = EDGE_CURVE('',#22081,#22167,#22169,.T.); -#22167 = VERTEX_POINT('',#22168); -#22168 = CARTESIAN_POINT('',(1.4,2.435,0.895)); -#22169 = SURFACE_CURVE('',#22170,(#22174,#22181),.PCURVE_S1.); -#22170 = LINE('',#22171,#22172); -#22171 = CARTESIAN_POINT('',(2.2,2.435,0.895)); -#22172 = VECTOR('',#22173,1.); -#22173 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22174 = PCURVE('',#22124,#22175); -#22175 = DEFINITIONAL_REPRESENTATION('',(#22176),#22180); -#22176 = LINE('',#22177,#22178); -#22177 = CARTESIAN_POINT('',(-1.75,-0.8)); -#22178 = VECTOR('',#22179,1.); -#22179 = DIRECTION('',(0.E+000,1.)); -#22180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22181 = PCURVE('',#22096,#22182); -#22182 = DEFINITIONAL_REPRESENTATION('',(#22183),#22187); -#22183 = LINE('',#22184,#22185); -#22184 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); -#22185 = VECTOR('',#22186,1.); -#22186 = DIRECTION('',(2.80259692865E-045,1.)); -#22187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22188 = ORIENTED_EDGE('',*,*,#22189,.F.); -#22189 = EDGE_CURVE('',#22190,#22167,#22192,.T.); -#22190 = VERTEX_POINT('',#22191); -#22191 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22192 = SURFACE_CURVE('',#22193,(#22197,#22204),.PCURVE_S1.); -#22193 = LINE('',#22194,#22195); -#22194 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22195 = VECTOR('',#22196,1.); -#22196 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#22197 = PCURVE('',#22124,#22198); -#22198 = DEFINITIONAL_REPRESENTATION('',(#22199),#22203); -#22199 = LINE('',#22200,#22201); -#22200 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22201 = VECTOR('',#22202,1.); -#22202 = DIRECTION('',(-1.,0.E+000)); -#22203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22204 = PCURVE('',#22205,#22210); -#22205 = PLANE('',#22206); -#22206 = AXIS2_PLACEMENT_3D('',#22207,#22208,#22209); -#22207 = CARTESIAN_POINT('',(1.4,0.445,0.195)); -#22208 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22209 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22210 = DEFINITIONAL_REPRESENTATION('',(#22211),#22215); -#22211 = LINE('',#22212,#22213); -#22212 = CARTESIAN_POINT('',(-1.99,2.45)); -#22213 = VECTOR('',#22214,1.); -#22214 = DIRECTION('',(-1.770125995895E-016,-1.)); -#22215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22216 = ORIENTED_EDGE('',*,*,#22217,.T.); -#22217 = EDGE_CURVE('',#22190,#22109,#22218,.T.); -#22218 = SURFACE_CURVE('',#22219,(#22223,#22230),.PCURVE_S1.); -#22219 = LINE('',#22220,#22221); -#22220 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22221 = VECTOR('',#22222,1.); -#22222 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22223 = PCURVE('',#22124,#22224); -#22224 = DEFINITIONAL_REPRESENTATION('',(#22225),#22229); -#22225 = LINE('',#22226,#22227); -#22226 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22227 = VECTOR('',#22228,1.); -#22228 = DIRECTION('',(0.E+000,-1.)); -#22229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22230 = PCURVE('',#22150,#22231); -#22231 = DEFINITIONAL_REPRESENTATION('',(#22232),#22236); -#22232 = LINE('',#22233,#22234); -#22233 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22234 = VECTOR('',#22235,1.); -#22235 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22237 = ADVANCED_FACE('',(#22238,#22286,#22400,#22514,#22628),#22096, - .F.); -#22238 = FACE_BOUND('',#22239,.T.); -#22239 = EDGE_LOOP('',(#22240,#22263,#22284,#22285)); -#22240 = ORIENTED_EDGE('',*,*,#22241,.F.); -#22241 = EDGE_CURVE('',#22242,#22046,#22244,.T.); -#22242 = VERTEX_POINT('',#22243); -#22243 = CARTESIAN_POINT('',(1.4,1.955,0.895)); -#22244 = SURFACE_CURVE('',#22245,(#22249,#22256),.PCURVE_S1.); -#22245 = LINE('',#22246,#22247); -#22246 = CARTESIAN_POINT('',(1.4,1.955,0.895)); -#22247 = VECTOR('',#22248,1.); -#22248 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22249 = PCURVE('',#22096,#22250); -#22250 = DEFINITIONAL_REPRESENTATION('',(#22251),#22255); -#22251 = LINE('',#22252,#22253); -#22252 = CARTESIAN_POINT('',(-1.2,0.8)); -#22253 = VECTOR('',#22254,1.); -#22254 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22256 = PCURVE('',#22068,#22257); -#22257 = DEFINITIONAL_REPRESENTATION('',(#22258),#22262); -#22258 = LINE('',#22259,#22260); -#22259 = CARTESIAN_POINT('',(1.754821928288,-7.738493006118E-018)); -#22260 = VECTOR('',#22261,1.); -#22261 = DIRECTION('',(-1.109335647967E-030,-1.)); -#22262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22263 = ORIENTED_EDGE('',*,*,#22264,.T.); -#22264 = EDGE_CURVE('',#22242,#22167,#22265,.T.); -#22265 = SURFACE_CURVE('',#22266,(#22270,#22277),.PCURVE_S1.); -#22266 = LINE('',#22267,#22268); -#22267 = CARTESIAN_POINT('',(1.4,0.755,0.895)); -#22268 = VECTOR('',#22269,1.); -#22269 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22270 = PCURVE('',#22096,#22271); -#22271 = DEFINITIONAL_REPRESENTATION('',(#22272),#22276); -#22272 = LINE('',#22273,#22274); -#22273 = CARTESIAN_POINT('',(1.231036094495E-031,0.8)); -#22274 = VECTOR('',#22275,1.); -#22275 = DIRECTION('',(-1.,0.E+000)); -#22276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22277 = PCURVE('',#22205,#22278); -#22278 = DEFINITIONAL_REPRESENTATION('',(#22279),#22283); -#22279 = LINE('',#22280,#22281); -#22280 = CARTESIAN_POINT('',(-0.31,0.7)); -#22281 = VECTOR('',#22282,1.); -#22282 = DIRECTION('',(-1.,1.702510980039E-043)); -#22283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22284 = ORIENTED_EDGE('',*,*,#22166,.F.); -#22285 = ORIENTED_EDGE('',*,*,#22080,.F.); -#22286 = FACE_BOUND('',#22287,.T.); -#22287 = EDGE_LOOP('',(#22288,#22318,#22346,#22374)); -#22288 = ORIENTED_EDGE('',*,*,#22289,.F.); -#22289 = EDGE_CURVE('',#22290,#22292,#22294,.T.); -#22290 = VERTEX_POINT('',#22291); -#22291 = CARTESIAN_POINT('',(0.4,1.955,0.895)); -#22292 = VERTEX_POINT('',#22293); -#22293 = CARTESIAN_POINT('',(0.6,1.955,0.895)); -#22294 = SURFACE_CURVE('',#22295,(#22299,#22306),.PCURVE_S1.); -#22295 = LINE('',#22296,#22297); -#22296 = CARTESIAN_POINT('',(0.4,1.955,0.895)); -#22297 = VECTOR('',#22298,1.); -#22298 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22299 = PCURVE('',#22096,#22300); -#22300 = DEFINITIONAL_REPRESENTATION('',(#22301),#22305); -#22301 = LINE('',#22302,#22303); -#22302 = CARTESIAN_POINT('',(-1.2,1.8)); -#22303 = VECTOR('',#22304,1.); -#22304 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22306 = PCURVE('',#22307,#22312); -#22307 = PLANE('',#22308); -#22308 = AXIS2_PLACEMENT_3D('',#22309,#22310,#22311); -#22309 = CARTESIAN_POINT('',(0.4,2.085,2.645)); -#22310 = DIRECTION('',(-5.173092832126E-016,0.997252183706, - -7.408159078957E-002)); -#22311 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, - -0.997252183706)); -#22312 = DEFINITIONAL_REPRESENTATION('',(#22313),#22317); -#22313 = LINE('',#22314,#22315); -#22314 = CARTESIAN_POINT('',(1.754821928288,-6.324964423738E-017)); -#22315 = VECTOR('',#22316,1.); -#22316 = DIRECTION('',(-1.109335647967E-030,-1.)); -#22317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22318 = ORIENTED_EDGE('',*,*,#22319,.T.); -#22319 = EDGE_CURVE('',#22290,#22320,#22322,.T.); -#22320 = VERTEX_POINT('',#22321); -#22321 = CARTESIAN_POINT('',(0.4,2.435,0.895)); -#22322 = SURFACE_CURVE('',#22323,(#22327,#22334),.PCURVE_S1.); -#22323 = LINE('',#22324,#22325); -#22324 = CARTESIAN_POINT('',(0.4,0.755,0.895)); -#22325 = VECTOR('',#22326,1.); -#22326 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22327 = PCURVE('',#22096,#22328); -#22328 = DEFINITIONAL_REPRESENTATION('',(#22329),#22333); -#22329 = LINE('',#22330,#22331); -#22330 = CARTESIAN_POINT('',(8.316686038149E-032,1.8)); -#22331 = VECTOR('',#22332,1.); -#22332 = DIRECTION('',(-1.,0.E+000)); -#22333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22334 = PCURVE('',#22335,#22340); -#22335 = PLANE('',#22336); -#22336 = AXIS2_PLACEMENT_3D('',#22337,#22338,#22339); -#22337 = CARTESIAN_POINT('',(0.4,0.445,0.195)); -#22338 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22339 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22340 = DEFINITIONAL_REPRESENTATION('',(#22341),#22345); -#22341 = LINE('',#22342,#22343); -#22342 = CARTESIAN_POINT('',(-0.31,0.7)); -#22343 = VECTOR('',#22344,1.); -#22344 = DIRECTION('',(-1.,1.702510980039E-043)); -#22345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22346 = ORIENTED_EDGE('',*,*,#22347,.F.); -#22347 = EDGE_CURVE('',#22348,#22320,#22350,.T.); -#22348 = VERTEX_POINT('',#22349); -#22349 = CARTESIAN_POINT('',(0.6,2.435,0.895)); -#22350 = SURFACE_CURVE('',#22351,(#22355,#22362),.PCURVE_S1.); -#22351 = LINE('',#22352,#22353); -#22352 = CARTESIAN_POINT('',(2.2,2.435,0.895)); -#22353 = VECTOR('',#22354,1.); -#22354 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22355 = PCURVE('',#22096,#22356); -#22356 = DEFINITIONAL_REPRESENTATION('',(#22357),#22361); -#22357 = LINE('',#22358,#22359); -#22358 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); -#22359 = VECTOR('',#22360,1.); -#22360 = DIRECTION('',(2.80259692865E-045,1.)); -#22361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22362 = PCURVE('',#22363,#22368); -#22363 = PLANE('',#22364); -#22364 = AXIS2_PLACEMENT_3D('',#22365,#22366,#22367); -#22365 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#22366 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); -#22367 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); -#22368 = DEFINITIONAL_REPRESENTATION('',(#22369),#22373); -#22369 = LINE('',#22370,#22371); -#22370 = CARTESIAN_POINT('',(-1.75,-1.8)); -#22371 = VECTOR('',#22372,1.); -#22372 = DIRECTION('',(0.E+000,1.)); -#22373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22374 = ORIENTED_EDGE('',*,*,#22375,.F.); -#22375 = EDGE_CURVE('',#22292,#22348,#22376,.T.); -#22376 = SURFACE_CURVE('',#22377,(#22381,#22388),.PCURVE_S1.); -#22377 = LINE('',#22378,#22379); -#22378 = CARTESIAN_POINT('',(0.6,0.755,0.895)); -#22379 = VECTOR('',#22380,1.); -#22380 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22381 = PCURVE('',#22096,#22382); -#22382 = DEFINITIONAL_REPRESENTATION('',(#22383),#22387); -#22383 = LINE('',#22384,#22385); -#22384 = CARTESIAN_POINT('',(-1.414253028609E-031,1.6)); -#22385 = VECTOR('',#22386,1.); -#22386 = DIRECTION('',(-1.,0.E+000)); -#22387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22388 = PCURVE('',#22389,#22394); -#22389 = PLANE('',#22390); -#22390 = AXIS2_PLACEMENT_3D('',#22391,#22392,#22393); -#22391 = CARTESIAN_POINT('',(0.6,0.445,0.195)); -#22392 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22393 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22394 = DEFINITIONAL_REPRESENTATION('',(#22395),#22399); -#22395 = LINE('',#22396,#22397); -#22396 = CARTESIAN_POINT('',(-0.31,0.7)); -#22397 = VECTOR('',#22398,1.); -#22398 = DIRECTION('',(-1.,1.702510980039E-043)); -#22399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22400 = FACE_BOUND('',#22401,.T.); -#22401 = EDGE_LOOP('',(#22402,#22432,#22460,#22488)); -#22402 = ORIENTED_EDGE('',*,*,#22403,.F.); -#22403 = EDGE_CURVE('',#22404,#22406,#22408,.T.); -#22404 = VERTEX_POINT('',#22405); -#22405 = CARTESIAN_POINT('',(-0.6,1.955,0.895)); -#22406 = VERTEX_POINT('',#22407); -#22407 = CARTESIAN_POINT('',(-0.4,1.955,0.895)); -#22408 = SURFACE_CURVE('',#22409,(#22413,#22420),.PCURVE_S1.); -#22409 = LINE('',#22410,#22411); -#22410 = CARTESIAN_POINT('',(-0.6,1.955,0.895)); -#22411 = VECTOR('',#22412,1.); -#22412 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22413 = PCURVE('',#22096,#22414); -#22414 = DEFINITIONAL_REPRESENTATION('',(#22415),#22419); -#22415 = LINE('',#22416,#22417); -#22416 = CARTESIAN_POINT('',(-1.2,2.8)); -#22417 = VECTOR('',#22418,1.); -#22418 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22420 = PCURVE('',#22421,#22426); -#22421 = PLANE('',#22422); -#22422 = AXIS2_PLACEMENT_3D('',#22423,#22424,#22425); -#22423 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); -#22424 = DIRECTION('',(-5.173092832126E-016,0.997252183706, - -7.408159078957E-002)); -#22425 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, - -0.997252183706)); -#22426 = DEFINITIONAL_REPRESENTATION('',(#22427),#22431); -#22427 = LINE('',#22428,#22429); -#22428 = CARTESIAN_POINT('',(1.754821928288,-1.187607954686E-016)); -#22429 = VECTOR('',#22430,1.); -#22430 = DIRECTION('',(-1.109335647967E-030,-1.)); -#22431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22432 = ORIENTED_EDGE('',*,*,#22433,.T.); -#22433 = EDGE_CURVE('',#22404,#22434,#22436,.T.); -#22434 = VERTEX_POINT('',#22435); -#22435 = CARTESIAN_POINT('',(-0.6,2.435,0.895)); -#22436 = SURFACE_CURVE('',#22437,(#22441,#22448),.PCURVE_S1.); -#22437 = LINE('',#22438,#22439); -#22438 = CARTESIAN_POINT('',(-0.6,0.755,0.895)); -#22439 = VECTOR('',#22440,1.); -#22440 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22441 = PCURVE('',#22096,#22442); -#22442 = DEFINITIONAL_REPRESENTATION('',(#22443),#22447); -#22443 = LINE('',#22444,#22445); -#22444 = CARTESIAN_POINT('',(4.323011131344E-032,2.8)); -#22445 = VECTOR('',#22446,1.); -#22446 = DIRECTION('',(-1.,0.E+000)); -#22447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22448 = PCURVE('',#22449,#22454); -#22449 = PLANE('',#22450); -#22450 = AXIS2_PLACEMENT_3D('',#22451,#22452,#22453); -#22451 = CARTESIAN_POINT('',(-0.6,0.445,0.195)); -#22452 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22453 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22454 = DEFINITIONAL_REPRESENTATION('',(#22455),#22459); -#22455 = LINE('',#22456,#22457); -#22456 = CARTESIAN_POINT('',(-0.31,0.7)); -#22457 = VECTOR('',#22458,1.); -#22458 = DIRECTION('',(-1.,1.702510980039E-043)); -#22459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22460 = ORIENTED_EDGE('',*,*,#22461,.F.); -#22461 = EDGE_CURVE('',#22462,#22434,#22464,.T.); -#22462 = VERTEX_POINT('',#22463); -#22463 = CARTESIAN_POINT('',(-0.4,2.435,0.895)); -#22464 = SURFACE_CURVE('',#22465,(#22469,#22476),.PCURVE_S1.); -#22465 = LINE('',#22466,#22467); -#22466 = CARTESIAN_POINT('',(2.2,2.435,0.895)); -#22467 = VECTOR('',#22468,1.); -#22468 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22469 = PCURVE('',#22096,#22470); -#22470 = DEFINITIONAL_REPRESENTATION('',(#22471),#22475); -#22471 = LINE('',#22472,#22473); -#22472 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); -#22473 = VECTOR('',#22474,1.); -#22474 = DIRECTION('',(2.80259692865E-045,1.)); -#22475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22476 = PCURVE('',#22477,#22482); -#22477 = PLANE('',#22478); -#22478 = AXIS2_PLACEMENT_3D('',#22479,#22480,#22481); -#22479 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#22480 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); -#22481 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); -#22482 = DEFINITIONAL_REPRESENTATION('',(#22483),#22487); -#22483 = LINE('',#22484,#22485); -#22484 = CARTESIAN_POINT('',(-1.75,-2.8)); -#22485 = VECTOR('',#22486,1.); -#22486 = DIRECTION('',(0.E+000,1.)); -#22487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22488 = ORIENTED_EDGE('',*,*,#22489,.F.); -#22489 = EDGE_CURVE('',#22406,#22462,#22490,.T.); -#22490 = SURFACE_CURVE('',#22491,(#22495,#22502),.PCURVE_S1.); -#22491 = LINE('',#22492,#22493); -#22492 = CARTESIAN_POINT('',(-0.4,0.755,0.895)); -#22493 = VECTOR('',#22494,1.); -#22494 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22495 = PCURVE('',#22096,#22496); -#22496 = DEFINITIONAL_REPRESENTATION('',(#22497),#22501); -#22497 = LINE('',#22498,#22499); -#22498 = CARTESIAN_POINT('',(-1.813620519289E-031,2.6)); -#22499 = VECTOR('',#22500,1.); -#22500 = DIRECTION('',(-1.,0.E+000)); -#22501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22502 = PCURVE('',#22503,#22508); -#22503 = PLANE('',#22504); -#22504 = AXIS2_PLACEMENT_3D('',#22505,#22506,#22507); -#22505 = CARTESIAN_POINT('',(-0.4,0.445,0.195)); -#22506 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22507 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22508 = DEFINITIONAL_REPRESENTATION('',(#22509),#22513); -#22509 = LINE('',#22510,#22511); -#22510 = CARTESIAN_POINT('',(-0.31,0.7)); -#22511 = VECTOR('',#22512,1.); -#22512 = DIRECTION('',(-1.,1.702510980039E-043)); -#22513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22514 = FACE_BOUND('',#22515,.T.); -#22515 = EDGE_LOOP('',(#22516,#22546,#22574,#22602)); -#22516 = ORIENTED_EDGE('',*,*,#22517,.F.); -#22517 = EDGE_CURVE('',#22518,#22520,#22522,.T.); -#22518 = VERTEX_POINT('',#22519); -#22519 = CARTESIAN_POINT('',(-1.6,1.955,0.895)); -#22520 = VERTEX_POINT('',#22521); -#22521 = CARTESIAN_POINT('',(-1.4,1.955,0.895)); -#22522 = SURFACE_CURVE('',#22523,(#22527,#22534),.PCURVE_S1.); -#22523 = LINE('',#22524,#22525); -#22524 = CARTESIAN_POINT('',(-1.6,1.955,0.895)); -#22525 = VECTOR('',#22526,1.); -#22526 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22527 = PCURVE('',#22096,#22528); -#22528 = DEFINITIONAL_REPRESENTATION('',(#22529),#22533); -#22529 = LINE('',#22530,#22531); -#22530 = CARTESIAN_POINT('',(-1.2,3.8)); -#22531 = VECTOR('',#22532,1.); -#22532 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22534 = PCURVE('',#22535,#22540); -#22535 = PLANE('',#22536); -#22536 = AXIS2_PLACEMENT_3D('',#22537,#22538,#22539); -#22537 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); -#22538 = DIRECTION('',(-5.173092832126E-016,0.997252183706, - -7.408159078957E-002)); -#22539 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, - -0.997252183706)); -#22540 = DEFINITIONAL_REPRESENTATION('',(#22541),#22545); -#22541 = LINE('',#22542,#22543); -#22542 = CARTESIAN_POINT('',(1.754821928288,2.143061119189E-016)); -#22543 = VECTOR('',#22544,1.); -#22544 = DIRECTION('',(-1.109335647967E-030,-1.)); -#22545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22546 = ORIENTED_EDGE('',*,*,#22547,.T.); -#22547 = EDGE_CURVE('',#22518,#22548,#22550,.T.); -#22548 = VERTEX_POINT('',#22549); -#22549 = CARTESIAN_POINT('',(-1.6,2.435,0.895)); -#22550 = SURFACE_CURVE('',#22551,(#22555,#22562),.PCURVE_S1.); -#22551 = LINE('',#22552,#22553); -#22552 = CARTESIAN_POINT('',(-1.6,0.755,0.895)); -#22553 = VECTOR('',#22554,1.); -#22554 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22555 = PCURVE('',#22096,#22556); -#22556 = DEFINITIONAL_REPRESENTATION('',(#22557),#22561); -#22557 = LINE('',#22558,#22559); -#22558 = CARTESIAN_POINT('',(3.293362245417E-033,3.8)); -#22559 = VECTOR('',#22560,1.); -#22560 = DIRECTION('',(-1.,0.E+000)); -#22561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22562 = PCURVE('',#22563,#22568); -#22563 = PLANE('',#22564); -#22564 = AXIS2_PLACEMENT_3D('',#22565,#22566,#22567); -#22565 = CARTESIAN_POINT('',(-1.6,0.445,0.195)); -#22566 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22567 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22568 = DEFINITIONAL_REPRESENTATION('',(#22569),#22573); -#22569 = LINE('',#22570,#22571); -#22570 = CARTESIAN_POINT('',(-0.31,0.7)); -#22571 = VECTOR('',#22572,1.); -#22572 = DIRECTION('',(-1.,1.702510980039E-043)); -#22573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22574 = ORIENTED_EDGE('',*,*,#22575,.F.); -#22575 = EDGE_CURVE('',#22576,#22548,#22578,.T.); -#22576 = VERTEX_POINT('',#22577); -#22577 = CARTESIAN_POINT('',(-1.4,2.435,0.895)); -#22578 = SURFACE_CURVE('',#22579,(#22583,#22590),.PCURVE_S1.); -#22579 = LINE('',#22580,#22581); -#22580 = CARTESIAN_POINT('',(2.2,2.435,0.895)); -#22581 = VECTOR('',#22582,1.); -#22582 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22583 = PCURVE('',#22096,#22584); -#22584 = DEFINITIONAL_REPRESENTATION('',(#22585),#22589); -#22585 = LINE('',#22586,#22587); -#22586 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); -#22587 = VECTOR('',#22588,1.); -#22588 = DIRECTION('',(2.80259692865E-045,1.)); -#22589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22590 = PCURVE('',#22591,#22596); -#22591 = PLANE('',#22592); -#22592 = AXIS2_PLACEMENT_3D('',#22593,#22594,#22595); -#22593 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#22594 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); -#22595 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); -#22596 = DEFINITIONAL_REPRESENTATION('',(#22597),#22601); -#22597 = LINE('',#22598,#22599); -#22598 = CARTESIAN_POINT('',(-1.75,-3.8)); -#22599 = VECTOR('',#22600,1.); -#22600 = DIRECTION('',(0.E+000,1.)); -#22601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22602 = ORIENTED_EDGE('',*,*,#22603,.F.); -#22603 = EDGE_CURVE('',#22520,#22576,#22604,.T.); -#22604 = SURFACE_CURVE('',#22605,(#22609,#22616),.PCURVE_S1.); -#22605 = LINE('',#22606,#22607); -#22606 = CARTESIAN_POINT('',(-1.4,0.755,0.895)); -#22607 = VECTOR('',#22608,1.); -#22608 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22609 = PCURVE('',#22096,#22610); -#22610 = DEFINITIONAL_REPRESENTATION('',(#22611),#22615); -#22611 = LINE('',#22612,#22613); -#22612 = CARTESIAN_POINT('',(1.66333720763E-031,3.6)); -#22613 = VECTOR('',#22614,1.); -#22614 = DIRECTION('',(-1.,0.E+000)); -#22615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22616 = PCURVE('',#22617,#22622); -#22617 = PLANE('',#22618); -#22618 = AXIS2_PLACEMENT_3D('',#22619,#22620,#22621); -#22619 = CARTESIAN_POINT('',(-1.4,0.445,0.195)); -#22620 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#22621 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22622 = DEFINITIONAL_REPRESENTATION('',(#22623),#22627); -#22623 = LINE('',#22624,#22625); -#22624 = CARTESIAN_POINT('',(-0.31,0.7)); -#22625 = VECTOR('',#22626,1.); -#22626 = DIRECTION('',(-1.,1.702510980039E-043)); -#22627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22628 = FACE_BOUND('',#22629,.T.); -#22629 = EDGE_LOOP('',(#22630,#22660,#22688,#22716)); -#22630 = ORIENTED_EDGE('',*,*,#22631,.T.); -#22631 = EDGE_CURVE('',#22632,#22634,#22636,.T.); -#22632 = VERTEX_POINT('',#22633); -#22633 = CARTESIAN_POINT('',(2.2,0.755,0.895)); -#22634 = VERTEX_POINT('',#22635); -#22635 = CARTESIAN_POINT('',(2.2,2.855,0.895)); -#22636 = SURFACE_CURVE('',#22637,(#22641,#22648),.PCURVE_S1.); -#22637 = LINE('',#22638,#22639); -#22638 = CARTESIAN_POINT('',(2.2,2.855,0.895)); -#22639 = VECTOR('',#22640,1.); -#22640 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); -#22641 = PCURVE('',#22096,#22642); -#22642 = DEFINITIONAL_REPRESENTATION('',(#22643),#22647); -#22643 = LINE('',#22644,#22645); -#22644 = CARTESIAN_POINT('',(-2.1,4.440892098501E-016)); -#22645 = VECTOR('',#22646,1.); -#22646 = DIRECTION('',(-1.,2.06514699521E-016)); -#22647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22648 = PCURVE('',#22649,#22654); -#22649 = PLANE('',#22650); -#22650 = AXIS2_PLACEMENT_3D('',#22651,#22652,#22653); -#22651 = CARTESIAN_POINT('',(2.2,2.855,0.895)); -#22652 = DIRECTION('',(1.,2.06514699521E-016,-7.085009279629E-015)); -#22653 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); -#22654 = DEFINITIONAL_REPRESENTATION('',(#22655),#22659); -#22655 = LINE('',#22656,#22657); -#22656 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22657 = VECTOR('',#22658,1.); -#22658 = DIRECTION('',(1.,1.145632479557E-031)); -#22659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22660 = ORIENTED_EDGE('',*,*,#22661,.T.); -#22661 = EDGE_CURVE('',#22634,#22662,#22664,.T.); -#22662 = VERTEX_POINT('',#22663); -#22663 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22664 = SURFACE_CURVE('',#22665,(#22669,#22676),.PCURVE_S1.); -#22665 = LINE('',#22666,#22667); -#22666 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22667 = VECTOR('',#22668,1.); -#22668 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); -#22669 = PCURVE('',#22096,#22670); -#22670 = DEFINITIONAL_REPRESENTATION('',(#22671),#22675); -#22671 = LINE('',#22672,#22673); -#22672 = CARTESIAN_POINT('',(-2.1,4.4)); -#22673 = VECTOR('',#22674,1.); -#22674 = DIRECTION('',(9.856383386232E-017,1.)); -#22675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22676 = PCURVE('',#22677,#22682); -#22677 = PLANE('',#22678); -#22678 = AXIS2_PLACEMENT_3D('',#22679,#22680,#22681); -#22679 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22680 = DIRECTION('',(-9.856383386229E-017,1.,3.491483361109E-015)); -#22681 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); -#22682 = DEFINITIONAL_REPRESENTATION('',(#22683),#22687); -#22683 = LINE('',#22684,#22685); -#22684 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22685 = VECTOR('',#22686,1.); -#22686 = DIRECTION('',(1.,3.439710880676E-031)); -#22687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22688 = ORIENTED_EDGE('',*,*,#22689,.T.); -#22689 = EDGE_CURVE('',#22662,#22690,#22692,.T.); -#22690 = VERTEX_POINT('',#22691); -#22691 = CARTESIAN_POINT('',(-2.2,0.755,0.895)); -#22692 = SURFACE_CURVE('',#22693,(#22697,#22704),.PCURVE_S1.); -#22693 = LINE('',#22694,#22695); -#22694 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22695 = VECTOR('',#22696,1.); -#22696 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); -#22697 = PCURVE('',#22096,#22698); -#22698 = DEFINITIONAL_REPRESENTATION('',(#22699),#22703); -#22699 = LINE('',#22700,#22701); -#22700 = CARTESIAN_POINT('',(-2.1,4.4)); -#22701 = VECTOR('',#22702,1.); -#22702 = DIRECTION('',(1.,-2.06514699521E-016)); -#22703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22704 = PCURVE('',#22705,#22710); -#22705 = PLANE('',#22706); -#22706 = AXIS2_PLACEMENT_3D('',#22707,#22708,#22709); -#22707 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22708 = DIRECTION('',(-1.,-2.06514699521E-016,7.085009279629E-015)); -#22709 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); -#22710 = DEFINITIONAL_REPRESENTATION('',(#22711),#22715); -#22711 = LINE('',#22712,#22713); -#22712 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22713 = VECTOR('',#22714,1.); -#22714 = DIRECTION('',(1.,-1.145632479557E-031)); -#22715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22716 = ORIENTED_EDGE('',*,*,#22717,.T.); -#22717 = EDGE_CURVE('',#22690,#22632,#22718,.T.); -#22718 = SURFACE_CURVE('',#22719,(#22723,#22730),.PCURVE_S1.); -#22719 = LINE('',#22720,#22721); -#22720 = CARTESIAN_POINT('',(2.2,0.755,0.895)); -#22721 = VECTOR('',#22722,1.); -#22722 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); -#22723 = PCURVE('',#22096,#22724); -#22724 = DEFINITIONAL_REPRESENTATION('',(#22725),#22729); -#22725 = LINE('',#22726,#22727); -#22726 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22727 = VECTOR('',#22728,1.); -#22728 = DIRECTION('',(-1.232047923279E-016,-1.)); -#22729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22730 = PCURVE('',#22731,#22736); -#22731 = PLANE('',#22732); -#22732 = AXIS2_PLACEMENT_3D('',#22733,#22734,#22735); -#22733 = CARTESIAN_POINT('',(2.2,0.755,0.895)); -#22734 = DIRECTION('',(1.232047923279E-016,-1.,-3.491483361109E-015)); -#22735 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); -#22736 = DEFINITIONAL_REPRESENTATION('',(#22737),#22741); -#22737 = LINE('',#22738,#22739); -#22738 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22739 = VECTOR('',#22740,1.); -#22740 = DIRECTION('',(1.,3.586081556449E-031)); -#22741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22742 = ADVANCED_FACE('',(#22743),#22150,.F.); -#22743 = FACE_BOUND('',#22744,.T.); -#22744 = EDGE_LOOP('',(#22745,#22746,#22747,#22770)); -#22745 = ORIENTED_EDGE('',*,*,#22136,.T.); -#22746 = ORIENTED_EDGE('',*,*,#22217,.F.); -#22747 = ORIENTED_EDGE('',*,*,#22748,.F.); -#22748 = EDGE_CURVE('',#22749,#22190,#22751,.T.); -#22749 = VERTEX_POINT('',#22750); -#22750 = CARTESIAN_POINT('',(1.4,2.085,2.645)); -#22751 = SURFACE_CURVE('',#22752,(#22756,#22763),.PCURVE_S1.); -#22752 = LINE('',#22753,#22754); -#22753 = CARTESIAN_POINT('',(1.4,2.435,2.645)); -#22754 = VECTOR('',#22755,1.); -#22755 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22756 = PCURVE('',#22150,#22757); -#22757 = DEFINITIONAL_REPRESENTATION('',(#22758),#22762); -#22758 = LINE('',#22759,#22760); -#22759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22760 = VECTOR('',#22761,1.); -#22761 = DIRECTION('',(-1.,0.E+000)); -#22762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22763 = PCURVE('',#22205,#22764); -#22764 = DEFINITIONAL_REPRESENTATION('',(#22765),#22769); -#22765 = LINE('',#22766,#22767); -#22766 = CARTESIAN_POINT('',(-1.99,2.45)); -#22767 = VECTOR('',#22768,1.); -#22768 = DIRECTION('',(-1.,1.702510980039E-043)); -#22769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22770 = ORIENTED_EDGE('',*,*,#22771,.T.); -#22771 = EDGE_CURVE('',#22749,#22048,#22772,.T.); -#22772 = SURFACE_CURVE('',#22773,(#22777,#22784),.PCURVE_S1.); -#22773 = LINE('',#22774,#22775); -#22774 = CARTESIAN_POINT('',(1.4,2.085,2.645)); -#22775 = VECTOR('',#22776,1.); -#22776 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#22777 = PCURVE('',#22150,#22778); -#22778 = DEFINITIONAL_REPRESENTATION('',(#22779),#22783); -#22779 = LINE('',#22780,#22781); -#22780 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); -#22781 = VECTOR('',#22782,1.); -#22782 = DIRECTION('',(-2.80259692865E-045,-1.)); -#22783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22784 = PCURVE('',#22068,#22785); -#22785 = DEFINITIONAL_REPRESENTATION('',(#22786),#22790); -#22786 = LINE('',#22787,#22788); -#22787 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22788 = VECTOR('',#22789,1.); -#22789 = DIRECTION('',(-1.109335647967E-030,-1.)); -#22790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22791 = ADVANCED_FACE('',(#22792),#22068,.F.); -#22792 = FACE_BOUND('',#22793,.T.); -#22793 = EDGE_LOOP('',(#22794,#22795,#22796,#22817)); -#22794 = ORIENTED_EDGE('',*,*,#22045,.T.); -#22795 = ORIENTED_EDGE('',*,*,#22771,.F.); -#22796 = ORIENTED_EDGE('',*,*,#22797,.F.); -#22797 = EDGE_CURVE('',#22242,#22749,#22798,.T.); -#22798 = SURFACE_CURVE('',#22799,(#22803,#22810),.PCURVE_S1.); -#22799 = LINE('',#22800,#22801); -#22800 = CARTESIAN_POINT('',(1.4,2.085,2.645)); -#22801 = VECTOR('',#22802,1.); -#22802 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#22803 = PCURVE('',#22068,#22804); -#22804 = DEFINITIONAL_REPRESENTATION('',(#22805),#22809); -#22805 = LINE('',#22806,#22807); -#22806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22807 = VECTOR('',#22808,1.); -#22808 = DIRECTION('',(-1.,4.74549138297E-031)); -#22809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22810 = PCURVE('',#22205,#22811); -#22811 = DEFINITIONAL_REPRESENTATION('',(#22812),#22816); -#22812 = LINE('',#22813,#22814); -#22813 = CARTESIAN_POINT('',(-1.64,2.45)); -#22814 = VECTOR('',#22815,1.); -#22815 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#22816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22817 = ORIENTED_EDGE('',*,*,#22241,.T.); -#22818 = ADVANCED_FACE('',(#22819),#22205,.T.); -#22819 = FACE_BOUND('',#22820,.T.); -#22820 = EDGE_LOOP('',(#22821,#22822,#22823,#22824)); -#22821 = ORIENTED_EDGE('',*,*,#22264,.F.); -#22822 = ORIENTED_EDGE('',*,*,#22797,.T.); -#22823 = ORIENTED_EDGE('',*,*,#22748,.T.); -#22824 = ORIENTED_EDGE('',*,*,#22189,.T.); -#22825 = ADVANCED_FACE('',(#22826),#22677,.F.); -#22826 = FACE_BOUND('',#22827,.T.); -#22827 = EDGE_LOOP('',(#22828,#22858,#22879,#22880)); -#22828 = ORIENTED_EDGE('',*,*,#22829,.T.); -#22829 = EDGE_CURVE('',#22830,#22832,#22834,.T.); -#22830 = VERTEX_POINT('',#22831); -#22831 = CARTESIAN_POINT('',(2.2,2.855,3.895)); -#22832 = VERTEX_POINT('',#22833); -#22833 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); -#22834 = SURFACE_CURVE('',#22835,(#22839,#22846),.PCURVE_S1.); -#22835 = LINE('',#22836,#22837); -#22836 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); -#22837 = VECTOR('',#22838,1.); -#22838 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); -#22839 = PCURVE('',#22677,#22840); -#22840 = DEFINITIONAL_REPRESENTATION('',(#22841),#22845); -#22841 = LINE('',#22842,#22843); -#22842 = CARTESIAN_POINT('',(-3.673819061467E-016,3.)); -#22843 = VECTOR('',#22844,1.); -#22844 = DIRECTION('',(1.,3.439710880676E-031)); -#22845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22846 = PCURVE('',#22847,#22852); -#22847 = PLANE('',#22848); -#22848 = AXIS2_PLACEMENT_3D('',#22849,#22850,#22851); -#22849 = CARTESIAN_POINT('',(-3.,3.255,3.895)); -#22850 = DIRECTION('',(-7.127527011883E-015,3.491483361109E-015,-1.)); -#22851 = DIRECTION('',(-1.,-5.047298460416E-031,7.127527011883E-015)); -#22852 = DEFINITIONAL_REPRESENTATION('',(#22853),#22857); -#22853 = LINE('',#22854,#22855); -#22854 = CARTESIAN_POINT('',(-0.8,-0.4)); -#22855 = VECTOR('',#22856,1.); -#22856 = DIRECTION('',(1.,-9.856383386232E-017)); -#22857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22858 = ORIENTED_EDGE('',*,*,#22859,.F.); -#22859 = EDGE_CURVE('',#22662,#22832,#22860,.T.); -#22860 = SURFACE_CURVE('',#22861,(#22865,#22872),.PCURVE_S1.); -#22861 = LINE('',#22862,#22863); -#22862 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); -#22863 = VECTOR('',#22864,1.); -#22864 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#22865 = PCURVE('',#22677,#22866); -#22866 = DEFINITIONAL_REPRESENTATION('',(#22867),#22871); -#22867 = LINE('',#22868,#22869); -#22868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22869 = VECTOR('',#22870,1.); -#22870 = DIRECTION('',(-1.020425574104E-016,1.)); -#22871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22872 = PCURVE('',#22705,#22873); -#22873 = DEFINITIONAL_REPRESENTATION('',(#22874),#22878); -#22874 = LINE('',#22875,#22876); -#22875 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22876 = VECTOR('',#22877,1.); -#22877 = DIRECTION('',(-1.145632479557E-031,1.)); -#22878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22879 = ORIENTED_EDGE('',*,*,#22661,.F.); -#22880 = ORIENTED_EDGE('',*,*,#22881,.T.); -#22881 = EDGE_CURVE('',#22634,#22830,#22882,.T.); -#22882 = SURFACE_CURVE('',#22883,(#22887,#22894),.PCURVE_S1.); -#22883 = LINE('',#22884,#22885); -#22884 = CARTESIAN_POINT('',(2.2,2.855,0.895)); -#22885 = VECTOR('',#22886,1.); -#22886 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#22887 = PCURVE('',#22677,#22888); -#22888 = DEFINITIONAL_REPRESENTATION('',(#22889),#22893); -#22889 = LINE('',#22890,#22891); -#22890 = CARTESIAN_POINT('',(-4.4,-2.812420435427E-017)); -#22891 = VECTOR('',#22892,1.); -#22892 = DIRECTION('',(-1.020425574104E-016,1.)); -#22893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22894 = PCURVE('',#22649,#22895); -#22895 = DEFINITIONAL_REPRESENTATION('',(#22896),#22900); -#22896 = LINE('',#22897,#22898); -#22897 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#22898 = VECTOR('',#22899,1.); -#22899 = DIRECTION('',(1.145632479557E-031,1.)); -#22900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22901 = ADVANCED_FACE('',(#22902),#22617,.F.); -#22902 = FACE_BOUND('',#22903,.T.); -#22903 = EDGE_LOOP('',(#22904,#22927,#22928,#22951)); -#22904 = ORIENTED_EDGE('',*,*,#22905,.F.); -#22905 = EDGE_CURVE('',#22520,#22906,#22908,.T.); -#22906 = VERTEX_POINT('',#22907); -#22907 = CARTESIAN_POINT('',(-1.4,2.085,2.645)); -#22908 = SURFACE_CURVE('',#22909,(#22913,#22920),.PCURVE_S1.); -#22909 = LINE('',#22910,#22911); -#22910 = CARTESIAN_POINT('',(-1.4,2.085,2.645)); -#22911 = VECTOR('',#22912,1.); -#22912 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#22913 = PCURVE('',#22617,#22914); -#22914 = DEFINITIONAL_REPRESENTATION('',(#22915),#22919); -#22915 = LINE('',#22916,#22917); -#22916 = CARTESIAN_POINT('',(-1.64,2.45)); -#22917 = VECTOR('',#22918,1.); -#22918 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#22919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22920 = PCURVE('',#22535,#22921); -#22921 = DEFINITIONAL_REPRESENTATION('',(#22922),#22926); -#22922 = LINE('',#22923,#22924); -#22923 = CARTESIAN_POINT('',(-6.414895964605E-017,-0.2)); -#22924 = VECTOR('',#22925,1.); -#22925 = DIRECTION('',(-1.,4.74549138297E-031)); -#22926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22927 = ORIENTED_EDGE('',*,*,#22603,.T.); -#22928 = ORIENTED_EDGE('',*,*,#22929,.F.); -#22929 = EDGE_CURVE('',#22930,#22576,#22932,.T.); -#22930 = VERTEX_POINT('',#22931); -#22931 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); -#22932 = SURFACE_CURVE('',#22933,(#22937,#22944),.PCURVE_S1.); -#22933 = LINE('',#22934,#22935); -#22934 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); -#22935 = VECTOR('',#22936,1.); -#22936 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#22937 = PCURVE('',#22617,#22938); -#22938 = DEFINITIONAL_REPRESENTATION('',(#22939),#22943); -#22939 = LINE('',#22940,#22941); -#22940 = CARTESIAN_POINT('',(-1.99,2.45)); -#22941 = VECTOR('',#22942,1.); -#22942 = DIRECTION('',(-1.770125995895E-016,-1.)); -#22943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22944 = PCURVE('',#22591,#22945); -#22945 = DEFINITIONAL_REPRESENTATION('',(#22946),#22950); -#22946 = LINE('',#22947,#22948); -#22947 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); -#22948 = VECTOR('',#22949,1.); -#22949 = DIRECTION('',(-1.,0.E+000)); -#22950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22951 = ORIENTED_EDGE('',*,*,#22952,.F.); -#22952 = EDGE_CURVE('',#22906,#22930,#22953,.T.); -#22953 = SURFACE_CURVE('',#22954,(#22958,#22965),.PCURVE_S1.); -#22954 = LINE('',#22955,#22956); -#22955 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); -#22956 = VECTOR('',#22957,1.); -#22957 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#22958 = PCURVE('',#22617,#22959); -#22959 = DEFINITIONAL_REPRESENTATION('',(#22960),#22964); -#22960 = LINE('',#22961,#22962); -#22961 = CARTESIAN_POINT('',(-1.99,2.45)); -#22962 = VECTOR('',#22963,1.); -#22963 = DIRECTION('',(-1.,1.702510980039E-043)); -#22964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22965 = PCURVE('',#22966,#22971); -#22966 = PLANE('',#22967); -#22967 = AXIS2_PLACEMENT_3D('',#22968,#22969,#22970); -#22968 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#22969 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#22970 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22971 = DEFINITIONAL_REPRESENTATION('',(#22972),#22976); -#22972 = LINE('',#22973,#22974); -#22973 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); -#22974 = VECTOR('',#22975,1.); -#22975 = DIRECTION('',(-1.,0.E+000)); -#22976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22977 = ADVANCED_FACE('',(#22978),#22649,.F.); -#22978 = FACE_BOUND('',#22979,.T.); -#22979 = EDGE_LOOP('',(#22980,#23010,#23038,#23059,#23060,#23061,#23084, - #23107)); -#22980 = ORIENTED_EDGE('',*,*,#22981,.F.); -#22981 = EDGE_CURVE('',#22982,#22984,#22986,.T.); -#22982 = VERTEX_POINT('',#22983); -#22983 = CARTESIAN_POINT('',(2.2,2.355,1.495)); -#22984 = VERTEX_POINT('',#22985); -#22985 = CARTESIAN_POINT('',(2.2,1.755,1.495)); -#22986 = SURFACE_CURVE('',#22987,(#22991,#22998),.PCURVE_S1.); -#22987 = LINE('',#22988,#22989); -#22988 = CARTESIAN_POINT('',(2.2,2.355,1.495)); -#22989 = VECTOR('',#22990,1.); -#22990 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#22991 = PCURVE('',#22649,#22992); -#22992 = DEFINITIONAL_REPRESENTATION('',(#22993),#22997); -#22993 = LINE('',#22994,#22995); -#22994 = CARTESIAN_POINT('',(-0.5,0.6)); -#22995 = VECTOR('',#22996,1.); -#22996 = DIRECTION('',(-1.,-1.145632479557E-031)); -#22997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#22998 = PCURVE('',#22999,#23004); -#22999 = PLANE('',#23000); -#23000 = AXIS2_PLACEMENT_3D('',#23001,#23002,#23003); -#23001 = CARTESIAN_POINT('',(2.2,1.755,1.495)); -#23002 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#23003 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23004 = DEFINITIONAL_REPRESENTATION('',(#23005),#23009); -#23005 = LINE('',#23006,#23007); -#23006 = CARTESIAN_POINT('',(0.6,1.395477078336E-029)); -#23007 = VECTOR('',#23008,1.); -#23008 = DIRECTION('',(-1.,0.E+000)); -#23009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23010 = ORIENTED_EDGE('',*,*,#23011,.T.); -#23011 = EDGE_CURVE('',#22982,#23012,#23014,.T.); -#23012 = VERTEX_POINT('',#23013); -#23013 = CARTESIAN_POINT('',(2.2,2.355,3.895)); -#23014 = SURFACE_CURVE('',#23015,(#23019,#23026),.PCURVE_S1.); -#23015 = LINE('',#23016,#23017); -#23016 = CARTESIAN_POINT('',(2.2,2.355,1.495)); -#23017 = VECTOR('',#23018,1.); -#23018 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23019 = PCURVE('',#22649,#23020); -#23020 = DEFINITIONAL_REPRESENTATION('',(#23021),#23025); -#23021 = LINE('',#23022,#23023); -#23022 = CARTESIAN_POINT('',(-0.5,0.6)); -#23023 = VECTOR('',#23024,1.); -#23024 = DIRECTION('',(1.145632479557E-031,1.)); -#23025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23026 = PCURVE('',#23027,#23032); -#23027 = PLANE('',#23028); -#23028 = AXIS2_PLACEMENT_3D('',#23029,#23030,#23031); -#23029 = CARTESIAN_POINT('',(2.2,2.355,1.495)); -#23030 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23031 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); -#23032 = DEFINITIONAL_REPRESENTATION('',(#23033),#23037); -#23033 = LINE('',#23034,#23035); -#23034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23035 = VECTOR('',#23036,1.); -#23036 = DIRECTION('',(-1.020425574104E-016,1.)); -#23037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23038 = ORIENTED_EDGE('',*,*,#23039,.T.); -#23039 = EDGE_CURVE('',#23012,#22830,#23040,.T.); -#23040 = SURFACE_CURVE('',#23041,(#23045,#23052),.PCURVE_S1.); -#23041 = LINE('',#23042,#23043); -#23042 = CARTESIAN_POINT('',(2.2,2.855,3.895)); -#23043 = VECTOR('',#23044,1.); -#23044 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); -#23045 = PCURVE('',#22649,#23046); -#23046 = DEFINITIONAL_REPRESENTATION('',(#23047),#23051); -#23047 = LINE('',#23048,#23049); -#23048 = CARTESIAN_POINT('',(-1.836909530734E-016,3.)); -#23049 = VECTOR('',#23050,1.); -#23050 = DIRECTION('',(1.,1.145632479557E-031)); -#23051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23052 = PCURVE('',#22847,#23053); -#23053 = DEFINITIONAL_REPRESENTATION('',(#23054),#23058); -#23054 = LINE('',#23055,#23056); -#23055 = CARTESIAN_POINT('',(-5.2,-0.4)); -#23056 = VECTOR('',#23057,1.); -#23057 = DIRECTION('',(2.06514699521E-016,1.)); -#23058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23059 = ORIENTED_EDGE('',*,*,#22881,.F.); -#23060 = ORIENTED_EDGE('',*,*,#22631,.F.); -#23061 = ORIENTED_EDGE('',*,*,#23062,.T.); -#23062 = EDGE_CURVE('',#22632,#23063,#23065,.T.); -#23063 = VERTEX_POINT('',#23064); -#23064 = CARTESIAN_POINT('',(2.2,0.755,3.895)); -#23065 = SURFACE_CURVE('',#23066,(#23070,#23077),.PCURVE_S1.); -#23066 = LINE('',#23067,#23068); -#23067 = CARTESIAN_POINT('',(2.2,0.755,0.895)); -#23068 = VECTOR('',#23069,1.); -#23069 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23070 = PCURVE('',#22649,#23071); -#23071 = DEFINITIONAL_REPRESENTATION('',(#23072),#23076); -#23072 = LINE('',#23073,#23074); -#23073 = CARTESIAN_POINT('',(-2.1,4.643095803673E-018)); -#23074 = VECTOR('',#23075,1.); -#23075 = DIRECTION('',(1.145632479557E-031,1.)); -#23076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23077 = PCURVE('',#22731,#23078); -#23078 = DEFINITIONAL_REPRESENTATION('',(#23079),#23083); -#23079 = LINE('',#23080,#23081); -#23080 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23081 = VECTOR('',#23082,1.); -#23082 = DIRECTION('',(1.020425574104E-016,1.)); -#23083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23084 = ORIENTED_EDGE('',*,*,#23085,.T.); -#23085 = EDGE_CURVE('',#23063,#23086,#23088,.T.); -#23086 = VERTEX_POINT('',#23087); -#23087 = CARTESIAN_POINT('',(2.2,1.755,3.895)); -#23088 = SURFACE_CURVE('',#23089,(#23093,#23100),.PCURVE_S1.); -#23089 = LINE('',#23090,#23091); -#23090 = CARTESIAN_POINT('',(2.2,2.855,3.895)); -#23091 = VECTOR('',#23092,1.); -#23092 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); -#23093 = PCURVE('',#22649,#23094); -#23094 = DEFINITIONAL_REPRESENTATION('',(#23095),#23099); -#23095 = LINE('',#23096,#23097); -#23096 = CARTESIAN_POINT('',(-1.836909530734E-016,3.)); -#23097 = VECTOR('',#23098,1.); -#23098 = DIRECTION('',(1.,1.145632479557E-031)); -#23099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23100 = PCURVE('',#22847,#23101); -#23101 = DEFINITIONAL_REPRESENTATION('',(#23102),#23106); -#23102 = LINE('',#23103,#23104); -#23103 = CARTESIAN_POINT('',(-5.2,-0.4)); -#23104 = VECTOR('',#23105,1.); -#23105 = DIRECTION('',(2.06514699521E-016,1.)); -#23106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23107 = ORIENTED_EDGE('',*,*,#23108,.F.); -#23108 = EDGE_CURVE('',#22984,#23086,#23109,.T.); -#23109 = SURFACE_CURVE('',#23110,(#23114,#23121),.PCURVE_S1.); -#23110 = LINE('',#23111,#23112); -#23111 = CARTESIAN_POINT('',(2.2,1.755,1.495)); -#23112 = VECTOR('',#23113,1.); -#23113 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23114 = PCURVE('',#22649,#23115); -#23115 = DEFINITIONAL_REPRESENTATION('',(#23116),#23120); -#23116 = LINE('',#23117,#23118); -#23117 = CARTESIAN_POINT('',(-1.1,0.6)); -#23118 = VECTOR('',#23119,1.); -#23119 = DIRECTION('',(1.145632479557E-031,1.)); -#23120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23121 = PCURVE('',#23122,#23127); -#23122 = PLANE('',#23123); -#23123 = AXIS2_PLACEMENT_3D('',#23124,#23125,#23126); -#23124 = CARTESIAN_POINT('',(2.2,1.755,1.495)); -#23125 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23126 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); -#23127 = DEFINITIONAL_REPRESENTATION('',(#23128),#23132); -#23128 = LINE('',#23129,#23130); -#23129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23130 = VECTOR('',#23131,1.); -#23131 = DIRECTION('',(1.020425574104E-016,1.)); -#23132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23133 = ADVANCED_FACE('',(#23134),#22477,.F.); -#23134 = FACE_BOUND('',#23135,.T.); -#23135 = EDGE_LOOP('',(#23136,#23159,#23160,#23183)); -#23136 = ORIENTED_EDGE('',*,*,#23137,.T.); -#23137 = EDGE_CURVE('',#23138,#22462,#23140,.T.); -#23138 = VERTEX_POINT('',#23139); -#23139 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); -#23140 = SURFACE_CURVE('',#23141,(#23145,#23152),.PCURVE_S1.); -#23141 = LINE('',#23142,#23143); -#23142 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); -#23143 = VECTOR('',#23144,1.); -#23144 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#23145 = PCURVE('',#22477,#23146); -#23146 = DEFINITIONAL_REPRESENTATION('',(#23147),#23151); -#23147 = LINE('',#23148,#23149); -#23148 = CARTESIAN_POINT('',(-3.797634949565E-016,-0.2)); -#23149 = VECTOR('',#23150,1.); -#23150 = DIRECTION('',(-1.,0.E+000)); -#23151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23152 = PCURVE('',#22503,#23153); -#23153 = DEFINITIONAL_REPRESENTATION('',(#23154),#23158); -#23154 = LINE('',#23155,#23156); -#23155 = CARTESIAN_POINT('',(-1.99,2.45)); -#23156 = VECTOR('',#23157,1.); -#23157 = DIRECTION('',(-1.770125995895E-016,-1.)); -#23158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23159 = ORIENTED_EDGE('',*,*,#22461,.T.); -#23160 = ORIENTED_EDGE('',*,*,#23161,.F.); -#23161 = EDGE_CURVE('',#23162,#22434,#23164,.T.); -#23162 = VERTEX_POINT('',#23163); -#23163 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#23164 = SURFACE_CURVE('',#23165,(#23169,#23176),.PCURVE_S1.); -#23165 = LINE('',#23166,#23167); -#23166 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#23167 = VECTOR('',#23168,1.); -#23168 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#23169 = PCURVE('',#22477,#23170); -#23170 = DEFINITIONAL_REPRESENTATION('',(#23171),#23175); -#23171 = LINE('',#23172,#23173); -#23172 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23173 = VECTOR('',#23174,1.); -#23174 = DIRECTION('',(-1.,0.E+000)); -#23175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23176 = PCURVE('',#22449,#23177); -#23177 = DEFINITIONAL_REPRESENTATION('',(#23178),#23182); -#23178 = LINE('',#23179,#23180); -#23179 = CARTESIAN_POINT('',(-1.99,2.45)); -#23180 = VECTOR('',#23181,1.); -#23181 = DIRECTION('',(-1.770125995895E-016,-1.)); -#23182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23183 = ORIENTED_EDGE('',*,*,#23184,.T.); -#23184 = EDGE_CURVE('',#23162,#23138,#23185,.T.); -#23185 = SURFACE_CURVE('',#23186,(#23190,#23197),.PCURVE_S1.); -#23186 = LINE('',#23187,#23188); -#23187 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#23188 = VECTOR('',#23189,1.); -#23189 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23190 = PCURVE('',#22477,#23191); -#23191 = DEFINITIONAL_REPRESENTATION('',(#23192),#23196); -#23192 = LINE('',#23193,#23194); -#23193 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23194 = VECTOR('',#23195,1.); -#23195 = DIRECTION('',(0.E+000,-1.)); -#23196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23197 = PCURVE('',#23198,#23203); -#23198 = PLANE('',#23199); -#23199 = AXIS2_PLACEMENT_3D('',#23200,#23201,#23202); -#23200 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#23201 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#23202 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23203 = DEFINITIONAL_REPRESENTATION('',(#23204),#23208); -#23204 = LINE('',#23205,#23206); -#23205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23206 = VECTOR('',#23207,1.); -#23207 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23209 = ADVANCED_FACE('',(#23210),#22307,.F.); -#23210 = FACE_BOUND('',#23211,.T.); -#23211 = EDGE_LOOP('',(#23212,#23235,#23263,#23284)); -#23212 = ORIENTED_EDGE('',*,*,#23213,.T.); -#23213 = EDGE_CURVE('',#22292,#23214,#23216,.T.); -#23214 = VERTEX_POINT('',#23215); -#23215 = CARTESIAN_POINT('',(0.6,2.085,2.645)); -#23216 = SURFACE_CURVE('',#23217,(#23221,#23228),.PCURVE_S1.); -#23217 = LINE('',#23218,#23219); -#23218 = CARTESIAN_POINT('',(0.6,2.085,2.645)); -#23219 = VECTOR('',#23220,1.); -#23220 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#23221 = PCURVE('',#22307,#23222); -#23222 = DEFINITIONAL_REPRESENTATION('',(#23223),#23227); -#23223 = LINE('',#23224,#23225); -#23224 = CARTESIAN_POINT('',(3.787199746371E-016,-0.2)); -#23225 = VECTOR('',#23226,1.); -#23226 = DIRECTION('',(-1.,4.74549138297E-031)); -#23227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23228 = PCURVE('',#22389,#23229); -#23229 = DEFINITIONAL_REPRESENTATION('',(#23230),#23234); -#23230 = LINE('',#23231,#23232); -#23231 = CARTESIAN_POINT('',(-1.64,2.45)); -#23232 = VECTOR('',#23233,1.); -#23233 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#23234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23235 = ORIENTED_EDGE('',*,*,#23236,.F.); -#23236 = EDGE_CURVE('',#23237,#23214,#23239,.T.); -#23237 = VERTEX_POINT('',#23238); -#23238 = CARTESIAN_POINT('',(0.4,2.085,2.645)); -#23239 = SURFACE_CURVE('',#23240,(#23244,#23251),.PCURVE_S1.); -#23240 = LINE('',#23241,#23242); -#23241 = CARTESIAN_POINT('',(0.4,2.085,2.645)); -#23242 = VECTOR('',#23243,1.); -#23243 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23244 = PCURVE('',#22307,#23245); -#23245 = DEFINITIONAL_REPRESENTATION('',(#23246),#23250); -#23246 = LINE('',#23247,#23248); -#23247 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23248 = VECTOR('',#23249,1.); -#23249 = DIRECTION('',(-1.109335647967E-030,-1.)); -#23250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23251 = PCURVE('',#23252,#23257); -#23252 = PLANE('',#23253); -#23253 = AXIS2_PLACEMENT_3D('',#23254,#23255,#23256); -#23254 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#23255 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#23256 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23257 = DEFINITIONAL_REPRESENTATION('',(#23258),#23262); -#23258 = LINE('',#23259,#23260); -#23259 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); -#23260 = VECTOR('',#23261,1.); -#23261 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23263 = ORIENTED_EDGE('',*,*,#23264,.F.); -#23264 = EDGE_CURVE('',#22290,#23237,#23265,.T.); -#23265 = SURFACE_CURVE('',#23266,(#23270,#23277),.PCURVE_S1.); -#23266 = LINE('',#23267,#23268); -#23267 = CARTESIAN_POINT('',(0.4,2.085,2.645)); -#23268 = VECTOR('',#23269,1.); -#23269 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#23270 = PCURVE('',#22307,#23271); -#23271 = DEFINITIONAL_REPRESENTATION('',(#23272),#23276); -#23272 = LINE('',#23273,#23274); -#23273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23274 = VECTOR('',#23275,1.); -#23275 = DIRECTION('',(-1.,4.74549138297E-031)); -#23276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23277 = PCURVE('',#22335,#23278); -#23278 = DEFINITIONAL_REPRESENTATION('',(#23279),#23283); -#23279 = LINE('',#23280,#23281); -#23280 = CARTESIAN_POINT('',(-1.64,2.45)); -#23281 = VECTOR('',#23282,1.); -#23282 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#23283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23284 = ORIENTED_EDGE('',*,*,#22289,.T.); -#23285 = ADVANCED_FACE('',(#23286),#22731,.F.); -#23286 = FACE_BOUND('',#23287,.T.); -#23287 = EDGE_LOOP('',(#23288,#23311,#23312,#23313)); -#23288 = ORIENTED_EDGE('',*,*,#23289,.T.); -#23289 = EDGE_CURVE('',#23290,#23063,#23292,.T.); -#23290 = VERTEX_POINT('',#23291); -#23291 = CARTESIAN_POINT('',(-2.2,0.755,3.895)); -#23292 = SURFACE_CURVE('',#23293,(#23297,#23304),.PCURVE_S1.); -#23293 = LINE('',#23294,#23295); -#23294 = CARTESIAN_POINT('',(2.2,0.755,3.895)); -#23295 = VECTOR('',#23296,1.); -#23296 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); -#23297 = PCURVE('',#22731,#23298); -#23298 = DEFINITIONAL_REPRESENTATION('',(#23299),#23303); -#23299 = LINE('',#23300,#23301); -#23300 = CARTESIAN_POINT('',(3.673819061467E-016,3.)); -#23301 = VECTOR('',#23302,1.); -#23302 = DIRECTION('',(1.,3.586081556449E-031)); -#23303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23304 = PCURVE('',#22847,#23305); -#23305 = DEFINITIONAL_REPRESENTATION('',(#23306),#23310); -#23306 = LINE('',#23307,#23308); -#23307 = CARTESIAN_POINT('',(-5.2,-2.5)); -#23308 = VECTOR('',#23309,1.); -#23309 = DIRECTION('',(-1.,1.232047923279E-016)); -#23310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23311 = ORIENTED_EDGE('',*,*,#23062,.F.); -#23312 = ORIENTED_EDGE('',*,*,#22717,.F.); -#23313 = ORIENTED_EDGE('',*,*,#23314,.T.); -#23314 = EDGE_CURVE('',#22690,#23290,#23315,.T.); -#23315 = SURFACE_CURVE('',#23316,(#23320,#23327),.PCURVE_S1.); -#23316 = LINE('',#23317,#23318); -#23317 = CARTESIAN_POINT('',(-2.2,0.755,0.895)); -#23318 = VECTOR('',#23319,1.); -#23319 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23320 = PCURVE('',#22731,#23321); -#23321 = DEFINITIONAL_REPRESENTATION('',(#23322),#23326); -#23322 = LINE('',#23323,#23324); -#23323 = CARTESIAN_POINT('',(-4.4,2.812420435427E-017)); -#23324 = VECTOR('',#23325,1.); -#23325 = DIRECTION('',(1.020425574104E-016,1.)); -#23326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23327 = PCURVE('',#22705,#23328); -#23328 = DEFINITIONAL_REPRESENTATION('',(#23329),#23333); -#23329 = LINE('',#23330,#23331); -#23330 = CARTESIAN_POINT('',(2.1,4.643095803673E-018)); -#23331 = VECTOR('',#23332,1.); -#23332 = DIRECTION('',(-1.145632479557E-031,1.)); -#23333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23334 = ADVANCED_FACE('',(#23335),#22449,.T.); -#23335 = FACE_BOUND('',#23336,.T.); -#23336 = EDGE_LOOP('',(#23337,#23338,#23361,#23382)); -#23337 = ORIENTED_EDGE('',*,*,#22433,.F.); -#23338 = ORIENTED_EDGE('',*,*,#23339,.T.); -#23339 = EDGE_CURVE('',#22404,#23340,#23342,.T.); -#23340 = VERTEX_POINT('',#23341); -#23341 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); -#23342 = SURFACE_CURVE('',#23343,(#23347,#23354),.PCURVE_S1.); -#23343 = LINE('',#23344,#23345); -#23344 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); -#23345 = VECTOR('',#23346,1.); -#23346 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#23347 = PCURVE('',#22449,#23348); -#23348 = DEFINITIONAL_REPRESENTATION('',(#23349),#23353); -#23349 = LINE('',#23350,#23351); -#23350 = CARTESIAN_POINT('',(-1.64,2.45)); -#23351 = VECTOR('',#23352,1.); -#23352 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#23353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23354 = PCURVE('',#22421,#23355); -#23355 = DEFINITIONAL_REPRESENTATION('',(#23356),#23360); -#23356 = LINE('',#23357,#23358); -#23357 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23358 = VECTOR('',#23359,1.); -#23359 = DIRECTION('',(-1.,4.74549138297E-031)); -#23360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23361 = ORIENTED_EDGE('',*,*,#23362,.T.); -#23362 = EDGE_CURVE('',#23340,#23162,#23363,.T.); -#23363 = SURFACE_CURVE('',#23364,(#23368,#23375),.PCURVE_S1.); -#23364 = LINE('',#23365,#23366); -#23365 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); -#23366 = VECTOR('',#23367,1.); -#23367 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23368 = PCURVE('',#22449,#23369); -#23369 = DEFINITIONAL_REPRESENTATION('',(#23370),#23374); -#23370 = LINE('',#23371,#23372); -#23371 = CARTESIAN_POINT('',(-1.99,2.45)); -#23372 = VECTOR('',#23373,1.); -#23373 = DIRECTION('',(-1.,1.702510980039E-043)); -#23374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23375 = PCURVE('',#23198,#23376); -#23376 = DEFINITIONAL_REPRESENTATION('',(#23377),#23381); -#23377 = LINE('',#23378,#23379); -#23378 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23379 = VECTOR('',#23380,1.); -#23380 = DIRECTION('',(-1.,0.E+000)); -#23381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23382 = ORIENTED_EDGE('',*,*,#23161,.T.); -#23383 = ADVANCED_FACE('',(#23384),#22563,.T.); -#23384 = FACE_BOUND('',#23385,.T.); -#23385 = EDGE_LOOP('',(#23386,#23387,#23410,#23433)); -#23386 = ORIENTED_EDGE('',*,*,#22547,.F.); -#23387 = ORIENTED_EDGE('',*,*,#23388,.T.); -#23388 = EDGE_CURVE('',#22518,#23389,#23391,.T.); -#23389 = VERTEX_POINT('',#23390); -#23390 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); -#23391 = SURFACE_CURVE('',#23392,(#23396,#23403),.PCURVE_S1.); -#23392 = LINE('',#23393,#23394); -#23393 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); -#23394 = VECTOR('',#23395,1.); -#23395 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, +#24430 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#24431),#30847); +#24431 = MANIFOLD_SOLID_BREP('',#24432); +#24432 = CLOSED_SHELL('',(#24433,#24553,#24629,#25134,#25183,#25210, + #25217,#25293,#25369,#25525,#25601,#25677,#25726,#25775,#25846, + #25917,#25966,#25993,#26127,#26154,#26181,#26208,#26235,#26726, + #26733,#26804,#26831,#26858,#26865,#26872,#26943,#26970,#26997, + #27073,#27080,#27156,#27451,#28047,#28096,#28222,#28338,#28494, + #28521,#28745,#28752,#28779,#28806,#28813,#28820,#28891,#28940, + #28967,#29354,#29401,#29428,#29435,#29442,#29547,#29652,#29679, + #29784,#29879,#29984,#30011,#30106,#30133,#30228,#30255,#30350, + #30377,#30404,#30411,#30506,#30515,#30542,#30569,#30596,#30603, + #30630,#30657,#30684,#30711,#30738,#30745,#30772,#30779,#30806, + #30813,#30840)); +#24433 = ADVANCED_FACE('',(#24434),#24448,.F.); +#24434 = FACE_BOUND('',#24435,.T.); +#24435 = EDGE_LOOP('',(#24436,#24471,#24499,#24527)); +#24436 = ORIENTED_EDGE('',*,*,#24437,.F.); +#24437 = EDGE_CURVE('',#24438,#24440,#24442,.T.); +#24438 = VERTEX_POINT('',#24439); +#24439 = CARTESIAN_POINT('',(1.6,1.955,0.895)); +#24440 = VERTEX_POINT('',#24441); +#24441 = CARTESIAN_POINT('',(1.6,2.085,2.645)); +#24442 = SURFACE_CURVE('',#24443,(#24447,#24459),.PCURVE_S1.); +#24443 = LINE('',#24444,#24445); +#24444 = CARTESIAN_POINT('',(1.6,2.085,2.645)); +#24445 = VECTOR('',#24446,1.); +#24446 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, 0.997252183706)); -#23396 = PCURVE('',#22563,#23397); -#23397 = DEFINITIONAL_REPRESENTATION('',(#23398),#23402); -#23398 = LINE('',#23399,#23400); -#23399 = CARTESIAN_POINT('',(-1.64,2.45)); -#23400 = VECTOR('',#23401,1.); -#23401 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#23402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23403 = PCURVE('',#22535,#23404); -#23404 = DEFINITIONAL_REPRESENTATION('',(#23405),#23409); -#23405 = LINE('',#23406,#23407); -#23406 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23407 = VECTOR('',#23408,1.); -#23408 = DIRECTION('',(-1.,4.74549138297E-031)); -#23409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23410 = ORIENTED_EDGE('',*,*,#23411,.T.); -#23411 = EDGE_CURVE('',#23389,#23412,#23414,.T.); -#23412 = VERTEX_POINT('',#23413); -#23413 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#23414 = SURFACE_CURVE('',#23415,(#23419,#23426),.PCURVE_S1.); -#23415 = LINE('',#23416,#23417); -#23416 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#23417 = VECTOR('',#23418,1.); -#23418 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23419 = PCURVE('',#22563,#23420); -#23420 = DEFINITIONAL_REPRESENTATION('',(#23421),#23425); -#23421 = LINE('',#23422,#23423); -#23422 = CARTESIAN_POINT('',(-1.99,2.45)); -#23423 = VECTOR('',#23424,1.); -#23424 = DIRECTION('',(-1.,1.702510980039E-043)); -#23425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23426 = PCURVE('',#22966,#23427); -#23427 = DEFINITIONAL_REPRESENTATION('',(#23428),#23432); -#23428 = LINE('',#23429,#23430); -#23429 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23430 = VECTOR('',#23431,1.); -#23431 = DIRECTION('',(-1.,0.E+000)); -#23432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23433 = ORIENTED_EDGE('',*,*,#23434,.T.); -#23434 = EDGE_CURVE('',#23412,#22548,#23435,.T.); -#23435 = SURFACE_CURVE('',#23436,(#23440,#23447),.PCURVE_S1.); -#23436 = LINE('',#23437,#23438); -#23437 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#23438 = VECTOR('',#23439,1.); -#23439 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#23440 = PCURVE('',#22563,#23441); -#23441 = DEFINITIONAL_REPRESENTATION('',(#23442),#23446); -#23442 = LINE('',#23443,#23444); -#23443 = CARTESIAN_POINT('',(-1.99,2.45)); -#23444 = VECTOR('',#23445,1.); -#23445 = DIRECTION('',(-1.770125995895E-016,-1.)); -#23446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23447 = PCURVE('',#22591,#23448); -#23448 = DEFINITIONAL_REPRESENTATION('',(#23449),#23453); -#23449 = LINE('',#23450,#23451); -#23450 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23451 = VECTOR('',#23452,1.); -#23452 = DIRECTION('',(-1.,0.E+000)); -#23453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23454 = ADVANCED_FACE('',(#23455),#22363,.F.); -#23455 = FACE_BOUND('',#23456,.T.); -#23456 = EDGE_LOOP('',(#23457,#23480,#23481,#23504)); -#23457 = ORIENTED_EDGE('',*,*,#23458,.T.); -#23458 = EDGE_CURVE('',#23459,#22348,#23461,.T.); -#23459 = VERTEX_POINT('',#23460); -#23460 = CARTESIAN_POINT('',(0.6,2.435,2.645)); -#23461 = SURFACE_CURVE('',#23462,(#23466,#23473),.PCURVE_S1.); -#23462 = LINE('',#23463,#23464); -#23463 = CARTESIAN_POINT('',(0.6,2.435,2.645)); -#23464 = VECTOR('',#23465,1.); -#23465 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#23466 = PCURVE('',#22363,#23467); -#23467 = DEFINITIONAL_REPRESENTATION('',(#23468),#23472); -#23468 = LINE('',#23469,#23470); -#23469 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); -#23470 = VECTOR('',#23471,1.); -#23471 = DIRECTION('',(-1.,0.E+000)); -#23472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23473 = PCURVE('',#22389,#23474); -#23474 = DEFINITIONAL_REPRESENTATION('',(#23475),#23479); -#23475 = LINE('',#23476,#23477); -#23476 = CARTESIAN_POINT('',(-1.99,2.45)); -#23477 = VECTOR('',#23478,1.); -#23478 = DIRECTION('',(-1.770125995895E-016,-1.)); -#23479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23480 = ORIENTED_EDGE('',*,*,#22347,.T.); -#23481 = ORIENTED_EDGE('',*,*,#23482,.F.); -#23482 = EDGE_CURVE('',#23483,#22320,#23485,.T.); -#23483 = VERTEX_POINT('',#23484); -#23484 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#23485 = SURFACE_CURVE('',#23486,(#23490,#23497),.PCURVE_S1.); -#23486 = LINE('',#23487,#23488); -#23487 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#23488 = VECTOR('',#23489,1.); -#23489 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); -#23490 = PCURVE('',#22363,#23491); -#23491 = DEFINITIONAL_REPRESENTATION('',(#23492),#23496); -#23492 = LINE('',#23493,#23494); -#23493 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23494 = VECTOR('',#23495,1.); -#23495 = DIRECTION('',(-1.,0.E+000)); -#23496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23497 = PCURVE('',#22335,#23498); -#23498 = DEFINITIONAL_REPRESENTATION('',(#23499),#23503); -#23499 = LINE('',#23500,#23501); -#23500 = CARTESIAN_POINT('',(-1.99,2.45)); -#23501 = VECTOR('',#23502,1.); -#23502 = DIRECTION('',(-1.770125995895E-016,-1.)); -#23503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23504 = ORIENTED_EDGE('',*,*,#23505,.T.); -#23505 = EDGE_CURVE('',#23483,#23459,#23506,.T.); -#23506 = SURFACE_CURVE('',#23507,(#23511,#23518),.PCURVE_S1.); -#23507 = LINE('',#23508,#23509); -#23508 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#23509 = VECTOR('',#23510,1.); -#23510 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23511 = PCURVE('',#22363,#23512); -#23512 = DEFINITIONAL_REPRESENTATION('',(#23513),#23517); -#23513 = LINE('',#23514,#23515); -#23514 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23515 = VECTOR('',#23516,1.); -#23516 = DIRECTION('',(0.E+000,-1.)); -#23517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23518 = PCURVE('',#23252,#23519); -#23519 = DEFINITIONAL_REPRESENTATION('',(#23520),#23524); -#23520 = LINE('',#23521,#23522); -#23521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23522 = VECTOR('',#23523,1.); -#23523 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23525 = ADVANCED_FACE('',(#23526),#22503,.F.); -#23526 = FACE_BOUND('',#23527,.T.); -#23527 = EDGE_LOOP('',(#23528,#23551,#23552,#23553)); -#23528 = ORIENTED_EDGE('',*,*,#23529,.F.); -#23529 = EDGE_CURVE('',#22406,#23530,#23532,.T.); -#23530 = VERTEX_POINT('',#23531); -#23531 = CARTESIAN_POINT('',(-0.4,2.085,2.645)); -#23532 = SURFACE_CURVE('',#23533,(#23537,#23544),.PCURVE_S1.); -#23533 = LINE('',#23534,#23535); -#23534 = CARTESIAN_POINT('',(-0.4,2.085,2.645)); -#23535 = VECTOR('',#23536,1.); -#23536 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, - 0.997252183706)); -#23537 = PCURVE('',#22503,#23538); -#23538 = DEFINITIONAL_REPRESENTATION('',(#23539),#23543); -#23539 = LINE('',#23540,#23541); -#23540 = CARTESIAN_POINT('',(-1.64,2.45)); -#23541 = VECTOR('',#23542,1.); -#23542 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); -#23543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23544 = PCURVE('',#22421,#23545); -#23545 = DEFINITIONAL_REPRESENTATION('',(#23546),#23550); -#23546 = LINE('',#23547,#23548); -#23547 = CARTESIAN_POINT('',(3.787199746371E-016,-0.2)); -#23548 = VECTOR('',#23549,1.); -#23549 = DIRECTION('',(-1.,4.74549138297E-031)); -#23550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23551 = ORIENTED_EDGE('',*,*,#22489,.T.); -#23552 = ORIENTED_EDGE('',*,*,#23137,.F.); -#23553 = ORIENTED_EDGE('',*,*,#23554,.F.); -#23554 = EDGE_CURVE('',#23530,#23138,#23555,.T.); -#23555 = SURFACE_CURVE('',#23556,(#23560,#23567),.PCURVE_S1.); -#23556 = LINE('',#23557,#23558); -#23557 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); -#23558 = VECTOR('',#23559,1.); -#23559 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23560 = PCURVE('',#22503,#23561); -#23561 = DEFINITIONAL_REPRESENTATION('',(#23562),#23566); -#23562 = LINE('',#23563,#23564); -#23563 = CARTESIAN_POINT('',(-1.99,2.45)); -#23564 = VECTOR('',#23565,1.); -#23565 = DIRECTION('',(-1.,1.702510980039E-043)); -#23566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23567 = PCURVE('',#23198,#23568); -#23568 = DEFINITIONAL_REPRESENTATION('',(#23569),#23573); -#23569 = LINE('',#23570,#23571); -#23570 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); -#23571 = VECTOR('',#23572,1.); -#23572 = DIRECTION('',(-1.,0.E+000)); -#23573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23574 = ADVANCED_FACE('',(#23575),#22335,.T.); -#23575 = FACE_BOUND('',#23576,.T.); -#23576 = EDGE_LOOP('',(#23577,#23578,#23579,#23600)); -#23577 = ORIENTED_EDGE('',*,*,#22319,.F.); -#23578 = ORIENTED_EDGE('',*,*,#23264,.T.); -#23579 = ORIENTED_EDGE('',*,*,#23580,.T.); -#23580 = EDGE_CURVE('',#23237,#23483,#23581,.T.); -#23581 = SURFACE_CURVE('',#23582,(#23586,#23593),.PCURVE_S1.); -#23582 = LINE('',#23583,#23584); -#23583 = CARTESIAN_POINT('',(0.4,2.435,2.645)); -#23584 = VECTOR('',#23585,1.); -#23585 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23586 = PCURVE('',#22335,#23587); -#23587 = DEFINITIONAL_REPRESENTATION('',(#23588),#23592); -#23588 = LINE('',#23589,#23590); -#23589 = CARTESIAN_POINT('',(-1.99,2.45)); -#23590 = VECTOR('',#23591,1.); -#23591 = DIRECTION('',(-1.,1.702510980039E-043)); -#23592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23593 = PCURVE('',#23252,#23594); -#23594 = DEFINITIONAL_REPRESENTATION('',(#23595),#23599); -#23595 = LINE('',#23596,#23597); -#23596 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23597 = VECTOR('',#23598,1.); -#23598 = DIRECTION('',(-1.,0.E+000)); -#23599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23600 = ORIENTED_EDGE('',*,*,#23482,.T.); -#23601 = ADVANCED_FACE('',(#23602),#22705,.F.); -#23602 = FACE_BOUND('',#23603,.T.); -#23603 = EDGE_LOOP('',(#23604,#23627,#23655,#23683,#23711,#23732,#23733, - #23734)); -#23604 = ORIENTED_EDGE('',*,*,#23605,.T.); -#23605 = EDGE_CURVE('',#22832,#23606,#23608,.T.); -#23606 = VERTEX_POINT('',#23607); -#23607 = CARTESIAN_POINT('',(-2.2,2.355,3.895)); -#23608 = SURFACE_CURVE('',#23609,(#23613,#23620),.PCURVE_S1.); -#23609 = LINE('',#23610,#23611); -#23610 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); -#23611 = VECTOR('',#23612,1.); -#23612 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); -#23613 = PCURVE('',#22705,#23614); -#23614 = DEFINITIONAL_REPRESENTATION('',(#23615),#23619); -#23615 = LINE('',#23616,#23617); -#23616 = CARTESIAN_POINT('',(1.836909530734E-016,3.)); -#23617 = VECTOR('',#23618,1.); -#23618 = DIRECTION('',(1.,-1.145632479557E-031)); -#23619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23620 = PCURVE('',#22847,#23621); -#23621 = DEFINITIONAL_REPRESENTATION('',(#23622),#23626); -#23622 = LINE('',#23623,#23624); -#23623 = CARTESIAN_POINT('',(-0.8,-0.4)); -#23624 = VECTOR('',#23625,1.); -#23625 = DIRECTION('',(-2.06514699521E-016,-1.)); -#23626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23627 = ORIENTED_EDGE('',*,*,#23628,.F.); -#23628 = EDGE_CURVE('',#23629,#23606,#23631,.T.); -#23629 = VERTEX_POINT('',#23630); -#23630 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); -#23631 = SURFACE_CURVE('',#23632,(#23636,#23643),.PCURVE_S1.); -#23632 = LINE('',#23633,#23634); -#23633 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); -#23634 = VECTOR('',#23635,1.); -#23635 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23636 = PCURVE('',#22705,#23637); -#23637 = DEFINITIONAL_REPRESENTATION('',(#23638),#23642); -#23638 = LINE('',#23639,#23640); -#23639 = CARTESIAN_POINT('',(0.5,0.6)); -#23640 = VECTOR('',#23641,1.); -#23641 = DIRECTION('',(-1.145632479557E-031,1.)); -#23642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23643 = PCURVE('',#23644,#23649); -#23644 = PLANE('',#23645); -#23645 = AXIS2_PLACEMENT_3D('',#23646,#23647,#23648); -#23646 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); -#23647 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23648 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); -#23649 = DEFINITIONAL_REPRESENTATION('',(#23650),#23654); -#23650 = LINE('',#23651,#23652); -#23651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23652 = VECTOR('',#23653,1.); -#23653 = DIRECTION('',(-1.020425574104E-016,1.)); -#23654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23655 = ORIENTED_EDGE('',*,*,#23656,.F.); -#23656 = EDGE_CURVE('',#23657,#23629,#23659,.T.); -#23657 = VERTEX_POINT('',#23658); -#23658 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); -#23659 = SURFACE_CURVE('',#23660,(#23664,#23671),.PCURVE_S1.); -#23660 = LINE('',#23661,#23662); -#23661 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); -#23662 = VECTOR('',#23663,1.); -#23663 = DIRECTION('',(-1.445602896647E-015,1.,3.491483361109E-015)); -#23664 = PCURVE('',#22705,#23665); -#23665 = DEFINITIONAL_REPRESENTATION('',(#23666),#23670); -#23666 = LINE('',#23667,#23668); -#23667 = CARTESIAN_POINT('',(0.5,0.6)); -#23668 = VECTOR('',#23669,1.); -#23669 = DIRECTION('',(-1.,1.145632479557E-031)); -#23670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23671 = PCURVE('',#23672,#23677); -#23672 = PLANE('',#23673); -#23673 = AXIS2_PLACEMENT_3D('',#23674,#23675,#23676); -#23674 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); -#23675 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#23676 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23677 = DEFINITIONAL_REPRESENTATION('',(#23678),#23682); -#23678 = LINE('',#23679,#23680); -#23679 = CARTESIAN_POINT('',(5.403763914175E-033,-0.35)); -#23680 = VECTOR('',#23681,1.); -#23681 = DIRECTION('',(1.,1.445602896647E-015)); -#23682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23683 = ORIENTED_EDGE('',*,*,#23684,.T.); -#23684 = EDGE_CURVE('',#23657,#23685,#23687,.T.); -#23685 = VERTEX_POINT('',#23686); -#23686 = CARTESIAN_POINT('',(-2.2,1.755,3.895)); -#23687 = SURFACE_CURVE('',#23688,(#23692,#23699),.PCURVE_S1.); -#23688 = LINE('',#23689,#23690); -#23689 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); -#23690 = VECTOR('',#23691,1.); -#23691 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#23692 = PCURVE('',#22705,#23693); -#23693 = DEFINITIONAL_REPRESENTATION('',(#23694),#23698); -#23694 = LINE('',#23695,#23696); -#23695 = CARTESIAN_POINT('',(1.1,0.6)); -#23696 = VECTOR('',#23697,1.); -#23697 = DIRECTION('',(-1.145632479557E-031,1.)); -#23698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23699 = PCURVE('',#23700,#23705); -#23700 = PLANE('',#23701); -#23701 = AXIS2_PLACEMENT_3D('',#23702,#23703,#23704); -#23702 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); -#23703 = DIRECTION('',(6.195440985631E-016,-1.,-3.491483361109E-015)); -#23704 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); -#23705 = DEFINITIONAL_REPRESENTATION('',(#23706),#23710); -#23706 = LINE('',#23707,#23708); -#23707 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23708 = VECTOR('',#23709,1.); -#23709 = DIRECTION('',(1.020425574104E-016,1.)); -#23710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23711 = ORIENTED_EDGE('',*,*,#23712,.T.); -#23712 = EDGE_CURVE('',#23685,#23290,#23713,.T.); -#23713 = SURFACE_CURVE('',#23714,(#23718,#23725),.PCURVE_S1.); -#23714 = LINE('',#23715,#23716); -#23715 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); -#23716 = VECTOR('',#23717,1.); -#23717 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); -#23718 = PCURVE('',#22705,#23719); -#23719 = DEFINITIONAL_REPRESENTATION('',(#23720),#23724); -#23720 = LINE('',#23721,#23722); -#23721 = CARTESIAN_POINT('',(1.836909530734E-016,3.)); -#23722 = VECTOR('',#23723,1.); -#23723 = DIRECTION('',(1.,-1.145632479557E-031)); -#23724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23725 = PCURVE('',#22847,#23726); -#23726 = DEFINITIONAL_REPRESENTATION('',(#23727),#23731); -#23727 = LINE('',#23728,#23729); -#23728 = CARTESIAN_POINT('',(-0.8,-0.4)); -#23729 = VECTOR('',#23730,1.); -#23730 = DIRECTION('',(-2.06514699521E-016,-1.)); -#23731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23732 = ORIENTED_EDGE('',*,*,#23314,.F.); -#23733 = ORIENTED_EDGE('',*,*,#22689,.F.); -#23734 = ORIENTED_EDGE('',*,*,#22859,.T.); -#23735 = ADVANCED_FACE('',(#23736),#22591,.F.); -#23736 = FACE_BOUND('',#23737,.T.); -#23737 = EDGE_LOOP('',(#23738,#23739,#23740,#23741)); -#23738 = ORIENTED_EDGE('',*,*,#22929,.T.); -#23739 = ORIENTED_EDGE('',*,*,#22575,.T.); -#23740 = ORIENTED_EDGE('',*,*,#23434,.F.); -#23741 = ORIENTED_EDGE('',*,*,#23742,.T.); -#23742 = EDGE_CURVE('',#23412,#22930,#23743,.T.); -#23743 = SURFACE_CURVE('',#23744,(#23748,#23755),.PCURVE_S1.); -#23744 = LINE('',#23745,#23746); -#23745 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); -#23746 = VECTOR('',#23747,1.); -#23747 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23748 = PCURVE('',#22591,#23749); -#23749 = DEFINITIONAL_REPRESENTATION('',(#23750),#23754); -#23750 = LINE('',#23751,#23752); -#23751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23752 = VECTOR('',#23753,1.); -#23753 = DIRECTION('',(0.E+000,-1.)); -#23754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23755 = PCURVE('',#22966,#23756); -#23756 = DEFINITIONAL_REPRESENTATION('',(#23757),#23761); -#23757 = LINE('',#23758,#23759); -#23758 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23759 = VECTOR('',#23760,1.); -#23760 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23762 = ADVANCED_FACE('',(#23763),#22389,.F.); -#23763 = FACE_BOUND('',#23764,.T.); -#23764 = EDGE_LOOP('',(#23765,#23766,#23767,#23768)); -#23765 = ORIENTED_EDGE('',*,*,#23213,.F.); -#23766 = ORIENTED_EDGE('',*,*,#22375,.T.); -#23767 = ORIENTED_EDGE('',*,*,#23458,.F.); -#23768 = ORIENTED_EDGE('',*,*,#23769,.F.); -#23769 = EDGE_CURVE('',#23214,#23459,#23770,.T.); -#23770 = SURFACE_CURVE('',#23771,(#23775,#23782),.PCURVE_S1.); -#23771 = LINE('',#23772,#23773); -#23772 = CARTESIAN_POINT('',(0.6,2.435,2.645)); -#23773 = VECTOR('',#23774,1.); -#23774 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23775 = PCURVE('',#22389,#23776); -#23776 = DEFINITIONAL_REPRESENTATION('',(#23777),#23781); -#23777 = LINE('',#23778,#23779); -#23778 = CARTESIAN_POINT('',(-1.99,2.45)); -#23779 = VECTOR('',#23780,1.); -#23780 = DIRECTION('',(-1.,1.702510980039E-043)); -#23781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23782 = PCURVE('',#23252,#23783); -#23783 = DEFINITIONAL_REPRESENTATION('',(#23784),#23788); -#23784 = LINE('',#23785,#23786); -#23785 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); -#23786 = VECTOR('',#23787,1.); -#23787 = DIRECTION('',(-1.,0.E+000)); -#23788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23789 = ADVANCED_FACE('',(#23790),#22535,.F.); -#23790 = FACE_BOUND('',#23791,.T.); -#23791 = EDGE_LOOP('',(#23792,#23793,#23814,#23815)); -#23792 = ORIENTED_EDGE('',*,*,#22905,.T.); -#23793 = ORIENTED_EDGE('',*,*,#23794,.F.); -#23794 = EDGE_CURVE('',#23389,#22906,#23795,.T.); -#23795 = SURFACE_CURVE('',#23796,(#23800,#23807),.PCURVE_S1.); -#23796 = LINE('',#23797,#23798); -#23797 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); -#23798 = VECTOR('',#23799,1.); -#23799 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23800 = PCURVE('',#22535,#23801); -#23801 = DEFINITIONAL_REPRESENTATION('',(#23802),#23806); -#23802 = LINE('',#23803,#23804); -#23803 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23804 = VECTOR('',#23805,1.); -#23805 = DIRECTION('',(-1.109335647967E-030,-1.)); -#23806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23807 = PCURVE('',#22966,#23808); -#23808 = DEFINITIONAL_REPRESENTATION('',(#23809),#23813); -#23809 = LINE('',#23810,#23811); -#23810 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); -#23811 = VECTOR('',#23812,1.); -#23812 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23814 = ORIENTED_EDGE('',*,*,#23388,.F.); -#23815 = ORIENTED_EDGE('',*,*,#22517,.T.); -#23816 = ADVANCED_FACE('',(#23817),#22421,.F.); -#23817 = FACE_BOUND('',#23818,.T.); -#23818 = EDGE_LOOP('',(#23819,#23820,#23841,#23842)); -#23819 = ORIENTED_EDGE('',*,*,#23529,.T.); -#23820 = ORIENTED_EDGE('',*,*,#23821,.F.); -#23821 = EDGE_CURVE('',#23340,#23530,#23822,.T.); -#23822 = SURFACE_CURVE('',#23823,(#23827,#23834),.PCURVE_S1.); -#23823 = LINE('',#23824,#23825); -#23824 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); -#23825 = VECTOR('',#23826,1.); -#23826 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23827 = PCURVE('',#22421,#23828); -#23828 = DEFINITIONAL_REPRESENTATION('',(#23829),#23833); -#23829 = LINE('',#23830,#23831); -#23830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23831 = VECTOR('',#23832,1.); -#23832 = DIRECTION('',(-1.109335647967E-030,-1.)); -#23833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23834 = PCURVE('',#23198,#23835); -#23835 = DEFINITIONAL_REPRESENTATION('',(#23836),#23840); -#23836 = LINE('',#23837,#23838); -#23837 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); -#23838 = VECTOR('',#23839,1.); -#23839 = DIRECTION('',(-2.80259692865E-045,-1.)); -#23840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23841 = ORIENTED_EDGE('',*,*,#23339,.F.); -#23842 = ORIENTED_EDGE('',*,*,#22403,.T.); -#23843 = ADVANCED_FACE('',(#23844,#24182),#22847,.F.); -#23844 = FACE_BOUND('',#23845,.T.); -#23845 = EDGE_LOOP('',(#23846,#23876,#23904,#23932,#23960,#23988,#24016, - #24044,#24072,#24100,#24128,#24156)); -#23846 = ORIENTED_EDGE('',*,*,#23847,.F.); -#23847 = EDGE_CURVE('',#23848,#23850,#23852,.T.); -#23848 = VERTEX_POINT('',#23849); -#23849 = CARTESIAN_POINT('',(-2.7,1.555,3.895)); -#23850 = VERTEX_POINT('',#23851); -#23851 = CARTESIAN_POINT('',(-3.,1.555,3.895)); -#23852 = SURFACE_CURVE('',#23853,(#23857,#23864),.PCURVE_S1.); -#23853 = LINE('',#23854,#23855); -#23854 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); -#23855 = VECTOR('',#23856,1.); -#23856 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#23857 = PCURVE('',#22847,#23858); -#23858 = DEFINITIONAL_REPRESENTATION('',(#23859),#23863); -#23859 = LINE('',#23860,#23861); -#23860 = CARTESIAN_POINT('',(-0.5,-1.7)); -#23861 = VECTOR('',#23862,1.); -#23862 = DIRECTION('',(1.,2.835439861407E-045)); -#23863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23864 = PCURVE('',#23865,#23870); -#23865 = PLANE('',#23866); -#23866 = AXIS2_PLACEMENT_3D('',#23867,#23868,#23869); -#23867 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); -#23868 = DIRECTION('',(-2.135253304556E-029,-1.,-3.057802492115E-015)); -#23869 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); -#23870 = DEFINITIONAL_REPRESENTATION('',(#23871),#23875); -#23871 = LINE('',#23872,#23873); -#23872 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23873 = VECTOR('',#23874,1.); -#23874 = DIRECTION('',(0.E+000,1.)); -#23875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23876 = ORIENTED_EDGE('',*,*,#23877,.T.); -#23877 = EDGE_CURVE('',#23848,#23878,#23880,.T.); -#23878 = VERTEX_POINT('',#23879); -#23879 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); -#23880 = SURFACE_CURVE('',#23881,(#23885,#23892),.PCURVE_S1.); -#23881 = LINE('',#23882,#23883); -#23882 = CARTESIAN_POINT('',(-2.7,1.555,3.895)); -#23883 = VECTOR('',#23884,1.); -#23884 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23885 = PCURVE('',#22847,#23886); -#23886 = DEFINITIONAL_REPRESENTATION('',(#23887),#23891); -#23887 = LINE('',#23888,#23889); -#23888 = CARTESIAN_POINT('',(-0.3,-1.7)); -#23889 = VECTOR('',#23890,1.); -#23890 = DIRECTION('',(4.608958230318E-045,-1.)); -#23891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23892 = PCURVE('',#23893,#23898); -#23893 = PLANE('',#23894); -#23894 = AXIS2_PLACEMENT_3D('',#23895,#23896,#23897); -#23895 = CARTESIAN_POINT('',(-2.7,0.905,2.395)); -#23896 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#23897 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23898 = DEFINITIONAL_REPRESENTATION('',(#23899),#23903); -#23899 = LINE('',#23900,#23901); -#23900 = CARTESIAN_POINT('',(0.65,-1.5)); -#23901 = VECTOR('',#23902,1.); -#23902 = DIRECTION('',(-1.,1.702510980039E-043)); -#23903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23904 = ORIENTED_EDGE('',*,*,#23905,.T.); -#23905 = EDGE_CURVE('',#23878,#23906,#23908,.T.); -#23906 = VERTEX_POINT('',#23907); -#23907 = CARTESIAN_POINT('',(-2.5,0.305,3.895)); -#23908 = SURFACE_CURVE('',#23909,(#23913,#23920),.PCURVE_S1.); -#23909 = LINE('',#23910,#23911); -#23910 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); -#23911 = VECTOR('',#23912,1.); -#23912 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#23913 = PCURVE('',#22847,#23914); -#23914 = DEFINITIONAL_REPRESENTATION('',(#23915),#23919); -#23915 = LINE('',#23916,#23917); -#23916 = CARTESIAN_POINT('',(-0.3,-2.95)); -#23917 = VECTOR('',#23918,1.); -#23918 = DIRECTION('',(-1.,-2.835439861407E-045)); -#23919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23920 = PCURVE('',#23921,#23926); -#23921 = PLANE('',#23922); -#23922 = AXIS2_PLACEMENT_3D('',#23923,#23924,#23925); -#23923 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); -#23924 = DIRECTION('',(-2.5232643737E-029,-1.,-3.613456105514E-015)); -#23925 = DIRECTION('',(6.982966722219E-015,-3.613456105514E-015,1.)); -#23926 = DEFINITIONAL_REPRESENTATION('',(#23927),#23931); -#23927 = LINE('',#23928,#23929); -#23928 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#23929 = VECTOR('',#23930,1.); -#23930 = DIRECTION('',(0.E+000,-1.)); -#23931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23932 = ORIENTED_EDGE('',*,*,#23933,.F.); -#23933 = EDGE_CURVE('',#23934,#23906,#23936,.T.); -#23934 = VERTEX_POINT('',#23935); -#23935 = CARTESIAN_POINT('',(-2.5,0.355,3.895)); -#23936 = SURFACE_CURVE('',#23937,(#23941,#23948),.PCURVE_S1.); -#23937 = LINE('',#23938,#23939); -#23938 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); -#23939 = VECTOR('',#23940,1.); -#23940 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23941 = PCURVE('',#22847,#23942); -#23942 = DEFINITIONAL_REPRESENTATION('',(#23943),#23947); -#23943 = LINE('',#23944,#23945); -#23944 = CARTESIAN_POINT('',(-0.5,-1.7)); -#23945 = VECTOR('',#23946,1.); -#23946 = DIRECTION('',(4.608958230318E-045,-1.)); -#23947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23948 = PCURVE('',#23949,#23954); -#23949 = PLANE('',#23950); -#23950 = AXIS2_PLACEMENT_3D('',#23951,#23952,#23953); -#23951 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); -#23952 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#23953 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#23954 = DEFINITIONAL_REPRESENTATION('',(#23955),#23959); -#23955 = LINE('',#23956,#23957); -#23956 = CARTESIAN_POINT('',(0.65,-1.5)); -#23957 = VECTOR('',#23958,1.); -#23958 = DIRECTION('',(-1.,1.702510980039E-043)); -#23959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23960 = ORIENTED_EDGE('',*,*,#23961,.T.); -#23961 = EDGE_CURVE('',#23934,#23962,#23964,.T.); -#23962 = VERTEX_POINT('',#23963); -#23963 = CARTESIAN_POINT('',(2.5,0.355,3.895)); -#23964 = SURFACE_CURVE('',#23965,(#23969,#23976),.PCURVE_S1.); -#23965 = LINE('',#23966,#23967); -#23966 = CARTESIAN_POINT('',(-3.,0.355,3.895)); -#23967 = VECTOR('',#23968,1.); -#23968 = DIRECTION('',(1.,5.047298460416E-031,-7.127527011883E-015)); -#23969 = PCURVE('',#22847,#23970); -#23970 = DEFINITIONAL_REPRESENTATION('',(#23971),#23975); -#23971 = LINE('',#23972,#23973); -#23972 = CARTESIAN_POINT('',(-7.1337213741E-029,-2.9)); -#23973 = VECTOR('',#23974,1.); -#23974 = DIRECTION('',(-1.,-6.51384833026E-045)); -#23975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23976 = PCURVE('',#23977,#23982); -#23977 = PLANE('',#23978); -#23978 = AXIS2_PLACEMENT_3D('',#23979,#23980,#23981); -#23979 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); -#23980 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23981 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); -#23982 = DEFINITIONAL_REPRESENTATION('',(#23983),#23987); -#23983 = LINE('',#23984,#23985); -#23984 = CARTESIAN_POINT('',(-3.677207193256E-016,4.25)); -#23985 = VECTOR('',#23986,1.); -#23986 = DIRECTION('',(1.,-1.445602896647E-016)); -#23987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#23988 = ORIENTED_EDGE('',*,*,#23989,.T.); -#23989 = EDGE_CURVE('',#23962,#23990,#23992,.T.); -#23990 = VERTEX_POINT('',#23991); -#23991 = CARTESIAN_POINT('',(2.5,0.305,3.895)); -#23992 = SURFACE_CURVE('',#23993,(#23997,#24004),.PCURVE_S1.); -#23993 = LINE('',#23994,#23995); -#23994 = CARTESIAN_POINT('',(2.5,1.555,3.895)); -#23995 = VECTOR('',#23996,1.); -#23996 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#23997 = PCURVE('',#22847,#23998); -#23998 = DEFINITIONAL_REPRESENTATION('',(#23999),#24003); -#23999 = LINE('',#24000,#24001); -#24000 = CARTESIAN_POINT('',(-5.5,-1.7)); -#24001 = VECTOR('',#24002,1.); -#24002 = DIRECTION('',(4.608958230318E-045,-1.)); -#24003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24004 = PCURVE('',#24005,#24010); -#24005 = PLANE('',#24006); -#24006 = AXIS2_PLACEMENT_3D('',#24007,#24008,#24009); -#24007 = CARTESIAN_POINT('',(2.5,0.905,2.395)); -#24008 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24009 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24010 = DEFINITIONAL_REPRESENTATION('',(#24011),#24015); -#24011 = LINE('',#24012,#24013); -#24012 = CARTESIAN_POINT('',(0.65,1.5)); -#24013 = VECTOR('',#24014,1.); -#24014 = DIRECTION('',(-1.,-1.702510980039E-043)); -#24015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24016 = ORIENTED_EDGE('',*,*,#24017,.F.); -#24017 = EDGE_CURVE('',#24018,#23990,#24020,.T.); -#24018 = VERTEX_POINT('',#24019); -#24019 = CARTESIAN_POINT('',(2.7,0.305,3.895)); -#24020 = SURFACE_CURVE('',#24021,(#24025,#24032),.PCURVE_S1.); -#24021 = LINE('',#24022,#24023); -#24022 = CARTESIAN_POINT('',(2.7,0.305,3.895)); -#24023 = VECTOR('',#24024,1.); -#24024 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24025 = PCURVE('',#22847,#24026); -#24026 = DEFINITIONAL_REPRESENTATION('',(#24027),#24031); -#24027 = LINE('',#24028,#24029); -#24028 = CARTESIAN_POINT('',(-5.7,-2.95)); -#24029 = VECTOR('',#24030,1.); -#24030 = DIRECTION('',(1.,2.835439861407E-045)); -#24031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24032 = PCURVE('',#24033,#24038); -#24033 = PLANE('',#24034); -#24034 = AXIS2_PLACEMENT_3D('',#24035,#24036,#24037); -#24035 = CARTESIAN_POINT('',(2.7,0.305,3.895)); -#24036 = DIRECTION('',(2.5232643737E-029,1.,3.613456105514E-015)); -#24037 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); -#24038 = DEFINITIONAL_REPRESENTATION('',(#24039),#24043); -#24039 = LINE('',#24040,#24041); -#24040 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24041 = VECTOR('',#24042,1.); -#24042 = DIRECTION('',(0.E+000,1.)); -#24043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24044 = ORIENTED_EDGE('',*,*,#24045,.F.); -#24045 = EDGE_CURVE('',#24046,#24018,#24048,.T.); -#24046 = VERTEX_POINT('',#24047); -#24047 = CARTESIAN_POINT('',(2.7,1.555,3.895)); -#24048 = SURFACE_CURVE('',#24049,(#24053,#24060),.PCURVE_S1.); -#24049 = LINE('',#24050,#24051); -#24050 = CARTESIAN_POINT('',(2.7,1.555,3.895)); -#24051 = VECTOR('',#24052,1.); -#24052 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24053 = PCURVE('',#22847,#24054); -#24054 = DEFINITIONAL_REPRESENTATION('',(#24055),#24059); -#24055 = LINE('',#24056,#24057); -#24056 = CARTESIAN_POINT('',(-5.7,-1.7)); -#24057 = VECTOR('',#24058,1.); -#24058 = DIRECTION('',(4.608958230318E-045,-1.)); -#24059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24060 = PCURVE('',#24061,#24066); -#24061 = PLANE('',#24062); -#24062 = AXIS2_PLACEMENT_3D('',#24063,#24064,#24065); -#24063 = CARTESIAN_POINT('',(2.7,0.905,2.395)); -#24064 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24065 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24066 = DEFINITIONAL_REPRESENTATION('',(#24067),#24071); -#24067 = LINE('',#24068,#24069); -#24068 = CARTESIAN_POINT('',(0.65,1.5)); -#24069 = VECTOR('',#24070,1.); -#24070 = DIRECTION('',(-1.,-1.702510980039E-043)); -#24071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24072 = ORIENTED_EDGE('',*,*,#24073,.T.); -#24073 = EDGE_CURVE('',#24046,#24074,#24076,.T.); -#24074 = VERTEX_POINT('',#24075); -#24075 = CARTESIAN_POINT('',(3.,1.555,3.895)); -#24076 = SURFACE_CURVE('',#24077,(#24081,#24088),.PCURVE_S1.); -#24077 = LINE('',#24078,#24079); -#24078 = CARTESIAN_POINT('',(2.5,1.555,3.895)); -#24079 = VECTOR('',#24080,1.); -#24080 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24081 = PCURVE('',#22847,#24082); -#24082 = DEFINITIONAL_REPRESENTATION('',(#24083),#24087); -#24083 = LINE('',#24084,#24085); -#24084 = CARTESIAN_POINT('',(-5.5,-1.7)); -#24085 = VECTOR('',#24086,1.); -#24086 = DIRECTION('',(-1.,-2.835439861407E-045)); -#24087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24088 = PCURVE('',#24089,#24094); -#24089 = PLANE('',#24090); -#24090 = AXIS2_PLACEMENT_3D('',#24091,#24092,#24093); -#24091 = CARTESIAN_POINT('',(2.5,1.555,3.895)); -#24092 = DIRECTION('',(2.135253304556E-029,1.,3.057802492115E-015)); -#24093 = DIRECTION('',(-6.982966722219E-015,3.057802492115E-015,-1.)); -#24094 = DEFINITIONAL_REPRESENTATION('',(#24095),#24099); -#24095 = LINE('',#24096,#24097); -#24096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24097 = VECTOR('',#24098,1.); -#24098 = DIRECTION('',(0.E+000,-1.)); -#24099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24100 = ORIENTED_EDGE('',*,*,#24101,.F.); -#24101 = EDGE_CURVE('',#24102,#24074,#24104,.T.); -#24102 = VERTEX_POINT('',#24103); -#24103 = CARTESIAN_POINT('',(3.,3.255,3.895)); -#24104 = SURFACE_CURVE('',#24105,(#24109,#24116),.PCURVE_S1.); -#24105 = LINE('',#24106,#24107); -#24106 = CARTESIAN_POINT('',(3.,3.255,3.895)); -#24107 = VECTOR('',#24108,1.); -#24108 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24109 = PCURVE('',#22847,#24110); -#24110 = DEFINITIONAL_REPRESENTATION('',(#24111),#24115); -#24111 = LINE('',#24112,#24113); -#24112 = CARTESIAN_POINT('',(-6.,-2.565415624968E-030)); -#24113 = VECTOR('',#24114,1.); -#24114 = DIRECTION('',(4.608958230318E-045,-1.)); -#24115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24116 = PCURVE('',#24117,#24122); -#24117 = PLANE('',#24118); -#24118 = AXIS2_PLACEMENT_3D('',#24119,#24120,#24121); -#24119 = CARTESIAN_POINT('',(3.,3.255,-0.355)); -#24120 = DIRECTION('',(-1.,-7.125597826469E-031,7.18705183704E-015)); -#24121 = DIRECTION('',(7.18705183704E-015,-3.491483361109E-015,1.)); -#24122 = DEFINITIONAL_REPRESENTATION('',(#24123),#24127); -#24123 = LINE('',#24124,#24125); -#24124 = CARTESIAN_POINT('',(4.25,1.838603596628E-016)); -#24125 = VECTOR('',#24126,1.); -#24126 = DIRECTION('',(-1.752268792537E-043,-1.)); -#24127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24128 = ORIENTED_EDGE('',*,*,#24129,.F.); -#24129 = EDGE_CURVE('',#24130,#24102,#24132,.T.); -#24130 = VERTEX_POINT('',#24131); -#24131 = CARTESIAN_POINT('',(-3.,3.255,3.895)); -#24132 = SURFACE_CURVE('',#24133,(#24137,#24144),.PCURVE_S1.); -#24133 = LINE('',#24134,#24135); -#24134 = CARTESIAN_POINT('',(-3.,3.255,3.895)); -#24135 = VECTOR('',#24136,1.); -#24136 = DIRECTION('',(1.,5.047298460416E-031,-7.127527011883E-015)); -#24137 = PCURVE('',#22847,#24138); -#24138 = DEFINITIONAL_REPRESENTATION('',(#24139),#24143); -#24139 = LINE('',#24140,#24141); -#24140 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24141 = VECTOR('',#24142,1.); -#24142 = DIRECTION('',(-1.,-6.51384833026E-045)); -#24143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24144 = PCURVE('',#24145,#24150); -#24145 = PLANE('',#24146); -#24146 = AXIS2_PLACEMENT_3D('',#24147,#24148,#24149); -#24147 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); -#24148 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24149 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); -#24150 = DEFINITIONAL_REPRESENTATION('',(#24151),#24155); -#24151 = LINE('',#24152,#24153); -#24152 = CARTESIAN_POINT('',(-3.677207193256E-016,4.25)); -#24153 = VECTOR('',#24154,1.); -#24154 = DIRECTION('',(1.,-1.445602896647E-016)); -#24155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24156 = ORIENTED_EDGE('',*,*,#24157,.T.); -#24157 = EDGE_CURVE('',#24130,#23850,#24158,.T.); -#24158 = SURFACE_CURVE('',#24159,(#24163,#24170),.PCURVE_S1.); -#24159 = LINE('',#24160,#24161); -#24160 = CARTESIAN_POINT('',(-3.,3.255,3.895)); -#24161 = VECTOR('',#24162,1.); -#24162 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24163 = PCURVE('',#22847,#24164); -#24164 = DEFINITIONAL_REPRESENTATION('',(#24165),#24169); -#24165 = LINE('',#24166,#24167); -#24166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24167 = VECTOR('',#24168,1.); -#24168 = DIRECTION('',(4.608958230318E-045,-1.)); -#24169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24170 = PCURVE('',#24171,#24176); -#24171 = PLANE('',#24172); -#24172 = AXIS2_PLACEMENT_3D('',#24173,#24174,#24175); -#24173 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); -#24174 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24175 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24176 = DEFINITIONAL_REPRESENTATION('',(#24177),#24181); -#24177 = LINE('',#24178,#24179); -#24178 = CARTESIAN_POINT('',(1.838603596628E-016,4.25)); -#24179 = VECTOR('',#24180,1.); -#24180 = DIRECTION('',(-1.,-1.702510980039E-043)); -#24181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24182 = FACE_BOUND('',#24183,.T.); -#24183 = EDGE_LOOP('',(#24184,#24214,#24235,#24236,#24237,#24238,#24261, - #24289,#24310,#24311,#24312,#24313)); -#24184 = ORIENTED_EDGE('',*,*,#24185,.F.); -#24185 = EDGE_CURVE('',#24186,#24188,#24190,.T.); -#24186 = VERTEX_POINT('',#24187); -#24187 = CARTESIAN_POINT('',(-2.55,2.355,3.895)); -#24188 = VERTEX_POINT('',#24189); -#24189 = CARTESIAN_POINT('',(-2.55,1.755,3.895)); -#24190 = SURFACE_CURVE('',#24191,(#24195,#24202),.PCURVE_S1.); -#24191 = LINE('',#24192,#24193); -#24192 = CARTESIAN_POINT('',(-2.55,2.355,3.895)); -#24193 = VECTOR('',#24194,1.); -#24194 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); -#24195 = PCURVE('',#22847,#24196); -#24196 = DEFINITIONAL_REPRESENTATION('',(#24197),#24201); -#24197 = LINE('',#24198,#24199); -#24198 = CARTESIAN_POINT('',(-0.45,-0.9)); -#24199 = VECTOR('',#24200,1.); -#24200 = DIRECTION('',(-1.445602896647E-015,-1.)); -#24201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24202 = PCURVE('',#24203,#24208); -#24203 = PLANE('',#24204); -#24204 = AXIS2_PLACEMENT_3D('',#24205,#24206,#24207); -#24205 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); -#24206 = DIRECTION('',(-1.,-1.445602896647E-015,7.085009279629E-015)); -#24207 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); -#24208 = DEFINITIONAL_REPRESENTATION('',(#24209),#24213); -#24209 = LINE('',#24210,#24211); -#24210 = CARTESIAN_POINT('',(5.813492048867E-017,2.4)); -#24211 = VECTOR('',#24212,1.); -#24212 = DIRECTION('',(1.,-1.308183046813E-032)); -#24213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24214 = ORIENTED_EDGE('',*,*,#24215,.F.); -#24215 = EDGE_CURVE('',#23606,#24186,#24216,.T.); -#24216 = SURFACE_CURVE('',#24217,(#24221,#24228),.PCURVE_S1.); -#24217 = LINE('',#24218,#24219); -#24218 = CARTESIAN_POINT('',(-2.2,2.355,3.895)); -#24219 = VECTOR('',#24220,1.); -#24220 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24221 = PCURVE('',#22847,#24222); -#24222 = DEFINITIONAL_REPRESENTATION('',(#24223),#24227); -#24223 = LINE('',#24224,#24225); -#24224 = CARTESIAN_POINT('',(-0.8,-0.9)); -#24225 = VECTOR('',#24226,1.); -#24226 = DIRECTION('',(1.,2.835439861407E-045)); -#24227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24228 = PCURVE('',#23644,#24229); -#24229 = DEFINITIONAL_REPRESENTATION('',(#24230),#24234); -#24230 = LINE('',#24231,#24232); -#24231 = CARTESIAN_POINT('',(-1.162698409773E-016,2.4)); -#24232 = VECTOR('',#24233,1.); -#24233 = DIRECTION('',(1.,0.E+000)); -#24234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24235 = ORIENTED_EDGE('',*,*,#23605,.F.); -#24236 = ORIENTED_EDGE('',*,*,#22829,.F.); -#24237 = ORIENTED_EDGE('',*,*,#23039,.F.); -#24238 = ORIENTED_EDGE('',*,*,#24239,.F.); -#24239 = EDGE_CURVE('',#24240,#23012,#24242,.T.); -#24240 = VERTEX_POINT('',#24241); -#24241 = CARTESIAN_POINT('',(2.55,2.355,3.895)); -#24242 = SURFACE_CURVE('',#24243,(#24247,#24254),.PCURVE_S1.); -#24243 = LINE('',#24244,#24245); -#24244 = CARTESIAN_POINT('',(2.2,2.355,3.895)); -#24245 = VECTOR('',#24246,1.); -#24246 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24247 = PCURVE('',#22847,#24248); -#24248 = DEFINITIONAL_REPRESENTATION('',(#24249),#24253); -#24249 = LINE('',#24250,#24251); -#24250 = CARTESIAN_POINT('',(-5.2,-0.9)); -#24251 = VECTOR('',#24252,1.); -#24252 = DIRECTION('',(1.,2.835439861407E-045)); -#24253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24254 = PCURVE('',#23027,#24255); -#24255 = DEFINITIONAL_REPRESENTATION('',(#24256),#24260); -#24256 = LINE('',#24257,#24258); -#24257 = CARTESIAN_POINT('',(-1.162698409773E-016,2.4)); -#24258 = VECTOR('',#24259,1.); -#24259 = DIRECTION('',(1.,0.E+000)); -#24260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24261 = ORIENTED_EDGE('',*,*,#24262,.F.); -#24262 = EDGE_CURVE('',#24263,#24240,#24265,.T.); -#24263 = VERTEX_POINT('',#24264); -#24264 = CARTESIAN_POINT('',(2.55,1.755,3.895)); -#24265 = SURFACE_CURVE('',#24266,(#24270,#24277),.PCURVE_S1.); -#24266 = LINE('',#24267,#24268); -#24267 = CARTESIAN_POINT('',(2.55,2.355,3.895)); -#24268 = VECTOR('',#24269,1.); -#24269 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24270 = PCURVE('',#22847,#24271); -#24271 = DEFINITIONAL_REPRESENTATION('',(#24272),#24276); -#24272 = LINE('',#24273,#24274); -#24273 = CARTESIAN_POINT('',(-5.55,-0.9)); -#24274 = VECTOR('',#24275,1.); -#24275 = DIRECTION('',(-4.608958230318E-045,1.)); -#24276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24277 = PCURVE('',#24278,#24283); -#24278 = PLANE('',#24279); -#24279 = AXIS2_PLACEMENT_3D('',#24280,#24281,#24282); -#24280 = CARTESIAN_POINT('',(2.55,2.355,1.495)); -#24281 = DIRECTION('',(1.,3.562798913235E-031,-7.085009279629E-015)); -#24282 = DIRECTION('',(-7.085009279629E-015,3.491483361109E-015,-1.)); -#24283 = DEFINITIONAL_REPRESENTATION('',(#24284),#24288); -#24284 = LINE('',#24285,#24286); -#24285 = CARTESIAN_POINT('',(-2.4,-5.813492048867E-017)); -#24286 = VECTOR('',#24287,1.); -#24287 = DIRECTION('',(-1.727389886288E-043,1.)); -#24288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24289 = ORIENTED_EDGE('',*,*,#24290,.F.); -#24290 = EDGE_CURVE('',#23086,#24263,#24291,.T.); -#24291 = SURFACE_CURVE('',#24292,(#24296,#24303),.PCURVE_S1.); -#24292 = LINE('',#24293,#24294); -#24293 = CARTESIAN_POINT('',(2.2,1.755,3.895)); -#24294 = VECTOR('',#24295,1.); -#24295 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24296 = PCURVE('',#22847,#24297); -#24297 = DEFINITIONAL_REPRESENTATION('',(#24298),#24302); -#24298 = LINE('',#24299,#24300); -#24299 = CARTESIAN_POINT('',(-5.2,-1.5)); -#24300 = VECTOR('',#24301,1.); -#24301 = DIRECTION('',(-1.,-2.835439861407E-045)); -#24302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24303 = PCURVE('',#23122,#24304); -#24304 = DEFINITIONAL_REPRESENTATION('',(#24305),#24309); -#24305 = LINE('',#24306,#24307); -#24306 = CARTESIAN_POINT('',(1.162698409773E-016,2.4)); -#24307 = VECTOR('',#24308,1.); -#24308 = DIRECTION('',(1.,0.E+000)); -#24309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24310 = ORIENTED_EDGE('',*,*,#23085,.F.); -#24311 = ORIENTED_EDGE('',*,*,#23289,.F.); -#24312 = ORIENTED_EDGE('',*,*,#23712,.F.); -#24313 = ORIENTED_EDGE('',*,*,#24314,.F.); -#24314 = EDGE_CURVE('',#24188,#23685,#24315,.T.); -#24315 = SURFACE_CURVE('',#24316,(#24320,#24327),.PCURVE_S1.); -#24316 = LINE('',#24317,#24318); -#24317 = CARTESIAN_POINT('',(-2.2,1.755,3.895)); -#24318 = VECTOR('',#24319,1.); -#24319 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); -#24320 = PCURVE('',#22847,#24321); -#24321 = DEFINITIONAL_REPRESENTATION('',(#24322),#24326); -#24322 = LINE('',#24323,#24324); -#24323 = CARTESIAN_POINT('',(-0.8,-1.5)); -#24324 = VECTOR('',#24325,1.); -#24325 = DIRECTION('',(-1.,6.195440985631E-016)); -#24326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24327 = PCURVE('',#23700,#24328); -#24328 = DEFINITIONAL_REPRESENTATION('',(#24329),#24333); -#24329 = LINE('',#24330,#24331); -#24330 = CARTESIAN_POINT('',(1.162698409773E-016,2.4)); -#24331 = VECTOR('',#24332,1.); -#24332 = DIRECTION('',(1.,2.033782021273E-031)); -#24333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24334 = ADVANCED_FACE('',(#24335),#22966,.F.); -#24335 = FACE_BOUND('',#24336,.T.); -#24336 = EDGE_LOOP('',(#24337,#24338,#24339,#24340)); -#24337 = ORIENTED_EDGE('',*,*,#22952,.T.); -#24338 = ORIENTED_EDGE('',*,*,#23742,.F.); -#24339 = ORIENTED_EDGE('',*,*,#23411,.F.); -#24340 = ORIENTED_EDGE('',*,*,#23794,.T.); -#24341 = ADVANCED_FACE('',(#24342),#22999,.T.); -#24342 = FACE_BOUND('',#24343,.T.); -#24343 = EDGE_LOOP('',(#24344,#24345,#24368,#24391)); -#24344 = ORIENTED_EDGE('',*,*,#22981,.T.); -#24345 = ORIENTED_EDGE('',*,*,#24346,.T.); -#24346 = EDGE_CURVE('',#22984,#24347,#24349,.T.); -#24347 = VERTEX_POINT('',#24348); -#24348 = CARTESIAN_POINT('',(2.55,1.755,1.495)); -#24349 = SURFACE_CURVE('',#24350,(#24354,#24361),.PCURVE_S1.); -#24350 = LINE('',#24351,#24352); -#24351 = CARTESIAN_POINT('',(2.2,1.755,1.495)); -#24352 = VECTOR('',#24353,1.); -#24353 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#24354 = PCURVE('',#22999,#24355); -#24355 = DEFINITIONAL_REPRESENTATION('',(#24356),#24360); -#24356 = LINE('',#24357,#24358); -#24357 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24358 = VECTOR('',#24359,1.); -#24359 = DIRECTION('',(2.80259692865E-045,-1.)); -#24360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24361 = PCURVE('',#23122,#24362); -#24362 = DEFINITIONAL_REPRESENTATION('',(#24363),#24367); -#24363 = LINE('',#24364,#24365); -#24364 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24365 = VECTOR('',#24366,1.); -#24366 = DIRECTION('',(1.,0.E+000)); -#24367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24368 = ORIENTED_EDGE('',*,*,#24369,.T.); -#24369 = EDGE_CURVE('',#24347,#24370,#24372,.T.); -#24370 = VERTEX_POINT('',#24371); -#24371 = CARTESIAN_POINT('',(2.55,2.355,1.495)); -#24372 = SURFACE_CURVE('',#24373,(#24377,#24384),.PCURVE_S1.); -#24373 = LINE('',#24374,#24375); -#24374 = CARTESIAN_POINT('',(2.55,2.355,1.495)); -#24375 = VECTOR('',#24376,1.); -#24376 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24377 = PCURVE('',#22999,#24378); -#24378 = DEFINITIONAL_REPRESENTATION('',(#24379),#24383); -#24379 = LINE('',#24380,#24381); -#24380 = CARTESIAN_POINT('',(0.6,-0.35)); -#24381 = VECTOR('',#24382,1.); -#24382 = DIRECTION('',(1.,0.E+000)); -#24383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24384 = PCURVE('',#24278,#24385); -#24385 = DEFINITIONAL_REPRESENTATION('',(#24386),#24390); -#24386 = LINE('',#24387,#24388); -#24387 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24388 = VECTOR('',#24389,1.); -#24389 = DIRECTION('',(-1.727389886288E-043,1.)); -#24390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24391 = ORIENTED_EDGE('',*,*,#24392,.T.); -#24392 = EDGE_CURVE('',#24370,#22982,#24393,.T.); -#24393 = SURFACE_CURVE('',#24394,(#24398,#24405),.PCURVE_S1.); -#24394 = LINE('',#24395,#24396); -#24395 = CARTESIAN_POINT('',(2.2,2.355,1.495)); -#24396 = VECTOR('',#24397,1.); -#24397 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24398 = PCURVE('',#22999,#24399); -#24399 = DEFINITIONAL_REPRESENTATION('',(#24400),#24404); -#24400 = LINE('',#24401,#24402); -#24401 = CARTESIAN_POINT('',(0.6,1.395477078336E-029)); -#24402 = VECTOR('',#24403,1.); -#24403 = DIRECTION('',(-2.80259692865E-045,1.)); -#24404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24405 = PCURVE('',#23027,#24406); -#24406 = DEFINITIONAL_REPRESENTATION('',(#24407),#24411); -#24407 = LINE('',#24408,#24409); -#24408 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24409 = VECTOR('',#24410,1.); -#24410 = DIRECTION('',(1.,0.E+000)); -#24411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24412 = ADVANCED_FACE('',(#24413),#23122,.F.); -#24413 = FACE_BOUND('',#24414,.T.); -#24414 = EDGE_LOOP('',(#24415,#24416,#24437,#24438)); -#24415 = ORIENTED_EDGE('',*,*,#24290,.T.); -#24416 = ORIENTED_EDGE('',*,*,#24417,.F.); -#24417 = EDGE_CURVE('',#24347,#24263,#24418,.T.); -#24418 = SURFACE_CURVE('',#24419,(#24423,#24430),.PCURVE_S1.); -#24419 = LINE('',#24420,#24421); -#24420 = CARTESIAN_POINT('',(2.55,1.755,1.495)); -#24421 = VECTOR('',#24422,1.); -#24422 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#24423 = PCURVE('',#23122,#24424); -#24424 = DEFINITIONAL_REPRESENTATION('',(#24425),#24429); -#24425 = LINE('',#24426,#24427); -#24426 = CARTESIAN_POINT('',(0.35,1.547698601221E-018)); -#24427 = VECTOR('',#24428,1.); -#24428 = DIRECTION('',(1.020425574104E-016,1.)); -#24429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24430 = PCURVE('',#24278,#24431); -#24431 = DEFINITIONAL_REPRESENTATION('',(#24432),#24436); -#24432 = LINE('',#24433,#24434); -#24433 = CARTESIAN_POINT('',(-9.648857234035E-017,-0.6)); -#24434 = VECTOR('',#24435,1.); -#24435 = DIRECTION('',(-1.,1.727389886288E-043)); -#24436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24437 = ORIENTED_EDGE('',*,*,#24346,.F.); -#24438 = ORIENTED_EDGE('',*,*,#23108,.T.); -#24439 = ADVANCED_FACE('',(#24440),#23027,.F.); -#24440 = FACE_BOUND('',#24441,.T.); -#24441 = EDGE_LOOP('',(#24442,#24443,#24444,#24445)); -#24442 = ORIENTED_EDGE('',*,*,#24239,.T.); -#24443 = ORIENTED_EDGE('',*,*,#23011,.F.); -#24444 = ORIENTED_EDGE('',*,*,#24392,.F.); -#24445 = ORIENTED_EDGE('',*,*,#24446,.T.); -#24446 = EDGE_CURVE('',#24370,#24240,#24447,.T.); -#24447 = SURFACE_CURVE('',#24448,(#24452,#24459),.PCURVE_S1.); -#24448 = LINE('',#24449,#24450); -#24449 = CARTESIAN_POINT('',(2.55,2.355,1.495)); -#24450 = VECTOR('',#24451,1.); -#24451 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#24452 = PCURVE('',#23027,#24453); +#24447 = PCURVE('',#24448,#24453); +#24448 = PLANE('',#24449); +#24449 = AXIS2_PLACEMENT_3D('',#24450,#24451,#24452); +#24450 = CARTESIAN_POINT('',(1.6,0.445,0.195)); +#24451 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24452 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); #24453 = DEFINITIONAL_REPRESENTATION('',(#24454),#24458); #24454 = LINE('',#24455,#24456); -#24455 = CARTESIAN_POINT('',(-0.35,1.547698601221E-018)); +#24455 = CARTESIAN_POINT('',(-1.64,2.45)); #24456 = VECTOR('',#24457,1.); -#24457 = DIRECTION('',(-1.020425574104E-016,1.)); +#24457 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); #24458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#24459 = PCURVE('',#24278,#24460); -#24460 = DEFINITIONAL_REPRESENTATION('',(#24461),#24465); -#24461 = LINE('',#24462,#24463); -#24462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24463 = VECTOR('',#24464,1.); -#24464 = DIRECTION('',(-1.,1.727389886288E-043)); -#24465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24466 = ADVANCED_FACE('',(#24467),#23198,.F.); -#24467 = FACE_BOUND('',#24468,.T.); -#24468 = EDGE_LOOP('',(#24469,#24470,#24471,#24472)); -#24469 = ORIENTED_EDGE('',*,*,#23554,.T.); -#24470 = ORIENTED_EDGE('',*,*,#23184,.F.); -#24471 = ORIENTED_EDGE('',*,*,#23362,.F.); -#24472 = ORIENTED_EDGE('',*,*,#23821,.T.); -#24473 = ADVANCED_FACE('',(#24474),#23252,.F.); -#24474 = FACE_BOUND('',#24475,.T.); -#24475 = EDGE_LOOP('',(#24476,#24477,#24478,#24479)); -#24476 = ORIENTED_EDGE('',*,*,#23769,.T.); -#24477 = ORIENTED_EDGE('',*,*,#23505,.F.); -#24478 = ORIENTED_EDGE('',*,*,#23580,.F.); -#24479 = ORIENTED_EDGE('',*,*,#23236,.T.); -#24480 = ADVANCED_FACE('',(#24481),#23672,.T.); -#24481 = FACE_BOUND('',#24482,.T.); -#24482 = EDGE_LOOP('',(#24483,#24506,#24529,#24550)); -#24483 = ORIENTED_EDGE('',*,*,#24484,.T.); -#24484 = EDGE_CURVE('',#23629,#24485,#24487,.T.); -#24485 = VERTEX_POINT('',#24486); -#24486 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); -#24487 = SURFACE_CURVE('',#24488,(#24492,#24499),.PCURVE_S1.); -#24488 = LINE('',#24489,#24490); -#24489 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); -#24490 = VECTOR('',#24491,1.); -#24491 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24492 = PCURVE('',#23672,#24493); +#24459 = PCURVE('',#24460,#24465); +#24460 = PLANE('',#24461); +#24461 = AXIS2_PLACEMENT_3D('',#24462,#24463,#24464); +#24462 = CARTESIAN_POINT('',(1.4,2.085,2.645)); +#24463 = DIRECTION('',(-5.173092832126E-016,0.997252183706, + -7.408159078957E-002)); +#24464 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, + -0.997252183706)); +#24465 = DEFINITIONAL_REPRESENTATION('',(#24466),#24470); +#24466 = LINE('',#24467,#24468); +#24467 = CARTESIAN_POINT('',(-6.414895964605E-017,-0.2)); +#24468 = VECTOR('',#24469,1.); +#24469 = DIRECTION('',(-1.,4.74549138297E-031)); +#24470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24471 = ORIENTED_EDGE('',*,*,#24472,.T.); +#24472 = EDGE_CURVE('',#24438,#24473,#24475,.T.); +#24473 = VERTEX_POINT('',#24474); +#24474 = CARTESIAN_POINT('',(1.6,2.435,0.895)); +#24475 = SURFACE_CURVE('',#24476,(#24480,#24487),.PCURVE_S1.); +#24476 = LINE('',#24477,#24478); +#24477 = CARTESIAN_POINT('',(1.6,0.755,0.895)); +#24478 = VECTOR('',#24479,1.); +#24479 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24480 = PCURVE('',#24448,#24481); +#24481 = DEFINITIONAL_REPRESENTATION('',(#24482),#24486); +#24482 = LINE('',#24483,#24484); +#24483 = CARTESIAN_POINT('',(-0.31,0.7)); +#24484 = VECTOR('',#24485,1.); +#24485 = DIRECTION('',(-1.,1.702510980039E-043)); +#24486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24487 = PCURVE('',#24488,#24493); +#24488 = PLANE('',#24489); +#24489 = AXIS2_PLACEMENT_3D('',#24490,#24491,#24492); +#24490 = CARTESIAN_POINT('',(2.2,0.755,0.895)); +#24491 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#24492 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); #24493 = DEFINITIONAL_REPRESENTATION('',(#24494),#24498); #24494 = LINE('',#24495,#24496); -#24495 = CARTESIAN_POINT('',(5.403763914175E-033,-0.35)); +#24495 = CARTESIAN_POINT('',(-1.014885537928E-031,0.6)); #24496 = VECTOR('',#24497,1.); -#24497 = DIRECTION('',(-2.80259692865E-045,1.)); +#24497 = DIRECTION('',(-1.,0.E+000)); #24498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#24499 = PCURVE('',#23644,#24500); -#24500 = DEFINITIONAL_REPRESENTATION('',(#24501),#24505); -#24501 = LINE('',#24502,#24503); -#24502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24503 = VECTOR('',#24504,1.); -#24504 = DIRECTION('',(1.,0.E+000)); -#24505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24506 = ORIENTED_EDGE('',*,*,#24507,.T.); -#24507 = EDGE_CURVE('',#24485,#24508,#24510,.T.); -#24508 = VERTEX_POINT('',#24509); -#24509 = CARTESIAN_POINT('',(-2.55,1.755,1.495)); -#24510 = SURFACE_CURVE('',#24511,(#24515,#24522),.PCURVE_S1.); -#24511 = LINE('',#24512,#24513); -#24512 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); -#24513 = VECTOR('',#24514,1.); -#24514 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); -#24515 = PCURVE('',#23672,#24516); -#24516 = DEFINITIONAL_REPRESENTATION('',(#24517),#24521); -#24517 = LINE('',#24518,#24519); -#24518 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24519 = VECTOR('',#24520,1.); -#24520 = DIRECTION('',(-1.,-1.445602896647E-015)); -#24521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24522 = PCURVE('',#24203,#24523); -#24523 = DEFINITIONAL_REPRESENTATION('',(#24524),#24528); -#24524 = LINE('',#24525,#24526); -#24525 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24526 = VECTOR('',#24527,1.); -#24527 = DIRECTION('',(1.,-1.308183046813E-032)); -#24528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24529 = ORIENTED_EDGE('',*,*,#24530,.T.); -#24530 = EDGE_CURVE('',#24508,#23657,#24531,.T.); -#24531 = SURFACE_CURVE('',#24532,(#24536,#24543),.PCURVE_S1.); -#24532 = LINE('',#24533,#24534); -#24533 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); -#24534 = VECTOR('',#24535,1.); -#24535 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); -#24536 = PCURVE('',#23672,#24537); -#24537 = DEFINITIONAL_REPRESENTATION('',(#24538),#24542); -#24538 = LINE('',#24539,#24540); -#24539 = CARTESIAN_POINT('',(-0.6,-0.35)); -#24540 = VECTOR('',#24541,1.); -#24541 = DIRECTION('',(6.195440985631E-016,-1.)); -#24542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24543 = PCURVE('',#23700,#24544); -#24544 = DEFINITIONAL_REPRESENTATION('',(#24545),#24549); -#24545 = LINE('',#24546,#24547); -#24546 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24547 = VECTOR('',#24548,1.); -#24548 = DIRECTION('',(1.,2.033782021273E-031)); -#24549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24550 = ORIENTED_EDGE('',*,*,#23656,.T.); -#24551 = ADVANCED_FACE('',(#24552),#23700,.F.); -#24552 = FACE_BOUND('',#24553,.T.); -#24553 = EDGE_LOOP('',(#24554,#24555,#24556,#24557)); -#24554 = ORIENTED_EDGE('',*,*,#24314,.T.); -#24555 = ORIENTED_EDGE('',*,*,#23684,.F.); -#24556 = ORIENTED_EDGE('',*,*,#24530,.F.); +#24499 = ORIENTED_EDGE('',*,*,#24500,.F.); +#24500 = EDGE_CURVE('',#24501,#24473,#24503,.T.); +#24501 = VERTEX_POINT('',#24502); +#24502 = CARTESIAN_POINT('',(1.6,2.435,2.645)); +#24503 = SURFACE_CURVE('',#24504,(#24508,#24515),.PCURVE_S1.); +#24504 = LINE('',#24505,#24506); +#24505 = CARTESIAN_POINT('',(1.6,2.435,2.645)); +#24506 = VECTOR('',#24507,1.); +#24507 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#24508 = PCURVE('',#24448,#24509); +#24509 = DEFINITIONAL_REPRESENTATION('',(#24510),#24514); +#24510 = LINE('',#24511,#24512); +#24511 = CARTESIAN_POINT('',(-1.99,2.45)); +#24512 = VECTOR('',#24513,1.); +#24513 = DIRECTION('',(-1.770125995895E-016,-1.)); +#24514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24515 = PCURVE('',#24516,#24521); +#24516 = PLANE('',#24517); +#24517 = AXIS2_PLACEMENT_3D('',#24518,#24519,#24520); +#24518 = CARTESIAN_POINT('',(1.4,2.435,2.645)); +#24519 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); +#24520 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); +#24521 = DEFINITIONAL_REPRESENTATION('',(#24522),#24526); +#24522 = LINE('',#24523,#24524); +#24523 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); +#24524 = VECTOR('',#24525,1.); +#24525 = DIRECTION('',(-1.,0.E+000)); +#24526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24527 = ORIENTED_EDGE('',*,*,#24528,.F.); +#24528 = EDGE_CURVE('',#24440,#24501,#24529,.T.); +#24529 = SURFACE_CURVE('',#24530,(#24534,#24541),.PCURVE_S1.); +#24530 = LINE('',#24531,#24532); +#24531 = CARTESIAN_POINT('',(1.6,2.435,2.645)); +#24532 = VECTOR('',#24533,1.); +#24533 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24534 = PCURVE('',#24448,#24535); +#24535 = DEFINITIONAL_REPRESENTATION('',(#24536),#24540); +#24536 = LINE('',#24537,#24538); +#24537 = CARTESIAN_POINT('',(-1.99,2.45)); +#24538 = VECTOR('',#24539,1.); +#24539 = DIRECTION('',(-1.,1.702510980039E-043)); +#24540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24541 = PCURVE('',#24542,#24547); +#24542 = PLANE('',#24543); +#24543 = AXIS2_PLACEMENT_3D('',#24544,#24545,#24546); +#24544 = CARTESIAN_POINT('',(1.4,2.435,2.645)); +#24545 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#24546 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24547 = DEFINITIONAL_REPRESENTATION('',(#24548),#24552); +#24548 = LINE('',#24549,#24550); +#24549 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); +#24550 = VECTOR('',#24551,1.); +#24551 = DIRECTION('',(-1.,0.E+000)); +#24552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24553 = ADVANCED_FACE('',(#24554),#24516,.F.); +#24554 = FACE_BOUND('',#24555,.T.); +#24555 = EDGE_LOOP('',(#24556,#24557,#24580,#24608)); +#24556 = ORIENTED_EDGE('',*,*,#24500,.T.); #24557 = ORIENTED_EDGE('',*,*,#24558,.T.); -#24558 = EDGE_CURVE('',#24508,#24188,#24559,.T.); -#24559 = SURFACE_CURVE('',#24560,(#24564,#24571),.PCURVE_S1.); -#24560 = LINE('',#24561,#24562); -#24561 = CARTESIAN_POINT('',(-2.55,1.755,1.495)); -#24562 = VECTOR('',#24563,1.); -#24563 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#24564 = PCURVE('',#23700,#24565); -#24565 = DEFINITIONAL_REPRESENTATION('',(#24566),#24570); -#24566 = LINE('',#24567,#24568); -#24567 = CARTESIAN_POINT('',(-0.35,-1.54769860122E-018)); -#24568 = VECTOR('',#24569,1.); -#24569 = DIRECTION('',(1.020425574104E-016,1.)); -#24570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24571 = PCURVE('',#24203,#24572); -#24572 = DEFINITIONAL_REPRESENTATION('',(#24573),#24577); -#24573 = LINE('',#24574,#24575); -#24574 = CARTESIAN_POINT('',(0.6,3.185331772654E-016)); -#24575 = VECTOR('',#24576,1.); -#24576 = DIRECTION('',(-1.308183046813E-032,1.)); -#24577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24578 = ADVANCED_FACE('',(#24579),#23644,.F.); -#24579 = FACE_BOUND('',#24580,.T.); -#24580 = EDGE_LOOP('',(#24581,#24582,#24603,#24604)); -#24581 = ORIENTED_EDGE('',*,*,#24215,.T.); -#24582 = ORIENTED_EDGE('',*,*,#24583,.F.); -#24583 = EDGE_CURVE('',#24485,#24186,#24584,.T.); +#24558 = EDGE_CURVE('',#24473,#24559,#24561,.T.); +#24559 = VERTEX_POINT('',#24560); +#24560 = CARTESIAN_POINT('',(1.4,2.435,0.895)); +#24561 = SURFACE_CURVE('',#24562,(#24566,#24573),.PCURVE_S1.); +#24562 = LINE('',#24563,#24564); +#24563 = CARTESIAN_POINT('',(2.2,2.435,0.895)); +#24564 = VECTOR('',#24565,1.); +#24565 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24566 = PCURVE('',#24516,#24567); +#24567 = DEFINITIONAL_REPRESENTATION('',(#24568),#24572); +#24568 = LINE('',#24569,#24570); +#24569 = CARTESIAN_POINT('',(-1.75,-0.8)); +#24570 = VECTOR('',#24571,1.); +#24571 = DIRECTION('',(0.E+000,1.)); +#24572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24573 = PCURVE('',#24488,#24574); +#24574 = DEFINITIONAL_REPRESENTATION('',(#24575),#24579); +#24575 = LINE('',#24576,#24577); +#24576 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); +#24577 = VECTOR('',#24578,1.); +#24578 = DIRECTION('',(2.80259692865E-045,1.)); +#24579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24580 = ORIENTED_EDGE('',*,*,#24581,.F.); +#24581 = EDGE_CURVE('',#24582,#24559,#24584,.T.); +#24582 = VERTEX_POINT('',#24583); +#24583 = CARTESIAN_POINT('',(1.4,2.435,2.645)); #24584 = SURFACE_CURVE('',#24585,(#24589,#24596),.PCURVE_S1.); #24585 = LINE('',#24586,#24587); -#24586 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#24586 = CARTESIAN_POINT('',(1.4,2.435,2.645)); #24587 = VECTOR('',#24588,1.); -#24588 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); -#24589 = PCURVE('',#23644,#24590); +#24588 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#24589 = PCURVE('',#24516,#24590); #24590 = DEFINITIONAL_REPRESENTATION('',(#24591),#24595); #24591 = LINE('',#24592,#24593); -#24592 = CARTESIAN_POINT('',(0.35,-2.235923035263E-016)); +#24592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #24593 = VECTOR('',#24594,1.); -#24594 = DIRECTION('',(-1.020425574104E-016,1.)); +#24594 = DIRECTION('',(-1.,0.E+000)); #24595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#24596 = PCURVE('',#24203,#24597); -#24597 = DEFINITIONAL_REPRESENTATION('',(#24598),#24602); -#24598 = LINE('',#24599,#24600); -#24599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24600 = VECTOR('',#24601,1.); -#24601 = DIRECTION('',(-1.308183046813E-032,1.)); -#24602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#24596 = PCURVE('',#24597,#24602); +#24597 = PLANE('',#24598); +#24598 = AXIS2_PLACEMENT_3D('',#24599,#24600,#24601); +#24599 = CARTESIAN_POINT('',(1.4,0.445,0.195)); +#24600 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24601 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24602 = DEFINITIONAL_REPRESENTATION('',(#24603),#24607); +#24603 = LINE('',#24604,#24605); +#24604 = CARTESIAN_POINT('',(-1.99,2.45)); +#24605 = VECTOR('',#24606,1.); +#24606 = DIRECTION('',(-1.770125995895E-016,-1.)); +#24607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#24603 = ORIENTED_EDGE('',*,*,#24484,.F.); -#24604 = ORIENTED_EDGE('',*,*,#23628,.T.); -#24605 = ADVANCED_FACE('',(#24606),#24033,.F.); -#24606 = FACE_BOUND('',#24607,.T.); -#24607 = EDGE_LOOP('',(#24608,#24631,#24659,#24680)); #24608 = ORIENTED_EDGE('',*,*,#24609,.T.); -#24609 = EDGE_CURVE('',#23990,#24610,#24612,.T.); -#24610 = VERTEX_POINT('',#24611); -#24611 = CARTESIAN_POINT('',(2.5,0.305,2.395)); -#24612 = SURFACE_CURVE('',#24613,(#24617,#24624),.PCURVE_S1.); -#24613 = LINE('',#24614,#24615); -#24614 = CARTESIAN_POINT('',(2.5,0.305,3.895)); -#24615 = VECTOR('',#24616,1.); -#24616 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); -#24617 = PCURVE('',#24033,#24618); -#24618 = DEFINITIONAL_REPRESENTATION('',(#24619),#24623); -#24619 = LINE('',#24620,#24621); -#24620 = CARTESIAN_POINT('',(-3.797634949565E-016,0.2)); -#24621 = VECTOR('',#24622,1.); -#24622 = DIRECTION('',(1.,0.E+000)); -#24623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24624 = PCURVE('',#24005,#24625); -#24625 = DEFINITIONAL_REPRESENTATION('',(#24626),#24630); -#24626 = LINE('',#24627,#24628); -#24627 = CARTESIAN_POINT('',(-0.6,1.5)); -#24628 = VECTOR('',#24629,1.); -#24629 = DIRECTION('',(1.219727444046E-016,-1.)); -#24630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24631 = ORIENTED_EDGE('',*,*,#24632,.F.); -#24632 = EDGE_CURVE('',#24633,#24610,#24635,.T.); -#24633 = VERTEX_POINT('',#24634); -#24634 = CARTESIAN_POINT('',(2.7,0.305,2.395)); -#24635 = SURFACE_CURVE('',#24636,(#24640,#24647),.PCURVE_S1.); -#24636 = LINE('',#24637,#24638); -#24637 = CARTESIAN_POINT('',(2.7,0.305,2.395)); -#24638 = VECTOR('',#24639,1.); -#24639 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#24640 = PCURVE('',#24033,#24641); -#24641 = DEFINITIONAL_REPRESENTATION('',(#24642),#24646); -#24642 = LINE('',#24643,#24644); -#24643 = CARTESIAN_POINT('',(1.5,-2.603982567767E-016)); -#24644 = VECTOR('',#24645,1.); -#24645 = DIRECTION('',(0.E+000,1.)); -#24646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24647 = PCURVE('',#24648,#24653); -#24648 = PLANE('',#24649); -#24649 = AXIS2_PLACEMENT_3D('',#24650,#24651,#24652); -#24650 = CARTESIAN_POINT('',(2.7,0.305,2.395)); -#24651 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#24652 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24653 = DEFINITIONAL_REPRESENTATION('',(#24654),#24658); -#24654 = LINE('',#24655,#24656); -#24655 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24656 = VECTOR('',#24657,1.); -#24657 = DIRECTION('',(-2.80259692865E-045,1.)); -#24658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24659 = ORIENTED_EDGE('',*,*,#24660,.F.); -#24660 = EDGE_CURVE('',#24018,#24633,#24661,.T.); -#24661 = SURFACE_CURVE('',#24662,(#24666,#24673),.PCURVE_S1.); -#24662 = LINE('',#24663,#24664); -#24663 = CARTESIAN_POINT('',(2.7,0.305,3.895)); -#24664 = VECTOR('',#24665,1.); -#24665 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); -#24666 = PCURVE('',#24033,#24667); -#24667 = DEFINITIONAL_REPRESENTATION('',(#24668),#24672); -#24668 = LINE('',#24669,#24670); -#24669 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24670 = VECTOR('',#24671,1.); -#24671 = DIRECTION('',(1.,0.E+000)); -#24672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24673 = PCURVE('',#24061,#24674); -#24674 = DEFINITIONAL_REPRESENTATION('',(#24675),#24679); -#24675 = LINE('',#24676,#24677); -#24676 = CARTESIAN_POINT('',(-0.6,1.5)); -#24677 = VECTOR('',#24678,1.); -#24678 = DIRECTION('',(1.219727444046E-016,-1.)); -#24679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24680 = ORIENTED_EDGE('',*,*,#24017,.T.); -#24681 = ADVANCED_FACE('',(#24682),#24203,.F.); -#24682 = FACE_BOUND('',#24683,.T.); -#24683 = EDGE_LOOP('',(#24684,#24685,#24686,#24687)); -#24684 = ORIENTED_EDGE('',*,*,#24185,.T.); -#24685 = ORIENTED_EDGE('',*,*,#24558,.F.); -#24686 = ORIENTED_EDGE('',*,*,#24507,.F.); -#24687 = ORIENTED_EDGE('',*,*,#24583,.T.); -#24688 = ADVANCED_FACE('',(#24689),#23949,.F.); -#24689 = FACE_BOUND('',#24690,.T.); -#24690 = EDGE_LOOP('',(#24691,#24714,#24715,#24738)); -#24691 = ORIENTED_EDGE('',*,*,#24692,.F.); -#24692 = EDGE_CURVE('',#23934,#24693,#24695,.T.); -#24693 = VERTEX_POINT('',#24694); -#24694 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); -#24695 = SURFACE_CURVE('',#24696,(#24700,#24707),.PCURVE_S1.); -#24696 = LINE('',#24697,#24698); -#24697 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); -#24698 = VECTOR('',#24699,1.); -#24699 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#24700 = PCURVE('',#23949,#24701); -#24701 = DEFINITIONAL_REPRESENTATION('',(#24702),#24706); -#24702 = LINE('',#24703,#24704); -#24703 = CARTESIAN_POINT('',(-0.55,3.001302006402E-016)); -#24704 = VECTOR('',#24705,1.); -#24705 = DIRECTION('',(-1.702510980039E-043,1.)); -#24706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24707 = PCURVE('',#23977,#24708); -#24708 = DEFINITIONAL_REPRESENTATION('',(#24709),#24713); -#24709 = LINE('',#24710,#24711); -#24710 = CARTESIAN_POINT('',(0.5,2.75)); -#24711 = VECTOR('',#24712,1.); -#24712 = DIRECTION('',(0.E+000,-1.)); -#24713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24714 = ORIENTED_EDGE('',*,*,#23933,.T.); -#24715 = ORIENTED_EDGE('',*,*,#24716,.T.); -#24716 = EDGE_CURVE('',#23906,#24717,#24719,.T.); -#24717 = VERTEX_POINT('',#24718); -#24718 = CARTESIAN_POINT('',(-2.5,0.305,2.395)); -#24719 = SURFACE_CURVE('',#24720,(#24724,#24731),.PCURVE_S1.); -#24720 = LINE('',#24721,#24722); -#24721 = CARTESIAN_POINT('',(-2.5,0.305,3.895)); -#24722 = VECTOR('',#24723,1.); -#24723 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); -#24724 = PCURVE('',#23949,#24725); -#24725 = DEFINITIONAL_REPRESENTATION('',(#24726),#24730); -#24726 = LINE('',#24727,#24728); -#24727 = CARTESIAN_POINT('',(-0.6,-1.5)); -#24728 = VECTOR('',#24729,1.); -#24729 = DIRECTION('',(1.219727444046E-016,1.)); -#24730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24731 = PCURVE('',#23921,#24732); +#24609 = EDGE_CURVE('',#24582,#24501,#24610,.T.); +#24610 = SURFACE_CURVE('',#24611,(#24615,#24622),.PCURVE_S1.); +#24611 = LINE('',#24612,#24613); +#24612 = CARTESIAN_POINT('',(1.4,2.435,2.645)); +#24613 = VECTOR('',#24614,1.); +#24614 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#24615 = PCURVE('',#24516,#24616); +#24616 = DEFINITIONAL_REPRESENTATION('',(#24617),#24621); +#24617 = LINE('',#24618,#24619); +#24618 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#24619 = VECTOR('',#24620,1.); +#24620 = DIRECTION('',(0.E+000,-1.)); +#24621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24622 = PCURVE('',#24542,#24623); +#24623 = DEFINITIONAL_REPRESENTATION('',(#24624),#24628); +#24624 = LINE('',#24625,#24626); +#24625 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#24626 = VECTOR('',#24627,1.); +#24627 = DIRECTION('',(-2.80259692865E-045,-1.)); +#24628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24629 = ADVANCED_FACE('',(#24630,#24678,#24792,#24906,#25020),#24488, + .F.); +#24630 = FACE_BOUND('',#24631,.T.); +#24631 = EDGE_LOOP('',(#24632,#24655,#24676,#24677)); +#24632 = ORIENTED_EDGE('',*,*,#24633,.F.); +#24633 = EDGE_CURVE('',#24634,#24438,#24636,.T.); +#24634 = VERTEX_POINT('',#24635); +#24635 = CARTESIAN_POINT('',(1.4,1.955,0.895)); +#24636 = SURFACE_CURVE('',#24637,(#24641,#24648),.PCURVE_S1.); +#24637 = LINE('',#24638,#24639); +#24638 = CARTESIAN_POINT('',(1.4,1.955,0.895)); +#24639 = VECTOR('',#24640,1.); +#24640 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#24641 = PCURVE('',#24488,#24642); +#24642 = DEFINITIONAL_REPRESENTATION('',(#24643),#24647); +#24643 = LINE('',#24644,#24645); +#24644 = CARTESIAN_POINT('',(-1.2,0.8)); +#24645 = VECTOR('',#24646,1.); +#24646 = DIRECTION('',(-2.80259692865E-045,-1.)); +#24647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24648 = PCURVE('',#24460,#24649); +#24649 = DEFINITIONAL_REPRESENTATION('',(#24650),#24654); +#24650 = LINE('',#24651,#24652); +#24651 = CARTESIAN_POINT('',(1.754821928288,-7.738493006118E-018)); +#24652 = VECTOR('',#24653,1.); +#24653 = DIRECTION('',(-1.109335647967E-030,-1.)); +#24654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24655 = ORIENTED_EDGE('',*,*,#24656,.T.); +#24656 = EDGE_CURVE('',#24634,#24559,#24657,.T.); +#24657 = SURFACE_CURVE('',#24658,(#24662,#24669),.PCURVE_S1.); +#24658 = LINE('',#24659,#24660); +#24659 = CARTESIAN_POINT('',(1.4,0.755,0.895)); +#24660 = VECTOR('',#24661,1.); +#24661 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24662 = PCURVE('',#24488,#24663); +#24663 = DEFINITIONAL_REPRESENTATION('',(#24664),#24668); +#24664 = LINE('',#24665,#24666); +#24665 = CARTESIAN_POINT('',(1.231036094495E-031,0.8)); +#24666 = VECTOR('',#24667,1.); +#24667 = DIRECTION('',(-1.,0.E+000)); +#24668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24669 = PCURVE('',#24597,#24670); +#24670 = DEFINITIONAL_REPRESENTATION('',(#24671),#24675); +#24671 = LINE('',#24672,#24673); +#24672 = CARTESIAN_POINT('',(-0.31,0.7)); +#24673 = VECTOR('',#24674,1.); +#24674 = DIRECTION('',(-1.,1.702510980039E-043)); +#24675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24676 = ORIENTED_EDGE('',*,*,#24558,.F.); +#24677 = ORIENTED_EDGE('',*,*,#24472,.F.); +#24678 = FACE_BOUND('',#24679,.T.); +#24679 = EDGE_LOOP('',(#24680,#24710,#24738,#24766)); +#24680 = ORIENTED_EDGE('',*,*,#24681,.F.); +#24681 = EDGE_CURVE('',#24682,#24684,#24686,.T.); +#24682 = VERTEX_POINT('',#24683); +#24683 = CARTESIAN_POINT('',(0.4,1.955,0.895)); +#24684 = VERTEX_POINT('',#24685); +#24685 = CARTESIAN_POINT('',(0.6,1.955,0.895)); +#24686 = SURFACE_CURVE('',#24687,(#24691,#24698),.PCURVE_S1.); +#24687 = LINE('',#24688,#24689); +#24688 = CARTESIAN_POINT('',(0.4,1.955,0.895)); +#24689 = VECTOR('',#24690,1.); +#24690 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#24691 = PCURVE('',#24488,#24692); +#24692 = DEFINITIONAL_REPRESENTATION('',(#24693),#24697); +#24693 = LINE('',#24694,#24695); +#24694 = CARTESIAN_POINT('',(-1.2,1.8)); +#24695 = VECTOR('',#24696,1.); +#24696 = DIRECTION('',(-2.80259692865E-045,-1.)); +#24697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24698 = PCURVE('',#24699,#24704); +#24699 = PLANE('',#24700); +#24700 = AXIS2_PLACEMENT_3D('',#24701,#24702,#24703); +#24701 = CARTESIAN_POINT('',(0.4,2.085,2.645)); +#24702 = DIRECTION('',(-5.173092832126E-016,0.997252183706, + -7.408159078957E-002)); +#24703 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, + -0.997252183706)); +#24704 = DEFINITIONAL_REPRESENTATION('',(#24705),#24709); +#24705 = LINE('',#24706,#24707); +#24706 = CARTESIAN_POINT('',(1.754821928288,-6.324964423738E-017)); +#24707 = VECTOR('',#24708,1.); +#24708 = DIRECTION('',(-1.109335647967E-030,-1.)); +#24709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24710 = ORIENTED_EDGE('',*,*,#24711,.T.); +#24711 = EDGE_CURVE('',#24682,#24712,#24714,.T.); +#24712 = VERTEX_POINT('',#24713); +#24713 = CARTESIAN_POINT('',(0.4,2.435,0.895)); +#24714 = SURFACE_CURVE('',#24715,(#24719,#24726),.PCURVE_S1.); +#24715 = LINE('',#24716,#24717); +#24716 = CARTESIAN_POINT('',(0.4,0.755,0.895)); +#24717 = VECTOR('',#24718,1.); +#24718 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24719 = PCURVE('',#24488,#24720); +#24720 = DEFINITIONAL_REPRESENTATION('',(#24721),#24725); +#24721 = LINE('',#24722,#24723); +#24722 = CARTESIAN_POINT('',(8.316686038149E-032,1.8)); +#24723 = VECTOR('',#24724,1.); +#24724 = DIRECTION('',(-1.,0.E+000)); +#24725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24726 = PCURVE('',#24727,#24732); +#24727 = PLANE('',#24728); +#24728 = AXIS2_PLACEMENT_3D('',#24729,#24730,#24731); +#24729 = CARTESIAN_POINT('',(0.4,0.445,0.195)); +#24730 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24731 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); #24732 = DEFINITIONAL_REPRESENTATION('',(#24733),#24737); #24733 = LINE('',#24734,#24735); -#24734 = CARTESIAN_POINT('',(-3.797634949565E-016,-0.2)); +#24734 = CARTESIAN_POINT('',(-0.31,0.7)); #24735 = VECTOR('',#24736,1.); -#24736 = DIRECTION('',(-1.,0.E+000)); +#24736 = DIRECTION('',(-1.,1.702510980039E-043)); #24737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#24738 = ORIENTED_EDGE('',*,*,#24739,.T.); -#24739 = EDGE_CURVE('',#24717,#24693,#24740,.T.); -#24740 = SURFACE_CURVE('',#24741,(#24745,#24752),.PCURVE_S1.); -#24741 = LINE('',#24742,#24743); -#24742 = CARTESIAN_POINT('',(-2.5,0.305,2.395)); -#24743 = VECTOR('',#24744,1.); -#24744 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24745 = PCURVE('',#23949,#24746); -#24746 = DEFINITIONAL_REPRESENTATION('',(#24747),#24751); -#24747 = LINE('',#24748,#24749); -#24748 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); -#24749 = VECTOR('',#24750,1.); -#24750 = DIRECTION('',(1.,-1.702510980039E-043)); -#24751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24752 = PCURVE('',#24753,#24758); -#24753 = PLANE('',#24754); -#24754 = AXIS2_PLACEMENT_3D('',#24755,#24756,#24757); -#24755 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); -#24756 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#24757 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24758 = DEFINITIONAL_REPRESENTATION('',(#24759),#24763); -#24759 = LINE('',#24760,#24761); -#24760 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); -#24761 = VECTOR('',#24762,1.); -#24762 = DIRECTION('',(-1.,0.E+000)); -#24763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24764 = ADVANCED_FACE('',(#24765),#24171,.F.); -#24765 = FACE_BOUND('',#24766,.T.); -#24766 = EDGE_LOOP('',(#24767,#24797,#24825,#24848,#24876,#24904,#24932, - #24953,#24954,#24977,#25005,#25033)); -#24767 = ORIENTED_EDGE('',*,*,#24768,.T.); -#24768 = EDGE_CURVE('',#24769,#24771,#24773,.T.); -#24769 = VERTEX_POINT('',#24770); -#24770 = CARTESIAN_POINT('',(-3.,1.755,0.195)); -#24771 = VERTEX_POINT('',#24772); -#24772 = CARTESIAN_POINT('',(-3.,1.755,-0.355)); -#24773 = SURFACE_CURVE('',#24774,(#24778,#24785),.PCURVE_S1.); -#24774 = LINE('',#24775,#24776); -#24775 = CARTESIAN_POINT('',(-3.,1.755,0.195)); -#24776 = VECTOR('',#24777,1.); -#24777 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#24778 = PCURVE('',#24171,#24779); -#24779 = DEFINITIONAL_REPRESENTATION('',(#24780),#24784); -#24780 = LINE('',#24781,#24782); -#24781 = CARTESIAN_POINT('',(-1.5,0.55)); -#24782 = VECTOR('',#24783,1.); -#24783 = DIRECTION('',(-1.702510980039E-043,-1.)); -#24784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24785 = PCURVE('',#24786,#24791); -#24786 = PLANE('',#24787); -#24787 = AXIS2_PLACEMENT_3D('',#24788,#24789,#24790); -#24788 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); -#24789 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24790 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); -#24791 = DEFINITIONAL_REPRESENTATION('',(#24792),#24796); -#24792 = LINE('',#24793,#24794); -#24793 = CARTESIAN_POINT('',(0.5,-2.203640915577E-017)); -#24794 = VECTOR('',#24795,1.); -#24795 = DIRECTION('',(0.E+000,-1.)); -#24796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24797 = ORIENTED_EDGE('',*,*,#24798,.T.); -#24798 = EDGE_CURVE('',#24771,#24799,#24801,.T.); -#24799 = VERTEX_POINT('',#24800); -#24800 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); -#24801 = SURFACE_CURVE('',#24802,(#24806,#24813),.PCURVE_S1.); -#24802 = LINE('',#24803,#24804); -#24803 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); -#24804 = VECTOR('',#24805,1.); -#24805 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#24806 = PCURVE('',#24171,#24807); -#24807 = DEFINITIONAL_REPRESENTATION('',(#24808),#24812); -#24808 = LINE('',#24809,#24810); -#24809 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24810 = VECTOR('',#24811,1.); -#24811 = DIRECTION('',(-1.,-1.702510980039E-043)); -#24812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24813 = PCURVE('',#24814,#24819); -#24814 = PLANE('',#24815); -#24815 = AXIS2_PLACEMENT_3D('',#24816,#24817,#24818); -#24816 = CARTESIAN_POINT('',(3.,3.255,-0.355)); -#24817 = DIRECTION('',(7.105427357601E-015,-3.491483361109E-015,1.)); -#24818 = DIRECTION('',(1.,4.27569270828E-031,-7.105427357601E-015)); -#24819 = DEFINITIONAL_REPRESENTATION('',(#24820),#24824); -#24820 = LINE('',#24821,#24822); -#24821 = CARTESIAN_POINT('',(-6.,2.565415624968E-030)); -#24822 = VECTOR('',#24823,1.); -#24823 = DIRECTION('',(-2.80259692865E-045,-1.)); -#24824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24825 = ORIENTED_EDGE('',*,*,#24826,.T.); -#24826 = EDGE_CURVE('',#24799,#24827,#24829,.T.); -#24827 = VERTEX_POINT('',#24828); -#24828 = CARTESIAN_POINT('',(-3.,0.355,2.395)); -#24829 = SURFACE_CURVE('',#24830,(#24834,#24841),.PCURVE_S1.); -#24830 = LINE('',#24831,#24832); -#24831 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); -#24832 = VECTOR('',#24833,1.); -#24833 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#24834 = PCURVE('',#24171,#24835); -#24835 = DEFINITIONAL_REPRESENTATION('',(#24836),#24840); -#24836 = LINE('',#24837,#24838); -#24837 = CARTESIAN_POINT('',(-2.9,-3.323892810297E-017)); -#24838 = VECTOR('',#24839,1.); -#24839 = DIRECTION('',(1.702510980039E-043,1.)); -#24840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24841 = PCURVE('',#23977,#24842); -#24842 = DEFINITIONAL_REPRESENTATION('',(#24843),#24847); -#24843 = LINE('',#24844,#24845); -#24844 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24845 = VECTOR('',#24846,1.); -#24846 = DIRECTION('',(0.E+000,1.)); -#24847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24848 = ORIENTED_EDGE('',*,*,#24849,.T.); -#24849 = EDGE_CURVE('',#24827,#24850,#24852,.T.); -#24850 = VERTEX_POINT('',#24851); -#24851 = CARTESIAN_POINT('',(-3.,0.905,2.395)); -#24852 = SURFACE_CURVE('',#24853,(#24857,#24864),.PCURVE_S1.); -#24853 = LINE('',#24854,#24855); -#24854 = CARTESIAN_POINT('',(-3.,0.905,2.395)); -#24855 = VECTOR('',#24856,1.); -#24856 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24857 = PCURVE('',#24171,#24858); -#24858 = DEFINITIONAL_REPRESENTATION('',(#24859),#24863); -#24859 = LINE('',#24860,#24861); -#24860 = CARTESIAN_POINT('',(-2.35,2.75)); -#24861 = VECTOR('',#24862,1.); -#24862 = DIRECTION('',(1.,1.702510980039E-043)); -#24863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24864 = PCURVE('',#24865,#24870); -#24865 = PLANE('',#24866); -#24866 = AXIS2_PLACEMENT_3D('',#24867,#24868,#24869); -#24867 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); -#24868 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#24869 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24870 = DEFINITIONAL_REPRESENTATION('',(#24871),#24875); -#24871 = LINE('',#24872,#24873); -#24872 = CARTESIAN_POINT('',(2.13784635414E-031,0.5)); -#24873 = VECTOR('',#24874,1.); -#24874 = DIRECTION('',(1.,0.E+000)); -#24875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24876 = ORIENTED_EDGE('',*,*,#24877,.T.); -#24877 = EDGE_CURVE('',#24850,#24878,#24880,.T.); -#24878 = VERTEX_POINT('',#24879); -#24879 = CARTESIAN_POINT('',(-3.,0.905,3.395)); -#24880 = SURFACE_CURVE('',#24881,(#24885,#24892),.PCURVE_S1.); -#24881 = LINE('',#24882,#24883); -#24882 = CARTESIAN_POINT('',(-3.,0.905,3.395)); -#24883 = VECTOR('',#24884,1.); -#24884 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); -#24885 = PCURVE('',#24171,#24886); -#24886 = DEFINITIONAL_REPRESENTATION('',(#24887),#24891); -#24887 = LINE('',#24888,#24889); -#24888 = CARTESIAN_POINT('',(-2.35,3.75)); -#24889 = VECTOR('',#24890,1.); -#24890 = DIRECTION('',(-1.084202172486E-016,1.)); -#24891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24892 = PCURVE('',#24893,#24898); -#24893 = PLANE('',#24894); -#24894 = AXIS2_PLACEMENT_3D('',#24895,#24896,#24897); -#24895 = CARTESIAN_POINT('',(-2.5,0.905,3.395)); -#24896 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#24897 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); -#24898 = DEFINITIONAL_REPRESENTATION('',(#24899),#24903); -#24899 = LINE('',#24900,#24901); -#24900 = CARTESIAN_POINT('',(6.123031769112E-017,0.5)); -#24901 = VECTOR('',#24902,1.); -#24902 = DIRECTION('',(1.,0.E+000)); -#24903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24904 = ORIENTED_EDGE('',*,*,#24905,.T.); -#24905 = EDGE_CURVE('',#24878,#24906,#24908,.T.); -#24906 = VERTEX_POINT('',#24907); -#24907 = CARTESIAN_POINT('',(-3.,1.555,3.395)); -#24908 = SURFACE_CURVE('',#24909,(#24913,#24920),.PCURVE_S1.); -#24909 = LINE('',#24910,#24911); -#24910 = CARTESIAN_POINT('',(-3.,1.555,3.395)); -#24911 = VECTOR('',#24912,1.); -#24912 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24913 = PCURVE('',#24171,#24914); -#24914 = DEFINITIONAL_REPRESENTATION('',(#24915),#24919); +#24738 = ORIENTED_EDGE('',*,*,#24739,.F.); +#24739 = EDGE_CURVE('',#24740,#24712,#24742,.T.); +#24740 = VERTEX_POINT('',#24741); +#24741 = CARTESIAN_POINT('',(0.6,2.435,0.895)); +#24742 = SURFACE_CURVE('',#24743,(#24747,#24754),.PCURVE_S1.); +#24743 = LINE('',#24744,#24745); +#24744 = CARTESIAN_POINT('',(2.2,2.435,0.895)); +#24745 = VECTOR('',#24746,1.); +#24746 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24747 = PCURVE('',#24488,#24748); +#24748 = DEFINITIONAL_REPRESENTATION('',(#24749),#24753); +#24749 = LINE('',#24750,#24751); +#24750 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); +#24751 = VECTOR('',#24752,1.); +#24752 = DIRECTION('',(2.80259692865E-045,1.)); +#24753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24754 = PCURVE('',#24755,#24760); +#24755 = PLANE('',#24756); +#24756 = AXIS2_PLACEMENT_3D('',#24757,#24758,#24759); +#24757 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#24758 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); +#24759 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); +#24760 = DEFINITIONAL_REPRESENTATION('',(#24761),#24765); +#24761 = LINE('',#24762,#24763); +#24762 = CARTESIAN_POINT('',(-1.75,-1.8)); +#24763 = VECTOR('',#24764,1.); +#24764 = DIRECTION('',(0.E+000,1.)); +#24765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24766 = ORIENTED_EDGE('',*,*,#24767,.F.); +#24767 = EDGE_CURVE('',#24684,#24740,#24768,.T.); +#24768 = SURFACE_CURVE('',#24769,(#24773,#24780),.PCURVE_S1.); +#24769 = LINE('',#24770,#24771); +#24770 = CARTESIAN_POINT('',(0.6,0.755,0.895)); +#24771 = VECTOR('',#24772,1.); +#24772 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24773 = PCURVE('',#24488,#24774); +#24774 = DEFINITIONAL_REPRESENTATION('',(#24775),#24779); +#24775 = LINE('',#24776,#24777); +#24776 = CARTESIAN_POINT('',(-1.414253028609E-031,1.6)); +#24777 = VECTOR('',#24778,1.); +#24778 = DIRECTION('',(-1.,0.E+000)); +#24779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24780 = PCURVE('',#24781,#24786); +#24781 = PLANE('',#24782); +#24782 = AXIS2_PLACEMENT_3D('',#24783,#24784,#24785); +#24783 = CARTESIAN_POINT('',(0.6,0.445,0.195)); +#24784 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24785 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24786 = DEFINITIONAL_REPRESENTATION('',(#24787),#24791); +#24787 = LINE('',#24788,#24789); +#24788 = CARTESIAN_POINT('',(-0.31,0.7)); +#24789 = VECTOR('',#24790,1.); +#24790 = DIRECTION('',(-1.,1.702510980039E-043)); +#24791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24792 = FACE_BOUND('',#24793,.T.); +#24793 = EDGE_LOOP('',(#24794,#24824,#24852,#24880)); +#24794 = ORIENTED_EDGE('',*,*,#24795,.F.); +#24795 = EDGE_CURVE('',#24796,#24798,#24800,.T.); +#24796 = VERTEX_POINT('',#24797); +#24797 = CARTESIAN_POINT('',(-0.6,1.955,0.895)); +#24798 = VERTEX_POINT('',#24799); +#24799 = CARTESIAN_POINT('',(-0.4,1.955,0.895)); +#24800 = SURFACE_CURVE('',#24801,(#24805,#24812),.PCURVE_S1.); +#24801 = LINE('',#24802,#24803); +#24802 = CARTESIAN_POINT('',(-0.6,1.955,0.895)); +#24803 = VECTOR('',#24804,1.); +#24804 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#24805 = PCURVE('',#24488,#24806); +#24806 = DEFINITIONAL_REPRESENTATION('',(#24807),#24811); +#24807 = LINE('',#24808,#24809); +#24808 = CARTESIAN_POINT('',(-1.2,2.8)); +#24809 = VECTOR('',#24810,1.); +#24810 = DIRECTION('',(-2.80259692865E-045,-1.)); +#24811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24812 = PCURVE('',#24813,#24818); +#24813 = PLANE('',#24814); +#24814 = AXIS2_PLACEMENT_3D('',#24815,#24816,#24817); +#24815 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); +#24816 = DIRECTION('',(-5.173092832126E-016,0.997252183706, + -7.408159078957E-002)); +#24817 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, + -0.997252183706)); +#24818 = DEFINITIONAL_REPRESENTATION('',(#24819),#24823); +#24819 = LINE('',#24820,#24821); +#24820 = CARTESIAN_POINT('',(1.754821928288,-1.187607954686E-016)); +#24821 = VECTOR('',#24822,1.); +#24822 = DIRECTION('',(-1.109335647967E-030,-1.)); +#24823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24824 = ORIENTED_EDGE('',*,*,#24825,.T.); +#24825 = EDGE_CURVE('',#24796,#24826,#24828,.T.); +#24826 = VERTEX_POINT('',#24827); +#24827 = CARTESIAN_POINT('',(-0.6,2.435,0.895)); +#24828 = SURFACE_CURVE('',#24829,(#24833,#24840),.PCURVE_S1.); +#24829 = LINE('',#24830,#24831); +#24830 = CARTESIAN_POINT('',(-0.6,0.755,0.895)); +#24831 = VECTOR('',#24832,1.); +#24832 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24833 = PCURVE('',#24488,#24834); +#24834 = DEFINITIONAL_REPRESENTATION('',(#24835),#24839); +#24835 = LINE('',#24836,#24837); +#24836 = CARTESIAN_POINT('',(4.323011131344E-032,2.8)); +#24837 = VECTOR('',#24838,1.); +#24838 = DIRECTION('',(-1.,0.E+000)); +#24839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24840 = PCURVE('',#24841,#24846); +#24841 = PLANE('',#24842); +#24842 = AXIS2_PLACEMENT_3D('',#24843,#24844,#24845); +#24843 = CARTESIAN_POINT('',(-0.6,0.445,0.195)); +#24844 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24845 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24846 = DEFINITIONAL_REPRESENTATION('',(#24847),#24851); +#24847 = LINE('',#24848,#24849); +#24848 = CARTESIAN_POINT('',(-0.31,0.7)); +#24849 = VECTOR('',#24850,1.); +#24850 = DIRECTION('',(-1.,1.702510980039E-043)); +#24851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24852 = ORIENTED_EDGE('',*,*,#24853,.F.); +#24853 = EDGE_CURVE('',#24854,#24826,#24856,.T.); +#24854 = VERTEX_POINT('',#24855); +#24855 = CARTESIAN_POINT('',(-0.4,2.435,0.895)); +#24856 = SURFACE_CURVE('',#24857,(#24861,#24868),.PCURVE_S1.); +#24857 = LINE('',#24858,#24859); +#24858 = CARTESIAN_POINT('',(2.2,2.435,0.895)); +#24859 = VECTOR('',#24860,1.); +#24860 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24861 = PCURVE('',#24488,#24862); +#24862 = DEFINITIONAL_REPRESENTATION('',(#24863),#24867); +#24863 = LINE('',#24864,#24865); +#24864 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); +#24865 = VECTOR('',#24866,1.); +#24866 = DIRECTION('',(2.80259692865E-045,1.)); +#24867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24868 = PCURVE('',#24869,#24874); +#24869 = PLANE('',#24870); +#24870 = AXIS2_PLACEMENT_3D('',#24871,#24872,#24873); +#24871 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#24872 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); +#24873 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); +#24874 = DEFINITIONAL_REPRESENTATION('',(#24875),#24879); +#24875 = LINE('',#24876,#24877); +#24876 = CARTESIAN_POINT('',(-1.75,-2.8)); +#24877 = VECTOR('',#24878,1.); +#24878 = DIRECTION('',(0.E+000,1.)); +#24879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24880 = ORIENTED_EDGE('',*,*,#24881,.F.); +#24881 = EDGE_CURVE('',#24798,#24854,#24882,.T.); +#24882 = SURFACE_CURVE('',#24883,(#24887,#24894),.PCURVE_S1.); +#24883 = LINE('',#24884,#24885); +#24884 = CARTESIAN_POINT('',(-0.4,0.755,0.895)); +#24885 = VECTOR('',#24886,1.); +#24886 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24887 = PCURVE('',#24488,#24888); +#24888 = DEFINITIONAL_REPRESENTATION('',(#24889),#24893); +#24889 = LINE('',#24890,#24891); +#24890 = CARTESIAN_POINT('',(-1.813620519289E-031,2.6)); +#24891 = VECTOR('',#24892,1.); +#24892 = DIRECTION('',(-1.,0.E+000)); +#24893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24894 = PCURVE('',#24895,#24900); +#24895 = PLANE('',#24896); +#24896 = AXIS2_PLACEMENT_3D('',#24897,#24898,#24899); +#24897 = CARTESIAN_POINT('',(-0.4,0.445,0.195)); +#24898 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24899 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24900 = DEFINITIONAL_REPRESENTATION('',(#24901),#24905); +#24901 = LINE('',#24902,#24903); +#24902 = CARTESIAN_POINT('',(-0.31,0.7)); +#24903 = VECTOR('',#24904,1.); +#24904 = DIRECTION('',(-1.,1.702510980039E-043)); +#24905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24906 = FACE_BOUND('',#24907,.T.); +#24907 = EDGE_LOOP('',(#24908,#24938,#24966,#24994)); +#24908 = ORIENTED_EDGE('',*,*,#24909,.F.); +#24909 = EDGE_CURVE('',#24910,#24912,#24914,.T.); +#24910 = VERTEX_POINT('',#24911); +#24911 = CARTESIAN_POINT('',(-1.6,1.955,0.895)); +#24912 = VERTEX_POINT('',#24913); +#24913 = CARTESIAN_POINT('',(-1.4,1.955,0.895)); +#24914 = SURFACE_CURVE('',#24915,(#24919,#24926),.PCURVE_S1.); #24915 = LINE('',#24916,#24917); -#24916 = CARTESIAN_POINT('',(-1.7,3.75)); +#24916 = CARTESIAN_POINT('',(-1.6,1.955,0.895)); #24917 = VECTOR('',#24918,1.); -#24918 = DIRECTION('',(1.,1.702510980039E-043)); -#24919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24920 = PCURVE('',#24921,#24926); -#24921 = PLANE('',#24922); -#24922 = AXIS2_PLACEMENT_3D('',#24923,#24924,#24925); -#24923 = CARTESIAN_POINT('',(-2.5,1.555,3.395)); -#24924 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#24925 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#24926 = DEFINITIONAL_REPRESENTATION('',(#24927),#24931); -#24927 = LINE('',#24928,#24929); -#24928 = CARTESIAN_POINT('',(2.13784635414E-031,0.5)); -#24929 = VECTOR('',#24930,1.); -#24930 = DIRECTION('',(1.,0.E+000)); -#24931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24932 = ORIENTED_EDGE('',*,*,#24933,.T.); -#24933 = EDGE_CURVE('',#24906,#23850,#24934,.T.); -#24934 = SURFACE_CURVE('',#24935,(#24939,#24946),.PCURVE_S1.); -#24935 = LINE('',#24936,#24937); -#24936 = CARTESIAN_POINT('',(-3.,1.555,3.895)); -#24937 = VECTOR('',#24938,1.); -#24938 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); -#24939 = PCURVE('',#24171,#24940); -#24940 = DEFINITIONAL_REPRESENTATION('',(#24941),#24945); -#24941 = LINE('',#24942,#24943); -#24942 = CARTESIAN_POINT('',(-1.7,4.25)); -#24943 = VECTOR('',#24944,1.); -#24944 = DIRECTION('',(4.336808689942E-016,1.)); -#24945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24946 = PCURVE('',#23865,#24947); -#24947 = DEFINITIONAL_REPRESENTATION('',(#24948),#24952); -#24948 = LINE('',#24949,#24950); -#24949 = CARTESIAN_POINT('',(-3.828588921589E-016,0.5)); -#24950 = VECTOR('',#24951,1.); -#24951 = DIRECTION('',(1.,0.E+000)); -#24952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24953 = ORIENTED_EDGE('',*,*,#24157,.F.); -#24954 = ORIENTED_EDGE('',*,*,#24955,.F.); -#24955 = EDGE_CURVE('',#24956,#24130,#24958,.T.); -#24956 = VERTEX_POINT('',#24957); -#24957 = CARTESIAN_POINT('',(-3.,3.255,1.133675134595)); -#24958 = SURFACE_CURVE('',#24959,(#24963,#24970),.PCURVE_S1.); -#24959 = LINE('',#24960,#24961); -#24960 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); -#24961 = VECTOR('',#24962,1.); -#24962 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#24963 = PCURVE('',#24171,#24964); -#24964 = DEFINITIONAL_REPRESENTATION('',(#24965),#24969); -#24965 = LINE('',#24966,#24967); -#24966 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24967 = VECTOR('',#24968,1.); -#24968 = DIRECTION('',(1.702510980039E-043,1.)); -#24969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24970 = PCURVE('',#24145,#24971); -#24971 = DEFINITIONAL_REPRESENTATION('',(#24972),#24976); -#24972 = LINE('',#24973,#24974); -#24973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#24974 = VECTOR('',#24975,1.); -#24975 = DIRECTION('',(0.E+000,1.)); -#24976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24977 = ORIENTED_EDGE('',*,*,#24978,.T.); -#24978 = EDGE_CURVE('',#24956,#24979,#24981,.T.); -#24979 = VERTEX_POINT('',#24980); -#24980 = CARTESIAN_POINT('',(-3.,2.755,0.845)); -#24981 = SURFACE_CURVE('',#24982,(#24986,#24993),.PCURVE_S1.); -#24982 = LINE('',#24983,#24984); -#24983 = CARTESIAN_POINT('',(-3.,2.755,0.845)); -#24984 = VECTOR('',#24985,1.); -#24985 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); -#24986 = PCURVE('',#24171,#24987); -#24987 = DEFINITIONAL_REPRESENTATION('',(#24988),#24992); -#24988 = LINE('',#24989,#24990); -#24989 = CARTESIAN_POINT('',(-0.5,1.2)); -#24990 = VECTOR('',#24991,1.); -#24991 = DIRECTION('',(-0.866025403784,-0.5)); -#24992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#24993 = PCURVE('',#24994,#24999); -#24994 = PLANE('',#24995); -#24995 = AXIS2_PLACEMENT_3D('',#24996,#24997,#24998); -#24996 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); -#24997 = DIRECTION('',(-6.047426575223E-015,0.5,-0.866025403784)); -#24998 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); -#24999 = DEFINITIONAL_REPRESENTATION('',(#25000),#25004); -#25000 = LINE('',#25001,#25002); -#25001 = CARTESIAN_POINT('',(-3.061515884556E-017,0.5)); -#25002 = VECTOR('',#25003,1.); -#25003 = DIRECTION('',(1.,1.961367055364E-030)); -#25004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25005 = ORIENTED_EDGE('',*,*,#25006,.T.); -#25006 = EDGE_CURVE('',#24979,#25007,#25009,.T.); -#25007 = VERTEX_POINT('',#25008); -#25008 = CARTESIAN_POINT('',(-3.,2.755,0.195)); -#25009 = SURFACE_CURVE('',#25010,(#25014,#25021),.PCURVE_S1.); -#25010 = LINE('',#25011,#25012); -#25011 = CARTESIAN_POINT('',(-3.,2.755,0.195)); -#25012 = VECTOR('',#25013,1.); -#25013 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25014 = PCURVE('',#24171,#25015); -#25015 = DEFINITIONAL_REPRESENTATION('',(#25016),#25020); -#25016 = LINE('',#25017,#25018); -#25017 = CARTESIAN_POINT('',(-0.5,0.55)); -#25018 = VECTOR('',#25019,1.); -#25019 = DIRECTION('',(-1.702510980039E-043,-1.)); -#25020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25021 = PCURVE('',#25022,#25027); -#25022 = PLANE('',#25023); -#25023 = AXIS2_PLACEMENT_3D('',#25024,#25025,#25026); -#25024 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#25025 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25026 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); -#25027 = DEFINITIONAL_REPRESENTATION('',(#25028),#25032); -#25028 = LINE('',#25029,#25030); -#25029 = CARTESIAN_POINT('',(0.5,-2.203640915577E-017)); -#25030 = VECTOR('',#25031,1.); -#25031 = DIRECTION('',(0.E+000,-1.)); -#25032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25033 = ORIENTED_EDGE('',*,*,#25034,.T.); -#25034 = EDGE_CURVE('',#25007,#24769,#25035,.T.); -#25035 = SURFACE_CURVE('',#25036,(#25040,#25047),.PCURVE_S1.); -#25036 = LINE('',#25037,#25038); -#25037 = CARTESIAN_POINT('',(-3.,2.755,0.195)); -#25038 = VECTOR('',#25039,1.); -#25039 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#25040 = PCURVE('',#24171,#25041); -#25041 = DEFINITIONAL_REPRESENTATION('',(#25042),#25046); -#25042 = LINE('',#25043,#25044); -#25043 = CARTESIAN_POINT('',(-0.5,0.55)); -#25044 = VECTOR('',#25045,1.); -#25045 = DIRECTION('',(-1.,-1.084202172486E-016)); -#25046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25047 = PCURVE('',#25048,#25053); -#25048 = PLANE('',#25049); -#25049 = AXIS2_PLACEMENT_3D('',#25050,#25051,#25052); -#25050 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#25051 = DIRECTION('',(-6.982966722219E-015,3.599903578358E-015,-1.)); -#25052 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#25053 = DEFINITIONAL_REPRESENTATION('',(#25054),#25058); -#25054 = LINE('',#25055,#25056); -#25055 = CARTESIAN_POINT('',(-2.058844780408E-032,0.5)); -#25056 = VECTOR('',#25057,1.); -#25057 = DIRECTION('',(1.,0.E+000)); -#25058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25059 = ADVANCED_FACE('',(#25060),#23977,.T.); -#25060 = FACE_BOUND('',#25061,.T.); -#25061 = EDGE_LOOP('',(#25062,#25092,#25120,#25148,#25171,#25194,#25222, - #25245,#25266,#25267,#25268,#25291,#25312,#25313,#25336,#25364, - #25392,#25420,#25443,#25471,#25499,#25527,#25550,#25578,#25606, - #25634)); -#25062 = ORIENTED_EDGE('',*,*,#25063,.F.); -#25063 = EDGE_CURVE('',#25064,#25066,#25068,.T.); -#25064 = VERTEX_POINT('',#25065); -#25065 = CARTESIAN_POINT('',(1.4,0.355,-0.255)); -#25066 = VERTEX_POINT('',#25067); -#25067 = CARTESIAN_POINT('',(1.4,0.355,-0.355)); -#25068 = SURFACE_CURVE('',#25069,(#25073,#25080),.PCURVE_S1.); -#25069 = LINE('',#25070,#25071); -#25070 = CARTESIAN_POINT('',(1.4,0.355,-0.355)); -#25071 = VECTOR('',#25072,1.); -#25072 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25073 = PCURVE('',#23977,#25074); +#24918 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#24919 = PCURVE('',#24488,#24920); +#24920 = DEFINITIONAL_REPRESENTATION('',(#24921),#24925); +#24921 = LINE('',#24922,#24923); +#24922 = CARTESIAN_POINT('',(-1.2,3.8)); +#24923 = VECTOR('',#24924,1.); +#24924 = DIRECTION('',(-2.80259692865E-045,-1.)); +#24925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24926 = PCURVE('',#24927,#24932); +#24927 = PLANE('',#24928); +#24928 = AXIS2_PLACEMENT_3D('',#24929,#24930,#24931); +#24929 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); +#24930 = DIRECTION('',(-5.173092832126E-016,0.997252183706, + -7.408159078957E-002)); +#24931 = DIRECTION('',(-6.963778812478E-015,-7.408159078957E-002, + -0.997252183706)); +#24932 = DEFINITIONAL_REPRESENTATION('',(#24933),#24937); +#24933 = LINE('',#24934,#24935); +#24934 = CARTESIAN_POINT('',(1.754821928288,2.143061119189E-016)); +#24935 = VECTOR('',#24936,1.); +#24936 = DIRECTION('',(-1.109335647967E-030,-1.)); +#24937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24938 = ORIENTED_EDGE('',*,*,#24939,.T.); +#24939 = EDGE_CURVE('',#24910,#24940,#24942,.T.); +#24940 = VERTEX_POINT('',#24941); +#24941 = CARTESIAN_POINT('',(-1.6,2.435,0.895)); +#24942 = SURFACE_CURVE('',#24943,(#24947,#24954),.PCURVE_S1.); +#24943 = LINE('',#24944,#24945); +#24944 = CARTESIAN_POINT('',(-1.6,0.755,0.895)); +#24945 = VECTOR('',#24946,1.); +#24946 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#24947 = PCURVE('',#24488,#24948); +#24948 = DEFINITIONAL_REPRESENTATION('',(#24949),#24953); +#24949 = LINE('',#24950,#24951); +#24950 = CARTESIAN_POINT('',(3.293362245417E-033,3.8)); +#24951 = VECTOR('',#24952,1.); +#24952 = DIRECTION('',(-1.,0.E+000)); +#24953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24954 = PCURVE('',#24955,#24960); +#24955 = PLANE('',#24956); +#24956 = AXIS2_PLACEMENT_3D('',#24957,#24958,#24959); +#24957 = CARTESIAN_POINT('',(-1.6,0.445,0.195)); +#24958 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24959 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#24960 = DEFINITIONAL_REPRESENTATION('',(#24961),#24965); +#24961 = LINE('',#24962,#24963); +#24962 = CARTESIAN_POINT('',(-0.31,0.7)); +#24963 = VECTOR('',#24964,1.); +#24964 = DIRECTION('',(-1.,1.702510980039E-043)); +#24965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24966 = ORIENTED_EDGE('',*,*,#24967,.F.); +#24967 = EDGE_CURVE('',#24968,#24940,#24970,.T.); +#24968 = VERTEX_POINT('',#24969); +#24969 = CARTESIAN_POINT('',(-1.4,2.435,0.895)); +#24970 = SURFACE_CURVE('',#24971,(#24975,#24982),.PCURVE_S1.); +#24971 = LINE('',#24972,#24973); +#24972 = CARTESIAN_POINT('',(2.2,2.435,0.895)); +#24973 = VECTOR('',#24974,1.); +#24974 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#24975 = PCURVE('',#24488,#24976); +#24976 = DEFINITIONAL_REPRESENTATION('',(#24977),#24981); +#24977 = LINE('',#24978,#24979); +#24978 = CARTESIAN_POINT('',(-1.68,4.108904730655E-029)); +#24979 = VECTOR('',#24980,1.); +#24980 = DIRECTION('',(2.80259692865E-045,1.)); +#24981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24982 = PCURVE('',#24983,#24988); +#24983 = PLANE('',#24984); +#24984 = AXIS2_PLACEMENT_3D('',#24985,#24986,#24987); +#24985 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); +#24986 = DIRECTION('',(-2.561698521415E-029,-1.,-3.668495960699E-015)); +#24987 = DIRECTION('',(6.982966722219E-015,-3.668495960699E-015,1.)); +#24988 = DEFINITIONAL_REPRESENTATION('',(#24989),#24993); +#24989 = LINE('',#24990,#24991); +#24990 = CARTESIAN_POINT('',(-1.75,-3.8)); +#24991 = VECTOR('',#24992,1.); +#24992 = DIRECTION('',(0.E+000,1.)); +#24993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#24994 = ORIENTED_EDGE('',*,*,#24995,.F.); +#24995 = EDGE_CURVE('',#24912,#24968,#24996,.T.); +#24996 = SURFACE_CURVE('',#24997,(#25001,#25008),.PCURVE_S1.); +#24997 = LINE('',#24998,#24999); +#24998 = CARTESIAN_POINT('',(-1.4,0.755,0.895)); +#24999 = VECTOR('',#25000,1.); +#25000 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25001 = PCURVE('',#24488,#25002); +#25002 = DEFINITIONAL_REPRESENTATION('',(#25003),#25007); +#25003 = LINE('',#25004,#25005); +#25004 = CARTESIAN_POINT('',(1.66333720763E-031,3.6)); +#25005 = VECTOR('',#25006,1.); +#25006 = DIRECTION('',(-1.,0.E+000)); +#25007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25008 = PCURVE('',#25009,#25014); +#25009 = PLANE('',#25010); +#25010 = AXIS2_PLACEMENT_3D('',#25011,#25012,#25013); +#25011 = CARTESIAN_POINT('',(-1.4,0.445,0.195)); +#25012 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#25013 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#25014 = DEFINITIONAL_REPRESENTATION('',(#25015),#25019); +#25015 = LINE('',#25016,#25017); +#25016 = CARTESIAN_POINT('',(-0.31,0.7)); +#25017 = VECTOR('',#25018,1.); +#25018 = DIRECTION('',(-1.,1.702510980039E-043)); +#25019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25020 = FACE_BOUND('',#25021,.T.); +#25021 = EDGE_LOOP('',(#25022,#25052,#25080,#25108)); +#25022 = ORIENTED_EDGE('',*,*,#25023,.T.); +#25023 = EDGE_CURVE('',#25024,#25026,#25028,.T.); +#25024 = VERTEX_POINT('',#25025); +#25025 = CARTESIAN_POINT('',(2.2,0.755,0.895)); +#25026 = VERTEX_POINT('',#25027); +#25027 = CARTESIAN_POINT('',(2.2,2.855,0.895)); +#25028 = SURFACE_CURVE('',#25029,(#25033,#25040),.PCURVE_S1.); +#25029 = LINE('',#25030,#25031); +#25030 = CARTESIAN_POINT('',(2.2,2.855,0.895)); +#25031 = VECTOR('',#25032,1.); +#25032 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); +#25033 = PCURVE('',#24488,#25034); +#25034 = DEFINITIONAL_REPRESENTATION('',(#25035),#25039); +#25035 = LINE('',#25036,#25037); +#25036 = CARTESIAN_POINT('',(-2.1,4.440892098501E-016)); +#25037 = VECTOR('',#25038,1.); +#25038 = DIRECTION('',(-1.,2.06514699521E-016)); +#25039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25040 = PCURVE('',#25041,#25046); +#25041 = PLANE('',#25042); +#25042 = AXIS2_PLACEMENT_3D('',#25043,#25044,#25045); +#25043 = CARTESIAN_POINT('',(2.2,2.855,0.895)); +#25044 = DIRECTION('',(1.,2.06514699521E-016,-7.085009279629E-015)); +#25045 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); +#25046 = DEFINITIONAL_REPRESENTATION('',(#25047),#25051); +#25047 = LINE('',#25048,#25049); +#25048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25049 = VECTOR('',#25050,1.); +#25050 = DIRECTION('',(1.,1.145632479557E-031)); +#25051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25052 = ORIENTED_EDGE('',*,*,#25053,.T.); +#25053 = EDGE_CURVE('',#25026,#25054,#25056,.T.); +#25054 = VERTEX_POINT('',#25055); +#25055 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25056 = SURFACE_CURVE('',#25057,(#25061,#25068),.PCURVE_S1.); +#25057 = LINE('',#25058,#25059); +#25058 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25059 = VECTOR('',#25060,1.); +#25060 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); +#25061 = PCURVE('',#24488,#25062); +#25062 = DEFINITIONAL_REPRESENTATION('',(#25063),#25067); +#25063 = LINE('',#25064,#25065); +#25064 = CARTESIAN_POINT('',(-2.1,4.4)); +#25065 = VECTOR('',#25066,1.); +#25066 = DIRECTION('',(9.856383386232E-017,1.)); +#25067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25068 = PCURVE('',#25069,#25074); +#25069 = PLANE('',#25070); +#25070 = AXIS2_PLACEMENT_3D('',#25071,#25072,#25073); +#25071 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25072 = DIRECTION('',(-9.856383386229E-017,1.,3.491483361109E-015)); +#25073 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); #25074 = DEFINITIONAL_REPRESENTATION('',(#25075),#25079); #25075 = LINE('',#25076,#25077); -#25076 = CARTESIAN_POINT('',(4.4,2.7386946877E-017)); +#25076 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25077 = VECTOR('',#25078,1.); -#25078 = DIRECTION('',(0.E+000,-1.)); +#25078 = DIRECTION('',(1.,3.439710880676E-031)); #25079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25080 = PCURVE('',#25081,#25086); -#25081 = PLANE('',#25082); -#25082 = AXIS2_PLACEMENT_3D('',#25083,#25084,#25085); -#25083 = CARTESIAN_POINT('',(1.4,0.445,0.195)); -#25084 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25085 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25086 = DEFINITIONAL_REPRESENTATION('',(#25087),#25091); -#25087 = LINE('',#25088,#25089); -#25088 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25089 = VECTOR('',#25090,1.); -#25090 = DIRECTION('',(1.702510980039E-043,-1.)); -#25091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25092 = ORIENTED_EDGE('',*,*,#25093,.T.); -#25093 = EDGE_CURVE('',#25064,#25094,#25096,.T.); -#25094 = VERTEX_POINT('',#25095); -#25095 = CARTESIAN_POINT('',(1.6,0.355,-0.255)); -#25096 = SURFACE_CURVE('',#25097,(#25101,#25108),.PCURVE_S1.); -#25097 = LINE('',#25098,#25099); -#25098 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); -#25099 = VECTOR('',#25100,1.); -#25100 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25101 = PCURVE('',#23977,#25102); +#25080 = ORIENTED_EDGE('',*,*,#25081,.T.); +#25081 = EDGE_CURVE('',#25054,#25082,#25084,.T.); +#25082 = VERTEX_POINT('',#25083); +#25083 = CARTESIAN_POINT('',(-2.2,0.755,0.895)); +#25084 = SURFACE_CURVE('',#25085,(#25089,#25096),.PCURVE_S1.); +#25085 = LINE('',#25086,#25087); +#25086 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25087 = VECTOR('',#25088,1.); +#25088 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); +#25089 = PCURVE('',#24488,#25090); +#25090 = DEFINITIONAL_REPRESENTATION('',(#25091),#25095); +#25091 = LINE('',#25092,#25093); +#25092 = CARTESIAN_POINT('',(-2.1,4.4)); +#25093 = VECTOR('',#25094,1.); +#25094 = DIRECTION('',(1.,-2.06514699521E-016)); +#25095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25096 = PCURVE('',#25097,#25102); +#25097 = PLANE('',#25098); +#25098 = AXIS2_PLACEMENT_3D('',#25099,#25100,#25101); +#25099 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25100 = DIRECTION('',(-1.,-2.06514699521E-016,7.085009279629E-015)); +#25101 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); #25102 = DEFINITIONAL_REPRESENTATION('',(#25103),#25107); #25103 = LINE('',#25104,#25105); -#25104 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); +#25104 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25105 = VECTOR('',#25106,1.); -#25106 = DIRECTION('',(1.,0.E+000)); +#25106 = DIRECTION('',(1.,-1.145632479557E-031)); #25107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25108 = PCURVE('',#25109,#25114); -#25109 = PLANE('',#25110); -#25110 = AXIS2_PLACEMENT_3D('',#25111,#25112,#25113); -#25111 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#25112 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); -#25113 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); -#25114 = DEFINITIONAL_REPRESENTATION('',(#25115),#25119); -#25115 = LINE('',#25116,#25117); -#25116 = CARTESIAN_POINT('',(-6.E-002,4.4)); -#25117 = VECTOR('',#25118,1.); -#25118 = DIRECTION('',(-1.642146637881E-047,-1.)); -#25119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25120 = ORIENTED_EDGE('',*,*,#25121,.T.); -#25121 = EDGE_CURVE('',#25094,#25122,#25124,.T.); -#25122 = VERTEX_POINT('',#25123); -#25123 = CARTESIAN_POINT('',(1.6,0.355,-0.355)); -#25124 = SURFACE_CURVE('',#25125,(#25129,#25136),.PCURVE_S1.); -#25125 = LINE('',#25126,#25127); -#25126 = CARTESIAN_POINT('',(1.6,0.355,-0.355)); -#25127 = VECTOR('',#25128,1.); -#25128 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25129 = PCURVE('',#23977,#25130); -#25130 = DEFINITIONAL_REPRESENTATION('',(#25131),#25135); -#25131 = LINE('',#25132,#25133); -#25132 = CARTESIAN_POINT('',(4.6,-1.930964069196E-017)); -#25133 = VECTOR('',#25134,1.); -#25134 = DIRECTION('',(0.E+000,-1.)); -#25135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25136 = PCURVE('',#25137,#25142); -#25137 = PLANE('',#25138); -#25138 = AXIS2_PLACEMENT_3D('',#25139,#25140,#25141); -#25139 = CARTESIAN_POINT('',(1.6,0.445,0.195)); -#25140 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25141 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25142 = DEFINITIONAL_REPRESENTATION('',(#25143),#25147); -#25143 = LINE('',#25144,#25145); -#25144 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25145 = VECTOR('',#25146,1.); -#25146 = DIRECTION('',(1.702510980039E-043,-1.)); -#25147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25148 = ORIENTED_EDGE('',*,*,#25149,.F.); -#25149 = EDGE_CURVE('',#25150,#25122,#25152,.T.); -#25150 = VERTEX_POINT('',#25151); -#25151 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25152 = SURFACE_CURVE('',#25153,(#25157,#25164),.PCURVE_S1.); -#25153 = LINE('',#25154,#25155); -#25154 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25155 = VECTOR('',#25156,1.); -#25156 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#25157 = PCURVE('',#23977,#25158); -#25158 = DEFINITIONAL_REPRESENTATION('',(#25159),#25163); -#25159 = LINE('',#25160,#25161); -#25160 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25161 = VECTOR('',#25162,1.); -#25162 = DIRECTION('',(-1.,1.224606353822E-016)); -#25163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25164 = PCURVE('',#24814,#25165); -#25165 = DEFINITIONAL_REPRESENTATION('',(#25166),#25170); -#25166 = LINE('',#25167,#25168); -#25167 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); -#25168 = VECTOR('',#25169,1.); -#25169 = DIRECTION('',(-1.,0.E+000)); -#25170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25171 = ORIENTED_EDGE('',*,*,#25172,.F.); -#25172 = EDGE_CURVE('',#25173,#25150,#25175,.T.); -#25173 = VERTEX_POINT('',#25174); -#25174 = CARTESIAN_POINT('',(3.,0.355,2.395)); -#25175 = SURFACE_CURVE('',#25176,(#25180,#25187),.PCURVE_S1.); -#25176 = LINE('',#25177,#25178); -#25177 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25178 = VECTOR('',#25179,1.); -#25179 = DIRECTION('',(-7.18705183704E-015,3.491483361109E-015,-1.)); -#25180 = PCURVE('',#23977,#25181); -#25181 = DEFINITIONAL_REPRESENTATION('',(#25182),#25186); -#25182 = LINE('',#25183,#25184); -#25183 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25184 = VECTOR('',#25185,1.); -#25185 = DIRECTION('',(-2.040851148208E-016,-1.)); -#25186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25187 = PCURVE('',#24117,#25188); -#25188 = DEFINITIONAL_REPRESENTATION('',(#25189),#25193); -#25189 = LINE('',#25190,#25191); -#25190 = CARTESIAN_POINT('',(7.778337435954E-017,-2.9)); -#25191 = VECTOR('',#25192,1.); -#25192 = DIRECTION('',(-1.,-1.752268792537E-043)); -#25193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25194 = ORIENTED_EDGE('',*,*,#25195,.F.); -#25195 = EDGE_CURVE('',#25196,#25173,#25198,.T.); -#25196 = VERTEX_POINT('',#25197); -#25197 = CARTESIAN_POINT('',(2.7,0.355,2.395)); -#25198 = SURFACE_CURVE('',#25199,(#25203,#25210),.PCURVE_S1.); -#25199 = LINE('',#25200,#25201); -#25200 = CARTESIAN_POINT('',(2.5,0.355,2.395)); -#25201 = VECTOR('',#25202,1.); -#25202 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25203 = PCURVE('',#23977,#25204); -#25204 = DEFINITIONAL_REPRESENTATION('',(#25205),#25209); -#25205 = LINE('',#25206,#25207); -#25206 = CARTESIAN_POINT('',(5.5,2.75)); -#25207 = VECTOR('',#25208,1.); -#25208 = DIRECTION('',(1.,0.E+000)); -#25209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25210 = PCURVE('',#25211,#25216); -#25211 = PLANE('',#25212); -#25212 = AXIS2_PLACEMENT_3D('',#25213,#25214,#25215); -#25213 = CARTESIAN_POINT('',(2.5,0.905,2.395)); -#25214 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25215 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25216 = DEFINITIONAL_REPRESENTATION('',(#25217),#25221); -#25217 = LINE('',#25218,#25219); -#25218 = CARTESIAN_POINT('',(0.55,-1.240424069632E-029)); -#25219 = VECTOR('',#25220,1.); -#25220 = DIRECTION('',(-2.80259692865E-045,-1.)); -#25221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25222 = ORIENTED_EDGE('',*,*,#25223,.F.); -#25223 = EDGE_CURVE('',#25224,#25196,#25226,.T.); +#25108 = ORIENTED_EDGE('',*,*,#25109,.T.); +#25109 = EDGE_CURVE('',#25082,#25024,#25110,.T.); +#25110 = SURFACE_CURVE('',#25111,(#25115,#25122),.PCURVE_S1.); +#25111 = LINE('',#25112,#25113); +#25112 = CARTESIAN_POINT('',(2.2,0.755,0.895)); +#25113 = VECTOR('',#25114,1.); +#25114 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); +#25115 = PCURVE('',#24488,#25116); +#25116 = DEFINITIONAL_REPRESENTATION('',(#25117),#25121); +#25117 = LINE('',#25118,#25119); +#25118 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25119 = VECTOR('',#25120,1.); +#25120 = DIRECTION('',(-1.232047923279E-016,-1.)); +#25121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25122 = PCURVE('',#25123,#25128); +#25123 = PLANE('',#25124); +#25124 = AXIS2_PLACEMENT_3D('',#25125,#25126,#25127); +#25125 = CARTESIAN_POINT('',(2.2,0.755,0.895)); +#25126 = DIRECTION('',(1.232047923279E-016,-1.,-3.491483361109E-015)); +#25127 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); +#25128 = DEFINITIONAL_REPRESENTATION('',(#25129),#25133); +#25129 = LINE('',#25130,#25131); +#25130 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25131 = VECTOR('',#25132,1.); +#25132 = DIRECTION('',(1.,3.586081556449E-031)); +#25133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25134 = ADVANCED_FACE('',(#25135),#24542,.F.); +#25135 = FACE_BOUND('',#25136,.T.); +#25136 = EDGE_LOOP('',(#25137,#25138,#25139,#25162)); +#25137 = ORIENTED_EDGE('',*,*,#24528,.T.); +#25138 = ORIENTED_EDGE('',*,*,#24609,.F.); +#25139 = ORIENTED_EDGE('',*,*,#25140,.F.); +#25140 = EDGE_CURVE('',#25141,#24582,#25143,.T.); +#25141 = VERTEX_POINT('',#25142); +#25142 = CARTESIAN_POINT('',(1.4,2.085,2.645)); +#25143 = SURFACE_CURVE('',#25144,(#25148,#25155),.PCURVE_S1.); +#25144 = LINE('',#25145,#25146); +#25145 = CARTESIAN_POINT('',(1.4,2.435,2.645)); +#25146 = VECTOR('',#25147,1.); +#25147 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25148 = PCURVE('',#24542,#25149); +#25149 = DEFINITIONAL_REPRESENTATION('',(#25150),#25154); +#25150 = LINE('',#25151,#25152); +#25151 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25152 = VECTOR('',#25153,1.); +#25153 = DIRECTION('',(-1.,0.E+000)); +#25154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25155 = PCURVE('',#24597,#25156); +#25156 = DEFINITIONAL_REPRESENTATION('',(#25157),#25161); +#25157 = LINE('',#25158,#25159); +#25158 = CARTESIAN_POINT('',(-1.99,2.45)); +#25159 = VECTOR('',#25160,1.); +#25160 = DIRECTION('',(-1.,1.702510980039E-043)); +#25161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25162 = ORIENTED_EDGE('',*,*,#25163,.T.); +#25163 = EDGE_CURVE('',#25141,#24440,#25164,.T.); +#25164 = SURFACE_CURVE('',#25165,(#25169,#25176),.PCURVE_S1.); +#25165 = LINE('',#25166,#25167); +#25166 = CARTESIAN_POINT('',(1.4,2.085,2.645)); +#25167 = VECTOR('',#25168,1.); +#25168 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#25169 = PCURVE('',#24542,#25170); +#25170 = DEFINITIONAL_REPRESENTATION('',(#25171),#25175); +#25171 = LINE('',#25172,#25173); +#25172 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); +#25173 = VECTOR('',#25174,1.); +#25174 = DIRECTION('',(-2.80259692865E-045,-1.)); +#25175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25176 = PCURVE('',#24460,#25177); +#25177 = DEFINITIONAL_REPRESENTATION('',(#25178),#25182); +#25178 = LINE('',#25179,#25180); +#25179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25180 = VECTOR('',#25181,1.); +#25181 = DIRECTION('',(-1.109335647967E-030,-1.)); +#25182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25183 = ADVANCED_FACE('',(#25184),#24460,.F.); +#25184 = FACE_BOUND('',#25185,.T.); +#25185 = EDGE_LOOP('',(#25186,#25187,#25188,#25209)); +#25186 = ORIENTED_EDGE('',*,*,#24437,.T.); +#25187 = ORIENTED_EDGE('',*,*,#25163,.F.); +#25188 = ORIENTED_EDGE('',*,*,#25189,.F.); +#25189 = EDGE_CURVE('',#24634,#25141,#25190,.T.); +#25190 = SURFACE_CURVE('',#25191,(#25195,#25202),.PCURVE_S1.); +#25191 = LINE('',#25192,#25193); +#25192 = CARTESIAN_POINT('',(1.4,2.085,2.645)); +#25193 = VECTOR('',#25194,1.); +#25194 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25195 = PCURVE('',#24460,#25196); +#25196 = DEFINITIONAL_REPRESENTATION('',(#25197),#25201); +#25197 = LINE('',#25198,#25199); +#25198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25199 = VECTOR('',#25200,1.); +#25200 = DIRECTION('',(-1.,4.74549138297E-031)); +#25201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25202 = PCURVE('',#24597,#25203); +#25203 = DEFINITIONAL_REPRESENTATION('',(#25204),#25208); +#25204 = LINE('',#25205,#25206); +#25205 = CARTESIAN_POINT('',(-1.64,2.45)); +#25206 = VECTOR('',#25207,1.); +#25207 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25209 = ORIENTED_EDGE('',*,*,#24633,.T.); +#25210 = ADVANCED_FACE('',(#25211),#24597,.T.); +#25211 = FACE_BOUND('',#25212,.T.); +#25212 = EDGE_LOOP('',(#25213,#25214,#25215,#25216)); +#25213 = ORIENTED_EDGE('',*,*,#24656,.F.); +#25214 = ORIENTED_EDGE('',*,*,#25189,.T.); +#25215 = ORIENTED_EDGE('',*,*,#25140,.T.); +#25216 = ORIENTED_EDGE('',*,*,#24581,.T.); +#25217 = ADVANCED_FACE('',(#25218),#25069,.F.); +#25218 = FACE_BOUND('',#25219,.T.); +#25219 = EDGE_LOOP('',(#25220,#25250,#25271,#25272)); +#25220 = ORIENTED_EDGE('',*,*,#25221,.T.); +#25221 = EDGE_CURVE('',#25222,#25224,#25226,.T.); +#25222 = VERTEX_POINT('',#25223); +#25223 = CARTESIAN_POINT('',(2.2,2.855,3.895)); #25224 = VERTEX_POINT('',#25225); -#25225 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#25225 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); #25226 = SURFACE_CURVE('',#25227,(#25231,#25238),.PCURVE_S1.); #25227 = LINE('',#25228,#25229); -#25228 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#25228 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); #25229 = VECTOR('',#25230,1.); -#25230 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25231 = PCURVE('',#23977,#25232); +#25230 = DIRECTION('',(-1.,-9.856383386232E-017,6.982966722219E-015)); +#25231 = PCURVE('',#25069,#25232); #25232 = DEFINITIONAL_REPRESENTATION('',(#25233),#25237); #25233 = LINE('',#25234,#25235); -#25234 = CARTESIAN_POINT('',(5.5,2.75)); +#25234 = CARTESIAN_POINT('',(-3.673819061467E-016,3.)); #25235 = VECTOR('',#25236,1.); -#25236 = DIRECTION('',(1.,0.E+000)); +#25236 = DIRECTION('',(1.,3.439710880676E-031)); #25237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25238 = PCURVE('',#24648,#25239); -#25239 = DEFINITIONAL_REPRESENTATION('',(#25240),#25244); -#25240 = LINE('',#25241,#25242); -#25241 = CARTESIAN_POINT('',(5.E-002,0.2)); -#25242 = VECTOR('',#25243,1.); -#25243 = DIRECTION('',(2.80259692865E-045,-1.)); -#25244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25245 = ORIENTED_EDGE('',*,*,#25246,.F.); -#25246 = EDGE_CURVE('',#23962,#25224,#25247,.T.); -#25247 = SURFACE_CURVE('',#25248,(#25252,#25259),.PCURVE_S1.); -#25248 = LINE('',#25249,#25250); -#25249 = CARTESIAN_POINT('',(2.5,0.355,2.395)); -#25250 = VECTOR('',#25251,1.); -#25251 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25252 = PCURVE('',#23977,#25253); -#25253 = DEFINITIONAL_REPRESENTATION('',(#25254),#25258); -#25254 = LINE('',#25255,#25256); -#25255 = CARTESIAN_POINT('',(5.5,2.75)); -#25256 = VECTOR('',#25257,1.); -#25257 = DIRECTION('',(0.E+000,-1.)); -#25258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25259 = PCURVE('',#24005,#25260); -#25260 = DEFINITIONAL_REPRESENTATION('',(#25261),#25265); -#25261 = LINE('',#25262,#25263); -#25262 = CARTESIAN_POINT('',(-0.55,-3.001302006402E-016)); -#25263 = VECTOR('',#25264,1.); -#25264 = DIRECTION('',(-1.702510980039E-043,-1.)); -#25265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25266 = ORIENTED_EDGE('',*,*,#23961,.F.); -#25267 = ORIENTED_EDGE('',*,*,#24692,.T.); -#25268 = ORIENTED_EDGE('',*,*,#25269,.T.); -#25269 = EDGE_CURVE('',#24693,#25270,#25272,.T.); -#25270 = VERTEX_POINT('',#25271); -#25271 = CARTESIAN_POINT('',(-2.7,0.355,2.395)); -#25272 = SURFACE_CURVE('',#25273,(#25277,#25284),.PCURVE_S1.); -#25273 = LINE('',#25274,#25275); -#25274 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); -#25275 = VECTOR('',#25276,1.); -#25276 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25277 = PCURVE('',#23977,#25278); -#25278 = DEFINITIONAL_REPRESENTATION('',(#25279),#25283); -#25279 = LINE('',#25280,#25281); -#25280 = CARTESIAN_POINT('',(0.5,2.75)); -#25281 = VECTOR('',#25282,1.); -#25282 = DIRECTION('',(-1.,0.E+000)); -#25283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25284 = PCURVE('',#24753,#25285); -#25285 = DEFINITIONAL_REPRESENTATION('',(#25286),#25290); -#25286 = LINE('',#25287,#25288); -#25287 = CARTESIAN_POINT('',(-5.E-002,-0.2)); -#25288 = VECTOR('',#25289,1.); -#25289 = DIRECTION('',(2.80259692865E-045,1.)); -#25290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25291 = ORIENTED_EDGE('',*,*,#25292,.T.); -#25292 = EDGE_CURVE('',#25270,#24827,#25293,.T.); -#25293 = SURFACE_CURVE('',#25294,(#25298,#25305),.PCURVE_S1.); -#25294 = LINE('',#25295,#25296); -#25295 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); -#25296 = VECTOR('',#25297,1.); -#25297 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25298 = PCURVE('',#23977,#25299); -#25299 = DEFINITIONAL_REPRESENTATION('',(#25300),#25304); -#25300 = LINE('',#25301,#25302); -#25301 = CARTESIAN_POINT('',(0.5,2.75)); -#25302 = VECTOR('',#25303,1.); -#25303 = DIRECTION('',(-1.,0.E+000)); -#25304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25305 = PCURVE('',#24865,#25306); +#25238 = PCURVE('',#25239,#25244); +#25239 = PLANE('',#25240); +#25240 = AXIS2_PLACEMENT_3D('',#25241,#25242,#25243); +#25241 = CARTESIAN_POINT('',(-3.,3.255,3.895)); +#25242 = DIRECTION('',(-7.127527011883E-015,3.491483361109E-015,-1.)); +#25243 = DIRECTION('',(-1.,-5.047298460416E-031,7.127527011883E-015)); +#25244 = DEFINITIONAL_REPRESENTATION('',(#25245),#25249); +#25245 = LINE('',#25246,#25247); +#25246 = CARTESIAN_POINT('',(-0.8,-0.4)); +#25247 = VECTOR('',#25248,1.); +#25248 = DIRECTION('',(1.,-9.856383386232E-017)); +#25249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25250 = ORIENTED_EDGE('',*,*,#25251,.F.); +#25251 = EDGE_CURVE('',#25054,#25224,#25252,.T.); +#25252 = SURFACE_CURVE('',#25253,(#25257,#25264),.PCURVE_S1.); +#25253 = LINE('',#25254,#25255); +#25254 = CARTESIAN_POINT('',(-2.2,2.855,0.895)); +#25255 = VECTOR('',#25256,1.); +#25256 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25257 = PCURVE('',#25069,#25258); +#25258 = DEFINITIONAL_REPRESENTATION('',(#25259),#25263); +#25259 = LINE('',#25260,#25261); +#25260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25261 = VECTOR('',#25262,1.); +#25262 = DIRECTION('',(-1.020425574104E-016,1.)); +#25263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25264 = PCURVE('',#25097,#25265); +#25265 = DEFINITIONAL_REPRESENTATION('',(#25266),#25270); +#25266 = LINE('',#25267,#25268); +#25267 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25268 = VECTOR('',#25269,1.); +#25269 = DIRECTION('',(-1.145632479557E-031,1.)); +#25270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25271 = ORIENTED_EDGE('',*,*,#25053,.F.); +#25272 = ORIENTED_EDGE('',*,*,#25273,.T.); +#25273 = EDGE_CURVE('',#25026,#25222,#25274,.T.); +#25274 = SURFACE_CURVE('',#25275,(#25279,#25286),.PCURVE_S1.); +#25275 = LINE('',#25276,#25277); +#25276 = CARTESIAN_POINT('',(2.2,2.855,0.895)); +#25277 = VECTOR('',#25278,1.); +#25278 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25279 = PCURVE('',#25069,#25280); +#25280 = DEFINITIONAL_REPRESENTATION('',(#25281),#25285); +#25281 = LINE('',#25282,#25283); +#25282 = CARTESIAN_POINT('',(-4.4,-2.812420435427E-017)); +#25283 = VECTOR('',#25284,1.); +#25284 = DIRECTION('',(-1.020425574104E-016,1.)); +#25285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25286 = PCURVE('',#25041,#25287); +#25287 = DEFINITIONAL_REPRESENTATION('',(#25288),#25292); +#25288 = LINE('',#25289,#25290); +#25289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25290 = VECTOR('',#25291,1.); +#25291 = DIRECTION('',(1.145632479557E-031,1.)); +#25292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25293 = ADVANCED_FACE('',(#25294),#25009,.F.); +#25294 = FACE_BOUND('',#25295,.T.); +#25295 = EDGE_LOOP('',(#25296,#25319,#25320,#25343)); +#25296 = ORIENTED_EDGE('',*,*,#25297,.F.); +#25297 = EDGE_CURVE('',#24912,#25298,#25300,.T.); +#25298 = VERTEX_POINT('',#25299); +#25299 = CARTESIAN_POINT('',(-1.4,2.085,2.645)); +#25300 = SURFACE_CURVE('',#25301,(#25305,#25312),.PCURVE_S1.); +#25301 = LINE('',#25302,#25303); +#25302 = CARTESIAN_POINT('',(-1.4,2.085,2.645)); +#25303 = VECTOR('',#25304,1.); +#25304 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25305 = PCURVE('',#25009,#25306); #25306 = DEFINITIONAL_REPRESENTATION('',(#25307),#25311); #25307 = LINE('',#25308,#25309); -#25308 = CARTESIAN_POINT('',(-0.55,-1.240424069632E-029)); +#25308 = CARTESIAN_POINT('',(-1.64,2.45)); #25309 = VECTOR('',#25310,1.); -#25310 = DIRECTION('',(-2.80259692865E-045,1.)); +#25310 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); #25311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25312 = ORIENTED_EDGE('',*,*,#24826,.F.); -#25313 = ORIENTED_EDGE('',*,*,#25314,.F.); -#25314 = EDGE_CURVE('',#25315,#24799,#25317,.T.); -#25315 = VERTEX_POINT('',#25316); -#25316 = CARTESIAN_POINT('',(-1.6,0.355,-0.355)); -#25317 = SURFACE_CURVE('',#25318,(#25322,#25329),.PCURVE_S1.); -#25318 = LINE('',#25319,#25320); -#25319 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25320 = VECTOR('',#25321,1.); -#25321 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#25322 = PCURVE('',#23977,#25323); -#25323 = DEFINITIONAL_REPRESENTATION('',(#25324),#25328); -#25324 = LINE('',#25325,#25326); -#25325 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25326 = VECTOR('',#25327,1.); -#25327 = DIRECTION('',(-1.,1.224606353822E-016)); -#25328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25329 = PCURVE('',#24814,#25330); +#25312 = PCURVE('',#24927,#25313); +#25313 = DEFINITIONAL_REPRESENTATION('',(#25314),#25318); +#25314 = LINE('',#25315,#25316); +#25315 = CARTESIAN_POINT('',(-6.414895964605E-017,-0.2)); +#25316 = VECTOR('',#25317,1.); +#25317 = DIRECTION('',(-1.,4.74549138297E-031)); +#25318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25319 = ORIENTED_EDGE('',*,*,#24995,.T.); +#25320 = ORIENTED_EDGE('',*,*,#25321,.F.); +#25321 = EDGE_CURVE('',#25322,#24968,#25324,.T.); +#25322 = VERTEX_POINT('',#25323); +#25323 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); +#25324 = SURFACE_CURVE('',#25325,(#25329,#25336),.PCURVE_S1.); +#25325 = LINE('',#25326,#25327); +#25326 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); +#25327 = VECTOR('',#25328,1.); +#25328 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25329 = PCURVE('',#25009,#25330); #25330 = DEFINITIONAL_REPRESENTATION('',(#25331),#25335); #25331 = LINE('',#25332,#25333); -#25332 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#25332 = CARTESIAN_POINT('',(-1.99,2.45)); #25333 = VECTOR('',#25334,1.); -#25334 = DIRECTION('',(-1.,0.E+000)); +#25334 = DIRECTION('',(-1.770125995895E-016,-1.)); #25335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25336 = ORIENTED_EDGE('',*,*,#25337,.F.); -#25337 = EDGE_CURVE('',#25338,#25315,#25340,.T.); -#25338 = VERTEX_POINT('',#25339); -#25339 = CARTESIAN_POINT('',(-1.6,0.355,-0.255)); -#25340 = SURFACE_CURVE('',#25341,(#25345,#25352),.PCURVE_S1.); -#25341 = LINE('',#25342,#25343); -#25342 = CARTESIAN_POINT('',(-1.6,0.355,-0.355)); -#25343 = VECTOR('',#25344,1.); -#25344 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25345 = PCURVE('',#23977,#25346); -#25346 = DEFINITIONAL_REPRESENTATION('',(#25347),#25351); -#25347 = LINE('',#25348,#25349); -#25348 = CARTESIAN_POINT('',(1.4,6.170194563616E-017)); -#25349 = VECTOR('',#25350,1.); -#25350 = DIRECTION('',(0.E+000,-1.)); -#25351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25352 = PCURVE('',#25353,#25358); -#25353 = PLANE('',#25354); -#25354 = AXIS2_PLACEMENT_3D('',#25355,#25356,#25357); -#25355 = CARTESIAN_POINT('',(-1.6,0.445,0.195)); -#25356 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25357 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25358 = DEFINITIONAL_REPRESENTATION('',(#25359),#25363); -#25359 = LINE('',#25360,#25361); -#25360 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25361 = VECTOR('',#25362,1.); -#25362 = DIRECTION('',(1.702510980039E-043,-1.)); -#25363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25364 = ORIENTED_EDGE('',*,*,#25365,.T.); -#25365 = EDGE_CURVE('',#25338,#25366,#25368,.T.); -#25366 = VERTEX_POINT('',#25367); -#25367 = CARTESIAN_POINT('',(-1.4,0.355,-0.255)); -#25368 = SURFACE_CURVE('',#25369,(#25373,#25380),.PCURVE_S1.); -#25369 = LINE('',#25370,#25371); -#25370 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); -#25371 = VECTOR('',#25372,1.); -#25372 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25373 = PCURVE('',#23977,#25374); -#25374 = DEFINITIONAL_REPRESENTATION('',(#25375),#25379); -#25375 = LINE('',#25376,#25377); -#25376 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); -#25377 = VECTOR('',#25378,1.); -#25378 = DIRECTION('',(1.,0.E+000)); -#25379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25380 = PCURVE('',#25381,#25386); -#25381 = PLANE('',#25382); -#25382 = AXIS2_PLACEMENT_3D('',#25383,#25384,#25385); -#25383 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#25384 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); -#25385 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); -#25386 = DEFINITIONAL_REPRESENTATION('',(#25387),#25391); -#25387 = LINE('',#25388,#25389); -#25388 = CARTESIAN_POINT('',(-6.E-002,1.4)); -#25389 = VECTOR('',#25390,1.); -#25390 = DIRECTION('',(-1.642146637881E-047,-1.)); -#25391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25392 = ORIENTED_EDGE('',*,*,#25393,.T.); -#25393 = EDGE_CURVE('',#25366,#25394,#25396,.T.); -#25394 = VERTEX_POINT('',#25395); -#25395 = CARTESIAN_POINT('',(-1.4,0.355,-0.355)); -#25396 = SURFACE_CURVE('',#25397,(#25401,#25408),.PCURVE_S1.); +#25336 = PCURVE('',#24983,#25337); +#25337 = DEFINITIONAL_REPRESENTATION('',(#25338),#25342); +#25338 = LINE('',#25339,#25340); +#25339 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); +#25340 = VECTOR('',#25341,1.); +#25341 = DIRECTION('',(-1.,0.E+000)); +#25342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25343 = ORIENTED_EDGE('',*,*,#25344,.F.); +#25344 = EDGE_CURVE('',#25298,#25322,#25345,.T.); +#25345 = SURFACE_CURVE('',#25346,(#25350,#25357),.PCURVE_S1.); +#25346 = LINE('',#25347,#25348); +#25347 = CARTESIAN_POINT('',(-1.4,2.435,2.645)); +#25348 = VECTOR('',#25349,1.); +#25349 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25350 = PCURVE('',#25009,#25351); +#25351 = DEFINITIONAL_REPRESENTATION('',(#25352),#25356); +#25352 = LINE('',#25353,#25354); +#25353 = CARTESIAN_POINT('',(-1.99,2.45)); +#25354 = VECTOR('',#25355,1.); +#25355 = DIRECTION('',(-1.,1.702510980039E-043)); +#25356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25357 = PCURVE('',#25358,#25363); +#25358 = PLANE('',#25359); +#25359 = AXIS2_PLACEMENT_3D('',#25360,#25361,#25362); +#25360 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); +#25361 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#25362 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#25363 = DEFINITIONAL_REPRESENTATION('',(#25364),#25368); +#25364 = LINE('',#25365,#25366); +#25365 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); +#25366 = VECTOR('',#25367,1.); +#25367 = DIRECTION('',(-1.,0.E+000)); +#25368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25369 = ADVANCED_FACE('',(#25370),#25041,.F.); +#25370 = FACE_BOUND('',#25371,.T.); +#25371 = EDGE_LOOP('',(#25372,#25402,#25430,#25451,#25452,#25453,#25476, + #25499)); +#25372 = ORIENTED_EDGE('',*,*,#25373,.F.); +#25373 = EDGE_CURVE('',#25374,#25376,#25378,.T.); +#25374 = VERTEX_POINT('',#25375); +#25375 = CARTESIAN_POINT('',(2.2,2.355,1.495)); +#25376 = VERTEX_POINT('',#25377); +#25377 = CARTESIAN_POINT('',(2.2,1.755,1.495)); +#25378 = SURFACE_CURVE('',#25379,(#25383,#25390),.PCURVE_S1.); +#25379 = LINE('',#25380,#25381); +#25380 = CARTESIAN_POINT('',(2.2,2.355,1.495)); +#25381 = VECTOR('',#25382,1.); +#25382 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#25383 = PCURVE('',#25041,#25384); +#25384 = DEFINITIONAL_REPRESENTATION('',(#25385),#25389); +#25385 = LINE('',#25386,#25387); +#25386 = CARTESIAN_POINT('',(-0.5,0.6)); +#25387 = VECTOR('',#25388,1.); +#25388 = DIRECTION('',(-1.,-1.145632479557E-031)); +#25389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25390 = PCURVE('',#25391,#25396); +#25391 = PLANE('',#25392); +#25392 = AXIS2_PLACEMENT_3D('',#25393,#25394,#25395); +#25393 = CARTESIAN_POINT('',(2.2,1.755,1.495)); +#25394 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#25395 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25396 = DEFINITIONAL_REPRESENTATION('',(#25397),#25401); #25397 = LINE('',#25398,#25399); -#25398 = CARTESIAN_POINT('',(-1.4,0.355,-0.355)); +#25398 = CARTESIAN_POINT('',(0.6,1.395477078336E-029)); #25399 = VECTOR('',#25400,1.); -#25400 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25401 = PCURVE('',#23977,#25402); -#25402 = DEFINITIONAL_REPRESENTATION('',(#25403),#25407); -#25403 = LINE('',#25404,#25405); -#25404 = CARTESIAN_POINT('',(1.6,1.500535806721E-017)); -#25405 = VECTOR('',#25406,1.); -#25406 = DIRECTION('',(0.E+000,-1.)); -#25407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25408 = PCURVE('',#25409,#25414); -#25409 = PLANE('',#25410); -#25410 = AXIS2_PLACEMENT_3D('',#25411,#25412,#25413); -#25411 = CARTESIAN_POINT('',(-1.4,0.445,0.195)); -#25412 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25413 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25414 = DEFINITIONAL_REPRESENTATION('',(#25415),#25419); -#25415 = LINE('',#25416,#25417); -#25416 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25417 = VECTOR('',#25418,1.); -#25418 = DIRECTION('',(1.702510980039E-043,-1.)); -#25419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25420 = ORIENTED_EDGE('',*,*,#25421,.F.); -#25421 = EDGE_CURVE('',#25422,#25394,#25424,.T.); -#25422 = VERTEX_POINT('',#25423); -#25423 = CARTESIAN_POINT('',(-0.6,0.355,-0.355)); -#25424 = SURFACE_CURVE('',#25425,(#25429,#25436),.PCURVE_S1.); +#25400 = DIRECTION('',(-1.,0.E+000)); +#25401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25402 = ORIENTED_EDGE('',*,*,#25403,.T.); +#25403 = EDGE_CURVE('',#25374,#25404,#25406,.T.); +#25404 = VERTEX_POINT('',#25405); +#25405 = CARTESIAN_POINT('',(2.2,2.355,3.895)); +#25406 = SURFACE_CURVE('',#25407,(#25411,#25418),.PCURVE_S1.); +#25407 = LINE('',#25408,#25409); +#25408 = CARTESIAN_POINT('',(2.2,2.355,1.495)); +#25409 = VECTOR('',#25410,1.); +#25410 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25411 = PCURVE('',#25041,#25412); +#25412 = DEFINITIONAL_REPRESENTATION('',(#25413),#25417); +#25413 = LINE('',#25414,#25415); +#25414 = CARTESIAN_POINT('',(-0.5,0.6)); +#25415 = VECTOR('',#25416,1.); +#25416 = DIRECTION('',(1.145632479557E-031,1.)); +#25417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25418 = PCURVE('',#25419,#25424); +#25419 = PLANE('',#25420); +#25420 = AXIS2_PLACEMENT_3D('',#25421,#25422,#25423); +#25421 = CARTESIAN_POINT('',(2.2,2.355,1.495)); +#25422 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25423 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); +#25424 = DEFINITIONAL_REPRESENTATION('',(#25425),#25429); #25425 = LINE('',#25426,#25427); -#25426 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#25426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25427 = VECTOR('',#25428,1.); -#25428 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#25429 = PCURVE('',#23977,#25430); -#25430 = DEFINITIONAL_REPRESENTATION('',(#25431),#25435); -#25431 = LINE('',#25432,#25433); -#25432 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25433 = VECTOR('',#25434,1.); -#25434 = DIRECTION('',(-1.,1.224606353822E-016)); -#25435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25436 = PCURVE('',#24814,#25437); -#25437 = DEFINITIONAL_REPRESENTATION('',(#25438),#25442); -#25438 = LINE('',#25439,#25440); -#25439 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); -#25440 = VECTOR('',#25441,1.); -#25441 = DIRECTION('',(-1.,0.E+000)); -#25442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25443 = ORIENTED_EDGE('',*,*,#25444,.F.); -#25444 = EDGE_CURVE('',#25445,#25422,#25447,.T.); -#25445 = VERTEX_POINT('',#25446); -#25446 = CARTESIAN_POINT('',(-0.6,0.355,-0.255)); -#25447 = SURFACE_CURVE('',#25448,(#25452,#25459),.PCURVE_S1.); -#25448 = LINE('',#25449,#25450); -#25449 = CARTESIAN_POINT('',(-0.6,0.355,-0.355)); -#25450 = VECTOR('',#25451,1.); -#25451 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25452 = PCURVE('',#23977,#25453); -#25453 = DEFINITIONAL_REPRESENTATION('',(#25454),#25458); -#25454 = LINE('',#25455,#25456); -#25455 = CARTESIAN_POINT('',(2.4,5.026361271644E-017)); -#25456 = VECTOR('',#25457,1.); -#25457 = DIRECTION('',(0.E+000,-1.)); -#25458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25459 = PCURVE('',#25460,#25465); -#25460 = PLANE('',#25461); -#25461 = AXIS2_PLACEMENT_3D('',#25462,#25463,#25464); -#25462 = CARTESIAN_POINT('',(-0.6,0.445,0.195)); -#25463 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25464 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25465 = DEFINITIONAL_REPRESENTATION('',(#25466),#25470); -#25466 = LINE('',#25467,#25468); -#25467 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25468 = VECTOR('',#25469,1.); -#25469 = DIRECTION('',(1.702510980039E-043,-1.)); -#25470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25471 = ORIENTED_EDGE('',*,*,#25472,.T.); -#25472 = EDGE_CURVE('',#25445,#25473,#25475,.T.); -#25473 = VERTEX_POINT('',#25474); -#25474 = CARTESIAN_POINT('',(-0.4,0.355,-0.255)); -#25475 = SURFACE_CURVE('',#25476,(#25480,#25487),.PCURVE_S1.); -#25476 = LINE('',#25477,#25478); -#25477 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); -#25478 = VECTOR('',#25479,1.); -#25479 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25480 = PCURVE('',#23977,#25481); -#25481 = DEFINITIONAL_REPRESENTATION('',(#25482),#25486); -#25482 = LINE('',#25483,#25484); -#25483 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); -#25484 = VECTOR('',#25485,1.); -#25485 = DIRECTION('',(1.,0.E+000)); -#25486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25487 = PCURVE('',#25488,#25493); -#25488 = PLANE('',#25489); -#25489 = AXIS2_PLACEMENT_3D('',#25490,#25491,#25492); -#25490 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#25491 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); -#25492 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); +#25428 = DIRECTION('',(-1.020425574104E-016,1.)); +#25429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25430 = ORIENTED_EDGE('',*,*,#25431,.T.); +#25431 = EDGE_CURVE('',#25404,#25222,#25432,.T.); +#25432 = SURFACE_CURVE('',#25433,(#25437,#25444),.PCURVE_S1.); +#25433 = LINE('',#25434,#25435); +#25434 = CARTESIAN_POINT('',(2.2,2.855,3.895)); +#25435 = VECTOR('',#25436,1.); +#25436 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); +#25437 = PCURVE('',#25041,#25438); +#25438 = DEFINITIONAL_REPRESENTATION('',(#25439),#25443); +#25439 = LINE('',#25440,#25441); +#25440 = CARTESIAN_POINT('',(-1.836909530734E-016,3.)); +#25441 = VECTOR('',#25442,1.); +#25442 = DIRECTION('',(1.,1.145632479557E-031)); +#25443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25444 = PCURVE('',#25239,#25445); +#25445 = DEFINITIONAL_REPRESENTATION('',(#25446),#25450); +#25446 = LINE('',#25447,#25448); +#25447 = CARTESIAN_POINT('',(-5.2,-0.4)); +#25448 = VECTOR('',#25449,1.); +#25449 = DIRECTION('',(2.06514699521E-016,1.)); +#25450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25451 = ORIENTED_EDGE('',*,*,#25273,.F.); +#25452 = ORIENTED_EDGE('',*,*,#25023,.F.); +#25453 = ORIENTED_EDGE('',*,*,#25454,.T.); +#25454 = EDGE_CURVE('',#25024,#25455,#25457,.T.); +#25455 = VERTEX_POINT('',#25456); +#25456 = CARTESIAN_POINT('',(2.2,0.755,3.895)); +#25457 = SURFACE_CURVE('',#25458,(#25462,#25469),.PCURVE_S1.); +#25458 = LINE('',#25459,#25460); +#25459 = CARTESIAN_POINT('',(2.2,0.755,0.895)); +#25460 = VECTOR('',#25461,1.); +#25461 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25462 = PCURVE('',#25041,#25463); +#25463 = DEFINITIONAL_REPRESENTATION('',(#25464),#25468); +#25464 = LINE('',#25465,#25466); +#25465 = CARTESIAN_POINT('',(-2.1,4.643095803673E-018)); +#25466 = VECTOR('',#25467,1.); +#25467 = DIRECTION('',(1.145632479557E-031,1.)); +#25468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25469 = PCURVE('',#25123,#25470); +#25470 = DEFINITIONAL_REPRESENTATION('',(#25471),#25475); +#25471 = LINE('',#25472,#25473); +#25472 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25473 = VECTOR('',#25474,1.); +#25474 = DIRECTION('',(1.020425574104E-016,1.)); +#25475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25476 = ORIENTED_EDGE('',*,*,#25477,.T.); +#25477 = EDGE_CURVE('',#25455,#25478,#25480,.T.); +#25478 = VERTEX_POINT('',#25479); +#25479 = CARTESIAN_POINT('',(2.2,1.755,3.895)); +#25480 = SURFACE_CURVE('',#25481,(#25485,#25492),.PCURVE_S1.); +#25481 = LINE('',#25482,#25483); +#25482 = CARTESIAN_POINT('',(2.2,2.855,3.895)); +#25483 = VECTOR('',#25484,1.); +#25484 = DIRECTION('',(-2.06514699521E-016,1.,3.491483361109E-015)); +#25485 = PCURVE('',#25041,#25486); +#25486 = DEFINITIONAL_REPRESENTATION('',(#25487),#25491); +#25487 = LINE('',#25488,#25489); +#25488 = CARTESIAN_POINT('',(-1.836909530734E-016,3.)); +#25489 = VECTOR('',#25490,1.); +#25490 = DIRECTION('',(1.,1.145632479557E-031)); +#25491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25492 = PCURVE('',#25239,#25493); #25493 = DEFINITIONAL_REPRESENTATION('',(#25494),#25498); #25494 = LINE('',#25495,#25496); -#25495 = CARTESIAN_POINT('',(-6.E-002,2.4)); +#25495 = CARTESIAN_POINT('',(-5.2,-0.4)); #25496 = VECTOR('',#25497,1.); -#25497 = DIRECTION('',(-1.642146637881E-047,-1.)); +#25497 = DIRECTION('',(2.06514699521E-016,1.)); #25498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25499 = ORIENTED_EDGE('',*,*,#25500,.T.); -#25500 = EDGE_CURVE('',#25473,#25501,#25503,.T.); -#25501 = VERTEX_POINT('',#25502); -#25502 = CARTESIAN_POINT('',(-0.4,0.355,-0.355)); -#25503 = SURFACE_CURVE('',#25504,(#25508,#25515),.PCURVE_S1.); -#25504 = LINE('',#25505,#25506); -#25505 = CARTESIAN_POINT('',(-0.4,0.355,-0.355)); -#25506 = VECTOR('',#25507,1.); -#25507 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25508 = PCURVE('',#23977,#25509); -#25509 = DEFINITIONAL_REPRESENTATION('',(#25510),#25514); -#25510 = LINE('',#25511,#25512); -#25511 = CARTESIAN_POINT('',(2.6,3.567025147487E-018)); -#25512 = VECTOR('',#25513,1.); -#25513 = DIRECTION('',(0.E+000,-1.)); -#25514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25515 = PCURVE('',#25516,#25521); -#25516 = PLANE('',#25517); -#25517 = AXIS2_PLACEMENT_3D('',#25518,#25519,#25520); -#25518 = CARTESIAN_POINT('',(-0.4,0.445,0.195)); -#25519 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25520 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25521 = DEFINITIONAL_REPRESENTATION('',(#25522),#25526); -#25522 = LINE('',#25523,#25524); -#25523 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25524 = VECTOR('',#25525,1.); -#25525 = DIRECTION('',(1.702510980039E-043,-1.)); -#25526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25527 = ORIENTED_EDGE('',*,*,#25528,.F.); -#25528 = EDGE_CURVE('',#25529,#25501,#25531,.T.); -#25529 = VERTEX_POINT('',#25530); -#25530 = CARTESIAN_POINT('',(0.4,0.355,-0.355)); -#25531 = SURFACE_CURVE('',#25532,(#25536,#25543),.PCURVE_S1.); -#25532 = LINE('',#25533,#25534); -#25533 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25534 = VECTOR('',#25535,1.); -#25535 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#25536 = PCURVE('',#23977,#25537); -#25537 = DEFINITIONAL_REPRESENTATION('',(#25538),#25542); -#25538 = LINE('',#25539,#25540); -#25539 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25540 = VECTOR('',#25541,1.); -#25541 = DIRECTION('',(-1.,1.224606353822E-016)); -#25542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25543 = PCURVE('',#24814,#25544); -#25544 = DEFINITIONAL_REPRESENTATION('',(#25545),#25549); -#25545 = LINE('',#25546,#25547); -#25546 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); -#25547 = VECTOR('',#25548,1.); -#25548 = DIRECTION('',(-1.,0.E+000)); -#25549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25550 = ORIENTED_EDGE('',*,*,#25551,.F.); -#25551 = EDGE_CURVE('',#25552,#25529,#25554,.T.); -#25552 = VERTEX_POINT('',#25553); -#25553 = CARTESIAN_POINT('',(0.4,0.355,-0.255)); -#25554 = SURFACE_CURVE('',#25555,(#25559,#25566),.PCURVE_S1.); -#25555 = LINE('',#25556,#25557); -#25556 = CARTESIAN_POINT('',(0.4,0.355,-0.355)); -#25557 = VECTOR('',#25558,1.); -#25558 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25559 = PCURVE('',#23977,#25560); -#25560 = DEFINITIONAL_REPRESENTATION('',(#25561),#25565); -#25561 = LINE('',#25562,#25563); -#25562 = CARTESIAN_POINT('',(3.4,3.882527979672E-017)); -#25563 = VECTOR('',#25564,1.); -#25564 = DIRECTION('',(0.E+000,-1.)); -#25565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25566 = PCURVE('',#25567,#25572); -#25567 = PLANE('',#25568); -#25568 = AXIS2_PLACEMENT_3D('',#25569,#25570,#25571); -#25569 = CARTESIAN_POINT('',(0.4,0.445,0.195)); -#25570 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25571 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25572 = DEFINITIONAL_REPRESENTATION('',(#25573),#25577); -#25573 = LINE('',#25574,#25575); -#25574 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25575 = VECTOR('',#25576,1.); -#25576 = DIRECTION('',(1.702510980039E-043,-1.)); -#25577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25578 = ORIENTED_EDGE('',*,*,#25579,.T.); -#25579 = EDGE_CURVE('',#25552,#25580,#25582,.T.); -#25580 = VERTEX_POINT('',#25581); -#25581 = CARTESIAN_POINT('',(0.6,0.355,-0.255)); -#25582 = SURFACE_CURVE('',#25583,(#25587,#25594),.PCURVE_S1.); -#25583 = LINE('',#25584,#25585); -#25584 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); -#25585 = VECTOR('',#25586,1.); -#25586 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#25587 = PCURVE('',#23977,#25588); -#25588 = DEFINITIONAL_REPRESENTATION('',(#25589),#25593); -#25589 = LINE('',#25590,#25591); -#25590 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); -#25591 = VECTOR('',#25592,1.); -#25592 = DIRECTION('',(1.,0.E+000)); -#25593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25594 = PCURVE('',#25595,#25600); -#25595 = PLANE('',#25596); -#25596 = AXIS2_PLACEMENT_3D('',#25597,#25598,#25599); -#25597 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#25598 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); -#25599 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); -#25600 = DEFINITIONAL_REPRESENTATION('',(#25601),#25605); -#25601 = LINE('',#25602,#25603); -#25602 = CARTESIAN_POINT('',(-6.E-002,3.4)); -#25603 = VECTOR('',#25604,1.); -#25604 = DIRECTION('',(-1.642146637881E-047,-1.)); -#25605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25606 = ORIENTED_EDGE('',*,*,#25607,.T.); -#25607 = EDGE_CURVE('',#25580,#25608,#25610,.T.); -#25608 = VERTEX_POINT('',#25609); -#25609 = CARTESIAN_POINT('',(0.6,0.355,-0.355)); -#25610 = SURFACE_CURVE('',#25611,(#25615,#25622),.PCURVE_S1.); -#25611 = LINE('',#25612,#25613); -#25612 = CARTESIAN_POINT('',(0.6,0.355,-0.355)); -#25613 = VECTOR('',#25614,1.); -#25614 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25615 = PCURVE('',#23977,#25616); -#25616 = DEFINITIONAL_REPRESENTATION('',(#25617),#25621); -#25617 = LINE('',#25618,#25619); -#25618 = CARTESIAN_POINT('',(3.6,-7.871307772235E-018)); -#25619 = VECTOR('',#25620,1.); -#25620 = DIRECTION('',(0.E+000,-1.)); -#25621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25622 = PCURVE('',#25623,#25628); -#25623 = PLANE('',#25624); -#25624 = AXIS2_PLACEMENT_3D('',#25625,#25626,#25627); -#25625 = CARTESIAN_POINT('',(0.6,0.445,0.195)); -#25626 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25627 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25628 = DEFINITIONAL_REPRESENTATION('',(#25629),#25633); -#25629 = LINE('',#25630,#25631); -#25630 = CARTESIAN_POINT('',(9.E-002,-0.55)); -#25631 = VECTOR('',#25632,1.); -#25632 = DIRECTION('',(1.702510980039E-043,-1.)); -#25633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25634 = ORIENTED_EDGE('',*,*,#25635,.F.); -#25635 = EDGE_CURVE('',#25066,#25608,#25636,.T.); -#25636 = SURFACE_CURVE('',#25637,(#25641,#25648),.PCURVE_S1.); -#25637 = LINE('',#25638,#25639); -#25638 = CARTESIAN_POINT('',(3.,0.355,-0.355)); -#25639 = VECTOR('',#25640,1.); -#25640 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#25641 = PCURVE('',#23977,#25642); -#25642 = DEFINITIONAL_REPRESENTATION('',(#25643),#25647); -#25643 = LINE('',#25644,#25645); -#25644 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); -#25645 = VECTOR('',#25646,1.); -#25646 = DIRECTION('',(-1.,1.224606353822E-016)); -#25647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25648 = PCURVE('',#24814,#25649); +#25499 = ORIENTED_EDGE('',*,*,#25500,.F.); +#25500 = EDGE_CURVE('',#25376,#25478,#25501,.T.); +#25501 = SURFACE_CURVE('',#25502,(#25506,#25513),.PCURVE_S1.); +#25502 = LINE('',#25503,#25504); +#25503 = CARTESIAN_POINT('',(2.2,1.755,1.495)); +#25504 = VECTOR('',#25505,1.); +#25505 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25506 = PCURVE('',#25041,#25507); +#25507 = DEFINITIONAL_REPRESENTATION('',(#25508),#25512); +#25508 = LINE('',#25509,#25510); +#25509 = CARTESIAN_POINT('',(-1.1,0.6)); +#25510 = VECTOR('',#25511,1.); +#25511 = DIRECTION('',(1.145632479557E-031,1.)); +#25512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25513 = PCURVE('',#25514,#25519); +#25514 = PLANE('',#25515); +#25515 = AXIS2_PLACEMENT_3D('',#25516,#25517,#25518); +#25516 = CARTESIAN_POINT('',(2.2,1.755,1.495)); +#25517 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#25518 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); +#25519 = DEFINITIONAL_REPRESENTATION('',(#25520),#25524); +#25520 = LINE('',#25521,#25522); +#25521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25522 = VECTOR('',#25523,1.); +#25523 = DIRECTION('',(1.020425574104E-016,1.)); +#25524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25525 = ADVANCED_FACE('',(#25526),#24869,.F.); +#25526 = FACE_BOUND('',#25527,.T.); +#25527 = EDGE_LOOP('',(#25528,#25551,#25552,#25575)); +#25528 = ORIENTED_EDGE('',*,*,#25529,.T.); +#25529 = EDGE_CURVE('',#25530,#24854,#25532,.T.); +#25530 = VERTEX_POINT('',#25531); +#25531 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); +#25532 = SURFACE_CURVE('',#25533,(#25537,#25544),.PCURVE_S1.); +#25533 = LINE('',#25534,#25535); +#25534 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); +#25535 = VECTOR('',#25536,1.); +#25536 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25537 = PCURVE('',#24869,#25538); +#25538 = DEFINITIONAL_REPRESENTATION('',(#25539),#25543); +#25539 = LINE('',#25540,#25541); +#25540 = CARTESIAN_POINT('',(-3.797634949565E-016,-0.2)); +#25541 = VECTOR('',#25542,1.); +#25542 = DIRECTION('',(-1.,0.E+000)); +#25543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25544 = PCURVE('',#24895,#25545); +#25545 = DEFINITIONAL_REPRESENTATION('',(#25546),#25550); +#25546 = LINE('',#25547,#25548); +#25547 = CARTESIAN_POINT('',(-1.99,2.45)); +#25548 = VECTOR('',#25549,1.); +#25549 = DIRECTION('',(-1.770125995895E-016,-1.)); +#25550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25551 = ORIENTED_EDGE('',*,*,#24853,.T.); +#25552 = ORIENTED_EDGE('',*,*,#25553,.F.); +#25553 = EDGE_CURVE('',#25554,#24826,#25556,.T.); +#25554 = VERTEX_POINT('',#25555); +#25555 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#25556 = SURFACE_CURVE('',#25557,(#25561,#25568),.PCURVE_S1.); +#25557 = LINE('',#25558,#25559); +#25558 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#25559 = VECTOR('',#25560,1.); +#25560 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25561 = PCURVE('',#24869,#25562); +#25562 = DEFINITIONAL_REPRESENTATION('',(#25563),#25567); +#25563 = LINE('',#25564,#25565); +#25564 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25565 = VECTOR('',#25566,1.); +#25566 = DIRECTION('',(-1.,0.E+000)); +#25567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25568 = PCURVE('',#24841,#25569); +#25569 = DEFINITIONAL_REPRESENTATION('',(#25570),#25574); +#25570 = LINE('',#25571,#25572); +#25571 = CARTESIAN_POINT('',(-1.99,2.45)); +#25572 = VECTOR('',#25573,1.); +#25573 = DIRECTION('',(-1.770125995895E-016,-1.)); +#25574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25575 = ORIENTED_EDGE('',*,*,#25576,.T.); +#25576 = EDGE_CURVE('',#25554,#25530,#25577,.T.); +#25577 = SURFACE_CURVE('',#25578,(#25582,#25589),.PCURVE_S1.); +#25578 = LINE('',#25579,#25580); +#25579 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#25580 = VECTOR('',#25581,1.); +#25581 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#25582 = PCURVE('',#24869,#25583); +#25583 = DEFINITIONAL_REPRESENTATION('',(#25584),#25588); +#25584 = LINE('',#25585,#25586); +#25585 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25586 = VECTOR('',#25587,1.); +#25587 = DIRECTION('',(0.E+000,-1.)); +#25588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25589 = PCURVE('',#25590,#25595); +#25590 = PLANE('',#25591); +#25591 = AXIS2_PLACEMENT_3D('',#25592,#25593,#25594); +#25592 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#25593 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#25594 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#25595 = DEFINITIONAL_REPRESENTATION('',(#25596),#25600); +#25596 = LINE('',#25597,#25598); +#25597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25598 = VECTOR('',#25599,1.); +#25599 = DIRECTION('',(-2.80259692865E-045,-1.)); +#25600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25601 = ADVANCED_FACE('',(#25602),#24699,.F.); +#25602 = FACE_BOUND('',#25603,.T.); +#25603 = EDGE_LOOP('',(#25604,#25627,#25655,#25676)); +#25604 = ORIENTED_EDGE('',*,*,#25605,.T.); +#25605 = EDGE_CURVE('',#24684,#25606,#25608,.T.); +#25606 = VERTEX_POINT('',#25607); +#25607 = CARTESIAN_POINT('',(0.6,2.085,2.645)); +#25608 = SURFACE_CURVE('',#25609,(#25613,#25620),.PCURVE_S1.); +#25609 = LINE('',#25610,#25611); +#25610 = CARTESIAN_POINT('',(0.6,2.085,2.645)); +#25611 = VECTOR('',#25612,1.); +#25612 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25613 = PCURVE('',#24699,#25614); +#25614 = DEFINITIONAL_REPRESENTATION('',(#25615),#25619); +#25615 = LINE('',#25616,#25617); +#25616 = CARTESIAN_POINT('',(3.787199746371E-016,-0.2)); +#25617 = VECTOR('',#25618,1.); +#25618 = DIRECTION('',(-1.,4.74549138297E-031)); +#25619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25620 = PCURVE('',#24781,#25621); +#25621 = DEFINITIONAL_REPRESENTATION('',(#25622),#25626); +#25622 = LINE('',#25623,#25624); +#25623 = CARTESIAN_POINT('',(-1.64,2.45)); +#25624 = VECTOR('',#25625,1.); +#25625 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25627 = ORIENTED_EDGE('',*,*,#25628,.F.); +#25628 = EDGE_CURVE('',#25629,#25606,#25631,.T.); +#25629 = VERTEX_POINT('',#25630); +#25630 = CARTESIAN_POINT('',(0.4,2.085,2.645)); +#25631 = SURFACE_CURVE('',#25632,(#25636,#25643),.PCURVE_S1.); +#25632 = LINE('',#25633,#25634); +#25633 = CARTESIAN_POINT('',(0.4,2.085,2.645)); +#25634 = VECTOR('',#25635,1.); +#25635 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#25636 = PCURVE('',#24699,#25637); +#25637 = DEFINITIONAL_REPRESENTATION('',(#25638),#25642); +#25638 = LINE('',#25639,#25640); +#25639 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25640 = VECTOR('',#25641,1.); +#25641 = DIRECTION('',(-1.109335647967E-030,-1.)); +#25642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25643 = PCURVE('',#25644,#25649); +#25644 = PLANE('',#25645); +#25645 = AXIS2_PLACEMENT_3D('',#25646,#25647,#25648); +#25646 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#25647 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#25648 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); #25649 = DEFINITIONAL_REPRESENTATION('',(#25650),#25654); #25650 = LINE('',#25651,#25652); -#25651 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#25651 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); #25652 = VECTOR('',#25653,1.); -#25653 = DIRECTION('',(-1.,0.E+000)); +#25653 = DIRECTION('',(-2.80259692865E-045,-1.)); #25654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25655 = ADVANCED_FACE('',(#25656),#23865,.T.); -#25656 = FACE_BOUND('',#25657,.T.); -#25657 = EDGE_LOOP('',(#25658,#25681,#25682,#25683)); -#25658 = ORIENTED_EDGE('',*,*,#25659,.T.); -#25659 = EDGE_CURVE('',#25660,#23848,#25662,.T.); -#25660 = VERTEX_POINT('',#25661); -#25661 = CARTESIAN_POINT('',(-2.7,1.555,3.395)); -#25662 = SURFACE_CURVE('',#25663,(#25667,#25674),.PCURVE_S1.); -#25663 = LINE('',#25664,#25665); -#25664 = CARTESIAN_POINT('',(-2.7,1.555,2.595)); -#25665 = VECTOR('',#25666,1.); -#25666 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#25667 = PCURVE('',#23865,#25668); -#25668 = DEFINITIONAL_REPRESENTATION('',(#25669),#25673); -#25669 = LINE('',#25670,#25671); -#25670 = CARTESIAN_POINT('',(-1.3,0.2)); -#25671 = VECTOR('',#25672,1.); -#25672 = DIRECTION('',(1.,0.E+000)); -#25673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25674 = PCURVE('',#23893,#25675); -#25675 = DEFINITIONAL_REPRESENTATION('',(#25676),#25680); -#25676 = LINE('',#25677,#25678); -#25677 = CARTESIAN_POINT('',(0.65,-0.2)); -#25678 = VECTOR('',#25679,1.); -#25679 = DIRECTION('',(1.702510980039E-043,-1.)); -#25680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25681 = ORIENTED_EDGE('',*,*,#23847,.T.); -#25682 = ORIENTED_EDGE('',*,*,#24933,.F.); -#25683 = ORIENTED_EDGE('',*,*,#25684,.F.); -#25684 = EDGE_CURVE('',#25660,#24906,#25685,.T.); -#25685 = SURFACE_CURVE('',#25686,(#25690,#25697),.PCURVE_S1.); -#25686 = LINE('',#25687,#25688); -#25687 = CARTESIAN_POINT('',(-2.5,1.555,3.395)); -#25688 = VECTOR('',#25689,1.); -#25689 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25690 = PCURVE('',#23865,#25691); -#25691 = DEFINITIONAL_REPRESENTATION('',(#25692),#25696); -#25692 = LINE('',#25693,#25694); -#25693 = CARTESIAN_POINT('',(-0.5,6.123031769112E-017)); -#25694 = VECTOR('',#25695,1.); -#25695 = DIRECTION('',(0.E+000,1.)); -#25696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25697 = PCURVE('',#24921,#25698); -#25698 = DEFINITIONAL_REPRESENTATION('',(#25699),#25703); -#25699 = LINE('',#25700,#25701); -#25700 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#25701 = VECTOR('',#25702,1.); -#25702 = DIRECTION('',(-2.80259692865E-045,1.)); -#25703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25704 = ADVANCED_FACE('',(#25705),#24061,.T.); -#25705 = FACE_BOUND('',#25706,.T.); -#25706 = EDGE_LOOP('',(#25707,#25737,#25758,#25759,#25760,#25781,#25804) - ); -#25707 = ORIENTED_EDGE('',*,*,#25708,.T.); -#25708 = EDGE_CURVE('',#25709,#25711,#25713,.T.); -#25709 = VERTEX_POINT('',#25710); -#25710 = CARTESIAN_POINT('',(2.7,0.905,3.395)); -#25711 = VERTEX_POINT('',#25712); -#25712 = CARTESIAN_POINT('',(2.7,1.555,3.395)); -#25713 = SURFACE_CURVE('',#25714,(#25718,#25725),.PCURVE_S1.); +#25655 = ORIENTED_EDGE('',*,*,#25656,.F.); +#25656 = EDGE_CURVE('',#24682,#25629,#25657,.T.); +#25657 = SURFACE_CURVE('',#25658,(#25662,#25669),.PCURVE_S1.); +#25658 = LINE('',#25659,#25660); +#25659 = CARTESIAN_POINT('',(0.4,2.085,2.645)); +#25660 = VECTOR('',#25661,1.); +#25661 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25662 = PCURVE('',#24699,#25663); +#25663 = DEFINITIONAL_REPRESENTATION('',(#25664),#25668); +#25664 = LINE('',#25665,#25666); +#25665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25666 = VECTOR('',#25667,1.); +#25667 = DIRECTION('',(-1.,4.74549138297E-031)); +#25668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25669 = PCURVE('',#24727,#25670); +#25670 = DEFINITIONAL_REPRESENTATION('',(#25671),#25675); +#25671 = LINE('',#25672,#25673); +#25672 = CARTESIAN_POINT('',(-1.64,2.45)); +#25673 = VECTOR('',#25674,1.); +#25674 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25676 = ORIENTED_EDGE('',*,*,#24681,.T.); +#25677 = ADVANCED_FACE('',(#25678),#25123,.F.); +#25678 = FACE_BOUND('',#25679,.T.); +#25679 = EDGE_LOOP('',(#25680,#25703,#25704,#25705)); +#25680 = ORIENTED_EDGE('',*,*,#25681,.T.); +#25681 = EDGE_CURVE('',#25682,#25455,#25684,.T.); +#25682 = VERTEX_POINT('',#25683); +#25683 = CARTESIAN_POINT('',(-2.2,0.755,3.895)); +#25684 = SURFACE_CURVE('',#25685,(#25689,#25696),.PCURVE_S1.); +#25685 = LINE('',#25686,#25687); +#25686 = CARTESIAN_POINT('',(2.2,0.755,3.895)); +#25687 = VECTOR('',#25688,1.); +#25688 = DIRECTION('',(1.,1.232047923279E-016,-6.982966722219E-015)); +#25689 = PCURVE('',#25123,#25690); +#25690 = DEFINITIONAL_REPRESENTATION('',(#25691),#25695); +#25691 = LINE('',#25692,#25693); +#25692 = CARTESIAN_POINT('',(3.673819061467E-016,3.)); +#25693 = VECTOR('',#25694,1.); +#25694 = DIRECTION('',(1.,3.586081556449E-031)); +#25695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25696 = PCURVE('',#25239,#25697); +#25697 = DEFINITIONAL_REPRESENTATION('',(#25698),#25702); +#25698 = LINE('',#25699,#25700); +#25699 = CARTESIAN_POINT('',(-5.2,-2.5)); +#25700 = VECTOR('',#25701,1.); +#25701 = DIRECTION('',(-1.,1.232047923279E-016)); +#25702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25703 = ORIENTED_EDGE('',*,*,#25454,.F.); +#25704 = ORIENTED_EDGE('',*,*,#25109,.F.); +#25705 = ORIENTED_EDGE('',*,*,#25706,.T.); +#25706 = EDGE_CURVE('',#25082,#25682,#25707,.T.); +#25707 = SURFACE_CURVE('',#25708,(#25712,#25719),.PCURVE_S1.); +#25708 = LINE('',#25709,#25710); +#25709 = CARTESIAN_POINT('',(-2.2,0.755,0.895)); +#25710 = VECTOR('',#25711,1.); +#25711 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#25712 = PCURVE('',#25123,#25713); +#25713 = DEFINITIONAL_REPRESENTATION('',(#25714),#25718); #25714 = LINE('',#25715,#25716); -#25715 = CARTESIAN_POINT('',(2.7,0.905,3.395)); +#25715 = CARTESIAN_POINT('',(-4.4,2.812420435427E-017)); #25716 = VECTOR('',#25717,1.); -#25717 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25718 = PCURVE('',#24061,#25719); -#25719 = DEFINITIONAL_REPRESENTATION('',(#25720),#25724); -#25720 = LINE('',#25721,#25722); -#25721 = CARTESIAN_POINT('',(4.97919847714E-017,1.)); -#25722 = VECTOR('',#25723,1.); -#25723 = DIRECTION('',(1.,1.702510980039E-043)); -#25724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25725 = PCURVE('',#25726,#25731); -#25726 = PLANE('',#25727); -#25727 = AXIS2_PLACEMENT_3D('',#25728,#25729,#25730); -#25728 = CARTESIAN_POINT('',(2.5,1.555,3.395)); -#25729 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#25730 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25731 = DEFINITIONAL_REPRESENTATION('',(#25732),#25736); -#25732 = LINE('',#25733,#25734); -#25733 = CARTESIAN_POINT('',(0.65,-0.2)); -#25734 = VECTOR('',#25735,1.); -#25735 = DIRECTION('',(-1.,0.E+000)); -#25736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25737 = ORIENTED_EDGE('',*,*,#25738,.T.); -#25738 = EDGE_CURVE('',#25711,#24046,#25739,.T.); -#25739 = SURFACE_CURVE('',#25740,(#25744,#25751),.PCURVE_S1.); -#25740 = LINE('',#25741,#25742); -#25741 = CARTESIAN_POINT('',(2.7,1.555,2.595)); -#25742 = VECTOR('',#25743,1.); -#25743 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#25744 = PCURVE('',#24061,#25745); -#25745 = DEFINITIONAL_REPRESENTATION('',(#25746),#25750); -#25746 = LINE('',#25747,#25748); -#25747 = CARTESIAN_POINT('',(0.65,0.2)); -#25748 = VECTOR('',#25749,1.); -#25749 = DIRECTION('',(1.702510980039E-043,1.)); -#25750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25751 = PCURVE('',#24089,#25752); -#25752 = DEFINITIONAL_REPRESENTATION('',(#25753),#25757); -#25753 = LINE('',#25754,#25755); -#25754 = CARTESIAN_POINT('',(1.3,-0.2)); -#25755 = VECTOR('',#25756,1.); -#25756 = DIRECTION('',(-1.,0.E+000)); -#25757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25758 = ORIENTED_EDGE('',*,*,#24045,.T.); -#25759 = ORIENTED_EDGE('',*,*,#24660,.T.); -#25760 = ORIENTED_EDGE('',*,*,#25761,.T.); -#25761 = EDGE_CURVE('',#24633,#25196,#25762,.T.); -#25762 = SURFACE_CURVE('',#25763,(#25767,#25774),.PCURVE_S1.); -#25763 = LINE('',#25764,#25765); -#25764 = CARTESIAN_POINT('',(2.7,0.305,2.395)); -#25765 = VECTOR('',#25766,1.); -#25766 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25767 = PCURVE('',#24061,#25768); +#25717 = DIRECTION('',(1.020425574104E-016,1.)); +#25718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25719 = PCURVE('',#25097,#25720); +#25720 = DEFINITIONAL_REPRESENTATION('',(#25721),#25725); +#25721 = LINE('',#25722,#25723); +#25722 = CARTESIAN_POINT('',(2.1,4.643095803673E-018)); +#25723 = VECTOR('',#25724,1.); +#25724 = DIRECTION('',(-1.145632479557E-031,1.)); +#25725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25726 = ADVANCED_FACE('',(#25727),#24841,.T.); +#25727 = FACE_BOUND('',#25728,.T.); +#25728 = EDGE_LOOP('',(#25729,#25730,#25753,#25774)); +#25729 = ORIENTED_EDGE('',*,*,#24825,.F.); +#25730 = ORIENTED_EDGE('',*,*,#25731,.T.); +#25731 = EDGE_CURVE('',#24796,#25732,#25734,.T.); +#25732 = VERTEX_POINT('',#25733); +#25733 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); +#25734 = SURFACE_CURVE('',#25735,(#25739,#25746),.PCURVE_S1.); +#25735 = LINE('',#25736,#25737); +#25736 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); +#25737 = VECTOR('',#25738,1.); +#25738 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25739 = PCURVE('',#24841,#25740); +#25740 = DEFINITIONAL_REPRESENTATION('',(#25741),#25745); +#25741 = LINE('',#25742,#25743); +#25742 = CARTESIAN_POINT('',(-1.64,2.45)); +#25743 = VECTOR('',#25744,1.); +#25744 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25746 = PCURVE('',#24813,#25747); +#25747 = DEFINITIONAL_REPRESENTATION('',(#25748),#25752); +#25748 = LINE('',#25749,#25750); +#25749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25750 = VECTOR('',#25751,1.); +#25751 = DIRECTION('',(-1.,4.74549138297E-031)); +#25752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25753 = ORIENTED_EDGE('',*,*,#25754,.T.); +#25754 = EDGE_CURVE('',#25732,#25554,#25755,.T.); +#25755 = SURFACE_CURVE('',#25756,(#25760,#25767),.PCURVE_S1.); +#25756 = LINE('',#25757,#25758); +#25757 = CARTESIAN_POINT('',(-0.6,2.435,2.645)); +#25758 = VECTOR('',#25759,1.); +#25759 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25760 = PCURVE('',#24841,#25761); +#25761 = DEFINITIONAL_REPRESENTATION('',(#25762),#25766); +#25762 = LINE('',#25763,#25764); +#25763 = CARTESIAN_POINT('',(-1.99,2.45)); +#25764 = VECTOR('',#25765,1.); +#25765 = DIRECTION('',(-1.,1.702510980039E-043)); +#25766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25767 = PCURVE('',#25590,#25768); #25768 = DEFINITIONAL_REPRESENTATION('',(#25769),#25773); #25769 = LINE('',#25770,#25771); -#25770 = CARTESIAN_POINT('',(-0.6,3.185331772654E-016)); +#25770 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25771 = VECTOR('',#25772,1.); -#25772 = DIRECTION('',(1.,1.702510980039E-043)); +#25772 = DIRECTION('',(-1.,0.E+000)); #25773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25774 = PCURVE('',#24648,#25775); -#25775 = DEFINITIONAL_REPRESENTATION('',(#25776),#25780); -#25776 = LINE('',#25777,#25778); -#25777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#25778 = VECTOR('',#25779,1.); -#25779 = DIRECTION('',(1.,0.E+000)); -#25780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25781 = ORIENTED_EDGE('',*,*,#25782,.F.); -#25782 = EDGE_CURVE('',#25783,#25196,#25785,.T.); -#25783 = VERTEX_POINT('',#25784); -#25784 = CARTESIAN_POINT('',(2.7,0.905,2.395)); -#25785 = SURFACE_CURVE('',#25786,(#25790,#25797),.PCURVE_S1.); -#25786 = LINE('',#25787,#25788); -#25787 = CARTESIAN_POINT('',(2.7,0.905,2.395)); -#25788 = VECTOR('',#25789,1.); -#25789 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#25790 = PCURVE('',#24061,#25791); -#25791 = DEFINITIONAL_REPRESENTATION('',(#25792),#25796); -#25792 = LINE('',#25793,#25794); -#25793 = CARTESIAN_POINT('',(-1.55053008704E-030,-4.440892098501E-016)); -#25794 = VECTOR('',#25795,1.); -#25795 = DIRECTION('',(-1.,-1.702510980039E-043)); -#25796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25797 = PCURVE('',#25211,#25798); -#25798 = DEFINITIONAL_REPRESENTATION('',(#25799),#25803); -#25799 = LINE('',#25800,#25801); -#25800 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); -#25801 = VECTOR('',#25802,1.); -#25802 = DIRECTION('',(1.,0.E+000)); -#25803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25804 = ORIENTED_EDGE('',*,*,#25805,.T.); -#25805 = EDGE_CURVE('',#25783,#25709,#25806,.T.); +#25774 = ORIENTED_EDGE('',*,*,#25553,.T.); +#25775 = ADVANCED_FACE('',(#25776),#24955,.T.); +#25776 = FACE_BOUND('',#25777,.T.); +#25777 = EDGE_LOOP('',(#25778,#25779,#25802,#25825)); +#25778 = ORIENTED_EDGE('',*,*,#24939,.F.); +#25779 = ORIENTED_EDGE('',*,*,#25780,.T.); +#25780 = EDGE_CURVE('',#24910,#25781,#25783,.T.); +#25781 = VERTEX_POINT('',#25782); +#25782 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); +#25783 = SURFACE_CURVE('',#25784,(#25788,#25795),.PCURVE_S1.); +#25784 = LINE('',#25785,#25786); +#25785 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); +#25786 = VECTOR('',#25787,1.); +#25787 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25788 = PCURVE('',#24955,#25789); +#25789 = DEFINITIONAL_REPRESENTATION('',(#25790),#25794); +#25790 = LINE('',#25791,#25792); +#25791 = CARTESIAN_POINT('',(-1.64,2.45)); +#25792 = VECTOR('',#25793,1.); +#25793 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25795 = PCURVE('',#24927,#25796); +#25796 = DEFINITIONAL_REPRESENTATION('',(#25797),#25801); +#25797 = LINE('',#25798,#25799); +#25798 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25799 = VECTOR('',#25800,1.); +#25800 = DIRECTION('',(-1.,4.74549138297E-031)); +#25801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25802 = ORIENTED_EDGE('',*,*,#25803,.T.); +#25803 = EDGE_CURVE('',#25781,#25804,#25806,.T.); +#25804 = VERTEX_POINT('',#25805); +#25805 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); #25806 = SURFACE_CURVE('',#25807,(#25811,#25818),.PCURVE_S1.); #25807 = LINE('',#25808,#25809); -#25808 = CARTESIAN_POINT('',(2.7,0.905,2.095)); +#25808 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); #25809 = VECTOR('',#25810,1.); -#25810 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#25811 = PCURVE('',#24061,#25812); +#25810 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25811 = PCURVE('',#24955,#25812); #25812 = DEFINITIONAL_REPRESENTATION('',(#25813),#25817); #25813 = LINE('',#25814,#25815); -#25814 = CARTESIAN_POINT('',(6.277801629234E-017,-0.3)); +#25814 = CARTESIAN_POINT('',(-1.99,2.45)); #25815 = VECTOR('',#25816,1.); -#25816 = DIRECTION('',(1.702510980039E-043,1.)); +#25816 = DIRECTION('',(-1.,1.702510980039E-043)); #25817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25818 = PCURVE('',#25819,#25824); -#25819 = PLANE('',#25820); -#25820 = AXIS2_PLACEMENT_3D('',#25821,#25822,#25823); -#25821 = CARTESIAN_POINT('',(2.5,0.905,3.395)); -#25822 = DIRECTION('',(2.513800689087E-029,1.,3.599903578358E-015)); -#25823 = DIRECTION('',(-6.982966722219E-015,3.599903578358E-015,-1.)); -#25824 = DEFINITIONAL_REPRESENTATION('',(#25825),#25829); -#25825 = LINE('',#25826,#25827); -#25826 = CARTESIAN_POINT('',(1.3,-0.2)); -#25827 = VECTOR('',#25828,1.); -#25828 = DIRECTION('',(-1.,0.E+000)); -#25829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25830 = ADVANCED_FACE('',(#25831),#23893,.T.); -#25831 = FACE_BOUND('',#25832,.T.); -#25832 = EDGE_LOOP('',(#25833,#25858,#25879,#25902,#25923,#25924,#25925) - ); -#25833 = ORIENTED_EDGE('',*,*,#25834,.F.); -#25834 = EDGE_CURVE('',#25835,#25837,#25839,.T.); -#25835 = VERTEX_POINT('',#25836); -#25836 = CARTESIAN_POINT('',(-2.7,0.905,2.395)); -#25837 = VERTEX_POINT('',#25838); -#25838 = CARTESIAN_POINT('',(-2.7,0.905,3.395)); -#25839 = SURFACE_CURVE('',#25840,(#25844,#25851),.PCURVE_S1.); -#25840 = LINE('',#25841,#25842); -#25841 = CARTESIAN_POINT('',(-2.7,0.905,2.095)); -#25842 = VECTOR('',#25843,1.); -#25843 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#25844 = PCURVE('',#23893,#25845); -#25845 = DEFINITIONAL_REPRESENTATION('',(#25846),#25850); -#25846 = LINE('',#25847,#25848); -#25847 = CARTESIAN_POINT('',(6.277801629234E-017,0.3)); -#25848 = VECTOR('',#25849,1.); -#25849 = DIRECTION('',(1.702510980039E-043,-1.)); -#25850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25851 = PCURVE('',#24893,#25852); -#25852 = DEFINITIONAL_REPRESENTATION('',(#25853),#25857); -#25853 = LINE('',#25854,#25855); -#25854 = CARTESIAN_POINT('',(-1.3,0.2)); -#25855 = VECTOR('',#25856,1.); -#25856 = DIRECTION('',(1.,0.E+000)); -#25857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25858 = ORIENTED_EDGE('',*,*,#25859,.F.); -#25859 = EDGE_CURVE('',#25270,#25835,#25860,.T.); -#25860 = SURFACE_CURVE('',#25861,(#25865,#25872),.PCURVE_S1.); -#25861 = LINE('',#25862,#25863); -#25862 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); -#25863 = VECTOR('',#25864,1.); -#25864 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25865 = PCURVE('',#23893,#25866); +#25818 = PCURVE('',#25358,#25819); +#25819 = DEFINITIONAL_REPRESENTATION('',(#25820),#25824); +#25820 = LINE('',#25821,#25822); +#25821 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25822 = VECTOR('',#25823,1.); +#25823 = DIRECTION('',(-1.,0.E+000)); +#25824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25825 = ORIENTED_EDGE('',*,*,#25826,.T.); +#25826 = EDGE_CURVE('',#25804,#24940,#25827,.T.); +#25827 = SURFACE_CURVE('',#25828,(#25832,#25839),.PCURVE_S1.); +#25828 = LINE('',#25829,#25830); +#25829 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); +#25830 = VECTOR('',#25831,1.); +#25831 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25832 = PCURVE('',#24955,#25833); +#25833 = DEFINITIONAL_REPRESENTATION('',(#25834),#25838); +#25834 = LINE('',#25835,#25836); +#25835 = CARTESIAN_POINT('',(-1.99,2.45)); +#25836 = VECTOR('',#25837,1.); +#25837 = DIRECTION('',(-1.770125995895E-016,-1.)); +#25838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25839 = PCURVE('',#24983,#25840); +#25840 = DEFINITIONAL_REPRESENTATION('',(#25841),#25845); +#25841 = LINE('',#25842,#25843); +#25842 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25843 = VECTOR('',#25844,1.); +#25844 = DIRECTION('',(-1.,0.E+000)); +#25845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25846 = ADVANCED_FACE('',(#25847),#24755,.F.); +#25847 = FACE_BOUND('',#25848,.T.); +#25848 = EDGE_LOOP('',(#25849,#25872,#25873,#25896)); +#25849 = ORIENTED_EDGE('',*,*,#25850,.T.); +#25850 = EDGE_CURVE('',#25851,#24740,#25853,.T.); +#25851 = VERTEX_POINT('',#25852); +#25852 = CARTESIAN_POINT('',(0.6,2.435,2.645)); +#25853 = SURFACE_CURVE('',#25854,(#25858,#25865),.PCURVE_S1.); +#25854 = LINE('',#25855,#25856); +#25855 = CARTESIAN_POINT('',(0.6,2.435,2.645)); +#25856 = VECTOR('',#25857,1.); +#25857 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25858 = PCURVE('',#24755,#25859); +#25859 = DEFINITIONAL_REPRESENTATION('',(#25860),#25864); +#25860 = LINE('',#25861,#25862); +#25861 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); +#25862 = VECTOR('',#25863,1.); +#25863 = DIRECTION('',(-1.,0.E+000)); +#25864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25865 = PCURVE('',#24781,#25866); #25866 = DEFINITIONAL_REPRESENTATION('',(#25867),#25871); #25867 = LINE('',#25868,#25869); -#25868 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); +#25868 = CARTESIAN_POINT('',(-1.99,2.45)); #25869 = VECTOR('',#25870,1.); -#25870 = DIRECTION('',(1.,-1.702510980039E-043)); +#25870 = DIRECTION('',(-1.770125995895E-016,-1.)); #25871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#25872 = PCURVE('',#24865,#25873); -#25873 = DEFINITIONAL_REPRESENTATION('',(#25874),#25878); -#25874 = LINE('',#25875,#25876); -#25875 = CARTESIAN_POINT('',(-0.6,0.2)); -#25876 = VECTOR('',#25877,1.); -#25877 = DIRECTION('',(1.,0.E+000)); -#25878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25879 = ORIENTED_EDGE('',*,*,#25880,.F.); -#25880 = EDGE_CURVE('',#25881,#25270,#25883,.T.); -#25881 = VERTEX_POINT('',#25882); -#25882 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); -#25883 = SURFACE_CURVE('',#25884,(#25888,#25895),.PCURVE_S1.); +#25872 = ORIENTED_EDGE('',*,*,#24739,.T.); +#25873 = ORIENTED_EDGE('',*,*,#25874,.F.); +#25874 = EDGE_CURVE('',#25875,#24712,#25877,.T.); +#25875 = VERTEX_POINT('',#25876); +#25876 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#25877 = SURFACE_CURVE('',#25878,(#25882,#25889),.PCURVE_S1.); +#25878 = LINE('',#25879,#25880); +#25879 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#25880 = VECTOR('',#25881,1.); +#25881 = DIRECTION('',(-6.982966722219E-015,3.668495960699E-015,-1.)); +#25882 = PCURVE('',#24755,#25883); +#25883 = DEFINITIONAL_REPRESENTATION('',(#25884),#25888); #25884 = LINE('',#25885,#25886); -#25885 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#25885 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25886 = VECTOR('',#25887,1.); -#25887 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25888 = PCURVE('',#23893,#25889); -#25889 = DEFINITIONAL_REPRESENTATION('',(#25890),#25894); -#25890 = LINE('',#25891,#25892); -#25891 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); -#25892 = VECTOR('',#25893,1.); -#25893 = DIRECTION('',(1.,-1.702510980039E-043)); -#25894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25895 = PCURVE('',#24753,#25896); -#25896 = DEFINITIONAL_REPRESENTATION('',(#25897),#25901); -#25897 = LINE('',#25898,#25899); -#25898 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#25899 = VECTOR('',#25900,1.); -#25900 = DIRECTION('',(-1.,0.E+000)); -#25901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25902 = ORIENTED_EDGE('',*,*,#25903,.F.); -#25903 = EDGE_CURVE('',#23878,#25881,#25904,.T.); -#25904 = SURFACE_CURVE('',#25905,(#25909,#25916),.PCURVE_S1.); +#25887 = DIRECTION('',(-1.,0.E+000)); +#25888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25889 = PCURVE('',#24727,#25890); +#25890 = DEFINITIONAL_REPRESENTATION('',(#25891),#25895); +#25891 = LINE('',#25892,#25893); +#25892 = CARTESIAN_POINT('',(-1.99,2.45)); +#25893 = VECTOR('',#25894,1.); +#25894 = DIRECTION('',(-1.770125995895E-016,-1.)); +#25895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25896 = ORIENTED_EDGE('',*,*,#25897,.T.); +#25897 = EDGE_CURVE('',#25875,#25851,#25898,.T.); +#25898 = SURFACE_CURVE('',#25899,(#25903,#25910),.PCURVE_S1.); +#25899 = LINE('',#25900,#25901); +#25900 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#25901 = VECTOR('',#25902,1.); +#25902 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#25903 = PCURVE('',#24755,#25904); +#25904 = DEFINITIONAL_REPRESENTATION('',(#25905),#25909); #25905 = LINE('',#25906,#25907); -#25906 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); +#25906 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #25907 = VECTOR('',#25908,1.); -#25908 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); -#25909 = PCURVE('',#23893,#25910); -#25910 = DEFINITIONAL_REPRESENTATION('',(#25911),#25915); -#25911 = LINE('',#25912,#25913); -#25912 = CARTESIAN_POINT('',(-0.6,-1.5)); -#25913 = VECTOR('',#25914,1.); -#25914 = DIRECTION('',(1.219727444046E-016,1.)); -#25915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25916 = PCURVE('',#23921,#25917); -#25917 = DEFINITIONAL_REPRESENTATION('',(#25918),#25922); -#25918 = LINE('',#25919,#25920); -#25919 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#25920 = VECTOR('',#25921,1.); -#25921 = DIRECTION('',(-1.,0.E+000)); -#25922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25923 = ORIENTED_EDGE('',*,*,#23877,.F.); -#25924 = ORIENTED_EDGE('',*,*,#25659,.F.); -#25925 = ORIENTED_EDGE('',*,*,#25926,.F.); -#25926 = EDGE_CURVE('',#25837,#25660,#25927,.T.); -#25927 = SURFACE_CURVE('',#25928,(#25932,#25939),.PCURVE_S1.); -#25928 = LINE('',#25929,#25930); -#25929 = CARTESIAN_POINT('',(-2.7,0.905,3.395)); -#25930 = VECTOR('',#25931,1.); -#25931 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#25932 = PCURVE('',#23893,#25933); -#25933 = DEFINITIONAL_REPRESENTATION('',(#25934),#25938); -#25934 = LINE('',#25935,#25936); -#25935 = CARTESIAN_POINT('',(4.97919847714E-017,-1.)); -#25936 = VECTOR('',#25937,1.); -#25937 = DIRECTION('',(1.,-1.702510980039E-043)); -#25938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25939 = PCURVE('',#24921,#25940); -#25940 = DEFINITIONAL_REPRESENTATION('',(#25941),#25945); -#25941 = LINE('',#25942,#25943); -#25942 = CARTESIAN_POINT('',(-0.65,0.2)); -#25943 = VECTOR('',#25944,1.); -#25944 = DIRECTION('',(1.,0.E+000)); -#25945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25946 = ADVANCED_FACE('',(#25947),#24145,.F.); -#25947 = FACE_BOUND('',#25948,.T.); -#25948 = EDGE_LOOP('',(#25949,#25972,#25973,#25974,#25997,#26025,#26053, - #26076)); -#25949 = ORIENTED_EDGE('',*,*,#25950,.T.); -#25950 = EDGE_CURVE('',#25951,#24956,#25953,.T.); -#25951 = VERTEX_POINT('',#25952); -#25952 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); -#25953 = SURFACE_CURVE('',#25954,(#25958,#25965),.PCURVE_S1.); +#25908 = DIRECTION('',(0.E+000,-1.)); +#25909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25910 = PCURVE('',#25644,#25911); +#25911 = DEFINITIONAL_REPRESENTATION('',(#25912),#25916); +#25912 = LINE('',#25913,#25914); +#25913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25914 = VECTOR('',#25915,1.); +#25915 = DIRECTION('',(-2.80259692865E-045,-1.)); +#25916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25917 = ADVANCED_FACE('',(#25918),#24895,.F.); +#25918 = FACE_BOUND('',#25919,.T.); +#25919 = EDGE_LOOP('',(#25920,#25943,#25944,#25945)); +#25920 = ORIENTED_EDGE('',*,*,#25921,.F.); +#25921 = EDGE_CURVE('',#24798,#25922,#25924,.T.); +#25922 = VERTEX_POINT('',#25923); +#25923 = CARTESIAN_POINT('',(-0.4,2.085,2.645)); +#25924 = SURFACE_CURVE('',#25925,(#25929,#25936),.PCURVE_S1.); +#25925 = LINE('',#25926,#25927); +#25926 = CARTESIAN_POINT('',(-0.4,2.085,2.645)); +#25927 = VECTOR('',#25928,1.); +#25928 = DIRECTION('',(6.963778812478E-015,7.408159078957E-002, + 0.997252183706)); +#25929 = PCURVE('',#24895,#25930); +#25930 = DEFINITIONAL_REPRESENTATION('',(#25931),#25935); +#25931 = LINE('',#25932,#25933); +#25932 = CARTESIAN_POINT('',(-1.64,2.45)); +#25933 = VECTOR('',#25934,1.); +#25934 = DIRECTION('',(-7.408159078958E-002,0.997252183706)); +#25935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25936 = PCURVE('',#24813,#25937); +#25937 = DEFINITIONAL_REPRESENTATION('',(#25938),#25942); +#25938 = LINE('',#25939,#25940); +#25939 = CARTESIAN_POINT('',(3.787199746371E-016,-0.2)); +#25940 = VECTOR('',#25941,1.); +#25941 = DIRECTION('',(-1.,4.74549138297E-031)); +#25942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25943 = ORIENTED_EDGE('',*,*,#24881,.T.); +#25944 = ORIENTED_EDGE('',*,*,#25529,.F.); +#25945 = ORIENTED_EDGE('',*,*,#25946,.F.); +#25946 = EDGE_CURVE('',#25922,#25530,#25947,.T.); +#25947 = SURFACE_CURVE('',#25948,(#25952,#25959),.PCURVE_S1.); +#25948 = LINE('',#25949,#25950); +#25949 = CARTESIAN_POINT('',(-0.4,2.435,2.645)); +#25950 = VECTOR('',#25951,1.); +#25951 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25952 = PCURVE('',#24895,#25953); +#25953 = DEFINITIONAL_REPRESENTATION('',(#25954),#25958); #25954 = LINE('',#25955,#25956); -#25955 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); +#25955 = CARTESIAN_POINT('',(-1.99,2.45)); #25956 = VECTOR('',#25957,1.); -#25957 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#25958 = PCURVE('',#24145,#25959); -#25959 = DEFINITIONAL_REPRESENTATION('',(#25960),#25964); -#25960 = LINE('',#25961,#25962); -#25961 = CARTESIAN_POINT('',(0.5,1.488675134595)); -#25962 = VECTOR('',#25963,1.); -#25963 = DIRECTION('',(-1.,0.E+000)); -#25964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25965 = PCURVE('',#24994,#25966); -#25966 = DEFINITIONAL_REPRESENTATION('',(#25967),#25971); -#25967 = LINE('',#25968,#25969); -#25968 = CARTESIAN_POINT('',(-0.57735026919,-2.046371908427E-016)); -#25969 = VECTOR('',#25970,1.); -#25970 = DIRECTION('',(-1.228743304519E-031,1.)); -#25971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25972 = ORIENTED_EDGE('',*,*,#24955,.T.); -#25973 = ORIENTED_EDGE('',*,*,#24129,.T.); -#25974 = ORIENTED_EDGE('',*,*,#25975,.T.); -#25975 = EDGE_CURVE('',#24102,#25976,#25978,.T.); -#25976 = VERTEX_POINT('',#25977); -#25977 = CARTESIAN_POINT('',(3.,3.255,1.133675134595)); -#25978 = SURFACE_CURVE('',#25979,(#25983,#25990),.PCURVE_S1.); -#25979 = LINE('',#25980,#25981); -#25980 = CARTESIAN_POINT('',(3.,3.255,-0.355)); -#25981 = VECTOR('',#25982,1.); -#25982 = DIRECTION('',(-7.18705183704E-015,3.491483361109E-015,-1.)); -#25983 = PCURVE('',#24145,#25984); -#25984 = DEFINITIONAL_REPRESENTATION('',(#25985),#25989); -#25985 = LINE('',#25986,#25987); -#25986 = CARTESIAN_POINT('',(6.,-7.902749635247E-016)); -#25987 = VECTOR('',#25988,1.); -#25988 = DIRECTION('',(-2.040851148208E-016,-1.)); -#25989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25990 = PCURVE('',#24117,#25991); -#25991 = DEFINITIONAL_REPRESENTATION('',(#25992),#25996); -#25992 = LINE('',#25993,#25994); -#25993 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#25994 = VECTOR('',#25995,1.); -#25995 = DIRECTION('',(-1.,-1.752268792537E-043)); -#25996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#25997 = ORIENTED_EDGE('',*,*,#25998,.F.); -#25998 = EDGE_CURVE('',#25999,#25976,#26001,.T.); -#25999 = VERTEX_POINT('',#26000); -#26000 = CARTESIAN_POINT('',(2.5,3.255,1.133675134595)); -#26001 = SURFACE_CURVE('',#26002,(#26006,#26013),.PCURVE_S1.); -#26002 = LINE('',#26003,#26004); -#26003 = CARTESIAN_POINT('',(2.5,3.255,1.133675134595)); -#26004 = VECTOR('',#26005,1.); -#26005 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26006 = PCURVE('',#24145,#26007); -#26007 = DEFINITIONAL_REPRESENTATION('',(#26008),#26012); -#26008 = LINE('',#26009,#26010); -#26009 = CARTESIAN_POINT('',(5.5,1.488675134595)); -#26010 = VECTOR('',#26011,1.); -#26011 = DIRECTION('',(1.,0.E+000)); -#26012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26013 = PCURVE('',#26014,#26019); -#26014 = PLANE('',#26015); -#26015 = AXIS2_PLACEMENT_3D('',#26016,#26017,#26018); -#26016 = CARTESIAN_POINT('',(2.5,2.755,0.845)); -#26017 = DIRECTION('',(6.047426575223E-015,-0.5,0.866025403784)); -#26018 = DIRECTION('',(3.491483361109E-015,0.866025403784,0.5)); -#26019 = DEFINITIONAL_REPRESENTATION('',(#26020),#26024); -#26020 = LINE('',#26021,#26022); -#26021 = CARTESIAN_POINT('',(0.57735026919,-2.046371908427E-016)); -#26022 = VECTOR('',#26023,1.); -#26023 = DIRECTION('',(-1.228743304519E-031,-1.)); -#26024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26025 = ORIENTED_EDGE('',*,*,#26026,.F.); -#26026 = EDGE_CURVE('',#26027,#25999,#26029,.T.); -#26027 = VERTEX_POINT('',#26028); -#26028 = CARTESIAN_POINT('',(2.5,3.255,-0.355)); -#26029 = SURFACE_CURVE('',#26030,(#26034,#26041),.PCURVE_S1.); +#25957 = DIRECTION('',(-1.,1.702510980039E-043)); +#25958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25959 = PCURVE('',#25590,#25960); +#25960 = DEFINITIONAL_REPRESENTATION('',(#25961),#25965); +#25961 = LINE('',#25962,#25963); +#25962 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); +#25963 = VECTOR('',#25964,1.); +#25964 = DIRECTION('',(-1.,0.E+000)); +#25965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25966 = ADVANCED_FACE('',(#25967),#24727,.T.); +#25967 = FACE_BOUND('',#25968,.T.); +#25968 = EDGE_LOOP('',(#25969,#25970,#25971,#25992)); +#25969 = ORIENTED_EDGE('',*,*,#24711,.F.); +#25970 = ORIENTED_EDGE('',*,*,#25656,.T.); +#25971 = ORIENTED_EDGE('',*,*,#25972,.T.); +#25972 = EDGE_CURVE('',#25629,#25875,#25973,.T.); +#25973 = SURFACE_CURVE('',#25974,(#25978,#25985),.PCURVE_S1.); +#25974 = LINE('',#25975,#25976); +#25975 = CARTESIAN_POINT('',(0.4,2.435,2.645)); +#25976 = VECTOR('',#25977,1.); +#25977 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#25978 = PCURVE('',#24727,#25979); +#25979 = DEFINITIONAL_REPRESENTATION('',(#25980),#25984); +#25980 = LINE('',#25981,#25982); +#25981 = CARTESIAN_POINT('',(-1.99,2.45)); +#25982 = VECTOR('',#25983,1.); +#25983 = DIRECTION('',(-1.,1.702510980039E-043)); +#25984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25985 = PCURVE('',#25644,#25986); +#25986 = DEFINITIONAL_REPRESENTATION('',(#25987),#25991); +#25987 = LINE('',#25988,#25989); +#25988 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#25989 = VECTOR('',#25990,1.); +#25990 = DIRECTION('',(-1.,0.E+000)); +#25991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#25992 = ORIENTED_EDGE('',*,*,#25874,.T.); +#25993 = ADVANCED_FACE('',(#25994),#25097,.F.); +#25994 = FACE_BOUND('',#25995,.T.); +#25995 = EDGE_LOOP('',(#25996,#26019,#26047,#26075,#26103,#26124,#26125, + #26126)); +#25996 = ORIENTED_EDGE('',*,*,#25997,.T.); +#25997 = EDGE_CURVE('',#25224,#25998,#26000,.T.); +#25998 = VERTEX_POINT('',#25999); +#25999 = CARTESIAN_POINT('',(-2.2,2.355,3.895)); +#26000 = SURFACE_CURVE('',#26001,(#26005,#26012),.PCURVE_S1.); +#26001 = LINE('',#26002,#26003); +#26002 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); +#26003 = VECTOR('',#26004,1.); +#26004 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); +#26005 = PCURVE('',#25097,#26006); +#26006 = DEFINITIONAL_REPRESENTATION('',(#26007),#26011); +#26007 = LINE('',#26008,#26009); +#26008 = CARTESIAN_POINT('',(1.836909530734E-016,3.)); +#26009 = VECTOR('',#26010,1.); +#26010 = DIRECTION('',(1.,-1.145632479557E-031)); +#26011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26012 = PCURVE('',#25239,#26013); +#26013 = DEFINITIONAL_REPRESENTATION('',(#26014),#26018); +#26014 = LINE('',#26015,#26016); +#26015 = CARTESIAN_POINT('',(-0.8,-0.4)); +#26016 = VECTOR('',#26017,1.); +#26017 = DIRECTION('',(-2.06514699521E-016,-1.)); +#26018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26019 = ORIENTED_EDGE('',*,*,#26020,.F.); +#26020 = EDGE_CURVE('',#26021,#25998,#26023,.T.); +#26021 = VERTEX_POINT('',#26022); +#26022 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); +#26023 = SURFACE_CURVE('',#26024,(#26028,#26035),.PCURVE_S1.); +#26024 = LINE('',#26025,#26026); +#26025 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); +#26026 = VECTOR('',#26027,1.); +#26027 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26028 = PCURVE('',#25097,#26029); +#26029 = DEFINITIONAL_REPRESENTATION('',(#26030),#26034); #26030 = LINE('',#26031,#26032); -#26031 = CARTESIAN_POINT('',(2.5,3.255,0.195)); +#26031 = CARTESIAN_POINT('',(0.5,0.6)); #26032 = VECTOR('',#26033,1.); -#26033 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#26034 = PCURVE('',#24145,#26035); -#26035 = DEFINITIONAL_REPRESENTATION('',(#26036),#26040); -#26036 = LINE('',#26037,#26038); -#26037 = CARTESIAN_POINT('',(5.5,0.55)); -#26038 = VECTOR('',#26039,1.); -#26039 = DIRECTION('',(0.E+000,1.)); -#26040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26041 = PCURVE('',#26042,#26047); -#26042 = PLANE('',#26043); -#26043 = AXIS2_PLACEMENT_3D('',#26044,#26045,#26046); -#26044 = CARTESIAN_POINT('',(2.5,2.755,-0.355)); -#26045 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26046 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26047 = DEFINITIONAL_REPRESENTATION('',(#26048),#26052); -#26048 = LINE('',#26049,#26050); -#26049 = CARTESIAN_POINT('',(-0.5,0.55)); -#26050 = VECTOR('',#26051,1.); -#26051 = DIRECTION('',(-1.702510980039E-043,1.)); -#26052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26053 = ORIENTED_EDGE('',*,*,#26054,.T.); -#26054 = EDGE_CURVE('',#26027,#26055,#26057,.T.); -#26055 = VERTEX_POINT('',#26056); -#26056 = CARTESIAN_POINT('',(-2.5,3.255,-0.355)); -#26057 = SURFACE_CURVE('',#26058,(#26062,#26069),.PCURVE_S1.); +#26033 = DIRECTION('',(-1.145632479557E-031,1.)); +#26034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26035 = PCURVE('',#26036,#26041); +#26036 = PLANE('',#26037); +#26037 = AXIS2_PLACEMENT_3D('',#26038,#26039,#26040); +#26038 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); +#26039 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26040 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); +#26041 = DEFINITIONAL_REPRESENTATION('',(#26042),#26046); +#26042 = LINE('',#26043,#26044); +#26043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26044 = VECTOR('',#26045,1.); +#26045 = DIRECTION('',(-1.020425574104E-016,1.)); +#26046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26047 = ORIENTED_EDGE('',*,*,#26048,.F.); +#26048 = EDGE_CURVE('',#26049,#26021,#26051,.T.); +#26049 = VERTEX_POINT('',#26050); +#26050 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); +#26051 = SURFACE_CURVE('',#26052,(#26056,#26063),.PCURVE_S1.); +#26052 = LINE('',#26053,#26054); +#26053 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); +#26054 = VECTOR('',#26055,1.); +#26055 = DIRECTION('',(-1.445602896647E-015,1.,3.491483361109E-015)); +#26056 = PCURVE('',#25097,#26057); +#26057 = DEFINITIONAL_REPRESENTATION('',(#26058),#26062); #26058 = LINE('',#26059,#26060); -#26059 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#26059 = CARTESIAN_POINT('',(0.5,0.6)); #26060 = VECTOR('',#26061,1.); -#26061 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); -#26062 = PCURVE('',#24145,#26063); -#26063 = DEFINITIONAL_REPRESENTATION('',(#26064),#26068); -#26064 = LINE('',#26065,#26066); -#26065 = CARTESIAN_POINT('',(6.,-7.902749635247E-016)); -#26066 = VECTOR('',#26067,1.); -#26067 = DIRECTION('',(-1.,1.224606353822E-016)); -#26068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26069 = PCURVE('',#24814,#26070); -#26070 = DEFINITIONAL_REPRESENTATION('',(#26071),#26075); -#26071 = LINE('',#26072,#26073); -#26072 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26073 = VECTOR('',#26074,1.); -#26074 = DIRECTION('',(-1.,0.E+000)); -#26075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26076 = ORIENTED_EDGE('',*,*,#26077,.T.); -#26077 = EDGE_CURVE('',#26055,#25951,#26078,.T.); -#26078 = SURFACE_CURVE('',#26079,(#26083,#26090),.PCURVE_S1.); -#26079 = LINE('',#26080,#26081); -#26080 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); -#26081 = VECTOR('',#26082,1.); -#26082 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); -#26083 = PCURVE('',#24145,#26084); -#26084 = DEFINITIONAL_REPRESENTATION('',(#26085),#26089); -#26085 = LINE('',#26086,#26087); -#26086 = CARTESIAN_POINT('',(0.5,1.488675134595)); -#26087 = VECTOR('',#26088,1.); -#26088 = DIRECTION('',(0.E+000,1.)); -#26089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26090 = PCURVE('',#26091,#26096); -#26091 = PLANE('',#26092); -#26092 = AXIS2_PLACEMENT_3D('',#26093,#26094,#26095); -#26093 = CARTESIAN_POINT('',(-2.5,2.755,-0.355)); -#26094 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26095 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26096 = DEFINITIONAL_REPRESENTATION('',(#26097),#26101); -#26097 = LINE('',#26098,#26099); -#26098 = CARTESIAN_POINT('',(-0.5,-1.488675134595)); -#26099 = VECTOR('',#26100,1.); -#26100 = DIRECTION('',(-1.702510980039E-043,-1.)); -#26101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26102 = ADVANCED_FACE('',(#26103),#24005,.F.); -#26103 = FACE_BOUND('',#26104,.T.); -#26104 = EDGE_LOOP('',(#26105,#26106,#26127,#26128)); -#26105 = ORIENTED_EDGE('',*,*,#25246,.T.); -#26106 = ORIENTED_EDGE('',*,*,#26107,.F.); -#26107 = EDGE_CURVE('',#24610,#25224,#26108,.T.); -#26108 = SURFACE_CURVE('',#26109,(#26113,#26120),.PCURVE_S1.); -#26109 = LINE('',#26110,#26111); -#26110 = CARTESIAN_POINT('',(2.5,0.305,2.395)); -#26111 = VECTOR('',#26112,1.); -#26112 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#26113 = PCURVE('',#24005,#26114); -#26114 = DEFINITIONAL_REPRESENTATION('',(#26115),#26119); -#26115 = LINE('',#26116,#26117); -#26116 = CARTESIAN_POINT('',(-0.6,3.185331772654E-016)); -#26117 = VECTOR('',#26118,1.); -#26118 = DIRECTION('',(1.,1.702510980039E-043)); -#26119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26120 = PCURVE('',#24648,#26121); -#26121 = DEFINITIONAL_REPRESENTATION('',(#26122),#26126); -#26122 = LINE('',#26123,#26124); -#26123 = CARTESIAN_POINT('',(-2.245921632424E-031,0.2)); -#26124 = VECTOR('',#26125,1.); -#26125 = DIRECTION('',(1.,0.E+000)); -#26126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26127 = ORIENTED_EDGE('',*,*,#24609,.F.); -#26128 = ORIENTED_EDGE('',*,*,#23989,.F.); -#26129 = ADVANCED_FACE('',(#26130),#24117,.F.); -#26130 = FACE_BOUND('',#26131,.T.); -#26131 = EDGE_LOOP('',(#26132,#26162,#26183,#26184,#26185,#26208,#26231, - #26254,#26275,#26276,#26299,#26327)); -#26132 = ORIENTED_EDGE('',*,*,#26133,.F.); -#26133 = EDGE_CURVE('',#26134,#26136,#26138,.T.); -#26134 = VERTEX_POINT('',#26135); -#26135 = CARTESIAN_POINT('',(3.,2.755,0.845)); -#26136 = VERTEX_POINT('',#26137); -#26137 = CARTESIAN_POINT('',(3.,2.755,0.195)); -#26138 = SURFACE_CURVE('',#26139,(#26143,#26150),.PCURVE_S1.); -#26139 = LINE('',#26140,#26141); -#26140 = CARTESIAN_POINT('',(3.,2.755,0.195)); -#26141 = VECTOR('',#26142,1.); -#26142 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#26143 = PCURVE('',#24117,#26144); -#26144 = DEFINITIONAL_REPRESENTATION('',(#26145),#26149); -#26145 = LINE('',#26146,#26147); -#26146 = CARTESIAN_POINT('',(0.55,-0.5)); -#26147 = VECTOR('',#26148,1.); -#26148 = DIRECTION('',(-1.,-1.752268792537E-043)); -#26149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26150 = PCURVE('',#26151,#26156); -#26151 = PLANE('',#26152); -#26152 = AXIS2_PLACEMENT_3D('',#26153,#26154,#26155); -#26153 = CARTESIAN_POINT('',(2.5,2.755,0.195)); -#26154 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26155 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); -#26156 = DEFINITIONAL_REPRESENTATION('',(#26157),#26161); -#26157 = LINE('',#26158,#26159); -#26158 = CARTESIAN_POINT('',(0.5,-5.719166459861E-018)); -#26159 = VECTOR('',#26160,1.); -#26160 = DIRECTION('',(0.E+000,-1.)); -#26161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26162 = ORIENTED_EDGE('',*,*,#26163,.F.); -#26163 = EDGE_CURVE('',#25976,#26134,#26164,.T.); -#26164 = SURFACE_CURVE('',#26165,(#26169,#26176),.PCURVE_S1.); -#26165 = LINE('',#26166,#26167); -#26166 = CARTESIAN_POINT('',(3.,2.755,0.845)); -#26167 = VECTOR('',#26168,1.); -#26168 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); -#26169 = PCURVE('',#24117,#26170); -#26170 = DEFINITIONAL_REPRESENTATION('',(#26171),#26175); -#26171 = LINE('',#26172,#26173); -#26172 = CARTESIAN_POINT('',(1.2,-0.5)); -#26173 = VECTOR('',#26174,1.); -#26174 = DIRECTION('',(-0.5,-0.866025403784)); -#26175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26176 = PCURVE('',#26014,#26177); -#26177 = DEFINITIONAL_REPRESENTATION('',(#26178),#26182); -#26178 = LINE('',#26179,#26180); -#26179 = CARTESIAN_POINT('',(2.48959923857E-017,-0.5)); -#26180 = VECTOR('',#26181,1.); -#26181 = DIRECTION('',(-1.,1.961367055364E-030)); -#26182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26183 = ORIENTED_EDGE('',*,*,#25975,.F.); -#26184 = ORIENTED_EDGE('',*,*,#24101,.T.); +#26061 = DIRECTION('',(-1.,1.145632479557E-031)); +#26062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26063 = PCURVE('',#26064,#26069); +#26064 = PLANE('',#26065); +#26065 = AXIS2_PLACEMENT_3D('',#26066,#26067,#26068); +#26066 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#26067 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#26068 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26069 = DEFINITIONAL_REPRESENTATION('',(#26070),#26074); +#26070 = LINE('',#26071,#26072); +#26071 = CARTESIAN_POINT('',(5.403763914175E-033,-0.35)); +#26072 = VECTOR('',#26073,1.); +#26073 = DIRECTION('',(1.,1.445602896647E-015)); +#26074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26075 = ORIENTED_EDGE('',*,*,#26076,.T.); +#26076 = EDGE_CURVE('',#26049,#26077,#26079,.T.); +#26077 = VERTEX_POINT('',#26078); +#26078 = CARTESIAN_POINT('',(-2.2,1.755,3.895)); +#26079 = SURFACE_CURVE('',#26080,(#26084,#26091),.PCURVE_S1.); +#26080 = LINE('',#26081,#26082); +#26081 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); +#26082 = VECTOR('',#26083,1.); +#26083 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26084 = PCURVE('',#25097,#26085); +#26085 = DEFINITIONAL_REPRESENTATION('',(#26086),#26090); +#26086 = LINE('',#26087,#26088); +#26087 = CARTESIAN_POINT('',(1.1,0.6)); +#26088 = VECTOR('',#26089,1.); +#26089 = DIRECTION('',(-1.145632479557E-031,1.)); +#26090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26091 = PCURVE('',#26092,#26097); +#26092 = PLANE('',#26093); +#26093 = AXIS2_PLACEMENT_3D('',#26094,#26095,#26096); +#26094 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); +#26095 = DIRECTION('',(6.195440985631E-016,-1.,-3.491483361109E-015)); +#26096 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); +#26097 = DEFINITIONAL_REPRESENTATION('',(#26098),#26102); +#26098 = LINE('',#26099,#26100); +#26099 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26100 = VECTOR('',#26101,1.); +#26101 = DIRECTION('',(1.020425574104E-016,1.)); +#26102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26103 = ORIENTED_EDGE('',*,*,#26104,.T.); +#26104 = EDGE_CURVE('',#26077,#25682,#26105,.T.); +#26105 = SURFACE_CURVE('',#26106,(#26110,#26117),.PCURVE_S1.); +#26106 = LINE('',#26107,#26108); +#26107 = CARTESIAN_POINT('',(-2.2,2.855,3.895)); +#26108 = VECTOR('',#26109,1.); +#26109 = DIRECTION('',(2.06514699521E-016,-1.,-3.491483361109E-015)); +#26110 = PCURVE('',#25097,#26111); +#26111 = DEFINITIONAL_REPRESENTATION('',(#26112),#26116); +#26112 = LINE('',#26113,#26114); +#26113 = CARTESIAN_POINT('',(1.836909530734E-016,3.)); +#26114 = VECTOR('',#26115,1.); +#26115 = DIRECTION('',(1.,-1.145632479557E-031)); +#26116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26117 = PCURVE('',#25239,#26118); +#26118 = DEFINITIONAL_REPRESENTATION('',(#26119),#26123); +#26119 = LINE('',#26120,#26121); +#26120 = CARTESIAN_POINT('',(-0.8,-0.4)); +#26121 = VECTOR('',#26122,1.); +#26122 = DIRECTION('',(-2.06514699521E-016,-1.)); +#26123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26124 = ORIENTED_EDGE('',*,*,#25706,.F.); +#26125 = ORIENTED_EDGE('',*,*,#25081,.F.); +#26126 = ORIENTED_EDGE('',*,*,#25251,.T.); +#26127 = ADVANCED_FACE('',(#26128),#24983,.F.); +#26128 = FACE_BOUND('',#26129,.T.); +#26129 = EDGE_LOOP('',(#26130,#26131,#26132,#26133)); +#26130 = ORIENTED_EDGE('',*,*,#25321,.T.); +#26131 = ORIENTED_EDGE('',*,*,#24967,.T.); +#26132 = ORIENTED_EDGE('',*,*,#25826,.F.); +#26133 = ORIENTED_EDGE('',*,*,#26134,.T.); +#26134 = EDGE_CURVE('',#25804,#25322,#26135,.T.); +#26135 = SURFACE_CURVE('',#26136,(#26140,#26147),.PCURVE_S1.); +#26136 = LINE('',#26137,#26138); +#26137 = CARTESIAN_POINT('',(-1.6,2.435,2.645)); +#26138 = VECTOR('',#26139,1.); +#26139 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26140 = PCURVE('',#24983,#26141); +#26141 = DEFINITIONAL_REPRESENTATION('',(#26142),#26146); +#26142 = LINE('',#26143,#26144); +#26143 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26144 = VECTOR('',#26145,1.); +#26145 = DIRECTION('',(0.E+000,-1.)); +#26146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26147 = PCURVE('',#25358,#26148); +#26148 = DEFINITIONAL_REPRESENTATION('',(#26149),#26153); +#26149 = LINE('',#26150,#26151); +#26150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26151 = VECTOR('',#26152,1.); +#26152 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26154 = ADVANCED_FACE('',(#26155),#24781,.F.); +#26155 = FACE_BOUND('',#26156,.T.); +#26156 = EDGE_LOOP('',(#26157,#26158,#26159,#26160)); +#26157 = ORIENTED_EDGE('',*,*,#25605,.F.); +#26158 = ORIENTED_EDGE('',*,*,#24767,.T.); +#26159 = ORIENTED_EDGE('',*,*,#25850,.F.); +#26160 = ORIENTED_EDGE('',*,*,#26161,.F.); +#26161 = EDGE_CURVE('',#25606,#25851,#26162,.T.); +#26162 = SURFACE_CURVE('',#26163,(#26167,#26174),.PCURVE_S1.); +#26163 = LINE('',#26164,#26165); +#26164 = CARTESIAN_POINT('',(0.6,2.435,2.645)); +#26165 = VECTOR('',#26166,1.); +#26166 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26167 = PCURVE('',#24781,#26168); +#26168 = DEFINITIONAL_REPRESENTATION('',(#26169),#26173); +#26169 = LINE('',#26170,#26171); +#26170 = CARTESIAN_POINT('',(-1.99,2.45)); +#26171 = VECTOR('',#26172,1.); +#26172 = DIRECTION('',(-1.,1.702510980039E-043)); +#26173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26174 = PCURVE('',#25644,#26175); +#26175 = DEFINITIONAL_REPRESENTATION('',(#26176),#26180); +#26176 = LINE('',#26177,#26178); +#26177 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); +#26178 = VECTOR('',#26179,1.); +#26179 = DIRECTION('',(-1.,0.E+000)); +#26180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26181 = ADVANCED_FACE('',(#26182),#24927,.F.); +#26182 = FACE_BOUND('',#26183,.T.); +#26183 = EDGE_LOOP('',(#26184,#26185,#26206,#26207)); +#26184 = ORIENTED_EDGE('',*,*,#25297,.T.); #26185 = ORIENTED_EDGE('',*,*,#26186,.F.); -#26186 = EDGE_CURVE('',#26187,#24074,#26189,.T.); -#26187 = VERTEX_POINT('',#26188); -#26188 = CARTESIAN_POINT('',(3.,1.555,3.395)); -#26189 = SURFACE_CURVE('',#26190,(#26194,#26201),.PCURVE_S1.); -#26190 = LINE('',#26191,#26192); -#26191 = CARTESIAN_POINT('',(3.,1.555,3.895)); -#26192 = VECTOR('',#26193,1.); -#26193 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); -#26194 = PCURVE('',#24117,#26195); -#26195 = DEFINITIONAL_REPRESENTATION('',(#26196),#26200); -#26196 = LINE('',#26197,#26198); -#26197 = CARTESIAN_POINT('',(4.25,-1.7)); -#26198 = VECTOR('',#26199,1.); -#26199 = DIRECTION('',(1.,4.336808689942E-016)); -#26200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26201 = PCURVE('',#24089,#26202); -#26202 = DEFINITIONAL_REPRESENTATION('',(#26203),#26207); -#26203 = LINE('',#26204,#26205); -#26204 = CARTESIAN_POINT('',(-3.828588921589E-016,-0.5)); -#26205 = VECTOR('',#26206,1.); -#26206 = DIRECTION('',(-1.,0.E+000)); -#26207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26208 = ORIENTED_EDGE('',*,*,#26209,.F.); -#26209 = EDGE_CURVE('',#26210,#26187,#26212,.T.); -#26210 = VERTEX_POINT('',#26211); -#26211 = CARTESIAN_POINT('',(3.,0.905,3.395)); -#26212 = SURFACE_CURVE('',#26213,(#26217,#26224),.PCURVE_S1.); -#26213 = LINE('',#26214,#26215); -#26214 = CARTESIAN_POINT('',(3.,1.555,3.395)); -#26215 = VECTOR('',#26216,1.); -#26216 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#26217 = PCURVE('',#24117,#26218); -#26218 = DEFINITIONAL_REPRESENTATION('',(#26219),#26223); -#26219 = LINE('',#26220,#26221); -#26220 = CARTESIAN_POINT('',(3.75,-1.7)); -#26221 = VECTOR('',#26222,1.); -#26222 = DIRECTION('',(1.752268792537E-043,1.)); -#26223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26224 = PCURVE('',#25726,#26225); -#26225 = DEFINITIONAL_REPRESENTATION('',(#26226),#26230); -#26226 = LINE('',#26227,#26228); -#26227 = CARTESIAN_POINT('',(2.13784635414E-031,-0.5)); -#26228 = VECTOR('',#26229,1.); -#26229 = DIRECTION('',(-1.,0.E+000)); -#26230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26231 = ORIENTED_EDGE('',*,*,#26232,.F.); -#26232 = EDGE_CURVE('',#26233,#26210,#26235,.T.); -#26233 = VERTEX_POINT('',#26234); -#26234 = CARTESIAN_POINT('',(3.,0.905,2.395)); -#26235 = SURFACE_CURVE('',#26236,(#26240,#26247),.PCURVE_S1.); -#26236 = LINE('',#26237,#26238); -#26237 = CARTESIAN_POINT('',(3.,0.905,3.395)); -#26238 = VECTOR('',#26239,1.); -#26239 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); -#26240 = PCURVE('',#24117,#26241); -#26241 = DEFINITIONAL_REPRESENTATION('',(#26242),#26246); -#26242 = LINE('',#26243,#26244); -#26243 = CARTESIAN_POINT('',(3.75,-2.35)); -#26244 = VECTOR('',#26245,1.); -#26245 = DIRECTION('',(1.,-1.084202172486E-016)); -#26246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26247 = PCURVE('',#25819,#26248); -#26248 = DEFINITIONAL_REPRESENTATION('',(#26249),#26253); -#26249 = LINE('',#26250,#26251); -#26250 = CARTESIAN_POINT('',(6.123031769112E-017,-0.5)); -#26251 = VECTOR('',#26252,1.); -#26252 = DIRECTION('',(-1.,0.E+000)); -#26253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26254 = ORIENTED_EDGE('',*,*,#26255,.F.); -#26255 = EDGE_CURVE('',#25173,#26233,#26256,.T.); -#26256 = SURFACE_CURVE('',#26257,(#26261,#26268),.PCURVE_S1.); -#26257 = LINE('',#26258,#26259); -#26258 = CARTESIAN_POINT('',(3.,0.905,2.395)); -#26259 = VECTOR('',#26260,1.); -#26260 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#26261 = PCURVE('',#24117,#26262); +#26186 = EDGE_CURVE('',#25781,#25298,#26187,.T.); +#26187 = SURFACE_CURVE('',#26188,(#26192,#26199),.PCURVE_S1.); +#26188 = LINE('',#26189,#26190); +#26189 = CARTESIAN_POINT('',(-1.6,2.085,2.645)); +#26190 = VECTOR('',#26191,1.); +#26191 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26192 = PCURVE('',#24927,#26193); +#26193 = DEFINITIONAL_REPRESENTATION('',(#26194),#26198); +#26194 = LINE('',#26195,#26196); +#26195 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26196 = VECTOR('',#26197,1.); +#26197 = DIRECTION('',(-1.109335647967E-030,-1.)); +#26198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26199 = PCURVE('',#25358,#26200); +#26200 = DEFINITIONAL_REPRESENTATION('',(#26201),#26205); +#26201 = LINE('',#26202,#26203); +#26202 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); +#26203 = VECTOR('',#26204,1.); +#26204 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26206 = ORIENTED_EDGE('',*,*,#25780,.F.); +#26207 = ORIENTED_EDGE('',*,*,#24909,.T.); +#26208 = ADVANCED_FACE('',(#26209),#24813,.F.); +#26209 = FACE_BOUND('',#26210,.T.); +#26210 = EDGE_LOOP('',(#26211,#26212,#26233,#26234)); +#26211 = ORIENTED_EDGE('',*,*,#25921,.T.); +#26212 = ORIENTED_EDGE('',*,*,#26213,.F.); +#26213 = EDGE_CURVE('',#25732,#25922,#26214,.T.); +#26214 = SURFACE_CURVE('',#26215,(#26219,#26226),.PCURVE_S1.); +#26215 = LINE('',#26216,#26217); +#26216 = CARTESIAN_POINT('',(-0.6,2.085,2.645)); +#26217 = VECTOR('',#26218,1.); +#26218 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26219 = PCURVE('',#24813,#26220); +#26220 = DEFINITIONAL_REPRESENTATION('',(#26221),#26225); +#26221 = LINE('',#26222,#26223); +#26222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26223 = VECTOR('',#26224,1.); +#26224 = DIRECTION('',(-1.109335647967E-030,-1.)); +#26225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26226 = PCURVE('',#25590,#26227); +#26227 = DEFINITIONAL_REPRESENTATION('',(#26228),#26232); +#26228 = LINE('',#26229,#26230); +#26229 = CARTESIAN_POINT('',(0.35,-9.303180522238E-030)); +#26230 = VECTOR('',#26231,1.); +#26231 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26233 = ORIENTED_EDGE('',*,*,#25731,.F.); +#26234 = ORIENTED_EDGE('',*,*,#24795,.T.); +#26235 = ADVANCED_FACE('',(#26236,#26574),#25239,.F.); +#26236 = FACE_BOUND('',#26237,.T.); +#26237 = EDGE_LOOP('',(#26238,#26268,#26296,#26324,#26352,#26380,#26408, + #26436,#26464,#26492,#26520,#26548)); +#26238 = ORIENTED_EDGE('',*,*,#26239,.F.); +#26239 = EDGE_CURVE('',#26240,#26242,#26244,.T.); +#26240 = VERTEX_POINT('',#26241); +#26241 = CARTESIAN_POINT('',(-2.7,1.555,3.895)); +#26242 = VERTEX_POINT('',#26243); +#26243 = CARTESIAN_POINT('',(-3.,1.555,3.895)); +#26244 = SURFACE_CURVE('',#26245,(#26249,#26256),.PCURVE_S1.); +#26245 = LINE('',#26246,#26247); +#26246 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); +#26247 = VECTOR('',#26248,1.); +#26248 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26249 = PCURVE('',#25239,#26250); +#26250 = DEFINITIONAL_REPRESENTATION('',(#26251),#26255); +#26251 = LINE('',#26252,#26253); +#26252 = CARTESIAN_POINT('',(-0.5,-1.7)); +#26253 = VECTOR('',#26254,1.); +#26254 = DIRECTION('',(1.,2.835439861407E-045)); +#26255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26256 = PCURVE('',#26257,#26262); +#26257 = PLANE('',#26258); +#26258 = AXIS2_PLACEMENT_3D('',#26259,#26260,#26261); +#26259 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); +#26260 = DIRECTION('',(-2.135253304556E-029,-1.,-3.057802492115E-015)); +#26261 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); #26262 = DEFINITIONAL_REPRESENTATION('',(#26263),#26267); #26263 = LINE('',#26264,#26265); -#26264 = CARTESIAN_POINT('',(2.75,-2.35)); +#26264 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #26265 = VECTOR('',#26266,1.); -#26266 = DIRECTION('',(1.752268792537E-043,1.)); +#26266 = DIRECTION('',(0.E+000,1.)); #26267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26268 = PCURVE('',#25211,#26269); -#26269 = DEFINITIONAL_REPRESENTATION('',(#26270),#26274); -#26270 = LINE('',#26271,#26272); -#26271 = CARTESIAN_POINT('',(2.13784635414E-031,-0.5)); -#26272 = VECTOR('',#26273,1.); -#26273 = DIRECTION('',(-1.,0.E+000)); -#26274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26275 = ORIENTED_EDGE('',*,*,#25172,.T.); -#26276 = ORIENTED_EDGE('',*,*,#26277,.F.); -#26277 = EDGE_CURVE('',#26278,#25150,#26280,.T.); -#26278 = VERTEX_POINT('',#26279); -#26279 = CARTESIAN_POINT('',(3.,1.755,-0.355)); -#26280 = SURFACE_CURVE('',#26281,(#26285,#26292),.PCURVE_S1.); -#26281 = LINE('',#26282,#26283); -#26282 = CARTESIAN_POINT('',(3.,3.255,-0.355)); -#26283 = VECTOR('',#26284,1.); -#26284 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26285 = PCURVE('',#24117,#26286); -#26286 = DEFINITIONAL_REPRESENTATION('',(#26287),#26291); -#26287 = LINE('',#26288,#26289); -#26288 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26289 = VECTOR('',#26290,1.); -#26290 = DIRECTION('',(-1.752268792537E-043,-1.)); -#26291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26292 = PCURVE('',#24814,#26293); -#26293 = DEFINITIONAL_REPRESENTATION('',(#26294),#26298); -#26294 = LINE('',#26295,#26296); -#26295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26296 = VECTOR('',#26297,1.); -#26297 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26299 = ORIENTED_EDGE('',*,*,#26300,.F.); -#26300 = EDGE_CURVE('',#26301,#26278,#26303,.T.); -#26301 = VERTEX_POINT('',#26302); -#26302 = CARTESIAN_POINT('',(3.,1.755,0.195)); -#26303 = SURFACE_CURVE('',#26304,(#26308,#26315),.PCURVE_S1.); -#26304 = LINE('',#26305,#26306); -#26305 = CARTESIAN_POINT('',(3.,1.755,0.195)); -#26306 = VECTOR('',#26307,1.); -#26307 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#26308 = PCURVE('',#24117,#26309); -#26309 = DEFINITIONAL_REPRESENTATION('',(#26310),#26314); -#26310 = LINE('',#26311,#26312); -#26311 = CARTESIAN_POINT('',(0.55,-1.5)); -#26312 = VECTOR('',#26313,1.); -#26313 = DIRECTION('',(-1.,-1.752268792537E-043)); -#26314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26315 = PCURVE('',#26316,#26321); -#26316 = PLANE('',#26317); -#26317 = AXIS2_PLACEMENT_3D('',#26318,#26319,#26320); -#26318 = CARTESIAN_POINT('',(2.5,1.755,0.195)); -#26319 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26320 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); -#26321 = DEFINITIONAL_REPRESENTATION('',(#26322),#26326); -#26322 = LINE('',#26323,#26324); -#26323 = CARTESIAN_POINT('',(0.5,2.203640915577E-017)); -#26324 = VECTOR('',#26325,1.); -#26325 = DIRECTION('',(0.E+000,-1.)); -#26326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26327 = ORIENTED_EDGE('',*,*,#26328,.F.); -#26328 = EDGE_CURVE('',#26136,#26301,#26329,.T.); -#26329 = SURFACE_CURVE('',#26330,(#26334,#26341),.PCURVE_S1.); -#26330 = LINE('',#26331,#26332); -#26331 = CARTESIAN_POINT('',(3.,2.755,0.195)); -#26332 = VECTOR('',#26333,1.); -#26333 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#26334 = PCURVE('',#24117,#26335); -#26335 = DEFINITIONAL_REPRESENTATION('',(#26336),#26340); -#26336 = LINE('',#26337,#26338); -#26337 = CARTESIAN_POINT('',(0.55,-0.5)); -#26338 = VECTOR('',#26339,1.); -#26339 = DIRECTION('',(-1.084202172486E-016,-1.)); -#26340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26341 = PCURVE('',#26342,#26347); -#26342 = PLANE('',#26343); -#26343 = AXIS2_PLACEMENT_3D('',#26344,#26345,#26346); -#26344 = CARTESIAN_POINT('',(2.5,2.755,0.195)); -#26345 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); -#26346 = DIRECTION('',(2.513800689087E-029,1.,3.599903578358E-015)); -#26347 = DEFINITIONAL_REPRESENTATION('',(#26348),#26352); -#26348 = LINE('',#26349,#26350); -#26349 = CARTESIAN_POINT('',(-2.058844780408E-032,-0.5)); -#26350 = VECTOR('',#26351,1.); -#26351 = DIRECTION('',(-1.,0.E+000)); -#26352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26353 = ADVANCED_FACE('',(#26354),#24278,.F.); -#26354 = FACE_BOUND('',#26355,.T.); -#26355 = EDGE_LOOP('',(#26356,#26357,#26358,#26359)); -#26356 = ORIENTED_EDGE('',*,*,#24262,.T.); -#26357 = ORIENTED_EDGE('',*,*,#24446,.F.); -#26358 = ORIENTED_EDGE('',*,*,#24369,.F.); -#26359 = ORIENTED_EDGE('',*,*,#24417,.T.); -#26360 = ADVANCED_FACE('',(#26361),#24089,.F.); -#26361 = FACE_BOUND('',#26362,.T.); -#26362 = EDGE_LOOP('',(#26363,#26364,#26365,#26386)); -#26363 = ORIENTED_EDGE('',*,*,#24073,.F.); -#26364 = ORIENTED_EDGE('',*,*,#25738,.F.); -#26365 = ORIENTED_EDGE('',*,*,#26366,.T.); -#26366 = EDGE_CURVE('',#25711,#26187,#26367,.T.); -#26367 = SURFACE_CURVE('',#26368,(#26372,#26379),.PCURVE_S1.); -#26368 = LINE('',#26369,#26370); -#26369 = CARTESIAN_POINT('',(2.5,1.555,3.395)); -#26370 = VECTOR('',#26371,1.); -#26371 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26372 = PCURVE('',#24089,#26373); -#26373 = DEFINITIONAL_REPRESENTATION('',(#26374),#26378); -#26374 = LINE('',#26375,#26376); -#26375 = CARTESIAN_POINT('',(0.5,6.123031769112E-017)); -#26376 = VECTOR('',#26377,1.); -#26377 = DIRECTION('',(0.E+000,-1.)); -#26378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26379 = PCURVE('',#25726,#26380); -#26380 = DEFINITIONAL_REPRESENTATION('',(#26381),#26385); -#26381 = LINE('',#26382,#26383); -#26382 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26383 = VECTOR('',#26384,1.); -#26384 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26386 = ORIENTED_EDGE('',*,*,#26186,.T.); -#26387 = ADVANCED_FACE('',(#26388),#23921,.T.); -#26388 = FACE_BOUND('',#26389,.T.); -#26389 = EDGE_LOOP('',(#26390,#26391,#26392,#26393)); -#26390 = ORIENTED_EDGE('',*,*,#24716,.F.); -#26391 = ORIENTED_EDGE('',*,*,#23905,.F.); -#26392 = ORIENTED_EDGE('',*,*,#25903,.T.); -#26393 = ORIENTED_EDGE('',*,*,#26394,.T.); -#26394 = EDGE_CURVE('',#25881,#24717,#26395,.T.); -#26395 = SURFACE_CURVE('',#26396,(#26400,#26407),.PCURVE_S1.); -#26396 = LINE('',#26397,#26398); -#26397 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); -#26398 = VECTOR('',#26399,1.); -#26399 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26400 = PCURVE('',#23921,#26401); -#26401 = DEFINITIONAL_REPRESENTATION('',(#26402),#26406); -#26402 = LINE('',#26403,#26404); -#26403 = CARTESIAN_POINT('',(-1.5,-2.603982567767E-016)); -#26404 = VECTOR('',#26405,1.); -#26405 = DIRECTION('',(0.E+000,-1.)); -#26406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26407 = PCURVE('',#24753,#26408); -#26408 = DEFINITIONAL_REPRESENTATION('',(#26409),#26413); -#26409 = LINE('',#26410,#26411); -#26410 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26411 = VECTOR('',#26412,1.); -#26412 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26414 = ADVANCED_FACE('',(#26415),#24648,.F.); -#26415 = FACE_BOUND('',#26416,.T.); -#26416 = EDGE_LOOP('',(#26417,#26418,#26419,#26420)); -#26417 = ORIENTED_EDGE('',*,*,#25223,.T.); -#26418 = ORIENTED_EDGE('',*,*,#25761,.F.); -#26419 = ORIENTED_EDGE('',*,*,#24632,.T.); -#26420 = ORIENTED_EDGE('',*,*,#26107,.T.); -#26421 = ADVANCED_FACE('',(#26422),#24753,.T.); -#26422 = FACE_BOUND('',#26423,.T.); -#26423 = EDGE_LOOP('',(#26424,#26425,#26426,#26427)); -#26424 = ORIENTED_EDGE('',*,*,#25880,.T.); -#26425 = ORIENTED_EDGE('',*,*,#25269,.F.); -#26426 = ORIENTED_EDGE('',*,*,#24739,.F.); -#26427 = ORIENTED_EDGE('',*,*,#26394,.F.); -#26428 = ADVANCED_FACE('',(#26429),#25048,.T.); -#26429 = FACE_BOUND('',#26430,.T.); -#26430 = EDGE_LOOP('',(#26431,#26432,#26455,#26478)); -#26431 = ORIENTED_EDGE('',*,*,#25034,.F.); -#26432 = ORIENTED_EDGE('',*,*,#26433,.F.); -#26433 = EDGE_CURVE('',#26434,#25007,#26436,.T.); -#26434 = VERTEX_POINT('',#26435); -#26435 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#26436 = SURFACE_CURVE('',#26437,(#26441,#26448),.PCURVE_S1.); -#26437 = LINE('',#26438,#26439); -#26438 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#26439 = VECTOR('',#26440,1.); -#26440 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26441 = PCURVE('',#25048,#26442); -#26442 = DEFINITIONAL_REPRESENTATION('',(#26443),#26447); -#26443 = LINE('',#26444,#26445); -#26444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26445 = VECTOR('',#26446,1.); -#26446 = DIRECTION('',(2.80259692865E-045,1.)); -#26447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26448 = PCURVE('',#25022,#26449); -#26449 = DEFINITIONAL_REPRESENTATION('',(#26450),#26454); -#26450 = LINE('',#26451,#26452); -#26451 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26452 = VECTOR('',#26453,1.); -#26453 = DIRECTION('',(1.,0.E+000)); -#26454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26455 = ORIENTED_EDGE('',*,*,#26456,.T.); -#26456 = EDGE_CURVE('',#26434,#26457,#26459,.T.); -#26457 = VERTEX_POINT('',#26458); -#26458 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); -#26459 = SURFACE_CURVE('',#26460,(#26464,#26471),.PCURVE_S1.); -#26460 = LINE('',#26461,#26462); -#26461 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#26462 = VECTOR('',#26463,1.); -#26463 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#26464 = PCURVE('',#25048,#26465); -#26465 = DEFINITIONAL_REPRESENTATION('',(#26466),#26470); -#26466 = LINE('',#26467,#26468); -#26467 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26468 = VECTOR('',#26469,1.); -#26469 = DIRECTION('',(1.,0.E+000)); -#26470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26471 = PCURVE('',#26091,#26472); -#26472 = DEFINITIONAL_REPRESENTATION('',(#26473),#26477); -#26473 = LINE('',#26474,#26475); -#26474 = CARTESIAN_POINT('',(-1.439590092099E-016,-0.55)); -#26475 = VECTOR('',#26476,1.); -#26476 = DIRECTION('',(1.,1.084202172486E-016)); -#26477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26478 = ORIENTED_EDGE('',*,*,#26479,.T.); -#26479 = EDGE_CURVE('',#26457,#24769,#26480,.T.); -#26480 = SURFACE_CURVE('',#26481,(#26485,#26492),.PCURVE_S1.); -#26481 = LINE('',#26482,#26483); -#26482 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); -#26483 = VECTOR('',#26484,1.); -#26484 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26485 = PCURVE('',#25048,#26486); +#26268 = ORIENTED_EDGE('',*,*,#26269,.T.); +#26269 = EDGE_CURVE('',#26240,#26270,#26272,.T.); +#26270 = VERTEX_POINT('',#26271); +#26271 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); +#26272 = SURFACE_CURVE('',#26273,(#26277,#26284),.PCURVE_S1.); +#26273 = LINE('',#26274,#26275); +#26274 = CARTESIAN_POINT('',(-2.7,1.555,3.895)); +#26275 = VECTOR('',#26276,1.); +#26276 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26277 = PCURVE('',#25239,#26278); +#26278 = DEFINITIONAL_REPRESENTATION('',(#26279),#26283); +#26279 = LINE('',#26280,#26281); +#26280 = CARTESIAN_POINT('',(-0.3,-1.7)); +#26281 = VECTOR('',#26282,1.); +#26282 = DIRECTION('',(4.608958230318E-045,-1.)); +#26283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26284 = PCURVE('',#26285,#26290); +#26285 = PLANE('',#26286); +#26286 = AXIS2_PLACEMENT_3D('',#26287,#26288,#26289); +#26287 = CARTESIAN_POINT('',(-2.7,0.905,2.395)); +#26288 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26289 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26290 = DEFINITIONAL_REPRESENTATION('',(#26291),#26295); +#26291 = LINE('',#26292,#26293); +#26292 = CARTESIAN_POINT('',(0.65,-1.5)); +#26293 = VECTOR('',#26294,1.); +#26294 = DIRECTION('',(-1.,1.702510980039E-043)); +#26295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26296 = ORIENTED_EDGE('',*,*,#26297,.T.); +#26297 = EDGE_CURVE('',#26270,#26298,#26300,.T.); +#26298 = VERTEX_POINT('',#26299); +#26299 = CARTESIAN_POINT('',(-2.5,0.305,3.895)); +#26300 = SURFACE_CURVE('',#26301,(#26305,#26312),.PCURVE_S1.); +#26301 = LINE('',#26302,#26303); +#26302 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); +#26303 = VECTOR('',#26304,1.); +#26304 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26305 = PCURVE('',#25239,#26306); +#26306 = DEFINITIONAL_REPRESENTATION('',(#26307),#26311); +#26307 = LINE('',#26308,#26309); +#26308 = CARTESIAN_POINT('',(-0.3,-2.95)); +#26309 = VECTOR('',#26310,1.); +#26310 = DIRECTION('',(-1.,-2.835439861407E-045)); +#26311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26312 = PCURVE('',#26313,#26318); +#26313 = PLANE('',#26314); +#26314 = AXIS2_PLACEMENT_3D('',#26315,#26316,#26317); +#26315 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); +#26316 = DIRECTION('',(-2.5232643737E-029,-1.,-3.613456105514E-015)); +#26317 = DIRECTION('',(6.982966722219E-015,-3.613456105514E-015,1.)); +#26318 = DEFINITIONAL_REPRESENTATION('',(#26319),#26323); +#26319 = LINE('',#26320,#26321); +#26320 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26321 = VECTOR('',#26322,1.); +#26322 = DIRECTION('',(0.E+000,-1.)); +#26323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26324 = ORIENTED_EDGE('',*,*,#26325,.F.); +#26325 = EDGE_CURVE('',#26326,#26298,#26328,.T.); +#26326 = VERTEX_POINT('',#26327); +#26327 = CARTESIAN_POINT('',(-2.5,0.355,3.895)); +#26328 = SURFACE_CURVE('',#26329,(#26333,#26340),.PCURVE_S1.); +#26329 = LINE('',#26330,#26331); +#26330 = CARTESIAN_POINT('',(-2.5,1.555,3.895)); +#26331 = VECTOR('',#26332,1.); +#26332 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26333 = PCURVE('',#25239,#26334); +#26334 = DEFINITIONAL_REPRESENTATION('',(#26335),#26339); +#26335 = LINE('',#26336,#26337); +#26336 = CARTESIAN_POINT('',(-0.5,-1.7)); +#26337 = VECTOR('',#26338,1.); +#26338 = DIRECTION('',(4.608958230318E-045,-1.)); +#26339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26340 = PCURVE('',#26341,#26346); +#26341 = PLANE('',#26342); +#26342 = AXIS2_PLACEMENT_3D('',#26343,#26344,#26345); +#26343 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); +#26344 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26345 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26346 = DEFINITIONAL_REPRESENTATION('',(#26347),#26351); +#26347 = LINE('',#26348,#26349); +#26348 = CARTESIAN_POINT('',(0.65,-1.5)); +#26349 = VECTOR('',#26350,1.); +#26350 = DIRECTION('',(-1.,1.702510980039E-043)); +#26351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26352 = ORIENTED_EDGE('',*,*,#26353,.T.); +#26353 = EDGE_CURVE('',#26326,#26354,#26356,.T.); +#26354 = VERTEX_POINT('',#26355); +#26355 = CARTESIAN_POINT('',(2.5,0.355,3.895)); +#26356 = SURFACE_CURVE('',#26357,(#26361,#26368),.PCURVE_S1.); +#26357 = LINE('',#26358,#26359); +#26358 = CARTESIAN_POINT('',(-3.,0.355,3.895)); +#26359 = VECTOR('',#26360,1.); +#26360 = DIRECTION('',(1.,5.047298460416E-031,-7.127527011883E-015)); +#26361 = PCURVE('',#25239,#26362); +#26362 = DEFINITIONAL_REPRESENTATION('',(#26363),#26367); +#26363 = LINE('',#26364,#26365); +#26364 = CARTESIAN_POINT('',(-7.1337213741E-029,-2.9)); +#26365 = VECTOR('',#26366,1.); +#26366 = DIRECTION('',(-1.,-6.51384833026E-045)); +#26367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26368 = PCURVE('',#26369,#26374); +#26369 = PLANE('',#26370); +#26370 = AXIS2_PLACEMENT_3D('',#26371,#26372,#26373); +#26371 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); +#26372 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26373 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); +#26374 = DEFINITIONAL_REPRESENTATION('',(#26375),#26379); +#26375 = LINE('',#26376,#26377); +#26376 = CARTESIAN_POINT('',(-3.677207193256E-016,4.25)); +#26377 = VECTOR('',#26378,1.); +#26378 = DIRECTION('',(1.,-1.445602896647E-016)); +#26379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26380 = ORIENTED_EDGE('',*,*,#26381,.T.); +#26381 = EDGE_CURVE('',#26354,#26382,#26384,.T.); +#26382 = VERTEX_POINT('',#26383); +#26383 = CARTESIAN_POINT('',(2.5,0.305,3.895)); +#26384 = SURFACE_CURVE('',#26385,(#26389,#26396),.PCURVE_S1.); +#26385 = LINE('',#26386,#26387); +#26386 = CARTESIAN_POINT('',(2.5,1.555,3.895)); +#26387 = VECTOR('',#26388,1.); +#26388 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26389 = PCURVE('',#25239,#26390); +#26390 = DEFINITIONAL_REPRESENTATION('',(#26391),#26395); +#26391 = LINE('',#26392,#26393); +#26392 = CARTESIAN_POINT('',(-5.5,-1.7)); +#26393 = VECTOR('',#26394,1.); +#26394 = DIRECTION('',(4.608958230318E-045,-1.)); +#26395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26396 = PCURVE('',#26397,#26402); +#26397 = PLANE('',#26398); +#26398 = AXIS2_PLACEMENT_3D('',#26399,#26400,#26401); +#26399 = CARTESIAN_POINT('',(2.5,0.905,2.395)); +#26400 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26401 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26402 = DEFINITIONAL_REPRESENTATION('',(#26403),#26407); +#26403 = LINE('',#26404,#26405); +#26404 = CARTESIAN_POINT('',(0.65,1.5)); +#26405 = VECTOR('',#26406,1.); +#26406 = DIRECTION('',(-1.,-1.702510980039E-043)); +#26407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26408 = ORIENTED_EDGE('',*,*,#26409,.F.); +#26409 = EDGE_CURVE('',#26410,#26382,#26412,.T.); +#26410 = VERTEX_POINT('',#26411); +#26411 = CARTESIAN_POINT('',(2.7,0.305,3.895)); +#26412 = SURFACE_CURVE('',#26413,(#26417,#26424),.PCURVE_S1.); +#26413 = LINE('',#26414,#26415); +#26414 = CARTESIAN_POINT('',(2.7,0.305,3.895)); +#26415 = VECTOR('',#26416,1.); +#26416 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26417 = PCURVE('',#25239,#26418); +#26418 = DEFINITIONAL_REPRESENTATION('',(#26419),#26423); +#26419 = LINE('',#26420,#26421); +#26420 = CARTESIAN_POINT('',(-5.7,-2.95)); +#26421 = VECTOR('',#26422,1.); +#26422 = DIRECTION('',(1.,2.835439861407E-045)); +#26423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26424 = PCURVE('',#26425,#26430); +#26425 = PLANE('',#26426); +#26426 = AXIS2_PLACEMENT_3D('',#26427,#26428,#26429); +#26427 = CARTESIAN_POINT('',(2.7,0.305,3.895)); +#26428 = DIRECTION('',(2.5232643737E-029,1.,3.613456105514E-015)); +#26429 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); +#26430 = DEFINITIONAL_REPRESENTATION('',(#26431),#26435); +#26431 = LINE('',#26432,#26433); +#26432 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26433 = VECTOR('',#26434,1.); +#26434 = DIRECTION('',(0.E+000,1.)); +#26435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26436 = ORIENTED_EDGE('',*,*,#26437,.F.); +#26437 = EDGE_CURVE('',#26438,#26410,#26440,.T.); +#26438 = VERTEX_POINT('',#26439); +#26439 = CARTESIAN_POINT('',(2.7,1.555,3.895)); +#26440 = SURFACE_CURVE('',#26441,(#26445,#26452),.PCURVE_S1.); +#26441 = LINE('',#26442,#26443); +#26442 = CARTESIAN_POINT('',(2.7,1.555,3.895)); +#26443 = VECTOR('',#26444,1.); +#26444 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26445 = PCURVE('',#25239,#26446); +#26446 = DEFINITIONAL_REPRESENTATION('',(#26447),#26451); +#26447 = LINE('',#26448,#26449); +#26448 = CARTESIAN_POINT('',(-5.7,-1.7)); +#26449 = VECTOR('',#26450,1.); +#26450 = DIRECTION('',(4.608958230318E-045,-1.)); +#26451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26452 = PCURVE('',#26453,#26458); +#26453 = PLANE('',#26454); +#26454 = AXIS2_PLACEMENT_3D('',#26455,#26456,#26457); +#26455 = CARTESIAN_POINT('',(2.7,0.905,2.395)); +#26456 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26457 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26458 = DEFINITIONAL_REPRESENTATION('',(#26459),#26463); +#26459 = LINE('',#26460,#26461); +#26460 = CARTESIAN_POINT('',(0.65,1.5)); +#26461 = VECTOR('',#26462,1.); +#26462 = DIRECTION('',(-1.,-1.702510980039E-043)); +#26463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26464 = ORIENTED_EDGE('',*,*,#26465,.T.); +#26465 = EDGE_CURVE('',#26438,#26466,#26468,.T.); +#26466 = VERTEX_POINT('',#26467); +#26467 = CARTESIAN_POINT('',(3.,1.555,3.895)); +#26468 = SURFACE_CURVE('',#26469,(#26473,#26480),.PCURVE_S1.); +#26469 = LINE('',#26470,#26471); +#26470 = CARTESIAN_POINT('',(2.5,1.555,3.895)); +#26471 = VECTOR('',#26472,1.); +#26472 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26473 = PCURVE('',#25239,#26474); +#26474 = DEFINITIONAL_REPRESENTATION('',(#26475),#26479); +#26475 = LINE('',#26476,#26477); +#26476 = CARTESIAN_POINT('',(-5.5,-1.7)); +#26477 = VECTOR('',#26478,1.); +#26478 = DIRECTION('',(-1.,-2.835439861407E-045)); +#26479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26480 = PCURVE('',#26481,#26486); +#26481 = PLANE('',#26482); +#26482 = AXIS2_PLACEMENT_3D('',#26483,#26484,#26485); +#26483 = CARTESIAN_POINT('',(2.5,1.555,3.895)); +#26484 = DIRECTION('',(2.135253304556E-029,1.,3.057802492115E-015)); +#26485 = DIRECTION('',(-6.982966722219E-015,3.057802492115E-015,-1.)); #26486 = DEFINITIONAL_REPRESENTATION('',(#26487),#26491); #26487 = LINE('',#26488,#26489); -#26488 = CARTESIAN_POINT('',(1.,-2.51961139144E-029)); +#26488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #26489 = VECTOR('',#26490,1.); -#26490 = DIRECTION('',(2.80259692865E-045,1.)); +#26490 = DIRECTION('',(0.E+000,-1.)); #26491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26492 = PCURVE('',#24786,#26493); -#26493 = DEFINITIONAL_REPRESENTATION('',(#26494),#26498); -#26494 = LINE('',#26495,#26496); -#26495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26496 = VECTOR('',#26497,1.); -#26497 = DIRECTION('',(1.,0.E+000)); -#26498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26499 = ADVANCED_FACE('',(#26500),#25022,.T.); -#26500 = FACE_BOUND('',#26501,.T.); -#26501 = EDGE_LOOP('',(#26502,#26503,#26526,#26547)); -#26502 = ORIENTED_EDGE('',*,*,#25006,.F.); -#26503 = ORIENTED_EDGE('',*,*,#26504,.F.); -#26504 = EDGE_CURVE('',#26505,#24979,#26507,.T.); -#26505 = VERTEX_POINT('',#26506); -#26506 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); -#26507 = SURFACE_CURVE('',#26508,(#26512,#26519),.PCURVE_S1.); -#26508 = LINE('',#26509,#26510); -#26509 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); -#26510 = VECTOR('',#26511,1.); -#26511 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26512 = PCURVE('',#25022,#26513); -#26513 = DEFINITIONAL_REPRESENTATION('',(#26514),#26518); -#26514 = LINE('',#26515,#26516); -#26515 = CARTESIAN_POINT('',(9.803627094157E-017,0.65)); -#26516 = VECTOR('',#26517,1.); -#26517 = DIRECTION('',(1.,0.E+000)); -#26518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26519 = PCURVE('',#24994,#26520); -#26520 = DEFINITIONAL_REPRESENTATION('',(#26521),#26525); -#26521 = LINE('',#26522,#26523); -#26522 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26523 = VECTOR('',#26524,1.); -#26524 = DIRECTION('',(-1.228743304519E-031,1.)); -#26525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26526 = ORIENTED_EDGE('',*,*,#26527,.T.); -#26527 = EDGE_CURVE('',#26505,#26434,#26528,.T.); -#26528 = SURFACE_CURVE('',#26529,(#26533,#26540),.PCURVE_S1.); -#26529 = LINE('',#26530,#26531); -#26530 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); -#26531 = VECTOR('',#26532,1.); -#26532 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#26533 = PCURVE('',#25022,#26534); -#26534 = DEFINITIONAL_REPRESENTATION('',(#26535),#26539); -#26535 = LINE('',#26536,#26537); -#26536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26537 = VECTOR('',#26538,1.); -#26538 = DIRECTION('',(0.E+000,-1.)); -#26539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26540 = PCURVE('',#26091,#26541); -#26541 = DEFINITIONAL_REPRESENTATION('',(#26542),#26546); -#26542 = LINE('',#26543,#26544); -#26543 = CARTESIAN_POINT('',(-1.439590092099E-016,-0.55)); -#26544 = VECTOR('',#26545,1.); -#26545 = DIRECTION('',(1.702510980039E-043,1.)); -#26546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26547 = ORIENTED_EDGE('',*,*,#26433,.T.); -#26548 = ADVANCED_FACE('',(#26549),#24994,.T.); -#26549 = FACE_BOUND('',#26550,.T.); -#26550 = EDGE_LOOP('',(#26551,#26552,#26553,#26574)); -#26551 = ORIENTED_EDGE('',*,*,#24978,.F.); -#26552 = ORIENTED_EDGE('',*,*,#25950,.F.); -#26553 = ORIENTED_EDGE('',*,*,#26554,.T.); -#26554 = EDGE_CURVE('',#25951,#26505,#26555,.T.); -#26555 = SURFACE_CURVE('',#26556,(#26560,#26567),.PCURVE_S1.); -#26556 = LINE('',#26557,#26558); -#26557 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); -#26558 = VECTOR('',#26559,1.); -#26559 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); -#26560 = PCURVE('',#24994,#26561); -#26561 = DEFINITIONAL_REPRESENTATION('',(#26562),#26566); -#26562 = LINE('',#26563,#26564); -#26563 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26564 = VECTOR('',#26565,1.); -#26565 = DIRECTION('',(1.,1.961367055364E-030)); -#26566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26567 = PCURVE('',#26091,#26568); +#26492 = ORIENTED_EDGE('',*,*,#26493,.F.); +#26493 = EDGE_CURVE('',#26494,#26466,#26496,.T.); +#26494 = VERTEX_POINT('',#26495); +#26495 = CARTESIAN_POINT('',(3.,3.255,3.895)); +#26496 = SURFACE_CURVE('',#26497,(#26501,#26508),.PCURVE_S1.); +#26497 = LINE('',#26498,#26499); +#26498 = CARTESIAN_POINT('',(3.,3.255,3.895)); +#26499 = VECTOR('',#26500,1.); +#26500 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26501 = PCURVE('',#25239,#26502); +#26502 = DEFINITIONAL_REPRESENTATION('',(#26503),#26507); +#26503 = LINE('',#26504,#26505); +#26504 = CARTESIAN_POINT('',(-6.,-2.565415624968E-030)); +#26505 = VECTOR('',#26506,1.); +#26506 = DIRECTION('',(4.608958230318E-045,-1.)); +#26507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26508 = PCURVE('',#26509,#26514); +#26509 = PLANE('',#26510); +#26510 = AXIS2_PLACEMENT_3D('',#26511,#26512,#26513); +#26511 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#26512 = DIRECTION('',(-1.,-7.125597826469E-031,7.18705183704E-015)); +#26513 = DIRECTION('',(7.18705183704E-015,-3.491483361109E-015,1.)); +#26514 = DEFINITIONAL_REPRESENTATION('',(#26515),#26519); +#26515 = LINE('',#26516,#26517); +#26516 = CARTESIAN_POINT('',(4.25,1.838603596628E-016)); +#26517 = VECTOR('',#26518,1.); +#26518 = DIRECTION('',(-1.752268792537E-043,-1.)); +#26519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26520 = ORIENTED_EDGE('',*,*,#26521,.F.); +#26521 = EDGE_CURVE('',#26522,#26494,#26524,.T.); +#26522 = VERTEX_POINT('',#26523); +#26523 = CARTESIAN_POINT('',(-3.,3.255,3.895)); +#26524 = SURFACE_CURVE('',#26525,(#26529,#26536),.PCURVE_S1.); +#26525 = LINE('',#26526,#26527); +#26526 = CARTESIAN_POINT('',(-3.,3.255,3.895)); +#26527 = VECTOR('',#26528,1.); +#26528 = DIRECTION('',(1.,5.047298460416E-031,-7.127527011883E-015)); +#26529 = PCURVE('',#25239,#26530); +#26530 = DEFINITIONAL_REPRESENTATION('',(#26531),#26535); +#26531 = LINE('',#26532,#26533); +#26532 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26533 = VECTOR('',#26534,1.); +#26534 = DIRECTION('',(-1.,-6.51384833026E-045)); +#26535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26536 = PCURVE('',#26537,#26542); +#26537 = PLANE('',#26538); +#26538 = AXIS2_PLACEMENT_3D('',#26539,#26540,#26541); +#26539 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); +#26540 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26541 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); +#26542 = DEFINITIONAL_REPRESENTATION('',(#26543),#26547); +#26543 = LINE('',#26544,#26545); +#26544 = CARTESIAN_POINT('',(-3.677207193256E-016,4.25)); +#26545 = VECTOR('',#26546,1.); +#26546 = DIRECTION('',(1.,-1.445602896647E-016)); +#26547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26548 = ORIENTED_EDGE('',*,*,#26549,.T.); +#26549 = EDGE_CURVE('',#26522,#26242,#26550,.T.); +#26550 = SURFACE_CURVE('',#26551,(#26555,#26562),.PCURVE_S1.); +#26551 = LINE('',#26552,#26553); +#26552 = CARTESIAN_POINT('',(-3.,3.255,3.895)); +#26553 = VECTOR('',#26554,1.); +#26554 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#26555 = PCURVE('',#25239,#26556); +#26556 = DEFINITIONAL_REPRESENTATION('',(#26557),#26561); +#26557 = LINE('',#26558,#26559); +#26558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26559 = VECTOR('',#26560,1.); +#26560 = DIRECTION('',(4.608958230318E-045,-1.)); +#26561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26562 = PCURVE('',#26563,#26568); +#26563 = PLANE('',#26564); +#26564 = AXIS2_PLACEMENT_3D('',#26565,#26566,#26567); +#26565 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); +#26566 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26567 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); #26568 = DEFINITIONAL_REPRESENTATION('',(#26569),#26573); #26569 = LINE('',#26570,#26571); -#26570 = CARTESIAN_POINT('',(2.511120651694E-016,-1.2)); +#26570 = CARTESIAN_POINT('',(1.838603596628E-016,4.25)); #26571 = VECTOR('',#26572,1.); -#26572 = DIRECTION('',(0.866025403784,0.5)); +#26572 = DIRECTION('',(-1.,-1.702510980039E-043)); #26573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26574 = ORIENTED_EDGE('',*,*,#26504,.T.); -#26575 = ADVANCED_FACE('',(#26576),#24814,.F.); -#26576 = FACE_BOUND('',#26577,.T.); -#26577 = EDGE_LOOP('',(#26578,#26608,#26629,#26630,#26653,#26681,#26702, - #26703,#26726,#26754,#26775,#26776,#26799,#26827,#26848,#26849, - #26850,#26873,#26894,#26895,#26918,#26939,#26940,#26941)); -#26578 = ORIENTED_EDGE('',*,*,#26579,.F.); -#26579 = EDGE_CURVE('',#26580,#26582,#26584,.T.); +#26574 = FACE_BOUND('',#26575,.T.); +#26575 = EDGE_LOOP('',(#26576,#26606,#26627,#26628,#26629,#26630,#26653, + #26681,#26702,#26703,#26704,#26705)); +#26576 = ORIENTED_EDGE('',*,*,#26577,.F.); +#26577 = EDGE_CURVE('',#26578,#26580,#26582,.T.); +#26578 = VERTEX_POINT('',#26579); +#26579 = CARTESIAN_POINT('',(-2.55,2.355,3.895)); #26580 = VERTEX_POINT('',#26581); -#26581 = CARTESIAN_POINT('',(1.4,0.495,-0.355)); -#26582 = VERTEX_POINT('',#26583); -#26583 = CARTESIAN_POINT('',(1.6,0.495,-0.355)); -#26584 = SURFACE_CURVE('',#26585,(#26589,#26596),.PCURVE_S1.); -#26585 = LINE('',#26586,#26587); -#26586 = CARTESIAN_POINT('',(1.4,0.495,-0.355)); -#26587 = VECTOR('',#26588,1.); -#26588 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26589 = PCURVE('',#24814,#26590); -#26590 = DEFINITIONAL_REPRESENTATION('',(#26591),#26595); -#26591 = LINE('',#26592,#26593); -#26592 = CARTESIAN_POINT('',(-1.6,-2.76)); -#26593 = VECTOR('',#26594,1.); -#26594 = DIRECTION('',(1.,0.E+000)); -#26595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26596 = PCURVE('',#26597,#26602); -#26597 = PLANE('',#26598); -#26598 = AXIS2_PLACEMENT_3D('',#26599,#26600,#26601); -#26599 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); -#26600 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); -#26601 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); -#26602 = DEFINITIONAL_REPRESENTATION('',(#26603),#26607); -#26603 = LINE('',#26604,#26605); -#26604 = CARTESIAN_POINT('',(0.7,3.095397202444E-018)); -#26605 = VECTOR('',#26606,1.); -#26606 = DIRECTION('',(0.E+000,-1.)); -#26607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26608 = ORIENTED_EDGE('',*,*,#26609,.T.); -#26609 = EDGE_CURVE('',#26580,#25066,#26610,.T.); -#26610 = SURFACE_CURVE('',#26611,(#26615,#26622),.PCURVE_S1.); -#26611 = LINE('',#26612,#26613); -#26612 = CARTESIAN_POINT('',(1.4,3.255,-0.355)); -#26613 = VECTOR('',#26614,1.); -#26614 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26615 = PCURVE('',#24814,#26616); -#26616 = DEFINITIONAL_REPRESENTATION('',(#26617),#26621); -#26617 = LINE('',#26618,#26619); -#26618 = CARTESIAN_POINT('',(-1.6,7.228740855008E-031)); -#26619 = VECTOR('',#26620,1.); -#26620 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26622 = PCURVE('',#25081,#26623); -#26623 = DEFINITIONAL_REPRESENTATION('',(#26624),#26628); -#26624 = LINE('',#26625,#26626); -#26625 = CARTESIAN_POINT('',(-2.81,-0.55)); -#26626 = VECTOR('',#26627,1.); -#26627 = DIRECTION('',(1.,-1.702510980039E-043)); -#26628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26629 = ORIENTED_EDGE('',*,*,#25635,.T.); +#26581 = CARTESIAN_POINT('',(-2.55,1.755,3.895)); +#26582 = SURFACE_CURVE('',#26583,(#26587,#26594),.PCURVE_S1.); +#26583 = LINE('',#26584,#26585); +#26584 = CARTESIAN_POINT('',(-2.55,2.355,3.895)); +#26585 = VECTOR('',#26586,1.); +#26586 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); +#26587 = PCURVE('',#25239,#26588); +#26588 = DEFINITIONAL_REPRESENTATION('',(#26589),#26593); +#26589 = LINE('',#26590,#26591); +#26590 = CARTESIAN_POINT('',(-0.45,-0.9)); +#26591 = VECTOR('',#26592,1.); +#26592 = DIRECTION('',(-1.445602896647E-015,-1.)); +#26593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26594 = PCURVE('',#26595,#26600); +#26595 = PLANE('',#26596); +#26596 = AXIS2_PLACEMENT_3D('',#26597,#26598,#26599); +#26597 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#26598 = DIRECTION('',(-1.,-1.445602896647E-015,7.085009279629E-015)); +#26599 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); +#26600 = DEFINITIONAL_REPRESENTATION('',(#26601),#26605); +#26601 = LINE('',#26602,#26603); +#26602 = CARTESIAN_POINT('',(5.813492048867E-017,2.4)); +#26603 = VECTOR('',#26604,1.); +#26604 = DIRECTION('',(1.,-1.308183046813E-032)); +#26605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26606 = ORIENTED_EDGE('',*,*,#26607,.F.); +#26607 = EDGE_CURVE('',#25998,#26578,#26608,.T.); +#26608 = SURFACE_CURVE('',#26609,(#26613,#26620),.PCURVE_S1.); +#26609 = LINE('',#26610,#26611); +#26610 = CARTESIAN_POINT('',(-2.2,2.355,3.895)); +#26611 = VECTOR('',#26612,1.); +#26612 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26613 = PCURVE('',#25239,#26614); +#26614 = DEFINITIONAL_REPRESENTATION('',(#26615),#26619); +#26615 = LINE('',#26616,#26617); +#26616 = CARTESIAN_POINT('',(-0.8,-0.9)); +#26617 = VECTOR('',#26618,1.); +#26618 = DIRECTION('',(1.,2.835439861407E-045)); +#26619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26620 = PCURVE('',#26036,#26621); +#26621 = DEFINITIONAL_REPRESENTATION('',(#26622),#26626); +#26622 = LINE('',#26623,#26624); +#26623 = CARTESIAN_POINT('',(-1.162698409773E-016,2.4)); +#26624 = VECTOR('',#26625,1.); +#26625 = DIRECTION('',(1.,0.E+000)); +#26626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26627 = ORIENTED_EDGE('',*,*,#25997,.F.); +#26628 = ORIENTED_EDGE('',*,*,#25221,.F.); +#26629 = ORIENTED_EDGE('',*,*,#25431,.F.); #26630 = ORIENTED_EDGE('',*,*,#26631,.F.); -#26631 = EDGE_CURVE('',#26632,#25608,#26634,.T.); +#26631 = EDGE_CURVE('',#26632,#25404,#26634,.T.); #26632 = VERTEX_POINT('',#26633); -#26633 = CARTESIAN_POINT('',(0.6,0.495,-0.355)); +#26633 = CARTESIAN_POINT('',(2.55,2.355,3.895)); #26634 = SURFACE_CURVE('',#26635,(#26639,#26646),.PCURVE_S1.); #26635 = LINE('',#26636,#26637); -#26636 = CARTESIAN_POINT('',(0.6,3.255,-0.355)); +#26636 = CARTESIAN_POINT('',(2.2,2.355,3.895)); #26637 = VECTOR('',#26638,1.); -#26638 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26639 = PCURVE('',#24814,#26640); +#26638 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26639 = PCURVE('',#25239,#26640); #26640 = DEFINITIONAL_REPRESENTATION('',(#26641),#26645); #26641 = LINE('',#26642,#26643); -#26642 = CARTESIAN_POINT('',(-2.4,9.874029978112E-031)); +#26642 = CARTESIAN_POINT('',(-5.2,-0.9)); #26643 = VECTOR('',#26644,1.); -#26644 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26644 = DIRECTION('',(1.,2.835439861407E-045)); #26645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26646 = PCURVE('',#25623,#26647); +#26646 = PCURVE('',#25419,#26647); #26647 = DEFINITIONAL_REPRESENTATION('',(#26648),#26652); #26648 = LINE('',#26649,#26650); -#26649 = CARTESIAN_POINT('',(-2.81,-0.55)); +#26649 = CARTESIAN_POINT('',(-1.162698409773E-016,2.4)); #26650 = VECTOR('',#26651,1.); -#26651 = DIRECTION('',(1.,-1.702510980039E-043)); +#26651 = DIRECTION('',(1.,0.E+000)); #26652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); #26653 = ORIENTED_EDGE('',*,*,#26654,.F.); #26654 = EDGE_CURVE('',#26655,#26632,#26657,.T.); #26655 = VERTEX_POINT('',#26656); -#26656 = CARTESIAN_POINT('',(0.4,0.495,-0.355)); +#26656 = CARTESIAN_POINT('',(2.55,1.755,3.895)); #26657 = SURFACE_CURVE('',#26658,(#26662,#26669),.PCURVE_S1.); #26658 = LINE('',#26659,#26660); -#26659 = CARTESIAN_POINT('',(0.4,0.495,-0.355)); +#26659 = CARTESIAN_POINT('',(2.55,2.355,3.895)); #26660 = VECTOR('',#26661,1.); -#26661 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26662 = PCURVE('',#24814,#26663); +#26661 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26662 = PCURVE('',#25239,#26663); #26663 = DEFINITIONAL_REPRESENTATION('',(#26664),#26668); #26664 = LINE('',#26665,#26666); -#26665 = CARTESIAN_POINT('',(-2.6,-2.76)); +#26665 = CARTESIAN_POINT('',(-5.55,-0.9)); #26666 = VECTOR('',#26667,1.); -#26667 = DIRECTION('',(1.,0.E+000)); +#26667 = DIRECTION('',(-4.608958230318E-045,1.)); #26668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); #26669 = PCURVE('',#26670,#26675); #26670 = PLANE('',#26671); #26671 = AXIS2_PLACEMENT_3D('',#26672,#26673,#26674); -#26672 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); -#26673 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); -#26674 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); +#26672 = CARTESIAN_POINT('',(2.55,2.355,1.495)); +#26673 = DIRECTION('',(1.,3.562798913235E-031,-7.085009279629E-015)); +#26674 = DIRECTION('',(-7.085009279629E-015,3.491483361109E-015,-1.)); #26675 = DEFINITIONAL_REPRESENTATION('',(#26676),#26680); #26676 = LINE('',#26677,#26678); -#26677 = CARTESIAN_POINT('',(0.7,3.095397202446E-018)); +#26677 = CARTESIAN_POINT('',(-2.4,-5.813492048867E-017)); #26678 = VECTOR('',#26679,1.); -#26679 = DIRECTION('',(0.E+000,-1.)); +#26679 = DIRECTION('',(-1.727389886288E-043,1.)); #26680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26681 = ORIENTED_EDGE('',*,*,#26682,.T.); -#26682 = EDGE_CURVE('',#26655,#25529,#26683,.T.); +#26681 = ORIENTED_EDGE('',*,*,#26682,.F.); +#26682 = EDGE_CURVE('',#25478,#26655,#26683,.T.); #26683 = SURFACE_CURVE('',#26684,(#26688,#26695),.PCURVE_S1.); #26684 = LINE('',#26685,#26686); -#26685 = CARTESIAN_POINT('',(0.4,3.255,-0.355)); +#26685 = CARTESIAN_POINT('',(2.2,1.755,3.895)); #26686 = VECTOR('',#26687,1.); -#26687 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26688 = PCURVE('',#24814,#26689); +#26687 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26688 = PCURVE('',#25239,#26689); #26689 = DEFINITIONAL_REPRESENTATION('',(#26690),#26694); #26690 = LINE('',#26691,#26692); -#26691 = CARTESIAN_POINT('',(-2.6,1.150443356329E-030)); +#26691 = CARTESIAN_POINT('',(-5.2,-1.5)); #26692 = VECTOR('',#26693,1.); -#26693 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26693 = DIRECTION('',(-1.,-2.835439861407E-045)); #26694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26695 = PCURVE('',#25567,#26696); +#26695 = PCURVE('',#25514,#26696); #26696 = DEFINITIONAL_REPRESENTATION('',(#26697),#26701); #26697 = LINE('',#26698,#26699); -#26698 = CARTESIAN_POINT('',(-2.81,-0.55)); +#26698 = CARTESIAN_POINT('',(1.162698409773E-016,2.4)); #26699 = VECTOR('',#26700,1.); -#26700 = DIRECTION('',(1.,-1.702510980039E-043)); +#26700 = DIRECTION('',(1.,0.E+000)); #26701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26702 = ORIENTED_EDGE('',*,*,#25528,.T.); -#26703 = ORIENTED_EDGE('',*,*,#26704,.F.); -#26704 = EDGE_CURVE('',#26705,#25501,#26707,.T.); -#26705 = VERTEX_POINT('',#26706); -#26706 = CARTESIAN_POINT('',(-0.4,0.495,-0.355)); +#26702 = ORIENTED_EDGE('',*,*,#25477,.F.); +#26703 = ORIENTED_EDGE('',*,*,#25681,.F.); +#26704 = ORIENTED_EDGE('',*,*,#26104,.F.); +#26705 = ORIENTED_EDGE('',*,*,#26706,.F.); +#26706 = EDGE_CURVE('',#26580,#26077,#26707,.T.); #26707 = SURFACE_CURVE('',#26708,(#26712,#26719),.PCURVE_S1.); #26708 = LINE('',#26709,#26710); -#26709 = CARTESIAN_POINT('',(-0.4,3.255,-0.355)); +#26709 = CARTESIAN_POINT('',(-2.2,1.755,3.895)); #26710 = VECTOR('',#26711,1.); -#26711 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26712 = PCURVE('',#24814,#26713); +#26711 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); +#26712 = PCURVE('',#25239,#26713); #26713 = DEFINITIONAL_REPRESENTATION('',(#26714),#26718); #26714 = LINE('',#26715,#26716); -#26715 = CARTESIAN_POINT('',(-3.4,1.414972268639E-030)); +#26715 = CARTESIAN_POINT('',(-0.8,-1.5)); #26716 = VECTOR('',#26717,1.); -#26717 = DIRECTION('',(-2.80259692865E-045,-1.)); +#26717 = DIRECTION('',(-1.,6.195440985631E-016)); #26718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26719 = PCURVE('',#25516,#26720); +#26719 = PCURVE('',#26092,#26720); #26720 = DEFINITIONAL_REPRESENTATION('',(#26721),#26725); #26721 = LINE('',#26722,#26723); -#26722 = CARTESIAN_POINT('',(-2.81,-0.55)); +#26722 = CARTESIAN_POINT('',(1.162698409773E-016,2.4)); #26723 = VECTOR('',#26724,1.); -#26724 = DIRECTION('',(1.,-1.702510980039E-043)); +#26724 = DIRECTION('',(1.,2.033782021273E-031)); #26725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#26726 = ORIENTED_EDGE('',*,*,#26727,.F.); -#26727 = EDGE_CURVE('',#26728,#26705,#26730,.T.); -#26728 = VERTEX_POINT('',#26729); -#26729 = CARTESIAN_POINT('',(-0.6,0.495,-0.355)); -#26730 = SURFACE_CURVE('',#26731,(#26735,#26742),.PCURVE_S1.); -#26731 = LINE('',#26732,#26733); -#26732 = CARTESIAN_POINT('',(-0.6,0.495,-0.355)); -#26733 = VECTOR('',#26734,1.); -#26734 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26735 = PCURVE('',#24814,#26736); -#26736 = DEFINITIONAL_REPRESENTATION('',(#26737),#26741); -#26737 = LINE('',#26738,#26739); -#26738 = CARTESIAN_POINT('',(-3.6,-2.76)); -#26739 = VECTOR('',#26740,1.); -#26740 = DIRECTION('',(1.,0.E+000)); -#26741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26742 = PCURVE('',#26743,#26748); -#26743 = PLANE('',#26744); -#26744 = AXIS2_PLACEMENT_3D('',#26745,#26746,#26747); -#26745 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); -#26746 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); -#26747 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); -#26748 = DEFINITIONAL_REPRESENTATION('',(#26749),#26753); -#26749 = LINE('',#26750,#26751); -#26750 = CARTESIAN_POINT('',(0.7,3.095397202444E-018)); -#26751 = VECTOR('',#26752,1.); -#26752 = DIRECTION('',(0.E+000,-1.)); -#26753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26754 = ORIENTED_EDGE('',*,*,#26755,.T.); -#26755 = EDGE_CURVE('',#26728,#25422,#26756,.T.); -#26756 = SURFACE_CURVE('',#26757,(#26761,#26768),.PCURVE_S1.); -#26757 = LINE('',#26758,#26759); -#26758 = CARTESIAN_POINT('',(-0.6,3.255,-0.355)); -#26759 = VECTOR('',#26760,1.); -#26760 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26761 = PCURVE('',#24814,#26762); -#26762 = DEFINITIONAL_REPRESENTATION('',(#26763),#26767); -#26763 = LINE('',#26764,#26765); -#26764 = CARTESIAN_POINT('',(-3.6,1.578012627157E-030)); -#26765 = VECTOR('',#26766,1.); -#26766 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26768 = PCURVE('',#25460,#26769); -#26769 = DEFINITIONAL_REPRESENTATION('',(#26770),#26774); -#26770 = LINE('',#26771,#26772); -#26771 = CARTESIAN_POINT('',(-2.81,-0.55)); -#26772 = VECTOR('',#26773,1.); -#26773 = DIRECTION('',(1.,-1.702510980039E-043)); -#26774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26775 = ORIENTED_EDGE('',*,*,#25421,.T.); -#26776 = ORIENTED_EDGE('',*,*,#26777,.F.); -#26777 = EDGE_CURVE('',#26778,#25394,#26780,.T.); -#26778 = VERTEX_POINT('',#26779); -#26779 = CARTESIAN_POINT('',(-1.4,0.495,-0.355)); -#26780 = SURFACE_CURVE('',#26781,(#26785,#26792),.PCURVE_S1.); -#26781 = LINE('',#26782,#26783); -#26782 = CARTESIAN_POINT('',(-1.4,3.255,-0.355)); -#26783 = VECTOR('',#26784,1.); -#26784 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26785 = PCURVE('',#24814,#26786); -#26786 = DEFINITIONAL_REPRESENTATION('',(#26787),#26791); -#26787 = LINE('',#26788,#26789); -#26788 = CARTESIAN_POINT('',(-4.4,1.842541539467E-030)); -#26789 = VECTOR('',#26790,1.); -#26790 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26792 = PCURVE('',#25409,#26793); -#26793 = DEFINITIONAL_REPRESENTATION('',(#26794),#26798); -#26794 = LINE('',#26795,#26796); -#26795 = CARTESIAN_POINT('',(-2.81,-0.55)); -#26796 = VECTOR('',#26797,1.); -#26797 = DIRECTION('',(1.,-1.702510980039E-043)); -#26798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26799 = ORIENTED_EDGE('',*,*,#26800,.F.); -#26800 = EDGE_CURVE('',#26801,#26778,#26803,.T.); -#26801 = VERTEX_POINT('',#26802); -#26802 = CARTESIAN_POINT('',(-1.6,0.495,-0.355)); -#26803 = SURFACE_CURVE('',#26804,(#26808,#26815),.PCURVE_S1.); -#26804 = LINE('',#26805,#26806); -#26805 = CARTESIAN_POINT('',(-1.6,0.495,-0.355)); -#26806 = VECTOR('',#26807,1.); -#26807 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26808 = PCURVE('',#24814,#26809); -#26809 = DEFINITIONAL_REPRESENTATION('',(#26810),#26814); -#26810 = LINE('',#26811,#26812); -#26811 = CARTESIAN_POINT('',(-4.6,-2.76)); -#26812 = VECTOR('',#26813,1.); -#26813 = DIRECTION('',(1.,0.E+000)); -#26814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26815 = PCURVE('',#26816,#26821); -#26816 = PLANE('',#26817); -#26817 = AXIS2_PLACEMENT_3D('',#26818,#26819,#26820); -#26818 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); -#26819 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); -#26820 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); -#26821 = DEFINITIONAL_REPRESENTATION('',(#26822),#26826); -#26822 = LINE('',#26823,#26824); -#26823 = CARTESIAN_POINT('',(0.7,3.095397202446E-018)); -#26824 = VECTOR('',#26825,1.); -#26825 = DIRECTION('',(0.E+000,-1.)); -#26826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26827 = ORIENTED_EDGE('',*,*,#26828,.T.); -#26828 = EDGE_CURVE('',#26801,#25315,#26829,.T.); -#26829 = SURFACE_CURVE('',#26830,(#26834,#26841),.PCURVE_S1.); -#26830 = LINE('',#26831,#26832); -#26831 = CARTESIAN_POINT('',(-1.6,3.255,-0.355)); -#26832 = VECTOR('',#26833,1.); -#26833 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26834 = PCURVE('',#24814,#26835); -#26835 = DEFINITIONAL_REPRESENTATION('',(#26836),#26840); -#26836 = LINE('',#26837,#26838); -#26837 = CARTESIAN_POINT('',(-4.6,2.005581897985E-030)); -#26838 = VECTOR('',#26839,1.); -#26839 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26841 = PCURVE('',#25353,#26842); -#26842 = DEFINITIONAL_REPRESENTATION('',(#26843),#26847); -#26843 = LINE('',#26844,#26845); -#26844 = CARTESIAN_POINT('',(-2.81,-0.55)); -#26845 = VECTOR('',#26846,1.); -#26846 = DIRECTION('',(1.,-1.702510980039E-043)); -#26847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26848 = ORIENTED_EDGE('',*,*,#25314,.T.); -#26849 = ORIENTED_EDGE('',*,*,#24798,.F.); -#26850 = ORIENTED_EDGE('',*,*,#26851,.F.); -#26851 = EDGE_CURVE('',#26852,#24771,#26854,.T.); -#26852 = VERTEX_POINT('',#26853); -#26853 = CARTESIAN_POINT('',(-2.5,1.755,-0.355)); -#26854 = SURFACE_CURVE('',#26855,(#26859,#26866),.PCURVE_S1.); -#26855 = LINE('',#26856,#26857); -#26856 = CARTESIAN_POINT('',(-2.5,1.755,-0.355)); -#26857 = VECTOR('',#26858,1.); -#26858 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26859 = PCURVE('',#24814,#26860); -#26860 = DEFINITIONAL_REPRESENTATION('',(#26861),#26865); -#26861 = LINE('',#26862,#26863); -#26862 = CARTESIAN_POINT('',(-5.5,-1.5)); -#26863 = VECTOR('',#26864,1.); -#26864 = DIRECTION('',(-1.,0.E+000)); -#26865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26866 = PCURVE('',#24786,#26867); -#26867 = DEFINITIONAL_REPRESENTATION('',(#26868),#26872); -#26868 = LINE('',#26869,#26870); -#26869 = CARTESIAN_POINT('',(1.561711914302E-016,-0.55)); -#26870 = VECTOR('',#26871,1.); -#26871 = DIRECTION('',(1.,0.E+000)); -#26872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26873 = ORIENTED_EDGE('',*,*,#26874,.T.); -#26874 = EDGE_CURVE('',#26852,#26055,#26875,.T.); -#26875 = SURFACE_CURVE('',#26876,(#26880,#26887),.PCURVE_S1.); -#26876 = LINE('',#26877,#26878); -#26877 = CARTESIAN_POINT('',(-2.5,2.755,-0.355)); -#26878 = VECTOR('',#26879,1.); -#26879 = DIRECTION('',(2.405242980303E-029,1.,3.444442850701E-015)); -#26880 = PCURVE('',#24814,#26881); -#26881 = DEFINITIONAL_REPRESENTATION('',(#26882),#26886); -#26882 = LINE('',#26883,#26884); -#26883 = CARTESIAN_POINT('',(-5.5,-0.5)); -#26884 = VECTOR('',#26885,1.); -#26885 = DIRECTION('',(5.760610793312E-033,1.)); -#26886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26887 = PCURVE('',#26091,#26888); -#26888 = DEFINITIONAL_REPRESENTATION('',(#26889),#26893); -#26889 = LINE('',#26890,#26891); -#26890 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26891 = VECTOR('',#26892,1.); -#26892 = DIRECTION('',(-1.,4.704051040836E-017)); -#26893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26894 = ORIENTED_EDGE('',*,*,#26054,.F.); -#26895 = ORIENTED_EDGE('',*,*,#26896,.F.); -#26896 = EDGE_CURVE('',#26897,#26027,#26899,.T.); -#26897 = VERTEX_POINT('',#26898); -#26898 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); -#26899 = SURFACE_CURVE('',#26900,(#26904,#26911),.PCURVE_S1.); -#26900 = LINE('',#26901,#26902); -#26901 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); -#26902 = VECTOR('',#26903,1.); -#26903 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); -#26904 = PCURVE('',#24814,#26905); -#26905 = DEFINITIONAL_REPRESENTATION('',(#26906),#26910); -#26906 = LINE('',#26907,#26908); -#26907 = CARTESIAN_POINT('',(-0.5,-1.5)); -#26908 = VECTOR('',#26909,1.); -#26909 = DIRECTION('',(2.80259692865E-045,1.)); -#26910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26911 = PCURVE('',#26042,#26912); -#26912 = DEFINITIONAL_REPRESENTATION('',(#26913),#26917); -#26913 = LINE('',#26914,#26915); -#26914 = CARTESIAN_POINT('',(1.,-5.719166459861E-018)); -#26915 = VECTOR('',#26916,1.); -#26916 = DIRECTION('',(-1.,1.702510980039E-043)); -#26917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26918 = ORIENTED_EDGE('',*,*,#26919,.T.); -#26919 = EDGE_CURVE('',#26897,#26278,#26920,.T.); -#26920 = SURFACE_CURVE('',#26921,(#26925,#26932),.PCURVE_S1.); -#26921 = LINE('',#26922,#26923); -#26922 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); -#26923 = VECTOR('',#26924,1.); -#26924 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#26925 = PCURVE('',#24814,#26926); -#26926 = DEFINITIONAL_REPRESENTATION('',(#26927),#26931); -#26927 = LINE('',#26928,#26929); -#26928 = CARTESIAN_POINT('',(-0.5,-1.5)); -#26929 = VECTOR('',#26930,1.); -#26930 = DIRECTION('',(1.,0.E+000)); -#26931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26932 = PCURVE('',#26316,#26933); -#26933 = DEFINITIONAL_REPRESENTATION('',(#26934),#26938); -#26934 = LINE('',#26935,#26936); -#26935 = CARTESIAN_POINT('',(-1.561711914302E-016,-0.55)); -#26936 = VECTOR('',#26937,1.); -#26937 = DIRECTION('',(1.,0.E+000)); -#26938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26939 = ORIENTED_EDGE('',*,*,#26277,.T.); -#26940 = ORIENTED_EDGE('',*,*,#25149,.T.); -#26941 = ORIENTED_EDGE('',*,*,#26942,.F.); -#26942 = EDGE_CURVE('',#26582,#25122,#26943,.T.); -#26943 = SURFACE_CURVE('',#26944,(#26948,#26955),.PCURVE_S1.); -#26944 = LINE('',#26945,#26946); -#26945 = CARTESIAN_POINT('',(1.6,3.255,-0.355)); -#26946 = VECTOR('',#26947,1.); -#26947 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); -#26948 = PCURVE('',#24814,#26949); -#26949 = DEFINITIONAL_REPRESENTATION('',(#26950),#26954); -#26950 = LINE('',#26951,#26952); -#26951 = CARTESIAN_POINT('',(-1.4,5.598337269832E-031)); -#26952 = VECTOR('',#26953,1.); -#26953 = DIRECTION('',(-2.80259692865E-045,-1.)); -#26954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26955 = PCURVE('',#25137,#26956); -#26956 = DEFINITIONAL_REPRESENTATION('',(#26957),#26961); -#26957 = LINE('',#26958,#26959); -#26958 = CARTESIAN_POINT('',(-2.81,-0.55)); -#26959 = VECTOR('',#26960,1.); -#26960 = DIRECTION('',(1.,-1.702510980039E-043)); -#26961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26962 = ADVANCED_FACE('',(#26963),#24893,.T.); -#26963 = FACE_BOUND('',#26964,.T.); -#26964 = EDGE_LOOP('',(#26965,#26966,#26987,#26988)); -#26965 = ORIENTED_EDGE('',*,*,#25834,.T.); -#26966 = ORIENTED_EDGE('',*,*,#26967,.T.); -#26967 = EDGE_CURVE('',#25837,#24878,#26968,.T.); -#26968 = SURFACE_CURVE('',#26969,(#26973,#26980),.PCURVE_S1.); -#26969 = LINE('',#26970,#26971); -#26970 = CARTESIAN_POINT('',(-2.5,0.905,3.395)); -#26971 = VECTOR('',#26972,1.); -#26972 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26973 = PCURVE('',#24893,#26974); -#26974 = DEFINITIONAL_REPRESENTATION('',(#26975),#26979); -#26975 = LINE('',#26976,#26977); -#26976 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#26977 = VECTOR('',#26978,1.); -#26978 = DIRECTION('',(0.E+000,1.)); -#26979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26980 = PCURVE('',#24921,#26981); -#26981 = DEFINITIONAL_REPRESENTATION('',(#26982),#26986); -#26982 = LINE('',#26983,#26984); -#26983 = CARTESIAN_POINT('',(-0.65,-1.55053008704E-029)); -#26984 = VECTOR('',#26985,1.); -#26985 = DIRECTION('',(-2.80259692865E-045,1.)); -#26986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#26987 = ORIENTED_EDGE('',*,*,#24877,.F.); -#26988 = ORIENTED_EDGE('',*,*,#26989,.F.); -#26989 = EDGE_CURVE('',#25835,#24850,#26990,.T.); -#26990 = SURFACE_CURVE('',#26991,(#26995,#27002),.PCURVE_S1.); -#26991 = LINE('',#26992,#26993); -#26992 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); -#26993 = VECTOR('',#26994,1.); -#26994 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); -#26995 = PCURVE('',#24893,#26996); -#26996 = DEFINITIONAL_REPRESENTATION('',(#26997),#27001); -#26997 = LINE('',#26998,#26999); -#26998 = CARTESIAN_POINT('',(-1.,1.224606353822E-016)); -#26999 = VECTOR('',#27000,1.); -#27000 = DIRECTION('',(0.E+000,1.)); -#27001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27002 = PCURVE('',#24865,#27003); -#27003 = DEFINITIONAL_REPRESENTATION('',(#27004),#27008); -#27004 = LINE('',#27005,#27006); -#27005 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27006 = VECTOR('',#27007,1.); -#27007 = DIRECTION('',(-2.80259692865E-045,1.)); -#27008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27009 = ADVANCED_FACE('',(#27010),#24786,.T.); -#27010 = FACE_BOUND('',#27011,.T.); -#27011 = EDGE_LOOP('',(#27012,#27013,#27014,#27035)); -#27012 = ORIENTED_EDGE('',*,*,#24768,.F.); -#27013 = ORIENTED_EDGE('',*,*,#26479,.F.); -#27014 = ORIENTED_EDGE('',*,*,#27015,.T.); -#27015 = EDGE_CURVE('',#26457,#26852,#27016,.T.); -#27016 = SURFACE_CURVE('',#27017,(#27021,#27028),.PCURVE_S1.); -#27017 = LINE('',#27018,#27019); -#27018 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); -#27019 = VECTOR('',#27020,1.); -#27020 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#27021 = PCURVE('',#24786,#27022); -#27022 = DEFINITIONAL_REPRESENTATION('',(#27023),#27027); -#27023 = LINE('',#27024,#27025); -#27024 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27025 = VECTOR('',#27026,1.); -#27026 = DIRECTION('',(0.E+000,-1.)); -#27027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27028 = PCURVE('',#26091,#27029); -#27029 = DEFINITIONAL_REPRESENTATION('',(#27030),#27034); -#27030 = LINE('',#27031,#27032); -#27031 = CARTESIAN_POINT('',(1.,-0.55)); -#27032 = VECTOR('',#27033,1.); -#27033 = DIRECTION('',(1.702510980039E-043,1.)); -#27034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27035 = ORIENTED_EDGE('',*,*,#26851,.T.); -#27036 = ADVANCED_FACE('',(#27037),#24921,.T.); -#27037 = FACE_BOUND('',#27038,.T.); -#27038 = EDGE_LOOP('',(#27039,#27040,#27041,#27042)); -#27039 = ORIENTED_EDGE('',*,*,#25926,.T.); -#27040 = ORIENTED_EDGE('',*,*,#25684,.T.); -#27041 = ORIENTED_EDGE('',*,*,#24905,.F.); -#27042 = ORIENTED_EDGE('',*,*,#26967,.F.); -#27043 = ADVANCED_FACE('',(#27044),#24865,.T.); -#27044 = FACE_BOUND('',#27045,.T.); -#27045 = EDGE_LOOP('',(#27046,#27047,#27048,#27049)); -#27046 = ORIENTED_EDGE('',*,*,#25859,.T.); -#27047 = ORIENTED_EDGE('',*,*,#26989,.T.); -#27048 = ORIENTED_EDGE('',*,*,#24849,.F.); -#27049 = ORIENTED_EDGE('',*,*,#25292,.F.); -#27050 = ADVANCED_FACE('',(#27051),#25567,.T.); -#27051 = FACE_BOUND('',#27052,.T.); -#27052 = EDGE_LOOP('',(#27053,#27054,#27077,#27105,#27133,#27154)); -#27053 = ORIENTED_EDGE('',*,*,#26682,.F.); -#27054 = ORIENTED_EDGE('',*,*,#27055,.T.); -#27055 = EDGE_CURVE('',#26655,#27056,#27058,.T.); -#27056 = VERTEX_POINT('',#27057); -#27057 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); -#27058 = SURFACE_CURVE('',#27059,(#27063,#27070),.PCURVE_S1.); -#27059 = LINE('',#27060,#27061); -#27060 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); -#27061 = VECTOR('',#27062,1.); -#27062 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27063 = PCURVE('',#25567,#27064); -#27064 = DEFINITIONAL_REPRESENTATION('',(#27065),#27069); -#27065 = LINE('',#27066,#27067); -#27066 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27067 = VECTOR('',#27068,1.); -#27068 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27070 = PCURVE('',#26670,#27071); -#27071 = DEFINITIONAL_REPRESENTATION('',(#27072),#27076); -#27072 = LINE('',#27073,#27074); -#27073 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27074 = VECTOR('',#27075,1.); -#27075 = DIRECTION('',(-1.,0.E+000)); -#27076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27077 = ORIENTED_EDGE('',*,*,#27078,.T.); -#27078 = EDGE_CURVE('',#27056,#27079,#27081,.T.); -#27079 = VERTEX_POINT('',#27080); -#27080 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); -#27081 = SURFACE_CURVE('',#27082,(#27086,#27093),.PCURVE_S1.); -#27082 = LINE('',#27083,#27084); -#27083 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); -#27084 = VECTOR('',#27085,1.); -#27085 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27086 = PCURVE('',#25567,#27087); -#27087 = DEFINITIONAL_REPRESENTATION('',(#27088),#27092); +#26726 = ADVANCED_FACE('',(#26727),#25358,.F.); +#26727 = FACE_BOUND('',#26728,.T.); +#26728 = EDGE_LOOP('',(#26729,#26730,#26731,#26732)); +#26729 = ORIENTED_EDGE('',*,*,#25344,.T.); +#26730 = ORIENTED_EDGE('',*,*,#26134,.F.); +#26731 = ORIENTED_EDGE('',*,*,#25803,.F.); +#26732 = ORIENTED_EDGE('',*,*,#26186,.T.); +#26733 = ADVANCED_FACE('',(#26734),#25391,.T.); +#26734 = FACE_BOUND('',#26735,.T.); +#26735 = EDGE_LOOP('',(#26736,#26737,#26760,#26783)); +#26736 = ORIENTED_EDGE('',*,*,#25373,.T.); +#26737 = ORIENTED_EDGE('',*,*,#26738,.T.); +#26738 = EDGE_CURVE('',#25376,#26739,#26741,.T.); +#26739 = VERTEX_POINT('',#26740); +#26740 = CARTESIAN_POINT('',(2.55,1.755,1.495)); +#26741 = SURFACE_CURVE('',#26742,(#26746,#26753),.PCURVE_S1.); +#26742 = LINE('',#26743,#26744); +#26743 = CARTESIAN_POINT('',(2.2,1.755,1.495)); +#26744 = VECTOR('',#26745,1.); +#26745 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#26746 = PCURVE('',#25391,#26747); +#26747 = DEFINITIONAL_REPRESENTATION('',(#26748),#26752); +#26748 = LINE('',#26749,#26750); +#26749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26750 = VECTOR('',#26751,1.); +#26751 = DIRECTION('',(2.80259692865E-045,-1.)); +#26752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26753 = PCURVE('',#25514,#26754); +#26754 = DEFINITIONAL_REPRESENTATION('',(#26755),#26759); +#26755 = LINE('',#26756,#26757); +#26756 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26757 = VECTOR('',#26758,1.); +#26758 = DIRECTION('',(1.,0.E+000)); +#26759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26760 = ORIENTED_EDGE('',*,*,#26761,.T.); +#26761 = EDGE_CURVE('',#26739,#26762,#26764,.T.); +#26762 = VERTEX_POINT('',#26763); +#26763 = CARTESIAN_POINT('',(2.55,2.355,1.495)); +#26764 = SURFACE_CURVE('',#26765,(#26769,#26776),.PCURVE_S1.); +#26765 = LINE('',#26766,#26767); +#26766 = CARTESIAN_POINT('',(2.55,2.355,1.495)); +#26767 = VECTOR('',#26768,1.); +#26768 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#26769 = PCURVE('',#25391,#26770); +#26770 = DEFINITIONAL_REPRESENTATION('',(#26771),#26775); +#26771 = LINE('',#26772,#26773); +#26772 = CARTESIAN_POINT('',(0.6,-0.35)); +#26773 = VECTOR('',#26774,1.); +#26774 = DIRECTION('',(1.,0.E+000)); +#26775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26776 = PCURVE('',#26670,#26777); +#26777 = DEFINITIONAL_REPRESENTATION('',(#26778),#26782); +#26778 = LINE('',#26779,#26780); +#26779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26780 = VECTOR('',#26781,1.); +#26781 = DIRECTION('',(-1.727389886288E-043,1.)); +#26782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26783 = ORIENTED_EDGE('',*,*,#26784,.T.); +#26784 = EDGE_CURVE('',#26762,#25374,#26785,.T.); +#26785 = SURFACE_CURVE('',#26786,(#26790,#26797),.PCURVE_S1.); +#26786 = LINE('',#26787,#26788); +#26787 = CARTESIAN_POINT('',(2.2,2.355,1.495)); +#26788 = VECTOR('',#26789,1.); +#26789 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26790 = PCURVE('',#25391,#26791); +#26791 = DEFINITIONAL_REPRESENTATION('',(#26792),#26796); +#26792 = LINE('',#26793,#26794); +#26793 = CARTESIAN_POINT('',(0.6,1.395477078336E-029)); +#26794 = VECTOR('',#26795,1.); +#26795 = DIRECTION('',(-2.80259692865E-045,1.)); +#26796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26797 = PCURVE('',#25419,#26798); +#26798 = DEFINITIONAL_REPRESENTATION('',(#26799),#26803); +#26799 = LINE('',#26800,#26801); +#26800 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26801 = VECTOR('',#26802,1.); +#26802 = DIRECTION('',(1.,0.E+000)); +#26803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26804 = ADVANCED_FACE('',(#26805),#25514,.F.); +#26805 = FACE_BOUND('',#26806,.T.); +#26806 = EDGE_LOOP('',(#26807,#26808,#26829,#26830)); +#26807 = ORIENTED_EDGE('',*,*,#26682,.T.); +#26808 = ORIENTED_EDGE('',*,*,#26809,.F.); +#26809 = EDGE_CURVE('',#26739,#26655,#26810,.T.); +#26810 = SURFACE_CURVE('',#26811,(#26815,#26822),.PCURVE_S1.); +#26811 = LINE('',#26812,#26813); +#26812 = CARTESIAN_POINT('',(2.55,1.755,1.495)); +#26813 = VECTOR('',#26814,1.); +#26814 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26815 = PCURVE('',#25514,#26816); +#26816 = DEFINITIONAL_REPRESENTATION('',(#26817),#26821); +#26817 = LINE('',#26818,#26819); +#26818 = CARTESIAN_POINT('',(0.35,1.547698601221E-018)); +#26819 = VECTOR('',#26820,1.); +#26820 = DIRECTION('',(1.020425574104E-016,1.)); +#26821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26822 = PCURVE('',#26670,#26823); +#26823 = DEFINITIONAL_REPRESENTATION('',(#26824),#26828); +#26824 = LINE('',#26825,#26826); +#26825 = CARTESIAN_POINT('',(-9.648857234035E-017,-0.6)); +#26826 = VECTOR('',#26827,1.); +#26827 = DIRECTION('',(-1.,1.727389886288E-043)); +#26828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26829 = ORIENTED_EDGE('',*,*,#26738,.F.); +#26830 = ORIENTED_EDGE('',*,*,#25500,.T.); +#26831 = ADVANCED_FACE('',(#26832),#25419,.F.); +#26832 = FACE_BOUND('',#26833,.T.); +#26833 = EDGE_LOOP('',(#26834,#26835,#26836,#26837)); +#26834 = ORIENTED_EDGE('',*,*,#26631,.T.); +#26835 = ORIENTED_EDGE('',*,*,#25403,.F.); +#26836 = ORIENTED_EDGE('',*,*,#26784,.F.); +#26837 = ORIENTED_EDGE('',*,*,#26838,.T.); +#26838 = EDGE_CURVE('',#26762,#26632,#26839,.T.); +#26839 = SURFACE_CURVE('',#26840,(#26844,#26851),.PCURVE_S1.); +#26840 = LINE('',#26841,#26842); +#26841 = CARTESIAN_POINT('',(2.55,2.355,1.495)); +#26842 = VECTOR('',#26843,1.); +#26843 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26844 = PCURVE('',#25419,#26845); +#26845 = DEFINITIONAL_REPRESENTATION('',(#26846),#26850); +#26846 = LINE('',#26847,#26848); +#26847 = CARTESIAN_POINT('',(-0.35,1.547698601221E-018)); +#26848 = VECTOR('',#26849,1.); +#26849 = DIRECTION('',(-1.020425574104E-016,1.)); +#26850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26851 = PCURVE('',#26670,#26852); +#26852 = DEFINITIONAL_REPRESENTATION('',(#26853),#26857); +#26853 = LINE('',#26854,#26855); +#26854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26855 = VECTOR('',#26856,1.); +#26856 = DIRECTION('',(-1.,1.727389886288E-043)); +#26857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26858 = ADVANCED_FACE('',(#26859),#25590,.F.); +#26859 = FACE_BOUND('',#26860,.T.); +#26860 = EDGE_LOOP('',(#26861,#26862,#26863,#26864)); +#26861 = ORIENTED_EDGE('',*,*,#25946,.T.); +#26862 = ORIENTED_EDGE('',*,*,#25576,.F.); +#26863 = ORIENTED_EDGE('',*,*,#25754,.F.); +#26864 = ORIENTED_EDGE('',*,*,#26213,.T.); +#26865 = ADVANCED_FACE('',(#26866),#25644,.F.); +#26866 = FACE_BOUND('',#26867,.T.); +#26867 = EDGE_LOOP('',(#26868,#26869,#26870,#26871)); +#26868 = ORIENTED_EDGE('',*,*,#26161,.T.); +#26869 = ORIENTED_EDGE('',*,*,#25897,.F.); +#26870 = ORIENTED_EDGE('',*,*,#25972,.F.); +#26871 = ORIENTED_EDGE('',*,*,#25628,.T.); +#26872 = ADVANCED_FACE('',(#26873),#26064,.T.); +#26873 = FACE_BOUND('',#26874,.T.); +#26874 = EDGE_LOOP('',(#26875,#26898,#26921,#26942)); +#26875 = ORIENTED_EDGE('',*,*,#26876,.T.); +#26876 = EDGE_CURVE('',#26021,#26877,#26879,.T.); +#26877 = VERTEX_POINT('',#26878); +#26878 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#26879 = SURFACE_CURVE('',#26880,(#26884,#26891),.PCURVE_S1.); +#26880 = LINE('',#26881,#26882); +#26881 = CARTESIAN_POINT('',(-2.2,2.355,1.495)); +#26882 = VECTOR('',#26883,1.); +#26883 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#26884 = PCURVE('',#26064,#26885); +#26885 = DEFINITIONAL_REPRESENTATION('',(#26886),#26890); +#26886 = LINE('',#26887,#26888); +#26887 = CARTESIAN_POINT('',(5.403763914175E-033,-0.35)); +#26888 = VECTOR('',#26889,1.); +#26889 = DIRECTION('',(-2.80259692865E-045,1.)); +#26890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26891 = PCURVE('',#26036,#26892); +#26892 = DEFINITIONAL_REPRESENTATION('',(#26893),#26897); +#26893 = LINE('',#26894,#26895); +#26894 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26895 = VECTOR('',#26896,1.); +#26896 = DIRECTION('',(1.,0.E+000)); +#26897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26898 = ORIENTED_EDGE('',*,*,#26899,.T.); +#26899 = EDGE_CURVE('',#26877,#26900,#26902,.T.); +#26900 = VERTEX_POINT('',#26901); +#26901 = CARTESIAN_POINT('',(-2.55,1.755,1.495)); +#26902 = SURFACE_CURVE('',#26903,(#26907,#26914),.PCURVE_S1.); +#26903 = LINE('',#26904,#26905); +#26904 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#26905 = VECTOR('',#26906,1.); +#26906 = DIRECTION('',(1.445602896647E-015,-1.,-3.491483361109E-015)); +#26907 = PCURVE('',#26064,#26908); +#26908 = DEFINITIONAL_REPRESENTATION('',(#26909),#26913); +#26909 = LINE('',#26910,#26911); +#26910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26911 = VECTOR('',#26912,1.); +#26912 = DIRECTION('',(-1.,-1.445602896647E-015)); +#26913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26914 = PCURVE('',#26595,#26915); +#26915 = DEFINITIONAL_REPRESENTATION('',(#26916),#26920); +#26916 = LINE('',#26917,#26918); +#26917 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26918 = VECTOR('',#26919,1.); +#26919 = DIRECTION('',(1.,-1.308183046813E-032)); +#26920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26921 = ORIENTED_EDGE('',*,*,#26922,.T.); +#26922 = EDGE_CURVE('',#26900,#26049,#26923,.T.); +#26923 = SURFACE_CURVE('',#26924,(#26928,#26935),.PCURVE_S1.); +#26924 = LINE('',#26925,#26926); +#26925 = CARTESIAN_POINT('',(-2.2,1.755,1.495)); +#26926 = VECTOR('',#26927,1.); +#26927 = DIRECTION('',(1.,6.195440985631E-016,-6.982966722219E-015)); +#26928 = PCURVE('',#26064,#26929); +#26929 = DEFINITIONAL_REPRESENTATION('',(#26930),#26934); +#26930 = LINE('',#26931,#26932); +#26931 = CARTESIAN_POINT('',(-0.6,-0.35)); +#26932 = VECTOR('',#26933,1.); +#26933 = DIRECTION('',(6.195440985631E-016,-1.)); +#26934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26935 = PCURVE('',#26092,#26936); +#26936 = DEFINITIONAL_REPRESENTATION('',(#26937),#26941); +#26937 = LINE('',#26938,#26939); +#26938 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26939 = VECTOR('',#26940,1.); +#26940 = DIRECTION('',(1.,2.033782021273E-031)); +#26941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26942 = ORIENTED_EDGE('',*,*,#26048,.T.); +#26943 = ADVANCED_FACE('',(#26944),#26092,.F.); +#26944 = FACE_BOUND('',#26945,.T.); +#26945 = EDGE_LOOP('',(#26946,#26947,#26948,#26949)); +#26946 = ORIENTED_EDGE('',*,*,#26706,.T.); +#26947 = ORIENTED_EDGE('',*,*,#26076,.F.); +#26948 = ORIENTED_EDGE('',*,*,#26922,.F.); +#26949 = ORIENTED_EDGE('',*,*,#26950,.T.); +#26950 = EDGE_CURVE('',#26900,#26580,#26951,.T.); +#26951 = SURFACE_CURVE('',#26952,(#26956,#26963),.PCURVE_S1.); +#26952 = LINE('',#26953,#26954); +#26953 = CARTESIAN_POINT('',(-2.55,1.755,1.495)); +#26954 = VECTOR('',#26955,1.); +#26955 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26956 = PCURVE('',#26092,#26957); +#26957 = DEFINITIONAL_REPRESENTATION('',(#26958),#26962); +#26958 = LINE('',#26959,#26960); +#26959 = CARTESIAN_POINT('',(-0.35,-1.54769860122E-018)); +#26960 = VECTOR('',#26961,1.); +#26961 = DIRECTION('',(1.020425574104E-016,1.)); +#26962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26963 = PCURVE('',#26595,#26964); +#26964 = DEFINITIONAL_REPRESENTATION('',(#26965),#26969); +#26965 = LINE('',#26966,#26967); +#26966 = CARTESIAN_POINT('',(0.6,3.185331772654E-016)); +#26967 = VECTOR('',#26968,1.); +#26968 = DIRECTION('',(-1.308183046813E-032,1.)); +#26969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26970 = ADVANCED_FACE('',(#26971),#26036,.F.); +#26971 = FACE_BOUND('',#26972,.T.); +#26972 = EDGE_LOOP('',(#26973,#26974,#26995,#26996)); +#26973 = ORIENTED_EDGE('',*,*,#26607,.T.); +#26974 = ORIENTED_EDGE('',*,*,#26975,.F.); +#26975 = EDGE_CURVE('',#26877,#26578,#26976,.T.); +#26976 = SURFACE_CURVE('',#26977,(#26981,#26988),.PCURVE_S1.); +#26977 = LINE('',#26978,#26979); +#26978 = CARTESIAN_POINT('',(-2.55,2.355,1.495)); +#26979 = VECTOR('',#26980,1.); +#26980 = DIRECTION('',(7.085009279629E-015,-3.491483361109E-015,1.)); +#26981 = PCURVE('',#26036,#26982); +#26982 = DEFINITIONAL_REPRESENTATION('',(#26983),#26987); +#26983 = LINE('',#26984,#26985); +#26984 = CARTESIAN_POINT('',(0.35,-2.235923035263E-016)); +#26985 = VECTOR('',#26986,1.); +#26986 = DIRECTION('',(-1.020425574104E-016,1.)); +#26987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26988 = PCURVE('',#26595,#26989); +#26989 = DEFINITIONAL_REPRESENTATION('',(#26990),#26994); +#26990 = LINE('',#26991,#26992); +#26991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#26992 = VECTOR('',#26993,1.); +#26993 = DIRECTION('',(-1.308183046813E-032,1.)); +#26994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#26995 = ORIENTED_EDGE('',*,*,#26876,.F.); +#26996 = ORIENTED_EDGE('',*,*,#26020,.T.); +#26997 = ADVANCED_FACE('',(#26998),#26425,.F.); +#26998 = FACE_BOUND('',#26999,.T.); +#26999 = EDGE_LOOP('',(#27000,#27023,#27051,#27072)); +#27000 = ORIENTED_EDGE('',*,*,#27001,.T.); +#27001 = EDGE_CURVE('',#26382,#27002,#27004,.T.); +#27002 = VERTEX_POINT('',#27003); +#27003 = CARTESIAN_POINT('',(2.5,0.305,2.395)); +#27004 = SURFACE_CURVE('',#27005,(#27009,#27016),.PCURVE_S1.); +#27005 = LINE('',#27006,#27007); +#27006 = CARTESIAN_POINT('',(2.5,0.305,3.895)); +#27007 = VECTOR('',#27008,1.); +#27008 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); +#27009 = PCURVE('',#26425,#27010); +#27010 = DEFINITIONAL_REPRESENTATION('',(#27011),#27015); +#27011 = LINE('',#27012,#27013); +#27012 = CARTESIAN_POINT('',(-3.797634949565E-016,0.2)); +#27013 = VECTOR('',#27014,1.); +#27014 = DIRECTION('',(1.,0.E+000)); +#27015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27016 = PCURVE('',#26397,#27017); +#27017 = DEFINITIONAL_REPRESENTATION('',(#27018),#27022); +#27018 = LINE('',#27019,#27020); +#27019 = CARTESIAN_POINT('',(-0.6,1.5)); +#27020 = VECTOR('',#27021,1.); +#27021 = DIRECTION('',(1.219727444046E-016,-1.)); +#27022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27023 = ORIENTED_EDGE('',*,*,#27024,.F.); +#27024 = EDGE_CURVE('',#27025,#27002,#27027,.T.); +#27025 = VERTEX_POINT('',#27026); +#27026 = CARTESIAN_POINT('',(2.7,0.305,2.395)); +#27027 = SURFACE_CURVE('',#27028,(#27032,#27039),.PCURVE_S1.); +#27028 = LINE('',#27029,#27030); +#27029 = CARTESIAN_POINT('',(2.7,0.305,2.395)); +#27030 = VECTOR('',#27031,1.); +#27031 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27032 = PCURVE('',#26425,#27033); +#27033 = DEFINITIONAL_REPRESENTATION('',(#27034),#27038); +#27034 = LINE('',#27035,#27036); +#27035 = CARTESIAN_POINT('',(1.5,-2.603982567767E-016)); +#27036 = VECTOR('',#27037,1.); +#27037 = DIRECTION('',(0.E+000,1.)); +#27038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27039 = PCURVE('',#27040,#27045); +#27040 = PLANE('',#27041); +#27041 = AXIS2_PLACEMENT_3D('',#27042,#27043,#27044); +#27042 = CARTESIAN_POINT('',(2.7,0.305,2.395)); +#27043 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#27044 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27045 = DEFINITIONAL_REPRESENTATION('',(#27046),#27050); +#27046 = LINE('',#27047,#27048); +#27047 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27048 = VECTOR('',#27049,1.); +#27049 = DIRECTION('',(-2.80259692865E-045,1.)); +#27050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27051 = ORIENTED_EDGE('',*,*,#27052,.F.); +#27052 = EDGE_CURVE('',#26410,#27025,#27053,.T.); +#27053 = SURFACE_CURVE('',#27054,(#27058,#27065),.PCURVE_S1.); +#27054 = LINE('',#27055,#27056); +#27055 = CARTESIAN_POINT('',(2.7,0.305,3.895)); +#27056 = VECTOR('',#27057,1.); +#27057 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); +#27058 = PCURVE('',#26425,#27059); +#27059 = DEFINITIONAL_REPRESENTATION('',(#27060),#27064); +#27060 = LINE('',#27061,#27062); +#27061 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27062 = VECTOR('',#27063,1.); +#27063 = DIRECTION('',(1.,0.E+000)); +#27064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27065 = PCURVE('',#26453,#27066); +#27066 = DEFINITIONAL_REPRESENTATION('',(#27067),#27071); +#27067 = LINE('',#27068,#27069); +#27068 = CARTESIAN_POINT('',(-0.6,1.5)); +#27069 = VECTOR('',#27070,1.); +#27070 = DIRECTION('',(1.219727444046E-016,-1.)); +#27071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27072 = ORIENTED_EDGE('',*,*,#26409,.T.); +#27073 = ADVANCED_FACE('',(#27074),#26595,.F.); +#27074 = FACE_BOUND('',#27075,.T.); +#27075 = EDGE_LOOP('',(#27076,#27077,#27078,#27079)); +#27076 = ORIENTED_EDGE('',*,*,#26577,.T.); +#27077 = ORIENTED_EDGE('',*,*,#26950,.F.); +#27078 = ORIENTED_EDGE('',*,*,#26899,.F.); +#27079 = ORIENTED_EDGE('',*,*,#26975,.T.); +#27080 = ADVANCED_FACE('',(#27081),#26341,.F.); +#27081 = FACE_BOUND('',#27082,.T.); +#27082 = EDGE_LOOP('',(#27083,#27106,#27107,#27130)); +#27083 = ORIENTED_EDGE('',*,*,#27084,.F.); +#27084 = EDGE_CURVE('',#26326,#27085,#27087,.T.); +#27085 = VERTEX_POINT('',#27086); +#27086 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); +#27087 = SURFACE_CURVE('',#27088,(#27092,#27099),.PCURVE_S1.); #27088 = LINE('',#27089,#27090); -#27089 = CARTESIAN_POINT('',(0.15,-1.25)); +#27089 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); #27090 = VECTOR('',#27091,1.); -#27091 = DIRECTION('',(1.,-2.710505431214E-015)); -#27092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27093 = PCURVE('',#27094,#27099); -#27094 = PLANE('',#27095); -#27095 = AXIS2_PLACEMENT_3D('',#27096,#27097,#27098); -#27096 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); -#27097 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); -#27098 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); -#27099 = DEFINITIONAL_REPRESENTATION('',(#27100),#27104); -#27100 = LINE('',#27101,#27102); -#27101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27102 = VECTOR('',#27103,1.); -#27103 = DIRECTION('',(-1.,0.E+000)); -#27104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27105 = ORIENTED_EDGE('',*,*,#27106,.T.); -#27106 = EDGE_CURVE('',#27079,#27107,#27109,.T.); -#27107 = VERTEX_POINT('',#27108); -#27108 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#27109 = SURFACE_CURVE('',#27110,(#27114,#27121),.PCURVE_S1.); -#27110 = LINE('',#27111,#27112); -#27111 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#27112 = VECTOR('',#27113,1.); -#27113 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27114 = PCURVE('',#25567,#27115); -#27115 = DEFINITIONAL_REPRESENTATION('',(#27116),#27120); -#27116 = LINE('',#27117,#27118); -#27117 = CARTESIAN_POINT('',(0.15,-0.45)); -#27118 = VECTOR('',#27119,1.); -#27119 = DIRECTION('',(-1.101142831431E-016,1.)); -#27120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27121 = PCURVE('',#27122,#27127); -#27122 = PLANE('',#27123); -#27123 = AXIS2_PLACEMENT_3D('',#27124,#27125,#27126); -#27124 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#27125 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); -#27126 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); -#27127 = DEFINITIONAL_REPRESENTATION('',(#27128),#27132); -#27128 = LINE('',#27129,#27130); -#27129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27130 = VECTOR('',#27131,1.); -#27131 = DIRECTION('',(-1.,0.E+000)); -#27132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27133 = ORIENTED_EDGE('',*,*,#27134,.T.); -#27134 = EDGE_CURVE('',#27107,#25552,#27135,.T.); -#27135 = SURFACE_CURVE('',#27136,(#27140,#27147),.PCURVE_S1.); -#27136 = LINE('',#27137,#27138); -#27137 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#27138 = VECTOR('',#27139,1.); -#27139 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27140 = PCURVE('',#25567,#27141); -#27141 = DEFINITIONAL_REPRESENTATION('',(#27142),#27146); -#27142 = LINE('',#27143,#27144); -#27143 = CARTESIAN_POINT('',(0.15,-0.45)); -#27144 = VECTOR('',#27145,1.); -#27145 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27147 = PCURVE('',#25595,#27148); -#27148 = DEFINITIONAL_REPRESENTATION('',(#27149),#27153); -#27149 = LINE('',#27150,#27151); -#27150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27151 = VECTOR('',#27152,1.); -#27152 = DIRECTION('',(-1.,0.E+000)); -#27153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27154 = ORIENTED_EDGE('',*,*,#25551,.T.); -#27155 = ADVANCED_FACE('',(#27156),#25137,.F.); -#27156 = FACE_BOUND('',#27157,.T.); -#27157 = EDGE_LOOP('',(#27158,#27181,#27182,#27183,#27206,#27234)); -#27158 = ORIENTED_EDGE('',*,*,#27159,.F.); -#27159 = EDGE_CURVE('',#26582,#27160,#27162,.T.); -#27160 = VERTEX_POINT('',#27161); -#27161 = CARTESIAN_POINT('',(1.6,0.495,-1.055)); -#27162 = SURFACE_CURVE('',#27163,(#27167,#27174),.PCURVE_S1.); -#27163 = LINE('',#27164,#27165); -#27164 = CARTESIAN_POINT('',(1.6,0.495,-1.055)); -#27165 = VECTOR('',#27166,1.); -#27166 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27167 = PCURVE('',#25137,#27168); -#27168 = DEFINITIONAL_REPRESENTATION('',(#27169),#27173); -#27169 = LINE('',#27170,#27171); -#27170 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27171 = VECTOR('',#27172,1.); -#27172 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27174 = PCURVE('',#26597,#27175); -#27175 = DEFINITIONAL_REPRESENTATION('',(#27176),#27180); -#27176 = LINE('',#27177,#27178); -#27177 = CARTESIAN_POINT('',(-1.577188900315E-016,-0.2)); -#27178 = VECTOR('',#27179,1.); -#27179 = DIRECTION('',(-1.,0.E+000)); -#27180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27181 = ORIENTED_EDGE('',*,*,#26942,.T.); -#27182 = ORIENTED_EDGE('',*,*,#25121,.F.); -#27183 = ORIENTED_EDGE('',*,*,#27184,.F.); -#27184 = EDGE_CURVE('',#27185,#25094,#27187,.T.); -#27185 = VERTEX_POINT('',#27186); -#27186 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); -#27187 = SURFACE_CURVE('',#27188,(#27192,#27199),.PCURVE_S1.); -#27188 = LINE('',#27189,#27190); -#27189 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); -#27190 = VECTOR('',#27191,1.); -#27191 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27192 = PCURVE('',#25137,#27193); -#27193 = DEFINITIONAL_REPRESENTATION('',(#27194),#27198); +#27091 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27092 = PCURVE('',#26341,#27093); +#27093 = DEFINITIONAL_REPRESENTATION('',(#27094),#27098); +#27094 = LINE('',#27095,#27096); +#27095 = CARTESIAN_POINT('',(-0.55,3.001302006402E-016)); +#27096 = VECTOR('',#27097,1.); +#27097 = DIRECTION('',(-1.702510980039E-043,1.)); +#27098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27099 = PCURVE('',#26369,#27100); +#27100 = DEFINITIONAL_REPRESENTATION('',(#27101),#27105); +#27101 = LINE('',#27102,#27103); +#27102 = CARTESIAN_POINT('',(0.5,2.75)); +#27103 = VECTOR('',#27104,1.); +#27104 = DIRECTION('',(0.E+000,-1.)); +#27105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27106 = ORIENTED_EDGE('',*,*,#26325,.T.); +#27107 = ORIENTED_EDGE('',*,*,#27108,.T.); +#27108 = EDGE_CURVE('',#26298,#27109,#27111,.T.); +#27109 = VERTEX_POINT('',#27110); +#27110 = CARTESIAN_POINT('',(-2.5,0.305,2.395)); +#27111 = SURFACE_CURVE('',#27112,(#27116,#27123),.PCURVE_S1.); +#27112 = LINE('',#27113,#27114); +#27113 = CARTESIAN_POINT('',(-2.5,0.305,3.895)); +#27114 = VECTOR('',#27115,1.); +#27115 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); +#27116 = PCURVE('',#26341,#27117); +#27117 = DEFINITIONAL_REPRESENTATION('',(#27118),#27122); +#27118 = LINE('',#27119,#27120); +#27119 = CARTESIAN_POINT('',(-0.6,-1.5)); +#27120 = VECTOR('',#27121,1.); +#27121 = DIRECTION('',(1.219727444046E-016,1.)); +#27122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27123 = PCURVE('',#26313,#27124); +#27124 = DEFINITIONAL_REPRESENTATION('',(#27125),#27129); +#27125 = LINE('',#27126,#27127); +#27126 = CARTESIAN_POINT('',(-3.797634949565E-016,-0.2)); +#27127 = VECTOR('',#27128,1.); +#27128 = DIRECTION('',(-1.,0.E+000)); +#27129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27130 = ORIENTED_EDGE('',*,*,#27131,.T.); +#27131 = EDGE_CURVE('',#27109,#27085,#27132,.T.); +#27132 = SURFACE_CURVE('',#27133,(#27137,#27144),.PCURVE_S1.); +#27133 = LINE('',#27134,#27135); +#27134 = CARTESIAN_POINT('',(-2.5,0.305,2.395)); +#27135 = VECTOR('',#27136,1.); +#27136 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27137 = PCURVE('',#26341,#27138); +#27138 = DEFINITIONAL_REPRESENTATION('',(#27139),#27143); +#27139 = LINE('',#27140,#27141); +#27140 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); +#27141 = VECTOR('',#27142,1.); +#27142 = DIRECTION('',(1.,-1.702510980039E-043)); +#27143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27144 = PCURVE('',#27145,#27150); +#27145 = PLANE('',#27146); +#27146 = AXIS2_PLACEMENT_3D('',#27147,#27148,#27149); +#27147 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#27148 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27149 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27150 = DEFINITIONAL_REPRESENTATION('',(#27151),#27155); +#27151 = LINE('',#27152,#27153); +#27152 = CARTESIAN_POINT('',(-2.245921632423E-031,-0.2)); +#27153 = VECTOR('',#27154,1.); +#27154 = DIRECTION('',(-1.,0.E+000)); +#27155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27156 = ADVANCED_FACE('',(#27157),#26563,.F.); +#27157 = FACE_BOUND('',#27158,.T.); +#27158 = EDGE_LOOP('',(#27159,#27189,#27217,#27240,#27268,#27296,#27324, + #27345,#27346,#27369,#27397,#27425)); +#27159 = ORIENTED_EDGE('',*,*,#27160,.T.); +#27160 = EDGE_CURVE('',#27161,#27163,#27165,.T.); +#27161 = VERTEX_POINT('',#27162); +#27162 = CARTESIAN_POINT('',(-3.,1.755,0.195)); +#27163 = VERTEX_POINT('',#27164); +#27164 = CARTESIAN_POINT('',(-3.,1.755,-0.355)); +#27165 = SURFACE_CURVE('',#27166,(#27170,#27177),.PCURVE_S1.); +#27166 = LINE('',#27167,#27168); +#27167 = CARTESIAN_POINT('',(-3.,1.755,0.195)); +#27168 = VECTOR('',#27169,1.); +#27169 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27170 = PCURVE('',#26563,#27171); +#27171 = DEFINITIONAL_REPRESENTATION('',(#27172),#27176); +#27172 = LINE('',#27173,#27174); +#27173 = CARTESIAN_POINT('',(-1.5,0.55)); +#27174 = VECTOR('',#27175,1.); +#27175 = DIRECTION('',(-1.702510980039E-043,-1.)); +#27176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27177 = PCURVE('',#27178,#27183); +#27178 = PLANE('',#27179); +#27179 = AXIS2_PLACEMENT_3D('',#27180,#27181,#27182); +#27180 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); +#27181 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27182 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); +#27183 = DEFINITIONAL_REPRESENTATION('',(#27184),#27188); +#27184 = LINE('',#27185,#27186); +#27185 = CARTESIAN_POINT('',(0.5,-2.203640915577E-017)); +#27186 = VECTOR('',#27187,1.); +#27187 = DIRECTION('',(0.E+000,-1.)); +#27188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27189 = ORIENTED_EDGE('',*,*,#27190,.T.); +#27190 = EDGE_CURVE('',#27163,#27191,#27193,.T.); +#27191 = VERTEX_POINT('',#27192); +#27192 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); +#27193 = SURFACE_CURVE('',#27194,(#27198,#27205),.PCURVE_S1.); #27194 = LINE('',#27195,#27196); -#27195 = CARTESIAN_POINT('',(0.15,-0.45)); +#27195 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); #27196 = VECTOR('',#27197,1.); -#27197 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27199 = PCURVE('',#25109,#27200); -#27200 = DEFINITIONAL_REPRESENTATION('',(#27201),#27205); -#27201 = LINE('',#27202,#27203); -#27202 = CARTESIAN_POINT('',(-2.997950493971E-032,-0.2)); -#27203 = VECTOR('',#27204,1.); -#27204 = DIRECTION('',(-1.,0.E+000)); -#27205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27206 = ORIENTED_EDGE('',*,*,#27207,.F.); -#27207 = EDGE_CURVE('',#27208,#27185,#27210,.T.); -#27208 = VERTEX_POINT('',#27209); -#27209 = CARTESIAN_POINT('',(1.6,0.295,-1.055)); -#27210 = SURFACE_CURVE('',#27211,(#27215,#27222),.PCURVE_S1.); -#27211 = LINE('',#27212,#27213); -#27212 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); -#27213 = VECTOR('',#27214,1.); -#27214 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27215 = PCURVE('',#25137,#27216); -#27216 = DEFINITIONAL_REPRESENTATION('',(#27217),#27221); -#27217 = LINE('',#27218,#27219); -#27218 = CARTESIAN_POINT('',(0.15,-0.45)); -#27219 = VECTOR('',#27220,1.); -#27220 = DIRECTION('',(-1.101142831431E-016,1.)); -#27221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27222 = PCURVE('',#27223,#27228); -#27223 = PLANE('',#27224); -#27224 = AXIS2_PLACEMENT_3D('',#27225,#27226,#27227); -#27225 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#27226 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); -#27227 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); -#27228 = DEFINITIONAL_REPRESENTATION('',(#27229),#27233); -#27229 = LINE('',#27230,#27231); -#27230 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); -#27231 = VECTOR('',#27232,1.); -#27232 = DIRECTION('',(-1.,0.E+000)); -#27233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27234 = ORIENTED_EDGE('',*,*,#27235,.F.); -#27235 = EDGE_CURVE('',#27160,#27208,#27236,.T.); -#27236 = SURFACE_CURVE('',#27237,(#27241,#27248),.PCURVE_S1.); -#27237 = LINE('',#27238,#27239); -#27238 = CARTESIAN_POINT('',(1.6,0.295,-1.055)); -#27239 = VECTOR('',#27240,1.); -#27240 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27241 = PCURVE('',#25137,#27242); -#27242 = DEFINITIONAL_REPRESENTATION('',(#27243),#27247); -#27243 = LINE('',#27244,#27245); -#27244 = CARTESIAN_POINT('',(0.15,-1.25)); -#27245 = VECTOR('',#27246,1.); -#27246 = DIRECTION('',(1.,-2.710505431214E-015)); -#27247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27248 = PCURVE('',#27249,#27254); -#27249 = PLANE('',#27250); -#27250 = AXIS2_PLACEMENT_3D('',#27251,#27252,#27253); -#27251 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); -#27252 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); -#27253 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); -#27254 = DEFINITIONAL_REPRESENTATION('',(#27255),#27259); -#27255 = LINE('',#27256,#27257); -#27256 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); -#27257 = VECTOR('',#27258,1.); -#27258 = DIRECTION('',(-1.,0.E+000)); -#27259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27260 = ADVANCED_FACE('',(#27261),#25211,.F.); -#27261 = FACE_BOUND('',#27262,.T.); -#27262 = EDGE_LOOP('',(#27263,#27284,#27285,#27286)); -#27263 = ORIENTED_EDGE('',*,*,#27264,.F.); -#27264 = EDGE_CURVE('',#25783,#26233,#27265,.T.); -#27265 = SURFACE_CURVE('',#27266,(#27270,#27277),.PCURVE_S1.); -#27266 = LINE('',#27267,#27268); -#27267 = CARTESIAN_POINT('',(2.5,0.905,2.395)); -#27268 = VECTOR('',#27269,1.); -#27269 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27270 = PCURVE('',#25211,#27271); -#27271 = DEFINITIONAL_REPRESENTATION('',(#27272),#27276); -#27272 = LINE('',#27273,#27274); -#27273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27274 = VECTOR('',#27275,1.); -#27275 = DIRECTION('',(-2.80259692865E-045,-1.)); -#27276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27277 = PCURVE('',#25819,#27278); +#27197 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27198 = PCURVE('',#26563,#27199); +#27199 = DEFINITIONAL_REPRESENTATION('',(#27200),#27204); +#27200 = LINE('',#27201,#27202); +#27201 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27202 = VECTOR('',#27203,1.); +#27203 = DIRECTION('',(-1.,-1.702510980039E-043)); +#27204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27205 = PCURVE('',#27206,#27211); +#27206 = PLANE('',#27207); +#27207 = AXIS2_PLACEMENT_3D('',#27208,#27209,#27210); +#27208 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#27209 = DIRECTION('',(7.105427357601E-015,-3.491483361109E-015,1.)); +#27210 = DIRECTION('',(1.,4.27569270828E-031,-7.105427357601E-015)); +#27211 = DEFINITIONAL_REPRESENTATION('',(#27212),#27216); +#27212 = LINE('',#27213,#27214); +#27213 = CARTESIAN_POINT('',(-6.,2.565415624968E-030)); +#27214 = VECTOR('',#27215,1.); +#27215 = DIRECTION('',(-2.80259692865E-045,-1.)); +#27216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27217 = ORIENTED_EDGE('',*,*,#27218,.T.); +#27218 = EDGE_CURVE('',#27191,#27219,#27221,.T.); +#27219 = VERTEX_POINT('',#27220); +#27220 = CARTESIAN_POINT('',(-3.,0.355,2.395)); +#27221 = SURFACE_CURVE('',#27222,(#27226,#27233),.PCURVE_S1.); +#27222 = LINE('',#27223,#27224); +#27223 = CARTESIAN_POINT('',(-3.,0.355,-0.355)); +#27224 = VECTOR('',#27225,1.); +#27225 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#27226 = PCURVE('',#26563,#27227); +#27227 = DEFINITIONAL_REPRESENTATION('',(#27228),#27232); +#27228 = LINE('',#27229,#27230); +#27229 = CARTESIAN_POINT('',(-2.9,-3.323892810297E-017)); +#27230 = VECTOR('',#27231,1.); +#27231 = DIRECTION('',(1.702510980039E-043,1.)); +#27232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27233 = PCURVE('',#26369,#27234); +#27234 = DEFINITIONAL_REPRESENTATION('',(#27235),#27239); +#27235 = LINE('',#27236,#27237); +#27236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27237 = VECTOR('',#27238,1.); +#27238 = DIRECTION('',(0.E+000,1.)); +#27239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27240 = ORIENTED_EDGE('',*,*,#27241,.T.); +#27241 = EDGE_CURVE('',#27219,#27242,#27244,.T.); +#27242 = VERTEX_POINT('',#27243); +#27243 = CARTESIAN_POINT('',(-3.,0.905,2.395)); +#27244 = SURFACE_CURVE('',#27245,(#27249,#27256),.PCURVE_S1.); +#27245 = LINE('',#27246,#27247); +#27246 = CARTESIAN_POINT('',(-3.,0.905,2.395)); +#27247 = VECTOR('',#27248,1.); +#27248 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27249 = PCURVE('',#26563,#27250); +#27250 = DEFINITIONAL_REPRESENTATION('',(#27251),#27255); +#27251 = LINE('',#27252,#27253); +#27252 = CARTESIAN_POINT('',(-2.35,2.75)); +#27253 = VECTOR('',#27254,1.); +#27254 = DIRECTION('',(1.,1.702510980039E-043)); +#27255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27256 = PCURVE('',#27257,#27262); +#27257 = PLANE('',#27258); +#27258 = AXIS2_PLACEMENT_3D('',#27259,#27260,#27261); +#27259 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); +#27260 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#27261 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27262 = DEFINITIONAL_REPRESENTATION('',(#27263),#27267); +#27263 = LINE('',#27264,#27265); +#27264 = CARTESIAN_POINT('',(2.13784635414E-031,0.5)); +#27265 = VECTOR('',#27266,1.); +#27266 = DIRECTION('',(1.,0.E+000)); +#27267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27268 = ORIENTED_EDGE('',*,*,#27269,.T.); +#27269 = EDGE_CURVE('',#27242,#27270,#27272,.T.); +#27270 = VERTEX_POINT('',#27271); +#27271 = CARTESIAN_POINT('',(-3.,0.905,3.395)); +#27272 = SURFACE_CURVE('',#27273,(#27277,#27284),.PCURVE_S1.); +#27273 = LINE('',#27274,#27275); +#27274 = CARTESIAN_POINT('',(-3.,0.905,3.395)); +#27275 = VECTOR('',#27276,1.); +#27276 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); +#27277 = PCURVE('',#26563,#27278); #27278 = DEFINITIONAL_REPRESENTATION('',(#27279),#27283); #27279 = LINE('',#27280,#27281); -#27280 = CARTESIAN_POINT('',(1.,-3.216285744678E-016)); +#27280 = CARTESIAN_POINT('',(-2.35,3.75)); #27281 = VECTOR('',#27282,1.); -#27282 = DIRECTION('',(0.E+000,-1.)); +#27282 = DIRECTION('',(-1.084202172486E-016,1.)); #27283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#27284 = ORIENTED_EDGE('',*,*,#25782,.T.); -#27285 = ORIENTED_EDGE('',*,*,#25195,.T.); -#27286 = ORIENTED_EDGE('',*,*,#26255,.T.); -#27287 = ADVANCED_FACE('',(#27288),#25353,.T.); -#27288 = FACE_BOUND('',#27289,.T.); -#27289 = EDGE_LOOP('',(#27290,#27291,#27314,#27342,#27370,#27391)); -#27290 = ORIENTED_EDGE('',*,*,#26828,.F.); -#27291 = ORIENTED_EDGE('',*,*,#27292,.T.); -#27292 = EDGE_CURVE('',#26801,#27293,#27295,.T.); -#27293 = VERTEX_POINT('',#27294); -#27294 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); -#27295 = SURFACE_CURVE('',#27296,(#27300,#27307),.PCURVE_S1.); -#27296 = LINE('',#27297,#27298); -#27297 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); -#27298 = VECTOR('',#27299,1.); -#27299 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27300 = PCURVE('',#25353,#27301); -#27301 = DEFINITIONAL_REPRESENTATION('',(#27302),#27306); -#27302 = LINE('',#27303,#27304); -#27303 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27304 = VECTOR('',#27305,1.); -#27305 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27307 = PCURVE('',#26816,#27308); -#27308 = DEFINITIONAL_REPRESENTATION('',(#27309),#27313); -#27309 = LINE('',#27310,#27311); -#27310 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27311 = VECTOR('',#27312,1.); -#27312 = DIRECTION('',(-1.,0.E+000)); -#27313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27314 = ORIENTED_EDGE('',*,*,#27315,.T.); -#27315 = EDGE_CURVE('',#27293,#27316,#27318,.T.); -#27316 = VERTEX_POINT('',#27317); -#27317 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); -#27318 = SURFACE_CURVE('',#27319,(#27323,#27330),.PCURVE_S1.); +#27284 = PCURVE('',#27285,#27290); +#27285 = PLANE('',#27286); +#27286 = AXIS2_PLACEMENT_3D('',#27287,#27288,#27289); +#27287 = CARTESIAN_POINT('',(-2.5,0.905,3.395)); +#27288 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#27289 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); +#27290 = DEFINITIONAL_REPRESENTATION('',(#27291),#27295); +#27291 = LINE('',#27292,#27293); +#27292 = CARTESIAN_POINT('',(6.123031769112E-017,0.5)); +#27293 = VECTOR('',#27294,1.); +#27294 = DIRECTION('',(1.,0.E+000)); +#27295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27296 = ORIENTED_EDGE('',*,*,#27297,.T.); +#27297 = EDGE_CURVE('',#27270,#27298,#27300,.T.); +#27298 = VERTEX_POINT('',#27299); +#27299 = CARTESIAN_POINT('',(-3.,1.555,3.395)); +#27300 = SURFACE_CURVE('',#27301,(#27305,#27312),.PCURVE_S1.); +#27301 = LINE('',#27302,#27303); +#27302 = CARTESIAN_POINT('',(-3.,1.555,3.395)); +#27303 = VECTOR('',#27304,1.); +#27304 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27305 = PCURVE('',#26563,#27306); +#27306 = DEFINITIONAL_REPRESENTATION('',(#27307),#27311); +#27307 = LINE('',#27308,#27309); +#27308 = CARTESIAN_POINT('',(-1.7,3.75)); +#27309 = VECTOR('',#27310,1.); +#27310 = DIRECTION('',(1.,1.702510980039E-043)); +#27311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27312 = PCURVE('',#27313,#27318); +#27313 = PLANE('',#27314); +#27314 = AXIS2_PLACEMENT_3D('',#27315,#27316,#27317); +#27315 = CARTESIAN_POINT('',(-2.5,1.555,3.395)); +#27316 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#27317 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27318 = DEFINITIONAL_REPRESENTATION('',(#27319),#27323); #27319 = LINE('',#27320,#27321); -#27320 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#27320 = CARTESIAN_POINT('',(2.13784635414E-031,0.5)); #27321 = VECTOR('',#27322,1.); -#27322 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27323 = PCURVE('',#25353,#27324); -#27324 = DEFINITIONAL_REPRESENTATION('',(#27325),#27329); -#27325 = LINE('',#27326,#27327); -#27326 = CARTESIAN_POINT('',(0.15,-1.25)); -#27327 = VECTOR('',#27328,1.); -#27328 = DIRECTION('',(1.,-2.710505431214E-015)); -#27329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27330 = PCURVE('',#27331,#27336); -#27331 = PLANE('',#27332); -#27332 = AXIS2_PLACEMENT_3D('',#27333,#27334,#27335); -#27333 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); -#27334 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); -#27335 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); -#27336 = DEFINITIONAL_REPRESENTATION('',(#27337),#27341); -#27337 = LINE('',#27338,#27339); -#27338 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27339 = VECTOR('',#27340,1.); -#27340 = DIRECTION('',(-1.,0.E+000)); -#27341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27342 = ORIENTED_EDGE('',*,*,#27343,.T.); -#27343 = EDGE_CURVE('',#27316,#27344,#27346,.T.); -#27344 = VERTEX_POINT('',#27345); -#27345 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#27346 = SURFACE_CURVE('',#27347,(#27351,#27358),.PCURVE_S1.); -#27347 = LINE('',#27348,#27349); -#27348 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#27349 = VECTOR('',#27350,1.); -#27350 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27351 = PCURVE('',#25353,#27352); -#27352 = DEFINITIONAL_REPRESENTATION('',(#27353),#27357); -#27353 = LINE('',#27354,#27355); -#27354 = CARTESIAN_POINT('',(0.15,-0.45)); -#27355 = VECTOR('',#27356,1.); -#27356 = DIRECTION('',(-1.101142831431E-016,1.)); -#27357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27358 = PCURVE('',#27359,#27364); -#27359 = PLANE('',#27360); -#27360 = AXIS2_PLACEMENT_3D('',#27361,#27362,#27363); -#27361 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#27362 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); -#27363 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); -#27364 = DEFINITIONAL_REPRESENTATION('',(#27365),#27369); -#27365 = LINE('',#27366,#27367); -#27366 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27367 = VECTOR('',#27368,1.); -#27368 = DIRECTION('',(-1.,0.E+000)); -#27369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27370 = ORIENTED_EDGE('',*,*,#27371,.T.); -#27371 = EDGE_CURVE('',#27344,#25338,#27372,.T.); -#27372 = SURFACE_CURVE('',#27373,(#27377,#27384),.PCURVE_S1.); -#27373 = LINE('',#27374,#27375); -#27374 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#27375 = VECTOR('',#27376,1.); -#27376 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27377 = PCURVE('',#25353,#27378); -#27378 = DEFINITIONAL_REPRESENTATION('',(#27379),#27383); -#27379 = LINE('',#27380,#27381); -#27380 = CARTESIAN_POINT('',(0.15,-0.45)); -#27381 = VECTOR('',#27382,1.); -#27382 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27384 = PCURVE('',#25381,#27385); -#27385 = DEFINITIONAL_REPRESENTATION('',(#27386),#27390); -#27386 = LINE('',#27387,#27388); -#27387 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27388 = VECTOR('',#27389,1.); -#27389 = DIRECTION('',(-1.,0.E+000)); -#27390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27391 = ORIENTED_EDGE('',*,*,#25337,.T.); -#27392 = ADVANCED_FACE('',(#27393),#25623,.F.); -#27393 = FACE_BOUND('',#27394,.T.); -#27394 = EDGE_LOOP('',(#27395,#27418,#27419,#27420,#27443,#27466)); -#27395 = ORIENTED_EDGE('',*,*,#27396,.F.); -#27396 = EDGE_CURVE('',#26632,#27397,#27399,.T.); -#27397 = VERTEX_POINT('',#27398); -#27398 = CARTESIAN_POINT('',(0.6,0.495,-1.055)); -#27399 = SURFACE_CURVE('',#27400,(#27404,#27411),.PCURVE_S1.); -#27400 = LINE('',#27401,#27402); -#27401 = CARTESIAN_POINT('',(0.6,0.495,-1.055)); -#27402 = VECTOR('',#27403,1.); -#27403 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27404 = PCURVE('',#25623,#27405); -#27405 = DEFINITIONAL_REPRESENTATION('',(#27406),#27410); -#27406 = LINE('',#27407,#27408); -#27407 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27408 = VECTOR('',#27409,1.); -#27409 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27411 = PCURVE('',#26670,#27412); -#27412 = DEFINITIONAL_REPRESENTATION('',(#27413),#27417); -#27413 = LINE('',#27414,#27415); -#27414 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); -#27415 = VECTOR('',#27416,1.); -#27416 = DIRECTION('',(-1.,0.E+000)); -#27417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27418 = ORIENTED_EDGE('',*,*,#26631,.T.); -#27419 = ORIENTED_EDGE('',*,*,#25607,.F.); -#27420 = ORIENTED_EDGE('',*,*,#27421,.F.); -#27421 = EDGE_CURVE('',#27422,#25580,#27424,.T.); -#27422 = VERTEX_POINT('',#27423); -#27423 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); -#27424 = SURFACE_CURVE('',#27425,(#27429,#27436),.PCURVE_S1.); -#27425 = LINE('',#27426,#27427); -#27426 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); -#27427 = VECTOR('',#27428,1.); -#27428 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27429 = PCURVE('',#25623,#27430); -#27430 = DEFINITIONAL_REPRESENTATION('',(#27431),#27435); -#27431 = LINE('',#27432,#27433); -#27432 = CARTESIAN_POINT('',(0.15,-0.45)); -#27433 = VECTOR('',#27434,1.); -#27434 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27436 = PCURVE('',#25595,#27437); -#27437 = DEFINITIONAL_REPRESENTATION('',(#27438),#27442); -#27438 = LINE('',#27439,#27440); -#27439 = CARTESIAN_POINT('',(-2.99795049397E-032,-0.2)); -#27440 = VECTOR('',#27441,1.); -#27441 = DIRECTION('',(-1.,0.E+000)); -#27442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27443 = ORIENTED_EDGE('',*,*,#27444,.F.); -#27444 = EDGE_CURVE('',#27445,#27422,#27447,.T.); -#27445 = VERTEX_POINT('',#27446); -#27446 = CARTESIAN_POINT('',(0.6,0.295,-1.055)); -#27447 = SURFACE_CURVE('',#27448,(#27452,#27459),.PCURVE_S1.); -#27448 = LINE('',#27449,#27450); -#27449 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); -#27450 = VECTOR('',#27451,1.); -#27451 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27452 = PCURVE('',#25623,#27453); -#27453 = DEFINITIONAL_REPRESENTATION('',(#27454),#27458); -#27454 = LINE('',#27455,#27456); -#27455 = CARTESIAN_POINT('',(0.15,-0.45)); -#27456 = VECTOR('',#27457,1.); -#27457 = DIRECTION('',(-1.101142831431E-016,1.)); -#27458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27459 = PCURVE('',#27122,#27460); -#27460 = DEFINITIONAL_REPRESENTATION('',(#27461),#27465); +#27322 = DIRECTION('',(1.,0.E+000)); +#27323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27324 = ORIENTED_EDGE('',*,*,#27325,.T.); +#27325 = EDGE_CURVE('',#27298,#26242,#27326,.T.); +#27326 = SURFACE_CURVE('',#27327,(#27331,#27338),.PCURVE_S1.); +#27327 = LINE('',#27328,#27329); +#27328 = CARTESIAN_POINT('',(-3.,1.555,3.895)); +#27329 = VECTOR('',#27330,1.); +#27330 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); +#27331 = PCURVE('',#26563,#27332); +#27332 = DEFINITIONAL_REPRESENTATION('',(#27333),#27337); +#27333 = LINE('',#27334,#27335); +#27334 = CARTESIAN_POINT('',(-1.7,4.25)); +#27335 = VECTOR('',#27336,1.); +#27336 = DIRECTION('',(4.336808689942E-016,1.)); +#27337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27338 = PCURVE('',#26257,#27339); +#27339 = DEFINITIONAL_REPRESENTATION('',(#27340),#27344); +#27340 = LINE('',#27341,#27342); +#27341 = CARTESIAN_POINT('',(-3.828588921589E-016,0.5)); +#27342 = VECTOR('',#27343,1.); +#27343 = DIRECTION('',(1.,0.E+000)); +#27344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27345 = ORIENTED_EDGE('',*,*,#26549,.F.); +#27346 = ORIENTED_EDGE('',*,*,#27347,.F.); +#27347 = EDGE_CURVE('',#27348,#26522,#27350,.T.); +#27348 = VERTEX_POINT('',#27349); +#27349 = CARTESIAN_POINT('',(-3.,3.255,1.133675134595)); +#27350 = SURFACE_CURVE('',#27351,(#27355,#27362),.PCURVE_S1.); +#27351 = LINE('',#27352,#27353); +#27352 = CARTESIAN_POINT('',(-3.,3.255,-0.355)); +#27353 = VECTOR('',#27354,1.); +#27354 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#27355 = PCURVE('',#26563,#27356); +#27356 = DEFINITIONAL_REPRESENTATION('',(#27357),#27361); +#27357 = LINE('',#27358,#27359); +#27358 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27359 = VECTOR('',#27360,1.); +#27360 = DIRECTION('',(1.702510980039E-043,1.)); +#27361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27362 = PCURVE('',#26537,#27363); +#27363 = DEFINITIONAL_REPRESENTATION('',(#27364),#27368); +#27364 = LINE('',#27365,#27366); +#27365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#27366 = VECTOR('',#27367,1.); +#27367 = DIRECTION('',(0.E+000,1.)); +#27368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27369 = ORIENTED_EDGE('',*,*,#27370,.T.); +#27370 = EDGE_CURVE('',#27348,#27371,#27373,.T.); +#27371 = VERTEX_POINT('',#27372); +#27372 = CARTESIAN_POINT('',(-3.,2.755,0.845)); +#27373 = SURFACE_CURVE('',#27374,(#27378,#27385),.PCURVE_S1.); +#27374 = LINE('',#27375,#27376); +#27375 = CARTESIAN_POINT('',(-3.,2.755,0.845)); +#27376 = VECTOR('',#27377,1.); +#27377 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); +#27378 = PCURVE('',#26563,#27379); +#27379 = DEFINITIONAL_REPRESENTATION('',(#27380),#27384); +#27380 = LINE('',#27381,#27382); +#27381 = CARTESIAN_POINT('',(-0.5,1.2)); +#27382 = VECTOR('',#27383,1.); +#27383 = DIRECTION('',(-0.866025403784,-0.5)); +#27384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27385 = PCURVE('',#27386,#27391); +#27386 = PLANE('',#27387); +#27387 = AXIS2_PLACEMENT_3D('',#27388,#27389,#27390); +#27388 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); +#27389 = DIRECTION('',(-6.047426575223E-015,0.5,-0.866025403784)); +#27390 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); +#27391 = DEFINITIONAL_REPRESENTATION('',(#27392),#27396); +#27392 = LINE('',#27393,#27394); +#27393 = CARTESIAN_POINT('',(-3.061515884556E-017,0.5)); +#27394 = VECTOR('',#27395,1.); +#27395 = DIRECTION('',(1.,1.961367055364E-030)); +#27396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27397 = ORIENTED_EDGE('',*,*,#27398,.T.); +#27398 = EDGE_CURVE('',#27371,#27399,#27401,.T.); +#27399 = VERTEX_POINT('',#27400); +#27400 = CARTESIAN_POINT('',(-3.,2.755,0.195)); +#27401 = SURFACE_CURVE('',#27402,(#27406,#27413),.PCURVE_S1.); +#27402 = LINE('',#27403,#27404); +#27403 = CARTESIAN_POINT('',(-3.,2.755,0.195)); +#27404 = VECTOR('',#27405,1.); +#27405 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27406 = PCURVE('',#26563,#27407); +#27407 = DEFINITIONAL_REPRESENTATION('',(#27408),#27412); +#27408 = LINE('',#27409,#27410); +#27409 = CARTESIAN_POINT('',(-0.5,0.55)); +#27410 = VECTOR('',#27411,1.); +#27411 = DIRECTION('',(-1.702510980039E-043,-1.)); +#27412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27413 = PCURVE('',#27414,#27419); +#27414 = PLANE('',#27415); +#27415 = AXIS2_PLACEMENT_3D('',#27416,#27417,#27418); +#27416 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#27417 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#27418 = DIRECTION('',(-1.,2.80259692865E-045,6.982966722219E-015)); +#27419 = DEFINITIONAL_REPRESENTATION('',(#27420),#27424); +#27420 = LINE('',#27421,#27422); +#27421 = CARTESIAN_POINT('',(0.5,-2.203640915577E-017)); +#27422 = VECTOR('',#27423,1.); +#27423 = DIRECTION('',(0.E+000,-1.)); +#27424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27425 = ORIENTED_EDGE('',*,*,#27426,.T.); +#27426 = EDGE_CURVE('',#27399,#27161,#27427,.T.); +#27427 = SURFACE_CURVE('',#27428,(#27432,#27439),.PCURVE_S1.); +#27428 = LINE('',#27429,#27430); +#27429 = CARTESIAN_POINT('',(-3.,2.755,0.195)); +#27430 = VECTOR('',#27431,1.); +#27431 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#27432 = PCURVE('',#26563,#27433); +#27433 = DEFINITIONAL_REPRESENTATION('',(#27434),#27438); +#27434 = LINE('',#27435,#27436); +#27435 = CARTESIAN_POINT('',(-0.5,0.55)); +#27436 = VECTOR('',#27437,1.); +#27437 = DIRECTION('',(-1.,-1.084202172486E-016)); +#27438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27439 = PCURVE('',#27440,#27445); +#27440 = PLANE('',#27441); +#27441 = AXIS2_PLACEMENT_3D('',#27442,#27443,#27444); +#27442 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#27443 = DIRECTION('',(-6.982966722219E-015,3.599903578358E-015,-1.)); +#27444 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#27445 = DEFINITIONAL_REPRESENTATION('',(#27446),#27450); +#27446 = LINE('',#27447,#27448); +#27447 = CARTESIAN_POINT('',(-2.058844780408E-032,0.5)); +#27448 = VECTOR('',#27449,1.); +#27449 = DIRECTION('',(1.,0.E+000)); +#27450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27451 = ADVANCED_FACE('',(#27452),#26369,.T.); +#27452 = FACE_BOUND('',#27453,.T.); +#27453 = EDGE_LOOP('',(#27454,#27484,#27512,#27540,#27563,#27586,#27614, + #27637,#27658,#27659,#27660,#27683,#27704,#27705,#27728,#27756, + #27784,#27812,#27835,#27863,#27891,#27919,#27942,#27970,#27998, + #28026)); +#27454 = ORIENTED_EDGE('',*,*,#27455,.F.); +#27455 = EDGE_CURVE('',#27456,#27458,#27460,.T.); +#27456 = VERTEX_POINT('',#27457); +#27457 = CARTESIAN_POINT('',(1.4,0.355,-0.255)); +#27458 = VERTEX_POINT('',#27459); +#27459 = CARTESIAN_POINT('',(1.4,0.355,-0.355)); +#27460 = SURFACE_CURVE('',#27461,(#27465,#27472),.PCURVE_S1.); #27461 = LINE('',#27462,#27463); -#27462 = CARTESIAN_POINT('',(4.669658756895E-017,-0.2)); +#27462 = CARTESIAN_POINT('',(1.4,0.355,-0.355)); #27463 = VECTOR('',#27464,1.); -#27464 = DIRECTION('',(-1.,0.E+000)); -#27465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27466 = ORIENTED_EDGE('',*,*,#27467,.F.); -#27467 = EDGE_CURVE('',#27397,#27445,#27468,.T.); -#27468 = SURFACE_CURVE('',#27469,(#27473,#27480),.PCURVE_S1.); -#27469 = LINE('',#27470,#27471); -#27470 = CARTESIAN_POINT('',(0.6,0.295,-1.055)); -#27471 = VECTOR('',#27472,1.); -#27472 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27473 = PCURVE('',#25623,#27474); -#27474 = DEFINITIONAL_REPRESENTATION('',(#27475),#27479); -#27475 = LINE('',#27476,#27477); -#27476 = CARTESIAN_POINT('',(0.15,-1.25)); -#27477 = VECTOR('',#27478,1.); -#27478 = DIRECTION('',(1.,-2.710505431214E-015)); -#27479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27480 = PCURVE('',#27094,#27481); -#27481 = DEFINITIONAL_REPRESENTATION('',(#27482),#27486); -#27482 = LINE('',#27483,#27484); -#27483 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); -#27484 = VECTOR('',#27485,1.); -#27485 = DIRECTION('',(-1.,0.E+000)); -#27486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27487 = ADVANCED_FACE('',(#27488),#25516,.F.); -#27488 = FACE_BOUND('',#27489,.T.); -#27489 = EDGE_LOOP('',(#27490,#27513,#27514,#27515,#27538,#27566)); -#27490 = ORIENTED_EDGE('',*,*,#27491,.F.); -#27491 = EDGE_CURVE('',#26705,#27492,#27494,.T.); -#27492 = VERTEX_POINT('',#27493); -#27493 = CARTESIAN_POINT('',(-0.4,0.495,-1.055)); -#27494 = SURFACE_CURVE('',#27495,(#27499,#27506),.PCURVE_S1.); +#27464 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27465 = PCURVE('',#26369,#27466); +#27466 = DEFINITIONAL_REPRESENTATION('',(#27467),#27471); +#27467 = LINE('',#27468,#27469); +#27468 = CARTESIAN_POINT('',(4.4,2.7386946877E-017)); +#27469 = VECTOR('',#27470,1.); +#27470 = DIRECTION('',(0.E+000,-1.)); +#27471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27472 = PCURVE('',#27473,#27478); +#27473 = PLANE('',#27474); +#27474 = AXIS2_PLACEMENT_3D('',#27475,#27476,#27477); +#27475 = CARTESIAN_POINT('',(1.4,0.445,0.195)); +#27476 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27477 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27478 = DEFINITIONAL_REPRESENTATION('',(#27479),#27483); +#27479 = LINE('',#27480,#27481); +#27480 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27481 = VECTOR('',#27482,1.); +#27482 = DIRECTION('',(1.702510980039E-043,-1.)); +#27483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27484 = ORIENTED_EDGE('',*,*,#27485,.T.); +#27485 = EDGE_CURVE('',#27456,#27486,#27488,.T.); +#27486 = VERTEX_POINT('',#27487); +#27487 = CARTESIAN_POINT('',(1.6,0.355,-0.255)); +#27488 = SURFACE_CURVE('',#27489,(#27493,#27500),.PCURVE_S1.); +#27489 = LINE('',#27490,#27491); +#27490 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); +#27491 = VECTOR('',#27492,1.); +#27492 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27493 = PCURVE('',#26369,#27494); +#27494 = DEFINITIONAL_REPRESENTATION('',(#27495),#27499); #27495 = LINE('',#27496,#27497); -#27496 = CARTESIAN_POINT('',(-0.4,0.495,-1.055)); +#27496 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); #27497 = VECTOR('',#27498,1.); -#27498 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27499 = PCURVE('',#25516,#27500); -#27500 = DEFINITIONAL_REPRESENTATION('',(#27501),#27505); -#27501 = LINE('',#27502,#27503); -#27502 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27503 = VECTOR('',#27504,1.); -#27504 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27506 = PCURVE('',#26743,#27507); -#27507 = DEFINITIONAL_REPRESENTATION('',(#27508),#27512); -#27508 = LINE('',#27509,#27510); -#27509 = CARTESIAN_POINT('',(-1.577188900315E-016,-0.2)); -#27510 = VECTOR('',#27511,1.); -#27511 = DIRECTION('',(-1.,0.E+000)); -#27512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27513 = ORIENTED_EDGE('',*,*,#26704,.T.); -#27514 = ORIENTED_EDGE('',*,*,#25500,.F.); -#27515 = ORIENTED_EDGE('',*,*,#27516,.F.); -#27516 = EDGE_CURVE('',#27517,#25473,#27519,.T.); -#27517 = VERTEX_POINT('',#27518); -#27518 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); -#27519 = SURFACE_CURVE('',#27520,(#27524,#27531),.PCURVE_S1.); -#27520 = LINE('',#27521,#27522); -#27521 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); -#27522 = VECTOR('',#27523,1.); -#27523 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27524 = PCURVE('',#25516,#27525); -#27525 = DEFINITIONAL_REPRESENTATION('',(#27526),#27530); -#27526 = LINE('',#27527,#27528); -#27527 = CARTESIAN_POINT('',(0.15,-0.45)); -#27528 = VECTOR('',#27529,1.); -#27529 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27531 = PCURVE('',#25488,#27532); -#27532 = DEFINITIONAL_REPRESENTATION('',(#27533),#27537); -#27533 = LINE('',#27534,#27535); -#27534 = CARTESIAN_POINT('',(-2.99795049397E-032,-0.2)); -#27535 = VECTOR('',#27536,1.); -#27536 = DIRECTION('',(-1.,0.E+000)); -#27537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27538 = ORIENTED_EDGE('',*,*,#27539,.F.); -#27539 = EDGE_CURVE('',#27540,#27517,#27542,.T.); -#27540 = VERTEX_POINT('',#27541); -#27541 = CARTESIAN_POINT('',(-0.4,0.295,-1.055)); -#27542 = SURFACE_CURVE('',#27543,(#27547,#27554),.PCURVE_S1.); -#27543 = LINE('',#27544,#27545); -#27544 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); -#27545 = VECTOR('',#27546,1.); -#27546 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27547 = PCURVE('',#25516,#27548); -#27548 = DEFINITIONAL_REPRESENTATION('',(#27549),#27553); -#27549 = LINE('',#27550,#27551); -#27550 = CARTESIAN_POINT('',(0.15,-0.45)); -#27551 = VECTOR('',#27552,1.); -#27552 = DIRECTION('',(-1.101142831431E-016,1.)); -#27553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27554 = PCURVE('',#27555,#27560); -#27555 = PLANE('',#27556); -#27556 = AXIS2_PLACEMENT_3D('',#27557,#27558,#27559); -#27557 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#27558 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); -#27559 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); -#27560 = DEFINITIONAL_REPRESENTATION('',(#27561),#27565); -#27561 = LINE('',#27562,#27563); -#27562 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); -#27563 = VECTOR('',#27564,1.); -#27564 = DIRECTION('',(-1.,0.E+000)); -#27565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27566 = ORIENTED_EDGE('',*,*,#27567,.F.); -#27567 = EDGE_CURVE('',#27492,#27540,#27568,.T.); -#27568 = SURFACE_CURVE('',#27569,(#27573,#27580),.PCURVE_S1.); -#27569 = LINE('',#27570,#27571); -#27570 = CARTESIAN_POINT('',(-0.4,0.295,-1.055)); -#27571 = VECTOR('',#27572,1.); -#27572 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27573 = PCURVE('',#25516,#27574); -#27574 = DEFINITIONAL_REPRESENTATION('',(#27575),#27579); -#27575 = LINE('',#27576,#27577); -#27576 = CARTESIAN_POINT('',(0.15,-1.25)); -#27577 = VECTOR('',#27578,1.); -#27578 = DIRECTION('',(1.,-2.710505431214E-015)); -#27579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27580 = PCURVE('',#27581,#27586); -#27581 = PLANE('',#27582); -#27582 = AXIS2_PLACEMENT_3D('',#27583,#27584,#27585); -#27583 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); -#27584 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); -#27585 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); -#27586 = DEFINITIONAL_REPRESENTATION('',(#27587),#27591); -#27587 = LINE('',#27588,#27589); -#27588 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); -#27589 = VECTOR('',#27590,1.); -#27590 = DIRECTION('',(-1.,0.E+000)); -#27591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27592 = ADVANCED_FACE('',(#27593),#25595,.F.); -#27593 = FACE_BOUND('',#27594,.T.); -#27594 = EDGE_LOOP('',(#27595,#27596,#27597,#27618)); -#27595 = ORIENTED_EDGE('',*,*,#25579,.F.); -#27596 = ORIENTED_EDGE('',*,*,#27134,.F.); -#27597 = ORIENTED_EDGE('',*,*,#27598,.T.); -#27598 = EDGE_CURVE('',#27107,#27422,#27599,.T.); -#27599 = SURFACE_CURVE('',#27600,(#27604,#27611),.PCURVE_S1.); -#27600 = LINE('',#27601,#27602); -#27601 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); -#27602 = VECTOR('',#27603,1.); -#27603 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27604 = PCURVE('',#25595,#27605); -#27605 = DEFINITIONAL_REPRESENTATION('',(#27606),#27610); -#27606 = LINE('',#27607,#27608); -#27607 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27608 = VECTOR('',#27609,1.); -#27609 = DIRECTION('',(-1.642146637881E-047,-1.)); -#27610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27611 = PCURVE('',#27122,#27612); -#27612 = DEFINITIONAL_REPRESENTATION('',(#27613),#27617); -#27613 = LINE('',#27614,#27615); -#27614 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27615 = VECTOR('',#27616,1.); -#27616 = DIRECTION('',(0.E+000,-1.)); -#27617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27618 = ORIENTED_EDGE('',*,*,#27421,.T.); -#27619 = ADVANCED_FACE('',(#27620),#25460,.T.); -#27620 = FACE_BOUND('',#27621,.T.); -#27621 = EDGE_LOOP('',(#27622,#27623,#27646,#27669,#27692,#27713)); -#27622 = ORIENTED_EDGE('',*,*,#26755,.F.); -#27623 = ORIENTED_EDGE('',*,*,#27624,.T.); -#27624 = EDGE_CURVE('',#26728,#27625,#27627,.T.); -#27625 = VERTEX_POINT('',#27626); -#27626 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); -#27627 = SURFACE_CURVE('',#27628,(#27632,#27639),.PCURVE_S1.); -#27628 = LINE('',#27629,#27630); -#27629 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); -#27630 = VECTOR('',#27631,1.); -#27631 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27632 = PCURVE('',#25460,#27633); -#27633 = DEFINITIONAL_REPRESENTATION('',(#27634),#27638); -#27634 = LINE('',#27635,#27636); -#27635 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27636 = VECTOR('',#27637,1.); -#27637 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27639 = PCURVE('',#26743,#27640); -#27640 = DEFINITIONAL_REPRESENTATION('',(#27641),#27645); -#27641 = LINE('',#27642,#27643); -#27642 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27643 = VECTOR('',#27644,1.); -#27644 = DIRECTION('',(-1.,0.E+000)); -#27645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27646 = ORIENTED_EDGE('',*,*,#27647,.T.); -#27647 = EDGE_CURVE('',#27625,#27648,#27650,.T.); -#27648 = VERTEX_POINT('',#27649); -#27649 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); -#27650 = SURFACE_CURVE('',#27651,(#27655,#27662),.PCURVE_S1.); -#27651 = LINE('',#27652,#27653); -#27652 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); -#27653 = VECTOR('',#27654,1.); -#27654 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27655 = PCURVE('',#25460,#27656); -#27656 = DEFINITIONAL_REPRESENTATION('',(#27657),#27661); -#27657 = LINE('',#27658,#27659); -#27658 = CARTESIAN_POINT('',(0.15,-1.25)); -#27659 = VECTOR('',#27660,1.); -#27660 = DIRECTION('',(1.,-2.710505431214E-015)); -#27661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27662 = PCURVE('',#27581,#27663); -#27663 = DEFINITIONAL_REPRESENTATION('',(#27664),#27668); -#27664 = LINE('',#27665,#27666); -#27665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27666 = VECTOR('',#27667,1.); -#27667 = DIRECTION('',(-1.,0.E+000)); -#27668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27669 = ORIENTED_EDGE('',*,*,#27670,.T.); -#27670 = EDGE_CURVE('',#27648,#27671,#27673,.T.); -#27671 = VERTEX_POINT('',#27672); -#27672 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#27673 = SURFACE_CURVE('',#27674,(#27678,#27685),.PCURVE_S1.); -#27674 = LINE('',#27675,#27676); -#27675 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#27676 = VECTOR('',#27677,1.); -#27677 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27678 = PCURVE('',#25460,#27679); -#27679 = DEFINITIONAL_REPRESENTATION('',(#27680),#27684); -#27680 = LINE('',#27681,#27682); -#27681 = CARTESIAN_POINT('',(0.15,-0.45)); -#27682 = VECTOR('',#27683,1.); -#27683 = DIRECTION('',(-1.101142831431E-016,1.)); -#27684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27685 = PCURVE('',#27555,#27686); -#27686 = DEFINITIONAL_REPRESENTATION('',(#27687),#27691); -#27687 = LINE('',#27688,#27689); -#27688 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27689 = VECTOR('',#27690,1.); -#27690 = DIRECTION('',(-1.,0.E+000)); -#27691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27692 = ORIENTED_EDGE('',*,*,#27693,.T.); -#27693 = EDGE_CURVE('',#27671,#25445,#27694,.T.); -#27694 = SURFACE_CURVE('',#27695,(#27699,#27706),.PCURVE_S1.); -#27695 = LINE('',#27696,#27697); -#27696 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#27697 = VECTOR('',#27698,1.); -#27698 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27699 = PCURVE('',#25460,#27700); -#27700 = DEFINITIONAL_REPRESENTATION('',(#27701),#27705); -#27701 = LINE('',#27702,#27703); -#27702 = CARTESIAN_POINT('',(0.15,-0.45)); -#27703 = VECTOR('',#27704,1.); -#27704 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27706 = PCURVE('',#25488,#27707); -#27707 = DEFINITIONAL_REPRESENTATION('',(#27708),#27712); -#27708 = LINE('',#27709,#27710); -#27709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27710 = VECTOR('',#27711,1.); -#27711 = DIRECTION('',(-1.,0.E+000)); -#27712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27713 = ORIENTED_EDGE('',*,*,#25444,.T.); -#27714 = ADVANCED_FACE('',(#27715),#25488,.F.); -#27715 = FACE_BOUND('',#27716,.T.); -#27716 = EDGE_LOOP('',(#27717,#27718,#27719,#27740)); -#27717 = ORIENTED_EDGE('',*,*,#25472,.F.); -#27718 = ORIENTED_EDGE('',*,*,#27693,.F.); -#27719 = ORIENTED_EDGE('',*,*,#27720,.T.); -#27720 = EDGE_CURVE('',#27671,#27517,#27721,.T.); -#27721 = SURFACE_CURVE('',#27722,(#27726,#27733),.PCURVE_S1.); -#27722 = LINE('',#27723,#27724); -#27723 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); -#27724 = VECTOR('',#27725,1.); -#27725 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27726 = PCURVE('',#25488,#27727); -#27727 = DEFINITIONAL_REPRESENTATION('',(#27728),#27732); -#27728 = LINE('',#27729,#27730); -#27729 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27730 = VECTOR('',#27731,1.); -#27731 = DIRECTION('',(-1.642146637881E-047,-1.)); -#27732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27733 = PCURVE('',#27555,#27734); -#27734 = DEFINITIONAL_REPRESENTATION('',(#27735),#27739); -#27735 = LINE('',#27736,#27737); -#27736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27737 = VECTOR('',#27738,1.); -#27738 = DIRECTION('',(0.E+000,-1.)); -#27739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27740 = ORIENTED_EDGE('',*,*,#27516,.T.); -#27741 = ADVANCED_FACE('',(#27742),#25409,.F.); -#27742 = FACE_BOUND('',#27743,.T.); -#27743 = EDGE_LOOP('',(#27744,#27767,#27768,#27769,#27792,#27815)); -#27744 = ORIENTED_EDGE('',*,*,#27745,.F.); -#27745 = EDGE_CURVE('',#26778,#27746,#27748,.T.); -#27746 = VERTEX_POINT('',#27747); -#27747 = CARTESIAN_POINT('',(-1.4,0.495,-1.055)); -#27748 = SURFACE_CURVE('',#27749,(#27753,#27760),.PCURVE_S1.); -#27749 = LINE('',#27750,#27751); -#27750 = CARTESIAN_POINT('',(-1.4,0.495,-1.055)); -#27751 = VECTOR('',#27752,1.); -#27752 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27753 = PCURVE('',#25409,#27754); -#27754 = DEFINITIONAL_REPRESENTATION('',(#27755),#27759); -#27755 = LINE('',#27756,#27757); -#27756 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27757 = VECTOR('',#27758,1.); -#27758 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27760 = PCURVE('',#26816,#27761); -#27761 = DEFINITIONAL_REPRESENTATION('',(#27762),#27766); -#27762 = LINE('',#27763,#27764); -#27763 = CARTESIAN_POINT('',(6.432571489356E-017,-0.2)); -#27764 = VECTOR('',#27765,1.); -#27765 = DIRECTION('',(-1.,0.E+000)); -#27766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27767 = ORIENTED_EDGE('',*,*,#26777,.T.); -#27768 = ORIENTED_EDGE('',*,*,#25393,.F.); -#27769 = ORIENTED_EDGE('',*,*,#27770,.F.); -#27770 = EDGE_CURVE('',#27771,#25366,#27773,.T.); -#27771 = VERTEX_POINT('',#27772); -#27772 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); -#27773 = SURFACE_CURVE('',#27774,(#27778,#27785),.PCURVE_S1.); -#27774 = LINE('',#27775,#27776); -#27775 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); -#27776 = VECTOR('',#27777,1.); -#27777 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27778 = PCURVE('',#25409,#27779); -#27779 = DEFINITIONAL_REPRESENTATION('',(#27780),#27784); -#27780 = LINE('',#27781,#27782); -#27781 = CARTESIAN_POINT('',(0.15,-0.45)); -#27782 = VECTOR('',#27783,1.); -#27783 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27785 = PCURVE('',#25381,#27786); -#27786 = DEFINITIONAL_REPRESENTATION('',(#27787),#27791); -#27787 = LINE('',#27788,#27789); -#27788 = CARTESIAN_POINT('',(-2.997950493971E-032,-0.2)); -#27789 = VECTOR('',#27790,1.); -#27790 = DIRECTION('',(-1.,0.E+000)); -#27791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27792 = ORIENTED_EDGE('',*,*,#27793,.F.); -#27793 = EDGE_CURVE('',#27794,#27771,#27796,.T.); -#27794 = VERTEX_POINT('',#27795); -#27795 = CARTESIAN_POINT('',(-1.4,0.295,-1.055)); -#27796 = SURFACE_CURVE('',#27797,(#27801,#27808),.PCURVE_S1.); -#27797 = LINE('',#27798,#27799); -#27798 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); -#27799 = VECTOR('',#27800,1.); -#27800 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27801 = PCURVE('',#25409,#27802); -#27802 = DEFINITIONAL_REPRESENTATION('',(#27803),#27807); -#27803 = LINE('',#27804,#27805); -#27804 = CARTESIAN_POINT('',(0.15,-0.45)); -#27805 = VECTOR('',#27806,1.); -#27806 = DIRECTION('',(-1.101142831431E-016,1.)); -#27807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27808 = PCURVE('',#27359,#27809); -#27809 = DEFINITIONAL_REPRESENTATION('',(#27810),#27814); -#27810 = LINE('',#27811,#27812); -#27811 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); -#27812 = VECTOR('',#27813,1.); -#27813 = DIRECTION('',(-1.,0.E+000)); -#27814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27815 = ORIENTED_EDGE('',*,*,#27816,.F.); -#27816 = EDGE_CURVE('',#27746,#27794,#27817,.T.); -#27817 = SURFACE_CURVE('',#27818,(#27822,#27829),.PCURVE_S1.); -#27818 = LINE('',#27819,#27820); -#27819 = CARTESIAN_POINT('',(-1.4,0.295,-1.055)); -#27820 = VECTOR('',#27821,1.); -#27821 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27822 = PCURVE('',#25409,#27823); -#27823 = DEFINITIONAL_REPRESENTATION('',(#27824),#27828); -#27824 = LINE('',#27825,#27826); -#27825 = CARTESIAN_POINT('',(0.15,-1.25)); -#27826 = VECTOR('',#27827,1.); -#27827 = DIRECTION('',(1.,-2.710505431214E-015)); -#27828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27829 = PCURVE('',#27331,#27830); -#27830 = DEFINITIONAL_REPRESENTATION('',(#27831),#27835); -#27831 = LINE('',#27832,#27833); -#27832 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); -#27833 = VECTOR('',#27834,1.); -#27834 = DIRECTION('',(-1.,0.E+000)); -#27835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27836 = ADVANCED_FACE('',(#27837),#25381,.F.); -#27837 = FACE_BOUND('',#27838,.T.); -#27838 = EDGE_LOOP('',(#27839,#27840,#27841,#27862)); -#27839 = ORIENTED_EDGE('',*,*,#25365,.F.); -#27840 = ORIENTED_EDGE('',*,*,#27371,.F.); -#27841 = ORIENTED_EDGE('',*,*,#27842,.T.); -#27842 = EDGE_CURVE('',#27344,#27771,#27843,.T.); -#27843 = SURFACE_CURVE('',#27844,(#27848,#27855),.PCURVE_S1.); -#27844 = LINE('',#27845,#27846); -#27845 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); -#27846 = VECTOR('',#27847,1.); -#27847 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27848 = PCURVE('',#25381,#27849); -#27849 = DEFINITIONAL_REPRESENTATION('',(#27850),#27854); -#27850 = LINE('',#27851,#27852); -#27851 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27852 = VECTOR('',#27853,1.); -#27853 = DIRECTION('',(-1.642146637881E-047,-1.)); -#27854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27855 = PCURVE('',#27359,#27856); -#27856 = DEFINITIONAL_REPRESENTATION('',(#27857),#27861); -#27857 = LINE('',#27858,#27859); -#27858 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27859 = VECTOR('',#27860,1.); -#27860 = DIRECTION('',(0.E+000,-1.)); -#27861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27862 = ORIENTED_EDGE('',*,*,#27770,.T.); -#27863 = ADVANCED_FACE('',(#27864),#25081,.T.); -#27864 = FACE_BOUND('',#27865,.T.); -#27865 = EDGE_LOOP('',(#27866,#27867,#27890,#27913,#27936,#27957)); -#27866 = ORIENTED_EDGE('',*,*,#26609,.F.); -#27867 = ORIENTED_EDGE('',*,*,#27868,.T.); -#27868 = EDGE_CURVE('',#26580,#27869,#27871,.T.); -#27869 = VERTEX_POINT('',#27870); -#27870 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); -#27871 = SURFACE_CURVE('',#27872,(#27876,#27883),.PCURVE_S1.); -#27872 = LINE('',#27873,#27874); -#27873 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); -#27874 = VECTOR('',#27875,1.); -#27875 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); -#27876 = PCURVE('',#25081,#27877); -#27877 = DEFINITIONAL_REPRESENTATION('',(#27878),#27882); -#27878 = LINE('',#27879,#27880); -#27879 = CARTESIAN_POINT('',(-5.E-002,-1.25)); -#27880 = VECTOR('',#27881,1.); -#27881 = DIRECTION('',(-7.744301232039E-017,-1.)); -#27882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27883 = PCURVE('',#26597,#27884); -#27884 = DEFINITIONAL_REPRESENTATION('',(#27885),#27889); -#27885 = LINE('',#27886,#27887); -#27886 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27887 = VECTOR('',#27888,1.); -#27888 = DIRECTION('',(-1.,0.E+000)); -#27889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27890 = ORIENTED_EDGE('',*,*,#27891,.T.); -#27891 = EDGE_CURVE('',#27869,#27892,#27894,.T.); -#27892 = VERTEX_POINT('',#27893); -#27893 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); -#27894 = SURFACE_CURVE('',#27895,(#27899,#27906),.PCURVE_S1.); -#27895 = LINE('',#27896,#27897); -#27896 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); -#27897 = VECTOR('',#27898,1.); -#27898 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); -#27899 = PCURVE('',#25081,#27900); -#27900 = DEFINITIONAL_REPRESENTATION('',(#27901),#27905); -#27901 = LINE('',#27902,#27903); -#27902 = CARTESIAN_POINT('',(0.15,-1.25)); -#27903 = VECTOR('',#27904,1.); -#27904 = DIRECTION('',(1.,-2.710505431214E-015)); -#27905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27906 = PCURVE('',#27249,#27907); -#27907 = DEFINITIONAL_REPRESENTATION('',(#27908),#27912); -#27908 = LINE('',#27909,#27910); -#27909 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27910 = VECTOR('',#27911,1.); -#27911 = DIRECTION('',(-1.,0.E+000)); -#27912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27913 = ORIENTED_EDGE('',*,*,#27914,.T.); -#27914 = EDGE_CURVE('',#27892,#27915,#27917,.T.); -#27915 = VERTEX_POINT('',#27916); -#27916 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#27917 = SURFACE_CURVE('',#27918,(#27922,#27929),.PCURVE_S1.); -#27918 = LINE('',#27919,#27920); -#27919 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#27920 = VECTOR('',#27921,1.); -#27921 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); -#27922 = PCURVE('',#25081,#27923); -#27923 = DEFINITIONAL_REPRESENTATION('',(#27924),#27928); +#27498 = DIRECTION('',(1.,0.E+000)); +#27499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27500 = PCURVE('',#27501,#27506); +#27501 = PLANE('',#27502); +#27502 = AXIS2_PLACEMENT_3D('',#27503,#27504,#27505); +#27503 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#27504 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); +#27505 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); +#27506 = DEFINITIONAL_REPRESENTATION('',(#27507),#27511); +#27507 = LINE('',#27508,#27509); +#27508 = CARTESIAN_POINT('',(-6.E-002,4.4)); +#27509 = VECTOR('',#27510,1.); +#27510 = DIRECTION('',(-1.642146637881E-047,-1.)); +#27511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27512 = ORIENTED_EDGE('',*,*,#27513,.T.); +#27513 = EDGE_CURVE('',#27486,#27514,#27516,.T.); +#27514 = VERTEX_POINT('',#27515); +#27515 = CARTESIAN_POINT('',(1.6,0.355,-0.355)); +#27516 = SURFACE_CURVE('',#27517,(#27521,#27528),.PCURVE_S1.); +#27517 = LINE('',#27518,#27519); +#27518 = CARTESIAN_POINT('',(1.6,0.355,-0.355)); +#27519 = VECTOR('',#27520,1.); +#27520 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27521 = PCURVE('',#26369,#27522); +#27522 = DEFINITIONAL_REPRESENTATION('',(#27523),#27527); +#27523 = LINE('',#27524,#27525); +#27524 = CARTESIAN_POINT('',(4.6,-1.930964069196E-017)); +#27525 = VECTOR('',#27526,1.); +#27526 = DIRECTION('',(0.E+000,-1.)); +#27527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27528 = PCURVE('',#27529,#27534); +#27529 = PLANE('',#27530); +#27530 = AXIS2_PLACEMENT_3D('',#27531,#27532,#27533); +#27531 = CARTESIAN_POINT('',(1.6,0.445,0.195)); +#27532 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27533 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27534 = DEFINITIONAL_REPRESENTATION('',(#27535),#27539); +#27535 = LINE('',#27536,#27537); +#27536 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27537 = VECTOR('',#27538,1.); +#27538 = DIRECTION('',(1.702510980039E-043,-1.)); +#27539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27540 = ORIENTED_EDGE('',*,*,#27541,.F.); +#27541 = EDGE_CURVE('',#27542,#27514,#27544,.T.); +#27542 = VERTEX_POINT('',#27543); +#27543 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#27544 = SURFACE_CURVE('',#27545,(#27549,#27556),.PCURVE_S1.); +#27545 = LINE('',#27546,#27547); +#27546 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#27547 = VECTOR('',#27548,1.); +#27548 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#27549 = PCURVE('',#26369,#27550); +#27550 = DEFINITIONAL_REPRESENTATION('',(#27551),#27555); +#27551 = LINE('',#27552,#27553); +#27552 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); +#27553 = VECTOR('',#27554,1.); +#27554 = DIRECTION('',(-1.,1.224606353822E-016)); +#27555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27556 = PCURVE('',#27206,#27557); +#27557 = DEFINITIONAL_REPRESENTATION('',(#27558),#27562); +#27558 = LINE('',#27559,#27560); +#27559 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#27560 = VECTOR('',#27561,1.); +#27561 = DIRECTION('',(-1.,0.E+000)); +#27562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27563 = ORIENTED_EDGE('',*,*,#27564,.F.); +#27564 = EDGE_CURVE('',#27565,#27542,#27567,.T.); +#27565 = VERTEX_POINT('',#27566); +#27566 = CARTESIAN_POINT('',(3.,0.355,2.395)); +#27567 = SURFACE_CURVE('',#27568,(#27572,#27579),.PCURVE_S1.); +#27568 = LINE('',#27569,#27570); +#27569 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#27570 = VECTOR('',#27571,1.); +#27571 = DIRECTION('',(-7.18705183704E-015,3.491483361109E-015,-1.)); +#27572 = PCURVE('',#26369,#27573); +#27573 = DEFINITIONAL_REPRESENTATION('',(#27574),#27578); +#27574 = LINE('',#27575,#27576); +#27575 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); +#27576 = VECTOR('',#27577,1.); +#27577 = DIRECTION('',(-2.040851148208E-016,-1.)); +#27578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27579 = PCURVE('',#26509,#27580); +#27580 = DEFINITIONAL_REPRESENTATION('',(#27581),#27585); +#27581 = LINE('',#27582,#27583); +#27582 = CARTESIAN_POINT('',(7.778337435954E-017,-2.9)); +#27583 = VECTOR('',#27584,1.); +#27584 = DIRECTION('',(-1.,-1.752268792537E-043)); +#27585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27586 = ORIENTED_EDGE('',*,*,#27587,.F.); +#27587 = EDGE_CURVE('',#27588,#27565,#27590,.T.); +#27588 = VERTEX_POINT('',#27589); +#27589 = CARTESIAN_POINT('',(2.7,0.355,2.395)); +#27590 = SURFACE_CURVE('',#27591,(#27595,#27602),.PCURVE_S1.); +#27591 = LINE('',#27592,#27593); +#27592 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#27593 = VECTOR('',#27594,1.); +#27594 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27595 = PCURVE('',#26369,#27596); +#27596 = DEFINITIONAL_REPRESENTATION('',(#27597),#27601); +#27597 = LINE('',#27598,#27599); +#27598 = CARTESIAN_POINT('',(5.5,2.75)); +#27599 = VECTOR('',#27600,1.); +#27600 = DIRECTION('',(1.,0.E+000)); +#27601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27602 = PCURVE('',#27603,#27608); +#27603 = PLANE('',#27604); +#27604 = AXIS2_PLACEMENT_3D('',#27605,#27606,#27607); +#27605 = CARTESIAN_POINT('',(2.5,0.905,2.395)); +#27606 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27607 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27608 = DEFINITIONAL_REPRESENTATION('',(#27609),#27613); +#27609 = LINE('',#27610,#27611); +#27610 = CARTESIAN_POINT('',(0.55,-1.240424069632E-029)); +#27611 = VECTOR('',#27612,1.); +#27612 = DIRECTION('',(-2.80259692865E-045,-1.)); +#27613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27614 = ORIENTED_EDGE('',*,*,#27615,.F.); +#27615 = EDGE_CURVE('',#27616,#27588,#27618,.T.); +#27616 = VERTEX_POINT('',#27617); +#27617 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#27618 = SURFACE_CURVE('',#27619,(#27623,#27630),.PCURVE_S1.); +#27619 = LINE('',#27620,#27621); +#27620 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#27621 = VECTOR('',#27622,1.); +#27622 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27623 = PCURVE('',#26369,#27624); +#27624 = DEFINITIONAL_REPRESENTATION('',(#27625),#27629); +#27625 = LINE('',#27626,#27627); +#27626 = CARTESIAN_POINT('',(5.5,2.75)); +#27627 = VECTOR('',#27628,1.); +#27628 = DIRECTION('',(1.,0.E+000)); +#27629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27630 = PCURVE('',#27040,#27631); +#27631 = DEFINITIONAL_REPRESENTATION('',(#27632),#27636); +#27632 = LINE('',#27633,#27634); +#27633 = CARTESIAN_POINT('',(5.E-002,0.2)); +#27634 = VECTOR('',#27635,1.); +#27635 = DIRECTION('',(2.80259692865E-045,-1.)); +#27636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27637 = ORIENTED_EDGE('',*,*,#27638,.F.); +#27638 = EDGE_CURVE('',#26354,#27616,#27639,.T.); +#27639 = SURFACE_CURVE('',#27640,(#27644,#27651),.PCURVE_S1.); +#27640 = LINE('',#27641,#27642); +#27641 = CARTESIAN_POINT('',(2.5,0.355,2.395)); +#27642 = VECTOR('',#27643,1.); +#27643 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27644 = PCURVE('',#26369,#27645); +#27645 = DEFINITIONAL_REPRESENTATION('',(#27646),#27650); +#27646 = LINE('',#27647,#27648); +#27647 = CARTESIAN_POINT('',(5.5,2.75)); +#27648 = VECTOR('',#27649,1.); +#27649 = DIRECTION('',(0.E+000,-1.)); +#27650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27651 = PCURVE('',#26397,#27652); +#27652 = DEFINITIONAL_REPRESENTATION('',(#27653),#27657); +#27653 = LINE('',#27654,#27655); +#27654 = CARTESIAN_POINT('',(-0.55,-3.001302006402E-016)); +#27655 = VECTOR('',#27656,1.); +#27656 = DIRECTION('',(-1.702510980039E-043,-1.)); +#27657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27658 = ORIENTED_EDGE('',*,*,#26353,.F.); +#27659 = ORIENTED_EDGE('',*,*,#27084,.T.); +#27660 = ORIENTED_EDGE('',*,*,#27661,.T.); +#27661 = EDGE_CURVE('',#27085,#27662,#27664,.T.); +#27662 = VERTEX_POINT('',#27663); +#27663 = CARTESIAN_POINT('',(-2.7,0.355,2.395)); +#27664 = SURFACE_CURVE('',#27665,(#27669,#27676),.PCURVE_S1.); +#27665 = LINE('',#27666,#27667); +#27666 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); +#27667 = VECTOR('',#27668,1.); +#27668 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27669 = PCURVE('',#26369,#27670); +#27670 = DEFINITIONAL_REPRESENTATION('',(#27671),#27675); +#27671 = LINE('',#27672,#27673); +#27672 = CARTESIAN_POINT('',(0.5,2.75)); +#27673 = VECTOR('',#27674,1.); +#27674 = DIRECTION('',(-1.,0.E+000)); +#27675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27676 = PCURVE('',#27145,#27677); +#27677 = DEFINITIONAL_REPRESENTATION('',(#27678),#27682); +#27678 = LINE('',#27679,#27680); +#27679 = CARTESIAN_POINT('',(-5.E-002,-0.2)); +#27680 = VECTOR('',#27681,1.); +#27681 = DIRECTION('',(2.80259692865E-045,1.)); +#27682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27683 = ORIENTED_EDGE('',*,*,#27684,.T.); +#27684 = EDGE_CURVE('',#27662,#27219,#27685,.T.); +#27685 = SURFACE_CURVE('',#27686,(#27690,#27697),.PCURVE_S1.); +#27686 = LINE('',#27687,#27688); +#27687 = CARTESIAN_POINT('',(-2.5,0.355,2.395)); +#27688 = VECTOR('',#27689,1.); +#27689 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27690 = PCURVE('',#26369,#27691); +#27691 = DEFINITIONAL_REPRESENTATION('',(#27692),#27696); +#27692 = LINE('',#27693,#27694); +#27693 = CARTESIAN_POINT('',(0.5,2.75)); +#27694 = VECTOR('',#27695,1.); +#27695 = DIRECTION('',(-1.,0.E+000)); +#27696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27697 = PCURVE('',#27257,#27698); +#27698 = DEFINITIONAL_REPRESENTATION('',(#27699),#27703); +#27699 = LINE('',#27700,#27701); +#27700 = CARTESIAN_POINT('',(-0.55,-1.240424069632E-029)); +#27701 = VECTOR('',#27702,1.); +#27702 = DIRECTION('',(-2.80259692865E-045,1.)); +#27703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27704 = ORIENTED_EDGE('',*,*,#27218,.F.); +#27705 = ORIENTED_EDGE('',*,*,#27706,.F.); +#27706 = EDGE_CURVE('',#27707,#27191,#27709,.T.); +#27707 = VERTEX_POINT('',#27708); +#27708 = CARTESIAN_POINT('',(-1.6,0.355,-0.355)); +#27709 = SURFACE_CURVE('',#27710,(#27714,#27721),.PCURVE_S1.); +#27710 = LINE('',#27711,#27712); +#27711 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#27712 = VECTOR('',#27713,1.); +#27713 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#27714 = PCURVE('',#26369,#27715); +#27715 = DEFINITIONAL_REPRESENTATION('',(#27716),#27720); +#27716 = LINE('',#27717,#27718); +#27717 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); +#27718 = VECTOR('',#27719,1.); +#27719 = DIRECTION('',(-1.,1.224606353822E-016)); +#27720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27721 = PCURVE('',#27206,#27722); +#27722 = DEFINITIONAL_REPRESENTATION('',(#27723),#27727); +#27723 = LINE('',#27724,#27725); +#27724 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#27725 = VECTOR('',#27726,1.); +#27726 = DIRECTION('',(-1.,0.E+000)); +#27727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27728 = ORIENTED_EDGE('',*,*,#27729,.F.); +#27729 = EDGE_CURVE('',#27730,#27707,#27732,.T.); +#27730 = VERTEX_POINT('',#27731); +#27731 = CARTESIAN_POINT('',(-1.6,0.355,-0.255)); +#27732 = SURFACE_CURVE('',#27733,(#27737,#27744),.PCURVE_S1.); +#27733 = LINE('',#27734,#27735); +#27734 = CARTESIAN_POINT('',(-1.6,0.355,-0.355)); +#27735 = VECTOR('',#27736,1.); +#27736 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27737 = PCURVE('',#26369,#27738); +#27738 = DEFINITIONAL_REPRESENTATION('',(#27739),#27743); +#27739 = LINE('',#27740,#27741); +#27740 = CARTESIAN_POINT('',(1.4,6.170194563616E-017)); +#27741 = VECTOR('',#27742,1.); +#27742 = DIRECTION('',(0.E+000,-1.)); +#27743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27744 = PCURVE('',#27745,#27750); +#27745 = PLANE('',#27746); +#27746 = AXIS2_PLACEMENT_3D('',#27747,#27748,#27749); +#27747 = CARTESIAN_POINT('',(-1.6,0.445,0.195)); +#27748 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27749 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27750 = DEFINITIONAL_REPRESENTATION('',(#27751),#27755); +#27751 = LINE('',#27752,#27753); +#27752 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27753 = VECTOR('',#27754,1.); +#27754 = DIRECTION('',(1.702510980039E-043,-1.)); +#27755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27756 = ORIENTED_EDGE('',*,*,#27757,.T.); +#27757 = EDGE_CURVE('',#27730,#27758,#27760,.T.); +#27758 = VERTEX_POINT('',#27759); +#27759 = CARTESIAN_POINT('',(-1.4,0.355,-0.255)); +#27760 = SURFACE_CURVE('',#27761,(#27765,#27772),.PCURVE_S1.); +#27761 = LINE('',#27762,#27763); +#27762 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); +#27763 = VECTOR('',#27764,1.); +#27764 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27765 = PCURVE('',#26369,#27766); +#27766 = DEFINITIONAL_REPRESENTATION('',(#27767),#27771); +#27767 = LINE('',#27768,#27769); +#27768 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); +#27769 = VECTOR('',#27770,1.); +#27770 = DIRECTION('',(1.,0.E+000)); +#27771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27772 = PCURVE('',#27773,#27778); +#27773 = PLANE('',#27774); +#27774 = AXIS2_PLACEMENT_3D('',#27775,#27776,#27777); +#27775 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#27776 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); +#27777 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); +#27778 = DEFINITIONAL_REPRESENTATION('',(#27779),#27783); +#27779 = LINE('',#27780,#27781); +#27780 = CARTESIAN_POINT('',(-6.E-002,1.4)); +#27781 = VECTOR('',#27782,1.); +#27782 = DIRECTION('',(-1.642146637881E-047,-1.)); +#27783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27784 = ORIENTED_EDGE('',*,*,#27785,.T.); +#27785 = EDGE_CURVE('',#27758,#27786,#27788,.T.); +#27786 = VERTEX_POINT('',#27787); +#27787 = CARTESIAN_POINT('',(-1.4,0.355,-0.355)); +#27788 = SURFACE_CURVE('',#27789,(#27793,#27800),.PCURVE_S1.); +#27789 = LINE('',#27790,#27791); +#27790 = CARTESIAN_POINT('',(-1.4,0.355,-0.355)); +#27791 = VECTOR('',#27792,1.); +#27792 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27793 = PCURVE('',#26369,#27794); +#27794 = DEFINITIONAL_REPRESENTATION('',(#27795),#27799); +#27795 = LINE('',#27796,#27797); +#27796 = CARTESIAN_POINT('',(1.6,1.500535806721E-017)); +#27797 = VECTOR('',#27798,1.); +#27798 = DIRECTION('',(0.E+000,-1.)); +#27799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27800 = PCURVE('',#27801,#27806); +#27801 = PLANE('',#27802); +#27802 = AXIS2_PLACEMENT_3D('',#27803,#27804,#27805); +#27803 = CARTESIAN_POINT('',(-1.4,0.445,0.195)); +#27804 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27805 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27806 = DEFINITIONAL_REPRESENTATION('',(#27807),#27811); +#27807 = LINE('',#27808,#27809); +#27808 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27809 = VECTOR('',#27810,1.); +#27810 = DIRECTION('',(1.702510980039E-043,-1.)); +#27811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27812 = ORIENTED_EDGE('',*,*,#27813,.F.); +#27813 = EDGE_CURVE('',#27814,#27786,#27816,.T.); +#27814 = VERTEX_POINT('',#27815); +#27815 = CARTESIAN_POINT('',(-0.6,0.355,-0.355)); +#27816 = SURFACE_CURVE('',#27817,(#27821,#27828),.PCURVE_S1.); +#27817 = LINE('',#27818,#27819); +#27818 = CARTESIAN_POINT('',(3.,0.355,-0.355)); +#27819 = VECTOR('',#27820,1.); +#27820 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#27821 = PCURVE('',#26369,#27822); +#27822 = DEFINITIONAL_REPRESENTATION('',(#27823),#27827); +#27823 = LINE('',#27824,#27825); +#27824 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); +#27825 = VECTOR('',#27826,1.); +#27826 = DIRECTION('',(-1.,1.224606353822E-016)); +#27827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27828 = PCURVE('',#27206,#27829); +#27829 = DEFINITIONAL_REPRESENTATION('',(#27830),#27834); +#27830 = LINE('',#27831,#27832); +#27831 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#27832 = VECTOR('',#27833,1.); +#27833 = DIRECTION('',(-1.,0.E+000)); +#27834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27835 = ORIENTED_EDGE('',*,*,#27836,.F.); +#27836 = EDGE_CURVE('',#27837,#27814,#27839,.T.); +#27837 = VERTEX_POINT('',#27838); +#27838 = CARTESIAN_POINT('',(-0.6,0.355,-0.255)); +#27839 = SURFACE_CURVE('',#27840,(#27844,#27851),.PCURVE_S1.); +#27840 = LINE('',#27841,#27842); +#27841 = CARTESIAN_POINT('',(-0.6,0.355,-0.355)); +#27842 = VECTOR('',#27843,1.); +#27843 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27844 = PCURVE('',#26369,#27845); +#27845 = DEFINITIONAL_REPRESENTATION('',(#27846),#27850); +#27846 = LINE('',#27847,#27848); +#27847 = CARTESIAN_POINT('',(2.4,5.026361271644E-017)); +#27848 = VECTOR('',#27849,1.); +#27849 = DIRECTION('',(0.E+000,-1.)); +#27850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27851 = PCURVE('',#27852,#27857); +#27852 = PLANE('',#27853); +#27853 = AXIS2_PLACEMENT_3D('',#27854,#27855,#27856); +#27854 = CARTESIAN_POINT('',(-0.6,0.445,0.195)); +#27855 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27856 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27857 = DEFINITIONAL_REPRESENTATION('',(#27858),#27862); +#27858 = LINE('',#27859,#27860); +#27859 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27860 = VECTOR('',#27861,1.); +#27861 = DIRECTION('',(1.702510980039E-043,-1.)); +#27862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27863 = ORIENTED_EDGE('',*,*,#27864,.T.); +#27864 = EDGE_CURVE('',#27837,#27865,#27867,.T.); +#27865 = VERTEX_POINT('',#27866); +#27866 = CARTESIAN_POINT('',(-0.4,0.355,-0.255)); +#27867 = SURFACE_CURVE('',#27868,(#27872,#27879),.PCURVE_S1.); +#27868 = LINE('',#27869,#27870); +#27869 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); +#27870 = VECTOR('',#27871,1.); +#27871 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27872 = PCURVE('',#26369,#27873); +#27873 = DEFINITIONAL_REPRESENTATION('',(#27874),#27878); +#27874 = LINE('',#27875,#27876); +#27875 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); +#27876 = VECTOR('',#27877,1.); +#27877 = DIRECTION('',(1.,0.E+000)); +#27878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27879 = PCURVE('',#27880,#27885); +#27880 = PLANE('',#27881); +#27881 = AXIS2_PLACEMENT_3D('',#27882,#27883,#27884); +#27882 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#27883 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); +#27884 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); +#27885 = DEFINITIONAL_REPRESENTATION('',(#27886),#27890); +#27886 = LINE('',#27887,#27888); +#27887 = CARTESIAN_POINT('',(-6.E-002,2.4)); +#27888 = VECTOR('',#27889,1.); +#27889 = DIRECTION('',(-1.642146637881E-047,-1.)); +#27890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27891 = ORIENTED_EDGE('',*,*,#27892,.T.); +#27892 = EDGE_CURVE('',#27865,#27893,#27895,.T.); +#27893 = VERTEX_POINT('',#27894); +#27894 = CARTESIAN_POINT('',(-0.4,0.355,-0.355)); +#27895 = SURFACE_CURVE('',#27896,(#27900,#27907),.PCURVE_S1.); +#27896 = LINE('',#27897,#27898); +#27897 = CARTESIAN_POINT('',(-0.4,0.355,-0.355)); +#27898 = VECTOR('',#27899,1.); +#27899 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27900 = PCURVE('',#26369,#27901); +#27901 = DEFINITIONAL_REPRESENTATION('',(#27902),#27906); +#27902 = LINE('',#27903,#27904); +#27903 = CARTESIAN_POINT('',(2.6,3.567025147487E-018)); +#27904 = VECTOR('',#27905,1.); +#27905 = DIRECTION('',(0.E+000,-1.)); +#27906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27907 = PCURVE('',#27908,#27913); +#27908 = PLANE('',#27909); +#27909 = AXIS2_PLACEMENT_3D('',#27910,#27911,#27912); +#27910 = CARTESIAN_POINT('',(-0.4,0.445,0.195)); +#27911 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27912 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27913 = DEFINITIONAL_REPRESENTATION('',(#27914),#27918); +#27914 = LINE('',#27915,#27916); +#27915 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27916 = VECTOR('',#27917,1.); +#27917 = DIRECTION('',(1.702510980039E-043,-1.)); +#27918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27919 = ORIENTED_EDGE('',*,*,#27920,.F.); +#27920 = EDGE_CURVE('',#27921,#27893,#27923,.T.); +#27921 = VERTEX_POINT('',#27922); +#27922 = CARTESIAN_POINT('',(0.4,0.355,-0.355)); +#27923 = SURFACE_CURVE('',#27924,(#27928,#27935),.PCURVE_S1.); #27924 = LINE('',#27925,#27926); -#27925 = CARTESIAN_POINT('',(0.15,-0.45)); +#27925 = CARTESIAN_POINT('',(3.,0.355,-0.355)); #27926 = VECTOR('',#27927,1.); -#27927 = DIRECTION('',(-1.101142831431E-016,1.)); -#27928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27929 = PCURVE('',#27223,#27930); -#27930 = DEFINITIONAL_REPRESENTATION('',(#27931),#27935); -#27931 = LINE('',#27932,#27933); -#27932 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27933 = VECTOR('',#27934,1.); -#27934 = DIRECTION('',(-1.,0.E+000)); -#27935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27936 = ORIENTED_EDGE('',*,*,#27937,.T.); -#27937 = EDGE_CURVE('',#27915,#25064,#27938,.T.); -#27938 = SURFACE_CURVE('',#27939,(#27943,#27950),.PCURVE_S1.); -#27939 = LINE('',#27940,#27941); -#27940 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#27941 = VECTOR('',#27942,1.); -#27942 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); -#27943 = PCURVE('',#25081,#27944); -#27944 = DEFINITIONAL_REPRESENTATION('',(#27945),#27949); -#27945 = LINE('',#27946,#27947); -#27946 = CARTESIAN_POINT('',(0.15,-0.45)); -#27947 = VECTOR('',#27948,1.); -#27948 = DIRECTION('',(-1.,-9.035018104046E-017)); -#27949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27950 = PCURVE('',#25109,#27951); -#27951 = DEFINITIONAL_REPRESENTATION('',(#27952),#27956); -#27952 = LINE('',#27953,#27954); -#27953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27954 = VECTOR('',#27955,1.); -#27955 = DIRECTION('',(-1.,0.E+000)); -#27956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27957 = ORIENTED_EDGE('',*,*,#25063,.T.); -#27958 = ADVANCED_FACE('',(#27959),#25109,.F.); -#27959 = FACE_BOUND('',#27960,.T.); -#27960 = EDGE_LOOP('',(#27961,#27962,#27963,#27984)); -#27961 = ORIENTED_EDGE('',*,*,#25093,.F.); -#27962 = ORIENTED_EDGE('',*,*,#27937,.F.); -#27963 = ORIENTED_EDGE('',*,*,#27964,.T.); -#27964 = EDGE_CURVE('',#27915,#27185,#27965,.T.); -#27965 = SURFACE_CURVE('',#27966,(#27970,#27977),.PCURVE_S1.); -#27966 = LINE('',#27967,#27968); -#27967 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); -#27968 = VECTOR('',#27969,1.); -#27969 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27970 = PCURVE('',#25109,#27971); -#27971 = DEFINITIONAL_REPRESENTATION('',(#27972),#27976); -#27972 = LINE('',#27973,#27974); -#27973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27974 = VECTOR('',#27975,1.); -#27975 = DIRECTION('',(-1.642146637881E-047,-1.)); -#27976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27977 = PCURVE('',#27223,#27978); -#27978 = DEFINITIONAL_REPRESENTATION('',(#27979),#27983); -#27979 = LINE('',#27980,#27981); -#27980 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#27981 = VECTOR('',#27982,1.); -#27982 = DIRECTION('',(0.E+000,-1.)); -#27983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#27984 = ORIENTED_EDGE('',*,*,#27184,.T.); -#27985 = ADVANCED_FACE('',(#27986),#25726,.F.); -#27986 = FACE_BOUND('',#27987,.T.); -#27987 = EDGE_LOOP('',(#27988,#27989,#27990,#28011)); -#27988 = ORIENTED_EDGE('',*,*,#26366,.F.); -#27989 = ORIENTED_EDGE('',*,*,#25708,.F.); -#27990 = ORIENTED_EDGE('',*,*,#27991,.T.); -#27991 = EDGE_CURVE('',#25709,#26210,#27992,.T.); -#27992 = SURFACE_CURVE('',#27993,(#27997,#28004),.PCURVE_S1.); +#27927 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#27928 = PCURVE('',#26369,#27929); +#27929 = DEFINITIONAL_REPRESENTATION('',(#27930),#27934); +#27930 = LINE('',#27931,#27932); +#27931 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); +#27932 = VECTOR('',#27933,1.); +#27933 = DIRECTION('',(-1.,1.224606353822E-016)); +#27934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27935 = PCURVE('',#27206,#27936); +#27936 = DEFINITIONAL_REPRESENTATION('',(#27937),#27941); +#27937 = LINE('',#27938,#27939); +#27938 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); +#27939 = VECTOR('',#27940,1.); +#27940 = DIRECTION('',(-1.,0.E+000)); +#27941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27942 = ORIENTED_EDGE('',*,*,#27943,.F.); +#27943 = EDGE_CURVE('',#27944,#27921,#27946,.T.); +#27944 = VERTEX_POINT('',#27945); +#27945 = CARTESIAN_POINT('',(0.4,0.355,-0.255)); +#27946 = SURFACE_CURVE('',#27947,(#27951,#27958),.PCURVE_S1.); +#27947 = LINE('',#27948,#27949); +#27948 = CARTESIAN_POINT('',(0.4,0.355,-0.355)); +#27949 = VECTOR('',#27950,1.); +#27950 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#27951 = PCURVE('',#26369,#27952); +#27952 = DEFINITIONAL_REPRESENTATION('',(#27953),#27957); +#27953 = LINE('',#27954,#27955); +#27954 = CARTESIAN_POINT('',(3.4,3.882527979672E-017)); +#27955 = VECTOR('',#27956,1.); +#27956 = DIRECTION('',(0.E+000,-1.)); +#27957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27958 = PCURVE('',#27959,#27964); +#27959 = PLANE('',#27960); +#27960 = AXIS2_PLACEMENT_3D('',#27961,#27962,#27963); +#27961 = CARTESIAN_POINT('',(0.4,0.445,0.195)); +#27962 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#27963 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#27964 = DEFINITIONAL_REPRESENTATION('',(#27965),#27969); +#27965 = LINE('',#27966,#27967); +#27966 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#27967 = VECTOR('',#27968,1.); +#27968 = DIRECTION('',(1.702510980039E-043,-1.)); +#27969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27970 = ORIENTED_EDGE('',*,*,#27971,.T.); +#27971 = EDGE_CURVE('',#27944,#27972,#27974,.T.); +#27972 = VERTEX_POINT('',#27973); +#27973 = CARTESIAN_POINT('',(0.6,0.355,-0.255)); +#27974 = SURFACE_CURVE('',#27975,(#27979,#27986),.PCURVE_S1.); +#27975 = LINE('',#27976,#27977); +#27976 = CARTESIAN_POINT('',(-3.,0.355,-0.255)); +#27977 = VECTOR('',#27978,1.); +#27978 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#27979 = PCURVE('',#26369,#27980); +#27980 = DEFINITIONAL_REPRESENTATION('',(#27981),#27985); +#27981 = LINE('',#27982,#27983); +#27982 = CARTESIAN_POINT('',(-2.542074623718E-016,1.E-001)); +#27983 = VECTOR('',#27984,1.); +#27984 = DIRECTION('',(1.,0.E+000)); +#27985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27986 = PCURVE('',#27987,#27992); +#27987 = PLANE('',#27988); +#27988 = AXIS2_PLACEMENT_3D('',#27989,#27990,#27991); +#27989 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#27990 = DIRECTION('',(-6.982966722219E-015,3.401133180069E-015,-1.)); +#27991 = DIRECTION('',(-2.374999981426E-029,-1.,-3.401133180069E-015)); +#27992 = DEFINITIONAL_REPRESENTATION('',(#27993),#27997); #27993 = LINE('',#27994,#27995); -#27994 = CARTESIAN_POINT('',(2.5,0.905,3.395)); +#27994 = CARTESIAN_POINT('',(-6.E-002,3.4)); #27995 = VECTOR('',#27996,1.); -#27996 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#27997 = PCURVE('',#25726,#27998); -#27998 = DEFINITIONAL_REPRESENTATION('',(#27999),#28003); -#27999 = LINE('',#28000,#28001); -#28000 = CARTESIAN_POINT('',(0.65,-1.55053008704E-029)); -#28001 = VECTOR('',#28002,1.); -#28002 = DIRECTION('',(-2.80259692865E-045,-1.)); -#28003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28004 = PCURVE('',#25819,#28005); -#28005 = DEFINITIONAL_REPRESENTATION('',(#28006),#28010); -#28006 = LINE('',#28007,#28008); -#28007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28008 = VECTOR('',#28009,1.); -#28009 = DIRECTION('',(0.E+000,-1.)); -#28010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28011 = ORIENTED_EDGE('',*,*,#26209,.T.); -#28012 = ADVANCED_FACE('',(#28013),#25819,.F.); -#28013 = FACE_BOUND('',#28014,.T.); -#28014 = EDGE_LOOP('',(#28015,#28016,#28017,#28018)); -#28015 = ORIENTED_EDGE('',*,*,#27991,.F.); -#28016 = ORIENTED_EDGE('',*,*,#25805,.F.); -#28017 = ORIENTED_EDGE('',*,*,#27264,.T.); -#28018 = ORIENTED_EDGE('',*,*,#26232,.T.); -#28019 = ADVANCED_FACE('',(#28020),#26042,.F.); -#28020 = FACE_BOUND('',#28021,.T.); -#28021 = EDGE_LOOP('',(#28022,#28047,#28070,#28091,#28092,#28093)); -#28022 = ORIENTED_EDGE('',*,*,#28023,.T.); -#28023 = EDGE_CURVE('',#28024,#28026,#28028,.T.); -#28024 = VERTEX_POINT('',#28025); -#28025 = CARTESIAN_POINT('',(2.5,2.755,0.845)); -#28026 = VERTEX_POINT('',#28027); -#28027 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#27996 = DIRECTION('',(-1.642146637881E-047,-1.)); +#27997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#27998 = ORIENTED_EDGE('',*,*,#27999,.T.); +#27999 = EDGE_CURVE('',#27972,#28000,#28002,.T.); +#28000 = VERTEX_POINT('',#28001); +#28001 = CARTESIAN_POINT('',(0.6,0.355,-0.355)); +#28002 = SURFACE_CURVE('',#28003,(#28007,#28014),.PCURVE_S1.); +#28003 = LINE('',#28004,#28005); +#28004 = CARTESIAN_POINT('',(0.6,0.355,-0.355)); +#28005 = VECTOR('',#28006,1.); +#28006 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#28007 = PCURVE('',#26369,#28008); +#28008 = DEFINITIONAL_REPRESENTATION('',(#28009),#28013); +#28009 = LINE('',#28010,#28011); +#28010 = CARTESIAN_POINT('',(3.6,-7.871307772235E-018)); +#28011 = VECTOR('',#28012,1.); +#28012 = DIRECTION('',(0.E+000,-1.)); +#28013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28014 = PCURVE('',#28015,#28020); +#28015 = PLANE('',#28016); +#28016 = AXIS2_PLACEMENT_3D('',#28017,#28018,#28019); +#28017 = CARTESIAN_POINT('',(0.6,0.445,0.195)); +#28018 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28019 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28020 = DEFINITIONAL_REPRESENTATION('',(#28021),#28025); +#28021 = LINE('',#28022,#28023); +#28022 = CARTESIAN_POINT('',(9.E-002,-0.55)); +#28023 = VECTOR('',#28024,1.); +#28024 = DIRECTION('',(1.702510980039E-043,-1.)); +#28025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28026 = ORIENTED_EDGE('',*,*,#28027,.F.); +#28027 = EDGE_CURVE('',#27458,#28000,#28028,.T.); #28028 = SURFACE_CURVE('',#28029,(#28033,#28040),.PCURVE_S1.); #28029 = LINE('',#28030,#28031); -#28030 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#28030 = CARTESIAN_POINT('',(3.,0.355,-0.355)); #28031 = VECTOR('',#28032,1.); -#28032 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#28033 = PCURVE('',#26042,#28034); +#28032 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#28033 = PCURVE('',#26369,#28034); #28034 = DEFINITIONAL_REPRESENTATION('',(#28035),#28039); #28035 = LINE('',#28036,#28037); -#28036 = CARTESIAN_POINT('',(-1.439590092099E-016,0.55)); +#28036 = CARTESIAN_POINT('',(6.,-6.792526610622E-016)); #28037 = VECTOR('',#28038,1.); -#28038 = DIRECTION('',(1.702510980039E-043,-1.)); +#28038 = DIRECTION('',(-1.,1.224606353822E-016)); #28039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#28040 = PCURVE('',#26151,#28041); +#28040 = PCURVE('',#27206,#28041); #28041 = DEFINITIONAL_REPRESENTATION('',(#28042),#28046); #28042 = LINE('',#28043,#28044); -#28043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28043 = CARTESIAN_POINT('',(7.054639148971E-029,-2.9)); #28044 = VECTOR('',#28045,1.); -#28045 = DIRECTION('',(0.E+000,-1.)); +#28045 = DIRECTION('',(-1.,0.E+000)); #28046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#28047 = ORIENTED_EDGE('',*,*,#28048,.T.); -#28048 = EDGE_CURVE('',#28026,#28049,#28051,.T.); -#28049 = VERTEX_POINT('',#28050); -#28050 = CARTESIAN_POINT('',(2.5,1.755,0.195)); -#28051 = SURFACE_CURVE('',#28052,(#28056,#28063),.PCURVE_S1.); -#28052 = LINE('',#28053,#28054); -#28053 = CARTESIAN_POINT('',(2.5,2.755,0.195)); -#28054 = VECTOR('',#28055,1.); -#28055 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); -#28056 = PCURVE('',#26042,#28057); -#28057 = DEFINITIONAL_REPRESENTATION('',(#28058),#28062); -#28058 = LINE('',#28059,#28060); -#28059 = CARTESIAN_POINT('',(-1.439590092099E-016,0.55)); -#28060 = VECTOR('',#28061,1.); -#28061 = DIRECTION('',(1.,-1.084202172486E-016)); -#28062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28063 = PCURVE('',#26342,#28064); -#28064 = DEFINITIONAL_REPRESENTATION('',(#28065),#28069); -#28065 = LINE('',#28066,#28067); -#28066 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28067 = VECTOR('',#28068,1.); -#28068 = DIRECTION('',(-1.,0.E+000)); -#28069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28070 = ORIENTED_EDGE('',*,*,#28071,.T.); -#28071 = EDGE_CURVE('',#28049,#26897,#28072,.T.); -#28072 = SURFACE_CURVE('',#28073,(#28077,#28084),.PCURVE_S1.); -#28073 = LINE('',#28074,#28075); -#28074 = CARTESIAN_POINT('',(2.5,1.755,0.195)); -#28075 = VECTOR('',#28076,1.); -#28076 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); -#28077 = PCURVE('',#26042,#28078); -#28078 = DEFINITIONAL_REPRESENTATION('',(#28079),#28083); -#28079 = LINE('',#28080,#28081); -#28080 = CARTESIAN_POINT('',(1.,0.55)); -#28081 = VECTOR('',#28082,1.); -#28082 = DIRECTION('',(1.702510980039E-043,-1.)); -#28083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28084 = PCURVE('',#26316,#28085); -#28085 = DEFINITIONAL_REPRESENTATION('',(#28086),#28090); -#28086 = LINE('',#28087,#28088); -#28087 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28088 = VECTOR('',#28089,1.); -#28089 = DIRECTION('',(0.E+000,-1.)); -#28090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28091 = ORIENTED_EDGE('',*,*,#26896,.T.); -#28092 = ORIENTED_EDGE('',*,*,#26026,.T.); -#28093 = ORIENTED_EDGE('',*,*,#28094,.T.); -#28094 = EDGE_CURVE('',#25999,#28024,#28095,.T.); -#28095 = SURFACE_CURVE('',#28096,(#28100,#28107),.PCURVE_S1.); -#28096 = LINE('',#28097,#28098); -#28097 = CARTESIAN_POINT('',(2.5,2.755,0.845)); -#28098 = VECTOR('',#28099,1.); -#28099 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); -#28100 = PCURVE('',#26042,#28101); -#28101 = DEFINITIONAL_REPRESENTATION('',(#28102),#28106); -#28102 = LINE('',#28103,#28104); -#28103 = CARTESIAN_POINT('',(2.511120651694E-016,1.2)); -#28104 = VECTOR('',#28105,1.); -#28105 = DIRECTION('',(0.866025403784,-0.5)); -#28106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28107 = PCURVE('',#26014,#28108); -#28108 = DEFINITIONAL_REPRESENTATION('',(#28109),#28113); -#28109 = LINE('',#28110,#28111); -#28110 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28111 = VECTOR('',#28112,1.); -#28112 = DIRECTION('',(-1.,1.961367055364E-030)); -#28113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28114 = ADVANCED_FACE('',(#28115),#26091,.F.); -#28115 = FACE_BOUND('',#28116,.T.); -#28116 = EDGE_LOOP('',(#28117,#28118,#28119,#28120,#28121,#28122)); -#28117 = ORIENTED_EDGE('',*,*,#26527,.F.); -#28118 = ORIENTED_EDGE('',*,*,#26554,.F.); -#28119 = ORIENTED_EDGE('',*,*,#26077,.F.); -#28120 = ORIENTED_EDGE('',*,*,#26874,.F.); -#28121 = ORIENTED_EDGE('',*,*,#27015,.F.); -#28122 = ORIENTED_EDGE('',*,*,#26456,.F.); -#28123 = ADVANCED_FACE('',(#28124),#26014,.F.); -#28124 = FACE_BOUND('',#28125,.T.); -#28125 = EDGE_LOOP('',(#28126,#28127,#28148,#28149)); -#28126 = ORIENTED_EDGE('',*,*,#26163,.T.); -#28127 = ORIENTED_EDGE('',*,*,#28128,.F.); -#28128 = EDGE_CURVE('',#28024,#26134,#28129,.T.); -#28129 = SURFACE_CURVE('',#28130,(#28134,#28141),.PCURVE_S1.); -#28130 = LINE('',#28131,#28132); -#28131 = CARTESIAN_POINT('',(2.5,2.755,0.845)); -#28132 = VECTOR('',#28133,1.); -#28133 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28134 = PCURVE('',#26014,#28135); -#28135 = DEFINITIONAL_REPRESENTATION('',(#28136),#28140); -#28136 = LINE('',#28137,#28138); -#28137 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28138 = VECTOR('',#28139,1.); -#28139 = DIRECTION('',(-1.228743304519E-031,-1.)); -#28140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28141 = PCURVE('',#26151,#28142); -#28142 = DEFINITIONAL_REPRESENTATION('',(#28143),#28147); -#28143 = LINE('',#28144,#28145); -#28144 = CARTESIAN_POINT('',(-5.421254807916E-016,0.65)); -#28145 = VECTOR('',#28146,1.); -#28146 = DIRECTION('',(1.,0.E+000)); -#28147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28148 = ORIENTED_EDGE('',*,*,#28094,.F.); -#28149 = ORIENTED_EDGE('',*,*,#25998,.T.); -#28150 = ADVANCED_FACE('',(#28151),#26316,.F.); -#28151 = FACE_BOUND('',#28152,.T.); -#28152 = EDGE_LOOP('',(#28153,#28154,#28155,#28156)); -#28153 = ORIENTED_EDGE('',*,*,#26300,.T.); -#28154 = ORIENTED_EDGE('',*,*,#26919,.F.); -#28155 = ORIENTED_EDGE('',*,*,#28071,.F.); -#28156 = ORIENTED_EDGE('',*,*,#28157,.T.); -#28157 = EDGE_CURVE('',#28049,#26301,#28158,.T.); -#28158 = SURFACE_CURVE('',#28159,(#28163,#28170),.PCURVE_S1.); -#28159 = LINE('',#28160,#28161); -#28160 = CARTESIAN_POINT('',(2.5,1.755,0.195)); -#28161 = VECTOR('',#28162,1.); -#28162 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28163 = PCURVE('',#26316,#28164); -#28164 = DEFINITIONAL_REPRESENTATION('',(#28165),#28169); -#28165 = LINE('',#28166,#28167); -#28166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28167 = VECTOR('',#28168,1.); -#28168 = DIRECTION('',(1.,0.E+000)); -#28169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28170 = PCURVE('',#26342,#28171); -#28171 = DEFINITIONAL_REPRESENTATION('',(#28172),#28176); -#28172 = LINE('',#28173,#28174); -#28173 = CARTESIAN_POINT('',(-1.,-2.51961139144E-029)); -#28174 = VECTOR('',#28175,1.); -#28175 = DIRECTION('',(2.80259692865E-045,-1.)); -#28176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28177 = ADVANCED_FACE('',(#28178),#26342,.F.); -#28178 = FACE_BOUND('',#28179,.T.); -#28179 = EDGE_LOOP('',(#28180,#28181,#28182,#28183)); -#28180 = ORIENTED_EDGE('',*,*,#26328,.T.); -#28181 = ORIENTED_EDGE('',*,*,#28157,.F.); -#28182 = ORIENTED_EDGE('',*,*,#28048,.F.); -#28183 = ORIENTED_EDGE('',*,*,#28184,.T.); -#28184 = EDGE_CURVE('',#28026,#26136,#28185,.T.); -#28185 = SURFACE_CURVE('',#28186,(#28190,#28197),.PCURVE_S1.); -#28186 = LINE('',#28187,#28188); -#28187 = CARTESIAN_POINT('',(2.5,2.755,0.195)); -#28188 = VECTOR('',#28189,1.); -#28189 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28190 = PCURVE('',#26342,#28191); -#28191 = DEFINITIONAL_REPRESENTATION('',(#28192),#28196); -#28192 = LINE('',#28193,#28194); -#28193 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28194 = VECTOR('',#28195,1.); -#28195 = DIRECTION('',(2.80259692865E-045,-1.)); -#28196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28197 = PCURVE('',#26151,#28198); -#28198 = DEFINITIONAL_REPRESENTATION('',(#28199),#28203); +#28047 = ADVANCED_FACE('',(#28048),#26257,.T.); +#28048 = FACE_BOUND('',#28049,.T.); +#28049 = EDGE_LOOP('',(#28050,#28073,#28074,#28075)); +#28050 = ORIENTED_EDGE('',*,*,#28051,.T.); +#28051 = EDGE_CURVE('',#28052,#26240,#28054,.T.); +#28052 = VERTEX_POINT('',#28053); +#28053 = CARTESIAN_POINT('',(-2.7,1.555,3.395)); +#28054 = SURFACE_CURVE('',#28055,(#28059,#28066),.PCURVE_S1.); +#28055 = LINE('',#28056,#28057); +#28056 = CARTESIAN_POINT('',(-2.7,1.555,2.595)); +#28057 = VECTOR('',#28058,1.); +#28058 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28059 = PCURVE('',#26257,#28060); +#28060 = DEFINITIONAL_REPRESENTATION('',(#28061),#28065); +#28061 = LINE('',#28062,#28063); +#28062 = CARTESIAN_POINT('',(-1.3,0.2)); +#28063 = VECTOR('',#28064,1.); +#28064 = DIRECTION('',(1.,0.E+000)); +#28065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28066 = PCURVE('',#26285,#28067); +#28067 = DEFINITIONAL_REPRESENTATION('',(#28068),#28072); +#28068 = LINE('',#28069,#28070); +#28069 = CARTESIAN_POINT('',(0.65,-0.2)); +#28070 = VECTOR('',#28071,1.); +#28071 = DIRECTION('',(1.702510980039E-043,-1.)); +#28072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28073 = ORIENTED_EDGE('',*,*,#26239,.T.); +#28074 = ORIENTED_EDGE('',*,*,#27325,.F.); +#28075 = ORIENTED_EDGE('',*,*,#28076,.F.); +#28076 = EDGE_CURVE('',#28052,#27298,#28077,.T.); +#28077 = SURFACE_CURVE('',#28078,(#28082,#28089),.PCURVE_S1.); +#28078 = LINE('',#28079,#28080); +#28079 = CARTESIAN_POINT('',(-2.5,1.555,3.395)); +#28080 = VECTOR('',#28081,1.); +#28081 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28082 = PCURVE('',#26257,#28083); +#28083 = DEFINITIONAL_REPRESENTATION('',(#28084),#28088); +#28084 = LINE('',#28085,#28086); +#28085 = CARTESIAN_POINT('',(-0.5,6.123031769112E-017)); +#28086 = VECTOR('',#28087,1.); +#28087 = DIRECTION('',(0.E+000,1.)); +#28088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28089 = PCURVE('',#27313,#28090); +#28090 = DEFINITIONAL_REPRESENTATION('',(#28091),#28095); +#28091 = LINE('',#28092,#28093); +#28092 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28093 = VECTOR('',#28094,1.); +#28094 = DIRECTION('',(-2.80259692865E-045,1.)); +#28095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28096 = ADVANCED_FACE('',(#28097),#26453,.T.); +#28097 = FACE_BOUND('',#28098,.T.); +#28098 = EDGE_LOOP('',(#28099,#28129,#28150,#28151,#28152,#28173,#28196) + ); +#28099 = ORIENTED_EDGE('',*,*,#28100,.T.); +#28100 = EDGE_CURVE('',#28101,#28103,#28105,.T.); +#28101 = VERTEX_POINT('',#28102); +#28102 = CARTESIAN_POINT('',(2.7,0.905,3.395)); +#28103 = VERTEX_POINT('',#28104); +#28104 = CARTESIAN_POINT('',(2.7,1.555,3.395)); +#28105 = SURFACE_CURVE('',#28106,(#28110,#28117),.PCURVE_S1.); +#28106 = LINE('',#28107,#28108); +#28107 = CARTESIAN_POINT('',(2.7,0.905,3.395)); +#28108 = VECTOR('',#28109,1.); +#28109 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28110 = PCURVE('',#26453,#28111); +#28111 = DEFINITIONAL_REPRESENTATION('',(#28112),#28116); +#28112 = LINE('',#28113,#28114); +#28113 = CARTESIAN_POINT('',(4.97919847714E-017,1.)); +#28114 = VECTOR('',#28115,1.); +#28115 = DIRECTION('',(1.,1.702510980039E-043)); +#28116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28117 = PCURVE('',#28118,#28123); +#28118 = PLANE('',#28119); +#28119 = AXIS2_PLACEMENT_3D('',#28120,#28121,#28122); +#28120 = CARTESIAN_POINT('',(2.5,1.555,3.395)); +#28121 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#28122 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28123 = DEFINITIONAL_REPRESENTATION('',(#28124),#28128); +#28124 = LINE('',#28125,#28126); +#28125 = CARTESIAN_POINT('',(0.65,-0.2)); +#28126 = VECTOR('',#28127,1.); +#28127 = DIRECTION('',(-1.,0.E+000)); +#28128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28129 = ORIENTED_EDGE('',*,*,#28130,.T.); +#28130 = EDGE_CURVE('',#28103,#26438,#28131,.T.); +#28131 = SURFACE_CURVE('',#28132,(#28136,#28143),.PCURVE_S1.); +#28132 = LINE('',#28133,#28134); +#28133 = CARTESIAN_POINT('',(2.7,1.555,2.595)); +#28134 = VECTOR('',#28135,1.); +#28135 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28136 = PCURVE('',#26453,#28137); +#28137 = DEFINITIONAL_REPRESENTATION('',(#28138),#28142); +#28138 = LINE('',#28139,#28140); +#28139 = CARTESIAN_POINT('',(0.65,0.2)); +#28140 = VECTOR('',#28141,1.); +#28141 = DIRECTION('',(1.702510980039E-043,1.)); +#28142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28143 = PCURVE('',#26481,#28144); +#28144 = DEFINITIONAL_REPRESENTATION('',(#28145),#28149); +#28145 = LINE('',#28146,#28147); +#28146 = CARTESIAN_POINT('',(1.3,-0.2)); +#28147 = VECTOR('',#28148,1.); +#28148 = DIRECTION('',(-1.,0.E+000)); +#28149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28150 = ORIENTED_EDGE('',*,*,#26437,.T.); +#28151 = ORIENTED_EDGE('',*,*,#27052,.T.); +#28152 = ORIENTED_EDGE('',*,*,#28153,.T.); +#28153 = EDGE_CURVE('',#27025,#27588,#28154,.T.); +#28154 = SURFACE_CURVE('',#28155,(#28159,#28166),.PCURVE_S1.); +#28155 = LINE('',#28156,#28157); +#28156 = CARTESIAN_POINT('',(2.7,0.305,2.395)); +#28157 = VECTOR('',#28158,1.); +#28158 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28159 = PCURVE('',#26453,#28160); +#28160 = DEFINITIONAL_REPRESENTATION('',(#28161),#28165); +#28161 = LINE('',#28162,#28163); +#28162 = CARTESIAN_POINT('',(-0.6,3.185331772654E-016)); +#28163 = VECTOR('',#28164,1.); +#28164 = DIRECTION('',(1.,1.702510980039E-043)); +#28165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28166 = PCURVE('',#27040,#28167); +#28167 = DEFINITIONAL_REPRESENTATION('',(#28168),#28172); +#28168 = LINE('',#28169,#28170); +#28169 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28170 = VECTOR('',#28171,1.); +#28171 = DIRECTION('',(1.,0.E+000)); +#28172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28173 = ORIENTED_EDGE('',*,*,#28174,.F.); +#28174 = EDGE_CURVE('',#28175,#27588,#28177,.T.); +#28175 = VERTEX_POINT('',#28176); +#28176 = CARTESIAN_POINT('',(2.7,0.905,2.395)); +#28177 = SURFACE_CURVE('',#28178,(#28182,#28189),.PCURVE_S1.); +#28178 = LINE('',#28179,#28180); +#28179 = CARTESIAN_POINT('',(2.7,0.905,2.395)); +#28180 = VECTOR('',#28181,1.); +#28181 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28182 = PCURVE('',#26453,#28183); +#28183 = DEFINITIONAL_REPRESENTATION('',(#28184),#28188); +#28184 = LINE('',#28185,#28186); +#28185 = CARTESIAN_POINT('',(-1.55053008704E-030,-4.440892098501E-016)); +#28186 = VECTOR('',#28187,1.); +#28187 = DIRECTION('',(-1.,-1.702510980039E-043)); +#28188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28189 = PCURVE('',#27603,#28190); +#28190 = DEFINITIONAL_REPRESENTATION('',(#28191),#28195); +#28191 = LINE('',#28192,#28193); +#28192 = CARTESIAN_POINT('',(-2.245921632424E-031,-0.2)); +#28193 = VECTOR('',#28194,1.); +#28194 = DIRECTION('',(1.,0.E+000)); +#28195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28196 = ORIENTED_EDGE('',*,*,#28197,.T.); +#28197 = EDGE_CURVE('',#28175,#28101,#28198,.T.); +#28198 = SURFACE_CURVE('',#28199,(#28203,#28210),.PCURVE_S1.); #28199 = LINE('',#28200,#28201); -#28200 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28200 = CARTESIAN_POINT('',(2.7,0.905,2.095)); #28201 = VECTOR('',#28202,1.); -#28202 = DIRECTION('',(1.,0.E+000)); -#28203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28204 = ADVANCED_FACE('',(#28205),#26151,.F.); -#28205 = FACE_BOUND('',#28206,.T.); -#28206 = EDGE_LOOP('',(#28207,#28208,#28209,#28210)); -#28207 = ORIENTED_EDGE('',*,*,#26133,.T.); -#28208 = ORIENTED_EDGE('',*,*,#28184,.F.); -#28209 = ORIENTED_EDGE('',*,*,#28023,.F.); -#28210 = ORIENTED_EDGE('',*,*,#28128,.T.); -#28211 = ADVANCED_FACE('',(#28212),#26816,.F.); -#28212 = FACE_BOUND('',#28213,.T.); -#28213 = EDGE_LOOP('',(#28214,#28215,#28236,#28237)); -#28214 = ORIENTED_EDGE('',*,*,#27745,.T.); -#28215 = ORIENTED_EDGE('',*,*,#28216,.F.); -#28216 = EDGE_CURVE('',#27293,#27746,#28217,.T.); -#28217 = SURFACE_CURVE('',#28218,(#28222,#28229),.PCURVE_S1.); -#28218 = LINE('',#28219,#28220); -#28219 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); -#28220 = VECTOR('',#28221,1.); -#28221 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28222 = PCURVE('',#26816,#28223); -#28223 = DEFINITIONAL_REPRESENTATION('',(#28224),#28228); -#28224 = LINE('',#28225,#28226); -#28225 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28226 = VECTOR('',#28227,1.); -#28227 = DIRECTION('',(0.E+000,-1.)); -#28228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28229 = PCURVE('',#27331,#28230); -#28230 = DEFINITIONAL_REPRESENTATION('',(#28231),#28235); -#28231 = LINE('',#28232,#28233); -#28232 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); -#28233 = VECTOR('',#28234,1.); -#28234 = DIRECTION('',(5.315081284607E-045,-1.)); -#28235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28236 = ORIENTED_EDGE('',*,*,#27292,.F.); -#28237 = ORIENTED_EDGE('',*,*,#26800,.T.); -#28238 = ADVANCED_FACE('',(#28239),#26670,.F.); -#28239 = FACE_BOUND('',#28240,.T.); -#28240 = EDGE_LOOP('',(#28241,#28242,#28263,#28264)); -#28241 = ORIENTED_EDGE('',*,*,#27396,.T.); -#28242 = ORIENTED_EDGE('',*,*,#28243,.F.); -#28243 = EDGE_CURVE('',#27056,#27397,#28244,.T.); -#28244 = SURFACE_CURVE('',#28245,(#28249,#28256),.PCURVE_S1.); +#28202 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28203 = PCURVE('',#26453,#28204); +#28204 = DEFINITIONAL_REPRESENTATION('',(#28205),#28209); +#28205 = LINE('',#28206,#28207); +#28206 = CARTESIAN_POINT('',(6.277801629234E-017,-0.3)); +#28207 = VECTOR('',#28208,1.); +#28208 = DIRECTION('',(1.702510980039E-043,1.)); +#28209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28210 = PCURVE('',#28211,#28216); +#28211 = PLANE('',#28212); +#28212 = AXIS2_PLACEMENT_3D('',#28213,#28214,#28215); +#28213 = CARTESIAN_POINT('',(2.5,0.905,3.395)); +#28214 = DIRECTION('',(2.513800689087E-029,1.,3.599903578358E-015)); +#28215 = DIRECTION('',(-6.982966722219E-015,3.599903578358E-015,-1.)); +#28216 = DEFINITIONAL_REPRESENTATION('',(#28217),#28221); +#28217 = LINE('',#28218,#28219); +#28218 = CARTESIAN_POINT('',(1.3,-0.2)); +#28219 = VECTOR('',#28220,1.); +#28220 = DIRECTION('',(-1.,0.E+000)); +#28221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28222 = ADVANCED_FACE('',(#28223),#26285,.T.); +#28223 = FACE_BOUND('',#28224,.T.); +#28224 = EDGE_LOOP('',(#28225,#28250,#28271,#28294,#28315,#28316,#28317) + ); +#28225 = ORIENTED_EDGE('',*,*,#28226,.F.); +#28226 = EDGE_CURVE('',#28227,#28229,#28231,.T.); +#28227 = VERTEX_POINT('',#28228); +#28228 = CARTESIAN_POINT('',(-2.7,0.905,2.395)); +#28229 = VERTEX_POINT('',#28230); +#28230 = CARTESIAN_POINT('',(-2.7,0.905,3.395)); +#28231 = SURFACE_CURVE('',#28232,(#28236,#28243),.PCURVE_S1.); +#28232 = LINE('',#28233,#28234); +#28233 = CARTESIAN_POINT('',(-2.7,0.905,2.095)); +#28234 = VECTOR('',#28235,1.); +#28235 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28236 = PCURVE('',#26285,#28237); +#28237 = DEFINITIONAL_REPRESENTATION('',(#28238),#28242); +#28238 = LINE('',#28239,#28240); +#28239 = CARTESIAN_POINT('',(6.277801629234E-017,0.3)); +#28240 = VECTOR('',#28241,1.); +#28241 = DIRECTION('',(1.702510980039E-043,-1.)); +#28242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28243 = PCURVE('',#27285,#28244); +#28244 = DEFINITIONAL_REPRESENTATION('',(#28245),#28249); #28245 = LINE('',#28246,#28247); -#28246 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); +#28246 = CARTESIAN_POINT('',(-1.3,0.2)); #28247 = VECTOR('',#28248,1.); -#28248 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28249 = PCURVE('',#26670,#28250); -#28250 = DEFINITIONAL_REPRESENTATION('',(#28251),#28255); -#28251 = LINE('',#28252,#28253); -#28252 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28253 = VECTOR('',#28254,1.); -#28254 = DIRECTION('',(0.E+000,-1.)); -#28255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28256 = PCURVE('',#27094,#28257); -#28257 = DEFINITIONAL_REPRESENTATION('',(#28258),#28262); -#28258 = LINE('',#28259,#28260); -#28259 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); -#28260 = VECTOR('',#28261,1.); -#28261 = DIRECTION('',(5.315081284607E-045,-1.)); -#28262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28263 = ORIENTED_EDGE('',*,*,#27055,.F.); -#28264 = ORIENTED_EDGE('',*,*,#26654,.T.); -#28265 = ADVANCED_FACE('',(#28266),#26743,.F.); -#28266 = FACE_BOUND('',#28267,.T.); -#28267 = EDGE_LOOP('',(#28268,#28269,#28290,#28291)); -#28268 = ORIENTED_EDGE('',*,*,#27491,.T.); -#28269 = ORIENTED_EDGE('',*,*,#28270,.F.); -#28270 = EDGE_CURVE('',#27625,#27492,#28271,.T.); -#28271 = SURFACE_CURVE('',#28272,(#28276,#28283),.PCURVE_S1.); -#28272 = LINE('',#28273,#28274); -#28273 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); -#28274 = VECTOR('',#28275,1.); -#28275 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28276 = PCURVE('',#26743,#28277); -#28277 = DEFINITIONAL_REPRESENTATION('',(#28278),#28282); -#28278 = LINE('',#28279,#28280); -#28279 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28280 = VECTOR('',#28281,1.); -#28281 = DIRECTION('',(0.E+000,-1.)); -#28282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28283 = PCURVE('',#27581,#28284); -#28284 = DEFINITIONAL_REPRESENTATION('',(#28285),#28289); -#28285 = LINE('',#28286,#28287); -#28286 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); -#28287 = VECTOR('',#28288,1.); -#28288 = DIRECTION('',(5.315081284607E-045,-1.)); -#28289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28290 = ORIENTED_EDGE('',*,*,#27624,.F.); -#28291 = ORIENTED_EDGE('',*,*,#26727,.T.); -#28292 = ADVANCED_FACE('',(#28293),#26597,.F.); -#28293 = FACE_BOUND('',#28294,.T.); -#28294 = EDGE_LOOP('',(#28295,#28296,#28317,#28318)); -#28295 = ORIENTED_EDGE('',*,*,#27159,.T.); -#28296 = ORIENTED_EDGE('',*,*,#28297,.F.); -#28297 = EDGE_CURVE('',#27869,#27160,#28298,.T.); -#28298 = SURFACE_CURVE('',#28299,(#28303,#28310),.PCURVE_S1.); -#28299 = LINE('',#28300,#28301); -#28300 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); -#28301 = VECTOR('',#28302,1.); -#28302 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28303 = PCURVE('',#26597,#28304); -#28304 = DEFINITIONAL_REPRESENTATION('',(#28305),#28309); -#28305 = LINE('',#28306,#28307); -#28306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28307 = VECTOR('',#28308,1.); -#28308 = DIRECTION('',(0.E+000,-1.)); -#28309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28310 = PCURVE('',#27249,#28311); -#28311 = DEFINITIONAL_REPRESENTATION('',(#28312),#28316); -#28312 = LINE('',#28313,#28314); -#28313 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); -#28314 = VECTOR('',#28315,1.); -#28315 = DIRECTION('',(5.315081284607E-045,-1.)); -#28316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28317 = ORIENTED_EDGE('',*,*,#27868,.F.); -#28318 = ORIENTED_EDGE('',*,*,#26579,.T.); -#28319 = ADVANCED_FACE('',(#28320),#27122,.F.); -#28320 = FACE_BOUND('',#28321,.T.); -#28321 = EDGE_LOOP('',(#28322,#28323,#28324,#28325)); -#28322 = ORIENTED_EDGE('',*,*,#27444,.T.); -#28323 = ORIENTED_EDGE('',*,*,#27598,.F.); -#28324 = ORIENTED_EDGE('',*,*,#27106,.F.); -#28325 = ORIENTED_EDGE('',*,*,#28326,.T.); -#28326 = EDGE_CURVE('',#27079,#27445,#28327,.T.); -#28327 = SURFACE_CURVE('',#28328,(#28332,#28339),.PCURVE_S1.); -#28328 = LINE('',#28329,#28330); -#28329 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); -#28330 = VECTOR('',#28331,1.); -#28331 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28332 = PCURVE('',#27122,#28333); -#28333 = DEFINITIONAL_REPRESENTATION('',(#28334),#28338); -#28334 = LINE('',#28335,#28336); -#28335 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); -#28336 = VECTOR('',#28337,1.); -#28337 = DIRECTION('',(0.E+000,-1.)); -#28338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28339 = PCURVE('',#27094,#28340); -#28340 = DEFINITIONAL_REPRESENTATION('',(#28341),#28345); -#28341 = LINE('',#28342,#28343); -#28342 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28343 = VECTOR('',#28344,1.); -#28344 = DIRECTION('',(5.315081284607E-045,-1.)); -#28345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28346 = ADVANCED_FACE('',(#28347),#27094,.F.); -#28347 = FACE_BOUND('',#28348,.T.); -#28348 = EDGE_LOOP('',(#28349,#28350,#28351,#28352)); -#28349 = ORIENTED_EDGE('',*,*,#27467,.T.); -#28350 = ORIENTED_EDGE('',*,*,#28326,.F.); -#28351 = ORIENTED_EDGE('',*,*,#27078,.F.); -#28352 = ORIENTED_EDGE('',*,*,#28243,.T.); -#28353 = ADVANCED_FACE('',(#28354),#27223,.F.); -#28354 = FACE_BOUND('',#28355,.T.); -#28355 = EDGE_LOOP('',(#28356,#28357,#28358,#28359)); -#28356 = ORIENTED_EDGE('',*,*,#27207,.T.); -#28357 = ORIENTED_EDGE('',*,*,#27964,.F.); -#28358 = ORIENTED_EDGE('',*,*,#27914,.F.); -#28359 = ORIENTED_EDGE('',*,*,#28360,.T.); -#28360 = EDGE_CURVE('',#27892,#27208,#28361,.T.); -#28361 = SURFACE_CURVE('',#28362,(#28366,#28373),.PCURVE_S1.); -#28362 = LINE('',#28363,#28364); -#28363 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); -#28364 = VECTOR('',#28365,1.); -#28365 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28366 = PCURVE('',#27223,#28367); -#28367 = DEFINITIONAL_REPRESENTATION('',(#28368),#28372); -#28368 = LINE('',#28369,#28370); -#28369 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); -#28370 = VECTOR('',#28371,1.); -#28371 = DIRECTION('',(0.E+000,-1.)); -#28372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28373 = PCURVE('',#27249,#28374); -#28374 = DEFINITIONAL_REPRESENTATION('',(#28375),#28379); -#28375 = LINE('',#28376,#28377); -#28376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28377 = VECTOR('',#28378,1.); -#28378 = DIRECTION('',(5.315081284607E-045,-1.)); -#28379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28380 = ADVANCED_FACE('',(#28381),#27249,.F.); -#28381 = FACE_BOUND('',#28382,.T.); -#28382 = EDGE_LOOP('',(#28383,#28384,#28385,#28386)); -#28383 = ORIENTED_EDGE('',*,*,#27235,.T.); -#28384 = ORIENTED_EDGE('',*,*,#28360,.F.); -#28385 = ORIENTED_EDGE('',*,*,#27891,.F.); -#28386 = ORIENTED_EDGE('',*,*,#28297,.T.); -#28387 = ADVANCED_FACE('',(#28388),#27331,.F.); -#28388 = FACE_BOUND('',#28389,.T.); -#28389 = EDGE_LOOP('',(#28390,#28391,#28412,#28413)); -#28390 = ORIENTED_EDGE('',*,*,#27816,.T.); -#28391 = ORIENTED_EDGE('',*,*,#28392,.F.); -#28392 = EDGE_CURVE('',#27316,#27794,#28393,.T.); +#28248 = DIRECTION('',(1.,0.E+000)); +#28249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28250 = ORIENTED_EDGE('',*,*,#28251,.F.); +#28251 = EDGE_CURVE('',#27662,#28227,#28252,.T.); +#28252 = SURFACE_CURVE('',#28253,(#28257,#28264),.PCURVE_S1.); +#28253 = LINE('',#28254,#28255); +#28254 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#28255 = VECTOR('',#28256,1.); +#28256 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28257 = PCURVE('',#26285,#28258); +#28258 = DEFINITIONAL_REPRESENTATION('',(#28259),#28263); +#28259 = LINE('',#28260,#28261); +#28260 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); +#28261 = VECTOR('',#28262,1.); +#28262 = DIRECTION('',(1.,-1.702510980039E-043)); +#28263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28264 = PCURVE('',#27257,#28265); +#28265 = DEFINITIONAL_REPRESENTATION('',(#28266),#28270); +#28266 = LINE('',#28267,#28268); +#28267 = CARTESIAN_POINT('',(-0.6,0.2)); +#28268 = VECTOR('',#28269,1.); +#28269 = DIRECTION('',(1.,0.E+000)); +#28270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28271 = ORIENTED_EDGE('',*,*,#28272,.F.); +#28272 = EDGE_CURVE('',#28273,#27662,#28275,.T.); +#28273 = VERTEX_POINT('',#28274); +#28274 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#28275 = SURFACE_CURVE('',#28276,(#28280,#28287),.PCURVE_S1.); +#28276 = LINE('',#28277,#28278); +#28277 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#28278 = VECTOR('',#28279,1.); +#28279 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28280 = PCURVE('',#26285,#28281); +#28281 = DEFINITIONAL_REPRESENTATION('',(#28282),#28286); +#28282 = LINE('',#28283,#28284); +#28283 = CARTESIAN_POINT('',(-0.6,-3.185331772654E-016)); +#28284 = VECTOR('',#28285,1.); +#28285 = DIRECTION('',(1.,-1.702510980039E-043)); +#28286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28287 = PCURVE('',#27145,#28288); +#28288 = DEFINITIONAL_REPRESENTATION('',(#28289),#28293); +#28289 = LINE('',#28290,#28291); +#28290 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28291 = VECTOR('',#28292,1.); +#28292 = DIRECTION('',(-1.,0.E+000)); +#28293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28294 = ORIENTED_EDGE('',*,*,#28295,.F.); +#28295 = EDGE_CURVE('',#26270,#28273,#28296,.T.); +#28296 = SURFACE_CURVE('',#28297,(#28301,#28308),.PCURVE_S1.); +#28297 = LINE('',#28298,#28299); +#28298 = CARTESIAN_POINT('',(-2.7,0.305,3.895)); +#28299 = VECTOR('',#28300,1.); +#28300 = DIRECTION('',(-6.982966722219E-015,3.613456105514E-015,-1.)); +#28301 = PCURVE('',#26285,#28302); +#28302 = DEFINITIONAL_REPRESENTATION('',(#28303),#28307); +#28303 = LINE('',#28304,#28305); +#28304 = CARTESIAN_POINT('',(-0.6,-1.5)); +#28305 = VECTOR('',#28306,1.); +#28306 = DIRECTION('',(1.219727444046E-016,1.)); +#28307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28308 = PCURVE('',#26313,#28309); +#28309 = DEFINITIONAL_REPRESENTATION('',(#28310),#28314); +#28310 = LINE('',#28311,#28312); +#28311 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28312 = VECTOR('',#28313,1.); +#28313 = DIRECTION('',(-1.,0.E+000)); +#28314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28315 = ORIENTED_EDGE('',*,*,#26269,.F.); +#28316 = ORIENTED_EDGE('',*,*,#28051,.F.); +#28317 = ORIENTED_EDGE('',*,*,#28318,.F.); +#28318 = EDGE_CURVE('',#28229,#28052,#28319,.T.); +#28319 = SURFACE_CURVE('',#28320,(#28324,#28331),.PCURVE_S1.); +#28320 = LINE('',#28321,#28322); +#28321 = CARTESIAN_POINT('',(-2.7,0.905,3.395)); +#28322 = VECTOR('',#28323,1.); +#28323 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28324 = PCURVE('',#26285,#28325); +#28325 = DEFINITIONAL_REPRESENTATION('',(#28326),#28330); +#28326 = LINE('',#28327,#28328); +#28327 = CARTESIAN_POINT('',(4.97919847714E-017,-1.)); +#28328 = VECTOR('',#28329,1.); +#28329 = DIRECTION('',(1.,-1.702510980039E-043)); +#28330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28331 = PCURVE('',#27313,#28332); +#28332 = DEFINITIONAL_REPRESENTATION('',(#28333),#28337); +#28333 = LINE('',#28334,#28335); +#28334 = CARTESIAN_POINT('',(-0.65,0.2)); +#28335 = VECTOR('',#28336,1.); +#28336 = DIRECTION('',(1.,0.E+000)); +#28337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28338 = ADVANCED_FACE('',(#28339),#26537,.F.); +#28339 = FACE_BOUND('',#28340,.T.); +#28340 = EDGE_LOOP('',(#28341,#28364,#28365,#28366,#28389,#28417,#28445, + #28468)); +#28341 = ORIENTED_EDGE('',*,*,#28342,.T.); +#28342 = EDGE_CURVE('',#28343,#27348,#28345,.T.); +#28343 = VERTEX_POINT('',#28344); +#28344 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); +#28345 = SURFACE_CURVE('',#28346,(#28350,#28357),.PCURVE_S1.); +#28346 = LINE('',#28347,#28348); +#28347 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); +#28348 = VECTOR('',#28349,1.); +#28349 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28350 = PCURVE('',#26537,#28351); +#28351 = DEFINITIONAL_REPRESENTATION('',(#28352),#28356); +#28352 = LINE('',#28353,#28354); +#28353 = CARTESIAN_POINT('',(0.5,1.488675134595)); +#28354 = VECTOR('',#28355,1.); +#28355 = DIRECTION('',(-1.,0.E+000)); +#28356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28357 = PCURVE('',#27386,#28358); +#28358 = DEFINITIONAL_REPRESENTATION('',(#28359),#28363); +#28359 = LINE('',#28360,#28361); +#28360 = CARTESIAN_POINT('',(-0.57735026919,-2.046371908427E-016)); +#28361 = VECTOR('',#28362,1.); +#28362 = DIRECTION('',(-1.228743304519E-031,1.)); +#28363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28364 = ORIENTED_EDGE('',*,*,#27347,.T.); +#28365 = ORIENTED_EDGE('',*,*,#26521,.T.); +#28366 = ORIENTED_EDGE('',*,*,#28367,.T.); +#28367 = EDGE_CURVE('',#26494,#28368,#28370,.T.); +#28368 = VERTEX_POINT('',#28369); +#28369 = CARTESIAN_POINT('',(3.,3.255,1.133675134595)); +#28370 = SURFACE_CURVE('',#28371,(#28375,#28382),.PCURVE_S1.); +#28371 = LINE('',#28372,#28373); +#28372 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#28373 = VECTOR('',#28374,1.); +#28374 = DIRECTION('',(-7.18705183704E-015,3.491483361109E-015,-1.)); +#28375 = PCURVE('',#26537,#28376); +#28376 = DEFINITIONAL_REPRESENTATION('',(#28377),#28381); +#28377 = LINE('',#28378,#28379); +#28378 = CARTESIAN_POINT('',(6.,-7.902749635247E-016)); +#28379 = VECTOR('',#28380,1.); +#28380 = DIRECTION('',(-2.040851148208E-016,-1.)); +#28381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28382 = PCURVE('',#26509,#28383); +#28383 = DEFINITIONAL_REPRESENTATION('',(#28384),#28388); +#28384 = LINE('',#28385,#28386); +#28385 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28386 = VECTOR('',#28387,1.); +#28387 = DIRECTION('',(-1.,-1.752268792537E-043)); +#28388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28389 = ORIENTED_EDGE('',*,*,#28390,.F.); +#28390 = EDGE_CURVE('',#28391,#28368,#28393,.T.); +#28391 = VERTEX_POINT('',#28392); +#28392 = CARTESIAN_POINT('',(2.5,3.255,1.133675134595)); #28393 = SURFACE_CURVE('',#28394,(#28398,#28405),.PCURVE_S1.); #28394 = LINE('',#28395,#28396); -#28395 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#28395 = CARTESIAN_POINT('',(2.5,3.255,1.133675134595)); #28396 = VECTOR('',#28397,1.); #28397 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28398 = PCURVE('',#27331,#28399); +#28398 = PCURVE('',#26537,#28399); #28399 = DEFINITIONAL_REPRESENTATION('',(#28400),#28404); #28400 = LINE('',#28401,#28402); -#28401 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28401 = CARTESIAN_POINT('',(5.5,1.488675134595)); #28402 = VECTOR('',#28403,1.); -#28403 = DIRECTION('',(5.315081284607E-045,-1.)); +#28403 = DIRECTION('',(1.,0.E+000)); #28404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#28405 = PCURVE('',#27359,#28406); -#28406 = DEFINITIONAL_REPRESENTATION('',(#28407),#28411); -#28407 = LINE('',#28408,#28409); -#28408 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); -#28409 = VECTOR('',#28410,1.); -#28410 = DIRECTION('',(0.E+000,-1.)); -#28411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28412 = ORIENTED_EDGE('',*,*,#27315,.F.); -#28413 = ORIENTED_EDGE('',*,*,#28216,.T.); -#28414 = ADVANCED_FACE('',(#28415),#27359,.F.); -#28415 = FACE_BOUND('',#28416,.T.); -#28416 = EDGE_LOOP('',(#28417,#28418,#28419,#28420)); -#28417 = ORIENTED_EDGE('',*,*,#27793,.T.); -#28418 = ORIENTED_EDGE('',*,*,#27842,.F.); -#28419 = ORIENTED_EDGE('',*,*,#27343,.F.); -#28420 = ORIENTED_EDGE('',*,*,#28392,.T.); -#28421 = ADVANCED_FACE('',(#28422),#27555,.F.); -#28422 = FACE_BOUND('',#28423,.T.); -#28423 = EDGE_LOOP('',(#28424,#28425,#28426,#28427)); -#28424 = ORIENTED_EDGE('',*,*,#27539,.T.); -#28425 = ORIENTED_EDGE('',*,*,#27720,.F.); -#28426 = ORIENTED_EDGE('',*,*,#27670,.F.); -#28427 = ORIENTED_EDGE('',*,*,#28428,.T.); -#28428 = EDGE_CURVE('',#27648,#27540,#28429,.T.); -#28429 = SURFACE_CURVE('',#28430,(#28434,#28441),.PCURVE_S1.); -#28430 = LINE('',#28431,#28432); -#28431 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); -#28432 = VECTOR('',#28433,1.); -#28433 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); -#28434 = PCURVE('',#27555,#28435); -#28435 = DEFINITIONAL_REPRESENTATION('',(#28436),#28440); -#28436 = LINE('',#28437,#28438); -#28437 = CARTESIAN_POINT('',(0.8,-1.462805571117E-016)); -#28438 = VECTOR('',#28439,1.); -#28439 = DIRECTION('',(0.E+000,-1.)); -#28440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28441 = PCURVE('',#27581,#28442); -#28442 = DEFINITIONAL_REPRESENTATION('',(#28443),#28447); -#28443 = LINE('',#28444,#28445); -#28444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#28445 = VECTOR('',#28446,1.); -#28446 = DIRECTION('',(5.315081284607E-045,-1.)); -#28447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28448 = ADVANCED_FACE('',(#28449),#27581,.F.); -#28449 = FACE_BOUND('',#28450,.T.); -#28450 = EDGE_LOOP('',(#28451,#28452,#28453,#28454)); -#28451 = ORIENTED_EDGE('',*,*,#27567,.T.); -#28452 = ORIENTED_EDGE('',*,*,#28428,.F.); -#28453 = ORIENTED_EDGE('',*,*,#27647,.F.); -#28454 = ORIENTED_EDGE('',*,*,#28270,.T.); -#28455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28459)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28456,#28457,#28458)) +#28405 = PCURVE('',#28406,#28411); +#28406 = PLANE('',#28407); +#28407 = AXIS2_PLACEMENT_3D('',#28408,#28409,#28410); +#28408 = CARTESIAN_POINT('',(2.5,2.755,0.845)); +#28409 = DIRECTION('',(6.047426575223E-015,-0.5,0.866025403784)); +#28410 = DIRECTION('',(3.491483361109E-015,0.866025403784,0.5)); +#28411 = DEFINITIONAL_REPRESENTATION('',(#28412),#28416); +#28412 = LINE('',#28413,#28414); +#28413 = CARTESIAN_POINT('',(0.57735026919,-2.046371908427E-016)); +#28414 = VECTOR('',#28415,1.); +#28415 = DIRECTION('',(-1.228743304519E-031,-1.)); +#28416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28417 = ORIENTED_EDGE('',*,*,#28418,.F.); +#28418 = EDGE_CURVE('',#28419,#28391,#28421,.T.); +#28419 = VERTEX_POINT('',#28420); +#28420 = CARTESIAN_POINT('',(2.5,3.255,-0.355)); +#28421 = SURFACE_CURVE('',#28422,(#28426,#28433),.PCURVE_S1.); +#28422 = LINE('',#28423,#28424); +#28423 = CARTESIAN_POINT('',(2.5,3.255,0.195)); +#28424 = VECTOR('',#28425,1.); +#28425 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28426 = PCURVE('',#26537,#28427); +#28427 = DEFINITIONAL_REPRESENTATION('',(#28428),#28432); +#28428 = LINE('',#28429,#28430); +#28429 = CARTESIAN_POINT('',(5.5,0.55)); +#28430 = VECTOR('',#28431,1.); +#28431 = DIRECTION('',(0.E+000,1.)); +#28432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28433 = PCURVE('',#28434,#28439); +#28434 = PLANE('',#28435); +#28435 = AXIS2_PLACEMENT_3D('',#28436,#28437,#28438); +#28436 = CARTESIAN_POINT('',(2.5,2.755,-0.355)); +#28437 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28438 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28439 = DEFINITIONAL_REPRESENTATION('',(#28440),#28444); +#28440 = LINE('',#28441,#28442); +#28441 = CARTESIAN_POINT('',(-0.5,0.55)); +#28442 = VECTOR('',#28443,1.); +#28443 = DIRECTION('',(-1.702510980039E-043,1.)); +#28444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28445 = ORIENTED_EDGE('',*,*,#28446,.T.); +#28446 = EDGE_CURVE('',#28419,#28447,#28449,.T.); +#28447 = VERTEX_POINT('',#28448); +#28448 = CARTESIAN_POINT('',(-2.5,3.255,-0.355)); +#28449 = SURFACE_CURVE('',#28450,(#28454,#28461),.PCURVE_S1.); +#28450 = LINE('',#28451,#28452); +#28451 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#28452 = VECTOR('',#28453,1.); +#28453 = DIRECTION('',(-1.,-4.27569270828E-031,7.105427357601E-015)); +#28454 = PCURVE('',#26537,#28455); +#28455 = DEFINITIONAL_REPRESENTATION('',(#28456),#28460); +#28456 = LINE('',#28457,#28458); +#28457 = CARTESIAN_POINT('',(6.,-7.902749635247E-016)); +#28458 = VECTOR('',#28459,1.); +#28459 = DIRECTION('',(-1.,1.224606353822E-016)); +#28460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28461 = PCURVE('',#27206,#28462); +#28462 = DEFINITIONAL_REPRESENTATION('',(#28463),#28467); +#28463 = LINE('',#28464,#28465); +#28464 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28465 = VECTOR('',#28466,1.); +#28466 = DIRECTION('',(-1.,0.E+000)); +#28467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28468 = ORIENTED_EDGE('',*,*,#28469,.T.); +#28469 = EDGE_CURVE('',#28447,#28343,#28470,.T.); +#28470 = SURFACE_CURVE('',#28471,(#28475,#28482),.PCURVE_S1.); +#28471 = LINE('',#28472,#28473); +#28472 = CARTESIAN_POINT('',(-2.5,3.255,1.133675134595)); +#28473 = VECTOR('',#28474,1.); +#28474 = DIRECTION('',(6.982966722219E-015,-3.491483361109E-015,1.)); +#28475 = PCURVE('',#26537,#28476); +#28476 = DEFINITIONAL_REPRESENTATION('',(#28477),#28481); +#28477 = LINE('',#28478,#28479); +#28478 = CARTESIAN_POINT('',(0.5,1.488675134595)); +#28479 = VECTOR('',#28480,1.); +#28480 = DIRECTION('',(0.E+000,1.)); +#28481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28482 = PCURVE('',#28483,#28488); +#28483 = PLANE('',#28484); +#28484 = AXIS2_PLACEMENT_3D('',#28485,#28486,#28487); +#28485 = CARTESIAN_POINT('',(-2.5,2.755,-0.355)); +#28486 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#28487 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28488 = DEFINITIONAL_REPRESENTATION('',(#28489),#28493); +#28489 = LINE('',#28490,#28491); +#28490 = CARTESIAN_POINT('',(-0.5,-1.488675134595)); +#28491 = VECTOR('',#28492,1.); +#28492 = DIRECTION('',(-1.702510980039E-043,-1.)); +#28493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28494 = ADVANCED_FACE('',(#28495),#26397,.F.); +#28495 = FACE_BOUND('',#28496,.T.); +#28496 = EDGE_LOOP('',(#28497,#28498,#28519,#28520)); +#28497 = ORIENTED_EDGE('',*,*,#27638,.T.); +#28498 = ORIENTED_EDGE('',*,*,#28499,.F.); +#28499 = EDGE_CURVE('',#27002,#27616,#28500,.T.); +#28500 = SURFACE_CURVE('',#28501,(#28505,#28512),.PCURVE_S1.); +#28501 = LINE('',#28502,#28503); +#28502 = CARTESIAN_POINT('',(2.5,0.305,2.395)); +#28503 = VECTOR('',#28504,1.); +#28504 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28505 = PCURVE('',#26397,#28506); +#28506 = DEFINITIONAL_REPRESENTATION('',(#28507),#28511); +#28507 = LINE('',#28508,#28509); +#28508 = CARTESIAN_POINT('',(-0.6,3.185331772654E-016)); +#28509 = VECTOR('',#28510,1.); +#28510 = DIRECTION('',(1.,1.702510980039E-043)); +#28511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28512 = PCURVE('',#27040,#28513); +#28513 = DEFINITIONAL_REPRESENTATION('',(#28514),#28518); +#28514 = LINE('',#28515,#28516); +#28515 = CARTESIAN_POINT('',(-2.245921632424E-031,0.2)); +#28516 = VECTOR('',#28517,1.); +#28517 = DIRECTION('',(1.,0.E+000)); +#28518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28519 = ORIENTED_EDGE('',*,*,#27001,.F.); +#28520 = ORIENTED_EDGE('',*,*,#26381,.F.); +#28521 = ADVANCED_FACE('',(#28522),#26509,.F.); +#28522 = FACE_BOUND('',#28523,.T.); +#28523 = EDGE_LOOP('',(#28524,#28554,#28575,#28576,#28577,#28600,#28623, + #28646,#28667,#28668,#28691,#28719)); +#28524 = ORIENTED_EDGE('',*,*,#28525,.F.); +#28525 = EDGE_CURVE('',#28526,#28528,#28530,.T.); +#28526 = VERTEX_POINT('',#28527); +#28527 = CARTESIAN_POINT('',(3.,2.755,0.845)); +#28528 = VERTEX_POINT('',#28529); +#28529 = CARTESIAN_POINT('',(3.,2.755,0.195)); +#28530 = SURFACE_CURVE('',#28531,(#28535,#28542),.PCURVE_S1.); +#28531 = LINE('',#28532,#28533); +#28532 = CARTESIAN_POINT('',(3.,2.755,0.195)); +#28533 = VECTOR('',#28534,1.); +#28534 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#28535 = PCURVE('',#26509,#28536); +#28536 = DEFINITIONAL_REPRESENTATION('',(#28537),#28541); +#28537 = LINE('',#28538,#28539); +#28538 = CARTESIAN_POINT('',(0.55,-0.5)); +#28539 = VECTOR('',#28540,1.); +#28540 = DIRECTION('',(-1.,-1.752268792537E-043)); +#28541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28542 = PCURVE('',#28543,#28548); +#28543 = PLANE('',#28544); +#28544 = AXIS2_PLACEMENT_3D('',#28545,#28546,#28547); +#28545 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#28546 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28547 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); +#28548 = DEFINITIONAL_REPRESENTATION('',(#28549),#28553); +#28549 = LINE('',#28550,#28551); +#28550 = CARTESIAN_POINT('',(0.5,-5.719166459861E-018)); +#28551 = VECTOR('',#28552,1.); +#28552 = DIRECTION('',(0.E+000,-1.)); +#28553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28554 = ORIENTED_EDGE('',*,*,#28555,.F.); +#28555 = EDGE_CURVE('',#28368,#28526,#28556,.T.); +#28556 = SURFACE_CURVE('',#28557,(#28561,#28568),.PCURVE_S1.); +#28557 = LINE('',#28558,#28559); +#28558 = CARTESIAN_POINT('',(3.,2.755,0.845)); +#28559 = VECTOR('',#28560,1.); +#28560 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); +#28561 = PCURVE('',#26509,#28562); +#28562 = DEFINITIONAL_REPRESENTATION('',(#28563),#28567); +#28563 = LINE('',#28564,#28565); +#28564 = CARTESIAN_POINT('',(1.2,-0.5)); +#28565 = VECTOR('',#28566,1.); +#28566 = DIRECTION('',(-0.5,-0.866025403784)); +#28567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28568 = PCURVE('',#28406,#28569); +#28569 = DEFINITIONAL_REPRESENTATION('',(#28570),#28574); +#28570 = LINE('',#28571,#28572); +#28571 = CARTESIAN_POINT('',(2.48959923857E-017,-0.5)); +#28572 = VECTOR('',#28573,1.); +#28573 = DIRECTION('',(-1.,1.961367055364E-030)); +#28574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28575 = ORIENTED_EDGE('',*,*,#28367,.F.); +#28576 = ORIENTED_EDGE('',*,*,#26493,.T.); +#28577 = ORIENTED_EDGE('',*,*,#28578,.F.); +#28578 = EDGE_CURVE('',#28579,#26466,#28581,.T.); +#28579 = VERTEX_POINT('',#28580); +#28580 = CARTESIAN_POINT('',(3.,1.555,3.395)); +#28581 = SURFACE_CURVE('',#28582,(#28586,#28593),.PCURVE_S1.); +#28582 = LINE('',#28583,#28584); +#28583 = CARTESIAN_POINT('',(3.,1.555,3.895)); +#28584 = VECTOR('',#28585,1.); +#28585 = DIRECTION('',(6.982966722219E-015,-3.057802492115E-015,1.)); +#28586 = PCURVE('',#26509,#28587); +#28587 = DEFINITIONAL_REPRESENTATION('',(#28588),#28592); +#28588 = LINE('',#28589,#28590); +#28589 = CARTESIAN_POINT('',(4.25,-1.7)); +#28590 = VECTOR('',#28591,1.); +#28591 = DIRECTION('',(1.,4.336808689942E-016)); +#28592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28593 = PCURVE('',#26481,#28594); +#28594 = DEFINITIONAL_REPRESENTATION('',(#28595),#28599); +#28595 = LINE('',#28596,#28597); +#28596 = CARTESIAN_POINT('',(-3.828588921589E-016,-0.5)); +#28597 = VECTOR('',#28598,1.); +#28598 = DIRECTION('',(-1.,0.E+000)); +#28599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28600 = ORIENTED_EDGE('',*,*,#28601,.F.); +#28601 = EDGE_CURVE('',#28602,#28579,#28604,.T.); +#28602 = VERTEX_POINT('',#28603); +#28603 = CARTESIAN_POINT('',(3.,0.905,3.395)); +#28604 = SURFACE_CURVE('',#28605,(#28609,#28616),.PCURVE_S1.); +#28605 = LINE('',#28606,#28607); +#28606 = CARTESIAN_POINT('',(3.,1.555,3.395)); +#28607 = VECTOR('',#28608,1.); +#28608 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28609 = PCURVE('',#26509,#28610); +#28610 = DEFINITIONAL_REPRESENTATION('',(#28611),#28615); +#28611 = LINE('',#28612,#28613); +#28612 = CARTESIAN_POINT('',(3.75,-1.7)); +#28613 = VECTOR('',#28614,1.); +#28614 = DIRECTION('',(1.752268792537E-043,1.)); +#28615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28616 = PCURVE('',#28118,#28617); +#28617 = DEFINITIONAL_REPRESENTATION('',(#28618),#28622); +#28618 = LINE('',#28619,#28620); +#28619 = CARTESIAN_POINT('',(2.13784635414E-031,-0.5)); +#28620 = VECTOR('',#28621,1.); +#28621 = DIRECTION('',(-1.,0.E+000)); +#28622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28623 = ORIENTED_EDGE('',*,*,#28624,.F.); +#28624 = EDGE_CURVE('',#28625,#28602,#28627,.T.); +#28625 = VERTEX_POINT('',#28626); +#28626 = CARTESIAN_POINT('',(3.,0.905,2.395)); +#28627 = SURFACE_CURVE('',#28628,(#28632,#28639),.PCURVE_S1.); +#28628 = LINE('',#28629,#28630); +#28629 = CARTESIAN_POINT('',(3.,0.905,3.395)); +#28630 = VECTOR('',#28631,1.); +#28631 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); +#28632 = PCURVE('',#26509,#28633); +#28633 = DEFINITIONAL_REPRESENTATION('',(#28634),#28638); +#28634 = LINE('',#28635,#28636); +#28635 = CARTESIAN_POINT('',(3.75,-2.35)); +#28636 = VECTOR('',#28637,1.); +#28637 = DIRECTION('',(1.,-1.084202172486E-016)); +#28638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28639 = PCURVE('',#28211,#28640); +#28640 = DEFINITIONAL_REPRESENTATION('',(#28641),#28645); +#28641 = LINE('',#28642,#28643); +#28642 = CARTESIAN_POINT('',(6.123031769112E-017,-0.5)); +#28643 = VECTOR('',#28644,1.); +#28644 = DIRECTION('',(-1.,0.E+000)); +#28645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28646 = ORIENTED_EDGE('',*,*,#28647,.F.); +#28647 = EDGE_CURVE('',#27565,#28625,#28648,.T.); +#28648 = SURFACE_CURVE('',#28649,(#28653,#28660),.PCURVE_S1.); +#28649 = LINE('',#28650,#28651); +#28650 = CARTESIAN_POINT('',(3.,0.905,2.395)); +#28651 = VECTOR('',#28652,1.); +#28652 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#28653 = PCURVE('',#26509,#28654); +#28654 = DEFINITIONAL_REPRESENTATION('',(#28655),#28659); +#28655 = LINE('',#28656,#28657); +#28656 = CARTESIAN_POINT('',(2.75,-2.35)); +#28657 = VECTOR('',#28658,1.); +#28658 = DIRECTION('',(1.752268792537E-043,1.)); +#28659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28660 = PCURVE('',#27603,#28661); +#28661 = DEFINITIONAL_REPRESENTATION('',(#28662),#28666); +#28662 = LINE('',#28663,#28664); +#28663 = CARTESIAN_POINT('',(2.13784635414E-031,-0.5)); +#28664 = VECTOR('',#28665,1.); +#28665 = DIRECTION('',(-1.,0.E+000)); +#28666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28667 = ORIENTED_EDGE('',*,*,#27564,.T.); +#28668 = ORIENTED_EDGE('',*,*,#28669,.F.); +#28669 = EDGE_CURVE('',#28670,#27542,#28672,.T.); +#28670 = VERTEX_POINT('',#28671); +#28671 = CARTESIAN_POINT('',(3.,1.755,-0.355)); +#28672 = SURFACE_CURVE('',#28673,(#28677,#28684),.PCURVE_S1.); +#28673 = LINE('',#28674,#28675); +#28674 = CARTESIAN_POINT('',(3.,3.255,-0.355)); +#28675 = VECTOR('',#28676,1.); +#28676 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28677 = PCURVE('',#26509,#28678); +#28678 = DEFINITIONAL_REPRESENTATION('',(#28679),#28683); +#28679 = LINE('',#28680,#28681); +#28680 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28681 = VECTOR('',#28682,1.); +#28682 = DIRECTION('',(-1.752268792537E-043,-1.)); +#28683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28684 = PCURVE('',#27206,#28685); +#28685 = DEFINITIONAL_REPRESENTATION('',(#28686),#28690); +#28686 = LINE('',#28687,#28688); +#28687 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28688 = VECTOR('',#28689,1.); +#28689 = DIRECTION('',(-2.80259692865E-045,-1.)); +#28690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28691 = ORIENTED_EDGE('',*,*,#28692,.F.); +#28692 = EDGE_CURVE('',#28693,#28670,#28695,.T.); +#28693 = VERTEX_POINT('',#28694); +#28694 = CARTESIAN_POINT('',(3.,1.755,0.195)); +#28695 = SURFACE_CURVE('',#28696,(#28700,#28707),.PCURVE_S1.); +#28696 = LINE('',#28697,#28698); +#28697 = CARTESIAN_POINT('',(3.,1.755,0.195)); +#28698 = VECTOR('',#28699,1.); +#28699 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#28700 = PCURVE('',#26509,#28701); +#28701 = DEFINITIONAL_REPRESENTATION('',(#28702),#28706); +#28702 = LINE('',#28703,#28704); +#28703 = CARTESIAN_POINT('',(0.55,-1.5)); +#28704 = VECTOR('',#28705,1.); +#28705 = DIRECTION('',(-1.,-1.752268792537E-043)); +#28706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28707 = PCURVE('',#28708,#28713); +#28708 = PLANE('',#28709); +#28709 = AXIS2_PLACEMENT_3D('',#28710,#28711,#28712); +#28710 = CARTESIAN_POINT('',(2.5,1.755,0.195)); +#28711 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#28712 = DIRECTION('',(1.,-2.80259692865E-045,-6.982966722219E-015)); +#28713 = DEFINITIONAL_REPRESENTATION('',(#28714),#28718); +#28714 = LINE('',#28715,#28716); +#28715 = CARTESIAN_POINT('',(0.5,2.203640915577E-017)); +#28716 = VECTOR('',#28717,1.); +#28717 = DIRECTION('',(0.E+000,-1.)); +#28718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28719 = ORIENTED_EDGE('',*,*,#28720,.F.); +#28720 = EDGE_CURVE('',#28528,#28693,#28721,.T.); +#28721 = SURFACE_CURVE('',#28722,(#28726,#28733),.PCURVE_S1.); +#28722 = LINE('',#28723,#28724); +#28723 = CARTESIAN_POINT('',(3.,2.755,0.195)); +#28724 = VECTOR('',#28725,1.); +#28725 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#28726 = PCURVE('',#26509,#28727); +#28727 = DEFINITIONAL_REPRESENTATION('',(#28728),#28732); +#28728 = LINE('',#28729,#28730); +#28729 = CARTESIAN_POINT('',(0.55,-0.5)); +#28730 = VECTOR('',#28731,1.); +#28731 = DIRECTION('',(-1.084202172486E-016,-1.)); +#28732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28733 = PCURVE('',#28734,#28739); +#28734 = PLANE('',#28735); +#28735 = AXIS2_PLACEMENT_3D('',#28736,#28737,#28738); +#28736 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#28737 = DIRECTION('',(6.982966722219E-015,-3.599903578358E-015,1.)); +#28738 = DIRECTION('',(2.513800689087E-029,1.,3.599903578358E-015)); +#28739 = DEFINITIONAL_REPRESENTATION('',(#28740),#28744); +#28740 = LINE('',#28741,#28742); +#28741 = CARTESIAN_POINT('',(-2.058844780408E-032,-0.5)); +#28742 = VECTOR('',#28743,1.); +#28743 = DIRECTION('',(-1.,0.E+000)); +#28744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28745 = ADVANCED_FACE('',(#28746),#26670,.F.); +#28746 = FACE_BOUND('',#28747,.T.); +#28747 = EDGE_LOOP('',(#28748,#28749,#28750,#28751)); +#28748 = ORIENTED_EDGE('',*,*,#26654,.T.); +#28749 = ORIENTED_EDGE('',*,*,#26838,.F.); +#28750 = ORIENTED_EDGE('',*,*,#26761,.F.); +#28751 = ORIENTED_EDGE('',*,*,#26809,.T.); +#28752 = ADVANCED_FACE('',(#28753),#26481,.F.); +#28753 = FACE_BOUND('',#28754,.T.); +#28754 = EDGE_LOOP('',(#28755,#28756,#28757,#28778)); +#28755 = ORIENTED_EDGE('',*,*,#26465,.F.); +#28756 = ORIENTED_EDGE('',*,*,#28130,.F.); +#28757 = ORIENTED_EDGE('',*,*,#28758,.T.); +#28758 = EDGE_CURVE('',#28103,#28579,#28759,.T.); +#28759 = SURFACE_CURVE('',#28760,(#28764,#28771),.PCURVE_S1.); +#28760 = LINE('',#28761,#28762); +#28761 = CARTESIAN_POINT('',(2.5,1.555,3.395)); +#28762 = VECTOR('',#28763,1.); +#28763 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#28764 = PCURVE('',#26481,#28765); +#28765 = DEFINITIONAL_REPRESENTATION('',(#28766),#28770); +#28766 = LINE('',#28767,#28768); +#28767 = CARTESIAN_POINT('',(0.5,6.123031769112E-017)); +#28768 = VECTOR('',#28769,1.); +#28769 = DIRECTION('',(0.E+000,-1.)); +#28770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28771 = PCURVE('',#28118,#28772); +#28772 = DEFINITIONAL_REPRESENTATION('',(#28773),#28777); +#28773 = LINE('',#28774,#28775); +#28774 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28775 = VECTOR('',#28776,1.); +#28776 = DIRECTION('',(-2.80259692865E-045,-1.)); +#28777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28778 = ORIENTED_EDGE('',*,*,#28578,.T.); +#28779 = ADVANCED_FACE('',(#28780),#26313,.T.); +#28780 = FACE_BOUND('',#28781,.T.); +#28781 = EDGE_LOOP('',(#28782,#28783,#28784,#28785)); +#28782 = ORIENTED_EDGE('',*,*,#27108,.F.); +#28783 = ORIENTED_EDGE('',*,*,#26297,.F.); +#28784 = ORIENTED_EDGE('',*,*,#28295,.T.); +#28785 = ORIENTED_EDGE('',*,*,#28786,.T.); +#28786 = EDGE_CURVE('',#28273,#27109,#28787,.T.); +#28787 = SURFACE_CURVE('',#28788,(#28792,#28799),.PCURVE_S1.); +#28788 = LINE('',#28789,#28790); +#28789 = CARTESIAN_POINT('',(-2.7,0.305,2.395)); +#28790 = VECTOR('',#28791,1.); +#28791 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#28792 = PCURVE('',#26313,#28793); +#28793 = DEFINITIONAL_REPRESENTATION('',(#28794),#28798); +#28794 = LINE('',#28795,#28796); +#28795 = CARTESIAN_POINT('',(-1.5,-2.603982567767E-016)); +#28796 = VECTOR('',#28797,1.); +#28797 = DIRECTION('',(0.E+000,-1.)); +#28798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28799 = PCURVE('',#27145,#28800); +#28800 = DEFINITIONAL_REPRESENTATION('',(#28801),#28805); +#28801 = LINE('',#28802,#28803); +#28802 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28803 = VECTOR('',#28804,1.); +#28804 = DIRECTION('',(-2.80259692865E-045,-1.)); +#28805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28806 = ADVANCED_FACE('',(#28807),#27040,.F.); +#28807 = FACE_BOUND('',#28808,.T.); +#28808 = EDGE_LOOP('',(#28809,#28810,#28811,#28812)); +#28809 = ORIENTED_EDGE('',*,*,#27615,.T.); +#28810 = ORIENTED_EDGE('',*,*,#28153,.F.); +#28811 = ORIENTED_EDGE('',*,*,#27024,.T.); +#28812 = ORIENTED_EDGE('',*,*,#28499,.T.); +#28813 = ADVANCED_FACE('',(#28814),#27145,.T.); +#28814 = FACE_BOUND('',#28815,.T.); +#28815 = EDGE_LOOP('',(#28816,#28817,#28818,#28819)); +#28816 = ORIENTED_EDGE('',*,*,#28272,.T.); +#28817 = ORIENTED_EDGE('',*,*,#27661,.F.); +#28818 = ORIENTED_EDGE('',*,*,#27131,.F.); +#28819 = ORIENTED_EDGE('',*,*,#28786,.F.); +#28820 = ADVANCED_FACE('',(#28821),#27440,.T.); +#28821 = FACE_BOUND('',#28822,.T.); +#28822 = EDGE_LOOP('',(#28823,#28824,#28847,#28870)); +#28823 = ORIENTED_EDGE('',*,*,#27426,.F.); +#28824 = ORIENTED_EDGE('',*,*,#28825,.F.); +#28825 = EDGE_CURVE('',#28826,#27399,#28828,.T.); +#28826 = VERTEX_POINT('',#28827); +#28827 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#28828 = SURFACE_CURVE('',#28829,(#28833,#28840),.PCURVE_S1.); +#28829 = LINE('',#28830,#28831); +#28830 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#28831 = VECTOR('',#28832,1.); +#28832 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28833 = PCURVE('',#27440,#28834); +#28834 = DEFINITIONAL_REPRESENTATION('',(#28835),#28839); +#28835 = LINE('',#28836,#28837); +#28836 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28837 = VECTOR('',#28838,1.); +#28838 = DIRECTION('',(2.80259692865E-045,1.)); +#28839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28840 = PCURVE('',#27414,#28841); +#28841 = DEFINITIONAL_REPRESENTATION('',(#28842),#28846); +#28842 = LINE('',#28843,#28844); +#28843 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28844 = VECTOR('',#28845,1.); +#28845 = DIRECTION('',(1.,0.E+000)); +#28846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28847 = ORIENTED_EDGE('',*,*,#28848,.T.); +#28848 = EDGE_CURVE('',#28826,#28849,#28851,.T.); +#28849 = VERTEX_POINT('',#28850); +#28850 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); +#28851 = SURFACE_CURVE('',#28852,(#28856,#28863),.PCURVE_S1.); +#28852 = LINE('',#28853,#28854); +#28853 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#28854 = VECTOR('',#28855,1.); +#28855 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#28856 = PCURVE('',#27440,#28857); +#28857 = DEFINITIONAL_REPRESENTATION('',(#28858),#28862); +#28858 = LINE('',#28859,#28860); +#28859 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28860 = VECTOR('',#28861,1.); +#28861 = DIRECTION('',(1.,0.E+000)); +#28862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28863 = PCURVE('',#28483,#28864); +#28864 = DEFINITIONAL_REPRESENTATION('',(#28865),#28869); +#28865 = LINE('',#28866,#28867); +#28866 = CARTESIAN_POINT('',(-1.439590092099E-016,-0.55)); +#28867 = VECTOR('',#28868,1.); +#28868 = DIRECTION('',(1.,1.084202172486E-016)); +#28869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28870 = ORIENTED_EDGE('',*,*,#28871,.T.); +#28871 = EDGE_CURVE('',#28849,#27161,#28872,.T.); +#28872 = SURFACE_CURVE('',#28873,(#28877,#28884),.PCURVE_S1.); +#28873 = LINE('',#28874,#28875); +#28874 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); +#28875 = VECTOR('',#28876,1.); +#28876 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28877 = PCURVE('',#27440,#28878); +#28878 = DEFINITIONAL_REPRESENTATION('',(#28879),#28883); +#28879 = LINE('',#28880,#28881); +#28880 = CARTESIAN_POINT('',(1.,-2.51961139144E-029)); +#28881 = VECTOR('',#28882,1.); +#28882 = DIRECTION('',(2.80259692865E-045,1.)); +#28883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28884 = PCURVE('',#27178,#28885); +#28885 = DEFINITIONAL_REPRESENTATION('',(#28886),#28890); +#28886 = LINE('',#28887,#28888); +#28887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28888 = VECTOR('',#28889,1.); +#28889 = DIRECTION('',(1.,0.E+000)); +#28890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28891 = ADVANCED_FACE('',(#28892),#27414,.T.); +#28892 = FACE_BOUND('',#28893,.T.); +#28893 = EDGE_LOOP('',(#28894,#28895,#28918,#28939)); +#28894 = ORIENTED_EDGE('',*,*,#27398,.F.); +#28895 = ORIENTED_EDGE('',*,*,#28896,.F.); +#28896 = EDGE_CURVE('',#28897,#27371,#28899,.T.); +#28897 = VERTEX_POINT('',#28898); +#28898 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); +#28899 = SURFACE_CURVE('',#28900,(#28904,#28911),.PCURVE_S1.); +#28900 = LINE('',#28901,#28902); +#28901 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); +#28902 = VECTOR('',#28903,1.); +#28903 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#28904 = PCURVE('',#27414,#28905); +#28905 = DEFINITIONAL_REPRESENTATION('',(#28906),#28910); +#28906 = LINE('',#28907,#28908); +#28907 = CARTESIAN_POINT('',(9.803627094157E-017,0.65)); +#28908 = VECTOR('',#28909,1.); +#28909 = DIRECTION('',(1.,0.E+000)); +#28910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28911 = PCURVE('',#27386,#28912); +#28912 = DEFINITIONAL_REPRESENTATION('',(#28913),#28917); +#28913 = LINE('',#28914,#28915); +#28914 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28915 = VECTOR('',#28916,1.); +#28916 = DIRECTION('',(-1.228743304519E-031,1.)); +#28917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28918 = ORIENTED_EDGE('',*,*,#28919,.T.); +#28919 = EDGE_CURVE('',#28897,#28826,#28920,.T.); +#28920 = SURFACE_CURVE('',#28921,(#28925,#28932),.PCURVE_S1.); +#28921 = LINE('',#28922,#28923); +#28922 = CARTESIAN_POINT('',(-2.5,2.755,0.195)); +#28923 = VECTOR('',#28924,1.); +#28924 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#28925 = PCURVE('',#27414,#28926); +#28926 = DEFINITIONAL_REPRESENTATION('',(#28927),#28931); +#28927 = LINE('',#28928,#28929); +#28928 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28929 = VECTOR('',#28930,1.); +#28930 = DIRECTION('',(0.E+000,-1.)); +#28931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28932 = PCURVE('',#28483,#28933); +#28933 = DEFINITIONAL_REPRESENTATION('',(#28934),#28938); +#28934 = LINE('',#28935,#28936); +#28935 = CARTESIAN_POINT('',(-1.439590092099E-016,-0.55)); +#28936 = VECTOR('',#28937,1.); +#28937 = DIRECTION('',(1.702510980039E-043,1.)); +#28938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28939 = ORIENTED_EDGE('',*,*,#28825,.T.); +#28940 = ADVANCED_FACE('',(#28941),#27386,.T.); +#28941 = FACE_BOUND('',#28942,.T.); +#28942 = EDGE_LOOP('',(#28943,#28944,#28945,#28966)); +#28943 = ORIENTED_EDGE('',*,*,#27370,.F.); +#28944 = ORIENTED_EDGE('',*,*,#28342,.F.); +#28945 = ORIENTED_EDGE('',*,*,#28946,.T.); +#28946 = EDGE_CURVE('',#28343,#28897,#28947,.T.); +#28947 = SURFACE_CURVE('',#28948,(#28952,#28959),.PCURVE_S1.); +#28948 = LINE('',#28949,#28950); +#28949 = CARTESIAN_POINT('',(-2.5,2.755,0.845)); +#28950 = VECTOR('',#28951,1.); +#28951 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); +#28952 = PCURVE('',#27386,#28953); +#28953 = DEFINITIONAL_REPRESENTATION('',(#28954),#28958); +#28954 = LINE('',#28955,#28956); +#28955 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#28956 = VECTOR('',#28957,1.); +#28957 = DIRECTION('',(1.,1.961367055364E-030)); +#28958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28959 = PCURVE('',#28483,#28960); +#28960 = DEFINITIONAL_REPRESENTATION('',(#28961),#28965); +#28961 = LINE('',#28962,#28963); +#28962 = CARTESIAN_POINT('',(2.511120651694E-016,-1.2)); +#28963 = VECTOR('',#28964,1.); +#28964 = DIRECTION('',(0.866025403784,0.5)); +#28965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28966 = ORIENTED_EDGE('',*,*,#28896,.T.); +#28967 = ADVANCED_FACE('',(#28968),#27206,.F.); +#28968 = FACE_BOUND('',#28969,.T.); +#28969 = EDGE_LOOP('',(#28970,#29000,#29021,#29022,#29045,#29073,#29094, + #29095,#29118,#29146,#29167,#29168,#29191,#29219,#29240,#29241, + #29242,#29265,#29286,#29287,#29310,#29331,#29332,#29333)); +#28970 = ORIENTED_EDGE('',*,*,#28971,.F.); +#28971 = EDGE_CURVE('',#28972,#28974,#28976,.T.); +#28972 = VERTEX_POINT('',#28973); +#28973 = CARTESIAN_POINT('',(1.4,0.495,-0.355)); +#28974 = VERTEX_POINT('',#28975); +#28975 = CARTESIAN_POINT('',(1.6,0.495,-0.355)); +#28976 = SURFACE_CURVE('',#28977,(#28981,#28988),.PCURVE_S1.); +#28977 = LINE('',#28978,#28979); +#28978 = CARTESIAN_POINT('',(1.4,0.495,-0.355)); +#28979 = VECTOR('',#28980,1.); +#28980 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#28981 = PCURVE('',#27206,#28982); +#28982 = DEFINITIONAL_REPRESENTATION('',(#28983),#28987); +#28983 = LINE('',#28984,#28985); +#28984 = CARTESIAN_POINT('',(-1.6,-2.76)); +#28985 = VECTOR('',#28986,1.); +#28986 = DIRECTION('',(1.,0.E+000)); +#28987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#28988 = PCURVE('',#28989,#28994); +#28989 = PLANE('',#28990); +#28990 = AXIS2_PLACEMENT_3D('',#28991,#28992,#28993); +#28991 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); +#28992 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); +#28993 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); +#28994 = DEFINITIONAL_REPRESENTATION('',(#28995),#28999); +#28995 = LINE('',#28996,#28997); +#28996 = CARTESIAN_POINT('',(0.7,3.095397202444E-018)); +#28997 = VECTOR('',#28998,1.); +#28998 = DIRECTION('',(0.E+000,-1.)); +#28999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29000 = ORIENTED_EDGE('',*,*,#29001,.T.); +#29001 = EDGE_CURVE('',#28972,#27458,#29002,.T.); +#29002 = SURFACE_CURVE('',#29003,(#29007,#29014),.PCURVE_S1.); +#29003 = LINE('',#29004,#29005); +#29004 = CARTESIAN_POINT('',(1.4,3.255,-0.355)); +#29005 = VECTOR('',#29006,1.); +#29006 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29007 = PCURVE('',#27206,#29008); +#29008 = DEFINITIONAL_REPRESENTATION('',(#29009),#29013); +#29009 = LINE('',#29010,#29011); +#29010 = CARTESIAN_POINT('',(-1.6,7.228740855008E-031)); +#29011 = VECTOR('',#29012,1.); +#29012 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29014 = PCURVE('',#27473,#29015); +#29015 = DEFINITIONAL_REPRESENTATION('',(#29016),#29020); +#29016 = LINE('',#29017,#29018); +#29017 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29018 = VECTOR('',#29019,1.); +#29019 = DIRECTION('',(1.,-1.702510980039E-043)); +#29020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29021 = ORIENTED_EDGE('',*,*,#28027,.T.); +#29022 = ORIENTED_EDGE('',*,*,#29023,.F.); +#29023 = EDGE_CURVE('',#29024,#28000,#29026,.T.); +#29024 = VERTEX_POINT('',#29025); +#29025 = CARTESIAN_POINT('',(0.6,0.495,-0.355)); +#29026 = SURFACE_CURVE('',#29027,(#29031,#29038),.PCURVE_S1.); +#29027 = LINE('',#29028,#29029); +#29028 = CARTESIAN_POINT('',(0.6,3.255,-0.355)); +#29029 = VECTOR('',#29030,1.); +#29030 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29031 = PCURVE('',#27206,#29032); +#29032 = DEFINITIONAL_REPRESENTATION('',(#29033),#29037); +#29033 = LINE('',#29034,#29035); +#29034 = CARTESIAN_POINT('',(-2.4,9.874029978112E-031)); +#29035 = VECTOR('',#29036,1.); +#29036 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29038 = PCURVE('',#28015,#29039); +#29039 = DEFINITIONAL_REPRESENTATION('',(#29040),#29044); +#29040 = LINE('',#29041,#29042); +#29041 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29042 = VECTOR('',#29043,1.); +#29043 = DIRECTION('',(1.,-1.702510980039E-043)); +#29044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29045 = ORIENTED_EDGE('',*,*,#29046,.F.); +#29046 = EDGE_CURVE('',#29047,#29024,#29049,.T.); +#29047 = VERTEX_POINT('',#29048); +#29048 = CARTESIAN_POINT('',(0.4,0.495,-0.355)); +#29049 = SURFACE_CURVE('',#29050,(#29054,#29061),.PCURVE_S1.); +#29050 = LINE('',#29051,#29052); +#29051 = CARTESIAN_POINT('',(0.4,0.495,-0.355)); +#29052 = VECTOR('',#29053,1.); +#29053 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29054 = PCURVE('',#27206,#29055); +#29055 = DEFINITIONAL_REPRESENTATION('',(#29056),#29060); +#29056 = LINE('',#29057,#29058); +#29057 = CARTESIAN_POINT('',(-2.6,-2.76)); +#29058 = VECTOR('',#29059,1.); +#29059 = DIRECTION('',(1.,0.E+000)); +#29060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29061 = PCURVE('',#29062,#29067); +#29062 = PLANE('',#29063); +#29063 = AXIS2_PLACEMENT_3D('',#29064,#29065,#29066); +#29064 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); +#29065 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); +#29066 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); +#29067 = DEFINITIONAL_REPRESENTATION('',(#29068),#29072); +#29068 = LINE('',#29069,#29070); +#29069 = CARTESIAN_POINT('',(0.7,3.095397202446E-018)); +#29070 = VECTOR('',#29071,1.); +#29071 = DIRECTION('',(0.E+000,-1.)); +#29072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29073 = ORIENTED_EDGE('',*,*,#29074,.T.); +#29074 = EDGE_CURVE('',#29047,#27921,#29075,.T.); +#29075 = SURFACE_CURVE('',#29076,(#29080,#29087),.PCURVE_S1.); +#29076 = LINE('',#29077,#29078); +#29077 = CARTESIAN_POINT('',(0.4,3.255,-0.355)); +#29078 = VECTOR('',#29079,1.); +#29079 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29080 = PCURVE('',#27206,#29081); +#29081 = DEFINITIONAL_REPRESENTATION('',(#29082),#29086); +#29082 = LINE('',#29083,#29084); +#29083 = CARTESIAN_POINT('',(-2.6,1.150443356329E-030)); +#29084 = VECTOR('',#29085,1.); +#29085 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29087 = PCURVE('',#27959,#29088); +#29088 = DEFINITIONAL_REPRESENTATION('',(#29089),#29093); +#29089 = LINE('',#29090,#29091); +#29090 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29091 = VECTOR('',#29092,1.); +#29092 = DIRECTION('',(1.,-1.702510980039E-043)); +#29093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29094 = ORIENTED_EDGE('',*,*,#27920,.T.); +#29095 = ORIENTED_EDGE('',*,*,#29096,.F.); +#29096 = EDGE_CURVE('',#29097,#27893,#29099,.T.); +#29097 = VERTEX_POINT('',#29098); +#29098 = CARTESIAN_POINT('',(-0.4,0.495,-0.355)); +#29099 = SURFACE_CURVE('',#29100,(#29104,#29111),.PCURVE_S1.); +#29100 = LINE('',#29101,#29102); +#29101 = CARTESIAN_POINT('',(-0.4,3.255,-0.355)); +#29102 = VECTOR('',#29103,1.); +#29103 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29104 = PCURVE('',#27206,#29105); +#29105 = DEFINITIONAL_REPRESENTATION('',(#29106),#29110); +#29106 = LINE('',#29107,#29108); +#29107 = CARTESIAN_POINT('',(-3.4,1.414972268639E-030)); +#29108 = VECTOR('',#29109,1.); +#29109 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29111 = PCURVE('',#27908,#29112); +#29112 = DEFINITIONAL_REPRESENTATION('',(#29113),#29117); +#29113 = LINE('',#29114,#29115); +#29114 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29115 = VECTOR('',#29116,1.); +#29116 = DIRECTION('',(1.,-1.702510980039E-043)); +#29117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29118 = ORIENTED_EDGE('',*,*,#29119,.F.); +#29119 = EDGE_CURVE('',#29120,#29097,#29122,.T.); +#29120 = VERTEX_POINT('',#29121); +#29121 = CARTESIAN_POINT('',(-0.6,0.495,-0.355)); +#29122 = SURFACE_CURVE('',#29123,(#29127,#29134),.PCURVE_S1.); +#29123 = LINE('',#29124,#29125); +#29124 = CARTESIAN_POINT('',(-0.6,0.495,-0.355)); +#29125 = VECTOR('',#29126,1.); +#29126 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29127 = PCURVE('',#27206,#29128); +#29128 = DEFINITIONAL_REPRESENTATION('',(#29129),#29133); +#29129 = LINE('',#29130,#29131); +#29130 = CARTESIAN_POINT('',(-3.6,-2.76)); +#29131 = VECTOR('',#29132,1.); +#29132 = DIRECTION('',(1.,0.E+000)); +#29133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29134 = PCURVE('',#29135,#29140); +#29135 = PLANE('',#29136); +#29136 = AXIS2_PLACEMENT_3D('',#29137,#29138,#29139); +#29137 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); +#29138 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); +#29139 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); +#29140 = DEFINITIONAL_REPRESENTATION('',(#29141),#29145); +#29141 = LINE('',#29142,#29143); +#29142 = CARTESIAN_POINT('',(0.7,3.095397202444E-018)); +#29143 = VECTOR('',#29144,1.); +#29144 = DIRECTION('',(0.E+000,-1.)); +#29145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29146 = ORIENTED_EDGE('',*,*,#29147,.T.); +#29147 = EDGE_CURVE('',#29120,#27814,#29148,.T.); +#29148 = SURFACE_CURVE('',#29149,(#29153,#29160),.PCURVE_S1.); +#29149 = LINE('',#29150,#29151); +#29150 = CARTESIAN_POINT('',(-0.6,3.255,-0.355)); +#29151 = VECTOR('',#29152,1.); +#29152 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29153 = PCURVE('',#27206,#29154); +#29154 = DEFINITIONAL_REPRESENTATION('',(#29155),#29159); +#29155 = LINE('',#29156,#29157); +#29156 = CARTESIAN_POINT('',(-3.6,1.578012627157E-030)); +#29157 = VECTOR('',#29158,1.); +#29158 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29160 = PCURVE('',#27852,#29161); +#29161 = DEFINITIONAL_REPRESENTATION('',(#29162),#29166); +#29162 = LINE('',#29163,#29164); +#29163 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29164 = VECTOR('',#29165,1.); +#29165 = DIRECTION('',(1.,-1.702510980039E-043)); +#29166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29167 = ORIENTED_EDGE('',*,*,#27813,.T.); +#29168 = ORIENTED_EDGE('',*,*,#29169,.F.); +#29169 = EDGE_CURVE('',#29170,#27786,#29172,.T.); +#29170 = VERTEX_POINT('',#29171); +#29171 = CARTESIAN_POINT('',(-1.4,0.495,-0.355)); +#29172 = SURFACE_CURVE('',#29173,(#29177,#29184),.PCURVE_S1.); +#29173 = LINE('',#29174,#29175); +#29174 = CARTESIAN_POINT('',(-1.4,3.255,-0.355)); +#29175 = VECTOR('',#29176,1.); +#29176 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29177 = PCURVE('',#27206,#29178); +#29178 = DEFINITIONAL_REPRESENTATION('',(#29179),#29183); +#29179 = LINE('',#29180,#29181); +#29180 = CARTESIAN_POINT('',(-4.4,1.842541539467E-030)); +#29181 = VECTOR('',#29182,1.); +#29182 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29184 = PCURVE('',#27801,#29185); +#29185 = DEFINITIONAL_REPRESENTATION('',(#29186),#29190); +#29186 = LINE('',#29187,#29188); +#29187 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29188 = VECTOR('',#29189,1.); +#29189 = DIRECTION('',(1.,-1.702510980039E-043)); +#29190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29191 = ORIENTED_EDGE('',*,*,#29192,.F.); +#29192 = EDGE_CURVE('',#29193,#29170,#29195,.T.); +#29193 = VERTEX_POINT('',#29194); +#29194 = CARTESIAN_POINT('',(-1.6,0.495,-0.355)); +#29195 = SURFACE_CURVE('',#29196,(#29200,#29207),.PCURVE_S1.); +#29196 = LINE('',#29197,#29198); +#29197 = CARTESIAN_POINT('',(-1.6,0.495,-0.355)); +#29198 = VECTOR('',#29199,1.); +#29199 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29200 = PCURVE('',#27206,#29201); +#29201 = DEFINITIONAL_REPRESENTATION('',(#29202),#29206); +#29202 = LINE('',#29203,#29204); +#29203 = CARTESIAN_POINT('',(-4.6,-2.76)); +#29204 = VECTOR('',#29205,1.); +#29205 = DIRECTION('',(1.,0.E+000)); +#29206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29207 = PCURVE('',#29208,#29213); +#29208 = PLANE('',#29209); +#29209 = AXIS2_PLACEMENT_3D('',#29210,#29211,#29212); +#29210 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); +#29211 = DIRECTION('',(-2.492169409971E-029,-1.,-3.56892637343E-015)); +#29212 = DIRECTION('',(6.982966722219E-015,-3.56892637343E-015,1.)); +#29213 = DEFINITIONAL_REPRESENTATION('',(#29214),#29218); +#29214 = LINE('',#29215,#29216); +#29215 = CARTESIAN_POINT('',(0.7,3.095397202446E-018)); +#29216 = VECTOR('',#29217,1.); +#29217 = DIRECTION('',(0.E+000,-1.)); +#29218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29219 = ORIENTED_EDGE('',*,*,#29220,.T.); +#29220 = EDGE_CURVE('',#29193,#27707,#29221,.T.); +#29221 = SURFACE_CURVE('',#29222,(#29226,#29233),.PCURVE_S1.); +#29222 = LINE('',#29223,#29224); +#29223 = CARTESIAN_POINT('',(-1.6,3.255,-0.355)); +#29224 = VECTOR('',#29225,1.); +#29225 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29226 = PCURVE('',#27206,#29227); +#29227 = DEFINITIONAL_REPRESENTATION('',(#29228),#29232); +#29228 = LINE('',#29229,#29230); +#29229 = CARTESIAN_POINT('',(-4.6,2.005581897985E-030)); +#29230 = VECTOR('',#29231,1.); +#29231 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29233 = PCURVE('',#27745,#29234); +#29234 = DEFINITIONAL_REPRESENTATION('',(#29235),#29239); +#29235 = LINE('',#29236,#29237); +#29236 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29237 = VECTOR('',#29238,1.); +#29238 = DIRECTION('',(1.,-1.702510980039E-043)); +#29239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29240 = ORIENTED_EDGE('',*,*,#27706,.T.); +#29241 = ORIENTED_EDGE('',*,*,#27190,.F.); +#29242 = ORIENTED_EDGE('',*,*,#29243,.F.); +#29243 = EDGE_CURVE('',#29244,#27163,#29246,.T.); +#29244 = VERTEX_POINT('',#29245); +#29245 = CARTESIAN_POINT('',(-2.5,1.755,-0.355)); +#29246 = SURFACE_CURVE('',#29247,(#29251,#29258),.PCURVE_S1.); +#29247 = LINE('',#29248,#29249); +#29248 = CARTESIAN_POINT('',(-2.5,1.755,-0.355)); +#29249 = VECTOR('',#29250,1.); +#29250 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#29251 = PCURVE('',#27206,#29252); +#29252 = DEFINITIONAL_REPRESENTATION('',(#29253),#29257); +#29253 = LINE('',#29254,#29255); +#29254 = CARTESIAN_POINT('',(-5.5,-1.5)); +#29255 = VECTOR('',#29256,1.); +#29256 = DIRECTION('',(-1.,0.E+000)); +#29257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29258 = PCURVE('',#27178,#29259); +#29259 = DEFINITIONAL_REPRESENTATION('',(#29260),#29264); +#29260 = LINE('',#29261,#29262); +#29261 = CARTESIAN_POINT('',(1.561711914302E-016,-0.55)); +#29262 = VECTOR('',#29263,1.); +#29263 = DIRECTION('',(1.,0.E+000)); +#29264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29265 = ORIENTED_EDGE('',*,*,#29266,.T.); +#29266 = EDGE_CURVE('',#29244,#28447,#29267,.T.); +#29267 = SURFACE_CURVE('',#29268,(#29272,#29279),.PCURVE_S1.); +#29268 = LINE('',#29269,#29270); +#29269 = CARTESIAN_POINT('',(-2.5,2.755,-0.355)); +#29270 = VECTOR('',#29271,1.); +#29271 = DIRECTION('',(2.405242980303E-029,1.,3.444442850701E-015)); +#29272 = PCURVE('',#27206,#29273); +#29273 = DEFINITIONAL_REPRESENTATION('',(#29274),#29278); +#29274 = LINE('',#29275,#29276); +#29275 = CARTESIAN_POINT('',(-5.5,-0.5)); +#29276 = VECTOR('',#29277,1.); +#29277 = DIRECTION('',(5.760610793312E-033,1.)); +#29278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29279 = PCURVE('',#28483,#29280); +#29280 = DEFINITIONAL_REPRESENTATION('',(#29281),#29285); +#29281 = LINE('',#29282,#29283); +#29282 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29283 = VECTOR('',#29284,1.); +#29284 = DIRECTION('',(-1.,4.704051040836E-017)); +#29285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29286 = ORIENTED_EDGE('',*,*,#28446,.F.); +#29287 = ORIENTED_EDGE('',*,*,#29288,.F.); +#29288 = EDGE_CURVE('',#29289,#28419,#29291,.T.); +#29289 = VERTEX_POINT('',#29290); +#29290 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); +#29291 = SURFACE_CURVE('',#29292,(#29296,#29303),.PCURVE_S1.); +#29292 = LINE('',#29293,#29294); +#29293 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); +#29294 = VECTOR('',#29295,1.); +#29295 = DIRECTION('',(2.438091212181E-029,1.,3.491483361109E-015)); +#29296 = PCURVE('',#27206,#29297); +#29297 = DEFINITIONAL_REPRESENTATION('',(#29298),#29302); +#29298 = LINE('',#29299,#29300); +#29299 = CARTESIAN_POINT('',(-0.5,-1.5)); +#29300 = VECTOR('',#29301,1.); +#29301 = DIRECTION('',(2.80259692865E-045,1.)); +#29302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29303 = PCURVE('',#28434,#29304); +#29304 = DEFINITIONAL_REPRESENTATION('',(#29305),#29309); +#29305 = LINE('',#29306,#29307); +#29306 = CARTESIAN_POINT('',(1.,-5.719166459861E-018)); +#29307 = VECTOR('',#29308,1.); +#29308 = DIRECTION('',(-1.,1.702510980039E-043)); +#29309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29310 = ORIENTED_EDGE('',*,*,#29311,.T.); +#29311 = EDGE_CURVE('',#29289,#28670,#29312,.T.); +#29312 = SURFACE_CURVE('',#29313,(#29317,#29324),.PCURVE_S1.); +#29313 = LINE('',#29314,#29315); +#29314 = CARTESIAN_POINT('',(2.5,1.755,-0.355)); +#29315 = VECTOR('',#29316,1.); +#29316 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29317 = PCURVE('',#27206,#29318); +#29318 = DEFINITIONAL_REPRESENTATION('',(#29319),#29323); +#29319 = LINE('',#29320,#29321); +#29320 = CARTESIAN_POINT('',(-0.5,-1.5)); +#29321 = VECTOR('',#29322,1.); +#29322 = DIRECTION('',(1.,0.E+000)); +#29323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29324 = PCURVE('',#28708,#29325); +#29325 = DEFINITIONAL_REPRESENTATION('',(#29326),#29330); +#29326 = LINE('',#29327,#29328); +#29327 = CARTESIAN_POINT('',(-1.561711914302E-016,-0.55)); +#29328 = VECTOR('',#29329,1.); +#29329 = DIRECTION('',(1.,0.E+000)); +#29330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29331 = ORIENTED_EDGE('',*,*,#28669,.T.); +#29332 = ORIENTED_EDGE('',*,*,#27541,.T.); +#29333 = ORIENTED_EDGE('',*,*,#29334,.F.); +#29334 = EDGE_CURVE('',#28974,#27514,#29335,.T.); +#29335 = SURFACE_CURVE('',#29336,(#29340,#29347),.PCURVE_S1.); +#29336 = LINE('',#29337,#29338); +#29337 = CARTESIAN_POINT('',(1.6,3.255,-0.355)); +#29338 = VECTOR('',#29339,1.); +#29339 = DIRECTION('',(-2.438091212181E-029,-1.,-3.491483361109E-015)); +#29340 = PCURVE('',#27206,#29341); +#29341 = DEFINITIONAL_REPRESENTATION('',(#29342),#29346); +#29342 = LINE('',#29343,#29344); +#29343 = CARTESIAN_POINT('',(-1.4,5.598337269832E-031)); +#29344 = VECTOR('',#29345,1.); +#29345 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29347 = PCURVE('',#27529,#29348); +#29348 = DEFINITIONAL_REPRESENTATION('',(#29349),#29353); +#29349 = LINE('',#29350,#29351); +#29350 = CARTESIAN_POINT('',(-2.81,-0.55)); +#29351 = VECTOR('',#29352,1.); +#29352 = DIRECTION('',(1.,-1.702510980039E-043)); +#29353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29354 = ADVANCED_FACE('',(#29355),#27285,.T.); +#29355 = FACE_BOUND('',#29356,.T.); +#29356 = EDGE_LOOP('',(#29357,#29358,#29379,#29380)); +#29357 = ORIENTED_EDGE('',*,*,#28226,.T.); +#29358 = ORIENTED_EDGE('',*,*,#29359,.T.); +#29359 = EDGE_CURVE('',#28229,#27270,#29360,.T.); +#29360 = SURFACE_CURVE('',#29361,(#29365,#29372),.PCURVE_S1.); +#29361 = LINE('',#29362,#29363); +#29362 = CARTESIAN_POINT('',(-2.5,0.905,3.395)); +#29363 = VECTOR('',#29364,1.); +#29364 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#29365 = PCURVE('',#27285,#29366); +#29366 = DEFINITIONAL_REPRESENTATION('',(#29367),#29371); +#29367 = LINE('',#29368,#29369); +#29368 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29369 = VECTOR('',#29370,1.); +#29370 = DIRECTION('',(0.E+000,1.)); +#29371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29372 = PCURVE('',#27313,#29373); +#29373 = DEFINITIONAL_REPRESENTATION('',(#29374),#29378); +#29374 = LINE('',#29375,#29376); +#29375 = CARTESIAN_POINT('',(-0.65,-1.55053008704E-029)); +#29376 = VECTOR('',#29377,1.); +#29377 = DIRECTION('',(-2.80259692865E-045,1.)); +#29378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29379 = ORIENTED_EDGE('',*,*,#27269,.F.); +#29380 = ORIENTED_EDGE('',*,*,#29381,.F.); +#29381 = EDGE_CURVE('',#28227,#27242,#29382,.T.); +#29382 = SURFACE_CURVE('',#29383,(#29387,#29394),.PCURVE_S1.); +#29383 = LINE('',#29384,#29385); +#29384 = CARTESIAN_POINT('',(-2.5,0.905,2.395)); +#29385 = VECTOR('',#29386,1.); +#29386 = DIRECTION('',(-1.,0.E+000,6.982966722219E-015)); +#29387 = PCURVE('',#27285,#29388); +#29388 = DEFINITIONAL_REPRESENTATION('',(#29389),#29393); +#29389 = LINE('',#29390,#29391); +#29390 = CARTESIAN_POINT('',(-1.,1.224606353822E-016)); +#29391 = VECTOR('',#29392,1.); +#29392 = DIRECTION('',(0.E+000,1.)); +#29393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29394 = PCURVE('',#27257,#29395); +#29395 = DEFINITIONAL_REPRESENTATION('',(#29396),#29400); +#29396 = LINE('',#29397,#29398); +#29397 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29398 = VECTOR('',#29399,1.); +#29399 = DIRECTION('',(-2.80259692865E-045,1.)); +#29400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29401 = ADVANCED_FACE('',(#29402),#27178,.T.); +#29402 = FACE_BOUND('',#29403,.T.); +#29403 = EDGE_LOOP('',(#29404,#29405,#29406,#29427)); +#29404 = ORIENTED_EDGE('',*,*,#27160,.F.); +#29405 = ORIENTED_EDGE('',*,*,#28871,.F.); +#29406 = ORIENTED_EDGE('',*,*,#29407,.T.); +#29407 = EDGE_CURVE('',#28849,#29244,#29408,.T.); +#29408 = SURFACE_CURVE('',#29409,(#29413,#29420),.PCURVE_S1.); +#29409 = LINE('',#29410,#29411); +#29410 = CARTESIAN_POINT('',(-2.5,1.755,0.195)); +#29411 = VECTOR('',#29412,1.); +#29412 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#29413 = PCURVE('',#27178,#29414); +#29414 = DEFINITIONAL_REPRESENTATION('',(#29415),#29419); +#29415 = LINE('',#29416,#29417); +#29416 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29417 = VECTOR('',#29418,1.); +#29418 = DIRECTION('',(0.E+000,-1.)); +#29419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29420 = PCURVE('',#28483,#29421); +#29421 = DEFINITIONAL_REPRESENTATION('',(#29422),#29426); +#29422 = LINE('',#29423,#29424); +#29423 = CARTESIAN_POINT('',(1.,-0.55)); +#29424 = VECTOR('',#29425,1.); +#29425 = DIRECTION('',(1.702510980039E-043,1.)); +#29426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29427 = ORIENTED_EDGE('',*,*,#29243,.T.); +#29428 = ADVANCED_FACE('',(#29429),#27313,.T.); +#29429 = FACE_BOUND('',#29430,.T.); +#29430 = EDGE_LOOP('',(#29431,#29432,#29433,#29434)); +#29431 = ORIENTED_EDGE('',*,*,#28318,.T.); +#29432 = ORIENTED_EDGE('',*,*,#28076,.T.); +#29433 = ORIENTED_EDGE('',*,*,#27297,.F.); +#29434 = ORIENTED_EDGE('',*,*,#29359,.F.); +#29435 = ADVANCED_FACE('',(#29436),#27257,.T.); +#29436 = FACE_BOUND('',#29437,.T.); +#29437 = EDGE_LOOP('',(#29438,#29439,#29440,#29441)); +#29438 = ORIENTED_EDGE('',*,*,#28251,.T.); +#29439 = ORIENTED_EDGE('',*,*,#29381,.T.); +#29440 = ORIENTED_EDGE('',*,*,#27241,.F.); +#29441 = ORIENTED_EDGE('',*,*,#27684,.F.); +#29442 = ADVANCED_FACE('',(#29443),#27959,.T.); +#29443 = FACE_BOUND('',#29444,.T.); +#29444 = EDGE_LOOP('',(#29445,#29446,#29469,#29497,#29525,#29546)); +#29445 = ORIENTED_EDGE('',*,*,#29074,.F.); +#29446 = ORIENTED_EDGE('',*,*,#29447,.T.); +#29447 = EDGE_CURVE('',#29047,#29448,#29450,.T.); +#29448 = VERTEX_POINT('',#29449); +#29449 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); +#29450 = SURFACE_CURVE('',#29451,(#29455,#29462),.PCURVE_S1.); +#29451 = LINE('',#29452,#29453); +#29452 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); +#29453 = VECTOR('',#29454,1.); +#29454 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#29455 = PCURVE('',#27959,#29456); +#29456 = DEFINITIONAL_REPRESENTATION('',(#29457),#29461); +#29457 = LINE('',#29458,#29459); +#29458 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#29459 = VECTOR('',#29460,1.); +#29460 = DIRECTION('',(-7.744301232039E-017,-1.)); +#29461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29462 = PCURVE('',#29062,#29463); +#29463 = DEFINITIONAL_REPRESENTATION('',(#29464),#29468); +#29464 = LINE('',#29465,#29466); +#29465 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29466 = VECTOR('',#29467,1.); +#29467 = DIRECTION('',(-1.,0.E+000)); +#29468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29469 = ORIENTED_EDGE('',*,*,#29470,.T.); +#29470 = EDGE_CURVE('',#29448,#29471,#29473,.T.); +#29471 = VERTEX_POINT('',#29472); +#29472 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); +#29473 = SURFACE_CURVE('',#29474,(#29478,#29485),.PCURVE_S1.); +#29474 = LINE('',#29475,#29476); +#29475 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); +#29476 = VECTOR('',#29477,1.); +#29477 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#29478 = PCURVE('',#27959,#29479); +#29479 = DEFINITIONAL_REPRESENTATION('',(#29480),#29484); +#29480 = LINE('',#29481,#29482); +#29481 = CARTESIAN_POINT('',(0.15,-1.25)); +#29482 = VECTOR('',#29483,1.); +#29483 = DIRECTION('',(1.,-2.710505431214E-015)); +#29484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29485 = PCURVE('',#29486,#29491); +#29486 = PLANE('',#29487); +#29487 = AXIS2_PLACEMENT_3D('',#29488,#29489,#29490); +#29488 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); +#29489 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); +#29490 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); +#29491 = DEFINITIONAL_REPRESENTATION('',(#29492),#29496); +#29492 = LINE('',#29493,#29494); +#29493 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29494 = VECTOR('',#29495,1.); +#29495 = DIRECTION('',(-1.,0.E+000)); +#29496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29497 = ORIENTED_EDGE('',*,*,#29498,.T.); +#29498 = EDGE_CURVE('',#29471,#29499,#29501,.T.); +#29499 = VERTEX_POINT('',#29500); +#29500 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#29501 = SURFACE_CURVE('',#29502,(#29506,#29513),.PCURVE_S1.); +#29502 = LINE('',#29503,#29504); +#29503 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#29504 = VECTOR('',#29505,1.); +#29505 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#29506 = PCURVE('',#27959,#29507); +#29507 = DEFINITIONAL_REPRESENTATION('',(#29508),#29512); +#29508 = LINE('',#29509,#29510); +#29509 = CARTESIAN_POINT('',(0.15,-0.45)); +#29510 = VECTOR('',#29511,1.); +#29511 = DIRECTION('',(-1.101142831431E-016,1.)); +#29512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29513 = PCURVE('',#29514,#29519); +#29514 = PLANE('',#29515); +#29515 = AXIS2_PLACEMENT_3D('',#29516,#29517,#29518); +#29516 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#29517 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); +#29518 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); +#29519 = DEFINITIONAL_REPRESENTATION('',(#29520),#29524); +#29520 = LINE('',#29521,#29522); +#29521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29522 = VECTOR('',#29523,1.); +#29523 = DIRECTION('',(-1.,0.E+000)); +#29524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29525 = ORIENTED_EDGE('',*,*,#29526,.T.); +#29526 = EDGE_CURVE('',#29499,#27944,#29527,.T.); +#29527 = SURFACE_CURVE('',#29528,(#29532,#29539),.PCURVE_S1.); +#29528 = LINE('',#29529,#29530); +#29529 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#29530 = VECTOR('',#29531,1.); +#29531 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#29532 = PCURVE('',#27959,#29533); +#29533 = DEFINITIONAL_REPRESENTATION('',(#29534),#29538); +#29534 = LINE('',#29535,#29536); +#29535 = CARTESIAN_POINT('',(0.15,-0.45)); +#29536 = VECTOR('',#29537,1.); +#29537 = DIRECTION('',(-1.,-9.035018104046E-017)); +#29538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29539 = PCURVE('',#27987,#29540); +#29540 = DEFINITIONAL_REPRESENTATION('',(#29541),#29545); +#29541 = LINE('',#29542,#29543); +#29542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29543 = VECTOR('',#29544,1.); +#29544 = DIRECTION('',(-1.,0.E+000)); +#29545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29546 = ORIENTED_EDGE('',*,*,#27943,.T.); +#29547 = ADVANCED_FACE('',(#29548),#27529,.F.); +#29548 = FACE_BOUND('',#29549,.T.); +#29549 = EDGE_LOOP('',(#29550,#29573,#29574,#29575,#29598,#29626)); +#29550 = ORIENTED_EDGE('',*,*,#29551,.F.); +#29551 = EDGE_CURVE('',#28974,#29552,#29554,.T.); +#29552 = VERTEX_POINT('',#29553); +#29553 = CARTESIAN_POINT('',(1.6,0.495,-1.055)); +#29554 = SURFACE_CURVE('',#29555,(#29559,#29566),.PCURVE_S1.); +#29555 = LINE('',#29556,#29557); +#29556 = CARTESIAN_POINT('',(1.6,0.495,-1.055)); +#29557 = VECTOR('',#29558,1.); +#29558 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#29559 = PCURVE('',#27529,#29560); +#29560 = DEFINITIONAL_REPRESENTATION('',(#29561),#29565); +#29561 = LINE('',#29562,#29563); +#29562 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#29563 = VECTOR('',#29564,1.); +#29564 = DIRECTION('',(-7.744301232039E-017,-1.)); +#29565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29566 = PCURVE('',#28989,#29567); +#29567 = DEFINITIONAL_REPRESENTATION('',(#29568),#29572); +#29568 = LINE('',#29569,#29570); +#29569 = CARTESIAN_POINT('',(-1.577188900315E-016,-0.2)); +#29570 = VECTOR('',#29571,1.); +#29571 = DIRECTION('',(-1.,0.E+000)); +#29572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29573 = ORIENTED_EDGE('',*,*,#29334,.T.); +#29574 = ORIENTED_EDGE('',*,*,#27513,.F.); +#29575 = ORIENTED_EDGE('',*,*,#29576,.F.); +#29576 = EDGE_CURVE('',#29577,#27486,#29579,.T.); +#29577 = VERTEX_POINT('',#29578); +#29578 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); +#29579 = SURFACE_CURVE('',#29580,(#29584,#29591),.PCURVE_S1.); +#29580 = LINE('',#29581,#29582); +#29581 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); +#29582 = VECTOR('',#29583,1.); +#29583 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#29584 = PCURVE('',#27529,#29585); +#29585 = DEFINITIONAL_REPRESENTATION('',(#29586),#29590); +#29586 = LINE('',#29587,#29588); +#29587 = CARTESIAN_POINT('',(0.15,-0.45)); +#29588 = VECTOR('',#29589,1.); +#29589 = DIRECTION('',(-1.,-9.035018104046E-017)); +#29590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29591 = PCURVE('',#27501,#29592); +#29592 = DEFINITIONAL_REPRESENTATION('',(#29593),#29597); +#29593 = LINE('',#29594,#29595); +#29594 = CARTESIAN_POINT('',(-2.997950493971E-032,-0.2)); +#29595 = VECTOR('',#29596,1.); +#29596 = DIRECTION('',(-1.,0.E+000)); +#29597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29598 = ORIENTED_EDGE('',*,*,#29599,.F.); +#29599 = EDGE_CURVE('',#29600,#29577,#29602,.T.); +#29600 = VERTEX_POINT('',#29601); +#29601 = CARTESIAN_POINT('',(1.6,0.295,-1.055)); +#29602 = SURFACE_CURVE('',#29603,(#29607,#29614),.PCURVE_S1.); +#29603 = LINE('',#29604,#29605); +#29604 = CARTESIAN_POINT('',(1.6,0.295,-0.255)); +#29605 = VECTOR('',#29606,1.); +#29606 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#29607 = PCURVE('',#27529,#29608); +#29608 = DEFINITIONAL_REPRESENTATION('',(#29609),#29613); +#29609 = LINE('',#29610,#29611); +#29610 = CARTESIAN_POINT('',(0.15,-0.45)); +#29611 = VECTOR('',#29612,1.); +#29612 = DIRECTION('',(-1.101142831431E-016,1.)); +#29613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29614 = PCURVE('',#29615,#29620); +#29615 = PLANE('',#29616); +#29616 = AXIS2_PLACEMENT_3D('',#29617,#29618,#29619); +#29617 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#29618 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); +#29619 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); +#29620 = DEFINITIONAL_REPRESENTATION('',(#29621),#29625); +#29621 = LINE('',#29622,#29623); +#29622 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); +#29623 = VECTOR('',#29624,1.); +#29624 = DIRECTION('',(-1.,0.E+000)); +#29625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29626 = ORIENTED_EDGE('',*,*,#29627,.F.); +#29627 = EDGE_CURVE('',#29552,#29600,#29628,.T.); +#29628 = SURFACE_CURVE('',#29629,(#29633,#29640),.PCURVE_S1.); +#29629 = LINE('',#29630,#29631); +#29630 = CARTESIAN_POINT('',(1.6,0.295,-1.055)); +#29631 = VECTOR('',#29632,1.); +#29632 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#29633 = PCURVE('',#27529,#29634); +#29634 = DEFINITIONAL_REPRESENTATION('',(#29635),#29639); +#29635 = LINE('',#29636,#29637); +#29636 = CARTESIAN_POINT('',(0.15,-1.25)); +#29637 = VECTOR('',#29638,1.); +#29638 = DIRECTION('',(1.,-2.710505431214E-015)); +#29639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29640 = PCURVE('',#29641,#29646); +#29641 = PLANE('',#29642); +#29642 = AXIS2_PLACEMENT_3D('',#29643,#29644,#29645); +#29643 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); +#29644 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); +#29645 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); +#29646 = DEFINITIONAL_REPRESENTATION('',(#29647),#29651); +#29647 = LINE('',#29648,#29649); +#29648 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); +#29649 = VECTOR('',#29650,1.); +#29650 = DIRECTION('',(-1.,0.E+000)); +#29651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29652 = ADVANCED_FACE('',(#29653),#27603,.F.); +#29653 = FACE_BOUND('',#29654,.T.); +#29654 = EDGE_LOOP('',(#29655,#29676,#29677,#29678)); +#29655 = ORIENTED_EDGE('',*,*,#29656,.F.); +#29656 = EDGE_CURVE('',#28175,#28625,#29657,.T.); +#29657 = SURFACE_CURVE('',#29658,(#29662,#29669),.PCURVE_S1.); +#29658 = LINE('',#29659,#29660); +#29659 = CARTESIAN_POINT('',(2.5,0.905,2.395)); +#29660 = VECTOR('',#29661,1.); +#29661 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29662 = PCURVE('',#27603,#29663); +#29663 = DEFINITIONAL_REPRESENTATION('',(#29664),#29668); +#29664 = LINE('',#29665,#29666); +#29665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29666 = VECTOR('',#29667,1.); +#29667 = DIRECTION('',(-2.80259692865E-045,-1.)); +#29668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29669 = PCURVE('',#28211,#29670); +#29670 = DEFINITIONAL_REPRESENTATION('',(#29671),#29675); +#29671 = LINE('',#29672,#29673); +#29672 = CARTESIAN_POINT('',(1.,-3.216285744678E-016)); +#29673 = VECTOR('',#29674,1.); +#29674 = DIRECTION('',(0.E+000,-1.)); +#29675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29676 = ORIENTED_EDGE('',*,*,#28174,.T.); +#29677 = ORIENTED_EDGE('',*,*,#27587,.T.); +#29678 = ORIENTED_EDGE('',*,*,#28647,.T.); +#29679 = ADVANCED_FACE('',(#29680),#27745,.T.); +#29680 = FACE_BOUND('',#29681,.T.); +#29681 = EDGE_LOOP('',(#29682,#29683,#29706,#29734,#29762,#29783)); +#29682 = ORIENTED_EDGE('',*,*,#29220,.F.); +#29683 = ORIENTED_EDGE('',*,*,#29684,.T.); +#29684 = EDGE_CURVE('',#29193,#29685,#29687,.T.); +#29685 = VERTEX_POINT('',#29686); +#29686 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); +#29687 = SURFACE_CURVE('',#29688,(#29692,#29699),.PCURVE_S1.); +#29688 = LINE('',#29689,#29690); +#29689 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); +#29690 = VECTOR('',#29691,1.); +#29691 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#29692 = PCURVE('',#27745,#29693); +#29693 = DEFINITIONAL_REPRESENTATION('',(#29694),#29698); +#29694 = LINE('',#29695,#29696); +#29695 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#29696 = VECTOR('',#29697,1.); +#29697 = DIRECTION('',(-7.744301232039E-017,-1.)); +#29698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29699 = PCURVE('',#29208,#29700); +#29700 = DEFINITIONAL_REPRESENTATION('',(#29701),#29705); +#29701 = LINE('',#29702,#29703); +#29702 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29703 = VECTOR('',#29704,1.); +#29704 = DIRECTION('',(-1.,0.E+000)); +#29705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29706 = ORIENTED_EDGE('',*,*,#29707,.T.); +#29707 = EDGE_CURVE('',#29685,#29708,#29710,.T.); +#29708 = VERTEX_POINT('',#29709); +#29709 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#29710 = SURFACE_CURVE('',#29711,(#29715,#29722),.PCURVE_S1.); +#29711 = LINE('',#29712,#29713); +#29712 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#29713 = VECTOR('',#29714,1.); +#29714 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#29715 = PCURVE('',#27745,#29716); +#29716 = DEFINITIONAL_REPRESENTATION('',(#29717),#29721); +#29717 = LINE('',#29718,#29719); +#29718 = CARTESIAN_POINT('',(0.15,-1.25)); +#29719 = VECTOR('',#29720,1.); +#29720 = DIRECTION('',(1.,-2.710505431214E-015)); +#29721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29722 = PCURVE('',#29723,#29728); +#29723 = PLANE('',#29724); +#29724 = AXIS2_PLACEMENT_3D('',#29725,#29726,#29727); +#29725 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#29726 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); +#29727 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); +#29728 = DEFINITIONAL_REPRESENTATION('',(#29729),#29733); +#29729 = LINE('',#29730,#29731); +#29730 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29731 = VECTOR('',#29732,1.); +#29732 = DIRECTION('',(-1.,0.E+000)); +#29733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29734 = ORIENTED_EDGE('',*,*,#29735,.T.); +#29735 = EDGE_CURVE('',#29708,#29736,#29738,.T.); +#29736 = VERTEX_POINT('',#29737); +#29737 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#29738 = SURFACE_CURVE('',#29739,(#29743,#29750),.PCURVE_S1.); +#29739 = LINE('',#29740,#29741); +#29740 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#29741 = VECTOR('',#29742,1.); +#29742 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#29743 = PCURVE('',#27745,#29744); +#29744 = DEFINITIONAL_REPRESENTATION('',(#29745),#29749); +#29745 = LINE('',#29746,#29747); +#29746 = CARTESIAN_POINT('',(0.15,-0.45)); +#29747 = VECTOR('',#29748,1.); +#29748 = DIRECTION('',(-1.101142831431E-016,1.)); +#29749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29750 = PCURVE('',#29751,#29756); +#29751 = PLANE('',#29752); +#29752 = AXIS2_PLACEMENT_3D('',#29753,#29754,#29755); +#29753 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#29754 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); +#29755 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); +#29756 = DEFINITIONAL_REPRESENTATION('',(#29757),#29761); +#29757 = LINE('',#29758,#29759); +#29758 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29759 = VECTOR('',#29760,1.); +#29760 = DIRECTION('',(-1.,0.E+000)); +#29761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29762 = ORIENTED_EDGE('',*,*,#29763,.T.); +#29763 = EDGE_CURVE('',#29736,#27730,#29764,.T.); +#29764 = SURFACE_CURVE('',#29765,(#29769,#29776),.PCURVE_S1.); +#29765 = LINE('',#29766,#29767); +#29766 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#29767 = VECTOR('',#29768,1.); +#29768 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#29769 = PCURVE('',#27745,#29770); +#29770 = DEFINITIONAL_REPRESENTATION('',(#29771),#29775); +#29771 = LINE('',#29772,#29773); +#29772 = CARTESIAN_POINT('',(0.15,-0.45)); +#29773 = VECTOR('',#29774,1.); +#29774 = DIRECTION('',(-1.,-9.035018104046E-017)); +#29775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29776 = PCURVE('',#27773,#29777); +#29777 = DEFINITIONAL_REPRESENTATION('',(#29778),#29782); +#29778 = LINE('',#29779,#29780); +#29779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#29780 = VECTOR('',#29781,1.); +#29781 = DIRECTION('',(-1.,0.E+000)); +#29782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29783 = ORIENTED_EDGE('',*,*,#27729,.T.); +#29784 = ADVANCED_FACE('',(#29785),#28015,.F.); +#29785 = FACE_BOUND('',#29786,.T.); +#29786 = EDGE_LOOP('',(#29787,#29810,#29811,#29812,#29835,#29858)); +#29787 = ORIENTED_EDGE('',*,*,#29788,.F.); +#29788 = EDGE_CURVE('',#29024,#29789,#29791,.T.); +#29789 = VERTEX_POINT('',#29790); +#29790 = CARTESIAN_POINT('',(0.6,0.495,-1.055)); +#29791 = SURFACE_CURVE('',#29792,(#29796,#29803),.PCURVE_S1.); +#29792 = LINE('',#29793,#29794); +#29793 = CARTESIAN_POINT('',(0.6,0.495,-1.055)); +#29794 = VECTOR('',#29795,1.); +#29795 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#29796 = PCURVE('',#28015,#29797); +#29797 = DEFINITIONAL_REPRESENTATION('',(#29798),#29802); +#29798 = LINE('',#29799,#29800); +#29799 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#29800 = VECTOR('',#29801,1.); +#29801 = DIRECTION('',(-7.744301232039E-017,-1.)); +#29802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29803 = PCURVE('',#29062,#29804); +#29804 = DEFINITIONAL_REPRESENTATION('',(#29805),#29809); +#29805 = LINE('',#29806,#29807); +#29806 = CARTESIAN_POINT('',(6.432571489357E-017,-0.2)); +#29807 = VECTOR('',#29808,1.); +#29808 = DIRECTION('',(-1.,0.E+000)); +#29809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29810 = ORIENTED_EDGE('',*,*,#29023,.T.); +#29811 = ORIENTED_EDGE('',*,*,#27999,.F.); +#29812 = ORIENTED_EDGE('',*,*,#29813,.F.); +#29813 = EDGE_CURVE('',#29814,#27972,#29816,.T.); +#29814 = VERTEX_POINT('',#29815); +#29815 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); +#29816 = SURFACE_CURVE('',#29817,(#29821,#29828),.PCURVE_S1.); +#29817 = LINE('',#29818,#29819); +#29818 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); +#29819 = VECTOR('',#29820,1.); +#29820 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#29821 = PCURVE('',#28015,#29822); +#29822 = DEFINITIONAL_REPRESENTATION('',(#29823),#29827); +#29823 = LINE('',#29824,#29825); +#29824 = CARTESIAN_POINT('',(0.15,-0.45)); +#29825 = VECTOR('',#29826,1.); +#29826 = DIRECTION('',(-1.,-9.035018104046E-017)); +#29827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29828 = PCURVE('',#27987,#29829); +#29829 = DEFINITIONAL_REPRESENTATION('',(#29830),#29834); +#29830 = LINE('',#29831,#29832); +#29831 = CARTESIAN_POINT('',(-2.99795049397E-032,-0.2)); +#29832 = VECTOR('',#29833,1.); +#29833 = DIRECTION('',(-1.,0.E+000)); +#29834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29835 = ORIENTED_EDGE('',*,*,#29836,.F.); +#29836 = EDGE_CURVE('',#29837,#29814,#29839,.T.); +#29837 = VERTEX_POINT('',#29838); +#29838 = CARTESIAN_POINT('',(0.6,0.295,-1.055)); +#29839 = SURFACE_CURVE('',#29840,(#29844,#29851),.PCURVE_S1.); +#29840 = LINE('',#29841,#29842); +#29841 = CARTESIAN_POINT('',(0.6,0.295,-0.255)); +#29842 = VECTOR('',#29843,1.); +#29843 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#29844 = PCURVE('',#28015,#29845); +#29845 = DEFINITIONAL_REPRESENTATION('',(#29846),#29850); +#29846 = LINE('',#29847,#29848); +#29847 = CARTESIAN_POINT('',(0.15,-0.45)); +#29848 = VECTOR('',#29849,1.); +#29849 = DIRECTION('',(-1.101142831431E-016,1.)); +#29850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29851 = PCURVE('',#29514,#29852); +#29852 = DEFINITIONAL_REPRESENTATION('',(#29853),#29857); +#29853 = LINE('',#29854,#29855); +#29854 = CARTESIAN_POINT('',(4.669658756895E-017,-0.2)); +#29855 = VECTOR('',#29856,1.); +#29856 = DIRECTION('',(-1.,0.E+000)); +#29857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29858 = ORIENTED_EDGE('',*,*,#29859,.F.); +#29859 = EDGE_CURVE('',#29789,#29837,#29860,.T.); +#29860 = SURFACE_CURVE('',#29861,(#29865,#29872),.PCURVE_S1.); +#29861 = LINE('',#29862,#29863); +#29862 = CARTESIAN_POINT('',(0.6,0.295,-1.055)); +#29863 = VECTOR('',#29864,1.); +#29864 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#29865 = PCURVE('',#28015,#29866); +#29866 = DEFINITIONAL_REPRESENTATION('',(#29867),#29871); +#29867 = LINE('',#29868,#29869); +#29868 = CARTESIAN_POINT('',(0.15,-1.25)); +#29869 = VECTOR('',#29870,1.); +#29870 = DIRECTION('',(1.,-2.710505431214E-015)); +#29871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29872 = PCURVE('',#29486,#29873); +#29873 = DEFINITIONAL_REPRESENTATION('',(#29874),#29878); +#29874 = LINE('',#29875,#29876); +#29875 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); +#29876 = VECTOR('',#29877,1.); +#29877 = DIRECTION('',(-1.,0.E+000)); +#29878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29879 = ADVANCED_FACE('',(#29880),#27908,.F.); +#29880 = FACE_BOUND('',#29881,.T.); +#29881 = EDGE_LOOP('',(#29882,#29905,#29906,#29907,#29930,#29958)); +#29882 = ORIENTED_EDGE('',*,*,#29883,.F.); +#29883 = EDGE_CURVE('',#29097,#29884,#29886,.T.); +#29884 = VERTEX_POINT('',#29885); +#29885 = CARTESIAN_POINT('',(-0.4,0.495,-1.055)); +#29886 = SURFACE_CURVE('',#29887,(#29891,#29898),.PCURVE_S1.); +#29887 = LINE('',#29888,#29889); +#29888 = CARTESIAN_POINT('',(-0.4,0.495,-1.055)); +#29889 = VECTOR('',#29890,1.); +#29890 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#29891 = PCURVE('',#27908,#29892); +#29892 = DEFINITIONAL_REPRESENTATION('',(#29893),#29897); +#29893 = LINE('',#29894,#29895); +#29894 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#29895 = VECTOR('',#29896,1.); +#29896 = DIRECTION('',(-7.744301232039E-017,-1.)); +#29897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29898 = PCURVE('',#29135,#29899); +#29899 = DEFINITIONAL_REPRESENTATION('',(#29900),#29904); +#29900 = LINE('',#29901,#29902); +#29901 = CARTESIAN_POINT('',(-1.577188900315E-016,-0.2)); +#29902 = VECTOR('',#29903,1.); +#29903 = DIRECTION('',(-1.,0.E+000)); +#29904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29905 = ORIENTED_EDGE('',*,*,#29096,.T.); +#29906 = ORIENTED_EDGE('',*,*,#27892,.F.); +#29907 = ORIENTED_EDGE('',*,*,#29908,.F.); +#29908 = EDGE_CURVE('',#29909,#27865,#29911,.T.); +#29909 = VERTEX_POINT('',#29910); +#29910 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); +#29911 = SURFACE_CURVE('',#29912,(#29916,#29923),.PCURVE_S1.); +#29912 = LINE('',#29913,#29914); +#29913 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); +#29914 = VECTOR('',#29915,1.); +#29915 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#29916 = PCURVE('',#27908,#29917); +#29917 = DEFINITIONAL_REPRESENTATION('',(#29918),#29922); +#29918 = LINE('',#29919,#29920); +#29919 = CARTESIAN_POINT('',(0.15,-0.45)); +#29920 = VECTOR('',#29921,1.); +#29921 = DIRECTION('',(-1.,-9.035018104046E-017)); +#29922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29923 = PCURVE('',#27880,#29924); +#29924 = DEFINITIONAL_REPRESENTATION('',(#29925),#29929); +#29925 = LINE('',#29926,#29927); +#29926 = CARTESIAN_POINT('',(-2.99795049397E-032,-0.2)); +#29927 = VECTOR('',#29928,1.); +#29928 = DIRECTION('',(-1.,0.E+000)); +#29929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29930 = ORIENTED_EDGE('',*,*,#29931,.F.); +#29931 = EDGE_CURVE('',#29932,#29909,#29934,.T.); +#29932 = VERTEX_POINT('',#29933); +#29933 = CARTESIAN_POINT('',(-0.4,0.295,-1.055)); +#29934 = SURFACE_CURVE('',#29935,(#29939,#29946),.PCURVE_S1.); +#29935 = LINE('',#29936,#29937); +#29936 = CARTESIAN_POINT('',(-0.4,0.295,-0.255)); +#29937 = VECTOR('',#29938,1.); +#29938 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#29939 = PCURVE('',#27908,#29940); +#29940 = DEFINITIONAL_REPRESENTATION('',(#29941),#29945); +#29941 = LINE('',#29942,#29943); +#29942 = CARTESIAN_POINT('',(0.15,-0.45)); +#29943 = VECTOR('',#29944,1.); +#29944 = DIRECTION('',(-1.101142831431E-016,1.)); +#29945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29946 = PCURVE('',#29947,#29952); +#29947 = PLANE('',#29948); +#29948 = AXIS2_PLACEMENT_3D('',#29949,#29950,#29951); +#29949 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#29950 = DIRECTION('',(2.361198774698E-029,1.,3.381369077966E-015)); +#29951 = DIRECTION('',(-6.982966722219E-015,3.381369077966E-015,-1.)); +#29952 = DEFINITIONAL_REPRESENTATION('',(#29953),#29957); +#29953 = LINE('',#29954,#29955); +#29954 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); +#29955 = VECTOR('',#29956,1.); +#29956 = DIRECTION('',(-1.,0.E+000)); +#29957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29958 = ORIENTED_EDGE('',*,*,#29959,.F.); +#29959 = EDGE_CURVE('',#29884,#29932,#29960,.T.); +#29960 = SURFACE_CURVE('',#29961,(#29965,#29972),.PCURVE_S1.); +#29961 = LINE('',#29962,#29963); +#29962 = CARTESIAN_POINT('',(-0.4,0.295,-1.055)); +#29963 = VECTOR('',#29964,1.); +#29964 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#29965 = PCURVE('',#27908,#29966); +#29966 = DEFINITIONAL_REPRESENTATION('',(#29967),#29971); +#29967 = LINE('',#29968,#29969); +#29968 = CARTESIAN_POINT('',(0.15,-1.25)); +#29969 = VECTOR('',#29970,1.); +#29970 = DIRECTION('',(1.,-2.710505431214E-015)); +#29971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29972 = PCURVE('',#29973,#29978); +#29973 = PLANE('',#29974); +#29974 = AXIS2_PLACEMENT_3D('',#29975,#29976,#29977); +#29975 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); +#29976 = DIRECTION('',(6.982966722219E-015,-6.201988792323E-015,1.)); +#29977 = DIRECTION('',(4.330828134837E-029,1.,6.201988792323E-015)); +#29978 = DEFINITIONAL_REPRESENTATION('',(#29979),#29983); +#29979 = LINE('',#29980,#29981); +#29980 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); +#29981 = VECTOR('',#29982,1.); +#29982 = DIRECTION('',(-1.,0.E+000)); +#29983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#29984 = ADVANCED_FACE('',(#29985),#27987,.F.); +#29985 = FACE_BOUND('',#29986,.T.); +#29986 = EDGE_LOOP('',(#29987,#29988,#29989,#30010)); +#29987 = ORIENTED_EDGE('',*,*,#27971,.F.); +#29988 = ORIENTED_EDGE('',*,*,#29526,.F.); +#29989 = ORIENTED_EDGE('',*,*,#29990,.T.); +#29990 = EDGE_CURVE('',#29499,#29814,#29991,.T.); +#29991 = SURFACE_CURVE('',#29992,(#29996,#30003),.PCURVE_S1.); +#29992 = LINE('',#29993,#29994); +#29993 = CARTESIAN_POINT('',(0.4,0.295,-0.255)); +#29994 = VECTOR('',#29995,1.); +#29995 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#29996 = PCURVE('',#27987,#29997); +#29997 = DEFINITIONAL_REPRESENTATION('',(#29998),#30002); +#29998 = LINE('',#29999,#30000); +#29999 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30000 = VECTOR('',#30001,1.); +#30001 = DIRECTION('',(-1.642146637881E-047,-1.)); +#30002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30003 = PCURVE('',#29514,#30004); +#30004 = DEFINITIONAL_REPRESENTATION('',(#30005),#30009); +#30005 = LINE('',#30006,#30007); +#30006 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30007 = VECTOR('',#30008,1.); +#30008 = DIRECTION('',(0.E+000,-1.)); +#30009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30010 = ORIENTED_EDGE('',*,*,#29813,.T.); +#30011 = ADVANCED_FACE('',(#30012),#27852,.T.); +#30012 = FACE_BOUND('',#30013,.T.); +#30013 = EDGE_LOOP('',(#30014,#30015,#30038,#30061,#30084,#30105)); +#30014 = ORIENTED_EDGE('',*,*,#29147,.F.); +#30015 = ORIENTED_EDGE('',*,*,#30016,.T.); +#30016 = EDGE_CURVE('',#29120,#30017,#30019,.T.); +#30017 = VERTEX_POINT('',#30018); +#30018 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); +#30019 = SURFACE_CURVE('',#30020,(#30024,#30031),.PCURVE_S1.); +#30020 = LINE('',#30021,#30022); +#30021 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); +#30022 = VECTOR('',#30023,1.); +#30023 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#30024 = PCURVE('',#27852,#30025); +#30025 = DEFINITIONAL_REPRESENTATION('',(#30026),#30030); +#30026 = LINE('',#30027,#30028); +#30027 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#30028 = VECTOR('',#30029,1.); +#30029 = DIRECTION('',(-7.744301232039E-017,-1.)); +#30030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30031 = PCURVE('',#29135,#30032); +#30032 = DEFINITIONAL_REPRESENTATION('',(#30033),#30037); +#30033 = LINE('',#30034,#30035); +#30034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30035 = VECTOR('',#30036,1.); +#30036 = DIRECTION('',(-1.,0.E+000)); +#30037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30038 = ORIENTED_EDGE('',*,*,#30039,.T.); +#30039 = EDGE_CURVE('',#30017,#30040,#30042,.T.); +#30040 = VERTEX_POINT('',#30041); +#30041 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); +#30042 = SURFACE_CURVE('',#30043,(#30047,#30054),.PCURVE_S1.); +#30043 = LINE('',#30044,#30045); +#30044 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); +#30045 = VECTOR('',#30046,1.); +#30046 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#30047 = PCURVE('',#27852,#30048); +#30048 = DEFINITIONAL_REPRESENTATION('',(#30049),#30053); +#30049 = LINE('',#30050,#30051); +#30050 = CARTESIAN_POINT('',(0.15,-1.25)); +#30051 = VECTOR('',#30052,1.); +#30052 = DIRECTION('',(1.,-2.710505431214E-015)); +#30053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30054 = PCURVE('',#29973,#30055); +#30055 = DEFINITIONAL_REPRESENTATION('',(#30056),#30060); +#30056 = LINE('',#30057,#30058); +#30057 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30058 = VECTOR('',#30059,1.); +#30059 = DIRECTION('',(-1.,0.E+000)); +#30060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30061 = ORIENTED_EDGE('',*,*,#30062,.T.); +#30062 = EDGE_CURVE('',#30040,#30063,#30065,.T.); +#30063 = VERTEX_POINT('',#30064); +#30064 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#30065 = SURFACE_CURVE('',#30066,(#30070,#30077),.PCURVE_S1.); +#30066 = LINE('',#30067,#30068); +#30067 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#30068 = VECTOR('',#30069,1.); +#30069 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#30070 = PCURVE('',#27852,#30071); +#30071 = DEFINITIONAL_REPRESENTATION('',(#30072),#30076); +#30072 = LINE('',#30073,#30074); +#30073 = CARTESIAN_POINT('',(0.15,-0.45)); +#30074 = VECTOR('',#30075,1.); +#30075 = DIRECTION('',(-1.101142831431E-016,1.)); +#30076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30077 = PCURVE('',#29947,#30078); +#30078 = DEFINITIONAL_REPRESENTATION('',(#30079),#30083); +#30079 = LINE('',#30080,#30081); +#30080 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30081 = VECTOR('',#30082,1.); +#30082 = DIRECTION('',(-1.,0.E+000)); +#30083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30084 = ORIENTED_EDGE('',*,*,#30085,.T.); +#30085 = EDGE_CURVE('',#30063,#27837,#30086,.T.); +#30086 = SURFACE_CURVE('',#30087,(#30091,#30098),.PCURVE_S1.); +#30087 = LINE('',#30088,#30089); +#30088 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#30089 = VECTOR('',#30090,1.); +#30090 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#30091 = PCURVE('',#27852,#30092); +#30092 = DEFINITIONAL_REPRESENTATION('',(#30093),#30097); +#30093 = LINE('',#30094,#30095); +#30094 = CARTESIAN_POINT('',(0.15,-0.45)); +#30095 = VECTOR('',#30096,1.); +#30096 = DIRECTION('',(-1.,-9.035018104046E-017)); +#30097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30098 = PCURVE('',#27880,#30099); +#30099 = DEFINITIONAL_REPRESENTATION('',(#30100),#30104); +#30100 = LINE('',#30101,#30102); +#30101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30102 = VECTOR('',#30103,1.); +#30103 = DIRECTION('',(-1.,0.E+000)); +#30104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30105 = ORIENTED_EDGE('',*,*,#27836,.T.); +#30106 = ADVANCED_FACE('',(#30107),#27880,.F.); +#30107 = FACE_BOUND('',#30108,.T.); +#30108 = EDGE_LOOP('',(#30109,#30110,#30111,#30132)); +#30109 = ORIENTED_EDGE('',*,*,#27864,.F.); +#30110 = ORIENTED_EDGE('',*,*,#30085,.F.); +#30111 = ORIENTED_EDGE('',*,*,#30112,.T.); +#30112 = EDGE_CURVE('',#30063,#29909,#30113,.T.); +#30113 = SURFACE_CURVE('',#30114,(#30118,#30125),.PCURVE_S1.); +#30114 = LINE('',#30115,#30116); +#30115 = CARTESIAN_POINT('',(-0.6,0.295,-0.255)); +#30116 = VECTOR('',#30117,1.); +#30117 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30118 = PCURVE('',#27880,#30119); +#30119 = DEFINITIONAL_REPRESENTATION('',(#30120),#30124); +#30120 = LINE('',#30121,#30122); +#30121 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30122 = VECTOR('',#30123,1.); +#30123 = DIRECTION('',(-1.642146637881E-047,-1.)); +#30124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30125 = PCURVE('',#29947,#30126); +#30126 = DEFINITIONAL_REPRESENTATION('',(#30127),#30131); +#30127 = LINE('',#30128,#30129); +#30128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30129 = VECTOR('',#30130,1.); +#30130 = DIRECTION('',(0.E+000,-1.)); +#30131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30132 = ORIENTED_EDGE('',*,*,#29908,.T.); +#30133 = ADVANCED_FACE('',(#30134),#27801,.F.); +#30134 = FACE_BOUND('',#30135,.T.); +#30135 = EDGE_LOOP('',(#30136,#30159,#30160,#30161,#30184,#30207)); +#30136 = ORIENTED_EDGE('',*,*,#30137,.F.); +#30137 = EDGE_CURVE('',#29170,#30138,#30140,.T.); +#30138 = VERTEX_POINT('',#30139); +#30139 = CARTESIAN_POINT('',(-1.4,0.495,-1.055)); +#30140 = SURFACE_CURVE('',#30141,(#30145,#30152),.PCURVE_S1.); +#30141 = LINE('',#30142,#30143); +#30142 = CARTESIAN_POINT('',(-1.4,0.495,-1.055)); +#30143 = VECTOR('',#30144,1.); +#30144 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#30145 = PCURVE('',#27801,#30146); +#30146 = DEFINITIONAL_REPRESENTATION('',(#30147),#30151); +#30147 = LINE('',#30148,#30149); +#30148 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#30149 = VECTOR('',#30150,1.); +#30150 = DIRECTION('',(-7.744301232039E-017,-1.)); +#30151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30152 = PCURVE('',#29208,#30153); +#30153 = DEFINITIONAL_REPRESENTATION('',(#30154),#30158); +#30154 = LINE('',#30155,#30156); +#30155 = CARTESIAN_POINT('',(6.432571489356E-017,-0.2)); +#30156 = VECTOR('',#30157,1.); +#30157 = DIRECTION('',(-1.,0.E+000)); +#30158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30159 = ORIENTED_EDGE('',*,*,#29169,.T.); +#30160 = ORIENTED_EDGE('',*,*,#27785,.F.); +#30161 = ORIENTED_EDGE('',*,*,#30162,.F.); +#30162 = EDGE_CURVE('',#30163,#27758,#30165,.T.); +#30163 = VERTEX_POINT('',#30164); +#30164 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); +#30165 = SURFACE_CURVE('',#30166,(#30170,#30177),.PCURVE_S1.); +#30166 = LINE('',#30167,#30168); +#30167 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); +#30168 = VECTOR('',#30169,1.); +#30169 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#30170 = PCURVE('',#27801,#30171); +#30171 = DEFINITIONAL_REPRESENTATION('',(#30172),#30176); +#30172 = LINE('',#30173,#30174); +#30173 = CARTESIAN_POINT('',(0.15,-0.45)); +#30174 = VECTOR('',#30175,1.); +#30175 = DIRECTION('',(-1.,-9.035018104046E-017)); +#30176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30177 = PCURVE('',#27773,#30178); +#30178 = DEFINITIONAL_REPRESENTATION('',(#30179),#30183); +#30179 = LINE('',#30180,#30181); +#30180 = CARTESIAN_POINT('',(-2.997950493971E-032,-0.2)); +#30181 = VECTOR('',#30182,1.); +#30182 = DIRECTION('',(-1.,0.E+000)); +#30183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30184 = ORIENTED_EDGE('',*,*,#30185,.F.); +#30185 = EDGE_CURVE('',#30186,#30163,#30188,.T.); +#30186 = VERTEX_POINT('',#30187); +#30187 = CARTESIAN_POINT('',(-1.4,0.295,-1.055)); +#30188 = SURFACE_CURVE('',#30189,(#30193,#30200),.PCURVE_S1.); +#30189 = LINE('',#30190,#30191); +#30190 = CARTESIAN_POINT('',(-1.4,0.295,-0.255)); +#30191 = VECTOR('',#30192,1.); +#30192 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#30193 = PCURVE('',#27801,#30194); +#30194 = DEFINITIONAL_REPRESENTATION('',(#30195),#30199); +#30195 = LINE('',#30196,#30197); +#30196 = CARTESIAN_POINT('',(0.15,-0.45)); +#30197 = VECTOR('',#30198,1.); +#30198 = DIRECTION('',(-1.101142831431E-016,1.)); +#30199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30200 = PCURVE('',#29751,#30201); +#30201 = DEFINITIONAL_REPRESENTATION('',(#30202),#30206); +#30202 = LINE('',#30203,#30204); +#30203 = CARTESIAN_POINT('',(-8.814563662308E-018,-0.2)); +#30204 = VECTOR('',#30205,1.); +#30205 = DIRECTION('',(-1.,0.E+000)); +#30206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30207 = ORIENTED_EDGE('',*,*,#30208,.F.); +#30208 = EDGE_CURVE('',#30138,#30186,#30209,.T.); +#30209 = SURFACE_CURVE('',#30210,(#30214,#30221),.PCURVE_S1.); +#30210 = LINE('',#30211,#30212); +#30211 = CARTESIAN_POINT('',(-1.4,0.295,-1.055)); +#30212 = VECTOR('',#30213,1.); +#30213 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#30214 = PCURVE('',#27801,#30215); +#30215 = DEFINITIONAL_REPRESENTATION('',(#30216),#30220); +#30216 = LINE('',#30217,#30218); +#30217 = CARTESIAN_POINT('',(0.15,-1.25)); +#30218 = VECTOR('',#30219,1.); +#30219 = DIRECTION('',(1.,-2.710505431214E-015)); +#30220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30221 = PCURVE('',#29723,#30222); +#30222 = DEFINITIONAL_REPRESENTATION('',(#30223),#30227); +#30223 = LINE('',#30224,#30225); +#30224 = CARTESIAN_POINT('',(3.989473628281E-031,-0.2)); +#30225 = VECTOR('',#30226,1.); +#30226 = DIRECTION('',(-1.,0.E+000)); +#30227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30228 = ADVANCED_FACE('',(#30229),#27773,.F.); +#30229 = FACE_BOUND('',#30230,.T.); +#30230 = EDGE_LOOP('',(#30231,#30232,#30233,#30254)); +#30231 = ORIENTED_EDGE('',*,*,#27757,.F.); +#30232 = ORIENTED_EDGE('',*,*,#29763,.F.); +#30233 = ORIENTED_EDGE('',*,*,#30234,.T.); +#30234 = EDGE_CURVE('',#29736,#30163,#30235,.T.); +#30235 = SURFACE_CURVE('',#30236,(#30240,#30247),.PCURVE_S1.); +#30236 = LINE('',#30237,#30238); +#30237 = CARTESIAN_POINT('',(-1.6,0.295,-0.255)); +#30238 = VECTOR('',#30239,1.); +#30239 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30240 = PCURVE('',#27773,#30241); +#30241 = DEFINITIONAL_REPRESENTATION('',(#30242),#30246); +#30242 = LINE('',#30243,#30244); +#30243 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30244 = VECTOR('',#30245,1.); +#30245 = DIRECTION('',(-1.642146637881E-047,-1.)); +#30246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30247 = PCURVE('',#29751,#30248); +#30248 = DEFINITIONAL_REPRESENTATION('',(#30249),#30253); +#30249 = LINE('',#30250,#30251); +#30250 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30251 = VECTOR('',#30252,1.); +#30252 = DIRECTION('',(0.E+000,-1.)); +#30253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30254 = ORIENTED_EDGE('',*,*,#30162,.T.); +#30255 = ADVANCED_FACE('',(#30256),#27473,.T.); +#30256 = FACE_BOUND('',#30257,.T.); +#30257 = EDGE_LOOP('',(#30258,#30259,#30282,#30305,#30328,#30349)); +#30258 = ORIENTED_EDGE('',*,*,#29001,.F.); +#30259 = ORIENTED_EDGE('',*,*,#30260,.T.); +#30260 = EDGE_CURVE('',#28972,#30261,#30263,.T.); +#30261 = VERTEX_POINT('',#30262); +#30262 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); +#30263 = SURFACE_CURVE('',#30264,(#30268,#30275),.PCURVE_S1.); +#30264 = LINE('',#30265,#30266); +#30265 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); +#30266 = VECTOR('',#30267,1.); +#30267 = DIRECTION('',(-6.982966722219E-015,3.56892637343E-015,-1.)); +#30268 = PCURVE('',#27473,#30269); +#30269 = DEFINITIONAL_REPRESENTATION('',(#30270),#30274); +#30270 = LINE('',#30271,#30272); +#30271 = CARTESIAN_POINT('',(-5.E-002,-1.25)); +#30272 = VECTOR('',#30273,1.); +#30273 = DIRECTION('',(-7.744301232039E-017,-1.)); +#30274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30275 = PCURVE('',#28989,#30276); +#30276 = DEFINITIONAL_REPRESENTATION('',(#30277),#30281); +#30277 = LINE('',#30278,#30279); +#30278 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30279 = VECTOR('',#30280,1.); +#30280 = DIRECTION('',(-1.,0.E+000)); +#30281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30282 = ORIENTED_EDGE('',*,*,#30283,.T.); +#30283 = EDGE_CURVE('',#30261,#30284,#30286,.T.); +#30284 = VERTEX_POINT('',#30285); +#30285 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); +#30286 = SURFACE_CURVE('',#30287,(#30291,#30298),.PCURVE_S1.); +#30287 = LINE('',#30288,#30289); +#30288 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); +#30289 = VECTOR('',#30290,1.); +#30290 = DIRECTION('',(-4.330828134837E-029,-1.,-6.201988792323E-015)); +#30291 = PCURVE('',#27473,#30292); +#30292 = DEFINITIONAL_REPRESENTATION('',(#30293),#30297); +#30293 = LINE('',#30294,#30295); +#30294 = CARTESIAN_POINT('',(0.15,-1.25)); +#30295 = VECTOR('',#30296,1.); +#30296 = DIRECTION('',(1.,-2.710505431214E-015)); +#30297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30298 = PCURVE('',#29641,#30299); +#30299 = DEFINITIONAL_REPRESENTATION('',(#30300),#30304); +#30300 = LINE('',#30301,#30302); +#30301 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30302 = VECTOR('',#30303,1.); +#30303 = DIRECTION('',(-1.,0.E+000)); +#30304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30305 = ORIENTED_EDGE('',*,*,#30306,.T.); +#30306 = EDGE_CURVE('',#30284,#30307,#30309,.T.); +#30307 = VERTEX_POINT('',#30308); +#30308 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#30309 = SURFACE_CURVE('',#30310,(#30314,#30321),.PCURVE_S1.); +#30310 = LINE('',#30311,#30312); +#30311 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#30312 = VECTOR('',#30313,1.); +#30313 = DIRECTION('',(6.982966722219E-015,-3.381369077966E-015,1.)); +#30314 = PCURVE('',#27473,#30315); +#30315 = DEFINITIONAL_REPRESENTATION('',(#30316),#30320); +#30316 = LINE('',#30317,#30318); +#30317 = CARTESIAN_POINT('',(0.15,-0.45)); +#30318 = VECTOR('',#30319,1.); +#30319 = DIRECTION('',(-1.101142831431E-016,1.)); +#30320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30321 = PCURVE('',#29615,#30322); +#30322 = DEFINITIONAL_REPRESENTATION('',(#30323),#30327); +#30323 = LINE('',#30324,#30325); +#30324 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30325 = VECTOR('',#30326,1.); +#30326 = DIRECTION('',(-1.,0.E+000)); +#30327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30328 = ORIENTED_EDGE('',*,*,#30329,.T.); +#30329 = EDGE_CURVE('',#30307,#27456,#30330,.T.); +#30330 = SURFACE_CURVE('',#30331,(#30335,#30342),.PCURVE_S1.); +#30331 = LINE('',#30332,#30333); +#30332 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#30333 = VECTOR('',#30334,1.); +#30334 = DIRECTION('',(2.374999981426E-029,1.,3.401133180069E-015)); +#30335 = PCURVE('',#27473,#30336); +#30336 = DEFINITIONAL_REPRESENTATION('',(#30337),#30341); +#30337 = LINE('',#30338,#30339); +#30338 = CARTESIAN_POINT('',(0.15,-0.45)); +#30339 = VECTOR('',#30340,1.); +#30340 = DIRECTION('',(-1.,-9.035018104046E-017)); +#30341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30342 = PCURVE('',#27501,#30343); +#30343 = DEFINITIONAL_REPRESENTATION('',(#30344),#30348); +#30344 = LINE('',#30345,#30346); +#30345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30346 = VECTOR('',#30347,1.); +#30347 = DIRECTION('',(-1.,0.E+000)); +#30348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30349 = ORIENTED_EDGE('',*,*,#27455,.T.); +#30350 = ADVANCED_FACE('',(#30351),#27501,.F.); +#30351 = FACE_BOUND('',#30352,.T.); +#30352 = EDGE_LOOP('',(#30353,#30354,#30355,#30376)); +#30353 = ORIENTED_EDGE('',*,*,#27485,.F.); +#30354 = ORIENTED_EDGE('',*,*,#30329,.F.); +#30355 = ORIENTED_EDGE('',*,*,#30356,.T.); +#30356 = EDGE_CURVE('',#30307,#29577,#30357,.T.); +#30357 = SURFACE_CURVE('',#30358,(#30362,#30369),.PCURVE_S1.); +#30358 = LINE('',#30359,#30360); +#30359 = CARTESIAN_POINT('',(1.4,0.295,-0.255)); +#30360 = VECTOR('',#30361,1.); +#30361 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30362 = PCURVE('',#27501,#30363); +#30363 = DEFINITIONAL_REPRESENTATION('',(#30364),#30368); +#30364 = LINE('',#30365,#30366); +#30365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30366 = VECTOR('',#30367,1.); +#30367 = DIRECTION('',(-1.642146637881E-047,-1.)); +#30368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30369 = PCURVE('',#29615,#30370); +#30370 = DEFINITIONAL_REPRESENTATION('',(#30371),#30375); +#30371 = LINE('',#30372,#30373); +#30372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30373 = VECTOR('',#30374,1.); +#30374 = DIRECTION('',(0.E+000,-1.)); +#30375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30376 = ORIENTED_EDGE('',*,*,#29576,.T.); +#30377 = ADVANCED_FACE('',(#30378),#28118,.F.); +#30378 = FACE_BOUND('',#30379,.T.); +#30379 = EDGE_LOOP('',(#30380,#30381,#30382,#30403)); +#30380 = ORIENTED_EDGE('',*,*,#28758,.F.); +#30381 = ORIENTED_EDGE('',*,*,#28100,.F.); +#30382 = ORIENTED_EDGE('',*,*,#30383,.T.); +#30383 = EDGE_CURVE('',#28101,#28602,#30384,.T.); +#30384 = SURFACE_CURVE('',#30385,(#30389,#30396),.PCURVE_S1.); +#30385 = LINE('',#30386,#30387); +#30386 = CARTESIAN_POINT('',(2.5,0.905,3.395)); +#30387 = VECTOR('',#30388,1.); +#30388 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30389 = PCURVE('',#28118,#30390); +#30390 = DEFINITIONAL_REPRESENTATION('',(#30391),#30395); +#30391 = LINE('',#30392,#30393); +#30392 = CARTESIAN_POINT('',(0.65,-1.55053008704E-029)); +#30393 = VECTOR('',#30394,1.); +#30394 = DIRECTION('',(-2.80259692865E-045,-1.)); +#30395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30396 = PCURVE('',#28211,#30397); +#30397 = DEFINITIONAL_REPRESENTATION('',(#30398),#30402); +#30398 = LINE('',#30399,#30400); +#30399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30400 = VECTOR('',#30401,1.); +#30401 = DIRECTION('',(0.E+000,-1.)); +#30402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30403 = ORIENTED_EDGE('',*,*,#28601,.T.); +#30404 = ADVANCED_FACE('',(#30405),#28211,.F.); +#30405 = FACE_BOUND('',#30406,.T.); +#30406 = EDGE_LOOP('',(#30407,#30408,#30409,#30410)); +#30407 = ORIENTED_EDGE('',*,*,#30383,.F.); +#30408 = ORIENTED_EDGE('',*,*,#28197,.F.); +#30409 = ORIENTED_EDGE('',*,*,#29656,.T.); +#30410 = ORIENTED_EDGE('',*,*,#28624,.T.); +#30411 = ADVANCED_FACE('',(#30412),#28434,.F.); +#30412 = FACE_BOUND('',#30413,.T.); +#30413 = EDGE_LOOP('',(#30414,#30439,#30462,#30483,#30484,#30485)); +#30414 = ORIENTED_EDGE('',*,*,#30415,.T.); +#30415 = EDGE_CURVE('',#30416,#30418,#30420,.T.); +#30416 = VERTEX_POINT('',#30417); +#30417 = CARTESIAN_POINT('',(2.5,2.755,0.845)); +#30418 = VERTEX_POINT('',#30419); +#30419 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#30420 = SURFACE_CURVE('',#30421,(#30425,#30432),.PCURVE_S1.); +#30421 = LINE('',#30422,#30423); +#30422 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#30423 = VECTOR('',#30424,1.); +#30424 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#30425 = PCURVE('',#28434,#30426); +#30426 = DEFINITIONAL_REPRESENTATION('',(#30427),#30431); +#30427 = LINE('',#30428,#30429); +#30428 = CARTESIAN_POINT('',(-1.439590092099E-016,0.55)); +#30429 = VECTOR('',#30430,1.); +#30430 = DIRECTION('',(1.702510980039E-043,-1.)); +#30431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30432 = PCURVE('',#28543,#30433); +#30433 = DEFINITIONAL_REPRESENTATION('',(#30434),#30438); +#30434 = LINE('',#30435,#30436); +#30435 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30436 = VECTOR('',#30437,1.); +#30437 = DIRECTION('',(0.E+000,-1.)); +#30438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30439 = ORIENTED_EDGE('',*,*,#30440,.T.); +#30440 = EDGE_CURVE('',#30418,#30441,#30443,.T.); +#30441 = VERTEX_POINT('',#30442); +#30442 = CARTESIAN_POINT('',(2.5,1.755,0.195)); +#30443 = SURFACE_CURVE('',#30444,(#30448,#30455),.PCURVE_S1.); +#30444 = LINE('',#30445,#30446); +#30445 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#30446 = VECTOR('',#30447,1.); +#30447 = DIRECTION('',(-2.513800689087E-029,-1.,-3.599903578358E-015)); +#30448 = PCURVE('',#28434,#30449); +#30449 = DEFINITIONAL_REPRESENTATION('',(#30450),#30454); +#30450 = LINE('',#30451,#30452); +#30451 = CARTESIAN_POINT('',(-1.439590092099E-016,0.55)); +#30452 = VECTOR('',#30453,1.); +#30453 = DIRECTION('',(1.,-1.084202172486E-016)); +#30454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30455 = PCURVE('',#28734,#30456); +#30456 = DEFINITIONAL_REPRESENTATION('',(#30457),#30461); +#30457 = LINE('',#30458,#30459); +#30458 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30459 = VECTOR('',#30460,1.); +#30460 = DIRECTION('',(-1.,0.E+000)); +#30461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30462 = ORIENTED_EDGE('',*,*,#30463,.T.); +#30463 = EDGE_CURVE('',#30441,#29289,#30464,.T.); +#30464 = SURFACE_CURVE('',#30465,(#30469,#30476),.PCURVE_S1.); +#30465 = LINE('',#30466,#30467); +#30466 = CARTESIAN_POINT('',(2.5,1.755,0.195)); +#30467 = VECTOR('',#30468,1.); +#30468 = DIRECTION('',(-6.982966722219E-015,3.491483361109E-015,-1.)); +#30469 = PCURVE('',#28434,#30470); +#30470 = DEFINITIONAL_REPRESENTATION('',(#30471),#30475); +#30471 = LINE('',#30472,#30473); +#30472 = CARTESIAN_POINT('',(1.,0.55)); +#30473 = VECTOR('',#30474,1.); +#30474 = DIRECTION('',(1.702510980039E-043,-1.)); +#30475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30476 = PCURVE('',#28708,#30477); +#30477 = DEFINITIONAL_REPRESENTATION('',(#30478),#30482); +#30478 = LINE('',#30479,#30480); +#30479 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30480 = VECTOR('',#30481,1.); +#30481 = DIRECTION('',(0.E+000,-1.)); +#30482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30483 = ORIENTED_EDGE('',*,*,#29288,.T.); +#30484 = ORIENTED_EDGE('',*,*,#28418,.T.); +#30485 = ORIENTED_EDGE('',*,*,#30486,.T.); +#30486 = EDGE_CURVE('',#28391,#30416,#30487,.T.); +#30487 = SURFACE_CURVE('',#30488,(#30492,#30499),.PCURVE_S1.); +#30488 = LINE('',#30489,#30490); +#30489 = CARTESIAN_POINT('',(2.5,2.755,0.845)); +#30490 = VECTOR('',#30491,1.); +#30491 = DIRECTION('',(-3.491483361109E-015,-0.866025403784,-0.5)); +#30492 = PCURVE('',#28434,#30493); +#30493 = DEFINITIONAL_REPRESENTATION('',(#30494),#30498); +#30494 = LINE('',#30495,#30496); +#30495 = CARTESIAN_POINT('',(2.511120651694E-016,1.2)); +#30496 = VECTOR('',#30497,1.); +#30497 = DIRECTION('',(0.866025403784,-0.5)); +#30498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30499 = PCURVE('',#28406,#30500); +#30500 = DEFINITIONAL_REPRESENTATION('',(#30501),#30505); +#30501 = LINE('',#30502,#30503); +#30502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30503 = VECTOR('',#30504,1.); +#30504 = DIRECTION('',(-1.,1.961367055364E-030)); +#30505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30506 = ADVANCED_FACE('',(#30507),#28483,.F.); +#30507 = FACE_BOUND('',#30508,.T.); +#30508 = EDGE_LOOP('',(#30509,#30510,#30511,#30512,#30513,#30514)); +#30509 = ORIENTED_EDGE('',*,*,#28919,.F.); +#30510 = ORIENTED_EDGE('',*,*,#28946,.F.); +#30511 = ORIENTED_EDGE('',*,*,#28469,.F.); +#30512 = ORIENTED_EDGE('',*,*,#29266,.F.); +#30513 = ORIENTED_EDGE('',*,*,#29407,.F.); +#30514 = ORIENTED_EDGE('',*,*,#28848,.F.); +#30515 = ADVANCED_FACE('',(#30516),#28406,.F.); +#30516 = FACE_BOUND('',#30517,.T.); +#30517 = EDGE_LOOP('',(#30518,#30519,#30540,#30541)); +#30518 = ORIENTED_EDGE('',*,*,#28555,.T.); +#30519 = ORIENTED_EDGE('',*,*,#30520,.F.); +#30520 = EDGE_CURVE('',#30416,#28526,#30521,.T.); +#30521 = SURFACE_CURVE('',#30522,(#30526,#30533),.PCURVE_S1.); +#30522 = LINE('',#30523,#30524); +#30523 = CARTESIAN_POINT('',(2.5,2.755,0.845)); +#30524 = VECTOR('',#30525,1.); +#30525 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30526 = PCURVE('',#28406,#30527); +#30527 = DEFINITIONAL_REPRESENTATION('',(#30528),#30532); +#30528 = LINE('',#30529,#30530); +#30529 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30530 = VECTOR('',#30531,1.); +#30531 = DIRECTION('',(-1.228743304519E-031,-1.)); +#30532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30533 = PCURVE('',#28543,#30534); +#30534 = DEFINITIONAL_REPRESENTATION('',(#30535),#30539); +#30535 = LINE('',#30536,#30537); +#30536 = CARTESIAN_POINT('',(-5.421254807916E-016,0.65)); +#30537 = VECTOR('',#30538,1.); +#30538 = DIRECTION('',(1.,0.E+000)); +#30539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30540 = ORIENTED_EDGE('',*,*,#30486,.F.); +#30541 = ORIENTED_EDGE('',*,*,#28390,.T.); +#30542 = ADVANCED_FACE('',(#30543),#28708,.F.); +#30543 = FACE_BOUND('',#30544,.T.); +#30544 = EDGE_LOOP('',(#30545,#30546,#30547,#30548)); +#30545 = ORIENTED_EDGE('',*,*,#28692,.T.); +#30546 = ORIENTED_EDGE('',*,*,#29311,.F.); +#30547 = ORIENTED_EDGE('',*,*,#30463,.F.); +#30548 = ORIENTED_EDGE('',*,*,#30549,.T.); +#30549 = EDGE_CURVE('',#30441,#28693,#30550,.T.); +#30550 = SURFACE_CURVE('',#30551,(#30555,#30562),.PCURVE_S1.); +#30551 = LINE('',#30552,#30553); +#30552 = CARTESIAN_POINT('',(2.5,1.755,0.195)); +#30553 = VECTOR('',#30554,1.); +#30554 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30555 = PCURVE('',#28708,#30556); +#30556 = DEFINITIONAL_REPRESENTATION('',(#30557),#30561); +#30557 = LINE('',#30558,#30559); +#30558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30559 = VECTOR('',#30560,1.); +#30560 = DIRECTION('',(1.,0.E+000)); +#30561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30562 = PCURVE('',#28734,#30563); +#30563 = DEFINITIONAL_REPRESENTATION('',(#30564),#30568); +#30564 = LINE('',#30565,#30566); +#30565 = CARTESIAN_POINT('',(-1.,-2.51961139144E-029)); +#30566 = VECTOR('',#30567,1.); +#30567 = DIRECTION('',(2.80259692865E-045,-1.)); +#30568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30569 = ADVANCED_FACE('',(#30570),#28734,.F.); +#30570 = FACE_BOUND('',#30571,.T.); +#30571 = EDGE_LOOP('',(#30572,#30573,#30574,#30575)); +#30572 = ORIENTED_EDGE('',*,*,#28720,.T.); +#30573 = ORIENTED_EDGE('',*,*,#30549,.F.); +#30574 = ORIENTED_EDGE('',*,*,#30440,.F.); +#30575 = ORIENTED_EDGE('',*,*,#30576,.T.); +#30576 = EDGE_CURVE('',#30418,#28528,#30577,.T.); +#30577 = SURFACE_CURVE('',#30578,(#30582,#30589),.PCURVE_S1.); +#30578 = LINE('',#30579,#30580); +#30579 = CARTESIAN_POINT('',(2.5,2.755,0.195)); +#30580 = VECTOR('',#30581,1.); +#30581 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30582 = PCURVE('',#28734,#30583); +#30583 = DEFINITIONAL_REPRESENTATION('',(#30584),#30588); +#30584 = LINE('',#30585,#30586); +#30585 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30586 = VECTOR('',#30587,1.); +#30587 = DIRECTION('',(2.80259692865E-045,-1.)); +#30588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30589 = PCURVE('',#28543,#30590); +#30590 = DEFINITIONAL_REPRESENTATION('',(#30591),#30595); +#30591 = LINE('',#30592,#30593); +#30592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30593 = VECTOR('',#30594,1.); +#30594 = DIRECTION('',(1.,0.E+000)); +#30595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30596 = ADVANCED_FACE('',(#30597),#28543,.F.); +#30597 = FACE_BOUND('',#30598,.T.); +#30598 = EDGE_LOOP('',(#30599,#30600,#30601,#30602)); +#30599 = ORIENTED_EDGE('',*,*,#28525,.T.); +#30600 = ORIENTED_EDGE('',*,*,#30576,.F.); +#30601 = ORIENTED_EDGE('',*,*,#30415,.F.); +#30602 = ORIENTED_EDGE('',*,*,#30520,.T.); +#30603 = ADVANCED_FACE('',(#30604),#29208,.F.); +#30604 = FACE_BOUND('',#30605,.T.); +#30605 = EDGE_LOOP('',(#30606,#30607,#30628,#30629)); +#30606 = ORIENTED_EDGE('',*,*,#30137,.T.); +#30607 = ORIENTED_EDGE('',*,*,#30608,.F.); +#30608 = EDGE_CURVE('',#29685,#30138,#30609,.T.); +#30609 = SURFACE_CURVE('',#30610,(#30614,#30621),.PCURVE_S1.); +#30610 = LINE('',#30611,#30612); +#30611 = CARTESIAN_POINT('',(-1.6,0.495,-1.055)); +#30612 = VECTOR('',#30613,1.); +#30613 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30614 = PCURVE('',#29208,#30615); +#30615 = DEFINITIONAL_REPRESENTATION('',(#30616),#30620); +#30616 = LINE('',#30617,#30618); +#30617 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30618 = VECTOR('',#30619,1.); +#30619 = DIRECTION('',(0.E+000,-1.)); +#30620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30621 = PCURVE('',#29723,#30622); +#30622 = DEFINITIONAL_REPRESENTATION('',(#30623),#30627); +#30623 = LINE('',#30624,#30625); +#30624 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); +#30625 = VECTOR('',#30626,1.); +#30626 = DIRECTION('',(5.315081284607E-045,-1.)); +#30627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30628 = ORIENTED_EDGE('',*,*,#29684,.F.); +#30629 = ORIENTED_EDGE('',*,*,#29192,.T.); +#30630 = ADVANCED_FACE('',(#30631),#29062,.F.); +#30631 = FACE_BOUND('',#30632,.T.); +#30632 = EDGE_LOOP('',(#30633,#30634,#30655,#30656)); +#30633 = ORIENTED_EDGE('',*,*,#29788,.T.); +#30634 = ORIENTED_EDGE('',*,*,#30635,.F.); +#30635 = EDGE_CURVE('',#29448,#29789,#30636,.T.); +#30636 = SURFACE_CURVE('',#30637,(#30641,#30648),.PCURVE_S1.); +#30637 = LINE('',#30638,#30639); +#30638 = CARTESIAN_POINT('',(0.4,0.495,-1.055)); +#30639 = VECTOR('',#30640,1.); +#30640 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30641 = PCURVE('',#29062,#30642); +#30642 = DEFINITIONAL_REPRESENTATION('',(#30643),#30647); +#30643 = LINE('',#30644,#30645); +#30644 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30645 = VECTOR('',#30646,1.); +#30646 = DIRECTION('',(0.E+000,-1.)); +#30647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30648 = PCURVE('',#29486,#30649); +#30649 = DEFINITIONAL_REPRESENTATION('',(#30650),#30654); +#30650 = LINE('',#30651,#30652); +#30651 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); +#30652 = VECTOR('',#30653,1.); +#30653 = DIRECTION('',(5.315081284607E-045,-1.)); +#30654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30655 = ORIENTED_EDGE('',*,*,#29447,.F.); +#30656 = ORIENTED_EDGE('',*,*,#29046,.T.); +#30657 = ADVANCED_FACE('',(#30658),#29135,.F.); +#30658 = FACE_BOUND('',#30659,.T.); +#30659 = EDGE_LOOP('',(#30660,#30661,#30682,#30683)); +#30660 = ORIENTED_EDGE('',*,*,#29883,.T.); +#30661 = ORIENTED_EDGE('',*,*,#30662,.F.); +#30662 = EDGE_CURVE('',#30017,#29884,#30663,.T.); +#30663 = SURFACE_CURVE('',#30664,(#30668,#30675),.PCURVE_S1.); +#30664 = LINE('',#30665,#30666); +#30665 = CARTESIAN_POINT('',(-0.6,0.495,-1.055)); +#30666 = VECTOR('',#30667,1.); +#30667 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30668 = PCURVE('',#29135,#30669); +#30669 = DEFINITIONAL_REPRESENTATION('',(#30670),#30674); +#30670 = LINE('',#30671,#30672); +#30671 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30672 = VECTOR('',#30673,1.); +#30673 = DIRECTION('',(0.E+000,-1.)); +#30674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30675 = PCURVE('',#29973,#30676); +#30676 = DEFINITIONAL_REPRESENTATION('',(#30677),#30681); +#30677 = LINE('',#30678,#30679); +#30678 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); +#30679 = VECTOR('',#30680,1.); +#30680 = DIRECTION('',(5.315081284607E-045,-1.)); +#30681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30682 = ORIENTED_EDGE('',*,*,#30016,.F.); +#30683 = ORIENTED_EDGE('',*,*,#29119,.T.); +#30684 = ADVANCED_FACE('',(#30685),#28989,.F.); +#30685 = FACE_BOUND('',#30686,.T.); +#30686 = EDGE_LOOP('',(#30687,#30688,#30709,#30710)); +#30687 = ORIENTED_EDGE('',*,*,#29551,.T.); +#30688 = ORIENTED_EDGE('',*,*,#30689,.F.); +#30689 = EDGE_CURVE('',#30261,#29552,#30690,.T.); +#30690 = SURFACE_CURVE('',#30691,(#30695,#30702),.PCURVE_S1.); +#30691 = LINE('',#30692,#30693); +#30692 = CARTESIAN_POINT('',(1.4,0.495,-1.055)); +#30693 = VECTOR('',#30694,1.); +#30694 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30695 = PCURVE('',#28989,#30696); +#30696 = DEFINITIONAL_REPRESENTATION('',(#30697),#30701); +#30697 = LINE('',#30698,#30699); +#30698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30699 = VECTOR('',#30700,1.); +#30700 = DIRECTION('',(0.E+000,-1.)); +#30701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30702 = PCURVE('',#29641,#30703); +#30703 = DEFINITIONAL_REPRESENTATION('',(#30704),#30708); +#30704 = LINE('',#30705,#30706); +#30705 = CARTESIAN_POINT('',(0.2,9.303180522238E-030)); +#30706 = VECTOR('',#30707,1.); +#30707 = DIRECTION('',(5.315081284607E-045,-1.)); +#30708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30709 = ORIENTED_EDGE('',*,*,#30260,.F.); +#30710 = ORIENTED_EDGE('',*,*,#28971,.T.); +#30711 = ADVANCED_FACE('',(#30712),#29514,.F.); +#30712 = FACE_BOUND('',#30713,.T.); +#30713 = EDGE_LOOP('',(#30714,#30715,#30716,#30717)); +#30714 = ORIENTED_EDGE('',*,*,#29836,.T.); +#30715 = ORIENTED_EDGE('',*,*,#29990,.F.); +#30716 = ORIENTED_EDGE('',*,*,#29498,.F.); +#30717 = ORIENTED_EDGE('',*,*,#30718,.T.); +#30718 = EDGE_CURVE('',#29471,#29837,#30719,.T.); +#30719 = SURFACE_CURVE('',#30720,(#30724,#30731),.PCURVE_S1.); +#30720 = LINE('',#30721,#30722); +#30721 = CARTESIAN_POINT('',(0.4,0.295,-1.055)); +#30722 = VECTOR('',#30723,1.); +#30723 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30724 = PCURVE('',#29514,#30725); +#30725 = DEFINITIONAL_REPRESENTATION('',(#30726),#30730); +#30726 = LINE('',#30727,#30728); +#30727 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); +#30728 = VECTOR('',#30729,1.); +#30729 = DIRECTION('',(0.E+000,-1.)); +#30730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30731 = PCURVE('',#29486,#30732); +#30732 = DEFINITIONAL_REPRESENTATION('',(#30733),#30737); +#30733 = LINE('',#30734,#30735); +#30734 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30735 = VECTOR('',#30736,1.); +#30736 = DIRECTION('',(5.315081284607E-045,-1.)); +#30737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30738 = ADVANCED_FACE('',(#30739),#29486,.F.); +#30739 = FACE_BOUND('',#30740,.T.); +#30740 = EDGE_LOOP('',(#30741,#30742,#30743,#30744)); +#30741 = ORIENTED_EDGE('',*,*,#29859,.T.); +#30742 = ORIENTED_EDGE('',*,*,#30718,.F.); +#30743 = ORIENTED_EDGE('',*,*,#29470,.F.); +#30744 = ORIENTED_EDGE('',*,*,#30635,.T.); +#30745 = ADVANCED_FACE('',(#30746),#29615,.F.); +#30746 = FACE_BOUND('',#30747,.T.); +#30747 = EDGE_LOOP('',(#30748,#30749,#30750,#30751)); +#30748 = ORIENTED_EDGE('',*,*,#29599,.T.); +#30749 = ORIENTED_EDGE('',*,*,#30356,.F.); +#30750 = ORIENTED_EDGE('',*,*,#30306,.F.); +#30751 = ORIENTED_EDGE('',*,*,#30752,.T.); +#30752 = EDGE_CURVE('',#30284,#29600,#30753,.T.); +#30753 = SURFACE_CURVE('',#30754,(#30758,#30765),.PCURVE_S1.); +#30754 = LINE('',#30755,#30756); +#30755 = CARTESIAN_POINT('',(1.4,0.295,-1.055)); +#30756 = VECTOR('',#30757,1.); +#30757 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30758 = PCURVE('',#29615,#30759); +#30759 = DEFINITIONAL_REPRESENTATION('',(#30760),#30764); +#30760 = LINE('',#30761,#30762); +#30761 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); +#30762 = VECTOR('',#30763,1.); +#30763 = DIRECTION('',(0.E+000,-1.)); +#30764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30765 = PCURVE('',#29641,#30766); +#30766 = DEFINITIONAL_REPRESENTATION('',(#30767),#30771); +#30767 = LINE('',#30768,#30769); +#30768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30769 = VECTOR('',#30770,1.); +#30770 = DIRECTION('',(5.315081284607E-045,-1.)); +#30771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30772 = ADVANCED_FACE('',(#30773),#29641,.F.); +#30773 = FACE_BOUND('',#30774,.T.); +#30774 = EDGE_LOOP('',(#30775,#30776,#30777,#30778)); +#30775 = ORIENTED_EDGE('',*,*,#29627,.T.); +#30776 = ORIENTED_EDGE('',*,*,#30752,.F.); +#30777 = ORIENTED_EDGE('',*,*,#30283,.F.); +#30778 = ORIENTED_EDGE('',*,*,#30689,.T.); +#30779 = ADVANCED_FACE('',(#30780),#29723,.F.); +#30780 = FACE_BOUND('',#30781,.T.); +#30781 = EDGE_LOOP('',(#30782,#30783,#30804,#30805)); +#30782 = ORIENTED_EDGE('',*,*,#30208,.T.); +#30783 = ORIENTED_EDGE('',*,*,#30784,.F.); +#30784 = EDGE_CURVE('',#29708,#30186,#30785,.T.); +#30785 = SURFACE_CURVE('',#30786,(#30790,#30797),.PCURVE_S1.); +#30786 = LINE('',#30787,#30788); +#30787 = CARTESIAN_POINT('',(-1.6,0.295,-1.055)); +#30788 = VECTOR('',#30789,1.); +#30789 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30790 = PCURVE('',#29723,#30791); +#30791 = DEFINITIONAL_REPRESENTATION('',(#30792),#30796); +#30792 = LINE('',#30793,#30794); +#30793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30794 = VECTOR('',#30795,1.); +#30795 = DIRECTION('',(5.315081284607E-045,-1.)); +#30796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30797 = PCURVE('',#29751,#30798); +#30798 = DEFINITIONAL_REPRESENTATION('',(#30799),#30803); +#30799 = LINE('',#30800,#30801); +#30800 = CARTESIAN_POINT('',(0.8,-3.525825464923E-017)); +#30801 = VECTOR('',#30802,1.); +#30802 = DIRECTION('',(0.E+000,-1.)); +#30803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30804 = ORIENTED_EDGE('',*,*,#29707,.F.); +#30805 = ORIENTED_EDGE('',*,*,#30608,.T.); +#30806 = ADVANCED_FACE('',(#30807),#29751,.F.); +#30807 = FACE_BOUND('',#30808,.T.); +#30808 = EDGE_LOOP('',(#30809,#30810,#30811,#30812)); +#30809 = ORIENTED_EDGE('',*,*,#30185,.T.); +#30810 = ORIENTED_EDGE('',*,*,#30234,.F.); +#30811 = ORIENTED_EDGE('',*,*,#29735,.F.); +#30812 = ORIENTED_EDGE('',*,*,#30784,.T.); +#30813 = ADVANCED_FACE('',(#30814),#29947,.F.); +#30814 = FACE_BOUND('',#30815,.T.); +#30815 = EDGE_LOOP('',(#30816,#30817,#30818,#30819)); +#30816 = ORIENTED_EDGE('',*,*,#29931,.T.); +#30817 = ORIENTED_EDGE('',*,*,#30112,.F.); +#30818 = ORIENTED_EDGE('',*,*,#30062,.F.); +#30819 = ORIENTED_EDGE('',*,*,#30820,.T.); +#30820 = EDGE_CURVE('',#30040,#29932,#30821,.T.); +#30821 = SURFACE_CURVE('',#30822,(#30826,#30833),.PCURVE_S1.); +#30822 = LINE('',#30823,#30824); +#30823 = CARTESIAN_POINT('',(-0.6,0.295,-1.055)); +#30824 = VECTOR('',#30825,1.); +#30825 = DIRECTION('',(1.,0.E+000,-6.982966722219E-015)); +#30826 = PCURVE('',#29947,#30827); +#30827 = DEFINITIONAL_REPRESENTATION('',(#30828),#30832); +#30828 = LINE('',#30829,#30830); +#30829 = CARTESIAN_POINT('',(0.8,-1.462805571117E-016)); +#30830 = VECTOR('',#30831,1.); +#30831 = DIRECTION('',(0.E+000,-1.)); +#30832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30833 = PCURVE('',#29973,#30834); +#30834 = DEFINITIONAL_REPRESENTATION('',(#30835),#30839); +#30835 = LINE('',#30836,#30837); +#30836 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#30837 = VECTOR('',#30838,1.); +#30838 = DIRECTION('',(5.315081284607E-045,-1.)); +#30839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#30840 = ADVANCED_FACE('',(#30841),#29973,.F.); +#30841 = FACE_BOUND('',#30842,.T.); +#30842 = EDGE_LOOP('',(#30843,#30844,#30845,#30846)); +#30843 = ORIENTED_EDGE('',*,*,#29959,.T.); +#30844 = ORIENTED_EDGE('',*,*,#30820,.F.); +#30845 = ORIENTED_EDGE('',*,*,#30039,.F.); +#30846 = ORIENTED_EDGE('',*,*,#30662,.T.); +#30847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30851)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30848,#30849,#30850)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28456 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28457 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28458 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28459 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#28456, +#30848 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30849 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30850 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30851 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#30848, 'distance_accuracy_value','confusion accuracy'); -#28460 = SHAPE_DEFINITION_REPRESENTATION(#28461,#22038); -#28461 = PRODUCT_DEFINITION_SHAPE('','',#28462); -#28462 = PRODUCT_DEFINITION('design','',#28463,#28466); -#28463 = PRODUCT_DEFINITION_FORMATION('','',#28464); -#28464 = PRODUCT('SM04B-SRSS-TB','SM04B-SRSS-TB','',(#28465)); -#28465 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28466 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28467 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28468,#28470); -#28468 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#22028) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28469) +#30852 = SHAPE_DEFINITION_REPRESENTATION(#30853,#24430); +#30853 = PRODUCT_DEFINITION_SHAPE('','',#30854); +#30854 = PRODUCT_DEFINITION('design','',#30855,#30858); +#30855 = PRODUCT_DEFINITION_FORMATION('','',#30856); +#30856 = PRODUCT('SM04B-SRSS-TB','SM04B-SRSS-TB','',(#30857)); +#30857 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30858 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30859 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30860,#30862); +#30860 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#24420) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30861) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28469 = ITEM_DEFINED_TRANSFORMATION('','',#11,#22029); -#28470 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28471); -#28471 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('170','=>[0:1:1:31]','',#22023, - #28462,$); -#28472 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28464)); -#28473 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28474,#28476); -#28474 = ( REPRESENTATION_RELATIONSHIP('','',#22028,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28475) +#30861 = ITEM_DEFINED_TRANSFORMATION('','',#11,#24421); +#30862 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30863); +#30863 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('271','=>[0:1:1:31]','',#24415, + #30854,$); +#30864 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30856)); +#30865 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30866,#30868); +#30866 = ( REPRESENTATION_RELATIONSHIP('','',#24420,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30867) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28475 = ITEM_DEFINED_TRANSFORMATION('','',#11,#71); -#28476 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28477); -#28477 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('171','=>[0:1:1:30]','',#5, - #22023,$); -#28478 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#22025)); -#28479 = SHAPE_DEFINITION_REPRESENTATION(#28480,#28486); -#28480 = PRODUCT_DEFINITION_SHAPE('','',#28481); -#28481 = PRODUCT_DEFINITION('design','',#28482,#28485); -#28482 = PRODUCT_DEFINITION_FORMATION('','',#28483); -#28483 = PRODUCT('R4','R4','',(#28484)); -#28484 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28485 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28486 = SHAPE_REPRESENTATION('',(#11,#28487),#28491); -#28487 = AXIS2_PLACEMENT_3D('',#28488,#28489,#28490); -#28488 = CARTESIAN_POINT('',(3.048,8.0050005,-1.27E-002)); -#28489 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28490 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#28491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28495)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28492,#28493,#28494)) +#30867 = ITEM_DEFINED_TRANSFORMATION('','',#11,#71); +#30868 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30869); +#30869 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('272','=>[0:1:1:30]','',#5, + #24415,$); +#30870 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#24417)); +#30871 = SHAPE_DEFINITION_REPRESENTATION(#30872,#30878); +#30872 = PRODUCT_DEFINITION_SHAPE('','',#30873); +#30873 = PRODUCT_DEFINITION('design','',#30874,#30877); +#30874 = PRODUCT_DEFINITION_FORMATION('','',#30875); +#30875 = PRODUCT('R4','R4','',(#30876)); +#30876 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30877 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30878 = SHAPE_REPRESENTATION('',(#11,#30879),#30883); +#30879 = AXIS2_PLACEMENT_3D('',#30880,#30881,#30882); +#30880 = CARTESIAN_POINT('',(3.048,8.0050005,-1.27E-002)); +#30881 = DIRECTION('',(0.E+000,0.E+000,1.)); +#30882 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#30883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30887)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30884,#30885,#30886)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28492 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28493 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28494 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28495 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#28492, +#30884 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30885 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30886 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30887 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#30884, 'distance_accuracy_value','confusion accuracy'); -#28496 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28497,#28499); -#28497 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#28486) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28498) +#30888 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30889,#30891); +#30889 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#30878) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30890) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28498 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28487); -#28499 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28500); -#28500 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('172','=>[0:1:1:7]','',#28481, - #7462,$); -#28501 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28502,#28504); -#28502 = ( REPRESENTATION_RELATIONSHIP('','',#28486,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28503) +#30890 = ITEM_DEFINED_TRANSFORMATION('','',#11,#30879); +#30891 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30892); +#30892 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('273','=>[0:1:1:7]','',#30873, + #9854,$); +#30893 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30894,#30896); +#30894 = ( REPRESENTATION_RELATIONSHIP('','',#30878,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30895) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28503 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75); -#28504 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28505); -#28505 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('173','=>[0:1:1:32]','',#5, - #28481,$); -#28506 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28483)); -#28507 = SHAPE_DEFINITION_REPRESENTATION(#28508,#28514); -#28508 = PRODUCT_DEFINITION_SHAPE('','',#28509); -#28509 = PRODUCT_DEFINITION('design','',#28510,#28513); -#28510 = PRODUCT_DEFINITION_FORMATION('','',#28511); -#28511 = PRODUCT('C22','C22','',(#28512)); -#28512 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28513 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28514 = SHAPE_REPRESENTATION('',(#11,#28515),#28519); -#28515 = AXIS2_PLACEMENT_3D('',#28516,#28517,#28518); -#28516 = CARTESIAN_POINT('',(21.9710635,11.04891872,1.27E-002)); -#28517 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28518 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#28519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28523)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28520,#28521,#28522)) +#30895 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75); +#30896 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30897); +#30897 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('274','=>[0:1:1:32]','',#5, + #30873,$); +#30898 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30875)); +#30899 = SHAPE_DEFINITION_REPRESENTATION(#30900,#30906); +#30900 = PRODUCT_DEFINITION_SHAPE('','',#30901); +#30901 = PRODUCT_DEFINITION('design','',#30902,#30905); +#30902 = PRODUCT_DEFINITION_FORMATION('','',#30903); +#30903 = PRODUCT('C22','C22','',(#30904)); +#30904 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30905 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30906 = SHAPE_REPRESENTATION('',(#11,#30907),#30911); +#30907 = AXIS2_PLACEMENT_3D('',#30908,#30909,#30910); +#30908 = CARTESIAN_POINT('',(21.9710635,11.04891872,1.27E-002)); +#30909 = DIRECTION('',(0.E+000,0.E+000,1.)); +#30910 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#30911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30915)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30912,#30913,#30914)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28520 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28521 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28522 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28523 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28520, +#30912 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30913 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30914 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30915 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#30912, 'distance_accuracy_value','confusion accuracy'); -#28524 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28525,#28527); -#28525 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28514) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28526) +#30916 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30917,#30919); +#30917 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#30906) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30918) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28526 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28515); -#28527 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28528); -#28528 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('174','=>[0:1:1:18]','',#28509, - #11876,$); -#28529 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28530,#28532); -#28530 = ( REPRESENTATION_RELATIONSHIP('','',#28514,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28531) +#30918 = ITEM_DEFINED_TRANSFORMATION('','',#11,#30907); +#30919 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30920); +#30920 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('275','=>[0:1:1:18]','',#30901, + #14268,$); +#30921 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30922,#30924); +#30922 = ( REPRESENTATION_RELATIONSHIP('','',#30906,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30923) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28531 = ITEM_DEFINED_TRANSFORMATION('','',#11,#79); -#28532 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28533); -#28533 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('175','=>[0:1:1:33]','',#5, - #28509,$); -#28534 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28511)); -#28535 = SHAPE_DEFINITION_REPRESENTATION(#28536,#28542); -#28536 = PRODUCT_DEFINITION_SHAPE('','',#28537); -#28537 = PRODUCT_DEFINITION('design','',#28538,#28541); -#28538 = PRODUCT_DEFINITION_FORMATION('','',#28539); -#28539 = PRODUCT('C21','C21','',(#28540)); -#28540 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28541 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28542 = SHAPE_REPRESENTATION('',(#11,#28543),#28547); -#28543 = AXIS2_PLACEMENT_3D('',#28544,#28545,#28546); -#28544 = CARTESIAN_POINT('',(9.6519365,12.95408128,1.27E-002)); -#28545 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28546 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#28547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28551)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28548,#28549,#28550)) +#30923 = ITEM_DEFINED_TRANSFORMATION('','',#11,#79); +#30924 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30925); +#30925 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('276','=>[0:1:1:33]','',#5, + #30901,$); +#30926 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30903)); +#30927 = SHAPE_DEFINITION_REPRESENTATION(#30928,#30934); +#30928 = PRODUCT_DEFINITION_SHAPE('','',#30929); +#30929 = PRODUCT_DEFINITION('design','',#30930,#30933); +#30930 = PRODUCT_DEFINITION_FORMATION('','',#30931); +#30931 = PRODUCT('C21','C21','',(#30932)); +#30932 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30933 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30934 = SHAPE_REPRESENTATION('',(#11,#30935),#30939); +#30935 = AXIS2_PLACEMENT_3D('',#30936,#30937,#30938); +#30936 = CARTESIAN_POINT('',(9.6519365,12.95408128,1.27E-002)); +#30937 = DIRECTION('',(0.E+000,0.E+000,1.)); +#30938 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#30939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30943)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30940,#30941,#30942)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28548 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28549 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28550 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28551 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28548, +#30940 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30941 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30942 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30943 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#30940, 'distance_accuracy_value','confusion accuracy'); -#28552 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28553,#28555); -#28553 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28542) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28554) +#30944 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30945,#30947); +#30945 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#30934) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30946) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28554 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28543); -#28555 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28556); -#28556 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('176','=>[0:1:1:18]','',#28537, - #11876,$); -#28557 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28558,#28560); -#28558 = ( REPRESENTATION_RELATIONSHIP('','',#28542,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28559) +#30946 = ITEM_DEFINED_TRANSFORMATION('','',#11,#30935); +#30947 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30948); +#30948 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('277','=>[0:1:1:18]','',#30929, + #14268,$); +#30949 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30950,#30952); +#30950 = ( REPRESENTATION_RELATIONSHIP('','',#30934,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30951) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28559 = ITEM_DEFINED_TRANSFORMATION('','',#11,#83); -#28560 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28561); -#28561 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('177','=>[0:1:1:34]','',#5, - #28537,$); -#28562 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28539)); -#28563 = SHAPE_DEFINITION_REPRESENTATION(#28564,#28570); -#28564 = PRODUCT_DEFINITION_SHAPE('','',#28565); -#28565 = PRODUCT_DEFINITION('design','',#28566,#28569); -#28566 = PRODUCT_DEFINITION_FORMATION('','',#28567); -#28567 = PRODUCT('C20','C20','',(#28568)); -#28568 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28569 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28570 = SHAPE_REPRESENTATION('',(#11,#28571),#28575); -#28571 = AXIS2_PLACEMENT_3D('',#28572,#28573,#28574); -#28572 = CARTESIAN_POINT('',(24.5109365,12.44608128,1.27E-002)); -#28573 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28574 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#28575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28579)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28576,#28577,#28578)) +#30951 = ITEM_DEFINED_TRANSFORMATION('','',#11,#83); +#30952 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30953); +#30953 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('278','=>[0:1:1:34]','',#5, + #30929,$); +#30954 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30931)); +#30955 = SHAPE_DEFINITION_REPRESENTATION(#30956,#30962); +#30956 = PRODUCT_DEFINITION_SHAPE('','',#30957); +#30957 = PRODUCT_DEFINITION('design','',#30958,#30961); +#30958 = PRODUCT_DEFINITION_FORMATION('','',#30959); +#30959 = PRODUCT('C20','C20','',(#30960)); +#30960 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30961 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30962 = SHAPE_REPRESENTATION('',(#11,#30963),#30967); +#30963 = AXIS2_PLACEMENT_3D('',#30964,#30965,#30966); +#30964 = CARTESIAN_POINT('',(24.5109365,12.44608128,1.27E-002)); +#30965 = DIRECTION('',(0.E+000,0.E+000,1.)); +#30966 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#30967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30971)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30968,#30969,#30970)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28576 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28577 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28578 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28579 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28576, +#30968 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30969 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30970 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30971 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#30968, 'distance_accuracy_value','confusion accuracy'); -#28580 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28581,#28583); -#28581 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28570) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28582) +#30972 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30973,#30975); +#30973 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#30962) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30974) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28582 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28571); -#28583 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28584); -#28584 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('178','=>[0:1:1:18]','',#28565, - #11876,$); -#28585 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28586,#28588); -#28586 = ( REPRESENTATION_RELATIONSHIP('','',#28570,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28587) +#30974 = ITEM_DEFINED_TRANSFORMATION('','',#11,#30963); +#30975 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30976); +#30976 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('279','=>[0:1:1:18]','',#30957, + #14268,$); +#30977 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#30978,#30980); +#30978 = ( REPRESENTATION_RELATIONSHIP('','',#30962,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#30979) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28587 = ITEM_DEFINED_TRANSFORMATION('','',#11,#87); -#28588 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28589); -#28589 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('179','=>[0:1:1:35]','',#5, - #28565,$); -#28590 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28567)); -#28591 = SHAPE_DEFINITION_REPRESENTATION(#28592,#28598); -#28592 = PRODUCT_DEFINITION_SHAPE('','',#28593); -#28593 = PRODUCT_DEFINITION('design','',#28594,#28597); -#28594 = PRODUCT_DEFINITION_FORMATION('','',#28595); -#28595 = PRODUCT('C19','C19','',(#28596)); -#28596 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28597 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28598 = SHAPE_REPRESENTATION('',(#11,#28599),#28603); -#28599 = AXIS2_PLACEMENT_3D('',#28600,#28601,#28602); -#28600 = CARTESIAN_POINT('',(11.43008128,11.9380635,1.27E-002)); -#28601 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28602 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#28603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28607)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28604,#28605,#28606)) +#30979 = ITEM_DEFINED_TRANSFORMATION('','',#11,#87); +#30980 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #30981); +#30981 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('280','=>[0:1:1:35]','',#5, + #30957,$); +#30982 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30959)); +#30983 = SHAPE_DEFINITION_REPRESENTATION(#30984,#30990); +#30984 = PRODUCT_DEFINITION_SHAPE('','',#30985); +#30985 = PRODUCT_DEFINITION('design','',#30986,#30989); +#30986 = PRODUCT_DEFINITION_FORMATION('','',#30987); +#30987 = PRODUCT('C19','C19','',(#30988)); +#30988 = PRODUCT_CONTEXT('',#2,'mechanical'); +#30989 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#30990 = SHAPE_REPRESENTATION('',(#11,#30991),#30995); +#30991 = AXIS2_PLACEMENT_3D('',#30992,#30993,#30994); +#30992 = CARTESIAN_POINT('',(11.43008128,11.9380635,1.27E-002)); +#30993 = DIRECTION('',(0.E+000,0.E+000,1.)); +#30994 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#30995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#30999)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#30996,#30997,#30998)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28604 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28605 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28606 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28607 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28604, +#30996 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#30997 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#30998 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#30999 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#30996, 'distance_accuracy_value','confusion accuracy'); -#28608 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28609,#28611); -#28609 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28598) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28610) +#31000 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31001,#31003); +#31001 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#30990) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31002) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28610 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28599); -#28611 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28612); -#28612 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('180','=>[0:1:1:18]','',#28593, - #11876,$); -#28613 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28614,#28616); -#28614 = ( REPRESENTATION_RELATIONSHIP('','',#28598,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28615) +#31002 = ITEM_DEFINED_TRANSFORMATION('','',#11,#30991); +#31003 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31004); +#31004 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('281','=>[0:1:1:18]','',#30985, + #14268,$); +#31005 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31006,#31008); +#31006 = ( REPRESENTATION_RELATIONSHIP('','',#30990,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31007) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28615 = ITEM_DEFINED_TRANSFORMATION('','',#11,#91); -#28616 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28617); -#28617 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('181','=>[0:1:1:36]','',#5, - #28593,$); -#28618 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28595)); -#28619 = SHAPE_DEFINITION_REPRESENTATION(#28620,#28626); -#28620 = PRODUCT_DEFINITION_SHAPE('','',#28621); -#28621 = PRODUCT_DEFINITION('design','',#28622,#28625); -#28622 = PRODUCT_DEFINITION_FORMATION('','',#28623); -#28623 = PRODUCT('C18','C18','',(#28624)); -#28624 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28625 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28626 = SHAPE_REPRESENTATION('',(#11,#28627),#28631); -#28627 = AXIS2_PLACEMENT_3D('',#28628,#28629,#28630); -#28628 = CARTESIAN_POINT('',(3.04808128,9.1440635,1.27E-002)); -#28629 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28630 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#28631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28635)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28632,#28633,#28634)) +#31007 = ITEM_DEFINED_TRANSFORMATION('','',#11,#91); +#31008 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31009); +#31009 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('282','=>[0:1:1:36]','',#5, + #30985,$); +#31010 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#30987)); +#31011 = SHAPE_DEFINITION_REPRESENTATION(#31012,#31018); +#31012 = PRODUCT_DEFINITION_SHAPE('','',#31013); +#31013 = PRODUCT_DEFINITION('design','',#31014,#31017); +#31014 = PRODUCT_DEFINITION_FORMATION('','',#31015); +#31015 = PRODUCT('C18','C18','',(#31016)); +#31016 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31017 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31018 = SHAPE_REPRESENTATION('',(#11,#31019),#31023); +#31019 = AXIS2_PLACEMENT_3D('',#31020,#31021,#31022); +#31020 = CARTESIAN_POINT('',(3.04808128,9.1440635,1.27E-002)); +#31021 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31022 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#31023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31027)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31024,#31025,#31026)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28632 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28633 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28634 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28635 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28632, +#31024 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31025 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31026 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31027 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#31024, 'distance_accuracy_value','confusion accuracy'); -#28636 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28637,#28639); -#28637 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28626) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28638) +#31028 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31029,#31031); +#31029 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#31018) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31030) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28638 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28627); -#28639 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28640); -#28640 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('182','=>[0:1:1:18]','',#28621, - #11876,$); -#28641 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28642,#28644); -#28642 = ( REPRESENTATION_RELATIONSHIP('','',#28626,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28643) +#31030 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31019); +#31031 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31032); +#31032 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('283','=>[0:1:1:18]','',#31013, + #14268,$); +#31033 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31034,#31036); +#31034 = ( REPRESENTATION_RELATIONSHIP('','',#31018,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31035) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28643 = ITEM_DEFINED_TRANSFORMATION('','',#11,#95); -#28644 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28645); -#28645 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('183','=>[0:1:1:37]','',#5, - #28621,$); -#28646 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28623)); -#28647 = SHAPE_DEFINITION_REPRESENTATION(#28648,#28654); -#28648 = PRODUCT_DEFINITION_SHAPE('','',#28649); -#28649 = PRODUCT_DEFINITION('design','',#28650,#28653); -#28650 = PRODUCT_DEFINITION_FORMATION('','',#28651); -#28651 = PRODUCT('C17','C17','',(#28652)); -#28652 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28653 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28654 = SHAPE_REPRESENTATION('',(#11,#28655),#28659); -#28655 = AXIS2_PLACEMENT_3D('',#28656,#28657,#28658); -#28656 = CARTESIAN_POINT('',(12.70008128,24.3840635,1.27E-002)); -#28657 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28658 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#28659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28663)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28660,#28661,#28662)) +#31035 = ITEM_DEFINED_TRANSFORMATION('','',#11,#95); +#31036 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31037); +#31037 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('284','=>[0:1:1:37]','',#5, + #31013,$); +#31038 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31015)); +#31039 = SHAPE_DEFINITION_REPRESENTATION(#31040,#31046); +#31040 = PRODUCT_DEFINITION_SHAPE('','',#31041); +#31041 = PRODUCT_DEFINITION('design','',#31042,#31045); +#31042 = PRODUCT_DEFINITION_FORMATION('','',#31043); +#31043 = PRODUCT('C17','C17','',(#31044)); +#31044 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31045 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31046 = SHAPE_REPRESENTATION('',(#11,#31047),#31051); +#31047 = AXIS2_PLACEMENT_3D('',#31048,#31049,#31050); +#31048 = CARTESIAN_POINT('',(12.70008128,24.3840635,1.27E-002)); +#31049 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31050 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#31051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31055)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31052,#31053,#31054)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28660 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28661 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28662 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28663 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28660, +#31052 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31053 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31054 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31055 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#31052, 'distance_accuracy_value','confusion accuracy'); -#28664 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28665,#28667); -#28665 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28654) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28666) +#31056 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31057,#31059); +#31057 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#31046) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31058) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28666 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28655); -#28667 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28668); -#28668 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('184','=>[0:1:1:18]','',#28649, - #11876,$); -#28669 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28670,#28672); -#28670 = ( REPRESENTATION_RELATIONSHIP('','',#28654,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28671) +#31058 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31047); +#31059 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31060); +#31060 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('285','=>[0:1:1:18]','',#31041, + #14268,$); +#31061 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31062,#31064); +#31062 = ( REPRESENTATION_RELATIONSHIP('','',#31046,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31063) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28671 = ITEM_DEFINED_TRANSFORMATION('','',#11,#99); -#28672 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28673); -#28673 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('185','=>[0:1:1:38]','',#5, - #28649,$); -#28674 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28651)); -#28675 = SHAPE_DEFINITION_REPRESENTATION(#28676,#28682); -#28676 = PRODUCT_DEFINITION_SHAPE('','',#28677); -#28677 = PRODUCT_DEFINITION('design','',#28678,#28681); -#28678 = PRODUCT_DEFINITION_FORMATION('','',#28679); -#28679 = PRODUCT('C16','C16','',(#28680)); -#28680 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28681 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28682 = SHAPE_REPRESENTATION('',(#11,#28683),#28687); -#28683 = AXIS2_PLACEMENT_3D('',#28684,#28685,#28686); -#28684 = CARTESIAN_POINT('',(21.08191872,24.3839365,1.27E-002)); -#28685 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28686 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#28687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28691)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28688,#28689,#28690)) +#31063 = ITEM_DEFINED_TRANSFORMATION('','',#11,#99); +#31064 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31065); +#31065 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('286','=>[0:1:1:38]','',#5, + #31041,$); +#31066 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31043)); +#31067 = SHAPE_DEFINITION_REPRESENTATION(#31068,#31074); +#31068 = PRODUCT_DEFINITION_SHAPE('','',#31069); +#31069 = PRODUCT_DEFINITION('design','',#31070,#31073); +#31070 = PRODUCT_DEFINITION_FORMATION('','',#31071); +#31071 = PRODUCT('C16','C16','',(#31072)); +#31072 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31073 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31074 = SHAPE_REPRESENTATION('',(#11,#31075),#31079); +#31075 = AXIS2_PLACEMENT_3D('',#31076,#31077,#31078); +#31076 = CARTESIAN_POINT('',(21.08191872,24.3839365,1.27E-002)); +#31077 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31078 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#31079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31083)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31080,#31081,#31082)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28688 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28689 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28690 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28691 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28688, +#31080 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31081 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31082 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31083 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#31080, 'distance_accuracy_value','confusion accuracy'); -#28692 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28693,#28695); -#28693 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28682) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28694) +#31084 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31085,#31087); +#31085 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#31074) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31086) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28694 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28683); -#28695 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28696); -#28696 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('186','=>[0:1:1:18]','',#28677, - #11876,$); -#28697 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28698,#28700); -#28698 = ( REPRESENTATION_RELATIONSHIP('','',#28682,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28699) +#31086 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31075); +#31087 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31088); +#31088 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('287','=>[0:1:1:18]','',#31069, + #14268,$); +#31089 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31090,#31092); +#31090 = ( REPRESENTATION_RELATIONSHIP('','',#31074,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31091) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28699 = ITEM_DEFINED_TRANSFORMATION('','',#11,#103); -#28700 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28701); -#28701 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('187','=>[0:1:1:39]','',#5, - #28677,$); -#28702 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28679)); -#28703 = SHAPE_DEFINITION_REPRESENTATION(#28704,#28710); -#28704 = PRODUCT_DEFINITION_SHAPE('','',#28705); -#28705 = PRODUCT_DEFINITION('design','',#28706,#28709); -#28706 = PRODUCT_DEFINITION_FORMATION('','',#28707); -#28707 = PRODUCT('C15','C15','',(#28708)); -#28708 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28709 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28710 = SHAPE_REPRESENTATION('',(#11,#28711),#28715); -#28711 = AXIS2_PLACEMENT_3D('',#28712,#28713,#28714); -#28712 = CARTESIAN_POINT('',(11.6840635,22.60591872,1.27E-002)); -#28713 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28714 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#28715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28719)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28716,#28717,#28718)) +#31091 = ITEM_DEFINED_TRANSFORMATION('','',#11,#103); +#31092 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31093); +#31093 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('288','=>[0:1:1:39]','',#5, + #31069,$); +#31094 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31071)); +#31095 = SHAPE_DEFINITION_REPRESENTATION(#31096,#31102); +#31096 = PRODUCT_DEFINITION_SHAPE('','',#31097); +#31097 = PRODUCT_DEFINITION('design','',#31098,#31101); +#31098 = PRODUCT_DEFINITION_FORMATION('','',#31099); +#31099 = PRODUCT('C15','C15','',(#31100)); +#31100 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31101 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31102 = SHAPE_REPRESENTATION('',(#11,#31103),#31107); +#31103 = AXIS2_PLACEMENT_3D('',#31104,#31105,#31106); +#31104 = CARTESIAN_POINT('',(11.6840635,22.60591872,1.27E-002)); +#31105 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31106 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#31107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31111)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31108,#31109,#31110)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28716 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28717 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28718 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28719 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28716, +#31108 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31109 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31110 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31111 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#31108, 'distance_accuracy_value','confusion accuracy'); -#28720 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28721,#28723); -#28721 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28710) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28722) +#31112 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31113,#31115); +#31113 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#31102) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31114) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28722 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28711); -#28723 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28724); -#28724 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('188','=>[0:1:1:18]','',#28705, - #11876,$); -#28725 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28726,#28728); -#28726 = ( REPRESENTATION_RELATIONSHIP('','',#28710,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28727) +#31114 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31103); +#31115 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31116); +#31116 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('289','=>[0:1:1:18]','',#31097, + #14268,$); +#31117 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31118,#31120); +#31118 = ( REPRESENTATION_RELATIONSHIP('','',#31102,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31119) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28727 = ITEM_DEFINED_TRANSFORMATION('','',#11,#107); -#28728 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28729); -#28729 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('189','=>[0:1:1:40]','',#5, - #28705,$); -#28730 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28707)); -#28731 = SHAPE_DEFINITION_REPRESENTATION(#28732,#28738); -#28732 = PRODUCT_DEFINITION_SHAPE('','',#28733); -#28733 = PRODUCT_DEFINITION('design','',#28734,#28737); -#28734 = PRODUCT_DEFINITION_FORMATION('','',#28735); -#28735 = PRODUCT('R21','R21','',(#28736)); -#28736 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28737 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28738 = SHAPE_REPRESENTATION('',(#11,#28739),#28743); -#28739 = AXIS2_PLACEMENT_3D('',#28740,#28741,#28742); -#28740 = CARTESIAN_POINT('',(10.795,29.4680005,-1.27E-002)); -#28741 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28742 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#28743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28747)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28744,#28745,#28746)) +#31119 = ITEM_DEFINED_TRANSFORMATION('','',#11,#107); +#31120 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31121); +#31121 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('290','=>[0:1:1:40]','',#5, + #31097,$); +#31122 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31099)); +#31123 = SHAPE_DEFINITION_REPRESENTATION(#31124,#31130); +#31124 = PRODUCT_DEFINITION_SHAPE('','',#31125); +#31125 = PRODUCT_DEFINITION('design','',#31126,#31129); +#31126 = PRODUCT_DEFINITION_FORMATION('','',#31127); +#31127 = PRODUCT('R21','R21','',(#31128)); +#31128 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31129 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31130 = SHAPE_REPRESENTATION('',(#11,#31131),#31135); +#31131 = AXIS2_PLACEMENT_3D('',#31132,#31133,#31134); +#31132 = CARTESIAN_POINT('',(10.795,29.4680005,-1.27E-002)); +#31133 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31134 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#31135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31139)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31136,#31137,#31138)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28744 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28745 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28746 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28747 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#28744, +#31136 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31137 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31138 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31139 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#31136, 'distance_accuracy_value','confusion accuracy'); -#28748 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28749,#28751); -#28749 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#28738) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28750) +#31140 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31141,#31143); +#31141 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#31130) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31142) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28750 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28739); -#28751 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28752); -#28752 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('190','=>[0:1:1:7]','',#28733, - #7462,$); -#28753 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28754,#28756); -#28754 = ( REPRESENTATION_RELATIONSHIP('','',#28738,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28755) +#31142 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31131); +#31143 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31144); +#31144 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('291','=>[0:1:1:7]','',#31125, + #9854,$); +#31145 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31146,#31148); +#31146 = ( REPRESENTATION_RELATIONSHIP('','',#31130,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31147) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28755 = ITEM_DEFINED_TRANSFORMATION('','',#11,#111); -#28756 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28757); -#28757 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('191','=>[0:1:1:41]','',#5, - #28733,$); -#28758 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28735)); -#28759 = SHAPE_DEFINITION_REPRESENTATION(#28760,#28766); -#28760 = PRODUCT_DEFINITION_SHAPE('','',#28761); -#28761 = PRODUCT_DEFINITION('design','',#28762,#28765); -#28762 = PRODUCT_DEFINITION_FORMATION('','',#28763); -#28763 = PRODUCT('R20','R20','',(#28764)); -#28764 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28765 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28766 = SHAPE_REPRESENTATION('',(#11,#28767),#28771); -#28767 = AXIS2_PLACEMENT_3D('',#28768,#28769,#28770); -#28768 = CARTESIAN_POINT('',(8.382,29.4599995,-1.27E-002)); -#28769 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28770 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#28771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28775)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28772,#28773,#28774)) +#31147 = ITEM_DEFINED_TRANSFORMATION('','',#11,#111); +#31148 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31149); +#31149 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('292','=>[0:1:1:41]','',#5, + #31125,$); +#31150 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31127)); +#31151 = SHAPE_DEFINITION_REPRESENTATION(#31152,#31158); +#31152 = PRODUCT_DEFINITION_SHAPE('','',#31153); +#31153 = PRODUCT_DEFINITION('design','',#31154,#31157); +#31154 = PRODUCT_DEFINITION_FORMATION('','',#31155); +#31155 = PRODUCT('R20','R20','',(#31156)); +#31156 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31157 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31158 = SHAPE_REPRESENTATION('',(#11,#31159),#31163); +#31159 = AXIS2_PLACEMENT_3D('',#31160,#31161,#31162); +#31160 = CARTESIAN_POINT('',(8.382,29.4599995,-1.27E-002)); +#31161 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31162 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#31163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31167)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31164,#31165,#31166)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28772 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28773 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28774 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28775 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#28772, +#31164 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31165 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31166 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31167 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#31164, 'distance_accuracy_value','confusion accuracy'); -#28776 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28777,#28779); -#28777 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#28766) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28778) +#31168 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31169,#31171); +#31169 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#31158) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31170) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28778 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28767); -#28779 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28780); -#28780 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('192','=>[0:1:1:7]','',#28761, - #7462,$); -#28781 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28782,#28784); -#28782 = ( REPRESENTATION_RELATIONSHIP('','',#28766,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28783) +#31170 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31159); +#31171 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31172); +#31172 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('293','=>[0:1:1:7]','',#31153, + #9854,$); +#31173 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31174,#31176); +#31174 = ( REPRESENTATION_RELATIONSHIP('','',#31158,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31175) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28783 = ITEM_DEFINED_TRANSFORMATION('','',#11,#115); -#28784 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28785); -#28785 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('193','=>[0:1:1:42]','',#5, - #28761,$); -#28786 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28763)); -#28787 = SHAPE_DEFINITION_REPRESENTATION(#28788,#28794); -#28788 = PRODUCT_DEFINITION_SHAPE('','',#28789); -#28789 = PRODUCT_DEFINITION('design','',#28790,#28793); -#28790 = PRODUCT_DEFINITION_FORMATION('','',#28791); -#28791 = PRODUCT('C2','C2','',(#28792)); -#28792 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28793 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28794 = SHAPE_REPRESENTATION('',(#11,#28795),#28799); -#28795 = AXIS2_PLACEMENT_3D('',#28796,#28797,#28798); -#28796 = CARTESIAN_POINT('',(24.38391872,30.2259365,1.27E-002)); -#28797 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28798 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#28799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28803)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28800,#28801,#28802)) +#31175 = ITEM_DEFINED_TRANSFORMATION('','',#11,#115); +#31176 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31177); +#31177 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('294','=>[0:1:1:42]','',#5, + #31153,$); +#31178 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31155)); +#31179 = SHAPE_DEFINITION_REPRESENTATION(#31180,#31186); +#31180 = PRODUCT_DEFINITION_SHAPE('','',#31181); +#31181 = PRODUCT_DEFINITION('design','',#31182,#31185); +#31182 = PRODUCT_DEFINITION_FORMATION('','',#31183); +#31183 = PRODUCT('C2','C2','',(#31184)); +#31184 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31185 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31186 = SHAPE_REPRESENTATION('',(#11,#31187),#31191); +#31187 = AXIS2_PLACEMENT_3D('',#31188,#31189,#31190); +#31188 = CARTESIAN_POINT('',(24.38391872,30.2259365,1.27E-002)); +#31189 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31190 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#31191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31195)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31192,#31193,#31194)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28800 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28801 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28802 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28803 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#28800, +#31192 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31193 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31194 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31195 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#31192, 'distance_accuracy_value','confusion accuracy'); -#28804 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28805,#28807); -#28805 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#28794) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28806) +#31196 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31197,#31199); +#31197 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#31186) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31198) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28806 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28795); -#28807 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28808); -#28808 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('194','=>[0:1:1:18]','',#28789, - #11876,$); -#28809 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#28810,#28812); -#28810 = ( REPRESENTATION_RELATIONSHIP('','',#28794,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#28811) +#31198 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31187); +#31199 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31200); +#31200 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('295','=>[0:1:1:18]','',#31181, + #14268,$); +#31201 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#31202,#31204); +#31202 = ( REPRESENTATION_RELATIONSHIP('','',#31186,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#31203) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#28811 = ITEM_DEFINED_TRANSFORMATION('','',#11,#119); -#28812 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #28813); -#28813 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('195','=>[0:1:1:43]','',#5, - #28789,$); -#28814 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28791)); -#28815 = SHAPE_DEFINITION_REPRESENTATION(#28816,#28822); -#28816 = PRODUCT_DEFINITION_SHAPE('','',#28817); -#28817 = PRODUCT_DEFINITION('design','',#28818,#28821); -#28818 = PRODUCT_DEFINITION_FORMATION('','',#28819); -#28819 = PRODUCT('C3','C3','',(#28820)); -#28820 = PRODUCT_CONTEXT('',#2,'mechanical'); -#28821 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#28822 = SHAPE_REPRESENTATION('',(#11,#28823),#28827); -#28823 = AXIS2_PLACEMENT_3D('',#28824,#28825,#28826); -#28824 = CARTESIAN_POINT('',(24.38393142,28.82891872,1.27E-002)); -#28825 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); -#28826 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#28827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#28831)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#28828,#28829,#28830)) +#31203 = ITEM_DEFINED_TRANSFORMATION('','',#11,#119); +#31204 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #31205); +#31205 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('296','=>[0:1:1:43]','',#5, + #31181,$); +#31206 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31183)); +#31207 = SHAPE_DEFINITION_REPRESENTATION(#31208,#31214); +#31208 = PRODUCT_DEFINITION_SHAPE('','',#31209); +#31209 = PRODUCT_DEFINITION('design','',#31210,#31213); +#31210 = PRODUCT_DEFINITION_FORMATION('','',#31211); +#31211 = PRODUCT('C3','C3','',(#31212)); +#31212 = PRODUCT_CONTEXT('',#2,'mechanical'); +#31213 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#31214 = SHAPE_REPRESENTATION('',(#11,#31215),#31219); +#31215 = AXIS2_PLACEMENT_3D('',#31216,#31217,#31218); +#31216 = CARTESIAN_POINT('',(24.38393142,28.82891872,1.27E-002)); +#31217 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); +#31218 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#31219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#31223)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#31220,#31221,#31222)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#28828 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#28829 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#28830 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#28831 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#28828, +#31220 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#31221 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#31222 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#31223 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#31220, 'distance_accuracy_value','confusion accuracy'); -#28832 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#28833),#37339); -#28833 = MANIFOLD_SOLID_BREP('',#28834); -#28834 = CLOSED_SHELL('',(#28835,#31047,#31151,#31255,#31372,#31484, - #31563,#31637,#31692,#31742,#31825,#31903,#32002,#32101,#32132, - #32163,#32219,#32270,#32366,#32411,#32507,#32552,#32597,#32642, - #32713,#32784,#32833,#32840,#32885,#32892,#32918,#32963,#32969, - #33017,#33065,#33071,#33078,#33127,#33153,#33160,#33185,#33210, - #33217,#34309,#34352,#34377,#34402,#34427,#34452,#34477,#34502, - #34509,#34605,#34676,#34747,#34798,#34902,#34973,#35052,#35111, - #35118,#35125,#35824,#35867,#35892,#35917,#35942,#35949,#36037, - #36116,#36195,#36274,#36317,#36325,#36430,#36493,#36556,#36635, - #36699,#36748,#36797,#36846,#36895,#36944,#36992,#37055,#37134, - #37213,#37293,#37320)); -#28835 = ADVANCED_FACE('',(#28836,#29757,#30245,#30357),#28866,.T.); -#28836 = FACE_BOUND('',#28837,.T.); -#28837 = EDGE_LOOP('',(#28838,#28939,#28967,#29061,#29155,#29249,#29311, - #29339,#29367,#29395,#29423,#29451,#29479,#29541,#29635,#29697)); -#28838 = ORIENTED_EDGE('',*,*,#28839,.T.); -#28839 = EDGE_CURVE('',#28840,#28842,#28844,.T.); -#28840 = VERTEX_POINT('',#28841); -#28841 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); -#28842 = VERTEX_POINT('',#28843); -#28843 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); -#28844 = SURFACE_CURVE('',#28845,(#28865,#28893),.PCURVE_S1.); -#28845 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#28846,#28847,#28848,#28849, - #28850,#28851,#28852,#28853,#28854,#28855,#28856,#28857,#28858, - #28859,#28860,#28861,#28862,#28863,#28864),.UNSPECIFIED.,.F.,.F.,(4, +#31224 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#31225),#39731); +#31225 = MANIFOLD_SOLID_BREP('',#31226); +#31226 = CLOSED_SHELL('',(#31227,#33439,#33543,#33647,#33764,#33876, + #33955,#34029,#34084,#34134,#34217,#34295,#34394,#34493,#34524, + #34555,#34611,#34662,#34758,#34803,#34899,#34944,#34989,#35034, + #35105,#35176,#35225,#35232,#35277,#35284,#35310,#35355,#35361, + #35409,#35457,#35463,#35470,#35519,#35545,#35552,#35577,#35602, + #35609,#36701,#36744,#36769,#36794,#36819,#36844,#36869,#36894, + #36901,#36997,#37068,#37139,#37190,#37294,#37365,#37444,#37503, + #37510,#37517,#38216,#38259,#38284,#38309,#38334,#38341,#38429, + #38508,#38587,#38666,#38709,#38717,#38822,#38885,#38948,#39027, + #39091,#39140,#39189,#39238,#39287,#39336,#39384,#39447,#39526, + #39605,#39685,#39712)); +#31227 = ADVANCED_FACE('',(#31228,#32149,#32637,#32749),#31258,.T.); +#31228 = FACE_BOUND('',#31229,.T.); +#31229 = EDGE_LOOP('',(#31230,#31331,#31359,#31453,#31547,#31641,#31703, + #31731,#31759,#31787,#31815,#31843,#31871,#31933,#32027,#32089)); +#31230 = ORIENTED_EDGE('',*,*,#31231,.T.); +#31231 = EDGE_CURVE('',#31232,#31234,#31236,.T.); +#31232 = VERTEX_POINT('',#31233); +#31233 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); +#31234 = VERTEX_POINT('',#31235); +#31235 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); +#31236 = SURFACE_CURVE('',#31237,(#31257,#31285),.PCURVE_S1.); +#31237 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31238,#31239,#31240,#31241, + #31242,#31243,#31244,#31245,#31246,#31247,#31248,#31249,#31250, + #31251,#31252,#31253,#31254,#31255,#31256),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.929802345975E-002, 0.135560844101,0.199670955647,0.261716238496,0.322661929947, 0.382906923778,0.443032033073,0.50350078735,0.563724281017, 0.623980022053,0.683629386996,0.743848272486,0.80519184623, 0.86764874296,0.932778084231,1.),.UNSPECIFIED.); -#28846 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); -#28847 = CARTESIAN_POINT('',(0.238622576902,0.78,-0.184263348524)); -#28848 = CARTESIAN_POINT('',(0.233215879453,0.78,-0.1843730225)); -#28849 = CARTESIAN_POINT('',(0.225299512414,0.78,-0.185326476104)); -#28850 = CARTESIAN_POINT('',(0.217770111238,0.78,-0.186846898403)); -#28851 = CARTESIAN_POINT('',(0.210625317089,0.78,-0.189027654649)); -#28852 = CARTESIAN_POINT('',(0.203843604617,0.78,-0.191783244251)); -#28853 = CARTESIAN_POINT('',(0.1975038024,0.78,-0.195283787924)); -#28854 = CARTESIAN_POINT('',(0.191495890002,0.78,-0.199288191857)); -#28855 = CARTESIAN_POINT('',(0.185952021473,0.78,-0.203919830996)); -#28856 = CARTESIAN_POINT('',(0.180900835422,0.78,-0.209085889254)); -#28857 = CARTESIAN_POINT('',(0.176374870135,0.78,-0.214676908992)); -#28858 = CARTESIAN_POINT('',(0.172435374254,0.78,-0.22069653596)); -#28859 = CARTESIAN_POINT('',(0.169084249171,0.78,-0.227108750047)); -#28860 = CARTESIAN_POINT('',(0.166291241159,0.78,-0.233907401761)); -#28861 = CARTESIAN_POINT('',(0.164154479603,0.78,-0.241138894496)); -#28862 = CARTESIAN_POINT('',(0.162461986633,0.78,-0.248732276169)); -#28863 = CARTESIAN_POINT('',(0.161883400067,0.78,-0.253981123638)); -#28864 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); -#28865 = PCURVE('',#28866,#28871); -#28866 = PLANE('',#28867); -#28867 = AXIS2_PLACEMENT_3D('',#28868,#28869,#28870); -#28868 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#28869 = DIRECTION('',(0.E+000,1.,0.E+000)); -#28870 = DIRECTION('',(0.E+000,0.E+000,1.)); -#28871 = DEFINITIONAL_REPRESENTATION('',(#28872),#28892); -#28872 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#28873,#28874,#28875,#28876, - #28877,#28878,#28879,#28880,#28881,#28882,#28883,#28884,#28885, - #28886,#28887,#28888,#28889,#28890,#28891),.UNSPECIFIED.,.F.,.F.,(4, +#31238 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); +#31239 = CARTESIAN_POINT('',(0.238622576902,0.78,-0.184263348524)); +#31240 = CARTESIAN_POINT('',(0.233215879453,0.78,-0.1843730225)); +#31241 = CARTESIAN_POINT('',(0.225299512414,0.78,-0.185326476104)); +#31242 = CARTESIAN_POINT('',(0.217770111238,0.78,-0.186846898403)); +#31243 = CARTESIAN_POINT('',(0.210625317089,0.78,-0.189027654649)); +#31244 = CARTESIAN_POINT('',(0.203843604617,0.78,-0.191783244251)); +#31245 = CARTESIAN_POINT('',(0.1975038024,0.78,-0.195283787924)); +#31246 = CARTESIAN_POINT('',(0.191495890002,0.78,-0.199288191857)); +#31247 = CARTESIAN_POINT('',(0.185952021473,0.78,-0.203919830996)); +#31248 = CARTESIAN_POINT('',(0.180900835422,0.78,-0.209085889254)); +#31249 = CARTESIAN_POINT('',(0.176374870135,0.78,-0.214676908992)); +#31250 = CARTESIAN_POINT('',(0.172435374254,0.78,-0.22069653596)); +#31251 = CARTESIAN_POINT('',(0.169084249171,0.78,-0.227108750047)); +#31252 = CARTESIAN_POINT('',(0.166291241159,0.78,-0.233907401761)); +#31253 = CARTESIAN_POINT('',(0.164154479603,0.78,-0.241138894496)); +#31254 = CARTESIAN_POINT('',(0.162461986633,0.78,-0.248732276169)); +#31255 = CARTESIAN_POINT('',(0.161883400067,0.78,-0.253981123638)); +#31256 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); +#31257 = PCURVE('',#31258,#31263); +#31258 = PLANE('',#31259); +#31259 = AXIS2_PLACEMENT_3D('',#31260,#31261,#31262); +#31260 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#31261 = DIRECTION('',(0.E+000,1.,0.E+000)); +#31262 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31263 = DEFINITIONAL_REPRESENTATION('',(#31264),#31284); +#31264 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31265,#31266,#31267,#31268, + #31269,#31270,#31271,#31272,#31273,#31274,#31275,#31276,#31277, + #31278,#31279,#31280,#31281,#31282,#31283),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.929802345975E-002, 0.135560844101,0.199670955647,0.261716238496,0.322661929947, 0.382906923778,0.443032033073,0.50350078735,0.563724281017, 0.623980022053,0.683629386996,0.743848272486,0.80519184623, 0.86764874296,0.932778084231,1.),.UNSPECIFIED.); -#28873 = CARTESIAN_POINT('',(-0.809207283737,1.241386453514)); -#28874 = CARTESIAN_POINT('',(-0.809263348524,1.238622576902)); -#28875 = CARTESIAN_POINT('',(-0.8093730225,1.233215879453)); -#28876 = CARTESIAN_POINT('',(-0.810326476104,1.225299512414)); -#28877 = CARTESIAN_POINT('',(-0.811846898403,1.217770111238)); -#28878 = CARTESIAN_POINT('',(-0.814027654649,1.210625317089)); -#28879 = CARTESIAN_POINT('',(-0.816783244251,1.203843604617)); -#28880 = CARTESIAN_POINT('',(-0.820283787924,1.1975038024)); -#28881 = CARTESIAN_POINT('',(-0.824288191857,1.191495890002)); -#28882 = CARTESIAN_POINT('',(-0.828919830996,1.185952021473)); -#28883 = CARTESIAN_POINT('',(-0.834085889254,1.180900835422)); -#28884 = CARTESIAN_POINT('',(-0.839676908992,1.176374870135)); -#28885 = CARTESIAN_POINT('',(-0.84569653596,1.172435374254)); -#28886 = CARTESIAN_POINT('',(-0.852108750047,1.169084249171)); -#28887 = CARTESIAN_POINT('',(-0.858907401761,1.166291241159)); -#28888 = CARTESIAN_POINT('',(-0.866138894496,1.164154479603)); -#28889 = CARTESIAN_POINT('',(-0.873732276169,1.162461986633)); -#28890 = CARTESIAN_POINT('',(-0.878981123638,1.161883400067)); -#28891 = CARTESIAN_POINT('',(-0.881647041516,1.161589532836)); -#28892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28893 = PCURVE('',#28894,#28933); -#28894 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#28895,#28896) - ,(#28897,#28898) - ,(#28899,#28900) - ,(#28901,#28902) - ,(#28903,#28904) - ,(#28905,#28906) - ,(#28907,#28908) - ,(#28909,#28910) - ,(#28911,#28912) - ,(#28913,#28914) - ,(#28915,#28916) - ,(#28917,#28918) - ,(#28919,#28920) - ,(#28921,#28922) - ,(#28923,#28924) - ,(#28925,#28926) - ,(#28927,#28928) - ,(#28929,#28930) - ,(#28931,#28932 +#31265 = CARTESIAN_POINT('',(-0.809207283737,1.241386453514)); +#31266 = CARTESIAN_POINT('',(-0.809263348524,1.238622576902)); +#31267 = CARTESIAN_POINT('',(-0.8093730225,1.233215879453)); +#31268 = CARTESIAN_POINT('',(-0.810326476104,1.225299512414)); +#31269 = CARTESIAN_POINT('',(-0.811846898403,1.217770111238)); +#31270 = CARTESIAN_POINT('',(-0.814027654649,1.210625317089)); +#31271 = CARTESIAN_POINT('',(-0.816783244251,1.203843604617)); +#31272 = CARTESIAN_POINT('',(-0.820283787924,1.1975038024)); +#31273 = CARTESIAN_POINT('',(-0.824288191857,1.191495890002)); +#31274 = CARTESIAN_POINT('',(-0.828919830996,1.185952021473)); +#31275 = CARTESIAN_POINT('',(-0.834085889254,1.180900835422)); +#31276 = CARTESIAN_POINT('',(-0.839676908992,1.176374870135)); +#31277 = CARTESIAN_POINT('',(-0.84569653596,1.172435374254)); +#31278 = CARTESIAN_POINT('',(-0.852108750047,1.169084249171)); +#31279 = CARTESIAN_POINT('',(-0.858907401761,1.166291241159)); +#31280 = CARTESIAN_POINT('',(-0.866138894496,1.164154479603)); +#31281 = CARTESIAN_POINT('',(-0.873732276169,1.162461986633)); +#31282 = CARTESIAN_POINT('',(-0.878981123638,1.161883400067)); +#31283 = CARTESIAN_POINT('',(-0.881647041516,1.161589532836)); +#31284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31285 = PCURVE('',#31286,#31325); +#31286 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31287,#31288) + ,(#31289,#31290) + ,(#31291,#31292) + ,(#31293,#31294) + ,(#31295,#31296) + ,(#31297,#31298) + ,(#31299,#31300) + ,(#31301,#31302) + ,(#31303,#31304) + ,(#31305,#31306) + ,(#31307,#31308) + ,(#31309,#31310) + ,(#31311,#31312) + ,(#31313,#31314) + ,(#31315,#31316) + ,(#31317,#31318) + ,(#31319,#31320) + ,(#31321,#31322) + ,(#31323,#31324 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.929802345975E-002,0.135560844101,0.199670955647, 0.261716238496,0.322661929947,0.382906923778,0.443032033073, 0.50350078735,0.563724281017,0.623980022053,0.683629386996, 0.743848272486,0.80519184623,0.86764874296,0.932778084231,1.),( 0.E+000,1.),.UNSPECIFIED.); -#28895 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#28896 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); -#28897 = CARTESIAN_POINT('',(0.238622576902,0.782,-0.184263348524)); -#28898 = CARTESIAN_POINT('',(0.238622576902,0.78,-0.184263348524)); -#28899 = CARTESIAN_POINT('',(0.233215879453,0.782,-0.1843730225)); -#28900 = CARTESIAN_POINT('',(0.233215879453,0.78,-0.1843730225)); -#28901 = CARTESIAN_POINT('',(0.225299512414,0.782,-0.185326476104)); -#28902 = CARTESIAN_POINT('',(0.225299512414,0.78,-0.185326476104)); -#28903 = CARTESIAN_POINT('',(0.217770111238,0.782,-0.186846898403)); -#28904 = CARTESIAN_POINT('',(0.217770111238,0.78,-0.186846898403)); -#28905 = CARTESIAN_POINT('',(0.210625317089,0.782,-0.189027654649)); -#28906 = CARTESIAN_POINT('',(0.210625317089,0.78,-0.189027654649)); -#28907 = CARTESIAN_POINT('',(0.203843604617,0.782,-0.191783244251)); -#28908 = CARTESIAN_POINT('',(0.203843604617,0.78,-0.191783244251)); -#28909 = CARTESIAN_POINT('',(0.1975038024,0.782,-0.195283787924)); -#28910 = CARTESIAN_POINT('',(0.1975038024,0.78,-0.195283787924)); -#28911 = CARTESIAN_POINT('',(0.191495890002,0.782,-0.199288191857)); -#28912 = CARTESIAN_POINT('',(0.191495890002,0.78,-0.199288191857)); -#28913 = CARTESIAN_POINT('',(0.185952021473,0.782,-0.203919830996)); -#28914 = CARTESIAN_POINT('',(0.185952021473,0.78,-0.203919830996)); -#28915 = CARTESIAN_POINT('',(0.180900835422,0.782,-0.209085889254)); -#28916 = CARTESIAN_POINT('',(0.180900835422,0.78,-0.209085889254)); -#28917 = CARTESIAN_POINT('',(0.176374870135,0.782,-0.214676908992)); -#28918 = CARTESIAN_POINT('',(0.176374870135,0.78,-0.214676908992)); -#28919 = CARTESIAN_POINT('',(0.172435374254,0.782,-0.22069653596)); -#28920 = CARTESIAN_POINT('',(0.172435374254,0.78,-0.22069653596)); -#28921 = CARTESIAN_POINT('',(0.169084249171,0.782,-0.227108750047)); -#28922 = CARTESIAN_POINT('',(0.169084249171,0.78,-0.227108750047)); -#28923 = CARTESIAN_POINT('',(0.166291241159,0.782,-0.233907401761)); -#28924 = CARTESIAN_POINT('',(0.166291241159,0.78,-0.233907401761)); -#28925 = CARTESIAN_POINT('',(0.164154479603,0.782,-0.241138894496)); -#28926 = CARTESIAN_POINT('',(0.164154479603,0.78,-0.241138894496)); -#28927 = CARTESIAN_POINT('',(0.162461986633,0.782,-0.248732276169)); -#28928 = CARTESIAN_POINT('',(0.162461986633,0.78,-0.248732276169)); -#28929 = CARTESIAN_POINT('',(0.161883400067,0.782,-0.253981123638)); -#28930 = CARTESIAN_POINT('',(0.161883400067,0.78,-0.253981123638)); -#28931 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#28932 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); -#28933 = DEFINITIONAL_REPRESENTATION('',(#28934),#28938); -#28934 = LINE('',#28935,#28936); -#28935 = CARTESIAN_POINT('',(0.E+000,1.)); -#28936 = VECTOR('',#28937,1.); -#28937 = DIRECTION('',(1.,0.E+000)); -#28938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#31287 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#31288 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); +#31289 = CARTESIAN_POINT('',(0.238622576902,0.782,-0.184263348524)); +#31290 = CARTESIAN_POINT('',(0.238622576902,0.78,-0.184263348524)); +#31291 = CARTESIAN_POINT('',(0.233215879453,0.782,-0.1843730225)); +#31292 = CARTESIAN_POINT('',(0.233215879453,0.78,-0.1843730225)); +#31293 = CARTESIAN_POINT('',(0.225299512414,0.782,-0.185326476104)); +#31294 = CARTESIAN_POINT('',(0.225299512414,0.78,-0.185326476104)); +#31295 = CARTESIAN_POINT('',(0.217770111238,0.782,-0.186846898403)); +#31296 = CARTESIAN_POINT('',(0.217770111238,0.78,-0.186846898403)); +#31297 = CARTESIAN_POINT('',(0.210625317089,0.782,-0.189027654649)); +#31298 = CARTESIAN_POINT('',(0.210625317089,0.78,-0.189027654649)); +#31299 = CARTESIAN_POINT('',(0.203843604617,0.782,-0.191783244251)); +#31300 = CARTESIAN_POINT('',(0.203843604617,0.78,-0.191783244251)); +#31301 = CARTESIAN_POINT('',(0.1975038024,0.782,-0.195283787924)); +#31302 = CARTESIAN_POINT('',(0.1975038024,0.78,-0.195283787924)); +#31303 = CARTESIAN_POINT('',(0.191495890002,0.782,-0.199288191857)); +#31304 = CARTESIAN_POINT('',(0.191495890002,0.78,-0.199288191857)); +#31305 = CARTESIAN_POINT('',(0.185952021473,0.782,-0.203919830996)); +#31306 = CARTESIAN_POINT('',(0.185952021473,0.78,-0.203919830996)); +#31307 = CARTESIAN_POINT('',(0.180900835422,0.782,-0.209085889254)); +#31308 = CARTESIAN_POINT('',(0.180900835422,0.78,-0.209085889254)); +#31309 = CARTESIAN_POINT('',(0.176374870135,0.782,-0.214676908992)); +#31310 = CARTESIAN_POINT('',(0.176374870135,0.78,-0.214676908992)); +#31311 = CARTESIAN_POINT('',(0.172435374254,0.782,-0.22069653596)); +#31312 = CARTESIAN_POINT('',(0.172435374254,0.78,-0.22069653596)); +#31313 = CARTESIAN_POINT('',(0.169084249171,0.782,-0.227108750047)); +#31314 = CARTESIAN_POINT('',(0.169084249171,0.78,-0.227108750047)); +#31315 = CARTESIAN_POINT('',(0.166291241159,0.782,-0.233907401761)); +#31316 = CARTESIAN_POINT('',(0.166291241159,0.78,-0.233907401761)); +#31317 = CARTESIAN_POINT('',(0.164154479603,0.782,-0.241138894496)); +#31318 = CARTESIAN_POINT('',(0.164154479603,0.78,-0.241138894496)); +#31319 = CARTESIAN_POINT('',(0.162461986633,0.782,-0.248732276169)); +#31320 = CARTESIAN_POINT('',(0.162461986633,0.78,-0.248732276169)); +#31321 = CARTESIAN_POINT('',(0.161883400067,0.782,-0.253981123638)); +#31322 = CARTESIAN_POINT('',(0.161883400067,0.78,-0.253981123638)); +#31323 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#31324 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); +#31325 = DEFINITIONAL_REPRESENTATION('',(#31326),#31330); +#31326 = LINE('',#31327,#31328); +#31327 = CARTESIAN_POINT('',(0.E+000,1.)); +#31328 = VECTOR('',#31329,1.); +#31329 = DIRECTION('',(1.,0.E+000)); +#31330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31331 = ORIENTED_EDGE('',*,*,#31332,.T.); +#31332 = EDGE_CURVE('',#31234,#31333,#31335,.T.); +#31333 = VERTEX_POINT('',#31334); +#31334 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); +#31335 = SURFACE_CURVE('',#31336,(#31340,#31347),.PCURVE_S1.); +#31336 = LINE('',#31337,#31338); +#31337 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); +#31338 = VECTOR('',#31339,1.); +#31339 = DIRECTION('',(0.99503719021,0.E+000,-9.9503719021E-002)); +#31340 = PCURVE('',#31258,#31341); +#31341 = DEFINITIONAL_REPRESENTATION('',(#31342),#31346); +#31342 = LINE('',#31343,#31344); +#31343 = CARTESIAN_POINT('',(-0.881647041516,1.161589532836)); +#31344 = VECTOR('',#31345,1.); +#31345 = DIRECTION('',(-9.9503719021E-002,0.99503719021)); +#31346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#28939 = ORIENTED_EDGE('',*,*,#28940,.T.); -#28940 = EDGE_CURVE('',#28842,#28941,#28943,.T.); -#28941 = VERTEX_POINT('',#28942); -#28942 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); -#28943 = SURFACE_CURVE('',#28944,(#28948,#28955),.PCURVE_S1.); -#28944 = LINE('',#28945,#28946); -#28945 = CARTESIAN_POINT('',(0.161589532836,0.78,-0.256647041516)); -#28946 = VECTOR('',#28947,1.); -#28947 = DIRECTION('',(0.99503719021,0.E+000,-9.9503719021E-002)); -#28948 = PCURVE('',#28866,#28949); -#28949 = DEFINITIONAL_REPRESENTATION('',(#28950),#28954); -#28950 = LINE('',#28951,#28952); -#28951 = CARTESIAN_POINT('',(-0.881647041516,1.161589532836)); -#28952 = VECTOR('',#28953,1.); -#28953 = DIRECTION('',(-9.9503719021E-002,0.99503719021)); -#28954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28955 = PCURVE('',#28956,#28961); -#28956 = PLANE('',#28957); -#28957 = AXIS2_PLACEMENT_3D('',#28958,#28959,#28960); -#28958 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#28959 = DIRECTION('',(-9.9503719021E-002,0.E+000,-0.99503719021)); -#28960 = DIRECTION('',(-0.99503719021,0.E+000,9.9503719021E-002)); -#28961 = DEFINITIONAL_REPRESENTATION('',(#28962),#28966); -#28962 = LINE('',#28963,#28964); -#28963 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#28964 = VECTOR('',#28965,1.); -#28965 = DIRECTION('',(-1.,0.E+000)); -#28966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#28967 = ORIENTED_EDGE('',*,*,#28968,.T.); -#28968 = EDGE_CURVE('',#28941,#28969,#28971,.T.); -#28969 = VERTEX_POINT('',#28970); -#28970 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); -#28971 = SURFACE_CURVE('',#28972,(#28992,#29015),.PCURVE_S1.); -#28972 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#28973,#28974,#28975,#28976, - #28977,#28978,#28979,#28980,#28981,#28982,#28983,#28984,#28985, - #28986,#28987,#28988,#28989,#28990,#28991),.UNSPECIFIED.,.F.,.F.,(4, +#31347 = PCURVE('',#31348,#31353); +#31348 = PLANE('',#31349); +#31349 = AXIS2_PLACEMENT_3D('',#31350,#31351,#31352); +#31350 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#31351 = DIRECTION('',(-9.9503719021E-002,0.E+000,-0.99503719021)); +#31352 = DIRECTION('',(-0.99503719021,0.E+000,9.9503719021E-002)); +#31353 = DEFINITIONAL_REPRESENTATION('',(#31354),#31358); +#31354 = LINE('',#31355,#31356); +#31355 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31356 = VECTOR('',#31357,1.); +#31357 = DIRECTION('',(-1.,0.E+000)); +#31358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31359 = ORIENTED_EDGE('',*,*,#31360,.T.); +#31360 = EDGE_CURVE('',#31333,#31361,#31363,.T.); +#31361 = VERTEX_POINT('',#31362); +#31362 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); +#31363 = SURFACE_CURVE('',#31364,(#31384,#31407),.PCURVE_S1.); +#31364 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31365,#31366,#31367,#31368, + #31369,#31370,#31371,#31372,#31373,#31374,#31375,#31376,#31377, + #31378,#31379,#31380,#31381,#31382,#31383),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.736133711898E-002, 0.150479832281,0.219977236852,0.286680996862,0.349678494186, 0.410679625017,0.469427113519,0.526755701427,0.583141980835, 0.638824427779,0.695263470404,0.752695804899,0.810849183335, 0.871356303636,0.934436430984,1.),.UNSPECIFIED.); -#28973 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); -#28974 = CARTESIAN_POINT('',(0.194842726066,0.78,-0.258084492877)); -#28975 = CARTESIAN_POINT('',(0.195476906297,0.78,-0.254475714102)); -#28976 = CARTESIAN_POINT('',(0.196685406815,0.78,-0.249251899786)); -#28977 = CARTESIAN_POINT('',(0.198254904982,0.78,-0.244398830275)); -#28978 = CARTESIAN_POINT('',(0.200018408963,0.78,-0.239874475214)); -#28979 = CARTESIAN_POINT('',(0.202114630955,0.78,-0.235726673994)); -#28980 = CARTESIAN_POINT('',(0.20438590485,0.78,-0.231889935001)); -#28981 = CARTESIAN_POINT('',(0.20706440823,0.78,-0.228500450512)); -#28982 = CARTESIAN_POINT('',(0.209880494901,0.78,-0.225380947289)); -#28983 = CARTESIAN_POINT('',(0.2129713652,0.78,-0.222632113258)); -#28984 = CARTESIAN_POINT('',(0.216366843711,0.78,-0.220314751341)); -#28985 = CARTESIAN_POINT('',(0.219972194359,0.78,-0.218292993394)); -#28986 = CARTESIAN_POINT('',(0.223831328955,0.78,-0.216637667807)); -#28987 = CARTESIAN_POINT('',(0.227950162072,0.78,-0.215426056656)); -#28988 = CARTESIAN_POINT('',(0.232276271971,0.78,-0.214467880234)); -#28989 = CARTESIAN_POINT('',(0.236865365146,0.78,-0.213985059654)); -#28990 = CARTESIAN_POINT('',(0.239996472098,0.78,-0.213890117565)); -#28991 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); -#28992 = PCURVE('',#28866,#28993); -#28993 = DEFINITIONAL_REPRESENTATION('',(#28994),#29014); -#28994 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#28995,#28996,#28997,#28998, - #28999,#29000,#29001,#29002,#29003,#29004,#29005,#29006,#29007, - #29008,#29009,#29010,#29011,#29012,#29013),.UNSPECIFIED.,.F.,.F.,(4, +#31365 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); +#31366 = CARTESIAN_POINT('',(0.194842726066,0.78,-0.258084492877)); +#31367 = CARTESIAN_POINT('',(0.195476906297,0.78,-0.254475714102)); +#31368 = CARTESIAN_POINT('',(0.196685406815,0.78,-0.249251899786)); +#31369 = CARTESIAN_POINT('',(0.198254904982,0.78,-0.244398830275)); +#31370 = CARTESIAN_POINT('',(0.200018408963,0.78,-0.239874475214)); +#31371 = CARTESIAN_POINT('',(0.202114630955,0.78,-0.235726673994)); +#31372 = CARTESIAN_POINT('',(0.20438590485,0.78,-0.231889935001)); +#31373 = CARTESIAN_POINT('',(0.20706440823,0.78,-0.228500450512)); +#31374 = CARTESIAN_POINT('',(0.209880494901,0.78,-0.225380947289)); +#31375 = CARTESIAN_POINT('',(0.2129713652,0.78,-0.222632113258)); +#31376 = CARTESIAN_POINT('',(0.216366843711,0.78,-0.220314751341)); +#31377 = CARTESIAN_POINT('',(0.219972194359,0.78,-0.218292993394)); +#31378 = CARTESIAN_POINT('',(0.223831328955,0.78,-0.216637667807)); +#31379 = CARTESIAN_POINT('',(0.227950162072,0.78,-0.215426056656)); +#31380 = CARTESIAN_POINT('',(0.232276271971,0.78,-0.214467880234)); +#31381 = CARTESIAN_POINT('',(0.236865365146,0.78,-0.213985059654)); +#31382 = CARTESIAN_POINT('',(0.239996472098,0.78,-0.213890117565)); +#31383 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); +#31384 = PCURVE('',#31258,#31385); +#31385 = DEFINITIONAL_REPRESENTATION('',(#31386),#31406); +#31386 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31387,#31388,#31389,#31390, + #31391,#31392,#31393,#31394,#31395,#31396,#31397,#31398,#31399, + #31400,#31401,#31402,#31403,#31404,#31405),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.736133711898E-002, 0.150479832281,0.219977236852,0.286680996862,0.349678494186, 0.410679625017,0.469427113519,0.526755701427,0.583141980835, 0.638824427779,0.695263470404,0.752695804899,0.810849183335, 0.871356303636,0.934436430984,1.),.UNSPECIFIED.); -#28995 = CARTESIAN_POINT('',(-0.884939757779,1.194516695463)); -#28996 = CARTESIAN_POINT('',(-0.883084492877,1.194842726066)); -#28997 = CARTESIAN_POINT('',(-0.879475714102,1.195476906297)); -#28998 = CARTESIAN_POINT('',(-0.874251899786,1.196685406815)); -#28999 = CARTESIAN_POINT('',(-0.869398830275,1.198254904982)); -#29000 = CARTESIAN_POINT('',(-0.864874475214,1.200018408963)); -#29001 = CARTESIAN_POINT('',(-0.860726673994,1.202114630955)); -#29002 = CARTESIAN_POINT('',(-0.856889935001,1.20438590485)); -#29003 = CARTESIAN_POINT('',(-0.853500450512,1.20706440823)); -#29004 = CARTESIAN_POINT('',(-0.850380947289,1.209880494901)); -#29005 = CARTESIAN_POINT('',(-0.847632113258,1.2129713652)); -#29006 = CARTESIAN_POINT('',(-0.845314751341,1.216366843711)); -#29007 = CARTESIAN_POINT('',(-0.843292993394,1.219972194359)); -#29008 = CARTESIAN_POINT('',(-0.841637667807,1.223831328955)); -#29009 = CARTESIAN_POINT('',(-0.840426056656,1.227950162072)); -#29010 = CARTESIAN_POINT('',(-0.839467880234,1.232276271971)); -#29011 = CARTESIAN_POINT('',(-0.838985059654,1.236865365146)); -#29012 = CARTESIAN_POINT('',(-0.838890117565,1.239996472098)); -#29013 = CARTESIAN_POINT('',(-0.838841730101,1.241592248281)); -#29014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29015 = PCURVE('',#29016,#29055); -#29016 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29017,#29018) - ,(#29019,#29020) - ,(#29021,#29022) - ,(#29023,#29024) - ,(#29025,#29026) - ,(#29027,#29028) - ,(#29029,#29030) - ,(#29031,#29032) - ,(#29033,#29034) - ,(#29035,#29036) - ,(#29037,#29038) - ,(#29039,#29040) - ,(#29041,#29042) - ,(#29043,#29044) - ,(#29045,#29046) - ,(#29047,#29048) - ,(#29049,#29050) - ,(#29051,#29052) - ,(#29053,#29054 +#31387 = CARTESIAN_POINT('',(-0.884939757779,1.194516695463)); +#31388 = CARTESIAN_POINT('',(-0.883084492877,1.194842726066)); +#31389 = CARTESIAN_POINT('',(-0.879475714102,1.195476906297)); +#31390 = CARTESIAN_POINT('',(-0.874251899786,1.196685406815)); +#31391 = CARTESIAN_POINT('',(-0.869398830275,1.198254904982)); +#31392 = CARTESIAN_POINT('',(-0.864874475214,1.200018408963)); +#31393 = CARTESIAN_POINT('',(-0.860726673994,1.202114630955)); +#31394 = CARTESIAN_POINT('',(-0.856889935001,1.20438590485)); +#31395 = CARTESIAN_POINT('',(-0.853500450512,1.20706440823)); +#31396 = CARTESIAN_POINT('',(-0.850380947289,1.209880494901)); +#31397 = CARTESIAN_POINT('',(-0.847632113258,1.2129713652)); +#31398 = CARTESIAN_POINT('',(-0.845314751341,1.216366843711)); +#31399 = CARTESIAN_POINT('',(-0.843292993394,1.219972194359)); +#31400 = CARTESIAN_POINT('',(-0.841637667807,1.223831328955)); +#31401 = CARTESIAN_POINT('',(-0.840426056656,1.227950162072)); +#31402 = CARTESIAN_POINT('',(-0.839467880234,1.232276271971)); +#31403 = CARTESIAN_POINT('',(-0.838985059654,1.236865365146)); +#31404 = CARTESIAN_POINT('',(-0.838890117565,1.239996472098)); +#31405 = CARTESIAN_POINT('',(-0.838841730101,1.241592248281)); +#31406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31407 = PCURVE('',#31408,#31447); +#31408 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31409,#31410) + ,(#31411,#31412) + ,(#31413,#31414) + ,(#31415,#31416) + ,(#31417,#31418) + ,(#31419,#31420) + ,(#31421,#31422) + ,(#31423,#31424) + ,(#31425,#31426) + ,(#31427,#31428) + ,(#31429,#31430) + ,(#31431,#31432) + ,(#31433,#31434) + ,(#31435,#31436) + ,(#31437,#31438) + ,(#31439,#31440) + ,(#31441,#31442) + ,(#31443,#31444) + ,(#31445,#31446 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.736133711898E-002,0.150479832281,0.219977236852, 0.286680996862,0.349678494186,0.410679625017,0.469427113519, 0.526755701427,0.583141980835,0.638824427779,0.695263470404, 0.752695804899,0.810849183335,0.871356303636,0.934436430984,1.),( 0.E+000,1.),.UNSPECIFIED.); -#29017 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); -#29018 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); -#29019 = CARTESIAN_POINT('',(0.194842726066,0.782,-0.258084492877)); -#29020 = CARTESIAN_POINT('',(0.194842726066,0.78,-0.258084492877)); -#29021 = CARTESIAN_POINT('',(0.195476906297,0.782,-0.254475714102)); -#29022 = CARTESIAN_POINT('',(0.195476906297,0.78,-0.254475714102)); -#29023 = CARTESIAN_POINT('',(0.196685406815,0.782,-0.249251899786)); -#29024 = CARTESIAN_POINT('',(0.196685406815,0.78,-0.249251899786)); -#29025 = CARTESIAN_POINT('',(0.198254904982,0.782,-0.244398830275)); -#29026 = CARTESIAN_POINT('',(0.198254904982,0.78,-0.244398830275)); -#29027 = CARTESIAN_POINT('',(0.200018408963,0.782,-0.239874475214)); -#29028 = CARTESIAN_POINT('',(0.200018408963,0.78,-0.239874475214)); -#29029 = CARTESIAN_POINT('',(0.202114630955,0.782,-0.235726673994)); -#29030 = CARTESIAN_POINT('',(0.202114630955,0.78,-0.235726673994)); -#29031 = CARTESIAN_POINT('',(0.20438590485,0.782,-0.231889935001)); -#29032 = CARTESIAN_POINT('',(0.20438590485,0.78,-0.231889935001)); -#29033 = CARTESIAN_POINT('',(0.20706440823,0.782,-0.228500450512)); -#29034 = CARTESIAN_POINT('',(0.20706440823,0.78,-0.228500450512)); -#29035 = CARTESIAN_POINT('',(0.209880494901,0.782,-0.225380947289)); -#29036 = CARTESIAN_POINT('',(0.209880494901,0.78,-0.225380947289)); -#29037 = CARTESIAN_POINT('',(0.2129713652,0.782,-0.222632113258)); -#29038 = CARTESIAN_POINT('',(0.2129713652,0.78,-0.222632113258)); -#29039 = CARTESIAN_POINT('',(0.216366843711,0.782,-0.220314751341)); -#29040 = CARTESIAN_POINT('',(0.216366843711,0.78,-0.220314751341)); -#29041 = CARTESIAN_POINT('',(0.219972194359,0.782,-0.218292993394)); -#29042 = CARTESIAN_POINT('',(0.219972194359,0.78,-0.218292993394)); -#29043 = CARTESIAN_POINT('',(0.223831328955,0.782,-0.216637667807)); -#29044 = CARTESIAN_POINT('',(0.223831328955,0.78,-0.216637667807)); -#29045 = CARTESIAN_POINT('',(0.227950162072,0.782,-0.215426056656)); -#29046 = CARTESIAN_POINT('',(0.227950162072,0.78,-0.215426056656)); -#29047 = CARTESIAN_POINT('',(0.232276271971,0.782,-0.214467880234)); -#29048 = CARTESIAN_POINT('',(0.232276271971,0.78,-0.214467880234)); -#29049 = CARTESIAN_POINT('',(0.236865365146,0.782,-0.213985059654)); -#29050 = CARTESIAN_POINT('',(0.236865365146,0.78,-0.213985059654)); -#29051 = CARTESIAN_POINT('',(0.239996472098,0.782,-0.213890117565)); -#29052 = CARTESIAN_POINT('',(0.239996472098,0.78,-0.213890117565)); -#29053 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#29054 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); -#29055 = DEFINITIONAL_REPRESENTATION('',(#29056),#29060); -#29056 = LINE('',#29057,#29058); -#29057 = CARTESIAN_POINT('',(0.E+000,1.)); -#29058 = VECTOR('',#29059,1.); -#29059 = DIRECTION('',(1.,0.E+000)); -#29060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29061 = ORIENTED_EDGE('',*,*,#29062,.T.); -#29062 = EDGE_CURVE('',#28969,#29063,#29065,.T.); -#29063 = VERTEX_POINT('',#29064); -#29064 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); -#29065 = SURFACE_CURVE('',#29066,(#29086,#29109),.PCURVE_S1.); -#29066 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29067,#29068,#29069,#29070, - #29071,#29072,#29073,#29074,#29075,#29076,#29077,#29078,#29079, - #29080,#29081,#29082,#29083,#29084,#29085),.UNSPECIFIED.,.F.,.F.,(4, +#31409 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); +#31410 = CARTESIAN_POINT('',(0.194516695463,0.78,-0.259939757779)); +#31411 = CARTESIAN_POINT('',(0.194842726066,0.782,-0.258084492877)); +#31412 = CARTESIAN_POINT('',(0.194842726066,0.78,-0.258084492877)); +#31413 = CARTESIAN_POINT('',(0.195476906297,0.782,-0.254475714102)); +#31414 = CARTESIAN_POINT('',(0.195476906297,0.78,-0.254475714102)); +#31415 = CARTESIAN_POINT('',(0.196685406815,0.782,-0.249251899786)); +#31416 = CARTESIAN_POINT('',(0.196685406815,0.78,-0.249251899786)); +#31417 = CARTESIAN_POINT('',(0.198254904982,0.782,-0.244398830275)); +#31418 = CARTESIAN_POINT('',(0.198254904982,0.78,-0.244398830275)); +#31419 = CARTESIAN_POINT('',(0.200018408963,0.782,-0.239874475214)); +#31420 = CARTESIAN_POINT('',(0.200018408963,0.78,-0.239874475214)); +#31421 = CARTESIAN_POINT('',(0.202114630955,0.782,-0.235726673994)); +#31422 = CARTESIAN_POINT('',(0.202114630955,0.78,-0.235726673994)); +#31423 = CARTESIAN_POINT('',(0.20438590485,0.782,-0.231889935001)); +#31424 = CARTESIAN_POINT('',(0.20438590485,0.78,-0.231889935001)); +#31425 = CARTESIAN_POINT('',(0.20706440823,0.782,-0.228500450512)); +#31426 = CARTESIAN_POINT('',(0.20706440823,0.78,-0.228500450512)); +#31427 = CARTESIAN_POINT('',(0.209880494901,0.782,-0.225380947289)); +#31428 = CARTESIAN_POINT('',(0.209880494901,0.78,-0.225380947289)); +#31429 = CARTESIAN_POINT('',(0.2129713652,0.782,-0.222632113258)); +#31430 = CARTESIAN_POINT('',(0.2129713652,0.78,-0.222632113258)); +#31431 = CARTESIAN_POINT('',(0.216366843711,0.782,-0.220314751341)); +#31432 = CARTESIAN_POINT('',(0.216366843711,0.78,-0.220314751341)); +#31433 = CARTESIAN_POINT('',(0.219972194359,0.782,-0.218292993394)); +#31434 = CARTESIAN_POINT('',(0.219972194359,0.78,-0.218292993394)); +#31435 = CARTESIAN_POINT('',(0.223831328955,0.782,-0.216637667807)); +#31436 = CARTESIAN_POINT('',(0.223831328955,0.78,-0.216637667807)); +#31437 = CARTESIAN_POINT('',(0.227950162072,0.782,-0.215426056656)); +#31438 = CARTESIAN_POINT('',(0.227950162072,0.78,-0.215426056656)); +#31439 = CARTESIAN_POINT('',(0.232276271971,0.782,-0.214467880234)); +#31440 = CARTESIAN_POINT('',(0.232276271971,0.78,-0.214467880234)); +#31441 = CARTESIAN_POINT('',(0.236865365146,0.782,-0.213985059654)); +#31442 = CARTESIAN_POINT('',(0.236865365146,0.78,-0.213985059654)); +#31443 = CARTESIAN_POINT('',(0.239996472098,0.782,-0.213890117565)); +#31444 = CARTESIAN_POINT('',(0.239996472098,0.78,-0.213890117565)); +#31445 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#31446 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); +#31447 = DEFINITIONAL_REPRESENTATION('',(#31448),#31452); +#31448 = LINE('',#31449,#31450); +#31449 = CARTESIAN_POINT('',(0.E+000,1.)); +#31450 = VECTOR('',#31451,1.); +#31451 = DIRECTION('',(1.,0.E+000)); +#31452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31453 = ORIENTED_EDGE('',*,*,#31454,.T.); +#31454 = EDGE_CURVE('',#31361,#31455,#31457,.T.); +#31455 = VERTEX_POINT('',#31456); +#31456 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); +#31457 = SURFACE_CURVE('',#31458,(#31478,#31501),.PCURVE_S1.); +#31458 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31459,#31460,#31461,#31462, + #31463,#31464,#31465,#31466,#31467,#31468,#31469,#31470,#31471, + #31472,#31473,#31474,#31475,#31476,#31477),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.580103760947E-002, 0.128676795949,0.188675874952,0.247598436734,0.304849420119, 0.361785899283,0.419522706369,0.478681815421,0.538769503044, 0.598799056013,0.660184281501,0.722951530611,0.787992689105, 0.855403768434,0.926153061284,1.),.UNSPECIFIED.); -#29067 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); -#29068 = CARTESIAN_POINT('',(0.243549908167,0.78,-0.213889032847)); -#29069 = CARTESIAN_POINT('',(0.247378197369,0.78,-0.213981535427)); -#29070 = CARTESIAN_POINT('',(0.252947632967,0.78,-0.214763885084)); -#29071 = CARTESIAN_POINT('',(0.258208415951,0.78,-0.216053889032)); -#29072 = CARTESIAN_POINT('',(0.263135374274,0.78,-0.217859153727)); -#29073 = CARTESIAN_POINT('',(0.26778626697,0.78,-0.220104213983)); -#29074 = CARTESIAN_POINT('',(0.27200680351,0.78,-0.223011158053)); -#29075 = CARTESIAN_POINT('',(0.276027110805,0.78,-0.226278850425)); -#29076 = CARTESIAN_POINT('',(0.279588481171,0.78,-0.230174566874)); -#29077 = CARTESIAN_POINT('',(0.282830328799,0.78,-0.23441570496)); -#29078 = CARTESIAN_POINT('',(0.285628287023,0.78,-0.239045087591)); -#29079 = CARTESIAN_POINT('',(0.287983772535,0.78,-0.243997737718)); -#29080 = CARTESIAN_POINT('',(0.289966833881,0.78,-0.249272705825)); -#29081 = CARTESIAN_POINT('',(0.29143117997,0.78,-0.254900125977)); -#29082 = CARTESIAN_POINT('',(0.292508324801,0.78,-0.260850061369)); -#29083 = CARTESIAN_POINT('',(0.293199808784,0.78,-0.267126302118)); -#29084 = CARTESIAN_POINT('',(0.293264926822,0.78,-0.271428121632)); -#29085 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); -#29086 = PCURVE('',#28866,#29087); -#29087 = DEFINITIONAL_REPRESENTATION('',(#29088),#29108); -#29088 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29089,#29090,#29091,#29092, - #29093,#29094,#29095,#29096,#29097,#29098,#29099,#29100,#29101, - #29102,#29103,#29104,#29105,#29106,#29107),.UNSPECIFIED.,.F.,.F.,(4, +#31459 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); +#31460 = CARTESIAN_POINT('',(0.243549908167,0.78,-0.213889032847)); +#31461 = CARTESIAN_POINT('',(0.247378197369,0.78,-0.213981535427)); +#31462 = CARTESIAN_POINT('',(0.252947632967,0.78,-0.214763885084)); +#31463 = CARTESIAN_POINT('',(0.258208415951,0.78,-0.216053889032)); +#31464 = CARTESIAN_POINT('',(0.263135374274,0.78,-0.217859153727)); +#31465 = CARTESIAN_POINT('',(0.26778626697,0.78,-0.220104213983)); +#31466 = CARTESIAN_POINT('',(0.27200680351,0.78,-0.223011158053)); +#31467 = CARTESIAN_POINT('',(0.276027110805,0.78,-0.226278850425)); +#31468 = CARTESIAN_POINT('',(0.279588481171,0.78,-0.230174566874)); +#31469 = CARTESIAN_POINT('',(0.282830328799,0.78,-0.23441570496)); +#31470 = CARTESIAN_POINT('',(0.285628287023,0.78,-0.239045087591)); +#31471 = CARTESIAN_POINT('',(0.287983772535,0.78,-0.243997737718)); +#31472 = CARTESIAN_POINT('',(0.289966833881,0.78,-0.249272705825)); +#31473 = CARTESIAN_POINT('',(0.29143117997,0.78,-0.254900125977)); +#31474 = CARTESIAN_POINT('',(0.292508324801,0.78,-0.260850061369)); +#31475 = CARTESIAN_POINT('',(0.293199808784,0.78,-0.267126302118)); +#31476 = CARTESIAN_POINT('',(0.293264926822,0.78,-0.271428121632)); +#31477 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); +#31478 = PCURVE('',#31258,#31479); +#31479 = DEFINITIONAL_REPRESENTATION('',(#31480),#31500); +#31480 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31481,#31482,#31483,#31484, + #31485,#31486,#31487,#31488,#31489,#31490,#31491,#31492,#31493, + #31494,#31495,#31496,#31497,#31498,#31499),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.580103760947E-002, 0.128676795949,0.188675874952,0.247598436734,0.304849420119, 0.361785899283,0.419522706369,0.478681815421,0.538769503044, 0.598799056013,0.660184281501,0.722951530611,0.787992689105, 0.855403768434,0.926153061284,1.),.UNSPECIFIED.); -#29089 = CARTESIAN_POINT('',(-0.838841730101,1.241592248281)); -#29090 = CARTESIAN_POINT('',(-0.838889032847,1.243549908167)); -#29091 = CARTESIAN_POINT('',(-0.838981535427,1.247378197369)); -#29092 = CARTESIAN_POINT('',(-0.839763885084,1.252947632967)); -#29093 = CARTESIAN_POINT('',(-0.841053889032,1.258208415951)); -#29094 = CARTESIAN_POINT('',(-0.842859153727,1.263135374274)); -#29095 = CARTESIAN_POINT('',(-0.845104213983,1.26778626697)); -#29096 = CARTESIAN_POINT('',(-0.848011158053,1.27200680351)); -#29097 = CARTESIAN_POINT('',(-0.851278850425,1.276027110805)); -#29098 = CARTESIAN_POINT('',(-0.855174566874,1.279588481171)); -#29099 = CARTESIAN_POINT('',(-0.85941570496,1.282830328799)); -#29100 = CARTESIAN_POINT('',(-0.864045087591,1.285628287023)); -#29101 = CARTESIAN_POINT('',(-0.868997737718,1.287983772535)); -#29102 = CARTESIAN_POINT('',(-0.874272705825,1.289966833881)); -#29103 = CARTESIAN_POINT('',(-0.879900125977,1.29143117997)); -#29104 = CARTESIAN_POINT('',(-0.885850061369,1.292508324801)); -#29105 = CARTESIAN_POINT('',(-0.892126302118,1.293199808784)); -#29106 = CARTESIAN_POINT('',(-0.896428121632,1.293264926822)); -#29107 = CARTESIAN_POINT('',(-0.898625109746,1.293298183343)); -#29108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29109 = PCURVE('',#29110,#29149); -#29110 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29111,#29112) - ,(#29113,#29114) - ,(#29115,#29116) - ,(#29117,#29118) - ,(#29119,#29120) - ,(#29121,#29122) - ,(#29123,#29124) - ,(#29125,#29126) - ,(#29127,#29128) - ,(#29129,#29130) - ,(#29131,#29132) - ,(#29133,#29134) - ,(#29135,#29136) - ,(#29137,#29138) - ,(#29139,#29140) - ,(#29141,#29142) - ,(#29143,#29144) - ,(#29145,#29146) - ,(#29147,#29148 +#31481 = CARTESIAN_POINT('',(-0.838841730101,1.241592248281)); +#31482 = CARTESIAN_POINT('',(-0.838889032847,1.243549908167)); +#31483 = CARTESIAN_POINT('',(-0.838981535427,1.247378197369)); +#31484 = CARTESIAN_POINT('',(-0.839763885084,1.252947632967)); +#31485 = CARTESIAN_POINT('',(-0.841053889032,1.258208415951)); +#31486 = CARTESIAN_POINT('',(-0.842859153727,1.263135374274)); +#31487 = CARTESIAN_POINT('',(-0.845104213983,1.26778626697)); +#31488 = CARTESIAN_POINT('',(-0.848011158053,1.27200680351)); +#31489 = CARTESIAN_POINT('',(-0.851278850425,1.276027110805)); +#31490 = CARTESIAN_POINT('',(-0.855174566874,1.279588481171)); +#31491 = CARTESIAN_POINT('',(-0.85941570496,1.282830328799)); +#31492 = CARTESIAN_POINT('',(-0.864045087591,1.285628287023)); +#31493 = CARTESIAN_POINT('',(-0.868997737718,1.287983772535)); +#31494 = CARTESIAN_POINT('',(-0.874272705825,1.289966833881)); +#31495 = CARTESIAN_POINT('',(-0.879900125977,1.29143117997)); +#31496 = CARTESIAN_POINT('',(-0.885850061369,1.292508324801)); +#31497 = CARTESIAN_POINT('',(-0.892126302118,1.293199808784)); +#31498 = CARTESIAN_POINT('',(-0.896428121632,1.293264926822)); +#31499 = CARTESIAN_POINT('',(-0.898625109746,1.293298183343)); +#31500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31501 = PCURVE('',#31502,#31541); +#31502 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31503,#31504) + ,(#31505,#31506) + ,(#31507,#31508) + ,(#31509,#31510) + ,(#31511,#31512) + ,(#31513,#31514) + ,(#31515,#31516) + ,(#31517,#31518) + ,(#31519,#31520) + ,(#31521,#31522) + ,(#31523,#31524) + ,(#31525,#31526) + ,(#31527,#31528) + ,(#31529,#31530) + ,(#31531,#31532) + ,(#31533,#31534) + ,(#31535,#31536) + ,(#31537,#31538) + ,(#31539,#31540 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.580103760947E-002,0.128676795949,0.188675874952, 0.247598436734,0.304849420119,0.361785899283,0.419522706369, 0.478681815421,0.538769503044,0.598799056013,0.660184281501, 0.722951530611,0.787992689105,0.855403768434,0.926153061284,1.),( 0.E+000,1.),.UNSPECIFIED.); -#29111 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#29112 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); -#29113 = CARTESIAN_POINT('',(0.243549908167,0.782,-0.213889032847)); -#29114 = CARTESIAN_POINT('',(0.243549908167,0.78,-0.213889032847)); -#29115 = CARTESIAN_POINT('',(0.247378197369,0.782,-0.213981535427)); -#29116 = CARTESIAN_POINT('',(0.247378197369,0.78,-0.213981535427)); -#29117 = CARTESIAN_POINT('',(0.252947632967,0.782,-0.214763885084)); -#29118 = CARTESIAN_POINT('',(0.252947632967,0.78,-0.214763885084)); -#29119 = CARTESIAN_POINT('',(0.258208415951,0.782,-0.216053889032)); -#29120 = CARTESIAN_POINT('',(0.258208415951,0.78,-0.216053889032)); -#29121 = CARTESIAN_POINT('',(0.263135374274,0.782,-0.217859153727)); -#29122 = CARTESIAN_POINT('',(0.263135374274,0.78,-0.217859153727)); -#29123 = CARTESIAN_POINT('',(0.26778626697,0.782,-0.220104213983)); -#29124 = CARTESIAN_POINT('',(0.26778626697,0.78,-0.220104213983)); -#29125 = CARTESIAN_POINT('',(0.27200680351,0.782,-0.223011158053)); -#29126 = CARTESIAN_POINT('',(0.27200680351,0.78,-0.223011158053)); -#29127 = CARTESIAN_POINT('',(0.276027110805,0.782,-0.226278850425)); -#29128 = CARTESIAN_POINT('',(0.276027110805,0.78,-0.226278850425)); -#29129 = CARTESIAN_POINT('',(0.279588481171,0.782,-0.230174566874)); -#29130 = CARTESIAN_POINT('',(0.279588481171,0.78,-0.230174566874)); -#29131 = CARTESIAN_POINT('',(0.282830328799,0.782,-0.23441570496)); -#29132 = CARTESIAN_POINT('',(0.282830328799,0.78,-0.23441570496)); -#29133 = CARTESIAN_POINT('',(0.285628287023,0.782,-0.239045087591)); -#29134 = CARTESIAN_POINT('',(0.285628287023,0.78,-0.239045087591)); -#29135 = CARTESIAN_POINT('',(0.287983772535,0.782,-0.243997737718)); -#29136 = CARTESIAN_POINT('',(0.287983772535,0.78,-0.243997737718)); -#29137 = CARTESIAN_POINT('',(0.289966833881,0.782,-0.249272705825)); -#29138 = CARTESIAN_POINT('',(0.289966833881,0.78,-0.249272705825)); -#29139 = CARTESIAN_POINT('',(0.29143117997,0.782,-0.254900125977)); -#29140 = CARTESIAN_POINT('',(0.29143117997,0.78,-0.254900125977)); -#29141 = CARTESIAN_POINT('',(0.292508324801,0.782,-0.260850061369)); -#29142 = CARTESIAN_POINT('',(0.292508324801,0.78,-0.260850061369)); -#29143 = CARTESIAN_POINT('',(0.293199808784,0.782,-0.267126302118)); -#29144 = CARTESIAN_POINT('',(0.293199808784,0.78,-0.267126302118)); -#29145 = CARTESIAN_POINT('',(0.293264926822,0.782,-0.271428121632)); -#29146 = CARTESIAN_POINT('',(0.293264926822,0.78,-0.271428121632)); -#29147 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#29148 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); -#29149 = DEFINITIONAL_REPRESENTATION('',(#29150),#29154); -#29150 = LINE('',#29151,#29152); -#29151 = CARTESIAN_POINT('',(0.E+000,1.)); -#29152 = VECTOR('',#29153,1.); -#29153 = DIRECTION('',(1.,0.E+000)); -#29154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29155 = ORIENTED_EDGE('',*,*,#29156,.T.); -#29156 = EDGE_CURVE('',#29063,#29157,#29159,.T.); -#29157 = VERTEX_POINT('',#29158); -#29158 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); -#29159 = SURFACE_CURVE('',#29160,(#29180,#29203),.PCURVE_S1.); -#29160 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29161,#29162,#29163,#29164, - #29165,#29166,#29167,#29168,#29169,#29170,#29171,#29172,#29173, - #29174,#29175,#29176,#29177,#29178,#29179),.UNSPECIFIED.,.F.,.F.,(4, +#31503 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#31504 = CARTESIAN_POINT('',(0.241592248281,0.78,-0.213841730101)); +#31505 = CARTESIAN_POINT('',(0.243549908167,0.782,-0.213889032847)); +#31506 = CARTESIAN_POINT('',(0.243549908167,0.78,-0.213889032847)); +#31507 = CARTESIAN_POINT('',(0.247378197369,0.782,-0.213981535427)); +#31508 = CARTESIAN_POINT('',(0.247378197369,0.78,-0.213981535427)); +#31509 = CARTESIAN_POINT('',(0.252947632967,0.782,-0.214763885084)); +#31510 = CARTESIAN_POINT('',(0.252947632967,0.78,-0.214763885084)); +#31511 = CARTESIAN_POINT('',(0.258208415951,0.782,-0.216053889032)); +#31512 = CARTESIAN_POINT('',(0.258208415951,0.78,-0.216053889032)); +#31513 = CARTESIAN_POINT('',(0.263135374274,0.782,-0.217859153727)); +#31514 = CARTESIAN_POINT('',(0.263135374274,0.78,-0.217859153727)); +#31515 = CARTESIAN_POINT('',(0.26778626697,0.782,-0.220104213983)); +#31516 = CARTESIAN_POINT('',(0.26778626697,0.78,-0.220104213983)); +#31517 = CARTESIAN_POINT('',(0.27200680351,0.782,-0.223011158053)); +#31518 = CARTESIAN_POINT('',(0.27200680351,0.78,-0.223011158053)); +#31519 = CARTESIAN_POINT('',(0.276027110805,0.782,-0.226278850425)); +#31520 = CARTESIAN_POINT('',(0.276027110805,0.78,-0.226278850425)); +#31521 = CARTESIAN_POINT('',(0.279588481171,0.782,-0.230174566874)); +#31522 = CARTESIAN_POINT('',(0.279588481171,0.78,-0.230174566874)); +#31523 = CARTESIAN_POINT('',(0.282830328799,0.782,-0.23441570496)); +#31524 = CARTESIAN_POINT('',(0.282830328799,0.78,-0.23441570496)); +#31525 = CARTESIAN_POINT('',(0.285628287023,0.782,-0.239045087591)); +#31526 = CARTESIAN_POINT('',(0.285628287023,0.78,-0.239045087591)); +#31527 = CARTESIAN_POINT('',(0.287983772535,0.782,-0.243997737718)); +#31528 = CARTESIAN_POINT('',(0.287983772535,0.78,-0.243997737718)); +#31529 = CARTESIAN_POINT('',(0.289966833881,0.782,-0.249272705825)); +#31530 = CARTESIAN_POINT('',(0.289966833881,0.78,-0.249272705825)); +#31531 = CARTESIAN_POINT('',(0.29143117997,0.782,-0.254900125977)); +#31532 = CARTESIAN_POINT('',(0.29143117997,0.78,-0.254900125977)); +#31533 = CARTESIAN_POINT('',(0.292508324801,0.782,-0.260850061369)); +#31534 = CARTESIAN_POINT('',(0.292508324801,0.78,-0.260850061369)); +#31535 = CARTESIAN_POINT('',(0.293199808784,0.782,-0.267126302118)); +#31536 = CARTESIAN_POINT('',(0.293199808784,0.78,-0.267126302118)); +#31537 = CARTESIAN_POINT('',(0.293264926822,0.782,-0.271428121632)); +#31538 = CARTESIAN_POINT('',(0.293264926822,0.78,-0.271428121632)); +#31539 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#31540 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); +#31541 = DEFINITIONAL_REPRESENTATION('',(#31542),#31546); +#31542 = LINE('',#31543,#31544); +#31543 = CARTESIAN_POINT('',(0.E+000,1.)); +#31544 = VECTOR('',#31545,1.); +#31545 = DIRECTION('',(1.,0.E+000)); +#31546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31547 = ORIENTED_EDGE('',*,*,#31548,.T.); +#31548 = EDGE_CURVE('',#31455,#31549,#31551,.T.); +#31549 = VERTEX_POINT('',#31550); +#31550 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); +#31551 = SURFACE_CURVE('',#31552,(#31572,#31595),.PCURVE_S1.); +#31552 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31553,#31554,#31555,#31556, + #31557,#31558,#31559,#31560,#31561,#31562,#31563,#31564,#31565, + #31566,#31567,#31568,#31569,#31570,#31571),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.286593345654E-002, 0.141886871964,0.207452626415,0.27043768,0.331640872248, 0.390107577493,0.448069286949,0.505502951925,0.562488152834, 0.619084328885,0.676415530692,0.735452360451,0.796240769449, 0.860405678089,0.928304927285,1.),.UNSPECIFIED.); -#29161 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); -#29162 = CARTESIAN_POINT('',(0.29326038452,0.78,-0.27571881079)); -#29163 = CARTESIAN_POINT('',(0.293186781443,0.78,-0.279795732308)); -#29164 = CARTESIAN_POINT('',(0.292566923459,0.78,-0.285732407895)); -#29165 = CARTESIAN_POINT('',(0.291521150064,0.78,-0.291314679553)); -#29166 = CARTESIAN_POINT('',(0.290168017209,0.78,-0.296604073658)); -#29167 = CARTESIAN_POINT('',(0.28830289424,0.78,-0.301517936914)); -#29168 = CARTESIAN_POINT('',(0.286090753377,0.78,-0.306127515532)); -#29169 = CARTESIAN_POINT('',(0.283380787846,0.78,-0.310334980685)); -#29170 = CARTESIAN_POINT('',(0.28036577237,0.78,-0.314271337599)); -#29171 = CARTESIAN_POINT('',(0.276922244051,0.78,-0.317800122959)); -#29172 = CARTESIAN_POINT('',(0.273003681401,0.78,-0.320779735243)); -#29173 = CARTESIAN_POINT('',(0.268763807319,0.78,-0.32338749773)); -#29174 = CARTESIAN_POINT('',(0.264117226398,0.78,-0.325502230425)); -#29175 = CARTESIAN_POINT('',(0.259061202504,0.78,-0.327073397351)); -#29176 = CARTESIAN_POINT('',(0.253645978584,0.78,-0.328282268926)); -#29177 = CARTESIAN_POINT('',(0.247815363669,0.78,-0.328918085874)); -#29178 = CARTESIAN_POINT('',(0.243805859365,0.78,-0.329029551174)); -#29179 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); -#29180 = PCURVE('',#28866,#29181); -#29181 = DEFINITIONAL_REPRESENTATION('',(#29182),#29202); -#29182 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29183,#29184,#29185,#29186, - #29187,#29188,#29189,#29190,#29191,#29192,#29193,#29194,#29195, - #29196,#29197,#29198,#29199,#29200,#29201),.UNSPECIFIED.,.F.,.F.,(4, +#31553 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); +#31554 = CARTESIAN_POINT('',(0.29326038452,0.78,-0.27571881079)); +#31555 = CARTESIAN_POINT('',(0.293186781443,0.78,-0.279795732308)); +#31556 = CARTESIAN_POINT('',(0.292566923459,0.78,-0.285732407895)); +#31557 = CARTESIAN_POINT('',(0.291521150064,0.78,-0.291314679553)); +#31558 = CARTESIAN_POINT('',(0.290168017209,0.78,-0.296604073658)); +#31559 = CARTESIAN_POINT('',(0.28830289424,0.78,-0.301517936914)); +#31560 = CARTESIAN_POINT('',(0.286090753377,0.78,-0.306127515532)); +#31561 = CARTESIAN_POINT('',(0.283380787846,0.78,-0.310334980685)); +#31562 = CARTESIAN_POINT('',(0.28036577237,0.78,-0.314271337599)); +#31563 = CARTESIAN_POINT('',(0.276922244051,0.78,-0.317800122959)); +#31564 = CARTESIAN_POINT('',(0.273003681401,0.78,-0.320779735243)); +#31565 = CARTESIAN_POINT('',(0.268763807319,0.78,-0.32338749773)); +#31566 = CARTESIAN_POINT('',(0.264117226398,0.78,-0.325502230425)); +#31567 = CARTESIAN_POINT('',(0.259061202504,0.78,-0.327073397351)); +#31568 = CARTESIAN_POINT('',(0.253645978584,0.78,-0.328282268926)); +#31569 = CARTESIAN_POINT('',(0.247815363669,0.78,-0.328918085874)); +#31570 = CARTESIAN_POINT('',(0.243805859365,0.78,-0.329029551174)); +#31571 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); +#31572 = PCURVE('',#31258,#31573); +#31573 = DEFINITIONAL_REPRESENTATION('',(#31574),#31594); +#31574 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31575,#31576,#31577,#31578, + #31579,#31580,#31581,#31582,#31583,#31584,#31585,#31586,#31587, + #31588,#31589,#31590,#31591,#31592,#31593),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.286593345654E-002, 0.141886871964,0.207452626415,0.27043768,0.331640872248, 0.390107577493,0.448069286949,0.505502951925,0.562488152834, 0.619084328885,0.676415530692,0.735452360451,0.796240769449, 0.860405678089,0.928304927285,1.),.UNSPECIFIED.); -#29183 = CARTESIAN_POINT('',(-0.898625109746,1.293298183343)); -#29184 = CARTESIAN_POINT('',(-0.90071881079,1.29326038452)); -#29185 = CARTESIAN_POINT('',(-0.904795732308,1.293186781443)); -#29186 = CARTESIAN_POINT('',(-0.910732407895,1.292566923459)); -#29187 = CARTESIAN_POINT('',(-0.916314679553,1.291521150064)); -#29188 = CARTESIAN_POINT('',(-0.921604073658,1.290168017209)); -#29189 = CARTESIAN_POINT('',(-0.926517936914,1.28830289424)); -#29190 = CARTESIAN_POINT('',(-0.931127515532,1.286090753377)); -#29191 = CARTESIAN_POINT('',(-0.935334980685,1.283380787846)); -#29192 = CARTESIAN_POINT('',(-0.939271337599,1.28036577237)); -#29193 = CARTESIAN_POINT('',(-0.942800122959,1.276922244051)); -#29194 = CARTESIAN_POINT('',(-0.945779735243,1.273003681401)); -#29195 = CARTESIAN_POINT('',(-0.94838749773,1.268763807319)); -#29196 = CARTESIAN_POINT('',(-0.950502230425,1.264117226398)); -#29197 = CARTESIAN_POINT('',(-0.952073397351,1.259061202504)); -#29198 = CARTESIAN_POINT('',(-0.953282268926,1.253645978584)); -#29199 = CARTESIAN_POINT('',(-0.953918085874,1.247815363669)); -#29200 = CARTESIAN_POINT('',(-0.954029551174,1.243805859365)); -#29201 = CARTESIAN_POINT('',(-0.954086799296,1.241746594356)); -#29202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29203 = PCURVE('',#29204,#29243); -#29204 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29205,#29206) - ,(#29207,#29208) - ,(#29209,#29210) - ,(#29211,#29212) - ,(#29213,#29214) - ,(#29215,#29216) - ,(#29217,#29218) - ,(#29219,#29220) - ,(#29221,#29222) - ,(#29223,#29224) - ,(#29225,#29226) - ,(#29227,#29228) - ,(#29229,#29230) - ,(#29231,#29232) - ,(#29233,#29234) - ,(#29235,#29236) - ,(#29237,#29238) - ,(#29239,#29240) - ,(#29241,#29242 +#31575 = CARTESIAN_POINT('',(-0.898625109746,1.293298183343)); +#31576 = CARTESIAN_POINT('',(-0.90071881079,1.29326038452)); +#31577 = CARTESIAN_POINT('',(-0.904795732308,1.293186781443)); +#31578 = CARTESIAN_POINT('',(-0.910732407895,1.292566923459)); +#31579 = CARTESIAN_POINT('',(-0.916314679553,1.291521150064)); +#31580 = CARTESIAN_POINT('',(-0.921604073658,1.290168017209)); +#31581 = CARTESIAN_POINT('',(-0.926517936914,1.28830289424)); +#31582 = CARTESIAN_POINT('',(-0.931127515532,1.286090753377)); +#31583 = CARTESIAN_POINT('',(-0.935334980685,1.283380787846)); +#31584 = CARTESIAN_POINT('',(-0.939271337599,1.28036577237)); +#31585 = CARTESIAN_POINT('',(-0.942800122959,1.276922244051)); +#31586 = CARTESIAN_POINT('',(-0.945779735243,1.273003681401)); +#31587 = CARTESIAN_POINT('',(-0.94838749773,1.268763807319)); +#31588 = CARTESIAN_POINT('',(-0.950502230425,1.264117226398)); +#31589 = CARTESIAN_POINT('',(-0.952073397351,1.259061202504)); +#31590 = CARTESIAN_POINT('',(-0.953282268926,1.253645978584)); +#31591 = CARTESIAN_POINT('',(-0.953918085874,1.247815363669)); +#31592 = CARTESIAN_POINT('',(-0.954029551174,1.243805859365)); +#31593 = CARTESIAN_POINT('',(-0.954086799296,1.241746594356)); +#31594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31595 = PCURVE('',#31596,#31635); +#31596 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31597,#31598) + ,(#31599,#31600) + ,(#31601,#31602) + ,(#31603,#31604) + ,(#31605,#31606) + ,(#31607,#31608) + ,(#31609,#31610) + ,(#31611,#31612) + ,(#31613,#31614) + ,(#31615,#31616) + ,(#31617,#31618) + ,(#31619,#31620) + ,(#31621,#31622) + ,(#31623,#31624) + ,(#31625,#31626) + ,(#31627,#31628) + ,(#31629,#31630) + ,(#31631,#31632) + ,(#31633,#31634 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.286593345654E-002,0.141886871964,0.207452626415, 0.27043768,0.331640872248,0.390107577493,0.448069286949, 0.505502951925,0.562488152834,0.619084328885,0.676415530692, 0.735452360451,0.796240769449,0.860405678089,0.928304927285,1.),( 0.E+000,1.),.UNSPECIFIED.); -#29205 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#29206 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); -#29207 = CARTESIAN_POINT('',(0.29326038452,0.782,-0.27571881079)); -#29208 = CARTESIAN_POINT('',(0.29326038452,0.78,-0.27571881079)); -#29209 = CARTESIAN_POINT('',(0.293186781443,0.782,-0.279795732308)); -#29210 = CARTESIAN_POINT('',(0.293186781443,0.78,-0.279795732308)); -#29211 = CARTESIAN_POINT('',(0.292566923459,0.782,-0.285732407895)); -#29212 = CARTESIAN_POINT('',(0.292566923459,0.78,-0.285732407895)); -#29213 = CARTESIAN_POINT('',(0.291521150064,0.782,-0.291314679553)); -#29214 = CARTESIAN_POINT('',(0.291521150064,0.78,-0.291314679553)); -#29215 = CARTESIAN_POINT('',(0.290168017209,0.782,-0.296604073658)); -#29216 = CARTESIAN_POINT('',(0.290168017209,0.78,-0.296604073658)); -#29217 = CARTESIAN_POINT('',(0.28830289424,0.782,-0.301517936914)); -#29218 = CARTESIAN_POINT('',(0.28830289424,0.78,-0.301517936914)); -#29219 = CARTESIAN_POINT('',(0.286090753377,0.782,-0.306127515532)); -#29220 = CARTESIAN_POINT('',(0.286090753377,0.78,-0.306127515532)); -#29221 = CARTESIAN_POINT('',(0.283380787846,0.782,-0.310334980685)); -#29222 = CARTESIAN_POINT('',(0.283380787846,0.78,-0.310334980685)); -#29223 = CARTESIAN_POINT('',(0.28036577237,0.782,-0.314271337599)); -#29224 = CARTESIAN_POINT('',(0.28036577237,0.78,-0.314271337599)); -#29225 = CARTESIAN_POINT('',(0.276922244051,0.782,-0.317800122959)); -#29226 = CARTESIAN_POINT('',(0.276922244051,0.78,-0.317800122959)); -#29227 = CARTESIAN_POINT('',(0.273003681401,0.782,-0.320779735243)); -#29228 = CARTESIAN_POINT('',(0.273003681401,0.78,-0.320779735243)); -#29229 = CARTESIAN_POINT('',(0.268763807319,0.782,-0.32338749773)); -#29230 = CARTESIAN_POINT('',(0.268763807319,0.78,-0.32338749773)); -#29231 = CARTESIAN_POINT('',(0.264117226398,0.782,-0.325502230425)); -#29232 = CARTESIAN_POINT('',(0.264117226398,0.78,-0.325502230425)); -#29233 = CARTESIAN_POINT('',(0.259061202504,0.782,-0.327073397351)); -#29234 = CARTESIAN_POINT('',(0.259061202504,0.78,-0.327073397351)); -#29235 = CARTESIAN_POINT('',(0.253645978584,0.782,-0.328282268926)); -#29236 = CARTESIAN_POINT('',(0.253645978584,0.78,-0.328282268926)); -#29237 = CARTESIAN_POINT('',(0.247815363669,0.782,-0.328918085874)); -#29238 = CARTESIAN_POINT('',(0.247815363669,0.78,-0.328918085874)); -#29239 = CARTESIAN_POINT('',(0.243805859365,0.782,-0.329029551174)); -#29240 = CARTESIAN_POINT('',(0.243805859365,0.78,-0.329029551174)); -#29241 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#29242 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); -#29243 = DEFINITIONAL_REPRESENTATION('',(#29244),#29248); -#29244 = LINE('',#29245,#29246); -#29245 = CARTESIAN_POINT('',(0.E+000,1.)); -#29246 = VECTOR('',#29247,1.); -#29247 = DIRECTION('',(1.,0.E+000)); -#29248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29249 = ORIENTED_EDGE('',*,*,#29250,.T.); -#29250 = EDGE_CURVE('',#29157,#29251,#29253,.T.); -#29251 = VERTEX_POINT('',#29252); -#29252 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); -#29253 = SURFACE_CURVE('',#29254,(#29266,#29281),.PCURVE_S1.); -#29254 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29255,#29256,#29257,#29258, - #29259,#29260,#29261,#29262,#29263,#29264,#29265),.UNSPECIFIED.,.F., +#31597 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#31598 = CARTESIAN_POINT('',(0.293298183343,0.78,-0.273625109746)); +#31599 = CARTESIAN_POINT('',(0.29326038452,0.782,-0.27571881079)); +#31600 = CARTESIAN_POINT('',(0.29326038452,0.78,-0.27571881079)); +#31601 = CARTESIAN_POINT('',(0.293186781443,0.782,-0.279795732308)); +#31602 = CARTESIAN_POINT('',(0.293186781443,0.78,-0.279795732308)); +#31603 = CARTESIAN_POINT('',(0.292566923459,0.782,-0.285732407895)); +#31604 = CARTESIAN_POINT('',(0.292566923459,0.78,-0.285732407895)); +#31605 = CARTESIAN_POINT('',(0.291521150064,0.782,-0.291314679553)); +#31606 = CARTESIAN_POINT('',(0.291521150064,0.78,-0.291314679553)); +#31607 = CARTESIAN_POINT('',(0.290168017209,0.782,-0.296604073658)); +#31608 = CARTESIAN_POINT('',(0.290168017209,0.78,-0.296604073658)); +#31609 = CARTESIAN_POINT('',(0.28830289424,0.782,-0.301517936914)); +#31610 = CARTESIAN_POINT('',(0.28830289424,0.78,-0.301517936914)); +#31611 = CARTESIAN_POINT('',(0.286090753377,0.782,-0.306127515532)); +#31612 = CARTESIAN_POINT('',(0.286090753377,0.78,-0.306127515532)); +#31613 = CARTESIAN_POINT('',(0.283380787846,0.782,-0.310334980685)); +#31614 = CARTESIAN_POINT('',(0.283380787846,0.78,-0.310334980685)); +#31615 = CARTESIAN_POINT('',(0.28036577237,0.782,-0.314271337599)); +#31616 = CARTESIAN_POINT('',(0.28036577237,0.78,-0.314271337599)); +#31617 = CARTESIAN_POINT('',(0.276922244051,0.782,-0.317800122959)); +#31618 = CARTESIAN_POINT('',(0.276922244051,0.78,-0.317800122959)); +#31619 = CARTESIAN_POINT('',(0.273003681401,0.782,-0.320779735243)); +#31620 = CARTESIAN_POINT('',(0.273003681401,0.78,-0.320779735243)); +#31621 = CARTESIAN_POINT('',(0.268763807319,0.782,-0.32338749773)); +#31622 = CARTESIAN_POINT('',(0.268763807319,0.78,-0.32338749773)); +#31623 = CARTESIAN_POINT('',(0.264117226398,0.782,-0.325502230425)); +#31624 = CARTESIAN_POINT('',(0.264117226398,0.78,-0.325502230425)); +#31625 = CARTESIAN_POINT('',(0.259061202504,0.782,-0.327073397351)); +#31626 = CARTESIAN_POINT('',(0.259061202504,0.78,-0.327073397351)); +#31627 = CARTESIAN_POINT('',(0.253645978584,0.782,-0.328282268926)); +#31628 = CARTESIAN_POINT('',(0.253645978584,0.78,-0.328282268926)); +#31629 = CARTESIAN_POINT('',(0.247815363669,0.782,-0.328918085874)); +#31630 = CARTESIAN_POINT('',(0.247815363669,0.78,-0.328918085874)); +#31631 = CARTESIAN_POINT('',(0.243805859365,0.782,-0.329029551174)); +#31632 = CARTESIAN_POINT('',(0.243805859365,0.78,-0.329029551174)); +#31633 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#31634 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); +#31635 = DEFINITIONAL_REPRESENTATION('',(#31636),#31640); +#31636 = LINE('',#31637,#31638); +#31637 = CARTESIAN_POINT('',(0.E+000,1.)); +#31638 = VECTOR('',#31639,1.); +#31639 = DIRECTION('',(1.,0.E+000)); +#31640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31641 = ORIENTED_EDGE('',*,*,#31642,.T.); +#31642 = EDGE_CURVE('',#31549,#31643,#31645,.T.); +#31643 = VERTEX_POINT('',#31644); +#31644 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); +#31645 = SURFACE_CURVE('',#31646,(#31658,#31673),.PCURVE_S1.); +#31646 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31647,#31648,#31649,#31650, + #31651,#31652,#31653,#31654,#31655,#31656,#31657),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.147859636731,0.28356132194, 0.412369396139,0.534236355888,0.652691629312,0.768663059498, 0.88365240186,1.),.UNSPECIFIED.); -#29255 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); -#29256 = CARTESIAN_POINT('',(0.239185998247,0.78,-0.329011896854)); -#29257 = CARTESIAN_POINT('',(0.234275354387,0.78,-0.328868250923)); -#29258 = CARTESIAN_POINT('',(0.227219264145,0.78,-0.32765980921)); -#29259 = CARTESIAN_POINT('',(0.220795849733,0.78,-0.325707725562)); -#29260 = CARTESIAN_POINT('',(0.215077836823,0.78,-0.322798382377)); -#29261 = CARTESIAN_POINT('',(0.209969074838,0.78,-0.319322694065)); -#29262 = CARTESIAN_POINT('',(0.205363431998,0.78,-0.315389795065)); -#29263 = CARTESIAN_POINT('',(0.201222930099,0.78,-0.311002344362)); -#29264 = CARTESIAN_POINT('',(0.198951696239,0.78,-0.307699103232)); -#29265 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); -#29266 = PCURVE('',#28866,#29267); -#29267 = DEFINITIONAL_REPRESENTATION('',(#29268),#29280); -#29268 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29269,#29270,#29271,#29272, - #29273,#29274,#29275,#29276,#29277,#29278,#29279),.UNSPECIFIED.,.F., +#31647 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); +#31648 = CARTESIAN_POINT('',(0.239185998247,0.78,-0.329011896854)); +#31649 = CARTESIAN_POINT('',(0.234275354387,0.78,-0.328868250923)); +#31650 = CARTESIAN_POINT('',(0.227219264145,0.78,-0.32765980921)); +#31651 = CARTESIAN_POINT('',(0.220795849733,0.78,-0.325707725562)); +#31652 = CARTESIAN_POINT('',(0.215077836823,0.78,-0.322798382377)); +#31653 = CARTESIAN_POINT('',(0.209969074838,0.78,-0.319322694065)); +#31654 = CARTESIAN_POINT('',(0.205363431998,0.78,-0.315389795065)); +#31655 = CARTESIAN_POINT('',(0.201222930099,0.78,-0.311002344362)); +#31656 = CARTESIAN_POINT('',(0.198951696239,0.78,-0.307699103232)); +#31657 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); +#31658 = PCURVE('',#31258,#31659); +#31659 = DEFINITIONAL_REPRESENTATION('',(#31660),#31672); +#31660 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31661,#31662,#31663,#31664, + #31665,#31666,#31667,#31668,#31669,#31670,#31671),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.147859636731,0.28356132194, 0.412369396139,0.534236355888,0.652691629312,0.768663059498, 0.88365240186,1.),.UNSPECIFIED.); -#29269 = CARTESIAN_POINT('',(-0.954086799296,1.241746594356)); -#29270 = CARTESIAN_POINT('',(-0.954011896854,1.239185998247)); -#29271 = CARTESIAN_POINT('',(-0.953868250923,1.234275354387)); -#29272 = CARTESIAN_POINT('',(-0.95265980921,1.227219264145)); -#29273 = CARTESIAN_POINT('',(-0.950707725562,1.220795849733)); -#29274 = CARTESIAN_POINT('',(-0.947798382377,1.215077836823)); -#29275 = CARTESIAN_POINT('',(-0.944322694065,1.209969074838)); -#29276 = CARTESIAN_POINT('',(-0.940389795065,1.205363431998)); -#29277 = CARTESIAN_POINT('',(-0.936002344362,1.201222930099)); -#29278 = CARTESIAN_POINT('',(-0.932699103232,1.198951696239)); -#29279 = CARTESIAN_POINT('',(-0.931037785457,1.197809411725)); -#29280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29281 = PCURVE('',#29282,#29305); -#29282 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29283,#29284) - ,(#29285,#29286) - ,(#29287,#29288) - ,(#29289,#29290) - ,(#29291,#29292) - ,(#29293,#29294) - ,(#29295,#29296) - ,(#29297,#29298) - ,(#29299,#29300) - ,(#29301,#29302) - ,(#29303,#29304 +#31661 = CARTESIAN_POINT('',(-0.954086799296,1.241746594356)); +#31662 = CARTESIAN_POINT('',(-0.954011896854,1.239185998247)); +#31663 = CARTESIAN_POINT('',(-0.953868250923,1.234275354387)); +#31664 = CARTESIAN_POINT('',(-0.95265980921,1.227219264145)); +#31665 = CARTESIAN_POINT('',(-0.950707725562,1.220795849733)); +#31666 = CARTESIAN_POINT('',(-0.947798382377,1.215077836823)); +#31667 = CARTESIAN_POINT('',(-0.944322694065,1.209969074838)); +#31668 = CARTESIAN_POINT('',(-0.940389795065,1.205363431998)); +#31669 = CARTESIAN_POINT('',(-0.936002344362,1.201222930099)); +#31670 = CARTESIAN_POINT('',(-0.932699103232,1.198951696239)); +#31671 = CARTESIAN_POINT('',(-0.931037785457,1.197809411725)); +#31672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31673 = PCURVE('',#31674,#31697); +#31674 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31675,#31676) + ,(#31677,#31678) + ,(#31679,#31680) + ,(#31681,#31682) + ,(#31683,#31684) + ,(#31685,#31686) + ,(#31687,#31688) + ,(#31689,#31690) + ,(#31691,#31692) + ,(#31693,#31694) + ,(#31695,#31696 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.147859636731,0.28356132194,0.412369396139,0.534236355888, 0.652691629312,0.768663059498,0.88365240186,1.),(0.E+000,1.), .UNSPECIFIED.); -#29283 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#29284 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); -#29285 = CARTESIAN_POINT('',(0.239185998247,0.782,-0.329011896854)); -#29286 = CARTESIAN_POINT('',(0.239185998247,0.78,-0.329011896854)); -#29287 = CARTESIAN_POINT('',(0.234275354387,0.782,-0.328868250923)); -#29288 = CARTESIAN_POINT('',(0.234275354387,0.78,-0.328868250923)); -#29289 = CARTESIAN_POINT('',(0.227219264145,0.782,-0.32765980921)); -#29290 = CARTESIAN_POINT('',(0.227219264145,0.78,-0.32765980921)); -#29291 = CARTESIAN_POINT('',(0.220795849733,0.782,-0.325707725562)); -#29292 = CARTESIAN_POINT('',(0.220795849733,0.78,-0.325707725562)); -#29293 = CARTESIAN_POINT('',(0.215077836823,0.782,-0.322798382377)); -#29294 = CARTESIAN_POINT('',(0.215077836823,0.78,-0.322798382377)); -#29295 = CARTESIAN_POINT('',(0.209969074838,0.782,-0.319322694065)); -#29296 = CARTESIAN_POINT('',(0.209969074838,0.78,-0.319322694065)); -#29297 = CARTESIAN_POINT('',(0.205363431998,0.782,-0.315389795065)); -#29298 = CARTESIAN_POINT('',(0.205363431998,0.78,-0.315389795065)); -#29299 = CARTESIAN_POINT('',(0.201222930099,0.782,-0.311002344362)); -#29300 = CARTESIAN_POINT('',(0.201222930099,0.78,-0.311002344362)); -#29301 = CARTESIAN_POINT('',(0.198951696239,0.782,-0.307699103232)); -#29302 = CARTESIAN_POINT('',(0.198951696239,0.78,-0.307699103232)); -#29303 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#29304 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); -#29305 = DEFINITIONAL_REPRESENTATION('',(#29306),#29310); -#29306 = LINE('',#29307,#29308); -#29307 = CARTESIAN_POINT('',(0.E+000,1.)); -#29308 = VECTOR('',#29309,1.); -#29309 = DIRECTION('',(1.,0.E+000)); -#29310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29311 = ORIENTED_EDGE('',*,*,#29312,.T.); -#29312 = EDGE_CURVE('',#29251,#29313,#29315,.T.); -#29313 = VERTEX_POINT('',#29314); -#29314 = CARTESIAN_POINT('',(0.164882249099,0.78,-0.309330501719)); -#29315 = SURFACE_CURVE('',#29316,(#29320,#29327),.PCURVE_S1.); -#29316 = LINE('',#29317,#29318); -#29317 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); -#29318 = VECTOR('',#29319,1.); -#29319 = DIRECTION('',(-0.99503719021,0.E+000,-9.9503719021E-002)); -#29320 = PCURVE('',#28866,#29321); -#29321 = DEFINITIONAL_REPRESENTATION('',(#29322),#29326); -#29322 = LINE('',#29323,#29324); -#29323 = CARTESIAN_POINT('',(-0.931037785457,1.197809411725)); -#29324 = VECTOR('',#29325,1.); -#29325 = DIRECTION('',(-9.9503719021E-002,-0.99503719021)); -#29326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29327 = PCURVE('',#29328,#29333); -#29328 = PLANE('',#29329); -#29329 = AXIS2_PLACEMENT_3D('',#29330,#29331,#29332); -#29330 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#29331 = DIRECTION('',(-9.9503719021E-002,0.E+000,0.99503719021)); -#29332 = DIRECTION('',(0.99503719021,0.E+000,9.9503719021E-002)); -#29333 = DEFINITIONAL_REPRESENTATION('',(#29334),#29338); -#29334 = LINE('',#29335,#29336); -#29335 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29336 = VECTOR('',#29337,1.); -#29337 = DIRECTION('',(-1.,0.E+000)); -#29338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29339 = ORIENTED_EDGE('',*,*,#29340,.T.); -#29340 = EDGE_CURVE('',#29313,#29341,#29343,.T.); -#29341 = VERTEX_POINT('',#29342); -#29342 = CARTESIAN_POINT('',(0.1912239792,0.78,-0.441039152227)); -#29343 = SURFACE_CURVE('',#29344,(#29348,#29355),.PCURVE_S1.); -#29344 = LINE('',#29345,#29346); -#29345 = CARTESIAN_POINT('',(0.164882249099,0.78,-0.309330501719)); -#29346 = VECTOR('',#29347,1.); -#29347 = DIRECTION('',(0.196116135138,0.E+000,-0.980580675691)); -#29348 = PCURVE('',#28866,#29349); -#29349 = DEFINITIONAL_REPRESENTATION('',(#29350),#29354); -#29350 = LINE('',#29351,#29352); -#29351 = CARTESIAN_POINT('',(-0.934330501719,1.164882249099)); -#29352 = VECTOR('',#29353,1.); -#29353 = DIRECTION('',(-0.980580675691,0.196116135138)); -#29354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29355 = PCURVE('',#29356,#29361); -#29356 = PLANE('',#29357); -#29357 = AXIS2_PLACEMENT_3D('',#29358,#29359,#29360); -#29358 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); -#29359 = DIRECTION('',(-0.980580675691,0.E+000,-0.196116135138)); -#29360 = DIRECTION('',(-0.196116135138,0.E+000,0.980580675691)); -#29361 = DEFINITIONAL_REPRESENTATION('',(#29362),#29366); -#29362 = LINE('',#29363,#29364); -#29363 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29364 = VECTOR('',#29365,1.); -#29365 = DIRECTION('',(-1.,0.E+000)); -#29366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29367 = ORIENTED_EDGE('',*,*,#29368,.T.); -#29368 = EDGE_CURVE('',#29341,#29369,#29371,.T.); -#29369 = VERTEX_POINT('',#29370); -#29370 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.441039152227)); -#29371 = SURFACE_CURVE('',#29372,(#29376,#29383),.PCURVE_S1.); -#29372 = LINE('',#29373,#29374); -#29373 = CARTESIAN_POINT('',(0.1912239792,0.78,-0.441039152227)); -#29374 = VECTOR('',#29375,1.); -#29375 = DIRECTION('',(1.,0.E+000,0.E+000)); -#29376 = PCURVE('',#28866,#29377); -#29377 = DEFINITIONAL_REPRESENTATION('',(#29378),#29382); -#29378 = LINE('',#29379,#29380); -#29379 = CARTESIAN_POINT('',(-1.066039152227,1.1912239792)); -#29380 = VECTOR('',#29381,1.); -#29381 = DIRECTION('',(0.E+000,1.)); -#29382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29383 = PCURVE('',#29384,#29389); -#29384 = PLANE('',#29385); -#29385 = AXIS2_PLACEMENT_3D('',#29386,#29387,#29388); -#29386 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); -#29387 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#29388 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#29389 = DEFINITIONAL_REPRESENTATION('',(#29390),#29394); -#29390 = LINE('',#29391,#29392); -#29391 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29392 = VECTOR('',#29393,1.); -#29393 = DIRECTION('',(-1.,0.E+000)); -#29394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29395 = ORIENTED_EDGE('',*,*,#29396,.T.); -#29396 = EDGE_CURVE('',#29369,#29397,#29399,.T.); -#29397 = VERTEX_POINT('',#29398); -#29398 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.4081119896)); -#29399 = SURFACE_CURVE('',#29400,(#29404,#29411),.PCURVE_S1.); -#29400 = LINE('',#29401,#29402); -#29401 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.441039152227)); -#29402 = VECTOR('',#29403,1.); -#29403 = DIRECTION('',(0.E+000,0.E+000,1.)); -#29404 = PCURVE('',#28866,#29405); -#29405 = DEFINITIONAL_REPRESENTATION('',(#29406),#29410); -#29406 = LINE('',#29407,#29408); -#29407 = CARTESIAN_POINT('',(-1.066039152227,1.313054480919)); -#29408 = VECTOR('',#29409,1.); -#29409 = DIRECTION('',(1.,0.E+000)); -#29410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29411 = PCURVE('',#29412,#29417); -#29412 = PLANE('',#29413); -#29413 = AXIS2_PLACEMENT_3D('',#29414,#29415,#29416); -#29414 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); -#29415 = DIRECTION('',(1.,0.E+000,0.E+000)); -#29416 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#29417 = DEFINITIONAL_REPRESENTATION('',(#29418),#29422); -#29418 = LINE('',#29419,#29420); -#29419 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29420 = VECTOR('',#29421,1.); -#29421 = DIRECTION('',(-1.,0.E+000)); -#29422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29423 = ORIENTED_EDGE('',*,*,#29424,.T.); -#29424 = EDGE_CURVE('',#29397,#29425,#29427,.T.); -#29425 = VERTEX_POINT('',#29426); -#29426 = CARTESIAN_POINT('',(0.218131644909,0.78,-0.4081119896)); -#29427 = SURFACE_CURVE('',#29428,(#29432,#29439),.PCURVE_S1.); -#29428 = LINE('',#29429,#29430); -#29429 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.4081119896)); -#29430 = VECTOR('',#29431,1.); -#29431 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#29432 = PCURVE('',#28866,#29433); -#29433 = DEFINITIONAL_REPRESENTATION('',(#29434),#29438); -#29434 = LINE('',#29435,#29436); -#29435 = CARTESIAN_POINT('',(-1.0331119896,1.313054480919)); -#29436 = VECTOR('',#29437,1.); -#29437 = DIRECTION('',(0.E+000,-1.)); -#29438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29439 = PCURVE('',#29440,#29445); -#29440 = PLANE('',#29441); -#29441 = AXIS2_PLACEMENT_3D('',#29442,#29443,#29444); -#29442 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); -#29443 = DIRECTION('',(0.E+000,0.E+000,1.)); -#29444 = DIRECTION('',(1.,0.E+000,0.E+000)); -#29445 = DEFINITIONAL_REPRESENTATION('',(#29446),#29450); -#29446 = LINE('',#29447,#29448); -#29447 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29448 = VECTOR('',#29449,1.); -#29449 = DIRECTION('',(-1.,0.E+000)); -#29450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29451 = ORIENTED_EDGE('',*,*,#29452,.T.); -#29452 = EDGE_CURVE('',#29425,#29453,#29455,.T.); -#29453 = VERTEX_POINT('',#29454); -#29454 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); -#29455 = SURFACE_CURVE('',#29456,(#29460,#29467),.PCURVE_S1.); -#29456 = LINE('',#29457,#29458); -#29457 = CARTESIAN_POINT('',(0.218131644909,0.78,-0.4081119896)); -#29458 = VECTOR('',#29459,1.); -#29459 = DIRECTION('',(-0.192758352188,0.E+000,0.9812462574)); -#29460 = PCURVE('',#28866,#29461); -#29461 = DEFINITIONAL_REPRESENTATION('',(#29462),#29466); -#29462 = LINE('',#29463,#29464); -#29463 = CARTESIAN_POINT('',(-1.0331119896,1.218131644909)); -#29464 = VECTOR('',#29465,1.); -#29465 = DIRECTION('',(0.9812462574,-0.192758352188)); -#29466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29467 = PCURVE('',#29468,#29473); -#29468 = PLANE('',#29469); -#29469 = AXIS2_PLACEMENT_3D('',#29470,#29471,#29472); -#29470 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); -#29471 = DIRECTION('',(0.9812462574,0.E+000,0.192758352188)); -#29472 = DIRECTION('',(0.192758352188,0.E+000,-0.9812462574)); -#29473 = DEFINITIONAL_REPRESENTATION('',(#29474),#29478); -#29474 = LINE('',#29475,#29476); -#29475 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); -#29476 = VECTOR('',#29477,1.); -#29477 = DIRECTION('',(-1.,0.E+000)); -#29478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#31675 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#31676 = CARTESIAN_POINT('',(0.241746594356,0.78,-0.329086799296)); +#31677 = CARTESIAN_POINT('',(0.239185998247,0.782,-0.329011896854)); +#31678 = CARTESIAN_POINT('',(0.239185998247,0.78,-0.329011896854)); +#31679 = CARTESIAN_POINT('',(0.234275354387,0.782,-0.328868250923)); +#31680 = CARTESIAN_POINT('',(0.234275354387,0.78,-0.328868250923)); +#31681 = CARTESIAN_POINT('',(0.227219264145,0.782,-0.32765980921)); +#31682 = CARTESIAN_POINT('',(0.227219264145,0.78,-0.32765980921)); +#31683 = CARTESIAN_POINT('',(0.220795849733,0.782,-0.325707725562)); +#31684 = CARTESIAN_POINT('',(0.220795849733,0.78,-0.325707725562)); +#31685 = CARTESIAN_POINT('',(0.215077836823,0.782,-0.322798382377)); +#31686 = CARTESIAN_POINT('',(0.215077836823,0.78,-0.322798382377)); +#31687 = CARTESIAN_POINT('',(0.209969074838,0.782,-0.319322694065)); +#31688 = CARTESIAN_POINT('',(0.209969074838,0.78,-0.319322694065)); +#31689 = CARTESIAN_POINT('',(0.205363431998,0.782,-0.315389795065)); +#31690 = CARTESIAN_POINT('',(0.205363431998,0.78,-0.315389795065)); +#31691 = CARTESIAN_POINT('',(0.201222930099,0.782,-0.311002344362)); +#31692 = CARTESIAN_POINT('',(0.201222930099,0.78,-0.311002344362)); +#31693 = CARTESIAN_POINT('',(0.198951696239,0.782,-0.307699103232)); +#31694 = CARTESIAN_POINT('',(0.198951696239,0.78,-0.307699103232)); +#31695 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#31696 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); +#31697 = DEFINITIONAL_REPRESENTATION('',(#31698),#31702); +#31698 = LINE('',#31699,#31700); +#31699 = CARTESIAN_POINT('',(0.E+000,1.)); +#31700 = VECTOR('',#31701,1.); +#31701 = DIRECTION('',(1.,0.E+000)); +#31702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31703 = ORIENTED_EDGE('',*,*,#31704,.T.); +#31704 = EDGE_CURVE('',#31643,#31705,#31707,.T.); +#31705 = VERTEX_POINT('',#31706); +#31706 = CARTESIAN_POINT('',(0.164882249099,0.78,-0.309330501719)); +#31707 = SURFACE_CURVE('',#31708,(#31712,#31719),.PCURVE_S1.); +#31708 = LINE('',#31709,#31710); +#31709 = CARTESIAN_POINT('',(0.197809411725,0.78,-0.306037785457)); +#31710 = VECTOR('',#31711,1.); +#31711 = DIRECTION('',(-0.99503719021,0.E+000,-9.9503719021E-002)); +#31712 = PCURVE('',#31258,#31713); +#31713 = DEFINITIONAL_REPRESENTATION('',(#31714),#31718); +#31714 = LINE('',#31715,#31716); +#31715 = CARTESIAN_POINT('',(-0.931037785457,1.197809411725)); +#31716 = VECTOR('',#31717,1.); +#31717 = DIRECTION('',(-9.9503719021E-002,-0.99503719021)); +#31718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31719 = PCURVE('',#31720,#31725); +#31720 = PLANE('',#31721); +#31721 = AXIS2_PLACEMENT_3D('',#31722,#31723,#31724); +#31722 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#31723 = DIRECTION('',(-9.9503719021E-002,0.E+000,0.99503719021)); +#31724 = DIRECTION('',(0.99503719021,0.E+000,9.9503719021E-002)); +#31725 = DEFINITIONAL_REPRESENTATION('',(#31726),#31730); +#31726 = LINE('',#31727,#31728); +#31727 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31728 = VECTOR('',#31729,1.); +#31729 = DIRECTION('',(-1.,0.E+000)); +#31730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31731 = ORIENTED_EDGE('',*,*,#31732,.T.); +#31732 = EDGE_CURVE('',#31705,#31733,#31735,.T.); +#31733 = VERTEX_POINT('',#31734); +#31734 = CARTESIAN_POINT('',(0.1912239792,0.78,-0.441039152227)); +#31735 = SURFACE_CURVE('',#31736,(#31740,#31747),.PCURVE_S1.); +#31736 = LINE('',#31737,#31738); +#31737 = CARTESIAN_POINT('',(0.164882249099,0.78,-0.309330501719)); +#31738 = VECTOR('',#31739,1.); +#31739 = DIRECTION('',(0.196116135138,0.E+000,-0.980580675691)); +#31740 = PCURVE('',#31258,#31741); +#31741 = DEFINITIONAL_REPRESENTATION('',(#31742),#31746); +#31742 = LINE('',#31743,#31744); +#31743 = CARTESIAN_POINT('',(-0.934330501719,1.164882249099)); +#31744 = VECTOR('',#31745,1.); +#31745 = DIRECTION('',(-0.980580675691,0.196116135138)); +#31746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31747 = PCURVE('',#31748,#31753); +#31748 = PLANE('',#31749); +#31749 = AXIS2_PLACEMENT_3D('',#31750,#31751,#31752); +#31750 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); +#31751 = DIRECTION('',(-0.980580675691,0.E+000,-0.196116135138)); +#31752 = DIRECTION('',(-0.196116135138,0.E+000,0.980580675691)); +#31753 = DEFINITIONAL_REPRESENTATION('',(#31754),#31758); +#31754 = LINE('',#31755,#31756); +#31755 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31756 = VECTOR('',#31757,1.); +#31757 = DIRECTION('',(-1.,0.E+000)); +#31758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31759 = ORIENTED_EDGE('',*,*,#31760,.T.); +#31760 = EDGE_CURVE('',#31733,#31761,#31763,.T.); +#31761 = VERTEX_POINT('',#31762); +#31762 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.441039152227)); +#31763 = SURFACE_CURVE('',#31764,(#31768,#31775),.PCURVE_S1.); +#31764 = LINE('',#31765,#31766); +#31765 = CARTESIAN_POINT('',(0.1912239792,0.78,-0.441039152227)); +#31766 = VECTOR('',#31767,1.); +#31767 = DIRECTION('',(1.,0.E+000,0.E+000)); +#31768 = PCURVE('',#31258,#31769); +#31769 = DEFINITIONAL_REPRESENTATION('',(#31770),#31774); +#31770 = LINE('',#31771,#31772); +#31771 = CARTESIAN_POINT('',(-1.066039152227,1.1912239792)); +#31772 = VECTOR('',#31773,1.); +#31773 = DIRECTION('',(0.E+000,1.)); +#31774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31775 = PCURVE('',#31776,#31781); +#31776 = PLANE('',#31777); +#31777 = AXIS2_PLACEMENT_3D('',#31778,#31779,#31780); +#31778 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); +#31779 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#31780 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#31781 = DEFINITIONAL_REPRESENTATION('',(#31782),#31786); +#31782 = LINE('',#31783,#31784); +#31783 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31784 = VECTOR('',#31785,1.); +#31785 = DIRECTION('',(-1.,0.E+000)); +#31786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31787 = ORIENTED_EDGE('',*,*,#31788,.T.); +#31788 = EDGE_CURVE('',#31761,#31789,#31791,.T.); +#31789 = VERTEX_POINT('',#31790); +#31790 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.4081119896)); +#31791 = SURFACE_CURVE('',#31792,(#31796,#31803),.PCURVE_S1.); +#31792 = LINE('',#31793,#31794); +#31793 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.441039152227)); +#31794 = VECTOR('',#31795,1.); +#31795 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31796 = PCURVE('',#31258,#31797); +#31797 = DEFINITIONAL_REPRESENTATION('',(#31798),#31802); +#31798 = LINE('',#31799,#31800); +#31799 = CARTESIAN_POINT('',(-1.066039152227,1.313054480919)); +#31800 = VECTOR('',#31801,1.); +#31801 = DIRECTION('',(1.,0.E+000)); +#31802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31803 = PCURVE('',#31804,#31809); +#31804 = PLANE('',#31805); +#31805 = AXIS2_PLACEMENT_3D('',#31806,#31807,#31808); +#31806 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); +#31807 = DIRECTION('',(1.,0.E+000,0.E+000)); +#31808 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#31809 = DEFINITIONAL_REPRESENTATION('',(#31810),#31814); +#31810 = LINE('',#31811,#31812); +#31811 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31812 = VECTOR('',#31813,1.); +#31813 = DIRECTION('',(-1.,0.E+000)); +#31814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31815 = ORIENTED_EDGE('',*,*,#31816,.T.); +#31816 = EDGE_CURVE('',#31789,#31817,#31819,.T.); +#31817 = VERTEX_POINT('',#31818); +#31818 = CARTESIAN_POINT('',(0.218131644909,0.78,-0.4081119896)); +#31819 = SURFACE_CURVE('',#31820,(#31824,#31831),.PCURVE_S1.); +#31820 = LINE('',#31821,#31822); +#31821 = CARTESIAN_POINT('',(0.313054480919,0.78,-0.4081119896)); +#31822 = VECTOR('',#31823,1.); +#31823 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#31824 = PCURVE('',#31258,#31825); +#31825 = DEFINITIONAL_REPRESENTATION('',(#31826),#31830); +#31826 = LINE('',#31827,#31828); +#31827 = CARTESIAN_POINT('',(-1.0331119896,1.313054480919)); +#31828 = VECTOR('',#31829,1.); +#31829 = DIRECTION('',(0.E+000,-1.)); +#31830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31831 = PCURVE('',#31832,#31837); +#31832 = PLANE('',#31833); +#31833 = AXIS2_PLACEMENT_3D('',#31834,#31835,#31836); +#31834 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); +#31835 = DIRECTION('',(0.E+000,0.E+000,1.)); +#31836 = DIRECTION('',(1.,0.E+000,0.E+000)); +#31837 = DEFINITIONAL_REPRESENTATION('',(#31838),#31842); +#31838 = LINE('',#31839,#31840); +#31839 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31840 = VECTOR('',#31841,1.); +#31841 = DIRECTION('',(-1.,0.E+000)); +#31842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31843 = ORIENTED_EDGE('',*,*,#31844,.T.); +#31844 = EDGE_CURVE('',#31817,#31845,#31847,.T.); +#31845 = VERTEX_POINT('',#31846); +#31846 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); +#31847 = SURFACE_CURVE('',#31848,(#31852,#31859),.PCURVE_S1.); +#31848 = LINE('',#31849,#31850); +#31849 = CARTESIAN_POINT('',(0.218131644909,0.78,-0.4081119896)); +#31850 = VECTOR('',#31851,1.); +#31851 = DIRECTION('',(-0.192758352188,0.E+000,0.9812462574)); +#31852 = PCURVE('',#31258,#31853); +#31853 = DEFINITIONAL_REPRESENTATION('',(#31854),#31858); +#31854 = LINE('',#31855,#31856); +#31855 = CARTESIAN_POINT('',(-1.0331119896,1.218131644909)); +#31856 = VECTOR('',#31857,1.); +#31857 = DIRECTION('',(0.9812462574,-0.192758352188)); +#31858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31859 = PCURVE('',#31860,#31865); +#31860 = PLANE('',#31861); +#31861 = AXIS2_PLACEMENT_3D('',#31862,#31863,#31864); +#31862 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); +#31863 = DIRECTION('',(0.9812462574,0.E+000,0.192758352188)); +#31864 = DIRECTION('',(0.192758352188,0.E+000,-0.9812462574)); +#31865 = DEFINITIONAL_REPRESENTATION('',(#31866),#31870); +#31866 = LINE('',#31867,#31868); +#31867 = CARTESIAN_POINT('',(0.E+000,-2.E-003)); +#31868 = VECTOR('',#31869,1.); +#31869 = DIRECTION('',(-1.,0.E+000)); +#31870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#29479 = ORIENTED_EDGE('',*,*,#29480,.T.); -#29480 = EDGE_CURVE('',#29453,#29481,#29483,.T.); -#29481 = VERTEX_POINT('',#29482); -#29482 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); -#29483 = SURFACE_CURVE('',#29484,(#29496,#29511),.PCURVE_S1.); -#29484 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29485,#29486,#29487,#29488, - #29489,#29490,#29491,#29492,#29493,#29494,#29495),.UNSPECIFIED.,.F., +#31871 = ORIENTED_EDGE('',*,*,#31872,.T.); +#31872 = EDGE_CURVE('',#31845,#31873,#31875,.T.); +#31873 = VERTEX_POINT('',#31874); +#31874 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); +#31875 = SURFACE_CURVE('',#31876,(#31888,#31903),.PCURVE_S1.); +#31876 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31877,#31878,#31879,#31880, + #31881,#31882,#31883,#31884,#31885,#31886,#31887),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.13672940186,0.268514916791, 0.395529404685,0.519999953566,0.640496476841,0.761236101763, 0.880106717176,1.),.UNSPECIFIED.); -#29485 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); -#29486 = CARTESIAN_POINT('',(0.206880509894,0.78,-0.342952208043)); -#29487 = CARTESIAN_POINT('',(0.210448481829,0.78,-0.345629664193)); -#29488 = CARTESIAN_POINT('',(0.21601387851,0.78,-0.349135440098)); -#29489 = CARTESIAN_POINT('',(0.221658854525,0.78,-0.352090575417)); -#29490 = CARTESIAN_POINT('',(0.227350549029,0.78,-0.354510582745)); -#29491 = CARTESIAN_POINT('',(0.233134173604,0.78,-0.356395764197)); -#29492 = CARTESIAN_POINT('',(0.238974827182,0.78,-0.357705501218)); -#29493 = CARTESIAN_POINT('',(0.244892396205,0.78,-0.358590698564)); -#29494 = CARTESIAN_POINT('',(0.248860475257,0.78,-0.358677605881)); -#29495 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); -#29496 = PCURVE('',#28866,#29497); -#29497 = DEFINITIONAL_REPRESENTATION('',(#29498),#29510); -#29498 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29499,#29500,#29501,#29502, - #29503,#29504,#29505,#29506,#29507,#29508,#29509),.UNSPECIFIED.,.F., +#31877 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); +#31878 = CARTESIAN_POINT('',(0.206880509894,0.78,-0.342952208043)); +#31879 = CARTESIAN_POINT('',(0.210448481829,0.78,-0.345629664193)); +#31880 = CARTESIAN_POINT('',(0.21601387851,0.78,-0.349135440098)); +#31881 = CARTESIAN_POINT('',(0.221658854525,0.78,-0.352090575417)); +#31882 = CARTESIAN_POINT('',(0.227350549029,0.78,-0.354510582745)); +#31883 = CARTESIAN_POINT('',(0.233134173604,0.78,-0.356395764197)); +#31884 = CARTESIAN_POINT('',(0.238974827182,0.78,-0.357705501218)); +#31885 = CARTESIAN_POINT('',(0.244892396205,0.78,-0.358590698564)); +#31886 = CARTESIAN_POINT('',(0.248860475257,0.78,-0.358677605881)); +#31887 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); +#31888 = PCURVE('',#31258,#31889); +#31889 = DEFINITIONAL_REPRESENTATION('',(#31890),#31902); +#31890 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31891,#31892,#31893,#31894, + #31895,#31896,#31897,#31898,#31899,#31900,#31901),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.13672940186,0.268514916791, 0.395529404685,0.519999953566,0.640496476841,0.761236101763, 0.880106717176,1.),.UNSPECIFIED.); -#29499 = CARTESIAN_POINT('',(-0.966588831355,1.205063677242)); -#29500 = CARTESIAN_POINT('',(-0.967952208043,1.206880509894)); -#29501 = CARTESIAN_POINT('',(-0.970629664193,1.210448481829)); -#29502 = CARTESIAN_POINT('',(-0.974135440098,1.21601387851)); -#29503 = CARTESIAN_POINT('',(-0.977090575417,1.221658854525)); -#29504 = CARTESIAN_POINT('',(-0.979510582745,1.227350549029)); -#29505 = CARTESIAN_POINT('',(-0.981395764197,1.233134173604)); -#29506 = CARTESIAN_POINT('',(-0.982705501218,1.238974827182)); -#29507 = CARTESIAN_POINT('',(-0.983590698564,1.244892396205)); -#29508 = CARTESIAN_POINT('',(-0.983677605881,1.248860475257)); -#29509 = CARTESIAN_POINT('',(-0.98372124566,1.25085301277)); -#29510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29511 = PCURVE('',#29512,#29535); -#29512 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29513,#29514) - ,(#29515,#29516) - ,(#29517,#29518) - ,(#29519,#29520) - ,(#29521,#29522) - ,(#29523,#29524) - ,(#29525,#29526) - ,(#29527,#29528) - ,(#29529,#29530) - ,(#29531,#29532) - ,(#29533,#29534 +#31891 = CARTESIAN_POINT('',(-0.966588831355,1.205063677242)); +#31892 = CARTESIAN_POINT('',(-0.967952208043,1.206880509894)); +#31893 = CARTESIAN_POINT('',(-0.970629664193,1.210448481829)); +#31894 = CARTESIAN_POINT('',(-0.974135440098,1.21601387851)); +#31895 = CARTESIAN_POINT('',(-0.977090575417,1.221658854525)); +#31896 = CARTESIAN_POINT('',(-0.979510582745,1.227350549029)); +#31897 = CARTESIAN_POINT('',(-0.981395764197,1.233134173604)); +#31898 = CARTESIAN_POINT('',(-0.982705501218,1.238974827182)); +#31899 = CARTESIAN_POINT('',(-0.983590698564,1.244892396205)); +#31900 = CARTESIAN_POINT('',(-0.983677605881,1.248860475257)); +#31901 = CARTESIAN_POINT('',(-0.98372124566,1.25085301277)); +#31902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31903 = PCURVE('',#31904,#31927); +#31904 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31905,#31906) + ,(#31907,#31908) + ,(#31909,#31910) + ,(#31911,#31912) + ,(#31913,#31914) + ,(#31915,#31916) + ,(#31917,#31918) + ,(#31919,#31920) + ,(#31921,#31922) + ,(#31923,#31924) + ,(#31925,#31926 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.13672940186,0.268514916791,0.395529404685,0.519999953566, 0.640496476841,0.761236101763,0.880106717176,1.),(0.E+000,1.), .UNSPECIFIED.); -#29513 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); -#29514 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); -#29515 = CARTESIAN_POINT('',(0.206880509894,0.782,-0.342952208043)); -#29516 = CARTESIAN_POINT('',(0.206880509894,0.78,-0.342952208043)); -#29517 = CARTESIAN_POINT('',(0.210448481829,0.782,-0.345629664193)); -#29518 = CARTESIAN_POINT('',(0.210448481829,0.78,-0.345629664193)); -#29519 = CARTESIAN_POINT('',(0.21601387851,0.782,-0.349135440098)); -#29520 = CARTESIAN_POINT('',(0.21601387851,0.78,-0.349135440098)); -#29521 = CARTESIAN_POINT('',(0.221658854525,0.782,-0.352090575417)); -#29522 = CARTESIAN_POINT('',(0.221658854525,0.78,-0.352090575417)); -#29523 = CARTESIAN_POINT('',(0.227350549029,0.782,-0.354510582745)); -#29524 = CARTESIAN_POINT('',(0.227350549029,0.78,-0.354510582745)); -#29525 = CARTESIAN_POINT('',(0.233134173604,0.782,-0.356395764197)); -#29526 = CARTESIAN_POINT('',(0.233134173604,0.78,-0.356395764197)); -#29527 = CARTESIAN_POINT('',(0.238974827182,0.782,-0.357705501218)); -#29528 = CARTESIAN_POINT('',(0.238974827182,0.78,-0.357705501218)); -#29529 = CARTESIAN_POINT('',(0.244892396205,0.782,-0.358590698564)); -#29530 = CARTESIAN_POINT('',(0.244892396205,0.78,-0.358590698564)); -#29531 = CARTESIAN_POINT('',(0.248860475257,0.782,-0.358677605881)); -#29532 = CARTESIAN_POINT('',(0.248860475257,0.78,-0.358677605881)); -#29533 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#29534 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); -#29535 = DEFINITIONAL_REPRESENTATION('',(#29536),#29540); -#29536 = LINE('',#29537,#29538); -#29537 = CARTESIAN_POINT('',(0.E+000,1.)); -#29538 = VECTOR('',#29539,1.); -#29539 = DIRECTION('',(1.,0.E+000)); -#29540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29541 = ORIENTED_EDGE('',*,*,#29542,.T.); -#29542 = EDGE_CURVE('',#29481,#29543,#29545,.T.); -#29543 = VERTEX_POINT('',#29544); -#29544 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); -#29545 = SURFACE_CURVE('',#29546,(#29566,#29589),.PCURVE_S1.); -#29546 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29547,#29548,#29549,#29550, - #29551,#29552,#29553,#29554,#29555,#29556,#29557,#29558,#29559, - #29560,#29561,#29562,#29563,#29564,#29565),.UNSPECIFIED.,.F.,.F.,(4, +#31905 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); +#31906 = CARTESIAN_POINT('',(0.205063677242,0.78,-0.341588831355)); +#31907 = CARTESIAN_POINT('',(0.206880509894,0.782,-0.342952208043)); +#31908 = CARTESIAN_POINT('',(0.206880509894,0.78,-0.342952208043)); +#31909 = CARTESIAN_POINT('',(0.210448481829,0.782,-0.345629664193)); +#31910 = CARTESIAN_POINT('',(0.210448481829,0.78,-0.345629664193)); +#31911 = CARTESIAN_POINT('',(0.21601387851,0.782,-0.349135440098)); +#31912 = CARTESIAN_POINT('',(0.21601387851,0.78,-0.349135440098)); +#31913 = CARTESIAN_POINT('',(0.221658854525,0.782,-0.352090575417)); +#31914 = CARTESIAN_POINT('',(0.221658854525,0.78,-0.352090575417)); +#31915 = CARTESIAN_POINT('',(0.227350549029,0.782,-0.354510582745)); +#31916 = CARTESIAN_POINT('',(0.227350549029,0.78,-0.354510582745)); +#31917 = CARTESIAN_POINT('',(0.233134173604,0.782,-0.356395764197)); +#31918 = CARTESIAN_POINT('',(0.233134173604,0.78,-0.356395764197)); +#31919 = CARTESIAN_POINT('',(0.238974827182,0.782,-0.357705501218)); +#31920 = CARTESIAN_POINT('',(0.238974827182,0.78,-0.357705501218)); +#31921 = CARTESIAN_POINT('',(0.244892396205,0.782,-0.358590698564)); +#31922 = CARTESIAN_POINT('',(0.244892396205,0.78,-0.358590698564)); +#31923 = CARTESIAN_POINT('',(0.248860475257,0.782,-0.358677605881)); +#31924 = CARTESIAN_POINT('',(0.248860475257,0.78,-0.358677605881)); +#31925 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#31926 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); +#31927 = DEFINITIONAL_REPRESENTATION('',(#31928),#31932); +#31928 = LINE('',#31929,#31930); +#31929 = CARTESIAN_POINT('',(0.E+000,1.)); +#31930 = VECTOR('',#31931,1.); +#31931 = DIRECTION('',(1.,0.E+000)); +#31932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31933 = ORIENTED_EDGE('',*,*,#31934,.T.); +#31934 = EDGE_CURVE('',#31873,#31935,#31937,.T.); +#31935 = VERTEX_POINT('',#31936); +#31936 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); +#31937 = SURFACE_CURVE('',#31938,(#31958,#31981),.PCURVE_S1.); +#31938 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31939,#31940,#31941,#31942, + #31943,#31944,#31945,#31946,#31947,#31948,#31949,#31950,#31951, + #31952,#31953,#31954,#31955,#31956,#31957),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.199741907572E-002, 0.122087954082,0.181375310787,0.239508008395,0.297835697897, 0.356879970653,0.417281825115,0.47964040908,0.542500067478, 0.604962419648,0.666991033078,0.73021624301,0.794172863251, 0.86045814315,0.928578179985,1.),.UNSPECIFIED.); -#29547 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); -#29548 = CARTESIAN_POINT('',(0.253446165278,0.78,-0.358653303007)); -#29549 = CARTESIAN_POINT('',(0.258552711472,0.78,-0.358519507446)); -#29550 = CARTESIAN_POINT('',(0.266077384107,0.78,-0.357420208445)); -#29551 = CARTESIAN_POINT('',(0.273272236932,0.78,-0.355554075516)); -#29552 = CARTESIAN_POINT('',(0.280193705771,0.78,-0.353040666526)); -#29553 = CARTESIAN_POINT('',(0.28675052298,0.78,-0.349708713553)); -#29554 = CARTESIAN_POINT('',(0.293009104401,0.78,-0.345674426003)); -#29555 = CARTESIAN_POINT('',(0.298944181976,0.78,-0.340904550372)); -#29556 = CARTESIAN_POINT('',(0.304522203003,0.78,-0.335489084369)); -#29557 = CARTESIAN_POINT('',(0.309581689909,0.78,-0.329477347787)); -#29558 = CARTESIAN_POINT('',(0.31411009582,0.78,-0.323065405188)); -#29559 = CARTESIAN_POINT('',(0.317808650414,0.78,-0.316124907125)); -#29560 = CARTESIAN_POINT('',(0.320919388672,0.78,-0.30883707119)); -#29561 = CARTESIAN_POINT('',(0.323265574073,0.78,-0.301082264907)); -#29562 = CARTESIAN_POINT('',(0.32504641068,0.78,-0.292970544817)); -#29563 = CARTESIAN_POINT('',(0.325998564893,0.78,-0.2844004959)); -#29564 = CARTESIAN_POINT('',(0.326148569164,0.78,-0.278566287547)); -#29565 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); -#29566 = PCURVE('',#28866,#29567); -#29567 = DEFINITIONAL_REPRESENTATION('',(#29568),#29588); -#29568 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29569,#29570,#29571,#29572, - #29573,#29574,#29575,#29576,#29577,#29578,#29579,#29580,#29581, - #29582,#29583,#29584,#29585,#29586,#29587),.UNSPECIFIED.,.F.,.F.,(4, +#31939 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); +#31940 = CARTESIAN_POINT('',(0.253446165278,0.78,-0.358653303007)); +#31941 = CARTESIAN_POINT('',(0.258552711472,0.78,-0.358519507446)); +#31942 = CARTESIAN_POINT('',(0.266077384107,0.78,-0.357420208445)); +#31943 = CARTESIAN_POINT('',(0.273272236932,0.78,-0.355554075516)); +#31944 = CARTESIAN_POINT('',(0.280193705771,0.78,-0.353040666526)); +#31945 = CARTESIAN_POINT('',(0.28675052298,0.78,-0.349708713553)); +#31946 = CARTESIAN_POINT('',(0.293009104401,0.78,-0.345674426003)); +#31947 = CARTESIAN_POINT('',(0.298944181976,0.78,-0.340904550372)); +#31948 = CARTESIAN_POINT('',(0.304522203003,0.78,-0.335489084369)); +#31949 = CARTESIAN_POINT('',(0.309581689909,0.78,-0.329477347787)); +#31950 = CARTESIAN_POINT('',(0.31411009582,0.78,-0.323065405188)); +#31951 = CARTESIAN_POINT('',(0.317808650414,0.78,-0.316124907125)); +#31952 = CARTESIAN_POINT('',(0.320919388672,0.78,-0.30883707119)); +#31953 = CARTESIAN_POINT('',(0.323265574073,0.78,-0.301082264907)); +#31954 = CARTESIAN_POINT('',(0.32504641068,0.78,-0.292970544817)); +#31955 = CARTESIAN_POINT('',(0.325998564893,0.78,-0.2844004959)); +#31956 = CARTESIAN_POINT('',(0.326148569164,0.78,-0.278566287547)); +#31957 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); +#31958 = PCURVE('',#31258,#31959); +#31959 = DEFINITIONAL_REPRESENTATION('',(#31960),#31980); +#31960 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#31961,#31962,#31963,#31964, + #31965,#31966,#31967,#31968,#31969,#31970,#31971,#31972,#31973, + #31974,#31975,#31976,#31977,#31978,#31979),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.199741907572E-002, 0.122087954082,0.181375310787,0.239508008395,0.297835697897, 0.356879970653,0.417281825115,0.47964040908,0.542500067478, 0.604962419648,0.666991033078,0.73021624301,0.794172863251, 0.86045814315,0.928578179985,1.),.UNSPECIFIED.); -#29569 = CARTESIAN_POINT('',(-0.98372124566,1.25085301277)); -#29570 = CARTESIAN_POINT('',(-0.983653303007,1.253446165278)); -#29571 = CARTESIAN_POINT('',(-0.983519507446,1.258552711472)); -#29572 = CARTESIAN_POINT('',(-0.982420208445,1.266077384107)); -#29573 = CARTESIAN_POINT('',(-0.980554075516,1.273272236932)); -#29574 = CARTESIAN_POINT('',(-0.978040666526,1.280193705771)); -#29575 = CARTESIAN_POINT('',(-0.974708713553,1.28675052298)); -#29576 = CARTESIAN_POINT('',(-0.970674426003,1.293009104401)); -#29577 = CARTESIAN_POINT('',(-0.965904550372,1.298944181976)); -#29578 = CARTESIAN_POINT('',(-0.960489084369,1.304522203003)); -#29579 = CARTESIAN_POINT('',(-0.954477347787,1.309581689909)); -#29580 = CARTESIAN_POINT('',(-0.948065405188,1.31411009582)); -#29581 = CARTESIAN_POINT('',(-0.941124907125,1.317808650414)); -#29582 = CARTESIAN_POINT('',(-0.93383707119,1.320919388672)); -#29583 = CARTESIAN_POINT('',(-0.926082264907,1.323265574073)); -#29584 = CARTESIAN_POINT('',(-0.917970544817,1.32504641068)); -#29585 = CARTESIAN_POINT('',(-0.9094004959,1.325998564893)); -#29586 = CARTESIAN_POINT('',(-0.903566287547,1.326148569164)); -#29587 = CARTESIAN_POINT('',(-0.900580160027,1.32622534597)); -#29588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29589 = PCURVE('',#29590,#29629); -#29590 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29591,#29592) - ,(#29593,#29594) - ,(#29595,#29596) - ,(#29597,#29598) - ,(#29599,#29600) - ,(#29601,#29602) - ,(#29603,#29604) - ,(#29605,#29606) - ,(#29607,#29608) - ,(#29609,#29610) - ,(#29611,#29612) - ,(#29613,#29614) - ,(#29615,#29616) - ,(#29617,#29618) - ,(#29619,#29620) - ,(#29621,#29622) - ,(#29623,#29624) - ,(#29625,#29626) - ,(#29627,#29628 +#31961 = CARTESIAN_POINT('',(-0.98372124566,1.25085301277)); +#31962 = CARTESIAN_POINT('',(-0.983653303007,1.253446165278)); +#31963 = CARTESIAN_POINT('',(-0.983519507446,1.258552711472)); +#31964 = CARTESIAN_POINT('',(-0.982420208445,1.266077384107)); +#31965 = CARTESIAN_POINT('',(-0.980554075516,1.273272236932)); +#31966 = CARTESIAN_POINT('',(-0.978040666526,1.280193705771)); +#31967 = CARTESIAN_POINT('',(-0.974708713553,1.28675052298)); +#31968 = CARTESIAN_POINT('',(-0.970674426003,1.293009104401)); +#31969 = CARTESIAN_POINT('',(-0.965904550372,1.298944181976)); +#31970 = CARTESIAN_POINT('',(-0.960489084369,1.304522203003)); +#31971 = CARTESIAN_POINT('',(-0.954477347787,1.309581689909)); +#31972 = CARTESIAN_POINT('',(-0.948065405188,1.31411009582)); +#31973 = CARTESIAN_POINT('',(-0.941124907125,1.317808650414)); +#31974 = CARTESIAN_POINT('',(-0.93383707119,1.320919388672)); +#31975 = CARTESIAN_POINT('',(-0.926082264907,1.323265574073)); +#31976 = CARTESIAN_POINT('',(-0.917970544817,1.32504641068)); +#31977 = CARTESIAN_POINT('',(-0.9094004959,1.325998564893)); +#31978 = CARTESIAN_POINT('',(-0.903566287547,1.326148569164)); +#31979 = CARTESIAN_POINT('',(-0.900580160027,1.32622534597)); +#31980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#31981 = PCURVE('',#31982,#32021); +#31982 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#31983,#31984) + ,(#31985,#31986) + ,(#31987,#31988) + ,(#31989,#31990) + ,(#31991,#31992) + ,(#31993,#31994) + ,(#31995,#31996) + ,(#31997,#31998) + ,(#31999,#32000) + ,(#32001,#32002) + ,(#32003,#32004) + ,(#32005,#32006) + ,(#32007,#32008) + ,(#32009,#32010) + ,(#32011,#32012) + ,(#32013,#32014) + ,(#32015,#32016) + ,(#32017,#32018) + ,(#32019,#32020 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.199741907572E-002,0.122087954082,0.181375310787, 0.239508008395,0.297835697897,0.356879970653,0.417281825115, 0.47964040908,0.542500067478,0.604962419648,0.666991033078, 0.73021624301,0.794172863251,0.86045814315,0.928578179985,1.),( 0.E+000,1.),.UNSPECIFIED.); -#29591 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#29592 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); -#29593 = CARTESIAN_POINT('',(0.253446165278,0.782,-0.358653303007)); -#29594 = CARTESIAN_POINT('',(0.253446165278,0.78,-0.358653303007)); -#29595 = CARTESIAN_POINT('',(0.258552711472,0.782,-0.358519507446)); -#29596 = CARTESIAN_POINT('',(0.258552711472,0.78,-0.358519507446)); -#29597 = CARTESIAN_POINT('',(0.266077384107,0.782,-0.357420208445)); -#29598 = CARTESIAN_POINT('',(0.266077384107,0.78,-0.357420208445)); -#29599 = CARTESIAN_POINT('',(0.273272236932,0.782,-0.355554075516)); -#29600 = CARTESIAN_POINT('',(0.273272236932,0.78,-0.355554075516)); -#29601 = CARTESIAN_POINT('',(0.280193705771,0.782,-0.353040666526)); -#29602 = CARTESIAN_POINT('',(0.280193705771,0.78,-0.353040666526)); -#29603 = CARTESIAN_POINT('',(0.28675052298,0.782,-0.349708713553)); -#29604 = CARTESIAN_POINT('',(0.28675052298,0.78,-0.349708713553)); -#29605 = CARTESIAN_POINT('',(0.293009104401,0.782,-0.345674426003)); -#29606 = CARTESIAN_POINT('',(0.293009104401,0.78,-0.345674426003)); -#29607 = CARTESIAN_POINT('',(0.298944181976,0.782,-0.340904550372)); -#29608 = CARTESIAN_POINT('',(0.298944181976,0.78,-0.340904550372)); -#29609 = CARTESIAN_POINT('',(0.304522203003,0.782,-0.335489084369)); -#29610 = CARTESIAN_POINT('',(0.304522203003,0.78,-0.335489084369)); -#29611 = CARTESIAN_POINT('',(0.309581689909,0.782,-0.329477347787)); -#29612 = CARTESIAN_POINT('',(0.309581689909,0.78,-0.329477347787)); -#29613 = CARTESIAN_POINT('',(0.31411009582,0.782,-0.323065405188)); -#29614 = CARTESIAN_POINT('',(0.31411009582,0.78,-0.323065405188)); -#29615 = CARTESIAN_POINT('',(0.317808650414,0.782,-0.316124907125)); -#29616 = CARTESIAN_POINT('',(0.317808650414,0.78,-0.316124907125)); -#29617 = CARTESIAN_POINT('',(0.320919388672,0.782,-0.30883707119)); -#29618 = CARTESIAN_POINT('',(0.320919388672,0.78,-0.30883707119)); -#29619 = CARTESIAN_POINT('',(0.323265574073,0.782,-0.301082264907)); -#29620 = CARTESIAN_POINT('',(0.323265574073,0.78,-0.301082264907)); -#29621 = CARTESIAN_POINT('',(0.32504641068,0.782,-0.292970544817)); -#29622 = CARTESIAN_POINT('',(0.32504641068,0.78,-0.292970544817)); -#29623 = CARTESIAN_POINT('',(0.325998564893,0.782,-0.2844004959)); -#29624 = CARTESIAN_POINT('',(0.325998564893,0.78,-0.2844004959)); -#29625 = CARTESIAN_POINT('',(0.326148569164,0.782,-0.278566287547)); -#29626 = CARTESIAN_POINT('',(0.326148569164,0.78,-0.278566287547)); -#29627 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#29628 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); -#29629 = DEFINITIONAL_REPRESENTATION('',(#29630),#29634); -#29630 = LINE('',#29631,#29632); -#29631 = CARTESIAN_POINT('',(0.E+000,1.)); -#29632 = VECTOR('',#29633,1.); -#29633 = DIRECTION('',(1.,0.E+000)); -#29634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29635 = ORIENTED_EDGE('',*,*,#29636,.T.); -#29636 = EDGE_CURVE('',#29543,#29637,#29639,.T.); -#29637 = VERTEX_POINT('',#29638); -#29638 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); -#29639 = SURFACE_CURVE('',#29640,(#29652,#29667),.PCURVE_S1.); -#29640 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29641,#29642,#29643,#29644, - #29645,#29646,#29647,#29648,#29649,#29650,#29651),.UNSPECIFIED.,.F., +#31983 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#31984 = CARTESIAN_POINT('',(0.25085301277,0.78,-0.35872124566)); +#31985 = CARTESIAN_POINT('',(0.253446165278,0.782,-0.358653303007)); +#31986 = CARTESIAN_POINT('',(0.253446165278,0.78,-0.358653303007)); +#31987 = CARTESIAN_POINT('',(0.258552711472,0.782,-0.358519507446)); +#31988 = CARTESIAN_POINT('',(0.258552711472,0.78,-0.358519507446)); +#31989 = CARTESIAN_POINT('',(0.266077384107,0.782,-0.357420208445)); +#31990 = CARTESIAN_POINT('',(0.266077384107,0.78,-0.357420208445)); +#31991 = CARTESIAN_POINT('',(0.273272236932,0.782,-0.355554075516)); +#31992 = CARTESIAN_POINT('',(0.273272236932,0.78,-0.355554075516)); +#31993 = CARTESIAN_POINT('',(0.280193705771,0.782,-0.353040666526)); +#31994 = CARTESIAN_POINT('',(0.280193705771,0.78,-0.353040666526)); +#31995 = CARTESIAN_POINT('',(0.28675052298,0.782,-0.349708713553)); +#31996 = CARTESIAN_POINT('',(0.28675052298,0.78,-0.349708713553)); +#31997 = CARTESIAN_POINT('',(0.293009104401,0.782,-0.345674426003)); +#31998 = CARTESIAN_POINT('',(0.293009104401,0.78,-0.345674426003)); +#31999 = CARTESIAN_POINT('',(0.298944181976,0.782,-0.340904550372)); +#32000 = CARTESIAN_POINT('',(0.298944181976,0.78,-0.340904550372)); +#32001 = CARTESIAN_POINT('',(0.304522203003,0.782,-0.335489084369)); +#32002 = CARTESIAN_POINT('',(0.304522203003,0.78,-0.335489084369)); +#32003 = CARTESIAN_POINT('',(0.309581689909,0.782,-0.329477347787)); +#32004 = CARTESIAN_POINT('',(0.309581689909,0.78,-0.329477347787)); +#32005 = CARTESIAN_POINT('',(0.31411009582,0.782,-0.323065405188)); +#32006 = CARTESIAN_POINT('',(0.31411009582,0.78,-0.323065405188)); +#32007 = CARTESIAN_POINT('',(0.317808650414,0.782,-0.316124907125)); +#32008 = CARTESIAN_POINT('',(0.317808650414,0.78,-0.316124907125)); +#32009 = CARTESIAN_POINT('',(0.320919388672,0.782,-0.30883707119)); +#32010 = CARTESIAN_POINT('',(0.320919388672,0.78,-0.30883707119)); +#32011 = CARTESIAN_POINT('',(0.323265574073,0.782,-0.301082264907)); +#32012 = CARTESIAN_POINT('',(0.323265574073,0.78,-0.301082264907)); +#32013 = CARTESIAN_POINT('',(0.32504641068,0.782,-0.292970544817)); +#32014 = CARTESIAN_POINT('',(0.32504641068,0.78,-0.292970544817)); +#32015 = CARTESIAN_POINT('',(0.325998564893,0.782,-0.2844004959)); +#32016 = CARTESIAN_POINT('',(0.325998564893,0.78,-0.2844004959)); +#32017 = CARTESIAN_POINT('',(0.326148569164,0.782,-0.278566287547)); +#32018 = CARTESIAN_POINT('',(0.326148569164,0.78,-0.278566287547)); +#32019 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#32020 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); +#32021 = DEFINITIONAL_REPRESENTATION('',(#32022),#32026); +#32022 = LINE('',#32023,#32024); +#32023 = CARTESIAN_POINT('',(0.E+000,1.)); +#32024 = VECTOR('',#32025,1.); +#32025 = DIRECTION('',(1.,0.E+000)); +#32026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32027 = ORIENTED_EDGE('',*,*,#32028,.T.); +#32028 = EDGE_CURVE('',#31935,#32029,#32031,.T.); +#32029 = VERTEX_POINT('',#32030); +#32030 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); +#32031 = SURFACE_CURVE('',#32032,(#32044,#32059),.PCURVE_S1.); +#32032 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32033,#32034,#32035,#32036, + #32037,#32038,#32039,#32040,#32041,#32042,#32043),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.132461622243,0.261649501035, 0.387546698416,0.510781629293,0.6326753606,0.754660354138, 0.876522779803,1.),.UNSPECIFIED.); -#29641 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); -#29642 = CARTESIAN_POINT('',(0.326167045263,0.78,-0.272730903454)); -#29643 = CARTESIAN_POINT('',(0.32605188473,0.78,-0.267102808703)); -#29644 = CARTESIAN_POINT('',(0.325108120345,0.78,-0.258808770662)); -#29645 = CARTESIAN_POINT('',(0.323553492815,0.78,-0.250816812181)); -#29646 = CARTESIAN_POINT('',(0.321472275533,0.78,-0.243103266612)); -#29647 = CARTESIAN_POINT('',(0.318660271687,0.78,-0.235711940929)); -#29648 = CARTESIAN_POINT('',(0.315249574225,0.78,-0.228618960549)); -#29649 = CARTESIAN_POINT('',(0.311315143396,0.78,-0.221750312623)); -#29650 = CARTESIAN_POINT('',(0.308159934047,0.78,-0.217516187599)); -#29651 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); -#29652 = PCURVE('',#28866,#29653); -#29653 = DEFINITIONAL_REPRESENTATION('',(#29654),#29666); -#29654 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29655,#29656,#29657,#29658, - #29659,#29660,#29661,#29662,#29663,#29664,#29665),.UNSPECIFIED.,.F., +#32033 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); +#32034 = CARTESIAN_POINT('',(0.326167045263,0.78,-0.272730903454)); +#32035 = CARTESIAN_POINT('',(0.32605188473,0.78,-0.267102808703)); +#32036 = CARTESIAN_POINT('',(0.325108120345,0.78,-0.258808770662)); +#32037 = CARTESIAN_POINT('',(0.323553492815,0.78,-0.250816812181)); +#32038 = CARTESIAN_POINT('',(0.321472275533,0.78,-0.243103266612)); +#32039 = CARTESIAN_POINT('',(0.318660271687,0.78,-0.235711940929)); +#32040 = CARTESIAN_POINT('',(0.315249574225,0.78,-0.228618960549)); +#32041 = CARTESIAN_POINT('',(0.311315143396,0.78,-0.221750312623)); +#32042 = CARTESIAN_POINT('',(0.308159934047,0.78,-0.217516187599)); +#32043 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); +#32044 = PCURVE('',#31258,#32045); +#32045 = DEFINITIONAL_REPRESENTATION('',(#32046),#32058); +#32046 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32047,#32048,#32049,#32050, + #32051,#32052,#32053,#32054,#32055,#32056,#32057),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.132461622243,0.261649501035, 0.387546698416,0.510781629293,0.6326753606,0.754660354138, 0.876522779803,1.),.UNSPECIFIED.); -#29655 = CARTESIAN_POINT('',(-0.900580160027,1.32622534597)); -#29656 = CARTESIAN_POINT('',(-0.897730903454,1.326167045263)); -#29657 = CARTESIAN_POINT('',(-0.892102808703,1.32605188473)); -#29658 = CARTESIAN_POINT('',(-0.883808770662,1.325108120345)); -#29659 = CARTESIAN_POINT('',(-0.875816812181,1.323553492815)); -#29660 = CARTESIAN_POINT('',(-0.868103266612,1.321472275533)); -#29661 = CARTESIAN_POINT('',(-0.860711940929,1.318660271687)); -#29662 = CARTESIAN_POINT('',(-0.853618960549,1.315249574225)); -#29663 = CARTESIAN_POINT('',(-0.846750312623,1.311315143396)); -#29664 = CARTESIAN_POINT('',(-0.842516187599,1.308159934047)); -#29665 = CARTESIAN_POINT('',(-0.84038519085,1.306571945777)); -#29666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29667 = PCURVE('',#29668,#29691); -#29668 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29669,#29670) - ,(#29671,#29672) - ,(#29673,#29674) - ,(#29675,#29676) - ,(#29677,#29678) - ,(#29679,#29680) - ,(#29681,#29682) - ,(#29683,#29684) - ,(#29685,#29686) - ,(#29687,#29688) - ,(#29689,#29690 +#32047 = CARTESIAN_POINT('',(-0.900580160027,1.32622534597)); +#32048 = CARTESIAN_POINT('',(-0.897730903454,1.326167045263)); +#32049 = CARTESIAN_POINT('',(-0.892102808703,1.32605188473)); +#32050 = CARTESIAN_POINT('',(-0.883808770662,1.325108120345)); +#32051 = CARTESIAN_POINT('',(-0.875816812181,1.323553492815)); +#32052 = CARTESIAN_POINT('',(-0.868103266612,1.321472275533)); +#32053 = CARTESIAN_POINT('',(-0.860711940929,1.318660271687)); +#32054 = CARTESIAN_POINT('',(-0.853618960549,1.315249574225)); +#32055 = CARTESIAN_POINT('',(-0.846750312623,1.311315143396)); +#32056 = CARTESIAN_POINT('',(-0.842516187599,1.308159934047)); +#32057 = CARTESIAN_POINT('',(-0.84038519085,1.306571945777)); +#32058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32059 = PCURVE('',#32060,#32083); +#32060 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32061,#32062) + ,(#32063,#32064) + ,(#32065,#32066) + ,(#32067,#32068) + ,(#32069,#32070) + ,(#32071,#32072) + ,(#32073,#32074) + ,(#32075,#32076) + ,(#32077,#32078) + ,(#32079,#32080) + ,(#32081,#32082 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.132461622243,0.261649501035,0.387546698416,0.510781629293, 0.6326753606,0.754660354138,0.876522779803,1.),(0.E+000,1.), .UNSPECIFIED.); -#29669 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#29670 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); -#29671 = CARTESIAN_POINT('',(0.326167045263,0.782,-0.272730903454)); -#29672 = CARTESIAN_POINT('',(0.326167045263,0.78,-0.272730903454)); -#29673 = CARTESIAN_POINT('',(0.32605188473,0.782,-0.267102808703)); -#29674 = CARTESIAN_POINT('',(0.32605188473,0.78,-0.267102808703)); -#29675 = CARTESIAN_POINT('',(0.325108120345,0.782,-0.258808770662)); -#29676 = CARTESIAN_POINT('',(0.325108120345,0.78,-0.258808770662)); -#29677 = CARTESIAN_POINT('',(0.323553492815,0.782,-0.250816812181)); -#29678 = CARTESIAN_POINT('',(0.323553492815,0.78,-0.250816812181)); -#29679 = CARTESIAN_POINT('',(0.321472275533,0.782,-0.243103266612)); -#29680 = CARTESIAN_POINT('',(0.321472275533,0.78,-0.243103266612)); -#29681 = CARTESIAN_POINT('',(0.318660271687,0.782,-0.235711940929)); -#29682 = CARTESIAN_POINT('',(0.318660271687,0.78,-0.235711940929)); -#29683 = CARTESIAN_POINT('',(0.315249574225,0.782,-0.228618960549)); -#29684 = CARTESIAN_POINT('',(0.315249574225,0.78,-0.228618960549)); -#29685 = CARTESIAN_POINT('',(0.311315143396,0.782,-0.221750312623)); -#29686 = CARTESIAN_POINT('',(0.311315143396,0.78,-0.221750312623)); -#29687 = CARTESIAN_POINT('',(0.308159934047,0.782,-0.217516187599)); -#29688 = CARTESIAN_POINT('',(0.308159934047,0.78,-0.217516187599)); -#29689 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#29690 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); -#29691 = DEFINITIONAL_REPRESENTATION('',(#29692),#29696); -#29692 = LINE('',#29693,#29694); -#29693 = CARTESIAN_POINT('',(0.E+000,1.)); -#29694 = VECTOR('',#29695,1.); -#29695 = DIRECTION('',(1.,0.E+000)); -#29696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29697 = ORIENTED_EDGE('',*,*,#29698,.T.); -#29698 = EDGE_CURVE('',#29637,#28840,#29699,.T.); -#29699 = SURFACE_CURVE('',#29700,(#29712,#29727),.PCURVE_S1.); -#29700 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29701,#29702,#29703,#29704, - #29705,#29706,#29707,#29708,#29709,#29710,#29711),.UNSPECIFIED.,.F., +#32061 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#32062 = CARTESIAN_POINT('',(0.32622534597,0.78,-0.275580160027)); +#32063 = CARTESIAN_POINT('',(0.326167045263,0.782,-0.272730903454)); +#32064 = CARTESIAN_POINT('',(0.326167045263,0.78,-0.272730903454)); +#32065 = CARTESIAN_POINT('',(0.32605188473,0.782,-0.267102808703)); +#32066 = CARTESIAN_POINT('',(0.32605188473,0.78,-0.267102808703)); +#32067 = CARTESIAN_POINT('',(0.325108120345,0.782,-0.258808770662)); +#32068 = CARTESIAN_POINT('',(0.325108120345,0.78,-0.258808770662)); +#32069 = CARTESIAN_POINT('',(0.323553492815,0.782,-0.250816812181)); +#32070 = CARTESIAN_POINT('',(0.323553492815,0.78,-0.250816812181)); +#32071 = CARTESIAN_POINT('',(0.321472275533,0.782,-0.243103266612)); +#32072 = CARTESIAN_POINT('',(0.321472275533,0.78,-0.243103266612)); +#32073 = CARTESIAN_POINT('',(0.318660271687,0.782,-0.235711940929)); +#32074 = CARTESIAN_POINT('',(0.318660271687,0.78,-0.235711940929)); +#32075 = CARTESIAN_POINT('',(0.315249574225,0.782,-0.228618960549)); +#32076 = CARTESIAN_POINT('',(0.315249574225,0.78,-0.228618960549)); +#32077 = CARTESIAN_POINT('',(0.311315143396,0.782,-0.221750312623)); +#32078 = CARTESIAN_POINT('',(0.311315143396,0.78,-0.221750312623)); +#32079 = CARTESIAN_POINT('',(0.308159934047,0.782,-0.217516187599)); +#32080 = CARTESIAN_POINT('',(0.308159934047,0.78,-0.217516187599)); +#32081 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#32082 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); +#32083 = DEFINITIONAL_REPRESENTATION('',(#32084),#32088); +#32084 = LINE('',#32085,#32086); +#32085 = CARTESIAN_POINT('',(0.E+000,1.)); +#32086 = VECTOR('',#32087,1.); +#32087 = DIRECTION('',(1.,0.E+000)); +#32088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32089 = ORIENTED_EDGE('',*,*,#32090,.T.); +#32090 = EDGE_CURVE('',#32029,#31232,#32091,.T.); +#32091 = SURFACE_CURVE('',#32092,(#32104,#32119),.PCURVE_S1.); +#32092 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32093,#32094,#32095,#32096, + #32097,#32098,#32099,#32100,#32101,#32102,#32103),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127892619465,0.251578513504, 0.372792819702,0.492777698608,0.613590069243,0.73780864928, 0.866179901539,1.),.UNSPECIFIED.); -#29701 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); -#29702 = CARTESIAN_POINT('',(0.304554451204,0.78,-0.212897646984)); -#29703 = CARTESIAN_POINT('',(0.300585822772,0.78,-0.208004381129)); -#29704 = CARTESIAN_POINT('',(0.293714185963,0.78,-0.201653214923)); -#29705 = CARTESIAN_POINT('',(0.286327078968,0.78,-0.196255597723)); -#29706 = CARTESIAN_POINT('',(0.278380540216,0.78,-0.19187042492)); -#29707 = CARTESIAN_POINT('',(0.269927917393,0.78,-0.18834656724)); -#29708 = CARTESIAN_POINT('',(0.260865372344,0.78,-0.186001572274)); -#29709 = CARTESIAN_POINT('',(0.251302410337,0.78,-0.184426815267)); -#29710 = CARTESIAN_POINT('',(0.244737251379,0.78,-0.184281467782)); -#29711 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); -#29712 = PCURVE('',#28866,#29713); -#29713 = DEFINITIONAL_REPRESENTATION('',(#29714),#29726); -#29714 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29715,#29716,#29717,#29718, - #29719,#29720,#29721,#29722,#29723,#29724,#29725),.UNSPECIFIED.,.F., +#32093 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); +#32094 = CARTESIAN_POINT('',(0.304554451204,0.78,-0.212897646984)); +#32095 = CARTESIAN_POINT('',(0.300585822772,0.78,-0.208004381129)); +#32096 = CARTESIAN_POINT('',(0.293714185963,0.78,-0.201653214923)); +#32097 = CARTESIAN_POINT('',(0.286327078968,0.78,-0.196255597723)); +#32098 = CARTESIAN_POINT('',(0.278380540216,0.78,-0.19187042492)); +#32099 = CARTESIAN_POINT('',(0.269927917393,0.78,-0.18834656724)); +#32100 = CARTESIAN_POINT('',(0.260865372344,0.78,-0.186001572274)); +#32101 = CARTESIAN_POINT('',(0.251302410337,0.78,-0.184426815267)); +#32102 = CARTESIAN_POINT('',(0.244737251379,0.78,-0.184281467782)); +#32103 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); +#32104 = PCURVE('',#31258,#32105); +#32105 = DEFINITIONAL_REPRESENTATION('',(#32106),#32118); +#32106 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32107,#32108,#32109,#32110, + #32111,#32112,#32113,#32114,#32115,#32116,#32117),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127892619465,0.251578513504, 0.372792819702,0.492777698608,0.613590069243,0.73780864928, 0.866179901539,1.),.UNSPECIFIED.); -#29715 = CARTESIAN_POINT('',(-0.84038519085,1.306571945777)); -#29716 = CARTESIAN_POINT('',(-0.837897646984,1.304554451204)); -#29717 = CARTESIAN_POINT('',(-0.833004381129,1.300585822772)); -#29718 = CARTESIAN_POINT('',(-0.826653214923,1.293714185963)); -#29719 = CARTESIAN_POINT('',(-0.821255597723,1.286327078968)); -#29720 = CARTESIAN_POINT('',(-0.81687042492,1.278380540216)); -#29721 = CARTESIAN_POINT('',(-0.81334656724,1.269927917393)); -#29722 = CARTESIAN_POINT('',(-0.811001572274,1.260865372344)); -#29723 = CARTESIAN_POINT('',(-0.809426815267,1.251302410337)); -#29724 = CARTESIAN_POINT('',(-0.809281467782,1.244737251379)); -#29725 = CARTESIAN_POINT('',(-0.809207283737,1.241386453514)); -#29726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29727 = PCURVE('',#29728,#29751); -#29728 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29729,#29730) - ,(#29731,#29732) - ,(#29733,#29734) - ,(#29735,#29736) - ,(#29737,#29738) - ,(#29739,#29740) - ,(#29741,#29742) - ,(#29743,#29744) - ,(#29745,#29746) - ,(#29747,#29748) - ,(#29749,#29750 +#32107 = CARTESIAN_POINT('',(-0.84038519085,1.306571945777)); +#32108 = CARTESIAN_POINT('',(-0.837897646984,1.304554451204)); +#32109 = CARTESIAN_POINT('',(-0.833004381129,1.300585822772)); +#32110 = CARTESIAN_POINT('',(-0.826653214923,1.293714185963)); +#32111 = CARTESIAN_POINT('',(-0.821255597723,1.286327078968)); +#32112 = CARTESIAN_POINT('',(-0.81687042492,1.278380540216)); +#32113 = CARTESIAN_POINT('',(-0.81334656724,1.269927917393)); +#32114 = CARTESIAN_POINT('',(-0.811001572274,1.260865372344)); +#32115 = CARTESIAN_POINT('',(-0.809426815267,1.251302410337)); +#32116 = CARTESIAN_POINT('',(-0.809281467782,1.244737251379)); +#32117 = CARTESIAN_POINT('',(-0.809207283737,1.241386453514)); +#32118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32119 = PCURVE('',#32120,#32143); +#32120 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32121,#32122) + ,(#32123,#32124) + ,(#32125,#32126) + ,(#32127,#32128) + ,(#32129,#32130) + ,(#32131,#32132) + ,(#32133,#32134) + ,(#32135,#32136) + ,(#32137,#32138) + ,(#32139,#32140) + ,(#32141,#32142 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.127892619465,0.251578513504,0.372792819702,0.492777698608, 0.613590069243,0.73780864928,0.866179901539,1.),(0.E+000,1.), .UNSPECIFIED.); -#29729 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#29730 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); -#29731 = CARTESIAN_POINT('',(0.304554451204,0.782,-0.212897646984)); -#29732 = CARTESIAN_POINT('',(0.304554451204,0.78,-0.212897646984)); -#29733 = CARTESIAN_POINT('',(0.300585822772,0.782,-0.208004381129)); -#29734 = CARTESIAN_POINT('',(0.300585822772,0.78,-0.208004381129)); -#29735 = CARTESIAN_POINT('',(0.293714185963,0.782,-0.201653214923)); -#29736 = CARTESIAN_POINT('',(0.293714185963,0.78,-0.201653214923)); -#29737 = CARTESIAN_POINT('',(0.286327078968,0.782,-0.196255597723)); -#29738 = CARTESIAN_POINT('',(0.286327078968,0.78,-0.196255597723)); -#29739 = CARTESIAN_POINT('',(0.278380540216,0.782,-0.19187042492)); -#29740 = CARTESIAN_POINT('',(0.278380540216,0.78,-0.19187042492)); -#29741 = CARTESIAN_POINT('',(0.269927917393,0.782,-0.18834656724)); -#29742 = CARTESIAN_POINT('',(0.269927917393,0.78,-0.18834656724)); -#29743 = CARTESIAN_POINT('',(0.260865372344,0.782,-0.186001572274)); -#29744 = CARTESIAN_POINT('',(0.260865372344,0.78,-0.186001572274)); -#29745 = CARTESIAN_POINT('',(0.251302410337,0.782,-0.184426815267)); -#29746 = CARTESIAN_POINT('',(0.251302410337,0.78,-0.184426815267)); -#29747 = CARTESIAN_POINT('',(0.244737251379,0.782,-0.184281467782)); -#29748 = CARTESIAN_POINT('',(0.244737251379,0.78,-0.184281467782)); -#29749 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#29750 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); -#29751 = DEFINITIONAL_REPRESENTATION('',(#29752),#29756); -#29752 = LINE('',#29753,#29754); -#29753 = CARTESIAN_POINT('',(0.E+000,1.)); -#29754 = VECTOR('',#29755,1.); -#29755 = DIRECTION('',(1.,0.E+000)); -#29756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29757 = FACE_BOUND('',#29758,.T.); -#29758 = EDGE_LOOP('',(#29759,#29823,#29949,#30059,#30185)); -#29759 = ORIENTED_EDGE('',*,*,#29760,.T.); -#29760 = EDGE_CURVE('',#29761,#29763,#29765,.T.); -#29761 = VERTEX_POINT('',#29762); -#29762 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) - ); -#29763 = VERTEX_POINT('',#29764); -#29764 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); -#29765 = SURFACE_CURVE('',#29766,(#29778,#29793),.PCURVE_S1.); -#29766 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29767,#29768,#29769,#29770, - #29771,#29772,#29773,#29774,#29775,#29776,#29777),.UNSPECIFIED.,.F., +#32121 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#32122 = CARTESIAN_POINT('',(0.306571945777,0.78,-0.21538519085)); +#32123 = CARTESIAN_POINT('',(0.304554451204,0.782,-0.212897646984)); +#32124 = CARTESIAN_POINT('',(0.304554451204,0.78,-0.212897646984)); +#32125 = CARTESIAN_POINT('',(0.300585822772,0.782,-0.208004381129)); +#32126 = CARTESIAN_POINT('',(0.300585822772,0.78,-0.208004381129)); +#32127 = CARTESIAN_POINT('',(0.293714185963,0.782,-0.201653214923)); +#32128 = CARTESIAN_POINT('',(0.293714185963,0.78,-0.201653214923)); +#32129 = CARTESIAN_POINT('',(0.286327078968,0.782,-0.196255597723)); +#32130 = CARTESIAN_POINT('',(0.286327078968,0.78,-0.196255597723)); +#32131 = CARTESIAN_POINT('',(0.278380540216,0.782,-0.19187042492)); +#32132 = CARTESIAN_POINT('',(0.278380540216,0.78,-0.19187042492)); +#32133 = CARTESIAN_POINT('',(0.269927917393,0.782,-0.18834656724)); +#32134 = CARTESIAN_POINT('',(0.269927917393,0.78,-0.18834656724)); +#32135 = CARTESIAN_POINT('',(0.260865372344,0.782,-0.186001572274)); +#32136 = CARTESIAN_POINT('',(0.260865372344,0.78,-0.186001572274)); +#32137 = CARTESIAN_POINT('',(0.251302410337,0.782,-0.184426815267)); +#32138 = CARTESIAN_POINT('',(0.251302410337,0.78,-0.184426815267)); +#32139 = CARTESIAN_POINT('',(0.244737251379,0.782,-0.184281467782)); +#32140 = CARTESIAN_POINT('',(0.244737251379,0.78,-0.184281467782)); +#32141 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#32142 = CARTESIAN_POINT('',(0.241386453514,0.78,-0.184207283737)); +#32143 = DEFINITIONAL_REPRESENTATION('',(#32144),#32148); +#32144 = LINE('',#32145,#32146); +#32145 = CARTESIAN_POINT('',(0.E+000,1.)); +#32146 = VECTOR('',#32147,1.); +#32147 = DIRECTION('',(1.,0.E+000)); +#32148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32149 = FACE_BOUND('',#32150,.T.); +#32150 = EDGE_LOOP('',(#32151,#32215,#32341,#32451,#32577)); +#32151 = ORIENTED_EDGE('',*,*,#32152,.T.); +#32152 = EDGE_CURVE('',#32153,#32155,#32157,.T.); +#32153 = VERTEX_POINT('',#32154); +#32154 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) + ); +#32155 = VERTEX_POINT('',#32156); +#32156 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); +#32157 = SURFACE_CURVE('',#32158,(#32170,#32185),.PCURVE_S1.); +#32158 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32159,#32160,#32161,#32162, + #32163,#32164,#32165,#32166,#32167,#32168,#32169),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,9.742066817721E-002,0.200885588039, 0.311171970173,0.429797945825,0.557739926365,0.694715269364, 0.842129910206,1.),.UNSPECIFIED.); -#29767 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) +#32159 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) ); -#29768 = CARTESIAN_POINT('',(-1.3056297112E-002,0.78,-0.21189029918)); -#29769 = CARTESIAN_POINT('',(-1.725352258953E-002,0.78,-0.217944858507) +#32160 = CARTESIAN_POINT('',(-1.3056297112E-002,0.78,-0.21189029918)); +#32161 = CARTESIAN_POINT('',(-1.725352258953E-002,0.78,-0.217944858507) ); -#29770 = CARTESIAN_POINT('',(-2.216601109072E-002,0.78,-0.228268443793) +#32162 = CARTESIAN_POINT('',(-2.216601109072E-002,0.78,-0.228268443793) ); -#29771 = CARTESIAN_POINT('',(-2.654803780823E-002,0.78,-0.23963326173)); -#29772 = CARTESIAN_POINT('',(-2.998712535972E-002,0.78,-0.2522622887)); -#29773 = CARTESIAN_POINT('',(-3.268078820585E-002,0.78,-0.266055011925) +#32163 = CARTESIAN_POINT('',(-2.654803780823E-002,0.78,-0.23963326173)); +#32164 = CARTESIAN_POINT('',(-2.998712535972E-002,0.78,-0.2522622887)); +#32165 = CARTESIAN_POINT('',(-3.268078820585E-002,0.78,-0.266055011925) ); -#29774 = CARTESIAN_POINT('',(-3.462628530538E-002,0.78,-0.281038495666) +#32166 = CARTESIAN_POINT('',(-3.462628530538E-002,0.78,-0.281038495666) ); -#29775 = CARTESIAN_POINT('',(-3.572724513147E-002,0.78,-0.297206266562) +#32167 = CARTESIAN_POINT('',(-3.572724513147E-002,0.78,-0.297206266562) ); -#29776 = CARTESIAN_POINT('',(-3.58895244037E-002,0.78,-0.308385584215)); -#29777 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); -#29778 = PCURVE('',#28866,#29779); -#29779 = DEFINITIONAL_REPRESENTATION('',(#29780),#29792); -#29780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29781,#29782,#29783,#29784, - #29785,#29786,#29787,#29788,#29789,#29790,#29791),.UNSPECIFIED.,.F., +#32168 = CARTESIAN_POINT('',(-3.58895244037E-002,0.78,-0.308385584215)); +#32169 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); +#32170 = PCURVE('',#31258,#32171); +#32171 = DEFINITIONAL_REPRESENTATION('',(#32172),#32184); +#32172 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32173,#32174,#32175,#32176, + #32177,#32178,#32179,#32180,#32181,#32182,#32183),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,9.742066817721E-002,0.200885588039, 0.311171970173,0.429797945825,0.557739926365,0.694715269364, 0.842129910206,1.),.UNSPECIFIED.); -#29781 = CARTESIAN_POINT('',(-0.833954104399,0.988979172503)); -#29782 = CARTESIAN_POINT('',(-0.83689029918,0.986943702888)); -#29783 = CARTESIAN_POINT('',(-0.842944858507,0.98274647741)); -#29784 = CARTESIAN_POINT('',(-0.853268443793,0.977833988909)); -#29785 = CARTESIAN_POINT('',(-0.86463326173,0.973451962192)); -#29786 = CARTESIAN_POINT('',(-0.8772622887,0.97001287464)); -#29787 = CARTESIAN_POINT('',(-0.891055011925,0.967319211794)); -#29788 = CARTESIAN_POINT('',(-0.906038495666,0.965373714695)); -#29789 = CARTESIAN_POINT('',(-0.922206266562,0.964272754869)); -#29790 = CARTESIAN_POINT('',(-0.933385584215,0.964110475596)); -#29791 = CARTESIAN_POINT('',(-0.93916667873,0.964026557075)); -#29792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29793 = PCURVE('',#29794,#29817); -#29794 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29795,#29796) - ,(#29797,#29798) - ,(#29799,#29800) - ,(#29801,#29802) - ,(#29803,#29804) - ,(#29805,#29806) - ,(#29807,#29808) - ,(#29809,#29810) - ,(#29811,#29812) - ,(#29813,#29814) - ,(#29815,#29816 +#32173 = CARTESIAN_POINT('',(-0.833954104399,0.988979172503)); +#32174 = CARTESIAN_POINT('',(-0.83689029918,0.986943702888)); +#32175 = CARTESIAN_POINT('',(-0.842944858507,0.98274647741)); +#32176 = CARTESIAN_POINT('',(-0.853268443793,0.977833988909)); +#32177 = CARTESIAN_POINT('',(-0.86463326173,0.973451962192)); +#32178 = CARTESIAN_POINT('',(-0.8772622887,0.97001287464)); +#32179 = CARTESIAN_POINT('',(-0.891055011925,0.967319211794)); +#32180 = CARTESIAN_POINT('',(-0.906038495666,0.965373714695)); +#32181 = CARTESIAN_POINT('',(-0.922206266562,0.964272754869)); +#32182 = CARTESIAN_POINT('',(-0.933385584215,0.964110475596)); +#32183 = CARTESIAN_POINT('',(-0.93916667873,0.964026557075)); +#32184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32185 = PCURVE('',#32186,#32209); +#32186 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32187,#32188) + ,(#32189,#32190) + ,(#32191,#32192) + ,(#32193,#32194) + ,(#32195,#32196) + ,(#32197,#32198) + ,(#32199,#32200) + ,(#32201,#32202) + ,(#32203,#32204) + ,(#32205,#32206) + ,(#32207,#32208 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 9.742066817721E-002,0.200885588039,0.311171970173,0.429797945825, 0.557739926365,0.694715269364,0.842129910206,1.),(0.E+000,1.), .UNSPECIFIED.); -#29795 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) +#32187 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) ); -#29796 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) +#32188 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) ); -#29797 = CARTESIAN_POINT('',(-1.3056297112E-002,0.782,-0.21189029918)); -#29798 = CARTESIAN_POINT('',(-1.3056297112E-002,0.78,-0.21189029918)); -#29799 = CARTESIAN_POINT('',(-1.725352258953E-002,0.782,-0.217944858507) +#32189 = CARTESIAN_POINT('',(-1.3056297112E-002,0.782,-0.21189029918)); +#32190 = CARTESIAN_POINT('',(-1.3056297112E-002,0.78,-0.21189029918)); +#32191 = CARTESIAN_POINT('',(-1.725352258953E-002,0.782,-0.217944858507) ); -#29800 = CARTESIAN_POINT('',(-1.725352258953E-002,0.78,-0.217944858507) +#32192 = CARTESIAN_POINT('',(-1.725352258953E-002,0.78,-0.217944858507) ); -#29801 = CARTESIAN_POINT('',(-2.216601109072E-002,0.782,-0.228268443793) +#32193 = CARTESIAN_POINT('',(-2.216601109072E-002,0.782,-0.228268443793) ); -#29802 = CARTESIAN_POINT('',(-2.216601109072E-002,0.78,-0.228268443793) +#32194 = CARTESIAN_POINT('',(-2.216601109072E-002,0.78,-0.228268443793) ); -#29803 = CARTESIAN_POINT('',(-2.654803780823E-002,0.782,-0.23963326173) +#32195 = CARTESIAN_POINT('',(-2.654803780823E-002,0.782,-0.23963326173) ); -#29804 = CARTESIAN_POINT('',(-2.654803780823E-002,0.78,-0.23963326173)); -#29805 = CARTESIAN_POINT('',(-2.998712535972E-002,0.782,-0.2522622887)); -#29806 = CARTESIAN_POINT('',(-2.998712535972E-002,0.78,-0.2522622887)); -#29807 = CARTESIAN_POINT('',(-3.268078820585E-002,0.782,-0.266055011925) +#32196 = CARTESIAN_POINT('',(-2.654803780823E-002,0.78,-0.23963326173)); +#32197 = CARTESIAN_POINT('',(-2.998712535972E-002,0.782,-0.2522622887)); +#32198 = CARTESIAN_POINT('',(-2.998712535972E-002,0.78,-0.2522622887)); +#32199 = CARTESIAN_POINT('',(-3.268078820585E-002,0.782,-0.266055011925) ); -#29808 = CARTESIAN_POINT('',(-3.268078820585E-002,0.78,-0.266055011925) +#32200 = CARTESIAN_POINT('',(-3.268078820585E-002,0.78,-0.266055011925) ); -#29809 = CARTESIAN_POINT('',(-3.462628530538E-002,0.782,-0.281038495666) +#32201 = CARTESIAN_POINT('',(-3.462628530538E-002,0.782,-0.281038495666) ); -#29810 = CARTESIAN_POINT('',(-3.462628530538E-002,0.78,-0.281038495666) +#32202 = CARTESIAN_POINT('',(-3.462628530538E-002,0.78,-0.281038495666) ); -#29811 = CARTESIAN_POINT('',(-3.572724513147E-002,0.782,-0.297206266562) +#32203 = CARTESIAN_POINT('',(-3.572724513147E-002,0.782,-0.297206266562) ); -#29812 = CARTESIAN_POINT('',(-3.572724513147E-002,0.78,-0.297206266562) +#32204 = CARTESIAN_POINT('',(-3.572724513147E-002,0.78,-0.297206266562) ); -#29813 = CARTESIAN_POINT('',(-3.58895244037E-002,0.782,-0.308385584215) +#32205 = CARTESIAN_POINT('',(-3.58895244037E-002,0.782,-0.308385584215) ); -#29814 = CARTESIAN_POINT('',(-3.58895244037E-002,0.78,-0.308385584215)); -#29815 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) +#32206 = CARTESIAN_POINT('',(-3.58895244037E-002,0.78,-0.308385584215)); +#32207 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) ); -#29816 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); -#29817 = DEFINITIONAL_REPRESENTATION('',(#29818),#29822); -#29818 = LINE('',#29819,#29820); -#29819 = CARTESIAN_POINT('',(0.E+000,1.)); -#29820 = VECTOR('',#29821,1.); -#29821 = DIRECTION('',(1.,0.E+000)); -#29822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#32208 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); +#32209 = DEFINITIONAL_REPRESENTATION('',(#32210),#32214); +#32210 = LINE('',#32211,#32212); +#32211 = CARTESIAN_POINT('',(0.E+000,1.)); +#32212 = VECTOR('',#32213,1.); +#32213 = DIRECTION('',(1.,0.E+000)); +#32214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#29823 = ORIENTED_EDGE('',*,*,#29824,.T.); -#29824 = EDGE_CURVE('',#29763,#29825,#29827,.T.); -#29825 = VERTEX_POINT('',#29826); -#29826 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); -#29827 = SURFACE_CURVE('',#29828,(#29856,#29887),.PCURVE_S1.); -#29828 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29829,#29830,#29831,#29832, - #29833,#29834,#29835,#29836,#29837,#29838,#29839,#29840,#29841, - #29842,#29843,#29844,#29845,#29846,#29847,#29848,#29849,#29850, - #29851,#29852,#29853,#29854,#29855),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#32215 = ORIENTED_EDGE('',*,*,#32216,.T.); +#32216 = EDGE_CURVE('',#32155,#32217,#32219,.T.); +#32217 = VERTEX_POINT('',#32218); +#32218 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); +#32219 = SURFACE_CURVE('',#32220,(#32248,#32279),.PCURVE_S1.); +#32220 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32221,#32222,#32223,#32224, + #32225,#32226,#32227,#32228,#32229,#32230,#32231,#32232,#32233, + #32234,#32235,#32236,#32237,#32238,#32239,#32240,#32241,#32242, + #32243,#32244,#32245,#32246,#32247),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.311445839479E-002,0.123614645769,0.180973711186,0.235261455008, 0.287100701834,0.336030736303,0.382382348585,0.42633408366, @@ -36476,51 +39465,51 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.61899431503,0.653583018621,0.68715613619,0.720422191979, 0.753230218812,0.786260156078,0.819503983499,0.853545274712, 0.88830828034,0.923995860741,0.961350304755,1.),.UNSPECIFIED.); -#29829 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); -#29830 = CARTESIAN_POINT('',(-3.59402688018E-002,0.78,-0.317837041881)); -#29831 = CARTESIAN_POINT('',(-3.587529466378E-002,0.78,-0.32502573766)); -#29832 = CARTESIAN_POINT('',(-3.547228119311E-002,0.78,-0.33554409099)); -#29833 = CARTESIAN_POINT('',(-3.476865233001E-002,0.78,-0.34553293562)); -#29834 = CARTESIAN_POINT('',(-3.371832814217E-002,0.78,-0.354983596705) +#32221 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); +#32222 = CARTESIAN_POINT('',(-3.59402688018E-002,0.78,-0.317837041881)); +#32223 = CARTESIAN_POINT('',(-3.587529466378E-002,0.78,-0.32502573766)); +#32224 = CARTESIAN_POINT('',(-3.547228119311E-002,0.78,-0.33554409099)); +#32225 = CARTESIAN_POINT('',(-3.476865233001E-002,0.78,-0.34553293562)); +#32226 = CARTESIAN_POINT('',(-3.371832814217E-002,0.78,-0.354983596705) ); -#29835 = CARTESIAN_POINT('',(-3.247454752437E-002,0.78,-0.363917406242) +#32227 = CARTESIAN_POINT('',(-3.247454752437E-002,0.78,-0.363917406242) ); -#29836 = CARTESIAN_POINT('',(-3.085762487453E-002,0.78,-0.372321614766) +#32228 = CARTESIAN_POINT('',(-3.085762487453E-002,0.78,-0.372321614766) ); -#29837 = CARTESIAN_POINT('',(-2.903835183156E-002,0.78,-0.380215078472) +#32229 = CARTESIAN_POINT('',(-2.903835183156E-002,0.78,-0.380215078472) ); -#29838 = CARTESIAN_POINT('',(-2.685555065364E-002,0.78,-0.387589569702) +#32230 = CARTESIAN_POINT('',(-2.685555065364E-002,0.78,-0.387589569702) ); -#29839 = CARTESIAN_POINT('',(-2.445736673545E-002,0.78,-0.394508495657) +#32231 = CARTESIAN_POINT('',(-2.445736673545E-002,0.78,-0.394508495657) ); -#29840 = CARTESIAN_POINT('',(-2.173655057069E-002,0.78,-0.400960756818) +#32232 = CARTESIAN_POINT('',(-2.173655057069E-002,0.78,-0.400960756818) ); -#29841 = CARTESIAN_POINT('',(-1.867526329643E-002,0.78,-0.406939512268) +#32233 = CARTESIAN_POINT('',(-1.867526329643E-002,0.78,-0.406939512268) ); -#29842 = CARTESIAN_POINT('',(-1.542394815444E-002,0.78,-0.412506765057) +#32234 = CARTESIAN_POINT('',(-1.542394815444E-002,0.78,-0.412506765057) ); -#29843 = CARTESIAN_POINT('',(-1.181144925028E-002,0.78,-0.417575921489) +#32235 = CARTESIAN_POINT('',(-1.181144925028E-002,0.78,-0.417575921489) ); -#29844 = CARTESIAN_POINT('',(-8.055809774141E-003,0.78,-0.422289242847) +#32236 = CARTESIAN_POINT('',(-8.055809774141E-003,0.78,-0.422289242847) ); -#29845 = CARTESIAN_POINT('',(-3.884092272847E-003,0.78,-0.426473873245) +#32237 = CARTESIAN_POINT('',(-3.884092272847E-003,0.78,-0.426473873245) ); -#29846 = CARTESIAN_POINT('',(5.302342909642E-004,0.78,-0.430237483603)); -#29847 = CARTESIAN_POINT('',(5.252172020433E-003,0.78,-0.433558650412)); -#29848 = CARTESIAN_POINT('',(1.0256737177E-002,0.78,-0.436424416779)); -#29849 = CARTESIAN_POINT('',(1.552467355536E-002,0.78,-0.438954681848)); -#29850 = CARTESIAN_POINT('',(2.115638219723E-002,0.78,-0.44085946473)); -#29851 = CARTESIAN_POINT('',(2.703494991357E-002,0.78,-0.442412266576)); -#29852 = CARTESIAN_POINT('',(3.320562687015E-002,0.78,-0.443554526441)); -#29853 = CARTESIAN_POINT('',(3.96752130578E-002,0.78,-0.44422792718)); -#29854 = CARTESIAN_POINT('',(4.409626580613E-002,0.78,-0.444296829976)); -#29855 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); -#29856 = PCURVE('',#28866,#29857); -#29857 = DEFINITIONAL_REPRESENTATION('',(#29858),#29886); -#29858 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29859,#29860,#29861,#29862, - #29863,#29864,#29865,#29866,#29867,#29868,#29869,#29870,#29871, - #29872,#29873,#29874,#29875,#29876,#29877,#29878,#29879,#29880, - #29881,#29882,#29883,#29884,#29885),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#32238 = CARTESIAN_POINT('',(5.302342909642E-004,0.78,-0.430237483603)); +#32239 = CARTESIAN_POINT('',(5.252172020433E-003,0.78,-0.433558650412)); +#32240 = CARTESIAN_POINT('',(1.0256737177E-002,0.78,-0.436424416779)); +#32241 = CARTESIAN_POINT('',(1.552467355536E-002,0.78,-0.438954681848)); +#32242 = CARTESIAN_POINT('',(2.115638219723E-002,0.78,-0.44085946473)); +#32243 = CARTESIAN_POINT('',(2.703494991357E-002,0.78,-0.442412266576)); +#32244 = CARTESIAN_POINT('',(3.320562687015E-002,0.78,-0.443554526441)); +#32245 = CARTESIAN_POINT('',(3.96752130578E-002,0.78,-0.44422792718)); +#32246 = CARTESIAN_POINT('',(4.409626580613E-002,0.78,-0.444296829976)); +#32247 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); +#32248 = PCURVE('',#31258,#32249); +#32249 = DEFINITIONAL_REPRESENTATION('',(#32250),#32278); +#32250 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32251,#32252,#32253,#32254, + #32255,#32256,#32257,#32258,#32259,#32260,#32261,#32262,#32263, + #32264,#32265,#32266,#32267,#32268,#32269,#32270,#32271,#32272, + #32273,#32274,#32275,#32276,#32277),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.311445839479E-002,0.123614645769,0.180973711186,0.235261455008, 0.287100701834,0.336030736303,0.382382348585,0.42633408366, @@ -36528,65 +39517,65 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.61899431503,0.653583018621,0.68715613619,0.720422191979, 0.753230218812,0.786260156078,0.819503983499,0.853545274712, 0.88830828034,0.923995860741,0.961350304755,1.),.UNSPECIFIED.); -#29859 = CARTESIAN_POINT('',(-0.93916667873,0.964026557075)); -#29860 = CARTESIAN_POINT('',(-0.942837041881,0.964059731198)); -#29861 = CARTESIAN_POINT('',(-0.95002573766,0.964124705336)); -#29862 = CARTESIAN_POINT('',(-0.96054409099,0.964527718807)); -#29863 = CARTESIAN_POINT('',(-0.97053293562,0.96523134767)); -#29864 = CARTESIAN_POINT('',(-0.979983596705,0.966281671858)); -#29865 = CARTESIAN_POINT('',(-0.988917406242,0.967525452476)); -#29866 = CARTESIAN_POINT('',(-0.997321614766,0.969142375125)); -#29867 = CARTESIAN_POINT('',(-1.005215078472,0.970961648168)); -#29868 = CARTESIAN_POINT('',(-1.012589569702,0.973144449346)); -#29869 = CARTESIAN_POINT('',(-1.019508495657,0.975542633265)); -#29870 = CARTESIAN_POINT('',(-1.025960756818,0.978263449429)); -#29871 = CARTESIAN_POINT('',(-1.031939512268,0.981324736704)); -#29872 = CARTESIAN_POINT('',(-1.037506765057,0.984576051846)); -#29873 = CARTESIAN_POINT('',(-1.042575921489,0.98818855075)); -#29874 = CARTESIAN_POINT('',(-1.047289242847,0.991944190226)); -#29875 = CARTESIAN_POINT('',(-1.051473873245,0.996115907727)); -#29876 = CARTESIAN_POINT('',(-1.055237483603,1.000530234291)); -#29877 = CARTESIAN_POINT('',(-1.058558650412,1.00525217202)); -#29878 = CARTESIAN_POINT('',(-1.061424416779,1.010256737177)); -#29879 = CARTESIAN_POINT('',(-1.063954681848,1.015524673555)); -#29880 = CARTESIAN_POINT('',(-1.06585946473,1.021156382197)); -#29881 = CARTESIAN_POINT('',(-1.067412266576,1.027034949914)); -#29882 = CARTESIAN_POINT('',(-1.068554526441,1.03320562687)); -#29883 = CARTESIAN_POINT('',(-1.06922792718,1.039675213058)); -#29884 = CARTESIAN_POINT('',(-1.069296829976,1.044096265806)); -#29885 = CARTESIAN_POINT('',(-1.06933186849,1.046344463642)); -#29886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#29887 = PCURVE('',#29888,#29943); -#29888 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#29889,#29890) - ,(#29891,#29892) - ,(#29893,#29894) - ,(#29895,#29896) - ,(#29897,#29898) - ,(#29899,#29900) - ,(#29901,#29902) - ,(#29903,#29904) - ,(#29905,#29906) - ,(#29907,#29908) - ,(#29909,#29910) - ,(#29911,#29912) - ,(#29913,#29914) - ,(#29915,#29916) - ,(#29917,#29918) - ,(#29919,#29920) - ,(#29921,#29922) - ,(#29923,#29924) - ,(#29925,#29926) - ,(#29927,#29928) - ,(#29929,#29930) - ,(#29931,#29932) - ,(#29933,#29934) - ,(#29935,#29936) - ,(#29937,#29938) - ,(#29939,#29940) - ,(#29941,#29942 +#32251 = CARTESIAN_POINT('',(-0.93916667873,0.964026557075)); +#32252 = CARTESIAN_POINT('',(-0.942837041881,0.964059731198)); +#32253 = CARTESIAN_POINT('',(-0.95002573766,0.964124705336)); +#32254 = CARTESIAN_POINT('',(-0.96054409099,0.964527718807)); +#32255 = CARTESIAN_POINT('',(-0.97053293562,0.96523134767)); +#32256 = CARTESIAN_POINT('',(-0.979983596705,0.966281671858)); +#32257 = CARTESIAN_POINT('',(-0.988917406242,0.967525452476)); +#32258 = CARTESIAN_POINT('',(-0.997321614766,0.969142375125)); +#32259 = CARTESIAN_POINT('',(-1.005215078472,0.970961648168)); +#32260 = CARTESIAN_POINT('',(-1.012589569702,0.973144449346)); +#32261 = CARTESIAN_POINT('',(-1.019508495657,0.975542633265)); +#32262 = CARTESIAN_POINT('',(-1.025960756818,0.978263449429)); +#32263 = CARTESIAN_POINT('',(-1.031939512268,0.981324736704)); +#32264 = CARTESIAN_POINT('',(-1.037506765057,0.984576051846)); +#32265 = CARTESIAN_POINT('',(-1.042575921489,0.98818855075)); +#32266 = CARTESIAN_POINT('',(-1.047289242847,0.991944190226)); +#32267 = CARTESIAN_POINT('',(-1.051473873245,0.996115907727)); +#32268 = CARTESIAN_POINT('',(-1.055237483603,1.000530234291)); +#32269 = CARTESIAN_POINT('',(-1.058558650412,1.00525217202)); +#32270 = CARTESIAN_POINT('',(-1.061424416779,1.010256737177)); +#32271 = CARTESIAN_POINT('',(-1.063954681848,1.015524673555)); +#32272 = CARTESIAN_POINT('',(-1.06585946473,1.021156382197)); +#32273 = CARTESIAN_POINT('',(-1.067412266576,1.027034949914)); +#32274 = CARTESIAN_POINT('',(-1.068554526441,1.03320562687)); +#32275 = CARTESIAN_POINT('',(-1.06922792718,1.039675213058)); +#32276 = CARTESIAN_POINT('',(-1.069296829976,1.044096265806)); +#32277 = CARTESIAN_POINT('',(-1.06933186849,1.046344463642)); +#32278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32279 = PCURVE('',#32280,#32335); +#32280 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32281,#32282) + ,(#32283,#32284) + ,(#32285,#32286) + ,(#32287,#32288) + ,(#32289,#32290) + ,(#32291,#32292) + ,(#32293,#32294) + ,(#32295,#32296) + ,(#32297,#32298) + ,(#32299,#32300) + ,(#32301,#32302) + ,(#32303,#32304) + ,(#32305,#32306) + ,(#32307,#32308) + ,(#32309,#32310) + ,(#32311,#32312) + ,(#32313,#32314) + ,(#32315,#32316) + ,(#32317,#32318) + ,(#32319,#32320) + ,(#32321,#32322) + ,(#32323,#32324) + ,(#32325,#32326) + ,(#32327,#32328) + ,(#32329,#32330) + ,(#32331,#32332) + ,(#32333,#32334 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,4),(2,2),(0.E+000,6.311445839479E-002,0.123614645769, 0.180973711186,0.235261455008,0.287100701834,0.336030736303, @@ -36595,204 +39584,204 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.68715613619,0.720422191979,0.753230218812,0.786260156078, 0.819503983499,0.853545274712,0.88830828034,0.923995860741, 0.961350304755,1.),(0.E+000,1.),.UNSPECIFIED.); -#29889 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) +#32281 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) ); -#29890 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); -#29891 = CARTESIAN_POINT('',(-3.59402688018E-002,0.782,-0.317837041881) +#32282 = CARTESIAN_POINT('',(-3.597344292535E-002,0.78,-0.31416667873)); +#32283 = CARTESIAN_POINT('',(-3.59402688018E-002,0.782,-0.317837041881) ); -#29892 = CARTESIAN_POINT('',(-3.59402688018E-002,0.78,-0.317837041881)); -#29893 = CARTESIAN_POINT('',(-3.587529466378E-002,0.782,-0.32502573766) +#32284 = CARTESIAN_POINT('',(-3.59402688018E-002,0.78,-0.317837041881)); +#32285 = CARTESIAN_POINT('',(-3.587529466378E-002,0.782,-0.32502573766) ); -#29894 = CARTESIAN_POINT('',(-3.587529466378E-002,0.78,-0.32502573766)); -#29895 = CARTESIAN_POINT('',(-3.547228119311E-002,0.782,-0.33554409099) +#32286 = CARTESIAN_POINT('',(-3.587529466378E-002,0.78,-0.32502573766)); +#32287 = CARTESIAN_POINT('',(-3.547228119311E-002,0.782,-0.33554409099) ); -#29896 = CARTESIAN_POINT('',(-3.547228119311E-002,0.78,-0.33554409099)); -#29897 = CARTESIAN_POINT('',(-3.476865233001E-002,0.782,-0.34553293562) +#32288 = CARTESIAN_POINT('',(-3.547228119311E-002,0.78,-0.33554409099)); +#32289 = CARTESIAN_POINT('',(-3.476865233001E-002,0.782,-0.34553293562) ); -#29898 = CARTESIAN_POINT('',(-3.476865233001E-002,0.78,-0.34553293562)); -#29899 = CARTESIAN_POINT('',(-3.371832814217E-002,0.782,-0.354983596705) +#32290 = CARTESIAN_POINT('',(-3.476865233001E-002,0.78,-0.34553293562)); +#32291 = CARTESIAN_POINT('',(-3.371832814217E-002,0.782,-0.354983596705) ); -#29900 = CARTESIAN_POINT('',(-3.371832814217E-002,0.78,-0.354983596705) +#32292 = CARTESIAN_POINT('',(-3.371832814217E-002,0.78,-0.354983596705) ); -#29901 = CARTESIAN_POINT('',(-3.247454752437E-002,0.782,-0.363917406242) +#32293 = CARTESIAN_POINT('',(-3.247454752437E-002,0.782,-0.363917406242) ); -#29902 = CARTESIAN_POINT('',(-3.247454752437E-002,0.78,-0.363917406242) +#32294 = CARTESIAN_POINT('',(-3.247454752437E-002,0.78,-0.363917406242) ); -#29903 = CARTESIAN_POINT('',(-3.085762487453E-002,0.782,-0.372321614766) +#32295 = CARTESIAN_POINT('',(-3.085762487453E-002,0.782,-0.372321614766) ); -#29904 = CARTESIAN_POINT('',(-3.085762487453E-002,0.78,-0.372321614766) +#32296 = CARTESIAN_POINT('',(-3.085762487453E-002,0.78,-0.372321614766) ); -#29905 = CARTESIAN_POINT('',(-2.903835183156E-002,0.782,-0.380215078472) +#32297 = CARTESIAN_POINT('',(-2.903835183156E-002,0.782,-0.380215078472) ); -#29906 = CARTESIAN_POINT('',(-2.903835183156E-002,0.78,-0.380215078472) +#32298 = CARTESIAN_POINT('',(-2.903835183156E-002,0.78,-0.380215078472) ); -#29907 = CARTESIAN_POINT('',(-2.685555065364E-002,0.782,-0.387589569702) +#32299 = CARTESIAN_POINT('',(-2.685555065364E-002,0.782,-0.387589569702) ); -#29908 = CARTESIAN_POINT('',(-2.685555065364E-002,0.78,-0.387589569702) +#32300 = CARTESIAN_POINT('',(-2.685555065364E-002,0.78,-0.387589569702) ); -#29909 = CARTESIAN_POINT('',(-2.445736673545E-002,0.782,-0.394508495657) +#32301 = CARTESIAN_POINT('',(-2.445736673545E-002,0.782,-0.394508495657) ); -#29910 = CARTESIAN_POINT('',(-2.445736673545E-002,0.78,-0.394508495657) +#32302 = CARTESIAN_POINT('',(-2.445736673545E-002,0.78,-0.394508495657) ); -#29911 = CARTESIAN_POINT('',(-2.173655057069E-002,0.782,-0.400960756818) +#32303 = CARTESIAN_POINT('',(-2.173655057069E-002,0.782,-0.400960756818) ); -#29912 = CARTESIAN_POINT('',(-2.173655057069E-002,0.78,-0.400960756818) +#32304 = CARTESIAN_POINT('',(-2.173655057069E-002,0.78,-0.400960756818) ); -#29913 = CARTESIAN_POINT('',(-1.867526329643E-002,0.782,-0.406939512268) +#32305 = CARTESIAN_POINT('',(-1.867526329643E-002,0.782,-0.406939512268) ); -#29914 = CARTESIAN_POINT('',(-1.867526329643E-002,0.78,-0.406939512268) +#32306 = CARTESIAN_POINT('',(-1.867526329643E-002,0.78,-0.406939512268) ); -#29915 = CARTESIAN_POINT('',(-1.542394815444E-002,0.782,-0.412506765057) +#32307 = CARTESIAN_POINT('',(-1.542394815444E-002,0.782,-0.412506765057) ); -#29916 = CARTESIAN_POINT('',(-1.542394815444E-002,0.78,-0.412506765057) +#32308 = CARTESIAN_POINT('',(-1.542394815444E-002,0.78,-0.412506765057) ); -#29917 = CARTESIAN_POINT('',(-1.181144925028E-002,0.782,-0.417575921489) +#32309 = CARTESIAN_POINT('',(-1.181144925028E-002,0.782,-0.417575921489) ); -#29918 = CARTESIAN_POINT('',(-1.181144925028E-002,0.78,-0.417575921489) +#32310 = CARTESIAN_POINT('',(-1.181144925028E-002,0.78,-0.417575921489) ); -#29919 = CARTESIAN_POINT('',(-8.055809774141E-003,0.782,-0.422289242847) +#32311 = CARTESIAN_POINT('',(-8.055809774141E-003,0.782,-0.422289242847) ); -#29920 = CARTESIAN_POINT('',(-8.055809774141E-003,0.78,-0.422289242847) +#32312 = CARTESIAN_POINT('',(-8.055809774141E-003,0.78,-0.422289242847) ); -#29921 = CARTESIAN_POINT('',(-3.884092272847E-003,0.782,-0.426473873245) +#32313 = CARTESIAN_POINT('',(-3.884092272847E-003,0.782,-0.426473873245) ); -#29922 = CARTESIAN_POINT('',(-3.884092272847E-003,0.78,-0.426473873245) +#32314 = CARTESIAN_POINT('',(-3.884092272847E-003,0.78,-0.426473873245) ); -#29923 = CARTESIAN_POINT('',(5.302342909642E-004,0.782,-0.430237483603) +#32315 = CARTESIAN_POINT('',(5.302342909642E-004,0.782,-0.430237483603) ); -#29924 = CARTESIAN_POINT('',(5.302342909642E-004,0.78,-0.430237483603)); -#29925 = CARTESIAN_POINT('',(5.252172020433E-003,0.782,-0.433558650412) +#32316 = CARTESIAN_POINT('',(5.302342909642E-004,0.78,-0.430237483603)); +#32317 = CARTESIAN_POINT('',(5.252172020433E-003,0.782,-0.433558650412) ); -#29926 = CARTESIAN_POINT('',(5.252172020433E-003,0.78,-0.433558650412)); -#29927 = CARTESIAN_POINT('',(1.0256737177E-002,0.782,-0.436424416779)); -#29928 = CARTESIAN_POINT('',(1.0256737177E-002,0.78,-0.436424416779)); -#29929 = CARTESIAN_POINT('',(1.552467355536E-002,0.782,-0.438954681848) +#32318 = CARTESIAN_POINT('',(5.252172020433E-003,0.78,-0.433558650412)); +#32319 = CARTESIAN_POINT('',(1.0256737177E-002,0.782,-0.436424416779)); +#32320 = CARTESIAN_POINT('',(1.0256737177E-002,0.78,-0.436424416779)); +#32321 = CARTESIAN_POINT('',(1.552467355536E-002,0.782,-0.438954681848) ); -#29930 = CARTESIAN_POINT('',(1.552467355536E-002,0.78,-0.438954681848)); -#29931 = CARTESIAN_POINT('',(2.115638219723E-002,0.782,-0.44085946473)); -#29932 = CARTESIAN_POINT('',(2.115638219723E-002,0.78,-0.44085946473)); -#29933 = CARTESIAN_POINT('',(2.703494991357E-002,0.782,-0.442412266576) +#32322 = CARTESIAN_POINT('',(1.552467355536E-002,0.78,-0.438954681848)); +#32323 = CARTESIAN_POINT('',(2.115638219723E-002,0.782,-0.44085946473)); +#32324 = CARTESIAN_POINT('',(2.115638219723E-002,0.78,-0.44085946473)); +#32325 = CARTESIAN_POINT('',(2.703494991357E-002,0.782,-0.442412266576) ); -#29934 = CARTESIAN_POINT('',(2.703494991357E-002,0.78,-0.442412266576)); -#29935 = CARTESIAN_POINT('',(3.320562687015E-002,0.782,-0.443554526441) +#32326 = CARTESIAN_POINT('',(2.703494991357E-002,0.78,-0.442412266576)); +#32327 = CARTESIAN_POINT('',(3.320562687015E-002,0.782,-0.443554526441) ); -#29936 = CARTESIAN_POINT('',(3.320562687015E-002,0.78,-0.443554526441)); -#29937 = CARTESIAN_POINT('',(3.96752130578E-002,0.782,-0.44422792718)); -#29938 = CARTESIAN_POINT('',(3.96752130578E-002,0.78,-0.44422792718)); -#29939 = CARTESIAN_POINT('',(4.409626580613E-002,0.782,-0.444296829976) +#32328 = CARTESIAN_POINT('',(3.320562687015E-002,0.78,-0.443554526441)); +#32329 = CARTESIAN_POINT('',(3.96752130578E-002,0.782,-0.44422792718)); +#32330 = CARTESIAN_POINT('',(3.96752130578E-002,0.78,-0.44422792718)); +#32331 = CARTESIAN_POINT('',(4.409626580613E-002,0.782,-0.444296829976) ); -#29940 = CARTESIAN_POINT('',(4.409626580613E-002,0.78,-0.444296829976)); -#29941 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#29942 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); -#29943 = DEFINITIONAL_REPRESENTATION('',(#29944),#29948); -#29944 = LINE('',#29945,#29946); -#29945 = CARTESIAN_POINT('',(0.E+000,1.)); -#29946 = VECTOR('',#29947,1.); -#29947 = DIRECTION('',(1.,0.E+000)); -#29948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#32332 = CARTESIAN_POINT('',(4.409626580613E-002,0.78,-0.444296829976)); +#32333 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#32334 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); +#32335 = DEFINITIONAL_REPRESENTATION('',(#32336),#32340); +#32336 = LINE('',#32337,#32338); +#32337 = CARTESIAN_POINT('',(0.E+000,1.)); +#32338 = VECTOR('',#32339,1.); +#32339 = DIRECTION('',(1.,0.E+000)); +#32340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#29949 = ORIENTED_EDGE('',*,*,#29950,.T.); -#29950 = EDGE_CURVE('',#29825,#29951,#29953,.T.); -#29951 = VERTEX_POINT('',#29952); -#29952 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); -#29953 = SURFACE_CURVE('',#29954,(#29978,#30005),.PCURVE_S1.); -#29954 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29955,#29956,#29957,#29958, - #29959,#29960,#29961,#29962,#29963,#29964,#29965,#29966,#29967, - #29968,#29969,#29970,#29971,#29972,#29973,#29974,#29975,#29976, - #29977),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 +#32341 = ORIENTED_EDGE('',*,*,#32342,.T.); +#32342 = EDGE_CURVE('',#32217,#32343,#32345,.T.); +#32343 = VERTEX_POINT('',#32344); +#32344 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); +#32345 = SURFACE_CURVE('',#32346,(#32370,#32397),.PCURVE_S1.); +#32346 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32347,#32348,#32349,#32350, + #32351,#32352,#32353,#32354,#32355,#32356,#32357,#32358,#32359, + #32360,#32361,#32362,#32363,#32364,#32365,#32366,#32367,#32368, + #32369),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 ,1,4),(0.E+000,5.672433721815E-002,0.111437235737,0.164367822223, 0.216435372462,0.267641490322,0.317359779969,0.367473063332, 0.418210397053,0.471404282647,0.527965720129,0.588061115823, 0.652134262994,0.686344836335,0.723263680317,0.762610250772, 0.804738936645,0.849430338791,0.896711258386,0.946889638053,1.), .UNSPECIFIED.); -#29955 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); -#29956 = CARTESIAN_POINT('',(4.964286228049E-002,0.78,-0.444234897904)); -#29957 = CARTESIAN_POINT('',(5.612269870835E-002,0.78,-0.444044395299)); -#29958 = CARTESIAN_POINT('',(6.558329335559E-002,0.78,-0.442490690621)); -#29959 = CARTESIAN_POINT('',(7.449929406124E-002,0.78,-0.439832839307)); -#29960 = CARTESIAN_POINT('',(8.286490816458E-002,0.78,-0.436247283227)); -#29961 = CARTESIAN_POINT('',(9.053712678853E-002,0.78,-0.431692936904)); -#29962 = CARTESIAN_POINT('',(9.738874139268E-002,0.78,-0.426156435073)); -#29963 = CARTESIAN_POINT('',(0.103345846246,0.78,-0.419695909909)); -#29964 = CARTESIAN_POINT('',(0.108343428768,0.78,-0.412234806307)); -#29965 = CARTESIAN_POINT('',(0.112711814733,0.78,-0.403978951331)); -#29966 = CARTESIAN_POINT('',(0.116592592929,0.78,-0.394891289657)); -#29967 = CARTESIAN_POINT('',(0.120100703701,0.78,-0.384982005036)); -#29968 = CARTESIAN_POINT('',(0.122590135474,0.78,-0.376111811952)); -#29969 = CARTESIAN_POINT('',(0.124365845114,0.78,-0.36845474654)); -#29970 = CARTESIAN_POINT('',(0.12554122381,0.78,-0.362139415592)); -#29971 = CARTESIAN_POINT('',(0.126517023766,0.78,-0.355325137946)); -#29972 = CARTESIAN_POINT('',(0.127264618408,0.78,-0.348028399174)); -#29973 = CARTESIAN_POINT('',(0.127878002172,0.78,-0.340257383216)); -#29974 = CARTESIAN_POINT('',(0.128351690341,0.78,-0.332007251691)); -#29975 = CARTESIAN_POINT('',(0.128592135588,0.78,-0.323257384797)); -#29976 = CARTESIAN_POINT('',(0.128638519777,0.78,-0.317253721294)); -#29977 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); -#29978 = PCURVE('',#28866,#29979); -#29979 = DEFINITIONAL_REPRESENTATION('',(#29980),#30004); -#29980 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#29981,#29982,#29983,#29984, - #29985,#29986,#29987,#29988,#29989,#29990,#29991,#29992,#29993, - #29994,#29995,#29996,#29997,#29998,#29999,#30000,#30001,#30002, - #30003),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 +#32347 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); +#32348 = CARTESIAN_POINT('',(4.964286228049E-002,0.78,-0.444234897904)); +#32349 = CARTESIAN_POINT('',(5.612269870835E-002,0.78,-0.444044395299)); +#32350 = CARTESIAN_POINT('',(6.558329335559E-002,0.78,-0.442490690621)); +#32351 = CARTESIAN_POINT('',(7.449929406124E-002,0.78,-0.439832839307)); +#32352 = CARTESIAN_POINT('',(8.286490816458E-002,0.78,-0.436247283227)); +#32353 = CARTESIAN_POINT('',(9.053712678853E-002,0.78,-0.431692936904)); +#32354 = CARTESIAN_POINT('',(9.738874139268E-002,0.78,-0.426156435073)); +#32355 = CARTESIAN_POINT('',(0.103345846246,0.78,-0.419695909909)); +#32356 = CARTESIAN_POINT('',(0.108343428768,0.78,-0.412234806307)); +#32357 = CARTESIAN_POINT('',(0.112711814733,0.78,-0.403978951331)); +#32358 = CARTESIAN_POINT('',(0.116592592929,0.78,-0.394891289657)); +#32359 = CARTESIAN_POINT('',(0.120100703701,0.78,-0.384982005036)); +#32360 = CARTESIAN_POINT('',(0.122590135474,0.78,-0.376111811952)); +#32361 = CARTESIAN_POINT('',(0.124365845114,0.78,-0.36845474654)); +#32362 = CARTESIAN_POINT('',(0.12554122381,0.78,-0.362139415592)); +#32363 = CARTESIAN_POINT('',(0.126517023766,0.78,-0.355325137946)); +#32364 = CARTESIAN_POINT('',(0.127264618408,0.78,-0.348028399174)); +#32365 = CARTESIAN_POINT('',(0.127878002172,0.78,-0.340257383216)); +#32366 = CARTESIAN_POINT('',(0.128351690341,0.78,-0.332007251691)); +#32367 = CARTESIAN_POINT('',(0.128592135588,0.78,-0.323257384797)); +#32368 = CARTESIAN_POINT('',(0.128638519777,0.78,-0.317253721294)); +#32369 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); +#32370 = PCURVE('',#31258,#32371); +#32371 = DEFINITIONAL_REPRESENTATION('',(#32372),#32396); +#32372 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32373,#32374,#32375,#32376, + #32377,#32378,#32379,#32380,#32381,#32382,#32383,#32384,#32385, + #32386,#32387,#32388,#32389,#32390,#32391,#32392,#32393,#32394, + #32395),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 ,1,4),(0.E+000,5.672433721815E-002,0.111437235737,0.164367822223, 0.216435372462,0.267641490322,0.317359779969,0.367473063332, 0.418210397053,0.471404282647,0.527965720129,0.588061115823, 0.652134262994,0.686344836335,0.723263680317,0.762610250772, 0.804738936645,0.849430338791,0.896711258386,0.946889638053,1.), .UNSPECIFIED.); -#29981 = CARTESIAN_POINT('',(-1.06933186849,1.046344463642)); -#29982 = CARTESIAN_POINT('',(-1.069234897904,1.04964286228)); -#29983 = CARTESIAN_POINT('',(-1.069044395299,1.056122698708)); -#29984 = CARTESIAN_POINT('',(-1.067490690621,1.065583293356)); -#29985 = CARTESIAN_POINT('',(-1.064832839307,1.074499294061)); -#29986 = CARTESIAN_POINT('',(-1.061247283227,1.082864908165)); -#29987 = CARTESIAN_POINT('',(-1.056692936904,1.090537126789)); -#29988 = CARTESIAN_POINT('',(-1.051156435073,1.097388741393)); -#29989 = CARTESIAN_POINT('',(-1.044695909909,1.103345846246)); -#29990 = CARTESIAN_POINT('',(-1.037234806307,1.108343428768)); -#29991 = CARTESIAN_POINT('',(-1.028978951331,1.112711814733)); -#29992 = CARTESIAN_POINT('',(-1.019891289657,1.116592592929)); -#29993 = CARTESIAN_POINT('',(-1.009982005036,1.120100703701)); -#29994 = CARTESIAN_POINT('',(-1.001111811952,1.122590135474)); -#29995 = CARTESIAN_POINT('',(-0.99345474654,1.124365845114)); -#29996 = CARTESIAN_POINT('',(-0.987139415592,1.12554122381)); -#29997 = CARTESIAN_POINT('',(-0.980325137946,1.126517023766)); -#29998 = CARTESIAN_POINT('',(-0.973028399174,1.127264618408)); -#29999 = CARTESIAN_POINT('',(-0.965257383216,1.127878002172)); -#30000 = CARTESIAN_POINT('',(-0.957007251691,1.128351690341)); -#30001 = CARTESIAN_POINT('',(-0.948257384797,1.128592135588)); -#30002 = CARTESIAN_POINT('',(-0.942253721294,1.128638519777)); -#30003 = CARTESIAN_POINT('',(-0.93916667873,1.128662370209)); -#30004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30005 = PCURVE('',#30006,#30053); -#30006 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30007,#30008) - ,(#30009,#30010) - ,(#30011,#30012) - ,(#30013,#30014) - ,(#30015,#30016) - ,(#30017,#30018) - ,(#30019,#30020) - ,(#30021,#30022) - ,(#30023,#30024) - ,(#30025,#30026) - ,(#30027,#30028) - ,(#30029,#30030) - ,(#30031,#30032) - ,(#30033,#30034) - ,(#30035,#30036) - ,(#30037,#30038) - ,(#30039,#30040) - ,(#30041,#30042) - ,(#30043,#30044) - ,(#30045,#30046) - ,(#30047,#30048) - ,(#30049,#30050) - ,(#30051,#30052 +#32373 = CARTESIAN_POINT('',(-1.06933186849,1.046344463642)); +#32374 = CARTESIAN_POINT('',(-1.069234897904,1.04964286228)); +#32375 = CARTESIAN_POINT('',(-1.069044395299,1.056122698708)); +#32376 = CARTESIAN_POINT('',(-1.067490690621,1.065583293356)); +#32377 = CARTESIAN_POINT('',(-1.064832839307,1.074499294061)); +#32378 = CARTESIAN_POINT('',(-1.061247283227,1.082864908165)); +#32379 = CARTESIAN_POINT('',(-1.056692936904,1.090537126789)); +#32380 = CARTESIAN_POINT('',(-1.051156435073,1.097388741393)); +#32381 = CARTESIAN_POINT('',(-1.044695909909,1.103345846246)); +#32382 = CARTESIAN_POINT('',(-1.037234806307,1.108343428768)); +#32383 = CARTESIAN_POINT('',(-1.028978951331,1.112711814733)); +#32384 = CARTESIAN_POINT('',(-1.019891289657,1.116592592929)); +#32385 = CARTESIAN_POINT('',(-1.009982005036,1.120100703701)); +#32386 = CARTESIAN_POINT('',(-1.001111811952,1.122590135474)); +#32387 = CARTESIAN_POINT('',(-0.99345474654,1.124365845114)); +#32388 = CARTESIAN_POINT('',(-0.987139415592,1.12554122381)); +#32389 = CARTESIAN_POINT('',(-0.980325137946,1.126517023766)); +#32390 = CARTESIAN_POINT('',(-0.973028399174,1.127264618408)); +#32391 = CARTESIAN_POINT('',(-0.965257383216,1.127878002172)); +#32392 = CARTESIAN_POINT('',(-0.957007251691,1.128351690341)); +#32393 = CARTESIAN_POINT('',(-0.948257384797,1.128592135588)); +#32394 = CARTESIAN_POINT('',(-0.942253721294,1.128638519777)); +#32395 = CARTESIAN_POINT('',(-0.93916667873,1.128662370209)); +#32396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32397 = PCURVE('',#32398,#32445); +#32398 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32399,#32400) + ,(#32401,#32402) + ,(#32403,#32404) + ,(#32405,#32406) + ,(#32407,#32408) + ,(#32409,#32410) + ,(#32411,#32412) + ,(#32413,#32414) + ,(#32415,#32416) + ,(#32417,#32418) + ,(#32419,#32420) + ,(#32421,#32422) + ,(#32423,#32424) + ,(#32425,#32426) + ,(#32427,#32428) + ,(#32429,#32430) + ,(#32431,#32432) + ,(#32433,#32434) + ,(#32435,#32436) + ,(#32437,#32438) + ,(#32439,#32440) + ,(#32441,#32442) + ,(#32443,#32444 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,4),(2,2),(0.E+000,5.672433721815E-002,0.111437235737, 0.164367822223,0.216435372462,0.267641490322,0.317359779969, @@ -36800,76 +39789,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.588061115823,0.652134262994,0.686344836335,0.723263680317, 0.762610250772,0.804738936645,0.849430338791,0.896711258386, 0.946889638053,1.),(0.E+000,1.),.UNSPECIFIED.); -#30007 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#30008 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); -#30009 = CARTESIAN_POINT('',(4.964286228049E-002,0.782,-0.444234897904) - ); -#30010 = CARTESIAN_POINT('',(4.964286228049E-002,0.78,-0.444234897904)); -#30011 = CARTESIAN_POINT('',(5.612269870835E-002,0.782,-0.444044395299) - ); -#30012 = CARTESIAN_POINT('',(5.612269870835E-002,0.78,-0.444044395299)); -#30013 = CARTESIAN_POINT('',(6.558329335559E-002,0.782,-0.442490690621) - ); -#30014 = CARTESIAN_POINT('',(6.558329335559E-002,0.78,-0.442490690621)); -#30015 = CARTESIAN_POINT('',(7.449929406124E-002,0.782,-0.439832839307) - ); -#30016 = CARTESIAN_POINT('',(7.449929406124E-002,0.78,-0.439832839307)); -#30017 = CARTESIAN_POINT('',(8.286490816458E-002,0.782,-0.436247283227) - ); -#30018 = CARTESIAN_POINT('',(8.286490816458E-002,0.78,-0.436247283227)); -#30019 = CARTESIAN_POINT('',(9.053712678853E-002,0.782,-0.431692936904) - ); -#30020 = CARTESIAN_POINT('',(9.053712678853E-002,0.78,-0.431692936904)); -#30021 = CARTESIAN_POINT('',(9.738874139268E-002,0.782,-0.426156435073) - ); -#30022 = CARTESIAN_POINT('',(9.738874139268E-002,0.78,-0.426156435073)); -#30023 = CARTESIAN_POINT('',(0.103345846246,0.782,-0.419695909909)); -#30024 = CARTESIAN_POINT('',(0.103345846246,0.78,-0.419695909909)); -#30025 = CARTESIAN_POINT('',(0.108343428768,0.782,-0.412234806307)); -#30026 = CARTESIAN_POINT('',(0.108343428768,0.78,-0.412234806307)); -#30027 = CARTESIAN_POINT('',(0.112711814733,0.782,-0.403978951331)); -#30028 = CARTESIAN_POINT('',(0.112711814733,0.78,-0.403978951331)); -#30029 = CARTESIAN_POINT('',(0.116592592929,0.782,-0.394891289657)); -#30030 = CARTESIAN_POINT('',(0.116592592929,0.78,-0.394891289657)); -#30031 = CARTESIAN_POINT('',(0.120100703701,0.782,-0.384982005036)); -#30032 = CARTESIAN_POINT('',(0.120100703701,0.78,-0.384982005036)); -#30033 = CARTESIAN_POINT('',(0.122590135474,0.782,-0.376111811952)); -#30034 = CARTESIAN_POINT('',(0.122590135474,0.78,-0.376111811952)); -#30035 = CARTESIAN_POINT('',(0.124365845114,0.782,-0.36845474654)); -#30036 = CARTESIAN_POINT('',(0.124365845114,0.78,-0.36845474654)); -#30037 = CARTESIAN_POINT('',(0.12554122381,0.782,-0.362139415592)); -#30038 = CARTESIAN_POINT('',(0.12554122381,0.78,-0.362139415592)); -#30039 = CARTESIAN_POINT('',(0.126517023766,0.782,-0.355325137946)); -#30040 = CARTESIAN_POINT('',(0.126517023766,0.78,-0.355325137946)); -#30041 = CARTESIAN_POINT('',(0.127264618408,0.782,-0.348028399174)); -#30042 = CARTESIAN_POINT('',(0.127264618408,0.78,-0.348028399174)); -#30043 = CARTESIAN_POINT('',(0.127878002172,0.782,-0.340257383216)); -#30044 = CARTESIAN_POINT('',(0.127878002172,0.78,-0.340257383216)); -#30045 = CARTESIAN_POINT('',(0.128351690341,0.782,-0.332007251691)); -#30046 = CARTESIAN_POINT('',(0.128351690341,0.78,-0.332007251691)); -#30047 = CARTESIAN_POINT('',(0.128592135588,0.782,-0.323257384797)); -#30048 = CARTESIAN_POINT('',(0.128592135588,0.78,-0.323257384797)); -#30049 = CARTESIAN_POINT('',(0.128638519777,0.782,-0.317253721294)); -#30050 = CARTESIAN_POINT('',(0.128638519777,0.78,-0.317253721294)); -#30051 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#30052 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); -#30053 = DEFINITIONAL_REPRESENTATION('',(#30054),#30058); -#30054 = LINE('',#30055,#30056); -#30055 = CARTESIAN_POINT('',(0.E+000,1.)); -#30056 = VECTOR('',#30057,1.); -#30057 = DIRECTION('',(1.,0.E+000)); -#30058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30059 = ORIENTED_EDGE('',*,*,#30060,.T.); -#30060 = EDGE_CURVE('',#29951,#30061,#30063,.T.); -#30061 = VERTEX_POINT('',#30062); -#30062 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); -#30063 = SURFACE_CURVE('',#30064,(#30092,#30123),.PCURVE_S1.); -#30064 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30065,#30066,#30067,#30068, - #30069,#30070,#30071,#30072,#30073,#30074,#30075,#30076,#30077, - #30078,#30079,#30080,#30081,#30082,#30083,#30084,#30085,#30086, - #30087,#30088,#30089,#30090,#30091),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#32399 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#32400 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.44433186849)); +#32401 = CARTESIAN_POINT('',(4.964286228049E-002,0.782,-0.444234897904) + ); +#32402 = CARTESIAN_POINT('',(4.964286228049E-002,0.78,-0.444234897904)); +#32403 = CARTESIAN_POINT('',(5.612269870835E-002,0.782,-0.444044395299) + ); +#32404 = CARTESIAN_POINT('',(5.612269870835E-002,0.78,-0.444044395299)); +#32405 = CARTESIAN_POINT('',(6.558329335559E-002,0.782,-0.442490690621) + ); +#32406 = CARTESIAN_POINT('',(6.558329335559E-002,0.78,-0.442490690621)); +#32407 = CARTESIAN_POINT('',(7.449929406124E-002,0.782,-0.439832839307) + ); +#32408 = CARTESIAN_POINT('',(7.449929406124E-002,0.78,-0.439832839307)); +#32409 = CARTESIAN_POINT('',(8.286490816458E-002,0.782,-0.436247283227) + ); +#32410 = CARTESIAN_POINT('',(8.286490816458E-002,0.78,-0.436247283227)); +#32411 = CARTESIAN_POINT('',(9.053712678853E-002,0.782,-0.431692936904) + ); +#32412 = CARTESIAN_POINT('',(9.053712678853E-002,0.78,-0.431692936904)); +#32413 = CARTESIAN_POINT('',(9.738874139268E-002,0.782,-0.426156435073) + ); +#32414 = CARTESIAN_POINT('',(9.738874139268E-002,0.78,-0.426156435073)); +#32415 = CARTESIAN_POINT('',(0.103345846246,0.782,-0.419695909909)); +#32416 = CARTESIAN_POINT('',(0.103345846246,0.78,-0.419695909909)); +#32417 = CARTESIAN_POINT('',(0.108343428768,0.782,-0.412234806307)); +#32418 = CARTESIAN_POINT('',(0.108343428768,0.78,-0.412234806307)); +#32419 = CARTESIAN_POINT('',(0.112711814733,0.782,-0.403978951331)); +#32420 = CARTESIAN_POINT('',(0.112711814733,0.78,-0.403978951331)); +#32421 = CARTESIAN_POINT('',(0.116592592929,0.782,-0.394891289657)); +#32422 = CARTESIAN_POINT('',(0.116592592929,0.78,-0.394891289657)); +#32423 = CARTESIAN_POINT('',(0.120100703701,0.782,-0.384982005036)); +#32424 = CARTESIAN_POINT('',(0.120100703701,0.78,-0.384982005036)); +#32425 = CARTESIAN_POINT('',(0.122590135474,0.782,-0.376111811952)); +#32426 = CARTESIAN_POINT('',(0.122590135474,0.78,-0.376111811952)); +#32427 = CARTESIAN_POINT('',(0.124365845114,0.782,-0.36845474654)); +#32428 = CARTESIAN_POINT('',(0.124365845114,0.78,-0.36845474654)); +#32429 = CARTESIAN_POINT('',(0.12554122381,0.782,-0.362139415592)); +#32430 = CARTESIAN_POINT('',(0.12554122381,0.78,-0.362139415592)); +#32431 = CARTESIAN_POINT('',(0.126517023766,0.782,-0.355325137946)); +#32432 = CARTESIAN_POINT('',(0.126517023766,0.78,-0.355325137946)); +#32433 = CARTESIAN_POINT('',(0.127264618408,0.782,-0.348028399174)); +#32434 = CARTESIAN_POINT('',(0.127264618408,0.78,-0.348028399174)); +#32435 = CARTESIAN_POINT('',(0.127878002172,0.782,-0.340257383216)); +#32436 = CARTESIAN_POINT('',(0.127878002172,0.78,-0.340257383216)); +#32437 = CARTESIAN_POINT('',(0.128351690341,0.782,-0.332007251691)); +#32438 = CARTESIAN_POINT('',(0.128351690341,0.78,-0.332007251691)); +#32439 = CARTESIAN_POINT('',(0.128592135588,0.782,-0.323257384797)); +#32440 = CARTESIAN_POINT('',(0.128592135588,0.78,-0.323257384797)); +#32441 = CARTESIAN_POINT('',(0.128638519777,0.782,-0.317253721294)); +#32442 = CARTESIAN_POINT('',(0.128638519777,0.78,-0.317253721294)); +#32443 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#32444 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); +#32445 = DEFINITIONAL_REPRESENTATION('',(#32446),#32450); +#32446 = LINE('',#32447,#32448); +#32447 = CARTESIAN_POINT('',(0.E+000,1.)); +#32448 = VECTOR('',#32449,1.); +#32449 = DIRECTION('',(1.,0.E+000)); +#32450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32451 = ORIENTED_EDGE('',*,*,#32452,.T.); +#32452 = EDGE_CURVE('',#32343,#32453,#32455,.T.); +#32453 = VERTEX_POINT('',#32454); +#32454 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); +#32455 = SURFACE_CURVE('',#32456,(#32484,#32515),.PCURVE_S1.); +#32456 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32457,#32458,#32459,#32460, + #32461,#32462,#32463,#32464,#32465,#32466,#32467,#32468,#32469, + #32470,#32471,#32472,#32473,#32474,#32475,#32476,#32477,#32478, + #32479,#32480,#32481,#32482,#32483),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.287394621143E-002,0.122836629992,0.179656567443,0.233960012231, 0.285595018696,0.334513106078,0.380904825906,0.424894591939, @@ -36877,39 +39866,39 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.617448279949,0.652066912769,0.685879714247,0.719174554791, 0.752181646206,0.785240163918,0.818656449777,0.852547740653, 0.887626342259,0.923635078069,0.961021844477,1.),.UNSPECIFIED.); -#30065 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); -#30066 = CARTESIAN_POINT('',(0.12862857468,0.78,-0.310513555812)); -#30067 = CARTESIAN_POINT('',(0.12856254846,0.78,-0.303376461114)); -#30068 = CARTESIAN_POINT('',(0.128170333926,0.78,-0.292942447254)); -#30069 = CARTESIAN_POINT('',(0.127424306491,0.78,-0.283028963594)); -#30070 = CARTESIAN_POINT('',(0.126506306103,0.78,-0.273613301226)); -#30071 = CARTESIAN_POINT('',(0.125117563801,0.78,-0.264720595538)); -#30072 = CARTESIAN_POINT('',(0.123621118727,0.78,-0.256313063777)); -#30073 = CARTESIAN_POINT('',(0.121770385811,0.78,-0.24842888354)); -#30074 = CARTESIAN_POINT('',(0.119611015005,0.78,-0.241064599394)); -#30075 = CARTESIAN_POINT('',(0.117179073138,0.78,-0.234181271658)); -#30076 = CARTESIAN_POINT('',(0.114512072558,0.78,-0.227726879966)); -#30077 = CARTESIAN_POINT('',(0.111558113332,0.78,-0.221705834687)); -#30078 = CARTESIAN_POINT('',(0.108229274478,0.78,-0.216176862074)); -#30079 = CARTESIAN_POINT('',(0.104677865453,0.78,-0.211066574274)); -#30080 = CARTESIAN_POINT('',(0.100877875962,0.78,-0.206355801449)); -#30081 = CARTESIAN_POINT('',(9.674874177921E-002,0.78,-0.202112345235)); -#30082 = CARTESIAN_POINT('',(9.229463525764E-002,0.78,-0.198360023683)); -#30083 = CARTESIAN_POINT('',(8.760585146748E-002,0.78,-0.194979960739)); -#30084 = CARTESIAN_POINT('',(8.258911929682E-002,0.78,-0.192085900606)); -#30085 = CARTESIAN_POINT('',(7.726639620043E-002,0.78,-0.189688222053)); -#30086 = CARTESIAN_POINT('',(7.167324534091E-002,0.78,-0.187638326011)); -#30087 = CARTESIAN_POINT('',(6.575291613377E-002,0.78,-0.186136282424)); -#30088 = CARTESIAN_POINT('',(5.955209574418E-002,0.78,-0.184986491529)); -#30089 = CARTESIAN_POINT('',(5.30479370719E-002,0.78,-0.184309411386)); -#30090 = CARTESIAN_POINT('',(4.860978407257E-002,0.78,-0.184241795972)); -#30091 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); -#30092 = PCURVE('',#28866,#30093); -#30093 = DEFINITIONAL_REPRESENTATION('',(#30094),#30122); -#30094 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30095,#30096,#30097,#30098, - #30099,#30100,#30101,#30102,#30103,#30104,#30105,#30106,#30107, - #30108,#30109,#30110,#30111,#30112,#30113,#30114,#30115,#30116, - #30117,#30118,#30119,#30120,#30121),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#32457 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); +#32458 = CARTESIAN_POINT('',(0.12862857468,0.78,-0.310513555812)); +#32459 = CARTESIAN_POINT('',(0.12856254846,0.78,-0.303376461114)); +#32460 = CARTESIAN_POINT('',(0.128170333926,0.78,-0.292942447254)); +#32461 = CARTESIAN_POINT('',(0.127424306491,0.78,-0.283028963594)); +#32462 = CARTESIAN_POINT('',(0.126506306103,0.78,-0.273613301226)); +#32463 = CARTESIAN_POINT('',(0.125117563801,0.78,-0.264720595538)); +#32464 = CARTESIAN_POINT('',(0.123621118727,0.78,-0.256313063777)); +#32465 = CARTESIAN_POINT('',(0.121770385811,0.78,-0.24842888354)); +#32466 = CARTESIAN_POINT('',(0.119611015005,0.78,-0.241064599394)); +#32467 = CARTESIAN_POINT('',(0.117179073138,0.78,-0.234181271658)); +#32468 = CARTESIAN_POINT('',(0.114512072558,0.78,-0.227726879966)); +#32469 = CARTESIAN_POINT('',(0.111558113332,0.78,-0.221705834687)); +#32470 = CARTESIAN_POINT('',(0.108229274478,0.78,-0.216176862074)); +#32471 = CARTESIAN_POINT('',(0.104677865453,0.78,-0.211066574274)); +#32472 = CARTESIAN_POINT('',(0.100877875962,0.78,-0.206355801449)); +#32473 = CARTESIAN_POINT('',(9.674874177921E-002,0.78,-0.202112345235)); +#32474 = CARTESIAN_POINT('',(9.229463525764E-002,0.78,-0.198360023683)); +#32475 = CARTESIAN_POINT('',(8.760585146748E-002,0.78,-0.194979960739)); +#32476 = CARTESIAN_POINT('',(8.258911929682E-002,0.78,-0.192085900606)); +#32477 = CARTESIAN_POINT('',(7.726639620043E-002,0.78,-0.189688222053)); +#32478 = CARTESIAN_POINT('',(7.167324534091E-002,0.78,-0.187638326011)); +#32479 = CARTESIAN_POINT('',(6.575291613377E-002,0.78,-0.186136282424)); +#32480 = CARTESIAN_POINT('',(5.955209574418E-002,0.78,-0.184986491529)); +#32481 = CARTESIAN_POINT('',(5.30479370719E-002,0.78,-0.184309411386)); +#32482 = CARTESIAN_POINT('',(4.860978407257E-002,0.78,-0.184241795972)); +#32483 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); +#32484 = PCURVE('',#31258,#32485); +#32485 = DEFINITIONAL_REPRESENTATION('',(#32486),#32514); +#32486 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32487,#32488,#32489,#32490, + #32491,#32492,#32493,#32494,#32495,#32496,#32497,#32498,#32499, + #32500,#32501,#32502,#32503,#32504,#32505,#32506,#32507,#32508, + #32509,#32510,#32511,#32512,#32513),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.287394621143E-002,0.122836629992,0.179656567443,0.233960012231, 0.285595018696,0.334513106078,0.380904825906,0.424894591939, @@ -36917,65 +39906,65 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.617448279949,0.652066912769,0.685879714247,0.719174554791, 0.752181646206,0.785240163918,0.818656449777,0.852547740653, 0.887626342259,0.923635078069,0.961021844477,1.),.UNSPECIFIED.); -#30095 = CARTESIAN_POINT('',(-0.93916667873,1.128662370209)); -#30096 = CARTESIAN_POINT('',(-0.935513555812,1.12862857468)); -#30097 = CARTESIAN_POINT('',(-0.928376461114,1.12856254846)); -#30098 = CARTESIAN_POINT('',(-0.917942447254,1.128170333926)); -#30099 = CARTESIAN_POINT('',(-0.908028963594,1.127424306491)); -#30100 = CARTESIAN_POINT('',(-0.898613301226,1.126506306103)); -#30101 = CARTESIAN_POINT('',(-0.889720595538,1.125117563801)); -#30102 = CARTESIAN_POINT('',(-0.881313063777,1.123621118727)); -#30103 = CARTESIAN_POINT('',(-0.87342888354,1.121770385811)); -#30104 = CARTESIAN_POINT('',(-0.866064599394,1.119611015005)); -#30105 = CARTESIAN_POINT('',(-0.859181271658,1.117179073138)); -#30106 = CARTESIAN_POINT('',(-0.852726879966,1.114512072558)); -#30107 = CARTESIAN_POINT('',(-0.846705834687,1.111558113332)); -#30108 = CARTESIAN_POINT('',(-0.841176862074,1.108229274478)); -#30109 = CARTESIAN_POINT('',(-0.836066574274,1.104677865453)); -#30110 = CARTESIAN_POINT('',(-0.831355801449,1.100877875962)); -#30111 = CARTESIAN_POINT('',(-0.827112345235,1.096748741779)); -#30112 = CARTESIAN_POINT('',(-0.823360023683,1.092294635258)); -#30113 = CARTESIAN_POINT('',(-0.819979960739,1.087605851467)); -#30114 = CARTESIAN_POINT('',(-0.817085900606,1.082589119297)); -#30115 = CARTESIAN_POINT('',(-0.814688222053,1.0772663962)); -#30116 = CARTESIAN_POINT('',(-0.812638326011,1.071673245341)); -#30117 = CARTESIAN_POINT('',(-0.811136282424,1.065752916134)); -#30118 = CARTESIAN_POINT('',(-0.809986491529,1.059552095744)); -#30119 = CARTESIAN_POINT('',(-0.809309411386,1.053047937072)); -#30120 = CARTESIAN_POINT('',(-0.809241795972,1.048609784073)); -#30121 = CARTESIAN_POINT('',(-0.809207283737,1.046344463642)); -#30122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30123 = PCURVE('',#30124,#30179); -#30124 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30125,#30126) - ,(#30127,#30128) - ,(#30129,#30130) - ,(#30131,#30132) - ,(#30133,#30134) - ,(#30135,#30136) - ,(#30137,#30138) - ,(#30139,#30140) - ,(#30141,#30142) - ,(#30143,#30144) - ,(#30145,#30146) - ,(#30147,#30148) - ,(#30149,#30150) - ,(#30151,#30152) - ,(#30153,#30154) - ,(#30155,#30156) - ,(#30157,#30158) - ,(#30159,#30160) - ,(#30161,#30162) - ,(#30163,#30164) - ,(#30165,#30166) - ,(#30167,#30168) - ,(#30169,#30170) - ,(#30171,#30172) - ,(#30173,#30174) - ,(#30175,#30176) - ,(#30177,#30178 +#32487 = CARTESIAN_POINT('',(-0.93916667873,1.128662370209)); +#32488 = CARTESIAN_POINT('',(-0.935513555812,1.12862857468)); +#32489 = CARTESIAN_POINT('',(-0.928376461114,1.12856254846)); +#32490 = CARTESIAN_POINT('',(-0.917942447254,1.128170333926)); +#32491 = CARTESIAN_POINT('',(-0.908028963594,1.127424306491)); +#32492 = CARTESIAN_POINT('',(-0.898613301226,1.126506306103)); +#32493 = CARTESIAN_POINT('',(-0.889720595538,1.125117563801)); +#32494 = CARTESIAN_POINT('',(-0.881313063777,1.123621118727)); +#32495 = CARTESIAN_POINT('',(-0.87342888354,1.121770385811)); +#32496 = CARTESIAN_POINT('',(-0.866064599394,1.119611015005)); +#32497 = CARTESIAN_POINT('',(-0.859181271658,1.117179073138)); +#32498 = CARTESIAN_POINT('',(-0.852726879966,1.114512072558)); +#32499 = CARTESIAN_POINT('',(-0.846705834687,1.111558113332)); +#32500 = CARTESIAN_POINT('',(-0.841176862074,1.108229274478)); +#32501 = CARTESIAN_POINT('',(-0.836066574274,1.104677865453)); +#32502 = CARTESIAN_POINT('',(-0.831355801449,1.100877875962)); +#32503 = CARTESIAN_POINT('',(-0.827112345235,1.096748741779)); +#32504 = CARTESIAN_POINT('',(-0.823360023683,1.092294635258)); +#32505 = CARTESIAN_POINT('',(-0.819979960739,1.087605851467)); +#32506 = CARTESIAN_POINT('',(-0.817085900606,1.082589119297)); +#32507 = CARTESIAN_POINT('',(-0.814688222053,1.0772663962)); +#32508 = CARTESIAN_POINT('',(-0.812638326011,1.071673245341)); +#32509 = CARTESIAN_POINT('',(-0.811136282424,1.065752916134)); +#32510 = CARTESIAN_POINT('',(-0.809986491529,1.059552095744)); +#32511 = CARTESIAN_POINT('',(-0.809309411386,1.053047937072)); +#32512 = CARTESIAN_POINT('',(-0.809241795972,1.048609784073)); +#32513 = CARTESIAN_POINT('',(-0.809207283737,1.046344463642)); +#32514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32515 = PCURVE('',#32516,#32571); +#32516 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32517,#32518) + ,(#32519,#32520) + ,(#32521,#32522) + ,(#32523,#32524) + ,(#32525,#32526) + ,(#32527,#32528) + ,(#32529,#32530) + ,(#32531,#32532) + ,(#32533,#32534) + ,(#32535,#32536) + ,(#32537,#32538) + ,(#32539,#32540) + ,(#32541,#32542) + ,(#32543,#32544) + ,(#32545,#32546) + ,(#32547,#32548) + ,(#32549,#32550) + ,(#32551,#32552) + ,(#32553,#32554) + ,(#32555,#32556) + ,(#32557,#32558) + ,(#32559,#32560) + ,(#32561,#32562) + ,(#32563,#32564) + ,(#32565,#32566) + ,(#32567,#32568) + ,(#32569,#32570 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,4),(2,2),(0.E+000,6.287394621143E-002,0.122836629992, 0.179656567443,0.233960012231,0.285595018696,0.334513106078, @@ -36984,3388 +39973,3388 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.685879714247,0.719174554791,0.752181646206,0.785240163918, 0.818656449777,0.852547740653,0.887626342259,0.923635078069, 0.961021844477,1.),(0.E+000,1.),.UNSPECIFIED.); -#30125 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#30126 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); -#30127 = CARTESIAN_POINT('',(0.12862857468,0.782,-0.310513555812)); -#30128 = CARTESIAN_POINT('',(0.12862857468,0.78,-0.310513555812)); -#30129 = CARTESIAN_POINT('',(0.12856254846,0.782,-0.303376461114)); -#30130 = CARTESIAN_POINT('',(0.12856254846,0.78,-0.303376461114)); -#30131 = CARTESIAN_POINT('',(0.128170333926,0.782,-0.292942447254)); -#30132 = CARTESIAN_POINT('',(0.128170333926,0.78,-0.292942447254)); -#30133 = CARTESIAN_POINT('',(0.127424306491,0.782,-0.283028963594)); -#30134 = CARTESIAN_POINT('',(0.127424306491,0.78,-0.283028963594)); -#30135 = CARTESIAN_POINT('',(0.126506306103,0.782,-0.273613301226)); -#30136 = CARTESIAN_POINT('',(0.126506306103,0.78,-0.273613301226)); -#30137 = CARTESIAN_POINT('',(0.125117563801,0.782,-0.264720595538)); -#30138 = CARTESIAN_POINT('',(0.125117563801,0.78,-0.264720595538)); -#30139 = CARTESIAN_POINT('',(0.123621118727,0.782,-0.256313063777)); -#30140 = CARTESIAN_POINT('',(0.123621118727,0.78,-0.256313063777)); -#30141 = CARTESIAN_POINT('',(0.121770385811,0.782,-0.24842888354)); -#30142 = CARTESIAN_POINT('',(0.121770385811,0.78,-0.24842888354)); -#30143 = CARTESIAN_POINT('',(0.119611015005,0.782,-0.241064599394)); -#30144 = CARTESIAN_POINT('',(0.119611015005,0.78,-0.241064599394)); -#30145 = CARTESIAN_POINT('',(0.117179073138,0.782,-0.234181271658)); -#30146 = CARTESIAN_POINT('',(0.117179073138,0.78,-0.234181271658)); -#30147 = CARTESIAN_POINT('',(0.114512072558,0.782,-0.227726879966)); -#30148 = CARTESIAN_POINT('',(0.114512072558,0.78,-0.227726879966)); -#30149 = CARTESIAN_POINT('',(0.111558113332,0.782,-0.221705834687)); -#30150 = CARTESIAN_POINT('',(0.111558113332,0.78,-0.221705834687)); -#30151 = CARTESIAN_POINT('',(0.108229274478,0.782,-0.216176862074)); -#30152 = CARTESIAN_POINT('',(0.108229274478,0.78,-0.216176862074)); -#30153 = CARTESIAN_POINT('',(0.104677865453,0.782,-0.211066574274)); -#30154 = CARTESIAN_POINT('',(0.104677865453,0.78,-0.211066574274)); -#30155 = CARTESIAN_POINT('',(0.100877875962,0.782,-0.206355801449)); -#30156 = CARTESIAN_POINT('',(0.100877875962,0.78,-0.206355801449)); -#30157 = CARTESIAN_POINT('',(9.674874177921E-002,0.782,-0.202112345235) - ); -#30158 = CARTESIAN_POINT('',(9.674874177921E-002,0.78,-0.202112345235)); -#30159 = CARTESIAN_POINT('',(9.229463525764E-002,0.782,-0.198360023683) - ); -#30160 = CARTESIAN_POINT('',(9.229463525764E-002,0.78,-0.198360023683)); -#30161 = CARTESIAN_POINT('',(8.760585146748E-002,0.782,-0.194979960739) - ); -#30162 = CARTESIAN_POINT('',(8.760585146748E-002,0.78,-0.194979960739)); -#30163 = CARTESIAN_POINT('',(8.258911929682E-002,0.782,-0.192085900606) - ); -#30164 = CARTESIAN_POINT('',(8.258911929682E-002,0.78,-0.192085900606)); -#30165 = CARTESIAN_POINT('',(7.726639620043E-002,0.782,-0.189688222053) - ); -#30166 = CARTESIAN_POINT('',(7.726639620043E-002,0.78,-0.189688222053)); -#30167 = CARTESIAN_POINT('',(7.167324534091E-002,0.782,-0.187638326011) - ); -#30168 = CARTESIAN_POINT('',(7.167324534091E-002,0.78,-0.187638326011)); -#30169 = CARTESIAN_POINT('',(6.575291613377E-002,0.782,-0.186136282424) - ); -#30170 = CARTESIAN_POINT('',(6.575291613377E-002,0.78,-0.186136282424)); -#30171 = CARTESIAN_POINT('',(5.955209574418E-002,0.782,-0.184986491529) - ); -#30172 = CARTESIAN_POINT('',(5.955209574418E-002,0.78,-0.184986491529)); -#30173 = CARTESIAN_POINT('',(5.30479370719E-002,0.782,-0.184309411386)); -#30174 = CARTESIAN_POINT('',(5.30479370719E-002,0.78,-0.184309411386)); -#30175 = CARTESIAN_POINT('',(4.860978407257E-002,0.782,-0.184241795972) - ); -#30176 = CARTESIAN_POINT('',(4.860978407257E-002,0.78,-0.184241795972)); -#30177 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) - ); -#30178 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); -#30179 = DEFINITIONAL_REPRESENTATION('',(#30180),#30184); -#30180 = LINE('',#30181,#30182); -#30181 = CARTESIAN_POINT('',(0.E+000,1.)); -#30182 = VECTOR('',#30183,1.); -#30183 = DIRECTION('',(1.,0.E+000)); -#30184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30185 = ORIENTED_EDGE('',*,*,#30186,.T.); -#30186 = EDGE_CURVE('',#30061,#29761,#30187,.T.); -#30187 = SURFACE_CURVE('',#30188,(#30200,#30215),.PCURVE_S1.); -#30188 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30189,#30190,#30191,#30192, - #30193,#30194,#30195,#30196,#30197,#30198,#30199),.UNSPECIFIED.,.F., +#32517 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#32518 = CARTESIAN_POINT('',(0.128662370209,0.78,-0.31416667873)); +#32519 = CARTESIAN_POINT('',(0.12862857468,0.782,-0.310513555812)); +#32520 = CARTESIAN_POINT('',(0.12862857468,0.78,-0.310513555812)); +#32521 = CARTESIAN_POINT('',(0.12856254846,0.782,-0.303376461114)); +#32522 = CARTESIAN_POINT('',(0.12856254846,0.78,-0.303376461114)); +#32523 = CARTESIAN_POINT('',(0.128170333926,0.782,-0.292942447254)); +#32524 = CARTESIAN_POINT('',(0.128170333926,0.78,-0.292942447254)); +#32525 = CARTESIAN_POINT('',(0.127424306491,0.782,-0.283028963594)); +#32526 = CARTESIAN_POINT('',(0.127424306491,0.78,-0.283028963594)); +#32527 = CARTESIAN_POINT('',(0.126506306103,0.782,-0.273613301226)); +#32528 = CARTESIAN_POINT('',(0.126506306103,0.78,-0.273613301226)); +#32529 = CARTESIAN_POINT('',(0.125117563801,0.782,-0.264720595538)); +#32530 = CARTESIAN_POINT('',(0.125117563801,0.78,-0.264720595538)); +#32531 = CARTESIAN_POINT('',(0.123621118727,0.782,-0.256313063777)); +#32532 = CARTESIAN_POINT('',(0.123621118727,0.78,-0.256313063777)); +#32533 = CARTESIAN_POINT('',(0.121770385811,0.782,-0.24842888354)); +#32534 = CARTESIAN_POINT('',(0.121770385811,0.78,-0.24842888354)); +#32535 = CARTESIAN_POINT('',(0.119611015005,0.782,-0.241064599394)); +#32536 = CARTESIAN_POINT('',(0.119611015005,0.78,-0.241064599394)); +#32537 = CARTESIAN_POINT('',(0.117179073138,0.782,-0.234181271658)); +#32538 = CARTESIAN_POINT('',(0.117179073138,0.78,-0.234181271658)); +#32539 = CARTESIAN_POINT('',(0.114512072558,0.782,-0.227726879966)); +#32540 = CARTESIAN_POINT('',(0.114512072558,0.78,-0.227726879966)); +#32541 = CARTESIAN_POINT('',(0.111558113332,0.782,-0.221705834687)); +#32542 = CARTESIAN_POINT('',(0.111558113332,0.78,-0.221705834687)); +#32543 = CARTESIAN_POINT('',(0.108229274478,0.782,-0.216176862074)); +#32544 = CARTESIAN_POINT('',(0.108229274478,0.78,-0.216176862074)); +#32545 = CARTESIAN_POINT('',(0.104677865453,0.782,-0.211066574274)); +#32546 = CARTESIAN_POINT('',(0.104677865453,0.78,-0.211066574274)); +#32547 = CARTESIAN_POINT('',(0.100877875962,0.782,-0.206355801449)); +#32548 = CARTESIAN_POINT('',(0.100877875962,0.78,-0.206355801449)); +#32549 = CARTESIAN_POINT('',(9.674874177921E-002,0.782,-0.202112345235) + ); +#32550 = CARTESIAN_POINT('',(9.674874177921E-002,0.78,-0.202112345235)); +#32551 = CARTESIAN_POINT('',(9.229463525764E-002,0.782,-0.198360023683) + ); +#32552 = CARTESIAN_POINT('',(9.229463525764E-002,0.78,-0.198360023683)); +#32553 = CARTESIAN_POINT('',(8.760585146748E-002,0.782,-0.194979960739) + ); +#32554 = CARTESIAN_POINT('',(8.760585146748E-002,0.78,-0.194979960739)); +#32555 = CARTESIAN_POINT('',(8.258911929682E-002,0.782,-0.192085900606) + ); +#32556 = CARTESIAN_POINT('',(8.258911929682E-002,0.78,-0.192085900606)); +#32557 = CARTESIAN_POINT('',(7.726639620043E-002,0.782,-0.189688222053) + ); +#32558 = CARTESIAN_POINT('',(7.726639620043E-002,0.78,-0.189688222053)); +#32559 = CARTESIAN_POINT('',(7.167324534091E-002,0.782,-0.187638326011) + ); +#32560 = CARTESIAN_POINT('',(7.167324534091E-002,0.78,-0.187638326011)); +#32561 = CARTESIAN_POINT('',(6.575291613377E-002,0.782,-0.186136282424) + ); +#32562 = CARTESIAN_POINT('',(6.575291613377E-002,0.78,-0.186136282424)); +#32563 = CARTESIAN_POINT('',(5.955209574418E-002,0.782,-0.184986491529) + ); +#32564 = CARTESIAN_POINT('',(5.955209574418E-002,0.78,-0.184986491529)); +#32565 = CARTESIAN_POINT('',(5.30479370719E-002,0.782,-0.184309411386)); +#32566 = CARTESIAN_POINT('',(5.30479370719E-002,0.78,-0.184309411386)); +#32567 = CARTESIAN_POINT('',(4.860978407257E-002,0.782,-0.184241795972) + ); +#32568 = CARTESIAN_POINT('',(4.860978407257E-002,0.78,-0.184241795972)); +#32569 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) + ); +#32570 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); +#32571 = DEFINITIONAL_REPRESENTATION('',(#32572),#32576); +#32572 = LINE('',#32573,#32574); +#32573 = CARTESIAN_POINT('',(0.E+000,1.)); +#32574 = VECTOR('',#32575,1.); +#32575 = DIRECTION('',(1.,0.E+000)); +#32576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32577 = ORIENTED_EDGE('',*,*,#32578,.T.); +#32578 = EDGE_CURVE('',#32453,#32153,#32579,.T.); +#32579 = SURFACE_CURVE('',#32580,(#32592,#32607),.PCURVE_S1.); +#32580 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32581,#32582,#32583,#32584, + #32585,#32586,#32587,#32588,#32589,#32590,#32591),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.137903229993,0.2688733426, 0.395178127346,0.517089238131,0.636743026514,0.756221816464, 0.876628359464,1.),.UNSPECIFIED.); -#30189 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); -#30190 = CARTESIAN_POINT('',(4.337436589961E-002,0.78,-0.184292005932)); -#30191 = CARTESIAN_POINT('',(3.758349277912E-002,0.78,-0.184457190894)); -#30192 = CARTESIAN_POINT('',(2.912634958092E-002,0.78,-0.185579520965)); -#30193 = CARTESIAN_POINT('',(2.118886959051E-002,0.78,-0.187554874584)); -#30194 = CARTESIAN_POINT('',(1.370410470972E-002,0.78,-0.190204102324)); -#30195 = CARTESIAN_POINT('',(6.756185742306E-003,0.78,-0.193747596984)); -#30196 = CARTESIAN_POINT('',(3.119391379252E-004,0.78,-0.198058950176)); -#30197 = CARTESIAN_POINT('',(-5.758127593215E-003,0.78,-0.203037853712) - ); -#30198 = CARTESIAN_POINT('',(-9.252427028939E-003,0.78,-0.206966094314) - ); -#30199 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) - ); -#30200 = PCURVE('',#28866,#30201); -#30201 = DEFINITIONAL_REPRESENTATION('',(#30202),#30214); -#30202 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30203,#30204,#30205,#30206, - #30207,#30208,#30209,#30210,#30211,#30212,#30213),.UNSPECIFIED.,.F., +#32581 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); +#32582 = CARTESIAN_POINT('',(4.337436589961E-002,0.78,-0.184292005932)); +#32583 = CARTESIAN_POINT('',(3.758349277912E-002,0.78,-0.184457190894)); +#32584 = CARTESIAN_POINT('',(2.912634958092E-002,0.78,-0.185579520965)); +#32585 = CARTESIAN_POINT('',(2.118886959051E-002,0.78,-0.187554874584)); +#32586 = CARTESIAN_POINT('',(1.370410470972E-002,0.78,-0.190204102324)); +#32587 = CARTESIAN_POINT('',(6.756185742306E-003,0.78,-0.193747596984)); +#32588 = CARTESIAN_POINT('',(3.119391379252E-004,0.78,-0.198058950176)); +#32589 = CARTESIAN_POINT('',(-5.758127593215E-003,0.78,-0.203037853712) + ); +#32590 = CARTESIAN_POINT('',(-9.252427028939E-003,0.78,-0.206966094314) + ); +#32591 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) + ); +#32592 = PCURVE('',#31258,#32593); +#32593 = DEFINITIONAL_REPRESENTATION('',(#32594),#32606); +#32594 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32595,#32596,#32597,#32598, + #32599,#32600,#32601,#32602,#32603,#32604,#32605),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.137903229993,0.2688733426, 0.395178127346,0.517089238131,0.636743026514,0.756221816464, 0.876628359464,1.),.UNSPECIFIED.); -#30203 = CARTESIAN_POINT('',(-0.809207283737,1.046344463642)); -#30204 = CARTESIAN_POINT('',(-0.809292005932,1.0433743659)); -#30205 = CARTESIAN_POINT('',(-0.809457190894,1.037583492779)); -#30206 = CARTESIAN_POINT('',(-0.810579520965,1.029126349581)); -#30207 = CARTESIAN_POINT('',(-0.812554874584,1.021188869591)); -#30208 = CARTESIAN_POINT('',(-0.815204102324,1.01370410471)); -#30209 = CARTESIAN_POINT('',(-0.818747596984,1.006756185742)); -#30210 = CARTESIAN_POINT('',(-0.823058950176,1.000311939138)); -#30211 = CARTESIAN_POINT('',(-0.828037853712,0.994241872407)); -#30212 = CARTESIAN_POINT('',(-0.831966094314,0.990747572971)); -#30213 = CARTESIAN_POINT('',(-0.833954104399,0.988979172503)); -#30214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30215 = PCURVE('',#30216,#30239); -#30216 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30217,#30218) - ,(#30219,#30220) - ,(#30221,#30222) - ,(#30223,#30224) - ,(#30225,#30226) - ,(#30227,#30228) - ,(#30229,#30230) - ,(#30231,#30232) - ,(#30233,#30234) - ,(#30235,#30236) - ,(#30237,#30238 +#32595 = CARTESIAN_POINT('',(-0.809207283737,1.046344463642)); +#32596 = CARTESIAN_POINT('',(-0.809292005932,1.0433743659)); +#32597 = CARTESIAN_POINT('',(-0.809457190894,1.037583492779)); +#32598 = CARTESIAN_POINT('',(-0.810579520965,1.029126349581)); +#32599 = CARTESIAN_POINT('',(-0.812554874584,1.021188869591)); +#32600 = CARTESIAN_POINT('',(-0.815204102324,1.01370410471)); +#32601 = CARTESIAN_POINT('',(-0.818747596984,1.006756185742)); +#32602 = CARTESIAN_POINT('',(-0.823058950176,1.000311939138)); +#32603 = CARTESIAN_POINT('',(-0.828037853712,0.994241872407)); +#32604 = CARTESIAN_POINT('',(-0.831966094314,0.990747572971)); +#32605 = CARTESIAN_POINT('',(-0.833954104399,0.988979172503)); +#32606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32607 = PCURVE('',#32608,#32631); +#32608 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32609,#32610) + ,(#32611,#32612) + ,(#32613,#32614) + ,(#32615,#32616) + ,(#32617,#32618) + ,(#32619,#32620) + ,(#32621,#32622) + ,(#32623,#32624) + ,(#32625,#32626) + ,(#32627,#32628) + ,(#32629,#32630 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.137903229993,0.2688733426,0.395178127346,0.517089238131, 0.636743026514,0.756221816464,0.876628359464,1.),(0.E+000,1.), .UNSPECIFIED.); -#30217 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) - ); -#30218 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); -#30219 = CARTESIAN_POINT('',(4.337436589961E-002,0.782,-0.184292005932) - ); -#30220 = CARTESIAN_POINT('',(4.337436589961E-002,0.78,-0.184292005932)); -#30221 = CARTESIAN_POINT('',(3.758349277912E-002,0.782,-0.184457190894) - ); -#30222 = CARTESIAN_POINT('',(3.758349277912E-002,0.78,-0.184457190894)); -#30223 = CARTESIAN_POINT('',(2.912634958092E-002,0.782,-0.185579520965) - ); -#30224 = CARTESIAN_POINT('',(2.912634958092E-002,0.78,-0.185579520965)); -#30225 = CARTESIAN_POINT('',(2.118886959051E-002,0.782,-0.187554874584) - ); -#30226 = CARTESIAN_POINT('',(2.118886959051E-002,0.78,-0.187554874584)); -#30227 = CARTESIAN_POINT('',(1.370410470972E-002,0.782,-0.190204102324) - ); -#30228 = CARTESIAN_POINT('',(1.370410470972E-002,0.78,-0.190204102324)); -#30229 = CARTESIAN_POINT('',(6.756185742306E-003,0.782,-0.193747596984) - ); -#30230 = CARTESIAN_POINT('',(6.756185742306E-003,0.78,-0.193747596984)); -#30231 = CARTESIAN_POINT('',(3.119391379252E-004,0.782,-0.198058950176) - ); -#30232 = CARTESIAN_POINT('',(3.119391379252E-004,0.78,-0.198058950176)); -#30233 = CARTESIAN_POINT('',(-5.758127593215E-003,0.782,-0.203037853712) - ); -#30234 = CARTESIAN_POINT('',(-5.758127593215E-003,0.78,-0.203037853712) - ); -#30235 = CARTESIAN_POINT('',(-9.252427028939E-003,0.782,-0.206966094314) - ); -#30236 = CARTESIAN_POINT('',(-9.252427028939E-003,0.78,-0.206966094314) - ); -#30237 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) - ); -#30238 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) - ); -#30239 = DEFINITIONAL_REPRESENTATION('',(#30240),#30244); -#30240 = LINE('',#30241,#30242); -#30241 = CARTESIAN_POINT('',(0.E+000,1.)); -#30242 = VECTOR('',#30243,1.); -#30243 = DIRECTION('',(1.,0.E+000)); -#30244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30245 = FACE_BOUND('',#30246,.T.); -#30246 = EDGE_LOOP('',(#30247,#30277,#30304,#30332)); -#30247 = ORIENTED_EDGE('',*,*,#30248,.F.); -#30248 = EDGE_CURVE('',#30249,#30251,#30253,.T.); -#30249 = VERTEX_POINT('',#30250); -#30250 = CARTESIAN_POINT('',(-0.5,0.78,0.475)); -#30251 = VERTEX_POINT('',#30252); -#30252 = CARTESIAN_POINT('',(-0.5,0.78,-0.475)); -#30253 = SURFACE_CURVE('',#30254,(#30258,#30265),.PCURVE_S1.); -#30254 = LINE('',#30255,#30256); -#30255 = CARTESIAN_POINT('',(-0.5,0.78,0.625)); -#30256 = VECTOR('',#30257,1.); -#30257 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#30258 = PCURVE('',#28866,#30259); -#30259 = DEFINITIONAL_REPRESENTATION('',(#30260),#30264); -#30260 = LINE('',#30261,#30262); -#30261 = CARTESIAN_POINT('',(0.E+000,0.5)); -#30262 = VECTOR('',#30263,1.); -#30263 = DIRECTION('',(-1.,0.E+000)); -#30264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30265 = PCURVE('',#30266,#30271); -#30266 = PLANE('',#30267); -#30267 = AXIS2_PLACEMENT_3D('',#30268,#30269,#30270); -#30268 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#30269 = DIRECTION('',(0.E+000,1.,0.E+000)); -#30270 = DIRECTION('',(0.E+000,0.E+000,1.)); -#30271 = DEFINITIONAL_REPRESENTATION('',(#30272),#30276); -#30272 = LINE('',#30273,#30274); -#30273 = CARTESIAN_POINT('',(0.E+000,0.5)); -#30274 = VECTOR('',#30275,1.); -#30275 = DIRECTION('',(-1.,0.E+000)); -#30276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30277 = ORIENTED_EDGE('',*,*,#30278,.T.); -#30278 = EDGE_CURVE('',#30249,#30279,#30281,.T.); -#30279 = VERTEX_POINT('',#30280); -#30280 = CARTESIAN_POINT('',(0.5,0.78,0.475)); -#30281 = SURFACE_CURVE('',#30282,(#30286,#30293),.PCURVE_S1.); -#30282 = LINE('',#30283,#30284); -#30283 = CARTESIAN_POINT('',(1.,0.78,0.475)); -#30284 = VECTOR('',#30285,1.); -#30285 = DIRECTION('',(1.,0.E+000,0.E+000)); -#30286 = PCURVE('',#28866,#30287); -#30287 = DEFINITIONAL_REPRESENTATION('',(#30288),#30292); -#30288 = LINE('',#30289,#30290); -#30289 = CARTESIAN_POINT('',(-0.15,2.)); -#30290 = VECTOR('',#30291,1.); -#30291 = DIRECTION('',(0.E+000,1.)); -#30292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30293 = PCURVE('',#30294,#30299); -#30294 = CYLINDRICAL_SURFACE('',#30295,0.15); -#30295 = AXIS2_PLACEMENT_3D('',#30296,#30297,#30298); -#30296 = CARTESIAN_POINT('',(-1.,0.63,0.475)); -#30297 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#30298 = DIRECTION('',(0.E+000,0.E+000,1.)); -#30299 = DEFINITIONAL_REPRESENTATION('',(#30300),#30303); -#30300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#30301,#30302),.UNSPECIFIED., +#32609 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) + ); +#32610 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.184207283737)); +#32611 = CARTESIAN_POINT('',(4.337436589961E-002,0.782,-0.184292005932) + ); +#32612 = CARTESIAN_POINT('',(4.337436589961E-002,0.78,-0.184292005932)); +#32613 = CARTESIAN_POINT('',(3.758349277912E-002,0.782,-0.184457190894) + ); +#32614 = CARTESIAN_POINT('',(3.758349277912E-002,0.78,-0.184457190894)); +#32615 = CARTESIAN_POINT('',(2.912634958092E-002,0.782,-0.185579520965) + ); +#32616 = CARTESIAN_POINT('',(2.912634958092E-002,0.78,-0.185579520965)); +#32617 = CARTESIAN_POINT('',(2.118886959051E-002,0.782,-0.187554874584) + ); +#32618 = CARTESIAN_POINT('',(2.118886959051E-002,0.78,-0.187554874584)); +#32619 = CARTESIAN_POINT('',(1.370410470972E-002,0.782,-0.190204102324) + ); +#32620 = CARTESIAN_POINT('',(1.370410470972E-002,0.78,-0.190204102324)); +#32621 = CARTESIAN_POINT('',(6.756185742306E-003,0.782,-0.193747596984) + ); +#32622 = CARTESIAN_POINT('',(6.756185742306E-003,0.78,-0.193747596984)); +#32623 = CARTESIAN_POINT('',(3.119391379252E-004,0.782,-0.198058950176) + ); +#32624 = CARTESIAN_POINT('',(3.119391379252E-004,0.78,-0.198058950176)); +#32625 = CARTESIAN_POINT('',(-5.758127593215E-003,0.782,-0.203037853712) + ); +#32626 = CARTESIAN_POINT('',(-5.758127593215E-003,0.78,-0.203037853712) + ); +#32627 = CARTESIAN_POINT('',(-9.252427028939E-003,0.782,-0.206966094314) + ); +#32628 = CARTESIAN_POINT('',(-9.252427028939E-003,0.78,-0.206966094314) + ); +#32629 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) + ); +#32630 = CARTESIAN_POINT('',(-1.102082749717E-002,0.78,-0.208954104399) + ); +#32631 = DEFINITIONAL_REPRESENTATION('',(#32632),#32636); +#32632 = LINE('',#32633,#32634); +#32633 = CARTESIAN_POINT('',(0.E+000,1.)); +#32634 = VECTOR('',#32635,1.); +#32635 = DIRECTION('',(1.,0.E+000)); +#32636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32637 = FACE_BOUND('',#32638,.T.); +#32638 = EDGE_LOOP('',(#32639,#32669,#32696,#32724)); +#32639 = ORIENTED_EDGE('',*,*,#32640,.F.); +#32640 = EDGE_CURVE('',#32641,#32643,#32645,.T.); +#32641 = VERTEX_POINT('',#32642); +#32642 = CARTESIAN_POINT('',(-0.5,0.78,0.475)); +#32643 = VERTEX_POINT('',#32644); +#32644 = CARTESIAN_POINT('',(-0.5,0.78,-0.475)); +#32645 = SURFACE_CURVE('',#32646,(#32650,#32657),.PCURVE_S1.); +#32646 = LINE('',#32647,#32648); +#32647 = CARTESIAN_POINT('',(-0.5,0.78,0.625)); +#32648 = VECTOR('',#32649,1.); +#32649 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#32650 = PCURVE('',#31258,#32651); +#32651 = DEFINITIONAL_REPRESENTATION('',(#32652),#32656); +#32652 = LINE('',#32653,#32654); +#32653 = CARTESIAN_POINT('',(0.E+000,0.5)); +#32654 = VECTOR('',#32655,1.); +#32655 = DIRECTION('',(-1.,0.E+000)); +#32656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32657 = PCURVE('',#32658,#32663); +#32658 = PLANE('',#32659); +#32659 = AXIS2_PLACEMENT_3D('',#32660,#32661,#32662); +#32660 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#32661 = DIRECTION('',(0.E+000,1.,0.E+000)); +#32662 = DIRECTION('',(0.E+000,0.E+000,1.)); +#32663 = DEFINITIONAL_REPRESENTATION('',(#32664),#32668); +#32664 = LINE('',#32665,#32666); +#32665 = CARTESIAN_POINT('',(0.E+000,0.5)); +#32666 = VECTOR('',#32667,1.); +#32667 = DIRECTION('',(-1.,0.E+000)); +#32668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32669 = ORIENTED_EDGE('',*,*,#32670,.T.); +#32670 = EDGE_CURVE('',#32641,#32671,#32673,.T.); +#32671 = VERTEX_POINT('',#32672); +#32672 = CARTESIAN_POINT('',(0.5,0.78,0.475)); +#32673 = SURFACE_CURVE('',#32674,(#32678,#32685),.PCURVE_S1.); +#32674 = LINE('',#32675,#32676); +#32675 = CARTESIAN_POINT('',(1.,0.78,0.475)); +#32676 = VECTOR('',#32677,1.); +#32677 = DIRECTION('',(1.,0.E+000,0.E+000)); +#32678 = PCURVE('',#31258,#32679); +#32679 = DEFINITIONAL_REPRESENTATION('',(#32680),#32684); +#32680 = LINE('',#32681,#32682); +#32681 = CARTESIAN_POINT('',(-0.15,2.)); +#32682 = VECTOR('',#32683,1.); +#32683 = DIRECTION('',(0.E+000,1.)); +#32684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32685 = PCURVE('',#32686,#32691); +#32686 = CYLINDRICAL_SURFACE('',#32687,0.15); +#32687 = AXIS2_PLACEMENT_3D('',#32688,#32689,#32690); +#32688 = CARTESIAN_POINT('',(-1.,0.63,0.475)); +#32689 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#32690 = DIRECTION('',(0.E+000,0.E+000,1.)); +#32691 = DEFINITIONAL_REPRESENTATION('',(#32692),#32695); +#32692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32693,#32694),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#30301 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#30302 = CARTESIAN_POINT('',(1.570796326795,-1.5)); -#30303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30304 = ORIENTED_EDGE('',*,*,#30305,.F.); -#30305 = EDGE_CURVE('',#30306,#30279,#30308,.T.); -#30306 = VERTEX_POINT('',#30307); -#30307 = CARTESIAN_POINT('',(0.5,0.78,-0.475)); -#30308 = SURFACE_CURVE('',#30309,(#30313,#30320),.PCURVE_S1.); -#30309 = LINE('',#30310,#30311); -#30310 = CARTESIAN_POINT('',(0.5,0.78,0.625)); -#30311 = VECTOR('',#30312,1.); -#30312 = DIRECTION('',(0.E+000,0.E+000,1.)); -#30313 = PCURVE('',#28866,#30314); -#30314 = DEFINITIONAL_REPRESENTATION('',(#30315),#30319); -#30315 = LINE('',#30316,#30317); -#30316 = CARTESIAN_POINT('',(0.E+000,1.5)); -#30317 = VECTOR('',#30318,1.); -#30318 = DIRECTION('',(1.,0.E+000)); -#30319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30320 = PCURVE('',#30321,#30326); -#30321 = PLANE('',#30322); -#30322 = AXIS2_PLACEMENT_3D('',#30323,#30324,#30325); -#30323 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#30324 = DIRECTION('',(0.E+000,1.,0.E+000)); -#30325 = DIRECTION('',(0.E+000,0.E+000,1.)); -#30326 = DEFINITIONAL_REPRESENTATION('',(#30327),#30331); -#30327 = LINE('',#30328,#30329); -#30328 = CARTESIAN_POINT('',(0.E+000,1.5)); -#30329 = VECTOR('',#30330,1.); -#30330 = DIRECTION('',(1.,0.E+000)); -#30331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30332 = ORIENTED_EDGE('',*,*,#30333,.T.); -#30333 = EDGE_CURVE('',#30306,#30251,#30334,.T.); -#30334 = SURFACE_CURVE('',#30335,(#30339,#30346),.PCURVE_S1.); -#30335 = LINE('',#30336,#30337); -#30336 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); -#30337 = VECTOR('',#30338,1.); -#30338 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#30339 = PCURVE('',#28866,#30340); -#30340 = DEFINITIONAL_REPRESENTATION('',(#30341),#30345); -#30341 = LINE('',#30342,#30343); -#30342 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#30343 = VECTOR('',#30344,1.); -#30344 = DIRECTION('',(0.E+000,-1.)); -#30345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30346 = PCURVE('',#30347,#30352); -#30347 = CYLINDRICAL_SURFACE('',#30348,0.15); -#30348 = AXIS2_PLACEMENT_3D('',#30349,#30350,#30351); -#30349 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); -#30350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#30351 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#30352 = DEFINITIONAL_REPRESENTATION('',(#30353),#30356); -#30353 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#30354,#30355),.UNSPECIFIED., +#32693 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#32694 = CARTESIAN_POINT('',(1.570796326795,-1.5)); +#32695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32696 = ORIENTED_EDGE('',*,*,#32697,.F.); +#32697 = EDGE_CURVE('',#32698,#32671,#32700,.T.); +#32698 = VERTEX_POINT('',#32699); +#32699 = CARTESIAN_POINT('',(0.5,0.78,-0.475)); +#32700 = SURFACE_CURVE('',#32701,(#32705,#32712),.PCURVE_S1.); +#32701 = LINE('',#32702,#32703); +#32702 = CARTESIAN_POINT('',(0.5,0.78,0.625)); +#32703 = VECTOR('',#32704,1.); +#32704 = DIRECTION('',(0.E+000,0.E+000,1.)); +#32705 = PCURVE('',#31258,#32706); +#32706 = DEFINITIONAL_REPRESENTATION('',(#32707),#32711); +#32707 = LINE('',#32708,#32709); +#32708 = CARTESIAN_POINT('',(0.E+000,1.5)); +#32709 = VECTOR('',#32710,1.); +#32710 = DIRECTION('',(1.,0.E+000)); +#32711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32712 = PCURVE('',#32713,#32718); +#32713 = PLANE('',#32714); +#32714 = AXIS2_PLACEMENT_3D('',#32715,#32716,#32717); +#32715 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#32716 = DIRECTION('',(0.E+000,1.,0.E+000)); +#32717 = DIRECTION('',(0.E+000,0.E+000,1.)); +#32718 = DEFINITIONAL_REPRESENTATION('',(#32719),#32723); +#32719 = LINE('',#32720,#32721); +#32720 = CARTESIAN_POINT('',(0.E+000,1.5)); +#32721 = VECTOR('',#32722,1.); +#32722 = DIRECTION('',(1.,0.E+000)); +#32723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32724 = ORIENTED_EDGE('',*,*,#32725,.T.); +#32725 = EDGE_CURVE('',#32698,#32643,#32726,.T.); +#32726 = SURFACE_CURVE('',#32727,(#32731,#32738),.PCURVE_S1.); +#32727 = LINE('',#32728,#32729); +#32728 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); +#32729 = VECTOR('',#32730,1.); +#32730 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#32731 = PCURVE('',#31258,#32732); +#32732 = DEFINITIONAL_REPRESENTATION('',(#32733),#32737); +#32733 = LINE('',#32734,#32735); +#32734 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#32735 = VECTOR('',#32736,1.); +#32736 = DIRECTION('',(0.E+000,-1.)); +#32737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32738 = PCURVE('',#32739,#32744); +#32739 = CYLINDRICAL_SURFACE('',#32740,0.15); +#32740 = AXIS2_PLACEMENT_3D('',#32741,#32742,#32743); +#32741 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); +#32742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#32743 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#32744 = DEFINITIONAL_REPRESENTATION('',(#32745),#32748); +#32745 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32746,#32747),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#30354 = CARTESIAN_POINT('',(1.570796326795,1.5)); -#30355 = CARTESIAN_POINT('',(1.570796326795,0.5)); -#30356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30357 = FACE_BOUND('',#30358,.T.); -#30358 = EDGE_LOOP('',(#30359,#30455,#30517,#30611,#30705,#30767,#30861, - #30955)); -#30359 = ORIENTED_EDGE('',*,*,#30360,.T.); -#30360 = EDGE_CURVE('',#30361,#30363,#30365,.T.); -#30361 = VERTEX_POINT('',#30362); -#30362 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); -#30363 = VERTEX_POINT('',#30364); -#30364 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); -#30365 = SURFACE_CURVE('',#30366,(#30386,#30409),.PCURVE_S1.); -#30366 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30367,#30368,#30369,#30370, - #30371,#30372,#30373,#30374,#30375,#30376,#30377,#30378,#30379, - #30380,#30381,#30382,#30383,#30384,#30385),.UNSPECIFIED.,.F.,.F.,(4, +#32746 = CARTESIAN_POINT('',(1.570796326795,1.5)); +#32747 = CARTESIAN_POINT('',(1.570796326795,0.5)); +#32748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32749 = FACE_BOUND('',#32750,.T.); +#32750 = EDGE_LOOP('',(#32751,#32847,#32909,#33003,#33097,#33159,#33253, + #33347)); +#32751 = ORIENTED_EDGE('',*,*,#32752,.T.); +#32752 = EDGE_CURVE('',#32753,#32755,#32757,.T.); +#32753 = VERTEX_POINT('',#32754); +#32754 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); +#32755 = VERTEX_POINT('',#32756); +#32756 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); +#32757 = SURFACE_CURVE('',#32758,(#32778,#32801),.PCURVE_S1.); +#32758 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32759,#32760,#32761,#32762, + #32763,#32764,#32765,#32766,#32767,#32768,#32769,#32770,#32771, + #32772,#32773,#32774,#32775,#32776,#32777),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.983406803225E-002, 0.137026523956,0.201482296865,0.264539949244,0.325972593288, 0.386386309529,0.445760766791,0.505611907075,0.565114421739, 0.624750391664,0.684178951265,0.744219141657,0.805179145467, 0.868394860823,0.933203933413,1.),.UNSPECIFIED.); -#30367 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); -#30368 = CARTESIAN_POINT('',(-0.233491754798,0.78,-0.265188395173)); -#30369 = CARTESIAN_POINT('',(-0.233404116522,0.78,-0.269228153309)); -#30370 = CARTESIAN_POINT('',(-0.232868763985,0.78,-0.275153379217)); -#30371 = CARTESIAN_POINT('',(-0.231801816663,0.78,-0.280800742308)); -#30372 = CARTESIAN_POINT('',(-0.230427520555,0.78,-0.286203522458)); -#30373 = CARTESIAN_POINT('',(-0.228682594508,0.78,-0.291375235964)); -#30374 = CARTESIAN_POINT('',(-0.226529896099,0.78,-0.296275269332)); -#30375 = CARTESIAN_POINT('',(-0.223918118321,0.78,-0.300891779709)); -#30376 = CARTESIAN_POINT('',(-0.220950967505,0.78,-0.305254806535)); -#30377 = CARTESIAN_POINT('',(-0.217591001607,0.78,-0.309333719746)); -#30378 = CARTESIAN_POINT('',(-0.213892677899,0.78,-0.313092799429)); -#30379 = CARTESIAN_POINT('',(-0.209842562382,0.78,-0.316489288576)); -#30380 = CARTESIAN_POINT('',(-0.205531668344,0.78,-0.319622388404)); -#30381 = CARTESIAN_POINT('',(-0.200779298559,0.78,-0.322270472453)); -#30382 = CARTESIAN_POINT('',(-0.195762192151,0.78,-0.324700582966)); -#30383 = CARTESIAN_POINT('',(-0.190394091767,0.78,-0.326773016643)); -#30384 = CARTESIAN_POINT('',(-0.186658868273,0.78,-0.32783003097)); -#30385 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); -#30386 = PCURVE('',#28866,#30387); -#30387 = DEFINITIONAL_REPRESENTATION('',(#30388),#30408); -#30388 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30389,#30390,#30391,#30392, - #30393,#30394,#30395,#30396,#30397,#30398,#30399,#30400,#30401, - #30402,#30403,#30404,#30405,#30406,#30407),.UNSPECIFIED.,.F.,.F.,(4, +#32759 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); +#32760 = CARTESIAN_POINT('',(-0.233491754798,0.78,-0.265188395173)); +#32761 = CARTESIAN_POINT('',(-0.233404116522,0.78,-0.269228153309)); +#32762 = CARTESIAN_POINT('',(-0.232868763985,0.78,-0.275153379217)); +#32763 = CARTESIAN_POINT('',(-0.231801816663,0.78,-0.280800742308)); +#32764 = CARTESIAN_POINT('',(-0.230427520555,0.78,-0.286203522458)); +#32765 = CARTESIAN_POINT('',(-0.228682594508,0.78,-0.291375235964)); +#32766 = CARTESIAN_POINT('',(-0.226529896099,0.78,-0.296275269332)); +#32767 = CARTESIAN_POINT('',(-0.223918118321,0.78,-0.300891779709)); +#32768 = CARTESIAN_POINT('',(-0.220950967505,0.78,-0.305254806535)); +#32769 = CARTESIAN_POINT('',(-0.217591001607,0.78,-0.309333719746)); +#32770 = CARTESIAN_POINT('',(-0.213892677899,0.78,-0.313092799429)); +#32771 = CARTESIAN_POINT('',(-0.209842562382,0.78,-0.316489288576)); +#32772 = CARTESIAN_POINT('',(-0.205531668344,0.78,-0.319622388404)); +#32773 = CARTESIAN_POINT('',(-0.200779298559,0.78,-0.322270472453)); +#32774 = CARTESIAN_POINT('',(-0.195762192151,0.78,-0.324700582966)); +#32775 = CARTESIAN_POINT('',(-0.190394091767,0.78,-0.326773016643)); +#32776 = CARTESIAN_POINT('',(-0.186658868273,0.78,-0.32783003097)); +#32777 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); +#32778 = PCURVE('',#31258,#32779); +#32779 = DEFINITIONAL_REPRESENTATION('',(#32780),#32800); +#32780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32781,#32782,#32783,#32784, + #32785,#32786,#32787,#32788,#32789,#32790,#32791,#32792,#32793, + #32794,#32795,#32796,#32797,#32798,#32799),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.983406803225E-002, 0.137026523956,0.201482296865,0.264539949244,0.325972593288, 0.386386309529,0.445760766791,0.505611907075,0.565114421739, 0.624750391664,0.684178951265,0.744219141657,0.805179145467, 0.868394860823,0.933203933413,1.),.UNSPECIFIED.); -#30389 = CARTESIAN_POINT('',(-0.888129576659,0.766463581313)); -#30390 = CARTESIAN_POINT('',(-0.890188395173,0.766508245202)); -#30391 = CARTESIAN_POINT('',(-0.894228153309,0.766595883478)); -#30392 = CARTESIAN_POINT('',(-0.900153379217,0.767131236015)); -#30393 = CARTESIAN_POINT('',(-0.905800742308,0.768198183337)); -#30394 = CARTESIAN_POINT('',(-0.911203522458,0.769572479445)); -#30395 = CARTESIAN_POINT('',(-0.916375235964,0.771317405492)); -#30396 = CARTESIAN_POINT('',(-0.921275269332,0.773470103901)); -#30397 = CARTESIAN_POINT('',(-0.925891779709,0.776081881679)); -#30398 = CARTESIAN_POINT('',(-0.930254806535,0.779049032495)); -#30399 = CARTESIAN_POINT('',(-0.934333719746,0.782408998393)); -#30400 = CARTESIAN_POINT('',(-0.938092799429,0.786107322101)); -#30401 = CARTESIAN_POINT('',(-0.941489288576,0.790157437618)); -#30402 = CARTESIAN_POINT('',(-0.944622388404,0.794468331656)); -#30403 = CARTESIAN_POINT('',(-0.947270472453,0.799220701441)); -#30404 = CARTESIAN_POINT('',(-0.949700582966,0.804237807849)); -#30405 = CARTESIAN_POINT('',(-0.951773016643,0.809605908233)); -#30406 = CARTESIAN_POINT('',(-0.95283003097,0.813341131727)); -#30407 = CARTESIAN_POINT('',(-0.953366517613,0.815236940954)); -#30408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30409 = PCURVE('',#30410,#30449); -#30410 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30411,#30412) - ,(#30413,#30414) - ,(#30415,#30416) - ,(#30417,#30418) - ,(#30419,#30420) - ,(#30421,#30422) - ,(#30423,#30424) - ,(#30425,#30426) - ,(#30427,#30428) - ,(#30429,#30430) - ,(#30431,#30432) - ,(#30433,#30434) - ,(#30435,#30436) - ,(#30437,#30438) - ,(#30439,#30440) - ,(#30441,#30442) - ,(#30443,#30444) - ,(#30445,#30446) - ,(#30447,#30448 +#32781 = CARTESIAN_POINT('',(-0.888129576659,0.766463581313)); +#32782 = CARTESIAN_POINT('',(-0.890188395173,0.766508245202)); +#32783 = CARTESIAN_POINT('',(-0.894228153309,0.766595883478)); +#32784 = CARTESIAN_POINT('',(-0.900153379217,0.767131236015)); +#32785 = CARTESIAN_POINT('',(-0.905800742308,0.768198183337)); +#32786 = CARTESIAN_POINT('',(-0.911203522458,0.769572479445)); +#32787 = CARTESIAN_POINT('',(-0.916375235964,0.771317405492)); +#32788 = CARTESIAN_POINT('',(-0.921275269332,0.773470103901)); +#32789 = CARTESIAN_POINT('',(-0.925891779709,0.776081881679)); +#32790 = CARTESIAN_POINT('',(-0.930254806535,0.779049032495)); +#32791 = CARTESIAN_POINT('',(-0.934333719746,0.782408998393)); +#32792 = CARTESIAN_POINT('',(-0.938092799429,0.786107322101)); +#32793 = CARTESIAN_POINT('',(-0.941489288576,0.790157437618)); +#32794 = CARTESIAN_POINT('',(-0.944622388404,0.794468331656)); +#32795 = CARTESIAN_POINT('',(-0.947270472453,0.799220701441)); +#32796 = CARTESIAN_POINT('',(-0.949700582966,0.804237807849)); +#32797 = CARTESIAN_POINT('',(-0.951773016643,0.809605908233)); +#32798 = CARTESIAN_POINT('',(-0.95283003097,0.813341131727)); +#32799 = CARTESIAN_POINT('',(-0.953366517613,0.815236940954)); +#32800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32801 = PCURVE('',#32802,#32841); +#32802 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32803,#32804) + ,(#32805,#32806) + ,(#32807,#32808) + ,(#32809,#32810) + ,(#32811,#32812) + ,(#32813,#32814) + ,(#32815,#32816) + ,(#32817,#32818) + ,(#32819,#32820) + ,(#32821,#32822) + ,(#32823,#32824) + ,(#32825,#32826) + ,(#32827,#32828) + ,(#32829,#32830) + ,(#32831,#32832) + ,(#32833,#32834) + ,(#32835,#32836) + ,(#32837,#32838) + ,(#32839,#32840 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.983406803225E-002,0.137026523956,0.201482296865, 0.264539949244,0.325972593288,0.386386309529,0.445760766791, 0.505611907075,0.565114421739,0.624750391664,0.684178951265, 0.744219141657,0.805179145467,0.868394860823,0.933203933413,1.),( 0.E+000,1.),.UNSPECIFIED.); -#30411 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#30412 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); -#30413 = CARTESIAN_POINT('',(-0.233491754798,0.782,-0.265188395173)); -#30414 = CARTESIAN_POINT('',(-0.233491754798,0.78,-0.265188395173)); -#30415 = CARTESIAN_POINT('',(-0.233404116522,0.782,-0.269228153309)); -#30416 = CARTESIAN_POINT('',(-0.233404116522,0.78,-0.269228153309)); -#30417 = CARTESIAN_POINT('',(-0.232868763985,0.782,-0.275153379217)); -#30418 = CARTESIAN_POINT('',(-0.232868763985,0.78,-0.275153379217)); -#30419 = CARTESIAN_POINT('',(-0.231801816663,0.782,-0.280800742308)); -#30420 = CARTESIAN_POINT('',(-0.231801816663,0.78,-0.280800742308)); -#30421 = CARTESIAN_POINT('',(-0.230427520555,0.782,-0.286203522458)); -#30422 = CARTESIAN_POINT('',(-0.230427520555,0.78,-0.286203522458)); -#30423 = CARTESIAN_POINT('',(-0.228682594508,0.782,-0.291375235964)); -#30424 = CARTESIAN_POINT('',(-0.228682594508,0.78,-0.291375235964)); -#30425 = CARTESIAN_POINT('',(-0.226529896099,0.782,-0.296275269332)); -#30426 = CARTESIAN_POINT('',(-0.226529896099,0.78,-0.296275269332)); -#30427 = CARTESIAN_POINT('',(-0.223918118321,0.782,-0.300891779709)); -#30428 = CARTESIAN_POINT('',(-0.223918118321,0.78,-0.300891779709)); -#30429 = CARTESIAN_POINT('',(-0.220950967505,0.782,-0.305254806535)); -#30430 = CARTESIAN_POINT('',(-0.220950967505,0.78,-0.305254806535)); -#30431 = CARTESIAN_POINT('',(-0.217591001607,0.782,-0.309333719746)); -#30432 = CARTESIAN_POINT('',(-0.217591001607,0.78,-0.309333719746)); -#30433 = CARTESIAN_POINT('',(-0.213892677899,0.782,-0.313092799429)); -#30434 = CARTESIAN_POINT('',(-0.213892677899,0.78,-0.313092799429)); -#30435 = CARTESIAN_POINT('',(-0.209842562382,0.782,-0.316489288576)); -#30436 = CARTESIAN_POINT('',(-0.209842562382,0.78,-0.316489288576)); -#30437 = CARTESIAN_POINT('',(-0.205531668344,0.782,-0.319622388404)); -#30438 = CARTESIAN_POINT('',(-0.205531668344,0.78,-0.319622388404)); -#30439 = CARTESIAN_POINT('',(-0.200779298559,0.782,-0.322270472453)); -#30440 = CARTESIAN_POINT('',(-0.200779298559,0.78,-0.322270472453)); -#30441 = CARTESIAN_POINT('',(-0.195762192151,0.782,-0.324700582966)); -#30442 = CARTESIAN_POINT('',(-0.195762192151,0.78,-0.324700582966)); -#30443 = CARTESIAN_POINT('',(-0.190394091767,0.782,-0.326773016643)); -#30444 = CARTESIAN_POINT('',(-0.190394091767,0.78,-0.326773016643)); -#30445 = CARTESIAN_POINT('',(-0.186658868273,0.782,-0.32783003097)); -#30446 = CARTESIAN_POINT('',(-0.186658868273,0.78,-0.32783003097)); -#30447 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#30448 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); -#30449 = DEFINITIONAL_REPRESENTATION('',(#30450),#30454); -#30450 = LINE('',#30451,#30452); -#30451 = CARTESIAN_POINT('',(0.E+000,1.)); -#30452 = VECTOR('',#30453,1.); -#30453 = DIRECTION('',(1.,0.E+000)); -#30454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30455 = ORIENTED_EDGE('',*,*,#30456,.T.); -#30456 = EDGE_CURVE('',#30363,#30457,#30459,.T.); -#30457 = VERTEX_POINT('',#30458); -#30458 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); -#30459 = SURFACE_CURVE('',#30460,(#30472,#30487),.PCURVE_S1.); -#30460 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30461,#30462,#30463,#30464, - #30465,#30466,#30467,#30468,#30469,#30470,#30471),.UNSPECIFIED.,.F., +#32803 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#32804 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); +#32805 = CARTESIAN_POINT('',(-0.233491754798,0.782,-0.265188395173)); +#32806 = CARTESIAN_POINT('',(-0.233491754798,0.78,-0.265188395173)); +#32807 = CARTESIAN_POINT('',(-0.233404116522,0.782,-0.269228153309)); +#32808 = CARTESIAN_POINT('',(-0.233404116522,0.78,-0.269228153309)); +#32809 = CARTESIAN_POINT('',(-0.232868763985,0.782,-0.275153379217)); +#32810 = CARTESIAN_POINT('',(-0.232868763985,0.78,-0.275153379217)); +#32811 = CARTESIAN_POINT('',(-0.231801816663,0.782,-0.280800742308)); +#32812 = CARTESIAN_POINT('',(-0.231801816663,0.78,-0.280800742308)); +#32813 = CARTESIAN_POINT('',(-0.230427520555,0.782,-0.286203522458)); +#32814 = CARTESIAN_POINT('',(-0.230427520555,0.78,-0.286203522458)); +#32815 = CARTESIAN_POINT('',(-0.228682594508,0.782,-0.291375235964)); +#32816 = CARTESIAN_POINT('',(-0.228682594508,0.78,-0.291375235964)); +#32817 = CARTESIAN_POINT('',(-0.226529896099,0.782,-0.296275269332)); +#32818 = CARTESIAN_POINT('',(-0.226529896099,0.78,-0.296275269332)); +#32819 = CARTESIAN_POINT('',(-0.223918118321,0.782,-0.300891779709)); +#32820 = CARTESIAN_POINT('',(-0.223918118321,0.78,-0.300891779709)); +#32821 = CARTESIAN_POINT('',(-0.220950967505,0.782,-0.305254806535)); +#32822 = CARTESIAN_POINT('',(-0.220950967505,0.78,-0.305254806535)); +#32823 = CARTESIAN_POINT('',(-0.217591001607,0.782,-0.309333719746)); +#32824 = CARTESIAN_POINT('',(-0.217591001607,0.78,-0.309333719746)); +#32825 = CARTESIAN_POINT('',(-0.213892677899,0.782,-0.313092799429)); +#32826 = CARTESIAN_POINT('',(-0.213892677899,0.78,-0.313092799429)); +#32827 = CARTESIAN_POINT('',(-0.209842562382,0.782,-0.316489288576)); +#32828 = CARTESIAN_POINT('',(-0.209842562382,0.78,-0.316489288576)); +#32829 = CARTESIAN_POINT('',(-0.205531668344,0.782,-0.319622388404)); +#32830 = CARTESIAN_POINT('',(-0.205531668344,0.78,-0.319622388404)); +#32831 = CARTESIAN_POINT('',(-0.200779298559,0.782,-0.322270472453)); +#32832 = CARTESIAN_POINT('',(-0.200779298559,0.78,-0.322270472453)); +#32833 = CARTESIAN_POINT('',(-0.195762192151,0.782,-0.324700582966)); +#32834 = CARTESIAN_POINT('',(-0.195762192151,0.78,-0.324700582966)); +#32835 = CARTESIAN_POINT('',(-0.190394091767,0.782,-0.326773016643)); +#32836 = CARTESIAN_POINT('',(-0.190394091767,0.78,-0.326773016643)); +#32837 = CARTESIAN_POINT('',(-0.186658868273,0.782,-0.32783003097)); +#32838 = CARTESIAN_POINT('',(-0.186658868273,0.78,-0.32783003097)); +#32839 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#32840 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); +#32841 = DEFINITIONAL_REPRESENTATION('',(#32842),#32846); +#32842 = LINE('',#32843,#32844); +#32843 = CARTESIAN_POINT('',(0.E+000,1.)); +#32844 = VECTOR('',#32845,1.); +#32845 = DIRECTION('',(1.,0.E+000)); +#32846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32847 = ORIENTED_EDGE('',*,*,#32848,.T.); +#32848 = EDGE_CURVE('',#32755,#32849,#32851,.T.); +#32849 = VERTEX_POINT('',#32850); +#32850 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); +#32851 = SURFACE_CURVE('',#32852,(#32864,#32879),.PCURVE_S1.); +#32852 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32853,#32854,#32855,#32856, + #32857,#32858,#32859,#32860,#32861,#32862,#32863),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.145359195055,0.278701778935, 0.403602234418,0.52166879118,0.637520693608,0.753704150763, 0.873212770364,1.),.UNSPECIFIED.); -#30461 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); -#30462 = CARTESIAN_POINT('',(-0.187887265347,0.78,-0.329588724812)); -#30463 = CARTESIAN_POINT('',(-0.193877404834,0.78,-0.331932101303)); -#30464 = CARTESIAN_POINT('',(-0.20195655867,0.78,-0.336621857279)); -#30465 = CARTESIAN_POINT('',(-0.208794270984,0.78,-0.342016803924)); -#30466 = CARTESIAN_POINT('',(-0.214306583707,0.78,-0.348247036847)); -#30467 = CARTESIAN_POINT('',(-0.218507968165,0.78,-0.355183760097)); -#30468 = CARTESIAN_POINT('',(-0.221533131079,0.78,-0.362738530708)); -#30469 = CARTESIAN_POINT('',(-0.223305022055,0.78,-0.37095343712)); -#30470 = CARTESIAN_POINT('',(-0.223538223405,0.78,-0.37663383328)); -#30471 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); -#30472 = PCURVE('',#28866,#30473); -#30473 = DEFINITIONAL_REPRESENTATION('',(#30474),#30486); -#30474 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30475,#30476,#30477,#30478, - #30479,#30480,#30481,#30482,#30483,#30484,#30485),.UNSPECIFIED.,.F., +#32853 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); +#32854 = CARTESIAN_POINT('',(-0.187887265347,0.78,-0.329588724812)); +#32855 = CARTESIAN_POINT('',(-0.193877404834,0.78,-0.331932101303)); +#32856 = CARTESIAN_POINT('',(-0.20195655867,0.78,-0.336621857279)); +#32857 = CARTESIAN_POINT('',(-0.208794270984,0.78,-0.342016803924)); +#32858 = CARTESIAN_POINT('',(-0.214306583707,0.78,-0.348247036847)); +#32859 = CARTESIAN_POINT('',(-0.218507968165,0.78,-0.355183760097)); +#32860 = CARTESIAN_POINT('',(-0.221533131079,0.78,-0.362738530708)); +#32861 = CARTESIAN_POINT('',(-0.223305022055,0.78,-0.37095343712)); +#32862 = CARTESIAN_POINT('',(-0.223538223405,0.78,-0.37663383328)); +#32863 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); +#32864 = PCURVE('',#31258,#32865); +#32865 = DEFINITIONAL_REPRESENTATION('',(#32866),#32878); +#32866 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32867,#32868,#32869,#32870, + #32871,#32872,#32873,#32874,#32875,#32876,#32877),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.145359195055,0.278701778935, 0.403602234418,0.52166879118,0.637520693608,0.753704150763, 0.873212770364,1.),.UNSPECIFIED.); -#30475 = CARTESIAN_POINT('',(-0.953366517613,0.815236940954)); -#30476 = CARTESIAN_POINT('',(-0.954588724812,0.812112734653)); -#30477 = CARTESIAN_POINT('',(-0.956932101303,0.806122595166)); -#30478 = CARTESIAN_POINT('',(-0.961621857279,0.79804344133)); -#30479 = CARTESIAN_POINT('',(-0.967016803924,0.791205729016)); -#30480 = CARTESIAN_POINT('',(-0.973247036847,0.785693416293)); -#30481 = CARTESIAN_POINT('',(-0.980183760097,0.781492031835)); -#30482 = CARTESIAN_POINT('',(-0.987738530708,0.778466868921)); -#30483 = CARTESIAN_POINT('',(-0.99595343712,0.776694977945)); -#30484 = CARTESIAN_POINT('',(-1.00163383328,0.776461776595)); -#30485 = CARTESIAN_POINT('',(-1.00455796576,0.776341730101)); -#30486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30487 = PCURVE('',#30488,#30511); -#30488 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30489,#30490) - ,(#30491,#30492) - ,(#30493,#30494) - ,(#30495,#30496) - ,(#30497,#30498) - ,(#30499,#30500) - ,(#30501,#30502) - ,(#30503,#30504) - ,(#30505,#30506) - ,(#30507,#30508) - ,(#30509,#30510 +#32867 = CARTESIAN_POINT('',(-0.953366517613,0.815236940954)); +#32868 = CARTESIAN_POINT('',(-0.954588724812,0.812112734653)); +#32869 = CARTESIAN_POINT('',(-0.956932101303,0.806122595166)); +#32870 = CARTESIAN_POINT('',(-0.961621857279,0.79804344133)); +#32871 = CARTESIAN_POINT('',(-0.967016803924,0.791205729016)); +#32872 = CARTESIAN_POINT('',(-0.973247036847,0.785693416293)); +#32873 = CARTESIAN_POINT('',(-0.980183760097,0.781492031835)); +#32874 = CARTESIAN_POINT('',(-0.987738530708,0.778466868921)); +#32875 = CARTESIAN_POINT('',(-0.99595343712,0.776694977945)); +#32876 = CARTESIAN_POINT('',(-1.00163383328,0.776461776595)); +#32877 = CARTESIAN_POINT('',(-1.00455796576,0.776341730101)); +#32878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32879 = PCURVE('',#32880,#32903); +#32880 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32881,#32882) + ,(#32883,#32884) + ,(#32885,#32886) + ,(#32887,#32888) + ,(#32889,#32890) + ,(#32891,#32892) + ,(#32893,#32894) + ,(#32895,#32896) + ,(#32897,#32898) + ,(#32899,#32900) + ,(#32901,#32902 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.145359195055,0.278701778935,0.403602234418,0.52166879118, 0.637520693608,0.753704150763,0.873212770364,1.),(0.E+000,1.), .UNSPECIFIED.); -#30489 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#30490 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); -#30491 = CARTESIAN_POINT('',(-0.187887265347,0.782,-0.329588724812)); -#30492 = CARTESIAN_POINT('',(-0.187887265347,0.78,-0.329588724812)); -#30493 = CARTESIAN_POINT('',(-0.193877404834,0.782,-0.331932101303)); -#30494 = CARTESIAN_POINT('',(-0.193877404834,0.78,-0.331932101303)); -#30495 = CARTESIAN_POINT('',(-0.20195655867,0.782,-0.336621857279)); -#30496 = CARTESIAN_POINT('',(-0.20195655867,0.78,-0.336621857279)); -#30497 = CARTESIAN_POINT('',(-0.208794270984,0.782,-0.342016803924)); -#30498 = CARTESIAN_POINT('',(-0.208794270984,0.78,-0.342016803924)); -#30499 = CARTESIAN_POINT('',(-0.214306583707,0.782,-0.348247036847)); -#30500 = CARTESIAN_POINT('',(-0.214306583707,0.78,-0.348247036847)); -#30501 = CARTESIAN_POINT('',(-0.218507968165,0.782,-0.355183760097)); -#30502 = CARTESIAN_POINT('',(-0.218507968165,0.78,-0.355183760097)); -#30503 = CARTESIAN_POINT('',(-0.221533131079,0.782,-0.362738530708)); -#30504 = CARTESIAN_POINT('',(-0.221533131079,0.78,-0.362738530708)); -#30505 = CARTESIAN_POINT('',(-0.223305022055,0.782,-0.37095343712)); -#30506 = CARTESIAN_POINT('',(-0.223305022055,0.78,-0.37095343712)); -#30507 = CARTESIAN_POINT('',(-0.223538223405,0.782,-0.37663383328)); -#30508 = CARTESIAN_POINT('',(-0.223538223405,0.78,-0.37663383328)); -#30509 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#30510 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); -#30511 = DEFINITIONAL_REPRESENTATION('',(#30512),#30516); -#30512 = LINE('',#30513,#30514); -#30513 = CARTESIAN_POINT('',(0.E+000,1.)); -#30514 = VECTOR('',#30515,1.); -#30515 = DIRECTION('',(1.,0.E+000)); -#30516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30517 = ORIENTED_EDGE('',*,*,#30518,.T.); -#30518 = EDGE_CURVE('',#30457,#30519,#30521,.T.); -#30519 = VERTEX_POINT('',#30520); -#30520 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); -#30521 = SURFACE_CURVE('',#30522,(#30542,#30565),.PCURVE_S1.); -#30522 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30523,#30524,#30525,#30526, - #30527,#30528,#30529,#30530,#30531,#30532,#30533,#30534,#30535, - #30536,#30537,#30538,#30539,#30540,#30541),.UNSPECIFIED.,.F.,.F.,(4, +#32881 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#32882 = CARTESIAN_POINT('',(-0.184763059046,0.78,-0.328366517613)); +#32883 = CARTESIAN_POINT('',(-0.187887265347,0.782,-0.329588724812)); +#32884 = CARTESIAN_POINT('',(-0.187887265347,0.78,-0.329588724812)); +#32885 = CARTESIAN_POINT('',(-0.193877404834,0.782,-0.331932101303)); +#32886 = CARTESIAN_POINT('',(-0.193877404834,0.78,-0.331932101303)); +#32887 = CARTESIAN_POINT('',(-0.20195655867,0.782,-0.336621857279)); +#32888 = CARTESIAN_POINT('',(-0.20195655867,0.78,-0.336621857279)); +#32889 = CARTESIAN_POINT('',(-0.208794270984,0.782,-0.342016803924)); +#32890 = CARTESIAN_POINT('',(-0.208794270984,0.78,-0.342016803924)); +#32891 = CARTESIAN_POINT('',(-0.214306583707,0.782,-0.348247036847)); +#32892 = CARTESIAN_POINT('',(-0.214306583707,0.78,-0.348247036847)); +#32893 = CARTESIAN_POINT('',(-0.218507968165,0.782,-0.355183760097)); +#32894 = CARTESIAN_POINT('',(-0.218507968165,0.78,-0.355183760097)); +#32895 = CARTESIAN_POINT('',(-0.221533131079,0.782,-0.362738530708)); +#32896 = CARTESIAN_POINT('',(-0.221533131079,0.78,-0.362738530708)); +#32897 = CARTESIAN_POINT('',(-0.223305022055,0.782,-0.37095343712)); +#32898 = CARTESIAN_POINT('',(-0.223305022055,0.78,-0.37095343712)); +#32899 = CARTESIAN_POINT('',(-0.223538223405,0.782,-0.37663383328)); +#32900 = CARTESIAN_POINT('',(-0.223538223405,0.78,-0.37663383328)); +#32901 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#32902 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); +#32903 = DEFINITIONAL_REPRESENTATION('',(#32904),#32908); +#32904 = LINE('',#32905,#32906); +#32905 = CARTESIAN_POINT('',(0.E+000,1.)); +#32906 = VECTOR('',#32907,1.); +#32907 = DIRECTION('',(1.,0.E+000)); +#32908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32909 = ORIENTED_EDGE('',*,*,#32910,.T.); +#32910 = EDGE_CURVE('',#32849,#32911,#32913,.T.); +#32911 = VERTEX_POINT('',#32912); +#32912 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); +#32913 = SURFACE_CURVE('',#32914,(#32934,#32957),.PCURVE_S1.); +#32914 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32915,#32916,#32917,#32918, + #32919,#32920,#32921,#32922,#32923,#32924,#32925,#32926,#32927, + #32928,#32929,#32930,#32931,#32932,#32933),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.213137173661E-002, 0.121965824785,0.180570236649,0.238575970589,0.296000242091, 0.354358996444,0.413781228052,0.475097965352,0.537279897386, 0.598917953677,0.661235112979,0.724321980574,0.789217182509, 0.856396662088,0.926507768736,1.),.UNSPECIFIED.); -#30523 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); -#30524 = CARTESIAN_POINT('',(-0.223601769609,0.78,-0.38180795677)); -#30525 = CARTESIAN_POINT('',(-0.223490857774,0.78,-0.386224759452)); -#30526 = CARTESIAN_POINT('',(-0.222532554281,0.78,-0.392705669639)); -#30527 = CARTESIAN_POINT('',(-0.220997693172,0.78,-0.398916003004)); -#30528 = CARTESIAN_POINT('',(-0.218819366141,0.78,-0.404838231514)); -#30529 = CARTESIAN_POINT('',(-0.216090279388,0.78,-0.410521100535)); -#30530 = CARTESIAN_POINT('',(-0.212646632142,0.78,-0.415860497384)); -#30531 = CARTESIAN_POINT('',(-0.208688373522,0.78,-0.42100732422)); -#30532 = CARTESIAN_POINT('',(-0.204051461642,0.78,-0.425753530638)); -#30533 = CARTESIAN_POINT('',(-0.198941664913,0.78,-0.430100596353)); -#30534 = CARTESIAN_POINT('',(-0.193406957627,0.78,-0.433969057892)); -#30535 = CARTESIAN_POINT('',(-0.187404988129,0.78,-0.437132518976)); -#30536 = CARTESIAN_POINT('',(-0.181035826347,0.78,-0.439777439017)); -#30537 = CARTESIAN_POINT('',(-0.174267979923,0.78,-0.44184813175)); -#30538 = CARTESIAN_POINT('',(-0.167077608856,0.78,-0.44325838886)); -#30539 = CARTESIAN_POINT('',(-0.159490060777,0.78,-0.444155417005)); -#30540 = CARTESIAN_POINT('',(-0.154290892639,0.78,-0.444272135288)); -#30541 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); -#30542 = PCURVE('',#28866,#30543); -#30543 = DEFINITIONAL_REPRESENTATION('',(#30544),#30564); -#30544 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30545,#30546,#30547,#30548, - #30549,#30550,#30551,#30552,#30553,#30554,#30555,#30556,#30557, - #30558,#30559,#30560,#30561,#30562,#30563),.UNSPECIFIED.,.F.,.F.,(4, +#32915 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); +#32916 = CARTESIAN_POINT('',(-0.223601769609,0.78,-0.38180795677)); +#32917 = CARTESIAN_POINT('',(-0.223490857774,0.78,-0.386224759452)); +#32918 = CARTESIAN_POINT('',(-0.222532554281,0.78,-0.392705669639)); +#32919 = CARTESIAN_POINT('',(-0.220997693172,0.78,-0.398916003004)); +#32920 = CARTESIAN_POINT('',(-0.218819366141,0.78,-0.404838231514)); +#32921 = CARTESIAN_POINT('',(-0.216090279388,0.78,-0.410521100535)); +#32922 = CARTESIAN_POINT('',(-0.212646632142,0.78,-0.415860497384)); +#32923 = CARTESIAN_POINT('',(-0.208688373522,0.78,-0.42100732422)); +#32924 = CARTESIAN_POINT('',(-0.204051461642,0.78,-0.425753530638)); +#32925 = CARTESIAN_POINT('',(-0.198941664913,0.78,-0.430100596353)); +#32926 = CARTESIAN_POINT('',(-0.193406957627,0.78,-0.433969057892)); +#32927 = CARTESIAN_POINT('',(-0.187404988129,0.78,-0.437132518976)); +#32928 = CARTESIAN_POINT('',(-0.181035826347,0.78,-0.439777439017)); +#32929 = CARTESIAN_POINT('',(-0.174267979923,0.78,-0.44184813175)); +#32930 = CARTESIAN_POINT('',(-0.167077608856,0.78,-0.44325838886)); +#32931 = CARTESIAN_POINT('',(-0.159490060777,0.78,-0.444155417005)); +#32932 = CARTESIAN_POINT('',(-0.154290892639,0.78,-0.444272135288)); +#32933 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); +#32934 = PCURVE('',#31258,#32935); +#32935 = DEFINITIONAL_REPRESENTATION('',(#32936),#32956); +#32936 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32937,#32938,#32939,#32940, + #32941,#32942,#32943,#32944,#32945,#32946,#32947,#32948,#32949, + #32950,#32951,#32952,#32953,#32954,#32955),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.213137173661E-002, 0.121965824785,0.180570236649,0.238575970589,0.296000242091, 0.354358996444,0.413781228052,0.475097965352,0.537279897386, 0.598917953677,0.661235112979,0.724321980574,0.789217182509, 0.856396662088,0.926507768736,1.),.UNSPECIFIED.); -#30545 = CARTESIAN_POINT('',(-1.00455796576,0.776341730101)); -#30546 = CARTESIAN_POINT('',(-1.00680795677,0.776398230391)); -#30547 = CARTESIAN_POINT('',(-1.011224759452,0.776509142226)); -#30548 = CARTESIAN_POINT('',(-1.017705669639,0.777467445719)); -#30549 = CARTESIAN_POINT('',(-1.023916003004,0.779002306828)); -#30550 = CARTESIAN_POINT('',(-1.029838231514,0.781180633859)); -#30551 = CARTESIAN_POINT('',(-1.035521100535,0.783909720612)); -#30552 = CARTESIAN_POINT('',(-1.040860497384,0.787353367858)); -#30553 = CARTESIAN_POINT('',(-1.04600732422,0.791311626478)); -#30554 = CARTESIAN_POINT('',(-1.050753530638,0.795948538358)); -#30555 = CARTESIAN_POINT('',(-1.055100596353,0.801058335087)); -#30556 = CARTESIAN_POINT('',(-1.058969057892,0.806593042373)); -#30557 = CARTESIAN_POINT('',(-1.062132518976,0.812595011871)); -#30558 = CARTESIAN_POINT('',(-1.064777439017,0.818964173653)); -#30559 = CARTESIAN_POINT('',(-1.06684813175,0.825732020077)); -#30560 = CARTESIAN_POINT('',(-1.06825838886,0.832922391144)); -#30561 = CARTESIAN_POINT('',(-1.069155417005,0.840509939223)); -#30562 = CARTESIAN_POINT('',(-1.069272135288,0.845709107361)); -#30563 = CARTESIAN_POINT('',(-1.06933186849,0.848369898348)); -#30564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30565 = PCURVE('',#30566,#30605); -#30566 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30567,#30568) - ,(#30569,#30570) - ,(#30571,#30572) - ,(#30573,#30574) - ,(#30575,#30576) - ,(#30577,#30578) - ,(#30579,#30580) - ,(#30581,#30582) - ,(#30583,#30584) - ,(#30585,#30586) - ,(#30587,#30588) - ,(#30589,#30590) - ,(#30591,#30592) - ,(#30593,#30594) - ,(#30595,#30596) - ,(#30597,#30598) - ,(#30599,#30600) - ,(#30601,#30602) - ,(#30603,#30604 +#32937 = CARTESIAN_POINT('',(-1.00455796576,0.776341730101)); +#32938 = CARTESIAN_POINT('',(-1.00680795677,0.776398230391)); +#32939 = CARTESIAN_POINT('',(-1.011224759452,0.776509142226)); +#32940 = CARTESIAN_POINT('',(-1.017705669639,0.777467445719)); +#32941 = CARTESIAN_POINT('',(-1.023916003004,0.779002306828)); +#32942 = CARTESIAN_POINT('',(-1.029838231514,0.781180633859)); +#32943 = CARTESIAN_POINT('',(-1.035521100535,0.783909720612)); +#32944 = CARTESIAN_POINT('',(-1.040860497384,0.787353367858)); +#32945 = CARTESIAN_POINT('',(-1.04600732422,0.791311626478)); +#32946 = CARTESIAN_POINT('',(-1.050753530638,0.795948538358)); +#32947 = CARTESIAN_POINT('',(-1.055100596353,0.801058335087)); +#32948 = CARTESIAN_POINT('',(-1.058969057892,0.806593042373)); +#32949 = CARTESIAN_POINT('',(-1.062132518976,0.812595011871)); +#32950 = CARTESIAN_POINT('',(-1.064777439017,0.818964173653)); +#32951 = CARTESIAN_POINT('',(-1.06684813175,0.825732020077)); +#32952 = CARTESIAN_POINT('',(-1.06825838886,0.832922391144)); +#32953 = CARTESIAN_POINT('',(-1.069155417005,0.840509939223)); +#32954 = CARTESIAN_POINT('',(-1.069272135288,0.845709107361)); +#32955 = CARTESIAN_POINT('',(-1.06933186849,0.848369898348)); +#32956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#32957 = PCURVE('',#32958,#32997); +#32958 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#32959,#32960) + ,(#32961,#32962) + ,(#32963,#32964) + ,(#32965,#32966) + ,(#32967,#32968) + ,(#32969,#32970) + ,(#32971,#32972) + ,(#32973,#32974) + ,(#32975,#32976) + ,(#32977,#32978) + ,(#32979,#32980) + ,(#32981,#32982) + ,(#32983,#32984) + ,(#32985,#32986) + ,(#32987,#32988) + ,(#32989,#32990) + ,(#32991,#32992) + ,(#32993,#32994) + ,(#32995,#32996 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.213137173661E-002,0.121965824785,0.180570236649, 0.238575970589,0.296000242091,0.354358996444,0.413781228052, 0.475097965352,0.537279897386,0.598917953677,0.661235112979, 0.724321980574,0.789217182509,0.856396662088,0.926507768736,1.),( 0.E+000,1.),.UNSPECIFIED.); -#30567 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#30568 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); -#30569 = CARTESIAN_POINT('',(-0.223601769609,0.782,-0.38180795677)); -#30570 = CARTESIAN_POINT('',(-0.223601769609,0.78,-0.38180795677)); -#30571 = CARTESIAN_POINT('',(-0.223490857774,0.782,-0.386224759452)); -#30572 = CARTESIAN_POINT('',(-0.223490857774,0.78,-0.386224759452)); -#30573 = CARTESIAN_POINT('',(-0.222532554281,0.782,-0.392705669639)); -#30574 = CARTESIAN_POINT('',(-0.222532554281,0.78,-0.392705669639)); -#30575 = CARTESIAN_POINT('',(-0.220997693172,0.782,-0.398916003004)); -#30576 = CARTESIAN_POINT('',(-0.220997693172,0.78,-0.398916003004)); -#30577 = CARTESIAN_POINT('',(-0.218819366141,0.782,-0.404838231514)); -#30578 = CARTESIAN_POINT('',(-0.218819366141,0.78,-0.404838231514)); -#30579 = CARTESIAN_POINT('',(-0.216090279388,0.782,-0.410521100535)); -#30580 = CARTESIAN_POINT('',(-0.216090279388,0.78,-0.410521100535)); -#30581 = CARTESIAN_POINT('',(-0.212646632142,0.782,-0.415860497384)); -#30582 = CARTESIAN_POINT('',(-0.212646632142,0.78,-0.415860497384)); -#30583 = CARTESIAN_POINT('',(-0.208688373522,0.782,-0.42100732422)); -#30584 = CARTESIAN_POINT('',(-0.208688373522,0.78,-0.42100732422)); -#30585 = CARTESIAN_POINT('',(-0.204051461642,0.782,-0.425753530638)); -#30586 = CARTESIAN_POINT('',(-0.204051461642,0.78,-0.425753530638)); -#30587 = CARTESIAN_POINT('',(-0.198941664913,0.782,-0.430100596353)); -#30588 = CARTESIAN_POINT('',(-0.198941664913,0.78,-0.430100596353)); -#30589 = CARTESIAN_POINT('',(-0.193406957627,0.782,-0.433969057892)); -#30590 = CARTESIAN_POINT('',(-0.193406957627,0.78,-0.433969057892)); -#30591 = CARTESIAN_POINT('',(-0.187404988129,0.782,-0.437132518976)); -#30592 = CARTESIAN_POINT('',(-0.187404988129,0.78,-0.437132518976)); -#30593 = CARTESIAN_POINT('',(-0.181035826347,0.782,-0.439777439017)); -#30594 = CARTESIAN_POINT('',(-0.181035826347,0.78,-0.439777439017)); -#30595 = CARTESIAN_POINT('',(-0.174267979923,0.782,-0.44184813175)); -#30596 = CARTESIAN_POINT('',(-0.174267979923,0.78,-0.44184813175)); -#30597 = CARTESIAN_POINT('',(-0.167077608856,0.782,-0.44325838886)); -#30598 = CARTESIAN_POINT('',(-0.167077608856,0.78,-0.44325838886)); -#30599 = CARTESIAN_POINT('',(-0.159490060777,0.782,-0.444155417005)); -#30600 = CARTESIAN_POINT('',(-0.159490060777,0.78,-0.444155417005)); -#30601 = CARTESIAN_POINT('',(-0.154290892639,0.782,-0.444272135288)); -#30602 = CARTESIAN_POINT('',(-0.154290892639,0.78,-0.444272135288)); -#30603 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#30604 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); -#30605 = DEFINITIONAL_REPRESENTATION('',(#30606),#30610); -#30606 = LINE('',#30607,#30608); -#30607 = CARTESIAN_POINT('',(0.E+000,1.)); -#30608 = VECTOR('',#30609,1.); -#30609 = DIRECTION('',(1.,0.E+000)); -#30610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30611 = ORIENTED_EDGE('',*,*,#30612,.T.); -#30612 = EDGE_CURVE('',#30519,#30613,#30615,.T.); -#30613 = VERTEX_POINT('',#30614); -#30614 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) - ); -#30615 = SURFACE_CURVE('',#30616,(#30636,#30659),.PCURVE_S1.); -#30616 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30617,#30618,#30619,#30620, - #30621,#30622,#30623,#30624,#30625,#30626,#30627,#30628,#30629, - #30630,#30631,#30632,#30633,#30634,#30635),.UNSPECIFIED.,.F.,.F.,(4, +#32959 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#32960 = CARTESIAN_POINT('',(-0.223658269899,0.78,-0.37955796576)); +#32961 = CARTESIAN_POINT('',(-0.223601769609,0.782,-0.38180795677)); +#32962 = CARTESIAN_POINT('',(-0.223601769609,0.78,-0.38180795677)); +#32963 = CARTESIAN_POINT('',(-0.223490857774,0.782,-0.386224759452)); +#32964 = CARTESIAN_POINT('',(-0.223490857774,0.78,-0.386224759452)); +#32965 = CARTESIAN_POINT('',(-0.222532554281,0.782,-0.392705669639)); +#32966 = CARTESIAN_POINT('',(-0.222532554281,0.78,-0.392705669639)); +#32967 = CARTESIAN_POINT('',(-0.220997693172,0.782,-0.398916003004)); +#32968 = CARTESIAN_POINT('',(-0.220997693172,0.78,-0.398916003004)); +#32969 = CARTESIAN_POINT('',(-0.218819366141,0.782,-0.404838231514)); +#32970 = CARTESIAN_POINT('',(-0.218819366141,0.78,-0.404838231514)); +#32971 = CARTESIAN_POINT('',(-0.216090279388,0.782,-0.410521100535)); +#32972 = CARTESIAN_POINT('',(-0.216090279388,0.78,-0.410521100535)); +#32973 = CARTESIAN_POINT('',(-0.212646632142,0.782,-0.415860497384)); +#32974 = CARTESIAN_POINT('',(-0.212646632142,0.78,-0.415860497384)); +#32975 = CARTESIAN_POINT('',(-0.208688373522,0.782,-0.42100732422)); +#32976 = CARTESIAN_POINT('',(-0.208688373522,0.78,-0.42100732422)); +#32977 = CARTESIAN_POINT('',(-0.204051461642,0.782,-0.425753530638)); +#32978 = CARTESIAN_POINT('',(-0.204051461642,0.78,-0.425753530638)); +#32979 = CARTESIAN_POINT('',(-0.198941664913,0.782,-0.430100596353)); +#32980 = CARTESIAN_POINT('',(-0.198941664913,0.78,-0.430100596353)); +#32981 = CARTESIAN_POINT('',(-0.193406957627,0.782,-0.433969057892)); +#32982 = CARTESIAN_POINT('',(-0.193406957627,0.78,-0.433969057892)); +#32983 = CARTESIAN_POINT('',(-0.187404988129,0.782,-0.437132518976)); +#32984 = CARTESIAN_POINT('',(-0.187404988129,0.78,-0.437132518976)); +#32985 = CARTESIAN_POINT('',(-0.181035826347,0.782,-0.439777439017)); +#32986 = CARTESIAN_POINT('',(-0.181035826347,0.78,-0.439777439017)); +#32987 = CARTESIAN_POINT('',(-0.174267979923,0.782,-0.44184813175)); +#32988 = CARTESIAN_POINT('',(-0.174267979923,0.78,-0.44184813175)); +#32989 = CARTESIAN_POINT('',(-0.167077608856,0.782,-0.44325838886)); +#32990 = CARTESIAN_POINT('',(-0.167077608856,0.78,-0.44325838886)); +#32991 = CARTESIAN_POINT('',(-0.159490060777,0.782,-0.444155417005)); +#32992 = CARTESIAN_POINT('',(-0.159490060777,0.78,-0.444155417005)); +#32993 = CARTESIAN_POINT('',(-0.154290892639,0.782,-0.444272135288)); +#32994 = CARTESIAN_POINT('',(-0.154290892639,0.78,-0.444272135288)); +#32995 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#32996 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); +#32997 = DEFINITIONAL_REPRESENTATION('',(#32998),#33002); +#32998 = LINE('',#32999,#33000); +#32999 = CARTESIAN_POINT('',(0.E+000,1.)); +#33000 = VECTOR('',#33001,1.); +#33001 = DIRECTION('',(1.,0.E+000)); +#33002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33003 = ORIENTED_EDGE('',*,*,#33004,.T.); +#33004 = EDGE_CURVE('',#32911,#33005,#33007,.T.); +#33005 = VERTEX_POINT('',#33006); +#33006 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) + ); +#33007 = SURFACE_CURVE('',#33008,(#33028,#33051),.PCURVE_S1.); +#33008 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33009,#33010,#33011,#33012, + #33013,#33014,#33015,#33016,#33017,#33018,#33019,#33020,#33021, + #33022,#33023,#33024,#33025,#33026,#33027),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.320074496854E-002, 0.142586791322,0.209624781468,0.274882926768,0.337930609532, 0.400461822188,0.462500620686,0.525005458137,0.586688852711, 0.646812765771,0.705215315751,0.762881021008,0.820727541693, 0.879295495725,0.938511165414,1.),.UNSPECIFIED.); -#30617 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); -#30618 = CARTESIAN_POINT('',(-0.148952355843,0.78,-0.444271528812)); -#30619 = CARTESIAN_POINT('',(-0.14373640916,0.78,-0.444153993928)); -#30620 = CARTESIAN_POINT('',(-0.136108549957,0.78,-0.443269018362)); -#30621 = CARTESIAN_POINT('',(-0.12887280298,0.78,-0.441785744181)); -#30622 = CARTESIAN_POINT('',(-0.122033428257,0.78,-0.439681351531)); -#30623 = CARTESIAN_POINT('',(-0.115579643283,0.78,-0.436990758818)); -#30624 = CARTESIAN_POINT('',(-0.109553855828,0.78,-0.433683667182)); -#30625 = CARTESIAN_POINT('',(-0.103894034067,0.78,-0.429814621087)); -#30626 = CARTESIAN_POINT('',(-9.874484109579E-002,0.78,-0.425337480783) +#33009 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); +#33010 = CARTESIAN_POINT('',(-0.148952355843,0.78,-0.444271528812)); +#33011 = CARTESIAN_POINT('',(-0.14373640916,0.78,-0.444153993928)); +#33012 = CARTESIAN_POINT('',(-0.136108549957,0.78,-0.443269018362)); +#33013 = CARTESIAN_POINT('',(-0.12887280298,0.78,-0.441785744181)); +#33014 = CARTESIAN_POINT('',(-0.122033428257,0.78,-0.439681351531)); +#33015 = CARTESIAN_POINT('',(-0.115579643283,0.78,-0.436990758818)); +#33016 = CARTESIAN_POINT('',(-0.109553855828,0.78,-0.433683667182)); +#33017 = CARTESIAN_POINT('',(-0.103894034067,0.78,-0.429814621087)); +#33018 = CARTESIAN_POINT('',(-9.874484109579E-002,0.78,-0.425337480783) ); -#30627 = CARTESIAN_POINT('',(-9.40596892566E-002,0.78,-0.420476762361)); -#30628 = CARTESIAN_POINT('',(-9.000044772922E-002,0.78,-0.415269287689) +#33019 = CARTESIAN_POINT('',(-9.40596892566E-002,0.78,-0.420476762361)); +#33020 = CARTESIAN_POINT('',(-9.000044772922E-002,0.78,-0.415269287689) ); -#30629 = CARTESIAN_POINT('',(-8.651896546958E-002,0.78,-0.409836569666) +#33021 = CARTESIAN_POINT('',(-8.651896546958E-002,0.78,-0.409836569666) ); -#30630 = CARTESIAN_POINT('',(-8.364204346514E-002,0.78,-0.404145603279) +#33022 = CARTESIAN_POINT('',(-8.364204346514E-002,0.78,-0.404145603279) ); -#30631 = CARTESIAN_POINT('',(-8.151368568852E-002,0.78,-0.398131583659) +#33023 = CARTESIAN_POINT('',(-8.151368568852E-002,0.78,-0.398131583659) ); -#30632 = CARTESIAN_POINT('',(-7.989139930784E-002,0.78,-0.391907817721) +#33024 = CARTESIAN_POINT('',(-7.989139930784E-002,0.78,-0.391907817721) ); -#30633 = CARTESIAN_POINT('',(-7.895039800517E-002,0.78,-0.385400354993) +#33025 = CARTESIAN_POINT('',(-7.895039800517E-002,0.78,-0.385400354993) ); -#30634 = CARTESIAN_POINT('',(-7.883668274196E-002,0.78,-0.380984364144) +#33026 = CARTESIAN_POINT('',(-7.883668274196E-002,0.78,-0.380984364144) ); -#30635 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) +#33027 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) ); -#30636 = PCURVE('',#28866,#30637); -#30637 = DEFINITIONAL_REPRESENTATION('',(#30638),#30658); -#30638 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30639,#30640,#30641,#30642, - #30643,#30644,#30645,#30646,#30647,#30648,#30649,#30650,#30651, - #30652,#30653,#30654,#30655,#30656,#30657),.UNSPECIFIED.,.F.,.F.,(4, +#33028 = PCURVE('',#31258,#33029); +#33029 = DEFINITIONAL_REPRESENTATION('',(#33030),#33050); +#33030 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33031,#33032,#33033,#33034, + #33035,#33036,#33037,#33038,#33039,#33040,#33041,#33042,#33043, + #33044,#33045,#33046,#33047,#33048,#33049),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.320074496854E-002, 0.142586791322,0.209624781468,0.274882926768,0.337930609532, 0.400461822188,0.462500620686,0.525005458137,0.586688852711, 0.646812765771,0.705215315751,0.762881021008,0.820727541693, 0.879295495725,0.938511165414,1.),.UNSPECIFIED.); -#30639 = CARTESIAN_POINT('',(-1.06933186849,0.848369898348)); -#30640 = CARTESIAN_POINT('',(-1.069271528812,0.851047644157)); -#30641 = CARTESIAN_POINT('',(-1.069153993928,0.85626359084)); -#30642 = CARTESIAN_POINT('',(-1.068269018362,0.863891450043)); -#30643 = CARTESIAN_POINT('',(-1.066785744181,0.87112719702)); -#30644 = CARTESIAN_POINT('',(-1.064681351531,0.877966571743)); -#30645 = CARTESIAN_POINT('',(-1.061990758818,0.884420356717)); -#30646 = CARTESIAN_POINT('',(-1.058683667182,0.890446144172)); -#30647 = CARTESIAN_POINT('',(-1.054814621087,0.896105965933)); -#30648 = CARTESIAN_POINT('',(-1.050337480783,0.901255158904)); -#30649 = CARTESIAN_POINT('',(-1.045476762361,0.905940310743)); -#30650 = CARTESIAN_POINT('',(-1.040269287689,0.909999552271)); -#30651 = CARTESIAN_POINT('',(-1.034836569666,0.91348103453)); -#30652 = CARTESIAN_POINT('',(-1.029145603279,0.916357956535)); -#30653 = CARTESIAN_POINT('',(-1.023131583659,0.918486314311)); -#30654 = CARTESIAN_POINT('',(-1.016907817721,0.920108600692)); -#30655 = CARTESIAN_POINT('',(-1.010400354993,0.921049601995)); -#30656 = CARTESIAN_POINT('',(-1.005984364144,0.921163317258)); -#30657 = CARTESIAN_POINT('',(-1.003734786694,0.92122124566)); -#30658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30659 = PCURVE('',#30660,#30699); -#30660 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30661,#30662) - ,(#30663,#30664) - ,(#30665,#30666) - ,(#30667,#30668) - ,(#30669,#30670) - ,(#30671,#30672) - ,(#30673,#30674) - ,(#30675,#30676) - ,(#30677,#30678) - ,(#30679,#30680) - ,(#30681,#30682) - ,(#30683,#30684) - ,(#30685,#30686) - ,(#30687,#30688) - ,(#30689,#30690) - ,(#30691,#30692) - ,(#30693,#30694) - ,(#30695,#30696) - ,(#30697,#30698 +#33031 = CARTESIAN_POINT('',(-1.06933186849,0.848369898348)); +#33032 = CARTESIAN_POINT('',(-1.069271528812,0.851047644157)); +#33033 = CARTESIAN_POINT('',(-1.069153993928,0.85626359084)); +#33034 = CARTESIAN_POINT('',(-1.068269018362,0.863891450043)); +#33035 = CARTESIAN_POINT('',(-1.066785744181,0.87112719702)); +#33036 = CARTESIAN_POINT('',(-1.064681351531,0.877966571743)); +#33037 = CARTESIAN_POINT('',(-1.061990758818,0.884420356717)); +#33038 = CARTESIAN_POINT('',(-1.058683667182,0.890446144172)); +#33039 = CARTESIAN_POINT('',(-1.054814621087,0.896105965933)); +#33040 = CARTESIAN_POINT('',(-1.050337480783,0.901255158904)); +#33041 = CARTESIAN_POINT('',(-1.045476762361,0.905940310743)); +#33042 = CARTESIAN_POINT('',(-1.040269287689,0.909999552271)); +#33043 = CARTESIAN_POINT('',(-1.034836569666,0.91348103453)); +#33044 = CARTESIAN_POINT('',(-1.029145603279,0.916357956535)); +#33045 = CARTESIAN_POINT('',(-1.023131583659,0.918486314311)); +#33046 = CARTESIAN_POINT('',(-1.016907817721,0.920108600692)); +#33047 = CARTESIAN_POINT('',(-1.010400354993,0.921049601995)); +#33048 = CARTESIAN_POINT('',(-1.005984364144,0.921163317258)); +#33049 = CARTESIAN_POINT('',(-1.003734786694,0.92122124566)); +#33050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33051 = PCURVE('',#33052,#33091); +#33052 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#33053,#33054) + ,(#33055,#33056) + ,(#33057,#33058) + ,(#33059,#33060) + ,(#33061,#33062) + ,(#33063,#33064) + ,(#33065,#33066) + ,(#33067,#33068) + ,(#33069,#33070) + ,(#33071,#33072) + ,(#33073,#33074) + ,(#33075,#33076) + ,(#33077,#33078) + ,(#33079,#33080) + ,(#33081,#33082) + ,(#33083,#33084) + ,(#33085,#33086) + ,(#33087,#33088) + ,(#33089,#33090 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.320074496854E-002,0.142586791322,0.209624781468, 0.274882926768,0.337930609532,0.400461822188,0.462500620686, 0.525005458137,0.586688852711,0.646812765771,0.705215315751, 0.762881021008,0.820727541693,0.879295495725,0.938511165414,1.),( 0.E+000,1.),.UNSPECIFIED.); -#30661 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#30662 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); -#30663 = CARTESIAN_POINT('',(-0.148952355843,0.782,-0.444271528812)); -#30664 = CARTESIAN_POINT('',(-0.148952355843,0.78,-0.444271528812)); -#30665 = CARTESIAN_POINT('',(-0.14373640916,0.782,-0.444153993928)); -#30666 = CARTESIAN_POINT('',(-0.14373640916,0.78,-0.444153993928)); -#30667 = CARTESIAN_POINT('',(-0.136108549957,0.782,-0.443269018362)); -#30668 = CARTESIAN_POINT('',(-0.136108549957,0.78,-0.443269018362)); -#30669 = CARTESIAN_POINT('',(-0.12887280298,0.782,-0.441785744181)); -#30670 = CARTESIAN_POINT('',(-0.12887280298,0.78,-0.441785744181)); -#30671 = CARTESIAN_POINT('',(-0.122033428257,0.782,-0.439681351531)); -#30672 = CARTESIAN_POINT('',(-0.122033428257,0.78,-0.439681351531)); -#30673 = CARTESIAN_POINT('',(-0.115579643283,0.782,-0.436990758818)); -#30674 = CARTESIAN_POINT('',(-0.115579643283,0.78,-0.436990758818)); -#30675 = CARTESIAN_POINT('',(-0.109553855828,0.782,-0.433683667182)); -#30676 = CARTESIAN_POINT('',(-0.109553855828,0.78,-0.433683667182)); -#30677 = CARTESIAN_POINT('',(-0.103894034067,0.782,-0.429814621087)); -#30678 = CARTESIAN_POINT('',(-0.103894034067,0.78,-0.429814621087)); -#30679 = CARTESIAN_POINT('',(-9.874484109579E-002,0.782,-0.425337480783) +#33053 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#33054 = CARTESIAN_POINT('',(-0.151630101652,0.78,-0.44433186849)); +#33055 = CARTESIAN_POINT('',(-0.148952355843,0.782,-0.444271528812)); +#33056 = CARTESIAN_POINT('',(-0.148952355843,0.78,-0.444271528812)); +#33057 = CARTESIAN_POINT('',(-0.14373640916,0.782,-0.444153993928)); +#33058 = CARTESIAN_POINT('',(-0.14373640916,0.78,-0.444153993928)); +#33059 = CARTESIAN_POINT('',(-0.136108549957,0.782,-0.443269018362)); +#33060 = CARTESIAN_POINT('',(-0.136108549957,0.78,-0.443269018362)); +#33061 = CARTESIAN_POINT('',(-0.12887280298,0.782,-0.441785744181)); +#33062 = CARTESIAN_POINT('',(-0.12887280298,0.78,-0.441785744181)); +#33063 = CARTESIAN_POINT('',(-0.122033428257,0.782,-0.439681351531)); +#33064 = CARTESIAN_POINT('',(-0.122033428257,0.78,-0.439681351531)); +#33065 = CARTESIAN_POINT('',(-0.115579643283,0.782,-0.436990758818)); +#33066 = CARTESIAN_POINT('',(-0.115579643283,0.78,-0.436990758818)); +#33067 = CARTESIAN_POINT('',(-0.109553855828,0.782,-0.433683667182)); +#33068 = CARTESIAN_POINT('',(-0.109553855828,0.78,-0.433683667182)); +#33069 = CARTESIAN_POINT('',(-0.103894034067,0.782,-0.429814621087)); +#33070 = CARTESIAN_POINT('',(-0.103894034067,0.78,-0.429814621087)); +#33071 = CARTESIAN_POINT('',(-9.874484109579E-002,0.782,-0.425337480783) ); -#30680 = CARTESIAN_POINT('',(-9.874484109579E-002,0.78,-0.425337480783) +#33072 = CARTESIAN_POINT('',(-9.874484109579E-002,0.78,-0.425337480783) ); -#30681 = CARTESIAN_POINT('',(-9.40596892566E-002,0.782,-0.420476762361) +#33073 = CARTESIAN_POINT('',(-9.40596892566E-002,0.782,-0.420476762361) ); -#30682 = CARTESIAN_POINT('',(-9.40596892566E-002,0.78,-0.420476762361)); -#30683 = CARTESIAN_POINT('',(-9.000044772922E-002,0.782,-0.415269287689) +#33074 = CARTESIAN_POINT('',(-9.40596892566E-002,0.78,-0.420476762361)); +#33075 = CARTESIAN_POINT('',(-9.000044772922E-002,0.782,-0.415269287689) ); -#30684 = CARTESIAN_POINT('',(-9.000044772922E-002,0.78,-0.415269287689) +#33076 = CARTESIAN_POINT('',(-9.000044772922E-002,0.78,-0.415269287689) ); -#30685 = CARTESIAN_POINT('',(-8.651896546958E-002,0.782,-0.409836569666) +#33077 = CARTESIAN_POINT('',(-8.651896546958E-002,0.782,-0.409836569666) ); -#30686 = CARTESIAN_POINT('',(-8.651896546958E-002,0.78,-0.409836569666) +#33078 = CARTESIAN_POINT('',(-8.651896546958E-002,0.78,-0.409836569666) ); -#30687 = CARTESIAN_POINT('',(-8.364204346514E-002,0.782,-0.404145603279) +#33079 = CARTESIAN_POINT('',(-8.364204346514E-002,0.782,-0.404145603279) ); -#30688 = CARTESIAN_POINT('',(-8.364204346514E-002,0.78,-0.404145603279) +#33080 = CARTESIAN_POINT('',(-8.364204346514E-002,0.78,-0.404145603279) ); -#30689 = CARTESIAN_POINT('',(-8.151368568852E-002,0.782,-0.398131583659) +#33081 = CARTESIAN_POINT('',(-8.151368568852E-002,0.782,-0.398131583659) ); -#30690 = CARTESIAN_POINT('',(-8.151368568852E-002,0.78,-0.398131583659) +#33082 = CARTESIAN_POINT('',(-8.151368568852E-002,0.78,-0.398131583659) ); -#30691 = CARTESIAN_POINT('',(-7.989139930784E-002,0.782,-0.391907817721) +#33083 = CARTESIAN_POINT('',(-7.989139930784E-002,0.782,-0.391907817721) ); -#30692 = CARTESIAN_POINT('',(-7.989139930784E-002,0.78,-0.391907817721) +#33084 = CARTESIAN_POINT('',(-7.989139930784E-002,0.78,-0.391907817721) ); -#30693 = CARTESIAN_POINT('',(-7.895039800517E-002,0.782,-0.385400354993) +#33085 = CARTESIAN_POINT('',(-7.895039800517E-002,0.782,-0.385400354993) ); -#30694 = CARTESIAN_POINT('',(-7.895039800517E-002,0.78,-0.385400354993) +#33086 = CARTESIAN_POINT('',(-7.895039800517E-002,0.78,-0.385400354993) ); -#30695 = CARTESIAN_POINT('',(-7.883668274196E-002,0.782,-0.380984364144) +#33087 = CARTESIAN_POINT('',(-7.883668274196E-002,0.782,-0.380984364144) ); -#30696 = CARTESIAN_POINT('',(-7.883668274196E-002,0.78,-0.380984364144) +#33088 = CARTESIAN_POINT('',(-7.883668274196E-002,0.78,-0.380984364144) ); -#30697 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) +#33089 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) ); -#30698 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) +#33090 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) ); -#30699 = DEFINITIONAL_REPRESENTATION('',(#30700),#30704); -#30700 = LINE('',#30701,#30702); -#30701 = CARTESIAN_POINT('',(0.E+000,1.)); -#30702 = VECTOR('',#30703,1.); -#30703 = DIRECTION('',(1.,0.E+000)); -#30704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33091 = DEFINITIONAL_REPRESENTATION('',(#33092),#33096); +#33092 = LINE('',#33093,#33094); +#33093 = CARTESIAN_POINT('',(0.E+000,1.)); +#33094 = VECTOR('',#33095,1.); +#33095 = DIRECTION('',(1.,0.E+000)); +#33096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#30705 = ORIENTED_EDGE('',*,*,#30706,.T.); -#30706 = EDGE_CURVE('',#30613,#30707,#30709,.T.); -#30707 = VERTEX_POINT('',#30708); -#30708 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); -#30709 = SURFACE_CURVE('',#30710,(#30722,#30737),.PCURVE_S1.); -#30710 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30711,#30712,#30713,#30714, - #30715,#30716,#30717,#30718,#30719,#30720,#30721),.UNSPECIFIED.,.F., +#33097 = ORIENTED_EDGE('',*,*,#33098,.T.); +#33098 = EDGE_CURVE('',#33005,#33099,#33101,.T.); +#33099 = VERTEX_POINT('',#33100); +#33100 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); +#33101 = SURFACE_CURVE('',#33102,(#33114,#33129),.PCURVE_S1.); +#33102 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33103,#33104,#33105,#33106, + #33107,#33108,#33109,#33110,#33111,#33112,#33113),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.124835092167,0.244778133283, 0.360988977841,0.477964172247,0.596922117558,0.721590756697, 0.855097865757,1.),.UNSPECIFIED.); -#30711 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) +#33103 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) ); -#30712 = CARTESIAN_POINT('',(-7.887285724434E-002,0.78,-0.375911436438) +#33104 = CARTESIAN_POINT('',(-7.887285724434E-002,0.78,-0.375911436438) ); -#30713 = CARTESIAN_POINT('',(-7.905737533771E-002,0.78,-0.37037537768)); -#30714 = CARTESIAN_POINT('',(-8.093769722843E-002,0.78,-0.362395102964) +#33105 = CARTESIAN_POINT('',(-7.905737533771E-002,0.78,-0.37037537768)); +#33106 = CARTESIAN_POINT('',(-8.093769722843E-002,0.78,-0.362395102964) ); -#30715 = CARTESIAN_POINT('',(-8.386833973693E-002,0.78,-0.354945116544) +#33107 = CARTESIAN_POINT('',(-8.386833973693E-002,0.78,-0.354945116544) ); -#30716 = CARTESIAN_POINT('',(-8.810400249721E-002,0.78,-0.348167402211) +#33108 = CARTESIAN_POINT('',(-8.810400249721E-002,0.78,-0.348167402211) ); -#30717 = CARTESIAN_POINT('',(-9.346831185091E-002,0.78,-0.341991961362) +#33109 = CARTESIAN_POINT('',(-9.346831185091E-002,0.78,-0.341991961362) ); -#30718 = CARTESIAN_POINT('',(-0.100124991939,0.78,-0.336623582911)); -#30719 = CARTESIAN_POINT('',(-0.107972949029,0.78,-0.331941156302)); -#30720 = CARTESIAN_POINT('',(-0.113811846918,0.78,-0.329590138812)); -#30721 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); -#30722 = PCURVE('',#28866,#30723); -#30723 = DEFINITIONAL_REPRESENTATION('',(#30724),#30736); -#30724 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30725,#30726,#30727,#30728, - #30729,#30730,#30731,#30732,#30733,#30734,#30735),.UNSPECIFIED.,.F., +#33110 = CARTESIAN_POINT('',(-0.100124991939,0.78,-0.336623582911)); +#33111 = CARTESIAN_POINT('',(-0.107972949029,0.78,-0.331941156302)); +#33112 = CARTESIAN_POINT('',(-0.113811846918,0.78,-0.329590138812)); +#33113 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); +#33114 = PCURVE('',#31258,#33115); +#33115 = DEFINITIONAL_REPRESENTATION('',(#33116),#33128); +#33116 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33117,#33118,#33119,#33120, + #33121,#33122,#33123,#33124,#33125,#33126,#33127),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.124835092167,0.244778133283, 0.360988977841,0.477964172247,0.596922117558,0.721590756697, 0.855097865757,1.),.UNSPECIFIED.); -#30725 = CARTESIAN_POINT('',(-1.003734786694,0.92122124566)); -#30726 = CARTESIAN_POINT('',(-1.000911436438,0.921127142756)); -#30727 = CARTESIAN_POINT('',(-0.99537537768,0.920942624662)); -#30728 = CARTESIAN_POINT('',(-0.987395102964,0.919062302772)); -#30729 = CARTESIAN_POINT('',(-0.979945116544,0.916131660263)); -#30730 = CARTESIAN_POINT('',(-0.973167402211,0.911895997503)); -#30731 = CARTESIAN_POINT('',(-0.966991961362,0.906531688149)); -#30732 = CARTESIAN_POINT('',(-0.961623582911,0.899875008061)); -#30733 = CARTESIAN_POINT('',(-0.956941156302,0.892027050971)); -#30734 = CARTESIAN_POINT('',(-0.954590138812,0.886188153082)); -#30735 = CARTESIAN_POINT('',(-0.953366517613,0.883149213872)); -#30736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30737 = PCURVE('',#30738,#30761); -#30738 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30739,#30740) - ,(#30741,#30742) - ,(#30743,#30744) - ,(#30745,#30746) - ,(#30747,#30748) - ,(#30749,#30750) - ,(#30751,#30752) - ,(#30753,#30754) - ,(#30755,#30756) - ,(#30757,#30758) - ,(#30759,#30760 +#33117 = CARTESIAN_POINT('',(-1.003734786694,0.92122124566)); +#33118 = CARTESIAN_POINT('',(-1.000911436438,0.921127142756)); +#33119 = CARTESIAN_POINT('',(-0.99537537768,0.920942624662)); +#33120 = CARTESIAN_POINT('',(-0.987395102964,0.919062302772)); +#33121 = CARTESIAN_POINT('',(-0.979945116544,0.916131660263)); +#33122 = CARTESIAN_POINT('',(-0.973167402211,0.911895997503)); +#33123 = CARTESIAN_POINT('',(-0.966991961362,0.906531688149)); +#33124 = CARTESIAN_POINT('',(-0.961623582911,0.899875008061)); +#33125 = CARTESIAN_POINT('',(-0.956941156302,0.892027050971)); +#33126 = CARTESIAN_POINT('',(-0.954590138812,0.886188153082)); +#33127 = CARTESIAN_POINT('',(-0.953366517613,0.883149213872)); +#33128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33129 = PCURVE('',#33130,#33153); +#33130 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#33131,#33132) + ,(#33133,#33134) + ,(#33135,#33136) + ,(#33137,#33138) + ,(#33139,#33140) + ,(#33141,#33142) + ,(#33143,#33144) + ,(#33145,#33146) + ,(#33147,#33148) + ,(#33149,#33150) + ,(#33151,#33152 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.124835092167,0.244778133283,0.360988977841,0.477964172247, 0.596922117558,0.721590756697,0.855097865757,1.),(0.E+000,1.), .UNSPECIFIED.); -#30739 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) +#33131 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) ); -#30740 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) +#33132 = CARTESIAN_POINT('',(-7.877875434028E-002,0.78,-0.378734786694) ); -#30741 = CARTESIAN_POINT('',(-7.887285724434E-002,0.782,-0.375911436438) +#33133 = CARTESIAN_POINT('',(-7.887285724434E-002,0.782,-0.375911436438) ); -#30742 = CARTESIAN_POINT('',(-7.887285724434E-002,0.78,-0.375911436438) +#33134 = CARTESIAN_POINT('',(-7.887285724434E-002,0.78,-0.375911436438) ); -#30743 = CARTESIAN_POINT('',(-7.905737533771E-002,0.782,-0.37037537768) +#33135 = CARTESIAN_POINT('',(-7.905737533771E-002,0.782,-0.37037537768) ); -#30744 = CARTESIAN_POINT('',(-7.905737533771E-002,0.78,-0.37037537768)); -#30745 = CARTESIAN_POINT('',(-8.093769722843E-002,0.782,-0.362395102964) +#33136 = CARTESIAN_POINT('',(-7.905737533771E-002,0.78,-0.37037537768)); +#33137 = CARTESIAN_POINT('',(-8.093769722843E-002,0.782,-0.362395102964) ); -#30746 = CARTESIAN_POINT('',(-8.093769722843E-002,0.78,-0.362395102964) +#33138 = CARTESIAN_POINT('',(-8.093769722843E-002,0.78,-0.362395102964) ); -#30747 = CARTESIAN_POINT('',(-8.386833973693E-002,0.782,-0.354945116544) +#33139 = CARTESIAN_POINT('',(-8.386833973693E-002,0.782,-0.354945116544) ); -#30748 = CARTESIAN_POINT('',(-8.386833973693E-002,0.78,-0.354945116544) +#33140 = CARTESIAN_POINT('',(-8.386833973693E-002,0.78,-0.354945116544) ); -#30749 = CARTESIAN_POINT('',(-8.810400249721E-002,0.782,-0.348167402211) +#33141 = CARTESIAN_POINT('',(-8.810400249721E-002,0.782,-0.348167402211) ); -#30750 = CARTESIAN_POINT('',(-8.810400249721E-002,0.78,-0.348167402211) +#33142 = CARTESIAN_POINT('',(-8.810400249721E-002,0.78,-0.348167402211) ); -#30751 = CARTESIAN_POINT('',(-9.346831185091E-002,0.782,-0.341991961362) +#33143 = CARTESIAN_POINT('',(-9.346831185091E-002,0.782,-0.341991961362) ); -#30752 = CARTESIAN_POINT('',(-9.346831185091E-002,0.78,-0.341991961362) +#33144 = CARTESIAN_POINT('',(-9.346831185091E-002,0.78,-0.341991961362) ); -#30753 = CARTESIAN_POINT('',(-0.100124991939,0.782,-0.336623582911)); -#30754 = CARTESIAN_POINT('',(-0.100124991939,0.78,-0.336623582911)); -#30755 = CARTESIAN_POINT('',(-0.107972949029,0.782,-0.331941156302)); -#30756 = CARTESIAN_POINT('',(-0.107972949029,0.78,-0.331941156302)); -#30757 = CARTESIAN_POINT('',(-0.113811846918,0.782,-0.329590138812)); -#30758 = CARTESIAN_POINT('',(-0.113811846918,0.78,-0.329590138812)); -#30759 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#30760 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); -#30761 = DEFINITIONAL_REPRESENTATION('',(#30762),#30766); -#30762 = LINE('',#30763,#30764); -#30763 = CARTESIAN_POINT('',(0.E+000,1.)); -#30764 = VECTOR('',#30765,1.); -#30765 = DIRECTION('',(1.,0.E+000)); -#30766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33145 = CARTESIAN_POINT('',(-0.100124991939,0.782,-0.336623582911)); +#33146 = CARTESIAN_POINT('',(-0.100124991939,0.78,-0.336623582911)); +#33147 = CARTESIAN_POINT('',(-0.107972949029,0.782,-0.331941156302)); +#33148 = CARTESIAN_POINT('',(-0.107972949029,0.78,-0.331941156302)); +#33149 = CARTESIAN_POINT('',(-0.113811846918,0.782,-0.329590138812)); +#33150 = CARTESIAN_POINT('',(-0.113811846918,0.78,-0.329590138812)); +#33151 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#33152 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); +#33153 = DEFINITIONAL_REPRESENTATION('',(#33154),#33158); +#33154 = LINE('',#33155,#33156); +#33155 = CARTESIAN_POINT('',(0.E+000,1.)); +#33156 = VECTOR('',#33157,1.); +#33157 = DIRECTION('',(1.,0.E+000)); +#33158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#30767 = ORIENTED_EDGE('',*,*,#30768,.T.); -#30768 = EDGE_CURVE('',#30707,#30769,#30771,.T.); -#30769 = VERTEX_POINT('',#30770); -#30770 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) +#33159 = ORIENTED_EDGE('',*,*,#33160,.T.); +#33160 = EDGE_CURVE('',#33099,#33161,#33163,.T.); +#33161 = VERTEX_POINT('',#33162); +#33162 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) ); -#30771 = SURFACE_CURVE('',#30772,(#30792,#30815),.PCURVE_S1.); -#30772 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30773,#30774,#30775,#30776, - #30777,#30778,#30779,#30780,#30781,#30782,#30783,#30784,#30785, - #30786,#30787,#30788,#30789,#30790,#30791),.UNSPECIFIED.,.F.,.F.,(4, +#33163 = SURFACE_CURVE('',#33164,(#33184,#33207),.PCURVE_S1.); +#33164 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33165,#33166,#33167,#33168, + #33169,#33170,#33171,#33172,#33173,#33174,#33175,#33176,#33177, + #33178,#33179,#33180,#33181,#33182,#33183),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.901300291099E-002, 0.135235544056,0.199611185116,0.262418519503,0.32372349721, 0.383765365604,0.443773035096,0.503794956498,0.563822577717, 0.623484312883,0.683469172274,0.743590762456,0.805727219974, 0.868616210735,0.933278202847,1.),.UNSPECIFIED.); -#30773 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); -#30774 = CARTESIAN_POINT('',(-0.114933412774,0.78,-0.327715660212)); -#30775 = CARTESIAN_POINT('',(-0.111176192863,0.78,-0.326440262085)); -#30776 = CARTESIAN_POINT('',(-0.105864604895,0.78,-0.32396049507)); -#30777 = CARTESIAN_POINT('',(-0.100863904474,0.78,-0.321286717616)); -#30778 = CARTESIAN_POINT('',(-9.614589209932E-002,0.78,-0.318392351899) +#33165 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); +#33166 = CARTESIAN_POINT('',(-0.114933412774,0.78,-0.327715660212)); +#33167 = CARTESIAN_POINT('',(-0.111176192863,0.78,-0.326440262085)); +#33168 = CARTESIAN_POINT('',(-0.105864604895,0.78,-0.32396049507)); +#33169 = CARTESIAN_POINT('',(-0.100863904474,0.78,-0.321286717616)); +#33170 = CARTESIAN_POINT('',(-9.614589209932E-002,0.78,-0.318392351899) ); -#30779 = CARTESIAN_POINT('',(-9.188472123138E-002,0.78,-0.315062150838) +#33171 = CARTESIAN_POINT('',(-9.188472123138E-002,0.78,-0.315062150838) ); -#30780 = CARTESIAN_POINT('',(-8.793822669242E-002,0.78,-0.31149301542)); -#30781 = CARTESIAN_POINT('',(-8.432300128947E-002,0.78,-0.30763464951)); -#30782 = CARTESIAN_POINT('',(-8.10884251632E-002,0.78,-0.303454237299)); -#30783 = CARTESIAN_POINT('',(-7.820060751267E-002,0.78,-0.299039518498) +#33172 = CARTESIAN_POINT('',(-8.793822669242E-002,0.78,-0.31149301542)); +#33173 = CARTESIAN_POINT('',(-8.432300128947E-002,0.78,-0.30763464951)); +#33174 = CARTESIAN_POINT('',(-8.10884251632E-002,0.78,-0.303454237299)); +#33175 = CARTESIAN_POINT('',(-7.820060751267E-002,0.78,-0.299039518498) ); -#30784 = CARTESIAN_POINT('',(-7.572840637402E-002,0.78,-0.294379729823) +#33176 = CARTESIAN_POINT('',(-7.572840637402E-002,0.78,-0.294379729823) ); -#30785 = CARTESIAN_POINT('',(-7.362881342303E-002,0.78,-0.28954119727)); -#30786 = CARTESIAN_POINT('',(-7.183442898442E-002,0.78,-0.284501483646) +#33177 = CARTESIAN_POINT('',(-7.362881342303E-002,0.78,-0.28954119727)); +#33178 = CARTESIAN_POINT('',(-7.183442898442E-002,0.78,-0.284501483646) ); -#30787 = CARTESIAN_POINT('',(-7.05237729917E-002,0.78,-0.27922508981)); -#30788 = CARTESIAN_POINT('',(-6.960672455506E-002,0.78,-0.273736263582) +#33179 = CARTESIAN_POINT('',(-7.05237729917E-002,0.78,-0.27922508981)); +#33180 = CARTESIAN_POINT('',(-6.960672455506E-002,0.78,-0.273736263582) ); -#30789 = CARTESIAN_POINT('',(-6.902488317678E-002,0.78,-0.268063932998) +#33181 = CARTESIAN_POINT('',(-6.902488317678E-002,0.78,-0.268063932998) ); -#30790 = CARTESIAN_POINT('',(-6.894246215307E-002,0.78,-0.264211409926) +#33182 = CARTESIAN_POINT('',(-6.894246215307E-002,0.78,-0.264211409926) ); -#30791 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) +#33183 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) ); -#30792 = PCURVE('',#28866,#30793); -#30793 = DEFINITIONAL_REPRESENTATION('',(#30794),#30814); -#30794 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30795,#30796,#30797,#30798, - #30799,#30800,#30801,#30802,#30803,#30804,#30805,#30806,#30807, - #30808,#30809,#30810,#30811,#30812,#30813),.UNSPECIFIED.,.F.,.F.,(4, +#33184 = PCURVE('',#31258,#33185); +#33185 = DEFINITIONAL_REPRESENTATION('',(#33186),#33206); +#33186 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33187,#33188,#33189,#33190, + #33191,#33192,#33193,#33194,#33195,#33196,#33197,#33198,#33199, + #33200,#33201,#33202,#33203,#33204,#33205),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.901300291099E-002, 0.135235544056,0.199611185116,0.262418519503,0.32372349721, 0.383765365604,0.443773035096,0.503794956498,0.563822577717, 0.623484312883,0.683469172274,0.743590762456,0.805727219974, 0.868616210735,0.933278202847,1.),.UNSPECIFIED.); -#30795 = CARTESIAN_POINT('',(-0.953366517613,0.883149213872)); -#30796 = CARTESIAN_POINT('',(-0.952715660212,0.885066587226)); -#30797 = CARTESIAN_POINT('',(-0.951440262085,0.888823807137)); -#30798 = CARTESIAN_POINT('',(-0.94896049507,0.894135395105)); -#30799 = CARTESIAN_POINT('',(-0.946286717616,0.899136095526)); -#30800 = CARTESIAN_POINT('',(-0.943392351899,0.903854107901)); -#30801 = CARTESIAN_POINT('',(-0.940062150838,0.908115278769)); -#30802 = CARTESIAN_POINT('',(-0.93649301542,0.912061773308)); -#30803 = CARTESIAN_POINT('',(-0.93263464951,0.915676998711)); -#30804 = CARTESIAN_POINT('',(-0.928454237299,0.918911574837)); -#30805 = CARTESIAN_POINT('',(-0.924039518498,0.921799392487)); -#30806 = CARTESIAN_POINT('',(-0.919379729823,0.924271593626)); -#30807 = CARTESIAN_POINT('',(-0.91454119727,0.926371186577)); -#30808 = CARTESIAN_POINT('',(-0.909501483646,0.928165571016)); -#30809 = CARTESIAN_POINT('',(-0.90422508981,0.929476227008)); -#30810 = CARTESIAN_POINT('',(-0.898736263582,0.930393275445)); -#30811 = CARTESIAN_POINT('',(-0.893063932998,0.930975116823)); -#30812 = CARTESIAN_POINT('',(-0.889211409926,0.931057537847)); -#30813 = CARTESIAN_POINT('',(-0.887254948901,0.931099394448)); -#30814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30815 = PCURVE('',#30816,#30855); -#30816 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30817,#30818) - ,(#30819,#30820) - ,(#30821,#30822) - ,(#30823,#30824) - ,(#30825,#30826) - ,(#30827,#30828) - ,(#30829,#30830) - ,(#30831,#30832) - ,(#30833,#30834) - ,(#30835,#30836) - ,(#30837,#30838) - ,(#30839,#30840) - ,(#30841,#30842) - ,(#30843,#30844) - ,(#30845,#30846) - ,(#30847,#30848) - ,(#30849,#30850) - ,(#30851,#30852) - ,(#30853,#30854 +#33187 = CARTESIAN_POINT('',(-0.953366517613,0.883149213872)); +#33188 = CARTESIAN_POINT('',(-0.952715660212,0.885066587226)); +#33189 = CARTESIAN_POINT('',(-0.951440262085,0.888823807137)); +#33190 = CARTESIAN_POINT('',(-0.94896049507,0.894135395105)); +#33191 = CARTESIAN_POINT('',(-0.946286717616,0.899136095526)); +#33192 = CARTESIAN_POINT('',(-0.943392351899,0.903854107901)); +#33193 = CARTESIAN_POINT('',(-0.940062150838,0.908115278769)); +#33194 = CARTESIAN_POINT('',(-0.93649301542,0.912061773308)); +#33195 = CARTESIAN_POINT('',(-0.93263464951,0.915676998711)); +#33196 = CARTESIAN_POINT('',(-0.928454237299,0.918911574837)); +#33197 = CARTESIAN_POINT('',(-0.924039518498,0.921799392487)); +#33198 = CARTESIAN_POINT('',(-0.919379729823,0.924271593626)); +#33199 = CARTESIAN_POINT('',(-0.91454119727,0.926371186577)); +#33200 = CARTESIAN_POINT('',(-0.909501483646,0.928165571016)); +#33201 = CARTESIAN_POINT('',(-0.90422508981,0.929476227008)); +#33202 = CARTESIAN_POINT('',(-0.898736263582,0.930393275445)); +#33203 = CARTESIAN_POINT('',(-0.893063932998,0.930975116823)); +#33204 = CARTESIAN_POINT('',(-0.889211409926,0.931057537847)); +#33205 = CARTESIAN_POINT('',(-0.887254948901,0.931099394448)); +#33206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33207 = PCURVE('',#33208,#33247); +#33208 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#33209,#33210) + ,(#33211,#33212) + ,(#33213,#33214) + ,(#33215,#33216) + ,(#33217,#33218) + ,(#33219,#33220) + ,(#33221,#33222) + ,(#33223,#33224) + ,(#33225,#33226) + ,(#33227,#33228) + ,(#33229,#33230) + ,(#33231,#33232) + ,(#33233,#33234) + ,(#33235,#33236) + ,(#33237,#33238) + ,(#33239,#33240) + ,(#33241,#33242) + ,(#33243,#33244) + ,(#33245,#33246 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.901300291099E-002,0.135235544056,0.199611185116, 0.262418519503,0.32372349721,0.383765365604,0.443773035096, 0.503794956498,0.563822577717,0.623484312883,0.683469172274, 0.743590762456,0.805727219974,0.868616210735,0.933278202847,1.),( 0.E+000,1.),.UNSPECIFIED.); -#30817 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#30818 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); -#30819 = CARTESIAN_POINT('',(-0.114933412774,0.782,-0.327715660212)); -#30820 = CARTESIAN_POINT('',(-0.114933412774,0.78,-0.327715660212)); -#30821 = CARTESIAN_POINT('',(-0.111176192863,0.782,-0.326440262085)); -#30822 = CARTESIAN_POINT('',(-0.111176192863,0.78,-0.326440262085)); -#30823 = CARTESIAN_POINT('',(-0.105864604895,0.782,-0.32396049507)); -#30824 = CARTESIAN_POINT('',(-0.105864604895,0.78,-0.32396049507)); -#30825 = CARTESIAN_POINT('',(-0.100863904474,0.782,-0.321286717616)); -#30826 = CARTESIAN_POINT('',(-0.100863904474,0.78,-0.321286717616)); -#30827 = CARTESIAN_POINT('',(-9.614589209932E-002,0.782,-0.318392351899) +#33209 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#33210 = CARTESIAN_POINT('',(-0.116850786128,0.78,-0.328366517613)); +#33211 = CARTESIAN_POINT('',(-0.114933412774,0.782,-0.327715660212)); +#33212 = CARTESIAN_POINT('',(-0.114933412774,0.78,-0.327715660212)); +#33213 = CARTESIAN_POINT('',(-0.111176192863,0.782,-0.326440262085)); +#33214 = CARTESIAN_POINT('',(-0.111176192863,0.78,-0.326440262085)); +#33215 = CARTESIAN_POINT('',(-0.105864604895,0.782,-0.32396049507)); +#33216 = CARTESIAN_POINT('',(-0.105864604895,0.78,-0.32396049507)); +#33217 = CARTESIAN_POINT('',(-0.100863904474,0.782,-0.321286717616)); +#33218 = CARTESIAN_POINT('',(-0.100863904474,0.78,-0.321286717616)); +#33219 = CARTESIAN_POINT('',(-9.614589209932E-002,0.782,-0.318392351899) ); -#30828 = CARTESIAN_POINT('',(-9.614589209932E-002,0.78,-0.318392351899) +#33220 = CARTESIAN_POINT('',(-9.614589209932E-002,0.78,-0.318392351899) ); -#30829 = CARTESIAN_POINT('',(-9.188472123138E-002,0.782,-0.315062150838) +#33221 = CARTESIAN_POINT('',(-9.188472123138E-002,0.782,-0.315062150838) ); -#30830 = CARTESIAN_POINT('',(-9.188472123138E-002,0.78,-0.315062150838) +#33222 = CARTESIAN_POINT('',(-9.188472123138E-002,0.78,-0.315062150838) ); -#30831 = CARTESIAN_POINT('',(-8.793822669242E-002,0.782,-0.31149301542) +#33223 = CARTESIAN_POINT('',(-8.793822669242E-002,0.782,-0.31149301542) ); -#30832 = CARTESIAN_POINT('',(-8.793822669242E-002,0.78,-0.31149301542)); -#30833 = CARTESIAN_POINT('',(-8.432300128947E-002,0.782,-0.30763464951) +#33224 = CARTESIAN_POINT('',(-8.793822669242E-002,0.78,-0.31149301542)); +#33225 = CARTESIAN_POINT('',(-8.432300128947E-002,0.782,-0.30763464951) ); -#30834 = CARTESIAN_POINT('',(-8.432300128947E-002,0.78,-0.30763464951)); -#30835 = CARTESIAN_POINT('',(-8.10884251632E-002,0.782,-0.303454237299) +#33226 = CARTESIAN_POINT('',(-8.432300128947E-002,0.78,-0.30763464951)); +#33227 = CARTESIAN_POINT('',(-8.10884251632E-002,0.782,-0.303454237299) ); -#30836 = CARTESIAN_POINT('',(-8.10884251632E-002,0.78,-0.303454237299)); -#30837 = CARTESIAN_POINT('',(-7.820060751267E-002,0.782,-0.299039518498) +#33228 = CARTESIAN_POINT('',(-8.10884251632E-002,0.78,-0.303454237299)); +#33229 = CARTESIAN_POINT('',(-7.820060751267E-002,0.782,-0.299039518498) ); -#30838 = CARTESIAN_POINT('',(-7.820060751267E-002,0.78,-0.299039518498) +#33230 = CARTESIAN_POINT('',(-7.820060751267E-002,0.78,-0.299039518498) ); -#30839 = CARTESIAN_POINT('',(-7.572840637402E-002,0.782,-0.294379729823) +#33231 = CARTESIAN_POINT('',(-7.572840637402E-002,0.782,-0.294379729823) ); -#30840 = CARTESIAN_POINT('',(-7.572840637402E-002,0.78,-0.294379729823) +#33232 = CARTESIAN_POINT('',(-7.572840637402E-002,0.78,-0.294379729823) ); -#30841 = CARTESIAN_POINT('',(-7.362881342303E-002,0.782,-0.28954119727) +#33233 = CARTESIAN_POINT('',(-7.362881342303E-002,0.782,-0.28954119727) ); -#30842 = CARTESIAN_POINT('',(-7.362881342303E-002,0.78,-0.28954119727)); -#30843 = CARTESIAN_POINT('',(-7.183442898442E-002,0.782,-0.284501483646) +#33234 = CARTESIAN_POINT('',(-7.362881342303E-002,0.78,-0.28954119727)); +#33235 = CARTESIAN_POINT('',(-7.183442898442E-002,0.782,-0.284501483646) ); -#30844 = CARTESIAN_POINT('',(-7.183442898442E-002,0.78,-0.284501483646) +#33236 = CARTESIAN_POINT('',(-7.183442898442E-002,0.78,-0.284501483646) ); -#30845 = CARTESIAN_POINT('',(-7.05237729917E-002,0.782,-0.27922508981)); -#30846 = CARTESIAN_POINT('',(-7.05237729917E-002,0.78,-0.27922508981)); -#30847 = CARTESIAN_POINT('',(-6.960672455506E-002,0.782,-0.273736263582) +#33237 = CARTESIAN_POINT('',(-7.05237729917E-002,0.782,-0.27922508981)); +#33238 = CARTESIAN_POINT('',(-7.05237729917E-002,0.78,-0.27922508981)); +#33239 = CARTESIAN_POINT('',(-6.960672455506E-002,0.782,-0.273736263582) ); -#30848 = CARTESIAN_POINT('',(-6.960672455506E-002,0.78,-0.273736263582) +#33240 = CARTESIAN_POINT('',(-6.960672455506E-002,0.78,-0.273736263582) ); -#30849 = CARTESIAN_POINT('',(-6.902488317678E-002,0.782,-0.268063932998) +#33241 = CARTESIAN_POINT('',(-6.902488317678E-002,0.782,-0.268063932998) ); -#30850 = CARTESIAN_POINT('',(-6.902488317678E-002,0.78,-0.268063932998) +#33242 = CARTESIAN_POINT('',(-6.902488317678E-002,0.78,-0.268063932998) ); -#30851 = CARTESIAN_POINT('',(-6.894246215307E-002,0.782,-0.264211409926) +#33243 = CARTESIAN_POINT('',(-6.894246215307E-002,0.782,-0.264211409926) ); -#30852 = CARTESIAN_POINT('',(-6.894246215307E-002,0.78,-0.264211409926) +#33244 = CARTESIAN_POINT('',(-6.894246215307E-002,0.78,-0.264211409926) ); -#30853 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) +#33245 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) ); -#30854 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) +#33246 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) ); -#30855 = DEFINITIONAL_REPRESENTATION('',(#30856),#30860); -#30856 = LINE('',#30857,#30858); -#30857 = CARTESIAN_POINT('',(0.E+000,1.)); -#30858 = VECTOR('',#30859,1.); -#30859 = DIRECTION('',(1.,0.E+000)); -#30860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33247 = DEFINITIONAL_REPRESENTATION('',(#33248),#33252); +#33248 = LINE('',#33249,#33250); +#33249 = CARTESIAN_POINT('',(0.E+000,1.)); +#33250 = VECTOR('',#33251,1.); +#33251 = DIRECTION('',(1.,0.E+000)); +#33252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#30861 = ORIENTED_EDGE('',*,*,#30862,.T.); -#30862 = EDGE_CURVE('',#30769,#30863,#30865,.T.); -#30863 = VERTEX_POINT('',#30864); -#30864 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); -#30865 = SURFACE_CURVE('',#30866,(#30886,#30909),.PCURVE_S1.); -#30866 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30867,#30868,#30869,#30870, - #30871,#30872,#30873,#30874,#30875,#30876,#30877,#30878,#30879, - #30880,#30881,#30882,#30883,#30884,#30885),.UNSPECIFIED.,.F.,.F.,(4, +#33253 = ORIENTED_EDGE('',*,*,#33254,.T.); +#33254 = EDGE_CURVE('',#33161,#33255,#33257,.T.); +#33255 = VERTEX_POINT('',#33256); +#33256 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); +#33257 = SURFACE_CURVE('',#33258,(#33278,#33301),.PCURVE_S1.); +#33258 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33259,#33260,#33261,#33262, + #33263,#33264,#33265,#33266,#33267,#33268,#33269,#33270,#33271, + #33272,#33273,#33274,#33275,#33276,#33277),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.359990034717E-002, 0.125296650794,0.185568720195,0.244698211001,0.30371680619, 0.362919650948,0.423300313869,0.485177309545,0.547083413224, 0.608524799634,0.669964853245,0.732299377978,0.79565029349, 0.861055470947,0.929122115173,1.),.UNSPECIFIED.); -#30867 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) +#33259 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) ); -#30868 = CARTESIAN_POINT('',(-6.896604125846E-002,0.78,-0.259558415664) +#33260 = CARTESIAN_POINT('',(-6.896604125846E-002,0.78,-0.259558415664) ); -#30869 = CARTESIAN_POINT('',(-6.909495458679E-002,0.78,-0.254246039676) +#33261 = CARTESIAN_POINT('',(-6.909495458679E-002,0.78,-0.254246039676) ); -#30870 = CARTESIAN_POINT('',(-7.022762763978E-002,0.78,-0.246448095159) +#33262 = CARTESIAN_POINT('',(-7.022762763978E-002,0.78,-0.246448095159) ); -#30871 = CARTESIAN_POINT('',(-7.194141210995E-002,0.78,-0.238957105397) +#33263 = CARTESIAN_POINT('',(-7.194141210995E-002,0.78,-0.238957105397) ); -#30872 = CARTESIAN_POINT('',(-7.444030771623E-002,0.78,-0.231804715104) +#33264 = CARTESIAN_POINT('',(-7.444030771623E-002,0.78,-0.231804715104) ); -#30873 = CARTESIAN_POINT('',(-7.763201825955E-002,0.78,-0.224985868182) +#33265 = CARTESIAN_POINT('',(-7.763201825955E-002,0.78,-0.224985868182) ); -#30874 = CARTESIAN_POINT('',(-8.158020278859E-002,0.78,-0.218510466344) +#33266 = CARTESIAN_POINT('',(-8.158020278859E-002,0.78,-0.218510466344) ); -#30875 = CARTESIAN_POINT('',(-8.624606907258E-002,0.78,-0.212385170715) +#33267 = CARTESIAN_POINT('',(-8.624606907258E-002,0.78,-0.212385170715) ); -#30876 = CARTESIAN_POINT('',(-9.149198214336E-002,0.78,-0.20659094194)); -#30877 = CARTESIAN_POINT('',(-9.735690982358E-002,0.78,-0.201353210079) +#33268 = CARTESIAN_POINT('',(-9.149198214336E-002,0.78,-0.20659094194)); +#33269 = CARTESIAN_POINT('',(-9.735690982358E-002,0.78,-0.201353210079) ); -#30878 = CARTESIAN_POINT('',(-0.103701675181,0.78,-0.196737612617)); -#30879 = CARTESIAN_POINT('',(-0.110550084589,0.78,-0.192871461252)); -#30880 = CARTESIAN_POINT('',(-0.117819043423,0.78,-0.18967030182)); -#30881 = CARTESIAN_POINT('',(-0.12554335796,0.78,-0.187189415129)); -#30882 = CARTESIAN_POINT('',(-0.133713099132,0.78,-0.18545226843)); -#30883 = CARTESIAN_POINT('',(-0.142325548317,0.78,-0.184417874018)); -#30884 = CARTESIAN_POINT('',(-0.148214474312,0.78,-0.184278421007)); -#30885 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); -#30886 = PCURVE('',#28866,#30887); -#30887 = DEFINITIONAL_REPRESENTATION('',(#30888),#30908); -#30888 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30889,#30890,#30891,#30892, - #30893,#30894,#30895,#30896,#30897,#30898,#30899,#30900,#30901, - #30902,#30903,#30904,#30905,#30906,#30907),.UNSPECIFIED.,.F.,.F.,(4, +#33270 = CARTESIAN_POINT('',(-0.103701675181,0.78,-0.196737612617)); +#33271 = CARTESIAN_POINT('',(-0.110550084589,0.78,-0.192871461252)); +#33272 = CARTESIAN_POINT('',(-0.117819043423,0.78,-0.18967030182)); +#33273 = CARTESIAN_POINT('',(-0.12554335796,0.78,-0.187189415129)); +#33274 = CARTESIAN_POINT('',(-0.133713099132,0.78,-0.18545226843)); +#33275 = CARTESIAN_POINT('',(-0.142325548317,0.78,-0.184417874018)); +#33276 = CARTESIAN_POINT('',(-0.148214474312,0.78,-0.184278421007)); +#33277 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); +#33278 = PCURVE('',#31258,#33279); +#33279 = DEFINITIONAL_REPRESENTATION('',(#33280),#33300); +#33280 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33281,#33282,#33283,#33284, + #33285,#33286,#33287,#33288,#33289,#33290,#33291,#33292,#33293, + #33294,#33295,#33296,#33297,#33298,#33299),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.359990034717E-002, 0.125296650794,0.185568720195,0.244698211001,0.30371680619, 0.362919650948,0.423300313869,0.485177309545,0.547083413224, 0.608524799634,0.669964853245,0.732299377978,0.79565029349, 0.861055470947,0.929122115173,1.),.UNSPECIFIED.); -#30889 = CARTESIAN_POINT('',(-0.887254948901,0.931099394448)); -#30890 = CARTESIAN_POINT('',(-0.884558415664,0.931033958742)); -#30891 = CARTESIAN_POINT('',(-0.879246039676,0.930905045413)); -#30892 = CARTESIAN_POINT('',(-0.871448095159,0.92977237236)); -#30893 = CARTESIAN_POINT('',(-0.863957105397,0.92805858789)); -#30894 = CARTESIAN_POINT('',(-0.856804715104,0.925559692284)); -#30895 = CARTESIAN_POINT('',(-0.849985868182,0.92236798174)); -#30896 = CARTESIAN_POINT('',(-0.843510466344,0.918419797211)); -#30897 = CARTESIAN_POINT('',(-0.837385170715,0.913753930927)); -#30898 = CARTESIAN_POINT('',(-0.83159094194,0.908508017857)); -#30899 = CARTESIAN_POINT('',(-0.826353210079,0.902643090176)); -#30900 = CARTESIAN_POINT('',(-0.821737612617,0.896298324819)); -#30901 = CARTESIAN_POINT('',(-0.817871461252,0.889449915411)); -#30902 = CARTESIAN_POINT('',(-0.81467030182,0.882180956577)); -#30903 = CARTESIAN_POINT('',(-0.812189415129,0.87445664204)); -#30904 = CARTESIAN_POINT('',(-0.81045226843,0.866286900868)); -#30905 = CARTESIAN_POINT('',(-0.809417874018,0.857674451683)); -#30906 = CARTESIAN_POINT('',(-0.809278421007,0.851785525688)); -#30907 = CARTESIAN_POINT('',(-0.809207283737,0.848781487881)); -#30908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#30909 = PCURVE('',#30910,#30949); -#30910 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#30911,#30912) - ,(#30913,#30914) - ,(#30915,#30916) - ,(#30917,#30918) - ,(#30919,#30920) - ,(#30921,#30922) - ,(#30923,#30924) - ,(#30925,#30926) - ,(#30927,#30928) - ,(#30929,#30930) - ,(#30931,#30932) - ,(#30933,#30934) - ,(#30935,#30936) - ,(#30937,#30938) - ,(#30939,#30940) - ,(#30941,#30942) - ,(#30943,#30944) - ,(#30945,#30946) - ,(#30947,#30948 +#33281 = CARTESIAN_POINT('',(-0.887254948901,0.931099394448)); +#33282 = CARTESIAN_POINT('',(-0.884558415664,0.931033958742)); +#33283 = CARTESIAN_POINT('',(-0.879246039676,0.930905045413)); +#33284 = CARTESIAN_POINT('',(-0.871448095159,0.92977237236)); +#33285 = CARTESIAN_POINT('',(-0.863957105397,0.92805858789)); +#33286 = CARTESIAN_POINT('',(-0.856804715104,0.925559692284)); +#33287 = CARTESIAN_POINT('',(-0.849985868182,0.92236798174)); +#33288 = CARTESIAN_POINT('',(-0.843510466344,0.918419797211)); +#33289 = CARTESIAN_POINT('',(-0.837385170715,0.913753930927)); +#33290 = CARTESIAN_POINT('',(-0.83159094194,0.908508017857)); +#33291 = CARTESIAN_POINT('',(-0.826353210079,0.902643090176)); +#33292 = CARTESIAN_POINT('',(-0.821737612617,0.896298324819)); +#33293 = CARTESIAN_POINT('',(-0.817871461252,0.889449915411)); +#33294 = CARTESIAN_POINT('',(-0.81467030182,0.882180956577)); +#33295 = CARTESIAN_POINT('',(-0.812189415129,0.87445664204)); +#33296 = CARTESIAN_POINT('',(-0.81045226843,0.866286900868)); +#33297 = CARTESIAN_POINT('',(-0.809417874018,0.857674451683)); +#33298 = CARTESIAN_POINT('',(-0.809278421007,0.851785525688)); +#33299 = CARTESIAN_POINT('',(-0.809207283737,0.848781487881)); +#33300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33301 = PCURVE('',#33302,#33341); +#33302 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#33303,#33304) + ,(#33305,#33306) + ,(#33307,#33308) + ,(#33309,#33310) + ,(#33311,#33312) + ,(#33313,#33314) + ,(#33315,#33316) + ,(#33317,#33318) + ,(#33319,#33320) + ,(#33321,#33322) + ,(#33323,#33324) + ,(#33325,#33326) + ,(#33327,#33328) + ,(#33329,#33330) + ,(#33331,#33332) + ,(#33333,#33334) + ,(#33335,#33336) + ,(#33337,#33338) + ,(#33339,#33340 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.359990034717E-002,0.125296650794,0.185568720195, 0.244698211001,0.30371680619,0.362919650948,0.423300313869, 0.485177309545,0.547083413224,0.608524799634,0.669964853245, 0.732299377978,0.79565029349,0.861055470947,0.929122115173,1.),( 0.E+000,1.),.UNSPECIFIED.); -#30911 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) +#33303 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) ); -#30912 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) +#33304 = CARTESIAN_POINT('',(-6.890060555222E-002,0.78,-0.262254948901) ); -#30913 = CARTESIAN_POINT('',(-6.896604125846E-002,0.782,-0.259558415664) +#33305 = CARTESIAN_POINT('',(-6.896604125846E-002,0.782,-0.259558415664) ); -#30914 = CARTESIAN_POINT('',(-6.896604125846E-002,0.78,-0.259558415664) +#33306 = CARTESIAN_POINT('',(-6.896604125846E-002,0.78,-0.259558415664) ); -#30915 = CARTESIAN_POINT('',(-6.909495458679E-002,0.782,-0.254246039676) +#33307 = CARTESIAN_POINT('',(-6.909495458679E-002,0.782,-0.254246039676) ); -#30916 = CARTESIAN_POINT('',(-6.909495458679E-002,0.78,-0.254246039676) +#33308 = CARTESIAN_POINT('',(-6.909495458679E-002,0.78,-0.254246039676) ); -#30917 = CARTESIAN_POINT('',(-7.022762763978E-002,0.782,-0.246448095159) +#33309 = CARTESIAN_POINT('',(-7.022762763978E-002,0.782,-0.246448095159) ); -#30918 = CARTESIAN_POINT('',(-7.022762763978E-002,0.78,-0.246448095159) +#33310 = CARTESIAN_POINT('',(-7.022762763978E-002,0.78,-0.246448095159) ); -#30919 = CARTESIAN_POINT('',(-7.194141210995E-002,0.782,-0.238957105397) +#33311 = CARTESIAN_POINT('',(-7.194141210995E-002,0.782,-0.238957105397) ); -#30920 = CARTESIAN_POINT('',(-7.194141210995E-002,0.78,-0.238957105397) +#33312 = CARTESIAN_POINT('',(-7.194141210995E-002,0.78,-0.238957105397) ); -#30921 = CARTESIAN_POINT('',(-7.444030771623E-002,0.782,-0.231804715104) +#33313 = CARTESIAN_POINT('',(-7.444030771623E-002,0.782,-0.231804715104) ); -#30922 = CARTESIAN_POINT('',(-7.444030771623E-002,0.78,-0.231804715104) +#33314 = CARTESIAN_POINT('',(-7.444030771623E-002,0.78,-0.231804715104) ); -#30923 = CARTESIAN_POINT('',(-7.763201825955E-002,0.782,-0.224985868182) +#33315 = CARTESIAN_POINT('',(-7.763201825955E-002,0.782,-0.224985868182) ); -#30924 = CARTESIAN_POINT('',(-7.763201825955E-002,0.78,-0.224985868182) +#33316 = CARTESIAN_POINT('',(-7.763201825955E-002,0.78,-0.224985868182) ); -#30925 = CARTESIAN_POINT('',(-8.158020278859E-002,0.782,-0.218510466344) +#33317 = CARTESIAN_POINT('',(-8.158020278859E-002,0.782,-0.218510466344) ); -#30926 = CARTESIAN_POINT('',(-8.158020278859E-002,0.78,-0.218510466344) +#33318 = CARTESIAN_POINT('',(-8.158020278859E-002,0.78,-0.218510466344) ); -#30927 = CARTESIAN_POINT('',(-8.624606907258E-002,0.782,-0.212385170715) +#33319 = CARTESIAN_POINT('',(-8.624606907258E-002,0.782,-0.212385170715) ); -#30928 = CARTESIAN_POINT('',(-8.624606907258E-002,0.78,-0.212385170715) +#33320 = CARTESIAN_POINT('',(-8.624606907258E-002,0.78,-0.212385170715) ); -#30929 = CARTESIAN_POINT('',(-9.149198214336E-002,0.782,-0.20659094194) +#33321 = CARTESIAN_POINT('',(-9.149198214336E-002,0.782,-0.20659094194) ); -#30930 = CARTESIAN_POINT('',(-9.149198214336E-002,0.78,-0.20659094194)); -#30931 = CARTESIAN_POINT('',(-9.735690982358E-002,0.782,-0.201353210079) +#33322 = CARTESIAN_POINT('',(-9.149198214336E-002,0.78,-0.20659094194)); +#33323 = CARTESIAN_POINT('',(-9.735690982358E-002,0.782,-0.201353210079) ); -#30932 = CARTESIAN_POINT('',(-9.735690982358E-002,0.78,-0.201353210079) +#33324 = CARTESIAN_POINT('',(-9.735690982358E-002,0.78,-0.201353210079) ); -#30933 = CARTESIAN_POINT('',(-0.103701675181,0.782,-0.196737612617)); -#30934 = CARTESIAN_POINT('',(-0.103701675181,0.78,-0.196737612617)); -#30935 = CARTESIAN_POINT('',(-0.110550084589,0.782,-0.192871461252)); -#30936 = CARTESIAN_POINT('',(-0.110550084589,0.78,-0.192871461252)); -#30937 = CARTESIAN_POINT('',(-0.117819043423,0.782,-0.18967030182)); -#30938 = CARTESIAN_POINT('',(-0.117819043423,0.78,-0.18967030182)); -#30939 = CARTESIAN_POINT('',(-0.12554335796,0.782,-0.187189415129)); -#30940 = CARTESIAN_POINT('',(-0.12554335796,0.78,-0.187189415129)); -#30941 = CARTESIAN_POINT('',(-0.133713099132,0.782,-0.18545226843)); -#30942 = CARTESIAN_POINT('',(-0.133713099132,0.78,-0.18545226843)); -#30943 = CARTESIAN_POINT('',(-0.142325548317,0.782,-0.184417874018)); -#30944 = CARTESIAN_POINT('',(-0.142325548317,0.78,-0.184417874018)); -#30945 = CARTESIAN_POINT('',(-0.148214474312,0.782,-0.184278421007)); -#30946 = CARTESIAN_POINT('',(-0.148214474312,0.78,-0.184278421007)); -#30947 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#30948 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); -#30949 = DEFINITIONAL_REPRESENTATION('',(#30950),#30954); -#30950 = LINE('',#30951,#30952); -#30951 = CARTESIAN_POINT('',(0.E+000,1.)); -#30952 = VECTOR('',#30953,1.); -#30953 = DIRECTION('',(1.,0.E+000)); -#30954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33325 = CARTESIAN_POINT('',(-0.103701675181,0.782,-0.196737612617)); +#33326 = CARTESIAN_POINT('',(-0.103701675181,0.78,-0.196737612617)); +#33327 = CARTESIAN_POINT('',(-0.110550084589,0.782,-0.192871461252)); +#33328 = CARTESIAN_POINT('',(-0.110550084589,0.78,-0.192871461252)); +#33329 = CARTESIAN_POINT('',(-0.117819043423,0.782,-0.18967030182)); +#33330 = CARTESIAN_POINT('',(-0.117819043423,0.78,-0.18967030182)); +#33331 = CARTESIAN_POINT('',(-0.12554335796,0.782,-0.187189415129)); +#33332 = CARTESIAN_POINT('',(-0.12554335796,0.78,-0.187189415129)); +#33333 = CARTESIAN_POINT('',(-0.133713099132,0.782,-0.18545226843)); +#33334 = CARTESIAN_POINT('',(-0.133713099132,0.78,-0.18545226843)); +#33335 = CARTESIAN_POINT('',(-0.142325548317,0.782,-0.184417874018)); +#33336 = CARTESIAN_POINT('',(-0.142325548317,0.78,-0.184417874018)); +#33337 = CARTESIAN_POINT('',(-0.148214474312,0.782,-0.184278421007)); +#33338 = CARTESIAN_POINT('',(-0.148214474312,0.78,-0.184278421007)); +#33339 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#33340 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); +#33341 = DEFINITIONAL_REPRESENTATION('',(#33342),#33346); +#33342 = LINE('',#33343,#33344); +#33343 = CARTESIAN_POINT('',(0.E+000,1.)); +#33344 = VECTOR('',#33345,1.); +#33345 = DIRECTION('',(1.,0.E+000)); +#33346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#30955 = ORIENTED_EDGE('',*,*,#30956,.T.); -#30956 = EDGE_CURVE('',#30863,#30361,#30957,.T.); -#30957 = SURFACE_CURVE('',#30958,(#30978,#31001),.PCURVE_S1.); -#30958 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30959,#30960,#30961,#30962, - #30963,#30964,#30965,#30966,#30967,#30968,#30969,#30970,#30971, - #30972,#30973,#30974,#30975,#30976,#30977),.UNSPECIFIED.,.F.,.F.,(4, +#33347 = ORIENTED_EDGE('',*,*,#33348,.T.); +#33348 = EDGE_CURVE('',#33255,#32753,#33349,.T.); +#33349 = SURFACE_CURVE('',#33350,(#33370,#33393),.PCURVE_S1.); +#33350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33351,#33352,#33353,#33354, + #33355,#33356,#33357,#33358,#33359,#33360,#33361,#33362,#33363, + #33364,#33365,#33366,#33367,#33368,#33369),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.044163105955E-002, 0.13808932472,0.203177733524,0.266138723805,0.327928781367, 0.389190360761,0.450253575103,0.512346578128,0.573842720559, 0.633932556807,0.693459807598,0.752479435483,0.812385930843, 0.873070465232,0.935184306584,1.),.UNSPECIFIED.); -#30959 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); -#30960 = CARTESIAN_POINT('',(-0.15422224945,0.78,-0.184279954097)); -#30961 = CARTESIAN_POINT('',(-0.16011058641,0.78,-0.18442241248)); -#30962 = CARTESIAN_POINT('',(-0.168730904373,0.78,-0.185435660286)); -#30963 = CARTESIAN_POINT('',(-0.176888956674,0.78,-0.187251556488)); -#30964 = CARTESIAN_POINT('',(-0.184603227745,0.78,-0.189734964963)); -#30965 = CARTESIAN_POINT('',(-0.191915564883,0.78,-0.192849452628)); -#30966 = CARTESIAN_POINT('',(-0.198717980682,0.78,-0.19680271821)); -#30967 = CARTESIAN_POINT('',(-0.205104189941,0.78,-0.201412468033)); -#30968 = CARTESIAN_POINT('',(-0.210973195665,0.78,-0.206682596761)); -#30969 = CARTESIAN_POINT('',(-0.216262683863,0.78,-0.212476207474)); -#30970 = CARTESIAN_POINT('',(-0.220867043727,0.78,-0.218691964243)); -#30971 = CARTESIAN_POINT('',(-0.224791789972,0.78,-0.225234208511)); -#30972 = CARTESIAN_POINT('',(-0.228021770962,0.78,-0.232139820494)); -#30973 = CARTESIAN_POINT('',(-0.230483753007,0.78,-0.23940886311)); -#30974 = CARTESIAN_POINT('',(-0.232211601209,0.78,-0.247014045784)); -#30975 = CARTESIAN_POINT('',(-0.233346324416,0.78,-0.254949557005)); -#30976 = CARTESIAN_POINT('',(-0.233472161067,0.78,-0.260364482314)); -#30977 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); -#30978 = PCURVE('',#28866,#30979); -#30979 = DEFINITIONAL_REPRESENTATION('',(#30980),#31000); -#30980 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#30981,#30982,#30983,#30984, - #30985,#30986,#30987,#30988,#30989,#30990,#30991,#30992,#30993, - #30994,#30995,#30996,#30997,#30998,#30999),.UNSPECIFIED.,.F.,.F.,(4, +#33351 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); +#33352 = CARTESIAN_POINT('',(-0.15422224945,0.78,-0.184279954097)); +#33353 = CARTESIAN_POINT('',(-0.16011058641,0.78,-0.18442241248)); +#33354 = CARTESIAN_POINT('',(-0.168730904373,0.78,-0.185435660286)); +#33355 = CARTESIAN_POINT('',(-0.176888956674,0.78,-0.187251556488)); +#33356 = CARTESIAN_POINT('',(-0.184603227745,0.78,-0.189734964963)); +#33357 = CARTESIAN_POINT('',(-0.191915564883,0.78,-0.192849452628)); +#33358 = CARTESIAN_POINT('',(-0.198717980682,0.78,-0.19680271821)); +#33359 = CARTESIAN_POINT('',(-0.205104189941,0.78,-0.201412468033)); +#33360 = CARTESIAN_POINT('',(-0.210973195665,0.78,-0.206682596761)); +#33361 = CARTESIAN_POINT('',(-0.216262683863,0.78,-0.212476207474)); +#33362 = CARTESIAN_POINT('',(-0.220867043727,0.78,-0.218691964243)); +#33363 = CARTESIAN_POINT('',(-0.224791789972,0.78,-0.225234208511)); +#33364 = CARTESIAN_POINT('',(-0.228021770962,0.78,-0.232139820494)); +#33365 = CARTESIAN_POINT('',(-0.230483753007,0.78,-0.23940886311)); +#33366 = CARTESIAN_POINT('',(-0.232211601209,0.78,-0.247014045784)); +#33367 = CARTESIAN_POINT('',(-0.233346324416,0.78,-0.254949557005)); +#33368 = CARTESIAN_POINT('',(-0.233472161067,0.78,-0.260364482314)); +#33369 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); +#33370 = PCURVE('',#31258,#33371); +#33371 = DEFINITIONAL_REPRESENTATION('',(#33372),#33392); +#33372 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33373,#33374,#33375,#33376, + #33377,#33378,#33379,#33380,#33381,#33382,#33383,#33384,#33385, + #33386,#33387,#33388,#33389,#33390,#33391),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.044163105955E-002, 0.13808932472,0.203177733524,0.266138723805,0.327928781367, 0.389190360761,0.450253575103,0.512346578128,0.573842720559, 0.633932556807,0.693459807598,0.752479435483,0.812385930843, 0.873070465232,0.935184306584,1.),.UNSPECIFIED.); -#30981 = CARTESIAN_POINT('',(-0.809207283737,0.848781487881)); -#30982 = CARTESIAN_POINT('',(-0.809279954097,0.84577775055)); -#30983 = CARTESIAN_POINT('',(-0.80942241248,0.83988941359)); -#30984 = CARTESIAN_POINT('',(-0.810435660286,0.831269095627)); -#30985 = CARTESIAN_POINT('',(-0.812251556488,0.823111043326)); -#30986 = CARTESIAN_POINT('',(-0.814734964963,0.815396772255)); -#30987 = CARTESIAN_POINT('',(-0.817849452628,0.808084435117)); -#30988 = CARTESIAN_POINT('',(-0.82180271821,0.801282019318)); -#30989 = CARTESIAN_POINT('',(-0.826412468033,0.794895810059)); -#30990 = CARTESIAN_POINT('',(-0.831682596761,0.789026804335)); -#30991 = CARTESIAN_POINT('',(-0.837476207474,0.783737316137)); -#30992 = CARTESIAN_POINT('',(-0.843691964243,0.779132956273)); -#30993 = CARTESIAN_POINT('',(-0.850234208511,0.775208210028)); -#30994 = CARTESIAN_POINT('',(-0.857139820494,0.771978229038)); -#30995 = CARTESIAN_POINT('',(-0.86440886311,0.769516246993)); -#30996 = CARTESIAN_POINT('',(-0.872014045784,0.767788398791)); -#30997 = CARTESIAN_POINT('',(-0.879949557005,0.766653675584)); -#30998 = CARTESIAN_POINT('',(-0.885364482314,0.766527838933)); -#30999 = CARTESIAN_POINT('',(-0.888129576659,0.766463581313)); -#31000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31001 = PCURVE('',#31002,#31041); -#31002 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#31003,#31004) - ,(#31005,#31006) - ,(#31007,#31008) - ,(#31009,#31010) - ,(#31011,#31012) - ,(#31013,#31014) - ,(#31015,#31016) - ,(#31017,#31018) - ,(#31019,#31020) - ,(#31021,#31022) - ,(#31023,#31024) - ,(#31025,#31026) - ,(#31027,#31028) - ,(#31029,#31030) - ,(#31031,#31032) - ,(#31033,#31034) - ,(#31035,#31036) - ,(#31037,#31038) - ,(#31039,#31040 +#33373 = CARTESIAN_POINT('',(-0.809207283737,0.848781487881)); +#33374 = CARTESIAN_POINT('',(-0.809279954097,0.84577775055)); +#33375 = CARTESIAN_POINT('',(-0.80942241248,0.83988941359)); +#33376 = CARTESIAN_POINT('',(-0.810435660286,0.831269095627)); +#33377 = CARTESIAN_POINT('',(-0.812251556488,0.823111043326)); +#33378 = CARTESIAN_POINT('',(-0.814734964963,0.815396772255)); +#33379 = CARTESIAN_POINT('',(-0.817849452628,0.808084435117)); +#33380 = CARTESIAN_POINT('',(-0.82180271821,0.801282019318)); +#33381 = CARTESIAN_POINT('',(-0.826412468033,0.794895810059)); +#33382 = CARTESIAN_POINT('',(-0.831682596761,0.789026804335)); +#33383 = CARTESIAN_POINT('',(-0.837476207474,0.783737316137)); +#33384 = CARTESIAN_POINT('',(-0.843691964243,0.779132956273)); +#33385 = CARTESIAN_POINT('',(-0.850234208511,0.775208210028)); +#33386 = CARTESIAN_POINT('',(-0.857139820494,0.771978229038)); +#33387 = CARTESIAN_POINT('',(-0.86440886311,0.769516246993)); +#33388 = CARTESIAN_POINT('',(-0.872014045784,0.767788398791)); +#33389 = CARTESIAN_POINT('',(-0.879949557005,0.766653675584)); +#33390 = CARTESIAN_POINT('',(-0.885364482314,0.766527838933)); +#33391 = CARTESIAN_POINT('',(-0.888129576659,0.766463581313)); +#33392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33393 = PCURVE('',#33394,#33433); +#33394 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#33395,#33396) + ,(#33397,#33398) + ,(#33399,#33400) + ,(#33401,#33402) + ,(#33403,#33404) + ,(#33405,#33406) + ,(#33407,#33408) + ,(#33409,#33410) + ,(#33411,#33412) + ,(#33413,#33414) + ,(#33415,#33416) + ,(#33417,#33418) + ,(#33419,#33420) + ,(#33421,#33422) + ,(#33423,#33424) + ,(#33425,#33426) + ,(#33427,#33428) + ,(#33429,#33430) + ,(#33431,#33432 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.044163105955E-002,0.13808932472,0.203177733524, 0.266138723805,0.327928781367,0.389190360761,0.450253575103, 0.512346578128,0.573842720559,0.633932556807,0.693459807598, 0.752479435483,0.812385930843,0.873070465232,0.935184306584,1.),( 0.E+000,1.),.UNSPECIFIED.); -#31003 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#31004 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); -#31005 = CARTESIAN_POINT('',(-0.15422224945,0.782,-0.184279954097)); -#31006 = CARTESIAN_POINT('',(-0.15422224945,0.78,-0.184279954097)); -#31007 = CARTESIAN_POINT('',(-0.16011058641,0.782,-0.18442241248)); -#31008 = CARTESIAN_POINT('',(-0.16011058641,0.78,-0.18442241248)); -#31009 = CARTESIAN_POINT('',(-0.168730904373,0.782,-0.185435660286)); -#31010 = CARTESIAN_POINT('',(-0.168730904373,0.78,-0.185435660286)); -#31011 = CARTESIAN_POINT('',(-0.176888956674,0.782,-0.187251556488)); -#31012 = CARTESIAN_POINT('',(-0.176888956674,0.78,-0.187251556488)); -#31013 = CARTESIAN_POINT('',(-0.184603227745,0.782,-0.189734964963)); -#31014 = CARTESIAN_POINT('',(-0.184603227745,0.78,-0.189734964963)); -#31015 = CARTESIAN_POINT('',(-0.191915564883,0.782,-0.192849452628)); -#31016 = CARTESIAN_POINT('',(-0.191915564883,0.78,-0.192849452628)); -#31017 = CARTESIAN_POINT('',(-0.198717980682,0.782,-0.19680271821)); -#31018 = CARTESIAN_POINT('',(-0.198717980682,0.78,-0.19680271821)); -#31019 = CARTESIAN_POINT('',(-0.205104189941,0.782,-0.201412468033)); -#31020 = CARTESIAN_POINT('',(-0.205104189941,0.78,-0.201412468033)); -#31021 = CARTESIAN_POINT('',(-0.210973195665,0.782,-0.206682596761)); -#31022 = CARTESIAN_POINT('',(-0.210973195665,0.78,-0.206682596761)); -#31023 = CARTESIAN_POINT('',(-0.216262683863,0.782,-0.212476207474)); -#31024 = CARTESIAN_POINT('',(-0.216262683863,0.78,-0.212476207474)); -#31025 = CARTESIAN_POINT('',(-0.220867043727,0.782,-0.218691964243)); -#31026 = CARTESIAN_POINT('',(-0.220867043727,0.78,-0.218691964243)); -#31027 = CARTESIAN_POINT('',(-0.224791789972,0.782,-0.225234208511)); -#31028 = CARTESIAN_POINT('',(-0.224791789972,0.78,-0.225234208511)); -#31029 = CARTESIAN_POINT('',(-0.228021770962,0.782,-0.232139820494)); -#31030 = CARTESIAN_POINT('',(-0.228021770962,0.78,-0.232139820494)); -#31031 = CARTESIAN_POINT('',(-0.230483753007,0.782,-0.23940886311)); -#31032 = CARTESIAN_POINT('',(-0.230483753007,0.78,-0.23940886311)); -#31033 = CARTESIAN_POINT('',(-0.232211601209,0.782,-0.247014045784)); -#31034 = CARTESIAN_POINT('',(-0.232211601209,0.78,-0.247014045784)); -#31035 = CARTESIAN_POINT('',(-0.233346324416,0.782,-0.254949557005)); -#31036 = CARTESIAN_POINT('',(-0.233346324416,0.78,-0.254949557005)); -#31037 = CARTESIAN_POINT('',(-0.233472161067,0.782,-0.260364482314)); -#31038 = CARTESIAN_POINT('',(-0.233472161067,0.78,-0.260364482314)); -#31039 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#31040 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); -#31041 = DEFINITIONAL_REPRESENTATION('',(#31042),#31046); -#31042 = LINE('',#31043,#31044); -#31043 = CARTESIAN_POINT('',(0.E+000,1.)); -#31044 = VECTOR('',#31045,1.); -#31045 = DIRECTION('',(1.,0.E+000)); -#31046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31047 = ADVANCED_FACE('',(#31048),#31060,.T.); -#31048 = FACE_BOUND('',#31049,.T.); -#31049 = EDGE_LOOP('',(#31050,#31077,#31099,#31126)); -#31050 = ORIENTED_EDGE('',*,*,#31051,.F.); -#31051 = EDGE_CURVE('',#30251,#31052,#31054,.T.); -#31052 = VERTEX_POINT('',#31053); -#31053 = CARTESIAN_POINT('',(-0.85,0.78,-0.475)); -#31054 = SURFACE_CURVE('',#31055,(#31059,#31070),.PCURVE_S1.); -#31055 = LINE('',#31056,#31057); -#31056 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); -#31057 = VECTOR('',#31058,1.); -#31058 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31059 = PCURVE('',#31060,#31065); -#31060 = CYLINDRICAL_SURFACE('',#31061,0.15); -#31061 = AXIS2_PLACEMENT_3D('',#31062,#31063,#31064); -#31062 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); -#31063 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31064 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31065 = DEFINITIONAL_REPRESENTATION('',(#31066),#31069); -#31066 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31067,#31068),.UNSPECIFIED., +#33395 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#33396 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.184207283737)); +#33397 = CARTESIAN_POINT('',(-0.15422224945,0.782,-0.184279954097)); +#33398 = CARTESIAN_POINT('',(-0.15422224945,0.78,-0.184279954097)); +#33399 = CARTESIAN_POINT('',(-0.16011058641,0.782,-0.18442241248)); +#33400 = CARTESIAN_POINT('',(-0.16011058641,0.78,-0.18442241248)); +#33401 = CARTESIAN_POINT('',(-0.168730904373,0.782,-0.185435660286)); +#33402 = CARTESIAN_POINT('',(-0.168730904373,0.78,-0.185435660286)); +#33403 = CARTESIAN_POINT('',(-0.176888956674,0.782,-0.187251556488)); +#33404 = CARTESIAN_POINT('',(-0.176888956674,0.78,-0.187251556488)); +#33405 = CARTESIAN_POINT('',(-0.184603227745,0.782,-0.189734964963)); +#33406 = CARTESIAN_POINT('',(-0.184603227745,0.78,-0.189734964963)); +#33407 = CARTESIAN_POINT('',(-0.191915564883,0.782,-0.192849452628)); +#33408 = CARTESIAN_POINT('',(-0.191915564883,0.78,-0.192849452628)); +#33409 = CARTESIAN_POINT('',(-0.198717980682,0.782,-0.19680271821)); +#33410 = CARTESIAN_POINT('',(-0.198717980682,0.78,-0.19680271821)); +#33411 = CARTESIAN_POINT('',(-0.205104189941,0.782,-0.201412468033)); +#33412 = CARTESIAN_POINT('',(-0.205104189941,0.78,-0.201412468033)); +#33413 = CARTESIAN_POINT('',(-0.210973195665,0.782,-0.206682596761)); +#33414 = CARTESIAN_POINT('',(-0.210973195665,0.78,-0.206682596761)); +#33415 = CARTESIAN_POINT('',(-0.216262683863,0.782,-0.212476207474)); +#33416 = CARTESIAN_POINT('',(-0.216262683863,0.78,-0.212476207474)); +#33417 = CARTESIAN_POINT('',(-0.220867043727,0.782,-0.218691964243)); +#33418 = CARTESIAN_POINT('',(-0.220867043727,0.78,-0.218691964243)); +#33419 = CARTESIAN_POINT('',(-0.224791789972,0.782,-0.225234208511)); +#33420 = CARTESIAN_POINT('',(-0.224791789972,0.78,-0.225234208511)); +#33421 = CARTESIAN_POINT('',(-0.228021770962,0.782,-0.232139820494)); +#33422 = CARTESIAN_POINT('',(-0.228021770962,0.78,-0.232139820494)); +#33423 = CARTESIAN_POINT('',(-0.230483753007,0.782,-0.23940886311)); +#33424 = CARTESIAN_POINT('',(-0.230483753007,0.78,-0.23940886311)); +#33425 = CARTESIAN_POINT('',(-0.232211601209,0.782,-0.247014045784)); +#33426 = CARTESIAN_POINT('',(-0.232211601209,0.78,-0.247014045784)); +#33427 = CARTESIAN_POINT('',(-0.233346324416,0.782,-0.254949557005)); +#33428 = CARTESIAN_POINT('',(-0.233346324416,0.78,-0.254949557005)); +#33429 = CARTESIAN_POINT('',(-0.233472161067,0.782,-0.260364482314)); +#33430 = CARTESIAN_POINT('',(-0.233472161067,0.78,-0.260364482314)); +#33431 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#33432 = CARTESIAN_POINT('',(-0.233536418687,0.78,-0.263129576659)); +#33433 = DEFINITIONAL_REPRESENTATION('',(#33434),#33438); +#33434 = LINE('',#33435,#33436); +#33435 = CARTESIAN_POINT('',(0.E+000,1.)); +#33436 = VECTOR('',#33437,1.); +#33437 = DIRECTION('',(1.,0.E+000)); +#33438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33439 = ADVANCED_FACE('',(#33440),#33452,.T.); +#33440 = FACE_BOUND('',#33441,.T.); +#33441 = EDGE_LOOP('',(#33442,#33469,#33491,#33518)); +#33442 = ORIENTED_EDGE('',*,*,#33443,.F.); +#33443 = EDGE_CURVE('',#32643,#33444,#33446,.T.); +#33444 = VERTEX_POINT('',#33445); +#33445 = CARTESIAN_POINT('',(-0.85,0.78,-0.475)); +#33446 = SURFACE_CURVE('',#33447,(#33451,#33462),.PCURVE_S1.); +#33447 = LINE('',#33448,#33449); +#33448 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); +#33449 = VECTOR('',#33450,1.); +#33450 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33451 = PCURVE('',#33452,#33457); +#33452 = CYLINDRICAL_SURFACE('',#33453,0.15); +#33453 = AXIS2_PLACEMENT_3D('',#33454,#33455,#33456); +#33454 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); +#33455 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33456 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33457 = DEFINITIONAL_REPRESENTATION('',(#33458),#33461); +#33458 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33459,#33460),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31067 = CARTESIAN_POINT('',(1.570796326795,0.5)); -#31068 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#31069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31070 = PCURVE('',#30266,#31071); -#31071 = DEFINITIONAL_REPRESENTATION('',(#31072),#31076); -#31072 = LINE('',#31073,#31074); -#31073 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#31074 = VECTOR('',#31075,1.); -#31075 = DIRECTION('',(0.E+000,-1.)); -#31076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31077 = ORIENTED_EDGE('',*,*,#31078,.T.); -#31078 = EDGE_CURVE('',#30251,#31079,#31081,.T.); -#31079 = VERTEX_POINT('',#31080); -#31080 = CARTESIAN_POINT('',(-0.5,0.63,-0.625)); -#31081 = SURFACE_CURVE('',#31082,(#31087,#31093),.PCURVE_S1.); -#31082 = CIRCLE('',#31083,0.15); -#31083 = AXIS2_PLACEMENT_3D('',#31084,#31085,#31086); -#31084 = CARTESIAN_POINT('',(-0.5,0.63,-0.475)); -#31085 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); -#31086 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); -#31087 = PCURVE('',#31060,#31088); -#31088 = DEFINITIONAL_REPRESENTATION('',(#31089),#31092); -#31089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31090,#31091),.UNSPECIFIED., +#33459 = CARTESIAN_POINT('',(1.570796326795,0.5)); +#33460 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#33461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33462 = PCURVE('',#32658,#33463); +#33463 = DEFINITIONAL_REPRESENTATION('',(#33464),#33468); +#33464 = LINE('',#33465,#33466); +#33465 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#33466 = VECTOR('',#33467,1.); +#33467 = DIRECTION('',(0.E+000,-1.)); +#33468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33469 = ORIENTED_EDGE('',*,*,#33470,.T.); +#33470 = EDGE_CURVE('',#32643,#33471,#33473,.T.); +#33471 = VERTEX_POINT('',#33472); +#33472 = CARTESIAN_POINT('',(-0.5,0.63,-0.625)); +#33473 = SURFACE_CURVE('',#33474,(#33479,#33485),.PCURVE_S1.); +#33474 = CIRCLE('',#33475,0.15); +#33475 = AXIS2_PLACEMENT_3D('',#33476,#33477,#33478); +#33476 = CARTESIAN_POINT('',(-0.5,0.63,-0.475)); +#33477 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); +#33478 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); +#33479 = PCURVE('',#33452,#33480); +#33480 = DEFINITIONAL_REPRESENTATION('',(#33481),#33484); +#33481 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33482,#33483),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31090 = CARTESIAN_POINT('',(1.570796326795,0.5)); -#31091 = CARTESIAN_POINT('',(0.E+000,0.5)); -#31092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33482 = CARTESIAN_POINT('',(1.570796326795,0.5)); +#33483 = CARTESIAN_POINT('',(0.E+000,0.5)); +#33484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31093 = PCURVE('',#30347,#31094); -#31094 = DEFINITIONAL_REPRESENTATION('',(#31095),#31098); -#31095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31096,#31097),.UNSPECIFIED., +#33485 = PCURVE('',#32739,#33486); +#33486 = DEFINITIONAL_REPRESENTATION('',(#33487),#33490); +#33487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33488,#33489),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31096 = CARTESIAN_POINT('',(1.570796326795,0.5)); -#31097 = CARTESIAN_POINT('',(0.E+000,0.5)); -#31098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31099 = ORIENTED_EDGE('',*,*,#31100,.F.); -#31100 = EDGE_CURVE('',#31101,#31079,#31103,.T.); -#31101 = VERTEX_POINT('',#31102); -#31102 = CARTESIAN_POINT('',(-0.85,0.63,-0.625)); -#31103 = SURFACE_CURVE('',#31104,(#31108,#31114),.PCURVE_S1.); -#31104 = LINE('',#31105,#31106); -#31105 = CARTESIAN_POINT('',(1.,0.63,-0.625)); -#31106 = VECTOR('',#31107,1.); -#31107 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31108 = PCURVE('',#31060,#31109); -#31109 = DEFINITIONAL_REPRESENTATION('',(#31110),#31113); -#31110 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31111,#31112),.UNSPECIFIED., +#33488 = CARTESIAN_POINT('',(1.570796326795,0.5)); +#33489 = CARTESIAN_POINT('',(0.E+000,0.5)); +#33490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33491 = ORIENTED_EDGE('',*,*,#33492,.F.); +#33492 = EDGE_CURVE('',#33493,#33471,#33495,.T.); +#33493 = VERTEX_POINT('',#33494); +#33494 = CARTESIAN_POINT('',(-0.85,0.63,-0.625)); +#33495 = SURFACE_CURVE('',#33496,(#33500,#33506),.PCURVE_S1.); +#33496 = LINE('',#33497,#33498); +#33497 = CARTESIAN_POINT('',(1.,0.63,-0.625)); +#33498 = VECTOR('',#33499,1.); +#33499 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33500 = PCURVE('',#33452,#33501); +#33501 = DEFINITIONAL_REPRESENTATION('',(#33502),#33505); +#33502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33503,#33504),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#31111 = CARTESIAN_POINT('',(0.E+000,0.15)); -#31112 = CARTESIAN_POINT('',(0.E+000,0.5)); -#31113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31114 = PCURVE('',#31115,#31120); -#31115 = PLANE('',#31116); -#31116 = AXIS2_PLACEMENT_3D('',#31117,#31118,#31119); -#31117 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); -#31118 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31119 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31120 = DEFINITIONAL_REPRESENTATION('',(#31121),#31125); -#31121 = LINE('',#31122,#31123); -#31122 = CARTESIAN_POINT('',(2.,-0.15)); -#31123 = VECTOR('',#31124,1.); -#31124 = DIRECTION('',(1.,0.E+000)); -#31125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31126 = ORIENTED_EDGE('',*,*,#31127,.F.); -#31127 = EDGE_CURVE('',#31052,#31101,#31128,.T.); -#31128 = SURFACE_CURVE('',#31129,(#31134,#31140),.PCURVE_S1.); -#31129 = CIRCLE('',#31130,0.15); -#31130 = AXIS2_PLACEMENT_3D('',#31131,#31132,#31133); -#31131 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); -#31132 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31134 = PCURVE('',#31060,#31135); -#31135 = DEFINITIONAL_REPRESENTATION('',(#31136),#31139); -#31136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31137,#31138),.UNSPECIFIED., +#33503 = CARTESIAN_POINT('',(0.E+000,0.15)); +#33504 = CARTESIAN_POINT('',(0.E+000,0.5)); +#33505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33506 = PCURVE('',#33507,#33512); +#33507 = PLANE('',#33508); +#33508 = AXIS2_PLACEMENT_3D('',#33509,#33510,#33511); +#33509 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); +#33510 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33511 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33512 = DEFINITIONAL_REPRESENTATION('',(#33513),#33517); +#33513 = LINE('',#33514,#33515); +#33514 = CARTESIAN_POINT('',(2.,-0.15)); +#33515 = VECTOR('',#33516,1.); +#33516 = DIRECTION('',(1.,0.E+000)); +#33517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33518 = ORIENTED_EDGE('',*,*,#33519,.F.); +#33519 = EDGE_CURVE('',#33444,#33493,#33520,.T.); +#33520 = SURFACE_CURVE('',#33521,(#33526,#33532),.PCURVE_S1.); +#33521 = CIRCLE('',#33522,0.15); +#33522 = AXIS2_PLACEMENT_3D('',#33523,#33524,#33525); +#33523 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); +#33524 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33526 = PCURVE('',#33452,#33527); +#33527 = DEFINITIONAL_REPRESENTATION('',(#33528),#33531); +#33528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33529,#33530),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31137 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#31138 = CARTESIAN_POINT('',(0.E+000,0.15)); -#31139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33529 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#33530 = CARTESIAN_POINT('',(0.E+000,0.15)); +#33531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31140 = PCURVE('',#31141,#31146); -#31141 = SPHERICAL_SURFACE('',#31142,0.15); -#31142 = AXIS2_PLACEMENT_3D('',#31143,#31144,#31145); -#31143 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); -#31144 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31145 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31146 = DEFINITIONAL_REPRESENTATION('',(#31147),#31150); -#31147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31148,#31149),.UNSPECIFIED., +#33532 = PCURVE('',#33533,#33538); +#33533 = SPHERICAL_SURFACE('',#33534,0.15); +#33534 = AXIS2_PLACEMENT_3D('',#33535,#33536,#33537); +#33535 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); +#33536 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33537 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33538 = DEFINITIONAL_REPRESENTATION('',(#33539),#33542); +#33539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33540,#33541),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31148 = CARTESIAN_POINT('',(1.570796326795,1.570796326795)); -#31149 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#31150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31151 = ADVANCED_FACE('',(#31152),#31166,.T.); -#31152 = FACE_BOUND('',#31153,.T.); -#31153 = EDGE_LOOP('',(#31154,#31188,#31208,#31230)); -#31154 = ORIENTED_EDGE('',*,*,#31155,.F.); -#31155 = EDGE_CURVE('',#31156,#31158,#31160,.T.); -#31156 = VERTEX_POINT('',#31157); -#31157 = CARTESIAN_POINT('',(0.5,0.63,-0.625)); -#31158 = VERTEX_POINT('',#31159); -#31159 = CARTESIAN_POINT('',(0.85,0.63,-0.625)); -#31160 = SURFACE_CURVE('',#31161,(#31165,#31176),.PCURVE_S1.); -#31161 = LINE('',#31162,#31163); -#31162 = CARTESIAN_POINT('',(1.,0.63,-0.625)); -#31163 = VECTOR('',#31164,1.); -#31164 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31165 = PCURVE('',#31166,#31171); -#31166 = CYLINDRICAL_SURFACE('',#31167,0.15); -#31167 = AXIS2_PLACEMENT_3D('',#31168,#31169,#31170); -#31168 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); -#31169 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31170 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31171 = DEFINITIONAL_REPRESENTATION('',(#31172),#31175); -#31172 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31173,#31174),.UNSPECIFIED., +#33540 = CARTESIAN_POINT('',(1.570796326795,1.570796326795)); +#33541 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#33542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33543 = ADVANCED_FACE('',(#33544),#33558,.T.); +#33544 = FACE_BOUND('',#33545,.T.); +#33545 = EDGE_LOOP('',(#33546,#33580,#33600,#33622)); +#33546 = ORIENTED_EDGE('',*,*,#33547,.F.); +#33547 = EDGE_CURVE('',#33548,#33550,#33552,.T.); +#33548 = VERTEX_POINT('',#33549); +#33549 = CARTESIAN_POINT('',(0.5,0.63,-0.625)); +#33550 = VERTEX_POINT('',#33551); +#33551 = CARTESIAN_POINT('',(0.85,0.63,-0.625)); +#33552 = SURFACE_CURVE('',#33553,(#33557,#33568),.PCURVE_S1.); +#33553 = LINE('',#33554,#33555); +#33554 = CARTESIAN_POINT('',(1.,0.63,-0.625)); +#33555 = VECTOR('',#33556,1.); +#33556 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33557 = PCURVE('',#33558,#33563); +#33558 = CYLINDRICAL_SURFACE('',#33559,0.15); +#33559 = AXIS2_PLACEMENT_3D('',#33560,#33561,#33562); +#33560 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); +#33561 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33562 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33563 = DEFINITIONAL_REPRESENTATION('',(#33564),#33567); +#33564 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33565,#33566),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31173 = CARTESIAN_POINT('',(0.E+000,1.5)); -#31174 = CARTESIAN_POINT('',(0.E+000,1.85)); -#31175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31176 = PCURVE('',#31177,#31182); -#31177 = PLANE('',#31178); -#31178 = AXIS2_PLACEMENT_3D('',#31179,#31180,#31181); -#31179 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); -#31180 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31181 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31182 = DEFINITIONAL_REPRESENTATION('',(#31183),#31187); -#31183 = LINE('',#31184,#31185); -#31184 = CARTESIAN_POINT('',(2.,-0.15)); -#31185 = VECTOR('',#31186,1.); -#31186 = DIRECTION('',(1.,0.E+000)); -#31187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31188 = ORIENTED_EDGE('',*,*,#31189,.T.); -#31189 = EDGE_CURVE('',#31156,#30306,#31190,.T.); -#31190 = SURFACE_CURVE('',#31191,(#31196,#31202),.PCURVE_S1.); -#31191 = CIRCLE('',#31192,0.15); -#31192 = AXIS2_PLACEMENT_3D('',#31193,#31194,#31195); -#31193 = CARTESIAN_POINT('',(0.5,0.63,-0.475)); -#31194 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); -#31195 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); -#31196 = PCURVE('',#31166,#31197); -#31197 = DEFINITIONAL_REPRESENTATION('',(#31198),#31201); -#31198 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31199,#31200),.UNSPECIFIED., +#33565 = CARTESIAN_POINT('',(0.E+000,1.5)); +#33566 = CARTESIAN_POINT('',(0.E+000,1.85)); +#33567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33568 = PCURVE('',#33569,#33574); +#33569 = PLANE('',#33570); +#33570 = AXIS2_PLACEMENT_3D('',#33571,#33572,#33573); +#33571 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); +#33572 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33573 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33574 = DEFINITIONAL_REPRESENTATION('',(#33575),#33579); +#33575 = LINE('',#33576,#33577); +#33576 = CARTESIAN_POINT('',(2.,-0.15)); +#33577 = VECTOR('',#33578,1.); +#33578 = DIRECTION('',(1.,0.E+000)); +#33579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33580 = ORIENTED_EDGE('',*,*,#33581,.T.); +#33581 = EDGE_CURVE('',#33548,#32698,#33582,.T.); +#33582 = SURFACE_CURVE('',#33583,(#33588,#33594),.PCURVE_S1.); +#33583 = CIRCLE('',#33584,0.15); +#33584 = AXIS2_PLACEMENT_3D('',#33585,#33586,#33587); +#33585 = CARTESIAN_POINT('',(0.5,0.63,-0.475)); +#33586 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); +#33587 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); +#33588 = PCURVE('',#33558,#33589); +#33589 = DEFINITIONAL_REPRESENTATION('',(#33590),#33593); +#33590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33591,#33592),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31199 = CARTESIAN_POINT('',(0.E+000,1.5)); -#31200 = CARTESIAN_POINT('',(1.570796326795,1.5)); -#31201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33591 = CARTESIAN_POINT('',(0.E+000,1.5)); +#33592 = CARTESIAN_POINT('',(1.570796326795,1.5)); +#33593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31202 = PCURVE('',#30347,#31203); -#31203 = DEFINITIONAL_REPRESENTATION('',(#31204),#31207); -#31204 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31205,#31206),.UNSPECIFIED., +#33594 = PCURVE('',#32739,#33595); +#33595 = DEFINITIONAL_REPRESENTATION('',(#33596),#33599); +#33596 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33597,#33598),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31205 = CARTESIAN_POINT('',(0.E+000,1.5)); -#31206 = CARTESIAN_POINT('',(1.570796326795,1.5)); -#31207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31208 = ORIENTED_EDGE('',*,*,#31209,.F.); -#31209 = EDGE_CURVE('',#31210,#30306,#31212,.T.); -#31210 = VERTEX_POINT('',#31211); -#31211 = CARTESIAN_POINT('',(0.85,0.78,-0.475)); -#31212 = SURFACE_CURVE('',#31213,(#31217,#31223),.PCURVE_S1.); -#31213 = LINE('',#31214,#31215); -#31214 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); -#31215 = VECTOR('',#31216,1.); -#31216 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31217 = PCURVE('',#31166,#31218); -#31218 = DEFINITIONAL_REPRESENTATION('',(#31219),#31222); -#31219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31220,#31221),.UNSPECIFIED., +#33597 = CARTESIAN_POINT('',(0.E+000,1.5)); +#33598 = CARTESIAN_POINT('',(1.570796326795,1.5)); +#33599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33600 = ORIENTED_EDGE('',*,*,#33601,.F.); +#33601 = EDGE_CURVE('',#33602,#32698,#33604,.T.); +#33602 = VERTEX_POINT('',#33603); +#33603 = CARTESIAN_POINT('',(0.85,0.78,-0.475)); +#33604 = SURFACE_CURVE('',#33605,(#33609,#33615),.PCURVE_S1.); +#33605 = LINE('',#33606,#33607); +#33606 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); +#33607 = VECTOR('',#33608,1.); +#33608 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33609 = PCURVE('',#33558,#33610); +#33610 = DEFINITIONAL_REPRESENTATION('',(#33611),#33614); +#33611 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33612,#33613),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#31220 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#31221 = CARTESIAN_POINT('',(1.570796326795,1.5)); -#31222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31223 = PCURVE('',#30321,#31224); -#31224 = DEFINITIONAL_REPRESENTATION('',(#31225),#31229); -#31225 = LINE('',#31226,#31227); -#31226 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#31227 = VECTOR('',#31228,1.); -#31228 = DIRECTION('',(0.E+000,-1.)); -#31229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31230 = ORIENTED_EDGE('',*,*,#31231,.T.); -#31231 = EDGE_CURVE('',#31210,#31158,#31232,.T.); -#31232 = SURFACE_CURVE('',#31233,(#31238,#31244),.PCURVE_S1.); -#31233 = CIRCLE('',#31234,0.15); -#31234 = AXIS2_PLACEMENT_3D('',#31235,#31236,#31237); -#31235 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); -#31236 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31237 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31238 = PCURVE('',#31166,#31239); -#31239 = DEFINITIONAL_REPRESENTATION('',(#31240),#31243); -#31240 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31241,#31242),.UNSPECIFIED., +#33612 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#33613 = CARTESIAN_POINT('',(1.570796326795,1.5)); +#33614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33615 = PCURVE('',#32713,#33616); +#33616 = DEFINITIONAL_REPRESENTATION('',(#33617),#33621); +#33617 = LINE('',#33618,#33619); +#33618 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#33619 = VECTOR('',#33620,1.); +#33620 = DIRECTION('',(0.E+000,-1.)); +#33621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33622 = ORIENTED_EDGE('',*,*,#33623,.T.); +#33623 = EDGE_CURVE('',#33602,#33550,#33624,.T.); +#33624 = SURFACE_CURVE('',#33625,(#33630,#33636),.PCURVE_S1.); +#33625 = CIRCLE('',#33626,0.15); +#33626 = AXIS2_PLACEMENT_3D('',#33627,#33628,#33629); +#33627 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); +#33628 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33629 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33630 = PCURVE('',#33558,#33631); +#33631 = DEFINITIONAL_REPRESENTATION('',(#33632),#33635); +#33632 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33633,#33634),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31241 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#31242 = CARTESIAN_POINT('',(0.E+000,1.85)); -#31243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#33633 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#33634 = CARTESIAN_POINT('',(0.E+000,1.85)); +#33635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31244 = PCURVE('',#31245,#31250); -#31245 = SPHERICAL_SURFACE('',#31246,0.15); -#31246 = AXIS2_PLACEMENT_3D('',#31247,#31248,#31249); -#31247 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); -#31248 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31249 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31250 = DEFINITIONAL_REPRESENTATION('',(#31251),#31254); -#31251 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31252,#31253),.UNSPECIFIED., +#33636 = PCURVE('',#33637,#33642); +#33637 = SPHERICAL_SURFACE('',#33638,0.15); +#33638 = AXIS2_PLACEMENT_3D('',#33639,#33640,#33641); +#33639 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); +#33640 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33641 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33642 = DEFINITIONAL_REPRESENTATION('',(#33643),#33646); +#33643 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33644,#33645),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31252 = CARTESIAN_POINT('',(1.570796326795,1.570796326795)); -#31253 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#31254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31255 = ADVANCED_FACE('',(#31256),#31270,.F.); -#31256 = FACE_BOUND('',#31257,.T.); -#31257 = EDGE_LOOP('',(#31258,#31293,#31320,#31347)); -#31258 = ORIENTED_EDGE('',*,*,#31259,.F.); -#31259 = EDGE_CURVE('',#31260,#31262,#31264,.T.); -#31260 = VERTEX_POINT('',#31261); -#31261 = CARTESIAN_POINT('',(-0.5,0.E+000,0.475)); -#31262 = VERTEX_POINT('',#31263); -#31263 = CARTESIAN_POINT('',(-0.5,0.E+000,-0.475)); -#31264 = SURFACE_CURVE('',#31265,(#31269,#31281),.PCURVE_S1.); -#31265 = LINE('',#31266,#31267); -#31266 = CARTESIAN_POINT('',(-0.5,0.E+000,0.625)); -#31267 = VECTOR('',#31268,1.); -#31268 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31269 = PCURVE('',#31270,#31275); -#31270 = PLANE('',#31271); -#31271 = AXIS2_PLACEMENT_3D('',#31272,#31273,#31274); -#31272 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); -#31273 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31274 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31275 = DEFINITIONAL_REPRESENTATION('',(#31276),#31280); -#31276 = LINE('',#31277,#31278); -#31277 = CARTESIAN_POINT('',(0.E+000,0.5)); -#31278 = VECTOR('',#31279,1.); -#31279 = DIRECTION('',(-1.,0.E+000)); -#31280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31281 = PCURVE('',#31282,#31287); -#31282 = PLANE('',#31283); -#31283 = AXIS2_PLACEMENT_3D('',#31284,#31285,#31286); -#31284 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); -#31285 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31286 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31287 = DEFINITIONAL_REPRESENTATION('',(#31288),#31292); -#31288 = LINE('',#31289,#31290); -#31289 = CARTESIAN_POINT('',(0.E+000,0.5)); -#31290 = VECTOR('',#31291,1.); -#31291 = DIRECTION('',(-1.,0.E+000)); -#31292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31293 = ORIENTED_EDGE('',*,*,#31294,.T.); -#31294 = EDGE_CURVE('',#31260,#31295,#31297,.T.); -#31295 = VERTEX_POINT('',#31296); -#31296 = CARTESIAN_POINT('',(-0.85,0.E+000,0.475)); -#31297 = SURFACE_CURVE('',#31298,(#31302,#31309),.PCURVE_S1.); -#31298 = LINE('',#31299,#31300); -#31299 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); -#31300 = VECTOR('',#31301,1.); -#31301 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31302 = PCURVE('',#31270,#31303); -#31303 = DEFINITIONAL_REPRESENTATION('',(#31304),#31308); -#31304 = LINE('',#31305,#31306); -#31305 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#31306 = VECTOR('',#31307,1.); -#31307 = DIRECTION('',(0.E+000,-1.)); -#31308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31309 = PCURVE('',#31310,#31315); -#31310 = CYLINDRICAL_SURFACE('',#31311,0.15); -#31311 = AXIS2_PLACEMENT_3D('',#31312,#31313,#31314); -#31312 = CARTESIAN_POINT('',(-1.,0.15,0.475)); -#31313 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31314 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31315 = DEFINITIONAL_REPRESENTATION('',(#31316),#31319); -#31316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31317,#31318),.UNSPECIFIED., +#33644 = CARTESIAN_POINT('',(1.570796326795,1.570796326795)); +#33645 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#33646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33647 = ADVANCED_FACE('',(#33648),#33662,.F.); +#33648 = FACE_BOUND('',#33649,.T.); +#33649 = EDGE_LOOP('',(#33650,#33685,#33712,#33739)); +#33650 = ORIENTED_EDGE('',*,*,#33651,.F.); +#33651 = EDGE_CURVE('',#33652,#33654,#33656,.T.); +#33652 = VERTEX_POINT('',#33653); +#33653 = CARTESIAN_POINT('',(-0.5,0.E+000,0.475)); +#33654 = VERTEX_POINT('',#33655); +#33655 = CARTESIAN_POINT('',(-0.5,0.E+000,-0.475)); +#33656 = SURFACE_CURVE('',#33657,(#33661,#33673),.PCURVE_S1.); +#33657 = LINE('',#33658,#33659); +#33658 = CARTESIAN_POINT('',(-0.5,0.E+000,0.625)); +#33659 = VECTOR('',#33660,1.); +#33660 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33661 = PCURVE('',#33662,#33667); +#33662 = PLANE('',#33663); +#33663 = AXIS2_PLACEMENT_3D('',#33664,#33665,#33666); +#33664 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); +#33665 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33666 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33667 = DEFINITIONAL_REPRESENTATION('',(#33668),#33672); +#33668 = LINE('',#33669,#33670); +#33669 = CARTESIAN_POINT('',(0.E+000,0.5)); +#33670 = VECTOR('',#33671,1.); +#33671 = DIRECTION('',(-1.,0.E+000)); +#33672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33673 = PCURVE('',#33674,#33679); +#33674 = PLANE('',#33675); +#33675 = AXIS2_PLACEMENT_3D('',#33676,#33677,#33678); +#33676 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); +#33677 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33678 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33679 = DEFINITIONAL_REPRESENTATION('',(#33680),#33684); +#33680 = LINE('',#33681,#33682); +#33681 = CARTESIAN_POINT('',(0.E+000,0.5)); +#33682 = VECTOR('',#33683,1.); +#33683 = DIRECTION('',(-1.,0.E+000)); +#33684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33685 = ORIENTED_EDGE('',*,*,#33686,.T.); +#33686 = EDGE_CURVE('',#33652,#33687,#33689,.T.); +#33687 = VERTEX_POINT('',#33688); +#33688 = CARTESIAN_POINT('',(-0.85,0.E+000,0.475)); +#33689 = SURFACE_CURVE('',#33690,(#33694,#33701),.PCURVE_S1.); +#33690 = LINE('',#33691,#33692); +#33691 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); +#33692 = VECTOR('',#33693,1.); +#33693 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33694 = PCURVE('',#33662,#33695); +#33695 = DEFINITIONAL_REPRESENTATION('',(#33696),#33700); +#33696 = LINE('',#33697,#33698); +#33697 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#33698 = VECTOR('',#33699,1.); +#33699 = DIRECTION('',(0.E+000,-1.)); +#33700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33701 = PCURVE('',#33702,#33707); +#33702 = CYLINDRICAL_SURFACE('',#33703,0.15); +#33703 = AXIS2_PLACEMENT_3D('',#33704,#33705,#33706); +#33704 = CARTESIAN_POINT('',(-1.,0.15,0.475)); +#33705 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33706 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33707 = DEFINITIONAL_REPRESENTATION('',(#33708),#33711); +#33708 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33709,#33710),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31317 = CARTESIAN_POINT('',(4.712388980385,0.5)); -#31318 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#31319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31320 = ORIENTED_EDGE('',*,*,#31321,.T.); -#31321 = EDGE_CURVE('',#31295,#31322,#31324,.T.); -#31322 = VERTEX_POINT('',#31323); -#31323 = CARTESIAN_POINT('',(-0.85,0.E+000,-0.475)); -#31324 = SURFACE_CURVE('',#31325,(#31329,#31336),.PCURVE_S1.); -#31325 = LINE('',#31326,#31327); -#31326 = CARTESIAN_POINT('',(-0.85,0.E+000,0.625)); -#31327 = VECTOR('',#31328,1.); -#31328 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31329 = PCURVE('',#31270,#31330); -#31330 = DEFINITIONAL_REPRESENTATION('',(#31331),#31335); -#31331 = LINE('',#31332,#31333); -#31332 = CARTESIAN_POINT('',(0.E+000,0.15)); -#31333 = VECTOR('',#31334,1.); -#31334 = DIRECTION('',(-1.,0.E+000)); -#31335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31336 = PCURVE('',#31337,#31342); -#31337 = CYLINDRICAL_SURFACE('',#31338,0.15); -#31338 = AXIS2_PLACEMENT_3D('',#31339,#31340,#31341); -#31339 = CARTESIAN_POINT('',(-0.85,0.15,-0.625)); -#31340 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31341 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31342 = DEFINITIONAL_REPRESENTATION('',(#31343),#31346); -#31343 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31344,#31345),.UNSPECIFIED., +#33709 = CARTESIAN_POINT('',(4.712388980385,0.5)); +#33710 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#33711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33712 = ORIENTED_EDGE('',*,*,#33713,.T.); +#33713 = EDGE_CURVE('',#33687,#33714,#33716,.T.); +#33714 = VERTEX_POINT('',#33715); +#33715 = CARTESIAN_POINT('',(-0.85,0.E+000,-0.475)); +#33716 = SURFACE_CURVE('',#33717,(#33721,#33728),.PCURVE_S1.); +#33717 = LINE('',#33718,#33719); +#33718 = CARTESIAN_POINT('',(-0.85,0.E+000,0.625)); +#33719 = VECTOR('',#33720,1.); +#33720 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33721 = PCURVE('',#33662,#33722); +#33722 = DEFINITIONAL_REPRESENTATION('',(#33723),#33727); +#33723 = LINE('',#33724,#33725); +#33724 = CARTESIAN_POINT('',(0.E+000,0.15)); +#33725 = VECTOR('',#33726,1.); +#33726 = DIRECTION('',(-1.,0.E+000)); +#33727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33728 = PCURVE('',#33729,#33734); +#33729 = CYLINDRICAL_SURFACE('',#33730,0.15); +#33730 = AXIS2_PLACEMENT_3D('',#33731,#33732,#33733); +#33731 = CARTESIAN_POINT('',(-0.85,0.15,-0.625)); +#33732 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33733 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33734 = DEFINITIONAL_REPRESENTATION('',(#33735),#33738); +#33735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33736,#33737),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,1.1),.PIECEWISE_BEZIER_KNOTS.); -#31344 = CARTESIAN_POINT('',(4.712388980385,1.1)); -#31345 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#31346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31347 = ORIENTED_EDGE('',*,*,#31348,.T.); -#31348 = EDGE_CURVE('',#31322,#31262,#31349,.T.); -#31349 = SURFACE_CURVE('',#31350,(#31354,#31361),.PCURVE_S1.); -#31350 = LINE('',#31351,#31352); -#31351 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); -#31352 = VECTOR('',#31353,1.); -#31353 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31354 = PCURVE('',#31270,#31355); -#31355 = DEFINITIONAL_REPRESENTATION('',(#31356),#31360); -#31356 = LINE('',#31357,#31358); -#31357 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#31358 = VECTOR('',#31359,1.); -#31359 = DIRECTION('',(0.E+000,1.)); -#31360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31361 = PCURVE('',#31362,#31367); -#31362 = CYLINDRICAL_SURFACE('',#31363,0.15); -#31363 = AXIS2_PLACEMENT_3D('',#31364,#31365,#31366); -#31364 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); -#31365 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31366 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31367 = DEFINITIONAL_REPRESENTATION('',(#31368),#31371); -#31368 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31369,#31370),.UNSPECIFIED., +#33736 = CARTESIAN_POINT('',(4.712388980385,1.1)); +#33737 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#33738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33739 = ORIENTED_EDGE('',*,*,#33740,.T.); +#33740 = EDGE_CURVE('',#33714,#33654,#33741,.T.); +#33741 = SURFACE_CURVE('',#33742,(#33746,#33753),.PCURVE_S1.); +#33742 = LINE('',#33743,#33744); +#33743 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); +#33744 = VECTOR('',#33745,1.); +#33745 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33746 = PCURVE('',#33662,#33747); +#33747 = DEFINITIONAL_REPRESENTATION('',(#33748),#33752); +#33748 = LINE('',#33749,#33750); +#33749 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#33750 = VECTOR('',#33751,1.); +#33751 = DIRECTION('',(0.E+000,1.)); +#33752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33753 = PCURVE('',#33754,#33759); +#33754 = CYLINDRICAL_SURFACE('',#33755,0.15); +#33755 = AXIS2_PLACEMENT_3D('',#33756,#33757,#33758); +#33756 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); +#33757 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33758 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33759 = DEFINITIONAL_REPRESENTATION('',(#33760),#33763); +#33760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33761,#33762),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.5),.PIECEWISE_BEZIER_KNOTS.); -#31369 = CARTESIAN_POINT('',(4.712388980385,-0.15)); -#31370 = CARTESIAN_POINT('',(4.712388980385,-0.5)); -#31371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31372 = ADVANCED_FACE('',(#31373),#31387,.F.); -#31373 = FACE_BOUND('',#31374,.T.); -#31374 = EDGE_LOOP('',(#31375,#31405,#31432,#31459)); -#31375 = ORIENTED_EDGE('',*,*,#31376,.F.); -#31376 = EDGE_CURVE('',#31377,#31379,#31381,.T.); -#31377 = VERTEX_POINT('',#31378); -#31378 = CARTESIAN_POINT('',(0.5,0.E+000,-0.475)); -#31379 = VERTEX_POINT('',#31380); -#31380 = CARTESIAN_POINT('',(0.5,0.E+000,0.475)); -#31381 = SURFACE_CURVE('',#31382,(#31386,#31398),.PCURVE_S1.); -#31382 = LINE('',#31383,#31384); -#31383 = CARTESIAN_POINT('',(0.5,0.E+000,0.625)); -#31384 = VECTOR('',#31385,1.); -#31385 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31386 = PCURVE('',#31387,#31392); -#31387 = PLANE('',#31388); -#31388 = AXIS2_PLACEMENT_3D('',#31389,#31390,#31391); -#31389 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); -#31390 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31391 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31392 = DEFINITIONAL_REPRESENTATION('',(#31393),#31397); -#31393 = LINE('',#31394,#31395); -#31394 = CARTESIAN_POINT('',(0.E+000,1.5)); -#31395 = VECTOR('',#31396,1.); -#31396 = DIRECTION('',(1.,0.E+000)); -#31397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31398 = PCURVE('',#31282,#31399); -#31399 = DEFINITIONAL_REPRESENTATION('',(#31400),#31404); -#31400 = LINE('',#31401,#31402); -#31401 = CARTESIAN_POINT('',(0.E+000,1.5)); -#31402 = VECTOR('',#31403,1.); -#31403 = DIRECTION('',(1.,0.E+000)); -#31404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31405 = ORIENTED_EDGE('',*,*,#31406,.T.); -#31406 = EDGE_CURVE('',#31377,#31407,#31409,.T.); -#31407 = VERTEX_POINT('',#31408); -#31408 = CARTESIAN_POINT('',(0.85,0.E+000,-0.475)); -#31409 = SURFACE_CURVE('',#31410,(#31414,#31421),.PCURVE_S1.); -#31410 = LINE('',#31411,#31412); -#31411 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); -#31412 = VECTOR('',#31413,1.); -#31413 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31414 = PCURVE('',#31387,#31415); -#31415 = DEFINITIONAL_REPRESENTATION('',(#31416),#31420); -#31416 = LINE('',#31417,#31418); -#31417 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#31418 = VECTOR('',#31419,1.); -#31419 = DIRECTION('',(0.E+000,1.)); -#31420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31421 = PCURVE('',#31422,#31427); -#31422 = CYLINDRICAL_SURFACE('',#31423,0.15); -#31423 = AXIS2_PLACEMENT_3D('',#31424,#31425,#31426); -#31424 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); -#31425 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31426 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31427 = DEFINITIONAL_REPRESENTATION('',(#31428),#31431); -#31428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31429,#31430),.UNSPECIFIED., +#33761 = CARTESIAN_POINT('',(4.712388980385,-0.15)); +#33762 = CARTESIAN_POINT('',(4.712388980385,-0.5)); +#33763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33764 = ADVANCED_FACE('',(#33765),#33779,.F.); +#33765 = FACE_BOUND('',#33766,.T.); +#33766 = EDGE_LOOP('',(#33767,#33797,#33824,#33851)); +#33767 = ORIENTED_EDGE('',*,*,#33768,.F.); +#33768 = EDGE_CURVE('',#33769,#33771,#33773,.T.); +#33769 = VERTEX_POINT('',#33770); +#33770 = CARTESIAN_POINT('',(0.5,0.E+000,-0.475)); +#33771 = VERTEX_POINT('',#33772); +#33772 = CARTESIAN_POINT('',(0.5,0.E+000,0.475)); +#33773 = SURFACE_CURVE('',#33774,(#33778,#33790),.PCURVE_S1.); +#33774 = LINE('',#33775,#33776); +#33775 = CARTESIAN_POINT('',(0.5,0.E+000,0.625)); +#33776 = VECTOR('',#33777,1.); +#33777 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33778 = PCURVE('',#33779,#33784); +#33779 = PLANE('',#33780); +#33780 = AXIS2_PLACEMENT_3D('',#33781,#33782,#33783); +#33781 = CARTESIAN_POINT('',(-1.,0.E+000,0.625)); +#33782 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33783 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33784 = DEFINITIONAL_REPRESENTATION('',(#33785),#33789); +#33785 = LINE('',#33786,#33787); +#33786 = CARTESIAN_POINT('',(0.E+000,1.5)); +#33787 = VECTOR('',#33788,1.); +#33788 = DIRECTION('',(1.,0.E+000)); +#33789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33790 = PCURVE('',#33674,#33791); +#33791 = DEFINITIONAL_REPRESENTATION('',(#33792),#33796); +#33792 = LINE('',#33793,#33794); +#33793 = CARTESIAN_POINT('',(0.E+000,1.5)); +#33794 = VECTOR('',#33795,1.); +#33795 = DIRECTION('',(1.,0.E+000)); +#33796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33797 = ORIENTED_EDGE('',*,*,#33798,.T.); +#33798 = EDGE_CURVE('',#33769,#33799,#33801,.T.); +#33799 = VERTEX_POINT('',#33800); +#33800 = CARTESIAN_POINT('',(0.85,0.E+000,-0.475)); +#33801 = SURFACE_CURVE('',#33802,(#33806,#33813),.PCURVE_S1.); +#33802 = LINE('',#33803,#33804); +#33803 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); +#33804 = VECTOR('',#33805,1.); +#33805 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33806 = PCURVE('',#33779,#33807); +#33807 = DEFINITIONAL_REPRESENTATION('',(#33808),#33812); +#33808 = LINE('',#33809,#33810); +#33809 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#33810 = VECTOR('',#33811,1.); +#33811 = DIRECTION('',(0.E+000,1.)); +#33812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33813 = PCURVE('',#33814,#33819); +#33814 = CYLINDRICAL_SURFACE('',#33815,0.15); +#33815 = AXIS2_PLACEMENT_3D('',#33816,#33817,#33818); +#33816 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); +#33817 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33818 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33819 = DEFINITIONAL_REPRESENTATION('',(#33820),#33823); +#33820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33821,#33822),.UNSPECIFIED., .F.,.F.,(2,2),(1.5,1.85),.PIECEWISE_BEZIER_KNOTS.); -#31429 = CARTESIAN_POINT('',(4.712388980385,-1.5)); -#31430 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#31431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31432 = ORIENTED_EDGE('',*,*,#31433,.T.); -#31433 = EDGE_CURVE('',#31407,#31434,#31436,.T.); -#31434 = VERTEX_POINT('',#31435); -#31435 = CARTESIAN_POINT('',(0.85,0.E+000,0.475)); -#31436 = SURFACE_CURVE('',#31437,(#31441,#31448),.PCURVE_S1.); -#31437 = LINE('',#31438,#31439); -#31438 = CARTESIAN_POINT('',(0.85,0.E+000,0.625)); -#31439 = VECTOR('',#31440,1.); -#31440 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31441 = PCURVE('',#31387,#31442); -#31442 = DEFINITIONAL_REPRESENTATION('',(#31443),#31447); -#31443 = LINE('',#31444,#31445); -#31444 = CARTESIAN_POINT('',(0.E+000,1.85)); -#31445 = VECTOR('',#31446,1.); -#31446 = DIRECTION('',(1.,0.E+000)); -#31447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31448 = PCURVE('',#31449,#31454); -#31449 = CYLINDRICAL_SURFACE('',#31450,0.15); -#31450 = AXIS2_PLACEMENT_3D('',#31451,#31452,#31453); -#31451 = CARTESIAN_POINT('',(0.85,0.15,-0.625)); -#31452 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31453 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31454 = DEFINITIONAL_REPRESENTATION('',(#31455),#31458); -#31455 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31456,#31457),.UNSPECIFIED., +#33821 = CARTESIAN_POINT('',(4.712388980385,-1.5)); +#33822 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#33823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33824 = ORIENTED_EDGE('',*,*,#33825,.T.); +#33825 = EDGE_CURVE('',#33799,#33826,#33828,.T.); +#33826 = VERTEX_POINT('',#33827); +#33827 = CARTESIAN_POINT('',(0.85,0.E+000,0.475)); +#33828 = SURFACE_CURVE('',#33829,(#33833,#33840),.PCURVE_S1.); +#33829 = LINE('',#33830,#33831); +#33830 = CARTESIAN_POINT('',(0.85,0.E+000,0.625)); +#33831 = VECTOR('',#33832,1.); +#33832 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33833 = PCURVE('',#33779,#33834); +#33834 = DEFINITIONAL_REPRESENTATION('',(#33835),#33839); +#33835 = LINE('',#33836,#33837); +#33836 = CARTESIAN_POINT('',(0.E+000,1.85)); +#33837 = VECTOR('',#33838,1.); +#33838 = DIRECTION('',(1.,0.E+000)); +#33839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33840 = PCURVE('',#33841,#33846); +#33841 = CYLINDRICAL_SURFACE('',#33842,0.15); +#33842 = AXIS2_PLACEMENT_3D('',#33843,#33844,#33845); +#33843 = CARTESIAN_POINT('',(0.85,0.15,-0.625)); +#33844 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33845 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33846 = DEFINITIONAL_REPRESENTATION('',(#33847),#33850); +#33847 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33848,#33849),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31456 = CARTESIAN_POINT('',(4.712388980385,-0.15)); -#31457 = CARTESIAN_POINT('',(4.712388980385,-1.1)); -#31458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31459 = ORIENTED_EDGE('',*,*,#31460,.T.); -#31460 = EDGE_CURVE('',#31434,#31379,#31461,.T.); -#31461 = SURFACE_CURVE('',#31462,(#31466,#31473),.PCURVE_S1.); -#31462 = LINE('',#31463,#31464); -#31463 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); -#31464 = VECTOR('',#31465,1.); -#31465 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31466 = PCURVE('',#31387,#31467); -#31467 = DEFINITIONAL_REPRESENTATION('',(#31468),#31472); -#31468 = LINE('',#31469,#31470); -#31469 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#31470 = VECTOR('',#31471,1.); -#31471 = DIRECTION('',(0.E+000,-1.)); -#31472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31473 = PCURVE('',#31474,#31479); -#31474 = CYLINDRICAL_SURFACE('',#31475,0.15); -#31475 = AXIS2_PLACEMENT_3D('',#31476,#31477,#31478); -#31476 = CARTESIAN_POINT('',(-1.,0.15,0.475)); -#31477 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31478 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31479 = DEFINITIONAL_REPRESENTATION('',(#31480),#31483); -#31480 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31481,#31482),.UNSPECIFIED., +#33848 = CARTESIAN_POINT('',(4.712388980385,-0.15)); +#33849 = CARTESIAN_POINT('',(4.712388980385,-1.1)); +#33850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33851 = ORIENTED_EDGE('',*,*,#33852,.T.); +#33852 = EDGE_CURVE('',#33826,#33771,#33853,.T.); +#33853 = SURFACE_CURVE('',#33854,(#33858,#33865),.PCURVE_S1.); +#33854 = LINE('',#33855,#33856); +#33855 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); +#33856 = VECTOR('',#33857,1.); +#33857 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33858 = PCURVE('',#33779,#33859); +#33859 = DEFINITIONAL_REPRESENTATION('',(#33860),#33864); +#33860 = LINE('',#33861,#33862); +#33861 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#33862 = VECTOR('',#33863,1.); +#33863 = DIRECTION('',(0.E+000,-1.)); +#33864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33865 = PCURVE('',#33866,#33871); +#33866 = CYLINDRICAL_SURFACE('',#33867,0.15); +#33867 = AXIS2_PLACEMENT_3D('',#33868,#33869,#33870); +#33868 = CARTESIAN_POINT('',(-1.,0.15,0.475)); +#33869 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33870 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33871 = DEFINITIONAL_REPRESENTATION('',(#33872),#33875); +#33872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33873,#33874),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#31481 = CARTESIAN_POINT('',(4.712388980385,1.85)); -#31482 = CARTESIAN_POINT('',(4.712388980385,1.5)); -#31483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31484 = ADVANCED_FACE('',(#31485),#31115,.F.); -#31485 = FACE_BOUND('',#31486,.T.); -#31486 = EDGE_LOOP('',(#31487,#31515,#31537,#31562)); -#31487 = ORIENTED_EDGE('',*,*,#31488,.F.); -#31488 = EDGE_CURVE('',#31489,#31079,#31491,.T.); -#31489 = VERTEX_POINT('',#31490); -#31490 = CARTESIAN_POINT('',(-0.5,0.15,-0.625)); -#31491 = SURFACE_CURVE('',#31492,(#31496,#31503),.PCURVE_S1.); -#31492 = LINE('',#31493,#31494); -#31493 = CARTESIAN_POINT('',(-0.5,0.78,-0.625)); -#31494 = VECTOR('',#31495,1.); -#31495 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); -#31496 = PCURVE('',#31115,#31497); -#31497 = DEFINITIONAL_REPRESENTATION('',(#31498),#31502); -#31498 = LINE('',#31499,#31500); -#31499 = CARTESIAN_POINT('',(0.5,1.110223024625E-016)); -#31500 = VECTOR('',#31501,1.); -#31501 = DIRECTION('',(-1.390002785238E-016,1.)); -#31502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31503 = PCURVE('',#31504,#31509); -#31504 = PLANE('',#31505); -#31505 = AXIS2_PLACEMENT_3D('',#31506,#31507,#31508); -#31506 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); -#31507 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31508 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31509 = DEFINITIONAL_REPRESENTATION('',(#31510),#31514); -#31510 = LINE('',#31511,#31512); -#31511 = CARTESIAN_POINT('',(0.5,1.110223024625E-016)); -#31512 = VECTOR('',#31513,1.); -#31513 = DIRECTION('',(-1.390002785238E-016,1.)); -#31514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31515 = ORIENTED_EDGE('',*,*,#31516,.T.); -#31516 = EDGE_CURVE('',#31489,#31517,#31519,.T.); -#31517 = VERTEX_POINT('',#31518); -#31518 = CARTESIAN_POINT('',(-0.85,0.15,-0.625)); -#31519 = SURFACE_CURVE('',#31520,(#31524,#31531),.PCURVE_S1.); -#31520 = LINE('',#31521,#31522); -#31521 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); -#31522 = VECTOR('',#31523,1.); -#31523 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31524 = PCURVE('',#31115,#31525); -#31525 = DEFINITIONAL_REPRESENTATION('',(#31526),#31530); -#31526 = LINE('',#31527,#31528); -#31527 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#31528 = VECTOR('',#31529,1.); -#31529 = DIRECTION('',(-1.,0.E+000)); -#31530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31531 = PCURVE('',#31362,#31532); -#31532 = DEFINITIONAL_REPRESENTATION('',(#31533),#31536); -#31533 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31534,#31535),.UNSPECIFIED., +#33873 = CARTESIAN_POINT('',(4.712388980385,1.85)); +#33874 = CARTESIAN_POINT('',(4.712388980385,1.5)); +#33875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33876 = ADVANCED_FACE('',(#33877),#33507,.F.); +#33877 = FACE_BOUND('',#33878,.T.); +#33878 = EDGE_LOOP('',(#33879,#33907,#33929,#33954)); +#33879 = ORIENTED_EDGE('',*,*,#33880,.F.); +#33880 = EDGE_CURVE('',#33881,#33471,#33883,.T.); +#33881 = VERTEX_POINT('',#33882); +#33882 = CARTESIAN_POINT('',(-0.5,0.15,-0.625)); +#33883 = SURFACE_CURVE('',#33884,(#33888,#33895),.PCURVE_S1.); +#33884 = LINE('',#33885,#33886); +#33885 = CARTESIAN_POINT('',(-0.5,0.78,-0.625)); +#33886 = VECTOR('',#33887,1.); +#33887 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); +#33888 = PCURVE('',#33507,#33889); +#33889 = DEFINITIONAL_REPRESENTATION('',(#33890),#33894); +#33890 = LINE('',#33891,#33892); +#33891 = CARTESIAN_POINT('',(0.5,1.110223024625E-016)); +#33892 = VECTOR('',#33893,1.); +#33893 = DIRECTION('',(-1.390002785238E-016,1.)); +#33894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33895 = PCURVE('',#33896,#33901); +#33896 = PLANE('',#33897); +#33897 = AXIS2_PLACEMENT_3D('',#33898,#33899,#33900); +#33898 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); +#33899 = DIRECTION('',(0.E+000,0.E+000,1.)); +#33900 = DIRECTION('',(1.,0.E+000,0.E+000)); +#33901 = DEFINITIONAL_REPRESENTATION('',(#33902),#33906); +#33902 = LINE('',#33903,#33904); +#33903 = CARTESIAN_POINT('',(0.5,1.110223024625E-016)); +#33904 = VECTOR('',#33905,1.); +#33905 = DIRECTION('',(-1.390002785238E-016,1.)); +#33906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33907 = ORIENTED_EDGE('',*,*,#33908,.T.); +#33908 = EDGE_CURVE('',#33881,#33909,#33911,.T.); +#33909 = VERTEX_POINT('',#33910); +#33910 = CARTESIAN_POINT('',(-0.85,0.15,-0.625)); +#33911 = SURFACE_CURVE('',#33912,(#33916,#33923),.PCURVE_S1.); +#33912 = LINE('',#33913,#33914); +#33913 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); +#33914 = VECTOR('',#33915,1.); +#33915 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#33916 = PCURVE('',#33507,#33917); +#33917 = DEFINITIONAL_REPRESENTATION('',(#33918),#33922); +#33918 = LINE('',#33919,#33920); +#33919 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#33920 = VECTOR('',#33921,1.); +#33921 = DIRECTION('',(-1.,0.E+000)); +#33922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33923 = PCURVE('',#33754,#33924); +#33924 = DEFINITIONAL_REPRESENTATION('',(#33925),#33928); +#33925 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33926,#33927),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31534 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#31535 = CARTESIAN_POINT('',(3.14159265359,-0.15)); -#31536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31537 = ORIENTED_EDGE('',*,*,#31538,.T.); -#31538 = EDGE_CURVE('',#31517,#31101,#31539,.T.); -#31539 = SURFACE_CURVE('',#31540,(#31544,#31551),.PCURVE_S1.); -#31540 = LINE('',#31541,#31542); -#31541 = CARTESIAN_POINT('',(-0.85,0.78,-0.625)); -#31542 = VECTOR('',#31543,1.); -#31543 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31544 = PCURVE('',#31115,#31545); -#31545 = DEFINITIONAL_REPRESENTATION('',(#31546),#31550); -#31546 = LINE('',#31547,#31548); -#31547 = CARTESIAN_POINT('',(0.15,0.E+000)); -#31548 = VECTOR('',#31549,1.); -#31549 = DIRECTION('',(0.E+000,1.)); -#31550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31551 = PCURVE('',#31552,#31557); -#31552 = CYLINDRICAL_SURFACE('',#31553,0.15); -#31553 = AXIS2_PLACEMENT_3D('',#31554,#31555,#31556); -#31554 = CARTESIAN_POINT('',(-0.85,0.78,-0.475)); -#31555 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#31556 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31557 = DEFINITIONAL_REPRESENTATION('',(#31558),#31561); -#31558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31559,#31560),.UNSPECIFIED., +#33926 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#33927 = CARTESIAN_POINT('',(3.14159265359,-0.15)); +#33928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33929 = ORIENTED_EDGE('',*,*,#33930,.T.); +#33930 = EDGE_CURVE('',#33909,#33493,#33931,.T.); +#33931 = SURFACE_CURVE('',#33932,(#33936,#33943),.PCURVE_S1.); +#33932 = LINE('',#33933,#33934); +#33933 = CARTESIAN_POINT('',(-0.85,0.78,-0.625)); +#33934 = VECTOR('',#33935,1.); +#33935 = DIRECTION('',(0.E+000,1.,0.E+000)); +#33936 = PCURVE('',#33507,#33937); +#33937 = DEFINITIONAL_REPRESENTATION('',(#33938),#33942); +#33938 = LINE('',#33939,#33940); +#33939 = CARTESIAN_POINT('',(0.15,0.E+000)); +#33940 = VECTOR('',#33941,1.); +#33941 = DIRECTION('',(0.E+000,1.)); +#33942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33943 = PCURVE('',#33944,#33949); +#33944 = CYLINDRICAL_SURFACE('',#33945,0.15); +#33945 = AXIS2_PLACEMENT_3D('',#33946,#33947,#33948); +#33946 = CARTESIAN_POINT('',(-0.85,0.78,-0.475)); +#33947 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#33948 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#33949 = DEFINITIONAL_REPRESENTATION('',(#33950),#33953); +#33950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33951,#33952),.UNSPECIFIED., .F.,.F.,(2,2),(-0.63,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31559 = CARTESIAN_POINT('',(6.28318530718,0.63)); -#31560 = CARTESIAN_POINT('',(6.28318530718,0.15)); -#31561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31562 = ORIENTED_EDGE('',*,*,#31100,.T.); -#31563 = ADVANCED_FACE('',(#31564),#31177,.F.); -#31564 = FACE_BOUND('',#31565,.T.); -#31565 = EDGE_LOOP('',(#31566,#31589,#31590,#31617)); -#31566 = ORIENTED_EDGE('',*,*,#31567,.F.); -#31567 = EDGE_CURVE('',#31156,#31568,#31570,.T.); -#31568 = VERTEX_POINT('',#31569); -#31569 = CARTESIAN_POINT('',(0.5,0.15,-0.625)); -#31570 = SURFACE_CURVE('',#31571,(#31575,#31582),.PCURVE_S1.); -#31571 = LINE('',#31572,#31573); -#31572 = CARTESIAN_POINT('',(0.5,0.78,-0.625)); -#31573 = VECTOR('',#31574,1.); -#31574 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); -#31575 = PCURVE('',#31177,#31576); -#31576 = DEFINITIONAL_REPRESENTATION('',(#31577),#31581); -#31577 = LINE('',#31578,#31579); -#31578 = CARTESIAN_POINT('',(1.5,-2.22044604925E-016)); -#31579 = VECTOR('',#31580,1.); -#31580 = DIRECTION('',(-1.390002785238E-016,-1.)); -#31581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31582 = PCURVE('',#31504,#31583); -#31583 = DEFINITIONAL_REPRESENTATION('',(#31584),#31588); -#31584 = LINE('',#31585,#31586); -#31585 = CARTESIAN_POINT('',(1.5,-2.22044604925E-016)); -#31586 = VECTOR('',#31587,1.); -#31587 = DIRECTION('',(-1.390002785238E-016,-1.)); -#31588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31589 = ORIENTED_EDGE('',*,*,#31155,.T.); -#31590 = ORIENTED_EDGE('',*,*,#31591,.T.); -#31591 = EDGE_CURVE('',#31158,#31592,#31594,.T.); -#31592 = VERTEX_POINT('',#31593); -#31593 = CARTESIAN_POINT('',(0.85,0.15,-0.625)); -#31594 = SURFACE_CURVE('',#31595,(#31599,#31606),.PCURVE_S1.); -#31595 = LINE('',#31596,#31597); -#31596 = CARTESIAN_POINT('',(0.85,0.78,-0.625)); -#31597 = VECTOR('',#31598,1.); -#31598 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#31599 = PCURVE('',#31177,#31600); -#31600 = DEFINITIONAL_REPRESENTATION('',(#31601),#31605); -#31601 = LINE('',#31602,#31603); -#31602 = CARTESIAN_POINT('',(1.85,0.E+000)); -#31603 = VECTOR('',#31604,1.); -#31604 = DIRECTION('',(0.E+000,-1.)); -#31605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31606 = PCURVE('',#31607,#31612); -#31607 = CYLINDRICAL_SURFACE('',#31608,0.15); -#31608 = AXIS2_PLACEMENT_3D('',#31609,#31610,#31611); -#31609 = CARTESIAN_POINT('',(0.85,0.78,-0.475)); -#31610 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#31611 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31612 = DEFINITIONAL_REPRESENTATION('',(#31613),#31616); -#31613 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31614,#31615),.UNSPECIFIED., +#33951 = CARTESIAN_POINT('',(6.28318530718,0.63)); +#33952 = CARTESIAN_POINT('',(6.28318530718,0.15)); +#33953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33954 = ORIENTED_EDGE('',*,*,#33492,.T.); +#33955 = ADVANCED_FACE('',(#33956),#33569,.F.); +#33956 = FACE_BOUND('',#33957,.T.); +#33957 = EDGE_LOOP('',(#33958,#33981,#33982,#34009)); +#33958 = ORIENTED_EDGE('',*,*,#33959,.F.); +#33959 = EDGE_CURVE('',#33548,#33960,#33962,.T.); +#33960 = VERTEX_POINT('',#33961); +#33961 = CARTESIAN_POINT('',(0.5,0.15,-0.625)); +#33962 = SURFACE_CURVE('',#33963,(#33967,#33974),.PCURVE_S1.); +#33963 = LINE('',#33964,#33965); +#33964 = CARTESIAN_POINT('',(0.5,0.78,-0.625)); +#33965 = VECTOR('',#33966,1.); +#33966 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); +#33967 = PCURVE('',#33569,#33968); +#33968 = DEFINITIONAL_REPRESENTATION('',(#33969),#33973); +#33969 = LINE('',#33970,#33971); +#33970 = CARTESIAN_POINT('',(1.5,-2.22044604925E-016)); +#33971 = VECTOR('',#33972,1.); +#33972 = DIRECTION('',(-1.390002785238E-016,-1.)); +#33973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33974 = PCURVE('',#33896,#33975); +#33975 = DEFINITIONAL_REPRESENTATION('',(#33976),#33980); +#33976 = LINE('',#33977,#33978); +#33977 = CARTESIAN_POINT('',(1.5,-2.22044604925E-016)); +#33978 = VECTOR('',#33979,1.); +#33979 = DIRECTION('',(-1.390002785238E-016,-1.)); +#33980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33981 = ORIENTED_EDGE('',*,*,#33547,.T.); +#33982 = ORIENTED_EDGE('',*,*,#33983,.T.); +#33983 = EDGE_CURVE('',#33550,#33984,#33986,.T.); +#33984 = VERTEX_POINT('',#33985); +#33985 = CARTESIAN_POINT('',(0.85,0.15,-0.625)); +#33986 = SURFACE_CURVE('',#33987,(#33991,#33998),.PCURVE_S1.); +#33987 = LINE('',#33988,#33989); +#33988 = CARTESIAN_POINT('',(0.85,0.78,-0.625)); +#33989 = VECTOR('',#33990,1.); +#33990 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#33991 = PCURVE('',#33569,#33992); +#33992 = DEFINITIONAL_REPRESENTATION('',(#33993),#33997); +#33993 = LINE('',#33994,#33995); +#33994 = CARTESIAN_POINT('',(1.85,0.E+000)); +#33995 = VECTOR('',#33996,1.); +#33996 = DIRECTION('',(0.E+000,-1.)); +#33997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#33998 = PCURVE('',#33999,#34004); +#33999 = CYLINDRICAL_SURFACE('',#34000,0.15); +#34000 = AXIS2_PLACEMENT_3D('',#34001,#34002,#34003); +#34001 = CARTESIAN_POINT('',(0.85,0.78,-0.475)); +#34002 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34003 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34004 = DEFINITIONAL_REPRESENTATION('',(#34005),#34008); +#34005 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34006,#34007),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.63),.PIECEWISE_BEZIER_KNOTS.); -#31614 = CARTESIAN_POINT('',(0.E+000,0.15)); -#31615 = CARTESIAN_POINT('',(0.E+000,0.63)); -#31616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31617 = ORIENTED_EDGE('',*,*,#31618,.T.); -#31618 = EDGE_CURVE('',#31592,#31568,#31619,.T.); -#31619 = SURFACE_CURVE('',#31620,(#31624,#31631),.PCURVE_S1.); -#31620 = LINE('',#31621,#31622); -#31621 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); -#31622 = VECTOR('',#31623,1.); -#31623 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31624 = PCURVE('',#31177,#31625); -#31625 = DEFINITIONAL_REPRESENTATION('',(#31626),#31630); -#31626 = LINE('',#31627,#31628); -#31627 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#31628 = VECTOR('',#31629,1.); -#31629 = DIRECTION('',(-1.,0.E+000)); -#31630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31631 = PCURVE('',#31422,#31632); -#31632 = DEFINITIONAL_REPRESENTATION('',(#31633),#31636); -#31633 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31634,#31635),.UNSPECIFIED., +#34006 = CARTESIAN_POINT('',(0.E+000,0.15)); +#34007 = CARTESIAN_POINT('',(0.E+000,0.63)); +#34008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34009 = ORIENTED_EDGE('',*,*,#34010,.T.); +#34010 = EDGE_CURVE('',#33984,#33960,#34011,.T.); +#34011 = SURFACE_CURVE('',#34012,(#34016,#34023),.PCURVE_S1.); +#34012 = LINE('',#34013,#34014); +#34013 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); +#34014 = VECTOR('',#34015,1.); +#34015 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34016 = PCURVE('',#33569,#34017); +#34017 = DEFINITIONAL_REPRESENTATION('',(#34018),#34022); +#34018 = LINE('',#34019,#34020); +#34019 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34020 = VECTOR('',#34021,1.); +#34021 = DIRECTION('',(-1.,0.E+000)); +#34022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34023 = PCURVE('',#33814,#34024); +#34024 = DEFINITIONAL_REPRESENTATION('',(#34025),#34028); +#34025 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34026,#34027),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#31634 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#31635 = CARTESIAN_POINT('',(3.14159265359,-1.5)); -#31636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34026 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#34027 = CARTESIAN_POINT('',(3.14159265359,-1.5)); +#34028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31637 = ADVANCED_FACE('',(#31638),#31362,.T.); -#31638 = FACE_BOUND('',#31639,.T.); -#31639 = EDGE_LOOP('',(#31640,#31641,#31666,#31667)); -#31640 = ORIENTED_EDGE('',*,*,#31516,.F.); -#31641 = ORIENTED_EDGE('',*,*,#31642,.T.); -#31642 = EDGE_CURVE('',#31489,#31262,#31643,.T.); -#31643 = SURFACE_CURVE('',#31644,(#31649,#31655),.PCURVE_S1.); -#31644 = CIRCLE('',#31645,0.15); -#31645 = AXIS2_PLACEMENT_3D('',#31646,#31647,#31648); -#31646 = CARTESIAN_POINT('',(-0.5,0.15,-0.475)); -#31647 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); -#31648 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); -#31649 = PCURVE('',#31362,#31650); -#31650 = DEFINITIONAL_REPRESENTATION('',(#31651),#31654); -#31651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31652,#31653),.UNSPECIFIED., +#34029 = ADVANCED_FACE('',(#34030),#33754,.T.); +#34030 = FACE_BOUND('',#34031,.T.); +#34031 = EDGE_LOOP('',(#34032,#34033,#34058,#34059)); +#34032 = ORIENTED_EDGE('',*,*,#33908,.F.); +#34033 = ORIENTED_EDGE('',*,*,#34034,.T.); +#34034 = EDGE_CURVE('',#33881,#33654,#34035,.T.); +#34035 = SURFACE_CURVE('',#34036,(#34041,#34047),.PCURVE_S1.); +#34036 = CIRCLE('',#34037,0.15); +#34037 = AXIS2_PLACEMENT_3D('',#34038,#34039,#34040); +#34038 = CARTESIAN_POINT('',(-0.5,0.15,-0.475)); +#34039 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); +#34040 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); +#34041 = PCURVE('',#33754,#34042); +#34042 = DEFINITIONAL_REPRESENTATION('',(#34043),#34046); +#34043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34044,#34045),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31652 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#31653 = CARTESIAN_POINT('',(4.712388980385,-0.5)); -#31654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34044 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#34045 = CARTESIAN_POINT('',(4.712388980385,-0.5)); +#34046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31655 = PCURVE('',#31656,#31661); -#31656 = CYLINDRICAL_SURFACE('',#31657,0.15); -#31657 = AXIS2_PLACEMENT_3D('',#31658,#31659,#31660); -#31658 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); -#31659 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31660 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31661 = DEFINITIONAL_REPRESENTATION('',(#31662),#31665); -#31662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31663,#31664),.UNSPECIFIED., +#34047 = PCURVE('',#34048,#34053); +#34048 = CYLINDRICAL_SURFACE('',#34049,0.15); +#34049 = AXIS2_PLACEMENT_3D('',#34050,#34051,#34052); +#34050 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); +#34051 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34052 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34053 = DEFINITIONAL_REPRESENTATION('',(#34054),#34057); +#34054 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34055,#34056),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31663 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#31664 = CARTESIAN_POINT('',(4.712388980385,-0.5)); -#31665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31666 = ORIENTED_EDGE('',*,*,#31348,.F.); -#31667 = ORIENTED_EDGE('',*,*,#31668,.F.); -#31668 = EDGE_CURVE('',#31517,#31322,#31669,.T.); -#31669 = SURFACE_CURVE('',#31670,(#31675,#31681),.PCURVE_S1.); -#31670 = CIRCLE('',#31671,0.15); -#31671 = AXIS2_PLACEMENT_3D('',#31672,#31673,#31674); -#31672 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); -#31673 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31674 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31675 = PCURVE('',#31362,#31676); -#31676 = DEFINITIONAL_REPRESENTATION('',(#31677),#31680); -#31677 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31678,#31679),.UNSPECIFIED., +#34055 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#34056 = CARTESIAN_POINT('',(4.712388980385,-0.5)); +#34057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34058 = ORIENTED_EDGE('',*,*,#33740,.F.); +#34059 = ORIENTED_EDGE('',*,*,#34060,.F.); +#34060 = EDGE_CURVE('',#33909,#33714,#34061,.T.); +#34061 = SURFACE_CURVE('',#34062,(#34067,#34073),.PCURVE_S1.); +#34062 = CIRCLE('',#34063,0.15); +#34063 = AXIS2_PLACEMENT_3D('',#34064,#34065,#34066); +#34064 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); +#34065 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34066 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34067 = PCURVE('',#33754,#34068); +#34068 = DEFINITIONAL_REPRESENTATION('',(#34069),#34072); +#34069 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34070,#34071),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#31678 = CARTESIAN_POINT('',(3.14159265359,-0.15)); -#31679 = CARTESIAN_POINT('',(4.712388980385,-0.15)); -#31680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34070 = CARTESIAN_POINT('',(3.14159265359,-0.15)); +#34071 = CARTESIAN_POINT('',(4.712388980385,-0.15)); +#34072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31681 = PCURVE('',#31682,#31687); -#31682 = SPHERICAL_SURFACE('',#31683,0.15); -#31683 = AXIS2_PLACEMENT_3D('',#31684,#31685,#31686); -#31684 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); -#31685 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31686 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31687 = DEFINITIONAL_REPRESENTATION('',(#31688),#31691); -#31688 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31689,#31690),.UNSPECIFIED., +#34073 = PCURVE('',#34074,#34079); +#34074 = SPHERICAL_SURFACE('',#34075,0.15); +#34075 = AXIS2_PLACEMENT_3D('',#34076,#34077,#34078); +#34076 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); +#34077 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34078 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34079 = DEFINITIONAL_REPRESENTATION('',(#34080),#34083); +#34080 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34081,#34082),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#31689 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#31690 = CARTESIAN_POINT('',(1.570796326795,-1.570796326795)); -#31691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31692 = ADVANCED_FACE('',(#31693),#31422,.T.); -#31693 = FACE_BOUND('',#31694,.T.); -#31694 = EDGE_LOOP('',(#31695,#31696,#31716,#31717)); -#31695 = ORIENTED_EDGE('',*,*,#31406,.F.); -#31696 = ORIENTED_EDGE('',*,*,#31697,.T.); -#31697 = EDGE_CURVE('',#31377,#31568,#31698,.T.); -#31698 = SURFACE_CURVE('',#31699,(#31704,#31710),.PCURVE_S1.); -#31699 = CIRCLE('',#31700,0.15); -#31700 = AXIS2_PLACEMENT_3D('',#31701,#31702,#31703); -#31701 = CARTESIAN_POINT('',(0.5,0.15,-0.475)); -#31702 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); -#31703 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); -#31704 = PCURVE('',#31422,#31705); -#31705 = DEFINITIONAL_REPRESENTATION('',(#31706),#31709); -#31706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31707,#31708),.UNSPECIFIED., +#34081 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#34082 = CARTESIAN_POINT('',(1.570796326795,-1.570796326795)); +#34083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34084 = ADVANCED_FACE('',(#34085),#33814,.T.); +#34085 = FACE_BOUND('',#34086,.T.); +#34086 = EDGE_LOOP('',(#34087,#34088,#34108,#34109)); +#34087 = ORIENTED_EDGE('',*,*,#33798,.F.); +#34088 = ORIENTED_EDGE('',*,*,#34089,.T.); +#34089 = EDGE_CURVE('',#33769,#33960,#34090,.T.); +#34090 = SURFACE_CURVE('',#34091,(#34096,#34102),.PCURVE_S1.); +#34091 = CIRCLE('',#34092,0.15); +#34092 = AXIS2_PLACEMENT_3D('',#34093,#34094,#34095); +#34093 = CARTESIAN_POINT('',(0.5,0.15,-0.475)); +#34094 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); +#34095 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); +#34096 = PCURVE('',#33814,#34097); +#34097 = DEFINITIONAL_REPRESENTATION('',(#34098),#34101); +#34098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34099,#34100),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31707 = CARTESIAN_POINT('',(4.712388980385,-1.5)); -#31708 = CARTESIAN_POINT('',(3.14159265359,-1.5)); -#31709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34099 = CARTESIAN_POINT('',(4.712388980385,-1.5)); +#34100 = CARTESIAN_POINT('',(3.14159265359,-1.5)); +#34101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31710 = PCURVE('',#31656,#31711); -#31711 = DEFINITIONAL_REPRESENTATION('',(#31712),#31715); -#31712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31713,#31714),.UNSPECIFIED., +#34102 = PCURVE('',#34048,#34103); +#34103 = DEFINITIONAL_REPRESENTATION('',(#34104),#34107); +#34104 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34105,#34106),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31713 = CARTESIAN_POINT('',(4.712388980385,-1.5)); -#31714 = CARTESIAN_POINT('',(3.14159265359,-1.5)); -#31715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31716 = ORIENTED_EDGE('',*,*,#31618,.F.); -#31717 = ORIENTED_EDGE('',*,*,#31718,.T.); -#31718 = EDGE_CURVE('',#31592,#31407,#31719,.T.); -#31719 = SURFACE_CURVE('',#31720,(#31725,#31731),.PCURVE_S1.); -#31720 = CIRCLE('',#31721,0.15); -#31721 = AXIS2_PLACEMENT_3D('',#31722,#31723,#31724); -#31722 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); -#31723 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31724 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31725 = PCURVE('',#31422,#31726); -#31726 = DEFINITIONAL_REPRESENTATION('',(#31727),#31730); -#31727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31728,#31729),.UNSPECIFIED., +#34105 = CARTESIAN_POINT('',(4.712388980385,-1.5)); +#34106 = CARTESIAN_POINT('',(3.14159265359,-1.5)); +#34107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34108 = ORIENTED_EDGE('',*,*,#34010,.F.); +#34109 = ORIENTED_EDGE('',*,*,#34110,.T.); +#34110 = EDGE_CURVE('',#33984,#33799,#34111,.T.); +#34111 = SURFACE_CURVE('',#34112,(#34117,#34123),.PCURVE_S1.); +#34112 = CIRCLE('',#34113,0.15); +#34113 = AXIS2_PLACEMENT_3D('',#34114,#34115,#34116); +#34114 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); +#34115 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34116 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34117 = PCURVE('',#33814,#34118); +#34118 = DEFINITIONAL_REPRESENTATION('',(#34119),#34122); +#34119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34120,#34121),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31728 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#31729 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#31730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34120 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#34121 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#34122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31731 = PCURVE('',#31732,#31737); -#31732 = SPHERICAL_SURFACE('',#31733,0.15); -#31733 = AXIS2_PLACEMENT_3D('',#31734,#31735,#31736); -#31734 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); -#31735 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31736 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31737 = DEFINITIONAL_REPRESENTATION('',(#31738),#31741); -#31738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31739,#31740),.UNSPECIFIED., +#34123 = PCURVE('',#34124,#34129); +#34124 = SPHERICAL_SURFACE('',#34125,0.15); +#34125 = AXIS2_PLACEMENT_3D('',#34126,#34127,#34128); +#34126 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); +#34127 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34128 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34129 = DEFINITIONAL_REPRESENTATION('',(#34130),#34133); +#34130 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34131,#34132),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31739 = CARTESIAN_POINT('',(1.570796326795,1.850371707709E-016)); -#31740 = CARTESIAN_POINT('',(1.570796326795,-1.570796326795)); -#31741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31742 = ADVANCED_FACE('',(#31743),#31310,.T.); -#31743 = FACE_BOUND('',#31744,.T.); -#31744 = EDGE_LOOP('',(#31745,#31746,#31773,#31800)); -#31745 = ORIENTED_EDGE('',*,*,#31294,.F.); -#31746 = ORIENTED_EDGE('',*,*,#31747,.T.); -#31747 = EDGE_CURVE('',#31260,#31748,#31750,.T.); -#31748 = VERTEX_POINT('',#31749); -#31749 = CARTESIAN_POINT('',(-0.5,0.15,0.625)); -#31750 = SURFACE_CURVE('',#31751,(#31756,#31762),.PCURVE_S1.); -#31751 = CIRCLE('',#31752,0.15); -#31752 = AXIS2_PLACEMENT_3D('',#31753,#31754,#31755); -#31753 = CARTESIAN_POINT('',(-0.5,0.15,0.475)); -#31754 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); -#31755 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); -#31756 = PCURVE('',#31310,#31757); -#31757 = DEFINITIONAL_REPRESENTATION('',(#31758),#31761); -#31758 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31759,#31760),.UNSPECIFIED., +#34131 = CARTESIAN_POINT('',(1.570796326795,1.850371707709E-016)); +#34132 = CARTESIAN_POINT('',(1.570796326795,-1.570796326795)); +#34133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34134 = ADVANCED_FACE('',(#34135),#33702,.T.); +#34135 = FACE_BOUND('',#34136,.T.); +#34136 = EDGE_LOOP('',(#34137,#34138,#34165,#34192)); +#34137 = ORIENTED_EDGE('',*,*,#33686,.F.); +#34138 = ORIENTED_EDGE('',*,*,#34139,.T.); +#34139 = EDGE_CURVE('',#33652,#34140,#34142,.T.); +#34140 = VERTEX_POINT('',#34141); +#34141 = CARTESIAN_POINT('',(-0.5,0.15,0.625)); +#34142 = SURFACE_CURVE('',#34143,(#34148,#34154),.PCURVE_S1.); +#34143 = CIRCLE('',#34144,0.15); +#34144 = AXIS2_PLACEMENT_3D('',#34145,#34146,#34147); +#34145 = CARTESIAN_POINT('',(-0.5,0.15,0.475)); +#34146 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); +#34147 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); +#34148 = PCURVE('',#33702,#34149); +#34149 = DEFINITIONAL_REPRESENTATION('',(#34150),#34153); +#34150 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34151,#34152),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#31759 = CARTESIAN_POINT('',(4.712388980385,0.5)); -#31760 = CARTESIAN_POINT('',(3.14159265359,0.5)); -#31761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34151 = CARTESIAN_POINT('',(4.712388980385,0.5)); +#34152 = CARTESIAN_POINT('',(3.14159265359,0.5)); +#34153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31762 = PCURVE('',#31763,#31768); -#31763 = CYLINDRICAL_SURFACE('',#31764,0.15); -#31764 = AXIS2_PLACEMENT_3D('',#31765,#31766,#31767); -#31765 = CARTESIAN_POINT('',(-1.,0.15,0.475)); -#31766 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31767 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31768 = DEFINITIONAL_REPRESENTATION('',(#31769),#31772); -#31769 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31770,#31771),.UNSPECIFIED., +#34154 = PCURVE('',#34155,#34160); +#34155 = CYLINDRICAL_SURFACE('',#34156,0.15); +#34156 = AXIS2_PLACEMENT_3D('',#34157,#34158,#34159); +#34157 = CARTESIAN_POINT('',(-1.,0.15,0.475)); +#34158 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34159 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34160 = DEFINITIONAL_REPRESENTATION('',(#34161),#34164); +#34161 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34162,#34163),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#31770 = CARTESIAN_POINT('',(4.712388980385,0.5)); -#31771 = CARTESIAN_POINT('',(3.14159265359,0.5)); -#31772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31773 = ORIENTED_EDGE('',*,*,#31774,.F.); -#31774 = EDGE_CURVE('',#31775,#31748,#31777,.T.); -#31775 = VERTEX_POINT('',#31776); -#31776 = CARTESIAN_POINT('',(-0.85,0.15,0.625)); -#31777 = SURFACE_CURVE('',#31778,(#31782,#31788),.PCURVE_S1.); -#31778 = LINE('',#31779,#31780); -#31779 = CARTESIAN_POINT('',(-1.,0.15,0.625)); -#31780 = VECTOR('',#31781,1.); -#31781 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31782 = PCURVE('',#31310,#31783); -#31783 = DEFINITIONAL_REPRESENTATION('',(#31784),#31787); -#31784 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31785,#31786),.UNSPECIFIED., +#34162 = CARTESIAN_POINT('',(4.712388980385,0.5)); +#34163 = CARTESIAN_POINT('',(3.14159265359,0.5)); +#34164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34165 = ORIENTED_EDGE('',*,*,#34166,.F.); +#34166 = EDGE_CURVE('',#34167,#34140,#34169,.T.); +#34167 = VERTEX_POINT('',#34168); +#34168 = CARTESIAN_POINT('',(-0.85,0.15,0.625)); +#34169 = SURFACE_CURVE('',#34170,(#34174,#34180),.PCURVE_S1.); +#34170 = LINE('',#34171,#34172); +#34171 = CARTESIAN_POINT('',(-1.,0.15,0.625)); +#34172 = VECTOR('',#34173,1.); +#34173 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34174 = PCURVE('',#33702,#34175); +#34175 = DEFINITIONAL_REPRESENTATION('',(#34176),#34179); +#34176 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34177,#34178),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.5),.PIECEWISE_BEZIER_KNOTS.); -#31785 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#31786 = CARTESIAN_POINT('',(3.14159265359,0.5)); -#31787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31788 = PCURVE('',#31789,#31794); -#31789 = PLANE('',#31790); -#31790 = AXIS2_PLACEMENT_3D('',#31791,#31792,#31793); -#31791 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#31792 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31793 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31794 = DEFINITIONAL_REPRESENTATION('',(#31795),#31799); -#31795 = LINE('',#31796,#31797); -#31796 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#31797 = VECTOR('',#31798,1.); -#31798 = DIRECTION('',(-1.,0.E+000)); -#31799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31800 = ORIENTED_EDGE('',*,*,#31801,.F.); -#31801 = EDGE_CURVE('',#31295,#31775,#31802,.T.); -#31802 = SURFACE_CURVE('',#31803,(#31808,#31814),.PCURVE_S1.); -#31803 = CIRCLE('',#31804,0.15); -#31804 = AXIS2_PLACEMENT_3D('',#31805,#31806,#31807); -#31805 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); -#31806 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31807 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31808 = PCURVE('',#31310,#31809); -#31809 = DEFINITIONAL_REPRESENTATION('',(#31810),#31813); -#31810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31811,#31812),.UNSPECIFIED., +#34177 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#34178 = CARTESIAN_POINT('',(3.14159265359,0.5)); +#34179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34180 = PCURVE('',#34181,#34186); +#34181 = PLANE('',#34182); +#34182 = AXIS2_PLACEMENT_3D('',#34183,#34184,#34185); +#34183 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#34184 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34185 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34186 = DEFINITIONAL_REPRESENTATION('',(#34187),#34191); +#34187 = LINE('',#34188,#34189); +#34188 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34189 = VECTOR('',#34190,1.); +#34190 = DIRECTION('',(-1.,0.E+000)); +#34191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34192 = ORIENTED_EDGE('',*,*,#34193,.F.); +#34193 = EDGE_CURVE('',#33687,#34167,#34194,.T.); +#34194 = SURFACE_CURVE('',#34195,(#34200,#34206),.PCURVE_S1.); +#34195 = CIRCLE('',#34196,0.15); +#34196 = AXIS2_PLACEMENT_3D('',#34197,#34198,#34199); +#34197 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); +#34198 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34199 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34200 = PCURVE('',#33702,#34201); +#34201 = DEFINITIONAL_REPRESENTATION('',(#34202),#34205); +#34202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34203,#34204),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31811 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#31812 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#31813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34203 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#34204 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#34205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31814 = PCURVE('',#31815,#31820); -#31815 = SPHERICAL_SURFACE('',#31816,0.15); -#31816 = AXIS2_PLACEMENT_3D('',#31817,#31818,#31819); -#31817 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); -#31818 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31819 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31820 = DEFINITIONAL_REPRESENTATION('',(#31821),#31824); -#31821 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31822,#31823),.UNSPECIFIED., +#34206 = PCURVE('',#34207,#34212); +#34207 = SPHERICAL_SURFACE('',#34208,0.15); +#34208 = AXIS2_PLACEMENT_3D('',#34209,#34210,#34211); +#34209 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); +#34210 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34211 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34212 = DEFINITIONAL_REPRESENTATION('',(#34213),#34216); +#34213 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34214,#34215),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31822 = CARTESIAN_POINT('',(4.712388980385,-1.570796326795)); -#31823 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#31824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31825 = ADVANCED_FACE('',(#31826),#31474,.T.); -#31826 = FACE_BOUND('',#31827,.T.); -#31827 = EDGE_LOOP('',(#31828,#31857,#31877,#31878)); -#31828 = ORIENTED_EDGE('',*,*,#31829,.F.); -#31829 = EDGE_CURVE('',#31830,#31832,#31834,.T.); -#31830 = VERTEX_POINT('',#31831); -#31831 = CARTESIAN_POINT('',(0.5,0.15,0.625)); -#31832 = VERTEX_POINT('',#31833); -#31833 = CARTESIAN_POINT('',(0.85,0.15,0.625)); -#31834 = SURFACE_CURVE('',#31835,(#31839,#31845),.PCURVE_S1.); -#31835 = LINE('',#31836,#31837); -#31836 = CARTESIAN_POINT('',(-1.,0.15,0.625)); -#31837 = VECTOR('',#31838,1.); -#31838 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31839 = PCURVE('',#31474,#31840); -#31840 = DEFINITIONAL_REPRESENTATION('',(#31841),#31844); -#31841 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31842,#31843),.UNSPECIFIED., +#34214 = CARTESIAN_POINT('',(4.712388980385,-1.570796326795)); +#34215 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#34216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34217 = ADVANCED_FACE('',(#34218),#33866,.T.); +#34218 = FACE_BOUND('',#34219,.T.); +#34219 = EDGE_LOOP('',(#34220,#34249,#34269,#34270)); +#34220 = ORIENTED_EDGE('',*,*,#34221,.F.); +#34221 = EDGE_CURVE('',#34222,#34224,#34226,.T.); +#34222 = VERTEX_POINT('',#34223); +#34223 = CARTESIAN_POINT('',(0.5,0.15,0.625)); +#34224 = VERTEX_POINT('',#34225); +#34225 = CARTESIAN_POINT('',(0.85,0.15,0.625)); +#34226 = SURFACE_CURVE('',#34227,(#34231,#34237),.PCURVE_S1.); +#34227 = LINE('',#34228,#34229); +#34228 = CARTESIAN_POINT('',(-1.,0.15,0.625)); +#34229 = VECTOR('',#34230,1.); +#34230 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34231 = PCURVE('',#33866,#34232); +#34232 = DEFINITIONAL_REPRESENTATION('',(#34233),#34236); +#34233 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34234,#34235),.UNSPECIFIED., .F.,.F.,(2,2),(1.5,1.85),.PIECEWISE_BEZIER_KNOTS.); -#31842 = CARTESIAN_POINT('',(3.14159265359,1.5)); -#31843 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#31844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31845 = PCURVE('',#31846,#31851); -#31846 = PLANE('',#31847); -#31847 = AXIS2_PLACEMENT_3D('',#31848,#31849,#31850); -#31848 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#31849 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#31850 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31851 = DEFINITIONAL_REPRESENTATION('',(#31852),#31856); -#31852 = LINE('',#31853,#31854); -#31853 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#31854 = VECTOR('',#31855,1.); -#31855 = DIRECTION('',(-1.,0.E+000)); -#31856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31857 = ORIENTED_EDGE('',*,*,#31858,.T.); -#31858 = EDGE_CURVE('',#31830,#31379,#31859,.T.); -#31859 = SURFACE_CURVE('',#31860,(#31865,#31871),.PCURVE_S1.); -#31860 = CIRCLE('',#31861,0.15); -#31861 = AXIS2_PLACEMENT_3D('',#31862,#31863,#31864); -#31862 = CARTESIAN_POINT('',(0.5,0.15,0.475)); -#31863 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); -#31864 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); -#31865 = PCURVE('',#31474,#31866); -#31866 = DEFINITIONAL_REPRESENTATION('',(#31867),#31870); -#31867 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31868,#31869),.UNSPECIFIED., +#34234 = CARTESIAN_POINT('',(3.14159265359,1.5)); +#34235 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#34236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34237 = PCURVE('',#34238,#34243); +#34238 = PLANE('',#34239); +#34239 = AXIS2_PLACEMENT_3D('',#34240,#34241,#34242); +#34240 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#34241 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34242 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34243 = DEFINITIONAL_REPRESENTATION('',(#34244),#34248); +#34244 = LINE('',#34245,#34246); +#34245 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34246 = VECTOR('',#34247,1.); +#34247 = DIRECTION('',(-1.,0.E+000)); +#34248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34249 = ORIENTED_EDGE('',*,*,#34250,.T.); +#34250 = EDGE_CURVE('',#34222,#33771,#34251,.T.); +#34251 = SURFACE_CURVE('',#34252,(#34257,#34263),.PCURVE_S1.); +#34252 = CIRCLE('',#34253,0.15); +#34253 = AXIS2_PLACEMENT_3D('',#34254,#34255,#34256); +#34254 = CARTESIAN_POINT('',(0.5,0.15,0.475)); +#34255 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); +#34256 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); +#34257 = PCURVE('',#33866,#34258); +#34258 = DEFINITIONAL_REPRESENTATION('',(#34259),#34262); +#34259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34260,#34261),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31868 = CARTESIAN_POINT('',(3.14159265359,1.5)); -#31869 = CARTESIAN_POINT('',(4.712388980385,1.5)); -#31870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34260 = CARTESIAN_POINT('',(3.14159265359,1.5)); +#34261 = CARTESIAN_POINT('',(4.712388980385,1.5)); +#34262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31871 = PCURVE('',#31763,#31872); -#31872 = DEFINITIONAL_REPRESENTATION('',(#31873),#31876); -#31873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31874,#31875),.UNSPECIFIED., +#34263 = PCURVE('',#34155,#34264); +#34264 = DEFINITIONAL_REPRESENTATION('',(#34265),#34268); +#34265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34266,#34267),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31874 = CARTESIAN_POINT('',(3.14159265359,1.5)); -#31875 = CARTESIAN_POINT('',(4.712388980385,1.5)); -#31876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31877 = ORIENTED_EDGE('',*,*,#31460,.F.); -#31878 = ORIENTED_EDGE('',*,*,#31879,.T.); -#31879 = EDGE_CURVE('',#31434,#31832,#31880,.T.); -#31880 = SURFACE_CURVE('',#31881,(#31886,#31892),.PCURVE_S1.); -#31881 = CIRCLE('',#31882,0.15); -#31882 = AXIS2_PLACEMENT_3D('',#31883,#31884,#31885); -#31883 = CARTESIAN_POINT('',(0.85,0.15,0.475)); -#31884 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31885 = DIRECTION('',(0.E+000,9.035018104046E-016,-1.)); -#31886 = PCURVE('',#31474,#31887); -#31887 = DEFINITIONAL_REPRESENTATION('',(#31888),#31891); -#31888 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31889,#31890),.UNSPECIFIED., +#34266 = CARTESIAN_POINT('',(3.14159265359,1.5)); +#34267 = CARTESIAN_POINT('',(4.712388980385,1.5)); +#34268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34269 = ORIENTED_EDGE('',*,*,#33852,.F.); +#34270 = ORIENTED_EDGE('',*,*,#34271,.T.); +#34271 = EDGE_CURVE('',#33826,#34224,#34272,.T.); +#34272 = SURFACE_CURVE('',#34273,(#34278,#34284),.PCURVE_S1.); +#34273 = CIRCLE('',#34274,0.15); +#34274 = AXIS2_PLACEMENT_3D('',#34275,#34276,#34277); +#34275 = CARTESIAN_POINT('',(0.85,0.15,0.475)); +#34276 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34277 = DIRECTION('',(0.E+000,9.035018104046E-016,-1.)); +#34278 = PCURVE('',#33866,#34279); +#34279 = DEFINITIONAL_REPRESENTATION('',(#34280),#34283); +#34280 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34281,#34282),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31889 = CARTESIAN_POINT('',(4.712388980385,1.85)); -#31890 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#31891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34281 = CARTESIAN_POINT('',(4.712388980385,1.85)); +#34282 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#34283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31892 = PCURVE('',#31893,#31898); -#31893 = SPHERICAL_SURFACE('',#31894,0.15); -#31894 = AXIS2_PLACEMENT_3D('',#31895,#31896,#31897); -#31895 = CARTESIAN_POINT('',(0.85,0.15,0.475)); -#31896 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31897 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31898 = DEFINITIONAL_REPRESENTATION('',(#31899),#31902); -#31899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31900,#31901),.UNSPECIFIED., +#34284 = PCURVE('',#34285,#34290); +#34285 = SPHERICAL_SURFACE('',#34286,0.15); +#34286 = AXIS2_PLACEMENT_3D('',#34287,#34288,#34289); +#34287 = CARTESIAN_POINT('',(0.85,0.15,0.475)); +#34288 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34289 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34290 = DEFINITIONAL_REPRESENTATION('',(#34291),#34294); +#34291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34292,#34293),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#31900 = CARTESIAN_POINT('',(4.712388980385,-1.570796326795)); -#31901 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#31902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31903 = ADVANCED_FACE('',(#31904),#31918,.T.); -#31904 = FACE_BOUND('',#31905,.T.); -#31905 = EDGE_LOOP('',(#31906,#31935,#31955,#31977)); -#31906 = ORIENTED_EDGE('',*,*,#31907,.F.); -#31907 = EDGE_CURVE('',#31908,#31910,#31912,.T.); -#31908 = VERTEX_POINT('',#31909); -#31909 = CARTESIAN_POINT('',(-0.5,0.63,0.625)); -#31910 = VERTEX_POINT('',#31911); -#31911 = CARTESIAN_POINT('',(-0.85,0.63,0.625)); -#31912 = SURFACE_CURVE('',#31913,(#31917,#31928),.PCURVE_S1.); -#31913 = LINE('',#31914,#31915); -#31914 = CARTESIAN_POINT('',(-1.,0.63,0.625)); -#31915 = VECTOR('',#31916,1.); -#31916 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31917 = PCURVE('',#31918,#31923); -#31918 = CYLINDRICAL_SURFACE('',#31919,0.15); -#31919 = AXIS2_PLACEMENT_3D('',#31920,#31921,#31922); -#31920 = CARTESIAN_POINT('',(-1.,0.63,0.475)); -#31921 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31922 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31923 = DEFINITIONAL_REPRESENTATION('',(#31924),#31927); -#31924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31925,#31926),.UNSPECIFIED., +#34292 = CARTESIAN_POINT('',(4.712388980385,-1.570796326795)); +#34293 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#34294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34295 = ADVANCED_FACE('',(#34296),#34310,.T.); +#34296 = FACE_BOUND('',#34297,.T.); +#34297 = EDGE_LOOP('',(#34298,#34327,#34347,#34369)); +#34298 = ORIENTED_EDGE('',*,*,#34299,.F.); +#34299 = EDGE_CURVE('',#34300,#34302,#34304,.T.); +#34300 = VERTEX_POINT('',#34301); +#34301 = CARTESIAN_POINT('',(-0.5,0.63,0.625)); +#34302 = VERTEX_POINT('',#34303); +#34303 = CARTESIAN_POINT('',(-0.85,0.63,0.625)); +#34304 = SURFACE_CURVE('',#34305,(#34309,#34320),.PCURVE_S1.); +#34305 = LINE('',#34306,#34307); +#34306 = CARTESIAN_POINT('',(-1.,0.63,0.625)); +#34307 = VECTOR('',#34308,1.); +#34308 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34309 = PCURVE('',#34310,#34315); +#34310 = CYLINDRICAL_SURFACE('',#34311,0.15); +#34311 = AXIS2_PLACEMENT_3D('',#34312,#34313,#34314); +#34312 = CARTESIAN_POINT('',(-1.,0.63,0.475)); +#34313 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34314 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34315 = DEFINITIONAL_REPRESENTATION('',(#34316),#34319); +#34316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34317,#34318),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#31925 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#31926 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#31927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31928 = PCURVE('',#31789,#31929); -#31929 = DEFINITIONAL_REPRESENTATION('',(#31930),#31934); -#31930 = LINE('',#31931,#31932); -#31931 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#31932 = VECTOR('',#31933,1.); -#31933 = DIRECTION('',(1.,0.E+000)); -#31934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31935 = ORIENTED_EDGE('',*,*,#31936,.T.); -#31936 = EDGE_CURVE('',#31908,#30249,#31937,.T.); -#31937 = SURFACE_CURVE('',#31938,(#31943,#31949),.PCURVE_S1.); -#31938 = CIRCLE('',#31939,0.15); -#31939 = AXIS2_PLACEMENT_3D('',#31940,#31941,#31942); -#31940 = CARTESIAN_POINT('',(-0.5,0.63,0.475)); -#31941 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); -#31942 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); -#31943 = PCURVE('',#31918,#31944); -#31944 = DEFINITIONAL_REPRESENTATION('',(#31945),#31948); -#31945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31946,#31947),.UNSPECIFIED., +#34317 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#34318 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34320 = PCURVE('',#34181,#34321); +#34321 = DEFINITIONAL_REPRESENTATION('',(#34322),#34326); +#34322 = LINE('',#34323,#34324); +#34323 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34324 = VECTOR('',#34325,1.); +#34325 = DIRECTION('',(1.,0.E+000)); +#34326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34327 = ORIENTED_EDGE('',*,*,#34328,.T.); +#34328 = EDGE_CURVE('',#34300,#32641,#34329,.T.); +#34329 = SURFACE_CURVE('',#34330,(#34335,#34341),.PCURVE_S1.); +#34330 = CIRCLE('',#34331,0.15); +#34331 = AXIS2_PLACEMENT_3D('',#34332,#34333,#34334); +#34332 = CARTESIAN_POINT('',(-0.5,0.63,0.475)); +#34333 = DIRECTION('',(-1.,-1.390002785238E-016,0.E+000)); +#34334 = DIRECTION('',(-1.390002785238E-016,1.,0.E+000)); +#34335 = PCURVE('',#34310,#34336); +#34336 = DEFINITIONAL_REPRESENTATION('',(#34337),#34340); +#34337 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34338,#34339),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31946 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#31947 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#31948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34338 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#34339 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#34340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#31949 = PCURVE('',#30294,#31950); -#31950 = DEFINITIONAL_REPRESENTATION('',(#31951),#31954); -#31951 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31952,#31953),.UNSPECIFIED., +#34341 = PCURVE('',#32686,#34342); +#34342 = DEFINITIONAL_REPRESENTATION('',(#34343),#34346); +#34343 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34344,#34345),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#31952 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#31953 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#31954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31955 = ORIENTED_EDGE('',*,*,#31956,.F.); -#31956 = EDGE_CURVE('',#31957,#30249,#31959,.T.); -#31957 = VERTEX_POINT('',#31958); -#31958 = CARTESIAN_POINT('',(-0.85,0.78,0.475)); -#31959 = SURFACE_CURVE('',#31960,(#31964,#31970),.PCURVE_S1.); -#31960 = LINE('',#31961,#31962); -#31961 = CARTESIAN_POINT('',(1.,0.78,0.475)); -#31962 = VECTOR('',#31963,1.); -#31963 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31964 = PCURVE('',#31918,#31965); -#31965 = DEFINITIONAL_REPRESENTATION('',(#31966),#31969); -#31966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31967,#31968),.UNSPECIFIED., +#34344 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#34345 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#34346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34347 = ORIENTED_EDGE('',*,*,#34348,.F.); +#34348 = EDGE_CURVE('',#34349,#32641,#34351,.T.); +#34349 = VERTEX_POINT('',#34350); +#34350 = CARTESIAN_POINT('',(-0.85,0.78,0.475)); +#34351 = SURFACE_CURVE('',#34352,(#34356,#34362),.PCURVE_S1.); +#34352 = LINE('',#34353,#34354); +#34353 = CARTESIAN_POINT('',(1.,0.78,0.475)); +#34354 = VECTOR('',#34355,1.); +#34355 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34356 = PCURVE('',#34310,#34357); +#34357 = DEFINITIONAL_REPRESENTATION('',(#34358),#34361); +#34358 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34359,#34360),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#31967 = CARTESIAN_POINT('',(1.570796326795,-0.15)); -#31968 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#31969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31970 = PCURVE('',#30266,#31971); -#31971 = DEFINITIONAL_REPRESENTATION('',(#31972),#31976); -#31972 = LINE('',#31973,#31974); -#31973 = CARTESIAN_POINT('',(-0.15,2.)); -#31974 = VECTOR('',#31975,1.); -#31975 = DIRECTION('',(0.E+000,1.)); -#31976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31977 = ORIENTED_EDGE('',*,*,#31978,.F.); -#31978 = EDGE_CURVE('',#31910,#31957,#31979,.T.); -#31979 = SURFACE_CURVE('',#31980,(#31985,#31991),.PCURVE_S1.); -#31980 = CIRCLE('',#31981,0.15); -#31981 = AXIS2_PLACEMENT_3D('',#31982,#31983,#31984); -#31982 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); -#31983 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#31984 = DIRECTION('',(0.E+000,0.E+000,1.)); -#31985 = PCURVE('',#31918,#31986); -#31986 = DEFINITIONAL_REPRESENTATION('',(#31987),#31990); -#31987 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31988,#31989),.UNSPECIFIED., +#34359 = CARTESIAN_POINT('',(1.570796326795,-0.15)); +#34360 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#34361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34362 = PCURVE('',#32658,#34363); +#34363 = DEFINITIONAL_REPRESENTATION('',(#34364),#34368); +#34364 = LINE('',#34365,#34366); +#34365 = CARTESIAN_POINT('',(-0.15,2.)); +#34366 = VECTOR('',#34367,1.); +#34367 = DIRECTION('',(0.E+000,1.)); +#34368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34369 = ORIENTED_EDGE('',*,*,#34370,.F.); +#34370 = EDGE_CURVE('',#34302,#34349,#34371,.T.); +#34371 = SURFACE_CURVE('',#34372,(#34377,#34383),.PCURVE_S1.); +#34372 = CIRCLE('',#34373,0.15); +#34373 = AXIS2_PLACEMENT_3D('',#34374,#34375,#34376); +#34374 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); +#34375 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34376 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34377 = PCURVE('',#34310,#34378); +#34378 = DEFINITIONAL_REPRESENTATION('',(#34379),#34382); +#34379 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34380,#34381),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31988 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#31989 = CARTESIAN_POINT('',(1.570796326795,-0.15)); -#31990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#31991 = PCURVE('',#31992,#31997); -#31992 = SPHERICAL_SURFACE('',#31993,0.15); -#31993 = AXIS2_PLACEMENT_3D('',#31994,#31995,#31996); -#31994 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); -#31995 = DIRECTION('',(0.E+000,1.,0.E+000)); -#31996 = DIRECTION('',(1.,0.E+000,0.E+000)); -#31997 = DEFINITIONAL_REPRESENTATION('',(#31998),#32001); -#31998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#31999,#32000),.UNSPECIFIED., +#34380 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34381 = CARTESIAN_POINT('',(1.570796326795,-0.15)); +#34382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34383 = PCURVE('',#34384,#34389); +#34384 = SPHERICAL_SURFACE('',#34385,0.15); +#34385 = AXIS2_PLACEMENT_3D('',#34386,#34387,#34388); +#34386 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); +#34387 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34388 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34389 = DEFINITIONAL_REPRESENTATION('',(#34390),#34393); +#34390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34391,#34392),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#31999 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#32000 = CARTESIAN_POINT('',(4.712388980385,1.570796326795)); -#32001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32002 = ADVANCED_FACE('',(#32003),#32015,.T.); -#32003 = FACE_BOUND('',#32004,.T.); -#32004 = EDGE_LOOP('',(#32005,#32032,#32054,#32076)); -#32005 = ORIENTED_EDGE('',*,*,#32006,.F.); -#32006 = EDGE_CURVE('',#30279,#32007,#32009,.T.); -#32007 = VERTEX_POINT('',#32008); -#32008 = CARTESIAN_POINT('',(0.85,0.78,0.475)); -#32009 = SURFACE_CURVE('',#32010,(#32014,#32025),.PCURVE_S1.); -#32010 = LINE('',#32011,#32012); -#32011 = CARTESIAN_POINT('',(1.,0.78,0.475)); -#32012 = VECTOR('',#32013,1.); -#32013 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32014 = PCURVE('',#32015,#32020); -#32015 = CYLINDRICAL_SURFACE('',#32016,0.15); -#32016 = AXIS2_PLACEMENT_3D('',#32017,#32018,#32019); -#32017 = CARTESIAN_POINT('',(-1.,0.63,0.475)); -#32018 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32019 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32020 = DEFINITIONAL_REPRESENTATION('',(#32021),#32024); -#32021 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32022,#32023),.UNSPECIFIED., +#34391 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#34392 = CARTESIAN_POINT('',(4.712388980385,1.570796326795)); +#34393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34394 = ADVANCED_FACE('',(#34395),#34407,.T.); +#34395 = FACE_BOUND('',#34396,.T.); +#34396 = EDGE_LOOP('',(#34397,#34424,#34446,#34468)); +#34397 = ORIENTED_EDGE('',*,*,#34398,.F.); +#34398 = EDGE_CURVE('',#32671,#34399,#34401,.T.); +#34399 = VERTEX_POINT('',#34400); +#34400 = CARTESIAN_POINT('',(0.85,0.78,0.475)); +#34401 = SURFACE_CURVE('',#34402,(#34406,#34417),.PCURVE_S1.); +#34402 = LINE('',#34403,#34404); +#34403 = CARTESIAN_POINT('',(1.,0.78,0.475)); +#34404 = VECTOR('',#34405,1.); +#34405 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34406 = PCURVE('',#34407,#34412); +#34407 = CYLINDRICAL_SURFACE('',#34408,0.15); +#34408 = AXIS2_PLACEMENT_3D('',#34409,#34410,#34411); +#34409 = CARTESIAN_POINT('',(-1.,0.63,0.475)); +#34410 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34411 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34412 = DEFINITIONAL_REPRESENTATION('',(#34413),#34416); +#34413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34414,#34415),.UNSPECIFIED., .F.,.F.,(2,2),(-0.5,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32022 = CARTESIAN_POINT('',(1.570796326795,-1.5)); -#32023 = CARTESIAN_POINT('',(1.570796326795,-1.85)); -#32024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32025 = PCURVE('',#30321,#32026); -#32026 = DEFINITIONAL_REPRESENTATION('',(#32027),#32031); -#32027 = LINE('',#32028,#32029); -#32028 = CARTESIAN_POINT('',(-0.15,2.)); -#32029 = VECTOR('',#32030,1.); -#32030 = DIRECTION('',(0.E+000,1.)); -#32031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32032 = ORIENTED_EDGE('',*,*,#32033,.T.); -#32033 = EDGE_CURVE('',#30279,#32034,#32036,.T.); -#32034 = VERTEX_POINT('',#32035); -#32035 = CARTESIAN_POINT('',(0.5,0.63,0.625)); -#32036 = SURFACE_CURVE('',#32037,(#32042,#32048),.PCURVE_S1.); -#32037 = CIRCLE('',#32038,0.15); -#32038 = AXIS2_PLACEMENT_3D('',#32039,#32040,#32041); -#32039 = CARTESIAN_POINT('',(0.5,0.63,0.475)); -#32040 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); -#32041 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); -#32042 = PCURVE('',#32015,#32043); -#32043 = DEFINITIONAL_REPRESENTATION('',(#32044),#32047); -#32044 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32045,#32046),.UNSPECIFIED., +#34414 = CARTESIAN_POINT('',(1.570796326795,-1.5)); +#34415 = CARTESIAN_POINT('',(1.570796326795,-1.85)); +#34416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34417 = PCURVE('',#32713,#34418); +#34418 = DEFINITIONAL_REPRESENTATION('',(#34419),#34423); +#34419 = LINE('',#34420,#34421); +#34420 = CARTESIAN_POINT('',(-0.15,2.)); +#34421 = VECTOR('',#34422,1.); +#34422 = DIRECTION('',(0.E+000,1.)); +#34423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34424 = ORIENTED_EDGE('',*,*,#34425,.T.); +#34425 = EDGE_CURVE('',#32671,#34426,#34428,.T.); +#34426 = VERTEX_POINT('',#34427); +#34427 = CARTESIAN_POINT('',(0.5,0.63,0.625)); +#34428 = SURFACE_CURVE('',#34429,(#34434,#34440),.PCURVE_S1.); +#34429 = CIRCLE('',#34430,0.15); +#34430 = AXIS2_PLACEMENT_3D('',#34431,#34432,#34433); +#34431 = CARTESIAN_POINT('',(0.5,0.63,0.475)); +#34432 = DIRECTION('',(1.,-1.390002785238E-016,0.E+000)); +#34433 = DIRECTION('',(-1.390002785238E-016,-1.,0.E+000)); +#34434 = PCURVE('',#34407,#34435); +#34435 = DEFINITIONAL_REPRESENTATION('',(#34436),#34439); +#34436 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34437,#34438),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32045 = CARTESIAN_POINT('',(1.570796326795,-1.5)); -#32046 = CARTESIAN_POINT('',(0.E+000,-1.5)); -#32047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34437 = CARTESIAN_POINT('',(1.570796326795,-1.5)); +#34438 = CARTESIAN_POINT('',(0.E+000,-1.5)); +#34439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32048 = PCURVE('',#30294,#32049); -#32049 = DEFINITIONAL_REPRESENTATION('',(#32050),#32053); -#32050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32051,#32052),.UNSPECIFIED., +#34440 = PCURVE('',#32686,#34441); +#34441 = DEFINITIONAL_REPRESENTATION('',(#34442),#34445); +#34442 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34443,#34444),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32051 = CARTESIAN_POINT('',(1.570796326795,-1.5)); -#32052 = CARTESIAN_POINT('',(0.E+000,-1.5)); -#32053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32054 = ORIENTED_EDGE('',*,*,#32055,.F.); -#32055 = EDGE_CURVE('',#32056,#32034,#32058,.T.); -#32056 = VERTEX_POINT('',#32057); -#32057 = CARTESIAN_POINT('',(0.85,0.63,0.625)); -#32058 = SURFACE_CURVE('',#32059,(#32063,#32069),.PCURVE_S1.); -#32059 = LINE('',#32060,#32061); -#32060 = CARTESIAN_POINT('',(-1.,0.63,0.625)); -#32061 = VECTOR('',#32062,1.); -#32062 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32063 = PCURVE('',#32015,#32064); -#32064 = DEFINITIONAL_REPRESENTATION('',(#32065),#32068); -#32065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32066,#32067),.UNSPECIFIED., +#34443 = CARTESIAN_POINT('',(1.570796326795,-1.5)); +#34444 = CARTESIAN_POINT('',(0.E+000,-1.5)); +#34445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34446 = ORIENTED_EDGE('',*,*,#34447,.F.); +#34447 = EDGE_CURVE('',#34448,#34426,#34450,.T.); +#34448 = VERTEX_POINT('',#34449); +#34449 = CARTESIAN_POINT('',(0.85,0.63,0.625)); +#34450 = SURFACE_CURVE('',#34451,(#34455,#34461),.PCURVE_S1.); +#34451 = LINE('',#34452,#34453); +#34452 = CARTESIAN_POINT('',(-1.,0.63,0.625)); +#34453 = VECTOR('',#34454,1.); +#34454 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34455 = PCURVE('',#34407,#34456); +#34456 = DEFINITIONAL_REPRESENTATION('',(#34457),#34460); +#34457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34458,#34459),.UNSPECIFIED., .F.,.F.,(2,2),(-1.85,-1.5),.PIECEWISE_BEZIER_KNOTS.); -#32066 = CARTESIAN_POINT('',(0.E+000,-1.85)); -#32067 = CARTESIAN_POINT('',(0.E+000,-1.5)); -#32068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32069 = PCURVE('',#31846,#32070); -#32070 = DEFINITIONAL_REPRESENTATION('',(#32071),#32075); -#32071 = LINE('',#32072,#32073); -#32072 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#32073 = VECTOR('',#32074,1.); -#32074 = DIRECTION('',(1.,0.E+000)); -#32075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32076 = ORIENTED_EDGE('',*,*,#32077,.T.); -#32077 = EDGE_CURVE('',#32056,#32007,#32078,.T.); -#32078 = SURFACE_CURVE('',#32079,(#32084,#32090),.PCURVE_S1.); -#32079 = CIRCLE('',#32080,0.15); -#32080 = AXIS2_PLACEMENT_3D('',#32081,#32082,#32083); -#32081 = CARTESIAN_POINT('',(0.85,0.63,0.475)); -#32082 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32083 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32084 = PCURVE('',#32015,#32085); -#32085 = DEFINITIONAL_REPRESENTATION('',(#32086),#32089); -#32086 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32087,#32088),.UNSPECIFIED., +#34458 = CARTESIAN_POINT('',(0.E+000,-1.85)); +#34459 = CARTESIAN_POINT('',(0.E+000,-1.5)); +#34460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34461 = PCURVE('',#34238,#34462); +#34462 = DEFINITIONAL_REPRESENTATION('',(#34463),#34467); +#34463 = LINE('',#34464,#34465); +#34464 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34465 = VECTOR('',#34466,1.); +#34466 = DIRECTION('',(1.,0.E+000)); +#34467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34468 = ORIENTED_EDGE('',*,*,#34469,.T.); +#34469 = EDGE_CURVE('',#34448,#34399,#34470,.T.); +#34470 = SURFACE_CURVE('',#34471,(#34476,#34482),.PCURVE_S1.); +#34471 = CIRCLE('',#34472,0.15); +#34472 = AXIS2_PLACEMENT_3D('',#34473,#34474,#34475); +#34473 = CARTESIAN_POINT('',(0.85,0.63,0.475)); +#34474 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34475 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34476 = PCURVE('',#34407,#34477); +#34477 = DEFINITIONAL_REPRESENTATION('',(#34478),#34481); +#34478 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34479,#34480),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32087 = CARTESIAN_POINT('',(0.E+000,-1.85)); -#32088 = CARTESIAN_POINT('',(1.570796326795,-1.85)); -#32089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#34479 = CARTESIAN_POINT('',(0.E+000,-1.85)); +#34480 = CARTESIAN_POINT('',(1.570796326795,-1.85)); +#34481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32090 = PCURVE('',#32091,#32096); -#32091 = SPHERICAL_SURFACE('',#32092,0.15); -#32092 = AXIS2_PLACEMENT_3D('',#32093,#32094,#32095); -#32093 = CARTESIAN_POINT('',(0.85,0.63,0.475)); -#32094 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32095 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32096 = DEFINITIONAL_REPRESENTATION('',(#32097),#32100); -#32097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32098,#32099),.UNSPECIFIED., +#34482 = PCURVE('',#34483,#34488); +#34483 = SPHERICAL_SURFACE('',#34484,0.15); +#34484 = AXIS2_PLACEMENT_3D('',#34485,#34486,#34487); +#34485 = CARTESIAN_POINT('',(0.85,0.63,0.475)); +#34486 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34487 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34488 = DEFINITIONAL_REPRESENTATION('',(#34489),#34492); +#34489 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34490,#34491),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32098 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#32099 = CARTESIAN_POINT('',(4.712388980385,1.570796326795)); -#32100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32101 = ADVANCED_FACE('',(#32102),#30266,.T.); -#32102 = FACE_BOUND('',#32103,.T.); -#32103 = EDGE_LOOP('',(#32104,#32105,#32106,#32107)); -#32104 = ORIENTED_EDGE('',*,*,#31956,.T.); -#32105 = ORIENTED_EDGE('',*,*,#30248,.T.); -#32106 = ORIENTED_EDGE('',*,*,#31051,.T.); -#32107 = ORIENTED_EDGE('',*,*,#32108,.T.); -#32108 = EDGE_CURVE('',#31052,#31957,#32109,.T.); -#32109 = SURFACE_CURVE('',#32110,(#32114,#32121),.PCURVE_S1.); -#32110 = LINE('',#32111,#32112); -#32111 = CARTESIAN_POINT('',(-0.85,0.78,0.625)); -#32112 = VECTOR('',#32113,1.); -#32113 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32114 = PCURVE('',#30266,#32115); -#32115 = DEFINITIONAL_REPRESENTATION('',(#32116),#32120); -#32116 = LINE('',#32117,#32118); -#32117 = CARTESIAN_POINT('',(0.E+000,0.15)); -#32118 = VECTOR('',#32119,1.); -#32119 = DIRECTION('',(1.,0.E+000)); -#32120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32121 = PCURVE('',#32122,#32127); -#32122 = CYLINDRICAL_SURFACE('',#32123,0.15); -#32123 = AXIS2_PLACEMENT_3D('',#32124,#32125,#32126); -#32124 = CARTESIAN_POINT('',(-0.85,0.63,0.625)); -#32125 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32126 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32127 = DEFINITIONAL_REPRESENTATION('',(#32128),#32131); -#32128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32129,#32130),.UNSPECIFIED., +#34490 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#34491 = CARTESIAN_POINT('',(4.712388980385,1.570796326795)); +#34492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34493 = ADVANCED_FACE('',(#34494),#32658,.T.); +#34494 = FACE_BOUND('',#34495,.T.); +#34495 = EDGE_LOOP('',(#34496,#34497,#34498,#34499)); +#34496 = ORIENTED_EDGE('',*,*,#34348,.T.); +#34497 = ORIENTED_EDGE('',*,*,#32640,.T.); +#34498 = ORIENTED_EDGE('',*,*,#33443,.T.); +#34499 = ORIENTED_EDGE('',*,*,#34500,.T.); +#34500 = EDGE_CURVE('',#33444,#34349,#34501,.T.); +#34501 = SURFACE_CURVE('',#34502,(#34506,#34513),.PCURVE_S1.); +#34502 = LINE('',#34503,#34504); +#34503 = CARTESIAN_POINT('',(-0.85,0.78,0.625)); +#34504 = VECTOR('',#34505,1.); +#34505 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34506 = PCURVE('',#32658,#34507); +#34507 = DEFINITIONAL_REPRESENTATION('',(#34508),#34512); +#34508 = LINE('',#34509,#34510); +#34509 = CARTESIAN_POINT('',(0.E+000,0.15)); +#34510 = VECTOR('',#34511,1.); +#34511 = DIRECTION('',(1.,0.E+000)); +#34512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34513 = PCURVE('',#34514,#34519); +#34514 = CYLINDRICAL_SURFACE('',#34515,0.15); +#34515 = AXIS2_PLACEMENT_3D('',#34516,#34517,#34518); +#34516 = CARTESIAN_POINT('',(-0.85,0.63,0.625)); +#34517 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34518 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34519 = DEFINITIONAL_REPRESENTATION('',(#34520),#34523); +#34520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34521,#34522),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32129 = CARTESIAN_POINT('',(1.570796326795,1.1)); -#32130 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#32131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32132 = ADVANCED_FACE('',(#32133),#30321,.T.); -#32133 = FACE_BOUND('',#32134,.T.); -#32134 = EDGE_LOOP('',(#32135,#32136,#32137,#32138)); -#32135 = ORIENTED_EDGE('',*,*,#31209,.T.); -#32136 = ORIENTED_EDGE('',*,*,#30305,.T.); -#32137 = ORIENTED_EDGE('',*,*,#32006,.T.); -#32138 = ORIENTED_EDGE('',*,*,#32139,.T.); -#32139 = EDGE_CURVE('',#32007,#31210,#32140,.T.); -#32140 = SURFACE_CURVE('',#32141,(#32145,#32152),.PCURVE_S1.); -#32141 = LINE('',#32142,#32143); -#32142 = CARTESIAN_POINT('',(0.85,0.78,-0.625)); -#32143 = VECTOR('',#32144,1.); -#32144 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32145 = PCURVE('',#30321,#32146); -#32146 = DEFINITIONAL_REPRESENTATION('',(#32147),#32151); -#32147 = LINE('',#32148,#32149); -#32148 = CARTESIAN_POINT('',(-1.25,1.85)); -#32149 = VECTOR('',#32150,1.); -#32150 = DIRECTION('',(-1.,0.E+000)); -#32151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32152 = PCURVE('',#32153,#32158); -#32153 = CYLINDRICAL_SURFACE('',#32154,0.15); -#32154 = AXIS2_PLACEMENT_3D('',#32155,#32156,#32157); -#32155 = CARTESIAN_POINT('',(0.85,0.63,0.625)); -#32156 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32157 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32158 = DEFINITIONAL_REPRESENTATION('',(#32159),#32162); -#32159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32160,#32161),.UNSPECIFIED., +#34521 = CARTESIAN_POINT('',(1.570796326795,1.1)); +#34522 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#34523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34524 = ADVANCED_FACE('',(#34525),#32713,.T.); +#34525 = FACE_BOUND('',#34526,.T.); +#34526 = EDGE_LOOP('',(#34527,#34528,#34529,#34530)); +#34527 = ORIENTED_EDGE('',*,*,#33601,.T.); +#34528 = ORIENTED_EDGE('',*,*,#32697,.T.); +#34529 = ORIENTED_EDGE('',*,*,#34398,.T.); +#34530 = ORIENTED_EDGE('',*,*,#34531,.T.); +#34531 = EDGE_CURVE('',#34399,#33602,#34532,.T.); +#34532 = SURFACE_CURVE('',#34533,(#34537,#34544),.PCURVE_S1.); +#34533 = LINE('',#34534,#34535); +#34534 = CARTESIAN_POINT('',(0.85,0.78,-0.625)); +#34535 = VECTOR('',#34536,1.); +#34536 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34537 = PCURVE('',#32713,#34538); +#34538 = DEFINITIONAL_REPRESENTATION('',(#34539),#34543); +#34539 = LINE('',#34540,#34541); +#34540 = CARTESIAN_POINT('',(-1.25,1.85)); +#34541 = VECTOR('',#34542,1.); +#34542 = DIRECTION('',(-1.,0.E+000)); +#34543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34544 = PCURVE('',#34545,#34550); +#34545 = CYLINDRICAL_SURFACE('',#34546,0.15); +#34546 = AXIS2_PLACEMENT_3D('',#34547,#34548,#34549); +#34547 = CARTESIAN_POINT('',(0.85,0.63,0.625)); +#34548 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34549 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34550 = DEFINITIONAL_REPRESENTATION('',(#34551),#34554); +#34551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34552,#34553),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32160 = CARTESIAN_POINT('',(1.570796326795,-0.15)); -#32161 = CARTESIAN_POINT('',(1.570796326795,-1.1)); -#32162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32163 = ADVANCED_FACE('',(#32164),#31789,.F.); -#32164 = FACE_BOUND('',#32165,.T.); -#32165 = EDGE_LOOP('',(#32166,#32192,#32193,#32218)); -#32166 = ORIENTED_EDGE('',*,*,#32167,.F.); -#32167 = EDGE_CURVE('',#31908,#31748,#32168,.T.); -#32168 = SURFACE_CURVE('',#32169,(#32173,#32180),.PCURVE_S1.); -#32169 = LINE('',#32170,#32171); -#32170 = CARTESIAN_POINT('',(-0.5,0.78,0.625)); -#32171 = VECTOR('',#32172,1.); -#32172 = DIRECTION('',(1.390002785238E-016,-1.,0.E+000)); -#32173 = PCURVE('',#31789,#32174); -#32174 = DEFINITIONAL_REPRESENTATION('',(#32175),#32179); -#32175 = LINE('',#32176,#32177); -#32176 = CARTESIAN_POINT('',(-0.5,1.110223024625E-016)); -#32177 = VECTOR('',#32178,1.); -#32178 = DIRECTION('',(-1.390002785238E-016,-1.)); -#32179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32180 = PCURVE('',#32181,#32186); -#32181 = PLANE('',#32182); -#32182 = AXIS2_PLACEMENT_3D('',#32183,#32184,#32185); -#32183 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#32184 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32185 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32186 = DEFINITIONAL_REPRESENTATION('',(#32187),#32191); -#32187 = LINE('',#32188,#32189); -#32188 = CARTESIAN_POINT('',(-0.5,1.110223024625E-016)); -#32189 = VECTOR('',#32190,1.); -#32190 = DIRECTION('',(-1.390002785238E-016,-1.)); -#32191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32192 = ORIENTED_EDGE('',*,*,#31907,.T.); -#32193 = ORIENTED_EDGE('',*,*,#32194,.T.); -#32194 = EDGE_CURVE('',#31910,#31775,#32195,.T.); -#32195 = SURFACE_CURVE('',#32196,(#32200,#32207),.PCURVE_S1.); -#32196 = LINE('',#32197,#32198); -#32197 = CARTESIAN_POINT('',(-0.85,0.78,0.625)); -#32198 = VECTOR('',#32199,1.); -#32199 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32200 = PCURVE('',#31789,#32201); -#32201 = DEFINITIONAL_REPRESENTATION('',(#32202),#32206); -#32202 = LINE('',#32203,#32204); -#32203 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#32204 = VECTOR('',#32205,1.); -#32205 = DIRECTION('',(0.E+000,-1.)); -#32206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32207 = PCURVE('',#32208,#32213); -#32208 = CYLINDRICAL_SURFACE('',#32209,0.15); -#32209 = AXIS2_PLACEMENT_3D('',#32210,#32211,#32212); -#32210 = CARTESIAN_POINT('',(-0.85,0.78,0.475)); -#32211 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32212 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32213 = DEFINITIONAL_REPRESENTATION('',(#32214),#32217); -#32214 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32215,#32216),.UNSPECIFIED., +#34552 = CARTESIAN_POINT('',(1.570796326795,-0.15)); +#34553 = CARTESIAN_POINT('',(1.570796326795,-1.1)); +#34554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34555 = ADVANCED_FACE('',(#34556),#34181,.F.); +#34556 = FACE_BOUND('',#34557,.T.); +#34557 = EDGE_LOOP('',(#34558,#34584,#34585,#34610)); +#34558 = ORIENTED_EDGE('',*,*,#34559,.F.); +#34559 = EDGE_CURVE('',#34300,#34140,#34560,.T.); +#34560 = SURFACE_CURVE('',#34561,(#34565,#34572),.PCURVE_S1.); +#34561 = LINE('',#34562,#34563); +#34562 = CARTESIAN_POINT('',(-0.5,0.78,0.625)); +#34563 = VECTOR('',#34564,1.); +#34564 = DIRECTION('',(1.390002785238E-016,-1.,0.E+000)); +#34565 = PCURVE('',#34181,#34566); +#34566 = DEFINITIONAL_REPRESENTATION('',(#34567),#34571); +#34567 = LINE('',#34568,#34569); +#34568 = CARTESIAN_POINT('',(-0.5,1.110223024625E-016)); +#34569 = VECTOR('',#34570,1.); +#34570 = DIRECTION('',(-1.390002785238E-016,-1.)); +#34571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34572 = PCURVE('',#34573,#34578); +#34573 = PLANE('',#34574); +#34574 = AXIS2_PLACEMENT_3D('',#34575,#34576,#34577); +#34575 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#34576 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34577 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34578 = DEFINITIONAL_REPRESENTATION('',(#34579),#34583); +#34579 = LINE('',#34580,#34581); +#34580 = CARTESIAN_POINT('',(-0.5,1.110223024625E-016)); +#34581 = VECTOR('',#34582,1.); +#34582 = DIRECTION('',(-1.390002785238E-016,-1.)); +#34583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34584 = ORIENTED_EDGE('',*,*,#34299,.T.); +#34585 = ORIENTED_EDGE('',*,*,#34586,.T.); +#34586 = EDGE_CURVE('',#34302,#34167,#34587,.T.); +#34587 = SURFACE_CURVE('',#34588,(#34592,#34599),.PCURVE_S1.); +#34588 = LINE('',#34589,#34590); +#34589 = CARTESIAN_POINT('',(-0.85,0.78,0.625)); +#34590 = VECTOR('',#34591,1.); +#34591 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34592 = PCURVE('',#34181,#34593); +#34593 = DEFINITIONAL_REPRESENTATION('',(#34594),#34598); +#34594 = LINE('',#34595,#34596); +#34595 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#34596 = VECTOR('',#34597,1.); +#34597 = DIRECTION('',(0.E+000,-1.)); +#34598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34599 = PCURVE('',#34600,#34605); +#34600 = CYLINDRICAL_SURFACE('',#34601,0.15); +#34601 = AXIS2_PLACEMENT_3D('',#34602,#34603,#34604); +#34602 = CARTESIAN_POINT('',(-0.85,0.78,0.475)); +#34603 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34604 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34605 = DEFINITIONAL_REPRESENTATION('',(#34606),#34609); +#34606 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34607,#34608),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.63),.PIECEWISE_BEZIER_KNOTS.); -#32215 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#32216 = CARTESIAN_POINT('',(3.14159265359,0.63)); -#32217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32218 = ORIENTED_EDGE('',*,*,#31774,.T.); -#32219 = ADVANCED_FACE('',(#32220),#31846,.F.); -#32220 = FACE_BOUND('',#32221,.T.); -#32221 = EDGE_LOOP('',(#32222,#32243,#32244,#32269)); -#32222 = ORIENTED_EDGE('',*,*,#32223,.F.); -#32223 = EDGE_CURVE('',#31830,#32034,#32224,.T.); -#32224 = SURFACE_CURVE('',#32225,(#32229,#32236),.PCURVE_S1.); -#32225 = LINE('',#32226,#32227); -#32226 = CARTESIAN_POINT('',(0.5,0.78,0.625)); -#32227 = VECTOR('',#32228,1.); -#32228 = DIRECTION('',(1.390002785238E-016,1.,0.E+000)); -#32229 = PCURVE('',#31846,#32230); -#32230 = DEFINITIONAL_REPRESENTATION('',(#32231),#32235); -#32231 = LINE('',#32232,#32233); -#32232 = CARTESIAN_POINT('',(-1.5,-2.22044604925E-016)); -#32233 = VECTOR('',#32234,1.); -#32234 = DIRECTION('',(-1.390002785238E-016,1.)); -#32235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32236 = PCURVE('',#32181,#32237); -#32237 = DEFINITIONAL_REPRESENTATION('',(#32238),#32242); -#32238 = LINE('',#32239,#32240); -#32239 = CARTESIAN_POINT('',(-1.5,-2.22044604925E-016)); -#32240 = VECTOR('',#32241,1.); -#32241 = DIRECTION('',(-1.390002785238E-016,1.)); -#32242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32243 = ORIENTED_EDGE('',*,*,#31829,.T.); -#32244 = ORIENTED_EDGE('',*,*,#32245,.T.); -#32245 = EDGE_CURVE('',#31832,#32056,#32246,.T.); -#32246 = SURFACE_CURVE('',#32247,(#32251,#32258),.PCURVE_S1.); -#32247 = LINE('',#32248,#32249); -#32248 = CARTESIAN_POINT('',(0.85,0.78,0.625)); -#32249 = VECTOR('',#32250,1.); -#32250 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32251 = PCURVE('',#31846,#32252); -#32252 = DEFINITIONAL_REPRESENTATION('',(#32253),#32257); -#32253 = LINE('',#32254,#32255); -#32254 = CARTESIAN_POINT('',(-1.85,0.E+000)); -#32255 = VECTOR('',#32256,1.); -#32256 = DIRECTION('',(0.E+000,1.)); -#32257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32258 = PCURVE('',#32259,#32264); -#32259 = CYLINDRICAL_SURFACE('',#32260,0.15); -#32260 = AXIS2_PLACEMENT_3D('',#32261,#32262,#32263); -#32261 = CARTESIAN_POINT('',(0.85,0.78,0.475)); -#32262 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32263 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32264 = DEFINITIONAL_REPRESENTATION('',(#32265),#32268); -#32265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32266,#32267),.UNSPECIFIED., +#34607 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#34608 = CARTESIAN_POINT('',(3.14159265359,0.63)); +#34609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34610 = ORIENTED_EDGE('',*,*,#34166,.T.); +#34611 = ADVANCED_FACE('',(#34612),#34238,.F.); +#34612 = FACE_BOUND('',#34613,.T.); +#34613 = EDGE_LOOP('',(#34614,#34635,#34636,#34661)); +#34614 = ORIENTED_EDGE('',*,*,#34615,.F.); +#34615 = EDGE_CURVE('',#34222,#34426,#34616,.T.); +#34616 = SURFACE_CURVE('',#34617,(#34621,#34628),.PCURVE_S1.); +#34617 = LINE('',#34618,#34619); +#34618 = CARTESIAN_POINT('',(0.5,0.78,0.625)); +#34619 = VECTOR('',#34620,1.); +#34620 = DIRECTION('',(1.390002785238E-016,1.,0.E+000)); +#34621 = PCURVE('',#34238,#34622); +#34622 = DEFINITIONAL_REPRESENTATION('',(#34623),#34627); +#34623 = LINE('',#34624,#34625); +#34624 = CARTESIAN_POINT('',(-1.5,-2.22044604925E-016)); +#34625 = VECTOR('',#34626,1.); +#34626 = DIRECTION('',(-1.390002785238E-016,1.)); +#34627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34628 = PCURVE('',#34573,#34629); +#34629 = DEFINITIONAL_REPRESENTATION('',(#34630),#34634); +#34630 = LINE('',#34631,#34632); +#34631 = CARTESIAN_POINT('',(-1.5,-2.22044604925E-016)); +#34632 = VECTOR('',#34633,1.); +#34633 = DIRECTION('',(-1.390002785238E-016,1.)); +#34634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34635 = ORIENTED_EDGE('',*,*,#34221,.T.); +#34636 = ORIENTED_EDGE('',*,*,#34637,.T.); +#34637 = EDGE_CURVE('',#34224,#34448,#34638,.T.); +#34638 = SURFACE_CURVE('',#34639,(#34643,#34650),.PCURVE_S1.); +#34639 = LINE('',#34640,#34641); +#34640 = CARTESIAN_POINT('',(0.85,0.78,0.625)); +#34641 = VECTOR('',#34642,1.); +#34642 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34643 = PCURVE('',#34238,#34644); +#34644 = DEFINITIONAL_REPRESENTATION('',(#34645),#34649); +#34645 = LINE('',#34646,#34647); +#34646 = CARTESIAN_POINT('',(-1.85,0.E+000)); +#34647 = VECTOR('',#34648,1.); +#34648 = DIRECTION('',(0.E+000,1.)); +#34649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34650 = PCURVE('',#34651,#34656); +#34651 = CYLINDRICAL_SURFACE('',#34652,0.15); +#34652 = AXIS2_PLACEMENT_3D('',#34653,#34654,#34655); +#34653 = CARTESIAN_POINT('',(0.85,0.78,0.475)); +#34654 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34655 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34656 = DEFINITIONAL_REPRESENTATION('',(#34657),#34660); +#34657 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34658,#34659),.UNSPECIFIED., .F.,.F.,(2,2),(-0.63,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32266 = CARTESIAN_POINT('',(3.14159265359,0.63)); -#32267 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#32268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32269 = ORIENTED_EDGE('',*,*,#32055,.T.); -#32270 = ADVANCED_FACE('',(#32271),#32285,.F.); -#32271 = FACE_BOUND('',#32272,.T.); -#32272 = EDGE_LOOP('',(#32273,#32302,#32324,#32346)); -#32273 = ORIENTED_EDGE('',*,*,#32274,.T.); -#32274 = EDGE_CURVE('',#32275,#32277,#32279,.T.); -#32275 = VERTEX_POINT('',#32276); -#32276 = CARTESIAN_POINT('',(-1.,0.63,0.475)); -#32277 = VERTEX_POINT('',#32278); -#32278 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); -#32279 = SURFACE_CURVE('',#32280,(#32284,#32296),.PCURVE_S1.); -#32280 = LINE('',#32281,#32282); -#32281 = CARTESIAN_POINT('',(-1.,0.63,-0.625)); -#32282 = VECTOR('',#32283,1.); -#32283 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32284 = PCURVE('',#32285,#32290); -#32285 = PLANE('',#32286); -#32286 = AXIS2_PLACEMENT_3D('',#32287,#32288,#32289); -#32287 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); -#32288 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32289 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32290 = DEFINITIONAL_REPRESENTATION('',(#32291),#32295); -#32291 = LINE('',#32292,#32293); -#32292 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#32293 = VECTOR('',#32294,1.); -#32294 = DIRECTION('',(1.,0.E+000)); -#32295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32296 = PCURVE('',#32122,#32297); -#32297 = DEFINITIONAL_REPRESENTATION('',(#32298),#32301); -#32298 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32299,#32300),.UNSPECIFIED., +#34658 = CARTESIAN_POINT('',(3.14159265359,0.63)); +#34659 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#34660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34661 = ORIENTED_EDGE('',*,*,#34447,.T.); +#34662 = ADVANCED_FACE('',(#34663),#34677,.F.); +#34663 = FACE_BOUND('',#34664,.T.); +#34664 = EDGE_LOOP('',(#34665,#34694,#34716,#34738)); +#34665 = ORIENTED_EDGE('',*,*,#34666,.T.); +#34666 = EDGE_CURVE('',#34667,#34669,#34671,.T.); +#34667 = VERTEX_POINT('',#34668); +#34668 = CARTESIAN_POINT('',(-1.,0.63,0.475)); +#34669 = VERTEX_POINT('',#34670); +#34670 = CARTESIAN_POINT('',(-1.,0.63,-0.475)); +#34671 = SURFACE_CURVE('',#34672,(#34676,#34688),.PCURVE_S1.); +#34672 = LINE('',#34673,#34674); +#34673 = CARTESIAN_POINT('',(-1.,0.63,-0.625)); +#34674 = VECTOR('',#34675,1.); +#34675 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34676 = PCURVE('',#34677,#34682); +#34677 = PLANE('',#34678); +#34678 = AXIS2_PLACEMENT_3D('',#34679,#34680,#34681); +#34679 = CARTESIAN_POINT('',(-1.,0.78,-0.625)); +#34680 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34681 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34682 = DEFINITIONAL_REPRESENTATION('',(#34683),#34687); +#34683 = LINE('',#34684,#34685); +#34684 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34685 = VECTOR('',#34686,1.); +#34686 = DIRECTION('',(1.,0.E+000)); +#34687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34688 = PCURVE('',#34514,#34689); +#34689 = DEFINITIONAL_REPRESENTATION('',(#34690),#34693); +#34690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34691,#34692),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32299 = CARTESIAN_POINT('',(0.E+000,0.15)); -#32300 = CARTESIAN_POINT('',(0.E+000,1.1)); -#32301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32302 = ORIENTED_EDGE('',*,*,#32303,.T.); -#32303 = EDGE_CURVE('',#32277,#32304,#32306,.T.); -#32304 = VERTEX_POINT('',#32305); -#32305 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); -#32306 = SURFACE_CURVE('',#32307,(#32311,#32318),.PCURVE_S1.); -#32307 = LINE('',#32308,#32309); -#32308 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); -#32309 = VECTOR('',#32310,1.); -#32310 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32311 = PCURVE('',#32285,#32312); -#32312 = DEFINITIONAL_REPRESENTATION('',(#32313),#32317); -#32313 = LINE('',#32314,#32315); -#32314 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#32315 = VECTOR('',#32316,1.); -#32316 = DIRECTION('',(0.E+000,-1.)); -#32317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32318 = PCURVE('',#31552,#32319); -#32319 = DEFINITIONAL_REPRESENTATION('',(#32320),#32323); -#32320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32321,#32322),.UNSPECIFIED., +#34691 = CARTESIAN_POINT('',(0.E+000,0.15)); +#34692 = CARTESIAN_POINT('',(0.E+000,1.1)); +#34693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34694 = ORIENTED_EDGE('',*,*,#34695,.T.); +#34695 = EDGE_CURVE('',#34669,#34696,#34698,.T.); +#34696 = VERTEX_POINT('',#34697); +#34697 = CARTESIAN_POINT('',(-1.,0.15,-0.475)); +#34698 = SURFACE_CURVE('',#34699,(#34703,#34710),.PCURVE_S1.); +#34699 = LINE('',#34700,#34701); +#34700 = CARTESIAN_POINT('',(-1.,0.78,-0.475)); +#34701 = VECTOR('',#34702,1.); +#34702 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34703 = PCURVE('',#34677,#34704); +#34704 = DEFINITIONAL_REPRESENTATION('',(#34705),#34709); +#34705 = LINE('',#34706,#34707); +#34706 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#34707 = VECTOR('',#34708,1.); +#34708 = DIRECTION('',(0.E+000,-1.)); +#34709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34710 = PCURVE('',#33944,#34711); +#34711 = DEFINITIONAL_REPRESENTATION('',(#34712),#34715); +#34712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34713,#34714),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.63),.PIECEWISE_BEZIER_KNOTS.); -#32321 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#32322 = CARTESIAN_POINT('',(4.712388980385,0.63)); -#32323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32324 = ORIENTED_EDGE('',*,*,#32325,.T.); -#32325 = EDGE_CURVE('',#32304,#32326,#32328,.T.); -#32326 = VERTEX_POINT('',#32327); -#32327 = CARTESIAN_POINT('',(-1.,0.15,0.475)); -#32328 = SURFACE_CURVE('',#32329,(#32333,#32340),.PCURVE_S1.); -#32329 = LINE('',#32330,#32331); -#32330 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); -#32331 = VECTOR('',#32332,1.); -#32332 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32333 = PCURVE('',#32285,#32334); -#32334 = DEFINITIONAL_REPRESENTATION('',(#32335),#32339); -#32335 = LINE('',#32336,#32337); -#32336 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#32337 = VECTOR('',#32338,1.); -#32338 = DIRECTION('',(-1.,0.E+000)); -#32339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32340 = PCURVE('',#31337,#32341); -#32341 = DEFINITIONAL_REPRESENTATION('',(#32342),#32345); -#32342 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32343,#32344),.UNSPECIFIED., +#34713 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#34714 = CARTESIAN_POINT('',(4.712388980385,0.63)); +#34715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34716 = ORIENTED_EDGE('',*,*,#34717,.T.); +#34717 = EDGE_CURVE('',#34696,#34718,#34720,.T.); +#34718 = VERTEX_POINT('',#34719); +#34719 = CARTESIAN_POINT('',(-1.,0.15,0.475)); +#34720 = SURFACE_CURVE('',#34721,(#34725,#34732),.PCURVE_S1.); +#34721 = LINE('',#34722,#34723); +#34722 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); +#34723 = VECTOR('',#34724,1.); +#34724 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34725 = PCURVE('',#34677,#34726); +#34726 = DEFINITIONAL_REPRESENTATION('',(#34727),#34731); +#34727 = LINE('',#34728,#34729); +#34728 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34729 = VECTOR('',#34730,1.); +#34730 = DIRECTION('',(-1.,0.E+000)); +#34731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34732 = PCURVE('',#33729,#34733); +#34733 = DEFINITIONAL_REPRESENTATION('',(#34734),#34737); +#34734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34735,#34736),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,1.1),.PIECEWISE_BEZIER_KNOTS.); -#32343 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#32344 = CARTESIAN_POINT('',(3.14159265359,1.1)); -#32345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32346 = ORIENTED_EDGE('',*,*,#32347,.T.); -#32347 = EDGE_CURVE('',#32326,#32275,#32348,.T.); -#32348 = SURFACE_CURVE('',#32349,(#32353,#32360),.PCURVE_S1.); -#32349 = LINE('',#32350,#32351); -#32350 = CARTESIAN_POINT('',(-1.,0.78,0.475)); -#32351 = VECTOR('',#32352,1.); -#32352 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32353 = PCURVE('',#32285,#32354); -#32354 = DEFINITIONAL_REPRESENTATION('',(#32355),#32359); -#32355 = LINE('',#32356,#32357); -#32356 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#32357 = VECTOR('',#32358,1.); -#32358 = DIRECTION('',(0.E+000,1.)); -#32359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32360 = PCURVE('',#32208,#32361); -#32361 = DEFINITIONAL_REPRESENTATION('',(#32362),#32365); -#32362 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32363,#32364),.UNSPECIFIED., +#34735 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#34736 = CARTESIAN_POINT('',(3.14159265359,1.1)); +#34737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34738 = ORIENTED_EDGE('',*,*,#34739,.T.); +#34739 = EDGE_CURVE('',#34718,#34667,#34740,.T.); +#34740 = SURFACE_CURVE('',#34741,(#34745,#34752),.PCURVE_S1.); +#34741 = LINE('',#34742,#34743); +#34742 = CARTESIAN_POINT('',(-1.,0.78,0.475)); +#34743 = VECTOR('',#34744,1.); +#34744 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34745 = PCURVE('',#34677,#34746); +#34746 = DEFINITIONAL_REPRESENTATION('',(#34747),#34751); +#34747 = LINE('',#34748,#34749); +#34748 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#34749 = VECTOR('',#34750,1.); +#34750 = DIRECTION('',(0.E+000,1.)); +#34751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34752 = PCURVE('',#34600,#34753); +#34753 = DEFINITIONAL_REPRESENTATION('',(#34754),#34757); +#34754 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34755,#34756),.UNSPECIFIED., .F.,.F.,(2,2),(-0.63,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32363 = CARTESIAN_POINT('',(4.712388980385,0.63)); -#32364 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#32365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32366 = ADVANCED_FACE('',(#32367),#32181,.F.); -#32367 = FACE_BOUND('',#32368,.T.); -#32368 = EDGE_LOOP('',(#32369,#32389,#32390,#32410)); -#32369 = ORIENTED_EDGE('',*,*,#32370,.T.); -#32370 = EDGE_CURVE('',#32034,#31908,#32371,.T.); -#32371 = SURFACE_CURVE('',#32372,(#32376,#32383),.PCURVE_S1.); -#32372 = LINE('',#32373,#32374); -#32373 = CARTESIAN_POINT('',(-1.,0.63,0.625)); -#32374 = VECTOR('',#32375,1.); -#32375 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32376 = PCURVE('',#32181,#32377); -#32377 = DEFINITIONAL_REPRESENTATION('',(#32378),#32382); -#32378 = LINE('',#32379,#32380); -#32379 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#32380 = VECTOR('',#32381,1.); -#32381 = DIRECTION('',(1.,0.E+000)); -#32382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32383 = PCURVE('',#30294,#32384); -#32384 = DEFINITIONAL_REPRESENTATION('',(#32385),#32388); -#32385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32386,#32387),.UNSPECIFIED., +#34755 = CARTESIAN_POINT('',(4.712388980385,0.63)); +#34756 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#34757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34758 = ADVANCED_FACE('',(#34759),#34573,.F.); +#34759 = FACE_BOUND('',#34760,.T.); +#34760 = EDGE_LOOP('',(#34761,#34781,#34782,#34802)); +#34761 = ORIENTED_EDGE('',*,*,#34762,.T.); +#34762 = EDGE_CURVE('',#34426,#34300,#34763,.T.); +#34763 = SURFACE_CURVE('',#34764,(#34768,#34775),.PCURVE_S1.); +#34764 = LINE('',#34765,#34766); +#34765 = CARTESIAN_POINT('',(-1.,0.63,0.625)); +#34766 = VECTOR('',#34767,1.); +#34767 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34768 = PCURVE('',#34573,#34769); +#34769 = DEFINITIONAL_REPRESENTATION('',(#34770),#34774); +#34770 = LINE('',#34771,#34772); +#34771 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34772 = VECTOR('',#34773,1.); +#34773 = DIRECTION('',(1.,0.E+000)); +#34774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34775 = PCURVE('',#32686,#34776); +#34776 = DEFINITIONAL_REPRESENTATION('',(#34777),#34780); +#34777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34778,#34779),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#32386 = CARTESIAN_POINT('',(0.E+000,-1.5)); -#32387 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#32388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32389 = ORIENTED_EDGE('',*,*,#32167,.T.); -#32390 = ORIENTED_EDGE('',*,*,#32391,.T.); -#32391 = EDGE_CURVE('',#31748,#31830,#32392,.T.); -#32392 = SURFACE_CURVE('',#32393,(#32397,#32404),.PCURVE_S1.); -#32393 = LINE('',#32394,#32395); -#32394 = CARTESIAN_POINT('',(-1.,0.15,0.625)); -#32395 = VECTOR('',#32396,1.); -#32396 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32397 = PCURVE('',#32181,#32398); -#32398 = DEFINITIONAL_REPRESENTATION('',(#32399),#32403); -#32399 = LINE('',#32400,#32401); -#32400 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#32401 = VECTOR('',#32402,1.); -#32402 = DIRECTION('',(-1.,0.E+000)); -#32403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32404 = PCURVE('',#31763,#32405); -#32405 = DEFINITIONAL_REPRESENTATION('',(#32406),#32409); -#32406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32407,#32408),.UNSPECIFIED., +#34778 = CARTESIAN_POINT('',(0.E+000,-1.5)); +#34779 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#34780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34781 = ORIENTED_EDGE('',*,*,#34559,.T.); +#34782 = ORIENTED_EDGE('',*,*,#34783,.T.); +#34783 = EDGE_CURVE('',#34140,#34222,#34784,.T.); +#34784 = SURFACE_CURVE('',#34785,(#34789,#34796),.PCURVE_S1.); +#34785 = LINE('',#34786,#34787); +#34786 = CARTESIAN_POINT('',(-1.,0.15,0.625)); +#34787 = VECTOR('',#34788,1.); +#34788 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34789 = PCURVE('',#34573,#34790); +#34790 = DEFINITIONAL_REPRESENTATION('',(#34791),#34795); +#34791 = LINE('',#34792,#34793); +#34792 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34793 = VECTOR('',#34794,1.); +#34794 = DIRECTION('',(-1.,0.E+000)); +#34795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34796 = PCURVE('',#34155,#34797); +#34797 = DEFINITIONAL_REPRESENTATION('',(#34798),#34801); +#34798 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34799,#34800),.UNSPECIFIED., .F.,.F.,(2,2),(0.5,1.5),.PIECEWISE_BEZIER_KNOTS.); -#32407 = CARTESIAN_POINT('',(3.14159265359,0.5)); -#32408 = CARTESIAN_POINT('',(3.14159265359,1.5)); -#32409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32410 = ORIENTED_EDGE('',*,*,#32223,.T.); -#32411 = ADVANCED_FACE('',(#32412),#32426,.F.); -#32412 = FACE_BOUND('',#32413,.T.); -#32413 = EDGE_LOOP('',(#32414,#32443,#32465,#32487)); -#32414 = ORIENTED_EDGE('',*,*,#32415,.T.); -#32415 = EDGE_CURVE('',#32416,#32418,#32420,.T.); -#32416 = VERTEX_POINT('',#32417); -#32417 = CARTESIAN_POINT('',(1.,0.63,0.475)); -#32418 = VERTEX_POINT('',#32419); -#32419 = CARTESIAN_POINT('',(1.,0.15,0.475)); -#32420 = SURFACE_CURVE('',#32421,(#32425,#32437),.PCURVE_S1.); -#32421 = LINE('',#32422,#32423); -#32422 = CARTESIAN_POINT('',(1.,0.78,0.475)); -#32423 = VECTOR('',#32424,1.); -#32424 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32425 = PCURVE('',#32426,#32431); -#32426 = PLANE('',#32427); -#32427 = AXIS2_PLACEMENT_3D('',#32428,#32429,#32430); -#32428 = CARTESIAN_POINT('',(1.,0.78,-0.625)); -#32429 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32430 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32431 = DEFINITIONAL_REPRESENTATION('',(#32432),#32436); -#32432 = LINE('',#32433,#32434); -#32433 = CARTESIAN_POINT('',(1.1,0.E+000)); -#32434 = VECTOR('',#32435,1.); -#32435 = DIRECTION('',(0.E+000,-1.)); -#32436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32437 = PCURVE('',#32259,#32438); -#32438 = DEFINITIONAL_REPRESENTATION('',(#32439),#32442); -#32439 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32440,#32441),.UNSPECIFIED., +#34799 = CARTESIAN_POINT('',(3.14159265359,0.5)); +#34800 = CARTESIAN_POINT('',(3.14159265359,1.5)); +#34801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34802 = ORIENTED_EDGE('',*,*,#34615,.T.); +#34803 = ADVANCED_FACE('',(#34804),#34818,.F.); +#34804 = FACE_BOUND('',#34805,.T.); +#34805 = EDGE_LOOP('',(#34806,#34835,#34857,#34879)); +#34806 = ORIENTED_EDGE('',*,*,#34807,.T.); +#34807 = EDGE_CURVE('',#34808,#34810,#34812,.T.); +#34808 = VERTEX_POINT('',#34809); +#34809 = CARTESIAN_POINT('',(1.,0.63,0.475)); +#34810 = VERTEX_POINT('',#34811); +#34811 = CARTESIAN_POINT('',(1.,0.15,0.475)); +#34812 = SURFACE_CURVE('',#34813,(#34817,#34829),.PCURVE_S1.); +#34813 = LINE('',#34814,#34815); +#34814 = CARTESIAN_POINT('',(1.,0.78,0.475)); +#34815 = VECTOR('',#34816,1.); +#34816 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#34817 = PCURVE('',#34818,#34823); +#34818 = PLANE('',#34819); +#34819 = AXIS2_PLACEMENT_3D('',#34820,#34821,#34822); +#34820 = CARTESIAN_POINT('',(1.,0.78,-0.625)); +#34821 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34822 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34823 = DEFINITIONAL_REPRESENTATION('',(#34824),#34828); +#34824 = LINE('',#34825,#34826); +#34825 = CARTESIAN_POINT('',(1.1,0.E+000)); +#34826 = VECTOR('',#34827,1.); +#34827 = DIRECTION('',(0.E+000,-1.)); +#34828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34829 = PCURVE('',#34651,#34830); +#34830 = DEFINITIONAL_REPRESENTATION('',(#34831),#34834); +#34831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34832,#34833),.UNSPECIFIED., .F.,.F.,(2,2),(0.15,0.63),.PIECEWISE_BEZIER_KNOTS.); -#32440 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#32441 = CARTESIAN_POINT('',(1.570796326795,0.63)); -#32442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32443 = ORIENTED_EDGE('',*,*,#32444,.T.); -#32444 = EDGE_CURVE('',#32418,#32445,#32447,.T.); -#32445 = VERTEX_POINT('',#32446); -#32446 = CARTESIAN_POINT('',(1.,0.15,-0.475)); -#32447 = SURFACE_CURVE('',#32448,(#32452,#32459),.PCURVE_S1.); -#32448 = LINE('',#32449,#32450); -#32449 = CARTESIAN_POINT('',(1.,0.15,-0.625)); -#32450 = VECTOR('',#32451,1.); -#32451 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32452 = PCURVE('',#32426,#32453); -#32453 = DEFINITIONAL_REPRESENTATION('',(#32454),#32458); -#32454 = LINE('',#32455,#32456); -#32455 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#32456 = VECTOR('',#32457,1.); -#32457 = DIRECTION('',(-1.,0.E+000)); -#32458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32459 = PCURVE('',#31449,#32460); -#32460 = DEFINITIONAL_REPRESENTATION('',(#32461),#32464); -#32461 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32462,#32463),.UNSPECIFIED., +#34832 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#34833 = CARTESIAN_POINT('',(1.570796326795,0.63)); +#34834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34835 = ORIENTED_EDGE('',*,*,#34836,.T.); +#34836 = EDGE_CURVE('',#34810,#34837,#34839,.T.); +#34837 = VERTEX_POINT('',#34838); +#34838 = CARTESIAN_POINT('',(1.,0.15,-0.475)); +#34839 = SURFACE_CURVE('',#34840,(#34844,#34851),.PCURVE_S1.); +#34840 = LINE('',#34841,#34842); +#34841 = CARTESIAN_POINT('',(1.,0.15,-0.625)); +#34842 = VECTOR('',#34843,1.); +#34843 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#34844 = PCURVE('',#34818,#34845); +#34845 = DEFINITIONAL_REPRESENTATION('',(#34846),#34850); +#34846 = LINE('',#34847,#34848); +#34847 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34848 = VECTOR('',#34849,1.); +#34849 = DIRECTION('',(-1.,0.E+000)); +#34850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34851 = PCURVE('',#33841,#34852); +#34852 = DEFINITIONAL_REPRESENTATION('',(#34853),#34856); +#34853 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34854,#34855),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32462 = CARTESIAN_POINT('',(3.14159265359,-1.1)); -#32463 = CARTESIAN_POINT('',(3.14159265359,-0.15)); -#32464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32465 = ORIENTED_EDGE('',*,*,#32466,.T.); -#32466 = EDGE_CURVE('',#32445,#32467,#32469,.T.); -#32467 = VERTEX_POINT('',#32468); -#32468 = CARTESIAN_POINT('',(1.,0.63,-0.475)); -#32469 = SURFACE_CURVE('',#32470,(#32474,#32481),.PCURVE_S1.); -#32470 = LINE('',#32471,#32472); -#32471 = CARTESIAN_POINT('',(1.,0.78,-0.475)); -#32472 = VECTOR('',#32473,1.); -#32473 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32474 = PCURVE('',#32426,#32475); -#32475 = DEFINITIONAL_REPRESENTATION('',(#32476),#32480); -#32476 = LINE('',#32477,#32478); -#32477 = CARTESIAN_POINT('',(0.15,0.E+000)); -#32478 = VECTOR('',#32479,1.); -#32479 = DIRECTION('',(0.E+000,1.)); -#32480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32481 = PCURVE('',#31607,#32482); -#32482 = DEFINITIONAL_REPRESENTATION('',(#32483),#32486); -#32483 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32484,#32485),.UNSPECIFIED., +#34854 = CARTESIAN_POINT('',(3.14159265359,-1.1)); +#34855 = CARTESIAN_POINT('',(3.14159265359,-0.15)); +#34856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34857 = ORIENTED_EDGE('',*,*,#34858,.T.); +#34858 = EDGE_CURVE('',#34837,#34859,#34861,.T.); +#34859 = VERTEX_POINT('',#34860); +#34860 = CARTESIAN_POINT('',(1.,0.63,-0.475)); +#34861 = SURFACE_CURVE('',#34862,(#34866,#34873),.PCURVE_S1.); +#34862 = LINE('',#34863,#34864); +#34863 = CARTESIAN_POINT('',(1.,0.78,-0.475)); +#34864 = VECTOR('',#34865,1.); +#34865 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34866 = PCURVE('',#34818,#34867); +#34867 = DEFINITIONAL_REPRESENTATION('',(#34868),#34872); +#34868 = LINE('',#34869,#34870); +#34869 = CARTESIAN_POINT('',(0.15,0.E+000)); +#34870 = VECTOR('',#34871,1.); +#34871 = DIRECTION('',(0.E+000,1.)); +#34872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34873 = PCURVE('',#33999,#34874); +#34874 = DEFINITIONAL_REPRESENTATION('',(#34875),#34878); +#34875 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34876,#34877),.UNSPECIFIED., .F.,.F.,(2,2),(-0.63,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32484 = CARTESIAN_POINT('',(1.570796326795,0.63)); -#32485 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#32486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32487 = ORIENTED_EDGE('',*,*,#32488,.T.); -#32488 = EDGE_CURVE('',#32467,#32416,#32489,.T.); -#32489 = SURFACE_CURVE('',#32490,(#32494,#32501),.PCURVE_S1.); -#32490 = LINE('',#32491,#32492); -#32491 = CARTESIAN_POINT('',(1.,0.63,0.625)); -#32492 = VECTOR('',#32493,1.); -#32493 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32494 = PCURVE('',#32426,#32495); -#32495 = DEFINITIONAL_REPRESENTATION('',(#32496),#32500); -#32496 = LINE('',#32497,#32498); -#32497 = CARTESIAN_POINT('',(1.25,-0.15)); -#32498 = VECTOR('',#32499,1.); -#32499 = DIRECTION('',(1.,0.E+000)); -#32500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32501 = PCURVE('',#32153,#32502); -#32502 = DEFINITIONAL_REPRESENTATION('',(#32503),#32506); -#32503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32504,#32505),.UNSPECIFIED., +#34876 = CARTESIAN_POINT('',(1.570796326795,0.63)); +#34877 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#34878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34879 = ORIENTED_EDGE('',*,*,#34880,.T.); +#34880 = EDGE_CURVE('',#34859,#34808,#34881,.T.); +#34881 = SURFACE_CURVE('',#34882,(#34886,#34893),.PCURVE_S1.); +#34882 = LINE('',#34883,#34884); +#34883 = CARTESIAN_POINT('',(1.,0.63,0.625)); +#34884 = VECTOR('',#34885,1.); +#34885 = DIRECTION('',(0.E+000,0.E+000,1.)); +#34886 = PCURVE('',#34818,#34887); +#34887 = DEFINITIONAL_REPRESENTATION('',(#34888),#34892); +#34888 = LINE('',#34889,#34890); +#34889 = CARTESIAN_POINT('',(1.25,-0.15)); +#34890 = VECTOR('',#34891,1.); +#34891 = DIRECTION('',(1.,0.E+000)); +#34892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34893 = PCURVE('',#34545,#34894); +#34894 = DEFINITIONAL_REPRESENTATION('',(#34895),#34898); +#34895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34896,#34897),.UNSPECIFIED., .F.,.F.,(2,2),(-1.1,-0.15),.PIECEWISE_BEZIER_KNOTS.); -#32504 = CARTESIAN_POINT('',(0.E+000,-1.1)); -#32505 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#32506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32507 = ADVANCED_FACE('',(#32508),#31504,.F.); -#32508 = FACE_BOUND('',#32509,.T.); -#32509 = EDGE_LOOP('',(#32510,#32530,#32531,#32551)); -#32510 = ORIENTED_EDGE('',*,*,#32511,.T.); -#32511 = EDGE_CURVE('',#31568,#31489,#32512,.T.); -#32512 = SURFACE_CURVE('',#32513,(#32517,#32524),.PCURVE_S1.); -#32513 = LINE('',#32514,#32515); -#32514 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); -#32515 = VECTOR('',#32516,1.); -#32516 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32517 = PCURVE('',#31504,#32518); -#32518 = DEFINITIONAL_REPRESENTATION('',(#32519),#32523); -#32519 = LINE('',#32520,#32521); -#32520 = CARTESIAN_POINT('',(0.E+000,-0.63)); -#32521 = VECTOR('',#32522,1.); -#32522 = DIRECTION('',(-1.,0.E+000)); -#32523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32524 = PCURVE('',#31656,#32525); -#32525 = DEFINITIONAL_REPRESENTATION('',(#32526),#32529); -#32526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32527,#32528),.UNSPECIFIED., +#34896 = CARTESIAN_POINT('',(0.E+000,-1.1)); +#34897 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#34898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34899 = ADVANCED_FACE('',(#34900),#33896,.F.); +#34900 = FACE_BOUND('',#34901,.T.); +#34901 = EDGE_LOOP('',(#34902,#34922,#34923,#34943)); +#34902 = ORIENTED_EDGE('',*,*,#34903,.T.); +#34903 = EDGE_CURVE('',#33960,#33881,#34904,.T.); +#34904 = SURFACE_CURVE('',#34905,(#34909,#34916),.PCURVE_S1.); +#34905 = LINE('',#34906,#34907); +#34906 = CARTESIAN_POINT('',(-1.,0.15,-0.625)); +#34907 = VECTOR('',#34908,1.); +#34908 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34909 = PCURVE('',#33896,#34910); +#34910 = DEFINITIONAL_REPRESENTATION('',(#34911),#34915); +#34911 = LINE('',#34912,#34913); +#34912 = CARTESIAN_POINT('',(0.E+000,-0.63)); +#34913 = VECTOR('',#34914,1.); +#34914 = DIRECTION('',(-1.,0.E+000)); +#34915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34916 = PCURVE('',#34048,#34917); +#34917 = DEFINITIONAL_REPRESENTATION('',(#34918),#34921); +#34918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34919,#34920),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#32527 = CARTESIAN_POINT('',(3.14159265359,-1.5)); -#32528 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#32529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32530 = ORIENTED_EDGE('',*,*,#31488,.T.); -#32531 = ORIENTED_EDGE('',*,*,#32532,.T.); -#32532 = EDGE_CURVE('',#31079,#31156,#32533,.T.); -#32533 = SURFACE_CURVE('',#32534,(#32538,#32545),.PCURVE_S1.); -#32534 = LINE('',#32535,#32536); -#32535 = CARTESIAN_POINT('',(1.,0.63,-0.625)); -#32536 = VECTOR('',#32537,1.); -#32537 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32538 = PCURVE('',#31504,#32539); -#32539 = DEFINITIONAL_REPRESENTATION('',(#32540),#32544); -#32540 = LINE('',#32541,#32542); -#32541 = CARTESIAN_POINT('',(2.,-0.15)); -#32542 = VECTOR('',#32543,1.); -#32543 = DIRECTION('',(1.,0.E+000)); -#32544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32545 = PCURVE('',#30347,#32546); -#32546 = DEFINITIONAL_REPRESENTATION('',(#32547),#32550); -#32547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32548,#32549),.UNSPECIFIED., +#34919 = CARTESIAN_POINT('',(3.14159265359,-1.5)); +#34920 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#34921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34922 = ORIENTED_EDGE('',*,*,#33880,.T.); +#34923 = ORIENTED_EDGE('',*,*,#34924,.T.); +#34924 = EDGE_CURVE('',#33471,#33548,#34925,.T.); +#34925 = SURFACE_CURVE('',#34926,(#34930,#34937),.PCURVE_S1.); +#34926 = LINE('',#34927,#34928); +#34927 = CARTESIAN_POINT('',(1.,0.63,-0.625)); +#34928 = VECTOR('',#34929,1.); +#34929 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34930 = PCURVE('',#33896,#34931); +#34931 = DEFINITIONAL_REPRESENTATION('',(#34932),#34936); +#34932 = LINE('',#34933,#34934); +#34933 = CARTESIAN_POINT('',(2.,-0.15)); +#34934 = VECTOR('',#34935,1.); +#34935 = DIRECTION('',(1.,0.E+000)); +#34936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34937 = PCURVE('',#32739,#34938); +#34938 = DEFINITIONAL_REPRESENTATION('',(#34939),#34942); +#34939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34940,#34941),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#32548 = CARTESIAN_POINT('',(0.E+000,0.5)); -#32549 = CARTESIAN_POINT('',(0.E+000,1.5)); -#32550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32551 = ORIENTED_EDGE('',*,*,#31567,.T.); -#32552 = ADVANCED_FACE('',(#32553),#31282,.F.); -#32553 = FACE_BOUND('',#32554,.T.); -#32554 = EDGE_LOOP('',(#32555,#32575,#32576,#32596)); -#32555 = ORIENTED_EDGE('',*,*,#32556,.T.); -#32556 = EDGE_CURVE('',#31379,#31260,#32557,.T.); -#32557 = SURFACE_CURVE('',#32558,(#32562,#32569),.PCURVE_S1.); -#32558 = LINE('',#32559,#32560); -#32559 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); -#32560 = VECTOR('',#32561,1.); -#32561 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32562 = PCURVE('',#31282,#32563); -#32563 = DEFINITIONAL_REPRESENTATION('',(#32564),#32568); -#32564 = LINE('',#32565,#32566); -#32565 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#32566 = VECTOR('',#32567,1.); -#32567 = DIRECTION('',(0.E+000,-1.)); -#32568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32569 = PCURVE('',#31763,#32570); -#32570 = DEFINITIONAL_REPRESENTATION('',(#32571),#32574); -#32571 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32572,#32573),.UNSPECIFIED., +#34940 = CARTESIAN_POINT('',(0.E+000,0.5)); +#34941 = CARTESIAN_POINT('',(0.E+000,1.5)); +#34942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34943 = ORIENTED_EDGE('',*,*,#33959,.T.); +#34944 = ADVANCED_FACE('',(#34945),#33674,.F.); +#34945 = FACE_BOUND('',#34946,.T.); +#34946 = EDGE_LOOP('',(#34947,#34967,#34968,#34988)); +#34947 = ORIENTED_EDGE('',*,*,#34948,.T.); +#34948 = EDGE_CURVE('',#33771,#33652,#34949,.T.); +#34949 = SURFACE_CURVE('',#34950,(#34954,#34961),.PCURVE_S1.); +#34950 = LINE('',#34951,#34952); +#34951 = CARTESIAN_POINT('',(-1.,0.E+000,0.475)); +#34952 = VECTOR('',#34953,1.); +#34953 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#34954 = PCURVE('',#33674,#34955); +#34955 = DEFINITIONAL_REPRESENTATION('',(#34956),#34960); +#34956 = LINE('',#34957,#34958); +#34957 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#34958 = VECTOR('',#34959,1.); +#34959 = DIRECTION('',(0.E+000,-1.)); +#34960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34961 = PCURVE('',#34155,#34962); +#34962 = DEFINITIONAL_REPRESENTATION('',(#34963),#34966); +#34963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34964,#34965),.UNSPECIFIED., .F.,.F.,(2,2),(-1.5,-0.5),.PIECEWISE_BEZIER_KNOTS.); -#32572 = CARTESIAN_POINT('',(4.712388980385,1.5)); -#32573 = CARTESIAN_POINT('',(4.712388980385,0.5)); -#32574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32575 = ORIENTED_EDGE('',*,*,#31259,.T.); -#32576 = ORIENTED_EDGE('',*,*,#32577,.T.); -#32577 = EDGE_CURVE('',#31262,#31377,#32578,.T.); -#32578 = SURFACE_CURVE('',#32579,(#32583,#32590),.PCURVE_S1.); -#32579 = LINE('',#32580,#32581); -#32580 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); -#32581 = VECTOR('',#32582,1.); -#32582 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32583 = PCURVE('',#31282,#32584); -#32584 = DEFINITIONAL_REPRESENTATION('',(#32585),#32589); -#32585 = LINE('',#32586,#32587); -#32586 = CARTESIAN_POINT('',(-1.1,0.E+000)); -#32587 = VECTOR('',#32588,1.); -#32588 = DIRECTION('',(0.E+000,1.)); -#32589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32590 = PCURVE('',#31656,#32591); -#32591 = DEFINITIONAL_REPRESENTATION('',(#32592),#32595); -#32592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32593,#32594),.UNSPECIFIED., +#34964 = CARTESIAN_POINT('',(4.712388980385,1.5)); +#34965 = CARTESIAN_POINT('',(4.712388980385,0.5)); +#34966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34967 = ORIENTED_EDGE('',*,*,#33651,.T.); +#34968 = ORIENTED_EDGE('',*,*,#34969,.T.); +#34969 = EDGE_CURVE('',#33654,#33769,#34970,.T.); +#34970 = SURFACE_CURVE('',#34971,(#34975,#34982),.PCURVE_S1.); +#34971 = LINE('',#34972,#34973); +#34972 = CARTESIAN_POINT('',(-1.,0.E+000,-0.475)); +#34973 = VECTOR('',#34974,1.); +#34974 = DIRECTION('',(1.,0.E+000,0.E+000)); +#34975 = PCURVE('',#33674,#34976); +#34976 = DEFINITIONAL_REPRESENTATION('',(#34977),#34981); +#34977 = LINE('',#34978,#34979); +#34978 = CARTESIAN_POINT('',(-1.1,0.E+000)); +#34979 = VECTOR('',#34980,1.); +#34980 = DIRECTION('',(0.E+000,1.)); +#34981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34982 = PCURVE('',#34048,#34983); +#34983 = DEFINITIONAL_REPRESENTATION('',(#34984),#34987); +#34984 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34985,#34986),.UNSPECIFIED., .F.,.F.,(2,2),(0.5,1.5),.PIECEWISE_BEZIER_KNOTS.); -#32593 = CARTESIAN_POINT('',(4.712388980385,-0.5)); -#32594 = CARTESIAN_POINT('',(4.712388980385,-1.5)); -#32595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32596 = ORIENTED_EDGE('',*,*,#31376,.T.); -#32597 = ADVANCED_FACE('',(#32598),#32259,.T.); -#32598 = FACE_BOUND('',#32599,.T.); -#32599 = EDGE_LOOP('',(#32600,#32620,#32621,#32641)); -#32600 = ORIENTED_EDGE('',*,*,#32601,.F.); -#32601 = EDGE_CURVE('',#32056,#32416,#32602,.T.); -#32602 = SURFACE_CURVE('',#32603,(#32608,#32614),.PCURVE_S1.); -#32603 = CIRCLE('',#32604,0.15); -#32604 = AXIS2_PLACEMENT_3D('',#32605,#32606,#32607); -#32605 = CARTESIAN_POINT('',(0.85,0.63,0.475)); -#32606 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32607 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32608 = PCURVE('',#32259,#32609); -#32609 = DEFINITIONAL_REPRESENTATION('',(#32610),#32613); -#32610 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32611,#32612),.UNSPECIFIED., +#34985 = CARTESIAN_POINT('',(4.712388980385,-0.5)); +#34986 = CARTESIAN_POINT('',(4.712388980385,-1.5)); +#34987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#34988 = ORIENTED_EDGE('',*,*,#33768,.T.); +#34989 = ADVANCED_FACE('',(#34990),#34651,.T.); +#34990 = FACE_BOUND('',#34991,.T.); +#34991 = EDGE_LOOP('',(#34992,#35012,#35013,#35033)); +#34992 = ORIENTED_EDGE('',*,*,#34993,.F.); +#34993 = EDGE_CURVE('',#34448,#34808,#34994,.T.); +#34994 = SURFACE_CURVE('',#34995,(#35000,#35006),.PCURVE_S1.); +#34995 = CIRCLE('',#34996,0.15); +#34996 = AXIS2_PLACEMENT_3D('',#34997,#34998,#34999); +#34997 = CARTESIAN_POINT('',(0.85,0.63,0.475)); +#34998 = DIRECTION('',(0.E+000,1.,0.E+000)); +#34999 = DIRECTION('',(0.E+000,0.E+000,1.)); +#35000 = PCURVE('',#34651,#35001); +#35001 = DEFINITIONAL_REPRESENTATION('',(#35002),#35005); +#35002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35003,#35004),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#32611 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#32612 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#32613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35003 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#35004 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#35005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32614 = PCURVE('',#32091,#32615); -#32615 = DEFINITIONAL_REPRESENTATION('',(#32616),#32619); -#32616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32617,#32618),.UNSPECIFIED., +#35006 = PCURVE('',#34483,#35007); +#35007 = DEFINITIONAL_REPRESENTATION('',(#35008),#35011); +#35008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35009,#35010),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#32617 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#32618 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#32619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32620 = ORIENTED_EDGE('',*,*,#32245,.F.); -#32621 = ORIENTED_EDGE('',*,*,#32622,.F.); -#32622 = EDGE_CURVE('',#32418,#31832,#32623,.T.); -#32623 = SURFACE_CURVE('',#32624,(#32629,#32635),.PCURVE_S1.); -#32624 = CIRCLE('',#32625,0.15); -#32625 = AXIS2_PLACEMENT_3D('',#32626,#32627,#32628); -#32626 = CARTESIAN_POINT('',(0.85,0.15,0.475)); -#32627 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32628 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32629 = PCURVE('',#32259,#32630); -#32630 = DEFINITIONAL_REPRESENTATION('',(#32631),#32634); -#32631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32632,#32633),.UNSPECIFIED., +#35009 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#35010 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#35011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35012 = ORIENTED_EDGE('',*,*,#34637,.F.); +#35013 = ORIENTED_EDGE('',*,*,#35014,.F.); +#35014 = EDGE_CURVE('',#34810,#34224,#35015,.T.); +#35015 = SURFACE_CURVE('',#35016,(#35021,#35027),.PCURVE_S1.); +#35016 = CIRCLE('',#35017,0.15); +#35017 = AXIS2_PLACEMENT_3D('',#35018,#35019,#35020); +#35018 = CARTESIAN_POINT('',(0.85,0.15,0.475)); +#35019 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#35020 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35021 = PCURVE('',#34651,#35022); +#35022 = DEFINITIONAL_REPRESENTATION('',(#35023),#35026); +#35023 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35024,#35025),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#32632 = CARTESIAN_POINT('',(1.570796326795,0.63)); -#32633 = CARTESIAN_POINT('',(3.14159265359,0.63)); -#32634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35024 = CARTESIAN_POINT('',(1.570796326795,0.63)); +#35025 = CARTESIAN_POINT('',(3.14159265359,0.63)); +#35026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32635 = PCURVE('',#31893,#32636); -#32636 = DEFINITIONAL_REPRESENTATION('',(#32637),#32640); -#32637 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32638,#32639),.UNSPECIFIED., +#35027 = PCURVE('',#34285,#35028); +#35028 = DEFINITIONAL_REPRESENTATION('',(#35029),#35032); +#35029 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35030,#35031),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#32638 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#32639 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#32640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32641 = ORIENTED_EDGE('',*,*,#32415,.F.); -#32642 = ADVANCED_FACE('',(#32643),#32091,.T.); -#32643 = FACE_BOUND('',#32644,.T.); -#32644 = EDGE_LOOP('',(#32645,#32646,#32647)); -#32645 = ORIENTED_EDGE('',*,*,#32077,.F.); -#32646 = ORIENTED_EDGE('',*,*,#32601,.T.); -#32647 = ORIENTED_EDGE('',*,*,#32648,.F.); -#32648 = EDGE_CURVE('',#32007,#32416,#32649,.T.); -#32649 = SURFACE_CURVE('',#32650,(#32655,#32684),.PCURVE_S1.); -#32650 = CIRCLE('',#32651,0.15); -#32651 = AXIS2_PLACEMENT_3D('',#32652,#32653,#32654); -#32652 = CARTESIAN_POINT('',(0.85,0.63,0.475)); -#32653 = DIRECTION('',(0.E+000,1.445602896647E-015,-1.)); -#32654 = DIRECTION('',(0.E+000,-1.,-1.445602896647E-015)); -#32655 = PCURVE('',#32091,#32656); -#32656 = DEFINITIONAL_REPRESENTATION('',(#32657),#32683); -#32657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32658,#32659,#32660,#32661, - #32662,#32663,#32664,#32665,#32666,#32667,#32668,#32669,#32670, - #32671,#32672,#32673,#32674,#32675,#32676,#32677,#32678,#32679, - #32680,#32681,#32682),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35030 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#35031 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#35032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35033 = ORIENTED_EDGE('',*,*,#34807,.F.); +#35034 = ADVANCED_FACE('',(#35035),#34483,.T.); +#35035 = FACE_BOUND('',#35036,.T.); +#35036 = EDGE_LOOP('',(#35037,#35038,#35039)); +#35037 = ORIENTED_EDGE('',*,*,#34469,.F.); +#35038 = ORIENTED_EDGE('',*,*,#34993,.T.); +#35039 = ORIENTED_EDGE('',*,*,#35040,.F.); +#35040 = EDGE_CURVE('',#34399,#34808,#35041,.T.); +#35041 = SURFACE_CURVE('',#35042,(#35047,#35076),.PCURVE_S1.); +#35042 = CIRCLE('',#35043,0.15); +#35043 = AXIS2_PLACEMENT_3D('',#35044,#35045,#35046); +#35044 = CARTESIAN_POINT('',(0.85,0.63,0.475)); +#35045 = DIRECTION('',(0.E+000,1.445602896647E-015,-1.)); +#35046 = DIRECTION('',(0.E+000,-1.,-1.445602896647E-015)); +#35047 = PCURVE('',#34483,#35048); +#35048 = DEFINITIONAL_REPRESENTATION('',(#35049),#35075); +#35049 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35050,#35051,#35052,#35053, + #35054,#35055,#35056,#35057,#35058,#35059,#35060,#35061,#35062, + #35063,#35064,#35065,#35066,#35067,#35068,#35069,#35070,#35071, + #35072,#35073,#35074),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -40373,40 +43362,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#32658 = CARTESIAN_POINT('',(6.28318530718,1.570796326795)); -#32659 = CARTESIAN_POINT('',(6.28318530718,1.54699638245)); -#32660 = CARTESIAN_POINT('',(6.28318530718,1.499396493759)); -#32661 = CARTESIAN_POINT('',(6.28318530718,1.427996660723)); -#32662 = CARTESIAN_POINT('',(6.28318530718,1.356596827687)); -#32663 = CARTESIAN_POINT('',(6.28318530718,1.28519699465)); -#32664 = CARTESIAN_POINT('',(6.28318530718,1.213797161614)); -#32665 = CARTESIAN_POINT('',(6.28318530718,1.142397328578)); -#32666 = CARTESIAN_POINT('',(6.28318530718,1.070997495542)); -#32667 = CARTESIAN_POINT('',(6.28318530718,0.999597662506)); -#32668 = CARTESIAN_POINT('',(6.28318530718,0.92819782947)); -#32669 = CARTESIAN_POINT('',(6.28318530718,0.856797996434)); -#32670 = CARTESIAN_POINT('',(6.28318530718,0.785398163397)); -#32671 = CARTESIAN_POINT('',(6.28318530718,0.713998330361)); -#32672 = CARTESIAN_POINT('',(6.28318530718,0.642598497325)); -#32673 = CARTESIAN_POINT('',(6.28318530718,0.571198664289)); -#32674 = CARTESIAN_POINT('',(6.28318530718,0.499798831253)); -#32675 = CARTESIAN_POINT('',(6.28318530718,0.428398998217)); -#32676 = CARTESIAN_POINT('',(6.28318530718,0.356999165181)); -#32677 = CARTESIAN_POINT('',(6.28318530718,0.285599332145)); -#32678 = CARTESIAN_POINT('',(6.28318530718,0.214199499108)); -#32679 = CARTESIAN_POINT('',(6.28318530718,0.142799666072)); -#32680 = CARTESIAN_POINT('',(6.28318530718,7.139983303613E-002)); -#32681 = CARTESIAN_POINT('',(6.28318530718,2.379994434538E-002)); -#32682 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#32683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32684 = PCURVE('',#32153,#32685); -#32685 = DEFINITIONAL_REPRESENTATION('',(#32686),#32712); -#32686 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32687,#32688,#32689,#32690, - #32691,#32692,#32693,#32694,#32695,#32696,#32697,#32698,#32699, - #32700,#32701,#32702,#32703,#32704,#32705,#32706,#32707,#32708, - #32709,#32710,#32711),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35050 = CARTESIAN_POINT('',(6.28318530718,1.570796326795)); +#35051 = CARTESIAN_POINT('',(6.28318530718,1.54699638245)); +#35052 = CARTESIAN_POINT('',(6.28318530718,1.499396493759)); +#35053 = CARTESIAN_POINT('',(6.28318530718,1.427996660723)); +#35054 = CARTESIAN_POINT('',(6.28318530718,1.356596827687)); +#35055 = CARTESIAN_POINT('',(6.28318530718,1.28519699465)); +#35056 = CARTESIAN_POINT('',(6.28318530718,1.213797161614)); +#35057 = CARTESIAN_POINT('',(6.28318530718,1.142397328578)); +#35058 = CARTESIAN_POINT('',(6.28318530718,1.070997495542)); +#35059 = CARTESIAN_POINT('',(6.28318530718,0.999597662506)); +#35060 = CARTESIAN_POINT('',(6.28318530718,0.92819782947)); +#35061 = CARTESIAN_POINT('',(6.28318530718,0.856797996434)); +#35062 = CARTESIAN_POINT('',(6.28318530718,0.785398163397)); +#35063 = CARTESIAN_POINT('',(6.28318530718,0.713998330361)); +#35064 = CARTESIAN_POINT('',(6.28318530718,0.642598497325)); +#35065 = CARTESIAN_POINT('',(6.28318530718,0.571198664289)); +#35066 = CARTESIAN_POINT('',(6.28318530718,0.499798831253)); +#35067 = CARTESIAN_POINT('',(6.28318530718,0.428398998217)); +#35068 = CARTESIAN_POINT('',(6.28318530718,0.356999165181)); +#35069 = CARTESIAN_POINT('',(6.28318530718,0.285599332145)); +#35070 = CARTESIAN_POINT('',(6.28318530718,0.214199499108)); +#35071 = CARTESIAN_POINT('',(6.28318530718,0.142799666072)); +#35072 = CARTESIAN_POINT('',(6.28318530718,7.139983303613E-002)); +#35073 = CARTESIAN_POINT('',(6.28318530718,2.379994434538E-002)); +#35074 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#35075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35076 = PCURVE('',#34545,#35077); +#35077 = DEFINITIONAL_REPRESENTATION('',(#35078),#35104); +#35078 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35079,#35080,#35081,#35082, + #35083,#35084,#35085,#35086,#35087,#35088,#35089,#35090,#35091, + #35092,#35093,#35094,#35095,#35096,#35097,#35098,#35099,#35100, + #35101,#35102,#35103),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -40414,51 +43403,51 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#32687 = CARTESIAN_POINT('',(1.570796326795,-0.15)); -#32688 = CARTESIAN_POINT('',(1.54699638245,-0.15)); -#32689 = CARTESIAN_POINT('',(1.499396493759,-0.15)); -#32690 = CARTESIAN_POINT('',(1.427996660723,-0.15)); -#32691 = CARTESIAN_POINT('',(1.356596827687,-0.15)); -#32692 = CARTESIAN_POINT('',(1.28519699465,-0.15)); -#32693 = CARTESIAN_POINT('',(1.213797161614,-0.15)); -#32694 = CARTESIAN_POINT('',(1.142397328578,-0.15)); -#32695 = CARTESIAN_POINT('',(1.070997495542,-0.15)); -#32696 = CARTESIAN_POINT('',(0.999597662506,-0.15)); -#32697 = CARTESIAN_POINT('',(0.92819782947,-0.15)); -#32698 = CARTESIAN_POINT('',(0.856797996434,-0.15)); -#32699 = CARTESIAN_POINT('',(0.785398163397,-0.15)); -#32700 = CARTESIAN_POINT('',(0.713998330361,-0.15)); -#32701 = CARTESIAN_POINT('',(0.642598497325,-0.15)); -#32702 = CARTESIAN_POINT('',(0.571198664289,-0.15)); -#32703 = CARTESIAN_POINT('',(0.499798831253,-0.15)); -#32704 = CARTESIAN_POINT('',(0.428398998217,-0.15)); -#32705 = CARTESIAN_POINT('',(0.356999165181,-0.15)); -#32706 = CARTESIAN_POINT('',(0.285599332145,-0.15)); -#32707 = CARTESIAN_POINT('',(0.214199499108,-0.15)); -#32708 = CARTESIAN_POINT('',(0.142799666072,-0.15)); -#32709 = CARTESIAN_POINT('',(7.139983303613E-002,-0.15)); -#32710 = CARTESIAN_POINT('',(2.379994434538E-002,-0.15)); -#32711 = CARTESIAN_POINT('',(0.E+000,-0.15)); -#32712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32713 = ADVANCED_FACE('',(#32714),#31893,.T.); -#32714 = FACE_BOUND('',#32715,.T.); -#32715 = EDGE_LOOP('',(#32716,#32782,#32783)); -#32716 = ORIENTED_EDGE('',*,*,#32717,.F.); -#32717 = EDGE_CURVE('',#32418,#31434,#32718,.T.); -#32718 = SURFACE_CURVE('',#32719,(#32724,#32753),.PCURVE_S1.); -#32719 = CIRCLE('',#32720,0.15); -#32720 = AXIS2_PLACEMENT_3D('',#32721,#32722,#32723); -#32721 = CARTESIAN_POINT('',(0.85,0.15,0.475)); -#32722 = DIRECTION('',(-1.445602896647E-015,0.E+000,-1.)); -#32723 = DIRECTION('',(1.,0.E+000,-1.445602896647E-015)); -#32724 = PCURVE('',#31893,#32725); -#32725 = DEFINITIONAL_REPRESENTATION('',(#32726),#32752); -#32726 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32727,#32728,#32729,#32730, - #32731,#32732,#32733,#32734,#32735,#32736,#32737,#32738,#32739, - #32740,#32741,#32742,#32743,#32744,#32745,#32746,#32747,#32748, - #32749,#32750,#32751),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35079 = CARTESIAN_POINT('',(1.570796326795,-0.15)); +#35080 = CARTESIAN_POINT('',(1.54699638245,-0.15)); +#35081 = CARTESIAN_POINT('',(1.499396493759,-0.15)); +#35082 = CARTESIAN_POINT('',(1.427996660723,-0.15)); +#35083 = CARTESIAN_POINT('',(1.356596827687,-0.15)); +#35084 = CARTESIAN_POINT('',(1.28519699465,-0.15)); +#35085 = CARTESIAN_POINT('',(1.213797161614,-0.15)); +#35086 = CARTESIAN_POINT('',(1.142397328578,-0.15)); +#35087 = CARTESIAN_POINT('',(1.070997495542,-0.15)); +#35088 = CARTESIAN_POINT('',(0.999597662506,-0.15)); +#35089 = CARTESIAN_POINT('',(0.92819782947,-0.15)); +#35090 = CARTESIAN_POINT('',(0.856797996434,-0.15)); +#35091 = CARTESIAN_POINT('',(0.785398163397,-0.15)); +#35092 = CARTESIAN_POINT('',(0.713998330361,-0.15)); +#35093 = CARTESIAN_POINT('',(0.642598497325,-0.15)); +#35094 = CARTESIAN_POINT('',(0.571198664289,-0.15)); +#35095 = CARTESIAN_POINT('',(0.499798831253,-0.15)); +#35096 = CARTESIAN_POINT('',(0.428398998217,-0.15)); +#35097 = CARTESIAN_POINT('',(0.356999165181,-0.15)); +#35098 = CARTESIAN_POINT('',(0.285599332145,-0.15)); +#35099 = CARTESIAN_POINT('',(0.214199499108,-0.15)); +#35100 = CARTESIAN_POINT('',(0.142799666072,-0.15)); +#35101 = CARTESIAN_POINT('',(7.139983303613E-002,-0.15)); +#35102 = CARTESIAN_POINT('',(2.379994434538E-002,-0.15)); +#35103 = CARTESIAN_POINT('',(0.E+000,-0.15)); +#35104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35105 = ADVANCED_FACE('',(#35106),#34285,.T.); +#35106 = FACE_BOUND('',#35107,.T.); +#35107 = EDGE_LOOP('',(#35108,#35174,#35175)); +#35108 = ORIENTED_EDGE('',*,*,#35109,.F.); +#35109 = EDGE_CURVE('',#34810,#33826,#35110,.T.); +#35110 = SURFACE_CURVE('',#35111,(#35116,#35145),.PCURVE_S1.); +#35111 = CIRCLE('',#35112,0.15); +#35112 = AXIS2_PLACEMENT_3D('',#35113,#35114,#35115); +#35113 = CARTESIAN_POINT('',(0.85,0.15,0.475)); +#35114 = DIRECTION('',(-1.445602896647E-015,0.E+000,-1.)); +#35115 = DIRECTION('',(1.,0.E+000,-1.445602896647E-015)); +#35116 = PCURVE('',#34285,#35117); +#35117 = DEFINITIONAL_REPRESENTATION('',(#35118),#35144); +#35118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35119,#35120,#35121,#35122, + #35123,#35124,#35125,#35126,#35127,#35128,#35129,#35130,#35131, + #35132,#35133,#35134,#35135,#35136,#35137,#35138,#35139,#35140, + #35141,#35142,#35143),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -40466,40 +43455,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#32727 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#32728 = CARTESIAN_POINT('',(6.28318530718,-2.379994434538E-002)); -#32729 = CARTESIAN_POINT('',(6.28318530718,-7.139983303613E-002)); -#32730 = CARTESIAN_POINT('',(6.28318530718,-0.142799666072)); -#32731 = CARTESIAN_POINT('',(6.28318530718,-0.214199499108)); -#32732 = CARTESIAN_POINT('',(6.28318530718,-0.285599332145)); -#32733 = CARTESIAN_POINT('',(6.28318530718,-0.356999165181)); -#32734 = CARTESIAN_POINT('',(6.28318530718,-0.428398998217)); -#32735 = CARTESIAN_POINT('',(6.28318530718,-0.499798831253)); -#32736 = CARTESIAN_POINT('',(6.28318530718,-0.571198664289)); -#32737 = CARTESIAN_POINT('',(6.28318530718,-0.642598497325)); -#32738 = CARTESIAN_POINT('',(6.28318530718,-0.713998330361)); -#32739 = CARTESIAN_POINT('',(6.28318530718,-0.785398163397)); -#32740 = CARTESIAN_POINT('',(6.28318530718,-0.856797996434)); -#32741 = CARTESIAN_POINT('',(6.28318530718,-0.92819782947)); -#32742 = CARTESIAN_POINT('',(6.28318530718,-0.999597662506)); -#32743 = CARTESIAN_POINT('',(6.28318530718,-1.070997495542)); -#32744 = CARTESIAN_POINT('',(6.28318530718,-1.142397328578)); -#32745 = CARTESIAN_POINT('',(6.28318530718,-1.213797161614)); -#32746 = CARTESIAN_POINT('',(6.28318530718,-1.28519699465)); -#32747 = CARTESIAN_POINT('',(6.28318530718,-1.356596827687)); -#32748 = CARTESIAN_POINT('',(6.28318530718,-1.427996660723)); -#32749 = CARTESIAN_POINT('',(6.28318530718,-1.499396493759)); -#32750 = CARTESIAN_POINT('',(6.28318530718,-1.54699638245)); -#32751 = CARTESIAN_POINT('',(6.28318530718,-1.570796326795)); -#32752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32753 = PCURVE('',#31449,#32754); -#32754 = DEFINITIONAL_REPRESENTATION('',(#32755),#32781); -#32755 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32756,#32757,#32758,#32759, - #32760,#32761,#32762,#32763,#32764,#32765,#32766,#32767,#32768, - #32769,#32770,#32771,#32772,#32773,#32774,#32775,#32776,#32777, - #32778,#32779,#32780),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35119 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#35120 = CARTESIAN_POINT('',(6.28318530718,-2.379994434538E-002)); +#35121 = CARTESIAN_POINT('',(6.28318530718,-7.139983303613E-002)); +#35122 = CARTESIAN_POINT('',(6.28318530718,-0.142799666072)); +#35123 = CARTESIAN_POINT('',(6.28318530718,-0.214199499108)); +#35124 = CARTESIAN_POINT('',(6.28318530718,-0.285599332145)); +#35125 = CARTESIAN_POINT('',(6.28318530718,-0.356999165181)); +#35126 = CARTESIAN_POINT('',(6.28318530718,-0.428398998217)); +#35127 = CARTESIAN_POINT('',(6.28318530718,-0.499798831253)); +#35128 = CARTESIAN_POINT('',(6.28318530718,-0.571198664289)); +#35129 = CARTESIAN_POINT('',(6.28318530718,-0.642598497325)); +#35130 = CARTESIAN_POINT('',(6.28318530718,-0.713998330361)); +#35131 = CARTESIAN_POINT('',(6.28318530718,-0.785398163397)); +#35132 = CARTESIAN_POINT('',(6.28318530718,-0.856797996434)); +#35133 = CARTESIAN_POINT('',(6.28318530718,-0.92819782947)); +#35134 = CARTESIAN_POINT('',(6.28318530718,-0.999597662506)); +#35135 = CARTESIAN_POINT('',(6.28318530718,-1.070997495542)); +#35136 = CARTESIAN_POINT('',(6.28318530718,-1.142397328578)); +#35137 = CARTESIAN_POINT('',(6.28318530718,-1.213797161614)); +#35138 = CARTESIAN_POINT('',(6.28318530718,-1.28519699465)); +#35139 = CARTESIAN_POINT('',(6.28318530718,-1.356596827687)); +#35140 = CARTESIAN_POINT('',(6.28318530718,-1.427996660723)); +#35141 = CARTESIAN_POINT('',(6.28318530718,-1.499396493759)); +#35142 = CARTESIAN_POINT('',(6.28318530718,-1.54699638245)); +#35143 = CARTESIAN_POINT('',(6.28318530718,-1.570796326795)); +#35144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35145 = PCURVE('',#33841,#35146); +#35146 = DEFINITIONAL_REPRESENTATION('',(#35147),#35173); +#35147 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35148,#35149,#35150,#35151, + #35152,#35153,#35154,#35155,#35156,#35157,#35158,#35159,#35160, + #35161,#35162,#35163,#35164,#35165,#35166,#35167,#35168,#35169, + #35170,#35171,#35172),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -40507,65 +43496,65 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#32756 = CARTESIAN_POINT('',(3.14159265359,-1.1)); -#32757 = CARTESIAN_POINT('',(3.165392597935,-1.1)); -#32758 = CARTESIAN_POINT('',(3.212992486626,-1.1)); -#32759 = CARTESIAN_POINT('',(3.284392319662,-1.1)); -#32760 = CARTESIAN_POINT('',(3.355792152698,-1.1)); -#32761 = CARTESIAN_POINT('',(3.427191985734,-1.1)); -#32762 = CARTESIAN_POINT('',(3.49859181877,-1.1)); -#32763 = CARTESIAN_POINT('',(3.569991651807,-1.1)); -#32764 = CARTESIAN_POINT('',(3.641391484843,-1.1)); -#32765 = CARTESIAN_POINT('',(3.712791317879,-1.1)); -#32766 = CARTESIAN_POINT('',(3.784191150915,-1.1)); -#32767 = CARTESIAN_POINT('',(3.855590983951,-1.1)); -#32768 = CARTESIAN_POINT('',(3.926990816987,-1.1)); -#32769 = CARTESIAN_POINT('',(3.998390650023,-1.1)); -#32770 = CARTESIAN_POINT('',(4.06979048306,-1.1)); -#32771 = CARTESIAN_POINT('',(4.141190316096,-1.1)); -#32772 = CARTESIAN_POINT('',(4.212590149132,-1.1)); -#32773 = CARTESIAN_POINT('',(4.283989982168,-1.1)); -#32774 = CARTESIAN_POINT('',(4.355389815204,-1.1)); -#32775 = CARTESIAN_POINT('',(4.42678964824,-1.1)); -#32776 = CARTESIAN_POINT('',(4.498189481276,-1.1)); -#32777 = CARTESIAN_POINT('',(4.569589314312,-1.1)); -#32778 = CARTESIAN_POINT('',(4.640989147349,-1.1)); -#32779 = CARTESIAN_POINT('',(4.688589036039,-1.1)); -#32780 = CARTESIAN_POINT('',(4.712388980385,-1.1)); -#32781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32782 = ORIENTED_EDGE('',*,*,#32622,.T.); -#32783 = ORIENTED_EDGE('',*,*,#31879,.F.); -#32784 = ADVANCED_FACE('',(#32785),#32153,.T.); -#32785 = FACE_BOUND('',#32786,.T.); -#32786 = EDGE_LOOP('',(#32787,#32788,#32789,#32832)); -#32787 = ORIENTED_EDGE('',*,*,#32648,.T.); -#32788 = ORIENTED_EDGE('',*,*,#32488,.F.); -#32789 = ORIENTED_EDGE('',*,*,#32790,.F.); -#32790 = EDGE_CURVE('',#31210,#32467,#32791,.T.); -#32791 = SURFACE_CURVE('',#32792,(#32797,#32803),.PCURVE_S1.); -#32792 = CIRCLE('',#32793,0.15); -#32793 = AXIS2_PLACEMENT_3D('',#32794,#32795,#32796); -#32794 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); -#32795 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32796 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32797 = PCURVE('',#32153,#32798); -#32798 = DEFINITIONAL_REPRESENTATION('',(#32799),#32802); -#32799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32800,#32801),.UNSPECIFIED., +#35148 = CARTESIAN_POINT('',(3.14159265359,-1.1)); +#35149 = CARTESIAN_POINT('',(3.165392597935,-1.1)); +#35150 = CARTESIAN_POINT('',(3.212992486626,-1.1)); +#35151 = CARTESIAN_POINT('',(3.284392319662,-1.1)); +#35152 = CARTESIAN_POINT('',(3.355792152698,-1.1)); +#35153 = CARTESIAN_POINT('',(3.427191985734,-1.1)); +#35154 = CARTESIAN_POINT('',(3.49859181877,-1.1)); +#35155 = CARTESIAN_POINT('',(3.569991651807,-1.1)); +#35156 = CARTESIAN_POINT('',(3.641391484843,-1.1)); +#35157 = CARTESIAN_POINT('',(3.712791317879,-1.1)); +#35158 = CARTESIAN_POINT('',(3.784191150915,-1.1)); +#35159 = CARTESIAN_POINT('',(3.855590983951,-1.1)); +#35160 = CARTESIAN_POINT('',(3.926990816987,-1.1)); +#35161 = CARTESIAN_POINT('',(3.998390650023,-1.1)); +#35162 = CARTESIAN_POINT('',(4.06979048306,-1.1)); +#35163 = CARTESIAN_POINT('',(4.141190316096,-1.1)); +#35164 = CARTESIAN_POINT('',(4.212590149132,-1.1)); +#35165 = CARTESIAN_POINT('',(4.283989982168,-1.1)); +#35166 = CARTESIAN_POINT('',(4.355389815204,-1.1)); +#35167 = CARTESIAN_POINT('',(4.42678964824,-1.1)); +#35168 = CARTESIAN_POINT('',(4.498189481276,-1.1)); +#35169 = CARTESIAN_POINT('',(4.569589314312,-1.1)); +#35170 = CARTESIAN_POINT('',(4.640989147349,-1.1)); +#35171 = CARTESIAN_POINT('',(4.688589036039,-1.1)); +#35172 = CARTESIAN_POINT('',(4.712388980385,-1.1)); +#35173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35174 = ORIENTED_EDGE('',*,*,#35014,.T.); +#35175 = ORIENTED_EDGE('',*,*,#34271,.F.); +#35176 = ADVANCED_FACE('',(#35177),#34545,.T.); +#35177 = FACE_BOUND('',#35178,.T.); +#35178 = EDGE_LOOP('',(#35179,#35180,#35181,#35224)); +#35179 = ORIENTED_EDGE('',*,*,#35040,.T.); +#35180 = ORIENTED_EDGE('',*,*,#34880,.F.); +#35181 = ORIENTED_EDGE('',*,*,#35182,.F.); +#35182 = EDGE_CURVE('',#33602,#34859,#35183,.T.); +#35183 = SURFACE_CURVE('',#35184,(#35189,#35195),.PCURVE_S1.); +#35184 = CIRCLE('',#35185,0.15); +#35185 = AXIS2_PLACEMENT_3D('',#35186,#35187,#35188); +#35186 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); +#35187 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35188 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#35189 = PCURVE('',#34545,#35190); +#35190 = DEFINITIONAL_REPRESENTATION('',(#35191),#35194); +#35191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35192,#35193),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#32800 = CARTESIAN_POINT('',(1.570796326795,-1.1)); -#32801 = CARTESIAN_POINT('',(0.E+000,-1.1)); -#32802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35192 = CARTESIAN_POINT('',(1.570796326795,-1.1)); +#35193 = CARTESIAN_POINT('',(0.E+000,-1.1)); +#35194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32803 = PCURVE('',#31245,#32804); -#32804 = DEFINITIONAL_REPRESENTATION('',(#32805),#32831); -#32805 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32806,#32807,#32808,#32809, - #32810,#32811,#32812,#32813,#32814,#32815,#32816,#32817,#32818, - #32819,#32820,#32821,#32822,#32823,#32824,#32825,#32826,#32827, - #32828,#32829,#32830),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35195 = PCURVE('',#33637,#35196); +#35196 = DEFINITIONAL_REPRESENTATION('',(#35197),#35223); +#35197 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35198,#35199,#35200,#35201, + #35202,#35203,#35204,#35205,#35206,#35207,#35208,#35209,#35210, + #35211,#35212,#35213,#35214,#35215,#35216,#35217,#35218,#35219, + #35220,#35221,#35222),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -40573,228 +43562,228 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#32806 = CARTESIAN_POINT('',(5.18753264259E-015,1.570796326795)); -#32807 = CARTESIAN_POINT('',(6.098154026375E-015,1.54699638245)); -#32808 = CARTESIAN_POINT('',(5.699925215548E-015,1.499396493759)); -#32809 = CARTESIAN_POINT('',(2.028226561561E-015,1.427996660723)); -#32810 = CARTESIAN_POINT('',(1.789519467958E-015,1.356596827687)); -#32811 = CARTESIAN_POINT('',(1.259643980478E-015,1.28519699465)); -#32812 = CARTESIAN_POINT('',(1.053301329573E-015,1.213797161614)); -#32813 = CARTESIAN_POINT('',(8.81009490987E-016,1.142397328578)); -#32814 = CARTESIAN_POINT('',(7.677878197364E-016,1.070997495542)); -#32815 = CARTESIAN_POINT('',(6.81017621214E-016,0.999597662506)); -#32816 = CARTESIAN_POINT('',(6.152049757945E-016,0.92819782947)); -#32817 = CARTESIAN_POINT('',(5.633665459956E-016,0.856797996434)); -#32818 = CARTESIAN_POINT('',(5.220437421121E-016,0.785398163397)); -#32819 = CARTESIAN_POINT('',(4.886434029234E-016,0.713998330361)); -#32820 = CARTESIAN_POINT('',(4.614538335283E-016,0.642598497325)); -#32821 = CARTESIAN_POINT('',(4.392222874241E-016,0.571198664289)); -#32822 = CARTESIAN_POINT('',(4.211063178408E-016,0.499798831253)); -#32823 = CARTESIAN_POINT('',(4.062592472819E-016,0.428398998217)); -#32824 = CARTESIAN_POINT('',(3.948944540052E-016,0.356999165181)); -#32825 = CARTESIAN_POINT('',(3.840297395834E-016,0.285599332145)); -#32826 = CARTESIAN_POINT('',(3.83173465847E-016,0.214199499108)); -#32827 = CARTESIAN_POINT('',(3.556533820824E-016,0.142799666072)); -#32828 = CARTESIAN_POINT('',(4.374924048135E-016,7.139983303613E-002)); -#32829 = CARTESIAN_POINT('',(2.261607624683E-016,2.379994434538E-002)); -#32830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#32831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32832 = ORIENTED_EDGE('',*,*,#32139,.F.); -#32833 = ADVANCED_FACE('',(#32834),#30294,.T.); -#32834 = FACE_BOUND('',#32835,.T.); -#32835 = EDGE_LOOP('',(#32836,#32837,#32838,#32839)); -#32836 = ORIENTED_EDGE('',*,*,#31936,.F.); -#32837 = ORIENTED_EDGE('',*,*,#32370,.F.); -#32838 = ORIENTED_EDGE('',*,*,#32033,.F.); -#32839 = ORIENTED_EDGE('',*,*,#30278,.F.); -#32840 = ADVANCED_FACE('',(#32841),#32208,.T.); -#32841 = FACE_BOUND('',#32842,.T.); -#32842 = EDGE_LOOP('',(#32843,#32863,#32864,#32884)); -#32843 = ORIENTED_EDGE('',*,*,#32844,.F.); -#32844 = EDGE_CURVE('',#31775,#32326,#32845,.T.); -#32845 = SURFACE_CURVE('',#32846,(#32851,#32857),.PCURVE_S1.); -#32846 = CIRCLE('',#32847,0.15); -#32847 = AXIS2_PLACEMENT_3D('',#32848,#32849,#32850); -#32848 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); -#32849 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32850 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32851 = PCURVE('',#32208,#32852); -#32852 = DEFINITIONAL_REPRESENTATION('',(#32853),#32856); -#32853 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32854,#32855),.UNSPECIFIED., +#35198 = CARTESIAN_POINT('',(5.18753264259E-015,1.570796326795)); +#35199 = CARTESIAN_POINT('',(6.098154026375E-015,1.54699638245)); +#35200 = CARTESIAN_POINT('',(5.699925215548E-015,1.499396493759)); +#35201 = CARTESIAN_POINT('',(2.028226561561E-015,1.427996660723)); +#35202 = CARTESIAN_POINT('',(1.789519467958E-015,1.356596827687)); +#35203 = CARTESIAN_POINT('',(1.259643980478E-015,1.28519699465)); +#35204 = CARTESIAN_POINT('',(1.053301329573E-015,1.213797161614)); +#35205 = CARTESIAN_POINT('',(8.81009490987E-016,1.142397328578)); +#35206 = CARTESIAN_POINT('',(7.677878197364E-016,1.070997495542)); +#35207 = CARTESIAN_POINT('',(6.81017621214E-016,0.999597662506)); +#35208 = CARTESIAN_POINT('',(6.152049757945E-016,0.92819782947)); +#35209 = CARTESIAN_POINT('',(5.633665459956E-016,0.856797996434)); +#35210 = CARTESIAN_POINT('',(5.220437421121E-016,0.785398163397)); +#35211 = CARTESIAN_POINT('',(4.886434029234E-016,0.713998330361)); +#35212 = CARTESIAN_POINT('',(4.614538335283E-016,0.642598497325)); +#35213 = CARTESIAN_POINT('',(4.392222874241E-016,0.571198664289)); +#35214 = CARTESIAN_POINT('',(4.211063178408E-016,0.499798831253)); +#35215 = CARTESIAN_POINT('',(4.062592472819E-016,0.428398998217)); +#35216 = CARTESIAN_POINT('',(3.948944540052E-016,0.356999165181)); +#35217 = CARTESIAN_POINT('',(3.840297395834E-016,0.285599332145)); +#35218 = CARTESIAN_POINT('',(3.83173465847E-016,0.214199499108)); +#35219 = CARTESIAN_POINT('',(3.556533820824E-016,0.142799666072)); +#35220 = CARTESIAN_POINT('',(4.374924048135E-016,7.139983303613E-002)); +#35221 = CARTESIAN_POINT('',(2.261607624683E-016,2.379994434538E-002)); +#35222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35224 = ORIENTED_EDGE('',*,*,#34531,.F.); +#35225 = ADVANCED_FACE('',(#35226),#32686,.T.); +#35226 = FACE_BOUND('',#35227,.T.); +#35227 = EDGE_LOOP('',(#35228,#35229,#35230,#35231)); +#35228 = ORIENTED_EDGE('',*,*,#34328,.F.); +#35229 = ORIENTED_EDGE('',*,*,#34762,.F.); +#35230 = ORIENTED_EDGE('',*,*,#34425,.F.); +#35231 = ORIENTED_EDGE('',*,*,#32670,.F.); +#35232 = ADVANCED_FACE('',(#35233),#34600,.T.); +#35233 = FACE_BOUND('',#35234,.T.); +#35234 = EDGE_LOOP('',(#35235,#35255,#35256,#35276)); +#35235 = ORIENTED_EDGE('',*,*,#35236,.F.); +#35236 = EDGE_CURVE('',#34167,#34718,#35237,.T.); +#35237 = SURFACE_CURVE('',#35238,(#35243,#35249),.PCURVE_S1.); +#35238 = CIRCLE('',#35239,0.15); +#35239 = AXIS2_PLACEMENT_3D('',#35240,#35241,#35242); +#35240 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); +#35241 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#35242 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35243 = PCURVE('',#34600,#35244); +#35244 = DEFINITIONAL_REPRESENTATION('',(#35245),#35248); +#35245 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35246,#35247),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32854 = CARTESIAN_POINT('',(3.14159265359,0.63)); -#32855 = CARTESIAN_POINT('',(4.712388980385,0.63)); -#32856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35246 = CARTESIAN_POINT('',(3.14159265359,0.63)); +#35247 = CARTESIAN_POINT('',(4.712388980385,0.63)); +#35248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32857 = PCURVE('',#31815,#32858); -#32858 = DEFINITIONAL_REPRESENTATION('',(#32859),#32862); -#32859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32860,#32861),.UNSPECIFIED., +#35249 = PCURVE('',#34207,#35250); +#35250 = DEFINITIONAL_REPRESENTATION('',(#35251),#35254); +#35251 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35252,#35253),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32860 = CARTESIAN_POINT('',(4.712388980385,-1.850371707709E-016)); -#32861 = CARTESIAN_POINT('',(3.14159265359,-1.850371707709E-016)); -#32862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32863 = ORIENTED_EDGE('',*,*,#32194,.F.); -#32864 = ORIENTED_EDGE('',*,*,#32865,.F.); -#32865 = EDGE_CURVE('',#32275,#31910,#32866,.T.); -#32866 = SURFACE_CURVE('',#32867,(#32872,#32878),.PCURVE_S1.); -#32867 = CIRCLE('',#32868,0.15); -#32868 = AXIS2_PLACEMENT_3D('',#32869,#32870,#32871); -#32869 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); -#32870 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32871 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32872 = PCURVE('',#32208,#32873); -#32873 = DEFINITIONAL_REPRESENTATION('',(#32874),#32877); -#32874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32875,#32876),.UNSPECIFIED., +#35252 = CARTESIAN_POINT('',(4.712388980385,-1.850371707709E-016)); +#35253 = CARTESIAN_POINT('',(3.14159265359,-1.850371707709E-016)); +#35254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35255 = ORIENTED_EDGE('',*,*,#34586,.F.); +#35256 = ORIENTED_EDGE('',*,*,#35257,.F.); +#35257 = EDGE_CURVE('',#34667,#34302,#35258,.T.); +#35258 = SURFACE_CURVE('',#35259,(#35264,#35270),.PCURVE_S1.); +#35259 = CIRCLE('',#35260,0.15); +#35260 = AXIS2_PLACEMENT_3D('',#35261,#35262,#35263); +#35261 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); +#35262 = DIRECTION('',(0.E+000,1.,0.E+000)); +#35263 = DIRECTION('',(0.E+000,0.E+000,1.)); +#35264 = PCURVE('',#34600,#35265); +#35265 = DEFINITIONAL_REPRESENTATION('',(#35266),#35269); +#35266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35267,#35268),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#32875 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#32876 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#32877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35267 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#35268 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#35269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32878 = PCURVE('',#31992,#32879); -#32879 = DEFINITIONAL_REPRESENTATION('',(#32880),#32883); -#32880 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32881,#32882),.UNSPECIFIED., +#35270 = PCURVE('',#34384,#35271); +#35271 = DEFINITIONAL_REPRESENTATION('',(#35272),#35275); +#35272 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35273,#35274),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#32881 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#32882 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#32883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32884 = ORIENTED_EDGE('',*,*,#32347,.F.); -#32885 = ADVANCED_FACE('',(#32886),#31763,.T.); -#32886 = FACE_BOUND('',#32887,.T.); -#32887 = EDGE_LOOP('',(#32888,#32889,#32890,#32891)); -#32888 = ORIENTED_EDGE('',*,*,#31747,.F.); -#32889 = ORIENTED_EDGE('',*,*,#32556,.F.); -#32890 = ORIENTED_EDGE('',*,*,#31858,.F.); -#32891 = ORIENTED_EDGE('',*,*,#32391,.F.); -#32892 = ADVANCED_FACE('',(#32893),#31449,.T.); -#32893 = FACE_BOUND('',#32894,.T.); -#32894 = EDGE_LOOP('',(#32895,#32896,#32897,#32917)); -#32895 = ORIENTED_EDGE('',*,*,#32717,.T.); -#32896 = ORIENTED_EDGE('',*,*,#31433,.F.); -#32897 = ORIENTED_EDGE('',*,*,#32898,.F.); -#32898 = EDGE_CURVE('',#32445,#31407,#32899,.T.); -#32899 = SURFACE_CURVE('',#32900,(#32905,#32911),.PCURVE_S1.); -#32900 = CIRCLE('',#32901,0.15); -#32901 = AXIS2_PLACEMENT_3D('',#32902,#32903,#32904); -#32902 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); -#32903 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32904 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#32905 = PCURVE('',#31449,#32906); -#32906 = DEFINITIONAL_REPRESENTATION('',(#32907),#32910); -#32907 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32908,#32909),.UNSPECIFIED., +#35273 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35274 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#35275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35276 = ORIENTED_EDGE('',*,*,#34739,.F.); +#35277 = ADVANCED_FACE('',(#35278),#34155,.T.); +#35278 = FACE_BOUND('',#35279,.T.); +#35279 = EDGE_LOOP('',(#35280,#35281,#35282,#35283)); +#35280 = ORIENTED_EDGE('',*,*,#34139,.F.); +#35281 = ORIENTED_EDGE('',*,*,#34948,.F.); +#35282 = ORIENTED_EDGE('',*,*,#34250,.F.); +#35283 = ORIENTED_EDGE('',*,*,#34783,.F.); +#35284 = ADVANCED_FACE('',(#35285),#33841,.T.); +#35285 = FACE_BOUND('',#35286,.T.); +#35286 = EDGE_LOOP('',(#35287,#35288,#35289,#35309)); +#35287 = ORIENTED_EDGE('',*,*,#35109,.T.); +#35288 = ORIENTED_EDGE('',*,*,#33825,.F.); +#35289 = ORIENTED_EDGE('',*,*,#35290,.F.); +#35290 = EDGE_CURVE('',#34837,#33799,#35291,.T.); +#35291 = SURFACE_CURVE('',#35292,(#35297,#35303),.PCURVE_S1.); +#35292 = CIRCLE('',#35293,0.15); +#35293 = AXIS2_PLACEMENT_3D('',#35294,#35295,#35296); +#35294 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); +#35295 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35296 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#35297 = PCURVE('',#33841,#35298); +#35298 = DEFINITIONAL_REPRESENTATION('',(#35299),#35302); +#35299 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35300,#35301),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32908 = CARTESIAN_POINT('',(3.14159265359,-0.15)); -#32909 = CARTESIAN_POINT('',(4.712388980385,-0.15)); -#32910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35300 = CARTESIAN_POINT('',(3.14159265359,-0.15)); +#35301 = CARTESIAN_POINT('',(4.712388980385,-0.15)); +#35302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32911 = PCURVE('',#31732,#32912); -#32912 = DEFINITIONAL_REPRESENTATION('',(#32913),#32916); -#32913 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32914,#32915),.UNSPECIFIED., +#35303 = PCURVE('',#34124,#35304); +#35304 = DEFINITIONAL_REPRESENTATION('',(#35305),#35308); +#35305 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35306,#35307),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#32914 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#32915 = CARTESIAN_POINT('',(0.E+000,-1.570796326795)); -#32916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32917 = ORIENTED_EDGE('',*,*,#32444,.F.); -#32918 = ADVANCED_FACE('',(#32919),#31607,.T.); -#32919 = FACE_BOUND('',#32920,.T.); -#32920 = EDGE_LOOP('',(#32921,#32941,#32942,#32962)); -#32921 = ORIENTED_EDGE('',*,*,#32922,.F.); -#32922 = EDGE_CURVE('',#32467,#31158,#32923,.T.); -#32923 = SURFACE_CURVE('',#32924,(#32929,#32935),.PCURVE_S1.); -#32924 = CIRCLE('',#32925,0.15); -#32925 = AXIS2_PLACEMENT_3D('',#32926,#32927,#32928); -#32926 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); -#32927 = DIRECTION('',(0.E+000,1.,0.E+000)); -#32928 = DIRECTION('',(0.E+000,0.E+000,1.)); -#32929 = PCURVE('',#31607,#32930); -#32930 = DEFINITIONAL_REPRESENTATION('',(#32931),#32934); -#32931 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32932,#32933),.UNSPECIFIED., +#35306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35307 = CARTESIAN_POINT('',(0.E+000,-1.570796326795)); +#35308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35309 = ORIENTED_EDGE('',*,*,#34836,.F.); +#35310 = ADVANCED_FACE('',(#35311),#33999,.T.); +#35311 = FACE_BOUND('',#35312,.T.); +#35312 = EDGE_LOOP('',(#35313,#35333,#35334,#35354)); +#35313 = ORIENTED_EDGE('',*,*,#35314,.F.); +#35314 = EDGE_CURVE('',#34859,#33550,#35315,.T.); +#35315 = SURFACE_CURVE('',#35316,(#35321,#35327),.PCURVE_S1.); +#35316 = CIRCLE('',#35317,0.15); +#35317 = AXIS2_PLACEMENT_3D('',#35318,#35319,#35320); +#35318 = CARTESIAN_POINT('',(0.85,0.63,-0.475)); +#35319 = DIRECTION('',(0.E+000,1.,0.E+000)); +#35320 = DIRECTION('',(0.E+000,0.E+000,1.)); +#35321 = PCURVE('',#33999,#35322); +#35322 = DEFINITIONAL_REPRESENTATION('',(#35323),#35326); +#35323 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35324,#35325),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#32932 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#32933 = CARTESIAN_POINT('',(0.E+000,0.15)); -#32934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35324 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#35325 = CARTESIAN_POINT('',(0.E+000,0.15)); +#35326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32935 = PCURVE('',#31245,#32936); -#32936 = DEFINITIONAL_REPRESENTATION('',(#32937),#32940); -#32937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32938,#32939),.UNSPECIFIED., +#35327 = PCURVE('',#33637,#35328); +#35328 = DEFINITIONAL_REPRESENTATION('',(#35329),#35332); +#35329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35330,#35331),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#32938 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#32939 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#32940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32941 = ORIENTED_EDGE('',*,*,#32466,.F.); -#32942 = ORIENTED_EDGE('',*,*,#32943,.F.); -#32943 = EDGE_CURVE('',#31592,#32445,#32944,.T.); -#32944 = SURFACE_CURVE('',#32945,(#32950,#32956),.PCURVE_S1.); -#32945 = CIRCLE('',#32946,0.15); -#32946 = AXIS2_PLACEMENT_3D('',#32947,#32948,#32949); -#32947 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); -#32948 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#32949 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32950 = PCURVE('',#31607,#32951); -#32951 = DEFINITIONAL_REPRESENTATION('',(#32952),#32955); -#32952 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32953,#32954),.UNSPECIFIED., +#35330 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35331 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#35332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35333 = ORIENTED_EDGE('',*,*,#34858,.F.); +#35334 = ORIENTED_EDGE('',*,*,#35335,.F.); +#35335 = EDGE_CURVE('',#33984,#34837,#35336,.T.); +#35336 = SURFACE_CURVE('',#35337,(#35342,#35348),.PCURVE_S1.); +#35337 = CIRCLE('',#35338,0.15); +#35338 = AXIS2_PLACEMENT_3D('',#35339,#35340,#35341); +#35339 = CARTESIAN_POINT('',(0.85,0.15,-0.475)); +#35340 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#35341 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35342 = PCURVE('',#33999,#35343); +#35343 = DEFINITIONAL_REPRESENTATION('',(#35344),#35347); +#35344 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35345,#35346),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#32953 = CARTESIAN_POINT('',(0.E+000,0.63)); -#32954 = CARTESIAN_POINT('',(1.570796326795,0.63)); -#32955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35345 = CARTESIAN_POINT('',(0.E+000,0.63)); +#35346 = CARTESIAN_POINT('',(1.570796326795,0.63)); +#35347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#32956 = PCURVE('',#31732,#32957); -#32957 = DEFINITIONAL_REPRESENTATION('',(#32958),#32961); -#32958 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#32959,#32960),.UNSPECIFIED., +#35348 = PCURVE('',#34124,#35349); +#35349 = DEFINITIONAL_REPRESENTATION('',(#35350),#35353); +#35350 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35351,#35352),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#32959 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#32960 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#32961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#32962 = ORIENTED_EDGE('',*,*,#31591,.F.); -#32963 = ADVANCED_FACE('',(#32964),#31245,.T.); -#32964 = FACE_BOUND('',#32965,.T.); -#32965 = EDGE_LOOP('',(#32966,#32967,#32968)); -#32966 = ORIENTED_EDGE('',*,*,#32790,.T.); -#32967 = ORIENTED_EDGE('',*,*,#32922,.T.); -#32968 = ORIENTED_EDGE('',*,*,#31231,.F.); -#32969 = ADVANCED_FACE('',(#32970),#31992,.T.); -#32970 = FACE_BOUND('',#32971,.T.); -#32971 = EDGE_LOOP('',(#32972,#32973,#32974)); -#32972 = ORIENTED_EDGE('',*,*,#32865,.T.); -#32973 = ORIENTED_EDGE('',*,*,#31978,.T.); -#32974 = ORIENTED_EDGE('',*,*,#32975,.F.); -#32975 = EDGE_CURVE('',#32275,#31957,#32976,.T.); -#32976 = SURFACE_CURVE('',#32977,(#32982,#33011),.PCURVE_S1.); -#32977 = CIRCLE('',#32978,0.15); -#32978 = AXIS2_PLACEMENT_3D('',#32979,#32980,#32981); -#32979 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); -#32980 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#32981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#32982 = PCURVE('',#31992,#32983); -#32983 = DEFINITIONAL_REPRESENTATION('',(#32984),#33010); -#32984 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#32985,#32986,#32987,#32988, - #32989,#32990,#32991,#32992,#32993,#32994,#32995,#32996,#32997, - #32998,#32999,#33000,#33001,#33002,#33003,#33004,#33005,#33006, - #33007,#33008,#33009),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35351 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#35352 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35354 = ORIENTED_EDGE('',*,*,#33983,.F.); +#35355 = ADVANCED_FACE('',(#35356),#33637,.T.); +#35356 = FACE_BOUND('',#35357,.T.); +#35357 = EDGE_LOOP('',(#35358,#35359,#35360)); +#35358 = ORIENTED_EDGE('',*,*,#35182,.T.); +#35359 = ORIENTED_EDGE('',*,*,#35314,.T.); +#35360 = ORIENTED_EDGE('',*,*,#33623,.F.); +#35361 = ADVANCED_FACE('',(#35362),#34384,.T.); +#35362 = FACE_BOUND('',#35363,.T.); +#35363 = EDGE_LOOP('',(#35364,#35365,#35366)); +#35364 = ORIENTED_EDGE('',*,*,#35257,.T.); +#35365 = ORIENTED_EDGE('',*,*,#34370,.T.); +#35366 = ORIENTED_EDGE('',*,*,#35367,.F.); +#35367 = EDGE_CURVE('',#34667,#34349,#35368,.T.); +#35368 = SURFACE_CURVE('',#35369,(#35374,#35403),.PCURVE_S1.); +#35369 = CIRCLE('',#35370,0.15); +#35370 = AXIS2_PLACEMENT_3D('',#35371,#35372,#35373); +#35371 = CARTESIAN_POINT('',(-0.85,0.63,0.475)); +#35372 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#35374 = PCURVE('',#34384,#35375); +#35375 = DEFINITIONAL_REPRESENTATION('',(#35376),#35402); +#35376 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35377,#35378,#35379,#35380, + #35381,#35382,#35383,#35384,#35385,#35386,#35387,#35388,#35389, + #35390,#35391,#35392,#35393,#35394,#35395,#35396,#35397,#35398, + #35399,#35400,#35401),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.212992486626,3.284392319662 ,3.355792152698,3.427191985734,3.49859181877,3.569991651807, 3.641391484843,3.712791317879,3.784191150915,3.855590983951, @@ -40802,63 +43791,63 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.212590149132,4.283989982168,4.355389815204,4.42678964824, 4.498189481276,4.569589314312,4.640989147349,4.712388980385), .QUASI_UNIFORM_KNOTS.); -#32985 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#32986 = CARTESIAN_POINT('',(3.14159265359,2.379994434538E-002)); -#32987 = CARTESIAN_POINT('',(3.14159265359,7.139983303613E-002)); -#32988 = CARTESIAN_POINT('',(3.14159265359,0.142799666072)); -#32989 = CARTESIAN_POINT('',(3.14159265359,0.214199499108)); -#32990 = CARTESIAN_POINT('',(3.14159265359,0.285599332145)); -#32991 = CARTESIAN_POINT('',(3.14159265359,0.356999165181)); -#32992 = CARTESIAN_POINT('',(3.14159265359,0.428398998217)); -#32993 = CARTESIAN_POINT('',(3.14159265359,0.499798831253)); -#32994 = CARTESIAN_POINT('',(3.14159265359,0.571198664289)); -#32995 = CARTESIAN_POINT('',(3.14159265359,0.642598497325)); -#32996 = CARTESIAN_POINT('',(3.14159265359,0.713998330361)); -#32997 = CARTESIAN_POINT('',(3.14159265359,0.785398163397)); -#32998 = CARTESIAN_POINT('',(3.14159265359,0.856797996434)); -#32999 = CARTESIAN_POINT('',(3.14159265359,0.92819782947)); -#33000 = CARTESIAN_POINT('',(3.14159265359,0.999597662506)); -#33001 = CARTESIAN_POINT('',(3.14159265359,1.070997495542)); -#33002 = CARTESIAN_POINT('',(3.14159265359,1.142397328578)); -#33003 = CARTESIAN_POINT('',(3.14159265359,1.213797161614)); -#33004 = CARTESIAN_POINT('',(3.14159265359,1.28519699465)); -#33005 = CARTESIAN_POINT('',(3.14159265359,1.356596827687)); -#33006 = CARTESIAN_POINT('',(3.14159265359,1.427996660723)); -#33007 = CARTESIAN_POINT('',(3.14159265359,1.499396493759)); -#33008 = CARTESIAN_POINT('',(3.14159265359,1.54699638245)); -#33009 = CARTESIAN_POINT('',(3.14159265359,1.570796326795)); -#33010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33011 = PCURVE('',#32122,#33012); -#33012 = DEFINITIONAL_REPRESENTATION('',(#33013),#33016); -#33013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33014,#33015),.UNSPECIFIED., +#35377 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35378 = CARTESIAN_POINT('',(3.14159265359,2.379994434538E-002)); +#35379 = CARTESIAN_POINT('',(3.14159265359,7.139983303613E-002)); +#35380 = CARTESIAN_POINT('',(3.14159265359,0.142799666072)); +#35381 = CARTESIAN_POINT('',(3.14159265359,0.214199499108)); +#35382 = CARTESIAN_POINT('',(3.14159265359,0.285599332145)); +#35383 = CARTESIAN_POINT('',(3.14159265359,0.356999165181)); +#35384 = CARTESIAN_POINT('',(3.14159265359,0.428398998217)); +#35385 = CARTESIAN_POINT('',(3.14159265359,0.499798831253)); +#35386 = CARTESIAN_POINT('',(3.14159265359,0.571198664289)); +#35387 = CARTESIAN_POINT('',(3.14159265359,0.642598497325)); +#35388 = CARTESIAN_POINT('',(3.14159265359,0.713998330361)); +#35389 = CARTESIAN_POINT('',(3.14159265359,0.785398163397)); +#35390 = CARTESIAN_POINT('',(3.14159265359,0.856797996434)); +#35391 = CARTESIAN_POINT('',(3.14159265359,0.92819782947)); +#35392 = CARTESIAN_POINT('',(3.14159265359,0.999597662506)); +#35393 = CARTESIAN_POINT('',(3.14159265359,1.070997495542)); +#35394 = CARTESIAN_POINT('',(3.14159265359,1.142397328578)); +#35395 = CARTESIAN_POINT('',(3.14159265359,1.213797161614)); +#35396 = CARTESIAN_POINT('',(3.14159265359,1.28519699465)); +#35397 = CARTESIAN_POINT('',(3.14159265359,1.356596827687)); +#35398 = CARTESIAN_POINT('',(3.14159265359,1.427996660723)); +#35399 = CARTESIAN_POINT('',(3.14159265359,1.499396493759)); +#35400 = CARTESIAN_POINT('',(3.14159265359,1.54699638245)); +#35401 = CARTESIAN_POINT('',(3.14159265359,1.570796326795)); +#35402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35403 = PCURVE('',#34514,#35404); +#35404 = DEFINITIONAL_REPRESENTATION('',(#35405),#35408); +#35405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35406,#35407),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#33014 = CARTESIAN_POINT('',(0.E+000,0.15)); -#33015 = CARTESIAN_POINT('',(1.570796326795,0.15)); -#33016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33017 = ADVANCED_FACE('',(#33018),#31815,.T.); -#33018 = FACE_BOUND('',#33019,.T.); -#33019 = EDGE_LOOP('',(#33020,#33021,#33022)); -#33020 = ORIENTED_EDGE('',*,*,#31801,.T.); -#33021 = ORIENTED_EDGE('',*,*,#32844,.T.); -#33022 = ORIENTED_EDGE('',*,*,#33023,.F.); -#33023 = EDGE_CURVE('',#31295,#32326,#33024,.T.); -#33024 = SURFACE_CURVE('',#33025,(#33030,#33059),.PCURVE_S1.); -#33025 = CIRCLE('',#33026,0.15); -#33026 = AXIS2_PLACEMENT_3D('',#33027,#33028,#33029); -#33027 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); -#33028 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#33029 = DIRECTION('',(1.,0.E+000,0.E+000)); -#33030 = PCURVE('',#31815,#33031); -#33031 = DEFINITIONAL_REPRESENTATION('',(#33032),#33058); -#33032 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33033,#33034,#33035,#33036, - #33037,#33038,#33039,#33040,#33041,#33042,#33043,#33044,#33045, - #33046,#33047,#33048,#33049,#33050,#33051,#33052,#33053,#33054, - #33055,#33056,#33057),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35406 = CARTESIAN_POINT('',(0.E+000,0.15)); +#35407 = CARTESIAN_POINT('',(1.570796326795,0.15)); +#35408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35409 = ADVANCED_FACE('',(#35410),#34207,.T.); +#35410 = FACE_BOUND('',#35411,.T.); +#35411 = EDGE_LOOP('',(#35412,#35413,#35414)); +#35412 = ORIENTED_EDGE('',*,*,#34193,.T.); +#35413 = ORIENTED_EDGE('',*,*,#35236,.T.); +#35414 = ORIENTED_EDGE('',*,*,#35415,.F.); +#35415 = EDGE_CURVE('',#33687,#34718,#35416,.T.); +#35416 = SURFACE_CURVE('',#35417,(#35422,#35451),.PCURVE_S1.); +#35417 = CIRCLE('',#35418,0.15); +#35418 = AXIS2_PLACEMENT_3D('',#35419,#35420,#35421); +#35419 = CARTESIAN_POINT('',(-0.85,0.15,0.475)); +#35420 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35421 = DIRECTION('',(1.,0.E+000,0.E+000)); +#35422 = PCURVE('',#34207,#35423); +#35423 = DEFINITIONAL_REPRESENTATION('',(#35424),#35450); +#35424 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35425,#35426,#35427,#35428, + #35429,#35430,#35431,#35432,#35433,#35434,#35435,#35436,#35437, + #35438,#35439,#35440,#35441,#35442,#35443,#35444,#35445,#35446, + #35447,#35448,#35449),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.642196159831, 1.713595992867,1.784995825903,1.856395658939,1.927795491976, 1.999195325012,2.070595158048,2.141994991084,2.21339482412, @@ -40866,85 +43855,85 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.570393989301,2.641793822337,2.713193655373,2.784593488409, 2.855993321445,2.927393154481,2.998792987518,3.070192820554, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#33033 = CARTESIAN_POINT('',(3.14159265359,-1.570796326795)); -#33034 = CARTESIAN_POINT('',(3.14159265359,-1.54699638245)); -#33035 = CARTESIAN_POINT('',(3.14159265359,-1.499396493759)); -#33036 = CARTESIAN_POINT('',(3.14159265359,-1.427996660723)); -#33037 = CARTESIAN_POINT('',(3.14159265359,-1.356596827687)); -#33038 = CARTESIAN_POINT('',(3.14159265359,-1.28519699465)); -#33039 = CARTESIAN_POINT('',(3.14159265359,-1.213797161614)); -#33040 = CARTESIAN_POINT('',(3.14159265359,-1.142397328578)); -#33041 = CARTESIAN_POINT('',(3.14159265359,-1.070997495542)); -#33042 = CARTESIAN_POINT('',(3.14159265359,-0.999597662506)); -#33043 = CARTESIAN_POINT('',(3.14159265359,-0.92819782947)); -#33044 = CARTESIAN_POINT('',(3.14159265359,-0.856797996434)); -#33045 = CARTESIAN_POINT('',(3.14159265359,-0.785398163397)); -#33046 = CARTESIAN_POINT('',(3.14159265359,-0.713998330361)); -#33047 = CARTESIAN_POINT('',(3.14159265359,-0.642598497325)); -#33048 = CARTESIAN_POINT('',(3.14159265359,-0.571198664289)); -#33049 = CARTESIAN_POINT('',(3.14159265359,-0.499798831253)); -#33050 = CARTESIAN_POINT('',(3.14159265359,-0.428398998217)); -#33051 = CARTESIAN_POINT('',(3.14159265359,-0.356999165181)); -#33052 = CARTESIAN_POINT('',(3.14159265359,-0.285599332145)); -#33053 = CARTESIAN_POINT('',(3.14159265359,-0.214199499108)); -#33054 = CARTESIAN_POINT('',(3.14159265359,-0.142799666072)); -#33055 = CARTESIAN_POINT('',(3.14159265359,-7.139983303613E-002)); -#33056 = CARTESIAN_POINT('',(3.14159265359,-2.379994434538E-002)); -#33057 = CARTESIAN_POINT('',(3.14159265359,-3.700743415417E-016)); -#33058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33059 = PCURVE('',#31337,#33060); -#33060 = DEFINITIONAL_REPRESENTATION('',(#33061),#33064); -#33061 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33062,#33063),.UNSPECIFIED., +#35425 = CARTESIAN_POINT('',(3.14159265359,-1.570796326795)); +#35426 = CARTESIAN_POINT('',(3.14159265359,-1.54699638245)); +#35427 = CARTESIAN_POINT('',(3.14159265359,-1.499396493759)); +#35428 = CARTESIAN_POINT('',(3.14159265359,-1.427996660723)); +#35429 = CARTESIAN_POINT('',(3.14159265359,-1.356596827687)); +#35430 = CARTESIAN_POINT('',(3.14159265359,-1.28519699465)); +#35431 = CARTESIAN_POINT('',(3.14159265359,-1.213797161614)); +#35432 = CARTESIAN_POINT('',(3.14159265359,-1.142397328578)); +#35433 = CARTESIAN_POINT('',(3.14159265359,-1.070997495542)); +#35434 = CARTESIAN_POINT('',(3.14159265359,-0.999597662506)); +#35435 = CARTESIAN_POINT('',(3.14159265359,-0.92819782947)); +#35436 = CARTESIAN_POINT('',(3.14159265359,-0.856797996434)); +#35437 = CARTESIAN_POINT('',(3.14159265359,-0.785398163397)); +#35438 = CARTESIAN_POINT('',(3.14159265359,-0.713998330361)); +#35439 = CARTESIAN_POINT('',(3.14159265359,-0.642598497325)); +#35440 = CARTESIAN_POINT('',(3.14159265359,-0.571198664289)); +#35441 = CARTESIAN_POINT('',(3.14159265359,-0.499798831253)); +#35442 = CARTESIAN_POINT('',(3.14159265359,-0.428398998217)); +#35443 = CARTESIAN_POINT('',(3.14159265359,-0.356999165181)); +#35444 = CARTESIAN_POINT('',(3.14159265359,-0.285599332145)); +#35445 = CARTESIAN_POINT('',(3.14159265359,-0.214199499108)); +#35446 = CARTESIAN_POINT('',(3.14159265359,-0.142799666072)); +#35447 = CARTESIAN_POINT('',(3.14159265359,-7.139983303613E-002)); +#35448 = CARTESIAN_POINT('',(3.14159265359,-2.379994434538E-002)); +#35449 = CARTESIAN_POINT('',(3.14159265359,-3.700743415417E-016)); +#35450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35451 = PCURVE('',#33729,#35452); +#35452 = DEFINITIONAL_REPRESENTATION('',(#35453),#35456); +#35453 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35454,#35455),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#33062 = CARTESIAN_POINT('',(4.712388980385,1.1)); -#33063 = CARTESIAN_POINT('',(3.14159265359,1.1)); -#33064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33065 = ADVANCED_FACE('',(#33066),#31732,.T.); -#33066 = FACE_BOUND('',#33067,.T.); -#33067 = EDGE_LOOP('',(#33068,#33069,#33070)); -#33068 = ORIENTED_EDGE('',*,*,#32943,.T.); -#33069 = ORIENTED_EDGE('',*,*,#32898,.T.); -#33070 = ORIENTED_EDGE('',*,*,#31718,.F.); -#33071 = ADVANCED_FACE('',(#33072),#30347,.T.); -#33072 = FACE_BOUND('',#33073,.T.); -#33073 = EDGE_LOOP('',(#33074,#33075,#33076,#33077)); -#33074 = ORIENTED_EDGE('',*,*,#31078,.F.); -#33075 = ORIENTED_EDGE('',*,*,#30333,.F.); -#33076 = ORIENTED_EDGE('',*,*,#31189,.F.); -#33077 = ORIENTED_EDGE('',*,*,#32532,.F.); -#33078 = ADVANCED_FACE('',(#33079),#32122,.T.); -#33079 = FACE_BOUND('',#33080,.T.); -#33080 = EDGE_LOOP('',(#33081,#33082,#33083,#33126)); -#33081 = ORIENTED_EDGE('',*,*,#32975,.T.); -#33082 = ORIENTED_EDGE('',*,*,#32108,.F.); -#33083 = ORIENTED_EDGE('',*,*,#33084,.F.); -#33084 = EDGE_CURVE('',#32277,#31052,#33085,.T.); -#33085 = SURFACE_CURVE('',#33086,(#33091,#33097),.PCURVE_S1.); -#33086 = CIRCLE('',#33087,0.15); -#33087 = AXIS2_PLACEMENT_3D('',#33088,#33089,#33090); -#33088 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); -#33089 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#33090 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#33091 = PCURVE('',#32122,#33092); -#33092 = DEFINITIONAL_REPRESENTATION('',(#33093),#33096); -#33093 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33094,#33095),.UNSPECIFIED., +#35454 = CARTESIAN_POINT('',(4.712388980385,1.1)); +#35455 = CARTESIAN_POINT('',(3.14159265359,1.1)); +#35456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35457 = ADVANCED_FACE('',(#35458),#34124,.T.); +#35458 = FACE_BOUND('',#35459,.T.); +#35459 = EDGE_LOOP('',(#35460,#35461,#35462)); +#35460 = ORIENTED_EDGE('',*,*,#35335,.T.); +#35461 = ORIENTED_EDGE('',*,*,#35290,.T.); +#35462 = ORIENTED_EDGE('',*,*,#34110,.F.); +#35463 = ADVANCED_FACE('',(#35464),#32739,.T.); +#35464 = FACE_BOUND('',#35465,.T.); +#35465 = EDGE_LOOP('',(#35466,#35467,#35468,#35469)); +#35466 = ORIENTED_EDGE('',*,*,#33470,.F.); +#35467 = ORIENTED_EDGE('',*,*,#32725,.F.); +#35468 = ORIENTED_EDGE('',*,*,#33581,.F.); +#35469 = ORIENTED_EDGE('',*,*,#34924,.F.); +#35470 = ADVANCED_FACE('',(#35471),#34514,.T.); +#35471 = FACE_BOUND('',#35472,.T.); +#35472 = EDGE_LOOP('',(#35473,#35474,#35475,#35518)); +#35473 = ORIENTED_EDGE('',*,*,#35367,.T.); +#35474 = ORIENTED_EDGE('',*,*,#34500,.F.); +#35475 = ORIENTED_EDGE('',*,*,#35476,.F.); +#35476 = EDGE_CURVE('',#34669,#33444,#35477,.T.); +#35477 = SURFACE_CURVE('',#35478,(#35483,#35489),.PCURVE_S1.); +#35478 = CIRCLE('',#35479,0.15); +#35479 = AXIS2_PLACEMENT_3D('',#35480,#35481,#35482); +#35480 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); +#35481 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35482 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#35483 = PCURVE('',#34514,#35484); +#35484 = DEFINITIONAL_REPRESENTATION('',(#35485),#35488); +#35485 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35486,#35487),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#33094 = CARTESIAN_POINT('',(0.E+000,1.1)); -#33095 = CARTESIAN_POINT('',(1.570796326795,1.1)); -#33096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35486 = CARTESIAN_POINT('',(0.E+000,1.1)); +#35487 = CARTESIAN_POINT('',(1.570796326795,1.1)); +#35488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#33097 = PCURVE('',#31141,#33098); -#33098 = DEFINITIONAL_REPRESENTATION('',(#33099),#33125); -#33099 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33100,#33101,#33102,#33103, - #33104,#33105,#33106,#33107,#33108,#33109,#33110,#33111,#33112, - #33113,#33114,#33115,#33116,#33117,#33118,#33119,#33120,#33121, - #33122,#33123,#33124),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#35489 = PCURVE('',#33533,#35490); +#35490 = DEFINITIONAL_REPRESENTATION('',(#35491),#35517); +#35491 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35492,#35493,#35494,#35495, + #35496,#35497,#35498,#35499,#35500,#35501,#35502,#35503,#35504, + #35505,#35506,#35507,#35508,#35509,#35510,#35511,#35512,#35513, + #35514,#35515,#35516),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -40952,2921 +43941,2921 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#33100 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#33101 = CARTESIAN_POINT('',(3.14159265359,2.379994434538E-002)); -#33102 = CARTESIAN_POINT('',(3.14159265359,7.139983303613E-002)); -#33103 = CARTESIAN_POINT('',(3.14159265359,0.142799666072)); -#33104 = CARTESIAN_POINT('',(3.14159265359,0.214199499108)); -#33105 = CARTESIAN_POINT('',(3.14159265359,0.285599332145)); -#33106 = CARTESIAN_POINT('',(3.14159265359,0.356999165181)); -#33107 = CARTESIAN_POINT('',(3.14159265359,0.428398998217)); -#33108 = CARTESIAN_POINT('',(3.14159265359,0.499798831253)); -#33109 = CARTESIAN_POINT('',(3.14159265359,0.571198664289)); -#33110 = CARTESIAN_POINT('',(3.14159265359,0.642598497325)); -#33111 = CARTESIAN_POINT('',(3.14159265359,0.713998330361)); -#33112 = CARTESIAN_POINT('',(3.14159265359,0.785398163397)); -#33113 = CARTESIAN_POINT('',(3.14159265359,0.856797996434)); -#33114 = CARTESIAN_POINT('',(3.14159265359,0.92819782947)); -#33115 = CARTESIAN_POINT('',(3.14159265359,0.999597662506)); -#33116 = CARTESIAN_POINT('',(3.14159265359,1.070997495542)); -#33117 = CARTESIAN_POINT('',(3.14159265359,1.142397328578)); -#33118 = CARTESIAN_POINT('',(3.14159265359,1.213797161614)); -#33119 = CARTESIAN_POINT('',(3.14159265359,1.28519699465)); -#33120 = CARTESIAN_POINT('',(3.14159265359,1.356596827687)); -#33121 = CARTESIAN_POINT('',(3.14159265359,1.427996660723)); -#33122 = CARTESIAN_POINT('',(3.14159265359,1.499396493759)); -#33123 = CARTESIAN_POINT('',(3.14159265359,1.54699638245)); -#33124 = CARTESIAN_POINT('',(3.14159265359,1.570796326795)); -#33125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33126 = ORIENTED_EDGE('',*,*,#32274,.F.); -#33127 = ADVANCED_FACE('',(#33128),#31337,.T.); -#33128 = FACE_BOUND('',#33129,.T.); -#33129 = EDGE_LOOP('',(#33130,#33131,#33132,#33152)); -#33130 = ORIENTED_EDGE('',*,*,#33023,.T.); -#33131 = ORIENTED_EDGE('',*,*,#32325,.F.); -#33132 = ORIENTED_EDGE('',*,*,#33133,.F.); -#33133 = EDGE_CURVE('',#31322,#32304,#33134,.T.); -#33134 = SURFACE_CURVE('',#33135,(#33140,#33146),.PCURVE_S1.); -#33135 = CIRCLE('',#33136,0.15); -#33136 = AXIS2_PLACEMENT_3D('',#33137,#33138,#33139); -#33137 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); -#33138 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#33139 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#33140 = PCURVE('',#31337,#33141); -#33141 = DEFINITIONAL_REPRESENTATION('',(#33142),#33145); -#33142 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33143,#33144),.UNSPECIFIED., +#35492 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35493 = CARTESIAN_POINT('',(3.14159265359,2.379994434538E-002)); +#35494 = CARTESIAN_POINT('',(3.14159265359,7.139983303613E-002)); +#35495 = CARTESIAN_POINT('',(3.14159265359,0.142799666072)); +#35496 = CARTESIAN_POINT('',(3.14159265359,0.214199499108)); +#35497 = CARTESIAN_POINT('',(3.14159265359,0.285599332145)); +#35498 = CARTESIAN_POINT('',(3.14159265359,0.356999165181)); +#35499 = CARTESIAN_POINT('',(3.14159265359,0.428398998217)); +#35500 = CARTESIAN_POINT('',(3.14159265359,0.499798831253)); +#35501 = CARTESIAN_POINT('',(3.14159265359,0.571198664289)); +#35502 = CARTESIAN_POINT('',(3.14159265359,0.642598497325)); +#35503 = CARTESIAN_POINT('',(3.14159265359,0.713998330361)); +#35504 = CARTESIAN_POINT('',(3.14159265359,0.785398163397)); +#35505 = CARTESIAN_POINT('',(3.14159265359,0.856797996434)); +#35506 = CARTESIAN_POINT('',(3.14159265359,0.92819782947)); +#35507 = CARTESIAN_POINT('',(3.14159265359,0.999597662506)); +#35508 = CARTESIAN_POINT('',(3.14159265359,1.070997495542)); +#35509 = CARTESIAN_POINT('',(3.14159265359,1.142397328578)); +#35510 = CARTESIAN_POINT('',(3.14159265359,1.213797161614)); +#35511 = CARTESIAN_POINT('',(3.14159265359,1.28519699465)); +#35512 = CARTESIAN_POINT('',(3.14159265359,1.356596827687)); +#35513 = CARTESIAN_POINT('',(3.14159265359,1.427996660723)); +#35514 = CARTESIAN_POINT('',(3.14159265359,1.499396493759)); +#35515 = CARTESIAN_POINT('',(3.14159265359,1.54699638245)); +#35516 = CARTESIAN_POINT('',(3.14159265359,1.570796326795)); +#35517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35518 = ORIENTED_EDGE('',*,*,#34666,.F.); +#35519 = ADVANCED_FACE('',(#35520),#33729,.T.); +#35520 = FACE_BOUND('',#35521,.T.); +#35521 = EDGE_LOOP('',(#35522,#35523,#35524,#35544)); +#35522 = ORIENTED_EDGE('',*,*,#35415,.T.); +#35523 = ORIENTED_EDGE('',*,*,#34717,.F.); +#35524 = ORIENTED_EDGE('',*,*,#35525,.F.); +#35525 = EDGE_CURVE('',#33714,#34696,#35526,.T.); +#35526 = SURFACE_CURVE('',#35527,(#35532,#35538),.PCURVE_S1.); +#35527 = CIRCLE('',#35528,0.15); +#35528 = AXIS2_PLACEMENT_3D('',#35529,#35530,#35531); +#35529 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); +#35530 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35531 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#35532 = PCURVE('',#33729,#35533); +#35533 = DEFINITIONAL_REPRESENTATION('',(#35534),#35537); +#35534 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35535,#35536),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#33143 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#33144 = CARTESIAN_POINT('',(3.14159265359,0.15)); -#33145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35535 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#35536 = CARTESIAN_POINT('',(3.14159265359,0.15)); +#35537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#33146 = PCURVE('',#31682,#33147); -#33147 = DEFINITIONAL_REPRESENTATION('',(#33148),#33151); -#33148 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33149,#33150),.UNSPECIFIED., +#35538 = PCURVE('',#34074,#35539); +#35539 = DEFINITIONAL_REPRESENTATION('',(#35540),#35543); +#35540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35541,#35542),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#33149 = CARTESIAN_POINT('',(3.14159265359,-1.570796326795)); -#33150 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#33151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33152 = ORIENTED_EDGE('',*,*,#31321,.F.); -#33153 = ADVANCED_FACE('',(#33154),#31656,.T.); -#33154 = FACE_BOUND('',#33155,.T.); -#33155 = EDGE_LOOP('',(#33156,#33157,#33158,#33159)); -#33156 = ORIENTED_EDGE('',*,*,#31642,.F.); -#33157 = ORIENTED_EDGE('',*,*,#32511,.F.); -#33158 = ORIENTED_EDGE('',*,*,#31697,.F.); -#33159 = ORIENTED_EDGE('',*,*,#32577,.F.); -#33160 = ADVANCED_FACE('',(#33161),#31141,.T.); -#33161 = FACE_BOUND('',#33162,.T.); -#33162 = EDGE_LOOP('',(#33163,#33164,#33165)); -#33163 = ORIENTED_EDGE('',*,*,#33084,.T.); -#33164 = ORIENTED_EDGE('',*,*,#31127,.T.); -#33165 = ORIENTED_EDGE('',*,*,#33166,.F.); -#33166 = EDGE_CURVE('',#32277,#31101,#33167,.T.); -#33167 = SURFACE_CURVE('',#33168,(#33173,#33179),.PCURVE_S1.); -#33168 = CIRCLE('',#33169,0.15); -#33169 = AXIS2_PLACEMENT_3D('',#33170,#33171,#33172); -#33170 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); -#33171 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#33172 = DIRECTION('',(7.228014483237E-016,0.E+000,1.)); -#33173 = PCURVE('',#31141,#33174); -#33174 = DEFINITIONAL_REPRESENTATION('',(#33175),#33178); -#33175 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33176,#33177),.UNSPECIFIED., +#35541 = CARTESIAN_POINT('',(3.14159265359,-1.570796326795)); +#35542 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35544 = ORIENTED_EDGE('',*,*,#33713,.F.); +#35545 = ADVANCED_FACE('',(#35546),#34048,.T.); +#35546 = FACE_BOUND('',#35547,.T.); +#35547 = EDGE_LOOP('',(#35548,#35549,#35550,#35551)); +#35548 = ORIENTED_EDGE('',*,*,#34034,.F.); +#35549 = ORIENTED_EDGE('',*,*,#34903,.F.); +#35550 = ORIENTED_EDGE('',*,*,#34089,.F.); +#35551 = ORIENTED_EDGE('',*,*,#34969,.F.); +#35552 = ADVANCED_FACE('',(#35553),#33533,.T.); +#35553 = FACE_BOUND('',#35554,.T.); +#35554 = EDGE_LOOP('',(#35555,#35556,#35557)); +#35555 = ORIENTED_EDGE('',*,*,#35476,.T.); +#35556 = ORIENTED_EDGE('',*,*,#33519,.T.); +#35557 = ORIENTED_EDGE('',*,*,#35558,.F.); +#35558 = EDGE_CURVE('',#34669,#33493,#35559,.T.); +#35559 = SURFACE_CURVE('',#35560,(#35565,#35571),.PCURVE_S1.); +#35560 = CIRCLE('',#35561,0.15); +#35561 = AXIS2_PLACEMENT_3D('',#35562,#35563,#35564); +#35562 = CARTESIAN_POINT('',(-0.85,0.63,-0.475)); +#35563 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#35564 = DIRECTION('',(7.228014483237E-016,0.E+000,1.)); +#35565 = PCURVE('',#33533,#35566); +#35566 = DEFINITIONAL_REPRESENTATION('',(#35567),#35570); +#35567 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35568,#35569),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#33176 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#33177 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#33178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35568 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35569 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#35570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#33179 = PCURVE('',#31552,#33180); -#33180 = DEFINITIONAL_REPRESENTATION('',(#33181),#33184); -#33181 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33182,#33183),.UNSPECIFIED., +#35571 = PCURVE('',#33944,#35572); +#35572 = DEFINITIONAL_REPRESENTATION('',(#35573),#35576); +#35573 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35574,#35575),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#33182 = CARTESIAN_POINT('',(4.712388980385,0.15)); -#33183 = CARTESIAN_POINT('',(6.28318530718,0.15)); -#33184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33185 = ADVANCED_FACE('',(#33186),#31682,.T.); -#33186 = FACE_BOUND('',#33187,.T.); -#33187 = EDGE_LOOP('',(#33188,#33189,#33190)); -#33188 = ORIENTED_EDGE('',*,*,#31668,.T.); -#33189 = ORIENTED_EDGE('',*,*,#33133,.T.); -#33190 = ORIENTED_EDGE('',*,*,#33191,.F.); -#33191 = EDGE_CURVE('',#31517,#32304,#33192,.T.); -#33192 = SURFACE_CURVE('',#33193,(#33198,#33204),.PCURVE_S1.); -#33193 = CIRCLE('',#33194,0.15); -#33194 = AXIS2_PLACEMENT_3D('',#33195,#33196,#33197); -#33195 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); -#33196 = DIRECTION('',(0.E+000,1.,0.E+000)); -#33197 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#33198 = PCURVE('',#31682,#33199); -#33199 = DEFINITIONAL_REPRESENTATION('',(#33200),#33203); -#33200 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33201,#33202),.UNSPECIFIED., +#35574 = CARTESIAN_POINT('',(4.712388980385,0.15)); +#35575 = CARTESIAN_POINT('',(6.28318530718,0.15)); +#35576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35577 = ADVANCED_FACE('',(#35578),#34074,.T.); +#35578 = FACE_BOUND('',#35579,.T.); +#35579 = EDGE_LOOP('',(#35580,#35581,#35582)); +#35580 = ORIENTED_EDGE('',*,*,#34060,.T.); +#35581 = ORIENTED_EDGE('',*,*,#35525,.T.); +#35582 = ORIENTED_EDGE('',*,*,#35583,.F.); +#35583 = EDGE_CURVE('',#33909,#34696,#35584,.T.); +#35584 = SURFACE_CURVE('',#35585,(#35590,#35596),.PCURVE_S1.); +#35585 = CIRCLE('',#35586,0.15); +#35586 = AXIS2_PLACEMENT_3D('',#35587,#35588,#35589); +#35587 = CARTESIAN_POINT('',(-0.85,0.15,-0.475)); +#35588 = DIRECTION('',(0.E+000,1.,0.E+000)); +#35589 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#35590 = PCURVE('',#34074,#35591); +#35591 = DEFINITIONAL_REPRESENTATION('',(#35592),#35595); +#35592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35593,#35594),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#33201 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#33202 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#33203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#35593 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#35594 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#35595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#33204 = PCURVE('',#31552,#33205); -#33205 = DEFINITIONAL_REPRESENTATION('',(#33206),#33209); -#33206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#33207,#33208),.UNSPECIFIED., +#35596 = PCURVE('',#33944,#35597); +#35597 = DEFINITIONAL_REPRESENTATION('',(#35598),#35601); +#35598 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35599,#35600),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#33207 = CARTESIAN_POINT('',(6.28318530718,0.63)); -#33208 = CARTESIAN_POINT('',(4.712388980385,0.63)); -#33209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33210 = ADVANCED_FACE('',(#33211),#31552,.T.); -#33211 = FACE_BOUND('',#33212,.T.); -#33212 = EDGE_LOOP('',(#33213,#33214,#33215,#33216)); -#33213 = ORIENTED_EDGE('',*,*,#33166,.T.); -#33214 = ORIENTED_EDGE('',*,*,#31538,.F.); -#33215 = ORIENTED_EDGE('',*,*,#33191,.T.); -#33216 = ORIENTED_EDGE('',*,*,#32303,.F.); -#33217 = ADVANCED_FACE('',(#33218,#33537,#33947),#33244,.T.); -#33218 = FACE_BOUND('',#33219,.T.); -#33219 = EDGE_LOOP('',(#33220,#33305,#33383,#33461)); -#33220 = ORIENTED_EDGE('',*,*,#33221,.F.); -#33221 = EDGE_CURVE('',#33222,#33224,#33226,.T.); -#33222 = VERTEX_POINT('',#33223); -#33223 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#33224 = VERTEX_POINT('',#33225); -#33225 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#33226 = SURFACE_CURVE('',#33227,(#33243,#33267),.PCURVE_S1.); -#33227 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33228,#33229,#33230,#33231, - #33232,#33233,#33234,#33235,#33236,#33237,#33238,#33239,#33240, - #33241,#33242),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35599 = CARTESIAN_POINT('',(6.28318530718,0.63)); +#35600 = CARTESIAN_POINT('',(4.712388980385,0.63)); +#35601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35602 = ADVANCED_FACE('',(#35603),#33944,.T.); +#35603 = FACE_BOUND('',#35604,.T.); +#35604 = EDGE_LOOP('',(#35605,#35606,#35607,#35608)); +#35605 = ORIENTED_EDGE('',*,*,#35558,.T.); +#35606 = ORIENTED_EDGE('',*,*,#33930,.F.); +#35607 = ORIENTED_EDGE('',*,*,#35583,.T.); +#35608 = ORIENTED_EDGE('',*,*,#34695,.F.); +#35609 = ADVANCED_FACE('',(#35610,#35929,#36339),#35636,.T.); +#35610 = FACE_BOUND('',#35611,.T.); +#35611 = EDGE_LOOP('',(#35612,#35697,#35775,#35853)); +#35612 = ORIENTED_EDGE('',*,*,#35613,.F.); +#35613 = EDGE_CURVE('',#35614,#35616,#35618,.T.); +#35614 = VERTEX_POINT('',#35615); +#35615 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#35616 = VERTEX_POINT('',#35617); +#35617 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#35618 = SURFACE_CURVE('',#35619,(#35635,#35659),.PCURVE_S1.); +#35619 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35620,#35621,#35622,#35623, + #35624,#35625,#35626,#35627,#35628,#35629,#35630,#35631,#35632, + #35633,#35634),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.127393941339,0.246181611293,0.361268004354,0.477140268037, 0.536326583436,0.595671915044,0.656618953206,0.718835621496, 0.783581552706,0.851587816689,0.923926527481,1.),.UNSPECIFIED.); -#33228 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#33229 = CARTESIAN_POINT('',(-0.190633379827,0.782,-0.376782386698)); -#33230 = CARTESIAN_POINT('',(-0.19044452705,0.782,-0.371717001692)); -#33231 = CARTESIAN_POINT('',(-0.188390732865,0.782,-0.364521993412)); -#33232 = CARTESIAN_POINT('',(-0.185179194788,0.782,-0.358058858245)); -#33233 = CARTESIAN_POINT('',(-0.181414230001,0.782,-0.353371942249)); -#33234 = CARTESIAN_POINT('',(-0.177804574294,0.782,-0.350178503967)); -#33235 = CARTESIAN_POINT('',(-0.17479181951,0.782,-0.348046358697)); -#33236 = CARTESIAN_POINT('',(-0.171499461141,0.782,-0.346236210411)); -#33237 = CARTESIAN_POINT('',(-0.167903647571,0.782,-0.344829249004)); -#33238 = CARTESIAN_POINT('',(-0.164091469566,0.782,-0.343582768799)); -#33239 = CARTESIAN_POINT('',(-0.159931450534,0.782,-0.342886076981)); -#33240 = CARTESIAN_POINT('',(-0.155521369245,0.782,-0.342319707935)); -#33241 = CARTESIAN_POINT('',(-0.152472577135,0.782,-0.342278689615)); -#33242 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#33243 = PCURVE('',#33244,#33249); -#33244 = PLANE('',#33245); -#33245 = AXIS2_PLACEMENT_3D('',#33246,#33247,#33248); -#33246 = CARTESIAN_POINT('',(-0.221176146186,0.782,-0.304816046149)); -#33247 = DIRECTION('',(0.E+000,1.,0.E+000)); -#33248 = DIRECTION('',(0.E+000,0.E+000,1.)); -#33249 = DEFINITIONAL_REPRESENTATION('',(#33250),#33266); -#33250 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33251,#33252,#33253,#33254, - #33255,#33256,#33257,#33258,#33259,#33260,#33261,#33262,#33263, - #33264,#33265),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35620 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#35621 = CARTESIAN_POINT('',(-0.190633379827,0.782,-0.376782386698)); +#35622 = CARTESIAN_POINT('',(-0.19044452705,0.782,-0.371717001692)); +#35623 = CARTESIAN_POINT('',(-0.188390732865,0.782,-0.364521993412)); +#35624 = CARTESIAN_POINT('',(-0.185179194788,0.782,-0.358058858245)); +#35625 = CARTESIAN_POINT('',(-0.181414230001,0.782,-0.353371942249)); +#35626 = CARTESIAN_POINT('',(-0.177804574294,0.782,-0.350178503967)); +#35627 = CARTESIAN_POINT('',(-0.17479181951,0.782,-0.348046358697)); +#35628 = CARTESIAN_POINT('',(-0.171499461141,0.782,-0.346236210411)); +#35629 = CARTESIAN_POINT('',(-0.167903647571,0.782,-0.344829249004)); +#35630 = CARTESIAN_POINT('',(-0.164091469566,0.782,-0.343582768799)); +#35631 = CARTESIAN_POINT('',(-0.159931450534,0.782,-0.342886076981)); +#35632 = CARTESIAN_POINT('',(-0.155521369245,0.782,-0.342319707935)); +#35633 = CARTESIAN_POINT('',(-0.152472577135,0.782,-0.342278689615)); +#35634 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#35635 = PCURVE('',#35636,#35641); +#35636 = PLANE('',#35637); +#35637 = AXIS2_PLACEMENT_3D('',#35638,#35639,#35640); +#35638 = CARTESIAN_POINT('',(-0.221176146186,0.782,-0.304816046149)); +#35639 = DIRECTION('',(0.E+000,1.,0.E+000)); +#35640 = DIRECTION('',(0.E+000,0.E+000,1.)); +#35641 = DEFINITIONAL_REPRESENTATION('',(#35642),#35658); +#35642 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35643,#35644,#35645,#35646, + #35647,#35648,#35649,#35650,#35651,#35652,#35653,#35654,#35655, + #35656,#35657),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.127393941339,0.246181611293,0.361268004354,0.477140268037, 0.536326583436,0.595671915044,0.656618953206,0.718835621496, 0.783581552706,0.851587816689,0.923926527481,1.),.UNSPECIFIED.); -#33251 = CARTESIAN_POINT('',(-7.458757353593E-002,3.044503891429E-002)); -#33252 = CARTESIAN_POINT('',(-7.196634054895E-002,3.054276635848E-002)); -#33253 = CARTESIAN_POINT('',(-6.6900955543E-002,3.073161913614E-002)); -#33254 = CARTESIAN_POINT('',(-5.970594726335E-002,3.278541332119E-002)); -#33255 = CARTESIAN_POINT('',(-5.324281209644E-002,3.599695139766E-002)); -#33256 = CARTESIAN_POINT('',(-4.85558960999E-002,3.976191618542E-002)); -#33257 = CARTESIAN_POINT('',(-4.536245781831E-002,4.337157189156E-002)); -#33258 = CARTESIAN_POINT('',(-4.323031254868E-002,4.638432667639E-002)); -#33259 = CARTESIAN_POINT('',(-4.142016426202E-002,4.967668504517E-002)); -#33260 = CARTESIAN_POINT('',(-4.001320285484E-002,5.327249861458E-002)); -#33261 = CARTESIAN_POINT('',(-3.876672264996E-002,5.70846766197E-002)); -#33262 = CARTESIAN_POINT('',(-3.807003083264E-002,6.124469565193E-002)); -#33263 = CARTESIAN_POINT('',(-3.750366178666E-002,6.565477694045E-002)); -#33264 = CARTESIAN_POINT('',(-3.746264346638E-002,6.870356905113E-002)); -#33265 = CARTESIAN_POINT('',(-3.74416181975E-002,7.026632621616E-002)); -#33266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33267 = PCURVE('',#33268,#33299); -#33268 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#33269,#33270) - ,(#33271,#33272) - ,(#33273,#33274) - ,(#33275,#33276) - ,(#33277,#33278) - ,(#33279,#33280) - ,(#33281,#33282) - ,(#33283,#33284) - ,(#33285,#33286) - ,(#33287,#33288) - ,(#33289,#33290) - ,(#33291,#33292) - ,(#33293,#33294) - ,(#33295,#33296) - ,(#33297,#33298 +#35643 = CARTESIAN_POINT('',(-7.458757353593E-002,3.044503891429E-002)); +#35644 = CARTESIAN_POINT('',(-7.196634054895E-002,3.054276635848E-002)); +#35645 = CARTESIAN_POINT('',(-6.6900955543E-002,3.073161913614E-002)); +#35646 = CARTESIAN_POINT('',(-5.970594726335E-002,3.278541332119E-002)); +#35647 = CARTESIAN_POINT('',(-5.324281209644E-002,3.599695139766E-002)); +#35648 = CARTESIAN_POINT('',(-4.85558960999E-002,3.976191618542E-002)); +#35649 = CARTESIAN_POINT('',(-4.536245781831E-002,4.337157189156E-002)); +#35650 = CARTESIAN_POINT('',(-4.323031254868E-002,4.638432667639E-002)); +#35651 = CARTESIAN_POINT('',(-4.142016426202E-002,4.967668504517E-002)); +#35652 = CARTESIAN_POINT('',(-4.001320285484E-002,5.327249861458E-002)); +#35653 = CARTESIAN_POINT('',(-3.876672264996E-002,5.70846766197E-002)); +#35654 = CARTESIAN_POINT('',(-3.807003083264E-002,6.124469565193E-002)); +#35655 = CARTESIAN_POINT('',(-3.750366178666E-002,6.565477694045E-002)); +#35656 = CARTESIAN_POINT('',(-3.746264346638E-002,6.870356905113E-002)); +#35657 = CARTESIAN_POINT('',(-3.74416181975E-002,7.026632621616E-002)); +#35658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35659 = PCURVE('',#35660,#35691); +#35660 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#35661,#35662) + ,(#35663,#35664) + ,(#35665,#35666) + ,(#35667,#35668) + ,(#35669,#35670) + ,(#35671,#35672) + ,(#35673,#35674) + ,(#35675,#35676) + ,(#35677,#35678) + ,(#35679,#35680) + ,(#35681,#35682) + ,(#35683,#35684) + ,(#35685,#35686) + ,(#35687,#35688) + ,(#35689,#35690 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(2,2),( 0.E+000,0.127393941339,0.246181611293,0.361268004354,0.477140268037, 0.536326583436,0.595671915044,0.656618953206,0.718835621496, 0.783581552706,0.851587816689,0.923926527481,1.),(0.E+000,1.), .UNSPECIFIED.); -#33269 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#33270 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); -#33271 = CARTESIAN_POINT('',(-0.190633379827,0.782,-0.376782386698)); -#33272 = CARTESIAN_POINT('',(-0.190633379827,0.78,-0.376782386698)); -#33273 = CARTESIAN_POINT('',(-0.19044452705,0.782,-0.371717001692)); -#33274 = CARTESIAN_POINT('',(-0.19044452705,0.78,-0.371717001692)); -#33275 = CARTESIAN_POINT('',(-0.188390732865,0.782,-0.364521993412)); -#33276 = CARTESIAN_POINT('',(-0.188390732865,0.78,-0.364521993412)); -#33277 = CARTESIAN_POINT('',(-0.185179194788,0.782,-0.358058858245)); -#33278 = CARTESIAN_POINT('',(-0.185179194788,0.78,-0.358058858245)); -#33279 = CARTESIAN_POINT('',(-0.181414230001,0.782,-0.353371942249)); -#33280 = CARTESIAN_POINT('',(-0.181414230001,0.78,-0.353371942249)); -#33281 = CARTESIAN_POINT('',(-0.177804574294,0.782,-0.350178503967)); -#33282 = CARTESIAN_POINT('',(-0.177804574294,0.78,-0.350178503967)); -#33283 = CARTESIAN_POINT('',(-0.17479181951,0.782,-0.348046358697)); -#33284 = CARTESIAN_POINT('',(-0.17479181951,0.78,-0.348046358697)); -#33285 = CARTESIAN_POINT('',(-0.171499461141,0.782,-0.346236210411)); -#33286 = CARTESIAN_POINT('',(-0.171499461141,0.78,-0.346236210411)); -#33287 = CARTESIAN_POINT('',(-0.167903647571,0.782,-0.344829249004)); -#33288 = CARTESIAN_POINT('',(-0.167903647571,0.78,-0.344829249004)); -#33289 = CARTESIAN_POINT('',(-0.164091469566,0.782,-0.343582768799)); -#33290 = CARTESIAN_POINT('',(-0.164091469566,0.78,-0.343582768799)); -#33291 = CARTESIAN_POINT('',(-0.159931450534,0.782,-0.342886076981)); -#33292 = CARTESIAN_POINT('',(-0.159931450534,0.78,-0.342886076981)); -#33293 = CARTESIAN_POINT('',(-0.155521369245,0.782,-0.342319707935)); -#33294 = CARTESIAN_POINT('',(-0.155521369245,0.78,-0.342319707935)); -#33295 = CARTESIAN_POINT('',(-0.152472577135,0.782,-0.342278689615)); -#33296 = CARTESIAN_POINT('',(-0.152472577135,0.78,-0.342278689615)); -#33297 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#33298 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); -#33299 = DEFINITIONAL_REPRESENTATION('',(#33300),#33304); -#33300 = LINE('',#33301,#33302); -#33301 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33302 = VECTOR('',#33303,1.); -#33303 = DIRECTION('',(1.,0.E+000)); -#33304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33305 = ORIENTED_EDGE('',*,*,#33306,.F.); -#33306 = EDGE_CURVE('',#33307,#33222,#33309,.T.); -#33307 = VERTEX_POINT('',#33308); -#33308 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#33309 = SURFACE_CURVE('',#33310,(#33326,#33345),.PCURVE_S1.); -#33310 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33311,#33312,#33313,#33314, - #33315,#33316,#33317,#33318,#33319,#33320,#33321,#33322,#33323, - #33324,#33325),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35661 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#35662 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); +#35663 = CARTESIAN_POINT('',(-0.190633379827,0.782,-0.376782386698)); +#35664 = CARTESIAN_POINT('',(-0.190633379827,0.78,-0.376782386698)); +#35665 = CARTESIAN_POINT('',(-0.19044452705,0.782,-0.371717001692)); +#35666 = CARTESIAN_POINT('',(-0.19044452705,0.78,-0.371717001692)); +#35667 = CARTESIAN_POINT('',(-0.188390732865,0.782,-0.364521993412)); +#35668 = CARTESIAN_POINT('',(-0.188390732865,0.78,-0.364521993412)); +#35669 = CARTESIAN_POINT('',(-0.185179194788,0.782,-0.358058858245)); +#35670 = CARTESIAN_POINT('',(-0.185179194788,0.78,-0.358058858245)); +#35671 = CARTESIAN_POINT('',(-0.181414230001,0.782,-0.353371942249)); +#35672 = CARTESIAN_POINT('',(-0.181414230001,0.78,-0.353371942249)); +#35673 = CARTESIAN_POINT('',(-0.177804574294,0.782,-0.350178503967)); +#35674 = CARTESIAN_POINT('',(-0.177804574294,0.78,-0.350178503967)); +#35675 = CARTESIAN_POINT('',(-0.17479181951,0.782,-0.348046358697)); +#35676 = CARTESIAN_POINT('',(-0.17479181951,0.78,-0.348046358697)); +#35677 = CARTESIAN_POINT('',(-0.171499461141,0.782,-0.346236210411)); +#35678 = CARTESIAN_POINT('',(-0.171499461141,0.78,-0.346236210411)); +#35679 = CARTESIAN_POINT('',(-0.167903647571,0.782,-0.344829249004)); +#35680 = CARTESIAN_POINT('',(-0.167903647571,0.78,-0.344829249004)); +#35681 = CARTESIAN_POINT('',(-0.164091469566,0.782,-0.343582768799)); +#35682 = CARTESIAN_POINT('',(-0.164091469566,0.78,-0.343582768799)); +#35683 = CARTESIAN_POINT('',(-0.159931450534,0.782,-0.342886076981)); +#35684 = CARTESIAN_POINT('',(-0.159931450534,0.78,-0.342886076981)); +#35685 = CARTESIAN_POINT('',(-0.155521369245,0.782,-0.342319707935)); +#35686 = CARTESIAN_POINT('',(-0.155521369245,0.78,-0.342319707935)); +#35687 = CARTESIAN_POINT('',(-0.152472577135,0.782,-0.342278689615)); +#35688 = CARTESIAN_POINT('',(-0.152472577135,0.78,-0.342278689615)); +#35689 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#35690 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); +#35691 = DEFINITIONAL_REPRESENTATION('',(#35692),#35696); +#35692 = LINE('',#35693,#35694); +#35693 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35694 = VECTOR('',#35695,1.); +#35695 = DIRECTION('',(1.,0.E+000)); +#35696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35697 = ORIENTED_EDGE('',*,*,#35698,.F.); +#35698 = EDGE_CURVE('',#35699,#35614,#35701,.T.); +#35699 = VERTEX_POINT('',#35700); +#35700 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#35701 = SURFACE_CURVE('',#35702,(#35718,#35737),.PCURVE_S1.); +#35702 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35703,#35704,#35705,#35706, + #35707,#35708,#35709,#35710,#35711,#35712,#35713,#35714,#35715, + #35716,#35717),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.623586740752E-002,0.148618099954,0.218239428141, 0.284251690269,0.348257520785,0.41065620425,0.472862373, 0.534194748022,0.653476101422,0.767766789522,0.881712609467,1.), .UNSPECIFIED.); -#33311 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#33312 = CARTESIAN_POINT('',(-0.152729777306,0.782,-0.414676353545)); -#33313 = CARTESIAN_POINT('',(-0.155675914972,0.782,-0.414635281378)); -#33314 = CARTESIAN_POINT('',(-0.159966976294,0.782,-0.41406634463)); -#33315 = CARTESIAN_POINT('',(-0.164028697593,0.782,-0.413351771644)); -#33316 = CARTESIAN_POINT('',(-0.167823606873,0.782,-0.412205014228)); -#33317 = CARTESIAN_POINT('',(-0.171335929925,0.782,-0.410706468873)); -#33318 = CARTESIAN_POINT('',(-0.174602353061,0.782,-0.408882707038)); -#33319 = CARTESIAN_POINT('',(-0.177647122399,0.782,-0.406795757015)); -#33320 = CARTESIAN_POINT('',(-0.18123776941,0.782,-0.40358139709)); -#33321 = CARTESIAN_POINT('',(-0.184998380579,0.782,-0.399058532957)); -#33322 = CARTESIAN_POINT('',(-0.188311373258,0.782,-0.392982728043)); -#33323 = CARTESIAN_POINT('',(-0.190358909926,0.782,-0.386358050111)); -#33324 = CARTESIAN_POINT('',(-0.190605504803,0.782,-0.381750475834)); -#33325 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#33326 = PCURVE('',#33244,#33327); -#33327 = DEFINITIONAL_REPRESENTATION('',(#33328),#33344); -#33328 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33329,#33330,#33331,#33332, - #33333,#33334,#33335,#33336,#33337,#33338,#33339,#33340,#33341, - #33342,#33343),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35703 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#35704 = CARTESIAN_POINT('',(-0.152729777306,0.782,-0.414676353545)); +#35705 = CARTESIAN_POINT('',(-0.155675914972,0.782,-0.414635281378)); +#35706 = CARTESIAN_POINT('',(-0.159966976294,0.782,-0.41406634463)); +#35707 = CARTESIAN_POINT('',(-0.164028697593,0.782,-0.413351771644)); +#35708 = CARTESIAN_POINT('',(-0.167823606873,0.782,-0.412205014228)); +#35709 = CARTESIAN_POINT('',(-0.171335929925,0.782,-0.410706468873)); +#35710 = CARTESIAN_POINT('',(-0.174602353061,0.782,-0.408882707038)); +#35711 = CARTESIAN_POINT('',(-0.177647122399,0.782,-0.406795757015)); +#35712 = CARTESIAN_POINT('',(-0.18123776941,0.782,-0.40358139709)); +#35713 = CARTESIAN_POINT('',(-0.184998380579,0.782,-0.399058532957)); +#35714 = CARTESIAN_POINT('',(-0.188311373258,0.782,-0.392982728043)); +#35715 = CARTESIAN_POINT('',(-0.190358909926,0.782,-0.386358050111)); +#35716 = CARTESIAN_POINT('',(-0.190605504803,0.782,-0.381750475834)); +#35717 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#35718 = PCURVE('',#35636,#35719); +#35719 = DEFINITIONAL_REPRESENTATION('',(#35720),#35736); +#35720 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35721,#35722,#35723,#35724, + #35725,#35726,#35727,#35728,#35729,#35730,#35731,#35732,#35733, + #35734,#35735),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.623586740752E-002,0.148618099954,0.218239428141, 0.284251690269,0.348257520785,0.41065620425,0.472862373, 0.534194748022,0.653476101422,0.767766789522,0.881712609467,1.), .UNSPECIFIED.); -#33329 = CARTESIAN_POINT('',(-0.109881375977,6.995763406653E-002)); -#33330 = CARTESIAN_POINT('',(-0.109860307397,6.844636888024E-002)); -#33331 = CARTESIAN_POINT('',(-0.109819235229,6.550023121366E-002)); -#33332 = CARTESIAN_POINT('',(-0.109250298481,6.120916989191E-002)); -#33333 = CARTESIAN_POINT('',(-0.108535725495,5.714744859281E-002)); -#33334 = CARTESIAN_POINT('',(-0.107388968079,5.335253931247E-002)); -#33335 = CARTESIAN_POINT('',(-0.105890422725,4.984021626065E-002)); -#33336 = CARTESIAN_POINT('',(-0.104066660889,4.657379312452E-002)); -#33337 = CARTESIAN_POINT('',(-0.101979710866,4.352902378723E-002)); -#33338 = CARTESIAN_POINT('',(-9.876535094104E-002,3.993837677622E-002)); -#33339 = CARTESIAN_POINT('',(-9.42424868079E-002,3.617776560648E-002)); -#33340 = CARTESIAN_POINT('',(-8.816668189413E-002,3.286477292752E-002)); -#33341 = CARTESIAN_POINT('',(-8.154200396221E-002,3.081723625961E-002)); -#33342 = CARTESIAN_POINT('',(-7.693442968474E-002,3.057064138277E-002)); -#33343 = CARTESIAN_POINT('',(-7.458757353593E-002,3.044503891429E-002)); -#33344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33345 = PCURVE('',#33346,#33377); -#33346 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#33347,#33348) - ,(#33349,#33350) - ,(#33351,#33352) - ,(#33353,#33354) - ,(#33355,#33356) - ,(#33357,#33358) - ,(#33359,#33360) - ,(#33361,#33362) - ,(#33363,#33364) - ,(#33365,#33366) - ,(#33367,#33368) - ,(#33369,#33370) - ,(#33371,#33372) - ,(#33373,#33374) - ,(#33375,#33376 +#35721 = CARTESIAN_POINT('',(-0.109881375977,6.995763406653E-002)); +#35722 = CARTESIAN_POINT('',(-0.109860307397,6.844636888024E-002)); +#35723 = CARTESIAN_POINT('',(-0.109819235229,6.550023121366E-002)); +#35724 = CARTESIAN_POINT('',(-0.109250298481,6.120916989191E-002)); +#35725 = CARTESIAN_POINT('',(-0.108535725495,5.714744859281E-002)); +#35726 = CARTESIAN_POINT('',(-0.107388968079,5.335253931247E-002)); +#35727 = CARTESIAN_POINT('',(-0.105890422725,4.984021626065E-002)); +#35728 = CARTESIAN_POINT('',(-0.104066660889,4.657379312452E-002)); +#35729 = CARTESIAN_POINT('',(-0.101979710866,4.352902378723E-002)); +#35730 = CARTESIAN_POINT('',(-9.876535094104E-002,3.993837677622E-002)); +#35731 = CARTESIAN_POINT('',(-9.42424868079E-002,3.617776560648E-002)); +#35732 = CARTESIAN_POINT('',(-8.816668189413E-002,3.286477292752E-002)); +#35733 = CARTESIAN_POINT('',(-8.154200396221E-002,3.081723625961E-002)); +#35734 = CARTESIAN_POINT('',(-7.693442968474E-002,3.057064138277E-002)); +#35735 = CARTESIAN_POINT('',(-7.458757353593E-002,3.044503891429E-002)); +#35736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35737 = PCURVE('',#35738,#35769); +#35738 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#35739,#35740) + ,(#35741,#35742) + ,(#35743,#35744) + ,(#35745,#35746) + ,(#35747,#35748) + ,(#35749,#35750) + ,(#35751,#35752) + ,(#35753,#35754) + ,(#35755,#35756) + ,(#35757,#35758) + ,(#35759,#35760) + ,(#35761,#35762) + ,(#35763,#35764) + ,(#35765,#35766) + ,(#35767,#35768 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(2,2),( 0.E+000,7.623586740752E-002,0.148618099954,0.218239428141, 0.284251690269,0.348257520785,0.41065620425,0.472862373, 0.534194748022,0.653476101422,0.767766789522,0.881712609467,1.),( 0.E+000,1.),.UNSPECIFIED.); -#33347 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#33348 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); -#33349 = CARTESIAN_POINT('',(-0.152729777306,0.782,-0.414676353545)); -#33350 = CARTESIAN_POINT('',(-0.152729777306,0.78,-0.414676353545)); -#33351 = CARTESIAN_POINT('',(-0.155675914972,0.782,-0.414635281378)); -#33352 = CARTESIAN_POINT('',(-0.155675914972,0.78,-0.414635281378)); -#33353 = CARTESIAN_POINT('',(-0.159966976294,0.782,-0.41406634463)); -#33354 = CARTESIAN_POINT('',(-0.159966976294,0.78,-0.41406634463)); -#33355 = CARTESIAN_POINT('',(-0.164028697593,0.782,-0.413351771644)); -#33356 = CARTESIAN_POINT('',(-0.164028697593,0.78,-0.413351771644)); -#33357 = CARTESIAN_POINT('',(-0.167823606873,0.782,-0.412205014228)); -#33358 = CARTESIAN_POINT('',(-0.167823606873,0.78,-0.412205014228)); -#33359 = CARTESIAN_POINT('',(-0.171335929925,0.782,-0.410706468873)); -#33360 = CARTESIAN_POINT('',(-0.171335929925,0.78,-0.410706468873)); -#33361 = CARTESIAN_POINT('',(-0.174602353061,0.782,-0.408882707038)); -#33362 = CARTESIAN_POINT('',(-0.174602353061,0.78,-0.408882707038)); -#33363 = CARTESIAN_POINT('',(-0.177647122399,0.782,-0.406795757015)); -#33364 = CARTESIAN_POINT('',(-0.177647122399,0.78,-0.406795757015)); -#33365 = CARTESIAN_POINT('',(-0.18123776941,0.782,-0.40358139709)); -#33366 = CARTESIAN_POINT('',(-0.18123776941,0.78,-0.40358139709)); -#33367 = CARTESIAN_POINT('',(-0.184998380579,0.782,-0.399058532957)); -#33368 = CARTESIAN_POINT('',(-0.184998380579,0.78,-0.399058532957)); -#33369 = CARTESIAN_POINT('',(-0.188311373258,0.782,-0.392982728043)); -#33370 = CARTESIAN_POINT('',(-0.188311373258,0.78,-0.392982728043)); -#33371 = CARTESIAN_POINT('',(-0.190358909926,0.782,-0.386358050111)); -#33372 = CARTESIAN_POINT('',(-0.190358909926,0.78,-0.386358050111)); -#33373 = CARTESIAN_POINT('',(-0.190605504803,0.782,-0.381750475834)); -#33374 = CARTESIAN_POINT('',(-0.190605504803,0.78,-0.381750475834)); -#33375 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#33376 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); -#33377 = DEFINITIONAL_REPRESENTATION('',(#33378),#33382); -#33378 = LINE('',#33379,#33380); -#33379 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33380 = VECTOR('',#33381,1.); -#33381 = DIRECTION('',(1.,0.E+000)); -#33382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33383 = ORIENTED_EDGE('',*,*,#33384,.F.); -#33384 = EDGE_CURVE('',#33385,#33307,#33387,.T.); -#33385 = VERTEX_POINT('',#33386); -#33386 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#33387 = SURFACE_CURVE('',#33388,(#33404,#33423),.PCURVE_S1.); -#33388 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33389,#33390,#33391,#33392, - #33393,#33394,#33395,#33396,#33397,#33398,#33399,#33400,#33401, - #33402,#33403),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35739 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#35740 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); +#35741 = CARTESIAN_POINT('',(-0.152729777306,0.782,-0.414676353545)); +#35742 = CARTESIAN_POINT('',(-0.152729777306,0.78,-0.414676353545)); +#35743 = CARTESIAN_POINT('',(-0.155675914972,0.782,-0.414635281378)); +#35744 = CARTESIAN_POINT('',(-0.155675914972,0.78,-0.414635281378)); +#35745 = CARTESIAN_POINT('',(-0.159966976294,0.782,-0.41406634463)); +#35746 = CARTESIAN_POINT('',(-0.159966976294,0.78,-0.41406634463)); +#35747 = CARTESIAN_POINT('',(-0.164028697593,0.782,-0.413351771644)); +#35748 = CARTESIAN_POINT('',(-0.164028697593,0.78,-0.413351771644)); +#35749 = CARTESIAN_POINT('',(-0.167823606873,0.782,-0.412205014228)); +#35750 = CARTESIAN_POINT('',(-0.167823606873,0.78,-0.412205014228)); +#35751 = CARTESIAN_POINT('',(-0.171335929925,0.782,-0.410706468873)); +#35752 = CARTESIAN_POINT('',(-0.171335929925,0.78,-0.410706468873)); +#35753 = CARTESIAN_POINT('',(-0.174602353061,0.782,-0.408882707038)); +#35754 = CARTESIAN_POINT('',(-0.174602353061,0.78,-0.408882707038)); +#35755 = CARTESIAN_POINT('',(-0.177647122399,0.782,-0.406795757015)); +#35756 = CARTESIAN_POINT('',(-0.177647122399,0.78,-0.406795757015)); +#35757 = CARTESIAN_POINT('',(-0.18123776941,0.782,-0.40358139709)); +#35758 = CARTESIAN_POINT('',(-0.18123776941,0.78,-0.40358139709)); +#35759 = CARTESIAN_POINT('',(-0.184998380579,0.782,-0.399058532957)); +#35760 = CARTESIAN_POINT('',(-0.184998380579,0.78,-0.399058532957)); +#35761 = CARTESIAN_POINT('',(-0.188311373258,0.782,-0.392982728043)); +#35762 = CARTESIAN_POINT('',(-0.188311373258,0.78,-0.392982728043)); +#35763 = CARTESIAN_POINT('',(-0.190358909926,0.782,-0.386358050111)); +#35764 = CARTESIAN_POINT('',(-0.190358909926,0.78,-0.386358050111)); +#35765 = CARTESIAN_POINT('',(-0.190605504803,0.782,-0.381750475834)); +#35766 = CARTESIAN_POINT('',(-0.190605504803,0.78,-0.381750475834)); +#35767 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#35768 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); +#35769 = DEFINITIONAL_REPRESENTATION('',(#35770),#35774); +#35770 = LINE('',#35771,#35772); +#35771 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35772 = VECTOR('',#35773,1.); +#35773 = DIRECTION('',(1.,0.E+000)); +#35774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35775 = ORIENTED_EDGE('',*,*,#35776,.F.); +#35776 = EDGE_CURVE('',#35777,#35699,#35779,.T.); +#35777 = VERTEX_POINT('',#35778); +#35778 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#35779 = SURFACE_CURVE('',#35780,(#35796,#35815),.PCURVE_S1.); +#35780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35781,#35782,#35783,#35784, + #35785,#35786,#35787,#35788,#35789,#35790,#35791,#35792,#35793, + #35794,#35795),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.123386121363,0.241434686423,0.357448546151,0.476713920453, 0.537889586874,0.59927039383,0.660352052257,0.723006936299, 0.787875537201,0.855360105861,0.925373213756,1.),.UNSPECIFIED.); -#33389 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#33390 = CARTESIAN_POINT('',(-0.111832665366,0.782,-0.38035978059)); -#33391 = CARTESIAN_POINT('',(-0.112080679158,0.782,-0.385250892843)); -#33392 = CARTESIAN_POINT('',(-0.114083774905,0.782,-0.392272304946)); -#33393 = CARTESIAN_POINT('',(-0.117456162002,0.782,-0.398631607373)); -#33394 = CARTESIAN_POINT('',(-0.121308646739,0.782,-0.40327571587)); -#33395 = CARTESIAN_POINT('',(-0.12487424297,0.782,-0.406640099038)); -#33396 = CARTESIAN_POINT('',(-0.127924792318,0.782,-0.408781754244)); -#33397 = CARTESIAN_POINT('',(-0.13120414428,0.782,-0.410604492294)); -#33398 = CARTESIAN_POINT('',(-0.134724780019,0.782,-0.412093003298)); -#33399 = CARTESIAN_POINT('',(-0.138491790595,0.782,-0.413293502917)); -#33400 = CARTESIAN_POINT('',(-0.142515380373,0.782,-0.414081088495)); -#33401 = CARTESIAN_POINT('',(-0.146778642189,0.782,-0.414633449941)); -#33402 = CARTESIAN_POINT('',(-0.149707415113,0.782,-0.414675649376)); -#33403 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#33404 = PCURVE('',#33244,#33405); -#33405 = DEFINITIONAL_REPRESENTATION('',(#33406),#33422); -#33406 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33407,#33408,#33409,#33410, - #33411,#33412,#33413,#33414,#33415,#33416,#33417,#33418,#33419, - #33420,#33421),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35781 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#35782 = CARTESIAN_POINT('',(-0.111832665366,0.782,-0.38035978059)); +#35783 = CARTESIAN_POINT('',(-0.112080679158,0.782,-0.385250892843)); +#35784 = CARTESIAN_POINT('',(-0.114083774905,0.782,-0.392272304946)); +#35785 = CARTESIAN_POINT('',(-0.117456162002,0.782,-0.398631607373)); +#35786 = CARTESIAN_POINT('',(-0.121308646739,0.782,-0.40327571587)); +#35787 = CARTESIAN_POINT('',(-0.12487424297,0.782,-0.406640099038)); +#35788 = CARTESIAN_POINT('',(-0.127924792318,0.782,-0.408781754244)); +#35789 = CARTESIAN_POINT('',(-0.13120414428,0.782,-0.410604492294)); +#35790 = CARTESIAN_POINT('',(-0.134724780019,0.782,-0.412093003298)); +#35791 = CARTESIAN_POINT('',(-0.138491790595,0.782,-0.413293502917)); +#35792 = CARTESIAN_POINT('',(-0.142515380373,0.782,-0.414081088495)); +#35793 = CARTESIAN_POINT('',(-0.146778642189,0.782,-0.414633449941)); +#35794 = CARTESIAN_POINT('',(-0.149707415113,0.782,-0.414675649376)); +#35795 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#35796 = PCURVE('',#35636,#35797); +#35797 = DEFINITIONAL_REPRESENTATION('',(#35798),#35814); +#35798 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35799,#35800,#35801,#35802, + #35803,#35804,#35805,#35806,#35807,#35808,#35809,#35810,#35811, + #35812,#35813),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.123386121363,0.241434686423,0.357448546151,0.476713920453, 0.537889586874,0.59927039383,0.660352052257,0.723006936299, 0.787875537201,0.855360105861,0.925373213756,1.),.UNSPECIFIED.); -#33407 = CARTESIAN_POINT('',(-7.30441127878E-002,0.109470229219)); -#33408 = CARTESIAN_POINT('',(-7.554373444124E-002,0.10934348082)); -#33409 = CARTESIAN_POINT('',(-8.043484669446E-002,0.109095467028)); -#33410 = CARTESIAN_POINT('',(-8.745625879714E-002,0.107092371281)); -#33411 = CARTESIAN_POINT('',(-9.381556122432E-002,0.103719984184)); -#33412 = CARTESIAN_POINT('',(-9.845966972083E-002,9.986749944721E-002)); -#33413 = CARTESIAN_POINT('',(-0.101824052889,9.630190321627E-002)); -#33414 = CARTESIAN_POINT('',(-0.103965708096,9.32513538677E-002)); -#33415 = CARTESIAN_POINT('',(-0.105788446145,8.997200190548E-002)); -#33416 = CARTESIAN_POINT('',(-0.107276957149,8.645136616718E-002)); -#33417 = CARTESIAN_POINT('',(-0.108477456768,8.268435559116E-002)); -#33418 = CARTESIAN_POINT('',(-0.109265042346,7.86607658125E-002)); -#33419 = CARTESIAN_POINT('',(-0.109817403792,7.439750399689E-002)); -#33420 = CARTESIAN_POINT('',(-0.109859603227,7.146873107254E-002)); -#33421 = CARTESIAN_POINT('',(-0.109881375977,6.995763406653E-002)); -#33422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33423 = PCURVE('',#33424,#33455); -#33424 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#33425,#33426) - ,(#33427,#33428) - ,(#33429,#33430) - ,(#33431,#33432) - ,(#33433,#33434) - ,(#33435,#33436) - ,(#33437,#33438) - ,(#33439,#33440) - ,(#33441,#33442) - ,(#33443,#33444) - ,(#33445,#33446) - ,(#33447,#33448) - ,(#33449,#33450) - ,(#33451,#33452) - ,(#33453,#33454 +#35799 = CARTESIAN_POINT('',(-7.30441127878E-002,0.109470229219)); +#35800 = CARTESIAN_POINT('',(-7.554373444124E-002,0.10934348082)); +#35801 = CARTESIAN_POINT('',(-8.043484669446E-002,0.109095467028)); +#35802 = CARTESIAN_POINT('',(-8.745625879714E-002,0.107092371281)); +#35803 = CARTESIAN_POINT('',(-9.381556122432E-002,0.103719984184)); +#35804 = CARTESIAN_POINT('',(-9.845966972083E-002,9.986749944721E-002)); +#35805 = CARTESIAN_POINT('',(-0.101824052889,9.630190321627E-002)); +#35806 = CARTESIAN_POINT('',(-0.103965708096,9.32513538677E-002)); +#35807 = CARTESIAN_POINT('',(-0.105788446145,8.997200190548E-002)); +#35808 = CARTESIAN_POINT('',(-0.107276957149,8.645136616718E-002)); +#35809 = CARTESIAN_POINT('',(-0.108477456768,8.268435559116E-002)); +#35810 = CARTESIAN_POINT('',(-0.109265042346,7.86607658125E-002)); +#35811 = CARTESIAN_POINT('',(-0.109817403792,7.439750399689E-002)); +#35812 = CARTESIAN_POINT('',(-0.109859603227,7.146873107254E-002)); +#35813 = CARTESIAN_POINT('',(-0.109881375977,6.995763406653E-002)); +#35814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35815 = PCURVE('',#35816,#35847); +#35816 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#35817,#35818) + ,(#35819,#35820) + ,(#35821,#35822) + ,(#35823,#35824) + ,(#35825,#35826) + ,(#35827,#35828) + ,(#35829,#35830) + ,(#35831,#35832) + ,(#35833,#35834) + ,(#35835,#35836) + ,(#35837,#35838) + ,(#35839,#35840) + ,(#35841,#35842) + ,(#35843,#35844) + ,(#35845,#35846 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(2,2),( 0.E+000,0.123386121363,0.241434686423,0.357448546151,0.476713920453, 0.537889586874,0.59927039383,0.660352052257,0.723006936299, 0.787875537201,0.855360105861,0.925373213756,1.),(0.E+000,1.), .UNSPECIFIED.); -#33425 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#33426 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); -#33427 = CARTESIAN_POINT('',(-0.111832665366,0.782,-0.38035978059)); -#33428 = CARTESIAN_POINT('',(-0.111832665366,0.78,-0.38035978059)); -#33429 = CARTESIAN_POINT('',(-0.112080679158,0.782,-0.385250892843)); -#33430 = CARTESIAN_POINT('',(-0.112080679158,0.78,-0.385250892843)); -#33431 = CARTESIAN_POINT('',(-0.114083774905,0.782,-0.392272304946)); -#33432 = CARTESIAN_POINT('',(-0.114083774905,0.78,-0.392272304946)); -#33433 = CARTESIAN_POINT('',(-0.117456162002,0.782,-0.398631607373)); -#33434 = CARTESIAN_POINT('',(-0.117456162002,0.78,-0.398631607373)); -#33435 = CARTESIAN_POINT('',(-0.121308646739,0.782,-0.40327571587)); -#33436 = CARTESIAN_POINT('',(-0.121308646739,0.78,-0.40327571587)); -#33437 = CARTESIAN_POINT('',(-0.12487424297,0.782,-0.406640099038)); -#33438 = CARTESIAN_POINT('',(-0.12487424297,0.78,-0.406640099038)); -#33439 = CARTESIAN_POINT('',(-0.127924792318,0.782,-0.408781754244)); -#33440 = CARTESIAN_POINT('',(-0.127924792318,0.78,-0.408781754244)); -#33441 = CARTESIAN_POINT('',(-0.13120414428,0.782,-0.410604492294)); -#33442 = CARTESIAN_POINT('',(-0.13120414428,0.78,-0.410604492294)); -#33443 = CARTESIAN_POINT('',(-0.134724780019,0.782,-0.412093003298)); -#33444 = CARTESIAN_POINT('',(-0.134724780019,0.78,-0.412093003298)); -#33445 = CARTESIAN_POINT('',(-0.138491790595,0.782,-0.413293502917)); -#33446 = CARTESIAN_POINT('',(-0.138491790595,0.78,-0.413293502917)); -#33447 = CARTESIAN_POINT('',(-0.142515380373,0.782,-0.414081088495)); -#33448 = CARTESIAN_POINT('',(-0.142515380373,0.78,-0.414081088495)); -#33449 = CARTESIAN_POINT('',(-0.146778642189,0.782,-0.414633449941)); -#33450 = CARTESIAN_POINT('',(-0.146778642189,0.78,-0.414633449941)); -#33451 = CARTESIAN_POINT('',(-0.149707415113,0.782,-0.414675649376)); -#33452 = CARTESIAN_POINT('',(-0.149707415113,0.78,-0.414675649376)); -#33453 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#33454 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); -#33455 = DEFINITIONAL_REPRESENTATION('',(#33456),#33460); -#33456 = LINE('',#33457,#33458); -#33457 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33458 = VECTOR('',#33459,1.); -#33459 = DIRECTION('',(1.,0.E+000)); -#33460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33461 = ORIENTED_EDGE('',*,*,#33462,.F.); -#33462 = EDGE_CURVE('',#33224,#33385,#33463,.T.); -#33463 = SURFACE_CURVE('',#33464,(#33480,#33499),.PCURVE_S1.); -#33464 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33465,#33466,#33467,#33468, - #33469,#33470,#33471,#33472,#33473,#33474,#33475,#33476,#33477, - #33478,#33479),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35817 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#35818 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); +#35819 = CARTESIAN_POINT('',(-0.111832665366,0.782,-0.38035978059)); +#35820 = CARTESIAN_POINT('',(-0.111832665366,0.78,-0.38035978059)); +#35821 = CARTESIAN_POINT('',(-0.112080679158,0.782,-0.385250892843)); +#35822 = CARTESIAN_POINT('',(-0.112080679158,0.78,-0.385250892843)); +#35823 = CARTESIAN_POINT('',(-0.114083774905,0.782,-0.392272304946)); +#35824 = CARTESIAN_POINT('',(-0.114083774905,0.78,-0.392272304946)); +#35825 = CARTESIAN_POINT('',(-0.117456162002,0.782,-0.398631607373)); +#35826 = CARTESIAN_POINT('',(-0.117456162002,0.78,-0.398631607373)); +#35827 = CARTESIAN_POINT('',(-0.121308646739,0.782,-0.40327571587)); +#35828 = CARTESIAN_POINT('',(-0.121308646739,0.78,-0.40327571587)); +#35829 = CARTESIAN_POINT('',(-0.12487424297,0.782,-0.406640099038)); +#35830 = CARTESIAN_POINT('',(-0.12487424297,0.78,-0.406640099038)); +#35831 = CARTESIAN_POINT('',(-0.127924792318,0.782,-0.408781754244)); +#35832 = CARTESIAN_POINT('',(-0.127924792318,0.78,-0.408781754244)); +#35833 = CARTESIAN_POINT('',(-0.13120414428,0.782,-0.410604492294)); +#35834 = CARTESIAN_POINT('',(-0.13120414428,0.78,-0.410604492294)); +#35835 = CARTESIAN_POINT('',(-0.134724780019,0.782,-0.412093003298)); +#35836 = CARTESIAN_POINT('',(-0.134724780019,0.78,-0.412093003298)); +#35837 = CARTESIAN_POINT('',(-0.138491790595,0.782,-0.413293502917)); +#35838 = CARTESIAN_POINT('',(-0.138491790595,0.78,-0.413293502917)); +#35839 = CARTESIAN_POINT('',(-0.142515380373,0.782,-0.414081088495)); +#35840 = CARTESIAN_POINT('',(-0.142515380373,0.78,-0.414081088495)); +#35841 = CARTESIAN_POINT('',(-0.146778642189,0.782,-0.414633449941)); +#35842 = CARTESIAN_POINT('',(-0.146778642189,0.78,-0.414633449941)); +#35843 = CARTESIAN_POINT('',(-0.149707415113,0.782,-0.414675649376)); +#35844 = CARTESIAN_POINT('',(-0.149707415113,0.78,-0.414675649376)); +#35845 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#35846 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); +#35847 = DEFINITIONAL_REPRESENTATION('',(#35848),#35852); +#35848 = LINE('',#35849,#35850); +#35849 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35850 = VECTOR('',#35851,1.); +#35851 = DIRECTION('',(1.,0.E+000)); +#35852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35853 = ORIENTED_EDGE('',*,*,#35854,.F.); +#35854 = EDGE_CURVE('',#35616,#35777,#35855,.T.); +#35855 = SURFACE_CURVE('',#35856,(#35872,#35891),.PCURVE_S1.); +#35856 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35857,#35858,#35859,#35860, + #35861,#35862,#35863,#35864,#35865,#35866,#35867,#35868,#35869, + #35870,#35871),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.684269792878E-002,0.149839053285,0.218379396445, 0.284997020701,0.347657670814,0.409847159115,0.469935761508, 0.530419606657,0.648751736026,0.763774893077,0.878749487778,1.), .UNSPECIFIED.); -#33465 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#33466 = CARTESIAN_POINT('',(-0.149381559204,0.782,-0.342279466551)); -#33467 = CARTESIAN_POINT('',(-0.146401534394,0.782,-0.342321979656)); -#33468 = CARTESIAN_POINT('',(-0.142090778599,0.782,-0.342876802095)); -#33469 = CARTESIAN_POINT('',(-0.138017129395,0.782,-0.343617819681)); -#33470 = CARTESIAN_POINT('',(-0.134240783365,0.782,-0.34474071794)); -#33471 = CARTESIAN_POINT('',(-0.130718142787,0.782,-0.346200813163)); -#33472 = CARTESIAN_POINT('',(-0.127506501884,0.782,-0.348000750153)); -#33473 = CARTESIAN_POINT('',(-0.124509752925,0.782,-0.350069394279)); -#33474 = CARTESIAN_POINT('',(-0.121006135521,0.782,-0.353287230249)); -#33475 = CARTESIAN_POINT('',(-0.11724636631,0.782,-0.357809991944)); -#33476 = CARTESIAN_POINT('',(-0.114024065579,0.782,-0.363984409633)); -#33477 = CARTESIAN_POINT('',(-0.112016064922,0.782,-0.370739589242)); -#33478 = CARTESIAN_POINT('',(-0.111811114626,0.782,-0.37544496563)); -#33479 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#33480 = PCURVE('',#33244,#33481); -#33481 = DEFINITIONAL_REPRESENTATION('',(#33482),#33498); -#33482 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33483,#33484,#33485,#33486, - #33487,#33488,#33489,#33490,#33491,#33492,#33493,#33494,#33495, - #33496,#33497),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#35857 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#35858 = CARTESIAN_POINT('',(-0.149381559204,0.782,-0.342279466551)); +#35859 = CARTESIAN_POINT('',(-0.146401534394,0.782,-0.342321979656)); +#35860 = CARTESIAN_POINT('',(-0.142090778599,0.782,-0.342876802095)); +#35861 = CARTESIAN_POINT('',(-0.138017129395,0.782,-0.343617819681)); +#35862 = CARTESIAN_POINT('',(-0.134240783365,0.782,-0.34474071794)); +#35863 = CARTESIAN_POINT('',(-0.130718142787,0.782,-0.346200813163)); +#35864 = CARTESIAN_POINT('',(-0.127506501884,0.782,-0.348000750153)); +#35865 = CARTESIAN_POINT('',(-0.124509752925,0.782,-0.350069394279)); +#35866 = CARTESIAN_POINT('',(-0.121006135521,0.782,-0.353287230249)); +#35867 = CARTESIAN_POINT('',(-0.11724636631,0.782,-0.357809991944)); +#35868 = CARTESIAN_POINT('',(-0.114024065579,0.782,-0.363984409633)); +#35869 = CARTESIAN_POINT('',(-0.112016064922,0.782,-0.370739589242)); +#35870 = CARTESIAN_POINT('',(-0.111811114626,0.782,-0.37544496563)); +#35871 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#35872 = PCURVE('',#35636,#35873); +#35873 = DEFINITIONAL_REPRESENTATION('',(#35874),#35890); +#35874 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35875,#35876,#35877,#35878, + #35879,#35880,#35881,#35882,#35883,#35884,#35885,#35886,#35887, + #35888,#35889),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.684269792878E-002,0.149839053285,0.218379396445, 0.284997020701,0.347657670814,0.409847159115,0.469935761508, 0.530419606657,0.648751736026,0.763774893077,0.878749487778,1.), .UNSPECIFIED.); -#33483 = CARTESIAN_POINT('',(-3.74416181975E-002,7.026632621616E-002)); -#33484 = CARTESIAN_POINT('',(-3.746342040217E-002,7.179458698176E-002)); -#33485 = CARTESIAN_POINT('',(-3.750593350745E-002,7.477461179171E-002)); -#33486 = CARTESIAN_POINT('',(-3.806075594573E-002,7.908536758708E-002)); -#33487 = CARTESIAN_POINT('',(-3.880177353191E-002,8.315901679135E-002)); -#33488 = CARTESIAN_POINT('',(-3.992467179098E-002,8.693536282129E-002)); -#33489 = CARTESIAN_POINT('',(-4.138476701432E-002,9.045800339873E-002)); -#33490 = CARTESIAN_POINT('',(-4.318470400449E-002,9.3669644302E-002)); -#33491 = CARTESIAN_POINT('',(-4.525334813028E-002,9.666639326097E-002)); -#33492 = CARTESIAN_POINT('',(-4.847118410022E-002,0.100170010665)); -#33493 = CARTESIAN_POINT('',(-5.299394579563E-002,0.103929779876)); -#33494 = CARTESIAN_POINT('',(-5.91683634847E-002,0.107152080607)); -#33495 = CARTESIAN_POINT('',(-6.592354309346E-002,0.109160081264)); -#33496 = CARTESIAN_POINT('',(-7.062891948087E-002,0.10936503156)); -#33497 = CARTESIAN_POINT('',(-7.30441127878E-002,0.109470229219)); -#33498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33499 = PCURVE('',#33500,#33531); -#33500 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#33501,#33502) - ,(#33503,#33504) - ,(#33505,#33506) - ,(#33507,#33508) - ,(#33509,#33510) - ,(#33511,#33512) - ,(#33513,#33514) - ,(#33515,#33516) - ,(#33517,#33518) - ,(#33519,#33520) - ,(#33521,#33522) - ,(#33523,#33524) - ,(#33525,#33526) - ,(#33527,#33528) - ,(#33529,#33530 +#35875 = CARTESIAN_POINT('',(-3.74416181975E-002,7.026632621616E-002)); +#35876 = CARTESIAN_POINT('',(-3.746342040217E-002,7.179458698176E-002)); +#35877 = CARTESIAN_POINT('',(-3.750593350745E-002,7.477461179171E-002)); +#35878 = CARTESIAN_POINT('',(-3.806075594573E-002,7.908536758708E-002)); +#35879 = CARTESIAN_POINT('',(-3.880177353191E-002,8.315901679135E-002)); +#35880 = CARTESIAN_POINT('',(-3.992467179098E-002,8.693536282129E-002)); +#35881 = CARTESIAN_POINT('',(-4.138476701432E-002,9.045800339873E-002)); +#35882 = CARTESIAN_POINT('',(-4.318470400449E-002,9.3669644302E-002)); +#35883 = CARTESIAN_POINT('',(-4.525334813028E-002,9.666639326097E-002)); +#35884 = CARTESIAN_POINT('',(-4.847118410022E-002,0.100170010665)); +#35885 = CARTESIAN_POINT('',(-5.299394579563E-002,0.103929779876)); +#35886 = CARTESIAN_POINT('',(-5.91683634847E-002,0.107152080607)); +#35887 = CARTESIAN_POINT('',(-6.592354309346E-002,0.109160081264)); +#35888 = CARTESIAN_POINT('',(-7.062891948087E-002,0.10936503156)); +#35889 = CARTESIAN_POINT('',(-7.30441127878E-002,0.109470229219)); +#35890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35891 = PCURVE('',#35892,#35923); +#35892 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#35893,#35894) + ,(#35895,#35896) + ,(#35897,#35898) + ,(#35899,#35900) + ,(#35901,#35902) + ,(#35903,#35904) + ,(#35905,#35906) + ,(#35907,#35908) + ,(#35909,#35910) + ,(#35911,#35912) + ,(#35913,#35914) + ,(#35915,#35916) + ,(#35917,#35918) + ,(#35919,#35920) + ,(#35921,#35922 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(2,2),( 0.E+000,7.684269792878E-002,0.149839053285,0.218379396445, 0.284997020701,0.347657670814,0.409847159115,0.469935761508, 0.530419606657,0.648751736026,0.763774893077,0.878749487778,1.),( 0.E+000,1.),.UNSPECIFIED.); -#33501 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#33502 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); -#33503 = CARTESIAN_POINT('',(-0.149381559204,0.782,-0.342279466551)); -#33504 = CARTESIAN_POINT('',(-0.149381559204,0.78,-0.342279466551)); -#33505 = CARTESIAN_POINT('',(-0.146401534394,0.782,-0.342321979656)); -#33506 = CARTESIAN_POINT('',(-0.146401534394,0.78,-0.342321979656)); -#33507 = CARTESIAN_POINT('',(-0.142090778599,0.782,-0.342876802095)); -#33508 = CARTESIAN_POINT('',(-0.142090778599,0.78,-0.342876802095)); -#33509 = CARTESIAN_POINT('',(-0.138017129395,0.782,-0.343617819681)); -#33510 = CARTESIAN_POINT('',(-0.138017129395,0.78,-0.343617819681)); -#33511 = CARTESIAN_POINT('',(-0.134240783365,0.782,-0.34474071794)); -#33512 = CARTESIAN_POINT('',(-0.134240783365,0.78,-0.34474071794)); -#33513 = CARTESIAN_POINT('',(-0.130718142787,0.782,-0.346200813163)); -#33514 = CARTESIAN_POINT('',(-0.130718142787,0.78,-0.346200813163)); -#33515 = CARTESIAN_POINT('',(-0.127506501884,0.782,-0.348000750153)); -#33516 = CARTESIAN_POINT('',(-0.127506501884,0.78,-0.348000750153)); -#33517 = CARTESIAN_POINT('',(-0.124509752925,0.782,-0.350069394279)); -#33518 = CARTESIAN_POINT('',(-0.124509752925,0.78,-0.350069394279)); -#33519 = CARTESIAN_POINT('',(-0.121006135521,0.782,-0.353287230249)); -#33520 = CARTESIAN_POINT('',(-0.121006135521,0.78,-0.353287230249)); -#33521 = CARTESIAN_POINT('',(-0.11724636631,0.782,-0.357809991944)); -#33522 = CARTESIAN_POINT('',(-0.11724636631,0.78,-0.357809991944)); -#33523 = CARTESIAN_POINT('',(-0.114024065579,0.782,-0.363984409633)); -#33524 = CARTESIAN_POINT('',(-0.114024065579,0.78,-0.363984409633)); -#33525 = CARTESIAN_POINT('',(-0.112016064922,0.782,-0.370739589242)); -#33526 = CARTESIAN_POINT('',(-0.112016064922,0.78,-0.370739589242)); -#33527 = CARTESIAN_POINT('',(-0.111811114626,0.782,-0.37544496563)); -#33528 = CARTESIAN_POINT('',(-0.111811114626,0.78,-0.37544496563)); -#33529 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#33530 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); -#33531 = DEFINITIONAL_REPRESENTATION('',(#33532),#33536); -#33532 = LINE('',#33533,#33534); -#33533 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33534 = VECTOR('',#33535,1.); -#33535 = DIRECTION('',(1.,0.E+000)); -#33536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33537 = FACE_BOUND('',#33538,.T.); -#33538 = EDGE_LOOP('',(#33539,#33596,#33651,#33706,#33761,#33800,#33855, - #33910)); -#33539 = ORIENTED_EDGE('',*,*,#33540,.F.); -#33540 = EDGE_CURVE('',#33541,#33543,#33545,.T.); -#33541 = VERTEX_POINT('',#33542); -#33542 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#33543 = VERTEX_POINT('',#33544); -#33544 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#33545 = SURFACE_CURVE('',#33546,(#33566,#33589),.PCURVE_S1.); -#33546 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33547,#33548,#33549,#33550, - #33551,#33552,#33553,#33554,#33555,#33556,#33557,#33558,#33559, - #33560,#33561,#33562,#33563,#33564,#33565),.UNSPECIFIED.,.F.,.F.,(4, +#35893 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#35894 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); +#35895 = CARTESIAN_POINT('',(-0.149381559204,0.782,-0.342279466551)); +#35896 = CARTESIAN_POINT('',(-0.149381559204,0.78,-0.342279466551)); +#35897 = CARTESIAN_POINT('',(-0.146401534394,0.782,-0.342321979656)); +#35898 = CARTESIAN_POINT('',(-0.146401534394,0.78,-0.342321979656)); +#35899 = CARTESIAN_POINT('',(-0.142090778599,0.782,-0.342876802095)); +#35900 = CARTESIAN_POINT('',(-0.142090778599,0.78,-0.342876802095)); +#35901 = CARTESIAN_POINT('',(-0.138017129395,0.782,-0.343617819681)); +#35902 = CARTESIAN_POINT('',(-0.138017129395,0.78,-0.343617819681)); +#35903 = CARTESIAN_POINT('',(-0.134240783365,0.782,-0.34474071794)); +#35904 = CARTESIAN_POINT('',(-0.134240783365,0.78,-0.34474071794)); +#35905 = CARTESIAN_POINT('',(-0.130718142787,0.782,-0.346200813163)); +#35906 = CARTESIAN_POINT('',(-0.130718142787,0.78,-0.346200813163)); +#35907 = CARTESIAN_POINT('',(-0.127506501884,0.782,-0.348000750153)); +#35908 = CARTESIAN_POINT('',(-0.127506501884,0.78,-0.348000750153)); +#35909 = CARTESIAN_POINT('',(-0.124509752925,0.782,-0.350069394279)); +#35910 = CARTESIAN_POINT('',(-0.124509752925,0.78,-0.350069394279)); +#35911 = CARTESIAN_POINT('',(-0.121006135521,0.782,-0.353287230249)); +#35912 = CARTESIAN_POINT('',(-0.121006135521,0.78,-0.353287230249)); +#35913 = CARTESIAN_POINT('',(-0.11724636631,0.782,-0.357809991944)); +#35914 = CARTESIAN_POINT('',(-0.11724636631,0.78,-0.357809991944)); +#35915 = CARTESIAN_POINT('',(-0.114024065579,0.782,-0.363984409633)); +#35916 = CARTESIAN_POINT('',(-0.114024065579,0.78,-0.363984409633)); +#35917 = CARTESIAN_POINT('',(-0.112016064922,0.782,-0.370739589242)); +#35918 = CARTESIAN_POINT('',(-0.112016064922,0.78,-0.370739589242)); +#35919 = CARTESIAN_POINT('',(-0.111811114626,0.782,-0.37544496563)); +#35920 = CARTESIAN_POINT('',(-0.111811114626,0.78,-0.37544496563)); +#35921 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#35922 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); +#35923 = DEFINITIONAL_REPRESENTATION('',(#35924),#35928); +#35924 = LINE('',#35925,#35926); +#35925 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35926 = VECTOR('',#35927,1.); +#35927 = DIRECTION('',(1.,0.E+000)); +#35928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35929 = FACE_BOUND('',#35930,.T.); +#35930 = EDGE_LOOP('',(#35931,#35988,#36043,#36098,#36153,#36192,#36247, + #36302)); +#35931 = ORIENTED_EDGE('',*,*,#35932,.F.); +#35932 = EDGE_CURVE('',#35933,#35935,#35937,.T.); +#35933 = VERTEX_POINT('',#35934); +#35934 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#35935 = VERTEX_POINT('',#35936); +#35936 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#35937 = SURFACE_CURVE('',#35938,(#35958,#35981),.PCURVE_S1.); +#35938 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35939,#35940,#35941,#35942, + #35943,#35944,#35945,#35946,#35947,#35948,#35949,#35950,#35951, + #35952,#35953,#35954,#35955,#35956,#35957),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.983406803225E-002, 0.137026523956,0.201482296865,0.264539949244,0.325972593288, 0.386386309529,0.445760766791,0.505611907075,0.565114421739, 0.624750391664,0.684178951265,0.744219141657,0.805179145467, 0.868394860823,0.933203933413,1.),.UNSPECIFIED.); -#33547 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#33548 = CARTESIAN_POINT('',(-0.233491754798,0.782,-0.265188395173)); -#33549 = CARTESIAN_POINT('',(-0.233404116522,0.782,-0.269228153309)); -#33550 = CARTESIAN_POINT('',(-0.232868763985,0.782,-0.275153379217)); -#33551 = CARTESIAN_POINT('',(-0.231801816663,0.782,-0.280800742308)); -#33552 = CARTESIAN_POINT('',(-0.230427520555,0.782,-0.286203522458)); -#33553 = CARTESIAN_POINT('',(-0.228682594508,0.782,-0.291375235964)); -#33554 = CARTESIAN_POINT('',(-0.226529896099,0.782,-0.296275269332)); -#33555 = CARTESIAN_POINT('',(-0.223918118321,0.782,-0.300891779709)); -#33556 = CARTESIAN_POINT('',(-0.220950967505,0.782,-0.305254806535)); -#33557 = CARTESIAN_POINT('',(-0.217591001607,0.782,-0.309333719746)); -#33558 = CARTESIAN_POINT('',(-0.213892677899,0.782,-0.313092799429)); -#33559 = CARTESIAN_POINT('',(-0.209842562382,0.782,-0.316489288576)); -#33560 = CARTESIAN_POINT('',(-0.205531668344,0.782,-0.319622388404)); -#33561 = CARTESIAN_POINT('',(-0.200779298559,0.782,-0.322270472453)); -#33562 = CARTESIAN_POINT('',(-0.195762192151,0.782,-0.324700582966)); -#33563 = CARTESIAN_POINT('',(-0.190394091767,0.782,-0.326773016643)); -#33564 = CARTESIAN_POINT('',(-0.186658868273,0.782,-0.32783003097)); -#33565 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#33566 = PCURVE('',#33244,#33567); -#33567 = DEFINITIONAL_REPRESENTATION('',(#33568),#33588); -#33568 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33569,#33570,#33571,#33572, - #33573,#33574,#33575,#33576,#33577,#33578,#33579,#33580,#33581, - #33582,#33583,#33584,#33585,#33586,#33587),.UNSPECIFIED.,.F.,.F.,(4, +#35939 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#35940 = CARTESIAN_POINT('',(-0.233491754798,0.782,-0.265188395173)); +#35941 = CARTESIAN_POINT('',(-0.233404116522,0.782,-0.269228153309)); +#35942 = CARTESIAN_POINT('',(-0.232868763985,0.782,-0.275153379217)); +#35943 = CARTESIAN_POINT('',(-0.231801816663,0.782,-0.280800742308)); +#35944 = CARTESIAN_POINT('',(-0.230427520555,0.782,-0.286203522458)); +#35945 = CARTESIAN_POINT('',(-0.228682594508,0.782,-0.291375235964)); +#35946 = CARTESIAN_POINT('',(-0.226529896099,0.782,-0.296275269332)); +#35947 = CARTESIAN_POINT('',(-0.223918118321,0.782,-0.300891779709)); +#35948 = CARTESIAN_POINT('',(-0.220950967505,0.782,-0.305254806535)); +#35949 = CARTESIAN_POINT('',(-0.217591001607,0.782,-0.309333719746)); +#35950 = CARTESIAN_POINT('',(-0.213892677899,0.782,-0.313092799429)); +#35951 = CARTESIAN_POINT('',(-0.209842562382,0.782,-0.316489288576)); +#35952 = CARTESIAN_POINT('',(-0.205531668344,0.782,-0.319622388404)); +#35953 = CARTESIAN_POINT('',(-0.200779298559,0.782,-0.322270472453)); +#35954 = CARTESIAN_POINT('',(-0.195762192151,0.782,-0.324700582966)); +#35955 = CARTESIAN_POINT('',(-0.190394091767,0.782,-0.326773016643)); +#35956 = CARTESIAN_POINT('',(-0.186658868273,0.782,-0.32783003097)); +#35957 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#35958 = PCURVE('',#35636,#35959); +#35959 = DEFINITIONAL_REPRESENTATION('',(#35960),#35980); +#35960 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35961,#35962,#35963,#35964, + #35965,#35966,#35967,#35968,#35969,#35970,#35971,#35972,#35973, + #35974,#35975,#35976,#35977,#35978,#35979),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.983406803225E-002, 0.137026523956,0.201482296865,0.264539949244,0.325972593288, 0.386386309529,0.445760766791,0.505611907075,0.565114421739, 0.624750391664,0.684178951265,0.744219141657,0.805179145467, 0.868394860823,0.933203933413,1.),.UNSPECIFIED.); -#33569 = CARTESIAN_POINT('',(4.16864694902E-002,-1.236027250064E-002)); -#33570 = CARTESIAN_POINT('',(3.962765097581E-002,-1.231560861237E-002)); -#33571 = CARTESIAN_POINT('',(3.558789284008E-002,-1.222797033599E-002)); -#33572 = CARTESIAN_POINT('',(2.966266693201E-002,-1.169261779931E-002)); -#33573 = CARTESIAN_POINT('',(2.401530384089E-002,-1.062567047723E-002)); -#33574 = CARTESIAN_POINT('',(1.86125236906E-002,-9.251374369532E-003)); -#33575 = CARTESIAN_POINT('',(1.344081018494E-002,-7.506448321588E-003)); -#33576 = CARTESIAN_POINT('',(8.540776816794E-003,-5.353749912846E-003)); -#33577 = CARTESIAN_POINT('',(3.924266439798E-003,-2.741972134699E-003)); -#33578 = CARTESIAN_POINT('',(-4.387603858302E-004,2.251786809354E-004)); -#33579 = CARTESIAN_POINT('',(-4.5176735973E-003,3.58514457871E-003)); -#33580 = CARTESIAN_POINT('',(-8.276753280242E-003,7.283468286675E-003)); -#33581 = CARTESIAN_POINT('',(-1.167324242725E-002,1.133358380406E-002)); -#33582 = CARTESIAN_POINT('',(-1.480634225547E-002,1.564447784146E-002)); -#33583 = CARTESIAN_POINT('',(-1.745442630416E-002,2.039684762693E-002)); -#33584 = CARTESIAN_POINT('',(-1.988453681768E-002,2.541395403537E-002)); -#33585 = CARTESIAN_POINT('',(-2.195697049424E-002,3.078205441916E-002)); -#33586 = CARTESIAN_POINT('',(-2.301398482102E-002,3.451727791308E-002)); -#33587 = CARTESIAN_POINT('',(-2.355047146429E-002,3.641308714041E-002)); -#33588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33589 = PCURVE('',#30410,#33590); -#33590 = DEFINITIONAL_REPRESENTATION('',(#33591),#33595); -#33591 = LINE('',#33592,#33593); -#33592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33593 = VECTOR('',#33594,1.); -#33594 = DIRECTION('',(1.,0.E+000)); -#33595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33596 = ORIENTED_EDGE('',*,*,#33597,.F.); -#33597 = EDGE_CURVE('',#33598,#33541,#33600,.T.); -#33598 = VERTEX_POINT('',#33599); -#33599 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#33600 = SURFACE_CURVE('',#33601,(#33621,#33644),.PCURVE_S1.); -#33601 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33602,#33603,#33604,#33605, - #33606,#33607,#33608,#33609,#33610,#33611,#33612,#33613,#33614, - #33615,#33616,#33617,#33618,#33619,#33620),.UNSPECIFIED.,.F.,.F.,(4, +#35961 = CARTESIAN_POINT('',(4.16864694902E-002,-1.236027250064E-002)); +#35962 = CARTESIAN_POINT('',(3.962765097581E-002,-1.231560861237E-002)); +#35963 = CARTESIAN_POINT('',(3.558789284008E-002,-1.222797033599E-002)); +#35964 = CARTESIAN_POINT('',(2.966266693201E-002,-1.169261779931E-002)); +#35965 = CARTESIAN_POINT('',(2.401530384089E-002,-1.062567047723E-002)); +#35966 = CARTESIAN_POINT('',(1.86125236906E-002,-9.251374369532E-003)); +#35967 = CARTESIAN_POINT('',(1.344081018494E-002,-7.506448321588E-003)); +#35968 = CARTESIAN_POINT('',(8.540776816794E-003,-5.353749912846E-003)); +#35969 = CARTESIAN_POINT('',(3.924266439798E-003,-2.741972134699E-003)); +#35970 = CARTESIAN_POINT('',(-4.387603858302E-004,2.251786809354E-004)); +#35971 = CARTESIAN_POINT('',(-4.5176735973E-003,3.58514457871E-003)); +#35972 = CARTESIAN_POINT('',(-8.276753280242E-003,7.283468286675E-003)); +#35973 = CARTESIAN_POINT('',(-1.167324242725E-002,1.133358380406E-002)); +#35974 = CARTESIAN_POINT('',(-1.480634225547E-002,1.564447784146E-002)); +#35975 = CARTESIAN_POINT('',(-1.745442630416E-002,2.039684762693E-002)); +#35976 = CARTESIAN_POINT('',(-1.988453681768E-002,2.541395403537E-002)); +#35977 = CARTESIAN_POINT('',(-2.195697049424E-002,3.078205441916E-002)); +#35978 = CARTESIAN_POINT('',(-2.301398482102E-002,3.451727791308E-002)); +#35979 = CARTESIAN_POINT('',(-2.355047146429E-002,3.641308714041E-002)); +#35980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35981 = PCURVE('',#32802,#35982); +#35982 = DEFINITIONAL_REPRESENTATION('',(#35983),#35987); +#35983 = LINE('',#35984,#35985); +#35984 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#35985 = VECTOR('',#35986,1.); +#35986 = DIRECTION('',(1.,0.E+000)); +#35987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#35988 = ORIENTED_EDGE('',*,*,#35989,.F.); +#35989 = EDGE_CURVE('',#35990,#35933,#35992,.T.); +#35990 = VERTEX_POINT('',#35991); +#35991 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#35992 = SURFACE_CURVE('',#35993,(#36013,#36036),.PCURVE_S1.); +#35993 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35994,#35995,#35996,#35997, + #35998,#35999,#36000,#36001,#36002,#36003,#36004,#36005,#36006, + #36007,#36008,#36009,#36010,#36011,#36012),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.044163105955E-002, 0.13808932472,0.203177733524,0.266138723805,0.327928781367, 0.389190360761,0.450253575103,0.512346578128,0.573842720559, 0.633932556807,0.693459807598,0.752479435483,0.812385930843, 0.873070465232,0.935184306584,1.),.UNSPECIFIED.); -#33602 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#33603 = CARTESIAN_POINT('',(-0.15422224945,0.782,-0.184279954097)); -#33604 = CARTESIAN_POINT('',(-0.16011058641,0.782,-0.18442241248)); -#33605 = CARTESIAN_POINT('',(-0.168730904373,0.782,-0.185435660286)); -#33606 = CARTESIAN_POINT('',(-0.176888956674,0.782,-0.187251556488)); -#33607 = CARTESIAN_POINT('',(-0.184603227745,0.782,-0.189734964963)); -#33608 = CARTESIAN_POINT('',(-0.191915564883,0.782,-0.192849452628)); -#33609 = CARTESIAN_POINT('',(-0.198717980682,0.782,-0.19680271821)); -#33610 = CARTESIAN_POINT('',(-0.205104189941,0.782,-0.201412468033)); -#33611 = CARTESIAN_POINT('',(-0.210973195665,0.782,-0.206682596761)); -#33612 = CARTESIAN_POINT('',(-0.216262683863,0.782,-0.212476207474)); -#33613 = CARTESIAN_POINT('',(-0.220867043727,0.782,-0.218691964243)); -#33614 = CARTESIAN_POINT('',(-0.224791789972,0.782,-0.225234208511)); -#33615 = CARTESIAN_POINT('',(-0.228021770962,0.782,-0.232139820494)); -#33616 = CARTESIAN_POINT('',(-0.230483753007,0.782,-0.23940886311)); -#33617 = CARTESIAN_POINT('',(-0.232211601209,0.782,-0.247014045784)); -#33618 = CARTESIAN_POINT('',(-0.233346324416,0.782,-0.254949557005)); -#33619 = CARTESIAN_POINT('',(-0.233472161067,0.782,-0.260364482314)); -#33620 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#33621 = PCURVE('',#33244,#33622); -#33622 = DEFINITIONAL_REPRESENTATION('',(#33623),#33643); -#33623 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33624,#33625,#33626,#33627, - #33628,#33629,#33630,#33631,#33632,#33633,#33634,#33635,#33636, - #33637,#33638,#33639,#33640,#33641,#33642),.UNSPECIFIED.,.F.,.F.,(4, +#35994 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#35995 = CARTESIAN_POINT('',(-0.15422224945,0.782,-0.184279954097)); +#35996 = CARTESIAN_POINT('',(-0.16011058641,0.782,-0.18442241248)); +#35997 = CARTESIAN_POINT('',(-0.168730904373,0.782,-0.185435660286)); +#35998 = CARTESIAN_POINT('',(-0.176888956674,0.782,-0.187251556488)); +#35999 = CARTESIAN_POINT('',(-0.184603227745,0.782,-0.189734964963)); +#36000 = CARTESIAN_POINT('',(-0.191915564883,0.782,-0.192849452628)); +#36001 = CARTESIAN_POINT('',(-0.198717980682,0.782,-0.19680271821)); +#36002 = CARTESIAN_POINT('',(-0.205104189941,0.782,-0.201412468033)); +#36003 = CARTESIAN_POINT('',(-0.210973195665,0.782,-0.206682596761)); +#36004 = CARTESIAN_POINT('',(-0.216262683863,0.782,-0.212476207474)); +#36005 = CARTESIAN_POINT('',(-0.220867043727,0.782,-0.218691964243)); +#36006 = CARTESIAN_POINT('',(-0.224791789972,0.782,-0.225234208511)); +#36007 = CARTESIAN_POINT('',(-0.228021770962,0.782,-0.232139820494)); +#36008 = CARTESIAN_POINT('',(-0.230483753007,0.782,-0.23940886311)); +#36009 = CARTESIAN_POINT('',(-0.232211601209,0.782,-0.247014045784)); +#36010 = CARTESIAN_POINT('',(-0.233346324416,0.782,-0.254949557005)); +#36011 = CARTESIAN_POINT('',(-0.233472161067,0.782,-0.260364482314)); +#36012 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#36013 = PCURVE('',#35636,#36014); +#36014 = DEFINITIONAL_REPRESENTATION('',(#36015),#36035); +#36015 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36016,#36017,#36018,#36019, + #36020,#36021,#36022,#36023,#36024,#36025,#36026,#36027,#36028, + #36029,#36030,#36031,#36032,#36033,#36034),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.044163105955E-002, 0.13808932472,0.203177733524,0.266138723805,0.327928781367, 0.389190360761,0.450253575103,0.512346578128,0.573842720559, 0.633932556807,0.693459807598,0.752479435483,0.812385930843, 0.873070465232,0.935184306584,1.),.UNSPECIFIED.); -#33624 = CARTESIAN_POINT('',(0.120608762411,6.995763406653E-002)); -#33625 = CARTESIAN_POINT('',(0.120536092052,6.695389673573E-002)); -#33626 = CARTESIAN_POINT('',(0.120393633669,6.106555977634E-002)); -#33627 = CARTESIAN_POINT('',(0.119380385863,5.244524181301E-002)); -#33628 = CARTESIAN_POINT('',(0.117564489661,4.42871895116E-002)); -#33629 = CARTESIAN_POINT('',(0.115081081186,3.657291844129E-002)); -#33630 = CARTESIAN_POINT('',(0.111966593521,2.926058130277E-002)); -#33631 = CARTESIAN_POINT('',(0.108013327939,2.245816550391E-002)); -#33632 = CARTESIAN_POINT('',(0.103403578116,1.607195624457E-002)); -#33633 = CARTESIAN_POINT('',(9.813344938806E-002,1.020295052099E-002)); -#33634 = CARTESIAN_POINT('',(9.233983867528E-002,4.913462322497E-003)); -#33635 = CARTESIAN_POINT('',(8.612408190621E-002,3.091024592475E-004)); -#33636 = CARTESIAN_POINT('',(7.958183763757E-002,-3.615643785743E-003)); -#33637 = CARTESIAN_POINT('',(7.267622565492E-002,-6.845624775869E-003)); -#33638 = CARTESIAN_POINT('',(6.540718303928E-002,-9.307606821214E-003)); -#33639 = CARTESIAN_POINT('',(5.780200036489E-002,-1.103545502259E-002)); -#33640 = CARTESIAN_POINT('',(4.9866489144E-002,-1.217017823017E-002)); -#33641 = CARTESIAN_POINT('',(4.445156383461E-002,-1.229601488092E-002)); -#33642 = CARTESIAN_POINT('',(4.16864694902E-002,-1.236027250064E-002)); -#33643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33644 = PCURVE('',#31002,#33645); -#33645 = DEFINITIONAL_REPRESENTATION('',(#33646),#33650); -#33646 = LINE('',#33647,#33648); -#33647 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33648 = VECTOR('',#33649,1.); -#33649 = DIRECTION('',(1.,0.E+000)); -#33650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33651 = ORIENTED_EDGE('',*,*,#33652,.F.); -#33652 = EDGE_CURVE('',#33653,#33598,#33655,.T.); -#33653 = VERTEX_POINT('',#33654); -#33654 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) - ); -#33655 = SURFACE_CURVE('',#33656,(#33676,#33699),.PCURVE_S1.); -#33656 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33657,#33658,#33659,#33660, - #33661,#33662,#33663,#33664,#33665,#33666,#33667,#33668,#33669, - #33670,#33671,#33672,#33673,#33674,#33675),.UNSPECIFIED.,.F.,.F.,(4, +#36016 = CARTESIAN_POINT('',(0.120608762411,6.995763406653E-002)); +#36017 = CARTESIAN_POINT('',(0.120536092052,6.695389673573E-002)); +#36018 = CARTESIAN_POINT('',(0.120393633669,6.106555977634E-002)); +#36019 = CARTESIAN_POINT('',(0.119380385863,5.244524181301E-002)); +#36020 = CARTESIAN_POINT('',(0.117564489661,4.42871895116E-002)); +#36021 = CARTESIAN_POINT('',(0.115081081186,3.657291844129E-002)); +#36022 = CARTESIAN_POINT('',(0.111966593521,2.926058130277E-002)); +#36023 = CARTESIAN_POINT('',(0.108013327939,2.245816550391E-002)); +#36024 = CARTESIAN_POINT('',(0.103403578116,1.607195624457E-002)); +#36025 = CARTESIAN_POINT('',(9.813344938806E-002,1.020295052099E-002)); +#36026 = CARTESIAN_POINT('',(9.233983867528E-002,4.913462322497E-003)); +#36027 = CARTESIAN_POINT('',(8.612408190621E-002,3.091024592475E-004)); +#36028 = CARTESIAN_POINT('',(7.958183763757E-002,-3.615643785743E-003)); +#36029 = CARTESIAN_POINT('',(7.267622565492E-002,-6.845624775869E-003)); +#36030 = CARTESIAN_POINT('',(6.540718303928E-002,-9.307606821214E-003)); +#36031 = CARTESIAN_POINT('',(5.780200036489E-002,-1.103545502259E-002)); +#36032 = CARTESIAN_POINT('',(4.9866489144E-002,-1.217017823017E-002)); +#36033 = CARTESIAN_POINT('',(4.445156383461E-002,-1.229601488092E-002)); +#36034 = CARTESIAN_POINT('',(4.16864694902E-002,-1.236027250064E-002)); +#36035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36036 = PCURVE('',#33394,#36037); +#36037 = DEFINITIONAL_REPRESENTATION('',(#36038),#36042); +#36038 = LINE('',#36039,#36040); +#36039 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36040 = VECTOR('',#36041,1.); +#36041 = DIRECTION('',(1.,0.E+000)); +#36042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36043 = ORIENTED_EDGE('',*,*,#36044,.F.); +#36044 = EDGE_CURVE('',#36045,#35990,#36047,.T.); +#36045 = VERTEX_POINT('',#36046); +#36046 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) + ); +#36047 = SURFACE_CURVE('',#36048,(#36068,#36091),.PCURVE_S1.); +#36048 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36049,#36050,#36051,#36052, + #36053,#36054,#36055,#36056,#36057,#36058,#36059,#36060,#36061, + #36062,#36063,#36064,#36065,#36066,#36067),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.359990034717E-002, 0.125296650794,0.185568720195,0.244698211001,0.30371680619, 0.362919650948,0.423300313869,0.485177309545,0.547083413224, 0.608524799634,0.669964853245,0.732299377978,0.79565029349, 0.861055470947,0.929122115173,1.),.UNSPECIFIED.); -#33657 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) +#36049 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) ); -#33658 = CARTESIAN_POINT('',(-6.896604125846E-002,0.782,-0.259558415664) +#36050 = CARTESIAN_POINT('',(-6.896604125846E-002,0.782,-0.259558415664) ); -#33659 = CARTESIAN_POINT('',(-6.909495458679E-002,0.782,-0.254246039676) +#36051 = CARTESIAN_POINT('',(-6.909495458679E-002,0.782,-0.254246039676) ); -#33660 = CARTESIAN_POINT('',(-7.022762763978E-002,0.782,-0.246448095159) +#36052 = CARTESIAN_POINT('',(-7.022762763978E-002,0.782,-0.246448095159) ); -#33661 = CARTESIAN_POINT('',(-7.194141210995E-002,0.782,-0.238957105397) +#36053 = CARTESIAN_POINT('',(-7.194141210995E-002,0.782,-0.238957105397) ); -#33662 = CARTESIAN_POINT('',(-7.444030771623E-002,0.782,-0.231804715104) +#36054 = CARTESIAN_POINT('',(-7.444030771623E-002,0.782,-0.231804715104) ); -#33663 = CARTESIAN_POINT('',(-7.763201825955E-002,0.782,-0.224985868182) +#36055 = CARTESIAN_POINT('',(-7.763201825955E-002,0.782,-0.224985868182) ); -#33664 = CARTESIAN_POINT('',(-8.158020278859E-002,0.782,-0.218510466344) +#36056 = CARTESIAN_POINT('',(-8.158020278859E-002,0.782,-0.218510466344) ); -#33665 = CARTESIAN_POINT('',(-8.624606907258E-002,0.782,-0.212385170715) +#36057 = CARTESIAN_POINT('',(-8.624606907258E-002,0.782,-0.212385170715) ); -#33666 = CARTESIAN_POINT('',(-9.149198214336E-002,0.782,-0.20659094194) +#36058 = CARTESIAN_POINT('',(-9.149198214336E-002,0.782,-0.20659094194) ); -#33667 = CARTESIAN_POINT('',(-9.735690982358E-002,0.782,-0.201353210079) +#36059 = CARTESIAN_POINT('',(-9.735690982358E-002,0.782,-0.201353210079) ); -#33668 = CARTESIAN_POINT('',(-0.103701675181,0.782,-0.196737612617)); -#33669 = CARTESIAN_POINT('',(-0.110550084589,0.782,-0.192871461252)); -#33670 = CARTESIAN_POINT('',(-0.117819043423,0.782,-0.18967030182)); -#33671 = CARTESIAN_POINT('',(-0.12554335796,0.782,-0.187189415129)); -#33672 = CARTESIAN_POINT('',(-0.133713099132,0.782,-0.18545226843)); -#33673 = CARTESIAN_POINT('',(-0.142325548317,0.782,-0.184417874018)); -#33674 = CARTESIAN_POINT('',(-0.148214474312,0.782,-0.184278421007)); -#33675 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#33676 = PCURVE('',#33244,#33677); -#33677 = DEFINITIONAL_REPRESENTATION('',(#33678),#33698); -#33678 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33679,#33680,#33681,#33682, - #33683,#33684,#33685,#33686,#33687,#33688,#33689,#33690,#33691, - #33692,#33693,#33694,#33695,#33696,#33697),.UNSPECIFIED.,.F.,.F.,(4, +#36060 = CARTESIAN_POINT('',(-0.103701675181,0.782,-0.196737612617)); +#36061 = CARTESIAN_POINT('',(-0.110550084589,0.782,-0.192871461252)); +#36062 = CARTESIAN_POINT('',(-0.117819043423,0.782,-0.18967030182)); +#36063 = CARTESIAN_POINT('',(-0.12554335796,0.782,-0.187189415129)); +#36064 = CARTESIAN_POINT('',(-0.133713099132,0.782,-0.18545226843)); +#36065 = CARTESIAN_POINT('',(-0.142325548317,0.782,-0.184417874018)); +#36066 = CARTESIAN_POINT('',(-0.148214474312,0.782,-0.184278421007)); +#36067 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#36068 = PCURVE('',#35636,#36069); +#36069 = DEFINITIONAL_REPRESENTATION('',(#36070),#36090); +#36070 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36071,#36072,#36073,#36074, + #36075,#36076,#36077,#36078,#36079,#36080,#36081,#36082,#36083, + #36084,#36085,#36086,#36087,#36088,#36089),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.359990034717E-002, 0.125296650794,0.185568720195,0.244698211001,0.30371680619, 0.362919650948,0.423300313869,0.485177309545,0.547083413224, 0.608524799634,0.669964853245,0.732299377978,0.79565029349, 0.861055470947,0.929122115173,1.),.UNSPECIFIED.); -#33679 = CARTESIAN_POINT('',(4.256109724748E-002,0.152275540634)); -#33680 = CARTESIAN_POINT('',(4.5257630485E-002,0.152210104927)); -#33681 = CARTESIAN_POINT('',(5.057000647257E-002,0.152081191599)); -#33682 = CARTESIAN_POINT('',(5.836795098993E-002,0.150948518546)); -#33683 = CARTESIAN_POINT('',(6.585894075203E-002,0.149234734076)); -#33684 = CARTESIAN_POINT('',(7.30113310452E-002,0.14673583847)); -#33685 = CARTESIAN_POINT('',(7.983017796642E-002,0.143544127926)); -#33686 = CARTESIAN_POINT('',(8.630557980486E-002,0.139595943397)); -#33687 = CARTESIAN_POINT('',(9.243087543361E-002,0.134930077113)); -#33688 = CARTESIAN_POINT('',(9.822510420853E-002,0.129684164043)); -#33689 = CARTESIAN_POINT('',(0.10346283607,0.123819236362)); -#33690 = CARTESIAN_POINT('',(0.108078433532,0.117474471005)); -#33691 = CARTESIAN_POINT('',(0.111944584897,0.110626061597)); -#33692 = CARTESIAN_POINT('',(0.115145744329,0.103357102763)); -#33693 = CARTESIAN_POINT('',(0.11762663102,9.563278822584E-002)); -#33694 = CARTESIAN_POINT('',(0.119363777719,8.746304705442E-002)); -#33695 = CARTESIAN_POINT('',(0.120398172131,7.885059786923E-002)); -#33696 = CARTESIAN_POINT('',(0.120537625142,7.296167187413E-002)); -#33697 = CARTESIAN_POINT('',(0.120608762411,6.995763406653E-002)); -#33698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33699 = PCURVE('',#30910,#33700); -#33700 = DEFINITIONAL_REPRESENTATION('',(#33701),#33705); -#33701 = LINE('',#33702,#33703); -#33702 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33703 = VECTOR('',#33704,1.); -#33704 = DIRECTION('',(1.,0.E+000)); -#33705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33706 = ORIENTED_EDGE('',*,*,#33707,.F.); -#33707 = EDGE_CURVE('',#33708,#33653,#33710,.T.); -#33708 = VERTEX_POINT('',#33709); -#33709 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#33710 = SURFACE_CURVE('',#33711,(#33731,#33754),.PCURVE_S1.); -#33711 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33712,#33713,#33714,#33715, - #33716,#33717,#33718,#33719,#33720,#33721,#33722,#33723,#33724, - #33725,#33726,#33727,#33728,#33729,#33730),.UNSPECIFIED.,.F.,.F.,(4, +#36071 = CARTESIAN_POINT('',(4.256109724748E-002,0.152275540634)); +#36072 = CARTESIAN_POINT('',(4.5257630485E-002,0.152210104927)); +#36073 = CARTESIAN_POINT('',(5.057000647257E-002,0.152081191599)); +#36074 = CARTESIAN_POINT('',(5.836795098993E-002,0.150948518546)); +#36075 = CARTESIAN_POINT('',(6.585894075203E-002,0.149234734076)); +#36076 = CARTESIAN_POINT('',(7.30113310452E-002,0.14673583847)); +#36077 = CARTESIAN_POINT('',(7.983017796642E-002,0.143544127926)); +#36078 = CARTESIAN_POINT('',(8.630557980486E-002,0.139595943397)); +#36079 = CARTESIAN_POINT('',(9.243087543361E-002,0.134930077113)); +#36080 = CARTESIAN_POINT('',(9.822510420853E-002,0.129684164043)); +#36081 = CARTESIAN_POINT('',(0.10346283607,0.123819236362)); +#36082 = CARTESIAN_POINT('',(0.108078433532,0.117474471005)); +#36083 = CARTESIAN_POINT('',(0.111944584897,0.110626061597)); +#36084 = CARTESIAN_POINT('',(0.115145744329,0.103357102763)); +#36085 = CARTESIAN_POINT('',(0.11762663102,9.563278822584E-002)); +#36086 = CARTESIAN_POINT('',(0.119363777719,8.746304705442E-002)); +#36087 = CARTESIAN_POINT('',(0.120398172131,7.885059786923E-002)); +#36088 = CARTESIAN_POINT('',(0.120537625142,7.296167187413E-002)); +#36089 = CARTESIAN_POINT('',(0.120608762411,6.995763406653E-002)); +#36090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36091 = PCURVE('',#33302,#36092); +#36092 = DEFINITIONAL_REPRESENTATION('',(#36093),#36097); +#36093 = LINE('',#36094,#36095); +#36094 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36095 = VECTOR('',#36096,1.); +#36096 = DIRECTION('',(1.,0.E+000)); +#36097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36098 = ORIENTED_EDGE('',*,*,#36099,.F.); +#36099 = EDGE_CURVE('',#36100,#36045,#36102,.T.); +#36100 = VERTEX_POINT('',#36101); +#36101 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#36102 = SURFACE_CURVE('',#36103,(#36123,#36146),.PCURVE_S1.); +#36103 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36104,#36105,#36106,#36107, + #36108,#36109,#36110,#36111,#36112,#36113,#36114,#36115,#36116, + #36117,#36118,#36119,#36120,#36121,#36122),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.901300291099E-002, 0.135235544056,0.199611185116,0.262418519503,0.32372349721, 0.383765365604,0.443773035096,0.503794956498,0.563822577717, 0.623484312883,0.683469172274,0.743590762456,0.805727219974, 0.868616210735,0.933278202847,1.),.UNSPECIFIED.); -#33712 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#33713 = CARTESIAN_POINT('',(-0.114933412774,0.782,-0.327715660212)); -#33714 = CARTESIAN_POINT('',(-0.111176192863,0.782,-0.326440262085)); -#33715 = CARTESIAN_POINT('',(-0.105864604895,0.782,-0.32396049507)); -#33716 = CARTESIAN_POINT('',(-0.100863904474,0.782,-0.321286717616)); -#33717 = CARTESIAN_POINT('',(-9.614589209932E-002,0.782,-0.318392351899) +#36104 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#36105 = CARTESIAN_POINT('',(-0.114933412774,0.782,-0.327715660212)); +#36106 = CARTESIAN_POINT('',(-0.111176192863,0.782,-0.326440262085)); +#36107 = CARTESIAN_POINT('',(-0.105864604895,0.782,-0.32396049507)); +#36108 = CARTESIAN_POINT('',(-0.100863904474,0.782,-0.321286717616)); +#36109 = CARTESIAN_POINT('',(-9.614589209932E-002,0.782,-0.318392351899) ); -#33718 = CARTESIAN_POINT('',(-9.188472123138E-002,0.782,-0.315062150838) +#36110 = CARTESIAN_POINT('',(-9.188472123138E-002,0.782,-0.315062150838) ); -#33719 = CARTESIAN_POINT('',(-8.793822669242E-002,0.782,-0.31149301542) +#36111 = CARTESIAN_POINT('',(-8.793822669242E-002,0.782,-0.31149301542) ); -#33720 = CARTESIAN_POINT('',(-8.432300128947E-002,0.782,-0.30763464951) +#36112 = CARTESIAN_POINT('',(-8.432300128947E-002,0.782,-0.30763464951) ); -#33721 = CARTESIAN_POINT('',(-8.10884251632E-002,0.782,-0.303454237299) +#36113 = CARTESIAN_POINT('',(-8.10884251632E-002,0.782,-0.303454237299) ); -#33722 = CARTESIAN_POINT('',(-7.820060751267E-002,0.782,-0.299039518498) +#36114 = CARTESIAN_POINT('',(-7.820060751267E-002,0.782,-0.299039518498) ); -#33723 = CARTESIAN_POINT('',(-7.572840637402E-002,0.782,-0.294379729823) +#36115 = CARTESIAN_POINT('',(-7.572840637402E-002,0.782,-0.294379729823) ); -#33724 = CARTESIAN_POINT('',(-7.362881342303E-002,0.782,-0.28954119727) +#36116 = CARTESIAN_POINT('',(-7.362881342303E-002,0.782,-0.28954119727) ); -#33725 = CARTESIAN_POINT('',(-7.183442898442E-002,0.782,-0.284501483646) +#36117 = CARTESIAN_POINT('',(-7.183442898442E-002,0.782,-0.284501483646) ); -#33726 = CARTESIAN_POINT('',(-7.05237729917E-002,0.782,-0.27922508981)); -#33727 = CARTESIAN_POINT('',(-6.960672455506E-002,0.782,-0.273736263582) +#36118 = CARTESIAN_POINT('',(-7.05237729917E-002,0.782,-0.27922508981)); +#36119 = CARTESIAN_POINT('',(-6.960672455506E-002,0.782,-0.273736263582) ); -#33728 = CARTESIAN_POINT('',(-6.902488317678E-002,0.782,-0.268063932998) +#36120 = CARTESIAN_POINT('',(-6.902488317678E-002,0.782,-0.268063932998) ); -#33729 = CARTESIAN_POINT('',(-6.894246215307E-002,0.782,-0.264211409926) +#36121 = CARTESIAN_POINT('',(-6.894246215307E-002,0.782,-0.264211409926) ); -#33730 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) +#36122 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) ); -#33731 = PCURVE('',#33244,#33732); -#33732 = DEFINITIONAL_REPRESENTATION('',(#33733),#33753); -#33733 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33734,#33735,#33736,#33737, - #33738,#33739,#33740,#33741,#33742,#33743,#33744,#33745,#33746, - #33747,#33748,#33749,#33750,#33751,#33752),.UNSPECIFIED.,.F.,.F.,(4, +#36123 = PCURVE('',#35636,#36124); +#36124 = DEFINITIONAL_REPRESENTATION('',(#36125),#36145); +#36125 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36126,#36127,#36128,#36129, + #36130,#36131,#36132,#36133,#36134,#36135,#36136,#36137,#36138, + #36139,#36140,#36141,#36142,#36143,#36144),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.901300291099E-002, 0.135235544056,0.199611185116,0.262418519503,0.32372349721, 0.383765365604,0.443773035096,0.503794956498,0.563822577717, 0.623484312883,0.683469172274,0.743590762456,0.805727219974, 0.868616210735,0.933278202847,1.),.UNSPECIFIED.); -#33734 = CARTESIAN_POINT('',(-2.355047146429E-002,0.104325360058)); -#33735 = CARTESIAN_POINT('',(-2.289961406359E-002,0.106242733412)); -#33736 = CARTESIAN_POINT('',(-2.162421593609E-002,0.109999953323)); -#33737 = CARTESIAN_POINT('',(-1.91444489209E-002,0.115311541291)); -#33738 = CARTESIAN_POINT('',(-1.647067146695E-002,0.120312241712)); -#33739 = CARTESIAN_POINT('',(-1.357630575065E-002,0.125030254087)); -#33740 = CARTESIAN_POINT('',(-1.02461046888E-002,0.129291424955)); -#33741 = CARTESIAN_POINT('',(-6.676969270997E-003,0.133237919494)); -#33742 = CARTESIAN_POINT('',(-2.818603360954E-003,0.136853144896)); -#33743 = CARTESIAN_POINT('',(1.361808849834E-003,0.140087721023)); -#33744 = CARTESIAN_POINT('',(5.776527650779E-003,0.142975538673)); -#33745 = CARTESIAN_POINT('',(1.043631632607E-002,0.145447739812)); -#33746 = CARTESIAN_POINT('',(1.527484887896E-002,0.147547332763)); -#33747 = CARTESIAN_POINT('',(2.031456250325E-002,0.149341717202)); -#33748 = CARTESIAN_POINT('',(2.559095633845E-002,0.150652373194)); -#33749 = CARTESIAN_POINT('',(3.107978256693E-002,0.151569421631)); -#33750 = CARTESIAN_POINT('',(3.675211315063E-002,0.152151263009)); -#33751 = CARTESIAN_POINT('',(4.060463622292E-002,0.152233684033)); -#33752 = CARTESIAN_POINT('',(4.256109724748E-002,0.152275540634)); -#33753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33754 = PCURVE('',#30816,#33755); -#33755 = DEFINITIONAL_REPRESENTATION('',(#33756),#33760); -#33756 = LINE('',#33757,#33758); -#33757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33758 = VECTOR('',#33759,1.); -#33759 = DIRECTION('',(1.,0.E+000)); -#33760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33761 = ORIENTED_EDGE('',*,*,#33762,.F.); -#33762 = EDGE_CURVE('',#33763,#33708,#33765,.T.); -#33763 = VERTEX_POINT('',#33764); -#33764 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) - ); -#33765 = SURFACE_CURVE('',#33766,(#33778,#33793),.PCURVE_S1.); -#33766 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33767,#33768,#33769,#33770, - #33771,#33772,#33773,#33774,#33775,#33776,#33777),.UNSPECIFIED.,.F., +#36126 = CARTESIAN_POINT('',(-2.355047146429E-002,0.104325360058)); +#36127 = CARTESIAN_POINT('',(-2.289961406359E-002,0.106242733412)); +#36128 = CARTESIAN_POINT('',(-2.162421593609E-002,0.109999953323)); +#36129 = CARTESIAN_POINT('',(-1.91444489209E-002,0.115311541291)); +#36130 = CARTESIAN_POINT('',(-1.647067146695E-002,0.120312241712)); +#36131 = CARTESIAN_POINT('',(-1.357630575065E-002,0.125030254087)); +#36132 = CARTESIAN_POINT('',(-1.02461046888E-002,0.129291424955)); +#36133 = CARTESIAN_POINT('',(-6.676969270997E-003,0.133237919494)); +#36134 = CARTESIAN_POINT('',(-2.818603360954E-003,0.136853144896)); +#36135 = CARTESIAN_POINT('',(1.361808849834E-003,0.140087721023)); +#36136 = CARTESIAN_POINT('',(5.776527650779E-003,0.142975538673)); +#36137 = CARTESIAN_POINT('',(1.043631632607E-002,0.145447739812)); +#36138 = CARTESIAN_POINT('',(1.527484887896E-002,0.147547332763)); +#36139 = CARTESIAN_POINT('',(2.031456250325E-002,0.149341717202)); +#36140 = CARTESIAN_POINT('',(2.559095633845E-002,0.150652373194)); +#36141 = CARTESIAN_POINT('',(3.107978256693E-002,0.151569421631)); +#36142 = CARTESIAN_POINT('',(3.675211315063E-002,0.152151263009)); +#36143 = CARTESIAN_POINT('',(4.060463622292E-002,0.152233684033)); +#36144 = CARTESIAN_POINT('',(4.256109724748E-002,0.152275540634)); +#36145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36146 = PCURVE('',#33208,#36147); +#36147 = DEFINITIONAL_REPRESENTATION('',(#36148),#36152); +#36148 = LINE('',#36149,#36150); +#36149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36150 = VECTOR('',#36151,1.); +#36151 = DIRECTION('',(1.,0.E+000)); +#36152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36153 = ORIENTED_EDGE('',*,*,#36154,.F.); +#36154 = EDGE_CURVE('',#36155,#36100,#36157,.T.); +#36155 = VERTEX_POINT('',#36156); +#36156 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) + ); +#36157 = SURFACE_CURVE('',#36158,(#36170,#36185),.PCURVE_S1.); +#36158 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36159,#36160,#36161,#36162, + #36163,#36164,#36165,#36166,#36167,#36168,#36169),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.124835092167,0.244778133283, 0.360988977841,0.477964172247,0.596922117558,0.721590756697, 0.855097865757,1.),.UNSPECIFIED.); -#33767 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) +#36159 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) ); -#33768 = CARTESIAN_POINT('',(-7.887285724434E-002,0.782,-0.375911436438) +#36160 = CARTESIAN_POINT('',(-7.887285724434E-002,0.782,-0.375911436438) ); -#33769 = CARTESIAN_POINT('',(-7.905737533771E-002,0.782,-0.37037537768) +#36161 = CARTESIAN_POINT('',(-7.905737533771E-002,0.782,-0.37037537768) ); -#33770 = CARTESIAN_POINT('',(-8.093769722843E-002,0.782,-0.362395102964) +#36162 = CARTESIAN_POINT('',(-8.093769722843E-002,0.782,-0.362395102964) ); -#33771 = CARTESIAN_POINT('',(-8.386833973693E-002,0.782,-0.354945116544) +#36163 = CARTESIAN_POINT('',(-8.386833973693E-002,0.782,-0.354945116544) ); -#33772 = CARTESIAN_POINT('',(-8.810400249721E-002,0.782,-0.348167402211) +#36164 = CARTESIAN_POINT('',(-8.810400249721E-002,0.782,-0.348167402211) ); -#33773 = CARTESIAN_POINT('',(-9.346831185091E-002,0.782,-0.341991961362) +#36165 = CARTESIAN_POINT('',(-9.346831185091E-002,0.782,-0.341991961362) ); -#33774 = CARTESIAN_POINT('',(-0.100124991939,0.782,-0.336623582911)); -#33775 = CARTESIAN_POINT('',(-0.107972949029,0.782,-0.331941156302)); -#33776 = CARTESIAN_POINT('',(-0.113811846918,0.782,-0.329590138812)); -#33777 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#33778 = PCURVE('',#33244,#33779); -#33779 = DEFINITIONAL_REPRESENTATION('',(#33780),#33792); -#33780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33781,#33782,#33783,#33784, - #33785,#33786,#33787,#33788,#33789,#33790,#33791),.UNSPECIFIED.,.F., +#36166 = CARTESIAN_POINT('',(-0.100124991939,0.782,-0.336623582911)); +#36167 = CARTESIAN_POINT('',(-0.107972949029,0.782,-0.331941156302)); +#36168 = CARTESIAN_POINT('',(-0.113811846918,0.782,-0.329590138812)); +#36169 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#36170 = PCURVE('',#35636,#36171); +#36171 = DEFINITIONAL_REPRESENTATION('',(#36172),#36184); +#36172 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36173,#36174,#36175,#36176, + #36177,#36178,#36179,#36180,#36181,#36182,#36183),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.124835092167,0.244778133283, 0.360988977841,0.477964172247,0.596922117558,0.721590756697, 0.855097865757,1.),.UNSPECIFIED.); -#33781 = CARTESIAN_POINT('',(-7.391874054508E-002,0.142397391846)); -#33782 = CARTESIAN_POINT('',(-7.109539028896E-002,0.142303288942)); -#33783 = CARTESIAN_POINT('',(-6.555933153095E-002,0.142118770848)); -#33784 = CARTESIAN_POINT('',(-5.757905681511E-002,0.140238448957)); -#33785 = CARTESIAN_POINT('',(-5.012907039484E-002,0.137307806449)); -#33786 = CARTESIAN_POINT('',(-4.335135606176E-002,0.133072143689)); -#33787 = CARTESIAN_POINT('',(-3.717591521279E-002,0.127707834335)); -#33788 = CARTESIAN_POINT('',(-3.180753676259E-002,0.121051154247)); -#33789 = CARTESIAN_POINT('',(-2.71251101537E-002,0.113203197157)); -#33790 = CARTESIAN_POINT('',(-2.477409266305E-002,0.107364299268)); -#33791 = CARTESIAN_POINT('',(-2.355047146429E-002,0.104325360058)); -#33792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33793 = PCURVE('',#30738,#33794); -#33794 = DEFINITIONAL_REPRESENTATION('',(#33795),#33799); -#33795 = LINE('',#33796,#33797); -#33796 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33797 = VECTOR('',#33798,1.); -#33798 = DIRECTION('',(1.,0.E+000)); -#33799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33800 = ORIENTED_EDGE('',*,*,#33801,.F.); -#33801 = EDGE_CURVE('',#33802,#33763,#33804,.T.); -#33802 = VERTEX_POINT('',#33803); -#33803 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#33804 = SURFACE_CURVE('',#33805,(#33825,#33848),.PCURVE_S1.); -#33805 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33806,#33807,#33808,#33809, - #33810,#33811,#33812,#33813,#33814,#33815,#33816,#33817,#33818, - #33819,#33820,#33821,#33822,#33823,#33824),.UNSPECIFIED.,.F.,.F.,(4, +#36173 = CARTESIAN_POINT('',(-7.391874054508E-002,0.142397391846)); +#36174 = CARTESIAN_POINT('',(-7.109539028896E-002,0.142303288942)); +#36175 = CARTESIAN_POINT('',(-6.555933153095E-002,0.142118770848)); +#36176 = CARTESIAN_POINT('',(-5.757905681511E-002,0.140238448957)); +#36177 = CARTESIAN_POINT('',(-5.012907039484E-002,0.137307806449)); +#36178 = CARTESIAN_POINT('',(-4.335135606176E-002,0.133072143689)); +#36179 = CARTESIAN_POINT('',(-3.717591521279E-002,0.127707834335)); +#36180 = CARTESIAN_POINT('',(-3.180753676259E-002,0.121051154247)); +#36181 = CARTESIAN_POINT('',(-2.71251101537E-002,0.113203197157)); +#36182 = CARTESIAN_POINT('',(-2.477409266305E-002,0.107364299268)); +#36183 = CARTESIAN_POINT('',(-2.355047146429E-002,0.104325360058)); +#36184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36185 = PCURVE('',#33130,#36186); +#36186 = DEFINITIONAL_REPRESENTATION('',(#36187),#36191); +#36187 = LINE('',#36188,#36189); +#36188 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36189 = VECTOR('',#36190,1.); +#36190 = DIRECTION('',(1.,0.E+000)); +#36191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36192 = ORIENTED_EDGE('',*,*,#36193,.F.); +#36193 = EDGE_CURVE('',#36194,#36155,#36196,.T.); +#36194 = VERTEX_POINT('',#36195); +#36195 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#36196 = SURFACE_CURVE('',#36197,(#36217,#36240),.PCURVE_S1.); +#36197 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36198,#36199,#36200,#36201, + #36202,#36203,#36204,#36205,#36206,#36207,#36208,#36209,#36210, + #36211,#36212,#36213,#36214,#36215,#36216),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.320074496854E-002, 0.142586791322,0.209624781468,0.274882926768,0.337930609532, 0.400461822188,0.462500620686,0.525005458137,0.586688852711, 0.646812765771,0.705215315751,0.762881021008,0.820727541693, 0.879295495725,0.938511165414,1.),.UNSPECIFIED.); -#33806 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#33807 = CARTESIAN_POINT('',(-0.148952355843,0.782,-0.444271528812)); -#33808 = CARTESIAN_POINT('',(-0.14373640916,0.782,-0.444153993928)); -#33809 = CARTESIAN_POINT('',(-0.136108549957,0.782,-0.443269018362)); -#33810 = CARTESIAN_POINT('',(-0.12887280298,0.782,-0.441785744181)); -#33811 = CARTESIAN_POINT('',(-0.122033428257,0.782,-0.439681351531)); -#33812 = CARTESIAN_POINT('',(-0.115579643283,0.782,-0.436990758818)); -#33813 = CARTESIAN_POINT('',(-0.109553855828,0.782,-0.433683667182)); -#33814 = CARTESIAN_POINT('',(-0.103894034067,0.782,-0.429814621087)); -#33815 = CARTESIAN_POINT('',(-9.874484109579E-002,0.782,-0.425337480783) +#36198 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#36199 = CARTESIAN_POINT('',(-0.148952355843,0.782,-0.444271528812)); +#36200 = CARTESIAN_POINT('',(-0.14373640916,0.782,-0.444153993928)); +#36201 = CARTESIAN_POINT('',(-0.136108549957,0.782,-0.443269018362)); +#36202 = CARTESIAN_POINT('',(-0.12887280298,0.782,-0.441785744181)); +#36203 = CARTESIAN_POINT('',(-0.122033428257,0.782,-0.439681351531)); +#36204 = CARTESIAN_POINT('',(-0.115579643283,0.782,-0.436990758818)); +#36205 = CARTESIAN_POINT('',(-0.109553855828,0.782,-0.433683667182)); +#36206 = CARTESIAN_POINT('',(-0.103894034067,0.782,-0.429814621087)); +#36207 = CARTESIAN_POINT('',(-9.874484109579E-002,0.782,-0.425337480783) ); -#33816 = CARTESIAN_POINT('',(-9.40596892566E-002,0.782,-0.420476762361) +#36208 = CARTESIAN_POINT('',(-9.40596892566E-002,0.782,-0.420476762361) ); -#33817 = CARTESIAN_POINT('',(-9.000044772922E-002,0.782,-0.415269287689) +#36209 = CARTESIAN_POINT('',(-9.000044772922E-002,0.782,-0.415269287689) ); -#33818 = CARTESIAN_POINT('',(-8.651896546958E-002,0.782,-0.409836569666) +#36210 = CARTESIAN_POINT('',(-8.651896546958E-002,0.782,-0.409836569666) ); -#33819 = CARTESIAN_POINT('',(-8.364204346514E-002,0.782,-0.404145603279) +#36211 = CARTESIAN_POINT('',(-8.364204346514E-002,0.782,-0.404145603279) ); -#33820 = CARTESIAN_POINT('',(-8.151368568852E-002,0.782,-0.398131583659) +#36212 = CARTESIAN_POINT('',(-8.151368568852E-002,0.782,-0.398131583659) ); -#33821 = CARTESIAN_POINT('',(-7.989139930784E-002,0.782,-0.391907817721) +#36213 = CARTESIAN_POINT('',(-7.989139930784E-002,0.782,-0.391907817721) ); -#33822 = CARTESIAN_POINT('',(-7.895039800517E-002,0.782,-0.385400354993) +#36214 = CARTESIAN_POINT('',(-7.895039800517E-002,0.782,-0.385400354993) ); -#33823 = CARTESIAN_POINT('',(-7.883668274196E-002,0.782,-0.380984364144) +#36215 = CARTESIAN_POINT('',(-7.883668274196E-002,0.782,-0.380984364144) ); -#33824 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) +#36216 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) ); -#33825 = PCURVE('',#33244,#33826); -#33826 = DEFINITIONAL_REPRESENTATION('',(#33827),#33847); -#33827 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33828,#33829,#33830,#33831, - #33832,#33833,#33834,#33835,#33836,#33837,#33838,#33839,#33840, - #33841,#33842,#33843,#33844,#33845,#33846),.UNSPECIFIED.,.F.,.F.,(4, +#36217 = PCURVE('',#35636,#36218); +#36218 = DEFINITIONAL_REPRESENTATION('',(#36219),#36239); +#36219 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36220,#36221,#36222,#36223, + #36224,#36225,#36226,#36227,#36228,#36229,#36230,#36231,#36232, + #36233,#36234,#36235,#36236,#36237,#36238),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.320074496854E-002, 0.142586791322,0.209624781468,0.274882926768,0.337930609532, 0.400461822188,0.462500620686,0.525005458137,0.586688852711, 0.646812765771,0.705215315751,0.762881021008,0.820727541693, 0.879295495725,0.938511165414,1.),.UNSPECIFIED.); -#33828 = CARTESIAN_POINT('',(-0.139515822341,6.95460445337E-002)); -#33829 = CARTESIAN_POINT('',(-0.139455482663,7.222379034303E-002)); -#33830 = CARTESIAN_POINT('',(-0.13933794778,7.743973702627E-002)); -#33831 = CARTESIAN_POINT('',(-0.138452972213,8.506759622939E-002)); -#33832 = CARTESIAN_POINT('',(-0.136969698032,9.230334320627E-002)); -#33833 = CARTESIAN_POINT('',(-0.134865305382,9.914271792916E-002)); -#33834 = CARTESIAN_POINT('',(-0.132174712669,0.105596502903)); -#33835 = CARTESIAN_POINT('',(-0.128867621033,0.111622290358)); -#33836 = CARTESIAN_POINT('',(-0.124998574938,0.117282112119)); -#33837 = CARTESIAN_POINT('',(-0.120521434634,0.12243130509)); -#33838 = CARTESIAN_POINT('',(-0.115660716213,0.127116456929)); -#33839 = CARTESIAN_POINT('',(-0.110453241541,0.131175698457)); -#33840 = CARTESIAN_POINT('',(-0.105020523517,0.134657180716)); -#33841 = CARTESIAN_POINT('',(-9.932955713037E-002,0.137534102721)); -#33842 = CARTESIAN_POINT('',(-9.331553751046E-002,0.139662460497)); -#33843 = CARTESIAN_POINT('',(-8.709177157173E-002,0.141284746878)); -#33844 = CARTESIAN_POINT('',(-8.058430884436E-002,0.142225748181)); -#33845 = CARTESIAN_POINT('',(-7.616831799472E-002,0.142339463444)); -#33846 = CARTESIAN_POINT('',(-7.391874054508E-002,0.142397391846)); -#33847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33848 = PCURVE('',#30660,#33849); -#33849 = DEFINITIONAL_REPRESENTATION('',(#33850),#33854); -#33850 = LINE('',#33851,#33852); -#33851 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33852 = VECTOR('',#33853,1.); -#33853 = DIRECTION('',(1.,0.E+000)); -#33854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33855 = ORIENTED_EDGE('',*,*,#33856,.F.); -#33856 = EDGE_CURVE('',#33857,#33802,#33859,.T.); -#33857 = VERTEX_POINT('',#33858); -#33858 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#33859 = SURFACE_CURVE('',#33860,(#33880,#33903),.PCURVE_S1.); -#33860 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33861,#33862,#33863,#33864, - #33865,#33866,#33867,#33868,#33869,#33870,#33871,#33872,#33873, - #33874,#33875,#33876,#33877,#33878,#33879),.UNSPECIFIED.,.F.,.F.,(4, +#36220 = CARTESIAN_POINT('',(-0.139515822341,6.95460445337E-002)); +#36221 = CARTESIAN_POINT('',(-0.139455482663,7.222379034303E-002)); +#36222 = CARTESIAN_POINT('',(-0.13933794778,7.743973702627E-002)); +#36223 = CARTESIAN_POINT('',(-0.138452972213,8.506759622939E-002)); +#36224 = CARTESIAN_POINT('',(-0.136969698032,9.230334320627E-002)); +#36225 = CARTESIAN_POINT('',(-0.134865305382,9.914271792916E-002)); +#36226 = CARTESIAN_POINT('',(-0.132174712669,0.105596502903)); +#36227 = CARTESIAN_POINT('',(-0.128867621033,0.111622290358)); +#36228 = CARTESIAN_POINT('',(-0.124998574938,0.117282112119)); +#36229 = CARTESIAN_POINT('',(-0.120521434634,0.12243130509)); +#36230 = CARTESIAN_POINT('',(-0.115660716213,0.127116456929)); +#36231 = CARTESIAN_POINT('',(-0.110453241541,0.131175698457)); +#36232 = CARTESIAN_POINT('',(-0.105020523517,0.134657180716)); +#36233 = CARTESIAN_POINT('',(-9.932955713037E-002,0.137534102721)); +#36234 = CARTESIAN_POINT('',(-9.331553751046E-002,0.139662460497)); +#36235 = CARTESIAN_POINT('',(-8.709177157173E-002,0.141284746878)); +#36236 = CARTESIAN_POINT('',(-8.058430884436E-002,0.142225748181)); +#36237 = CARTESIAN_POINT('',(-7.616831799472E-002,0.142339463444)); +#36238 = CARTESIAN_POINT('',(-7.391874054508E-002,0.142397391846)); +#36239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36240 = PCURVE('',#33052,#36241); +#36241 = DEFINITIONAL_REPRESENTATION('',(#36242),#36246); +#36242 = LINE('',#36243,#36244); +#36243 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36244 = VECTOR('',#36245,1.); +#36245 = DIRECTION('',(1.,0.E+000)); +#36246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36247 = ORIENTED_EDGE('',*,*,#36248,.F.); +#36248 = EDGE_CURVE('',#36249,#36194,#36251,.T.); +#36249 = VERTEX_POINT('',#36250); +#36250 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#36251 = SURFACE_CURVE('',#36252,(#36272,#36295),.PCURVE_S1.); +#36252 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36253,#36254,#36255,#36256, + #36257,#36258,#36259,#36260,#36261,#36262,#36263,#36264,#36265, + #36266,#36267,#36268,#36269,#36270,#36271),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.213137173661E-002, 0.121965824785,0.180570236649,0.238575970589,0.296000242091, 0.354358996444,0.413781228052,0.475097965352,0.537279897386, 0.598917953677,0.661235112979,0.724321980574,0.789217182509, 0.856396662088,0.926507768736,1.),.UNSPECIFIED.); -#33861 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#33862 = CARTESIAN_POINT('',(-0.223601769609,0.782,-0.38180795677)); -#33863 = CARTESIAN_POINT('',(-0.223490857774,0.782,-0.386224759452)); -#33864 = CARTESIAN_POINT('',(-0.222532554281,0.782,-0.392705669639)); -#33865 = CARTESIAN_POINT('',(-0.220997693172,0.782,-0.398916003004)); -#33866 = CARTESIAN_POINT('',(-0.218819366141,0.782,-0.404838231514)); -#33867 = CARTESIAN_POINT('',(-0.216090279388,0.782,-0.410521100535)); -#33868 = CARTESIAN_POINT('',(-0.212646632142,0.782,-0.415860497384)); -#33869 = CARTESIAN_POINT('',(-0.208688373522,0.782,-0.42100732422)); -#33870 = CARTESIAN_POINT('',(-0.204051461642,0.782,-0.425753530638)); -#33871 = CARTESIAN_POINT('',(-0.198941664913,0.782,-0.430100596353)); -#33872 = CARTESIAN_POINT('',(-0.193406957627,0.782,-0.433969057892)); -#33873 = CARTESIAN_POINT('',(-0.187404988129,0.782,-0.437132518976)); -#33874 = CARTESIAN_POINT('',(-0.181035826347,0.782,-0.439777439017)); -#33875 = CARTESIAN_POINT('',(-0.174267979923,0.782,-0.44184813175)); -#33876 = CARTESIAN_POINT('',(-0.167077608856,0.782,-0.44325838886)); -#33877 = CARTESIAN_POINT('',(-0.159490060777,0.782,-0.444155417005)); -#33878 = CARTESIAN_POINT('',(-0.154290892639,0.782,-0.444272135288)); -#33879 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#33880 = PCURVE('',#33244,#33881); -#33881 = DEFINITIONAL_REPRESENTATION('',(#33882),#33902); -#33882 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33883,#33884,#33885,#33886, - #33887,#33888,#33889,#33890,#33891,#33892,#33893,#33894,#33895, - #33896,#33897,#33898,#33899,#33900,#33901),.UNSPECIFIED.,.F.,.F.,(4, +#36253 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#36254 = CARTESIAN_POINT('',(-0.223601769609,0.782,-0.38180795677)); +#36255 = CARTESIAN_POINT('',(-0.223490857774,0.782,-0.386224759452)); +#36256 = CARTESIAN_POINT('',(-0.222532554281,0.782,-0.392705669639)); +#36257 = CARTESIAN_POINT('',(-0.220997693172,0.782,-0.398916003004)); +#36258 = CARTESIAN_POINT('',(-0.218819366141,0.782,-0.404838231514)); +#36259 = CARTESIAN_POINT('',(-0.216090279388,0.782,-0.410521100535)); +#36260 = CARTESIAN_POINT('',(-0.212646632142,0.782,-0.415860497384)); +#36261 = CARTESIAN_POINT('',(-0.208688373522,0.782,-0.42100732422)); +#36262 = CARTESIAN_POINT('',(-0.204051461642,0.782,-0.425753530638)); +#36263 = CARTESIAN_POINT('',(-0.198941664913,0.782,-0.430100596353)); +#36264 = CARTESIAN_POINT('',(-0.193406957627,0.782,-0.433969057892)); +#36265 = CARTESIAN_POINT('',(-0.187404988129,0.782,-0.437132518976)); +#36266 = CARTESIAN_POINT('',(-0.181035826347,0.782,-0.439777439017)); +#36267 = CARTESIAN_POINT('',(-0.174267979923,0.782,-0.44184813175)); +#36268 = CARTESIAN_POINT('',(-0.167077608856,0.782,-0.44325838886)); +#36269 = CARTESIAN_POINT('',(-0.159490060777,0.782,-0.444155417005)); +#36270 = CARTESIAN_POINT('',(-0.154290892639,0.782,-0.444272135288)); +#36271 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#36272 = PCURVE('',#35636,#36273); +#36273 = DEFINITIONAL_REPRESENTATION('',(#36274),#36294); +#36274 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36275,#36276,#36277,#36278, + #36279,#36280,#36281,#36282,#36283,#36284,#36285,#36286,#36287, + #36288,#36289,#36290,#36291,#36292,#36293),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.213137173661E-002, 0.121965824785,0.180570236649,0.238575970589,0.296000242091, 0.354358996444,0.413781228052,0.475097965352,0.537279897386, 0.598917953677,0.661235112979,0.724321980574,0.789217182509, 0.856396662088,0.926507768736,1.),.UNSPECIFIED.); -#33883 = CARTESIAN_POINT('',(-7.474191961075E-002,-2.482123712579E-003) - ); -#33884 = CARTESIAN_POINT('',(-7.699191062117E-002,-2.425623422887E-003) - ); -#33885 = CARTESIAN_POINT('',(-8.140871330353E-002,-2.314711588169E-003) - ); -#33886 = CARTESIAN_POINT('',(-8.788962349037E-002,-1.356408095422E-003) - ); -#33887 = CARTESIAN_POINT('',(-9.409995685511E-002,1.784530139252E-004)); -#33888 = CARTESIAN_POINT('',(-0.100022185365,2.356780044929E-003)); -#33889 = CARTESIAN_POINT('',(-0.105705054387,5.0858667976E-003)); -#33890 = CARTESIAN_POINT('',(-0.111044451235,8.529514044281E-003)); -#33891 = CARTESIAN_POINT('',(-0.116191278071,1.248777266427E-002)); -#33892 = CARTESIAN_POINT('',(-0.120937484489,1.712468454365E-002)); -#33893 = CARTESIAN_POINT('',(-0.125284550204,2.22344812732E-002)); -#33894 = CARTESIAN_POINT('',(-0.129153011743,2.776918855936E-002)); -#33895 = CARTESIAN_POINT('',(-0.132316472828,3.377115805728E-002)); -#33896 = CARTESIAN_POINT('',(-0.134961392869,4.014031983853E-002)); -#33897 = CARTESIAN_POINT('',(-0.137032085602,4.690816626274E-002)); -#33898 = CARTESIAN_POINT('',(-0.138442342711,5.409853732969E-002)); -#33899 = CARTESIAN_POINT('',(-0.139339370856,6.168608540844E-002)); -#33900 = CARTESIAN_POINT('',(-0.13945608914,6.68852535468E-002)); -#33901 = CARTESIAN_POINT('',(-0.139515822341,6.95460445337E-002)); -#33902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33903 = PCURVE('',#30566,#33904); -#33904 = DEFINITIONAL_REPRESENTATION('',(#33905),#33909); -#33905 = LINE('',#33906,#33907); -#33906 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33907 = VECTOR('',#33908,1.); -#33908 = DIRECTION('',(1.,0.E+000)); -#33909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33910 = ORIENTED_EDGE('',*,*,#33911,.F.); -#33911 = EDGE_CURVE('',#33543,#33857,#33912,.T.); -#33912 = SURFACE_CURVE('',#33913,(#33925,#33940),.PCURVE_S1.); -#33913 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33914,#33915,#33916,#33917, - #33918,#33919,#33920,#33921,#33922,#33923,#33924),.UNSPECIFIED.,.F., +#36275 = CARTESIAN_POINT('',(-7.474191961075E-002,-2.482123712579E-003) + ); +#36276 = CARTESIAN_POINT('',(-7.699191062117E-002,-2.425623422887E-003) + ); +#36277 = CARTESIAN_POINT('',(-8.140871330353E-002,-2.314711588169E-003) + ); +#36278 = CARTESIAN_POINT('',(-8.788962349037E-002,-1.356408095422E-003) + ); +#36279 = CARTESIAN_POINT('',(-9.409995685511E-002,1.784530139252E-004)); +#36280 = CARTESIAN_POINT('',(-0.100022185365,2.356780044929E-003)); +#36281 = CARTESIAN_POINT('',(-0.105705054387,5.0858667976E-003)); +#36282 = CARTESIAN_POINT('',(-0.111044451235,8.529514044281E-003)); +#36283 = CARTESIAN_POINT('',(-0.116191278071,1.248777266427E-002)); +#36284 = CARTESIAN_POINT('',(-0.120937484489,1.712468454365E-002)); +#36285 = CARTESIAN_POINT('',(-0.125284550204,2.22344812732E-002)); +#36286 = CARTESIAN_POINT('',(-0.129153011743,2.776918855936E-002)); +#36287 = CARTESIAN_POINT('',(-0.132316472828,3.377115805728E-002)); +#36288 = CARTESIAN_POINT('',(-0.134961392869,4.014031983853E-002)); +#36289 = CARTESIAN_POINT('',(-0.137032085602,4.690816626274E-002)); +#36290 = CARTESIAN_POINT('',(-0.138442342711,5.409853732969E-002)); +#36291 = CARTESIAN_POINT('',(-0.139339370856,6.168608540844E-002)); +#36292 = CARTESIAN_POINT('',(-0.13945608914,6.68852535468E-002)); +#36293 = CARTESIAN_POINT('',(-0.139515822341,6.95460445337E-002)); +#36294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36295 = PCURVE('',#32958,#36296); +#36296 = DEFINITIONAL_REPRESENTATION('',(#36297),#36301); +#36297 = LINE('',#36298,#36299); +#36298 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36299 = VECTOR('',#36300,1.); +#36300 = DIRECTION('',(1.,0.E+000)); +#36301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36302 = ORIENTED_EDGE('',*,*,#36303,.F.); +#36303 = EDGE_CURVE('',#35935,#36249,#36304,.T.); +#36304 = SURFACE_CURVE('',#36305,(#36317,#36332),.PCURVE_S1.); +#36305 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36306,#36307,#36308,#36309, + #36310,#36311,#36312,#36313,#36314,#36315,#36316),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.145359195055,0.278701778935, 0.403602234418,0.52166879118,0.637520693608,0.753704150763, 0.873212770364,1.),.UNSPECIFIED.); -#33914 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#33915 = CARTESIAN_POINT('',(-0.187887265347,0.782,-0.329588724812)); -#33916 = CARTESIAN_POINT('',(-0.193877404834,0.782,-0.331932101303)); -#33917 = CARTESIAN_POINT('',(-0.20195655867,0.782,-0.336621857279)); -#33918 = CARTESIAN_POINT('',(-0.208794270984,0.782,-0.342016803924)); -#33919 = CARTESIAN_POINT('',(-0.214306583707,0.782,-0.348247036847)); -#33920 = CARTESIAN_POINT('',(-0.218507968165,0.782,-0.355183760097)); -#33921 = CARTESIAN_POINT('',(-0.221533131079,0.782,-0.362738530708)); -#33922 = CARTESIAN_POINT('',(-0.223305022055,0.782,-0.37095343712)); -#33923 = CARTESIAN_POINT('',(-0.223538223405,0.782,-0.37663383328)); -#33924 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#33925 = PCURVE('',#33244,#33926); -#33926 = DEFINITIONAL_REPRESENTATION('',(#33927),#33939); -#33927 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33928,#33929,#33930,#33931, - #33932,#33933,#33934,#33935,#33936,#33937,#33938),.UNSPECIFIED.,.F., +#36306 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#36307 = CARTESIAN_POINT('',(-0.187887265347,0.782,-0.329588724812)); +#36308 = CARTESIAN_POINT('',(-0.193877404834,0.782,-0.331932101303)); +#36309 = CARTESIAN_POINT('',(-0.20195655867,0.782,-0.336621857279)); +#36310 = CARTESIAN_POINT('',(-0.208794270984,0.782,-0.342016803924)); +#36311 = CARTESIAN_POINT('',(-0.214306583707,0.782,-0.348247036847)); +#36312 = CARTESIAN_POINT('',(-0.218507968165,0.782,-0.355183760097)); +#36313 = CARTESIAN_POINT('',(-0.221533131079,0.782,-0.362738530708)); +#36314 = CARTESIAN_POINT('',(-0.223305022055,0.782,-0.37095343712)); +#36315 = CARTESIAN_POINT('',(-0.223538223405,0.782,-0.37663383328)); +#36316 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#36317 = PCURVE('',#35636,#36318); +#36318 = DEFINITIONAL_REPRESENTATION('',(#36319),#36331); +#36319 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36320,#36321,#36322,#36323, + #36324,#36325,#36326,#36327,#36328,#36329,#36330),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.145359195055,0.278701778935, 0.403602234418,0.52166879118,0.637520693608,0.753704150763, 0.873212770364,1.),.UNSPECIFIED.); -#33928 = CARTESIAN_POINT('',(-2.355047146429E-002,3.641308714041E-002)); -#33929 = CARTESIAN_POINT('',(-2.477267866307E-002,3.328888083855E-002)); -#33930 = CARTESIAN_POINT('',(-2.711605515464E-002,2.729874135164E-002)); -#33931 = CARTESIAN_POINT('',(-3.180581113024E-002,1.921958751543E-002)); -#33932 = CARTESIAN_POINT('',(-3.720075777497E-002,1.238187520167E-002)); -#33933 = CARTESIAN_POINT('',(-4.343099069815E-002,6.869562478914E-003)); -#33934 = CARTESIAN_POINT('',(-5.036771394868E-002,2.668178021088E-003)); -#33935 = CARTESIAN_POINT('',(-5.792248455907E-002,-3.569848931041E-004) - ); -#33936 = CARTESIAN_POINT('',(-6.613739097146E-002,-2.128875869203E-003) - ); -#33937 = CARTESIAN_POINT('',(-7.181778713121E-002,-2.362077218989E-003) - ); -#33938 = CARTESIAN_POINT('',(-7.474191961075E-002,-2.482123712579E-003) - ); -#33939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33940 = PCURVE('',#30488,#33941); -#33941 = DEFINITIONAL_REPRESENTATION('',(#33942),#33946); -#33942 = LINE('',#33943,#33944); -#33943 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#33944 = VECTOR('',#33945,1.); -#33945 = DIRECTION('',(1.,0.E+000)); -#33946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33947 = FACE_BOUND('',#33948,.T.); -#33948 = EDGE_LOOP('',(#33949,#34029,#34123,#34217)); -#33949 = ORIENTED_EDGE('',*,*,#33950,.F.); -#33950 = EDGE_CURVE('',#33951,#33953,#33955,.T.); -#33951 = VERTEX_POINT('',#33952); -#33952 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#33953 = VERTEX_POINT('',#33954); -#33954 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#33955 = SURFACE_CURVE('',#33956,(#33972,#33991),.PCURVE_S1.); -#33956 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33957,#33958,#33959,#33960, - #33961,#33962,#33963,#33964,#33965,#33966,#33967,#33968,#33969, - #33970,#33971),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#36320 = CARTESIAN_POINT('',(-2.355047146429E-002,3.641308714041E-002)); +#36321 = CARTESIAN_POINT('',(-2.477267866307E-002,3.328888083855E-002)); +#36322 = CARTESIAN_POINT('',(-2.711605515464E-002,2.729874135164E-002)); +#36323 = CARTESIAN_POINT('',(-3.180581113024E-002,1.921958751543E-002)); +#36324 = CARTESIAN_POINT('',(-3.720075777497E-002,1.238187520167E-002)); +#36325 = CARTESIAN_POINT('',(-4.343099069815E-002,6.869562478914E-003)); +#36326 = CARTESIAN_POINT('',(-5.036771394868E-002,2.668178021088E-003)); +#36327 = CARTESIAN_POINT('',(-5.792248455907E-002,-3.569848931041E-004) + ); +#36328 = CARTESIAN_POINT('',(-6.613739097146E-002,-2.128875869203E-003) + ); +#36329 = CARTESIAN_POINT('',(-7.181778713121E-002,-2.362077218989E-003) + ); +#36330 = CARTESIAN_POINT('',(-7.474191961075E-002,-2.482123712579E-003) + ); +#36331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36332 = PCURVE('',#32880,#36333); +#36333 = DEFINITIONAL_REPRESENTATION('',(#36334),#36338); +#36334 = LINE('',#36335,#36336); +#36335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36336 = VECTOR('',#36337,1.); +#36337 = DIRECTION('',(1.,0.E+000)); +#36338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36339 = FACE_BOUND('',#36340,.T.); +#36340 = EDGE_LOOP('',(#36341,#36421,#36515,#36609)); +#36341 = ORIENTED_EDGE('',*,*,#36342,.F.); +#36342 = EDGE_CURVE('',#36343,#36345,#36347,.T.); +#36343 = VERTEX_POINT('',#36344); +#36344 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#36345 = VERTEX_POINT('',#36346); +#36346 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#36347 = SURFACE_CURVE('',#36348,(#36364,#36383),.PCURVE_S1.); +#36348 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36349,#36350,#36351,#36352, + #36353,#36354,#36355,#36356,#36357,#36358,#36359,#36360,#36361, + #36362,#36363),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.982327127979E-002,0.159856811666,0.239732702115, 0.321364602325,0.402583696349,0.483265588546,0.566017011661, 0.65307135966,0.741855686507,0.828590905074,0.914280745201,1.), .UNSPECIFIED.); -#33957 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#33958 = CARTESIAN_POINT('',(-0.200552317567,0.782,-0.26163417388)); -#33959 = CARTESIAN_POINT('',(-0.200438290596,0.782,-0.257403034255)); -#33960 = CARTESIAN_POINT('',(-0.199438028632,0.782,-0.251118895293)); -#33961 = CARTESIAN_POINT('',(-0.197740791267,0.782,-0.244951778484)); -#33962 = CARTESIAN_POINT('',(-0.195565486121,0.782,-0.238895858564)); -#33963 = CARTESIAN_POINT('',(-0.192497082943,0.782,-0.233195563055)); -#33964 = CARTESIAN_POINT('',(-0.188428035233,0.782,-0.228107629908)); -#33965 = CARTESIAN_POINT('',(-0.183322142487,0.782,-0.223830002489)); -#33966 = CARTESIAN_POINT('',(-0.177490933776,0.782,-0.220216100506)); -#33967 = CARTESIAN_POINT('',(-0.171127585823,0.782,-0.217371648834)); -#33968 = CARTESIAN_POINT('',(-0.164496791189,0.782,-0.215386124915)); -#33969 = CARTESIAN_POINT('',(-0.157769687252,0.782,-0.214074189816)); -#33970 = CARTESIAN_POINT('',(-0.153231001145,0.782,-0.213919225537)); -#33971 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#33972 = PCURVE('',#33244,#33973); -#33973 = DEFINITIONAL_REPRESENTATION('',(#33974),#33990); -#33974 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#33975,#33976,#33977,#33978, - #33979,#33980,#33981,#33982,#33983,#33984,#33985,#33986,#33987, - #33988,#33989),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#36349 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#36350 = CARTESIAN_POINT('',(-0.200552317567,0.782,-0.26163417388)); +#36351 = CARTESIAN_POINT('',(-0.200438290596,0.782,-0.257403034255)); +#36352 = CARTESIAN_POINT('',(-0.199438028632,0.782,-0.251118895293)); +#36353 = CARTESIAN_POINT('',(-0.197740791267,0.782,-0.244951778484)); +#36354 = CARTESIAN_POINT('',(-0.195565486121,0.782,-0.238895858564)); +#36355 = CARTESIAN_POINT('',(-0.192497082943,0.782,-0.233195563055)); +#36356 = CARTESIAN_POINT('',(-0.188428035233,0.782,-0.228107629908)); +#36357 = CARTESIAN_POINT('',(-0.183322142487,0.782,-0.223830002489)); +#36358 = CARTESIAN_POINT('',(-0.177490933776,0.782,-0.220216100506)); +#36359 = CARTESIAN_POINT('',(-0.171127585823,0.782,-0.217371648834)); +#36360 = CARTESIAN_POINT('',(-0.164496791189,0.782,-0.215386124915)); +#36361 = CARTESIAN_POINT('',(-0.157769687252,0.782,-0.214074189816)); +#36362 = CARTESIAN_POINT('',(-0.153231001145,0.782,-0.213919225537)); +#36363 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#36364 = PCURVE('',#35636,#36365); +#36365 = DEFINITIONAL_REPRESENTATION('',(#36366),#36382); +#36366 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36367,#36368,#36369,#36370, + #36371,#36372,#36373,#36374,#36375,#36376,#36377,#36378,#36379, + #36380,#36381),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.982327127979E-002,0.159856811666,0.239732702115, 0.321364602325,0.402583696349,0.483265588546,0.566017011661, 0.65307135966,0.741855686507,0.828590905074,0.914280745201,1.), .UNSPECIFIED.); -#33975 = CARTESIAN_POINT('',(4.106908519095E-002,2.056689012623E-002)); -#33976 = CARTESIAN_POINT('',(4.318187226923E-002,2.062382861872E-002)); -#33977 = CARTESIAN_POINT('',(4.741301189366E-002,2.073785559011E-002)); -#33978 = CARTESIAN_POINT('',(5.369715085598E-002,2.173811755409E-002)); -#33979 = CARTESIAN_POINT('',(5.986426766469E-002,2.343535491853E-002)); -#33980 = CARTESIAN_POINT('',(6.592018758527E-002,2.561066006454E-002)); -#33981 = CARTESIAN_POINT('',(7.162048309397E-002,2.867906324338E-002)); -#33982 = CARTESIAN_POINT('',(7.6708416241E-002,3.274811095303E-002)); -#33983 = CARTESIAN_POINT('',(8.098604365975E-002,3.785400369928E-002)); -#33984 = CARTESIAN_POINT('',(8.459994564282E-002,4.368521241031E-002)); -#33985 = CARTESIAN_POINT('',(8.74443973147E-002,5.004856036291E-002)); -#33986 = CARTESIAN_POINT('',(8.942992123417E-002,5.667935499672E-002)); -#33987 = CARTESIAN_POINT('',(9.074185633249E-002,6.34064589344E-002)); -#33988 = CARTESIAN_POINT('',(9.089682061147E-002,6.794514504063E-002)); -#33989 = CARTESIAN_POINT('',(9.097431604729E-002,7.021487752456E-002)); -#33990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#33991 = PCURVE('',#33992,#34023); -#33992 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#33993,#33994) - ,(#33995,#33996) - ,(#33997,#33998) - ,(#33999,#34000) - ,(#34001,#34002) - ,(#34003,#34004) - ,(#34005,#34006) - ,(#34007,#34008) - ,(#34009,#34010) - ,(#34011,#34012) - ,(#34013,#34014) - ,(#34015,#34016) - ,(#34017,#34018) - ,(#34019,#34020) - ,(#34021,#34022 +#36367 = CARTESIAN_POINT('',(4.106908519095E-002,2.056689012623E-002)); +#36368 = CARTESIAN_POINT('',(4.318187226923E-002,2.062382861872E-002)); +#36369 = CARTESIAN_POINT('',(4.741301189366E-002,2.073785559011E-002)); +#36370 = CARTESIAN_POINT('',(5.369715085598E-002,2.173811755409E-002)); +#36371 = CARTESIAN_POINT('',(5.986426766469E-002,2.343535491853E-002)); +#36372 = CARTESIAN_POINT('',(6.592018758527E-002,2.561066006454E-002)); +#36373 = CARTESIAN_POINT('',(7.162048309397E-002,2.867906324338E-002)); +#36374 = CARTESIAN_POINT('',(7.6708416241E-002,3.274811095303E-002)); +#36375 = CARTESIAN_POINT('',(8.098604365975E-002,3.785400369928E-002)); +#36376 = CARTESIAN_POINT('',(8.459994564282E-002,4.368521241031E-002)); +#36377 = CARTESIAN_POINT('',(8.74443973147E-002,5.004856036291E-002)); +#36378 = CARTESIAN_POINT('',(8.942992123417E-002,5.667935499672E-002)); +#36379 = CARTESIAN_POINT('',(9.074185633249E-002,6.34064589344E-002)); +#36380 = CARTESIAN_POINT('',(9.089682061147E-002,6.794514504063E-002)); +#36381 = CARTESIAN_POINT('',(9.097431604729E-002,7.021487752456E-002)); +#36382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36383 = PCURVE('',#36384,#36415); +#36384 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#36385,#36386) + ,(#36387,#36388) + ,(#36389,#36390) + ,(#36391,#36392) + ,(#36393,#36394) + ,(#36395,#36396) + ,(#36397,#36398) + ,(#36399,#36400) + ,(#36401,#36402) + ,(#36403,#36404) + ,(#36405,#36406) + ,(#36407,#36408) + ,(#36409,#36410) + ,(#36411,#36412) + ,(#36413,#36414 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),(2,2),( 0.E+000,7.982327127979E-002,0.159856811666,0.239732702115, 0.321364602325,0.402583696349,0.483265588546,0.566017011661, 0.65307135966,0.741855686507,0.828590905074,0.914280745201,1.),( 0.E+000,1.),.UNSPECIFIED.); -#33993 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#33994 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); -#33995 = CARTESIAN_POINT('',(-0.200552317567,0.782,-0.26163417388)); -#33996 = CARTESIAN_POINT('',(-0.200552317567,0.78,-0.26163417388)); -#33997 = CARTESIAN_POINT('',(-0.200438290596,0.782,-0.257403034255)); -#33998 = CARTESIAN_POINT('',(-0.200438290596,0.78,-0.257403034255)); -#33999 = CARTESIAN_POINT('',(-0.199438028632,0.782,-0.251118895293)); -#34000 = CARTESIAN_POINT('',(-0.199438028632,0.78,-0.251118895293)); -#34001 = CARTESIAN_POINT('',(-0.197740791267,0.782,-0.244951778484)); -#34002 = CARTESIAN_POINT('',(-0.197740791267,0.78,-0.244951778484)); -#34003 = CARTESIAN_POINT('',(-0.195565486121,0.782,-0.238895858564)); -#34004 = CARTESIAN_POINT('',(-0.195565486121,0.78,-0.238895858564)); -#34005 = CARTESIAN_POINT('',(-0.192497082943,0.782,-0.233195563055)); -#34006 = CARTESIAN_POINT('',(-0.192497082943,0.78,-0.233195563055)); -#34007 = CARTESIAN_POINT('',(-0.188428035233,0.782,-0.228107629908)); -#34008 = CARTESIAN_POINT('',(-0.188428035233,0.78,-0.228107629908)); -#34009 = CARTESIAN_POINT('',(-0.183322142487,0.782,-0.223830002489)); -#34010 = CARTESIAN_POINT('',(-0.183322142487,0.78,-0.223830002489)); -#34011 = CARTESIAN_POINT('',(-0.177490933776,0.782,-0.220216100506)); -#34012 = CARTESIAN_POINT('',(-0.177490933776,0.78,-0.220216100506)); -#34013 = CARTESIAN_POINT('',(-0.171127585823,0.782,-0.217371648834)); -#34014 = CARTESIAN_POINT('',(-0.171127585823,0.78,-0.217371648834)); -#34015 = CARTESIAN_POINT('',(-0.164496791189,0.782,-0.215386124915)); -#34016 = CARTESIAN_POINT('',(-0.164496791189,0.78,-0.215386124915)); -#34017 = CARTESIAN_POINT('',(-0.157769687252,0.782,-0.214074189816)); -#34018 = CARTESIAN_POINT('',(-0.157769687252,0.78,-0.214074189816)); -#34019 = CARTESIAN_POINT('',(-0.153231001145,0.782,-0.213919225537)); -#34020 = CARTESIAN_POINT('',(-0.153231001145,0.78,-0.213919225537)); -#34021 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#34022 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); -#34023 = DEFINITIONAL_REPRESENTATION('',(#34024),#34028); -#34024 = LINE('',#34025,#34026); -#34025 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34026 = VECTOR('',#34027,1.); -#34027 = DIRECTION('',(1.,0.E+000)); -#34028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34029 = ORIENTED_EDGE('',*,*,#34030,.F.); -#34030 = EDGE_CURVE('',#34031,#33951,#34033,.T.); -#34031 = VERTEX_POINT('',#34032); -#34032 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34033 = SURFACE_CURVE('',#34034,(#34054,#34077),.PCURVE_S1.); -#34034 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34035,#34036,#34037,#34038, - #34039,#34040,#34041,#34042,#34043,#34044,#34045,#34046,#34047, - #34048,#34049,#34050,#34051,#34052,#34053),.UNSPECIFIED.,.F.,.F.,(4, +#36385 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#36386 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); +#36387 = CARTESIAN_POINT('',(-0.200552317567,0.782,-0.26163417388)); +#36388 = CARTESIAN_POINT('',(-0.200552317567,0.78,-0.26163417388)); +#36389 = CARTESIAN_POINT('',(-0.200438290596,0.782,-0.257403034255)); +#36390 = CARTESIAN_POINT('',(-0.200438290596,0.78,-0.257403034255)); +#36391 = CARTESIAN_POINT('',(-0.199438028632,0.782,-0.251118895293)); +#36392 = CARTESIAN_POINT('',(-0.199438028632,0.78,-0.251118895293)); +#36393 = CARTESIAN_POINT('',(-0.197740791267,0.782,-0.244951778484)); +#36394 = CARTESIAN_POINT('',(-0.197740791267,0.78,-0.244951778484)); +#36395 = CARTESIAN_POINT('',(-0.195565486121,0.782,-0.238895858564)); +#36396 = CARTESIAN_POINT('',(-0.195565486121,0.78,-0.238895858564)); +#36397 = CARTESIAN_POINT('',(-0.192497082943,0.782,-0.233195563055)); +#36398 = CARTESIAN_POINT('',(-0.192497082943,0.78,-0.233195563055)); +#36399 = CARTESIAN_POINT('',(-0.188428035233,0.782,-0.228107629908)); +#36400 = CARTESIAN_POINT('',(-0.188428035233,0.78,-0.228107629908)); +#36401 = CARTESIAN_POINT('',(-0.183322142487,0.782,-0.223830002489)); +#36402 = CARTESIAN_POINT('',(-0.183322142487,0.78,-0.223830002489)); +#36403 = CARTESIAN_POINT('',(-0.177490933776,0.782,-0.220216100506)); +#36404 = CARTESIAN_POINT('',(-0.177490933776,0.78,-0.220216100506)); +#36405 = CARTESIAN_POINT('',(-0.171127585823,0.782,-0.217371648834)); +#36406 = CARTESIAN_POINT('',(-0.171127585823,0.78,-0.217371648834)); +#36407 = CARTESIAN_POINT('',(-0.164496791189,0.782,-0.215386124915)); +#36408 = CARTESIAN_POINT('',(-0.164496791189,0.78,-0.215386124915)); +#36409 = CARTESIAN_POINT('',(-0.157769687252,0.782,-0.214074189816)); +#36410 = CARTESIAN_POINT('',(-0.157769687252,0.78,-0.214074189816)); +#36411 = CARTESIAN_POINT('',(-0.153231001145,0.782,-0.213919225537)); +#36412 = CARTESIAN_POINT('',(-0.153231001145,0.78,-0.213919225537)); +#36413 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#36414 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); +#36415 = DEFINITIONAL_REPRESENTATION('',(#36416),#36420); +#36416 = LINE('',#36417,#36418); +#36417 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36418 = VECTOR('',#36419,1.); +#36419 = DIRECTION('',(1.,0.E+000)); +#36420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36421 = ORIENTED_EDGE('',*,*,#36422,.F.); +#36422 = EDGE_CURVE('',#36423,#36343,#36425,.T.); +#36423 = VERTEX_POINT('',#36424); +#36424 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#36425 = SURFACE_CURVE('',#36426,(#36446,#36469),.PCURVE_S1.); +#36426 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36427,#36428,#36429,#36430, + #36431,#36432,#36433,#36434,#36435,#36436,#36437,#36438,#36439, + #36440,#36441,#36442,#36443,#36444,#36445),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.095246541543E-002, 0.139088927142,0.203559823919,0.26642378113,0.327516566198, 0.387860871761,0.447898785011,0.508818828589,0.569482456819, 0.629035711667,0.688378458553,0.748067961558,0.808630169751, 0.870231145607,0.933682580472,1.),.UNSPECIFIED.); -#34035 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34036 = CARTESIAN_POINT('',(-0.153776102454,0.782,-0.312590019051)); -#34037 = CARTESIAN_POINT('',(-0.157377799559,0.782,-0.312524938806)); -#34038 = CARTESIAN_POINT('',(-0.162610069873,0.782,-0.311832429033)); -#34039 = CARTESIAN_POINT('',(-0.167563422339,0.782,-0.310768963702)); -#34040 = CARTESIAN_POINT('',(-0.172194277152,0.782,-0.309212440623)); -#34041 = CARTESIAN_POINT('',(-0.17656053432,0.782,-0.30726740685)); -#34042 = CARTESIAN_POINT('',(-0.180582336475,0.782,-0.304821666067)); -#34043 = CARTESIAN_POINT('',(-0.184331432281,0.782,-0.30198285888)); -#34044 = CARTESIAN_POINT('',(-0.187693300282,0.782,-0.298683285504)); -#34045 = CARTESIAN_POINT('',(-0.190726576438,0.782,-0.295099051732)); -#34046 = CARTESIAN_POINT('',(-0.193349168521,0.782,-0.291256764141)); -#34047 = CARTESIAN_POINT('',(-0.195665962824,0.782,-0.287245552298)); -#34048 = CARTESIAN_POINT('',(-0.197424129085,0.782,-0.282933793713)); -#34049 = CARTESIAN_POINT('',(-0.198912259431,0.782,-0.278460879664)); -#34050 = CARTESIAN_POINT('',(-0.199842576285,0.782,-0.273739995734)); -#34051 = CARTESIAN_POINT('',(-0.200503915316,0.782,-0.268824779437)); -#34052 = CARTESIAN_POINT('',(-0.200573629261,0.782,-0.265464306143)); -#34053 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#34054 = PCURVE('',#33244,#34055); -#34055 = DEFINITIONAL_REPRESENTATION('',(#34056),#34076); -#34056 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34057,#34058,#34059,#34060, - #34061,#34062,#34063,#34064,#34065,#34066,#34067,#34068,#34069, - #34070,#34071,#34072,#34073,#34074,#34075),.UNSPECIFIED.,.F.,.F.,(4, +#36427 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#36428 = CARTESIAN_POINT('',(-0.153776102454,0.782,-0.312590019051)); +#36429 = CARTESIAN_POINT('',(-0.157377799559,0.782,-0.312524938806)); +#36430 = CARTESIAN_POINT('',(-0.162610069873,0.782,-0.311832429033)); +#36431 = CARTESIAN_POINT('',(-0.167563422339,0.782,-0.310768963702)); +#36432 = CARTESIAN_POINT('',(-0.172194277152,0.782,-0.309212440623)); +#36433 = CARTESIAN_POINT('',(-0.17656053432,0.782,-0.30726740685)); +#36434 = CARTESIAN_POINT('',(-0.180582336475,0.782,-0.304821666067)); +#36435 = CARTESIAN_POINT('',(-0.184331432281,0.782,-0.30198285888)); +#36436 = CARTESIAN_POINT('',(-0.187693300282,0.782,-0.298683285504)); +#36437 = CARTESIAN_POINT('',(-0.190726576438,0.782,-0.295099051732)); +#36438 = CARTESIAN_POINT('',(-0.193349168521,0.782,-0.291256764141)); +#36439 = CARTESIAN_POINT('',(-0.195665962824,0.782,-0.287245552298)); +#36440 = CARTESIAN_POINT('',(-0.197424129085,0.782,-0.282933793713)); +#36441 = CARTESIAN_POINT('',(-0.198912259431,0.782,-0.278460879664)); +#36442 = CARTESIAN_POINT('',(-0.199842576285,0.782,-0.273739995734)); +#36443 = CARTESIAN_POINT('',(-0.200503915316,0.782,-0.268824779437)); +#36444 = CARTESIAN_POINT('',(-0.200573629261,0.782,-0.265464306143)); +#36445 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#36446 = PCURVE('',#35636,#36447); +#36447 = DEFINITIONAL_REPRESENTATION('',(#36448),#36468); +#36448 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36449,#36450,#36451,#36452, + #36453,#36454,#36455,#36456,#36457,#36458,#36459,#36460,#36461, + #36462,#36463,#36464,#36465,#36466,#36467),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.095246541543E-002, 0.139088927142,0.203559823919,0.26642378113,0.327516566198, 0.387860871761,0.447898785011,0.508818828589,0.569482456819, 0.629035711667,0.688378458553,0.748067961558,0.808630169751, 0.870231145607,0.933682580472,1.),.UNSPECIFIED.); -#34057 = CARTESIAN_POINT('',(-7.807171833314E-003,6.923735238407E-002)); -#34058 = CARTESIAN_POINT('',(-7.773972901754E-003,6.740004373171E-002)); -#34059 = CARTESIAN_POINT('',(-7.708892657596E-003,6.379834662664E-002)); -#34060 = CARTESIAN_POINT('',(-7.016382884371E-003,5.856607631315E-002)); -#34061 = CARTESIAN_POINT('',(-5.95291755304E-003,5.361272384708E-002)); -#34062 = CARTESIAN_POINT('',(-4.396394474066E-003,4.898186903394E-002)); -#34063 = CARTESIAN_POINT('',(-2.451360701612E-003,4.461561186544E-002)); -#34064 = CARTESIAN_POINT('',(-5.619918451161E-006,4.05938097114E-002)); -#34065 = CARTESIAN_POINT('',(2.833187268883E-003,3.684471390483E-002)); -#34066 = CARTESIAN_POINT('',(6.132760645276E-003,3.348284590439E-002)); -#34067 = CARTESIAN_POINT('',(9.716994417118E-003,3.044956974799E-002)); -#34068 = CARTESIAN_POINT('',(1.35592820073E-002,2.782697766515E-002)); -#34069 = CARTESIAN_POINT('',(1.75704938508E-002,2.551018336155E-002)); -#34070 = CARTESIAN_POINT('',(2.188225243584E-002,2.375201710053E-002)); -#34071 = CARTESIAN_POINT('',(2.635516648441E-002,2.226388675513E-002)); -#34072 = CARTESIAN_POINT('',(3.107605041513E-002,2.133356990131E-002)); -#34073 = CARTESIAN_POINT('',(3.599126671222E-002,2.067223086968E-002)); -#34074 = CARTESIAN_POINT('',(3.935174000606E-002,2.060251692528E-002)); -#34075 = CARTESIAN_POINT('',(4.106908519095E-002,2.056689012623E-002)); -#34076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34077 = PCURVE('',#34078,#34117); -#34078 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#34079,#34080) - ,(#34081,#34082) - ,(#34083,#34084) - ,(#34085,#34086) - ,(#34087,#34088) - ,(#34089,#34090) - ,(#34091,#34092) - ,(#34093,#34094) - ,(#34095,#34096) - ,(#34097,#34098) - ,(#34099,#34100) - ,(#34101,#34102) - ,(#34103,#34104) - ,(#34105,#34106) - ,(#34107,#34108) - ,(#34109,#34110) - ,(#34111,#34112) - ,(#34113,#34114) - ,(#34115,#34116 +#36449 = CARTESIAN_POINT('',(-7.807171833314E-003,6.923735238407E-002)); +#36450 = CARTESIAN_POINT('',(-7.773972901754E-003,6.740004373171E-002)); +#36451 = CARTESIAN_POINT('',(-7.708892657596E-003,6.379834662664E-002)); +#36452 = CARTESIAN_POINT('',(-7.016382884371E-003,5.856607631315E-002)); +#36453 = CARTESIAN_POINT('',(-5.95291755304E-003,5.361272384708E-002)); +#36454 = CARTESIAN_POINT('',(-4.396394474066E-003,4.898186903394E-002)); +#36455 = CARTESIAN_POINT('',(-2.451360701612E-003,4.461561186544E-002)); +#36456 = CARTESIAN_POINT('',(-5.619918451161E-006,4.05938097114E-002)); +#36457 = CARTESIAN_POINT('',(2.833187268883E-003,3.684471390483E-002)); +#36458 = CARTESIAN_POINT('',(6.132760645276E-003,3.348284590439E-002)); +#36459 = CARTESIAN_POINT('',(9.716994417118E-003,3.044956974799E-002)); +#36460 = CARTESIAN_POINT('',(1.35592820073E-002,2.782697766515E-002)); +#36461 = CARTESIAN_POINT('',(1.75704938508E-002,2.551018336155E-002)); +#36462 = CARTESIAN_POINT('',(2.188225243584E-002,2.375201710053E-002)); +#36463 = CARTESIAN_POINT('',(2.635516648441E-002,2.226388675513E-002)); +#36464 = CARTESIAN_POINT('',(3.107605041513E-002,2.133356990131E-002)); +#36465 = CARTESIAN_POINT('',(3.599126671222E-002,2.067223086968E-002)); +#36466 = CARTESIAN_POINT('',(3.935174000606E-002,2.060251692528E-002)); +#36467 = CARTESIAN_POINT('',(4.106908519095E-002,2.056689012623E-002)); +#36468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36469 = PCURVE('',#36470,#36509); +#36470 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#36471,#36472) + ,(#36473,#36474) + ,(#36475,#36476) + ,(#36477,#36478) + ,(#36479,#36480) + ,(#36481,#36482) + ,(#36483,#36484) + ,(#36485,#36486) + ,(#36487,#36488) + ,(#36489,#36490) + ,(#36491,#36492) + ,(#36493,#36494) + ,(#36495,#36496) + ,(#36497,#36498) + ,(#36499,#36500) + ,(#36501,#36502) + ,(#36503,#36504) + ,(#36505,#36506) + ,(#36507,#36508 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.095246541543E-002,0.139088927142,0.203559823919, 0.26642378113,0.327516566198,0.387860871761,0.447898785011, 0.508818828589,0.569482456819,0.629035711667,0.688378458553, 0.748067961558,0.808630169751,0.870231145607,0.933682580472,1.),( 0.E+000,1.),.UNSPECIFIED.); -#34079 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34080 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); -#34081 = CARTESIAN_POINT('',(-0.153776102454,0.782,-0.312590019051)); -#34082 = CARTESIAN_POINT('',(-0.153776102454,0.78,-0.312590019051)); -#34083 = CARTESIAN_POINT('',(-0.157377799559,0.782,-0.312524938806)); -#34084 = CARTESIAN_POINT('',(-0.157377799559,0.78,-0.312524938806)); -#34085 = CARTESIAN_POINT('',(-0.162610069873,0.782,-0.311832429033)); -#34086 = CARTESIAN_POINT('',(-0.162610069873,0.78,-0.311832429033)); -#34087 = CARTESIAN_POINT('',(-0.167563422339,0.782,-0.310768963702)); -#34088 = CARTESIAN_POINT('',(-0.167563422339,0.78,-0.310768963702)); -#34089 = CARTESIAN_POINT('',(-0.172194277152,0.782,-0.309212440623)); -#34090 = CARTESIAN_POINT('',(-0.172194277152,0.78,-0.309212440623)); -#34091 = CARTESIAN_POINT('',(-0.17656053432,0.782,-0.30726740685)); -#34092 = CARTESIAN_POINT('',(-0.17656053432,0.78,-0.30726740685)); -#34093 = CARTESIAN_POINT('',(-0.180582336475,0.782,-0.304821666067)); -#34094 = CARTESIAN_POINT('',(-0.180582336475,0.78,-0.304821666067)); -#34095 = CARTESIAN_POINT('',(-0.184331432281,0.782,-0.30198285888)); -#34096 = CARTESIAN_POINT('',(-0.184331432281,0.78,-0.30198285888)); -#34097 = CARTESIAN_POINT('',(-0.187693300282,0.782,-0.298683285504)); -#34098 = CARTESIAN_POINT('',(-0.187693300282,0.78,-0.298683285504)); -#34099 = CARTESIAN_POINT('',(-0.190726576438,0.782,-0.295099051732)); -#34100 = CARTESIAN_POINT('',(-0.190726576438,0.78,-0.295099051732)); -#34101 = CARTESIAN_POINT('',(-0.193349168521,0.782,-0.291256764141)); -#34102 = CARTESIAN_POINT('',(-0.193349168521,0.78,-0.291256764141)); -#34103 = CARTESIAN_POINT('',(-0.195665962824,0.782,-0.287245552298)); -#34104 = CARTESIAN_POINT('',(-0.195665962824,0.78,-0.287245552298)); -#34105 = CARTESIAN_POINT('',(-0.197424129085,0.782,-0.282933793713)); -#34106 = CARTESIAN_POINT('',(-0.197424129085,0.78,-0.282933793713)); -#34107 = CARTESIAN_POINT('',(-0.198912259431,0.782,-0.278460879664)); -#34108 = CARTESIAN_POINT('',(-0.198912259431,0.78,-0.278460879664)); -#34109 = CARTESIAN_POINT('',(-0.199842576285,0.782,-0.273739995734)); -#34110 = CARTESIAN_POINT('',(-0.199842576285,0.78,-0.273739995734)); -#34111 = CARTESIAN_POINT('',(-0.200503915316,0.782,-0.268824779437)); -#34112 = CARTESIAN_POINT('',(-0.200503915316,0.78,-0.268824779437)); -#34113 = CARTESIAN_POINT('',(-0.200573629261,0.782,-0.265464306143)); -#34114 = CARTESIAN_POINT('',(-0.200573629261,0.78,-0.265464306143)); -#34115 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#34116 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); -#34117 = DEFINITIONAL_REPRESENTATION('',(#34118),#34122); -#34118 = LINE('',#34119,#34120); -#34119 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34120 = VECTOR('',#34121,1.); -#34121 = DIRECTION('',(1.,0.E+000)); -#34122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34123 = ORIENTED_EDGE('',*,*,#34124,.F.); -#34124 = EDGE_CURVE('',#34125,#34031,#34127,.T.); -#34125 = VERTEX_POINT('',#34126); -#34126 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#34127 = SURFACE_CURVE('',#34128,(#34148,#34171),.PCURVE_S1.); -#34128 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34129,#34130,#34131,#34132, - #34133,#34134,#34135,#34136,#34137,#34138,#34139,#34140,#34141, - #34142,#34143,#34144,#34145,#34146,#34147),.UNSPECIFIED.,.F.,.F.,(4, +#36471 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#36472 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); +#36473 = CARTESIAN_POINT('',(-0.153776102454,0.782,-0.312590019051)); +#36474 = CARTESIAN_POINT('',(-0.153776102454,0.78,-0.312590019051)); +#36475 = CARTESIAN_POINT('',(-0.157377799559,0.782,-0.312524938806)); +#36476 = CARTESIAN_POINT('',(-0.157377799559,0.78,-0.312524938806)); +#36477 = CARTESIAN_POINT('',(-0.162610069873,0.782,-0.311832429033)); +#36478 = CARTESIAN_POINT('',(-0.162610069873,0.78,-0.311832429033)); +#36479 = CARTESIAN_POINT('',(-0.167563422339,0.782,-0.310768963702)); +#36480 = CARTESIAN_POINT('',(-0.167563422339,0.78,-0.310768963702)); +#36481 = CARTESIAN_POINT('',(-0.172194277152,0.782,-0.309212440623)); +#36482 = CARTESIAN_POINT('',(-0.172194277152,0.78,-0.309212440623)); +#36483 = CARTESIAN_POINT('',(-0.17656053432,0.782,-0.30726740685)); +#36484 = CARTESIAN_POINT('',(-0.17656053432,0.78,-0.30726740685)); +#36485 = CARTESIAN_POINT('',(-0.180582336475,0.782,-0.304821666067)); +#36486 = CARTESIAN_POINT('',(-0.180582336475,0.78,-0.304821666067)); +#36487 = CARTESIAN_POINT('',(-0.184331432281,0.782,-0.30198285888)); +#36488 = CARTESIAN_POINT('',(-0.184331432281,0.78,-0.30198285888)); +#36489 = CARTESIAN_POINT('',(-0.187693300282,0.782,-0.298683285504)); +#36490 = CARTESIAN_POINT('',(-0.187693300282,0.78,-0.298683285504)); +#36491 = CARTESIAN_POINT('',(-0.190726576438,0.782,-0.295099051732)); +#36492 = CARTESIAN_POINT('',(-0.190726576438,0.78,-0.295099051732)); +#36493 = CARTESIAN_POINT('',(-0.193349168521,0.782,-0.291256764141)); +#36494 = CARTESIAN_POINT('',(-0.193349168521,0.78,-0.291256764141)); +#36495 = CARTESIAN_POINT('',(-0.195665962824,0.782,-0.287245552298)); +#36496 = CARTESIAN_POINT('',(-0.195665962824,0.78,-0.287245552298)); +#36497 = CARTESIAN_POINT('',(-0.197424129085,0.782,-0.282933793713)); +#36498 = CARTESIAN_POINT('',(-0.197424129085,0.78,-0.282933793713)); +#36499 = CARTESIAN_POINT('',(-0.198912259431,0.782,-0.278460879664)); +#36500 = CARTESIAN_POINT('',(-0.198912259431,0.78,-0.278460879664)); +#36501 = CARTESIAN_POINT('',(-0.199842576285,0.782,-0.273739995734)); +#36502 = CARTESIAN_POINT('',(-0.199842576285,0.78,-0.273739995734)); +#36503 = CARTESIAN_POINT('',(-0.200503915316,0.782,-0.268824779437)); +#36504 = CARTESIAN_POINT('',(-0.200503915316,0.78,-0.268824779437)); +#36505 = CARTESIAN_POINT('',(-0.200573629261,0.782,-0.265464306143)); +#36506 = CARTESIAN_POINT('',(-0.200573629261,0.78,-0.265464306143)); +#36507 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#36508 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); +#36509 = DEFINITIONAL_REPRESENTATION('',(#36510),#36514); +#36510 = LINE('',#36511,#36512); +#36511 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36512 = VECTOR('',#36513,1.); +#36513 = DIRECTION('',(1.,0.E+000)); +#36514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36515 = ORIENTED_EDGE('',*,*,#36516,.F.); +#36516 = EDGE_CURVE('',#36517,#36423,#36519,.T.); +#36517 = VERTEX_POINT('',#36518); +#36518 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#36519 = SURFACE_CURVE('',#36520,(#36540,#36563),.PCURVE_S1.); +#36520 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36521,#36522,#36523,#36524, + #36525,#36526,#36527,#36528,#36529,#36530,#36531,#36532,#36533, + #36534,#36535,#36536,#36537,#36538,#36539),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.661618043518E-002, 0.130423869924,0.19267095757,0.252968504796,0.312880382806, 0.372200255918,0.431927107146,0.492421745255,0.552771220908, 0.613262406816,0.673556490556,0.734319796033,0.79685808014, 0.861769004751,0.928863107315,1.),.UNSPECIFIED.); -#34129 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#34130 = CARTESIAN_POINT('',(-0.10186686026,0.782,-0.26448594315)); -#34131 = CARTESIAN_POINT('',(-0.101943396327,0.782,-0.267947319425)); -#34132 = CARTESIAN_POINT('',(-0.102557703262,0.782,-0.273034351424)); -#34133 = CARTESIAN_POINT('',(-0.103661139043,0.782,-0.27786003999)); -#34134 = CARTESIAN_POINT('',(-0.105080162052,0.782,-0.282497287228)); -#34135 = CARTESIAN_POINT('',(-0.107003343979,0.782,-0.28686541831)); -#34136 = CARTESIAN_POINT('',(-0.109311854622,0.782,-0.29102706702)); -#34137 = CARTESIAN_POINT('',(-0.112138842285,0.782,-0.294872541544)); -#34138 = CARTESIAN_POINT('',(-0.115238859767,0.782,-0.298532396355)); -#34139 = CARTESIAN_POINT('',(-0.118747041454,0.782,-0.30184541093)); -#34140 = CARTESIAN_POINT('',(-0.122621172084,0.782,-0.304702348574)); -#34141 = CARTESIAN_POINT('',(-0.126738471674,0.782,-0.307225508361)); -#34142 = CARTESIAN_POINT('',(-0.131223492272,0.782,-0.309160984933)); -#34143 = CARTESIAN_POINT('',(-0.135977422796,0.782,-0.310711345801)); -#34144 = CARTESIAN_POINT('',(-0.14102284836,0.782,-0.31183786157)); -#34145 = CARTESIAN_POINT('',(-0.146380340656,0.782,-0.312526470698)); -#34146 = CARTESIAN_POINT('',(-0.150050199095,0.782,-0.312590346173)); -#34147 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34148 = PCURVE('',#33244,#34149); -#34149 = DEFINITIONAL_REPRESENTATION('',(#34150),#34170); -#34150 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34151,#34152,#34153,#34154, - #34155,#34156,#34157,#34158,#34159,#34160,#34161,#34162,#34163, - #34164,#34165,#34166,#34167,#34168,#34169),.UNSPECIFIED.,.F.,.F.,(4, +#36521 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#36522 = CARTESIAN_POINT('',(-0.10186686026,0.782,-0.26448594315)); +#36523 = CARTESIAN_POINT('',(-0.101943396327,0.782,-0.267947319425)); +#36524 = CARTESIAN_POINT('',(-0.102557703262,0.782,-0.273034351424)); +#36525 = CARTESIAN_POINT('',(-0.103661139043,0.782,-0.27786003999)); +#36526 = CARTESIAN_POINT('',(-0.105080162052,0.782,-0.282497287228)); +#36527 = CARTESIAN_POINT('',(-0.107003343979,0.782,-0.28686541831)); +#36528 = CARTESIAN_POINT('',(-0.109311854622,0.782,-0.29102706702)); +#36529 = CARTESIAN_POINT('',(-0.112138842285,0.782,-0.294872541544)); +#36530 = CARTESIAN_POINT('',(-0.115238859767,0.782,-0.298532396355)); +#36531 = CARTESIAN_POINT('',(-0.118747041454,0.782,-0.30184541093)); +#36532 = CARTESIAN_POINT('',(-0.122621172084,0.782,-0.304702348574)); +#36533 = CARTESIAN_POINT('',(-0.126738471674,0.782,-0.307225508361)); +#36534 = CARTESIAN_POINT('',(-0.131223492272,0.782,-0.309160984933)); +#36535 = CARTESIAN_POINT('',(-0.135977422796,0.782,-0.310711345801)); +#36536 = CARTESIAN_POINT('',(-0.14102284836,0.782,-0.31183786157)); +#36537 = CARTESIAN_POINT('',(-0.146380340656,0.782,-0.312526470698)); +#36538 = CARTESIAN_POINT('',(-0.150050199095,0.782,-0.312590346173)); +#36539 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#36540 = PCURVE('',#35636,#36541); +#36541 = DEFINITIONAL_REPRESENTATION('',(#36542),#36562); +#36542 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36543,#36544,#36545,#36546, + #36547,#36548,#36549,#36550,#36551,#36552,#36553,#36554,#36555, + #36556,#36557,#36558,#36559,#36560,#36561),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.661618043518E-002, 0.130423869924,0.19267095757,0.252968504796,0.312880382806, 0.372200255918,0.431927107146,0.492421745255,0.552771220908, 0.613262406816,0.673556490556,0.734319796033,0.79685808014, 0.861769004751,0.928863107315,1.),.UNSPECIFIED.); -#34151 = CARTESIAN_POINT('',(4.209805902304E-002,0.119348378007)); -#34152 = CARTESIAN_POINT('',(4.033010299913E-002,0.119309285926)); -#34153 = CARTESIAN_POINT('',(3.686872672407E-002,0.119232749859)); -#34154 = CARTESIAN_POINT('',(3.178169472474E-002,0.118618442924)); -#34155 = CARTESIAN_POINT('',(2.695600615839E-002,0.117515007143)); -#34156 = CARTESIAN_POINT('',(2.231875892104E-002,0.116095984133)); -#34157 = CARTESIAN_POINT('',(1.795062783889E-002,0.114172802207)); -#34158 = CARTESIAN_POINT('',(1.378897912925E-002,0.111864291564)); -#34159 = CARTESIAN_POINT('',(9.943504604842E-003,0.1090373039)); -#34160 = CARTESIAN_POINT('',(6.283649793739E-003,0.105937286419)); -#34161 = CARTESIAN_POINT('',(2.970635218296E-003,0.102429104732)); -#34162 = CARTESIAN_POINT('',(1.136975747372E-004,9.855497410241E-002)); -#34163 = CARTESIAN_POINT('',(-2.409462211956E-003,9.443767451189E-002)); -#34164 = CARTESIAN_POINT('',(-4.344938784101E-003,8.995265391387E-002)); -#34165 = CARTESIAN_POINT('',(-5.895299651936E-003,8.51987233901E-002)); -#34166 = CARTESIAN_POINT('',(-7.021815420845E-003,8.015329782563E-002)); -#34167 = CARTESIAN_POINT('',(-7.710424548866E-003,7.479580553023E-002)); -#34168 = CARTESIAN_POINT('',(-7.774300024465E-003,7.1125947091E-002)); -#34169 = CARTESIAN_POINT('',(-7.807171833314E-003,6.923735238407E-002)); -#34170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34171 = PCURVE('',#34172,#34211); -#34172 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#34173,#34174) - ,(#34175,#34176) - ,(#34177,#34178) - ,(#34179,#34180) - ,(#34181,#34182) - ,(#34183,#34184) - ,(#34185,#34186) - ,(#34187,#34188) - ,(#34189,#34190) - ,(#34191,#34192) - ,(#34193,#34194) - ,(#34195,#34196) - ,(#34197,#34198) - ,(#34199,#34200) - ,(#34201,#34202) - ,(#34203,#34204) - ,(#34205,#34206) - ,(#34207,#34208) - ,(#34209,#34210 +#36543 = CARTESIAN_POINT('',(4.209805902304E-002,0.119348378007)); +#36544 = CARTESIAN_POINT('',(4.033010299913E-002,0.119309285926)); +#36545 = CARTESIAN_POINT('',(3.686872672407E-002,0.119232749859)); +#36546 = CARTESIAN_POINT('',(3.178169472474E-002,0.118618442924)); +#36547 = CARTESIAN_POINT('',(2.695600615839E-002,0.117515007143)); +#36548 = CARTESIAN_POINT('',(2.231875892104E-002,0.116095984133)); +#36549 = CARTESIAN_POINT('',(1.795062783889E-002,0.114172802207)); +#36550 = CARTESIAN_POINT('',(1.378897912925E-002,0.111864291564)); +#36551 = CARTESIAN_POINT('',(9.943504604842E-003,0.1090373039)); +#36552 = CARTESIAN_POINT('',(6.283649793739E-003,0.105937286419)); +#36553 = CARTESIAN_POINT('',(2.970635218296E-003,0.102429104732)); +#36554 = CARTESIAN_POINT('',(1.136975747372E-004,9.855497410241E-002)); +#36555 = CARTESIAN_POINT('',(-2.409462211956E-003,9.443767451189E-002)); +#36556 = CARTESIAN_POINT('',(-4.344938784101E-003,8.995265391387E-002)); +#36557 = CARTESIAN_POINT('',(-5.895299651936E-003,8.51987233901E-002)); +#36558 = CARTESIAN_POINT('',(-7.021815420845E-003,8.015329782563E-002)); +#36559 = CARTESIAN_POINT('',(-7.710424548866E-003,7.479580553023E-002)); +#36560 = CARTESIAN_POINT('',(-7.774300024465E-003,7.1125947091E-002)); +#36561 = CARTESIAN_POINT('',(-7.807171833314E-003,6.923735238407E-002)); +#36562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36563 = PCURVE('',#36564,#36603); +#36564 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#36565,#36566) + ,(#36567,#36568) + ,(#36569,#36570) + ,(#36571,#36572) + ,(#36573,#36574) + ,(#36575,#36576) + ,(#36577,#36578) + ,(#36579,#36580) + ,(#36581,#36582) + ,(#36583,#36584) + ,(#36585,#36586) + ,(#36587,#36588) + ,(#36589,#36590) + ,(#36591,#36592) + ,(#36593,#36594) + ,(#36595,#36596) + ,(#36597,#36598) + ,(#36599,#36600) + ,(#36601,#36602 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,6.661618043518E-002,0.130423869924,0.19267095757, 0.252968504796,0.312880382806,0.372200255918,0.431927107146, 0.492421745255,0.552771220908,0.613262406816,0.673556490556, 0.734319796033,0.79685808014,0.861769004751,0.928863107315,1.),( 0.E+000,1.),.UNSPECIFIED.); -#34173 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#34174 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); -#34175 = CARTESIAN_POINT('',(-0.10186686026,0.782,-0.26448594315)); -#34176 = CARTESIAN_POINT('',(-0.10186686026,0.78,-0.26448594315)); -#34177 = CARTESIAN_POINT('',(-0.101943396327,0.782,-0.267947319425)); -#34178 = CARTESIAN_POINT('',(-0.101943396327,0.78,-0.267947319425)); -#34179 = CARTESIAN_POINT('',(-0.102557703262,0.782,-0.273034351424)); -#34180 = CARTESIAN_POINT('',(-0.102557703262,0.78,-0.273034351424)); -#34181 = CARTESIAN_POINT('',(-0.103661139043,0.782,-0.27786003999)); -#34182 = CARTESIAN_POINT('',(-0.103661139043,0.78,-0.27786003999)); -#34183 = CARTESIAN_POINT('',(-0.105080162052,0.782,-0.282497287228)); -#34184 = CARTESIAN_POINT('',(-0.105080162052,0.78,-0.282497287228)); -#34185 = CARTESIAN_POINT('',(-0.107003343979,0.782,-0.28686541831)); -#34186 = CARTESIAN_POINT('',(-0.107003343979,0.78,-0.28686541831)); -#34187 = CARTESIAN_POINT('',(-0.109311854622,0.782,-0.29102706702)); -#34188 = CARTESIAN_POINT('',(-0.109311854622,0.78,-0.29102706702)); -#34189 = CARTESIAN_POINT('',(-0.112138842285,0.782,-0.294872541544)); -#34190 = CARTESIAN_POINT('',(-0.112138842285,0.78,-0.294872541544)); -#34191 = CARTESIAN_POINT('',(-0.115238859767,0.782,-0.298532396355)); -#34192 = CARTESIAN_POINT('',(-0.115238859767,0.78,-0.298532396355)); -#34193 = CARTESIAN_POINT('',(-0.118747041454,0.782,-0.30184541093)); -#34194 = CARTESIAN_POINT('',(-0.118747041454,0.78,-0.30184541093)); -#34195 = CARTESIAN_POINT('',(-0.122621172084,0.782,-0.304702348574)); -#34196 = CARTESIAN_POINT('',(-0.122621172084,0.78,-0.304702348574)); -#34197 = CARTESIAN_POINT('',(-0.126738471674,0.782,-0.307225508361)); -#34198 = CARTESIAN_POINT('',(-0.126738471674,0.78,-0.307225508361)); -#34199 = CARTESIAN_POINT('',(-0.131223492272,0.782,-0.309160984933)); -#34200 = CARTESIAN_POINT('',(-0.131223492272,0.78,-0.309160984933)); -#34201 = CARTESIAN_POINT('',(-0.135977422796,0.782,-0.310711345801)); -#34202 = CARTESIAN_POINT('',(-0.135977422796,0.78,-0.310711345801)); -#34203 = CARTESIAN_POINT('',(-0.14102284836,0.782,-0.31183786157)); -#34204 = CARTESIAN_POINT('',(-0.14102284836,0.78,-0.31183786157)); -#34205 = CARTESIAN_POINT('',(-0.146380340656,0.782,-0.312526470698)); -#34206 = CARTESIAN_POINT('',(-0.146380340656,0.78,-0.312526470698)); -#34207 = CARTESIAN_POINT('',(-0.150050199095,0.782,-0.312590346173)); -#34208 = CARTESIAN_POINT('',(-0.150050199095,0.78,-0.312590346173)); -#34209 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34210 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); -#34211 = DEFINITIONAL_REPRESENTATION('',(#34212),#34216); -#34212 = LINE('',#34213,#34214); -#34213 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34214 = VECTOR('',#34215,1.); -#34215 = DIRECTION('',(1.,0.E+000)); -#34216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34217 = ORIENTED_EDGE('',*,*,#34218,.F.); -#34218 = EDGE_CURVE('',#33953,#34125,#34219,.T.); -#34219 = SURFACE_CURVE('',#34220,(#34240,#34263),.PCURVE_S1.); -#34220 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34221,#34222,#34223,#34224, - #34225,#34226,#34227,#34228,#34229,#34230,#34231,#34232,#34233, - #34234,#34235,#34236,#34237,#34238,#34239),.UNSPECIFIED.,.F.,.F.,(4, +#36565 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#36566 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); +#36567 = CARTESIAN_POINT('',(-0.10186686026,0.782,-0.26448594315)); +#36568 = CARTESIAN_POINT('',(-0.10186686026,0.78,-0.26448594315)); +#36569 = CARTESIAN_POINT('',(-0.101943396327,0.782,-0.267947319425)); +#36570 = CARTESIAN_POINT('',(-0.101943396327,0.78,-0.267947319425)); +#36571 = CARTESIAN_POINT('',(-0.102557703262,0.782,-0.273034351424)); +#36572 = CARTESIAN_POINT('',(-0.102557703262,0.78,-0.273034351424)); +#36573 = CARTESIAN_POINT('',(-0.103661139043,0.782,-0.27786003999)); +#36574 = CARTESIAN_POINT('',(-0.103661139043,0.78,-0.27786003999)); +#36575 = CARTESIAN_POINT('',(-0.105080162052,0.782,-0.282497287228)); +#36576 = CARTESIAN_POINT('',(-0.105080162052,0.78,-0.282497287228)); +#36577 = CARTESIAN_POINT('',(-0.107003343979,0.782,-0.28686541831)); +#36578 = CARTESIAN_POINT('',(-0.107003343979,0.78,-0.28686541831)); +#36579 = CARTESIAN_POINT('',(-0.109311854622,0.782,-0.29102706702)); +#36580 = CARTESIAN_POINT('',(-0.109311854622,0.78,-0.29102706702)); +#36581 = CARTESIAN_POINT('',(-0.112138842285,0.782,-0.294872541544)); +#36582 = CARTESIAN_POINT('',(-0.112138842285,0.78,-0.294872541544)); +#36583 = CARTESIAN_POINT('',(-0.115238859767,0.782,-0.298532396355)); +#36584 = CARTESIAN_POINT('',(-0.115238859767,0.78,-0.298532396355)); +#36585 = CARTESIAN_POINT('',(-0.118747041454,0.782,-0.30184541093)); +#36586 = CARTESIAN_POINT('',(-0.118747041454,0.78,-0.30184541093)); +#36587 = CARTESIAN_POINT('',(-0.122621172084,0.782,-0.304702348574)); +#36588 = CARTESIAN_POINT('',(-0.122621172084,0.78,-0.304702348574)); +#36589 = CARTESIAN_POINT('',(-0.126738471674,0.782,-0.307225508361)); +#36590 = CARTESIAN_POINT('',(-0.126738471674,0.78,-0.307225508361)); +#36591 = CARTESIAN_POINT('',(-0.131223492272,0.782,-0.309160984933)); +#36592 = CARTESIAN_POINT('',(-0.131223492272,0.78,-0.309160984933)); +#36593 = CARTESIAN_POINT('',(-0.135977422796,0.782,-0.310711345801)); +#36594 = CARTESIAN_POINT('',(-0.135977422796,0.78,-0.310711345801)); +#36595 = CARTESIAN_POINT('',(-0.14102284836,0.782,-0.31183786157)); +#36596 = CARTESIAN_POINT('',(-0.14102284836,0.78,-0.31183786157)); +#36597 = CARTESIAN_POINT('',(-0.146380340656,0.782,-0.312526470698)); +#36598 = CARTESIAN_POINT('',(-0.146380340656,0.78,-0.312526470698)); +#36599 = CARTESIAN_POINT('',(-0.150050199095,0.782,-0.312590346173)); +#36600 = CARTESIAN_POINT('',(-0.150050199095,0.78,-0.312590346173)); +#36601 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#36602 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); +#36603 = DEFINITIONAL_REPRESENTATION('',(#36604),#36608); +#36604 = LINE('',#36605,#36606); +#36605 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36606 = VECTOR('',#36607,1.); +#36607 = DIRECTION('',(1.,0.E+000)); +#36608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36609 = ORIENTED_EDGE('',*,*,#36610,.F.); +#36610 = EDGE_CURVE('',#36345,#36517,#36611,.T.); +#36611 = SURFACE_CURVE('',#36612,(#36632,#36655),.PCURVE_S1.); +#36612 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36613,#36614,#36615,#36616, + #36617,#36618,#36619,#36620,#36621,#36622,#36623,#36624,#36625, + #36626,#36627,#36628,#36629,#36630,#36631),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.183671713195E-002, 0.139558262918,0.204923352654,0.267826558604,0.328547320094, 0.388755146329,0.44802996798,0.508600527697,0.569321289187, 0.628511895402,0.687493275539,0.747078295389,0.807702541317, 0.869709812621,0.933428331305,1.),.UNSPECIFIED.); -#34221 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#34222 = CARTESIAN_POINT('',(-0.149089629476,0.782,-0.2138734343)); -#34223 = CARTESIAN_POINT('',(-0.145453568086,0.782,-0.213935026519)); -#34224 = CARTESIAN_POINT('',(-0.14015332903,0.782,-0.214638849754)); -#34225 = CARTESIAN_POINT('',(-0.135159305537,0.782,-0.215706779839)); -#34226 = CARTESIAN_POINT('',(-0.130448617732,0.782,-0.217171087032)); -#34227 = CARTESIAN_POINT('',(-0.126090601696,0.782,-0.2191743562)); -#34228 = CARTESIAN_POINT('',(-0.122014288911,0.782,-0.221515742715)); -#34229 = CARTESIAN_POINT('',(-0.118261374819,0.782,-0.224345487547)); -#34230 = CARTESIAN_POINT('',(-0.114832921846,0.782,-0.227574940682)); -#34231 = CARTESIAN_POINT('',(-0.111763848655,0.782,-0.231147321084)); -#34232 = CARTESIAN_POINT('',(-0.109134799364,0.782,-0.23500113898)); -#34233 = CARTESIAN_POINT('',(-0.106841448614,0.782,-0.239028015166)); -#34234 = CARTESIAN_POINT('',(-0.104969032574,0.782,-0.243314855844)); -#34235 = CARTESIAN_POINT('',(-0.103614973993,0.782,-0.247870500851)); -#34236 = CARTESIAN_POINT('',(-0.102570126549,0.782,-0.252612756481)); -#34237 = CARTESIAN_POINT('',(-0.101939800998,0.782,-0.257590536503)); -#34238 = CARTESIAN_POINT('',(-0.101865653688,0.782,-0.260984065934)); -#34239 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#34240 = PCURVE('',#33244,#34241); -#34241 = DEFINITIONAL_REPRESENTATION('',(#34242),#34262); -#34242 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34243,#34244,#34245,#34246, - #34247,#34248,#34249,#34250,#34251,#34252,#34253,#34254,#34255, - #34256,#34257,#34258,#34259,#34260,#34261),.UNSPECIFIED.,.F.,.F.,(4, +#36613 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#36614 = CARTESIAN_POINT('',(-0.149089629476,0.782,-0.2138734343)); +#36615 = CARTESIAN_POINT('',(-0.145453568086,0.782,-0.213935026519)); +#36616 = CARTESIAN_POINT('',(-0.14015332903,0.782,-0.214638849754)); +#36617 = CARTESIAN_POINT('',(-0.135159305537,0.782,-0.215706779839)); +#36618 = CARTESIAN_POINT('',(-0.130448617732,0.782,-0.217171087032)); +#36619 = CARTESIAN_POINT('',(-0.126090601696,0.782,-0.2191743562)); +#36620 = CARTESIAN_POINT('',(-0.122014288911,0.782,-0.221515742715)); +#36621 = CARTESIAN_POINT('',(-0.118261374819,0.782,-0.224345487547)); +#36622 = CARTESIAN_POINT('',(-0.114832921846,0.782,-0.227574940682)); +#36623 = CARTESIAN_POINT('',(-0.111763848655,0.782,-0.231147321084)); +#36624 = CARTESIAN_POINT('',(-0.109134799364,0.782,-0.23500113898)); +#36625 = CARTESIAN_POINT('',(-0.106841448614,0.782,-0.239028015166)); +#36626 = CARTESIAN_POINT('',(-0.104969032574,0.782,-0.243314855844)); +#36627 = CARTESIAN_POINT('',(-0.103614973993,0.782,-0.247870500851)); +#36628 = CARTESIAN_POINT('',(-0.102570126549,0.782,-0.252612756481)); +#36629 = CARTESIAN_POINT('',(-0.101939800998,0.782,-0.257590536503)); +#36630 = CARTESIAN_POINT('',(-0.101865653688,0.782,-0.260984065934)); +#36631 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#36632 = PCURVE('',#35636,#36633); +#36633 = DEFINITIONAL_REPRESENTATION('',(#36634),#36654); +#36634 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36635,#36636,#36637,#36638, + #36639,#36640,#36641,#36642,#36643,#36644,#36645,#36646,#36647, + #36648,#36649,#36650,#36651,#36652,#36653),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.183671713195E-002, 0.139558262918,0.204923352654,0.267826558604,0.328547320094, 0.388755146329,0.44802996798,0.508600527697,0.569321289187, 0.628511895402,0.687493275539,0.747078295389,0.807702541317, 0.869709812621,0.933428331305,1.),.UNSPECIFIED.); -#34243 = CARTESIAN_POINT('',(9.097431604729E-002,7.021487752456E-002)); -#34244 = CARTESIAN_POINT('',(9.094261184907E-002,7.208651671015E-002)); -#34245 = CARTESIAN_POINT('',(9.088101962982E-002,7.572257810019E-002)); -#34246 = CARTESIAN_POINT('',(9.017719639498E-002,8.102281715569E-002)); -#34247 = CARTESIAN_POINT('',(8.910926630973E-002,8.601684064923E-002)); -#34248 = CARTESIAN_POINT('',(8.764495911729E-002,9.072752845404E-002)); -#34249 = CARTESIAN_POINT('',(8.564168994844E-002,9.508554449018E-002)); -#34250 = CARTESIAN_POINT('',(8.330030343415E-002,9.916185727482E-002)); -#34251 = CARTESIAN_POINT('',(8.047055860186E-002,0.102914771366)); -#34252 = CARTESIAN_POINT('',(7.724110546651E-002,0.10634322434)); -#34253 = CARTESIAN_POINT('',(7.366872506445E-002,0.109412297531)); -#34254 = CARTESIAN_POINT('',(6.981490716917E-002,0.112041346822)); -#34255 = CARTESIAN_POINT('',(6.578803098247E-002,0.114334697572)); -#34256 = CARTESIAN_POINT('',(6.150119030451E-002,0.116207113612)); -#34257 = CARTESIAN_POINT('',(5.694554529736E-002,0.117561172193)); -#34258 = CARTESIAN_POINT('',(5.220328966793E-002,0.118606019637)); -#34259 = CARTESIAN_POINT('',(4.722550964545E-002,0.119236345188)); -#34260 = CARTESIAN_POINT('',(4.383198021474E-002,0.119310492497)); -#34261 = CARTESIAN_POINT('',(4.209805902304E-002,0.119348378007)); -#34262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34263 = PCURVE('',#34264,#34303); -#34264 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#34265,#34266) - ,(#34267,#34268) - ,(#34269,#34270) - ,(#34271,#34272) - ,(#34273,#34274) - ,(#34275,#34276) - ,(#34277,#34278) - ,(#34279,#34280) - ,(#34281,#34282) - ,(#34283,#34284) - ,(#34285,#34286) - ,(#34287,#34288) - ,(#34289,#34290) - ,(#34291,#34292) - ,(#34293,#34294) - ,(#34295,#34296) - ,(#34297,#34298) - ,(#34299,#34300) - ,(#34301,#34302 +#36635 = CARTESIAN_POINT('',(9.097431604729E-002,7.021487752456E-002)); +#36636 = CARTESIAN_POINT('',(9.094261184907E-002,7.208651671015E-002)); +#36637 = CARTESIAN_POINT('',(9.088101962982E-002,7.572257810019E-002)); +#36638 = CARTESIAN_POINT('',(9.017719639498E-002,8.102281715569E-002)); +#36639 = CARTESIAN_POINT('',(8.910926630973E-002,8.601684064923E-002)); +#36640 = CARTESIAN_POINT('',(8.764495911729E-002,9.072752845404E-002)); +#36641 = CARTESIAN_POINT('',(8.564168994844E-002,9.508554449018E-002)); +#36642 = CARTESIAN_POINT('',(8.330030343415E-002,9.916185727482E-002)); +#36643 = CARTESIAN_POINT('',(8.047055860186E-002,0.102914771366)); +#36644 = CARTESIAN_POINT('',(7.724110546651E-002,0.10634322434)); +#36645 = CARTESIAN_POINT('',(7.366872506445E-002,0.109412297531)); +#36646 = CARTESIAN_POINT('',(6.981490716917E-002,0.112041346822)); +#36647 = CARTESIAN_POINT('',(6.578803098247E-002,0.114334697572)); +#36648 = CARTESIAN_POINT('',(6.150119030451E-002,0.116207113612)); +#36649 = CARTESIAN_POINT('',(5.694554529736E-002,0.117561172193)); +#36650 = CARTESIAN_POINT('',(5.220328966793E-002,0.118606019637)); +#36651 = CARTESIAN_POINT('',(4.722550964545E-002,0.119236345188)); +#36652 = CARTESIAN_POINT('',(4.383198021474E-002,0.119310492497)); +#36653 = CARTESIAN_POINT('',(4.209805902304E-002,0.119348378007)); +#36654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36655 = PCURVE('',#36656,#36695); +#36656 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#36657,#36658) + ,(#36659,#36660) + ,(#36661,#36662) + ,(#36663,#36664) + ,(#36665,#36666) + ,(#36667,#36668) + ,(#36669,#36670) + ,(#36671,#36672) + ,(#36673,#36674) + ,(#36675,#36676) + ,(#36677,#36678) + ,(#36679,#36680) + ,(#36681,#36682) + ,(#36683,#36684) + ,(#36685,#36686) + ,(#36687,#36688) + ,(#36689,#36690) + ,(#36691,#36692) + ,(#36693,#36694 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,7.183671713195E-002,0.139558262918,0.204923352654, 0.267826558604,0.328547320094,0.388755146329,0.44802996798, 0.508600527697,0.569321289187,0.628511895402,0.687493275539, 0.747078295389,0.807702541317,0.869709812621,0.933428331305,1.),( 0.E+000,1.),.UNSPECIFIED.); -#34265 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#34266 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); -#34267 = CARTESIAN_POINT('',(-0.149089629476,0.782,-0.2138734343)); -#34268 = CARTESIAN_POINT('',(-0.149089629476,0.78,-0.2138734343)); -#34269 = CARTESIAN_POINT('',(-0.145453568086,0.782,-0.213935026519)); -#34270 = CARTESIAN_POINT('',(-0.145453568086,0.78,-0.213935026519)); -#34271 = CARTESIAN_POINT('',(-0.14015332903,0.782,-0.214638849754)); -#34272 = CARTESIAN_POINT('',(-0.14015332903,0.78,-0.214638849754)); -#34273 = CARTESIAN_POINT('',(-0.135159305537,0.782,-0.215706779839)); -#34274 = CARTESIAN_POINT('',(-0.135159305537,0.78,-0.215706779839)); -#34275 = CARTESIAN_POINT('',(-0.130448617732,0.782,-0.217171087032)); -#34276 = CARTESIAN_POINT('',(-0.130448617732,0.78,-0.217171087032)); -#34277 = CARTESIAN_POINT('',(-0.126090601696,0.782,-0.2191743562)); -#34278 = CARTESIAN_POINT('',(-0.126090601696,0.78,-0.2191743562)); -#34279 = CARTESIAN_POINT('',(-0.122014288911,0.782,-0.221515742715)); -#34280 = CARTESIAN_POINT('',(-0.122014288911,0.78,-0.221515742715)); -#34281 = CARTESIAN_POINT('',(-0.118261374819,0.782,-0.224345487547)); -#34282 = CARTESIAN_POINT('',(-0.118261374819,0.78,-0.224345487547)); -#34283 = CARTESIAN_POINT('',(-0.114832921846,0.782,-0.227574940682)); -#34284 = CARTESIAN_POINT('',(-0.114832921846,0.78,-0.227574940682)); -#34285 = CARTESIAN_POINT('',(-0.111763848655,0.782,-0.231147321084)); -#34286 = CARTESIAN_POINT('',(-0.111763848655,0.78,-0.231147321084)); -#34287 = CARTESIAN_POINT('',(-0.109134799364,0.782,-0.23500113898)); -#34288 = CARTESIAN_POINT('',(-0.109134799364,0.78,-0.23500113898)); -#34289 = CARTESIAN_POINT('',(-0.106841448614,0.782,-0.239028015166)); -#34290 = CARTESIAN_POINT('',(-0.106841448614,0.78,-0.239028015166)); -#34291 = CARTESIAN_POINT('',(-0.104969032574,0.782,-0.243314855844)); -#34292 = CARTESIAN_POINT('',(-0.104969032574,0.78,-0.243314855844)); -#34293 = CARTESIAN_POINT('',(-0.103614973993,0.782,-0.247870500851)); -#34294 = CARTESIAN_POINT('',(-0.103614973993,0.78,-0.247870500851)); -#34295 = CARTESIAN_POINT('',(-0.102570126549,0.782,-0.252612756481)); -#34296 = CARTESIAN_POINT('',(-0.102570126549,0.78,-0.252612756481)); -#34297 = CARTESIAN_POINT('',(-0.101939800998,0.782,-0.257590536503)); -#34298 = CARTESIAN_POINT('',(-0.101939800998,0.78,-0.257590536503)); -#34299 = CARTESIAN_POINT('',(-0.101865653688,0.782,-0.260984065934)); -#34300 = CARTESIAN_POINT('',(-0.101865653688,0.78,-0.260984065934)); -#34301 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#34302 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); -#34303 = DEFINITIONAL_REPRESENTATION('',(#34304),#34308); -#34304 = LINE('',#34305,#34306); -#34305 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34306 = VECTOR('',#34307,1.); -#34307 = DIRECTION('',(1.,0.E+000)); -#34308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34309 = ADVANCED_FACE('',(#34310),#30410,.T.); -#34310 = FACE_BOUND('',#34311,.T.); -#34311 = EDGE_LOOP('',(#34312,#34313,#34332,#34333)); -#34312 = ORIENTED_EDGE('',*,*,#30360,.F.); -#34313 = ORIENTED_EDGE('',*,*,#34314,.F.); -#34314 = EDGE_CURVE('',#33541,#30361,#34315,.T.); -#34315 = SURFACE_CURVE('',#34316,(#34320,#34326),.PCURVE_S1.); -#34316 = LINE('',#34317,#34318); -#34317 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); -#34318 = VECTOR('',#34319,1.); -#34319 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34320 = PCURVE('',#30410,#34321); -#34321 = DEFINITIONAL_REPRESENTATION('',(#34322),#34325); -#34322 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34323,#34324),.UNSPECIFIED., +#36657 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#36658 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); +#36659 = CARTESIAN_POINT('',(-0.149089629476,0.782,-0.2138734343)); +#36660 = CARTESIAN_POINT('',(-0.149089629476,0.78,-0.2138734343)); +#36661 = CARTESIAN_POINT('',(-0.145453568086,0.782,-0.213935026519)); +#36662 = CARTESIAN_POINT('',(-0.145453568086,0.78,-0.213935026519)); +#36663 = CARTESIAN_POINT('',(-0.14015332903,0.782,-0.214638849754)); +#36664 = CARTESIAN_POINT('',(-0.14015332903,0.78,-0.214638849754)); +#36665 = CARTESIAN_POINT('',(-0.135159305537,0.782,-0.215706779839)); +#36666 = CARTESIAN_POINT('',(-0.135159305537,0.78,-0.215706779839)); +#36667 = CARTESIAN_POINT('',(-0.130448617732,0.782,-0.217171087032)); +#36668 = CARTESIAN_POINT('',(-0.130448617732,0.78,-0.217171087032)); +#36669 = CARTESIAN_POINT('',(-0.126090601696,0.782,-0.2191743562)); +#36670 = CARTESIAN_POINT('',(-0.126090601696,0.78,-0.2191743562)); +#36671 = CARTESIAN_POINT('',(-0.122014288911,0.782,-0.221515742715)); +#36672 = CARTESIAN_POINT('',(-0.122014288911,0.78,-0.221515742715)); +#36673 = CARTESIAN_POINT('',(-0.118261374819,0.782,-0.224345487547)); +#36674 = CARTESIAN_POINT('',(-0.118261374819,0.78,-0.224345487547)); +#36675 = CARTESIAN_POINT('',(-0.114832921846,0.782,-0.227574940682)); +#36676 = CARTESIAN_POINT('',(-0.114832921846,0.78,-0.227574940682)); +#36677 = CARTESIAN_POINT('',(-0.111763848655,0.782,-0.231147321084)); +#36678 = CARTESIAN_POINT('',(-0.111763848655,0.78,-0.231147321084)); +#36679 = CARTESIAN_POINT('',(-0.109134799364,0.782,-0.23500113898)); +#36680 = CARTESIAN_POINT('',(-0.109134799364,0.78,-0.23500113898)); +#36681 = CARTESIAN_POINT('',(-0.106841448614,0.782,-0.239028015166)); +#36682 = CARTESIAN_POINT('',(-0.106841448614,0.78,-0.239028015166)); +#36683 = CARTESIAN_POINT('',(-0.104969032574,0.782,-0.243314855844)); +#36684 = CARTESIAN_POINT('',(-0.104969032574,0.78,-0.243314855844)); +#36685 = CARTESIAN_POINT('',(-0.103614973993,0.782,-0.247870500851)); +#36686 = CARTESIAN_POINT('',(-0.103614973993,0.78,-0.247870500851)); +#36687 = CARTESIAN_POINT('',(-0.102570126549,0.782,-0.252612756481)); +#36688 = CARTESIAN_POINT('',(-0.102570126549,0.78,-0.252612756481)); +#36689 = CARTESIAN_POINT('',(-0.101939800998,0.782,-0.257590536503)); +#36690 = CARTESIAN_POINT('',(-0.101939800998,0.78,-0.257590536503)); +#36691 = CARTESIAN_POINT('',(-0.101865653688,0.782,-0.260984065934)); +#36692 = CARTESIAN_POINT('',(-0.101865653688,0.78,-0.260984065934)); +#36693 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#36694 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); +#36695 = DEFINITIONAL_REPRESENTATION('',(#36696),#36700); +#36696 = LINE('',#36697,#36698); +#36697 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36698 = VECTOR('',#36699,1.); +#36699 = DIRECTION('',(1.,0.E+000)); +#36700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36701 = ADVANCED_FACE('',(#36702),#32802,.T.); +#36702 = FACE_BOUND('',#36703,.T.); +#36703 = EDGE_LOOP('',(#36704,#36705,#36724,#36725)); +#36704 = ORIENTED_EDGE('',*,*,#32752,.F.); +#36705 = ORIENTED_EDGE('',*,*,#36706,.F.); +#36706 = EDGE_CURVE('',#35933,#32753,#36707,.T.); +#36707 = SURFACE_CURVE('',#36708,(#36712,#36718),.PCURVE_S1.); +#36708 = LINE('',#36709,#36710); +#36709 = CARTESIAN_POINT('',(-0.233536418687,0.782,-0.263129576659)); +#36710 = VECTOR('',#36711,1.); +#36711 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36712 = PCURVE('',#32802,#36713); +#36713 = DEFINITIONAL_REPRESENTATION('',(#36714),#36717); +#36714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36715,#36716),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34323 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34324 = CARTESIAN_POINT('',(0.E+000,1.)); -#34325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36715 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36716 = CARTESIAN_POINT('',(0.E+000,1.)); +#36717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34326 = PCURVE('',#31002,#34327); -#34327 = DEFINITIONAL_REPRESENTATION('',(#34328),#34331); -#34328 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34329,#34330),.UNSPECIFIED., +#36718 = PCURVE('',#33394,#36719); +#36719 = DEFINITIONAL_REPRESENTATION('',(#36720),#36723); +#36720 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36721,#36722),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34329 = CARTESIAN_POINT('',(1.,0.E+000)); -#34330 = CARTESIAN_POINT('',(1.,1.)); -#34331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34332 = ORIENTED_EDGE('',*,*,#33540,.T.); -#34333 = ORIENTED_EDGE('',*,*,#34334,.T.); -#34334 = EDGE_CURVE('',#33543,#30363,#34335,.T.); -#34335 = SURFACE_CURVE('',#34336,(#34340,#34346),.PCURVE_S1.); -#34336 = LINE('',#34337,#34338); -#34337 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); -#34338 = VECTOR('',#34339,1.); -#34339 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34340 = PCURVE('',#30410,#34341); -#34341 = DEFINITIONAL_REPRESENTATION('',(#34342),#34345); -#34342 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34343,#34344),.UNSPECIFIED., +#36721 = CARTESIAN_POINT('',(1.,0.E+000)); +#36722 = CARTESIAN_POINT('',(1.,1.)); +#36723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36724 = ORIENTED_EDGE('',*,*,#35932,.T.); +#36725 = ORIENTED_EDGE('',*,*,#36726,.T.); +#36726 = EDGE_CURVE('',#35935,#32755,#36727,.T.); +#36727 = SURFACE_CURVE('',#36728,(#36732,#36738),.PCURVE_S1.); +#36728 = LINE('',#36729,#36730); +#36729 = CARTESIAN_POINT('',(-0.184763059046,0.782,-0.328366517613)); +#36730 = VECTOR('',#36731,1.); +#36731 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36732 = PCURVE('',#32802,#36733); +#36733 = DEFINITIONAL_REPRESENTATION('',(#36734),#36737); +#36734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36735,#36736),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34343 = CARTESIAN_POINT('',(1.,0.E+000)); -#34344 = CARTESIAN_POINT('',(1.,1.)); -#34345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36735 = CARTESIAN_POINT('',(1.,0.E+000)); +#36736 = CARTESIAN_POINT('',(1.,1.)); +#36737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34346 = PCURVE('',#30488,#34347); -#34347 = DEFINITIONAL_REPRESENTATION('',(#34348),#34351); -#34348 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34349,#34350),.UNSPECIFIED., +#36738 = PCURVE('',#32880,#36739); +#36739 = DEFINITIONAL_REPRESENTATION('',(#36740),#36743); +#36740 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36741,#36742),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34349 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34350 = CARTESIAN_POINT('',(0.E+000,1.)); -#34351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34352 = ADVANCED_FACE('',(#34353),#31002,.T.); -#34353 = FACE_BOUND('',#34354,.T.); -#34354 = EDGE_LOOP('',(#34355,#34356,#34375,#34376)); -#34355 = ORIENTED_EDGE('',*,*,#30956,.F.); -#34356 = ORIENTED_EDGE('',*,*,#34357,.F.); -#34357 = EDGE_CURVE('',#33598,#30863,#34358,.T.); -#34358 = SURFACE_CURVE('',#34359,(#34363,#34369),.PCURVE_S1.); -#34359 = LINE('',#34360,#34361); -#34360 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); -#34361 = VECTOR('',#34362,1.); -#34362 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34363 = PCURVE('',#31002,#34364); -#34364 = DEFINITIONAL_REPRESENTATION('',(#34365),#34368); -#34365 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34366,#34367),.UNSPECIFIED., +#36741 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36742 = CARTESIAN_POINT('',(0.E+000,1.)); +#36743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36744 = ADVANCED_FACE('',(#36745),#33394,.T.); +#36745 = FACE_BOUND('',#36746,.T.); +#36746 = EDGE_LOOP('',(#36747,#36748,#36767,#36768)); +#36747 = ORIENTED_EDGE('',*,*,#33348,.F.); +#36748 = ORIENTED_EDGE('',*,*,#36749,.F.); +#36749 = EDGE_CURVE('',#35990,#33255,#36750,.T.); +#36750 = SURFACE_CURVE('',#36751,(#36755,#36761),.PCURVE_S1.); +#36751 = LINE('',#36752,#36753); +#36752 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.184207283737)); +#36753 = VECTOR('',#36754,1.); +#36754 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36755 = PCURVE('',#33394,#36756); +#36756 = DEFINITIONAL_REPRESENTATION('',(#36757),#36760); +#36757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36758,#36759),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34366 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34367 = CARTESIAN_POINT('',(0.E+000,1.)); -#34368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36758 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36759 = CARTESIAN_POINT('',(0.E+000,1.)); +#36760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34369 = PCURVE('',#30910,#34370); -#34370 = DEFINITIONAL_REPRESENTATION('',(#34371),#34374); -#34371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34372,#34373),.UNSPECIFIED., +#36761 = PCURVE('',#33302,#36762); +#36762 = DEFINITIONAL_REPRESENTATION('',(#36763),#36766); +#36763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36764,#36765),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34372 = CARTESIAN_POINT('',(1.,0.E+000)); -#34373 = CARTESIAN_POINT('',(1.,1.)); -#34374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34375 = ORIENTED_EDGE('',*,*,#33597,.T.); -#34376 = ORIENTED_EDGE('',*,*,#34314,.T.); -#34377 = ADVANCED_FACE('',(#34378),#30910,.T.); -#34378 = FACE_BOUND('',#34379,.T.); -#34379 = EDGE_LOOP('',(#34380,#34381,#34400,#34401)); -#34380 = ORIENTED_EDGE('',*,*,#30862,.F.); -#34381 = ORIENTED_EDGE('',*,*,#34382,.F.); -#34382 = EDGE_CURVE('',#33653,#30769,#34383,.T.); -#34383 = SURFACE_CURVE('',#34384,(#34388,#34394),.PCURVE_S1.); -#34384 = LINE('',#34385,#34386); -#34385 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) - ); -#34386 = VECTOR('',#34387,1.); -#34387 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34388 = PCURVE('',#30910,#34389); -#34389 = DEFINITIONAL_REPRESENTATION('',(#34390),#34393); -#34390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34391,#34392),.UNSPECIFIED., +#36764 = CARTESIAN_POINT('',(1.,0.E+000)); +#36765 = CARTESIAN_POINT('',(1.,1.)); +#36766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36767 = ORIENTED_EDGE('',*,*,#35989,.T.); +#36768 = ORIENTED_EDGE('',*,*,#36706,.T.); +#36769 = ADVANCED_FACE('',(#36770),#33302,.T.); +#36770 = FACE_BOUND('',#36771,.T.); +#36771 = EDGE_LOOP('',(#36772,#36773,#36792,#36793)); +#36772 = ORIENTED_EDGE('',*,*,#33254,.F.); +#36773 = ORIENTED_EDGE('',*,*,#36774,.F.); +#36774 = EDGE_CURVE('',#36045,#33161,#36775,.T.); +#36775 = SURFACE_CURVE('',#36776,(#36780,#36786),.PCURVE_S1.); +#36776 = LINE('',#36777,#36778); +#36777 = CARTESIAN_POINT('',(-6.890060555222E-002,0.782,-0.262254948901) + ); +#36778 = VECTOR('',#36779,1.); +#36779 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36780 = PCURVE('',#33302,#36781); +#36781 = DEFINITIONAL_REPRESENTATION('',(#36782),#36785); +#36782 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36783,#36784),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34391 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34392 = CARTESIAN_POINT('',(0.E+000,1.)); -#34393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36783 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36784 = CARTESIAN_POINT('',(0.E+000,1.)); +#36785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34394 = PCURVE('',#30816,#34395); -#34395 = DEFINITIONAL_REPRESENTATION('',(#34396),#34399); -#34396 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34397,#34398),.UNSPECIFIED., +#36786 = PCURVE('',#33208,#36787); +#36787 = DEFINITIONAL_REPRESENTATION('',(#36788),#36791); +#36788 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36789,#36790),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34397 = CARTESIAN_POINT('',(1.,0.E+000)); -#34398 = CARTESIAN_POINT('',(1.,1.)); -#34399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34400 = ORIENTED_EDGE('',*,*,#33652,.T.); -#34401 = ORIENTED_EDGE('',*,*,#34357,.T.); -#34402 = ADVANCED_FACE('',(#34403),#30816,.T.); -#34403 = FACE_BOUND('',#34404,.T.); -#34404 = EDGE_LOOP('',(#34405,#34406,#34425,#34426)); -#34405 = ORIENTED_EDGE('',*,*,#30768,.F.); -#34406 = ORIENTED_EDGE('',*,*,#34407,.F.); -#34407 = EDGE_CURVE('',#33708,#30707,#34408,.T.); -#34408 = SURFACE_CURVE('',#34409,(#34413,#34419),.PCURVE_S1.); -#34409 = LINE('',#34410,#34411); -#34410 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); -#34411 = VECTOR('',#34412,1.); -#34412 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34413 = PCURVE('',#30816,#34414); -#34414 = DEFINITIONAL_REPRESENTATION('',(#34415),#34418); -#34415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34416,#34417),.UNSPECIFIED., +#36789 = CARTESIAN_POINT('',(1.,0.E+000)); +#36790 = CARTESIAN_POINT('',(1.,1.)); +#36791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36792 = ORIENTED_EDGE('',*,*,#36044,.T.); +#36793 = ORIENTED_EDGE('',*,*,#36749,.T.); +#36794 = ADVANCED_FACE('',(#36795),#33208,.T.); +#36795 = FACE_BOUND('',#36796,.T.); +#36796 = EDGE_LOOP('',(#36797,#36798,#36817,#36818)); +#36797 = ORIENTED_EDGE('',*,*,#33160,.F.); +#36798 = ORIENTED_EDGE('',*,*,#36799,.F.); +#36799 = EDGE_CURVE('',#36100,#33099,#36800,.T.); +#36800 = SURFACE_CURVE('',#36801,(#36805,#36811),.PCURVE_S1.); +#36801 = LINE('',#36802,#36803); +#36802 = CARTESIAN_POINT('',(-0.116850786128,0.782,-0.328366517613)); +#36803 = VECTOR('',#36804,1.); +#36804 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36805 = PCURVE('',#33208,#36806); +#36806 = DEFINITIONAL_REPRESENTATION('',(#36807),#36810); +#36807 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36808,#36809),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34416 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34417 = CARTESIAN_POINT('',(0.E+000,1.)); -#34418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36808 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36809 = CARTESIAN_POINT('',(0.E+000,1.)); +#36810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34419 = PCURVE('',#30738,#34420); -#34420 = DEFINITIONAL_REPRESENTATION('',(#34421),#34424); -#34421 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34422,#34423),.UNSPECIFIED., +#36811 = PCURVE('',#33130,#36812); +#36812 = DEFINITIONAL_REPRESENTATION('',(#36813),#36816); +#36813 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36814,#36815),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34422 = CARTESIAN_POINT('',(1.,0.E+000)); -#34423 = CARTESIAN_POINT('',(1.,1.)); -#34424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34425 = ORIENTED_EDGE('',*,*,#33707,.T.); -#34426 = ORIENTED_EDGE('',*,*,#34382,.T.); -#34427 = ADVANCED_FACE('',(#34428),#30738,.T.); -#34428 = FACE_BOUND('',#34429,.T.); -#34429 = EDGE_LOOP('',(#34430,#34431,#34450,#34451)); -#34430 = ORIENTED_EDGE('',*,*,#30706,.F.); -#34431 = ORIENTED_EDGE('',*,*,#34432,.F.); -#34432 = EDGE_CURVE('',#33763,#30613,#34433,.T.); -#34433 = SURFACE_CURVE('',#34434,(#34438,#34444),.PCURVE_S1.); -#34434 = LINE('',#34435,#34436); -#34435 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) - ); -#34436 = VECTOR('',#34437,1.); -#34437 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34438 = PCURVE('',#30738,#34439); -#34439 = DEFINITIONAL_REPRESENTATION('',(#34440),#34443); -#34440 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34441,#34442),.UNSPECIFIED., +#36814 = CARTESIAN_POINT('',(1.,0.E+000)); +#36815 = CARTESIAN_POINT('',(1.,1.)); +#36816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36817 = ORIENTED_EDGE('',*,*,#36099,.T.); +#36818 = ORIENTED_EDGE('',*,*,#36774,.T.); +#36819 = ADVANCED_FACE('',(#36820),#33130,.T.); +#36820 = FACE_BOUND('',#36821,.T.); +#36821 = EDGE_LOOP('',(#36822,#36823,#36842,#36843)); +#36822 = ORIENTED_EDGE('',*,*,#33098,.F.); +#36823 = ORIENTED_EDGE('',*,*,#36824,.F.); +#36824 = EDGE_CURVE('',#36155,#33005,#36825,.T.); +#36825 = SURFACE_CURVE('',#36826,(#36830,#36836),.PCURVE_S1.); +#36826 = LINE('',#36827,#36828); +#36827 = CARTESIAN_POINT('',(-7.877875434028E-002,0.782,-0.378734786694) + ); +#36828 = VECTOR('',#36829,1.); +#36829 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36830 = PCURVE('',#33130,#36831); +#36831 = DEFINITIONAL_REPRESENTATION('',(#36832),#36835); +#36832 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36833,#36834),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34441 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34442 = CARTESIAN_POINT('',(0.E+000,1.)); -#34443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36833 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36834 = CARTESIAN_POINT('',(0.E+000,1.)); +#36835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34444 = PCURVE('',#30660,#34445); -#34445 = DEFINITIONAL_REPRESENTATION('',(#34446),#34449); -#34446 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34447,#34448),.UNSPECIFIED., +#36836 = PCURVE('',#33052,#36837); +#36837 = DEFINITIONAL_REPRESENTATION('',(#36838),#36841); +#36838 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36839,#36840),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34447 = CARTESIAN_POINT('',(1.,0.E+000)); -#34448 = CARTESIAN_POINT('',(1.,1.)); -#34449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34450 = ORIENTED_EDGE('',*,*,#33762,.T.); -#34451 = ORIENTED_EDGE('',*,*,#34407,.T.); -#34452 = ADVANCED_FACE('',(#34453),#30660,.T.); -#34453 = FACE_BOUND('',#34454,.T.); -#34454 = EDGE_LOOP('',(#34455,#34456,#34475,#34476)); -#34455 = ORIENTED_EDGE('',*,*,#30612,.F.); -#34456 = ORIENTED_EDGE('',*,*,#34457,.F.); -#34457 = EDGE_CURVE('',#33802,#30519,#34458,.T.); -#34458 = SURFACE_CURVE('',#34459,(#34463,#34469),.PCURVE_S1.); -#34459 = LINE('',#34460,#34461); -#34460 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); -#34461 = VECTOR('',#34462,1.); -#34462 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34463 = PCURVE('',#30660,#34464); -#34464 = DEFINITIONAL_REPRESENTATION('',(#34465),#34468); -#34465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34466,#34467),.UNSPECIFIED., +#36839 = CARTESIAN_POINT('',(1.,0.E+000)); +#36840 = CARTESIAN_POINT('',(1.,1.)); +#36841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36842 = ORIENTED_EDGE('',*,*,#36154,.T.); +#36843 = ORIENTED_EDGE('',*,*,#36799,.T.); +#36844 = ADVANCED_FACE('',(#36845),#33052,.T.); +#36845 = FACE_BOUND('',#36846,.T.); +#36846 = EDGE_LOOP('',(#36847,#36848,#36867,#36868)); +#36847 = ORIENTED_EDGE('',*,*,#33004,.F.); +#36848 = ORIENTED_EDGE('',*,*,#36849,.F.); +#36849 = EDGE_CURVE('',#36194,#32911,#36850,.T.); +#36850 = SURFACE_CURVE('',#36851,(#36855,#36861),.PCURVE_S1.); +#36851 = LINE('',#36852,#36853); +#36852 = CARTESIAN_POINT('',(-0.151630101652,0.782,-0.44433186849)); +#36853 = VECTOR('',#36854,1.); +#36854 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36855 = PCURVE('',#33052,#36856); +#36856 = DEFINITIONAL_REPRESENTATION('',(#36857),#36860); +#36857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36858,#36859),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34466 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34467 = CARTESIAN_POINT('',(0.E+000,1.)); -#34468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36858 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36859 = CARTESIAN_POINT('',(0.E+000,1.)); +#36860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34469 = PCURVE('',#30566,#34470); -#34470 = DEFINITIONAL_REPRESENTATION('',(#34471),#34474); -#34471 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34472,#34473),.UNSPECIFIED., +#36861 = PCURVE('',#32958,#36862); +#36862 = DEFINITIONAL_REPRESENTATION('',(#36863),#36866); +#36863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36864,#36865),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34472 = CARTESIAN_POINT('',(1.,0.E+000)); -#34473 = CARTESIAN_POINT('',(1.,1.)); -#34474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34475 = ORIENTED_EDGE('',*,*,#33801,.T.); -#34476 = ORIENTED_EDGE('',*,*,#34432,.T.); -#34477 = ADVANCED_FACE('',(#34478),#30566,.T.); -#34478 = FACE_BOUND('',#34479,.T.); -#34479 = EDGE_LOOP('',(#34480,#34481,#34500,#34501)); -#34480 = ORIENTED_EDGE('',*,*,#30518,.F.); -#34481 = ORIENTED_EDGE('',*,*,#34482,.F.); -#34482 = EDGE_CURVE('',#33857,#30457,#34483,.T.); -#34483 = SURFACE_CURVE('',#34484,(#34488,#34494),.PCURVE_S1.); -#34484 = LINE('',#34485,#34486); -#34485 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); -#34486 = VECTOR('',#34487,1.); -#34487 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34488 = PCURVE('',#30566,#34489); -#34489 = DEFINITIONAL_REPRESENTATION('',(#34490),#34493); -#34490 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34491,#34492),.UNSPECIFIED., +#36864 = CARTESIAN_POINT('',(1.,0.E+000)); +#36865 = CARTESIAN_POINT('',(1.,1.)); +#36866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36867 = ORIENTED_EDGE('',*,*,#36193,.T.); +#36868 = ORIENTED_EDGE('',*,*,#36824,.T.); +#36869 = ADVANCED_FACE('',(#36870),#32958,.T.); +#36870 = FACE_BOUND('',#36871,.T.); +#36871 = EDGE_LOOP('',(#36872,#36873,#36892,#36893)); +#36872 = ORIENTED_EDGE('',*,*,#32910,.F.); +#36873 = ORIENTED_EDGE('',*,*,#36874,.F.); +#36874 = EDGE_CURVE('',#36249,#32849,#36875,.T.); +#36875 = SURFACE_CURVE('',#36876,(#36880,#36886),.PCURVE_S1.); +#36876 = LINE('',#36877,#36878); +#36877 = CARTESIAN_POINT('',(-0.223658269899,0.782,-0.37955796576)); +#36878 = VECTOR('',#36879,1.); +#36879 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36880 = PCURVE('',#32958,#36881); +#36881 = DEFINITIONAL_REPRESENTATION('',(#36882),#36885); +#36882 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36883,#36884),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34491 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34492 = CARTESIAN_POINT('',(0.E+000,1.)); -#34493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36883 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36884 = CARTESIAN_POINT('',(0.E+000,1.)); +#36885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34494 = PCURVE('',#30488,#34495); -#34495 = DEFINITIONAL_REPRESENTATION('',(#34496),#34499); -#34496 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34497,#34498),.UNSPECIFIED., +#36886 = PCURVE('',#32880,#36887); +#36887 = DEFINITIONAL_REPRESENTATION('',(#36888),#36891); +#36888 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36889,#36890),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34497 = CARTESIAN_POINT('',(1.,0.E+000)); -#34498 = CARTESIAN_POINT('',(1.,1.)); -#34499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34500 = ORIENTED_EDGE('',*,*,#33856,.T.); -#34501 = ORIENTED_EDGE('',*,*,#34457,.T.); -#34502 = ADVANCED_FACE('',(#34503),#30488,.T.); -#34503 = FACE_BOUND('',#34504,.T.); -#34504 = EDGE_LOOP('',(#34505,#34506,#34507,#34508)); -#34505 = ORIENTED_EDGE('',*,*,#30456,.F.); -#34506 = ORIENTED_EDGE('',*,*,#34334,.F.); -#34507 = ORIENTED_EDGE('',*,*,#33911,.T.); -#34508 = ORIENTED_EDGE('',*,*,#34482,.T.); -#34509 = ADVANCED_FACE('',(#34510),#33346,.T.); -#34510 = FACE_BOUND('',#34511,.T.); -#34511 = EDGE_LOOP('',(#34512,#34566,#34585,#34586)); -#34512 = ORIENTED_EDGE('',*,*,#34513,.F.); -#34513 = EDGE_CURVE('',#34514,#34516,#34518,.T.); -#34514 = VERTEX_POINT('',#34515); -#34515 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); -#34516 = VERTEX_POINT('',#34517); -#34517 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); -#34518 = SURFACE_CURVE('',#34519,(#34535,#34542),.PCURVE_S1.); -#34519 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34520,#34521,#34522,#34523, - #34524,#34525,#34526,#34527,#34528,#34529,#34530,#34531,#34532, - #34533,#34534),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#36889 = CARTESIAN_POINT('',(1.,0.E+000)); +#36890 = CARTESIAN_POINT('',(1.,1.)); +#36891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36892 = ORIENTED_EDGE('',*,*,#36248,.T.); +#36893 = ORIENTED_EDGE('',*,*,#36849,.T.); +#36894 = ADVANCED_FACE('',(#36895),#32880,.T.); +#36895 = FACE_BOUND('',#36896,.T.); +#36896 = EDGE_LOOP('',(#36897,#36898,#36899,#36900)); +#36897 = ORIENTED_EDGE('',*,*,#32848,.F.); +#36898 = ORIENTED_EDGE('',*,*,#36726,.F.); +#36899 = ORIENTED_EDGE('',*,*,#36303,.T.); +#36900 = ORIENTED_EDGE('',*,*,#36874,.T.); +#36901 = ADVANCED_FACE('',(#36902),#35738,.T.); +#36902 = FACE_BOUND('',#36903,.T.); +#36903 = EDGE_LOOP('',(#36904,#36958,#36977,#36978)); +#36904 = ORIENTED_EDGE('',*,*,#36905,.F.); +#36905 = EDGE_CURVE('',#36906,#36908,#36910,.T.); +#36906 = VERTEX_POINT('',#36907); +#36907 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); +#36908 = VERTEX_POINT('',#36909); +#36909 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); +#36910 = SURFACE_CURVE('',#36911,(#36927,#36934),.PCURVE_S1.); +#36911 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36912,#36913,#36914,#36915, + #36916,#36917,#36918,#36919,#36920,#36921,#36922,#36923,#36924, + #36925,#36926),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.623586740752E-002,0.148618099954,0.218239428141, 0.284251690269,0.348257520785,0.41065620425,0.472862373, 0.534194748022,0.653476101422,0.767766789522,0.881712609467,1.), .UNSPECIFIED.); -#34520 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); -#34521 = CARTESIAN_POINT('',(-0.152729777306,0.78,-0.414676353545)); -#34522 = CARTESIAN_POINT('',(-0.155675914972,0.78,-0.414635281378)); -#34523 = CARTESIAN_POINT('',(-0.159966976294,0.78,-0.41406634463)); -#34524 = CARTESIAN_POINT('',(-0.164028697593,0.78,-0.413351771644)); -#34525 = CARTESIAN_POINT('',(-0.167823606873,0.78,-0.412205014228)); -#34526 = CARTESIAN_POINT('',(-0.171335929925,0.78,-0.410706468873)); -#34527 = CARTESIAN_POINT('',(-0.174602353061,0.78,-0.408882707038)); -#34528 = CARTESIAN_POINT('',(-0.177647122399,0.78,-0.406795757015)); -#34529 = CARTESIAN_POINT('',(-0.18123776941,0.78,-0.40358139709)); -#34530 = CARTESIAN_POINT('',(-0.184998380579,0.78,-0.399058532957)); -#34531 = CARTESIAN_POINT('',(-0.188311373258,0.78,-0.392982728043)); -#34532 = CARTESIAN_POINT('',(-0.190358909926,0.78,-0.386358050111)); -#34533 = CARTESIAN_POINT('',(-0.190605504803,0.78,-0.381750475834)); -#34534 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); -#34535 = PCURVE('',#33346,#34536); -#34536 = DEFINITIONAL_REPRESENTATION('',(#34537),#34541); -#34537 = LINE('',#34538,#34539); -#34538 = CARTESIAN_POINT('',(0.E+000,1.)); -#34539 = VECTOR('',#34540,1.); -#34540 = DIRECTION('',(1.,0.E+000)); -#34541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34542 = PCURVE('',#34543,#34548); -#34543 = PLANE('',#34544); -#34544 = AXIS2_PLACEMENT_3D('',#34545,#34546,#34547); -#34545 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#34546 = DIRECTION('',(0.E+000,1.,0.E+000)); -#34547 = DIRECTION('',(0.E+000,0.E+000,1.)); -#34548 = DEFINITIONAL_REPRESENTATION('',(#34549),#34565); -#34549 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34550,#34551,#34552,#34553, - #34554,#34555,#34556,#34557,#34558,#34559,#34560,#34561,#34562, - #34563,#34564),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#36912 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); +#36913 = CARTESIAN_POINT('',(-0.152729777306,0.78,-0.414676353545)); +#36914 = CARTESIAN_POINT('',(-0.155675914972,0.78,-0.414635281378)); +#36915 = CARTESIAN_POINT('',(-0.159966976294,0.78,-0.41406634463)); +#36916 = CARTESIAN_POINT('',(-0.164028697593,0.78,-0.413351771644)); +#36917 = CARTESIAN_POINT('',(-0.167823606873,0.78,-0.412205014228)); +#36918 = CARTESIAN_POINT('',(-0.171335929925,0.78,-0.410706468873)); +#36919 = CARTESIAN_POINT('',(-0.174602353061,0.78,-0.408882707038)); +#36920 = CARTESIAN_POINT('',(-0.177647122399,0.78,-0.406795757015)); +#36921 = CARTESIAN_POINT('',(-0.18123776941,0.78,-0.40358139709)); +#36922 = CARTESIAN_POINT('',(-0.184998380579,0.78,-0.399058532957)); +#36923 = CARTESIAN_POINT('',(-0.188311373258,0.78,-0.392982728043)); +#36924 = CARTESIAN_POINT('',(-0.190358909926,0.78,-0.386358050111)); +#36925 = CARTESIAN_POINT('',(-0.190605504803,0.78,-0.381750475834)); +#36926 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); +#36927 = PCURVE('',#35738,#36928); +#36928 = DEFINITIONAL_REPRESENTATION('',(#36929),#36933); +#36929 = LINE('',#36930,#36931); +#36930 = CARTESIAN_POINT('',(0.E+000,1.)); +#36931 = VECTOR('',#36932,1.); +#36932 = DIRECTION('',(1.,0.E+000)); +#36933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36934 = PCURVE('',#36935,#36940); +#36935 = PLANE('',#36936); +#36936 = AXIS2_PLACEMENT_3D('',#36937,#36938,#36939); +#36937 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#36938 = DIRECTION('',(0.E+000,1.,0.E+000)); +#36939 = DIRECTION('',(0.E+000,0.E+000,1.)); +#36940 = DEFINITIONAL_REPRESENTATION('',(#36941),#36957); +#36941 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36942,#36943,#36944,#36945, + #36946,#36947,#36948,#36949,#36950,#36951,#36952,#36953,#36954, + #36955,#36956),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.623586740752E-002,0.148618099954,0.218239428141, 0.284251690269,0.348257520785,0.41065620425,0.472862373, 0.534194748022,0.653476101422,0.767766789522,0.881712609467,1.), .UNSPECIFIED.); -#34550 = CARTESIAN_POINT('',(-1.039697422125,0.848781487881)); -#34551 = CARTESIAN_POINT('',(-1.039676353545,0.847270222694)); -#34552 = CARTESIAN_POINT('',(-1.039635281378,0.844324085028)); -#34553 = CARTESIAN_POINT('',(-1.03906634463,0.840033023706)); -#34554 = CARTESIAN_POINT('',(-1.038351771644,0.835971302407)); -#34555 = CARTESIAN_POINT('',(-1.037205014228,0.832176393127)); -#34556 = CARTESIAN_POINT('',(-1.035706468873,0.828664070075)); -#34557 = CARTESIAN_POINT('',(-1.033882707038,0.825397646939)); -#34558 = CARTESIAN_POINT('',(-1.031795757015,0.822352877601)); -#34559 = CARTESIAN_POINT('',(-1.02858139709,0.81876223059)); -#34560 = CARTESIAN_POINT('',(-1.024058532957,0.815001619421)); -#34561 = CARTESIAN_POINT('',(-1.017982728043,0.811688626742)); -#34562 = CARTESIAN_POINT('',(-1.011358050111,0.809641090074)); -#34563 = CARTESIAN_POINT('',(-1.006750475834,0.809394495197)); -#34564 = CARTESIAN_POINT('',(-1.004403619685,0.809268892728)); -#34565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34566 = ORIENTED_EDGE('',*,*,#34567,.F.); -#34567 = EDGE_CURVE('',#33307,#34514,#34568,.T.); -#34568 = SURFACE_CURVE('',#34569,(#34573,#34579),.PCURVE_S1.); -#34569 = LINE('',#34570,#34571); -#34570 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); -#34571 = VECTOR('',#34572,1.); -#34572 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34573 = PCURVE('',#33346,#34574); -#34574 = DEFINITIONAL_REPRESENTATION('',(#34575),#34578); -#34575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34576,#34577),.UNSPECIFIED., +#36942 = CARTESIAN_POINT('',(-1.039697422125,0.848781487881)); +#36943 = CARTESIAN_POINT('',(-1.039676353545,0.847270222694)); +#36944 = CARTESIAN_POINT('',(-1.039635281378,0.844324085028)); +#36945 = CARTESIAN_POINT('',(-1.03906634463,0.840033023706)); +#36946 = CARTESIAN_POINT('',(-1.038351771644,0.835971302407)); +#36947 = CARTESIAN_POINT('',(-1.037205014228,0.832176393127)); +#36948 = CARTESIAN_POINT('',(-1.035706468873,0.828664070075)); +#36949 = CARTESIAN_POINT('',(-1.033882707038,0.825397646939)); +#36950 = CARTESIAN_POINT('',(-1.031795757015,0.822352877601)); +#36951 = CARTESIAN_POINT('',(-1.02858139709,0.81876223059)); +#36952 = CARTESIAN_POINT('',(-1.024058532957,0.815001619421)); +#36953 = CARTESIAN_POINT('',(-1.017982728043,0.811688626742)); +#36954 = CARTESIAN_POINT('',(-1.011358050111,0.809641090074)); +#36955 = CARTESIAN_POINT('',(-1.006750475834,0.809394495197)); +#36956 = CARTESIAN_POINT('',(-1.004403619685,0.809268892728)); +#36957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36958 = ORIENTED_EDGE('',*,*,#36959,.F.); +#36959 = EDGE_CURVE('',#35699,#36906,#36960,.T.); +#36960 = SURFACE_CURVE('',#36961,(#36965,#36971),.PCURVE_S1.); +#36961 = LINE('',#36962,#36963); +#36962 = CARTESIAN_POINT('',(-0.151218512119,0.782,-0.414697422125)); +#36963 = VECTOR('',#36964,1.); +#36964 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36965 = PCURVE('',#35738,#36966); +#36966 = DEFINITIONAL_REPRESENTATION('',(#36967),#36970); +#36967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36968,#36969),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34577 = CARTESIAN_POINT('',(0.E+000,1.)); -#34578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36968 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36969 = CARTESIAN_POINT('',(0.E+000,1.)); +#36970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34579 = PCURVE('',#33424,#34580); -#34580 = DEFINITIONAL_REPRESENTATION('',(#34581),#34584); -#34581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34582,#34583),.UNSPECIFIED., +#36971 = PCURVE('',#35816,#36972); +#36972 = DEFINITIONAL_REPRESENTATION('',(#36973),#36976); +#36973 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36974,#36975),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34582 = CARTESIAN_POINT('',(1.,0.E+000)); -#34583 = CARTESIAN_POINT('',(1.,1.)); -#34584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34585 = ORIENTED_EDGE('',*,*,#33306,.T.); -#34586 = ORIENTED_EDGE('',*,*,#34587,.T.); -#34587 = EDGE_CURVE('',#33222,#34516,#34588,.T.); -#34588 = SURFACE_CURVE('',#34589,(#34593,#34599),.PCURVE_S1.); -#34589 = LINE('',#34590,#34591); -#34590 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); -#34591 = VECTOR('',#34592,1.); -#34592 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34593 = PCURVE('',#33346,#34594); -#34594 = DEFINITIONAL_REPRESENTATION('',(#34595),#34598); -#34595 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34596,#34597),.UNSPECIFIED., +#36974 = CARTESIAN_POINT('',(1.,0.E+000)); +#36975 = CARTESIAN_POINT('',(1.,1.)); +#36976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36977 = ORIENTED_EDGE('',*,*,#35698,.T.); +#36978 = ORIENTED_EDGE('',*,*,#36979,.T.); +#36979 = EDGE_CURVE('',#35614,#36908,#36980,.T.); +#36980 = SURFACE_CURVE('',#36981,(#36985,#36991),.PCURVE_S1.); +#36981 = LINE('',#36982,#36983); +#36982 = CARTESIAN_POINT('',(-0.190731107272,0.782,-0.379403619685)); +#36983 = VECTOR('',#36984,1.); +#36984 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#36985 = PCURVE('',#35738,#36986); +#36986 = DEFINITIONAL_REPRESENTATION('',(#36987),#36990); +#36987 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36988,#36989),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34596 = CARTESIAN_POINT('',(1.,0.E+000)); -#34597 = CARTESIAN_POINT('',(1.,1.)); -#34598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#36988 = CARTESIAN_POINT('',(1.,0.E+000)); +#36989 = CARTESIAN_POINT('',(1.,1.)); +#36990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34599 = PCURVE('',#33268,#34600); -#34600 = DEFINITIONAL_REPRESENTATION('',(#34601),#34604); -#34601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34602,#34603),.UNSPECIFIED., +#36991 = PCURVE('',#35660,#36992); +#36992 = DEFINITIONAL_REPRESENTATION('',(#36993),#36996); +#36993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36994,#36995),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34602 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34603 = CARTESIAN_POINT('',(0.E+000,1.)); -#34604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34605 = ADVANCED_FACE('',(#34606),#33268,.T.); -#34606 = FACE_BOUND('',#34607,.T.); -#34607 = EDGE_LOOP('',(#34608,#34655,#34656,#34657)); -#34608 = ORIENTED_EDGE('',*,*,#34609,.F.); -#34609 = EDGE_CURVE('',#34516,#34610,#34612,.T.); -#34610 = VERTEX_POINT('',#34611); -#34611 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); -#34612 = SURFACE_CURVE('',#34613,(#34629,#34636),.PCURVE_S1.); -#34613 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34614,#34615,#34616,#34617, - #34618,#34619,#34620,#34621,#34622,#34623,#34624,#34625,#34626, - #34627,#34628),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#36994 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#36995 = CARTESIAN_POINT('',(0.E+000,1.)); +#36996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#36997 = ADVANCED_FACE('',(#36998),#35660,.T.); +#36998 = FACE_BOUND('',#36999,.T.); +#36999 = EDGE_LOOP('',(#37000,#37047,#37048,#37049)); +#37000 = ORIENTED_EDGE('',*,*,#37001,.F.); +#37001 = EDGE_CURVE('',#36908,#37002,#37004,.T.); +#37002 = VERTEX_POINT('',#37003); +#37003 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); +#37004 = SURFACE_CURVE('',#37005,(#37021,#37028),.PCURVE_S1.); +#37005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37006,#37007,#37008,#37009, + #37010,#37011,#37012,#37013,#37014,#37015,#37016,#37017,#37018, + #37019,#37020),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.127393941339,0.246181611293,0.361268004354,0.477140268037, 0.536326583436,0.595671915044,0.656618953206,0.718835621496, 0.783581552706,0.851587816689,0.923926527481,1.),.UNSPECIFIED.); -#34614 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); -#34615 = CARTESIAN_POINT('',(-0.190633379827,0.78,-0.376782386698)); -#34616 = CARTESIAN_POINT('',(-0.19044452705,0.78,-0.371717001692)); -#34617 = CARTESIAN_POINT('',(-0.188390732865,0.78,-0.364521993412)); -#34618 = CARTESIAN_POINT('',(-0.185179194788,0.78,-0.358058858245)); -#34619 = CARTESIAN_POINT('',(-0.181414230001,0.78,-0.353371942249)); -#34620 = CARTESIAN_POINT('',(-0.177804574294,0.78,-0.350178503967)); -#34621 = CARTESIAN_POINT('',(-0.17479181951,0.78,-0.348046358697)); -#34622 = CARTESIAN_POINT('',(-0.171499461141,0.78,-0.346236210411)); -#34623 = CARTESIAN_POINT('',(-0.167903647571,0.78,-0.344829249004)); -#34624 = CARTESIAN_POINT('',(-0.164091469566,0.78,-0.343582768799)); -#34625 = CARTESIAN_POINT('',(-0.159931450534,0.78,-0.342886076981)); -#34626 = CARTESIAN_POINT('',(-0.155521369245,0.78,-0.342319707935)); -#34627 = CARTESIAN_POINT('',(-0.152472577135,0.78,-0.342278689615)); -#34628 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); -#34629 = PCURVE('',#33268,#34630); -#34630 = DEFINITIONAL_REPRESENTATION('',(#34631),#34635); -#34631 = LINE('',#34632,#34633); -#34632 = CARTESIAN_POINT('',(0.E+000,1.)); -#34633 = VECTOR('',#34634,1.); -#34634 = DIRECTION('',(1.,0.E+000)); -#34635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34636 = PCURVE('',#34543,#34637); -#34637 = DEFINITIONAL_REPRESENTATION('',(#34638),#34654); -#34638 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34639,#34640,#34641,#34642, - #34643,#34644,#34645,#34646,#34647,#34648,#34649,#34650,#34651, - #34652,#34653),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37006 = CARTESIAN_POINT('',(-0.190731107272,0.78,-0.379403619685)); +#37007 = CARTESIAN_POINT('',(-0.190633379827,0.78,-0.376782386698)); +#37008 = CARTESIAN_POINT('',(-0.19044452705,0.78,-0.371717001692)); +#37009 = CARTESIAN_POINT('',(-0.188390732865,0.78,-0.364521993412)); +#37010 = CARTESIAN_POINT('',(-0.185179194788,0.78,-0.358058858245)); +#37011 = CARTESIAN_POINT('',(-0.181414230001,0.78,-0.353371942249)); +#37012 = CARTESIAN_POINT('',(-0.177804574294,0.78,-0.350178503967)); +#37013 = CARTESIAN_POINT('',(-0.17479181951,0.78,-0.348046358697)); +#37014 = CARTESIAN_POINT('',(-0.171499461141,0.78,-0.346236210411)); +#37015 = CARTESIAN_POINT('',(-0.167903647571,0.78,-0.344829249004)); +#37016 = CARTESIAN_POINT('',(-0.164091469566,0.78,-0.343582768799)); +#37017 = CARTESIAN_POINT('',(-0.159931450534,0.78,-0.342886076981)); +#37018 = CARTESIAN_POINT('',(-0.155521369245,0.78,-0.342319707935)); +#37019 = CARTESIAN_POINT('',(-0.152472577135,0.78,-0.342278689615)); +#37020 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); +#37021 = PCURVE('',#35660,#37022); +#37022 = DEFINITIONAL_REPRESENTATION('',(#37023),#37027); +#37023 = LINE('',#37024,#37025); +#37024 = CARTESIAN_POINT('',(0.E+000,1.)); +#37025 = VECTOR('',#37026,1.); +#37026 = DIRECTION('',(1.,0.E+000)); +#37027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37028 = PCURVE('',#36935,#37029); +#37029 = DEFINITIONAL_REPRESENTATION('',(#37030),#37046); +#37030 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37031,#37032,#37033,#37034, + #37035,#37036,#37037,#37038,#37039,#37040,#37041,#37042,#37043, + #37044,#37045),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.127393941339,0.246181611293,0.361268004354,0.477140268037, 0.536326583436,0.595671915044,0.656618953206,0.718835621496, 0.783581552706,0.851587816689,0.923926527481,1.),.UNSPECIFIED.); -#34639 = CARTESIAN_POINT('',(-1.004403619685,0.809268892728)); -#34640 = CARTESIAN_POINT('',(-1.001782386698,0.809366620173)); -#34641 = CARTESIAN_POINT('',(-0.996717001692,0.80955547295)); -#34642 = CARTESIAN_POINT('',(-0.989521993412,0.811609267135)); -#34643 = CARTESIAN_POINT('',(-0.983058858245,0.814820805212)); -#34644 = CARTESIAN_POINT('',(-0.978371942249,0.818585769999)); -#34645 = CARTESIAN_POINT('',(-0.975178503967,0.822195425706)); -#34646 = CARTESIAN_POINT('',(-0.973046358697,0.82520818049)); -#34647 = CARTESIAN_POINT('',(-0.971236210411,0.828500538859)); -#34648 = CARTESIAN_POINT('',(-0.969829249004,0.832096352429)); -#34649 = CARTESIAN_POINT('',(-0.968582768799,0.835908530434)); -#34650 = CARTESIAN_POINT('',(-0.967886076981,0.840068549466)); -#34651 = CARTESIAN_POINT('',(-0.967319707935,0.844478630755)); -#34652 = CARTESIAN_POINT('',(-0.967278689615,0.847527422865)); -#34653 = CARTESIAN_POINT('',(-0.967257664346,0.84909018003)); -#34654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34655 = ORIENTED_EDGE('',*,*,#34587,.F.); -#34656 = ORIENTED_EDGE('',*,*,#33221,.T.); -#34657 = ORIENTED_EDGE('',*,*,#34658,.T.); -#34658 = EDGE_CURVE('',#33224,#34610,#34659,.T.); -#34659 = SURFACE_CURVE('',#34660,(#34664,#34670),.PCURVE_S1.); -#34660 = LINE('',#34661,#34662); -#34661 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); -#34662 = VECTOR('',#34663,1.); -#34663 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34664 = PCURVE('',#33268,#34665); -#34665 = DEFINITIONAL_REPRESENTATION('',(#34666),#34669); -#34666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34667,#34668),.UNSPECIFIED., +#37031 = CARTESIAN_POINT('',(-1.004403619685,0.809268892728)); +#37032 = CARTESIAN_POINT('',(-1.001782386698,0.809366620173)); +#37033 = CARTESIAN_POINT('',(-0.996717001692,0.80955547295)); +#37034 = CARTESIAN_POINT('',(-0.989521993412,0.811609267135)); +#37035 = CARTESIAN_POINT('',(-0.983058858245,0.814820805212)); +#37036 = CARTESIAN_POINT('',(-0.978371942249,0.818585769999)); +#37037 = CARTESIAN_POINT('',(-0.975178503967,0.822195425706)); +#37038 = CARTESIAN_POINT('',(-0.973046358697,0.82520818049)); +#37039 = CARTESIAN_POINT('',(-0.971236210411,0.828500538859)); +#37040 = CARTESIAN_POINT('',(-0.969829249004,0.832096352429)); +#37041 = CARTESIAN_POINT('',(-0.968582768799,0.835908530434)); +#37042 = CARTESIAN_POINT('',(-0.967886076981,0.840068549466)); +#37043 = CARTESIAN_POINT('',(-0.967319707935,0.844478630755)); +#37044 = CARTESIAN_POINT('',(-0.967278689615,0.847527422865)); +#37045 = CARTESIAN_POINT('',(-0.967257664346,0.84909018003)); +#37046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37047 = ORIENTED_EDGE('',*,*,#36979,.F.); +#37048 = ORIENTED_EDGE('',*,*,#35613,.T.); +#37049 = ORIENTED_EDGE('',*,*,#37050,.T.); +#37050 = EDGE_CURVE('',#35616,#37002,#37051,.T.); +#37051 = SURFACE_CURVE('',#37052,(#37056,#37062),.PCURVE_S1.); +#37052 = LINE('',#37053,#37054); +#37053 = CARTESIAN_POINT('',(-0.15090981997,0.782,-0.342257664346)); +#37054 = VECTOR('',#37055,1.); +#37055 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37056 = PCURVE('',#35660,#37057); +#37057 = DEFINITIONAL_REPRESENTATION('',(#37058),#37061); +#37058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37059,#37060),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34667 = CARTESIAN_POINT('',(1.,0.E+000)); -#34668 = CARTESIAN_POINT('',(1.,1.)); -#34669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37059 = CARTESIAN_POINT('',(1.,0.E+000)); +#37060 = CARTESIAN_POINT('',(1.,1.)); +#37061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34670 = PCURVE('',#33500,#34671); -#34671 = DEFINITIONAL_REPRESENTATION('',(#34672),#34675); -#34672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34673,#34674),.UNSPECIFIED., +#37062 = PCURVE('',#35892,#37063); +#37063 = DEFINITIONAL_REPRESENTATION('',(#37064),#37067); +#37064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37065,#37066),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34674 = CARTESIAN_POINT('',(0.E+000,1.)); -#34675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34676 = ADVANCED_FACE('',(#34677),#33500,.T.); -#34677 = FACE_BOUND('',#34678,.T.); -#34678 = EDGE_LOOP('',(#34679,#34726,#34727,#34728)); -#34679 = ORIENTED_EDGE('',*,*,#34680,.F.); -#34680 = EDGE_CURVE('',#34610,#34681,#34683,.T.); -#34681 = VERTEX_POINT('',#34682); -#34682 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); -#34683 = SURFACE_CURVE('',#34684,(#34700,#34707),.PCURVE_S1.); -#34684 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34685,#34686,#34687,#34688, - #34689,#34690,#34691,#34692,#34693,#34694,#34695,#34696,#34697, - #34698,#34699),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37066 = CARTESIAN_POINT('',(0.E+000,1.)); +#37067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37068 = ADVANCED_FACE('',(#37069),#35892,.T.); +#37069 = FACE_BOUND('',#37070,.T.); +#37070 = EDGE_LOOP('',(#37071,#37118,#37119,#37120)); +#37071 = ORIENTED_EDGE('',*,*,#37072,.F.); +#37072 = EDGE_CURVE('',#37002,#37073,#37075,.T.); +#37073 = VERTEX_POINT('',#37074); +#37074 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); +#37075 = SURFACE_CURVE('',#37076,(#37092,#37099),.PCURVE_S1.); +#37076 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37077,#37078,#37079,#37080, + #37081,#37082,#37083,#37084,#37085,#37086,#37087,#37088,#37089, + #37090,#37091),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.684269792878E-002,0.149839053285,0.218379396445, 0.284997020701,0.347657670814,0.409847159115,0.469935761508, 0.530419606657,0.648751736026,0.763774893077,0.878749487778,1.), .UNSPECIFIED.); -#34685 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); -#34686 = CARTESIAN_POINT('',(-0.149381559204,0.78,-0.342279466551)); -#34687 = CARTESIAN_POINT('',(-0.146401534394,0.78,-0.342321979656)); -#34688 = CARTESIAN_POINT('',(-0.142090778599,0.78,-0.342876802095)); -#34689 = CARTESIAN_POINT('',(-0.138017129395,0.78,-0.343617819681)); -#34690 = CARTESIAN_POINT('',(-0.134240783365,0.78,-0.34474071794)); -#34691 = CARTESIAN_POINT('',(-0.130718142787,0.78,-0.346200813163)); -#34692 = CARTESIAN_POINT('',(-0.127506501884,0.78,-0.348000750153)); -#34693 = CARTESIAN_POINT('',(-0.124509752925,0.78,-0.350069394279)); -#34694 = CARTESIAN_POINT('',(-0.121006135521,0.78,-0.353287230249)); -#34695 = CARTESIAN_POINT('',(-0.11724636631,0.78,-0.357809991944)); -#34696 = CARTESIAN_POINT('',(-0.114024065579,0.78,-0.363984409633)); -#34697 = CARTESIAN_POINT('',(-0.112016064922,0.78,-0.370739589242)); -#34698 = CARTESIAN_POINT('',(-0.111811114626,0.78,-0.37544496563)); -#34699 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); -#34700 = PCURVE('',#33500,#34701); -#34701 = DEFINITIONAL_REPRESENTATION('',(#34702),#34706); -#34702 = LINE('',#34703,#34704); -#34703 = CARTESIAN_POINT('',(0.E+000,1.)); -#34704 = VECTOR('',#34705,1.); -#34705 = DIRECTION('',(1.,0.E+000)); -#34706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34707 = PCURVE('',#34543,#34708); -#34708 = DEFINITIONAL_REPRESENTATION('',(#34709),#34725); -#34709 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34710,#34711,#34712,#34713, - #34714,#34715,#34716,#34717,#34718,#34719,#34720,#34721,#34722, - #34723,#34724),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37077 = CARTESIAN_POINT('',(-0.15090981997,0.78,-0.342257664346)); +#37078 = CARTESIAN_POINT('',(-0.149381559204,0.78,-0.342279466551)); +#37079 = CARTESIAN_POINT('',(-0.146401534394,0.78,-0.342321979656)); +#37080 = CARTESIAN_POINT('',(-0.142090778599,0.78,-0.342876802095)); +#37081 = CARTESIAN_POINT('',(-0.138017129395,0.78,-0.343617819681)); +#37082 = CARTESIAN_POINT('',(-0.134240783365,0.78,-0.34474071794)); +#37083 = CARTESIAN_POINT('',(-0.130718142787,0.78,-0.346200813163)); +#37084 = CARTESIAN_POINT('',(-0.127506501884,0.78,-0.348000750153)); +#37085 = CARTESIAN_POINT('',(-0.124509752925,0.78,-0.350069394279)); +#37086 = CARTESIAN_POINT('',(-0.121006135521,0.78,-0.353287230249)); +#37087 = CARTESIAN_POINT('',(-0.11724636631,0.78,-0.357809991944)); +#37088 = CARTESIAN_POINT('',(-0.114024065579,0.78,-0.363984409633)); +#37089 = CARTESIAN_POINT('',(-0.112016064922,0.78,-0.370739589242)); +#37090 = CARTESIAN_POINT('',(-0.111811114626,0.78,-0.37544496563)); +#37091 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); +#37092 = PCURVE('',#35892,#37093); +#37093 = DEFINITIONAL_REPRESENTATION('',(#37094),#37098); +#37094 = LINE('',#37095,#37096); +#37095 = CARTESIAN_POINT('',(0.E+000,1.)); +#37096 = VECTOR('',#37097,1.); +#37097 = DIRECTION('',(1.,0.E+000)); +#37098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37099 = PCURVE('',#36935,#37100); +#37100 = DEFINITIONAL_REPRESENTATION('',(#37101),#37117); +#37101 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37102,#37103,#37104,#37105, + #37106,#37107,#37108,#37109,#37110,#37111,#37112,#37113,#37114, + #37115,#37116),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.684269792878E-002,0.149839053285,0.218379396445, 0.284997020701,0.347657670814,0.409847159115,0.469935761508, 0.530419606657,0.648751736026,0.763774893077,0.878749487778,1.), .UNSPECIFIED.); -#34710 = CARTESIAN_POINT('',(-0.967257664346,0.84909018003)); -#34711 = CARTESIAN_POINT('',(-0.967279466551,0.850618440796)); -#34712 = CARTESIAN_POINT('',(-0.967321979656,0.853598465606)); -#34713 = CARTESIAN_POINT('',(-0.967876802095,0.857909221401)); -#34714 = CARTESIAN_POINT('',(-0.968617819681,0.861982870605)); -#34715 = CARTESIAN_POINT('',(-0.96974071794,0.865759216635)); -#34716 = CARTESIAN_POINT('',(-0.971200813163,0.869281857213)); -#34717 = CARTESIAN_POINT('',(-0.973000750153,0.872493498116)); -#34718 = CARTESIAN_POINT('',(-0.975069394279,0.875490247075)); -#34719 = CARTESIAN_POINT('',(-0.978287230249,0.878993864479)); -#34720 = CARTESIAN_POINT('',(-0.982809991944,0.88275363369)); -#34721 = CARTESIAN_POINT('',(-0.988984409633,0.885975934421)); -#34722 = CARTESIAN_POINT('',(-0.995739589242,0.887983935078)); -#34723 = CARTESIAN_POINT('',(-1.00044496563,0.888188885374)); -#34724 = CARTESIAN_POINT('',(-1.002860158937,0.888294083033)); -#34725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34726 = ORIENTED_EDGE('',*,*,#34658,.F.); -#34727 = ORIENTED_EDGE('',*,*,#33462,.T.); -#34728 = ORIENTED_EDGE('',*,*,#34729,.T.); -#34729 = EDGE_CURVE('',#33385,#34681,#34730,.T.); -#34730 = SURFACE_CURVE('',#34731,(#34735,#34741),.PCURVE_S1.); -#34731 = LINE('',#34732,#34733); -#34732 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); -#34733 = VECTOR('',#34734,1.); -#34734 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34735 = PCURVE('',#33500,#34736); -#34736 = DEFINITIONAL_REPRESENTATION('',(#34737),#34740); -#34737 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34738,#34739),.UNSPECIFIED., +#37102 = CARTESIAN_POINT('',(-0.967257664346,0.84909018003)); +#37103 = CARTESIAN_POINT('',(-0.967279466551,0.850618440796)); +#37104 = CARTESIAN_POINT('',(-0.967321979656,0.853598465606)); +#37105 = CARTESIAN_POINT('',(-0.967876802095,0.857909221401)); +#37106 = CARTESIAN_POINT('',(-0.968617819681,0.861982870605)); +#37107 = CARTESIAN_POINT('',(-0.96974071794,0.865759216635)); +#37108 = CARTESIAN_POINT('',(-0.971200813163,0.869281857213)); +#37109 = CARTESIAN_POINT('',(-0.973000750153,0.872493498116)); +#37110 = CARTESIAN_POINT('',(-0.975069394279,0.875490247075)); +#37111 = CARTESIAN_POINT('',(-0.978287230249,0.878993864479)); +#37112 = CARTESIAN_POINT('',(-0.982809991944,0.88275363369)); +#37113 = CARTESIAN_POINT('',(-0.988984409633,0.885975934421)); +#37114 = CARTESIAN_POINT('',(-0.995739589242,0.887983935078)); +#37115 = CARTESIAN_POINT('',(-1.00044496563,0.888188885374)); +#37116 = CARTESIAN_POINT('',(-1.002860158937,0.888294083033)); +#37117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37118 = ORIENTED_EDGE('',*,*,#37050,.F.); +#37119 = ORIENTED_EDGE('',*,*,#35854,.T.); +#37120 = ORIENTED_EDGE('',*,*,#37121,.T.); +#37121 = EDGE_CURVE('',#35777,#37073,#37122,.T.); +#37122 = SURFACE_CURVE('',#37123,(#37127,#37133),.PCURVE_S1.); +#37123 = LINE('',#37124,#37125); +#37124 = CARTESIAN_POINT('',(-0.111705916967,0.782,-0.377860158937)); +#37125 = VECTOR('',#37126,1.); +#37126 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37127 = PCURVE('',#35892,#37128); +#37128 = DEFINITIONAL_REPRESENTATION('',(#37129),#37132); +#37129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37130,#37131),.UNSPECIFIED., .F.,.F.,(2,2),(2.22044604925E-016,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34738 = CARTESIAN_POINT('',(1.,0.E+000)); -#34739 = CARTESIAN_POINT('',(1.,1.)); -#34740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37130 = CARTESIAN_POINT('',(1.,0.E+000)); +#37131 = CARTESIAN_POINT('',(1.,1.)); +#37132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34741 = PCURVE('',#33424,#34742); -#34742 = DEFINITIONAL_REPRESENTATION('',(#34743),#34746); -#34743 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34744,#34745),.UNSPECIFIED., +#37133 = PCURVE('',#35816,#37134); +#37134 = DEFINITIONAL_REPRESENTATION('',(#37135),#37138); +#37135 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37136,#37137),.UNSPECIFIED., .F.,.F.,(2,2),(2.22044604925E-016,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34744 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34745 = CARTESIAN_POINT('',(0.E+000,1.)); -#34746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34747 = ADVANCED_FACE('',(#34748),#33424,.T.); -#34748 = FACE_BOUND('',#34749,.T.); -#34749 = EDGE_LOOP('',(#34750,#34795,#34796,#34797)); -#34750 = ORIENTED_EDGE('',*,*,#34751,.F.); -#34751 = EDGE_CURVE('',#34681,#34514,#34752,.T.); -#34752 = SURFACE_CURVE('',#34753,(#34769,#34776),.PCURVE_S1.); -#34753 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34754,#34755,#34756,#34757, - #34758,#34759,#34760,#34761,#34762,#34763,#34764,#34765,#34766, - #34767,#34768),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37136 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37137 = CARTESIAN_POINT('',(0.E+000,1.)); +#37138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37139 = ADVANCED_FACE('',(#37140),#35816,.T.); +#37140 = FACE_BOUND('',#37141,.T.); +#37141 = EDGE_LOOP('',(#37142,#37187,#37188,#37189)); +#37142 = ORIENTED_EDGE('',*,*,#37143,.F.); +#37143 = EDGE_CURVE('',#37073,#36906,#37144,.T.); +#37144 = SURFACE_CURVE('',#37145,(#37161,#37168),.PCURVE_S1.); +#37145 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37146,#37147,#37148,#37149, + #37150,#37151,#37152,#37153,#37154,#37155,#37156,#37157,#37158, + #37159,#37160),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.123386121363,0.241434686423,0.357448546151,0.476713920453, 0.537889586874,0.59927039383,0.660352052257,0.723006936299, 0.787875537201,0.855360105861,0.925373213756,1.),.UNSPECIFIED.); -#34754 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); -#34755 = CARTESIAN_POINT('',(-0.111832665366,0.78,-0.38035978059)); -#34756 = CARTESIAN_POINT('',(-0.112080679158,0.78,-0.385250892843)); -#34757 = CARTESIAN_POINT('',(-0.114083774905,0.78,-0.392272304946)); -#34758 = CARTESIAN_POINT('',(-0.117456162002,0.78,-0.398631607373)); -#34759 = CARTESIAN_POINT('',(-0.121308646739,0.78,-0.40327571587)); -#34760 = CARTESIAN_POINT('',(-0.12487424297,0.78,-0.406640099038)); -#34761 = CARTESIAN_POINT('',(-0.127924792318,0.78,-0.408781754244)); -#34762 = CARTESIAN_POINT('',(-0.13120414428,0.78,-0.410604492294)); -#34763 = CARTESIAN_POINT('',(-0.134724780019,0.78,-0.412093003298)); -#34764 = CARTESIAN_POINT('',(-0.138491790595,0.78,-0.413293502917)); -#34765 = CARTESIAN_POINT('',(-0.142515380373,0.78,-0.414081088495)); -#34766 = CARTESIAN_POINT('',(-0.146778642189,0.78,-0.414633449941)); -#34767 = CARTESIAN_POINT('',(-0.149707415113,0.78,-0.414675649376)); -#34768 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); -#34769 = PCURVE('',#33424,#34770); -#34770 = DEFINITIONAL_REPRESENTATION('',(#34771),#34775); -#34771 = LINE('',#34772,#34773); -#34772 = CARTESIAN_POINT('',(0.E+000,1.)); -#34773 = VECTOR('',#34774,1.); -#34774 = DIRECTION('',(1.,0.E+000)); -#34775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34776 = PCURVE('',#34543,#34777); -#34777 = DEFINITIONAL_REPRESENTATION('',(#34778),#34794); -#34778 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34779,#34780,#34781,#34782, - #34783,#34784,#34785,#34786,#34787,#34788,#34789,#34790,#34791, - #34792,#34793),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37146 = CARTESIAN_POINT('',(-0.111705916967,0.78,-0.377860158937)); +#37147 = CARTESIAN_POINT('',(-0.111832665366,0.78,-0.38035978059)); +#37148 = CARTESIAN_POINT('',(-0.112080679158,0.78,-0.385250892843)); +#37149 = CARTESIAN_POINT('',(-0.114083774905,0.78,-0.392272304946)); +#37150 = CARTESIAN_POINT('',(-0.117456162002,0.78,-0.398631607373)); +#37151 = CARTESIAN_POINT('',(-0.121308646739,0.78,-0.40327571587)); +#37152 = CARTESIAN_POINT('',(-0.12487424297,0.78,-0.406640099038)); +#37153 = CARTESIAN_POINT('',(-0.127924792318,0.78,-0.408781754244)); +#37154 = CARTESIAN_POINT('',(-0.13120414428,0.78,-0.410604492294)); +#37155 = CARTESIAN_POINT('',(-0.134724780019,0.78,-0.412093003298)); +#37156 = CARTESIAN_POINT('',(-0.138491790595,0.78,-0.413293502917)); +#37157 = CARTESIAN_POINT('',(-0.142515380373,0.78,-0.414081088495)); +#37158 = CARTESIAN_POINT('',(-0.146778642189,0.78,-0.414633449941)); +#37159 = CARTESIAN_POINT('',(-0.149707415113,0.78,-0.414675649376)); +#37160 = CARTESIAN_POINT('',(-0.151218512119,0.78,-0.414697422125)); +#37161 = PCURVE('',#35816,#37162); +#37162 = DEFINITIONAL_REPRESENTATION('',(#37163),#37167); +#37163 = LINE('',#37164,#37165); +#37164 = CARTESIAN_POINT('',(0.E+000,1.)); +#37165 = VECTOR('',#37166,1.); +#37166 = DIRECTION('',(1.,0.E+000)); +#37167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37168 = PCURVE('',#36935,#37169); +#37169 = DEFINITIONAL_REPRESENTATION('',(#37170),#37186); +#37170 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37171,#37172,#37173,#37174, + #37175,#37176,#37177,#37178,#37179,#37180,#37181,#37182,#37183, + #37184,#37185),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,0.123386121363,0.241434686423,0.357448546151,0.476713920453, 0.537889586874,0.59927039383,0.660352052257,0.723006936299, 0.787875537201,0.855360105861,0.925373213756,1.),.UNSPECIFIED.); -#34779 = CARTESIAN_POINT('',(-1.002860158937,0.888294083033)); -#34780 = CARTESIAN_POINT('',(-1.00535978059,0.888167334634)); -#34781 = CARTESIAN_POINT('',(-1.010250892843,0.887919320842)); -#34782 = CARTESIAN_POINT('',(-1.017272304946,0.885916225095)); -#34783 = CARTESIAN_POINT('',(-1.023631607373,0.882543837998)); -#34784 = CARTESIAN_POINT('',(-1.02827571587,0.878691353261)); -#34785 = CARTESIAN_POINT('',(-1.031640099038,0.87512575703)); -#34786 = CARTESIAN_POINT('',(-1.033781754244,0.872075207682)); -#34787 = CARTESIAN_POINT('',(-1.035604492294,0.86879585572)); -#34788 = CARTESIAN_POINT('',(-1.037093003298,0.865275219981)); -#34789 = CARTESIAN_POINT('',(-1.038293502917,0.861508209405)); -#34790 = CARTESIAN_POINT('',(-1.039081088495,0.857484619627)); -#34791 = CARTESIAN_POINT('',(-1.039633449941,0.853221357811)); -#34792 = CARTESIAN_POINT('',(-1.039675649376,0.850292584887)); -#34793 = CARTESIAN_POINT('',(-1.039697422125,0.848781487881)); -#34794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34795 = ORIENTED_EDGE('',*,*,#34729,.F.); -#34796 = ORIENTED_EDGE('',*,*,#33384,.T.); -#34797 = ORIENTED_EDGE('',*,*,#34567,.T.); -#34798 = ADVANCED_FACE('',(#34799),#34078,.T.); -#34799 = FACE_BOUND('',#34800,.T.); -#34800 = EDGE_LOOP('',(#34801,#34863,#34882,#34883)); -#34801 = ORIENTED_EDGE('',*,*,#34802,.F.); -#34802 = EDGE_CURVE('',#34803,#34805,#34807,.T.); -#34803 = VERTEX_POINT('',#34804); -#34804 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); -#34805 = VERTEX_POINT('',#34806); -#34806 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); -#34807 = SURFACE_CURVE('',#34808,(#34828,#34835),.PCURVE_S1.); -#34808 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34809,#34810,#34811,#34812, - #34813,#34814,#34815,#34816,#34817,#34818,#34819,#34820,#34821, - #34822,#34823,#34824,#34825,#34826,#34827),.UNSPECIFIED.,.F.,.F.,(4, +#37171 = CARTESIAN_POINT('',(-1.002860158937,0.888294083033)); +#37172 = CARTESIAN_POINT('',(-1.00535978059,0.888167334634)); +#37173 = CARTESIAN_POINT('',(-1.010250892843,0.887919320842)); +#37174 = CARTESIAN_POINT('',(-1.017272304946,0.885916225095)); +#37175 = CARTESIAN_POINT('',(-1.023631607373,0.882543837998)); +#37176 = CARTESIAN_POINT('',(-1.02827571587,0.878691353261)); +#37177 = CARTESIAN_POINT('',(-1.031640099038,0.87512575703)); +#37178 = CARTESIAN_POINT('',(-1.033781754244,0.872075207682)); +#37179 = CARTESIAN_POINT('',(-1.035604492294,0.86879585572)); +#37180 = CARTESIAN_POINT('',(-1.037093003298,0.865275219981)); +#37181 = CARTESIAN_POINT('',(-1.038293502917,0.861508209405)); +#37182 = CARTESIAN_POINT('',(-1.039081088495,0.857484619627)); +#37183 = CARTESIAN_POINT('',(-1.039633449941,0.853221357811)); +#37184 = CARTESIAN_POINT('',(-1.039675649376,0.850292584887)); +#37185 = CARTESIAN_POINT('',(-1.039697422125,0.848781487881)); +#37186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37187 = ORIENTED_EDGE('',*,*,#37121,.F.); +#37188 = ORIENTED_EDGE('',*,*,#35776,.T.); +#37189 = ORIENTED_EDGE('',*,*,#36959,.T.); +#37190 = ADVANCED_FACE('',(#37191),#36470,.T.); +#37191 = FACE_BOUND('',#37192,.T.); +#37192 = EDGE_LOOP('',(#37193,#37255,#37274,#37275)); +#37193 = ORIENTED_EDGE('',*,*,#37194,.F.); +#37194 = EDGE_CURVE('',#37195,#37197,#37199,.T.); +#37195 = VERTEX_POINT('',#37196); +#37196 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); +#37197 = VERTEX_POINT('',#37198); +#37198 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); +#37199 = SURFACE_CURVE('',#37200,(#37220,#37227),.PCURVE_S1.); +#37200 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37201,#37202,#37203,#37204, + #37205,#37206,#37207,#37208,#37209,#37210,#37211,#37212,#37213, + #37214,#37215,#37216,#37217,#37218,#37219),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.095246541543E-002, 0.139088927142,0.203559823919,0.26642378113,0.327516566198, 0.387860871761,0.447898785011,0.508818828589,0.569482456819, 0.629035711667,0.688378458553,0.748067961558,0.808630169751, 0.870231145607,0.933682580472,1.),.UNSPECIFIED.); -#34809 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); -#34810 = CARTESIAN_POINT('',(-0.153776102454,0.78,-0.312590019051)); -#34811 = CARTESIAN_POINT('',(-0.157377799559,0.78,-0.312524938806)); -#34812 = CARTESIAN_POINT('',(-0.162610069873,0.78,-0.311832429033)); -#34813 = CARTESIAN_POINT('',(-0.167563422339,0.78,-0.310768963702)); -#34814 = CARTESIAN_POINT('',(-0.172194277152,0.78,-0.309212440623)); -#34815 = CARTESIAN_POINT('',(-0.17656053432,0.78,-0.30726740685)); -#34816 = CARTESIAN_POINT('',(-0.180582336475,0.78,-0.304821666067)); -#34817 = CARTESIAN_POINT('',(-0.184331432281,0.78,-0.30198285888)); -#34818 = CARTESIAN_POINT('',(-0.187693300282,0.78,-0.298683285504)); -#34819 = CARTESIAN_POINT('',(-0.190726576438,0.78,-0.295099051732)); -#34820 = CARTESIAN_POINT('',(-0.193349168521,0.78,-0.291256764141)); -#34821 = CARTESIAN_POINT('',(-0.195665962824,0.78,-0.287245552298)); -#34822 = CARTESIAN_POINT('',(-0.197424129085,0.78,-0.282933793713)); -#34823 = CARTESIAN_POINT('',(-0.198912259431,0.78,-0.278460879664)); -#34824 = CARTESIAN_POINT('',(-0.199842576285,0.78,-0.273739995734)); -#34825 = CARTESIAN_POINT('',(-0.200503915316,0.78,-0.268824779437)); -#34826 = CARTESIAN_POINT('',(-0.200573629261,0.78,-0.265464306143)); -#34827 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); -#34828 = PCURVE('',#34078,#34829); -#34829 = DEFINITIONAL_REPRESENTATION('',(#34830),#34834); -#34830 = LINE('',#34831,#34832); -#34831 = CARTESIAN_POINT('',(0.E+000,1.)); -#34832 = VECTOR('',#34833,1.); -#34833 = DIRECTION('',(1.,0.E+000)); -#34834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34835 = PCURVE('',#34836,#34841); -#34836 = PLANE('',#34837); -#34837 = AXIS2_PLACEMENT_3D('',#34838,#34839,#34840); -#34838 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#34839 = DIRECTION('',(0.E+000,1.,0.E+000)); -#34840 = DIRECTION('',(0.E+000,0.E+000,1.)); -#34841 = DEFINITIONAL_REPRESENTATION('',(#34842),#34862); -#34842 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34843,#34844,#34845,#34846, - #34847,#34848,#34849,#34850,#34851,#34852,#34853,#34854,#34855, - #34856,#34857,#34858,#34859,#34860,#34861),.UNSPECIFIED.,.F.,.F.,(4, +#37201 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); +#37202 = CARTESIAN_POINT('',(-0.153776102454,0.78,-0.312590019051)); +#37203 = CARTESIAN_POINT('',(-0.157377799559,0.78,-0.312524938806)); +#37204 = CARTESIAN_POINT('',(-0.162610069873,0.78,-0.311832429033)); +#37205 = CARTESIAN_POINT('',(-0.167563422339,0.78,-0.310768963702)); +#37206 = CARTESIAN_POINT('',(-0.172194277152,0.78,-0.309212440623)); +#37207 = CARTESIAN_POINT('',(-0.17656053432,0.78,-0.30726740685)); +#37208 = CARTESIAN_POINT('',(-0.180582336475,0.78,-0.304821666067)); +#37209 = CARTESIAN_POINT('',(-0.184331432281,0.78,-0.30198285888)); +#37210 = CARTESIAN_POINT('',(-0.187693300282,0.78,-0.298683285504)); +#37211 = CARTESIAN_POINT('',(-0.190726576438,0.78,-0.295099051732)); +#37212 = CARTESIAN_POINT('',(-0.193349168521,0.78,-0.291256764141)); +#37213 = CARTESIAN_POINT('',(-0.195665962824,0.78,-0.287245552298)); +#37214 = CARTESIAN_POINT('',(-0.197424129085,0.78,-0.282933793713)); +#37215 = CARTESIAN_POINT('',(-0.198912259431,0.78,-0.278460879664)); +#37216 = CARTESIAN_POINT('',(-0.199842576285,0.78,-0.273739995734)); +#37217 = CARTESIAN_POINT('',(-0.200503915316,0.78,-0.268824779437)); +#37218 = CARTESIAN_POINT('',(-0.200573629261,0.78,-0.265464306143)); +#37219 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); +#37220 = PCURVE('',#36470,#37221); +#37221 = DEFINITIONAL_REPRESENTATION('',(#37222),#37226); +#37222 = LINE('',#37223,#37224); +#37223 = CARTESIAN_POINT('',(0.E+000,1.)); +#37224 = VECTOR('',#37225,1.); +#37225 = DIRECTION('',(1.,0.E+000)); +#37226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37227 = PCURVE('',#37228,#37233); +#37228 = PLANE('',#37229); +#37229 = AXIS2_PLACEMENT_3D('',#37230,#37231,#37232); +#37230 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#37231 = DIRECTION('',(0.E+000,1.,0.E+000)); +#37232 = DIRECTION('',(0.E+000,0.E+000,1.)); +#37233 = DEFINITIONAL_REPRESENTATION('',(#37234),#37254); +#37234 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37235,#37236,#37237,#37238, + #37239,#37240,#37241,#37242,#37243,#37244,#37245,#37246,#37247, + #37248,#37249,#37250,#37251,#37252,#37253),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.095246541543E-002, 0.139088927142,0.203559823919,0.26642378113,0.327516566198, 0.387860871761,0.447898785011,0.508818828589,0.569482456819, 0.629035711667,0.688378458553,0.748067961558,0.808630169751, 0.870231145607,0.933682580472,1.),.UNSPECIFIED.); -#34843 = CARTESIAN_POINT('',(-0.937623217982,0.848061206198)); -#34844 = CARTESIAN_POINT('',(-0.937590019051,0.846223897546)); -#34845 = CARTESIAN_POINT('',(-0.937524938806,0.842622200441)); -#34846 = CARTESIAN_POINT('',(-0.936832429033,0.837389930127)); -#34847 = CARTESIAN_POINT('',(-0.935768963702,0.832436577661)); -#34848 = CARTESIAN_POINT('',(-0.934212440623,0.827805722848)); -#34849 = CARTESIAN_POINT('',(-0.93226740685,0.82343946568)); -#34850 = CARTESIAN_POINT('',(-0.929821666067,0.819417663525)); -#34851 = CARTESIAN_POINT('',(-0.92698285888,0.815668567719)); -#34852 = CARTESIAN_POINT('',(-0.923683285504,0.812306699718)); -#34853 = CARTESIAN_POINT('',(-0.920099051732,0.809273423562)); -#34854 = CARTESIAN_POINT('',(-0.916256764141,0.806650831479)); -#34855 = CARTESIAN_POINT('',(-0.912245552298,0.804334037176)); -#34856 = CARTESIAN_POINT('',(-0.907933793713,0.802575870915)); -#34857 = CARTESIAN_POINT('',(-0.903460879664,0.801087740569)); -#34858 = CARTESIAN_POINT('',(-0.898739995734,0.800157423715)); -#34859 = CARTESIAN_POINT('',(-0.893824779437,0.799496084684)); -#34860 = CARTESIAN_POINT('',(-0.890464306143,0.799426370739)); -#34861 = CARTESIAN_POINT('',(-0.888746960958,0.79939074394)); -#34862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34863 = ORIENTED_EDGE('',*,*,#34864,.F.); -#34864 = EDGE_CURVE('',#34031,#34803,#34865,.T.); -#34865 = SURFACE_CURVE('',#34866,(#34870,#34876),.PCURVE_S1.); -#34866 = LINE('',#34867,#34868); -#34867 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); -#34868 = VECTOR('',#34869,1.); -#34869 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34870 = PCURVE('',#34078,#34871); -#34871 = DEFINITIONAL_REPRESENTATION('',(#34872),#34875); -#34872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34873,#34874),.UNSPECIFIED., +#37235 = CARTESIAN_POINT('',(-0.937623217982,0.848061206198)); +#37236 = CARTESIAN_POINT('',(-0.937590019051,0.846223897546)); +#37237 = CARTESIAN_POINT('',(-0.937524938806,0.842622200441)); +#37238 = CARTESIAN_POINT('',(-0.936832429033,0.837389930127)); +#37239 = CARTESIAN_POINT('',(-0.935768963702,0.832436577661)); +#37240 = CARTESIAN_POINT('',(-0.934212440623,0.827805722848)); +#37241 = CARTESIAN_POINT('',(-0.93226740685,0.82343946568)); +#37242 = CARTESIAN_POINT('',(-0.929821666067,0.819417663525)); +#37243 = CARTESIAN_POINT('',(-0.92698285888,0.815668567719)); +#37244 = CARTESIAN_POINT('',(-0.923683285504,0.812306699718)); +#37245 = CARTESIAN_POINT('',(-0.920099051732,0.809273423562)); +#37246 = CARTESIAN_POINT('',(-0.916256764141,0.806650831479)); +#37247 = CARTESIAN_POINT('',(-0.912245552298,0.804334037176)); +#37248 = CARTESIAN_POINT('',(-0.907933793713,0.802575870915)); +#37249 = CARTESIAN_POINT('',(-0.903460879664,0.801087740569)); +#37250 = CARTESIAN_POINT('',(-0.898739995734,0.800157423715)); +#37251 = CARTESIAN_POINT('',(-0.893824779437,0.799496084684)); +#37252 = CARTESIAN_POINT('',(-0.890464306143,0.799426370739)); +#37253 = CARTESIAN_POINT('',(-0.888746960958,0.79939074394)); +#37254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37255 = ORIENTED_EDGE('',*,*,#37256,.F.); +#37256 = EDGE_CURVE('',#36423,#37195,#37257,.T.); +#37257 = SURFACE_CURVE('',#37258,(#37262,#37268),.PCURVE_S1.); +#37258 = LINE('',#37259,#37260); +#37259 = CARTESIAN_POINT('',(-0.151938793802,0.782,-0.312623217982)); +#37260 = VECTOR('',#37261,1.); +#37261 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37262 = PCURVE('',#36470,#37263); +#37263 = DEFINITIONAL_REPRESENTATION('',(#37264),#37267); +#37264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37265,#37266),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34873 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34874 = CARTESIAN_POINT('',(0.E+000,1.)); -#34875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37266 = CARTESIAN_POINT('',(0.E+000,1.)); +#37267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34876 = PCURVE('',#34172,#34877); -#34877 = DEFINITIONAL_REPRESENTATION('',(#34878),#34881); -#34878 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34879,#34880),.UNSPECIFIED., +#37268 = PCURVE('',#36564,#37269); +#37269 = DEFINITIONAL_REPRESENTATION('',(#37270),#37273); +#37270 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37271,#37272),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34879 = CARTESIAN_POINT('',(1.,0.E+000)); -#34880 = CARTESIAN_POINT('',(1.,1.)); -#34881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34882 = ORIENTED_EDGE('',*,*,#34030,.T.); -#34883 = ORIENTED_EDGE('',*,*,#34884,.T.); -#34884 = EDGE_CURVE('',#33951,#34805,#34885,.T.); -#34885 = SURFACE_CURVE('',#34886,(#34890,#34896),.PCURVE_S1.); -#34886 = LINE('',#34887,#34888); -#34887 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); -#34888 = VECTOR('',#34889,1.); -#34889 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34890 = PCURVE('',#34078,#34891); -#34891 = DEFINITIONAL_REPRESENTATION('',(#34892),#34895); -#34892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34893,#34894),.UNSPECIFIED., +#37271 = CARTESIAN_POINT('',(1.,0.E+000)); +#37272 = CARTESIAN_POINT('',(1.,1.)); +#37273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37274 = ORIENTED_EDGE('',*,*,#36422,.T.); +#37275 = ORIENTED_EDGE('',*,*,#37276,.T.); +#37276 = EDGE_CURVE('',#36343,#37197,#37277,.T.); +#37277 = SURFACE_CURVE('',#37278,(#37282,#37288),.PCURVE_S1.); +#37278 = LINE('',#37279,#37280); +#37279 = CARTESIAN_POINT('',(-0.20060925606,0.782,-0.263746960958)); +#37280 = VECTOR('',#37281,1.); +#37281 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37282 = PCURVE('',#36470,#37283); +#37283 = DEFINITIONAL_REPRESENTATION('',(#37284),#37287); +#37284 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37285,#37286),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34893 = CARTESIAN_POINT('',(1.,0.E+000)); -#34894 = CARTESIAN_POINT('',(1.,1.)); -#34895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37285 = CARTESIAN_POINT('',(1.,0.E+000)); +#37286 = CARTESIAN_POINT('',(1.,1.)); +#37287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34896 = PCURVE('',#33992,#34897); -#34897 = DEFINITIONAL_REPRESENTATION('',(#34898),#34901); -#34898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34899,#34900),.UNSPECIFIED., +#37288 = PCURVE('',#36384,#37289); +#37289 = DEFINITIONAL_REPRESENTATION('',(#37290),#37293); +#37290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37291,#37292),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34899 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34900 = CARTESIAN_POINT('',(0.E+000,1.)); -#34901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34902 = ADVANCED_FACE('',(#34903),#33992,.T.); -#34903 = FACE_BOUND('',#34904,.T.); -#34904 = EDGE_LOOP('',(#34905,#34952,#34953,#34954)); -#34905 = ORIENTED_EDGE('',*,*,#34906,.F.); -#34906 = EDGE_CURVE('',#34805,#34907,#34909,.T.); -#34907 = VERTEX_POINT('',#34908); -#34908 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); -#34909 = SURFACE_CURVE('',#34910,(#34926,#34933),.PCURVE_S1.); -#34910 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34911,#34912,#34913,#34914, - #34915,#34916,#34917,#34918,#34919,#34920,#34921,#34922,#34923, - #34924,#34925),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37291 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37292 = CARTESIAN_POINT('',(0.E+000,1.)); +#37293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37294 = ADVANCED_FACE('',(#37295),#36384,.T.); +#37295 = FACE_BOUND('',#37296,.T.); +#37296 = EDGE_LOOP('',(#37297,#37344,#37345,#37346)); +#37297 = ORIENTED_EDGE('',*,*,#37298,.F.); +#37298 = EDGE_CURVE('',#37197,#37299,#37301,.T.); +#37299 = VERTEX_POINT('',#37300); +#37300 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); +#37301 = SURFACE_CURVE('',#37302,(#37318,#37325),.PCURVE_S1.); +#37302 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37303,#37304,#37305,#37306, + #37307,#37308,#37309,#37310,#37311,#37312,#37313,#37314,#37315, + #37316,#37317),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.982327127979E-002,0.159856811666,0.239732702115, 0.321364602325,0.402583696349,0.483265588546,0.566017011661, 0.65307135966,0.741855686507,0.828590905074,0.914280745201,1.), .UNSPECIFIED.); -#34911 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); -#34912 = CARTESIAN_POINT('',(-0.200552317567,0.78,-0.26163417388)); -#34913 = CARTESIAN_POINT('',(-0.200438290596,0.78,-0.257403034255)); -#34914 = CARTESIAN_POINT('',(-0.199438028632,0.78,-0.251118895293)); -#34915 = CARTESIAN_POINT('',(-0.197740791267,0.78,-0.244951778484)); -#34916 = CARTESIAN_POINT('',(-0.195565486121,0.78,-0.238895858564)); -#34917 = CARTESIAN_POINT('',(-0.192497082943,0.78,-0.233195563055)); -#34918 = CARTESIAN_POINT('',(-0.188428035233,0.78,-0.228107629908)); -#34919 = CARTESIAN_POINT('',(-0.183322142487,0.78,-0.223830002489)); -#34920 = CARTESIAN_POINT('',(-0.177490933776,0.78,-0.220216100506)); -#34921 = CARTESIAN_POINT('',(-0.171127585823,0.78,-0.217371648834)); -#34922 = CARTESIAN_POINT('',(-0.164496791189,0.78,-0.215386124915)); -#34923 = CARTESIAN_POINT('',(-0.157769687252,0.78,-0.214074189816)); -#34924 = CARTESIAN_POINT('',(-0.153231001145,0.78,-0.213919225537)); -#34925 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); -#34926 = PCURVE('',#33992,#34927); -#34927 = DEFINITIONAL_REPRESENTATION('',(#34928),#34932); -#34928 = LINE('',#34929,#34930); -#34929 = CARTESIAN_POINT('',(0.E+000,1.)); -#34930 = VECTOR('',#34931,1.); -#34931 = DIRECTION('',(1.,0.E+000)); -#34932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34933 = PCURVE('',#34836,#34934); -#34934 = DEFINITIONAL_REPRESENTATION('',(#34935),#34951); -#34935 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34936,#34937,#34938,#34939, - #34940,#34941,#34942,#34943,#34944,#34945,#34946,#34947,#34948, - #34949,#34950),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( +#37303 = CARTESIAN_POINT('',(-0.20060925606,0.78,-0.263746960958)); +#37304 = CARTESIAN_POINT('',(-0.200552317567,0.78,-0.26163417388)); +#37305 = CARTESIAN_POINT('',(-0.200438290596,0.78,-0.257403034255)); +#37306 = CARTESIAN_POINT('',(-0.199438028632,0.78,-0.251118895293)); +#37307 = CARTESIAN_POINT('',(-0.197740791267,0.78,-0.244951778484)); +#37308 = CARTESIAN_POINT('',(-0.195565486121,0.78,-0.238895858564)); +#37309 = CARTESIAN_POINT('',(-0.192497082943,0.78,-0.233195563055)); +#37310 = CARTESIAN_POINT('',(-0.188428035233,0.78,-0.228107629908)); +#37311 = CARTESIAN_POINT('',(-0.183322142487,0.78,-0.223830002489)); +#37312 = CARTESIAN_POINT('',(-0.177490933776,0.78,-0.220216100506)); +#37313 = CARTESIAN_POINT('',(-0.171127585823,0.78,-0.217371648834)); +#37314 = CARTESIAN_POINT('',(-0.164496791189,0.78,-0.215386124915)); +#37315 = CARTESIAN_POINT('',(-0.157769687252,0.78,-0.214074189816)); +#37316 = CARTESIAN_POINT('',(-0.153231001145,0.78,-0.213919225537)); +#37317 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); +#37318 = PCURVE('',#36384,#37319); +#37319 = DEFINITIONAL_REPRESENTATION('',(#37320),#37324); +#37320 = LINE('',#37321,#37322); +#37321 = CARTESIAN_POINT('',(0.E+000,1.)); +#37322 = VECTOR('',#37323,1.); +#37323 = DIRECTION('',(1.,0.E+000)); +#37324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37325 = PCURVE('',#37228,#37326); +#37326 = DEFINITIONAL_REPRESENTATION('',(#37327),#37343); +#37327 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37328,#37329,#37330,#37331, + #37332,#37333,#37334,#37335,#37336,#37337,#37338,#37339,#37340, + #37341,#37342),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,4),( 0.E+000,7.982327127979E-002,0.159856811666,0.239732702115, 0.321364602325,0.402583696349,0.483265588546,0.566017011661, 0.65307135966,0.741855686507,0.828590905074,0.914280745201,1.), .UNSPECIFIED.); -#34936 = CARTESIAN_POINT('',(-0.888746960958,0.79939074394)); -#34937 = CARTESIAN_POINT('',(-0.88663417388,0.799447682433)); -#34938 = CARTESIAN_POINT('',(-0.882403034255,0.799561709404)); -#34939 = CARTESIAN_POINT('',(-0.876118895293,0.800561971368)); -#34940 = CARTESIAN_POINT('',(-0.869951778484,0.802259208733)); -#34941 = CARTESIAN_POINT('',(-0.863895858564,0.804434513879)); -#34942 = CARTESIAN_POINT('',(-0.858195563055,0.807502917057)); -#34943 = CARTESIAN_POINT('',(-0.853107629908,0.811571964767)); -#34944 = CARTESIAN_POINT('',(-0.848830002489,0.816677857513)); -#34945 = CARTESIAN_POINT('',(-0.845216100506,0.822509066224)); -#34946 = CARTESIAN_POINT('',(-0.842371648834,0.828872414177)); -#34947 = CARTESIAN_POINT('',(-0.840386124915,0.835503208811)); -#34948 = CARTESIAN_POINT('',(-0.839074189816,0.842230312748)); -#34949 = CARTESIAN_POINT('',(-0.838919225537,0.846768998855)); -#34950 = CARTESIAN_POINT('',(-0.838841730101,0.849038731339)); -#34951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34952 = ORIENTED_EDGE('',*,*,#34884,.F.); -#34953 = ORIENTED_EDGE('',*,*,#33950,.T.); -#34954 = ORIENTED_EDGE('',*,*,#34955,.T.); -#34955 = EDGE_CURVE('',#33953,#34907,#34956,.T.); -#34956 = SURFACE_CURVE('',#34957,(#34961,#34967),.PCURVE_S1.); -#34957 = LINE('',#34958,#34959); -#34958 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); -#34959 = VECTOR('',#34960,1.); -#34960 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#34961 = PCURVE('',#33992,#34962); -#34962 = DEFINITIONAL_REPRESENTATION('',(#34963),#34966); -#34963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34964,#34965),.UNSPECIFIED., +#37328 = CARTESIAN_POINT('',(-0.888746960958,0.79939074394)); +#37329 = CARTESIAN_POINT('',(-0.88663417388,0.799447682433)); +#37330 = CARTESIAN_POINT('',(-0.882403034255,0.799561709404)); +#37331 = CARTESIAN_POINT('',(-0.876118895293,0.800561971368)); +#37332 = CARTESIAN_POINT('',(-0.869951778484,0.802259208733)); +#37333 = CARTESIAN_POINT('',(-0.863895858564,0.804434513879)); +#37334 = CARTESIAN_POINT('',(-0.858195563055,0.807502917057)); +#37335 = CARTESIAN_POINT('',(-0.853107629908,0.811571964767)); +#37336 = CARTESIAN_POINT('',(-0.848830002489,0.816677857513)); +#37337 = CARTESIAN_POINT('',(-0.845216100506,0.822509066224)); +#37338 = CARTESIAN_POINT('',(-0.842371648834,0.828872414177)); +#37339 = CARTESIAN_POINT('',(-0.840386124915,0.835503208811)); +#37340 = CARTESIAN_POINT('',(-0.839074189816,0.842230312748)); +#37341 = CARTESIAN_POINT('',(-0.838919225537,0.846768998855)); +#37342 = CARTESIAN_POINT('',(-0.838841730101,0.849038731339)); +#37343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37344 = ORIENTED_EDGE('',*,*,#37276,.F.); +#37345 = ORIENTED_EDGE('',*,*,#36342,.T.); +#37346 = ORIENTED_EDGE('',*,*,#37347,.T.); +#37347 = EDGE_CURVE('',#36345,#37299,#37348,.T.); +#37348 = SURFACE_CURVE('',#37349,(#37353,#37359),.PCURVE_S1.); +#37349 = LINE('',#37350,#37351); +#37350 = CARTESIAN_POINT('',(-0.150961268661,0.782,-0.213841730101)); +#37351 = VECTOR('',#37352,1.); +#37352 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37353 = PCURVE('',#36384,#37354); +#37354 = DEFINITIONAL_REPRESENTATION('',(#37355),#37358); +#37355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37356,#37357),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34964 = CARTESIAN_POINT('',(1.,0.E+000)); -#34965 = CARTESIAN_POINT('',(1.,1.)); -#34966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37356 = CARTESIAN_POINT('',(1.,0.E+000)); +#37357 = CARTESIAN_POINT('',(1.,1.)); +#37358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#34967 = PCURVE('',#34264,#34968); -#34968 = DEFINITIONAL_REPRESENTATION('',(#34969),#34972); -#34969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#34970,#34971),.UNSPECIFIED., +#37359 = PCURVE('',#36656,#37360); +#37360 = DEFINITIONAL_REPRESENTATION('',(#37361),#37364); +#37361 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37362,#37363),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#34970 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#34971 = CARTESIAN_POINT('',(0.E+000,1.)); -#34972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#34973 = ADVANCED_FACE('',(#34974),#34264,.T.); -#34974 = FACE_BOUND('',#34975,.T.); -#34975 = EDGE_LOOP('',(#34976,#35031,#35032,#35033)); -#34976 = ORIENTED_EDGE('',*,*,#34977,.F.); -#34977 = EDGE_CURVE('',#34907,#34978,#34980,.T.); -#34978 = VERTEX_POINT('',#34979); -#34979 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); -#34980 = SURFACE_CURVE('',#34981,(#35001,#35008),.PCURVE_S1.); -#34981 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#34982,#34983,#34984,#34985, - #34986,#34987,#34988,#34989,#34990,#34991,#34992,#34993,#34994, - #34995,#34996,#34997,#34998,#34999,#35000),.UNSPECIFIED.,.F.,.F.,(4, +#37362 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37363 = CARTESIAN_POINT('',(0.E+000,1.)); +#37364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37365 = ADVANCED_FACE('',(#37366),#36656,.T.); +#37366 = FACE_BOUND('',#37367,.T.); +#37367 = EDGE_LOOP('',(#37368,#37423,#37424,#37425)); +#37368 = ORIENTED_EDGE('',*,*,#37369,.F.); +#37369 = EDGE_CURVE('',#37299,#37370,#37372,.T.); +#37370 = VERTEX_POINT('',#37371); +#37371 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); +#37372 = SURFACE_CURVE('',#37373,(#37393,#37400),.PCURVE_S1.); +#37373 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37374,#37375,#37376,#37377, + #37378,#37379,#37380,#37381,#37382,#37383,#37384,#37385,#37386, + #37387,#37388,#37389,#37390,#37391,#37392),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.183671713195E-002, 0.139558262918,0.204923352654,0.267826558604,0.328547320094, 0.388755146329,0.44802996798,0.508600527697,0.569321289187, 0.628511895402,0.687493275539,0.747078295389,0.807702541317, 0.869709812621,0.933428331305,1.),.UNSPECIFIED.); -#34982 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); -#34983 = CARTESIAN_POINT('',(-0.149089629476,0.78,-0.2138734343)); -#34984 = CARTESIAN_POINT('',(-0.145453568086,0.78,-0.213935026519)); -#34985 = CARTESIAN_POINT('',(-0.14015332903,0.78,-0.214638849754)); -#34986 = CARTESIAN_POINT('',(-0.135159305537,0.78,-0.215706779839)); -#34987 = CARTESIAN_POINT('',(-0.130448617732,0.78,-0.217171087032)); -#34988 = CARTESIAN_POINT('',(-0.126090601696,0.78,-0.2191743562)); -#34989 = CARTESIAN_POINT('',(-0.122014288911,0.78,-0.221515742715)); -#34990 = CARTESIAN_POINT('',(-0.118261374819,0.78,-0.224345487547)); -#34991 = CARTESIAN_POINT('',(-0.114832921846,0.78,-0.227574940682)); -#34992 = CARTESIAN_POINT('',(-0.111763848655,0.78,-0.231147321084)); -#34993 = CARTESIAN_POINT('',(-0.109134799364,0.78,-0.23500113898)); -#34994 = CARTESIAN_POINT('',(-0.106841448614,0.78,-0.239028015166)); -#34995 = CARTESIAN_POINT('',(-0.104969032574,0.78,-0.243314855844)); -#34996 = CARTESIAN_POINT('',(-0.103614973993,0.78,-0.247870500851)); -#34997 = CARTESIAN_POINT('',(-0.102570126549,0.78,-0.252612756481)); -#34998 = CARTESIAN_POINT('',(-0.101939800998,0.78,-0.257590536503)); -#34999 = CARTESIAN_POINT('',(-0.101865653688,0.78,-0.260984065934)); -#35000 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); -#35001 = PCURVE('',#34264,#35002); -#35002 = DEFINITIONAL_REPRESENTATION('',(#35003),#35007); -#35003 = LINE('',#35004,#35005); -#35004 = CARTESIAN_POINT('',(0.E+000,1.)); -#35005 = VECTOR('',#35006,1.); -#35006 = DIRECTION('',(1.,0.E+000)); -#35007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35008 = PCURVE('',#34836,#35009); -#35009 = DEFINITIONAL_REPRESENTATION('',(#35010),#35030); -#35010 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35011,#35012,#35013,#35014, - #35015,#35016,#35017,#35018,#35019,#35020,#35021,#35022,#35023, - #35024,#35025,#35026,#35027,#35028,#35029),.UNSPECIFIED.,.F.,.F.,(4, +#37374 = CARTESIAN_POINT('',(-0.150961268661,0.78,-0.213841730101)); +#37375 = CARTESIAN_POINT('',(-0.149089629476,0.78,-0.2138734343)); +#37376 = CARTESIAN_POINT('',(-0.145453568086,0.78,-0.213935026519)); +#37377 = CARTESIAN_POINT('',(-0.14015332903,0.78,-0.214638849754)); +#37378 = CARTESIAN_POINT('',(-0.135159305537,0.78,-0.215706779839)); +#37379 = CARTESIAN_POINT('',(-0.130448617732,0.78,-0.217171087032)); +#37380 = CARTESIAN_POINT('',(-0.126090601696,0.78,-0.2191743562)); +#37381 = CARTESIAN_POINT('',(-0.122014288911,0.78,-0.221515742715)); +#37382 = CARTESIAN_POINT('',(-0.118261374819,0.78,-0.224345487547)); +#37383 = CARTESIAN_POINT('',(-0.114832921846,0.78,-0.227574940682)); +#37384 = CARTESIAN_POINT('',(-0.111763848655,0.78,-0.231147321084)); +#37385 = CARTESIAN_POINT('',(-0.109134799364,0.78,-0.23500113898)); +#37386 = CARTESIAN_POINT('',(-0.106841448614,0.78,-0.239028015166)); +#37387 = CARTESIAN_POINT('',(-0.104969032574,0.78,-0.243314855844)); +#37388 = CARTESIAN_POINT('',(-0.103614973993,0.78,-0.247870500851)); +#37389 = CARTESIAN_POINT('',(-0.102570126549,0.78,-0.252612756481)); +#37390 = CARTESIAN_POINT('',(-0.101939800998,0.78,-0.257590536503)); +#37391 = CARTESIAN_POINT('',(-0.101865653688,0.78,-0.260984065934)); +#37392 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); +#37393 = PCURVE('',#36656,#37394); +#37394 = DEFINITIONAL_REPRESENTATION('',(#37395),#37399); +#37395 = LINE('',#37396,#37397); +#37396 = CARTESIAN_POINT('',(0.E+000,1.)); +#37397 = VECTOR('',#37398,1.); +#37398 = DIRECTION('',(1.,0.E+000)); +#37399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37400 = PCURVE('',#37228,#37401); +#37401 = DEFINITIONAL_REPRESENTATION('',(#37402),#37422); +#37402 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37403,#37404,#37405,#37406, + #37407,#37408,#37409,#37410,#37411,#37412,#37413,#37414,#37415, + #37416,#37417,#37418,#37419,#37420,#37421),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.183671713195E-002, 0.139558262918,0.204923352654,0.267826558604,0.328547320094, 0.388755146329,0.44802996798,0.508600527697,0.569321289187, 0.628511895402,0.687493275539,0.747078295389,0.807702541317, 0.869709812621,0.933428331305,1.),.UNSPECIFIED.); -#35011 = CARTESIAN_POINT('',(-0.838841730101,0.849038731339)); -#35012 = CARTESIAN_POINT('',(-0.8388734343,0.850910370524)); -#35013 = CARTESIAN_POINT('',(-0.838935026519,0.854546431914)); -#35014 = CARTESIAN_POINT('',(-0.839638849754,0.85984667097)); -#35015 = CARTESIAN_POINT('',(-0.840706779839,0.864840694463)); -#35016 = CARTESIAN_POINT('',(-0.842171087032,0.869551382268)); -#35017 = CARTESIAN_POINT('',(-0.8441743562,0.873909398304)); -#35018 = CARTESIAN_POINT('',(-0.846515742715,0.877985711089)); -#35019 = CARTESIAN_POINT('',(-0.849345487547,0.881738625181)); -#35020 = CARTESIAN_POINT('',(-0.852574940682,0.885167078154)); -#35021 = CARTESIAN_POINT('',(-0.856147321084,0.888236151345)); -#35022 = CARTESIAN_POINT('',(-0.86000113898,0.890865200636)); -#35023 = CARTESIAN_POINT('',(-0.864028015166,0.893158551386)); -#35024 = CARTESIAN_POINT('',(-0.868314855844,0.895030967426)); -#35025 = CARTESIAN_POINT('',(-0.872870500851,0.896385026007)); -#35026 = CARTESIAN_POINT('',(-0.877612756481,0.897429873451)); -#35027 = CARTESIAN_POINT('',(-0.882590536503,0.898060199002)); -#35028 = CARTESIAN_POINT('',(-0.885984065934,0.898134346312)); -#35029 = CARTESIAN_POINT('',(-0.887717987126,0.898172231821)); -#35030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35031 = ORIENTED_EDGE('',*,*,#34955,.F.); -#35032 = ORIENTED_EDGE('',*,*,#34218,.T.); -#35033 = ORIENTED_EDGE('',*,*,#35034,.T.); -#35034 = EDGE_CURVE('',#34125,#34978,#35035,.T.); -#35035 = SURFACE_CURVE('',#35036,(#35040,#35046),.PCURVE_S1.); -#35036 = LINE('',#35037,#35038); -#35037 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); -#35038 = VECTOR('',#35039,1.); -#35039 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35040 = PCURVE('',#34264,#35041); -#35041 = DEFINITIONAL_REPRESENTATION('',(#35042),#35045); -#35042 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35043,#35044),.UNSPECIFIED., +#37403 = CARTESIAN_POINT('',(-0.838841730101,0.849038731339)); +#37404 = CARTESIAN_POINT('',(-0.8388734343,0.850910370524)); +#37405 = CARTESIAN_POINT('',(-0.838935026519,0.854546431914)); +#37406 = CARTESIAN_POINT('',(-0.839638849754,0.85984667097)); +#37407 = CARTESIAN_POINT('',(-0.840706779839,0.864840694463)); +#37408 = CARTESIAN_POINT('',(-0.842171087032,0.869551382268)); +#37409 = CARTESIAN_POINT('',(-0.8441743562,0.873909398304)); +#37410 = CARTESIAN_POINT('',(-0.846515742715,0.877985711089)); +#37411 = CARTESIAN_POINT('',(-0.849345487547,0.881738625181)); +#37412 = CARTESIAN_POINT('',(-0.852574940682,0.885167078154)); +#37413 = CARTESIAN_POINT('',(-0.856147321084,0.888236151345)); +#37414 = CARTESIAN_POINT('',(-0.86000113898,0.890865200636)); +#37415 = CARTESIAN_POINT('',(-0.864028015166,0.893158551386)); +#37416 = CARTESIAN_POINT('',(-0.868314855844,0.895030967426)); +#37417 = CARTESIAN_POINT('',(-0.872870500851,0.896385026007)); +#37418 = CARTESIAN_POINT('',(-0.877612756481,0.897429873451)); +#37419 = CARTESIAN_POINT('',(-0.882590536503,0.898060199002)); +#37420 = CARTESIAN_POINT('',(-0.885984065934,0.898134346312)); +#37421 = CARTESIAN_POINT('',(-0.887717987126,0.898172231821)); +#37422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37423 = ORIENTED_EDGE('',*,*,#37347,.F.); +#37424 = ORIENTED_EDGE('',*,*,#36610,.T.); +#37425 = ORIENTED_EDGE('',*,*,#37426,.T.); +#37426 = EDGE_CURVE('',#36517,#37370,#37427,.T.); +#37427 = SURFACE_CURVE('',#37428,(#37432,#37438),.PCURVE_S1.); +#37428 = LINE('',#37429,#37430); +#37429 = CARTESIAN_POINT('',(-0.101827768179,0.782,-0.262717987126)); +#37430 = VECTOR('',#37431,1.); +#37431 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#37432 = PCURVE('',#36656,#37433); +#37433 = DEFINITIONAL_REPRESENTATION('',(#37434),#37437); +#37434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37435,#37436),.UNSPECIFIED., .F.,.F.,(2,2),(3.330669073875E-016,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35043 = CARTESIAN_POINT('',(1.,0.E+000)); -#35044 = CARTESIAN_POINT('',(1.,1.)); -#35045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37435 = CARTESIAN_POINT('',(1.,0.E+000)); +#37436 = CARTESIAN_POINT('',(1.,1.)); +#37437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35046 = PCURVE('',#34172,#35047); -#35047 = DEFINITIONAL_REPRESENTATION('',(#35048),#35051); -#35048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35049,#35050),.UNSPECIFIED., +#37438 = PCURVE('',#36564,#37439); +#37439 = DEFINITIONAL_REPRESENTATION('',(#37440),#37443); +#37440 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37441,#37442),.UNSPECIFIED., .F.,.F.,(2,2),(3.330669073875E-016,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35049 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35050 = CARTESIAN_POINT('',(0.E+000,1.)); -#35051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35052 = ADVANCED_FACE('',(#35053),#34172,.T.); -#35053 = FACE_BOUND('',#35054,.T.); -#35054 = EDGE_LOOP('',(#35055,#35108,#35109,#35110)); -#35055 = ORIENTED_EDGE('',*,*,#35056,.F.); -#35056 = EDGE_CURVE('',#34978,#34803,#35057,.T.); -#35057 = SURFACE_CURVE('',#35058,(#35078,#35085),.PCURVE_S1.); -#35058 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35059,#35060,#35061,#35062, - #35063,#35064,#35065,#35066,#35067,#35068,#35069,#35070,#35071, - #35072,#35073,#35074,#35075,#35076,#35077),.UNSPECIFIED.,.F.,.F.,(4, +#37441 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37442 = CARTESIAN_POINT('',(0.E+000,1.)); +#37443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37444 = ADVANCED_FACE('',(#37445),#36564,.T.); +#37445 = FACE_BOUND('',#37446,.T.); +#37446 = EDGE_LOOP('',(#37447,#37500,#37501,#37502)); +#37447 = ORIENTED_EDGE('',*,*,#37448,.F.); +#37448 = EDGE_CURVE('',#37370,#37195,#37449,.T.); +#37449 = SURFACE_CURVE('',#37450,(#37470,#37477),.PCURVE_S1.); +#37450 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37451,#37452,#37453,#37454, + #37455,#37456,#37457,#37458,#37459,#37460,#37461,#37462,#37463, + #37464,#37465,#37466,#37467,#37468,#37469),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.661618043518E-002, 0.130423869924,0.19267095757,0.252968504796,0.312880382806, 0.372200255918,0.431927107146,0.492421745255,0.552771220908, 0.613262406816,0.673556490556,0.734319796033,0.79685808014, 0.861769004751,0.928863107315,1.),.UNSPECIFIED.); -#35059 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); -#35060 = CARTESIAN_POINT('',(-0.10186686026,0.78,-0.26448594315)); -#35061 = CARTESIAN_POINT('',(-0.101943396327,0.78,-0.267947319425)); -#35062 = CARTESIAN_POINT('',(-0.102557703262,0.78,-0.273034351424)); -#35063 = CARTESIAN_POINT('',(-0.103661139043,0.78,-0.27786003999)); -#35064 = CARTESIAN_POINT('',(-0.105080162052,0.78,-0.282497287228)); -#35065 = CARTESIAN_POINT('',(-0.107003343979,0.78,-0.28686541831)); -#35066 = CARTESIAN_POINT('',(-0.109311854622,0.78,-0.29102706702)); -#35067 = CARTESIAN_POINT('',(-0.112138842285,0.78,-0.294872541544)); -#35068 = CARTESIAN_POINT('',(-0.115238859767,0.78,-0.298532396355)); -#35069 = CARTESIAN_POINT('',(-0.118747041454,0.78,-0.30184541093)); -#35070 = CARTESIAN_POINT('',(-0.122621172084,0.78,-0.304702348574)); -#35071 = CARTESIAN_POINT('',(-0.126738471674,0.78,-0.307225508361)); -#35072 = CARTESIAN_POINT('',(-0.131223492272,0.78,-0.309160984933)); -#35073 = CARTESIAN_POINT('',(-0.135977422796,0.78,-0.310711345801)); -#35074 = CARTESIAN_POINT('',(-0.14102284836,0.78,-0.31183786157)); -#35075 = CARTESIAN_POINT('',(-0.146380340656,0.78,-0.312526470698)); -#35076 = CARTESIAN_POINT('',(-0.150050199095,0.78,-0.312590346173)); -#35077 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); -#35078 = PCURVE('',#34172,#35079); -#35079 = DEFINITIONAL_REPRESENTATION('',(#35080),#35084); -#35080 = LINE('',#35081,#35082); -#35081 = CARTESIAN_POINT('',(0.E+000,1.)); -#35082 = VECTOR('',#35083,1.); -#35083 = DIRECTION('',(1.,0.E+000)); -#35084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35085 = PCURVE('',#34836,#35086); -#35086 = DEFINITIONAL_REPRESENTATION('',(#35087),#35107); -#35087 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35088,#35089,#35090,#35091, - #35092,#35093,#35094,#35095,#35096,#35097,#35098,#35099,#35100, - #35101,#35102,#35103,#35104,#35105,#35106),.UNSPECIFIED.,.F.,.F.,(4, +#37451 = CARTESIAN_POINT('',(-0.101827768179,0.78,-0.262717987126)); +#37452 = CARTESIAN_POINT('',(-0.10186686026,0.78,-0.26448594315)); +#37453 = CARTESIAN_POINT('',(-0.101943396327,0.78,-0.267947319425)); +#37454 = CARTESIAN_POINT('',(-0.102557703262,0.78,-0.273034351424)); +#37455 = CARTESIAN_POINT('',(-0.103661139043,0.78,-0.27786003999)); +#37456 = CARTESIAN_POINT('',(-0.105080162052,0.78,-0.282497287228)); +#37457 = CARTESIAN_POINT('',(-0.107003343979,0.78,-0.28686541831)); +#37458 = CARTESIAN_POINT('',(-0.109311854622,0.78,-0.29102706702)); +#37459 = CARTESIAN_POINT('',(-0.112138842285,0.78,-0.294872541544)); +#37460 = CARTESIAN_POINT('',(-0.115238859767,0.78,-0.298532396355)); +#37461 = CARTESIAN_POINT('',(-0.118747041454,0.78,-0.30184541093)); +#37462 = CARTESIAN_POINT('',(-0.122621172084,0.78,-0.304702348574)); +#37463 = CARTESIAN_POINT('',(-0.126738471674,0.78,-0.307225508361)); +#37464 = CARTESIAN_POINT('',(-0.131223492272,0.78,-0.309160984933)); +#37465 = CARTESIAN_POINT('',(-0.135977422796,0.78,-0.310711345801)); +#37466 = CARTESIAN_POINT('',(-0.14102284836,0.78,-0.31183786157)); +#37467 = CARTESIAN_POINT('',(-0.146380340656,0.78,-0.312526470698)); +#37468 = CARTESIAN_POINT('',(-0.150050199095,0.78,-0.312590346173)); +#37469 = CARTESIAN_POINT('',(-0.151938793802,0.78,-0.312623217982)); +#37470 = PCURVE('',#36564,#37471); +#37471 = DEFINITIONAL_REPRESENTATION('',(#37472),#37476); +#37472 = LINE('',#37473,#37474); +#37473 = CARTESIAN_POINT('',(0.E+000,1.)); +#37474 = VECTOR('',#37475,1.); +#37475 = DIRECTION('',(1.,0.E+000)); +#37476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37477 = PCURVE('',#37228,#37478); +#37478 = DEFINITIONAL_REPRESENTATION('',(#37479),#37499); +#37479 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37480,#37481,#37482,#37483, + #37484,#37485,#37486,#37487,#37488,#37489,#37490,#37491,#37492, + #37493,#37494,#37495,#37496,#37497,#37498),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.661618043518E-002, 0.130423869924,0.19267095757,0.252968504796,0.312880382806, 0.372200255918,0.431927107146,0.492421745255,0.552771220908, 0.613262406816,0.673556490556,0.734319796033,0.79685808014, 0.861769004751,0.928863107315,1.),.UNSPECIFIED.); -#35088 = CARTESIAN_POINT('',(-0.887717987126,0.898172231821)); -#35089 = CARTESIAN_POINT('',(-0.88948594315,0.89813313974)); -#35090 = CARTESIAN_POINT('',(-0.892947319425,0.898056603673)); -#35091 = CARTESIAN_POINT('',(-0.898034351424,0.897442296738)); -#35092 = CARTESIAN_POINT('',(-0.90286003999,0.896338860957)); -#35093 = CARTESIAN_POINT('',(-0.907497287228,0.894919837948)); -#35094 = CARTESIAN_POINT('',(-0.91186541831,0.892996656021)); -#35095 = CARTESIAN_POINT('',(-0.91602706702,0.890688145378)); -#35096 = CARTESIAN_POINT('',(-0.919872541544,0.887861157715)); -#35097 = CARTESIAN_POINT('',(-0.923532396355,0.884761140233)); -#35098 = CARTESIAN_POINT('',(-0.92684541093,0.881252958546)); -#35099 = CARTESIAN_POINT('',(-0.929702348574,0.877378827916)); -#35100 = CARTESIAN_POINT('',(-0.932225508361,0.873261528326)); -#35101 = CARTESIAN_POINT('',(-0.934160984933,0.868776507728)); -#35102 = CARTESIAN_POINT('',(-0.935711345801,0.864022577204)); -#35103 = CARTESIAN_POINT('',(-0.93683786157,0.85897715164)); -#35104 = CARTESIAN_POINT('',(-0.937526470698,0.853619659344)); -#35105 = CARTESIAN_POINT('',(-0.937590346173,0.849949800905)); -#35106 = CARTESIAN_POINT('',(-0.937623217982,0.848061206198)); -#35107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35108 = ORIENTED_EDGE('',*,*,#35034,.F.); -#35109 = ORIENTED_EDGE('',*,*,#34124,.T.); -#35110 = ORIENTED_EDGE('',*,*,#34864,.T.); -#35111 = ADVANCED_FACE('',(#35112),#34836,.T.); -#35112 = FACE_BOUND('',#35113,.T.); -#35113 = EDGE_LOOP('',(#35114,#35115,#35116,#35117)); -#35114 = ORIENTED_EDGE('',*,*,#34802,.T.); -#35115 = ORIENTED_EDGE('',*,*,#34906,.T.); -#35116 = ORIENTED_EDGE('',*,*,#34977,.T.); -#35117 = ORIENTED_EDGE('',*,*,#35056,.T.); -#35118 = ADVANCED_FACE('',(#35119),#34543,.T.); -#35119 = FACE_BOUND('',#35120,.T.); -#35120 = EDGE_LOOP('',(#35121,#35122,#35123,#35124)); -#35121 = ORIENTED_EDGE('',*,*,#34513,.T.); -#35122 = ORIENTED_EDGE('',*,*,#34609,.T.); -#35123 = ORIENTED_EDGE('',*,*,#34680,.T.); -#35124 = ORIENTED_EDGE('',*,*,#34751,.T.); -#35125 = ADVANCED_FACE('',(#35126,#35416),#35148,.T.); -#35126 = FACE_BOUND('',#35127,.T.); -#35127 = EDGE_LOOP('',(#35128,#35174,#35213,#35284,#35347)); -#35128 = ORIENTED_EDGE('',*,*,#35129,.F.); -#35129 = EDGE_CURVE('',#35130,#35132,#35134,.T.); -#35130 = VERTEX_POINT('',#35131); -#35131 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) - ); -#35132 = VERTEX_POINT('',#35133); -#35133 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) - ); -#35134 = SURFACE_CURVE('',#35135,(#35147,#35167),.PCURVE_S1.); -#35135 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35136,#35137,#35138,#35139, - #35140,#35141,#35142,#35143,#35144,#35145,#35146),.UNSPECIFIED.,.F., +#37480 = CARTESIAN_POINT('',(-0.887717987126,0.898172231821)); +#37481 = CARTESIAN_POINT('',(-0.88948594315,0.89813313974)); +#37482 = CARTESIAN_POINT('',(-0.892947319425,0.898056603673)); +#37483 = CARTESIAN_POINT('',(-0.898034351424,0.897442296738)); +#37484 = CARTESIAN_POINT('',(-0.90286003999,0.896338860957)); +#37485 = CARTESIAN_POINT('',(-0.907497287228,0.894919837948)); +#37486 = CARTESIAN_POINT('',(-0.91186541831,0.892996656021)); +#37487 = CARTESIAN_POINT('',(-0.91602706702,0.890688145378)); +#37488 = CARTESIAN_POINT('',(-0.919872541544,0.887861157715)); +#37489 = CARTESIAN_POINT('',(-0.923532396355,0.884761140233)); +#37490 = CARTESIAN_POINT('',(-0.92684541093,0.881252958546)); +#37491 = CARTESIAN_POINT('',(-0.929702348574,0.877378827916)); +#37492 = CARTESIAN_POINT('',(-0.932225508361,0.873261528326)); +#37493 = CARTESIAN_POINT('',(-0.934160984933,0.868776507728)); +#37494 = CARTESIAN_POINT('',(-0.935711345801,0.864022577204)); +#37495 = CARTESIAN_POINT('',(-0.93683786157,0.85897715164)); +#37496 = CARTESIAN_POINT('',(-0.937526470698,0.853619659344)); +#37497 = CARTESIAN_POINT('',(-0.937590346173,0.849949800905)); +#37498 = CARTESIAN_POINT('',(-0.937623217982,0.848061206198)); +#37499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37500 = ORIENTED_EDGE('',*,*,#37426,.F.); +#37501 = ORIENTED_EDGE('',*,*,#36516,.T.); +#37502 = ORIENTED_EDGE('',*,*,#37256,.T.); +#37503 = ADVANCED_FACE('',(#37504),#37228,.T.); +#37504 = FACE_BOUND('',#37505,.T.); +#37505 = EDGE_LOOP('',(#37506,#37507,#37508,#37509)); +#37506 = ORIENTED_EDGE('',*,*,#37194,.T.); +#37507 = ORIENTED_EDGE('',*,*,#37298,.T.); +#37508 = ORIENTED_EDGE('',*,*,#37369,.T.); +#37509 = ORIENTED_EDGE('',*,*,#37448,.T.); +#37510 = ADVANCED_FACE('',(#37511),#36935,.T.); +#37511 = FACE_BOUND('',#37512,.T.); +#37512 = EDGE_LOOP('',(#37513,#37514,#37515,#37516)); +#37513 = ORIENTED_EDGE('',*,*,#36905,.T.); +#37514 = ORIENTED_EDGE('',*,*,#37001,.T.); +#37515 = ORIENTED_EDGE('',*,*,#37072,.T.); +#37516 = ORIENTED_EDGE('',*,*,#37143,.T.); +#37517 = ADVANCED_FACE('',(#37518,#37808),#37540,.T.); +#37518 = FACE_BOUND('',#37519,.T.); +#37519 = EDGE_LOOP('',(#37520,#37566,#37605,#37676,#37739)); +#37520 = ORIENTED_EDGE('',*,*,#37521,.F.); +#37521 = EDGE_CURVE('',#37522,#37524,#37526,.T.); +#37522 = VERTEX_POINT('',#37523); +#37523 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) + ); +#37524 = VERTEX_POINT('',#37525); +#37525 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) + ); +#37526 = SURFACE_CURVE('',#37527,(#37539,#37559),.PCURVE_S1.); +#37527 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37528,#37529,#37530,#37531, + #37532,#37533,#37534,#37535,#37536,#37537,#37538),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,9.742066817721E-002,0.200885588039, 0.311171970173,0.429797945825,0.557739926365,0.694715269364, 0.842129910206,1.),.UNSPECIFIED.); -#35136 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) +#37528 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) ); -#35137 = CARTESIAN_POINT('',(-1.3056297112E-002,0.782,-0.21189029918)); -#35138 = CARTESIAN_POINT('',(-1.725352258953E-002,0.782,-0.217944858507) +#37529 = CARTESIAN_POINT('',(-1.3056297112E-002,0.782,-0.21189029918)); +#37530 = CARTESIAN_POINT('',(-1.725352258953E-002,0.782,-0.217944858507) ); -#35139 = CARTESIAN_POINT('',(-2.216601109072E-002,0.782,-0.228268443793) +#37531 = CARTESIAN_POINT('',(-2.216601109072E-002,0.782,-0.228268443793) ); -#35140 = CARTESIAN_POINT('',(-2.654803780823E-002,0.782,-0.23963326173) +#37532 = CARTESIAN_POINT('',(-2.654803780823E-002,0.782,-0.23963326173) ); -#35141 = CARTESIAN_POINT('',(-2.998712535972E-002,0.782,-0.2522622887)); -#35142 = CARTESIAN_POINT('',(-3.268078820585E-002,0.782,-0.266055011925) +#37533 = CARTESIAN_POINT('',(-2.998712535972E-002,0.782,-0.2522622887)); +#37534 = CARTESIAN_POINT('',(-3.268078820585E-002,0.782,-0.266055011925) ); -#35143 = CARTESIAN_POINT('',(-3.462628530538E-002,0.782,-0.281038495666) +#37535 = CARTESIAN_POINT('',(-3.462628530538E-002,0.782,-0.281038495666) ); -#35144 = CARTESIAN_POINT('',(-3.572724513147E-002,0.782,-0.297206266562) +#37536 = CARTESIAN_POINT('',(-3.572724513147E-002,0.782,-0.297206266562) ); -#35145 = CARTESIAN_POINT('',(-3.58895244037E-002,0.782,-0.308385584215) +#37537 = CARTESIAN_POINT('',(-3.58895244037E-002,0.782,-0.308385584215) ); -#35146 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) +#37538 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) ); -#35147 = PCURVE('',#35148,#35153); -#35148 = PLANE('',#35149); -#35149 = AXIS2_PLACEMENT_3D('',#35150,#35151,#35152); -#35150 = CARTESIAN_POINT('',(-3.136132771767E-002,0.782,-0.259508284596) +#37539 = PCURVE('',#37540,#37545); +#37540 = PLANE('',#37541); +#37541 = AXIS2_PLACEMENT_3D('',#37542,#37543,#37544); +#37542 = CARTESIAN_POINT('',(-3.136132771767E-002,0.782,-0.259508284596) ); -#35151 = DIRECTION('',(0.E+000,1.,0.E+000)); -#35152 = DIRECTION('',(0.E+000,0.E+000,1.)); -#35153 = DEFINITIONAL_REPRESENTATION('',(#35154),#35166); -#35154 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35155,#35156,#35157,#35158, - #35159,#35160,#35161,#35162,#35163,#35164,#35165),.UNSPECIFIED.,.F., +#37543 = DIRECTION('',(0.E+000,1.,0.E+000)); +#37544 = DIRECTION('',(0.E+000,0.E+000,1.)); +#37545 = DEFINITIONAL_REPRESENTATION('',(#37546),#37558); +#37546 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37547,#37548,#37549,#37550, + #37551,#37552,#37553,#37554,#37555,#37556,#37557),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,9.742066817721E-002,0.200885588039, 0.311171970173,0.429797945825,0.557739926365,0.694715269364, 0.842129910206,1.),.UNSPECIFIED.); -#35155 = CARTESIAN_POINT('',(5.0554180197E-002,2.03405002205E-002)); -#35156 = CARTESIAN_POINT('',(4.761798541601E-002,1.830503060567E-002)); -#35157 = CARTESIAN_POINT('',(4.156342608876E-002,1.410780512814E-002)); -#35158 = CARTESIAN_POINT('',(3.123984080342E-002,9.195316626952E-003)); -#35159 = CARTESIAN_POINT('',(1.987502286596E-002,4.813289909443E-003)); -#35160 = CARTESIAN_POINT('',(7.245995895723E-003,1.374202357951E-003)); -#35161 = CARTESIAN_POINT('',(-6.546727329082E-003,-1.319460488178E-003) +#37547 = CARTESIAN_POINT('',(5.0554180197E-002,2.03405002205E-002)); +#37548 = CARTESIAN_POINT('',(4.761798541601E-002,1.830503060567E-002)); +#37549 = CARTESIAN_POINT('',(4.156342608876E-002,1.410780512814E-002)); +#37550 = CARTESIAN_POINT('',(3.123984080342E-002,9.195316626952E-003)); +#37551 = CARTESIAN_POINT('',(1.987502286596E-002,4.813289909443E-003)); +#37552 = CARTESIAN_POINT('',(7.245995895723E-003,1.374202357951E-003)); +#37553 = CARTESIAN_POINT('',(-6.546727329082E-003,-1.319460488178E-003) ); -#35162 = CARTESIAN_POINT('',(-2.153021106945E-002,-3.264957587712E-003) +#37554 = CARTESIAN_POINT('',(-2.153021106945E-002,-3.264957587712E-003) ); -#35163 = CARTESIAN_POINT('',(-3.76979819661E-002,-4.365917413801E-003)); -#35164 = CARTESIAN_POINT('',(-4.887729961931E-002,-4.528196686024E-003) +#37555 = CARTESIAN_POINT('',(-3.76979819661E-002,-4.365917413801E-003)); +#37556 = CARTESIAN_POINT('',(-4.887729961931E-002,-4.528196686024E-003) ); -#35165 = CARTESIAN_POINT('',(-5.465839413417E-002,-4.612115207676E-003) +#37557 = CARTESIAN_POINT('',(-5.465839413417E-002,-4.612115207676E-003) ); -#35166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35167 = PCURVE('',#29794,#35168); -#35168 = DEFINITIONAL_REPRESENTATION('',(#35169),#35173); -#35169 = LINE('',#35170,#35171); -#35170 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35171 = VECTOR('',#35172,1.); -#35172 = DIRECTION('',(1.,0.E+000)); -#35173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37559 = PCURVE('',#32186,#37560); +#37560 = DEFINITIONAL_REPRESENTATION('',(#37561),#37565); +#37561 = LINE('',#37562,#37563); +#37562 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37563 = VECTOR('',#37564,1.); +#37564 = DIRECTION('',(1.,0.E+000)); +#37565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35174 = ORIENTED_EDGE('',*,*,#35175,.F.); -#35175 = EDGE_CURVE('',#35176,#35130,#35178,.T.); -#35176 = VERTEX_POINT('',#35177); -#35177 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) +#37566 = ORIENTED_EDGE('',*,*,#37567,.F.); +#37567 = EDGE_CURVE('',#37568,#37522,#37570,.T.); +#37568 = VERTEX_POINT('',#37569); +#37569 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) ); -#35178 = SURFACE_CURVE('',#35179,(#35191,#35206),.PCURVE_S1.); -#35179 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35180,#35181,#35182,#35183, - #35184,#35185,#35186,#35187,#35188,#35189,#35190),.UNSPECIFIED.,.F., +#37570 = SURFACE_CURVE('',#37571,(#37583,#37598),.PCURVE_S1.); +#37571 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37572,#37573,#37574,#37575, + #37576,#37577,#37578,#37579,#37580,#37581,#37582),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.137903229993,0.2688733426, 0.395178127346,0.517089238131,0.636743026514,0.756221816464, 0.876628359464,1.),.UNSPECIFIED.); -#35180 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) +#37572 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) ); -#35181 = CARTESIAN_POINT('',(4.337436589961E-002,0.782,-0.184292005932) +#37573 = CARTESIAN_POINT('',(4.337436589961E-002,0.782,-0.184292005932) ); -#35182 = CARTESIAN_POINT('',(3.758349277912E-002,0.782,-0.184457190894) +#37574 = CARTESIAN_POINT('',(3.758349277912E-002,0.782,-0.184457190894) ); -#35183 = CARTESIAN_POINT('',(2.912634958092E-002,0.782,-0.185579520965) +#37575 = CARTESIAN_POINT('',(2.912634958092E-002,0.782,-0.185579520965) ); -#35184 = CARTESIAN_POINT('',(2.118886959051E-002,0.782,-0.187554874584) +#37576 = CARTESIAN_POINT('',(2.118886959051E-002,0.782,-0.187554874584) ); -#35185 = CARTESIAN_POINT('',(1.370410470972E-002,0.782,-0.190204102324) +#37577 = CARTESIAN_POINT('',(1.370410470972E-002,0.782,-0.190204102324) ); -#35186 = CARTESIAN_POINT('',(6.756185742306E-003,0.782,-0.193747596984) +#37578 = CARTESIAN_POINT('',(6.756185742306E-003,0.782,-0.193747596984) ); -#35187 = CARTESIAN_POINT('',(3.119391379252E-004,0.782,-0.198058950176) +#37579 = CARTESIAN_POINT('',(3.119391379252E-004,0.782,-0.198058950176) ); -#35188 = CARTESIAN_POINT('',(-5.758127593215E-003,0.782,-0.203037853712) +#37580 = CARTESIAN_POINT('',(-5.758127593215E-003,0.782,-0.203037853712) ); -#35189 = CARTESIAN_POINT('',(-9.252427028939E-003,0.782,-0.206966094314) +#37581 = CARTESIAN_POINT('',(-9.252427028939E-003,0.782,-0.206966094314) ); -#35190 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) +#37582 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) ); -#35191 = PCURVE('',#35148,#35192); -#35192 = DEFINITIONAL_REPRESENTATION('',(#35193),#35205); -#35193 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35194,#35195,#35196,#35197, - #35198,#35199,#35200,#35201,#35202,#35203,#35204),.UNSPECIFIED.,.F., +#37583 = PCURVE('',#37540,#37584); +#37584 = DEFINITIONAL_REPRESENTATION('',(#37585),#37597); +#37585 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37586,#37587,#37588,#37589, + #37590,#37591,#37592,#37593,#37594,#37595,#37596),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.137903229993,0.2688733426, 0.395178127346,0.517089238131,0.636743026514,0.756221816464, 0.876628359464,1.),.UNSPECIFIED.); -#35194 = CARTESIAN_POINT('',(7.530100085876E-002,7.77057913595E-002)); -#35195 = CARTESIAN_POINT('',(7.521627866361E-002,7.473569361728E-002)); -#35196 = CARTESIAN_POINT('',(7.505109370165E-002,6.894482049679E-002)); -#35197 = CARTESIAN_POINT('',(7.392876363136E-002,6.048767729859E-002)); -#35198 = CARTESIAN_POINT('',(7.195341001225E-002,5.255019730818E-002)); -#35199 = CARTESIAN_POINT('',(6.930418227168E-002,4.506543242739E-002)); -#35200 = CARTESIAN_POINT('',(6.576068761159E-002,3.811751345998E-002)); -#35201 = CARTESIAN_POINT('',(6.144933442035E-002,3.16732668556E-002)); -#35202 = CARTESIAN_POINT('',(5.647043088358E-002,2.560320012446E-002)); -#35203 = CARTESIAN_POINT('',(5.254219028218E-002,2.210890068873E-002)); -#35204 = CARTESIAN_POINT('',(5.0554180197E-002,2.03405002205E-002)); -#35205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35206 = PCURVE('',#30216,#35207); -#35207 = DEFINITIONAL_REPRESENTATION('',(#35208),#35212); -#35208 = LINE('',#35209,#35210); -#35209 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35210 = VECTOR('',#35211,1.); -#35211 = DIRECTION('',(1.,0.E+000)); -#35212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35213 = ORIENTED_EDGE('',*,*,#35214,.F.); -#35214 = EDGE_CURVE('',#35215,#35176,#35217,.T.); -#35215 = VERTEX_POINT('',#35216); -#35216 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#35217 = SURFACE_CURVE('',#35218,(#35246,#35277),.PCURVE_S1.); -#35218 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35219,#35220,#35221,#35222, - #35223,#35224,#35225,#35226,#35227,#35228,#35229,#35230,#35231, - #35232,#35233,#35234,#35235,#35236,#35237,#35238,#35239,#35240, - #35241,#35242,#35243,#35244,#35245),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#37586 = CARTESIAN_POINT('',(7.530100085876E-002,7.77057913595E-002)); +#37587 = CARTESIAN_POINT('',(7.521627866361E-002,7.473569361728E-002)); +#37588 = CARTESIAN_POINT('',(7.505109370165E-002,6.894482049679E-002)); +#37589 = CARTESIAN_POINT('',(7.392876363136E-002,6.048767729859E-002)); +#37590 = CARTESIAN_POINT('',(7.195341001225E-002,5.255019730818E-002)); +#37591 = CARTESIAN_POINT('',(6.930418227168E-002,4.506543242739E-002)); +#37592 = CARTESIAN_POINT('',(6.576068761159E-002,3.811751345998E-002)); +#37593 = CARTESIAN_POINT('',(6.144933442035E-002,3.16732668556E-002)); +#37594 = CARTESIAN_POINT('',(5.647043088358E-002,2.560320012446E-002)); +#37595 = CARTESIAN_POINT('',(5.254219028218E-002,2.210890068873E-002)); +#37596 = CARTESIAN_POINT('',(5.0554180197E-002,2.03405002205E-002)); +#37597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37598 = PCURVE('',#32608,#37599); +#37599 = DEFINITIONAL_REPRESENTATION('',(#37600),#37604); +#37600 = LINE('',#37601,#37602); +#37601 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37602 = VECTOR('',#37603,1.); +#37603 = DIRECTION('',(1.,0.E+000)); +#37604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37605 = ORIENTED_EDGE('',*,*,#37606,.F.); +#37606 = EDGE_CURVE('',#37607,#37568,#37609,.T.); +#37607 = VERTEX_POINT('',#37608); +#37608 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#37609 = SURFACE_CURVE('',#37610,(#37638,#37669),.PCURVE_S1.); +#37610 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37611,#37612,#37613,#37614, + #37615,#37616,#37617,#37618,#37619,#37620,#37621,#37622,#37623, + #37624,#37625,#37626,#37627,#37628,#37629,#37630,#37631,#37632, + #37633,#37634,#37635,#37636,#37637),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.287394621143E-002,0.122836629992,0.179656567443,0.233960012231, 0.285595018696,0.334513106078,0.380904825906,0.424894591939, @@ -43874,49 +46863,49 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.617448279949,0.652066912769,0.685879714247,0.719174554791, 0.752181646206,0.785240163918,0.818656449777,0.852547740653, 0.887626342259,0.923635078069,0.961021844477,1.),.UNSPECIFIED.); -#35219 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#35220 = CARTESIAN_POINT('',(0.12862857468,0.782,-0.310513555812)); -#35221 = CARTESIAN_POINT('',(0.12856254846,0.782,-0.303376461114)); -#35222 = CARTESIAN_POINT('',(0.128170333926,0.782,-0.292942447254)); -#35223 = CARTESIAN_POINT('',(0.127424306491,0.782,-0.283028963594)); -#35224 = CARTESIAN_POINT('',(0.126506306103,0.782,-0.273613301226)); -#35225 = CARTESIAN_POINT('',(0.125117563801,0.782,-0.264720595538)); -#35226 = CARTESIAN_POINT('',(0.123621118727,0.782,-0.256313063777)); -#35227 = CARTESIAN_POINT('',(0.121770385811,0.782,-0.24842888354)); -#35228 = CARTESIAN_POINT('',(0.119611015005,0.782,-0.241064599394)); -#35229 = CARTESIAN_POINT('',(0.117179073138,0.782,-0.234181271658)); -#35230 = CARTESIAN_POINT('',(0.114512072558,0.782,-0.227726879966)); -#35231 = CARTESIAN_POINT('',(0.111558113332,0.782,-0.221705834687)); -#35232 = CARTESIAN_POINT('',(0.108229274478,0.782,-0.216176862074)); -#35233 = CARTESIAN_POINT('',(0.104677865453,0.782,-0.211066574274)); -#35234 = CARTESIAN_POINT('',(0.100877875962,0.782,-0.206355801449)); -#35235 = CARTESIAN_POINT('',(9.674874177921E-002,0.782,-0.202112345235) +#37611 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#37612 = CARTESIAN_POINT('',(0.12862857468,0.782,-0.310513555812)); +#37613 = CARTESIAN_POINT('',(0.12856254846,0.782,-0.303376461114)); +#37614 = CARTESIAN_POINT('',(0.128170333926,0.782,-0.292942447254)); +#37615 = CARTESIAN_POINT('',(0.127424306491,0.782,-0.283028963594)); +#37616 = CARTESIAN_POINT('',(0.126506306103,0.782,-0.273613301226)); +#37617 = CARTESIAN_POINT('',(0.125117563801,0.782,-0.264720595538)); +#37618 = CARTESIAN_POINT('',(0.123621118727,0.782,-0.256313063777)); +#37619 = CARTESIAN_POINT('',(0.121770385811,0.782,-0.24842888354)); +#37620 = CARTESIAN_POINT('',(0.119611015005,0.782,-0.241064599394)); +#37621 = CARTESIAN_POINT('',(0.117179073138,0.782,-0.234181271658)); +#37622 = CARTESIAN_POINT('',(0.114512072558,0.782,-0.227726879966)); +#37623 = CARTESIAN_POINT('',(0.111558113332,0.782,-0.221705834687)); +#37624 = CARTESIAN_POINT('',(0.108229274478,0.782,-0.216176862074)); +#37625 = CARTESIAN_POINT('',(0.104677865453,0.782,-0.211066574274)); +#37626 = CARTESIAN_POINT('',(0.100877875962,0.782,-0.206355801449)); +#37627 = CARTESIAN_POINT('',(9.674874177921E-002,0.782,-0.202112345235) ); -#35236 = CARTESIAN_POINT('',(9.229463525764E-002,0.782,-0.198360023683) +#37628 = CARTESIAN_POINT('',(9.229463525764E-002,0.782,-0.198360023683) ); -#35237 = CARTESIAN_POINT('',(8.760585146748E-002,0.782,-0.194979960739) +#37629 = CARTESIAN_POINT('',(8.760585146748E-002,0.782,-0.194979960739) ); -#35238 = CARTESIAN_POINT('',(8.258911929682E-002,0.782,-0.192085900606) +#37630 = CARTESIAN_POINT('',(8.258911929682E-002,0.782,-0.192085900606) ); -#35239 = CARTESIAN_POINT('',(7.726639620043E-002,0.782,-0.189688222053) +#37631 = CARTESIAN_POINT('',(7.726639620043E-002,0.782,-0.189688222053) ); -#35240 = CARTESIAN_POINT('',(7.167324534091E-002,0.782,-0.187638326011) +#37632 = CARTESIAN_POINT('',(7.167324534091E-002,0.782,-0.187638326011) ); -#35241 = CARTESIAN_POINT('',(6.575291613377E-002,0.782,-0.186136282424) +#37633 = CARTESIAN_POINT('',(6.575291613377E-002,0.782,-0.186136282424) ); -#35242 = CARTESIAN_POINT('',(5.955209574418E-002,0.782,-0.184986491529) +#37634 = CARTESIAN_POINT('',(5.955209574418E-002,0.782,-0.184986491529) ); -#35243 = CARTESIAN_POINT('',(5.30479370719E-002,0.782,-0.184309411386)); -#35244 = CARTESIAN_POINT('',(4.860978407257E-002,0.782,-0.184241795972) +#37635 = CARTESIAN_POINT('',(5.30479370719E-002,0.782,-0.184309411386)); +#37636 = CARTESIAN_POINT('',(4.860978407257E-002,0.782,-0.184241795972) ); -#35245 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) +#37637 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) ); -#35246 = PCURVE('',#35148,#35247); -#35247 = DEFINITIONAL_REPRESENTATION('',(#35248),#35276); -#35248 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35249,#35250,#35251,#35252, - #35253,#35254,#35255,#35256,#35257,#35258,#35259,#35260,#35261, - #35262,#35263,#35264,#35265,#35266,#35267,#35268,#35269,#35270, - #35271,#35272,#35273,#35274,#35275),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#37638 = PCURVE('',#37540,#37639); +#37639 = DEFINITIONAL_REPRESENTATION('',(#37640),#37668); +#37640 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37641,#37642,#37643,#37644, + #37645,#37646,#37647,#37648,#37649,#37650,#37651,#37652,#37653, + #37654,#37655,#37656,#37657,#37658,#37659,#37660,#37661,#37662, + #37663,#37664,#37665,#37666,#37667),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.287394621143E-002,0.122836629992,0.179656567443,0.233960012231, 0.285595018696,0.334513106078,0.380904825906,0.424894591939, @@ -43924,144 +46913,144 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.617448279949,0.652066912769,0.685879714247,0.719174554791, 0.752181646206,0.785240163918,0.818656449777,0.852547740653, 0.887626342259,0.923635078069,0.961021844477,1.),.UNSPECIFIED.); -#35249 = CARTESIAN_POINT('',(-5.465839413417E-002,0.160023697927)); -#35250 = CARTESIAN_POINT('',(-5.10052712163E-002,0.159989902397)); -#35251 = CARTESIAN_POINT('',(-4.386817651783E-002,0.159923876178)); -#35252 = CARTESIAN_POINT('',(-3.343416265799E-002,0.159531661643)); -#35253 = CARTESIAN_POINT('',(-2.352067899766E-002,0.158785634209)); -#35254 = CARTESIAN_POINT('',(-1.41050166301E-002,0.157867633821)); -#35255 = CARTESIAN_POINT('',(-5.212310942359E-003,0.156478891519)); -#35256 = CARTESIAN_POINT('',(3.195220819352E-003,0.154982446445)); -#35257 = CARTESIAN_POINT('',(1.107940105639E-002,0.153131713529)); -#35258 = CARTESIAN_POINT('',(1.844368520175E-002,0.150972342723)); -#35259 = CARTESIAN_POINT('',(2.532701293796E-002,0.148540400855)); -#35260 = CARTESIAN_POINT('',(3.178140462962E-002,0.145873400275)); -#35261 = CARTESIAN_POINT('',(3.780244990955E-002,0.14291944105)); -#35262 = CARTESIAN_POINT('',(4.333142252206E-002,0.139590602196)); -#35263 = CARTESIAN_POINT('',(4.844171032182E-002,0.136039193171)); -#35264 = CARTESIAN_POINT('',(5.315248314716E-002,0.13223920368)); -#35265 = CARTESIAN_POINT('',(5.739593936075E-002,0.128110069497)); -#35266 = CARTESIAN_POINT('',(6.114826091294E-002,0.123655962975)); -#35267 = CARTESIAN_POINT('',(6.452832385723E-002,0.118967179185)); -#35268 = CARTESIAN_POINT('',(6.742238399006E-002,0.113950447014)); -#35269 = CARTESIAN_POINT('',(6.982006254266E-002,0.108627723918)); -#35270 = CARTESIAN_POINT('',(7.186995858495E-002,0.103034573059)); -#35271 = CARTESIAN_POINT('',(7.337200217202E-002,9.711424385144E-002)); -#35272 = CARTESIAN_POINT('',(7.452179306685E-002,9.091342346185E-002)); -#35273 = CARTESIAN_POINT('',(7.519887321034E-002,8.440926478957E-002)); -#35274 = CARTESIAN_POINT('',(7.526648862403E-002,7.997111179024E-002)); -#35275 = CARTESIAN_POINT('',(7.530100085876E-002,7.77057913595E-002)); -#35276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35277 = PCURVE('',#30124,#35278); -#35278 = DEFINITIONAL_REPRESENTATION('',(#35279),#35283); -#35279 = LINE('',#35280,#35281); -#35280 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35281 = VECTOR('',#35282,1.); -#35282 = DIRECTION('',(1.,0.E+000)); -#35283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35284 = ORIENTED_EDGE('',*,*,#35285,.F.); -#35285 = EDGE_CURVE('',#35286,#35215,#35288,.T.); -#35286 = VERTEX_POINT('',#35287); -#35287 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#35288 = SURFACE_CURVE('',#35289,(#35313,#35340),.PCURVE_S1.); -#35289 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35290,#35291,#35292,#35293, - #35294,#35295,#35296,#35297,#35298,#35299,#35300,#35301,#35302, - #35303,#35304,#35305,#35306,#35307,#35308,#35309,#35310,#35311, - #35312),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 +#37641 = CARTESIAN_POINT('',(-5.465839413417E-002,0.160023697927)); +#37642 = CARTESIAN_POINT('',(-5.10052712163E-002,0.159989902397)); +#37643 = CARTESIAN_POINT('',(-4.386817651783E-002,0.159923876178)); +#37644 = CARTESIAN_POINT('',(-3.343416265799E-002,0.159531661643)); +#37645 = CARTESIAN_POINT('',(-2.352067899766E-002,0.158785634209)); +#37646 = CARTESIAN_POINT('',(-1.41050166301E-002,0.157867633821)); +#37647 = CARTESIAN_POINT('',(-5.212310942359E-003,0.156478891519)); +#37648 = CARTESIAN_POINT('',(3.195220819352E-003,0.154982446445)); +#37649 = CARTESIAN_POINT('',(1.107940105639E-002,0.153131713529)); +#37650 = CARTESIAN_POINT('',(1.844368520175E-002,0.150972342723)); +#37651 = CARTESIAN_POINT('',(2.532701293796E-002,0.148540400855)); +#37652 = CARTESIAN_POINT('',(3.178140462962E-002,0.145873400275)); +#37653 = CARTESIAN_POINT('',(3.780244990955E-002,0.14291944105)); +#37654 = CARTESIAN_POINT('',(4.333142252206E-002,0.139590602196)); +#37655 = CARTESIAN_POINT('',(4.844171032182E-002,0.136039193171)); +#37656 = CARTESIAN_POINT('',(5.315248314716E-002,0.13223920368)); +#37657 = CARTESIAN_POINT('',(5.739593936075E-002,0.128110069497)); +#37658 = CARTESIAN_POINT('',(6.114826091294E-002,0.123655962975)); +#37659 = CARTESIAN_POINT('',(6.452832385723E-002,0.118967179185)); +#37660 = CARTESIAN_POINT('',(6.742238399006E-002,0.113950447014)); +#37661 = CARTESIAN_POINT('',(6.982006254266E-002,0.108627723918)); +#37662 = CARTESIAN_POINT('',(7.186995858495E-002,0.103034573059)); +#37663 = CARTESIAN_POINT('',(7.337200217202E-002,9.711424385144E-002)); +#37664 = CARTESIAN_POINT('',(7.452179306685E-002,9.091342346185E-002)); +#37665 = CARTESIAN_POINT('',(7.519887321034E-002,8.440926478957E-002)); +#37666 = CARTESIAN_POINT('',(7.526648862403E-002,7.997111179024E-002)); +#37667 = CARTESIAN_POINT('',(7.530100085876E-002,7.77057913595E-002)); +#37668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37669 = PCURVE('',#32516,#37670); +#37670 = DEFINITIONAL_REPRESENTATION('',(#37671),#37675); +#37671 = LINE('',#37672,#37673); +#37672 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37673 = VECTOR('',#37674,1.); +#37674 = DIRECTION('',(1.,0.E+000)); +#37675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37676 = ORIENTED_EDGE('',*,*,#37677,.F.); +#37677 = EDGE_CURVE('',#37678,#37607,#37680,.T.); +#37678 = VERTEX_POINT('',#37679); +#37679 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#37680 = SURFACE_CURVE('',#37681,(#37705,#37732),.PCURVE_S1.); +#37681 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37682,#37683,#37684,#37685, + #37686,#37687,#37688,#37689,#37690,#37691,#37692,#37693,#37694, + #37695,#37696,#37697,#37698,#37699,#37700,#37701,#37702,#37703, + #37704),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 ,1,4),(0.E+000,5.672433721815E-002,0.111437235737,0.164367822223, 0.216435372462,0.267641490322,0.317359779969,0.367473063332, 0.418210397053,0.471404282647,0.527965720129,0.588061115823, 0.652134262994,0.686344836335,0.723263680317,0.762610250772, 0.804738936645,0.849430338791,0.896711258386,0.946889638053,1.), .UNSPECIFIED.); -#35290 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#35291 = CARTESIAN_POINT('',(4.964286228049E-002,0.782,-0.444234897904) - ); -#35292 = CARTESIAN_POINT('',(5.612269870835E-002,0.782,-0.444044395299) - ); -#35293 = CARTESIAN_POINT('',(6.558329335559E-002,0.782,-0.442490690621) - ); -#35294 = CARTESIAN_POINT('',(7.449929406124E-002,0.782,-0.439832839307) - ); -#35295 = CARTESIAN_POINT('',(8.286490816458E-002,0.782,-0.436247283227) - ); -#35296 = CARTESIAN_POINT('',(9.053712678853E-002,0.782,-0.431692936904) - ); -#35297 = CARTESIAN_POINT('',(9.738874139268E-002,0.782,-0.426156435073) - ); -#35298 = CARTESIAN_POINT('',(0.103345846246,0.782,-0.419695909909)); -#35299 = CARTESIAN_POINT('',(0.108343428768,0.782,-0.412234806307)); -#35300 = CARTESIAN_POINT('',(0.112711814733,0.782,-0.403978951331)); -#35301 = CARTESIAN_POINT('',(0.116592592929,0.782,-0.394891289657)); -#35302 = CARTESIAN_POINT('',(0.120100703701,0.782,-0.384982005036)); -#35303 = CARTESIAN_POINT('',(0.122590135474,0.782,-0.376111811952)); -#35304 = CARTESIAN_POINT('',(0.124365845114,0.782,-0.36845474654)); -#35305 = CARTESIAN_POINT('',(0.12554122381,0.782,-0.362139415592)); -#35306 = CARTESIAN_POINT('',(0.126517023766,0.782,-0.355325137946)); -#35307 = CARTESIAN_POINT('',(0.127264618408,0.782,-0.348028399174)); -#35308 = CARTESIAN_POINT('',(0.127878002172,0.782,-0.340257383216)); -#35309 = CARTESIAN_POINT('',(0.128351690341,0.782,-0.332007251691)); -#35310 = CARTESIAN_POINT('',(0.128592135588,0.782,-0.323257384797)); -#35311 = CARTESIAN_POINT('',(0.128638519777,0.782,-0.317253721294)); -#35312 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#35313 = PCURVE('',#35148,#35314); -#35314 = DEFINITIONAL_REPRESENTATION('',(#35315),#35339); -#35315 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35316,#35317,#35318,#35319, - #35320,#35321,#35322,#35323,#35324,#35325,#35326,#35327,#35328, - #35329,#35330,#35331,#35332,#35333,#35334,#35335,#35336,#35337, - #35338),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 +#37682 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#37683 = CARTESIAN_POINT('',(4.964286228049E-002,0.782,-0.444234897904) + ); +#37684 = CARTESIAN_POINT('',(5.612269870835E-002,0.782,-0.444044395299) + ); +#37685 = CARTESIAN_POINT('',(6.558329335559E-002,0.782,-0.442490690621) + ); +#37686 = CARTESIAN_POINT('',(7.449929406124E-002,0.782,-0.439832839307) + ); +#37687 = CARTESIAN_POINT('',(8.286490816458E-002,0.782,-0.436247283227) + ); +#37688 = CARTESIAN_POINT('',(9.053712678853E-002,0.782,-0.431692936904) + ); +#37689 = CARTESIAN_POINT('',(9.738874139268E-002,0.782,-0.426156435073) + ); +#37690 = CARTESIAN_POINT('',(0.103345846246,0.782,-0.419695909909)); +#37691 = CARTESIAN_POINT('',(0.108343428768,0.782,-0.412234806307)); +#37692 = CARTESIAN_POINT('',(0.112711814733,0.782,-0.403978951331)); +#37693 = CARTESIAN_POINT('',(0.116592592929,0.782,-0.394891289657)); +#37694 = CARTESIAN_POINT('',(0.120100703701,0.782,-0.384982005036)); +#37695 = CARTESIAN_POINT('',(0.122590135474,0.782,-0.376111811952)); +#37696 = CARTESIAN_POINT('',(0.124365845114,0.782,-0.36845474654)); +#37697 = CARTESIAN_POINT('',(0.12554122381,0.782,-0.362139415592)); +#37698 = CARTESIAN_POINT('',(0.126517023766,0.782,-0.355325137946)); +#37699 = CARTESIAN_POINT('',(0.127264618408,0.782,-0.348028399174)); +#37700 = CARTESIAN_POINT('',(0.127878002172,0.782,-0.340257383216)); +#37701 = CARTESIAN_POINT('',(0.128351690341,0.782,-0.332007251691)); +#37702 = CARTESIAN_POINT('',(0.128592135588,0.782,-0.323257384797)); +#37703 = CARTESIAN_POINT('',(0.128638519777,0.782,-0.317253721294)); +#37704 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#37705 = PCURVE('',#37540,#37706); +#37706 = DEFINITIONAL_REPRESENTATION('',(#37707),#37731); +#37707 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37708,#37709,#37710,#37711, + #37712,#37713,#37714,#37715,#37716,#37717,#37718,#37719,#37720, + #37721,#37722,#37723,#37724,#37725,#37726,#37727,#37728,#37729, + #37730),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1 ,1,4),(0.E+000,5.672433721815E-002,0.111437235737,0.164367822223, 0.216435372462,0.267641490322,0.317359779969,0.367473063332, 0.418210397053,0.471404282647,0.527965720129,0.588061115823, 0.652134262994,0.686344836335,0.723263680317,0.762610250772, 0.804738936645,0.849430338791,0.896711258386,0.946889638053,1.), .UNSPECIFIED.); -#35316 = CARTESIAN_POINT('',(-0.184823583894,7.77057913595E-002)); -#35317 = CARTESIAN_POINT('',(-0.184726613308,8.100418999817E-002)); -#35318 = CARTESIAN_POINT('',(-0.184536110703,8.748402642602E-002)); -#35319 = CARTESIAN_POINT('',(-0.182982406025,9.694462107326E-002)); -#35320 = CARTESIAN_POINT('',(-0.180324554711,0.105860621779)); -#35321 = CARTESIAN_POINT('',(-0.17673899863,0.114226235882)); -#35322 = CARTESIAN_POINT('',(-0.172184652308,0.121898454506)); -#35323 = CARTESIAN_POINT('',(-0.166648150477,0.12875006911)); -#35324 = CARTESIAN_POINT('',(-0.160187625313,0.134707173964)); -#35325 = CARTESIAN_POINT('',(-0.152726521711,0.139704756485)); -#35326 = CARTESIAN_POINT('',(-0.144470666735,0.14407314245)); -#35327 = CARTESIAN_POINT('',(-0.135383005061,0.147953920647)); -#35328 = CARTESIAN_POINT('',(-0.12547372044,0.151462031419)); -#35329 = CARTESIAN_POINT('',(-0.116603527356,0.153951463192)); -#35330 = CARTESIAN_POINT('',(-0.108946461944,0.155727172832)); -#35331 = CARTESIAN_POINT('',(-0.102631130996,0.156902551527)); -#35332 = CARTESIAN_POINT('',(-9.581685335022E-002,0.157878351484)); -#35333 = CARTESIAN_POINT('',(-8.852011457753E-002,0.158625946125)); -#35334 = CARTESIAN_POINT('',(-8.074909862009E-002,0.159239329889)); -#35335 = CARTESIAN_POINT('',(-7.249896709469E-002,0.159713018059)); -#35336 = CARTESIAN_POINT('',(-6.374910020124E-002,0.159953463306)); -#35337 = CARTESIAN_POINT('',(-5.774543669759E-002,0.159999847495)); -#35338 = CARTESIAN_POINT('',(-5.465839413417E-002,0.160023697927)); -#35339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35340 = PCURVE('',#30006,#35341); -#35341 = DEFINITIONAL_REPRESENTATION('',(#35342),#35346); -#35342 = LINE('',#35343,#35344); -#35343 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35344 = VECTOR('',#35345,1.); -#35345 = DIRECTION('',(1.,0.E+000)); -#35346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35347 = ORIENTED_EDGE('',*,*,#35348,.F.); -#35348 = EDGE_CURVE('',#35132,#35286,#35349,.T.); -#35349 = SURFACE_CURVE('',#35350,(#35378,#35409),.PCURVE_S1.); -#35350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35351,#35352,#35353,#35354, - #35355,#35356,#35357,#35358,#35359,#35360,#35361,#35362,#35363, - #35364,#35365,#35366,#35367,#35368,#35369,#35370,#35371,#35372, - #35373,#35374,#35375,#35376,#35377),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#37708 = CARTESIAN_POINT('',(-0.184823583894,7.77057913595E-002)); +#37709 = CARTESIAN_POINT('',(-0.184726613308,8.100418999817E-002)); +#37710 = CARTESIAN_POINT('',(-0.184536110703,8.748402642602E-002)); +#37711 = CARTESIAN_POINT('',(-0.182982406025,9.694462107326E-002)); +#37712 = CARTESIAN_POINT('',(-0.180324554711,0.105860621779)); +#37713 = CARTESIAN_POINT('',(-0.17673899863,0.114226235882)); +#37714 = CARTESIAN_POINT('',(-0.172184652308,0.121898454506)); +#37715 = CARTESIAN_POINT('',(-0.166648150477,0.12875006911)); +#37716 = CARTESIAN_POINT('',(-0.160187625313,0.134707173964)); +#37717 = CARTESIAN_POINT('',(-0.152726521711,0.139704756485)); +#37718 = CARTESIAN_POINT('',(-0.144470666735,0.14407314245)); +#37719 = CARTESIAN_POINT('',(-0.135383005061,0.147953920647)); +#37720 = CARTESIAN_POINT('',(-0.12547372044,0.151462031419)); +#37721 = CARTESIAN_POINT('',(-0.116603527356,0.153951463192)); +#37722 = CARTESIAN_POINT('',(-0.108946461944,0.155727172832)); +#37723 = CARTESIAN_POINT('',(-0.102631130996,0.156902551527)); +#37724 = CARTESIAN_POINT('',(-9.581685335022E-002,0.157878351484)); +#37725 = CARTESIAN_POINT('',(-8.852011457753E-002,0.158625946125)); +#37726 = CARTESIAN_POINT('',(-8.074909862009E-002,0.159239329889)); +#37727 = CARTESIAN_POINT('',(-7.249896709469E-002,0.159713018059)); +#37728 = CARTESIAN_POINT('',(-6.374910020124E-002,0.159953463306)); +#37729 = CARTESIAN_POINT('',(-5.774543669759E-002,0.159999847495)); +#37730 = CARTESIAN_POINT('',(-5.465839413417E-002,0.160023697927)); +#37731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37732 = PCURVE('',#32398,#37733); +#37733 = DEFINITIONAL_REPRESENTATION('',(#37734),#37738); +#37734 = LINE('',#37735,#37736); +#37735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37736 = VECTOR('',#37737,1.); +#37737 = DIRECTION('',(1.,0.E+000)); +#37738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37739 = ORIENTED_EDGE('',*,*,#37740,.F.); +#37740 = EDGE_CURVE('',#37524,#37678,#37741,.T.); +#37741 = SURFACE_CURVE('',#37742,(#37770,#37801),.PCURVE_S1.); +#37742 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37743,#37744,#37745,#37746, + #37747,#37748,#37749,#37750,#37751,#37752,#37753,#37754,#37755, + #37756,#37757,#37758,#37759,#37760,#37761,#37762,#37763,#37764, + #37765,#37766,#37767,#37768,#37769),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.311445839479E-002,0.123614645769,0.180973711186,0.235261455008, 0.287100701834,0.336030736303,0.382382348585,0.42633408366, @@ -44069,62 +47058,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.61899431503,0.653583018621,0.68715613619,0.720422191979, 0.753230218812,0.786260156078,0.819503983499,0.853545274712, 0.88830828034,0.923995860741,0.961350304755,1.),.UNSPECIFIED.); -#35351 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) +#37743 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) ); -#35352 = CARTESIAN_POINT('',(-3.59402688018E-002,0.782,-0.317837041881) +#37744 = CARTESIAN_POINT('',(-3.59402688018E-002,0.782,-0.317837041881) ); -#35353 = CARTESIAN_POINT('',(-3.587529466378E-002,0.782,-0.32502573766) +#37745 = CARTESIAN_POINT('',(-3.587529466378E-002,0.782,-0.32502573766) ); -#35354 = CARTESIAN_POINT('',(-3.547228119311E-002,0.782,-0.33554409099) +#37746 = CARTESIAN_POINT('',(-3.547228119311E-002,0.782,-0.33554409099) ); -#35355 = CARTESIAN_POINT('',(-3.476865233001E-002,0.782,-0.34553293562) +#37747 = CARTESIAN_POINT('',(-3.476865233001E-002,0.782,-0.34553293562) ); -#35356 = CARTESIAN_POINT('',(-3.371832814217E-002,0.782,-0.354983596705) +#37748 = CARTESIAN_POINT('',(-3.371832814217E-002,0.782,-0.354983596705) ); -#35357 = CARTESIAN_POINT('',(-3.247454752437E-002,0.782,-0.363917406242) +#37749 = CARTESIAN_POINT('',(-3.247454752437E-002,0.782,-0.363917406242) ); -#35358 = CARTESIAN_POINT('',(-3.085762487453E-002,0.782,-0.372321614766) +#37750 = CARTESIAN_POINT('',(-3.085762487453E-002,0.782,-0.372321614766) ); -#35359 = CARTESIAN_POINT('',(-2.903835183156E-002,0.782,-0.380215078472) +#37751 = CARTESIAN_POINT('',(-2.903835183156E-002,0.782,-0.380215078472) ); -#35360 = CARTESIAN_POINT('',(-2.685555065364E-002,0.782,-0.387589569702) +#37752 = CARTESIAN_POINT('',(-2.685555065364E-002,0.782,-0.387589569702) ); -#35361 = CARTESIAN_POINT('',(-2.445736673545E-002,0.782,-0.394508495657) +#37753 = CARTESIAN_POINT('',(-2.445736673545E-002,0.782,-0.394508495657) ); -#35362 = CARTESIAN_POINT('',(-2.173655057069E-002,0.782,-0.400960756818) +#37754 = CARTESIAN_POINT('',(-2.173655057069E-002,0.782,-0.400960756818) ); -#35363 = CARTESIAN_POINT('',(-1.867526329643E-002,0.782,-0.406939512268) +#37755 = CARTESIAN_POINT('',(-1.867526329643E-002,0.782,-0.406939512268) ); -#35364 = CARTESIAN_POINT('',(-1.542394815444E-002,0.782,-0.412506765057) +#37756 = CARTESIAN_POINT('',(-1.542394815444E-002,0.782,-0.412506765057) ); -#35365 = CARTESIAN_POINT('',(-1.181144925028E-002,0.782,-0.417575921489) +#37757 = CARTESIAN_POINT('',(-1.181144925028E-002,0.782,-0.417575921489) ); -#35366 = CARTESIAN_POINT('',(-8.055809774141E-003,0.782,-0.422289242847) +#37758 = CARTESIAN_POINT('',(-8.055809774141E-003,0.782,-0.422289242847) ); -#35367 = CARTESIAN_POINT('',(-3.884092272847E-003,0.782,-0.426473873245) +#37759 = CARTESIAN_POINT('',(-3.884092272847E-003,0.782,-0.426473873245) ); -#35368 = CARTESIAN_POINT('',(5.302342909642E-004,0.782,-0.430237483603) +#37760 = CARTESIAN_POINT('',(5.302342909642E-004,0.782,-0.430237483603) ); -#35369 = CARTESIAN_POINT('',(5.252172020433E-003,0.782,-0.433558650412) +#37761 = CARTESIAN_POINT('',(5.252172020433E-003,0.782,-0.433558650412) ); -#35370 = CARTESIAN_POINT('',(1.0256737177E-002,0.782,-0.436424416779)); -#35371 = CARTESIAN_POINT('',(1.552467355536E-002,0.782,-0.438954681848) +#37762 = CARTESIAN_POINT('',(1.0256737177E-002,0.782,-0.436424416779)); +#37763 = CARTESIAN_POINT('',(1.552467355536E-002,0.782,-0.438954681848) ); -#35372 = CARTESIAN_POINT('',(2.115638219723E-002,0.782,-0.44085946473)); -#35373 = CARTESIAN_POINT('',(2.703494991357E-002,0.782,-0.442412266576) +#37764 = CARTESIAN_POINT('',(2.115638219723E-002,0.782,-0.44085946473)); +#37765 = CARTESIAN_POINT('',(2.703494991357E-002,0.782,-0.442412266576) ); -#35374 = CARTESIAN_POINT('',(3.320562687015E-002,0.782,-0.443554526441) +#37766 = CARTESIAN_POINT('',(3.320562687015E-002,0.782,-0.443554526441) ); -#35375 = CARTESIAN_POINT('',(3.96752130578E-002,0.782,-0.44422792718)); -#35376 = CARTESIAN_POINT('',(4.409626580613E-002,0.782,-0.444296829976) +#37767 = CARTESIAN_POINT('',(3.96752130578E-002,0.782,-0.44422792718)); +#37768 = CARTESIAN_POINT('',(4.409626580613E-002,0.782,-0.444296829976) ); -#35377 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#35378 = PCURVE('',#35148,#35379); -#35379 = DEFINITIONAL_REPRESENTATION('',(#35380),#35408); -#35380 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35381,#35382,#35383,#35384, - #35385,#35386,#35387,#35388,#35389,#35390,#35391,#35392,#35393, - #35394,#35395,#35396,#35397,#35398,#35399,#35400,#35401,#35402, - #35403,#35404,#35405,#35406,#35407),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 +#37769 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#37770 = PCURVE('',#37540,#37771); +#37771 = DEFINITIONAL_REPRESENTATION('',(#37772),#37800); +#37772 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37773,#37774,#37775,#37776, + #37777,#37778,#37779,#37780,#37781,#37782,#37783,#37784,#37785, + #37786,#37787,#37788,#37789,#37790,#37791,#37792,#37793,#37794, + #37795,#37796,#37797,#37798,#37799),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 6.311445839479E-002,0.123614645769,0.180973711186,0.235261455008, 0.287100701834,0.336030736303,0.382382348585,0.42633408366, @@ -44132,4436 +47121,4436 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.61899431503,0.653583018621,0.68715613619,0.720422191979, 0.753230218812,0.786260156078,0.819503983499,0.853545274712, 0.88830828034,0.923995860741,0.961350304755,1.),.UNSPECIFIED.); -#35381 = CARTESIAN_POINT('',(-5.465839413417E-002,-4.612115207676E-003) - ); -#35382 = CARTESIAN_POINT('',(-5.832875728443E-002,-4.578941084131E-003) - ); -#35383 = CARTESIAN_POINT('',(-6.551745306358E-002,-4.513966946111E-003) - ); -#35384 = CARTESIAN_POINT('',(-7.603580639436E-002,-4.110953475443E-003) - ); -#35385 = CARTESIAN_POINT('',(-8.602465102428E-002,-3.407324612335E-003) - ); -#35386 = CARTESIAN_POINT('',(-9.547531210853E-002,-2.357000424501E-003) - ); -#35387 = CARTESIAN_POINT('',(-0.104409121646,-1.113219806694E-003)); -#35388 = CARTESIAN_POINT('',(-0.11281333017,5.037028431395E-004)); -#35389 = CARTESIAN_POINT('',(-0.120706793876,2.322975886114E-003)); -#35390 = CARTESIAN_POINT('',(-0.128081285106,4.505777064027E-003)); -#35391 = CARTESIAN_POINT('',(-0.135000211061,6.903960982218E-003)); -#35392 = CARTESIAN_POINT('',(-0.141452472221,9.62477714698E-003)); -#35393 = CARTESIAN_POINT('',(-0.147431227672,1.268606442124E-002)); -#35394 = CARTESIAN_POINT('',(-0.15299848046,1.593737956323E-002)); -#35395 = CARTESIAN_POINT('',(-0.158067636893,1.954987846739E-002)); -#35396 = CARTESIAN_POINT('',(-0.162780958251,2.330551794353E-002)); -#35397 = CARTESIAN_POINT('',(-0.166965588649,2.747723544482E-002)); -#35398 = CARTESIAN_POINT('',(-0.170729199007,3.189156200864E-002)); -#35399 = CARTESIAN_POINT('',(-0.174050365816,3.66134997381E-002)); -#35400 = CARTESIAN_POINT('',(-0.176916132183,4.161806489467E-002)); -#35401 = CARTESIAN_POINT('',(-0.179446397251,4.688600127303E-002)); -#35402 = CARTESIAN_POINT('',(-0.181351180134,5.25177099149E-002)); -#35403 = CARTESIAN_POINT('',(-0.182903981979,5.839627763124E-002)); -#35404 = CARTESIAN_POINT('',(-0.184046241845,6.456695458782E-002)); -#35405 = CARTESIAN_POINT('',(-0.184719642584,7.103654077547E-002)); -#35406 = CARTESIAN_POINT('',(-0.18478854538,7.54575935238E-002)); -#35407 = CARTESIAN_POINT('',(-0.184823583894,7.77057913595E-002)); -#35408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35409 = PCURVE('',#29888,#35410); -#35410 = DEFINITIONAL_REPRESENTATION('',(#35411),#35415); -#35411 = LINE('',#35412,#35413); -#35412 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35413 = VECTOR('',#35414,1.); -#35414 = DIRECTION('',(1.,0.E+000)); -#35415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35416 = FACE_BOUND('',#35417,.T.); -#35417 = EDGE_LOOP('',(#35418,#35514,#35576,#35638,#35732)); -#35418 = ORIENTED_EDGE('',*,*,#35419,.F.); -#35419 = EDGE_CURVE('',#35420,#35422,#35424,.T.); -#35420 = VERTEX_POINT('',#35421); -#35421 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) - ); -#35422 = VERTEX_POINT('',#35423); -#35423 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) - ); -#35424 = SURFACE_CURVE('',#35425,(#35445,#35468),.PCURVE_S1.); -#35425 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35426,#35427,#35428,#35429, - #35430,#35431,#35432,#35433,#35434,#35435,#35436,#35437,#35438, - #35439,#35440,#35441,#35442,#35443,#35444),.UNSPECIFIED.,.F.,.F.,(4, +#37773 = CARTESIAN_POINT('',(-5.465839413417E-002,-4.612115207676E-003) + ); +#37774 = CARTESIAN_POINT('',(-5.832875728443E-002,-4.578941084131E-003) + ); +#37775 = CARTESIAN_POINT('',(-6.551745306358E-002,-4.513966946111E-003) + ); +#37776 = CARTESIAN_POINT('',(-7.603580639436E-002,-4.110953475443E-003) + ); +#37777 = CARTESIAN_POINT('',(-8.602465102428E-002,-3.407324612335E-003) + ); +#37778 = CARTESIAN_POINT('',(-9.547531210853E-002,-2.357000424501E-003) + ); +#37779 = CARTESIAN_POINT('',(-0.104409121646,-1.113219806694E-003)); +#37780 = CARTESIAN_POINT('',(-0.11281333017,5.037028431395E-004)); +#37781 = CARTESIAN_POINT('',(-0.120706793876,2.322975886114E-003)); +#37782 = CARTESIAN_POINT('',(-0.128081285106,4.505777064027E-003)); +#37783 = CARTESIAN_POINT('',(-0.135000211061,6.903960982218E-003)); +#37784 = CARTESIAN_POINT('',(-0.141452472221,9.62477714698E-003)); +#37785 = CARTESIAN_POINT('',(-0.147431227672,1.268606442124E-002)); +#37786 = CARTESIAN_POINT('',(-0.15299848046,1.593737956323E-002)); +#37787 = CARTESIAN_POINT('',(-0.158067636893,1.954987846739E-002)); +#37788 = CARTESIAN_POINT('',(-0.162780958251,2.330551794353E-002)); +#37789 = CARTESIAN_POINT('',(-0.166965588649,2.747723544482E-002)); +#37790 = CARTESIAN_POINT('',(-0.170729199007,3.189156200864E-002)); +#37791 = CARTESIAN_POINT('',(-0.174050365816,3.66134997381E-002)); +#37792 = CARTESIAN_POINT('',(-0.176916132183,4.161806489467E-002)); +#37793 = CARTESIAN_POINT('',(-0.179446397251,4.688600127303E-002)); +#37794 = CARTESIAN_POINT('',(-0.181351180134,5.25177099149E-002)); +#37795 = CARTESIAN_POINT('',(-0.182903981979,5.839627763124E-002)); +#37796 = CARTESIAN_POINT('',(-0.184046241845,6.456695458782E-002)); +#37797 = CARTESIAN_POINT('',(-0.184719642584,7.103654077547E-002)); +#37798 = CARTESIAN_POINT('',(-0.18478854538,7.54575935238E-002)); +#37799 = CARTESIAN_POINT('',(-0.184823583894,7.77057913595E-002)); +#37800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37801 = PCURVE('',#32280,#37802); +#37802 = DEFINITIONAL_REPRESENTATION('',(#37803),#37807); +#37803 = LINE('',#37804,#37805); +#37804 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37805 = VECTOR('',#37806,1.); +#37806 = DIRECTION('',(1.,0.E+000)); +#37807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37808 = FACE_BOUND('',#37809,.T.); +#37809 = EDGE_LOOP('',(#37810,#37906,#37968,#38030,#38124)); +#37810 = ORIENTED_EDGE('',*,*,#37811,.F.); +#37811 = EDGE_CURVE('',#37812,#37814,#37816,.T.); +#37812 = VERTEX_POINT('',#37813); +#37813 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) + ); +#37814 = VERTEX_POINT('',#37815); +#37815 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) + ); +#37816 = SURFACE_CURVE('',#37817,(#37837,#37860),.PCURVE_S1.); +#37817 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37818,#37819,#37820,#37821, + #37822,#37823,#37824,#37825,#37826,#37827,#37828,#37829,#37830, + #37831,#37832,#37833,#37834,#37835,#37836),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.118405508154, 0.226654332817,0.324092341929,0.411704803005,0.489025905006, 0.556909397343,0.616233344493,0.667349281277,0.713512393201, 0.757696504521,0.799492511442,0.839976064744,0.879885741817, 0.919148659386,0.959227356493,1.),.UNSPECIFIED.); -#35426 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) +#37818 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) ); -#35427 = CARTESIAN_POINT('',(-3.013586244362E-003,0.782,-0.309329765127) +#37819 = CARTESIAN_POINT('',(-3.013586244362E-003,0.782,-0.309329765127) ); -#35428 = CARTESIAN_POINT('',(-2.951002593161E-003,0.782,-0.299873874259) +#37820 = CARTESIAN_POINT('',(-2.951002593161E-003,0.782,-0.299873874259) ); -#35429 = CARTESIAN_POINT('',(-2.297155351481E-003,0.782,-0.286364502734) +#37821 = CARTESIAN_POINT('',(-2.297155351481E-003,0.782,-0.286364502734) ); -#35430 = CARTESIAN_POINT('',(-1.17158423761E-003,0.782,-0.274177205581) +#37822 = CARTESIAN_POINT('',(-1.17158423761E-003,0.782,-0.274177205581) ); -#35431 = CARTESIAN_POINT('',(3.164942935639E-004,0.782,-0.263328856907) +#37823 = CARTESIAN_POINT('',(3.164942935639E-004,0.782,-0.263328856907) ); -#35432 = CARTESIAN_POINT('',(2.281360452602E-003,0.782,-0.253804782175) +#37824 = CARTESIAN_POINT('',(2.281360452602E-003,0.782,-0.253804782175) ); -#35433 = CARTESIAN_POINT('',(4.748482306681E-003,0.782,-0.245629251661) +#37825 = CARTESIAN_POINT('',(4.748482306681E-003,0.782,-0.245629251661) ); -#35434 = CARTESIAN_POINT('',(7.529515432953E-003,0.782,-0.238704140464) +#37826 = CARTESIAN_POINT('',(7.529515432953E-003,0.782,-0.238704140464) ); -#35435 = CARTESIAN_POINT('',(1.09709912278E-002,0.782,-0.233115280007)); -#35436 = CARTESIAN_POINT('',(1.473902710952E-002,0.782,-0.228559543441) +#37827 = CARTESIAN_POINT('',(1.09709912278E-002,0.782,-0.233115280007)); +#37828 = CARTESIAN_POINT('',(1.473902710952E-002,0.782,-0.228559543441) ); -#35437 = CARTESIAN_POINT('',(1.86292666432E-002,0.782,-0.224641462662)); -#35438 = CARTESIAN_POINT('',(2.273323371754E-002,0.782,-0.221311183714) +#37829 = CARTESIAN_POINT('',(1.86292666432E-002,0.782,-0.224641462662)); +#37830 = CARTESIAN_POINT('',(2.273323371754E-002,0.782,-0.221311183714) ); -#35439 = CARTESIAN_POINT('',(2.702415044334E-002,0.782,-0.218534410237) +#37831 = CARTESIAN_POINT('',(2.702415044334E-002,0.782,-0.218534410237) ); -#35440 = CARTESIAN_POINT('',(3.156859348143E-002,0.782,-0.216432019795) +#37832 = CARTESIAN_POINT('',(3.156859348143E-002,0.782,-0.216432019795) ); -#35441 = CARTESIAN_POINT('',(3.631687010258E-002,0.782,-0.214908202522) +#37833 = CARTESIAN_POINT('',(3.631687010258E-002,0.782,-0.214908202522) ); -#35442 = CARTESIAN_POINT('',(4.127001349122E-002,0.782,-0.214031269077) +#37834 = CARTESIAN_POINT('',(4.127001349122E-002,0.782,-0.214031269077) ); -#35443 = CARTESIAN_POINT('',(4.464332921115E-002,0.782,-0.213905270242) +#37835 = CARTESIAN_POINT('',(4.464332921115E-002,0.782,-0.213905270242) ); -#35444 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) +#37836 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) ); -#35445 = PCURVE('',#35148,#35446); -#35446 = DEFINITIONAL_REPRESENTATION('',(#35447),#35467); -#35447 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35448,#35449,#35450,#35451, - #35452,#35453,#35454,#35455,#35456,#35457,#35458,#35459,#35460, - #35461,#35462,#35463,#35464,#35465,#35466),.UNSPECIFIED.,.F.,.F.,(4, +#37837 = PCURVE('',#37540,#37838); +#37838 = DEFINITIONAL_REPRESENTATION('',(#37839),#37859); +#37839 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37840,#37841,#37842,#37843, + #37844,#37845,#37846,#37847,#37848,#37849,#37850,#37851,#37852, + #37853,#37854,#37855,#37856,#37857,#37858),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.118405508154, 0.226654332817,0.324092341929,0.411704803005,0.489025905006, 0.556909397343,0.616233344493,0.667349281277,0.713512393201, 0.757696504521,0.799492511442,0.839976064744,0.879885741817, 0.919148659386,0.959227356493,1.),.UNSPECIFIED.); -#35448 = CARTESIAN_POINT('',(-5.476129151737E-002,2.831504741919E-002)); -#35449 = CARTESIAN_POINT('',(-4.98214805311E-002,2.834774147331E-002)); -#35450 = CARTESIAN_POINT('',(-4.036558966258E-002,2.841032512451E-002)); -#35451 = CARTESIAN_POINT('',(-2.685621813843E-002,2.906417236619E-002)); -#35452 = CARTESIAN_POINT('',(-1.466892098469E-002,3.018974348006E-002)); -#35453 = CARTESIAN_POINT('',(-3.820572310608E-003,3.167782201124E-002)); -#35454 = CARTESIAN_POINT('',(5.703502420664E-003,3.364268817027E-002)); -#35455 = CARTESIAN_POINT('',(1.38790329347E-002,3.610981002435E-002)); -#35456 = CARTESIAN_POINT('',(2.080414413191E-002,3.889084315062E-002)); -#35457 = CARTESIAN_POINT('',(2.639300458865E-002,4.233231894547E-002)); -#35458 = CARTESIAN_POINT('',(3.094874115519E-002,4.610035482719E-002)); -#35459 = CARTESIAN_POINT('',(3.486682193414E-002,4.999059436087E-002)); -#35460 = CARTESIAN_POINT('',(3.819710088221E-002,5.409456143521E-002)); -#35461 = CARTESIAN_POINT('',(4.097387435943E-002,5.838547816102E-002)); -#35462 = CARTESIAN_POINT('',(4.307626480085E-002,6.29299211991E-002)); -#35463 = CARTESIAN_POINT('',(4.460008207434E-002,6.767819782025E-002)); -#35464 = CARTESIAN_POINT('',(4.547701551858E-002,7.26313412089E-002)); -#35465 = CARTESIAN_POINT('',(4.560301435358E-002,7.600465692883E-002)); -#35466 = CARTESIAN_POINT('',(4.566655449458E-002,7.77057913595E-002)); -#35467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35468 = PCURVE('',#35469,#35508); -#35469 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#35470,#35471) - ,(#35472,#35473) - ,(#35474,#35475) - ,(#35476,#35477) - ,(#35478,#35479) - ,(#35480,#35481) - ,(#35482,#35483) - ,(#35484,#35485) - ,(#35486,#35487) - ,(#35488,#35489) - ,(#35490,#35491) - ,(#35492,#35493) - ,(#35494,#35495) - ,(#35496,#35497) - ,(#35498,#35499) - ,(#35500,#35501) - ,(#35502,#35503) - ,(#35504,#35505) - ,(#35506,#35507 +#37840 = CARTESIAN_POINT('',(-5.476129151737E-002,2.831504741919E-002)); +#37841 = CARTESIAN_POINT('',(-4.98214805311E-002,2.834774147331E-002)); +#37842 = CARTESIAN_POINT('',(-4.036558966258E-002,2.841032512451E-002)); +#37843 = CARTESIAN_POINT('',(-2.685621813843E-002,2.906417236619E-002)); +#37844 = CARTESIAN_POINT('',(-1.466892098469E-002,3.018974348006E-002)); +#37845 = CARTESIAN_POINT('',(-3.820572310608E-003,3.167782201124E-002)); +#37846 = CARTESIAN_POINT('',(5.703502420664E-003,3.364268817027E-002)); +#37847 = CARTESIAN_POINT('',(1.38790329347E-002,3.610981002435E-002)); +#37848 = CARTESIAN_POINT('',(2.080414413191E-002,3.889084315062E-002)); +#37849 = CARTESIAN_POINT('',(2.639300458865E-002,4.233231894547E-002)); +#37850 = CARTESIAN_POINT('',(3.094874115519E-002,4.610035482719E-002)); +#37851 = CARTESIAN_POINT('',(3.486682193414E-002,4.999059436087E-002)); +#37852 = CARTESIAN_POINT('',(3.819710088221E-002,5.409456143521E-002)); +#37853 = CARTESIAN_POINT('',(4.097387435943E-002,5.838547816102E-002)); +#37854 = CARTESIAN_POINT('',(4.307626480085E-002,6.29299211991E-002)); +#37855 = CARTESIAN_POINT('',(4.460008207434E-002,6.767819782025E-002)); +#37856 = CARTESIAN_POINT('',(4.547701551858E-002,7.26313412089E-002)); +#37857 = CARTESIAN_POINT('',(4.560301435358E-002,7.600465692883E-002)); +#37858 = CARTESIAN_POINT('',(4.566655449458E-002,7.77057913595E-002)); +#37859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37860 = PCURVE('',#37861,#37900); +#37861 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#37862,#37863) + ,(#37864,#37865) + ,(#37866,#37867) + ,(#37868,#37869) + ,(#37870,#37871) + ,(#37872,#37873) + ,(#37874,#37875) + ,(#37876,#37877) + ,(#37878,#37879) + ,(#37880,#37881) + ,(#37882,#37883) + ,(#37884,#37885) + ,(#37886,#37887) + ,(#37888,#37889) + ,(#37890,#37891) + ,(#37892,#37893) + ,(#37894,#37895) + ,(#37896,#37897) + ,(#37898,#37899 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,0.118405508154,0.226654332817,0.324092341929, 0.411704803005,0.489025905006,0.556909397343,0.616233344493, 0.667349281277,0.713512393201,0.757696504521,0.799492511442, 0.839976064744,0.879885741817,0.919148659386,0.959227356493,1.),( 0.E+000,1.),.UNSPECIFIED.); -#35470 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) +#37862 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) ); -#35471 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) +#37863 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) ); -#35472 = CARTESIAN_POINT('',(-3.013586244362E-003,0.782,-0.309329765127) +#37864 = CARTESIAN_POINT('',(-3.013586244362E-003,0.782,-0.309329765127) ); -#35473 = CARTESIAN_POINT('',(-3.013586244362E-003,0.78,-0.309329765127) +#37865 = CARTESIAN_POINT('',(-3.013586244362E-003,0.78,-0.309329765127) ); -#35474 = CARTESIAN_POINT('',(-2.951002593161E-003,0.782,-0.299873874259) +#37866 = CARTESIAN_POINT('',(-2.951002593161E-003,0.782,-0.299873874259) ); -#35475 = CARTESIAN_POINT('',(-2.951002593161E-003,0.78,-0.299873874259) +#37867 = CARTESIAN_POINT('',(-2.951002593161E-003,0.78,-0.299873874259) ); -#35476 = CARTESIAN_POINT('',(-2.297155351481E-003,0.782,-0.286364502734) +#37868 = CARTESIAN_POINT('',(-2.297155351481E-003,0.782,-0.286364502734) ); -#35477 = CARTESIAN_POINT('',(-2.297155351481E-003,0.78,-0.286364502734) +#37869 = CARTESIAN_POINT('',(-2.297155351481E-003,0.78,-0.286364502734) ); -#35478 = CARTESIAN_POINT('',(-1.17158423761E-003,0.782,-0.274177205581) +#37870 = CARTESIAN_POINT('',(-1.17158423761E-003,0.782,-0.274177205581) ); -#35479 = CARTESIAN_POINT('',(-1.17158423761E-003,0.78,-0.274177205581)); -#35480 = CARTESIAN_POINT('',(3.164942935639E-004,0.782,-0.263328856907) +#37871 = CARTESIAN_POINT('',(-1.17158423761E-003,0.78,-0.274177205581)); +#37872 = CARTESIAN_POINT('',(3.164942935639E-004,0.782,-0.263328856907) ); -#35481 = CARTESIAN_POINT('',(3.164942935639E-004,0.78,-0.263328856907)); -#35482 = CARTESIAN_POINT('',(2.281360452602E-003,0.782,-0.253804782175) +#37873 = CARTESIAN_POINT('',(3.164942935639E-004,0.78,-0.263328856907)); +#37874 = CARTESIAN_POINT('',(2.281360452602E-003,0.782,-0.253804782175) ); -#35483 = CARTESIAN_POINT('',(2.281360452602E-003,0.78,-0.253804782175)); -#35484 = CARTESIAN_POINT('',(4.748482306681E-003,0.782,-0.245629251661) +#37875 = CARTESIAN_POINT('',(2.281360452602E-003,0.78,-0.253804782175)); +#37876 = CARTESIAN_POINT('',(4.748482306681E-003,0.782,-0.245629251661) ); -#35485 = CARTESIAN_POINT('',(4.748482306681E-003,0.78,-0.245629251661)); -#35486 = CARTESIAN_POINT('',(7.529515432953E-003,0.782,-0.238704140464) +#37877 = CARTESIAN_POINT('',(4.748482306681E-003,0.78,-0.245629251661)); +#37878 = CARTESIAN_POINT('',(7.529515432953E-003,0.782,-0.238704140464) ); -#35487 = CARTESIAN_POINT('',(7.529515432953E-003,0.78,-0.238704140464)); -#35488 = CARTESIAN_POINT('',(1.09709912278E-002,0.782,-0.233115280007)); -#35489 = CARTESIAN_POINT('',(1.09709912278E-002,0.78,-0.233115280007)); -#35490 = CARTESIAN_POINT('',(1.473902710952E-002,0.782,-0.228559543441) +#37879 = CARTESIAN_POINT('',(7.529515432953E-003,0.78,-0.238704140464)); +#37880 = CARTESIAN_POINT('',(1.09709912278E-002,0.782,-0.233115280007)); +#37881 = CARTESIAN_POINT('',(1.09709912278E-002,0.78,-0.233115280007)); +#37882 = CARTESIAN_POINT('',(1.473902710952E-002,0.782,-0.228559543441) ); -#35491 = CARTESIAN_POINT('',(1.473902710952E-002,0.78,-0.228559543441)); -#35492 = CARTESIAN_POINT('',(1.86292666432E-002,0.782,-0.224641462662)); -#35493 = CARTESIAN_POINT('',(1.86292666432E-002,0.78,-0.224641462662)); -#35494 = CARTESIAN_POINT('',(2.273323371754E-002,0.782,-0.221311183714) +#37883 = CARTESIAN_POINT('',(1.473902710952E-002,0.78,-0.228559543441)); +#37884 = CARTESIAN_POINT('',(1.86292666432E-002,0.782,-0.224641462662)); +#37885 = CARTESIAN_POINT('',(1.86292666432E-002,0.78,-0.224641462662)); +#37886 = CARTESIAN_POINT('',(2.273323371754E-002,0.782,-0.221311183714) ); -#35495 = CARTESIAN_POINT('',(2.273323371754E-002,0.78,-0.221311183714)); -#35496 = CARTESIAN_POINT('',(2.702415044334E-002,0.782,-0.218534410237) +#37887 = CARTESIAN_POINT('',(2.273323371754E-002,0.78,-0.221311183714)); +#37888 = CARTESIAN_POINT('',(2.702415044334E-002,0.782,-0.218534410237) ); -#35497 = CARTESIAN_POINT('',(2.702415044334E-002,0.78,-0.218534410237)); -#35498 = CARTESIAN_POINT('',(3.156859348143E-002,0.782,-0.216432019795) +#37889 = CARTESIAN_POINT('',(2.702415044334E-002,0.78,-0.218534410237)); +#37890 = CARTESIAN_POINT('',(3.156859348143E-002,0.782,-0.216432019795) ); -#35499 = CARTESIAN_POINT('',(3.156859348143E-002,0.78,-0.216432019795)); -#35500 = CARTESIAN_POINT('',(3.631687010258E-002,0.782,-0.214908202522) +#37891 = CARTESIAN_POINT('',(3.156859348143E-002,0.78,-0.216432019795)); +#37892 = CARTESIAN_POINT('',(3.631687010258E-002,0.782,-0.214908202522) ); -#35501 = CARTESIAN_POINT('',(3.631687010258E-002,0.78,-0.214908202522)); -#35502 = CARTESIAN_POINT('',(4.127001349122E-002,0.782,-0.214031269077) +#37893 = CARTESIAN_POINT('',(3.631687010258E-002,0.78,-0.214908202522)); +#37894 = CARTESIAN_POINT('',(4.127001349122E-002,0.782,-0.214031269077) ); -#35503 = CARTESIAN_POINT('',(4.127001349122E-002,0.78,-0.214031269077)); -#35504 = CARTESIAN_POINT('',(4.464332921115E-002,0.782,-0.213905270242) +#37895 = CARTESIAN_POINT('',(4.127001349122E-002,0.78,-0.214031269077)); +#37896 = CARTESIAN_POINT('',(4.464332921115E-002,0.782,-0.213905270242) ); -#35505 = CARTESIAN_POINT('',(4.464332921115E-002,0.78,-0.213905270242)); -#35506 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) +#37897 = CARTESIAN_POINT('',(4.464332921115E-002,0.78,-0.213905270242)); +#37898 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) ); -#35507 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); -#35508 = DEFINITIONAL_REPRESENTATION('',(#35509),#35513); -#35509 = LINE('',#35510,#35511); -#35510 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35511 = VECTOR('',#35512,1.); -#35512 = DIRECTION('',(1.,0.E+000)); -#35513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37899 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); +#37900 = DEFINITIONAL_REPRESENTATION('',(#37901),#37905); +#37901 = LINE('',#37902,#37903); +#37902 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37903 = VECTOR('',#37904,1.); +#37904 = DIRECTION('',(1.,0.E+000)); +#37905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35514 = ORIENTED_EDGE('',*,*,#35515,.F.); -#35515 = EDGE_CURVE('',#35516,#35420,#35518,.T.); -#35516 = VERTEX_POINT('',#35517); -#35517 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) +#37906 = ORIENTED_EDGE('',*,*,#37907,.F.); +#37907 = EDGE_CURVE('',#37908,#37812,#37910,.T.); +#37908 = VERTEX_POINT('',#37909); +#37909 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) ); -#35518 = SURFACE_CURVE('',#35519,(#35531,#35546),.PCURVE_S1.); -#35519 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35520,#35521,#35522,#35523, - #35524,#35525,#35526,#35527,#35528,#35529,#35530),.UNSPECIFIED.,.F., +#37910 = SURFACE_CURVE('',#37911,(#37923,#37938),.PCURVE_S1.); +#37911 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37912,#37913,#37914,#37915, + #37916,#37917,#37918,#37919,#37920,#37921,#37922),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,8.388811327955E-002,0.177154032754, 0.282513635562,0.39939986066,0.529490806191,0.672802177676, 0.82953576162,1.),.UNSPECIFIED.); -#35520 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) +#37912 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) ); -#35521 = CARTESIAN_POINT('',(1.059858853463E-002,0.782,-0.395055894417) +#37913 = CARTESIAN_POINT('',(1.059858853463E-002,0.782,-0.395055894417) ); -#35522 = CARTESIAN_POINT('',(8.014174182464E-003,0.782,-0.390735014434) +#37914 = CARTESIAN_POINT('',(8.014174182464E-003,0.782,-0.390735014434) ); -#35523 = CARTESIAN_POINT('',(5.122364794867E-003,0.782,-0.383225146997) +#37915 = CARTESIAN_POINT('',(5.122364794867E-003,0.782,-0.383225146997) ); -#35524 = CARTESIAN_POINT('',(2.567854700152E-003,0.782,-0.374642797984) +#37916 = CARTESIAN_POINT('',(2.567854700152E-003,0.782,-0.374642797984) ); -#35525 = CARTESIAN_POINT('',(4.646459563984E-004,0.782,-0.364855921721) +#37917 = CARTESIAN_POINT('',(4.646459563984E-004,0.782,-0.364855921721) ); -#35526 = CARTESIAN_POINT('',(-1.056878022553E-003,0.782,-0.353881306637) +#37918 = CARTESIAN_POINT('',(-1.056878022553E-003,0.782,-0.353881306637) ); -#35527 = CARTESIAN_POINT('',(-2.258062370921E-003,0.782,-0.341731697672) +#37919 = CARTESIAN_POINT('',(-2.258062370921E-003,0.782,-0.341731697672) ); -#35528 = CARTESIAN_POINT('',(-2.882032929567E-003,0.782,-0.328390132521) +#37920 = CARTESIAN_POINT('',(-2.882032929567E-003,0.782,-0.328390132521) ); -#35529 = CARTESIAN_POINT('',(-2.990020629803E-003,0.782,-0.319106291796) +#37921 = CARTESIAN_POINT('',(-2.990020629803E-003,0.782,-0.319106291796) ); -#35530 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) +#37922 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) ); -#35531 = PCURVE('',#35148,#35532); -#35532 = DEFINITIONAL_REPRESENTATION('',(#35533),#35545); -#35533 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35534,#35535,#35536,#35537, - #35538,#35539,#35540,#35541,#35542,#35543,#35544),.UNSPECIFIED.,.F., +#37923 = PCURVE('',#37540,#37924); +#37924 = DEFINITIONAL_REPRESENTATION('',(#37925),#37937); +#37925 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37926,#37927,#37928,#37929, + #37930,#37931,#37932,#37933,#37934,#37935,#37936),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,8.388811327955E-002,0.177154032754, 0.282513635562,0.39939986066,0.529490806191,0.672802177676, 0.82953576162,1.),.UNSPECIFIED.); -#35534 = CARTESIAN_POINT('',(-0.137593685001,4.318371929289E-002)); -#35535 = CARTESIAN_POINT('',(-0.13554760982,4.195991625231E-002)); -#35536 = CARTESIAN_POINT('',(-0.131226729837,3.937550190014E-002)); -#35537 = CARTESIAN_POINT('',(-0.123716862401,3.648369251254E-002)); -#35538 = CARTESIAN_POINT('',(-0.115134513388,3.392918241782E-002)); -#35539 = CARTESIAN_POINT('',(-0.105347637125,3.182597367407E-002)); -#35540 = CARTESIAN_POINT('',(-9.437302204053E-002,3.030444969512E-002)); -#35541 = CARTESIAN_POINT('',(-8.222341307634E-002,2.910326534675E-002)); -#35542 = CARTESIAN_POINT('',(-6.888184792444E-002,2.84792947881E-002)); -#35543 = CARTESIAN_POINT('',(-5.959800719956E-002,2.837130708787E-002)); -#35544 = CARTESIAN_POINT('',(-5.476129151737E-002,2.831504741919E-002)); -#35545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35546 = PCURVE('',#35547,#35570); -#35547 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#35548,#35549) - ,(#35550,#35551) - ,(#35552,#35553) - ,(#35554,#35555) - ,(#35556,#35557) - ,(#35558,#35559) - ,(#35560,#35561) - ,(#35562,#35563) - ,(#35564,#35565) - ,(#35566,#35567) - ,(#35568,#35569 +#37926 = CARTESIAN_POINT('',(-0.137593685001,4.318371929289E-002)); +#37927 = CARTESIAN_POINT('',(-0.13554760982,4.195991625231E-002)); +#37928 = CARTESIAN_POINT('',(-0.131226729837,3.937550190014E-002)); +#37929 = CARTESIAN_POINT('',(-0.123716862401,3.648369251254E-002)); +#37930 = CARTESIAN_POINT('',(-0.115134513388,3.392918241782E-002)); +#37931 = CARTESIAN_POINT('',(-0.105347637125,3.182597367407E-002)); +#37932 = CARTESIAN_POINT('',(-9.437302204053E-002,3.030444969512E-002)); +#37933 = CARTESIAN_POINT('',(-8.222341307634E-002,2.910326534675E-002)); +#37934 = CARTESIAN_POINT('',(-6.888184792444E-002,2.84792947881E-002)); +#37935 = CARTESIAN_POINT('',(-5.959800719956E-002,2.837130708787E-002)); +#37936 = CARTESIAN_POINT('',(-5.476129151737E-002,2.831504741919E-002)); +#37937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#37938 = PCURVE('',#37939,#37962); +#37939 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#37940,#37941) + ,(#37942,#37943) + ,(#37944,#37945) + ,(#37946,#37947) + ,(#37948,#37949) + ,(#37950,#37951) + ,(#37952,#37953) + ,(#37954,#37955) + ,(#37956,#37957) + ,(#37958,#37959) + ,(#37960,#37961 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 8.388811327955E-002,0.177154032754,0.282513635562,0.39939986066, 0.529490806191,0.672802177676,0.82953576162,1.),(0.E+000,1.), .UNSPECIFIED.); -#35548 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) +#37940 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) ); -#35549 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); -#35550 = CARTESIAN_POINT('',(1.059858853463E-002,0.782,-0.395055894417) +#37941 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); +#37942 = CARTESIAN_POINT('',(1.059858853463E-002,0.782,-0.395055894417) ); -#35551 = CARTESIAN_POINT('',(1.059858853463E-002,0.78,-0.395055894417)); -#35552 = CARTESIAN_POINT('',(8.014174182464E-003,0.782,-0.390735014434) +#37943 = CARTESIAN_POINT('',(1.059858853463E-002,0.78,-0.395055894417)); +#37944 = CARTESIAN_POINT('',(8.014174182464E-003,0.782,-0.390735014434) ); -#35553 = CARTESIAN_POINT('',(8.014174182464E-003,0.78,-0.390735014434)); -#35554 = CARTESIAN_POINT('',(5.122364794867E-003,0.782,-0.383225146997) +#37945 = CARTESIAN_POINT('',(8.014174182464E-003,0.78,-0.390735014434)); +#37946 = CARTESIAN_POINT('',(5.122364794867E-003,0.782,-0.383225146997) ); -#35555 = CARTESIAN_POINT('',(5.122364794867E-003,0.78,-0.383225146997)); -#35556 = CARTESIAN_POINT('',(2.567854700152E-003,0.782,-0.374642797984) +#37947 = CARTESIAN_POINT('',(5.122364794867E-003,0.78,-0.383225146997)); +#37948 = CARTESIAN_POINT('',(2.567854700152E-003,0.782,-0.374642797984) ); -#35557 = CARTESIAN_POINT('',(2.567854700152E-003,0.78,-0.374642797984)); -#35558 = CARTESIAN_POINT('',(4.646459563984E-004,0.782,-0.364855921721) +#37949 = CARTESIAN_POINT('',(2.567854700152E-003,0.78,-0.374642797984)); +#37950 = CARTESIAN_POINT('',(4.646459563984E-004,0.782,-0.364855921721) ); -#35559 = CARTESIAN_POINT('',(4.646459563984E-004,0.78,-0.364855921721)); -#35560 = CARTESIAN_POINT('',(-1.056878022553E-003,0.782,-0.353881306637) +#37951 = CARTESIAN_POINT('',(4.646459563984E-004,0.78,-0.364855921721)); +#37952 = CARTESIAN_POINT('',(-1.056878022553E-003,0.782,-0.353881306637) ); -#35561 = CARTESIAN_POINT('',(-1.056878022553E-003,0.78,-0.353881306637) +#37953 = CARTESIAN_POINT('',(-1.056878022553E-003,0.78,-0.353881306637) ); -#35562 = CARTESIAN_POINT('',(-2.258062370921E-003,0.782,-0.341731697672) +#37954 = CARTESIAN_POINT('',(-2.258062370921E-003,0.782,-0.341731697672) ); -#35563 = CARTESIAN_POINT('',(-2.258062370921E-003,0.78,-0.341731697672) +#37955 = CARTESIAN_POINT('',(-2.258062370921E-003,0.78,-0.341731697672) ); -#35564 = CARTESIAN_POINT('',(-2.882032929567E-003,0.782,-0.328390132521) +#37956 = CARTESIAN_POINT('',(-2.882032929567E-003,0.782,-0.328390132521) ); -#35565 = CARTESIAN_POINT('',(-2.882032929567E-003,0.78,-0.328390132521) +#37957 = CARTESIAN_POINT('',(-2.882032929567E-003,0.78,-0.328390132521) ); -#35566 = CARTESIAN_POINT('',(-2.990020629803E-003,0.782,-0.319106291796) +#37958 = CARTESIAN_POINT('',(-2.990020629803E-003,0.782,-0.319106291796) ); -#35567 = CARTESIAN_POINT('',(-2.990020629803E-003,0.78,-0.319106291796) +#37959 = CARTESIAN_POINT('',(-2.990020629803E-003,0.78,-0.319106291796) ); -#35568 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) +#37960 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) ); -#35569 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) +#37961 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) ); -#35570 = DEFINITIONAL_REPRESENTATION('',(#35571),#35575); -#35571 = LINE('',#35572,#35573); -#35572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35573 = VECTOR('',#35574,1.); -#35574 = DIRECTION('',(1.,0.E+000)); -#35575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#37962 = DEFINITIONAL_REPRESENTATION('',(#37963),#37967); +#37963 = LINE('',#37964,#37965); +#37964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#37965 = VECTOR('',#37966,1.); +#37966 = DIRECTION('',(1.,0.E+000)); +#37967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35576 = ORIENTED_EDGE('',*,*,#35577,.F.); -#35577 = EDGE_CURVE('',#35578,#35516,#35580,.T.); -#35578 = VERTEX_POINT('',#35579); -#35579 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#35580 = SURFACE_CURVE('',#35581,(#35593,#35608),.PCURVE_S1.); -#35581 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35582,#35583,#35584,#35585, - #35586,#35587,#35588,#35589,#35590,#35591,#35592),.UNSPECIFIED.,.F., +#37968 = ORIENTED_EDGE('',*,*,#37969,.F.); +#37969 = EDGE_CURVE('',#37970,#37908,#37972,.T.); +#37970 = VERTEX_POINT('',#37971); +#37971 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#37972 = SURFACE_CURVE('',#37973,(#37985,#38000),.PCURVE_S1.); +#37973 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37974,#37975,#37976,#37977, + #37978,#37979,#37980,#37981,#37982,#37983,#37984),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127664767896,0.251738563008, 0.372753349387,0.492146758972,0.614069621309,0.737197324412, 0.865606990601,1.),.UNSPECIFIED.); -#35582 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#35583 = CARTESIAN_POINT('',(4.428329521055E-002,0.782,-0.414652776866) +#37974 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#37975 = CARTESIAN_POINT('',(4.428329521055E-002,0.782,-0.414652776866) ); -#35584 = CARTESIAN_POINT('',(4.092908677692E-002,0.782,-0.414564742134) +#37976 = CARTESIAN_POINT('',(4.092908677692E-002,0.782,-0.414564742134) ); -#35585 = CARTESIAN_POINT('',(3.601808635406E-002,0.782,-0.413724451515) +#37977 = CARTESIAN_POINT('',(3.601808635406E-002,0.782,-0.413724451515) ); -#35586 = CARTESIAN_POINT('',(3.136398894619E-002,0.782,-0.412319298309) +#37978 = CARTESIAN_POINT('',(3.136398894619E-002,0.782,-0.412319298309) ); -#35587 = CARTESIAN_POINT('',(2.691347364148E-002,0.782,-0.410415881856) +#37979 = CARTESIAN_POINT('',(2.691347364148E-002,0.782,-0.410415881856) ); -#35588 = CARTESIAN_POINT('',(2.277764518064E-002,0.782,-0.407854259268) +#37980 = CARTESIAN_POINT('',(2.277764518064E-002,0.782,-0.407854259268) ); -#35589 = CARTESIAN_POINT('',(1.879248689221E-002,0.782,-0.40486338256)); -#35590 = CARTESIAN_POINT('',(1.514464817155E-002,0.782,-0.401219333118) +#37981 = CARTESIAN_POINT('',(1.879248689221E-002,0.782,-0.40486338256)); +#37982 = CARTESIAN_POINT('',(1.514464817155E-002,0.782,-0.401219333118) ); -#35591 = CARTESIAN_POINT('',(1.294649256335E-002,0.782,-0.398495098715) +#37983 = CARTESIAN_POINT('',(1.294649256335E-002,0.782,-0.398495098715) ); -#35592 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) +#37984 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) ); -#35593 = PCURVE('',#35148,#35594); -#35594 = DEFINITIONAL_REPRESENTATION('',(#35595),#35607); -#35595 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35596,#35597,#35598,#35599, - #35600,#35601,#35602,#35603,#35604,#35605,#35606),.UNSPECIFIED.,.F., +#37985 = PCURVE('',#37540,#37986); +#37986 = DEFINITIONAL_REPRESENTATION('',(#37987),#37999); +#37987 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37988,#37989,#37990,#37991, + #37992,#37993,#37994,#37995,#37996,#37997,#37998),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127664767896,0.251738563008, 0.372753349387,0.492146758972,0.614069621309,0.737197324412, 0.865606990601,1.),.UNSPECIFIED.); -#35596 = CARTESIAN_POINT('',(-0.155189137529,7.734565051827E-002)); -#35597 = CARTESIAN_POINT('',(-0.15514449227,7.564462292822E-002)); -#35598 = CARTESIAN_POINT('',(-0.155056457538,7.22904144946E-002)); -#35599 = CARTESIAN_POINT('',(-0.154216166919,6.737941407173E-002)); -#35600 = CARTESIAN_POINT('',(-0.152811013713,6.272531666386E-002)); -#35601 = CARTESIAN_POINT('',(-0.15090759726,5.827480135915E-002)); -#35602 = CARTESIAN_POINT('',(-0.148345974672,5.413897289832E-002)); -#35603 = CARTESIAN_POINT('',(-0.145355097964,5.015381460988E-002)); -#35604 = CARTESIAN_POINT('',(-0.141711048521,4.650597588922E-002)); -#35605 = CARTESIAN_POINT('',(-0.138986814119,4.430782028103E-002)); -#35606 = CARTESIAN_POINT('',(-0.137593685001,4.318371929289E-002)); -#35607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35608 = PCURVE('',#35609,#35632); -#35609 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#35610,#35611) - ,(#35612,#35613) - ,(#35614,#35615) - ,(#35616,#35617) - ,(#35618,#35619) - ,(#35620,#35621) - ,(#35622,#35623) - ,(#35624,#35625) - ,(#35626,#35627) - ,(#35628,#35629) - ,(#35630,#35631 +#37988 = CARTESIAN_POINT('',(-0.155189137529,7.734565051827E-002)); +#37989 = CARTESIAN_POINT('',(-0.15514449227,7.564462292822E-002)); +#37990 = CARTESIAN_POINT('',(-0.155056457538,7.22904144946E-002)); +#37991 = CARTESIAN_POINT('',(-0.154216166919,6.737941407173E-002)); +#37992 = CARTESIAN_POINT('',(-0.152811013713,6.272531666386E-002)); +#37993 = CARTESIAN_POINT('',(-0.15090759726,5.827480135915E-002)); +#37994 = CARTESIAN_POINT('',(-0.148345974672,5.413897289832E-002)); +#37995 = CARTESIAN_POINT('',(-0.145355097964,5.015381460988E-002)); +#37996 = CARTESIAN_POINT('',(-0.141711048521,4.650597588922E-002)); +#37997 = CARTESIAN_POINT('',(-0.138986814119,4.430782028103E-002)); +#37998 = CARTESIAN_POINT('',(-0.137593685001,4.318371929289E-002)); +#37999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38000 = PCURVE('',#38001,#38024); +#38001 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#38002,#38003) + ,(#38004,#38005) + ,(#38006,#38007) + ,(#38008,#38009) + ,(#38010,#38011) + ,(#38012,#38013) + ,(#38014,#38015) + ,(#38016,#38017) + ,(#38018,#38019) + ,(#38020,#38021) + ,(#38022,#38023 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,4),(2,2),(0.E+000, 0.127664767896,0.251738563008,0.372753349387,0.492146758972, 0.614069621309,0.737197324412,0.865606990601,1.),(0.E+000,1.), .UNSPECIFIED.); -#35610 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#35611 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); -#35612 = CARTESIAN_POINT('',(4.428329521055E-002,0.782,-0.414652776866) +#38002 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#38003 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); +#38004 = CARTESIAN_POINT('',(4.428329521055E-002,0.782,-0.414652776866) ); -#35613 = CARTESIAN_POINT('',(4.428329521055E-002,0.78,-0.414652776866)); -#35614 = CARTESIAN_POINT('',(4.092908677692E-002,0.782,-0.414564742134) +#38005 = CARTESIAN_POINT('',(4.428329521055E-002,0.78,-0.414652776866)); +#38006 = CARTESIAN_POINT('',(4.092908677692E-002,0.782,-0.414564742134) ); -#35615 = CARTESIAN_POINT('',(4.092908677692E-002,0.78,-0.414564742134)); -#35616 = CARTESIAN_POINT('',(3.601808635406E-002,0.782,-0.413724451515) +#38007 = CARTESIAN_POINT('',(4.092908677692E-002,0.78,-0.414564742134)); +#38008 = CARTESIAN_POINT('',(3.601808635406E-002,0.782,-0.413724451515) ); -#35617 = CARTESIAN_POINT('',(3.601808635406E-002,0.78,-0.413724451515)); -#35618 = CARTESIAN_POINT('',(3.136398894619E-002,0.782,-0.412319298309) +#38009 = CARTESIAN_POINT('',(3.601808635406E-002,0.78,-0.413724451515)); +#38010 = CARTESIAN_POINT('',(3.136398894619E-002,0.782,-0.412319298309) ); -#35619 = CARTESIAN_POINT('',(3.136398894619E-002,0.78,-0.412319298309)); -#35620 = CARTESIAN_POINT('',(2.691347364148E-002,0.782,-0.410415881856) +#38011 = CARTESIAN_POINT('',(3.136398894619E-002,0.78,-0.412319298309)); +#38012 = CARTESIAN_POINT('',(2.691347364148E-002,0.782,-0.410415881856) ); -#35621 = CARTESIAN_POINT('',(2.691347364148E-002,0.78,-0.410415881856)); -#35622 = CARTESIAN_POINT('',(2.277764518064E-002,0.782,-0.407854259268) +#38013 = CARTESIAN_POINT('',(2.691347364148E-002,0.78,-0.410415881856)); +#38014 = CARTESIAN_POINT('',(2.277764518064E-002,0.782,-0.407854259268) ); -#35623 = CARTESIAN_POINT('',(2.277764518064E-002,0.78,-0.407854259268)); -#35624 = CARTESIAN_POINT('',(1.879248689221E-002,0.782,-0.40486338256)); -#35625 = CARTESIAN_POINT('',(1.879248689221E-002,0.78,-0.40486338256)); -#35626 = CARTESIAN_POINT('',(1.514464817155E-002,0.782,-0.401219333118) +#38015 = CARTESIAN_POINT('',(2.277764518064E-002,0.78,-0.407854259268)); +#38016 = CARTESIAN_POINT('',(1.879248689221E-002,0.782,-0.40486338256)); +#38017 = CARTESIAN_POINT('',(1.879248689221E-002,0.78,-0.40486338256)); +#38018 = CARTESIAN_POINT('',(1.514464817155E-002,0.782,-0.401219333118) ); -#35627 = CARTESIAN_POINT('',(1.514464817155E-002,0.78,-0.401219333118)); -#35628 = CARTESIAN_POINT('',(1.294649256335E-002,0.782,-0.398495098715) +#38019 = CARTESIAN_POINT('',(1.514464817155E-002,0.78,-0.401219333118)); +#38020 = CARTESIAN_POINT('',(1.294649256335E-002,0.782,-0.398495098715) ); -#35629 = CARTESIAN_POINT('',(1.294649256335E-002,0.78,-0.398495098715)); -#35630 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) +#38021 = CARTESIAN_POINT('',(1.294649256335E-002,0.78,-0.398495098715)); +#38022 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) ); -#35631 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); -#35632 = DEFINITIONAL_REPRESENTATION('',(#35633),#35637); -#35633 = LINE('',#35634,#35635); -#35634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35635 = VECTOR('',#35636,1.); -#35636 = DIRECTION('',(1.,0.E+000)); -#35637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38023 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); +#38024 = DEFINITIONAL_REPRESENTATION('',(#38025),#38029); +#38025 = LINE('',#38026,#38027); +#38026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38027 = VECTOR('',#38028,1.); +#38028 = DIRECTION('',(1.,0.E+000)); +#38029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35638 = ORIENTED_EDGE('',*,*,#35639,.F.); -#35639 = EDGE_CURVE('',#35640,#35578,#35642,.T.); -#35640 = VERTEX_POINT('',#35641); -#35641 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) +#38030 = ORIENTED_EDGE('',*,*,#38031,.F.); +#38031 = EDGE_CURVE('',#38032,#37970,#38034,.T.); +#38032 = VERTEX_POINT('',#38033); +#38033 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) ); -#35642 = SURFACE_CURVE('',#35643,(#35663,#35686),.PCURVE_S1.); -#35643 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35644,#35645,#35646,#35647, - #35648,#35649,#35650,#35651,#35652,#35653,#35654,#35655,#35656, - #35657,#35658,#35659,#35660,#35661,#35662),.UNSPECIFIED.,.F.,.F.,(4, +#38034 = SURFACE_CURVE('',#38035,(#38055,#38078),.PCURVE_S1.); +#38035 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38036,#38037,#38038,#38039, + #38040,#38041,#38042,#38043,#38044,#38045,#38046,#38047,#38048, + #38049,#38050,#38051,#38052,#38053,#38054),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.115629130925, 0.22154103912,0.317047856219,0.40315087564,0.480181216716, 0.547649366148,0.607035842842,0.658652408064,0.705722890354, 0.74980408798,0.792586815345,0.83387396101,0.874768393303, 0.915222698892,0.95688070373,1.),.UNSPECIFIED.); -#35644 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) +#38036 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) ); -#35645 = CARTESIAN_POINT('',(9.570402613498E-002,0.782,-0.31910662744)); -#35646 = CARTESIAN_POINT('',(9.564428366222E-002,0.782,-0.328374234735) +#38037 = CARTESIAN_POINT('',(9.570402613498E-002,0.782,-0.31910662744)); +#38038 = CARTESIAN_POINT('',(9.564428366222E-002,0.782,-0.328374234735) ); -#35647 = CARTESIAN_POINT('',(9.496908424492E-002,0.782,-0.341623347885) +#38039 = CARTESIAN_POINT('',(9.496908424492E-002,0.782,-0.341623347885) ); -#35648 = CARTESIAN_POINT('',(9.39109860771E-002,0.782,-0.35360608623)); -#35649 = CARTESIAN_POINT('',(9.246367587471E-002,0.782,-0.364333496744) +#38040 = CARTESIAN_POINT('',(9.39109860771E-002,0.782,-0.35360608623)); +#38041 = CARTESIAN_POINT('',(9.246367587471E-002,0.782,-0.364333496744) ); -#35650 = CARTESIAN_POINT('',(9.054020088409E-002,0.782,-0.373793933352) +#38042 = CARTESIAN_POINT('',(9.054020088409E-002,0.782,-0.373793933352) ); -#35651 = CARTESIAN_POINT('',(8.820728810449E-002,0.782,-0.382007536038) +#38043 = CARTESIAN_POINT('',(8.820728810449E-002,0.782,-0.382007536038) ); -#35652 = CARTESIAN_POINT('',(8.542727370253E-002,0.782,-0.388956787959) +#38044 = CARTESIAN_POINT('',(8.542727370253E-002,0.782,-0.388956787959) ); -#35653 = CARTESIAN_POINT('',(8.212184649905E-002,0.782,-0.394711494488) +#38045 = CARTESIAN_POINT('',(8.212184649905E-002,0.782,-0.394711494488) ); -#35654 = CARTESIAN_POINT('',(7.844224465158E-002,0.782,-0.39943191503)); -#35655 = CARTESIAN_POINT('',(7.459855169955E-002,0.782,-0.40351784974)); -#35656 = CARTESIAN_POINT('',(7.049467493159E-002,0.782,-0.406992804096) +#38046 = CARTESIAN_POINT('',(7.844224465158E-002,0.782,-0.39943191503)); +#38047 = CARTESIAN_POINT('',(7.459855169955E-002,0.782,-0.40351784974)); +#38048 = CARTESIAN_POINT('',(7.049467493159E-002,0.782,-0.406992804096) ); -#35657 = CARTESIAN_POINT('',(6.60579060004E-002,0.782,-0.409780463741)); -#35658 = CARTESIAN_POINT('',(6.143125031312E-002,0.782,-0.412029443855) +#38049 = CARTESIAN_POINT('',(6.60579060004E-002,0.782,-0.409780463741)); +#38050 = CARTESIAN_POINT('',(6.143125031312E-002,0.782,-0.412029443855) ); -#35659 = CARTESIAN_POINT('',(5.650839908174E-002,0.782,-0.413577249241) +#38051 = CARTESIAN_POINT('',(5.650839908174E-002,0.782,-0.413577249241) ); -#35660 = CARTESIAN_POINT('',(5.133774004351E-002,0.782,-0.414528172457) +#38052 = CARTESIAN_POINT('',(5.133774004351E-002,0.782,-0.414528172457) ); -#35661 = CARTESIAN_POINT('',(4.778918382805E-002,0.782,-0.414640360978) +#38053 = CARTESIAN_POINT('',(4.778918382805E-002,0.782,-0.414640360978) ); -#35662 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#35663 = PCURVE('',#35148,#35664); -#35664 = DEFINITIONAL_REPRESENTATION('',(#35665),#35685); -#35665 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35666,#35667,#35668,#35669, - #35670,#35671,#35672,#35673,#35674,#35675,#35676,#35677,#35678, - #35679,#35680,#35681,#35682,#35683,#35684),.UNSPECIFIED.,.F.,.F.,(4, +#38054 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#38055 = PCURVE('',#37540,#38056); +#38056 = DEFINITIONAL_REPRESENTATION('',(#38057),#38077); +#38057 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38058,#38059,#38060,#38061, + #38062,#38063,#38064,#38065,#38066,#38067,#38068,#38069,#38070, + #38071,#38072,#38073,#38074,#38075,#38076),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.115629130925, 0.22154103912,0.317047856219,0.40315087564,0.480181216716, 0.547649366148,0.607035842842,0.658652408064,0.705722890354, 0.74980408798,0.792586815345,0.83387396101,0.874768393303, 0.915222698892,0.95688070373,1.),.UNSPECIFIED.); -#35666 = CARTESIAN_POINT('',(-5.476129151737E-002,0.1270965353)); -#35667 = CARTESIAN_POINT('',(-5.959834284442E-002,0.127065353853)); -#35668 = CARTESIAN_POINT('',(-6.886595013934E-002,0.12700561138)); -#35669 = CARTESIAN_POINT('',(-8.211506328915E-002,0.126330411963)); -#35670 = CARTESIAN_POINT('',(-9.409780163416E-002,0.125272313795)); -#35671 = CARTESIAN_POINT('',(-0.104825212148,0.123825003592)); -#35672 = CARTESIAN_POINT('',(-0.114285648756,0.121901528602)); -#35673 = CARTESIAN_POINT('',(-0.122499251441,0.119568615822)); -#35674 = CARTESIAN_POINT('',(-0.129448503363,0.11678860142)); -#35675 = CARTESIAN_POINT('',(-0.135203209892,0.113483174217)); -#35676 = CARTESIAN_POINT('',(-0.139923630434,0.109803572369)); -#35677 = CARTESIAN_POINT('',(-0.144009565144,0.105959879417)); -#35678 = CARTESIAN_POINT('',(-0.147484519499,0.101856002649)); -#35679 = CARTESIAN_POINT('',(-0.150272179145,9.741923371807E-002)); -#35680 = CARTESIAN_POINT('',(-0.152521159259,9.27925780308E-002)); -#35681 = CARTESIAN_POINT('',(-0.154068964645,8.786972679941E-002)); -#35682 = CARTESIAN_POINT('',(-0.155019887861,8.269906776118E-002)); -#35683 = CARTESIAN_POINT('',(-0.155132076382,7.915051154572E-002)); -#35684 = CARTESIAN_POINT('',(-0.155189137529,7.734565051827E-002)); -#35685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35686 = PCURVE('',#35687,#35726); -#35687 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#35688,#35689) - ,(#35690,#35691) - ,(#35692,#35693) - ,(#35694,#35695) - ,(#35696,#35697) - ,(#35698,#35699) - ,(#35700,#35701) - ,(#35702,#35703) - ,(#35704,#35705) - ,(#35706,#35707) - ,(#35708,#35709) - ,(#35710,#35711) - ,(#35712,#35713) - ,(#35714,#35715) - ,(#35716,#35717) - ,(#35718,#35719) - ,(#35720,#35721) - ,(#35722,#35723) - ,(#35724,#35725 +#38058 = CARTESIAN_POINT('',(-5.476129151737E-002,0.1270965353)); +#38059 = CARTESIAN_POINT('',(-5.959834284442E-002,0.127065353853)); +#38060 = CARTESIAN_POINT('',(-6.886595013934E-002,0.12700561138)); +#38061 = CARTESIAN_POINT('',(-8.211506328915E-002,0.126330411963)); +#38062 = CARTESIAN_POINT('',(-9.409780163416E-002,0.125272313795)); +#38063 = CARTESIAN_POINT('',(-0.104825212148,0.123825003592)); +#38064 = CARTESIAN_POINT('',(-0.114285648756,0.121901528602)); +#38065 = CARTESIAN_POINT('',(-0.122499251441,0.119568615822)); +#38066 = CARTESIAN_POINT('',(-0.129448503363,0.11678860142)); +#38067 = CARTESIAN_POINT('',(-0.135203209892,0.113483174217)); +#38068 = CARTESIAN_POINT('',(-0.139923630434,0.109803572369)); +#38069 = CARTESIAN_POINT('',(-0.144009565144,0.105959879417)); +#38070 = CARTESIAN_POINT('',(-0.147484519499,0.101856002649)); +#38071 = CARTESIAN_POINT('',(-0.150272179145,9.741923371807E-002)); +#38072 = CARTESIAN_POINT('',(-0.152521159259,9.27925780308E-002)); +#38073 = CARTESIAN_POINT('',(-0.154068964645,8.786972679941E-002)); +#38074 = CARTESIAN_POINT('',(-0.155019887861,8.269906776118E-002)); +#38075 = CARTESIAN_POINT('',(-0.155132076382,7.915051154572E-002)); +#38076 = CARTESIAN_POINT('',(-0.155189137529,7.734565051827E-002)); +#38077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38078 = PCURVE('',#38079,#38118); +#38079 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#38080,#38081) + ,(#38082,#38083) + ,(#38084,#38085) + ,(#38086,#38087) + ,(#38088,#38089) + ,(#38090,#38091) + ,(#38092,#38093) + ,(#38094,#38095) + ,(#38096,#38097) + ,(#38098,#38099) + ,(#38100,#38101) + ,(#38102,#38103) + ,(#38104,#38105) + ,(#38106,#38107) + ,(#38108,#38109) + ,(#38110,#38111) + ,(#38112,#38113) + ,(#38114,#38115) + ,(#38116,#38117 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,0.115629130925,0.22154103912,0.317047856219, 0.40315087564,0.480181216716,0.547649366148,0.607035842842, 0.658652408064,0.705722890354,0.74980408798,0.792586815345, 0.83387396101,0.874768393303,0.915222698892,0.95688070373,1.),( 0.E+000,1.),.UNSPECIFIED.); -#35688 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) - ); -#35689 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); -#35690 = CARTESIAN_POINT('',(9.570402613498E-002,0.782,-0.31910662744)); -#35691 = CARTESIAN_POINT('',(9.570402613498E-002,0.78,-0.31910662744)); -#35692 = CARTESIAN_POINT('',(9.564428366222E-002,0.782,-0.328374234735) - ); -#35693 = CARTESIAN_POINT('',(9.564428366222E-002,0.78,-0.328374234735)); -#35694 = CARTESIAN_POINT('',(9.496908424492E-002,0.782,-0.341623347885) - ); -#35695 = CARTESIAN_POINT('',(9.496908424492E-002,0.78,-0.341623347885)); -#35696 = CARTESIAN_POINT('',(9.39109860771E-002,0.782,-0.35360608623)); -#35697 = CARTESIAN_POINT('',(9.39109860771E-002,0.78,-0.35360608623)); -#35698 = CARTESIAN_POINT('',(9.246367587471E-002,0.782,-0.364333496744) - ); -#35699 = CARTESIAN_POINT('',(9.246367587471E-002,0.78,-0.364333496744)); -#35700 = CARTESIAN_POINT('',(9.054020088409E-002,0.782,-0.373793933352) - ); -#35701 = CARTESIAN_POINT('',(9.054020088409E-002,0.78,-0.373793933352)); -#35702 = CARTESIAN_POINT('',(8.820728810449E-002,0.782,-0.382007536038) - ); -#35703 = CARTESIAN_POINT('',(8.820728810449E-002,0.78,-0.382007536038)); -#35704 = CARTESIAN_POINT('',(8.542727370253E-002,0.782,-0.388956787959) - ); -#35705 = CARTESIAN_POINT('',(8.542727370253E-002,0.78,-0.388956787959)); -#35706 = CARTESIAN_POINT('',(8.212184649905E-002,0.782,-0.394711494488) - ); -#35707 = CARTESIAN_POINT('',(8.212184649905E-002,0.78,-0.394711494488)); -#35708 = CARTESIAN_POINT('',(7.844224465158E-002,0.782,-0.39943191503)); -#35709 = CARTESIAN_POINT('',(7.844224465158E-002,0.78,-0.39943191503)); -#35710 = CARTESIAN_POINT('',(7.459855169955E-002,0.782,-0.40351784974)); -#35711 = CARTESIAN_POINT('',(7.459855169955E-002,0.78,-0.40351784974)); -#35712 = CARTESIAN_POINT('',(7.049467493159E-002,0.782,-0.406992804096) - ); -#35713 = CARTESIAN_POINT('',(7.049467493159E-002,0.78,-0.406992804096)); -#35714 = CARTESIAN_POINT('',(6.60579060004E-002,0.782,-0.409780463741)); -#35715 = CARTESIAN_POINT('',(6.60579060004E-002,0.78,-0.409780463741)); -#35716 = CARTESIAN_POINT('',(6.143125031312E-002,0.782,-0.412029443855) - ); -#35717 = CARTESIAN_POINT('',(6.143125031312E-002,0.78,-0.412029443855)); -#35718 = CARTESIAN_POINT('',(5.650839908174E-002,0.782,-0.413577249241) - ); -#35719 = CARTESIAN_POINT('',(5.650839908174E-002,0.78,-0.413577249241)); -#35720 = CARTESIAN_POINT('',(5.133774004351E-002,0.782,-0.414528172457) - ); -#35721 = CARTESIAN_POINT('',(5.133774004351E-002,0.78,-0.414528172457)); -#35722 = CARTESIAN_POINT('',(4.778918382805E-002,0.782,-0.414640360978) - ); -#35723 = CARTESIAN_POINT('',(4.778918382805E-002,0.78,-0.414640360978)); -#35724 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#35725 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); -#35726 = DEFINITIONAL_REPRESENTATION('',(#35727),#35731); -#35727 = LINE('',#35728,#35729); -#35728 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35729 = VECTOR('',#35730,1.); -#35730 = DIRECTION('',(1.,0.E+000)); -#35731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35732 = ORIENTED_EDGE('',*,*,#35733,.F.); -#35733 = EDGE_CURVE('',#35422,#35640,#35734,.T.); -#35734 = SURFACE_CURVE('',#35735,(#35755,#35778),.PCURVE_S1.); -#35735 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35736,#35737,#35738,#35739, - #35740,#35741,#35742,#35743,#35744,#35745,#35746,#35747,#35748, - #35749,#35750,#35751,#35752,#35753,#35754),.UNSPECIFIED.,.F.,.F.,(4, +#38080 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) + ); +#38081 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); +#38082 = CARTESIAN_POINT('',(9.570402613498E-002,0.782,-0.31910662744)); +#38083 = CARTESIAN_POINT('',(9.570402613498E-002,0.78,-0.31910662744)); +#38084 = CARTESIAN_POINT('',(9.564428366222E-002,0.782,-0.328374234735) + ); +#38085 = CARTESIAN_POINT('',(9.564428366222E-002,0.78,-0.328374234735)); +#38086 = CARTESIAN_POINT('',(9.496908424492E-002,0.782,-0.341623347885) + ); +#38087 = CARTESIAN_POINT('',(9.496908424492E-002,0.78,-0.341623347885)); +#38088 = CARTESIAN_POINT('',(9.39109860771E-002,0.782,-0.35360608623)); +#38089 = CARTESIAN_POINT('',(9.39109860771E-002,0.78,-0.35360608623)); +#38090 = CARTESIAN_POINT('',(9.246367587471E-002,0.782,-0.364333496744) + ); +#38091 = CARTESIAN_POINT('',(9.246367587471E-002,0.78,-0.364333496744)); +#38092 = CARTESIAN_POINT('',(9.054020088409E-002,0.782,-0.373793933352) + ); +#38093 = CARTESIAN_POINT('',(9.054020088409E-002,0.78,-0.373793933352)); +#38094 = CARTESIAN_POINT('',(8.820728810449E-002,0.782,-0.382007536038) + ); +#38095 = CARTESIAN_POINT('',(8.820728810449E-002,0.78,-0.382007536038)); +#38096 = CARTESIAN_POINT('',(8.542727370253E-002,0.782,-0.388956787959) + ); +#38097 = CARTESIAN_POINT('',(8.542727370253E-002,0.78,-0.388956787959)); +#38098 = CARTESIAN_POINT('',(8.212184649905E-002,0.782,-0.394711494488) + ); +#38099 = CARTESIAN_POINT('',(8.212184649905E-002,0.78,-0.394711494488)); +#38100 = CARTESIAN_POINT('',(7.844224465158E-002,0.782,-0.39943191503)); +#38101 = CARTESIAN_POINT('',(7.844224465158E-002,0.78,-0.39943191503)); +#38102 = CARTESIAN_POINT('',(7.459855169955E-002,0.782,-0.40351784974)); +#38103 = CARTESIAN_POINT('',(7.459855169955E-002,0.78,-0.40351784974)); +#38104 = CARTESIAN_POINT('',(7.049467493159E-002,0.782,-0.406992804096) + ); +#38105 = CARTESIAN_POINT('',(7.049467493159E-002,0.78,-0.406992804096)); +#38106 = CARTESIAN_POINT('',(6.60579060004E-002,0.782,-0.409780463741)); +#38107 = CARTESIAN_POINT('',(6.60579060004E-002,0.78,-0.409780463741)); +#38108 = CARTESIAN_POINT('',(6.143125031312E-002,0.782,-0.412029443855) + ); +#38109 = CARTESIAN_POINT('',(6.143125031312E-002,0.78,-0.412029443855)); +#38110 = CARTESIAN_POINT('',(5.650839908174E-002,0.782,-0.413577249241) + ); +#38111 = CARTESIAN_POINT('',(5.650839908174E-002,0.78,-0.413577249241)); +#38112 = CARTESIAN_POINT('',(5.133774004351E-002,0.782,-0.414528172457) + ); +#38113 = CARTESIAN_POINT('',(5.133774004351E-002,0.78,-0.414528172457)); +#38114 = CARTESIAN_POINT('',(4.778918382805E-002,0.782,-0.414640360978) + ); +#38115 = CARTESIAN_POINT('',(4.778918382805E-002,0.78,-0.414640360978)); +#38116 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#38117 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); +#38118 = DEFINITIONAL_REPRESENTATION('',(#38119),#38123); +#38119 = LINE('',#38120,#38121); +#38120 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38121 = VECTOR('',#38122,1.); +#38122 = DIRECTION('',(1.,0.E+000)); +#38123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38124 = ORIENTED_EDGE('',*,*,#38125,.F.); +#38125 = EDGE_CURVE('',#37814,#38032,#38126,.T.); +#38126 = SURFACE_CURVE('',#38127,(#38147,#38170),.PCURVE_S1.); +#38127 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38128,#38129,#38130,#38131, + #38132,#38133,#38134,#38135,#38136,#38137,#38138,#38139,#38140, + #38141,#38142,#38143,#38144,#38145,#38146),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.078184587226E-002, 8.086958872159E-002,0.120268165788,0.160186850455,0.200459737639, 0.242265177898,0.286459261549,0.332952083749,0.38443053405, 0.44338912536,0.511681472214,0.589020025549,0.676245190651, 0.773705191473,0.881567767782,1.),.UNSPECIFIED.); -#35736 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) +#38128 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) ); -#35737 = CARTESIAN_POINT('',(4.804517208894E-002,0.782,-0.213906658604) +#38129 = CARTESIAN_POINT('',(4.804517208894E-002,0.782,-0.213906658604) ); -#35738 = CARTESIAN_POINT('',(5.141764309196E-002,0.782,-0.214035410531) +#38130 = CARTESIAN_POINT('',(5.141764309196E-002,0.782,-0.214035410531) ); -#35739 = CARTESIAN_POINT('',(5.638223117045E-002,0.782,-0.214893006742) +#38131 = CARTESIAN_POINT('',(5.638223117045E-002,0.782,-0.214893006742) ); -#35740 = CARTESIAN_POINT('',(6.111203334238E-002,0.782,-0.216495269081) +#38132 = CARTESIAN_POINT('',(6.111203334238E-002,0.782,-0.216495269081) ); -#35741 = CARTESIAN_POINT('',(6.564970062238E-002,0.782,-0.2185902339)); -#35742 = CARTESIAN_POINT('',(6.997180501741E-002,0.782,-0.221303716357) +#38133 = CARTESIAN_POINT('',(6.564970062238E-002,0.782,-0.2185902339)); +#38134 = CARTESIAN_POINT('',(6.997180501741E-002,0.782,-0.221303716357) ); -#35743 = CARTESIAN_POINT('',(7.405561628751E-002,0.782,-0.224646574521) +#38135 = CARTESIAN_POINT('',(7.405561628751E-002,0.782,-0.224646574521) ); -#35744 = CARTESIAN_POINT('',(7.796634882193E-002,0.782,-0.228562328874) +#38136 = CARTESIAN_POINT('',(7.796634882193E-002,0.782,-0.228562328874) ); -#35745 = CARTESIAN_POINT('',(8.171745878217E-002,0.782,-0.23317101758)); -#35746 = CARTESIAN_POINT('',(8.51327153258E-002,0.782,-0.238785717198)); -#35747 = CARTESIAN_POINT('',(8.79659172187E-002,0.782,-0.245705187194)); -#35748 = CARTESIAN_POINT('',(9.03945903539E-002,0.782,-0.253895035499)); -#35749 = CARTESIAN_POINT('',(9.23702381141E-002,0.782,-0.263414257755)); -#35750 = CARTESIAN_POINT('',(9.386445519084E-002,0.782,-0.27424545438)); -#35751 = CARTESIAN_POINT('',(9.498322097506E-002,0.782,-0.28639894949)); -#35752 = CARTESIAN_POINT('',(9.56414439216E-002,0.782,-0.299890938867)); -#35753 = CARTESIAN_POINT('',(9.570299473456E-002,0.782,-0.309329742842) +#38137 = CARTESIAN_POINT('',(8.171745878217E-002,0.782,-0.23317101758)); +#38138 = CARTESIAN_POINT('',(8.51327153258E-002,0.782,-0.238785717198)); +#38139 = CARTESIAN_POINT('',(8.79659172187E-002,0.782,-0.245705187194)); +#38140 = CARTESIAN_POINT('',(9.03945903539E-002,0.782,-0.253895035499)); +#38141 = CARTESIAN_POINT('',(9.23702381141E-002,0.782,-0.263414257755)); +#38142 = CARTESIAN_POINT('',(9.386445519084E-002,0.782,-0.27424545438)); +#38143 = CARTESIAN_POINT('',(9.498322097506E-002,0.782,-0.28639894949)); +#38144 = CARTESIAN_POINT('',(9.56414439216E-002,0.782,-0.299890938867)); +#38145 = CARTESIAN_POINT('',(9.570299473456E-002,0.782,-0.309329742842) ); -#35754 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) +#38146 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) ); -#35755 = PCURVE('',#35148,#35756); -#35756 = DEFINITIONAL_REPRESENTATION('',(#35757),#35777); -#35757 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35758,#35759,#35760,#35761, - #35762,#35763,#35764,#35765,#35766,#35767,#35768,#35769,#35770, - #35771,#35772,#35773,#35774,#35775,#35776),.UNSPECIFIED.,.F.,.F.,(4, +#38147 = PCURVE('',#37540,#38148); +#38148 = DEFINITIONAL_REPRESENTATION('',(#38149),#38169); +#38149 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38150,#38151,#38152,#38153, + #38154,#38155,#38156,#38157,#38158,#38159,#38160,#38161,#38162, + #38163,#38164,#38165,#38166,#38167,#38168),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.078184587226E-002, 8.086958872159E-002,0.120268165788,0.160186850455,0.200459737639, 0.242265177898,0.286459261549,0.332952083749,0.38443053405, 0.44338912536,0.511681472214,0.589020025549,0.676245190651, 0.773705191473,0.881567767782,1.),.UNSPECIFIED.); -#35758 = CARTESIAN_POINT('',(4.566655449458E-002,7.77057913595E-002)); -#35759 = CARTESIAN_POINT('',(4.560162599243E-002,7.940649980661E-002)); -#35760 = CARTESIAN_POINT('',(4.547287406489E-002,8.277897080963E-002)); -#35761 = CARTESIAN_POINT('',(4.461527785434E-002,8.774355888812E-002)); -#35762 = CARTESIAN_POINT('',(4.301301551476E-002,9.247336106005E-002)); -#35763 = CARTESIAN_POINT('',(4.091805069597E-002,9.701102834005E-002)); -#35764 = CARTESIAN_POINT('',(3.820456823873E-002,0.101333132735)); -#35765 = CARTESIAN_POINT('',(3.486171007477E-002,0.105416944005)); -#35766 = CARTESIAN_POINT('',(3.094595572246E-002,0.10932767654)); -#35767 = CARTESIAN_POINT('',(2.633726701619E-002,0.1130787865)); -#35768 = CARTESIAN_POINT('',(2.072256739797E-002,0.116494043043)); -#35769 = CARTESIAN_POINT('',(1.380309740233E-002,0.119327244936)); -#35770 = CARTESIAN_POINT('',(5.613249097452E-003,0.121755918072)); -#35771 = CARTESIAN_POINT('',(-3.905973158723E-003,0.123731565832)); -#35772 = CARTESIAN_POINT('',(-1.473716978379E-002,0.125225782909)); -#35773 = CARTESIAN_POINT('',(-2.689066489422E-002,0.126344548693)); -#35774 = CARTESIAN_POINT('',(-4.038265427061E-002,0.127002771639)); -#35775 = CARTESIAN_POINT('',(-4.982145824608E-002,0.127064322452)); -#35776 = CARTESIAN_POINT('',(-5.476129151737E-002,0.1270965353)); -#35777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35778 = PCURVE('',#35779,#35818); -#35779 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( - (#35780,#35781) - ,(#35782,#35783) - ,(#35784,#35785) - ,(#35786,#35787) - ,(#35788,#35789) - ,(#35790,#35791) - ,(#35792,#35793) - ,(#35794,#35795) - ,(#35796,#35797) - ,(#35798,#35799) - ,(#35800,#35801) - ,(#35802,#35803) - ,(#35804,#35805) - ,(#35806,#35807) - ,(#35808,#35809) - ,(#35810,#35811) - ,(#35812,#35813) - ,(#35814,#35815) - ,(#35816,#35817 +#38150 = CARTESIAN_POINT('',(4.566655449458E-002,7.77057913595E-002)); +#38151 = CARTESIAN_POINT('',(4.560162599243E-002,7.940649980661E-002)); +#38152 = CARTESIAN_POINT('',(4.547287406489E-002,8.277897080963E-002)); +#38153 = CARTESIAN_POINT('',(4.461527785434E-002,8.774355888812E-002)); +#38154 = CARTESIAN_POINT('',(4.301301551476E-002,9.247336106005E-002)); +#38155 = CARTESIAN_POINT('',(4.091805069597E-002,9.701102834005E-002)); +#38156 = CARTESIAN_POINT('',(3.820456823873E-002,0.101333132735)); +#38157 = CARTESIAN_POINT('',(3.486171007477E-002,0.105416944005)); +#38158 = CARTESIAN_POINT('',(3.094595572246E-002,0.10932767654)); +#38159 = CARTESIAN_POINT('',(2.633726701619E-002,0.1130787865)); +#38160 = CARTESIAN_POINT('',(2.072256739797E-002,0.116494043043)); +#38161 = CARTESIAN_POINT('',(1.380309740233E-002,0.119327244936)); +#38162 = CARTESIAN_POINT('',(5.613249097452E-003,0.121755918072)); +#38163 = CARTESIAN_POINT('',(-3.905973158723E-003,0.123731565832)); +#38164 = CARTESIAN_POINT('',(-1.473716978379E-002,0.125225782909)); +#38165 = CARTESIAN_POINT('',(-2.689066489422E-002,0.126344548693)); +#38166 = CARTESIAN_POINT('',(-4.038265427061E-002,0.127002771639)); +#38167 = CARTESIAN_POINT('',(-4.982145824608E-002,0.127064322452)); +#38168 = CARTESIAN_POINT('',(-5.476129151737E-002,0.1270965353)); +#38169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38170 = PCURVE('',#38171,#38210); +#38171 = B_SPLINE_SURFACE_WITH_KNOTS('',3,1,( + (#38172,#38173) + ,(#38174,#38175) + ,(#38176,#38177) + ,(#38178,#38179) + ,(#38180,#38181) + ,(#38182,#38183) + ,(#38184,#38185) + ,(#38186,#38187) + ,(#38188,#38189) + ,(#38190,#38191) + ,(#38192,#38193) + ,(#38194,#38195) + ,(#38196,#38197) + ,(#38198,#38199) + ,(#38200,#38201) + ,(#38202,#38203) + ,(#38204,#38205) + ,(#38206,#38207) + ,(#38208,#38209 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(2, 2),(0.E+000,4.078184587226E-002,8.086958872159E-002,0.120268165788, 0.160186850455,0.200459737639,0.242265177898,0.286459261549, 0.332952083749,0.38443053405,0.44338912536,0.511681472214, 0.589020025549,0.676245190651,0.773705191473,0.881567767782,1.),( 0.E+000,1.),.UNSPECIFIED.); -#35780 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) - ); -#35781 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); -#35782 = CARTESIAN_POINT('',(4.804517208894E-002,0.782,-0.213906658604) - ); -#35783 = CARTESIAN_POINT('',(4.804517208894E-002,0.78,-0.213906658604)); -#35784 = CARTESIAN_POINT('',(5.141764309196E-002,0.782,-0.214035410531) - ); -#35785 = CARTESIAN_POINT('',(5.141764309196E-002,0.78,-0.214035410531)); -#35786 = CARTESIAN_POINT('',(5.638223117045E-002,0.782,-0.214893006742) - ); -#35787 = CARTESIAN_POINT('',(5.638223117045E-002,0.78,-0.214893006742)); -#35788 = CARTESIAN_POINT('',(6.111203334238E-002,0.782,-0.216495269081) - ); -#35789 = CARTESIAN_POINT('',(6.111203334238E-002,0.78,-0.216495269081)); -#35790 = CARTESIAN_POINT('',(6.564970062238E-002,0.782,-0.2185902339)); -#35791 = CARTESIAN_POINT('',(6.564970062238E-002,0.78,-0.2185902339)); -#35792 = CARTESIAN_POINT('',(6.997180501741E-002,0.782,-0.221303716357) - ); -#35793 = CARTESIAN_POINT('',(6.997180501741E-002,0.78,-0.221303716357)); -#35794 = CARTESIAN_POINT('',(7.405561628751E-002,0.782,-0.224646574521) - ); -#35795 = CARTESIAN_POINT('',(7.405561628751E-002,0.78,-0.224646574521)); -#35796 = CARTESIAN_POINT('',(7.796634882193E-002,0.782,-0.228562328874) - ); -#35797 = CARTESIAN_POINT('',(7.796634882193E-002,0.78,-0.228562328874)); -#35798 = CARTESIAN_POINT('',(8.171745878217E-002,0.782,-0.23317101758)); -#35799 = CARTESIAN_POINT('',(8.171745878217E-002,0.78,-0.23317101758)); -#35800 = CARTESIAN_POINT('',(8.51327153258E-002,0.782,-0.238785717198)); -#35801 = CARTESIAN_POINT('',(8.51327153258E-002,0.78,-0.238785717198)); -#35802 = CARTESIAN_POINT('',(8.79659172187E-002,0.782,-0.245705187194)); -#35803 = CARTESIAN_POINT('',(8.79659172187E-002,0.78,-0.245705187194)); -#35804 = CARTESIAN_POINT('',(9.03945903539E-002,0.782,-0.253895035499)); -#35805 = CARTESIAN_POINT('',(9.03945903539E-002,0.78,-0.253895035499)); -#35806 = CARTESIAN_POINT('',(9.23702381141E-002,0.782,-0.263414257755)); -#35807 = CARTESIAN_POINT('',(9.23702381141E-002,0.78,-0.263414257755)); -#35808 = CARTESIAN_POINT('',(9.386445519084E-002,0.782,-0.27424545438)); -#35809 = CARTESIAN_POINT('',(9.386445519084E-002,0.78,-0.27424545438)); -#35810 = CARTESIAN_POINT('',(9.498322097506E-002,0.782,-0.28639894949)); -#35811 = CARTESIAN_POINT('',(9.498322097506E-002,0.78,-0.28639894949)); -#35812 = CARTESIAN_POINT('',(9.56414439216E-002,0.782,-0.299890938867)); -#35813 = CARTESIAN_POINT('',(9.56414439216E-002,0.78,-0.299890938867)); -#35814 = CARTESIAN_POINT('',(9.570299473456E-002,0.782,-0.309329742842) - ); -#35815 = CARTESIAN_POINT('',(9.570299473456E-002,0.78,-0.309329742842)); -#35816 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) - ); -#35817 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); -#35818 = DEFINITIONAL_REPRESENTATION('',(#35819),#35823); -#35819 = LINE('',#35820,#35821); -#35820 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35821 = VECTOR('',#35822,1.); -#35822 = DIRECTION('',(1.,0.E+000)); -#35823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35824 = ADVANCED_FACE('',(#35825),#29794,.T.); -#35825 = FACE_BOUND('',#35826,.T.); -#35826 = EDGE_LOOP('',(#35827,#35828,#35847,#35848)); -#35827 = ORIENTED_EDGE('',*,*,#29760,.F.); -#35828 = ORIENTED_EDGE('',*,*,#35829,.F.); -#35829 = EDGE_CURVE('',#35130,#29761,#35830,.T.); -#35830 = SURFACE_CURVE('',#35831,(#35835,#35841),.PCURVE_S1.); -#35831 = LINE('',#35832,#35833); -#35832 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) - ); -#35833 = VECTOR('',#35834,1.); -#35834 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35835 = PCURVE('',#29794,#35836); -#35836 = DEFINITIONAL_REPRESENTATION('',(#35837),#35840); -#35837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35838,#35839),.UNSPECIFIED., +#38172 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) + ); +#38173 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); +#38174 = CARTESIAN_POINT('',(4.804517208894E-002,0.782,-0.213906658604) + ); +#38175 = CARTESIAN_POINT('',(4.804517208894E-002,0.78,-0.213906658604)); +#38176 = CARTESIAN_POINT('',(5.141764309196E-002,0.782,-0.214035410531) + ); +#38177 = CARTESIAN_POINT('',(5.141764309196E-002,0.78,-0.214035410531)); +#38178 = CARTESIAN_POINT('',(5.638223117045E-002,0.782,-0.214893006742) + ); +#38179 = CARTESIAN_POINT('',(5.638223117045E-002,0.78,-0.214893006742)); +#38180 = CARTESIAN_POINT('',(6.111203334238E-002,0.782,-0.216495269081) + ); +#38181 = CARTESIAN_POINT('',(6.111203334238E-002,0.78,-0.216495269081)); +#38182 = CARTESIAN_POINT('',(6.564970062238E-002,0.782,-0.2185902339)); +#38183 = CARTESIAN_POINT('',(6.564970062238E-002,0.78,-0.2185902339)); +#38184 = CARTESIAN_POINT('',(6.997180501741E-002,0.782,-0.221303716357) + ); +#38185 = CARTESIAN_POINT('',(6.997180501741E-002,0.78,-0.221303716357)); +#38186 = CARTESIAN_POINT('',(7.405561628751E-002,0.782,-0.224646574521) + ); +#38187 = CARTESIAN_POINT('',(7.405561628751E-002,0.78,-0.224646574521)); +#38188 = CARTESIAN_POINT('',(7.796634882193E-002,0.782,-0.228562328874) + ); +#38189 = CARTESIAN_POINT('',(7.796634882193E-002,0.78,-0.228562328874)); +#38190 = CARTESIAN_POINT('',(8.171745878217E-002,0.782,-0.23317101758)); +#38191 = CARTESIAN_POINT('',(8.171745878217E-002,0.78,-0.23317101758)); +#38192 = CARTESIAN_POINT('',(8.51327153258E-002,0.782,-0.238785717198)); +#38193 = CARTESIAN_POINT('',(8.51327153258E-002,0.78,-0.238785717198)); +#38194 = CARTESIAN_POINT('',(8.79659172187E-002,0.782,-0.245705187194)); +#38195 = CARTESIAN_POINT('',(8.79659172187E-002,0.78,-0.245705187194)); +#38196 = CARTESIAN_POINT('',(9.03945903539E-002,0.782,-0.253895035499)); +#38197 = CARTESIAN_POINT('',(9.03945903539E-002,0.78,-0.253895035499)); +#38198 = CARTESIAN_POINT('',(9.23702381141E-002,0.782,-0.263414257755)); +#38199 = CARTESIAN_POINT('',(9.23702381141E-002,0.78,-0.263414257755)); +#38200 = CARTESIAN_POINT('',(9.386445519084E-002,0.782,-0.27424545438)); +#38201 = CARTESIAN_POINT('',(9.386445519084E-002,0.78,-0.27424545438)); +#38202 = CARTESIAN_POINT('',(9.498322097506E-002,0.782,-0.28639894949)); +#38203 = CARTESIAN_POINT('',(9.498322097506E-002,0.78,-0.28639894949)); +#38204 = CARTESIAN_POINT('',(9.56414439216E-002,0.782,-0.299890938867)); +#38205 = CARTESIAN_POINT('',(9.56414439216E-002,0.78,-0.299890938867)); +#38206 = CARTESIAN_POINT('',(9.570299473456E-002,0.782,-0.309329742842) + ); +#38207 = CARTESIAN_POINT('',(9.570299473456E-002,0.78,-0.309329742842)); +#38208 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) + ); +#38209 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); +#38210 = DEFINITIONAL_REPRESENTATION('',(#38211),#38215); +#38211 = LINE('',#38212,#38213); +#38212 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38213 = VECTOR('',#38214,1.); +#38214 = DIRECTION('',(1.,0.E+000)); +#38215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38216 = ADVANCED_FACE('',(#38217),#32186,.T.); +#38217 = FACE_BOUND('',#38218,.T.); +#38218 = EDGE_LOOP('',(#38219,#38220,#38239,#38240)); +#38219 = ORIENTED_EDGE('',*,*,#32152,.F.); +#38220 = ORIENTED_EDGE('',*,*,#38221,.F.); +#38221 = EDGE_CURVE('',#37522,#32153,#38222,.T.); +#38222 = SURFACE_CURVE('',#38223,(#38227,#38233),.PCURVE_S1.); +#38223 = LINE('',#38224,#38225); +#38224 = CARTESIAN_POINT('',(-1.102082749717E-002,0.782,-0.208954104399) + ); +#38225 = VECTOR('',#38226,1.); +#38226 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38227 = PCURVE('',#32186,#38228); +#38228 = DEFINITIONAL_REPRESENTATION('',(#38229),#38232); +#38229 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38230,#38231),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35838 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35839 = CARTESIAN_POINT('',(0.E+000,1.)); -#35840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38230 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38231 = CARTESIAN_POINT('',(0.E+000,1.)); +#38232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35841 = PCURVE('',#30216,#35842); -#35842 = DEFINITIONAL_REPRESENTATION('',(#35843),#35846); -#35843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35844,#35845),.UNSPECIFIED., +#38233 = PCURVE('',#32608,#38234); +#38234 = DEFINITIONAL_REPRESENTATION('',(#38235),#38238); +#38235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38236,#38237),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35844 = CARTESIAN_POINT('',(1.,0.E+000)); -#35845 = CARTESIAN_POINT('',(1.,1.)); -#35846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35847 = ORIENTED_EDGE('',*,*,#35129,.T.); -#35848 = ORIENTED_EDGE('',*,*,#35849,.T.); -#35849 = EDGE_CURVE('',#35132,#29763,#35850,.T.); -#35850 = SURFACE_CURVE('',#35851,(#35855,#35861),.PCURVE_S1.); -#35851 = LINE('',#35852,#35853); -#35852 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) - ); -#35853 = VECTOR('',#35854,1.); -#35854 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35855 = PCURVE('',#29794,#35856); -#35856 = DEFINITIONAL_REPRESENTATION('',(#35857),#35860); -#35857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35858,#35859),.UNSPECIFIED., +#38236 = CARTESIAN_POINT('',(1.,0.E+000)); +#38237 = CARTESIAN_POINT('',(1.,1.)); +#38238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38239 = ORIENTED_EDGE('',*,*,#37521,.T.); +#38240 = ORIENTED_EDGE('',*,*,#38241,.T.); +#38241 = EDGE_CURVE('',#37524,#32155,#38242,.T.); +#38242 = SURFACE_CURVE('',#38243,(#38247,#38253),.PCURVE_S1.); +#38243 = LINE('',#38244,#38245); +#38244 = CARTESIAN_POINT('',(-3.597344292535E-002,0.782,-0.31416667873) + ); +#38245 = VECTOR('',#38246,1.); +#38246 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38247 = PCURVE('',#32186,#38248); +#38248 = DEFINITIONAL_REPRESENTATION('',(#38249),#38252); +#38249 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38250,#38251),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35858 = CARTESIAN_POINT('',(1.,0.E+000)); -#35859 = CARTESIAN_POINT('',(1.,1.)); -#35860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38250 = CARTESIAN_POINT('',(1.,0.E+000)); +#38251 = CARTESIAN_POINT('',(1.,1.)); +#38252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35861 = PCURVE('',#29888,#35862); -#35862 = DEFINITIONAL_REPRESENTATION('',(#35863),#35866); -#35863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35864,#35865),.UNSPECIFIED., +#38253 = PCURVE('',#32280,#38254); +#38254 = DEFINITIONAL_REPRESENTATION('',(#38255),#38258); +#38255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38256,#38257),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35864 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35865 = CARTESIAN_POINT('',(0.E+000,1.)); -#35866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35867 = ADVANCED_FACE('',(#35868),#30216,.T.); -#35868 = FACE_BOUND('',#35869,.T.); -#35869 = EDGE_LOOP('',(#35870,#35871,#35890,#35891)); -#35870 = ORIENTED_EDGE('',*,*,#30186,.F.); -#35871 = ORIENTED_EDGE('',*,*,#35872,.F.); -#35872 = EDGE_CURVE('',#35176,#30061,#35873,.T.); -#35873 = SURFACE_CURVE('',#35874,(#35878,#35884),.PCURVE_S1.); -#35874 = LINE('',#35875,#35876); -#35875 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) - ); -#35876 = VECTOR('',#35877,1.); -#35877 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35878 = PCURVE('',#30216,#35879); -#35879 = DEFINITIONAL_REPRESENTATION('',(#35880),#35883); -#35880 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35881,#35882),.UNSPECIFIED., +#38256 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38257 = CARTESIAN_POINT('',(0.E+000,1.)); +#38258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38259 = ADVANCED_FACE('',(#38260),#32608,.T.); +#38260 = FACE_BOUND('',#38261,.T.); +#38261 = EDGE_LOOP('',(#38262,#38263,#38282,#38283)); +#38262 = ORIENTED_EDGE('',*,*,#32578,.F.); +#38263 = ORIENTED_EDGE('',*,*,#38264,.F.); +#38264 = EDGE_CURVE('',#37568,#32453,#38265,.T.); +#38265 = SURFACE_CURVE('',#38266,(#38270,#38276),.PCURVE_S1.); +#38266 = LINE('',#38267,#38268); +#38267 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.184207283737) + ); +#38268 = VECTOR('',#38269,1.); +#38269 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38270 = PCURVE('',#32608,#38271); +#38271 = DEFINITIONAL_REPRESENTATION('',(#38272),#38275); +#38272 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38273,#38274),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35882 = CARTESIAN_POINT('',(0.E+000,1.)); -#35883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38274 = CARTESIAN_POINT('',(0.E+000,1.)); +#38275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35884 = PCURVE('',#30124,#35885); -#35885 = DEFINITIONAL_REPRESENTATION('',(#35886),#35889); -#35886 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35887,#35888),.UNSPECIFIED., +#38276 = PCURVE('',#32516,#38277); +#38277 = DEFINITIONAL_REPRESENTATION('',(#38278),#38281); +#38278 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38279,#38280),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35887 = CARTESIAN_POINT('',(1.,0.E+000)); -#35888 = CARTESIAN_POINT('',(1.,1.)); -#35889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35890 = ORIENTED_EDGE('',*,*,#35175,.T.); -#35891 = ORIENTED_EDGE('',*,*,#35829,.T.); -#35892 = ADVANCED_FACE('',(#35893),#30124,.T.); -#35893 = FACE_BOUND('',#35894,.T.); -#35894 = EDGE_LOOP('',(#35895,#35896,#35915,#35916)); -#35895 = ORIENTED_EDGE('',*,*,#30060,.F.); -#35896 = ORIENTED_EDGE('',*,*,#35897,.F.); -#35897 = EDGE_CURVE('',#35215,#29951,#35898,.T.); -#35898 = SURFACE_CURVE('',#35899,(#35903,#35909),.PCURVE_S1.); -#35899 = LINE('',#35900,#35901); -#35900 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); -#35901 = VECTOR('',#35902,1.); -#35902 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35903 = PCURVE('',#30124,#35904); -#35904 = DEFINITIONAL_REPRESENTATION('',(#35905),#35908); -#35905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35906,#35907),.UNSPECIFIED., +#38279 = CARTESIAN_POINT('',(1.,0.E+000)); +#38280 = CARTESIAN_POINT('',(1.,1.)); +#38281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38282 = ORIENTED_EDGE('',*,*,#37567,.T.); +#38283 = ORIENTED_EDGE('',*,*,#38221,.T.); +#38284 = ADVANCED_FACE('',(#38285),#32516,.T.); +#38285 = FACE_BOUND('',#38286,.T.); +#38286 = EDGE_LOOP('',(#38287,#38288,#38307,#38308)); +#38287 = ORIENTED_EDGE('',*,*,#32452,.F.); +#38288 = ORIENTED_EDGE('',*,*,#38289,.F.); +#38289 = EDGE_CURVE('',#37607,#32343,#38290,.T.); +#38290 = SURFACE_CURVE('',#38291,(#38295,#38301),.PCURVE_S1.); +#38291 = LINE('',#38292,#38293); +#38292 = CARTESIAN_POINT('',(0.128662370209,0.782,-0.31416667873)); +#38293 = VECTOR('',#38294,1.); +#38294 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38295 = PCURVE('',#32516,#38296); +#38296 = DEFINITIONAL_REPRESENTATION('',(#38297),#38300); +#38297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38298,#38299),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35906 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35907 = CARTESIAN_POINT('',(0.E+000,1.)); -#35908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38298 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38299 = CARTESIAN_POINT('',(0.E+000,1.)); +#38300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35909 = PCURVE('',#30006,#35910); -#35910 = DEFINITIONAL_REPRESENTATION('',(#35911),#35914); -#35911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35912,#35913),.UNSPECIFIED., +#38301 = PCURVE('',#32398,#38302); +#38302 = DEFINITIONAL_REPRESENTATION('',(#38303),#38306); +#38303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38304,#38305),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35912 = CARTESIAN_POINT('',(1.,0.E+000)); -#35913 = CARTESIAN_POINT('',(1.,1.)); -#35914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35915 = ORIENTED_EDGE('',*,*,#35214,.T.); -#35916 = ORIENTED_EDGE('',*,*,#35872,.T.); -#35917 = ADVANCED_FACE('',(#35918),#30006,.T.); -#35918 = FACE_BOUND('',#35919,.T.); -#35919 = EDGE_LOOP('',(#35920,#35921,#35940,#35941)); -#35920 = ORIENTED_EDGE('',*,*,#29950,.F.); -#35921 = ORIENTED_EDGE('',*,*,#35922,.F.); -#35922 = EDGE_CURVE('',#35286,#29825,#35923,.T.); -#35923 = SURFACE_CURVE('',#35924,(#35928,#35934),.PCURVE_S1.); -#35924 = LINE('',#35925,#35926); -#35925 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); -#35926 = VECTOR('',#35927,1.); -#35927 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#35928 = PCURVE('',#30006,#35929); -#35929 = DEFINITIONAL_REPRESENTATION('',(#35930),#35933); -#35930 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35931,#35932),.UNSPECIFIED., +#38304 = CARTESIAN_POINT('',(1.,0.E+000)); +#38305 = CARTESIAN_POINT('',(1.,1.)); +#38306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38307 = ORIENTED_EDGE('',*,*,#37606,.T.); +#38308 = ORIENTED_EDGE('',*,*,#38264,.T.); +#38309 = ADVANCED_FACE('',(#38310),#32398,.T.); +#38310 = FACE_BOUND('',#38311,.T.); +#38311 = EDGE_LOOP('',(#38312,#38313,#38332,#38333)); +#38312 = ORIENTED_EDGE('',*,*,#32342,.F.); +#38313 = ORIENTED_EDGE('',*,*,#38314,.F.); +#38314 = EDGE_CURVE('',#37678,#32217,#38315,.T.); +#38315 = SURFACE_CURVE('',#38316,(#38320,#38326),.PCURVE_S1.); +#38316 = LINE('',#38317,#38318); +#38317 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.44433186849)); +#38318 = VECTOR('',#38319,1.); +#38319 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38320 = PCURVE('',#32398,#38321); +#38321 = DEFINITIONAL_REPRESENTATION('',(#38322),#38325); +#38322 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38323,#38324),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35931 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#35932 = CARTESIAN_POINT('',(0.E+000,1.)); -#35933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38323 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38324 = CARTESIAN_POINT('',(0.E+000,1.)); +#38325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#35934 = PCURVE('',#29888,#35935); -#35935 = DEFINITIONAL_REPRESENTATION('',(#35936),#35939); -#35936 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#35937,#35938),.UNSPECIFIED., +#38326 = PCURVE('',#32280,#38327); +#38327 = DEFINITIONAL_REPRESENTATION('',(#38328),#38331); +#38328 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38329,#38330),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#35937 = CARTESIAN_POINT('',(1.,0.E+000)); -#35938 = CARTESIAN_POINT('',(1.,1.)); -#35939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35940 = ORIENTED_EDGE('',*,*,#35285,.T.); -#35941 = ORIENTED_EDGE('',*,*,#35897,.T.); -#35942 = ADVANCED_FACE('',(#35943),#29888,.T.); -#35943 = FACE_BOUND('',#35944,.T.); -#35944 = EDGE_LOOP('',(#35945,#35946,#35947,#35948)); -#35945 = ORIENTED_EDGE('',*,*,#29824,.F.); -#35946 = ORIENTED_EDGE('',*,*,#35849,.F.); -#35947 = ORIENTED_EDGE('',*,*,#35348,.T.); -#35948 = ORIENTED_EDGE('',*,*,#35922,.T.); -#35949 = ADVANCED_FACE('',(#35950),#35547,.T.); -#35950 = FACE_BOUND('',#35951,.T.); -#35951 = EDGE_LOOP('',(#35952,#35998,#36017,#36018)); -#35952 = ORIENTED_EDGE('',*,*,#35953,.F.); -#35953 = EDGE_CURVE('',#35954,#35956,#35958,.T.); -#35954 = VERTEX_POINT('',#35955); -#35955 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); -#35956 = VERTEX_POINT('',#35957); -#35957 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) - ); -#35958 = SURFACE_CURVE('',#35959,(#35971,#35978),.PCURVE_S1.); -#35959 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35960,#35961,#35962,#35963, - #35964,#35965,#35966,#35967,#35968,#35969,#35970),.UNSPECIFIED.,.F., +#38329 = CARTESIAN_POINT('',(1.,0.E+000)); +#38330 = CARTESIAN_POINT('',(1.,1.)); +#38331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38332 = ORIENTED_EDGE('',*,*,#37677,.T.); +#38333 = ORIENTED_EDGE('',*,*,#38289,.T.); +#38334 = ADVANCED_FACE('',(#38335),#32280,.T.); +#38335 = FACE_BOUND('',#38336,.T.); +#38336 = EDGE_LOOP('',(#38337,#38338,#38339,#38340)); +#38337 = ORIENTED_EDGE('',*,*,#32216,.F.); +#38338 = ORIENTED_EDGE('',*,*,#38241,.F.); +#38339 = ORIENTED_EDGE('',*,*,#37740,.T.); +#38340 = ORIENTED_EDGE('',*,*,#38314,.T.); +#38341 = ADVANCED_FACE('',(#38342),#37939,.T.); +#38342 = FACE_BOUND('',#38343,.T.); +#38343 = EDGE_LOOP('',(#38344,#38390,#38409,#38410)); +#38344 = ORIENTED_EDGE('',*,*,#38345,.F.); +#38345 = EDGE_CURVE('',#38346,#38348,#38350,.T.); +#38346 = VERTEX_POINT('',#38347); +#38347 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); +#38348 = VERTEX_POINT('',#38349); +#38349 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) + ); +#38350 = SURFACE_CURVE('',#38351,(#38363,#38370),.PCURVE_S1.); +#38351 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38352,#38353,#38354,#38355, + #38356,#38357,#38358,#38359,#38360,#38361,#38362),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,8.388811327955E-002,0.177154032754, 0.282513635562,0.39939986066,0.529490806191,0.672802177676, 0.82953576162,1.),.UNSPECIFIED.); -#35960 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); -#35961 = CARTESIAN_POINT('',(1.059858853463E-002,0.78,-0.395055894417)); -#35962 = CARTESIAN_POINT('',(8.014174182464E-003,0.78,-0.390735014434)); -#35963 = CARTESIAN_POINT('',(5.122364794867E-003,0.78,-0.383225146997)); -#35964 = CARTESIAN_POINT('',(2.567854700152E-003,0.78,-0.374642797984)); -#35965 = CARTESIAN_POINT('',(4.646459563984E-004,0.78,-0.364855921721)); -#35966 = CARTESIAN_POINT('',(-1.056878022553E-003,0.78,-0.353881306637) - ); -#35967 = CARTESIAN_POINT('',(-2.258062370921E-003,0.78,-0.341731697672) - ); -#35968 = CARTESIAN_POINT('',(-2.882032929567E-003,0.78,-0.328390132521) - ); -#35969 = CARTESIAN_POINT('',(-2.990020629803E-003,0.78,-0.319106291796) - ); -#35970 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) - ); -#35971 = PCURVE('',#35547,#35972); -#35972 = DEFINITIONAL_REPRESENTATION('',(#35973),#35977); -#35973 = LINE('',#35974,#35975); -#35974 = CARTESIAN_POINT('',(0.E+000,1.)); -#35975 = VECTOR('',#35976,1.); -#35976 = DIRECTION('',(1.,0.E+000)); -#35977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35978 = PCURVE('',#35979,#35984); -#35979 = PLANE('',#35980); -#35980 = AXIS2_PLACEMENT_3D('',#35981,#35982,#35983); -#35981 = CARTESIAN_POINT('',(-1.,0.78,0.625)); -#35982 = DIRECTION('',(0.E+000,1.,0.E+000)); -#35983 = DIRECTION('',(0.E+000,0.E+000,1.)); -#35984 = DEFINITIONAL_REPRESENTATION('',(#35985),#35997); -#35985 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#35986,#35987,#35988,#35989, - #35990,#35991,#35992,#35993,#35994,#35995,#35996),.UNSPECIFIED.,.F., +#38352 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); +#38353 = CARTESIAN_POINT('',(1.059858853463E-002,0.78,-0.395055894417)); +#38354 = CARTESIAN_POINT('',(8.014174182464E-003,0.78,-0.390735014434)); +#38355 = CARTESIAN_POINT('',(5.122364794867E-003,0.78,-0.383225146997)); +#38356 = CARTESIAN_POINT('',(2.567854700152E-003,0.78,-0.374642797984)); +#38357 = CARTESIAN_POINT('',(4.646459563984E-004,0.78,-0.364855921721)); +#38358 = CARTESIAN_POINT('',(-1.056878022553E-003,0.78,-0.353881306637) + ); +#38359 = CARTESIAN_POINT('',(-2.258062370921E-003,0.78,-0.341731697672) + ); +#38360 = CARTESIAN_POINT('',(-2.882032929567E-003,0.78,-0.328390132521) + ); +#38361 = CARTESIAN_POINT('',(-2.990020629803E-003,0.78,-0.319106291796) + ); +#38362 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) + ); +#38363 = PCURVE('',#37939,#38364); +#38364 = DEFINITIONAL_REPRESENTATION('',(#38365),#38369); +#38365 = LINE('',#38366,#38367); +#38366 = CARTESIAN_POINT('',(0.E+000,1.)); +#38367 = VECTOR('',#38368,1.); +#38368 = DIRECTION('',(1.,0.E+000)); +#38369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38370 = PCURVE('',#38371,#38376); +#38371 = PLANE('',#38372); +#38372 = AXIS2_PLACEMENT_3D('',#38373,#38374,#38375); +#38373 = CARTESIAN_POINT('',(-1.,0.78,0.625)); +#38374 = DIRECTION('',(0.E+000,1.,0.E+000)); +#38375 = DIRECTION('',(0.E+000,0.E+000,1.)); +#38376 = DEFINITIONAL_REPRESENTATION('',(#38377),#38389); +#38377 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38378,#38379,#38380,#38381, + #38382,#38383,#38384,#38385,#38386,#38387,#38388),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,8.388811327955E-002,0.177154032754, 0.282513635562,0.39939986066,0.529490806191,0.672802177676, 0.82953576162,1.),.UNSPECIFIED.); -#35986 = CARTESIAN_POINT('',(-1.022101969597,1.011822391575)); -#35987 = CARTESIAN_POINT('',(-1.020055894417,1.010598588535)); -#35988 = CARTESIAN_POINT('',(-1.015735014434,1.008014174182)); -#35989 = CARTESIAN_POINT('',(-1.008225146997,1.005122364795)); -#35990 = CARTESIAN_POINT('',(-0.999642797984,1.0025678547)); -#35991 = CARTESIAN_POINT('',(-0.989855921721,1.000464645956)); -#35992 = CARTESIAN_POINT('',(-0.978881306637,0.998943121977)); -#35993 = CARTESIAN_POINT('',(-0.966731697672,0.997741937629)); -#35994 = CARTESIAN_POINT('',(-0.953390132521,0.99711796707)); -#35995 = CARTESIAN_POINT('',(-0.944106291796,0.99700997937)); -#35996 = CARTESIAN_POINT('',(-0.939269576113,0.996953719702)); -#35997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#35998 = ORIENTED_EDGE('',*,*,#35999,.F.); -#35999 = EDGE_CURVE('',#35516,#35954,#36000,.T.); -#36000 = SURFACE_CURVE('',#36001,(#36005,#36011),.PCURVE_S1.); -#36001 = LINE('',#36002,#36003); -#36002 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) - ); -#36003 = VECTOR('',#36004,1.); -#36004 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36005 = PCURVE('',#35547,#36006); -#36006 = DEFINITIONAL_REPRESENTATION('',(#36007),#36010); -#36007 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36008,#36009),.UNSPECIFIED., +#38378 = CARTESIAN_POINT('',(-1.022101969597,1.011822391575)); +#38379 = CARTESIAN_POINT('',(-1.020055894417,1.010598588535)); +#38380 = CARTESIAN_POINT('',(-1.015735014434,1.008014174182)); +#38381 = CARTESIAN_POINT('',(-1.008225146997,1.005122364795)); +#38382 = CARTESIAN_POINT('',(-0.999642797984,1.0025678547)); +#38383 = CARTESIAN_POINT('',(-0.989855921721,1.000464645956)); +#38384 = CARTESIAN_POINT('',(-0.978881306637,0.998943121977)); +#38385 = CARTESIAN_POINT('',(-0.966731697672,0.997741937629)); +#38386 = CARTESIAN_POINT('',(-0.953390132521,0.99711796707)); +#38387 = CARTESIAN_POINT('',(-0.944106291796,0.99700997937)); +#38388 = CARTESIAN_POINT('',(-0.939269576113,0.996953719702)); +#38389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38390 = ORIENTED_EDGE('',*,*,#38391,.F.); +#38391 = EDGE_CURVE('',#37908,#38346,#38392,.T.); +#38392 = SURFACE_CURVE('',#38393,(#38397,#38403),.PCURVE_S1.); +#38393 = LINE('',#38394,#38395); +#38394 = CARTESIAN_POINT('',(1.182239157522E-002,0.782,-0.397101969597) + ); +#38395 = VECTOR('',#38396,1.); +#38396 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38397 = PCURVE('',#37939,#38398); +#38398 = DEFINITIONAL_REPRESENTATION('',(#38399),#38402); +#38399 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38400,#38401),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36008 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36009 = CARTESIAN_POINT('',(0.E+000,1.)); -#36010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38400 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38401 = CARTESIAN_POINT('',(0.E+000,1.)); +#38402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36011 = PCURVE('',#35609,#36012); -#36012 = DEFINITIONAL_REPRESENTATION('',(#36013),#36016); -#36013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36014,#36015),.UNSPECIFIED., +#38403 = PCURVE('',#38001,#38404); +#38404 = DEFINITIONAL_REPRESENTATION('',(#38405),#38408); +#38405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38406,#38407),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36014 = CARTESIAN_POINT('',(1.,0.E+000)); -#36015 = CARTESIAN_POINT('',(1.,1.)); -#36016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36017 = ORIENTED_EDGE('',*,*,#35515,.T.); -#36018 = ORIENTED_EDGE('',*,*,#36019,.T.); -#36019 = EDGE_CURVE('',#35420,#35956,#36020,.T.); -#36020 = SURFACE_CURVE('',#36021,(#36025,#36031),.PCURVE_S1.); -#36021 = LINE('',#36022,#36023); -#36022 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) - ); -#36023 = VECTOR('',#36024,1.); -#36024 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36025 = PCURVE('',#35547,#36026); -#36026 = DEFINITIONAL_REPRESENTATION('',(#36027),#36030); -#36027 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36028,#36029),.UNSPECIFIED., +#38406 = CARTESIAN_POINT('',(1.,0.E+000)); +#38407 = CARTESIAN_POINT('',(1.,1.)); +#38408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38409 = ORIENTED_EDGE('',*,*,#37907,.T.); +#38410 = ORIENTED_EDGE('',*,*,#38411,.T.); +#38411 = EDGE_CURVE('',#37812,#38348,#38412,.T.); +#38412 = SURFACE_CURVE('',#38413,(#38417,#38423),.PCURVE_S1.); +#38413 = LINE('',#38414,#38415); +#38414 = CARTESIAN_POINT('',(-3.046280298478E-003,0.782,-0.314269576113) + ); +#38415 = VECTOR('',#38416,1.); +#38416 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38417 = PCURVE('',#37939,#38418); +#38418 = DEFINITIONAL_REPRESENTATION('',(#38419),#38422); +#38419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38420,#38421),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36028 = CARTESIAN_POINT('',(1.,0.E+000)); -#36029 = CARTESIAN_POINT('',(1.,1.)); -#36030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38420 = CARTESIAN_POINT('',(1.,0.E+000)); +#38421 = CARTESIAN_POINT('',(1.,1.)); +#38422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36031 = PCURVE('',#35469,#36032); -#36032 = DEFINITIONAL_REPRESENTATION('',(#36033),#36036); -#36033 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36034,#36035),.UNSPECIFIED., +#38423 = PCURVE('',#37861,#38424); +#38424 = DEFINITIONAL_REPRESENTATION('',(#38425),#38428); +#38425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38426,#38427),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36035 = CARTESIAN_POINT('',(0.E+000,1.)); -#36036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36037 = ADVANCED_FACE('',(#36038),#35469,.T.); -#36038 = FACE_BOUND('',#36039,.T.); -#36039 = EDGE_LOOP('',(#36040,#36095,#36096,#36097)); -#36040 = ORIENTED_EDGE('',*,*,#36041,.F.); -#36041 = EDGE_CURVE('',#35956,#36042,#36044,.T.); -#36042 = VERTEX_POINT('',#36043); -#36043 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); -#36044 = SURFACE_CURVE('',#36045,(#36065,#36072),.PCURVE_S1.); -#36045 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36046,#36047,#36048,#36049, - #36050,#36051,#36052,#36053,#36054,#36055,#36056,#36057,#36058, - #36059,#36060,#36061,#36062,#36063,#36064),.UNSPECIFIED.,.F.,.F.,(4, +#38426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38427 = CARTESIAN_POINT('',(0.E+000,1.)); +#38428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38429 = ADVANCED_FACE('',(#38430),#37861,.T.); +#38430 = FACE_BOUND('',#38431,.T.); +#38431 = EDGE_LOOP('',(#38432,#38487,#38488,#38489)); +#38432 = ORIENTED_EDGE('',*,*,#38433,.F.); +#38433 = EDGE_CURVE('',#38348,#38434,#38436,.T.); +#38434 = VERTEX_POINT('',#38435); +#38435 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); +#38436 = SURFACE_CURVE('',#38437,(#38457,#38464),.PCURVE_S1.); +#38437 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38438,#38439,#38440,#38441, + #38442,#38443,#38444,#38445,#38446,#38447,#38448,#38449,#38450, + #38451,#38452,#38453,#38454,#38455,#38456),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.118405508154, 0.226654332817,0.324092341929,0.411704803005,0.489025905006, 0.556909397343,0.616233344493,0.667349281277,0.713512393201, 0.757696504521,0.799492511442,0.839976064744,0.879885741817, 0.919148659386,0.959227356493,1.),.UNSPECIFIED.); -#36046 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) - ); -#36047 = CARTESIAN_POINT('',(-3.013586244362E-003,0.78,-0.309329765127) - ); -#36048 = CARTESIAN_POINT('',(-2.951002593161E-003,0.78,-0.299873874259) - ); -#36049 = CARTESIAN_POINT('',(-2.297155351481E-003,0.78,-0.286364502734) - ); -#36050 = CARTESIAN_POINT('',(-1.17158423761E-003,0.78,-0.274177205581)); -#36051 = CARTESIAN_POINT('',(3.164942935639E-004,0.78,-0.263328856907)); -#36052 = CARTESIAN_POINT('',(2.281360452602E-003,0.78,-0.253804782175)); -#36053 = CARTESIAN_POINT('',(4.748482306681E-003,0.78,-0.245629251661)); -#36054 = CARTESIAN_POINT('',(7.529515432953E-003,0.78,-0.238704140464)); -#36055 = CARTESIAN_POINT('',(1.09709912278E-002,0.78,-0.233115280007)); -#36056 = CARTESIAN_POINT('',(1.473902710952E-002,0.78,-0.228559543441)); -#36057 = CARTESIAN_POINT('',(1.86292666432E-002,0.78,-0.224641462662)); -#36058 = CARTESIAN_POINT('',(2.273323371754E-002,0.78,-0.221311183714)); -#36059 = CARTESIAN_POINT('',(2.702415044334E-002,0.78,-0.218534410237)); -#36060 = CARTESIAN_POINT('',(3.156859348143E-002,0.78,-0.216432019795)); -#36061 = CARTESIAN_POINT('',(3.631687010258E-002,0.78,-0.214908202522)); -#36062 = CARTESIAN_POINT('',(4.127001349122E-002,0.78,-0.214031269077)); -#36063 = CARTESIAN_POINT('',(4.464332921115E-002,0.78,-0.213905270242)); -#36064 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); -#36065 = PCURVE('',#35469,#36066); -#36066 = DEFINITIONAL_REPRESENTATION('',(#36067),#36071); -#36067 = LINE('',#36068,#36069); -#36068 = CARTESIAN_POINT('',(0.E+000,1.)); -#36069 = VECTOR('',#36070,1.); -#36070 = DIRECTION('',(1.,0.E+000)); -#36071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36072 = PCURVE('',#35979,#36073); -#36073 = DEFINITIONAL_REPRESENTATION('',(#36074),#36094); -#36074 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36075,#36076,#36077,#36078, - #36079,#36080,#36081,#36082,#36083,#36084,#36085,#36086,#36087, - #36088,#36089,#36090,#36091,#36092,#36093),.UNSPECIFIED.,.F.,.F.,(4, +#38438 = CARTESIAN_POINT('',(-3.046280298478E-003,0.78,-0.314269576113) + ); +#38439 = CARTESIAN_POINT('',(-3.013586244362E-003,0.78,-0.309329765127) + ); +#38440 = CARTESIAN_POINT('',(-2.951002593161E-003,0.78,-0.299873874259) + ); +#38441 = CARTESIAN_POINT('',(-2.297155351481E-003,0.78,-0.286364502734) + ); +#38442 = CARTESIAN_POINT('',(-1.17158423761E-003,0.78,-0.274177205581)); +#38443 = CARTESIAN_POINT('',(3.164942935639E-004,0.78,-0.263328856907)); +#38444 = CARTESIAN_POINT('',(2.281360452602E-003,0.78,-0.253804782175)); +#38445 = CARTESIAN_POINT('',(4.748482306681E-003,0.78,-0.245629251661)); +#38446 = CARTESIAN_POINT('',(7.529515432953E-003,0.78,-0.238704140464)); +#38447 = CARTESIAN_POINT('',(1.09709912278E-002,0.78,-0.233115280007)); +#38448 = CARTESIAN_POINT('',(1.473902710952E-002,0.78,-0.228559543441)); +#38449 = CARTESIAN_POINT('',(1.86292666432E-002,0.78,-0.224641462662)); +#38450 = CARTESIAN_POINT('',(2.273323371754E-002,0.78,-0.221311183714)); +#38451 = CARTESIAN_POINT('',(2.702415044334E-002,0.78,-0.218534410237)); +#38452 = CARTESIAN_POINT('',(3.156859348143E-002,0.78,-0.216432019795)); +#38453 = CARTESIAN_POINT('',(3.631687010258E-002,0.78,-0.214908202522)); +#38454 = CARTESIAN_POINT('',(4.127001349122E-002,0.78,-0.214031269077)); +#38455 = CARTESIAN_POINT('',(4.464332921115E-002,0.78,-0.213905270242)); +#38456 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); +#38457 = PCURVE('',#37861,#38458); +#38458 = DEFINITIONAL_REPRESENTATION('',(#38459),#38463); +#38459 = LINE('',#38460,#38461); +#38460 = CARTESIAN_POINT('',(0.E+000,1.)); +#38461 = VECTOR('',#38462,1.); +#38462 = DIRECTION('',(1.,0.E+000)); +#38463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38464 = PCURVE('',#38371,#38465); +#38465 = DEFINITIONAL_REPRESENTATION('',(#38466),#38486); +#38466 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38467,#38468,#38469,#38470, + #38471,#38472,#38473,#38474,#38475,#38476,#38477,#38478,#38479, + #38480,#38481,#38482,#38483,#38484,#38485),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.118405508154, 0.226654332817,0.324092341929,0.411704803005,0.489025905006, 0.556909397343,0.616233344493,0.667349281277,0.713512393201, 0.757696504521,0.799492511442,0.839976064744,0.879885741817, 0.919148659386,0.959227356493,1.),.UNSPECIFIED.); -#36075 = CARTESIAN_POINT('',(-0.939269576113,0.996953719702)); -#36076 = CARTESIAN_POINT('',(-0.934329765127,0.996986413756)); -#36077 = CARTESIAN_POINT('',(-0.924873874259,0.997048997407)); -#36078 = CARTESIAN_POINT('',(-0.911364502734,0.997702844649)); -#36079 = CARTESIAN_POINT('',(-0.899177205581,0.998828415762)); -#36080 = CARTESIAN_POINT('',(-0.888328856907,1.000316494294)); -#36081 = CARTESIAN_POINT('',(-0.878804782175,1.002281360453)); -#36082 = CARTESIAN_POINT('',(-0.870629251661,1.004748482307)); -#36083 = CARTESIAN_POINT('',(-0.863704140464,1.007529515433)); -#36084 = CARTESIAN_POINT('',(-0.858115280007,1.010970991228)); -#36085 = CARTESIAN_POINT('',(-0.853559543441,1.01473902711)); -#36086 = CARTESIAN_POINT('',(-0.849641462662,1.018629266643)); -#36087 = CARTESIAN_POINT('',(-0.846311183714,1.022733233718)); -#36088 = CARTESIAN_POINT('',(-0.843534410237,1.027024150443)); -#36089 = CARTESIAN_POINT('',(-0.841432019795,1.031568593481)); -#36090 = CARTESIAN_POINT('',(-0.839908202522,1.036316870103)); -#36091 = CARTESIAN_POINT('',(-0.839031269077,1.041270013491)); -#36092 = CARTESIAN_POINT('',(-0.838905270242,1.044643329211)); -#36093 = CARTESIAN_POINT('',(-0.838841730101,1.046344463642)); -#36094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36095 = ORIENTED_EDGE('',*,*,#36019,.F.); -#36096 = ORIENTED_EDGE('',*,*,#35419,.T.); -#36097 = ORIENTED_EDGE('',*,*,#36098,.T.); -#36098 = EDGE_CURVE('',#35422,#36042,#36099,.T.); -#36099 = SURFACE_CURVE('',#36100,(#36104,#36110),.PCURVE_S1.); -#36100 = LINE('',#36101,#36102); -#36101 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) - ); -#36102 = VECTOR('',#36103,1.); -#36103 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36104 = PCURVE('',#35469,#36105); -#36105 = DEFINITIONAL_REPRESENTATION('',(#36106),#36109); -#36106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36107,#36108),.UNSPECIFIED., +#38467 = CARTESIAN_POINT('',(-0.939269576113,0.996953719702)); +#38468 = CARTESIAN_POINT('',(-0.934329765127,0.996986413756)); +#38469 = CARTESIAN_POINT('',(-0.924873874259,0.997048997407)); +#38470 = CARTESIAN_POINT('',(-0.911364502734,0.997702844649)); +#38471 = CARTESIAN_POINT('',(-0.899177205581,0.998828415762)); +#38472 = CARTESIAN_POINT('',(-0.888328856907,1.000316494294)); +#38473 = CARTESIAN_POINT('',(-0.878804782175,1.002281360453)); +#38474 = CARTESIAN_POINT('',(-0.870629251661,1.004748482307)); +#38475 = CARTESIAN_POINT('',(-0.863704140464,1.007529515433)); +#38476 = CARTESIAN_POINT('',(-0.858115280007,1.010970991228)); +#38477 = CARTESIAN_POINT('',(-0.853559543441,1.01473902711)); +#38478 = CARTESIAN_POINT('',(-0.849641462662,1.018629266643)); +#38479 = CARTESIAN_POINT('',(-0.846311183714,1.022733233718)); +#38480 = CARTESIAN_POINT('',(-0.843534410237,1.027024150443)); +#38481 = CARTESIAN_POINT('',(-0.841432019795,1.031568593481)); +#38482 = CARTESIAN_POINT('',(-0.839908202522,1.036316870103)); +#38483 = CARTESIAN_POINT('',(-0.839031269077,1.041270013491)); +#38484 = CARTESIAN_POINT('',(-0.838905270242,1.044643329211)); +#38485 = CARTESIAN_POINT('',(-0.838841730101,1.046344463642)); +#38486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38487 = ORIENTED_EDGE('',*,*,#38411,.F.); +#38488 = ORIENTED_EDGE('',*,*,#37811,.T.); +#38489 = ORIENTED_EDGE('',*,*,#38490,.T.); +#38490 = EDGE_CURVE('',#37814,#38434,#38491,.T.); +#38491 = SURFACE_CURVE('',#38492,(#38496,#38502),.PCURVE_S1.); +#38492 = LINE('',#38493,#38494); +#38493 = CARTESIAN_POINT('',(4.634446364183E-002,0.782,-0.213841730101) + ); +#38494 = VECTOR('',#38495,1.); +#38495 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38496 = PCURVE('',#37861,#38497); +#38497 = DEFINITIONAL_REPRESENTATION('',(#38498),#38501); +#38498 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38499,#38500),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36107 = CARTESIAN_POINT('',(1.,0.E+000)); -#36108 = CARTESIAN_POINT('',(1.,1.)); -#36109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38499 = CARTESIAN_POINT('',(1.,0.E+000)); +#38500 = CARTESIAN_POINT('',(1.,1.)); +#38501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36110 = PCURVE('',#35779,#36111); -#36111 = DEFINITIONAL_REPRESENTATION('',(#36112),#36115); -#36112 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36113,#36114),.UNSPECIFIED., +#38502 = PCURVE('',#38171,#38503); +#38503 = DEFINITIONAL_REPRESENTATION('',(#38504),#38507); +#38504 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38505,#38506),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36114 = CARTESIAN_POINT('',(0.E+000,1.)); -#36115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36116 = ADVANCED_FACE('',(#36117),#35779,.T.); -#36117 = FACE_BOUND('',#36118,.T.); -#36118 = EDGE_LOOP('',(#36119,#36174,#36175,#36176)); -#36119 = ORIENTED_EDGE('',*,*,#36120,.F.); -#36120 = EDGE_CURVE('',#36042,#36121,#36123,.T.); -#36121 = VERTEX_POINT('',#36122); -#36122 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); -#36123 = SURFACE_CURVE('',#36124,(#36144,#36151),.PCURVE_S1.); -#36124 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36125,#36126,#36127,#36128, - #36129,#36130,#36131,#36132,#36133,#36134,#36135,#36136,#36137, - #36138,#36139,#36140,#36141,#36142,#36143),.UNSPECIFIED.,.F.,.F.,(4, +#38505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38506 = CARTESIAN_POINT('',(0.E+000,1.)); +#38507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38508 = ADVANCED_FACE('',(#38509),#38171,.T.); +#38509 = FACE_BOUND('',#38510,.T.); +#38510 = EDGE_LOOP('',(#38511,#38566,#38567,#38568)); +#38511 = ORIENTED_EDGE('',*,*,#38512,.F.); +#38512 = EDGE_CURVE('',#38434,#38513,#38515,.T.); +#38513 = VERTEX_POINT('',#38514); +#38514 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); +#38515 = SURFACE_CURVE('',#38516,(#38536,#38543),.PCURVE_S1.); +#38516 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38517,#38518,#38519,#38520, + #38521,#38522,#38523,#38524,#38525,#38526,#38527,#38528,#38529, + #38530,#38531,#38532,#38533,#38534,#38535),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.078184587226E-002, 8.086958872159E-002,0.120268165788,0.160186850455,0.200459737639, 0.242265177898,0.286459261549,0.332952083749,0.38443053405, 0.44338912536,0.511681472214,0.589020025549,0.676245190651, 0.773705191473,0.881567767782,1.),.UNSPECIFIED.); -#36125 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); -#36126 = CARTESIAN_POINT('',(4.804517208894E-002,0.78,-0.213906658604)); -#36127 = CARTESIAN_POINT('',(5.141764309196E-002,0.78,-0.214035410531)); -#36128 = CARTESIAN_POINT('',(5.638223117045E-002,0.78,-0.214893006742)); -#36129 = CARTESIAN_POINT('',(6.111203334238E-002,0.78,-0.216495269081)); -#36130 = CARTESIAN_POINT('',(6.564970062238E-002,0.78,-0.2185902339)); -#36131 = CARTESIAN_POINT('',(6.997180501741E-002,0.78,-0.221303716357)); -#36132 = CARTESIAN_POINT('',(7.405561628751E-002,0.78,-0.224646574521)); -#36133 = CARTESIAN_POINT('',(7.796634882193E-002,0.78,-0.228562328874)); -#36134 = CARTESIAN_POINT('',(8.171745878217E-002,0.78,-0.23317101758)); -#36135 = CARTESIAN_POINT('',(8.51327153258E-002,0.78,-0.238785717198)); -#36136 = CARTESIAN_POINT('',(8.79659172187E-002,0.78,-0.245705187194)); -#36137 = CARTESIAN_POINT('',(9.03945903539E-002,0.78,-0.253895035499)); -#36138 = CARTESIAN_POINT('',(9.23702381141E-002,0.78,-0.263414257755)); -#36139 = CARTESIAN_POINT('',(9.386445519084E-002,0.78,-0.27424545438)); -#36140 = CARTESIAN_POINT('',(9.498322097506E-002,0.78,-0.28639894949)); -#36141 = CARTESIAN_POINT('',(9.56414439216E-002,0.78,-0.299890938867)); -#36142 = CARTESIAN_POINT('',(9.570299473456E-002,0.78,-0.309329742842)); -#36143 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); -#36144 = PCURVE('',#35779,#36145); -#36145 = DEFINITIONAL_REPRESENTATION('',(#36146),#36150); -#36146 = LINE('',#36147,#36148); -#36147 = CARTESIAN_POINT('',(0.E+000,1.)); -#36148 = VECTOR('',#36149,1.); -#36149 = DIRECTION('',(1.,0.E+000)); -#36150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36151 = PCURVE('',#35979,#36152); -#36152 = DEFINITIONAL_REPRESENTATION('',(#36153),#36173); -#36153 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36154,#36155,#36156,#36157, - #36158,#36159,#36160,#36161,#36162,#36163,#36164,#36165,#36166, - #36167,#36168,#36169,#36170,#36171,#36172),.UNSPECIFIED.,.F.,.F.,(4, +#38517 = CARTESIAN_POINT('',(4.634446364183E-002,0.78,-0.213841730101)); +#38518 = CARTESIAN_POINT('',(4.804517208894E-002,0.78,-0.213906658604)); +#38519 = CARTESIAN_POINT('',(5.141764309196E-002,0.78,-0.214035410531)); +#38520 = CARTESIAN_POINT('',(5.638223117045E-002,0.78,-0.214893006742)); +#38521 = CARTESIAN_POINT('',(6.111203334238E-002,0.78,-0.216495269081)); +#38522 = CARTESIAN_POINT('',(6.564970062238E-002,0.78,-0.2185902339)); +#38523 = CARTESIAN_POINT('',(6.997180501741E-002,0.78,-0.221303716357)); +#38524 = CARTESIAN_POINT('',(7.405561628751E-002,0.78,-0.224646574521)); +#38525 = CARTESIAN_POINT('',(7.796634882193E-002,0.78,-0.228562328874)); +#38526 = CARTESIAN_POINT('',(8.171745878217E-002,0.78,-0.23317101758)); +#38527 = CARTESIAN_POINT('',(8.51327153258E-002,0.78,-0.238785717198)); +#38528 = CARTESIAN_POINT('',(8.79659172187E-002,0.78,-0.245705187194)); +#38529 = CARTESIAN_POINT('',(9.03945903539E-002,0.78,-0.253895035499)); +#38530 = CARTESIAN_POINT('',(9.23702381141E-002,0.78,-0.263414257755)); +#38531 = CARTESIAN_POINT('',(9.386445519084E-002,0.78,-0.27424545438)); +#38532 = CARTESIAN_POINT('',(9.498322097506E-002,0.78,-0.28639894949)); +#38533 = CARTESIAN_POINT('',(9.56414439216E-002,0.78,-0.299890938867)); +#38534 = CARTESIAN_POINT('',(9.570299473456E-002,0.78,-0.309329742842)); +#38535 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); +#38536 = PCURVE('',#38171,#38537); +#38537 = DEFINITIONAL_REPRESENTATION('',(#38538),#38542); +#38538 = LINE('',#38539,#38540); +#38539 = CARTESIAN_POINT('',(0.E+000,1.)); +#38540 = VECTOR('',#38541,1.); +#38541 = DIRECTION('',(1.,0.E+000)); +#38542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38543 = PCURVE('',#38371,#38544); +#38544 = DEFINITIONAL_REPRESENTATION('',(#38545),#38565); +#38545 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38546,#38547,#38548,#38549, + #38550,#38551,#38552,#38553,#38554,#38555,#38556,#38557,#38558, + #38559,#38560,#38561,#38562,#38563,#38564),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.078184587226E-002, 8.086958872159E-002,0.120268165788,0.160186850455,0.200459737639, 0.242265177898,0.286459261549,0.332952083749,0.38443053405, 0.44338912536,0.511681472214,0.589020025549,0.676245190651, 0.773705191473,0.881567767782,1.),.UNSPECIFIED.); -#36154 = CARTESIAN_POINT('',(-0.838841730101,1.046344463642)); -#36155 = CARTESIAN_POINT('',(-0.838906658604,1.048045172089)); -#36156 = CARTESIAN_POINT('',(-0.839035410531,1.051417643092)); -#36157 = CARTESIAN_POINT('',(-0.839893006742,1.05638223117)); -#36158 = CARTESIAN_POINT('',(-0.841495269081,1.061112033342)); -#36159 = CARTESIAN_POINT('',(-0.8435902339,1.065649700622)); -#36160 = CARTESIAN_POINT('',(-0.846303716357,1.069971805017)); -#36161 = CARTESIAN_POINT('',(-0.849646574521,1.074055616288)); -#36162 = CARTESIAN_POINT('',(-0.853562328874,1.077966348822)); -#36163 = CARTESIAN_POINT('',(-0.85817101758,1.081717458782)); -#36164 = CARTESIAN_POINT('',(-0.863785717198,1.085132715326)); -#36165 = CARTESIAN_POINT('',(-0.870705187194,1.087965917219)); -#36166 = CARTESIAN_POINT('',(-0.878895035499,1.090394590354)); -#36167 = CARTESIAN_POINT('',(-0.888414257755,1.092370238114)); -#36168 = CARTESIAN_POINT('',(-0.89924545438,1.093864455191)); -#36169 = CARTESIAN_POINT('',(-0.91139894949,1.094983220975)); -#36170 = CARTESIAN_POINT('',(-0.924890938867,1.095641443922)); -#36171 = CARTESIAN_POINT('',(-0.934329742842,1.095702994735)); -#36172 = CARTESIAN_POINT('',(-0.939269576113,1.095735207582)); -#36173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36174 = ORIENTED_EDGE('',*,*,#36098,.F.); -#36175 = ORIENTED_EDGE('',*,*,#35733,.T.); -#36176 = ORIENTED_EDGE('',*,*,#36177,.T.); -#36177 = EDGE_CURVE('',#35640,#36121,#36178,.T.); -#36178 = SURFACE_CURVE('',#36179,(#36183,#36189),.PCURVE_S1.); -#36179 = LINE('',#36180,#36181); -#36180 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) - ); -#36181 = VECTOR('',#36182,1.); -#36182 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36183 = PCURVE('',#35779,#36184); -#36184 = DEFINITIONAL_REPRESENTATION('',(#36185),#36188); -#36185 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36186,#36187),.UNSPECIFIED., +#38546 = CARTESIAN_POINT('',(-0.838841730101,1.046344463642)); +#38547 = CARTESIAN_POINT('',(-0.838906658604,1.048045172089)); +#38548 = CARTESIAN_POINT('',(-0.839035410531,1.051417643092)); +#38549 = CARTESIAN_POINT('',(-0.839893006742,1.05638223117)); +#38550 = CARTESIAN_POINT('',(-0.841495269081,1.061112033342)); +#38551 = CARTESIAN_POINT('',(-0.8435902339,1.065649700622)); +#38552 = CARTESIAN_POINT('',(-0.846303716357,1.069971805017)); +#38553 = CARTESIAN_POINT('',(-0.849646574521,1.074055616288)); +#38554 = CARTESIAN_POINT('',(-0.853562328874,1.077966348822)); +#38555 = CARTESIAN_POINT('',(-0.85817101758,1.081717458782)); +#38556 = CARTESIAN_POINT('',(-0.863785717198,1.085132715326)); +#38557 = CARTESIAN_POINT('',(-0.870705187194,1.087965917219)); +#38558 = CARTESIAN_POINT('',(-0.878895035499,1.090394590354)); +#38559 = CARTESIAN_POINT('',(-0.888414257755,1.092370238114)); +#38560 = CARTESIAN_POINT('',(-0.89924545438,1.093864455191)); +#38561 = CARTESIAN_POINT('',(-0.91139894949,1.094983220975)); +#38562 = CARTESIAN_POINT('',(-0.924890938867,1.095641443922)); +#38563 = CARTESIAN_POINT('',(-0.934329742842,1.095702994735)); +#38564 = CARTESIAN_POINT('',(-0.939269576113,1.095735207582)); +#38565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38566 = ORIENTED_EDGE('',*,*,#38490,.F.); +#38567 = ORIENTED_EDGE('',*,*,#38125,.T.); +#38568 = ORIENTED_EDGE('',*,*,#38569,.T.); +#38569 = EDGE_CURVE('',#38032,#38513,#38570,.T.); +#38570 = SURFACE_CURVE('',#38571,(#38575,#38581),.PCURVE_S1.); +#38571 = LINE('',#38572,#38573); +#38572 = CARTESIAN_POINT('',(9.573520758213E-002,0.782,-0.314269576113) + ); +#38573 = VECTOR('',#38574,1.); +#38574 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38575 = PCURVE('',#38171,#38576); +#38576 = DEFINITIONAL_REPRESENTATION('',(#38577),#38580); +#38577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38578,#38579),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36186 = CARTESIAN_POINT('',(1.,0.E+000)); -#36187 = CARTESIAN_POINT('',(1.,1.)); -#36188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38578 = CARTESIAN_POINT('',(1.,0.E+000)); +#38579 = CARTESIAN_POINT('',(1.,1.)); +#38580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36189 = PCURVE('',#35687,#36190); -#36190 = DEFINITIONAL_REPRESENTATION('',(#36191),#36194); -#36191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36192,#36193),.UNSPECIFIED., +#38581 = PCURVE('',#38079,#38582); +#38582 = DEFINITIONAL_REPRESENTATION('',(#38583),#38586); +#38583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38584,#38585),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36192 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36193 = CARTESIAN_POINT('',(0.E+000,1.)); -#36194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36195 = ADVANCED_FACE('',(#36196),#35687,.T.); -#36196 = FACE_BOUND('',#36197,.T.); -#36197 = EDGE_LOOP('',(#36198,#36253,#36254,#36255)); -#36198 = ORIENTED_EDGE('',*,*,#36199,.F.); -#36199 = EDGE_CURVE('',#36121,#36200,#36202,.T.); -#36200 = VERTEX_POINT('',#36201); -#36201 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); -#36202 = SURFACE_CURVE('',#36203,(#36223,#36230),.PCURVE_S1.); -#36203 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36204,#36205,#36206,#36207, - #36208,#36209,#36210,#36211,#36212,#36213,#36214,#36215,#36216, - #36217,#36218,#36219,#36220,#36221,#36222),.UNSPECIFIED.,.F.,.F.,(4, +#38584 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38585 = CARTESIAN_POINT('',(0.E+000,1.)); +#38586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38587 = ADVANCED_FACE('',(#38588),#38079,.T.); +#38588 = FACE_BOUND('',#38589,.T.); +#38589 = EDGE_LOOP('',(#38590,#38645,#38646,#38647)); +#38590 = ORIENTED_EDGE('',*,*,#38591,.F.); +#38591 = EDGE_CURVE('',#38513,#38592,#38594,.T.); +#38592 = VERTEX_POINT('',#38593); +#38593 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); +#38594 = SURFACE_CURVE('',#38595,(#38615,#38622),.PCURVE_S1.); +#38595 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38596,#38597,#38598,#38599, + #38600,#38601,#38602,#38603,#38604,#38605,#38606,#38607,#38608, + #38609,#38610,#38611,#38612,#38613,#38614),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.115629130925, 0.22154103912,0.317047856219,0.40315087564,0.480181216716, 0.547649366148,0.607035842842,0.658652408064,0.705722890354, 0.74980408798,0.792586815345,0.83387396101,0.874768393303, 0.915222698892,0.95688070373,1.),.UNSPECIFIED.); -#36204 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); -#36205 = CARTESIAN_POINT('',(9.570402613498E-002,0.78,-0.31910662744)); -#36206 = CARTESIAN_POINT('',(9.564428366222E-002,0.78,-0.328374234735)); -#36207 = CARTESIAN_POINT('',(9.496908424492E-002,0.78,-0.341623347885)); -#36208 = CARTESIAN_POINT('',(9.39109860771E-002,0.78,-0.35360608623)); -#36209 = CARTESIAN_POINT('',(9.246367587471E-002,0.78,-0.364333496744)); -#36210 = CARTESIAN_POINT('',(9.054020088409E-002,0.78,-0.373793933352)); -#36211 = CARTESIAN_POINT('',(8.820728810449E-002,0.78,-0.382007536038)); -#36212 = CARTESIAN_POINT('',(8.542727370253E-002,0.78,-0.388956787959)); -#36213 = CARTESIAN_POINT('',(8.212184649905E-002,0.78,-0.394711494488)); -#36214 = CARTESIAN_POINT('',(7.844224465158E-002,0.78,-0.39943191503)); -#36215 = CARTESIAN_POINT('',(7.459855169955E-002,0.78,-0.40351784974)); -#36216 = CARTESIAN_POINT('',(7.049467493159E-002,0.78,-0.406992804096)); -#36217 = CARTESIAN_POINT('',(6.60579060004E-002,0.78,-0.409780463741)); -#36218 = CARTESIAN_POINT('',(6.143125031312E-002,0.78,-0.412029443855)); -#36219 = CARTESIAN_POINT('',(5.650839908174E-002,0.78,-0.413577249241)); -#36220 = CARTESIAN_POINT('',(5.133774004351E-002,0.78,-0.414528172457)); -#36221 = CARTESIAN_POINT('',(4.778918382805E-002,0.78,-0.414640360978)); -#36222 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); -#36223 = PCURVE('',#35687,#36224); -#36224 = DEFINITIONAL_REPRESENTATION('',(#36225),#36229); -#36225 = LINE('',#36226,#36227); -#36226 = CARTESIAN_POINT('',(0.E+000,1.)); -#36227 = VECTOR('',#36228,1.); -#36228 = DIRECTION('',(1.,0.E+000)); -#36229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36230 = PCURVE('',#35979,#36231); -#36231 = DEFINITIONAL_REPRESENTATION('',(#36232),#36252); -#36232 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36233,#36234,#36235,#36236, - #36237,#36238,#36239,#36240,#36241,#36242,#36243,#36244,#36245, - #36246,#36247,#36248,#36249,#36250,#36251),.UNSPECIFIED.,.F.,.F.,(4, +#38596 = CARTESIAN_POINT('',(9.573520758213E-002,0.78,-0.314269576113)); +#38597 = CARTESIAN_POINT('',(9.570402613498E-002,0.78,-0.31910662744)); +#38598 = CARTESIAN_POINT('',(9.564428366222E-002,0.78,-0.328374234735)); +#38599 = CARTESIAN_POINT('',(9.496908424492E-002,0.78,-0.341623347885)); +#38600 = CARTESIAN_POINT('',(9.39109860771E-002,0.78,-0.35360608623)); +#38601 = CARTESIAN_POINT('',(9.246367587471E-002,0.78,-0.364333496744)); +#38602 = CARTESIAN_POINT('',(9.054020088409E-002,0.78,-0.373793933352)); +#38603 = CARTESIAN_POINT('',(8.820728810449E-002,0.78,-0.382007536038)); +#38604 = CARTESIAN_POINT('',(8.542727370253E-002,0.78,-0.388956787959)); +#38605 = CARTESIAN_POINT('',(8.212184649905E-002,0.78,-0.394711494488)); +#38606 = CARTESIAN_POINT('',(7.844224465158E-002,0.78,-0.39943191503)); +#38607 = CARTESIAN_POINT('',(7.459855169955E-002,0.78,-0.40351784974)); +#38608 = CARTESIAN_POINT('',(7.049467493159E-002,0.78,-0.406992804096)); +#38609 = CARTESIAN_POINT('',(6.60579060004E-002,0.78,-0.409780463741)); +#38610 = CARTESIAN_POINT('',(6.143125031312E-002,0.78,-0.412029443855)); +#38611 = CARTESIAN_POINT('',(5.650839908174E-002,0.78,-0.413577249241)); +#38612 = CARTESIAN_POINT('',(5.133774004351E-002,0.78,-0.414528172457)); +#38613 = CARTESIAN_POINT('',(4.778918382805E-002,0.78,-0.414640360978)); +#38614 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); +#38615 = PCURVE('',#38079,#38616); +#38616 = DEFINITIONAL_REPRESENTATION('',(#38617),#38621); +#38617 = LINE('',#38618,#38619); +#38618 = CARTESIAN_POINT('',(0.E+000,1.)); +#38619 = VECTOR('',#38620,1.); +#38620 = DIRECTION('',(1.,0.E+000)); +#38621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38622 = PCURVE('',#38371,#38623); +#38623 = DEFINITIONAL_REPRESENTATION('',(#38624),#38644); +#38624 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38625,#38626,#38627,#38628, + #38629,#38630,#38631,#38632,#38633,#38634,#38635,#38636,#38637, + #38638,#38639,#38640,#38641,#38642,#38643),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.115629130925, 0.22154103912,0.317047856219,0.40315087564,0.480181216716, 0.547649366148,0.607035842842,0.658652408064,0.705722890354, 0.74980408798,0.792586815345,0.83387396101,0.874768393303, 0.915222698892,0.95688070373,1.),.UNSPECIFIED.); -#36233 = CARTESIAN_POINT('',(-0.939269576113,1.095735207582)); -#36234 = CARTESIAN_POINT('',(-0.94410662744,1.095704026135)); -#36235 = CARTESIAN_POINT('',(-0.953374234735,1.095644283662)); -#36236 = CARTESIAN_POINT('',(-0.966623347885,1.094969084245)); -#36237 = CARTESIAN_POINT('',(-0.97860608623,1.093910986077)); -#36238 = CARTESIAN_POINT('',(-0.989333496744,1.092463675875)); -#36239 = CARTESIAN_POINT('',(-0.998793933352,1.090540200884)); -#36240 = CARTESIAN_POINT('',(-1.007007536038,1.088207288104)); -#36241 = CARTESIAN_POINT('',(-1.013956787959,1.085427273703)); -#36242 = CARTESIAN_POINT('',(-1.019711494488,1.082121846499)); -#36243 = CARTESIAN_POINT('',(-1.02443191503,1.078442244652)); -#36244 = CARTESIAN_POINT('',(-1.02851784974,1.0745985517)); -#36245 = CARTESIAN_POINT('',(-1.031992804096,1.070494674932)); -#36246 = CARTESIAN_POINT('',(-1.034780463741,1.066057906)); -#36247 = CARTESIAN_POINT('',(-1.037029443855,1.061431250313)); -#36248 = CARTESIAN_POINT('',(-1.038577249241,1.056508399082)); -#36249 = CARTESIAN_POINT('',(-1.039528172457,1.051337740044)); -#36250 = CARTESIAN_POINT('',(-1.039640360978,1.047789183828)); -#36251 = CARTESIAN_POINT('',(-1.039697422125,1.045984322801)); -#36252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36253 = ORIENTED_EDGE('',*,*,#36177,.F.); -#36254 = ORIENTED_EDGE('',*,*,#35639,.T.); -#36255 = ORIENTED_EDGE('',*,*,#36256,.T.); -#36256 = EDGE_CURVE('',#35578,#36200,#36257,.T.); -#36257 = SURFACE_CURVE('',#36258,(#36262,#36268),.PCURVE_S1.); -#36258 = LINE('',#36259,#36260); -#36259 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); -#36260 = VECTOR('',#36261,1.); -#36261 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36262 = PCURVE('',#35687,#36263); -#36263 = DEFINITIONAL_REPRESENTATION('',(#36264),#36267); -#36264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36265,#36266),.UNSPECIFIED., +#38625 = CARTESIAN_POINT('',(-0.939269576113,1.095735207582)); +#38626 = CARTESIAN_POINT('',(-0.94410662744,1.095704026135)); +#38627 = CARTESIAN_POINT('',(-0.953374234735,1.095644283662)); +#38628 = CARTESIAN_POINT('',(-0.966623347885,1.094969084245)); +#38629 = CARTESIAN_POINT('',(-0.97860608623,1.093910986077)); +#38630 = CARTESIAN_POINT('',(-0.989333496744,1.092463675875)); +#38631 = CARTESIAN_POINT('',(-0.998793933352,1.090540200884)); +#38632 = CARTESIAN_POINT('',(-1.007007536038,1.088207288104)); +#38633 = CARTESIAN_POINT('',(-1.013956787959,1.085427273703)); +#38634 = CARTESIAN_POINT('',(-1.019711494488,1.082121846499)); +#38635 = CARTESIAN_POINT('',(-1.02443191503,1.078442244652)); +#38636 = CARTESIAN_POINT('',(-1.02851784974,1.0745985517)); +#38637 = CARTESIAN_POINT('',(-1.031992804096,1.070494674932)); +#38638 = CARTESIAN_POINT('',(-1.034780463741,1.066057906)); +#38639 = CARTESIAN_POINT('',(-1.037029443855,1.061431250313)); +#38640 = CARTESIAN_POINT('',(-1.038577249241,1.056508399082)); +#38641 = CARTESIAN_POINT('',(-1.039528172457,1.051337740044)); +#38642 = CARTESIAN_POINT('',(-1.039640360978,1.047789183828)); +#38643 = CARTESIAN_POINT('',(-1.039697422125,1.045984322801)); +#38644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38645 = ORIENTED_EDGE('',*,*,#38569,.F.); +#38646 = ORIENTED_EDGE('',*,*,#38031,.T.); +#38647 = ORIENTED_EDGE('',*,*,#38648,.T.); +#38648 = EDGE_CURVE('',#37970,#38592,#38649,.T.); +#38649 = SURFACE_CURVE('',#38650,(#38654,#38660),.PCURVE_S1.); +#38650 = LINE('',#38651,#38652); +#38651 = CARTESIAN_POINT('',(4.59843228006E-002,0.782,-0.414697422125)); +#38652 = VECTOR('',#38653,1.); +#38653 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38654 = PCURVE('',#38079,#38655); +#38655 = DEFINITIONAL_REPRESENTATION('',(#38656),#38659); +#38656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38657,#38658),.UNSPECIFIED., .F.,.F.,(2,2),(-1.110223024625E-016,2.E-003), .PIECEWISE_BEZIER_KNOTS.); -#36265 = CARTESIAN_POINT('',(1.,0.E+000)); -#36266 = CARTESIAN_POINT('',(1.,1.)); -#36267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38657 = CARTESIAN_POINT('',(1.,0.E+000)); +#38658 = CARTESIAN_POINT('',(1.,1.)); +#38659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36268 = PCURVE('',#35609,#36269); -#36269 = DEFINITIONAL_REPRESENTATION('',(#36270),#36273); -#36270 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36271,#36272),.UNSPECIFIED., +#38660 = PCURVE('',#38001,#38661); +#38661 = DEFINITIONAL_REPRESENTATION('',(#38662),#38665); +#38662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38663,#38664),.UNSPECIFIED., .F.,.F.,(2,2),(-1.110223024625E-016,2.E-003), .PIECEWISE_BEZIER_KNOTS.); -#36271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36272 = CARTESIAN_POINT('',(0.E+000,1.)); -#36273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38664 = CARTESIAN_POINT('',(0.E+000,1.)); +#38665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36274 = ADVANCED_FACE('',(#36275),#35609,.T.); -#36275 = FACE_BOUND('',#36276,.T.); -#36276 = EDGE_LOOP('',(#36277,#36314,#36315,#36316)); -#36277 = ORIENTED_EDGE('',*,*,#36278,.F.); -#36278 = EDGE_CURVE('',#36200,#35954,#36279,.T.); -#36279 = SURFACE_CURVE('',#36280,(#36292,#36299),.PCURVE_S1.); -#36280 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36281,#36282,#36283,#36284, - #36285,#36286,#36287,#36288,#36289,#36290,#36291),.UNSPECIFIED.,.F., +#38666 = ADVANCED_FACE('',(#38667),#38001,.T.); +#38667 = FACE_BOUND('',#38668,.T.); +#38668 = EDGE_LOOP('',(#38669,#38706,#38707,#38708)); +#38669 = ORIENTED_EDGE('',*,*,#38670,.F.); +#38670 = EDGE_CURVE('',#38592,#38346,#38671,.T.); +#38671 = SURFACE_CURVE('',#38672,(#38684,#38691),.PCURVE_S1.); +#38672 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38673,#38674,#38675,#38676, + #38677,#38678,#38679,#38680,#38681,#38682,#38683),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127664767896,0.251738563008, 0.372753349387,0.492146758972,0.614069621309,0.737197324412, 0.865606990601,1.),.UNSPECIFIED.); -#36281 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); -#36282 = CARTESIAN_POINT('',(4.428329521055E-002,0.78,-0.414652776866)); -#36283 = CARTESIAN_POINT('',(4.092908677692E-002,0.78,-0.414564742134)); -#36284 = CARTESIAN_POINT('',(3.601808635406E-002,0.78,-0.413724451515)); -#36285 = CARTESIAN_POINT('',(3.136398894619E-002,0.78,-0.412319298309)); -#36286 = CARTESIAN_POINT('',(2.691347364148E-002,0.78,-0.410415881856)); -#36287 = CARTESIAN_POINT('',(2.277764518064E-002,0.78,-0.407854259268)); -#36288 = CARTESIAN_POINT('',(1.879248689221E-002,0.78,-0.40486338256)); -#36289 = CARTESIAN_POINT('',(1.514464817155E-002,0.78,-0.401219333118)); -#36290 = CARTESIAN_POINT('',(1.294649256335E-002,0.78,-0.398495098715)); -#36291 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); -#36292 = PCURVE('',#35609,#36293); -#36293 = DEFINITIONAL_REPRESENTATION('',(#36294),#36298); -#36294 = LINE('',#36295,#36296); -#36295 = CARTESIAN_POINT('',(0.E+000,1.)); -#36296 = VECTOR('',#36297,1.); -#36297 = DIRECTION('',(1.,0.E+000)); -#36298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36299 = PCURVE('',#35979,#36300); -#36300 = DEFINITIONAL_REPRESENTATION('',(#36301),#36313); -#36301 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36302,#36303,#36304,#36305, - #36306,#36307,#36308,#36309,#36310,#36311,#36312),.UNSPECIFIED.,.F., +#38673 = CARTESIAN_POINT('',(4.59843228006E-002,0.78,-0.414697422125)); +#38674 = CARTESIAN_POINT('',(4.428329521055E-002,0.78,-0.414652776866)); +#38675 = CARTESIAN_POINT('',(4.092908677692E-002,0.78,-0.414564742134)); +#38676 = CARTESIAN_POINT('',(3.601808635406E-002,0.78,-0.413724451515)); +#38677 = CARTESIAN_POINT('',(3.136398894619E-002,0.78,-0.412319298309)); +#38678 = CARTESIAN_POINT('',(2.691347364148E-002,0.78,-0.410415881856)); +#38679 = CARTESIAN_POINT('',(2.277764518064E-002,0.78,-0.407854259268)); +#38680 = CARTESIAN_POINT('',(1.879248689221E-002,0.78,-0.40486338256)); +#38681 = CARTESIAN_POINT('',(1.514464817155E-002,0.78,-0.401219333118)); +#38682 = CARTESIAN_POINT('',(1.294649256335E-002,0.78,-0.398495098715)); +#38683 = CARTESIAN_POINT('',(1.182239157522E-002,0.78,-0.397101969597)); +#38684 = PCURVE('',#38001,#38685); +#38685 = DEFINITIONAL_REPRESENTATION('',(#38686),#38690); +#38686 = LINE('',#38687,#38688); +#38687 = CARTESIAN_POINT('',(0.E+000,1.)); +#38688 = VECTOR('',#38689,1.); +#38689 = DIRECTION('',(1.,0.E+000)); +#38690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38691 = PCURVE('',#38371,#38692); +#38692 = DEFINITIONAL_REPRESENTATION('',(#38693),#38705); +#38693 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38694,#38695,#38696,#38697, + #38698,#38699,#38700,#38701,#38702,#38703,#38704),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127664767896,0.251738563008, 0.372753349387,0.492146758972,0.614069621309,0.737197324412, 0.865606990601,1.),.UNSPECIFIED.); -#36302 = CARTESIAN_POINT('',(-1.039697422125,1.045984322801)); -#36303 = CARTESIAN_POINT('',(-1.039652776866,1.044283295211)); -#36304 = CARTESIAN_POINT('',(-1.039564742134,1.040929086777)); -#36305 = CARTESIAN_POINT('',(-1.038724451515,1.036018086354)); -#36306 = CARTESIAN_POINT('',(-1.037319298309,1.031363988946)); -#36307 = CARTESIAN_POINT('',(-1.035415881856,1.026913473641)); -#36308 = CARTESIAN_POINT('',(-1.032854259268,1.022777645181)); -#36309 = CARTESIAN_POINT('',(-1.02986338256,1.018792486892)); -#36310 = CARTESIAN_POINT('',(-1.026219333118,1.015144648172)); -#36311 = CARTESIAN_POINT('',(-1.023495098715,1.012946492563)); -#36312 = CARTESIAN_POINT('',(-1.022101969597,1.011822391575)); -#36313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36314 = ORIENTED_EDGE('',*,*,#36256,.F.); -#36315 = ORIENTED_EDGE('',*,*,#35577,.T.); -#36316 = ORIENTED_EDGE('',*,*,#35999,.T.); -#36317 = ADVANCED_FACE('',(#36318),#35979,.T.); -#36318 = FACE_BOUND('',#36319,.T.); -#36319 = EDGE_LOOP('',(#36320,#36321,#36322,#36323,#36324)); -#36320 = ORIENTED_EDGE('',*,*,#35953,.T.); -#36321 = ORIENTED_EDGE('',*,*,#36041,.T.); -#36322 = ORIENTED_EDGE('',*,*,#36120,.T.); -#36323 = ORIENTED_EDGE('',*,*,#36199,.T.); -#36324 = ORIENTED_EDGE('',*,*,#36278,.T.); -#36325 = ADVANCED_FACE('',(#36326),#28894,.T.); -#36326 = FACE_BOUND('',#36327,.T.); -#36327 = EDGE_LOOP('',(#36328,#36329,#36350,#36410)); -#36328 = ORIENTED_EDGE('',*,*,#28839,.F.); -#36329 = ORIENTED_EDGE('',*,*,#36330,.F.); -#36330 = EDGE_CURVE('',#36331,#28840,#36333,.T.); -#36331 = VERTEX_POINT('',#36332); -#36332 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#36333 = SURFACE_CURVE('',#36334,(#36338,#36344),.PCURVE_S1.); -#36334 = LINE('',#36335,#36336); -#36335 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#36336 = VECTOR('',#36337,1.); -#36337 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36338 = PCURVE('',#28894,#36339); -#36339 = DEFINITIONAL_REPRESENTATION('',(#36340),#36343); -#36340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36341,#36342),.UNSPECIFIED., +#38694 = CARTESIAN_POINT('',(-1.039697422125,1.045984322801)); +#38695 = CARTESIAN_POINT('',(-1.039652776866,1.044283295211)); +#38696 = CARTESIAN_POINT('',(-1.039564742134,1.040929086777)); +#38697 = CARTESIAN_POINT('',(-1.038724451515,1.036018086354)); +#38698 = CARTESIAN_POINT('',(-1.037319298309,1.031363988946)); +#38699 = CARTESIAN_POINT('',(-1.035415881856,1.026913473641)); +#38700 = CARTESIAN_POINT('',(-1.032854259268,1.022777645181)); +#38701 = CARTESIAN_POINT('',(-1.02986338256,1.018792486892)); +#38702 = CARTESIAN_POINT('',(-1.026219333118,1.015144648172)); +#38703 = CARTESIAN_POINT('',(-1.023495098715,1.012946492563)); +#38704 = CARTESIAN_POINT('',(-1.022101969597,1.011822391575)); +#38705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38706 = ORIENTED_EDGE('',*,*,#38648,.F.); +#38707 = ORIENTED_EDGE('',*,*,#37969,.T.); +#38708 = ORIENTED_EDGE('',*,*,#38391,.T.); +#38709 = ADVANCED_FACE('',(#38710),#38371,.T.); +#38710 = FACE_BOUND('',#38711,.T.); +#38711 = EDGE_LOOP('',(#38712,#38713,#38714,#38715,#38716)); +#38712 = ORIENTED_EDGE('',*,*,#38345,.T.); +#38713 = ORIENTED_EDGE('',*,*,#38433,.T.); +#38714 = ORIENTED_EDGE('',*,*,#38512,.T.); +#38715 = ORIENTED_EDGE('',*,*,#38591,.T.); +#38716 = ORIENTED_EDGE('',*,*,#38670,.T.); +#38717 = ADVANCED_FACE('',(#38718),#31286,.T.); +#38718 = FACE_BOUND('',#38719,.T.); +#38719 = EDGE_LOOP('',(#38720,#38721,#38742,#38802)); +#38720 = ORIENTED_EDGE('',*,*,#31231,.F.); +#38721 = ORIENTED_EDGE('',*,*,#38722,.F.); +#38722 = EDGE_CURVE('',#38723,#31232,#38725,.T.); +#38723 = VERTEX_POINT('',#38724); +#38724 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#38725 = SURFACE_CURVE('',#38726,(#38730,#38736),.PCURVE_S1.); +#38726 = LINE('',#38727,#38728); +#38727 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#38728 = VECTOR('',#38729,1.); +#38729 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38730 = PCURVE('',#31286,#38731); +#38731 = DEFINITIONAL_REPRESENTATION('',(#38732),#38735); +#38732 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38733,#38734),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36341 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36342 = CARTESIAN_POINT('',(0.E+000,1.)); -#36343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38733 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38734 = CARTESIAN_POINT('',(0.E+000,1.)); +#38735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36344 = PCURVE('',#29728,#36345); -#36345 = DEFINITIONAL_REPRESENTATION('',(#36346),#36349); -#36346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36347,#36348),.UNSPECIFIED., +#38736 = PCURVE('',#32120,#38737); +#38737 = DEFINITIONAL_REPRESENTATION('',(#38738),#38741); +#38738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38739,#38740),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36347 = CARTESIAN_POINT('',(1.,0.E+000)); -#36348 = CARTESIAN_POINT('',(1.,1.)); -#36349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36350 = ORIENTED_EDGE('',*,*,#36351,.T.); -#36351 = EDGE_CURVE('',#36331,#36352,#36354,.T.); -#36352 = VERTEX_POINT('',#36353); -#36353 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#36354 = SURFACE_CURVE('',#36355,(#36375,#36382),.PCURVE_S1.); -#36355 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36356,#36357,#36358,#36359, - #36360,#36361,#36362,#36363,#36364,#36365,#36366,#36367,#36368, - #36369,#36370,#36371,#36372,#36373,#36374),.UNSPECIFIED.,.F.,.F.,(4, +#38739 = CARTESIAN_POINT('',(1.,0.E+000)); +#38740 = CARTESIAN_POINT('',(1.,1.)); +#38741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38742 = ORIENTED_EDGE('',*,*,#38743,.T.); +#38743 = EDGE_CURVE('',#38723,#38744,#38746,.T.); +#38744 = VERTEX_POINT('',#38745); +#38745 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#38746 = SURFACE_CURVE('',#38747,(#38767,#38774),.PCURVE_S1.); +#38747 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38748,#38749,#38750,#38751, + #38752,#38753,#38754,#38755,#38756,#38757,#38758,#38759,#38760, + #38761,#38762,#38763,#38764,#38765,#38766),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.929802345975E-002, 0.135560844101,0.199670955647,0.261716238496,0.322661929947, 0.382906923778,0.443032033073,0.50350078735,0.563724281017, 0.623980022053,0.683629386996,0.743848272486,0.80519184623, 0.86764874296,0.932778084231,1.),.UNSPECIFIED.); -#36356 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#36357 = CARTESIAN_POINT('',(0.238622576902,0.782,-0.184263348524)); -#36358 = CARTESIAN_POINT('',(0.233215879453,0.782,-0.1843730225)); -#36359 = CARTESIAN_POINT('',(0.225299512414,0.782,-0.185326476104)); -#36360 = CARTESIAN_POINT('',(0.217770111238,0.782,-0.186846898403)); -#36361 = CARTESIAN_POINT('',(0.210625317089,0.782,-0.189027654649)); -#36362 = CARTESIAN_POINT('',(0.203843604617,0.782,-0.191783244251)); -#36363 = CARTESIAN_POINT('',(0.1975038024,0.782,-0.195283787924)); -#36364 = CARTESIAN_POINT('',(0.191495890002,0.782,-0.199288191857)); -#36365 = CARTESIAN_POINT('',(0.185952021473,0.782,-0.203919830996)); -#36366 = CARTESIAN_POINT('',(0.180900835422,0.782,-0.209085889254)); -#36367 = CARTESIAN_POINT('',(0.176374870135,0.782,-0.214676908992)); -#36368 = CARTESIAN_POINT('',(0.172435374254,0.782,-0.22069653596)); -#36369 = CARTESIAN_POINT('',(0.169084249171,0.782,-0.227108750047)); -#36370 = CARTESIAN_POINT('',(0.166291241159,0.782,-0.233907401761)); -#36371 = CARTESIAN_POINT('',(0.164154479603,0.782,-0.241138894496)); -#36372 = CARTESIAN_POINT('',(0.162461986633,0.782,-0.248732276169)); -#36373 = CARTESIAN_POINT('',(0.161883400067,0.782,-0.253981123638)); -#36374 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#36375 = PCURVE('',#28894,#36376); -#36376 = DEFINITIONAL_REPRESENTATION('',(#36377),#36381); -#36377 = LINE('',#36378,#36379); -#36378 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36379 = VECTOR('',#36380,1.); -#36380 = DIRECTION('',(1.,0.E+000)); -#36381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36382 = PCURVE('',#36383,#36388); -#36383 = PLANE('',#36384); -#36384 = AXIS2_PLACEMENT_3D('',#36385,#36386,#36387); -#36385 = CARTESIAN_POINT('',(0.186336056019,0.782,-0.203731465836)); -#36386 = DIRECTION('',(-8.32147482049E-015,1.,4.102312887702E-013)); -#36387 = DIRECTION('',(3.359613068219E-043,-4.102312887702E-013,1.)); -#36388 = DEFINITIONAL_REPRESENTATION('',(#36389),#36409); -#36389 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36390,#36391,#36392,#36393, - #36394,#36395,#36396,#36397,#36398,#36399,#36400,#36401,#36402, - #36403,#36404,#36405,#36406,#36407,#36408),.UNSPECIFIED.,.F.,.F.,(4, +#38748 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#38749 = CARTESIAN_POINT('',(0.238622576902,0.782,-0.184263348524)); +#38750 = CARTESIAN_POINT('',(0.233215879453,0.782,-0.1843730225)); +#38751 = CARTESIAN_POINT('',(0.225299512414,0.782,-0.185326476104)); +#38752 = CARTESIAN_POINT('',(0.217770111238,0.782,-0.186846898403)); +#38753 = CARTESIAN_POINT('',(0.210625317089,0.782,-0.189027654649)); +#38754 = CARTESIAN_POINT('',(0.203843604617,0.782,-0.191783244251)); +#38755 = CARTESIAN_POINT('',(0.1975038024,0.782,-0.195283787924)); +#38756 = CARTESIAN_POINT('',(0.191495890002,0.782,-0.199288191857)); +#38757 = CARTESIAN_POINT('',(0.185952021473,0.782,-0.203919830996)); +#38758 = CARTESIAN_POINT('',(0.180900835422,0.782,-0.209085889254)); +#38759 = CARTESIAN_POINT('',(0.176374870135,0.782,-0.214676908992)); +#38760 = CARTESIAN_POINT('',(0.172435374254,0.782,-0.22069653596)); +#38761 = CARTESIAN_POINT('',(0.169084249171,0.782,-0.227108750047)); +#38762 = CARTESIAN_POINT('',(0.166291241159,0.782,-0.233907401761)); +#38763 = CARTESIAN_POINT('',(0.164154479603,0.782,-0.241138894496)); +#38764 = CARTESIAN_POINT('',(0.162461986633,0.782,-0.248732276169)); +#38765 = CARTESIAN_POINT('',(0.161883400067,0.782,-0.253981123638)); +#38766 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#38767 = PCURVE('',#31286,#38768); +#38768 = DEFINITIONAL_REPRESENTATION('',(#38769),#38773); +#38769 = LINE('',#38770,#38771); +#38770 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38771 = VECTOR('',#38772,1.); +#38772 = DIRECTION('',(1.,0.E+000)); +#38773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38774 = PCURVE('',#38775,#38780); +#38775 = PLANE('',#38776); +#38776 = AXIS2_PLACEMENT_3D('',#38777,#38778,#38779); +#38777 = CARTESIAN_POINT('',(0.186336056019,0.782,-0.203731465836)); +#38778 = DIRECTION('',(-8.32147482049E-015,1.,4.102312887702E-013)); +#38779 = DIRECTION('',(3.359613068219E-043,-4.102312887702E-013,1.)); +#38780 = DEFINITIONAL_REPRESENTATION('',(#38781),#38801); +#38781 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38782,#38783,#38784,#38785, + #38786,#38787,#38788,#38789,#38790,#38791,#38792,#38793,#38794, + #38795,#38796,#38797,#38798,#38799,#38800),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.929802345975E-002, 0.135560844101,0.199670955647,0.261716238496,0.322661929947, 0.382906923778,0.443032033073,0.50350078735,0.563724281017, 0.623980022053,0.683629386996,0.743848272486,0.80519184623, 0.86764874296,0.932778084231,1.),.UNSPECIFIED.); -#36390 = CARTESIAN_POINT('',(1.95241820989E-002,5.505039749506E-002)); -#36391 = CARTESIAN_POINT('',(1.946811731235E-002,5.22865208823E-002)); -#36392 = CARTESIAN_POINT('',(1.935844333596E-002,4.687982343393E-002)); -#36393 = CARTESIAN_POINT('',(1.8404989732E-002,3.896345639453E-002)); -#36394 = CARTESIAN_POINT('',(1.688456743298E-002,3.143405521907E-002)); -#36395 = CARTESIAN_POINT('',(1.470381118677E-002,2.428926106933E-002)); -#36396 = CARTESIAN_POINT('',(1.194822158555E-002,1.750754859777E-002)); -#36397 = CARTESIAN_POINT('',(8.447677912123E-003,1.116774638087E-002)); -#36398 = CARTESIAN_POINT('',(4.443273979344E-003,5.15983398262E-003)); -#36399 = CARTESIAN_POINT('',(-1.883651598015E-004,-3.84034546586E-004)); -#36400 = CARTESIAN_POINT('',(-5.354423418195E-003,-5.435220597663E-003) +#38782 = CARTESIAN_POINT('',(1.95241820989E-002,5.505039749506E-002)); +#38783 = CARTESIAN_POINT('',(1.946811731235E-002,5.22865208823E-002)); +#38784 = CARTESIAN_POINT('',(1.935844333596E-002,4.687982343393E-002)); +#38785 = CARTESIAN_POINT('',(1.8404989732E-002,3.896345639453E-002)); +#38786 = CARTESIAN_POINT('',(1.688456743298E-002,3.143405521907E-002)); +#38787 = CARTESIAN_POINT('',(1.470381118677E-002,2.428926106933E-002)); +#38788 = CARTESIAN_POINT('',(1.194822158555E-002,1.750754859777E-002)); +#38789 = CARTESIAN_POINT('',(8.447677912123E-003,1.116774638087E-002)); +#38790 = CARTESIAN_POINT('',(4.443273979344E-003,5.15983398262E-003)); +#38791 = CARTESIAN_POINT('',(-1.883651598015E-004,-3.84034546586E-004)); +#38792 = CARTESIAN_POINT('',(-5.354423418195E-003,-5.435220597663E-003) ); -#36401 = CARTESIAN_POINT('',(-1.09454431553E-002,-9.961185884372E-003)); -#36402 = CARTESIAN_POINT('',(-1.696507012396E-002,-1.390068176532E-002) +#38793 = CARTESIAN_POINT('',(-1.09454431553E-002,-9.961185884372E-003)); +#38794 = CARTESIAN_POINT('',(-1.696507012396E-002,-1.390068176532E-002) ); -#36403 = CARTESIAN_POINT('',(-2.337728421099E-002,-1.725180684859E-002) +#38795 = CARTESIAN_POINT('',(-2.337728421099E-002,-1.725180684859E-002) ); -#36404 = CARTESIAN_POINT('',(-3.017593592489E-002,-2.004481485987E-002) +#38796 = CARTESIAN_POINT('',(-3.017593592489E-002,-2.004481485987E-002) ); -#36405 = CARTESIAN_POINT('',(-3.740742865946E-002,-2.218157641641E-002) +#38797 = CARTESIAN_POINT('',(-3.740742865946E-002,-2.218157641641E-002) ); -#36406 = CARTESIAN_POINT('',(-4.500081033298E-002,-2.387406938663E-002) +#38798 = CARTESIAN_POINT('',(-4.500081033298E-002,-2.387406938663E-002) ); -#36407 = CARTESIAN_POINT('',(-5.024965780151E-002,-2.445265595265E-002) +#38799 = CARTESIAN_POINT('',(-5.024965780151E-002,-2.445265595265E-002) ); -#36408 = CARTESIAN_POINT('',(-5.291557568022E-002,-2.47465231835E-002)); -#36409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38800 = CARTESIAN_POINT('',(-5.291557568022E-002,-2.47465231835E-002)); +#38801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36410 = ORIENTED_EDGE('',*,*,#36411,.T.); -#36411 = EDGE_CURVE('',#36352,#28842,#36412,.T.); -#36412 = SURFACE_CURVE('',#36413,(#36417,#36423),.PCURVE_S1.); -#36413 = LINE('',#36414,#36415); -#36414 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#36415 = VECTOR('',#36416,1.); -#36416 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36417 = PCURVE('',#28894,#36418); -#36418 = DEFINITIONAL_REPRESENTATION('',(#36419),#36422); -#36419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36420,#36421),.UNSPECIFIED., +#38802 = ORIENTED_EDGE('',*,*,#38803,.T.); +#38803 = EDGE_CURVE('',#38744,#31234,#38804,.T.); +#38804 = SURFACE_CURVE('',#38805,(#38809,#38815),.PCURVE_S1.); +#38805 = LINE('',#38806,#38807); +#38806 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#38807 = VECTOR('',#38808,1.); +#38808 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38809 = PCURVE('',#31286,#38810); +#38810 = DEFINITIONAL_REPRESENTATION('',(#38811),#38814); +#38811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38812,#38813),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36420 = CARTESIAN_POINT('',(1.,0.E+000)); -#36421 = CARTESIAN_POINT('',(1.,1.)); -#36422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36423 = PCURVE('',#28956,#36424); -#36424 = DEFINITIONAL_REPRESENTATION('',(#36425),#36429); -#36425 = LINE('',#36426,#36427); -#36426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36427 = VECTOR('',#36428,1.); -#36428 = DIRECTION('',(0.E+000,-1.)); -#36429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36430 = ADVANCED_FACE('',(#36431),#29728,.T.); -#36431 = FACE_BOUND('',#36432,.T.); -#36432 = EDGE_LOOP('',(#36433,#36434,#36455,#36492)); -#36433 = ORIENTED_EDGE('',*,*,#29698,.F.); -#36434 = ORIENTED_EDGE('',*,*,#36435,.F.); -#36435 = EDGE_CURVE('',#36436,#29637,#36438,.T.); -#36436 = VERTEX_POINT('',#36437); -#36437 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#36438 = SURFACE_CURVE('',#36439,(#36443,#36449),.PCURVE_S1.); -#36439 = LINE('',#36440,#36441); -#36440 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#36441 = VECTOR('',#36442,1.); -#36442 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36443 = PCURVE('',#29728,#36444); -#36444 = DEFINITIONAL_REPRESENTATION('',(#36445),#36448); -#36445 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36446,#36447),.UNSPECIFIED., +#38812 = CARTESIAN_POINT('',(1.,0.E+000)); +#38813 = CARTESIAN_POINT('',(1.,1.)); +#38814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38815 = PCURVE('',#31348,#38816); +#38816 = DEFINITIONAL_REPRESENTATION('',(#38817),#38821); +#38817 = LINE('',#38818,#38819); +#38818 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38819 = VECTOR('',#38820,1.); +#38820 = DIRECTION('',(0.E+000,-1.)); +#38821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38822 = ADVANCED_FACE('',(#38823),#32120,.T.); +#38823 = FACE_BOUND('',#38824,.T.); +#38824 = EDGE_LOOP('',(#38825,#38826,#38847,#38884)); +#38825 = ORIENTED_EDGE('',*,*,#32090,.F.); +#38826 = ORIENTED_EDGE('',*,*,#38827,.F.); +#38827 = EDGE_CURVE('',#38828,#32029,#38830,.T.); +#38828 = VERTEX_POINT('',#38829); +#38829 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#38830 = SURFACE_CURVE('',#38831,(#38835,#38841),.PCURVE_S1.); +#38831 = LINE('',#38832,#38833); +#38832 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#38833 = VECTOR('',#38834,1.); +#38834 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38835 = PCURVE('',#32120,#38836); +#38836 = DEFINITIONAL_REPRESENTATION('',(#38837),#38840); +#38837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38838,#38839),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36446 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36447 = CARTESIAN_POINT('',(0.E+000,1.)); -#36448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38838 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38839 = CARTESIAN_POINT('',(0.E+000,1.)); +#38840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36449 = PCURVE('',#29668,#36450); -#36450 = DEFINITIONAL_REPRESENTATION('',(#36451),#36454); -#36451 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36452,#36453),.UNSPECIFIED., +#38841 = PCURVE('',#32060,#38842); +#38842 = DEFINITIONAL_REPRESENTATION('',(#38843),#38846); +#38843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38844,#38845),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36452 = CARTESIAN_POINT('',(1.,0.E+000)); -#36453 = CARTESIAN_POINT('',(1.,1.)); -#36454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38844 = CARTESIAN_POINT('',(1.,0.E+000)); +#38845 = CARTESIAN_POINT('',(1.,1.)); +#38846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36455 = ORIENTED_EDGE('',*,*,#36456,.T.); -#36456 = EDGE_CURVE('',#36436,#36331,#36457,.T.); -#36457 = SURFACE_CURVE('',#36458,(#36470,#36477),.PCURVE_S1.); -#36458 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36459,#36460,#36461,#36462, - #36463,#36464,#36465,#36466,#36467,#36468,#36469),.UNSPECIFIED.,.F., +#38847 = ORIENTED_EDGE('',*,*,#38848,.T.); +#38848 = EDGE_CURVE('',#38828,#38723,#38849,.T.); +#38849 = SURFACE_CURVE('',#38850,(#38862,#38869),.PCURVE_S1.); +#38850 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38851,#38852,#38853,#38854, + #38855,#38856,#38857,#38858,#38859,#38860,#38861),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127892619465,0.251578513504, 0.372792819702,0.492777698608,0.613590069243,0.73780864928, 0.866179901539,1.),.UNSPECIFIED.); -#36459 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#36460 = CARTESIAN_POINT('',(0.304554451204,0.782,-0.212897646984)); -#36461 = CARTESIAN_POINT('',(0.300585822772,0.782,-0.208004381129)); -#36462 = CARTESIAN_POINT('',(0.293714185963,0.782,-0.201653214923)); -#36463 = CARTESIAN_POINT('',(0.286327078968,0.782,-0.196255597723)); -#36464 = CARTESIAN_POINT('',(0.278380540216,0.782,-0.19187042492)); -#36465 = CARTESIAN_POINT('',(0.269927917393,0.782,-0.18834656724)); -#36466 = CARTESIAN_POINT('',(0.260865372344,0.782,-0.186001572274)); -#36467 = CARTESIAN_POINT('',(0.251302410337,0.782,-0.184426815267)); -#36468 = CARTESIAN_POINT('',(0.244737251379,0.782,-0.184281467782)); -#36469 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); -#36470 = PCURVE('',#29728,#36471); -#36471 = DEFINITIONAL_REPRESENTATION('',(#36472),#36476); -#36472 = LINE('',#36473,#36474); -#36473 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36474 = VECTOR('',#36475,1.); -#36475 = DIRECTION('',(1.,0.E+000)); -#36476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36477 = PCURVE('',#36383,#36478); -#36478 = DEFINITIONAL_REPRESENTATION('',(#36479),#36491); -#36479 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36480,#36481,#36482,#36483, - #36484,#36485,#36486,#36487,#36488,#36489,#36490),.UNSPECIFIED.,.F., +#38851 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#38852 = CARTESIAN_POINT('',(0.304554451204,0.782,-0.212897646984)); +#38853 = CARTESIAN_POINT('',(0.300585822772,0.782,-0.208004381129)); +#38854 = CARTESIAN_POINT('',(0.293714185963,0.782,-0.201653214923)); +#38855 = CARTESIAN_POINT('',(0.286327078968,0.782,-0.196255597723)); +#38856 = CARTESIAN_POINT('',(0.278380540216,0.782,-0.19187042492)); +#38857 = CARTESIAN_POINT('',(0.269927917393,0.782,-0.18834656724)); +#38858 = CARTESIAN_POINT('',(0.260865372344,0.782,-0.186001572274)); +#38859 = CARTESIAN_POINT('',(0.251302410337,0.782,-0.184426815267)); +#38860 = CARTESIAN_POINT('',(0.244737251379,0.782,-0.184281467782)); +#38861 = CARTESIAN_POINT('',(0.241386453514,0.782,-0.184207283737)); +#38862 = PCURVE('',#32120,#38863); +#38863 = DEFINITIONAL_REPRESENTATION('',(#38864),#38868); +#38864 = LINE('',#38865,#38866); +#38865 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38866 = VECTOR('',#38867,1.); +#38867 = DIRECTION('',(1.,0.E+000)); +#38868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38869 = PCURVE('',#38775,#38870); +#38870 = DEFINITIONAL_REPRESENTATION('',(#38871),#38883); +#38871 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38872,#38873,#38874,#38875, + #38876,#38877,#38878,#38879,#38880,#38881,#38882),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.127892619465,0.251578513504, 0.372792819702,0.492777698608,0.613590069243,0.73780864928, 0.866179901539,1.),.UNSPECIFIED.); -#36480 = CARTESIAN_POINT('',(-1.165372501342E-002,0.120235889758)); -#36481 = CARTESIAN_POINT('',(-9.166181147792E-003,0.118218395184)); -#36482 = CARTESIAN_POINT('',(-4.272915292367E-003,0.114249766753)); -#36483 = CARTESIAN_POINT('',(2.078250913532E-003,0.107378129944)); -#36484 = CARTESIAN_POINT('',(7.475868113264E-003,9.999102294902E-002)); -#36485 = CARTESIAN_POINT('',(1.186104091575E-002,9.204448419669E-002)); -#36486 = CARTESIAN_POINT('',(1.53848985958E-002,8.359186137341E-002)); -#36487 = CARTESIAN_POINT('',(1.772989356243E-002,7.452931632487E-002)); -#36488 = CARTESIAN_POINT('',(1.930465056894E-002,6.496635431725E-002)); -#36489 = CARTESIAN_POINT('',(1.944999805443E-002,5.840119535968E-002)); -#36490 = CARTESIAN_POINT('',(1.95241820989E-002,5.505039749506E-002)); -#36491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36492 = ORIENTED_EDGE('',*,*,#36330,.T.); -#36493 = ADVANCED_FACE('',(#36494),#29668,.T.); -#36494 = FACE_BOUND('',#36495,.T.); -#36495 = EDGE_LOOP('',(#36496,#36497,#36518,#36555)); -#36496 = ORIENTED_EDGE('',*,*,#29636,.F.); -#36497 = ORIENTED_EDGE('',*,*,#36498,.F.); -#36498 = EDGE_CURVE('',#36499,#29543,#36501,.T.); -#36499 = VERTEX_POINT('',#36500); -#36500 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#36501 = SURFACE_CURVE('',#36502,(#36506,#36512),.PCURVE_S1.); -#36502 = LINE('',#36503,#36504); -#36503 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#36504 = VECTOR('',#36505,1.); -#36505 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36506 = PCURVE('',#29668,#36507); -#36507 = DEFINITIONAL_REPRESENTATION('',(#36508),#36511); -#36508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36509,#36510),.UNSPECIFIED., +#38872 = CARTESIAN_POINT('',(-1.165372501342E-002,0.120235889758)); +#38873 = CARTESIAN_POINT('',(-9.166181147792E-003,0.118218395184)); +#38874 = CARTESIAN_POINT('',(-4.272915292367E-003,0.114249766753)); +#38875 = CARTESIAN_POINT('',(2.078250913532E-003,0.107378129944)); +#38876 = CARTESIAN_POINT('',(7.475868113264E-003,9.999102294902E-002)); +#38877 = CARTESIAN_POINT('',(1.186104091575E-002,9.204448419669E-002)); +#38878 = CARTESIAN_POINT('',(1.53848985958E-002,8.359186137341E-002)); +#38879 = CARTESIAN_POINT('',(1.772989356243E-002,7.452931632487E-002)); +#38880 = CARTESIAN_POINT('',(1.930465056894E-002,6.496635431725E-002)); +#38881 = CARTESIAN_POINT('',(1.944999805443E-002,5.840119535968E-002)); +#38882 = CARTESIAN_POINT('',(1.95241820989E-002,5.505039749506E-002)); +#38883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38884 = ORIENTED_EDGE('',*,*,#38722,.T.); +#38885 = ADVANCED_FACE('',(#38886),#32060,.T.); +#38886 = FACE_BOUND('',#38887,.T.); +#38887 = EDGE_LOOP('',(#38888,#38889,#38910,#38947)); +#38888 = ORIENTED_EDGE('',*,*,#32028,.F.); +#38889 = ORIENTED_EDGE('',*,*,#38890,.F.); +#38890 = EDGE_CURVE('',#38891,#31935,#38893,.T.); +#38891 = VERTEX_POINT('',#38892); +#38892 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#38893 = SURFACE_CURVE('',#38894,(#38898,#38904),.PCURVE_S1.); +#38894 = LINE('',#38895,#38896); +#38895 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#38896 = VECTOR('',#38897,1.); +#38897 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38898 = PCURVE('',#32060,#38899); +#38899 = DEFINITIONAL_REPRESENTATION('',(#38900),#38903); +#38900 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38901,#38902),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36509 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36510 = CARTESIAN_POINT('',(0.E+000,1.)); -#36511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38902 = CARTESIAN_POINT('',(0.E+000,1.)); +#38903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36512 = PCURVE('',#29590,#36513); -#36513 = DEFINITIONAL_REPRESENTATION('',(#36514),#36517); -#36514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36515,#36516),.UNSPECIFIED., +#38904 = PCURVE('',#31982,#38905); +#38905 = DEFINITIONAL_REPRESENTATION('',(#38906),#38909); +#38906 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38907,#38908),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36515 = CARTESIAN_POINT('',(1.,0.E+000)); -#36516 = CARTESIAN_POINT('',(1.,1.)); -#36517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38907 = CARTESIAN_POINT('',(1.,0.E+000)); +#38908 = CARTESIAN_POINT('',(1.,1.)); +#38909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36518 = ORIENTED_EDGE('',*,*,#36519,.T.); -#36519 = EDGE_CURVE('',#36499,#36436,#36520,.T.); -#36520 = SURFACE_CURVE('',#36521,(#36533,#36540),.PCURVE_S1.); -#36521 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36522,#36523,#36524,#36525, - #36526,#36527,#36528,#36529,#36530,#36531,#36532),.UNSPECIFIED.,.F., +#38910 = ORIENTED_EDGE('',*,*,#38911,.T.); +#38911 = EDGE_CURVE('',#38891,#38828,#38912,.T.); +#38912 = SURFACE_CURVE('',#38913,(#38925,#38932),.PCURVE_S1.); +#38913 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38914,#38915,#38916,#38917, + #38918,#38919,#38920,#38921,#38922,#38923,#38924),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.132461622243,0.261649501035, 0.387546698416,0.510781629293,0.6326753606,0.754660354138, 0.876522779803,1.),.UNSPECIFIED.); -#36522 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#36523 = CARTESIAN_POINT('',(0.326167045263,0.782,-0.272730903454)); -#36524 = CARTESIAN_POINT('',(0.32605188473,0.782,-0.267102808703)); -#36525 = CARTESIAN_POINT('',(0.325108120345,0.782,-0.258808770662)); -#36526 = CARTESIAN_POINT('',(0.323553492815,0.782,-0.250816812181)); -#36527 = CARTESIAN_POINT('',(0.321472275533,0.782,-0.243103266612)); -#36528 = CARTESIAN_POINT('',(0.318660271687,0.782,-0.235711940929)); -#36529 = CARTESIAN_POINT('',(0.315249574225,0.782,-0.228618960549)); -#36530 = CARTESIAN_POINT('',(0.311315143396,0.782,-0.221750312623)); -#36531 = CARTESIAN_POINT('',(0.308159934047,0.782,-0.217516187599)); -#36532 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); -#36533 = PCURVE('',#29668,#36534); -#36534 = DEFINITIONAL_REPRESENTATION('',(#36535),#36539); -#36535 = LINE('',#36536,#36537); -#36536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36537 = VECTOR('',#36538,1.); -#36538 = DIRECTION('',(1.,0.E+000)); -#36539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36540 = PCURVE('',#36383,#36541); -#36541 = DEFINITIONAL_REPRESENTATION('',(#36542),#36554); -#36542 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36543,#36544,#36545,#36546, - #36547,#36548,#36549,#36550,#36551,#36552,#36553),.UNSPECIFIED.,.F., +#38914 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#38915 = CARTESIAN_POINT('',(0.326167045263,0.782,-0.272730903454)); +#38916 = CARTESIAN_POINT('',(0.32605188473,0.782,-0.267102808703)); +#38917 = CARTESIAN_POINT('',(0.325108120345,0.782,-0.258808770662)); +#38918 = CARTESIAN_POINT('',(0.323553492815,0.782,-0.250816812181)); +#38919 = CARTESIAN_POINT('',(0.321472275533,0.782,-0.243103266612)); +#38920 = CARTESIAN_POINT('',(0.318660271687,0.782,-0.235711940929)); +#38921 = CARTESIAN_POINT('',(0.315249574225,0.782,-0.228618960549)); +#38922 = CARTESIAN_POINT('',(0.311315143396,0.782,-0.221750312623)); +#38923 = CARTESIAN_POINT('',(0.308159934047,0.782,-0.217516187599)); +#38924 = CARTESIAN_POINT('',(0.306571945777,0.782,-0.21538519085)); +#38925 = PCURVE('',#32060,#38926); +#38926 = DEFINITIONAL_REPRESENTATION('',(#38927),#38931); +#38927 = LINE('',#38928,#38929); +#38928 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38929 = VECTOR('',#38930,1.); +#38930 = DIRECTION('',(1.,0.E+000)); +#38931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38932 = PCURVE('',#38775,#38933); +#38933 = DEFINITIONAL_REPRESENTATION('',(#38934),#38946); +#38934 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38935,#38936,#38937,#38938, + #38939,#38940,#38941,#38942,#38943,#38944,#38945),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.132461622243,0.261649501035, 0.387546698416,0.510781629293,0.6326753606,0.754660354138, 0.876522779803,1.),.UNSPECIFIED.); -#36543 = CARTESIAN_POINT('',(-7.184869419067E-002,0.139889289951)); -#36544 = CARTESIAN_POINT('',(-6.89994376173E-002,0.139830989243)); -#36545 = CARTESIAN_POINT('',(-6.337134286712E-002,0.139715828711)); -#36546 = CARTESIAN_POINT('',(-5.507730482594E-002,0.138772064326)); -#36547 = CARTESIAN_POINT('',(-4.708534634466E-002,0.137217436796)); -#36548 = CARTESIAN_POINT('',(-3.937180077629E-002,0.135136219514)); -#36549 = CARTESIAN_POINT('',(-3.198047509262E-002,0.132324215668)); -#36550 = CARTESIAN_POINT('',(-2.488749471233E-002,0.128913518206)); -#36551 = CARTESIAN_POINT('',(-1.8018846787E-002,0.124979087377)); -#36552 = CARTESIAN_POINT('',(-1.378472176315E-002,0.121823878027)); -#36553 = CARTESIAN_POINT('',(-1.165372501342E-002,0.120235889758)); -#36554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36555 = ORIENTED_EDGE('',*,*,#36435,.T.); -#36556 = ADVANCED_FACE('',(#36557),#29590,.T.); -#36557 = FACE_BOUND('',#36558,.T.); -#36558 = EDGE_LOOP('',(#36559,#36560,#36581,#36634)); -#36559 = ORIENTED_EDGE('',*,*,#29542,.F.); -#36560 = ORIENTED_EDGE('',*,*,#36561,.F.); -#36561 = EDGE_CURVE('',#36562,#29481,#36564,.T.); -#36562 = VERTEX_POINT('',#36563); -#36563 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#36564 = SURFACE_CURVE('',#36565,(#36569,#36575),.PCURVE_S1.); -#36565 = LINE('',#36566,#36567); -#36566 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#36567 = VECTOR('',#36568,1.); -#36568 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36569 = PCURVE('',#29590,#36570); -#36570 = DEFINITIONAL_REPRESENTATION('',(#36571),#36574); -#36571 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36572,#36573),.UNSPECIFIED., +#38935 = CARTESIAN_POINT('',(-7.184869419067E-002,0.139889289951)); +#38936 = CARTESIAN_POINT('',(-6.89994376173E-002,0.139830989243)); +#38937 = CARTESIAN_POINT('',(-6.337134286712E-002,0.139715828711)); +#38938 = CARTESIAN_POINT('',(-5.507730482594E-002,0.138772064326)); +#38939 = CARTESIAN_POINT('',(-4.708534634466E-002,0.137217436796)); +#38940 = CARTESIAN_POINT('',(-3.937180077629E-002,0.135136219514)); +#38941 = CARTESIAN_POINT('',(-3.198047509262E-002,0.132324215668)); +#38942 = CARTESIAN_POINT('',(-2.488749471233E-002,0.128913518206)); +#38943 = CARTESIAN_POINT('',(-1.8018846787E-002,0.124979087377)); +#38944 = CARTESIAN_POINT('',(-1.378472176315E-002,0.121823878027)); +#38945 = CARTESIAN_POINT('',(-1.165372501342E-002,0.120235889758)); +#38946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#38947 = ORIENTED_EDGE('',*,*,#38827,.T.); +#38948 = ADVANCED_FACE('',(#38949),#31982,.T.); +#38949 = FACE_BOUND('',#38950,.T.); +#38950 = EDGE_LOOP('',(#38951,#38952,#38973,#39026)); +#38951 = ORIENTED_EDGE('',*,*,#31934,.F.); +#38952 = ORIENTED_EDGE('',*,*,#38953,.F.); +#38953 = EDGE_CURVE('',#38954,#31873,#38956,.T.); +#38954 = VERTEX_POINT('',#38955); +#38955 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#38956 = SURFACE_CURVE('',#38957,(#38961,#38967),.PCURVE_S1.); +#38957 = LINE('',#38958,#38959); +#38958 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#38959 = VECTOR('',#38960,1.); +#38960 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#38961 = PCURVE('',#31982,#38962); +#38962 = DEFINITIONAL_REPRESENTATION('',(#38963),#38966); +#38963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38964,#38965),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36573 = CARTESIAN_POINT('',(0.E+000,1.)); -#36574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#38965 = CARTESIAN_POINT('',(0.E+000,1.)); +#38966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36575 = PCURVE('',#29512,#36576); -#36576 = DEFINITIONAL_REPRESENTATION('',(#36577),#36580); -#36577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36578,#36579),.UNSPECIFIED., +#38967 = PCURVE('',#31904,#38968); +#38968 = DEFINITIONAL_REPRESENTATION('',(#38969),#38972); +#38969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38970,#38971),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36578 = CARTESIAN_POINT('',(1.,0.E+000)); -#36579 = CARTESIAN_POINT('',(1.,1.)); -#36580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#38970 = CARTESIAN_POINT('',(1.,0.E+000)); +#38971 = CARTESIAN_POINT('',(1.,1.)); +#38972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36581 = ORIENTED_EDGE('',*,*,#36582,.T.); -#36582 = EDGE_CURVE('',#36562,#36499,#36583,.T.); -#36583 = SURFACE_CURVE('',#36584,(#36604,#36611),.PCURVE_S1.); -#36584 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36585,#36586,#36587,#36588, - #36589,#36590,#36591,#36592,#36593,#36594,#36595,#36596,#36597, - #36598,#36599,#36600,#36601,#36602,#36603),.UNSPECIFIED.,.F.,.F.,(4, +#38973 = ORIENTED_EDGE('',*,*,#38974,.T.); +#38974 = EDGE_CURVE('',#38954,#38891,#38975,.T.); +#38975 = SURFACE_CURVE('',#38976,(#38996,#39003),.PCURVE_S1.); +#38976 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38977,#38978,#38979,#38980, + #38981,#38982,#38983,#38984,#38985,#38986,#38987,#38988,#38989, + #38990,#38991,#38992,#38993,#38994,#38995),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.199741907572E-002, 0.122087954082,0.181375310787,0.239508008395,0.297835697897, 0.356879970653,0.417281825115,0.47964040908,0.542500067478, 0.604962419648,0.666991033078,0.73021624301,0.794172863251, 0.86045814315,0.928578179985,1.),.UNSPECIFIED.); -#36585 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#36586 = CARTESIAN_POINT('',(0.253446165278,0.782,-0.358653303007)); -#36587 = CARTESIAN_POINT('',(0.258552711472,0.782,-0.358519507446)); -#36588 = CARTESIAN_POINT('',(0.266077384107,0.782,-0.357420208445)); -#36589 = CARTESIAN_POINT('',(0.273272236932,0.782,-0.355554075516)); -#36590 = CARTESIAN_POINT('',(0.280193705771,0.782,-0.353040666526)); -#36591 = CARTESIAN_POINT('',(0.28675052298,0.782,-0.349708713553)); -#36592 = CARTESIAN_POINT('',(0.293009104401,0.782,-0.345674426003)); -#36593 = CARTESIAN_POINT('',(0.298944181976,0.782,-0.340904550372)); -#36594 = CARTESIAN_POINT('',(0.304522203003,0.782,-0.335489084369)); -#36595 = CARTESIAN_POINT('',(0.309581689909,0.782,-0.329477347787)); -#36596 = CARTESIAN_POINT('',(0.31411009582,0.782,-0.323065405188)); -#36597 = CARTESIAN_POINT('',(0.317808650414,0.782,-0.316124907125)); -#36598 = CARTESIAN_POINT('',(0.320919388672,0.782,-0.30883707119)); -#36599 = CARTESIAN_POINT('',(0.323265574073,0.782,-0.301082264907)); -#36600 = CARTESIAN_POINT('',(0.32504641068,0.782,-0.292970544817)); -#36601 = CARTESIAN_POINT('',(0.325998564893,0.782,-0.2844004959)); -#36602 = CARTESIAN_POINT('',(0.326148569164,0.782,-0.278566287547)); -#36603 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); -#36604 = PCURVE('',#29590,#36605); -#36605 = DEFINITIONAL_REPRESENTATION('',(#36606),#36610); -#36606 = LINE('',#36607,#36608); -#36607 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36608 = VECTOR('',#36609,1.); -#36609 = DIRECTION('',(1.,0.E+000)); -#36610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36611 = PCURVE('',#36383,#36612); -#36612 = DEFINITIONAL_REPRESENTATION('',(#36613),#36633); -#36613 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36614,#36615,#36616,#36617, - #36618,#36619,#36620,#36621,#36622,#36623,#36624,#36625,#36626, - #36627,#36628,#36629,#36630,#36631,#36632),.UNSPECIFIED.,.F.,.F.,(4, +#38977 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#38978 = CARTESIAN_POINT('',(0.253446165278,0.782,-0.358653303007)); +#38979 = CARTESIAN_POINT('',(0.258552711472,0.782,-0.358519507446)); +#38980 = CARTESIAN_POINT('',(0.266077384107,0.782,-0.357420208445)); +#38981 = CARTESIAN_POINT('',(0.273272236932,0.782,-0.355554075516)); +#38982 = CARTESIAN_POINT('',(0.280193705771,0.782,-0.353040666526)); +#38983 = CARTESIAN_POINT('',(0.28675052298,0.782,-0.349708713553)); +#38984 = CARTESIAN_POINT('',(0.293009104401,0.782,-0.345674426003)); +#38985 = CARTESIAN_POINT('',(0.298944181976,0.782,-0.340904550372)); +#38986 = CARTESIAN_POINT('',(0.304522203003,0.782,-0.335489084369)); +#38987 = CARTESIAN_POINT('',(0.309581689909,0.782,-0.329477347787)); +#38988 = CARTESIAN_POINT('',(0.31411009582,0.782,-0.323065405188)); +#38989 = CARTESIAN_POINT('',(0.317808650414,0.782,-0.316124907125)); +#38990 = CARTESIAN_POINT('',(0.320919388672,0.782,-0.30883707119)); +#38991 = CARTESIAN_POINT('',(0.323265574073,0.782,-0.301082264907)); +#38992 = CARTESIAN_POINT('',(0.32504641068,0.782,-0.292970544817)); +#38993 = CARTESIAN_POINT('',(0.325998564893,0.782,-0.2844004959)); +#38994 = CARTESIAN_POINT('',(0.326148569164,0.782,-0.278566287547)); +#38995 = CARTESIAN_POINT('',(0.32622534597,0.782,-0.275580160027)); +#38996 = PCURVE('',#31982,#38997); +#38997 = DEFINITIONAL_REPRESENTATION('',(#38998),#39002); +#38998 = LINE('',#38999,#39000); +#38999 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39000 = VECTOR('',#39001,1.); +#39001 = DIRECTION('',(1.,0.E+000)); +#39002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39003 = PCURVE('',#38775,#39004); +#39004 = DEFINITIONAL_REPRESENTATION('',(#39005),#39025); +#39005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39006,#39007,#39008,#39009, + #39010,#39011,#39012,#39013,#39014,#39015,#39016,#39017,#39018, + #39019,#39020,#39021,#39022,#39023,#39024),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.199741907572E-002, 0.122087954082,0.181375310787,0.239508008395,0.297835697897, 0.356879970653,0.417281825115,0.47964040908,0.542500067478, 0.604962419648,0.666991033078,0.73021624301,0.794172863251, 0.86045814315,0.928578179985,1.),.UNSPECIFIED.); -#36614 = CARTESIAN_POINT('',(-0.154989779824,6.451695675028E-002)); -#36615 = CARTESIAN_POINT('',(-0.154921837171,6.711010925891E-002)); -#36616 = CARTESIAN_POINT('',(-0.15478804161,7.221665545263E-002)); -#36617 = CARTESIAN_POINT('',(-0.153688742609,7.974132808741E-002)); -#36618 = CARTESIAN_POINT('',(-0.15182260968,8.693618091248E-002)); -#36619 = CARTESIAN_POINT('',(-0.14930920069,9.385764975162E-002)); -#36620 = CARTESIAN_POINT('',(-0.145977247717,0.100414466961)); -#36621 = CARTESIAN_POINT('',(-0.141942960167,0.106673048382)); -#36622 = CARTESIAN_POINT('',(-0.137173084536,0.112608125956)); -#36623 = CARTESIAN_POINT('',(-0.131757618533,0.118186146983)); -#36624 = CARTESIAN_POINT('',(-0.12574588195,0.123245633889)); -#36625 = CARTESIAN_POINT('',(-0.119333939351,0.127774039801)); -#36626 = CARTESIAN_POINT('',(-0.112393441289,0.131472594395)); -#36627 = CARTESIAN_POINT('',(-0.105105605353,0.134583332652)); -#36628 = CARTESIAN_POINT('',(-9.735079907105E-002,0.136929518053)); -#36629 = CARTESIAN_POINT('',(-8.923907898116E-002,0.138710354661)); -#36630 = CARTESIAN_POINT('',(-8.066903006414E-002,0.139662508874)); -#36631 = CARTESIAN_POINT('',(-7.483482171077E-002,0.139812513145)); -#36632 = CARTESIAN_POINT('',(-7.184869419067E-002,0.139889289951)); -#36633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36634 = ORIENTED_EDGE('',*,*,#36498,.T.); -#36635 = ADVANCED_FACE('',(#36636),#29512,.T.); -#36636 = FACE_BOUND('',#36637,.T.); -#36637 = EDGE_LOOP('',(#36638,#36639,#36661,#36698)); -#36638 = ORIENTED_EDGE('',*,*,#29480,.F.); -#36639 = ORIENTED_EDGE('',*,*,#36640,.F.); -#36640 = EDGE_CURVE('',#36641,#29453,#36643,.T.); -#36641 = VERTEX_POINT('',#36642); -#36642 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); -#36643 = SURFACE_CURVE('',#36644,(#36648,#36654),.PCURVE_S1.); -#36644 = LINE('',#36645,#36646); -#36645 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); -#36646 = VECTOR('',#36647,1.); -#36647 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36648 = PCURVE('',#29512,#36649); -#36649 = DEFINITIONAL_REPRESENTATION('',(#36650),#36653); -#36650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36651,#36652),.UNSPECIFIED., +#39006 = CARTESIAN_POINT('',(-0.154989779824,6.451695675028E-002)); +#39007 = CARTESIAN_POINT('',(-0.154921837171,6.711010925891E-002)); +#39008 = CARTESIAN_POINT('',(-0.15478804161,7.221665545263E-002)); +#39009 = CARTESIAN_POINT('',(-0.153688742609,7.974132808741E-002)); +#39010 = CARTESIAN_POINT('',(-0.15182260968,8.693618091248E-002)); +#39011 = CARTESIAN_POINT('',(-0.14930920069,9.385764975162E-002)); +#39012 = CARTESIAN_POINT('',(-0.145977247717,0.100414466961)); +#39013 = CARTESIAN_POINT('',(-0.141942960167,0.106673048382)); +#39014 = CARTESIAN_POINT('',(-0.137173084536,0.112608125956)); +#39015 = CARTESIAN_POINT('',(-0.131757618533,0.118186146983)); +#39016 = CARTESIAN_POINT('',(-0.12574588195,0.123245633889)); +#39017 = CARTESIAN_POINT('',(-0.119333939351,0.127774039801)); +#39018 = CARTESIAN_POINT('',(-0.112393441289,0.131472594395)); +#39019 = CARTESIAN_POINT('',(-0.105105605353,0.134583332652)); +#39020 = CARTESIAN_POINT('',(-9.735079907105E-002,0.136929518053)); +#39021 = CARTESIAN_POINT('',(-8.923907898116E-002,0.138710354661)); +#39022 = CARTESIAN_POINT('',(-8.066903006414E-002,0.139662508874)); +#39023 = CARTESIAN_POINT('',(-7.483482171077E-002,0.139812513145)); +#39024 = CARTESIAN_POINT('',(-7.184869419067E-002,0.139889289951)); +#39025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39026 = ORIENTED_EDGE('',*,*,#38890,.T.); +#39027 = ADVANCED_FACE('',(#39028),#31904,.T.); +#39028 = FACE_BOUND('',#39029,.T.); +#39029 = EDGE_LOOP('',(#39030,#39031,#39053,#39090)); +#39030 = ORIENTED_EDGE('',*,*,#31872,.F.); +#39031 = ORIENTED_EDGE('',*,*,#39032,.F.); +#39032 = EDGE_CURVE('',#39033,#31845,#39035,.T.); +#39033 = VERTEX_POINT('',#39034); +#39034 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); +#39035 = SURFACE_CURVE('',#39036,(#39040,#39046),.PCURVE_S1.); +#39036 = LINE('',#39037,#39038); +#39037 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); +#39038 = VECTOR('',#39039,1.); +#39039 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39040 = PCURVE('',#31904,#39041); +#39041 = DEFINITIONAL_REPRESENTATION('',(#39042),#39045); +#39042 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39043,#39044),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36652 = CARTESIAN_POINT('',(0.E+000,1.)); -#36653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39044 = CARTESIAN_POINT('',(0.E+000,1.)); +#39045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36654 = PCURVE('',#29468,#36655); -#36655 = DEFINITIONAL_REPRESENTATION('',(#36656),#36660); -#36656 = LINE('',#36657,#36658); -#36657 = CARTESIAN_POINT('',(-6.779455997199E-002,0.E+000)); -#36658 = VECTOR('',#36659,1.); -#36659 = DIRECTION('',(0.E+000,-1.)); -#36660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39046 = PCURVE('',#31860,#39047); +#39047 = DEFINITIONAL_REPRESENTATION('',(#39048),#39052); +#39048 = LINE('',#39049,#39050); +#39049 = CARTESIAN_POINT('',(-6.779455997199E-002,0.E+000)); +#39050 = VECTOR('',#39051,1.); +#39051 = DIRECTION('',(0.E+000,-1.)); +#39052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36661 = ORIENTED_EDGE('',*,*,#36662,.T.); -#36662 = EDGE_CURVE('',#36641,#36562,#36663,.T.); -#36663 = SURFACE_CURVE('',#36664,(#36676,#36683),.PCURVE_S1.); -#36664 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36665,#36666,#36667,#36668, - #36669,#36670,#36671,#36672,#36673,#36674,#36675),.UNSPECIFIED.,.F., +#39053 = ORIENTED_EDGE('',*,*,#39054,.T.); +#39054 = EDGE_CURVE('',#39033,#38954,#39055,.T.); +#39055 = SURFACE_CURVE('',#39056,(#39068,#39075),.PCURVE_S1.); +#39056 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39057,#39058,#39059,#39060, + #39061,#39062,#39063,#39064,#39065,#39066,#39067),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.13672940186,0.268514916791, 0.395529404685,0.519999953566,0.640496476841,0.761236101763, 0.880106717176,1.),.UNSPECIFIED.); -#36665 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); -#36666 = CARTESIAN_POINT('',(0.206880509894,0.782,-0.342952208043)); -#36667 = CARTESIAN_POINT('',(0.210448481829,0.782,-0.345629664193)); -#36668 = CARTESIAN_POINT('',(0.21601387851,0.782,-0.349135440098)); -#36669 = CARTESIAN_POINT('',(0.221658854525,0.782,-0.352090575417)); -#36670 = CARTESIAN_POINT('',(0.227350549029,0.782,-0.354510582745)); -#36671 = CARTESIAN_POINT('',(0.233134173604,0.782,-0.356395764197)); -#36672 = CARTESIAN_POINT('',(0.238974827182,0.782,-0.357705501218)); -#36673 = CARTESIAN_POINT('',(0.244892396205,0.782,-0.358590698564)); -#36674 = CARTESIAN_POINT('',(0.248860475257,0.782,-0.358677605881)); -#36675 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); -#36676 = PCURVE('',#29512,#36677); -#36677 = DEFINITIONAL_REPRESENTATION('',(#36678),#36682); -#36678 = LINE('',#36679,#36680); -#36679 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36680 = VECTOR('',#36681,1.); -#36681 = DIRECTION('',(1.,0.E+000)); -#36682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36683 = PCURVE('',#36383,#36684); -#36684 = DEFINITIONAL_REPRESENTATION('',(#36685),#36697); -#36685 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#36686,#36687,#36688,#36689, - #36690,#36691,#36692,#36693,#36694,#36695,#36696),.UNSPECIFIED.,.F., +#39057 = CARTESIAN_POINT('',(0.205063677242,0.782,-0.341588831355)); +#39058 = CARTESIAN_POINT('',(0.206880509894,0.782,-0.342952208043)); +#39059 = CARTESIAN_POINT('',(0.210448481829,0.782,-0.345629664193)); +#39060 = CARTESIAN_POINT('',(0.21601387851,0.782,-0.349135440098)); +#39061 = CARTESIAN_POINT('',(0.221658854525,0.782,-0.352090575417)); +#39062 = CARTESIAN_POINT('',(0.227350549029,0.782,-0.354510582745)); +#39063 = CARTESIAN_POINT('',(0.233134173604,0.782,-0.356395764197)); +#39064 = CARTESIAN_POINT('',(0.238974827182,0.782,-0.357705501218)); +#39065 = CARTESIAN_POINT('',(0.244892396205,0.782,-0.358590698564)); +#39066 = CARTESIAN_POINT('',(0.248860475257,0.782,-0.358677605881)); +#39067 = CARTESIAN_POINT('',(0.25085301277,0.782,-0.35872124566)); +#39068 = PCURVE('',#31904,#39069); +#39069 = DEFINITIONAL_REPRESENTATION('',(#39070),#39074); +#39070 = LINE('',#39071,#39072); +#39071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39072 = VECTOR('',#39073,1.); +#39073 = DIRECTION('',(1.,0.E+000)); +#39074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39075 = PCURVE('',#38775,#39076); +#39076 = DEFINITIONAL_REPRESENTATION('',(#39077),#39089); +#39077 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39078,#39079,#39080,#39081, + #39082,#39083,#39084,#39085,#39086,#39087,#39088),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.13672940186,0.268514916791, 0.395529404685,0.519999953566,0.640496476841,0.761236101763, 0.880106717176,1.),.UNSPECIFIED.); -#36686 = CARTESIAN_POINT('',(-0.137857365519,1.872762122229E-002)); -#36687 = CARTESIAN_POINT('',(-0.139220742207,2.054445387484E-002)); -#36688 = CARTESIAN_POINT('',(-0.141898198357,2.411242580981E-002)); -#36689 = CARTESIAN_POINT('',(-0.145403974262,2.967782249085E-002)); -#36690 = CARTESIAN_POINT('',(-0.148359109581,3.532279850522E-002)); -#36691 = CARTESIAN_POINT('',(-0.150779116909,4.101449300996E-002)); -#36692 = CARTESIAN_POINT('',(-0.15266429836,4.679811758497E-002)); -#36693 = CARTESIAN_POINT('',(-0.153974035381,5.263877116231E-002)); -#36694 = CARTESIAN_POINT('',(-0.154859232727,5.855634018583E-002)); -#36695 = CARTESIAN_POINT('',(-0.154946140045,6.25244192373E-002)); -#36696 = CARTESIAN_POINT('',(-0.154989779824,6.451695675028E-002)); -#36697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36698 = ORIENTED_EDGE('',*,*,#36561,.T.); -#36699 = ADVANCED_FACE('',(#36700),#29468,.T.); -#36700 = FACE_BOUND('',#36701,.T.); -#36701 = EDGE_LOOP('',(#36702,#36703,#36726,#36747)); -#36702 = ORIENTED_EDGE('',*,*,#29452,.F.); -#36703 = ORIENTED_EDGE('',*,*,#36704,.F.); -#36704 = EDGE_CURVE('',#36705,#29425,#36707,.T.); -#36705 = VERTEX_POINT('',#36706); -#36706 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); -#36707 = SURFACE_CURVE('',#36708,(#36712,#36719),.PCURVE_S1.); -#36708 = LINE('',#36709,#36710); -#36709 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); -#36710 = VECTOR('',#36711,1.); -#36711 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36712 = PCURVE('',#29468,#36713); -#36713 = DEFINITIONAL_REPRESENTATION('',(#36714),#36718); -#36714 = LINE('',#36715,#36716); -#36715 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36716 = VECTOR('',#36717,1.); -#36717 = DIRECTION('',(0.E+000,-1.)); -#36718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36719 = PCURVE('',#29440,#36720); -#36720 = DEFINITIONAL_REPRESENTATION('',(#36721),#36725); -#36721 = LINE('',#36722,#36723); -#36722 = CARTESIAN_POINT('',(-9.492283601027E-002,0.E+000)); -#36723 = VECTOR('',#36724,1.); -#36724 = DIRECTION('',(0.E+000,-1.)); -#36725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36726 = ORIENTED_EDGE('',*,*,#36727,.T.); -#36727 = EDGE_CURVE('',#36705,#36641,#36728,.T.); -#36728 = SURFACE_CURVE('',#36729,(#36733,#36740),.PCURVE_S1.); -#36729 = LINE('',#36730,#36731); -#36730 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); -#36731 = VECTOR('',#36732,1.); -#36732 = DIRECTION('',(-0.192758352188,0.E+000,0.9812462574)); -#36733 = PCURVE('',#29468,#36734); -#36734 = DEFINITIONAL_REPRESENTATION('',(#36735),#36739); -#36735 = LINE('',#36736,#36737); -#36736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36737 = VECTOR('',#36738,1.); -#36738 = DIRECTION('',(-1.,0.E+000)); -#36739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36740 = PCURVE('',#36383,#36741); -#36741 = DEFINITIONAL_REPRESENTATION('',(#36742),#36746); -#36742 = LINE('',#36743,#36744); -#36743 = CARTESIAN_POINT('',(-0.204380523764,3.179558888983E-002)); -#36744 = VECTOR('',#36745,1.); -#36745 = DIRECTION('',(0.9812462574,-0.192758352188)); -#36746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36747 = ORIENTED_EDGE('',*,*,#36640,.T.); -#36748 = ADVANCED_FACE('',(#36749),#29440,.T.); -#36749 = FACE_BOUND('',#36750,.T.); -#36750 = EDGE_LOOP('',(#36751,#36752,#36775,#36796)); -#36751 = ORIENTED_EDGE('',*,*,#29424,.F.); -#36752 = ORIENTED_EDGE('',*,*,#36753,.F.); -#36753 = EDGE_CURVE('',#36754,#29397,#36756,.T.); -#36754 = VERTEX_POINT('',#36755); -#36755 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); -#36756 = SURFACE_CURVE('',#36757,(#36761,#36768),.PCURVE_S1.); -#36757 = LINE('',#36758,#36759); -#36758 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); -#36759 = VECTOR('',#36760,1.); -#36760 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36761 = PCURVE('',#29440,#36762); -#36762 = DEFINITIONAL_REPRESENTATION('',(#36763),#36767); -#36763 = LINE('',#36764,#36765); -#36764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36765 = VECTOR('',#36766,1.); -#36766 = DIRECTION('',(0.E+000,-1.)); -#36767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36768 = PCURVE('',#29412,#36769); -#36769 = DEFINITIONAL_REPRESENTATION('',(#36770),#36774); -#36770 = LINE('',#36771,#36772); -#36771 = CARTESIAN_POINT('',(-3.292716262687E-002,0.E+000)); -#36772 = VECTOR('',#36773,1.); -#36773 = DIRECTION('',(0.E+000,-1.)); -#36774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36775 = ORIENTED_EDGE('',*,*,#36776,.T.); -#36776 = EDGE_CURVE('',#36754,#36705,#36777,.T.); -#36777 = SURFACE_CURVE('',#36778,(#36782,#36789),.PCURVE_S1.); -#36778 = LINE('',#36779,#36780); -#36779 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); -#36780 = VECTOR('',#36781,1.); -#36781 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#36782 = PCURVE('',#29440,#36783); -#36783 = DEFINITIONAL_REPRESENTATION('',(#36784),#36788); -#36784 = LINE('',#36785,#36786); -#36785 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36786 = VECTOR('',#36787,1.); -#36787 = DIRECTION('',(-1.,0.E+000)); -#36788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36789 = PCURVE('',#36383,#36790); -#36790 = DEFINITIONAL_REPRESENTATION('',(#36791),#36795); -#36791 = LINE('',#36792,#36793); -#36792 = CARTESIAN_POINT('',(-0.204380523764,0.1267184249)); -#36793 = VECTOR('',#36794,1.); -#36794 = DIRECTION('',(0.E+000,-1.)); -#36795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36796 = ORIENTED_EDGE('',*,*,#36704,.T.); -#36797 = ADVANCED_FACE('',(#36798),#29412,.T.); -#36798 = FACE_BOUND('',#36799,.T.); -#36799 = EDGE_LOOP('',(#36800,#36801,#36824,#36845)); -#36800 = ORIENTED_EDGE('',*,*,#29396,.F.); -#36801 = ORIENTED_EDGE('',*,*,#36802,.F.); -#36802 = EDGE_CURVE('',#36803,#29369,#36805,.T.); -#36803 = VERTEX_POINT('',#36804); -#36804 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); -#36805 = SURFACE_CURVE('',#36806,(#36810,#36817),.PCURVE_S1.); -#36806 = LINE('',#36807,#36808); -#36807 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); -#36808 = VECTOR('',#36809,1.); -#36809 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36810 = PCURVE('',#29412,#36811); -#36811 = DEFINITIONAL_REPRESENTATION('',(#36812),#36816); -#36812 = LINE('',#36813,#36814); -#36813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36814 = VECTOR('',#36815,1.); -#36815 = DIRECTION('',(0.E+000,-1.)); -#36816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39078 = CARTESIAN_POINT('',(-0.137857365519,1.872762122229E-002)); +#39079 = CARTESIAN_POINT('',(-0.139220742207,2.054445387484E-002)); +#39080 = CARTESIAN_POINT('',(-0.141898198357,2.411242580981E-002)); +#39081 = CARTESIAN_POINT('',(-0.145403974262,2.967782249085E-002)); +#39082 = CARTESIAN_POINT('',(-0.148359109581,3.532279850522E-002)); +#39083 = CARTESIAN_POINT('',(-0.150779116909,4.101449300996E-002)); +#39084 = CARTESIAN_POINT('',(-0.15266429836,4.679811758497E-002)); +#39085 = CARTESIAN_POINT('',(-0.153974035381,5.263877116231E-002)); +#39086 = CARTESIAN_POINT('',(-0.154859232727,5.855634018583E-002)); +#39087 = CARTESIAN_POINT('',(-0.154946140045,6.25244192373E-002)); +#39088 = CARTESIAN_POINT('',(-0.154989779824,6.451695675028E-002)); +#39089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39090 = ORIENTED_EDGE('',*,*,#38953,.T.); +#39091 = ADVANCED_FACE('',(#39092),#31860,.T.); +#39092 = FACE_BOUND('',#39093,.T.); +#39093 = EDGE_LOOP('',(#39094,#39095,#39118,#39139)); +#39094 = ORIENTED_EDGE('',*,*,#31844,.F.); +#39095 = ORIENTED_EDGE('',*,*,#39096,.F.); +#39096 = EDGE_CURVE('',#39097,#31817,#39099,.T.); +#39097 = VERTEX_POINT('',#39098); +#39098 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); +#39099 = SURFACE_CURVE('',#39100,(#39104,#39111),.PCURVE_S1.); +#39100 = LINE('',#39101,#39102); +#39101 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); +#39102 = VECTOR('',#39103,1.); +#39103 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39104 = PCURVE('',#31860,#39105); +#39105 = DEFINITIONAL_REPRESENTATION('',(#39106),#39110); +#39106 = LINE('',#39107,#39108); +#39107 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39108 = VECTOR('',#39109,1.); +#39109 = DIRECTION('',(0.E+000,-1.)); +#39110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36817 = PCURVE('',#29384,#36818); -#36818 = DEFINITIONAL_REPRESENTATION('',(#36819),#36823); -#36819 = LINE('',#36820,#36821); -#36820 = CARTESIAN_POINT('',(-0.121830501719,0.E+000)); -#36821 = VECTOR('',#36822,1.); -#36822 = DIRECTION('',(0.E+000,-1.)); -#36823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36824 = ORIENTED_EDGE('',*,*,#36825,.T.); -#36825 = EDGE_CURVE('',#36803,#36754,#36826,.T.); -#36826 = SURFACE_CURVE('',#36827,(#36831,#36838),.PCURVE_S1.); -#36827 = LINE('',#36828,#36829); -#36828 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); -#36829 = VECTOR('',#36830,1.); -#36830 = DIRECTION('',(0.E+000,0.E+000,1.)); -#36831 = PCURVE('',#29412,#36832); -#36832 = DEFINITIONAL_REPRESENTATION('',(#36833),#36837); -#36833 = LINE('',#36834,#36835); -#36834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36835 = VECTOR('',#36836,1.); -#36836 = DIRECTION('',(-1.,0.E+000)); -#36837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36838 = PCURVE('',#36383,#36839); -#36839 = DEFINITIONAL_REPRESENTATION('',(#36840),#36844); -#36840 = LINE('',#36841,#36842); -#36841 = CARTESIAN_POINT('',(-0.237307686391,0.1267184249)); -#36842 = VECTOR('',#36843,1.); -#36843 = DIRECTION('',(1.,3.413729340079E-027)); -#36844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36845 = ORIENTED_EDGE('',*,*,#36753,.T.); -#36846 = ADVANCED_FACE('',(#36847),#29384,.T.); -#36847 = FACE_BOUND('',#36848,.T.); -#36848 = EDGE_LOOP('',(#36849,#36850,#36873,#36894)); -#36849 = ORIENTED_EDGE('',*,*,#29368,.F.); -#36850 = ORIENTED_EDGE('',*,*,#36851,.F.); -#36851 = EDGE_CURVE('',#36852,#29341,#36854,.T.); -#36852 = VERTEX_POINT('',#36853); -#36853 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); -#36854 = SURFACE_CURVE('',#36855,(#36859,#36866),.PCURVE_S1.); -#36855 = LINE('',#36856,#36857); -#36856 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); -#36857 = VECTOR('',#36858,1.); -#36858 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36859 = PCURVE('',#29384,#36860); -#36860 = DEFINITIONAL_REPRESENTATION('',(#36861),#36865); -#36861 = LINE('',#36862,#36863); -#36862 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36863 = VECTOR('',#36864,1.); -#36864 = DIRECTION('',(0.E+000,-1.)); -#36865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36866 = PCURVE('',#29356,#36867); -#36867 = DEFINITIONAL_REPRESENTATION('',(#36868),#36872); -#36868 = LINE('',#36869,#36870); -#36869 = CARTESIAN_POINT('',(-0.134316995809,0.E+000)); -#36870 = VECTOR('',#36871,1.); -#36871 = DIRECTION('',(0.E+000,-1.)); -#36872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36873 = ORIENTED_EDGE('',*,*,#36874,.T.); -#36874 = EDGE_CURVE('',#36852,#36803,#36875,.T.); -#36875 = SURFACE_CURVE('',#36876,(#36880,#36887),.PCURVE_S1.); -#36876 = LINE('',#36877,#36878); -#36877 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); -#36878 = VECTOR('',#36879,1.); -#36879 = DIRECTION('',(1.,0.E+000,0.E+000)); -#36880 = PCURVE('',#29384,#36881); -#36881 = DEFINITIONAL_REPRESENTATION('',(#36882),#36886); -#36882 = LINE('',#36883,#36884); -#36883 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36884 = VECTOR('',#36885,1.); -#36885 = DIRECTION('',(-1.,0.E+000)); -#36886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36887 = PCURVE('',#36383,#36888); -#36888 = DEFINITIONAL_REPRESENTATION('',(#36889),#36893); -#36889 = LINE('',#36890,#36891); -#36890 = CARTESIAN_POINT('',(-0.237307686391,4.887923180685E-003)); -#36891 = VECTOR('',#36892,1.); -#36892 = DIRECTION('',(0.E+000,1.)); -#36893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36894 = ORIENTED_EDGE('',*,*,#36802,.T.); -#36895 = ADVANCED_FACE('',(#36896),#29356,.T.); -#36896 = FACE_BOUND('',#36897,.T.); -#36897 = EDGE_LOOP('',(#36898,#36899,#36922,#36943)); -#36898 = ORIENTED_EDGE('',*,*,#29340,.F.); -#36899 = ORIENTED_EDGE('',*,*,#36900,.F.); -#36900 = EDGE_CURVE('',#36901,#29313,#36903,.T.); -#36901 = VERTEX_POINT('',#36902); -#36902 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); -#36903 = SURFACE_CURVE('',#36904,(#36908,#36915),.PCURVE_S1.); -#36904 = LINE('',#36905,#36906); -#36905 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); -#36906 = VECTOR('',#36907,1.); -#36907 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36908 = PCURVE('',#29356,#36909); -#36909 = DEFINITIONAL_REPRESENTATION('',(#36910),#36914); -#36910 = LINE('',#36911,#36912); -#36911 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36912 = VECTOR('',#36913,1.); -#36913 = DIRECTION('',(0.E+000,-1.)); -#36914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36915 = PCURVE('',#29328,#36916); -#36916 = DEFINITIONAL_REPRESENTATION('',(#36917),#36921); -#36917 = LINE('',#36918,#36919); -#36918 = CARTESIAN_POINT('',(-3.309138889565E-002,0.E+000)); -#36919 = VECTOR('',#36920,1.); -#36920 = DIRECTION('',(0.E+000,-1.)); -#36921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36922 = ORIENTED_EDGE('',*,*,#36923,.T.); -#36923 = EDGE_CURVE('',#36901,#36852,#36924,.T.); -#36924 = SURFACE_CURVE('',#36925,(#36929,#36936),.PCURVE_S1.); -#36925 = LINE('',#36926,#36927); -#36926 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); -#36927 = VECTOR('',#36928,1.); -#36928 = DIRECTION('',(0.196116135138,0.E+000,-0.980580675691)); -#36929 = PCURVE('',#29356,#36930); -#36930 = DEFINITIONAL_REPRESENTATION('',(#36931),#36935); -#36931 = LINE('',#36932,#36933); -#36932 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36933 = VECTOR('',#36934,1.); -#36934 = DIRECTION('',(-1.,0.E+000)); -#36935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36936 = PCURVE('',#36383,#36937); -#36937 = DEFINITIONAL_REPRESENTATION('',(#36938),#36942); -#36938 = LINE('',#36939,#36940); -#36939 = CARTESIAN_POINT('',(-0.105599035883,-2.145380692081E-002)); -#36940 = VECTOR('',#36941,1.); -#36941 = DIRECTION('',(-0.980580675691,0.196116135138)); -#36942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36943 = ORIENTED_EDGE('',*,*,#36851,.T.); -#36944 = ADVANCED_FACE('',(#36945),#29328,.T.); -#36945 = FACE_BOUND('',#36946,.T.); -#36946 = EDGE_LOOP('',(#36947,#36948,#36970,#36991)); -#36947 = ORIENTED_EDGE('',*,*,#29312,.F.); -#36948 = ORIENTED_EDGE('',*,*,#36949,.F.); -#36949 = EDGE_CURVE('',#36950,#29251,#36952,.T.); -#36950 = VERTEX_POINT('',#36951); -#36951 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#36952 = SURFACE_CURVE('',#36953,(#36957,#36964),.PCURVE_S1.); -#36953 = LINE('',#36954,#36955); -#36954 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#36955 = VECTOR('',#36956,1.); -#36956 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#36957 = PCURVE('',#29328,#36958); -#36958 = DEFINITIONAL_REPRESENTATION('',(#36959),#36963); -#36959 = LINE('',#36960,#36961); -#36960 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36961 = VECTOR('',#36962,1.); -#36962 = DIRECTION('',(0.E+000,-1.)); -#36963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36964 = PCURVE('',#29282,#36965); -#36965 = DEFINITIONAL_REPRESENTATION('',(#36966),#36969); -#36966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#36967,#36968),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#36967 = CARTESIAN_POINT('',(1.,0.E+000)); -#36968 = CARTESIAN_POINT('',(1.,1.)); -#36969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36970 = ORIENTED_EDGE('',*,*,#36971,.T.); -#36971 = EDGE_CURVE('',#36950,#36901,#36972,.T.); -#36972 = SURFACE_CURVE('',#36973,(#36977,#36984),.PCURVE_S1.); -#36973 = LINE('',#36974,#36975); -#36974 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#36975 = VECTOR('',#36976,1.); -#36976 = DIRECTION('',(-0.99503719021,0.E+000,-9.9503719021E-002)); -#36977 = PCURVE('',#29328,#36978); -#36978 = DEFINITIONAL_REPRESENTATION('',(#36979),#36983); -#36979 = LINE('',#36980,#36981); -#36980 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#36981 = VECTOR('',#36982,1.); -#36982 = DIRECTION('',(-1.,0.E+000)); -#36983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#36984 = PCURVE('',#36383,#36985); -#36985 = DEFINITIONAL_REPRESENTATION('',(#36986),#36990); -#36986 = LINE('',#36987,#36988); -#36987 = CARTESIAN_POINT('',(-0.102306319621,1.147335570606E-002)); -#36988 = VECTOR('',#36989,1.); -#36989 = DIRECTION('',(-9.9503719021E-002,-0.99503719021)); -#36990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39111 = PCURVE('',#31832,#39112); +#39112 = DEFINITIONAL_REPRESENTATION('',(#39113),#39117); +#39113 = LINE('',#39114,#39115); +#39114 = CARTESIAN_POINT('',(-9.492283601027E-002,0.E+000)); +#39115 = VECTOR('',#39116,1.); +#39116 = DIRECTION('',(0.E+000,-1.)); +#39117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39118 = ORIENTED_EDGE('',*,*,#39119,.T.); +#39119 = EDGE_CURVE('',#39097,#39033,#39120,.T.); +#39120 = SURFACE_CURVE('',#39121,(#39125,#39132),.PCURVE_S1.); +#39121 = LINE('',#39122,#39123); +#39122 = CARTESIAN_POINT('',(0.218131644909,0.782,-0.4081119896)); +#39123 = VECTOR('',#39124,1.); +#39124 = DIRECTION('',(-0.192758352188,0.E+000,0.9812462574)); +#39125 = PCURVE('',#31860,#39126); +#39126 = DEFINITIONAL_REPRESENTATION('',(#39127),#39131); +#39127 = LINE('',#39128,#39129); +#39128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39129 = VECTOR('',#39130,1.); +#39130 = DIRECTION('',(-1.,0.E+000)); +#39131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39132 = PCURVE('',#38775,#39133); +#39133 = DEFINITIONAL_REPRESENTATION('',(#39134),#39138); +#39134 = LINE('',#39135,#39136); +#39135 = CARTESIAN_POINT('',(-0.204380523764,3.179558888983E-002)); +#39136 = VECTOR('',#39137,1.); +#39137 = DIRECTION('',(0.9812462574,-0.192758352188)); +#39138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39139 = ORIENTED_EDGE('',*,*,#39032,.T.); +#39140 = ADVANCED_FACE('',(#39141),#31832,.T.); +#39141 = FACE_BOUND('',#39142,.T.); +#39142 = EDGE_LOOP('',(#39143,#39144,#39167,#39188)); +#39143 = ORIENTED_EDGE('',*,*,#31816,.F.); +#39144 = ORIENTED_EDGE('',*,*,#39145,.F.); +#39145 = EDGE_CURVE('',#39146,#31789,#39148,.T.); +#39146 = VERTEX_POINT('',#39147); +#39147 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); +#39148 = SURFACE_CURVE('',#39149,(#39153,#39160),.PCURVE_S1.); +#39149 = LINE('',#39150,#39151); +#39150 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); +#39151 = VECTOR('',#39152,1.); +#39152 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39153 = PCURVE('',#31832,#39154); +#39154 = DEFINITIONAL_REPRESENTATION('',(#39155),#39159); +#39155 = LINE('',#39156,#39157); +#39156 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39157 = VECTOR('',#39158,1.); +#39158 = DIRECTION('',(0.E+000,-1.)); +#39159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39160 = PCURVE('',#31804,#39161); +#39161 = DEFINITIONAL_REPRESENTATION('',(#39162),#39166); +#39162 = LINE('',#39163,#39164); +#39163 = CARTESIAN_POINT('',(-3.292716262687E-002,0.E+000)); +#39164 = VECTOR('',#39165,1.); +#39165 = DIRECTION('',(0.E+000,-1.)); +#39166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39167 = ORIENTED_EDGE('',*,*,#39168,.T.); +#39168 = EDGE_CURVE('',#39146,#39097,#39169,.T.); +#39169 = SURFACE_CURVE('',#39170,(#39174,#39181),.PCURVE_S1.); +#39170 = LINE('',#39171,#39172); +#39171 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.4081119896)); +#39172 = VECTOR('',#39173,1.); +#39173 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#39174 = PCURVE('',#31832,#39175); +#39175 = DEFINITIONAL_REPRESENTATION('',(#39176),#39180); +#39176 = LINE('',#39177,#39178); +#39177 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39178 = VECTOR('',#39179,1.); +#39179 = DIRECTION('',(-1.,0.E+000)); +#39180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39181 = PCURVE('',#38775,#39182); +#39182 = DEFINITIONAL_REPRESENTATION('',(#39183),#39187); +#39183 = LINE('',#39184,#39185); +#39184 = CARTESIAN_POINT('',(-0.204380523764,0.1267184249)); +#39185 = VECTOR('',#39186,1.); +#39186 = DIRECTION('',(0.E+000,-1.)); +#39187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#36991 = ORIENTED_EDGE('',*,*,#36900,.T.); -#36992 = ADVANCED_FACE('',(#36993),#29282,.T.); -#36993 = FACE_BOUND('',#36994,.T.); -#36994 = EDGE_LOOP('',(#36995,#36996,#37017,#37054)); -#36995 = ORIENTED_EDGE('',*,*,#29250,.F.); -#36996 = ORIENTED_EDGE('',*,*,#36997,.F.); -#36997 = EDGE_CURVE('',#36998,#29157,#37000,.T.); -#36998 = VERTEX_POINT('',#36999); -#36999 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#37000 = SURFACE_CURVE('',#37001,(#37005,#37011),.PCURVE_S1.); -#37001 = LINE('',#37002,#37003); -#37002 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#37003 = VECTOR('',#37004,1.); -#37004 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37005 = PCURVE('',#29282,#37006); -#37006 = DEFINITIONAL_REPRESENTATION('',(#37007),#37010); -#37007 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37008,#37009),.UNSPECIFIED., +#39188 = ORIENTED_EDGE('',*,*,#39096,.T.); +#39189 = ADVANCED_FACE('',(#39190),#31804,.T.); +#39190 = FACE_BOUND('',#39191,.T.); +#39191 = EDGE_LOOP('',(#39192,#39193,#39216,#39237)); +#39192 = ORIENTED_EDGE('',*,*,#31788,.F.); +#39193 = ORIENTED_EDGE('',*,*,#39194,.F.); +#39194 = EDGE_CURVE('',#39195,#31761,#39197,.T.); +#39195 = VERTEX_POINT('',#39196); +#39196 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); +#39197 = SURFACE_CURVE('',#39198,(#39202,#39209),.PCURVE_S1.); +#39198 = LINE('',#39199,#39200); +#39199 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); +#39200 = VECTOR('',#39201,1.); +#39201 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39202 = PCURVE('',#31804,#39203); +#39203 = DEFINITIONAL_REPRESENTATION('',(#39204),#39208); +#39204 = LINE('',#39205,#39206); +#39205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39206 = VECTOR('',#39207,1.); +#39207 = DIRECTION('',(0.E+000,-1.)); +#39208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39209 = PCURVE('',#31776,#39210); +#39210 = DEFINITIONAL_REPRESENTATION('',(#39211),#39215); +#39211 = LINE('',#39212,#39213); +#39212 = CARTESIAN_POINT('',(-0.121830501719,0.E+000)); +#39213 = VECTOR('',#39214,1.); +#39214 = DIRECTION('',(0.E+000,-1.)); +#39215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39216 = ORIENTED_EDGE('',*,*,#39217,.T.); +#39217 = EDGE_CURVE('',#39195,#39146,#39218,.T.); +#39218 = SURFACE_CURVE('',#39219,(#39223,#39230),.PCURVE_S1.); +#39219 = LINE('',#39220,#39221); +#39220 = CARTESIAN_POINT('',(0.313054480919,0.782,-0.441039152227)); +#39221 = VECTOR('',#39222,1.); +#39222 = DIRECTION('',(0.E+000,0.E+000,1.)); +#39223 = PCURVE('',#31804,#39224); +#39224 = DEFINITIONAL_REPRESENTATION('',(#39225),#39229); +#39225 = LINE('',#39226,#39227); +#39226 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39227 = VECTOR('',#39228,1.); +#39228 = DIRECTION('',(-1.,0.E+000)); +#39229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39230 = PCURVE('',#38775,#39231); +#39231 = DEFINITIONAL_REPRESENTATION('',(#39232),#39236); +#39232 = LINE('',#39233,#39234); +#39233 = CARTESIAN_POINT('',(-0.237307686391,0.1267184249)); +#39234 = VECTOR('',#39235,1.); +#39235 = DIRECTION('',(1.,3.413729340079E-027)); +#39236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39237 = ORIENTED_EDGE('',*,*,#39145,.T.); +#39238 = ADVANCED_FACE('',(#39239),#31776,.T.); +#39239 = FACE_BOUND('',#39240,.T.); +#39240 = EDGE_LOOP('',(#39241,#39242,#39265,#39286)); +#39241 = ORIENTED_EDGE('',*,*,#31760,.F.); +#39242 = ORIENTED_EDGE('',*,*,#39243,.F.); +#39243 = EDGE_CURVE('',#39244,#31733,#39246,.T.); +#39244 = VERTEX_POINT('',#39245); +#39245 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); +#39246 = SURFACE_CURVE('',#39247,(#39251,#39258),.PCURVE_S1.); +#39247 = LINE('',#39248,#39249); +#39248 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); +#39249 = VECTOR('',#39250,1.); +#39250 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39251 = PCURVE('',#31776,#39252); +#39252 = DEFINITIONAL_REPRESENTATION('',(#39253),#39257); +#39253 = LINE('',#39254,#39255); +#39254 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39255 = VECTOR('',#39256,1.); +#39256 = DIRECTION('',(0.E+000,-1.)); +#39257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39258 = PCURVE('',#31748,#39259); +#39259 = DEFINITIONAL_REPRESENTATION('',(#39260),#39264); +#39260 = LINE('',#39261,#39262); +#39261 = CARTESIAN_POINT('',(-0.134316995809,0.E+000)); +#39262 = VECTOR('',#39263,1.); +#39263 = DIRECTION('',(0.E+000,-1.)); +#39264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39265 = ORIENTED_EDGE('',*,*,#39266,.T.); +#39266 = EDGE_CURVE('',#39244,#39195,#39267,.T.); +#39267 = SURFACE_CURVE('',#39268,(#39272,#39279),.PCURVE_S1.); +#39268 = LINE('',#39269,#39270); +#39269 = CARTESIAN_POINT('',(0.1912239792,0.782,-0.441039152227)); +#39270 = VECTOR('',#39271,1.); +#39271 = DIRECTION('',(1.,0.E+000,0.E+000)); +#39272 = PCURVE('',#31776,#39273); +#39273 = DEFINITIONAL_REPRESENTATION('',(#39274),#39278); +#39274 = LINE('',#39275,#39276); +#39275 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39276 = VECTOR('',#39277,1.); +#39277 = DIRECTION('',(-1.,0.E+000)); +#39278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39279 = PCURVE('',#38775,#39280); +#39280 = DEFINITIONAL_REPRESENTATION('',(#39281),#39285); +#39281 = LINE('',#39282,#39283); +#39282 = CARTESIAN_POINT('',(-0.237307686391,4.887923180685E-003)); +#39283 = VECTOR('',#39284,1.); +#39284 = DIRECTION('',(0.E+000,1.)); +#39285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39286 = ORIENTED_EDGE('',*,*,#39194,.T.); +#39287 = ADVANCED_FACE('',(#39288),#31748,.T.); +#39288 = FACE_BOUND('',#39289,.T.); +#39289 = EDGE_LOOP('',(#39290,#39291,#39314,#39335)); +#39290 = ORIENTED_EDGE('',*,*,#31732,.F.); +#39291 = ORIENTED_EDGE('',*,*,#39292,.F.); +#39292 = EDGE_CURVE('',#39293,#31705,#39295,.T.); +#39293 = VERTEX_POINT('',#39294); +#39294 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); +#39295 = SURFACE_CURVE('',#39296,(#39300,#39307),.PCURVE_S1.); +#39296 = LINE('',#39297,#39298); +#39297 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); +#39298 = VECTOR('',#39299,1.); +#39299 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39300 = PCURVE('',#31748,#39301); +#39301 = DEFINITIONAL_REPRESENTATION('',(#39302),#39306); +#39302 = LINE('',#39303,#39304); +#39303 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39304 = VECTOR('',#39305,1.); +#39305 = DIRECTION('',(0.E+000,-1.)); +#39306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39307 = PCURVE('',#31720,#39308); +#39308 = DEFINITIONAL_REPRESENTATION('',(#39309),#39313); +#39309 = LINE('',#39310,#39311); +#39310 = CARTESIAN_POINT('',(-3.309138889565E-002,0.E+000)); +#39311 = VECTOR('',#39312,1.); +#39312 = DIRECTION('',(0.E+000,-1.)); +#39313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39314 = ORIENTED_EDGE('',*,*,#39315,.T.); +#39315 = EDGE_CURVE('',#39293,#39244,#39316,.T.); +#39316 = SURFACE_CURVE('',#39317,(#39321,#39328),.PCURVE_S1.); +#39317 = LINE('',#39318,#39319); +#39318 = CARTESIAN_POINT('',(0.164882249099,0.782,-0.309330501719)); +#39319 = VECTOR('',#39320,1.); +#39320 = DIRECTION('',(0.196116135138,0.E+000,-0.980580675691)); +#39321 = PCURVE('',#31748,#39322); +#39322 = DEFINITIONAL_REPRESENTATION('',(#39323),#39327); +#39323 = LINE('',#39324,#39325); +#39324 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39325 = VECTOR('',#39326,1.); +#39326 = DIRECTION('',(-1.,0.E+000)); +#39327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39328 = PCURVE('',#38775,#39329); +#39329 = DEFINITIONAL_REPRESENTATION('',(#39330),#39334); +#39330 = LINE('',#39331,#39332); +#39331 = CARTESIAN_POINT('',(-0.105599035883,-2.145380692081E-002)); +#39332 = VECTOR('',#39333,1.); +#39333 = DIRECTION('',(-0.980580675691,0.196116135138)); +#39334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39335 = ORIENTED_EDGE('',*,*,#39243,.T.); +#39336 = ADVANCED_FACE('',(#39337),#31720,.T.); +#39337 = FACE_BOUND('',#39338,.T.); +#39338 = EDGE_LOOP('',(#39339,#39340,#39362,#39383)); +#39339 = ORIENTED_EDGE('',*,*,#31704,.F.); +#39340 = ORIENTED_EDGE('',*,*,#39341,.F.); +#39341 = EDGE_CURVE('',#39342,#31643,#39344,.T.); +#39342 = VERTEX_POINT('',#39343); +#39343 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#39344 = SURFACE_CURVE('',#39345,(#39349,#39356),.PCURVE_S1.); +#39345 = LINE('',#39346,#39347); +#39346 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#39347 = VECTOR('',#39348,1.); +#39348 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39349 = PCURVE('',#31720,#39350); +#39350 = DEFINITIONAL_REPRESENTATION('',(#39351),#39355); +#39351 = LINE('',#39352,#39353); +#39352 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39353 = VECTOR('',#39354,1.); +#39354 = DIRECTION('',(0.E+000,-1.)); +#39355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39356 = PCURVE('',#31674,#39357); +#39357 = DEFINITIONAL_REPRESENTATION('',(#39358),#39361); +#39358 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39359,#39360),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37008 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37009 = CARTESIAN_POINT('',(0.E+000,1.)); -#37010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39359 = CARTESIAN_POINT('',(1.,0.E+000)); +#39360 = CARTESIAN_POINT('',(1.,1.)); +#39361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39362 = ORIENTED_EDGE('',*,*,#39363,.T.); +#39363 = EDGE_CURVE('',#39342,#39293,#39364,.T.); +#39364 = SURFACE_CURVE('',#39365,(#39369,#39376),.PCURVE_S1.); +#39365 = LINE('',#39366,#39367); +#39366 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#39367 = VECTOR('',#39368,1.); +#39368 = DIRECTION('',(-0.99503719021,0.E+000,-9.9503719021E-002)); +#39369 = PCURVE('',#31720,#39370); +#39370 = DEFINITIONAL_REPRESENTATION('',(#39371),#39375); +#39371 = LINE('',#39372,#39373); +#39372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39373 = VECTOR('',#39374,1.); +#39374 = DIRECTION('',(-1.,0.E+000)); +#39375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39376 = PCURVE('',#38775,#39377); +#39377 = DEFINITIONAL_REPRESENTATION('',(#39378),#39382); +#39378 = LINE('',#39379,#39380); +#39379 = CARTESIAN_POINT('',(-0.102306319621,1.147335570606E-002)); +#39380 = VECTOR('',#39381,1.); +#39381 = DIRECTION('',(-9.9503719021E-002,-0.99503719021)); +#39382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39383 = ORIENTED_EDGE('',*,*,#39292,.T.); +#39384 = ADVANCED_FACE('',(#39385),#31674,.T.); +#39385 = FACE_BOUND('',#39386,.T.); +#39386 = EDGE_LOOP('',(#39387,#39388,#39409,#39446)); +#39387 = ORIENTED_EDGE('',*,*,#31642,.F.); +#39388 = ORIENTED_EDGE('',*,*,#39389,.F.); +#39389 = EDGE_CURVE('',#39390,#31549,#39392,.T.); +#39390 = VERTEX_POINT('',#39391); +#39391 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#39392 = SURFACE_CURVE('',#39393,(#39397,#39403),.PCURVE_S1.); +#39393 = LINE('',#39394,#39395); +#39394 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#39395 = VECTOR('',#39396,1.); +#39396 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39397 = PCURVE('',#31674,#39398); +#39398 = DEFINITIONAL_REPRESENTATION('',(#39399),#39402); +#39399 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39400,#39401),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); +#39400 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39401 = CARTESIAN_POINT('',(0.E+000,1.)); +#39402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37011 = PCURVE('',#29204,#37012); -#37012 = DEFINITIONAL_REPRESENTATION('',(#37013),#37016); -#37013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37014,#37015),.UNSPECIFIED., +#39403 = PCURVE('',#31596,#39404); +#39404 = DEFINITIONAL_REPRESENTATION('',(#39405),#39408); +#39405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39406,#39407),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37014 = CARTESIAN_POINT('',(1.,0.E+000)); -#37015 = CARTESIAN_POINT('',(1.,1.)); -#37016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39406 = CARTESIAN_POINT('',(1.,0.E+000)); +#39407 = CARTESIAN_POINT('',(1.,1.)); +#39408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37017 = ORIENTED_EDGE('',*,*,#37018,.T.); -#37018 = EDGE_CURVE('',#36998,#36950,#37019,.T.); -#37019 = SURFACE_CURVE('',#37020,(#37032,#37039),.PCURVE_S1.); -#37020 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37021,#37022,#37023,#37024, - #37025,#37026,#37027,#37028,#37029,#37030,#37031),.UNSPECIFIED.,.F., +#39409 = ORIENTED_EDGE('',*,*,#39410,.T.); +#39410 = EDGE_CURVE('',#39390,#39342,#39411,.T.); +#39411 = SURFACE_CURVE('',#39412,(#39424,#39431),.PCURVE_S1.); +#39412 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39413,#39414,#39415,#39416, + #39417,#39418,#39419,#39420,#39421,#39422,#39423),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.147859636731,0.28356132194, 0.412369396139,0.534236355888,0.652691629312,0.768663059498, 0.88365240186,1.),.UNSPECIFIED.); -#37021 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#37022 = CARTESIAN_POINT('',(0.239185998247,0.782,-0.329011896854)); -#37023 = CARTESIAN_POINT('',(0.234275354387,0.782,-0.328868250923)); -#37024 = CARTESIAN_POINT('',(0.227219264145,0.782,-0.32765980921)); -#37025 = CARTESIAN_POINT('',(0.220795849733,0.782,-0.325707725562)); -#37026 = CARTESIAN_POINT('',(0.215077836823,0.782,-0.322798382377)); -#37027 = CARTESIAN_POINT('',(0.209969074838,0.782,-0.319322694065)); -#37028 = CARTESIAN_POINT('',(0.205363431998,0.782,-0.315389795065)); -#37029 = CARTESIAN_POINT('',(0.201222930099,0.782,-0.311002344362)); -#37030 = CARTESIAN_POINT('',(0.198951696239,0.782,-0.307699103232)); -#37031 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); -#37032 = PCURVE('',#29282,#37033); -#37033 = DEFINITIONAL_REPRESENTATION('',(#37034),#37038); -#37034 = LINE('',#37035,#37036); -#37035 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37036 = VECTOR('',#37037,1.); -#37037 = DIRECTION('',(1.,0.E+000)); -#37038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37039 = PCURVE('',#36383,#37040); -#37040 = DEFINITIONAL_REPRESENTATION('',(#37041),#37053); -#37041 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37042,#37043,#37044,#37045, - #37046,#37047,#37048,#37049,#37050,#37051,#37052),.UNSPECIFIED.,.F., +#39413 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#39414 = CARTESIAN_POINT('',(0.239185998247,0.782,-0.329011896854)); +#39415 = CARTESIAN_POINT('',(0.234275354387,0.782,-0.328868250923)); +#39416 = CARTESIAN_POINT('',(0.227219264145,0.782,-0.32765980921)); +#39417 = CARTESIAN_POINT('',(0.220795849733,0.782,-0.325707725562)); +#39418 = CARTESIAN_POINT('',(0.215077836823,0.782,-0.322798382377)); +#39419 = CARTESIAN_POINT('',(0.209969074838,0.782,-0.319322694065)); +#39420 = CARTESIAN_POINT('',(0.205363431998,0.782,-0.315389795065)); +#39421 = CARTESIAN_POINT('',(0.201222930099,0.782,-0.311002344362)); +#39422 = CARTESIAN_POINT('',(0.198951696239,0.782,-0.307699103232)); +#39423 = CARTESIAN_POINT('',(0.197809411725,0.782,-0.306037785457)); +#39424 = PCURVE('',#31674,#39425); +#39425 = DEFINITIONAL_REPRESENTATION('',(#39426),#39430); +#39426 = LINE('',#39427,#39428); +#39427 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39428 = VECTOR('',#39429,1.); +#39429 = DIRECTION('',(1.,0.E+000)); +#39430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39431 = PCURVE('',#38775,#39432); +#39432 = DEFINITIONAL_REPRESENTATION('',(#39433),#39445); +#39433 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39434,#39435,#39436,#39437, + #39438,#39439,#39440,#39441,#39442,#39443,#39444),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,4),(0.E+000,0.147859636731,0.28356132194, 0.412369396139,0.534236355888,0.652691629312,0.768663059498, 0.88365240186,1.),.UNSPECIFIED.); -#37042 = CARTESIAN_POINT('',(-0.125355333459,5.541053833629E-002)); -#37043 = CARTESIAN_POINT('',(-0.125280431018,5.284994222811E-002)); -#37044 = CARTESIAN_POINT('',(-0.125136785087,4.79392983672E-002)); -#37045 = CARTESIAN_POINT('',(-0.123928343373,4.088320812588E-002)); -#37046 = CARTESIAN_POINT('',(-0.121976259726,3.445979371338E-002)); -#37047 = CARTESIAN_POINT('',(-0.11906691654,2.874178080317E-002)); -#37048 = CARTESIAN_POINT('',(-0.115591228229,2.36330188187E-002)); -#37049 = CARTESIAN_POINT('',(-0.111658329229,1.902737597852E-002)); -#37050 = CARTESIAN_POINT('',(-0.107270878525,1.488687407977E-002)); -#37051 = CARTESIAN_POINT('',(-0.103967637396,1.261564021931E-002)); -#37052 = CARTESIAN_POINT('',(-0.102306319621,1.147335570606E-002)); -#37053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37054 = ORIENTED_EDGE('',*,*,#36949,.T.); -#37055 = ADVANCED_FACE('',(#37056),#29204,.T.); -#37056 = FACE_BOUND('',#37057,.T.); -#37057 = EDGE_LOOP('',(#37058,#37059,#37080,#37133)); -#37058 = ORIENTED_EDGE('',*,*,#29156,.F.); -#37059 = ORIENTED_EDGE('',*,*,#37060,.F.); -#37060 = EDGE_CURVE('',#37061,#29063,#37063,.T.); -#37061 = VERTEX_POINT('',#37062); -#37062 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#37063 = SURFACE_CURVE('',#37064,(#37068,#37074),.PCURVE_S1.); -#37064 = LINE('',#37065,#37066); -#37065 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#37066 = VECTOR('',#37067,1.); -#37067 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37068 = PCURVE('',#29204,#37069); -#37069 = DEFINITIONAL_REPRESENTATION('',(#37070),#37073); -#37070 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37071,#37072),.UNSPECIFIED., +#39434 = CARTESIAN_POINT('',(-0.125355333459,5.541053833629E-002)); +#39435 = CARTESIAN_POINT('',(-0.125280431018,5.284994222811E-002)); +#39436 = CARTESIAN_POINT('',(-0.125136785087,4.79392983672E-002)); +#39437 = CARTESIAN_POINT('',(-0.123928343373,4.088320812588E-002)); +#39438 = CARTESIAN_POINT('',(-0.121976259726,3.445979371338E-002)); +#39439 = CARTESIAN_POINT('',(-0.11906691654,2.874178080317E-002)); +#39440 = CARTESIAN_POINT('',(-0.115591228229,2.36330188187E-002)); +#39441 = CARTESIAN_POINT('',(-0.111658329229,1.902737597852E-002)); +#39442 = CARTESIAN_POINT('',(-0.107270878525,1.488687407977E-002)); +#39443 = CARTESIAN_POINT('',(-0.103967637396,1.261564021931E-002)); +#39444 = CARTESIAN_POINT('',(-0.102306319621,1.147335570606E-002)); +#39445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39446 = ORIENTED_EDGE('',*,*,#39341,.T.); +#39447 = ADVANCED_FACE('',(#39448),#31596,.T.); +#39448 = FACE_BOUND('',#39449,.T.); +#39449 = EDGE_LOOP('',(#39450,#39451,#39472,#39525)); +#39450 = ORIENTED_EDGE('',*,*,#31548,.F.); +#39451 = ORIENTED_EDGE('',*,*,#39452,.F.); +#39452 = EDGE_CURVE('',#39453,#31455,#39455,.T.); +#39453 = VERTEX_POINT('',#39454); +#39454 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#39455 = SURFACE_CURVE('',#39456,(#39460,#39466),.PCURVE_S1.); +#39456 = LINE('',#39457,#39458); +#39457 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#39458 = VECTOR('',#39459,1.); +#39459 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39460 = PCURVE('',#31596,#39461); +#39461 = DEFINITIONAL_REPRESENTATION('',(#39462),#39465); +#39462 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39463,#39464),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37072 = CARTESIAN_POINT('',(0.E+000,1.)); -#37073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39464 = CARTESIAN_POINT('',(0.E+000,1.)); +#39465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37074 = PCURVE('',#29110,#37075); -#37075 = DEFINITIONAL_REPRESENTATION('',(#37076),#37079); -#37076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37077,#37078),.UNSPECIFIED., +#39466 = PCURVE('',#31502,#39467); +#39467 = DEFINITIONAL_REPRESENTATION('',(#39468),#39471); +#39468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39469,#39470),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37077 = CARTESIAN_POINT('',(1.,0.E+000)); -#37078 = CARTESIAN_POINT('',(1.,1.)); -#37079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39469 = CARTESIAN_POINT('',(1.,0.E+000)); +#39470 = CARTESIAN_POINT('',(1.,1.)); +#39471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37080 = ORIENTED_EDGE('',*,*,#37081,.T.); -#37081 = EDGE_CURVE('',#37061,#36998,#37082,.T.); -#37082 = SURFACE_CURVE('',#37083,(#37103,#37110),.PCURVE_S1.); -#37083 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37084,#37085,#37086,#37087, - #37088,#37089,#37090,#37091,#37092,#37093,#37094,#37095,#37096, - #37097,#37098,#37099,#37100,#37101,#37102),.UNSPECIFIED.,.F.,.F.,(4, +#39472 = ORIENTED_EDGE('',*,*,#39473,.T.); +#39473 = EDGE_CURVE('',#39453,#39390,#39474,.T.); +#39474 = SURFACE_CURVE('',#39475,(#39495,#39502),.PCURVE_S1.); +#39475 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39476,#39477,#39478,#39479, + #39480,#39481,#39482,#39483,#39484,#39485,#39486,#39487,#39488, + #39489,#39490,#39491,#39492,#39493,#39494),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.286593345654E-002, 0.141886871964,0.207452626415,0.27043768,0.331640872248, 0.390107577493,0.448069286949,0.505502951925,0.562488152834, 0.619084328885,0.676415530692,0.735452360451,0.796240769449, 0.860405678089,0.928304927285,1.),.UNSPECIFIED.); -#37084 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#37085 = CARTESIAN_POINT('',(0.29326038452,0.782,-0.27571881079)); -#37086 = CARTESIAN_POINT('',(0.293186781443,0.782,-0.279795732308)); -#37087 = CARTESIAN_POINT('',(0.292566923459,0.782,-0.285732407895)); -#37088 = CARTESIAN_POINT('',(0.291521150064,0.782,-0.291314679553)); -#37089 = CARTESIAN_POINT('',(0.290168017209,0.782,-0.296604073658)); -#37090 = CARTESIAN_POINT('',(0.28830289424,0.782,-0.301517936914)); -#37091 = CARTESIAN_POINT('',(0.286090753377,0.782,-0.306127515532)); -#37092 = CARTESIAN_POINT('',(0.283380787846,0.782,-0.310334980685)); -#37093 = CARTESIAN_POINT('',(0.28036577237,0.782,-0.314271337599)); -#37094 = CARTESIAN_POINT('',(0.276922244051,0.782,-0.317800122959)); -#37095 = CARTESIAN_POINT('',(0.273003681401,0.782,-0.320779735243)); -#37096 = CARTESIAN_POINT('',(0.268763807319,0.782,-0.32338749773)); -#37097 = CARTESIAN_POINT('',(0.264117226398,0.782,-0.325502230425)); -#37098 = CARTESIAN_POINT('',(0.259061202504,0.782,-0.327073397351)); -#37099 = CARTESIAN_POINT('',(0.253645978584,0.782,-0.328282268926)); -#37100 = CARTESIAN_POINT('',(0.247815363669,0.782,-0.328918085874)); -#37101 = CARTESIAN_POINT('',(0.243805859365,0.782,-0.329029551174)); -#37102 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); -#37103 = PCURVE('',#29204,#37104); -#37104 = DEFINITIONAL_REPRESENTATION('',(#37105),#37109); -#37105 = LINE('',#37106,#37107); -#37106 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37107 = VECTOR('',#37108,1.); -#37108 = DIRECTION('',(1.,0.E+000)); -#37109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37110 = PCURVE('',#36383,#37111); -#37111 = DEFINITIONAL_REPRESENTATION('',(#37112),#37132); -#37112 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37113,#37114,#37115,#37116, - #37117,#37118,#37119,#37120,#37121,#37122,#37123,#37124,#37125, - #37126,#37127,#37128,#37129,#37130,#37131),.UNSPECIFIED.,.F.,.F.,(4, +#39476 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#39477 = CARTESIAN_POINT('',(0.29326038452,0.782,-0.27571881079)); +#39478 = CARTESIAN_POINT('',(0.293186781443,0.782,-0.279795732308)); +#39479 = CARTESIAN_POINT('',(0.292566923459,0.782,-0.285732407895)); +#39480 = CARTESIAN_POINT('',(0.291521150064,0.782,-0.291314679553)); +#39481 = CARTESIAN_POINT('',(0.290168017209,0.782,-0.296604073658)); +#39482 = CARTESIAN_POINT('',(0.28830289424,0.782,-0.301517936914)); +#39483 = CARTESIAN_POINT('',(0.286090753377,0.782,-0.306127515532)); +#39484 = CARTESIAN_POINT('',(0.283380787846,0.782,-0.310334980685)); +#39485 = CARTESIAN_POINT('',(0.28036577237,0.782,-0.314271337599)); +#39486 = CARTESIAN_POINT('',(0.276922244051,0.782,-0.317800122959)); +#39487 = CARTESIAN_POINT('',(0.273003681401,0.782,-0.320779735243)); +#39488 = CARTESIAN_POINT('',(0.268763807319,0.782,-0.32338749773)); +#39489 = CARTESIAN_POINT('',(0.264117226398,0.782,-0.325502230425)); +#39490 = CARTESIAN_POINT('',(0.259061202504,0.782,-0.327073397351)); +#39491 = CARTESIAN_POINT('',(0.253645978584,0.782,-0.328282268926)); +#39492 = CARTESIAN_POINT('',(0.247815363669,0.782,-0.328918085874)); +#39493 = CARTESIAN_POINT('',(0.243805859365,0.782,-0.329029551174)); +#39494 = CARTESIAN_POINT('',(0.241746594356,0.782,-0.329086799296)); +#39495 = PCURVE('',#31596,#39496); +#39496 = DEFINITIONAL_REPRESENTATION('',(#39497),#39501); +#39497 = LINE('',#39498,#39499); +#39498 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39499 = VECTOR('',#39500,1.); +#39500 = DIRECTION('',(1.,0.E+000)); +#39501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39502 = PCURVE('',#38775,#39503); +#39503 = DEFINITIONAL_REPRESENTATION('',(#39504),#39524); +#39504 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39505,#39506,#39507,#39508, + #39509,#39510,#39511,#39512,#39513,#39514,#39515,#39516,#39517, + #39518,#39519,#39520,#39521,#39522,#39523),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.286593345654E-002, 0.141886871964,0.207452626415,0.27043768,0.331640872248, 0.390107577493,0.448069286949,0.505502951925,0.562488152834, 0.619084328885,0.676415530692,0.735452360451,0.796240769449, 0.860405678089,0.928304927285,1.),.UNSPECIFIED.); -#37113 = CARTESIAN_POINT('',(-6.98936439097E-002,0.106962127324)); -#37114 = CARTESIAN_POINT('',(-7.198734495395E-002,0.1069243285)); -#37115 = CARTESIAN_POINT('',(-7.606426647138E-002,0.106850725424)); -#37116 = CARTESIAN_POINT('',(-8.200094205897E-002,0.106230867439)); -#37117 = CARTESIAN_POINT('',(-8.758321371685E-002,0.105185094044)); -#37118 = CARTESIAN_POINT('',(-9.287260782218E-002,0.10383196119)); -#37119 = CARTESIAN_POINT('',(-9.778647107772E-002,0.10196683822)); -#37120 = CARTESIAN_POINT('',(-0.102396049696,9.975469735714E-002)); -#37121 = CARTESIAN_POINT('',(-0.106603514849,9.704473182687E-002)); -#37122 = CARTESIAN_POINT('',(-0.110539871763,9.402971635052E-002)); -#37123 = CARTESIAN_POINT('',(-0.114068657123,9.05861880319E-002)); -#37124 = CARTESIAN_POINT('',(-0.117048269407,8.666762538205E-002)); -#37125 = CARTESIAN_POINT('',(-0.119656031893,8.242775130006E-002)); -#37126 = CARTESIAN_POINT('',(-0.121770764588,7.778117037845E-002)); -#37127 = CARTESIAN_POINT('',(-0.123341931515,7.272514648495E-002)); -#37128 = CARTESIAN_POINT('',(-0.12455080309,6.730992256501E-002)); -#37129 = CARTESIAN_POINT('',(-0.125186620038,6.147930764915E-002)); -#37130 = CARTESIAN_POINT('',(-0.125298085337,5.746980334553E-002)); -#37131 = CARTESIAN_POINT('',(-0.125355333459,5.541053833629E-002)); -#37132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37133 = ORIENTED_EDGE('',*,*,#36997,.T.); -#37134 = ADVANCED_FACE('',(#37135),#29110,.T.); -#37135 = FACE_BOUND('',#37136,.T.); -#37136 = EDGE_LOOP('',(#37137,#37138,#37159,#37212)); -#37137 = ORIENTED_EDGE('',*,*,#29062,.F.); -#37138 = ORIENTED_EDGE('',*,*,#37139,.F.); -#37139 = EDGE_CURVE('',#37140,#28969,#37142,.T.); -#37140 = VERTEX_POINT('',#37141); -#37141 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#37142 = SURFACE_CURVE('',#37143,(#37147,#37153),.PCURVE_S1.); -#37143 = LINE('',#37144,#37145); -#37144 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#37145 = VECTOR('',#37146,1.); -#37146 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37147 = PCURVE('',#29110,#37148); -#37148 = DEFINITIONAL_REPRESENTATION('',(#37149),#37152); -#37149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37150,#37151),.UNSPECIFIED., +#39505 = CARTESIAN_POINT('',(-6.98936439097E-002,0.106962127324)); +#39506 = CARTESIAN_POINT('',(-7.198734495395E-002,0.1069243285)); +#39507 = CARTESIAN_POINT('',(-7.606426647138E-002,0.106850725424)); +#39508 = CARTESIAN_POINT('',(-8.200094205897E-002,0.106230867439)); +#39509 = CARTESIAN_POINT('',(-8.758321371685E-002,0.105185094044)); +#39510 = CARTESIAN_POINT('',(-9.287260782218E-002,0.10383196119)); +#39511 = CARTESIAN_POINT('',(-9.778647107772E-002,0.10196683822)); +#39512 = CARTESIAN_POINT('',(-0.102396049696,9.975469735714E-002)); +#39513 = CARTESIAN_POINT('',(-0.106603514849,9.704473182687E-002)); +#39514 = CARTESIAN_POINT('',(-0.110539871763,9.402971635052E-002)); +#39515 = CARTESIAN_POINT('',(-0.114068657123,9.05861880319E-002)); +#39516 = CARTESIAN_POINT('',(-0.117048269407,8.666762538205E-002)); +#39517 = CARTESIAN_POINT('',(-0.119656031893,8.242775130006E-002)); +#39518 = CARTESIAN_POINT('',(-0.121770764588,7.778117037845E-002)); +#39519 = CARTESIAN_POINT('',(-0.123341931515,7.272514648495E-002)); +#39520 = CARTESIAN_POINT('',(-0.12455080309,6.730992256501E-002)); +#39521 = CARTESIAN_POINT('',(-0.125186620038,6.147930764915E-002)); +#39522 = CARTESIAN_POINT('',(-0.125298085337,5.746980334553E-002)); +#39523 = CARTESIAN_POINT('',(-0.125355333459,5.541053833629E-002)); +#39524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39525 = ORIENTED_EDGE('',*,*,#39389,.T.); +#39526 = ADVANCED_FACE('',(#39527),#31502,.T.); +#39527 = FACE_BOUND('',#39528,.T.); +#39528 = EDGE_LOOP('',(#39529,#39530,#39551,#39604)); +#39529 = ORIENTED_EDGE('',*,*,#31454,.F.); +#39530 = ORIENTED_EDGE('',*,*,#39531,.F.); +#39531 = EDGE_CURVE('',#39532,#31361,#39534,.T.); +#39532 = VERTEX_POINT('',#39533); +#39533 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#39534 = SURFACE_CURVE('',#39535,(#39539,#39545),.PCURVE_S1.); +#39535 = LINE('',#39536,#39537); +#39536 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#39537 = VECTOR('',#39538,1.); +#39538 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39539 = PCURVE('',#31502,#39540); +#39540 = DEFINITIONAL_REPRESENTATION('',(#39541),#39544); +#39541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39542,#39543),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37151 = CARTESIAN_POINT('',(0.E+000,1.)); -#37152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39543 = CARTESIAN_POINT('',(0.E+000,1.)); +#39544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37153 = PCURVE('',#29016,#37154); -#37154 = DEFINITIONAL_REPRESENTATION('',(#37155),#37158); -#37155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37156,#37157),.UNSPECIFIED., +#39545 = PCURVE('',#31408,#39546); +#39546 = DEFINITIONAL_REPRESENTATION('',(#39547),#39550); +#39547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39548,#39549),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37156 = CARTESIAN_POINT('',(1.,0.E+000)); -#37157 = CARTESIAN_POINT('',(1.,1.)); -#37158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#39548 = CARTESIAN_POINT('',(1.,0.E+000)); +#39549 = CARTESIAN_POINT('',(1.,1.)); +#39550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#37159 = ORIENTED_EDGE('',*,*,#37160,.T.); -#37160 = EDGE_CURVE('',#37140,#37061,#37161,.T.); -#37161 = SURFACE_CURVE('',#37162,(#37182,#37189),.PCURVE_S1.); -#37162 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37163,#37164,#37165,#37166, - #37167,#37168,#37169,#37170,#37171,#37172,#37173,#37174,#37175, - #37176,#37177,#37178,#37179,#37180,#37181),.UNSPECIFIED.,.F.,.F.,(4, +#39551 = ORIENTED_EDGE('',*,*,#39552,.T.); +#39552 = EDGE_CURVE('',#39532,#39453,#39553,.T.); +#39553 = SURFACE_CURVE('',#39554,(#39574,#39581),.PCURVE_S1.); +#39554 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39555,#39556,#39557,#39558, + #39559,#39560,#39561,#39562,#39563,#39564,#39565,#39566,#39567, + #39568,#39569,#39570,#39571,#39572,#39573),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.580103760947E-002, 0.128676795949,0.188675874952,0.247598436734,0.304849420119, 0.361785899283,0.419522706369,0.478681815421,0.538769503044, 0.598799056013,0.660184281501,0.722951530611,0.787992689105, 0.855403768434,0.926153061284,1.),.UNSPECIFIED.); -#37163 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#37164 = CARTESIAN_POINT('',(0.243549908167,0.782,-0.213889032847)); -#37165 = CARTESIAN_POINT('',(0.247378197369,0.782,-0.213981535427)); -#37166 = CARTESIAN_POINT('',(0.252947632967,0.782,-0.214763885084)); -#37167 = CARTESIAN_POINT('',(0.258208415951,0.782,-0.216053889032)); -#37168 = CARTESIAN_POINT('',(0.263135374274,0.782,-0.217859153727)); -#37169 = CARTESIAN_POINT('',(0.26778626697,0.782,-0.220104213983)); -#37170 = CARTESIAN_POINT('',(0.27200680351,0.782,-0.223011158053)); -#37171 = CARTESIAN_POINT('',(0.276027110805,0.782,-0.226278850425)); -#37172 = CARTESIAN_POINT('',(0.279588481171,0.782,-0.230174566874)); -#37173 = CARTESIAN_POINT('',(0.282830328799,0.782,-0.23441570496)); -#37174 = CARTESIAN_POINT('',(0.285628287023,0.782,-0.239045087591)); -#37175 = CARTESIAN_POINT('',(0.287983772535,0.782,-0.243997737718)); -#37176 = CARTESIAN_POINT('',(0.289966833881,0.782,-0.249272705825)); -#37177 = CARTESIAN_POINT('',(0.29143117997,0.782,-0.254900125977)); -#37178 = CARTESIAN_POINT('',(0.292508324801,0.782,-0.260850061369)); -#37179 = CARTESIAN_POINT('',(0.293199808784,0.782,-0.267126302118)); -#37180 = CARTESIAN_POINT('',(0.293264926822,0.782,-0.271428121632)); -#37181 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); -#37182 = PCURVE('',#29110,#37183); -#37183 = DEFINITIONAL_REPRESENTATION('',(#37184),#37188); -#37184 = LINE('',#37185,#37186); -#37185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37186 = VECTOR('',#37187,1.); -#37187 = DIRECTION('',(1.,0.E+000)); -#37188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37189 = PCURVE('',#36383,#37190); -#37190 = DEFINITIONAL_REPRESENTATION('',(#37191),#37211); -#37191 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37192,#37193,#37194,#37195, - #37196,#37197,#37198,#37199,#37200,#37201,#37202,#37203,#37204, - #37205,#37206,#37207,#37208,#37209,#37210),.UNSPECIFIED.,.F.,.F.,(4, +#39555 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#39556 = CARTESIAN_POINT('',(0.243549908167,0.782,-0.213889032847)); +#39557 = CARTESIAN_POINT('',(0.247378197369,0.782,-0.213981535427)); +#39558 = CARTESIAN_POINT('',(0.252947632967,0.782,-0.214763885084)); +#39559 = CARTESIAN_POINT('',(0.258208415951,0.782,-0.216053889032)); +#39560 = CARTESIAN_POINT('',(0.263135374274,0.782,-0.217859153727)); +#39561 = CARTESIAN_POINT('',(0.26778626697,0.782,-0.220104213983)); +#39562 = CARTESIAN_POINT('',(0.27200680351,0.782,-0.223011158053)); +#39563 = CARTESIAN_POINT('',(0.276027110805,0.782,-0.226278850425)); +#39564 = CARTESIAN_POINT('',(0.279588481171,0.782,-0.230174566874)); +#39565 = CARTESIAN_POINT('',(0.282830328799,0.782,-0.23441570496)); +#39566 = CARTESIAN_POINT('',(0.285628287023,0.782,-0.239045087591)); +#39567 = CARTESIAN_POINT('',(0.287983772535,0.782,-0.243997737718)); +#39568 = CARTESIAN_POINT('',(0.289966833881,0.782,-0.249272705825)); +#39569 = CARTESIAN_POINT('',(0.29143117997,0.782,-0.254900125977)); +#39570 = CARTESIAN_POINT('',(0.292508324801,0.782,-0.260850061369)); +#39571 = CARTESIAN_POINT('',(0.293199808784,0.782,-0.267126302118)); +#39572 = CARTESIAN_POINT('',(0.293264926822,0.782,-0.271428121632)); +#39573 = CARTESIAN_POINT('',(0.293298183343,0.782,-0.273625109746)); +#39574 = PCURVE('',#31502,#39575); +#39575 = DEFINITIONAL_REPRESENTATION('',(#39576),#39580); +#39576 = LINE('',#39577,#39578); +#39577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39578 = VECTOR('',#39579,1.); +#39579 = DIRECTION('',(1.,0.E+000)); +#39580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39581 = PCURVE('',#38775,#39582); +#39582 = DEFINITIONAL_REPRESENTATION('',(#39583),#39603); +#39583 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39584,#39585,#39586,#39587, + #39588,#39589,#39590,#39591,#39592,#39593,#39594,#39595,#39596, + #39597,#39598,#39599,#39600,#39601,#39602),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.580103760947E-002, 0.128676795949,0.188675874952,0.247598436734,0.304849420119, 0.361785899283,0.419522706369,0.478681815421,0.538769503044, 0.598799056013,0.660184281501,0.722951530611,0.787992689105, 0.855403768434,0.926153061284,1.),.UNSPECIFIED.); -#37192 = CARTESIAN_POINT('',(-1.011026426529E-002,5.525619226147E-002)); -#37193 = CARTESIAN_POINT('',(-1.015756701092E-002,5.721385214802E-002)); -#37194 = CARTESIAN_POINT('',(-1.025006959094E-002,6.104214135E-002)); -#37195 = CARTESIAN_POINT('',(-1.103241924814E-002,6.661157694798E-002)); -#37196 = CARTESIAN_POINT('',(-1.232242319587E-002,7.187235993168E-002)); -#37197 = CARTESIAN_POINT('',(-1.412768789087E-002,7.679931825469E-002)); -#37198 = CARTESIAN_POINT('',(-1.637274814712E-002,8.145021095106E-002)); -#37199 = CARTESIAN_POINT('',(-1.92796922164E-002,8.567074749049E-002)); -#37200 = CARTESIAN_POINT('',(-2.25473845886E-002,8.969105478571E-002)); -#37201 = CARTESIAN_POINT('',(-2.644310103763E-002,9.325242515149E-002)); -#37202 = CARTESIAN_POINT('',(-3.068423912412E-002,9.649427277956E-002)); -#37203 = CARTESIAN_POINT('',(-3.531362175499E-002,9.929223100372E-002)); -#37204 = CARTESIAN_POINT('',(-4.026627188147E-002,0.101647716516)); -#37205 = CARTESIAN_POINT('',(-4.554123998918E-002,0.103630777862)); -#37206 = CARTESIAN_POINT('',(-5.116866014043E-002,0.105095123951)); -#37207 = CARTESIAN_POINT('',(-5.71185955331E-002,0.106172268782)); -#37208 = CARTESIAN_POINT('',(-6.339483628172E-002,0.106863752765)); -#37209 = CARTESIAN_POINT('',(-6.769665579598E-002,0.106928870802)); -#37210 = CARTESIAN_POINT('',(-6.98936439097E-002,0.106962127324)); -#37211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37212 = ORIENTED_EDGE('',*,*,#37060,.T.); -#37213 = ADVANCED_FACE('',(#37214),#29016,.T.); -#37214 = FACE_BOUND('',#37215,.T.); -#37215 = EDGE_LOOP('',(#37216,#37217,#37239,#37292)); -#37216 = ORIENTED_EDGE('',*,*,#28968,.F.); -#37217 = ORIENTED_EDGE('',*,*,#37218,.F.); -#37218 = EDGE_CURVE('',#37219,#28941,#37221,.T.); -#37219 = VERTEX_POINT('',#37220); -#37220 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); -#37221 = SURFACE_CURVE('',#37222,(#37226,#37232),.PCURVE_S1.); -#37222 = LINE('',#37223,#37224); -#37223 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); -#37224 = VECTOR('',#37225,1.); -#37225 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37226 = PCURVE('',#29016,#37227); -#37227 = DEFINITIONAL_REPRESENTATION('',(#37228),#37231); -#37228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37229,#37230),.UNSPECIFIED., +#39584 = CARTESIAN_POINT('',(-1.011026426529E-002,5.525619226147E-002)); +#39585 = CARTESIAN_POINT('',(-1.015756701092E-002,5.721385214802E-002)); +#39586 = CARTESIAN_POINT('',(-1.025006959094E-002,6.104214135E-002)); +#39587 = CARTESIAN_POINT('',(-1.103241924814E-002,6.661157694798E-002)); +#39588 = CARTESIAN_POINT('',(-1.232242319587E-002,7.187235993168E-002)); +#39589 = CARTESIAN_POINT('',(-1.412768789087E-002,7.679931825469E-002)); +#39590 = CARTESIAN_POINT('',(-1.637274814712E-002,8.145021095106E-002)); +#39591 = CARTESIAN_POINT('',(-1.92796922164E-002,8.567074749049E-002)); +#39592 = CARTESIAN_POINT('',(-2.25473845886E-002,8.969105478571E-002)); +#39593 = CARTESIAN_POINT('',(-2.644310103763E-002,9.325242515149E-002)); +#39594 = CARTESIAN_POINT('',(-3.068423912412E-002,9.649427277956E-002)); +#39595 = CARTESIAN_POINT('',(-3.531362175499E-002,9.929223100372E-002)); +#39596 = CARTESIAN_POINT('',(-4.026627188147E-002,0.101647716516)); +#39597 = CARTESIAN_POINT('',(-4.554123998918E-002,0.103630777862)); +#39598 = CARTESIAN_POINT('',(-5.116866014043E-002,0.105095123951)); +#39599 = CARTESIAN_POINT('',(-5.71185955331E-002,0.106172268782)); +#39600 = CARTESIAN_POINT('',(-6.339483628172E-002,0.106863752765)); +#39601 = CARTESIAN_POINT('',(-6.769665579598E-002,0.106928870802)); +#39602 = CARTESIAN_POINT('',(-6.98936439097E-002,0.106962127324)); +#39603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39604 = ORIENTED_EDGE('',*,*,#39452,.T.); +#39605 = ADVANCED_FACE('',(#39606),#31408,.T.); +#39606 = FACE_BOUND('',#39607,.T.); +#39607 = EDGE_LOOP('',(#39608,#39609,#39631,#39684)); +#39608 = ORIENTED_EDGE('',*,*,#31360,.F.); +#39609 = ORIENTED_EDGE('',*,*,#39610,.F.); +#39610 = EDGE_CURVE('',#39611,#31333,#39613,.T.); +#39611 = VERTEX_POINT('',#39612); +#39612 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); +#39613 = SURFACE_CURVE('',#39614,(#39618,#39624),.PCURVE_S1.); +#39614 = LINE('',#39615,#39616); +#39615 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); +#39616 = VECTOR('',#39617,1.); +#39617 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#39618 = PCURVE('',#31408,#39619); +#39619 = DEFINITIONAL_REPRESENTATION('',(#39620),#39623); +#39620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39621,#39622),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.E-003),.PIECEWISE_BEZIER_KNOTS.); -#37229 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37230 = CARTESIAN_POINT('',(0.E+000,1.)); -#37231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37232 = PCURVE('',#28956,#37233); -#37233 = DEFINITIONAL_REPRESENTATION('',(#37234),#37238); -#37234 = LINE('',#37235,#37236); -#37235 = CARTESIAN_POINT('',(-3.309138889565E-002,0.E+000)); -#37236 = VECTOR('',#37237,1.); -#37237 = DIRECTION('',(0.E+000,-1.)); -#37238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37239 = ORIENTED_EDGE('',*,*,#37240,.T.); -#37240 = EDGE_CURVE('',#37219,#37140,#37241,.T.); -#37241 = SURFACE_CURVE('',#37242,(#37262,#37269),.PCURVE_S1.); -#37242 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37243,#37244,#37245,#37246, - #37247,#37248,#37249,#37250,#37251,#37252,#37253,#37254,#37255, - #37256,#37257,#37258,#37259,#37260,#37261),.UNSPECIFIED.,.F.,.F.,(4, +#39621 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39622 = CARTESIAN_POINT('',(0.E+000,1.)); +#39623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39624 = PCURVE('',#31348,#39625); +#39625 = DEFINITIONAL_REPRESENTATION('',(#39626),#39630); +#39626 = LINE('',#39627,#39628); +#39627 = CARTESIAN_POINT('',(-3.309138889565E-002,0.E+000)); +#39628 = VECTOR('',#39629,1.); +#39629 = DIRECTION('',(0.E+000,-1.)); +#39630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39631 = ORIENTED_EDGE('',*,*,#39632,.T.); +#39632 = EDGE_CURVE('',#39611,#39532,#39633,.T.); +#39633 = SURFACE_CURVE('',#39634,(#39654,#39661),.PCURVE_S1.); +#39634 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39635,#39636,#39637,#39638, + #39639,#39640,#39641,#39642,#39643,#39644,#39645,#39646,#39647, + #39648,#39649,#39650,#39651,#39652,#39653),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.736133711898E-002, 0.150479832281,0.219977236852,0.286680996862,0.349678494186, 0.410679625017,0.469427113519,0.526755701427,0.583141980835, 0.638824427779,0.695263470404,0.752695804899,0.810849183335, 0.871356303636,0.934436430984,1.),.UNSPECIFIED.); -#37243 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); -#37244 = CARTESIAN_POINT('',(0.194842726066,0.782,-0.258084492877)); -#37245 = CARTESIAN_POINT('',(0.195476906297,0.782,-0.254475714102)); -#37246 = CARTESIAN_POINT('',(0.196685406815,0.782,-0.249251899786)); -#37247 = CARTESIAN_POINT('',(0.198254904982,0.782,-0.244398830275)); -#37248 = CARTESIAN_POINT('',(0.200018408963,0.782,-0.239874475214)); -#37249 = CARTESIAN_POINT('',(0.202114630955,0.782,-0.235726673994)); -#37250 = CARTESIAN_POINT('',(0.20438590485,0.782,-0.231889935001)); -#37251 = CARTESIAN_POINT('',(0.20706440823,0.782,-0.228500450512)); -#37252 = CARTESIAN_POINT('',(0.209880494901,0.782,-0.225380947289)); -#37253 = CARTESIAN_POINT('',(0.2129713652,0.782,-0.222632113258)); -#37254 = CARTESIAN_POINT('',(0.216366843711,0.782,-0.220314751341)); -#37255 = CARTESIAN_POINT('',(0.219972194359,0.782,-0.218292993394)); -#37256 = CARTESIAN_POINT('',(0.223831328955,0.782,-0.216637667807)); -#37257 = CARTESIAN_POINT('',(0.227950162072,0.782,-0.215426056656)); -#37258 = CARTESIAN_POINT('',(0.232276271971,0.782,-0.214467880234)); -#37259 = CARTESIAN_POINT('',(0.236865365146,0.782,-0.213985059654)); -#37260 = CARTESIAN_POINT('',(0.239996472098,0.782,-0.213890117565)); -#37261 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); -#37262 = PCURVE('',#29016,#37263); -#37263 = DEFINITIONAL_REPRESENTATION('',(#37264),#37268); -#37264 = LINE('',#37265,#37266); -#37265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37266 = VECTOR('',#37267,1.); -#37267 = DIRECTION('',(1.,0.E+000)); -#37268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37269 = PCURVE('',#36383,#37270); -#37270 = DEFINITIONAL_REPRESENTATION('',(#37271),#37291); -#37271 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#37272,#37273,#37274,#37275, - #37276,#37277,#37278,#37279,#37280,#37281,#37282,#37283,#37284, - #37285,#37286,#37287,#37288,#37289,#37290),.UNSPECIFIED.,.F.,.F.,(4, +#39635 = CARTESIAN_POINT('',(0.194516695463,0.782,-0.259939757779)); +#39636 = CARTESIAN_POINT('',(0.194842726066,0.782,-0.258084492877)); +#39637 = CARTESIAN_POINT('',(0.195476906297,0.782,-0.254475714102)); +#39638 = CARTESIAN_POINT('',(0.196685406815,0.782,-0.249251899786)); +#39639 = CARTESIAN_POINT('',(0.198254904982,0.782,-0.244398830275)); +#39640 = CARTESIAN_POINT('',(0.200018408963,0.782,-0.239874475214)); +#39641 = CARTESIAN_POINT('',(0.202114630955,0.782,-0.235726673994)); +#39642 = CARTESIAN_POINT('',(0.20438590485,0.782,-0.231889935001)); +#39643 = CARTESIAN_POINT('',(0.20706440823,0.782,-0.228500450512)); +#39644 = CARTESIAN_POINT('',(0.209880494901,0.782,-0.225380947289)); +#39645 = CARTESIAN_POINT('',(0.2129713652,0.782,-0.222632113258)); +#39646 = CARTESIAN_POINT('',(0.216366843711,0.782,-0.220314751341)); +#39647 = CARTESIAN_POINT('',(0.219972194359,0.782,-0.218292993394)); +#39648 = CARTESIAN_POINT('',(0.223831328955,0.782,-0.216637667807)); +#39649 = CARTESIAN_POINT('',(0.227950162072,0.782,-0.215426056656)); +#39650 = CARTESIAN_POINT('',(0.232276271971,0.782,-0.214467880234)); +#39651 = CARTESIAN_POINT('',(0.236865365146,0.782,-0.213985059654)); +#39652 = CARTESIAN_POINT('',(0.239996472098,0.782,-0.213890117565)); +#39653 = CARTESIAN_POINT('',(0.241592248281,0.782,-0.213841730101)); +#39654 = PCURVE('',#31408,#39655); +#39655 = DEFINITIONAL_REPRESENTATION('',(#39656),#39660); +#39656 = LINE('',#39657,#39658); +#39657 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39658 = VECTOR('',#39659,1.); +#39659 = DIRECTION('',(1.,0.E+000)); +#39660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39661 = PCURVE('',#38775,#39662); +#39662 = DEFINITIONAL_REPRESENTATION('',(#39663),#39683); +#39663 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39664,#39665,#39666,#39667, + #39668,#39669,#39670,#39671,#39672,#39673,#39674,#39675,#39676, + #39677,#39678,#39679,#39680,#39681,#39682),.UNSPECIFIED.,.F.,.F.,(4, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.736133711898E-002, 0.150479832281,0.219977236852,0.286680996862,0.349678494186, 0.410679625017,0.469427113519,0.526755701427,0.583141980835, 0.638824427779,0.695263470404,0.752695804899,0.810849183335, 0.871356303636,0.934436430984,1.),.UNSPECIFIED.); -#37272 = CARTESIAN_POINT('',(-5.62082919429E-002,8.180639443372E-003)); -#37273 = CARTESIAN_POINT('',(-5.435302704037E-002,8.506670047131E-003)); -#37274 = CARTESIAN_POINT('',(-5.074424826578E-002,9.140850277194E-003)); -#37275 = CARTESIAN_POINT('',(-4.552043395028E-002,1.034935079609E-002)); -#37276 = CARTESIAN_POINT('',(-4.066736443902E-002,1.191884896238E-002)); -#37277 = CARTESIAN_POINT('',(-3.614300937815E-002,1.368235294392E-002)); -#37278 = CARTESIAN_POINT('',(-3.199520815739E-002,1.577857493578E-002)); -#37279 = CARTESIAN_POINT('',(-2.815846916524E-002,1.804984883104E-002)); -#37280 = CARTESIAN_POINT('',(-2.476898467544E-002,2.072835221057E-002)); -#37281 = CARTESIAN_POINT('',(-2.164948145238E-002,2.354443888135E-002)); -#37282 = CARTESIAN_POINT('',(-1.89006474222E-002,2.663530918047E-002)); -#37283 = CARTESIAN_POINT('',(-1.658328550502E-002,3.003078769211E-002)); -#37284 = CARTESIAN_POINT('',(-1.456152755773E-002,3.363613833984E-002)); -#37285 = CARTESIAN_POINT('',(-1.290620197123E-002,3.749527293545E-002)); -#37286 = CARTESIAN_POINT('',(-1.169459081942E-002,4.161410605221E-002)); -#37287 = CARTESIAN_POINT('',(-1.073641439786E-002,4.594021595199E-002)); -#37288 = CARTESIAN_POINT('',(-1.025359381812E-002,5.052930912665E-002)); -#37289 = CARTESIAN_POINT('',(-1.015865172912E-002,5.366041607857E-002)); -#37290 = CARTESIAN_POINT('',(-1.011026426529E-002,5.525619226147E-002)); -#37291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37292 = ORIENTED_EDGE('',*,*,#37139,.T.); -#37293 = ADVANCED_FACE('',(#37294),#28956,.T.); -#37294 = FACE_BOUND('',#37295,.T.); -#37295 = EDGE_LOOP('',(#37296,#37297,#37298,#37319)); -#37296 = ORIENTED_EDGE('',*,*,#28940,.F.); -#37297 = ORIENTED_EDGE('',*,*,#36411,.F.); -#37298 = ORIENTED_EDGE('',*,*,#37299,.T.); -#37299 = EDGE_CURVE('',#36352,#37219,#37300,.T.); -#37300 = SURFACE_CURVE('',#37301,(#37305,#37312),.PCURVE_S1.); -#37301 = LINE('',#37302,#37303); -#37302 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); -#37303 = VECTOR('',#37304,1.); -#37304 = DIRECTION('',(0.99503719021,0.E+000,-9.9503719021E-002)); -#37305 = PCURVE('',#28956,#37306); -#37306 = DEFINITIONAL_REPRESENTATION('',(#37307),#37311); -#37307 = LINE('',#37308,#37309); -#37308 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#37309 = VECTOR('',#37310,1.); -#37310 = DIRECTION('',(-1.,0.E+000)); -#37311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37312 = PCURVE('',#36383,#37313); -#37313 = DEFINITIONAL_REPRESENTATION('',(#37314),#37318); -#37314 = LINE('',#37315,#37316); -#37315 = CARTESIAN_POINT('',(-5.291557568022E-002,-2.47465231835E-002)); -#37316 = VECTOR('',#37317,1.); -#37317 = DIRECTION('',(-9.9503719021E-002,0.99503719021)); -#37318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37319 = ORIENTED_EDGE('',*,*,#37218,.T.); -#37320 = ADVANCED_FACE('',(#37321),#36383,.T.); -#37321 = FACE_BOUND('',#37322,.T.); -#37322 = EDGE_LOOP('',(#37323,#37324,#37325,#37326,#37327,#37328,#37329, - #37330,#37331,#37332,#37333,#37334,#37335,#37336,#37337,#37338)); -#37323 = ORIENTED_EDGE('',*,*,#36351,.F.); -#37324 = ORIENTED_EDGE('',*,*,#36456,.F.); -#37325 = ORIENTED_EDGE('',*,*,#36519,.F.); -#37326 = ORIENTED_EDGE('',*,*,#36582,.F.); -#37327 = ORIENTED_EDGE('',*,*,#36662,.F.); -#37328 = ORIENTED_EDGE('',*,*,#36727,.F.); -#37329 = ORIENTED_EDGE('',*,*,#36776,.F.); -#37330 = ORIENTED_EDGE('',*,*,#36825,.F.); -#37331 = ORIENTED_EDGE('',*,*,#36874,.F.); -#37332 = ORIENTED_EDGE('',*,*,#36923,.F.); -#37333 = ORIENTED_EDGE('',*,*,#36971,.F.); -#37334 = ORIENTED_EDGE('',*,*,#37018,.F.); -#37335 = ORIENTED_EDGE('',*,*,#37081,.F.); -#37336 = ORIENTED_EDGE('',*,*,#37160,.F.); -#37337 = ORIENTED_EDGE('',*,*,#37240,.F.); -#37338 = ORIENTED_EDGE('',*,*,#37299,.F.); -#37339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37343)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37340,#37341,#37342)) +#39664 = CARTESIAN_POINT('',(-5.62082919429E-002,8.180639443372E-003)); +#39665 = CARTESIAN_POINT('',(-5.435302704037E-002,8.506670047131E-003)); +#39666 = CARTESIAN_POINT('',(-5.074424826578E-002,9.140850277194E-003)); +#39667 = CARTESIAN_POINT('',(-4.552043395028E-002,1.034935079609E-002)); +#39668 = CARTESIAN_POINT('',(-4.066736443902E-002,1.191884896238E-002)); +#39669 = CARTESIAN_POINT('',(-3.614300937815E-002,1.368235294392E-002)); +#39670 = CARTESIAN_POINT('',(-3.199520815739E-002,1.577857493578E-002)); +#39671 = CARTESIAN_POINT('',(-2.815846916524E-002,1.804984883104E-002)); +#39672 = CARTESIAN_POINT('',(-2.476898467544E-002,2.072835221057E-002)); +#39673 = CARTESIAN_POINT('',(-2.164948145238E-002,2.354443888135E-002)); +#39674 = CARTESIAN_POINT('',(-1.89006474222E-002,2.663530918047E-002)); +#39675 = CARTESIAN_POINT('',(-1.658328550502E-002,3.003078769211E-002)); +#39676 = CARTESIAN_POINT('',(-1.456152755773E-002,3.363613833984E-002)); +#39677 = CARTESIAN_POINT('',(-1.290620197123E-002,3.749527293545E-002)); +#39678 = CARTESIAN_POINT('',(-1.169459081942E-002,4.161410605221E-002)); +#39679 = CARTESIAN_POINT('',(-1.073641439786E-002,4.594021595199E-002)); +#39680 = CARTESIAN_POINT('',(-1.025359381812E-002,5.052930912665E-002)); +#39681 = CARTESIAN_POINT('',(-1.015865172912E-002,5.366041607857E-002)); +#39682 = CARTESIAN_POINT('',(-1.011026426529E-002,5.525619226147E-002)); +#39683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39684 = ORIENTED_EDGE('',*,*,#39531,.T.); +#39685 = ADVANCED_FACE('',(#39686),#31348,.T.); +#39686 = FACE_BOUND('',#39687,.T.); +#39687 = EDGE_LOOP('',(#39688,#39689,#39690,#39711)); +#39688 = ORIENTED_EDGE('',*,*,#31332,.F.); +#39689 = ORIENTED_EDGE('',*,*,#38803,.F.); +#39690 = ORIENTED_EDGE('',*,*,#39691,.T.); +#39691 = EDGE_CURVE('',#38744,#39611,#39692,.T.); +#39692 = SURFACE_CURVE('',#39693,(#39697,#39704),.PCURVE_S1.); +#39693 = LINE('',#39694,#39695); +#39694 = CARTESIAN_POINT('',(0.161589532836,0.782,-0.256647041516)); +#39695 = VECTOR('',#39696,1.); +#39696 = DIRECTION('',(0.99503719021,0.E+000,-9.9503719021E-002)); +#39697 = PCURVE('',#31348,#39698); +#39698 = DEFINITIONAL_REPRESENTATION('',(#39699),#39703); +#39699 = LINE('',#39700,#39701); +#39700 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#39701 = VECTOR('',#39702,1.); +#39702 = DIRECTION('',(-1.,0.E+000)); +#39703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39704 = PCURVE('',#38775,#39705); +#39705 = DEFINITIONAL_REPRESENTATION('',(#39706),#39710); +#39706 = LINE('',#39707,#39708); +#39707 = CARTESIAN_POINT('',(-5.291557568022E-002,-2.47465231835E-002)); +#39708 = VECTOR('',#39709,1.); +#39709 = DIRECTION('',(-9.9503719021E-002,0.99503719021)); +#39710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#39711 = ORIENTED_EDGE('',*,*,#39610,.T.); +#39712 = ADVANCED_FACE('',(#39713),#38775,.T.); +#39713 = FACE_BOUND('',#39714,.T.); +#39714 = EDGE_LOOP('',(#39715,#39716,#39717,#39718,#39719,#39720,#39721, + #39722,#39723,#39724,#39725,#39726,#39727,#39728,#39729,#39730)); +#39715 = ORIENTED_EDGE('',*,*,#38743,.F.); +#39716 = ORIENTED_EDGE('',*,*,#38848,.F.); +#39717 = ORIENTED_EDGE('',*,*,#38911,.F.); +#39718 = ORIENTED_EDGE('',*,*,#38974,.F.); +#39719 = ORIENTED_EDGE('',*,*,#39054,.F.); +#39720 = ORIENTED_EDGE('',*,*,#39119,.F.); +#39721 = ORIENTED_EDGE('',*,*,#39168,.F.); +#39722 = ORIENTED_EDGE('',*,*,#39217,.F.); +#39723 = ORIENTED_EDGE('',*,*,#39266,.F.); +#39724 = ORIENTED_EDGE('',*,*,#39315,.F.); +#39725 = ORIENTED_EDGE('',*,*,#39363,.F.); +#39726 = ORIENTED_EDGE('',*,*,#39410,.F.); +#39727 = ORIENTED_EDGE('',*,*,#39473,.F.); +#39728 = ORIENTED_EDGE('',*,*,#39552,.F.); +#39729 = ORIENTED_EDGE('',*,*,#39632,.F.); +#39730 = ORIENTED_EDGE('',*,*,#39691,.F.); +#39731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39735)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39732,#39733,#39734)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37340 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37341 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37342 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37343 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#37340, +#39732 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39733 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39734 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39735 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#39732, 'distance_accuracy_value','confusion accuracy'); -#37344 = SHAPE_DEFINITION_REPRESENTATION(#37345,#28832); -#37345 = PRODUCT_DEFINITION_SHAPE('','',#37346); -#37346 = PRODUCT_DEFINITION('design','',#37347,#37350); -#37347 = PRODUCT_DEFINITION_FORMATION('','',#37348); -#37348 = PRODUCT('0805_SMD_Capacitor','0805_SMD_Capacitor','',(#37349)); -#37349 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37350 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37351 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37352,#37354); -#37352 = ( REPRESENTATION_RELATIONSHIP('','',#28832,#28822) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37353) +#39736 = SHAPE_DEFINITION_REPRESENTATION(#39737,#31224); +#39737 = PRODUCT_DEFINITION_SHAPE('','',#39738); +#39738 = PRODUCT_DEFINITION('design','',#39739,#39742); +#39739 = PRODUCT_DEFINITION_FORMATION('','',#39740); +#39740 = PRODUCT('0805_SMD_Capacitor','0805_SMD_Capacitor','',(#39741)); +#39741 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39742 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39743 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39744,#39746); +#39744 = ( REPRESENTATION_RELATIONSHIP('','',#31224,#31214) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39745) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37353 = ITEM_DEFINED_TRANSFORMATION('','',#11,#28823); -#37354 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37355); -#37355 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('196','=>[0:1:1:45]','',#28817, - #37346,$); -#37356 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37348)); -#37357 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37358,#37360); -#37358 = ( REPRESENTATION_RELATIONSHIP('','',#28822,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37359) +#39745 = ITEM_DEFINED_TRANSFORMATION('','',#11,#31215); +#39746 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39747); +#39747 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('297','=>[0:1:1:45]','',#31209, + #39738,$); +#39748 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39740)); +#39749 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39750,#39752); +#39750 = ( REPRESENTATION_RELATIONSHIP('','',#31214,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39751) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37359 = ITEM_DEFINED_TRANSFORMATION('','',#11,#123); -#37360 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37361); -#37361 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('197','=>[0:1:1:44]','',#5, - #28817,$); -#37362 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#28819)); -#37363 = SHAPE_DEFINITION_REPRESENTATION(#37364,#37370); -#37364 = PRODUCT_DEFINITION_SHAPE('','',#37365); -#37365 = PRODUCT_DEFINITION('design','',#37366,#37369); -#37366 = PRODUCT_DEFINITION_FORMATION('','',#37367); -#37367 = PRODUCT('C4','C4','',(#37368)); -#37368 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37369 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37370 = SHAPE_REPRESENTATION('',(#11,#37371),#37375); -#37371 = AXIS2_PLACEMENT_3D('',#37372,#37373,#37374); -#37372 = CARTESIAN_POINT('',(24.38406858,23.62208128,1.27E-002)); -#37373 = DIRECTION('',(-2.449212707645E-016,-1.,1.110223024625E-016)); -#37374 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#37375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37379)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37376,#37377,#37378)) +#39751 = ITEM_DEFINED_TRANSFORMATION('','',#11,#123); +#39752 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39753); +#39753 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('298','=>[0:1:1:44]','',#5, + #31209,$); +#39754 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#31211)); +#39755 = SHAPE_DEFINITION_REPRESENTATION(#39756,#39762); +#39756 = PRODUCT_DEFINITION_SHAPE('','',#39757); +#39757 = PRODUCT_DEFINITION('design','',#39758,#39761); +#39758 = PRODUCT_DEFINITION_FORMATION('','',#39759); +#39759 = PRODUCT('C4','C4','',(#39760)); +#39760 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39761 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39762 = SHAPE_REPRESENTATION('',(#11,#39763),#39767); +#39763 = AXIS2_PLACEMENT_3D('',#39764,#39765,#39766); +#39764 = CARTESIAN_POINT('',(24.38406858,23.62208128,1.27E-002)); +#39765 = DIRECTION('',(-2.449212707645E-016,-1.,1.110223024625E-016)); +#39766 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#39767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39771)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39768,#39769,#39770)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37376 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37377 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37378 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37379 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#37376, +#39768 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39769 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39770 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39771 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#39768, 'distance_accuracy_value','confusion accuracy'); -#37380 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37381,#37383); -#37381 = ( REPRESENTATION_RELATIONSHIP('','',#28832,#37370) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37382) +#39772 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39773,#39775); +#39773 = ( REPRESENTATION_RELATIONSHIP('','',#31224,#39762) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39774) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37382 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37371); -#37383 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37384); -#37384 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('198','=>[0:1:1:45]','',#37365, - #37346,$); -#37385 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37386,#37388); -#37386 = ( REPRESENTATION_RELATIONSHIP('','',#37370,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37387) +#39774 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39763); +#39775 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39776); +#39776 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('299','=>[0:1:1:45]','',#39757, + #39738,$); +#39777 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39778,#39780); +#39778 = ( REPRESENTATION_RELATIONSHIP('','',#39762,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39779) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37387 = ITEM_DEFINED_TRANSFORMATION('','',#11,#127); -#37388 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37389); -#37389 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('199','=>[0:1:1:46]','',#5, - #37365,$); -#37390 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37367)); -#37391 = SHAPE_DEFINITION_REPRESENTATION(#37392,#37398); -#37392 = PRODUCT_DEFINITION_SHAPE('','',#37393); -#37393 = PRODUCT_DEFINITION('design','',#37394,#37397); -#37394 = PRODUCT_DEFINITION_FORMATION('','',#37395); -#37395 = PRODUCT('C5','C5','',(#37396)); -#37396 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37397 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37398 = SHAPE_REPRESENTATION('',(#11,#37399),#37403); -#37399 = AXIS2_PLACEMENT_3D('',#37400,#37401,#37402); -#37400 = CARTESIAN_POINT('',(24.38408128,22.2250635,1.27E-002)); -#37401 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37402 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#37403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37407)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37404,#37405,#37406)) +#39779 = ITEM_DEFINED_TRANSFORMATION('','',#11,#127); +#39780 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39781); +#39781 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('300','=>[0:1:1:46]','',#5, + #39757,$); +#39782 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39759)); +#39783 = SHAPE_DEFINITION_REPRESENTATION(#39784,#39790); +#39784 = PRODUCT_DEFINITION_SHAPE('','',#39785); +#39785 = PRODUCT_DEFINITION('design','',#39786,#39789); +#39786 = PRODUCT_DEFINITION_FORMATION('','',#39787); +#39787 = PRODUCT('C5','C5','',(#39788)); +#39788 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39789 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39790 = SHAPE_REPRESENTATION('',(#11,#39791),#39795); +#39791 = AXIS2_PLACEMENT_3D('',#39792,#39793,#39794); +#39792 = CARTESIAN_POINT('',(24.38408128,22.2250635,1.27E-002)); +#39793 = DIRECTION('',(0.E+000,0.E+000,1.)); +#39794 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#39795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39799)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39796,#39797,#39798)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37404 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37405 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37406 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37407 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#37404, +#39796 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39797 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39798 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39799 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#39796, 'distance_accuracy_value','confusion accuracy'); -#37408 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37409,#37411); -#37409 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#37398) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37410) +#39800 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39801,#39803); +#39801 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#39790) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39802) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37410 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37399); -#37411 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37412); -#37412 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('200','=>[0:1:1:18]','',#37393, - #11876,$); -#37413 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37414,#37416); -#37414 = ( REPRESENTATION_RELATIONSHIP('','',#37398,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37415) +#39802 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39791); +#39803 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39804); +#39804 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('301','=>[0:1:1:18]','',#39785, + #14268,$); +#39805 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39806,#39808); +#39806 = ( REPRESENTATION_RELATIONSHIP('','',#39790,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39807) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37415 = ITEM_DEFINED_TRANSFORMATION('','',#11,#131); -#37416 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37417); -#37417 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('201','=>[0:1:1:47]','',#5, - #37393,$); -#37418 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37395)); -#37419 = SHAPE_DEFINITION_REPRESENTATION(#37420,#37426); -#37420 = PRODUCT_DEFINITION_SHAPE('','',#37421); -#37421 = PRODUCT_DEFINITION('design','',#37422,#37425); -#37422 = PRODUCT_DEFINITION_FORMATION('','',#37423); -#37423 = PRODUCT('C8','C8','',(#37424)); -#37424 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37425 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37426 = SHAPE_REPRESENTATION('',(#11,#37427),#37431); -#37427 = AXIS2_PLACEMENT_3D('',#37428,#37429,#37430); -#37428 = CARTESIAN_POINT('',(22.0980635,26.28891872,1.27E-002)); -#37429 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37430 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#37431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37435)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37432,#37433,#37434)) +#39807 = ITEM_DEFINED_TRANSFORMATION('','',#11,#131); +#39808 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39809); +#39809 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('302','=>[0:1:1:47]','',#5, + #39785,$); +#39810 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39787)); +#39811 = SHAPE_DEFINITION_REPRESENTATION(#39812,#39818); +#39812 = PRODUCT_DEFINITION_SHAPE('','',#39813); +#39813 = PRODUCT_DEFINITION('design','',#39814,#39817); +#39814 = PRODUCT_DEFINITION_FORMATION('','',#39815); +#39815 = PRODUCT('C8','C8','',(#39816)); +#39816 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39817 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39818 = SHAPE_REPRESENTATION('',(#11,#39819),#39823); +#39819 = AXIS2_PLACEMENT_3D('',#39820,#39821,#39822); +#39820 = CARTESIAN_POINT('',(22.0980635,26.28891872,1.27E-002)); +#39821 = DIRECTION('',(0.E+000,0.E+000,1.)); +#39822 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#39823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39827)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39824,#39825,#39826)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37432 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37433 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37434 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37435 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#37432, +#39824 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39825 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39826 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39827 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#39824, 'distance_accuracy_value','confusion accuracy'); -#37436 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37437,#37439); -#37437 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#37426) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37438) +#39828 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39829,#39831); +#39829 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#39818) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39830) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37438 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37427); -#37439 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37440); -#37440 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('202','=>[0:1:1:18]','',#37421, - #11876,$); -#37441 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37442,#37444); -#37442 = ( REPRESENTATION_RELATIONSHIP('','',#37426,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37443) +#39830 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39819); +#39831 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39832); +#39832 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('303','=>[0:1:1:18]','',#39813, + #14268,$); +#39833 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39834,#39836); +#39834 = ( REPRESENTATION_RELATIONSHIP('','',#39818,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39835) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37443 = ITEM_DEFINED_TRANSFORMATION('','',#11,#135); -#37444 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37445); -#37445 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('203','=>[0:1:1:48]','',#5, - #37421,$); -#37446 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37423)); -#37447 = SHAPE_DEFINITION_REPRESENTATION(#37448,#37454); -#37448 = PRODUCT_DEFINITION_SHAPE('','',#37449); -#37449 = PRODUCT_DEFINITION('design','',#37450,#37453); -#37450 = PRODUCT_DEFINITION_FORMATION('','',#37451); -#37451 = PRODUCT('C13','C13','',(#37452)); -#37452 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37453 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37454 = SHAPE_REPRESENTATION('',(#11,#37455),#37459); -#37455 = AXIS2_PLACEMENT_3D('',#37456,#37457,#37458); -#37456 = CARTESIAN_POINT('',(25.7809365,19.68508128,1.27E-002)); -#37457 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37458 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#37459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37463)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37460,#37461,#37462)) +#39835 = ITEM_DEFINED_TRANSFORMATION('','',#11,#135); +#39836 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39837); +#39837 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('304','=>[0:1:1:48]','',#5, + #39813,$); +#39838 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39815)); +#39839 = SHAPE_DEFINITION_REPRESENTATION(#39840,#39846); +#39840 = PRODUCT_DEFINITION_SHAPE('','',#39841); +#39841 = PRODUCT_DEFINITION('design','',#39842,#39845); +#39842 = PRODUCT_DEFINITION_FORMATION('','',#39843); +#39843 = PRODUCT('C13','C13','',(#39844)); +#39844 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39845 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39846 = SHAPE_REPRESENTATION('',(#11,#39847),#39851); +#39847 = AXIS2_PLACEMENT_3D('',#39848,#39849,#39850); +#39848 = CARTESIAN_POINT('',(25.7809365,19.68508128,1.27E-002)); +#39849 = DIRECTION('',(0.E+000,0.E+000,1.)); +#39850 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#39851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39855)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39852,#39853,#39854)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37460 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37461 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37462 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37463 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#37460, +#39852 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39853 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39854 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39855 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#39852, 'distance_accuracy_value','confusion accuracy'); -#37464 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37465,#37467); -#37465 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#37454) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37466) +#39856 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39857,#39859); +#39857 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#39846) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39858) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37466 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37455); -#37467 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37468); -#37468 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('204','=>[0:1:1:18]','',#37449, - #11876,$); -#37469 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37470,#37472); -#37470 = ( REPRESENTATION_RELATIONSHIP('','',#37454,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37471) +#39858 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39847); +#39859 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39860); +#39860 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('305','=>[0:1:1:18]','',#39841, + #14268,$); +#39861 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39862,#39864); +#39862 = ( REPRESENTATION_RELATIONSHIP('','',#39846,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39863) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37471 = ITEM_DEFINED_TRANSFORMATION('','',#11,#139); -#37472 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37473); -#37473 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('205','=>[0:1:1:49]','',#5, - #37449,$); -#37474 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37451)); -#37475 = SHAPE_DEFINITION_REPRESENTATION(#37476,#37482); -#37476 = PRODUCT_DEFINITION_SHAPE('','',#37477); -#37477 = PRODUCT_DEFINITION('design','',#37478,#37481); -#37478 = PRODUCT_DEFINITION_FORMATION('','',#37479); -#37479 = PRODUCT('C38','C38','',(#37480)); -#37480 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37481 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37482 = SHAPE_REPRESENTATION('',(#11,#37483),#37487); -#37483 = AXIS2_PLACEMENT_3D('',#37484,#37485,#37486); -#37484 = CARTESIAN_POINT('',(6.4770635,6.34991872,1.27E-002)); -#37485 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37486 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#37487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37491)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37488,#37489,#37490)) +#39863 = ITEM_DEFINED_TRANSFORMATION('','',#11,#139); +#39864 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39865); +#39865 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('306','=>[0:1:1:49]','',#5, + #39841,$); +#39866 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39843)); +#39867 = SHAPE_DEFINITION_REPRESENTATION(#39868,#39874); +#39868 = PRODUCT_DEFINITION_SHAPE('','',#39869); +#39869 = PRODUCT_DEFINITION('design','',#39870,#39873); +#39870 = PRODUCT_DEFINITION_FORMATION('','',#39871); +#39871 = PRODUCT('C38','C38','',(#39872)); +#39872 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39873 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39874 = SHAPE_REPRESENTATION('',(#11,#39875),#39879); +#39875 = AXIS2_PLACEMENT_3D('',#39876,#39877,#39878); +#39876 = CARTESIAN_POINT('',(6.4770635,6.34991872,1.27E-002)); +#39877 = DIRECTION('',(0.E+000,0.E+000,1.)); +#39878 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#39879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39883)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39880,#39881,#39882)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37488 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37489 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37490 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37491 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#37488, +#39880 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39881 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39882 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39883 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#39880, 'distance_accuracy_value','confusion accuracy'); -#37492 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37493,#37495); -#37493 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#37482) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37494) +#39884 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39885,#39887); +#39885 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#39874) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39886) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37494 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37483); -#37495 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37496); -#37496 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('206','=>[0:1:1:18]','',#37477, - #11876,$); -#37497 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37498,#37500); -#37498 = ( REPRESENTATION_RELATIONSHIP('','',#37482,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37499) +#39886 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39875); +#39887 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39888); +#39888 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('307','=>[0:1:1:18]','',#39869, + #14268,$); +#39889 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39890,#39892); +#39890 = ( REPRESENTATION_RELATIONSHIP('','',#39874,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39891) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37499 = ITEM_DEFINED_TRANSFORMATION('','',#11,#143); -#37500 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37501); -#37501 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('207','=>[0:1:1:50]','',#5, - #37477,$); -#37502 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37479)); -#37503 = SHAPE_DEFINITION_REPRESENTATION(#37504,#37510); -#37504 = PRODUCT_DEFINITION_SHAPE('','',#37505); -#37505 = PRODUCT_DEFINITION('design','',#37506,#37509); -#37506 = PRODUCT_DEFINITION_FORMATION('','',#37507); -#37507 = PRODUCT('CONN1','CONN1','',(#37508)); -#37508 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37509 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37510 = SHAPE_REPRESENTATION('',(#11,#37511),#37515); -#37511 = AXIS2_PLACEMENT_3D('',#37512,#37513,#37514); -#37512 = CARTESIAN_POINT('',(22.606,4.4030011,-1.94818)); -#37513 = DIRECTION('',(1.224606353822E-016,-1.,1.143833291972E-017)); -#37514 = DIRECTION('',(-1.,-1.224606353822E-016,1.499660721822E-032)); -#37515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37519)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37516,#37517,#37518)) +#39891 = ITEM_DEFINED_TRANSFORMATION('','',#11,#143); +#39892 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39893); +#39893 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('308','=>[0:1:1:50]','',#5, + #39869,$); +#39894 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39871)); +#39895 = SHAPE_DEFINITION_REPRESENTATION(#39896,#39902); +#39896 = PRODUCT_DEFINITION_SHAPE('','',#39897); +#39897 = PRODUCT_DEFINITION('design','',#39898,#39901); +#39898 = PRODUCT_DEFINITION_FORMATION('','',#39899); +#39899 = PRODUCT('CONN1','CONN1','',(#39900)); +#39900 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39901 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39902 = SHAPE_REPRESENTATION('',(#11,#39903),#39907); +#39903 = AXIS2_PLACEMENT_3D('',#39904,#39905,#39906); +#39904 = CARTESIAN_POINT('',(22.606,4.4030011,-1.3589)); +#39905 = DIRECTION('',(1.224606353822E-016,-1.,1.143833291972E-017)); +#39906 = DIRECTION('',(-1.,-1.224606353822E-016,1.499660721822E-032)); +#39907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39911)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39908,#39909,#39910)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37516 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37517 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37518 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37519 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#37516, +#39908 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39909 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39910 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39911 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#39908, 'distance_accuracy_value','confusion accuracy'); -#37520 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37521,#37523); -#37521 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#37510) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37522) +#39912 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39913,#39915); +#39913 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#39902) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39914) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37522 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37511); -#37523 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37524); -#37524 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('208','=>[0:1:1:31]','',#37505, - #28462,$); -#37525 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37526,#37528); -#37526 = ( REPRESENTATION_RELATIONSHIP('','',#37510,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37527) +#39914 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39903); +#39915 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39916); +#39916 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('309','=>[0:1:1:31]','',#39897, + #30854,$); +#39917 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39918,#39920); +#39918 = ( REPRESENTATION_RELATIONSHIP('','',#39902,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39919) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37527 = ITEM_DEFINED_TRANSFORMATION('','',#11,#147); -#37528 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37529); -#37529 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('209','=>[0:1:1:51]','',#5, - #37505,$); -#37530 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37507)); -#37531 = SHAPE_DEFINITION_REPRESENTATION(#37532,#37538); -#37532 = PRODUCT_DEFINITION_SHAPE('','',#37533); -#37533 = PRODUCT_DEFINITION('design','',#37534,#37537); -#37534 = PRODUCT_DEFINITION_FORMATION('','',#37535); -#37535 = PRODUCT('CONN2','CONN2','',(#37536)); -#37536 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37537 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37538 = SHAPE_REPRESENTATION('',(#11,#37539),#37543); -#37539 = AXIS2_PLACEMENT_3D('',#37540,#37541,#37542); -#37540 = CARTESIAN_POINT('',(4.4030011,24.892,-0.3175)); -#37541 = DIRECTION('',(-1.,2.22044604925E-016,1.110223024625E-016)); -#37542 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#37543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37547)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37544,#37545,#37546)) +#39919 = ITEM_DEFINED_TRANSFORMATION('','',#11,#147); +#39920 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39921); +#39921 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('310','=>[0:1:1:51]','',#5, + #39897,$); +#39922 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39899)); +#39923 = SHAPE_DEFINITION_REPRESENTATION(#39924,#39930); +#39924 = PRODUCT_DEFINITION_SHAPE('','',#39925); +#39925 = PRODUCT_DEFINITION('design','',#39926,#39929); +#39926 = PRODUCT_DEFINITION_FORMATION('','',#39927); +#39927 = PRODUCT('CONN2','CONN2','',(#39928)); +#39928 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39929 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39930 = SHAPE_REPRESENTATION('',(#11,#39931),#39935); +#39931 = AXIS2_PLACEMENT_3D('',#39932,#39933,#39934); +#39932 = CARTESIAN_POINT('',(4.4030011,24.892,-0.3175)); +#39933 = DIRECTION('',(-1.,2.22044604925E-016,1.110223024625E-016)); +#39934 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#39935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39939)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39936,#39937,#39938)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37544 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37545 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37546 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37547 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#37544, +#39936 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39937 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39938 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39939 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#39936, 'distance_accuracy_value','confusion accuracy'); -#37548 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37549,#37551); -#37549 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#37538) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37550) +#39940 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39941,#39943); +#39941 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#39930) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39942) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37550 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37539); -#37551 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37552); -#37552 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('210','=>[0:1:1:31]','',#37533, - #28462,$); -#37553 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37554,#37556); -#37554 = ( REPRESENTATION_RELATIONSHIP('','',#37538,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37555) +#39942 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39931); +#39943 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39944); +#39944 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('311','=>[0:1:1:31]','',#39925, + #30854,$); +#39945 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39946,#39948); +#39946 = ( REPRESENTATION_RELATIONSHIP('','',#39930,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39947) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37555 = ITEM_DEFINED_TRANSFORMATION('','',#11,#151); -#37556 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37557); -#37557 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('211','=>[0:1:1:52]','',#5, - #37533,$); -#37558 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37535)); -#37559 = SHAPE_DEFINITION_REPRESENTATION(#37560,#37566); -#37560 = PRODUCT_DEFINITION_SHAPE('','',#37561); -#37561 = PRODUCT_DEFINITION('design','',#37562,#37565); -#37562 = PRODUCT_DEFINITION_FORMATION('','',#37563); -#37563 = PRODUCT('CONN3','CONN3','',(#37564)); -#37564 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37565 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37566 = SHAPE_REPRESENTATION('',(#11,#37567),#37571); -#37567 = AXIS2_PLACEMENT_3D('',#37568,#37569,#37570); -#37568 = CARTESIAN_POINT('',(10.541,31.9189989,-0.3175)); -#37569 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); -#37570 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#37571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37575)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37572,#37573,#37574)) +#39947 = ITEM_DEFINED_TRANSFORMATION('','',#11,#151); +#39948 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39949); +#39949 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('312','=>[0:1:1:52]','',#5, + #39925,$); +#39950 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39927)); +#39951 = SHAPE_DEFINITION_REPRESENTATION(#39952,#39958); +#39952 = PRODUCT_DEFINITION_SHAPE('','',#39953); +#39953 = PRODUCT_DEFINITION('design','',#39954,#39957); +#39954 = PRODUCT_DEFINITION_FORMATION('','',#39955); +#39955 = PRODUCT('CONN3','CONN3','',(#39956)); +#39956 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39957 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39958 = SHAPE_REPRESENTATION('',(#11,#39959),#39963); +#39959 = AXIS2_PLACEMENT_3D('',#39960,#39961,#39962); +#39960 = CARTESIAN_POINT('',(10.541,31.9189989,-0.3175)); +#39961 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); +#39962 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#39963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39967)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39964,#39965,#39966)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37572 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37573 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37574 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37575 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#37572, +#39964 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39965 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39966 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39967 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#39964, 'distance_accuracy_value','confusion accuracy'); -#37576 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37577,#37579); -#37577 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#37566) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37578) +#39968 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39969,#39971); +#39969 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#39958) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39970) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37578 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37567); -#37579 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37580); -#37580 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('212','=>[0:1:1:31]','',#37561, - #28462,$); -#37581 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#37582,#37584); -#37582 = ( REPRESENTATION_RELATIONSHIP('','',#37566,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#37583) +#39970 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39959); +#39971 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39972); +#39972 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('313','=>[0:1:1:31]','',#39953, + #30854,$); +#39973 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#39974,#39976); +#39974 = ( REPRESENTATION_RELATIONSHIP('','',#39958,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#39975) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#37583 = ITEM_DEFINED_TRANSFORMATION('','',#11,#155); -#37584 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #37585); -#37585 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('213','=>[0:1:1:53]','',#5, - #37561,$); -#37586 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37563)); -#37587 = SHAPE_DEFINITION_REPRESENTATION(#37588,#37594); -#37588 = PRODUCT_DEFINITION_SHAPE('','',#37589); -#37589 = PRODUCT_DEFINITION('design','',#37590,#37593); -#37590 = PRODUCT_DEFINITION_FORMATION('','',#37591); -#37591 = PRODUCT('CONN4','CONN4','',(#37592)); -#37592 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37593 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37594 = SHAPE_REPRESENTATION('',(#11,#37595),#37599); -#37595 = AXIS2_PLACEMENT_3D('',#37596,#37597,#37598); -#37596 = CARTESIAN_POINT('',(2.20140022,14.3256,1.2827)); -#37597 = DIRECTION('',(-1.,2.22044604925E-016,1.110223024625E-016)); -#37598 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#37599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37603)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37600,#37601,#37602)) +#39975 = ITEM_DEFINED_TRANSFORMATION('','',#11,#155); +#39976 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #39977); +#39977 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('314','=>[0:1:1:53]','',#5, + #39953,$); +#39978 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39955)); +#39979 = SHAPE_DEFINITION_REPRESENTATION(#39980,#39986); +#39980 = PRODUCT_DEFINITION_SHAPE('','',#39981); +#39981 = PRODUCT_DEFINITION('design','',#39982,#39985); +#39982 = PRODUCT_DEFINITION_FORMATION('','',#39983); +#39983 = PRODUCT('CONN4','CONN4','',(#39984)); +#39984 = PRODUCT_CONTEXT('',#2,'mechanical'); +#39985 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#39986 = SHAPE_REPRESENTATION('',(#11,#39987),#39991); +#39987 = AXIS2_PLACEMENT_3D('',#39988,#39989,#39990); +#39988 = CARTESIAN_POINT('',(2.20140022,14.3256,1.2827)); +#39989 = DIRECTION('',(-1.,2.22044604925E-016,1.110223024625E-016)); +#39990 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#39991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#39995)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#39992,#39993,#39994)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37600 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37601 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37602 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37603 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#37600, +#39992 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#39993 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#39994 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#39995 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#39992, 'distance_accuracy_value','confusion accuracy'); -#37604 = SHAPE_DEFINITION_REPRESENTATION(#37605,#37611); -#37605 = PRODUCT_DEFINITION_SHAPE('','',#37606); -#37606 = PRODUCT_DEFINITION('design','',#37607,#37610); -#37607 = PRODUCT_DEFINITION_FORMATION('','',#37608); -#37608 = PRODUCT('473460001','473460001','',(#37609)); -#37609 = PRODUCT_CONTEXT('',#2,'mechanical'); -#37610 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#37611 = SHAPE_REPRESENTATION('',(#11,#37612,#37616),#37620); -#37612 = AXIS2_PLACEMENT_3D('',#37613,#37614,#37615); -#37613 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#37614 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37615 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37616 = AXIS2_PLACEMENT_3D('',#37617,#37618,#37619); -#37617 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#37618 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37619 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#37624)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#37621,#37622,#37623)) +#39996 = SHAPE_DEFINITION_REPRESENTATION(#39997,#40003); +#39997 = PRODUCT_DEFINITION_SHAPE('','',#39998); +#39998 = PRODUCT_DEFINITION('design','',#39999,#40002); +#39999 = PRODUCT_DEFINITION_FORMATION('','',#40000); +#40000 = PRODUCT('473460001','473460001','',(#40001)); +#40001 = PRODUCT_CONTEXT('',#2,'mechanical'); +#40002 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#40003 = SHAPE_REPRESENTATION('',(#11,#40004,#40008),#40012); +#40004 = AXIS2_PLACEMENT_3D('',#40005,#40006,#40007); +#40005 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#40006 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40007 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40008 = AXIS2_PLACEMENT_3D('',#40009,#40010,#40011); +#40009 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#40010 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40011 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#40016)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#40013,#40014,#40015)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#37621 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#37622 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#37623 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#37624 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#37621, +#40013 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#40014 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#40015 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#40016 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#40013, 'distance_accuracy_value','confusion accuracy'); -#37625 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#37626),#70769); -#37626 = MANIFOLD_SOLID_BREP('',#37627); -#37627 = CLOSED_SHELL('',(#37628,#37980,#38332,#38502,#38672,#38831, - #38990,#39111,#39233,#39348,#39417,#39468,#39612,#39638,#39835, - #39904,#40012,#40207,#40256,#40436,#40627,#40653,#40872,#40898, - #41046,#41848,#42731,#42919,#43022,#43154,#44435,#44510,#44643, - #44691,#44740,#45300,#45397,#45467,#45537,#45607,#45655,#45752, - #45851,#45920,#45947,#45997,#46046,#46073,#46120,#46167,#46194, - #46263,#46333,#46381,#46456,#46505,#46575,#46623,#46698,#46932, - #47009,#47118,#47194,#48404,#48512,#48560,#48632,#48720,#48818, - #48946,#49021,#50313,#50384,#50434,#50443,#50469,#50495,#50522, - #50549,#50576,#50603,#50629,#50655,#50662,#50736,#50834,#50961, - #51010,#51037,#51129,#51177,#51208,#51236,#51262,#51288,#51315, - #51342,#51369,#51396,#51422,#51448,#51455,#51462,#51545,#51751, - #52134,#52313,#52340,#52367,#52547,#52707,#52828,#52950,#52977, - #53363,#53613,#53734,#53827,#53898,#53946,#53953,#53960,#53967, - #53993,#54116,#54237,#54354,#54476,#54593,#54689,#54851,#54877, - #55096,#55122,#55196,#55845,#56541,#56617,#56693,#56742,#56791, - #56840,#56889,#57081,#57200,#57319,#57511,#57580,#57606,#57632, - #57658,#57707,#57754,#57781,#57808,#57835,#57862,#57869,#57918, - #57944,#57970,#57996,#58103,#58224,#58430,#58552,#58667,#58783, - #58879,#58908,#58939,#58966,#59039,#59065,#59072,#59098,#59147, - #59156,#59182,#59208,#59215,#59241,#59267,#59293,#59322,#59348, - #59374,#59424,#59473,#59546,#59733,#60342,#60418,#60546,#60702, - #60858,#61014,#61141,#61240,#61287,#61314,#61361,#61408,#61455, - #61482,#61509,#61540,#61810,#62080,#62290,#62338,#62364,#62390, - #62523,#62571,#62676,#62836,#62930,#62957,#62983,#63029,#63104, - #63228,#63413,#63439,#63465,#63491,#63518,#63525,#63574,#63602, - #63651,#63658,#63686,#63693,#63719,#63745,#63771,#63798,#63805, - #63855,#63883,#63964,#64043,#64092,#64140,#64235,#64287,#64313, - #64390,#64416,#64443,#64469,#64495,#64502,#64509,#64537,#64563, - #64589,#64661,#64734,#64829,#64855,#64881,#64888,#64958,#64965, - #64991,#65017,#65024,#65031,#65107,#65212,#65282,#65289,#65362, - #65389,#65415,#65422,#65498,#65603,#65693,#65700,#65773,#65800, - #65826,#65833,#65840,#65916,#66021,#66111,#66118,#66191,#66218, - #66244,#66251,#66258,#66334,#66439,#66529,#66536,#66609,#66636, - #66662,#66669,#66676,#66752,#66857,#66927,#66934,#67007,#67034, - #67060,#67067,#67093,#67214,#67240,#67438,#67470,#67478,#67510, - #67536,#67562,#67607,#67633,#67659,#67685,#67711,#67737,#67763, - #67770,#67777,#67803,#67883,#67909,#67957,#67965,#68025,#68070, - #68143,#68150,#68181,#68258,#68359,#68429,#68437,#68445,#68452, - #68478,#68523,#68549,#68575,#68601,#68627,#68653,#68679,#68705, - #68712,#68719,#68745,#68754,#68780,#68904,#68975,#69023,#69073, - #69082,#69089,#69160,#69208,#69215,#69222,#69229,#69256,#69263, - #69441,#69561,#69609,#69703,#69775,#69804,#69831,#69840,#69910, - #69958,#70028,#70077,#70103,#70109,#70188,#70257,#70284,#70314, - #70321,#70400,#70469,#70496,#70526,#70533,#70612,#70681,#70708, - #70738,#70745,#70755,#70762)); -#37628 = ADVANCED_FACE('',(#37629),#37643,.T.); -#37629 = FACE_BOUND('',#37630,.F.); -#37630 = EDGE_LOOP('',(#37631,#37666,#37694,#37726,#37754,#37786,#37814, - #37842,#37870,#37898,#37926,#37954)); -#37631 = ORIENTED_EDGE('',*,*,#37632,.T.); -#37632 = EDGE_CURVE('',#37633,#37635,#37637,.T.); -#37633 = VERTEX_POINT('',#37634); -#37634 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); -#37635 = VERTEX_POINT('',#37636); -#37636 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.35)); -#37637 = SURFACE_CURVE('',#37638,(#37642,#37654),.PCURVE_S1.); -#37638 = LINE('',#37639,#37640); -#37639 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); -#37640 = VECTOR('',#37641,1.); -#37641 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37642 = PCURVE('',#37643,#37648); -#37643 = PLANE('',#37644); -#37644 = AXIS2_PLACEMENT_3D('',#37645,#37646,#37647); -#37645 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); -#37646 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37647 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37648 = DEFINITIONAL_REPRESENTATION('',(#37649),#37653); -#37649 = LINE('',#37650,#37651); -#37650 = CARTESIAN_POINT('',(-3.75,2.5E-002)); -#37651 = VECTOR('',#37652,1.); -#37652 = DIRECTION('',(1.,0.E+000)); -#37653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37654 = PCURVE('',#37655,#37660); -#37655 = PLANE('',#37656); -#37656 = AXIS2_PLACEMENT_3D('',#37657,#37658,#37659); -#37657 = CARTESIAN_POINT('',(0.E+000,2.5E-002,0.E+000)); -#37658 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37659 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37660 = DEFINITIONAL_REPRESENTATION('',(#37661),#37665); -#37661 = LINE('',#37662,#37663); -#37662 = CARTESIAN_POINT('',(-3.75,2.35)); -#37663 = VECTOR('',#37664,1.); -#37664 = DIRECTION('',(1.,0.E+000)); -#37665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37666 = ORIENTED_EDGE('',*,*,#37667,.F.); -#37667 = EDGE_CURVE('',#37668,#37635,#37670,.T.); -#37668 = VERTEX_POINT('',#37669); -#37669 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); -#37670 = SURFACE_CURVE('',#37671,(#37675,#37682),.PCURVE_S1.); -#37671 = LINE('',#37672,#37673); -#37672 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); -#37673 = VECTOR('',#37674,1.); -#37674 = DIRECTION('',(0.E+000,1.,0.E+000)); -#37675 = PCURVE('',#37643,#37676); -#37676 = DEFINITIONAL_REPRESENTATION('',(#37677),#37681); -#37677 = LINE('',#37678,#37679); -#37678 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002)); -#37679 = VECTOR('',#37680,1.); -#37680 = DIRECTION('',(0.E+000,1.)); -#37681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37682 = PCURVE('',#37683,#37688); -#37683 = PLANE('',#37684); -#37684 = AXIS2_PLACEMENT_3D('',#37685,#37686,#37687); -#37685 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); -#37686 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37687 = DIRECTION('',(0.E+000,1.,0.E+000)); -#37688 = DEFINITIONAL_REPRESENTATION('',(#37689),#37693); -#37689 = LINE('',#37690,#37691); -#37690 = CARTESIAN_POINT('',(0.E+000,4.7)); -#37691 = VECTOR('',#37692,1.); -#37692 = DIRECTION('',(1.,0.E+000)); -#37693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37694 = ORIENTED_EDGE('',*,*,#37695,.F.); -#37695 = EDGE_CURVE('',#37696,#37668,#37698,.T.); -#37696 = VERTEX_POINT('',#37697); -#37697 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,2.35)); -#37698 = SURFACE_CURVE('',#37699,(#37704,#37715),.PCURVE_S1.); -#37699 = CIRCLE('',#37700,0.25); -#37700 = AXIS2_PLACEMENT_3D('',#37701,#37702,#37703); -#37701 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,2.35)); -#37702 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#37703 = DIRECTION('',(-0.707106781186,-0.707106781187,0.E+000)); -#37704 = PCURVE('',#37643,#37705); -#37705 = DEFINITIONAL_REPRESENTATION('',(#37706),#37714); -#37706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#37707,#37708,#37709,#37710 - ,#37711,#37712,#37713),.UNSPECIFIED.,.F.,.F.) +#40017 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#40018),#73161); +#40018 = MANIFOLD_SOLID_BREP('',#40019); +#40019 = CLOSED_SHELL('',(#40020,#40372,#40724,#40894,#41064,#41223, + #41382,#41503,#41625,#41740,#41809,#41860,#42004,#42030,#42227, + #42296,#42404,#42599,#42648,#42828,#43019,#43045,#43264,#43290, + #43438,#44240,#45123,#45311,#45414,#45546,#46827,#46902,#47035, + #47083,#47132,#47692,#47789,#47859,#47929,#47999,#48047,#48144, + #48243,#48312,#48339,#48389,#48438,#48465,#48512,#48559,#48586, + #48655,#48725,#48773,#48848,#48897,#48967,#49015,#49090,#49324, + #49401,#49510,#49586,#50796,#50904,#50952,#51024,#51112,#51210, + #51338,#51413,#52705,#52776,#52826,#52835,#52861,#52887,#52914, + #52941,#52968,#52995,#53021,#53047,#53054,#53128,#53226,#53353, + #53402,#53429,#53521,#53569,#53600,#53628,#53654,#53680,#53707, + #53734,#53761,#53788,#53814,#53840,#53847,#53854,#53937,#54143, + #54526,#54705,#54732,#54759,#54939,#55099,#55220,#55342,#55369, + #55755,#56005,#56126,#56219,#56290,#56338,#56345,#56352,#56359, + #56385,#56508,#56629,#56746,#56868,#56985,#57081,#57243,#57269, + #57488,#57514,#57588,#58237,#58933,#59009,#59085,#59134,#59183, + #59232,#59281,#59473,#59592,#59711,#59903,#59972,#59998,#60024, + #60050,#60099,#60146,#60173,#60200,#60227,#60254,#60261,#60310, + #60336,#60362,#60388,#60495,#60616,#60822,#60944,#61059,#61175, + #61271,#61300,#61331,#61358,#61431,#61457,#61464,#61490,#61539, + #61548,#61574,#61600,#61607,#61633,#61659,#61685,#61714,#61740, + #61766,#61816,#61865,#61938,#62125,#62734,#62810,#62938,#63094, + #63250,#63406,#63533,#63632,#63679,#63706,#63753,#63800,#63847, + #63874,#63901,#63932,#64202,#64472,#64682,#64730,#64756,#64782, + #64915,#64963,#65068,#65228,#65322,#65349,#65375,#65421,#65496, + #65620,#65805,#65831,#65857,#65883,#65910,#65917,#65966,#65994, + #66043,#66050,#66078,#66085,#66111,#66137,#66163,#66190,#66197, + #66247,#66275,#66356,#66435,#66484,#66532,#66627,#66679,#66705, + #66782,#66808,#66835,#66861,#66887,#66894,#66901,#66929,#66955, + #66981,#67053,#67126,#67221,#67247,#67273,#67280,#67350,#67357, + #67383,#67409,#67416,#67423,#67499,#67604,#67674,#67681,#67754, + #67781,#67807,#67814,#67890,#67995,#68085,#68092,#68165,#68192, + #68218,#68225,#68232,#68308,#68413,#68503,#68510,#68583,#68610, + #68636,#68643,#68650,#68726,#68831,#68921,#68928,#69001,#69028, + #69054,#69061,#69068,#69144,#69249,#69319,#69326,#69399,#69426, + #69452,#69459,#69485,#69606,#69632,#69830,#69862,#69870,#69902, + #69928,#69954,#69999,#70025,#70051,#70077,#70103,#70129,#70155, + #70162,#70169,#70195,#70275,#70301,#70349,#70357,#70417,#70462, + #70535,#70542,#70573,#70650,#70751,#70821,#70829,#70837,#70844, + #70870,#70915,#70941,#70967,#70993,#71019,#71045,#71071,#71097, + #71104,#71111,#71137,#71146,#71172,#71296,#71367,#71415,#71465, + #71474,#71481,#71552,#71600,#71607,#71614,#71621,#71648,#71655, + #71833,#71953,#72001,#72095,#72167,#72196,#72223,#72232,#72302, + #72350,#72420,#72469,#72495,#72501,#72580,#72649,#72676,#72706, + #72713,#72792,#72861,#72888,#72918,#72925,#73004,#73073,#73100, + #73130,#73137,#73147,#73154)); +#40020 = ADVANCED_FACE('',(#40021),#40035,.T.); +#40021 = FACE_BOUND('',#40022,.F.); +#40022 = EDGE_LOOP('',(#40023,#40058,#40086,#40118,#40146,#40178,#40206, + #40234,#40262,#40290,#40318,#40346)); +#40023 = ORIENTED_EDGE('',*,*,#40024,.T.); +#40024 = EDGE_CURVE('',#40025,#40027,#40029,.T.); +#40025 = VERTEX_POINT('',#40026); +#40026 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); +#40027 = VERTEX_POINT('',#40028); +#40028 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.35)); +#40029 = SURFACE_CURVE('',#40030,(#40034,#40046),.PCURVE_S1.); +#40030 = LINE('',#40031,#40032); +#40031 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); +#40032 = VECTOR('',#40033,1.); +#40033 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40034 = PCURVE('',#40035,#40040); +#40035 = PLANE('',#40036); +#40036 = AXIS2_PLACEMENT_3D('',#40037,#40038,#40039); +#40037 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); +#40038 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40039 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40040 = DEFINITIONAL_REPRESENTATION('',(#40041),#40045); +#40041 = LINE('',#40042,#40043); +#40042 = CARTESIAN_POINT('',(-3.75,2.5E-002)); +#40043 = VECTOR('',#40044,1.); +#40044 = DIRECTION('',(1.,0.E+000)); +#40045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40046 = PCURVE('',#40047,#40052); +#40047 = PLANE('',#40048); +#40048 = AXIS2_PLACEMENT_3D('',#40049,#40050,#40051); +#40049 = CARTESIAN_POINT('',(0.E+000,2.5E-002,0.E+000)); +#40050 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40051 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40052 = DEFINITIONAL_REPRESENTATION('',(#40053),#40057); +#40053 = LINE('',#40054,#40055); +#40054 = CARTESIAN_POINT('',(-3.75,2.35)); +#40055 = VECTOR('',#40056,1.); +#40056 = DIRECTION('',(1.,0.E+000)); +#40057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40058 = ORIENTED_EDGE('',*,*,#40059,.F.); +#40059 = EDGE_CURVE('',#40060,#40027,#40062,.T.); +#40060 = VERTEX_POINT('',#40061); +#40061 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); +#40062 = SURFACE_CURVE('',#40063,(#40067,#40074),.PCURVE_S1.); +#40063 = LINE('',#40064,#40065); +#40064 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); +#40065 = VECTOR('',#40066,1.); +#40066 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40067 = PCURVE('',#40035,#40068); +#40068 = DEFINITIONAL_REPRESENTATION('',(#40069),#40073); +#40069 = LINE('',#40070,#40071); +#40070 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002)); +#40071 = VECTOR('',#40072,1.); +#40072 = DIRECTION('',(0.E+000,1.)); +#40073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40074 = PCURVE('',#40075,#40080); +#40075 = PLANE('',#40076); +#40076 = AXIS2_PLACEMENT_3D('',#40077,#40078,#40079); +#40077 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); +#40078 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40079 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40080 = DEFINITIONAL_REPRESENTATION('',(#40081),#40085); +#40081 = LINE('',#40082,#40083); +#40082 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40083 = VECTOR('',#40084,1.); +#40084 = DIRECTION('',(1.,0.E+000)); +#40085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40086 = ORIENTED_EDGE('',*,*,#40087,.F.); +#40087 = EDGE_CURVE('',#40088,#40060,#40090,.T.); +#40088 = VERTEX_POINT('',#40089); +#40089 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,2.35)); +#40090 = SURFACE_CURVE('',#40091,(#40096,#40107),.PCURVE_S1.); +#40091 = CIRCLE('',#40092,0.25); +#40092 = AXIS2_PLACEMENT_3D('',#40093,#40094,#40095); +#40093 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,2.35)); +#40094 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40095 = DIRECTION('',(-0.707106781186,-0.707106781187,0.E+000)); +#40096 = PCURVE('',#40035,#40097); +#40097 = DEFINITIONAL_REPRESENTATION('',(#40098),#40106); +#40098 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40099,#40100,#40101,#40102 + ,#40103,#40104,#40105),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#37707 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703)); -#37708 = CARTESIAN_POINT('',(-3.682962913145,5.79629131445E-002)); -#37709 = CARTESIAN_POINT('',(-3.264704761276,0.170034847166)); -#37710 = CARTESIAN_POINT('',(-2.846446609407,0.282106781187)); -#37711 = CARTESIAN_POINT('',(-2.958518543428,-0.136151370682)); -#37712 = CARTESIAN_POINT('',(-3.070590477449,-0.554409522551)); -#37713 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703)); -#37714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37715 = PCURVE('',#37716,#37721); -#37716 = CYLINDRICAL_SURFACE('',#37717,0.25); -#37717 = AXIS2_PLACEMENT_3D('',#37718,#37719,#37720); -#37718 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#37719 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37720 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37721 = DEFINITIONAL_REPRESENTATION('',(#37722),#37725); -#37722 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37723,#37724),.UNSPECIFIED., +#40099 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703)); +#40100 = CARTESIAN_POINT('',(-3.682962913145,5.79629131445E-002)); +#40101 = CARTESIAN_POINT('',(-3.264704761276,0.170034847166)); +#40102 = CARTESIAN_POINT('',(-2.846446609407,0.282106781187)); +#40103 = CARTESIAN_POINT('',(-2.958518543428,-0.136151370682)); +#40104 = CARTESIAN_POINT('',(-3.070590477449,-0.554409522551)); +#40105 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703)); +#40106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40107 = PCURVE('',#40108,#40113); +#40108 = CYLINDRICAL_SURFACE('',#40109,0.25); +#40109 = AXIS2_PLACEMENT_3D('',#40110,#40111,#40112); +#40110 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#40111 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40112 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40113 = DEFINITIONAL_REPRESENTATION('',(#40114),#40117); +#40114 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40115,#40116),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163398),.PIECEWISE_BEZIER_KNOTS.); -#37723 = CARTESIAN_POINT('',(3.926990816987,4.7)); -#37724 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#37725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37726 = ORIENTED_EDGE('',*,*,#37727,.F.); -#37727 = EDGE_CURVE('',#37728,#37696,#37730,.T.); -#37728 = VERTEX_POINT('',#37729); -#37729 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,2.35)); -#37730 = SURFACE_CURVE('',#37731,(#37735,#37742),.PCURVE_S1.); -#37731 = LINE('',#37732,#37733); -#37732 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,2.35)); -#37733 = VECTOR('',#37734,1.); -#37734 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#37735 = PCURVE('',#37643,#37736); -#37736 = DEFINITIONAL_REPRESENTATION('',(#37737),#37741); -#37737 = LINE('',#37738,#37739); -#37738 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297)); -#37739 = VECTOR('',#37740,1.); -#37740 = DIRECTION('',(-0.707106781187,0.707106781187)); -#37741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37742 = PCURVE('',#37743,#37748); -#37743 = PLANE('',#37744); -#37744 = AXIS2_PLACEMENT_3D('',#37745,#37746,#37747); -#37745 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-2.35)); -#37746 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#37747 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#37748 = DEFINITIONAL_REPRESENTATION('',(#37749),#37753); -#37749 = LINE('',#37750,#37751); -#37750 = CARTESIAN_POINT('',(0.E+000,4.7)); -#37751 = VECTOR('',#37752,1.); -#37752 = DIRECTION('',(1.,0.E+000)); -#37753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37754 = ORIENTED_EDGE('',*,*,#37755,.F.); -#37755 = EDGE_CURVE('',#37756,#37728,#37758,.T.); -#37756 = VERTEX_POINT('',#37757); -#37757 = CARTESIAN_POINT('',(-2.596446609407,-0.925,2.35)); -#37758 = SURFACE_CURVE('',#37759,(#37764,#37775),.PCURVE_S1.); -#37759 = CIRCLE('',#37760,0.25); -#37760 = AXIS2_PLACEMENT_3D('',#37761,#37762,#37763); -#37761 = CARTESIAN_POINT('',(-2.596446609407,-0.675,2.35)); -#37762 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#37763 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37764 = PCURVE('',#37643,#37765); -#37765 = DEFINITIONAL_REPRESENTATION('',(#37766),#37774); -#37766 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#37767,#37768,#37769,#37770 - ,#37771,#37772,#37773),.UNSPECIFIED.,.F.,.F.) +#40115 = CARTESIAN_POINT('',(3.926990816987,4.7)); +#40116 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#40117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40118 = ORIENTED_EDGE('',*,*,#40119,.F.); +#40119 = EDGE_CURVE('',#40120,#40088,#40122,.T.); +#40120 = VERTEX_POINT('',#40121); +#40121 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,2.35)); +#40122 = SURFACE_CURVE('',#40123,(#40127,#40134),.PCURVE_S1.); +#40123 = LINE('',#40124,#40125); +#40124 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,2.35)); +#40125 = VECTOR('',#40126,1.); +#40126 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#40127 = PCURVE('',#40035,#40128); +#40128 = DEFINITIONAL_REPRESENTATION('',(#40129),#40133); +#40129 = LINE('',#40130,#40131); +#40130 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297)); +#40131 = VECTOR('',#40132,1.); +#40132 = DIRECTION('',(-0.707106781187,0.707106781187)); +#40133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40134 = PCURVE('',#40135,#40140); +#40135 = PLANE('',#40136); +#40136 = AXIS2_PLACEMENT_3D('',#40137,#40138,#40139); +#40137 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-2.35)); +#40138 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#40139 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#40140 = DEFINITIONAL_REPRESENTATION('',(#40141),#40145); +#40141 = LINE('',#40142,#40143); +#40142 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40143 = VECTOR('',#40144,1.); +#40144 = DIRECTION('',(1.,0.E+000)); +#40145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40146 = ORIENTED_EDGE('',*,*,#40147,.F.); +#40147 = EDGE_CURVE('',#40148,#40120,#40150,.T.); +#40148 = VERTEX_POINT('',#40149); +#40149 = CARTESIAN_POINT('',(-2.596446609407,-0.925,2.35)); +#40150 = SURFACE_CURVE('',#40151,(#40156,#40167),.PCURVE_S1.); +#40151 = CIRCLE('',#40152,0.25); +#40152 = AXIS2_PLACEMENT_3D('',#40153,#40154,#40155); +#40153 = CARTESIAN_POINT('',(-2.596446609407,-0.675,2.35)); +#40154 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40155 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40156 = PCURVE('',#40035,#40157); +#40157 = DEFINITIONAL_REPRESENTATION('',(#40158),#40166); +#40158 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40159,#40160,#40161,#40162 + ,#40163,#40164,#40165),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#37767 = CARTESIAN_POINT('',(-2.596446609407,-0.925)); -#37768 = CARTESIAN_POINT('',(-3.029459311299,-0.925)); -#37769 = CARTESIAN_POINT('',(-2.812952960353,-0.55)); -#37770 = CARTESIAN_POINT('',(-2.596446609407,-0.175)); -#37771 = CARTESIAN_POINT('',(-2.379940258461,-0.55)); -#37772 = CARTESIAN_POINT('',(-2.163433907515,-0.925)); -#37773 = CARTESIAN_POINT('',(-2.596446609407,-0.925)); -#37774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37775 = PCURVE('',#37776,#37781); -#37776 = CYLINDRICAL_SURFACE('',#37777,0.25); -#37777 = AXIS2_PLACEMENT_3D('',#37778,#37779,#37780); -#37778 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); -#37779 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37780 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37781 = DEFINITIONAL_REPRESENTATION('',(#37782),#37785); -#37782 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37783,#37784),.UNSPECIFIED., +#40159 = CARTESIAN_POINT('',(-2.596446609407,-0.925)); +#40160 = CARTESIAN_POINT('',(-3.029459311299,-0.925)); +#40161 = CARTESIAN_POINT('',(-2.812952960353,-0.55)); +#40162 = CARTESIAN_POINT('',(-2.596446609407,-0.175)); +#40163 = CARTESIAN_POINT('',(-2.379940258461,-0.55)); +#40164 = CARTESIAN_POINT('',(-2.163433907515,-0.925)); +#40165 = CARTESIAN_POINT('',(-2.596446609407,-0.925)); +#40166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40167 = PCURVE('',#40168,#40173); +#40168 = CYLINDRICAL_SURFACE('',#40169,0.25); +#40169 = AXIS2_PLACEMENT_3D('',#40170,#40171,#40172); +#40170 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); +#40171 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40172 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40173 = DEFINITIONAL_REPRESENTATION('',(#40174),#40177); +#40174 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40175,#40176),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#37783 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#37784 = CARTESIAN_POINT('',(3.926990816989,4.7)); -#37785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37786 = ORIENTED_EDGE('',*,*,#37787,.F.); -#37787 = EDGE_CURVE('',#37788,#37756,#37790,.T.); -#37788 = VERTEX_POINT('',#37789); -#37789 = CARTESIAN_POINT('',(-2.5,-0.925,2.35)); -#37790 = SURFACE_CURVE('',#37791,(#37795,#37802),.PCURVE_S1.); -#37791 = LINE('',#37792,#37793); -#37792 = CARTESIAN_POINT('',(-2.5,-0.925,2.35)); -#37793 = VECTOR('',#37794,1.); -#37794 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#37795 = PCURVE('',#37643,#37796); -#37796 = DEFINITIONAL_REPRESENTATION('',(#37797),#37801); -#37797 = LINE('',#37798,#37799); -#37798 = CARTESIAN_POINT('',(-2.5,-0.925)); -#37799 = VECTOR('',#37800,1.); -#37800 = DIRECTION('',(-1.,0.E+000)); -#37801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37802 = PCURVE('',#37803,#37808); -#37803 = PLANE('',#37804); -#37804 = AXIS2_PLACEMENT_3D('',#37805,#37806,#37807); -#37805 = CARTESIAN_POINT('',(2.596446609407,-0.925,-2.35)); -#37806 = DIRECTION('',(0.E+000,1.,0.E+000)); -#37807 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#37808 = DEFINITIONAL_REPRESENTATION('',(#37809),#37813); -#37809 = LINE('',#37810,#37811); -#37810 = CARTESIAN_POINT('',(5.096446609407,4.7)); -#37811 = VECTOR('',#37812,1.); -#37812 = DIRECTION('',(1.,0.E+000)); -#37813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37814 = ORIENTED_EDGE('',*,*,#37815,.F.); -#37815 = EDGE_CURVE('',#37816,#37788,#37818,.T.); -#37816 = VERTEX_POINT('',#37817); -#37817 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); -#37818 = SURFACE_CURVE('',#37819,(#37823,#37830),.PCURVE_S1.); -#37819 = LINE('',#37820,#37821); -#37820 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); -#37821 = VECTOR('',#37822,1.); -#37822 = DIRECTION('',(0.E+000,1.,0.E+000)); -#37823 = PCURVE('',#37643,#37824); -#37824 = DEFINITIONAL_REPRESENTATION('',(#37825),#37829); -#37825 = LINE('',#37826,#37827); -#37826 = CARTESIAN_POINT('',(-2.5,-1.225)); -#37827 = VECTOR('',#37828,1.); -#37828 = DIRECTION('',(0.E+000,1.)); -#37829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37830 = PCURVE('',#37831,#37836); -#37831 = PLANE('',#37832); -#37832 = AXIS2_PLACEMENT_3D('',#37833,#37834,#37835); -#37833 = CARTESIAN_POINT('',(-2.5,0.E+000,0.E+000)); -#37834 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#37835 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37836 = DEFINITIONAL_REPRESENTATION('',(#37837),#37841); -#37837 = LINE('',#37838,#37839); -#37838 = CARTESIAN_POINT('',(2.35,-1.225)); -#37839 = VECTOR('',#37840,1.); -#37840 = DIRECTION('',(0.E+000,1.)); -#37841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37842 = ORIENTED_EDGE('',*,*,#37843,.F.); -#37843 = EDGE_CURVE('',#37844,#37816,#37846,.T.); -#37844 = VERTEX_POINT('',#37845); -#37845 = CARTESIAN_POINT('',(-2.596446609407,-1.225,2.35)); -#37846 = SURFACE_CURVE('',#37847,(#37851,#37858),.PCURVE_S1.); -#37847 = LINE('',#37848,#37849); -#37848 = CARTESIAN_POINT('',(-2.596446609407,-1.225,2.35)); -#37849 = VECTOR('',#37850,1.); -#37850 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37851 = PCURVE('',#37643,#37852); -#37852 = DEFINITIONAL_REPRESENTATION('',(#37853),#37857); -#37853 = LINE('',#37854,#37855); -#37854 = CARTESIAN_POINT('',(-2.596446609407,-1.225)); -#37855 = VECTOR('',#37856,1.); -#37856 = DIRECTION('',(1.,0.E+000)); -#37857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37858 = PCURVE('',#37859,#37864); -#37859 = PLANE('',#37860); -#37860 = AXIS2_PLACEMENT_3D('',#37861,#37862,#37863); -#37861 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-2.35)); -#37862 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37863 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37864 = DEFINITIONAL_REPRESENTATION('',(#37865),#37869); -#37865 = LINE('',#37866,#37867); -#37866 = CARTESIAN_POINT('',(0.E+000,4.7)); -#37867 = VECTOR('',#37868,1.); -#37868 = DIRECTION('',(1.,0.E+000)); -#37869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37870 = ORIENTED_EDGE('',*,*,#37871,.F.); -#37871 = EDGE_CURVE('',#37872,#37844,#37874,.T.); -#37872 = VERTEX_POINT('',#37873); -#37873 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,2.35)); -#37874 = SURFACE_CURVE('',#37875,(#37880,#37887),.PCURVE_S1.); -#37875 = CIRCLE('',#37876,0.55); -#37876 = AXIS2_PLACEMENT_3D('',#37877,#37878,#37879); -#37877 = CARTESIAN_POINT('',(-2.596446609407,-0.675,2.35)); -#37878 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37879 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#37880 = PCURVE('',#37643,#37881); -#37881 = DEFINITIONAL_REPRESENTATION('',(#37882),#37886); -#37882 = CIRCLE('',#37883,0.55); -#37883 = AXIS2_PLACEMENT_2D('',#37884,#37885); -#37884 = CARTESIAN_POINT('',(-2.596446609407,-0.675)); -#37885 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#37886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37887 = PCURVE('',#37888,#37893); -#37888 = CYLINDRICAL_SURFACE('',#37889,0.55); -#37889 = AXIS2_PLACEMENT_3D('',#37890,#37891,#37892); -#37890 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); -#37891 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37892 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37893 = DEFINITIONAL_REPRESENTATION('',(#37894),#37897); -#37894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37895,#37896),.UNSPECIFIED., +#40175 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#40176 = CARTESIAN_POINT('',(3.926990816989,4.7)); +#40177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40178 = ORIENTED_EDGE('',*,*,#40179,.F.); +#40179 = EDGE_CURVE('',#40180,#40148,#40182,.T.); +#40180 = VERTEX_POINT('',#40181); +#40181 = CARTESIAN_POINT('',(-2.5,-0.925,2.35)); +#40182 = SURFACE_CURVE('',#40183,(#40187,#40194),.PCURVE_S1.); +#40183 = LINE('',#40184,#40185); +#40184 = CARTESIAN_POINT('',(-2.5,-0.925,2.35)); +#40185 = VECTOR('',#40186,1.); +#40186 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40187 = PCURVE('',#40035,#40188); +#40188 = DEFINITIONAL_REPRESENTATION('',(#40189),#40193); +#40189 = LINE('',#40190,#40191); +#40190 = CARTESIAN_POINT('',(-2.5,-0.925)); +#40191 = VECTOR('',#40192,1.); +#40192 = DIRECTION('',(-1.,0.E+000)); +#40193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40194 = PCURVE('',#40195,#40200); +#40195 = PLANE('',#40196); +#40196 = AXIS2_PLACEMENT_3D('',#40197,#40198,#40199); +#40197 = CARTESIAN_POINT('',(2.596446609407,-0.925,-2.35)); +#40198 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40199 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40200 = DEFINITIONAL_REPRESENTATION('',(#40201),#40205); +#40201 = LINE('',#40202,#40203); +#40202 = CARTESIAN_POINT('',(5.096446609407,4.7)); +#40203 = VECTOR('',#40204,1.); +#40204 = DIRECTION('',(1.,0.E+000)); +#40205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40206 = ORIENTED_EDGE('',*,*,#40207,.F.); +#40207 = EDGE_CURVE('',#40208,#40180,#40210,.T.); +#40208 = VERTEX_POINT('',#40209); +#40209 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); +#40210 = SURFACE_CURVE('',#40211,(#40215,#40222),.PCURVE_S1.); +#40211 = LINE('',#40212,#40213); +#40212 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); +#40213 = VECTOR('',#40214,1.); +#40214 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40215 = PCURVE('',#40035,#40216); +#40216 = DEFINITIONAL_REPRESENTATION('',(#40217),#40221); +#40217 = LINE('',#40218,#40219); +#40218 = CARTESIAN_POINT('',(-2.5,-1.225)); +#40219 = VECTOR('',#40220,1.); +#40220 = DIRECTION('',(0.E+000,1.)); +#40221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40222 = PCURVE('',#40223,#40228); +#40223 = PLANE('',#40224); +#40224 = AXIS2_PLACEMENT_3D('',#40225,#40226,#40227); +#40225 = CARTESIAN_POINT('',(-2.5,0.E+000,0.E+000)); +#40226 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40227 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40228 = DEFINITIONAL_REPRESENTATION('',(#40229),#40233); +#40229 = LINE('',#40230,#40231); +#40230 = CARTESIAN_POINT('',(2.35,-1.225)); +#40231 = VECTOR('',#40232,1.); +#40232 = DIRECTION('',(0.E+000,1.)); +#40233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40234 = ORIENTED_EDGE('',*,*,#40235,.F.); +#40235 = EDGE_CURVE('',#40236,#40208,#40238,.T.); +#40236 = VERTEX_POINT('',#40237); +#40237 = CARTESIAN_POINT('',(-2.596446609407,-1.225,2.35)); +#40238 = SURFACE_CURVE('',#40239,(#40243,#40250),.PCURVE_S1.); +#40239 = LINE('',#40240,#40241); +#40240 = CARTESIAN_POINT('',(-2.596446609407,-1.225,2.35)); +#40241 = VECTOR('',#40242,1.); +#40242 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40243 = PCURVE('',#40035,#40244); +#40244 = DEFINITIONAL_REPRESENTATION('',(#40245),#40249); +#40245 = LINE('',#40246,#40247); +#40246 = CARTESIAN_POINT('',(-2.596446609407,-1.225)); +#40247 = VECTOR('',#40248,1.); +#40248 = DIRECTION('',(1.,0.E+000)); +#40249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40250 = PCURVE('',#40251,#40256); +#40251 = PLANE('',#40252); +#40252 = AXIS2_PLACEMENT_3D('',#40253,#40254,#40255); +#40253 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-2.35)); +#40254 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40255 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40256 = DEFINITIONAL_REPRESENTATION('',(#40257),#40261); +#40257 = LINE('',#40258,#40259); +#40258 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40259 = VECTOR('',#40260,1.); +#40260 = DIRECTION('',(1.,0.E+000)); +#40261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40262 = ORIENTED_EDGE('',*,*,#40263,.F.); +#40263 = EDGE_CURVE('',#40264,#40236,#40266,.T.); +#40264 = VERTEX_POINT('',#40265); +#40265 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,2.35)); +#40266 = SURFACE_CURVE('',#40267,(#40272,#40279),.PCURVE_S1.); +#40267 = CIRCLE('',#40268,0.55); +#40268 = AXIS2_PLACEMENT_3D('',#40269,#40270,#40271); +#40269 = CARTESIAN_POINT('',(-2.596446609407,-0.675,2.35)); +#40270 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40271 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#40272 = PCURVE('',#40035,#40273); +#40273 = DEFINITIONAL_REPRESENTATION('',(#40274),#40278); +#40274 = CIRCLE('',#40275,0.55); +#40275 = AXIS2_PLACEMENT_2D('',#40276,#40277); +#40276 = CARTESIAN_POINT('',(-2.596446609407,-0.675)); +#40277 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#40278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40279 = PCURVE('',#40280,#40285); +#40280 = CYLINDRICAL_SURFACE('',#40281,0.55); +#40281 = AXIS2_PLACEMENT_3D('',#40282,#40283,#40284); +#40282 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); +#40283 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40284 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40285 = DEFINITIONAL_REPRESENTATION('',(#40286),#40289); +#40286 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40287,#40288),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#37895 = CARTESIAN_POINT('',(3.926990816987,4.7)); -#37896 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#37897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37898 = ORIENTED_EDGE('',*,*,#37899,.F.); -#37899 = EDGE_CURVE('',#37900,#37872,#37902,.T.); -#37900 = VERTEX_POINT('',#37901); -#37901 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,2.35)); -#37902 = SURFACE_CURVE('',#37903,(#37907,#37914),.PCURVE_S1.); -#37903 = LINE('',#37904,#37905); -#37904 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,2.35)); -#37905 = VECTOR('',#37906,1.); -#37906 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#37907 = PCURVE('',#37643,#37908); -#37908 = DEFINITIONAL_REPRESENTATION('',(#37909),#37913); -#37909 = LINE('',#37910,#37911); -#37910 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059)); -#37911 = VECTOR('',#37912,1.); -#37912 = DIRECTION('',(0.707106781187,-0.707106781187)); -#37913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37914 = PCURVE('',#37915,#37920); -#37915 = PLANE('',#37916); -#37916 = AXIS2_PLACEMENT_3D('',#37917,#37918,#37919); -#37917 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); -#37918 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#37919 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#37920 = DEFINITIONAL_REPRESENTATION('',(#37921),#37925); -#37921 = LINE('',#37922,#37923); -#37922 = CARTESIAN_POINT('',(0.E+000,4.7)); -#37923 = VECTOR('',#37924,1.); -#37924 = DIRECTION('',(1.,0.E+000)); -#37925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37926 = ORIENTED_EDGE('',*,*,#37927,.F.); -#37927 = EDGE_CURVE('',#37928,#37900,#37930,.T.); -#37928 = VERTEX_POINT('',#37929); -#37929 = CARTESIAN_POINT('',(-3.75,-7.144660940672E-002,2.35)); -#37930 = SURFACE_CURVE('',#37931,(#37936,#37943),.PCURVE_S1.); -#37931 = CIRCLE('',#37932,0.55); -#37932 = AXIS2_PLACEMENT_3D('',#37933,#37934,#37935); -#37933 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,2.35)); -#37934 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37935 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#37936 = PCURVE('',#37643,#37937); -#37937 = DEFINITIONAL_REPRESENTATION('',(#37938),#37942); -#37938 = CIRCLE('',#37939,0.55); -#37939 = AXIS2_PLACEMENT_2D('',#37940,#37941); -#37940 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002)); -#37941 = DIRECTION('',(-1.,0.E+000)); -#37942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37943 = PCURVE('',#37944,#37949); -#37944 = CYLINDRICAL_SURFACE('',#37945,0.55); -#37945 = AXIS2_PLACEMENT_3D('',#37946,#37947,#37948); -#37946 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#37947 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37948 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37949 = DEFINITIONAL_REPRESENTATION('',(#37950),#37953); -#37950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#37951,#37952),.UNSPECIFIED., +#40287 = CARTESIAN_POINT('',(3.926990816987,4.7)); +#40288 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#40289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40290 = ORIENTED_EDGE('',*,*,#40291,.F.); +#40291 = EDGE_CURVE('',#40292,#40264,#40294,.T.); +#40292 = VERTEX_POINT('',#40293); +#40293 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,2.35)); +#40294 = SURFACE_CURVE('',#40295,(#40299,#40306),.PCURVE_S1.); +#40295 = LINE('',#40296,#40297); +#40296 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,2.35)); +#40297 = VECTOR('',#40298,1.); +#40298 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#40299 = PCURVE('',#40035,#40300); +#40300 = DEFINITIONAL_REPRESENTATION('',(#40301),#40305); +#40301 = LINE('',#40302,#40303); +#40302 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059)); +#40303 = VECTOR('',#40304,1.); +#40304 = DIRECTION('',(0.707106781187,-0.707106781187)); +#40305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40306 = PCURVE('',#40307,#40312); +#40307 = PLANE('',#40308); +#40308 = AXIS2_PLACEMENT_3D('',#40309,#40310,#40311); +#40309 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); +#40310 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#40311 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#40312 = DEFINITIONAL_REPRESENTATION('',(#40313),#40317); +#40313 = LINE('',#40314,#40315); +#40314 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40315 = VECTOR('',#40316,1.); +#40316 = DIRECTION('',(1.,0.E+000)); +#40317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40318 = ORIENTED_EDGE('',*,*,#40319,.F.); +#40319 = EDGE_CURVE('',#40320,#40292,#40322,.T.); +#40320 = VERTEX_POINT('',#40321); +#40321 = CARTESIAN_POINT('',(-3.75,-7.144660940672E-002,2.35)); +#40322 = SURFACE_CURVE('',#40323,(#40328,#40335),.PCURVE_S1.); +#40323 = CIRCLE('',#40324,0.55); +#40324 = AXIS2_PLACEMENT_3D('',#40325,#40326,#40327); +#40325 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,2.35)); +#40326 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40327 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40328 = PCURVE('',#40035,#40329); +#40329 = DEFINITIONAL_REPRESENTATION('',(#40330),#40334); +#40330 = CIRCLE('',#40331,0.55); +#40331 = AXIS2_PLACEMENT_2D('',#40332,#40333); +#40332 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002)); +#40333 = DIRECTION('',(-1.,0.E+000)); +#40334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40335 = PCURVE('',#40336,#40341); +#40336 = CYLINDRICAL_SURFACE('',#40337,0.55); +#40337 = AXIS2_PLACEMENT_3D('',#40338,#40339,#40340); +#40338 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#40339 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40340 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40341 = DEFINITIONAL_REPRESENTATION('',(#40342),#40345); +#40342 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40343,#40344),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#37951 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#37952 = CARTESIAN_POINT('',(3.926990816987,4.7)); -#37953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37954 = ORIENTED_EDGE('',*,*,#37955,.F.); -#37955 = EDGE_CURVE('',#37633,#37928,#37956,.T.); -#37956 = SURFACE_CURVE('',#37957,(#37961,#37968),.PCURVE_S1.); -#37957 = LINE('',#37958,#37959); -#37958 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); -#37959 = VECTOR('',#37960,1.); -#37960 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37961 = PCURVE('',#37643,#37962); -#37962 = DEFINITIONAL_REPRESENTATION('',(#37963),#37967); -#37963 = LINE('',#37964,#37965); -#37964 = CARTESIAN_POINT('',(-3.75,2.5E-002)); -#37965 = VECTOR('',#37966,1.); -#37966 = DIRECTION('',(0.E+000,-1.)); -#37967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37968 = PCURVE('',#37969,#37974); -#37969 = PLANE('',#37970); -#37970 = AXIS2_PLACEMENT_3D('',#37971,#37972,#37973); -#37971 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); -#37972 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#37973 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#37974 = DEFINITIONAL_REPRESENTATION('',(#37975),#37979); -#37975 = LINE('',#37976,#37977); -#37976 = CARTESIAN_POINT('',(0.65,4.7)); -#37977 = VECTOR('',#37978,1.); -#37978 = DIRECTION('',(1.,0.E+000)); -#37979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#37980 = ADVANCED_FACE('',(#37981),#37995,.T.); -#37981 = FACE_BOUND('',#37982,.F.); -#37982 = EDGE_LOOP('',(#37983,#38018,#38046,#38074,#38102,#38130,#38158, - #38186,#38214,#38246,#38274,#38306)); -#37983 = ORIENTED_EDGE('',*,*,#37984,.T.); -#37984 = EDGE_CURVE('',#37985,#37987,#37989,.T.); -#37985 = VERTEX_POINT('',#37986); -#37986 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); -#37987 = VERTEX_POINT('',#37988); -#37988 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); -#37989 = SURFACE_CURVE('',#37990,(#37994,#38006),.PCURVE_S1.); -#37990 = LINE('',#37991,#37992); -#37991 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); -#37992 = VECTOR('',#37993,1.); -#37993 = DIRECTION('',(1.,0.E+000,0.E+000)); -#37994 = PCURVE('',#37995,#38000); -#37995 = PLANE('',#37996); -#37996 = AXIS2_PLACEMENT_3D('',#37997,#37998,#37999); -#37997 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); -#37998 = DIRECTION('',(0.E+000,0.E+000,1.)); -#37999 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38000 = DEFINITIONAL_REPRESENTATION('',(#38001),#38005); -#38001 = LINE('',#38002,#38003); -#38002 = CARTESIAN_POINT('',(3.45,2.5E-002)); -#38003 = VECTOR('',#38004,1.); -#38004 = DIRECTION('',(1.,0.E+000)); -#38005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38006 = PCURVE('',#38007,#38012); -#38007 = PLANE('',#38008); -#38008 = AXIS2_PLACEMENT_3D('',#38009,#38010,#38011); -#38009 = CARTESIAN_POINT('',(0.E+000,2.5E-002,0.E+000)); -#38010 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38011 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38012 = DEFINITIONAL_REPRESENTATION('',(#38013),#38017); -#38013 = LINE('',#38014,#38015); -#38014 = CARTESIAN_POINT('',(3.45,2.35)); -#38015 = VECTOR('',#38016,1.); -#38016 = DIRECTION('',(1.,0.E+000)); -#38017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38018 = ORIENTED_EDGE('',*,*,#38019,.F.); -#38019 = EDGE_CURVE('',#38020,#37987,#38022,.T.); -#38020 = VERTEX_POINT('',#38021); -#38021 = CARTESIAN_POINT('',(3.75,-7.144660940672E-002,2.35)); -#38022 = SURFACE_CURVE('',#38023,(#38027,#38034),.PCURVE_S1.); -#38023 = LINE('',#38024,#38025); -#38024 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,2.35)); -#38025 = VECTOR('',#38026,1.); -#38026 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38027 = PCURVE('',#37995,#38028); -#38028 = DEFINITIONAL_REPRESENTATION('',(#38029),#38033); -#38029 = LINE('',#38030,#38031); -#38030 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002)); -#38031 = VECTOR('',#38032,1.); -#38032 = DIRECTION('',(0.E+000,1.)); -#38033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38034 = PCURVE('',#38035,#38040); -#38035 = PLANE('',#38036); -#38036 = AXIS2_PLACEMENT_3D('',#38037,#38038,#38039); -#38037 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); -#38038 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38039 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38040 = DEFINITIONAL_REPRESENTATION('',(#38041),#38045); -#38041 = LINE('',#38042,#38043); -#38042 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38043 = VECTOR('',#38044,1.); -#38044 = DIRECTION('',(1.,0.E+000)); -#38045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38046 = ORIENTED_EDGE('',*,*,#38047,.F.); -#38047 = EDGE_CURVE('',#38048,#38020,#38050,.T.); -#38048 = VERTEX_POINT('',#38049); -#38049 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,2.35)); -#38050 = SURFACE_CURVE('',#38051,(#38056,#38063),.PCURVE_S1.); -#38051 = CIRCLE('',#38052,0.55); -#38052 = AXIS2_PLACEMENT_3D('',#38053,#38054,#38055); -#38053 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,2.35)); -#38054 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38055 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#38056 = PCURVE('',#37995,#38057); -#38057 = DEFINITIONAL_REPRESENTATION('',(#38058),#38062); -#38058 = CIRCLE('',#38059,0.55); -#38059 = AXIS2_PLACEMENT_2D('',#38060,#38061); -#38060 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002)); -#38061 = DIRECTION('',(0.707106781187,-0.707106781187)); -#38062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38063 = PCURVE('',#38064,#38069); -#38064 = CYLINDRICAL_SURFACE('',#38065,0.55); -#38065 = AXIS2_PLACEMENT_3D('',#38066,#38067,#38068); -#38066 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#38067 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38068 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38069 = DEFINITIONAL_REPRESENTATION('',(#38070),#38073); -#38070 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38071,#38072),.UNSPECIFIED., +#40343 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#40344 = CARTESIAN_POINT('',(3.926990816987,4.7)); +#40345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40346 = ORIENTED_EDGE('',*,*,#40347,.F.); +#40347 = EDGE_CURVE('',#40025,#40320,#40348,.T.); +#40348 = SURFACE_CURVE('',#40349,(#40353,#40360),.PCURVE_S1.); +#40349 = LINE('',#40350,#40351); +#40350 = CARTESIAN_POINT('',(-3.75,2.5E-002,2.35)); +#40351 = VECTOR('',#40352,1.); +#40352 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40353 = PCURVE('',#40035,#40354); +#40354 = DEFINITIONAL_REPRESENTATION('',(#40355),#40359); +#40355 = LINE('',#40356,#40357); +#40356 = CARTESIAN_POINT('',(-3.75,2.5E-002)); +#40357 = VECTOR('',#40358,1.); +#40358 = DIRECTION('',(0.E+000,-1.)); +#40359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40360 = PCURVE('',#40361,#40366); +#40361 = PLANE('',#40362); +#40362 = AXIS2_PLACEMENT_3D('',#40363,#40364,#40365); +#40363 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); +#40364 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40365 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40366 = DEFINITIONAL_REPRESENTATION('',(#40367),#40371); +#40367 = LINE('',#40368,#40369); +#40368 = CARTESIAN_POINT('',(0.65,4.7)); +#40369 = VECTOR('',#40370,1.); +#40370 = DIRECTION('',(1.,0.E+000)); +#40371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40372 = ADVANCED_FACE('',(#40373),#40387,.T.); +#40373 = FACE_BOUND('',#40374,.F.); +#40374 = EDGE_LOOP('',(#40375,#40410,#40438,#40466,#40494,#40522,#40550, + #40578,#40606,#40638,#40666,#40698)); +#40375 = ORIENTED_EDGE('',*,*,#40376,.T.); +#40376 = EDGE_CURVE('',#40377,#40379,#40381,.T.); +#40377 = VERTEX_POINT('',#40378); +#40378 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); +#40379 = VERTEX_POINT('',#40380); +#40380 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); +#40381 = SURFACE_CURVE('',#40382,(#40386,#40398),.PCURVE_S1.); +#40382 = LINE('',#40383,#40384); +#40383 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); +#40384 = VECTOR('',#40385,1.); +#40385 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40386 = PCURVE('',#40387,#40392); +#40387 = PLANE('',#40388); +#40388 = AXIS2_PLACEMENT_3D('',#40389,#40390,#40391); +#40389 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); +#40390 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40391 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40392 = DEFINITIONAL_REPRESENTATION('',(#40393),#40397); +#40393 = LINE('',#40394,#40395); +#40394 = CARTESIAN_POINT('',(3.45,2.5E-002)); +#40395 = VECTOR('',#40396,1.); +#40396 = DIRECTION('',(1.,0.E+000)); +#40397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40398 = PCURVE('',#40399,#40404); +#40399 = PLANE('',#40400); +#40400 = AXIS2_PLACEMENT_3D('',#40401,#40402,#40403); +#40401 = CARTESIAN_POINT('',(0.E+000,2.5E-002,0.E+000)); +#40402 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40403 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40404 = DEFINITIONAL_REPRESENTATION('',(#40405),#40409); +#40405 = LINE('',#40406,#40407); +#40406 = CARTESIAN_POINT('',(3.45,2.35)); +#40407 = VECTOR('',#40408,1.); +#40408 = DIRECTION('',(1.,0.E+000)); +#40409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40410 = ORIENTED_EDGE('',*,*,#40411,.F.); +#40411 = EDGE_CURVE('',#40412,#40379,#40414,.T.); +#40412 = VERTEX_POINT('',#40413); +#40413 = CARTESIAN_POINT('',(3.75,-7.144660940672E-002,2.35)); +#40414 = SURFACE_CURVE('',#40415,(#40419,#40426),.PCURVE_S1.); +#40415 = LINE('',#40416,#40417); +#40416 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,2.35)); +#40417 = VECTOR('',#40418,1.); +#40418 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40419 = PCURVE('',#40387,#40420); +#40420 = DEFINITIONAL_REPRESENTATION('',(#40421),#40425); +#40421 = LINE('',#40422,#40423); +#40422 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002)); +#40423 = VECTOR('',#40424,1.); +#40424 = DIRECTION('',(0.E+000,1.)); +#40425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40426 = PCURVE('',#40427,#40432); +#40427 = PLANE('',#40428); +#40428 = AXIS2_PLACEMENT_3D('',#40429,#40430,#40431); +#40429 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); +#40430 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40431 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40432 = DEFINITIONAL_REPRESENTATION('',(#40433),#40437); +#40433 = LINE('',#40434,#40435); +#40434 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40435 = VECTOR('',#40436,1.); +#40436 = DIRECTION('',(1.,0.E+000)); +#40437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40438 = ORIENTED_EDGE('',*,*,#40439,.F.); +#40439 = EDGE_CURVE('',#40440,#40412,#40442,.T.); +#40440 = VERTEX_POINT('',#40441); +#40441 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,2.35)); +#40442 = SURFACE_CURVE('',#40443,(#40448,#40455),.PCURVE_S1.); +#40443 = CIRCLE('',#40444,0.55); +#40444 = AXIS2_PLACEMENT_3D('',#40445,#40446,#40447); +#40445 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,2.35)); +#40446 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40447 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#40448 = PCURVE('',#40387,#40449); +#40449 = DEFINITIONAL_REPRESENTATION('',(#40450),#40454); +#40450 = CIRCLE('',#40451,0.55); +#40451 = AXIS2_PLACEMENT_2D('',#40452,#40453); +#40452 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002)); +#40453 = DIRECTION('',(0.707106781187,-0.707106781187)); +#40454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40455 = PCURVE('',#40456,#40461); +#40456 = CYLINDRICAL_SURFACE('',#40457,0.55); +#40457 = AXIS2_PLACEMENT_3D('',#40458,#40459,#40460); +#40458 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#40459 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40460 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40461 = DEFINITIONAL_REPRESENTATION('',(#40462),#40465); +#40462 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40463,#40464),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#38071 = CARTESIAN_POINT('',(5.497787143782,4.7)); -#38072 = CARTESIAN_POINT('',(6.28318530718,4.7)); -#38073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38074 = ORIENTED_EDGE('',*,*,#38075,.F.); -#38075 = EDGE_CURVE('',#38076,#38048,#38078,.T.); -#38076 = VERTEX_POINT('',#38077); -#38077 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,2.35)); -#38078 = SURFACE_CURVE('',#38079,(#38083,#38090),.PCURVE_S1.); -#38079 = LINE('',#38080,#38081); -#38080 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,2.35)); -#38081 = VECTOR('',#38082,1.); -#38082 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#38083 = PCURVE('',#37995,#38084); -#38084 = DEFINITIONAL_REPRESENTATION('',(#38085),#38089); -#38085 = LINE('',#38086,#38087); -#38086 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653)); -#38087 = VECTOR('',#38088,1.); -#38088 = DIRECTION('',(0.707106781187,0.707106781187)); -#38089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38090 = PCURVE('',#38091,#38096); -#38091 = PLANE('',#38092); -#38092 = AXIS2_PLACEMENT_3D('',#38093,#38094,#38095); -#38093 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-2.35)); -#38094 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#38095 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#38096 = DEFINITIONAL_REPRESENTATION('',(#38097),#38101); -#38097 = LINE('',#38098,#38099); -#38098 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38099 = VECTOR('',#38100,1.); -#38100 = DIRECTION('',(1.,0.E+000)); -#38101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38102 = ORIENTED_EDGE('',*,*,#38103,.F.); -#38103 = EDGE_CURVE('',#38104,#38076,#38106,.T.); -#38104 = VERTEX_POINT('',#38105); -#38105 = CARTESIAN_POINT('',(2.596446609407,-1.225,2.35)); -#38106 = SURFACE_CURVE('',#38107,(#38112,#38119),.PCURVE_S1.); -#38107 = CIRCLE('',#38108,0.55); -#38108 = AXIS2_PLACEMENT_3D('',#38109,#38110,#38111); -#38109 = CARTESIAN_POINT('',(2.596446609407,-0.675,2.35)); -#38110 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38111 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38112 = PCURVE('',#37995,#38113); -#38113 = DEFINITIONAL_REPRESENTATION('',(#38114),#38118); -#38114 = CIRCLE('',#38115,0.55); -#38115 = AXIS2_PLACEMENT_2D('',#38116,#38117); -#38116 = CARTESIAN_POINT('',(2.596446609407,-0.675)); -#38117 = DIRECTION('',(0.E+000,-1.)); -#38118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38119 = PCURVE('',#38120,#38125); -#38120 = CYLINDRICAL_SURFACE('',#38121,0.55); -#38121 = AXIS2_PLACEMENT_3D('',#38122,#38123,#38124); -#38122 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); -#38123 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38124 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38125 = DEFINITIONAL_REPRESENTATION('',(#38126),#38129); -#38126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38127,#38128),.UNSPECIFIED., +#40463 = CARTESIAN_POINT('',(5.497787143782,4.7)); +#40464 = CARTESIAN_POINT('',(6.28318530718,4.7)); +#40465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40466 = ORIENTED_EDGE('',*,*,#40467,.F.); +#40467 = EDGE_CURVE('',#40468,#40440,#40470,.T.); +#40468 = VERTEX_POINT('',#40469); +#40469 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,2.35)); +#40470 = SURFACE_CURVE('',#40471,(#40475,#40482),.PCURVE_S1.); +#40471 = LINE('',#40472,#40473); +#40472 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,2.35)); +#40473 = VECTOR('',#40474,1.); +#40474 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#40475 = PCURVE('',#40387,#40476); +#40476 = DEFINITIONAL_REPRESENTATION('',(#40477),#40481); +#40477 = LINE('',#40478,#40479); +#40478 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653)); +#40479 = VECTOR('',#40480,1.); +#40480 = DIRECTION('',(0.707106781187,0.707106781187)); +#40481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40482 = PCURVE('',#40483,#40488); +#40483 = PLANE('',#40484); +#40484 = AXIS2_PLACEMENT_3D('',#40485,#40486,#40487); +#40485 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-2.35)); +#40486 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#40487 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#40488 = DEFINITIONAL_REPRESENTATION('',(#40489),#40493); +#40489 = LINE('',#40490,#40491); +#40490 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40491 = VECTOR('',#40492,1.); +#40492 = DIRECTION('',(1.,0.E+000)); +#40493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40494 = ORIENTED_EDGE('',*,*,#40495,.F.); +#40495 = EDGE_CURVE('',#40496,#40468,#40498,.T.); +#40496 = VERTEX_POINT('',#40497); +#40497 = CARTESIAN_POINT('',(2.596446609407,-1.225,2.35)); +#40498 = SURFACE_CURVE('',#40499,(#40504,#40511),.PCURVE_S1.); +#40499 = CIRCLE('',#40500,0.55); +#40500 = AXIS2_PLACEMENT_3D('',#40501,#40502,#40503); +#40501 = CARTESIAN_POINT('',(2.596446609407,-0.675,2.35)); +#40502 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40503 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40504 = PCURVE('',#40387,#40505); +#40505 = DEFINITIONAL_REPRESENTATION('',(#40506),#40510); +#40506 = CIRCLE('',#40507,0.55); +#40507 = AXIS2_PLACEMENT_2D('',#40508,#40509); +#40508 = CARTESIAN_POINT('',(2.596446609407,-0.675)); +#40509 = DIRECTION('',(0.E+000,-1.)); +#40510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40511 = PCURVE('',#40512,#40517); +#40512 = CYLINDRICAL_SURFACE('',#40513,0.55); +#40513 = AXIS2_PLACEMENT_3D('',#40514,#40515,#40516); +#40514 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); +#40515 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40516 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40517 = DEFINITIONAL_REPRESENTATION('',(#40518),#40521); +#40518 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40519,#40520),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#38127 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#38128 = CARTESIAN_POINT('',(5.497787143781,4.7)); -#38129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38130 = ORIENTED_EDGE('',*,*,#38131,.F.); -#38131 = EDGE_CURVE('',#38132,#38104,#38134,.T.); -#38132 = VERTEX_POINT('',#38133); -#38133 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#38134 = SURFACE_CURVE('',#38135,(#38139,#38146),.PCURVE_S1.); -#38135 = LINE('',#38136,#38137); -#38136 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#38137 = VECTOR('',#38138,1.); -#38138 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38139 = PCURVE('',#37995,#38140); -#38140 = DEFINITIONAL_REPRESENTATION('',(#38141),#38145); -#38141 = LINE('',#38142,#38143); -#38142 = CARTESIAN_POINT('',(2.5,-1.225)); -#38143 = VECTOR('',#38144,1.); -#38144 = DIRECTION('',(1.,0.E+000)); -#38145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38146 = PCURVE('',#38147,#38152); -#38147 = PLANE('',#38148); -#38148 = AXIS2_PLACEMENT_3D('',#38149,#38150,#38151); -#38149 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-2.35)); -#38150 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38151 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38152 = DEFINITIONAL_REPRESENTATION('',(#38153),#38157); -#38153 = LINE('',#38154,#38155); -#38154 = CARTESIAN_POINT('',(5.096446609407,4.7)); -#38155 = VECTOR('',#38156,1.); -#38156 = DIRECTION('',(1.,0.E+000)); -#38157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38158 = ORIENTED_EDGE('',*,*,#38159,.T.); -#38159 = EDGE_CURVE('',#38132,#38160,#38162,.T.); -#38160 = VERTEX_POINT('',#38161); -#38161 = CARTESIAN_POINT('',(2.5,-0.925,2.35)); -#38162 = SURFACE_CURVE('',#38163,(#38167,#38174),.PCURVE_S1.); -#38163 = LINE('',#38164,#38165); -#38164 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#38165 = VECTOR('',#38166,1.); -#38166 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38167 = PCURVE('',#37995,#38168); -#38168 = DEFINITIONAL_REPRESENTATION('',(#38169),#38173); -#38169 = LINE('',#38170,#38171); -#38170 = CARTESIAN_POINT('',(2.5,-1.225)); -#38171 = VECTOR('',#38172,1.); -#38172 = DIRECTION('',(0.E+000,1.)); -#38173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38174 = PCURVE('',#38175,#38180); -#38175 = PLANE('',#38176); -#38176 = AXIS2_PLACEMENT_3D('',#38177,#38178,#38179); -#38177 = CARTESIAN_POINT('',(2.5,0.E+000,0.E+000)); -#38178 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38179 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38180 = DEFINITIONAL_REPRESENTATION('',(#38181),#38185); -#38181 = LINE('',#38182,#38183); -#38182 = CARTESIAN_POINT('',(2.35,-1.225)); -#38183 = VECTOR('',#38184,1.); -#38184 = DIRECTION('',(0.E+000,1.)); -#38185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38186 = ORIENTED_EDGE('',*,*,#38187,.F.); -#38187 = EDGE_CURVE('',#38188,#38160,#38190,.T.); -#38188 = VERTEX_POINT('',#38189); -#38189 = CARTESIAN_POINT('',(2.596446609407,-0.925,2.35)); -#38190 = SURFACE_CURVE('',#38191,(#38195,#38202),.PCURVE_S1.); -#38191 = LINE('',#38192,#38193); -#38192 = CARTESIAN_POINT('',(2.596446609407,-0.925,2.35)); -#38193 = VECTOR('',#38194,1.); -#38194 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38195 = PCURVE('',#37995,#38196); -#38196 = DEFINITIONAL_REPRESENTATION('',(#38197),#38201); -#38197 = LINE('',#38198,#38199); -#38198 = CARTESIAN_POINT('',(2.596446609407,-0.925)); -#38199 = VECTOR('',#38200,1.); -#38200 = DIRECTION('',(-1.,0.E+000)); -#38201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38202 = PCURVE('',#38203,#38208); -#38203 = PLANE('',#38204); -#38204 = AXIS2_PLACEMENT_3D('',#38205,#38206,#38207); -#38205 = CARTESIAN_POINT('',(2.596446609407,-0.925,-2.35)); -#38206 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38207 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38208 = DEFINITIONAL_REPRESENTATION('',(#38209),#38213); -#38209 = LINE('',#38210,#38211); -#38210 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38211 = VECTOR('',#38212,1.); -#38212 = DIRECTION('',(1.,0.E+000)); -#38213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38214 = ORIENTED_EDGE('',*,*,#38215,.F.); -#38215 = EDGE_CURVE('',#38216,#38188,#38218,.T.); -#38216 = VERTEX_POINT('',#38217); -#38217 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,2.35)); -#38218 = SURFACE_CURVE('',#38219,(#38224,#38235),.PCURVE_S1.); -#38219 = CIRCLE('',#38220,0.25); -#38220 = AXIS2_PLACEMENT_3D('',#38221,#38222,#38223); -#38221 = CARTESIAN_POINT('',(2.596446609407,-0.675,2.35)); -#38222 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#38223 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); -#38224 = PCURVE('',#37995,#38225); -#38225 = DEFINITIONAL_REPRESENTATION('',(#38226),#38234); -#38226 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#38227,#38228,#38229,#38230 - ,#38231,#38232,#38233),.UNSPECIFIED.,.T.,.F.) +#40519 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#40520 = CARTESIAN_POINT('',(5.497787143781,4.7)); +#40521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40522 = ORIENTED_EDGE('',*,*,#40523,.F.); +#40523 = EDGE_CURVE('',#40524,#40496,#40526,.T.); +#40524 = VERTEX_POINT('',#40525); +#40525 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#40526 = SURFACE_CURVE('',#40527,(#40531,#40538),.PCURVE_S1.); +#40527 = LINE('',#40528,#40529); +#40528 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#40529 = VECTOR('',#40530,1.); +#40530 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40531 = PCURVE('',#40387,#40532); +#40532 = DEFINITIONAL_REPRESENTATION('',(#40533),#40537); +#40533 = LINE('',#40534,#40535); +#40534 = CARTESIAN_POINT('',(2.5,-1.225)); +#40535 = VECTOR('',#40536,1.); +#40536 = DIRECTION('',(1.,0.E+000)); +#40537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40538 = PCURVE('',#40539,#40544); +#40539 = PLANE('',#40540); +#40540 = AXIS2_PLACEMENT_3D('',#40541,#40542,#40543); +#40541 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-2.35)); +#40542 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40543 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40544 = DEFINITIONAL_REPRESENTATION('',(#40545),#40549); +#40545 = LINE('',#40546,#40547); +#40546 = CARTESIAN_POINT('',(5.096446609407,4.7)); +#40547 = VECTOR('',#40548,1.); +#40548 = DIRECTION('',(1.,0.E+000)); +#40549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40550 = ORIENTED_EDGE('',*,*,#40551,.T.); +#40551 = EDGE_CURVE('',#40524,#40552,#40554,.T.); +#40552 = VERTEX_POINT('',#40553); +#40553 = CARTESIAN_POINT('',(2.5,-0.925,2.35)); +#40554 = SURFACE_CURVE('',#40555,(#40559,#40566),.PCURVE_S1.); +#40555 = LINE('',#40556,#40557); +#40556 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#40557 = VECTOR('',#40558,1.); +#40558 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40559 = PCURVE('',#40387,#40560); +#40560 = DEFINITIONAL_REPRESENTATION('',(#40561),#40565); +#40561 = LINE('',#40562,#40563); +#40562 = CARTESIAN_POINT('',(2.5,-1.225)); +#40563 = VECTOR('',#40564,1.); +#40564 = DIRECTION('',(0.E+000,1.)); +#40565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40566 = PCURVE('',#40567,#40572); +#40567 = PLANE('',#40568); +#40568 = AXIS2_PLACEMENT_3D('',#40569,#40570,#40571); +#40569 = CARTESIAN_POINT('',(2.5,0.E+000,0.E+000)); +#40570 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40571 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40572 = DEFINITIONAL_REPRESENTATION('',(#40573),#40577); +#40573 = LINE('',#40574,#40575); +#40574 = CARTESIAN_POINT('',(2.35,-1.225)); +#40575 = VECTOR('',#40576,1.); +#40576 = DIRECTION('',(0.E+000,1.)); +#40577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40578 = ORIENTED_EDGE('',*,*,#40579,.F.); +#40579 = EDGE_CURVE('',#40580,#40552,#40582,.T.); +#40580 = VERTEX_POINT('',#40581); +#40581 = CARTESIAN_POINT('',(2.596446609407,-0.925,2.35)); +#40582 = SURFACE_CURVE('',#40583,(#40587,#40594),.PCURVE_S1.); +#40583 = LINE('',#40584,#40585); +#40584 = CARTESIAN_POINT('',(2.596446609407,-0.925,2.35)); +#40585 = VECTOR('',#40586,1.); +#40586 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40587 = PCURVE('',#40387,#40588); +#40588 = DEFINITIONAL_REPRESENTATION('',(#40589),#40593); +#40589 = LINE('',#40590,#40591); +#40590 = CARTESIAN_POINT('',(2.596446609407,-0.925)); +#40591 = VECTOR('',#40592,1.); +#40592 = DIRECTION('',(-1.,0.E+000)); +#40593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40594 = PCURVE('',#40595,#40600); +#40595 = PLANE('',#40596); +#40596 = AXIS2_PLACEMENT_3D('',#40597,#40598,#40599); +#40597 = CARTESIAN_POINT('',(2.596446609407,-0.925,-2.35)); +#40598 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40599 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40600 = DEFINITIONAL_REPRESENTATION('',(#40601),#40605); +#40601 = LINE('',#40602,#40603); +#40602 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40603 = VECTOR('',#40604,1.); +#40604 = DIRECTION('',(1.,0.E+000)); +#40605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40606 = ORIENTED_EDGE('',*,*,#40607,.F.); +#40607 = EDGE_CURVE('',#40608,#40580,#40610,.T.); +#40608 = VERTEX_POINT('',#40609); +#40609 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,2.35)); +#40610 = SURFACE_CURVE('',#40611,(#40616,#40627),.PCURVE_S1.); +#40611 = CIRCLE('',#40612,0.25); +#40612 = AXIS2_PLACEMENT_3D('',#40613,#40614,#40615); +#40613 = CARTESIAN_POINT('',(2.596446609407,-0.675,2.35)); +#40614 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40615 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); +#40616 = PCURVE('',#40387,#40617); +#40617 = DEFINITIONAL_REPRESENTATION('',(#40618),#40626); +#40618 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40619,#40620,#40621,#40622 + ,#40623,#40624,#40625),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#38227 = CARTESIAN_POINT('',(2.773223304704,-0.851776695297)); -#38228 = CARTESIAN_POINT('',(2.467037086856,-1.157962913145)); -#38229 = CARTESIAN_POINT('',(2.354965152835,-0.739704761276)); -#38230 = CARTESIAN_POINT('',(2.242893218814,-0.321446609407)); -#38231 = CARTESIAN_POINT('',(2.661151370683,-0.433518543428)); -#38232 = CARTESIAN_POINT('',(3.079409522552,-0.545590477449)); -#38233 = CARTESIAN_POINT('',(2.773223304704,-0.851776695297)); -#38234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38235 = PCURVE('',#38236,#38241); -#38236 = CYLINDRICAL_SURFACE('',#38237,0.25); -#38237 = AXIS2_PLACEMENT_3D('',#38238,#38239,#38240); -#38238 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); -#38239 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38240 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38241 = DEFINITIONAL_REPRESENTATION('',(#38242),#38245); -#38242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38243,#38244),.UNSPECIFIED., +#40619 = CARTESIAN_POINT('',(2.773223304704,-0.851776695297)); +#40620 = CARTESIAN_POINT('',(2.467037086856,-1.157962913145)); +#40621 = CARTESIAN_POINT('',(2.354965152835,-0.739704761276)); +#40622 = CARTESIAN_POINT('',(2.242893218814,-0.321446609407)); +#40623 = CARTESIAN_POINT('',(2.661151370683,-0.433518543428)); +#40624 = CARTESIAN_POINT('',(3.079409522552,-0.545590477449)); +#40625 = CARTESIAN_POINT('',(2.773223304704,-0.851776695297)); +#40626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40627 = PCURVE('',#40628,#40633); +#40628 = CYLINDRICAL_SURFACE('',#40629,0.25); +#40629 = AXIS2_PLACEMENT_3D('',#40630,#40631,#40632); +#40630 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); +#40631 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40632 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40633 = DEFINITIONAL_REPRESENTATION('',(#40634),#40637); +#40634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40635,#40636),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#38243 = CARTESIAN_POINT('',(5.497787143782,4.7)); -#38244 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#38245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38246 = ORIENTED_EDGE('',*,*,#38247,.F.); -#38247 = EDGE_CURVE('',#38248,#38216,#38250,.T.); -#38248 = VERTEX_POINT('',#38249); -#38249 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,2.35)); -#38250 = SURFACE_CURVE('',#38251,(#38255,#38262),.PCURVE_S1.); -#38251 = LINE('',#38252,#38253); -#38252 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,2.35)); -#38253 = VECTOR('',#38254,1.); -#38254 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#38255 = PCURVE('',#37995,#38256); -#38256 = DEFINITIONAL_REPRESENTATION('',(#38257),#38261); -#38257 = LINE('',#38258,#38259); -#38258 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703)); -#38259 = VECTOR('',#38260,1.); -#38260 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#38261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38262 = PCURVE('',#38263,#38268); -#38263 = PLANE('',#38264); -#38264 = AXIS2_PLACEMENT_3D('',#38265,#38266,#38267); -#38265 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-2.35)); -#38266 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#38267 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#38268 = DEFINITIONAL_REPRESENTATION('',(#38269),#38273); -#38269 = LINE('',#38270,#38271); -#38270 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38271 = VECTOR('',#38272,1.); -#38272 = DIRECTION('',(1.,0.E+000)); -#38273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38274 = ORIENTED_EDGE('',*,*,#38275,.F.); -#38275 = EDGE_CURVE('',#38276,#38248,#38278,.T.); -#38276 = VERTEX_POINT('',#38277); -#38277 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,2.35)); -#38278 = SURFACE_CURVE('',#38279,(#38284,#38295),.PCURVE_S1.); -#38279 = CIRCLE('',#38280,0.25); -#38280 = AXIS2_PLACEMENT_3D('',#38281,#38282,#38283); -#38281 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,2.35)); -#38282 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#38283 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38284 = PCURVE('',#37995,#38285); -#38285 = DEFINITIONAL_REPRESENTATION('',(#38286),#38294); -#38286 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#38287,#38288,#38289,#38290 - ,#38291,#38292,#38293),.UNSPECIFIED.,.F.,.F.) +#40635 = CARTESIAN_POINT('',(5.497787143782,4.7)); +#40636 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#40637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40638 = ORIENTED_EDGE('',*,*,#40639,.F.); +#40639 = EDGE_CURVE('',#40640,#40608,#40642,.T.); +#40640 = VERTEX_POINT('',#40641); +#40641 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,2.35)); +#40642 = SURFACE_CURVE('',#40643,(#40647,#40654),.PCURVE_S1.); +#40643 = LINE('',#40644,#40645); +#40644 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,2.35)); +#40645 = VECTOR('',#40646,1.); +#40646 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#40647 = PCURVE('',#40387,#40648); +#40648 = DEFINITIONAL_REPRESENTATION('',(#40649),#40653); +#40649 = LINE('',#40650,#40651); +#40650 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703)); +#40651 = VECTOR('',#40652,1.); +#40652 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#40653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40654 = PCURVE('',#40655,#40660); +#40655 = PLANE('',#40656); +#40656 = AXIS2_PLACEMENT_3D('',#40657,#40658,#40659); +#40657 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-2.35)); +#40658 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#40659 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#40660 = DEFINITIONAL_REPRESENTATION('',(#40661),#40665); +#40661 = LINE('',#40662,#40663); +#40662 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40663 = VECTOR('',#40664,1.); +#40664 = DIRECTION('',(1.,0.E+000)); +#40665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40666 = ORIENTED_EDGE('',*,*,#40667,.F.); +#40667 = EDGE_CURVE('',#40668,#40640,#40670,.T.); +#40668 = VERTEX_POINT('',#40669); +#40669 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,2.35)); +#40670 = SURFACE_CURVE('',#40671,(#40676,#40687),.PCURVE_S1.); +#40671 = CIRCLE('',#40672,0.25); +#40672 = AXIS2_PLACEMENT_3D('',#40673,#40674,#40675); +#40673 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,2.35)); +#40674 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40675 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40676 = PCURVE('',#40387,#40677); +#40677 = DEFINITIONAL_REPRESENTATION('',(#40678),#40686); +#40678 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40679,#40680,#40681,#40682 + ,#40683,#40684,#40685),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#38287 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); -#38288 = CARTESIAN_POINT('',(3.45,-0.504459311299)); -#38289 = CARTESIAN_POINT('',(3.075,-0.287952960353)); -#38290 = CARTESIAN_POINT('',(2.7,-7.144660940673E-002)); -#38291 = CARTESIAN_POINT('',(3.075,0.145059741539)); -#38292 = CARTESIAN_POINT('',(3.45,0.361566092485)); -#38293 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); -#38294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38295 = PCURVE('',#38296,#38301); -#38296 = CYLINDRICAL_SURFACE('',#38297,0.25); -#38297 = AXIS2_PLACEMENT_3D('',#38298,#38299,#38300); -#38298 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#38299 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38300 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38301 = DEFINITIONAL_REPRESENTATION('',(#38302),#38305); -#38302 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38303,#38304),.UNSPECIFIED., +#40679 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); +#40680 = CARTESIAN_POINT('',(3.45,-0.504459311299)); +#40681 = CARTESIAN_POINT('',(3.075,-0.287952960353)); +#40682 = CARTESIAN_POINT('',(2.7,-7.144660940673E-002)); +#40683 = CARTESIAN_POINT('',(3.075,0.145059741539)); +#40684 = CARTESIAN_POINT('',(3.45,0.361566092485)); +#40685 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); +#40686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40687 = PCURVE('',#40688,#40693); +#40688 = CYLINDRICAL_SURFACE('',#40689,0.25); +#40689 = AXIS2_PLACEMENT_3D('',#40690,#40691,#40692); +#40690 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#40691 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40692 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40693 = DEFINITIONAL_REPRESENTATION('',(#40694),#40697); +#40694 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40695,#40696),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#38303 = CARTESIAN_POINT('',(6.28318530718,4.7)); -#38304 = CARTESIAN_POINT('',(5.497787143783,4.7)); -#38305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38306 = ORIENTED_EDGE('',*,*,#38307,.F.); -#38307 = EDGE_CURVE('',#37985,#38276,#38308,.T.); -#38308 = SURFACE_CURVE('',#38309,(#38313,#38320),.PCURVE_S1.); -#38309 = LINE('',#38310,#38311); -#38310 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); -#38311 = VECTOR('',#38312,1.); -#38312 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38313 = PCURVE('',#37995,#38314); -#38314 = DEFINITIONAL_REPRESENTATION('',(#38315),#38319); -#38315 = LINE('',#38316,#38317); -#38316 = CARTESIAN_POINT('',(3.45,2.5E-002)); -#38317 = VECTOR('',#38318,1.); -#38318 = DIRECTION('',(0.E+000,-1.)); -#38319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38320 = PCURVE('',#38321,#38326); -#38321 = PLANE('',#38322); -#38322 = AXIS2_PLACEMENT_3D('',#38323,#38324,#38325); -#38323 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); -#38324 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38325 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38326 = DEFINITIONAL_REPRESENTATION('',(#38327),#38331); -#38327 = LINE('',#38328,#38329); -#38328 = CARTESIAN_POINT('',(0.65,4.7)); -#38329 = VECTOR('',#38330,1.); -#38330 = DIRECTION('',(1.,0.E+000)); -#38331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38332 = ADVANCED_FACE('',(#38333),#38347,.T.); -#38333 = FACE_BOUND('',#38334,.F.); -#38334 = EDGE_LOOP('',(#38335,#38370,#38393,#38421,#38449,#38481)); -#38335 = ORIENTED_EDGE('',*,*,#38336,.F.); -#38336 = EDGE_CURVE('',#38337,#38339,#38341,.T.); -#38337 = VERTEX_POINT('',#38338); -#38338 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); -#38339 = VERTEX_POINT('',#38340); -#38340 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); -#38341 = SURFACE_CURVE('',#38342,(#38346,#38358),.PCURVE_S1.); -#38342 = LINE('',#38343,#38344); -#38343 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); -#38344 = VECTOR('',#38345,1.); -#38345 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38346 = PCURVE('',#38347,#38352); -#38347 = PLANE('',#38348); -#38348 = AXIS2_PLACEMENT_3D('',#38349,#38350,#38351); -#38349 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); -#38350 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38351 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38352 = DEFINITIONAL_REPRESENTATION('',(#38353),#38357); -#38353 = LINE('',#38354,#38355); -#38354 = CARTESIAN_POINT('',(-3.75,0.625)); -#38355 = VECTOR('',#38356,1.); -#38356 = DIRECTION('',(1.,0.E+000)); -#38357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38358 = PCURVE('',#38359,#38364); -#38359 = PLANE('',#38360); -#38360 = AXIS2_PLACEMENT_3D('',#38361,#38362,#38363); -#38361 = CARTESIAN_POINT('',(0.E+000,0.625,0.E+000)); -#38362 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38363 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38364 = DEFINITIONAL_REPRESENTATION('',(#38365),#38369); -#38365 = LINE('',#38366,#38367); -#38366 = CARTESIAN_POINT('',(-3.75,2.35)); -#38367 = VECTOR('',#38368,1.); -#38368 = DIRECTION('',(1.,0.E+000)); -#38369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38370 = ORIENTED_EDGE('',*,*,#38371,.F.); -#38371 = EDGE_CURVE('',#38372,#38337,#38374,.T.); -#38372 = VERTEX_POINT('',#38373); -#38373 = CARTESIAN_POINT('',(-3.75,0.675,2.35)); -#38374 = SURFACE_CURVE('',#38375,(#38379,#38386),.PCURVE_S1.); -#38375 = LINE('',#38376,#38377); -#38376 = CARTESIAN_POINT('',(-3.75,0.675,2.35)); -#38377 = VECTOR('',#38378,1.); -#38378 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38379 = PCURVE('',#38347,#38380); -#38380 = DEFINITIONAL_REPRESENTATION('',(#38381),#38385); -#38381 = LINE('',#38382,#38383); -#38382 = CARTESIAN_POINT('',(-3.75,0.675)); -#38383 = VECTOR('',#38384,1.); -#38384 = DIRECTION('',(0.E+000,-1.)); -#38385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38386 = PCURVE('',#37969,#38387); -#38387 = DEFINITIONAL_REPRESENTATION('',(#38388),#38392); -#38388 = LINE('',#38389,#38390); -#38389 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38390 = VECTOR('',#38391,1.); -#38391 = DIRECTION('',(1.,0.E+000)); -#38392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38393 = ORIENTED_EDGE('',*,*,#38394,.F.); -#38394 = EDGE_CURVE('',#38395,#38372,#38397,.T.); -#38395 = VERTEX_POINT('',#38396); -#38396 = CARTESIAN_POINT('',(-3.2,1.225,2.35)); -#38397 = SURFACE_CURVE('',#38398,(#38403,#38410),.PCURVE_S1.); -#38398 = CIRCLE('',#38399,0.55); -#38399 = AXIS2_PLACEMENT_3D('',#38400,#38401,#38402); -#38400 = CARTESIAN_POINT('',(-3.2,0.675,2.35)); -#38401 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38402 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38403 = PCURVE('',#38347,#38404); -#38404 = DEFINITIONAL_REPRESENTATION('',(#38405),#38409); -#38405 = CIRCLE('',#38406,0.55); -#38406 = AXIS2_PLACEMENT_2D('',#38407,#38408); -#38407 = CARTESIAN_POINT('',(-3.2,0.675)); -#38408 = DIRECTION('',(0.E+000,1.)); -#38409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38410 = PCURVE('',#38411,#38416); -#38411 = CYLINDRICAL_SURFACE('',#38412,0.55); -#38412 = AXIS2_PLACEMENT_3D('',#38413,#38414,#38415); -#38413 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); -#38414 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38415 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38416 = DEFINITIONAL_REPRESENTATION('',(#38417),#38420); -#38417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38418,#38419),.UNSPECIFIED., +#40695 = CARTESIAN_POINT('',(6.28318530718,4.7)); +#40696 = CARTESIAN_POINT('',(5.497787143783,4.7)); +#40697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40698 = ORIENTED_EDGE('',*,*,#40699,.F.); +#40699 = EDGE_CURVE('',#40377,#40668,#40700,.T.); +#40700 = SURFACE_CURVE('',#40701,(#40705,#40712),.PCURVE_S1.); +#40701 = LINE('',#40702,#40703); +#40702 = CARTESIAN_POINT('',(3.45,2.5E-002,2.35)); +#40703 = VECTOR('',#40704,1.); +#40704 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40705 = PCURVE('',#40387,#40706); +#40706 = DEFINITIONAL_REPRESENTATION('',(#40707),#40711); +#40707 = LINE('',#40708,#40709); +#40708 = CARTESIAN_POINT('',(3.45,2.5E-002)); +#40709 = VECTOR('',#40710,1.); +#40710 = DIRECTION('',(0.E+000,-1.)); +#40711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40712 = PCURVE('',#40713,#40718); +#40713 = PLANE('',#40714); +#40714 = AXIS2_PLACEMENT_3D('',#40715,#40716,#40717); +#40715 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); +#40716 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40717 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40718 = DEFINITIONAL_REPRESENTATION('',(#40719),#40723); +#40719 = LINE('',#40720,#40721); +#40720 = CARTESIAN_POINT('',(0.65,4.7)); +#40721 = VECTOR('',#40722,1.); +#40722 = DIRECTION('',(1.,0.E+000)); +#40723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40724 = ADVANCED_FACE('',(#40725),#40739,.T.); +#40725 = FACE_BOUND('',#40726,.F.); +#40726 = EDGE_LOOP('',(#40727,#40762,#40785,#40813,#40841,#40873)); +#40727 = ORIENTED_EDGE('',*,*,#40728,.F.); +#40728 = EDGE_CURVE('',#40729,#40731,#40733,.T.); +#40729 = VERTEX_POINT('',#40730); +#40730 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); +#40731 = VERTEX_POINT('',#40732); +#40732 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); +#40733 = SURFACE_CURVE('',#40734,(#40738,#40750),.PCURVE_S1.); +#40734 = LINE('',#40735,#40736); +#40735 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); +#40736 = VECTOR('',#40737,1.); +#40737 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40738 = PCURVE('',#40739,#40744); +#40739 = PLANE('',#40740); +#40740 = AXIS2_PLACEMENT_3D('',#40741,#40742,#40743); +#40741 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); +#40742 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40743 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40744 = DEFINITIONAL_REPRESENTATION('',(#40745),#40749); +#40745 = LINE('',#40746,#40747); +#40746 = CARTESIAN_POINT('',(-3.75,0.625)); +#40747 = VECTOR('',#40748,1.); +#40748 = DIRECTION('',(1.,0.E+000)); +#40749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40750 = PCURVE('',#40751,#40756); +#40751 = PLANE('',#40752); +#40752 = AXIS2_PLACEMENT_3D('',#40753,#40754,#40755); +#40753 = CARTESIAN_POINT('',(0.E+000,0.625,0.E+000)); +#40754 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40755 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40756 = DEFINITIONAL_REPRESENTATION('',(#40757),#40761); +#40757 = LINE('',#40758,#40759); +#40758 = CARTESIAN_POINT('',(-3.75,2.35)); +#40759 = VECTOR('',#40760,1.); +#40760 = DIRECTION('',(1.,0.E+000)); +#40761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40762 = ORIENTED_EDGE('',*,*,#40763,.F.); +#40763 = EDGE_CURVE('',#40764,#40729,#40766,.T.); +#40764 = VERTEX_POINT('',#40765); +#40765 = CARTESIAN_POINT('',(-3.75,0.675,2.35)); +#40766 = SURFACE_CURVE('',#40767,(#40771,#40778),.PCURVE_S1.); +#40767 = LINE('',#40768,#40769); +#40768 = CARTESIAN_POINT('',(-3.75,0.675,2.35)); +#40769 = VECTOR('',#40770,1.); +#40770 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40771 = PCURVE('',#40739,#40772); +#40772 = DEFINITIONAL_REPRESENTATION('',(#40773),#40777); +#40773 = LINE('',#40774,#40775); +#40774 = CARTESIAN_POINT('',(-3.75,0.675)); +#40775 = VECTOR('',#40776,1.); +#40776 = DIRECTION('',(0.E+000,-1.)); +#40777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40778 = PCURVE('',#40361,#40779); +#40779 = DEFINITIONAL_REPRESENTATION('',(#40780),#40784); +#40780 = LINE('',#40781,#40782); +#40781 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40782 = VECTOR('',#40783,1.); +#40783 = DIRECTION('',(1.,0.E+000)); +#40784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40785 = ORIENTED_EDGE('',*,*,#40786,.F.); +#40786 = EDGE_CURVE('',#40787,#40764,#40789,.T.); +#40787 = VERTEX_POINT('',#40788); +#40788 = CARTESIAN_POINT('',(-3.2,1.225,2.35)); +#40789 = SURFACE_CURVE('',#40790,(#40795,#40802),.PCURVE_S1.); +#40790 = CIRCLE('',#40791,0.55); +#40791 = AXIS2_PLACEMENT_3D('',#40792,#40793,#40794); +#40792 = CARTESIAN_POINT('',(-3.2,0.675,2.35)); +#40793 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40794 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40795 = PCURVE('',#40739,#40796); +#40796 = DEFINITIONAL_REPRESENTATION('',(#40797),#40801); +#40797 = CIRCLE('',#40798,0.55); +#40798 = AXIS2_PLACEMENT_2D('',#40799,#40800); +#40799 = CARTESIAN_POINT('',(-3.2,0.675)); +#40800 = DIRECTION('',(0.E+000,1.)); +#40801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40802 = PCURVE('',#40803,#40808); +#40803 = CYLINDRICAL_SURFACE('',#40804,0.55); +#40804 = AXIS2_PLACEMENT_3D('',#40805,#40806,#40807); +#40805 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); +#40806 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40807 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40808 = DEFINITIONAL_REPRESENTATION('',(#40809),#40812); +#40809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40810,#40811),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#38418 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#38419 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#38420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38421 = ORIENTED_EDGE('',*,*,#38422,.T.); -#38422 = EDGE_CURVE('',#38395,#38423,#38425,.T.); -#38423 = VERTEX_POINT('',#38424); -#38424 = CARTESIAN_POINT('',(-3.2,0.925,2.35)); -#38425 = SURFACE_CURVE('',#38426,(#38430,#38437),.PCURVE_S1.); -#38426 = LINE('',#38427,#38428); -#38427 = CARTESIAN_POINT('',(-3.2,1.225,2.35)); -#38428 = VECTOR('',#38429,1.); -#38429 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38430 = PCURVE('',#38347,#38431); -#38431 = DEFINITIONAL_REPRESENTATION('',(#38432),#38436); -#38432 = LINE('',#38433,#38434); -#38433 = CARTESIAN_POINT('',(-3.2,1.225)); -#38434 = VECTOR('',#38435,1.); -#38435 = DIRECTION('',(0.E+000,-1.)); -#38436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38437 = PCURVE('',#38438,#38443); -#38438 = PLANE('',#38439); -#38439 = AXIS2_PLACEMENT_3D('',#38440,#38441,#38442); -#38440 = CARTESIAN_POINT('',(-3.2,0.E+000,0.E+000)); -#38441 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38442 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38443 = DEFINITIONAL_REPRESENTATION('',(#38444),#38448); -#38444 = LINE('',#38445,#38446); -#38445 = CARTESIAN_POINT('',(2.35,1.225)); -#38446 = VECTOR('',#38447,1.); -#38447 = DIRECTION('',(0.E+000,-1.)); -#38448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38449 = ORIENTED_EDGE('',*,*,#38450,.F.); -#38450 = EDGE_CURVE('',#38451,#38423,#38453,.T.); -#38451 = VERTEX_POINT('',#38452); -#38452 = CARTESIAN_POINT('',(-3.45,0.675,2.35)); -#38453 = SURFACE_CURVE('',#38454,(#38459,#38470),.PCURVE_S1.); -#38454 = CIRCLE('',#38455,0.25); -#38455 = AXIS2_PLACEMENT_3D('',#38456,#38457,#38458); -#38456 = CARTESIAN_POINT('',(-3.2,0.675,2.35)); -#38457 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#38458 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38459 = PCURVE('',#38347,#38460); -#38460 = DEFINITIONAL_REPRESENTATION('',(#38461),#38469); -#38461 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#38462,#38463,#38464,#38465 - ,#38466,#38467,#38468),.UNSPECIFIED.,.T.,.F.) +#40810 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#40811 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#40812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40813 = ORIENTED_EDGE('',*,*,#40814,.T.); +#40814 = EDGE_CURVE('',#40787,#40815,#40817,.T.); +#40815 = VERTEX_POINT('',#40816); +#40816 = CARTESIAN_POINT('',(-3.2,0.925,2.35)); +#40817 = SURFACE_CURVE('',#40818,(#40822,#40829),.PCURVE_S1.); +#40818 = LINE('',#40819,#40820); +#40819 = CARTESIAN_POINT('',(-3.2,1.225,2.35)); +#40820 = VECTOR('',#40821,1.); +#40821 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40822 = PCURVE('',#40739,#40823); +#40823 = DEFINITIONAL_REPRESENTATION('',(#40824),#40828); +#40824 = LINE('',#40825,#40826); +#40825 = CARTESIAN_POINT('',(-3.2,1.225)); +#40826 = VECTOR('',#40827,1.); +#40827 = DIRECTION('',(0.E+000,-1.)); +#40828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40829 = PCURVE('',#40830,#40835); +#40830 = PLANE('',#40831); +#40831 = AXIS2_PLACEMENT_3D('',#40832,#40833,#40834); +#40832 = CARTESIAN_POINT('',(-3.2,0.E+000,0.E+000)); +#40833 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40834 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40835 = DEFINITIONAL_REPRESENTATION('',(#40836),#40840); +#40836 = LINE('',#40837,#40838); +#40837 = CARTESIAN_POINT('',(2.35,1.225)); +#40838 = VECTOR('',#40839,1.); +#40839 = DIRECTION('',(0.E+000,-1.)); +#40840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40841 = ORIENTED_EDGE('',*,*,#40842,.F.); +#40842 = EDGE_CURVE('',#40843,#40815,#40845,.T.); +#40843 = VERTEX_POINT('',#40844); +#40844 = CARTESIAN_POINT('',(-3.45,0.675,2.35)); +#40845 = SURFACE_CURVE('',#40846,(#40851,#40862),.PCURVE_S1.); +#40846 = CIRCLE('',#40847,0.25); +#40847 = AXIS2_PLACEMENT_3D('',#40848,#40849,#40850); +#40848 = CARTESIAN_POINT('',(-3.2,0.675,2.35)); +#40849 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40850 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#40851 = PCURVE('',#40739,#40852); +#40852 = DEFINITIONAL_REPRESENTATION('',(#40853),#40861); +#40853 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40854,#40855,#40856,#40857 + ,#40858,#40859,#40860),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#38462 = CARTESIAN_POINT('',(-3.45,0.675)); -#38463 = CARTESIAN_POINT('',(-3.45,1.108012701892)); -#38464 = CARTESIAN_POINT('',(-3.075,0.891506350946)); -#38465 = CARTESIAN_POINT('',(-2.7,0.675)); -#38466 = CARTESIAN_POINT('',(-3.075,0.458493649054)); -#38467 = CARTESIAN_POINT('',(-3.45,0.241987298108)); -#38468 = CARTESIAN_POINT('',(-3.45,0.675)); -#38469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38470 = PCURVE('',#38471,#38476); -#38471 = CYLINDRICAL_SURFACE('',#38472,0.25); -#38472 = AXIS2_PLACEMENT_3D('',#38473,#38474,#38475); -#38473 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); -#38474 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38475 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38476 = DEFINITIONAL_REPRESENTATION('',(#38477),#38480); -#38477 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38478,#38479),.UNSPECIFIED., +#40854 = CARTESIAN_POINT('',(-3.45,0.675)); +#40855 = CARTESIAN_POINT('',(-3.45,1.108012701892)); +#40856 = CARTESIAN_POINT('',(-3.075,0.891506350946)); +#40857 = CARTESIAN_POINT('',(-2.7,0.675)); +#40858 = CARTESIAN_POINT('',(-3.075,0.458493649054)); +#40859 = CARTESIAN_POINT('',(-3.45,0.241987298108)); +#40860 = CARTESIAN_POINT('',(-3.45,0.675)); +#40861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40862 = PCURVE('',#40863,#40868); +#40863 = CYLINDRICAL_SURFACE('',#40864,0.25); +#40864 = AXIS2_PLACEMENT_3D('',#40865,#40866,#40867); +#40865 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); +#40866 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40867 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40868 = DEFINITIONAL_REPRESENTATION('',(#40869),#40872); +#40869 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40870,#40871),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#38478 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#38479 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#38480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38481 = ORIENTED_EDGE('',*,*,#38482,.F.); -#38482 = EDGE_CURVE('',#38339,#38451,#38483,.T.); -#38483 = SURFACE_CURVE('',#38484,(#38488,#38495),.PCURVE_S1.); -#38484 = LINE('',#38485,#38486); -#38485 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); -#38486 = VECTOR('',#38487,1.); -#38487 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38488 = PCURVE('',#38347,#38489); -#38489 = DEFINITIONAL_REPRESENTATION('',(#38490),#38494); -#38490 = LINE('',#38491,#38492); -#38491 = CARTESIAN_POINT('',(-3.45,0.625)); -#38492 = VECTOR('',#38493,1.); -#38493 = DIRECTION('',(0.E+000,1.)); -#38494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38495 = PCURVE('',#37683,#38496); -#38496 = DEFINITIONAL_REPRESENTATION('',(#38497),#38501); -#38497 = LINE('',#38498,#38499); -#38498 = CARTESIAN_POINT('',(0.696446609407,4.7)); -#38499 = VECTOR('',#38500,1.); -#38500 = DIRECTION('',(1.,0.E+000)); -#38501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38502 = ADVANCED_FACE('',(#38503),#38517,.T.); -#38503 = FACE_BOUND('',#38504,.F.); -#38504 = EDGE_LOOP('',(#38505,#38540,#38563,#38595,#38623,#38651)); -#38505 = ORIENTED_EDGE('',*,*,#38506,.F.); -#38506 = EDGE_CURVE('',#38507,#38509,#38511,.T.); -#38507 = VERTEX_POINT('',#38508); -#38508 = CARTESIAN_POINT('',(3.45,0.625,2.35)); -#38509 = VERTEX_POINT('',#38510); -#38510 = CARTESIAN_POINT('',(3.75,0.625,2.35)); -#38511 = SURFACE_CURVE('',#38512,(#38516,#38528),.PCURVE_S1.); -#38512 = LINE('',#38513,#38514); -#38513 = CARTESIAN_POINT('',(3.45,0.625,2.35)); -#38514 = VECTOR('',#38515,1.); -#38515 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38516 = PCURVE('',#38517,#38522); -#38517 = PLANE('',#38518); -#38518 = AXIS2_PLACEMENT_3D('',#38519,#38520,#38521); -#38519 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); -#38520 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38521 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38522 = DEFINITIONAL_REPRESENTATION('',(#38523),#38527); -#38523 = LINE('',#38524,#38525); -#38524 = CARTESIAN_POINT('',(3.45,0.625)); -#38525 = VECTOR('',#38526,1.); -#38526 = DIRECTION('',(1.,0.E+000)); -#38527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38528 = PCURVE('',#38529,#38534); -#38529 = PLANE('',#38530); -#38530 = AXIS2_PLACEMENT_3D('',#38531,#38532,#38533); -#38531 = CARTESIAN_POINT('',(0.E+000,0.625,0.E+000)); -#38532 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38533 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38534 = DEFINITIONAL_REPRESENTATION('',(#38535),#38539); -#38535 = LINE('',#38536,#38537); -#38536 = CARTESIAN_POINT('',(3.45,2.35)); -#38537 = VECTOR('',#38538,1.); -#38538 = DIRECTION('',(1.,0.E+000)); -#38539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38540 = ORIENTED_EDGE('',*,*,#38541,.F.); -#38541 = EDGE_CURVE('',#38542,#38507,#38544,.T.); -#38542 = VERTEX_POINT('',#38543); -#38543 = CARTESIAN_POINT('',(3.45,0.675,2.35)); -#38544 = SURFACE_CURVE('',#38545,(#38549,#38556),.PCURVE_S1.); -#38545 = LINE('',#38546,#38547); -#38546 = CARTESIAN_POINT('',(3.45,0.675,2.35)); -#38547 = VECTOR('',#38548,1.); -#38548 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38549 = PCURVE('',#38517,#38550); -#38550 = DEFINITIONAL_REPRESENTATION('',(#38551),#38555); -#38551 = LINE('',#38552,#38553); -#38552 = CARTESIAN_POINT('',(3.45,0.675)); -#38553 = VECTOR('',#38554,1.); -#38554 = DIRECTION('',(0.E+000,-1.)); -#38555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38556 = PCURVE('',#38321,#38557); -#38557 = DEFINITIONAL_REPRESENTATION('',(#38558),#38562); -#38558 = LINE('',#38559,#38560); -#38559 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38560 = VECTOR('',#38561,1.); -#38561 = DIRECTION('',(1.,0.E+000)); -#38562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38563 = ORIENTED_EDGE('',*,*,#38564,.F.); -#38564 = EDGE_CURVE('',#38565,#38542,#38567,.T.); -#38565 = VERTEX_POINT('',#38566); -#38566 = CARTESIAN_POINT('',(3.2,0.925,2.35)); -#38567 = SURFACE_CURVE('',#38568,(#38573,#38584),.PCURVE_S1.); -#38568 = CIRCLE('',#38569,0.25); -#38569 = AXIS2_PLACEMENT_3D('',#38570,#38571,#38572); -#38570 = CARTESIAN_POINT('',(3.2,0.675,2.35)); -#38571 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#38572 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38573 = PCURVE('',#38517,#38574); -#38574 = DEFINITIONAL_REPRESENTATION('',(#38575),#38583); -#38575 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#38576,#38577,#38578,#38579 - ,#38580,#38581,#38582),.UNSPECIFIED.,.F.,.F.) +#40870 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#40871 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#40872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40873 = ORIENTED_EDGE('',*,*,#40874,.F.); +#40874 = EDGE_CURVE('',#40731,#40843,#40875,.T.); +#40875 = SURFACE_CURVE('',#40876,(#40880,#40887),.PCURVE_S1.); +#40876 = LINE('',#40877,#40878); +#40877 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); +#40878 = VECTOR('',#40879,1.); +#40879 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40880 = PCURVE('',#40739,#40881); +#40881 = DEFINITIONAL_REPRESENTATION('',(#40882),#40886); +#40882 = LINE('',#40883,#40884); +#40883 = CARTESIAN_POINT('',(-3.45,0.625)); +#40884 = VECTOR('',#40885,1.); +#40885 = DIRECTION('',(0.E+000,1.)); +#40886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40887 = PCURVE('',#40075,#40888); +#40888 = DEFINITIONAL_REPRESENTATION('',(#40889),#40893); +#40889 = LINE('',#40890,#40891); +#40890 = CARTESIAN_POINT('',(0.696446609407,4.7)); +#40891 = VECTOR('',#40892,1.); +#40892 = DIRECTION('',(1.,0.E+000)); +#40893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40894 = ADVANCED_FACE('',(#40895),#40909,.T.); +#40895 = FACE_BOUND('',#40896,.F.); +#40896 = EDGE_LOOP('',(#40897,#40932,#40955,#40987,#41015,#41043)); +#40897 = ORIENTED_EDGE('',*,*,#40898,.F.); +#40898 = EDGE_CURVE('',#40899,#40901,#40903,.T.); +#40899 = VERTEX_POINT('',#40900); +#40900 = CARTESIAN_POINT('',(3.45,0.625,2.35)); +#40901 = VERTEX_POINT('',#40902); +#40902 = CARTESIAN_POINT('',(3.75,0.625,2.35)); +#40903 = SURFACE_CURVE('',#40904,(#40908,#40920),.PCURVE_S1.); +#40904 = LINE('',#40905,#40906); +#40905 = CARTESIAN_POINT('',(3.45,0.625,2.35)); +#40906 = VECTOR('',#40907,1.); +#40907 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40908 = PCURVE('',#40909,#40914); +#40909 = PLANE('',#40910); +#40910 = AXIS2_PLACEMENT_3D('',#40911,#40912,#40913); +#40911 = CARTESIAN_POINT('',(0.E+000,0.E+000,2.35)); +#40912 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40913 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40914 = DEFINITIONAL_REPRESENTATION('',(#40915),#40919); +#40915 = LINE('',#40916,#40917); +#40916 = CARTESIAN_POINT('',(3.45,0.625)); +#40917 = VECTOR('',#40918,1.); +#40918 = DIRECTION('',(1.,0.E+000)); +#40919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40920 = PCURVE('',#40921,#40926); +#40921 = PLANE('',#40922); +#40922 = AXIS2_PLACEMENT_3D('',#40923,#40924,#40925); +#40923 = CARTESIAN_POINT('',(0.E+000,0.625,0.E+000)); +#40924 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40925 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40926 = DEFINITIONAL_REPRESENTATION('',(#40927),#40931); +#40927 = LINE('',#40928,#40929); +#40928 = CARTESIAN_POINT('',(3.45,2.35)); +#40929 = VECTOR('',#40930,1.); +#40930 = DIRECTION('',(1.,0.E+000)); +#40931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40932 = ORIENTED_EDGE('',*,*,#40933,.F.); +#40933 = EDGE_CURVE('',#40934,#40899,#40936,.T.); +#40934 = VERTEX_POINT('',#40935); +#40935 = CARTESIAN_POINT('',(3.45,0.675,2.35)); +#40936 = SURFACE_CURVE('',#40937,(#40941,#40948),.PCURVE_S1.); +#40937 = LINE('',#40938,#40939); +#40938 = CARTESIAN_POINT('',(3.45,0.675,2.35)); +#40939 = VECTOR('',#40940,1.); +#40940 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40941 = PCURVE('',#40909,#40942); +#40942 = DEFINITIONAL_REPRESENTATION('',(#40943),#40947); +#40943 = LINE('',#40944,#40945); +#40944 = CARTESIAN_POINT('',(3.45,0.675)); +#40945 = VECTOR('',#40946,1.); +#40946 = DIRECTION('',(0.E+000,-1.)); +#40947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40948 = PCURVE('',#40713,#40949); +#40949 = DEFINITIONAL_REPRESENTATION('',(#40950),#40954); +#40950 = LINE('',#40951,#40952); +#40951 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40952 = VECTOR('',#40953,1.); +#40953 = DIRECTION('',(1.,0.E+000)); +#40954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40955 = ORIENTED_EDGE('',*,*,#40956,.F.); +#40956 = EDGE_CURVE('',#40957,#40934,#40959,.T.); +#40957 = VERTEX_POINT('',#40958); +#40958 = CARTESIAN_POINT('',(3.2,0.925,2.35)); +#40959 = SURFACE_CURVE('',#40960,(#40965,#40976),.PCURVE_S1.); +#40960 = CIRCLE('',#40961,0.25); +#40961 = AXIS2_PLACEMENT_3D('',#40962,#40963,#40964); +#40962 = CARTESIAN_POINT('',(3.2,0.675,2.35)); +#40963 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#40964 = DIRECTION('',(0.E+000,1.,0.E+000)); +#40965 = PCURVE('',#40909,#40966); +#40966 = DEFINITIONAL_REPRESENTATION('',(#40967),#40975); +#40967 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40968,#40969,#40970,#40971 + ,#40972,#40973,#40974),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#38576 = CARTESIAN_POINT('',(3.2,0.925)); -#38577 = CARTESIAN_POINT('',(3.633012701892,0.925)); -#38578 = CARTESIAN_POINT('',(3.416506350946,0.55)); -#38579 = CARTESIAN_POINT('',(3.2,0.175)); -#38580 = CARTESIAN_POINT('',(2.983493649054,0.55)); -#38581 = CARTESIAN_POINT('',(2.766987298108,0.925)); -#38582 = CARTESIAN_POINT('',(3.2,0.925)); -#38583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38584 = PCURVE('',#38585,#38590); -#38585 = CYLINDRICAL_SURFACE('',#38586,0.25); -#38586 = AXIS2_PLACEMENT_3D('',#38587,#38588,#38589); -#38587 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); -#38588 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38589 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38590 = DEFINITIONAL_REPRESENTATION('',(#38591),#38594); -#38591 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38592,#38593),.UNSPECIFIED., +#40968 = CARTESIAN_POINT('',(3.2,0.925)); +#40969 = CARTESIAN_POINT('',(3.633012701892,0.925)); +#40970 = CARTESIAN_POINT('',(3.416506350946,0.55)); +#40971 = CARTESIAN_POINT('',(3.2,0.175)); +#40972 = CARTESIAN_POINT('',(2.983493649054,0.55)); +#40973 = CARTESIAN_POINT('',(2.766987298108,0.925)); +#40974 = CARTESIAN_POINT('',(3.2,0.925)); +#40975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40976 = PCURVE('',#40977,#40982); +#40977 = CYLINDRICAL_SURFACE('',#40978,0.25); +#40978 = AXIS2_PLACEMENT_3D('',#40979,#40980,#40981); +#40979 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); +#40980 = DIRECTION('',(0.E+000,0.E+000,1.)); +#40981 = DIRECTION('',(1.,0.E+000,0.E+000)); +#40982 = DEFINITIONAL_REPRESENTATION('',(#40983),#40986); +#40983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40984,#40985),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#38592 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#38593 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38595 = ORIENTED_EDGE('',*,*,#38596,.F.); -#38596 = EDGE_CURVE('',#38597,#38565,#38599,.T.); -#38597 = VERTEX_POINT('',#38598); -#38598 = CARTESIAN_POINT('',(3.2,1.225,2.35)); -#38599 = SURFACE_CURVE('',#38600,(#38604,#38611),.PCURVE_S1.); -#38600 = LINE('',#38601,#38602); -#38601 = CARTESIAN_POINT('',(3.2,1.225,2.35)); -#38602 = VECTOR('',#38603,1.); -#38603 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38604 = PCURVE('',#38517,#38605); -#38605 = DEFINITIONAL_REPRESENTATION('',(#38606),#38610); -#38606 = LINE('',#38607,#38608); -#38607 = CARTESIAN_POINT('',(3.2,1.225)); -#38608 = VECTOR('',#38609,1.); -#38609 = DIRECTION('',(0.E+000,-1.)); -#38610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38611 = PCURVE('',#38612,#38617); -#38612 = PLANE('',#38613); -#38613 = AXIS2_PLACEMENT_3D('',#38614,#38615,#38616); -#38614 = CARTESIAN_POINT('',(3.2,0.E+000,0.E+000)); -#38615 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#38616 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38617 = DEFINITIONAL_REPRESENTATION('',(#38618),#38622); -#38618 = LINE('',#38619,#38620); -#38619 = CARTESIAN_POINT('',(2.35,1.225)); -#38620 = VECTOR('',#38621,1.); -#38621 = DIRECTION('',(0.E+000,-1.)); -#38622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38623 = ORIENTED_EDGE('',*,*,#38624,.F.); -#38624 = EDGE_CURVE('',#38625,#38597,#38627,.T.); -#38625 = VERTEX_POINT('',#38626); -#38626 = CARTESIAN_POINT('',(3.75,0.675,2.35)); -#38627 = SURFACE_CURVE('',#38628,(#38633,#38640),.PCURVE_S1.); -#38628 = CIRCLE('',#38629,0.55); -#38629 = AXIS2_PLACEMENT_3D('',#38630,#38631,#38632); -#38630 = CARTESIAN_POINT('',(3.2,0.675,2.35)); -#38631 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38632 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38633 = PCURVE('',#38517,#38634); -#38634 = DEFINITIONAL_REPRESENTATION('',(#38635),#38639); -#38635 = CIRCLE('',#38636,0.55); -#38636 = AXIS2_PLACEMENT_2D('',#38637,#38638); -#38637 = CARTESIAN_POINT('',(3.2,0.675)); -#38638 = DIRECTION('',(1.,0.E+000)); -#38639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38640 = PCURVE('',#38641,#38646); -#38641 = CYLINDRICAL_SURFACE('',#38642,0.55); -#38642 = AXIS2_PLACEMENT_3D('',#38643,#38644,#38645); -#38643 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); -#38644 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38645 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38646 = DEFINITIONAL_REPRESENTATION('',(#38647),#38650); -#38647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38648,#38649),.UNSPECIFIED., +#40984 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#40985 = CARTESIAN_POINT('',(0.E+000,4.7)); +#40986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#40987 = ORIENTED_EDGE('',*,*,#40988,.F.); +#40988 = EDGE_CURVE('',#40989,#40957,#40991,.T.); +#40989 = VERTEX_POINT('',#40990); +#40990 = CARTESIAN_POINT('',(3.2,1.225,2.35)); +#40991 = SURFACE_CURVE('',#40992,(#40996,#41003),.PCURVE_S1.); +#40992 = LINE('',#40993,#40994); +#40993 = CARTESIAN_POINT('',(3.2,1.225,2.35)); +#40994 = VECTOR('',#40995,1.); +#40995 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#40996 = PCURVE('',#40909,#40997); +#40997 = DEFINITIONAL_REPRESENTATION('',(#40998),#41002); +#40998 = LINE('',#40999,#41000); +#40999 = CARTESIAN_POINT('',(3.2,1.225)); +#41000 = VECTOR('',#41001,1.); +#41001 = DIRECTION('',(0.E+000,-1.)); +#41002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41003 = PCURVE('',#41004,#41009); +#41004 = PLANE('',#41005); +#41005 = AXIS2_PLACEMENT_3D('',#41006,#41007,#41008); +#41006 = CARTESIAN_POINT('',(3.2,0.E+000,0.E+000)); +#41007 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#41008 = DIRECTION('',(0.E+000,0.E+000,1.)); +#41009 = DEFINITIONAL_REPRESENTATION('',(#41010),#41014); +#41010 = LINE('',#41011,#41012); +#41011 = CARTESIAN_POINT('',(2.35,1.225)); +#41012 = VECTOR('',#41013,1.); +#41013 = DIRECTION('',(0.E+000,-1.)); +#41014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41015 = ORIENTED_EDGE('',*,*,#41016,.F.); +#41016 = EDGE_CURVE('',#41017,#40989,#41019,.T.); +#41017 = VERTEX_POINT('',#41018); +#41018 = CARTESIAN_POINT('',(3.75,0.675,2.35)); +#41019 = SURFACE_CURVE('',#41020,(#41025,#41032),.PCURVE_S1.); +#41020 = CIRCLE('',#41021,0.55); +#41021 = AXIS2_PLACEMENT_3D('',#41022,#41023,#41024); +#41022 = CARTESIAN_POINT('',(3.2,0.675,2.35)); +#41023 = DIRECTION('',(0.E+000,0.E+000,1.)); +#41024 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41025 = PCURVE('',#40909,#41026); +#41026 = DEFINITIONAL_REPRESENTATION('',(#41027),#41031); +#41027 = CIRCLE('',#41028,0.55); +#41028 = AXIS2_PLACEMENT_2D('',#41029,#41030); +#41029 = CARTESIAN_POINT('',(3.2,0.675)); +#41030 = DIRECTION('',(1.,0.E+000)); +#41031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41032 = PCURVE('',#41033,#41038); +#41033 = CYLINDRICAL_SURFACE('',#41034,0.55); +#41034 = AXIS2_PLACEMENT_3D('',#41035,#41036,#41037); +#41035 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); +#41036 = DIRECTION('',(0.E+000,0.E+000,1.)); +#41037 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41038 = DEFINITIONAL_REPRESENTATION('',(#41039),#41042); +#41039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41040,#41041),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#38648 = CARTESIAN_POINT('',(0.E+000,4.7)); -#38649 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#38650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38651 = ORIENTED_EDGE('',*,*,#38652,.F.); -#38652 = EDGE_CURVE('',#38509,#38625,#38653,.T.); -#38653 = SURFACE_CURVE('',#38654,(#38658,#38665),.PCURVE_S1.); -#38654 = LINE('',#38655,#38656); -#38655 = CARTESIAN_POINT('',(3.75,0.625,2.35)); -#38656 = VECTOR('',#38657,1.); -#38657 = DIRECTION('',(0.E+000,1.,0.E+000)); -#38658 = PCURVE('',#38517,#38659); -#38659 = DEFINITIONAL_REPRESENTATION('',(#38660),#38664); -#38660 = LINE('',#38661,#38662); -#38661 = CARTESIAN_POINT('',(3.75,0.625)); -#38662 = VECTOR('',#38663,1.); -#38663 = DIRECTION('',(0.E+000,1.)); -#38664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38665 = PCURVE('',#38035,#38666); -#38666 = DEFINITIONAL_REPRESENTATION('',(#38667),#38671); -#38667 = LINE('',#38668,#38669); -#38668 = CARTESIAN_POINT('',(0.696446609407,4.7)); -#38669 = VECTOR('',#38670,1.); -#38670 = DIRECTION('',(1.,0.E+000)); -#38671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38672 = ADVANCED_FACE('',(#38673),#38007,.T.); -#38673 = FACE_BOUND('',#38674,.F.); -#38674 = EDGE_LOOP('',(#38675,#38727,#38753,#38754,#38777,#38805)); -#38675 = ORIENTED_EDGE('',*,*,#38676,.F.); -#38676 = EDGE_CURVE('',#38677,#38679,#38681,.T.); -#38677 = VERTEX_POINT('',#38678); -#38678 = CARTESIAN_POINT('',(3.836077234426,2.5E-002,2.421413924332)); -#38679 = VERTEX_POINT('',#38680); -#38680 = CARTESIAN_POINT('',(3.644524343464,2.5E-002,2.652298072692)); -#38681 = SURFACE_CURVE('',#38682,(#38686,#38693),.PCURVE_S1.); -#38682 = LINE('',#38683,#38684); -#38683 = CARTESIAN_POINT('',(3.836077234426,2.5E-002,2.421413924332)); -#38684 = VECTOR('',#38685,1.); -#38685 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#38686 = PCURVE('',#38007,#38687); -#38687 = DEFINITIONAL_REPRESENTATION('',(#38688),#38692); -#38688 = LINE('',#38689,#38690); -#38689 = CARTESIAN_POINT('',(3.836077234426,2.421413924332)); -#38690 = VECTOR('',#38691,1.); -#38691 = DIRECTION('',(-0.63850963654,0.769613827868)); -#38692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38693 = PCURVE('',#38694,#38699); -#38694 = CYLINDRICAL_SURFACE('',#38695,0.2); -#38695 = AXIS2_PLACEMENT_3D('',#38696,#38697,#38698); -#38696 = CARTESIAN_POINT('',(3.845983476177,0.225,2.409473649358)); -#38697 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#38698 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38699 = DEFINITIONAL_REPRESENTATION('',(#38700),#38726); -#38700 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38701,#38702,#38703,#38704, - #38705,#38706,#38707,#38708,#38709,#38710,#38711,#38712,#38713, - #38714,#38715,#38716,#38717,#38718,#38719,#38720,#38721,#38722, - #38723,#38724,#38725),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41040 = CARTESIAN_POINT('',(0.E+000,4.7)); +#41041 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#41042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41043 = ORIENTED_EDGE('',*,*,#41044,.F.); +#41044 = EDGE_CURVE('',#40901,#41017,#41045,.T.); +#41045 = SURFACE_CURVE('',#41046,(#41050,#41057),.PCURVE_S1.); +#41046 = LINE('',#41047,#41048); +#41047 = CARTESIAN_POINT('',(3.75,0.625,2.35)); +#41048 = VECTOR('',#41049,1.); +#41049 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41050 = PCURVE('',#40909,#41051); +#41051 = DEFINITIONAL_REPRESENTATION('',(#41052),#41056); +#41052 = LINE('',#41053,#41054); +#41053 = CARTESIAN_POINT('',(3.75,0.625)); +#41054 = VECTOR('',#41055,1.); +#41055 = DIRECTION('',(0.E+000,1.)); +#41056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41057 = PCURVE('',#40427,#41058); +#41058 = DEFINITIONAL_REPRESENTATION('',(#41059),#41063); +#41059 = LINE('',#41060,#41061); +#41060 = CARTESIAN_POINT('',(0.696446609407,4.7)); +#41061 = VECTOR('',#41062,1.); +#41062 = DIRECTION('',(1.,0.E+000)); +#41063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41064 = ADVANCED_FACE('',(#41065),#40399,.T.); +#41065 = FACE_BOUND('',#41066,.F.); +#41066 = EDGE_LOOP('',(#41067,#41119,#41145,#41146,#41169,#41197)); +#41067 = ORIENTED_EDGE('',*,*,#41068,.F.); +#41068 = EDGE_CURVE('',#41069,#41071,#41073,.T.); +#41069 = VERTEX_POINT('',#41070); +#41070 = CARTESIAN_POINT('',(3.836077234426,2.5E-002,2.421413924332)); +#41071 = VERTEX_POINT('',#41072); +#41072 = CARTESIAN_POINT('',(3.644524343464,2.5E-002,2.652298072692)); +#41073 = SURFACE_CURVE('',#41074,(#41078,#41085),.PCURVE_S1.); +#41074 = LINE('',#41075,#41076); +#41075 = CARTESIAN_POINT('',(3.836077234426,2.5E-002,2.421413924332)); +#41076 = VECTOR('',#41077,1.); +#41077 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41078 = PCURVE('',#40399,#41079); +#41079 = DEFINITIONAL_REPRESENTATION('',(#41080),#41084); +#41080 = LINE('',#41081,#41082); +#41081 = CARTESIAN_POINT('',(3.836077234426,2.421413924332)); +#41082 = VECTOR('',#41083,1.); +#41083 = DIRECTION('',(-0.63850963654,0.769613827868)); +#41084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41085 = PCURVE('',#41086,#41091); +#41086 = CYLINDRICAL_SURFACE('',#41087,0.2); +#41087 = AXIS2_PLACEMENT_3D('',#41088,#41089,#41090); +#41088 = CARTESIAN_POINT('',(3.845983476177,0.225,2.409473649358)); +#41089 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41090 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41091 = DEFINITIONAL_REPRESENTATION('',(#41092),#41118); +#41092 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41093,#41094,#41095,#41096, + #41097,#41098,#41099,#41100,#41101,#41102,#41103,#41104,#41105, + #41106,#41107,#41108,#41109,#41110,#41111,#41112,#41113,#41114, + #41115,#41116,#41117),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363635E-002, 2.72727272727E-002,4.090909090905E-002,5.45454545454E-002, 6.818181818175E-002,8.18181818181E-002,9.545454545445E-002, @@ -48569,189 +51558,189 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#38701 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); -#38702 = CARTESIAN_POINT('',(1.818298598108E-013,2.006008609389E-002)); -#38703 = CARTESIAN_POINT('',(3.512409270842E-013,2.915099518479E-002)); -#38704 = CARTESIAN_POINT('',(2.831505890862E-013,4.278735882114E-002)); -#38705 = CARTESIAN_POINT('',(3.013953401683E-013,5.642372245749E-002)); -#38706 = CARTESIAN_POINT('',(2.965066738378E-013,7.006008609385E-002)); -#38707 = CARTESIAN_POINT('',(2.978165880777E-013,8.36964497302E-002)); -#38708 = CARTESIAN_POINT('',(2.974655974485E-013,9.733281336655E-002)); -#38709 = CARTESIAN_POINT('',(2.975596457257E-013,0.110969177003)); -#38710 = CARTESIAN_POINT('',(2.975344432461E-013,0.124605540639)); -#38711 = CARTESIAN_POINT('',(2.97541204887E-013,0.138241904276)); -#38712 = CARTESIAN_POINT('',(2.975393608031E-013,0.151878267912)); -#38713 = CARTESIAN_POINT('',(2.975399754977E-013,0.165514631548)); -#38714 = CARTESIAN_POINT('',(2.975393608031E-013,0.179150995185)); -#38715 = CARTESIAN_POINT('',(2.97541204887E-013,0.192787358821)); -#38716 = CARTESIAN_POINT('',(2.975344432461E-013,0.206423722457)); -#38717 = CARTESIAN_POINT('',(2.975596457257E-013,0.220060086094)); -#38718 = CARTESIAN_POINT('',(2.974655974485E-013,0.23369644973)); -#38719 = CARTESIAN_POINT('',(2.978165880777E-013,0.247332813366)); -#38720 = CARTESIAN_POINT('',(2.965066738378E-013,0.260969177003)); -#38721 = CARTESIAN_POINT('',(3.013953401683E-013,0.274605540639)); -#38722 = CARTESIAN_POINT('',(2.831505890862E-013,0.288241904275)); -#38723 = CARTESIAN_POINT('',(3.512409270842E-013,0.301878267912)); -#38724 = CARTESIAN_POINT('',(1.818298598108E-013,0.310969177003)); -#38725 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#38726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38727 = ORIENTED_EDGE('',*,*,#38728,.F.); -#38728 = EDGE_CURVE('',#37987,#38677,#38729,.T.); -#38729 = SURFACE_CURVE('',#38730,(#38734,#38741),.PCURVE_S1.); -#38730 = LINE('',#38731,#38732); -#38731 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); -#38732 = VECTOR('',#38733,1.); -#38733 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#38734 = PCURVE('',#38007,#38735); -#38735 = DEFINITIONAL_REPRESENTATION('',(#38736),#38740); -#38736 = LINE('',#38737,#38738); -#38737 = CARTESIAN_POINT('',(3.75,2.35)); -#38738 = VECTOR('',#38739,1.); -#38739 = DIRECTION('',(0.769613827868,0.63850963654)); -#38740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38741 = PCURVE('',#38742,#38747); -#38742 = PLANE('',#38743); -#38743 = AXIS2_PLACEMENT_3D('',#38744,#38745,#38746); -#38744 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); -#38745 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#38746 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#38747 = DEFINITIONAL_REPRESENTATION('',(#38748),#38752); -#38748 = LINE('',#38749,#38750); -#38749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#38750 = VECTOR('',#38751,1.); -#38751 = DIRECTION('',(1.,0.E+000)); -#38752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38753 = ORIENTED_EDGE('',*,*,#37984,.F.); -#38754 = ORIENTED_EDGE('',*,*,#38755,.F.); -#38755 = EDGE_CURVE('',#38756,#37985,#38758,.T.); -#38756 = VERTEX_POINT('',#38757); -#38757 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); -#38758 = SURFACE_CURVE('',#38759,(#38763,#38770),.PCURVE_S1.); -#38759 = LINE('',#38760,#38761); -#38760 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); -#38761 = VECTOR('',#38762,1.); -#38762 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#38763 = PCURVE('',#38007,#38764); -#38764 = DEFINITIONAL_REPRESENTATION('',(#38765),#38769); -#38765 = LINE('',#38766,#38767); -#38766 = CARTESIAN_POINT('',(3.45,2.354697035713)); -#38767 = VECTOR('',#38768,1.); -#38768 = DIRECTION('',(0.E+000,-1.)); -#38769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38770 = PCURVE('',#38321,#38771); -#38771 = DEFINITIONAL_REPRESENTATION('',(#38772),#38776); -#38772 = LINE('',#38773,#38774); -#38773 = CARTESIAN_POINT('',(0.65,4.704697035713)); -#38774 = VECTOR('',#38775,1.); -#38775 = DIRECTION('',(0.E+000,-1.)); -#38776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38777 = ORIENTED_EDGE('',*,*,#38778,.F.); -#38778 = EDGE_CURVE('',#38779,#38756,#38781,.T.); -#38779 = VERTEX_POINT('',#38780); -#38780 = CARTESIAN_POINT('',(3.554832205403,2.5E-002,2.577885045795)); -#38781 = SURFACE_CURVE('',#38782,(#38787,#38794),.PCURVE_S1.); -#38782 = CIRCLE('',#38783,0.29); -#38783 = AXIS2_PLACEMENT_3D('',#38784,#38785,#38786); -#38784 = CARTESIAN_POINT('',(3.74,2.5E-002,2.354697035713)); -#38785 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38786 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#38787 = PCURVE('',#38007,#38788); -#38788 = DEFINITIONAL_REPRESENTATION('',(#38789),#38793); -#38789 = CIRCLE('',#38790,0.29); -#38790 = AXIS2_PLACEMENT_2D('',#38791,#38792); -#38791 = CARTESIAN_POINT('',(3.74,2.354697035713)); -#38792 = DIRECTION('',(-0.63850963654,0.769613827868)); -#38793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38794 = PCURVE('',#38795,#38800); -#38795 = CYLINDRICAL_SURFACE('',#38796,0.29); -#38796 = AXIS2_PLACEMENT_3D('',#38797,#38798,#38799); -#38797 = CARTESIAN_POINT('',(3.74,2.5E-002,2.354697035713)); -#38798 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38799 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38800 = DEFINITIONAL_REPRESENTATION('',(#38801),#38804); -#38801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38802,#38803),.UNSPECIFIED., +#41093 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); +#41094 = CARTESIAN_POINT('',(1.818298598108E-013,2.006008609389E-002)); +#41095 = CARTESIAN_POINT('',(3.512409270842E-013,2.915099518479E-002)); +#41096 = CARTESIAN_POINT('',(2.831505890862E-013,4.278735882114E-002)); +#41097 = CARTESIAN_POINT('',(3.013953401683E-013,5.642372245749E-002)); +#41098 = CARTESIAN_POINT('',(2.965066738378E-013,7.006008609385E-002)); +#41099 = CARTESIAN_POINT('',(2.978165880777E-013,8.36964497302E-002)); +#41100 = CARTESIAN_POINT('',(2.974655974485E-013,9.733281336655E-002)); +#41101 = CARTESIAN_POINT('',(2.975596457257E-013,0.110969177003)); +#41102 = CARTESIAN_POINT('',(2.975344432461E-013,0.124605540639)); +#41103 = CARTESIAN_POINT('',(2.97541204887E-013,0.138241904276)); +#41104 = CARTESIAN_POINT('',(2.975393608031E-013,0.151878267912)); +#41105 = CARTESIAN_POINT('',(2.975399754977E-013,0.165514631548)); +#41106 = CARTESIAN_POINT('',(2.975393608031E-013,0.179150995185)); +#41107 = CARTESIAN_POINT('',(2.97541204887E-013,0.192787358821)); +#41108 = CARTESIAN_POINT('',(2.975344432461E-013,0.206423722457)); +#41109 = CARTESIAN_POINT('',(2.975596457257E-013,0.220060086094)); +#41110 = CARTESIAN_POINT('',(2.974655974485E-013,0.23369644973)); +#41111 = CARTESIAN_POINT('',(2.978165880777E-013,0.247332813366)); +#41112 = CARTESIAN_POINT('',(2.965066738378E-013,0.260969177003)); +#41113 = CARTESIAN_POINT('',(3.013953401683E-013,0.274605540639)); +#41114 = CARTESIAN_POINT('',(2.831505890862E-013,0.288241904275)); +#41115 = CARTESIAN_POINT('',(3.512409270842E-013,0.301878267912)); +#41116 = CARTESIAN_POINT('',(1.818298598108E-013,0.310969177003)); +#41117 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#41118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41119 = ORIENTED_EDGE('',*,*,#41120,.F.); +#41120 = EDGE_CURVE('',#40379,#41069,#41121,.T.); +#41121 = SURFACE_CURVE('',#41122,(#41126,#41133),.PCURVE_S1.); +#41122 = LINE('',#41123,#41124); +#41123 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); +#41124 = VECTOR('',#41125,1.); +#41125 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41126 = PCURVE('',#40399,#41127); +#41127 = DEFINITIONAL_REPRESENTATION('',(#41128),#41132); +#41128 = LINE('',#41129,#41130); +#41129 = CARTESIAN_POINT('',(3.75,2.35)); +#41130 = VECTOR('',#41131,1.); +#41131 = DIRECTION('',(0.769613827868,0.63850963654)); +#41132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41133 = PCURVE('',#41134,#41139); +#41134 = PLANE('',#41135); +#41135 = AXIS2_PLACEMENT_3D('',#41136,#41137,#41138); +#41136 = CARTESIAN_POINT('',(3.75,2.5E-002,2.35)); +#41137 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41138 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41139 = DEFINITIONAL_REPRESENTATION('',(#41140),#41144); +#41140 = LINE('',#41141,#41142); +#41141 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#41142 = VECTOR('',#41143,1.); +#41143 = DIRECTION('',(1.,0.E+000)); +#41144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41145 = ORIENTED_EDGE('',*,*,#40376,.F.); +#41146 = ORIENTED_EDGE('',*,*,#41147,.F.); +#41147 = EDGE_CURVE('',#41148,#40377,#41150,.T.); +#41148 = VERTEX_POINT('',#41149); +#41149 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); +#41150 = SURFACE_CURVE('',#41151,(#41155,#41162),.PCURVE_S1.); +#41151 = LINE('',#41152,#41153); +#41152 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); +#41153 = VECTOR('',#41154,1.); +#41154 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#41155 = PCURVE('',#40399,#41156); +#41156 = DEFINITIONAL_REPRESENTATION('',(#41157),#41161); +#41157 = LINE('',#41158,#41159); +#41158 = CARTESIAN_POINT('',(3.45,2.354697035713)); +#41159 = VECTOR('',#41160,1.); +#41160 = DIRECTION('',(0.E+000,-1.)); +#41161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41162 = PCURVE('',#40713,#41163); +#41163 = DEFINITIONAL_REPRESENTATION('',(#41164),#41168); +#41164 = LINE('',#41165,#41166); +#41165 = CARTESIAN_POINT('',(0.65,4.704697035713)); +#41166 = VECTOR('',#41167,1.); +#41167 = DIRECTION('',(0.E+000,-1.)); +#41168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41169 = ORIENTED_EDGE('',*,*,#41170,.F.); +#41170 = EDGE_CURVE('',#41171,#41148,#41173,.T.); +#41171 = VERTEX_POINT('',#41172); +#41172 = CARTESIAN_POINT('',(3.554832205403,2.5E-002,2.577885045795)); +#41173 = SURFACE_CURVE('',#41174,(#41179,#41186),.PCURVE_S1.); +#41174 = CIRCLE('',#41175,0.29); +#41175 = AXIS2_PLACEMENT_3D('',#41176,#41177,#41178); +#41176 = CARTESIAN_POINT('',(3.74,2.5E-002,2.354697035713)); +#41177 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41178 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41179 = PCURVE('',#40399,#41180); +#41180 = DEFINITIONAL_REPRESENTATION('',(#41181),#41185); +#41181 = CIRCLE('',#41182,0.29); +#41182 = AXIS2_PLACEMENT_2D('',#41183,#41184); +#41183 = CARTESIAN_POINT('',(3.74,2.354697035713)); +#41184 = DIRECTION('',(-0.63850963654,0.769613827868)); +#41185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41186 = PCURVE('',#41187,#41192); +#41187 = CYLINDRICAL_SURFACE('',#41188,0.29); +#41188 = AXIS2_PLACEMENT_3D('',#41189,#41190,#41191); +#41189 = CARTESIAN_POINT('',(3.74,2.5E-002,2.354697035713)); +#41190 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41191 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41192 = DEFINITIONAL_REPRESENTATION('',(#41193),#41196); +#41193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41194,#41195),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.87823612867),.PIECEWISE_BEZIER_KNOTS.); -#38802 = CARTESIAN_POINT('',(2.26335652492,0.E+000)); -#38803 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#38804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38805 = ORIENTED_EDGE('',*,*,#38806,.F.); -#38806 = EDGE_CURVE('',#38679,#38779,#38807,.T.); -#38807 = SURFACE_CURVE('',#38808,(#38812,#38819),.PCURVE_S1.); -#38808 = LINE('',#38809,#38810); -#38809 = CARTESIAN_POINT('',(3.644524343464,2.5E-002,2.652298072692)); -#38810 = VECTOR('',#38811,1.); -#38811 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); -#38812 = PCURVE('',#38007,#38813); -#38813 = DEFINITIONAL_REPRESENTATION('',(#38814),#38818); -#38814 = LINE('',#38815,#38816); -#38815 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); -#38816 = VECTOR('',#38817,1.); -#38817 = DIRECTION('',(-0.769613827868,-0.63850963654)); -#38818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38819 = PCURVE('',#38820,#38825); -#38820 = PLANE('',#38821); -#38821 = AXIS2_PLACEMENT_3D('',#38822,#38823,#38824); -#38822 = CARTESIAN_POINT('',(3.798447109038,2.5E-002,2.78)); -#38823 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#38824 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); -#38825 = DEFINITIONAL_REPRESENTATION('',(#38826),#38830); -#38826 = LINE('',#38827,#38828); -#38827 = CARTESIAN_POINT('',(0.2,0.E+000)); -#38828 = VECTOR('',#38829,1.); -#38829 = DIRECTION('',(1.,0.E+000)); -#38830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38831 = ADVANCED_FACE('',(#38832),#37655,.T.); -#38832 = FACE_BOUND('',#38833,.F.); -#38833 = EDGE_LOOP('',(#38834,#38886,#38914,#38942,#38963,#38964)); -#38834 = ORIENTED_EDGE('',*,*,#38835,.F.); -#38835 = EDGE_CURVE('',#38836,#38838,#38840,.T.); -#38836 = VERTEX_POINT('',#38837); -#38837 = CARTESIAN_POINT('',(-3.644524343464,2.5E-002,2.652298072692)); -#38838 = VERTEX_POINT('',#38839); -#38839 = CARTESIAN_POINT('',(-3.836077234426,2.5E-002,2.421413924332)); -#38840 = SURFACE_CURVE('',#38841,(#38845,#38852),.PCURVE_S1.); -#38841 = LINE('',#38842,#38843); -#38842 = CARTESIAN_POINT('',(-3.644524343464,2.5E-002,2.652298072692)); -#38843 = VECTOR('',#38844,1.); -#38844 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#38845 = PCURVE('',#37655,#38846); -#38846 = DEFINITIONAL_REPRESENTATION('',(#38847),#38851); -#38847 = LINE('',#38848,#38849); -#38848 = CARTESIAN_POINT('',(-3.644524343464,2.652298072692)); -#38849 = VECTOR('',#38850,1.); -#38850 = DIRECTION('',(-0.63850963654,-0.769613827868)); -#38851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38852 = PCURVE('',#38853,#38858); -#38853 = CYLINDRICAL_SURFACE('',#38854,0.2); -#38854 = AXIS2_PLACEMENT_3D('',#38855,#38856,#38857); -#38855 = CARTESIAN_POINT('',(-3.634618101713,0.225,2.664238347666)); -#38856 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#38857 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38858 = DEFINITIONAL_REPRESENTATION('',(#38859),#38885); -#38859 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#38860,#38861,#38862,#38863, - #38864,#38865,#38866,#38867,#38868,#38869,#38870,#38871,#38872, - #38873,#38874,#38875,#38876,#38877,#38878,#38879,#38880,#38881, - #38882,#38883,#38884),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41194 = CARTESIAN_POINT('',(2.26335652492,0.E+000)); +#41195 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#41196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41197 = ORIENTED_EDGE('',*,*,#41198,.F.); +#41198 = EDGE_CURVE('',#41071,#41171,#41199,.T.); +#41199 = SURFACE_CURVE('',#41200,(#41204,#41211),.PCURVE_S1.); +#41200 = LINE('',#41201,#41202); +#41201 = CARTESIAN_POINT('',(3.644524343464,2.5E-002,2.652298072692)); +#41202 = VECTOR('',#41203,1.); +#41203 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); +#41204 = PCURVE('',#40399,#41205); +#41205 = DEFINITIONAL_REPRESENTATION('',(#41206),#41210); +#41206 = LINE('',#41207,#41208); +#41207 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); +#41208 = VECTOR('',#41209,1.); +#41209 = DIRECTION('',(-0.769613827868,-0.63850963654)); +#41210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41211 = PCURVE('',#41212,#41217); +#41212 = PLANE('',#41213); +#41213 = AXIS2_PLACEMENT_3D('',#41214,#41215,#41216); +#41214 = CARTESIAN_POINT('',(3.798447109038,2.5E-002,2.78)); +#41215 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41216 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); +#41217 = DEFINITIONAL_REPRESENTATION('',(#41218),#41222); +#41218 = LINE('',#41219,#41220); +#41219 = CARTESIAN_POINT('',(0.2,0.E+000)); +#41220 = VECTOR('',#41221,1.); +#41221 = DIRECTION('',(1.,0.E+000)); +#41222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41223 = ADVANCED_FACE('',(#41224),#40047,.T.); +#41224 = FACE_BOUND('',#41225,.F.); +#41225 = EDGE_LOOP('',(#41226,#41278,#41306,#41334,#41355,#41356)); +#41226 = ORIENTED_EDGE('',*,*,#41227,.F.); +#41227 = EDGE_CURVE('',#41228,#41230,#41232,.T.); +#41228 = VERTEX_POINT('',#41229); +#41229 = CARTESIAN_POINT('',(-3.644524343464,2.5E-002,2.652298072692)); +#41230 = VERTEX_POINT('',#41231); +#41231 = CARTESIAN_POINT('',(-3.836077234426,2.5E-002,2.421413924332)); +#41232 = SURFACE_CURVE('',#41233,(#41237,#41244),.PCURVE_S1.); +#41233 = LINE('',#41234,#41235); +#41234 = CARTESIAN_POINT('',(-3.644524343464,2.5E-002,2.652298072692)); +#41235 = VECTOR('',#41236,1.); +#41236 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#41237 = PCURVE('',#40047,#41238); +#41238 = DEFINITIONAL_REPRESENTATION('',(#41239),#41243); +#41239 = LINE('',#41240,#41241); +#41240 = CARTESIAN_POINT('',(-3.644524343464,2.652298072692)); +#41241 = VECTOR('',#41242,1.); +#41242 = DIRECTION('',(-0.63850963654,-0.769613827868)); +#41243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41244 = PCURVE('',#41245,#41250); +#41245 = CYLINDRICAL_SURFACE('',#41246,0.2); +#41246 = AXIS2_PLACEMENT_3D('',#41247,#41248,#41249); +#41247 = CARTESIAN_POINT('',(-3.634618101713,0.225,2.664238347666)); +#41248 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#41249 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41250 = DEFINITIONAL_REPRESENTATION('',(#41251),#41277); +#41251 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41252,#41253,#41254,#41255, + #41256,#41257,#41258,#41259,#41260,#41261,#41262,#41263,#41264, + #41265,#41266,#41267,#41268,#41269,#41270,#41271,#41272,#41273, + #41274,#41275,#41276),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363635E-002, 2.72727272727E-002,4.090909090905E-002,5.45454545454E-002, 6.818181818175E-002,8.18181818181E-002,9.545454545445E-002, @@ -48759,174 +51748,174 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#38860 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); -#38861 = CARTESIAN_POINT('',(-1.847411112976E-013,2.006008609389E-002)); -#38862 = CARTESIAN_POINT('',(-3.561595462998E-013,2.915099518479E-002)); -#38863 = CARTESIAN_POINT('',(-2.859934511434E-013,4.278735882114E-002)); -#38864 = CARTESIAN_POINT('',(-3.073097332162E-013,5.642372245749E-002)); -#38865 = CARTESIAN_POINT('',(-3.010924842783E-013,7.006008609385E-002)); -#38866 = CARTESIAN_POINT('',(-3.01980662698E-013,8.36964497302E-002)); -#38867 = CARTESIAN_POINT('',(-3.010924842783E-013,9.733281336655E-002)); -#38868 = CARTESIAN_POINT('',(-3.01980662698E-013,0.110969177003)); -#38869 = CARTESIAN_POINT('',(-3.010924842783E-013,0.124605540639)); -#38870 = CARTESIAN_POINT('',(-3.010924842783E-013,0.138241904276)); -#38871 = CARTESIAN_POINT('',(-3.028688411177E-013,0.151878267912)); -#38872 = CARTESIAN_POINT('',(-3.010924842783E-013,0.165514631548)); -#38873 = CARTESIAN_POINT('',(-3.028688411177E-013,0.179150995185)); -#38874 = CARTESIAN_POINT('',(-3.01980662698E-013,0.192787358821)); -#38875 = CARTESIAN_POINT('',(-3.01980662698E-013,0.206423722457)); -#38876 = CARTESIAN_POINT('',(-3.01980662698E-013,0.220060086094)); -#38877 = CARTESIAN_POINT('',(-3.010924842783E-013,0.23369644973)); -#38878 = CARTESIAN_POINT('',(-3.01980662698E-013,0.247332813366)); -#38879 = CARTESIAN_POINT('',(-3.002043058586E-013,0.260969177003)); -#38880 = CARTESIAN_POINT('',(-3.055333763768E-013,0.274605540639)); -#38881 = CARTESIAN_POINT('',(-2.868816295631E-013,0.288241904275)); -#38882 = CARTESIAN_POINT('',(-3.543831894603E-013,0.301878267912)); -#38883 = CARTESIAN_POINT('',(-1.838529328779E-013,0.310969177003)); -#38884 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#38885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38886 = ORIENTED_EDGE('',*,*,#38887,.F.); -#38887 = EDGE_CURVE('',#38888,#38836,#38890,.T.); -#38888 = VERTEX_POINT('',#38889); -#38889 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); -#38890 = SURFACE_CURVE('',#38891,(#38895,#38902),.PCURVE_S1.); -#38891 = LINE('',#38892,#38893); -#38892 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); -#38893 = VECTOR('',#38894,1.); -#38894 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#38895 = PCURVE('',#37655,#38896); -#38896 = DEFINITIONAL_REPRESENTATION('',(#38897),#38901); -#38897 = LINE('',#38898,#38899); -#38898 = CARTESIAN_POINT('',(-3.554832205403,2.577885045795)); -#38899 = VECTOR('',#38900,1.); -#38900 = DIRECTION('',(-0.769613827868,0.63850963654)); -#38901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38902 = PCURVE('',#38903,#38908); -#38903 = PLANE('',#38904); -#38904 = AXIS2_PLACEMENT_3D('',#38905,#38906,#38907); -#38905 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); -#38906 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#38907 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#38908 = DEFINITIONAL_REPRESENTATION('',(#38909),#38913); -#38909 = LINE('',#38910,#38911); -#38910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#38911 = VECTOR('',#38912,1.); -#38912 = DIRECTION('',(1.,0.E+000)); -#38913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38914 = ORIENTED_EDGE('',*,*,#38915,.F.); -#38915 = EDGE_CURVE('',#38916,#38888,#38918,.T.); -#38916 = VERTEX_POINT('',#38917); -#38917 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.354697035713)); -#38918 = SURFACE_CURVE('',#38919,(#38924,#38931),.PCURVE_S1.); -#38919 = CIRCLE('',#38920,0.29); -#38920 = AXIS2_PLACEMENT_3D('',#38921,#38922,#38923); -#38921 = CARTESIAN_POINT('',(-3.74,2.5E-002,2.354697035713)); -#38922 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38923 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38924 = PCURVE('',#37655,#38925); -#38925 = DEFINITIONAL_REPRESENTATION('',(#38926),#38930); -#38926 = CIRCLE('',#38927,0.29); -#38927 = AXIS2_PLACEMENT_2D('',#38928,#38929); -#38928 = CARTESIAN_POINT('',(-3.74,2.354697035713)); -#38929 = DIRECTION('',(1.,0.E+000)); -#38930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38931 = PCURVE('',#38932,#38937); -#38932 = CYLINDRICAL_SURFACE('',#38933,0.29); -#38933 = AXIS2_PLACEMENT_3D('',#38934,#38935,#38936); -#38934 = CARTESIAN_POINT('',(-3.74,2.5E-002,2.354697035713)); -#38935 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#38936 = DIRECTION('',(1.,0.E+000,0.E+000)); -#38937 = DEFINITIONAL_REPRESENTATION('',(#38938),#38941); -#38938 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#38939,#38940),.UNSPECIFIED., +#41252 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); +#41253 = CARTESIAN_POINT('',(-1.847411112976E-013,2.006008609389E-002)); +#41254 = CARTESIAN_POINT('',(-3.561595462998E-013,2.915099518479E-002)); +#41255 = CARTESIAN_POINT('',(-2.859934511434E-013,4.278735882114E-002)); +#41256 = CARTESIAN_POINT('',(-3.073097332162E-013,5.642372245749E-002)); +#41257 = CARTESIAN_POINT('',(-3.010924842783E-013,7.006008609385E-002)); +#41258 = CARTESIAN_POINT('',(-3.01980662698E-013,8.36964497302E-002)); +#41259 = CARTESIAN_POINT('',(-3.010924842783E-013,9.733281336655E-002)); +#41260 = CARTESIAN_POINT('',(-3.01980662698E-013,0.110969177003)); +#41261 = CARTESIAN_POINT('',(-3.010924842783E-013,0.124605540639)); +#41262 = CARTESIAN_POINT('',(-3.010924842783E-013,0.138241904276)); +#41263 = CARTESIAN_POINT('',(-3.028688411177E-013,0.151878267912)); +#41264 = CARTESIAN_POINT('',(-3.010924842783E-013,0.165514631548)); +#41265 = CARTESIAN_POINT('',(-3.028688411177E-013,0.179150995185)); +#41266 = CARTESIAN_POINT('',(-3.01980662698E-013,0.192787358821)); +#41267 = CARTESIAN_POINT('',(-3.01980662698E-013,0.206423722457)); +#41268 = CARTESIAN_POINT('',(-3.01980662698E-013,0.220060086094)); +#41269 = CARTESIAN_POINT('',(-3.010924842783E-013,0.23369644973)); +#41270 = CARTESIAN_POINT('',(-3.01980662698E-013,0.247332813366)); +#41271 = CARTESIAN_POINT('',(-3.002043058586E-013,0.260969177003)); +#41272 = CARTESIAN_POINT('',(-3.055333763768E-013,0.274605540639)); +#41273 = CARTESIAN_POINT('',(-2.868816295631E-013,0.288241904275)); +#41274 = CARTESIAN_POINT('',(-3.543831894603E-013,0.301878267912)); +#41275 = CARTESIAN_POINT('',(-1.838529328779E-013,0.310969177003)); +#41276 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#41277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41278 = ORIENTED_EDGE('',*,*,#41279,.F.); +#41279 = EDGE_CURVE('',#41280,#41228,#41282,.T.); +#41280 = VERTEX_POINT('',#41281); +#41281 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); +#41282 = SURFACE_CURVE('',#41283,(#41287,#41294),.PCURVE_S1.); +#41283 = LINE('',#41284,#41285); +#41284 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); +#41285 = VECTOR('',#41286,1.); +#41286 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#41287 = PCURVE('',#40047,#41288); +#41288 = DEFINITIONAL_REPRESENTATION('',(#41289),#41293); +#41289 = LINE('',#41290,#41291); +#41290 = CARTESIAN_POINT('',(-3.554832205403,2.577885045795)); +#41291 = VECTOR('',#41292,1.); +#41292 = DIRECTION('',(-0.769613827868,0.63850963654)); +#41293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41294 = PCURVE('',#41295,#41300); +#41295 = PLANE('',#41296); +#41296 = AXIS2_PLACEMENT_3D('',#41297,#41298,#41299); +#41297 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); +#41298 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#41299 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#41300 = DEFINITIONAL_REPRESENTATION('',(#41301),#41305); +#41301 = LINE('',#41302,#41303); +#41302 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#41303 = VECTOR('',#41304,1.); +#41304 = DIRECTION('',(1.,0.E+000)); +#41305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41306 = ORIENTED_EDGE('',*,*,#41307,.F.); +#41307 = EDGE_CURVE('',#41308,#41280,#41310,.T.); +#41308 = VERTEX_POINT('',#41309); +#41309 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.354697035713)); +#41310 = SURFACE_CURVE('',#41311,(#41316,#41323),.PCURVE_S1.); +#41311 = CIRCLE('',#41312,0.29); +#41312 = AXIS2_PLACEMENT_3D('',#41313,#41314,#41315); +#41313 = CARTESIAN_POINT('',(-3.74,2.5E-002,2.354697035713)); +#41314 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41315 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41316 = PCURVE('',#40047,#41317); +#41317 = DEFINITIONAL_REPRESENTATION('',(#41318),#41322); +#41318 = CIRCLE('',#41319,0.29); +#41319 = AXIS2_PLACEMENT_2D('',#41320,#41321); +#41320 = CARTESIAN_POINT('',(-3.74,2.354697035713)); +#41321 = DIRECTION('',(1.,0.E+000)); +#41322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41323 = PCURVE('',#41324,#41329); +#41324 = CYLINDRICAL_SURFACE('',#41325,0.29); +#41325 = AXIS2_PLACEMENT_3D('',#41326,#41327,#41328); +#41326 = CARTESIAN_POINT('',(-3.74,2.5E-002,2.354697035713)); +#41327 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41328 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41329 = DEFINITIONAL_REPRESENTATION('',(#41330),#41333); +#41330 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41331,#41332),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.878236128669),.PIECEWISE_BEZIER_KNOTS.); -#38939 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#38940 = CARTESIAN_POINT('',(0.878236128669,0.E+000)); -#38941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38942 = ORIENTED_EDGE('',*,*,#38943,.F.); -#38943 = EDGE_CURVE('',#37635,#38916,#38944,.T.); -#38944 = SURFACE_CURVE('',#38945,(#38949,#38956),.PCURVE_S1.); -#38945 = LINE('',#38946,#38947); -#38946 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.35)); -#38947 = VECTOR('',#38948,1.); -#38948 = DIRECTION('',(0.E+000,0.E+000,1.)); -#38949 = PCURVE('',#37655,#38950); -#38950 = DEFINITIONAL_REPRESENTATION('',(#38951),#38955); -#38951 = LINE('',#38952,#38953); -#38952 = CARTESIAN_POINT('',(-3.45,2.35)); -#38953 = VECTOR('',#38954,1.); -#38954 = DIRECTION('',(0.E+000,1.)); -#38955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38956 = PCURVE('',#37683,#38957); -#38957 = DEFINITIONAL_REPRESENTATION('',(#38958),#38962); -#38958 = LINE('',#38959,#38960); -#38959 = CARTESIAN_POINT('',(9.644660940673E-002,4.7)); -#38960 = VECTOR('',#38961,1.); -#38961 = DIRECTION('',(0.E+000,1.)); -#38962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38963 = ORIENTED_EDGE('',*,*,#37632,.F.); -#38964 = ORIENTED_EDGE('',*,*,#38965,.F.); -#38965 = EDGE_CURVE('',#38838,#37633,#38966,.T.); -#38966 = SURFACE_CURVE('',#38967,(#38971,#38978),.PCURVE_S1.); -#38967 = LINE('',#38968,#38969); -#38968 = CARTESIAN_POINT('',(-3.836077234426,2.5E-002,2.421413924332)); -#38969 = VECTOR('',#38970,1.); -#38970 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); -#38971 = PCURVE('',#37655,#38972); -#38972 = DEFINITIONAL_REPRESENTATION('',(#38973),#38977); -#38973 = LINE('',#38974,#38975); -#38974 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); -#38975 = VECTOR('',#38976,1.); -#38976 = DIRECTION('',(0.769613827868,-0.63850963654)); -#38977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38978 = PCURVE('',#38979,#38984); -#38979 = PLANE('',#38980); -#38980 = AXIS2_PLACEMENT_3D('',#38981,#38982,#38983); -#38981 = CARTESIAN_POINT('',(-3.99,2.5E-002,2.54911585164)); -#38982 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#38983 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); -#38984 = DEFINITIONAL_REPRESENTATION('',(#38985),#38989); -#38985 = LINE('',#38986,#38987); -#38986 = CARTESIAN_POINT('',(0.2,0.E+000)); -#38987 = VECTOR('',#38988,1.); -#38988 = DIRECTION('',(1.,0.E+000)); -#38989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#38990 = ADVANCED_FACE('',(#38991),#38694,.T.); -#38991 = FACE_BOUND('',#38992,.T.); -#38992 = EDGE_LOOP('',(#38993,#39039,#39040,#39086)); -#38993 = ORIENTED_EDGE('',*,*,#38994,.F.); -#38994 = EDGE_CURVE('',#38679,#38995,#38997,.T.); -#38995 = VERTEX_POINT('',#38996); -#38996 = CARTESIAN_POINT('',(3.798447109038,0.225,2.78)); -#38997 = SURFACE_CURVE('',#38998,(#39003,#39032),.PCURVE_S1.); -#38998 = CIRCLE('',#38999,0.2); -#38999 = AXIS2_PLACEMENT_3D('',#39000,#39001,#39002); -#39000 = CARTESIAN_POINT('',(3.644524343464,0.225,2.652298072692)); -#39001 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#39002 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39003 = PCURVE('',#38694,#39004); -#39004 = DEFINITIONAL_REPRESENTATION('',(#39005),#39031); -#39005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39006,#39007,#39008,#39009, - #39010,#39011,#39012,#39013,#39014,#39015,#39016,#39017,#39018, - #39019,#39020,#39021,#39022,#39023,#39024,#39025,#39026,#39027, - #39028,#39029,#39030),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41331 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#41332 = CARTESIAN_POINT('',(0.878236128669,0.E+000)); +#41333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41334 = ORIENTED_EDGE('',*,*,#41335,.F.); +#41335 = EDGE_CURVE('',#40027,#41308,#41336,.T.); +#41336 = SURFACE_CURVE('',#41337,(#41341,#41348),.PCURVE_S1.); +#41337 = LINE('',#41338,#41339); +#41338 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.35)); +#41339 = VECTOR('',#41340,1.); +#41340 = DIRECTION('',(0.E+000,0.E+000,1.)); +#41341 = PCURVE('',#40047,#41342); +#41342 = DEFINITIONAL_REPRESENTATION('',(#41343),#41347); +#41343 = LINE('',#41344,#41345); +#41344 = CARTESIAN_POINT('',(-3.45,2.35)); +#41345 = VECTOR('',#41346,1.); +#41346 = DIRECTION('',(0.E+000,1.)); +#41347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41348 = PCURVE('',#40075,#41349); +#41349 = DEFINITIONAL_REPRESENTATION('',(#41350),#41354); +#41350 = LINE('',#41351,#41352); +#41351 = CARTESIAN_POINT('',(9.644660940673E-002,4.7)); +#41352 = VECTOR('',#41353,1.); +#41353 = DIRECTION('',(0.E+000,1.)); +#41354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41355 = ORIENTED_EDGE('',*,*,#40024,.F.); +#41356 = ORIENTED_EDGE('',*,*,#41357,.F.); +#41357 = EDGE_CURVE('',#41230,#40025,#41358,.T.); +#41358 = SURFACE_CURVE('',#41359,(#41363,#41370),.PCURVE_S1.); +#41359 = LINE('',#41360,#41361); +#41360 = CARTESIAN_POINT('',(-3.836077234426,2.5E-002,2.421413924332)); +#41361 = VECTOR('',#41362,1.); +#41362 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); +#41363 = PCURVE('',#40047,#41364); +#41364 = DEFINITIONAL_REPRESENTATION('',(#41365),#41369); +#41365 = LINE('',#41366,#41367); +#41366 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); +#41367 = VECTOR('',#41368,1.); +#41368 = DIRECTION('',(0.769613827868,-0.63850963654)); +#41369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41370 = PCURVE('',#41371,#41376); +#41371 = PLANE('',#41372); +#41372 = AXIS2_PLACEMENT_3D('',#41373,#41374,#41375); +#41373 = CARTESIAN_POINT('',(-3.99,2.5E-002,2.54911585164)); +#41374 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#41375 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); +#41376 = DEFINITIONAL_REPRESENTATION('',(#41377),#41381); +#41377 = LINE('',#41378,#41379); +#41378 = CARTESIAN_POINT('',(0.2,0.E+000)); +#41379 = VECTOR('',#41380,1.); +#41380 = DIRECTION('',(1.,0.E+000)); +#41381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41382 = ADVANCED_FACE('',(#41383),#41086,.T.); +#41383 = FACE_BOUND('',#41384,.T.); +#41384 = EDGE_LOOP('',(#41385,#41431,#41432,#41478)); +#41385 = ORIENTED_EDGE('',*,*,#41386,.F.); +#41386 = EDGE_CURVE('',#41071,#41387,#41389,.T.); +#41387 = VERTEX_POINT('',#41388); +#41388 = CARTESIAN_POINT('',(3.798447109038,0.225,2.78)); +#41389 = SURFACE_CURVE('',#41390,(#41395,#41424),.PCURVE_S1.); +#41390 = CIRCLE('',#41391,0.2); +#41391 = AXIS2_PLACEMENT_3D('',#41392,#41393,#41394); +#41392 = CARTESIAN_POINT('',(3.644524343464,0.225,2.652298072692)); +#41393 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41394 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41395 = PCURVE('',#41086,#41396); +#41396 = DEFINITIONAL_REPRESENTATION('',(#41397),#41423); +#41397 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41398,#41399,#41400,#41401, + #41402,#41403,#41404,#41405,#41406,#41407,#41408,#41409,#41410, + #41411,#41412,#41413,#41414,#41415,#41416,#41417,#41418,#41419, + #41420,#41421,#41422),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -48934,60 +51923,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#39006 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#39007 = CARTESIAN_POINT('',(2.379994434458E-002,0.315514631548)); -#39008 = CARTESIAN_POINT('',(7.139983303459E-002,0.315514631548)); -#39009 = CARTESIAN_POINT('',(0.142799666071,0.315514631548)); -#39010 = CARTESIAN_POINT('',(0.214199499107,0.315514631548)); -#39011 = CARTESIAN_POINT('',(0.285599332143,0.315514631548)); -#39012 = CARTESIAN_POINT('',(0.356999165179,0.315514631548)); -#39013 = CARTESIAN_POINT('',(0.428398998216,0.315514631548)); -#39014 = CARTESIAN_POINT('',(0.499798831252,0.315514631548)); -#39015 = CARTESIAN_POINT('',(0.571198664288,0.315514631548)); -#39016 = CARTESIAN_POINT('',(0.642598497324,0.315514631548)); -#39017 = CARTESIAN_POINT('',(0.71399833036,0.315514631548)); -#39018 = CARTESIAN_POINT('',(0.785398163397,0.315514631548)); -#39019 = CARTESIAN_POINT('',(0.856797996433,0.315514631548)); -#39020 = CARTESIAN_POINT('',(0.928197829469,0.315514631548)); -#39021 = CARTESIAN_POINT('',(0.999597662505,0.315514631548)); -#39022 = CARTESIAN_POINT('',(1.070997495541,0.315514631548)); -#39023 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); -#39024 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); -#39025 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); -#39026 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); -#39027 = CARTESIAN_POINT('',(1.427996660722,0.315514631548)); -#39028 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); -#39029 = CARTESIAN_POINT('',(1.546996382449,0.315514631548)); -#39030 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#39031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39032 = PCURVE('',#38820,#39033); -#39033 = DEFINITIONAL_REPRESENTATION('',(#39034),#39038); -#39034 = CIRCLE('',#39035,0.2); -#39035 = AXIS2_PLACEMENT_2D('',#39036,#39037); -#39036 = CARTESIAN_POINT('',(0.2,-0.2)); -#39037 = DIRECTION('',(0.E+000,1.)); -#39038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39039 = ORIENTED_EDGE('',*,*,#38676,.F.); -#39040 = ORIENTED_EDGE('',*,*,#39041,.F.); -#39041 = EDGE_CURVE('',#39042,#38677,#39044,.T.); -#39042 = VERTEX_POINT('',#39043); -#39043 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); -#39044 = SURFACE_CURVE('',#39045,(#39050,#39079),.PCURVE_S1.); -#39045 = CIRCLE('',#39046,0.2); -#39046 = AXIS2_PLACEMENT_3D('',#39047,#39048,#39049); -#39047 = CARTESIAN_POINT('',(3.836077234426,0.225,2.421413924332)); -#39048 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#39049 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#39050 = PCURVE('',#38694,#39051); -#39051 = DEFINITIONAL_REPRESENTATION('',(#39052),#39078); -#39052 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39053,#39054,#39055,#39056, - #39057,#39058,#39059,#39060,#39061,#39062,#39063,#39064,#39065, - #39066,#39067,#39068,#39069,#39070,#39071,#39072,#39073,#39074, - #39075,#39076,#39077),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41398 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#41399 = CARTESIAN_POINT('',(2.379994434458E-002,0.315514631548)); +#41400 = CARTESIAN_POINT('',(7.139983303459E-002,0.315514631548)); +#41401 = CARTESIAN_POINT('',(0.142799666071,0.315514631548)); +#41402 = CARTESIAN_POINT('',(0.214199499107,0.315514631548)); +#41403 = CARTESIAN_POINT('',(0.285599332143,0.315514631548)); +#41404 = CARTESIAN_POINT('',(0.356999165179,0.315514631548)); +#41405 = CARTESIAN_POINT('',(0.428398998216,0.315514631548)); +#41406 = CARTESIAN_POINT('',(0.499798831252,0.315514631548)); +#41407 = CARTESIAN_POINT('',(0.571198664288,0.315514631548)); +#41408 = CARTESIAN_POINT('',(0.642598497324,0.315514631548)); +#41409 = CARTESIAN_POINT('',(0.71399833036,0.315514631548)); +#41410 = CARTESIAN_POINT('',(0.785398163397,0.315514631548)); +#41411 = CARTESIAN_POINT('',(0.856797996433,0.315514631548)); +#41412 = CARTESIAN_POINT('',(0.928197829469,0.315514631548)); +#41413 = CARTESIAN_POINT('',(0.999597662505,0.315514631548)); +#41414 = CARTESIAN_POINT('',(1.070997495541,0.315514631548)); +#41415 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); +#41416 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); +#41417 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); +#41418 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); +#41419 = CARTESIAN_POINT('',(1.427996660722,0.315514631548)); +#41420 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); +#41421 = CARTESIAN_POINT('',(1.546996382449,0.315514631548)); +#41422 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#41423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41424 = PCURVE('',#41212,#41425); +#41425 = DEFINITIONAL_REPRESENTATION('',(#41426),#41430); +#41426 = CIRCLE('',#41427,0.2); +#41427 = AXIS2_PLACEMENT_2D('',#41428,#41429); +#41428 = CARTESIAN_POINT('',(0.2,-0.2)); +#41429 = DIRECTION('',(0.E+000,1.)); +#41430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41431 = ORIENTED_EDGE('',*,*,#41068,.F.); +#41432 = ORIENTED_EDGE('',*,*,#41433,.F.); +#41433 = EDGE_CURVE('',#41434,#41069,#41436,.T.); +#41434 = VERTEX_POINT('',#41435); +#41435 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); +#41436 = SURFACE_CURVE('',#41437,(#41442,#41471),.PCURVE_S1.); +#41437 = CIRCLE('',#41438,0.2); +#41438 = AXIS2_PLACEMENT_3D('',#41439,#41440,#41441); +#41439 = CARTESIAN_POINT('',(3.836077234426,0.225,2.421413924332)); +#41440 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41441 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41442 = PCURVE('',#41086,#41443); +#41443 = DEFINITIONAL_REPRESENTATION('',(#41444),#41470); +#41444 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41445,#41446,#41447,#41448, + #41449,#41450,#41451,#41452,#41453,#41454,#41455,#41456,#41457, + #41458,#41459,#41460,#41461,#41462,#41463,#41464,#41465,#41466, + #41467,#41468,#41469),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -48995,108 +51984,108 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#39053 = CARTESIAN_POINT('',(1.570796326795,1.551463154844E-002)); -#39054 = CARTESIAN_POINT('',(1.54699638245,1.551463154844E-002)); -#39055 = CARTESIAN_POINT('',(1.499396493759,1.551463154844E-002)); -#39056 = CARTESIAN_POINT('',(1.427996660723,1.551463154844E-002)); -#39057 = CARTESIAN_POINT('',(1.356596827687,1.551463154844E-002)); -#39058 = CARTESIAN_POINT('',(1.28519699465,1.551463154844E-002)); -#39059 = CARTESIAN_POINT('',(1.213797161614,1.551463154844E-002)); -#39060 = CARTESIAN_POINT('',(1.142397328578,1.551463154844E-002)); -#39061 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); -#39062 = CARTESIAN_POINT('',(0.999597662506,1.551463154844E-002)); -#39063 = CARTESIAN_POINT('',(0.92819782947,1.551463154844E-002)); -#39064 = CARTESIAN_POINT('',(0.856797996434,1.551463154844E-002)); -#39065 = CARTESIAN_POINT('',(0.785398163398,1.551463154844E-002)); -#39066 = CARTESIAN_POINT('',(0.713998330362,1.551463154844E-002)); -#39067 = CARTESIAN_POINT('',(0.642598497325,1.551463154844E-002)); -#39068 = CARTESIAN_POINT('',(0.571198664289,1.551463154844E-002)); -#39069 = CARTESIAN_POINT('',(0.499798831253,1.551463154844E-002)); -#39070 = CARTESIAN_POINT('',(0.428398998217,1.551463154844E-002)); -#39071 = CARTESIAN_POINT('',(0.356999165181,1.551463154844E-002)); -#39072 = CARTESIAN_POINT('',(0.285599332145,1.551463154844E-002)); -#39073 = CARTESIAN_POINT('',(0.214199499109,1.551463154844E-002)); -#39074 = CARTESIAN_POINT('',(0.142799666073,1.551463154844E-002)); -#39075 = CARTESIAN_POINT('',(7.139983303648E-002,1.551463154844E-002)); -#39076 = CARTESIAN_POINT('',(2.379994434556E-002,1.551463154844E-002)); -#39077 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); -#39078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39079 = PCURVE('',#38742,#39080); -#39080 = DEFINITIONAL_REPRESENTATION('',(#39081),#39085); -#39081 = CIRCLE('',#39082,0.2); -#39082 = AXIS2_PLACEMENT_2D('',#39083,#39084); -#39083 = CARTESIAN_POINT('',(0.111844708748,-0.2)); -#39084 = DIRECTION('',(1.,0.E+000)); -#39085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39086 = ORIENTED_EDGE('',*,*,#39087,.T.); -#39087 = EDGE_CURVE('',#39042,#38995,#39088,.T.); -#39088 = SURFACE_CURVE('',#39089,(#39093,#39099),.PCURVE_S1.); -#39089 = LINE('',#39090,#39091); -#39090 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); -#39091 = VECTOR('',#39092,1.); -#39092 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#39093 = PCURVE('',#38694,#39094); -#39094 = DEFINITIONAL_REPRESENTATION('',(#39095),#39098); -#39095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39096,#39097),.UNSPECIFIED., +#41445 = CARTESIAN_POINT('',(1.570796326795,1.551463154844E-002)); +#41446 = CARTESIAN_POINT('',(1.54699638245,1.551463154844E-002)); +#41447 = CARTESIAN_POINT('',(1.499396493759,1.551463154844E-002)); +#41448 = CARTESIAN_POINT('',(1.427996660723,1.551463154844E-002)); +#41449 = CARTESIAN_POINT('',(1.356596827687,1.551463154844E-002)); +#41450 = CARTESIAN_POINT('',(1.28519699465,1.551463154844E-002)); +#41451 = CARTESIAN_POINT('',(1.213797161614,1.551463154844E-002)); +#41452 = CARTESIAN_POINT('',(1.142397328578,1.551463154844E-002)); +#41453 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); +#41454 = CARTESIAN_POINT('',(0.999597662506,1.551463154844E-002)); +#41455 = CARTESIAN_POINT('',(0.92819782947,1.551463154844E-002)); +#41456 = CARTESIAN_POINT('',(0.856797996434,1.551463154844E-002)); +#41457 = CARTESIAN_POINT('',(0.785398163398,1.551463154844E-002)); +#41458 = CARTESIAN_POINT('',(0.713998330362,1.551463154844E-002)); +#41459 = CARTESIAN_POINT('',(0.642598497325,1.551463154844E-002)); +#41460 = CARTESIAN_POINT('',(0.571198664289,1.551463154844E-002)); +#41461 = CARTESIAN_POINT('',(0.499798831253,1.551463154844E-002)); +#41462 = CARTESIAN_POINT('',(0.428398998217,1.551463154844E-002)); +#41463 = CARTESIAN_POINT('',(0.356999165181,1.551463154844E-002)); +#41464 = CARTESIAN_POINT('',(0.285599332145,1.551463154844E-002)); +#41465 = CARTESIAN_POINT('',(0.214199499109,1.551463154844E-002)); +#41466 = CARTESIAN_POINT('',(0.142799666073,1.551463154844E-002)); +#41467 = CARTESIAN_POINT('',(7.139983303648E-002,1.551463154844E-002)); +#41468 = CARTESIAN_POINT('',(2.379994434556E-002,1.551463154844E-002)); +#41469 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); +#41470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41471 = PCURVE('',#41134,#41472); +#41472 = DEFINITIONAL_REPRESENTATION('',(#41473),#41477); +#41473 = CIRCLE('',#41474,0.2); +#41474 = AXIS2_PLACEMENT_2D('',#41475,#41476); +#41475 = CARTESIAN_POINT('',(0.111844708748,-0.2)); +#41476 = DIRECTION('',(1.,0.E+000)); +#41477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41478 = ORIENTED_EDGE('',*,*,#41479,.T.); +#41479 = EDGE_CURVE('',#41434,#41387,#41480,.T.); +#41480 = SURFACE_CURVE('',#41481,(#41485,#41491),.PCURVE_S1.); +#41481 = LINE('',#41482,#41483); +#41482 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); +#41483 = VECTOR('',#41484,1.); +#41484 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41485 = PCURVE('',#41086,#41486); +#41486 = DEFINITIONAL_REPRESENTATION('',(#41487),#41490); +#41487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41488,#41489),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39096 = CARTESIAN_POINT('',(1.570796326795,1.551463154823E-002)); -#39097 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#39098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39099 = PCURVE('',#39100,#39105); -#39100 = PLANE('',#39101); -#39101 = AXIS2_PLACEMENT_3D('',#39102,#39103,#39104); -#39102 = CARTESIAN_POINT('',(3.99,2.5E-002,2.54911585164)); -#39103 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#39104 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#39105 = DEFINITIONAL_REPRESENTATION('',(#39106),#39110); -#39106 = LINE('',#39107,#39108); -#39107 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#39108 = VECTOR('',#39109,1.); -#39109 = DIRECTION('',(1.,0.E+000)); -#39110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39111 = ADVANCED_FACE('',(#39112),#38820,.T.); -#39112 = FACE_BOUND('',#39113,.F.); -#39113 = EDGE_LOOP('',(#39114,#39167,#39188,#39189,#39190,#39212)); -#39114 = ORIENTED_EDGE('',*,*,#39115,.F.); -#39115 = EDGE_CURVE('',#39116,#39118,#39120,.T.); -#39116 = VERTEX_POINT('',#39117); -#39117 = CARTESIAN_POINT('',(3.798447109038,0.425,2.78)); -#39118 = VERTEX_POINT('',#39119); -#39119 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); -#39120 = SURFACE_CURVE('',#39121,(#39126,#39133),.PCURVE_S1.); -#39121 = CIRCLE('',#39122,0.2); -#39122 = AXIS2_PLACEMENT_3D('',#39123,#39124,#39125); -#39123 = CARTESIAN_POINT('',(3.644524343464,0.425,2.652298072692)); -#39124 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#39125 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#39126 = PCURVE('',#38820,#39127); -#39127 = DEFINITIONAL_REPRESENTATION('',(#39128),#39132); -#39128 = CIRCLE('',#39129,0.2); -#39129 = AXIS2_PLACEMENT_2D('',#39130,#39131); -#39130 = CARTESIAN_POINT('',(0.2,-0.4)); -#39131 = DIRECTION('',(-1.,0.E+000)); -#39132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39133 = PCURVE('',#39134,#39139); -#39134 = CYLINDRICAL_SURFACE('',#39135,0.2); -#39135 = AXIS2_PLACEMENT_3D('',#39136,#39137,#39138); -#39136 = CARTESIAN_POINT('',(3.630451975851,0.425,2.669259897676)); -#39137 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#39138 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39139 = DEFINITIONAL_REPRESENTATION('',(#39140),#39166); -#39140 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39141,#39142,#39143,#39144, - #39145,#39146,#39147,#39148,#39149,#39150,#39151,#39152,#39153, - #39154,#39155,#39156,#39157,#39158,#39159,#39160,#39161,#39162, - #39163,#39164,#39165),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41488 = CARTESIAN_POINT('',(1.570796326795,1.551463154823E-002)); +#41489 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#41490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41491 = PCURVE('',#41492,#41497); +#41492 = PLANE('',#41493); +#41493 = AXIS2_PLACEMENT_3D('',#41494,#41495,#41496); +#41494 = CARTESIAN_POINT('',(3.99,2.5E-002,2.54911585164)); +#41495 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41496 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41497 = DEFINITIONAL_REPRESENTATION('',(#41498),#41502); +#41498 = LINE('',#41499,#41500); +#41499 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#41500 = VECTOR('',#41501,1.); +#41501 = DIRECTION('',(1.,0.E+000)); +#41502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41503 = ADVANCED_FACE('',(#41504),#41212,.T.); +#41504 = FACE_BOUND('',#41505,.F.); +#41505 = EDGE_LOOP('',(#41506,#41559,#41580,#41581,#41582,#41604)); +#41506 = ORIENTED_EDGE('',*,*,#41507,.F.); +#41507 = EDGE_CURVE('',#41508,#41510,#41512,.T.); +#41508 = VERTEX_POINT('',#41509); +#41509 = CARTESIAN_POINT('',(3.798447109038,0.425,2.78)); +#41510 = VERTEX_POINT('',#41511); +#41511 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); +#41512 = SURFACE_CURVE('',#41513,(#41518,#41525),.PCURVE_S1.); +#41513 = CIRCLE('',#41514,0.2); +#41514 = AXIS2_PLACEMENT_3D('',#41515,#41516,#41517); +#41515 = CARTESIAN_POINT('',(3.644524343464,0.425,2.652298072692)); +#41516 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41517 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41518 = PCURVE('',#41212,#41519); +#41519 = DEFINITIONAL_REPRESENTATION('',(#41520),#41524); +#41520 = CIRCLE('',#41521,0.2); +#41521 = AXIS2_PLACEMENT_2D('',#41522,#41523); +#41522 = CARTESIAN_POINT('',(0.2,-0.4)); +#41523 = DIRECTION('',(-1.,0.E+000)); +#41524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41525 = PCURVE('',#41526,#41531); +#41526 = CYLINDRICAL_SURFACE('',#41527,0.2); +#41527 = AXIS2_PLACEMENT_3D('',#41528,#41529,#41530); +#41528 = CARTESIAN_POINT('',(3.630451975851,0.425,2.669259897676)); +#41529 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41530 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41531 = DEFINITIONAL_REPRESENTATION('',(#41532),#41558); +#41532 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41533,#41534,#41535,#41536, + #41537,#41538,#41539,#41540,#41541,#41542,#41543,#41544,#41545, + #41546,#41547,#41548,#41549,#41550,#41551,#41552,#41553,#41554, + #41555,#41556,#41557),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -49104,134 +52093,134 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#39141 = CARTESIAN_POINT('',(1.570796326795,2.20393973834E-002)); -#39142 = CARTESIAN_POINT('',(1.54699638245,2.20393973834E-002)); -#39143 = CARTESIAN_POINT('',(1.499396493759,2.20393973834E-002)); -#39144 = CARTESIAN_POINT('',(1.427996660723,2.20393973834E-002)); -#39145 = CARTESIAN_POINT('',(1.356596827687,2.20393973834E-002)); -#39146 = CARTESIAN_POINT('',(1.285196994651,2.20393973834E-002)); -#39147 = CARTESIAN_POINT('',(1.213797161615,2.20393973834E-002)); -#39148 = CARTESIAN_POINT('',(1.142397328579,2.20393973834E-002)); -#39149 = CARTESIAN_POINT('',(1.070997495543,2.20393973834E-002)); -#39150 = CARTESIAN_POINT('',(0.999597662506,2.20393973834E-002)); -#39151 = CARTESIAN_POINT('',(0.92819782947,2.20393973834E-002)); -#39152 = CARTESIAN_POINT('',(0.856797996434,2.20393973834E-002)); -#39153 = CARTESIAN_POINT('',(0.785398163398,2.20393973834E-002)); -#39154 = CARTESIAN_POINT('',(0.713998330362,2.20393973834E-002)); -#39155 = CARTESIAN_POINT('',(0.642598497326,2.20393973834E-002)); -#39156 = CARTESIAN_POINT('',(0.57119866429,2.20393973834E-002)); -#39157 = CARTESIAN_POINT('',(0.499798831254,2.20393973834E-002)); -#39158 = CARTESIAN_POINT('',(0.428398998218,2.20393973834E-002)); -#39159 = CARTESIAN_POINT('',(0.356999165182,2.20393973834E-002)); -#39160 = CARTESIAN_POINT('',(0.285599332146,2.20393973834E-002)); -#39161 = CARTESIAN_POINT('',(0.21419949911,2.20393973834E-002)); -#39162 = CARTESIAN_POINT('',(0.142799666073,2.20393973834E-002)); -#39163 = CARTESIAN_POINT('',(7.139983303744E-002,2.20393973834E-002)); -#39164 = CARTESIAN_POINT('',(2.379994434606E-002,2.20393973834E-002)); -#39165 = CARTESIAN_POINT('',(0.E+000,2.20393973834E-002)); -#39166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39167 = ORIENTED_EDGE('',*,*,#39168,.F.); -#39168 = EDGE_CURVE('',#38995,#39116,#39169,.T.); -#39169 = SURFACE_CURVE('',#39170,(#39174,#39181),.PCURVE_S1.); -#39170 = LINE('',#39171,#39172); -#39171 = CARTESIAN_POINT('',(3.798447109038,0.225,2.78)); -#39172 = VECTOR('',#39173,1.); -#39173 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39174 = PCURVE('',#38820,#39175); -#39175 = DEFINITIONAL_REPRESENTATION('',(#39176),#39180); -#39176 = LINE('',#39177,#39178); -#39177 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#39178 = VECTOR('',#39179,1.); -#39179 = DIRECTION('',(0.E+000,-1.)); -#39180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39181 = PCURVE('',#39100,#39182); -#39182 = DEFINITIONAL_REPRESENTATION('',(#39183),#39187); -#39183 = LINE('',#39184,#39185); -#39184 = CARTESIAN_POINT('',(0.3,-0.2)); -#39185 = VECTOR('',#39186,1.); -#39186 = DIRECTION('',(0.E+000,-1.)); -#39187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39188 = ORIENTED_EDGE('',*,*,#38994,.F.); -#39189 = ORIENTED_EDGE('',*,*,#38806,.T.); -#39190 = ORIENTED_EDGE('',*,*,#39191,.T.); -#39191 = EDGE_CURVE('',#38779,#39192,#39194,.T.); -#39192 = VERTEX_POINT('',#39193); -#39193 = CARTESIAN_POINT('',(3.554832205403,0.625,2.577885045795)); -#39194 = SURFACE_CURVE('',#39195,(#39199,#39206),.PCURVE_S1.); -#39195 = LINE('',#39196,#39197); -#39196 = CARTESIAN_POINT('',(3.554832205403,2.5E-002,2.577885045795)); -#39197 = VECTOR('',#39198,1.); -#39198 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39199 = PCURVE('',#38820,#39200); -#39200 = DEFINITIONAL_REPRESENTATION('',(#39201),#39205); -#39201 = LINE('',#39202,#39203); -#39202 = CARTESIAN_POINT('',(0.316541744461,0.E+000)); -#39203 = VECTOR('',#39204,1.); -#39204 = DIRECTION('',(0.E+000,-1.)); -#39205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39206 = PCURVE('',#38795,#39207); -#39207 = DEFINITIONAL_REPRESENTATION('',(#39208),#39211); -#39208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39209,#39210),.UNSPECIFIED., +#41533 = CARTESIAN_POINT('',(1.570796326795,2.20393973834E-002)); +#41534 = CARTESIAN_POINT('',(1.54699638245,2.20393973834E-002)); +#41535 = CARTESIAN_POINT('',(1.499396493759,2.20393973834E-002)); +#41536 = CARTESIAN_POINT('',(1.427996660723,2.20393973834E-002)); +#41537 = CARTESIAN_POINT('',(1.356596827687,2.20393973834E-002)); +#41538 = CARTESIAN_POINT('',(1.285196994651,2.20393973834E-002)); +#41539 = CARTESIAN_POINT('',(1.213797161615,2.20393973834E-002)); +#41540 = CARTESIAN_POINT('',(1.142397328579,2.20393973834E-002)); +#41541 = CARTESIAN_POINT('',(1.070997495543,2.20393973834E-002)); +#41542 = CARTESIAN_POINT('',(0.999597662506,2.20393973834E-002)); +#41543 = CARTESIAN_POINT('',(0.92819782947,2.20393973834E-002)); +#41544 = CARTESIAN_POINT('',(0.856797996434,2.20393973834E-002)); +#41545 = CARTESIAN_POINT('',(0.785398163398,2.20393973834E-002)); +#41546 = CARTESIAN_POINT('',(0.713998330362,2.20393973834E-002)); +#41547 = CARTESIAN_POINT('',(0.642598497326,2.20393973834E-002)); +#41548 = CARTESIAN_POINT('',(0.57119866429,2.20393973834E-002)); +#41549 = CARTESIAN_POINT('',(0.499798831254,2.20393973834E-002)); +#41550 = CARTESIAN_POINT('',(0.428398998218,2.20393973834E-002)); +#41551 = CARTESIAN_POINT('',(0.356999165182,2.20393973834E-002)); +#41552 = CARTESIAN_POINT('',(0.285599332146,2.20393973834E-002)); +#41553 = CARTESIAN_POINT('',(0.21419949911,2.20393973834E-002)); +#41554 = CARTESIAN_POINT('',(0.142799666073,2.20393973834E-002)); +#41555 = CARTESIAN_POINT('',(7.139983303744E-002,2.20393973834E-002)); +#41556 = CARTESIAN_POINT('',(2.379994434606E-002,2.20393973834E-002)); +#41557 = CARTESIAN_POINT('',(0.E+000,2.20393973834E-002)); +#41558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41559 = ORIENTED_EDGE('',*,*,#41560,.F.); +#41560 = EDGE_CURVE('',#41387,#41508,#41561,.T.); +#41561 = SURFACE_CURVE('',#41562,(#41566,#41573),.PCURVE_S1.); +#41562 = LINE('',#41563,#41564); +#41563 = CARTESIAN_POINT('',(3.798447109038,0.225,2.78)); +#41564 = VECTOR('',#41565,1.); +#41565 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41566 = PCURVE('',#41212,#41567); +#41567 = DEFINITIONAL_REPRESENTATION('',(#41568),#41572); +#41568 = LINE('',#41569,#41570); +#41569 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#41570 = VECTOR('',#41571,1.); +#41571 = DIRECTION('',(0.E+000,-1.)); +#41572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41573 = PCURVE('',#41492,#41574); +#41574 = DEFINITIONAL_REPRESENTATION('',(#41575),#41579); +#41575 = LINE('',#41576,#41577); +#41576 = CARTESIAN_POINT('',(0.3,-0.2)); +#41577 = VECTOR('',#41578,1.); +#41578 = DIRECTION('',(0.E+000,-1.)); +#41579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41580 = ORIENTED_EDGE('',*,*,#41386,.F.); +#41581 = ORIENTED_EDGE('',*,*,#41198,.T.); +#41582 = ORIENTED_EDGE('',*,*,#41583,.T.); +#41583 = EDGE_CURVE('',#41171,#41584,#41586,.T.); +#41584 = VERTEX_POINT('',#41585); +#41585 = CARTESIAN_POINT('',(3.554832205403,0.625,2.577885045795)); +#41586 = SURFACE_CURVE('',#41587,(#41591,#41598),.PCURVE_S1.); +#41587 = LINE('',#41588,#41589); +#41588 = CARTESIAN_POINT('',(3.554832205403,2.5E-002,2.577885045795)); +#41589 = VECTOR('',#41590,1.); +#41590 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41591 = PCURVE('',#41212,#41592); +#41592 = DEFINITIONAL_REPRESENTATION('',(#41593),#41597); +#41593 = LINE('',#41594,#41595); +#41594 = CARTESIAN_POINT('',(0.316541744461,0.E+000)); +#41595 = VECTOR('',#41596,1.); +#41596 = DIRECTION('',(0.E+000,-1.)); +#41597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41598 = PCURVE('',#41187,#41599); +#41599 = DEFINITIONAL_REPRESENTATION('',(#41600),#41603); +#41600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41601,#41602),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.6),.PIECEWISE_BEZIER_KNOTS.); -#39209 = CARTESIAN_POINT('',(2.263356524921,0.E+000)); -#39210 = CARTESIAN_POINT('',(2.263356524921,-0.6)); -#39211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39212 = ORIENTED_EDGE('',*,*,#39213,.F.); -#39213 = EDGE_CURVE('',#39118,#39192,#39214,.T.); -#39214 = SURFACE_CURVE('',#39215,(#39219,#39226),.PCURVE_S1.); -#39215 = LINE('',#39216,#39217); -#39216 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); -#39217 = VECTOR('',#39218,1.); -#39218 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); -#39219 = PCURVE('',#38820,#39220); -#39220 = DEFINITIONAL_REPRESENTATION('',(#39221),#39225); -#39221 = LINE('',#39222,#39223); -#39222 = CARTESIAN_POINT('',(0.2,-0.6)); -#39223 = VECTOR('',#39224,1.); -#39224 = DIRECTION('',(1.,0.E+000)); -#39225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39226 = PCURVE('',#38529,#39227); -#39227 = DEFINITIONAL_REPRESENTATION('',(#39228),#39232); -#39228 = LINE('',#39229,#39230); -#39229 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); -#39230 = VECTOR('',#39231,1.); -#39231 = DIRECTION('',(-0.769613827868,-0.63850963654)); -#39232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39233 = ADVANCED_FACE('',(#39234),#39134,.T.); -#39234 = FACE_BOUND('',#39235,.T.); -#39235 = EDGE_LOOP('',(#39236,#39284,#39327,#39328)); -#39236 = ORIENTED_EDGE('',*,*,#39237,.F.); -#39237 = EDGE_CURVE('',#39238,#39240,#39242,.T.); -#39238 = VERTEX_POINT('',#39239); -#39239 = CARTESIAN_POINT('',(3.836077234426,0.625,2.421413924332)); -#39240 = VERTEX_POINT('',#39241); -#39241 = CARTESIAN_POINT('',(3.99,0.425,2.54911585164)); -#39242 = SURFACE_CURVE('',#39243,(#39248,#39277),.PCURVE_S1.); -#39243 = CIRCLE('',#39244,0.2); -#39244 = AXIS2_PLACEMENT_3D('',#39245,#39246,#39247); -#39245 = CARTESIAN_POINT('',(3.836077234426,0.425,2.421413924332)); -#39246 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#39247 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39248 = PCURVE('',#39134,#39249); -#39249 = DEFINITIONAL_REPRESENTATION('',(#39250),#39276); -#39250 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39251,#39252,#39253,#39254, - #39255,#39256,#39257,#39258,#39259,#39260,#39261,#39262,#39263, - #39264,#39265,#39266,#39267,#39268,#39269,#39270,#39271,#39272, - #39273,#39274,#39275),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41601 = CARTESIAN_POINT('',(2.263356524921,0.E+000)); +#41602 = CARTESIAN_POINT('',(2.263356524921,-0.6)); +#41603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41604 = ORIENTED_EDGE('',*,*,#41605,.F.); +#41605 = EDGE_CURVE('',#41510,#41584,#41606,.T.); +#41606 = SURFACE_CURVE('',#41607,(#41611,#41618),.PCURVE_S1.); +#41607 = LINE('',#41608,#41609); +#41608 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); +#41609 = VECTOR('',#41610,1.); +#41610 = DIRECTION('',(-0.769613827868,0.E+000,-0.63850963654)); +#41611 = PCURVE('',#41212,#41612); +#41612 = DEFINITIONAL_REPRESENTATION('',(#41613),#41617); +#41613 = LINE('',#41614,#41615); +#41614 = CARTESIAN_POINT('',(0.2,-0.6)); +#41615 = VECTOR('',#41616,1.); +#41616 = DIRECTION('',(1.,0.E+000)); +#41617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41618 = PCURVE('',#40921,#41619); +#41619 = DEFINITIONAL_REPRESENTATION('',(#41620),#41624); +#41620 = LINE('',#41621,#41622); +#41621 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); +#41622 = VECTOR('',#41623,1.); +#41623 = DIRECTION('',(-0.769613827868,-0.63850963654)); +#41624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41625 = ADVANCED_FACE('',(#41626),#41526,.T.); +#41626 = FACE_BOUND('',#41627,.T.); +#41627 = EDGE_LOOP('',(#41628,#41676,#41719,#41720)); +#41628 = ORIENTED_EDGE('',*,*,#41629,.F.); +#41629 = EDGE_CURVE('',#41630,#41632,#41634,.T.); +#41630 = VERTEX_POINT('',#41631); +#41631 = CARTESIAN_POINT('',(3.836077234426,0.625,2.421413924332)); +#41632 = VERTEX_POINT('',#41633); +#41633 = CARTESIAN_POINT('',(3.99,0.425,2.54911585164)); +#41634 = SURFACE_CURVE('',#41635,(#41640,#41669),.PCURVE_S1.); +#41635 = CIRCLE('',#41636,0.2); +#41636 = AXIS2_PLACEMENT_3D('',#41637,#41638,#41639); +#41637 = CARTESIAN_POINT('',(3.836077234426,0.425,2.421413924332)); +#41638 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41639 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41640 = PCURVE('',#41526,#41641); +#41641 = DEFINITIONAL_REPRESENTATION('',(#41642),#41668); +#41642 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41643,#41644,#41645,#41646, + #41647,#41648,#41649,#41650,#41651,#41652,#41653,#41654,#41655, + #41656,#41657,#41658,#41659,#41660,#41661,#41662,#41663,#41664, + #41665,#41666,#41667),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -49239,56 +52228,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#39251 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); -#39252 = CARTESIAN_POINT('',(2.379994434704E-002,0.322039397383)); -#39253 = CARTESIAN_POINT('',(7.139983303933E-002,0.322039397383)); -#39254 = CARTESIAN_POINT('',(0.142799666075,0.322039397383)); -#39255 = CARTESIAN_POINT('',(0.214199499111,0.322039397383)); -#39256 = CARTESIAN_POINT('',(0.285599332147,0.322039397383)); -#39257 = CARTESIAN_POINT('',(0.356999165183,0.322039397383)); -#39258 = CARTESIAN_POINT('',(0.428398998219,0.322039397383)); -#39259 = CARTESIAN_POINT('',(0.499798831255,0.322039397383)); -#39260 = CARTESIAN_POINT('',(0.571198664291,0.322039397383)); -#39261 = CARTESIAN_POINT('',(0.642598497327,0.322039397383)); -#39262 = CARTESIAN_POINT('',(0.713998330363,0.322039397383)); -#39263 = CARTESIAN_POINT('',(0.785398163399,0.322039397383)); -#39264 = CARTESIAN_POINT('',(0.856797996435,0.322039397383)); -#39265 = CARTESIAN_POINT('',(0.928197829471,0.322039397383)); -#39266 = CARTESIAN_POINT('',(0.999597662507,0.322039397383)); -#39267 = CARTESIAN_POINT('',(1.070997495543,0.322039397383)); -#39268 = CARTESIAN_POINT('',(1.142397328579,0.322039397383)); -#39269 = CARTESIAN_POINT('',(1.213797161615,0.322039397383)); -#39270 = CARTESIAN_POINT('',(1.285196994651,0.322039397383)); -#39271 = CARTESIAN_POINT('',(1.356596827687,0.322039397383)); -#39272 = CARTESIAN_POINT('',(1.427996660723,0.322039397383)); -#39273 = CARTESIAN_POINT('',(1.499396493759,0.322039397383)); -#39274 = CARTESIAN_POINT('',(1.54699638245,0.322039397383)); -#39275 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); -#39276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39277 = PCURVE('',#38742,#39278); -#39278 = DEFINITIONAL_REPRESENTATION('',(#39279),#39283); -#39279 = CIRCLE('',#39280,0.2); -#39280 = AXIS2_PLACEMENT_2D('',#39281,#39282); -#39281 = CARTESIAN_POINT('',(0.111844708748,-0.4)); -#39282 = DIRECTION('',(0.E+000,-1.)); -#39283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39284 = ORIENTED_EDGE('',*,*,#39285,.F.); -#39285 = EDGE_CURVE('',#39118,#39238,#39286,.T.); -#39286 = SURFACE_CURVE('',#39287,(#39291,#39320),.PCURVE_S1.); -#39287 = LINE('',#39288,#39289); -#39288 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); -#39289 = VECTOR('',#39290,1.); -#39290 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#39291 = PCURVE('',#39134,#39292); -#39292 = DEFINITIONAL_REPRESENTATION('',(#39293),#39319); -#39293 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39294,#39295,#39296,#39297, - #39298,#39299,#39300,#39301,#39302,#39303,#39304,#39305,#39306, - #39307,#39308,#39309,#39310,#39311,#39312,#39313,#39314,#39315, - #39316,#39317,#39318),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41643 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); +#41644 = CARTESIAN_POINT('',(2.379994434704E-002,0.322039397383)); +#41645 = CARTESIAN_POINT('',(7.139983303933E-002,0.322039397383)); +#41646 = CARTESIAN_POINT('',(0.142799666075,0.322039397383)); +#41647 = CARTESIAN_POINT('',(0.214199499111,0.322039397383)); +#41648 = CARTESIAN_POINT('',(0.285599332147,0.322039397383)); +#41649 = CARTESIAN_POINT('',(0.356999165183,0.322039397383)); +#41650 = CARTESIAN_POINT('',(0.428398998219,0.322039397383)); +#41651 = CARTESIAN_POINT('',(0.499798831255,0.322039397383)); +#41652 = CARTESIAN_POINT('',(0.571198664291,0.322039397383)); +#41653 = CARTESIAN_POINT('',(0.642598497327,0.322039397383)); +#41654 = CARTESIAN_POINT('',(0.713998330363,0.322039397383)); +#41655 = CARTESIAN_POINT('',(0.785398163399,0.322039397383)); +#41656 = CARTESIAN_POINT('',(0.856797996435,0.322039397383)); +#41657 = CARTESIAN_POINT('',(0.928197829471,0.322039397383)); +#41658 = CARTESIAN_POINT('',(0.999597662507,0.322039397383)); +#41659 = CARTESIAN_POINT('',(1.070997495543,0.322039397383)); +#41660 = CARTESIAN_POINT('',(1.142397328579,0.322039397383)); +#41661 = CARTESIAN_POINT('',(1.213797161615,0.322039397383)); +#41662 = CARTESIAN_POINT('',(1.285196994651,0.322039397383)); +#41663 = CARTESIAN_POINT('',(1.356596827687,0.322039397383)); +#41664 = CARTESIAN_POINT('',(1.427996660723,0.322039397383)); +#41665 = CARTESIAN_POINT('',(1.499396493759,0.322039397383)); +#41666 = CARTESIAN_POINT('',(1.54699638245,0.322039397383)); +#41667 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); +#41668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41669 = PCURVE('',#41134,#41670); +#41670 = DEFINITIONAL_REPRESENTATION('',(#41671),#41675); +#41671 = CIRCLE('',#41672,0.2); +#41672 = AXIS2_PLACEMENT_2D('',#41673,#41674); +#41673 = CARTESIAN_POINT('',(0.111844708748,-0.4)); +#41674 = DIRECTION('',(0.E+000,-1.)); +#41675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41676 = ORIENTED_EDGE('',*,*,#41677,.F.); +#41677 = EDGE_CURVE('',#41510,#41630,#41678,.T.); +#41678 = SURFACE_CURVE('',#41679,(#41683,#41712),.PCURVE_S1.); +#41679 = LINE('',#41680,#41681); +#41680 = CARTESIAN_POINT('',(3.644524343464,0.625,2.652298072692)); +#41681 = VECTOR('',#41682,1.); +#41682 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41683 = PCURVE('',#41526,#41684); +#41684 = DEFINITIONAL_REPRESENTATION('',(#41685),#41711); +#41685 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41686,#41687,#41688,#41689, + #41690,#41691,#41692,#41693,#41694,#41695,#41696,#41697,#41698, + #41699,#41700,#41701,#41702,#41703,#41704,#41705,#41706,#41707, + #41708,#41709,#41710),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363635E-002, 2.72727272727E-002,4.090909090905E-002,5.45454545454E-002, 6.818181818175E-002,8.18181818181E-002,9.545454545445E-002, @@ -49296,244 +52285,244 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#39294 = CARTESIAN_POINT('',(0.E+000,2.20393973834E-002)); -#39295 = CARTESIAN_POINT('',(6.784696261598E-013,2.658485192885E-002)); -#39296 = CARTESIAN_POINT('',(1.310600474195E-012,3.567576101975E-002)); -#39297 = CARTESIAN_POINT('',(1.056532048829E-012,4.93121246561E-002)); -#39298 = CARTESIAN_POINT('',(1.12460947824E-012,6.294848829245E-002)); -#39299 = CARTESIAN_POINT('',(1.106368185962E-012,7.65848519288E-002)); -#39300 = CARTESIAN_POINT('',(1.111255925663E-012,9.022121556515E-002)); -#39301 = CARTESIAN_POINT('',(1.109946259136E-012,0.103857579201)); -#39302 = CARTESIAN_POINT('',(1.110297185544E-012,0.117493942838)); -#39303 = CARTESIAN_POINT('',(1.110203146441E-012,0.131130306474)); -#39304 = CARTESIAN_POINT('',(1.110228376444E-012,0.144766670111)); -#39305 = CARTESIAN_POINT('',(1.110221495534E-012,0.158403033747)); -#39306 = CARTESIAN_POINT('',(1.110223789171E-012,0.172039397383)); -#39307 = CARTESIAN_POINT('',(1.110221495534E-012,0.18567576102)); -#39308 = CARTESIAN_POINT('',(1.110228376444E-012,0.199312124656)); -#39309 = CARTESIAN_POINT('',(1.110203146441E-012,0.212948488292)); -#39310 = CARTESIAN_POINT('',(1.110297185544E-012,0.226584851929)); -#39311 = CARTESIAN_POINT('',(1.109946259136E-012,0.240221215565)); -#39312 = CARTESIAN_POINT('',(1.111255925663E-012,0.253857579201)); -#39313 = CARTESIAN_POINT('',(1.106368185962E-012,0.267493942838)); -#39314 = CARTESIAN_POINT('',(1.12460947824E-012,0.281130306474)); -#39315 = CARTESIAN_POINT('',(1.056532048829E-012,0.29476667011)); -#39316 = CARTESIAN_POINT('',(1.310600474195E-012,0.308403033747)); -#39317 = CARTESIAN_POINT('',(6.784696261598E-013,0.317493942838)); -#39318 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); -#39319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39320 = PCURVE('',#38529,#39321); -#39321 = DEFINITIONAL_REPRESENTATION('',(#39322),#39326); -#39322 = LINE('',#39323,#39324); -#39323 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); -#39324 = VECTOR('',#39325,1.); -#39325 = DIRECTION('',(0.63850963654,-0.769613827868)); -#39326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39327 = ORIENTED_EDGE('',*,*,#39115,.F.); -#39328 = ORIENTED_EDGE('',*,*,#39329,.T.); -#39329 = EDGE_CURVE('',#39116,#39240,#39330,.T.); -#39330 = SURFACE_CURVE('',#39331,(#39335,#39341),.PCURVE_S1.); -#39331 = LINE('',#39332,#39333); -#39332 = CARTESIAN_POINT('',(3.798447109038,0.425,2.78)); -#39333 = VECTOR('',#39334,1.); -#39334 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); -#39335 = PCURVE('',#39134,#39336); -#39336 = DEFINITIONAL_REPRESENTATION('',(#39337),#39340); -#39337 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39338,#39339),.UNSPECIFIED., +#41686 = CARTESIAN_POINT('',(0.E+000,2.20393973834E-002)); +#41687 = CARTESIAN_POINT('',(6.784696261598E-013,2.658485192885E-002)); +#41688 = CARTESIAN_POINT('',(1.310600474195E-012,3.567576101975E-002)); +#41689 = CARTESIAN_POINT('',(1.056532048829E-012,4.93121246561E-002)); +#41690 = CARTESIAN_POINT('',(1.12460947824E-012,6.294848829245E-002)); +#41691 = CARTESIAN_POINT('',(1.106368185962E-012,7.65848519288E-002)); +#41692 = CARTESIAN_POINT('',(1.111255925663E-012,9.022121556515E-002)); +#41693 = CARTESIAN_POINT('',(1.109946259136E-012,0.103857579201)); +#41694 = CARTESIAN_POINT('',(1.110297185544E-012,0.117493942838)); +#41695 = CARTESIAN_POINT('',(1.110203146441E-012,0.131130306474)); +#41696 = CARTESIAN_POINT('',(1.110228376444E-012,0.144766670111)); +#41697 = CARTESIAN_POINT('',(1.110221495534E-012,0.158403033747)); +#41698 = CARTESIAN_POINT('',(1.110223789171E-012,0.172039397383)); +#41699 = CARTESIAN_POINT('',(1.110221495534E-012,0.18567576102)); +#41700 = CARTESIAN_POINT('',(1.110228376444E-012,0.199312124656)); +#41701 = CARTESIAN_POINT('',(1.110203146441E-012,0.212948488292)); +#41702 = CARTESIAN_POINT('',(1.110297185544E-012,0.226584851929)); +#41703 = CARTESIAN_POINT('',(1.109946259136E-012,0.240221215565)); +#41704 = CARTESIAN_POINT('',(1.111255925663E-012,0.253857579201)); +#41705 = CARTESIAN_POINT('',(1.106368185962E-012,0.267493942838)); +#41706 = CARTESIAN_POINT('',(1.12460947824E-012,0.281130306474)); +#41707 = CARTESIAN_POINT('',(1.056532048829E-012,0.29476667011)); +#41708 = CARTESIAN_POINT('',(1.310600474195E-012,0.308403033747)); +#41709 = CARTESIAN_POINT('',(6.784696261598E-013,0.317493942838)); +#41710 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); +#41711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41712 = PCURVE('',#40921,#41713); +#41713 = DEFINITIONAL_REPRESENTATION('',(#41714),#41718); +#41714 = LINE('',#41715,#41716); +#41715 = CARTESIAN_POINT('',(3.644524343464,2.652298072692)); +#41716 = VECTOR('',#41717,1.); +#41717 = DIRECTION('',(0.63850963654,-0.769613827868)); +#41718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41719 = ORIENTED_EDGE('',*,*,#41507,.F.); +#41720 = ORIENTED_EDGE('',*,*,#41721,.T.); +#41721 = EDGE_CURVE('',#41508,#41632,#41722,.T.); +#41722 = SURFACE_CURVE('',#41723,(#41727,#41733),.PCURVE_S1.); +#41723 = LINE('',#41724,#41725); +#41724 = CARTESIAN_POINT('',(3.798447109038,0.425,2.78)); +#41725 = VECTOR('',#41726,1.); +#41726 = DIRECTION('',(0.63850963654,0.E+000,-0.769613827868)); +#41727 = PCURVE('',#41526,#41728); +#41728 = DEFINITIONAL_REPRESENTATION('',(#41729),#41732); +#41729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41730,#41731),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39338 = CARTESIAN_POINT('',(1.570796326795,2.203939738361E-002)); -#39339 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); -#39340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39341 = PCURVE('',#39100,#39342); -#39342 = DEFINITIONAL_REPRESENTATION('',(#39343),#39347); -#39343 = LINE('',#39344,#39345); -#39344 = CARTESIAN_POINT('',(0.3,-0.4)); -#39345 = VECTOR('',#39346,1.); -#39346 = DIRECTION('',(-1.,0.E+000)); -#39347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39348 = ADVANCED_FACE('',(#39349),#38742,.T.); -#39349 = FACE_BOUND('',#39350,.F.); -#39350 = EDGE_LOOP('',(#39351,#39352,#39373,#39394,#39395,#39396)); -#39351 = ORIENTED_EDGE('',*,*,#39237,.F.); -#39352 = ORIENTED_EDGE('',*,*,#39353,.F.); -#39353 = EDGE_CURVE('',#38509,#39238,#39354,.T.); -#39354 = SURFACE_CURVE('',#39355,(#39359,#39366),.PCURVE_S1.); -#39355 = LINE('',#39356,#39357); -#39356 = CARTESIAN_POINT('',(3.75,0.625,2.35)); -#39357 = VECTOR('',#39358,1.); -#39358 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); -#39359 = PCURVE('',#38742,#39360); -#39360 = DEFINITIONAL_REPRESENTATION('',(#39361),#39365); -#39361 = LINE('',#39362,#39363); -#39362 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#39363 = VECTOR('',#39364,1.); -#39364 = DIRECTION('',(1.,0.E+000)); -#39365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39366 = PCURVE('',#38529,#39367); -#39367 = DEFINITIONAL_REPRESENTATION('',(#39368),#39372); -#39368 = LINE('',#39369,#39370); -#39369 = CARTESIAN_POINT('',(3.75,2.35)); -#39370 = VECTOR('',#39371,1.); -#39371 = DIRECTION('',(0.769613827868,0.63850963654)); -#39372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39373 = ORIENTED_EDGE('',*,*,#39374,.T.); -#39374 = EDGE_CURVE('',#38509,#37987,#39375,.T.); -#39375 = SURFACE_CURVE('',#39376,(#39380,#39387),.PCURVE_S1.); -#39376 = LINE('',#39377,#39378); -#39377 = CARTESIAN_POINT('',(3.75,0.625,2.35)); -#39378 = VECTOR('',#39379,1.); -#39379 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39380 = PCURVE('',#38742,#39381); -#39381 = DEFINITIONAL_REPRESENTATION('',(#39382),#39386); -#39382 = LINE('',#39383,#39384); -#39383 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#39384 = VECTOR('',#39385,1.); -#39385 = DIRECTION('',(0.E+000,1.)); -#39386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39387 = PCURVE('',#38035,#39388); -#39388 = DEFINITIONAL_REPRESENTATION('',(#39389),#39393); -#39389 = LINE('',#39390,#39391); -#39390 = CARTESIAN_POINT('',(0.696446609407,4.7)); -#39391 = VECTOR('',#39392,1.); -#39392 = DIRECTION('',(-1.,0.E+000)); -#39393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39394 = ORIENTED_EDGE('',*,*,#38728,.T.); -#39395 = ORIENTED_EDGE('',*,*,#39041,.F.); -#39396 = ORIENTED_EDGE('',*,*,#39397,.T.); -#39397 = EDGE_CURVE('',#39042,#39240,#39398,.T.); -#39398 = SURFACE_CURVE('',#39399,(#39403,#39410),.PCURVE_S1.); -#39399 = LINE('',#39400,#39401); -#39400 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); -#39401 = VECTOR('',#39402,1.); -#39402 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39403 = PCURVE('',#38742,#39404); -#39404 = DEFINITIONAL_REPRESENTATION('',(#39405),#39409); -#39405 = LINE('',#39406,#39407); -#39406 = CARTESIAN_POINT('',(0.311844708748,-0.2)); -#39407 = VECTOR('',#39408,1.); -#39408 = DIRECTION('',(0.E+000,-1.)); -#39409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39410 = PCURVE('',#39100,#39411); -#39411 = DEFINITIONAL_REPRESENTATION('',(#39412),#39416); -#39412 = LINE('',#39413,#39414); -#39413 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#39414 = VECTOR('',#39415,1.); -#39415 = DIRECTION('',(0.E+000,-1.)); -#39416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39417 = ADVANCED_FACE('',(#39418),#38529,.F.); -#39418 = FACE_BOUND('',#39419,.F.); -#39419 = EDGE_LOOP('',(#39420,#39421,#39422,#39445,#39466,#39467)); -#39420 = ORIENTED_EDGE('',*,*,#39285,.F.); -#39421 = ORIENTED_EDGE('',*,*,#39213,.T.); -#39422 = ORIENTED_EDGE('',*,*,#39423,.T.); -#39423 = EDGE_CURVE('',#39192,#39424,#39426,.T.); -#39424 = VERTEX_POINT('',#39425); -#39425 = CARTESIAN_POINT('',(3.45,0.625,2.354697035713)); -#39426 = SURFACE_CURVE('',#39427,(#39432,#39439),.PCURVE_S1.); -#39427 = CIRCLE('',#39428,0.29); -#39428 = AXIS2_PLACEMENT_3D('',#39429,#39430,#39431); -#39429 = CARTESIAN_POINT('',(3.74,0.625,2.354697035713)); -#39430 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39431 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); -#39432 = PCURVE('',#38529,#39433); -#39433 = DEFINITIONAL_REPRESENTATION('',(#39434),#39438); -#39434 = CIRCLE('',#39435,0.29); -#39435 = AXIS2_PLACEMENT_2D('',#39436,#39437); -#39436 = CARTESIAN_POINT('',(3.74,2.354697035713)); -#39437 = DIRECTION('',(-0.63850963654,0.769613827868)); -#39438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39439 = PCURVE('',#38795,#39440); -#39440 = DEFINITIONAL_REPRESENTATION('',(#39441),#39444); -#39441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39442,#39443),.UNSPECIFIED., +#41730 = CARTESIAN_POINT('',(1.570796326795,2.203939738361E-002)); +#41731 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); +#41732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41733 = PCURVE('',#41492,#41734); +#41734 = DEFINITIONAL_REPRESENTATION('',(#41735),#41739); +#41735 = LINE('',#41736,#41737); +#41736 = CARTESIAN_POINT('',(0.3,-0.4)); +#41737 = VECTOR('',#41738,1.); +#41738 = DIRECTION('',(-1.,0.E+000)); +#41739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41740 = ADVANCED_FACE('',(#41741),#41134,.T.); +#41741 = FACE_BOUND('',#41742,.F.); +#41742 = EDGE_LOOP('',(#41743,#41744,#41765,#41786,#41787,#41788)); +#41743 = ORIENTED_EDGE('',*,*,#41629,.F.); +#41744 = ORIENTED_EDGE('',*,*,#41745,.F.); +#41745 = EDGE_CURVE('',#40901,#41630,#41746,.T.); +#41746 = SURFACE_CURVE('',#41747,(#41751,#41758),.PCURVE_S1.); +#41747 = LINE('',#41748,#41749); +#41748 = CARTESIAN_POINT('',(3.75,0.625,2.35)); +#41749 = VECTOR('',#41750,1.); +#41750 = DIRECTION('',(0.769613827868,0.E+000,0.63850963654)); +#41751 = PCURVE('',#41134,#41752); +#41752 = DEFINITIONAL_REPRESENTATION('',(#41753),#41757); +#41753 = LINE('',#41754,#41755); +#41754 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#41755 = VECTOR('',#41756,1.); +#41756 = DIRECTION('',(1.,0.E+000)); +#41757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41758 = PCURVE('',#40921,#41759); +#41759 = DEFINITIONAL_REPRESENTATION('',(#41760),#41764); +#41760 = LINE('',#41761,#41762); +#41761 = CARTESIAN_POINT('',(3.75,2.35)); +#41762 = VECTOR('',#41763,1.); +#41763 = DIRECTION('',(0.769613827868,0.63850963654)); +#41764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41765 = ORIENTED_EDGE('',*,*,#41766,.T.); +#41766 = EDGE_CURVE('',#40901,#40379,#41767,.T.); +#41767 = SURFACE_CURVE('',#41768,(#41772,#41779),.PCURVE_S1.); +#41768 = LINE('',#41769,#41770); +#41769 = CARTESIAN_POINT('',(3.75,0.625,2.35)); +#41770 = VECTOR('',#41771,1.); +#41771 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41772 = PCURVE('',#41134,#41773); +#41773 = DEFINITIONAL_REPRESENTATION('',(#41774),#41778); +#41774 = LINE('',#41775,#41776); +#41775 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#41776 = VECTOR('',#41777,1.); +#41777 = DIRECTION('',(0.E+000,1.)); +#41778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41779 = PCURVE('',#40427,#41780); +#41780 = DEFINITIONAL_REPRESENTATION('',(#41781),#41785); +#41781 = LINE('',#41782,#41783); +#41782 = CARTESIAN_POINT('',(0.696446609407,4.7)); +#41783 = VECTOR('',#41784,1.); +#41784 = DIRECTION('',(-1.,0.E+000)); +#41785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41786 = ORIENTED_EDGE('',*,*,#41120,.T.); +#41787 = ORIENTED_EDGE('',*,*,#41433,.F.); +#41788 = ORIENTED_EDGE('',*,*,#41789,.T.); +#41789 = EDGE_CURVE('',#41434,#41632,#41790,.T.); +#41790 = SURFACE_CURVE('',#41791,(#41795,#41802),.PCURVE_S1.); +#41791 = LINE('',#41792,#41793); +#41792 = CARTESIAN_POINT('',(3.99,0.225,2.54911585164)); +#41793 = VECTOR('',#41794,1.); +#41794 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41795 = PCURVE('',#41134,#41796); +#41796 = DEFINITIONAL_REPRESENTATION('',(#41797),#41801); +#41797 = LINE('',#41798,#41799); +#41798 = CARTESIAN_POINT('',(0.311844708748,-0.2)); +#41799 = VECTOR('',#41800,1.); +#41800 = DIRECTION('',(0.E+000,-1.)); +#41801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41802 = PCURVE('',#41492,#41803); +#41803 = DEFINITIONAL_REPRESENTATION('',(#41804),#41808); +#41804 = LINE('',#41805,#41806); +#41805 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#41806 = VECTOR('',#41807,1.); +#41807 = DIRECTION('',(0.E+000,-1.)); +#41808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41809 = ADVANCED_FACE('',(#41810),#40921,.F.); +#41810 = FACE_BOUND('',#41811,.F.); +#41811 = EDGE_LOOP('',(#41812,#41813,#41814,#41837,#41858,#41859)); +#41812 = ORIENTED_EDGE('',*,*,#41677,.F.); +#41813 = ORIENTED_EDGE('',*,*,#41605,.T.); +#41814 = ORIENTED_EDGE('',*,*,#41815,.T.); +#41815 = EDGE_CURVE('',#41584,#41816,#41818,.T.); +#41816 = VERTEX_POINT('',#41817); +#41817 = CARTESIAN_POINT('',(3.45,0.625,2.354697035713)); +#41818 = SURFACE_CURVE('',#41819,(#41824,#41831),.PCURVE_S1.); +#41819 = CIRCLE('',#41820,0.29); +#41820 = AXIS2_PLACEMENT_3D('',#41821,#41822,#41823); +#41821 = CARTESIAN_POINT('',(3.74,0.625,2.354697035713)); +#41822 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41823 = DIRECTION('',(-0.63850963654,0.E+000,0.769613827868)); +#41824 = PCURVE('',#40921,#41825); +#41825 = DEFINITIONAL_REPRESENTATION('',(#41826),#41830); +#41826 = CIRCLE('',#41827,0.29); +#41827 = AXIS2_PLACEMENT_2D('',#41828,#41829); +#41828 = CARTESIAN_POINT('',(3.74,2.354697035713)); +#41829 = DIRECTION('',(-0.63850963654,0.769613827868)); +#41830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41831 = PCURVE('',#41187,#41832); +#41832 = DEFINITIONAL_REPRESENTATION('',(#41833),#41836); +#41833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41834,#41835),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.87823612867),.PIECEWISE_BEZIER_KNOTS.); -#39442 = CARTESIAN_POINT('',(2.26335652492,-0.6)); -#39443 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#39444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39445 = ORIENTED_EDGE('',*,*,#39446,.T.); -#39446 = EDGE_CURVE('',#39424,#38507,#39447,.T.); -#39447 = SURFACE_CURVE('',#39448,(#39452,#39459),.PCURVE_S1.); -#39448 = LINE('',#39449,#39450); -#39449 = CARTESIAN_POINT('',(3.45,0.625,2.354697035713)); -#39450 = VECTOR('',#39451,1.); -#39451 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#39452 = PCURVE('',#38529,#39453); -#39453 = DEFINITIONAL_REPRESENTATION('',(#39454),#39458); -#39454 = LINE('',#39455,#39456); -#39455 = CARTESIAN_POINT('',(3.45,2.354697035713)); -#39456 = VECTOR('',#39457,1.); -#39457 = DIRECTION('',(0.E+000,-1.)); -#39458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39459 = PCURVE('',#38321,#39460); -#39460 = DEFINITIONAL_REPRESENTATION('',(#39461),#39465); -#39461 = LINE('',#39462,#39463); -#39462 = CARTESIAN_POINT('',(5.E-002,4.704697035713)); -#39463 = VECTOR('',#39464,1.); -#39464 = DIRECTION('',(0.E+000,-1.)); -#39465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#41834 = CARTESIAN_POINT('',(2.26335652492,-0.6)); +#41835 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#41836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41837 = ORIENTED_EDGE('',*,*,#41838,.T.); +#41838 = EDGE_CURVE('',#41816,#40899,#41839,.T.); +#41839 = SURFACE_CURVE('',#41840,(#41844,#41851),.PCURVE_S1.); +#41840 = LINE('',#41841,#41842); +#41841 = CARTESIAN_POINT('',(3.45,0.625,2.354697035713)); +#41842 = VECTOR('',#41843,1.); +#41843 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#41844 = PCURVE('',#40921,#41845); +#41845 = DEFINITIONAL_REPRESENTATION('',(#41846),#41850); +#41846 = LINE('',#41847,#41848); +#41847 = CARTESIAN_POINT('',(3.45,2.354697035713)); +#41848 = VECTOR('',#41849,1.); +#41849 = DIRECTION('',(0.E+000,-1.)); +#41850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41851 = PCURVE('',#40713,#41852); +#41852 = DEFINITIONAL_REPRESENTATION('',(#41853),#41857); +#41853 = LINE('',#41854,#41855); +#41854 = CARTESIAN_POINT('',(5.E-002,4.704697035713)); +#41855 = VECTOR('',#41856,1.); +#41856 = DIRECTION('',(0.E+000,-1.)); +#41857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41858 = ORIENTED_EDGE('',*,*,#40898,.T.); +#41859 = ORIENTED_EDGE('',*,*,#41745,.T.); +#41860 = ADVANCED_FACE('',(#41861),#40751,.F.); +#41861 = FACE_BOUND('',#41862,.F.); +#41862 = EDGE_LOOP('',(#41863,#41915,#41936,#41937,#41960,#41983)); +#41863 = ORIENTED_EDGE('',*,*,#41864,.F.); +#41864 = EDGE_CURVE('',#41865,#41867,#41869,.T.); +#41865 = VERTEX_POINT('',#41866); +#41866 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); +#41867 = VERTEX_POINT('',#41868); +#41868 = CARTESIAN_POINT('',(-3.644524343464,0.625,2.652298072692)); +#41869 = SURFACE_CURVE('',#41870,(#41874,#41881),.PCURVE_S1.); +#41870 = LINE('',#41871,#41872); +#41871 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); +#41872 = VECTOR('',#41873,1.); +#41873 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#41874 = PCURVE('',#40751,#41875); +#41875 = DEFINITIONAL_REPRESENTATION('',(#41876),#41880); +#41876 = LINE('',#41877,#41878); +#41877 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); +#41878 = VECTOR('',#41879,1.); +#41879 = DIRECTION('',(0.63850963654,0.769613827868)); +#41880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#39466 = ORIENTED_EDGE('',*,*,#38506,.T.); -#39467 = ORIENTED_EDGE('',*,*,#39353,.T.); -#39468 = ADVANCED_FACE('',(#39469),#38359,.F.); -#39469 = FACE_BOUND('',#39470,.F.); -#39470 = EDGE_LOOP('',(#39471,#39523,#39544,#39545,#39568,#39591)); -#39471 = ORIENTED_EDGE('',*,*,#39472,.F.); -#39472 = EDGE_CURVE('',#39473,#39475,#39477,.T.); -#39473 = VERTEX_POINT('',#39474); -#39474 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); -#39475 = VERTEX_POINT('',#39476); -#39476 = CARTESIAN_POINT('',(-3.644524343464,0.625,2.652298072692)); -#39477 = SURFACE_CURVE('',#39478,(#39482,#39489),.PCURVE_S1.); -#39478 = LINE('',#39479,#39480); -#39479 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); -#39480 = VECTOR('',#39481,1.); -#39481 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#39482 = PCURVE('',#38359,#39483); -#39483 = DEFINITIONAL_REPRESENTATION('',(#39484),#39488); -#39484 = LINE('',#39485,#39486); -#39485 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); -#39486 = VECTOR('',#39487,1.); -#39487 = DIRECTION('',(0.63850963654,0.769613827868)); -#39488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39489 = PCURVE('',#39490,#39495); -#39490 = CYLINDRICAL_SURFACE('',#39491,0.2); -#39491 = AXIS2_PLACEMENT_3D('',#39492,#39493,#39494); -#39492 = CARTESIAN_POINT('',(-3.850149602039,0.425,2.404452099347)); -#39493 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#39494 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39495 = DEFINITIONAL_REPRESENTATION('',(#39496),#39522); -#39496 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#39497,#39498,#39499,#39500, - #39501,#39502,#39503,#39504,#39505,#39506,#39507,#39508,#39509, - #39510,#39511,#39512,#39513,#39514,#39515,#39516,#39517,#39518, - #39519,#39520,#39521),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#41881 = PCURVE('',#41882,#41887); +#41882 = CYLINDRICAL_SURFACE('',#41883,0.2); +#41883 = AXIS2_PLACEMENT_3D('',#41884,#41885,#41886); +#41884 = CARTESIAN_POINT('',(-3.850149602039,0.425,2.404452099347)); +#41885 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#41886 = DIRECTION('',(0.E+000,1.,0.E+000)); +#41887 = DEFINITIONAL_REPRESENTATION('',(#41888),#41914); +#41888 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#41889,#41890,#41891,#41892, + #41893,#41894,#41895,#41896,#41897,#41898,#41899,#41900,#41901, + #41902,#41903,#41904,#41905,#41906,#41907,#41908,#41909,#41910, + #41911,#41912,#41913),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363635E-002, 2.72727272727E-002,4.090909090905E-002,5.45454545454E-002, 6.818181818175E-002,8.18181818181E-002,9.545454545445E-002, @@ -49541,649 +52530,649 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#39497 = CARTESIAN_POINT('',(0.E+000,2.203939738417E-002)); -#39498 = CARTESIAN_POINT('',(1.270095140171E-012,2.658485192962E-002)); -#39499 = CARTESIAN_POINT('',(2.453444087693E-012,3.567576102052E-002)); -#39500 = CARTESIAN_POINT('',(1.977827995408E-012,4.931212465687E-002)); -#39501 = CARTESIAN_POINT('',(2.105268943265E-012,6.294848829322E-002)); -#39502 = CARTESIAN_POINT('',(2.071121244121E-012,7.658485192957E-002)); -#39503 = CARTESIAN_POINT('',(2.080271092842E-012,9.022121556592E-002)); -#39504 = CARTESIAN_POINT('',(2.077819397103E-012,0.103857579202)); -#39505 = CARTESIAN_POINT('',(2.078476331337E-012,0.117493942839)); -#39506 = CARTESIAN_POINT('',(2.078300290137E-012,0.131130306475)); -#39507 = CARTESIAN_POINT('',(2.078347520703E-012,0.144766670111)); -#39508 = CARTESIAN_POINT('',(2.07833463964E-012,0.158403033748)); -#39509 = CARTESIAN_POINT('',(2.078338933328E-012,0.172039397384)); -#39510 = CARTESIAN_POINT('',(2.07833463964E-012,0.18567576102)); -#39511 = CARTESIAN_POINT('',(2.078347520703E-012,0.199312124657)); -#39512 = CARTESIAN_POINT('',(2.078300290137E-012,0.212948488293)); -#39513 = CARTESIAN_POINT('',(2.078476331337E-012,0.226584851929)); -#39514 = CARTESIAN_POINT('',(2.077819397103E-012,0.240221215566)); -#39515 = CARTESIAN_POINT('',(2.080271092842E-012,0.253857579202)); -#39516 = CARTESIAN_POINT('',(2.071121244121E-012,0.267493942838)); -#39517 = CARTESIAN_POINT('',(2.105268943265E-012,0.281130306475)); -#39518 = CARTESIAN_POINT('',(1.977827995408E-012,0.294766670111)); -#39519 = CARTESIAN_POINT('',(2.453444087693E-012,0.308403033748)); -#39520 = CARTESIAN_POINT('',(1.270095140171E-012,0.317493942838)); -#39521 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#39522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39523 = ORIENTED_EDGE('',*,*,#39524,.T.); -#39524 = EDGE_CURVE('',#39473,#38337,#39525,.T.); -#39525 = SURFACE_CURVE('',#39526,(#39530,#39537),.PCURVE_S1.); -#39526 = LINE('',#39527,#39528); -#39527 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); -#39528 = VECTOR('',#39529,1.); -#39529 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); -#39530 = PCURVE('',#38359,#39531); -#39531 = DEFINITIONAL_REPRESENTATION('',(#39532),#39536); -#39532 = LINE('',#39533,#39534); -#39533 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); -#39534 = VECTOR('',#39535,1.); -#39535 = DIRECTION('',(0.769613827868,-0.63850963654)); -#39536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39537 = PCURVE('',#38979,#39538); -#39538 = DEFINITIONAL_REPRESENTATION('',(#39539),#39543); -#39539 = LINE('',#39540,#39541); -#39540 = CARTESIAN_POINT('',(0.2,-0.6)); -#39541 = VECTOR('',#39542,1.); -#39542 = DIRECTION('',(1.,0.E+000)); -#39543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39544 = ORIENTED_EDGE('',*,*,#38336,.T.); -#39545 = ORIENTED_EDGE('',*,*,#39546,.T.); -#39546 = EDGE_CURVE('',#38339,#39547,#39549,.T.); -#39547 = VERTEX_POINT('',#39548); -#39548 = CARTESIAN_POINT('',(-3.45,0.625,2.354697035713)); -#39549 = SURFACE_CURVE('',#39550,(#39554,#39561),.PCURVE_S1.); -#39550 = LINE('',#39551,#39552); -#39551 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); -#39552 = VECTOR('',#39553,1.); -#39553 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39554 = PCURVE('',#38359,#39555); -#39555 = DEFINITIONAL_REPRESENTATION('',(#39556),#39560); -#39556 = LINE('',#39557,#39558); -#39557 = CARTESIAN_POINT('',(-3.45,2.35)); -#39558 = VECTOR('',#39559,1.); -#39559 = DIRECTION('',(0.E+000,1.)); -#39560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39561 = PCURVE('',#37683,#39562); -#39562 = DEFINITIONAL_REPRESENTATION('',(#39563),#39567); -#39563 = LINE('',#39564,#39565); -#39564 = CARTESIAN_POINT('',(0.696446609407,4.7)); -#39565 = VECTOR('',#39566,1.); -#39566 = DIRECTION('',(0.E+000,1.)); -#39567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39568 = ORIENTED_EDGE('',*,*,#39569,.T.); -#39569 = EDGE_CURVE('',#39547,#39570,#39572,.T.); -#39570 = VERTEX_POINT('',#39571); -#39571 = CARTESIAN_POINT('',(-3.554832205403,0.625,2.577885045795)); -#39572 = SURFACE_CURVE('',#39573,(#39578,#39585),.PCURVE_S1.); -#39573 = CIRCLE('',#39574,0.29); -#39574 = AXIS2_PLACEMENT_3D('',#39575,#39576,#39577); -#39575 = CARTESIAN_POINT('',(-3.74,0.625,2.354697035713)); -#39576 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39577 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39578 = PCURVE('',#38359,#39579); -#39579 = DEFINITIONAL_REPRESENTATION('',(#39580),#39584); -#39580 = CIRCLE('',#39581,0.29); -#39581 = AXIS2_PLACEMENT_2D('',#39582,#39583); -#39582 = CARTESIAN_POINT('',(-3.74,2.354697035713)); -#39583 = DIRECTION('',(1.,0.E+000)); -#39584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39585 = PCURVE('',#38932,#39586); -#39586 = DEFINITIONAL_REPRESENTATION('',(#39587),#39590); -#39587 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39588,#39589),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.878236128669),.PIECEWISE_BEZIER_KNOTS.); -#39588 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#39589 = CARTESIAN_POINT('',(0.878236128669,-0.6)); -#39590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39591 = ORIENTED_EDGE('',*,*,#39592,.T.); -#39592 = EDGE_CURVE('',#39570,#39475,#39593,.T.); -#39593 = SURFACE_CURVE('',#39594,(#39598,#39605),.PCURVE_S1.); -#39594 = LINE('',#39595,#39596); -#39595 = CARTESIAN_POINT('',(-3.554832205403,0.625,2.577885045795)); -#39596 = VECTOR('',#39597,1.); -#39597 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#39598 = PCURVE('',#38359,#39599); -#39599 = DEFINITIONAL_REPRESENTATION('',(#39600),#39604); -#39600 = LINE('',#39601,#39602); -#39601 = CARTESIAN_POINT('',(-3.554832205403,2.577885045795)); -#39602 = VECTOR('',#39603,1.); -#39603 = DIRECTION('',(-0.769613827868,0.63850963654)); -#39604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39605 = PCURVE('',#38903,#39606); -#39606 = DEFINITIONAL_REPRESENTATION('',(#39607),#39611); -#39607 = LINE('',#39608,#39609); -#39608 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#39609 = VECTOR('',#39610,1.); -#39610 = DIRECTION('',(1.,0.E+000)); -#39611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39612 = ADVANCED_FACE('',(#39613),#38795,.T.); -#39613 = FACE_BOUND('',#39614,.T.); -#39614 = EDGE_LOOP('',(#39615,#39616,#39617,#39618)); -#39615 = ORIENTED_EDGE('',*,*,#38778,.F.); -#39616 = ORIENTED_EDGE('',*,*,#39191,.T.); -#39617 = ORIENTED_EDGE('',*,*,#39423,.T.); -#39618 = ORIENTED_EDGE('',*,*,#39619,.F.); -#39619 = EDGE_CURVE('',#38756,#39424,#39620,.T.); -#39620 = SURFACE_CURVE('',#39621,(#39625,#39631),.PCURVE_S1.); -#39621 = LINE('',#39622,#39623); -#39622 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); -#39623 = VECTOR('',#39624,1.); -#39624 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39625 = PCURVE('',#38795,#39626); -#39626 = DEFINITIONAL_REPRESENTATION('',(#39627),#39630); -#39627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39628,#39629),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.6),.PIECEWISE_BEZIER_KNOTS.); -#39628 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#39629 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#39630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#41889 = CARTESIAN_POINT('',(0.E+000,2.203939738417E-002)); +#41890 = CARTESIAN_POINT('',(1.270095140171E-012,2.658485192962E-002)); +#41891 = CARTESIAN_POINT('',(2.453444087693E-012,3.567576102052E-002)); +#41892 = CARTESIAN_POINT('',(1.977827995408E-012,4.931212465687E-002)); +#41893 = CARTESIAN_POINT('',(2.105268943265E-012,6.294848829322E-002)); +#41894 = CARTESIAN_POINT('',(2.071121244121E-012,7.658485192957E-002)); +#41895 = CARTESIAN_POINT('',(2.080271092842E-012,9.022121556592E-002)); +#41896 = CARTESIAN_POINT('',(2.077819397103E-012,0.103857579202)); +#41897 = CARTESIAN_POINT('',(2.078476331337E-012,0.117493942839)); +#41898 = CARTESIAN_POINT('',(2.078300290137E-012,0.131130306475)); +#41899 = CARTESIAN_POINT('',(2.078347520703E-012,0.144766670111)); +#41900 = CARTESIAN_POINT('',(2.07833463964E-012,0.158403033748)); +#41901 = CARTESIAN_POINT('',(2.078338933328E-012,0.172039397384)); +#41902 = CARTESIAN_POINT('',(2.07833463964E-012,0.18567576102)); +#41903 = CARTESIAN_POINT('',(2.078347520703E-012,0.199312124657)); +#41904 = CARTESIAN_POINT('',(2.078300290137E-012,0.212948488293)); +#41905 = CARTESIAN_POINT('',(2.078476331337E-012,0.226584851929)); +#41906 = CARTESIAN_POINT('',(2.077819397103E-012,0.240221215566)); +#41907 = CARTESIAN_POINT('',(2.080271092842E-012,0.253857579202)); +#41908 = CARTESIAN_POINT('',(2.071121244121E-012,0.267493942838)); +#41909 = CARTESIAN_POINT('',(2.105268943265E-012,0.281130306475)); +#41910 = CARTESIAN_POINT('',(1.977827995408E-012,0.294766670111)); +#41911 = CARTESIAN_POINT('',(2.453444087693E-012,0.308403033748)); +#41912 = CARTESIAN_POINT('',(1.270095140171E-012,0.317493942838)); +#41913 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#41914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41915 = ORIENTED_EDGE('',*,*,#41916,.T.); +#41916 = EDGE_CURVE('',#41865,#40729,#41917,.T.); +#41917 = SURFACE_CURVE('',#41918,(#41922,#41929),.PCURVE_S1.); +#41918 = LINE('',#41919,#41920); +#41919 = CARTESIAN_POINT('',(-3.836077234426,0.625,2.421413924332)); +#41920 = VECTOR('',#41921,1.); +#41921 = DIRECTION('',(0.769613827868,0.E+000,-0.63850963654)); +#41922 = PCURVE('',#40751,#41923); +#41923 = DEFINITIONAL_REPRESENTATION('',(#41924),#41928); +#41924 = LINE('',#41925,#41926); +#41925 = CARTESIAN_POINT('',(-3.836077234426,2.421413924332)); +#41926 = VECTOR('',#41927,1.); +#41927 = DIRECTION('',(0.769613827868,-0.63850963654)); +#41928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41929 = PCURVE('',#41371,#41930); +#41930 = DEFINITIONAL_REPRESENTATION('',(#41931),#41935); +#41931 = LINE('',#41932,#41933); +#41932 = CARTESIAN_POINT('',(0.2,-0.6)); +#41933 = VECTOR('',#41934,1.); +#41934 = DIRECTION('',(1.,0.E+000)); +#41935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#39631 = PCURVE('',#38321,#39632); -#39632 = DEFINITIONAL_REPRESENTATION('',(#39633),#39637); -#39633 = LINE('',#39634,#39635); -#39634 = CARTESIAN_POINT('',(0.65,4.704697035713)); -#39635 = VECTOR('',#39636,1.); -#39636 = DIRECTION('',(-1.,0.E+000)); -#39637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39638 = ADVANCED_FACE('',(#39639),#38321,.T.); -#39639 = FACE_BOUND('',#39640,.F.); -#39640 = EDGE_LOOP('',(#39641,#39671,#39703,#39730,#39758,#39778,#39779, - #39780,#39781,#39782,#39783,#39805)); -#39641 = ORIENTED_EDGE('',*,*,#39642,.F.); -#39642 = EDGE_CURVE('',#39643,#39645,#39647,.T.); -#39643 = VERTEX_POINT('',#39644); -#39644 = CARTESIAN_POINT('',(3.45,0.125,-0.26)); -#39645 = VERTEX_POINT('',#39646); -#39646 = CARTESIAN_POINT('',(3.45,0.125,0.66)); -#39647 = SURFACE_CURVE('',#39648,(#39652,#39659),.PCURVE_S1.); -#39648 = LINE('',#39649,#39650); -#39649 = CARTESIAN_POINT('',(3.45,0.125,-0.26)); -#39650 = VECTOR('',#39651,1.); -#39651 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39652 = PCURVE('',#38321,#39653); -#39653 = DEFINITIONAL_REPRESENTATION('',(#39654),#39658); -#39654 = LINE('',#39655,#39656); -#39655 = CARTESIAN_POINT('',(0.55,2.09)); -#39656 = VECTOR('',#39657,1.); -#39657 = DIRECTION('',(0.E+000,1.)); -#39658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39659 = PCURVE('',#39660,#39665); -#39660 = PLANE('',#39661); -#39661 = AXIS2_PLACEMENT_3D('',#39662,#39663,#39664); -#39662 = CARTESIAN_POINT('',(0.E+000,0.125,0.E+000)); -#39663 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39664 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39665 = DEFINITIONAL_REPRESENTATION('',(#39666),#39670); -#39666 = LINE('',#39667,#39668); -#39667 = CARTESIAN_POINT('',(3.45,-0.26)); -#39668 = VECTOR('',#39669,1.); -#39669 = DIRECTION('',(0.E+000,1.)); -#39670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39671 = ORIENTED_EDGE('',*,*,#39672,.F.); -#39672 = EDGE_CURVE('',#39673,#39643,#39675,.T.); -#39673 = VERTEX_POINT('',#39674); -#39674 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-0.541561175052) - ); -#39675 = SURFACE_CURVE('',#39676,(#39681,#39692),.PCURVE_S1.); -#39676 = CIRCLE('',#39677,0.3); -#39677 = AXIS2_PLACEMENT_3D('',#39678,#39679,#39680); -#39678 = CARTESIAN_POINT('',(3.45,-0.175,-0.26)); -#39679 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39680 = DIRECTION('',(0.E+000,0.345177968644,-0.938537250173)); -#39681 = PCURVE('',#38321,#39682); -#39682 = DEFINITIONAL_REPRESENTATION('',(#39683),#39691); -#39683 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#39684,#39685,#39686,#39687 - ,#39688,#39689,#39690),.UNSPECIFIED.,.T.,.F.) +#41936 = ORIENTED_EDGE('',*,*,#40728,.T.); +#41937 = ORIENTED_EDGE('',*,*,#41938,.T.); +#41938 = EDGE_CURVE('',#40731,#41939,#41941,.T.); +#41939 = VERTEX_POINT('',#41940); +#41940 = CARTESIAN_POINT('',(-3.45,0.625,2.354697035713)); +#41941 = SURFACE_CURVE('',#41942,(#41946,#41953),.PCURVE_S1.); +#41942 = LINE('',#41943,#41944); +#41943 = CARTESIAN_POINT('',(-3.45,0.625,2.35)); +#41944 = VECTOR('',#41945,1.); +#41945 = DIRECTION('',(0.E+000,0.E+000,1.)); +#41946 = PCURVE('',#40751,#41947); +#41947 = DEFINITIONAL_REPRESENTATION('',(#41948),#41952); +#41948 = LINE('',#41949,#41950); +#41949 = CARTESIAN_POINT('',(-3.45,2.35)); +#41950 = VECTOR('',#41951,1.); +#41951 = DIRECTION('',(0.E+000,1.)); +#41952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41953 = PCURVE('',#40075,#41954); +#41954 = DEFINITIONAL_REPRESENTATION('',(#41955),#41959); +#41955 = LINE('',#41956,#41957); +#41956 = CARTESIAN_POINT('',(0.696446609407,4.7)); +#41957 = VECTOR('',#41958,1.); +#41958 = DIRECTION('',(0.E+000,1.)); +#41959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41960 = ORIENTED_EDGE('',*,*,#41961,.T.); +#41961 = EDGE_CURVE('',#41939,#41962,#41964,.T.); +#41962 = VERTEX_POINT('',#41963); +#41963 = CARTESIAN_POINT('',(-3.554832205403,0.625,2.577885045795)); +#41964 = SURFACE_CURVE('',#41965,(#41970,#41977),.PCURVE_S1.); +#41965 = CIRCLE('',#41966,0.29); +#41966 = AXIS2_PLACEMENT_3D('',#41967,#41968,#41969); +#41967 = CARTESIAN_POINT('',(-3.74,0.625,2.354697035713)); +#41968 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#41969 = DIRECTION('',(1.,0.E+000,0.E+000)); +#41970 = PCURVE('',#40751,#41971); +#41971 = DEFINITIONAL_REPRESENTATION('',(#41972),#41976); +#41972 = CIRCLE('',#41973,0.29); +#41973 = AXIS2_PLACEMENT_2D('',#41974,#41975); +#41974 = CARTESIAN_POINT('',(-3.74,2.354697035713)); +#41975 = DIRECTION('',(1.,0.E+000)); +#41976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41977 = PCURVE('',#41324,#41978); +#41978 = DEFINITIONAL_REPRESENTATION('',(#41979),#41982); +#41979 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41980,#41981),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.878236128669),.PIECEWISE_BEZIER_KNOTS.); +#41980 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#41981 = CARTESIAN_POINT('',(0.878236128669,-0.6)); +#41982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41983 = ORIENTED_EDGE('',*,*,#41984,.T.); +#41984 = EDGE_CURVE('',#41962,#41867,#41985,.T.); +#41985 = SURFACE_CURVE('',#41986,(#41990,#41997),.PCURVE_S1.); +#41986 = LINE('',#41987,#41988); +#41987 = CARTESIAN_POINT('',(-3.554832205403,0.625,2.577885045795)); +#41988 = VECTOR('',#41989,1.); +#41989 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#41990 = PCURVE('',#40751,#41991); +#41991 = DEFINITIONAL_REPRESENTATION('',(#41992),#41996); +#41992 = LINE('',#41993,#41994); +#41993 = CARTESIAN_POINT('',(-3.554832205403,2.577885045795)); +#41994 = VECTOR('',#41995,1.); +#41995 = DIRECTION('',(-0.769613827868,0.63850963654)); +#41996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#41997 = PCURVE('',#41295,#41998); +#41998 = DEFINITIONAL_REPRESENTATION('',(#41999),#42003); +#41999 = LINE('',#42000,#42001); +#42000 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#42001 = VECTOR('',#42002,1.); +#42002 = DIRECTION('',(1.,0.E+000)); +#42003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42004 = ADVANCED_FACE('',(#42005),#41187,.T.); +#42005 = FACE_BOUND('',#42006,.T.); +#42006 = EDGE_LOOP('',(#42007,#42008,#42009,#42010)); +#42007 = ORIENTED_EDGE('',*,*,#41170,.F.); +#42008 = ORIENTED_EDGE('',*,*,#41583,.T.); +#42009 = ORIENTED_EDGE('',*,*,#41815,.T.); +#42010 = ORIENTED_EDGE('',*,*,#42011,.F.); +#42011 = EDGE_CURVE('',#41148,#41816,#42012,.T.); +#42012 = SURFACE_CURVE('',#42013,(#42017,#42023),.PCURVE_S1.); +#42013 = LINE('',#42014,#42015); +#42014 = CARTESIAN_POINT('',(3.45,2.5E-002,2.354697035713)); +#42015 = VECTOR('',#42016,1.); +#42016 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42017 = PCURVE('',#41187,#42018); +#42018 = DEFINITIONAL_REPRESENTATION('',(#42019),#42022); +#42019 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42020,#42021),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.6),.PIECEWISE_BEZIER_KNOTS.); +#42020 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#42021 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#42022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42023 = PCURVE('',#40713,#42024); +#42024 = DEFINITIONAL_REPRESENTATION('',(#42025),#42029); +#42025 = LINE('',#42026,#42027); +#42026 = CARTESIAN_POINT('',(0.65,4.704697035713)); +#42027 = VECTOR('',#42028,1.); +#42028 = DIRECTION('',(-1.,0.E+000)); +#42029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42030 = ADVANCED_FACE('',(#42031),#40713,.T.); +#42031 = FACE_BOUND('',#42032,.F.); +#42032 = EDGE_LOOP('',(#42033,#42063,#42095,#42122,#42150,#42170,#42171, + #42172,#42173,#42174,#42175,#42197)); +#42033 = ORIENTED_EDGE('',*,*,#42034,.F.); +#42034 = EDGE_CURVE('',#42035,#42037,#42039,.T.); +#42035 = VERTEX_POINT('',#42036); +#42036 = CARTESIAN_POINT('',(3.45,0.125,-0.26)); +#42037 = VERTEX_POINT('',#42038); +#42038 = CARTESIAN_POINT('',(3.45,0.125,0.66)); +#42039 = SURFACE_CURVE('',#42040,(#42044,#42051),.PCURVE_S1.); +#42040 = LINE('',#42041,#42042); +#42041 = CARTESIAN_POINT('',(3.45,0.125,-0.26)); +#42042 = VECTOR('',#42043,1.); +#42043 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42044 = PCURVE('',#40713,#42045); +#42045 = DEFINITIONAL_REPRESENTATION('',(#42046),#42050); +#42046 = LINE('',#42047,#42048); +#42047 = CARTESIAN_POINT('',(0.55,2.09)); +#42048 = VECTOR('',#42049,1.); +#42049 = DIRECTION('',(0.E+000,1.)); +#42050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42051 = PCURVE('',#42052,#42057); +#42052 = PLANE('',#42053); +#42053 = AXIS2_PLACEMENT_3D('',#42054,#42055,#42056); +#42054 = CARTESIAN_POINT('',(0.E+000,0.125,0.E+000)); +#42055 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42056 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42057 = DEFINITIONAL_REPRESENTATION('',(#42058),#42062); +#42058 = LINE('',#42059,#42060); +#42059 = CARTESIAN_POINT('',(3.45,-0.26)); +#42060 = VECTOR('',#42061,1.); +#42061 = DIRECTION('',(0.E+000,1.)); +#42062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42063 = ORIENTED_EDGE('',*,*,#42064,.F.); +#42064 = EDGE_CURVE('',#42065,#42035,#42067,.T.); +#42065 = VERTEX_POINT('',#42066); +#42066 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-0.541561175052) + ); +#42067 = SURFACE_CURVE('',#42068,(#42073,#42084),.PCURVE_S1.); +#42068 = CIRCLE('',#42069,0.3); +#42069 = AXIS2_PLACEMENT_3D('',#42070,#42071,#42072); +#42070 = CARTESIAN_POINT('',(3.45,-0.175,-0.26)); +#42071 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42072 = DIRECTION('',(0.E+000,0.345177968644,-0.938537250173)); +#42073 = PCURVE('',#40713,#42074); +#42074 = DEFINITIONAL_REPRESENTATION('',(#42075),#42083); +#42075 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42076,#42077,#42078,#42079 + ,#42080,#42081,#42082),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#39684 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); -#39685 = CARTESIAN_POINT('',(0.258768348778,1.987798558752)); -#39686 = CARTESIAN_POINT('',(0.657937564982,2.320460454428)); -#39687 = CARTESIAN_POINT('',(1.057106781187,2.653122350104)); -#39688 = CARTESIAN_POINT('',(1.145615825611,2.141100720624)); -#39689 = CARTESIAN_POINT('',(1.234124870036,1.629079091144)); -#39690 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); -#39691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39692 = PCURVE('',#39693,#39698); -#39693 = CYLINDRICAL_SURFACE('',#39694,0.3); -#39694 = AXIS2_PLACEMENT_3D('',#39695,#39696,#39697); -#39695 = CARTESIAN_POINT('',(3.76491772868,-0.175,-0.26)); -#39696 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#39697 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39698 = DEFINITIONAL_REPRESENTATION('',(#39699),#39702); -#39699 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39700,#39701),.UNSPECIFIED., +#42076 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); +#42077 = CARTESIAN_POINT('',(0.258768348778,1.987798558752)); +#42078 = CARTESIAN_POINT('',(0.657937564982,2.320460454428)); +#42079 = CARTESIAN_POINT('',(1.057106781187,2.653122350104)); +#42080 = CARTESIAN_POINT('',(1.145615825611,2.141100720624)); +#42081 = CARTESIAN_POINT('',(1.234124870036,1.629079091144)); +#42082 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); +#42083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42084 = PCURVE('',#42085,#42090); +#42085 = CYLINDRICAL_SURFACE('',#42086,0.3); +#42086 = AXIS2_PLACEMENT_3D('',#42087,#42088,#42089); +#42087 = CARTESIAN_POINT('',(3.76491772868,-0.175,-0.26)); +#42088 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42089 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42090 = DEFINITIONAL_REPRESENTATION('',(#42091),#42094); +#42091 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42092,#42093),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#39700 = CARTESIAN_POINT('',(1.218367924887,0.31491772868)); -#39701 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); -#39702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39703 = ORIENTED_EDGE('',*,*,#39704,.F.); -#39704 = EDGE_CURVE('',#39705,#39673,#39707,.T.); -#39705 = VERTEX_POINT('',#39706); -#39706 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-2.35)); -#39707 = SURFACE_CURVE('',#39708,(#39712,#39719),.PCURVE_S1.); -#39708 = LINE('',#39709,#39710); -#39709 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-2.35)); -#39710 = VECTOR('',#39711,1.); -#39711 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39712 = PCURVE('',#38321,#39713); -#39713 = DEFINITIONAL_REPRESENTATION('',(#39714),#39718); -#39714 = LINE('',#39715,#39716); -#39715 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); -#39716 = VECTOR('',#39717,1.); -#39717 = DIRECTION('',(0.E+000,1.)); -#39718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39719 = PCURVE('',#39720,#39725); -#39720 = CYLINDRICAL_SURFACE('',#39721,0.25); -#39721 = AXIS2_PLACEMENT_3D('',#39722,#39723,#39724); -#39722 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#39723 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39724 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39725 = DEFINITIONAL_REPRESENTATION('',(#39726),#39729); -#39726 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39727,#39728),.UNSPECIFIED., +#42092 = CARTESIAN_POINT('',(1.218367924887,0.31491772868)); +#42093 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); +#42094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42095 = ORIENTED_EDGE('',*,*,#42096,.F.); +#42096 = EDGE_CURVE('',#42097,#42065,#42099,.T.); +#42097 = VERTEX_POINT('',#42098); +#42098 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-2.35)); +#42099 = SURFACE_CURVE('',#42100,(#42104,#42111),.PCURVE_S1.); +#42100 = LINE('',#42101,#42102); +#42101 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-2.35)); +#42102 = VECTOR('',#42103,1.); +#42103 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42104 = PCURVE('',#40713,#42105); +#42105 = DEFINITIONAL_REPRESENTATION('',(#42106),#42110); +#42106 = LINE('',#42107,#42108); +#42107 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); +#42108 = VECTOR('',#42109,1.); +#42109 = DIRECTION('',(0.E+000,1.)); +#42110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42111 = PCURVE('',#42112,#42117); +#42112 = CYLINDRICAL_SURFACE('',#42113,0.25); +#42113 = AXIS2_PLACEMENT_3D('',#42114,#42115,#42116); +#42114 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#42115 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42116 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42117 = DEFINITIONAL_REPRESENTATION('',(#42118),#42121); +#42118 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42119,#42120),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.808438824948),.PIECEWISE_BEZIER_KNOTS.); -#39727 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#39728 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); -#39729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39730 = ORIENTED_EDGE('',*,*,#39731,.F.); -#39731 = EDGE_CURVE('',#39732,#39705,#39734,.T.); -#39732 = VERTEX_POINT('',#39733); -#39733 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); -#39734 = SURFACE_CURVE('',#39735,(#39739,#39746),.PCURVE_S1.); -#39735 = LINE('',#39736,#39737); -#39736 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); -#39737 = VECTOR('',#39738,1.); -#39738 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39739 = PCURVE('',#38321,#39740); -#39740 = DEFINITIONAL_REPRESENTATION('',(#39741),#39745); -#39741 = LINE('',#39742,#39743); -#39742 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#39743 = VECTOR('',#39744,1.); -#39744 = DIRECTION('',(1.,0.E+000)); -#39745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39746 = PCURVE('',#39747,#39752); -#39747 = PLANE('',#39748); -#39748 = AXIS2_PLACEMENT_3D('',#39749,#39750,#39751); -#39749 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#39750 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39752 = DEFINITIONAL_REPRESENTATION('',(#39753),#39757); -#39753 = LINE('',#39754,#39755); -#39754 = CARTESIAN_POINT('',(3.45,0.675)); -#39755 = VECTOR('',#39756,1.); -#39756 = DIRECTION('',(0.E+000,-1.)); -#39757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39758 = ORIENTED_EDGE('',*,*,#39759,.T.); -#39759 = EDGE_CURVE('',#39732,#38542,#39760,.T.); -#39760 = SURFACE_CURVE('',#39761,(#39765,#39772),.PCURVE_S1.); -#39761 = LINE('',#39762,#39763); -#39762 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); -#39763 = VECTOR('',#39764,1.); -#39764 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39765 = PCURVE('',#38321,#39766); -#39766 = DEFINITIONAL_REPRESENTATION('',(#39767),#39771); -#39767 = LINE('',#39768,#39769); -#39768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#39769 = VECTOR('',#39770,1.); -#39770 = DIRECTION('',(0.E+000,1.)); -#39771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39772 = PCURVE('',#38585,#39773); -#39773 = DEFINITIONAL_REPRESENTATION('',(#39774),#39777); -#39774 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39775,#39776),.UNSPECIFIED., +#42119 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#42120 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); +#42121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42122 = ORIENTED_EDGE('',*,*,#42123,.F.); +#42123 = EDGE_CURVE('',#42124,#42097,#42126,.T.); +#42124 = VERTEX_POINT('',#42125); +#42125 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); +#42126 = SURFACE_CURVE('',#42127,(#42131,#42138),.PCURVE_S1.); +#42127 = LINE('',#42128,#42129); +#42128 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); +#42129 = VECTOR('',#42130,1.); +#42130 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42131 = PCURVE('',#40713,#42132); +#42132 = DEFINITIONAL_REPRESENTATION('',(#42133),#42137); +#42133 = LINE('',#42134,#42135); +#42134 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#42135 = VECTOR('',#42136,1.); +#42136 = DIRECTION('',(1.,0.E+000)); +#42137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42138 = PCURVE('',#42139,#42144); +#42139 = PLANE('',#42140); +#42140 = AXIS2_PLACEMENT_3D('',#42141,#42142,#42143); +#42141 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#42142 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42144 = DEFINITIONAL_REPRESENTATION('',(#42145),#42149); +#42145 = LINE('',#42146,#42147); +#42146 = CARTESIAN_POINT('',(3.45,0.675)); +#42147 = VECTOR('',#42148,1.); +#42148 = DIRECTION('',(0.E+000,-1.)); +#42149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42150 = ORIENTED_EDGE('',*,*,#42151,.T.); +#42151 = EDGE_CURVE('',#42124,#40934,#42152,.T.); +#42152 = SURFACE_CURVE('',#42153,(#42157,#42164),.PCURVE_S1.); +#42153 = LINE('',#42154,#42155); +#42154 = CARTESIAN_POINT('',(3.45,0.675,-2.35)); +#42155 = VECTOR('',#42156,1.); +#42156 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42157 = PCURVE('',#40713,#42158); +#42158 = DEFINITIONAL_REPRESENTATION('',(#42159),#42163); +#42159 = LINE('',#42160,#42161); +#42160 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#42161 = VECTOR('',#42162,1.); +#42162 = DIRECTION('',(0.E+000,1.)); +#42163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42164 = PCURVE('',#40977,#42165); +#42165 = DEFINITIONAL_REPRESENTATION('',(#42166),#42169); +#42166 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42167,#42168),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#39775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#39776 = CARTESIAN_POINT('',(0.E+000,4.7)); -#39777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39778 = ORIENTED_EDGE('',*,*,#38541,.T.); -#39779 = ORIENTED_EDGE('',*,*,#39446,.F.); -#39780 = ORIENTED_EDGE('',*,*,#39619,.F.); -#39781 = ORIENTED_EDGE('',*,*,#38755,.T.); -#39782 = ORIENTED_EDGE('',*,*,#38307,.T.); -#39783 = ORIENTED_EDGE('',*,*,#39784,.F.); -#39784 = EDGE_CURVE('',#39785,#38276,#39787,.T.); -#39785 = VERTEX_POINT('',#39786); -#39786 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); -#39787 = SURFACE_CURVE('',#39788,(#39792,#39799),.PCURVE_S1.); -#39788 = LINE('',#39789,#39790); -#39789 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); -#39790 = VECTOR('',#39791,1.); -#39791 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39792 = PCURVE('',#38321,#39793); -#39793 = DEFINITIONAL_REPRESENTATION('',(#39794),#39798); -#39794 = LINE('',#39795,#39796); -#39795 = CARTESIAN_POINT('',(0.746446609407,3.291561175052)); -#39796 = VECTOR('',#39797,1.); -#39797 = DIRECTION('',(0.E+000,1.)); -#39798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39799 = PCURVE('',#38296,#39800); -#39800 = DEFINITIONAL_REPRESENTATION('',(#39801),#39804); -#39801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39802,#39803),.UNSPECIFIED., +#42167 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#42168 = CARTESIAN_POINT('',(0.E+000,4.7)); +#42169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42170 = ORIENTED_EDGE('',*,*,#40933,.T.); +#42171 = ORIENTED_EDGE('',*,*,#41838,.F.); +#42172 = ORIENTED_EDGE('',*,*,#42011,.F.); +#42173 = ORIENTED_EDGE('',*,*,#41147,.T.); +#42174 = ORIENTED_EDGE('',*,*,#40699,.T.); +#42175 = ORIENTED_EDGE('',*,*,#42176,.F.); +#42176 = EDGE_CURVE('',#42177,#40668,#42179,.T.); +#42177 = VERTEX_POINT('',#42178); +#42178 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); +#42179 = SURFACE_CURVE('',#42180,(#42184,#42191),.PCURVE_S1.); +#42180 = LINE('',#42181,#42182); +#42181 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); +#42182 = VECTOR('',#42183,1.); +#42183 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42184 = PCURVE('',#40713,#42185); +#42185 = DEFINITIONAL_REPRESENTATION('',(#42186),#42190); +#42186 = LINE('',#42187,#42188); +#42187 = CARTESIAN_POINT('',(0.746446609407,3.291561175052)); +#42188 = VECTOR('',#42189,1.); +#42189 = DIRECTION('',(0.E+000,1.)); +#42190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42191 = PCURVE('',#40688,#42192); +#42192 = DEFINITIONAL_REPRESENTATION('',(#42193),#42196); +#42193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42194,#42195),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.408438824948),.PIECEWISE_BEZIER_KNOTS.); -#39802 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); -#39803 = CARTESIAN_POINT('',(6.28318530718,4.7)); -#39804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39805 = ORIENTED_EDGE('',*,*,#39806,.F.); -#39806 = EDGE_CURVE('',#39645,#39785,#39807,.T.); -#39807 = SURFACE_CURVE('',#39808,(#39813,#39824),.PCURVE_S1.); -#39808 = CIRCLE('',#39809,0.3); -#39809 = AXIS2_PLACEMENT_3D('',#39810,#39811,#39812); -#39810 = CARTESIAN_POINT('',(3.45,-0.175,0.66)); -#39811 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39812 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39813 = PCURVE('',#38321,#39814); -#39814 = DEFINITIONAL_REPRESENTATION('',(#39815),#39823); -#39815 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#39816,#39817,#39818,#39819 - ,#39820,#39821,#39822),.UNSPECIFIED.,.F.,.F.) +#42194 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); +#42195 = CARTESIAN_POINT('',(6.28318530718,4.7)); +#42196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42197 = ORIENTED_EDGE('',*,*,#42198,.F.); +#42198 = EDGE_CURVE('',#42037,#42177,#42199,.T.); +#42199 = SURFACE_CURVE('',#42200,(#42205,#42216),.PCURVE_S1.); +#42200 = CIRCLE('',#42201,0.3); +#42201 = AXIS2_PLACEMENT_3D('',#42202,#42203,#42204); +#42202 = CARTESIAN_POINT('',(3.45,-0.175,0.66)); +#42203 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42204 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42205 = PCURVE('',#40713,#42206); +#42206 = DEFINITIONAL_REPRESENTATION('',(#42207),#42215); +#42207 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42208,#42209,#42210,#42211 + ,#42212,#42213,#42214),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#39816 = CARTESIAN_POINT('',(0.55,3.01)); -#39817 = CARTESIAN_POINT('',(0.55,3.529615242271)); -#39818 = CARTESIAN_POINT('',(1.,3.269807621135)); -#39819 = CARTESIAN_POINT('',(1.45,3.01)); -#39820 = CARTESIAN_POINT('',(1.,2.750192378865)); -#39821 = CARTESIAN_POINT('',(0.55,2.490384757729)); -#39822 = CARTESIAN_POINT('',(0.55,3.01)); -#39823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39824 = PCURVE('',#39825,#39830); -#39825 = CYLINDRICAL_SURFACE('',#39826,0.3); -#39826 = AXIS2_PLACEMENT_3D('',#39827,#39828,#39829); -#39827 = CARTESIAN_POINT('',(2.377960602616,-0.175,0.66)); -#39828 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39829 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39830 = DEFINITIONAL_REPRESENTATION('',(#39831),#39834); -#39831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39832,#39833),.UNSPECIFIED., +#42208 = CARTESIAN_POINT('',(0.55,3.01)); +#42209 = CARTESIAN_POINT('',(0.55,3.529615242271)); +#42210 = CARTESIAN_POINT('',(1.,3.269807621135)); +#42211 = CARTESIAN_POINT('',(1.45,3.01)); +#42212 = CARTESIAN_POINT('',(1.,2.750192378865)); +#42213 = CARTESIAN_POINT('',(0.55,2.490384757729)); +#42214 = CARTESIAN_POINT('',(0.55,3.01)); +#42215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42216 = PCURVE('',#42217,#42222); +#42217 = CYLINDRICAL_SURFACE('',#42218,0.3); +#42218 = AXIS2_PLACEMENT_3D('',#42219,#42220,#42221); +#42219 = CARTESIAN_POINT('',(2.377960602616,-0.175,0.66)); +#42220 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42221 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42222 = DEFINITIONAL_REPRESENTATION('',(#42223),#42226); +#42223 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42224,#42225),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#39832 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); -#39833 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); -#39834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39835 = ADVANCED_FACE('',(#39836),#39660,.T.); -#39836 = FACE_BOUND('',#39837,.F.); -#39837 = EDGE_LOOP('',(#39838,#39860,#39883,#39903)); -#39838 = ORIENTED_EDGE('',*,*,#39839,.T.); -#39839 = EDGE_CURVE('',#39645,#39840,#39842,.T.); -#39840 = VERTEX_POINT('',#39841); -#39841 = CARTESIAN_POINT('',(3.75,0.125,0.66)); -#39842 = SURFACE_CURVE('',#39843,(#39847,#39854),.PCURVE_S1.); -#39843 = LINE('',#39844,#39845); -#39844 = CARTESIAN_POINT('',(3.45,0.125,0.66)); -#39845 = VECTOR('',#39846,1.); -#39846 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39847 = PCURVE('',#39660,#39848); -#39848 = DEFINITIONAL_REPRESENTATION('',(#39849),#39853); -#39849 = LINE('',#39850,#39851); -#39850 = CARTESIAN_POINT('',(3.45,0.66)); -#39851 = VECTOR('',#39852,1.); -#39852 = DIRECTION('',(1.,0.E+000)); -#39853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39854 = PCURVE('',#39825,#39855); -#39855 = DEFINITIONAL_REPRESENTATION('',(#39856),#39859); -#39856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39857,#39858),.UNSPECIFIED., +#42224 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); +#42225 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); +#42226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42227 = ADVANCED_FACE('',(#42228),#42052,.T.); +#42228 = FACE_BOUND('',#42229,.F.); +#42229 = EDGE_LOOP('',(#42230,#42252,#42275,#42295)); +#42230 = ORIENTED_EDGE('',*,*,#42231,.T.); +#42231 = EDGE_CURVE('',#42037,#42232,#42234,.T.); +#42232 = VERTEX_POINT('',#42233); +#42233 = CARTESIAN_POINT('',(3.75,0.125,0.66)); +#42234 = SURFACE_CURVE('',#42235,(#42239,#42246),.PCURVE_S1.); +#42235 = LINE('',#42236,#42237); +#42236 = CARTESIAN_POINT('',(3.45,0.125,0.66)); +#42237 = VECTOR('',#42238,1.); +#42238 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42239 = PCURVE('',#42052,#42240); +#42240 = DEFINITIONAL_REPRESENTATION('',(#42241),#42245); +#42241 = LINE('',#42242,#42243); +#42242 = CARTESIAN_POINT('',(3.45,0.66)); +#42243 = VECTOR('',#42244,1.); +#42244 = DIRECTION('',(1.,0.E+000)); +#42245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42246 = PCURVE('',#42217,#42247); +#42247 = DEFINITIONAL_REPRESENTATION('',(#42248),#42251); +#42248 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42249,#42250),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39857 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); -#39858 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); -#39859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39860 = ORIENTED_EDGE('',*,*,#39861,.F.); -#39861 = EDGE_CURVE('',#39862,#39840,#39864,.T.); -#39862 = VERTEX_POINT('',#39863); -#39863 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); -#39864 = SURFACE_CURVE('',#39865,(#39869,#39876),.PCURVE_S1.); -#39865 = LINE('',#39866,#39867); -#39866 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); -#39867 = VECTOR('',#39868,1.); -#39868 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39869 = PCURVE('',#39660,#39870); -#39870 = DEFINITIONAL_REPRESENTATION('',(#39871),#39875); -#39871 = LINE('',#39872,#39873); -#39872 = CARTESIAN_POINT('',(3.75,-0.26)); -#39873 = VECTOR('',#39874,1.); -#39874 = DIRECTION('',(0.E+000,1.)); -#39875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39876 = PCURVE('',#38035,#39877); -#39877 = DEFINITIONAL_REPRESENTATION('',(#39878),#39882); -#39878 = LINE('',#39879,#39880); -#39879 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#39880 = VECTOR('',#39881,1.); -#39881 = DIRECTION('',(0.E+000,1.)); -#39882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39883 = ORIENTED_EDGE('',*,*,#39884,.T.); -#39884 = EDGE_CURVE('',#39862,#39643,#39885,.T.); -#39885 = SURFACE_CURVE('',#39886,(#39890,#39897),.PCURVE_S1.); -#39886 = LINE('',#39887,#39888); -#39887 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); -#39888 = VECTOR('',#39889,1.); -#39889 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#39890 = PCURVE('',#39660,#39891); -#39891 = DEFINITIONAL_REPRESENTATION('',(#39892),#39896); -#39892 = LINE('',#39893,#39894); -#39893 = CARTESIAN_POINT('',(3.75,-0.26)); -#39894 = VECTOR('',#39895,1.); -#39895 = DIRECTION('',(-1.,0.E+000)); -#39896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39897 = PCURVE('',#39693,#39898); -#39898 = DEFINITIONAL_REPRESENTATION('',(#39899),#39902); -#39899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39900,#39901),.UNSPECIFIED., +#42249 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); +#42250 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); +#42251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42252 = ORIENTED_EDGE('',*,*,#42253,.F.); +#42253 = EDGE_CURVE('',#42254,#42232,#42256,.T.); +#42254 = VERTEX_POINT('',#42255); +#42255 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); +#42256 = SURFACE_CURVE('',#42257,(#42261,#42268),.PCURVE_S1.); +#42257 = LINE('',#42258,#42259); +#42258 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); +#42259 = VECTOR('',#42260,1.); +#42260 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42261 = PCURVE('',#42052,#42262); +#42262 = DEFINITIONAL_REPRESENTATION('',(#42263),#42267); +#42263 = LINE('',#42264,#42265); +#42264 = CARTESIAN_POINT('',(3.75,-0.26)); +#42265 = VECTOR('',#42266,1.); +#42266 = DIRECTION('',(0.E+000,1.)); +#42267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42268 = PCURVE('',#40427,#42269); +#42269 = DEFINITIONAL_REPRESENTATION('',(#42270),#42274); +#42270 = LINE('',#42271,#42272); +#42271 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#42272 = VECTOR('',#42273,1.); +#42273 = DIRECTION('',(0.E+000,1.)); +#42274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42275 = ORIENTED_EDGE('',*,*,#42276,.T.); +#42276 = EDGE_CURVE('',#42254,#42035,#42277,.T.); +#42277 = SURFACE_CURVE('',#42278,(#42282,#42289),.PCURVE_S1.); +#42278 = LINE('',#42279,#42280); +#42279 = CARTESIAN_POINT('',(3.75,0.125,-0.26)); +#42280 = VECTOR('',#42281,1.); +#42281 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42282 = PCURVE('',#42052,#42283); +#42283 = DEFINITIONAL_REPRESENTATION('',(#42284),#42288); +#42284 = LINE('',#42285,#42286); +#42285 = CARTESIAN_POINT('',(3.75,-0.26)); +#42286 = VECTOR('',#42287,1.); +#42287 = DIRECTION('',(-1.,0.E+000)); +#42288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42289 = PCURVE('',#42085,#42290); +#42290 = DEFINITIONAL_REPRESENTATION('',(#42291),#42294); +#42291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42292,#42293),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39900 = CARTESIAN_POINT('',(0.E+000,1.491772868E-002)); -#39901 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); -#39902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39903 = ORIENTED_EDGE('',*,*,#39642,.T.); -#39904 = ADVANCED_FACE('',(#39905),#39919,.T.); -#39905 = FACE_BOUND('',#39906,.F.); -#39906 = EDGE_LOOP('',(#39907,#39941,#39964,#39991)); -#39907 = ORIENTED_EDGE('',*,*,#39908,.T.); -#39908 = EDGE_CURVE('',#39909,#39911,#39913,.T.); -#39909 = VERTEX_POINT('',#39910); -#39910 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); -#39911 = VERTEX_POINT('',#39912); -#39912 = CARTESIAN_POINT('',(-3.75,0.125,-0.26)); -#39913 = SURFACE_CURVE('',#39914,(#39918,#39930),.PCURVE_S1.); -#39914 = LINE('',#39915,#39916); -#39915 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); -#39916 = VECTOR('',#39917,1.); -#39917 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#39918 = PCURVE('',#39919,#39924); -#39919 = PLANE('',#39920); -#39920 = AXIS2_PLACEMENT_3D('',#39921,#39922,#39923); -#39921 = CARTESIAN_POINT('',(0.E+000,0.125,0.E+000)); -#39922 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#39923 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39924 = DEFINITIONAL_REPRESENTATION('',(#39925),#39929); -#39925 = LINE('',#39926,#39927); -#39926 = CARTESIAN_POINT('',(-3.45,-0.26)); -#39927 = VECTOR('',#39928,1.); -#39928 = DIRECTION('',(-1.,0.E+000)); -#39929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39930 = PCURVE('',#39931,#39936); -#39931 = CYLINDRICAL_SURFACE('',#39932,0.3); -#39932 = AXIS2_PLACEMENT_3D('',#39933,#39934,#39935); -#39933 = CARTESIAN_POINT('',(-2.377960602616,-0.175,-0.26)); -#39934 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#39935 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39936 = DEFINITIONAL_REPRESENTATION('',(#39937),#39940); -#39937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39938,#39939),.UNSPECIFIED., +#42292 = CARTESIAN_POINT('',(0.E+000,1.491772868E-002)); +#42293 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); +#42294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42295 = ORIENTED_EDGE('',*,*,#42034,.T.); +#42296 = ADVANCED_FACE('',(#42297),#42311,.T.); +#42297 = FACE_BOUND('',#42298,.F.); +#42298 = EDGE_LOOP('',(#42299,#42333,#42356,#42383)); +#42299 = ORIENTED_EDGE('',*,*,#42300,.T.); +#42300 = EDGE_CURVE('',#42301,#42303,#42305,.T.); +#42301 = VERTEX_POINT('',#42302); +#42302 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); +#42303 = VERTEX_POINT('',#42304); +#42304 = CARTESIAN_POINT('',(-3.75,0.125,-0.26)); +#42305 = SURFACE_CURVE('',#42306,(#42310,#42322),.PCURVE_S1.); +#42306 = LINE('',#42307,#42308); +#42307 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); +#42308 = VECTOR('',#42309,1.); +#42309 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42310 = PCURVE('',#42311,#42316); +#42311 = PLANE('',#42312); +#42312 = AXIS2_PLACEMENT_3D('',#42313,#42314,#42315); +#42313 = CARTESIAN_POINT('',(0.E+000,0.125,0.E+000)); +#42314 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42315 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42316 = DEFINITIONAL_REPRESENTATION('',(#42317),#42321); +#42317 = LINE('',#42318,#42319); +#42318 = CARTESIAN_POINT('',(-3.45,-0.26)); +#42319 = VECTOR('',#42320,1.); +#42320 = DIRECTION('',(-1.,0.E+000)); +#42321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42322 = PCURVE('',#42323,#42328); +#42323 = CYLINDRICAL_SURFACE('',#42324,0.3); +#42324 = AXIS2_PLACEMENT_3D('',#42325,#42326,#42327); +#42325 = CARTESIAN_POINT('',(-2.377960602616,-0.175,-0.26)); +#42326 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42327 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42328 = DEFINITIONAL_REPRESENTATION('',(#42329),#42332); +#42329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42330,#42331),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39938 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); -#39939 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); -#39940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39941 = ORIENTED_EDGE('',*,*,#39942,.T.); -#39942 = EDGE_CURVE('',#39911,#39943,#39945,.T.); -#39943 = VERTEX_POINT('',#39944); -#39944 = CARTESIAN_POINT('',(-3.75,0.125,0.66)); -#39945 = SURFACE_CURVE('',#39946,(#39950,#39957),.PCURVE_S1.); -#39946 = LINE('',#39947,#39948); -#39947 = CARTESIAN_POINT('',(-3.75,0.125,-0.26)); -#39948 = VECTOR('',#39949,1.); -#39949 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39950 = PCURVE('',#39919,#39951); -#39951 = DEFINITIONAL_REPRESENTATION('',(#39952),#39956); -#39952 = LINE('',#39953,#39954); -#39953 = CARTESIAN_POINT('',(-3.75,-0.26)); -#39954 = VECTOR('',#39955,1.); -#39955 = DIRECTION('',(0.E+000,1.)); -#39956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39957 = PCURVE('',#37969,#39958); -#39958 = DEFINITIONAL_REPRESENTATION('',(#39959),#39963); -#39959 = LINE('',#39960,#39961); -#39960 = CARTESIAN_POINT('',(0.55,2.09)); -#39961 = VECTOR('',#39962,1.); -#39962 = DIRECTION('',(0.E+000,1.)); -#39963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39964 = ORIENTED_EDGE('',*,*,#39965,.T.); -#39965 = EDGE_CURVE('',#39943,#39966,#39968,.T.); -#39966 = VERTEX_POINT('',#39967); -#39967 = CARTESIAN_POINT('',(-3.45,0.125,0.66)); -#39968 = SURFACE_CURVE('',#39969,(#39973,#39980),.PCURVE_S1.); -#39969 = LINE('',#39970,#39971); -#39970 = CARTESIAN_POINT('',(-3.75,0.125,0.66)); -#39971 = VECTOR('',#39972,1.); -#39972 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39973 = PCURVE('',#39919,#39974); -#39974 = DEFINITIONAL_REPRESENTATION('',(#39975),#39979); -#39975 = LINE('',#39976,#39977); -#39976 = CARTESIAN_POINT('',(-3.75,0.66)); -#39977 = VECTOR('',#39978,1.); -#39978 = DIRECTION('',(1.,0.E+000)); -#39979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39980 = PCURVE('',#39981,#39986); -#39981 = CYLINDRICAL_SURFACE('',#39982,0.3); -#39982 = AXIS2_PLACEMENT_3D('',#39983,#39984,#39985); -#39983 = CARTESIAN_POINT('',(-3.766262878957,-0.175,0.66)); -#39984 = DIRECTION('',(1.,0.E+000,0.E+000)); -#39985 = DIRECTION('',(0.E+000,1.,0.E+000)); -#39986 = DEFINITIONAL_REPRESENTATION('',(#39987),#39990); -#39987 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#39988,#39989),.UNSPECIFIED., +#42330 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); +#42331 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); +#42332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42333 = ORIENTED_EDGE('',*,*,#42334,.T.); +#42334 = EDGE_CURVE('',#42303,#42335,#42337,.T.); +#42335 = VERTEX_POINT('',#42336); +#42336 = CARTESIAN_POINT('',(-3.75,0.125,0.66)); +#42337 = SURFACE_CURVE('',#42338,(#42342,#42349),.PCURVE_S1.); +#42338 = LINE('',#42339,#42340); +#42339 = CARTESIAN_POINT('',(-3.75,0.125,-0.26)); +#42340 = VECTOR('',#42341,1.); +#42341 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42342 = PCURVE('',#42311,#42343); +#42343 = DEFINITIONAL_REPRESENTATION('',(#42344),#42348); +#42344 = LINE('',#42345,#42346); +#42345 = CARTESIAN_POINT('',(-3.75,-0.26)); +#42346 = VECTOR('',#42347,1.); +#42347 = DIRECTION('',(0.E+000,1.)); +#42348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42349 = PCURVE('',#40361,#42350); +#42350 = DEFINITIONAL_REPRESENTATION('',(#42351),#42355); +#42351 = LINE('',#42352,#42353); +#42352 = CARTESIAN_POINT('',(0.55,2.09)); +#42353 = VECTOR('',#42354,1.); +#42354 = DIRECTION('',(0.E+000,1.)); +#42355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42356 = ORIENTED_EDGE('',*,*,#42357,.T.); +#42357 = EDGE_CURVE('',#42335,#42358,#42360,.T.); +#42358 = VERTEX_POINT('',#42359); +#42359 = CARTESIAN_POINT('',(-3.45,0.125,0.66)); +#42360 = SURFACE_CURVE('',#42361,(#42365,#42372),.PCURVE_S1.); +#42361 = LINE('',#42362,#42363); +#42362 = CARTESIAN_POINT('',(-3.75,0.125,0.66)); +#42363 = VECTOR('',#42364,1.); +#42364 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42365 = PCURVE('',#42311,#42366); +#42366 = DEFINITIONAL_REPRESENTATION('',(#42367),#42371); +#42367 = LINE('',#42368,#42369); +#42368 = CARTESIAN_POINT('',(-3.75,0.66)); +#42369 = VECTOR('',#42370,1.); +#42370 = DIRECTION('',(1.,0.E+000)); +#42371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42372 = PCURVE('',#42373,#42378); +#42373 = CYLINDRICAL_SURFACE('',#42374,0.3); +#42374 = AXIS2_PLACEMENT_3D('',#42375,#42376,#42377); +#42375 = CARTESIAN_POINT('',(-3.766262878957,-0.175,0.66)); +#42376 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42377 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42378 = DEFINITIONAL_REPRESENTATION('',(#42379),#42382); +#42379 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42380,#42381),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#39988 = CARTESIAN_POINT('',(0.E+000,1.6262878957E-002)); -#39989 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); -#39990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#39991 = ORIENTED_EDGE('',*,*,#39992,.F.); -#39992 = EDGE_CURVE('',#39909,#39966,#39993,.T.); -#39993 = SURFACE_CURVE('',#39994,(#39998,#40005),.PCURVE_S1.); -#39994 = LINE('',#39995,#39996); -#39995 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); -#39996 = VECTOR('',#39997,1.); -#39997 = DIRECTION('',(0.E+000,0.E+000,1.)); -#39998 = PCURVE('',#39919,#39999); -#39999 = DEFINITIONAL_REPRESENTATION('',(#40000),#40004); -#40000 = LINE('',#40001,#40002); -#40001 = CARTESIAN_POINT('',(-3.45,-0.26)); -#40002 = VECTOR('',#40003,1.); -#40003 = DIRECTION('',(0.E+000,1.)); -#40004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40005 = PCURVE('',#37683,#40006); -#40006 = DEFINITIONAL_REPRESENTATION('',(#40007),#40011); -#40007 = LINE('',#40008,#40009); -#40008 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#40009 = VECTOR('',#40010,1.); -#40010 = DIRECTION('',(0.E+000,1.)); -#40011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40012 = ADVANCED_FACE('',(#40013),#39825,.F.); -#40013 = FACE_BOUND('',#40014,.F.); -#40014 = EDGE_LOOP('',(#40015,#40016,#40017,#40086,#40113,#40182)); -#40015 = ORIENTED_EDGE('',*,*,#39839,.F.); -#40016 = ORIENTED_EDGE('',*,*,#39806,.T.); -#40017 = ORIENTED_EDGE('',*,*,#40018,.T.); -#40018 = EDGE_CURVE('',#39785,#40019,#40021,.T.); -#40019 = VERTEX_POINT('',#40020); -#40020 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); -#40021 = SURFACE_CURVE('',#40022,(#40028,#40057),.PCURVE_S1.); -#40022 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40023,#40024,#40025,#40026, - #40027),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#42380 = CARTESIAN_POINT('',(0.E+000,1.6262878957E-002)); +#42381 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); +#42382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42383 = ORIENTED_EDGE('',*,*,#42384,.F.); +#42384 = EDGE_CURVE('',#42301,#42358,#42385,.T.); +#42385 = SURFACE_CURVE('',#42386,(#42390,#42397),.PCURVE_S1.); +#42386 = LINE('',#42387,#42388); +#42387 = CARTESIAN_POINT('',(-3.45,0.125,-0.26)); +#42388 = VECTOR('',#42389,1.); +#42389 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42390 = PCURVE('',#42311,#42391); +#42391 = DEFINITIONAL_REPRESENTATION('',(#42392),#42396); +#42392 = LINE('',#42393,#42394); +#42393 = CARTESIAN_POINT('',(-3.45,-0.26)); +#42394 = VECTOR('',#42395,1.); +#42395 = DIRECTION('',(0.E+000,1.)); +#42396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42397 = PCURVE('',#40075,#42398); +#42398 = DEFINITIONAL_REPRESENTATION('',(#42399),#42403); +#42399 = LINE('',#42400,#42401); +#42400 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#42401 = VECTOR('',#42402,1.); +#42402 = DIRECTION('',(0.E+000,1.)); +#42403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42404 = ADVANCED_FACE('',(#42405),#42217,.F.); +#42405 = FACE_BOUND('',#42406,.F.); +#42406 = EDGE_LOOP('',(#42407,#42408,#42409,#42478,#42505,#42574)); +#42407 = ORIENTED_EDGE('',*,*,#42231,.F.); +#42408 = ORIENTED_EDGE('',*,*,#42198,.T.); +#42409 = ORIENTED_EDGE('',*,*,#42410,.T.); +#42410 = EDGE_CURVE('',#42177,#42411,#42413,.T.); +#42411 = VERTEX_POINT('',#42412); +#42412 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); +#42413 = SURFACE_CURVE('',#42414,(#42420,#42449),.PCURVE_S1.); +#42414 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42415,#42416,#42417,#42418, + #42419),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#40023 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); -#40024 = CARTESIAN_POINT('',(3.45,-8.905545695663E-002,0.948037408389)); -#40025 = CARTESIAN_POINT('',(3.446265514013,-0.124399022516, +#42415 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,0.941561175052)); +#42416 = CARTESIAN_POINT('',(3.45,-8.905545695663E-002,0.948037408389)); +#42417 = CARTESIAN_POINT('',(3.446265514013,-0.124399022516, 0.957280182746)); -#40026 = CARTESIAN_POINT('',(3.435043419394,-0.158523058273,0.96)); -#40027 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); -#40028 = PCURVE('',#39825,#40029); -#40029 = DEFINITIONAL_REPRESENTATION('',(#40030),#40056); -#40030 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40031,#40032,#40033,#40034, - #40035,#40036,#40037,#40038,#40039,#40040,#40041,#40042,#40043, - #40044,#40045,#40046,#40047,#40048,#40049,#40050,#40051,#40052, - #40053,#40054,#40055),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42418 = CARTESIAN_POINT('',(3.435043419394,-0.158523058273,0.96)); +#42419 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); +#42420 = PCURVE('',#42217,#42421); +#42421 = DEFINITIONAL_REPRESENTATION('',(#42422),#42448); +#42422 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42423,#42424,#42425,#42426, + #42427,#42428,#42429,#42430,#42431,#42432,#42433,#42434,#42435, + #42436,#42437,#42438,#42439,#42440,#42441,#42442,#42443,#42444, + #42445,#42446,#42447),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50191,40 +53180,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40031 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); -#40032 = CARTESIAN_POINT('',(1.224053368679,1.072039397384)); -#40033 = CARTESIAN_POINT('',(1.235392290282,1.072008533863)); -#40034 = CARTESIAN_POINT('',(1.252305452933,1.071869627018)); -#40035 = CARTESIAN_POINT('',(1.269124141521,1.071638087605)); -#40036 = CARTESIAN_POINT('',(1.285848865488,1.071313894621)); -#40037 = CARTESIAN_POINT('',(1.302479984449,1.070897027064)); -#40038 = CARTESIAN_POINT('',(1.319017690454,1.07038746393)); -#40039 = CARTESIAN_POINT('',(1.335462018513,1.069785184216)); -#40040 = CARTESIAN_POINT('',(1.351812849887,1.069090166919)); -#40041 = CARTESIAN_POINT('',(1.368069917569,1.068302391038)); -#40042 = CARTESIAN_POINT('',(1.384232811654,1.067421835567)); -#40043 = CARTESIAN_POINT('',(1.400300984164,1.066448479505)); -#40044 = CARTESIAN_POINT('',(1.416273757301,1.065382301848)); -#40045 = CARTESIAN_POINT('',(1.432151728523,1.064223232546)); -#40046 = CARTESIAN_POINT('',(1.447935340012,1.062971201547)); -#40047 = CARTESIAN_POINT('',(1.463624884234,1.0616261388)); -#40048 = CARTESIAN_POINT('',(1.479220506559,1.060187974255)); -#40049 = CARTESIAN_POINT('',(1.49472220906,1.05865663786)); -#40050 = CARTESIAN_POINT('',(1.510129853916,1.057032059565)); -#40051 = CARTESIAN_POINT('',(1.525443168443,1.055314169318)); -#40052 = CARTESIAN_POINT('',(1.540661745136,1.053502897068)); -#40053 = CARTESIAN_POINT('',(1.55578506107,1.051598172765)); -#40054 = CARTESIAN_POINT('',(1.565803304202,1.050266008493)); -#40055 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); -#40056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40057 = PCURVE('',#38296,#40058); -#40058 = DEFINITIONAL_REPRESENTATION('',(#40059),#40085); -#40059 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40060,#40061,#40062,#40063, - #40064,#40065,#40066,#40067,#40068,#40069,#40070,#40071,#40072, - #40073,#40074,#40075,#40076,#40077,#40078,#40079,#40080,#40081, - #40082,#40083,#40084),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42423 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); +#42424 = CARTESIAN_POINT('',(1.224053368679,1.072039397384)); +#42425 = CARTESIAN_POINT('',(1.235392290282,1.072008533863)); +#42426 = CARTESIAN_POINT('',(1.252305452933,1.071869627018)); +#42427 = CARTESIAN_POINT('',(1.269124141521,1.071638087605)); +#42428 = CARTESIAN_POINT('',(1.285848865488,1.071313894621)); +#42429 = CARTESIAN_POINT('',(1.302479984449,1.070897027064)); +#42430 = CARTESIAN_POINT('',(1.319017690454,1.07038746393)); +#42431 = CARTESIAN_POINT('',(1.335462018513,1.069785184216)); +#42432 = CARTESIAN_POINT('',(1.351812849887,1.069090166919)); +#42433 = CARTESIAN_POINT('',(1.368069917569,1.068302391038)); +#42434 = CARTESIAN_POINT('',(1.384232811654,1.067421835567)); +#42435 = CARTESIAN_POINT('',(1.400300984164,1.066448479505)); +#42436 = CARTESIAN_POINT('',(1.416273757301,1.065382301848)); +#42437 = CARTESIAN_POINT('',(1.432151728523,1.064223232546)); +#42438 = CARTESIAN_POINT('',(1.447935340012,1.062971201547)); +#42439 = CARTESIAN_POINT('',(1.463624884234,1.0616261388)); +#42440 = CARTESIAN_POINT('',(1.479220506559,1.060187974255)); +#42441 = CARTESIAN_POINT('',(1.49472220906,1.05865663786)); +#42442 = CARTESIAN_POINT('',(1.510129853916,1.057032059565)); +#42443 = CARTESIAN_POINT('',(1.525443168443,1.055314169318)); +#42444 = CARTESIAN_POINT('',(1.540661745136,1.053502897068)); +#42445 = CARTESIAN_POINT('',(1.55578506107,1.051598172765)); +#42446 = CARTESIAN_POINT('',(1.565803304202,1.050266008493)); +#42447 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); +#42448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42449 = PCURVE('',#40688,#42450); +#42450 = DEFINITIONAL_REPRESENTATION('',(#42451),#42477); +#42451 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42452,#42453,#42454,#42455, + #42456,#42457,#42458,#42459,#42460,#42461,#42462,#42463,#42464, + #42465,#42466,#42467,#42468,#42469,#42470,#42471,#42472,#42473, + #42474,#42475,#42476),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50232,86 +53221,86 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40060 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); -#40061 = CARTESIAN_POINT('',(6.276782090783,3.292149923537)); -#40062 = CARTESIAN_POINT('',(6.263971493355,3.293296761893)); -#40063 = CARTESIAN_POINT('',(6.244742590574,3.294926053834)); -#40064 = CARTESIAN_POINT('',(6.225500166207,3.29646539043)); -#40065 = CARTESIAN_POINT('',(6.206243713069,3.29791578193)); -#40066 = CARTESIAN_POINT('',(6.18697271812,3.299278238583)); -#40067 = CARTESIAN_POINT('',(6.167686655202,3.300553770638)); -#40068 = CARTESIAN_POINT('',(6.148384976109,3.301743388344)); -#40069 = CARTESIAN_POINT('',(6.129067102162,3.30284810195)); -#40070 = CARTESIAN_POINT('',(6.109732415754,3.303868921704)); -#40071 = CARTESIAN_POINT('',(6.090380251919,3.304806857856)); -#40072 = CARTESIAN_POINT('',(6.071009890349,3.305662920654)); -#40073 = CARTESIAN_POINT('',(6.051620546195,3.306438120348)); -#40074 = CARTESIAN_POINT('',(6.032209783116,3.307133677812)); -#40075 = CARTESIAN_POINT('',(6.01277510274,3.30775081392)); -#40076 = CARTESIAN_POINT('',(5.99331394214,3.308290749547)); -#40077 = CARTESIAN_POINT('',(5.973823672514,3.308754705567)); -#40078 = CARTESIAN_POINT('',(5.954301597843,3.309143902855)); -#40079 = CARTESIAN_POINT('',(5.934744953627,3.309459562285)); -#40080 = CARTESIAN_POINT('',(5.91515090664,3.309702904731)); -#40081 = CARTESIAN_POINT('',(5.895516551932,3.309875151069)); -#40082 = CARTESIAN_POINT('',(5.875838921352,3.309977522171)); -#40083 = CARTESIAN_POINT('',(5.862689607355,3.31)); -#40084 = CARTESIAN_POINT('',(5.856106720787,3.31)); -#40085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40086 = ORIENTED_EDGE('',*,*,#40087,.T.); -#40087 = EDGE_CURVE('',#40019,#40088,#40090,.T.); -#40088 = VERTEX_POINT('',#40089); -#40089 = CARTESIAN_POINT('',(3.740163581979,-0.175,0.96)); -#40090 = SURFACE_CURVE('',#40091,(#40095,#40101),.PCURVE_S1.); -#40091 = LINE('',#40092,#40093); -#40092 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); -#40093 = VECTOR('',#40094,1.); -#40094 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40095 = PCURVE('',#39825,#40096); -#40096 = DEFINITIONAL_REPRESENTATION('',(#40097),#40100); -#40097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40098,#40099),.UNSPECIFIED., +#42452 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); +#42453 = CARTESIAN_POINT('',(6.276782090783,3.292149923537)); +#42454 = CARTESIAN_POINT('',(6.263971493355,3.293296761893)); +#42455 = CARTESIAN_POINT('',(6.244742590574,3.294926053834)); +#42456 = CARTESIAN_POINT('',(6.225500166207,3.29646539043)); +#42457 = CARTESIAN_POINT('',(6.206243713069,3.29791578193)); +#42458 = CARTESIAN_POINT('',(6.18697271812,3.299278238583)); +#42459 = CARTESIAN_POINT('',(6.167686655202,3.300553770638)); +#42460 = CARTESIAN_POINT('',(6.148384976109,3.301743388344)); +#42461 = CARTESIAN_POINT('',(6.129067102162,3.30284810195)); +#42462 = CARTESIAN_POINT('',(6.109732415754,3.303868921704)); +#42463 = CARTESIAN_POINT('',(6.090380251919,3.304806857856)); +#42464 = CARTESIAN_POINT('',(6.071009890349,3.305662920654)); +#42465 = CARTESIAN_POINT('',(6.051620546195,3.306438120348)); +#42466 = CARTESIAN_POINT('',(6.032209783116,3.307133677812)); +#42467 = CARTESIAN_POINT('',(6.01277510274,3.30775081392)); +#42468 = CARTESIAN_POINT('',(5.99331394214,3.308290749547)); +#42469 = CARTESIAN_POINT('',(5.973823672514,3.308754705567)); +#42470 = CARTESIAN_POINT('',(5.954301597843,3.309143902855)); +#42471 = CARTESIAN_POINT('',(5.934744953627,3.309459562285)); +#42472 = CARTESIAN_POINT('',(5.91515090664,3.309702904731)); +#42473 = CARTESIAN_POINT('',(5.895516551932,3.309875151069)); +#42474 = CARTESIAN_POINT('',(5.875838921352,3.309977522171)); +#42475 = CARTESIAN_POINT('',(5.862689607355,3.31)); +#42476 = CARTESIAN_POINT('',(5.856106720787,3.31)); +#42477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42478 = ORIENTED_EDGE('',*,*,#42479,.T.); +#42479 = EDGE_CURVE('',#42411,#42480,#42482,.T.); +#42480 = VERTEX_POINT('',#42481); +#42481 = CARTESIAN_POINT('',(3.740163581979,-0.175,0.96)); +#42482 = SURFACE_CURVE('',#42483,(#42487,#42493),.PCURVE_S1.); +#42483 = LINE('',#42484,#42485); +#42484 = CARTESIAN_POINT('',(3.427544930281,-0.175,0.96)); +#42485 = VECTOR('',#42486,1.); +#42486 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42487 = PCURVE('',#42217,#42488); +#42488 = DEFINITIONAL_REPRESENTATION('',(#42489),#42492); +#42489 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42490,#42491),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.312618651698),.PIECEWISE_BEZIER_KNOTS.); -#40098 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); -#40099 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); -#40100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40101 = PCURVE('',#40102,#40107); -#40102 = PLANE('',#40103); -#40103 = AXIS2_PLACEMENT_3D('',#40104,#40105,#40106); -#40104 = CARTESIAN_POINT('',(3.75,-1.225,0.96)); -#40105 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40106 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#40107 = DEFINITIONAL_REPRESENTATION('',(#40108),#40112); -#40108 = LINE('',#40109,#40110); -#40109 = CARTESIAN_POINT('',(0.322455069719,-1.05)); -#40110 = VECTOR('',#40111,1.); -#40111 = DIRECTION('',(-1.,0.E+000)); -#40112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40113 = ORIENTED_EDGE('',*,*,#40114,.T.); -#40114 = EDGE_CURVE('',#40088,#40115,#40117,.T.); -#40115 = VERTEX_POINT('',#40116); -#40116 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); -#40117 = SURFACE_CURVE('',#40118,(#40124,#40153),.PCURVE_S1.); -#40118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40119,#40120,#40121,#40122, - #40123),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#42490 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); +#42491 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); +#42492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42493 = PCURVE('',#42494,#42499); +#42494 = PLANE('',#42495); +#42495 = AXIS2_PLACEMENT_3D('',#42496,#42497,#42498); +#42496 = CARTESIAN_POINT('',(3.75,-1.225,0.96)); +#42497 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42498 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42499 = DEFINITIONAL_REPRESENTATION('',(#42500),#42504); +#42500 = LINE('',#42501,#42502); +#42501 = CARTESIAN_POINT('',(0.322455069719,-1.05)); +#42502 = VECTOR('',#42503,1.); +#42503 = DIRECTION('',(-1.,0.E+000)); +#42504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42505 = ORIENTED_EDGE('',*,*,#42506,.T.); +#42506 = EDGE_CURVE('',#42480,#42507,#42509,.T.); +#42507 = VERTEX_POINT('',#42508); +#42508 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); +#42509 = SURFACE_CURVE('',#42510,(#42516,#42545),.PCURVE_S1.); +#42510 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42511,#42512,#42513,#42514, + #42515),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#40119 = CARTESIAN_POINT('',(3.740163581979,-0.175,0.96)); -#40120 = CARTESIAN_POINT('',(3.743515535172,-0.157515270308,0.96)); -#40121 = CARTESIAN_POINT('',(3.748473534432,-0.122396186728, +#42511 = CARTESIAN_POINT('',(3.740163581979,-0.175,0.96)); +#42512 = CARTESIAN_POINT('',(3.743515535172,-0.157515270308,0.96)); +#42513 = CARTESIAN_POINT('',(3.748473534432,-0.122396186728, 0.95693337728)); -#40122 = CARTESIAN_POINT('',(3.75,-8.810914429415E-002,0.947689370756)); -#40123 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); -#40124 = PCURVE('',#39825,#40125); -#40125 = DEFINITIONAL_REPRESENTATION('',(#40126),#40152); -#40126 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40127,#40128,#40129,#40130, - #40131,#40132,#40133,#40134,#40135,#40136,#40137,#40138,#40139, - #40140,#40141,#40142,#40143,#40144,#40145,#40146,#40147,#40148, - #40149,#40150,#40151),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42514 = CARTESIAN_POINT('',(3.75,-8.810914429415E-002,0.947689370756)); +#42515 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); +#42516 = PCURVE('',#42217,#42517); +#42517 = DEFINITIONAL_REPRESENTATION('',(#42518),#42544); +#42518 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42519,#42520,#42521,#42522, + #42523,#42524,#42525,#42526,#42527,#42528,#42529,#42530,#42531, + #42532,#42533,#42534,#42535,#42536,#42537,#42538,#42539,#42540, + #42541,#42542,#42543),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50319,40 +53308,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40127 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); -#40128 = CARTESIAN_POINT('',(1.56549792408,1.362507702381)); -#40129 = CARTESIAN_POINT('',(1.554896995806,1.363102719431)); -#40130 = CARTESIAN_POINT('',(1.538983437791,1.363952025988)); -#40131 = CARTESIAN_POINT('',(1.523057917113,1.36475818146)); -#40132 = CARTESIAN_POINT('',(1.507120636663,1.365521253783)); -#40133 = CARTESIAN_POINT('',(1.491171793493,1.36624131089)); -#40134 = CARTESIAN_POINT('',(1.475211574561,1.366918420715)); -#40135 = CARTESIAN_POINT('',(1.459240152088,1.367552651195)); -#40136 = CARTESIAN_POINT('',(1.443257679003,1.368144070262)); -#40137 = CARTESIAN_POINT('',(1.427264284498,1.368692745853)); -#40138 = CARTESIAN_POINT('',(1.411260069235,1.3691987459)); -#40139 = CARTESIAN_POINT('',(1.395245101983,1.369662138339)); -#40140 = CARTESIAN_POINT('',(1.379219411097,1.370082991104)); -#40141 = CARTESIAN_POINT('',(1.363182990948,1.370461730869)); -#40142 = CARTESIAN_POINT('',(1.347135841657,1.37079878431)); -#40143 = CARTESIAN_POINT('',(1.331077960761,1.371094578101)); -#40144 = CARTESIAN_POINT('',(1.31500934008,1.371349538916)); -#40145 = CARTESIAN_POINT('',(1.298929961228,1.37156409343)); -#40146 = CARTESIAN_POINT('',(1.282839791397,1.371738668317)); -#40147 = CARTESIAN_POINT('',(1.26673877946,1.371873690253)); -#40148 = CARTESIAN_POINT('',(1.250626850657,1.371969585911)); -#40149 = CARTESIAN_POINT('',(1.234503906781,1.372026781966)); -#40150 = CARTESIAN_POINT('',(1.223747839559,1.372039397384)); -#40151 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); -#40152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40153 = PCURVE('',#38064,#40154); -#40154 = DEFINITIONAL_REPRESENTATION('',(#40155),#40181); -#40155 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40156,#40157,#40158,#40159, - #40160,#40161,#40162,#40163,#40164,#40165,#40166,#40167,#40168, - #40169,#40170,#40171,#40172,#40173,#40174,#40175,#40176,#40177, - #40178,#40179,#40180),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42519 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); +#42520 = CARTESIAN_POINT('',(1.56549792408,1.362507702381)); +#42521 = CARTESIAN_POINT('',(1.554896995806,1.363102719431)); +#42522 = CARTESIAN_POINT('',(1.538983437791,1.363952025988)); +#42523 = CARTESIAN_POINT('',(1.523057917113,1.36475818146)); +#42524 = CARTESIAN_POINT('',(1.507120636663,1.365521253783)); +#42525 = CARTESIAN_POINT('',(1.491171793493,1.36624131089)); +#42526 = CARTESIAN_POINT('',(1.475211574561,1.366918420715)); +#42527 = CARTESIAN_POINT('',(1.459240152088,1.367552651195)); +#42528 = CARTESIAN_POINT('',(1.443257679003,1.368144070262)); +#42529 = CARTESIAN_POINT('',(1.427264284498,1.368692745853)); +#42530 = CARTESIAN_POINT('',(1.411260069235,1.3691987459)); +#42531 = CARTESIAN_POINT('',(1.395245101983,1.369662138339)); +#42532 = CARTESIAN_POINT('',(1.379219411097,1.370082991104)); +#42533 = CARTESIAN_POINT('',(1.363182990948,1.370461730869)); +#42534 = CARTESIAN_POINT('',(1.347135841657,1.37079878431)); +#42535 = CARTESIAN_POINT('',(1.331077960761,1.371094578101)); +#42536 = CARTESIAN_POINT('',(1.31500934008,1.371349538916)); +#42537 = CARTESIAN_POINT('',(1.298929961228,1.37156409343)); +#42538 = CARTESIAN_POINT('',(1.282839791397,1.371738668317)); +#42539 = CARTESIAN_POINT('',(1.26673877946,1.371873690253)); +#42540 = CARTESIAN_POINT('',(1.250626850657,1.371969585911)); +#42541 = CARTESIAN_POINT('',(1.234503906781,1.372026781966)); +#42542 = CARTESIAN_POINT('',(1.223747839559,1.372039397384)); +#42543 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); +#42544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42545 = PCURVE('',#40456,#42546); +#42546 = DEFINITIONAL_REPRESENTATION('',(#42547),#42573); +#42547 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42548,#42549,#42550,#42551, + #42552,#42553,#42554,#42555,#42556,#42557,#42558,#42559,#42560, + #42561,#42562,#42563,#42564,#42565,#42566,#42567,#42568,#42569, + #42570,#42571,#42572),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50360,155 +53349,155 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40156 = CARTESIAN_POINT('',(6.093775905533,3.31)); -#40157 = CARTESIAN_POINT('',(6.096718570121,3.31)); -#40158 = CARTESIAN_POINT('',(6.102601172495,3.309974656011)); -#40159 = CARTESIAN_POINT('',(6.111415323724,3.309860558315)); -#40160 = CARTESIAN_POINT('',(6.120218155906,3.309670329167)); -#40161 = CARTESIAN_POINT('',(6.129008084074,3.309403918821)); -#40162 = CARTESIAN_POINT('',(6.13778351315,3.309061277537)); -#40163 = CARTESIAN_POINT('',(6.146542837619,3.308642355571)); -#40164 = CARTESIAN_POINT('',(6.155284443453,3.30814710318)); -#40165 = CARTESIAN_POINT('',(6.164006709447,3.307575470623)); -#40166 = CARTESIAN_POINT('',(6.172708008643,3.306927408155)); -#40167 = CARTESIAN_POINT('',(6.181386709876,3.306202866034)); -#40168 = CARTESIAN_POINT('',(6.190041178667,3.305401794519)); -#40169 = CARTESIAN_POINT('',(6.198669780474,3.304524143865)); -#40170 = CARTESIAN_POINT('',(6.207271010483,3.303570086065)); -#40171 = CARTESIAN_POINT('',(6.215843341388,3.30253979311)); -#40172 = CARTESIAN_POINT('',(6.224385226653,3.301433436993)); -#40173 = CARTESIAN_POINT('',(6.232895101381,3.300251189704)); -#40174 = CARTESIAN_POINT('',(6.241371383812,3.298993223237)); -#40175 = CARTESIAN_POINT('',(6.249812476611,3.297659709582)); -#40176 = CARTESIAN_POINT('',(6.258216768288,3.296250820731)); -#40177 = CARTESIAN_POINT('',(6.266582634174,3.294766728677)); -#40178 = CARTESIAN_POINT('',(6.274908438895,3.29320760541)); -#40179 = CARTESIAN_POINT('',(6.280431168395,3.292118283752)); -#40180 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); -#40181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40182 = ORIENTED_EDGE('',*,*,#40183,.T.); -#40183 = EDGE_CURVE('',#40115,#39840,#40184,.T.); -#40184 = SURFACE_CURVE('',#40185,(#40190,#40196),.PCURVE_S1.); -#40185 = CIRCLE('',#40186,0.3); -#40186 = AXIS2_PLACEMENT_3D('',#40187,#40188,#40189); -#40187 = CARTESIAN_POINT('',(3.75,-0.175,0.66)); -#40188 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#40189 = DIRECTION('',(0.E+000,0.345177968644,0.938537250173)); -#40190 = PCURVE('',#39825,#40191); -#40191 = DEFINITIONAL_REPRESENTATION('',(#40192),#40195); -#40192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40193,#40194),.UNSPECIFIED., +#42548 = CARTESIAN_POINT('',(6.093775905533,3.31)); +#42549 = CARTESIAN_POINT('',(6.096718570121,3.31)); +#42550 = CARTESIAN_POINT('',(6.102601172495,3.309974656011)); +#42551 = CARTESIAN_POINT('',(6.111415323724,3.309860558315)); +#42552 = CARTESIAN_POINT('',(6.120218155906,3.309670329167)); +#42553 = CARTESIAN_POINT('',(6.129008084074,3.309403918821)); +#42554 = CARTESIAN_POINT('',(6.13778351315,3.309061277537)); +#42555 = CARTESIAN_POINT('',(6.146542837619,3.308642355571)); +#42556 = CARTESIAN_POINT('',(6.155284443453,3.30814710318)); +#42557 = CARTESIAN_POINT('',(6.164006709447,3.307575470623)); +#42558 = CARTESIAN_POINT('',(6.172708008643,3.306927408155)); +#42559 = CARTESIAN_POINT('',(6.181386709876,3.306202866034)); +#42560 = CARTESIAN_POINT('',(6.190041178667,3.305401794519)); +#42561 = CARTESIAN_POINT('',(6.198669780474,3.304524143865)); +#42562 = CARTESIAN_POINT('',(6.207271010483,3.303570086065)); +#42563 = CARTESIAN_POINT('',(6.215843341388,3.30253979311)); +#42564 = CARTESIAN_POINT('',(6.224385226653,3.301433436993)); +#42565 = CARTESIAN_POINT('',(6.232895101381,3.300251189704)); +#42566 = CARTESIAN_POINT('',(6.241371383812,3.298993223237)); +#42567 = CARTESIAN_POINT('',(6.249812476611,3.297659709582)); +#42568 = CARTESIAN_POINT('',(6.258216768288,3.296250820731)); +#42569 = CARTESIAN_POINT('',(6.266582634174,3.294766728677)); +#42570 = CARTESIAN_POINT('',(6.274908438895,3.29320760541)); +#42571 = CARTESIAN_POINT('',(6.280431168395,3.292118283752)); +#42572 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); +#42573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42574 = ORIENTED_EDGE('',*,*,#42575,.T.); +#42575 = EDGE_CURVE('',#42507,#42232,#42576,.T.); +#42576 = SURFACE_CURVE('',#42577,(#42582,#42588),.PCURVE_S1.); +#42577 = CIRCLE('',#42578,0.3); +#42578 = AXIS2_PLACEMENT_3D('',#42579,#42580,#42581); +#42579 = CARTESIAN_POINT('',(3.75,-0.175,0.66)); +#42580 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42581 = DIRECTION('',(0.E+000,0.345177968644,0.938537250173)); +#42582 = PCURVE('',#42217,#42583); +#42583 = DEFINITIONAL_REPRESENTATION('',(#42584),#42587); +#42584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42585,#42586),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#40193 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); -#40194 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); -#40195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#42585 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); +#42586 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); +#42587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#40196 = PCURVE('',#38035,#40197); -#40197 = DEFINITIONAL_REPRESENTATION('',(#40198),#40206); -#40198 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40199,#40200,#40201,#40202 - ,#40203,#40204,#40205),.UNSPECIFIED.,.F.,.F.) +#42588 = PCURVE('',#40427,#42589); +#42589 = DEFINITIONAL_REPRESENTATION('',(#42590),#42598); +#42590 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42591,#42592,#42593,#42594 + ,#42595,#42596,#42597),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#40199 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); -#40200 = CARTESIAN_POINT('',(0.487678260629,3.112201441248)); -#40201 = CARTESIAN_POINT('',(8.850904442449E-002,2.779539545572)); -#40202 = CARTESIAN_POINT('',(-0.31066017178,2.446877649896)); -#40203 = CARTESIAN_POINT('',(-0.399169216204,2.958899279376)); -#40204 = CARTESIAN_POINT('',(-0.487678260629,3.470920908856)); -#40205 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); -#40206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40207 = ADVANCED_FACE('',(#40208),#38296,.F.); -#40208 = FACE_BOUND('',#40209,.F.); -#40209 = EDGE_LOOP('',(#40210,#40233,#40234,#40235,#40236)); -#40210 = ORIENTED_EDGE('',*,*,#40211,.T.); -#40211 = EDGE_CURVE('',#40212,#40019,#40214,.T.); -#40212 = VERTEX_POINT('',#40213); -#40213 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); -#40214 = SURFACE_CURVE('',#40215,(#40220,#40226),.PCURVE_S1.); -#40215 = CIRCLE('',#40216,0.25); -#40216 = AXIS2_PLACEMENT_3D('',#40217,#40218,#40219); -#40217 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,0.96)); -#40218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40219 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); -#40220 = PCURVE('',#38296,#40221); -#40221 = DEFINITIONAL_REPRESENTATION('',(#40222),#40225); -#40222 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40223,#40224),.UNSPECIFIED., +#42591 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); +#42592 = CARTESIAN_POINT('',(0.487678260629,3.112201441248)); +#42593 = CARTESIAN_POINT('',(8.850904442449E-002,2.779539545572)); +#42594 = CARTESIAN_POINT('',(-0.31066017178,2.446877649896)); +#42595 = CARTESIAN_POINT('',(-0.399169216204,2.958899279376)); +#42596 = CARTESIAN_POINT('',(-0.487678260629,3.470920908856)); +#42597 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); +#42598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42599 = ADVANCED_FACE('',(#42600),#40688,.F.); +#42600 = FACE_BOUND('',#42601,.F.); +#42601 = EDGE_LOOP('',(#42602,#42625,#42626,#42627,#42628)); +#42602 = ORIENTED_EDGE('',*,*,#42603,.T.); +#42603 = EDGE_CURVE('',#42604,#42411,#42606,.T.); +#42604 = VERTEX_POINT('',#42605); +#42605 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); +#42606 = SURFACE_CURVE('',#42607,(#42612,#42618),.PCURVE_S1.); +#42607 = CIRCLE('',#42608,0.25); +#42608 = AXIS2_PLACEMENT_3D('',#42609,#42610,#42611); +#42609 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,0.96)); +#42610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42611 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); +#42612 = PCURVE('',#40688,#42613); +#42613 = DEFINITIONAL_REPRESENTATION('',(#42614),#42617); +#42614 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42615,#42616),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.358319577005),.PIECEWISE_BEZIER_KNOTS.); -#40223 = CARTESIAN_POINT('',(5.497787143782,3.31)); -#40224 = CARTESIAN_POINT('',(5.856106720787,3.31)); -#40225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40226 = PCURVE('',#40102,#40227); -#40227 = DEFINITIONAL_REPRESENTATION('',(#40228),#40232); -#40228 = CIRCLE('',#40229,0.25); -#40229 = AXIS2_PLACEMENT_2D('',#40230,#40231); -#40230 = CARTESIAN_POINT('',(0.55,-1.153553390593)); -#40231 = DIRECTION('',(-0.707106781186,0.707106781187)); -#40232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40233 = ORIENTED_EDGE('',*,*,#40018,.F.); -#40234 = ORIENTED_EDGE('',*,*,#39784,.T.); -#40235 = ORIENTED_EDGE('',*,*,#38275,.T.); -#40236 = ORIENTED_EDGE('',*,*,#40237,.F.); -#40237 = EDGE_CURVE('',#40212,#38248,#40238,.T.); -#40238 = SURFACE_CURVE('',#40239,(#40243,#40249),.PCURVE_S1.); -#40239 = LINE('',#40240,#40241); -#40240 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); -#40241 = VECTOR('',#40242,1.); -#40242 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40243 = PCURVE('',#38296,#40244); -#40244 = DEFINITIONAL_REPRESENTATION('',(#40245),#40248); -#40245 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40246,#40247),.UNSPECIFIED., +#42615 = CARTESIAN_POINT('',(5.497787143782,3.31)); +#42616 = CARTESIAN_POINT('',(5.856106720787,3.31)); +#42617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42618 = PCURVE('',#42494,#42619); +#42619 = DEFINITIONAL_REPRESENTATION('',(#42620),#42624); +#42620 = CIRCLE('',#42621,0.25); +#42621 = AXIS2_PLACEMENT_2D('',#42622,#42623); +#42622 = CARTESIAN_POINT('',(0.55,-1.153553390593)); +#42623 = DIRECTION('',(-0.707106781186,0.707106781187)); +#42624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42625 = ORIENTED_EDGE('',*,*,#42410,.F.); +#42626 = ORIENTED_EDGE('',*,*,#42176,.T.); +#42627 = ORIENTED_EDGE('',*,*,#40667,.T.); +#42628 = ORIENTED_EDGE('',*,*,#42629,.F.); +#42629 = EDGE_CURVE('',#42604,#40640,#42630,.T.); +#42630 = SURFACE_CURVE('',#42631,(#42635,#42641),.PCURVE_S1.); +#42631 = LINE('',#42632,#42633); +#42632 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); +#42633 = VECTOR('',#42634,1.); +#42634 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42635 = PCURVE('',#40688,#42636); +#42636 = DEFINITIONAL_REPRESENTATION('',(#42637),#42640); +#42637 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42638,#42639),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#40246 = CARTESIAN_POINT('',(5.497787143783,3.31)); -#40247 = CARTESIAN_POINT('',(5.497787143783,4.7)); -#40248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40249 = PCURVE('',#38263,#40250); -#40250 = DEFINITIONAL_REPRESENTATION('',(#40251),#40255); -#40251 = LINE('',#40252,#40253); -#40252 = CARTESIAN_POINT('',(0.E+000,3.31)); -#40253 = VECTOR('',#40254,1.); -#40254 = DIRECTION('',(0.E+000,1.)); -#40255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40256 = ADVANCED_FACE('',(#40257),#39720,.F.); -#40257 = FACE_BOUND('',#40258,.F.); -#40258 = EDGE_LOOP('',(#40259,#40260,#40329,#40361,#40411)); -#40259 = ORIENTED_EDGE('',*,*,#39704,.T.); -#40260 = ORIENTED_EDGE('',*,*,#40261,.F.); -#40261 = EDGE_CURVE('',#40262,#39673,#40264,.T.); -#40262 = VERTEX_POINT('',#40263); -#40263 = CARTESIAN_POINT('',(3.427544930281,-0.175,-0.56)); -#40264 = SURFACE_CURVE('',#40265,(#40271,#40300),.PCURVE_S1.); -#40265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40266,#40267,#40268,#40269, - #40270),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#42638 = CARTESIAN_POINT('',(5.497787143783,3.31)); +#42639 = CARTESIAN_POINT('',(5.497787143783,4.7)); +#42640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42641 = PCURVE('',#40655,#42642); +#42642 = DEFINITIONAL_REPRESENTATION('',(#42643),#42647); +#42643 = LINE('',#42644,#42645); +#42644 = CARTESIAN_POINT('',(0.E+000,3.31)); +#42645 = VECTOR('',#42646,1.); +#42646 = DIRECTION('',(0.E+000,1.)); +#42647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42648 = ADVANCED_FACE('',(#42649),#42112,.F.); +#42649 = FACE_BOUND('',#42650,.F.); +#42650 = EDGE_LOOP('',(#42651,#42652,#42721,#42753,#42803)); +#42651 = ORIENTED_EDGE('',*,*,#42096,.T.); +#42652 = ORIENTED_EDGE('',*,*,#42653,.F.); +#42653 = EDGE_CURVE('',#42654,#42065,#42656,.T.); +#42654 = VERTEX_POINT('',#42655); +#42655 = CARTESIAN_POINT('',(3.427544930281,-0.175,-0.56)); +#42656 = SURFACE_CURVE('',#42657,(#42663,#42692),.PCURVE_S1.); +#42657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42658,#42659,#42660,#42661, + #42662),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#40266 = CARTESIAN_POINT('',(3.427544930281,-0.175,-0.56)); -#40267 = CARTESIAN_POINT('',(3.435044416718,-0.158520866785,-0.56)); -#40268 = CARTESIAN_POINT('',(3.44626655149,-0.12439411896, +#42658 = CARTESIAN_POINT('',(3.427544930281,-0.175,-0.56)); +#42659 = CARTESIAN_POINT('',(3.435044416718,-0.158520866785,-0.56)); +#42660 = CARTESIAN_POINT('',(3.44626655149,-0.12439411896, -0.557279371107)); -#40269 = CARTESIAN_POINT('',(3.45,-8.905319331764E-002,-0.548036575861) +#42661 = CARTESIAN_POINT('',(3.45,-8.905319331764E-002,-0.548036575861) ); -#40270 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-0.541561175052) +#42662 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002,-0.541561175052) ); -#40271 = PCURVE('',#39720,#40272); -#40272 = DEFINITIONAL_REPRESENTATION('',(#40273),#40299); -#40273 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40274,#40275,#40276,#40277, - #40278,#40279,#40280,#40281,#40282,#40283,#40284,#40285,#40286, - #40287,#40288,#40289,#40290,#40291,#40292,#40293,#40294,#40295, - #40296,#40297,#40298),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42663 = PCURVE('',#42112,#42664); +#42664 = DEFINITIONAL_REPRESENTATION('',(#42665),#42691); +#42665 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42666,#42667,#42668,#42669, + #42670,#42671,#42672,#42673,#42674,#42675,#42676,#42677,#42678, + #42679,#42680,#42681,#42682,#42683,#42684,#42685,#42686,#42687, + #42688,#42689,#42690),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50516,40 +53505,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40274 = CARTESIAN_POINT('',(5.856106720787,1.79)); -#40275 = CARTESIAN_POINT('',(5.862690482847,1.79)); -#40276 = CARTESIAN_POINT('',(5.875841470998,1.790022484536)); -#40277 = CARTESIAN_POINT('',(5.895521381605,1.790124883104)); -#40278 = CARTESIAN_POINT('',(5.91515778468,1.790297171588)); -#40279 = CARTESIAN_POINT('',(5.934753647009,1.790540568142)); -#40280 = CARTESIAN_POINT('',(5.954311871603,1.790856290921)); -#40281 = CARTESIAN_POINT('',(5.97383528909,1.791245558079)); -#40282 = CARTESIAN_POINT('',(5.993326660755,1.791709587769)); -#40283 = CARTESIAN_POINT('',(6.012788678789,1.792249598145)); -#40284 = CARTESIAN_POINT('',(6.032223967575,1.792866807362)); -#40285 = CARTESIAN_POINT('',(6.051635085044,1.793562433572)); -#40286 = CARTESIAN_POINT('',(6.071024524018,1.794337694931)); -#40287 = CARTESIAN_POINT('',(6.090394714745,1.795193809591)); -#40288 = CARTESIAN_POINT('',(6.10974645165,1.796131784894)); -#40289 = CARTESIAN_POINT('',(6.12908046424,1.797152628178)); -#40290 = CARTESIAN_POINT('',(6.14839742625,1.798257346784)); -#40291 = CARTESIAN_POINT('',(6.167697963593,1.799446948053)); -#40292 = CARTESIAN_POINT('',(6.186982662767,1.800722439323)); -#40293 = CARTESIAN_POINT('',(6.206252079266,1.802084827936)); -#40294 = CARTESIAN_POINT('',(6.225506745991,1.80353512123)); -#40295 = CARTESIAN_POINT('',(6.244747182119,1.805074326547)); -#40296 = CARTESIAN_POINT('',(6.263973900431,1.806703451226)); -#40297 = CARTESIAN_POINT('',(6.27678291387,1.807850152147)); -#40298 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); -#40299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40300 = PCURVE('',#39693,#40301); -#40301 = DEFINITIONAL_REPRESENTATION('',(#40302),#40328); -#40302 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40303,#40304,#40305,#40306, - #40307,#40308,#40309,#40310,#40311,#40312,#40313,#40314,#40315, - #40316,#40317,#40318,#40319,#40320,#40321,#40322,#40323,#40324, - #40325,#40326,#40327),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42666 = CARTESIAN_POINT('',(5.856106720787,1.79)); +#42667 = CARTESIAN_POINT('',(5.862690482847,1.79)); +#42668 = CARTESIAN_POINT('',(5.875841470998,1.790022484536)); +#42669 = CARTESIAN_POINT('',(5.895521381605,1.790124883104)); +#42670 = CARTESIAN_POINT('',(5.91515778468,1.790297171588)); +#42671 = CARTESIAN_POINT('',(5.934753647009,1.790540568142)); +#42672 = CARTESIAN_POINT('',(5.954311871603,1.790856290921)); +#42673 = CARTESIAN_POINT('',(5.97383528909,1.791245558079)); +#42674 = CARTESIAN_POINT('',(5.993326660755,1.791709587769)); +#42675 = CARTESIAN_POINT('',(6.012788678789,1.792249598145)); +#42676 = CARTESIAN_POINT('',(6.032223967575,1.792866807362)); +#42677 = CARTESIAN_POINT('',(6.051635085044,1.793562433572)); +#42678 = CARTESIAN_POINT('',(6.071024524018,1.794337694931)); +#42679 = CARTESIAN_POINT('',(6.090394714745,1.795193809591)); +#42680 = CARTESIAN_POINT('',(6.10974645165,1.796131784894)); +#42681 = CARTESIAN_POINT('',(6.12908046424,1.797152628178)); +#42682 = CARTESIAN_POINT('',(6.14839742625,1.798257346784)); +#42683 = CARTESIAN_POINT('',(6.167697963593,1.799446948053)); +#42684 = CARTESIAN_POINT('',(6.186982662767,1.800722439323)); +#42685 = CARTESIAN_POINT('',(6.206252079266,1.802084827936)); +#42686 = CARTESIAN_POINT('',(6.225506745991,1.80353512123)); +#42687 = CARTESIAN_POINT('',(6.244747182119,1.805074326547)); +#42688 = CARTESIAN_POINT('',(6.263973900431,1.806703451226)); +#42689 = CARTESIAN_POINT('',(6.27678291387,1.807850152147)); +#42690 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); +#42691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42692 = PCURVE('',#42085,#42693); +#42693 = DEFINITIONAL_REPRESENTATION('',(#42694),#42720); +#42694 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42695,#42696,#42697,#42698, + #42699,#42700,#42701,#42702,#42703,#42704,#42705,#42706,#42707, + #42708,#42709,#42710,#42711,#42712,#42713,#42714,#42715,#42716, + #42717,#42718,#42719),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -50557,93 +53546,93 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40303 = CARTESIAN_POINT('',(1.570796326795,0.337372798399)); -#40304 = CARTESIAN_POINT('',(1.565802640143,0.336691026905)); -#40305 = CARTESIAN_POINT('',(1.555783114816,0.335358697454)); -#40306 = CARTESIAN_POINT('',(1.540658019782,0.333453770651)); -#40307 = CARTESIAN_POINT('',(1.525437814476,0.331642337978)); -#40308 = CARTESIAN_POINT('',(1.510123028574,0.329924326193)); -#40309 = CARTESIAN_POINT('',(1.494714076604,0.328299662055)); -#40310 = CARTESIAN_POINT('',(1.479211238582,0.326768272322)); -#40311 = CARTESIAN_POINT('',(1.463614659934,0.325330083752)); -#40312 = CARTESIAN_POINT('',(1.447924346451,0.323985023103)); -#40313 = CARTESIAN_POINT('',(1.432140160865,0.322733017133)); -#40314 = CARTESIAN_POINT('',(1.416261819029,0.3215739926)); -#40315 = CARTESIAN_POINT('',(1.400288887279,0.320507876263)); -#40316 = CARTESIAN_POINT('',(1.384220776834,0.31953459488)); -#40317 = CARTESIAN_POINT('',(1.368058161245,0.318654123894)); -#40318 = CARTESIAN_POINT('',(1.351801584595,0.317866438751)); -#40319 = CARTESIAN_POINT('',(1.335451453245,0.317171514893)); -#40320 = CARTESIAN_POINT('',(1.319008031025,0.316569327766)); -#40321 = CARTESIAN_POINT('',(1.302471433862,0.316059852813)); -#40322 = CARTESIAN_POINT('',(1.285841624321,0.315643065478)); -#40323 = CARTESIAN_POINT('',(1.269118408315,0.315318941206)); -#40324 = CARTESIAN_POINT('',(1.252301424599,0.315087455441)); -#40325 = CARTESIAN_POINT('',(1.235390162465,0.314948583626)); -#40326 = CARTESIAN_POINT('',(1.224052637841,0.31491772868)); -#40327 = CARTESIAN_POINT('',(1.218367924887,0.31491772868)); -#40328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40329 = ORIENTED_EDGE('',*,*,#40330,.F.); -#40330 = EDGE_CURVE('',#40331,#40262,#40333,.T.); -#40331 = VERTEX_POINT('',#40332); -#40332 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-0.56)); -#40333 = SURFACE_CURVE('',#40334,(#40339,#40345),.PCURVE_S1.); -#40334 = CIRCLE('',#40335,0.25); -#40335 = AXIS2_PLACEMENT_3D('',#40336,#40337,#40338); -#40336 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-0.56)); -#40337 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40338 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); -#40339 = PCURVE('',#39720,#40340); -#40340 = DEFINITIONAL_REPRESENTATION('',(#40341),#40344); -#40341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40342,#40343),.UNSPECIFIED., +#42695 = CARTESIAN_POINT('',(1.570796326795,0.337372798399)); +#42696 = CARTESIAN_POINT('',(1.565802640143,0.336691026905)); +#42697 = CARTESIAN_POINT('',(1.555783114816,0.335358697454)); +#42698 = CARTESIAN_POINT('',(1.540658019782,0.333453770651)); +#42699 = CARTESIAN_POINT('',(1.525437814476,0.331642337978)); +#42700 = CARTESIAN_POINT('',(1.510123028574,0.329924326193)); +#42701 = CARTESIAN_POINT('',(1.494714076604,0.328299662055)); +#42702 = CARTESIAN_POINT('',(1.479211238582,0.326768272322)); +#42703 = CARTESIAN_POINT('',(1.463614659934,0.325330083752)); +#42704 = CARTESIAN_POINT('',(1.447924346451,0.323985023103)); +#42705 = CARTESIAN_POINT('',(1.432140160865,0.322733017133)); +#42706 = CARTESIAN_POINT('',(1.416261819029,0.3215739926)); +#42707 = CARTESIAN_POINT('',(1.400288887279,0.320507876263)); +#42708 = CARTESIAN_POINT('',(1.384220776834,0.31953459488)); +#42709 = CARTESIAN_POINT('',(1.368058161245,0.318654123894)); +#42710 = CARTESIAN_POINT('',(1.351801584595,0.317866438751)); +#42711 = CARTESIAN_POINT('',(1.335451453245,0.317171514893)); +#42712 = CARTESIAN_POINT('',(1.319008031025,0.316569327766)); +#42713 = CARTESIAN_POINT('',(1.302471433862,0.316059852813)); +#42714 = CARTESIAN_POINT('',(1.285841624321,0.315643065478)); +#42715 = CARTESIAN_POINT('',(1.269118408315,0.315318941206)); +#42716 = CARTESIAN_POINT('',(1.252301424599,0.315087455441)); +#42717 = CARTESIAN_POINT('',(1.235390162465,0.314948583626)); +#42718 = CARTESIAN_POINT('',(1.224052637841,0.31491772868)); +#42719 = CARTESIAN_POINT('',(1.218367924887,0.31491772868)); +#42720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42721 = ORIENTED_EDGE('',*,*,#42722,.F.); +#42722 = EDGE_CURVE('',#42723,#42654,#42725,.T.); +#42723 = VERTEX_POINT('',#42724); +#42724 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-0.56)); +#42725 = SURFACE_CURVE('',#42726,(#42731,#42737),.PCURVE_S1.); +#42726 = CIRCLE('',#42727,0.25); +#42727 = AXIS2_PLACEMENT_3D('',#42728,#42729,#42730); +#42728 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-0.56)); +#42729 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42730 = DIRECTION('',(0.707106781186,-0.707106781187,0.E+000)); +#42731 = PCURVE('',#42112,#42732); +#42732 = DEFINITIONAL_REPRESENTATION('',(#42733),#42736); +#42733 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42734,#42735),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.358319577005),.PIECEWISE_BEZIER_KNOTS.); -#40342 = CARTESIAN_POINT('',(5.497787143782,1.79)); -#40343 = CARTESIAN_POINT('',(5.856106720787,1.79)); -#40344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40345 = PCURVE('',#40346,#40351); -#40346 = PLANE('',#40347); -#40347 = AXIS2_PLACEMENT_3D('',#40348,#40349,#40350); -#40348 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); -#40349 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#40350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40351 = DEFINITIONAL_REPRESENTATION('',(#40352),#40360); -#40352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40353,#40354,#40355,#40356 - ,#40357,#40358,#40359),.UNSPECIFIED.,.F.,.F.) +#42734 = CARTESIAN_POINT('',(5.497787143782,1.79)); +#42735 = CARTESIAN_POINT('',(5.856106720787,1.79)); +#42736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42737 = PCURVE('',#42738,#42743); +#42738 = PLANE('',#42739); +#42739 = AXIS2_PLACEMENT_3D('',#42740,#42741,#42742); +#42740 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); +#42741 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#42742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42743 = DEFINITIONAL_REPRESENTATION('',(#42744),#42752); +#42744 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42745,#42746,#42747,#42748 + ,#42749,#42750,#42751),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#40353 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); -#40354 = CARTESIAN_POINT('',(1.282962913145,-1.282962913144)); -#40355 = CARTESIAN_POINT('',(0.864704761276,-1.395034847166)); -#40356 = CARTESIAN_POINT('',(0.446446609407,-1.507106781187)); -#40357 = CARTESIAN_POINT('',(0.558518543428,-1.088848629318)); -#40358 = CARTESIAN_POINT('',(0.670590477449,-0.670590477449)); -#40359 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); -#40360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40361 = ORIENTED_EDGE('',*,*,#40362,.F.); -#40362 = EDGE_CURVE('',#40363,#40331,#40365,.T.); -#40363 = VERTEX_POINT('',#40364); -#40364 = CARTESIAN_POINT('',(3.37629959392,-0.248699121896,-2.35)); -#40365 = SURFACE_CURVE('',#40366,(#40370,#40399),.PCURVE_S1.); -#40366 = LINE('',#40367,#40368); -#40367 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042,-2.35)); -#40368 = VECTOR('',#40369,1.); -#40369 = DIRECTION('',(8.872644532969E-005,8.872644532989E-005, +#42745 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); +#42746 = CARTESIAN_POINT('',(1.282962913145,-1.282962913144)); +#42747 = CARTESIAN_POINT('',(0.864704761276,-1.395034847166)); +#42748 = CARTESIAN_POINT('',(0.446446609407,-1.507106781187)); +#42749 = CARTESIAN_POINT('',(0.558518543428,-1.088848629318)); +#42750 = CARTESIAN_POINT('',(0.670590477449,-0.670590477449)); +#42751 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); +#42752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42753 = ORIENTED_EDGE('',*,*,#42754,.F.); +#42754 = EDGE_CURVE('',#42755,#42723,#42757,.T.); +#42755 = VERTEX_POINT('',#42756); +#42756 = CARTESIAN_POINT('',(3.37629959392,-0.248699121896,-2.35)); +#42757 = SURFACE_CURVE('',#42758,(#42762,#42791),.PCURVE_S1.); +#42758 = LINE('',#42759,#42760); +#42759 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042,-2.35)); +#42760 = VECTOR('',#42761,1.); +#42761 = DIRECTION('',(8.872644532969E-005,8.872644532989E-005, 0.999999992128)); -#40370 = PCURVE('',#39720,#40371); -#40371 = DEFINITIONAL_REPRESENTATION('',(#40372),#40398); -#40372 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40373,#40374,#40375,#40376, - #40377,#40378,#40379,#40380,#40381,#40382,#40383,#40384,#40385, - #40386,#40387,#40388,#40389,#40390,#40391,#40392,#40393,#40394, - #40395,#40396,#40397),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#42762 = PCURVE('',#42112,#42763); +#42763 = DEFINITIONAL_REPRESENTATION('',(#42764),#42790); +#42764 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#42765,#42766,#42767,#42768, + #42769,#42770,#42771,#42772,#42773,#42774,#42775,#42776,#42777, + #42778,#42779,#42780,#42781,#42782,#42783,#42784,#42785,#42786, + #42787,#42788,#42789),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-5.636594915377E-008,8.13635832003E-002, 0.162727222767,0.244090862333,0.325454501899,0.406818141465, 0.488181781032,0.569545420598,0.650909060164,0.73227269973, @@ -50651,396 +53640,396 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.139090897562,1.220454537128,1.301818176694,1.38318181626, 1.464545455827,1.545909095393,1.627272734959,1.708636374525, 1.790000014092),.UNSPECIFIED.); -#40373 = CARTESIAN_POINT('',(5.496888720489,-5.636594879732E-008)); -#40374 = CARTESIAN_POINT('',(5.496902332955,2.712115660929E-002)); -#40375 = CARTESIAN_POINT('',(5.49692955789,8.136358255978E-002)); -#40376 = CARTESIAN_POINT('',(5.496970395295,0.162727221486)); -#40377 = CARTESIAN_POINT('',(5.497011232702,0.244090860411)); -#40378 = CARTESIAN_POINT('',(5.497052070112,0.325454499337)); -#40379 = CARTESIAN_POINT('',(5.497092907525,0.406818138263)); -#40380 = CARTESIAN_POINT('',(5.49713374494,0.488181777188)); -#40381 = CARTESIAN_POINT('',(5.497174582357,0.569545416114)); -#40382 = CARTESIAN_POINT('',(5.497215419776,0.65090905504)); -#40383 = CARTESIAN_POINT('',(5.497256257197,0.732272693966)); -#40384 = CARTESIAN_POINT('',(5.49729709462,0.813636332891)); -#40385 = CARTESIAN_POINT('',(5.497337932044,0.894999971817)); -#40386 = CARTESIAN_POINT('',(5.49737876947,0.976363610743)); -#40387 = CARTESIAN_POINT('',(5.497419606897,1.057727249668)); -#40388 = CARTESIAN_POINT('',(5.497460444326,1.139090888594)); -#40389 = CARTESIAN_POINT('',(5.497501281755,1.22045452752)); -#40390 = CARTESIAN_POINT('',(5.497542119186,1.301818166446)); -#40391 = CARTESIAN_POINT('',(5.497582956617,1.383181805371)); -#40392 = CARTESIAN_POINT('',(5.497623794049,1.464545444297)); -#40393 = CARTESIAN_POINT('',(5.497664631482,1.545909083223)); -#40394 = CARTESIAN_POINT('',(5.497705468915,1.627272722149)); -#40395 = CARTESIAN_POINT('',(5.497746306348,1.708636361074)); -#40396 = CARTESIAN_POINT('',(5.497773531304,1.762878787025)); -#40397 = CARTESIAN_POINT('',(5.497787143781,1.79)); -#40398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40399 = PCURVE('',#40400,#40405); -#40400 = PLANE('',#40401); -#40401 = AXIS2_PLACEMENT_3D('',#40402,#40403,#40404); -#40402 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-2.35)); -#40403 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#40404 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#40405 = DEFINITIONAL_REPRESENTATION('',(#40406),#40410); -#40406 = LINE('',#40407,#40408); -#40407 = CARTESIAN_POINT('',(2.246058769703E-004,0.E+000)); -#40408 = VECTOR('',#40409,1.); -#40409 = DIRECTION('',(-1.254781423265E-004,0.999999992128)); -#40410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40411 = ORIENTED_EDGE('',*,*,#40412,.F.); -#40412 = EDGE_CURVE('',#39705,#40363,#40413,.T.); -#40413 = SURFACE_CURVE('',#40414,(#40419,#40425),.PCURVE_S1.); -#40414 = CIRCLE('',#40415,0.25); -#40415 = AXIS2_PLACEMENT_3D('',#40416,#40417,#40418); -#40416 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#40417 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#40418 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40419 = PCURVE('',#39720,#40420); -#40420 = DEFINITIONAL_REPRESENTATION('',(#40421),#40424); -#40421 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40422,#40423),.UNSPECIFIED., +#42765 = CARTESIAN_POINT('',(5.496888720489,-5.636594879732E-008)); +#42766 = CARTESIAN_POINT('',(5.496902332955,2.712115660929E-002)); +#42767 = CARTESIAN_POINT('',(5.49692955789,8.136358255978E-002)); +#42768 = CARTESIAN_POINT('',(5.496970395295,0.162727221486)); +#42769 = CARTESIAN_POINT('',(5.497011232702,0.244090860411)); +#42770 = CARTESIAN_POINT('',(5.497052070112,0.325454499337)); +#42771 = CARTESIAN_POINT('',(5.497092907525,0.406818138263)); +#42772 = CARTESIAN_POINT('',(5.49713374494,0.488181777188)); +#42773 = CARTESIAN_POINT('',(5.497174582357,0.569545416114)); +#42774 = CARTESIAN_POINT('',(5.497215419776,0.65090905504)); +#42775 = CARTESIAN_POINT('',(5.497256257197,0.732272693966)); +#42776 = CARTESIAN_POINT('',(5.49729709462,0.813636332891)); +#42777 = CARTESIAN_POINT('',(5.497337932044,0.894999971817)); +#42778 = CARTESIAN_POINT('',(5.49737876947,0.976363610743)); +#42779 = CARTESIAN_POINT('',(5.497419606897,1.057727249668)); +#42780 = CARTESIAN_POINT('',(5.497460444326,1.139090888594)); +#42781 = CARTESIAN_POINT('',(5.497501281755,1.22045452752)); +#42782 = CARTESIAN_POINT('',(5.497542119186,1.301818166446)); +#42783 = CARTESIAN_POINT('',(5.497582956617,1.383181805371)); +#42784 = CARTESIAN_POINT('',(5.497623794049,1.464545444297)); +#42785 = CARTESIAN_POINT('',(5.497664631482,1.545909083223)); +#42786 = CARTESIAN_POINT('',(5.497705468915,1.627272722149)); +#42787 = CARTESIAN_POINT('',(5.497746306348,1.708636361074)); +#42788 = CARTESIAN_POINT('',(5.497773531304,1.762878787025)); +#42789 = CARTESIAN_POINT('',(5.497787143781,1.79)); +#42790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42791 = PCURVE('',#42792,#42797); +#42792 = PLANE('',#42793); +#42793 = AXIS2_PLACEMENT_3D('',#42794,#42795,#42796); +#42794 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-2.35)); +#42795 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#42796 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#42797 = DEFINITIONAL_REPRESENTATION('',(#42798),#42802); +#42798 = LINE('',#42799,#42800); +#42799 = CARTESIAN_POINT('',(2.246058769703E-004,0.E+000)); +#42800 = VECTOR('',#42801,1.); +#42801 = DIRECTION('',(-1.254781423265E-004,0.999999992128)); +#42802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42803 = ORIENTED_EDGE('',*,*,#42804,.F.); +#42804 = EDGE_CURVE('',#42097,#42755,#42805,.T.); +#42805 = SURFACE_CURVE('',#42806,(#42811,#42817),.PCURVE_S1.); +#42806 = CIRCLE('',#42807,0.25); +#42807 = AXIS2_PLACEMENT_3D('',#42808,#42809,#42810); +#42808 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#42809 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#42810 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42811 = PCURVE('',#42112,#42812); +#42812 = DEFINITIONAL_REPRESENTATION('',(#42813),#42816); +#42813 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42814,#42815),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.788093427389),.PIECEWISE_BEZIER_KNOTS.); -#40422 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#40423 = CARTESIAN_POINT('',(5.49509187979,0.E+000)); -#40424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#42814 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#42815 = CARTESIAN_POINT('',(5.49509187979,0.E+000)); +#42816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#40425 = PCURVE('',#39747,#40426); -#40426 = DEFINITIONAL_REPRESENTATION('',(#40427),#40435); -#40427 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#40428,#40429,#40430,#40431 - ,#40432,#40433,#40434),.UNSPECIFIED.,.F.,.F.) +#42817 = PCURVE('',#42139,#42818); +#42818 = DEFINITIONAL_REPRESENTATION('',(#42819),#42827); +#42819 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42820,#42821,#42822,#42823 + ,#42824,#42825,#42826),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#40428 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); -#40429 = CARTESIAN_POINT('',(3.45,-0.504459311299)); -#40430 = CARTESIAN_POINT('',(3.075,-0.287952960353)); -#40431 = CARTESIAN_POINT('',(2.7,-7.144660940673E-002)); -#40432 = CARTESIAN_POINT('',(3.075,0.145059741539)); -#40433 = CARTESIAN_POINT('',(3.45,0.361566092485)); -#40434 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); -#40435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40436 = ADVANCED_FACE('',(#40437),#40102,.F.); -#40437 = FACE_BOUND('',#40438,.F.); -#40438 = EDGE_LOOP('',(#40439,#40440,#40441,#40464,#40487,#40510,#40537, - #40560,#40583,#40606)); -#40439 = ORIENTED_EDGE('',*,*,#40087,.F.); -#40440 = ORIENTED_EDGE('',*,*,#40211,.F.); -#40441 = ORIENTED_EDGE('',*,*,#40442,.T.); -#40442 = EDGE_CURVE('',#40212,#40443,#40445,.T.); -#40443 = VERTEX_POINT('',#40444); -#40444 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,0.96)); -#40445 = SURFACE_CURVE('',#40446,(#40450,#40457),.PCURVE_S1.); -#40446 = LINE('',#40447,#40448); -#40447 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); -#40448 = VECTOR('',#40449,1.); -#40449 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#40450 = PCURVE('',#40102,#40451); -#40451 = DEFINITIONAL_REPRESENTATION('',(#40452),#40456); -#40452 = LINE('',#40453,#40454); -#40453 = CARTESIAN_POINT('',(0.373223304703,-0.976776695297)); -#40454 = VECTOR('',#40455,1.); -#40455 = DIRECTION('',(0.707106781187,0.707106781187)); -#40456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40457 = PCURVE('',#38263,#40458); -#40458 = DEFINITIONAL_REPRESENTATION('',(#40459),#40463); -#40459 = LINE('',#40460,#40461); -#40460 = CARTESIAN_POINT('',(0.E+000,3.31)); -#40461 = VECTOR('',#40462,1.); -#40462 = DIRECTION('',(1.,0.E+000)); -#40463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40464 = ORIENTED_EDGE('',*,*,#40465,.F.); -#40465 = EDGE_CURVE('',#40466,#40443,#40468,.T.); -#40466 = VERTEX_POINT('',#40467); -#40467 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); -#40468 = SURFACE_CURVE('',#40469,(#40474,#40481),.PCURVE_S1.); -#40469 = CIRCLE('',#40470,0.25); -#40470 = AXIS2_PLACEMENT_3D('',#40471,#40472,#40473); -#40471 = CARTESIAN_POINT('',(2.596446609407,-0.675,0.96)); -#40472 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40473 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#40474 = PCURVE('',#40102,#40475); -#40475 = DEFINITIONAL_REPRESENTATION('',(#40476),#40480); -#40476 = CIRCLE('',#40477,0.25); -#40477 = AXIS2_PLACEMENT_2D('',#40478,#40479); -#40478 = CARTESIAN_POINT('',(1.153553390593,-0.55)); -#40479 = DIRECTION('',(0.E+000,1.)); -#40480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40481 = PCURVE('',#38236,#40482); -#40482 = DEFINITIONAL_REPRESENTATION('',(#40483),#40486); -#40483 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40484,#40485),.UNSPECIFIED., +#42820 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); +#42821 = CARTESIAN_POINT('',(3.45,-0.504459311299)); +#42822 = CARTESIAN_POINT('',(3.075,-0.287952960353)); +#42823 = CARTESIAN_POINT('',(2.7,-7.144660940673E-002)); +#42824 = CARTESIAN_POINT('',(3.075,0.145059741539)); +#42825 = CARTESIAN_POINT('',(3.45,0.361566092485)); +#42826 = CARTESIAN_POINT('',(3.45,-7.144660940673E-002)); +#42827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42828 = ADVANCED_FACE('',(#42829),#42494,.F.); +#42829 = FACE_BOUND('',#42830,.F.); +#42830 = EDGE_LOOP('',(#42831,#42832,#42833,#42856,#42879,#42902,#42929, + #42952,#42975,#42998)); +#42831 = ORIENTED_EDGE('',*,*,#42479,.F.); +#42832 = ORIENTED_EDGE('',*,*,#42603,.F.); +#42833 = ORIENTED_EDGE('',*,*,#42834,.T.); +#42834 = EDGE_CURVE('',#42604,#42835,#42837,.T.); +#42835 = VERTEX_POINT('',#42836); +#42836 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,0.96)); +#42837 = SURFACE_CURVE('',#42838,(#42842,#42849),.PCURVE_S1.); +#42838 = LINE('',#42839,#42840); +#42839 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,0.96)); +#42840 = VECTOR('',#42841,1.); +#42841 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#42842 = PCURVE('',#42494,#42843); +#42843 = DEFINITIONAL_REPRESENTATION('',(#42844),#42848); +#42844 = LINE('',#42845,#42846); +#42845 = CARTESIAN_POINT('',(0.373223304703,-0.976776695297)); +#42846 = VECTOR('',#42847,1.); +#42847 = DIRECTION('',(0.707106781187,0.707106781187)); +#42848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42849 = PCURVE('',#40655,#42850); +#42850 = DEFINITIONAL_REPRESENTATION('',(#42851),#42855); +#42851 = LINE('',#42852,#42853); +#42852 = CARTESIAN_POINT('',(0.E+000,3.31)); +#42853 = VECTOR('',#42854,1.); +#42854 = DIRECTION('',(1.,0.E+000)); +#42855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42856 = ORIENTED_EDGE('',*,*,#42857,.F.); +#42857 = EDGE_CURVE('',#42858,#42835,#42860,.T.); +#42858 = VERTEX_POINT('',#42859); +#42859 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); +#42860 = SURFACE_CURVE('',#42861,(#42866,#42873),.PCURVE_S1.); +#42861 = CIRCLE('',#42862,0.25); +#42862 = AXIS2_PLACEMENT_3D('',#42863,#42864,#42865); +#42863 = CARTESIAN_POINT('',(2.596446609407,-0.675,0.96)); +#42864 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42865 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42866 = PCURVE('',#42494,#42867); +#42867 = DEFINITIONAL_REPRESENTATION('',(#42868),#42872); +#42868 = CIRCLE('',#42869,0.25); +#42869 = AXIS2_PLACEMENT_2D('',#42870,#42871); +#42870 = CARTESIAN_POINT('',(1.153553390593,-0.55)); +#42871 = DIRECTION('',(0.E+000,1.)); +#42872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42873 = PCURVE('',#40628,#42874); +#42874 = DEFINITIONAL_REPRESENTATION('',(#42875),#42878); +#42875 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42876,#42877),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#40484 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#40485 = CARTESIAN_POINT('',(5.49778714378,3.31)); -#40486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40487 = ORIENTED_EDGE('',*,*,#40488,.T.); -#40488 = EDGE_CURVE('',#40466,#40489,#40491,.T.); -#40489 = VERTEX_POINT('',#40490); -#40490 = CARTESIAN_POINT('',(2.4,-0.925,0.96)); -#40491 = SURFACE_CURVE('',#40492,(#40496,#40503),.PCURVE_S1.); -#40492 = LINE('',#40493,#40494); -#40493 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); -#40494 = VECTOR('',#40495,1.); -#40495 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#40496 = PCURVE('',#40102,#40497); -#40497 = DEFINITIONAL_REPRESENTATION('',(#40498),#40502); -#40498 = LINE('',#40499,#40500); -#40499 = CARTESIAN_POINT('',(1.153553390593,-0.3)); -#40500 = VECTOR('',#40501,1.); -#40501 = DIRECTION('',(1.,0.E+000)); -#40502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40503 = PCURVE('',#38203,#40504); -#40504 = DEFINITIONAL_REPRESENTATION('',(#40505),#40509); -#40505 = LINE('',#40506,#40507); -#40506 = CARTESIAN_POINT('',(0.E+000,3.31)); -#40507 = VECTOR('',#40508,1.); -#40508 = DIRECTION('',(1.,0.E+000)); -#40509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40510 = ORIENTED_EDGE('',*,*,#40511,.F.); -#40511 = EDGE_CURVE('',#40512,#40489,#40514,.T.); -#40512 = VERTEX_POINT('',#40513); -#40513 = CARTESIAN_POINT('',(2.4,-1.225,0.96)); -#40514 = SURFACE_CURVE('',#40515,(#40519,#40526),.PCURVE_S1.); -#40515 = LINE('',#40516,#40517); -#40516 = CARTESIAN_POINT('',(2.4,-1.225,0.96)); -#40517 = VECTOR('',#40518,1.); -#40518 = DIRECTION('',(0.E+000,1.,0.E+000)); -#40519 = PCURVE('',#40102,#40520); -#40520 = DEFINITIONAL_REPRESENTATION('',(#40521),#40525); -#40521 = LINE('',#40522,#40523); -#40522 = CARTESIAN_POINT('',(1.35,0.E+000)); -#40523 = VECTOR('',#40524,1.); -#40524 = DIRECTION('',(0.E+000,-1.)); -#40525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40526 = PCURVE('',#40527,#40532); -#40527 = CYLINDRICAL_SURFACE('',#40528,0.15); -#40528 = AXIS2_PLACEMENT_3D('',#40529,#40530,#40531); -#40529 = CARTESIAN_POINT('',(2.4,-1.225,0.81)); -#40530 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#40531 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40532 = DEFINITIONAL_REPRESENTATION('',(#40533),#40536); -#40533 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40534,#40535),.UNSPECIFIED., +#42876 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#42877 = CARTESIAN_POINT('',(5.49778714378,3.31)); +#42878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42879 = ORIENTED_EDGE('',*,*,#42880,.T.); +#42880 = EDGE_CURVE('',#42858,#42881,#42883,.T.); +#42881 = VERTEX_POINT('',#42882); +#42882 = CARTESIAN_POINT('',(2.4,-0.925,0.96)); +#42883 = SURFACE_CURVE('',#42884,(#42888,#42895),.PCURVE_S1.); +#42884 = LINE('',#42885,#42886); +#42885 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); +#42886 = VECTOR('',#42887,1.); +#42887 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42888 = PCURVE('',#42494,#42889); +#42889 = DEFINITIONAL_REPRESENTATION('',(#42890),#42894); +#42890 = LINE('',#42891,#42892); +#42891 = CARTESIAN_POINT('',(1.153553390593,-0.3)); +#42892 = VECTOR('',#42893,1.); +#42893 = DIRECTION('',(1.,0.E+000)); +#42894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42895 = PCURVE('',#40595,#42896); +#42896 = DEFINITIONAL_REPRESENTATION('',(#42897),#42901); +#42897 = LINE('',#42898,#42899); +#42898 = CARTESIAN_POINT('',(0.E+000,3.31)); +#42899 = VECTOR('',#42900,1.); +#42900 = DIRECTION('',(1.,0.E+000)); +#42901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42902 = ORIENTED_EDGE('',*,*,#42903,.F.); +#42903 = EDGE_CURVE('',#42904,#42881,#42906,.T.); +#42904 = VERTEX_POINT('',#42905); +#42905 = CARTESIAN_POINT('',(2.4,-1.225,0.96)); +#42906 = SURFACE_CURVE('',#42907,(#42911,#42918),.PCURVE_S1.); +#42907 = LINE('',#42908,#42909); +#42908 = CARTESIAN_POINT('',(2.4,-1.225,0.96)); +#42909 = VECTOR('',#42910,1.); +#42910 = DIRECTION('',(0.E+000,1.,0.E+000)); +#42911 = PCURVE('',#42494,#42912); +#42912 = DEFINITIONAL_REPRESENTATION('',(#42913),#42917); +#42913 = LINE('',#42914,#42915); +#42914 = CARTESIAN_POINT('',(1.35,0.E+000)); +#42915 = VECTOR('',#42916,1.); +#42916 = DIRECTION('',(0.E+000,-1.)); +#42917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42918 = PCURVE('',#42919,#42924); +#42919 = CYLINDRICAL_SURFACE('',#42920,0.15); +#42920 = AXIS2_PLACEMENT_3D('',#42921,#42922,#42923); +#42921 = CARTESIAN_POINT('',(2.4,-1.225,0.81)); +#42922 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42923 = DIRECTION('',(1.,0.E+000,0.E+000)); +#42924 = DEFINITIONAL_REPRESENTATION('',(#42925),#42928); +#42925 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42926,#42927),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#40534 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#40535 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#40536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40537 = ORIENTED_EDGE('',*,*,#40538,.F.); -#40538 = EDGE_CURVE('',#40539,#40512,#40541,.T.); -#40539 = VERTEX_POINT('',#40540); -#40540 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); -#40541 = SURFACE_CURVE('',#40542,(#40546,#40553),.PCURVE_S1.); -#40542 = LINE('',#40543,#40544); -#40543 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); -#40544 = VECTOR('',#40545,1.); -#40545 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#40546 = PCURVE('',#40102,#40547); -#40547 = DEFINITIONAL_REPRESENTATION('',(#40548),#40552); -#40548 = LINE('',#40549,#40550); -#40549 = CARTESIAN_POINT('',(1.153553390593,0.E+000)); -#40550 = VECTOR('',#40551,1.); -#40551 = DIRECTION('',(1.,0.E+000)); -#40552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40553 = PCURVE('',#38147,#40554); -#40554 = DEFINITIONAL_REPRESENTATION('',(#40555),#40559); -#40555 = LINE('',#40556,#40557); -#40556 = CARTESIAN_POINT('',(5.192893218814,3.31)); -#40557 = VECTOR('',#40558,1.); -#40558 = DIRECTION('',(-1.,0.E+000)); -#40559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40560 = ORIENTED_EDGE('',*,*,#40561,.T.); -#40561 = EDGE_CURVE('',#40539,#40562,#40564,.T.); -#40562 = VERTEX_POINT('',#40563); -#40563 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); -#40564 = SURFACE_CURVE('',#40565,(#40570,#40577),.PCURVE_S1.); -#40565 = CIRCLE('',#40566,0.55); -#40566 = AXIS2_PLACEMENT_3D('',#40567,#40568,#40569); -#40567 = CARTESIAN_POINT('',(2.596446609407,-0.675,0.96)); -#40568 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40569 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#40570 = PCURVE('',#40102,#40571); -#40571 = DEFINITIONAL_REPRESENTATION('',(#40572),#40576); -#40572 = CIRCLE('',#40573,0.55); -#40573 = AXIS2_PLACEMENT_2D('',#40574,#40575); -#40574 = CARTESIAN_POINT('',(1.153553390593,-0.55)); -#40575 = DIRECTION('',(0.E+000,1.)); -#40576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40577 = PCURVE('',#38120,#40578); -#40578 = DEFINITIONAL_REPRESENTATION('',(#40579),#40582); -#40579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40580,#40581),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#40580 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#40581 = CARTESIAN_POINT('',(5.497787143781,3.31)); -#40582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40583 = ORIENTED_EDGE('',*,*,#40584,.T.); -#40584 = EDGE_CURVE('',#40562,#40585,#40587,.T.); -#40585 = VERTEX_POINT('',#40586); -#40586 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,0.96)); -#40587 = SURFACE_CURVE('',#40588,(#40592,#40599),.PCURVE_S1.); -#40588 = LINE('',#40589,#40590); -#40589 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); -#40590 = VECTOR('',#40591,1.); -#40591 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#40592 = PCURVE('',#40102,#40593); -#40593 = DEFINITIONAL_REPRESENTATION('',(#40594),#40598); -#40594 = LINE('',#40595,#40596); -#40595 = CARTESIAN_POINT('',(0.764644660941,-0.161091270347)); -#40596 = VECTOR('',#40597,1.); -#40597 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#40598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40599 = PCURVE('',#38091,#40600); -#40600 = DEFINITIONAL_REPRESENTATION('',(#40601),#40605); -#40601 = LINE('',#40602,#40603); -#40602 = CARTESIAN_POINT('',(0.E+000,3.31)); -#40603 = VECTOR('',#40604,1.); -#40604 = DIRECTION('',(1.,0.E+000)); -#40605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#42926 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#42927 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#42928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#40606 = ORIENTED_EDGE('',*,*,#40607,.T.); -#40607 = EDGE_CURVE('',#40585,#40088,#40608,.T.); -#40608 = SURFACE_CURVE('',#40609,(#40614,#40621),.PCURVE_S1.); -#40609 = CIRCLE('',#40610,0.55); -#40610 = AXIS2_PLACEMENT_3D('',#40611,#40612,#40613); -#40611 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,0.96)); -#40612 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40613 = DIRECTION('',(0.707106781187,-0.707106781186,0.E+000)); -#40614 = PCURVE('',#40102,#40615); -#40615 = DEFINITIONAL_REPRESENTATION('',(#40616),#40620); -#40616 = CIRCLE('',#40617,0.55); -#40617 = AXIS2_PLACEMENT_2D('',#40618,#40619); -#40618 = CARTESIAN_POINT('',(0.55,-1.153553390593)); -#40619 = DIRECTION('',(-0.707106781187,0.707106781186)); -#40620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40621 = PCURVE('',#38064,#40622); -#40622 = DEFINITIONAL_REPRESENTATION('',(#40623),#40626); -#40623 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40624,#40625),.UNSPECIFIED., +#42929 = ORIENTED_EDGE('',*,*,#42930,.F.); +#42930 = EDGE_CURVE('',#42931,#42904,#42933,.T.); +#42931 = VERTEX_POINT('',#42932); +#42932 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); +#42933 = SURFACE_CURVE('',#42934,(#42938,#42945),.PCURVE_S1.); +#42934 = LINE('',#42935,#42936); +#42935 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); +#42936 = VECTOR('',#42937,1.); +#42937 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#42938 = PCURVE('',#42494,#42939); +#42939 = DEFINITIONAL_REPRESENTATION('',(#42940),#42944); +#42940 = LINE('',#42941,#42942); +#42941 = CARTESIAN_POINT('',(1.153553390593,0.E+000)); +#42942 = VECTOR('',#42943,1.); +#42943 = DIRECTION('',(1.,0.E+000)); +#42944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42945 = PCURVE('',#40539,#42946); +#42946 = DEFINITIONAL_REPRESENTATION('',(#42947),#42951); +#42947 = LINE('',#42948,#42949); +#42948 = CARTESIAN_POINT('',(5.192893218814,3.31)); +#42949 = VECTOR('',#42950,1.); +#42950 = DIRECTION('',(-1.,0.E+000)); +#42951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42952 = ORIENTED_EDGE('',*,*,#42953,.T.); +#42953 = EDGE_CURVE('',#42931,#42954,#42956,.T.); +#42954 = VERTEX_POINT('',#42955); +#42955 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); +#42956 = SURFACE_CURVE('',#42957,(#42962,#42969),.PCURVE_S1.); +#42957 = CIRCLE('',#42958,0.55); +#42958 = AXIS2_PLACEMENT_3D('',#42959,#42960,#42961); +#42959 = CARTESIAN_POINT('',(2.596446609407,-0.675,0.96)); +#42960 = DIRECTION('',(0.E+000,0.E+000,1.)); +#42961 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#42962 = PCURVE('',#42494,#42963); +#42963 = DEFINITIONAL_REPRESENTATION('',(#42964),#42968); +#42964 = CIRCLE('',#42965,0.55); +#42965 = AXIS2_PLACEMENT_2D('',#42966,#42967); +#42966 = CARTESIAN_POINT('',(1.153553390593,-0.55)); +#42967 = DIRECTION('',(0.E+000,1.)); +#42968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42969 = PCURVE('',#40512,#42970); +#42970 = DEFINITIONAL_REPRESENTATION('',(#42971),#42974); +#42971 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42972,#42973),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); +#42972 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#42973 = CARTESIAN_POINT('',(5.497787143781,3.31)); +#42974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42975 = ORIENTED_EDGE('',*,*,#42976,.T.); +#42976 = EDGE_CURVE('',#42954,#42977,#42979,.T.); +#42977 = VERTEX_POINT('',#42978); +#42978 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,0.96)); +#42979 = SURFACE_CURVE('',#42980,(#42984,#42991),.PCURVE_S1.); +#42980 = LINE('',#42981,#42982); +#42981 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); +#42982 = VECTOR('',#42983,1.); +#42983 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#42984 = PCURVE('',#42494,#42985); +#42985 = DEFINITIONAL_REPRESENTATION('',(#42986),#42990); +#42986 = LINE('',#42987,#42988); +#42987 = CARTESIAN_POINT('',(0.764644660941,-0.161091270347)); +#42988 = VECTOR('',#42989,1.); +#42989 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#42990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42991 = PCURVE('',#40483,#42992); +#42992 = DEFINITIONAL_REPRESENTATION('',(#42993),#42997); +#42993 = LINE('',#42994,#42995); +#42994 = CARTESIAN_POINT('',(0.E+000,3.31)); +#42995 = VECTOR('',#42996,1.); +#42996 = DIRECTION('',(1.,0.E+000)); +#42997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#42998 = ORIENTED_EDGE('',*,*,#42999,.T.); +#42999 = EDGE_CURVE('',#42977,#42480,#43000,.T.); +#43000 = SURFACE_CURVE('',#43001,(#43006,#43013),.PCURVE_S1.); +#43001 = CIRCLE('',#43002,0.55); +#43002 = AXIS2_PLACEMENT_3D('',#43003,#43004,#43005); +#43003 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,0.96)); +#43004 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43005 = DIRECTION('',(0.707106781187,-0.707106781186,0.E+000)); +#43006 = PCURVE('',#42494,#43007); +#43007 = DEFINITIONAL_REPRESENTATION('',(#43008),#43012); +#43008 = CIRCLE('',#43009,0.55); +#43009 = AXIS2_PLACEMENT_2D('',#43010,#43011); +#43010 = CARTESIAN_POINT('',(0.55,-1.153553390593)); +#43011 = DIRECTION('',(-0.707106781187,0.707106781186)); +#43012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43013 = PCURVE('',#40456,#43014); +#43014 = DEFINITIONAL_REPRESENTATION('',(#43015),#43018); +#43015 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43016,#43017),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.595988761751),.PIECEWISE_BEZIER_KNOTS.); -#40624 = CARTESIAN_POINT('',(5.497787143782,3.31)); -#40625 = CARTESIAN_POINT('',(6.093775905533,3.31)); -#40626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#43016 = CARTESIAN_POINT('',(5.497787143782,3.31)); +#43017 = CARTESIAN_POINT('',(6.093775905533,3.31)); +#43018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#40627 = ADVANCED_FACE('',(#40628),#38263,.T.); -#40628 = FACE_BOUND('',#40629,.F.); -#40629 = EDGE_LOOP('',(#40630,#40631,#40632,#40633)); -#40630 = ORIENTED_EDGE('',*,*,#40442,.F.); -#40631 = ORIENTED_EDGE('',*,*,#40237,.T.); -#40632 = ORIENTED_EDGE('',*,*,#38247,.T.); -#40633 = ORIENTED_EDGE('',*,*,#40634,.F.); -#40634 = EDGE_CURVE('',#40443,#38216,#40635,.T.); -#40635 = SURFACE_CURVE('',#40636,(#40640,#40647),.PCURVE_S1.); -#40636 = LINE('',#40637,#40638); -#40637 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,0.96)); -#40638 = VECTOR('',#40639,1.); -#40639 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40640 = PCURVE('',#38263,#40641); -#40641 = DEFINITIONAL_REPRESENTATION('',(#40642),#40646); -#40642 = LINE('',#40643,#40644); -#40643 = CARTESIAN_POINT('',(0.853553390594,3.31)); -#40644 = VECTOR('',#40645,1.); -#40645 = DIRECTION('',(0.E+000,1.)); -#40646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40647 = PCURVE('',#38236,#40648); -#40648 = DEFINITIONAL_REPRESENTATION('',(#40649),#40652); -#40649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40650,#40651),.UNSPECIFIED., +#43019 = ADVANCED_FACE('',(#43020),#40655,.T.); +#43020 = FACE_BOUND('',#43021,.F.); +#43021 = EDGE_LOOP('',(#43022,#43023,#43024,#43025)); +#43022 = ORIENTED_EDGE('',*,*,#42834,.F.); +#43023 = ORIENTED_EDGE('',*,*,#42629,.T.); +#43024 = ORIENTED_EDGE('',*,*,#40639,.T.); +#43025 = ORIENTED_EDGE('',*,*,#43026,.F.); +#43026 = EDGE_CURVE('',#42835,#40608,#43027,.T.); +#43027 = SURFACE_CURVE('',#43028,(#43032,#43039),.PCURVE_S1.); +#43028 = LINE('',#43029,#43030); +#43029 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,0.96)); +#43030 = VECTOR('',#43031,1.); +#43031 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43032 = PCURVE('',#40655,#43033); +#43033 = DEFINITIONAL_REPRESENTATION('',(#43034),#43038); +#43034 = LINE('',#43035,#43036); +#43035 = CARTESIAN_POINT('',(0.853553390594,3.31)); +#43036 = VECTOR('',#43037,1.); +#43037 = DIRECTION('',(0.E+000,1.)); +#43038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43039 = PCURVE('',#40628,#43040); +#43040 = DEFINITIONAL_REPRESENTATION('',(#43041),#43044); +#43041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43042,#43043),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#40650 = CARTESIAN_POINT('',(5.49778714378,3.31)); -#40651 = CARTESIAN_POINT('',(5.49778714378,4.7)); -#40652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40653 = ADVANCED_FACE('',(#40654),#40400,.T.); -#40654 = FACE_BOUND('',#40655,.F.); -#40655 = EDGE_LOOP('',(#40656,#40718,#40739,#40740,#40763,#40790,#40846) - ); -#40656 = ORIENTED_EDGE('',*,*,#40657,.T.); -#40657 = EDGE_CURVE('',#40658,#40660,#40662,.T.); -#40658 = VERTEX_POINT('',#40659); -#40659 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); -#40660 = VERTEX_POINT('',#40661); -#40661 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); -#40662 = SURFACE_CURVE('',#40663,(#40672,#40684),.PCURVE_S1.); -#40663 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40664,#40665,#40666,#40667, - #40668,#40669,#40670,#40671),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#43042 = CARTESIAN_POINT('',(5.49778714378,3.31)); +#43043 = CARTESIAN_POINT('',(5.49778714378,4.7)); +#43044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43045 = ADVANCED_FACE('',(#43046),#42792,.T.); +#43046 = FACE_BOUND('',#43047,.F.); +#43047 = EDGE_LOOP('',(#43048,#43110,#43131,#43132,#43155,#43182,#43238) + ); +#43048 = ORIENTED_EDGE('',*,*,#43049,.T.); +#43049 = EDGE_CURVE('',#43050,#43052,#43054,.T.); +#43050 = VERTEX_POINT('',#43051); +#43051 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); +#43052 = VERTEX_POINT('',#43053); +#43053 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); +#43054 = SURFACE_CURVE('',#43055,(#43064,#43076),.PCURVE_S1.); +#43055 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43056,#43057,#43058,#43059, + #43060,#43061,#43062,#43063),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#40664 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); -#40665 = CARTESIAN_POINT('',(2.9,-0.725,-2.215088834765)); -#40666 = CARTESIAN_POINT('',(2.904063775792,-0.720936224208, +#43056 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); +#43057 = CARTESIAN_POINT('',(2.9,-0.725,-2.215088834765)); +#43058 = CARTESIAN_POINT('',(2.904063775792,-0.720936224208, -2.239519457455)); -#40667 = CARTESIAN_POINT('',(2.919357454992,-0.705642545008, +#43059 = CARTESIAN_POINT('',(2.919357454992,-0.705642545008, -2.278246267971)); -#40668 = CARTESIAN_POINT('',(2.947656106256,-0.677343893744, +#43060 = CARTESIAN_POINT('',(2.947656106256,-0.677343893744, -2.313670105381)); -#40669 = CARTESIAN_POINT('',(2.991922677631,-0.633077322369, +#43061 = CARTESIAN_POINT('',(2.991922677631,-0.633077322369, -2.341600728372)); -#40670 = CARTESIAN_POINT('',(3.028661165235,-0.596338834765,-2.35)); -#40671 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); -#40672 = PCURVE('',#40400,#40673); -#40673 = DEFINITIONAL_REPRESENTATION('',(#40674),#40683); -#40674 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40675,#40676,#40677,#40678, - #40679,#40680,#40681,#40682),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#43062 = CARTESIAN_POINT('',(3.028661165235,-0.596338834765,-2.35)); +#43063 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); +#43064 = PCURVE('',#42792,#43065); +#43065 = DEFINITIONAL_REPRESENTATION('',(#43066),#43075); +#43066 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43067,#43068,#43069,#43070, + #43071,#43072,#43073,#43074),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#40675 = CARTESIAN_POINT('',(0.674264068712,0.15)); -#40676 = CARTESIAN_POINT('',(0.674264068712,0.134911165235)); -#40677 = CARTESIAN_POINT('',(0.668517021873,0.110480542545)); -#40678 = CARTESIAN_POINT('',(0.646888493329,7.1753732029E-002)); -#40679 = CARTESIAN_POINT('',(0.606868156915,3.6329894619E-002)); -#40680 = CARTESIAN_POINT('',(0.544265771317,8.399271628E-003)); -#40681 = CARTESIAN_POINT('',(0.492309703886,0.E+000)); -#40682 = CARTESIAN_POINT('',(0.462132034356,0.E+000)); -#40683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40684 = PCURVE('',#40685,#40690); -#40685 = CYLINDRICAL_SURFACE('',#40686,0.15); -#40686 = AXIS2_PLACEMENT_3D('',#40687,#40688,#40689); -#40687 = CARTESIAN_POINT('',(-3.75,-0.575,-2.2)); -#40688 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40689 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#40690 = DEFINITIONAL_REPRESENTATION('',(#40691),#40717); -#40691 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40692,#40693,#40694,#40695, - #40696,#40697,#40698,#40699,#40700,#40701,#40702,#40703,#40704, - #40705,#40706,#40707,#40708,#40709,#40710,#40711,#40712,#40713, - #40714,#40715,#40716),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#43067 = CARTESIAN_POINT('',(0.674264068712,0.15)); +#43068 = CARTESIAN_POINT('',(0.674264068712,0.134911165235)); +#43069 = CARTESIAN_POINT('',(0.668517021873,0.110480542545)); +#43070 = CARTESIAN_POINT('',(0.646888493329,7.1753732029E-002)); +#43071 = CARTESIAN_POINT('',(0.606868156915,3.6329894619E-002)); +#43072 = CARTESIAN_POINT('',(0.544265771317,8.399271628E-003)); +#43073 = CARTESIAN_POINT('',(0.492309703886,0.E+000)); +#43074 = CARTESIAN_POINT('',(0.462132034356,0.E+000)); +#43075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43076 = PCURVE('',#43077,#43082); +#43077 = CYLINDRICAL_SURFACE('',#43078,0.15); +#43078 = AXIS2_PLACEMENT_3D('',#43079,#43080,#43081); +#43079 = CARTESIAN_POINT('',(-3.75,-0.575,-2.2)); +#43080 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43081 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43082 = DEFINITIONAL_REPRESENTATION('',(#43083),#43109); +#43083 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43084,#43085,#43086,#43087, + #43088,#43089,#43090,#43091,#43092,#43093,#43094,#43095,#43096, + #43097,#43098,#43099,#43100,#43101,#43102,#43103,#43104,#43105, + #43106,#43107,#43108),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -51048,164 +54037,164 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40692 = CARTESIAN_POINT('',(4.712388980385,6.65)); -#40693 = CARTESIAN_POINT('',(4.748933560976,6.650000071163)); -#40694 = CARTESIAN_POINT('',(4.81707874687,6.650536832124)); -#40695 = CARTESIAN_POINT('',(4.907992270893,6.652629433135)); -#40696 = CARTESIAN_POINT('',(4.991501242609,6.655668137668)); -#40697 = CARTESIAN_POINT('',(5.070203254432,6.659377948672)); -#40698 = CARTESIAN_POINT('',(5.144906443438,6.663702370713)); -#40699 = CARTESIAN_POINT('',(5.216603945889,6.668547599132)); -#40700 = CARTESIAN_POINT('',(5.285913848235,6.673861257224)); -#40701 = CARTESIAN_POINT('',(5.353274617376,6.679622122875)); -#40702 = CARTESIAN_POINT('',(5.419136101421,6.685802484836)); -#40703 = CARTESIAN_POINT('',(5.483899443317,6.692376371071)); -#40704 = CARTESIAN_POINT('',(5.547920698644,6.699317341829)); -#40705 = CARTESIAN_POINT('',(5.611491697867,6.706599089008)); -#40706 = CARTESIAN_POINT('',(5.674841699303,6.714224788906)); -#40707 = CARTESIAN_POINT('',(5.738220831198,6.722197721708)); -#40708 = CARTESIAN_POINT('',(5.801885308441,6.73052081094)); -#40709 = CARTESIAN_POINT('',(5.866098193035,6.739198302877)); -#40710 = CARTESIAN_POINT('',(5.931103476771,6.748229509457)); -#40711 = CARTESIAN_POINT('',(5.997203324603,6.757636998244)); -#40712 = CARTESIAN_POINT('',(6.064845544964,6.767466592411)); -#40713 = CARTESIAN_POINT('',(6.13454852804,6.777759180839)); -#40714 = CARTESIAN_POINT('',(6.206898120521,6.788556975001)); -#40715 = CARTESIAN_POINT('',(6.257321803275,6.796120211861)); -#40716 = CARTESIAN_POINT('',(6.28318530718,6.8)); -#40717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40718 = ORIENTED_EDGE('',*,*,#40719,.F.); -#40719 = EDGE_CURVE('',#40363,#40660,#40720,.T.); -#40720 = SURFACE_CURVE('',#40721,(#40725,#40732),.PCURVE_S1.); -#40721 = LINE('',#40722,#40723); -#40722 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042,-2.35)); -#40723 = VECTOR('',#40724,1.); -#40724 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#40725 = PCURVE('',#40400,#40726); -#40726 = DEFINITIONAL_REPRESENTATION('',(#40727),#40731); -#40727 = LINE('',#40728,#40729); -#40728 = CARTESIAN_POINT('',(2.246058769703E-004,0.E+000)); -#40729 = VECTOR('',#40730,1.); -#40730 = DIRECTION('',(1.,0.E+000)); -#40731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40732 = PCURVE('',#39747,#40733); -#40733 = DEFINITIONAL_REPRESENTATION('',(#40734),#40738); -#40734 = LINE('',#40735,#40736); -#40735 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042)); -#40736 = VECTOR('',#40737,1.); -#40737 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#40738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40739 = ORIENTED_EDGE('',*,*,#40362,.T.); -#40740 = ORIENTED_EDGE('',*,*,#40741,.T.); -#40741 = EDGE_CURVE('',#40331,#40742,#40744,.T.); -#40742 = VERTEX_POINT('',#40743); -#40743 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,-0.56)); -#40744 = SURFACE_CURVE('',#40745,(#40749,#40756),.PCURVE_S1.); -#40745 = LINE('',#40746,#40747); -#40746 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-0.56)); -#40747 = VECTOR('',#40748,1.); -#40748 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#40749 = PCURVE('',#40400,#40750); -#40750 = DEFINITIONAL_REPRESENTATION('',(#40751),#40755); -#40751 = LINE('',#40752,#40753); -#40752 = CARTESIAN_POINT('',(0.E+000,1.79)); -#40753 = VECTOR('',#40754,1.); -#40754 = DIRECTION('',(1.,0.E+000)); -#40755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40756 = PCURVE('',#40346,#40757); -#40757 = DEFINITIONAL_REPRESENTATION('',(#40758),#40762); -#40758 = LINE('',#40759,#40760); -#40759 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); -#40760 = VECTOR('',#40761,1.); -#40761 = DIRECTION('',(-0.707106781187,0.707106781187)); -#40762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40763 = ORIENTED_EDGE('',*,*,#40764,.F.); -#40764 = EDGE_CURVE('',#40765,#40742,#40767,.T.); -#40765 = VERTEX_POINT('',#40766); -#40766 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, +#43084 = CARTESIAN_POINT('',(4.712388980385,6.65)); +#43085 = CARTESIAN_POINT('',(4.748933560976,6.650000071163)); +#43086 = CARTESIAN_POINT('',(4.81707874687,6.650536832124)); +#43087 = CARTESIAN_POINT('',(4.907992270893,6.652629433135)); +#43088 = CARTESIAN_POINT('',(4.991501242609,6.655668137668)); +#43089 = CARTESIAN_POINT('',(5.070203254432,6.659377948672)); +#43090 = CARTESIAN_POINT('',(5.144906443438,6.663702370713)); +#43091 = CARTESIAN_POINT('',(5.216603945889,6.668547599132)); +#43092 = CARTESIAN_POINT('',(5.285913848235,6.673861257224)); +#43093 = CARTESIAN_POINT('',(5.353274617376,6.679622122875)); +#43094 = CARTESIAN_POINT('',(5.419136101421,6.685802484836)); +#43095 = CARTESIAN_POINT('',(5.483899443317,6.692376371071)); +#43096 = CARTESIAN_POINT('',(5.547920698644,6.699317341829)); +#43097 = CARTESIAN_POINT('',(5.611491697867,6.706599089008)); +#43098 = CARTESIAN_POINT('',(5.674841699303,6.714224788906)); +#43099 = CARTESIAN_POINT('',(5.738220831198,6.722197721708)); +#43100 = CARTESIAN_POINT('',(5.801885308441,6.73052081094)); +#43101 = CARTESIAN_POINT('',(5.866098193035,6.739198302877)); +#43102 = CARTESIAN_POINT('',(5.931103476771,6.748229509457)); +#43103 = CARTESIAN_POINT('',(5.997203324603,6.757636998244)); +#43104 = CARTESIAN_POINT('',(6.064845544964,6.767466592411)); +#43105 = CARTESIAN_POINT('',(6.13454852804,6.777759180839)); +#43106 = CARTESIAN_POINT('',(6.206898120521,6.788556975001)); +#43107 = CARTESIAN_POINT('',(6.257321803275,6.796120211861)); +#43108 = CARTESIAN_POINT('',(6.28318530718,6.8)); +#43109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43110 = ORIENTED_EDGE('',*,*,#43111,.F.); +#43111 = EDGE_CURVE('',#42755,#43052,#43112,.T.); +#43112 = SURFACE_CURVE('',#43113,(#43117,#43124),.PCURVE_S1.); +#43113 = LINE('',#43114,#43115); +#43114 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042,-2.35)); +#43115 = VECTOR('',#43116,1.); +#43116 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#43117 = PCURVE('',#42792,#43118); +#43118 = DEFINITIONAL_REPRESENTATION('',(#43119),#43123); +#43119 = LINE('',#43120,#43121); +#43120 = CARTESIAN_POINT('',(2.246058769703E-004,0.E+000)); +#43121 = VECTOR('',#43122,1.); +#43122 = DIRECTION('',(1.,0.E+000)); +#43123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43124 = PCURVE('',#42139,#43125); +#43125 = DEFINITIONAL_REPRESENTATION('',(#43126),#43130); +#43126 = LINE('',#43127,#43128); +#43127 = CARTESIAN_POINT('',(3.376617874958,-0.248382125042)); +#43128 = VECTOR('',#43129,1.); +#43129 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#43130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43131 = ORIENTED_EDGE('',*,*,#42754,.T.); +#43132 = ORIENTED_EDGE('',*,*,#43133,.T.); +#43133 = EDGE_CURVE('',#42723,#43134,#43136,.T.); +#43134 = VERTEX_POINT('',#43135); +#43135 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297,-0.56)); +#43136 = SURFACE_CURVE('',#43137,(#43141,#43148),.PCURVE_S1.); +#43137 = LINE('',#43138,#43139); +#43138 = CARTESIAN_POINT('',(3.376776695297,-0.248223304703,-0.56)); +#43139 = VECTOR('',#43140,1.); +#43140 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#43141 = PCURVE('',#42792,#43142); +#43142 = DEFINITIONAL_REPRESENTATION('',(#43143),#43147); +#43143 = LINE('',#43144,#43145); +#43144 = CARTESIAN_POINT('',(0.E+000,1.79)); +#43145 = VECTOR('',#43146,1.); +#43146 = DIRECTION('',(1.,0.E+000)); +#43147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43148 = PCURVE('',#42738,#43149); +#43149 = DEFINITIONAL_REPRESENTATION('',(#43150),#43154); +#43150 = LINE('',#43151,#43152); +#43151 = CARTESIAN_POINT('',(0.976776695297,-0.976776695297)); +#43152 = VECTOR('',#43153,1.); +#43153 = DIRECTION('',(-0.707106781187,0.707106781187)); +#43154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43155 = ORIENTED_EDGE('',*,*,#43156,.F.); +#43156 = EDGE_CURVE('',#43157,#43134,#43159,.T.); +#43157 = VERTEX_POINT('',#43158); +#43158 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, -1.531808643576)); -#40767 = SURFACE_CURVE('',#40768,(#40772,#40779),.PCURVE_S1.); -#40768 = LINE('',#40769,#40770); -#40769 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, +#43159 = SURFACE_CURVE('',#43160,(#43164,#43171),.PCURVE_S1.); +#43160 = LINE('',#43161,#43162); +#43161 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, -1.531808643576)); -#40770 = VECTOR('',#40771,1.); -#40771 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40772 = PCURVE('',#40400,#40773); -#40773 = DEFINITIONAL_REPRESENTATION('',(#40774),#40778); -#40774 = LINE('',#40775,#40776); -#40775 = CARTESIAN_POINT('',(0.853553390594,0.818191356424)); -#40776 = VECTOR('',#40777,1.); -#40777 = DIRECTION('',(0.E+000,1.)); -#40778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40779 = PCURVE('',#40780,#40785); -#40780 = CYLINDRICAL_SURFACE('',#40781,0.25); -#40781 = AXIS2_PLACEMENT_3D('',#40782,#40783,#40784); -#40782 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); -#40783 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40784 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40785 = DEFINITIONAL_REPRESENTATION('',(#40786),#40789); -#40786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40787,#40788),.UNSPECIFIED., +#43162 = VECTOR('',#43163,1.); +#43163 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43164 = PCURVE('',#42792,#43165); +#43165 = DEFINITIONAL_REPRESENTATION('',(#43166),#43170); +#43166 = LINE('',#43167,#43168); +#43167 = CARTESIAN_POINT('',(0.853553390594,0.818191356424)); +#43168 = VECTOR('',#43169,1.); +#43169 = DIRECTION('',(0.E+000,1.)); +#43170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43171 = PCURVE('',#43172,#43177); +#43172 = CYLINDRICAL_SURFACE('',#43173,0.25); +#43173 = AXIS2_PLACEMENT_3D('',#43174,#43175,#43176); +#43174 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); +#43175 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43176 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43177 = DEFINITIONAL_REPRESENTATION('',(#43178),#43181); +#43178 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43179,#43180),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.971808643576),.PIECEWISE_BEZIER_KNOTS.); -#40787 = CARTESIAN_POINT('',(5.49778714378,0.818191356424)); -#40788 = CARTESIAN_POINT('',(5.49778714378,1.79)); -#40789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40790 = ORIENTED_EDGE('',*,*,#40791,.F.); -#40791 = EDGE_CURVE('',#40792,#40765,#40794,.T.); -#40792 = VERTEX_POINT('',#40793); -#40793 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); -#40794 = SURFACE_CURVE('',#40795,(#40802,#40812),.PCURVE_S1.); -#40795 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40796,#40797,#40798,#40799, - #40800,#40801),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) +#43179 = CARTESIAN_POINT('',(5.49778714378,0.818191356424)); +#43180 = CARTESIAN_POINT('',(5.49778714378,1.79)); +#43181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43182 = ORIENTED_EDGE('',*,*,#43183,.F.); +#43183 = EDGE_CURVE('',#43184,#43157,#43186,.T.); +#43184 = VERTEX_POINT('',#43185); +#43185 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); +#43186 = SURFACE_CURVE('',#43187,(#43194,#43204),.PCURVE_S1.); +#43187 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43188,#43189,#43190,#43191, + #43192,#43193),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) ,.UNSPECIFIED.); -#40796 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); -#40797 = CARTESIAN_POINT('',(2.9,-0.725,-1.654274107399)); -#40798 = CARTESIAN_POINT('',(2.889099431951,-0.735900568049, +#43188 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); +#43189 = CARTESIAN_POINT('',(2.9,-0.725,-1.654274107399)); +#43190 = CARTESIAN_POINT('',(2.889099431951,-0.735900568049, -1.616624166029)); -#40799 = CARTESIAN_POINT('',(2.851332144966,-0.773667855034, +#43191 = CARTESIAN_POINT('',(2.851332144966,-0.773667855034, -1.561539956467)); -#40800 = CARTESIAN_POINT('',(2.80938387573,-0.81561612427, +#43192 = CARTESIAN_POINT('',(2.80938387573,-0.81561612427, -1.537475424551)); -#40801 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, +#43193 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, -1.531808643576)); -#40802 = PCURVE('',#40400,#40803); -#40803 = DEFINITIONAL_REPRESENTATION('',(#40804),#40811); -#40804 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40805,#40806,#40807,#40808, - #40809,#40810),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) +#43194 = PCURVE('',#42792,#43195); +#43195 = DEFINITIONAL_REPRESENTATION('',(#43196),#43203); +#43196 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43197,#43198,#43199,#43200, + #43201,#43202),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) ,.UNSPECIFIED.); -#40805 = CARTESIAN_POINT('',(0.674264068712,0.67)); -#40806 = CARTESIAN_POINT('',(0.674264068712,0.695725892601)); -#40807 = CARTESIAN_POINT('',(0.689679799885,0.733375833971)); -#40808 = CARTESIAN_POINT('',(0.743090809353,0.788460043533)); -#40809 = CARTESIAN_POINT('',(0.802414620624,0.812524575449)); -#40810 = CARTESIAN_POINT('',(0.853553390594,0.818191356424)); -#40811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40812 = PCURVE('',#40813,#40818); -#40813 = CYLINDRICAL_SURFACE('',#40814,0.15); -#40814 = AXIS2_PLACEMENT_3D('',#40815,#40816,#40817); -#40815 = CARTESIAN_POINT('',(-3.75,-0.875,-1.68)); -#40816 = DIRECTION('',(1.,0.E+000,0.E+000)); -#40817 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#40818 = DEFINITIONAL_REPRESENTATION('',(#40819),#40845); -#40819 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40820,#40821,#40822,#40823, - #40824,#40825,#40826,#40827,#40828,#40829,#40830,#40831,#40832, - #40833,#40834,#40835,#40836,#40837,#40838,#40839,#40840,#40841, - #40842,#40843,#40844),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#43197 = CARTESIAN_POINT('',(0.674264068712,0.67)); +#43198 = CARTESIAN_POINT('',(0.674264068712,0.695725892601)); +#43199 = CARTESIAN_POINT('',(0.689679799885,0.733375833971)); +#43200 = CARTESIAN_POINT('',(0.743090809353,0.788460043533)); +#43201 = CARTESIAN_POINT('',(0.802414620624,0.812524575449)); +#43202 = CARTESIAN_POINT('',(0.853553390594,0.818191356424)); +#43203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43204 = PCURVE('',#43205,#43210); +#43205 = CYLINDRICAL_SURFACE('',#43206,0.15); +#43206 = AXIS2_PLACEMENT_3D('',#43207,#43208,#43209); +#43207 = CARTESIAN_POINT('',(-3.75,-0.875,-1.68)); +#43208 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43209 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43210 = DEFINITIONAL_REPRESENTATION('',(#43211),#43237); +#43211 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43212,#43213,#43214,#43215, + #43216,#43217,#43218,#43219,#43220,#43221,#43222,#43223,#43224, + #43225,#43226,#43227,#43228,#43229,#43230,#43231,#43232,#43233, + #43234,#43235,#43236),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -51213,153 +54202,153 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40820 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#40821 = CARTESIAN_POINT('',(1.601978784657,6.65)); -#40822 = CARTESIAN_POINT('',(1.661298490424,6.649639642821)); -#40823 = CARTESIAN_POINT('',(1.742667831779,6.648142686476)); -#40824 = CARTESIAN_POINT('',(1.817984715493,6.64581367892)); -#40825 = CARTESIAN_POINT('',(1.888693686444,6.6427779751)); -#40826 = CARTESIAN_POINT('',(1.956042754055,6.639157269233)); -#40827 = CARTESIAN_POINT('',(2.021127727696,6.635086912879)); -#40828 = CARTESIAN_POINT('',(2.084500361835,6.630637889742)); -#40829 = CARTESIAN_POINT('',(2.146376278772,6.625816815798)); -#40830 = CARTESIAN_POINT('',(2.207037995137,6.620643963994)); -#40831 = CARTESIAN_POINT('',(2.266733448662,6.615135947904)); -#40832 = CARTESIAN_POINT('',(2.325694965596,6.609310361627)); -#40833 = CARTESIAN_POINT('',(2.384121053951,6.603184536531)); -#40834 = CARTESIAN_POINT('',(2.442168868974,6.596748838454)); -#40835 = CARTESIAN_POINT('',(2.500030317521,6.58999361437)); -#40836 = CARTESIAN_POINT('',(2.557922172611,6.582909216307)); -#40837 = CARTESIAN_POINT('',(2.616083543492,6.575485994939)); -#40838 = CARTESIAN_POINT('',(2.674771534703,6.567714301304)); -#40839 = CARTESIAN_POINT('',(2.734257156083,6.55958448634)); -#40840 = CARTESIAN_POINT('',(2.794820792471,6.551086901014)); -#40841 = CARTESIAN_POINT('',(2.856745683084,6.542211896284)); -#40842 = CARTESIAN_POINT('',(2.920313481355,6.532949823112)); -#40843 = CARTESIAN_POINT('',(2.96396043223,6.526510629342)); -#40844 = CARTESIAN_POINT('',(2.986145343503,6.523223304703)); -#40845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40846 = ORIENTED_EDGE('',*,*,#40847,.F.); -#40847 = EDGE_CURVE('',#40658,#40792,#40848,.T.); -#40848 = SURFACE_CURVE('',#40849,(#40853,#40860),.PCURVE_S1.); -#40849 = LINE('',#40850,#40851); -#40850 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); -#40851 = VECTOR('',#40852,1.); -#40852 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40853 = PCURVE('',#40400,#40854); -#40854 = DEFINITIONAL_REPRESENTATION('',(#40855),#40859); -#40855 = LINE('',#40856,#40857); -#40856 = CARTESIAN_POINT('',(0.674264068712,0.15)); -#40857 = VECTOR('',#40858,1.); -#40858 = DIRECTION('',(0.E+000,1.)); -#40859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40860 = PCURVE('',#40861,#40866); -#40861 = PLANE('',#40862); -#40862 = AXIS2_PLACEMENT_3D('',#40863,#40864,#40865); -#40863 = CARTESIAN_POINT('',(-3.75,-0.725,-2.2)); -#40864 = DIRECTION('',(0.E+000,1.,0.E+000)); -#40865 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40866 = DEFINITIONAL_REPRESENTATION('',(#40867),#40871); -#40867 = LINE('',#40868,#40869); -#40868 = CARTESIAN_POINT('',(0.E+000,6.65)); -#40869 = VECTOR('',#40870,1.); -#40870 = DIRECTION('',(1.,0.E+000)); -#40871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40872 = ADVANCED_FACE('',(#40873),#38236,.F.); -#40873 = FACE_BOUND('',#40874,.F.); -#40874 = EDGE_LOOP('',(#40875,#40876,#40877,#40878)); -#40875 = ORIENTED_EDGE('',*,*,#40465,.T.); -#40876 = ORIENTED_EDGE('',*,*,#40634,.T.); -#40877 = ORIENTED_EDGE('',*,*,#38215,.T.); -#40878 = ORIENTED_EDGE('',*,*,#40879,.F.); -#40879 = EDGE_CURVE('',#40466,#38188,#40880,.T.); -#40880 = SURFACE_CURVE('',#40881,(#40885,#40891),.PCURVE_S1.); -#40881 = LINE('',#40882,#40883); -#40882 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); -#40883 = VECTOR('',#40884,1.); -#40884 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40885 = PCURVE('',#38236,#40886); -#40886 = DEFINITIONAL_REPRESENTATION('',(#40887),#40890); -#40887 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40888,#40889),.UNSPECIFIED., +#43212 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#43213 = CARTESIAN_POINT('',(1.601978784657,6.65)); +#43214 = CARTESIAN_POINT('',(1.661298490424,6.649639642821)); +#43215 = CARTESIAN_POINT('',(1.742667831779,6.648142686476)); +#43216 = CARTESIAN_POINT('',(1.817984715493,6.64581367892)); +#43217 = CARTESIAN_POINT('',(1.888693686444,6.6427779751)); +#43218 = CARTESIAN_POINT('',(1.956042754055,6.639157269233)); +#43219 = CARTESIAN_POINT('',(2.021127727696,6.635086912879)); +#43220 = CARTESIAN_POINT('',(2.084500361835,6.630637889742)); +#43221 = CARTESIAN_POINT('',(2.146376278772,6.625816815798)); +#43222 = CARTESIAN_POINT('',(2.207037995137,6.620643963994)); +#43223 = CARTESIAN_POINT('',(2.266733448662,6.615135947904)); +#43224 = CARTESIAN_POINT('',(2.325694965596,6.609310361627)); +#43225 = CARTESIAN_POINT('',(2.384121053951,6.603184536531)); +#43226 = CARTESIAN_POINT('',(2.442168868974,6.596748838454)); +#43227 = CARTESIAN_POINT('',(2.500030317521,6.58999361437)); +#43228 = CARTESIAN_POINT('',(2.557922172611,6.582909216307)); +#43229 = CARTESIAN_POINT('',(2.616083543492,6.575485994939)); +#43230 = CARTESIAN_POINT('',(2.674771534703,6.567714301304)); +#43231 = CARTESIAN_POINT('',(2.734257156083,6.55958448634)); +#43232 = CARTESIAN_POINT('',(2.794820792471,6.551086901014)); +#43233 = CARTESIAN_POINT('',(2.856745683084,6.542211896284)); +#43234 = CARTESIAN_POINT('',(2.920313481355,6.532949823112)); +#43235 = CARTESIAN_POINT('',(2.96396043223,6.526510629342)); +#43236 = CARTESIAN_POINT('',(2.986145343503,6.523223304703)); +#43237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43238 = ORIENTED_EDGE('',*,*,#43239,.F.); +#43239 = EDGE_CURVE('',#43050,#43184,#43240,.T.); +#43240 = SURFACE_CURVE('',#43241,(#43245,#43252),.PCURVE_S1.); +#43241 = LINE('',#43242,#43243); +#43242 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); +#43243 = VECTOR('',#43244,1.); +#43244 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43245 = PCURVE('',#42792,#43246); +#43246 = DEFINITIONAL_REPRESENTATION('',(#43247),#43251); +#43247 = LINE('',#43248,#43249); +#43248 = CARTESIAN_POINT('',(0.674264068712,0.15)); +#43249 = VECTOR('',#43250,1.); +#43250 = DIRECTION('',(0.E+000,1.)); +#43251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43252 = PCURVE('',#43253,#43258); +#43253 = PLANE('',#43254); +#43254 = AXIS2_PLACEMENT_3D('',#43255,#43256,#43257); +#43255 = CARTESIAN_POINT('',(-3.75,-0.725,-2.2)); +#43256 = DIRECTION('',(0.E+000,1.,0.E+000)); +#43257 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43258 = DEFINITIONAL_REPRESENTATION('',(#43259),#43263); +#43259 = LINE('',#43260,#43261); +#43260 = CARTESIAN_POINT('',(0.E+000,6.65)); +#43261 = VECTOR('',#43262,1.); +#43262 = DIRECTION('',(1.,0.E+000)); +#43263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43264 = ADVANCED_FACE('',(#43265),#40628,.F.); +#43265 = FACE_BOUND('',#43266,.F.); +#43266 = EDGE_LOOP('',(#43267,#43268,#43269,#43270)); +#43267 = ORIENTED_EDGE('',*,*,#42857,.T.); +#43268 = ORIENTED_EDGE('',*,*,#43026,.T.); +#43269 = ORIENTED_EDGE('',*,*,#40607,.T.); +#43270 = ORIENTED_EDGE('',*,*,#43271,.F.); +#43271 = EDGE_CURVE('',#42858,#40580,#43272,.T.); +#43272 = SURFACE_CURVE('',#43273,(#43277,#43283),.PCURVE_S1.); +#43273 = LINE('',#43274,#43275); +#43274 = CARTESIAN_POINT('',(2.596446609407,-0.925,0.96)); +#43275 = VECTOR('',#43276,1.); +#43276 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43277 = PCURVE('',#40628,#43278); +#43278 = DEFINITIONAL_REPRESENTATION('',(#43279),#43282); +#43279 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43280,#43281),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#40888 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#40889 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#40890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40891 = PCURVE('',#38203,#40892); -#40892 = DEFINITIONAL_REPRESENTATION('',(#40893),#40897); -#40893 = LINE('',#40894,#40895); -#40894 = CARTESIAN_POINT('',(0.E+000,3.31)); -#40895 = VECTOR('',#40896,1.); -#40896 = DIRECTION('',(0.E+000,1.)); -#40897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40898 = ADVANCED_FACE('',(#40899),#40780,.F.); -#40899 = FACE_BOUND('',#40900,.F.); -#40900 = EDGE_LOOP('',(#40901,#40931,#40998,#40999,#41026)); -#40901 = ORIENTED_EDGE('',*,*,#40902,.T.); -#40902 = EDGE_CURVE('',#40903,#40905,#40907,.T.); -#40903 = VERTEX_POINT('',#40904); -#40904 = CARTESIAN_POINT('',(2.596446609407,-0.925,-1.53)); -#40905 = VERTEX_POINT('',#40906); -#40906 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); -#40907 = SURFACE_CURVE('',#40908,(#40913,#40919),.PCURVE_S1.); -#40908 = CIRCLE('',#40909,0.25); -#40909 = AXIS2_PLACEMENT_3D('',#40910,#40911,#40912); -#40910 = CARTESIAN_POINT('',(2.596446609407,-0.675,-1.53)); -#40911 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40912 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#40913 = PCURVE('',#40780,#40914); -#40914 = DEFINITIONAL_REPRESENTATION('',(#40915),#40918); -#40915 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#40916,#40917),.UNSPECIFIED., +#43280 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#43281 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#43282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43283 = PCURVE('',#40595,#43284); +#43284 = DEFINITIONAL_REPRESENTATION('',(#43285),#43289); +#43285 = LINE('',#43286,#43287); +#43286 = CARTESIAN_POINT('',(0.E+000,3.31)); +#43287 = VECTOR('',#43288,1.); +#43288 = DIRECTION('',(0.E+000,1.)); +#43289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43290 = ADVANCED_FACE('',(#43291),#43172,.F.); +#43291 = FACE_BOUND('',#43292,.F.); +#43292 = EDGE_LOOP('',(#43293,#43323,#43390,#43391,#43418)); +#43293 = ORIENTED_EDGE('',*,*,#43294,.T.); +#43294 = EDGE_CURVE('',#43295,#43297,#43299,.T.); +#43295 = VERTEX_POINT('',#43296); +#43296 = CARTESIAN_POINT('',(2.596446609407,-0.925,-1.53)); +#43297 = VERTEX_POINT('',#43298); +#43298 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); +#43299 = SURFACE_CURVE('',#43300,(#43305,#43311),.PCURVE_S1.); +#43300 = CIRCLE('',#43301,0.25); +#43301 = AXIS2_PLACEMENT_3D('',#43302,#43303,#43304); +#43302 = CARTESIAN_POINT('',(2.596446609407,-0.675,-1.53)); +#43303 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43304 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43305 = PCURVE('',#43172,#43306); +#43306 = DEFINITIONAL_REPRESENTATION('',(#43307),#43310); +#43307 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43308,#43309),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.643501108793),.PIECEWISE_BEZIER_KNOTS.); -#40916 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#40917 = CARTESIAN_POINT('',(5.355890089178,0.82)); -#40918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40919 = PCURVE('',#40920,#40925); -#40920 = PLANE('',#40921); -#40921 = AXIS2_PLACEMENT_3D('',#40922,#40923,#40924); -#40922 = CARTESIAN_POINT('',(-3.75,-0.875,-1.53)); -#40923 = DIRECTION('',(0.E+000,0.E+000,1.)); -#40924 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#40925 = DEFINITIONAL_REPRESENTATION('',(#40926),#40930); -#40926 = CIRCLE('',#40927,0.25); -#40927 = AXIS2_PLACEMENT_2D('',#40928,#40929); -#40928 = CARTESIAN_POINT('',(-0.2,6.346446609407)); -#40929 = DIRECTION('',(1.,0.E+000)); -#40930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40931 = ORIENTED_EDGE('',*,*,#40932,.F.); -#40932 = EDGE_CURVE('',#40765,#40905,#40933,.T.); -#40933 = SURFACE_CURVE('',#40934,(#40940,#40969),.PCURVE_S1.); -#40934 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40935,#40936,#40937,#40938, - #40939),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#43308 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#43309 = CARTESIAN_POINT('',(5.355890089178,0.82)); +#43310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43311 = PCURVE('',#43312,#43317); +#43312 = PLANE('',#43313); +#43313 = AXIS2_PLACEMENT_3D('',#43314,#43315,#43316); +#43314 = CARTESIAN_POINT('',(-3.75,-0.875,-1.53)); +#43315 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43316 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43317 = DEFINITIONAL_REPRESENTATION('',(#43318),#43322); +#43318 = CIRCLE('',#43319,0.25); +#43319 = AXIS2_PLACEMENT_2D('',#43320,#43321); +#43320 = CARTESIAN_POINT('',(-0.2,6.346446609407)); +#43321 = DIRECTION('',(1.,0.E+000)); +#43322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43323 = ORIENTED_EDGE('',*,*,#43324,.F.); +#43324 = EDGE_CURVE('',#43157,#43297,#43325,.T.); +#43325 = SURFACE_CURVE('',#43326,(#43332,#43361),.PCURVE_S1.); +#43326 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43327,#43328,#43329,#43330, + #43331),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#40935 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, +#43327 = CARTESIAN_POINT('',(2.773223304703,-0.851776695297, -1.531808643576)); -#40936 = CARTESIAN_POINT('',(2.769257066256,-0.855742933744,-1.531187088 +#43328 = CARTESIAN_POINT('',(2.769257066256,-0.855742933744,-1.531187088 )); -#40937 = CARTESIAN_POINT('',(2.760841086691,-0.863624978668, +#43329 = CARTESIAN_POINT('',(2.760841086691,-0.863624978668, -1.530279300007)); -#40938 = CARTESIAN_POINT('',(2.75141841309,-0.871271147238,-1.53)); -#40939 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); -#40940 = PCURVE('',#40780,#40941); -#40941 = DEFINITIONAL_REPRESENTATION('',(#40942),#40968); -#40942 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40943,#40944,#40945,#40946, - #40947,#40948,#40949,#40950,#40951,#40952,#40953,#40954,#40955, - #40956,#40957,#40958,#40959,#40960,#40961,#40962,#40963,#40964, - #40965,#40966,#40967),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#43330 = CARTESIAN_POINT('',(2.75141841309,-0.871271147238,-1.53)); +#43331 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); +#43332 = PCURVE('',#43172,#43333); +#43333 = DEFINITIONAL_REPRESENTATION('',(#43334),#43360); +#43334 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43335,#43336,#43337,#43338, + #43339,#43340,#43341,#43342,#43343,#43344,#43345,#43346,#43347, + #43348,#43349,#43350,#43351,#43352,#43353,#43354,#43355,#43356, + #43357,#43358,#43359),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -51367,40 +54356,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40943 = CARTESIAN_POINT('',(5.49778714378,0.818191356424)); -#40944 = CARTESIAN_POINT('',(5.495747467497,0.818247861476)); -#40945 = CARTESIAN_POINT('',(5.491657993891,0.818358100315)); -#40946 = CARTESIAN_POINT('',(5.485493484132,0.818515192288)); -#40947 = CARTESIAN_POINT('',(5.479298741503,0.818664065485)); -#40948 = CARTESIAN_POINT('',(5.473073822986,0.818804767419)); -#40949 = CARTESIAN_POINT('',(5.466818779263,0.818937345601)); -#40950 = CARTESIAN_POINT('',(5.460533653789,0.819061847542)); -#40951 = CARTESIAN_POINT('',(5.454218482967,0.819178320753)); -#40952 = CARTESIAN_POINT('',(5.447873296034,0.819286812746)); -#40953 = CARTESIAN_POINT('',(5.441498115025,0.819387371031)); -#40954 = CARTESIAN_POINT('',(5.435092954718,0.819480043121)); -#40955 = CARTESIAN_POINT('',(5.428657822588,0.819564876525)); -#40956 = CARTESIAN_POINT('',(5.422192718772,0.819641918757)); -#40957 = CARTESIAN_POINT('',(5.415697669144,0.819711248577)); -#40958 = CARTESIAN_POINT('',(5.409172691929,0.819772944747)); -#40959 = CARTESIAN_POINT('',(5.402617797672,0.819827086029)); -#40960 = CARTESIAN_POINT('',(5.39603298917,0.819873751185)); -#40961 = CARTESIAN_POINT('',(5.389418261438,0.819913018977)); -#40962 = CARTESIAN_POINT('',(5.382773601632,0.819944968166)); -#40963 = CARTESIAN_POINT('',(5.376098989084,0.819969677514)); -#40964 = CARTESIAN_POINT('',(5.369394394983,0.819987225783)); -#40965 = CARTESIAN_POINT('',(5.362659783357,0.819997691735)); -#40966 = CARTESIAN_POINT('',(5.358149999274,0.82)); -#40967 = CARTESIAN_POINT('',(5.355890089178,0.82)); -#40968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40969 = PCURVE('',#40813,#40970); -#40970 = DEFINITIONAL_REPRESENTATION('',(#40971),#40997); -#40971 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#40972,#40973,#40974,#40975, - #40976,#40977,#40978,#40979,#40980,#40981,#40982,#40983,#40984, - #40985,#40986,#40987,#40988,#40989,#40990,#40991,#40992,#40993, - #40994,#40995,#40996),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#43335 = CARTESIAN_POINT('',(5.49778714378,0.818191356424)); +#43336 = CARTESIAN_POINT('',(5.495747467497,0.818247861476)); +#43337 = CARTESIAN_POINT('',(5.491657993891,0.818358100315)); +#43338 = CARTESIAN_POINT('',(5.485493484132,0.818515192288)); +#43339 = CARTESIAN_POINT('',(5.479298741503,0.818664065485)); +#43340 = CARTESIAN_POINT('',(5.473073822986,0.818804767419)); +#43341 = CARTESIAN_POINT('',(5.466818779263,0.818937345601)); +#43342 = CARTESIAN_POINT('',(5.460533653789,0.819061847542)); +#43343 = CARTESIAN_POINT('',(5.454218482967,0.819178320753)); +#43344 = CARTESIAN_POINT('',(5.447873296034,0.819286812746)); +#43345 = CARTESIAN_POINT('',(5.441498115025,0.819387371031)); +#43346 = CARTESIAN_POINT('',(5.435092954718,0.819480043121)); +#43347 = CARTESIAN_POINT('',(5.428657822588,0.819564876525)); +#43348 = CARTESIAN_POINT('',(5.422192718772,0.819641918757)); +#43349 = CARTESIAN_POINT('',(5.415697669144,0.819711248577)); +#43350 = CARTESIAN_POINT('',(5.409172691929,0.819772944747)); +#43351 = CARTESIAN_POINT('',(5.402617797672,0.819827086029)); +#43352 = CARTESIAN_POINT('',(5.39603298917,0.819873751185)); +#43353 = CARTESIAN_POINT('',(5.389418261438,0.819913018977)); +#43354 = CARTESIAN_POINT('',(5.382773601632,0.819944968166)); +#43355 = CARTESIAN_POINT('',(5.376098989084,0.819969677514)); +#43356 = CARTESIAN_POINT('',(5.369394394983,0.819987225783)); +#43357 = CARTESIAN_POINT('',(5.362659783357,0.819997691735)); +#43358 = CARTESIAN_POINT('',(5.358149999274,0.82)); +#43359 = CARTESIAN_POINT('',(5.355890089178,0.82)); +#43360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43361 = PCURVE('',#43205,#43362); +#43362 = DEFINITIONAL_REPRESENTATION('',(#43363),#43389); +#43363 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#43364,#43365,#43366,#43367, + #43368,#43369,#43370,#43371,#43372,#43373,#43374,#43375,#43376, + #43377,#43378,#43379,#43380,#43381,#43382,#43383,#43384,#43385, + #43386,#43387,#43388),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -51408,5215 +54397,5215 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#40972 = CARTESIAN_POINT('',(2.986145343503,6.523223304703)); -#40973 = CARTESIAN_POINT('',(2.98857846135,6.522862737571)); -#40974 = CARTESIAN_POINT('',(2.993439094082,6.522137607419)); -#40975 = CARTESIAN_POINT('',(3.000712661371,6.521037879792)); -#40976 = CARTESIAN_POINT('',(3.007968276941,6.519926075039)); -#40977 = CARTESIAN_POINT('',(3.01520536037,6.518802148433)); -#40978 = CARTESIAN_POINT('',(3.022423324853,6.517666055245)); -#40979 = CARTESIAN_POINT('',(3.029621576592,6.516517750747)); -#40980 = CARTESIAN_POINT('',(3.036799515459,6.515357190211)); -#40981 = CARTESIAN_POINT('',(3.04395653531,6.514184328909)); -#40982 = CARTESIAN_POINT('',(3.051092024382,6.512999122114)); -#40983 = CARTESIAN_POINT('',(3.058205365704,6.511801525096)); -#40984 = CARTESIAN_POINT('',(3.065295937338,6.510591493128)); -#40985 = CARTESIAN_POINT('',(3.072363113255,6.509368981483)); -#40986 = CARTESIAN_POINT('',(3.079406230972,6.508133950519)); -#40987 = CARTESIAN_POINT('',(3.086424617924,6.506886360598)); -#40988 = CARTESIAN_POINT('',(3.093417592399,6.505626172081)); -#40989 = CARTESIAN_POINT('',(3.10038446381,6.504353345327)); -#40990 = CARTESIAN_POINT('',(3.107324533161,6.503067840697)); -#40991 = CARTESIAN_POINT('',(3.114237093424,6.501769618552)); -#40992 = CARTESIAN_POINT('',(3.121121430007,6.500458639252)); -#40993 = CARTESIAN_POINT('',(3.127976820942,6.499134863157)); -#40994 = CARTESIAN_POINT('',(3.134802538053,6.497798250628)); -#40995 = CARTESIAN_POINT('',(3.139332742314,6.49689859156)); -#40996 = CARTESIAN_POINT('',(3.14159265359,6.496446609407)); -#40997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#40998 = ORIENTED_EDGE('',*,*,#40764,.T.); -#40999 = ORIENTED_EDGE('',*,*,#41000,.F.); -#41000 = EDGE_CURVE('',#41001,#40742,#41003,.T.); -#41001 = VERTEX_POINT('',#41002); -#41002 = CARTESIAN_POINT('',(2.596446609407,-0.925,-0.56)); -#41003 = SURFACE_CURVE('',#41004,(#41009,#41015),.PCURVE_S1.); -#41004 = CIRCLE('',#41005,0.25); -#41005 = AXIS2_PLACEMENT_3D('',#41006,#41007,#41008); -#41006 = CARTESIAN_POINT('',(2.596446609407,-0.675,-0.56)); -#41007 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41008 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41009 = PCURVE('',#40780,#41010); -#41010 = DEFINITIONAL_REPRESENTATION('',(#41011),#41014); -#41011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41012,#41013),.UNSPECIFIED., +#43364 = CARTESIAN_POINT('',(2.986145343503,6.523223304703)); +#43365 = CARTESIAN_POINT('',(2.98857846135,6.522862737571)); +#43366 = CARTESIAN_POINT('',(2.993439094082,6.522137607419)); +#43367 = CARTESIAN_POINT('',(3.000712661371,6.521037879792)); +#43368 = CARTESIAN_POINT('',(3.007968276941,6.519926075039)); +#43369 = CARTESIAN_POINT('',(3.01520536037,6.518802148433)); +#43370 = CARTESIAN_POINT('',(3.022423324853,6.517666055245)); +#43371 = CARTESIAN_POINT('',(3.029621576592,6.516517750747)); +#43372 = CARTESIAN_POINT('',(3.036799515459,6.515357190211)); +#43373 = CARTESIAN_POINT('',(3.04395653531,6.514184328909)); +#43374 = CARTESIAN_POINT('',(3.051092024382,6.512999122114)); +#43375 = CARTESIAN_POINT('',(3.058205365704,6.511801525096)); +#43376 = CARTESIAN_POINT('',(3.065295937338,6.510591493128)); +#43377 = CARTESIAN_POINT('',(3.072363113255,6.509368981483)); +#43378 = CARTESIAN_POINT('',(3.079406230972,6.508133950519)); +#43379 = CARTESIAN_POINT('',(3.086424617924,6.506886360598)); +#43380 = CARTESIAN_POINT('',(3.093417592399,6.505626172081)); +#43381 = CARTESIAN_POINT('',(3.10038446381,6.504353345327)); +#43382 = CARTESIAN_POINT('',(3.107324533161,6.503067840697)); +#43383 = CARTESIAN_POINT('',(3.114237093424,6.501769618552)); +#43384 = CARTESIAN_POINT('',(3.121121430007,6.500458639252)); +#43385 = CARTESIAN_POINT('',(3.127976820942,6.499134863157)); +#43386 = CARTESIAN_POINT('',(3.134802538053,6.497798250628)); +#43387 = CARTESIAN_POINT('',(3.139332742314,6.49689859156)); +#43388 = CARTESIAN_POINT('',(3.14159265359,6.496446609407)); +#43389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43390 = ORIENTED_EDGE('',*,*,#43156,.T.); +#43391 = ORIENTED_EDGE('',*,*,#43392,.F.); +#43392 = EDGE_CURVE('',#43393,#43134,#43395,.T.); +#43393 = VERTEX_POINT('',#43394); +#43394 = CARTESIAN_POINT('',(2.596446609407,-0.925,-0.56)); +#43395 = SURFACE_CURVE('',#43396,(#43401,#43407),.PCURVE_S1.); +#43396 = CIRCLE('',#43397,0.25); +#43397 = AXIS2_PLACEMENT_3D('',#43398,#43399,#43400); +#43398 = CARTESIAN_POINT('',(2.596446609407,-0.675,-0.56)); +#43399 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43400 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43401 = PCURVE('',#43172,#43402); +#43402 = DEFINITIONAL_REPRESENTATION('',(#43403),#43406); +#43403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43404,#43405),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#41012 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#41013 = CARTESIAN_POINT('',(5.49778714378,1.79)); -#41014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#43404 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#43405 = CARTESIAN_POINT('',(5.49778714378,1.79)); +#43406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#41015 = PCURVE('',#40346,#41016); -#41016 = DEFINITIONAL_REPRESENTATION('',(#41017),#41025); -#41017 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41018,#41019,#41020,#41021 - ,#41022,#41023,#41024),.UNSPECIFIED.,.F.,.F.) +#43407 = PCURVE('',#42738,#43408); +#43408 = DEFINITIONAL_REPRESENTATION('',(#43409),#43417); +#43409 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43410,#43411,#43412,#43413 + ,#43414,#43415,#43416),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41018 = CARTESIAN_POINT('',(0.196446609407,-0.3)); -#41019 = CARTESIAN_POINT('',(0.629459311299,-0.3)); -#41020 = CARTESIAN_POINT('',(0.412952960353,-0.675)); -#41021 = CARTESIAN_POINT('',(0.196446609407,-1.05)); -#41022 = CARTESIAN_POINT('',(-2.005974153911E-002,-0.675)); -#41023 = CARTESIAN_POINT('',(-0.236566092485,-0.3)); -#41024 = CARTESIAN_POINT('',(0.196446609407,-0.3)); -#41025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41026 = ORIENTED_EDGE('',*,*,#41027,.F.); -#41027 = EDGE_CURVE('',#40903,#41001,#41028,.T.); -#41028 = SURFACE_CURVE('',#41029,(#41033,#41039),.PCURVE_S1.); -#41029 = LINE('',#41030,#41031); -#41030 = CARTESIAN_POINT('',(2.596446609407,-0.925,-1.53)); -#41031 = VECTOR('',#41032,1.); -#41032 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41033 = PCURVE('',#40780,#41034); -#41034 = DEFINITIONAL_REPRESENTATION('',(#41035),#41038); -#41035 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41036,#41037),.UNSPECIFIED., +#43410 = CARTESIAN_POINT('',(0.196446609407,-0.3)); +#43411 = CARTESIAN_POINT('',(0.629459311299,-0.3)); +#43412 = CARTESIAN_POINT('',(0.412952960353,-0.675)); +#43413 = CARTESIAN_POINT('',(0.196446609407,-1.05)); +#43414 = CARTESIAN_POINT('',(-2.005974153911E-002,-0.675)); +#43415 = CARTESIAN_POINT('',(-0.236566092485,-0.3)); +#43416 = CARTESIAN_POINT('',(0.196446609407,-0.3)); +#43417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43418 = ORIENTED_EDGE('',*,*,#43419,.F.); +#43419 = EDGE_CURVE('',#43295,#43393,#43420,.T.); +#43420 = SURFACE_CURVE('',#43421,(#43425,#43431),.PCURVE_S1.); +#43421 = LINE('',#43422,#43423); +#43422 = CARTESIAN_POINT('',(2.596446609407,-0.925,-1.53)); +#43423 = VECTOR('',#43424,1.); +#43424 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43425 = PCURVE('',#43172,#43426); +#43426 = DEFINITIONAL_REPRESENTATION('',(#43427),#43430); +#43427 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43428,#43429),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#41036 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#41037 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#41038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41039 = PCURVE('',#38203,#41040); -#41040 = DEFINITIONAL_REPRESENTATION('',(#41041),#41045); -#41041 = LINE('',#41042,#41043); -#41042 = CARTESIAN_POINT('',(0.E+000,0.82)); -#41043 = VECTOR('',#41044,1.); -#41044 = DIRECTION('',(0.E+000,1.)); -#41045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41046 = ADVANCED_FACE('',(#41047),#38203,.T.); -#41047 = FACE_BOUND('',#41048,.F.); -#41048 = EDGE_LOOP('',(#41049,#41079,#41100,#41101,#41124,#41156,#41184, - #41212,#41240,#41272,#41300,#41332,#41360,#41388,#41416,#41441, - #41442,#41443,#41444,#41467,#41494,#41522,#41554,#41582,#41614, - #41642,#41674,#41702,#41734,#41762,#41790,#41822)); -#41049 = ORIENTED_EDGE('',*,*,#41050,.T.); -#41050 = EDGE_CURVE('',#41051,#41053,#41055,.T.); -#41051 = VERTEX_POINT('',#41052); -#41052 = CARTESIAN_POINT('',(1.79,-0.925,-1.15)); -#41053 = VERTEX_POINT('',#41054); -#41054 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); -#41055 = SURFACE_CURVE('',#41056,(#41060,#41067),.PCURVE_S1.); -#41056 = LINE('',#41057,#41058); -#41057 = CARTESIAN_POINT('',(1.79,-0.925,-1.15)); -#41058 = VECTOR('',#41059,1.); -#41059 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41060 = PCURVE('',#38203,#41061); -#41061 = DEFINITIONAL_REPRESENTATION('',(#41062),#41066); -#41062 = LINE('',#41063,#41064); -#41063 = CARTESIAN_POINT('',(0.806446609407,1.2)); -#41064 = VECTOR('',#41065,1.); -#41065 = DIRECTION('',(0.E+000,-1.)); -#41066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41067 = PCURVE('',#41068,#41073); -#41068 = PLANE('',#41069); -#41069 = AXIS2_PLACEMENT_3D('',#41070,#41071,#41072); -#41070 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#41071 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41072 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41073 = DEFINITIONAL_REPRESENTATION('',(#41074),#41078); -#41074 = LINE('',#41075,#41076); -#41075 = CARTESIAN_POINT('',(0.38,-0.3)); -#41076 = VECTOR('',#41077,1.); -#41077 = DIRECTION('',(-1.,0.E+000)); -#41078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41079 = ORIENTED_EDGE('',*,*,#41080,.T.); -#41080 = EDGE_CURVE('',#41053,#40903,#41081,.T.); -#41081 = SURFACE_CURVE('',#41082,(#41086,#41093),.PCURVE_S1.); -#41082 = LINE('',#41083,#41084); -#41083 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); -#41084 = VECTOR('',#41085,1.); -#41085 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41086 = PCURVE('',#38203,#41087); -#41087 = DEFINITIONAL_REPRESENTATION('',(#41088),#41092); -#41088 = LINE('',#41089,#41090); -#41089 = CARTESIAN_POINT('',(0.806446609407,0.82)); -#41090 = VECTOR('',#41091,1.); -#41091 = DIRECTION('',(-1.,0.E+000)); -#41092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41093 = PCURVE('',#40920,#41094); -#41094 = DEFINITIONAL_REPRESENTATION('',(#41095),#41099); -#41095 = LINE('',#41096,#41097); -#41096 = CARTESIAN_POINT('',(5.E-002,5.54)); -#41097 = VECTOR('',#41098,1.); -#41098 = DIRECTION('',(0.E+000,1.)); -#41099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41100 = ORIENTED_EDGE('',*,*,#41027,.T.); -#41101 = ORIENTED_EDGE('',*,*,#41102,.T.); -#41102 = EDGE_CURVE('',#41001,#41103,#41105,.T.); -#41103 = VERTEX_POINT('',#41104); -#41104 = CARTESIAN_POINT('',(2.4,-0.925,-0.56)); -#41105 = SURFACE_CURVE('',#41106,(#41110,#41117),.PCURVE_S1.); -#41106 = LINE('',#41107,#41108); -#41107 = CARTESIAN_POINT('',(2.596446609407,-0.925,-0.56)); -#41108 = VECTOR('',#41109,1.); -#41109 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41110 = PCURVE('',#38203,#41111); -#41111 = DEFINITIONAL_REPRESENTATION('',(#41112),#41116); -#41112 = LINE('',#41113,#41114); -#41113 = CARTESIAN_POINT('',(0.E+000,1.79)); -#41114 = VECTOR('',#41115,1.); -#41115 = DIRECTION('',(1.,0.E+000)); -#41116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41117 = PCURVE('',#40346,#41118); -#41118 = DEFINITIONAL_REPRESENTATION('',(#41119),#41123); -#41119 = LINE('',#41120,#41121); -#41120 = CARTESIAN_POINT('',(0.196446609407,-0.3)); -#41121 = VECTOR('',#41122,1.); -#41122 = DIRECTION('',(-1.,0.E+000)); -#41123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41124 = ORIENTED_EDGE('',*,*,#41125,.F.); -#41125 = EDGE_CURVE('',#41126,#41103,#41128,.T.); -#41126 = VERTEX_POINT('',#41127); -#41127 = CARTESIAN_POINT('',(2.25,-0.925,-0.41)); -#41128 = SURFACE_CURVE('',#41129,(#41134,#41145),.PCURVE_S1.); -#41129 = CIRCLE('',#41130,0.15); -#41130 = AXIS2_PLACEMENT_3D('',#41131,#41132,#41133); -#41131 = CARTESIAN_POINT('',(2.4,-0.925,-0.41)); -#41132 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41133 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41134 = PCURVE('',#38203,#41135); -#41135 = DEFINITIONAL_REPRESENTATION('',(#41136),#41144); -#41136 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41137,#41138,#41139,#41140 - ,#41141,#41142,#41143),.UNSPECIFIED.,.T.,.F.) +#43428 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#43429 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#43430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43431 = PCURVE('',#40595,#43432); +#43432 = DEFINITIONAL_REPRESENTATION('',(#43433),#43437); +#43433 = LINE('',#43434,#43435); +#43434 = CARTESIAN_POINT('',(0.E+000,0.82)); +#43435 = VECTOR('',#43436,1.); +#43436 = DIRECTION('',(0.E+000,1.)); +#43437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43438 = ADVANCED_FACE('',(#43439),#40595,.T.); +#43439 = FACE_BOUND('',#43440,.F.); +#43440 = EDGE_LOOP('',(#43441,#43471,#43492,#43493,#43516,#43548,#43576, + #43604,#43632,#43664,#43692,#43724,#43752,#43780,#43808,#43833, + #43834,#43835,#43836,#43859,#43886,#43914,#43946,#43974,#44006, + #44034,#44066,#44094,#44126,#44154,#44182,#44214)); +#43441 = ORIENTED_EDGE('',*,*,#43442,.T.); +#43442 = EDGE_CURVE('',#43443,#43445,#43447,.T.); +#43443 = VERTEX_POINT('',#43444); +#43444 = CARTESIAN_POINT('',(1.79,-0.925,-1.15)); +#43445 = VERTEX_POINT('',#43446); +#43446 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); +#43447 = SURFACE_CURVE('',#43448,(#43452,#43459),.PCURVE_S1.); +#43448 = LINE('',#43449,#43450); +#43449 = CARTESIAN_POINT('',(1.79,-0.925,-1.15)); +#43450 = VECTOR('',#43451,1.); +#43451 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43452 = PCURVE('',#40595,#43453); +#43453 = DEFINITIONAL_REPRESENTATION('',(#43454),#43458); +#43454 = LINE('',#43455,#43456); +#43455 = CARTESIAN_POINT('',(0.806446609407,1.2)); +#43456 = VECTOR('',#43457,1.); +#43457 = DIRECTION('',(0.E+000,-1.)); +#43458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43459 = PCURVE('',#43460,#43465); +#43460 = PLANE('',#43461); +#43461 = AXIS2_PLACEMENT_3D('',#43462,#43463,#43464); +#43462 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#43463 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43464 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43465 = DEFINITIONAL_REPRESENTATION('',(#43466),#43470); +#43466 = LINE('',#43467,#43468); +#43467 = CARTESIAN_POINT('',(0.38,-0.3)); +#43468 = VECTOR('',#43469,1.); +#43469 = DIRECTION('',(-1.,0.E+000)); +#43470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43471 = ORIENTED_EDGE('',*,*,#43472,.T.); +#43472 = EDGE_CURVE('',#43445,#43295,#43473,.T.); +#43473 = SURFACE_CURVE('',#43474,(#43478,#43485),.PCURVE_S1.); +#43474 = LINE('',#43475,#43476); +#43475 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); +#43476 = VECTOR('',#43477,1.); +#43477 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43478 = PCURVE('',#40595,#43479); +#43479 = DEFINITIONAL_REPRESENTATION('',(#43480),#43484); +#43480 = LINE('',#43481,#43482); +#43481 = CARTESIAN_POINT('',(0.806446609407,0.82)); +#43482 = VECTOR('',#43483,1.); +#43483 = DIRECTION('',(-1.,0.E+000)); +#43484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43485 = PCURVE('',#43312,#43486); +#43486 = DEFINITIONAL_REPRESENTATION('',(#43487),#43491); +#43487 = LINE('',#43488,#43489); +#43488 = CARTESIAN_POINT('',(5.E-002,5.54)); +#43489 = VECTOR('',#43490,1.); +#43490 = DIRECTION('',(0.E+000,1.)); +#43491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43492 = ORIENTED_EDGE('',*,*,#43419,.T.); +#43493 = ORIENTED_EDGE('',*,*,#43494,.T.); +#43494 = EDGE_CURVE('',#43393,#43495,#43497,.T.); +#43495 = VERTEX_POINT('',#43496); +#43496 = CARTESIAN_POINT('',(2.4,-0.925,-0.56)); +#43497 = SURFACE_CURVE('',#43498,(#43502,#43509),.PCURVE_S1.); +#43498 = LINE('',#43499,#43500); +#43499 = CARTESIAN_POINT('',(2.596446609407,-0.925,-0.56)); +#43500 = VECTOR('',#43501,1.); +#43501 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43502 = PCURVE('',#40595,#43503); +#43503 = DEFINITIONAL_REPRESENTATION('',(#43504),#43508); +#43504 = LINE('',#43505,#43506); +#43505 = CARTESIAN_POINT('',(0.E+000,1.79)); +#43506 = VECTOR('',#43507,1.); +#43507 = DIRECTION('',(1.,0.E+000)); +#43508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43509 = PCURVE('',#42738,#43510); +#43510 = DEFINITIONAL_REPRESENTATION('',(#43511),#43515); +#43511 = LINE('',#43512,#43513); +#43512 = CARTESIAN_POINT('',(0.196446609407,-0.3)); +#43513 = VECTOR('',#43514,1.); +#43514 = DIRECTION('',(-1.,0.E+000)); +#43515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43516 = ORIENTED_EDGE('',*,*,#43517,.F.); +#43517 = EDGE_CURVE('',#43518,#43495,#43520,.T.); +#43518 = VERTEX_POINT('',#43519); +#43519 = CARTESIAN_POINT('',(2.25,-0.925,-0.41)); +#43520 = SURFACE_CURVE('',#43521,(#43526,#43537),.PCURVE_S1.); +#43521 = CIRCLE('',#43522,0.15); +#43522 = AXIS2_PLACEMENT_3D('',#43523,#43524,#43525); +#43523 = CARTESIAN_POINT('',(2.4,-0.925,-0.41)); +#43524 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43525 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43526 = PCURVE('',#40595,#43527); +#43527 = DEFINITIONAL_REPRESENTATION('',(#43528),#43536); +#43528 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43529,#43530,#43531,#43532 + ,#43533,#43534,#43535),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41137 = CARTESIAN_POINT('',(0.346446609407,1.94)); -#41138 = CARTESIAN_POINT('',(0.346446609407,1.680192378865)); -#41139 = CARTESIAN_POINT('',(0.121446609407,1.810096189432)); -#41140 = CARTESIAN_POINT('',(-0.103553390593,1.94)); -#41141 = CARTESIAN_POINT('',(0.121446609407,2.069903810568)); -#41142 = CARTESIAN_POINT('',(0.346446609407,2.199807621135)); -#41143 = CARTESIAN_POINT('',(0.346446609407,1.94)); -#41144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41145 = PCURVE('',#41146,#41151); -#41146 = CYLINDRICAL_SURFACE('',#41147,0.15); -#41147 = AXIS2_PLACEMENT_3D('',#41148,#41149,#41150); -#41148 = CARTESIAN_POINT('',(2.4,-1.225,-0.41)); -#41149 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41150 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41151 = DEFINITIONAL_REPRESENTATION('',(#41152),#41155); -#41152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41153,#41154),.UNSPECIFIED., +#43529 = CARTESIAN_POINT('',(0.346446609407,1.94)); +#43530 = CARTESIAN_POINT('',(0.346446609407,1.680192378865)); +#43531 = CARTESIAN_POINT('',(0.121446609407,1.810096189432)); +#43532 = CARTESIAN_POINT('',(-0.103553390593,1.94)); +#43533 = CARTESIAN_POINT('',(0.121446609407,2.069903810568)); +#43534 = CARTESIAN_POINT('',(0.346446609407,2.199807621135)); +#43535 = CARTESIAN_POINT('',(0.346446609407,1.94)); +#43536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43537 = PCURVE('',#43538,#43543); +#43538 = CYLINDRICAL_SURFACE('',#43539,0.15); +#43539 = AXIS2_PLACEMENT_3D('',#43540,#43541,#43542); +#43540 = CARTESIAN_POINT('',(2.4,-1.225,-0.41)); +#43541 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43542 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43543 = DEFINITIONAL_REPRESENTATION('',(#43544),#43547); +#43544 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43545,#43546),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41153 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#41154 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#41155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41156 = ORIENTED_EDGE('',*,*,#41157,.F.); -#41157 = EDGE_CURVE('',#41158,#41126,#41160,.T.); -#41158 = VERTEX_POINT('',#41159); -#41159 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); -#41160 = SURFACE_CURVE('',#41161,(#41165,#41172),.PCURVE_S1.); -#41161 = LINE('',#41162,#41163); -#41162 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); -#41163 = VECTOR('',#41164,1.); -#41164 = DIRECTION('',(0.E+000,-3.330669073875E-014,-1.)); -#41165 = PCURVE('',#38203,#41166); -#41166 = DEFINITIONAL_REPRESENTATION('',(#41167),#41171); -#41167 = LINE('',#41168,#41169); -#41168 = CARTESIAN_POINT('',(0.346446609407,1.95)); -#41169 = VECTOR('',#41170,1.); -#41170 = DIRECTION('',(0.E+000,-1.)); -#41171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41172 = PCURVE('',#41173,#41178); -#41173 = PLANE('',#41174); -#41174 = AXIS2_PLACEMENT_3D('',#41175,#41176,#41177); -#41175 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); -#41176 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41177 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41178 = DEFINITIONAL_REPRESENTATION('',(#41179),#41183); -#41179 = LINE('',#41180,#41181); -#41180 = CARTESIAN_POINT('',(1.21,-0.3)); -#41181 = VECTOR('',#41182,1.); -#41182 = DIRECTION('',(1.,3.330669073875E-014)); -#41183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41184 = ORIENTED_EDGE('',*,*,#41185,.T.); -#41185 = EDGE_CURVE('',#41158,#41186,#41188,.T.); -#41186 = VERTEX_POINT('',#41187); -#41187 = CARTESIAN_POINT('',(2.4,-0.925,-0.25)); -#41188 = SURFACE_CURVE('',#41189,(#41194,#41201),.PCURVE_S1.); -#41189 = CIRCLE('',#41190,0.15); -#41190 = AXIS2_PLACEMENT_3D('',#41191,#41192,#41193); -#41191 = CARTESIAN_POINT('',(2.4,-0.925,-0.4)); -#41192 = DIRECTION('',(0.E+000,1.,0.E+000)); -#41193 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41194 = PCURVE('',#38203,#41195); -#41195 = DEFINITIONAL_REPRESENTATION('',(#41196),#41200); -#41196 = CIRCLE('',#41197,0.15); -#41197 = AXIS2_PLACEMENT_2D('',#41198,#41199); -#41198 = CARTESIAN_POINT('',(0.196446609407,1.95)); -#41199 = DIRECTION('',(1.,0.E+000)); -#41200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41201 = PCURVE('',#41202,#41207); -#41202 = CYLINDRICAL_SURFACE('',#41203,0.15); -#41203 = AXIS2_PLACEMENT_3D('',#41204,#41205,#41206); -#41204 = CARTESIAN_POINT('',(2.4,-1.225,-0.4)); -#41205 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41207 = DEFINITIONAL_REPRESENTATION('',(#41208),#41211); -#41208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41209,#41210),.UNSPECIFIED., +#43545 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#43546 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#43547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43548 = ORIENTED_EDGE('',*,*,#43549,.F.); +#43549 = EDGE_CURVE('',#43550,#43518,#43552,.T.); +#43550 = VERTEX_POINT('',#43551); +#43551 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); +#43552 = SURFACE_CURVE('',#43553,(#43557,#43564),.PCURVE_S1.); +#43553 = LINE('',#43554,#43555); +#43554 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); +#43555 = VECTOR('',#43556,1.); +#43556 = DIRECTION('',(0.E+000,-3.330669073875E-014,-1.)); +#43557 = PCURVE('',#40595,#43558); +#43558 = DEFINITIONAL_REPRESENTATION('',(#43559),#43563); +#43559 = LINE('',#43560,#43561); +#43560 = CARTESIAN_POINT('',(0.346446609407,1.95)); +#43561 = VECTOR('',#43562,1.); +#43562 = DIRECTION('',(0.E+000,-1.)); +#43563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43564 = PCURVE('',#43565,#43570); +#43565 = PLANE('',#43566); +#43566 = AXIS2_PLACEMENT_3D('',#43567,#43568,#43569); +#43567 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); +#43568 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43569 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43570 = DEFINITIONAL_REPRESENTATION('',(#43571),#43575); +#43571 = LINE('',#43572,#43573); +#43572 = CARTESIAN_POINT('',(1.21,-0.3)); +#43573 = VECTOR('',#43574,1.); +#43574 = DIRECTION('',(1.,3.330669073875E-014)); +#43575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43576 = ORIENTED_EDGE('',*,*,#43577,.T.); +#43577 = EDGE_CURVE('',#43550,#43578,#43580,.T.); +#43578 = VERTEX_POINT('',#43579); +#43579 = CARTESIAN_POINT('',(2.4,-0.925,-0.25)); +#43580 = SURFACE_CURVE('',#43581,(#43586,#43593),.PCURVE_S1.); +#43581 = CIRCLE('',#43582,0.15); +#43582 = AXIS2_PLACEMENT_3D('',#43583,#43584,#43585); +#43583 = CARTESIAN_POINT('',(2.4,-0.925,-0.4)); +#43584 = DIRECTION('',(0.E+000,1.,0.E+000)); +#43585 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43586 = PCURVE('',#40595,#43587); +#43587 = DEFINITIONAL_REPRESENTATION('',(#43588),#43592); +#43588 = CIRCLE('',#43589,0.15); +#43589 = AXIS2_PLACEMENT_2D('',#43590,#43591); +#43590 = CARTESIAN_POINT('',(0.196446609407,1.95)); +#43591 = DIRECTION('',(1.,0.E+000)); +#43592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43593 = PCURVE('',#43594,#43599); +#43594 = CYLINDRICAL_SURFACE('',#43595,0.15); +#43595 = AXIS2_PLACEMENT_3D('',#43596,#43597,#43598); +#43596 = CARTESIAN_POINT('',(2.4,-1.225,-0.4)); +#43597 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43599 = DEFINITIONAL_REPRESENTATION('',(#43600),#43603); +#43600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43601,#43602),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41209 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#41210 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#41211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41212 = ORIENTED_EDGE('',*,*,#41213,.T.); -#41213 = EDGE_CURVE('',#41186,#41214,#41216,.T.); -#41214 = VERTEX_POINT('',#41215); -#41215 = CARTESIAN_POINT('',(3.7,-0.925,-0.25)); -#41216 = SURFACE_CURVE('',#41217,(#41221,#41228),.PCURVE_S1.); -#41217 = LINE('',#41218,#41219); -#41218 = CARTESIAN_POINT('',(2.4,-0.925,-0.25)); -#41219 = VECTOR('',#41220,1.); -#41220 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41221 = PCURVE('',#38203,#41222); -#41222 = DEFINITIONAL_REPRESENTATION('',(#41223),#41227); -#41223 = LINE('',#41224,#41225); -#41224 = CARTESIAN_POINT('',(0.196446609407,2.1)); -#41225 = VECTOR('',#41226,1.); -#41226 = DIRECTION('',(-1.,0.E+000)); -#41227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41228 = PCURVE('',#41229,#41234); -#41229 = PLANE('',#41230); -#41230 = AXIS2_PLACEMENT_3D('',#41231,#41232,#41233); -#41231 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); -#41232 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41233 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41234 = DEFINITIONAL_REPRESENTATION('',(#41235),#41239); -#41235 = LINE('',#41236,#41237); -#41236 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41237 = VECTOR('',#41238,1.); -#41238 = DIRECTION('',(1.,0.E+000)); -#41239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41240 = ORIENTED_EDGE('',*,*,#41241,.T.); -#41241 = EDGE_CURVE('',#41214,#41242,#41244,.T.); -#41242 = VERTEX_POINT('',#41243); -#41243 = CARTESIAN_POINT('',(3.9,-0.925,-5.E-002)); -#41244 = SURFACE_CURVE('',#41245,(#41250,#41261),.PCURVE_S1.); -#41245 = CIRCLE('',#41246,0.2); -#41246 = AXIS2_PLACEMENT_3D('',#41247,#41248,#41249); -#41247 = CARTESIAN_POINT('',(3.7,-0.925,-5.E-002)); -#41248 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41249 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41250 = PCURVE('',#38203,#41251); -#41251 = DEFINITIONAL_REPRESENTATION('',(#41252),#41260); -#41252 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41253,#41254,#41255,#41256 - ,#41257,#41258,#41259),.UNSPECIFIED.,.F.,.F.) +#43601 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#43602 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#43603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43604 = ORIENTED_EDGE('',*,*,#43605,.T.); +#43605 = EDGE_CURVE('',#43578,#43606,#43608,.T.); +#43606 = VERTEX_POINT('',#43607); +#43607 = CARTESIAN_POINT('',(3.7,-0.925,-0.25)); +#43608 = SURFACE_CURVE('',#43609,(#43613,#43620),.PCURVE_S1.); +#43609 = LINE('',#43610,#43611); +#43610 = CARTESIAN_POINT('',(2.4,-0.925,-0.25)); +#43611 = VECTOR('',#43612,1.); +#43612 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43613 = PCURVE('',#40595,#43614); +#43614 = DEFINITIONAL_REPRESENTATION('',(#43615),#43619); +#43615 = LINE('',#43616,#43617); +#43616 = CARTESIAN_POINT('',(0.196446609407,2.1)); +#43617 = VECTOR('',#43618,1.); +#43618 = DIRECTION('',(-1.,0.E+000)); +#43619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43620 = PCURVE('',#43621,#43626); +#43621 = PLANE('',#43622); +#43622 = AXIS2_PLACEMENT_3D('',#43623,#43624,#43625); +#43623 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); +#43624 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43625 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43626 = DEFINITIONAL_REPRESENTATION('',(#43627),#43631); +#43627 = LINE('',#43628,#43629); +#43628 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#43629 = VECTOR('',#43630,1.); +#43630 = DIRECTION('',(1.,0.E+000)); +#43631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43632 = ORIENTED_EDGE('',*,*,#43633,.T.); +#43633 = EDGE_CURVE('',#43606,#43634,#43636,.T.); +#43634 = VERTEX_POINT('',#43635); +#43635 = CARTESIAN_POINT('',(3.9,-0.925,-5.E-002)); +#43636 = SURFACE_CURVE('',#43637,(#43642,#43653),.PCURVE_S1.); +#43637 = CIRCLE('',#43638,0.2); +#43638 = AXIS2_PLACEMENT_3D('',#43639,#43640,#43641); +#43639 = CARTESIAN_POINT('',(3.7,-0.925,-5.E-002)); +#43640 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43641 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43642 = PCURVE('',#40595,#43643); +#43643 = DEFINITIONAL_REPRESENTATION('',(#43644),#43652); +#43644 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43645,#43646,#43647,#43648 + ,#43649,#43650,#43651),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41253 = CARTESIAN_POINT('',(-1.103553390593,2.1)); -#41254 = CARTESIAN_POINT('',(-1.449963552107,2.1)); -#41255 = CARTESIAN_POINT('',(-1.27675847135,2.4)); -#41256 = CARTESIAN_POINT('',(-1.103553390593,2.7)); -#41257 = CARTESIAN_POINT('',(-0.930348309836,2.4)); -#41258 = CARTESIAN_POINT('',(-0.757143229079,2.1)); -#41259 = CARTESIAN_POINT('',(-1.103553390593,2.1)); -#41260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41261 = PCURVE('',#41262,#41267); -#41262 = CYLINDRICAL_SURFACE('',#41263,0.2); -#41263 = AXIS2_PLACEMENT_3D('',#41264,#41265,#41266); -#41264 = CARTESIAN_POINT('',(3.7,-1.225,-5.E-002)); -#41265 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41266 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41267 = DEFINITIONAL_REPRESENTATION('',(#41268),#41271); -#41268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41269,#41270),.UNSPECIFIED., +#43645 = CARTESIAN_POINT('',(-1.103553390593,2.1)); +#43646 = CARTESIAN_POINT('',(-1.449963552107,2.1)); +#43647 = CARTESIAN_POINT('',(-1.27675847135,2.4)); +#43648 = CARTESIAN_POINT('',(-1.103553390593,2.7)); +#43649 = CARTESIAN_POINT('',(-0.930348309836,2.4)); +#43650 = CARTESIAN_POINT('',(-0.757143229079,2.1)); +#43651 = CARTESIAN_POINT('',(-1.103553390593,2.1)); +#43652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43653 = PCURVE('',#43654,#43659); +#43654 = CYLINDRICAL_SURFACE('',#43655,0.2); +#43655 = AXIS2_PLACEMENT_3D('',#43656,#43657,#43658); +#43656 = CARTESIAN_POINT('',(3.7,-1.225,-5.E-002)); +#43657 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43658 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43659 = DEFINITIONAL_REPRESENTATION('',(#43660),#43663); +#43660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43661,#43662),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41269 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#41270 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#41271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41272 = ORIENTED_EDGE('',*,*,#41273,.T.); -#41273 = EDGE_CURVE('',#41242,#41274,#41276,.T.); -#41274 = VERTEX_POINT('',#41275); -#41275 = CARTESIAN_POINT('',(3.9,-0.925,0.45)); -#41276 = SURFACE_CURVE('',#41277,(#41281,#41288),.PCURVE_S1.); -#41277 = LINE('',#41278,#41279); -#41278 = CARTESIAN_POINT('',(3.9,-0.925,-5.E-002)); -#41279 = VECTOR('',#41280,1.); -#41280 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41281 = PCURVE('',#38203,#41282); -#41282 = DEFINITIONAL_REPRESENTATION('',(#41283),#41287); -#41283 = LINE('',#41284,#41285); -#41284 = CARTESIAN_POINT('',(-1.303553390593,2.3)); -#41285 = VECTOR('',#41286,1.); -#41286 = DIRECTION('',(0.E+000,1.)); -#41287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41288 = PCURVE('',#41289,#41294); -#41289 = PLANE('',#41290); -#41290 = AXIS2_PLACEMENT_3D('',#41291,#41292,#41293); -#41291 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); -#41292 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41293 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41294 = DEFINITIONAL_REPRESENTATION('',(#41295),#41299); -#41295 = LINE('',#41296,#41297); -#41296 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41297 = VECTOR('',#41298,1.); -#41298 = DIRECTION('',(1.,0.E+000)); -#41299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41300 = ORIENTED_EDGE('',*,*,#41301,.T.); -#41301 = EDGE_CURVE('',#41274,#41302,#41304,.T.); -#41302 = VERTEX_POINT('',#41303); -#41303 = CARTESIAN_POINT('',(3.7,-0.925,0.65)); -#41304 = SURFACE_CURVE('',#41305,(#41310,#41321),.PCURVE_S1.); -#41305 = CIRCLE('',#41306,0.2); -#41306 = AXIS2_PLACEMENT_3D('',#41307,#41308,#41309); -#41307 = CARTESIAN_POINT('',(3.7,-0.925,0.45)); -#41308 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41309 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41310 = PCURVE('',#38203,#41311); -#41311 = DEFINITIONAL_REPRESENTATION('',(#41312),#41320); -#41312 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41313,#41314,#41315,#41316 - ,#41317,#41318,#41319),.UNSPECIFIED.,.T.,.F.) +#43661 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#43662 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#43663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43664 = ORIENTED_EDGE('',*,*,#43665,.T.); +#43665 = EDGE_CURVE('',#43634,#43666,#43668,.T.); +#43666 = VERTEX_POINT('',#43667); +#43667 = CARTESIAN_POINT('',(3.9,-0.925,0.45)); +#43668 = SURFACE_CURVE('',#43669,(#43673,#43680),.PCURVE_S1.); +#43669 = LINE('',#43670,#43671); +#43670 = CARTESIAN_POINT('',(3.9,-0.925,-5.E-002)); +#43671 = VECTOR('',#43672,1.); +#43672 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43673 = PCURVE('',#40595,#43674); +#43674 = DEFINITIONAL_REPRESENTATION('',(#43675),#43679); +#43675 = LINE('',#43676,#43677); +#43676 = CARTESIAN_POINT('',(-1.303553390593,2.3)); +#43677 = VECTOR('',#43678,1.); +#43678 = DIRECTION('',(0.E+000,1.)); +#43679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43680 = PCURVE('',#43681,#43686); +#43681 = PLANE('',#43682); +#43682 = AXIS2_PLACEMENT_3D('',#43683,#43684,#43685); +#43683 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); +#43684 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43685 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43686 = DEFINITIONAL_REPRESENTATION('',(#43687),#43691); +#43687 = LINE('',#43688,#43689); +#43688 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#43689 = VECTOR('',#43690,1.); +#43690 = DIRECTION('',(1.,0.E+000)); +#43691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43692 = ORIENTED_EDGE('',*,*,#43693,.T.); +#43693 = EDGE_CURVE('',#43666,#43694,#43696,.T.); +#43694 = VERTEX_POINT('',#43695); +#43695 = CARTESIAN_POINT('',(3.7,-0.925,0.65)); +#43696 = SURFACE_CURVE('',#43697,(#43702,#43713),.PCURVE_S1.); +#43697 = CIRCLE('',#43698,0.2); +#43698 = AXIS2_PLACEMENT_3D('',#43699,#43700,#43701); +#43699 = CARTESIAN_POINT('',(3.7,-0.925,0.45)); +#43700 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43701 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43702 = PCURVE('',#40595,#43703); +#43703 = DEFINITIONAL_REPRESENTATION('',(#43704),#43712); +#43704 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43705,#43706,#43707,#43708 + ,#43709,#43710,#43711),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41313 = CARTESIAN_POINT('',(-1.303553390593,2.8)); -#41314 = CARTESIAN_POINT('',(-1.303553390593,3.146410161514)); -#41315 = CARTESIAN_POINT('',(-1.003553390593,2.973205080757)); -#41316 = CARTESIAN_POINT('',(-0.703553390593,2.8)); -#41317 = CARTESIAN_POINT('',(-1.003553390593,2.626794919243)); -#41318 = CARTESIAN_POINT('',(-1.303553390593,2.453589838486)); -#41319 = CARTESIAN_POINT('',(-1.303553390593,2.8)); -#41320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41321 = PCURVE('',#41322,#41327); -#41322 = CYLINDRICAL_SURFACE('',#41323,0.2); -#41323 = AXIS2_PLACEMENT_3D('',#41324,#41325,#41326); -#41324 = CARTESIAN_POINT('',(3.7,-1.225,0.45)); -#41325 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41326 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41327 = DEFINITIONAL_REPRESENTATION('',(#41328),#41331); -#41328 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41329,#41330),.UNSPECIFIED., +#43705 = CARTESIAN_POINT('',(-1.303553390593,2.8)); +#43706 = CARTESIAN_POINT('',(-1.303553390593,3.146410161514)); +#43707 = CARTESIAN_POINT('',(-1.003553390593,2.973205080757)); +#43708 = CARTESIAN_POINT('',(-0.703553390593,2.8)); +#43709 = CARTESIAN_POINT('',(-1.003553390593,2.626794919243)); +#43710 = CARTESIAN_POINT('',(-1.303553390593,2.453589838486)); +#43711 = CARTESIAN_POINT('',(-1.303553390593,2.8)); +#43712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43713 = PCURVE('',#43714,#43719); +#43714 = CYLINDRICAL_SURFACE('',#43715,0.2); +#43715 = AXIS2_PLACEMENT_3D('',#43716,#43717,#43718); +#43716 = CARTESIAN_POINT('',(3.7,-1.225,0.45)); +#43717 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43718 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43719 = DEFINITIONAL_REPRESENTATION('',(#43720),#43723); +#43720 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43721,#43722),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41329 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41330 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#41331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41332 = ORIENTED_EDGE('',*,*,#41333,.T.); -#41333 = EDGE_CURVE('',#41302,#41334,#41336,.T.); -#41334 = VERTEX_POINT('',#41335); -#41335 = CARTESIAN_POINT('',(2.4,-0.925,0.65)); -#41336 = SURFACE_CURVE('',#41337,(#41341,#41348),.PCURVE_S1.); -#41337 = LINE('',#41338,#41339); -#41338 = CARTESIAN_POINT('',(3.7,-0.925,0.65)); -#41339 = VECTOR('',#41340,1.); -#41340 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41341 = PCURVE('',#38203,#41342); -#41342 = DEFINITIONAL_REPRESENTATION('',(#41343),#41347); -#41343 = LINE('',#41344,#41345); -#41344 = CARTESIAN_POINT('',(-1.103553390593,3.)); -#41345 = VECTOR('',#41346,1.); -#41346 = DIRECTION('',(1.,0.E+000)); -#41347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41348 = PCURVE('',#41349,#41354); -#41349 = PLANE('',#41350); -#41350 = AXIS2_PLACEMENT_3D('',#41351,#41352,#41353); -#41351 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); -#41352 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41353 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41354 = DEFINITIONAL_REPRESENTATION('',(#41355),#41359); -#41355 = LINE('',#41356,#41357); -#41356 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41357 = VECTOR('',#41358,1.); -#41358 = DIRECTION('',(1.,0.E+000)); -#41359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41360 = ORIENTED_EDGE('',*,*,#41361,.T.); -#41361 = EDGE_CURVE('',#41334,#41362,#41364,.T.); -#41362 = VERTEX_POINT('',#41363); -#41363 = CARTESIAN_POINT('',(2.25,-0.925,0.8)); -#41364 = SURFACE_CURVE('',#41365,(#41370,#41377),.PCURVE_S1.); -#41365 = CIRCLE('',#41366,0.15); -#41366 = AXIS2_PLACEMENT_3D('',#41367,#41368,#41369); -#41367 = CARTESIAN_POINT('',(2.4,-0.925,0.8)); -#41368 = DIRECTION('',(0.E+000,1.,0.E+000)); -#41369 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41370 = PCURVE('',#38203,#41371); -#41371 = DEFINITIONAL_REPRESENTATION('',(#41372),#41376); -#41372 = CIRCLE('',#41373,0.15); -#41373 = AXIS2_PLACEMENT_2D('',#41374,#41375); -#41374 = CARTESIAN_POINT('',(0.196446609407,3.15)); -#41375 = DIRECTION('',(0.E+000,-1.)); -#41376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41377 = PCURVE('',#41378,#41383); -#41378 = CYLINDRICAL_SURFACE('',#41379,0.15); -#41379 = AXIS2_PLACEMENT_3D('',#41380,#41381,#41382); -#41380 = CARTESIAN_POINT('',(2.4,-1.225,0.8)); -#41381 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41382 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41383 = DEFINITIONAL_REPRESENTATION('',(#41384),#41387); -#41384 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41385,#41386),.UNSPECIFIED., +#43721 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#43722 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#43723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43724 = ORIENTED_EDGE('',*,*,#43725,.T.); +#43725 = EDGE_CURVE('',#43694,#43726,#43728,.T.); +#43726 = VERTEX_POINT('',#43727); +#43727 = CARTESIAN_POINT('',(2.4,-0.925,0.65)); +#43728 = SURFACE_CURVE('',#43729,(#43733,#43740),.PCURVE_S1.); +#43729 = LINE('',#43730,#43731); +#43730 = CARTESIAN_POINT('',(3.7,-0.925,0.65)); +#43731 = VECTOR('',#43732,1.); +#43732 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43733 = PCURVE('',#40595,#43734); +#43734 = DEFINITIONAL_REPRESENTATION('',(#43735),#43739); +#43735 = LINE('',#43736,#43737); +#43736 = CARTESIAN_POINT('',(-1.103553390593,3.)); +#43737 = VECTOR('',#43738,1.); +#43738 = DIRECTION('',(1.,0.E+000)); +#43739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43740 = PCURVE('',#43741,#43746); +#43741 = PLANE('',#43742); +#43742 = AXIS2_PLACEMENT_3D('',#43743,#43744,#43745); +#43743 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); +#43744 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43745 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43746 = DEFINITIONAL_REPRESENTATION('',(#43747),#43751); +#43747 = LINE('',#43748,#43749); +#43748 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#43749 = VECTOR('',#43750,1.); +#43750 = DIRECTION('',(1.,0.E+000)); +#43751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43752 = ORIENTED_EDGE('',*,*,#43753,.T.); +#43753 = EDGE_CURVE('',#43726,#43754,#43756,.T.); +#43754 = VERTEX_POINT('',#43755); +#43755 = CARTESIAN_POINT('',(2.25,-0.925,0.8)); +#43756 = SURFACE_CURVE('',#43757,(#43762,#43769),.PCURVE_S1.); +#43757 = CIRCLE('',#43758,0.15); +#43758 = AXIS2_PLACEMENT_3D('',#43759,#43760,#43761); +#43759 = CARTESIAN_POINT('',(2.4,-0.925,0.8)); +#43760 = DIRECTION('',(0.E+000,1.,0.E+000)); +#43761 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43762 = PCURVE('',#40595,#43763); +#43763 = DEFINITIONAL_REPRESENTATION('',(#43764),#43768); +#43764 = CIRCLE('',#43765,0.15); +#43765 = AXIS2_PLACEMENT_2D('',#43766,#43767); +#43766 = CARTESIAN_POINT('',(0.196446609407,3.15)); +#43767 = DIRECTION('',(0.E+000,-1.)); +#43768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43769 = PCURVE('',#43770,#43775); +#43770 = CYLINDRICAL_SURFACE('',#43771,0.15); +#43771 = AXIS2_PLACEMENT_3D('',#43772,#43773,#43774); +#43772 = CARTESIAN_POINT('',(2.4,-1.225,0.8)); +#43773 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43774 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43775 = DEFINITIONAL_REPRESENTATION('',(#43776),#43779); +#43776 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43777,#43778),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41385 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#41386 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#41387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41388 = ORIENTED_EDGE('',*,*,#41389,.F.); -#41389 = EDGE_CURVE('',#41390,#41362,#41392,.T.); -#41390 = VERTEX_POINT('',#41391); -#41391 = CARTESIAN_POINT('',(2.25,-0.925,0.81)); -#41392 = SURFACE_CURVE('',#41393,(#41397,#41404),.PCURVE_S1.); -#41393 = LINE('',#41394,#41395); -#41394 = CARTESIAN_POINT('',(2.25,-0.925,0.81)); -#41395 = VECTOR('',#41396,1.); -#41396 = DIRECTION('',(0.E+000,3.330669073875E-014,-1.)); -#41397 = PCURVE('',#38203,#41398); -#41398 = DEFINITIONAL_REPRESENTATION('',(#41399),#41403); -#41399 = LINE('',#41400,#41401); -#41400 = CARTESIAN_POINT('',(0.346446609407,3.16)); -#41401 = VECTOR('',#41402,1.); -#41402 = DIRECTION('',(0.E+000,-1.)); -#41403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41404 = PCURVE('',#41405,#41410); -#41405 = PLANE('',#41406); -#41406 = AXIS2_PLACEMENT_3D('',#41407,#41408,#41409); -#41407 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); -#41408 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41409 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41410 = DEFINITIONAL_REPRESENTATION('',(#41411),#41415); -#41411 = LINE('',#41412,#41413); -#41412 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41413 = VECTOR('',#41414,1.); -#41414 = DIRECTION('',(1.,-3.330669073875E-014)); -#41415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41416 = ORIENTED_EDGE('',*,*,#41417,.F.); -#41417 = EDGE_CURVE('',#40489,#41390,#41418,.T.); -#41418 = SURFACE_CURVE('',#41419,(#41424,#41435),.PCURVE_S1.); -#41419 = CIRCLE('',#41420,0.15); -#41420 = AXIS2_PLACEMENT_3D('',#41421,#41422,#41423); -#41421 = CARTESIAN_POINT('',(2.4,-0.925,0.81)); -#41422 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41423 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41424 = PCURVE('',#38203,#41425); -#41425 = DEFINITIONAL_REPRESENTATION('',(#41426),#41434); -#41426 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41427,#41428,#41429,#41430 - ,#41431,#41432,#41433),.UNSPECIFIED.,.F.,.F.) +#43777 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#43778 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#43779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43780 = ORIENTED_EDGE('',*,*,#43781,.F.); +#43781 = EDGE_CURVE('',#43782,#43754,#43784,.T.); +#43782 = VERTEX_POINT('',#43783); +#43783 = CARTESIAN_POINT('',(2.25,-0.925,0.81)); +#43784 = SURFACE_CURVE('',#43785,(#43789,#43796),.PCURVE_S1.); +#43785 = LINE('',#43786,#43787); +#43786 = CARTESIAN_POINT('',(2.25,-0.925,0.81)); +#43787 = VECTOR('',#43788,1.); +#43788 = DIRECTION('',(0.E+000,3.330669073875E-014,-1.)); +#43789 = PCURVE('',#40595,#43790); +#43790 = DEFINITIONAL_REPRESENTATION('',(#43791),#43795); +#43791 = LINE('',#43792,#43793); +#43792 = CARTESIAN_POINT('',(0.346446609407,3.16)); +#43793 = VECTOR('',#43794,1.); +#43794 = DIRECTION('',(0.E+000,-1.)); +#43795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43796 = PCURVE('',#43797,#43802); +#43797 = PLANE('',#43798); +#43798 = AXIS2_PLACEMENT_3D('',#43799,#43800,#43801); +#43799 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); +#43800 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43801 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43802 = DEFINITIONAL_REPRESENTATION('',(#43803),#43807); +#43803 = LINE('',#43804,#43805); +#43804 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#43805 = VECTOR('',#43806,1.); +#43806 = DIRECTION('',(1.,-3.330669073875E-014)); +#43807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43808 = ORIENTED_EDGE('',*,*,#43809,.F.); +#43809 = EDGE_CURVE('',#42881,#43782,#43810,.T.); +#43810 = SURFACE_CURVE('',#43811,(#43816,#43827),.PCURVE_S1.); +#43811 = CIRCLE('',#43812,0.15); +#43812 = AXIS2_PLACEMENT_3D('',#43813,#43814,#43815); +#43813 = CARTESIAN_POINT('',(2.4,-0.925,0.81)); +#43814 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43815 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43816 = PCURVE('',#40595,#43817); +#43817 = DEFINITIONAL_REPRESENTATION('',(#43818),#43826); +#43818 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43819,#43820,#43821,#43822 + ,#43823,#43824,#43825),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41427 = CARTESIAN_POINT('',(0.196446609407,3.31)); -#41428 = CARTESIAN_POINT('',(0.456254230542,3.31)); -#41429 = CARTESIAN_POINT('',(0.326350419975,3.085)); -#41430 = CARTESIAN_POINT('',(0.196446609407,2.86)); -#41431 = CARTESIAN_POINT('',(6.654279883933E-002,3.085)); -#41432 = CARTESIAN_POINT('',(-6.336101172833E-002,3.31)); -#41433 = CARTESIAN_POINT('',(0.196446609407,3.31)); -#41434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41435 = PCURVE('',#40527,#41436); -#41436 = DEFINITIONAL_REPRESENTATION('',(#41437),#41440); -#41437 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41438,#41439),.UNSPECIFIED., +#43819 = CARTESIAN_POINT('',(0.196446609407,3.31)); +#43820 = CARTESIAN_POINT('',(0.456254230542,3.31)); +#43821 = CARTESIAN_POINT('',(0.326350419975,3.085)); +#43822 = CARTESIAN_POINT('',(0.196446609407,2.86)); +#43823 = CARTESIAN_POINT('',(6.654279883933E-002,3.085)); +#43824 = CARTESIAN_POINT('',(-6.336101172833E-002,3.31)); +#43825 = CARTESIAN_POINT('',(0.196446609407,3.31)); +#43826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43827 = PCURVE('',#42919,#43828); +#43828 = DEFINITIONAL_REPRESENTATION('',(#43829),#43832); +#43829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43830,#43831),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#41438 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#41439 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#41440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41441 = ORIENTED_EDGE('',*,*,#40488,.F.); -#41442 = ORIENTED_EDGE('',*,*,#40879,.T.); -#41443 = ORIENTED_EDGE('',*,*,#38187,.T.); -#41444 = ORIENTED_EDGE('',*,*,#41445,.F.); -#41445 = EDGE_CURVE('',#41446,#38160,#41448,.T.); -#41446 = VERTEX_POINT('',#41447); -#41447 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); -#41448 = SURFACE_CURVE('',#41449,(#41453,#41460),.PCURVE_S1.); -#41449 = LINE('',#41450,#41451); -#41450 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); -#41451 = VECTOR('',#41452,1.); -#41452 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41453 = PCURVE('',#38203,#41454); -#41454 = DEFINITIONAL_REPRESENTATION('',(#41455),#41459); -#41455 = LINE('',#41456,#41457); -#41456 = CARTESIAN_POINT('',(9.6446609407E-002,4.704813742174)); -#41457 = VECTOR('',#41458,1.); -#41458 = DIRECTION('',(0.E+000,-1.)); -#41459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41460 = PCURVE('',#38175,#41461); -#41461 = DEFINITIONAL_REPRESENTATION('',(#41462),#41466); -#41462 = LINE('',#41463,#41464); -#41463 = CARTESIAN_POINT('',(2.354813742174,-0.925)); -#41464 = VECTOR('',#41465,1.); -#41465 = DIRECTION('',(-1.,0.E+000)); -#41466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41467 = ORIENTED_EDGE('',*,*,#41468,.T.); -#41468 = EDGE_CURVE('',#41446,#41469,#41471,.T.); -#41469 = VERTEX_POINT('',#41470); -#41470 = CARTESIAN_POINT('',(1.E-002,-0.925,2.354813742174)); -#41471 = SURFACE_CURVE('',#41472,(#41476,#41483),.PCURVE_S1.); -#41472 = LINE('',#41473,#41474); -#41473 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); -#41474 = VECTOR('',#41475,1.); -#41475 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41476 = PCURVE('',#38203,#41477); -#41477 = DEFINITIONAL_REPRESENTATION('',(#41478),#41482); -#41478 = LINE('',#41479,#41480); -#41479 = CARTESIAN_POINT('',(9.6446609407E-002,4.704813742174)); -#41480 = VECTOR('',#41481,1.); -#41481 = DIRECTION('',(1.,0.E+000)); -#41482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41483 = PCURVE('',#41484,#41489); -#41484 = CYLINDRICAL_SURFACE('',#41485,0.29); -#41485 = AXIS2_PLACEMENT_3D('',#41486,#41487,#41488); -#41486 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); -#41487 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41488 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41489 = DEFINITIONAL_REPRESENTATION('',(#41490),#41493); -#41490 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41491,#41492),.UNSPECIFIED., +#43830 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#43831 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#43832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43833 = ORIENTED_EDGE('',*,*,#42880,.F.); +#43834 = ORIENTED_EDGE('',*,*,#43271,.T.); +#43835 = ORIENTED_EDGE('',*,*,#40579,.T.); +#43836 = ORIENTED_EDGE('',*,*,#43837,.F.); +#43837 = EDGE_CURVE('',#43838,#40552,#43840,.T.); +#43838 = VERTEX_POINT('',#43839); +#43839 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); +#43840 = SURFACE_CURVE('',#43841,(#43845,#43852),.PCURVE_S1.); +#43841 = LINE('',#43842,#43843); +#43842 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); +#43843 = VECTOR('',#43844,1.); +#43844 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43845 = PCURVE('',#40595,#43846); +#43846 = DEFINITIONAL_REPRESENTATION('',(#43847),#43851); +#43847 = LINE('',#43848,#43849); +#43848 = CARTESIAN_POINT('',(9.6446609407E-002,4.704813742174)); +#43849 = VECTOR('',#43850,1.); +#43850 = DIRECTION('',(0.E+000,-1.)); +#43851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43852 = PCURVE('',#40567,#43853); +#43853 = DEFINITIONAL_REPRESENTATION('',(#43854),#43858); +#43854 = LINE('',#43855,#43856); +#43855 = CARTESIAN_POINT('',(2.354813742174,-0.925)); +#43856 = VECTOR('',#43857,1.); +#43857 = DIRECTION('',(-1.,0.E+000)); +#43858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43859 = ORIENTED_EDGE('',*,*,#43860,.T.); +#43860 = EDGE_CURVE('',#43838,#43861,#43863,.T.); +#43861 = VERTEX_POINT('',#43862); +#43862 = CARTESIAN_POINT('',(1.E-002,-0.925,2.354813742174)); +#43863 = SURFACE_CURVE('',#43864,(#43868,#43875),.PCURVE_S1.); +#43864 = LINE('',#43865,#43866); +#43865 = CARTESIAN_POINT('',(2.5,-0.925,2.354813742174)); +#43866 = VECTOR('',#43867,1.); +#43867 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43868 = PCURVE('',#40595,#43869); +#43869 = DEFINITIONAL_REPRESENTATION('',(#43870),#43874); +#43870 = LINE('',#43871,#43872); +#43871 = CARTESIAN_POINT('',(9.6446609407E-002,4.704813742174)); +#43872 = VECTOR('',#43873,1.); +#43873 = DIRECTION('',(1.,0.E+000)); +#43874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43875 = PCURVE('',#43876,#43881); +#43876 = CYLINDRICAL_SURFACE('',#43877,0.29); +#43877 = AXIS2_PLACEMENT_3D('',#43878,#43879,#43880); +#43878 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); +#43879 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43880 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43881 = DEFINITIONAL_REPRESENTATION('',(#43882),#43885); +#43882 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43883,#43884),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.49),.PIECEWISE_BEZIER_KNOTS.); -#41491 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#41492 = CARTESIAN_POINT('',(1.570796326795,2.49)); -#41493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41494 = ORIENTED_EDGE('',*,*,#41495,.T.); -#41495 = EDGE_CURVE('',#41469,#41496,#41498,.T.); -#41496 = VERTEX_POINT('',#41497); -#41497 = CARTESIAN_POINT('',(1.E-002,-0.925,1.74515457349)); -#41498 = SURFACE_CURVE('',#41499,(#41503,#41510),.PCURVE_S1.); -#41499 = LINE('',#41500,#41501); -#41500 = CARTESIAN_POINT('',(1.E-002,-0.925,2.354813742174)); -#41501 = VECTOR('',#41502,1.); -#41502 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41503 = PCURVE('',#38203,#41504); -#41504 = DEFINITIONAL_REPRESENTATION('',(#41505),#41509); -#41505 = LINE('',#41506,#41507); -#41506 = CARTESIAN_POINT('',(2.586446609407,4.704813742174)); -#41507 = VECTOR('',#41508,1.); -#41508 = DIRECTION('',(0.E+000,-1.)); -#41509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41510 = PCURVE('',#41511,#41516); -#41511 = PLANE('',#41512); -#41512 = AXIS2_PLACEMENT_3D('',#41513,#41514,#41515); -#41513 = CARTESIAN_POINT('',(1.E-002,-1.525,1.74515457349)); -#41514 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41515 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41516 = DEFINITIONAL_REPRESENTATION('',(#41517),#41521); -#41517 = LINE('',#41518,#41519); -#41518 = CARTESIAN_POINT('',(0.609659168684,-0.6)); -#41519 = VECTOR('',#41520,1.); -#41520 = DIRECTION('',(-1.,0.E+000)); -#41521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41522 = ORIENTED_EDGE('',*,*,#41523,.T.); -#41523 = EDGE_CURVE('',#41496,#41524,#41526,.T.); -#41524 = VERTEX_POINT('',#41525); -#41525 = CARTESIAN_POINT('',(0.229314035204,-0.925,1.629788704102)); -#41526 = SURFACE_CURVE('',#41527,(#41532,#41543),.PCURVE_S1.); -#41527 = CIRCLE('',#41528,0.14); -#41528 = AXIS2_PLACEMENT_3D('',#41529,#41530,#41531); -#41529 = CARTESIAN_POINT('',(0.15,-0.925,1.74515457349)); -#41530 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41531 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41532 = PCURVE('',#38203,#41533); -#41533 = DEFINITIONAL_REPRESENTATION('',(#41534),#41542); -#41534 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41535,#41536,#41537,#41538 - ,#41539,#41540,#41541),.UNSPECIFIED.,.T.,.F.) +#43883 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#43884 = CARTESIAN_POINT('',(1.570796326795,2.49)); +#43885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43886 = ORIENTED_EDGE('',*,*,#43887,.T.); +#43887 = EDGE_CURVE('',#43861,#43888,#43890,.T.); +#43888 = VERTEX_POINT('',#43889); +#43889 = CARTESIAN_POINT('',(1.E-002,-0.925,1.74515457349)); +#43890 = SURFACE_CURVE('',#43891,(#43895,#43902),.PCURVE_S1.); +#43891 = LINE('',#43892,#43893); +#43892 = CARTESIAN_POINT('',(1.E-002,-0.925,2.354813742174)); +#43893 = VECTOR('',#43894,1.); +#43894 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#43895 = PCURVE('',#40595,#43896); +#43896 = DEFINITIONAL_REPRESENTATION('',(#43897),#43901); +#43897 = LINE('',#43898,#43899); +#43898 = CARTESIAN_POINT('',(2.586446609407,4.704813742174)); +#43899 = VECTOR('',#43900,1.); +#43900 = DIRECTION('',(0.E+000,-1.)); +#43901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43902 = PCURVE('',#43903,#43908); +#43903 = PLANE('',#43904); +#43904 = AXIS2_PLACEMENT_3D('',#43905,#43906,#43907); +#43905 = CARTESIAN_POINT('',(1.E-002,-1.525,1.74515457349)); +#43906 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43907 = DIRECTION('',(0.E+000,0.E+000,1.)); +#43908 = DEFINITIONAL_REPRESENTATION('',(#43909),#43913); +#43909 = LINE('',#43910,#43911); +#43910 = CARTESIAN_POINT('',(0.609659168684,-0.6)); +#43911 = VECTOR('',#43912,1.); +#43912 = DIRECTION('',(-1.,0.E+000)); +#43913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43914 = ORIENTED_EDGE('',*,*,#43915,.T.); +#43915 = EDGE_CURVE('',#43888,#43916,#43918,.T.); +#43916 = VERTEX_POINT('',#43917); +#43917 = CARTESIAN_POINT('',(0.229314035204,-0.925,1.629788704102)); +#43918 = SURFACE_CURVE('',#43919,(#43924,#43935),.PCURVE_S1.); +#43919 = CIRCLE('',#43920,0.14); +#43920 = AXIS2_PLACEMENT_3D('',#43921,#43922,#43923); +#43921 = CARTESIAN_POINT('',(0.15,-0.925,1.74515457349)); +#43922 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43923 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#43924 = PCURVE('',#40595,#43925); +#43925 = DEFINITIONAL_REPRESENTATION('',(#43926),#43934); +#43926 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43927,#43928,#43929,#43930 + ,#43931,#43932,#43933),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41535 = CARTESIAN_POINT('',(2.586446609407,4.09515457349)); -#41536 = CARTESIAN_POINT('',(2.586446609407,3.85266746043)); -#41537 = CARTESIAN_POINT('',(2.376446609407,3.97391101696)); -#41538 = CARTESIAN_POINT('',(2.166446609407,4.09515457349)); -#41539 = CARTESIAN_POINT('',(2.376446609407,4.21639813002)); -#41540 = CARTESIAN_POINT('',(2.586446609407,4.33764168655)); -#41541 = CARTESIAN_POINT('',(2.586446609407,4.09515457349)); -#41542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41543 = PCURVE('',#41544,#41549); -#41544 = CYLINDRICAL_SURFACE('',#41545,0.14); -#41545 = AXIS2_PLACEMENT_3D('',#41546,#41547,#41548); -#41546 = CARTESIAN_POINT('',(0.15,-1.525,1.74515457349)); -#41547 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41548 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41549 = DEFINITIONAL_REPRESENTATION('',(#41550),#41553); -#41550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41551,#41552),.UNSPECIFIED., +#43927 = CARTESIAN_POINT('',(2.586446609407,4.09515457349)); +#43928 = CARTESIAN_POINT('',(2.586446609407,3.85266746043)); +#43929 = CARTESIAN_POINT('',(2.376446609407,3.97391101696)); +#43930 = CARTESIAN_POINT('',(2.166446609407,4.09515457349)); +#43931 = CARTESIAN_POINT('',(2.376446609407,4.21639813002)); +#43932 = CARTESIAN_POINT('',(2.586446609407,4.33764168655)); +#43933 = CARTESIAN_POINT('',(2.586446609407,4.09515457349)); +#43934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43935 = PCURVE('',#43936,#43941); +#43936 = CYLINDRICAL_SURFACE('',#43937,0.14); +#43937 = AXIS2_PLACEMENT_3D('',#43938,#43939,#43940); +#43938 = CARTESIAN_POINT('',(0.15,-1.525,1.74515457349)); +#43939 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43940 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43941 = DEFINITIONAL_REPRESENTATION('',(#43942),#43945); +#43942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43943,#43944),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#41551 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#41552 = CARTESIAN_POINT('',(5.314676326519,-0.6)); -#41553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41554 = ORIENTED_EDGE('',*,*,#41555,.F.); -#41555 = EDGE_CURVE('',#41556,#41524,#41558,.T.); -#41556 = VERTEX_POINT('',#41557); -#41557 = CARTESIAN_POINT('',(0.559355388338,-0.925,1.856692134382)); -#41558 = SURFACE_CURVE('',#41559,(#41563,#41570),.PCURVE_S1.); -#41559 = LINE('',#41560,#41561); -#41560 = CARTESIAN_POINT('',(0.559355388338,-0.925,1.856692134382)); -#41561 = VECTOR('',#41562,1.); -#41562 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); -#41563 = PCURVE('',#38203,#41564); -#41564 = DEFINITIONAL_REPRESENTATION('',(#41565),#41569); -#41565 = LINE('',#41566,#41567); -#41566 = CARTESIAN_POINT('',(2.037091221069,4.206692134382)); -#41567 = VECTOR('',#41568,1.); -#41568 = DIRECTION('',(0.824041924199,-0.566528822887)); -#41569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41570 = PCURVE('',#41571,#41576); -#41571 = PLANE('',#41572); -#41572 = AXIS2_PLACEMENT_3D('',#41573,#41574,#41575); -#41573 = CARTESIAN_POINT('',(0.559355388338,-1.525,1.856692134382)); -#41574 = DIRECTION('',(-0.566528822887,0.E+000,0.824041924199)); -#41575 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); -#41576 = DEFINITIONAL_REPRESENTATION('',(#41577),#41581); -#41577 = LINE('',#41578,#41579); -#41578 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41579 = VECTOR('',#41580,1.); -#41580 = DIRECTION('',(1.,0.E+000)); -#41581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41582 = ORIENTED_EDGE('',*,*,#41583,.F.); -#41583 = EDGE_CURVE('',#41584,#41556,#41586,.T.); -#41584 = VERTEX_POINT('',#41585); -#41585 = CARTESIAN_POINT('',(0.81,-0.925,1.72484542651)); -#41586 = SURFACE_CURVE('',#41587,(#41592,#41603),.PCURVE_S1.); -#41587 = CIRCLE('',#41588,0.16); -#41588 = AXIS2_PLACEMENT_3D('',#41589,#41590,#41591); -#41589 = CARTESIAN_POINT('',(0.65,-0.925,1.72484542651)); -#41590 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41591 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41592 = PCURVE('',#38203,#41593); -#41593 = DEFINITIONAL_REPRESENTATION('',(#41594),#41602); -#41594 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41595,#41596,#41597,#41598 - ,#41599,#41600,#41601),.UNSPECIFIED.,.T.,.F.) +#43943 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#43944 = CARTESIAN_POINT('',(5.314676326519,-0.6)); +#43945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43946 = ORIENTED_EDGE('',*,*,#43947,.F.); +#43947 = EDGE_CURVE('',#43948,#43916,#43950,.T.); +#43948 = VERTEX_POINT('',#43949); +#43949 = CARTESIAN_POINT('',(0.559355388338,-0.925,1.856692134382)); +#43950 = SURFACE_CURVE('',#43951,(#43955,#43962),.PCURVE_S1.); +#43951 = LINE('',#43952,#43953); +#43952 = CARTESIAN_POINT('',(0.559355388338,-0.925,1.856692134382)); +#43953 = VECTOR('',#43954,1.); +#43954 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); +#43955 = PCURVE('',#40595,#43956); +#43956 = DEFINITIONAL_REPRESENTATION('',(#43957),#43961); +#43957 = LINE('',#43958,#43959); +#43958 = CARTESIAN_POINT('',(2.037091221069,4.206692134382)); +#43959 = VECTOR('',#43960,1.); +#43960 = DIRECTION('',(0.824041924199,-0.566528822887)); +#43961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43962 = PCURVE('',#43963,#43968); +#43963 = PLANE('',#43964); +#43964 = AXIS2_PLACEMENT_3D('',#43965,#43966,#43967); +#43965 = CARTESIAN_POINT('',(0.559355388338,-1.525,1.856692134382)); +#43966 = DIRECTION('',(-0.566528822887,0.E+000,0.824041924199)); +#43967 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); +#43968 = DEFINITIONAL_REPRESENTATION('',(#43969),#43973); +#43969 = LINE('',#43970,#43971); +#43970 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#43971 = VECTOR('',#43972,1.); +#43972 = DIRECTION('',(1.,0.E+000)); +#43973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43974 = ORIENTED_EDGE('',*,*,#43975,.F.); +#43975 = EDGE_CURVE('',#43976,#43948,#43978,.T.); +#43976 = VERTEX_POINT('',#43977); +#43977 = CARTESIAN_POINT('',(0.81,-0.925,1.72484542651)); +#43978 = SURFACE_CURVE('',#43979,(#43984,#43995),.PCURVE_S1.); +#43979 = CIRCLE('',#43980,0.16); +#43980 = AXIS2_PLACEMENT_3D('',#43981,#43982,#43983); +#43981 = CARTESIAN_POINT('',(0.65,-0.925,1.72484542651)); +#43982 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#43983 = DIRECTION('',(1.,0.E+000,0.E+000)); +#43984 = PCURVE('',#40595,#43985); +#43985 = DEFINITIONAL_REPRESENTATION('',(#43986),#43994); +#43986 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#43987,#43988,#43989,#43990 + ,#43991,#43992,#43993),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41595 = CARTESIAN_POINT('',(1.786446609407,4.07484542651)); -#41596 = CARTESIAN_POINT('',(1.786446609407,4.351973555721)); -#41597 = CARTESIAN_POINT('',(2.026446609407,4.213409491116)); -#41598 = CARTESIAN_POINT('',(2.266446609407,4.07484542651)); -#41599 = CARTESIAN_POINT('',(2.026446609407,3.936281361904)); -#41600 = CARTESIAN_POINT('',(1.786446609407,3.797717297299)); -#41601 = CARTESIAN_POINT('',(1.786446609407,4.07484542651)); -#41602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41603 = PCURVE('',#41604,#41609); -#41604 = CYLINDRICAL_SURFACE('',#41605,0.16); -#41605 = AXIS2_PLACEMENT_3D('',#41606,#41607,#41608); -#41606 = CARTESIAN_POINT('',(0.65,-1.525,1.72484542651)); -#41607 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41608 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41609 = DEFINITIONAL_REPRESENTATION('',(#41610),#41613); -#41610 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41611,#41612),.UNSPECIFIED., +#43987 = CARTESIAN_POINT('',(1.786446609407,4.07484542651)); +#43988 = CARTESIAN_POINT('',(1.786446609407,4.351973555721)); +#43989 = CARTESIAN_POINT('',(2.026446609407,4.213409491116)); +#43990 = CARTESIAN_POINT('',(2.266446609407,4.07484542651)); +#43991 = CARTESIAN_POINT('',(2.026446609407,3.936281361904)); +#43992 = CARTESIAN_POINT('',(1.786446609407,3.797717297299)); +#43993 = CARTESIAN_POINT('',(1.786446609407,4.07484542651)); +#43994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#43995 = PCURVE('',#43996,#44001); +#43996 = CYLINDRICAL_SURFACE('',#43997,0.16); +#43997 = AXIS2_PLACEMENT_3D('',#43998,#43999,#44000); +#43998 = CARTESIAN_POINT('',(0.65,-1.525,1.72484542651)); +#43999 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44000 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44001 = DEFINITIONAL_REPRESENTATION('',(#44002),#44005); +#44002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44003,#44004),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.173083672929),.PIECEWISE_BEZIER_KNOTS.); -#41611 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41612 = CARTESIAN_POINT('',(2.173083672929,-0.6)); -#41613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41614 = ORIENTED_EDGE('',*,*,#41615,.F.); -#41615 = EDGE_CURVE('',#41616,#41584,#41618,.T.); -#41616 = VERTEX_POINT('',#41617); -#41617 = CARTESIAN_POINT('',(0.81,-0.925,-0.40484542651)); -#41618 = SURFACE_CURVE('',#41619,(#41623,#41630),.PCURVE_S1.); -#41619 = LINE('',#41620,#41621); -#41620 = CARTESIAN_POINT('',(0.81,-0.925,-0.40484542651)); -#41621 = VECTOR('',#41622,1.); -#41622 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41623 = PCURVE('',#38203,#41624); -#41624 = DEFINITIONAL_REPRESENTATION('',(#41625),#41629); -#41625 = LINE('',#41626,#41627); -#41626 = CARTESIAN_POINT('',(1.786446609407,1.94515457349)); -#41627 = VECTOR('',#41628,1.); -#41628 = DIRECTION('',(0.E+000,1.)); -#41629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41630 = PCURVE('',#41631,#41636); -#41631 = PLANE('',#41632); -#41632 = AXIS2_PLACEMENT_3D('',#41633,#41634,#41635); -#41633 = CARTESIAN_POINT('',(0.81,-1.525,-0.40484542651)); -#41634 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41635 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41636 = DEFINITIONAL_REPRESENTATION('',(#41637),#41641); -#41637 = LINE('',#41638,#41639); -#41638 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41639 = VECTOR('',#41640,1.); -#41640 = DIRECTION('',(1.,0.E+000)); -#41641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41642 = ORIENTED_EDGE('',*,*,#41643,.F.); -#41643 = EDGE_CURVE('',#41644,#41616,#41646,.T.); -#41644 = VERTEX_POINT('',#41645); -#41645 = CARTESIAN_POINT('',(0.559355388338,-0.925,-0.536692134382)); -#41646 = SURFACE_CURVE('',#41647,(#41652,#41663),.PCURVE_S1.); -#41647 = CIRCLE('',#41648,0.16); -#41648 = AXIS2_PLACEMENT_3D('',#41649,#41650,#41651); -#41649 = CARTESIAN_POINT('',(0.65,-0.925,-0.40484542651)); -#41650 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41651 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); -#41652 = PCURVE('',#38203,#41653); -#41653 = DEFINITIONAL_REPRESENTATION('',(#41654),#41662); -#41654 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41655,#41656,#41657,#41658 - ,#41659,#41660,#41661),.UNSPECIFIED.,.T.,.F.) +#44003 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44004 = CARTESIAN_POINT('',(2.173083672929,-0.6)); +#44005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44006 = ORIENTED_EDGE('',*,*,#44007,.F.); +#44007 = EDGE_CURVE('',#44008,#43976,#44010,.T.); +#44008 = VERTEX_POINT('',#44009); +#44009 = CARTESIAN_POINT('',(0.81,-0.925,-0.40484542651)); +#44010 = SURFACE_CURVE('',#44011,(#44015,#44022),.PCURVE_S1.); +#44011 = LINE('',#44012,#44013); +#44012 = CARTESIAN_POINT('',(0.81,-0.925,-0.40484542651)); +#44013 = VECTOR('',#44014,1.); +#44014 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44015 = PCURVE('',#40595,#44016); +#44016 = DEFINITIONAL_REPRESENTATION('',(#44017),#44021); +#44017 = LINE('',#44018,#44019); +#44018 = CARTESIAN_POINT('',(1.786446609407,1.94515457349)); +#44019 = VECTOR('',#44020,1.); +#44020 = DIRECTION('',(0.E+000,1.)); +#44021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44022 = PCURVE('',#44023,#44028); +#44023 = PLANE('',#44024); +#44024 = AXIS2_PLACEMENT_3D('',#44025,#44026,#44027); +#44025 = CARTESIAN_POINT('',(0.81,-1.525,-0.40484542651)); +#44026 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44027 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44028 = DEFINITIONAL_REPRESENTATION('',(#44029),#44033); +#44029 = LINE('',#44030,#44031); +#44030 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44031 = VECTOR('',#44032,1.); +#44032 = DIRECTION('',(1.,0.E+000)); +#44033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44034 = ORIENTED_EDGE('',*,*,#44035,.F.); +#44035 = EDGE_CURVE('',#44036,#44008,#44038,.T.); +#44036 = VERTEX_POINT('',#44037); +#44037 = CARTESIAN_POINT('',(0.559355388338,-0.925,-0.536692134382)); +#44038 = SURFACE_CURVE('',#44039,(#44044,#44055),.PCURVE_S1.); +#44039 = CIRCLE('',#44040,0.16); +#44040 = AXIS2_PLACEMENT_3D('',#44041,#44042,#44043); +#44041 = CARTESIAN_POINT('',(0.65,-0.925,-0.40484542651)); +#44042 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44043 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); +#44044 = PCURVE('',#40595,#44045); +#44045 = DEFINITIONAL_REPRESENTATION('',(#44046),#44054); +#44046 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44047,#44048,#44049,#44050 + ,#44051,#44052,#44053),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41655 = CARTESIAN_POINT('',(2.037091221069,1.813307865618)); -#41656 = CARTESIAN_POINT('',(1.808726024224,1.656306792787)); -#41657 = CARTESIAN_POINT('',(1.786941705154,1.932577391011)); -#41658 = CARTESIAN_POINT('',(1.765157386083,2.208847989234)); -#41659 = CARTESIAN_POINT('',(2.015306901998,2.089578463841)); -#41660 = CARTESIAN_POINT('',(2.265456417914,1.970308938449)); -#41661 = CARTESIAN_POINT('',(2.037091221069,1.813307865618)); -#41662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41663 = PCURVE('',#41664,#41669); -#41664 = CYLINDRICAL_SURFACE('',#41665,0.16); -#41665 = AXIS2_PLACEMENT_3D('',#41666,#41667,#41668); -#41666 = CARTESIAN_POINT('',(0.65,-1.525,-0.40484542651)); -#41667 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41668 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41669 = DEFINITIONAL_REPRESENTATION('',(#41670),#41673); -#41670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41671,#41672),.UNSPECIFIED., +#44047 = CARTESIAN_POINT('',(2.037091221069,1.813307865618)); +#44048 = CARTESIAN_POINT('',(1.808726024224,1.656306792787)); +#44049 = CARTESIAN_POINT('',(1.786941705154,1.932577391011)); +#44050 = CARTESIAN_POINT('',(1.765157386083,2.208847989234)); +#44051 = CARTESIAN_POINT('',(2.015306901998,2.089578463841)); +#44052 = CARTESIAN_POINT('',(2.265456417914,1.970308938449)); +#44053 = CARTESIAN_POINT('',(2.037091221069,1.813307865618)); +#44054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44055 = PCURVE('',#44056,#44061); +#44056 = CYLINDRICAL_SURFACE('',#44057,0.16); +#44057 = AXIS2_PLACEMENT_3D('',#44058,#44059,#44060); +#44058 = CARTESIAN_POINT('',(0.65,-1.525,-0.40484542651)); +#44059 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44060 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44061 = DEFINITIONAL_REPRESENTATION('',(#44062),#44065); +#44062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44063,#44064),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#41671 = CARTESIAN_POINT('',(4.11010163425,-0.6)); -#41672 = CARTESIAN_POINT('',(6.28318530718,-0.6)); -#41673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41674 = ORIENTED_EDGE('',*,*,#41675,.F.); -#41675 = EDGE_CURVE('',#41676,#41644,#41678,.T.); -#41676 = VERTEX_POINT('',#41677); -#41677 = CARTESIAN_POINT('',(0.229314035204,-0.925,-0.309788704102)); -#41678 = SURFACE_CURVE('',#41679,(#41683,#41690),.PCURVE_S1.); -#41679 = LINE('',#41680,#41681); -#41680 = CARTESIAN_POINT('',(0.229314035204,-0.925,-0.309788704102)); -#41681 = VECTOR('',#41682,1.); -#41682 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); -#41683 = PCURVE('',#38203,#41684); -#41684 = DEFINITIONAL_REPRESENTATION('',(#41685),#41689); -#41685 = LINE('',#41686,#41687); -#41686 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); -#41687 = VECTOR('',#41688,1.); -#41688 = DIRECTION('',(-0.824041924199,-0.566528822887)); -#41689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41690 = PCURVE('',#41691,#41696); -#41691 = PLANE('',#41692); -#41692 = AXIS2_PLACEMENT_3D('',#41693,#41694,#41695); -#41693 = CARTESIAN_POINT('',(0.229314035204,-1.525,-0.309788704102)); -#41694 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); -#41695 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); -#41696 = DEFINITIONAL_REPRESENTATION('',(#41697),#41701); -#41697 = LINE('',#41698,#41699); -#41698 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41699 = VECTOR('',#41700,1.); -#41700 = DIRECTION('',(1.,0.E+000)); -#41701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41702 = ORIENTED_EDGE('',*,*,#41703,.T.); -#41703 = EDGE_CURVE('',#41676,#41704,#41706,.T.); -#41704 = VERTEX_POINT('',#41705); -#41705 = CARTESIAN_POINT('',(1.E-002,-0.925,-0.42515457349)); -#41706 = SURFACE_CURVE('',#41707,(#41712,#41723),.PCURVE_S1.); -#41707 = CIRCLE('',#41708,0.14); -#41708 = AXIS2_PLACEMENT_3D('',#41709,#41710,#41711); -#41709 = CARTESIAN_POINT('',(0.15,-0.925,-0.42515457349)); -#41710 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41711 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); -#41712 = PCURVE('',#38203,#41713); -#41713 = DEFINITIONAL_REPRESENTATION('',(#41714),#41722); -#41714 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41715,#41716,#41717,#41718 - ,#41719,#41720,#41721),.UNSPECIFIED.,.F.,.F.) +#44063 = CARTESIAN_POINT('',(4.11010163425,-0.6)); +#44064 = CARTESIAN_POINT('',(6.28318530718,-0.6)); +#44065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44066 = ORIENTED_EDGE('',*,*,#44067,.F.); +#44067 = EDGE_CURVE('',#44068,#44036,#44070,.T.); +#44068 = VERTEX_POINT('',#44069); +#44069 = CARTESIAN_POINT('',(0.229314035204,-0.925,-0.309788704102)); +#44070 = SURFACE_CURVE('',#44071,(#44075,#44082),.PCURVE_S1.); +#44071 = LINE('',#44072,#44073); +#44072 = CARTESIAN_POINT('',(0.229314035204,-0.925,-0.309788704102)); +#44073 = VECTOR('',#44074,1.); +#44074 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); +#44075 = PCURVE('',#40595,#44076); +#44076 = DEFINITIONAL_REPRESENTATION('',(#44077),#44081); +#44077 = LINE('',#44078,#44079); +#44078 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); +#44079 = VECTOR('',#44080,1.); +#44080 = DIRECTION('',(-0.824041924199,-0.566528822887)); +#44081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44082 = PCURVE('',#44083,#44088); +#44083 = PLANE('',#44084); +#44084 = AXIS2_PLACEMENT_3D('',#44085,#44086,#44087); +#44085 = CARTESIAN_POINT('',(0.229314035204,-1.525,-0.309788704102)); +#44086 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); +#44087 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); +#44088 = DEFINITIONAL_REPRESENTATION('',(#44089),#44093); +#44089 = LINE('',#44090,#44091); +#44090 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44091 = VECTOR('',#44092,1.); +#44092 = DIRECTION('',(1.,0.E+000)); +#44093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44094 = ORIENTED_EDGE('',*,*,#44095,.T.); +#44095 = EDGE_CURVE('',#44068,#44096,#44098,.T.); +#44096 = VERTEX_POINT('',#44097); +#44097 = CARTESIAN_POINT('',(1.E-002,-0.925,-0.42515457349)); +#44098 = SURFACE_CURVE('',#44099,(#44104,#44115),.PCURVE_S1.); +#44099 = CIRCLE('',#44100,0.14); +#44100 = AXIS2_PLACEMENT_3D('',#44101,#44102,#44103); +#44101 = CARTESIAN_POINT('',(0.15,-0.925,-0.42515457349)); +#44102 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44103 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); +#44104 = PCURVE('',#40595,#44105); +#44105 = DEFINITIONAL_REPRESENTATION('',(#44106),#44114); +#44106 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44107,#44108,#44109,#44110 + ,#44111,#44112,#44113),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41715 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); -#41716 = CARTESIAN_POINT('',(2.566952121442,2.177587234625)); -#41717 = CARTESIAN_POINT('',(2.586013400629,1.935850461179)); -#41718 = CARTESIAN_POINT('',(2.605074679815,1.694113687734)); -#41719 = CARTESIAN_POINT('',(2.386193853389,1.798474522452)); -#41720 = CARTESIAN_POINT('',(2.167313026964,1.902835357171)); -#41721 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); -#41722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41723 = PCURVE('',#41724,#41729); -#41724 = CYLINDRICAL_SURFACE('',#41725,0.14); -#41725 = AXIS2_PLACEMENT_3D('',#41726,#41727,#41728); -#41726 = CARTESIAN_POINT('',(0.15,-1.525,-0.42515457349)); -#41727 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41728 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41729 = DEFINITIONAL_REPRESENTATION('',(#41730),#41733); -#41730 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41731,#41732),.UNSPECIFIED., +#44107 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); +#44108 = CARTESIAN_POINT('',(2.566952121442,2.177587234625)); +#44109 = CARTESIAN_POINT('',(2.586013400629,1.935850461179)); +#44110 = CARTESIAN_POINT('',(2.605074679815,1.694113687734)); +#44111 = CARTESIAN_POINT('',(2.386193853389,1.798474522452)); +#44112 = CARTESIAN_POINT('',(2.167313026964,1.902835357171)); +#44113 = CARTESIAN_POINT('',(2.367132574203,2.040211295898)); +#44114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44115 = PCURVE('',#44116,#44121); +#44116 = CYLINDRICAL_SURFACE('',#44117,0.14); +#44117 = AXIS2_PLACEMENT_3D('',#44118,#44119,#44120); +#44118 = CARTESIAN_POINT('',(0.15,-1.525,-0.42515457349)); +#44119 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44120 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44121 = DEFINITIONAL_REPRESENTATION('',(#44122),#44125); +#44122 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44123,#44124),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#41731 = CARTESIAN_POINT('',(0.96850898066,-0.6)); -#41732 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#41733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41734 = ORIENTED_EDGE('',*,*,#41735,.F.); -#41735 = EDGE_CURVE('',#41736,#41704,#41738,.T.); -#41736 = VERTEX_POINT('',#41737); -#41737 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); -#41738 = SURFACE_CURVE('',#41739,(#41743,#41750),.PCURVE_S1.); -#41739 = LINE('',#41740,#41741); -#41740 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); -#41741 = VECTOR('',#41742,1.); -#41742 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41743 = PCURVE('',#38203,#41744); -#41744 = DEFINITIONAL_REPRESENTATION('',(#41745),#41749); -#41745 = LINE('',#41746,#41747); -#41746 = CARTESIAN_POINT('',(2.586446609407,1.22)); -#41747 = VECTOR('',#41748,1.); -#41748 = DIRECTION('',(0.E+000,1.)); -#41749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41750 = PCURVE('',#41751,#41756); -#41751 = PLANE('',#41752); -#41752 = AXIS2_PLACEMENT_3D('',#41753,#41754,#41755); -#41753 = CARTESIAN_POINT('',(1.E-002,-1.525,-1.13)); -#41754 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41755 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41756 = DEFINITIONAL_REPRESENTATION('',(#41757),#41761); -#41757 = LINE('',#41758,#41759); -#41758 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41759 = VECTOR('',#41760,1.); -#41760 = DIRECTION('',(1.,0.E+000)); -#41761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41762 = ORIENTED_EDGE('',*,*,#41763,.F.); -#41763 = EDGE_CURVE('',#41764,#41736,#41766,.T.); -#41764 = VERTEX_POINT('',#41765); -#41765 = CARTESIAN_POINT('',(1.71,-0.925,-1.13)); -#41766 = SURFACE_CURVE('',#41767,(#41771,#41778),.PCURVE_S1.); -#41767 = LINE('',#41768,#41769); -#41768 = CARTESIAN_POINT('',(1.71,-0.925,-1.13)); -#41769 = VECTOR('',#41770,1.); -#41770 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41771 = PCURVE('',#38203,#41772); -#41772 = DEFINITIONAL_REPRESENTATION('',(#41773),#41777); -#41773 = LINE('',#41774,#41775); -#41774 = CARTESIAN_POINT('',(0.886446609407,1.22)); -#41775 = VECTOR('',#41776,1.); -#41776 = DIRECTION('',(1.,0.E+000)); -#41777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41778 = PCURVE('',#41779,#41784); -#41779 = PLANE('',#41780); -#41780 = AXIS2_PLACEMENT_3D('',#41781,#41782,#41783); -#41781 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); -#41782 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41783 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41784 = DEFINITIONAL_REPRESENTATION('',(#41785),#41789); -#41785 = LINE('',#41786,#41787); -#41786 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#41787 = VECTOR('',#41788,1.); -#41788 = DIRECTION('',(1.,0.E+000)); -#41789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41790 = ORIENTED_EDGE('',*,*,#41791,.F.); -#41791 = EDGE_CURVE('',#41792,#41764,#41794,.T.); -#41792 = VERTEX_POINT('',#41793); -#41793 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); -#41794 = SURFACE_CURVE('',#41795,(#41800,#41811),.PCURVE_S1.); -#41795 = CIRCLE('',#41796,8.E-002); -#41796 = AXIS2_PLACEMENT_3D('',#41797,#41798,#41799); -#41797 = CARTESIAN_POINT('',(1.71,-0.925,-1.21)); -#41798 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41799 = DIRECTION('',(0.661437827766,0.E+000,0.75)); -#41800 = PCURVE('',#38203,#41801); -#41801 = DEFINITIONAL_REPRESENTATION('',(#41802),#41810); -#41802 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41803,#41804,#41805,#41806 - ,#41807,#41808,#41809),.UNSPECIFIED.,.F.,.F.) +#44123 = CARTESIAN_POINT('',(0.96850898066,-0.6)); +#44124 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#44125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44126 = ORIENTED_EDGE('',*,*,#44127,.F.); +#44127 = EDGE_CURVE('',#44128,#44096,#44130,.T.); +#44128 = VERTEX_POINT('',#44129); +#44129 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); +#44130 = SURFACE_CURVE('',#44131,(#44135,#44142),.PCURVE_S1.); +#44131 = LINE('',#44132,#44133); +#44132 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); +#44133 = VECTOR('',#44134,1.); +#44134 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44135 = PCURVE('',#40595,#44136); +#44136 = DEFINITIONAL_REPRESENTATION('',(#44137),#44141); +#44137 = LINE('',#44138,#44139); +#44138 = CARTESIAN_POINT('',(2.586446609407,1.22)); +#44139 = VECTOR('',#44140,1.); +#44140 = DIRECTION('',(0.E+000,1.)); +#44141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44142 = PCURVE('',#44143,#44148); +#44143 = PLANE('',#44144); +#44144 = AXIS2_PLACEMENT_3D('',#44145,#44146,#44147); +#44145 = CARTESIAN_POINT('',(1.E-002,-1.525,-1.13)); +#44146 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44147 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44148 = DEFINITIONAL_REPRESENTATION('',(#44149),#44153); +#44149 = LINE('',#44150,#44151); +#44150 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44151 = VECTOR('',#44152,1.); +#44152 = DIRECTION('',(1.,0.E+000)); +#44153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44154 = ORIENTED_EDGE('',*,*,#44155,.F.); +#44155 = EDGE_CURVE('',#44156,#44128,#44158,.T.); +#44156 = VERTEX_POINT('',#44157); +#44157 = CARTESIAN_POINT('',(1.71,-0.925,-1.13)); +#44158 = SURFACE_CURVE('',#44159,(#44163,#44170),.PCURVE_S1.); +#44159 = LINE('',#44160,#44161); +#44160 = CARTESIAN_POINT('',(1.71,-0.925,-1.13)); +#44161 = VECTOR('',#44162,1.); +#44162 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44163 = PCURVE('',#40595,#44164); +#44164 = DEFINITIONAL_REPRESENTATION('',(#44165),#44169); +#44165 = LINE('',#44166,#44167); +#44166 = CARTESIAN_POINT('',(0.886446609407,1.22)); +#44167 = VECTOR('',#44168,1.); +#44168 = DIRECTION('',(1.,0.E+000)); +#44169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44170 = PCURVE('',#44171,#44176); +#44171 = PLANE('',#44172); +#44172 = AXIS2_PLACEMENT_3D('',#44173,#44174,#44175); +#44173 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); +#44174 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44175 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44176 = DEFINITIONAL_REPRESENTATION('',(#44177),#44181); +#44177 = LINE('',#44178,#44179); +#44178 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44179 = VECTOR('',#44180,1.); +#44180 = DIRECTION('',(1.,0.E+000)); +#44181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44182 = ORIENTED_EDGE('',*,*,#44183,.F.); +#44183 = EDGE_CURVE('',#44184,#44156,#44186,.T.); +#44184 = VERTEX_POINT('',#44185); +#44185 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); +#44186 = SURFACE_CURVE('',#44187,(#44192,#44203),.PCURVE_S1.); +#44187 = CIRCLE('',#44188,8.E-002); +#44188 = AXIS2_PLACEMENT_3D('',#44189,#44190,#44191); +#44189 = CARTESIAN_POINT('',(1.71,-0.925,-1.21)); +#44190 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44191 = DIRECTION('',(0.661437827766,0.E+000,0.75)); +#44192 = PCURVE('',#40595,#44193); +#44193 = DEFINITIONAL_REPRESENTATION('',(#44194),#44202); +#44194 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44195,#44196,#44197,#44198 + ,#44199,#44200,#44201),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41803 = CARTESIAN_POINT('',(0.833531583186,1.2)); -#41804 = CARTESIAN_POINT('',(0.93745463164,1.291651513899)); -#41805 = CARTESIAN_POINT('',(0.964865646745,1.15582575695)); -#41806 = CARTESIAN_POINT('',(0.99227666185,1.02)); -#41807 = CARTESIAN_POINT('',(0.860942598291,1.06417424305)); -#41808 = CARTESIAN_POINT('',(0.729608534732,1.108348486101)); -#41809 = CARTESIAN_POINT('',(0.833531583186,1.2)); -#41810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41811 = PCURVE('',#41812,#41817); -#41812 = CYLINDRICAL_SURFACE('',#41813,8.E-002); -#41813 = AXIS2_PLACEMENT_3D('',#41814,#41815,#41816); -#41814 = CARTESIAN_POINT('',(1.71,-1.225,-1.21)); -#41815 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41816 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41817 = DEFINITIONAL_REPRESENTATION('',(#41818),#41821); -#41818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41819,#41820),.UNSPECIFIED., +#44195 = CARTESIAN_POINT('',(0.833531583186,1.2)); +#44196 = CARTESIAN_POINT('',(0.93745463164,1.291651513899)); +#44197 = CARTESIAN_POINT('',(0.964865646745,1.15582575695)); +#44198 = CARTESIAN_POINT('',(0.99227666185,1.02)); +#44199 = CARTESIAN_POINT('',(0.860942598291,1.06417424305)); +#44200 = CARTESIAN_POINT('',(0.729608534732,1.108348486101)); +#44201 = CARTESIAN_POINT('',(0.833531583186,1.2)); +#44202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44203 = PCURVE('',#44204,#44209); +#44204 = CYLINDRICAL_SURFACE('',#44205,8.E-002); +#44205 = AXIS2_PLACEMENT_3D('',#44206,#44207,#44208); +#44206 = CARTESIAN_POINT('',(1.71,-1.225,-1.21)); +#44207 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44208 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44209 = DEFINITIONAL_REPRESENTATION('',(#44210),#44213); +#44210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44211,#44212),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.722734247813),.PIECEWISE_BEZIER_KNOTS.); -#41819 = CARTESIAN_POINT('',(0.848062078982,-0.3)); -#41820 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#41821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41822 = ORIENTED_EDGE('',*,*,#41823,.T.); -#41823 = EDGE_CURVE('',#41792,#41051,#41824,.T.); -#41824 = SURFACE_CURVE('',#41825,(#41829,#41836),.PCURVE_S1.); -#41825 = LINE('',#41826,#41827); -#41826 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); -#41827 = VECTOR('',#41828,1.); -#41828 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41829 = PCURVE('',#38203,#41830); -#41830 = DEFINITIONAL_REPRESENTATION('',(#41831),#41835); -#41831 = LINE('',#41832,#41833); -#41832 = CARTESIAN_POINT('',(0.833531583186,1.2)); -#41833 = VECTOR('',#41834,1.); -#41834 = DIRECTION('',(-1.,0.E+000)); -#41835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41836 = PCURVE('',#41837,#41842); -#41837 = PLANE('',#41838); -#41838 = AXIS2_PLACEMENT_3D('',#41839,#41840,#41841); -#41839 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.15)); -#41840 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41841 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41842 = DEFINITIONAL_REPRESENTATION('',(#41843),#41847); -#41843 = LINE('',#41844,#41845); -#41844 = CARTESIAN_POINT('',(1.762915026221,-0.925)); -#41845 = VECTOR('',#41846,1.); -#41846 = DIRECTION('',(1.,0.E+000)); -#41847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41848 = ADVANCED_FACE('',(#41849),#37803,.T.); -#41849 = FACE_BOUND('',#41850,.F.); -#41850 = EDGE_LOOP('',(#41851,#41881,#41904,#41936,#41964,#41992,#42024, - #42052,#42084,#42112,#42144,#42172,#42204,#42232,#42259,#42280, - #42281,#42303,#42331,#42363,#42391,#42419,#42447,#42479,#42507, - #42539,#42567,#42595,#42623,#42655,#42683,#42710)); -#41851 = ORIENTED_EDGE('',*,*,#41852,.T.); -#41852 = EDGE_CURVE('',#41853,#41855,#41857,.T.); -#41853 = VERTEX_POINT('',#41854); -#41854 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); -#41855 = VERTEX_POINT('',#41856); -#41856 = CARTESIAN_POINT('',(-1.79,-0.925,-1.15)); -#41857 = SURFACE_CURVE('',#41858,(#41862,#41869),.PCURVE_S1.); -#41858 = LINE('',#41859,#41860); -#41859 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); -#41860 = VECTOR('',#41861,1.); -#41861 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41862 = PCURVE('',#37803,#41863); -#41863 = DEFINITIONAL_REPRESENTATION('',(#41864),#41868); -#41864 = LINE('',#41865,#41866); -#41865 = CARTESIAN_POINT('',(4.386446609407,0.82)); -#41866 = VECTOR('',#41867,1.); -#41867 = DIRECTION('',(0.E+000,1.)); -#41868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41869 = PCURVE('',#41870,#41875); -#41870 = PLANE('',#41871); -#41871 = AXIS2_PLACEMENT_3D('',#41872,#41873,#41874); -#41872 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); -#41873 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41874 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41875 = DEFINITIONAL_REPRESENTATION('',(#41876),#41880); -#41876 = LINE('',#41877,#41878); -#41877 = CARTESIAN_POINT('',(0.32,-0.3)); -#41878 = VECTOR('',#41879,1.); -#41879 = DIRECTION('',(-1.,0.E+000)); -#41880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41881 = ORIENTED_EDGE('',*,*,#41882,.T.); -#41882 = EDGE_CURVE('',#41855,#41883,#41885,.T.); -#41883 = VERTEX_POINT('',#41884); -#41884 = CARTESIAN_POINT('',(-1.762915026221,-0.925,-1.15)); -#41885 = SURFACE_CURVE('',#41886,(#41890,#41897),.PCURVE_S1.); -#41886 = LINE('',#41887,#41888); -#41887 = CARTESIAN_POINT('',(-1.79,-0.925,-1.15)); -#41888 = VECTOR('',#41889,1.); -#41889 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41890 = PCURVE('',#37803,#41891); -#41891 = DEFINITIONAL_REPRESENTATION('',(#41892),#41896); -#41892 = LINE('',#41893,#41894); -#41893 = CARTESIAN_POINT('',(4.386446609407,1.2)); -#41894 = VECTOR('',#41895,1.); -#41895 = DIRECTION('',(-1.,0.E+000)); -#41896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41897 = PCURVE('',#41837,#41898); -#41898 = DEFINITIONAL_REPRESENTATION('',(#41899),#41903); -#41899 = LINE('',#41900,#41901); -#41900 = CARTESIAN_POINT('',(-1.79,-0.925)); -#41901 = VECTOR('',#41902,1.); -#41902 = DIRECTION('',(1.,0.E+000)); -#41903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41904 = ORIENTED_EDGE('',*,*,#41905,.F.); -#41905 = EDGE_CURVE('',#41906,#41883,#41908,.T.); -#41906 = VERTEX_POINT('',#41907); -#41907 = CARTESIAN_POINT('',(-1.71,-0.925,-1.13)); -#41908 = SURFACE_CURVE('',#41909,(#41914,#41925),.PCURVE_S1.); -#41909 = CIRCLE('',#41910,8.E-002); -#41910 = AXIS2_PLACEMENT_3D('',#41911,#41912,#41913); -#41911 = CARTESIAN_POINT('',(-1.71,-0.925,-1.21)); -#41912 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41913 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41914 = PCURVE('',#37803,#41915); -#41915 = DEFINITIONAL_REPRESENTATION('',(#41916),#41924); -#41916 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#41917,#41918,#41919,#41920 - ,#41921,#41922,#41923),.UNSPECIFIED.,.F.,.F.) +#44211 = CARTESIAN_POINT('',(0.848062078982,-0.3)); +#44212 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#44213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44214 = ORIENTED_EDGE('',*,*,#44215,.T.); +#44215 = EDGE_CURVE('',#44184,#43443,#44216,.T.); +#44216 = SURFACE_CURVE('',#44217,(#44221,#44228),.PCURVE_S1.); +#44217 = LINE('',#44218,#44219); +#44218 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); +#44219 = VECTOR('',#44220,1.); +#44220 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44221 = PCURVE('',#40595,#44222); +#44222 = DEFINITIONAL_REPRESENTATION('',(#44223),#44227); +#44223 = LINE('',#44224,#44225); +#44224 = CARTESIAN_POINT('',(0.833531583186,1.2)); +#44225 = VECTOR('',#44226,1.); +#44226 = DIRECTION('',(-1.,0.E+000)); +#44227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44228 = PCURVE('',#44229,#44234); +#44229 = PLANE('',#44230); +#44230 = AXIS2_PLACEMENT_3D('',#44231,#44232,#44233); +#44231 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.15)); +#44232 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44233 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44234 = DEFINITIONAL_REPRESENTATION('',(#44235),#44239); +#44235 = LINE('',#44236,#44237); +#44236 = CARTESIAN_POINT('',(1.762915026221,-0.925)); +#44237 = VECTOR('',#44238,1.); +#44238 = DIRECTION('',(1.,0.E+000)); +#44239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44240 = ADVANCED_FACE('',(#44241),#40195,.T.); +#44241 = FACE_BOUND('',#44242,.F.); +#44242 = EDGE_LOOP('',(#44243,#44273,#44296,#44328,#44356,#44384,#44416, + #44444,#44476,#44504,#44536,#44564,#44596,#44624,#44651,#44672, + #44673,#44695,#44723,#44755,#44783,#44811,#44839,#44871,#44899, + #44931,#44959,#44987,#45015,#45047,#45075,#45102)); +#44243 = ORIENTED_EDGE('',*,*,#44244,.T.); +#44244 = EDGE_CURVE('',#44245,#44247,#44249,.T.); +#44245 = VERTEX_POINT('',#44246); +#44246 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); +#44247 = VERTEX_POINT('',#44248); +#44248 = CARTESIAN_POINT('',(-1.79,-0.925,-1.15)); +#44249 = SURFACE_CURVE('',#44250,(#44254,#44261),.PCURVE_S1.); +#44250 = LINE('',#44251,#44252); +#44251 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); +#44252 = VECTOR('',#44253,1.); +#44253 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44254 = PCURVE('',#40195,#44255); +#44255 = DEFINITIONAL_REPRESENTATION('',(#44256),#44260); +#44256 = LINE('',#44257,#44258); +#44257 = CARTESIAN_POINT('',(4.386446609407,0.82)); +#44258 = VECTOR('',#44259,1.); +#44259 = DIRECTION('',(0.E+000,1.)); +#44260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44261 = PCURVE('',#44262,#44267); +#44262 = PLANE('',#44263); +#44263 = AXIS2_PLACEMENT_3D('',#44264,#44265,#44266); +#44264 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); +#44265 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44266 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44267 = DEFINITIONAL_REPRESENTATION('',(#44268),#44272); +#44268 = LINE('',#44269,#44270); +#44269 = CARTESIAN_POINT('',(0.32,-0.3)); +#44270 = VECTOR('',#44271,1.); +#44271 = DIRECTION('',(-1.,0.E+000)); +#44272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44273 = ORIENTED_EDGE('',*,*,#44274,.T.); +#44274 = EDGE_CURVE('',#44247,#44275,#44277,.T.); +#44275 = VERTEX_POINT('',#44276); +#44276 = CARTESIAN_POINT('',(-1.762915026221,-0.925,-1.15)); +#44277 = SURFACE_CURVE('',#44278,(#44282,#44289),.PCURVE_S1.); +#44278 = LINE('',#44279,#44280); +#44279 = CARTESIAN_POINT('',(-1.79,-0.925,-1.15)); +#44280 = VECTOR('',#44281,1.); +#44281 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44282 = PCURVE('',#40195,#44283); +#44283 = DEFINITIONAL_REPRESENTATION('',(#44284),#44288); +#44284 = LINE('',#44285,#44286); +#44285 = CARTESIAN_POINT('',(4.386446609407,1.2)); +#44286 = VECTOR('',#44287,1.); +#44287 = DIRECTION('',(-1.,0.E+000)); +#44288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44289 = PCURVE('',#44229,#44290); +#44290 = DEFINITIONAL_REPRESENTATION('',(#44291),#44295); +#44291 = LINE('',#44292,#44293); +#44292 = CARTESIAN_POINT('',(-1.79,-0.925)); +#44293 = VECTOR('',#44294,1.); +#44294 = DIRECTION('',(1.,0.E+000)); +#44295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44296 = ORIENTED_EDGE('',*,*,#44297,.F.); +#44297 = EDGE_CURVE('',#44298,#44275,#44300,.T.); +#44298 = VERTEX_POINT('',#44299); +#44299 = CARTESIAN_POINT('',(-1.71,-0.925,-1.13)); +#44300 = SURFACE_CURVE('',#44301,(#44306,#44317),.PCURVE_S1.); +#44301 = CIRCLE('',#44302,8.E-002); +#44302 = AXIS2_PLACEMENT_3D('',#44303,#44304,#44305); +#44303 = CARTESIAN_POINT('',(-1.71,-0.925,-1.21)); +#44304 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44305 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44306 = PCURVE('',#40195,#44307); +#44307 = DEFINITIONAL_REPRESENTATION('',(#44308),#44316); +#44308 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44309,#44310,#44311,#44312 + ,#44313,#44314,#44315),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#41917 = CARTESIAN_POINT('',(4.306446609407,1.22)); -#41918 = CARTESIAN_POINT('',(4.445010674013,1.22)); -#41919 = CARTESIAN_POINT('',(4.37572864171,1.1)); -#41920 = CARTESIAN_POINT('',(4.306446609407,0.98)); -#41921 = CARTESIAN_POINT('',(4.237164577104,1.1)); -#41922 = CARTESIAN_POINT('',(4.167882544801,1.22)); -#41923 = CARTESIAN_POINT('',(4.306446609407,1.22)); -#41924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41925 = PCURVE('',#41926,#41931); -#41926 = CYLINDRICAL_SURFACE('',#41927,8.E-002); -#41927 = AXIS2_PLACEMENT_3D('',#41928,#41929,#41930); -#41928 = CARTESIAN_POINT('',(-1.71,-1.225,-1.21)); -#41929 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#41930 = DIRECTION('',(1.,0.E+000,0.E+000)); -#41931 = DEFINITIONAL_REPRESENTATION('',(#41932),#41935); -#41932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#41933,#41934),.UNSPECIFIED., +#44309 = CARTESIAN_POINT('',(4.306446609407,1.22)); +#44310 = CARTESIAN_POINT('',(4.445010674013,1.22)); +#44311 = CARTESIAN_POINT('',(4.37572864171,1.1)); +#44312 = CARTESIAN_POINT('',(4.306446609407,0.98)); +#44313 = CARTESIAN_POINT('',(4.237164577104,1.1)); +#44314 = CARTESIAN_POINT('',(4.167882544801,1.22)); +#44315 = CARTESIAN_POINT('',(4.306446609407,1.22)); +#44316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44317 = PCURVE('',#44318,#44323); +#44318 = CYLINDRICAL_SURFACE('',#44319,8.E-002); +#44319 = AXIS2_PLACEMENT_3D('',#44320,#44321,#44322); +#44320 = CARTESIAN_POINT('',(-1.71,-1.225,-1.21)); +#44321 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44322 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44323 = DEFINITIONAL_REPRESENTATION('',(#44324),#44327); +#44324 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44325,#44326),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.722734247811),.PIECEWISE_BEZIER_KNOTS.); -#41933 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#41934 = CARTESIAN_POINT('',(2.293530574606,-0.3)); -#41935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41936 = ORIENTED_EDGE('',*,*,#41937,.F.); -#41937 = EDGE_CURVE('',#41938,#41906,#41940,.T.); -#41938 = VERTEX_POINT('',#41939); -#41939 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); -#41940 = SURFACE_CURVE('',#41941,(#41945,#41952),.PCURVE_S1.); -#41941 = LINE('',#41942,#41943); -#41942 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); -#41943 = VECTOR('',#41944,1.); -#41944 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41945 = PCURVE('',#37803,#41946); -#41946 = DEFINITIONAL_REPRESENTATION('',(#41947),#41951); -#41947 = LINE('',#41948,#41949); -#41948 = CARTESIAN_POINT('',(2.606446609407,1.22)); -#41949 = VECTOR('',#41950,1.); -#41950 = DIRECTION('',(1.,0.E+000)); -#41951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41952 = PCURVE('',#41953,#41958); -#41953 = PLANE('',#41954); -#41954 = AXIS2_PLACEMENT_3D('',#41955,#41956,#41957); -#41955 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); -#41956 = DIRECTION('',(0.E+000,0.E+000,1.)); -#41957 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41958 = DEFINITIONAL_REPRESENTATION('',(#41959),#41963); -#41959 = LINE('',#41960,#41961); -#41960 = CARTESIAN_POINT('',(1.72,-0.3)); -#41961 = VECTOR('',#41962,1.); -#41962 = DIRECTION('',(1.,0.E+000)); -#41963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41964 = ORIENTED_EDGE('',*,*,#41965,.F.); -#41965 = EDGE_CURVE('',#41966,#41938,#41968,.T.); -#41966 = VERTEX_POINT('',#41967); -#41967 = CARTESIAN_POINT('',(-1.E-002,-0.925,-0.42515457349)); -#41968 = SURFACE_CURVE('',#41969,(#41973,#41980),.PCURVE_S1.); -#41969 = LINE('',#41970,#41971); -#41970 = CARTESIAN_POINT('',(-1.E-002,-0.925,-0.42515457349)); -#41971 = VECTOR('',#41972,1.); -#41972 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41973 = PCURVE('',#37803,#41974); -#41974 = DEFINITIONAL_REPRESENTATION('',(#41975),#41979); -#41975 = LINE('',#41976,#41977); -#41976 = CARTESIAN_POINT('',(2.606446609407,1.92484542651)); -#41977 = VECTOR('',#41978,1.); -#41978 = DIRECTION('',(0.E+000,-1.)); -#41979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41980 = PCURVE('',#41981,#41986); -#41981 = PLANE('',#41982); -#41982 = AXIS2_PLACEMENT_3D('',#41983,#41984,#41985); -#41983 = CARTESIAN_POINT('',(-1.E-002,-1.525,-0.42515457349)); -#41984 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#41985 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#41986 = DEFINITIONAL_REPRESENTATION('',(#41987),#41991); -#41987 = LINE('',#41988,#41989); -#41988 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#41989 = VECTOR('',#41990,1.); -#41990 = DIRECTION('',(1.,0.E+000)); -#41991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#41992 = ORIENTED_EDGE('',*,*,#41993,.F.); -#41993 = EDGE_CURVE('',#41994,#41966,#41996,.T.); -#41994 = VERTEX_POINT('',#41995); -#41995 = CARTESIAN_POINT('',(0.240644611662,-0.925,-0.293307865618)); -#41996 = SURFACE_CURVE('',#41997,(#42002,#42013),.PCURVE_S1.); -#41997 = CIRCLE('',#41998,0.16); -#41998 = AXIS2_PLACEMENT_3D('',#41999,#42000,#42001); -#41999 = CARTESIAN_POINT('',(0.15,-0.925,-0.42515457349)); -#42000 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42001 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); -#42002 = PCURVE('',#37803,#42003); -#42003 = DEFINITIONAL_REPRESENTATION('',(#42004),#42012); -#42004 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42005,#42006,#42007,#42008 - ,#42009,#42010,#42011),.UNSPECIFIED.,.F.,.F.) +#44325 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#44326 = CARTESIAN_POINT('',(2.293530574606,-0.3)); +#44327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44328 = ORIENTED_EDGE('',*,*,#44329,.F.); +#44329 = EDGE_CURVE('',#44330,#44298,#44332,.T.); +#44330 = VERTEX_POINT('',#44331); +#44331 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); +#44332 = SURFACE_CURVE('',#44333,(#44337,#44344),.PCURVE_S1.); +#44333 = LINE('',#44334,#44335); +#44334 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); +#44335 = VECTOR('',#44336,1.); +#44336 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44337 = PCURVE('',#40195,#44338); +#44338 = DEFINITIONAL_REPRESENTATION('',(#44339),#44343); +#44339 = LINE('',#44340,#44341); +#44340 = CARTESIAN_POINT('',(2.606446609407,1.22)); +#44341 = VECTOR('',#44342,1.); +#44342 = DIRECTION('',(1.,0.E+000)); +#44343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44344 = PCURVE('',#44345,#44350); +#44345 = PLANE('',#44346); +#44346 = AXIS2_PLACEMENT_3D('',#44347,#44348,#44349); +#44347 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); +#44348 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44349 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44350 = DEFINITIONAL_REPRESENTATION('',(#44351),#44355); +#44351 = LINE('',#44352,#44353); +#44352 = CARTESIAN_POINT('',(1.72,-0.3)); +#44353 = VECTOR('',#44354,1.); +#44354 = DIRECTION('',(1.,0.E+000)); +#44355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44356 = ORIENTED_EDGE('',*,*,#44357,.F.); +#44357 = EDGE_CURVE('',#44358,#44330,#44360,.T.); +#44358 = VERTEX_POINT('',#44359); +#44359 = CARTESIAN_POINT('',(-1.E-002,-0.925,-0.42515457349)); +#44360 = SURFACE_CURVE('',#44361,(#44365,#44372),.PCURVE_S1.); +#44361 = LINE('',#44362,#44363); +#44362 = CARTESIAN_POINT('',(-1.E-002,-0.925,-0.42515457349)); +#44363 = VECTOR('',#44364,1.); +#44364 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44365 = PCURVE('',#40195,#44366); +#44366 = DEFINITIONAL_REPRESENTATION('',(#44367),#44371); +#44367 = LINE('',#44368,#44369); +#44368 = CARTESIAN_POINT('',(2.606446609407,1.92484542651)); +#44369 = VECTOR('',#44370,1.); +#44370 = DIRECTION('',(0.E+000,-1.)); +#44371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44372 = PCURVE('',#44373,#44378); +#44373 = PLANE('',#44374); +#44374 = AXIS2_PLACEMENT_3D('',#44375,#44376,#44377); +#44375 = CARTESIAN_POINT('',(-1.E-002,-1.525,-0.42515457349)); +#44376 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44377 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44378 = DEFINITIONAL_REPRESENTATION('',(#44379),#44383); +#44379 = LINE('',#44380,#44381); +#44380 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44381 = VECTOR('',#44382,1.); +#44382 = DIRECTION('',(1.,0.E+000)); +#44383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44384 = ORIENTED_EDGE('',*,*,#44385,.F.); +#44385 = EDGE_CURVE('',#44386,#44358,#44388,.T.); +#44386 = VERTEX_POINT('',#44387); +#44387 = CARTESIAN_POINT('',(0.240644611662,-0.925,-0.293307865618)); +#44388 = SURFACE_CURVE('',#44389,(#44394,#44405),.PCURVE_S1.); +#44389 = CIRCLE('',#44390,0.16); +#44390 = AXIS2_PLACEMENT_3D('',#44391,#44392,#44393); +#44391 = CARTESIAN_POINT('',(0.15,-0.925,-0.42515457349)); +#44392 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44393 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); +#44394 = PCURVE('',#40195,#44395); +#44395 = DEFINITIONAL_REPRESENTATION('',(#44396),#44404); +#44396 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44397,#44398,#44399,#44400 + ,#44401,#44402,#44403),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42005 = CARTESIAN_POINT('',(2.355801997745,2.056692134382)); -#42006 = CARTESIAN_POINT('',(2.58416719459,2.213693207213)); -#42007 = CARTESIAN_POINT('',(2.60595151366,1.937422608989)); -#42008 = CARTESIAN_POINT('',(2.627735832731,1.661152010766)); -#42009 = CARTESIAN_POINT('',(2.377586316816,1.780421536159)); -#42010 = CARTESIAN_POINT('',(2.1274368009,1.899691061551)); -#42011 = CARTESIAN_POINT('',(2.355801997745,2.056692134382)); -#42012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42013 = PCURVE('',#42014,#42019); -#42014 = CYLINDRICAL_SURFACE('',#42015,0.16); -#42015 = AXIS2_PLACEMENT_3D('',#42016,#42017,#42018); -#42016 = CARTESIAN_POINT('',(0.15,-1.525,-0.42515457349)); -#42017 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42018 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42019 = DEFINITIONAL_REPRESENTATION('',(#42020),#42023); -#42020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42021,#42022),.UNSPECIFIED., +#44397 = CARTESIAN_POINT('',(2.355801997745,2.056692134382)); +#44398 = CARTESIAN_POINT('',(2.58416719459,2.213693207213)); +#44399 = CARTESIAN_POINT('',(2.60595151366,1.937422608989)); +#44400 = CARTESIAN_POINT('',(2.627735832731,1.661152010766)); +#44401 = CARTESIAN_POINT('',(2.377586316816,1.780421536159)); +#44402 = CARTESIAN_POINT('',(2.1274368009,1.899691061551)); +#44403 = CARTESIAN_POINT('',(2.355801997745,2.056692134382)); +#44404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44405 = PCURVE('',#44406,#44411); +#44406 = CYLINDRICAL_SURFACE('',#44407,0.16); +#44407 = AXIS2_PLACEMENT_3D('',#44408,#44409,#44410); +#44408 = CARTESIAN_POINT('',(0.15,-1.525,-0.42515457349)); +#44409 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44410 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44411 = DEFINITIONAL_REPRESENTATION('',(#44412),#44415); +#44412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44413,#44414),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#42021 = CARTESIAN_POINT('',(0.96850898066,-0.6)); -#42022 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#42023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42024 = ORIENTED_EDGE('',*,*,#42025,.F.); -#42025 = EDGE_CURVE('',#42026,#41994,#42028,.T.); -#42026 = VERTEX_POINT('',#42027); -#42027 = CARTESIAN_POINT('',(0.570685964796,-0.925,-0.520211295898)); -#42028 = SURFACE_CURVE('',#42029,(#42033,#42040),.PCURVE_S1.); -#42029 = LINE('',#42030,#42031); -#42030 = CARTESIAN_POINT('',(0.570685964796,-0.925,-0.520211295898)); -#42031 = VECTOR('',#42032,1.); -#42032 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); -#42033 = PCURVE('',#37803,#42034); -#42034 = DEFINITIONAL_REPRESENTATION('',(#42035),#42039); -#42035 = LINE('',#42036,#42037); -#42036 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); -#42037 = VECTOR('',#42038,1.); -#42038 = DIRECTION('',(0.824041924199,0.566528822887)); -#42039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42040 = PCURVE('',#42041,#42046); -#42041 = PLANE('',#42042); -#42042 = AXIS2_PLACEMENT_3D('',#42043,#42044,#42045); -#42043 = CARTESIAN_POINT('',(0.570685964796,-1.525,-0.520211295898)); -#42044 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); -#42045 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); -#42046 = DEFINITIONAL_REPRESENTATION('',(#42047),#42051); -#42047 = LINE('',#42048,#42049); -#42048 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#42049 = VECTOR('',#42050,1.); -#42050 = DIRECTION('',(1.,0.E+000)); -#42051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42052 = ORIENTED_EDGE('',*,*,#42053,.T.); -#42053 = EDGE_CURVE('',#42026,#42054,#42056,.T.); -#42054 = VERTEX_POINT('',#42055); -#42055 = CARTESIAN_POINT('',(0.79,-0.925,-0.40484542651)); -#42056 = SURFACE_CURVE('',#42057,(#42062,#42073),.PCURVE_S1.); -#42057 = CIRCLE('',#42058,0.14); -#42058 = AXIS2_PLACEMENT_3D('',#42059,#42060,#42061); -#42059 = CARTESIAN_POINT('',(0.65,-0.925,-0.40484542651)); -#42060 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42061 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); -#42062 = PCURVE('',#37803,#42063); -#42063 = DEFINITIONAL_REPRESENTATION('',(#42064),#42072); -#42064 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42065,#42066,#42067,#42068 - ,#42069,#42070,#42071),.UNSPECIFIED.,.T.,.F.) +#44413 = CARTESIAN_POINT('',(0.96850898066,-0.6)); +#44414 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#44415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44416 = ORIENTED_EDGE('',*,*,#44417,.F.); +#44417 = EDGE_CURVE('',#44418,#44386,#44420,.T.); +#44418 = VERTEX_POINT('',#44419); +#44419 = CARTESIAN_POINT('',(0.570685964796,-0.925,-0.520211295898)); +#44420 = SURFACE_CURVE('',#44421,(#44425,#44432),.PCURVE_S1.); +#44421 = LINE('',#44422,#44423); +#44422 = CARTESIAN_POINT('',(0.570685964796,-0.925,-0.520211295898)); +#44423 = VECTOR('',#44424,1.); +#44424 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); +#44425 = PCURVE('',#40195,#44426); +#44426 = DEFINITIONAL_REPRESENTATION('',(#44427),#44431); +#44427 = LINE('',#44428,#44429); +#44428 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); +#44429 = VECTOR('',#44430,1.); +#44430 = DIRECTION('',(0.824041924199,0.566528822887)); +#44431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44432 = PCURVE('',#44433,#44438); +#44433 = PLANE('',#44434); +#44434 = AXIS2_PLACEMENT_3D('',#44435,#44436,#44437); +#44435 = CARTESIAN_POINT('',(0.570685964796,-1.525,-0.520211295898)); +#44436 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); +#44437 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); +#44438 = DEFINITIONAL_REPRESENTATION('',(#44439),#44443); +#44439 = LINE('',#44440,#44441); +#44440 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44441 = VECTOR('',#44442,1.); +#44442 = DIRECTION('',(1.,0.E+000)); +#44443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44444 = ORIENTED_EDGE('',*,*,#44445,.T.); +#44445 = EDGE_CURVE('',#44418,#44446,#44448,.T.); +#44446 = VERTEX_POINT('',#44447); +#44447 = CARTESIAN_POINT('',(0.79,-0.925,-0.40484542651)); +#44448 = SURFACE_CURVE('',#44449,(#44454,#44465),.PCURVE_S1.); +#44449 = CIRCLE('',#44450,0.14); +#44450 = AXIS2_PLACEMENT_3D('',#44451,#44452,#44453); +#44451 = CARTESIAN_POINT('',(0.65,-0.925,-0.40484542651)); +#44452 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44453 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); +#44454 = PCURVE('',#40195,#44455); +#44455 = DEFINITIONAL_REPRESENTATION('',(#44456),#44464); +#44456 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44457,#44458,#44459,#44460 + ,#44461,#44462,#44463),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42065 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); -#42066 = CARTESIAN_POINT('',(1.825941097372,1.692412765375)); -#42067 = CARTESIAN_POINT('',(1.806879818185,1.934149538821)); -#42068 = CARTESIAN_POINT('',(1.787818538999,2.175886312266)); -#42069 = CARTESIAN_POINT('',(2.006699365425,2.071525477548)); -#42070 = CARTESIAN_POINT('',(2.22558019185,1.967164642829)); -#42071 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); -#42072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42073 = PCURVE('',#42074,#42079); -#42074 = CYLINDRICAL_SURFACE('',#42075,0.14); -#42075 = AXIS2_PLACEMENT_3D('',#42076,#42077,#42078); -#42076 = CARTESIAN_POINT('',(0.65,-1.525,-0.40484542651)); -#42077 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42078 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42079 = DEFINITIONAL_REPRESENTATION('',(#42080),#42083); -#42080 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42081,#42082),.UNSPECIFIED., +#44457 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); +#44458 = CARTESIAN_POINT('',(1.825941097372,1.692412765375)); +#44459 = CARTESIAN_POINT('',(1.806879818185,1.934149538821)); +#44460 = CARTESIAN_POINT('',(1.787818538999,2.175886312266)); +#44461 = CARTESIAN_POINT('',(2.006699365425,2.071525477548)); +#44462 = CARTESIAN_POINT('',(2.22558019185,1.967164642829)); +#44463 = CARTESIAN_POINT('',(2.025760644611,1.829788704102)); +#44464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44465 = PCURVE('',#44466,#44471); +#44466 = CYLINDRICAL_SURFACE('',#44467,0.14); +#44467 = AXIS2_PLACEMENT_3D('',#44468,#44469,#44470); +#44468 = CARTESIAN_POINT('',(0.65,-1.525,-0.40484542651)); +#44469 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44470 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44471 = DEFINITIONAL_REPRESENTATION('',(#44472),#44475); +#44472 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44473,#44474),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#42081 = CARTESIAN_POINT('',(4.11010163425,-0.6)); -#42082 = CARTESIAN_POINT('',(6.28318530718,-0.6)); -#42083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42084 = ORIENTED_EDGE('',*,*,#42085,.F.); -#42085 = EDGE_CURVE('',#42086,#42054,#42088,.T.); -#42086 = VERTEX_POINT('',#42087); -#42087 = CARTESIAN_POINT('',(0.79,-0.925,1.72484542651)); -#42088 = SURFACE_CURVE('',#42089,(#42093,#42100),.PCURVE_S1.); -#42089 = LINE('',#42090,#42091); -#42090 = CARTESIAN_POINT('',(0.79,-0.925,1.72484542651)); -#42091 = VECTOR('',#42092,1.); -#42092 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42093 = PCURVE('',#37803,#42094); -#42094 = DEFINITIONAL_REPRESENTATION('',(#42095),#42099); -#42095 = LINE('',#42096,#42097); -#42096 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); -#42097 = VECTOR('',#42098,1.); -#42098 = DIRECTION('',(0.E+000,-1.)); -#42099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42100 = PCURVE('',#42101,#42106); -#42101 = PLANE('',#42102); -#42102 = AXIS2_PLACEMENT_3D('',#42103,#42104,#42105); -#42103 = CARTESIAN_POINT('',(0.79,-1.525,1.72484542651)); -#42104 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42105 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42106 = DEFINITIONAL_REPRESENTATION('',(#42107),#42111); -#42107 = LINE('',#42108,#42109); -#42108 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#42109 = VECTOR('',#42110,1.); -#42110 = DIRECTION('',(1.,0.E+000)); -#42111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42112 = ORIENTED_EDGE('',*,*,#42113,.T.); -#42113 = EDGE_CURVE('',#42086,#42114,#42116,.T.); -#42114 = VERTEX_POINT('',#42115); -#42115 = CARTESIAN_POINT('',(0.570685964796,-0.925,1.840211295898)); -#42116 = SURFACE_CURVE('',#42117,(#42122,#42133),.PCURVE_S1.); -#42117 = CIRCLE('',#42118,0.14); -#42118 = AXIS2_PLACEMENT_3D('',#42119,#42120,#42121); -#42119 = CARTESIAN_POINT('',(0.65,-0.925,1.72484542651)); -#42120 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42121 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42122 = PCURVE('',#37803,#42123); -#42123 = DEFINITIONAL_REPRESENTATION('',(#42124),#42132); -#42124 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42125,#42126,#42127,#42128 - ,#42129,#42130,#42131),.UNSPECIFIED.,.T.,.F.) +#44473 = CARTESIAN_POINT('',(4.11010163425,-0.6)); +#44474 = CARTESIAN_POINT('',(6.28318530718,-0.6)); +#44475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44476 = ORIENTED_EDGE('',*,*,#44477,.F.); +#44477 = EDGE_CURVE('',#44478,#44446,#44480,.T.); +#44478 = VERTEX_POINT('',#44479); +#44479 = CARTESIAN_POINT('',(0.79,-0.925,1.72484542651)); +#44480 = SURFACE_CURVE('',#44481,(#44485,#44492),.PCURVE_S1.); +#44481 = LINE('',#44482,#44483); +#44482 = CARTESIAN_POINT('',(0.79,-0.925,1.72484542651)); +#44483 = VECTOR('',#44484,1.); +#44484 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44485 = PCURVE('',#40195,#44486); +#44486 = DEFINITIONAL_REPRESENTATION('',(#44487),#44491); +#44487 = LINE('',#44488,#44489); +#44488 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); +#44489 = VECTOR('',#44490,1.); +#44490 = DIRECTION('',(0.E+000,-1.)); +#44491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44492 = PCURVE('',#44493,#44498); +#44493 = PLANE('',#44494); +#44494 = AXIS2_PLACEMENT_3D('',#44495,#44496,#44497); +#44495 = CARTESIAN_POINT('',(0.79,-1.525,1.72484542651)); +#44496 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44497 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44498 = DEFINITIONAL_REPRESENTATION('',(#44499),#44503); +#44499 = LINE('',#44500,#44501); +#44500 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44501 = VECTOR('',#44502,1.); +#44502 = DIRECTION('',(1.,0.E+000)); +#44503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44504 = ORIENTED_EDGE('',*,*,#44505,.T.); +#44505 = EDGE_CURVE('',#44478,#44506,#44508,.T.); +#44506 = VERTEX_POINT('',#44507); +#44507 = CARTESIAN_POINT('',(0.570685964796,-0.925,1.840211295898)); +#44508 = SURFACE_CURVE('',#44509,(#44514,#44525),.PCURVE_S1.); +#44509 = CIRCLE('',#44510,0.14); +#44510 = AXIS2_PLACEMENT_3D('',#44511,#44512,#44513); +#44511 = CARTESIAN_POINT('',(0.65,-0.925,1.72484542651)); +#44512 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44513 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44514 = PCURVE('',#40195,#44515); +#44515 = DEFINITIONAL_REPRESENTATION('',(#44516),#44524); +#44516 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44517,#44518,#44519,#44520 + ,#44521,#44522,#44523),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42125 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); -#42126 = CARTESIAN_POINT('',(1.806446609407,4.31733253957)); -#42127 = CARTESIAN_POINT('',(2.016446609407,4.19608898304)); -#42128 = CARTESIAN_POINT('',(2.226446609407,4.07484542651)); -#42129 = CARTESIAN_POINT('',(2.016446609407,3.95360186998)); -#42130 = CARTESIAN_POINT('',(1.806446609407,3.83235831345)); -#42131 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); -#42132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42133 = PCURVE('',#42134,#42139); -#42134 = CYLINDRICAL_SURFACE('',#42135,0.14); -#42135 = AXIS2_PLACEMENT_3D('',#42136,#42137,#42138); -#42136 = CARTESIAN_POINT('',(0.65,-1.525,1.72484542651)); -#42137 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42138 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42139 = DEFINITIONAL_REPRESENTATION('',(#42140),#42143); -#42140 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42141,#42142),.UNSPECIFIED., +#44517 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); +#44518 = CARTESIAN_POINT('',(1.806446609407,4.31733253957)); +#44519 = CARTESIAN_POINT('',(2.016446609407,4.19608898304)); +#44520 = CARTESIAN_POINT('',(2.226446609407,4.07484542651)); +#44521 = CARTESIAN_POINT('',(2.016446609407,3.95360186998)); +#44522 = CARTESIAN_POINT('',(1.806446609407,3.83235831345)); +#44523 = CARTESIAN_POINT('',(1.806446609407,4.07484542651)); +#44524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44525 = PCURVE('',#44526,#44531); +#44526 = CYLINDRICAL_SURFACE('',#44527,0.14); +#44527 = AXIS2_PLACEMENT_3D('',#44528,#44529,#44530); +#44528 = CARTESIAN_POINT('',(0.65,-1.525,1.72484542651)); +#44529 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44530 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44531 = DEFINITIONAL_REPRESENTATION('',(#44532),#44535); +#44532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44533,#44534),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#42141 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#42142 = CARTESIAN_POINT('',(2.17308367293,-0.6)); -#42143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42144 = ORIENTED_EDGE('',*,*,#42145,.F.); -#42145 = EDGE_CURVE('',#42146,#42114,#42148,.T.); -#42146 = VERTEX_POINT('',#42147); -#42147 = CARTESIAN_POINT('',(0.240644611662,-0.925,1.613307865618)); -#42148 = SURFACE_CURVE('',#42149,(#42153,#42160),.PCURVE_S1.); -#42149 = LINE('',#42150,#42151); -#42150 = CARTESIAN_POINT('',(0.240644611662,-0.925,1.613307865618)); -#42151 = VECTOR('',#42152,1.); -#42152 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); -#42153 = PCURVE('',#37803,#42154); -#42154 = DEFINITIONAL_REPRESENTATION('',(#42155),#42159); -#42155 = LINE('',#42156,#42157); -#42156 = CARTESIAN_POINT('',(2.355801997745,3.963307865618)); -#42157 = VECTOR('',#42158,1.); -#42158 = DIRECTION('',(-0.824041924199,0.566528822887)); -#42159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42160 = PCURVE('',#42161,#42166); -#42161 = PLANE('',#42162); -#42162 = AXIS2_PLACEMENT_3D('',#42163,#42164,#42165); -#42163 = CARTESIAN_POINT('',(0.240644611662,-1.525,1.613307865618)); -#42164 = DIRECTION('',(0.566528822887,0.E+000,-0.824041924199)); -#42165 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); -#42166 = DEFINITIONAL_REPRESENTATION('',(#42167),#42171); -#42167 = LINE('',#42168,#42169); -#42168 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#42169 = VECTOR('',#42170,1.); -#42170 = DIRECTION('',(1.,0.E+000)); -#42171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42172 = ORIENTED_EDGE('',*,*,#42173,.F.); -#42173 = EDGE_CURVE('',#42174,#42146,#42176,.T.); -#42174 = VERTEX_POINT('',#42175); -#42175 = CARTESIAN_POINT('',(-1.E-002,-0.925,1.74515457349)); -#42176 = SURFACE_CURVE('',#42177,(#42182,#42193),.PCURVE_S1.); -#42177 = CIRCLE('',#42178,0.16); -#42178 = AXIS2_PLACEMENT_3D('',#42179,#42180,#42181); -#42179 = CARTESIAN_POINT('',(0.15,-0.925,1.74515457349)); -#42180 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42181 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42182 = PCURVE('',#37803,#42183); -#42183 = DEFINITIONAL_REPRESENTATION('',(#42184),#42192); -#42184 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42185,#42186,#42187,#42188 - ,#42189,#42190,#42191),.UNSPECIFIED.,.T.,.F.) +#44533 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44534 = CARTESIAN_POINT('',(2.17308367293,-0.6)); +#44535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44536 = ORIENTED_EDGE('',*,*,#44537,.F.); +#44537 = EDGE_CURVE('',#44538,#44506,#44540,.T.); +#44538 = VERTEX_POINT('',#44539); +#44539 = CARTESIAN_POINT('',(0.240644611662,-0.925,1.613307865618)); +#44540 = SURFACE_CURVE('',#44541,(#44545,#44552),.PCURVE_S1.); +#44541 = LINE('',#44542,#44543); +#44542 = CARTESIAN_POINT('',(0.240644611662,-0.925,1.613307865618)); +#44543 = VECTOR('',#44544,1.); +#44544 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); +#44545 = PCURVE('',#40195,#44546); +#44546 = DEFINITIONAL_REPRESENTATION('',(#44547),#44551); +#44547 = LINE('',#44548,#44549); +#44548 = CARTESIAN_POINT('',(2.355801997745,3.963307865618)); +#44549 = VECTOR('',#44550,1.); +#44550 = DIRECTION('',(-0.824041924199,0.566528822887)); +#44551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44552 = PCURVE('',#44553,#44558); +#44553 = PLANE('',#44554); +#44554 = AXIS2_PLACEMENT_3D('',#44555,#44556,#44557); +#44555 = CARTESIAN_POINT('',(0.240644611662,-1.525,1.613307865618)); +#44556 = DIRECTION('',(0.566528822887,0.E+000,-0.824041924199)); +#44557 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); +#44558 = DEFINITIONAL_REPRESENTATION('',(#44559),#44563); +#44559 = LINE('',#44560,#44561); +#44560 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#44561 = VECTOR('',#44562,1.); +#44562 = DIRECTION('',(1.,0.E+000)); +#44563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44564 = ORIENTED_EDGE('',*,*,#44565,.F.); +#44565 = EDGE_CURVE('',#44566,#44538,#44568,.T.); +#44566 = VERTEX_POINT('',#44567); +#44567 = CARTESIAN_POINT('',(-1.E-002,-0.925,1.74515457349)); +#44568 = SURFACE_CURVE('',#44569,(#44574,#44585),.PCURVE_S1.); +#44569 = CIRCLE('',#44570,0.16); +#44570 = AXIS2_PLACEMENT_3D('',#44571,#44572,#44573); +#44571 = CARTESIAN_POINT('',(0.15,-0.925,1.74515457349)); +#44572 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44573 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44574 = PCURVE('',#40195,#44575); +#44575 = DEFINITIONAL_REPRESENTATION('',(#44576),#44584); +#44576 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44577,#44578,#44579,#44580 + ,#44581,#44582,#44583),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42185 = CARTESIAN_POINT('',(2.606446609407,4.09515457349)); -#42186 = CARTESIAN_POINT('',(2.606446609407,3.818026444279)); -#42187 = CARTESIAN_POINT('',(2.366446609407,3.956590508884)); -#42188 = CARTESIAN_POINT('',(2.126446609407,4.09515457349)); -#42189 = CARTESIAN_POINT('',(2.366446609407,4.233718638096)); -#42190 = CARTESIAN_POINT('',(2.606446609407,4.372282702701)); -#42191 = CARTESIAN_POINT('',(2.606446609407,4.09515457349)); -#42192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42193 = PCURVE('',#42194,#42199); -#42194 = CYLINDRICAL_SURFACE('',#42195,0.16); -#42195 = AXIS2_PLACEMENT_3D('',#42196,#42197,#42198); -#42196 = CARTESIAN_POINT('',(0.15,-1.525,1.74515457349)); -#42197 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42198 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42199 = DEFINITIONAL_REPRESENTATION('',(#42200),#42203); -#42200 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42201,#42202),.UNSPECIFIED., +#44577 = CARTESIAN_POINT('',(2.606446609407,4.09515457349)); +#44578 = CARTESIAN_POINT('',(2.606446609407,3.818026444279)); +#44579 = CARTESIAN_POINT('',(2.366446609407,3.956590508884)); +#44580 = CARTESIAN_POINT('',(2.126446609407,4.09515457349)); +#44581 = CARTESIAN_POINT('',(2.366446609407,4.233718638096)); +#44582 = CARTESIAN_POINT('',(2.606446609407,4.372282702701)); +#44583 = CARTESIAN_POINT('',(2.606446609407,4.09515457349)); +#44584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44585 = PCURVE('',#44586,#44591); +#44586 = CYLINDRICAL_SURFACE('',#44587,0.16); +#44587 = AXIS2_PLACEMENT_3D('',#44588,#44589,#44590); +#44588 = CARTESIAN_POINT('',(0.15,-1.525,1.74515457349)); +#44589 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44590 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44591 = DEFINITIONAL_REPRESENTATION('',(#44592),#44595); +#44592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44593,#44594),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.173083672929),.PIECEWISE_BEZIER_KNOTS.); -#42201 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#42202 = CARTESIAN_POINT('',(5.314676326519,-0.6)); -#42203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42204 = ORIENTED_EDGE('',*,*,#42205,.F.); -#42205 = EDGE_CURVE('',#42206,#42174,#42208,.T.); -#42206 = VERTEX_POINT('',#42207); -#42207 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); -#42208 = SURFACE_CURVE('',#42209,(#42213,#42220),.PCURVE_S1.); -#42209 = LINE('',#42210,#42211); -#42210 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); -#42211 = VECTOR('',#42212,1.); -#42212 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42213 = PCURVE('',#37803,#42214); -#42214 = DEFINITIONAL_REPRESENTATION('',(#42215),#42219); -#42215 = LINE('',#42216,#42217); -#42216 = CARTESIAN_POINT('',(2.606446609407,4.704813742174)); -#42217 = VECTOR('',#42218,1.); -#42218 = DIRECTION('',(0.E+000,-1.)); -#42219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42220 = PCURVE('',#42221,#42226); -#42221 = PLANE('',#42222); -#42222 = AXIS2_PLACEMENT_3D('',#42223,#42224,#42225); -#42223 = CARTESIAN_POINT('',(-1.E-002,-1.525,2.78)); -#42224 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42225 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42226 = DEFINITIONAL_REPRESENTATION('',(#42227),#42231); -#42227 = LINE('',#42228,#42229); -#42228 = CARTESIAN_POINT('',(0.425186257826,-0.6)); -#42229 = VECTOR('',#42230,1.); -#42230 = DIRECTION('',(1.,0.E+000)); -#42231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42232 = ORIENTED_EDGE('',*,*,#42233,.T.); -#42233 = EDGE_CURVE('',#42206,#42234,#42236,.T.); -#42234 = VERTEX_POINT('',#42235); -#42235 = CARTESIAN_POINT('',(-2.5,-0.925,2.354813742174)); -#42236 = SURFACE_CURVE('',#42237,(#42241,#42248),.PCURVE_S1.); -#42237 = LINE('',#42238,#42239); -#42238 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); -#42239 = VECTOR('',#42240,1.); -#42240 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42241 = PCURVE('',#37803,#42242); -#42242 = DEFINITIONAL_REPRESENTATION('',(#42243),#42247); -#42243 = LINE('',#42244,#42245); -#42244 = CARTESIAN_POINT('',(2.606446609407,4.704813742174)); -#42245 = VECTOR('',#42246,1.); -#42246 = DIRECTION('',(1.,0.E+000)); -#42247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42248 = PCURVE('',#42249,#42254); -#42249 = CYLINDRICAL_SURFACE('',#42250,0.29); -#42250 = AXIS2_PLACEMENT_3D('',#42251,#42252,#42253); -#42251 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); -#42252 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42253 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42254 = DEFINITIONAL_REPRESENTATION('',(#42255),#42258); -#42255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42256,#42257),.UNSPECIFIED., +#44593 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#44594 = CARTESIAN_POINT('',(5.314676326519,-0.6)); +#44595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44596 = ORIENTED_EDGE('',*,*,#44597,.F.); +#44597 = EDGE_CURVE('',#44598,#44566,#44600,.T.); +#44598 = VERTEX_POINT('',#44599); +#44599 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); +#44600 = SURFACE_CURVE('',#44601,(#44605,#44612),.PCURVE_S1.); +#44601 = LINE('',#44602,#44603); +#44602 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); +#44603 = VECTOR('',#44604,1.); +#44604 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44605 = PCURVE('',#40195,#44606); +#44606 = DEFINITIONAL_REPRESENTATION('',(#44607),#44611); +#44607 = LINE('',#44608,#44609); +#44608 = CARTESIAN_POINT('',(2.606446609407,4.704813742174)); +#44609 = VECTOR('',#44610,1.); +#44610 = DIRECTION('',(0.E+000,-1.)); +#44611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44612 = PCURVE('',#44613,#44618); +#44613 = PLANE('',#44614); +#44614 = AXIS2_PLACEMENT_3D('',#44615,#44616,#44617); +#44615 = CARTESIAN_POINT('',(-1.E-002,-1.525,2.78)); +#44616 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44617 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44618 = DEFINITIONAL_REPRESENTATION('',(#44619),#44623); +#44619 = LINE('',#44620,#44621); +#44620 = CARTESIAN_POINT('',(0.425186257826,-0.6)); +#44621 = VECTOR('',#44622,1.); +#44622 = DIRECTION('',(1.,0.E+000)); +#44623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44624 = ORIENTED_EDGE('',*,*,#44625,.T.); +#44625 = EDGE_CURVE('',#44598,#44626,#44628,.T.); +#44626 = VERTEX_POINT('',#44627); +#44627 = CARTESIAN_POINT('',(-2.5,-0.925,2.354813742174)); +#44628 = SURFACE_CURVE('',#44629,(#44633,#44640),.PCURVE_S1.); +#44629 = LINE('',#44630,#44631); +#44630 = CARTESIAN_POINT('',(-1.E-002,-0.925,2.354813742174)); +#44631 = VECTOR('',#44632,1.); +#44632 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44633 = PCURVE('',#40195,#44634); +#44634 = DEFINITIONAL_REPRESENTATION('',(#44635),#44639); +#44635 = LINE('',#44636,#44637); +#44636 = CARTESIAN_POINT('',(2.606446609407,4.704813742174)); +#44637 = VECTOR('',#44638,1.); +#44638 = DIRECTION('',(1.,0.E+000)); +#44639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44640 = PCURVE('',#44641,#44646); +#44641 = CYLINDRICAL_SURFACE('',#44642,0.29); +#44642 = AXIS2_PLACEMENT_3D('',#44643,#44644,#44645); +#44643 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); +#44644 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44645 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44646 = DEFINITIONAL_REPRESENTATION('',(#44647),#44650); +#44647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44648,#44649),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.49),.PIECEWISE_BEZIER_KNOTS.); -#42256 = CARTESIAN_POINT('',(1.570796326795,2.51)); -#42257 = CARTESIAN_POINT('',(1.570796326795,5.)); -#42258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42259 = ORIENTED_EDGE('',*,*,#42260,.T.); -#42260 = EDGE_CURVE('',#42234,#37788,#42261,.T.); -#42261 = SURFACE_CURVE('',#42262,(#42266,#42273),.PCURVE_S1.); -#42262 = LINE('',#42263,#42264); -#42263 = CARTESIAN_POINT('',(-2.5,-0.925,2.354813742174)); -#42264 = VECTOR('',#42265,1.); -#42265 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42266 = PCURVE('',#37803,#42267); -#42267 = DEFINITIONAL_REPRESENTATION('',(#42268),#42272); -#42268 = LINE('',#42269,#42270); -#42269 = CARTESIAN_POINT('',(5.096446609407,4.704813742174)); -#42270 = VECTOR('',#42271,1.); -#42271 = DIRECTION('',(0.E+000,-1.)); -#42272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42273 = PCURVE('',#37831,#42274); -#42274 = DEFINITIONAL_REPRESENTATION('',(#42275),#42279); -#42275 = LINE('',#42276,#42277); -#42276 = CARTESIAN_POINT('',(2.354813742174,-0.925)); -#42277 = VECTOR('',#42278,1.); -#42278 = DIRECTION('',(-1.,0.E+000)); -#42279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42280 = ORIENTED_EDGE('',*,*,#37787,.T.); -#42281 = ORIENTED_EDGE('',*,*,#42282,.F.); -#42282 = EDGE_CURVE('',#42283,#37756,#42285,.T.); -#42283 = VERTEX_POINT('',#42284); -#42284 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); -#42285 = SURFACE_CURVE('',#42286,(#42290,#42297),.PCURVE_S1.); -#42286 = LINE('',#42287,#42288); -#42287 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); -#42288 = VECTOR('',#42289,1.); -#42289 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42290 = PCURVE('',#37803,#42291); -#42291 = DEFINITIONAL_REPRESENTATION('',(#42292),#42296); -#42292 = LINE('',#42293,#42294); -#42293 = CARTESIAN_POINT('',(5.192893218814,3.31)); -#42294 = VECTOR('',#42295,1.); -#42295 = DIRECTION('',(0.E+000,1.)); -#42296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42297 = PCURVE('',#37776,#42298); -#42298 = DEFINITIONAL_REPRESENTATION('',(#42299),#42302); -#42299 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42300,#42301),.UNSPECIFIED., +#44648 = CARTESIAN_POINT('',(1.570796326795,2.51)); +#44649 = CARTESIAN_POINT('',(1.570796326795,5.)); +#44650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44651 = ORIENTED_EDGE('',*,*,#44652,.T.); +#44652 = EDGE_CURVE('',#44626,#40180,#44653,.T.); +#44653 = SURFACE_CURVE('',#44654,(#44658,#44665),.PCURVE_S1.); +#44654 = LINE('',#44655,#44656); +#44655 = CARTESIAN_POINT('',(-2.5,-0.925,2.354813742174)); +#44656 = VECTOR('',#44657,1.); +#44657 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44658 = PCURVE('',#40195,#44659); +#44659 = DEFINITIONAL_REPRESENTATION('',(#44660),#44664); +#44660 = LINE('',#44661,#44662); +#44661 = CARTESIAN_POINT('',(5.096446609407,4.704813742174)); +#44662 = VECTOR('',#44663,1.); +#44663 = DIRECTION('',(0.E+000,-1.)); +#44664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44665 = PCURVE('',#40223,#44666); +#44666 = DEFINITIONAL_REPRESENTATION('',(#44667),#44671); +#44667 = LINE('',#44668,#44669); +#44668 = CARTESIAN_POINT('',(2.354813742174,-0.925)); +#44669 = VECTOR('',#44670,1.); +#44670 = DIRECTION('',(-1.,0.E+000)); +#44671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44672 = ORIENTED_EDGE('',*,*,#40179,.T.); +#44673 = ORIENTED_EDGE('',*,*,#44674,.F.); +#44674 = EDGE_CURVE('',#44675,#40148,#44677,.T.); +#44675 = VERTEX_POINT('',#44676); +#44676 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); +#44677 = SURFACE_CURVE('',#44678,(#44682,#44689),.PCURVE_S1.); +#44678 = LINE('',#44679,#44680); +#44679 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); +#44680 = VECTOR('',#44681,1.); +#44681 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44682 = PCURVE('',#40195,#44683); +#44683 = DEFINITIONAL_REPRESENTATION('',(#44684),#44688); +#44684 = LINE('',#44685,#44686); +#44685 = CARTESIAN_POINT('',(5.192893218814,3.31)); +#44686 = VECTOR('',#44687,1.); +#44687 = DIRECTION('',(0.E+000,1.)); +#44688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44689 = PCURVE('',#40168,#44690); +#44690 = DEFINITIONAL_REPRESENTATION('',(#44691),#44694); +#44691 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44692,#44693),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#42300 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#42301 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#42302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42303 = ORIENTED_EDGE('',*,*,#42304,.T.); -#42304 = EDGE_CURVE('',#42283,#42305,#42307,.T.); -#42305 = VERTEX_POINT('',#42306); -#42306 = CARTESIAN_POINT('',(-2.4,-0.925,0.96)); -#42307 = SURFACE_CURVE('',#42308,(#42312,#42319),.PCURVE_S1.); -#42308 = LINE('',#42309,#42310); -#42309 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); -#42310 = VECTOR('',#42311,1.); -#42311 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42312 = PCURVE('',#37803,#42313); -#42313 = DEFINITIONAL_REPRESENTATION('',(#42314),#42318); -#42314 = LINE('',#42315,#42316); -#42315 = CARTESIAN_POINT('',(5.192893218814,3.31)); -#42316 = VECTOR('',#42317,1.); -#42317 = DIRECTION('',(-1.,0.E+000)); -#42318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42319 = PCURVE('',#42320,#42325); -#42320 = PLANE('',#42321); -#42321 = AXIS2_PLACEMENT_3D('',#42322,#42323,#42324); -#42322 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); -#42323 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42324 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42325 = DEFINITIONAL_REPRESENTATION('',(#42326),#42330); -#42326 = LINE('',#42327,#42328); -#42327 = CARTESIAN_POINT('',(0.196446609407,-0.3)); -#42328 = VECTOR('',#42329,1.); -#42329 = DIRECTION('',(-1.,0.E+000)); -#42330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42331 = ORIENTED_EDGE('',*,*,#42332,.F.); -#42332 = EDGE_CURVE('',#42333,#42305,#42335,.T.); -#42333 = VERTEX_POINT('',#42334); -#42334 = CARTESIAN_POINT('',(-2.25,-0.925,0.81)); -#42335 = SURFACE_CURVE('',#42336,(#42341,#42352),.PCURVE_S1.); -#42336 = CIRCLE('',#42337,0.15); -#42337 = AXIS2_PLACEMENT_3D('',#42338,#42339,#42340); -#42338 = CARTESIAN_POINT('',(-2.4,-0.925,0.81)); -#42339 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42340 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42341 = PCURVE('',#37803,#42342); -#42342 = DEFINITIONAL_REPRESENTATION('',(#42343),#42351); -#42343 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42344,#42345,#42346,#42347 - ,#42348,#42349,#42350),.UNSPECIFIED.,.F.,.F.) +#44692 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#44693 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#44694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44695 = ORIENTED_EDGE('',*,*,#44696,.T.); +#44696 = EDGE_CURVE('',#44675,#44697,#44699,.T.); +#44697 = VERTEX_POINT('',#44698); +#44698 = CARTESIAN_POINT('',(-2.4,-0.925,0.96)); +#44699 = SURFACE_CURVE('',#44700,(#44704,#44711),.PCURVE_S1.); +#44700 = LINE('',#44701,#44702); +#44701 = CARTESIAN_POINT('',(-2.596446609407,-0.925,0.96)); +#44702 = VECTOR('',#44703,1.); +#44703 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44704 = PCURVE('',#40195,#44705); +#44705 = DEFINITIONAL_REPRESENTATION('',(#44706),#44710); +#44706 = LINE('',#44707,#44708); +#44707 = CARTESIAN_POINT('',(5.192893218814,3.31)); +#44708 = VECTOR('',#44709,1.); +#44709 = DIRECTION('',(-1.,0.E+000)); +#44710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44711 = PCURVE('',#44712,#44717); +#44712 = PLANE('',#44713); +#44713 = AXIS2_PLACEMENT_3D('',#44714,#44715,#44716); +#44714 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); +#44715 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44716 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44717 = DEFINITIONAL_REPRESENTATION('',(#44718),#44722); +#44718 = LINE('',#44719,#44720); +#44719 = CARTESIAN_POINT('',(0.196446609407,-0.3)); +#44720 = VECTOR('',#44721,1.); +#44721 = DIRECTION('',(-1.,0.E+000)); +#44722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44723 = ORIENTED_EDGE('',*,*,#44724,.F.); +#44724 = EDGE_CURVE('',#44725,#44697,#44727,.T.); +#44725 = VERTEX_POINT('',#44726); +#44726 = CARTESIAN_POINT('',(-2.25,-0.925,0.81)); +#44727 = SURFACE_CURVE('',#44728,(#44733,#44744),.PCURVE_S1.); +#44728 = CIRCLE('',#44729,0.15); +#44729 = AXIS2_PLACEMENT_3D('',#44730,#44731,#44732); +#44730 = CARTESIAN_POINT('',(-2.4,-0.925,0.81)); +#44731 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44732 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44733 = PCURVE('',#40195,#44734); +#44734 = DEFINITIONAL_REPRESENTATION('',(#44735),#44743); +#44735 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44736,#44737,#44738,#44739 + ,#44740,#44741,#44742),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42344 = CARTESIAN_POINT('',(4.846446609407,3.16)); -#42345 = CARTESIAN_POINT('',(4.846446609407,3.419807621135)); -#42346 = CARTESIAN_POINT('',(5.071446609407,3.289903810568)); -#42347 = CARTESIAN_POINT('',(5.296446609407,3.16)); -#42348 = CARTESIAN_POINT('',(5.071446609407,3.030096189432)); -#42349 = CARTESIAN_POINT('',(4.846446609407,2.900192378865)); -#42350 = CARTESIAN_POINT('',(4.846446609407,3.16)); -#42351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42352 = PCURVE('',#42353,#42358); -#42353 = CYLINDRICAL_SURFACE('',#42354,0.15); -#42354 = AXIS2_PLACEMENT_3D('',#42355,#42356,#42357); -#42355 = CARTESIAN_POINT('',(-2.4,-1.225,0.81)); -#42356 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42357 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42358 = DEFINITIONAL_REPRESENTATION('',(#42359),#42362); -#42359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42360,#42361),.UNSPECIFIED., +#44736 = CARTESIAN_POINT('',(4.846446609407,3.16)); +#44737 = CARTESIAN_POINT('',(4.846446609407,3.419807621135)); +#44738 = CARTESIAN_POINT('',(5.071446609407,3.289903810568)); +#44739 = CARTESIAN_POINT('',(5.296446609407,3.16)); +#44740 = CARTESIAN_POINT('',(5.071446609407,3.030096189432)); +#44741 = CARTESIAN_POINT('',(4.846446609407,2.900192378865)); +#44742 = CARTESIAN_POINT('',(4.846446609407,3.16)); +#44743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44744 = PCURVE('',#44745,#44750); +#44745 = CYLINDRICAL_SURFACE('',#44746,0.15); +#44746 = AXIS2_PLACEMENT_3D('',#44747,#44748,#44749); +#44747 = CARTESIAN_POINT('',(-2.4,-1.225,0.81)); +#44748 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44749 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44750 = DEFINITIONAL_REPRESENTATION('',(#44751),#44754); +#44751 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44752,#44753),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42360 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42361 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#42362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42363 = ORIENTED_EDGE('',*,*,#42364,.F.); -#42364 = EDGE_CURVE('',#42365,#42333,#42367,.T.); -#42365 = VERTEX_POINT('',#42366); -#42366 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); -#42367 = SURFACE_CURVE('',#42368,(#42372,#42379),.PCURVE_S1.); -#42368 = LINE('',#42369,#42370); -#42369 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); -#42370 = VECTOR('',#42371,1.); -#42371 = DIRECTION('',(0.E+000,-3.330669073875E-014,1.)); -#42372 = PCURVE('',#37803,#42373); -#42373 = DEFINITIONAL_REPRESENTATION('',(#42374),#42378); -#42374 = LINE('',#42375,#42376); -#42375 = CARTESIAN_POINT('',(4.846446609407,3.15)); -#42376 = VECTOR('',#42377,1.); -#42377 = DIRECTION('',(0.E+000,1.)); -#42378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42379 = PCURVE('',#42380,#42385); -#42380 = PLANE('',#42381); -#42381 = AXIS2_PLACEMENT_3D('',#42382,#42383,#42384); -#42382 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); -#42383 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42384 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42385 = DEFINITIONAL_REPRESENTATION('',(#42386),#42390); -#42386 = LINE('',#42387,#42388); -#42387 = CARTESIAN_POINT('',(1.21,-0.3)); -#42388 = VECTOR('',#42389,1.); -#42389 = DIRECTION('',(1.,3.330669073875E-014)); -#42390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42391 = ORIENTED_EDGE('',*,*,#42392,.T.); -#42392 = EDGE_CURVE('',#42365,#42393,#42395,.T.); -#42393 = VERTEX_POINT('',#42394); -#42394 = CARTESIAN_POINT('',(-2.4,-0.925,0.65)); -#42395 = SURFACE_CURVE('',#42396,(#42401,#42408),.PCURVE_S1.); -#42396 = CIRCLE('',#42397,0.15); -#42397 = AXIS2_PLACEMENT_3D('',#42398,#42399,#42400); -#42398 = CARTESIAN_POINT('',(-2.4,-0.925,0.8)); -#42399 = DIRECTION('',(0.E+000,1.,0.E+000)); -#42400 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42401 = PCURVE('',#37803,#42402); -#42402 = DEFINITIONAL_REPRESENTATION('',(#42403),#42407); -#42403 = CIRCLE('',#42404,0.15); -#42404 = AXIS2_PLACEMENT_2D('',#42405,#42406); -#42405 = CARTESIAN_POINT('',(4.996446609407,3.15)); -#42406 = DIRECTION('',(-1.,0.E+000)); -#42407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42408 = PCURVE('',#42409,#42414); -#42409 = CYLINDRICAL_SURFACE('',#42410,0.15); -#42410 = AXIS2_PLACEMENT_3D('',#42411,#42412,#42413); -#42411 = CARTESIAN_POINT('',(-2.4,-1.225,0.8)); -#42412 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42413 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42414 = DEFINITIONAL_REPRESENTATION('',(#42415),#42418); -#42415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42416,#42417),.UNSPECIFIED., +#44752 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44753 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#44754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44755 = ORIENTED_EDGE('',*,*,#44756,.F.); +#44756 = EDGE_CURVE('',#44757,#44725,#44759,.T.); +#44757 = VERTEX_POINT('',#44758); +#44758 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); +#44759 = SURFACE_CURVE('',#44760,(#44764,#44771),.PCURVE_S1.); +#44760 = LINE('',#44761,#44762); +#44761 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); +#44762 = VECTOR('',#44763,1.); +#44763 = DIRECTION('',(0.E+000,-3.330669073875E-014,1.)); +#44764 = PCURVE('',#40195,#44765); +#44765 = DEFINITIONAL_REPRESENTATION('',(#44766),#44770); +#44766 = LINE('',#44767,#44768); +#44767 = CARTESIAN_POINT('',(4.846446609407,3.15)); +#44768 = VECTOR('',#44769,1.); +#44769 = DIRECTION('',(0.E+000,1.)); +#44770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44771 = PCURVE('',#44772,#44777); +#44772 = PLANE('',#44773); +#44773 = AXIS2_PLACEMENT_3D('',#44774,#44775,#44776); +#44774 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); +#44775 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44776 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44777 = DEFINITIONAL_REPRESENTATION('',(#44778),#44782); +#44778 = LINE('',#44779,#44780); +#44779 = CARTESIAN_POINT('',(1.21,-0.3)); +#44780 = VECTOR('',#44781,1.); +#44781 = DIRECTION('',(1.,3.330669073875E-014)); +#44782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44783 = ORIENTED_EDGE('',*,*,#44784,.T.); +#44784 = EDGE_CURVE('',#44757,#44785,#44787,.T.); +#44785 = VERTEX_POINT('',#44786); +#44786 = CARTESIAN_POINT('',(-2.4,-0.925,0.65)); +#44787 = SURFACE_CURVE('',#44788,(#44793,#44800),.PCURVE_S1.); +#44788 = CIRCLE('',#44789,0.15); +#44789 = AXIS2_PLACEMENT_3D('',#44790,#44791,#44792); +#44790 = CARTESIAN_POINT('',(-2.4,-0.925,0.8)); +#44791 = DIRECTION('',(0.E+000,1.,0.E+000)); +#44792 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44793 = PCURVE('',#40195,#44794); +#44794 = DEFINITIONAL_REPRESENTATION('',(#44795),#44799); +#44795 = CIRCLE('',#44796,0.15); +#44796 = AXIS2_PLACEMENT_2D('',#44797,#44798); +#44797 = CARTESIAN_POINT('',(4.996446609407,3.15)); +#44798 = DIRECTION('',(-1.,0.E+000)); +#44799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44800 = PCURVE('',#44801,#44806); +#44801 = CYLINDRICAL_SURFACE('',#44802,0.15); +#44802 = AXIS2_PLACEMENT_3D('',#44803,#44804,#44805); +#44803 = CARTESIAN_POINT('',(-2.4,-1.225,0.8)); +#44804 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44805 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44806 = DEFINITIONAL_REPRESENTATION('',(#44807),#44810); +#44807 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44808,#44809),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42416 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#42417 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#42418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42419 = ORIENTED_EDGE('',*,*,#42420,.T.); -#42420 = EDGE_CURVE('',#42393,#42421,#42423,.T.); -#42421 = VERTEX_POINT('',#42422); -#42422 = CARTESIAN_POINT('',(-3.7,-0.925,0.65)); -#42423 = SURFACE_CURVE('',#42424,(#42428,#42435),.PCURVE_S1.); -#42424 = LINE('',#42425,#42426); -#42425 = CARTESIAN_POINT('',(-2.4,-0.925,0.65)); -#42426 = VECTOR('',#42427,1.); -#42427 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42428 = PCURVE('',#37803,#42429); -#42429 = DEFINITIONAL_REPRESENTATION('',(#42430),#42434); -#42430 = LINE('',#42431,#42432); -#42431 = CARTESIAN_POINT('',(4.996446609407,3.)); -#42432 = VECTOR('',#42433,1.); -#42433 = DIRECTION('',(1.,0.E+000)); -#42434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42435 = PCURVE('',#42436,#42441); -#42436 = PLANE('',#42437); -#42437 = AXIS2_PLACEMENT_3D('',#42438,#42439,#42440); -#42438 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); -#42439 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42440 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42441 = DEFINITIONAL_REPRESENTATION('',(#42442),#42446); -#42442 = LINE('',#42443,#42444); -#42443 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42444 = VECTOR('',#42445,1.); -#42445 = DIRECTION('',(1.,0.E+000)); -#42446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42447 = ORIENTED_EDGE('',*,*,#42448,.T.); -#42448 = EDGE_CURVE('',#42421,#42449,#42451,.T.); -#42449 = VERTEX_POINT('',#42450); -#42450 = CARTESIAN_POINT('',(-3.9,-0.925,0.45)); -#42451 = SURFACE_CURVE('',#42452,(#42457,#42468),.PCURVE_S1.); -#42452 = CIRCLE('',#42453,0.2); -#42453 = AXIS2_PLACEMENT_3D('',#42454,#42455,#42456); -#42454 = CARTESIAN_POINT('',(-3.7,-0.925,0.45)); -#42455 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42456 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42457 = PCURVE('',#37803,#42458); -#42458 = DEFINITIONAL_REPRESENTATION('',(#42459),#42467); -#42459 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42460,#42461,#42462,#42463 - ,#42464,#42465,#42466),.UNSPECIFIED.,.F.,.F.) +#44808 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#44809 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#44810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44811 = ORIENTED_EDGE('',*,*,#44812,.T.); +#44812 = EDGE_CURVE('',#44785,#44813,#44815,.T.); +#44813 = VERTEX_POINT('',#44814); +#44814 = CARTESIAN_POINT('',(-3.7,-0.925,0.65)); +#44815 = SURFACE_CURVE('',#44816,(#44820,#44827),.PCURVE_S1.); +#44816 = LINE('',#44817,#44818); +#44817 = CARTESIAN_POINT('',(-2.4,-0.925,0.65)); +#44818 = VECTOR('',#44819,1.); +#44819 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44820 = PCURVE('',#40195,#44821); +#44821 = DEFINITIONAL_REPRESENTATION('',(#44822),#44826); +#44822 = LINE('',#44823,#44824); +#44823 = CARTESIAN_POINT('',(4.996446609407,3.)); +#44824 = VECTOR('',#44825,1.); +#44825 = DIRECTION('',(1.,0.E+000)); +#44826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44827 = PCURVE('',#44828,#44833); +#44828 = PLANE('',#44829); +#44829 = AXIS2_PLACEMENT_3D('',#44830,#44831,#44832); +#44830 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); +#44831 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44832 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44833 = DEFINITIONAL_REPRESENTATION('',(#44834),#44838); +#44834 = LINE('',#44835,#44836); +#44835 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44836 = VECTOR('',#44837,1.); +#44837 = DIRECTION('',(1.,0.E+000)); +#44838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44839 = ORIENTED_EDGE('',*,*,#44840,.T.); +#44840 = EDGE_CURVE('',#44813,#44841,#44843,.T.); +#44841 = VERTEX_POINT('',#44842); +#44842 = CARTESIAN_POINT('',(-3.9,-0.925,0.45)); +#44843 = SURFACE_CURVE('',#44844,(#44849,#44860),.PCURVE_S1.); +#44844 = CIRCLE('',#44845,0.2); +#44845 = AXIS2_PLACEMENT_3D('',#44846,#44847,#44848); +#44846 = CARTESIAN_POINT('',(-3.7,-0.925,0.45)); +#44847 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44848 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44849 = PCURVE('',#40195,#44850); +#44850 = DEFINITIONAL_REPRESENTATION('',(#44851),#44859); +#44851 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44852,#44853,#44854,#44855 + ,#44856,#44857,#44858),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42460 = CARTESIAN_POINT('',(6.296446609407,3.)); -#42461 = CARTESIAN_POINT('',(6.642856770921,3.)); -#42462 = CARTESIAN_POINT('',(6.469651690164,2.7)); -#42463 = CARTESIAN_POINT('',(6.296446609407,2.4)); -#42464 = CARTESIAN_POINT('',(6.12324152865,2.7)); -#42465 = CARTESIAN_POINT('',(5.950036447893,3.)); -#42466 = CARTESIAN_POINT('',(6.296446609407,3.)); -#42467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42468 = PCURVE('',#42469,#42474); -#42469 = CYLINDRICAL_SURFACE('',#42470,0.2); -#42470 = AXIS2_PLACEMENT_3D('',#42471,#42472,#42473); -#42471 = CARTESIAN_POINT('',(-3.7,-1.225,0.45)); -#42472 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42473 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42474 = DEFINITIONAL_REPRESENTATION('',(#42475),#42478); -#42475 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42476,#42477),.UNSPECIFIED., +#44852 = CARTESIAN_POINT('',(6.296446609407,3.)); +#44853 = CARTESIAN_POINT('',(6.642856770921,3.)); +#44854 = CARTESIAN_POINT('',(6.469651690164,2.7)); +#44855 = CARTESIAN_POINT('',(6.296446609407,2.4)); +#44856 = CARTESIAN_POINT('',(6.12324152865,2.7)); +#44857 = CARTESIAN_POINT('',(5.950036447893,3.)); +#44858 = CARTESIAN_POINT('',(6.296446609407,3.)); +#44859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44860 = PCURVE('',#44861,#44866); +#44861 = CYLINDRICAL_SURFACE('',#44862,0.2); +#44862 = AXIS2_PLACEMENT_3D('',#44863,#44864,#44865); +#44863 = CARTESIAN_POINT('',(-3.7,-1.225,0.45)); +#44864 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44865 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44866 = DEFINITIONAL_REPRESENTATION('',(#44867),#44870); +#44867 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44868,#44869),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42476 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#42477 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#42478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42479 = ORIENTED_EDGE('',*,*,#42480,.T.); -#42480 = EDGE_CURVE('',#42449,#42481,#42483,.T.); -#42481 = VERTEX_POINT('',#42482); -#42482 = CARTESIAN_POINT('',(-3.9,-0.925,-5.E-002)); -#42483 = SURFACE_CURVE('',#42484,(#42488,#42495),.PCURVE_S1.); -#42484 = LINE('',#42485,#42486); -#42485 = CARTESIAN_POINT('',(-3.9,-0.925,0.45)); -#42486 = VECTOR('',#42487,1.); -#42487 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42488 = PCURVE('',#37803,#42489); -#42489 = DEFINITIONAL_REPRESENTATION('',(#42490),#42494); -#42490 = LINE('',#42491,#42492); -#42491 = CARTESIAN_POINT('',(6.496446609407,2.8)); -#42492 = VECTOR('',#42493,1.); -#42493 = DIRECTION('',(0.E+000,-1.)); -#42494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42495 = PCURVE('',#42496,#42501); -#42496 = PLANE('',#42497); -#42497 = AXIS2_PLACEMENT_3D('',#42498,#42499,#42500); -#42498 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); -#42499 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42500 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42501 = DEFINITIONAL_REPRESENTATION('',(#42502),#42506); -#42502 = LINE('',#42503,#42504); -#42503 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42504 = VECTOR('',#42505,1.); -#42505 = DIRECTION('',(1.,0.E+000)); -#42506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42507 = ORIENTED_EDGE('',*,*,#42508,.T.); -#42508 = EDGE_CURVE('',#42481,#42509,#42511,.T.); -#42509 = VERTEX_POINT('',#42510); -#42510 = CARTESIAN_POINT('',(-3.7,-0.925,-0.25)); -#42511 = SURFACE_CURVE('',#42512,(#42517,#42528),.PCURVE_S1.); -#42512 = CIRCLE('',#42513,0.2); -#42513 = AXIS2_PLACEMENT_3D('',#42514,#42515,#42516); -#42514 = CARTESIAN_POINT('',(-3.7,-0.925,-5.E-002)); -#42515 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42516 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42517 = PCURVE('',#37803,#42518); -#42518 = DEFINITIONAL_REPRESENTATION('',(#42519),#42527); -#42519 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42520,#42521,#42522,#42523 - ,#42524,#42525,#42526),.UNSPECIFIED.,.T.,.F.) +#44868 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#44869 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#44870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44871 = ORIENTED_EDGE('',*,*,#44872,.T.); +#44872 = EDGE_CURVE('',#44841,#44873,#44875,.T.); +#44873 = VERTEX_POINT('',#44874); +#44874 = CARTESIAN_POINT('',(-3.9,-0.925,-5.E-002)); +#44875 = SURFACE_CURVE('',#44876,(#44880,#44887),.PCURVE_S1.); +#44876 = LINE('',#44877,#44878); +#44877 = CARTESIAN_POINT('',(-3.9,-0.925,0.45)); +#44878 = VECTOR('',#44879,1.); +#44879 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44880 = PCURVE('',#40195,#44881); +#44881 = DEFINITIONAL_REPRESENTATION('',(#44882),#44886); +#44882 = LINE('',#44883,#44884); +#44883 = CARTESIAN_POINT('',(6.496446609407,2.8)); +#44884 = VECTOR('',#44885,1.); +#44885 = DIRECTION('',(0.E+000,-1.)); +#44886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44887 = PCURVE('',#44888,#44893); +#44888 = PLANE('',#44889); +#44889 = AXIS2_PLACEMENT_3D('',#44890,#44891,#44892); +#44890 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); +#44891 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44892 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44893 = DEFINITIONAL_REPRESENTATION('',(#44894),#44898); +#44894 = LINE('',#44895,#44896); +#44895 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44896 = VECTOR('',#44897,1.); +#44897 = DIRECTION('',(1.,0.E+000)); +#44898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44899 = ORIENTED_EDGE('',*,*,#44900,.T.); +#44900 = EDGE_CURVE('',#44873,#44901,#44903,.T.); +#44901 = VERTEX_POINT('',#44902); +#44902 = CARTESIAN_POINT('',(-3.7,-0.925,-0.25)); +#44903 = SURFACE_CURVE('',#44904,(#44909,#44920),.PCURVE_S1.); +#44904 = CIRCLE('',#44905,0.2); +#44905 = AXIS2_PLACEMENT_3D('',#44906,#44907,#44908); +#44906 = CARTESIAN_POINT('',(-3.7,-0.925,-5.E-002)); +#44907 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44908 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#44909 = PCURVE('',#40195,#44910); +#44910 = DEFINITIONAL_REPRESENTATION('',(#44911),#44919); +#44911 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#44912,#44913,#44914,#44915 + ,#44916,#44917,#44918),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42520 = CARTESIAN_POINT('',(6.496446609407,2.3)); -#42521 = CARTESIAN_POINT('',(6.496446609407,1.953589838486)); -#42522 = CARTESIAN_POINT('',(6.196446609407,2.126794919243)); -#42523 = CARTESIAN_POINT('',(5.896446609407,2.3)); -#42524 = CARTESIAN_POINT('',(6.196446609407,2.473205080757)); -#42525 = CARTESIAN_POINT('',(6.496446609407,2.646410161514)); -#42526 = CARTESIAN_POINT('',(6.496446609407,2.3)); -#42527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42528 = PCURVE('',#42529,#42534); -#42529 = CYLINDRICAL_SURFACE('',#42530,0.2); -#42530 = AXIS2_PLACEMENT_3D('',#42531,#42532,#42533); -#42531 = CARTESIAN_POINT('',(-3.7,-1.225,-5.E-002)); -#42532 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42533 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42534 = DEFINITIONAL_REPRESENTATION('',(#42535),#42538); -#42535 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42536,#42537),.UNSPECIFIED., +#44912 = CARTESIAN_POINT('',(6.496446609407,2.3)); +#44913 = CARTESIAN_POINT('',(6.496446609407,1.953589838486)); +#44914 = CARTESIAN_POINT('',(6.196446609407,2.126794919243)); +#44915 = CARTESIAN_POINT('',(5.896446609407,2.3)); +#44916 = CARTESIAN_POINT('',(6.196446609407,2.473205080757)); +#44917 = CARTESIAN_POINT('',(6.496446609407,2.646410161514)); +#44918 = CARTESIAN_POINT('',(6.496446609407,2.3)); +#44919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44920 = PCURVE('',#44921,#44926); +#44921 = CYLINDRICAL_SURFACE('',#44922,0.2); +#44922 = AXIS2_PLACEMENT_3D('',#44923,#44924,#44925); +#44923 = CARTESIAN_POINT('',(-3.7,-1.225,-5.E-002)); +#44924 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44925 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44926 = DEFINITIONAL_REPRESENTATION('',(#44927),#44930); +#44927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44928,#44929),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42536 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#42537 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#42538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42539 = ORIENTED_EDGE('',*,*,#42540,.T.); -#42540 = EDGE_CURVE('',#42509,#42541,#42543,.T.); -#42541 = VERTEX_POINT('',#42542); -#42542 = CARTESIAN_POINT('',(-2.4,-0.925,-0.25)); -#42543 = SURFACE_CURVE('',#42544,(#42548,#42555),.PCURVE_S1.); -#42544 = LINE('',#42545,#42546); -#42545 = CARTESIAN_POINT('',(-3.7,-0.925,-0.25)); -#42546 = VECTOR('',#42547,1.); -#42547 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42548 = PCURVE('',#37803,#42549); -#42549 = DEFINITIONAL_REPRESENTATION('',(#42550),#42554); -#42550 = LINE('',#42551,#42552); -#42551 = CARTESIAN_POINT('',(6.296446609407,2.1)); -#42552 = VECTOR('',#42553,1.); -#42553 = DIRECTION('',(-1.,0.E+000)); -#42554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42555 = PCURVE('',#42556,#42561); -#42556 = PLANE('',#42557); -#42557 = AXIS2_PLACEMENT_3D('',#42558,#42559,#42560); -#42558 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); -#42559 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42560 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42561 = DEFINITIONAL_REPRESENTATION('',(#42562),#42566); -#42562 = LINE('',#42563,#42564); -#42563 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42564 = VECTOR('',#42565,1.); -#42565 = DIRECTION('',(1.,0.E+000)); -#42566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42567 = ORIENTED_EDGE('',*,*,#42568,.T.); -#42568 = EDGE_CURVE('',#42541,#42569,#42571,.T.); -#42569 = VERTEX_POINT('',#42570); -#42570 = CARTESIAN_POINT('',(-2.25,-0.925,-0.4)); -#42571 = SURFACE_CURVE('',#42572,(#42577,#42584),.PCURVE_S1.); -#42572 = CIRCLE('',#42573,0.15); -#42573 = AXIS2_PLACEMENT_3D('',#42574,#42575,#42576); -#42574 = CARTESIAN_POINT('',(-2.4,-0.925,-0.4)); -#42575 = DIRECTION('',(0.E+000,1.,0.E+000)); -#42576 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42577 = PCURVE('',#37803,#42578); -#42578 = DEFINITIONAL_REPRESENTATION('',(#42579),#42583); -#42579 = CIRCLE('',#42580,0.15); -#42580 = AXIS2_PLACEMENT_2D('',#42581,#42582); -#42581 = CARTESIAN_POINT('',(4.996446609407,1.95)); -#42582 = DIRECTION('',(0.E+000,1.)); -#42583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42584 = PCURVE('',#42585,#42590); -#42585 = CYLINDRICAL_SURFACE('',#42586,0.15); -#42586 = AXIS2_PLACEMENT_3D('',#42587,#42588,#42589); -#42587 = CARTESIAN_POINT('',(-2.4,-1.225,-0.4)); -#42588 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42589 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42590 = DEFINITIONAL_REPRESENTATION('',(#42591),#42594); -#42591 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42592,#42593),.UNSPECIFIED., +#44928 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#44929 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#44930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44931 = ORIENTED_EDGE('',*,*,#44932,.T.); +#44932 = EDGE_CURVE('',#44901,#44933,#44935,.T.); +#44933 = VERTEX_POINT('',#44934); +#44934 = CARTESIAN_POINT('',(-2.4,-0.925,-0.25)); +#44935 = SURFACE_CURVE('',#44936,(#44940,#44947),.PCURVE_S1.); +#44936 = LINE('',#44937,#44938); +#44937 = CARTESIAN_POINT('',(-3.7,-0.925,-0.25)); +#44938 = VECTOR('',#44939,1.); +#44939 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44940 = PCURVE('',#40195,#44941); +#44941 = DEFINITIONAL_REPRESENTATION('',(#44942),#44946); +#44942 = LINE('',#44943,#44944); +#44943 = CARTESIAN_POINT('',(6.296446609407,2.1)); +#44944 = VECTOR('',#44945,1.); +#44945 = DIRECTION('',(-1.,0.E+000)); +#44946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44947 = PCURVE('',#44948,#44953); +#44948 = PLANE('',#44949); +#44949 = AXIS2_PLACEMENT_3D('',#44950,#44951,#44952); +#44950 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); +#44951 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#44952 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44953 = DEFINITIONAL_REPRESENTATION('',(#44954),#44958); +#44954 = LINE('',#44955,#44956); +#44955 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44956 = VECTOR('',#44957,1.); +#44957 = DIRECTION('',(1.,0.E+000)); +#44958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44959 = ORIENTED_EDGE('',*,*,#44960,.T.); +#44960 = EDGE_CURVE('',#44933,#44961,#44963,.T.); +#44961 = VERTEX_POINT('',#44962); +#44962 = CARTESIAN_POINT('',(-2.25,-0.925,-0.4)); +#44963 = SURFACE_CURVE('',#44964,(#44969,#44976),.PCURVE_S1.); +#44964 = CIRCLE('',#44965,0.15); +#44965 = AXIS2_PLACEMENT_3D('',#44966,#44967,#44968); +#44966 = CARTESIAN_POINT('',(-2.4,-0.925,-0.4)); +#44967 = DIRECTION('',(0.E+000,1.,0.E+000)); +#44968 = DIRECTION('',(0.E+000,0.E+000,1.)); +#44969 = PCURVE('',#40195,#44970); +#44970 = DEFINITIONAL_REPRESENTATION('',(#44971),#44975); +#44971 = CIRCLE('',#44972,0.15); +#44972 = AXIS2_PLACEMENT_2D('',#44973,#44974); +#44973 = CARTESIAN_POINT('',(4.996446609407,1.95)); +#44974 = DIRECTION('',(0.E+000,1.)); +#44975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44976 = PCURVE('',#44977,#44982); +#44977 = CYLINDRICAL_SURFACE('',#44978,0.15); +#44978 = AXIS2_PLACEMENT_3D('',#44979,#44980,#44981); +#44979 = CARTESIAN_POINT('',(-2.4,-1.225,-0.4)); +#44980 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#44981 = DIRECTION('',(1.,0.E+000,0.E+000)); +#44982 = DEFINITIONAL_REPRESENTATION('',(#44983),#44986); +#44983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44984,#44985),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42592 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#42593 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42595 = ORIENTED_EDGE('',*,*,#42596,.F.); -#42596 = EDGE_CURVE('',#42597,#42569,#42599,.T.); -#42597 = VERTEX_POINT('',#42598); -#42598 = CARTESIAN_POINT('',(-2.25,-0.925,-0.41)); -#42599 = SURFACE_CURVE('',#42600,(#42604,#42611),.PCURVE_S1.); -#42600 = LINE('',#42601,#42602); -#42601 = CARTESIAN_POINT('',(-2.25,-0.925,-0.41)); -#42602 = VECTOR('',#42603,1.); -#42603 = DIRECTION('',(0.E+000,3.330669073875E-014,1.)); -#42604 = PCURVE('',#37803,#42605); -#42605 = DEFINITIONAL_REPRESENTATION('',(#42606),#42610); -#42606 = LINE('',#42607,#42608); -#42607 = CARTESIAN_POINT('',(4.846446609407,1.94)); -#42608 = VECTOR('',#42609,1.); -#42609 = DIRECTION('',(0.E+000,1.)); -#42610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42611 = PCURVE('',#42612,#42617); -#42612 = PLANE('',#42613); -#42613 = AXIS2_PLACEMENT_3D('',#42614,#42615,#42616); -#42614 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); -#42615 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42616 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42617 = DEFINITIONAL_REPRESENTATION('',(#42618),#42622); -#42618 = LINE('',#42619,#42620); -#42619 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42620 = VECTOR('',#42621,1.); -#42621 = DIRECTION('',(1.,-3.330669073875E-014)); -#42622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42623 = ORIENTED_EDGE('',*,*,#42624,.F.); -#42624 = EDGE_CURVE('',#42625,#42597,#42627,.T.); -#42625 = VERTEX_POINT('',#42626); -#42626 = CARTESIAN_POINT('',(-2.4,-0.925,-0.56)); -#42627 = SURFACE_CURVE('',#42628,(#42633,#42644),.PCURVE_S1.); -#42628 = CIRCLE('',#42629,0.15); -#42629 = AXIS2_PLACEMENT_3D('',#42630,#42631,#42632); -#42630 = CARTESIAN_POINT('',(-2.4,-0.925,-0.41)); -#42631 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42632 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42633 = PCURVE('',#37803,#42634); -#42634 = DEFINITIONAL_REPRESENTATION('',(#42635),#42643); -#42635 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#42636,#42637,#42638,#42639 - ,#42640,#42641,#42642),.UNSPECIFIED.,.F.,.F.) +#44984 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#44985 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#44986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#44987 = ORIENTED_EDGE('',*,*,#44988,.F.); +#44988 = EDGE_CURVE('',#44989,#44961,#44991,.T.); +#44989 = VERTEX_POINT('',#44990); +#44990 = CARTESIAN_POINT('',(-2.25,-0.925,-0.41)); +#44991 = SURFACE_CURVE('',#44992,(#44996,#45003),.PCURVE_S1.); +#44992 = LINE('',#44993,#44994); +#44993 = CARTESIAN_POINT('',(-2.25,-0.925,-0.41)); +#44994 = VECTOR('',#44995,1.); +#44995 = DIRECTION('',(0.E+000,3.330669073875E-014,1.)); +#44996 = PCURVE('',#40195,#44997); +#44997 = DEFINITIONAL_REPRESENTATION('',(#44998),#45002); +#44998 = LINE('',#44999,#45000); +#44999 = CARTESIAN_POINT('',(4.846446609407,1.94)); +#45000 = VECTOR('',#45001,1.); +#45001 = DIRECTION('',(0.E+000,1.)); +#45002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45003 = PCURVE('',#45004,#45009); +#45004 = PLANE('',#45005); +#45005 = AXIS2_PLACEMENT_3D('',#45006,#45007,#45008); +#45006 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); +#45007 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45008 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45009 = DEFINITIONAL_REPRESENTATION('',(#45010),#45014); +#45010 = LINE('',#45011,#45012); +#45011 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#45012 = VECTOR('',#45013,1.); +#45013 = DIRECTION('',(1.,-3.330669073875E-014)); +#45014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45015 = ORIENTED_EDGE('',*,*,#45016,.F.); +#45016 = EDGE_CURVE('',#45017,#44989,#45019,.T.); +#45017 = VERTEX_POINT('',#45018); +#45018 = CARTESIAN_POINT('',(-2.4,-0.925,-0.56)); +#45019 = SURFACE_CURVE('',#45020,(#45025,#45036),.PCURVE_S1.); +#45020 = CIRCLE('',#45021,0.15); +#45021 = AXIS2_PLACEMENT_3D('',#45022,#45023,#45024); +#45022 = CARTESIAN_POINT('',(-2.4,-0.925,-0.41)); +#45023 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45024 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45025 = PCURVE('',#40195,#45026); +#45026 = DEFINITIONAL_REPRESENTATION('',(#45027),#45035); +#45027 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#45028,#45029,#45030,#45031 + ,#45032,#45033,#45034),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#42636 = CARTESIAN_POINT('',(4.996446609407,1.79)); -#42637 = CARTESIAN_POINT('',(4.736638988272,1.79)); -#42638 = CARTESIAN_POINT('',(4.866542798839,2.015)); -#42639 = CARTESIAN_POINT('',(4.996446609407,2.24)); -#42640 = CARTESIAN_POINT('',(5.126350419975,2.015)); -#42641 = CARTESIAN_POINT('',(5.256254230542,1.79)); -#42642 = CARTESIAN_POINT('',(4.996446609407,1.79)); -#42643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42644 = PCURVE('',#42645,#42650); -#42645 = CYLINDRICAL_SURFACE('',#42646,0.15); -#42646 = AXIS2_PLACEMENT_3D('',#42647,#42648,#42649); -#42647 = CARTESIAN_POINT('',(-2.4,-1.225,-0.41)); -#42648 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42649 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42650 = DEFINITIONAL_REPRESENTATION('',(#42651),#42654); -#42651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42652,#42653),.UNSPECIFIED., +#45028 = CARTESIAN_POINT('',(4.996446609407,1.79)); +#45029 = CARTESIAN_POINT('',(4.736638988272,1.79)); +#45030 = CARTESIAN_POINT('',(4.866542798839,2.015)); +#45031 = CARTESIAN_POINT('',(4.996446609407,2.24)); +#45032 = CARTESIAN_POINT('',(5.126350419975,2.015)); +#45033 = CARTESIAN_POINT('',(5.256254230542,1.79)); +#45034 = CARTESIAN_POINT('',(4.996446609407,1.79)); +#45035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45036 = PCURVE('',#45037,#45042); +#45037 = CYLINDRICAL_SURFACE('',#45038,0.15); +#45038 = AXIS2_PLACEMENT_3D('',#45039,#45040,#45041); +#45039 = CARTESIAN_POINT('',(-2.4,-1.225,-0.41)); +#45040 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45041 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45042 = DEFINITIONAL_REPRESENTATION('',(#45043),#45046); +#45043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45044,#45045),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#42652 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#42653 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#42654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42655 = ORIENTED_EDGE('',*,*,#42656,.F.); -#42656 = EDGE_CURVE('',#42657,#42625,#42659,.T.); -#42657 = VERTEX_POINT('',#42658); -#42658 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-0.56)); -#42659 = SURFACE_CURVE('',#42660,(#42664,#42671),.PCURVE_S1.); -#42660 = LINE('',#42661,#42662); -#42661 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-0.56)); -#42662 = VECTOR('',#42663,1.); -#42663 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42664 = PCURVE('',#37803,#42665); -#42665 = DEFINITIONAL_REPRESENTATION('',(#42666),#42670); -#42666 = LINE('',#42667,#42668); -#42667 = CARTESIAN_POINT('',(5.192893218814,1.79)); -#42668 = VECTOR('',#42669,1.); -#42669 = DIRECTION('',(-1.,0.E+000)); -#42670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42671 = PCURVE('',#42672,#42677); -#42672 = PLANE('',#42673); -#42673 = AXIS2_PLACEMENT_3D('',#42674,#42675,#42676); -#42674 = CARTESIAN_POINT('',(-3.75,-1.225,-0.56)); -#42675 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42676 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42677 = DEFINITIONAL_REPRESENTATION('',(#42678),#42682); -#42678 = LINE('',#42679,#42680); -#42679 = CARTESIAN_POINT('',(1.153553390593,-0.3)); -#42680 = VECTOR('',#42681,1.); -#42681 = DIRECTION('',(1.,0.E+000)); -#42682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42683 = ORIENTED_EDGE('',*,*,#42684,.F.); -#42684 = EDGE_CURVE('',#42685,#42657,#42687,.T.); -#42685 = VERTEX_POINT('',#42686); -#42686 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); -#42687 = SURFACE_CURVE('',#42688,(#42692,#42699),.PCURVE_S1.); -#42688 = LINE('',#42689,#42690); -#42689 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); -#42690 = VECTOR('',#42691,1.); -#42691 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42692 = PCURVE('',#37803,#42693); -#42693 = DEFINITIONAL_REPRESENTATION('',(#42694),#42698); -#42694 = LINE('',#42695,#42696); -#42695 = CARTESIAN_POINT('',(5.192893218814,0.82)); -#42696 = VECTOR('',#42697,1.); -#42697 = DIRECTION('',(0.E+000,1.)); -#42698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42699 = PCURVE('',#42700,#42705); -#42700 = CYLINDRICAL_SURFACE('',#42701,0.25); -#42701 = AXIS2_PLACEMENT_3D('',#42702,#42703,#42704); -#42702 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); -#42703 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42704 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42705 = DEFINITIONAL_REPRESENTATION('',(#42706),#42709); -#42706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42707,#42708),.UNSPECIFIED., +#45044 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#45045 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#45046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45047 = ORIENTED_EDGE('',*,*,#45048,.F.); +#45048 = EDGE_CURVE('',#45049,#45017,#45051,.T.); +#45049 = VERTEX_POINT('',#45050); +#45050 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-0.56)); +#45051 = SURFACE_CURVE('',#45052,(#45056,#45063),.PCURVE_S1.); +#45052 = LINE('',#45053,#45054); +#45053 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-0.56)); +#45054 = VECTOR('',#45055,1.); +#45055 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45056 = PCURVE('',#40195,#45057); +#45057 = DEFINITIONAL_REPRESENTATION('',(#45058),#45062); +#45058 = LINE('',#45059,#45060); +#45059 = CARTESIAN_POINT('',(5.192893218814,1.79)); +#45060 = VECTOR('',#45061,1.); +#45061 = DIRECTION('',(-1.,0.E+000)); +#45062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45063 = PCURVE('',#45064,#45069); +#45064 = PLANE('',#45065); +#45065 = AXIS2_PLACEMENT_3D('',#45066,#45067,#45068); +#45066 = CARTESIAN_POINT('',(-3.75,-1.225,-0.56)); +#45067 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45068 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45069 = DEFINITIONAL_REPRESENTATION('',(#45070),#45074); +#45070 = LINE('',#45071,#45072); +#45071 = CARTESIAN_POINT('',(1.153553390593,-0.3)); +#45072 = VECTOR('',#45073,1.); +#45073 = DIRECTION('',(1.,0.E+000)); +#45074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45075 = ORIENTED_EDGE('',*,*,#45076,.F.); +#45076 = EDGE_CURVE('',#45077,#45049,#45079,.T.); +#45077 = VERTEX_POINT('',#45078); +#45078 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); +#45079 = SURFACE_CURVE('',#45080,(#45084,#45091),.PCURVE_S1.); +#45080 = LINE('',#45081,#45082); +#45081 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); +#45082 = VECTOR('',#45083,1.); +#45083 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45084 = PCURVE('',#40195,#45085); +#45085 = DEFINITIONAL_REPRESENTATION('',(#45086),#45090); +#45086 = LINE('',#45087,#45088); +#45087 = CARTESIAN_POINT('',(5.192893218814,0.82)); +#45088 = VECTOR('',#45089,1.); +#45089 = DIRECTION('',(0.E+000,1.)); +#45090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45091 = PCURVE('',#45092,#45097); +#45092 = CYLINDRICAL_SURFACE('',#45093,0.25); +#45093 = AXIS2_PLACEMENT_3D('',#45094,#45095,#45096); +#45094 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); +#45095 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45096 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45097 = DEFINITIONAL_REPRESENTATION('',(#45098),#45101); +#45098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45099,#45100),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#42707 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#42708 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#42709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42710 = ORIENTED_EDGE('',*,*,#42711,.T.); -#42711 = EDGE_CURVE('',#42685,#41853,#42712,.T.); -#42712 = SURFACE_CURVE('',#42713,(#42717,#42724),.PCURVE_S1.); -#42713 = LINE('',#42714,#42715); -#42714 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); -#42715 = VECTOR('',#42716,1.); -#42716 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42717 = PCURVE('',#37803,#42718); -#42718 = DEFINITIONAL_REPRESENTATION('',(#42719),#42723); -#42719 = LINE('',#42720,#42721); -#42720 = CARTESIAN_POINT('',(5.192893218814,0.82)); -#42721 = VECTOR('',#42722,1.); -#42722 = DIRECTION('',(-1.,0.E+000)); -#42723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42724 = PCURVE('',#40920,#42725); -#42725 = DEFINITIONAL_REPRESENTATION('',(#42726),#42730); -#42726 = LINE('',#42727,#42728); -#42727 = CARTESIAN_POINT('',(5.E-002,1.153553390593)); -#42728 = VECTOR('',#42729,1.); -#42729 = DIRECTION('',(0.E+000,1.)); -#42730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42731 = ADVANCED_FACE('',(#42732),#41068,.T.); -#42732 = FACE_BOUND('',#42733,.F.); -#42733 = EDGE_LOOP('',(#42734,#42764,#42792,#42820,#42848,#42876,#42897, - #42898)); -#42734 = ORIENTED_EDGE('',*,*,#42735,.F.); -#42735 = EDGE_CURVE('',#42736,#42738,#42740,.T.); -#42736 = VERTEX_POINT('',#42737); -#42737 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); -#42738 = VERTEX_POINT('',#42739); -#42739 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); -#42740 = SURFACE_CURVE('',#42741,(#42745,#42752),.PCURVE_S1.); -#42741 = LINE('',#42742,#42743); -#42742 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); -#42743 = VECTOR('',#42744,1.); -#42744 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42745 = PCURVE('',#41068,#42746); -#42746 = DEFINITIONAL_REPRESENTATION('',(#42747),#42751); -#42747 = LINE('',#42748,#42749); -#42748 = CARTESIAN_POINT('',(-0.82,-0.305)); -#42749 = VECTOR('',#42750,1.); -#42750 = DIRECTION('',(1.,0.E+000)); -#42751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42752 = PCURVE('',#42753,#42758); -#42753 = PLANE('',#42754); -#42754 = AXIS2_PLACEMENT_3D('',#42755,#42756,#42757); -#42755 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); -#42756 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42757 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42758 = DEFINITIONAL_REPRESENTATION('',(#42759),#42763); -#42759 = LINE('',#42760,#42761); -#42760 = CARTESIAN_POINT('',(4.384375541595,0.E+000)); -#42761 = VECTOR('',#42762,1.); -#42762 = DIRECTION('',(0.E+000,1.)); -#42763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42764 = ORIENTED_EDGE('',*,*,#42765,.F.); -#42765 = EDGE_CURVE('',#42766,#42736,#42768,.T.); -#42766 = VERTEX_POINT('',#42767); -#42767 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); -#42768 = SURFACE_CURVE('',#42769,(#42773,#42780),.PCURVE_S1.); -#42769 = LINE('',#42770,#42771); -#42770 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); -#42771 = VECTOR('',#42772,1.); -#42772 = DIRECTION('',(0.E+000,1.,0.E+000)); -#42773 = PCURVE('',#41068,#42774); -#42774 = DEFINITIONAL_REPRESENTATION('',(#42775),#42779); -#42775 = LINE('',#42776,#42777); -#42776 = CARTESIAN_POINT('',(-0.82,-0.12)); -#42777 = VECTOR('',#42778,1.); -#42778 = DIRECTION('',(0.E+000,-1.)); -#42779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42780 = PCURVE('',#42781,#42786); -#42781 = PLANE('',#42782); -#42782 = AXIS2_PLACEMENT_3D('',#42783,#42784,#42785); -#42783 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#42784 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42785 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42786 = DEFINITIONAL_REPRESENTATION('',(#42787),#42791); -#42787 = LINE('',#42788,#42789); -#42788 = CARTESIAN_POINT('',(1.79,-1.105)); -#42789 = VECTOR('',#42790,1.); -#42790 = DIRECTION('',(0.E+000,1.)); -#42791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42792 = ORIENTED_EDGE('',*,*,#42793,.F.); -#42793 = EDGE_CURVE('',#42794,#42766,#42796,.T.); -#42794 = VERTEX_POINT('',#42795); -#42795 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#42796 = SURFACE_CURVE('',#42797,(#42801,#42808),.PCURVE_S1.); -#42797 = LINE('',#42798,#42799); -#42798 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#42799 = VECTOR('',#42800,1.); -#42800 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42801 = PCURVE('',#41068,#42802); -#42802 = DEFINITIONAL_REPRESENTATION('',(#42803),#42807); -#42803 = LINE('',#42804,#42805); -#42804 = CARTESIAN_POINT('',(-0.18,-0.12)); -#42805 = VECTOR('',#42806,1.); -#42806 = DIRECTION('',(-1.,0.E+000)); -#42807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42808 = PCURVE('',#42809,#42814); -#42809 = PLANE('',#42810); -#42810 = AXIS2_PLACEMENT_3D('',#42811,#42812,#42813); -#42811 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#42812 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42814 = DEFINITIONAL_REPRESENTATION('',(#42815),#42819); -#42815 = LINE('',#42816,#42817); -#42816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#42817 = VECTOR('',#42818,1.); -#42818 = DIRECTION('',(1.,0.E+000)); -#42819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42820 = ORIENTED_EDGE('',*,*,#42821,.F.); -#42821 = EDGE_CURVE('',#42822,#42794,#42824,.T.); -#42822 = VERTEX_POINT('',#42823); -#42823 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#42824 = SURFACE_CURVE('',#42825,(#42829,#42836),.PCURVE_S1.); -#42825 = LINE('',#42826,#42827); -#42826 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#42827 = VECTOR('',#42828,1.); -#42828 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42829 = PCURVE('',#41068,#42830); -#42830 = DEFINITIONAL_REPRESENTATION('',(#42831),#42835); -#42831 = LINE('',#42832,#42833); -#42832 = CARTESIAN_POINT('',(-0.18,-0.24)); -#42833 = VECTOR('',#42834,1.); -#42834 = DIRECTION('',(0.E+000,1.)); -#42835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42836 = PCURVE('',#42837,#42842); -#42837 = PLANE('',#42838); -#42838 = AXIS2_PLACEMENT_3D('',#42839,#42840,#42841); -#42839 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#42840 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42841 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42842 = DEFINITIONAL_REPRESENTATION('',(#42843),#42847); -#42843 = LINE('',#42844,#42845); -#42844 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#42845 = VECTOR('',#42846,1.); -#42846 = DIRECTION('',(1.,0.E+000)); -#42847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42848 = ORIENTED_EDGE('',*,*,#42849,.F.); -#42849 = EDGE_CURVE('',#42850,#42822,#42852,.T.); -#42850 = VERTEX_POINT('',#42851); -#42851 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); -#42852 = SURFACE_CURVE('',#42853,(#42857,#42864),.PCURVE_S1.); -#42853 = LINE('',#42854,#42855); -#42854 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); -#42855 = VECTOR('',#42856,1.); -#42856 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42857 = PCURVE('',#41068,#42858); -#42858 = DEFINITIONAL_REPRESENTATION('',(#42859),#42863); -#42859 = LINE('',#42860,#42861); -#42860 = CARTESIAN_POINT('',(0.E+000,-0.24)); -#42861 = VECTOR('',#42862,1.); -#42862 = DIRECTION('',(-1.,0.E+000)); -#42863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42864 = PCURVE('',#42865,#42870); -#42865 = PLANE('',#42866); -#42866 = AXIS2_PLACEMENT_3D('',#42867,#42868,#42869); -#42867 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); -#42868 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42869 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42870 = DEFINITIONAL_REPRESENTATION('',(#42871),#42875); -#42871 = LINE('',#42872,#42873); -#42872 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#42873 = VECTOR('',#42874,1.); -#42874 = DIRECTION('',(1.,0.E+000)); -#42875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42876 = ORIENTED_EDGE('',*,*,#42877,.F.); -#42877 = EDGE_CURVE('',#41053,#42850,#42878,.T.); -#42878 = SURFACE_CURVE('',#42879,(#42883,#42890),.PCURVE_S1.); -#42879 = LINE('',#42880,#42881); -#42880 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); -#42881 = VECTOR('',#42882,1.); -#42882 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#42883 = PCURVE('',#41068,#42884); -#42884 = DEFINITIONAL_REPRESENTATION('',(#42885),#42889); -#42885 = LINE('',#42886,#42887); -#42886 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#42887 = VECTOR('',#42888,1.); -#42888 = DIRECTION('',(0.E+000,1.)); -#42889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42890 = PCURVE('',#40920,#42891); -#42891 = DEFINITIONAL_REPRESENTATION('',(#42892),#42896); -#42892 = LINE('',#42893,#42894); -#42893 = CARTESIAN_POINT('',(5.E-002,5.54)); -#42894 = VECTOR('',#42895,1.); -#42895 = DIRECTION('',(1.,0.E+000)); -#42896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42897 = ORIENTED_EDGE('',*,*,#41050,.F.); -#42898 = ORIENTED_EDGE('',*,*,#42899,.F.); -#42899 = EDGE_CURVE('',#42738,#41051,#42900,.T.); -#42900 = SURFACE_CURVE('',#42901,(#42905,#42912),.PCURVE_S1.); -#42901 = LINE('',#42902,#42903); -#42902 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); -#42903 = VECTOR('',#42904,1.); -#42904 = DIRECTION('',(0.E+000,-1.,4.440892098501E-014)); -#42905 = PCURVE('',#41068,#42906); -#42906 = DEFINITIONAL_REPRESENTATION('',(#42907),#42911); -#42907 = LINE('',#42908,#42909); -#42908 = CARTESIAN_POINT('',(0.38,-0.305)); -#42909 = VECTOR('',#42910,1.); -#42910 = DIRECTION('',(4.440892098501E-014,1.)); -#42911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42912 = PCURVE('',#41837,#42913); -#42913 = DEFINITIONAL_REPRESENTATION('',(#42914),#42918); -#42914 = LINE('',#42915,#42916); -#42915 = CARTESIAN_POINT('',(1.79,-0.92)); -#42916 = VECTOR('',#42917,1.); -#42917 = DIRECTION('',(0.E+000,-1.)); -#42918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42919 = ADVANCED_FACE('',(#42920),#42753,.T.); -#42920 = FACE_BOUND('',#42921,.F.); -#42921 = EDGE_LOOP('',(#42922,#42923,#42946,#42973,#43001)); -#42922 = ORIENTED_EDGE('',*,*,#42735,.T.); -#42923 = ORIENTED_EDGE('',*,*,#42924,.T.); -#42924 = EDGE_CURVE('',#42738,#42925,#42927,.T.); -#42925 = VERTEX_POINT('',#42926); -#42926 = CARTESIAN_POINT('',(2.594375541595,-0.92,-1.15)); -#42927 = SURFACE_CURVE('',#42928,(#42932,#42939),.PCURVE_S1.); -#42928 = LINE('',#42929,#42930); -#42929 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); -#42930 = VECTOR('',#42931,1.); -#42931 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42932 = PCURVE('',#42753,#42933); -#42933 = DEFINITIONAL_REPRESENTATION('',(#42934),#42938); -#42934 = LINE('',#42935,#42936); -#42935 = CARTESIAN_POINT('',(4.384375541595,1.2)); -#42936 = VECTOR('',#42937,1.); -#42937 = DIRECTION('',(1.,0.E+000)); -#42938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42939 = PCURVE('',#41837,#42940); -#42940 = DEFINITIONAL_REPRESENTATION('',(#42941),#42945); -#42941 = LINE('',#42942,#42943); -#42942 = CARTESIAN_POINT('',(1.79,-0.92)); -#42943 = VECTOR('',#42944,1.); -#42944 = DIRECTION('',(1.,0.E+000)); -#42945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42946 = ORIENTED_EDGE('',*,*,#42947,.F.); -#42947 = EDGE_CURVE('',#42948,#42925,#42950,.T.); -#42948 = VERTEX_POINT('',#42949); -#42949 = CARTESIAN_POINT('',(2.594375541595,-0.92,-2.35)); -#42950 = SURFACE_CURVE('',#42951,(#42955,#42962),.PCURVE_S1.); -#42951 = LINE('',#42952,#42953); -#42952 = CARTESIAN_POINT('',(2.594375541595,-0.92,-2.35)); -#42953 = VECTOR('',#42954,1.); -#42954 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42955 = PCURVE('',#42753,#42956); -#42956 = DEFINITIONAL_REPRESENTATION('',(#42957),#42961); -#42957 = LINE('',#42958,#42959); -#42958 = CARTESIAN_POINT('',(5.18875108319,0.E+000)); -#42959 = VECTOR('',#42960,1.); -#42960 = DIRECTION('',(0.E+000,1.)); -#42961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42962 = PCURVE('',#42963,#42968); -#42963 = CYLINDRICAL_SURFACE('',#42964,0.25); -#42964 = AXIS2_PLACEMENT_3D('',#42965,#42966,#42967); -#42965 = CARTESIAN_POINT('',(2.594375541595,-0.67,-2.35)); -#42966 = DIRECTION('',(0.E+000,0.E+000,1.)); -#42967 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42968 = DEFINITIONAL_REPRESENTATION('',(#42969),#42972); -#42969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#42970,#42971),.UNSPECIFIED., +#45099 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#45100 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#45101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45102 = ORIENTED_EDGE('',*,*,#45103,.T.); +#45103 = EDGE_CURVE('',#45077,#44245,#45104,.T.); +#45104 = SURFACE_CURVE('',#45105,(#45109,#45116),.PCURVE_S1.); +#45105 = LINE('',#45106,#45107); +#45106 = CARTESIAN_POINT('',(-2.596446609407,-0.925,-1.53)); +#45107 = VECTOR('',#45108,1.); +#45108 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45109 = PCURVE('',#40195,#45110); +#45110 = DEFINITIONAL_REPRESENTATION('',(#45111),#45115); +#45111 = LINE('',#45112,#45113); +#45112 = CARTESIAN_POINT('',(5.192893218814,0.82)); +#45113 = VECTOR('',#45114,1.); +#45114 = DIRECTION('',(-1.,0.E+000)); +#45115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45116 = PCURVE('',#43312,#45117); +#45117 = DEFINITIONAL_REPRESENTATION('',(#45118),#45122); +#45118 = LINE('',#45119,#45120); +#45119 = CARTESIAN_POINT('',(5.E-002,1.153553390593)); +#45120 = VECTOR('',#45121,1.); +#45121 = DIRECTION('',(0.E+000,1.)); +#45122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45123 = ADVANCED_FACE('',(#45124),#43460,.T.); +#45124 = FACE_BOUND('',#45125,.F.); +#45125 = EDGE_LOOP('',(#45126,#45156,#45184,#45212,#45240,#45268,#45289, + #45290)); +#45126 = ORIENTED_EDGE('',*,*,#45127,.F.); +#45127 = EDGE_CURVE('',#45128,#45130,#45132,.T.); +#45128 = VERTEX_POINT('',#45129); +#45129 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); +#45130 = VERTEX_POINT('',#45131); +#45131 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); +#45132 = SURFACE_CURVE('',#45133,(#45137,#45144),.PCURVE_S1.); +#45133 = LINE('',#45134,#45135); +#45134 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); +#45135 = VECTOR('',#45136,1.); +#45136 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45137 = PCURVE('',#43460,#45138); +#45138 = DEFINITIONAL_REPRESENTATION('',(#45139),#45143); +#45139 = LINE('',#45140,#45141); +#45140 = CARTESIAN_POINT('',(-0.82,-0.305)); +#45141 = VECTOR('',#45142,1.); +#45142 = DIRECTION('',(1.,0.E+000)); +#45143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45144 = PCURVE('',#45145,#45150); +#45145 = PLANE('',#45146); +#45146 = AXIS2_PLACEMENT_3D('',#45147,#45148,#45149); +#45147 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); +#45148 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45149 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45150 = DEFINITIONAL_REPRESENTATION('',(#45151),#45155); +#45151 = LINE('',#45152,#45153); +#45152 = CARTESIAN_POINT('',(4.384375541595,0.E+000)); +#45153 = VECTOR('',#45154,1.); +#45154 = DIRECTION('',(0.E+000,1.)); +#45155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45156 = ORIENTED_EDGE('',*,*,#45157,.F.); +#45157 = EDGE_CURVE('',#45158,#45128,#45160,.T.); +#45158 = VERTEX_POINT('',#45159); +#45159 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); +#45160 = SURFACE_CURVE('',#45161,(#45165,#45172),.PCURVE_S1.); +#45161 = LINE('',#45162,#45163); +#45162 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); +#45163 = VECTOR('',#45164,1.); +#45164 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45165 = PCURVE('',#43460,#45166); +#45166 = DEFINITIONAL_REPRESENTATION('',(#45167),#45171); +#45167 = LINE('',#45168,#45169); +#45168 = CARTESIAN_POINT('',(-0.82,-0.12)); +#45169 = VECTOR('',#45170,1.); +#45170 = DIRECTION('',(0.E+000,-1.)); +#45171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45172 = PCURVE('',#45173,#45178); +#45173 = PLANE('',#45174); +#45174 = AXIS2_PLACEMENT_3D('',#45175,#45176,#45177); +#45175 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#45176 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45177 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45178 = DEFINITIONAL_REPRESENTATION('',(#45179),#45183); +#45179 = LINE('',#45180,#45181); +#45180 = CARTESIAN_POINT('',(1.79,-1.105)); +#45181 = VECTOR('',#45182,1.); +#45182 = DIRECTION('',(0.E+000,1.)); +#45183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45184 = ORIENTED_EDGE('',*,*,#45185,.F.); +#45185 = EDGE_CURVE('',#45186,#45158,#45188,.T.); +#45186 = VERTEX_POINT('',#45187); +#45187 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#45188 = SURFACE_CURVE('',#45189,(#45193,#45200),.PCURVE_S1.); +#45189 = LINE('',#45190,#45191); +#45190 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#45191 = VECTOR('',#45192,1.); +#45192 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45193 = PCURVE('',#43460,#45194); +#45194 = DEFINITIONAL_REPRESENTATION('',(#45195),#45199); +#45195 = LINE('',#45196,#45197); +#45196 = CARTESIAN_POINT('',(-0.18,-0.12)); +#45197 = VECTOR('',#45198,1.); +#45198 = DIRECTION('',(-1.,0.E+000)); +#45199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45200 = PCURVE('',#45201,#45206); +#45201 = PLANE('',#45202); +#45202 = AXIS2_PLACEMENT_3D('',#45203,#45204,#45205); +#45203 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#45204 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45206 = DEFINITIONAL_REPRESENTATION('',(#45207),#45211); +#45207 = LINE('',#45208,#45209); +#45208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45209 = VECTOR('',#45210,1.); +#45210 = DIRECTION('',(1.,0.E+000)); +#45211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45212 = ORIENTED_EDGE('',*,*,#45213,.F.); +#45213 = EDGE_CURVE('',#45214,#45186,#45216,.T.); +#45214 = VERTEX_POINT('',#45215); +#45215 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#45216 = SURFACE_CURVE('',#45217,(#45221,#45228),.PCURVE_S1.); +#45217 = LINE('',#45218,#45219); +#45218 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#45219 = VECTOR('',#45220,1.); +#45220 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45221 = PCURVE('',#43460,#45222); +#45222 = DEFINITIONAL_REPRESENTATION('',(#45223),#45227); +#45223 = LINE('',#45224,#45225); +#45224 = CARTESIAN_POINT('',(-0.18,-0.24)); +#45225 = VECTOR('',#45226,1.); +#45226 = DIRECTION('',(0.E+000,1.)); +#45227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45228 = PCURVE('',#45229,#45234); +#45229 = PLANE('',#45230); +#45230 = AXIS2_PLACEMENT_3D('',#45231,#45232,#45233); +#45231 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#45232 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45233 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45234 = DEFINITIONAL_REPRESENTATION('',(#45235),#45239); +#45235 = LINE('',#45236,#45237); +#45236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45237 = VECTOR('',#45238,1.); +#45238 = DIRECTION('',(1.,0.E+000)); +#45239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45240 = ORIENTED_EDGE('',*,*,#45241,.F.); +#45241 = EDGE_CURVE('',#45242,#45214,#45244,.T.); +#45242 = VERTEX_POINT('',#45243); +#45243 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); +#45244 = SURFACE_CURVE('',#45245,(#45249,#45256),.PCURVE_S1.); +#45245 = LINE('',#45246,#45247); +#45246 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); +#45247 = VECTOR('',#45248,1.); +#45248 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45249 = PCURVE('',#43460,#45250); +#45250 = DEFINITIONAL_REPRESENTATION('',(#45251),#45255); +#45251 = LINE('',#45252,#45253); +#45252 = CARTESIAN_POINT('',(0.E+000,-0.24)); +#45253 = VECTOR('',#45254,1.); +#45254 = DIRECTION('',(-1.,0.E+000)); +#45255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45256 = PCURVE('',#45257,#45262); +#45257 = PLANE('',#45258); +#45258 = AXIS2_PLACEMENT_3D('',#45259,#45260,#45261); +#45259 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); +#45260 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45261 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45262 = DEFINITIONAL_REPRESENTATION('',(#45263),#45267); +#45263 = LINE('',#45264,#45265); +#45264 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45265 = VECTOR('',#45266,1.); +#45266 = DIRECTION('',(1.,0.E+000)); +#45267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45268 = ORIENTED_EDGE('',*,*,#45269,.F.); +#45269 = EDGE_CURVE('',#43445,#45242,#45270,.T.); +#45270 = SURFACE_CURVE('',#45271,(#45275,#45282),.PCURVE_S1.); +#45271 = LINE('',#45272,#45273); +#45272 = CARTESIAN_POINT('',(1.79,-0.925,-1.53)); +#45273 = VECTOR('',#45274,1.); +#45274 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45275 = PCURVE('',#43460,#45276); +#45276 = DEFINITIONAL_REPRESENTATION('',(#45277),#45281); +#45277 = LINE('',#45278,#45279); +#45278 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#45279 = VECTOR('',#45280,1.); +#45280 = DIRECTION('',(0.E+000,1.)); +#45281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45282 = PCURVE('',#43312,#45283); +#45283 = DEFINITIONAL_REPRESENTATION('',(#45284),#45288); +#45284 = LINE('',#45285,#45286); +#45285 = CARTESIAN_POINT('',(5.E-002,5.54)); +#45286 = VECTOR('',#45287,1.); +#45287 = DIRECTION('',(1.,0.E+000)); +#45288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45289 = ORIENTED_EDGE('',*,*,#43442,.F.); +#45290 = ORIENTED_EDGE('',*,*,#45291,.F.); +#45291 = EDGE_CURVE('',#45130,#43443,#45292,.T.); +#45292 = SURFACE_CURVE('',#45293,(#45297,#45304),.PCURVE_S1.); +#45293 = LINE('',#45294,#45295); +#45294 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); +#45295 = VECTOR('',#45296,1.); +#45296 = DIRECTION('',(0.E+000,-1.,4.440892098501E-014)); +#45297 = PCURVE('',#43460,#45298); +#45298 = DEFINITIONAL_REPRESENTATION('',(#45299),#45303); +#45299 = LINE('',#45300,#45301); +#45300 = CARTESIAN_POINT('',(0.38,-0.305)); +#45301 = VECTOR('',#45302,1.); +#45302 = DIRECTION('',(4.440892098501E-014,1.)); +#45303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45304 = PCURVE('',#44229,#45305); +#45305 = DEFINITIONAL_REPRESENTATION('',(#45306),#45310); +#45306 = LINE('',#45307,#45308); +#45307 = CARTESIAN_POINT('',(1.79,-0.92)); +#45308 = VECTOR('',#45309,1.); +#45309 = DIRECTION('',(0.E+000,-1.)); +#45310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45311 = ADVANCED_FACE('',(#45312),#45145,.T.); +#45312 = FACE_BOUND('',#45313,.F.); +#45313 = EDGE_LOOP('',(#45314,#45315,#45338,#45365,#45393)); +#45314 = ORIENTED_EDGE('',*,*,#45127,.T.); +#45315 = ORIENTED_EDGE('',*,*,#45316,.T.); +#45316 = EDGE_CURVE('',#45130,#45317,#45319,.T.); +#45317 = VERTEX_POINT('',#45318); +#45318 = CARTESIAN_POINT('',(2.594375541595,-0.92,-1.15)); +#45319 = SURFACE_CURVE('',#45320,(#45324,#45331),.PCURVE_S1.); +#45320 = LINE('',#45321,#45322); +#45321 = CARTESIAN_POINT('',(1.79,-0.92,-1.15)); +#45322 = VECTOR('',#45323,1.); +#45323 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45324 = PCURVE('',#45145,#45325); +#45325 = DEFINITIONAL_REPRESENTATION('',(#45326),#45330); +#45326 = LINE('',#45327,#45328); +#45327 = CARTESIAN_POINT('',(4.384375541595,1.2)); +#45328 = VECTOR('',#45329,1.); +#45329 = DIRECTION('',(1.,0.E+000)); +#45330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45331 = PCURVE('',#44229,#45332); +#45332 = DEFINITIONAL_REPRESENTATION('',(#45333),#45337); +#45333 = LINE('',#45334,#45335); +#45334 = CARTESIAN_POINT('',(1.79,-0.92)); +#45335 = VECTOR('',#45336,1.); +#45336 = DIRECTION('',(1.,0.E+000)); +#45337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45338 = ORIENTED_EDGE('',*,*,#45339,.F.); +#45339 = EDGE_CURVE('',#45340,#45317,#45342,.T.); +#45340 = VERTEX_POINT('',#45341); +#45341 = CARTESIAN_POINT('',(2.594375541595,-0.92,-2.35)); +#45342 = SURFACE_CURVE('',#45343,(#45347,#45354),.PCURVE_S1.); +#45343 = LINE('',#45344,#45345); +#45344 = CARTESIAN_POINT('',(2.594375541595,-0.92,-2.35)); +#45345 = VECTOR('',#45346,1.); +#45346 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45347 = PCURVE('',#45145,#45348); +#45348 = DEFINITIONAL_REPRESENTATION('',(#45349),#45353); +#45349 = LINE('',#45350,#45351); +#45350 = CARTESIAN_POINT('',(5.18875108319,0.E+000)); +#45351 = VECTOR('',#45352,1.); +#45352 = DIRECTION('',(0.E+000,1.)); +#45353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45354 = PCURVE('',#45355,#45360); +#45355 = CYLINDRICAL_SURFACE('',#45356,0.25); +#45356 = AXIS2_PLACEMENT_3D('',#45357,#45358,#45359); +#45357 = CARTESIAN_POINT('',(2.594375541595,-0.67,-2.35)); +#45358 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45359 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45360 = DEFINITIONAL_REPRESENTATION('',(#45361),#45364); +#45361 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45362,#45363),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#42970 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#42971 = CARTESIAN_POINT('',(4.712388980385,1.2)); -#42972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42973 = ORIENTED_EDGE('',*,*,#42974,.F.); -#42974 = EDGE_CURVE('',#42975,#42948,#42977,.T.); -#42975 = VERTEX_POINT('',#42976); -#42976 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); -#42977 = SURFACE_CURVE('',#42978,(#42982,#42989),.PCURVE_S1.); -#42978 = LINE('',#42979,#42980); -#42979 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); -#42980 = VECTOR('',#42981,1.); -#42981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#42982 = PCURVE('',#42753,#42983); -#42983 = DEFINITIONAL_REPRESENTATION('',(#42984),#42988); -#42984 = LINE('',#42985,#42986); -#42985 = CARTESIAN_POINT('',(4.519375541595,0.E+000)); -#42986 = VECTOR('',#42987,1.); -#42987 = DIRECTION('',(1.,0.E+000)); -#42988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#42989 = PCURVE('',#42990,#42995); -#42990 = PLANE('',#42991); -#42991 = AXIS2_PLACEMENT_3D('',#42992,#42993,#42994); -#42992 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#42993 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#42994 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#42995 = DEFINITIONAL_REPRESENTATION('',(#42996),#43000); -#42996 = LINE('',#42997,#42998); -#42997 = CARTESIAN_POINT('',(-1.925,-0.92)); -#42998 = VECTOR('',#42999,1.); -#42999 = DIRECTION('',(-1.,0.E+000)); -#43000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43001 = ORIENTED_EDGE('',*,*,#43002,.F.); -#43002 = EDGE_CURVE('',#42736,#42975,#43003,.T.); -#43003 = SURFACE_CURVE('',#43004,(#43008,#43015),.PCURVE_S1.); -#43004 = LINE('',#43005,#43006); -#43005 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); -#43006 = VECTOR('',#43007,1.); -#43007 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43008 = PCURVE('',#42753,#43009); -#43009 = DEFINITIONAL_REPRESENTATION('',(#43010),#43014); -#43010 = LINE('',#43011,#43012); -#43011 = CARTESIAN_POINT('',(4.384375541595,0.E+000)); -#43012 = VECTOR('',#43013,1.); -#43013 = DIRECTION('',(1.,0.E+000)); -#43014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43015 = PCURVE('',#42781,#43016); -#43016 = DEFINITIONAL_REPRESENTATION('',(#43017),#43021); -#43017 = LINE('',#43018,#43019); -#43018 = CARTESIAN_POINT('',(1.79,-0.92)); -#43019 = VECTOR('',#43020,1.); -#43020 = DIRECTION('',(1.,0.E+000)); -#43021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43022 = ADVANCED_FACE('',(#43023),#43037,.T.); -#43023 = FACE_BOUND('',#43024,.F.); -#43024 = EDGE_LOOP('',(#43025,#43055,#43078,#43106,#43133)); -#43025 = ORIENTED_EDGE('',*,*,#43026,.F.); -#43026 = EDGE_CURVE('',#43027,#43029,#43031,.T.); -#43027 = VERTEX_POINT('',#43028); -#43028 = CARTESIAN_POINT('',(-1.79,-0.92,-2.35)); -#43029 = VERTEX_POINT('',#43030); -#43030 = CARTESIAN_POINT('',(-1.79,-0.92,-1.15)); -#43031 = SURFACE_CURVE('',#43032,(#43036,#43048),.PCURVE_S1.); -#43032 = LINE('',#43033,#43034); -#43033 = CARTESIAN_POINT('',(-1.79,-0.92,-2.35)); -#43034 = VECTOR('',#43035,1.); -#43035 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43036 = PCURVE('',#43037,#43042); -#43037 = PLANE('',#43038); -#43038 = AXIS2_PLACEMENT_3D('',#43039,#43040,#43041); -#43039 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); -#43040 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43041 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43042 = DEFINITIONAL_REPRESENTATION('',(#43043),#43047); -#43043 = LINE('',#43044,#43045); -#43044 = CARTESIAN_POINT('',(0.804375541595,0.E+000)); -#43045 = VECTOR('',#43046,1.); -#43046 = DIRECTION('',(0.E+000,1.)); -#43047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43048 = PCURVE('',#41870,#43049); -#43049 = DEFINITIONAL_REPRESENTATION('',(#43050),#43054); -#43050 = LINE('',#43051,#43052); -#43051 = CARTESIAN_POINT('',(1.14,-0.305)); -#43052 = VECTOR('',#43053,1.); -#43053 = DIRECTION('',(-1.,0.E+000)); -#43054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43055 = ORIENTED_EDGE('',*,*,#43056,.F.); -#43056 = EDGE_CURVE('',#43057,#43027,#43059,.T.); -#43057 = VERTEX_POINT('',#43058); -#43058 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); -#43059 = SURFACE_CURVE('',#43060,(#43064,#43071),.PCURVE_S1.); -#43060 = LINE('',#43061,#43062); -#43061 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); -#43062 = VECTOR('',#43063,1.); -#43063 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43064 = PCURVE('',#43037,#43065); -#43065 = DEFINITIONAL_REPRESENTATION('',(#43066),#43070); -#43066 = LINE('',#43067,#43068); -#43067 = CARTESIAN_POINT('',(0.669375541595,0.E+000)); -#43068 = VECTOR('',#43069,1.); -#43069 = DIRECTION('',(1.,0.E+000)); -#43070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43071 = PCURVE('',#42781,#43072); -#43072 = DEFINITIONAL_REPRESENTATION('',(#43073),#43077); -#43073 = LINE('',#43074,#43075); -#43074 = CARTESIAN_POINT('',(-1.925,-0.92)); -#43075 = VECTOR('',#43076,1.); -#43076 = DIRECTION('',(1.,0.E+000)); -#43077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43078 = ORIENTED_EDGE('',*,*,#43079,.F.); -#43079 = EDGE_CURVE('',#43080,#43057,#43082,.T.); -#43080 = VERTEX_POINT('',#43081); -#43081 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); -#43082 = SURFACE_CURVE('',#43083,(#43087,#43094),.PCURVE_S1.); -#43083 = LINE('',#43084,#43085); -#43084 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); -#43085 = VECTOR('',#43086,1.); -#43086 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43087 = PCURVE('',#43037,#43088); -#43088 = DEFINITIONAL_REPRESENTATION('',(#43089),#43093); -#43089 = LINE('',#43090,#43091); -#43090 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43091 = VECTOR('',#43092,1.); -#43092 = DIRECTION('',(1.,0.E+000)); -#43093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43094 = PCURVE('',#43095,#43100); -#43095 = PLANE('',#43096); -#43096 = AXIS2_PLACEMENT_3D('',#43097,#43098,#43099); -#43097 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#43098 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#43099 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43100 = DEFINITIONAL_REPRESENTATION('',(#43101),#43105); -#43101 = LINE('',#43102,#43103); -#43102 = CARTESIAN_POINT('',(2.594375541595,-0.92)); -#43103 = VECTOR('',#43104,1.); -#43104 = DIRECTION('',(-1.,0.E+000)); -#43105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43106 = ORIENTED_EDGE('',*,*,#43107,.T.); -#43107 = EDGE_CURVE('',#43080,#43108,#43110,.T.); -#43108 = VERTEX_POINT('',#43109); -#43109 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-1.15)); -#43110 = SURFACE_CURVE('',#43111,(#43115,#43122),.PCURVE_S1.); -#43111 = LINE('',#43112,#43113); -#43112 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); -#43113 = VECTOR('',#43114,1.); -#43114 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43115 = PCURVE('',#43037,#43116); -#43116 = DEFINITIONAL_REPRESENTATION('',(#43117),#43121); -#43117 = LINE('',#43118,#43119); -#43118 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43119 = VECTOR('',#43120,1.); -#43120 = DIRECTION('',(0.E+000,1.)); -#43121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43122 = PCURVE('',#43123,#43128); -#43123 = CYLINDRICAL_SURFACE('',#43124,0.25); -#43124 = AXIS2_PLACEMENT_3D('',#43125,#43126,#43127); -#43125 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-2.35)); -#43126 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43127 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43128 = DEFINITIONAL_REPRESENTATION('',(#43129),#43132); -#43129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43130,#43131),.UNSPECIFIED., +#45362 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#45363 = CARTESIAN_POINT('',(4.712388980385,1.2)); +#45364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45365 = ORIENTED_EDGE('',*,*,#45366,.F.); +#45366 = EDGE_CURVE('',#45367,#45340,#45369,.T.); +#45367 = VERTEX_POINT('',#45368); +#45368 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); +#45369 = SURFACE_CURVE('',#45370,(#45374,#45381),.PCURVE_S1.); +#45370 = LINE('',#45371,#45372); +#45371 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); +#45372 = VECTOR('',#45373,1.); +#45373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45374 = PCURVE('',#45145,#45375); +#45375 = DEFINITIONAL_REPRESENTATION('',(#45376),#45380); +#45376 = LINE('',#45377,#45378); +#45377 = CARTESIAN_POINT('',(4.519375541595,0.E+000)); +#45378 = VECTOR('',#45379,1.); +#45379 = DIRECTION('',(1.,0.E+000)); +#45380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45381 = PCURVE('',#45382,#45387); +#45382 = PLANE('',#45383); +#45383 = AXIS2_PLACEMENT_3D('',#45384,#45385,#45386); +#45384 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#45385 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45386 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45387 = DEFINITIONAL_REPRESENTATION('',(#45388),#45392); +#45388 = LINE('',#45389,#45390); +#45389 = CARTESIAN_POINT('',(-1.925,-0.92)); +#45390 = VECTOR('',#45391,1.); +#45391 = DIRECTION('',(-1.,0.E+000)); +#45392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45393 = ORIENTED_EDGE('',*,*,#45394,.F.); +#45394 = EDGE_CURVE('',#45128,#45367,#45395,.T.); +#45395 = SURFACE_CURVE('',#45396,(#45400,#45407),.PCURVE_S1.); +#45396 = LINE('',#45397,#45398); +#45397 = CARTESIAN_POINT('',(1.79,-0.92,-2.35)); +#45398 = VECTOR('',#45399,1.); +#45399 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45400 = PCURVE('',#45145,#45401); +#45401 = DEFINITIONAL_REPRESENTATION('',(#45402),#45406); +#45402 = LINE('',#45403,#45404); +#45403 = CARTESIAN_POINT('',(4.384375541595,0.E+000)); +#45404 = VECTOR('',#45405,1.); +#45405 = DIRECTION('',(1.,0.E+000)); +#45406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45407 = PCURVE('',#45173,#45408); +#45408 = DEFINITIONAL_REPRESENTATION('',(#45409),#45413); +#45409 = LINE('',#45410,#45411); +#45410 = CARTESIAN_POINT('',(1.79,-0.92)); +#45411 = VECTOR('',#45412,1.); +#45412 = DIRECTION('',(1.,0.E+000)); +#45413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45414 = ADVANCED_FACE('',(#45415),#45429,.T.); +#45415 = FACE_BOUND('',#45416,.F.); +#45416 = EDGE_LOOP('',(#45417,#45447,#45470,#45498,#45525)); +#45417 = ORIENTED_EDGE('',*,*,#45418,.F.); +#45418 = EDGE_CURVE('',#45419,#45421,#45423,.T.); +#45419 = VERTEX_POINT('',#45420); +#45420 = CARTESIAN_POINT('',(-1.79,-0.92,-2.35)); +#45421 = VERTEX_POINT('',#45422); +#45422 = CARTESIAN_POINT('',(-1.79,-0.92,-1.15)); +#45423 = SURFACE_CURVE('',#45424,(#45428,#45440),.PCURVE_S1.); +#45424 = LINE('',#45425,#45426); +#45425 = CARTESIAN_POINT('',(-1.79,-0.92,-2.35)); +#45426 = VECTOR('',#45427,1.); +#45427 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45428 = PCURVE('',#45429,#45434); +#45429 = PLANE('',#45430); +#45430 = AXIS2_PLACEMENT_3D('',#45431,#45432,#45433); +#45431 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); +#45432 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45433 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45434 = DEFINITIONAL_REPRESENTATION('',(#45435),#45439); +#45435 = LINE('',#45436,#45437); +#45436 = CARTESIAN_POINT('',(0.804375541595,0.E+000)); +#45437 = VECTOR('',#45438,1.); +#45438 = DIRECTION('',(0.E+000,1.)); +#45439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45440 = PCURVE('',#44262,#45441); +#45441 = DEFINITIONAL_REPRESENTATION('',(#45442),#45446); +#45442 = LINE('',#45443,#45444); +#45443 = CARTESIAN_POINT('',(1.14,-0.305)); +#45444 = VECTOR('',#45445,1.); +#45445 = DIRECTION('',(-1.,0.E+000)); +#45446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45447 = ORIENTED_EDGE('',*,*,#45448,.F.); +#45448 = EDGE_CURVE('',#45449,#45419,#45451,.T.); +#45449 = VERTEX_POINT('',#45450); +#45450 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); +#45451 = SURFACE_CURVE('',#45452,(#45456,#45463),.PCURVE_S1.); +#45452 = LINE('',#45453,#45454); +#45453 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); +#45454 = VECTOR('',#45455,1.); +#45455 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45456 = PCURVE('',#45429,#45457); +#45457 = DEFINITIONAL_REPRESENTATION('',(#45458),#45462); +#45458 = LINE('',#45459,#45460); +#45459 = CARTESIAN_POINT('',(0.669375541595,0.E+000)); +#45460 = VECTOR('',#45461,1.); +#45461 = DIRECTION('',(1.,0.E+000)); +#45462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45463 = PCURVE('',#45173,#45464); +#45464 = DEFINITIONAL_REPRESENTATION('',(#45465),#45469); +#45465 = LINE('',#45466,#45467); +#45466 = CARTESIAN_POINT('',(-1.925,-0.92)); +#45467 = VECTOR('',#45468,1.); +#45468 = DIRECTION('',(1.,0.E+000)); +#45469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45470 = ORIENTED_EDGE('',*,*,#45471,.F.); +#45471 = EDGE_CURVE('',#45472,#45449,#45474,.T.); +#45472 = VERTEX_POINT('',#45473); +#45473 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); +#45474 = SURFACE_CURVE('',#45475,(#45479,#45486),.PCURVE_S1.); +#45475 = LINE('',#45476,#45477); +#45476 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); +#45477 = VECTOR('',#45478,1.); +#45478 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45479 = PCURVE('',#45429,#45480); +#45480 = DEFINITIONAL_REPRESENTATION('',(#45481),#45485); +#45481 = LINE('',#45482,#45483); +#45482 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45483 = VECTOR('',#45484,1.); +#45484 = DIRECTION('',(1.,0.E+000)); +#45485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45486 = PCURVE('',#45487,#45492); +#45487 = PLANE('',#45488); +#45488 = AXIS2_PLACEMENT_3D('',#45489,#45490,#45491); +#45489 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#45490 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45491 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45492 = DEFINITIONAL_REPRESENTATION('',(#45493),#45497); +#45493 = LINE('',#45494,#45495); +#45494 = CARTESIAN_POINT('',(2.594375541595,-0.92)); +#45495 = VECTOR('',#45496,1.); +#45496 = DIRECTION('',(-1.,0.E+000)); +#45497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45498 = ORIENTED_EDGE('',*,*,#45499,.T.); +#45499 = EDGE_CURVE('',#45472,#45500,#45502,.T.); +#45500 = VERTEX_POINT('',#45501); +#45501 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-1.15)); +#45502 = SURFACE_CURVE('',#45503,(#45507,#45514),.PCURVE_S1.); +#45503 = LINE('',#45504,#45505); +#45504 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-2.35)); +#45505 = VECTOR('',#45506,1.); +#45506 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45507 = PCURVE('',#45429,#45508); +#45508 = DEFINITIONAL_REPRESENTATION('',(#45509),#45513); +#45509 = LINE('',#45510,#45511); +#45510 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45511 = VECTOR('',#45512,1.); +#45512 = DIRECTION('',(0.E+000,1.)); +#45513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45514 = PCURVE('',#45515,#45520); +#45515 = CYLINDRICAL_SURFACE('',#45516,0.25); +#45516 = AXIS2_PLACEMENT_3D('',#45517,#45518,#45519); +#45517 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-2.35)); +#45518 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45519 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45520 = DEFINITIONAL_REPRESENTATION('',(#45521),#45524); +#45521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45522,#45523),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#43130 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#43131 = CARTESIAN_POINT('',(4.712388980385,1.2)); -#43132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43133 = ORIENTED_EDGE('',*,*,#43134,.T.); -#43134 = EDGE_CURVE('',#43108,#43029,#43135,.T.); -#43135 = SURFACE_CURVE('',#43136,(#43140,#43147),.PCURVE_S1.); -#43136 = LINE('',#43137,#43138); -#43137 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-1.15)); -#43138 = VECTOR('',#43139,1.); -#43139 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43140 = PCURVE('',#43037,#43141); -#43141 = DEFINITIONAL_REPRESENTATION('',(#43142),#43146); -#43142 = LINE('',#43143,#43144); -#43143 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43144 = VECTOR('',#43145,1.); -#43145 = DIRECTION('',(1.,0.E+000)); -#43146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43147 = PCURVE('',#41837,#43148); -#43148 = DEFINITIONAL_REPRESENTATION('',(#43149),#43153); -#43149 = LINE('',#43150,#43151); -#43150 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); -#43151 = VECTOR('',#43152,1.); -#43152 = DIRECTION('',(1.,0.E+000)); -#43153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43154 = ADVANCED_FACE('',(#43155),#41837,.T.); -#43155 = FACE_BOUND('',#43156,.F.); -#43156 = EDGE_LOOP('',(#43157,#43187,#43215,#43243,#43271,#43299,#43327, - #43355,#43383,#43411,#43439,#43467,#43495,#43523,#43544,#43545, - #43546,#43547,#43569,#43597,#43617,#43618,#43639,#43640,#43663, - #43691,#43719,#43747,#43775,#43798,#43826,#43849,#43877,#43905, - #43933,#43961,#43989,#44017,#44045,#44073,#44101,#44129,#44157, - #44185,#44213,#44241,#44269,#44297,#44325,#44353,#44381,#44409)); -#43157 = ORIENTED_EDGE('',*,*,#43158,.T.); -#43158 = EDGE_CURVE('',#43159,#43161,#43163,.T.); -#43159 = VERTEX_POINT('',#43160); -#43160 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); -#43161 = VERTEX_POINT('',#43162); -#43162 = CARTESIAN_POINT('',(1.485,0.165,-1.15)); -#43163 = SURFACE_CURVE('',#43164,(#43168,#43175),.PCURVE_S1.); -#43164 = LINE('',#43165,#43166); -#43165 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); -#43166 = VECTOR('',#43167,1.); -#43167 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43168 = PCURVE('',#41837,#43169); -#43169 = DEFINITIONAL_REPRESENTATION('',(#43170),#43174); -#43170 = LINE('',#43171,#43172); -#43171 = CARTESIAN_POINT('',(1.115,0.165)); -#43172 = VECTOR('',#43173,1.); -#43173 = DIRECTION('',(1.,0.E+000)); -#43174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43175 = PCURVE('',#43176,#43181); -#43176 = PLANE('',#43177); -#43177 = AXIS2_PLACEMENT_3D('',#43178,#43179,#43180); -#43178 = CARTESIAN_POINT('',(1.115,0.165,1.05)); -#43179 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43180 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#43181 = DEFINITIONAL_REPRESENTATION('',(#43182),#43186); -#43182 = LINE('',#43183,#43184); -#43183 = CARTESIAN_POINT('',(2.2,0.E+000)); -#43184 = VECTOR('',#43185,1.); -#43185 = DIRECTION('',(0.E+000,1.)); -#43186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43187 = ORIENTED_EDGE('',*,*,#43188,.F.); -#43188 = EDGE_CURVE('',#43189,#43161,#43191,.T.); -#43189 = VERTEX_POINT('',#43190); -#43190 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); -#43191 = SURFACE_CURVE('',#43192,(#43196,#43203),.PCURVE_S1.); -#43192 = LINE('',#43193,#43194); -#43193 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); -#43194 = VECTOR('',#43195,1.); -#43195 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43196 = PCURVE('',#41837,#43197); -#43197 = DEFINITIONAL_REPRESENTATION('',(#43198),#43202); -#43198 = LINE('',#43199,#43200); -#43199 = CARTESIAN_POINT('',(1.485,4.5E-002)); -#43200 = VECTOR('',#43201,1.); -#43201 = DIRECTION('',(0.E+000,1.)); -#43202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43203 = PCURVE('',#43204,#43209); -#43204 = PLANE('',#43205); -#43205 = AXIS2_PLACEMENT_3D('',#43206,#43207,#43208); -#43206 = CARTESIAN_POINT('',(1.485,0.E+000,0.E+000)); -#43207 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43208 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#43209 = DEFINITIONAL_REPRESENTATION('',(#43210),#43214); -#43210 = LINE('',#43211,#43212); -#43211 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#43212 = VECTOR('',#43213,1.); -#43213 = DIRECTION('',(0.E+000,1.)); -#43214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43215 = ORIENTED_EDGE('',*,*,#43216,.T.); -#43216 = EDGE_CURVE('',#43189,#43217,#43219,.T.); -#43217 = VERTEX_POINT('',#43218); -#43218 = CARTESIAN_POINT('',(1.55,4.5E-002,-1.15)); -#43219 = SURFACE_CURVE('',#43220,(#43224,#43231),.PCURVE_S1.); -#43220 = LINE('',#43221,#43222); -#43221 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); -#43222 = VECTOR('',#43223,1.); -#43223 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43224 = PCURVE('',#41837,#43225); -#43225 = DEFINITIONAL_REPRESENTATION('',(#43226),#43230); -#43226 = LINE('',#43227,#43228); -#43227 = CARTESIAN_POINT('',(1.485,4.5E-002)); -#43228 = VECTOR('',#43229,1.); -#43229 = DIRECTION('',(1.,0.E+000)); -#43230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43231 = PCURVE('',#43232,#43237); -#43232 = PLANE('',#43233); -#43233 = AXIS2_PLACEMENT_3D('',#43234,#43235,#43236); -#43234 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#43235 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43236 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43237 = DEFINITIONAL_REPRESENTATION('',(#43238),#43242); -#43238 = LINE('',#43239,#43240); -#43239 = CARTESIAN_POINT('',(3.035,0.E+000)); -#43240 = VECTOR('',#43241,1.); -#43241 = DIRECTION('',(1.,0.E+000)); -#43242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43243 = ORIENTED_EDGE('',*,*,#43244,.T.); -#43244 = EDGE_CURVE('',#43217,#43245,#43247,.T.); -#43245 = VERTEX_POINT('',#43246); -#43246 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); -#43247 = SURFACE_CURVE('',#43248,(#43253,#43260),.PCURVE_S1.); -#43248 = CIRCLE('',#43249,0.2); -#43249 = AXIS2_PLACEMENT_3D('',#43250,#43251,#43252); -#43250 = CARTESIAN_POINT('',(1.55,0.245,-1.15)); -#43251 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43252 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43253 = PCURVE('',#41837,#43254); -#43254 = DEFINITIONAL_REPRESENTATION('',(#43255),#43259); -#43255 = CIRCLE('',#43256,0.2); -#43256 = AXIS2_PLACEMENT_2D('',#43257,#43258); -#43257 = CARTESIAN_POINT('',(1.55,0.245)); -#43258 = DIRECTION('',(0.E+000,-1.)); -#43259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43260 = PCURVE('',#43261,#43266); -#43261 = CYLINDRICAL_SURFACE('',#43262,0.2); -#43262 = AXIS2_PLACEMENT_3D('',#43263,#43264,#43265); -#43263 = CARTESIAN_POINT('',(1.55,0.245,-1.15)); -#43264 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43265 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43266 = DEFINITIONAL_REPRESENTATION('',(#43267),#43270); -#43267 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43268,#43269),.UNSPECIFIED., +#45522 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#45523 = CARTESIAN_POINT('',(4.712388980385,1.2)); +#45524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45525 = ORIENTED_EDGE('',*,*,#45526,.T.); +#45526 = EDGE_CURVE('',#45500,#45421,#45527,.T.); +#45527 = SURFACE_CURVE('',#45528,(#45532,#45539),.PCURVE_S1.); +#45528 = LINE('',#45529,#45530); +#45529 = CARTESIAN_POINT('',(-2.594375541595,-0.92,-1.15)); +#45530 = VECTOR('',#45531,1.); +#45531 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45532 = PCURVE('',#45429,#45533); +#45533 = DEFINITIONAL_REPRESENTATION('',(#45534),#45538); +#45534 = LINE('',#45535,#45536); +#45535 = CARTESIAN_POINT('',(0.E+000,1.2)); +#45536 = VECTOR('',#45537,1.); +#45537 = DIRECTION('',(1.,0.E+000)); +#45538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45539 = PCURVE('',#44229,#45540); +#45540 = DEFINITIONAL_REPRESENTATION('',(#45541),#45545); +#45541 = LINE('',#45542,#45543); +#45542 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); +#45543 = VECTOR('',#45544,1.); +#45544 = DIRECTION('',(1.,0.E+000)); +#45545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45546 = ADVANCED_FACE('',(#45547),#44229,.T.); +#45547 = FACE_BOUND('',#45548,.F.); +#45548 = EDGE_LOOP('',(#45549,#45579,#45607,#45635,#45663,#45691,#45719, + #45747,#45775,#45803,#45831,#45859,#45887,#45915,#45936,#45937, + #45938,#45939,#45961,#45989,#46009,#46010,#46031,#46032,#46055, + #46083,#46111,#46139,#46167,#46190,#46218,#46241,#46269,#46297, + #46325,#46353,#46381,#46409,#46437,#46465,#46493,#46521,#46549, + #46577,#46605,#46633,#46661,#46689,#46717,#46745,#46773,#46801)); +#45549 = ORIENTED_EDGE('',*,*,#45550,.T.); +#45550 = EDGE_CURVE('',#45551,#45553,#45555,.T.); +#45551 = VERTEX_POINT('',#45552); +#45552 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); +#45553 = VERTEX_POINT('',#45554); +#45554 = CARTESIAN_POINT('',(1.485,0.165,-1.15)); +#45555 = SURFACE_CURVE('',#45556,(#45560,#45567),.PCURVE_S1.); +#45556 = LINE('',#45557,#45558); +#45557 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); +#45558 = VECTOR('',#45559,1.); +#45559 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45560 = PCURVE('',#44229,#45561); +#45561 = DEFINITIONAL_REPRESENTATION('',(#45562),#45566); +#45562 = LINE('',#45563,#45564); +#45563 = CARTESIAN_POINT('',(1.115,0.165)); +#45564 = VECTOR('',#45565,1.); +#45565 = DIRECTION('',(1.,0.E+000)); +#45566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45567 = PCURVE('',#45568,#45573); +#45568 = PLANE('',#45569); +#45569 = AXIS2_PLACEMENT_3D('',#45570,#45571,#45572); +#45570 = CARTESIAN_POINT('',(1.115,0.165,1.05)); +#45571 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45572 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45573 = DEFINITIONAL_REPRESENTATION('',(#45574),#45578); +#45574 = LINE('',#45575,#45576); +#45575 = CARTESIAN_POINT('',(2.2,0.E+000)); +#45576 = VECTOR('',#45577,1.); +#45577 = DIRECTION('',(0.E+000,1.)); +#45578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45579 = ORIENTED_EDGE('',*,*,#45580,.F.); +#45580 = EDGE_CURVE('',#45581,#45553,#45583,.T.); +#45581 = VERTEX_POINT('',#45582); +#45582 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); +#45583 = SURFACE_CURVE('',#45584,(#45588,#45595),.PCURVE_S1.); +#45584 = LINE('',#45585,#45586); +#45585 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); +#45586 = VECTOR('',#45587,1.); +#45587 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45588 = PCURVE('',#44229,#45589); +#45589 = DEFINITIONAL_REPRESENTATION('',(#45590),#45594); +#45590 = LINE('',#45591,#45592); +#45591 = CARTESIAN_POINT('',(1.485,4.5E-002)); +#45592 = VECTOR('',#45593,1.); +#45593 = DIRECTION('',(0.E+000,1.)); +#45594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45595 = PCURVE('',#45596,#45601); +#45596 = PLANE('',#45597); +#45597 = AXIS2_PLACEMENT_3D('',#45598,#45599,#45600); +#45598 = CARTESIAN_POINT('',(1.485,0.E+000,0.E+000)); +#45599 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45600 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45601 = DEFINITIONAL_REPRESENTATION('',(#45602),#45606); +#45602 = LINE('',#45603,#45604); +#45603 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#45604 = VECTOR('',#45605,1.); +#45605 = DIRECTION('',(0.E+000,1.)); +#45606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45607 = ORIENTED_EDGE('',*,*,#45608,.T.); +#45608 = EDGE_CURVE('',#45581,#45609,#45611,.T.); +#45609 = VERTEX_POINT('',#45610); +#45610 = CARTESIAN_POINT('',(1.55,4.5E-002,-1.15)); +#45611 = SURFACE_CURVE('',#45612,(#45616,#45623),.PCURVE_S1.); +#45612 = LINE('',#45613,#45614); +#45613 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); +#45614 = VECTOR('',#45615,1.); +#45615 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45616 = PCURVE('',#44229,#45617); +#45617 = DEFINITIONAL_REPRESENTATION('',(#45618),#45622); +#45618 = LINE('',#45619,#45620); +#45619 = CARTESIAN_POINT('',(1.485,4.5E-002)); +#45620 = VECTOR('',#45621,1.); +#45621 = DIRECTION('',(1.,0.E+000)); +#45622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45623 = PCURVE('',#45624,#45629); +#45624 = PLANE('',#45625); +#45625 = AXIS2_PLACEMENT_3D('',#45626,#45627,#45628); +#45626 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#45627 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45628 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45629 = DEFINITIONAL_REPRESENTATION('',(#45630),#45634); +#45630 = LINE('',#45631,#45632); +#45631 = CARTESIAN_POINT('',(3.035,0.E+000)); +#45632 = VECTOR('',#45633,1.); +#45633 = DIRECTION('',(1.,0.E+000)); +#45634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45635 = ORIENTED_EDGE('',*,*,#45636,.T.); +#45636 = EDGE_CURVE('',#45609,#45637,#45639,.T.); +#45637 = VERTEX_POINT('',#45638); +#45638 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); +#45639 = SURFACE_CURVE('',#45640,(#45645,#45652),.PCURVE_S1.); +#45640 = CIRCLE('',#45641,0.2); +#45641 = AXIS2_PLACEMENT_3D('',#45642,#45643,#45644); +#45642 = CARTESIAN_POINT('',(1.55,0.245,-1.15)); +#45643 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45644 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45645 = PCURVE('',#44229,#45646); +#45646 = DEFINITIONAL_REPRESENTATION('',(#45647),#45651); +#45647 = CIRCLE('',#45648,0.2); +#45648 = AXIS2_PLACEMENT_2D('',#45649,#45650); +#45649 = CARTESIAN_POINT('',(1.55,0.245)); +#45650 = DIRECTION('',(0.E+000,-1.)); +#45651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45652 = PCURVE('',#45653,#45658); +#45653 = CYLINDRICAL_SURFACE('',#45654,0.2); +#45654 = AXIS2_PLACEMENT_3D('',#45655,#45656,#45657); +#45655 = CARTESIAN_POINT('',(1.55,0.245,-1.15)); +#45656 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45657 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45658 = DEFINITIONAL_REPRESENTATION('',(#45659),#45662); +#45659 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45660,#45661),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43268 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#43269 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#43270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43271 = ORIENTED_EDGE('',*,*,#43272,.T.); -#43272 = EDGE_CURVE('',#43245,#43273,#43275,.T.); -#43273 = VERTEX_POINT('',#43274); -#43274 = CARTESIAN_POINT('',(1.75,0.445,-1.15)); -#43275 = SURFACE_CURVE('',#43276,(#43280,#43287),.PCURVE_S1.); -#43276 = LINE('',#43277,#43278); -#43277 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); -#43278 = VECTOR('',#43279,1.); -#43279 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43280 = PCURVE('',#41837,#43281); -#43281 = DEFINITIONAL_REPRESENTATION('',(#43282),#43286); -#43282 = LINE('',#43283,#43284); -#43283 = CARTESIAN_POINT('',(1.75,0.245)); -#43284 = VECTOR('',#43285,1.); -#43285 = DIRECTION('',(0.E+000,1.)); -#43286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43287 = PCURVE('',#43288,#43293); -#43288 = PLANE('',#43289); -#43289 = AXIS2_PLACEMENT_3D('',#43290,#43291,#43292); -#43290 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); -#43291 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43292 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43293 = DEFINITIONAL_REPRESENTATION('',(#43294),#43298); -#43294 = LINE('',#43295,#43296); -#43295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43296 = VECTOR('',#43297,1.); -#43297 = DIRECTION('',(1.,0.E+000)); -#43298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43299 = ORIENTED_EDGE('',*,*,#43300,.T.); -#43300 = EDGE_CURVE('',#43273,#43301,#43303,.T.); -#43301 = VERTEX_POINT('',#43302); -#43302 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); -#43303 = SURFACE_CURVE('',#43304,(#43309,#43316),.PCURVE_S1.); -#43304 = CIRCLE('',#43305,0.2); -#43305 = AXIS2_PLACEMENT_3D('',#43306,#43307,#43308); -#43306 = CARTESIAN_POINT('',(1.55,0.445,-1.15)); -#43307 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43308 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43309 = PCURVE('',#41837,#43310); -#43310 = DEFINITIONAL_REPRESENTATION('',(#43311),#43315); -#43311 = CIRCLE('',#43312,0.2); -#43312 = AXIS2_PLACEMENT_2D('',#43313,#43314); -#43313 = CARTESIAN_POINT('',(1.55,0.445)); -#43314 = DIRECTION('',(1.,0.E+000)); -#43315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43316 = PCURVE('',#43317,#43322); -#43317 = CYLINDRICAL_SURFACE('',#43318,0.2); -#43318 = AXIS2_PLACEMENT_3D('',#43319,#43320,#43321); -#43319 = CARTESIAN_POINT('',(1.55,0.445,-1.15)); -#43320 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43321 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43322 = DEFINITIONAL_REPRESENTATION('',(#43323),#43326); -#43323 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43324,#43325),.UNSPECIFIED., +#45660 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#45661 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#45662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45663 = ORIENTED_EDGE('',*,*,#45664,.T.); +#45664 = EDGE_CURVE('',#45637,#45665,#45667,.T.); +#45665 = VERTEX_POINT('',#45666); +#45666 = CARTESIAN_POINT('',(1.75,0.445,-1.15)); +#45667 = SURFACE_CURVE('',#45668,(#45672,#45679),.PCURVE_S1.); +#45668 = LINE('',#45669,#45670); +#45669 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); +#45670 = VECTOR('',#45671,1.); +#45671 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45672 = PCURVE('',#44229,#45673); +#45673 = DEFINITIONAL_REPRESENTATION('',(#45674),#45678); +#45674 = LINE('',#45675,#45676); +#45675 = CARTESIAN_POINT('',(1.75,0.245)); +#45676 = VECTOR('',#45677,1.); +#45677 = DIRECTION('',(0.E+000,1.)); +#45678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45679 = PCURVE('',#45680,#45685); +#45680 = PLANE('',#45681); +#45681 = AXIS2_PLACEMENT_3D('',#45682,#45683,#45684); +#45682 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); +#45683 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45684 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45685 = DEFINITIONAL_REPRESENTATION('',(#45686),#45690); +#45686 = LINE('',#45687,#45688); +#45687 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45688 = VECTOR('',#45689,1.); +#45689 = DIRECTION('',(1.,0.E+000)); +#45690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45691 = ORIENTED_EDGE('',*,*,#45692,.T.); +#45692 = EDGE_CURVE('',#45665,#45693,#45695,.T.); +#45693 = VERTEX_POINT('',#45694); +#45694 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); +#45695 = SURFACE_CURVE('',#45696,(#45701,#45708),.PCURVE_S1.); +#45696 = CIRCLE('',#45697,0.2); +#45697 = AXIS2_PLACEMENT_3D('',#45698,#45699,#45700); +#45698 = CARTESIAN_POINT('',(1.55,0.445,-1.15)); +#45699 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45700 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45701 = PCURVE('',#44229,#45702); +#45702 = DEFINITIONAL_REPRESENTATION('',(#45703),#45707); +#45703 = CIRCLE('',#45704,0.2); +#45704 = AXIS2_PLACEMENT_2D('',#45705,#45706); +#45705 = CARTESIAN_POINT('',(1.55,0.445)); +#45706 = DIRECTION('',(1.,0.E+000)); +#45707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45708 = PCURVE('',#45709,#45714); +#45709 = CYLINDRICAL_SURFACE('',#45710,0.2); +#45710 = AXIS2_PLACEMENT_3D('',#45711,#45712,#45713); +#45711 = CARTESIAN_POINT('',(1.55,0.445,-1.15)); +#45712 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45713 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45714 = DEFINITIONAL_REPRESENTATION('',(#45715),#45718); +#45715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45716,#45717),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43324 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43325 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#43326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43327 = ORIENTED_EDGE('',*,*,#43328,.T.); -#43328 = EDGE_CURVE('',#43301,#43329,#43331,.T.); -#43329 = VERTEX_POINT('',#43330); -#43330 = CARTESIAN_POINT('',(0.51,0.645,-1.15)); -#43331 = SURFACE_CURVE('',#43332,(#43336,#43343),.PCURVE_S1.); -#43332 = LINE('',#43333,#43334); -#43333 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); -#43334 = VECTOR('',#43335,1.); -#43335 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43336 = PCURVE('',#41837,#43337); -#43337 = DEFINITIONAL_REPRESENTATION('',(#43338),#43342); -#43338 = LINE('',#43339,#43340); -#43339 = CARTESIAN_POINT('',(1.55,0.645)); -#43340 = VECTOR('',#43341,1.); -#43341 = DIRECTION('',(-1.,0.E+000)); -#43342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43343 = PCURVE('',#43344,#43349); -#43344 = PLANE('',#43345); -#43345 = AXIS2_PLACEMENT_3D('',#43346,#43347,#43348); -#43346 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); -#43347 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43348 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43349 = DEFINITIONAL_REPRESENTATION('',(#43350),#43354); -#43350 = LINE('',#43351,#43352); -#43351 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43352 = VECTOR('',#43353,1.); -#43353 = DIRECTION('',(1.,0.E+000)); -#43354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43355 = ORIENTED_EDGE('',*,*,#43356,.F.); -#43356 = EDGE_CURVE('',#43357,#43329,#43359,.T.); -#43357 = VERTEX_POINT('',#43358); -#43358 = CARTESIAN_POINT('',(0.51,0.92,-1.15)); -#43359 = SURFACE_CURVE('',#43360,(#43364,#43371),.PCURVE_S1.); -#43360 = LINE('',#43361,#43362); -#43361 = CARTESIAN_POINT('',(0.51,0.92,-1.15)); -#43362 = VECTOR('',#43363,1.); -#43363 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43364 = PCURVE('',#41837,#43365); -#43365 = DEFINITIONAL_REPRESENTATION('',(#43366),#43370); -#43366 = LINE('',#43367,#43368); -#43367 = CARTESIAN_POINT('',(0.51,0.92)); -#43368 = VECTOR('',#43369,1.); -#43369 = DIRECTION('',(0.E+000,-1.)); -#43370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43371 = PCURVE('',#43372,#43377); -#43372 = PLANE('',#43373); -#43373 = AXIS2_PLACEMENT_3D('',#43374,#43375,#43376); -#43374 = CARTESIAN_POINT('',(0.46,0.7825,-1.2)); -#43375 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); -#43376 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43377 = DEFINITIONAL_REPRESENTATION('',(#43378),#43382); -#43378 = LINE('',#43379,#43380); -#43379 = CARTESIAN_POINT('',(-0.1375,7.071067811865E-002)); -#43380 = VECTOR('',#43381,1.); -#43381 = DIRECTION('',(1.,0.E+000)); -#43382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43383 = ORIENTED_EDGE('',*,*,#43384,.F.); -#43384 = EDGE_CURVE('',#43385,#43357,#43387,.T.); -#43385 = VERTEX_POINT('',#43386); -#43386 = CARTESIAN_POINT('',(3.095,0.92,-1.15)); -#43387 = SURFACE_CURVE('',#43388,(#43392,#43399),.PCURVE_S1.); -#43388 = LINE('',#43389,#43390); -#43389 = CARTESIAN_POINT('',(3.095,0.92,-1.15)); -#43390 = VECTOR('',#43391,1.); -#43391 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43392 = PCURVE('',#41837,#43393); -#43393 = DEFINITIONAL_REPRESENTATION('',(#43394),#43398); -#43394 = LINE('',#43395,#43396); -#43395 = CARTESIAN_POINT('',(3.095,0.92)); -#43396 = VECTOR('',#43397,1.); -#43397 = DIRECTION('',(-1.,0.E+000)); -#43398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43399 = PCURVE('',#43400,#43405); -#43400 = PLANE('',#43401); -#43401 = AXIS2_PLACEMENT_3D('',#43402,#43403,#43404); -#43402 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); -#43403 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43404 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43405 = DEFINITIONAL_REPRESENTATION('',(#43406),#43410); -#43406 = LINE('',#43407,#43408); -#43407 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43408 = VECTOR('',#43409,1.); -#43409 = DIRECTION('',(1.,0.E+000)); -#43410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43411 = ORIENTED_EDGE('',*,*,#43412,.F.); -#43412 = EDGE_CURVE('',#43413,#43385,#43415,.T.); -#43413 = VERTEX_POINT('',#43414); -#43414 = CARTESIAN_POINT('',(3.445,0.57,-1.15)); -#43415 = SURFACE_CURVE('',#43416,(#43421,#43428),.PCURVE_S1.); -#43416 = CIRCLE('',#43417,0.35); -#43417 = AXIS2_PLACEMENT_3D('',#43418,#43419,#43420); -#43418 = CARTESIAN_POINT('',(3.095,0.57,-1.15)); -#43419 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43420 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43421 = PCURVE('',#41837,#43422); -#43422 = DEFINITIONAL_REPRESENTATION('',(#43423),#43427); -#43423 = CIRCLE('',#43424,0.35); -#43424 = AXIS2_PLACEMENT_2D('',#43425,#43426); -#43425 = CARTESIAN_POINT('',(3.095,0.57)); -#43426 = DIRECTION('',(1.,0.E+000)); -#43427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43428 = PCURVE('',#43429,#43434); -#43429 = CYLINDRICAL_SURFACE('',#43430,0.35); -#43430 = AXIS2_PLACEMENT_3D('',#43431,#43432,#43433); -#43431 = CARTESIAN_POINT('',(3.095,0.57,-2.35)); -#43432 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43433 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43434 = DEFINITIONAL_REPRESENTATION('',(#43435),#43438); -#43435 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43436,#43437),.UNSPECIFIED., +#45716 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45717 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#45718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45719 = ORIENTED_EDGE('',*,*,#45720,.T.); +#45720 = EDGE_CURVE('',#45693,#45721,#45723,.T.); +#45721 = VERTEX_POINT('',#45722); +#45722 = CARTESIAN_POINT('',(0.51,0.645,-1.15)); +#45723 = SURFACE_CURVE('',#45724,(#45728,#45735),.PCURVE_S1.); +#45724 = LINE('',#45725,#45726); +#45725 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); +#45726 = VECTOR('',#45727,1.); +#45727 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45728 = PCURVE('',#44229,#45729); +#45729 = DEFINITIONAL_REPRESENTATION('',(#45730),#45734); +#45730 = LINE('',#45731,#45732); +#45731 = CARTESIAN_POINT('',(1.55,0.645)); +#45732 = VECTOR('',#45733,1.); +#45733 = DIRECTION('',(-1.,0.E+000)); +#45734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45735 = PCURVE('',#45736,#45741); +#45736 = PLANE('',#45737); +#45737 = AXIS2_PLACEMENT_3D('',#45738,#45739,#45740); +#45738 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); +#45739 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45740 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45741 = DEFINITIONAL_REPRESENTATION('',(#45742),#45746); +#45742 = LINE('',#45743,#45744); +#45743 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#45744 = VECTOR('',#45745,1.); +#45745 = DIRECTION('',(1.,0.E+000)); +#45746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45747 = ORIENTED_EDGE('',*,*,#45748,.F.); +#45748 = EDGE_CURVE('',#45749,#45721,#45751,.T.); +#45749 = VERTEX_POINT('',#45750); +#45750 = CARTESIAN_POINT('',(0.51,0.92,-1.15)); +#45751 = SURFACE_CURVE('',#45752,(#45756,#45763),.PCURVE_S1.); +#45752 = LINE('',#45753,#45754); +#45753 = CARTESIAN_POINT('',(0.51,0.92,-1.15)); +#45754 = VECTOR('',#45755,1.); +#45755 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45756 = PCURVE('',#44229,#45757); +#45757 = DEFINITIONAL_REPRESENTATION('',(#45758),#45762); +#45758 = LINE('',#45759,#45760); +#45759 = CARTESIAN_POINT('',(0.51,0.92)); +#45760 = VECTOR('',#45761,1.); +#45761 = DIRECTION('',(0.E+000,-1.)); +#45762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45763 = PCURVE('',#45764,#45769); +#45764 = PLANE('',#45765); +#45765 = AXIS2_PLACEMENT_3D('',#45766,#45767,#45768); +#45766 = CARTESIAN_POINT('',(0.46,0.7825,-1.2)); +#45767 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); +#45768 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45769 = DEFINITIONAL_REPRESENTATION('',(#45770),#45774); +#45770 = LINE('',#45771,#45772); +#45771 = CARTESIAN_POINT('',(-0.1375,7.071067811865E-002)); +#45772 = VECTOR('',#45773,1.); +#45773 = DIRECTION('',(1.,0.E+000)); +#45774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45775 = ORIENTED_EDGE('',*,*,#45776,.F.); +#45776 = EDGE_CURVE('',#45777,#45749,#45779,.T.); +#45777 = VERTEX_POINT('',#45778); +#45778 = CARTESIAN_POINT('',(3.095,0.92,-1.15)); +#45779 = SURFACE_CURVE('',#45780,(#45784,#45791),.PCURVE_S1.); +#45780 = LINE('',#45781,#45782); +#45781 = CARTESIAN_POINT('',(3.095,0.92,-1.15)); +#45782 = VECTOR('',#45783,1.); +#45783 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45784 = PCURVE('',#44229,#45785); +#45785 = DEFINITIONAL_REPRESENTATION('',(#45786),#45790); +#45786 = LINE('',#45787,#45788); +#45787 = CARTESIAN_POINT('',(3.095,0.92)); +#45788 = VECTOR('',#45789,1.); +#45789 = DIRECTION('',(-1.,0.E+000)); +#45790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45791 = PCURVE('',#45792,#45797); +#45792 = PLANE('',#45793); +#45793 = AXIS2_PLACEMENT_3D('',#45794,#45795,#45796); +#45794 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); +#45795 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45796 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45797 = DEFINITIONAL_REPRESENTATION('',(#45798),#45802); +#45798 = LINE('',#45799,#45800); +#45799 = CARTESIAN_POINT('',(0.E+000,1.2)); +#45800 = VECTOR('',#45801,1.); +#45801 = DIRECTION('',(1.,0.E+000)); +#45802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45803 = ORIENTED_EDGE('',*,*,#45804,.F.); +#45804 = EDGE_CURVE('',#45805,#45777,#45807,.T.); +#45805 = VERTEX_POINT('',#45806); +#45806 = CARTESIAN_POINT('',(3.445,0.57,-1.15)); +#45807 = SURFACE_CURVE('',#45808,(#45813,#45820),.PCURVE_S1.); +#45808 = CIRCLE('',#45809,0.35); +#45809 = AXIS2_PLACEMENT_3D('',#45810,#45811,#45812); +#45810 = CARTESIAN_POINT('',(3.095,0.57,-1.15)); +#45811 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45812 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45813 = PCURVE('',#44229,#45814); +#45814 = DEFINITIONAL_REPRESENTATION('',(#45815),#45819); +#45815 = CIRCLE('',#45816,0.35); +#45816 = AXIS2_PLACEMENT_2D('',#45817,#45818); +#45817 = CARTESIAN_POINT('',(3.095,0.57)); +#45818 = DIRECTION('',(1.,0.E+000)); +#45819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45820 = PCURVE('',#45821,#45826); +#45821 = CYLINDRICAL_SURFACE('',#45822,0.35); +#45822 = AXIS2_PLACEMENT_3D('',#45823,#45824,#45825); +#45823 = CARTESIAN_POINT('',(3.095,0.57,-2.35)); +#45824 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45825 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45826 = DEFINITIONAL_REPRESENTATION('',(#45827),#45830); +#45827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45828,#45829),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43436 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43437 = CARTESIAN_POINT('',(1.570796326795,1.2)); -#43438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43439 = ORIENTED_EDGE('',*,*,#43440,.F.); -#43440 = EDGE_CURVE('',#43441,#43413,#43443,.T.); -#43441 = VERTEX_POINT('',#43442); -#43442 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-1.15)); -#43443 = SURFACE_CURVE('',#43444,(#43448,#43455),.PCURVE_S1.); -#43444 = LINE('',#43445,#43446); -#43445 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-1.15)); -#43446 = VECTOR('',#43447,1.); -#43447 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43448 = PCURVE('',#41837,#43449); -#43449 = DEFINITIONAL_REPRESENTATION('',(#43450),#43454); -#43450 = LINE('',#43451,#43452); -#43451 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002)); -#43452 = VECTOR('',#43453,1.); -#43453 = DIRECTION('',(0.E+000,1.)); -#43454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43455 = PCURVE('',#43456,#43461); -#43456 = PLANE('',#43457); -#43457 = AXIS2_PLACEMENT_3D('',#43458,#43459,#43460); -#43458 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); -#43459 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43460 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43461 = DEFINITIONAL_REPRESENTATION('',(#43462),#43466); -#43462 = LINE('',#43463,#43464); -#43463 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43464 = VECTOR('',#43465,1.); -#43465 = DIRECTION('',(1.,0.E+000)); -#43466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43467 = ORIENTED_EDGE('',*,*,#43468,.F.); -#43468 = EDGE_CURVE('',#43469,#43441,#43471,.T.); -#43469 = VERTEX_POINT('',#43470); -#43470 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-1.15)); -#43471 = SURFACE_CURVE('',#43472,(#43477,#43484),.PCURVE_S1.); -#43472 = CIRCLE('',#43473,0.25); -#43473 = AXIS2_PLACEMENT_3D('',#43474,#43475,#43476); -#43474 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-1.15)); -#43475 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43476 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#43477 = PCURVE('',#41837,#43478); -#43478 = DEFINITIONAL_REPRESENTATION('',(#43479),#43483); -#43479 = CIRCLE('',#43480,0.25); -#43480 = AXIS2_PLACEMENT_2D('',#43481,#43482); -#43481 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002)); -#43482 = DIRECTION('',(0.707106781187,-0.707106781187)); -#43483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43484 = PCURVE('',#43485,#43490); -#43485 = CYLINDRICAL_SURFACE('',#43486,0.25); -#43486 = AXIS2_PLACEMENT_3D('',#43487,#43488,#43489); -#43487 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-2.35)); -#43488 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43489 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43490 = DEFINITIONAL_REPRESENTATION('',(#43491),#43494); -#43491 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43492,#43493),.UNSPECIFIED., +#45828 = CARTESIAN_POINT('',(0.E+000,1.2)); +#45829 = CARTESIAN_POINT('',(1.570796326795,1.2)); +#45830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45831 = ORIENTED_EDGE('',*,*,#45832,.F.); +#45832 = EDGE_CURVE('',#45833,#45805,#45835,.T.); +#45833 = VERTEX_POINT('',#45834); +#45834 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-1.15)); +#45835 = SURFACE_CURVE('',#45836,(#45840,#45847),.PCURVE_S1.); +#45836 = LINE('',#45837,#45838); +#45837 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-1.15)); +#45838 = VECTOR('',#45839,1.); +#45839 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45840 = PCURVE('',#44229,#45841); +#45841 = DEFINITIONAL_REPRESENTATION('',(#45842),#45846); +#45842 = LINE('',#45843,#45844); +#45843 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002)); +#45844 = VECTOR('',#45845,1.); +#45845 = DIRECTION('',(0.E+000,1.)); +#45846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45847 = PCURVE('',#45848,#45853); +#45848 = PLANE('',#45849); +#45849 = AXIS2_PLACEMENT_3D('',#45850,#45851,#45852); +#45850 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); +#45851 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45852 = DIRECTION('',(0.E+000,1.,0.E+000)); +#45853 = DEFINITIONAL_REPRESENTATION('',(#45854),#45858); +#45854 = LINE('',#45855,#45856); +#45855 = CARTESIAN_POINT('',(0.E+000,1.2)); +#45856 = VECTOR('',#45857,1.); +#45857 = DIRECTION('',(1.,0.E+000)); +#45858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45859 = ORIENTED_EDGE('',*,*,#45860,.F.); +#45860 = EDGE_CURVE('',#45861,#45833,#45863,.T.); +#45861 = VERTEX_POINT('',#45862); +#45862 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-1.15)); +#45863 = SURFACE_CURVE('',#45864,(#45869,#45876),.PCURVE_S1.); +#45864 = CIRCLE('',#45865,0.25); +#45865 = AXIS2_PLACEMENT_3D('',#45866,#45867,#45868); +#45866 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-1.15)); +#45867 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45868 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#45869 = PCURVE('',#44229,#45870); +#45870 = DEFINITIONAL_REPRESENTATION('',(#45871),#45875); +#45871 = CIRCLE('',#45872,0.25); +#45872 = AXIS2_PLACEMENT_2D('',#45873,#45874); +#45873 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002)); +#45874 = DIRECTION('',(0.707106781187,-0.707106781187)); +#45875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45876 = PCURVE('',#45877,#45882); +#45877 = CYLINDRICAL_SURFACE('',#45878,0.25); +#45878 = AXIS2_PLACEMENT_3D('',#45879,#45880,#45881); +#45879 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-2.35)); +#45880 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45881 = DIRECTION('',(1.,0.E+000,0.E+000)); +#45882 = DEFINITIONAL_REPRESENTATION('',(#45883),#45886); +#45883 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45884,#45885),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#43492 = CARTESIAN_POINT('',(5.497787143782,1.2)); -#43493 = CARTESIAN_POINT('',(6.28318530718,1.2)); -#43494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43495 = ORIENTED_EDGE('',*,*,#43496,.F.); -#43496 = EDGE_CURVE('',#43497,#43469,#43499,.T.); -#43497 = VERTEX_POINT('',#43498); -#43498 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-1.15)); -#43499 = SURFACE_CURVE('',#43500,(#43504,#43511),.PCURVE_S1.); -#43500 = LINE('',#43501,#43502); -#43501 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-1.15)); -#43502 = VECTOR('',#43503,1.); -#43503 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#43504 = PCURVE('',#41837,#43505); -#43505 = DEFINITIONAL_REPRESENTATION('',(#43506),#43510); -#43506 = LINE('',#43507,#43508); -#43507 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297)); -#43508 = VECTOR('',#43509,1.); -#43509 = DIRECTION('',(0.707106781187,0.707106781187)); -#43510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43511 = PCURVE('',#43512,#43517); -#43512 = PLANE('',#43513); -#43513 = AXIS2_PLACEMENT_3D('',#43514,#43515,#43516); -#43514 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); -#43515 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#43516 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#43517 = DEFINITIONAL_REPRESENTATION('',(#43518),#43522); -#43518 = LINE('',#43519,#43520); -#43519 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43520 = VECTOR('',#43521,1.); -#43521 = DIRECTION('',(1.,0.E+000)); -#43522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43523 = ORIENTED_EDGE('',*,*,#43524,.F.); -#43524 = EDGE_CURVE('',#42925,#43497,#43525,.T.); -#43525 = SURFACE_CURVE('',#43526,(#43531,#43538),.PCURVE_S1.); -#43526 = CIRCLE('',#43527,0.25); -#43527 = AXIS2_PLACEMENT_3D('',#43528,#43529,#43530); -#43528 = CARTESIAN_POINT('',(2.594375541595,-0.67,-1.15)); -#43529 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43530 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43531 = PCURVE('',#41837,#43532); -#43532 = DEFINITIONAL_REPRESENTATION('',(#43533),#43537); -#43533 = CIRCLE('',#43534,0.25); -#43534 = AXIS2_PLACEMENT_2D('',#43535,#43536); -#43535 = CARTESIAN_POINT('',(2.594375541595,-0.67)); -#43536 = DIRECTION('',(0.E+000,-1.)); -#43537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43538 = PCURVE('',#42963,#43539); -#43539 = DEFINITIONAL_REPRESENTATION('',(#43540),#43543); -#43540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43541,#43542),.UNSPECIFIED., +#45884 = CARTESIAN_POINT('',(5.497787143782,1.2)); +#45885 = CARTESIAN_POINT('',(6.28318530718,1.2)); +#45886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45887 = ORIENTED_EDGE('',*,*,#45888,.F.); +#45888 = EDGE_CURVE('',#45889,#45861,#45891,.T.); +#45889 = VERTEX_POINT('',#45890); +#45890 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-1.15)); +#45891 = SURFACE_CURVE('',#45892,(#45896,#45903),.PCURVE_S1.); +#45892 = LINE('',#45893,#45894); +#45893 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-1.15)); +#45894 = VECTOR('',#45895,1.); +#45895 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#45896 = PCURVE('',#44229,#45897); +#45897 = DEFINITIONAL_REPRESENTATION('',(#45898),#45902); +#45898 = LINE('',#45899,#45900); +#45899 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297)); +#45900 = VECTOR('',#45901,1.); +#45901 = DIRECTION('',(0.707106781187,0.707106781187)); +#45902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45903 = PCURVE('',#45904,#45909); +#45904 = PLANE('',#45905); +#45905 = AXIS2_PLACEMENT_3D('',#45906,#45907,#45908); +#45906 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); +#45907 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#45908 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#45909 = DEFINITIONAL_REPRESENTATION('',(#45910),#45914); +#45910 = LINE('',#45911,#45912); +#45911 = CARTESIAN_POINT('',(0.E+000,1.2)); +#45912 = VECTOR('',#45913,1.); +#45913 = DIRECTION('',(1.,0.E+000)); +#45914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45915 = ORIENTED_EDGE('',*,*,#45916,.F.); +#45916 = EDGE_CURVE('',#45317,#45889,#45917,.T.); +#45917 = SURFACE_CURVE('',#45918,(#45923,#45930),.PCURVE_S1.); +#45918 = CIRCLE('',#45919,0.25); +#45919 = AXIS2_PLACEMENT_3D('',#45920,#45921,#45922); +#45920 = CARTESIAN_POINT('',(2.594375541595,-0.67,-1.15)); +#45921 = DIRECTION('',(0.E+000,0.E+000,1.)); +#45922 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45923 = PCURVE('',#44229,#45924); +#45924 = DEFINITIONAL_REPRESENTATION('',(#45925),#45929); +#45925 = CIRCLE('',#45926,0.25); +#45926 = AXIS2_PLACEMENT_2D('',#45927,#45928); +#45927 = CARTESIAN_POINT('',(2.594375541595,-0.67)); +#45928 = DIRECTION('',(0.E+000,-1.)); +#45929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45930 = PCURVE('',#45355,#45931); +#45931 = DEFINITIONAL_REPRESENTATION('',(#45932),#45935); +#45932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45933,#45934),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#43541 = CARTESIAN_POINT('',(4.712388980385,1.2)); -#43542 = CARTESIAN_POINT('',(5.49778714378,1.2)); -#43543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43544 = ORIENTED_EDGE('',*,*,#42924,.F.); -#43545 = ORIENTED_EDGE('',*,*,#42899,.T.); -#43546 = ORIENTED_EDGE('',*,*,#41823,.F.); -#43547 = ORIENTED_EDGE('',*,*,#43548,.T.); -#43548 = EDGE_CURVE('',#41792,#43549,#43551,.T.); -#43549 = VERTEX_POINT('',#43550); -#43550 = CARTESIAN_POINT('',(1.762915026221,-1.2,-1.15)); -#43551 = SURFACE_CURVE('',#43552,(#43556,#43563),.PCURVE_S1.); -#43552 = LINE('',#43553,#43554); -#43553 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); -#43554 = VECTOR('',#43555,1.); -#43555 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43556 = PCURVE('',#41837,#43557); -#43557 = DEFINITIONAL_REPRESENTATION('',(#43558),#43562); -#43558 = LINE('',#43559,#43560); -#43559 = CARTESIAN_POINT('',(1.762915026221,-0.925)); -#43560 = VECTOR('',#43561,1.); -#43561 = DIRECTION('',(0.E+000,-1.)); -#43562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43563 = PCURVE('',#41812,#43564); -#43564 = DEFINITIONAL_REPRESENTATION('',(#43565),#43568); -#43565 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43566,#43567),.UNSPECIFIED., +#45933 = CARTESIAN_POINT('',(4.712388980385,1.2)); +#45934 = CARTESIAN_POINT('',(5.49778714378,1.2)); +#45935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45936 = ORIENTED_EDGE('',*,*,#45316,.F.); +#45937 = ORIENTED_EDGE('',*,*,#45291,.T.); +#45938 = ORIENTED_EDGE('',*,*,#44215,.F.); +#45939 = ORIENTED_EDGE('',*,*,#45940,.T.); +#45940 = EDGE_CURVE('',#44184,#45941,#45943,.T.); +#45941 = VERTEX_POINT('',#45942); +#45942 = CARTESIAN_POINT('',(1.762915026221,-1.2,-1.15)); +#45943 = SURFACE_CURVE('',#45944,(#45948,#45955),.PCURVE_S1.); +#45944 = LINE('',#45945,#45946); +#45945 = CARTESIAN_POINT('',(1.762915026221,-0.925,-1.15)); +#45946 = VECTOR('',#45947,1.); +#45947 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45948 = PCURVE('',#44229,#45949); +#45949 = DEFINITIONAL_REPRESENTATION('',(#45950),#45954); +#45950 = LINE('',#45951,#45952); +#45951 = CARTESIAN_POINT('',(1.762915026221,-0.925)); +#45952 = VECTOR('',#45953,1.); +#45953 = DIRECTION('',(0.E+000,-1.)); +#45954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45955 = PCURVE('',#44204,#45956); +#45956 = DEFINITIONAL_REPRESENTATION('',(#45957),#45960); +#45957 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45958,#45959),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.275),.PIECEWISE_BEZIER_KNOTS.); -#43566 = CARTESIAN_POINT('',(0.848062078984,-0.3)); -#43567 = CARTESIAN_POINT('',(0.848062078984,-2.5E-002)); -#43568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43569 = ORIENTED_EDGE('',*,*,#43570,.T.); -#43570 = EDGE_CURVE('',#43549,#43571,#43573,.T.); -#43571 = VERTEX_POINT('',#43572); -#43572 = CARTESIAN_POINT('',(-1.762915026221,-1.2,-1.15)); -#43573 = SURFACE_CURVE('',#43574,(#43578,#43585),.PCURVE_S1.); -#43574 = LINE('',#43575,#43576); -#43575 = CARTESIAN_POINT('',(1.762915026221,-1.2,-1.15)); -#43576 = VECTOR('',#43577,1.); -#43577 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43578 = PCURVE('',#41837,#43579); -#43579 = DEFINITIONAL_REPRESENTATION('',(#43580),#43584); -#43580 = LINE('',#43581,#43582); -#43581 = CARTESIAN_POINT('',(1.762915026221,-1.2)); -#43582 = VECTOR('',#43583,1.); -#43583 = DIRECTION('',(-1.,0.E+000)); -#43584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43585 = PCURVE('',#43586,#43591); -#43586 = PLANE('',#43587); -#43587 = AXIS2_PLACEMENT_3D('',#43588,#43589,#43590); -#43588 = CARTESIAN_POINT('',(1.79,-1.2,-1.15)); -#43589 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43590 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#43591 = DEFINITIONAL_REPRESENTATION('',(#43592),#43596); -#43592 = LINE('',#43593,#43594); -#43593 = CARTESIAN_POINT('',(0.E+000,-2.7084973779E-002)); -#43594 = VECTOR('',#43595,1.); -#43595 = DIRECTION('',(0.E+000,-1.)); -#43596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43597 = ORIENTED_EDGE('',*,*,#43598,.F.); -#43598 = EDGE_CURVE('',#41883,#43571,#43599,.T.); -#43599 = SURFACE_CURVE('',#43600,(#43604,#43611),.PCURVE_S1.); -#43600 = LINE('',#43601,#43602); -#43601 = CARTESIAN_POINT('',(-1.762915026221,-0.925,-1.15)); -#43602 = VECTOR('',#43603,1.); -#43603 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43604 = PCURVE('',#41837,#43605); -#43605 = DEFINITIONAL_REPRESENTATION('',(#43606),#43610); -#43606 = LINE('',#43607,#43608); -#43607 = CARTESIAN_POINT('',(-1.762915026221,-0.925)); -#43608 = VECTOR('',#43609,1.); -#43609 = DIRECTION('',(0.E+000,-1.)); -#43610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43611 = PCURVE('',#41926,#43612); -#43612 = DEFINITIONAL_REPRESENTATION('',(#43613),#43616); -#43613 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43614,#43615),.UNSPECIFIED., +#45958 = CARTESIAN_POINT('',(0.848062078984,-0.3)); +#45959 = CARTESIAN_POINT('',(0.848062078984,-2.5E-002)); +#45960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45961 = ORIENTED_EDGE('',*,*,#45962,.T.); +#45962 = EDGE_CURVE('',#45941,#45963,#45965,.T.); +#45963 = VERTEX_POINT('',#45964); +#45964 = CARTESIAN_POINT('',(-1.762915026221,-1.2,-1.15)); +#45965 = SURFACE_CURVE('',#45966,(#45970,#45977),.PCURVE_S1.); +#45966 = LINE('',#45967,#45968); +#45967 = CARTESIAN_POINT('',(1.762915026221,-1.2,-1.15)); +#45968 = VECTOR('',#45969,1.); +#45969 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#45970 = PCURVE('',#44229,#45971); +#45971 = DEFINITIONAL_REPRESENTATION('',(#45972),#45976); +#45972 = LINE('',#45973,#45974); +#45973 = CARTESIAN_POINT('',(1.762915026221,-1.2)); +#45974 = VECTOR('',#45975,1.); +#45975 = DIRECTION('',(-1.,0.E+000)); +#45976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45977 = PCURVE('',#45978,#45983); +#45978 = PLANE('',#45979); +#45979 = AXIS2_PLACEMENT_3D('',#45980,#45981,#45982); +#45980 = CARTESIAN_POINT('',(1.79,-1.2,-1.15)); +#45981 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45982 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#45983 = DEFINITIONAL_REPRESENTATION('',(#45984),#45988); +#45984 = LINE('',#45985,#45986); +#45985 = CARTESIAN_POINT('',(0.E+000,-2.7084973779E-002)); +#45986 = VECTOR('',#45987,1.); +#45987 = DIRECTION('',(0.E+000,-1.)); +#45988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#45989 = ORIENTED_EDGE('',*,*,#45990,.F.); +#45990 = EDGE_CURVE('',#44275,#45963,#45991,.T.); +#45991 = SURFACE_CURVE('',#45992,(#45996,#46003),.PCURVE_S1.); +#45992 = LINE('',#45993,#45994); +#45993 = CARTESIAN_POINT('',(-1.762915026221,-0.925,-1.15)); +#45994 = VECTOR('',#45995,1.); +#45995 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#45996 = PCURVE('',#44229,#45997); +#45997 = DEFINITIONAL_REPRESENTATION('',(#45998),#46002); +#45998 = LINE('',#45999,#46000); +#45999 = CARTESIAN_POINT('',(-1.762915026221,-0.925)); +#46000 = VECTOR('',#46001,1.); +#46001 = DIRECTION('',(0.E+000,-1.)); +#46002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46003 = PCURVE('',#44318,#46004); +#46004 = DEFINITIONAL_REPRESENTATION('',(#46005),#46008); +#46005 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46006,#46007),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.275),.PIECEWISE_BEZIER_KNOTS.); -#43614 = CARTESIAN_POINT('',(2.293530574606,-0.3)); -#43615 = CARTESIAN_POINT('',(2.293530574606,-2.5E-002)); -#43616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43617 = ORIENTED_EDGE('',*,*,#41882,.F.); -#43618 = ORIENTED_EDGE('',*,*,#43619,.F.); -#43619 = EDGE_CURVE('',#43029,#41855,#43620,.T.); -#43620 = SURFACE_CURVE('',#43621,(#43625,#43632),.PCURVE_S1.); -#43621 = LINE('',#43622,#43623); -#43622 = CARTESIAN_POINT('',(-1.79,-0.92,-1.15)); -#43623 = VECTOR('',#43624,1.); -#43624 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43625 = PCURVE('',#41837,#43626); -#43626 = DEFINITIONAL_REPRESENTATION('',(#43627),#43631); -#43627 = LINE('',#43628,#43629); -#43628 = CARTESIAN_POINT('',(-1.79,-0.92)); -#43629 = VECTOR('',#43630,1.); -#43630 = DIRECTION('',(0.E+000,-1.)); -#43631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43632 = PCURVE('',#41870,#43633); -#43633 = DEFINITIONAL_REPRESENTATION('',(#43634),#43638); -#43634 = LINE('',#43635,#43636); -#43635 = CARTESIAN_POINT('',(-6.E-002,-0.305)); -#43636 = VECTOR('',#43637,1.); -#43637 = DIRECTION('',(0.E+000,1.)); -#43638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43639 = ORIENTED_EDGE('',*,*,#43134,.F.); -#43640 = ORIENTED_EDGE('',*,*,#43641,.F.); -#43641 = EDGE_CURVE('',#43642,#43108,#43644,.T.); -#43642 = VERTEX_POINT('',#43643); -#43643 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-1.15)); -#43644 = SURFACE_CURVE('',#43645,(#43650,#43657),.PCURVE_S1.); -#43645 = CIRCLE('',#43646,0.25); -#43646 = AXIS2_PLACEMENT_3D('',#43647,#43648,#43649); -#43647 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-1.15)); -#43648 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43649 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#43650 = PCURVE('',#41837,#43651); -#43651 = DEFINITIONAL_REPRESENTATION('',(#43652),#43656); -#43652 = CIRCLE('',#43653,0.25); -#43653 = AXIS2_PLACEMENT_2D('',#43654,#43655); -#43654 = CARTESIAN_POINT('',(-2.594375541595,-0.67)); -#43655 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#43656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43657 = PCURVE('',#43123,#43658); -#43658 = DEFINITIONAL_REPRESENTATION('',(#43659),#43662); -#43659 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43660,#43661),.UNSPECIFIED., +#46006 = CARTESIAN_POINT('',(2.293530574606,-0.3)); +#46007 = CARTESIAN_POINT('',(2.293530574606,-2.5E-002)); +#46008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46009 = ORIENTED_EDGE('',*,*,#44274,.F.); +#46010 = ORIENTED_EDGE('',*,*,#46011,.F.); +#46011 = EDGE_CURVE('',#45421,#44247,#46012,.T.); +#46012 = SURFACE_CURVE('',#46013,(#46017,#46024),.PCURVE_S1.); +#46013 = LINE('',#46014,#46015); +#46014 = CARTESIAN_POINT('',(-1.79,-0.92,-1.15)); +#46015 = VECTOR('',#46016,1.); +#46016 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46017 = PCURVE('',#44229,#46018); +#46018 = DEFINITIONAL_REPRESENTATION('',(#46019),#46023); +#46019 = LINE('',#46020,#46021); +#46020 = CARTESIAN_POINT('',(-1.79,-0.92)); +#46021 = VECTOR('',#46022,1.); +#46022 = DIRECTION('',(0.E+000,-1.)); +#46023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46024 = PCURVE('',#44262,#46025); +#46025 = DEFINITIONAL_REPRESENTATION('',(#46026),#46030); +#46026 = LINE('',#46027,#46028); +#46027 = CARTESIAN_POINT('',(-6.E-002,-0.305)); +#46028 = VECTOR('',#46029,1.); +#46029 = DIRECTION('',(0.E+000,1.)); +#46030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46031 = ORIENTED_EDGE('',*,*,#45526,.F.); +#46032 = ORIENTED_EDGE('',*,*,#46033,.F.); +#46033 = EDGE_CURVE('',#46034,#45500,#46036,.T.); +#46034 = VERTEX_POINT('',#46035); +#46035 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-1.15)); +#46036 = SURFACE_CURVE('',#46037,(#46042,#46049),.PCURVE_S1.); +#46037 = CIRCLE('',#46038,0.25); +#46038 = AXIS2_PLACEMENT_3D('',#46039,#46040,#46041); +#46039 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-1.15)); +#46040 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46041 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#46042 = PCURVE('',#44229,#46043); +#46043 = DEFINITIONAL_REPRESENTATION('',(#46044),#46048); +#46044 = CIRCLE('',#46045,0.25); +#46045 = AXIS2_PLACEMENT_2D('',#46046,#46047); +#46046 = CARTESIAN_POINT('',(-2.594375541595,-0.67)); +#46047 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#46048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46049 = PCURVE('',#45515,#46050); +#46050 = DEFINITIONAL_REPRESENTATION('',(#46051),#46054); +#46051 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46052,#46053),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#43660 = CARTESIAN_POINT('',(3.926990816987,1.2)); -#43661 = CARTESIAN_POINT('',(4.712388980385,1.2)); -#43662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43663 = ORIENTED_EDGE('',*,*,#43664,.F.); -#43664 = EDGE_CURVE('',#43665,#43642,#43667,.T.); -#43665 = VERTEX_POINT('',#43666); -#43666 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-1.15)); -#43667 = SURFACE_CURVE('',#43668,(#43672,#43679),.PCURVE_S1.); -#43668 = LINE('',#43669,#43670); -#43669 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-1.15)); -#43670 = VECTOR('',#43671,1.); -#43671 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#43672 = PCURVE('',#41837,#43673); -#43673 = DEFINITIONAL_REPRESENTATION('',(#43674),#43678); -#43674 = LINE('',#43675,#43676); -#43675 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892)); -#43676 = VECTOR('',#43677,1.); -#43677 = DIRECTION('',(0.707106781187,-0.707106781187)); -#43678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43679 = PCURVE('',#43680,#43685); -#43680 = PLANE('',#43681); -#43681 = AXIS2_PLACEMENT_3D('',#43682,#43683,#43684); -#43682 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); -#43683 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#43684 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#43685 = DEFINITIONAL_REPRESENTATION('',(#43686),#43690); -#43686 = LINE('',#43687,#43688); -#43687 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43688 = VECTOR('',#43689,1.); -#43689 = DIRECTION('',(1.,0.E+000)); -#43690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43691 = ORIENTED_EDGE('',*,*,#43692,.F.); -#43692 = EDGE_CURVE('',#43693,#43665,#43695,.T.); -#43693 = VERTEX_POINT('',#43694); -#43694 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-1.15)); -#43695 = SURFACE_CURVE('',#43696,(#43701,#43708),.PCURVE_S1.); -#43696 = CIRCLE('',#43697,0.25); -#43697 = AXIS2_PLACEMENT_3D('',#43698,#43699,#43700); -#43698 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-1.15)); -#43699 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43700 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43701 = PCURVE('',#41837,#43702); -#43702 = DEFINITIONAL_REPRESENTATION('',(#43703),#43707); -#43703 = CIRCLE('',#43704,0.25); -#43704 = AXIS2_PLACEMENT_2D('',#43705,#43706); -#43705 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002)); -#43706 = DIRECTION('',(-1.,0.E+000)); -#43707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43708 = PCURVE('',#43709,#43714); -#43709 = CYLINDRICAL_SURFACE('',#43710,0.25); -#43710 = AXIS2_PLACEMENT_3D('',#43711,#43712,#43713); -#43711 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-2.35)); -#43712 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43713 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43714 = DEFINITIONAL_REPRESENTATION('',(#43715),#43718); -#43715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43716,#43717),.UNSPECIFIED., +#46052 = CARTESIAN_POINT('',(3.926990816987,1.2)); +#46053 = CARTESIAN_POINT('',(4.712388980385,1.2)); +#46054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46055 = ORIENTED_EDGE('',*,*,#46056,.F.); +#46056 = EDGE_CURVE('',#46057,#46034,#46059,.T.); +#46057 = VERTEX_POINT('',#46058); +#46058 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-1.15)); +#46059 = SURFACE_CURVE('',#46060,(#46064,#46071),.PCURVE_S1.); +#46060 = LINE('',#46061,#46062); +#46061 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-1.15)); +#46062 = VECTOR('',#46063,1.); +#46063 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#46064 = PCURVE('',#44229,#46065); +#46065 = DEFINITIONAL_REPRESENTATION('',(#46066),#46070); +#46066 = LINE('',#46067,#46068); +#46067 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892)); +#46068 = VECTOR('',#46069,1.); +#46069 = DIRECTION('',(0.707106781187,-0.707106781187)); +#46070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46071 = PCURVE('',#46072,#46077); +#46072 = PLANE('',#46073); +#46073 = AXIS2_PLACEMENT_3D('',#46074,#46075,#46076); +#46074 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); +#46075 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#46076 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#46077 = DEFINITIONAL_REPRESENTATION('',(#46078),#46082); +#46078 = LINE('',#46079,#46080); +#46079 = CARTESIAN_POINT('',(0.E+000,1.2)); +#46080 = VECTOR('',#46081,1.); +#46081 = DIRECTION('',(1.,0.E+000)); +#46082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46083 = ORIENTED_EDGE('',*,*,#46084,.F.); +#46084 = EDGE_CURVE('',#46085,#46057,#46087,.T.); +#46085 = VERTEX_POINT('',#46086); +#46086 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-1.15)); +#46087 = SURFACE_CURVE('',#46088,(#46093,#46100),.PCURVE_S1.); +#46088 = CIRCLE('',#46089,0.25); +#46089 = AXIS2_PLACEMENT_3D('',#46090,#46091,#46092); +#46090 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-1.15)); +#46091 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46092 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#46093 = PCURVE('',#44229,#46094); +#46094 = DEFINITIONAL_REPRESENTATION('',(#46095),#46099); +#46095 = CIRCLE('',#46096,0.25); +#46096 = AXIS2_PLACEMENT_2D('',#46097,#46098); +#46097 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002)); +#46098 = DIRECTION('',(-1.,0.E+000)); +#46099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46100 = PCURVE('',#46101,#46106); +#46101 = CYLINDRICAL_SURFACE('',#46102,0.25); +#46102 = AXIS2_PLACEMENT_3D('',#46103,#46104,#46105); +#46103 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-2.35)); +#46104 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46105 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46106 = DEFINITIONAL_REPRESENTATION('',(#46107),#46110); +#46107 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46108,#46109),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#43716 = CARTESIAN_POINT('',(3.14159265359,1.2)); -#43717 = CARTESIAN_POINT('',(3.926990816986,1.2)); -#43718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43719 = ORIENTED_EDGE('',*,*,#43720,.F.); -#43720 = EDGE_CURVE('',#43721,#43693,#43723,.T.); -#43721 = VERTEX_POINT('',#43722); -#43722 = CARTESIAN_POINT('',(-3.445,0.57,-1.15)); -#43723 = SURFACE_CURVE('',#43724,(#43728,#43735),.PCURVE_S1.); -#43724 = LINE('',#43725,#43726); -#43725 = CARTESIAN_POINT('',(-3.445,0.57,-1.15)); -#43726 = VECTOR('',#43727,1.); -#43727 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43728 = PCURVE('',#41837,#43729); -#43729 = DEFINITIONAL_REPRESENTATION('',(#43730),#43734); -#43730 = LINE('',#43731,#43732); -#43731 = CARTESIAN_POINT('',(-3.445,0.57)); -#43732 = VECTOR('',#43733,1.); -#43733 = DIRECTION('',(0.E+000,-1.)); -#43734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43735 = PCURVE('',#43736,#43741); -#43736 = PLANE('',#43737); -#43737 = AXIS2_PLACEMENT_3D('',#43738,#43739,#43740); -#43738 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); -#43739 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43740 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43741 = DEFINITIONAL_REPRESENTATION('',(#43742),#43746); -#43742 = LINE('',#43743,#43744); -#43743 = CARTESIAN_POINT('',(0.E+000,1.2)); -#43744 = VECTOR('',#43745,1.); -#43745 = DIRECTION('',(1.,0.E+000)); -#43746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43747 = ORIENTED_EDGE('',*,*,#43748,.F.); -#43748 = EDGE_CURVE('',#43749,#43721,#43751,.T.); -#43749 = VERTEX_POINT('',#43750); -#43750 = CARTESIAN_POINT('',(-3.095,0.92,-1.15)); -#43751 = SURFACE_CURVE('',#43752,(#43757,#43764),.PCURVE_S1.); -#43752 = CIRCLE('',#43753,0.35); -#43753 = AXIS2_PLACEMENT_3D('',#43754,#43755,#43756); -#43754 = CARTESIAN_POINT('',(-3.095,0.57,-1.15)); -#43755 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43756 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43757 = PCURVE('',#41837,#43758); -#43758 = DEFINITIONAL_REPRESENTATION('',(#43759),#43763); -#43759 = CIRCLE('',#43760,0.35); -#43760 = AXIS2_PLACEMENT_2D('',#43761,#43762); -#43761 = CARTESIAN_POINT('',(-3.095,0.57)); -#43762 = DIRECTION('',(0.E+000,1.)); -#43763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43764 = PCURVE('',#43765,#43770); -#43765 = CYLINDRICAL_SURFACE('',#43766,0.35); -#43766 = AXIS2_PLACEMENT_3D('',#43767,#43768,#43769); -#43767 = CARTESIAN_POINT('',(-3.095,0.57,-2.35)); -#43768 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43769 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43770 = DEFINITIONAL_REPRESENTATION('',(#43771),#43774); -#43771 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43772,#43773),.UNSPECIFIED., +#46108 = CARTESIAN_POINT('',(3.14159265359,1.2)); +#46109 = CARTESIAN_POINT('',(3.926990816986,1.2)); +#46110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46111 = ORIENTED_EDGE('',*,*,#46112,.F.); +#46112 = EDGE_CURVE('',#46113,#46085,#46115,.T.); +#46113 = VERTEX_POINT('',#46114); +#46114 = CARTESIAN_POINT('',(-3.445,0.57,-1.15)); +#46115 = SURFACE_CURVE('',#46116,(#46120,#46127),.PCURVE_S1.); +#46116 = LINE('',#46117,#46118); +#46117 = CARTESIAN_POINT('',(-3.445,0.57,-1.15)); +#46118 = VECTOR('',#46119,1.); +#46119 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46120 = PCURVE('',#44229,#46121); +#46121 = DEFINITIONAL_REPRESENTATION('',(#46122),#46126); +#46122 = LINE('',#46123,#46124); +#46123 = CARTESIAN_POINT('',(-3.445,0.57)); +#46124 = VECTOR('',#46125,1.); +#46125 = DIRECTION('',(0.E+000,-1.)); +#46126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46127 = PCURVE('',#46128,#46133); +#46128 = PLANE('',#46129); +#46129 = AXIS2_PLACEMENT_3D('',#46130,#46131,#46132); +#46130 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); +#46131 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#46132 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46133 = DEFINITIONAL_REPRESENTATION('',(#46134),#46138); +#46134 = LINE('',#46135,#46136); +#46135 = CARTESIAN_POINT('',(0.E+000,1.2)); +#46136 = VECTOR('',#46137,1.); +#46137 = DIRECTION('',(1.,0.E+000)); +#46138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46139 = ORIENTED_EDGE('',*,*,#46140,.F.); +#46140 = EDGE_CURVE('',#46141,#46113,#46143,.T.); +#46141 = VERTEX_POINT('',#46142); +#46142 = CARTESIAN_POINT('',(-3.095,0.92,-1.15)); +#46143 = SURFACE_CURVE('',#46144,(#46149,#46156),.PCURVE_S1.); +#46144 = CIRCLE('',#46145,0.35); +#46145 = AXIS2_PLACEMENT_3D('',#46146,#46147,#46148); +#46146 = CARTESIAN_POINT('',(-3.095,0.57,-1.15)); +#46147 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46148 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46149 = PCURVE('',#44229,#46150); +#46150 = DEFINITIONAL_REPRESENTATION('',(#46151),#46155); +#46151 = CIRCLE('',#46152,0.35); +#46152 = AXIS2_PLACEMENT_2D('',#46153,#46154); +#46153 = CARTESIAN_POINT('',(-3.095,0.57)); +#46154 = DIRECTION('',(0.E+000,1.)); +#46155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46156 = PCURVE('',#46157,#46162); +#46157 = CYLINDRICAL_SURFACE('',#46158,0.35); +#46158 = AXIS2_PLACEMENT_3D('',#46159,#46160,#46161); +#46159 = CARTESIAN_POINT('',(-3.095,0.57,-2.35)); +#46160 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46161 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46162 = DEFINITIONAL_REPRESENTATION('',(#46163),#46166); +#46163 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46164,#46165),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43772 = CARTESIAN_POINT('',(1.570796326795,1.2)); -#43773 = CARTESIAN_POINT('',(3.14159265359,1.2)); -#43774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43775 = ORIENTED_EDGE('',*,*,#43776,.F.); -#43776 = EDGE_CURVE('',#43777,#43749,#43779,.T.); -#43777 = VERTEX_POINT('',#43778); -#43778 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); -#43779 = SURFACE_CURVE('',#43780,(#43784,#43791),.PCURVE_S1.); -#43780 = LINE('',#43781,#43782); -#43781 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); -#43782 = VECTOR('',#43783,1.); -#43783 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43784 = PCURVE('',#41837,#43785); -#43785 = DEFINITIONAL_REPRESENTATION('',(#43786),#43790); -#43786 = LINE('',#43787,#43788); -#43787 = CARTESIAN_POINT('',(-0.51,0.92)); -#43788 = VECTOR('',#43789,1.); -#43789 = DIRECTION('',(-1.,0.E+000)); -#43790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43791 = PCURVE('',#43400,#43792); -#43792 = DEFINITIONAL_REPRESENTATION('',(#43793),#43797); -#43793 = LINE('',#43794,#43795); -#43794 = CARTESIAN_POINT('',(3.605,1.2)); -#43795 = VECTOR('',#43796,1.); -#43796 = DIRECTION('',(1.,0.E+000)); -#43797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43798 = ORIENTED_EDGE('',*,*,#43799,.F.); -#43799 = EDGE_CURVE('',#43800,#43777,#43802,.T.); -#43800 = VERTEX_POINT('',#43801); -#43801 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); -#43802 = SURFACE_CURVE('',#43803,(#43807,#43814),.PCURVE_S1.); -#43803 = LINE('',#43804,#43805); -#43804 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); -#43805 = VECTOR('',#43806,1.); -#43806 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43807 = PCURVE('',#41837,#43808); -#43808 = DEFINITIONAL_REPRESENTATION('',(#43809),#43813); -#43809 = LINE('',#43810,#43811); -#43810 = CARTESIAN_POINT('',(-0.51,0.645)); -#43811 = VECTOR('',#43812,1.); -#43812 = DIRECTION('',(0.E+000,1.)); -#43813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43814 = PCURVE('',#43815,#43820); -#43815 = PLANE('',#43816); -#43816 = AXIS2_PLACEMENT_3D('',#43817,#43818,#43819); -#43817 = CARTESIAN_POINT('',(-0.46,0.7825,-1.2)); -#43818 = DIRECTION('',(0.707106781187,0.E+000,0.707106781187)); -#43819 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43820 = DEFINITIONAL_REPRESENTATION('',(#43821),#43825); -#43821 = LINE('',#43822,#43823); -#43822 = CARTESIAN_POINT('',(0.1375,-7.071067811865E-002)); -#43823 = VECTOR('',#43824,1.); -#43824 = DIRECTION('',(-1.,0.E+000)); -#43825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43826 = ORIENTED_EDGE('',*,*,#43827,.T.); -#43827 = EDGE_CURVE('',#43800,#43828,#43830,.T.); -#43828 = VERTEX_POINT('',#43829); -#43829 = CARTESIAN_POINT('',(-1.55,0.645,-1.15)); -#43830 = SURFACE_CURVE('',#43831,(#43835,#43842),.PCURVE_S1.); -#43831 = LINE('',#43832,#43833); -#43832 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); -#43833 = VECTOR('',#43834,1.); -#43834 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43835 = PCURVE('',#41837,#43836); -#43836 = DEFINITIONAL_REPRESENTATION('',(#43837),#43841); -#43837 = LINE('',#43838,#43839); -#43838 = CARTESIAN_POINT('',(-0.51,0.645)); -#43839 = VECTOR('',#43840,1.); -#43840 = DIRECTION('',(-1.,0.E+000)); -#43841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43842 = PCURVE('',#43344,#43843); -#43843 = DEFINITIONAL_REPRESENTATION('',(#43844),#43848); -#43844 = LINE('',#43845,#43846); -#43845 = CARTESIAN_POINT('',(2.06,0.E+000)); -#43846 = VECTOR('',#43847,1.); -#43847 = DIRECTION('',(1.,0.E+000)); -#43848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43849 = ORIENTED_EDGE('',*,*,#43850,.T.); -#43850 = EDGE_CURVE('',#43828,#43851,#43853,.T.); -#43851 = VERTEX_POINT('',#43852); -#43852 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); -#43853 = SURFACE_CURVE('',#43854,(#43859,#43866),.PCURVE_S1.); -#43854 = CIRCLE('',#43855,0.2); -#43855 = AXIS2_PLACEMENT_3D('',#43856,#43857,#43858); -#43856 = CARTESIAN_POINT('',(-1.55,0.445,-1.15)); -#43857 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43858 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43859 = PCURVE('',#41837,#43860); -#43860 = DEFINITIONAL_REPRESENTATION('',(#43861),#43865); -#43861 = CIRCLE('',#43862,0.2); -#43862 = AXIS2_PLACEMENT_2D('',#43863,#43864); -#43863 = CARTESIAN_POINT('',(-1.55,0.445)); -#43864 = DIRECTION('',(0.E+000,1.)); -#43865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43866 = PCURVE('',#43867,#43872); -#43867 = CYLINDRICAL_SURFACE('',#43868,0.2); -#43868 = AXIS2_PLACEMENT_3D('',#43869,#43870,#43871); -#43869 = CARTESIAN_POINT('',(-1.55,0.445,-1.15)); -#43870 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43871 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43872 = DEFINITIONAL_REPRESENTATION('',(#43873),#43876); -#43873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43874,#43875),.UNSPECIFIED., +#46164 = CARTESIAN_POINT('',(1.570796326795,1.2)); +#46165 = CARTESIAN_POINT('',(3.14159265359,1.2)); +#46166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46167 = ORIENTED_EDGE('',*,*,#46168,.F.); +#46168 = EDGE_CURVE('',#46169,#46141,#46171,.T.); +#46169 = VERTEX_POINT('',#46170); +#46170 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); +#46171 = SURFACE_CURVE('',#46172,(#46176,#46183),.PCURVE_S1.); +#46172 = LINE('',#46173,#46174); +#46173 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); +#46174 = VECTOR('',#46175,1.); +#46175 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#46176 = PCURVE('',#44229,#46177); +#46177 = DEFINITIONAL_REPRESENTATION('',(#46178),#46182); +#46178 = LINE('',#46179,#46180); +#46179 = CARTESIAN_POINT('',(-0.51,0.92)); +#46180 = VECTOR('',#46181,1.); +#46181 = DIRECTION('',(-1.,0.E+000)); +#46182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46183 = PCURVE('',#45792,#46184); +#46184 = DEFINITIONAL_REPRESENTATION('',(#46185),#46189); +#46185 = LINE('',#46186,#46187); +#46186 = CARTESIAN_POINT('',(3.605,1.2)); +#46187 = VECTOR('',#46188,1.); +#46188 = DIRECTION('',(1.,0.E+000)); +#46189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46190 = ORIENTED_EDGE('',*,*,#46191,.F.); +#46191 = EDGE_CURVE('',#46192,#46169,#46194,.T.); +#46192 = VERTEX_POINT('',#46193); +#46193 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); +#46194 = SURFACE_CURVE('',#46195,(#46199,#46206),.PCURVE_S1.); +#46195 = LINE('',#46196,#46197); +#46196 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); +#46197 = VECTOR('',#46198,1.); +#46198 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46199 = PCURVE('',#44229,#46200); +#46200 = DEFINITIONAL_REPRESENTATION('',(#46201),#46205); +#46201 = LINE('',#46202,#46203); +#46202 = CARTESIAN_POINT('',(-0.51,0.645)); +#46203 = VECTOR('',#46204,1.); +#46204 = DIRECTION('',(0.E+000,1.)); +#46205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46206 = PCURVE('',#46207,#46212); +#46207 = PLANE('',#46208); +#46208 = AXIS2_PLACEMENT_3D('',#46209,#46210,#46211); +#46209 = CARTESIAN_POINT('',(-0.46,0.7825,-1.2)); +#46210 = DIRECTION('',(0.707106781187,0.E+000,0.707106781187)); +#46211 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46212 = DEFINITIONAL_REPRESENTATION('',(#46213),#46217); +#46213 = LINE('',#46214,#46215); +#46214 = CARTESIAN_POINT('',(0.1375,-7.071067811865E-002)); +#46215 = VECTOR('',#46216,1.); +#46216 = DIRECTION('',(-1.,0.E+000)); +#46217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46218 = ORIENTED_EDGE('',*,*,#46219,.T.); +#46219 = EDGE_CURVE('',#46192,#46220,#46222,.T.); +#46220 = VERTEX_POINT('',#46221); +#46221 = CARTESIAN_POINT('',(-1.55,0.645,-1.15)); +#46222 = SURFACE_CURVE('',#46223,(#46227,#46234),.PCURVE_S1.); +#46223 = LINE('',#46224,#46225); +#46224 = CARTESIAN_POINT('',(-0.51,0.645,-1.15)); +#46225 = VECTOR('',#46226,1.); +#46226 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#46227 = PCURVE('',#44229,#46228); +#46228 = DEFINITIONAL_REPRESENTATION('',(#46229),#46233); +#46229 = LINE('',#46230,#46231); +#46230 = CARTESIAN_POINT('',(-0.51,0.645)); +#46231 = VECTOR('',#46232,1.); +#46232 = DIRECTION('',(-1.,0.E+000)); +#46233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46234 = PCURVE('',#45736,#46235); +#46235 = DEFINITIONAL_REPRESENTATION('',(#46236),#46240); +#46236 = LINE('',#46237,#46238); +#46237 = CARTESIAN_POINT('',(2.06,0.E+000)); +#46238 = VECTOR('',#46239,1.); +#46239 = DIRECTION('',(1.,0.E+000)); +#46240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46241 = ORIENTED_EDGE('',*,*,#46242,.T.); +#46242 = EDGE_CURVE('',#46220,#46243,#46245,.T.); +#46243 = VERTEX_POINT('',#46244); +#46244 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); +#46245 = SURFACE_CURVE('',#46246,(#46251,#46258),.PCURVE_S1.); +#46246 = CIRCLE('',#46247,0.2); +#46247 = AXIS2_PLACEMENT_3D('',#46248,#46249,#46250); +#46248 = CARTESIAN_POINT('',(-1.55,0.445,-1.15)); +#46249 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46250 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46251 = PCURVE('',#44229,#46252); +#46252 = DEFINITIONAL_REPRESENTATION('',(#46253),#46257); +#46253 = CIRCLE('',#46254,0.2); +#46254 = AXIS2_PLACEMENT_2D('',#46255,#46256); +#46255 = CARTESIAN_POINT('',(-1.55,0.445)); +#46256 = DIRECTION('',(0.E+000,1.)); +#46257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46258 = PCURVE('',#46259,#46264); +#46259 = CYLINDRICAL_SURFACE('',#46260,0.2); +#46260 = AXIS2_PLACEMENT_3D('',#46261,#46262,#46263); +#46261 = CARTESIAN_POINT('',(-1.55,0.445,-1.15)); +#46262 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46263 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46264 = DEFINITIONAL_REPRESENTATION('',(#46265),#46268); +#46265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46266,#46267),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43874 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#43875 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#43876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43877 = ORIENTED_EDGE('',*,*,#43878,.T.); -#43878 = EDGE_CURVE('',#43851,#43879,#43881,.T.); -#43879 = VERTEX_POINT('',#43880); -#43880 = CARTESIAN_POINT('',(-1.75,0.245,-1.15)); -#43881 = SURFACE_CURVE('',#43882,(#43886,#43893),.PCURVE_S1.); -#43882 = LINE('',#43883,#43884); -#43883 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); -#43884 = VECTOR('',#43885,1.); -#43885 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43886 = PCURVE('',#41837,#43887); -#43887 = DEFINITIONAL_REPRESENTATION('',(#43888),#43892); -#43888 = LINE('',#43889,#43890); -#43889 = CARTESIAN_POINT('',(-1.75,0.445)); -#43890 = VECTOR('',#43891,1.); -#43891 = DIRECTION('',(0.E+000,-1.)); -#43892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43893 = PCURVE('',#43894,#43899); -#43894 = PLANE('',#43895); -#43895 = AXIS2_PLACEMENT_3D('',#43896,#43897,#43898); -#43896 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); -#43897 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#43898 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43899 = DEFINITIONAL_REPRESENTATION('',(#43900),#43904); -#43900 = LINE('',#43901,#43902); -#43901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43902 = VECTOR('',#43903,1.); -#43903 = DIRECTION('',(1.,0.E+000)); -#43904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43905 = ORIENTED_EDGE('',*,*,#43906,.T.); -#43906 = EDGE_CURVE('',#43879,#43907,#43909,.T.); -#43907 = VERTEX_POINT('',#43908); -#43908 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#43909 = SURFACE_CURVE('',#43910,(#43915,#43922),.PCURVE_S1.); -#43910 = CIRCLE('',#43911,0.2); -#43911 = AXIS2_PLACEMENT_3D('',#43912,#43913,#43914); -#43912 = CARTESIAN_POINT('',(-1.55,0.245,-1.15)); -#43913 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43914 = DIRECTION('',(-1.,-1.679212324746E-014,0.E+000)); -#43915 = PCURVE('',#41837,#43916); -#43916 = DEFINITIONAL_REPRESENTATION('',(#43917),#43921); -#43917 = CIRCLE('',#43918,0.2); -#43918 = AXIS2_PLACEMENT_2D('',#43919,#43920); -#43919 = CARTESIAN_POINT('',(-1.55,0.245)); -#43920 = DIRECTION('',(-1.,-1.679212324746E-014)); -#43921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43922 = PCURVE('',#43923,#43928); -#43923 = CYLINDRICAL_SURFACE('',#43924,0.2); -#43924 = AXIS2_PLACEMENT_3D('',#43925,#43926,#43927); -#43925 = CARTESIAN_POINT('',(-1.55,0.245,-1.15)); -#43926 = DIRECTION('',(0.E+000,0.E+000,1.)); -#43927 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43928 = DEFINITIONAL_REPRESENTATION('',(#43929),#43932); -#43929 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#43930,#43931),.UNSPECIFIED., +#46266 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#46267 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#46268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46269 = ORIENTED_EDGE('',*,*,#46270,.T.); +#46270 = EDGE_CURVE('',#46243,#46271,#46273,.T.); +#46271 = VERTEX_POINT('',#46272); +#46272 = CARTESIAN_POINT('',(-1.75,0.245,-1.15)); +#46273 = SURFACE_CURVE('',#46274,(#46278,#46285),.PCURVE_S1.); +#46274 = LINE('',#46275,#46276); +#46275 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); +#46276 = VECTOR('',#46277,1.); +#46277 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46278 = PCURVE('',#44229,#46279); +#46279 = DEFINITIONAL_REPRESENTATION('',(#46280),#46284); +#46280 = LINE('',#46281,#46282); +#46281 = CARTESIAN_POINT('',(-1.75,0.445)); +#46282 = VECTOR('',#46283,1.); +#46283 = DIRECTION('',(0.E+000,-1.)); +#46284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46285 = PCURVE('',#46286,#46291); +#46286 = PLANE('',#46287); +#46287 = AXIS2_PLACEMENT_3D('',#46288,#46289,#46290); +#46288 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); +#46289 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#46290 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46291 = DEFINITIONAL_REPRESENTATION('',(#46292),#46296); +#46292 = LINE('',#46293,#46294); +#46293 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#46294 = VECTOR('',#46295,1.); +#46295 = DIRECTION('',(1.,0.E+000)); +#46296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46297 = ORIENTED_EDGE('',*,*,#46298,.T.); +#46298 = EDGE_CURVE('',#46271,#46299,#46301,.T.); +#46299 = VERTEX_POINT('',#46300); +#46300 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46301 = SURFACE_CURVE('',#46302,(#46307,#46314),.PCURVE_S1.); +#46302 = CIRCLE('',#46303,0.2); +#46303 = AXIS2_PLACEMENT_3D('',#46304,#46305,#46306); +#46304 = CARTESIAN_POINT('',(-1.55,0.245,-1.15)); +#46305 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46306 = DIRECTION('',(-1.,-1.679212324746E-014,0.E+000)); +#46307 = PCURVE('',#44229,#46308); +#46308 = DEFINITIONAL_REPRESENTATION('',(#46309),#46313); +#46309 = CIRCLE('',#46310,0.2); +#46310 = AXIS2_PLACEMENT_2D('',#46311,#46312); +#46311 = CARTESIAN_POINT('',(-1.55,0.245)); +#46312 = DIRECTION('',(-1.,-1.679212324746E-014)); +#46313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46314 = PCURVE('',#46315,#46320); +#46315 = CYLINDRICAL_SURFACE('',#46316,0.2); +#46316 = AXIS2_PLACEMENT_3D('',#46317,#46318,#46319); +#46317 = CARTESIAN_POINT('',(-1.55,0.245,-1.15)); +#46318 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46319 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46320 = DEFINITIONAL_REPRESENTATION('',(#46321),#46324); +#46321 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46322,#46323),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#43930 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#43931 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#43932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43933 = ORIENTED_EDGE('',*,*,#43934,.T.); -#43934 = EDGE_CURVE('',#43907,#43935,#43937,.T.); -#43935 = VERTEX_POINT('',#43936); -#43936 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); -#43937 = SURFACE_CURVE('',#43938,(#43942,#43949),.PCURVE_S1.); -#43938 = LINE('',#43939,#43940); -#43939 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#43940 = VECTOR('',#43941,1.); -#43941 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43942 = PCURVE('',#41837,#43943); -#43943 = DEFINITIONAL_REPRESENTATION('',(#43944),#43948); -#43944 = LINE('',#43945,#43946); -#43945 = CARTESIAN_POINT('',(-1.55,4.5E-002)); -#43946 = VECTOR('',#43947,1.); -#43947 = DIRECTION('',(1.,0.E+000)); -#43948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43949 = PCURVE('',#43950,#43955); -#43950 = PLANE('',#43951); -#43951 = AXIS2_PLACEMENT_3D('',#43952,#43953,#43954); -#43952 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#43953 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#43954 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43955 = DEFINITIONAL_REPRESENTATION('',(#43956),#43960); -#43956 = LINE('',#43957,#43958); -#43957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#43958 = VECTOR('',#43959,1.); -#43959 = DIRECTION('',(1.,0.E+000)); -#43960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43961 = ORIENTED_EDGE('',*,*,#43962,.T.); -#43962 = EDGE_CURVE('',#43935,#43963,#43965,.T.); -#43963 = VERTEX_POINT('',#43964); -#43964 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); -#43965 = SURFACE_CURVE('',#43966,(#43970,#43977),.PCURVE_S1.); -#43966 = LINE('',#43967,#43968); -#43967 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); -#43968 = VECTOR('',#43969,1.); -#43969 = DIRECTION('',(0.E+000,1.,0.E+000)); -#43970 = PCURVE('',#41837,#43971); -#43971 = DEFINITIONAL_REPRESENTATION('',(#43972),#43976); -#43972 = LINE('',#43973,#43974); -#43973 = CARTESIAN_POINT('',(-1.485,4.5E-002)); -#43974 = VECTOR('',#43975,1.); -#43975 = DIRECTION('',(0.E+000,1.)); -#43976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43977 = PCURVE('',#43978,#43983); -#43978 = PLANE('',#43979); -#43979 = AXIS2_PLACEMENT_3D('',#43980,#43981,#43982); -#43980 = CARTESIAN_POINT('',(-1.485,0.E+000,0.E+000)); -#43981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43982 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#43983 = DEFINITIONAL_REPRESENTATION('',(#43984),#43988); -#43984 = LINE('',#43985,#43986); -#43985 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#43986 = VECTOR('',#43987,1.); -#43987 = DIRECTION('',(0.E+000,1.)); -#43988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#43989 = ORIENTED_EDGE('',*,*,#43990,.T.); -#43990 = EDGE_CURVE('',#43963,#43991,#43993,.T.); -#43991 = VERTEX_POINT('',#43992); -#43992 = CARTESIAN_POINT('',(-1.115,0.165,-1.15)); -#43993 = SURFACE_CURVE('',#43994,(#43998,#44005),.PCURVE_S1.); -#43994 = LINE('',#43995,#43996); -#43995 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); -#43996 = VECTOR('',#43997,1.); -#43997 = DIRECTION('',(1.,0.E+000,0.E+000)); -#43998 = PCURVE('',#41837,#43999); -#43999 = DEFINITIONAL_REPRESENTATION('',(#44000),#44004); -#44000 = LINE('',#44001,#44002); -#44001 = CARTESIAN_POINT('',(-1.485,0.165)); -#44002 = VECTOR('',#44003,1.); -#44003 = DIRECTION('',(1.,0.E+000)); -#44004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44005 = PCURVE('',#44006,#44011); -#44006 = PLANE('',#44007); -#44007 = AXIS2_PLACEMENT_3D('',#44008,#44009,#44010); -#44008 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); -#44009 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44010 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44011 = DEFINITIONAL_REPRESENTATION('',(#44012),#44016); -#44012 = LINE('',#44013,#44014); -#44013 = CARTESIAN_POINT('',(2.2,0.E+000)); -#44014 = VECTOR('',#44015,1.); -#44015 = DIRECTION('',(0.E+000,1.)); -#44016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44017 = ORIENTED_EDGE('',*,*,#44018,.F.); -#44018 = EDGE_CURVE('',#44019,#43991,#44021,.T.); -#44019 = VERTEX_POINT('',#44020); -#44020 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); -#44021 = SURFACE_CURVE('',#44022,(#44026,#44033),.PCURVE_S1.); -#44022 = LINE('',#44023,#44024); -#44023 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); -#44024 = VECTOR('',#44025,1.); -#44025 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44026 = PCURVE('',#41837,#44027); -#44027 = DEFINITIONAL_REPRESENTATION('',(#44028),#44032); -#44028 = LINE('',#44029,#44030); -#44029 = CARTESIAN_POINT('',(-1.115,4.5E-002)); -#44030 = VECTOR('',#44031,1.); -#44031 = DIRECTION('',(0.E+000,1.)); -#44032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44033 = PCURVE('',#44034,#44039); -#44034 = PLANE('',#44035); -#44035 = AXIS2_PLACEMENT_3D('',#44036,#44037,#44038); -#44036 = CARTESIAN_POINT('',(-1.115,0.E+000,0.E+000)); -#44037 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44038 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44039 = DEFINITIONAL_REPRESENTATION('',(#44040),#44044); -#44040 = LINE('',#44041,#44042); -#44041 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44042 = VECTOR('',#44043,1.); -#44043 = DIRECTION('',(0.E+000,1.)); -#44044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44045 = ORIENTED_EDGE('',*,*,#44046,.T.); -#44046 = EDGE_CURVE('',#44019,#44047,#44049,.T.); -#44047 = VERTEX_POINT('',#44048); -#44048 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); -#44049 = SURFACE_CURVE('',#44050,(#44054,#44061),.PCURVE_S1.); -#44050 = LINE('',#44051,#44052); -#44051 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); -#44052 = VECTOR('',#44053,1.); -#44053 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44054 = PCURVE('',#41837,#44055); -#44055 = DEFINITIONAL_REPRESENTATION('',(#44056),#44060); -#44056 = LINE('',#44057,#44058); -#44057 = CARTESIAN_POINT('',(-1.115,4.5E-002)); -#44058 = VECTOR('',#44059,1.); -#44059 = DIRECTION('',(1.,0.E+000)); -#44060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44061 = PCURVE('',#44062,#44067); -#44062 = PLANE('',#44063); -#44063 = AXIS2_PLACEMENT_3D('',#44064,#44065,#44066); -#44064 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#44065 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44066 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44067 = DEFINITIONAL_REPRESENTATION('',(#44068),#44072); -#44068 = LINE('',#44069,#44070); -#44069 = CARTESIAN_POINT('',(0.435,0.E+000)); -#44070 = VECTOR('',#44071,1.); -#44071 = DIRECTION('',(1.,0.E+000)); -#44072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44073 = ORIENTED_EDGE('',*,*,#44074,.T.); -#44074 = EDGE_CURVE('',#44047,#44075,#44077,.T.); -#44075 = VERTEX_POINT('',#44076); -#44076 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); -#44077 = SURFACE_CURVE('',#44078,(#44082,#44089),.PCURVE_S1.); -#44078 = LINE('',#44079,#44080); -#44079 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); -#44080 = VECTOR('',#44081,1.); -#44081 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44082 = PCURVE('',#41837,#44083); -#44083 = DEFINITIONAL_REPRESENTATION('',(#44084),#44088); -#44084 = LINE('',#44085,#44086); -#44085 = CARTESIAN_POINT('',(-0.835,4.5E-002)); -#44086 = VECTOR('',#44087,1.); -#44087 = DIRECTION('',(0.E+000,1.)); -#44088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44089 = PCURVE('',#44090,#44095); -#44090 = PLANE('',#44091); -#44091 = AXIS2_PLACEMENT_3D('',#44092,#44093,#44094); -#44092 = CARTESIAN_POINT('',(-0.835,0.E+000,0.E+000)); -#44093 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44094 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44095 = DEFINITIONAL_REPRESENTATION('',(#44096),#44100); -#44096 = LINE('',#44097,#44098); -#44097 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44098 = VECTOR('',#44099,1.); -#44099 = DIRECTION('',(0.E+000,1.)); -#44100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44101 = ORIENTED_EDGE('',*,*,#44102,.T.); -#44102 = EDGE_CURVE('',#44075,#44103,#44105,.T.); -#44103 = VERTEX_POINT('',#44104); -#44104 = CARTESIAN_POINT('',(-0.465,0.165,-1.15)); -#44105 = SURFACE_CURVE('',#44106,(#44110,#44117),.PCURVE_S1.); -#44106 = LINE('',#44107,#44108); -#44107 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); -#44108 = VECTOR('',#44109,1.); -#44109 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44110 = PCURVE('',#41837,#44111); -#44111 = DEFINITIONAL_REPRESENTATION('',(#44112),#44116); -#44112 = LINE('',#44113,#44114); -#44113 = CARTESIAN_POINT('',(-0.835,0.165)); -#44114 = VECTOR('',#44115,1.); -#44115 = DIRECTION('',(1.,0.E+000)); -#44116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44117 = PCURVE('',#44118,#44123); -#44118 = PLANE('',#44119); -#44119 = AXIS2_PLACEMENT_3D('',#44120,#44121,#44122); -#44120 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); -#44121 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44122 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44123 = DEFINITIONAL_REPRESENTATION('',(#44124),#44128); -#44124 = LINE('',#44125,#44126); -#44125 = CARTESIAN_POINT('',(2.2,0.E+000)); -#44126 = VECTOR('',#44127,1.); -#44127 = DIRECTION('',(0.E+000,1.)); -#44128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44129 = ORIENTED_EDGE('',*,*,#44130,.F.); -#44130 = EDGE_CURVE('',#44131,#44103,#44133,.T.); -#44131 = VERTEX_POINT('',#44132); -#44132 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); -#44133 = SURFACE_CURVE('',#44134,(#44138,#44145),.PCURVE_S1.); -#44134 = LINE('',#44135,#44136); -#44135 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); -#44136 = VECTOR('',#44137,1.); -#44137 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44138 = PCURVE('',#41837,#44139); -#44139 = DEFINITIONAL_REPRESENTATION('',(#44140),#44144); -#44140 = LINE('',#44141,#44142); -#44141 = CARTESIAN_POINT('',(-0.465,4.5E-002)); -#44142 = VECTOR('',#44143,1.); -#44143 = DIRECTION('',(0.E+000,1.)); -#44144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44145 = PCURVE('',#44146,#44151); -#44146 = PLANE('',#44147); -#44147 = AXIS2_PLACEMENT_3D('',#44148,#44149,#44150); -#44148 = CARTESIAN_POINT('',(-0.465,0.E+000,0.E+000)); -#44149 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44150 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44151 = DEFINITIONAL_REPRESENTATION('',(#44152),#44156); -#44152 = LINE('',#44153,#44154); -#44153 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44154 = VECTOR('',#44155,1.); -#44155 = DIRECTION('',(0.E+000,1.)); -#44156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44157 = ORIENTED_EDGE('',*,*,#44158,.T.); -#44158 = EDGE_CURVE('',#44131,#44159,#44161,.T.); -#44159 = VERTEX_POINT('',#44160); -#44160 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); -#44161 = SURFACE_CURVE('',#44162,(#44166,#44173),.PCURVE_S1.); -#44162 = LINE('',#44163,#44164); -#44163 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); -#44164 = VECTOR('',#44165,1.); -#44165 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44166 = PCURVE('',#41837,#44167); -#44167 = DEFINITIONAL_REPRESENTATION('',(#44168),#44172); -#44168 = LINE('',#44169,#44170); -#44169 = CARTESIAN_POINT('',(-0.465,4.5E-002)); -#44170 = VECTOR('',#44171,1.); -#44171 = DIRECTION('',(1.,0.E+000)); -#44172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44173 = PCURVE('',#44174,#44179); -#44174 = PLANE('',#44175); -#44175 = AXIS2_PLACEMENT_3D('',#44176,#44177,#44178); -#44176 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#44177 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44178 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44179 = DEFINITIONAL_REPRESENTATION('',(#44180),#44184); -#44180 = LINE('',#44181,#44182); -#44181 = CARTESIAN_POINT('',(1.085,0.E+000)); -#44182 = VECTOR('',#44183,1.); -#44183 = DIRECTION('',(1.,0.E+000)); -#44184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44185 = ORIENTED_EDGE('',*,*,#44186,.T.); -#44186 = EDGE_CURVE('',#44159,#44187,#44189,.T.); -#44187 = VERTEX_POINT('',#44188); -#44188 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); -#44189 = SURFACE_CURVE('',#44190,(#44194,#44201),.PCURVE_S1.); -#44190 = LINE('',#44191,#44192); -#44191 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); -#44192 = VECTOR('',#44193,1.); -#44193 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44194 = PCURVE('',#41837,#44195); -#44195 = DEFINITIONAL_REPRESENTATION('',(#44196),#44200); -#44196 = LINE('',#44197,#44198); -#44197 = CARTESIAN_POINT('',(-0.185,4.5E-002)); -#44198 = VECTOR('',#44199,1.); -#44199 = DIRECTION('',(0.E+000,1.)); -#44200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44201 = PCURVE('',#44202,#44207); -#44202 = PLANE('',#44203); -#44203 = AXIS2_PLACEMENT_3D('',#44204,#44205,#44206); -#44204 = CARTESIAN_POINT('',(-0.185,0.E+000,0.E+000)); -#44205 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44206 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44207 = DEFINITIONAL_REPRESENTATION('',(#44208),#44212); -#44208 = LINE('',#44209,#44210); -#44209 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44210 = VECTOR('',#44211,1.); -#44211 = DIRECTION('',(0.E+000,1.)); -#44212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44213 = ORIENTED_EDGE('',*,*,#44214,.T.); -#44214 = EDGE_CURVE('',#44187,#44215,#44217,.T.); -#44215 = VERTEX_POINT('',#44216); -#44216 = CARTESIAN_POINT('',(0.185,0.165,-1.15)); -#44217 = SURFACE_CURVE('',#44218,(#44222,#44229),.PCURVE_S1.); -#44218 = LINE('',#44219,#44220); -#44219 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); -#44220 = VECTOR('',#44221,1.); -#44221 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44222 = PCURVE('',#41837,#44223); -#44223 = DEFINITIONAL_REPRESENTATION('',(#44224),#44228); -#44224 = LINE('',#44225,#44226); -#44225 = CARTESIAN_POINT('',(-0.185,0.165)); -#44226 = VECTOR('',#44227,1.); -#44227 = DIRECTION('',(1.,0.E+000)); -#44228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44229 = PCURVE('',#44230,#44235); -#44230 = PLANE('',#44231); -#44231 = AXIS2_PLACEMENT_3D('',#44232,#44233,#44234); -#44232 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); -#44233 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44234 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44235 = DEFINITIONAL_REPRESENTATION('',(#44236),#44240); -#44236 = LINE('',#44237,#44238); -#44237 = CARTESIAN_POINT('',(2.2,0.E+000)); -#44238 = VECTOR('',#44239,1.); -#44239 = DIRECTION('',(0.E+000,1.)); -#44240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44241 = ORIENTED_EDGE('',*,*,#44242,.F.); -#44242 = EDGE_CURVE('',#44243,#44215,#44245,.T.); -#44243 = VERTEX_POINT('',#44244); -#44244 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); -#44245 = SURFACE_CURVE('',#44246,(#44250,#44257),.PCURVE_S1.); -#44246 = LINE('',#44247,#44248); -#44247 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); -#44248 = VECTOR('',#44249,1.); -#44249 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44250 = PCURVE('',#41837,#44251); -#44251 = DEFINITIONAL_REPRESENTATION('',(#44252),#44256); -#44252 = LINE('',#44253,#44254); -#44253 = CARTESIAN_POINT('',(0.185,4.5E-002)); -#44254 = VECTOR('',#44255,1.); -#44255 = DIRECTION('',(0.E+000,1.)); -#44256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44257 = PCURVE('',#44258,#44263); -#44258 = PLANE('',#44259); -#44259 = AXIS2_PLACEMENT_3D('',#44260,#44261,#44262); -#44260 = CARTESIAN_POINT('',(0.185,0.E+000,0.E+000)); -#44261 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44262 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44263 = DEFINITIONAL_REPRESENTATION('',(#44264),#44268); -#44264 = LINE('',#44265,#44266); -#44265 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44266 = VECTOR('',#44267,1.); -#44267 = DIRECTION('',(0.E+000,1.)); -#44268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44269 = ORIENTED_EDGE('',*,*,#44270,.T.); -#44270 = EDGE_CURVE('',#44243,#44271,#44273,.T.); -#44271 = VERTEX_POINT('',#44272); -#44272 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); -#44273 = SURFACE_CURVE('',#44274,(#44278,#44285),.PCURVE_S1.); -#44274 = LINE('',#44275,#44276); -#44275 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); -#44276 = VECTOR('',#44277,1.); -#44277 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44278 = PCURVE('',#41837,#44279); -#44279 = DEFINITIONAL_REPRESENTATION('',(#44280),#44284); -#44280 = LINE('',#44281,#44282); -#44281 = CARTESIAN_POINT('',(0.185,4.5E-002)); -#44282 = VECTOR('',#44283,1.); -#44283 = DIRECTION('',(1.,0.E+000)); -#44284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44285 = PCURVE('',#44286,#44291); -#44286 = PLANE('',#44287); -#44287 = AXIS2_PLACEMENT_3D('',#44288,#44289,#44290); -#44288 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#44289 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44290 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44291 = DEFINITIONAL_REPRESENTATION('',(#44292),#44296); -#44292 = LINE('',#44293,#44294); -#44293 = CARTESIAN_POINT('',(1.735,0.E+000)); -#44294 = VECTOR('',#44295,1.); -#44295 = DIRECTION('',(1.,0.E+000)); -#44296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44297 = ORIENTED_EDGE('',*,*,#44298,.T.); -#44298 = EDGE_CURVE('',#44271,#44299,#44301,.T.); -#44299 = VERTEX_POINT('',#44300); -#44300 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); -#44301 = SURFACE_CURVE('',#44302,(#44306,#44313),.PCURVE_S1.); -#44302 = LINE('',#44303,#44304); -#44303 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); -#44304 = VECTOR('',#44305,1.); -#44305 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44306 = PCURVE('',#41837,#44307); -#44307 = DEFINITIONAL_REPRESENTATION('',(#44308),#44312); -#44308 = LINE('',#44309,#44310); -#44309 = CARTESIAN_POINT('',(0.465,4.5E-002)); -#44310 = VECTOR('',#44311,1.); -#44311 = DIRECTION('',(0.E+000,1.)); -#44312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44313 = PCURVE('',#44314,#44319); -#44314 = PLANE('',#44315); -#44315 = AXIS2_PLACEMENT_3D('',#44316,#44317,#44318); -#44316 = CARTESIAN_POINT('',(0.465,0.E+000,0.E+000)); -#44317 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44318 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44319 = DEFINITIONAL_REPRESENTATION('',(#44320),#44324); -#44320 = LINE('',#44321,#44322); -#44321 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44322 = VECTOR('',#44323,1.); -#44323 = DIRECTION('',(0.E+000,1.)); -#44324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44325 = ORIENTED_EDGE('',*,*,#44326,.T.); -#44326 = EDGE_CURVE('',#44299,#44327,#44329,.T.); -#44327 = VERTEX_POINT('',#44328); -#44328 = CARTESIAN_POINT('',(0.835,0.165,-1.15)); -#44329 = SURFACE_CURVE('',#44330,(#44334,#44341),.PCURVE_S1.); -#44330 = LINE('',#44331,#44332); -#44331 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); -#44332 = VECTOR('',#44333,1.); -#44333 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44334 = PCURVE('',#41837,#44335); -#44335 = DEFINITIONAL_REPRESENTATION('',(#44336),#44340); -#44336 = LINE('',#44337,#44338); -#44337 = CARTESIAN_POINT('',(0.465,0.165)); -#44338 = VECTOR('',#44339,1.); -#44339 = DIRECTION('',(1.,0.E+000)); -#44340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44341 = PCURVE('',#44342,#44347); -#44342 = PLANE('',#44343); -#44343 = AXIS2_PLACEMENT_3D('',#44344,#44345,#44346); -#44344 = CARTESIAN_POINT('',(0.465,0.165,1.05)); -#44345 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44346 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44347 = DEFINITIONAL_REPRESENTATION('',(#44348),#44352); -#44348 = LINE('',#44349,#44350); -#44349 = CARTESIAN_POINT('',(2.2,0.E+000)); -#44350 = VECTOR('',#44351,1.); -#44351 = DIRECTION('',(0.E+000,1.)); -#44352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44353 = ORIENTED_EDGE('',*,*,#44354,.F.); -#44354 = EDGE_CURVE('',#44355,#44327,#44357,.T.); -#44355 = VERTEX_POINT('',#44356); -#44356 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); -#44357 = SURFACE_CURVE('',#44358,(#44362,#44369),.PCURVE_S1.); -#44358 = LINE('',#44359,#44360); -#44359 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); -#44360 = VECTOR('',#44361,1.); -#44361 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44362 = PCURVE('',#41837,#44363); -#44363 = DEFINITIONAL_REPRESENTATION('',(#44364),#44368); -#44364 = LINE('',#44365,#44366); -#44365 = CARTESIAN_POINT('',(0.835,4.5E-002)); -#44366 = VECTOR('',#44367,1.); -#44367 = DIRECTION('',(0.E+000,1.)); -#44368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44369 = PCURVE('',#44370,#44375); -#44370 = PLANE('',#44371); -#44371 = AXIS2_PLACEMENT_3D('',#44372,#44373,#44374); -#44372 = CARTESIAN_POINT('',(0.835,0.E+000,0.E+000)); -#44373 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44374 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44375 = DEFINITIONAL_REPRESENTATION('',(#44376),#44380); -#44376 = LINE('',#44377,#44378); -#44377 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44378 = VECTOR('',#44379,1.); -#44379 = DIRECTION('',(0.E+000,1.)); -#44380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44381 = ORIENTED_EDGE('',*,*,#44382,.T.); -#44382 = EDGE_CURVE('',#44355,#44383,#44385,.T.); -#44383 = VERTEX_POINT('',#44384); -#44384 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); -#44385 = SURFACE_CURVE('',#44386,(#44390,#44397),.PCURVE_S1.); -#44386 = LINE('',#44387,#44388); -#44387 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); -#44388 = VECTOR('',#44389,1.); -#44389 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44390 = PCURVE('',#41837,#44391); -#44391 = DEFINITIONAL_REPRESENTATION('',(#44392),#44396); -#44392 = LINE('',#44393,#44394); -#44393 = CARTESIAN_POINT('',(0.835,4.5E-002)); -#44394 = VECTOR('',#44395,1.); -#44395 = DIRECTION('',(1.,0.E+000)); -#44396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44397 = PCURVE('',#44398,#44403); -#44398 = PLANE('',#44399); -#44399 = AXIS2_PLACEMENT_3D('',#44400,#44401,#44402); -#44400 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#44401 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#44402 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44403 = DEFINITIONAL_REPRESENTATION('',(#44404),#44408); -#44404 = LINE('',#44405,#44406); -#44405 = CARTESIAN_POINT('',(2.385,0.E+000)); -#44406 = VECTOR('',#44407,1.); -#44407 = DIRECTION('',(1.,0.E+000)); -#44408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44409 = ORIENTED_EDGE('',*,*,#44410,.T.); -#44410 = EDGE_CURVE('',#44383,#43159,#44411,.T.); -#44411 = SURFACE_CURVE('',#44412,(#44416,#44423),.PCURVE_S1.); -#44412 = LINE('',#44413,#44414); -#44413 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); -#44414 = VECTOR('',#44415,1.); -#44415 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44416 = PCURVE('',#41837,#44417); -#44417 = DEFINITIONAL_REPRESENTATION('',(#44418),#44422); -#44418 = LINE('',#44419,#44420); -#44419 = CARTESIAN_POINT('',(1.115,4.5E-002)); -#44420 = VECTOR('',#44421,1.); -#44421 = DIRECTION('',(0.E+000,1.)); -#44422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44423 = PCURVE('',#44424,#44429); -#44424 = PLANE('',#44425); -#44425 = AXIS2_PLACEMENT_3D('',#44426,#44427,#44428); -#44426 = CARTESIAN_POINT('',(1.115,0.E+000,0.E+000)); -#44427 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44428 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44429 = DEFINITIONAL_REPRESENTATION('',(#44430),#44434); -#44430 = LINE('',#44431,#44432); -#44431 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44432 = VECTOR('',#44433,1.); -#44433 = DIRECTION('',(0.E+000,1.)); -#44434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44435 = ADVANCED_FACE('',(#44436),#43176,.T.); -#44436 = FACE_BOUND('',#44437,.F.); -#44437 = EDGE_LOOP('',(#44438,#44439,#44462,#44489)); -#44438 = ORIENTED_EDGE('',*,*,#43158,.F.); -#44439 = ORIENTED_EDGE('',*,*,#44440,.T.); -#44440 = EDGE_CURVE('',#43159,#44441,#44443,.T.); -#44441 = VERTEX_POINT('',#44442); -#44442 = CARTESIAN_POINT('',(1.115,0.165,1.05)); -#44443 = SURFACE_CURVE('',#44444,(#44448,#44455),.PCURVE_S1.); -#44444 = LINE('',#44445,#44446); -#44445 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); -#44446 = VECTOR('',#44447,1.); -#44447 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44448 = PCURVE('',#43176,#44449); -#44449 = DEFINITIONAL_REPRESENTATION('',(#44450),#44454); -#44450 = LINE('',#44451,#44452); -#44451 = CARTESIAN_POINT('',(2.2,0.E+000)); -#44452 = VECTOR('',#44453,1.); -#44453 = DIRECTION('',(-1.,0.E+000)); -#44454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44455 = PCURVE('',#44424,#44456); -#44456 = DEFINITIONAL_REPRESENTATION('',(#44457),#44461); -#44457 = LINE('',#44458,#44459); -#44458 = CARTESIAN_POINT('',(1.15,0.165)); -#44459 = VECTOR('',#44460,1.); -#44460 = DIRECTION('',(-1.,0.E+000)); -#44461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44462 = ORIENTED_EDGE('',*,*,#44463,.T.); -#44463 = EDGE_CURVE('',#44441,#44464,#44466,.T.); -#44464 = VERTEX_POINT('',#44465); -#44465 = CARTESIAN_POINT('',(1.485,0.165,1.05)); -#44466 = SURFACE_CURVE('',#44467,(#44471,#44478),.PCURVE_S1.); -#44467 = LINE('',#44468,#44469); -#44468 = CARTESIAN_POINT('',(1.115,0.165,1.05)); -#44469 = VECTOR('',#44470,1.); -#44470 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44471 = PCURVE('',#43176,#44472); -#44472 = DEFINITIONAL_REPRESENTATION('',(#44473),#44477); -#44473 = LINE('',#44474,#44475); -#44474 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#44475 = VECTOR('',#44476,1.); -#44476 = DIRECTION('',(0.E+000,1.)); -#44477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44478 = PCURVE('',#44479,#44484); -#44479 = CYLINDRICAL_SURFACE('',#44480,0.1); -#44480 = AXIS2_PLACEMENT_3D('',#44481,#44482,#44483); -#44481 = CARTESIAN_POINT('',(1.115,0.265,1.05)); -#44482 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44483 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#44484 = DEFINITIONAL_REPRESENTATION('',(#44485),#44488); -#44485 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44486,#44487),.UNSPECIFIED., +#46322 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#46323 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#46324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46325 = ORIENTED_EDGE('',*,*,#46326,.T.); +#46326 = EDGE_CURVE('',#46299,#46327,#46329,.T.); +#46327 = VERTEX_POINT('',#46328); +#46328 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); +#46329 = SURFACE_CURVE('',#46330,(#46334,#46341),.PCURVE_S1.); +#46330 = LINE('',#46331,#46332); +#46331 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46332 = VECTOR('',#46333,1.); +#46333 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46334 = PCURVE('',#44229,#46335); +#46335 = DEFINITIONAL_REPRESENTATION('',(#46336),#46340); +#46336 = LINE('',#46337,#46338); +#46337 = CARTESIAN_POINT('',(-1.55,4.5E-002)); +#46338 = VECTOR('',#46339,1.); +#46339 = DIRECTION('',(1.,0.E+000)); +#46340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46341 = PCURVE('',#46342,#46347); +#46342 = PLANE('',#46343); +#46343 = AXIS2_PLACEMENT_3D('',#46344,#46345,#46346); +#46344 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46345 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46346 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46347 = DEFINITIONAL_REPRESENTATION('',(#46348),#46352); +#46348 = LINE('',#46349,#46350); +#46349 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#46350 = VECTOR('',#46351,1.); +#46351 = DIRECTION('',(1.,0.E+000)); +#46352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46353 = ORIENTED_EDGE('',*,*,#46354,.T.); +#46354 = EDGE_CURVE('',#46327,#46355,#46357,.T.); +#46355 = VERTEX_POINT('',#46356); +#46356 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); +#46357 = SURFACE_CURVE('',#46358,(#46362,#46369),.PCURVE_S1.); +#46358 = LINE('',#46359,#46360); +#46359 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); +#46360 = VECTOR('',#46361,1.); +#46361 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46362 = PCURVE('',#44229,#46363); +#46363 = DEFINITIONAL_REPRESENTATION('',(#46364),#46368); +#46364 = LINE('',#46365,#46366); +#46365 = CARTESIAN_POINT('',(-1.485,4.5E-002)); +#46366 = VECTOR('',#46367,1.); +#46367 = DIRECTION('',(0.E+000,1.)); +#46368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46369 = PCURVE('',#46370,#46375); +#46370 = PLANE('',#46371); +#46371 = AXIS2_PLACEMENT_3D('',#46372,#46373,#46374); +#46372 = CARTESIAN_POINT('',(-1.485,0.E+000,0.E+000)); +#46373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46374 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46375 = DEFINITIONAL_REPRESENTATION('',(#46376),#46380); +#46376 = LINE('',#46377,#46378); +#46377 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46378 = VECTOR('',#46379,1.); +#46379 = DIRECTION('',(0.E+000,1.)); +#46380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46381 = ORIENTED_EDGE('',*,*,#46382,.T.); +#46382 = EDGE_CURVE('',#46355,#46383,#46385,.T.); +#46383 = VERTEX_POINT('',#46384); +#46384 = CARTESIAN_POINT('',(-1.115,0.165,-1.15)); +#46385 = SURFACE_CURVE('',#46386,(#46390,#46397),.PCURVE_S1.); +#46386 = LINE('',#46387,#46388); +#46387 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); +#46388 = VECTOR('',#46389,1.); +#46389 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46390 = PCURVE('',#44229,#46391); +#46391 = DEFINITIONAL_REPRESENTATION('',(#46392),#46396); +#46392 = LINE('',#46393,#46394); +#46393 = CARTESIAN_POINT('',(-1.485,0.165)); +#46394 = VECTOR('',#46395,1.); +#46395 = DIRECTION('',(1.,0.E+000)); +#46396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46397 = PCURVE('',#46398,#46403); +#46398 = PLANE('',#46399); +#46399 = AXIS2_PLACEMENT_3D('',#46400,#46401,#46402); +#46400 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); +#46401 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46402 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46403 = DEFINITIONAL_REPRESENTATION('',(#46404),#46408); +#46404 = LINE('',#46405,#46406); +#46405 = CARTESIAN_POINT('',(2.2,0.E+000)); +#46406 = VECTOR('',#46407,1.); +#46407 = DIRECTION('',(0.E+000,1.)); +#46408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46409 = ORIENTED_EDGE('',*,*,#46410,.F.); +#46410 = EDGE_CURVE('',#46411,#46383,#46413,.T.); +#46411 = VERTEX_POINT('',#46412); +#46412 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); +#46413 = SURFACE_CURVE('',#46414,(#46418,#46425),.PCURVE_S1.); +#46414 = LINE('',#46415,#46416); +#46415 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); +#46416 = VECTOR('',#46417,1.); +#46417 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46418 = PCURVE('',#44229,#46419); +#46419 = DEFINITIONAL_REPRESENTATION('',(#46420),#46424); +#46420 = LINE('',#46421,#46422); +#46421 = CARTESIAN_POINT('',(-1.115,4.5E-002)); +#46422 = VECTOR('',#46423,1.); +#46423 = DIRECTION('',(0.E+000,1.)); +#46424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46425 = PCURVE('',#46426,#46431); +#46426 = PLANE('',#46427); +#46427 = AXIS2_PLACEMENT_3D('',#46428,#46429,#46430); +#46428 = CARTESIAN_POINT('',(-1.115,0.E+000,0.E+000)); +#46429 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46430 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46431 = DEFINITIONAL_REPRESENTATION('',(#46432),#46436); +#46432 = LINE('',#46433,#46434); +#46433 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46434 = VECTOR('',#46435,1.); +#46435 = DIRECTION('',(0.E+000,1.)); +#46436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46437 = ORIENTED_EDGE('',*,*,#46438,.T.); +#46438 = EDGE_CURVE('',#46411,#46439,#46441,.T.); +#46439 = VERTEX_POINT('',#46440); +#46440 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); +#46441 = SURFACE_CURVE('',#46442,(#46446,#46453),.PCURVE_S1.); +#46442 = LINE('',#46443,#46444); +#46443 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); +#46444 = VECTOR('',#46445,1.); +#46445 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46446 = PCURVE('',#44229,#46447); +#46447 = DEFINITIONAL_REPRESENTATION('',(#46448),#46452); +#46448 = LINE('',#46449,#46450); +#46449 = CARTESIAN_POINT('',(-1.115,4.5E-002)); +#46450 = VECTOR('',#46451,1.); +#46451 = DIRECTION('',(1.,0.E+000)); +#46452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46453 = PCURVE('',#46454,#46459); +#46454 = PLANE('',#46455); +#46455 = AXIS2_PLACEMENT_3D('',#46456,#46457,#46458); +#46456 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46457 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46458 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46459 = DEFINITIONAL_REPRESENTATION('',(#46460),#46464); +#46460 = LINE('',#46461,#46462); +#46461 = CARTESIAN_POINT('',(0.435,0.E+000)); +#46462 = VECTOR('',#46463,1.); +#46463 = DIRECTION('',(1.,0.E+000)); +#46464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46465 = ORIENTED_EDGE('',*,*,#46466,.T.); +#46466 = EDGE_CURVE('',#46439,#46467,#46469,.T.); +#46467 = VERTEX_POINT('',#46468); +#46468 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); +#46469 = SURFACE_CURVE('',#46470,(#46474,#46481),.PCURVE_S1.); +#46470 = LINE('',#46471,#46472); +#46471 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); +#46472 = VECTOR('',#46473,1.); +#46473 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46474 = PCURVE('',#44229,#46475); +#46475 = DEFINITIONAL_REPRESENTATION('',(#46476),#46480); +#46476 = LINE('',#46477,#46478); +#46477 = CARTESIAN_POINT('',(-0.835,4.5E-002)); +#46478 = VECTOR('',#46479,1.); +#46479 = DIRECTION('',(0.E+000,1.)); +#46480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46481 = PCURVE('',#46482,#46487); +#46482 = PLANE('',#46483); +#46483 = AXIS2_PLACEMENT_3D('',#46484,#46485,#46486); +#46484 = CARTESIAN_POINT('',(-0.835,0.E+000,0.E+000)); +#46485 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46486 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46487 = DEFINITIONAL_REPRESENTATION('',(#46488),#46492); +#46488 = LINE('',#46489,#46490); +#46489 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46490 = VECTOR('',#46491,1.); +#46491 = DIRECTION('',(0.E+000,1.)); +#46492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46493 = ORIENTED_EDGE('',*,*,#46494,.T.); +#46494 = EDGE_CURVE('',#46467,#46495,#46497,.T.); +#46495 = VERTEX_POINT('',#46496); +#46496 = CARTESIAN_POINT('',(-0.465,0.165,-1.15)); +#46497 = SURFACE_CURVE('',#46498,(#46502,#46509),.PCURVE_S1.); +#46498 = LINE('',#46499,#46500); +#46499 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); +#46500 = VECTOR('',#46501,1.); +#46501 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46502 = PCURVE('',#44229,#46503); +#46503 = DEFINITIONAL_REPRESENTATION('',(#46504),#46508); +#46504 = LINE('',#46505,#46506); +#46505 = CARTESIAN_POINT('',(-0.835,0.165)); +#46506 = VECTOR('',#46507,1.); +#46507 = DIRECTION('',(1.,0.E+000)); +#46508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46509 = PCURVE('',#46510,#46515); +#46510 = PLANE('',#46511); +#46511 = AXIS2_PLACEMENT_3D('',#46512,#46513,#46514); +#46512 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); +#46513 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46514 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46515 = DEFINITIONAL_REPRESENTATION('',(#46516),#46520); +#46516 = LINE('',#46517,#46518); +#46517 = CARTESIAN_POINT('',(2.2,0.E+000)); +#46518 = VECTOR('',#46519,1.); +#46519 = DIRECTION('',(0.E+000,1.)); +#46520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46521 = ORIENTED_EDGE('',*,*,#46522,.F.); +#46522 = EDGE_CURVE('',#46523,#46495,#46525,.T.); +#46523 = VERTEX_POINT('',#46524); +#46524 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); +#46525 = SURFACE_CURVE('',#46526,(#46530,#46537),.PCURVE_S1.); +#46526 = LINE('',#46527,#46528); +#46527 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); +#46528 = VECTOR('',#46529,1.); +#46529 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46530 = PCURVE('',#44229,#46531); +#46531 = DEFINITIONAL_REPRESENTATION('',(#46532),#46536); +#46532 = LINE('',#46533,#46534); +#46533 = CARTESIAN_POINT('',(-0.465,4.5E-002)); +#46534 = VECTOR('',#46535,1.); +#46535 = DIRECTION('',(0.E+000,1.)); +#46536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46537 = PCURVE('',#46538,#46543); +#46538 = PLANE('',#46539); +#46539 = AXIS2_PLACEMENT_3D('',#46540,#46541,#46542); +#46540 = CARTESIAN_POINT('',(-0.465,0.E+000,0.E+000)); +#46541 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46542 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46543 = DEFINITIONAL_REPRESENTATION('',(#46544),#46548); +#46544 = LINE('',#46545,#46546); +#46545 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46546 = VECTOR('',#46547,1.); +#46547 = DIRECTION('',(0.E+000,1.)); +#46548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46549 = ORIENTED_EDGE('',*,*,#46550,.T.); +#46550 = EDGE_CURVE('',#46523,#46551,#46553,.T.); +#46551 = VERTEX_POINT('',#46552); +#46552 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); +#46553 = SURFACE_CURVE('',#46554,(#46558,#46565),.PCURVE_S1.); +#46554 = LINE('',#46555,#46556); +#46555 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); +#46556 = VECTOR('',#46557,1.); +#46557 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46558 = PCURVE('',#44229,#46559); +#46559 = DEFINITIONAL_REPRESENTATION('',(#46560),#46564); +#46560 = LINE('',#46561,#46562); +#46561 = CARTESIAN_POINT('',(-0.465,4.5E-002)); +#46562 = VECTOR('',#46563,1.); +#46563 = DIRECTION('',(1.,0.E+000)); +#46564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46565 = PCURVE('',#46566,#46571); +#46566 = PLANE('',#46567); +#46567 = AXIS2_PLACEMENT_3D('',#46568,#46569,#46570); +#46568 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46569 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46570 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46571 = DEFINITIONAL_REPRESENTATION('',(#46572),#46576); +#46572 = LINE('',#46573,#46574); +#46573 = CARTESIAN_POINT('',(1.085,0.E+000)); +#46574 = VECTOR('',#46575,1.); +#46575 = DIRECTION('',(1.,0.E+000)); +#46576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46577 = ORIENTED_EDGE('',*,*,#46578,.T.); +#46578 = EDGE_CURVE('',#46551,#46579,#46581,.T.); +#46579 = VERTEX_POINT('',#46580); +#46580 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); +#46581 = SURFACE_CURVE('',#46582,(#46586,#46593),.PCURVE_S1.); +#46582 = LINE('',#46583,#46584); +#46583 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); +#46584 = VECTOR('',#46585,1.); +#46585 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46586 = PCURVE('',#44229,#46587); +#46587 = DEFINITIONAL_REPRESENTATION('',(#46588),#46592); +#46588 = LINE('',#46589,#46590); +#46589 = CARTESIAN_POINT('',(-0.185,4.5E-002)); +#46590 = VECTOR('',#46591,1.); +#46591 = DIRECTION('',(0.E+000,1.)); +#46592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46593 = PCURVE('',#46594,#46599); +#46594 = PLANE('',#46595); +#46595 = AXIS2_PLACEMENT_3D('',#46596,#46597,#46598); +#46596 = CARTESIAN_POINT('',(-0.185,0.E+000,0.E+000)); +#46597 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46598 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46599 = DEFINITIONAL_REPRESENTATION('',(#46600),#46604); +#46600 = LINE('',#46601,#46602); +#46601 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46602 = VECTOR('',#46603,1.); +#46603 = DIRECTION('',(0.E+000,1.)); +#46604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46605 = ORIENTED_EDGE('',*,*,#46606,.T.); +#46606 = EDGE_CURVE('',#46579,#46607,#46609,.T.); +#46607 = VERTEX_POINT('',#46608); +#46608 = CARTESIAN_POINT('',(0.185,0.165,-1.15)); +#46609 = SURFACE_CURVE('',#46610,(#46614,#46621),.PCURVE_S1.); +#46610 = LINE('',#46611,#46612); +#46611 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); +#46612 = VECTOR('',#46613,1.); +#46613 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46614 = PCURVE('',#44229,#46615); +#46615 = DEFINITIONAL_REPRESENTATION('',(#46616),#46620); +#46616 = LINE('',#46617,#46618); +#46617 = CARTESIAN_POINT('',(-0.185,0.165)); +#46618 = VECTOR('',#46619,1.); +#46619 = DIRECTION('',(1.,0.E+000)); +#46620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46621 = PCURVE('',#46622,#46627); +#46622 = PLANE('',#46623); +#46623 = AXIS2_PLACEMENT_3D('',#46624,#46625,#46626); +#46624 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); +#46625 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46626 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46627 = DEFINITIONAL_REPRESENTATION('',(#46628),#46632); +#46628 = LINE('',#46629,#46630); +#46629 = CARTESIAN_POINT('',(2.2,0.E+000)); +#46630 = VECTOR('',#46631,1.); +#46631 = DIRECTION('',(0.E+000,1.)); +#46632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46633 = ORIENTED_EDGE('',*,*,#46634,.F.); +#46634 = EDGE_CURVE('',#46635,#46607,#46637,.T.); +#46635 = VERTEX_POINT('',#46636); +#46636 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); +#46637 = SURFACE_CURVE('',#46638,(#46642,#46649),.PCURVE_S1.); +#46638 = LINE('',#46639,#46640); +#46639 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); +#46640 = VECTOR('',#46641,1.); +#46641 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46642 = PCURVE('',#44229,#46643); +#46643 = DEFINITIONAL_REPRESENTATION('',(#46644),#46648); +#46644 = LINE('',#46645,#46646); +#46645 = CARTESIAN_POINT('',(0.185,4.5E-002)); +#46646 = VECTOR('',#46647,1.); +#46647 = DIRECTION('',(0.E+000,1.)); +#46648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46649 = PCURVE('',#46650,#46655); +#46650 = PLANE('',#46651); +#46651 = AXIS2_PLACEMENT_3D('',#46652,#46653,#46654); +#46652 = CARTESIAN_POINT('',(0.185,0.E+000,0.E+000)); +#46653 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46654 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46655 = DEFINITIONAL_REPRESENTATION('',(#46656),#46660); +#46656 = LINE('',#46657,#46658); +#46657 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46658 = VECTOR('',#46659,1.); +#46659 = DIRECTION('',(0.E+000,1.)); +#46660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46661 = ORIENTED_EDGE('',*,*,#46662,.T.); +#46662 = EDGE_CURVE('',#46635,#46663,#46665,.T.); +#46663 = VERTEX_POINT('',#46664); +#46664 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); +#46665 = SURFACE_CURVE('',#46666,(#46670,#46677),.PCURVE_S1.); +#46666 = LINE('',#46667,#46668); +#46667 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); +#46668 = VECTOR('',#46669,1.); +#46669 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46670 = PCURVE('',#44229,#46671); +#46671 = DEFINITIONAL_REPRESENTATION('',(#46672),#46676); +#46672 = LINE('',#46673,#46674); +#46673 = CARTESIAN_POINT('',(0.185,4.5E-002)); +#46674 = VECTOR('',#46675,1.); +#46675 = DIRECTION('',(1.,0.E+000)); +#46676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46677 = PCURVE('',#46678,#46683); +#46678 = PLANE('',#46679); +#46679 = AXIS2_PLACEMENT_3D('',#46680,#46681,#46682); +#46680 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46681 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46682 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46683 = DEFINITIONAL_REPRESENTATION('',(#46684),#46688); +#46684 = LINE('',#46685,#46686); +#46685 = CARTESIAN_POINT('',(1.735,0.E+000)); +#46686 = VECTOR('',#46687,1.); +#46687 = DIRECTION('',(1.,0.E+000)); +#46688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46689 = ORIENTED_EDGE('',*,*,#46690,.T.); +#46690 = EDGE_CURVE('',#46663,#46691,#46693,.T.); +#46691 = VERTEX_POINT('',#46692); +#46692 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); +#46693 = SURFACE_CURVE('',#46694,(#46698,#46705),.PCURVE_S1.); +#46694 = LINE('',#46695,#46696); +#46695 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); +#46696 = VECTOR('',#46697,1.); +#46697 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46698 = PCURVE('',#44229,#46699); +#46699 = DEFINITIONAL_REPRESENTATION('',(#46700),#46704); +#46700 = LINE('',#46701,#46702); +#46701 = CARTESIAN_POINT('',(0.465,4.5E-002)); +#46702 = VECTOR('',#46703,1.); +#46703 = DIRECTION('',(0.E+000,1.)); +#46704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46705 = PCURVE('',#46706,#46711); +#46706 = PLANE('',#46707); +#46707 = AXIS2_PLACEMENT_3D('',#46708,#46709,#46710); +#46708 = CARTESIAN_POINT('',(0.465,0.E+000,0.E+000)); +#46709 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46710 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46711 = DEFINITIONAL_REPRESENTATION('',(#46712),#46716); +#46712 = LINE('',#46713,#46714); +#46713 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46714 = VECTOR('',#46715,1.); +#46715 = DIRECTION('',(0.E+000,1.)); +#46716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46717 = ORIENTED_EDGE('',*,*,#46718,.T.); +#46718 = EDGE_CURVE('',#46691,#46719,#46721,.T.); +#46719 = VERTEX_POINT('',#46720); +#46720 = CARTESIAN_POINT('',(0.835,0.165,-1.15)); +#46721 = SURFACE_CURVE('',#46722,(#46726,#46733),.PCURVE_S1.); +#46722 = LINE('',#46723,#46724); +#46723 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); +#46724 = VECTOR('',#46725,1.); +#46725 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46726 = PCURVE('',#44229,#46727); +#46727 = DEFINITIONAL_REPRESENTATION('',(#46728),#46732); +#46728 = LINE('',#46729,#46730); +#46729 = CARTESIAN_POINT('',(0.465,0.165)); +#46730 = VECTOR('',#46731,1.); +#46731 = DIRECTION('',(1.,0.E+000)); +#46732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46733 = PCURVE('',#46734,#46739); +#46734 = PLANE('',#46735); +#46735 = AXIS2_PLACEMENT_3D('',#46736,#46737,#46738); +#46736 = CARTESIAN_POINT('',(0.465,0.165,1.05)); +#46737 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46738 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46739 = DEFINITIONAL_REPRESENTATION('',(#46740),#46744); +#46740 = LINE('',#46741,#46742); +#46741 = CARTESIAN_POINT('',(2.2,0.E+000)); +#46742 = VECTOR('',#46743,1.); +#46743 = DIRECTION('',(0.E+000,1.)); +#46744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46745 = ORIENTED_EDGE('',*,*,#46746,.F.); +#46746 = EDGE_CURVE('',#46747,#46719,#46749,.T.); +#46747 = VERTEX_POINT('',#46748); +#46748 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); +#46749 = SURFACE_CURVE('',#46750,(#46754,#46761),.PCURVE_S1.); +#46750 = LINE('',#46751,#46752); +#46751 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); +#46752 = VECTOR('',#46753,1.); +#46753 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46754 = PCURVE('',#44229,#46755); +#46755 = DEFINITIONAL_REPRESENTATION('',(#46756),#46760); +#46756 = LINE('',#46757,#46758); +#46757 = CARTESIAN_POINT('',(0.835,4.5E-002)); +#46758 = VECTOR('',#46759,1.); +#46759 = DIRECTION('',(0.E+000,1.)); +#46760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46761 = PCURVE('',#46762,#46767); +#46762 = PLANE('',#46763); +#46763 = AXIS2_PLACEMENT_3D('',#46764,#46765,#46766); +#46764 = CARTESIAN_POINT('',(0.835,0.E+000,0.E+000)); +#46765 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46766 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46767 = DEFINITIONAL_REPRESENTATION('',(#46768),#46772); +#46768 = LINE('',#46769,#46770); +#46769 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46770 = VECTOR('',#46771,1.); +#46771 = DIRECTION('',(0.E+000,1.)); +#46772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46773 = ORIENTED_EDGE('',*,*,#46774,.T.); +#46774 = EDGE_CURVE('',#46747,#46775,#46777,.T.); +#46775 = VERTEX_POINT('',#46776); +#46776 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); +#46777 = SURFACE_CURVE('',#46778,(#46782,#46789),.PCURVE_S1.); +#46778 = LINE('',#46779,#46780); +#46779 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); +#46780 = VECTOR('',#46781,1.); +#46781 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46782 = PCURVE('',#44229,#46783); +#46783 = DEFINITIONAL_REPRESENTATION('',(#46784),#46788); +#46784 = LINE('',#46785,#46786); +#46785 = CARTESIAN_POINT('',(0.835,4.5E-002)); +#46786 = VECTOR('',#46787,1.); +#46787 = DIRECTION('',(1.,0.E+000)); +#46788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46789 = PCURVE('',#46790,#46795); +#46790 = PLANE('',#46791); +#46791 = AXIS2_PLACEMENT_3D('',#46792,#46793,#46794); +#46792 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#46793 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#46794 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46795 = DEFINITIONAL_REPRESENTATION('',(#46796),#46800); +#46796 = LINE('',#46797,#46798); +#46797 = CARTESIAN_POINT('',(2.385,0.E+000)); +#46798 = VECTOR('',#46799,1.); +#46799 = DIRECTION('',(1.,0.E+000)); +#46800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46801 = ORIENTED_EDGE('',*,*,#46802,.T.); +#46802 = EDGE_CURVE('',#46775,#45551,#46803,.T.); +#46803 = SURFACE_CURVE('',#46804,(#46808,#46815),.PCURVE_S1.); +#46804 = LINE('',#46805,#46806); +#46805 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); +#46806 = VECTOR('',#46807,1.); +#46807 = DIRECTION('',(0.E+000,1.,0.E+000)); +#46808 = PCURVE('',#44229,#46809); +#46809 = DEFINITIONAL_REPRESENTATION('',(#46810),#46814); +#46810 = LINE('',#46811,#46812); +#46811 = CARTESIAN_POINT('',(1.115,4.5E-002)); +#46812 = VECTOR('',#46813,1.); +#46813 = DIRECTION('',(0.E+000,1.)); +#46814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46815 = PCURVE('',#46816,#46821); +#46816 = PLANE('',#46817); +#46817 = AXIS2_PLACEMENT_3D('',#46818,#46819,#46820); +#46818 = CARTESIAN_POINT('',(1.115,0.E+000,0.E+000)); +#46819 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46820 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46821 = DEFINITIONAL_REPRESENTATION('',(#46822),#46826); +#46822 = LINE('',#46823,#46824); +#46823 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46824 = VECTOR('',#46825,1.); +#46825 = DIRECTION('',(0.E+000,1.)); +#46826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46827 = ADVANCED_FACE('',(#46828),#45568,.T.); +#46828 = FACE_BOUND('',#46829,.F.); +#46829 = EDGE_LOOP('',(#46830,#46831,#46854,#46881)); +#46830 = ORIENTED_EDGE('',*,*,#45550,.F.); +#46831 = ORIENTED_EDGE('',*,*,#46832,.T.); +#46832 = EDGE_CURVE('',#45551,#46833,#46835,.T.); +#46833 = VERTEX_POINT('',#46834); +#46834 = CARTESIAN_POINT('',(1.115,0.165,1.05)); +#46835 = SURFACE_CURVE('',#46836,(#46840,#46847),.PCURVE_S1.); +#46836 = LINE('',#46837,#46838); +#46837 = CARTESIAN_POINT('',(1.115,0.165,-1.15)); +#46838 = VECTOR('',#46839,1.); +#46839 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46840 = PCURVE('',#45568,#46841); +#46841 = DEFINITIONAL_REPRESENTATION('',(#46842),#46846); +#46842 = LINE('',#46843,#46844); +#46843 = CARTESIAN_POINT('',(2.2,0.E+000)); +#46844 = VECTOR('',#46845,1.); +#46845 = DIRECTION('',(-1.,0.E+000)); +#46846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46847 = PCURVE('',#46816,#46848); +#46848 = DEFINITIONAL_REPRESENTATION('',(#46849),#46853); +#46849 = LINE('',#46850,#46851); +#46850 = CARTESIAN_POINT('',(1.15,0.165)); +#46851 = VECTOR('',#46852,1.); +#46852 = DIRECTION('',(-1.,0.E+000)); +#46853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46854 = ORIENTED_EDGE('',*,*,#46855,.T.); +#46855 = EDGE_CURVE('',#46833,#46856,#46858,.T.); +#46856 = VERTEX_POINT('',#46857); +#46857 = CARTESIAN_POINT('',(1.485,0.165,1.05)); +#46858 = SURFACE_CURVE('',#46859,(#46863,#46870),.PCURVE_S1.); +#46859 = LINE('',#46860,#46861); +#46860 = CARTESIAN_POINT('',(1.115,0.165,1.05)); +#46861 = VECTOR('',#46862,1.); +#46862 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46863 = PCURVE('',#45568,#46864); +#46864 = DEFINITIONAL_REPRESENTATION('',(#46865),#46869); +#46865 = LINE('',#46866,#46867); +#46866 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#46867 = VECTOR('',#46868,1.); +#46868 = DIRECTION('',(0.E+000,1.)); +#46869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46870 = PCURVE('',#46871,#46876); +#46871 = CYLINDRICAL_SURFACE('',#46872,0.1); +#46872 = AXIS2_PLACEMENT_3D('',#46873,#46874,#46875); +#46873 = CARTESIAN_POINT('',(1.115,0.265,1.05)); +#46874 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46875 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#46876 = DEFINITIONAL_REPRESENTATION('',(#46877),#46880); +#46877 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46878,#46879),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#44486 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#44487 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#44488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44489 = ORIENTED_EDGE('',*,*,#44490,.F.); -#44490 = EDGE_CURVE('',#43161,#44464,#44491,.T.); -#44491 = SURFACE_CURVE('',#44492,(#44496,#44503),.PCURVE_S1.); -#44492 = LINE('',#44493,#44494); -#44493 = CARTESIAN_POINT('',(1.485,0.165,-1.15)); -#44494 = VECTOR('',#44495,1.); -#44495 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44496 = PCURVE('',#43176,#44497); -#44497 = DEFINITIONAL_REPRESENTATION('',(#44498),#44502); -#44498 = LINE('',#44499,#44500); -#44499 = CARTESIAN_POINT('',(2.2,0.37)); -#44500 = VECTOR('',#44501,1.); -#44501 = DIRECTION('',(-1.,0.E+000)); -#44502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44503 = PCURVE('',#43204,#44504); -#44504 = DEFINITIONAL_REPRESENTATION('',(#44505),#44509); -#44505 = LINE('',#44506,#44507); -#44506 = CARTESIAN_POINT('',(1.15,0.165)); -#44507 = VECTOR('',#44508,1.); -#44508 = DIRECTION('',(-1.,0.E+000)); -#44509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44510 = ADVANCED_FACE('',(#44511),#44424,.T.); -#44511 = FACE_BOUND('',#44512,.F.); -#44512 = EDGE_LOOP('',(#44513,#44536,#44537,#44538,#44561,#44589,#44617) - ); -#44513 = ORIENTED_EDGE('',*,*,#44514,.T.); -#44514 = EDGE_CURVE('',#44515,#44441,#44517,.T.); -#44515 = VERTEX_POINT('',#44516); -#44516 = CARTESIAN_POINT('',(1.115,0.265,1.15)); -#44517 = SURFACE_CURVE('',#44518,(#44523,#44530),.PCURVE_S1.); -#44518 = CIRCLE('',#44519,0.1); -#44519 = AXIS2_PLACEMENT_3D('',#44520,#44521,#44522); -#44520 = CARTESIAN_POINT('',(1.115,0.265,1.05)); -#44521 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44522 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44523 = PCURVE('',#44424,#44524); -#44524 = DEFINITIONAL_REPRESENTATION('',(#44525),#44529); -#44525 = CIRCLE('',#44526,0.1); -#44526 = AXIS2_PLACEMENT_2D('',#44527,#44528); -#44527 = CARTESIAN_POINT('',(-1.05,0.265)); -#44528 = DIRECTION('',(-1.,0.E+000)); -#44529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44530 = PCURVE('',#44479,#44531); -#44531 = DEFINITIONAL_REPRESENTATION('',(#44532),#44535); -#44532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44533,#44534),.UNSPECIFIED., +#46878 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#46879 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#46880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46881 = ORIENTED_EDGE('',*,*,#46882,.F.); +#46882 = EDGE_CURVE('',#45553,#46856,#46883,.T.); +#46883 = SURFACE_CURVE('',#46884,(#46888,#46895),.PCURVE_S1.); +#46884 = LINE('',#46885,#46886); +#46885 = CARTESIAN_POINT('',(1.485,0.165,-1.15)); +#46886 = VECTOR('',#46887,1.); +#46887 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46888 = PCURVE('',#45568,#46889); +#46889 = DEFINITIONAL_REPRESENTATION('',(#46890),#46894); +#46890 = LINE('',#46891,#46892); +#46891 = CARTESIAN_POINT('',(2.2,0.37)); +#46892 = VECTOR('',#46893,1.); +#46893 = DIRECTION('',(-1.,0.E+000)); +#46894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46895 = PCURVE('',#45596,#46896); +#46896 = DEFINITIONAL_REPRESENTATION('',(#46897),#46901); +#46897 = LINE('',#46898,#46899); +#46898 = CARTESIAN_POINT('',(1.15,0.165)); +#46899 = VECTOR('',#46900,1.); +#46900 = DIRECTION('',(-1.,0.E+000)); +#46901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46902 = ADVANCED_FACE('',(#46903),#46816,.T.); +#46903 = FACE_BOUND('',#46904,.F.); +#46904 = EDGE_LOOP('',(#46905,#46928,#46929,#46930,#46953,#46981,#47009) + ); +#46905 = ORIENTED_EDGE('',*,*,#46906,.T.); +#46906 = EDGE_CURVE('',#46907,#46833,#46909,.T.); +#46907 = VERTEX_POINT('',#46908); +#46908 = CARTESIAN_POINT('',(1.115,0.265,1.15)); +#46909 = SURFACE_CURVE('',#46910,(#46915,#46922),.PCURVE_S1.); +#46910 = CIRCLE('',#46911,0.1); +#46911 = AXIS2_PLACEMENT_3D('',#46912,#46913,#46914); +#46912 = CARTESIAN_POINT('',(1.115,0.265,1.05)); +#46913 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46914 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46915 = PCURVE('',#46816,#46916); +#46916 = DEFINITIONAL_REPRESENTATION('',(#46917),#46921); +#46917 = CIRCLE('',#46918,0.1); +#46918 = AXIS2_PLACEMENT_2D('',#46919,#46920); +#46919 = CARTESIAN_POINT('',(-1.05,0.265)); +#46920 = DIRECTION('',(-1.,0.E+000)); +#46921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46922 = PCURVE('',#46871,#46923); +#46923 = DEFINITIONAL_REPRESENTATION('',(#46924),#46927); +#46924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46925,#46926),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#44533 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#44534 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#44535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#46925 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#46926 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#46927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46928 = ORIENTED_EDGE('',*,*,#46832,.F.); +#46929 = ORIENTED_EDGE('',*,*,#46802,.F.); +#46930 = ORIENTED_EDGE('',*,*,#46931,.T.); +#46931 = EDGE_CURVE('',#46775,#46932,#46934,.T.); +#46932 = VERTEX_POINT('',#46933); +#46933 = CARTESIAN_POINT('',(1.115,4.5E-002,1.35)); +#46934 = SURFACE_CURVE('',#46935,(#46939,#46946),.PCURVE_S1.); +#46935 = LINE('',#46936,#46937); +#46936 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); +#46937 = VECTOR('',#46938,1.); +#46938 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46939 = PCURVE('',#46816,#46940); +#46940 = DEFINITIONAL_REPRESENTATION('',(#46941),#46945); +#46941 = LINE('',#46942,#46943); +#46942 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#46943 = VECTOR('',#46944,1.); +#46944 = DIRECTION('',(-1.,0.E+000)); +#46945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46946 = PCURVE('',#46790,#46947); +#46947 = DEFINITIONAL_REPRESENTATION('',(#46948),#46952); +#46948 = LINE('',#46949,#46950); +#46949 = CARTESIAN_POINT('',(2.665,0.E+000)); +#46950 = VECTOR('',#46951,1.); +#46951 = DIRECTION('',(0.E+000,1.)); +#46952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#44536 = ORIENTED_EDGE('',*,*,#44440,.F.); -#44537 = ORIENTED_EDGE('',*,*,#44410,.F.); -#44538 = ORIENTED_EDGE('',*,*,#44539,.T.); -#44539 = EDGE_CURVE('',#44383,#44540,#44542,.T.); -#44540 = VERTEX_POINT('',#44541); -#44541 = CARTESIAN_POINT('',(1.115,4.5E-002,1.35)); -#44542 = SURFACE_CURVE('',#44543,(#44547,#44554),.PCURVE_S1.); -#44543 = LINE('',#44544,#44545); -#44544 = CARTESIAN_POINT('',(1.115,4.5E-002,-1.15)); -#44545 = VECTOR('',#44546,1.); -#44546 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44547 = PCURVE('',#44424,#44548); -#44548 = DEFINITIONAL_REPRESENTATION('',(#44549),#44553); -#44549 = LINE('',#44550,#44551); -#44550 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#44551 = VECTOR('',#44552,1.); -#44552 = DIRECTION('',(-1.,0.E+000)); -#44553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44554 = PCURVE('',#44398,#44555); -#44555 = DEFINITIONAL_REPRESENTATION('',(#44556),#44560); -#44556 = LINE('',#44557,#44558); -#44557 = CARTESIAN_POINT('',(2.665,0.E+000)); -#44558 = VECTOR('',#44559,1.); -#44559 = DIRECTION('',(0.E+000,1.)); -#44560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44561 = ORIENTED_EDGE('',*,*,#44562,.F.); -#44562 = EDGE_CURVE('',#44563,#44540,#44565,.T.); -#44563 = VERTEX_POINT('',#44564); -#44564 = CARTESIAN_POINT('',(1.115,0.245,1.55)); -#44565 = SURFACE_CURVE('',#44566,(#44571,#44578),.PCURVE_S1.); -#44566 = CIRCLE('',#44567,0.2); -#44567 = AXIS2_PLACEMENT_3D('',#44568,#44569,#44570); -#44568 = CARTESIAN_POINT('',(1.115,0.245,1.35)); -#44569 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44570 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44571 = PCURVE('',#44424,#44572); -#44572 = DEFINITIONAL_REPRESENTATION('',(#44573),#44577); -#44573 = CIRCLE('',#44574,0.2); -#44574 = AXIS2_PLACEMENT_2D('',#44575,#44576); -#44575 = CARTESIAN_POINT('',(-1.35,0.245)); -#44576 = DIRECTION('',(-1.,0.E+000)); -#44577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44578 = PCURVE('',#44579,#44584); -#44579 = CYLINDRICAL_SURFACE('',#44580,0.2); -#44580 = AXIS2_PLACEMENT_3D('',#44581,#44582,#44583); -#44581 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#44582 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44583 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44584 = DEFINITIONAL_REPRESENTATION('',(#44585),#44588); -#44585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44586,#44587),.UNSPECIFIED., +#46953 = ORIENTED_EDGE('',*,*,#46954,.F.); +#46954 = EDGE_CURVE('',#46955,#46932,#46957,.T.); +#46955 = VERTEX_POINT('',#46956); +#46956 = CARTESIAN_POINT('',(1.115,0.245,1.55)); +#46957 = SURFACE_CURVE('',#46958,(#46963,#46970),.PCURVE_S1.); +#46958 = CIRCLE('',#46959,0.2); +#46959 = AXIS2_PLACEMENT_3D('',#46960,#46961,#46962); +#46960 = CARTESIAN_POINT('',(1.115,0.245,1.35)); +#46961 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46962 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46963 = PCURVE('',#46816,#46964); +#46964 = DEFINITIONAL_REPRESENTATION('',(#46965),#46969); +#46965 = CIRCLE('',#46966,0.2); +#46966 = AXIS2_PLACEMENT_2D('',#46967,#46968); +#46967 = CARTESIAN_POINT('',(-1.35,0.245)); +#46968 = DIRECTION('',(-1.,0.E+000)); +#46969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46970 = PCURVE('',#46971,#46976); +#46971 = CYLINDRICAL_SURFACE('',#46972,0.2); +#46972 = AXIS2_PLACEMENT_3D('',#46973,#46974,#46975); +#46973 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#46974 = DIRECTION('',(1.,0.E+000,0.E+000)); +#46975 = DIRECTION('',(0.E+000,0.E+000,1.)); +#46976 = DEFINITIONAL_REPRESENTATION('',(#46977),#46980); +#46977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46978,#46979),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#44586 = CARTESIAN_POINT('',(0.E+000,2.680514631548)); -#44587 = CARTESIAN_POINT('',(1.570796326795,2.680514631548)); -#44588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44589 = ORIENTED_EDGE('',*,*,#44590,.T.); -#44590 = EDGE_CURVE('',#44563,#44591,#44593,.T.); -#44591 = VERTEX_POINT('',#44592); -#44592 = CARTESIAN_POINT('',(1.115,0.265,1.55)); -#44593 = SURFACE_CURVE('',#44594,(#44598,#44605),.PCURVE_S1.); -#44594 = LINE('',#44595,#44596); -#44595 = CARTESIAN_POINT('',(1.115,0.245,1.55)); -#44596 = VECTOR('',#44597,1.); -#44597 = DIRECTION('',(1.110223024625E-014,1.,0.E+000)); -#44598 = PCURVE('',#44424,#44599); -#44599 = DEFINITIONAL_REPRESENTATION('',(#44600),#44604); -#44600 = LINE('',#44601,#44602); -#44601 = CARTESIAN_POINT('',(-1.55,0.245)); -#44602 = VECTOR('',#44603,1.); -#44603 = DIRECTION('',(0.E+000,1.)); -#44604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44605 = PCURVE('',#44606,#44611); -#44606 = PLANE('',#44607); -#44607 = AXIS2_PLACEMENT_3D('',#44608,#44609,#44610); -#44608 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.55)); -#44609 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44610 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44611 = DEFINITIONAL_REPRESENTATION('',(#44612),#44616); -#44612 = LINE('',#44613,#44614); -#44613 = CARTESIAN_POINT('',(1.115,0.245)); -#44614 = VECTOR('',#44615,1.); -#44615 = DIRECTION('',(1.110223024625E-014,1.)); -#44616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44617 = ORIENTED_EDGE('',*,*,#44618,.F.); -#44618 = EDGE_CURVE('',#44515,#44591,#44619,.T.); -#44619 = SURFACE_CURVE('',#44620,(#44624,#44631),.PCURVE_S1.); -#44620 = LINE('',#44621,#44622); -#44621 = CARTESIAN_POINT('',(1.115,0.265,1.15)); -#44622 = VECTOR('',#44623,1.); -#44623 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44624 = PCURVE('',#44424,#44625); -#44625 = DEFINITIONAL_REPRESENTATION('',(#44626),#44630); -#44626 = LINE('',#44627,#44628); -#44627 = CARTESIAN_POINT('',(-1.15,0.265)); -#44628 = VECTOR('',#44629,1.); -#44629 = DIRECTION('',(-1.,0.E+000)); -#44630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44631 = PCURVE('',#44632,#44637); -#44632 = PLANE('',#44633); -#44633 = AXIS2_PLACEMENT_3D('',#44634,#44635,#44636); -#44634 = CARTESIAN_POINT('',(1.115,0.265,-1.15)); -#44635 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44636 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44637 = DEFINITIONAL_REPRESENTATION('',(#44638),#44642); -#44638 = LINE('',#44639,#44640); -#44639 = CARTESIAN_POINT('',(2.3,0.E+000)); -#44640 = VECTOR('',#44641,1.); -#44641 = DIRECTION('',(1.,0.E+000)); -#44642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44643 = ADVANCED_FACE('',(#44644),#44479,.T.); -#44644 = FACE_BOUND('',#44645,.T.); -#44645 = EDGE_LOOP('',(#44646,#44647,#44648,#44671)); -#44646 = ORIENTED_EDGE('',*,*,#44514,.T.); -#44647 = ORIENTED_EDGE('',*,*,#44463,.T.); -#44648 = ORIENTED_EDGE('',*,*,#44649,.F.); -#44649 = EDGE_CURVE('',#44650,#44464,#44652,.T.); -#44650 = VERTEX_POINT('',#44651); -#44651 = CARTESIAN_POINT('',(1.485,0.265,1.15)); -#44652 = SURFACE_CURVE('',#44653,(#44658,#44664),.PCURVE_S1.); -#44653 = CIRCLE('',#44654,0.1); -#44654 = AXIS2_PLACEMENT_3D('',#44655,#44656,#44657); -#44655 = CARTESIAN_POINT('',(1.485,0.265,1.05)); -#44656 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44657 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44658 = PCURVE('',#44479,#44659); -#44659 = DEFINITIONAL_REPRESENTATION('',(#44660),#44663); -#44660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44661,#44662),.UNSPECIFIED., +#46978 = CARTESIAN_POINT('',(0.E+000,2.680514631548)); +#46979 = CARTESIAN_POINT('',(1.570796326795,2.680514631548)); +#46980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46981 = ORIENTED_EDGE('',*,*,#46982,.T.); +#46982 = EDGE_CURVE('',#46955,#46983,#46985,.T.); +#46983 = VERTEX_POINT('',#46984); +#46984 = CARTESIAN_POINT('',(1.115,0.265,1.55)); +#46985 = SURFACE_CURVE('',#46986,(#46990,#46997),.PCURVE_S1.); +#46986 = LINE('',#46987,#46988); +#46987 = CARTESIAN_POINT('',(1.115,0.245,1.55)); +#46988 = VECTOR('',#46989,1.); +#46989 = DIRECTION('',(1.110223024625E-014,1.,0.E+000)); +#46990 = PCURVE('',#46816,#46991); +#46991 = DEFINITIONAL_REPRESENTATION('',(#46992),#46996); +#46992 = LINE('',#46993,#46994); +#46993 = CARTESIAN_POINT('',(-1.55,0.245)); +#46994 = VECTOR('',#46995,1.); +#46995 = DIRECTION('',(0.E+000,1.)); +#46996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#46997 = PCURVE('',#46998,#47003); +#46998 = PLANE('',#46999); +#46999 = AXIS2_PLACEMENT_3D('',#47000,#47001,#47002); +#47000 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.55)); +#47001 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47002 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47003 = DEFINITIONAL_REPRESENTATION('',(#47004),#47008); +#47004 = LINE('',#47005,#47006); +#47005 = CARTESIAN_POINT('',(1.115,0.245)); +#47006 = VECTOR('',#47007,1.); +#47007 = DIRECTION('',(1.110223024625E-014,1.)); +#47008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47009 = ORIENTED_EDGE('',*,*,#47010,.F.); +#47010 = EDGE_CURVE('',#46907,#46983,#47011,.T.); +#47011 = SURFACE_CURVE('',#47012,(#47016,#47023),.PCURVE_S1.); +#47012 = LINE('',#47013,#47014); +#47013 = CARTESIAN_POINT('',(1.115,0.265,1.15)); +#47014 = VECTOR('',#47015,1.); +#47015 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47016 = PCURVE('',#46816,#47017); +#47017 = DEFINITIONAL_REPRESENTATION('',(#47018),#47022); +#47018 = LINE('',#47019,#47020); +#47019 = CARTESIAN_POINT('',(-1.15,0.265)); +#47020 = VECTOR('',#47021,1.); +#47021 = DIRECTION('',(-1.,0.E+000)); +#47022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47023 = PCURVE('',#47024,#47029); +#47024 = PLANE('',#47025); +#47025 = AXIS2_PLACEMENT_3D('',#47026,#47027,#47028); +#47026 = CARTESIAN_POINT('',(1.115,0.265,-1.15)); +#47027 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47028 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47029 = DEFINITIONAL_REPRESENTATION('',(#47030),#47034); +#47030 = LINE('',#47031,#47032); +#47031 = CARTESIAN_POINT('',(2.3,0.E+000)); +#47032 = VECTOR('',#47033,1.); +#47033 = DIRECTION('',(1.,0.E+000)); +#47034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47035 = ADVANCED_FACE('',(#47036),#46871,.T.); +#47036 = FACE_BOUND('',#47037,.T.); +#47037 = EDGE_LOOP('',(#47038,#47039,#47040,#47063)); +#47038 = ORIENTED_EDGE('',*,*,#46906,.T.); +#47039 = ORIENTED_EDGE('',*,*,#46855,.T.); +#47040 = ORIENTED_EDGE('',*,*,#47041,.F.); +#47041 = EDGE_CURVE('',#47042,#46856,#47044,.T.); +#47042 = VERTEX_POINT('',#47043); +#47043 = CARTESIAN_POINT('',(1.485,0.265,1.15)); +#47044 = SURFACE_CURVE('',#47045,(#47050,#47056),.PCURVE_S1.); +#47045 = CIRCLE('',#47046,0.1); +#47046 = AXIS2_PLACEMENT_3D('',#47047,#47048,#47049); +#47047 = CARTESIAN_POINT('',(1.485,0.265,1.05)); +#47048 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47049 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47050 = PCURVE('',#46871,#47051); +#47051 = DEFINITIONAL_REPRESENTATION('',(#47052),#47055); +#47052 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47053,#47054),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#44661 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#44662 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#44663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44664 = PCURVE('',#43204,#44665); -#44665 = DEFINITIONAL_REPRESENTATION('',(#44666),#44670); -#44666 = CIRCLE('',#44667,0.1); -#44667 = AXIS2_PLACEMENT_2D('',#44668,#44669); -#44668 = CARTESIAN_POINT('',(-1.05,0.265)); -#44669 = DIRECTION('',(-1.,0.E+000)); -#44670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44671 = ORIENTED_EDGE('',*,*,#44672,.F.); -#44672 = EDGE_CURVE('',#44515,#44650,#44673,.T.); -#44673 = SURFACE_CURVE('',#44674,(#44678,#44684),.PCURVE_S1.); -#44674 = LINE('',#44675,#44676); -#44675 = CARTESIAN_POINT('',(1.115,0.265,1.15)); -#44676 = VECTOR('',#44677,1.); -#44677 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44678 = PCURVE('',#44479,#44679); -#44679 = DEFINITIONAL_REPRESENTATION('',(#44680),#44683); -#44680 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44681,#44682),.UNSPECIFIED., +#47053 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#47054 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#47055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47056 = PCURVE('',#45596,#47057); +#47057 = DEFINITIONAL_REPRESENTATION('',(#47058),#47062); +#47058 = CIRCLE('',#47059,0.1); +#47059 = AXIS2_PLACEMENT_2D('',#47060,#47061); +#47060 = CARTESIAN_POINT('',(-1.05,0.265)); +#47061 = DIRECTION('',(-1.,0.E+000)); +#47062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47063 = ORIENTED_EDGE('',*,*,#47064,.F.); +#47064 = EDGE_CURVE('',#46907,#47042,#47065,.T.); +#47065 = SURFACE_CURVE('',#47066,(#47070,#47076),.PCURVE_S1.); +#47066 = LINE('',#47067,#47068); +#47067 = CARTESIAN_POINT('',(1.115,0.265,1.15)); +#47068 = VECTOR('',#47069,1.); +#47069 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47070 = PCURVE('',#46871,#47071); +#47071 = DEFINITIONAL_REPRESENTATION('',(#47072),#47075); +#47072 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47073,#47074),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#44681 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#44682 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#44683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44684 = PCURVE('',#44632,#44685); -#44685 = DEFINITIONAL_REPRESENTATION('',(#44686),#44690); -#44686 = LINE('',#44687,#44688); -#44687 = CARTESIAN_POINT('',(2.3,0.E+000)); -#44688 = VECTOR('',#44689,1.); -#44689 = DIRECTION('',(0.E+000,1.)); -#44690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44691 = ADVANCED_FACE('',(#44692),#44632,.F.); -#44692 = FACE_BOUND('',#44693,.F.); -#44693 = EDGE_LOOP('',(#44694,#44695,#44696,#44719)); -#44694 = ORIENTED_EDGE('',*,*,#44672,.F.); -#44695 = ORIENTED_EDGE('',*,*,#44618,.T.); -#44696 = ORIENTED_EDGE('',*,*,#44697,.T.); -#44697 = EDGE_CURVE('',#44591,#44698,#44700,.T.); -#44698 = VERTEX_POINT('',#44699); -#44699 = CARTESIAN_POINT('',(1.485,0.265,1.55)); -#44700 = SURFACE_CURVE('',#44701,(#44705,#44712),.PCURVE_S1.); -#44701 = LINE('',#44702,#44703); -#44702 = CARTESIAN_POINT('',(1.115,0.265,1.55)); -#44703 = VECTOR('',#44704,1.); -#44704 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44705 = PCURVE('',#44632,#44706); -#44706 = DEFINITIONAL_REPRESENTATION('',(#44707),#44711); -#44707 = LINE('',#44708,#44709); -#44708 = CARTESIAN_POINT('',(2.7,0.E+000)); -#44709 = VECTOR('',#44710,1.); -#44710 = DIRECTION('',(0.E+000,1.)); -#44711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44712 = PCURVE('',#44606,#44713); -#44713 = DEFINITIONAL_REPRESENTATION('',(#44714),#44718); -#44714 = LINE('',#44715,#44716); -#44715 = CARTESIAN_POINT('',(1.115,0.265)); -#44716 = VECTOR('',#44717,1.); -#44717 = DIRECTION('',(1.,0.E+000)); -#44718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44719 = ORIENTED_EDGE('',*,*,#44720,.F.); -#44720 = EDGE_CURVE('',#44650,#44698,#44721,.T.); -#44721 = SURFACE_CURVE('',#44722,(#44726,#44733),.PCURVE_S1.); -#44722 = LINE('',#44723,#44724); -#44723 = CARTESIAN_POINT('',(1.485,0.265,1.15)); -#44724 = VECTOR('',#44725,1.); -#44725 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44726 = PCURVE('',#44632,#44727); -#44727 = DEFINITIONAL_REPRESENTATION('',(#44728),#44732); -#44728 = LINE('',#44729,#44730); -#44729 = CARTESIAN_POINT('',(2.3,0.37)); -#44730 = VECTOR('',#44731,1.); -#44731 = DIRECTION('',(1.,0.E+000)); -#44732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44733 = PCURVE('',#43204,#44734); -#44734 = DEFINITIONAL_REPRESENTATION('',(#44735),#44739); -#44735 = LINE('',#44736,#44737); -#44736 = CARTESIAN_POINT('',(-1.15,0.265)); -#44737 = VECTOR('',#44738,1.); -#44738 = DIRECTION('',(-1.,0.E+000)); -#44739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44740 = ADVANCED_FACE('',(#44741),#44606,.T.); -#44741 = FACE_BOUND('',#44742,.F.); -#44742 = EDGE_LOOP('',(#44743,#44744,#44766,#44789,#44817,#44840,#44867, - #44890,#44918,#44941,#44968,#44991,#45019,#45042,#45069,#45092, - #45120,#45143,#45170,#45197,#45224,#45251,#45278,#45299)); -#44743 = ORIENTED_EDGE('',*,*,#44590,.F.); -#44744 = ORIENTED_EDGE('',*,*,#44745,.F.); -#44745 = EDGE_CURVE('',#44746,#44563,#44748,.T.); -#44746 = VERTEX_POINT('',#44747); -#44747 = CARTESIAN_POINT('',(0.835,0.245,1.55)); -#44748 = SURFACE_CURVE('',#44749,(#44753,#44760),.PCURVE_S1.); -#44749 = LINE('',#44750,#44751); -#44750 = CARTESIAN_POINT('',(0.835,0.245,1.55)); -#44751 = VECTOR('',#44752,1.); -#44752 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44753 = PCURVE('',#44606,#44754); -#44754 = DEFINITIONAL_REPRESENTATION('',(#44755),#44759); -#44755 = LINE('',#44756,#44757); -#44756 = CARTESIAN_POINT('',(0.835,0.245)); -#44757 = VECTOR('',#44758,1.); -#44758 = DIRECTION('',(1.,0.E+000)); -#44759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44760 = PCURVE('',#44579,#44761); -#44761 = DEFINITIONAL_REPRESENTATION('',(#44762),#44765); -#44762 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44763,#44764),.UNSPECIFIED., +#47073 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#47074 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#47075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47076 = PCURVE('',#47024,#47077); +#47077 = DEFINITIONAL_REPRESENTATION('',(#47078),#47082); +#47078 = LINE('',#47079,#47080); +#47079 = CARTESIAN_POINT('',(2.3,0.E+000)); +#47080 = VECTOR('',#47081,1.); +#47081 = DIRECTION('',(0.E+000,1.)); +#47082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47083 = ADVANCED_FACE('',(#47084),#47024,.F.); +#47084 = FACE_BOUND('',#47085,.F.); +#47085 = EDGE_LOOP('',(#47086,#47087,#47088,#47111)); +#47086 = ORIENTED_EDGE('',*,*,#47064,.F.); +#47087 = ORIENTED_EDGE('',*,*,#47010,.T.); +#47088 = ORIENTED_EDGE('',*,*,#47089,.T.); +#47089 = EDGE_CURVE('',#46983,#47090,#47092,.T.); +#47090 = VERTEX_POINT('',#47091); +#47091 = CARTESIAN_POINT('',(1.485,0.265,1.55)); +#47092 = SURFACE_CURVE('',#47093,(#47097,#47104),.PCURVE_S1.); +#47093 = LINE('',#47094,#47095); +#47094 = CARTESIAN_POINT('',(1.115,0.265,1.55)); +#47095 = VECTOR('',#47096,1.); +#47096 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47097 = PCURVE('',#47024,#47098); +#47098 = DEFINITIONAL_REPRESENTATION('',(#47099),#47103); +#47099 = LINE('',#47100,#47101); +#47100 = CARTESIAN_POINT('',(2.7,0.E+000)); +#47101 = VECTOR('',#47102,1.); +#47102 = DIRECTION('',(0.E+000,1.)); +#47103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47104 = PCURVE('',#46998,#47105); +#47105 = DEFINITIONAL_REPRESENTATION('',(#47106),#47110); +#47106 = LINE('',#47107,#47108); +#47107 = CARTESIAN_POINT('',(1.115,0.265)); +#47108 = VECTOR('',#47109,1.); +#47109 = DIRECTION('',(1.,0.E+000)); +#47110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47111 = ORIENTED_EDGE('',*,*,#47112,.F.); +#47112 = EDGE_CURVE('',#47042,#47090,#47113,.T.); +#47113 = SURFACE_CURVE('',#47114,(#47118,#47125),.PCURVE_S1.); +#47114 = LINE('',#47115,#47116); +#47115 = CARTESIAN_POINT('',(1.485,0.265,1.15)); +#47116 = VECTOR('',#47117,1.); +#47117 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47118 = PCURVE('',#47024,#47119); +#47119 = DEFINITIONAL_REPRESENTATION('',(#47120),#47124); +#47120 = LINE('',#47121,#47122); +#47121 = CARTESIAN_POINT('',(2.3,0.37)); +#47122 = VECTOR('',#47123,1.); +#47123 = DIRECTION('',(1.,0.E+000)); +#47124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47125 = PCURVE('',#45596,#47126); +#47126 = DEFINITIONAL_REPRESENTATION('',(#47127),#47131); +#47127 = LINE('',#47128,#47129); +#47128 = CARTESIAN_POINT('',(-1.15,0.265)); +#47129 = VECTOR('',#47130,1.); +#47130 = DIRECTION('',(-1.,0.E+000)); +#47131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47132 = ADVANCED_FACE('',(#47133),#46998,.T.); +#47133 = FACE_BOUND('',#47134,.F.); +#47134 = EDGE_LOOP('',(#47135,#47136,#47158,#47181,#47209,#47232,#47259, + #47282,#47310,#47333,#47360,#47383,#47411,#47434,#47461,#47484, + #47512,#47535,#47562,#47589,#47616,#47643,#47670,#47691)); +#47135 = ORIENTED_EDGE('',*,*,#46982,.F.); +#47136 = ORIENTED_EDGE('',*,*,#47137,.F.); +#47137 = EDGE_CURVE('',#47138,#46955,#47140,.T.); +#47138 = VERTEX_POINT('',#47139); +#47139 = CARTESIAN_POINT('',(0.835,0.245,1.55)); +#47140 = SURFACE_CURVE('',#47141,(#47145,#47152),.PCURVE_S1.); +#47141 = LINE('',#47142,#47143); +#47142 = CARTESIAN_POINT('',(0.835,0.245,1.55)); +#47143 = VECTOR('',#47144,1.); +#47144 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47145 = PCURVE('',#46998,#47146); +#47146 = DEFINITIONAL_REPRESENTATION('',(#47147),#47151); +#47147 = LINE('',#47148,#47149); +#47148 = CARTESIAN_POINT('',(0.835,0.245)); +#47149 = VECTOR('',#47150,1.); +#47150 = DIRECTION('',(1.,0.E+000)); +#47151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47152 = PCURVE('',#46971,#47153); +#47153 = DEFINITIONAL_REPRESENTATION('',(#47154),#47157); +#47154 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47155,#47156),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#44763 = CARTESIAN_POINT('',(0.E+000,2.400514631548)); -#44764 = CARTESIAN_POINT('',(0.E+000,2.680514631548)); -#44765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44766 = ORIENTED_EDGE('',*,*,#44767,.T.); -#44767 = EDGE_CURVE('',#44746,#44768,#44770,.T.); -#44768 = VERTEX_POINT('',#44769); -#44769 = CARTESIAN_POINT('',(0.835,0.265,1.55)); -#44770 = SURFACE_CURVE('',#44771,(#44775,#44782),.PCURVE_S1.); -#44771 = LINE('',#44772,#44773); -#44772 = CARTESIAN_POINT('',(0.835,0.245,1.55)); -#44773 = VECTOR('',#44774,1.); -#44774 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44775 = PCURVE('',#44606,#44776); -#44776 = DEFINITIONAL_REPRESENTATION('',(#44777),#44781); -#44777 = LINE('',#44778,#44779); -#44778 = CARTESIAN_POINT('',(0.835,0.245)); -#44779 = VECTOR('',#44780,1.); -#44780 = DIRECTION('',(0.E+000,1.)); -#44781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44782 = PCURVE('',#44370,#44783); -#44783 = DEFINITIONAL_REPRESENTATION('',(#44784),#44788); -#44784 = LINE('',#44785,#44786); -#44785 = CARTESIAN_POINT('',(-1.55,0.245)); -#44786 = VECTOR('',#44787,1.); -#44787 = DIRECTION('',(0.E+000,1.)); -#44788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44789 = ORIENTED_EDGE('',*,*,#44790,.F.); -#44790 = EDGE_CURVE('',#44791,#44768,#44793,.T.); -#44791 = VERTEX_POINT('',#44792); -#44792 = CARTESIAN_POINT('',(0.465,0.265,1.55)); -#44793 = SURFACE_CURVE('',#44794,(#44798,#44805),.PCURVE_S1.); -#44794 = LINE('',#44795,#44796); -#44795 = CARTESIAN_POINT('',(0.465,0.265,1.55)); -#44796 = VECTOR('',#44797,1.); -#44797 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44798 = PCURVE('',#44606,#44799); -#44799 = DEFINITIONAL_REPRESENTATION('',(#44800),#44804); -#44800 = LINE('',#44801,#44802); -#44801 = CARTESIAN_POINT('',(0.465,0.265)); -#44802 = VECTOR('',#44803,1.); -#44803 = DIRECTION('',(1.,0.E+000)); -#44804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44805 = PCURVE('',#44806,#44811); -#44806 = PLANE('',#44807); -#44807 = AXIS2_PLACEMENT_3D('',#44808,#44809,#44810); -#44808 = CARTESIAN_POINT('',(0.465,0.265,-1.15)); -#44809 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44810 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44811 = DEFINITIONAL_REPRESENTATION('',(#44812),#44816); -#44812 = LINE('',#44813,#44814); -#44813 = CARTESIAN_POINT('',(2.7,0.E+000)); -#44814 = VECTOR('',#44815,1.); -#44815 = DIRECTION('',(0.E+000,1.)); -#44816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44817 = ORIENTED_EDGE('',*,*,#44818,.F.); -#44818 = EDGE_CURVE('',#44819,#44791,#44821,.T.); -#44819 = VERTEX_POINT('',#44820); -#44820 = CARTESIAN_POINT('',(0.465,0.245,1.55)); -#44821 = SURFACE_CURVE('',#44822,(#44826,#44833),.PCURVE_S1.); -#44822 = LINE('',#44823,#44824); -#44823 = CARTESIAN_POINT('',(0.465,0.245,1.55)); -#44824 = VECTOR('',#44825,1.); -#44825 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44826 = PCURVE('',#44606,#44827); -#44827 = DEFINITIONAL_REPRESENTATION('',(#44828),#44832); -#44828 = LINE('',#44829,#44830); -#44829 = CARTESIAN_POINT('',(0.465,0.245)); -#44830 = VECTOR('',#44831,1.); -#44831 = DIRECTION('',(0.E+000,1.)); -#44832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44833 = PCURVE('',#44314,#44834); -#44834 = DEFINITIONAL_REPRESENTATION('',(#44835),#44839); -#44835 = LINE('',#44836,#44837); -#44836 = CARTESIAN_POINT('',(-1.55,0.245)); -#44837 = VECTOR('',#44838,1.); -#44838 = DIRECTION('',(0.E+000,1.)); -#44839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44840 = ORIENTED_EDGE('',*,*,#44841,.F.); -#44841 = EDGE_CURVE('',#44842,#44819,#44844,.T.); -#44842 = VERTEX_POINT('',#44843); -#44843 = CARTESIAN_POINT('',(0.185,0.245,1.55)); -#44844 = SURFACE_CURVE('',#44845,(#44849,#44856),.PCURVE_S1.); -#44845 = LINE('',#44846,#44847); -#44846 = CARTESIAN_POINT('',(0.185,0.245,1.55)); -#44847 = VECTOR('',#44848,1.); -#44848 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44849 = PCURVE('',#44606,#44850); -#44850 = DEFINITIONAL_REPRESENTATION('',(#44851),#44855); -#44851 = LINE('',#44852,#44853); -#44852 = CARTESIAN_POINT('',(0.185,0.245)); -#44853 = VECTOR('',#44854,1.); -#44854 = DIRECTION('',(1.,0.E+000)); -#44855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44856 = PCURVE('',#44857,#44862); -#44857 = CYLINDRICAL_SURFACE('',#44858,0.2); -#44858 = AXIS2_PLACEMENT_3D('',#44859,#44860,#44861); -#44859 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#44860 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44861 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44862 = DEFINITIONAL_REPRESENTATION('',(#44863),#44866); -#44863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44864,#44865),.UNSPECIFIED., +#47155 = CARTESIAN_POINT('',(0.E+000,2.400514631548)); +#47156 = CARTESIAN_POINT('',(0.E+000,2.680514631548)); +#47157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47158 = ORIENTED_EDGE('',*,*,#47159,.T.); +#47159 = EDGE_CURVE('',#47138,#47160,#47162,.T.); +#47160 = VERTEX_POINT('',#47161); +#47161 = CARTESIAN_POINT('',(0.835,0.265,1.55)); +#47162 = SURFACE_CURVE('',#47163,(#47167,#47174),.PCURVE_S1.); +#47163 = LINE('',#47164,#47165); +#47164 = CARTESIAN_POINT('',(0.835,0.245,1.55)); +#47165 = VECTOR('',#47166,1.); +#47166 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47167 = PCURVE('',#46998,#47168); +#47168 = DEFINITIONAL_REPRESENTATION('',(#47169),#47173); +#47169 = LINE('',#47170,#47171); +#47170 = CARTESIAN_POINT('',(0.835,0.245)); +#47171 = VECTOR('',#47172,1.); +#47172 = DIRECTION('',(0.E+000,1.)); +#47173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47174 = PCURVE('',#46762,#47175); +#47175 = DEFINITIONAL_REPRESENTATION('',(#47176),#47180); +#47176 = LINE('',#47177,#47178); +#47177 = CARTESIAN_POINT('',(-1.55,0.245)); +#47178 = VECTOR('',#47179,1.); +#47179 = DIRECTION('',(0.E+000,1.)); +#47180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47181 = ORIENTED_EDGE('',*,*,#47182,.F.); +#47182 = EDGE_CURVE('',#47183,#47160,#47185,.T.); +#47183 = VERTEX_POINT('',#47184); +#47184 = CARTESIAN_POINT('',(0.465,0.265,1.55)); +#47185 = SURFACE_CURVE('',#47186,(#47190,#47197),.PCURVE_S1.); +#47186 = LINE('',#47187,#47188); +#47187 = CARTESIAN_POINT('',(0.465,0.265,1.55)); +#47188 = VECTOR('',#47189,1.); +#47189 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47190 = PCURVE('',#46998,#47191); +#47191 = DEFINITIONAL_REPRESENTATION('',(#47192),#47196); +#47192 = LINE('',#47193,#47194); +#47193 = CARTESIAN_POINT('',(0.465,0.265)); +#47194 = VECTOR('',#47195,1.); +#47195 = DIRECTION('',(1.,0.E+000)); +#47196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47197 = PCURVE('',#47198,#47203); +#47198 = PLANE('',#47199); +#47199 = AXIS2_PLACEMENT_3D('',#47200,#47201,#47202); +#47200 = CARTESIAN_POINT('',(0.465,0.265,-1.15)); +#47201 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47202 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47203 = DEFINITIONAL_REPRESENTATION('',(#47204),#47208); +#47204 = LINE('',#47205,#47206); +#47205 = CARTESIAN_POINT('',(2.7,0.E+000)); +#47206 = VECTOR('',#47207,1.); +#47207 = DIRECTION('',(0.E+000,1.)); +#47208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47209 = ORIENTED_EDGE('',*,*,#47210,.F.); +#47210 = EDGE_CURVE('',#47211,#47183,#47213,.T.); +#47211 = VERTEX_POINT('',#47212); +#47212 = CARTESIAN_POINT('',(0.465,0.245,1.55)); +#47213 = SURFACE_CURVE('',#47214,(#47218,#47225),.PCURVE_S1.); +#47214 = LINE('',#47215,#47216); +#47215 = CARTESIAN_POINT('',(0.465,0.245,1.55)); +#47216 = VECTOR('',#47217,1.); +#47217 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47218 = PCURVE('',#46998,#47219); +#47219 = DEFINITIONAL_REPRESENTATION('',(#47220),#47224); +#47220 = LINE('',#47221,#47222); +#47221 = CARTESIAN_POINT('',(0.465,0.245)); +#47222 = VECTOR('',#47223,1.); +#47223 = DIRECTION('',(0.E+000,1.)); +#47224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47225 = PCURVE('',#46706,#47226); +#47226 = DEFINITIONAL_REPRESENTATION('',(#47227),#47231); +#47227 = LINE('',#47228,#47229); +#47228 = CARTESIAN_POINT('',(-1.55,0.245)); +#47229 = VECTOR('',#47230,1.); +#47230 = DIRECTION('',(0.E+000,1.)); +#47231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47232 = ORIENTED_EDGE('',*,*,#47233,.F.); +#47233 = EDGE_CURVE('',#47234,#47211,#47236,.T.); +#47234 = VERTEX_POINT('',#47235); +#47235 = CARTESIAN_POINT('',(0.185,0.245,1.55)); +#47236 = SURFACE_CURVE('',#47237,(#47241,#47248),.PCURVE_S1.); +#47237 = LINE('',#47238,#47239); +#47238 = CARTESIAN_POINT('',(0.185,0.245,1.55)); +#47239 = VECTOR('',#47240,1.); +#47240 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47241 = PCURVE('',#46998,#47242); +#47242 = DEFINITIONAL_REPRESENTATION('',(#47243),#47247); +#47243 = LINE('',#47244,#47245); +#47244 = CARTESIAN_POINT('',(0.185,0.245)); +#47245 = VECTOR('',#47246,1.); +#47246 = DIRECTION('',(1.,0.E+000)); +#47247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47248 = PCURVE('',#47249,#47254); +#47249 = CYLINDRICAL_SURFACE('',#47250,0.2); +#47250 = AXIS2_PLACEMENT_3D('',#47251,#47252,#47253); +#47251 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#47252 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47253 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47254 = DEFINITIONAL_REPRESENTATION('',(#47255),#47258); +#47255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47256,#47257),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#44864 = CARTESIAN_POINT('',(0.E+000,1.750514631548)); -#44865 = CARTESIAN_POINT('',(0.E+000,2.030514631548)); -#44866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44867 = ORIENTED_EDGE('',*,*,#44868,.T.); -#44868 = EDGE_CURVE('',#44842,#44869,#44871,.T.); -#44869 = VERTEX_POINT('',#44870); -#44870 = CARTESIAN_POINT('',(0.185,0.265,1.55)); -#44871 = SURFACE_CURVE('',#44872,(#44876,#44883),.PCURVE_S1.); -#44872 = LINE('',#44873,#44874); -#44873 = CARTESIAN_POINT('',(0.185,0.245,1.55)); -#44874 = VECTOR('',#44875,1.); -#44875 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44876 = PCURVE('',#44606,#44877); -#44877 = DEFINITIONAL_REPRESENTATION('',(#44878),#44882); -#44878 = LINE('',#44879,#44880); -#44879 = CARTESIAN_POINT('',(0.185,0.245)); -#44880 = VECTOR('',#44881,1.); -#44881 = DIRECTION('',(0.E+000,1.)); -#44882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44883 = PCURVE('',#44258,#44884); -#44884 = DEFINITIONAL_REPRESENTATION('',(#44885),#44889); -#44885 = LINE('',#44886,#44887); -#44886 = CARTESIAN_POINT('',(-1.55,0.245)); -#44887 = VECTOR('',#44888,1.); -#44888 = DIRECTION('',(0.E+000,1.)); -#44889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44890 = ORIENTED_EDGE('',*,*,#44891,.F.); -#44891 = EDGE_CURVE('',#44892,#44869,#44894,.T.); -#44892 = VERTEX_POINT('',#44893); -#44893 = CARTESIAN_POINT('',(-0.185,0.265,1.55)); -#44894 = SURFACE_CURVE('',#44895,(#44899,#44906),.PCURVE_S1.); -#44895 = LINE('',#44896,#44897); -#44896 = CARTESIAN_POINT('',(-0.185,0.265,1.55)); -#44897 = VECTOR('',#44898,1.); -#44898 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44899 = PCURVE('',#44606,#44900); -#44900 = DEFINITIONAL_REPRESENTATION('',(#44901),#44905); -#44901 = LINE('',#44902,#44903); -#44902 = CARTESIAN_POINT('',(-0.185,0.265)); -#44903 = VECTOR('',#44904,1.); -#44904 = DIRECTION('',(1.,0.E+000)); -#44905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44906 = PCURVE('',#44907,#44912); -#44907 = PLANE('',#44908); -#44908 = AXIS2_PLACEMENT_3D('',#44909,#44910,#44911); -#44909 = CARTESIAN_POINT('',(-0.185,0.265,-1.15)); -#44910 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44911 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44912 = DEFINITIONAL_REPRESENTATION('',(#44913),#44917); -#44913 = LINE('',#44914,#44915); -#44914 = CARTESIAN_POINT('',(2.7,0.E+000)); -#44915 = VECTOR('',#44916,1.); -#44916 = DIRECTION('',(0.E+000,1.)); -#44917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44918 = ORIENTED_EDGE('',*,*,#44919,.F.); -#44919 = EDGE_CURVE('',#44920,#44892,#44922,.T.); -#44920 = VERTEX_POINT('',#44921); -#44921 = CARTESIAN_POINT('',(-0.185,0.245,1.55)); -#44922 = SURFACE_CURVE('',#44923,(#44927,#44934),.PCURVE_S1.); -#44923 = LINE('',#44924,#44925); -#44924 = CARTESIAN_POINT('',(-0.185,0.245,1.55)); -#44925 = VECTOR('',#44926,1.); -#44926 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44927 = PCURVE('',#44606,#44928); -#44928 = DEFINITIONAL_REPRESENTATION('',(#44929),#44933); -#44929 = LINE('',#44930,#44931); -#44930 = CARTESIAN_POINT('',(-0.185,0.245)); -#44931 = VECTOR('',#44932,1.); -#44932 = DIRECTION('',(0.E+000,1.)); -#44933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44934 = PCURVE('',#44202,#44935); -#44935 = DEFINITIONAL_REPRESENTATION('',(#44936),#44940); -#44936 = LINE('',#44937,#44938); -#44937 = CARTESIAN_POINT('',(-1.55,0.245)); -#44938 = VECTOR('',#44939,1.); -#44939 = DIRECTION('',(0.E+000,1.)); -#44940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44941 = ORIENTED_EDGE('',*,*,#44942,.F.); -#44942 = EDGE_CURVE('',#44943,#44920,#44945,.T.); -#44943 = VERTEX_POINT('',#44944); -#44944 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); -#44945 = SURFACE_CURVE('',#44946,(#44950,#44957),.PCURVE_S1.); -#44946 = LINE('',#44947,#44948); -#44947 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); -#44948 = VECTOR('',#44949,1.); -#44949 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44950 = PCURVE('',#44606,#44951); -#44951 = DEFINITIONAL_REPRESENTATION('',(#44952),#44956); -#44952 = LINE('',#44953,#44954); -#44953 = CARTESIAN_POINT('',(-0.465,0.245)); -#44954 = VECTOR('',#44955,1.); -#44955 = DIRECTION('',(1.,0.E+000)); -#44956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44957 = PCURVE('',#44958,#44963); -#44958 = CYLINDRICAL_SURFACE('',#44959,0.2); -#44959 = AXIS2_PLACEMENT_3D('',#44960,#44961,#44962); -#44960 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#44961 = DIRECTION('',(1.,0.E+000,0.E+000)); -#44962 = DIRECTION('',(0.E+000,0.E+000,1.)); -#44963 = DEFINITIONAL_REPRESENTATION('',(#44964),#44967); -#44964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#44965,#44966),.UNSPECIFIED., +#47256 = CARTESIAN_POINT('',(0.E+000,1.750514631548)); +#47257 = CARTESIAN_POINT('',(0.E+000,2.030514631548)); +#47258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47259 = ORIENTED_EDGE('',*,*,#47260,.T.); +#47260 = EDGE_CURVE('',#47234,#47261,#47263,.T.); +#47261 = VERTEX_POINT('',#47262); +#47262 = CARTESIAN_POINT('',(0.185,0.265,1.55)); +#47263 = SURFACE_CURVE('',#47264,(#47268,#47275),.PCURVE_S1.); +#47264 = LINE('',#47265,#47266); +#47265 = CARTESIAN_POINT('',(0.185,0.245,1.55)); +#47266 = VECTOR('',#47267,1.); +#47267 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47268 = PCURVE('',#46998,#47269); +#47269 = DEFINITIONAL_REPRESENTATION('',(#47270),#47274); +#47270 = LINE('',#47271,#47272); +#47271 = CARTESIAN_POINT('',(0.185,0.245)); +#47272 = VECTOR('',#47273,1.); +#47273 = DIRECTION('',(0.E+000,1.)); +#47274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47275 = PCURVE('',#46650,#47276); +#47276 = DEFINITIONAL_REPRESENTATION('',(#47277),#47281); +#47277 = LINE('',#47278,#47279); +#47278 = CARTESIAN_POINT('',(-1.55,0.245)); +#47279 = VECTOR('',#47280,1.); +#47280 = DIRECTION('',(0.E+000,1.)); +#47281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47282 = ORIENTED_EDGE('',*,*,#47283,.F.); +#47283 = EDGE_CURVE('',#47284,#47261,#47286,.T.); +#47284 = VERTEX_POINT('',#47285); +#47285 = CARTESIAN_POINT('',(-0.185,0.265,1.55)); +#47286 = SURFACE_CURVE('',#47287,(#47291,#47298),.PCURVE_S1.); +#47287 = LINE('',#47288,#47289); +#47288 = CARTESIAN_POINT('',(-0.185,0.265,1.55)); +#47289 = VECTOR('',#47290,1.); +#47290 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47291 = PCURVE('',#46998,#47292); +#47292 = DEFINITIONAL_REPRESENTATION('',(#47293),#47297); +#47293 = LINE('',#47294,#47295); +#47294 = CARTESIAN_POINT('',(-0.185,0.265)); +#47295 = VECTOR('',#47296,1.); +#47296 = DIRECTION('',(1.,0.E+000)); +#47297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47298 = PCURVE('',#47299,#47304); +#47299 = PLANE('',#47300); +#47300 = AXIS2_PLACEMENT_3D('',#47301,#47302,#47303); +#47301 = CARTESIAN_POINT('',(-0.185,0.265,-1.15)); +#47302 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47303 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47304 = DEFINITIONAL_REPRESENTATION('',(#47305),#47309); +#47305 = LINE('',#47306,#47307); +#47306 = CARTESIAN_POINT('',(2.7,0.E+000)); +#47307 = VECTOR('',#47308,1.); +#47308 = DIRECTION('',(0.E+000,1.)); +#47309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47310 = ORIENTED_EDGE('',*,*,#47311,.F.); +#47311 = EDGE_CURVE('',#47312,#47284,#47314,.T.); +#47312 = VERTEX_POINT('',#47313); +#47313 = CARTESIAN_POINT('',(-0.185,0.245,1.55)); +#47314 = SURFACE_CURVE('',#47315,(#47319,#47326),.PCURVE_S1.); +#47315 = LINE('',#47316,#47317); +#47316 = CARTESIAN_POINT('',(-0.185,0.245,1.55)); +#47317 = VECTOR('',#47318,1.); +#47318 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47319 = PCURVE('',#46998,#47320); +#47320 = DEFINITIONAL_REPRESENTATION('',(#47321),#47325); +#47321 = LINE('',#47322,#47323); +#47322 = CARTESIAN_POINT('',(-0.185,0.245)); +#47323 = VECTOR('',#47324,1.); +#47324 = DIRECTION('',(0.E+000,1.)); +#47325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47326 = PCURVE('',#46594,#47327); +#47327 = DEFINITIONAL_REPRESENTATION('',(#47328),#47332); +#47328 = LINE('',#47329,#47330); +#47329 = CARTESIAN_POINT('',(-1.55,0.245)); +#47330 = VECTOR('',#47331,1.); +#47331 = DIRECTION('',(0.E+000,1.)); +#47332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47333 = ORIENTED_EDGE('',*,*,#47334,.F.); +#47334 = EDGE_CURVE('',#47335,#47312,#47337,.T.); +#47335 = VERTEX_POINT('',#47336); +#47336 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); +#47337 = SURFACE_CURVE('',#47338,(#47342,#47349),.PCURVE_S1.); +#47338 = LINE('',#47339,#47340); +#47339 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); +#47340 = VECTOR('',#47341,1.); +#47341 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47342 = PCURVE('',#46998,#47343); +#47343 = DEFINITIONAL_REPRESENTATION('',(#47344),#47348); +#47344 = LINE('',#47345,#47346); +#47345 = CARTESIAN_POINT('',(-0.465,0.245)); +#47346 = VECTOR('',#47347,1.); +#47347 = DIRECTION('',(1.,0.E+000)); +#47348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47349 = PCURVE('',#47350,#47355); +#47350 = CYLINDRICAL_SURFACE('',#47351,0.2); +#47351 = AXIS2_PLACEMENT_3D('',#47352,#47353,#47354); +#47352 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#47353 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47354 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47355 = DEFINITIONAL_REPRESENTATION('',(#47356),#47359); +#47356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47357,#47358),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#44965 = CARTESIAN_POINT('',(0.E+000,1.100514631548)); -#44966 = CARTESIAN_POINT('',(0.E+000,1.380514631548)); -#44967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44968 = ORIENTED_EDGE('',*,*,#44969,.T.); -#44969 = EDGE_CURVE('',#44943,#44970,#44972,.T.); -#44970 = VERTEX_POINT('',#44971); -#44971 = CARTESIAN_POINT('',(-0.465,0.265,1.55)); -#44972 = SURFACE_CURVE('',#44973,(#44977,#44984),.PCURVE_S1.); -#44973 = LINE('',#44974,#44975); -#44974 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); -#44975 = VECTOR('',#44976,1.); -#44976 = DIRECTION('',(0.E+000,1.,0.E+000)); -#44977 = PCURVE('',#44606,#44978); -#44978 = DEFINITIONAL_REPRESENTATION('',(#44979),#44983); -#44979 = LINE('',#44980,#44981); -#44980 = CARTESIAN_POINT('',(-0.465,0.245)); -#44981 = VECTOR('',#44982,1.); -#44982 = DIRECTION('',(0.E+000,1.)); -#44983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44984 = PCURVE('',#44146,#44985); -#44985 = DEFINITIONAL_REPRESENTATION('',(#44986),#44990); -#44986 = LINE('',#44987,#44988); -#44987 = CARTESIAN_POINT('',(-1.55,0.245)); -#44988 = VECTOR('',#44989,1.); -#44989 = DIRECTION('',(0.E+000,1.)); -#44990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#44991 = ORIENTED_EDGE('',*,*,#44992,.F.); -#44992 = EDGE_CURVE('',#44993,#44970,#44995,.T.); -#44993 = VERTEX_POINT('',#44994); -#44994 = CARTESIAN_POINT('',(-0.835,0.265,1.55)); -#44995 = SURFACE_CURVE('',#44996,(#45000,#45007),.PCURVE_S1.); -#44996 = LINE('',#44997,#44998); -#44997 = CARTESIAN_POINT('',(-0.835,0.265,1.55)); -#44998 = VECTOR('',#44999,1.); -#44999 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45000 = PCURVE('',#44606,#45001); -#45001 = DEFINITIONAL_REPRESENTATION('',(#45002),#45006); -#45002 = LINE('',#45003,#45004); -#45003 = CARTESIAN_POINT('',(-0.835,0.265)); -#45004 = VECTOR('',#45005,1.); -#45005 = DIRECTION('',(1.,0.E+000)); -#45006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45007 = PCURVE('',#45008,#45013); -#45008 = PLANE('',#45009); -#45009 = AXIS2_PLACEMENT_3D('',#45010,#45011,#45012); -#45010 = CARTESIAN_POINT('',(-0.835,0.265,-1.15)); -#45011 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45012 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45013 = DEFINITIONAL_REPRESENTATION('',(#45014),#45018); -#45014 = LINE('',#45015,#45016); -#45015 = CARTESIAN_POINT('',(2.7,0.E+000)); -#45016 = VECTOR('',#45017,1.); -#45017 = DIRECTION('',(0.E+000,1.)); -#45018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45019 = ORIENTED_EDGE('',*,*,#45020,.F.); -#45020 = EDGE_CURVE('',#45021,#44993,#45023,.T.); -#45021 = VERTEX_POINT('',#45022); -#45022 = CARTESIAN_POINT('',(-0.835,0.245,1.55)); -#45023 = SURFACE_CURVE('',#45024,(#45028,#45035),.PCURVE_S1.); -#45024 = LINE('',#45025,#45026); -#45025 = CARTESIAN_POINT('',(-0.835,0.245,1.55)); -#45026 = VECTOR('',#45027,1.); -#45027 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45028 = PCURVE('',#44606,#45029); -#45029 = DEFINITIONAL_REPRESENTATION('',(#45030),#45034); -#45030 = LINE('',#45031,#45032); -#45031 = CARTESIAN_POINT('',(-0.835,0.245)); -#45032 = VECTOR('',#45033,1.); -#45033 = DIRECTION('',(0.E+000,1.)); -#45034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45035 = PCURVE('',#44090,#45036); -#45036 = DEFINITIONAL_REPRESENTATION('',(#45037),#45041); -#45037 = LINE('',#45038,#45039); -#45038 = CARTESIAN_POINT('',(-1.55,0.245)); -#45039 = VECTOR('',#45040,1.); -#45040 = DIRECTION('',(0.E+000,1.)); -#45041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45042 = ORIENTED_EDGE('',*,*,#45043,.F.); -#45043 = EDGE_CURVE('',#45044,#45021,#45046,.T.); -#45044 = VERTEX_POINT('',#45045); -#45045 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); -#45046 = SURFACE_CURVE('',#45047,(#45051,#45058),.PCURVE_S1.); -#45047 = LINE('',#45048,#45049); -#45048 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); -#45049 = VECTOR('',#45050,1.); -#45050 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45051 = PCURVE('',#44606,#45052); -#45052 = DEFINITIONAL_REPRESENTATION('',(#45053),#45057); -#45053 = LINE('',#45054,#45055); -#45054 = CARTESIAN_POINT('',(-1.115,0.245)); -#45055 = VECTOR('',#45056,1.); -#45056 = DIRECTION('',(1.,0.E+000)); -#45057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45058 = PCURVE('',#45059,#45064); -#45059 = CYLINDRICAL_SURFACE('',#45060,0.2); -#45060 = AXIS2_PLACEMENT_3D('',#45061,#45062,#45063); -#45061 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#45062 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45063 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45064 = DEFINITIONAL_REPRESENTATION('',(#45065),#45068); -#45065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45066,#45067),.UNSPECIFIED., +#47357 = CARTESIAN_POINT('',(0.E+000,1.100514631548)); +#47358 = CARTESIAN_POINT('',(0.E+000,1.380514631548)); +#47359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47360 = ORIENTED_EDGE('',*,*,#47361,.T.); +#47361 = EDGE_CURVE('',#47335,#47362,#47364,.T.); +#47362 = VERTEX_POINT('',#47363); +#47363 = CARTESIAN_POINT('',(-0.465,0.265,1.55)); +#47364 = SURFACE_CURVE('',#47365,(#47369,#47376),.PCURVE_S1.); +#47365 = LINE('',#47366,#47367); +#47366 = CARTESIAN_POINT('',(-0.465,0.245,1.55)); +#47367 = VECTOR('',#47368,1.); +#47368 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47369 = PCURVE('',#46998,#47370); +#47370 = DEFINITIONAL_REPRESENTATION('',(#47371),#47375); +#47371 = LINE('',#47372,#47373); +#47372 = CARTESIAN_POINT('',(-0.465,0.245)); +#47373 = VECTOR('',#47374,1.); +#47374 = DIRECTION('',(0.E+000,1.)); +#47375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47376 = PCURVE('',#46538,#47377); +#47377 = DEFINITIONAL_REPRESENTATION('',(#47378),#47382); +#47378 = LINE('',#47379,#47380); +#47379 = CARTESIAN_POINT('',(-1.55,0.245)); +#47380 = VECTOR('',#47381,1.); +#47381 = DIRECTION('',(0.E+000,1.)); +#47382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47383 = ORIENTED_EDGE('',*,*,#47384,.F.); +#47384 = EDGE_CURVE('',#47385,#47362,#47387,.T.); +#47385 = VERTEX_POINT('',#47386); +#47386 = CARTESIAN_POINT('',(-0.835,0.265,1.55)); +#47387 = SURFACE_CURVE('',#47388,(#47392,#47399),.PCURVE_S1.); +#47388 = LINE('',#47389,#47390); +#47389 = CARTESIAN_POINT('',(-0.835,0.265,1.55)); +#47390 = VECTOR('',#47391,1.); +#47391 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47392 = PCURVE('',#46998,#47393); +#47393 = DEFINITIONAL_REPRESENTATION('',(#47394),#47398); +#47394 = LINE('',#47395,#47396); +#47395 = CARTESIAN_POINT('',(-0.835,0.265)); +#47396 = VECTOR('',#47397,1.); +#47397 = DIRECTION('',(1.,0.E+000)); +#47398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47399 = PCURVE('',#47400,#47405); +#47400 = PLANE('',#47401); +#47401 = AXIS2_PLACEMENT_3D('',#47402,#47403,#47404); +#47402 = CARTESIAN_POINT('',(-0.835,0.265,-1.15)); +#47403 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47404 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47405 = DEFINITIONAL_REPRESENTATION('',(#47406),#47410); +#47406 = LINE('',#47407,#47408); +#47407 = CARTESIAN_POINT('',(2.7,0.E+000)); +#47408 = VECTOR('',#47409,1.); +#47409 = DIRECTION('',(0.E+000,1.)); +#47410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47411 = ORIENTED_EDGE('',*,*,#47412,.F.); +#47412 = EDGE_CURVE('',#47413,#47385,#47415,.T.); +#47413 = VERTEX_POINT('',#47414); +#47414 = CARTESIAN_POINT('',(-0.835,0.245,1.55)); +#47415 = SURFACE_CURVE('',#47416,(#47420,#47427),.PCURVE_S1.); +#47416 = LINE('',#47417,#47418); +#47417 = CARTESIAN_POINT('',(-0.835,0.245,1.55)); +#47418 = VECTOR('',#47419,1.); +#47419 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47420 = PCURVE('',#46998,#47421); +#47421 = DEFINITIONAL_REPRESENTATION('',(#47422),#47426); +#47422 = LINE('',#47423,#47424); +#47423 = CARTESIAN_POINT('',(-0.835,0.245)); +#47424 = VECTOR('',#47425,1.); +#47425 = DIRECTION('',(0.E+000,1.)); +#47426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47427 = PCURVE('',#46482,#47428); +#47428 = DEFINITIONAL_REPRESENTATION('',(#47429),#47433); +#47429 = LINE('',#47430,#47431); +#47430 = CARTESIAN_POINT('',(-1.55,0.245)); +#47431 = VECTOR('',#47432,1.); +#47432 = DIRECTION('',(0.E+000,1.)); +#47433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47434 = ORIENTED_EDGE('',*,*,#47435,.F.); +#47435 = EDGE_CURVE('',#47436,#47413,#47438,.T.); +#47436 = VERTEX_POINT('',#47437); +#47437 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); +#47438 = SURFACE_CURVE('',#47439,(#47443,#47450),.PCURVE_S1.); +#47439 = LINE('',#47440,#47441); +#47440 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); +#47441 = VECTOR('',#47442,1.); +#47442 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47443 = PCURVE('',#46998,#47444); +#47444 = DEFINITIONAL_REPRESENTATION('',(#47445),#47449); +#47445 = LINE('',#47446,#47447); +#47446 = CARTESIAN_POINT('',(-1.115,0.245)); +#47447 = VECTOR('',#47448,1.); +#47448 = DIRECTION('',(1.,0.E+000)); +#47449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47450 = PCURVE('',#47451,#47456); +#47451 = CYLINDRICAL_SURFACE('',#47452,0.2); +#47452 = AXIS2_PLACEMENT_3D('',#47453,#47454,#47455); +#47453 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#47454 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47455 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47456 = DEFINITIONAL_REPRESENTATION('',(#47457),#47460); +#47457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47458,#47459),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#45066 = CARTESIAN_POINT('',(0.E+000,0.450514631548)); -#45067 = CARTESIAN_POINT('',(0.E+000,0.730514631548)); -#45068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45069 = ORIENTED_EDGE('',*,*,#45070,.T.); -#45070 = EDGE_CURVE('',#45044,#45071,#45073,.T.); -#45071 = VERTEX_POINT('',#45072); -#45072 = CARTESIAN_POINT('',(-1.115,0.265,1.55)); -#45073 = SURFACE_CURVE('',#45074,(#45078,#45085),.PCURVE_S1.); -#45074 = LINE('',#45075,#45076); -#45075 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); -#45076 = VECTOR('',#45077,1.); -#45077 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45078 = PCURVE('',#44606,#45079); -#45079 = DEFINITIONAL_REPRESENTATION('',(#45080),#45084); -#45080 = LINE('',#45081,#45082); -#45081 = CARTESIAN_POINT('',(-1.115,0.245)); -#45082 = VECTOR('',#45083,1.); -#45083 = DIRECTION('',(0.E+000,1.)); -#45084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45085 = PCURVE('',#44034,#45086); -#45086 = DEFINITIONAL_REPRESENTATION('',(#45087),#45091); -#45087 = LINE('',#45088,#45089); -#45088 = CARTESIAN_POINT('',(-1.55,0.245)); -#45089 = VECTOR('',#45090,1.); -#45090 = DIRECTION('',(0.E+000,1.)); -#45091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45092 = ORIENTED_EDGE('',*,*,#45093,.F.); -#45093 = EDGE_CURVE('',#45094,#45071,#45096,.T.); -#45094 = VERTEX_POINT('',#45095); -#45095 = CARTESIAN_POINT('',(-1.485,0.265,1.55)); -#45096 = SURFACE_CURVE('',#45097,(#45101,#45108),.PCURVE_S1.); -#45097 = LINE('',#45098,#45099); -#45098 = CARTESIAN_POINT('',(-1.485,0.265,1.55)); -#45099 = VECTOR('',#45100,1.); -#45100 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45101 = PCURVE('',#44606,#45102); -#45102 = DEFINITIONAL_REPRESENTATION('',(#45103),#45107); -#45103 = LINE('',#45104,#45105); -#45104 = CARTESIAN_POINT('',(-1.485,0.265)); -#45105 = VECTOR('',#45106,1.); -#45106 = DIRECTION('',(1.,0.E+000)); -#45107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45108 = PCURVE('',#45109,#45114); -#45109 = PLANE('',#45110); -#45110 = AXIS2_PLACEMENT_3D('',#45111,#45112,#45113); -#45111 = CARTESIAN_POINT('',(-1.485,0.265,-1.15)); -#45112 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45113 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45114 = DEFINITIONAL_REPRESENTATION('',(#45115),#45119); -#45115 = LINE('',#45116,#45117); -#45116 = CARTESIAN_POINT('',(2.7,0.E+000)); -#45117 = VECTOR('',#45118,1.); -#45118 = DIRECTION('',(0.E+000,1.)); -#45119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45120 = ORIENTED_EDGE('',*,*,#45121,.F.); -#45121 = EDGE_CURVE('',#45122,#45094,#45124,.T.); -#45122 = VERTEX_POINT('',#45123); -#45123 = CARTESIAN_POINT('',(-1.485,0.245,1.55)); -#45124 = SURFACE_CURVE('',#45125,(#45129,#45136),.PCURVE_S1.); -#45125 = LINE('',#45126,#45127); -#45126 = CARTESIAN_POINT('',(-1.485,0.245,1.55)); -#45127 = VECTOR('',#45128,1.); -#45128 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45129 = PCURVE('',#44606,#45130); -#45130 = DEFINITIONAL_REPRESENTATION('',(#45131),#45135); -#45131 = LINE('',#45132,#45133); -#45132 = CARTESIAN_POINT('',(-1.485,0.245)); -#45133 = VECTOR('',#45134,1.); -#45134 = DIRECTION('',(0.E+000,1.)); -#45135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45136 = PCURVE('',#43978,#45137); -#45137 = DEFINITIONAL_REPRESENTATION('',(#45138),#45142); -#45138 = LINE('',#45139,#45140); -#45139 = CARTESIAN_POINT('',(-1.55,0.245)); -#45140 = VECTOR('',#45141,1.); -#45141 = DIRECTION('',(0.E+000,1.)); -#45142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45143 = ORIENTED_EDGE('',*,*,#45144,.F.); -#45144 = EDGE_CURVE('',#45145,#45122,#45147,.T.); -#45145 = VERTEX_POINT('',#45146); -#45146 = CARTESIAN_POINT('',(-1.55,0.245,1.55)); -#45147 = SURFACE_CURVE('',#45148,(#45152,#45159),.PCURVE_S1.); -#45148 = LINE('',#45149,#45150); -#45149 = CARTESIAN_POINT('',(-1.55,0.245,1.55)); -#45150 = VECTOR('',#45151,1.); -#45151 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45152 = PCURVE('',#44606,#45153); -#45153 = DEFINITIONAL_REPRESENTATION('',(#45154),#45158); -#45154 = LINE('',#45155,#45156); -#45155 = CARTESIAN_POINT('',(-1.55,0.245)); -#45156 = VECTOR('',#45157,1.); -#45157 = DIRECTION('',(1.,0.E+000)); -#45158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45159 = PCURVE('',#45160,#45165); -#45160 = CYLINDRICAL_SURFACE('',#45161,0.2); -#45161 = AXIS2_PLACEMENT_3D('',#45162,#45163,#45164); -#45162 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#45163 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45164 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45165 = DEFINITIONAL_REPRESENTATION('',(#45166),#45169); -#45166 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45167,#45168),.UNSPECIFIED., +#47458 = CARTESIAN_POINT('',(0.E+000,0.450514631548)); +#47459 = CARTESIAN_POINT('',(0.E+000,0.730514631548)); +#47460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47461 = ORIENTED_EDGE('',*,*,#47462,.T.); +#47462 = EDGE_CURVE('',#47436,#47463,#47465,.T.); +#47463 = VERTEX_POINT('',#47464); +#47464 = CARTESIAN_POINT('',(-1.115,0.265,1.55)); +#47465 = SURFACE_CURVE('',#47466,(#47470,#47477),.PCURVE_S1.); +#47466 = LINE('',#47467,#47468); +#47467 = CARTESIAN_POINT('',(-1.115,0.245,1.55)); +#47468 = VECTOR('',#47469,1.); +#47469 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47470 = PCURVE('',#46998,#47471); +#47471 = DEFINITIONAL_REPRESENTATION('',(#47472),#47476); +#47472 = LINE('',#47473,#47474); +#47473 = CARTESIAN_POINT('',(-1.115,0.245)); +#47474 = VECTOR('',#47475,1.); +#47475 = DIRECTION('',(0.E+000,1.)); +#47476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47477 = PCURVE('',#46426,#47478); +#47478 = DEFINITIONAL_REPRESENTATION('',(#47479),#47483); +#47479 = LINE('',#47480,#47481); +#47480 = CARTESIAN_POINT('',(-1.55,0.245)); +#47481 = VECTOR('',#47482,1.); +#47482 = DIRECTION('',(0.E+000,1.)); +#47483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47484 = ORIENTED_EDGE('',*,*,#47485,.F.); +#47485 = EDGE_CURVE('',#47486,#47463,#47488,.T.); +#47486 = VERTEX_POINT('',#47487); +#47487 = CARTESIAN_POINT('',(-1.485,0.265,1.55)); +#47488 = SURFACE_CURVE('',#47489,(#47493,#47500),.PCURVE_S1.); +#47489 = LINE('',#47490,#47491); +#47490 = CARTESIAN_POINT('',(-1.485,0.265,1.55)); +#47491 = VECTOR('',#47492,1.); +#47492 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47493 = PCURVE('',#46998,#47494); +#47494 = DEFINITIONAL_REPRESENTATION('',(#47495),#47499); +#47495 = LINE('',#47496,#47497); +#47496 = CARTESIAN_POINT('',(-1.485,0.265)); +#47497 = VECTOR('',#47498,1.); +#47498 = DIRECTION('',(1.,0.E+000)); +#47499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47500 = PCURVE('',#47501,#47506); +#47501 = PLANE('',#47502); +#47502 = AXIS2_PLACEMENT_3D('',#47503,#47504,#47505); +#47503 = CARTESIAN_POINT('',(-1.485,0.265,-1.15)); +#47504 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47505 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47506 = DEFINITIONAL_REPRESENTATION('',(#47507),#47511); +#47507 = LINE('',#47508,#47509); +#47508 = CARTESIAN_POINT('',(2.7,0.E+000)); +#47509 = VECTOR('',#47510,1.); +#47510 = DIRECTION('',(0.E+000,1.)); +#47511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47512 = ORIENTED_EDGE('',*,*,#47513,.F.); +#47513 = EDGE_CURVE('',#47514,#47486,#47516,.T.); +#47514 = VERTEX_POINT('',#47515); +#47515 = CARTESIAN_POINT('',(-1.485,0.245,1.55)); +#47516 = SURFACE_CURVE('',#47517,(#47521,#47528),.PCURVE_S1.); +#47517 = LINE('',#47518,#47519); +#47518 = CARTESIAN_POINT('',(-1.485,0.245,1.55)); +#47519 = VECTOR('',#47520,1.); +#47520 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47521 = PCURVE('',#46998,#47522); +#47522 = DEFINITIONAL_REPRESENTATION('',(#47523),#47527); +#47523 = LINE('',#47524,#47525); +#47524 = CARTESIAN_POINT('',(-1.485,0.245)); +#47525 = VECTOR('',#47526,1.); +#47526 = DIRECTION('',(0.E+000,1.)); +#47527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47528 = PCURVE('',#46370,#47529); +#47529 = DEFINITIONAL_REPRESENTATION('',(#47530),#47534); +#47530 = LINE('',#47531,#47532); +#47531 = CARTESIAN_POINT('',(-1.55,0.245)); +#47532 = VECTOR('',#47533,1.); +#47533 = DIRECTION('',(0.E+000,1.)); +#47534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47535 = ORIENTED_EDGE('',*,*,#47536,.F.); +#47536 = EDGE_CURVE('',#47537,#47514,#47539,.T.); +#47537 = VERTEX_POINT('',#47538); +#47538 = CARTESIAN_POINT('',(-1.55,0.245,1.55)); +#47539 = SURFACE_CURVE('',#47540,(#47544,#47551),.PCURVE_S1.); +#47540 = LINE('',#47541,#47542); +#47541 = CARTESIAN_POINT('',(-1.55,0.245,1.55)); +#47542 = VECTOR('',#47543,1.); +#47543 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47544 = PCURVE('',#46998,#47545); +#47545 = DEFINITIONAL_REPRESENTATION('',(#47546),#47550); +#47546 = LINE('',#47547,#47548); +#47547 = CARTESIAN_POINT('',(-1.55,0.245)); +#47548 = VECTOR('',#47549,1.); +#47549 = DIRECTION('',(1.,0.E+000)); +#47550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47551 = PCURVE('',#47552,#47557); +#47552 = CYLINDRICAL_SURFACE('',#47553,0.2); +#47553 = AXIS2_PLACEMENT_3D('',#47554,#47555,#47556); +#47554 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#47555 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47556 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47557 = DEFINITIONAL_REPRESENTATION('',(#47558),#47561); +#47558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47559,#47560),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#45167 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#45168 = CARTESIAN_POINT('',(0.E+000,8.0514631548E-002)); -#45169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45170 = ORIENTED_EDGE('',*,*,#45171,.F.); -#45171 = EDGE_CURVE('',#45172,#45145,#45174,.T.); -#45172 = VERTEX_POINT('',#45173); -#45173 = CARTESIAN_POINT('',(-1.55,0.445,1.55)); -#45174 = SURFACE_CURVE('',#45175,(#45179,#45186),.PCURVE_S1.); -#45175 = LINE('',#45176,#45177); -#45176 = CARTESIAN_POINT('',(-1.55,0.445,1.55)); -#45177 = VECTOR('',#45178,1.); -#45178 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#45179 = PCURVE('',#44606,#45180); -#45180 = DEFINITIONAL_REPRESENTATION('',(#45181),#45185); -#45181 = LINE('',#45182,#45183); -#45182 = CARTESIAN_POINT('',(-1.55,0.445)); -#45183 = VECTOR('',#45184,1.); -#45184 = DIRECTION('',(0.E+000,-1.)); -#45185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45186 = PCURVE('',#45187,#45192); -#45187 = CYLINDRICAL_SURFACE('',#45188,0.2); -#45188 = AXIS2_PLACEMENT_3D('',#45189,#45190,#45191); -#45189 = CARTESIAN_POINT('',(-1.55,0.460514631548,1.35)); -#45190 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#45191 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45192 = DEFINITIONAL_REPRESENTATION('',(#45193),#45196); -#45193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45194,#45195),.UNSPECIFIED., +#47559 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#47560 = CARTESIAN_POINT('',(0.E+000,8.0514631548E-002)); +#47561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47562 = ORIENTED_EDGE('',*,*,#47563,.F.); +#47563 = EDGE_CURVE('',#47564,#47537,#47566,.T.); +#47564 = VERTEX_POINT('',#47565); +#47565 = CARTESIAN_POINT('',(-1.55,0.445,1.55)); +#47566 = SURFACE_CURVE('',#47567,(#47571,#47578),.PCURVE_S1.); +#47567 = LINE('',#47568,#47569); +#47568 = CARTESIAN_POINT('',(-1.55,0.445,1.55)); +#47569 = VECTOR('',#47570,1.); +#47570 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#47571 = PCURVE('',#46998,#47572); +#47572 = DEFINITIONAL_REPRESENTATION('',(#47573),#47577); +#47573 = LINE('',#47574,#47575); +#47574 = CARTESIAN_POINT('',(-1.55,0.445)); +#47575 = VECTOR('',#47576,1.); +#47576 = DIRECTION('',(0.E+000,-1.)); +#47577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47578 = PCURVE('',#47579,#47584); +#47579 = CYLINDRICAL_SURFACE('',#47580,0.2); +#47580 = AXIS2_PLACEMENT_3D('',#47581,#47582,#47583); +#47581 = CARTESIAN_POINT('',(-1.55,0.460514631548,1.35)); +#47582 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#47583 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47584 = DEFINITIONAL_REPRESENTATION('',(#47585),#47588); +#47585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47586,#47587),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#45194 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); -#45195 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); -#45196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45197 = ORIENTED_EDGE('',*,*,#45198,.F.); -#45198 = EDGE_CURVE('',#45199,#45172,#45201,.T.); -#45199 = VERTEX_POINT('',#45200); -#45200 = CARTESIAN_POINT('',(1.55,0.445,1.55)); -#45201 = SURFACE_CURVE('',#45202,(#45206,#45213),.PCURVE_S1.); -#45202 = LINE('',#45203,#45204); -#45203 = CARTESIAN_POINT('',(1.55,0.445,1.55)); -#45204 = VECTOR('',#45205,1.); -#45205 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#45206 = PCURVE('',#44606,#45207); -#45207 = DEFINITIONAL_REPRESENTATION('',(#45208),#45212); -#45208 = LINE('',#45209,#45210); -#45209 = CARTESIAN_POINT('',(1.55,0.445)); -#45210 = VECTOR('',#45211,1.); -#45211 = DIRECTION('',(-1.,0.E+000)); -#45212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45213 = PCURVE('',#45214,#45219); -#45214 = CYLINDRICAL_SURFACE('',#45215,0.2); -#45215 = AXIS2_PLACEMENT_3D('',#45216,#45217,#45218); -#45216 = CARTESIAN_POINT('',(1.565514631548,0.445,1.35)); -#45217 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#45218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45219 = DEFINITIONAL_REPRESENTATION('',(#45220),#45223); -#45220 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45221,#45222),.UNSPECIFIED., +#47586 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); +#47587 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); +#47588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47589 = ORIENTED_EDGE('',*,*,#47590,.F.); +#47590 = EDGE_CURVE('',#47591,#47564,#47593,.T.); +#47591 = VERTEX_POINT('',#47592); +#47592 = CARTESIAN_POINT('',(1.55,0.445,1.55)); +#47593 = SURFACE_CURVE('',#47594,(#47598,#47605),.PCURVE_S1.); +#47594 = LINE('',#47595,#47596); +#47595 = CARTESIAN_POINT('',(1.55,0.445,1.55)); +#47596 = VECTOR('',#47597,1.); +#47597 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#47598 = PCURVE('',#46998,#47599); +#47599 = DEFINITIONAL_REPRESENTATION('',(#47600),#47604); +#47600 = LINE('',#47601,#47602); +#47601 = CARTESIAN_POINT('',(1.55,0.445)); +#47602 = VECTOR('',#47603,1.); +#47603 = DIRECTION('',(-1.,0.E+000)); +#47604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47605 = PCURVE('',#47606,#47611); +#47606 = CYLINDRICAL_SURFACE('',#47607,0.2); +#47607 = AXIS2_PLACEMENT_3D('',#47608,#47609,#47610); +#47608 = CARTESIAN_POINT('',(1.565514631548,0.445,1.35)); +#47609 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#47610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47611 = DEFINITIONAL_REPRESENTATION('',(#47612),#47615); +#47612 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47613,#47614),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.1),.PIECEWISE_BEZIER_KNOTS.); -#45221 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#45222 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); -#45223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45224 = ORIENTED_EDGE('',*,*,#45225,.F.); -#45225 = EDGE_CURVE('',#45226,#45199,#45228,.T.); -#45226 = VERTEX_POINT('',#45227); -#45227 = CARTESIAN_POINT('',(1.55,0.245,1.55)); -#45228 = SURFACE_CURVE('',#45229,(#45233,#45240),.PCURVE_S1.); -#45229 = LINE('',#45230,#45231); -#45230 = CARTESIAN_POINT('',(1.55,0.245,1.55)); -#45231 = VECTOR('',#45232,1.); -#45232 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45233 = PCURVE('',#44606,#45234); -#45234 = DEFINITIONAL_REPRESENTATION('',(#45235),#45239); -#45235 = LINE('',#45236,#45237); -#45236 = CARTESIAN_POINT('',(1.55,0.245)); -#45237 = VECTOR('',#45238,1.); -#45238 = DIRECTION('',(0.E+000,1.)); -#45239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45240 = PCURVE('',#45241,#45246); -#45241 = CYLINDRICAL_SURFACE('',#45242,0.2); -#45242 = AXIS2_PLACEMENT_3D('',#45243,#45244,#45245); -#45243 = CARTESIAN_POINT('',(1.55,0.229485368452,1.35)); -#45244 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45245 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45246 = DEFINITIONAL_REPRESENTATION('',(#45247),#45250); -#45247 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45248,#45249),.UNSPECIFIED., +#47613 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#47614 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); +#47615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47616 = ORIENTED_EDGE('',*,*,#47617,.F.); +#47617 = EDGE_CURVE('',#47618,#47591,#47620,.T.); +#47618 = VERTEX_POINT('',#47619); +#47619 = CARTESIAN_POINT('',(1.55,0.245,1.55)); +#47620 = SURFACE_CURVE('',#47621,(#47625,#47632),.PCURVE_S1.); +#47621 = LINE('',#47622,#47623); +#47622 = CARTESIAN_POINT('',(1.55,0.245,1.55)); +#47623 = VECTOR('',#47624,1.); +#47624 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47625 = PCURVE('',#46998,#47626); +#47626 = DEFINITIONAL_REPRESENTATION('',(#47627),#47631); +#47627 = LINE('',#47628,#47629); +#47628 = CARTESIAN_POINT('',(1.55,0.245)); +#47629 = VECTOR('',#47630,1.); +#47630 = DIRECTION('',(0.E+000,1.)); +#47631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47632 = PCURVE('',#47633,#47638); +#47633 = CYLINDRICAL_SURFACE('',#47634,0.2); +#47634 = AXIS2_PLACEMENT_3D('',#47635,#47636,#47637); +#47635 = CARTESIAN_POINT('',(1.55,0.229485368452,1.35)); +#47636 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47637 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47638 = DEFINITIONAL_REPRESENTATION('',(#47639),#47642); +#47639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47640,#47641),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#45248 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); -#45249 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); -#45250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45251 = ORIENTED_EDGE('',*,*,#45252,.F.); -#45252 = EDGE_CURVE('',#45253,#45226,#45255,.T.); -#45253 = VERTEX_POINT('',#45254); -#45254 = CARTESIAN_POINT('',(1.485,0.245,1.55)); -#45255 = SURFACE_CURVE('',#45256,(#45260,#45267),.PCURVE_S1.); -#45256 = LINE('',#45257,#45258); -#45257 = CARTESIAN_POINT('',(1.485,0.245,1.55)); -#45258 = VECTOR('',#45259,1.); -#45259 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45260 = PCURVE('',#44606,#45261); -#45261 = DEFINITIONAL_REPRESENTATION('',(#45262),#45266); -#45262 = LINE('',#45263,#45264); -#45263 = CARTESIAN_POINT('',(1.485,0.245)); -#45264 = VECTOR('',#45265,1.); -#45265 = DIRECTION('',(1.,0.E+000)); -#45266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45267 = PCURVE('',#45268,#45273); -#45268 = CYLINDRICAL_SURFACE('',#45269,0.2); -#45269 = AXIS2_PLACEMENT_3D('',#45270,#45271,#45272); -#45270 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); -#45271 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45272 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45273 = DEFINITIONAL_REPRESENTATION('',(#45274),#45277); -#45274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45275,#45276),.UNSPECIFIED., +#47640 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); +#47641 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); +#47642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47643 = ORIENTED_EDGE('',*,*,#47644,.F.); +#47644 = EDGE_CURVE('',#47645,#47618,#47647,.T.); +#47645 = VERTEX_POINT('',#47646); +#47646 = CARTESIAN_POINT('',(1.485,0.245,1.55)); +#47647 = SURFACE_CURVE('',#47648,(#47652,#47659),.PCURVE_S1.); +#47648 = LINE('',#47649,#47650); +#47649 = CARTESIAN_POINT('',(1.485,0.245,1.55)); +#47650 = VECTOR('',#47651,1.); +#47651 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47652 = PCURVE('',#46998,#47653); +#47653 = DEFINITIONAL_REPRESENTATION('',(#47654),#47658); +#47654 = LINE('',#47655,#47656); +#47655 = CARTESIAN_POINT('',(1.485,0.245)); +#47656 = VECTOR('',#47657,1.); +#47657 = DIRECTION('',(1.,0.E+000)); +#47658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47659 = PCURVE('',#47660,#47665); +#47660 = CYLINDRICAL_SURFACE('',#47661,0.2); +#47661 = AXIS2_PLACEMENT_3D('',#47662,#47663,#47664); +#47662 = CARTESIAN_POINT('',(-1.565514631548,0.245,1.35)); +#47663 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47664 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47665 = DEFINITIONAL_REPRESENTATION('',(#47666),#47669); +#47666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47667,#47668),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#45275 = CARTESIAN_POINT('',(0.E+000,3.050514631548)); -#45276 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); -#45277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45278 = ORIENTED_EDGE('',*,*,#45279,.T.); -#45279 = EDGE_CURVE('',#45253,#44698,#45280,.T.); -#45280 = SURFACE_CURVE('',#45281,(#45285,#45292),.PCURVE_S1.); -#45281 = LINE('',#45282,#45283); -#45282 = CARTESIAN_POINT('',(1.485,0.245,1.55)); -#45283 = VECTOR('',#45284,1.); -#45284 = DIRECTION('',(0.E+000,1.,0.E+000)); -#45285 = PCURVE('',#44606,#45286); -#45286 = DEFINITIONAL_REPRESENTATION('',(#45287),#45291); -#45287 = LINE('',#45288,#45289); -#45288 = CARTESIAN_POINT('',(1.485,0.245)); -#45289 = VECTOR('',#45290,1.); -#45290 = DIRECTION('',(0.E+000,1.)); -#45291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45292 = PCURVE('',#43204,#45293); -#45293 = DEFINITIONAL_REPRESENTATION('',(#45294),#45298); -#45294 = LINE('',#45295,#45296); -#45295 = CARTESIAN_POINT('',(-1.55,0.245)); -#45296 = VECTOR('',#45297,1.); -#45297 = DIRECTION('',(0.E+000,1.)); -#45298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45299 = ORIENTED_EDGE('',*,*,#44697,.F.); -#45300 = ADVANCED_FACE('',(#45301),#45160,.T.); -#45301 = FACE_BOUND('',#45302,.T.); -#45302 = EDGE_LOOP('',(#45303,#45326,#45327,#45377)); -#45303 = ORIENTED_EDGE('',*,*,#45304,.F.); -#45304 = EDGE_CURVE('',#45122,#45305,#45307,.T.); -#45305 = VERTEX_POINT('',#45306); -#45306 = CARTESIAN_POINT('',(-1.485,4.5E-002,1.35)); -#45307 = SURFACE_CURVE('',#45308,(#45313,#45319),.PCURVE_S1.); -#45308 = CIRCLE('',#45309,0.2); -#45309 = AXIS2_PLACEMENT_3D('',#45310,#45311,#45312); -#45310 = CARTESIAN_POINT('',(-1.485,0.245,1.35)); -#45311 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45312 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45313 = PCURVE('',#45160,#45314); -#45314 = DEFINITIONAL_REPRESENTATION('',(#45315),#45318); -#45315 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45316,#45317),.UNSPECIFIED., +#47667 = CARTESIAN_POINT('',(0.E+000,3.050514631548)); +#47668 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); +#47669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47670 = ORIENTED_EDGE('',*,*,#47671,.T.); +#47671 = EDGE_CURVE('',#47645,#47090,#47672,.T.); +#47672 = SURFACE_CURVE('',#47673,(#47677,#47684),.PCURVE_S1.); +#47673 = LINE('',#47674,#47675); +#47674 = CARTESIAN_POINT('',(1.485,0.245,1.55)); +#47675 = VECTOR('',#47676,1.); +#47676 = DIRECTION('',(0.E+000,1.,0.E+000)); +#47677 = PCURVE('',#46998,#47678); +#47678 = DEFINITIONAL_REPRESENTATION('',(#47679),#47683); +#47679 = LINE('',#47680,#47681); +#47680 = CARTESIAN_POINT('',(1.485,0.245)); +#47681 = VECTOR('',#47682,1.); +#47682 = DIRECTION('',(0.E+000,1.)); +#47683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47684 = PCURVE('',#45596,#47685); +#47685 = DEFINITIONAL_REPRESENTATION('',(#47686),#47690); +#47686 = LINE('',#47687,#47688); +#47687 = CARTESIAN_POINT('',(-1.55,0.245)); +#47688 = VECTOR('',#47689,1.); +#47689 = DIRECTION('',(0.E+000,1.)); +#47690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47691 = ORIENTED_EDGE('',*,*,#47089,.F.); +#47692 = ADVANCED_FACE('',(#47693),#47552,.T.); +#47693 = FACE_BOUND('',#47694,.T.); +#47694 = EDGE_LOOP('',(#47695,#47718,#47719,#47769)); +#47695 = ORIENTED_EDGE('',*,*,#47696,.F.); +#47696 = EDGE_CURVE('',#47514,#47697,#47699,.T.); +#47697 = VERTEX_POINT('',#47698); +#47698 = CARTESIAN_POINT('',(-1.485,4.5E-002,1.35)); +#47699 = SURFACE_CURVE('',#47700,(#47705,#47711),.PCURVE_S1.); +#47700 = CIRCLE('',#47701,0.2); +#47701 = AXIS2_PLACEMENT_3D('',#47702,#47703,#47704); +#47702 = CARTESIAN_POINT('',(-1.485,0.245,1.35)); +#47703 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47704 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47705 = PCURVE('',#47552,#47706); +#47706 = DEFINITIONAL_REPRESENTATION('',(#47707),#47710); +#47707 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47708,#47709),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45316 = CARTESIAN_POINT('',(0.E+000,8.0514631548E-002)); -#45317 = CARTESIAN_POINT('',(1.570796326795,8.0514631548E-002)); -#45318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45319 = PCURVE('',#43978,#45320); -#45320 = DEFINITIONAL_REPRESENTATION('',(#45321),#45325); -#45321 = CIRCLE('',#45322,0.2); -#45322 = AXIS2_PLACEMENT_2D('',#45323,#45324); -#45323 = CARTESIAN_POINT('',(-1.35,0.245)); -#45324 = DIRECTION('',(-1.,0.E+000)); -#45325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45326 = ORIENTED_EDGE('',*,*,#45144,.F.); -#45327 = ORIENTED_EDGE('',*,*,#45328,.T.); -#45328 = EDGE_CURVE('',#45145,#45329,#45331,.T.); -#45329 = VERTEX_POINT('',#45330); -#45330 = CARTESIAN_POINT('',(-1.55,4.5E-002,1.35)); -#45331 = SURFACE_CURVE('',#45332,(#45337,#45343),.PCURVE_S1.); -#45332 = CIRCLE('',#45333,0.2); -#45333 = AXIS2_PLACEMENT_3D('',#45334,#45335,#45336); -#45334 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); -#45335 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45336 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45337 = PCURVE('',#45160,#45338); -#45338 = DEFINITIONAL_REPRESENTATION('',(#45339),#45342); -#45339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45340,#45341),.UNSPECIFIED., +#47708 = CARTESIAN_POINT('',(0.E+000,8.0514631548E-002)); +#47709 = CARTESIAN_POINT('',(1.570796326795,8.0514631548E-002)); +#47710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47711 = PCURVE('',#46370,#47712); +#47712 = DEFINITIONAL_REPRESENTATION('',(#47713),#47717); +#47713 = CIRCLE('',#47714,0.2); +#47714 = AXIS2_PLACEMENT_2D('',#47715,#47716); +#47715 = CARTESIAN_POINT('',(-1.35,0.245)); +#47716 = DIRECTION('',(-1.,0.E+000)); +#47717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47718 = ORIENTED_EDGE('',*,*,#47536,.F.); +#47719 = ORIENTED_EDGE('',*,*,#47720,.T.); +#47720 = EDGE_CURVE('',#47537,#47721,#47723,.T.); +#47721 = VERTEX_POINT('',#47722); +#47722 = CARTESIAN_POINT('',(-1.55,4.5E-002,1.35)); +#47723 = SURFACE_CURVE('',#47724,(#47729,#47735),.PCURVE_S1.); +#47724 = CIRCLE('',#47725,0.2); +#47725 = AXIS2_PLACEMENT_3D('',#47726,#47727,#47728); +#47726 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); +#47727 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47728 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47729 = PCURVE('',#47552,#47730); +#47730 = DEFINITIONAL_REPRESENTATION('',(#47731),#47734); +#47731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47732,#47733),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45340 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#45341 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#45342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45343 = PCURVE('',#45344,#45349); -#45344 = SPHERICAL_SURFACE('',#45345,0.2); -#45345 = AXIS2_PLACEMENT_3D('',#45346,#45347,#45348); -#45346 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); -#45347 = DIRECTION('',(-0.707104942284,0.707108620085,0.E+000)); -#45348 = DIRECTION('',(-0.707108620085,-0.707104942284,0.E+000)); -#45349 = DEFINITIONAL_REPRESENTATION('',(#45350),#45376); -#45350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#45351,#45352,#45353,#45354, - #45355,#45356,#45357,#45358,#45359,#45360,#45361,#45362,#45363, - #45364,#45365,#45366,#45367,#45368,#45369,#45370,#45371,#45372, - #45373,#45374,#45375),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#47732 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#47733 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#47734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47735 = PCURVE('',#47736,#47741); +#47736 = SPHERICAL_SURFACE('',#47737,0.2); +#47737 = AXIS2_PLACEMENT_3D('',#47738,#47739,#47740); +#47738 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); +#47739 = DIRECTION('',(-0.707104942284,0.707108620085,0.E+000)); +#47740 = DIRECTION('',(-0.707108620085,-0.707104942284,0.E+000)); +#47741 = DEFINITIONAL_REPRESENTATION('',(#47742),#47768); +#47742 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#47743,#47744,#47745,#47746, + #47747,#47748,#47749,#47750,#47751,#47752,#47753,#47754,#47755, + #47756,#47757,#47758,#47759,#47760,#47761,#47762,#47763,#47764, + #47765,#47766,#47767),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -56624,458 +59613,458 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#45351 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#45352 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); -#45353 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); -#45354 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); -#45355 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); -#45356 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); -#45357 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); -#45358 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); -#45359 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); -#45360 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); -#45361 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); -#45362 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); -#45363 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); -#45364 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); -#45365 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); -#45366 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); -#45367 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); -#45368 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); -#45369 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); -#45370 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); -#45371 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); -#45372 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); -#45373 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); -#45374 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); -#45375 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#45376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45377 = ORIENTED_EDGE('',*,*,#45378,.T.); -#45378 = EDGE_CURVE('',#45329,#45305,#45379,.T.); -#45379 = SURFACE_CURVE('',#45380,(#45384,#45390),.PCURVE_S1.); -#45380 = LINE('',#45381,#45382); -#45381 = CARTESIAN_POINT('',(-1.549999999909,4.5E-002,1.35)); -#45382 = VECTOR('',#45383,1.); -#45383 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45384 = PCURVE('',#45160,#45385); -#45385 = DEFINITIONAL_REPRESENTATION('',(#45386),#45389); -#45386 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45387,#45388),.UNSPECIFIED., +#47743 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#47744 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); +#47745 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); +#47746 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); +#47747 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); +#47748 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); +#47749 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); +#47750 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); +#47751 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); +#47752 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); +#47753 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); +#47754 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); +#47755 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); +#47756 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); +#47757 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); +#47758 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); +#47759 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); +#47760 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); +#47761 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); +#47762 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); +#47763 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); +#47764 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); +#47765 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); +#47766 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); +#47767 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#47768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47769 = ORIENTED_EDGE('',*,*,#47770,.T.); +#47770 = EDGE_CURVE('',#47721,#47697,#47771,.T.); +#47771 = SURFACE_CURVE('',#47772,(#47776,#47782),.PCURVE_S1.); +#47772 = LINE('',#47773,#47774); +#47773 = CARTESIAN_POINT('',(-1.549999999909,4.5E-002,1.35)); +#47774 = VECTOR('',#47775,1.); +#47775 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47776 = PCURVE('',#47552,#47777); +#47777 = DEFINITIONAL_REPRESENTATION('',(#47778),#47781); +#47778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47779,#47780),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#45387 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#45388 = CARTESIAN_POINT('',(1.570796326795,8.0514631548E-002)); -#45389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45390 = PCURVE('',#43950,#45391); -#45391 = DEFINITIONAL_REPRESENTATION('',(#45392),#45396); -#45392 = LINE('',#45393,#45394); -#45393 = CARTESIAN_POINT('',(9.100009634722E-011,2.5)); -#45394 = VECTOR('',#45395,1.); -#45395 = DIRECTION('',(1.,0.E+000)); -#45396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45397 = ADVANCED_FACE('',(#45398),#45059,.T.); -#45398 = FACE_BOUND('',#45399,.T.); -#45399 = EDGE_LOOP('',(#45400,#45423,#45424,#45447)); -#45400 = ORIENTED_EDGE('',*,*,#45401,.F.); -#45401 = EDGE_CURVE('',#45021,#45402,#45404,.T.); -#45402 = VERTEX_POINT('',#45403); -#45403 = CARTESIAN_POINT('',(-0.835,4.5E-002,1.35)); -#45404 = SURFACE_CURVE('',#45405,(#45410,#45416),.PCURVE_S1.); -#45405 = CIRCLE('',#45406,0.2); -#45406 = AXIS2_PLACEMENT_3D('',#45407,#45408,#45409); -#45407 = CARTESIAN_POINT('',(-0.835,0.245,1.35)); -#45408 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45409 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45410 = PCURVE('',#45059,#45411); -#45411 = DEFINITIONAL_REPRESENTATION('',(#45412),#45415); -#45412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45413,#45414),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45413 = CARTESIAN_POINT('',(0.E+000,0.730514631548)); -#45414 = CARTESIAN_POINT('',(1.570796326795,0.730514631548)); -#45415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45416 = PCURVE('',#44090,#45417); -#45417 = DEFINITIONAL_REPRESENTATION('',(#45418),#45422); -#45418 = CIRCLE('',#45419,0.2); -#45419 = AXIS2_PLACEMENT_2D('',#45420,#45421); -#45420 = CARTESIAN_POINT('',(-1.35,0.245)); -#45421 = DIRECTION('',(-1.,0.E+000)); -#45422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45423 = ORIENTED_EDGE('',*,*,#45043,.F.); -#45424 = ORIENTED_EDGE('',*,*,#45425,.T.); -#45425 = EDGE_CURVE('',#45044,#45426,#45428,.T.); -#45426 = VERTEX_POINT('',#45427); -#45427 = CARTESIAN_POINT('',(-1.115,4.5E-002,1.35)); -#45428 = SURFACE_CURVE('',#45429,(#45434,#45440),.PCURVE_S1.); -#45429 = CIRCLE('',#45430,0.2); -#45430 = AXIS2_PLACEMENT_3D('',#45431,#45432,#45433); -#45431 = CARTESIAN_POINT('',(-1.115,0.245,1.35)); -#45432 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45433 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45434 = PCURVE('',#45059,#45435); -#45435 = DEFINITIONAL_REPRESENTATION('',(#45436),#45439); -#45436 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45437,#45438),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45437 = CARTESIAN_POINT('',(0.E+000,0.450514631548)); -#45438 = CARTESIAN_POINT('',(1.570796326795,0.450514631548)); -#45439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45440 = PCURVE('',#44034,#45441); -#45441 = DEFINITIONAL_REPRESENTATION('',(#45442),#45446); -#45442 = CIRCLE('',#45443,0.2); -#45443 = AXIS2_PLACEMENT_2D('',#45444,#45445); -#45444 = CARTESIAN_POINT('',(-1.35,0.245)); -#45445 = DIRECTION('',(-1.,0.E+000)); -#45446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#47779 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#47780 = CARTESIAN_POINT('',(1.570796326795,8.0514631548E-002)); +#47781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#45447 = ORIENTED_EDGE('',*,*,#45448,.T.); -#45448 = EDGE_CURVE('',#45426,#45402,#45449,.T.); -#45449 = SURFACE_CURVE('',#45450,(#45454,#45460),.PCURVE_S1.); -#45450 = LINE('',#45451,#45452); -#45451 = CARTESIAN_POINT('',(-1.115,4.5E-002,1.35)); -#45452 = VECTOR('',#45453,1.); -#45453 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45454 = PCURVE('',#45059,#45455); -#45455 = DEFINITIONAL_REPRESENTATION('',(#45456),#45459); -#45456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45457,#45458),.UNSPECIFIED., +#47782 = PCURVE('',#46342,#47783); +#47783 = DEFINITIONAL_REPRESENTATION('',(#47784),#47788); +#47784 = LINE('',#47785,#47786); +#47785 = CARTESIAN_POINT('',(9.100009634722E-011,2.5)); +#47786 = VECTOR('',#47787,1.); +#47787 = DIRECTION('',(1.,0.E+000)); +#47788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47789 = ADVANCED_FACE('',(#47790),#47451,.T.); +#47790 = FACE_BOUND('',#47791,.T.); +#47791 = EDGE_LOOP('',(#47792,#47815,#47816,#47839)); +#47792 = ORIENTED_EDGE('',*,*,#47793,.F.); +#47793 = EDGE_CURVE('',#47413,#47794,#47796,.T.); +#47794 = VERTEX_POINT('',#47795); +#47795 = CARTESIAN_POINT('',(-0.835,4.5E-002,1.35)); +#47796 = SURFACE_CURVE('',#47797,(#47802,#47808),.PCURVE_S1.); +#47797 = CIRCLE('',#47798,0.2); +#47798 = AXIS2_PLACEMENT_3D('',#47799,#47800,#47801); +#47799 = CARTESIAN_POINT('',(-0.835,0.245,1.35)); +#47800 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47801 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47802 = PCURVE('',#47451,#47803); +#47803 = DEFINITIONAL_REPRESENTATION('',(#47804),#47807); +#47804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47805,#47806),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#47805 = CARTESIAN_POINT('',(0.E+000,0.730514631548)); +#47806 = CARTESIAN_POINT('',(1.570796326795,0.730514631548)); +#47807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47808 = PCURVE('',#46482,#47809); +#47809 = DEFINITIONAL_REPRESENTATION('',(#47810),#47814); +#47810 = CIRCLE('',#47811,0.2); +#47811 = AXIS2_PLACEMENT_2D('',#47812,#47813); +#47812 = CARTESIAN_POINT('',(-1.35,0.245)); +#47813 = DIRECTION('',(-1.,0.E+000)); +#47814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47815 = ORIENTED_EDGE('',*,*,#47435,.F.); +#47816 = ORIENTED_EDGE('',*,*,#47817,.T.); +#47817 = EDGE_CURVE('',#47436,#47818,#47820,.T.); +#47818 = VERTEX_POINT('',#47819); +#47819 = CARTESIAN_POINT('',(-1.115,4.5E-002,1.35)); +#47820 = SURFACE_CURVE('',#47821,(#47826,#47832),.PCURVE_S1.); +#47821 = CIRCLE('',#47822,0.2); +#47822 = AXIS2_PLACEMENT_3D('',#47823,#47824,#47825); +#47823 = CARTESIAN_POINT('',(-1.115,0.245,1.35)); +#47824 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47825 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47826 = PCURVE('',#47451,#47827); +#47827 = DEFINITIONAL_REPRESENTATION('',(#47828),#47831); +#47828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47829,#47830),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#47829 = CARTESIAN_POINT('',(0.E+000,0.450514631548)); +#47830 = CARTESIAN_POINT('',(1.570796326795,0.450514631548)); +#47831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47832 = PCURVE('',#46426,#47833); +#47833 = DEFINITIONAL_REPRESENTATION('',(#47834),#47838); +#47834 = CIRCLE('',#47835,0.2); +#47835 = AXIS2_PLACEMENT_2D('',#47836,#47837); +#47836 = CARTESIAN_POINT('',(-1.35,0.245)); +#47837 = DIRECTION('',(-1.,0.E+000)); +#47838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47839 = ORIENTED_EDGE('',*,*,#47840,.T.); +#47840 = EDGE_CURVE('',#47818,#47794,#47841,.T.); +#47841 = SURFACE_CURVE('',#47842,(#47846,#47852),.PCURVE_S1.); +#47842 = LINE('',#47843,#47844); +#47843 = CARTESIAN_POINT('',(-1.115,4.5E-002,1.35)); +#47844 = VECTOR('',#47845,1.); +#47845 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47846 = PCURVE('',#47451,#47847); +#47847 = DEFINITIONAL_REPRESENTATION('',(#47848),#47851); +#47848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47849,#47850),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#45457 = CARTESIAN_POINT('',(1.570796326795,0.450514631548)); -#45458 = CARTESIAN_POINT('',(1.570796326795,0.730514631548)); -#45459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45460 = PCURVE('',#44062,#45461); -#45461 = DEFINITIONAL_REPRESENTATION('',(#45462),#45466); -#45462 = LINE('',#45463,#45464); -#45463 = CARTESIAN_POINT('',(0.435,2.5)); -#45464 = VECTOR('',#45465,1.); -#45465 = DIRECTION('',(1.,0.E+000)); -#45466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45467 = ADVANCED_FACE('',(#45468),#44958,.T.); -#45468 = FACE_BOUND('',#45469,.T.); -#45469 = EDGE_LOOP('',(#45470,#45493,#45494,#45517)); -#45470 = ORIENTED_EDGE('',*,*,#45471,.F.); -#45471 = EDGE_CURVE('',#44920,#45472,#45474,.T.); -#45472 = VERTEX_POINT('',#45473); -#45473 = CARTESIAN_POINT('',(-0.185,4.5E-002,1.35)); -#45474 = SURFACE_CURVE('',#45475,(#45480,#45486),.PCURVE_S1.); -#45475 = CIRCLE('',#45476,0.2); -#45476 = AXIS2_PLACEMENT_3D('',#45477,#45478,#45479); -#45477 = CARTESIAN_POINT('',(-0.185,0.245,1.35)); -#45478 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45479 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45480 = PCURVE('',#44958,#45481); -#45481 = DEFINITIONAL_REPRESENTATION('',(#45482),#45485); -#45482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45483,#45484),.UNSPECIFIED., +#47849 = CARTESIAN_POINT('',(1.570796326795,0.450514631548)); +#47850 = CARTESIAN_POINT('',(1.570796326795,0.730514631548)); +#47851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47852 = PCURVE('',#46454,#47853); +#47853 = DEFINITIONAL_REPRESENTATION('',(#47854),#47858); +#47854 = LINE('',#47855,#47856); +#47855 = CARTESIAN_POINT('',(0.435,2.5)); +#47856 = VECTOR('',#47857,1.); +#47857 = DIRECTION('',(1.,0.E+000)); +#47858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47859 = ADVANCED_FACE('',(#47860),#47350,.T.); +#47860 = FACE_BOUND('',#47861,.T.); +#47861 = EDGE_LOOP('',(#47862,#47885,#47886,#47909)); +#47862 = ORIENTED_EDGE('',*,*,#47863,.F.); +#47863 = EDGE_CURVE('',#47312,#47864,#47866,.T.); +#47864 = VERTEX_POINT('',#47865); +#47865 = CARTESIAN_POINT('',(-0.185,4.5E-002,1.35)); +#47866 = SURFACE_CURVE('',#47867,(#47872,#47878),.PCURVE_S1.); +#47867 = CIRCLE('',#47868,0.2); +#47868 = AXIS2_PLACEMENT_3D('',#47869,#47870,#47871); +#47869 = CARTESIAN_POINT('',(-0.185,0.245,1.35)); +#47870 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47871 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47872 = PCURVE('',#47350,#47873); +#47873 = DEFINITIONAL_REPRESENTATION('',(#47874),#47877); +#47874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47875,#47876),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45483 = CARTESIAN_POINT('',(0.E+000,1.380514631548)); -#45484 = CARTESIAN_POINT('',(1.570796326795,1.380514631548)); -#45485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45486 = PCURVE('',#44202,#45487); -#45487 = DEFINITIONAL_REPRESENTATION('',(#45488),#45492); -#45488 = CIRCLE('',#45489,0.2); -#45489 = AXIS2_PLACEMENT_2D('',#45490,#45491); -#45490 = CARTESIAN_POINT('',(-1.35,0.245)); -#45491 = DIRECTION('',(-1.,0.E+000)); -#45492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45493 = ORIENTED_EDGE('',*,*,#44942,.F.); -#45494 = ORIENTED_EDGE('',*,*,#45495,.T.); -#45495 = EDGE_CURVE('',#44943,#45496,#45498,.T.); -#45496 = VERTEX_POINT('',#45497); -#45497 = CARTESIAN_POINT('',(-0.465,4.5E-002,1.35)); -#45498 = SURFACE_CURVE('',#45499,(#45504,#45510),.PCURVE_S1.); -#45499 = CIRCLE('',#45500,0.2); -#45500 = AXIS2_PLACEMENT_3D('',#45501,#45502,#45503); -#45501 = CARTESIAN_POINT('',(-0.465,0.245,1.35)); -#45502 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45503 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45504 = PCURVE('',#44958,#45505); -#45505 = DEFINITIONAL_REPRESENTATION('',(#45506),#45509); -#45506 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45507,#45508),.UNSPECIFIED., +#47875 = CARTESIAN_POINT('',(0.E+000,1.380514631548)); +#47876 = CARTESIAN_POINT('',(1.570796326795,1.380514631548)); +#47877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47878 = PCURVE('',#46594,#47879); +#47879 = DEFINITIONAL_REPRESENTATION('',(#47880),#47884); +#47880 = CIRCLE('',#47881,0.2); +#47881 = AXIS2_PLACEMENT_2D('',#47882,#47883); +#47882 = CARTESIAN_POINT('',(-1.35,0.245)); +#47883 = DIRECTION('',(-1.,0.E+000)); +#47884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47885 = ORIENTED_EDGE('',*,*,#47334,.F.); +#47886 = ORIENTED_EDGE('',*,*,#47887,.T.); +#47887 = EDGE_CURVE('',#47335,#47888,#47890,.T.); +#47888 = VERTEX_POINT('',#47889); +#47889 = CARTESIAN_POINT('',(-0.465,4.5E-002,1.35)); +#47890 = SURFACE_CURVE('',#47891,(#47896,#47902),.PCURVE_S1.); +#47891 = CIRCLE('',#47892,0.2); +#47892 = AXIS2_PLACEMENT_3D('',#47893,#47894,#47895); +#47893 = CARTESIAN_POINT('',(-0.465,0.245,1.35)); +#47894 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47895 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47896 = PCURVE('',#47350,#47897); +#47897 = DEFINITIONAL_REPRESENTATION('',(#47898),#47901); +#47898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47899,#47900),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45507 = CARTESIAN_POINT('',(0.E+000,1.100514631548)); -#45508 = CARTESIAN_POINT('',(1.570796326795,1.100514631548)); -#45509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45510 = PCURVE('',#44146,#45511); -#45511 = DEFINITIONAL_REPRESENTATION('',(#45512),#45516); -#45512 = CIRCLE('',#45513,0.2); -#45513 = AXIS2_PLACEMENT_2D('',#45514,#45515); -#45514 = CARTESIAN_POINT('',(-1.35,0.245)); -#45515 = DIRECTION('',(-1.,0.E+000)); -#45516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45517 = ORIENTED_EDGE('',*,*,#45518,.T.); -#45518 = EDGE_CURVE('',#45496,#45472,#45519,.T.); -#45519 = SURFACE_CURVE('',#45520,(#45524,#45530),.PCURVE_S1.); -#45520 = LINE('',#45521,#45522); -#45521 = CARTESIAN_POINT('',(-0.465,4.5E-002,1.35)); -#45522 = VECTOR('',#45523,1.); -#45523 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45524 = PCURVE('',#44958,#45525); -#45525 = DEFINITIONAL_REPRESENTATION('',(#45526),#45529); -#45526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45527,#45528),.UNSPECIFIED., +#47899 = CARTESIAN_POINT('',(0.E+000,1.100514631548)); +#47900 = CARTESIAN_POINT('',(1.570796326795,1.100514631548)); +#47901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47902 = PCURVE('',#46538,#47903); +#47903 = DEFINITIONAL_REPRESENTATION('',(#47904),#47908); +#47904 = CIRCLE('',#47905,0.2); +#47905 = AXIS2_PLACEMENT_2D('',#47906,#47907); +#47906 = CARTESIAN_POINT('',(-1.35,0.245)); +#47907 = DIRECTION('',(-1.,0.E+000)); +#47908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47909 = ORIENTED_EDGE('',*,*,#47910,.T.); +#47910 = EDGE_CURVE('',#47888,#47864,#47911,.T.); +#47911 = SURFACE_CURVE('',#47912,(#47916,#47922),.PCURVE_S1.); +#47912 = LINE('',#47913,#47914); +#47913 = CARTESIAN_POINT('',(-0.465,4.5E-002,1.35)); +#47914 = VECTOR('',#47915,1.); +#47915 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47916 = PCURVE('',#47350,#47917); +#47917 = DEFINITIONAL_REPRESENTATION('',(#47918),#47921); +#47918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47919,#47920),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#45527 = CARTESIAN_POINT('',(1.570796326795,1.100514631548)); -#45528 = CARTESIAN_POINT('',(1.570796326795,1.380514631548)); -#45529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45530 = PCURVE('',#44174,#45531); -#45531 = DEFINITIONAL_REPRESENTATION('',(#45532),#45536); -#45532 = LINE('',#45533,#45534); -#45533 = CARTESIAN_POINT('',(1.085,2.5)); -#45534 = VECTOR('',#45535,1.); -#45535 = DIRECTION('',(1.,0.E+000)); -#45536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45537 = ADVANCED_FACE('',(#45538),#44857,.T.); -#45538 = FACE_BOUND('',#45539,.T.); -#45539 = EDGE_LOOP('',(#45540,#45563,#45564,#45587)); -#45540 = ORIENTED_EDGE('',*,*,#45541,.F.); -#45541 = EDGE_CURVE('',#44819,#45542,#45544,.T.); -#45542 = VERTEX_POINT('',#45543); -#45543 = CARTESIAN_POINT('',(0.465,4.5E-002,1.35)); -#45544 = SURFACE_CURVE('',#45545,(#45550,#45556),.PCURVE_S1.); -#45545 = CIRCLE('',#45546,0.2); -#45546 = AXIS2_PLACEMENT_3D('',#45547,#45548,#45549); -#45547 = CARTESIAN_POINT('',(0.465,0.245,1.35)); -#45548 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45549 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45550 = PCURVE('',#44857,#45551); -#45551 = DEFINITIONAL_REPRESENTATION('',(#45552),#45555); -#45552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45553,#45554),.UNSPECIFIED., +#47919 = CARTESIAN_POINT('',(1.570796326795,1.100514631548)); +#47920 = CARTESIAN_POINT('',(1.570796326795,1.380514631548)); +#47921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47922 = PCURVE('',#46566,#47923); +#47923 = DEFINITIONAL_REPRESENTATION('',(#47924),#47928); +#47924 = LINE('',#47925,#47926); +#47925 = CARTESIAN_POINT('',(1.085,2.5)); +#47926 = VECTOR('',#47927,1.); +#47927 = DIRECTION('',(1.,0.E+000)); +#47928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47929 = ADVANCED_FACE('',(#47930),#47249,.T.); +#47930 = FACE_BOUND('',#47931,.T.); +#47931 = EDGE_LOOP('',(#47932,#47955,#47956,#47979)); +#47932 = ORIENTED_EDGE('',*,*,#47933,.F.); +#47933 = EDGE_CURVE('',#47211,#47934,#47936,.T.); +#47934 = VERTEX_POINT('',#47935); +#47935 = CARTESIAN_POINT('',(0.465,4.5E-002,1.35)); +#47936 = SURFACE_CURVE('',#47937,(#47942,#47948),.PCURVE_S1.); +#47937 = CIRCLE('',#47938,0.2); +#47938 = AXIS2_PLACEMENT_3D('',#47939,#47940,#47941); +#47939 = CARTESIAN_POINT('',(0.465,0.245,1.35)); +#47940 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47941 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47942 = PCURVE('',#47249,#47943); +#47943 = DEFINITIONAL_REPRESENTATION('',(#47944),#47947); +#47944 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47945,#47946),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45553 = CARTESIAN_POINT('',(0.E+000,2.030514631548)); -#45554 = CARTESIAN_POINT('',(1.570796326795,2.030514631548)); -#45555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45556 = PCURVE('',#44314,#45557); -#45557 = DEFINITIONAL_REPRESENTATION('',(#45558),#45562); -#45558 = CIRCLE('',#45559,0.2); -#45559 = AXIS2_PLACEMENT_2D('',#45560,#45561); -#45560 = CARTESIAN_POINT('',(-1.35,0.245)); -#45561 = DIRECTION('',(-1.,0.E+000)); -#45562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45563 = ORIENTED_EDGE('',*,*,#44841,.F.); -#45564 = ORIENTED_EDGE('',*,*,#45565,.T.); -#45565 = EDGE_CURVE('',#44842,#45566,#45568,.T.); -#45566 = VERTEX_POINT('',#45567); -#45567 = CARTESIAN_POINT('',(0.185,4.5E-002,1.35)); -#45568 = SURFACE_CURVE('',#45569,(#45574,#45580),.PCURVE_S1.); -#45569 = CIRCLE('',#45570,0.2); -#45570 = AXIS2_PLACEMENT_3D('',#45571,#45572,#45573); -#45571 = CARTESIAN_POINT('',(0.185,0.245,1.35)); -#45572 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45573 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45574 = PCURVE('',#44857,#45575); -#45575 = DEFINITIONAL_REPRESENTATION('',(#45576),#45579); -#45576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45577,#45578),.UNSPECIFIED., +#47945 = CARTESIAN_POINT('',(0.E+000,2.030514631548)); +#47946 = CARTESIAN_POINT('',(1.570796326795,2.030514631548)); +#47947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47948 = PCURVE('',#46706,#47949); +#47949 = DEFINITIONAL_REPRESENTATION('',(#47950),#47954); +#47950 = CIRCLE('',#47951,0.2); +#47951 = AXIS2_PLACEMENT_2D('',#47952,#47953); +#47952 = CARTESIAN_POINT('',(-1.35,0.245)); +#47953 = DIRECTION('',(-1.,0.E+000)); +#47954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47955 = ORIENTED_EDGE('',*,*,#47233,.F.); +#47956 = ORIENTED_EDGE('',*,*,#47957,.T.); +#47957 = EDGE_CURVE('',#47234,#47958,#47960,.T.); +#47958 = VERTEX_POINT('',#47959); +#47959 = CARTESIAN_POINT('',(0.185,4.5E-002,1.35)); +#47960 = SURFACE_CURVE('',#47961,(#47966,#47972),.PCURVE_S1.); +#47961 = CIRCLE('',#47962,0.2); +#47962 = AXIS2_PLACEMENT_3D('',#47963,#47964,#47965); +#47963 = CARTESIAN_POINT('',(0.185,0.245,1.35)); +#47964 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47965 = DIRECTION('',(0.E+000,0.E+000,1.)); +#47966 = PCURVE('',#47249,#47967); +#47967 = DEFINITIONAL_REPRESENTATION('',(#47968),#47971); +#47968 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47969,#47970),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45577 = CARTESIAN_POINT('',(0.E+000,1.750514631548)); -#45578 = CARTESIAN_POINT('',(1.570796326795,1.750514631548)); -#45579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45580 = PCURVE('',#44258,#45581); -#45581 = DEFINITIONAL_REPRESENTATION('',(#45582),#45586); -#45582 = CIRCLE('',#45583,0.2); -#45583 = AXIS2_PLACEMENT_2D('',#45584,#45585); -#45584 = CARTESIAN_POINT('',(-1.35,0.245)); -#45585 = DIRECTION('',(-1.,0.E+000)); -#45586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45587 = ORIENTED_EDGE('',*,*,#45588,.T.); -#45588 = EDGE_CURVE('',#45566,#45542,#45589,.T.); -#45589 = SURFACE_CURVE('',#45590,(#45594,#45600),.PCURVE_S1.); -#45590 = LINE('',#45591,#45592); -#45591 = CARTESIAN_POINT('',(0.185,4.5E-002,1.35)); -#45592 = VECTOR('',#45593,1.); -#45593 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45594 = PCURVE('',#44857,#45595); -#45595 = DEFINITIONAL_REPRESENTATION('',(#45596),#45599); -#45596 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45597,#45598),.UNSPECIFIED., +#47969 = CARTESIAN_POINT('',(0.E+000,1.750514631548)); +#47970 = CARTESIAN_POINT('',(1.570796326795,1.750514631548)); +#47971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47972 = PCURVE('',#46650,#47973); +#47973 = DEFINITIONAL_REPRESENTATION('',(#47974),#47978); +#47974 = CIRCLE('',#47975,0.2); +#47975 = AXIS2_PLACEMENT_2D('',#47976,#47977); +#47976 = CARTESIAN_POINT('',(-1.35,0.245)); +#47977 = DIRECTION('',(-1.,0.E+000)); +#47978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47979 = ORIENTED_EDGE('',*,*,#47980,.T.); +#47980 = EDGE_CURVE('',#47958,#47934,#47981,.T.); +#47981 = SURFACE_CURVE('',#47982,(#47986,#47992),.PCURVE_S1.); +#47982 = LINE('',#47983,#47984); +#47983 = CARTESIAN_POINT('',(0.185,4.5E-002,1.35)); +#47984 = VECTOR('',#47985,1.); +#47985 = DIRECTION('',(1.,0.E+000,0.E+000)); +#47986 = PCURVE('',#47249,#47987); +#47987 = DEFINITIONAL_REPRESENTATION('',(#47988),#47991); +#47988 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47989,#47990),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#45597 = CARTESIAN_POINT('',(1.570796326795,1.750514631548)); -#45598 = CARTESIAN_POINT('',(1.570796326795,2.030514631548)); -#45599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45600 = PCURVE('',#44286,#45601); -#45601 = DEFINITIONAL_REPRESENTATION('',(#45602),#45606); -#45602 = LINE('',#45603,#45604); -#45603 = CARTESIAN_POINT('',(1.735,2.5)); -#45604 = VECTOR('',#45605,1.); -#45605 = DIRECTION('',(1.,0.E+000)); -#45606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45607 = ADVANCED_FACE('',(#45608),#44579,.T.); -#45608 = FACE_BOUND('',#45609,.T.); -#45609 = EDGE_LOOP('',(#45610,#45611,#45612,#45635)); -#45610 = ORIENTED_EDGE('',*,*,#44562,.F.); -#45611 = ORIENTED_EDGE('',*,*,#44745,.F.); -#45612 = ORIENTED_EDGE('',*,*,#45613,.T.); -#45613 = EDGE_CURVE('',#44746,#45614,#45616,.T.); -#45614 = VERTEX_POINT('',#45615); -#45615 = CARTESIAN_POINT('',(0.835,4.5E-002,1.35)); -#45616 = SURFACE_CURVE('',#45617,(#45622,#45628),.PCURVE_S1.); -#45617 = CIRCLE('',#45618,0.2); -#45618 = AXIS2_PLACEMENT_3D('',#45619,#45620,#45621); -#45619 = CARTESIAN_POINT('',(0.835,0.245,1.35)); -#45620 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45621 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45622 = PCURVE('',#44579,#45623); -#45623 = DEFINITIONAL_REPRESENTATION('',(#45624),#45627); -#45624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45625,#45626),.UNSPECIFIED., +#47989 = CARTESIAN_POINT('',(1.570796326795,1.750514631548)); +#47990 = CARTESIAN_POINT('',(1.570796326795,2.030514631548)); +#47991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47992 = PCURVE('',#46678,#47993); +#47993 = DEFINITIONAL_REPRESENTATION('',(#47994),#47998); +#47994 = LINE('',#47995,#47996); +#47995 = CARTESIAN_POINT('',(1.735,2.5)); +#47996 = VECTOR('',#47997,1.); +#47997 = DIRECTION('',(1.,0.E+000)); +#47998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#47999 = ADVANCED_FACE('',(#48000),#46971,.T.); +#48000 = FACE_BOUND('',#48001,.T.); +#48001 = EDGE_LOOP('',(#48002,#48003,#48004,#48027)); +#48002 = ORIENTED_EDGE('',*,*,#46954,.F.); +#48003 = ORIENTED_EDGE('',*,*,#47137,.F.); +#48004 = ORIENTED_EDGE('',*,*,#48005,.T.); +#48005 = EDGE_CURVE('',#47138,#48006,#48008,.T.); +#48006 = VERTEX_POINT('',#48007); +#48007 = CARTESIAN_POINT('',(0.835,4.5E-002,1.35)); +#48008 = SURFACE_CURVE('',#48009,(#48014,#48020),.PCURVE_S1.); +#48009 = CIRCLE('',#48010,0.2); +#48010 = AXIS2_PLACEMENT_3D('',#48011,#48012,#48013); +#48011 = CARTESIAN_POINT('',(0.835,0.245,1.35)); +#48012 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48013 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48014 = PCURVE('',#46971,#48015); +#48015 = DEFINITIONAL_REPRESENTATION('',(#48016),#48019); +#48016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48017,#48018),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45625 = CARTESIAN_POINT('',(0.E+000,2.400514631548)); -#45626 = CARTESIAN_POINT('',(1.570796326795,2.400514631548)); -#45627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45628 = PCURVE('',#44370,#45629); -#45629 = DEFINITIONAL_REPRESENTATION('',(#45630),#45634); -#45630 = CIRCLE('',#45631,0.2); -#45631 = AXIS2_PLACEMENT_2D('',#45632,#45633); -#45632 = CARTESIAN_POINT('',(-1.35,0.245)); -#45633 = DIRECTION('',(-1.,0.E+000)); -#45634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45635 = ORIENTED_EDGE('',*,*,#45636,.T.); -#45636 = EDGE_CURVE('',#45614,#44540,#45637,.T.); -#45637 = SURFACE_CURVE('',#45638,(#45642,#45648),.PCURVE_S1.); -#45638 = LINE('',#45639,#45640); -#45639 = CARTESIAN_POINT('',(0.835,4.5E-002,1.35)); -#45640 = VECTOR('',#45641,1.); -#45641 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45642 = PCURVE('',#44579,#45643); -#45643 = DEFINITIONAL_REPRESENTATION('',(#45644),#45647); -#45644 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45645,#45646),.UNSPECIFIED., +#48017 = CARTESIAN_POINT('',(0.E+000,2.400514631548)); +#48018 = CARTESIAN_POINT('',(1.570796326795,2.400514631548)); +#48019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48020 = PCURVE('',#46762,#48021); +#48021 = DEFINITIONAL_REPRESENTATION('',(#48022),#48026); +#48022 = CIRCLE('',#48023,0.2); +#48023 = AXIS2_PLACEMENT_2D('',#48024,#48025); +#48024 = CARTESIAN_POINT('',(-1.35,0.245)); +#48025 = DIRECTION('',(-1.,0.E+000)); +#48026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48027 = ORIENTED_EDGE('',*,*,#48028,.T.); +#48028 = EDGE_CURVE('',#48006,#46932,#48029,.T.); +#48029 = SURFACE_CURVE('',#48030,(#48034,#48040),.PCURVE_S1.); +#48030 = LINE('',#48031,#48032); +#48031 = CARTESIAN_POINT('',(0.835,4.5E-002,1.35)); +#48032 = VECTOR('',#48033,1.); +#48033 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48034 = PCURVE('',#46971,#48035); +#48035 = DEFINITIONAL_REPRESENTATION('',(#48036),#48039); +#48036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48037,#48038),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.28),.PIECEWISE_BEZIER_KNOTS.); -#45645 = CARTESIAN_POINT('',(1.570796326795,2.400514631548)); -#45646 = CARTESIAN_POINT('',(1.570796326795,2.680514631548)); -#45647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45648 = PCURVE('',#44398,#45649); -#45649 = DEFINITIONAL_REPRESENTATION('',(#45650),#45654); -#45650 = LINE('',#45651,#45652); -#45651 = CARTESIAN_POINT('',(2.385,2.5)); -#45652 = VECTOR('',#45653,1.); -#45653 = DIRECTION('',(1.,0.E+000)); -#45654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45655 = ADVANCED_FACE('',(#45656),#45268,.T.); -#45656 = FACE_BOUND('',#45657,.T.); -#45657 = EDGE_LOOP('',(#45658,#45681,#45703,#45751)); -#45658 = ORIENTED_EDGE('',*,*,#45659,.T.); -#45659 = EDGE_CURVE('',#45253,#45660,#45662,.T.); -#45660 = VERTEX_POINT('',#45661); -#45661 = CARTESIAN_POINT('',(1.485,4.5E-002,1.35)); -#45662 = SURFACE_CURVE('',#45663,(#45668,#45674),.PCURVE_S1.); -#45663 = CIRCLE('',#45664,0.2); -#45664 = AXIS2_PLACEMENT_3D('',#45665,#45666,#45667); -#45665 = CARTESIAN_POINT('',(1.485,0.245,1.35)); -#45666 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45667 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45668 = PCURVE('',#45268,#45669); -#45669 = DEFINITIONAL_REPRESENTATION('',(#45670),#45673); -#45670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45671,#45672),.UNSPECIFIED., +#48037 = CARTESIAN_POINT('',(1.570796326795,2.400514631548)); +#48038 = CARTESIAN_POINT('',(1.570796326795,2.680514631548)); +#48039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48040 = PCURVE('',#46790,#48041); +#48041 = DEFINITIONAL_REPRESENTATION('',(#48042),#48046); +#48042 = LINE('',#48043,#48044); +#48043 = CARTESIAN_POINT('',(2.385,2.5)); +#48044 = VECTOR('',#48045,1.); +#48045 = DIRECTION('',(1.,0.E+000)); +#48046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48047 = ADVANCED_FACE('',(#48048),#47660,.T.); +#48048 = FACE_BOUND('',#48049,.T.); +#48049 = EDGE_LOOP('',(#48050,#48073,#48095,#48143)); +#48050 = ORIENTED_EDGE('',*,*,#48051,.T.); +#48051 = EDGE_CURVE('',#47645,#48052,#48054,.T.); +#48052 = VERTEX_POINT('',#48053); +#48053 = CARTESIAN_POINT('',(1.485,4.5E-002,1.35)); +#48054 = SURFACE_CURVE('',#48055,(#48060,#48066),.PCURVE_S1.); +#48055 = CIRCLE('',#48056,0.2); +#48056 = AXIS2_PLACEMENT_3D('',#48057,#48058,#48059); +#48057 = CARTESIAN_POINT('',(1.485,0.245,1.35)); +#48058 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48059 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48060 = PCURVE('',#47660,#48061); +#48061 = DEFINITIONAL_REPRESENTATION('',(#48062),#48065); +#48062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48063,#48064),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45671 = CARTESIAN_POINT('',(0.E+000,3.050514631548)); -#45672 = CARTESIAN_POINT('',(1.570796326795,3.050514631548)); -#45673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45674 = PCURVE('',#43204,#45675); -#45675 = DEFINITIONAL_REPRESENTATION('',(#45676),#45680); -#45676 = CIRCLE('',#45677,0.2); -#45677 = AXIS2_PLACEMENT_2D('',#45678,#45679); -#45678 = CARTESIAN_POINT('',(-1.35,0.245)); -#45679 = DIRECTION('',(-1.,0.E+000)); -#45680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45681 = ORIENTED_EDGE('',*,*,#45682,.T.); -#45682 = EDGE_CURVE('',#45660,#45683,#45685,.T.); -#45683 = VERTEX_POINT('',#45684); -#45684 = CARTESIAN_POINT('',(1.55,4.5E-002,1.35)); -#45685 = SURFACE_CURVE('',#45686,(#45690,#45696),.PCURVE_S1.); -#45686 = LINE('',#45687,#45688); -#45687 = CARTESIAN_POINT('',(1.485,4.5E-002,1.35)); -#45688 = VECTOR('',#45689,1.); -#45689 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45690 = PCURVE('',#45268,#45691); -#45691 = DEFINITIONAL_REPRESENTATION('',(#45692),#45695); -#45692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45693,#45694),.UNSPECIFIED., +#48063 = CARTESIAN_POINT('',(0.E+000,3.050514631548)); +#48064 = CARTESIAN_POINT('',(1.570796326795,3.050514631548)); +#48065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48066 = PCURVE('',#45596,#48067); +#48067 = DEFINITIONAL_REPRESENTATION('',(#48068),#48072); +#48068 = CIRCLE('',#48069,0.2); +#48069 = AXIS2_PLACEMENT_2D('',#48070,#48071); +#48070 = CARTESIAN_POINT('',(-1.35,0.245)); +#48071 = DIRECTION('',(-1.,0.E+000)); +#48072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48073 = ORIENTED_EDGE('',*,*,#48074,.T.); +#48074 = EDGE_CURVE('',#48052,#48075,#48077,.T.); +#48075 = VERTEX_POINT('',#48076); +#48076 = CARTESIAN_POINT('',(1.55,4.5E-002,1.35)); +#48077 = SURFACE_CURVE('',#48078,(#48082,#48088),.PCURVE_S1.); +#48078 = LINE('',#48079,#48080); +#48079 = CARTESIAN_POINT('',(1.485,4.5E-002,1.35)); +#48080 = VECTOR('',#48081,1.); +#48081 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48082 = PCURVE('',#47660,#48083); +#48083 = DEFINITIONAL_REPRESENTATION('',(#48084),#48087); +#48084 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48085,#48086),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#45693 = CARTESIAN_POINT('',(1.570796326795,3.050514631548)); -#45694 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); -#45695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45696 = PCURVE('',#43232,#45697); -#45697 = DEFINITIONAL_REPRESENTATION('',(#45698),#45702); -#45698 = LINE('',#45699,#45700); -#45699 = CARTESIAN_POINT('',(3.035,2.5)); -#45700 = VECTOR('',#45701,1.); -#45701 = DIRECTION('',(1.,0.E+000)); -#45702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45703 = ORIENTED_EDGE('',*,*,#45704,.F.); -#45704 = EDGE_CURVE('',#45226,#45683,#45705,.T.); -#45705 = SURFACE_CURVE('',#45706,(#45711,#45717),.PCURVE_S1.); -#45706 = CIRCLE('',#45707,0.2); -#45707 = AXIS2_PLACEMENT_3D('',#45708,#45709,#45710); -#45708 = CARTESIAN_POINT('',(1.55,0.245,1.35)); -#45709 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45710 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45711 = PCURVE('',#45268,#45712); -#45712 = DEFINITIONAL_REPRESENTATION('',(#45713),#45716); -#45713 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45714,#45715),.UNSPECIFIED., +#48085 = CARTESIAN_POINT('',(1.570796326795,3.050514631548)); +#48086 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); +#48087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48088 = PCURVE('',#45624,#48089); +#48089 = DEFINITIONAL_REPRESENTATION('',(#48090),#48094); +#48090 = LINE('',#48091,#48092); +#48091 = CARTESIAN_POINT('',(3.035,2.5)); +#48092 = VECTOR('',#48093,1.); +#48093 = DIRECTION('',(1.,0.E+000)); +#48094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48095 = ORIENTED_EDGE('',*,*,#48096,.F.); +#48096 = EDGE_CURVE('',#47618,#48075,#48097,.T.); +#48097 = SURFACE_CURVE('',#48098,(#48103,#48109),.PCURVE_S1.); +#48098 = CIRCLE('',#48099,0.2); +#48099 = AXIS2_PLACEMENT_3D('',#48100,#48101,#48102); +#48100 = CARTESIAN_POINT('',(1.55,0.245,1.35)); +#48101 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48102 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48103 = PCURVE('',#47660,#48104); +#48104 = DEFINITIONAL_REPRESENTATION('',(#48105),#48108); +#48105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48106,#48107),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45714 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); -#45715 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); -#45716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45717 = PCURVE('',#45718,#45723); -#45718 = SPHERICAL_SURFACE('',#45719,0.2); -#45719 = AXIS2_PLACEMENT_3D('',#45720,#45721,#45722); -#45720 = CARTESIAN_POINT('',(1.55,0.245,1.35)); -#45721 = DIRECTION('',(-0.707108620085,-0.707104942284,0.E+000)); -#45722 = DIRECTION('',(0.707104942284,-0.707108620085,0.E+000)); -#45723 = DEFINITIONAL_REPRESENTATION('',(#45724),#45750); -#45724 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#45725,#45726,#45727,#45728, - #45729,#45730,#45731,#45732,#45733,#45734,#45735,#45736,#45737, - #45738,#45739,#45740,#45741,#45742,#45743,#45744,#45745,#45746, - #45747,#45748,#45749),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48106 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); +#48107 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); +#48108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48109 = PCURVE('',#48110,#48115); +#48110 = SPHERICAL_SURFACE('',#48111,0.2); +#48111 = AXIS2_PLACEMENT_3D('',#48112,#48113,#48114); +#48112 = CARTESIAN_POINT('',(1.55,0.245,1.35)); +#48113 = DIRECTION('',(-0.707108620085,-0.707104942284,0.E+000)); +#48114 = DIRECTION('',(0.707104942284,-0.707108620085,0.E+000)); +#48115 = DEFINITIONAL_REPRESENTATION('',(#48116),#48142); +#48116 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48117,#48118,#48119,#48120, + #48121,#48122,#48123,#48124,#48125,#48126,#48127,#48128,#48129, + #48130,#48131,#48132,#48133,#48134,#48135,#48136,#48137,#48138, + #48139,#48140,#48141),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -57083,754 +60072,754 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#45725 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#45726 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); -#45727 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); -#45728 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); -#45729 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); -#45730 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); -#45731 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); -#45732 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); -#45733 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); -#45734 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); -#45735 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); -#45736 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); -#45737 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); -#45738 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); -#45739 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); -#45740 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); -#45741 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); -#45742 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); -#45743 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); -#45744 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); -#45745 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); -#45746 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); -#45747 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); -#45748 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); -#45749 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#45750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45751 = ORIENTED_EDGE('',*,*,#45252,.F.); -#45752 = ADVANCED_FACE('',(#45753),#43978,.T.); -#45753 = FACE_BOUND('',#45754,.F.); -#45754 = EDGE_LOOP('',(#45755,#45785,#45806,#45807,#45828,#45829,#45830) - ); -#45755 = ORIENTED_EDGE('',*,*,#45756,.T.); -#45756 = EDGE_CURVE('',#45757,#45759,#45761,.T.); -#45757 = VERTEX_POINT('',#45758); -#45758 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); -#45759 = VERTEX_POINT('',#45760); -#45760 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); -#45761 = SURFACE_CURVE('',#45762,(#45767,#45774),.PCURVE_S1.); -#45762 = CIRCLE('',#45763,0.1); -#45763 = AXIS2_PLACEMENT_3D('',#45764,#45765,#45766); -#45764 = CARTESIAN_POINT('',(-1.485,0.265,1.05)); -#45765 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45766 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45767 = PCURVE('',#43978,#45768); -#45768 = DEFINITIONAL_REPRESENTATION('',(#45769),#45773); -#45769 = CIRCLE('',#45770,0.1); -#45770 = AXIS2_PLACEMENT_2D('',#45771,#45772); -#45771 = CARTESIAN_POINT('',(-1.05,0.265)); -#45772 = DIRECTION('',(-1.,0.E+000)); -#45773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45774 = PCURVE('',#45775,#45780); -#45775 = CYLINDRICAL_SURFACE('',#45776,0.1); -#45776 = AXIS2_PLACEMENT_3D('',#45777,#45778,#45779); -#45777 = CARTESIAN_POINT('',(-1.485,0.265,1.05)); -#45778 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45779 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#45780 = DEFINITIONAL_REPRESENTATION('',(#45781),#45784); -#45781 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45782,#45783),.UNSPECIFIED., +#48117 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#48118 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); +#48119 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); +#48120 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); +#48121 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); +#48122 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); +#48123 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); +#48124 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); +#48125 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); +#48126 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); +#48127 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); +#48128 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); +#48129 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); +#48130 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); +#48131 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); +#48132 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); +#48133 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); +#48134 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); +#48135 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); +#48136 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); +#48137 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); +#48138 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); +#48139 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); +#48140 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); +#48141 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#48142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48143 = ORIENTED_EDGE('',*,*,#47644,.F.); +#48144 = ADVANCED_FACE('',(#48145),#46370,.T.); +#48145 = FACE_BOUND('',#48146,.F.); +#48146 = EDGE_LOOP('',(#48147,#48177,#48198,#48199,#48220,#48221,#48222) + ); +#48147 = ORIENTED_EDGE('',*,*,#48148,.T.); +#48148 = EDGE_CURVE('',#48149,#48151,#48153,.T.); +#48149 = VERTEX_POINT('',#48150); +#48150 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); +#48151 = VERTEX_POINT('',#48152); +#48152 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); +#48153 = SURFACE_CURVE('',#48154,(#48159,#48166),.PCURVE_S1.); +#48154 = CIRCLE('',#48155,0.1); +#48155 = AXIS2_PLACEMENT_3D('',#48156,#48157,#48158); +#48156 = CARTESIAN_POINT('',(-1.485,0.265,1.05)); +#48157 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48158 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48159 = PCURVE('',#46370,#48160); +#48160 = DEFINITIONAL_REPRESENTATION('',(#48161),#48165); +#48161 = CIRCLE('',#48162,0.1); +#48162 = AXIS2_PLACEMENT_2D('',#48163,#48164); +#48163 = CARTESIAN_POINT('',(-1.05,0.265)); +#48164 = DIRECTION('',(-1.,0.E+000)); +#48165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48166 = PCURVE('',#48167,#48172); +#48167 = CYLINDRICAL_SURFACE('',#48168,0.1); +#48168 = AXIS2_PLACEMENT_3D('',#48169,#48170,#48171); +#48169 = CARTESIAN_POINT('',(-1.485,0.265,1.05)); +#48170 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48171 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#48172 = DEFINITIONAL_REPRESENTATION('',(#48173),#48176); +#48173 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48174,#48175),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45782 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#45783 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#45784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45785 = ORIENTED_EDGE('',*,*,#45786,.F.); -#45786 = EDGE_CURVE('',#43963,#45759,#45787,.T.); -#45787 = SURFACE_CURVE('',#45788,(#45792,#45799),.PCURVE_S1.); -#45788 = LINE('',#45789,#45790); -#45789 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); -#45790 = VECTOR('',#45791,1.); -#45791 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45792 = PCURVE('',#43978,#45793); -#45793 = DEFINITIONAL_REPRESENTATION('',(#45794),#45798); -#45794 = LINE('',#45795,#45796); -#45795 = CARTESIAN_POINT('',(1.15,0.165)); -#45796 = VECTOR('',#45797,1.); -#45797 = DIRECTION('',(-1.,0.E+000)); -#45798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45799 = PCURVE('',#44006,#45800); -#45800 = DEFINITIONAL_REPRESENTATION('',(#45801),#45805); -#45801 = LINE('',#45802,#45803); -#45802 = CARTESIAN_POINT('',(2.2,0.E+000)); -#45803 = VECTOR('',#45804,1.); -#45804 = DIRECTION('',(-1.,0.E+000)); -#45805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45806 = ORIENTED_EDGE('',*,*,#43962,.F.); -#45807 = ORIENTED_EDGE('',*,*,#45808,.T.); -#45808 = EDGE_CURVE('',#43935,#45305,#45809,.T.); -#45809 = SURFACE_CURVE('',#45810,(#45814,#45821),.PCURVE_S1.); -#45810 = LINE('',#45811,#45812); -#45811 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); -#45812 = VECTOR('',#45813,1.); -#45813 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45814 = PCURVE('',#43978,#45815); -#45815 = DEFINITIONAL_REPRESENTATION('',(#45816),#45820); -#45816 = LINE('',#45817,#45818); -#45817 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#45818 = VECTOR('',#45819,1.); -#45819 = DIRECTION('',(-1.,0.E+000)); -#45820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45821 = PCURVE('',#43950,#45822); -#45822 = DEFINITIONAL_REPRESENTATION('',(#45823),#45827); -#45823 = LINE('',#45824,#45825); -#45824 = CARTESIAN_POINT('',(6.5E-002,0.E+000)); -#45825 = VECTOR('',#45826,1.); -#45826 = DIRECTION('',(0.E+000,1.)); -#45827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45828 = ORIENTED_EDGE('',*,*,#45304,.F.); -#45829 = ORIENTED_EDGE('',*,*,#45121,.T.); -#45830 = ORIENTED_EDGE('',*,*,#45831,.F.); -#45831 = EDGE_CURVE('',#45757,#45094,#45832,.T.); -#45832 = SURFACE_CURVE('',#45833,(#45837,#45844),.PCURVE_S1.); -#45833 = LINE('',#45834,#45835); -#45834 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); -#45835 = VECTOR('',#45836,1.); -#45836 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45837 = PCURVE('',#43978,#45838); -#45838 = DEFINITIONAL_REPRESENTATION('',(#45839),#45843); -#45839 = LINE('',#45840,#45841); -#45840 = CARTESIAN_POINT('',(-1.15,0.265)); -#45841 = VECTOR('',#45842,1.); -#45842 = DIRECTION('',(-1.,0.E+000)); -#45843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45844 = PCURVE('',#45109,#45845); -#45845 = DEFINITIONAL_REPRESENTATION('',(#45846),#45850); -#45846 = LINE('',#45847,#45848); -#45847 = CARTESIAN_POINT('',(2.3,0.E+000)); -#45848 = VECTOR('',#45849,1.); -#45849 = DIRECTION('',(1.,0.E+000)); -#45850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45851 = ADVANCED_FACE('',(#45852),#45775,.T.); -#45852 = FACE_BOUND('',#45853,.T.); -#45853 = EDGE_LOOP('',(#45854,#45855,#45877,#45900)); -#45854 = ORIENTED_EDGE('',*,*,#45756,.T.); -#45855 = ORIENTED_EDGE('',*,*,#45856,.T.); -#45856 = EDGE_CURVE('',#45759,#45857,#45859,.T.); -#45857 = VERTEX_POINT('',#45858); -#45858 = CARTESIAN_POINT('',(-1.115,0.165,1.05)); -#45859 = SURFACE_CURVE('',#45860,(#45864,#45870),.PCURVE_S1.); -#45860 = LINE('',#45861,#45862); -#45861 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); -#45862 = VECTOR('',#45863,1.); -#45863 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45864 = PCURVE('',#45775,#45865); -#45865 = DEFINITIONAL_REPRESENTATION('',(#45866),#45869); -#45866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45867,#45868),.UNSPECIFIED., +#48174 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#48175 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#48176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48177 = ORIENTED_EDGE('',*,*,#48178,.F.); +#48178 = EDGE_CURVE('',#46355,#48151,#48179,.T.); +#48179 = SURFACE_CURVE('',#48180,(#48184,#48191),.PCURVE_S1.); +#48180 = LINE('',#48181,#48182); +#48181 = CARTESIAN_POINT('',(-1.485,0.165,-1.15)); +#48182 = VECTOR('',#48183,1.); +#48183 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48184 = PCURVE('',#46370,#48185); +#48185 = DEFINITIONAL_REPRESENTATION('',(#48186),#48190); +#48186 = LINE('',#48187,#48188); +#48187 = CARTESIAN_POINT('',(1.15,0.165)); +#48188 = VECTOR('',#48189,1.); +#48189 = DIRECTION('',(-1.,0.E+000)); +#48190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48191 = PCURVE('',#46398,#48192); +#48192 = DEFINITIONAL_REPRESENTATION('',(#48193),#48197); +#48193 = LINE('',#48194,#48195); +#48194 = CARTESIAN_POINT('',(2.2,0.E+000)); +#48195 = VECTOR('',#48196,1.); +#48196 = DIRECTION('',(-1.,0.E+000)); +#48197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48198 = ORIENTED_EDGE('',*,*,#46354,.F.); +#48199 = ORIENTED_EDGE('',*,*,#48200,.T.); +#48200 = EDGE_CURVE('',#46327,#47697,#48201,.T.); +#48201 = SURFACE_CURVE('',#48202,(#48206,#48213),.PCURVE_S1.); +#48202 = LINE('',#48203,#48204); +#48203 = CARTESIAN_POINT('',(-1.485,4.5E-002,-1.15)); +#48204 = VECTOR('',#48205,1.); +#48205 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48206 = PCURVE('',#46370,#48207); +#48207 = DEFINITIONAL_REPRESENTATION('',(#48208),#48212); +#48208 = LINE('',#48209,#48210); +#48209 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48210 = VECTOR('',#48211,1.); +#48211 = DIRECTION('',(-1.,0.E+000)); +#48212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48213 = PCURVE('',#46342,#48214); +#48214 = DEFINITIONAL_REPRESENTATION('',(#48215),#48219); +#48215 = LINE('',#48216,#48217); +#48216 = CARTESIAN_POINT('',(6.5E-002,0.E+000)); +#48217 = VECTOR('',#48218,1.); +#48218 = DIRECTION('',(0.E+000,1.)); +#48219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48220 = ORIENTED_EDGE('',*,*,#47696,.F.); +#48221 = ORIENTED_EDGE('',*,*,#47513,.T.); +#48222 = ORIENTED_EDGE('',*,*,#48223,.F.); +#48223 = EDGE_CURVE('',#48149,#47486,#48224,.T.); +#48224 = SURFACE_CURVE('',#48225,(#48229,#48236),.PCURVE_S1.); +#48225 = LINE('',#48226,#48227); +#48226 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); +#48227 = VECTOR('',#48228,1.); +#48228 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48229 = PCURVE('',#46370,#48230); +#48230 = DEFINITIONAL_REPRESENTATION('',(#48231),#48235); +#48231 = LINE('',#48232,#48233); +#48232 = CARTESIAN_POINT('',(-1.15,0.265)); +#48233 = VECTOR('',#48234,1.); +#48234 = DIRECTION('',(-1.,0.E+000)); +#48235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48236 = PCURVE('',#47501,#48237); +#48237 = DEFINITIONAL_REPRESENTATION('',(#48238),#48242); +#48238 = LINE('',#48239,#48240); +#48239 = CARTESIAN_POINT('',(2.3,0.E+000)); +#48240 = VECTOR('',#48241,1.); +#48241 = DIRECTION('',(1.,0.E+000)); +#48242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48243 = ADVANCED_FACE('',(#48244),#48167,.T.); +#48244 = FACE_BOUND('',#48245,.T.); +#48245 = EDGE_LOOP('',(#48246,#48247,#48269,#48292)); +#48246 = ORIENTED_EDGE('',*,*,#48148,.T.); +#48247 = ORIENTED_EDGE('',*,*,#48248,.T.); +#48248 = EDGE_CURVE('',#48151,#48249,#48251,.T.); +#48249 = VERTEX_POINT('',#48250); +#48250 = CARTESIAN_POINT('',(-1.115,0.165,1.05)); +#48251 = SURFACE_CURVE('',#48252,(#48256,#48262),.PCURVE_S1.); +#48252 = LINE('',#48253,#48254); +#48253 = CARTESIAN_POINT('',(-1.485,0.165,1.05)); +#48254 = VECTOR('',#48255,1.); +#48255 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48256 = PCURVE('',#48167,#48257); +#48257 = DEFINITIONAL_REPRESENTATION('',(#48258),#48261); +#48258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48259,#48260),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#45867 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#45868 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#45869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45870 = PCURVE('',#44006,#45871); -#45871 = DEFINITIONAL_REPRESENTATION('',(#45872),#45876); -#45872 = LINE('',#45873,#45874); -#45873 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#45874 = VECTOR('',#45875,1.); -#45875 = DIRECTION('',(0.E+000,1.)); -#45876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45877 = ORIENTED_EDGE('',*,*,#45878,.F.); -#45878 = EDGE_CURVE('',#45879,#45857,#45881,.T.); -#45879 = VERTEX_POINT('',#45880); -#45880 = CARTESIAN_POINT('',(-1.115,0.265,1.15)); -#45881 = SURFACE_CURVE('',#45882,(#45887,#45893),.PCURVE_S1.); -#45882 = CIRCLE('',#45883,0.1); -#45883 = AXIS2_PLACEMENT_3D('',#45884,#45885,#45886); -#45884 = CARTESIAN_POINT('',(-1.115,0.265,1.05)); -#45885 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45886 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45887 = PCURVE('',#45775,#45888); -#45888 = DEFINITIONAL_REPRESENTATION('',(#45889),#45892); -#45889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45890,#45891),.UNSPECIFIED., +#48259 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#48260 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#48261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48262 = PCURVE('',#46398,#48263); +#48263 = DEFINITIONAL_REPRESENTATION('',(#48264),#48268); +#48264 = LINE('',#48265,#48266); +#48265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#48266 = VECTOR('',#48267,1.); +#48267 = DIRECTION('',(0.E+000,1.)); +#48268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48269 = ORIENTED_EDGE('',*,*,#48270,.F.); +#48270 = EDGE_CURVE('',#48271,#48249,#48273,.T.); +#48271 = VERTEX_POINT('',#48272); +#48272 = CARTESIAN_POINT('',(-1.115,0.265,1.15)); +#48273 = SURFACE_CURVE('',#48274,(#48279,#48285),.PCURVE_S1.); +#48274 = CIRCLE('',#48275,0.1); +#48275 = AXIS2_PLACEMENT_3D('',#48276,#48277,#48278); +#48276 = CARTESIAN_POINT('',(-1.115,0.265,1.05)); +#48277 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48278 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48279 = PCURVE('',#48167,#48280); +#48280 = DEFINITIONAL_REPRESENTATION('',(#48281),#48284); +#48281 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48282,#48283),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#45890 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#45891 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#45892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45893 = PCURVE('',#44034,#45894); -#45894 = DEFINITIONAL_REPRESENTATION('',(#45895),#45899); -#45895 = CIRCLE('',#45896,0.1); -#45896 = AXIS2_PLACEMENT_2D('',#45897,#45898); -#45897 = CARTESIAN_POINT('',(-1.05,0.265)); -#45898 = DIRECTION('',(-1.,0.E+000)); -#45899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45900 = ORIENTED_EDGE('',*,*,#45901,.F.); -#45901 = EDGE_CURVE('',#45757,#45879,#45902,.T.); -#45902 = SURFACE_CURVE('',#45903,(#45907,#45913),.PCURVE_S1.); -#45903 = LINE('',#45904,#45905); -#45904 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); -#45905 = VECTOR('',#45906,1.); -#45906 = DIRECTION('',(1.,0.E+000,0.E+000)); -#45907 = PCURVE('',#45775,#45908); -#45908 = DEFINITIONAL_REPRESENTATION('',(#45909),#45912); -#45909 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#45910,#45911),.UNSPECIFIED., +#48282 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#48283 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#48284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48285 = PCURVE('',#46426,#48286); +#48286 = DEFINITIONAL_REPRESENTATION('',(#48287),#48291); +#48287 = CIRCLE('',#48288,0.1); +#48288 = AXIS2_PLACEMENT_2D('',#48289,#48290); +#48289 = CARTESIAN_POINT('',(-1.05,0.265)); +#48290 = DIRECTION('',(-1.,0.E+000)); +#48291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48292 = ORIENTED_EDGE('',*,*,#48293,.F.); +#48293 = EDGE_CURVE('',#48149,#48271,#48294,.T.); +#48294 = SURFACE_CURVE('',#48295,(#48299,#48305),.PCURVE_S1.); +#48295 = LINE('',#48296,#48297); +#48296 = CARTESIAN_POINT('',(-1.485,0.265,1.15)); +#48297 = VECTOR('',#48298,1.); +#48298 = DIRECTION('',(1.,0.E+000,0.E+000)); +#48299 = PCURVE('',#48167,#48300); +#48300 = DEFINITIONAL_REPRESENTATION('',(#48301),#48304); +#48301 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48302,#48303),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#45910 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#45911 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#45912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45913 = PCURVE('',#45109,#45914); -#45914 = DEFINITIONAL_REPRESENTATION('',(#45915),#45919); -#45915 = LINE('',#45916,#45917); -#45916 = CARTESIAN_POINT('',(2.3,0.E+000)); -#45917 = VECTOR('',#45918,1.); -#45918 = DIRECTION('',(0.E+000,1.)); -#45919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45920 = ADVANCED_FACE('',(#45921),#45109,.F.); -#45921 = FACE_BOUND('',#45922,.F.); -#45922 = EDGE_LOOP('',(#45923,#45924,#45925,#45926)); -#45923 = ORIENTED_EDGE('',*,*,#45901,.F.); -#45924 = ORIENTED_EDGE('',*,*,#45831,.T.); -#45925 = ORIENTED_EDGE('',*,*,#45093,.T.); -#45926 = ORIENTED_EDGE('',*,*,#45927,.F.); -#45927 = EDGE_CURVE('',#45879,#45071,#45928,.T.); -#45928 = SURFACE_CURVE('',#45929,(#45933,#45940),.PCURVE_S1.); -#45929 = LINE('',#45930,#45931); -#45930 = CARTESIAN_POINT('',(-1.115,0.265,1.15)); -#45931 = VECTOR('',#45932,1.); -#45932 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45933 = PCURVE('',#45109,#45934); -#45934 = DEFINITIONAL_REPRESENTATION('',(#45935),#45939); -#45935 = LINE('',#45936,#45937); -#45936 = CARTESIAN_POINT('',(2.3,0.37)); -#45937 = VECTOR('',#45938,1.); -#45938 = DIRECTION('',(1.,0.E+000)); -#45939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45940 = PCURVE('',#44034,#45941); -#45941 = DEFINITIONAL_REPRESENTATION('',(#45942),#45946); -#45942 = LINE('',#45943,#45944); -#45943 = CARTESIAN_POINT('',(-1.15,0.265)); -#45944 = VECTOR('',#45945,1.); -#45945 = DIRECTION('',(-1.,0.E+000)); -#45946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45947 = ADVANCED_FACE('',(#45948),#44034,.F.); -#45948 = FACE_BOUND('',#45949,.F.); -#45949 = EDGE_LOOP('',(#45950,#45951,#45952,#45953,#45954,#45975,#45976) - ); -#45950 = ORIENTED_EDGE('',*,*,#45878,.F.); -#45951 = ORIENTED_EDGE('',*,*,#45927,.T.); -#45952 = ORIENTED_EDGE('',*,*,#45070,.F.); -#45953 = ORIENTED_EDGE('',*,*,#45425,.T.); -#45954 = ORIENTED_EDGE('',*,*,#45955,.F.); -#45955 = EDGE_CURVE('',#44019,#45426,#45956,.T.); -#45956 = SURFACE_CURVE('',#45957,(#45961,#45968),.PCURVE_S1.); -#45957 = LINE('',#45958,#45959); -#45958 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); -#45959 = VECTOR('',#45960,1.); -#45960 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45961 = PCURVE('',#44034,#45962); -#45962 = DEFINITIONAL_REPRESENTATION('',(#45963),#45967); -#45963 = LINE('',#45964,#45965); -#45964 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#45965 = VECTOR('',#45966,1.); -#45966 = DIRECTION('',(-1.,0.E+000)); -#45967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45968 = PCURVE('',#44062,#45969); -#45969 = DEFINITIONAL_REPRESENTATION('',(#45970),#45974); -#45970 = LINE('',#45971,#45972); -#45971 = CARTESIAN_POINT('',(0.435,0.E+000)); -#45972 = VECTOR('',#45973,1.); -#45973 = DIRECTION('',(0.E+000,1.)); -#45974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45975 = ORIENTED_EDGE('',*,*,#44018,.T.); -#45976 = ORIENTED_EDGE('',*,*,#45977,.T.); -#45977 = EDGE_CURVE('',#43991,#45857,#45978,.T.); -#45978 = SURFACE_CURVE('',#45979,(#45983,#45990),.PCURVE_S1.); -#45979 = LINE('',#45980,#45981); -#45980 = CARTESIAN_POINT('',(-1.115,0.165,-1.15)); -#45981 = VECTOR('',#45982,1.); -#45982 = DIRECTION('',(0.E+000,0.E+000,1.)); -#45983 = PCURVE('',#44034,#45984); -#45984 = DEFINITIONAL_REPRESENTATION('',(#45985),#45989); -#45985 = LINE('',#45986,#45987); -#45986 = CARTESIAN_POINT('',(1.15,0.165)); -#45987 = VECTOR('',#45988,1.); -#45988 = DIRECTION('',(-1.,0.E+000)); -#45989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45990 = PCURVE('',#44006,#45991); -#45991 = DEFINITIONAL_REPRESENTATION('',(#45992),#45996); -#45992 = LINE('',#45993,#45994); -#45993 = CARTESIAN_POINT('',(2.2,0.37)); -#45994 = VECTOR('',#45995,1.); -#45995 = DIRECTION('',(-1.,0.E+000)); -#45996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#45997 = ADVANCED_FACE('',(#45998),#43950,.T.); -#45998 = FACE_BOUND('',#45999,.F.); -#45999 = EDGE_LOOP('',(#46000,#46001,#46002,#46045)); -#46000 = ORIENTED_EDGE('',*,*,#45808,.F.); -#46001 = ORIENTED_EDGE('',*,*,#43934,.F.); -#46002 = ORIENTED_EDGE('',*,*,#46003,.T.); -#46003 = EDGE_CURVE('',#43907,#45329,#46004,.T.); -#46004 = SURFACE_CURVE('',#46005,(#46009,#46016),.PCURVE_S1.); -#46005 = LINE('',#46006,#46007); -#46006 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); -#46007 = VECTOR('',#46008,1.); -#46008 = DIRECTION('',(3.625473254942E-011,0.E+000,1.)); -#46009 = PCURVE('',#43950,#46010); -#46010 = DEFINITIONAL_REPRESENTATION('',(#46011),#46015); -#46011 = LINE('',#46012,#46013); -#46012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#46013 = VECTOR('',#46014,1.); -#46014 = DIRECTION('',(3.625473254942E-011,1.)); -#46015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46016 = PCURVE('',#43923,#46017); -#46017 = DEFINITIONAL_REPRESENTATION('',(#46018),#46044); -#46018 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46019,#46020,#46021,#46022, - #46023,#46024,#46025,#46026,#46027,#46028,#46029,#46030,#46031, - #46032,#46033,#46034,#46035,#46036,#46037,#46038,#46039,#46040, - #46041,#46042,#46043),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48302 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#48303 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#48304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48305 = PCURVE('',#47501,#48306); +#48306 = DEFINITIONAL_REPRESENTATION('',(#48307),#48311); +#48307 = LINE('',#48308,#48309); +#48308 = CARTESIAN_POINT('',(2.3,0.E+000)); +#48309 = VECTOR('',#48310,1.); +#48310 = DIRECTION('',(0.E+000,1.)); +#48311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48312 = ADVANCED_FACE('',(#48313),#47501,.F.); +#48313 = FACE_BOUND('',#48314,.F.); +#48314 = EDGE_LOOP('',(#48315,#48316,#48317,#48318)); +#48315 = ORIENTED_EDGE('',*,*,#48293,.F.); +#48316 = ORIENTED_EDGE('',*,*,#48223,.T.); +#48317 = ORIENTED_EDGE('',*,*,#47485,.T.); +#48318 = ORIENTED_EDGE('',*,*,#48319,.F.); +#48319 = EDGE_CURVE('',#48271,#47463,#48320,.T.); +#48320 = SURFACE_CURVE('',#48321,(#48325,#48332),.PCURVE_S1.); +#48321 = LINE('',#48322,#48323); +#48322 = CARTESIAN_POINT('',(-1.115,0.265,1.15)); +#48323 = VECTOR('',#48324,1.); +#48324 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48325 = PCURVE('',#47501,#48326); +#48326 = DEFINITIONAL_REPRESENTATION('',(#48327),#48331); +#48327 = LINE('',#48328,#48329); +#48328 = CARTESIAN_POINT('',(2.3,0.37)); +#48329 = VECTOR('',#48330,1.); +#48330 = DIRECTION('',(1.,0.E+000)); +#48331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48332 = PCURVE('',#46426,#48333); +#48333 = DEFINITIONAL_REPRESENTATION('',(#48334),#48338); +#48334 = LINE('',#48335,#48336); +#48335 = CARTESIAN_POINT('',(-1.15,0.265)); +#48336 = VECTOR('',#48337,1.); +#48337 = DIRECTION('',(-1.,0.E+000)); +#48338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48339 = ADVANCED_FACE('',(#48340),#46426,.F.); +#48340 = FACE_BOUND('',#48341,.F.); +#48341 = EDGE_LOOP('',(#48342,#48343,#48344,#48345,#48346,#48367,#48368) + ); +#48342 = ORIENTED_EDGE('',*,*,#48270,.F.); +#48343 = ORIENTED_EDGE('',*,*,#48319,.T.); +#48344 = ORIENTED_EDGE('',*,*,#47462,.F.); +#48345 = ORIENTED_EDGE('',*,*,#47817,.T.); +#48346 = ORIENTED_EDGE('',*,*,#48347,.F.); +#48347 = EDGE_CURVE('',#46411,#47818,#48348,.T.); +#48348 = SURFACE_CURVE('',#48349,(#48353,#48360),.PCURVE_S1.); +#48349 = LINE('',#48350,#48351); +#48350 = CARTESIAN_POINT('',(-1.115,4.5E-002,-1.15)); +#48351 = VECTOR('',#48352,1.); +#48352 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48353 = PCURVE('',#46426,#48354); +#48354 = DEFINITIONAL_REPRESENTATION('',(#48355),#48359); +#48355 = LINE('',#48356,#48357); +#48356 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48357 = VECTOR('',#48358,1.); +#48358 = DIRECTION('',(-1.,0.E+000)); +#48359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48360 = PCURVE('',#46454,#48361); +#48361 = DEFINITIONAL_REPRESENTATION('',(#48362),#48366); +#48362 = LINE('',#48363,#48364); +#48363 = CARTESIAN_POINT('',(0.435,0.E+000)); +#48364 = VECTOR('',#48365,1.); +#48365 = DIRECTION('',(0.E+000,1.)); +#48366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48367 = ORIENTED_EDGE('',*,*,#46410,.T.); +#48368 = ORIENTED_EDGE('',*,*,#48369,.T.); +#48369 = EDGE_CURVE('',#46383,#48249,#48370,.T.); +#48370 = SURFACE_CURVE('',#48371,(#48375,#48382),.PCURVE_S1.); +#48371 = LINE('',#48372,#48373); +#48372 = CARTESIAN_POINT('',(-1.115,0.165,-1.15)); +#48373 = VECTOR('',#48374,1.); +#48374 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48375 = PCURVE('',#46426,#48376); +#48376 = DEFINITIONAL_REPRESENTATION('',(#48377),#48381); +#48377 = LINE('',#48378,#48379); +#48378 = CARTESIAN_POINT('',(1.15,0.165)); +#48379 = VECTOR('',#48380,1.); +#48380 = DIRECTION('',(-1.,0.E+000)); +#48381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48382 = PCURVE('',#46398,#48383); +#48383 = DEFINITIONAL_REPRESENTATION('',(#48384),#48388); +#48384 = LINE('',#48385,#48386); +#48385 = CARTESIAN_POINT('',(2.2,0.37)); +#48386 = VECTOR('',#48387,1.); +#48387 = DIRECTION('',(-1.,0.E+000)); +#48388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48389 = ADVANCED_FACE('',(#48390),#46342,.T.); +#48390 = FACE_BOUND('',#48391,.F.); +#48391 = EDGE_LOOP('',(#48392,#48393,#48394,#48437)); +#48392 = ORIENTED_EDGE('',*,*,#48200,.F.); +#48393 = ORIENTED_EDGE('',*,*,#46326,.F.); +#48394 = ORIENTED_EDGE('',*,*,#48395,.T.); +#48395 = EDGE_CURVE('',#46299,#47721,#48396,.T.); +#48396 = SURFACE_CURVE('',#48397,(#48401,#48408),.PCURVE_S1.); +#48397 = LINE('',#48398,#48399); +#48398 = CARTESIAN_POINT('',(-1.55,4.5E-002,-1.15)); +#48399 = VECTOR('',#48400,1.); +#48400 = DIRECTION('',(3.625473254942E-011,0.E+000,1.)); +#48401 = PCURVE('',#46342,#48402); +#48402 = DEFINITIONAL_REPRESENTATION('',(#48403),#48407); +#48403 = LINE('',#48404,#48405); +#48404 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#48405 = VECTOR('',#48406,1.); +#48406 = DIRECTION('',(3.625473254942E-011,1.)); +#48407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48408 = PCURVE('',#46315,#48409); +#48409 = DEFINITIONAL_REPRESENTATION('',(#48410),#48436); +#48410 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48411,#48412,#48413,#48414, + #48415,#48416,#48417,#48418,#48419,#48420,#48421,#48422,#48423, + #48424,#48425,#48426,#48427,#48428,#48429,#48430,#48431,#48432, + #48433,#48434,#48435),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46019 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#46020 = CARTESIAN_POINT('',(4.712388980392,3.787878787879E-002)); -#46021 = CARTESIAN_POINT('',(4.712388980405,0.113636363636)); -#46022 = CARTESIAN_POINT('',(4.712388980426,0.227272727273)); -#46023 = CARTESIAN_POINT('',(4.712388980446,0.340909090909)); -#46024 = CARTESIAN_POINT('',(4.712388980467,0.454545454545)); -#46025 = CARTESIAN_POINT('',(4.712388980488,0.568181818182)); -#46026 = CARTESIAN_POINT('',(4.712388980508,0.681818181818)); -#46027 = CARTESIAN_POINT('',(4.712388980529,0.795454545455)); -#46028 = CARTESIAN_POINT('',(4.712388980549,0.909090909091)); -#46029 = CARTESIAN_POINT('',(4.71238898057,1.022727272727)); -#46030 = CARTESIAN_POINT('',(4.712388980591,1.136363636364)); -#46031 = CARTESIAN_POINT('',(4.712388980611,1.25)); -#46032 = CARTESIAN_POINT('',(4.712388980632,1.363636363636)); -#46033 = CARTESIAN_POINT('',(4.712388980652,1.477272727273)); -#46034 = CARTESIAN_POINT('',(4.712388980673,1.590909090909)); -#46035 = CARTESIAN_POINT('',(4.712388980694,1.704545454545)); -#46036 = CARTESIAN_POINT('',(4.712388980714,1.818181818182)); -#46037 = CARTESIAN_POINT('',(4.712388980735,1.931818181818)); -#46038 = CARTESIAN_POINT('',(4.712388980755,2.045454545455)); -#46039 = CARTESIAN_POINT('',(4.712388980776,2.159090909091)); -#46040 = CARTESIAN_POINT('',(4.712388980797,2.272727272727)); -#46041 = CARTESIAN_POINT('',(4.712388980817,2.386363636364)); -#46042 = CARTESIAN_POINT('',(4.712388980831,2.462121212121)); -#46043 = CARTESIAN_POINT('',(4.712388980838,2.5)); -#46044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46045 = ORIENTED_EDGE('',*,*,#45378,.T.); -#46046 = ADVANCED_FACE('',(#46047),#44062,.T.); -#46047 = FACE_BOUND('',#46048,.F.); -#46048 = EDGE_LOOP('',(#46049,#46070,#46071,#46072)); -#46049 = ORIENTED_EDGE('',*,*,#46050,.F.); -#46050 = EDGE_CURVE('',#44047,#45402,#46051,.T.); -#46051 = SURFACE_CURVE('',#46052,(#46056,#46063),.PCURVE_S1.); -#46052 = LINE('',#46053,#46054); -#46053 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); -#46054 = VECTOR('',#46055,1.); -#46055 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46056 = PCURVE('',#44062,#46057); -#46057 = DEFINITIONAL_REPRESENTATION('',(#46058),#46062); -#46058 = LINE('',#46059,#46060); -#46059 = CARTESIAN_POINT('',(0.715,0.E+000)); -#46060 = VECTOR('',#46061,1.); -#46061 = DIRECTION('',(0.E+000,1.)); -#46062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46063 = PCURVE('',#44090,#46064); -#46064 = DEFINITIONAL_REPRESENTATION('',(#46065),#46069); -#46065 = LINE('',#46066,#46067); -#46066 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46067 = VECTOR('',#46068,1.); -#46068 = DIRECTION('',(-1.,0.E+000)); -#46069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46070 = ORIENTED_EDGE('',*,*,#44046,.F.); -#46071 = ORIENTED_EDGE('',*,*,#45955,.T.); -#46072 = ORIENTED_EDGE('',*,*,#45448,.T.); -#46073 = ADVANCED_FACE('',(#46074),#44174,.T.); -#46074 = FACE_BOUND('',#46075,.F.); -#46075 = EDGE_LOOP('',(#46076,#46097,#46098,#46119)); -#46076 = ORIENTED_EDGE('',*,*,#46077,.F.); -#46077 = EDGE_CURVE('',#44159,#45472,#46078,.T.); -#46078 = SURFACE_CURVE('',#46079,(#46083,#46090),.PCURVE_S1.); -#46079 = LINE('',#46080,#46081); -#46080 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); -#46081 = VECTOR('',#46082,1.); -#46082 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46083 = PCURVE('',#44174,#46084); -#46084 = DEFINITIONAL_REPRESENTATION('',(#46085),#46089); -#46085 = LINE('',#46086,#46087); -#46086 = CARTESIAN_POINT('',(1.365,0.E+000)); -#46087 = VECTOR('',#46088,1.); -#46088 = DIRECTION('',(0.E+000,1.)); -#46089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46090 = PCURVE('',#44202,#46091); -#46091 = DEFINITIONAL_REPRESENTATION('',(#46092),#46096); -#46092 = LINE('',#46093,#46094); -#46093 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46094 = VECTOR('',#46095,1.); -#46095 = DIRECTION('',(-1.,0.E+000)); -#46096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46097 = ORIENTED_EDGE('',*,*,#44158,.F.); -#46098 = ORIENTED_EDGE('',*,*,#46099,.T.); -#46099 = EDGE_CURVE('',#44131,#45496,#46100,.T.); -#46100 = SURFACE_CURVE('',#46101,(#46105,#46112),.PCURVE_S1.); -#46101 = LINE('',#46102,#46103); -#46102 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); -#46103 = VECTOR('',#46104,1.); -#46104 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46105 = PCURVE('',#44174,#46106); -#46106 = DEFINITIONAL_REPRESENTATION('',(#46107),#46111); -#46107 = LINE('',#46108,#46109); -#46108 = CARTESIAN_POINT('',(1.085,0.E+000)); -#46109 = VECTOR('',#46110,1.); -#46110 = DIRECTION('',(0.E+000,1.)); -#46111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46112 = PCURVE('',#44146,#46113); -#46113 = DEFINITIONAL_REPRESENTATION('',(#46114),#46118); -#46114 = LINE('',#46115,#46116); -#46115 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46116 = VECTOR('',#46117,1.); -#46117 = DIRECTION('',(-1.,0.E+000)); -#46118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46119 = ORIENTED_EDGE('',*,*,#45518,.T.); -#46120 = ADVANCED_FACE('',(#46121),#44286,.T.); -#46121 = FACE_BOUND('',#46122,.F.); -#46122 = EDGE_LOOP('',(#46123,#46144,#46145,#46166)); -#46123 = ORIENTED_EDGE('',*,*,#46124,.F.); -#46124 = EDGE_CURVE('',#44271,#45542,#46125,.T.); -#46125 = SURFACE_CURVE('',#46126,(#46130,#46137),.PCURVE_S1.); -#46126 = LINE('',#46127,#46128); -#46127 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); -#46128 = VECTOR('',#46129,1.); -#46129 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46130 = PCURVE('',#44286,#46131); -#46131 = DEFINITIONAL_REPRESENTATION('',(#46132),#46136); -#46132 = LINE('',#46133,#46134); -#46133 = CARTESIAN_POINT('',(2.015,0.E+000)); -#46134 = VECTOR('',#46135,1.); -#46135 = DIRECTION('',(0.E+000,1.)); -#46136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46137 = PCURVE('',#44314,#46138); -#46138 = DEFINITIONAL_REPRESENTATION('',(#46139),#46143); -#46139 = LINE('',#46140,#46141); -#46140 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46141 = VECTOR('',#46142,1.); -#46142 = DIRECTION('',(-1.,0.E+000)); -#46143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46144 = ORIENTED_EDGE('',*,*,#44270,.F.); -#46145 = ORIENTED_EDGE('',*,*,#46146,.T.); -#46146 = EDGE_CURVE('',#44243,#45566,#46147,.T.); -#46147 = SURFACE_CURVE('',#46148,(#46152,#46159),.PCURVE_S1.); -#46148 = LINE('',#46149,#46150); -#46149 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); -#46150 = VECTOR('',#46151,1.); -#46151 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46152 = PCURVE('',#44286,#46153); -#46153 = DEFINITIONAL_REPRESENTATION('',(#46154),#46158); -#46154 = LINE('',#46155,#46156); -#46155 = CARTESIAN_POINT('',(1.735,0.E+000)); -#46156 = VECTOR('',#46157,1.); -#46157 = DIRECTION('',(0.E+000,1.)); -#46158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46159 = PCURVE('',#44258,#46160); -#46160 = DEFINITIONAL_REPRESENTATION('',(#46161),#46165); -#46161 = LINE('',#46162,#46163); -#46162 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46163 = VECTOR('',#46164,1.); -#46164 = DIRECTION('',(-1.,0.E+000)); -#46165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46166 = ORIENTED_EDGE('',*,*,#45588,.T.); -#46167 = ADVANCED_FACE('',(#46168),#44398,.T.); -#46168 = FACE_BOUND('',#46169,.F.); -#46169 = EDGE_LOOP('',(#46170,#46171,#46172,#46193)); -#46170 = ORIENTED_EDGE('',*,*,#44539,.F.); -#46171 = ORIENTED_EDGE('',*,*,#44382,.F.); -#46172 = ORIENTED_EDGE('',*,*,#46173,.T.); -#46173 = EDGE_CURVE('',#44355,#45614,#46174,.T.); -#46174 = SURFACE_CURVE('',#46175,(#46179,#46186),.PCURVE_S1.); -#46175 = LINE('',#46176,#46177); -#46176 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); -#46177 = VECTOR('',#46178,1.); -#46178 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46179 = PCURVE('',#44398,#46180); -#46180 = DEFINITIONAL_REPRESENTATION('',(#46181),#46185); -#46181 = LINE('',#46182,#46183); -#46182 = CARTESIAN_POINT('',(2.385,0.E+000)); -#46183 = VECTOR('',#46184,1.); -#46184 = DIRECTION('',(0.E+000,1.)); -#46185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46186 = PCURVE('',#44370,#46187); -#46187 = DEFINITIONAL_REPRESENTATION('',(#46188),#46192); -#46188 = LINE('',#46189,#46190); -#46189 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46190 = VECTOR('',#46191,1.); -#46191 = DIRECTION('',(-1.,0.E+000)); -#46192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46193 = ORIENTED_EDGE('',*,*,#45636,.T.); -#46194 = ADVANCED_FACE('',(#46195),#43232,.T.); -#46195 = FACE_BOUND('',#46196,.F.); -#46196 = EDGE_LOOP('',(#46197,#46218,#46219,#46262)); -#46197 = ORIENTED_EDGE('',*,*,#46198,.T.); -#46198 = EDGE_CURVE('',#43189,#45660,#46199,.T.); -#46199 = SURFACE_CURVE('',#46200,(#46204,#46211),.PCURVE_S1.); -#46200 = LINE('',#46201,#46202); -#46201 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); -#46202 = VECTOR('',#46203,1.); -#46203 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46204 = PCURVE('',#43232,#46205); -#46205 = DEFINITIONAL_REPRESENTATION('',(#46206),#46210); -#46206 = LINE('',#46207,#46208); -#46207 = CARTESIAN_POINT('',(3.035,0.E+000)); -#46208 = VECTOR('',#46209,1.); -#46209 = DIRECTION('',(0.E+000,1.)); -#46210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46211 = PCURVE('',#43204,#46212); -#46212 = DEFINITIONAL_REPRESENTATION('',(#46213),#46217); -#46213 = LINE('',#46214,#46215); -#46214 = CARTESIAN_POINT('',(1.15,4.5E-002)); -#46215 = VECTOR('',#46216,1.); -#46216 = DIRECTION('',(-1.,0.E+000)); -#46217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#48411 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#48412 = CARTESIAN_POINT('',(4.712388980392,3.787878787879E-002)); +#48413 = CARTESIAN_POINT('',(4.712388980405,0.113636363636)); +#48414 = CARTESIAN_POINT('',(4.712388980426,0.227272727273)); +#48415 = CARTESIAN_POINT('',(4.712388980446,0.340909090909)); +#48416 = CARTESIAN_POINT('',(4.712388980467,0.454545454545)); +#48417 = CARTESIAN_POINT('',(4.712388980488,0.568181818182)); +#48418 = CARTESIAN_POINT('',(4.712388980508,0.681818181818)); +#48419 = CARTESIAN_POINT('',(4.712388980529,0.795454545455)); +#48420 = CARTESIAN_POINT('',(4.712388980549,0.909090909091)); +#48421 = CARTESIAN_POINT('',(4.71238898057,1.022727272727)); +#48422 = CARTESIAN_POINT('',(4.712388980591,1.136363636364)); +#48423 = CARTESIAN_POINT('',(4.712388980611,1.25)); +#48424 = CARTESIAN_POINT('',(4.712388980632,1.363636363636)); +#48425 = CARTESIAN_POINT('',(4.712388980652,1.477272727273)); +#48426 = CARTESIAN_POINT('',(4.712388980673,1.590909090909)); +#48427 = CARTESIAN_POINT('',(4.712388980694,1.704545454545)); +#48428 = CARTESIAN_POINT('',(4.712388980714,1.818181818182)); +#48429 = CARTESIAN_POINT('',(4.712388980735,1.931818181818)); +#48430 = CARTESIAN_POINT('',(4.712388980755,2.045454545455)); +#48431 = CARTESIAN_POINT('',(4.712388980776,2.159090909091)); +#48432 = CARTESIAN_POINT('',(4.712388980797,2.272727272727)); +#48433 = CARTESIAN_POINT('',(4.712388980817,2.386363636364)); +#48434 = CARTESIAN_POINT('',(4.712388980831,2.462121212121)); +#48435 = CARTESIAN_POINT('',(4.712388980838,2.5)); +#48436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48437 = ORIENTED_EDGE('',*,*,#47770,.T.); +#48438 = ADVANCED_FACE('',(#48439),#46454,.T.); +#48439 = FACE_BOUND('',#48440,.F.); +#48440 = EDGE_LOOP('',(#48441,#48462,#48463,#48464)); +#48441 = ORIENTED_EDGE('',*,*,#48442,.F.); +#48442 = EDGE_CURVE('',#46439,#47794,#48443,.T.); +#48443 = SURFACE_CURVE('',#48444,(#48448,#48455),.PCURVE_S1.); +#48444 = LINE('',#48445,#48446); +#48445 = CARTESIAN_POINT('',(-0.835,4.5E-002,-1.15)); +#48446 = VECTOR('',#48447,1.); +#48447 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48448 = PCURVE('',#46454,#48449); +#48449 = DEFINITIONAL_REPRESENTATION('',(#48450),#48454); +#48450 = LINE('',#48451,#48452); +#48451 = CARTESIAN_POINT('',(0.715,0.E+000)); +#48452 = VECTOR('',#48453,1.); +#48453 = DIRECTION('',(0.E+000,1.)); +#48454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48455 = PCURVE('',#46482,#48456); +#48456 = DEFINITIONAL_REPRESENTATION('',(#48457),#48461); +#48457 = LINE('',#48458,#48459); +#48458 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48459 = VECTOR('',#48460,1.); +#48460 = DIRECTION('',(-1.,0.E+000)); +#48461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48462 = ORIENTED_EDGE('',*,*,#46438,.F.); +#48463 = ORIENTED_EDGE('',*,*,#48347,.T.); +#48464 = ORIENTED_EDGE('',*,*,#47840,.T.); +#48465 = ADVANCED_FACE('',(#48466),#46566,.T.); +#48466 = FACE_BOUND('',#48467,.F.); +#48467 = EDGE_LOOP('',(#48468,#48489,#48490,#48511)); +#48468 = ORIENTED_EDGE('',*,*,#48469,.F.); +#48469 = EDGE_CURVE('',#46551,#47864,#48470,.T.); +#48470 = SURFACE_CURVE('',#48471,(#48475,#48482),.PCURVE_S1.); +#48471 = LINE('',#48472,#48473); +#48472 = CARTESIAN_POINT('',(-0.185,4.5E-002,-1.15)); +#48473 = VECTOR('',#48474,1.); +#48474 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48475 = PCURVE('',#46566,#48476); +#48476 = DEFINITIONAL_REPRESENTATION('',(#48477),#48481); +#48477 = LINE('',#48478,#48479); +#48478 = CARTESIAN_POINT('',(1.365,0.E+000)); +#48479 = VECTOR('',#48480,1.); +#48480 = DIRECTION('',(0.E+000,1.)); +#48481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48482 = PCURVE('',#46594,#48483); +#48483 = DEFINITIONAL_REPRESENTATION('',(#48484),#48488); +#48484 = LINE('',#48485,#48486); +#48485 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48486 = VECTOR('',#48487,1.); +#48487 = DIRECTION('',(-1.,0.E+000)); +#48488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48489 = ORIENTED_EDGE('',*,*,#46550,.F.); +#48490 = ORIENTED_EDGE('',*,*,#48491,.T.); +#48491 = EDGE_CURVE('',#46523,#47888,#48492,.T.); +#48492 = SURFACE_CURVE('',#48493,(#48497,#48504),.PCURVE_S1.); +#48493 = LINE('',#48494,#48495); +#48494 = CARTESIAN_POINT('',(-0.465,4.5E-002,-1.15)); +#48495 = VECTOR('',#48496,1.); +#48496 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48497 = PCURVE('',#46566,#48498); +#48498 = DEFINITIONAL_REPRESENTATION('',(#48499),#48503); +#48499 = LINE('',#48500,#48501); +#48500 = CARTESIAN_POINT('',(1.085,0.E+000)); +#48501 = VECTOR('',#48502,1.); +#48502 = DIRECTION('',(0.E+000,1.)); +#48503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48504 = PCURVE('',#46538,#48505); +#48505 = DEFINITIONAL_REPRESENTATION('',(#48506),#48510); +#48506 = LINE('',#48507,#48508); +#48507 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48508 = VECTOR('',#48509,1.); +#48509 = DIRECTION('',(-1.,0.E+000)); +#48510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48511 = ORIENTED_EDGE('',*,*,#47910,.T.); +#48512 = ADVANCED_FACE('',(#48513),#46678,.T.); +#48513 = FACE_BOUND('',#48514,.F.); +#48514 = EDGE_LOOP('',(#48515,#48536,#48537,#48558)); +#48515 = ORIENTED_EDGE('',*,*,#48516,.F.); +#48516 = EDGE_CURVE('',#46663,#47934,#48517,.T.); +#48517 = SURFACE_CURVE('',#48518,(#48522,#48529),.PCURVE_S1.); +#48518 = LINE('',#48519,#48520); +#48519 = CARTESIAN_POINT('',(0.465,4.5E-002,-1.15)); +#48520 = VECTOR('',#48521,1.); +#48521 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48522 = PCURVE('',#46678,#48523); +#48523 = DEFINITIONAL_REPRESENTATION('',(#48524),#48528); +#48524 = LINE('',#48525,#48526); +#48525 = CARTESIAN_POINT('',(2.015,0.E+000)); +#48526 = VECTOR('',#48527,1.); +#48527 = DIRECTION('',(0.E+000,1.)); +#48528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48529 = PCURVE('',#46706,#48530); +#48530 = DEFINITIONAL_REPRESENTATION('',(#48531),#48535); +#48531 = LINE('',#48532,#48533); +#48532 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48533 = VECTOR('',#48534,1.); +#48534 = DIRECTION('',(-1.,0.E+000)); +#48535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48536 = ORIENTED_EDGE('',*,*,#46662,.F.); +#48537 = ORIENTED_EDGE('',*,*,#48538,.T.); +#48538 = EDGE_CURVE('',#46635,#47958,#48539,.T.); +#48539 = SURFACE_CURVE('',#48540,(#48544,#48551),.PCURVE_S1.); +#48540 = LINE('',#48541,#48542); +#48541 = CARTESIAN_POINT('',(0.185,4.5E-002,-1.15)); +#48542 = VECTOR('',#48543,1.); +#48543 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48544 = PCURVE('',#46678,#48545); +#48545 = DEFINITIONAL_REPRESENTATION('',(#48546),#48550); +#48546 = LINE('',#48547,#48548); +#48547 = CARTESIAN_POINT('',(1.735,0.E+000)); +#48548 = VECTOR('',#48549,1.); +#48549 = DIRECTION('',(0.E+000,1.)); +#48550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48551 = PCURVE('',#46650,#48552); +#48552 = DEFINITIONAL_REPRESENTATION('',(#48553),#48557); +#48553 = LINE('',#48554,#48555); +#48554 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48555 = VECTOR('',#48556,1.); +#48556 = DIRECTION('',(-1.,0.E+000)); +#48557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48558 = ORIENTED_EDGE('',*,*,#47980,.T.); +#48559 = ADVANCED_FACE('',(#48560),#46790,.T.); +#48560 = FACE_BOUND('',#48561,.F.); +#48561 = EDGE_LOOP('',(#48562,#48563,#48564,#48585)); +#48562 = ORIENTED_EDGE('',*,*,#46931,.F.); +#48563 = ORIENTED_EDGE('',*,*,#46774,.F.); +#48564 = ORIENTED_EDGE('',*,*,#48565,.T.); +#48565 = EDGE_CURVE('',#46747,#48006,#48566,.T.); +#48566 = SURFACE_CURVE('',#48567,(#48571,#48578),.PCURVE_S1.); +#48567 = LINE('',#48568,#48569); +#48568 = CARTESIAN_POINT('',(0.835,4.5E-002,-1.15)); +#48569 = VECTOR('',#48570,1.); +#48570 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48571 = PCURVE('',#46790,#48572); +#48572 = DEFINITIONAL_REPRESENTATION('',(#48573),#48577); +#48573 = LINE('',#48574,#48575); +#48574 = CARTESIAN_POINT('',(2.385,0.E+000)); +#48575 = VECTOR('',#48576,1.); +#48576 = DIRECTION('',(0.E+000,1.)); +#48577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48578 = PCURVE('',#46762,#48579); +#48579 = DEFINITIONAL_REPRESENTATION('',(#48580),#48584); +#48580 = LINE('',#48581,#48582); +#48581 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48582 = VECTOR('',#48583,1.); +#48583 = DIRECTION('',(-1.,0.E+000)); +#48584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48585 = ORIENTED_EDGE('',*,*,#48028,.T.); +#48586 = ADVANCED_FACE('',(#48587),#45624,.T.); +#48587 = FACE_BOUND('',#48588,.F.); +#48588 = EDGE_LOOP('',(#48589,#48610,#48611,#48654)); +#48589 = ORIENTED_EDGE('',*,*,#48590,.T.); +#48590 = EDGE_CURVE('',#45581,#48052,#48591,.T.); +#48591 = SURFACE_CURVE('',#48592,(#48596,#48603),.PCURVE_S1.); +#48592 = LINE('',#48593,#48594); +#48593 = CARTESIAN_POINT('',(1.485,4.5E-002,-1.15)); +#48594 = VECTOR('',#48595,1.); +#48595 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48596 = PCURVE('',#45624,#48597); +#48597 = DEFINITIONAL_REPRESENTATION('',(#48598),#48602); +#48598 = LINE('',#48599,#48600); +#48599 = CARTESIAN_POINT('',(3.035,0.E+000)); +#48600 = VECTOR('',#48601,1.); +#48601 = DIRECTION('',(0.E+000,1.)); +#48602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#46218 = ORIENTED_EDGE('',*,*,#45682,.T.); -#46219 = ORIENTED_EDGE('',*,*,#46220,.F.); -#46220 = EDGE_CURVE('',#43217,#45683,#46221,.T.); -#46221 = SURFACE_CURVE('',#46222,(#46226,#46233),.PCURVE_S1.); -#46222 = LINE('',#46223,#46224); -#46223 = CARTESIAN_POINT('',(1.55,4.5E-002,-1.15)); -#46224 = VECTOR('',#46225,1.); -#46225 = DIRECTION('',(-1.011119188377E-010,0.E+000,1.)); -#46226 = PCURVE('',#43232,#46227); -#46227 = DEFINITIONAL_REPRESENTATION('',(#46228),#46232); -#46228 = LINE('',#46229,#46230); -#46229 = CARTESIAN_POINT('',(3.1,0.E+000)); -#46230 = VECTOR('',#46231,1.); -#46231 = DIRECTION('',(-1.011119188377E-010,1.)); -#46232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46233 = PCURVE('',#43261,#46234); -#46234 = DEFINITIONAL_REPRESENTATION('',(#46235),#46261); -#46235 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46236,#46237,#46238,#46239, - #46240,#46241,#46242,#46243,#46244,#46245,#46246,#46247,#46248, - #46249,#46250,#46251,#46252,#46253,#46254,#46255,#46256,#46257, - #46258,#46259,#46260),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48603 = PCURVE('',#45596,#48604); +#48604 = DEFINITIONAL_REPRESENTATION('',(#48605),#48609); +#48605 = LINE('',#48606,#48607); +#48606 = CARTESIAN_POINT('',(1.15,4.5E-002)); +#48607 = VECTOR('',#48608,1.); +#48608 = DIRECTION('',(-1.,0.E+000)); +#48609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48610 = ORIENTED_EDGE('',*,*,#48074,.T.); +#48611 = ORIENTED_EDGE('',*,*,#48612,.F.); +#48612 = EDGE_CURVE('',#45609,#48075,#48613,.T.); +#48613 = SURFACE_CURVE('',#48614,(#48618,#48625),.PCURVE_S1.); +#48614 = LINE('',#48615,#48616); +#48615 = CARTESIAN_POINT('',(1.55,4.5E-002,-1.15)); +#48616 = VECTOR('',#48617,1.); +#48617 = DIRECTION('',(-1.011119188377E-010,0.E+000,1.)); +#48618 = PCURVE('',#45624,#48619); +#48619 = DEFINITIONAL_REPRESENTATION('',(#48620),#48624); +#48620 = LINE('',#48621,#48622); +#48621 = CARTESIAN_POINT('',(3.1,0.E+000)); +#48622 = VECTOR('',#48623,1.); +#48623 = DIRECTION('',(-1.011119188377E-010,1.)); +#48624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48625 = PCURVE('',#45653,#48626); +#48626 = DEFINITIONAL_REPRESENTATION('',(#48627),#48653); +#48627 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48628,#48629,#48630,#48631, + #48632,#48633,#48634,#48635,#48636,#48637,#48638,#48639,#48640, + #48641,#48642,#48643,#48644,#48645,#48646,#48647,#48648,#48649, + #48650,#48651,#48652),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46236 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#46237 = CARTESIAN_POINT('',(4.712388980366,3.787878787879E-002)); -#46238 = CARTESIAN_POINT('',(4.712388980327,0.113636363636)); -#46239 = CARTESIAN_POINT('',(4.71238898027,0.227272727273)); -#46240 = CARTESIAN_POINT('',(4.712388980212,0.340909090909)); -#46241 = CARTESIAN_POINT('',(4.712388980155,0.454545454545)); -#46242 = CARTESIAN_POINT('',(4.712388980097,0.568181818182)); -#46243 = CARTESIAN_POINT('',(4.71238898004,0.681818181818)); -#46244 = CARTESIAN_POINT('',(4.712388979983,0.795454545455)); -#46245 = CARTESIAN_POINT('',(4.712388979925,0.909090909091)); -#46246 = CARTESIAN_POINT('',(4.712388979868,1.022727272727)); -#46247 = CARTESIAN_POINT('',(4.71238897981,1.136363636364)); -#46248 = CARTESIAN_POINT('',(4.712388979753,1.25)); -#46249 = CARTESIAN_POINT('',(4.712388979695,1.363636363636)); -#46250 = CARTESIAN_POINT('',(4.712388979638,1.477272727273)); -#46251 = CARTESIAN_POINT('',(4.71238897958,1.590909090909)); -#46252 = CARTESIAN_POINT('',(4.712388979523,1.704545454545)); -#46253 = CARTESIAN_POINT('',(4.712388979465,1.818181818182)); -#46254 = CARTESIAN_POINT('',(4.712388979408,1.931818181818)); -#46255 = CARTESIAN_POINT('',(4.712388979351,2.045454545455)); -#46256 = CARTESIAN_POINT('',(4.712388979293,2.159090909091)); -#46257 = CARTESIAN_POINT('',(4.712388979236,2.272727272727)); -#46258 = CARTESIAN_POINT('',(4.712388979178,2.386363636364)); -#46259 = CARTESIAN_POINT('',(4.71238897914,2.462121212121)); -#46260 = CARTESIAN_POINT('',(4.712388979121,2.5)); -#46261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46262 = ORIENTED_EDGE('',*,*,#43216,.F.); -#46263 = ADVANCED_FACE('',(#46264),#43923,.T.); -#46264 = FACE_BOUND('',#46265,.T.); -#46265 = EDGE_LOOP('',(#46266,#46288,#46331,#46332)); -#46266 = ORIENTED_EDGE('',*,*,#46267,.F.); -#46267 = EDGE_CURVE('',#46268,#45329,#46270,.T.); -#46268 = VERTEX_POINT('',#46269); -#46269 = CARTESIAN_POINT('',(-1.75,0.245000000253,1.35)); -#46270 = SURFACE_CURVE('',#46271,(#46276,#46282),.PCURVE_S1.); -#46271 = CIRCLE('',#46272,0.2); -#46272 = AXIS2_PLACEMENT_3D('',#46273,#46274,#46275); -#46273 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); -#46274 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46275 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46276 = PCURVE('',#43923,#46277); -#46277 = DEFINITIONAL_REPRESENTATION('',(#46278),#46281); -#46278 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46279,#46280),.UNSPECIFIED., +#48628 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#48629 = CARTESIAN_POINT('',(4.712388980366,3.787878787879E-002)); +#48630 = CARTESIAN_POINT('',(4.712388980327,0.113636363636)); +#48631 = CARTESIAN_POINT('',(4.71238898027,0.227272727273)); +#48632 = CARTESIAN_POINT('',(4.712388980212,0.340909090909)); +#48633 = CARTESIAN_POINT('',(4.712388980155,0.454545454545)); +#48634 = CARTESIAN_POINT('',(4.712388980097,0.568181818182)); +#48635 = CARTESIAN_POINT('',(4.71238898004,0.681818181818)); +#48636 = CARTESIAN_POINT('',(4.712388979983,0.795454545455)); +#48637 = CARTESIAN_POINT('',(4.712388979925,0.909090909091)); +#48638 = CARTESIAN_POINT('',(4.712388979868,1.022727272727)); +#48639 = CARTESIAN_POINT('',(4.71238897981,1.136363636364)); +#48640 = CARTESIAN_POINT('',(4.712388979753,1.25)); +#48641 = CARTESIAN_POINT('',(4.712388979695,1.363636363636)); +#48642 = CARTESIAN_POINT('',(4.712388979638,1.477272727273)); +#48643 = CARTESIAN_POINT('',(4.71238897958,1.590909090909)); +#48644 = CARTESIAN_POINT('',(4.712388979523,1.704545454545)); +#48645 = CARTESIAN_POINT('',(4.712388979465,1.818181818182)); +#48646 = CARTESIAN_POINT('',(4.712388979408,1.931818181818)); +#48647 = CARTESIAN_POINT('',(4.712388979351,2.045454545455)); +#48648 = CARTESIAN_POINT('',(4.712388979293,2.159090909091)); +#48649 = CARTESIAN_POINT('',(4.712388979236,2.272727272727)); +#48650 = CARTESIAN_POINT('',(4.712388979178,2.386363636364)); +#48651 = CARTESIAN_POINT('',(4.71238897914,2.462121212121)); +#48652 = CARTESIAN_POINT('',(4.712388979121,2.5)); +#48653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48654 = ORIENTED_EDGE('',*,*,#45608,.F.); +#48655 = ADVANCED_FACE('',(#48656),#46315,.T.); +#48656 = FACE_BOUND('',#48657,.T.); +#48657 = EDGE_LOOP('',(#48658,#48680,#48723,#48724)); +#48658 = ORIENTED_EDGE('',*,*,#48659,.F.); +#48659 = EDGE_CURVE('',#48660,#47721,#48662,.T.); +#48660 = VERTEX_POINT('',#48661); +#48661 = CARTESIAN_POINT('',(-1.75,0.245000000253,1.35)); +#48662 = SURFACE_CURVE('',#48663,(#48668,#48674),.PCURVE_S1.); +#48663 = CIRCLE('',#48664,0.2); +#48664 = AXIS2_PLACEMENT_3D('',#48665,#48666,#48667); +#48665 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); +#48666 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48667 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#48668 = PCURVE('',#46315,#48669); +#48669 = DEFINITIONAL_REPRESENTATION('',(#48670),#48673); +#48670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48671,#48672),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46279 = CARTESIAN_POINT('',(3.14159265359,2.5)); -#46280 = CARTESIAN_POINT('',(4.712388980385,2.5)); -#46281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#48671 = CARTESIAN_POINT('',(3.14159265359,2.5)); +#48672 = CARTESIAN_POINT('',(4.712388980385,2.5)); +#48673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#46282 = PCURVE('',#45344,#46283); -#46283 = DEFINITIONAL_REPRESENTATION('',(#46284),#46287); -#46284 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46285,#46286),.UNSPECIFIED., +#48674 = PCURVE('',#47736,#48675); +#48675 = DEFINITIONAL_REPRESENTATION('',(#48676),#48679); +#48676 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48677,#48678),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46285 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#46286 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#46287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46288 = ORIENTED_EDGE('',*,*,#46289,.F.); -#46289 = EDGE_CURVE('',#43879,#46268,#46290,.T.); -#46290 = SURFACE_CURVE('',#46291,(#46295,#46324),.PCURVE_S1.); -#46291 = LINE('',#46292,#46293); -#46292 = CARTESIAN_POINT('',(-1.75,0.245,-1.15)); -#46293 = VECTOR('',#46294,1.); -#46294 = DIRECTION('',(0.E+000,1.011124406425E-010,1.)); -#46295 = PCURVE('',#43923,#46296); -#46296 = DEFINITIONAL_REPRESENTATION('',(#46297),#46323); -#46297 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46298,#46299,#46300,#46301, - #46302,#46303,#46304,#46305,#46306,#46307,#46308,#46309,#46310, - #46311,#46312,#46313,#46314,#46315,#46316,#46317,#46318,#46319, - #46320,#46321,#46322),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48677 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#48678 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#48679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48680 = ORIENTED_EDGE('',*,*,#48681,.F.); +#48681 = EDGE_CURVE('',#46271,#48660,#48682,.T.); +#48682 = SURFACE_CURVE('',#48683,(#48687,#48716),.PCURVE_S1.); +#48683 = LINE('',#48684,#48685); +#48684 = CARTESIAN_POINT('',(-1.75,0.245,-1.15)); +#48685 = VECTOR('',#48686,1.); +#48686 = DIRECTION('',(0.E+000,1.011124406425E-010,1.)); +#48687 = PCURVE('',#46315,#48688); +#48688 = DEFINITIONAL_REPRESENTATION('',(#48689),#48715); +#48689 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48690,#48691,#48692,#48693, + #48694,#48695,#48696,#48697,#48698,#48699,#48700,#48701,#48702, + #48703,#48704,#48705,#48706,#48707,#48708,#48709,#48710,#48711, + #48712,#48713,#48714),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46298 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#46299 = CARTESIAN_POINT('',(3.141592653571,3.787878787879E-002)); -#46300 = CARTESIAN_POINT('',(3.141592653532,0.113636363636)); -#46301 = CARTESIAN_POINT('',(3.141592653475,0.227272727273)); -#46302 = CARTESIAN_POINT('',(3.141592653417,0.340909090909)); -#46303 = CARTESIAN_POINT('',(3.14159265336,0.454545454545)); -#46304 = CARTESIAN_POINT('',(3.141592653303,0.568181818182)); -#46305 = CARTESIAN_POINT('',(3.141592653245,0.681818181818)); -#46306 = CARTESIAN_POINT('',(3.141592653188,0.795454545455)); -#46307 = CARTESIAN_POINT('',(3.14159265313,0.909090909091)); -#46308 = CARTESIAN_POINT('',(3.141592653073,1.022727272727)); -#46309 = CARTESIAN_POINT('',(3.141592653015,1.136363636364)); -#46310 = CARTESIAN_POINT('',(3.141592652958,1.25)); -#46311 = CARTESIAN_POINT('',(3.1415926529,1.363636363636)); -#46312 = CARTESIAN_POINT('',(3.141592652843,1.477272727273)); -#46313 = CARTESIAN_POINT('',(3.141592652785,1.590909090909)); -#46314 = CARTESIAN_POINT('',(3.141592652728,1.704545454545)); -#46315 = CARTESIAN_POINT('',(3.141592652671,1.818181818182)); -#46316 = CARTESIAN_POINT('',(3.141592652613,1.931818181818)); -#46317 = CARTESIAN_POINT('',(3.141592652556,2.045454545455)); -#46318 = CARTESIAN_POINT('',(3.141592652498,2.159090909091)); -#46319 = CARTESIAN_POINT('',(3.141592652441,2.272727272727)); -#46320 = CARTESIAN_POINT('',(3.141592652383,2.386363636364)); -#46321 = CARTESIAN_POINT('',(3.141592652345,2.462121212121)); -#46322 = CARTESIAN_POINT('',(3.141592652326,2.5)); -#46323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46324 = PCURVE('',#43894,#46325); -#46325 = DEFINITIONAL_REPRESENTATION('',(#46326),#46330); -#46326 = LINE('',#46327,#46328); -#46327 = CARTESIAN_POINT('',(0.2,0.E+000)); -#46328 = VECTOR('',#46329,1.); -#46329 = DIRECTION('',(-1.011124406425E-010,1.)); -#46330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46331 = ORIENTED_EDGE('',*,*,#43906,.T.); -#46332 = ORIENTED_EDGE('',*,*,#46003,.T.); -#46333 = ADVANCED_FACE('',(#46334),#45344,.T.); -#46334 = FACE_BOUND('',#46335,.T.); -#46335 = EDGE_LOOP('',(#46336,#46337,#46338)); -#46336 = ORIENTED_EDGE('',*,*,#46267,.T.); -#46337 = ORIENTED_EDGE('',*,*,#45328,.F.); -#46338 = ORIENTED_EDGE('',*,*,#46339,.T.); -#46339 = EDGE_CURVE('',#45145,#46268,#46340,.T.); -#46340 = SURFACE_CURVE('',#46341,(#46346,#46375),.PCURVE_S1.); -#46341 = CIRCLE('',#46342,0.2); -#46342 = AXIS2_PLACEMENT_3D('',#46343,#46344,#46345); -#46343 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); -#46344 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#46345 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46346 = PCURVE('',#45344,#46347); -#46347 = DEFINITIONAL_REPRESENTATION('',(#46348),#46374); -#46348 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46349,#46350,#46351,#46352, - #46353,#46354,#46355,#46356,#46357,#46358,#46359,#46360,#46361, - #46362,#46363,#46364,#46365,#46366,#46367,#46368,#46369,#46370, - #46371,#46372,#46373),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48690 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#48691 = CARTESIAN_POINT('',(3.141592653571,3.787878787879E-002)); +#48692 = CARTESIAN_POINT('',(3.141592653532,0.113636363636)); +#48693 = CARTESIAN_POINT('',(3.141592653475,0.227272727273)); +#48694 = CARTESIAN_POINT('',(3.141592653417,0.340909090909)); +#48695 = CARTESIAN_POINT('',(3.14159265336,0.454545454545)); +#48696 = CARTESIAN_POINT('',(3.141592653303,0.568181818182)); +#48697 = CARTESIAN_POINT('',(3.141592653245,0.681818181818)); +#48698 = CARTESIAN_POINT('',(3.141592653188,0.795454545455)); +#48699 = CARTESIAN_POINT('',(3.14159265313,0.909090909091)); +#48700 = CARTESIAN_POINT('',(3.141592653073,1.022727272727)); +#48701 = CARTESIAN_POINT('',(3.141592653015,1.136363636364)); +#48702 = CARTESIAN_POINT('',(3.141592652958,1.25)); +#48703 = CARTESIAN_POINT('',(3.1415926529,1.363636363636)); +#48704 = CARTESIAN_POINT('',(3.141592652843,1.477272727273)); +#48705 = CARTESIAN_POINT('',(3.141592652785,1.590909090909)); +#48706 = CARTESIAN_POINT('',(3.141592652728,1.704545454545)); +#48707 = CARTESIAN_POINT('',(3.141592652671,1.818181818182)); +#48708 = CARTESIAN_POINT('',(3.141592652613,1.931818181818)); +#48709 = CARTESIAN_POINT('',(3.141592652556,2.045454545455)); +#48710 = CARTESIAN_POINT('',(3.141592652498,2.159090909091)); +#48711 = CARTESIAN_POINT('',(3.141592652441,2.272727272727)); +#48712 = CARTESIAN_POINT('',(3.141592652383,2.386363636364)); +#48713 = CARTESIAN_POINT('',(3.141592652345,2.462121212121)); +#48714 = CARTESIAN_POINT('',(3.141592652326,2.5)); +#48715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48716 = PCURVE('',#46286,#48717); +#48717 = DEFINITIONAL_REPRESENTATION('',(#48718),#48722); +#48718 = LINE('',#48719,#48720); +#48719 = CARTESIAN_POINT('',(0.2,0.E+000)); +#48720 = VECTOR('',#48721,1.); +#48721 = DIRECTION('',(-1.011124406425E-010,1.)); +#48722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48723 = ORIENTED_EDGE('',*,*,#46298,.T.); +#48724 = ORIENTED_EDGE('',*,*,#48395,.T.); +#48725 = ADVANCED_FACE('',(#48726),#47736,.T.); +#48726 = FACE_BOUND('',#48727,.T.); +#48727 = EDGE_LOOP('',(#48728,#48729,#48730)); +#48728 = ORIENTED_EDGE('',*,*,#48659,.T.); +#48729 = ORIENTED_EDGE('',*,*,#47720,.F.); +#48730 = ORIENTED_EDGE('',*,*,#48731,.T.); +#48731 = EDGE_CURVE('',#47537,#48660,#48732,.T.); +#48732 = SURFACE_CURVE('',#48733,(#48738,#48767),.PCURVE_S1.); +#48733 = CIRCLE('',#48734,0.2); +#48734 = AXIS2_PLACEMENT_3D('',#48735,#48736,#48737); +#48735 = CARTESIAN_POINT('',(-1.55,0.245,1.35)); +#48736 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#48737 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48738 = PCURVE('',#47736,#48739); +#48739 = DEFINITIONAL_REPRESENTATION('',(#48740),#48766); +#48740 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48741,#48742,#48743,#48744, + #48745,#48746,#48747,#48748,#48749,#48750,#48751,#48752,#48753, + #48754,#48755,#48756,#48757,#48758,#48759,#48760,#48761,#48762, + #48763,#48764,#48765),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -57838,77 +60827,77 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#46349 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46350 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); -#46351 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); -#46352 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); -#46353 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); -#46354 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); -#46355 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); -#46356 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); -#46357 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); -#46358 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); -#46359 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); -#46360 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); -#46361 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); -#46362 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); -#46363 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); -#46364 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); -#46365 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); -#46366 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); -#46367 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); -#46368 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); -#46369 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); -#46370 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); -#46371 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); -#46372 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); -#46373 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#46374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46375 = PCURVE('',#45187,#46376); -#46376 = DEFINITIONAL_REPRESENTATION('',(#46377),#46380); -#46377 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46378,#46379),.UNSPECIFIED., +#48741 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#48742 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); +#48743 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); +#48744 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); +#48745 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); +#48746 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); +#48747 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); +#48748 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); +#48749 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); +#48750 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); +#48751 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); +#48752 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); +#48753 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); +#48754 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); +#48755 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); +#48756 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); +#48757 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); +#48758 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); +#48759 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); +#48760 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); +#48761 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); +#48762 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); +#48763 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); +#48764 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); +#48765 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#48766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48767 = PCURVE('',#47579,#48768); +#48768 = DEFINITIONAL_REPRESENTATION('',(#48769),#48772); +#48769 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48770,#48771),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46378 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); -#46379 = CARTESIAN_POINT('',(1.570796326795,0.215514631548)); -#46380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46381 = ADVANCED_FACE('',(#46382),#45187,.T.); -#46382 = FACE_BOUND('',#46383,.T.); -#46383 = EDGE_LOOP('',(#46384,#46385,#46435,#46455)); -#46384 = ORIENTED_EDGE('',*,*,#45171,.F.); -#46385 = ORIENTED_EDGE('',*,*,#46386,.T.); -#46386 = EDGE_CURVE('',#45172,#46387,#46389,.T.); -#46387 = VERTEX_POINT('',#46388); -#46388 = CARTESIAN_POINT('',(-1.75,0.445,1.35)); -#46389 = SURFACE_CURVE('',#46390,(#46395,#46401),.PCURVE_S1.); -#46390 = CIRCLE('',#46391,0.2); -#46391 = AXIS2_PLACEMENT_3D('',#46392,#46393,#46394); -#46392 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); -#46393 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#46394 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46395 = PCURVE('',#45187,#46396); -#46396 = DEFINITIONAL_REPRESENTATION('',(#46397),#46400); -#46397 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46398,#46399),.UNSPECIFIED., +#48770 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); +#48771 = CARTESIAN_POINT('',(1.570796326795,0.215514631548)); +#48772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48773 = ADVANCED_FACE('',(#48774),#47579,.T.); +#48774 = FACE_BOUND('',#48775,.T.); +#48775 = EDGE_LOOP('',(#48776,#48777,#48827,#48847)); +#48776 = ORIENTED_EDGE('',*,*,#47563,.F.); +#48777 = ORIENTED_EDGE('',*,*,#48778,.T.); +#48778 = EDGE_CURVE('',#47564,#48779,#48781,.T.); +#48779 = VERTEX_POINT('',#48780); +#48780 = CARTESIAN_POINT('',(-1.75,0.445,1.35)); +#48781 = SURFACE_CURVE('',#48782,(#48787,#48793),.PCURVE_S1.); +#48782 = CIRCLE('',#48783,0.2); +#48783 = AXIS2_PLACEMENT_3D('',#48784,#48785,#48786); +#48784 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); +#48785 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#48786 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48787 = PCURVE('',#47579,#48788); +#48788 = DEFINITIONAL_REPRESENTATION('',(#48789),#48792); +#48789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48790,#48791),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46398 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); -#46399 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); -#46400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46401 = PCURVE('',#46402,#46407); -#46402 = SPHERICAL_SURFACE('',#46403,0.2); -#46403 = AXIS2_PLACEMENT_3D('',#46404,#46405,#46406); -#46404 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); -#46405 = DIRECTION('',(0.707108620085,0.707104942284,0.E+000)); -#46406 = DIRECTION('',(-0.707104942284,0.707108620085,0.E+000)); -#46407 = DEFINITIONAL_REPRESENTATION('',(#46408),#46434); -#46408 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46409,#46410,#46411,#46412, - #46413,#46414,#46415,#46416,#46417,#46418,#46419,#46420,#46421, - #46422,#46423,#46424,#46425,#46426,#46427,#46428,#46429,#46430, - #46431,#46432,#46433),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48790 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); +#48791 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); +#48792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48793 = PCURVE('',#48794,#48799); +#48794 = SPHERICAL_SURFACE('',#48795,0.2); +#48795 = AXIS2_PLACEMENT_3D('',#48796,#48797,#48798); +#48796 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); +#48797 = DIRECTION('',(0.707108620085,0.707104942284,0.E+000)); +#48798 = DIRECTION('',(-0.707104942284,0.707108620085,0.E+000)); +#48799 = DEFINITIONAL_REPRESENTATION('',(#48800),#48826); +#48800 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48801,#48802,#48803,#48804, + #48805,#48806,#48807,#48808,#48809,#48810,#48811,#48812,#48813, + #48814,#48815,#48816,#48817,#48818,#48819,#48820,#48821,#48822, + #48823,#48824,#48825),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -57916,230 +60905,230 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#46409 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46410 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); -#46411 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); -#46412 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); -#46413 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); -#46414 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); -#46415 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); -#46416 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); -#46417 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); -#46418 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); -#46419 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); -#46420 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); -#46421 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); -#46422 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); -#46423 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); -#46424 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); -#46425 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); -#46426 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); -#46427 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); -#46428 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); -#46429 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); -#46430 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); -#46431 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); -#46432 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); -#46433 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#46434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46435 = ORIENTED_EDGE('',*,*,#46436,.T.); -#46436 = EDGE_CURVE('',#46387,#46268,#46437,.T.); -#46437 = SURFACE_CURVE('',#46438,(#46442,#46448),.PCURVE_S1.); -#46438 = LINE('',#46439,#46440); -#46439 = CARTESIAN_POINT('',(-1.75,0.444999999909,1.35)); -#46440 = VECTOR('',#46441,1.); -#46441 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#46442 = PCURVE('',#45187,#46443); -#46443 = DEFINITIONAL_REPRESENTATION('',(#46444),#46447); -#46444 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46445,#46446),.UNSPECIFIED., +#48801 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#48802 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); +#48803 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); +#48804 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); +#48805 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); +#48806 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); +#48807 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); +#48808 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); +#48809 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); +#48810 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); +#48811 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); +#48812 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); +#48813 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); +#48814 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); +#48815 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); +#48816 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); +#48817 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); +#48818 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); +#48819 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); +#48820 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); +#48821 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); +#48822 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); +#48823 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); +#48824 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); +#48825 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#48826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48827 = ORIENTED_EDGE('',*,*,#48828,.T.); +#48828 = EDGE_CURVE('',#48779,#48660,#48829,.T.); +#48829 = SURFACE_CURVE('',#48830,(#48834,#48840),.PCURVE_S1.); +#48830 = LINE('',#48831,#48832); +#48831 = CARTESIAN_POINT('',(-1.75,0.444999999909,1.35)); +#48832 = VECTOR('',#48833,1.); +#48833 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#48834 = PCURVE('',#47579,#48835); +#48835 = DEFINITIONAL_REPRESENTATION('',(#48836),#48839); +#48836 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48837,#48838),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.199999999747),.PIECEWISE_BEZIER_KNOTS.); -#46445 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); -#46446 = CARTESIAN_POINT('',(1.570796326795,0.215514631296)); -#46447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46448 = PCURVE('',#43894,#46449); -#46449 = DEFINITIONAL_REPRESENTATION('',(#46450),#46454); -#46450 = LINE('',#46451,#46452); -#46451 = CARTESIAN_POINT('',(9.060002748029E-011,2.5)); -#46452 = VECTOR('',#46453,1.); -#46453 = DIRECTION('',(1.,0.E+000)); -#46454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46455 = ORIENTED_EDGE('',*,*,#46339,.F.); -#46456 = ADVANCED_FACE('',(#46457),#43894,.T.); -#46457 = FACE_BOUND('',#46458,.F.); -#46458 = EDGE_LOOP('',(#46459,#46460,#46461,#46462)); -#46459 = ORIENTED_EDGE('',*,*,#46436,.T.); -#46460 = ORIENTED_EDGE('',*,*,#46289,.F.); -#46461 = ORIENTED_EDGE('',*,*,#43878,.F.); -#46462 = ORIENTED_EDGE('',*,*,#46463,.T.); -#46463 = EDGE_CURVE('',#43851,#46387,#46464,.T.); -#46464 = SURFACE_CURVE('',#46465,(#46469,#46476),.PCURVE_S1.); -#46465 = LINE('',#46466,#46467); -#46466 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); -#46467 = VECTOR('',#46468,1.); -#46468 = DIRECTION('',(0.E+000,-3.62547991628E-011,1.)); -#46469 = PCURVE('',#43894,#46470); -#46470 = DEFINITIONAL_REPRESENTATION('',(#46471),#46475); -#46471 = LINE('',#46472,#46473); -#46472 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#46473 = VECTOR('',#46474,1.); -#46474 = DIRECTION('',(3.62547991628E-011,1.)); -#46475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46476 = PCURVE('',#43867,#46477); -#46477 = DEFINITIONAL_REPRESENTATION('',(#46478),#46504); -#46478 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46479,#46480,#46481,#46482, - #46483,#46484,#46485,#46486,#46487,#46488,#46489,#46490,#46491, - #46492,#46493,#46494,#46495,#46496,#46497,#46498,#46499,#46500, - #46501,#46502,#46503),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48837 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); +#48838 = CARTESIAN_POINT('',(1.570796326795,0.215514631296)); +#48839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48840 = PCURVE('',#46286,#48841); +#48841 = DEFINITIONAL_REPRESENTATION('',(#48842),#48846); +#48842 = LINE('',#48843,#48844); +#48843 = CARTESIAN_POINT('',(9.060002748029E-011,2.5)); +#48844 = VECTOR('',#48845,1.); +#48845 = DIRECTION('',(1.,0.E+000)); +#48846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48847 = ORIENTED_EDGE('',*,*,#48731,.F.); +#48848 = ADVANCED_FACE('',(#48849),#46286,.T.); +#48849 = FACE_BOUND('',#48850,.F.); +#48850 = EDGE_LOOP('',(#48851,#48852,#48853,#48854)); +#48851 = ORIENTED_EDGE('',*,*,#48828,.T.); +#48852 = ORIENTED_EDGE('',*,*,#48681,.F.); +#48853 = ORIENTED_EDGE('',*,*,#46270,.F.); +#48854 = ORIENTED_EDGE('',*,*,#48855,.T.); +#48855 = EDGE_CURVE('',#46243,#48779,#48856,.T.); +#48856 = SURFACE_CURVE('',#48857,(#48861,#48868),.PCURVE_S1.); +#48857 = LINE('',#48858,#48859); +#48858 = CARTESIAN_POINT('',(-1.75,0.445,-1.15)); +#48859 = VECTOR('',#48860,1.); +#48860 = DIRECTION('',(0.E+000,-3.62547991628E-011,1.)); +#48861 = PCURVE('',#46286,#48862); +#48862 = DEFINITIONAL_REPRESENTATION('',(#48863),#48867); +#48863 = LINE('',#48864,#48865); +#48864 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#48865 = VECTOR('',#48866,1.); +#48866 = DIRECTION('',(3.62547991628E-011,1.)); +#48867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48868 = PCURVE('',#46259,#48869); +#48869 = DEFINITIONAL_REPRESENTATION('',(#48870),#48896); +#48870 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48871,#48872,#48873,#48874, + #48875,#48876,#48877,#48878,#48879,#48880,#48881,#48882,#48883, + #48884,#48885,#48886,#48887,#48888,#48889,#48890,#48891,#48892, + #48893,#48894,#48895),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46479 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#46480 = CARTESIAN_POINT('',(3.141592653597,3.787878787879E-002)); -#46481 = CARTESIAN_POINT('',(3.14159265361,0.113636363636)); -#46482 = CARTESIAN_POINT('',(3.141592653631,0.227272727273)); -#46483 = CARTESIAN_POINT('',(3.141592653652,0.340909090909)); -#46484 = CARTESIAN_POINT('',(3.141592653672,0.454545454545)); -#46485 = CARTESIAN_POINT('',(3.141592653693,0.568181818182)); -#46486 = CARTESIAN_POINT('',(3.141592653713,0.681818181818)); -#46487 = CARTESIAN_POINT('',(3.141592653734,0.795454545455)); -#46488 = CARTESIAN_POINT('',(3.141592653755,0.909090909091)); -#46489 = CARTESIAN_POINT('',(3.141592653775,1.022727272727)); -#46490 = CARTESIAN_POINT('',(3.141592653796,1.136363636364)); -#46491 = CARTESIAN_POINT('',(3.141592653816,1.25)); -#46492 = CARTESIAN_POINT('',(3.141592653837,1.363636363636)); -#46493 = CARTESIAN_POINT('',(3.141592653858,1.477272727273)); -#46494 = CARTESIAN_POINT('',(3.141592653878,1.590909090909)); -#46495 = CARTESIAN_POINT('',(3.141592653899,1.704545454545)); -#46496 = CARTESIAN_POINT('',(3.141592653919,1.818181818182)); -#46497 = CARTESIAN_POINT('',(3.14159265394,1.931818181818)); -#46498 = CARTESIAN_POINT('',(3.141592653961,2.045454545455)); -#46499 = CARTESIAN_POINT('',(3.141592653981,2.159090909091)); -#46500 = CARTESIAN_POINT('',(3.141592654002,2.272727272727)); -#46501 = CARTESIAN_POINT('',(3.141592654022,2.386363636364)); -#46502 = CARTESIAN_POINT('',(3.141592654036,2.462121212121)); -#46503 = CARTESIAN_POINT('',(3.141592654043,2.5)); -#46504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46505 = ADVANCED_FACE('',(#46506),#43867,.T.); -#46506 = FACE_BOUND('',#46507,.T.); -#46507 = EDGE_LOOP('',(#46508,#46530,#46573,#46574)); -#46508 = ORIENTED_EDGE('',*,*,#46509,.F.); -#46509 = EDGE_CURVE('',#46510,#46387,#46512,.T.); -#46510 = VERTEX_POINT('',#46511); -#46511 = CARTESIAN_POINT('',(-1.549999999747,0.645,1.35)); -#46512 = SURFACE_CURVE('',#46513,(#46518,#46524),.PCURVE_S1.); -#46513 = CIRCLE('',#46514,0.2); -#46514 = AXIS2_PLACEMENT_3D('',#46515,#46516,#46517); -#46515 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); -#46516 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46517 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46518 = PCURVE('',#43867,#46519); -#46519 = DEFINITIONAL_REPRESENTATION('',(#46520),#46523); -#46520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46521,#46522),.UNSPECIFIED., +#48871 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#48872 = CARTESIAN_POINT('',(3.141592653597,3.787878787879E-002)); +#48873 = CARTESIAN_POINT('',(3.14159265361,0.113636363636)); +#48874 = CARTESIAN_POINT('',(3.141592653631,0.227272727273)); +#48875 = CARTESIAN_POINT('',(3.141592653652,0.340909090909)); +#48876 = CARTESIAN_POINT('',(3.141592653672,0.454545454545)); +#48877 = CARTESIAN_POINT('',(3.141592653693,0.568181818182)); +#48878 = CARTESIAN_POINT('',(3.141592653713,0.681818181818)); +#48879 = CARTESIAN_POINT('',(3.141592653734,0.795454545455)); +#48880 = CARTESIAN_POINT('',(3.141592653755,0.909090909091)); +#48881 = CARTESIAN_POINT('',(3.141592653775,1.022727272727)); +#48882 = CARTESIAN_POINT('',(3.141592653796,1.136363636364)); +#48883 = CARTESIAN_POINT('',(3.141592653816,1.25)); +#48884 = CARTESIAN_POINT('',(3.141592653837,1.363636363636)); +#48885 = CARTESIAN_POINT('',(3.141592653858,1.477272727273)); +#48886 = CARTESIAN_POINT('',(3.141592653878,1.590909090909)); +#48887 = CARTESIAN_POINT('',(3.141592653899,1.704545454545)); +#48888 = CARTESIAN_POINT('',(3.141592653919,1.818181818182)); +#48889 = CARTESIAN_POINT('',(3.14159265394,1.931818181818)); +#48890 = CARTESIAN_POINT('',(3.141592653961,2.045454545455)); +#48891 = CARTESIAN_POINT('',(3.141592653981,2.159090909091)); +#48892 = CARTESIAN_POINT('',(3.141592654002,2.272727272727)); +#48893 = CARTESIAN_POINT('',(3.141592654022,2.386363636364)); +#48894 = CARTESIAN_POINT('',(3.141592654036,2.462121212121)); +#48895 = CARTESIAN_POINT('',(3.141592654043,2.5)); +#48896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48897 = ADVANCED_FACE('',(#48898),#46259,.T.); +#48898 = FACE_BOUND('',#48899,.T.); +#48899 = EDGE_LOOP('',(#48900,#48922,#48965,#48966)); +#48900 = ORIENTED_EDGE('',*,*,#48901,.F.); +#48901 = EDGE_CURVE('',#48902,#48779,#48904,.T.); +#48902 = VERTEX_POINT('',#48903); +#48903 = CARTESIAN_POINT('',(-1.549999999747,0.645,1.35)); +#48904 = SURFACE_CURVE('',#48905,(#48910,#48916),.PCURVE_S1.); +#48905 = CIRCLE('',#48906,0.2); +#48906 = AXIS2_PLACEMENT_3D('',#48907,#48908,#48909); +#48907 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); +#48908 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48909 = DIRECTION('',(0.E+000,1.,0.E+000)); +#48910 = PCURVE('',#46259,#48911); +#48911 = DEFINITIONAL_REPRESENTATION('',(#48912),#48915); +#48912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48913,#48914),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46521 = CARTESIAN_POINT('',(1.570796326795,2.5)); -#46522 = CARTESIAN_POINT('',(3.14159265359,2.5)); -#46523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#48913 = CARTESIAN_POINT('',(1.570796326795,2.5)); +#48914 = CARTESIAN_POINT('',(3.14159265359,2.5)); +#48915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#46524 = PCURVE('',#46402,#46525); -#46525 = DEFINITIONAL_REPRESENTATION('',(#46526),#46529); -#46526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46527,#46528),.UNSPECIFIED., +#48916 = PCURVE('',#48794,#48917); +#48917 = DEFINITIONAL_REPRESENTATION('',(#48918),#48921); +#48918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48919,#48920),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46527 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#46528 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#46529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46530 = ORIENTED_EDGE('',*,*,#46531,.F.); -#46531 = EDGE_CURVE('',#43828,#46510,#46532,.T.); -#46532 = SURFACE_CURVE('',#46533,(#46537,#46566),.PCURVE_S1.); -#46533 = LINE('',#46534,#46535); -#46534 = CARTESIAN_POINT('',(-1.55,0.645,-1.15)); -#46535 = VECTOR('',#46536,1.); -#46536 = DIRECTION('',(1.011119188377E-010,0.E+000,1.)); -#46537 = PCURVE('',#43867,#46538); -#46538 = DEFINITIONAL_REPRESENTATION('',(#46539),#46565); -#46539 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46540,#46541,#46542,#46543, - #46544,#46545,#46546,#46547,#46548,#46549,#46550,#46551,#46552, - #46553,#46554,#46555,#46556,#46557,#46558,#46559,#46560,#46561, - #46562,#46563,#46564),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48919 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#48920 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#48921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48922 = ORIENTED_EDGE('',*,*,#48923,.F.); +#48923 = EDGE_CURVE('',#46220,#48902,#48924,.T.); +#48924 = SURFACE_CURVE('',#48925,(#48929,#48958),.PCURVE_S1.); +#48925 = LINE('',#48926,#48927); +#48926 = CARTESIAN_POINT('',(-1.55,0.645,-1.15)); +#48927 = VECTOR('',#48928,1.); +#48928 = DIRECTION('',(1.011119188377E-010,0.E+000,1.)); +#48929 = PCURVE('',#46259,#48930); +#48930 = DEFINITIONAL_REPRESENTATION('',(#48931),#48957); +#48931 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48932,#48933,#48934,#48935, + #48936,#48937,#48938,#48939,#48940,#48941,#48942,#48943,#48944, + #48945,#48946,#48947,#48948,#48949,#48950,#48951,#48952,#48953, + #48954,#48955,#48956),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46540 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46541 = CARTESIAN_POINT('',(1.570796326776,3.787878787879E-002)); -#46542 = CARTESIAN_POINT('',(1.570796326737,0.113636363636)); -#46543 = CARTESIAN_POINT('',(1.57079632668,0.227272727273)); -#46544 = CARTESIAN_POINT('',(1.570796326623,0.340909090909)); -#46545 = CARTESIAN_POINT('',(1.570796326565,0.454545454545)); -#46546 = CARTESIAN_POINT('',(1.570796326508,0.568181818182)); -#46547 = CARTESIAN_POINT('',(1.57079632645,0.681818181818)); -#46548 = CARTESIAN_POINT('',(1.570796326393,0.795454545455)); -#46549 = CARTESIAN_POINT('',(1.570796326335,0.909090909091)); -#46550 = CARTESIAN_POINT('',(1.570796326278,1.022727272727)); -#46551 = CARTESIAN_POINT('',(1.57079632622,1.136363636364)); -#46552 = CARTESIAN_POINT('',(1.570796326163,1.25)); -#46553 = CARTESIAN_POINT('',(1.570796326105,1.363636363636)); -#46554 = CARTESIAN_POINT('',(1.570796326048,1.477272727273)); -#46555 = CARTESIAN_POINT('',(1.570796325991,1.590909090909)); -#46556 = CARTESIAN_POINT('',(1.570796325933,1.704545454545)); -#46557 = CARTESIAN_POINT('',(1.570796325876,1.818181818182)); -#46558 = CARTESIAN_POINT('',(1.570796325818,1.931818181818)); -#46559 = CARTESIAN_POINT('',(1.570796325761,2.045454545455)); -#46560 = CARTESIAN_POINT('',(1.570796325703,2.159090909091)); -#46561 = CARTESIAN_POINT('',(1.570796325646,2.272727272727)); -#46562 = CARTESIAN_POINT('',(1.570796325588,2.386363636364)); -#46563 = CARTESIAN_POINT('',(1.57079632555,2.462121212121)); -#46564 = CARTESIAN_POINT('',(1.570796325531,2.5)); -#46565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46566 = PCURVE('',#43344,#46567); -#46567 = DEFINITIONAL_REPRESENTATION('',(#46568),#46572); -#46568 = LINE('',#46569,#46570); -#46569 = CARTESIAN_POINT('',(3.1,0.E+000)); -#46570 = VECTOR('',#46571,1.); -#46571 = DIRECTION('',(-1.011119188377E-010,1.)); -#46572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46573 = ORIENTED_EDGE('',*,*,#43850,.T.); -#46574 = ORIENTED_EDGE('',*,*,#46463,.T.); -#46575 = ADVANCED_FACE('',(#46576),#46402,.T.); -#46576 = FACE_BOUND('',#46577,.T.); -#46577 = EDGE_LOOP('',(#46578,#46579,#46580)); -#46578 = ORIENTED_EDGE('',*,*,#46509,.T.); -#46579 = ORIENTED_EDGE('',*,*,#46386,.F.); -#46580 = ORIENTED_EDGE('',*,*,#46581,.T.); -#46581 = EDGE_CURVE('',#45172,#46510,#46582,.T.); -#46582 = SURFACE_CURVE('',#46583,(#46588,#46617),.PCURVE_S1.); -#46583 = CIRCLE('',#46584,0.2); -#46584 = AXIS2_PLACEMENT_3D('',#46585,#46586,#46587); -#46585 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); -#46586 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46587 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46588 = PCURVE('',#46402,#46589); -#46589 = DEFINITIONAL_REPRESENTATION('',(#46590),#46616); -#46590 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46591,#46592,#46593,#46594, - #46595,#46596,#46597,#46598,#46599,#46600,#46601,#46602,#46603, - #46604,#46605,#46606,#46607,#46608,#46609,#46610,#46611,#46612, - #46613,#46614,#46615),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#48932 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#48933 = CARTESIAN_POINT('',(1.570796326776,3.787878787879E-002)); +#48934 = CARTESIAN_POINT('',(1.570796326737,0.113636363636)); +#48935 = CARTESIAN_POINT('',(1.57079632668,0.227272727273)); +#48936 = CARTESIAN_POINT('',(1.570796326623,0.340909090909)); +#48937 = CARTESIAN_POINT('',(1.570796326565,0.454545454545)); +#48938 = CARTESIAN_POINT('',(1.570796326508,0.568181818182)); +#48939 = CARTESIAN_POINT('',(1.57079632645,0.681818181818)); +#48940 = CARTESIAN_POINT('',(1.570796326393,0.795454545455)); +#48941 = CARTESIAN_POINT('',(1.570796326335,0.909090909091)); +#48942 = CARTESIAN_POINT('',(1.570796326278,1.022727272727)); +#48943 = CARTESIAN_POINT('',(1.57079632622,1.136363636364)); +#48944 = CARTESIAN_POINT('',(1.570796326163,1.25)); +#48945 = CARTESIAN_POINT('',(1.570796326105,1.363636363636)); +#48946 = CARTESIAN_POINT('',(1.570796326048,1.477272727273)); +#48947 = CARTESIAN_POINT('',(1.570796325991,1.590909090909)); +#48948 = CARTESIAN_POINT('',(1.570796325933,1.704545454545)); +#48949 = CARTESIAN_POINT('',(1.570796325876,1.818181818182)); +#48950 = CARTESIAN_POINT('',(1.570796325818,1.931818181818)); +#48951 = CARTESIAN_POINT('',(1.570796325761,2.045454545455)); +#48952 = CARTESIAN_POINT('',(1.570796325703,2.159090909091)); +#48953 = CARTESIAN_POINT('',(1.570796325646,2.272727272727)); +#48954 = CARTESIAN_POINT('',(1.570796325588,2.386363636364)); +#48955 = CARTESIAN_POINT('',(1.57079632555,2.462121212121)); +#48956 = CARTESIAN_POINT('',(1.570796325531,2.5)); +#48957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48958 = PCURVE('',#45736,#48959); +#48959 = DEFINITIONAL_REPRESENTATION('',(#48960),#48964); +#48960 = LINE('',#48961,#48962); +#48961 = CARTESIAN_POINT('',(3.1,0.E+000)); +#48962 = VECTOR('',#48963,1.); +#48963 = DIRECTION('',(-1.011119188377E-010,1.)); +#48964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#48965 = ORIENTED_EDGE('',*,*,#46242,.T.); +#48966 = ORIENTED_EDGE('',*,*,#48855,.T.); +#48967 = ADVANCED_FACE('',(#48968),#48794,.T.); +#48968 = FACE_BOUND('',#48969,.T.); +#48969 = EDGE_LOOP('',(#48970,#48971,#48972)); +#48970 = ORIENTED_EDGE('',*,*,#48901,.T.); +#48971 = ORIENTED_EDGE('',*,*,#48778,.F.); +#48972 = ORIENTED_EDGE('',*,*,#48973,.T.); +#48973 = EDGE_CURVE('',#47564,#48902,#48974,.T.); +#48974 = SURFACE_CURVE('',#48975,(#48980,#49009),.PCURVE_S1.); +#48975 = CIRCLE('',#48976,0.2); +#48976 = AXIS2_PLACEMENT_3D('',#48977,#48978,#48979); +#48977 = CARTESIAN_POINT('',(-1.55,0.445,1.35)); +#48978 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#48979 = DIRECTION('',(0.E+000,0.E+000,1.)); +#48980 = PCURVE('',#48794,#48981); +#48981 = DEFINITIONAL_REPRESENTATION('',(#48982),#49008); +#48982 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48983,#48984,#48985,#48986, + #48987,#48988,#48989,#48990,#48991,#48992,#48993,#48994,#48995, + #48996,#48997,#48998,#48999,#49000,#49001,#49002,#49003,#49004, + #49005,#49006,#49007),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -58147,77 +61136,77 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#46591 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46592 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); -#46593 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); -#46594 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); -#46595 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); -#46596 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); -#46597 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); -#46598 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); -#46599 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); -#46600 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); -#46601 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); -#46602 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); -#46603 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); -#46604 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); -#46605 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); -#46606 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); -#46607 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); -#46608 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); -#46609 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); -#46610 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); -#46611 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); -#46612 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); -#46613 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); -#46614 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); -#46615 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#46616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46617 = PCURVE('',#45214,#46618); -#46618 = DEFINITIONAL_REPRESENTATION('',(#46619),#46622); -#46619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46620,#46621),.UNSPECIFIED., +#48983 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#48984 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); +#48985 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); +#48986 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); +#48987 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); +#48988 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); +#48989 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); +#48990 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); +#48991 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); +#48992 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); +#48993 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); +#48994 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); +#48995 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); +#48996 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); +#48997 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); +#48998 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); +#48999 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); +#49000 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); +#49001 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); +#49002 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); +#49003 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); +#49004 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); +#49005 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); +#49006 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); +#49007 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#49008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49009 = PCURVE('',#47606,#49010); +#49010 = DEFINITIONAL_REPRESENTATION('',(#49011),#49014); +#49011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49012,#49013),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46620 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); -#46621 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); -#46622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46623 = ADVANCED_FACE('',(#46624),#45214,.T.); -#46624 = FACE_BOUND('',#46625,.T.); -#46625 = EDGE_LOOP('',(#46626,#46627,#46677,#46697)); -#46626 = ORIENTED_EDGE('',*,*,#45198,.F.); -#46627 = ORIENTED_EDGE('',*,*,#46628,.T.); -#46628 = EDGE_CURVE('',#45199,#46629,#46631,.T.); -#46629 = VERTEX_POINT('',#46630); -#46630 = CARTESIAN_POINT('',(1.549999999909,0.645,1.35)); -#46631 = SURFACE_CURVE('',#46632,(#46637,#46643),.PCURVE_S1.); -#46632 = CIRCLE('',#46633,0.2); -#46633 = AXIS2_PLACEMENT_3D('',#46634,#46635,#46636); -#46634 = CARTESIAN_POINT('',(1.55,0.445,1.35)); -#46635 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46636 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46637 = PCURVE('',#45214,#46638); -#46638 = DEFINITIONAL_REPRESENTATION('',(#46639),#46642); -#46639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46640,#46641),.UNSPECIFIED., +#49012 = CARTESIAN_POINT('',(0.E+000,3.115514631548)); +#49013 = CARTESIAN_POINT('',(1.570796326795,3.115514631548)); +#49014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49015 = ADVANCED_FACE('',(#49016),#47606,.T.); +#49016 = FACE_BOUND('',#49017,.T.); +#49017 = EDGE_LOOP('',(#49018,#49019,#49069,#49089)); +#49018 = ORIENTED_EDGE('',*,*,#47590,.F.); +#49019 = ORIENTED_EDGE('',*,*,#49020,.T.); +#49020 = EDGE_CURVE('',#47591,#49021,#49023,.T.); +#49021 = VERTEX_POINT('',#49022); +#49022 = CARTESIAN_POINT('',(1.549999999909,0.645,1.35)); +#49023 = SURFACE_CURVE('',#49024,(#49029,#49035),.PCURVE_S1.); +#49024 = CIRCLE('',#49025,0.2); +#49025 = AXIS2_PLACEMENT_3D('',#49026,#49027,#49028); +#49026 = CARTESIAN_POINT('',(1.55,0.445,1.35)); +#49027 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49028 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49029 = PCURVE('',#47606,#49030); +#49030 = DEFINITIONAL_REPRESENTATION('',(#49031),#49034); +#49031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49032,#49033),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46640 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#46641 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#46642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46643 = PCURVE('',#46644,#46649); -#46644 = SPHERICAL_SURFACE('',#46645,0.2); -#46645 = AXIS2_PLACEMENT_3D('',#46646,#46647,#46648); -#46646 = CARTESIAN_POINT('',(1.55,0.445,1.35)); -#46647 = DIRECTION('',(0.707104942284,-0.707108620085,0.E+000)); -#46648 = DIRECTION('',(0.707108620085,0.707104942284,0.E+000)); -#46649 = DEFINITIONAL_REPRESENTATION('',(#46650),#46676); -#46650 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46651,#46652,#46653,#46654, - #46655,#46656,#46657,#46658,#46659,#46660,#46661,#46662,#46663, - #46664,#46665,#46666,#46667,#46668,#46669,#46670,#46671,#46672, - #46673,#46674,#46675),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#49032 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#49033 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#49034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49035 = PCURVE('',#49036,#49041); +#49036 = SPHERICAL_SURFACE('',#49037,0.2); +#49037 = AXIS2_PLACEMENT_3D('',#49038,#49039,#49040); +#49038 = CARTESIAN_POINT('',(1.55,0.445,1.35)); +#49039 = DIRECTION('',(0.707104942284,-0.707108620085,0.E+000)); +#49040 = DIRECTION('',(0.707108620085,0.707104942284,0.E+000)); +#49041 = DEFINITIONAL_REPRESENTATION('',(#49042),#49068); +#49042 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49043,#49044,#49045,#49046, + #49047,#49048,#49049,#49050,#49051,#49052,#49053,#49054,#49055, + #49056,#49057,#49058,#49059,#49060,#49061,#49062,#49063,#49064, + #49065,#49066,#49067),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -58225,2474 +61214,2474 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#46651 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46652 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); -#46653 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); -#46654 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); -#46655 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); -#46656 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); -#46657 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); -#46658 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); -#46659 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); -#46660 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); -#46661 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); -#46662 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); -#46663 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); -#46664 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); -#46665 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); -#46666 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); -#46667 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); -#46668 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); -#46669 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); -#46670 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); -#46671 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); -#46672 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); -#46673 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); -#46674 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); -#46675 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#46676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#49043 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49044 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); +#49045 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); +#49046 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); +#49047 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); +#49048 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); +#49049 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); +#49050 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); +#49051 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); +#49052 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); +#49053 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); +#49054 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); +#49055 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); +#49056 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); +#49057 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); +#49058 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); +#49059 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); +#49060 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); +#49061 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); +#49062 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); +#49063 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); +#49064 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); +#49065 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); +#49066 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); +#49067 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#49068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#46677 = ORIENTED_EDGE('',*,*,#46678,.T.); -#46678 = EDGE_CURVE('',#46629,#46510,#46679,.T.); -#46679 = SURFACE_CURVE('',#46680,(#46684,#46690),.PCURVE_S1.); -#46680 = LINE('',#46681,#46682); -#46681 = CARTESIAN_POINT('',(1.549999999909,0.645,1.35)); -#46682 = VECTOR('',#46683,1.); -#46683 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46684 = PCURVE('',#45214,#46685); -#46685 = DEFINITIONAL_REPRESENTATION('',(#46686),#46689); -#46686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46687,#46688),.UNSPECIFIED., +#49069 = ORIENTED_EDGE('',*,*,#49070,.T.); +#49070 = EDGE_CURVE('',#49021,#48902,#49071,.T.); +#49071 = SURFACE_CURVE('',#49072,(#49076,#49082),.PCURVE_S1.); +#49072 = LINE('',#49073,#49074); +#49073 = CARTESIAN_POINT('',(1.549999999909,0.645,1.35)); +#49074 = VECTOR('',#49075,1.); +#49075 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49076 = PCURVE('',#47606,#49077); +#49077 = DEFINITIONAL_REPRESENTATION('',(#49078),#49081); +#49078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49079,#49080),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.099999999656),.PIECEWISE_BEZIER_KNOTS.); -#46687 = CARTESIAN_POINT('',(1.570796326795,1.5514631639E-002)); -#46688 = CARTESIAN_POINT('',(1.570796326795,3.115514631295)); -#46689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46690 = PCURVE('',#43344,#46691); -#46691 = DEFINITIONAL_REPRESENTATION('',(#46692),#46696); -#46692 = LINE('',#46693,#46694); -#46693 = CARTESIAN_POINT('',(9.100009634722E-011,2.5)); -#46694 = VECTOR('',#46695,1.); -#46695 = DIRECTION('',(1.,0.E+000)); -#46696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46697 = ORIENTED_EDGE('',*,*,#46581,.F.); -#46698 = ADVANCED_FACE('',(#46699),#43344,.T.); -#46699 = FACE_BOUND('',#46700,.F.); -#46700 = EDGE_LOOP('',(#46701,#46702,#46703,#46704,#46727,#46755,#46783, - #46811,#46839,#46867,#46888,#46889)); -#46701 = ORIENTED_EDGE('',*,*,#46678,.T.); -#46702 = ORIENTED_EDGE('',*,*,#46531,.F.); -#46703 = ORIENTED_EDGE('',*,*,#43827,.F.); -#46704 = ORIENTED_EDGE('',*,*,#46705,.F.); -#46705 = EDGE_CURVE('',#46706,#43800,#46708,.T.); -#46706 = VERTEX_POINT('',#46707); -#46707 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); -#46708 = SURFACE_CURVE('',#46709,(#46713,#46720),.PCURVE_S1.); -#46709 = LINE('',#46710,#46711); -#46710 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); -#46711 = VECTOR('',#46712,1.); -#46712 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); -#46713 = PCURVE('',#43344,#46714); -#46714 = DEFINITIONAL_REPRESENTATION('',(#46715),#46719); -#46715 = LINE('',#46716,#46717); -#46716 = CARTESIAN_POINT('',(1.96,-0.1)); -#46717 = VECTOR('',#46718,1.); -#46718 = DIRECTION('',(0.707106781187,0.707106781187)); -#46719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46720 = PCURVE('',#43815,#46721); -#46721 = DEFINITIONAL_REPRESENTATION('',(#46722),#46726); -#46722 = LINE('',#46723,#46724); -#46723 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); -#46724 = VECTOR('',#46725,1.); -#46725 = DIRECTION('',(0.E+000,-1.)); -#46726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46727 = ORIENTED_EDGE('',*,*,#46728,.F.); -#46728 = EDGE_CURVE('',#46729,#46706,#46731,.T.); -#46729 = VERTEX_POINT('',#46730); -#46730 = CARTESIAN_POINT('',(-0.41,0.645,-1.5)); -#46731 = SURFACE_CURVE('',#46732,(#46736,#46743),.PCURVE_S1.); -#46732 = LINE('',#46733,#46734); -#46733 = CARTESIAN_POINT('',(-0.41,0.645,-1.5)); -#46734 = VECTOR('',#46735,1.); -#46735 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46736 = PCURVE('',#43344,#46737); -#46737 = DEFINITIONAL_REPRESENTATION('',(#46738),#46742); -#46738 = LINE('',#46739,#46740); -#46739 = CARTESIAN_POINT('',(1.96,-0.35)); -#46740 = VECTOR('',#46741,1.); -#46741 = DIRECTION('',(0.E+000,1.)); -#46742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46743 = PCURVE('',#46744,#46749); -#46744 = PLANE('',#46745); -#46745 = AXIS2_PLACEMENT_3D('',#46746,#46747,#46748); -#46746 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); -#46747 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46748 = DIRECTION('',(0.E+000,0.E+000,1.)); -#46749 = DEFINITIONAL_REPRESENTATION('',(#46750),#46754); -#46750 = LINE('',#46751,#46752); -#46751 = CARTESIAN_POINT('',(0.E+000,-0.58)); -#46752 = VECTOR('',#46753,1.); -#46753 = DIRECTION('',(1.,0.E+000)); -#46754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46755 = ORIENTED_EDGE('',*,*,#46756,.F.); -#46756 = EDGE_CURVE('',#46757,#46729,#46759,.T.); -#46757 = VERTEX_POINT('',#46758); -#46758 = CARTESIAN_POINT('',(-0.16,0.645,-1.75)); -#46759 = SURFACE_CURVE('',#46760,(#46765,#46772),.PCURVE_S1.); -#46760 = CIRCLE('',#46761,0.25); -#46761 = AXIS2_PLACEMENT_3D('',#46762,#46763,#46764); -#46762 = CARTESIAN_POINT('',(-0.16,0.645,-1.5)); -#46763 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46764 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#46765 = PCURVE('',#43344,#46766); -#46766 = DEFINITIONAL_REPRESENTATION('',(#46767),#46771); -#46767 = CIRCLE('',#46768,0.25); -#46768 = AXIS2_PLACEMENT_2D('',#46769,#46770); -#46769 = CARTESIAN_POINT('',(1.71,-0.35)); -#46770 = DIRECTION('',(0.E+000,-1.)); -#46771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46772 = PCURVE('',#46773,#46778); -#46773 = CYLINDRICAL_SURFACE('',#46774,0.25); -#46774 = AXIS2_PLACEMENT_3D('',#46775,#46776,#46777); -#46775 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); -#46776 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46777 = DIRECTION('',(1.,0.E+000,0.E+000)); -#46778 = DEFINITIONAL_REPRESENTATION('',(#46779),#46782); -#46779 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46780,#46781),.UNSPECIFIED., +#49079 = CARTESIAN_POINT('',(1.570796326795,1.5514631639E-002)); +#49080 = CARTESIAN_POINT('',(1.570796326795,3.115514631295)); +#49081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49082 = PCURVE('',#45736,#49083); +#49083 = DEFINITIONAL_REPRESENTATION('',(#49084),#49088); +#49084 = LINE('',#49085,#49086); +#49085 = CARTESIAN_POINT('',(9.100009634722E-011,2.5)); +#49086 = VECTOR('',#49087,1.); +#49087 = DIRECTION('',(1.,0.E+000)); +#49088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49089 = ORIENTED_EDGE('',*,*,#48973,.F.); +#49090 = ADVANCED_FACE('',(#49091),#45736,.T.); +#49091 = FACE_BOUND('',#49092,.F.); +#49092 = EDGE_LOOP('',(#49093,#49094,#49095,#49096,#49119,#49147,#49175, + #49203,#49231,#49259,#49280,#49281)); +#49093 = ORIENTED_EDGE('',*,*,#49070,.T.); +#49094 = ORIENTED_EDGE('',*,*,#48923,.F.); +#49095 = ORIENTED_EDGE('',*,*,#46219,.F.); +#49096 = ORIENTED_EDGE('',*,*,#49097,.F.); +#49097 = EDGE_CURVE('',#49098,#46192,#49100,.T.); +#49098 = VERTEX_POINT('',#49099); +#49099 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); +#49100 = SURFACE_CURVE('',#49101,(#49105,#49112),.PCURVE_S1.); +#49101 = LINE('',#49102,#49103); +#49102 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); +#49103 = VECTOR('',#49104,1.); +#49104 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); +#49105 = PCURVE('',#45736,#49106); +#49106 = DEFINITIONAL_REPRESENTATION('',(#49107),#49111); +#49107 = LINE('',#49108,#49109); +#49108 = CARTESIAN_POINT('',(1.96,-0.1)); +#49109 = VECTOR('',#49110,1.); +#49110 = DIRECTION('',(0.707106781187,0.707106781187)); +#49111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49112 = PCURVE('',#46207,#49113); +#49113 = DEFINITIONAL_REPRESENTATION('',(#49114),#49118); +#49114 = LINE('',#49115,#49116); +#49115 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); +#49116 = VECTOR('',#49117,1.); +#49117 = DIRECTION('',(0.E+000,-1.)); +#49118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49119 = ORIENTED_EDGE('',*,*,#49120,.F.); +#49120 = EDGE_CURVE('',#49121,#49098,#49123,.T.); +#49121 = VERTEX_POINT('',#49122); +#49122 = CARTESIAN_POINT('',(-0.41,0.645,-1.5)); +#49123 = SURFACE_CURVE('',#49124,(#49128,#49135),.PCURVE_S1.); +#49124 = LINE('',#49125,#49126); +#49125 = CARTESIAN_POINT('',(-0.41,0.645,-1.5)); +#49126 = VECTOR('',#49127,1.); +#49127 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49128 = PCURVE('',#45736,#49129); +#49129 = DEFINITIONAL_REPRESENTATION('',(#49130),#49134); +#49130 = LINE('',#49131,#49132); +#49131 = CARTESIAN_POINT('',(1.96,-0.35)); +#49132 = VECTOR('',#49133,1.); +#49133 = DIRECTION('',(0.E+000,1.)); +#49134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49135 = PCURVE('',#49136,#49141); +#49136 = PLANE('',#49137); +#49137 = AXIS2_PLACEMENT_3D('',#49138,#49139,#49140); +#49138 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); +#49139 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49140 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49141 = DEFINITIONAL_REPRESENTATION('',(#49142),#49146); +#49142 = LINE('',#49143,#49144); +#49143 = CARTESIAN_POINT('',(0.E+000,-0.58)); +#49144 = VECTOR('',#49145,1.); +#49145 = DIRECTION('',(1.,0.E+000)); +#49146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49147 = ORIENTED_EDGE('',*,*,#49148,.F.); +#49148 = EDGE_CURVE('',#49149,#49121,#49151,.T.); +#49149 = VERTEX_POINT('',#49150); +#49150 = CARTESIAN_POINT('',(-0.16,0.645,-1.75)); +#49151 = SURFACE_CURVE('',#49152,(#49157,#49164),.PCURVE_S1.); +#49152 = CIRCLE('',#49153,0.25); +#49153 = AXIS2_PLACEMENT_3D('',#49154,#49155,#49156); +#49154 = CARTESIAN_POINT('',(-0.16,0.645,-1.5)); +#49155 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49156 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49157 = PCURVE('',#45736,#49158); +#49158 = DEFINITIONAL_REPRESENTATION('',(#49159),#49163); +#49159 = CIRCLE('',#49160,0.25); +#49160 = AXIS2_PLACEMENT_2D('',#49161,#49162); +#49161 = CARTESIAN_POINT('',(1.71,-0.35)); +#49162 = DIRECTION('',(0.E+000,-1.)); +#49163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49164 = PCURVE('',#49165,#49170); +#49165 = CYLINDRICAL_SURFACE('',#49166,0.25); +#49166 = AXIS2_PLACEMENT_3D('',#49167,#49168,#49169); +#49167 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); +#49168 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49169 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49170 = DEFINITIONAL_REPRESENTATION('',(#49171),#49174); +#49171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49172,#49173),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46780 = CARTESIAN_POINT('',(1.570796326795,-0.58)); -#46781 = CARTESIAN_POINT('',(3.14159265359,-0.58)); -#46782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46783 = ORIENTED_EDGE('',*,*,#46784,.F.); -#46784 = EDGE_CURVE('',#46785,#46757,#46787,.T.); -#46785 = VERTEX_POINT('',#46786); -#46786 = CARTESIAN_POINT('',(0.16,0.645,-1.75)); -#46787 = SURFACE_CURVE('',#46788,(#46792,#46799),.PCURVE_S1.); -#46788 = LINE('',#46789,#46790); -#46789 = CARTESIAN_POINT('',(0.16,0.645,-1.75)); -#46790 = VECTOR('',#46791,1.); -#46791 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46792 = PCURVE('',#43344,#46793); -#46793 = DEFINITIONAL_REPRESENTATION('',(#46794),#46798); -#46794 = LINE('',#46795,#46796); -#46795 = CARTESIAN_POINT('',(1.39,-0.6)); -#46796 = VECTOR('',#46797,1.); -#46797 = DIRECTION('',(1.,0.E+000)); -#46798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46799 = PCURVE('',#46800,#46805); -#46800 = PLANE('',#46801); -#46801 = AXIS2_PLACEMENT_3D('',#46802,#46803,#46804); -#46802 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); -#46803 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#46804 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#46805 = DEFINITIONAL_REPRESENTATION('',(#46806),#46810); -#46806 = LINE('',#46807,#46808); -#46807 = CARTESIAN_POINT('',(0.E+000,-0.58)); -#46808 = VECTOR('',#46809,1.); -#46809 = DIRECTION('',(1.,0.E+000)); -#46810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46811 = ORIENTED_EDGE('',*,*,#46812,.F.); -#46812 = EDGE_CURVE('',#46813,#46785,#46815,.T.); -#46813 = VERTEX_POINT('',#46814); -#46814 = CARTESIAN_POINT('',(0.41,0.645,-1.5)); -#46815 = SURFACE_CURVE('',#46816,(#46821,#46828),.PCURVE_S1.); -#46816 = CIRCLE('',#46817,0.25); -#46817 = AXIS2_PLACEMENT_3D('',#46818,#46819,#46820); -#46818 = CARTESIAN_POINT('',(0.16,0.645,-1.5)); -#46819 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46820 = DIRECTION('',(1.,0.E+000,0.E+000)); -#46821 = PCURVE('',#43344,#46822); -#46822 = DEFINITIONAL_REPRESENTATION('',(#46823),#46827); -#46823 = CIRCLE('',#46824,0.25); -#46824 = AXIS2_PLACEMENT_2D('',#46825,#46826); -#46825 = CARTESIAN_POINT('',(1.39,-0.35)); -#46826 = DIRECTION('',(-1.,0.E+000)); -#46827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46828 = PCURVE('',#46829,#46834); -#46829 = CYLINDRICAL_SURFACE('',#46830,0.25); -#46830 = AXIS2_PLACEMENT_3D('',#46831,#46832,#46833); -#46831 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); -#46832 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46833 = DIRECTION('',(1.,0.E+000,0.E+000)); -#46834 = DEFINITIONAL_REPRESENTATION('',(#46835),#46838); -#46835 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#46836,#46837),.UNSPECIFIED., +#49172 = CARTESIAN_POINT('',(1.570796326795,-0.58)); +#49173 = CARTESIAN_POINT('',(3.14159265359,-0.58)); +#49174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49175 = ORIENTED_EDGE('',*,*,#49176,.F.); +#49176 = EDGE_CURVE('',#49177,#49149,#49179,.T.); +#49177 = VERTEX_POINT('',#49178); +#49178 = CARTESIAN_POINT('',(0.16,0.645,-1.75)); +#49179 = SURFACE_CURVE('',#49180,(#49184,#49191),.PCURVE_S1.); +#49180 = LINE('',#49181,#49182); +#49181 = CARTESIAN_POINT('',(0.16,0.645,-1.75)); +#49182 = VECTOR('',#49183,1.); +#49183 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49184 = PCURVE('',#45736,#49185); +#49185 = DEFINITIONAL_REPRESENTATION('',(#49186),#49190); +#49186 = LINE('',#49187,#49188); +#49187 = CARTESIAN_POINT('',(1.39,-0.6)); +#49188 = VECTOR('',#49189,1.); +#49189 = DIRECTION('',(1.,0.E+000)); +#49190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49191 = PCURVE('',#49192,#49197); +#49192 = PLANE('',#49193); +#49193 = AXIS2_PLACEMENT_3D('',#49194,#49195,#49196); +#49194 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); +#49195 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49196 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49197 = DEFINITIONAL_REPRESENTATION('',(#49198),#49202); +#49198 = LINE('',#49199,#49200); +#49199 = CARTESIAN_POINT('',(0.E+000,-0.58)); +#49200 = VECTOR('',#49201,1.); +#49201 = DIRECTION('',(1.,0.E+000)); +#49202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49203 = ORIENTED_EDGE('',*,*,#49204,.F.); +#49204 = EDGE_CURVE('',#49205,#49177,#49207,.T.); +#49205 = VERTEX_POINT('',#49206); +#49206 = CARTESIAN_POINT('',(0.41,0.645,-1.5)); +#49207 = SURFACE_CURVE('',#49208,(#49213,#49220),.PCURVE_S1.); +#49208 = CIRCLE('',#49209,0.25); +#49209 = AXIS2_PLACEMENT_3D('',#49210,#49211,#49212); +#49210 = CARTESIAN_POINT('',(0.16,0.645,-1.5)); +#49211 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49212 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49213 = PCURVE('',#45736,#49214); +#49214 = DEFINITIONAL_REPRESENTATION('',(#49215),#49219); +#49215 = CIRCLE('',#49216,0.25); +#49216 = AXIS2_PLACEMENT_2D('',#49217,#49218); +#49217 = CARTESIAN_POINT('',(1.39,-0.35)); +#49218 = DIRECTION('',(-1.,0.E+000)); +#49219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49220 = PCURVE('',#49221,#49226); +#49221 = CYLINDRICAL_SURFACE('',#49222,0.25); +#49222 = AXIS2_PLACEMENT_3D('',#49223,#49224,#49225); +#49223 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); +#49224 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49225 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49226 = DEFINITIONAL_REPRESENTATION('',(#49227),#49230); +#49227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49228,#49229),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#46836 = CARTESIAN_POINT('',(0.E+000,-0.58)); -#46837 = CARTESIAN_POINT('',(1.570796326795,-0.58)); -#46838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46839 = ORIENTED_EDGE('',*,*,#46840,.F.); -#46840 = EDGE_CURVE('',#46841,#46813,#46843,.T.); -#46841 = VERTEX_POINT('',#46842); -#46842 = CARTESIAN_POINT('',(0.41,0.645,-1.25)); -#46843 = SURFACE_CURVE('',#46844,(#46848,#46855),.PCURVE_S1.); -#46844 = LINE('',#46845,#46846); -#46845 = CARTESIAN_POINT('',(0.41,0.645,-1.25)); -#46846 = VECTOR('',#46847,1.); -#46847 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#46848 = PCURVE('',#43344,#46849); -#46849 = DEFINITIONAL_REPRESENTATION('',(#46850),#46854); -#46850 = LINE('',#46851,#46852); -#46851 = CARTESIAN_POINT('',(1.14,-0.1)); -#46852 = VECTOR('',#46853,1.); -#46853 = DIRECTION('',(0.E+000,-1.)); -#46854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46855 = PCURVE('',#46856,#46861); -#46856 = PLANE('',#46857); -#46857 = AXIS2_PLACEMENT_3D('',#46858,#46859,#46860); -#46858 = CARTESIAN_POINT('',(0.41,1.225,-1.1)); -#46859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#46860 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#46861 = DEFINITIONAL_REPRESENTATION('',(#46862),#46866); -#46862 = LINE('',#46863,#46864); -#46863 = CARTESIAN_POINT('',(0.15,-0.58)); -#46864 = VECTOR('',#46865,1.); -#46865 = DIRECTION('',(1.,0.E+000)); -#46866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46867 = ORIENTED_EDGE('',*,*,#46868,.F.); -#46868 = EDGE_CURVE('',#43329,#46841,#46869,.T.); -#46869 = SURFACE_CURVE('',#46870,(#46874,#46881),.PCURVE_S1.); -#46870 = LINE('',#46871,#46872); -#46871 = CARTESIAN_POINT('',(0.51,0.645,-1.15)); -#46872 = VECTOR('',#46873,1.); -#46873 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); -#46874 = PCURVE('',#43344,#46875); -#46875 = DEFINITIONAL_REPRESENTATION('',(#46876),#46880); -#46876 = LINE('',#46877,#46878); -#46877 = CARTESIAN_POINT('',(1.04,0.E+000)); -#46878 = VECTOR('',#46879,1.); -#46879 = DIRECTION('',(0.707106781187,-0.707106781187)); -#46880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#49228 = CARTESIAN_POINT('',(0.E+000,-0.58)); +#49229 = CARTESIAN_POINT('',(1.570796326795,-0.58)); +#49230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#46881 = PCURVE('',#43372,#46882); -#46882 = DEFINITIONAL_REPRESENTATION('',(#46883),#46887); -#46883 = LINE('',#46884,#46885); -#46884 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); -#46885 = VECTOR('',#46886,1.); -#46886 = DIRECTION('',(0.E+000,-1.)); -#46887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46888 = ORIENTED_EDGE('',*,*,#43328,.F.); -#46889 = ORIENTED_EDGE('',*,*,#46890,.T.); -#46890 = EDGE_CURVE('',#43301,#46629,#46891,.T.); -#46891 = SURFACE_CURVE('',#46892,(#46896,#46903),.PCURVE_S1.); -#46892 = LINE('',#46893,#46894); -#46893 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); -#46894 = VECTOR('',#46895,1.); -#46895 = DIRECTION('',(-3.625473254942E-011,0.E+000,1.)); -#46896 = PCURVE('',#43344,#46897); -#46897 = DEFINITIONAL_REPRESENTATION('',(#46898),#46902); -#46898 = LINE('',#46899,#46900); -#46899 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#46900 = VECTOR('',#46901,1.); -#46901 = DIRECTION('',(3.625473254942E-011,1.)); -#46902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46903 = PCURVE('',#43317,#46904); -#46904 = DEFINITIONAL_REPRESENTATION('',(#46905),#46931); -#46905 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#46906,#46907,#46908,#46909, - #46910,#46911,#46912,#46913,#46914,#46915,#46916,#46917,#46918, - #46919,#46920,#46921,#46922,#46923,#46924,#46925,#46926,#46927, - #46928,#46929,#46930),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#49231 = ORIENTED_EDGE('',*,*,#49232,.F.); +#49232 = EDGE_CURVE('',#49233,#49205,#49235,.T.); +#49233 = VERTEX_POINT('',#49234); +#49234 = CARTESIAN_POINT('',(0.41,0.645,-1.25)); +#49235 = SURFACE_CURVE('',#49236,(#49240,#49247),.PCURVE_S1.); +#49236 = LINE('',#49237,#49238); +#49237 = CARTESIAN_POINT('',(0.41,0.645,-1.25)); +#49238 = VECTOR('',#49239,1.); +#49239 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49240 = PCURVE('',#45736,#49241); +#49241 = DEFINITIONAL_REPRESENTATION('',(#49242),#49246); +#49242 = LINE('',#49243,#49244); +#49243 = CARTESIAN_POINT('',(1.14,-0.1)); +#49244 = VECTOR('',#49245,1.); +#49245 = DIRECTION('',(0.E+000,-1.)); +#49246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49247 = PCURVE('',#49248,#49253); +#49248 = PLANE('',#49249); +#49249 = AXIS2_PLACEMENT_3D('',#49250,#49251,#49252); +#49250 = CARTESIAN_POINT('',(0.41,1.225,-1.1)); +#49251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49252 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49253 = DEFINITIONAL_REPRESENTATION('',(#49254),#49258); +#49254 = LINE('',#49255,#49256); +#49255 = CARTESIAN_POINT('',(0.15,-0.58)); +#49256 = VECTOR('',#49257,1.); +#49257 = DIRECTION('',(1.,0.E+000)); +#49258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49259 = ORIENTED_EDGE('',*,*,#49260,.F.); +#49260 = EDGE_CURVE('',#45721,#49233,#49261,.T.); +#49261 = SURFACE_CURVE('',#49262,(#49266,#49273),.PCURVE_S1.); +#49262 = LINE('',#49263,#49264); +#49263 = CARTESIAN_POINT('',(0.51,0.645,-1.15)); +#49264 = VECTOR('',#49265,1.); +#49265 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); +#49266 = PCURVE('',#45736,#49267); +#49267 = DEFINITIONAL_REPRESENTATION('',(#49268),#49272); +#49268 = LINE('',#49269,#49270); +#49269 = CARTESIAN_POINT('',(1.04,0.E+000)); +#49270 = VECTOR('',#49271,1.); +#49271 = DIRECTION('',(0.707106781187,-0.707106781187)); +#49272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49273 = PCURVE('',#45764,#49274); +#49274 = DEFINITIONAL_REPRESENTATION('',(#49275),#49279); +#49275 = LINE('',#49276,#49277); +#49276 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); +#49277 = VECTOR('',#49278,1.); +#49278 = DIRECTION('',(0.E+000,-1.)); +#49279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49280 = ORIENTED_EDGE('',*,*,#45720,.F.); +#49281 = ORIENTED_EDGE('',*,*,#49282,.T.); +#49282 = EDGE_CURVE('',#45693,#49021,#49283,.T.); +#49283 = SURFACE_CURVE('',#49284,(#49288,#49295),.PCURVE_S1.); +#49284 = LINE('',#49285,#49286); +#49285 = CARTESIAN_POINT('',(1.55,0.645,-1.15)); +#49286 = VECTOR('',#49287,1.); +#49287 = DIRECTION('',(-3.625473254942E-011,0.E+000,1.)); +#49288 = PCURVE('',#45736,#49289); +#49289 = DEFINITIONAL_REPRESENTATION('',(#49290),#49294); +#49290 = LINE('',#49291,#49292); +#49291 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#49292 = VECTOR('',#49293,1.); +#49293 = DIRECTION('',(3.625473254942E-011,1.)); +#49294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49295 = PCURVE('',#45709,#49296); +#49296 = DEFINITIONAL_REPRESENTATION('',(#49297),#49323); +#49297 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49298,#49299,#49300,#49301, + #49302,#49303,#49304,#49305,#49306,#49307,#49308,#49309,#49310, + #49311,#49312,#49313,#49314,#49315,#49316,#49317,#49318,#49319, + #49320,#49321,#49322),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#46906 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#46907 = CARTESIAN_POINT('',(1.570796326802,3.787878787879E-002)); -#46908 = CARTESIAN_POINT('',(1.570796326815,0.113636363636)); -#46909 = CARTESIAN_POINT('',(1.570796326836,0.227272727273)); -#46910 = CARTESIAN_POINT('',(1.570796326857,0.340909090909)); -#46911 = CARTESIAN_POINT('',(1.570796326877,0.454545454545)); -#46912 = CARTESIAN_POINT('',(1.570796326898,0.568181818182)); -#46913 = CARTESIAN_POINT('',(1.570796326918,0.681818181818)); -#46914 = CARTESIAN_POINT('',(1.570796326939,0.795454545455)); -#46915 = CARTESIAN_POINT('',(1.57079632696,0.909090909091)); -#46916 = CARTESIAN_POINT('',(1.57079632698,1.022727272727)); -#46917 = CARTESIAN_POINT('',(1.570796327001,1.136363636364)); -#46918 = CARTESIAN_POINT('',(1.570796327021,1.25)); -#46919 = CARTESIAN_POINT('',(1.570796327042,1.363636363636)); -#46920 = CARTESIAN_POINT('',(1.570796327063,1.477272727273)); -#46921 = CARTESIAN_POINT('',(1.570796327083,1.590909090909)); -#46922 = CARTESIAN_POINT('',(1.570796327104,1.704545454545)); -#46923 = CARTESIAN_POINT('',(1.570796327124,1.818181818182)); -#46924 = CARTESIAN_POINT('',(1.570796327145,1.931818181818)); -#46925 = CARTESIAN_POINT('',(1.570796327166,2.045454545455)); -#46926 = CARTESIAN_POINT('',(1.570796327186,2.159090909091)); -#46927 = CARTESIAN_POINT('',(1.570796327207,2.272727272727)); -#46928 = CARTESIAN_POINT('',(1.570796327227,2.386363636364)); -#46929 = CARTESIAN_POINT('',(1.570796327241,2.462121212121)); -#46930 = CARTESIAN_POINT('',(1.570796327248,2.5)); -#46931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46932 = ADVANCED_FACE('',(#46933),#43815,.T.); -#46933 = FACE_BOUND('',#46934,.F.); -#46934 = EDGE_LOOP('',(#46935,#46965,#46986,#46987,#46988)); -#46935 = ORIENTED_EDGE('',*,*,#46936,.T.); -#46936 = EDGE_CURVE('',#46937,#46939,#46941,.T.); -#46937 = VERTEX_POINT('',#46938); -#46938 = CARTESIAN_POINT('',(-0.41,0.92,-1.25)); -#46939 = VERTEX_POINT('',#46940); -#46940 = CARTESIAN_POINT('',(-0.41,0.773013158464,-1.25)); -#46941 = SURFACE_CURVE('',#46942,(#46946,#46953),.PCURVE_S1.); -#46942 = LINE('',#46943,#46944); -#46943 = CARTESIAN_POINT('',(-0.41,0.92,-1.25)); -#46944 = VECTOR('',#46945,1.); -#46945 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#46946 = PCURVE('',#43815,#46947); -#46947 = DEFINITIONAL_REPRESENTATION('',(#46948),#46952); -#46948 = LINE('',#46949,#46950); -#46949 = CARTESIAN_POINT('',(-0.1375,7.071067811865E-002)); -#46950 = VECTOR('',#46951,1.); -#46951 = DIRECTION('',(1.,0.E+000)); -#46952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46953 = PCURVE('',#46954,#46959); -#46954 = PLANE('',#46955); -#46955 = AXIS2_PLACEMENT_3D('',#46956,#46957,#46958); -#46956 = CARTESIAN_POINT('',(-0.41,0.E+000,0.E+000)); -#46957 = DIRECTION('',(1.,0.E+000,0.E+000)); -#46958 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#46959 = DEFINITIONAL_REPRESENTATION('',(#46960),#46964); -#46960 = LINE('',#46961,#46962); -#46961 = CARTESIAN_POINT('',(1.25,0.92)); -#46962 = VECTOR('',#46963,1.); -#46963 = DIRECTION('',(0.E+000,-1.)); -#46964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46965 = ORIENTED_EDGE('',*,*,#46966,.F.); -#46966 = EDGE_CURVE('',#46706,#46939,#46967,.T.); -#46967 = SURFACE_CURVE('',#46968,(#46972,#46979),.PCURVE_S1.); -#46968 = LINE('',#46969,#46970); -#46969 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); -#46970 = VECTOR('',#46971,1.); -#46971 = DIRECTION('',(0.E+000,1.,0.E+000)); -#46972 = PCURVE('',#43815,#46973); -#46973 = DEFINITIONAL_REPRESENTATION('',(#46974),#46978); -#46974 = LINE('',#46975,#46976); -#46975 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); -#46976 = VECTOR('',#46977,1.); -#46977 = DIRECTION('',(-1.,0.E+000)); -#46978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46979 = PCURVE('',#46744,#46980); -#46980 = DEFINITIONAL_REPRESENTATION('',(#46981),#46985); -#46981 = LINE('',#46982,#46983); -#46982 = CARTESIAN_POINT('',(0.25,-0.58)); -#46983 = VECTOR('',#46984,1.); -#46984 = DIRECTION('',(0.E+000,1.)); -#46985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#46986 = ORIENTED_EDGE('',*,*,#46705,.T.); -#46987 = ORIENTED_EDGE('',*,*,#43799,.T.); -#46988 = ORIENTED_EDGE('',*,*,#46989,.T.); -#46989 = EDGE_CURVE('',#43777,#46937,#46990,.T.); -#46990 = SURFACE_CURVE('',#46991,(#46995,#47002),.PCURVE_S1.); -#46991 = LINE('',#46992,#46993); -#46992 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); -#46993 = VECTOR('',#46994,1.); -#46994 = DIRECTION('',(0.707106781187,0.E+000,-0.707106781187)); -#46995 = PCURVE('',#43815,#46996); -#46996 = DEFINITIONAL_REPRESENTATION('',(#46997),#47001); -#46997 = LINE('',#46998,#46999); -#46998 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); -#46999 = VECTOR('',#47000,1.); -#47000 = DIRECTION('',(0.E+000,1.)); -#47001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47002 = PCURVE('',#43400,#47003); -#47003 = DEFINITIONAL_REPRESENTATION('',(#47004),#47008); -#47004 = LINE('',#47005,#47006); -#47005 = CARTESIAN_POINT('',(3.605,1.2)); -#47006 = VECTOR('',#47007,1.); -#47007 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#47008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#49298 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49299 = CARTESIAN_POINT('',(1.570796326802,3.787878787879E-002)); +#49300 = CARTESIAN_POINT('',(1.570796326815,0.113636363636)); +#49301 = CARTESIAN_POINT('',(1.570796326836,0.227272727273)); +#49302 = CARTESIAN_POINT('',(1.570796326857,0.340909090909)); +#49303 = CARTESIAN_POINT('',(1.570796326877,0.454545454545)); +#49304 = CARTESIAN_POINT('',(1.570796326898,0.568181818182)); +#49305 = CARTESIAN_POINT('',(1.570796326918,0.681818181818)); +#49306 = CARTESIAN_POINT('',(1.570796326939,0.795454545455)); +#49307 = CARTESIAN_POINT('',(1.57079632696,0.909090909091)); +#49308 = CARTESIAN_POINT('',(1.57079632698,1.022727272727)); +#49309 = CARTESIAN_POINT('',(1.570796327001,1.136363636364)); +#49310 = CARTESIAN_POINT('',(1.570796327021,1.25)); +#49311 = CARTESIAN_POINT('',(1.570796327042,1.363636363636)); +#49312 = CARTESIAN_POINT('',(1.570796327063,1.477272727273)); +#49313 = CARTESIAN_POINT('',(1.570796327083,1.590909090909)); +#49314 = CARTESIAN_POINT('',(1.570796327104,1.704545454545)); +#49315 = CARTESIAN_POINT('',(1.570796327124,1.818181818182)); +#49316 = CARTESIAN_POINT('',(1.570796327145,1.931818181818)); +#49317 = CARTESIAN_POINT('',(1.570796327166,2.045454545455)); +#49318 = CARTESIAN_POINT('',(1.570796327186,2.159090909091)); +#49319 = CARTESIAN_POINT('',(1.570796327207,2.272727272727)); +#49320 = CARTESIAN_POINT('',(1.570796327227,2.386363636364)); +#49321 = CARTESIAN_POINT('',(1.570796327241,2.462121212121)); +#49322 = CARTESIAN_POINT('',(1.570796327248,2.5)); +#49323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49324 = ADVANCED_FACE('',(#49325),#46207,.T.); +#49325 = FACE_BOUND('',#49326,.F.); +#49326 = EDGE_LOOP('',(#49327,#49357,#49378,#49379,#49380)); +#49327 = ORIENTED_EDGE('',*,*,#49328,.T.); +#49328 = EDGE_CURVE('',#49329,#49331,#49333,.T.); +#49329 = VERTEX_POINT('',#49330); +#49330 = CARTESIAN_POINT('',(-0.41,0.92,-1.25)); +#49331 = VERTEX_POINT('',#49332); +#49332 = CARTESIAN_POINT('',(-0.41,0.773013158464,-1.25)); +#49333 = SURFACE_CURVE('',#49334,(#49338,#49345),.PCURVE_S1.); +#49334 = LINE('',#49335,#49336); +#49335 = CARTESIAN_POINT('',(-0.41,0.92,-1.25)); +#49336 = VECTOR('',#49337,1.); +#49337 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#49338 = PCURVE('',#46207,#49339); +#49339 = DEFINITIONAL_REPRESENTATION('',(#49340),#49344); +#49340 = LINE('',#49341,#49342); +#49341 = CARTESIAN_POINT('',(-0.1375,7.071067811865E-002)); +#49342 = VECTOR('',#49343,1.); +#49343 = DIRECTION('',(1.,0.E+000)); +#49344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49345 = PCURVE('',#49346,#49351); +#49346 = PLANE('',#49347); +#49347 = AXIS2_PLACEMENT_3D('',#49348,#49349,#49350); +#49348 = CARTESIAN_POINT('',(-0.41,0.E+000,0.E+000)); +#49349 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49350 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49351 = DEFINITIONAL_REPRESENTATION('',(#49352),#49356); +#49352 = LINE('',#49353,#49354); +#49353 = CARTESIAN_POINT('',(1.25,0.92)); +#49354 = VECTOR('',#49355,1.); +#49355 = DIRECTION('',(0.E+000,-1.)); +#49356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49357 = ORIENTED_EDGE('',*,*,#49358,.F.); +#49358 = EDGE_CURVE('',#49098,#49331,#49359,.T.); +#49359 = SURFACE_CURVE('',#49360,(#49364,#49371),.PCURVE_S1.); +#49360 = LINE('',#49361,#49362); +#49361 = CARTESIAN_POINT('',(-0.41,0.645,-1.25)); +#49362 = VECTOR('',#49363,1.); +#49363 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49364 = PCURVE('',#46207,#49365); +#49365 = DEFINITIONAL_REPRESENTATION('',(#49366),#49370); +#49366 = LINE('',#49367,#49368); +#49367 = CARTESIAN_POINT('',(0.1375,7.071067811865E-002)); +#49368 = VECTOR('',#49369,1.); +#49369 = DIRECTION('',(-1.,0.E+000)); +#49370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49371 = PCURVE('',#49136,#49372); +#49372 = DEFINITIONAL_REPRESENTATION('',(#49373),#49377); +#49373 = LINE('',#49374,#49375); +#49374 = CARTESIAN_POINT('',(0.25,-0.58)); +#49375 = VECTOR('',#49376,1.); +#49376 = DIRECTION('',(0.E+000,1.)); +#49377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49378 = ORIENTED_EDGE('',*,*,#49097,.T.); +#49379 = ORIENTED_EDGE('',*,*,#46191,.T.); +#49380 = ORIENTED_EDGE('',*,*,#49381,.T.); +#49381 = EDGE_CURVE('',#46169,#49329,#49382,.T.); +#49382 = SURFACE_CURVE('',#49383,(#49387,#49394),.PCURVE_S1.); +#49383 = LINE('',#49384,#49385); +#49384 = CARTESIAN_POINT('',(-0.51,0.92,-1.15)); +#49385 = VECTOR('',#49386,1.); +#49386 = DIRECTION('',(0.707106781187,0.E+000,-0.707106781187)); +#49387 = PCURVE('',#46207,#49388); +#49388 = DEFINITIONAL_REPRESENTATION('',(#49389),#49393); +#49389 = LINE('',#49390,#49391); +#49390 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); +#49391 = VECTOR('',#49392,1.); +#49392 = DIRECTION('',(0.E+000,1.)); +#49393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49394 = PCURVE('',#45792,#49395); +#49395 = DEFINITIONAL_REPRESENTATION('',(#49396),#49400); +#49396 = LINE('',#49397,#49398); +#49397 = CARTESIAN_POINT('',(3.605,1.2)); +#49398 = VECTOR('',#49399,1.); +#49399 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#49400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49401 = ADVANCED_FACE('',(#49402),#49346,.F.); +#49402 = FACE_BOUND('',#49403,.F.); +#49403 = EDGE_LOOP('',(#49404,#49434,#49462,#49488,#49489)); +#49404 = ORIENTED_EDGE('',*,*,#49405,.T.); +#49405 = EDGE_CURVE('',#49406,#49408,#49410,.T.); +#49406 = VERTEX_POINT('',#49407); +#49407 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); +#49408 = VERTEX_POINT('',#49409); +#49409 = CARTESIAN_POINT('',(-0.41,0.925,-1.75)); +#49410 = SURFACE_CURVE('',#49411,(#49415,#49422),.PCURVE_S1.); +#49411 = LINE('',#49412,#49413); +#49412 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); +#49413 = VECTOR('',#49414,1.); +#49414 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49415 = PCURVE('',#49346,#49416); +#49416 = DEFINITIONAL_REPRESENTATION('',(#49417),#49421); +#49417 = LINE('',#49418,#49419); +#49418 = CARTESIAN_POINT('',(1.75,0.92)); +#49419 = VECTOR('',#49420,1.); +#49420 = DIRECTION('',(0.E+000,1.)); +#49421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49422 = PCURVE('',#49423,#49428); +#49423 = PLANE('',#49424); +#49424 = AXIS2_PLACEMENT_3D('',#49425,#49426,#49427); +#49425 = CARTESIAN_POINT('',(-0.41,0.725,-1.75)); +#49426 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49427 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49428 = DEFINITIONAL_REPRESENTATION('',(#49429),#49433); +#49429 = LINE('',#49430,#49431); +#49430 = CARTESIAN_POINT('',(0.195,0.E+000)); +#49431 = VECTOR('',#49432,1.); +#49432 = DIRECTION('',(1.,0.E+000)); +#49433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49434 = ORIENTED_EDGE('',*,*,#49435,.F.); +#49435 = EDGE_CURVE('',#49436,#49408,#49438,.T.); +#49436 = VERTEX_POINT('',#49437); +#49437 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); +#49438 = SURFACE_CURVE('',#49439,(#49443,#49450),.PCURVE_S1.); +#49439 = LINE('',#49440,#49441); +#49440 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); +#49441 = VECTOR('',#49442,1.); +#49442 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49443 = PCURVE('',#49346,#49444); +#49444 = DEFINITIONAL_REPRESENTATION('',(#49445),#49449); +#49445 = LINE('',#49446,#49447); +#49446 = CARTESIAN_POINT('',(1.18,0.925)); +#49447 = VECTOR('',#49448,1.); +#49448 = DIRECTION('',(1.,0.E+000)); +#49449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#47009 = ADVANCED_FACE('',(#47010),#46954,.F.); -#47010 = FACE_BOUND('',#47011,.F.); -#47011 = EDGE_LOOP('',(#47012,#47042,#47070,#47096,#47097)); -#47012 = ORIENTED_EDGE('',*,*,#47013,.T.); -#47013 = EDGE_CURVE('',#47014,#47016,#47018,.T.); -#47014 = VERTEX_POINT('',#47015); -#47015 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); -#47016 = VERTEX_POINT('',#47017); -#47017 = CARTESIAN_POINT('',(-0.41,0.925,-1.75)); -#47018 = SURFACE_CURVE('',#47019,(#47023,#47030),.PCURVE_S1.); -#47019 = LINE('',#47020,#47021); -#47020 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); -#47021 = VECTOR('',#47022,1.); -#47022 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47023 = PCURVE('',#46954,#47024); -#47024 = DEFINITIONAL_REPRESENTATION('',(#47025),#47029); -#47025 = LINE('',#47026,#47027); -#47026 = CARTESIAN_POINT('',(1.75,0.92)); -#47027 = VECTOR('',#47028,1.); -#47028 = DIRECTION('',(0.E+000,1.)); -#47029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47030 = PCURVE('',#47031,#47036); -#47031 = PLANE('',#47032); -#47032 = AXIS2_PLACEMENT_3D('',#47033,#47034,#47035); -#47033 = CARTESIAN_POINT('',(-0.41,0.725,-1.75)); -#47034 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47035 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47036 = DEFINITIONAL_REPRESENTATION('',(#47037),#47041); -#47037 = LINE('',#47038,#47039); -#47038 = CARTESIAN_POINT('',(0.195,0.E+000)); -#47039 = VECTOR('',#47040,1.); -#47040 = DIRECTION('',(1.,0.E+000)); -#47041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47042 = ORIENTED_EDGE('',*,*,#47043,.F.); -#47043 = EDGE_CURVE('',#47044,#47016,#47046,.T.); -#47044 = VERTEX_POINT('',#47045); -#47045 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); -#47046 = SURFACE_CURVE('',#47047,(#47051,#47058),.PCURVE_S1.); -#47047 = LINE('',#47048,#47049); -#47048 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); -#47049 = VECTOR('',#47050,1.); -#47050 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47051 = PCURVE('',#46954,#47052); -#47052 = DEFINITIONAL_REPRESENTATION('',(#47053),#47057); -#47053 = LINE('',#47054,#47055); -#47054 = CARTESIAN_POINT('',(1.18,0.925)); -#47055 = VECTOR('',#47056,1.); -#47056 = DIRECTION('',(1.,0.E+000)); -#47057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47058 = PCURVE('',#47059,#47064); -#47059 = PLANE('',#47060); -#47060 = AXIS2_PLACEMENT_3D('',#47061,#47062,#47063); -#47061 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); -#47062 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#47063 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47064 = DEFINITIONAL_REPRESENTATION('',(#47065),#47069); -#47065 = LINE('',#47066,#47067); -#47066 = CARTESIAN_POINT('',(2.79,1.17)); -#47067 = VECTOR('',#47068,1.); -#47068 = DIRECTION('',(0.E+000,-1.)); -#47069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47070 = ORIENTED_EDGE('',*,*,#47071,.T.); -#47071 = EDGE_CURVE('',#47044,#46939,#47072,.T.); -#47072 = SURFACE_CURVE('',#47073,(#47078,#47085),.PCURVE_S1.); -#47073 = CIRCLE('',#47074,0.2); -#47074 = AXIS2_PLACEMENT_3D('',#47075,#47076,#47077); -#47075 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); -#47076 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47077 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47078 = PCURVE('',#46954,#47079); -#47079 = DEFINITIONAL_REPRESENTATION('',(#47080),#47084); -#47080 = CIRCLE('',#47081,0.2); -#47081 = AXIS2_PLACEMENT_2D('',#47082,#47083); -#47082 = CARTESIAN_POINT('',(1.38,0.925)); -#47083 = DIRECTION('',(-1.,0.E+000)); -#47084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47085 = PCURVE('',#47086,#47091); -#47086 = CYLINDRICAL_SURFACE('',#47087,0.2); -#47087 = AXIS2_PLACEMENT_3D('',#47088,#47089,#47090); -#47088 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); -#47089 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47090 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47091 = DEFINITIONAL_REPRESENTATION('',(#47092),#47095); -#47092 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47093,#47094),.UNSPECIFIED., +#49450 = PCURVE('',#49451,#49456); +#49451 = PLANE('',#49452); +#49452 = AXIS2_PLACEMENT_3D('',#49453,#49454,#49455); +#49453 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); +#49454 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#49455 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49456 = DEFINITIONAL_REPRESENTATION('',(#49457),#49461); +#49457 = LINE('',#49458,#49459); +#49458 = CARTESIAN_POINT('',(2.79,1.17)); +#49459 = VECTOR('',#49460,1.); +#49460 = DIRECTION('',(0.E+000,-1.)); +#49461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49462 = ORIENTED_EDGE('',*,*,#49463,.T.); +#49463 = EDGE_CURVE('',#49436,#49331,#49464,.T.); +#49464 = SURFACE_CURVE('',#49465,(#49470,#49477),.PCURVE_S1.); +#49465 = CIRCLE('',#49466,0.2); +#49466 = AXIS2_PLACEMENT_3D('',#49467,#49468,#49469); +#49467 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); +#49468 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49469 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49470 = PCURVE('',#49346,#49471); +#49471 = DEFINITIONAL_REPRESENTATION('',(#49472),#49476); +#49472 = CIRCLE('',#49473,0.2); +#49473 = AXIS2_PLACEMENT_2D('',#49474,#49475); +#49474 = CARTESIAN_POINT('',(1.38,0.925)); +#49475 = DIRECTION('',(-1.,0.E+000)); +#49476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49477 = PCURVE('',#49478,#49483); +#49478 = CYLINDRICAL_SURFACE('',#49479,0.2); +#49479 = AXIS2_PLACEMENT_3D('',#49480,#49481,#49482); +#49480 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); +#49481 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49482 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49483 = DEFINITIONAL_REPRESENTATION('',(#49484),#49487); +#49484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49485,#49486),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.86321189007),.PIECEWISE_BEZIER_KNOTS.); -#47093 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#47094 = CARTESIAN_POINT('',(4.004804543659,0.E+000)); -#47095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47096 = ORIENTED_EDGE('',*,*,#46936,.F.); -#47097 = ORIENTED_EDGE('',*,*,#47098,.F.); -#47098 = EDGE_CURVE('',#47014,#46937,#47099,.T.); -#47099 = SURFACE_CURVE('',#47100,(#47104,#47111),.PCURVE_S1.); -#47100 = LINE('',#47101,#47102); -#47101 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); -#47102 = VECTOR('',#47103,1.); -#47103 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47104 = PCURVE('',#46954,#47105); -#47105 = DEFINITIONAL_REPRESENTATION('',(#47106),#47110); -#47106 = LINE('',#47107,#47108); -#47107 = CARTESIAN_POINT('',(1.75,0.92)); -#47108 = VECTOR('',#47109,1.); -#47109 = DIRECTION('',(-1.,0.E+000)); -#47110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#49485 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#49486 = CARTESIAN_POINT('',(4.004804543659,0.E+000)); +#49487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49488 = ORIENTED_EDGE('',*,*,#49328,.F.); +#49489 = ORIENTED_EDGE('',*,*,#49490,.F.); +#49490 = EDGE_CURVE('',#49406,#49329,#49491,.T.); +#49491 = SURFACE_CURVE('',#49492,(#49496,#49503),.PCURVE_S1.); +#49492 = LINE('',#49493,#49494); +#49493 = CARTESIAN_POINT('',(-0.41,0.92,-1.75)); +#49494 = VECTOR('',#49495,1.); +#49495 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49496 = PCURVE('',#49346,#49497); +#49497 = DEFINITIONAL_REPRESENTATION('',(#49498),#49502); +#49498 = LINE('',#49499,#49500); +#49499 = CARTESIAN_POINT('',(1.75,0.92)); +#49500 = VECTOR('',#49501,1.); +#49501 = DIRECTION('',(-1.,0.E+000)); +#49502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49503 = PCURVE('',#45792,#49504); +#49504 = DEFINITIONAL_REPRESENTATION('',(#49505),#49509); +#49505 = LINE('',#49506,#49507); +#49506 = CARTESIAN_POINT('',(3.505,0.6)); +#49507 = VECTOR('',#49508,1.); +#49508 = DIRECTION('',(0.E+000,1.)); +#49509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49510 = ADVANCED_FACE('',(#49511),#49423,.T.); +#49511 = FACE_BOUND('',#49512,.F.); +#49512 = EDGE_LOOP('',(#49513,#49536,#49537,#49560)); +#49513 = ORIENTED_EDGE('',*,*,#49514,.F.); +#49514 = EDGE_CURVE('',#49408,#49515,#49517,.T.); +#49515 = VERTEX_POINT('',#49516); +#49516 = CARTESIAN_POINT('',(0.41,0.925,-1.75)); +#49517 = SURFACE_CURVE('',#49518,(#49522,#49529),.PCURVE_S1.); +#49518 = LINE('',#49519,#49520); +#49519 = CARTESIAN_POINT('',(-0.41,0.925,-1.75)); +#49520 = VECTOR('',#49521,1.); +#49521 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49522 = PCURVE('',#49423,#49523); +#49523 = DEFINITIONAL_REPRESENTATION('',(#49524),#49528); +#49524 = LINE('',#49525,#49526); +#49525 = CARTESIAN_POINT('',(0.2,0.E+000)); +#49526 = VECTOR('',#49527,1.); +#49527 = DIRECTION('',(0.E+000,1.)); +#49528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#47111 = PCURVE('',#43400,#47112); -#47112 = DEFINITIONAL_REPRESENTATION('',(#47113),#47117); -#47113 = LINE('',#47114,#47115); -#47114 = CARTESIAN_POINT('',(3.505,0.6)); -#47115 = VECTOR('',#47116,1.); -#47116 = DIRECTION('',(0.E+000,1.)); -#47117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47118 = ADVANCED_FACE('',(#47119),#47031,.T.); -#47119 = FACE_BOUND('',#47120,.F.); -#47120 = EDGE_LOOP('',(#47121,#47144,#47145,#47168)); -#47121 = ORIENTED_EDGE('',*,*,#47122,.F.); -#47122 = EDGE_CURVE('',#47016,#47123,#47125,.T.); -#47123 = VERTEX_POINT('',#47124); -#47124 = CARTESIAN_POINT('',(0.41,0.925,-1.75)); -#47125 = SURFACE_CURVE('',#47126,(#47130,#47137),.PCURVE_S1.); -#47126 = LINE('',#47127,#47128); -#47127 = CARTESIAN_POINT('',(-0.41,0.925,-1.75)); -#47128 = VECTOR('',#47129,1.); -#47129 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47130 = PCURVE('',#47031,#47131); -#47131 = DEFINITIONAL_REPRESENTATION('',(#47132),#47136); -#47132 = LINE('',#47133,#47134); -#47133 = CARTESIAN_POINT('',(0.2,0.E+000)); -#47134 = VECTOR('',#47135,1.); -#47135 = DIRECTION('',(0.E+000,1.)); -#47136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47137 = PCURVE('',#47059,#47138); -#47138 = DEFINITIONAL_REPRESENTATION('',(#47139),#47143); -#47139 = LINE('',#47140,#47141); -#47140 = CARTESIAN_POINT('',(2.79,0.6)); -#47141 = VECTOR('',#47142,1.); -#47142 = DIRECTION('',(1.,0.E+000)); -#47143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47144 = ORIENTED_EDGE('',*,*,#47013,.F.); -#47145 = ORIENTED_EDGE('',*,*,#47146,.F.); -#47146 = EDGE_CURVE('',#47147,#47014,#47149,.T.); -#47147 = VERTEX_POINT('',#47148); -#47148 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); -#47149 = SURFACE_CURVE('',#47150,(#47154,#47161),.PCURVE_S1.); -#47150 = LINE('',#47151,#47152); -#47151 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); -#47152 = VECTOR('',#47153,1.); -#47153 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47154 = PCURVE('',#47031,#47155); -#47155 = DEFINITIONAL_REPRESENTATION('',(#47156),#47160); -#47156 = LINE('',#47157,#47158); -#47157 = CARTESIAN_POINT('',(0.195,0.82)); -#47158 = VECTOR('',#47159,1.); -#47159 = DIRECTION('',(0.E+000,-1.)); -#47160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47161 = PCURVE('',#43400,#47162); -#47162 = DEFINITIONAL_REPRESENTATION('',(#47163),#47167); -#47163 = LINE('',#47164,#47165); -#47164 = CARTESIAN_POINT('',(2.685,0.6)); -#47165 = VECTOR('',#47166,1.); -#47166 = DIRECTION('',(1.,0.E+000)); -#47167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47168 = ORIENTED_EDGE('',*,*,#47169,.T.); -#47169 = EDGE_CURVE('',#47147,#47123,#47170,.T.); -#47170 = SURFACE_CURVE('',#47171,(#47175,#47182),.PCURVE_S1.); -#47171 = LINE('',#47172,#47173); -#47172 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); -#47173 = VECTOR('',#47174,1.); -#47174 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47175 = PCURVE('',#47031,#47176); -#47176 = DEFINITIONAL_REPRESENTATION('',(#47177),#47181); -#47177 = LINE('',#47178,#47179); -#47178 = CARTESIAN_POINT('',(0.195,0.82)); -#47179 = VECTOR('',#47180,1.); -#47180 = DIRECTION('',(1.,0.E+000)); -#47181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47182 = PCURVE('',#47183,#47188); -#47183 = PLANE('',#47184); -#47184 = AXIS2_PLACEMENT_3D('',#47185,#47186,#47187); -#47185 = CARTESIAN_POINT('',(0.41,0.E+000,0.E+000)); -#47186 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47187 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47188 = DEFINITIONAL_REPRESENTATION('',(#47189),#47193); -#47189 = LINE('',#47190,#47191); -#47190 = CARTESIAN_POINT('',(1.75,0.92)); -#47191 = VECTOR('',#47192,1.); -#47192 = DIRECTION('',(0.E+000,1.)); -#47193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47194 = ADVANCED_FACE('',(#47195,#47667,#48012,#48357),#47059,.T.); -#47195 = FACE_BOUND('',#47196,.F.); -#47196 = EDGE_LOOP('',(#47197,#47227,#47255,#47283,#47311,#47338,#47366, - #47386,#47409,#47436,#47457,#47479,#47502,#47529,#47557,#47585, - #47613,#47641)); -#47197 = ORIENTED_EDGE('',*,*,#47198,.T.); -#47198 = EDGE_CURVE('',#47199,#47201,#47203,.T.); -#47199 = VERTEX_POINT('',#47200); -#47200 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); -#47201 = VERTEX_POINT('',#47202); -#47202 = CARTESIAN_POINT('',(-1.21,0.925,-1.35)); -#47203 = SURFACE_CURVE('',#47204,(#47208,#47215),.PCURVE_S1.); -#47204 = LINE('',#47205,#47206); -#47205 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); -#47206 = VECTOR('',#47207,1.); -#47207 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47208 = PCURVE('',#47059,#47209); -#47209 = DEFINITIONAL_REPRESENTATION('',(#47210),#47214); -#47210 = LINE('',#47211,#47212); -#47211 = CARTESIAN_POINT('',(1.99,0.E+000)); -#47212 = VECTOR('',#47213,1.); -#47213 = DIRECTION('',(0.E+000,1.)); -#47214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47215 = PCURVE('',#47216,#47221); -#47216 = PLANE('',#47217); -#47217 = AXIS2_PLACEMENT_3D('',#47218,#47219,#47220); -#47218 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); -#47219 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47220 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47221 = DEFINITIONAL_REPRESENTATION('',(#47222),#47226); -#47222 = LINE('',#47223,#47224); -#47223 = CARTESIAN_POINT('',(1.,-0.3)); -#47224 = VECTOR('',#47225,1.); -#47225 = DIRECTION('',(-1.,0.E+000)); -#47226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47227 = ORIENTED_EDGE('',*,*,#47228,.F.); -#47228 = EDGE_CURVE('',#47229,#47201,#47231,.T.); -#47229 = VERTEX_POINT('',#47230); -#47230 = CARTESIAN_POINT('',(-2.37,0.925,-1.35)); -#47231 = SURFACE_CURVE('',#47232,(#47236,#47243),.PCURVE_S1.); -#47232 = LINE('',#47233,#47234); -#47233 = CARTESIAN_POINT('',(-2.37,0.925,-1.35)); -#47234 = VECTOR('',#47235,1.); -#47235 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47236 = PCURVE('',#47059,#47237); -#47237 = DEFINITIONAL_REPRESENTATION('',(#47238),#47242); -#47238 = LINE('',#47239,#47240); -#47239 = CARTESIAN_POINT('',(0.83,1.)); -#47240 = VECTOR('',#47241,1.); -#47241 = DIRECTION('',(1.,0.E+000)); -#47242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47243 = PCURVE('',#47244,#47249); -#47244 = PLANE('',#47245); -#47245 = AXIS2_PLACEMENT_3D('',#47246,#47247,#47248); -#47246 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); -#47247 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47248 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47249 = DEFINITIONAL_REPRESENTATION('',(#47250),#47254); -#47250 = LINE('',#47251,#47252); -#47251 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47252 = VECTOR('',#47253,1.); -#47253 = DIRECTION('',(1.,0.E+000)); -#47254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47255 = ORIENTED_EDGE('',*,*,#47256,.F.); -#47256 = EDGE_CURVE('',#47257,#47229,#47259,.T.); -#47257 = VERTEX_POINT('',#47258); -#47258 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); -#47259 = SURFACE_CURVE('',#47260,(#47264,#47271),.PCURVE_S1.); -#47260 = LINE('',#47261,#47262); -#47261 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); -#47262 = VECTOR('',#47263,1.); -#47263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47264 = PCURVE('',#47059,#47265); -#47265 = DEFINITIONAL_REPRESENTATION('',(#47266),#47270); -#47266 = LINE('',#47267,#47268); -#47267 = CARTESIAN_POINT('',(0.83,0.7)); -#47268 = VECTOR('',#47269,1.); -#47269 = DIRECTION('',(0.E+000,1.)); -#47270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47271 = PCURVE('',#47272,#47277); -#47272 = PLANE('',#47273); -#47273 = AXIS2_PLACEMENT_3D('',#47274,#47275,#47276); -#47274 = CARTESIAN_POINT('',(-2.37,1.225,-2.35)); -#47275 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47276 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47277 = DEFINITIONAL_REPRESENTATION('',(#47278),#47282); -#47278 = LINE('',#47279,#47280); -#47279 = CARTESIAN_POINT('',(0.7,-0.3)); -#47280 = VECTOR('',#47281,1.); -#47281 = DIRECTION('',(1.,0.E+000)); -#47282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47283 = ORIENTED_EDGE('',*,*,#47284,.F.); -#47284 = EDGE_CURVE('',#47285,#47257,#47287,.T.); -#47285 = VERTEX_POINT('',#47286); -#47286 = CARTESIAN_POINT('',(-2.32,0.925,-1.65)); -#47287 = SURFACE_CURVE('',#47288,(#47292,#47299),.PCURVE_S1.); -#47288 = LINE('',#47289,#47290); -#47289 = CARTESIAN_POINT('',(-2.32,0.925,-1.65)); -#47290 = VECTOR('',#47291,1.); -#47291 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47292 = PCURVE('',#47059,#47293); -#47293 = DEFINITIONAL_REPRESENTATION('',(#47294),#47298); -#47294 = LINE('',#47295,#47296); -#47295 = CARTESIAN_POINT('',(0.88,0.7)); -#47296 = VECTOR('',#47297,1.); -#47297 = DIRECTION('',(-1.,0.E+000)); -#47298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47299 = PCURVE('',#47300,#47305); -#47300 = PLANE('',#47301); -#47301 = AXIS2_PLACEMENT_3D('',#47302,#47303,#47304); -#47302 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.65)); -#47303 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47304 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47305 = DEFINITIONAL_REPRESENTATION('',(#47306),#47310); -#47306 = LINE('',#47307,#47308); -#47307 = CARTESIAN_POINT('',(2.32,0.925)); -#47308 = VECTOR('',#47309,1.); -#47309 = DIRECTION('',(1.,0.E+000)); -#47310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47311 = ORIENTED_EDGE('',*,*,#47312,.F.); -#47312 = EDGE_CURVE('',#47313,#47285,#47315,.T.); -#47313 = VERTEX_POINT('',#47314); -#47314 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); -#47315 = SURFACE_CURVE('',#47316,(#47320,#47327),.PCURVE_S1.); -#47316 = LINE('',#47317,#47318); -#47317 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); -#47318 = VECTOR('',#47319,1.); -#47319 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47320 = PCURVE('',#47059,#47321); -#47321 = DEFINITIONAL_REPRESENTATION('',(#47322),#47326); -#47322 = LINE('',#47323,#47324); -#47323 = CARTESIAN_POINT('',(0.88,0.E+000)); -#47324 = VECTOR('',#47325,1.); -#47325 = DIRECTION('',(0.E+000,1.)); -#47326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47327 = PCURVE('',#47328,#47333); -#47328 = CYLINDRICAL_SURFACE('',#47329,0.1); -#47329 = AXIS2_PLACEMENT_3D('',#47330,#47331,#47332); -#47330 = CARTESIAN_POINT('',(-2.32,0.825,-2.35)); -#47331 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47332 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47333 = DEFINITIONAL_REPRESENTATION('',(#47334),#47337); -#47334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47335,#47336),.UNSPECIFIED., +#49529 = PCURVE('',#49451,#49530); +#49530 = DEFINITIONAL_REPRESENTATION('',(#49531),#49535); +#49531 = LINE('',#49532,#49533); +#49532 = CARTESIAN_POINT('',(2.79,0.6)); +#49533 = VECTOR('',#49534,1.); +#49534 = DIRECTION('',(1.,0.E+000)); +#49535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49536 = ORIENTED_EDGE('',*,*,#49405,.F.); +#49537 = ORIENTED_EDGE('',*,*,#49538,.F.); +#49538 = EDGE_CURVE('',#49539,#49406,#49541,.T.); +#49539 = VERTEX_POINT('',#49540); +#49540 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); +#49541 = SURFACE_CURVE('',#49542,(#49546,#49553),.PCURVE_S1.); +#49542 = LINE('',#49543,#49544); +#49543 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); +#49544 = VECTOR('',#49545,1.); +#49545 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49546 = PCURVE('',#49423,#49547); +#49547 = DEFINITIONAL_REPRESENTATION('',(#49548),#49552); +#49548 = LINE('',#49549,#49550); +#49549 = CARTESIAN_POINT('',(0.195,0.82)); +#49550 = VECTOR('',#49551,1.); +#49551 = DIRECTION('',(0.E+000,-1.)); +#49552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49553 = PCURVE('',#45792,#49554); +#49554 = DEFINITIONAL_REPRESENTATION('',(#49555),#49559); +#49555 = LINE('',#49556,#49557); +#49556 = CARTESIAN_POINT('',(2.685,0.6)); +#49557 = VECTOR('',#49558,1.); +#49558 = DIRECTION('',(1.,0.E+000)); +#49559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49560 = ORIENTED_EDGE('',*,*,#49561,.T.); +#49561 = EDGE_CURVE('',#49539,#49515,#49562,.T.); +#49562 = SURFACE_CURVE('',#49563,(#49567,#49574),.PCURVE_S1.); +#49563 = LINE('',#49564,#49565); +#49564 = CARTESIAN_POINT('',(0.41,0.92,-1.75)); +#49565 = VECTOR('',#49566,1.); +#49566 = DIRECTION('',(0.E+000,1.,0.E+000)); +#49567 = PCURVE('',#49423,#49568); +#49568 = DEFINITIONAL_REPRESENTATION('',(#49569),#49573); +#49569 = LINE('',#49570,#49571); +#49570 = CARTESIAN_POINT('',(0.195,0.82)); +#49571 = VECTOR('',#49572,1.); +#49572 = DIRECTION('',(1.,0.E+000)); +#49573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49574 = PCURVE('',#49575,#49580); +#49575 = PLANE('',#49576); +#49576 = AXIS2_PLACEMENT_3D('',#49577,#49578,#49579); +#49577 = CARTESIAN_POINT('',(0.41,0.E+000,0.E+000)); +#49578 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49579 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49580 = DEFINITIONAL_REPRESENTATION('',(#49581),#49585); +#49581 = LINE('',#49582,#49583); +#49582 = CARTESIAN_POINT('',(1.75,0.92)); +#49583 = VECTOR('',#49584,1.); +#49584 = DIRECTION('',(0.E+000,1.)); +#49585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49586 = ADVANCED_FACE('',(#49587,#50059,#50404,#50749),#49451,.T.); +#49587 = FACE_BOUND('',#49588,.F.); +#49588 = EDGE_LOOP('',(#49589,#49619,#49647,#49675,#49703,#49730,#49758, + #49778,#49801,#49828,#49849,#49871,#49894,#49921,#49949,#49977, + #50005,#50033)); +#49589 = ORIENTED_EDGE('',*,*,#49590,.T.); +#49590 = EDGE_CURVE('',#49591,#49593,#49595,.T.); +#49591 = VERTEX_POINT('',#49592); +#49592 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); +#49593 = VERTEX_POINT('',#49594); +#49594 = CARTESIAN_POINT('',(-1.21,0.925,-1.35)); +#49595 = SURFACE_CURVE('',#49596,(#49600,#49607),.PCURVE_S1.); +#49596 = LINE('',#49597,#49598); +#49597 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); +#49598 = VECTOR('',#49599,1.); +#49599 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49600 = PCURVE('',#49451,#49601); +#49601 = DEFINITIONAL_REPRESENTATION('',(#49602),#49606); +#49602 = LINE('',#49603,#49604); +#49603 = CARTESIAN_POINT('',(1.99,0.E+000)); +#49604 = VECTOR('',#49605,1.); +#49605 = DIRECTION('',(0.E+000,1.)); +#49606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49607 = PCURVE('',#49608,#49613); +#49608 = PLANE('',#49609); +#49609 = AXIS2_PLACEMENT_3D('',#49610,#49611,#49612); +#49610 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); +#49611 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49612 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49613 = DEFINITIONAL_REPRESENTATION('',(#49614),#49618); +#49614 = LINE('',#49615,#49616); +#49615 = CARTESIAN_POINT('',(1.,-0.3)); +#49616 = VECTOR('',#49617,1.); +#49617 = DIRECTION('',(-1.,0.E+000)); +#49618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49619 = ORIENTED_EDGE('',*,*,#49620,.F.); +#49620 = EDGE_CURVE('',#49621,#49593,#49623,.T.); +#49621 = VERTEX_POINT('',#49622); +#49622 = CARTESIAN_POINT('',(-2.37,0.925,-1.35)); +#49623 = SURFACE_CURVE('',#49624,(#49628,#49635),.PCURVE_S1.); +#49624 = LINE('',#49625,#49626); +#49625 = CARTESIAN_POINT('',(-2.37,0.925,-1.35)); +#49626 = VECTOR('',#49627,1.); +#49627 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49628 = PCURVE('',#49451,#49629); +#49629 = DEFINITIONAL_REPRESENTATION('',(#49630),#49634); +#49630 = LINE('',#49631,#49632); +#49631 = CARTESIAN_POINT('',(0.83,1.)); +#49632 = VECTOR('',#49633,1.); +#49633 = DIRECTION('',(1.,0.E+000)); +#49634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49635 = PCURVE('',#49636,#49641); +#49636 = PLANE('',#49637); +#49637 = AXIS2_PLACEMENT_3D('',#49638,#49639,#49640); +#49638 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); +#49639 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49640 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49641 = DEFINITIONAL_REPRESENTATION('',(#49642),#49646); +#49642 = LINE('',#49643,#49644); +#49643 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#49644 = VECTOR('',#49645,1.); +#49645 = DIRECTION('',(1.,0.E+000)); +#49646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49647 = ORIENTED_EDGE('',*,*,#49648,.F.); +#49648 = EDGE_CURVE('',#49649,#49621,#49651,.T.); +#49649 = VERTEX_POINT('',#49650); +#49650 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); +#49651 = SURFACE_CURVE('',#49652,(#49656,#49663),.PCURVE_S1.); +#49652 = LINE('',#49653,#49654); +#49653 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); +#49654 = VECTOR('',#49655,1.); +#49655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49656 = PCURVE('',#49451,#49657); +#49657 = DEFINITIONAL_REPRESENTATION('',(#49658),#49662); +#49658 = LINE('',#49659,#49660); +#49659 = CARTESIAN_POINT('',(0.83,0.7)); +#49660 = VECTOR('',#49661,1.); +#49661 = DIRECTION('',(0.E+000,1.)); +#49662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49663 = PCURVE('',#49664,#49669); +#49664 = PLANE('',#49665); +#49665 = AXIS2_PLACEMENT_3D('',#49666,#49667,#49668); +#49666 = CARTESIAN_POINT('',(-2.37,1.225,-2.35)); +#49667 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49668 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49669 = DEFINITIONAL_REPRESENTATION('',(#49670),#49674); +#49670 = LINE('',#49671,#49672); +#49671 = CARTESIAN_POINT('',(0.7,-0.3)); +#49672 = VECTOR('',#49673,1.); +#49673 = DIRECTION('',(1.,0.E+000)); +#49674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49675 = ORIENTED_EDGE('',*,*,#49676,.F.); +#49676 = EDGE_CURVE('',#49677,#49649,#49679,.T.); +#49677 = VERTEX_POINT('',#49678); +#49678 = CARTESIAN_POINT('',(-2.32,0.925,-1.65)); +#49679 = SURFACE_CURVE('',#49680,(#49684,#49691),.PCURVE_S1.); +#49680 = LINE('',#49681,#49682); +#49681 = CARTESIAN_POINT('',(-2.32,0.925,-1.65)); +#49682 = VECTOR('',#49683,1.); +#49683 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49684 = PCURVE('',#49451,#49685); +#49685 = DEFINITIONAL_REPRESENTATION('',(#49686),#49690); +#49686 = LINE('',#49687,#49688); +#49687 = CARTESIAN_POINT('',(0.88,0.7)); +#49688 = VECTOR('',#49689,1.); +#49689 = DIRECTION('',(-1.,0.E+000)); +#49690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49691 = PCURVE('',#49692,#49697); +#49692 = PLANE('',#49693); +#49693 = AXIS2_PLACEMENT_3D('',#49694,#49695,#49696); +#49694 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.65)); +#49695 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49696 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49697 = DEFINITIONAL_REPRESENTATION('',(#49698),#49702); +#49698 = LINE('',#49699,#49700); +#49699 = CARTESIAN_POINT('',(2.32,0.925)); +#49700 = VECTOR('',#49701,1.); +#49701 = DIRECTION('',(1.,0.E+000)); +#49702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49703 = ORIENTED_EDGE('',*,*,#49704,.F.); +#49704 = EDGE_CURVE('',#49705,#49677,#49707,.T.); +#49705 = VERTEX_POINT('',#49706); +#49706 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); +#49707 = SURFACE_CURVE('',#49708,(#49712,#49719),.PCURVE_S1.); +#49708 = LINE('',#49709,#49710); +#49709 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); +#49710 = VECTOR('',#49711,1.); +#49711 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49712 = PCURVE('',#49451,#49713); +#49713 = DEFINITIONAL_REPRESENTATION('',(#49714),#49718); +#49714 = LINE('',#49715,#49716); +#49715 = CARTESIAN_POINT('',(0.88,0.E+000)); +#49716 = VECTOR('',#49717,1.); +#49717 = DIRECTION('',(0.E+000,1.)); +#49718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49719 = PCURVE('',#49720,#49725); +#49720 = CYLINDRICAL_SURFACE('',#49721,0.1); +#49721 = AXIS2_PLACEMENT_3D('',#49722,#49723,#49724); +#49722 = CARTESIAN_POINT('',(-2.32,0.825,-2.35)); +#49723 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49724 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49725 = DEFINITIONAL_REPRESENTATION('',(#49726),#49729); +#49726 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49727,#49728),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#47335 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#47336 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#47337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47338 = ORIENTED_EDGE('',*,*,#47339,.T.); -#47339 = EDGE_CURVE('',#47313,#47340,#47342,.T.); -#47340 = VERTEX_POINT('',#47341); -#47341 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); -#47342 = SURFACE_CURVE('',#47343,(#47347,#47354),.PCURVE_S1.); -#47343 = LINE('',#47344,#47345); -#47344 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); -#47345 = VECTOR('',#47346,1.); -#47346 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47347 = PCURVE('',#47059,#47348); -#47348 = DEFINITIONAL_REPRESENTATION('',(#47349),#47353); -#47349 = LINE('',#47350,#47351); -#47350 = CARTESIAN_POINT('',(0.88,0.E+000)); -#47351 = VECTOR('',#47352,1.); -#47352 = DIRECTION('',(-1.,0.E+000)); -#47353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47354 = PCURVE('',#47355,#47360); -#47355 = PLANE('',#47356); -#47356 = AXIS2_PLACEMENT_3D('',#47357,#47358,#47359); -#47357 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#47358 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47359 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47360 = DEFINITIONAL_REPRESENTATION('',(#47361),#47365); -#47361 = LINE('',#47362,#47363); -#47362 = CARTESIAN_POINT('',(-2.32,0.925)); -#47363 = VECTOR('',#47364,1.); -#47364 = DIRECTION('',(-1.,0.E+000)); -#47365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47366 = ORIENTED_EDGE('',*,*,#47367,.T.); -#47367 = EDGE_CURVE('',#47340,#38423,#47368,.T.); -#47368 = SURFACE_CURVE('',#47369,(#47373,#47380),.PCURVE_S1.); -#47369 = LINE('',#47370,#47371); -#47370 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); -#47371 = VECTOR('',#47372,1.); -#47372 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47373 = PCURVE('',#47059,#47374); -#47374 = DEFINITIONAL_REPRESENTATION('',(#47375),#47379); -#47375 = LINE('',#47376,#47377); -#47376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#47377 = VECTOR('',#47378,1.); -#47378 = DIRECTION('',(0.E+000,1.)); -#47379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47380 = PCURVE('',#38471,#47381); -#47381 = DEFINITIONAL_REPRESENTATION('',(#47382),#47385); -#47382 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47383,#47384),.UNSPECIFIED., +#49727 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49728 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#49729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49730 = ORIENTED_EDGE('',*,*,#49731,.T.); +#49731 = EDGE_CURVE('',#49705,#49732,#49734,.T.); +#49732 = VERTEX_POINT('',#49733); +#49733 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); +#49734 = SURFACE_CURVE('',#49735,(#49739,#49746),.PCURVE_S1.); +#49735 = LINE('',#49736,#49737); +#49736 = CARTESIAN_POINT('',(-2.32,0.925,-2.35)); +#49737 = VECTOR('',#49738,1.); +#49738 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49739 = PCURVE('',#49451,#49740); +#49740 = DEFINITIONAL_REPRESENTATION('',(#49741),#49745); +#49741 = LINE('',#49742,#49743); +#49742 = CARTESIAN_POINT('',(0.88,0.E+000)); +#49743 = VECTOR('',#49744,1.); +#49744 = DIRECTION('',(-1.,0.E+000)); +#49745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49746 = PCURVE('',#49747,#49752); +#49747 = PLANE('',#49748); +#49748 = AXIS2_PLACEMENT_3D('',#49749,#49750,#49751); +#49749 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#49750 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49751 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49752 = DEFINITIONAL_REPRESENTATION('',(#49753),#49757); +#49753 = LINE('',#49754,#49755); +#49754 = CARTESIAN_POINT('',(-2.32,0.925)); +#49755 = VECTOR('',#49756,1.); +#49756 = DIRECTION('',(-1.,0.E+000)); +#49757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49758 = ORIENTED_EDGE('',*,*,#49759,.T.); +#49759 = EDGE_CURVE('',#49732,#40815,#49760,.T.); +#49760 = SURFACE_CURVE('',#49761,(#49765,#49772),.PCURVE_S1.); +#49761 = LINE('',#49762,#49763); +#49762 = CARTESIAN_POINT('',(-3.2,0.925,-2.35)); +#49763 = VECTOR('',#49764,1.); +#49764 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49765 = PCURVE('',#49451,#49766); +#49766 = DEFINITIONAL_REPRESENTATION('',(#49767),#49771); +#49767 = LINE('',#49768,#49769); +#49768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#49769 = VECTOR('',#49770,1.); +#49770 = DIRECTION('',(0.E+000,1.)); +#49771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49772 = PCURVE('',#40863,#49773); +#49773 = DEFINITIONAL_REPRESENTATION('',(#49774),#49777); +#49774 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49775,#49776),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#47383 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#47384 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#47385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47386 = ORIENTED_EDGE('',*,*,#47387,.T.); -#47387 = EDGE_CURVE('',#38423,#47388,#47390,.T.); -#47388 = VERTEX_POINT('',#47389); -#47389 = CARTESIAN_POINT('',(-3.2,0.925,2.354813742174)); -#47390 = SURFACE_CURVE('',#47391,(#47395,#47402),.PCURVE_S1.); -#47391 = LINE('',#47392,#47393); -#47392 = CARTESIAN_POINT('',(-3.2,0.925,2.35)); -#47393 = VECTOR('',#47394,1.); -#47394 = DIRECTION('',(0.E+000,-2.306361629794E-014,1.)); -#47395 = PCURVE('',#47059,#47396); -#47396 = DEFINITIONAL_REPRESENTATION('',(#47397),#47401); -#47397 = LINE('',#47398,#47399); -#47398 = CARTESIAN_POINT('',(0.E+000,4.7)); -#47399 = VECTOR('',#47400,1.); -#47400 = DIRECTION('',(0.E+000,1.)); -#47401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47402 = PCURVE('',#38438,#47403); -#47403 = DEFINITIONAL_REPRESENTATION('',(#47404),#47408); -#47404 = LINE('',#47405,#47406); -#47405 = CARTESIAN_POINT('',(2.35,0.925)); -#47406 = VECTOR('',#47407,1.); -#47407 = DIRECTION('',(1.,-2.306361629794E-014)); -#47408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47409 = ORIENTED_EDGE('',*,*,#47410,.F.); -#47410 = EDGE_CURVE('',#47411,#47388,#47413,.T.); -#47411 = VERTEX_POINT('',#47412); -#47412 = CARTESIAN_POINT('',(3.2,0.925,2.354813742174)); -#47413 = SURFACE_CURVE('',#47414,(#47418,#47425),.PCURVE_S1.); -#47414 = LINE('',#47415,#47416); -#47415 = CARTESIAN_POINT('',(3.2,0.925,2.354813742174)); -#47416 = VECTOR('',#47417,1.); -#47417 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47418 = PCURVE('',#47059,#47419); -#47419 = DEFINITIONAL_REPRESENTATION('',(#47420),#47424); -#47420 = LINE('',#47421,#47422); -#47421 = CARTESIAN_POINT('',(6.4,4.704813742174)); -#47422 = VECTOR('',#47423,1.); -#47423 = DIRECTION('',(-1.,0.E+000)); -#47424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47425 = PCURVE('',#47426,#47431); -#47426 = CYLINDRICAL_SURFACE('',#47427,0.29); -#47427 = AXIS2_PLACEMENT_3D('',#47428,#47429,#47430); -#47428 = CARTESIAN_POINT('',(3.2,1.215,2.354813742174)); -#47429 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47430 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47431 = DEFINITIONAL_REPRESENTATION('',(#47432),#47435); -#47432 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47433,#47434),.UNSPECIFIED., +#49775 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49776 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#49777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49778 = ORIENTED_EDGE('',*,*,#49779,.T.); +#49779 = EDGE_CURVE('',#40815,#49780,#49782,.T.); +#49780 = VERTEX_POINT('',#49781); +#49781 = CARTESIAN_POINT('',(-3.2,0.925,2.354813742174)); +#49782 = SURFACE_CURVE('',#49783,(#49787,#49794),.PCURVE_S1.); +#49783 = LINE('',#49784,#49785); +#49784 = CARTESIAN_POINT('',(-3.2,0.925,2.35)); +#49785 = VECTOR('',#49786,1.); +#49786 = DIRECTION('',(0.E+000,-2.306361629794E-014,1.)); +#49787 = PCURVE('',#49451,#49788); +#49788 = DEFINITIONAL_REPRESENTATION('',(#49789),#49793); +#49789 = LINE('',#49790,#49791); +#49790 = CARTESIAN_POINT('',(0.E+000,4.7)); +#49791 = VECTOR('',#49792,1.); +#49792 = DIRECTION('',(0.E+000,1.)); +#49793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49794 = PCURVE('',#40830,#49795); +#49795 = DEFINITIONAL_REPRESENTATION('',(#49796),#49800); +#49796 = LINE('',#49797,#49798); +#49797 = CARTESIAN_POINT('',(2.35,0.925)); +#49798 = VECTOR('',#49799,1.); +#49799 = DIRECTION('',(1.,-2.306361629794E-014)); +#49800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49801 = ORIENTED_EDGE('',*,*,#49802,.F.); +#49802 = EDGE_CURVE('',#49803,#49780,#49805,.T.); +#49803 = VERTEX_POINT('',#49804); +#49804 = CARTESIAN_POINT('',(3.2,0.925,2.354813742174)); +#49805 = SURFACE_CURVE('',#49806,(#49810,#49817),.PCURVE_S1.); +#49806 = LINE('',#49807,#49808); +#49807 = CARTESIAN_POINT('',(3.2,0.925,2.354813742174)); +#49808 = VECTOR('',#49809,1.); +#49809 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49810 = PCURVE('',#49451,#49811); +#49811 = DEFINITIONAL_REPRESENTATION('',(#49812),#49816); +#49812 = LINE('',#49813,#49814); +#49813 = CARTESIAN_POINT('',(6.4,4.704813742174)); +#49814 = VECTOR('',#49815,1.); +#49815 = DIRECTION('',(-1.,0.E+000)); +#49816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49817 = PCURVE('',#49818,#49823); +#49818 = CYLINDRICAL_SURFACE('',#49819,0.29); +#49819 = AXIS2_PLACEMENT_3D('',#49820,#49821,#49822); +#49820 = CARTESIAN_POINT('',(3.2,1.215,2.354813742174)); +#49821 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49822 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49823 = DEFINITIONAL_REPRESENTATION('',(#49824),#49827); +#49824 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49825,#49826),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.4),.PIECEWISE_BEZIER_KNOTS.); -#47433 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#47434 = CARTESIAN_POINT('',(4.712388980385,6.4)); -#47435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47436 = ORIENTED_EDGE('',*,*,#47437,.F.); -#47437 = EDGE_CURVE('',#38565,#47411,#47438,.T.); -#47438 = SURFACE_CURVE('',#47439,(#47443,#47450),.PCURVE_S1.); -#47439 = LINE('',#47440,#47441); -#47440 = CARTESIAN_POINT('',(3.2,0.925,2.35)); -#47441 = VECTOR('',#47442,1.); -#47442 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47443 = PCURVE('',#47059,#47444); -#47444 = DEFINITIONAL_REPRESENTATION('',(#47445),#47449); -#47445 = LINE('',#47446,#47447); -#47446 = CARTESIAN_POINT('',(6.4,4.7)); -#47447 = VECTOR('',#47448,1.); -#47448 = DIRECTION('',(0.E+000,1.)); -#47449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47450 = PCURVE('',#38612,#47451); -#47451 = DEFINITIONAL_REPRESENTATION('',(#47452),#47456); -#47452 = LINE('',#47453,#47454); -#47453 = CARTESIAN_POINT('',(2.35,0.925)); -#47454 = VECTOR('',#47455,1.); -#47455 = DIRECTION('',(1.,0.E+000)); -#47456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47457 = ORIENTED_EDGE('',*,*,#47458,.F.); -#47458 = EDGE_CURVE('',#47459,#38565,#47461,.T.); -#47459 = VERTEX_POINT('',#47460); -#47460 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); -#47461 = SURFACE_CURVE('',#47462,(#47466,#47473),.PCURVE_S1.); -#47462 = LINE('',#47463,#47464); -#47463 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); -#47464 = VECTOR('',#47465,1.); -#47465 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47466 = PCURVE('',#47059,#47467); -#47467 = DEFINITIONAL_REPRESENTATION('',(#47468),#47472); -#47468 = LINE('',#47469,#47470); -#47469 = CARTESIAN_POINT('',(6.4,0.E+000)); -#47470 = VECTOR('',#47471,1.); -#47471 = DIRECTION('',(0.E+000,1.)); -#47472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47473 = PCURVE('',#38585,#47474); -#47474 = DEFINITIONAL_REPRESENTATION('',(#47475),#47478); -#47475 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47476,#47477),.UNSPECIFIED., +#49825 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#49826 = CARTESIAN_POINT('',(4.712388980385,6.4)); +#49827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49828 = ORIENTED_EDGE('',*,*,#49829,.F.); +#49829 = EDGE_CURVE('',#40957,#49803,#49830,.T.); +#49830 = SURFACE_CURVE('',#49831,(#49835,#49842),.PCURVE_S1.); +#49831 = LINE('',#49832,#49833); +#49832 = CARTESIAN_POINT('',(3.2,0.925,2.35)); +#49833 = VECTOR('',#49834,1.); +#49834 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49835 = PCURVE('',#49451,#49836); +#49836 = DEFINITIONAL_REPRESENTATION('',(#49837),#49841); +#49837 = LINE('',#49838,#49839); +#49838 = CARTESIAN_POINT('',(6.4,4.7)); +#49839 = VECTOR('',#49840,1.); +#49840 = DIRECTION('',(0.E+000,1.)); +#49841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49842 = PCURVE('',#41004,#49843); +#49843 = DEFINITIONAL_REPRESENTATION('',(#49844),#49848); +#49844 = LINE('',#49845,#49846); +#49845 = CARTESIAN_POINT('',(2.35,0.925)); +#49846 = VECTOR('',#49847,1.); +#49847 = DIRECTION('',(1.,0.E+000)); +#49848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49849 = ORIENTED_EDGE('',*,*,#49850,.F.); +#49850 = EDGE_CURVE('',#49851,#40957,#49853,.T.); +#49851 = VERTEX_POINT('',#49852); +#49852 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); +#49853 = SURFACE_CURVE('',#49854,(#49858,#49865),.PCURVE_S1.); +#49854 = LINE('',#49855,#49856); +#49855 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); +#49856 = VECTOR('',#49857,1.); +#49857 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49858 = PCURVE('',#49451,#49859); +#49859 = DEFINITIONAL_REPRESENTATION('',(#49860),#49864); +#49860 = LINE('',#49861,#49862); +#49861 = CARTESIAN_POINT('',(6.4,0.E+000)); +#49862 = VECTOR('',#49863,1.); +#49863 = DIRECTION('',(0.E+000,1.)); +#49864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49865 = PCURVE('',#40977,#49866); +#49866 = DEFINITIONAL_REPRESENTATION('',(#49867),#49870); +#49867 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49868,#49869),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#47476 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#47477 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#47478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47479 = ORIENTED_EDGE('',*,*,#47480,.T.); -#47480 = EDGE_CURVE('',#47459,#47481,#47483,.T.); -#47481 = VERTEX_POINT('',#47482); -#47482 = CARTESIAN_POINT('',(2.32,0.925,-2.35)); -#47483 = SURFACE_CURVE('',#47484,(#47488,#47495),.PCURVE_S1.); -#47484 = LINE('',#47485,#47486); -#47485 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); -#47486 = VECTOR('',#47487,1.); -#47487 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47488 = PCURVE('',#47059,#47489); -#47489 = DEFINITIONAL_REPRESENTATION('',(#47490),#47494); -#47490 = LINE('',#47491,#47492); -#47491 = CARTESIAN_POINT('',(6.4,0.E+000)); -#47492 = VECTOR('',#47493,1.); -#47493 = DIRECTION('',(-1.,0.E+000)); -#47494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47495 = PCURVE('',#39747,#47496); -#47496 = DEFINITIONAL_REPRESENTATION('',(#47497),#47501); -#47497 = LINE('',#47498,#47499); -#47498 = CARTESIAN_POINT('',(3.2,0.925)); -#47499 = VECTOR('',#47500,1.); -#47500 = DIRECTION('',(-1.,0.E+000)); -#47501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47502 = ORIENTED_EDGE('',*,*,#47503,.T.); -#47503 = EDGE_CURVE('',#47481,#47504,#47506,.T.); -#47504 = VERTEX_POINT('',#47505); -#47505 = CARTESIAN_POINT('',(2.32,0.925,-1.65)); -#47506 = SURFACE_CURVE('',#47507,(#47511,#47518),.PCURVE_S1.); -#47507 = LINE('',#47508,#47509); -#47508 = CARTESIAN_POINT('',(2.32,0.925,-2.35)); -#47509 = VECTOR('',#47510,1.); -#47510 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47511 = PCURVE('',#47059,#47512); -#47512 = DEFINITIONAL_REPRESENTATION('',(#47513),#47517); -#47513 = LINE('',#47514,#47515); -#47514 = CARTESIAN_POINT('',(5.52,0.E+000)); -#47515 = VECTOR('',#47516,1.); -#47516 = DIRECTION('',(0.E+000,1.)); -#47517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47518 = PCURVE('',#47519,#47524); -#47519 = CYLINDRICAL_SURFACE('',#47520,0.1); -#47520 = AXIS2_PLACEMENT_3D('',#47521,#47522,#47523); -#47521 = CARTESIAN_POINT('',(2.32,0.825,-2.35)); -#47522 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47523 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47524 = DEFINITIONAL_REPRESENTATION('',(#47525),#47528); -#47525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47526,#47527),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#47526 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#47527 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#47528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47529 = ORIENTED_EDGE('',*,*,#47530,.F.); -#47530 = EDGE_CURVE('',#47531,#47504,#47533,.T.); -#47531 = VERTEX_POINT('',#47532); -#47532 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); -#47533 = SURFACE_CURVE('',#47534,(#47538,#47545),.PCURVE_S1.); -#47534 = LINE('',#47535,#47536); -#47535 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); -#47536 = VECTOR('',#47537,1.); -#47537 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47538 = PCURVE('',#47059,#47539); -#47539 = DEFINITIONAL_REPRESENTATION('',(#47540),#47544); -#47540 = LINE('',#47541,#47542); -#47541 = CARTESIAN_POINT('',(5.57,0.7)); -#47542 = VECTOR('',#47543,1.); -#47543 = DIRECTION('',(-1.,0.E+000)); -#47544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47545 = PCURVE('',#47546,#47551); -#47546 = PLANE('',#47547); -#47547 = AXIS2_PLACEMENT_3D('',#47548,#47549,#47550); -#47548 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.65)); -#47549 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47550 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47551 = DEFINITIONAL_REPRESENTATION('',(#47552),#47556); -#47552 = LINE('',#47553,#47554); -#47553 = CARTESIAN_POINT('',(-2.37,0.925)); -#47554 = VECTOR('',#47555,1.); -#47555 = DIRECTION('',(1.,0.E+000)); -#47556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47557 = ORIENTED_EDGE('',*,*,#47558,.T.); -#47558 = EDGE_CURVE('',#47531,#47559,#47561,.T.); -#47559 = VERTEX_POINT('',#47560); -#47560 = CARTESIAN_POINT('',(2.37,0.925,-1.35)); -#47561 = SURFACE_CURVE('',#47562,(#47566,#47573),.PCURVE_S1.); -#47562 = LINE('',#47563,#47564); -#47563 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); -#47564 = VECTOR('',#47565,1.); -#47565 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47566 = PCURVE('',#47059,#47567); -#47567 = DEFINITIONAL_REPRESENTATION('',(#47568),#47572); -#47568 = LINE('',#47569,#47570); -#47569 = CARTESIAN_POINT('',(5.57,0.7)); -#47570 = VECTOR('',#47571,1.); -#47571 = DIRECTION('',(0.E+000,1.)); -#47572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47573 = PCURVE('',#47574,#47579); -#47574 = PLANE('',#47575); -#47575 = AXIS2_PLACEMENT_3D('',#47576,#47577,#47578); -#47576 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); -#47577 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47578 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47579 = DEFINITIONAL_REPRESENTATION('',(#47580),#47584); -#47580 = LINE('',#47581,#47582); -#47581 = CARTESIAN_POINT('',(0.3,-0.3)); -#47582 = VECTOR('',#47583,1.); -#47583 = DIRECTION('',(-1.,0.E+000)); -#47584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47585 = ORIENTED_EDGE('',*,*,#47586,.F.); -#47586 = EDGE_CURVE('',#47587,#47559,#47589,.T.); -#47587 = VERTEX_POINT('',#47588); -#47588 = CARTESIAN_POINT('',(1.21,0.925,-1.35)); -#47589 = SURFACE_CURVE('',#47590,(#47594,#47601),.PCURVE_S1.); -#47590 = LINE('',#47591,#47592); -#47591 = CARTESIAN_POINT('',(1.21,0.925,-1.35)); -#47592 = VECTOR('',#47593,1.); -#47593 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47594 = PCURVE('',#47059,#47595); -#47595 = DEFINITIONAL_REPRESENTATION('',(#47596),#47600); -#47596 = LINE('',#47597,#47598); -#47597 = CARTESIAN_POINT('',(4.41,1.)); -#47598 = VECTOR('',#47599,1.); -#47599 = DIRECTION('',(1.,0.E+000)); -#47600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47601 = PCURVE('',#47602,#47607); -#47602 = PLANE('',#47603); -#47603 = AXIS2_PLACEMENT_3D('',#47604,#47605,#47606); -#47604 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); -#47605 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47606 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47607 = DEFINITIONAL_REPRESENTATION('',(#47608),#47612); -#47608 = LINE('',#47609,#47610); -#47609 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47610 = VECTOR('',#47611,1.); -#47611 = DIRECTION('',(1.,0.E+000)); -#47612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47613 = ORIENTED_EDGE('',*,*,#47614,.F.); -#47614 = EDGE_CURVE('',#47615,#47587,#47617,.T.); -#47615 = VERTEX_POINT('',#47616); -#47616 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); -#47617 = SURFACE_CURVE('',#47618,(#47622,#47629),.PCURVE_S1.); -#47618 = LINE('',#47619,#47620); -#47619 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); -#47620 = VECTOR('',#47621,1.); -#47621 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47622 = PCURVE('',#47059,#47623); -#47623 = DEFINITIONAL_REPRESENTATION('',(#47624),#47628); -#47624 = LINE('',#47625,#47626); -#47625 = CARTESIAN_POINT('',(4.41,0.E+000)); -#47626 = VECTOR('',#47627,1.); -#47627 = DIRECTION('',(0.E+000,1.)); -#47628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47629 = PCURVE('',#47630,#47635); -#47630 = PLANE('',#47631); -#47631 = AXIS2_PLACEMENT_3D('',#47632,#47633,#47634); -#47632 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); -#47633 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47634 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47635 = DEFINITIONAL_REPRESENTATION('',(#47636),#47640); -#47636 = LINE('',#47637,#47638); -#47637 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47638 = VECTOR('',#47639,1.); -#47639 = DIRECTION('',(1.,0.E+000)); -#47640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47641 = ORIENTED_EDGE('',*,*,#47642,.T.); -#47642 = EDGE_CURVE('',#47615,#47199,#47643,.T.); -#47643 = SURFACE_CURVE('',#47644,(#47648,#47655),.PCURVE_S1.); -#47644 = LINE('',#47645,#47646); -#47645 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); -#47646 = VECTOR('',#47647,1.); -#47647 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47648 = PCURVE('',#47059,#47649); -#47649 = DEFINITIONAL_REPRESENTATION('',(#47650),#47654); -#47650 = LINE('',#47651,#47652); -#47651 = CARTESIAN_POINT('',(4.41,0.E+000)); -#47652 = VECTOR('',#47653,1.); -#47653 = DIRECTION('',(-1.,0.E+000)); -#47654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47655 = PCURVE('',#47656,#47661); -#47656 = PLANE('',#47657); -#47657 = AXIS2_PLACEMENT_3D('',#47658,#47659,#47660); -#47658 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#47659 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47660 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47661 = DEFINITIONAL_REPRESENTATION('',(#47662),#47666); -#47662 = LINE('',#47663,#47664); -#47663 = CARTESIAN_POINT('',(-1.21,0.925)); -#47664 = VECTOR('',#47665,1.); -#47665 = DIRECTION('',(1.,0.E+000)); -#47666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47667 = FACE_BOUND('',#47668,.F.); -#47668 = EDGE_LOOP('',(#47669,#47699,#47726,#47754,#47782,#47814,#47842, - #47870,#47898,#47926,#47954,#47986)); -#47669 = ORIENTED_EDGE('',*,*,#47670,.F.); -#47670 = EDGE_CURVE('',#47671,#47673,#47675,.T.); -#47671 = VERTEX_POINT('',#47672); -#47672 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); -#47673 = VERTEX_POINT('',#47674); -#47674 = CARTESIAN_POINT('',(2.725,0.925,1.35)); -#47675 = SURFACE_CURVE('',#47676,(#47680,#47687),.PCURVE_S1.); -#47676 = LINE('',#47677,#47678); -#47677 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); -#47678 = VECTOR('',#47679,1.); -#47679 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47680 = PCURVE('',#47059,#47681); -#47681 = DEFINITIONAL_REPRESENTATION('',(#47682),#47686); -#47682 = LINE('',#47683,#47684); -#47683 = CARTESIAN_POINT('',(5.925,4.102598183049)); -#47684 = VECTOR('',#47685,1.); -#47685 = DIRECTION('',(0.E+000,-1.)); -#47686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47687 = PCURVE('',#47688,#47693); -#47688 = PLANE('',#47689); -#47689 = AXIS2_PLACEMENT_3D('',#47690,#47691,#47692); -#47690 = CARTESIAN_POINT('',(2.725,1.225,1.78)); -#47691 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47692 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47693 = DEFINITIONAL_REPRESENTATION('',(#47694),#47698); -#47694 = LINE('',#47695,#47696); -#47695 = CARTESIAN_POINT('',(2.7401816951E-002,-0.3)); -#47696 = VECTOR('',#47697,1.); -#47697 = DIRECTION('',(1.,0.E+000)); -#47698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47699 = ORIENTED_EDGE('',*,*,#47700,.T.); -#47700 = EDGE_CURVE('',#47671,#47701,#47703,.T.); -#47701 = VERTEX_POINT('',#47702); -#47702 = CARTESIAN_POINT('',(2.025,0.925,1.752598183049)); -#47703 = SURFACE_CURVE('',#47704,(#47708,#47715),.PCURVE_S1.); -#47704 = LINE('',#47705,#47706); -#47705 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); -#47706 = VECTOR('',#47707,1.); -#47707 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47708 = PCURVE('',#47059,#47709); -#47709 = DEFINITIONAL_REPRESENTATION('',(#47710),#47714); -#47710 = LINE('',#47711,#47712); -#47711 = CARTESIAN_POINT('',(5.925,4.102598183049)); -#47712 = VECTOR('',#47713,1.); -#47713 = DIRECTION('',(-1.,0.E+000)); -#47714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47715 = PCURVE('',#47716,#47721); -#47716 = CYLINDRICAL_SURFACE('',#47717,0.3); -#47717 = AXIS2_PLACEMENT_3D('',#47718,#47719,#47720); -#47718 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); -#47719 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47720 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47721 = DEFINITIONAL_REPRESENTATION('',(#47722),#47725); -#47722 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47723,#47724),.UNSPECIFIED., +#49868 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49869 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#49870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49871 = ORIENTED_EDGE('',*,*,#49872,.T.); +#49872 = EDGE_CURVE('',#49851,#49873,#49875,.T.); +#49873 = VERTEX_POINT('',#49874); +#49874 = CARTESIAN_POINT('',(2.32,0.925,-2.35)); +#49875 = SURFACE_CURVE('',#49876,(#49880,#49887),.PCURVE_S1.); +#49876 = LINE('',#49877,#49878); +#49877 = CARTESIAN_POINT('',(3.2,0.925,-2.35)); +#49878 = VECTOR('',#49879,1.); +#49879 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49880 = PCURVE('',#49451,#49881); +#49881 = DEFINITIONAL_REPRESENTATION('',(#49882),#49886); +#49882 = LINE('',#49883,#49884); +#49883 = CARTESIAN_POINT('',(6.4,0.E+000)); +#49884 = VECTOR('',#49885,1.); +#49885 = DIRECTION('',(-1.,0.E+000)); +#49886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49887 = PCURVE('',#42139,#49888); +#49888 = DEFINITIONAL_REPRESENTATION('',(#49889),#49893); +#49889 = LINE('',#49890,#49891); +#49890 = CARTESIAN_POINT('',(3.2,0.925)); +#49891 = VECTOR('',#49892,1.); +#49892 = DIRECTION('',(-1.,0.E+000)); +#49893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49894 = ORIENTED_EDGE('',*,*,#49895,.T.); +#49895 = EDGE_CURVE('',#49873,#49896,#49898,.T.); +#49896 = VERTEX_POINT('',#49897); +#49897 = CARTESIAN_POINT('',(2.32,0.925,-1.65)); +#49898 = SURFACE_CURVE('',#49899,(#49903,#49910),.PCURVE_S1.); +#49899 = LINE('',#49900,#49901); +#49900 = CARTESIAN_POINT('',(2.32,0.925,-2.35)); +#49901 = VECTOR('',#49902,1.); +#49902 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49903 = PCURVE('',#49451,#49904); +#49904 = DEFINITIONAL_REPRESENTATION('',(#49905),#49909); +#49905 = LINE('',#49906,#49907); +#49906 = CARTESIAN_POINT('',(5.52,0.E+000)); +#49907 = VECTOR('',#49908,1.); +#49908 = DIRECTION('',(0.E+000,1.)); +#49909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49910 = PCURVE('',#49911,#49916); +#49911 = CYLINDRICAL_SURFACE('',#49912,0.1); +#49912 = AXIS2_PLACEMENT_3D('',#49913,#49914,#49915); +#49913 = CARTESIAN_POINT('',(2.32,0.825,-2.35)); +#49914 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49915 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49916 = DEFINITIONAL_REPRESENTATION('',(#49917),#49920); +#49917 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49918,#49919),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#47723 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#47724 = CARTESIAN_POINT('',(4.712388980385,0.7)); -#47725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47726 = ORIENTED_EDGE('',*,*,#47727,.F.); -#47727 = EDGE_CURVE('',#47728,#47701,#47730,.T.); -#47728 = VERTEX_POINT('',#47729); -#47729 = CARTESIAN_POINT('',(2.025,0.925,1.35)); -#47730 = SURFACE_CURVE('',#47731,(#47735,#47742),.PCURVE_S1.); -#47731 = LINE('',#47732,#47733); -#47732 = CARTESIAN_POINT('',(2.025,0.925,1.35)); -#47733 = VECTOR('',#47734,1.); -#47734 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47735 = PCURVE('',#47059,#47736); -#47736 = DEFINITIONAL_REPRESENTATION('',(#47737),#47741); -#47737 = LINE('',#47738,#47739); -#47738 = CARTESIAN_POINT('',(5.225,3.7)); -#47739 = VECTOR('',#47740,1.); -#47740 = DIRECTION('',(0.E+000,1.)); -#47741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47742 = PCURVE('',#47743,#47748); -#47743 = PLANE('',#47744); -#47744 = AXIS2_PLACEMENT_3D('',#47745,#47746,#47747); -#47745 = CARTESIAN_POINT('',(2.025,1.225,1.35)); -#47746 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47747 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47748 = DEFINITIONAL_REPRESENTATION('',(#47749),#47753); -#47749 = LINE('',#47750,#47751); -#47750 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47751 = VECTOR('',#47752,1.); -#47752 = DIRECTION('',(1.,0.E+000)); -#47753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47754 = ORIENTED_EDGE('',*,*,#47755,.F.); -#47755 = EDGE_CURVE('',#47756,#47728,#47758,.T.); -#47756 = VERTEX_POINT('',#47757); -#47757 = CARTESIAN_POINT('',(1.9,0.925,1.35)); -#47758 = SURFACE_CURVE('',#47759,(#47763,#47770),.PCURVE_S1.); -#47759 = LINE('',#47760,#47761); -#47760 = CARTESIAN_POINT('',(1.9,0.925,1.35)); -#47761 = VECTOR('',#47762,1.); -#47762 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47763 = PCURVE('',#47059,#47764); -#47764 = DEFINITIONAL_REPRESENTATION('',(#47765),#47769); -#47765 = LINE('',#47766,#47767); -#47766 = CARTESIAN_POINT('',(5.1,3.7)); -#47767 = VECTOR('',#47768,1.); -#47768 = DIRECTION('',(1.,0.E+000)); -#47769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47770 = PCURVE('',#47771,#47776); -#47771 = PLANE('',#47772); -#47772 = AXIS2_PLACEMENT_3D('',#47773,#47774,#47775); -#47773 = CARTESIAN_POINT('',(1.9,1.225,1.35)); -#47774 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47775 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47776 = DEFINITIONAL_REPRESENTATION('',(#47777),#47781); -#47777 = LINE('',#47778,#47779); -#47778 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47779 = VECTOR('',#47780,1.); -#47780 = DIRECTION('',(1.,0.E+000)); -#47781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47782 = ORIENTED_EDGE('',*,*,#47783,.F.); -#47783 = EDGE_CURVE('',#47784,#47756,#47786,.T.); -#47784 = VERTEX_POINT('',#47785); -#47785 = CARTESIAN_POINT('',(1.9,0.925,1.1)); -#47786 = SURFACE_CURVE('',#47787,(#47792,#47803),.PCURVE_S1.); -#47787 = CIRCLE('',#47788,0.125); -#47788 = AXIS2_PLACEMENT_3D('',#47789,#47790,#47791); -#47789 = CARTESIAN_POINT('',(1.9,0.925,1.225)); -#47790 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47791 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47792 = PCURVE('',#47059,#47793); -#47793 = DEFINITIONAL_REPRESENTATION('',(#47794),#47802); -#47794 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#47795,#47796,#47797,#47798 - ,#47799,#47800,#47801),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#47795 = CARTESIAN_POINT('',(5.1,3.45)); -#47796 = CARTESIAN_POINT('',(4.883493649054,3.45)); -#47797 = CARTESIAN_POINT('',(4.991746824527,3.6375)); -#47798 = CARTESIAN_POINT('',(5.1,3.825)); -#47799 = CARTESIAN_POINT('',(5.208253175473,3.6375)); -#47800 = CARTESIAN_POINT('',(5.316506350946,3.45)); -#47801 = CARTESIAN_POINT('',(5.1,3.45)); -#47802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47803 = PCURVE('',#47804,#47809); -#47804 = CYLINDRICAL_SURFACE('',#47805,0.125); -#47805 = AXIS2_PLACEMENT_3D('',#47806,#47807,#47808); -#47806 = CARTESIAN_POINT('',(1.9,1.225,1.225)); -#47807 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47808 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47809 = DEFINITIONAL_REPRESENTATION('',(#47810),#47813); -#47810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47811,#47812),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#47811 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#47812 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#47813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47814 = ORIENTED_EDGE('',*,*,#47815,.F.); -#47815 = EDGE_CURVE('',#47816,#47784,#47818,.T.); -#47816 = VERTEX_POINT('',#47817); -#47817 = CARTESIAN_POINT('',(2.025,0.925,1.1)); -#47818 = SURFACE_CURVE('',#47819,(#47823,#47830),.PCURVE_S1.); -#47819 = LINE('',#47820,#47821); -#47820 = CARTESIAN_POINT('',(2.025,0.925,1.1)); -#47821 = VECTOR('',#47822,1.); -#47822 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47823 = PCURVE('',#47059,#47824); -#47824 = DEFINITIONAL_REPRESENTATION('',(#47825),#47829); -#47825 = LINE('',#47826,#47827); -#47826 = CARTESIAN_POINT('',(5.225,3.45)); -#47827 = VECTOR('',#47828,1.); -#47828 = DIRECTION('',(-1.,0.E+000)); -#47829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47830 = PCURVE('',#47831,#47836); -#47831 = PLANE('',#47832); -#47832 = AXIS2_PLACEMENT_3D('',#47833,#47834,#47835); -#47833 = CARTESIAN_POINT('',(2.025,1.225,1.1)); -#47834 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47835 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47836 = DEFINITIONAL_REPRESENTATION('',(#47837),#47841); -#47837 = LINE('',#47838,#47839); -#47838 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47839 = VECTOR('',#47840,1.); -#47840 = DIRECTION('',(1.,0.E+000)); -#47841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47842 = ORIENTED_EDGE('',*,*,#47843,.F.); -#47843 = EDGE_CURVE('',#47844,#47816,#47846,.T.); -#47844 = VERTEX_POINT('',#47845); -#47845 = CARTESIAN_POINT('',(2.025,0.925,-0.12)); -#47846 = SURFACE_CURVE('',#47847,(#47851,#47858),.PCURVE_S1.); -#47847 = LINE('',#47848,#47849); -#47848 = CARTESIAN_POINT('',(2.025,0.925,-0.12)); -#47849 = VECTOR('',#47850,1.); -#47850 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47851 = PCURVE('',#47059,#47852); -#47852 = DEFINITIONAL_REPRESENTATION('',(#47853),#47857); -#47853 = LINE('',#47854,#47855); -#47854 = CARTESIAN_POINT('',(5.225,2.23)); -#47855 = VECTOR('',#47856,1.); -#47856 = DIRECTION('',(0.E+000,1.)); -#47857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47858 = PCURVE('',#47859,#47864); -#47859 = PLANE('',#47860); -#47860 = AXIS2_PLACEMENT_3D('',#47861,#47862,#47863); -#47861 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); -#47862 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47863 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47864 = DEFINITIONAL_REPRESENTATION('',(#47865),#47869); -#47865 = LINE('',#47866,#47867); -#47866 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47867 = VECTOR('',#47868,1.); -#47868 = DIRECTION('',(1.,0.E+000)); -#47869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47870 = ORIENTED_EDGE('',*,*,#47871,.F.); -#47871 = EDGE_CURVE('',#47872,#47844,#47874,.T.); -#47872 = VERTEX_POINT('',#47873); -#47873 = CARTESIAN_POINT('',(2.725,0.925,-0.12)); -#47874 = SURFACE_CURVE('',#47875,(#47879,#47886),.PCURVE_S1.); -#47875 = LINE('',#47876,#47877); -#47876 = CARTESIAN_POINT('',(2.725,0.925,-0.12)); -#47877 = VECTOR('',#47878,1.); -#47878 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47879 = PCURVE('',#47059,#47880); -#47880 = DEFINITIONAL_REPRESENTATION('',(#47881),#47885); -#47881 = LINE('',#47882,#47883); -#47882 = CARTESIAN_POINT('',(5.925,2.23)); -#47883 = VECTOR('',#47884,1.); -#47884 = DIRECTION('',(-1.,0.E+000)); -#47885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47886 = PCURVE('',#47887,#47892); -#47887 = PLANE('',#47888); -#47888 = AXIS2_PLACEMENT_3D('',#47889,#47890,#47891); -#47889 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); -#47890 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47891 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47892 = DEFINITIONAL_REPRESENTATION('',(#47893),#47897); -#47893 = LINE('',#47894,#47895); -#47894 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47895 = VECTOR('',#47896,1.); -#47896 = DIRECTION('',(1.,0.E+000)); -#47897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47898 = ORIENTED_EDGE('',*,*,#47899,.F.); -#47899 = EDGE_CURVE('',#47900,#47872,#47902,.T.); -#47900 = VERTEX_POINT('',#47901); -#47901 = CARTESIAN_POINT('',(2.725,0.925,1.1)); -#47902 = SURFACE_CURVE('',#47903,(#47907,#47914),.PCURVE_S1.); -#47903 = LINE('',#47904,#47905); -#47904 = CARTESIAN_POINT('',(2.725,0.925,1.1)); -#47905 = VECTOR('',#47906,1.); -#47906 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47907 = PCURVE('',#47059,#47908); -#47908 = DEFINITIONAL_REPRESENTATION('',(#47909),#47913); -#47909 = LINE('',#47910,#47911); -#47910 = CARTESIAN_POINT('',(5.925,3.45)); -#47911 = VECTOR('',#47912,1.); -#47912 = DIRECTION('',(0.E+000,-1.)); -#47913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47914 = PCURVE('',#47915,#47920); -#47915 = PLANE('',#47916); -#47916 = AXIS2_PLACEMENT_3D('',#47917,#47918,#47919); -#47917 = CARTESIAN_POINT('',(2.725,1.225,1.1)); -#47918 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47919 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47920 = DEFINITIONAL_REPRESENTATION('',(#47921),#47925); -#47921 = LINE('',#47922,#47923); -#47922 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47923 = VECTOR('',#47924,1.); -#47924 = DIRECTION('',(1.,0.E+000)); -#47925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47926 = ORIENTED_EDGE('',*,*,#47927,.F.); -#47927 = EDGE_CURVE('',#47928,#47900,#47930,.T.); -#47928 = VERTEX_POINT('',#47929); -#47929 = CARTESIAN_POINT('',(2.85,0.925,1.1)); -#47930 = SURFACE_CURVE('',#47931,(#47935,#47942),.PCURVE_S1.); -#47931 = LINE('',#47932,#47933); -#47932 = CARTESIAN_POINT('',(2.85,0.925,1.1)); -#47933 = VECTOR('',#47934,1.); -#47934 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47935 = PCURVE('',#47059,#47936); -#47936 = DEFINITIONAL_REPRESENTATION('',(#47937),#47941); -#47937 = LINE('',#47938,#47939); -#47938 = CARTESIAN_POINT('',(6.05,3.45)); -#47939 = VECTOR('',#47940,1.); -#47940 = DIRECTION('',(-1.,0.E+000)); -#47941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47942 = PCURVE('',#47943,#47948); -#47943 = PLANE('',#47944); -#47944 = AXIS2_PLACEMENT_3D('',#47945,#47946,#47947); -#47945 = CARTESIAN_POINT('',(2.85,1.225,1.1)); -#47946 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#47947 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#47948 = DEFINITIONAL_REPRESENTATION('',(#47949),#47953); -#47949 = LINE('',#47950,#47951); -#47950 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#47951 = VECTOR('',#47952,1.); -#47952 = DIRECTION('',(1.,0.E+000)); -#47953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47954 = ORIENTED_EDGE('',*,*,#47955,.F.); -#47955 = EDGE_CURVE('',#47956,#47928,#47958,.T.); -#47956 = VERTEX_POINT('',#47957); -#47957 = CARTESIAN_POINT('',(2.85,0.925,1.35)); -#47958 = SURFACE_CURVE('',#47959,(#47964,#47975),.PCURVE_S1.); -#47959 = CIRCLE('',#47960,0.125); -#47960 = AXIS2_PLACEMENT_3D('',#47961,#47962,#47963); -#47961 = CARTESIAN_POINT('',(2.85,0.925,1.225)); -#47962 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47963 = DIRECTION('',(0.E+000,0.E+000,1.)); -#47964 = PCURVE('',#47059,#47965); -#47965 = DEFINITIONAL_REPRESENTATION('',(#47966),#47974); -#47966 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#47967,#47968,#47969,#47970 - ,#47971,#47972,#47973),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#47967 = CARTESIAN_POINT('',(6.05,3.7)); -#47968 = CARTESIAN_POINT('',(6.266506350946,3.7)); -#47969 = CARTESIAN_POINT('',(6.158253175473,3.5125)); -#47970 = CARTESIAN_POINT('',(6.05,3.325)); -#47971 = CARTESIAN_POINT('',(5.941746824527,3.5125)); -#47972 = CARTESIAN_POINT('',(5.833493649054,3.7)); -#47973 = CARTESIAN_POINT('',(6.05,3.7)); -#47974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47975 = PCURVE('',#47976,#47981); -#47976 = CYLINDRICAL_SURFACE('',#47977,0.125); -#47977 = AXIS2_PLACEMENT_3D('',#47978,#47979,#47980); -#47978 = CARTESIAN_POINT('',(2.85,1.225,1.225)); -#47979 = DIRECTION('',(0.E+000,1.,0.E+000)); -#47980 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47981 = DEFINITIONAL_REPRESENTATION('',(#47982),#47985); -#47982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#47983,#47984),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#47983 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); -#47984 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#47985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#47986 = ORIENTED_EDGE('',*,*,#47987,.F.); -#47987 = EDGE_CURVE('',#47673,#47956,#47988,.T.); -#47988 = SURFACE_CURVE('',#47989,(#47993,#48000),.PCURVE_S1.); -#47989 = LINE('',#47990,#47991); -#47990 = CARTESIAN_POINT('',(2.725,0.925,1.35)); -#47991 = VECTOR('',#47992,1.); -#47992 = DIRECTION('',(1.,0.E+000,0.E+000)); -#47993 = PCURVE('',#47059,#47994); -#47994 = DEFINITIONAL_REPRESENTATION('',(#47995),#47999); -#47995 = LINE('',#47996,#47997); -#47996 = CARTESIAN_POINT('',(5.925,3.7)); -#47997 = VECTOR('',#47998,1.); -#47998 = DIRECTION('',(1.,0.E+000)); -#47999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48000 = PCURVE('',#48001,#48006); -#48001 = PLANE('',#48002); -#48002 = AXIS2_PLACEMENT_3D('',#48003,#48004,#48005); -#48003 = CARTESIAN_POINT('',(2.725,1.225,1.35)); -#48004 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48005 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48006 = DEFINITIONAL_REPRESENTATION('',(#48007),#48011); -#48007 = LINE('',#48008,#48009); -#48008 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48009 = VECTOR('',#48010,1.); -#48010 = DIRECTION('',(1.,0.E+000)); -#48011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48012 = FACE_BOUND('',#48013,.F.); -#48013 = EDGE_LOOP('',(#48014,#48044,#48071,#48099,#48127,#48159,#48187, - #48215,#48243,#48271,#48299,#48331)); -#48014 = ORIENTED_EDGE('',*,*,#48015,.F.); -#48015 = EDGE_CURVE('',#48016,#48018,#48020,.T.); -#48016 = VERTEX_POINT('',#48017); -#48017 = CARTESIAN_POINT('',(-2.025,0.925,1.752598183049)); -#48018 = VERTEX_POINT('',#48019); -#48019 = CARTESIAN_POINT('',(-2.025,0.925,1.35)); -#48020 = SURFACE_CURVE('',#48021,(#48025,#48032),.PCURVE_S1.); -#48021 = LINE('',#48022,#48023); -#48022 = CARTESIAN_POINT('',(-2.025,0.925,1.752598183049)); -#48023 = VECTOR('',#48024,1.); -#48024 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48025 = PCURVE('',#47059,#48026); -#48026 = DEFINITIONAL_REPRESENTATION('',(#48027),#48031); -#48027 = LINE('',#48028,#48029); -#48028 = CARTESIAN_POINT('',(1.175,4.102598183049)); -#48029 = VECTOR('',#48030,1.); -#48030 = DIRECTION('',(0.E+000,-1.)); -#48031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48032 = PCURVE('',#48033,#48038); -#48033 = PLANE('',#48034); -#48034 = AXIS2_PLACEMENT_3D('',#48035,#48036,#48037); -#48035 = CARTESIAN_POINT('',(-2.025,1.225,1.78)); -#48036 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48037 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48038 = DEFINITIONAL_REPRESENTATION('',(#48039),#48043); -#48039 = LINE('',#48040,#48041); -#48040 = CARTESIAN_POINT('',(2.7401816951E-002,-0.3)); -#48041 = VECTOR('',#48042,1.); -#48042 = DIRECTION('',(1.,0.E+000)); -#48043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48044 = ORIENTED_EDGE('',*,*,#48045,.F.); -#48045 = EDGE_CURVE('',#48046,#48016,#48048,.T.); -#48046 = VERTEX_POINT('',#48047); -#48047 = CARTESIAN_POINT('',(-2.725,0.925,1.752598183049)); -#48048 = SURFACE_CURVE('',#48049,(#48053,#48060),.PCURVE_S1.); -#48049 = LINE('',#48050,#48051); -#48050 = CARTESIAN_POINT('',(-2.725,0.925,1.752598183049)); -#48051 = VECTOR('',#48052,1.); -#48052 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48053 = PCURVE('',#47059,#48054); -#48054 = DEFINITIONAL_REPRESENTATION('',(#48055),#48059); -#48055 = LINE('',#48056,#48057); -#48056 = CARTESIAN_POINT('',(0.475,4.102598183049)); -#48057 = VECTOR('',#48058,1.); -#48058 = DIRECTION('',(1.,0.E+000)); -#48059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48060 = PCURVE('',#48061,#48066); -#48061 = CYLINDRICAL_SURFACE('',#48062,0.3); -#48062 = AXIS2_PLACEMENT_3D('',#48063,#48064,#48065); -#48063 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); -#48064 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48065 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48066 = DEFINITIONAL_REPRESENTATION('',(#48067),#48070); -#48067 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48068,#48069),.UNSPECIFIED., +#49918 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#49919 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#49920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49921 = ORIENTED_EDGE('',*,*,#49922,.F.); +#49922 = EDGE_CURVE('',#49923,#49896,#49925,.T.); +#49923 = VERTEX_POINT('',#49924); +#49924 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); +#49925 = SURFACE_CURVE('',#49926,(#49930,#49937),.PCURVE_S1.); +#49926 = LINE('',#49927,#49928); +#49927 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); +#49928 = VECTOR('',#49929,1.); +#49929 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49930 = PCURVE('',#49451,#49931); +#49931 = DEFINITIONAL_REPRESENTATION('',(#49932),#49936); +#49932 = LINE('',#49933,#49934); +#49933 = CARTESIAN_POINT('',(5.57,0.7)); +#49934 = VECTOR('',#49935,1.); +#49935 = DIRECTION('',(-1.,0.E+000)); +#49936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49937 = PCURVE('',#49938,#49943); +#49938 = PLANE('',#49939); +#49939 = AXIS2_PLACEMENT_3D('',#49940,#49941,#49942); +#49940 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.65)); +#49941 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49942 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#49943 = DEFINITIONAL_REPRESENTATION('',(#49944),#49948); +#49944 = LINE('',#49945,#49946); +#49945 = CARTESIAN_POINT('',(-2.37,0.925)); +#49946 = VECTOR('',#49947,1.); +#49947 = DIRECTION('',(1.,0.E+000)); +#49948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49949 = ORIENTED_EDGE('',*,*,#49950,.T.); +#49950 = EDGE_CURVE('',#49923,#49951,#49953,.T.); +#49951 = VERTEX_POINT('',#49952); +#49952 = CARTESIAN_POINT('',(2.37,0.925,-1.35)); +#49953 = SURFACE_CURVE('',#49954,(#49958,#49965),.PCURVE_S1.); +#49954 = LINE('',#49955,#49956); +#49955 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); +#49956 = VECTOR('',#49957,1.); +#49957 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49958 = PCURVE('',#49451,#49959); +#49959 = DEFINITIONAL_REPRESENTATION('',(#49960),#49964); +#49960 = LINE('',#49961,#49962); +#49961 = CARTESIAN_POINT('',(5.57,0.7)); +#49962 = VECTOR('',#49963,1.); +#49963 = DIRECTION('',(0.E+000,1.)); +#49964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49965 = PCURVE('',#49966,#49971); +#49966 = PLANE('',#49967); +#49967 = AXIS2_PLACEMENT_3D('',#49968,#49969,#49970); +#49968 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); +#49969 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49970 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#49971 = DEFINITIONAL_REPRESENTATION('',(#49972),#49976); +#49972 = LINE('',#49973,#49974); +#49973 = CARTESIAN_POINT('',(0.3,-0.3)); +#49974 = VECTOR('',#49975,1.); +#49975 = DIRECTION('',(-1.,0.E+000)); +#49976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49977 = ORIENTED_EDGE('',*,*,#49978,.F.); +#49978 = EDGE_CURVE('',#49979,#49951,#49981,.T.); +#49979 = VERTEX_POINT('',#49980); +#49980 = CARTESIAN_POINT('',(1.21,0.925,-1.35)); +#49981 = SURFACE_CURVE('',#49982,(#49986,#49993),.PCURVE_S1.); +#49982 = LINE('',#49983,#49984); +#49983 = CARTESIAN_POINT('',(1.21,0.925,-1.35)); +#49984 = VECTOR('',#49985,1.); +#49985 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49986 = PCURVE('',#49451,#49987); +#49987 = DEFINITIONAL_REPRESENTATION('',(#49988),#49992); +#49988 = LINE('',#49989,#49990); +#49989 = CARTESIAN_POINT('',(4.41,1.)); +#49990 = VECTOR('',#49991,1.); +#49991 = DIRECTION('',(1.,0.E+000)); +#49992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#49993 = PCURVE('',#49994,#49999); +#49994 = PLANE('',#49995); +#49995 = AXIS2_PLACEMENT_3D('',#49996,#49997,#49998); +#49996 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); +#49997 = DIRECTION('',(0.E+000,0.E+000,1.)); +#49998 = DIRECTION('',(1.,0.E+000,0.E+000)); +#49999 = DEFINITIONAL_REPRESENTATION('',(#50000),#50004); +#50000 = LINE('',#50001,#50002); +#50001 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50002 = VECTOR('',#50003,1.); +#50003 = DIRECTION('',(1.,0.E+000)); +#50004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50005 = ORIENTED_EDGE('',*,*,#50006,.F.); +#50006 = EDGE_CURVE('',#50007,#49979,#50009,.T.); +#50007 = VERTEX_POINT('',#50008); +#50008 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); +#50009 = SURFACE_CURVE('',#50010,(#50014,#50021),.PCURVE_S1.); +#50010 = LINE('',#50011,#50012); +#50011 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); +#50012 = VECTOR('',#50013,1.); +#50013 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50014 = PCURVE('',#49451,#50015); +#50015 = DEFINITIONAL_REPRESENTATION('',(#50016),#50020); +#50016 = LINE('',#50017,#50018); +#50017 = CARTESIAN_POINT('',(4.41,0.E+000)); +#50018 = VECTOR('',#50019,1.); +#50019 = DIRECTION('',(0.E+000,1.)); +#50020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50021 = PCURVE('',#50022,#50027); +#50022 = PLANE('',#50023); +#50023 = AXIS2_PLACEMENT_3D('',#50024,#50025,#50026); +#50024 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); +#50025 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50026 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50027 = DEFINITIONAL_REPRESENTATION('',(#50028),#50032); +#50028 = LINE('',#50029,#50030); +#50029 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50030 = VECTOR('',#50031,1.); +#50031 = DIRECTION('',(1.,0.E+000)); +#50032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50033 = ORIENTED_EDGE('',*,*,#50034,.T.); +#50034 = EDGE_CURVE('',#50007,#49591,#50035,.T.); +#50035 = SURFACE_CURVE('',#50036,(#50040,#50047),.PCURVE_S1.); +#50036 = LINE('',#50037,#50038); +#50037 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); +#50038 = VECTOR('',#50039,1.); +#50039 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50040 = PCURVE('',#49451,#50041); +#50041 = DEFINITIONAL_REPRESENTATION('',(#50042),#50046); +#50042 = LINE('',#50043,#50044); +#50043 = CARTESIAN_POINT('',(4.41,0.E+000)); +#50044 = VECTOR('',#50045,1.); +#50045 = DIRECTION('',(-1.,0.E+000)); +#50046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50047 = PCURVE('',#50048,#50053); +#50048 = PLANE('',#50049); +#50049 = AXIS2_PLACEMENT_3D('',#50050,#50051,#50052); +#50050 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#50051 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50052 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50053 = DEFINITIONAL_REPRESENTATION('',(#50054),#50058); +#50054 = LINE('',#50055,#50056); +#50055 = CARTESIAN_POINT('',(-1.21,0.925)); +#50056 = VECTOR('',#50057,1.); +#50057 = DIRECTION('',(1.,0.E+000)); +#50058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50059 = FACE_BOUND('',#50060,.F.); +#50060 = EDGE_LOOP('',(#50061,#50091,#50118,#50146,#50174,#50206,#50234, + #50262,#50290,#50318,#50346,#50378)); +#50061 = ORIENTED_EDGE('',*,*,#50062,.F.); +#50062 = EDGE_CURVE('',#50063,#50065,#50067,.T.); +#50063 = VERTEX_POINT('',#50064); +#50064 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); +#50065 = VERTEX_POINT('',#50066); +#50066 = CARTESIAN_POINT('',(2.725,0.925,1.35)); +#50067 = SURFACE_CURVE('',#50068,(#50072,#50079),.PCURVE_S1.); +#50068 = LINE('',#50069,#50070); +#50069 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); +#50070 = VECTOR('',#50071,1.); +#50071 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50072 = PCURVE('',#49451,#50073); +#50073 = DEFINITIONAL_REPRESENTATION('',(#50074),#50078); +#50074 = LINE('',#50075,#50076); +#50075 = CARTESIAN_POINT('',(5.925,4.102598183049)); +#50076 = VECTOR('',#50077,1.); +#50077 = DIRECTION('',(0.E+000,-1.)); +#50078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50079 = PCURVE('',#50080,#50085); +#50080 = PLANE('',#50081); +#50081 = AXIS2_PLACEMENT_3D('',#50082,#50083,#50084); +#50082 = CARTESIAN_POINT('',(2.725,1.225,1.78)); +#50083 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50084 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50085 = DEFINITIONAL_REPRESENTATION('',(#50086),#50090); +#50086 = LINE('',#50087,#50088); +#50087 = CARTESIAN_POINT('',(2.7401816951E-002,-0.3)); +#50088 = VECTOR('',#50089,1.); +#50089 = DIRECTION('',(1.,0.E+000)); +#50090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50091 = ORIENTED_EDGE('',*,*,#50092,.T.); +#50092 = EDGE_CURVE('',#50063,#50093,#50095,.T.); +#50093 = VERTEX_POINT('',#50094); +#50094 = CARTESIAN_POINT('',(2.025,0.925,1.752598183049)); +#50095 = SURFACE_CURVE('',#50096,(#50100,#50107),.PCURVE_S1.); +#50096 = LINE('',#50097,#50098); +#50097 = CARTESIAN_POINT('',(2.725,0.925,1.752598183049)); +#50098 = VECTOR('',#50099,1.); +#50099 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50100 = PCURVE('',#49451,#50101); +#50101 = DEFINITIONAL_REPRESENTATION('',(#50102),#50106); +#50102 = LINE('',#50103,#50104); +#50103 = CARTESIAN_POINT('',(5.925,4.102598183049)); +#50104 = VECTOR('',#50105,1.); +#50105 = DIRECTION('',(-1.,0.E+000)); +#50106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50107 = PCURVE('',#50108,#50113); +#50108 = CYLINDRICAL_SURFACE('',#50109,0.3); +#50109 = AXIS2_PLACEMENT_3D('',#50110,#50111,#50112); +#50110 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); +#50111 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50112 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50113 = DEFINITIONAL_REPRESENTATION('',(#50114),#50117); +#50114 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50115,#50116),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#48068 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#48069 = CARTESIAN_POINT('',(4.712388980385,-0.7)); -#48070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48071 = ORIENTED_EDGE('',*,*,#48072,.F.); -#48072 = EDGE_CURVE('',#48073,#48046,#48075,.T.); -#48073 = VERTEX_POINT('',#48074); -#48074 = CARTESIAN_POINT('',(-2.725,0.925,1.35)); -#48075 = SURFACE_CURVE('',#48076,(#48080,#48087),.PCURVE_S1.); -#48076 = LINE('',#48077,#48078); -#48077 = CARTESIAN_POINT('',(-2.725,0.925,1.35)); -#48078 = VECTOR('',#48079,1.); -#48079 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48080 = PCURVE('',#47059,#48081); -#48081 = DEFINITIONAL_REPRESENTATION('',(#48082),#48086); -#48082 = LINE('',#48083,#48084); -#48083 = CARTESIAN_POINT('',(0.475,3.7)); -#48084 = VECTOR('',#48085,1.); -#48085 = DIRECTION('',(0.E+000,1.)); -#48086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48087 = PCURVE('',#48088,#48093); -#48088 = PLANE('',#48089); -#48089 = AXIS2_PLACEMENT_3D('',#48090,#48091,#48092); -#48090 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); -#48091 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48092 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48093 = DEFINITIONAL_REPRESENTATION('',(#48094),#48098); -#48094 = LINE('',#48095,#48096); -#48095 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48096 = VECTOR('',#48097,1.); -#48097 = DIRECTION('',(1.,0.E+000)); -#48098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48099 = ORIENTED_EDGE('',*,*,#48100,.F.); -#48100 = EDGE_CURVE('',#48101,#48073,#48103,.T.); -#48101 = VERTEX_POINT('',#48102); -#48102 = CARTESIAN_POINT('',(-2.85,0.925,1.35)); -#48103 = SURFACE_CURVE('',#48104,(#48108,#48115),.PCURVE_S1.); -#48104 = LINE('',#48105,#48106); -#48105 = CARTESIAN_POINT('',(-2.85,0.925,1.35)); -#48106 = VECTOR('',#48107,1.); -#48107 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48108 = PCURVE('',#47059,#48109); -#48109 = DEFINITIONAL_REPRESENTATION('',(#48110),#48114); -#48110 = LINE('',#48111,#48112); -#48111 = CARTESIAN_POINT('',(0.35,3.7)); -#48112 = VECTOR('',#48113,1.); -#48113 = DIRECTION('',(1.,0.E+000)); -#48114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48115 = PCURVE('',#48116,#48121); -#48116 = PLANE('',#48117); -#48117 = AXIS2_PLACEMENT_3D('',#48118,#48119,#48120); -#48118 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); -#48119 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48120 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48121 = DEFINITIONAL_REPRESENTATION('',(#48122),#48126); -#48122 = LINE('',#48123,#48124); -#48123 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48124 = VECTOR('',#48125,1.); -#48125 = DIRECTION('',(1.,0.E+000)); -#48126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48127 = ORIENTED_EDGE('',*,*,#48128,.F.); -#48128 = EDGE_CURVE('',#48129,#48101,#48131,.T.); -#48129 = VERTEX_POINT('',#48130); -#48130 = CARTESIAN_POINT('',(-2.85,0.925,1.1)); -#48131 = SURFACE_CURVE('',#48132,(#48137,#48148),.PCURVE_S1.); -#48132 = CIRCLE('',#48133,0.125); -#48133 = AXIS2_PLACEMENT_3D('',#48134,#48135,#48136); -#48134 = CARTESIAN_POINT('',(-2.85,0.925,1.225)); -#48135 = DIRECTION('',(0.E+000,1.,0.E+000)); -#48136 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48137 = PCURVE('',#47059,#48138); -#48138 = DEFINITIONAL_REPRESENTATION('',(#48139),#48147); -#48139 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#48140,#48141,#48142,#48143 - ,#48144,#48145,#48146),.UNSPECIFIED.,.T.,.F.) +#50115 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#50116 = CARTESIAN_POINT('',(4.712388980385,0.7)); +#50117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50118 = ORIENTED_EDGE('',*,*,#50119,.F.); +#50119 = EDGE_CURVE('',#50120,#50093,#50122,.T.); +#50120 = VERTEX_POINT('',#50121); +#50121 = CARTESIAN_POINT('',(2.025,0.925,1.35)); +#50122 = SURFACE_CURVE('',#50123,(#50127,#50134),.PCURVE_S1.); +#50123 = LINE('',#50124,#50125); +#50124 = CARTESIAN_POINT('',(2.025,0.925,1.35)); +#50125 = VECTOR('',#50126,1.); +#50126 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50127 = PCURVE('',#49451,#50128); +#50128 = DEFINITIONAL_REPRESENTATION('',(#50129),#50133); +#50129 = LINE('',#50130,#50131); +#50130 = CARTESIAN_POINT('',(5.225,3.7)); +#50131 = VECTOR('',#50132,1.); +#50132 = DIRECTION('',(0.E+000,1.)); +#50133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50134 = PCURVE('',#50135,#50140); +#50135 = PLANE('',#50136); +#50136 = AXIS2_PLACEMENT_3D('',#50137,#50138,#50139); +#50137 = CARTESIAN_POINT('',(2.025,1.225,1.35)); +#50138 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50139 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50140 = DEFINITIONAL_REPRESENTATION('',(#50141),#50145); +#50141 = LINE('',#50142,#50143); +#50142 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50143 = VECTOR('',#50144,1.); +#50144 = DIRECTION('',(1.,0.E+000)); +#50145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50146 = ORIENTED_EDGE('',*,*,#50147,.F.); +#50147 = EDGE_CURVE('',#50148,#50120,#50150,.T.); +#50148 = VERTEX_POINT('',#50149); +#50149 = CARTESIAN_POINT('',(1.9,0.925,1.35)); +#50150 = SURFACE_CURVE('',#50151,(#50155,#50162),.PCURVE_S1.); +#50151 = LINE('',#50152,#50153); +#50152 = CARTESIAN_POINT('',(1.9,0.925,1.35)); +#50153 = VECTOR('',#50154,1.); +#50154 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50155 = PCURVE('',#49451,#50156); +#50156 = DEFINITIONAL_REPRESENTATION('',(#50157),#50161); +#50157 = LINE('',#50158,#50159); +#50158 = CARTESIAN_POINT('',(5.1,3.7)); +#50159 = VECTOR('',#50160,1.); +#50160 = DIRECTION('',(1.,0.E+000)); +#50161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50162 = PCURVE('',#50163,#50168); +#50163 = PLANE('',#50164); +#50164 = AXIS2_PLACEMENT_3D('',#50165,#50166,#50167); +#50165 = CARTESIAN_POINT('',(1.9,1.225,1.35)); +#50166 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50167 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50168 = DEFINITIONAL_REPRESENTATION('',(#50169),#50173); +#50169 = LINE('',#50170,#50171); +#50170 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50171 = VECTOR('',#50172,1.); +#50172 = DIRECTION('',(1.,0.E+000)); +#50173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50174 = ORIENTED_EDGE('',*,*,#50175,.F.); +#50175 = EDGE_CURVE('',#50176,#50148,#50178,.T.); +#50176 = VERTEX_POINT('',#50177); +#50177 = CARTESIAN_POINT('',(1.9,0.925,1.1)); +#50178 = SURFACE_CURVE('',#50179,(#50184,#50195),.PCURVE_S1.); +#50179 = CIRCLE('',#50180,0.125); +#50180 = AXIS2_PLACEMENT_3D('',#50181,#50182,#50183); +#50181 = CARTESIAN_POINT('',(1.9,0.925,1.225)); +#50182 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50183 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50184 = PCURVE('',#49451,#50185); +#50185 = DEFINITIONAL_REPRESENTATION('',(#50186),#50194); +#50186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50187,#50188,#50189,#50190 + ,#50191,#50192,#50193),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#48140 = CARTESIAN_POINT('',(0.35,3.45)); -#48141 = CARTESIAN_POINT('',(0.133493649054,3.45)); -#48142 = CARTESIAN_POINT('',(0.241746824527,3.6375)); -#48143 = CARTESIAN_POINT('',(0.35,3.825)); -#48144 = CARTESIAN_POINT('',(0.458253175473,3.6375)); -#48145 = CARTESIAN_POINT('',(0.566506350946,3.45)); -#48146 = CARTESIAN_POINT('',(0.35,3.45)); -#48147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48148 = PCURVE('',#48149,#48154); -#48149 = CYLINDRICAL_SURFACE('',#48150,0.125); -#48150 = AXIS2_PLACEMENT_3D('',#48151,#48152,#48153); -#48151 = CARTESIAN_POINT('',(-2.85,1.225,1.225)); -#48152 = DIRECTION('',(0.E+000,1.,0.E+000)); -#48153 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48154 = DEFINITIONAL_REPRESENTATION('',(#48155),#48158); -#48155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48156,#48157),.UNSPECIFIED., +#50187 = CARTESIAN_POINT('',(5.1,3.45)); +#50188 = CARTESIAN_POINT('',(4.883493649054,3.45)); +#50189 = CARTESIAN_POINT('',(4.991746824527,3.6375)); +#50190 = CARTESIAN_POINT('',(5.1,3.825)); +#50191 = CARTESIAN_POINT('',(5.208253175473,3.6375)); +#50192 = CARTESIAN_POINT('',(5.316506350946,3.45)); +#50193 = CARTESIAN_POINT('',(5.1,3.45)); +#50194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50195 = PCURVE('',#50196,#50201); +#50196 = CYLINDRICAL_SURFACE('',#50197,0.125); +#50197 = AXIS2_PLACEMENT_3D('',#50198,#50199,#50200); +#50198 = CARTESIAN_POINT('',(1.9,1.225,1.225)); +#50199 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50200 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50201 = DEFINITIONAL_REPRESENTATION('',(#50202),#50205); +#50202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50203,#50204),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#48156 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#48157 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#48158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48159 = ORIENTED_EDGE('',*,*,#48160,.F.); -#48160 = EDGE_CURVE('',#48161,#48129,#48163,.T.); -#48161 = VERTEX_POINT('',#48162); -#48162 = CARTESIAN_POINT('',(-2.725,0.925,1.1)); -#48163 = SURFACE_CURVE('',#48164,(#48168,#48175),.PCURVE_S1.); -#48164 = LINE('',#48165,#48166); -#48165 = CARTESIAN_POINT('',(-2.725,0.925,1.1)); -#48166 = VECTOR('',#48167,1.); -#48167 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48168 = PCURVE('',#47059,#48169); -#48169 = DEFINITIONAL_REPRESENTATION('',(#48170),#48174); -#48170 = LINE('',#48171,#48172); -#48171 = CARTESIAN_POINT('',(0.475,3.45)); -#48172 = VECTOR('',#48173,1.); -#48173 = DIRECTION('',(-1.,0.E+000)); -#48174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48175 = PCURVE('',#48176,#48181); -#48176 = PLANE('',#48177); -#48177 = AXIS2_PLACEMENT_3D('',#48178,#48179,#48180); -#48178 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); -#48179 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48180 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48181 = DEFINITIONAL_REPRESENTATION('',(#48182),#48186); -#48182 = LINE('',#48183,#48184); -#48183 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48184 = VECTOR('',#48185,1.); -#48185 = DIRECTION('',(1.,0.E+000)); -#48186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48187 = ORIENTED_EDGE('',*,*,#48188,.F.); -#48188 = EDGE_CURVE('',#48189,#48161,#48191,.T.); -#48189 = VERTEX_POINT('',#48190); -#48190 = CARTESIAN_POINT('',(-2.725,0.925,-0.12)); -#48191 = SURFACE_CURVE('',#48192,(#48196,#48203),.PCURVE_S1.); -#48192 = LINE('',#48193,#48194); -#48193 = CARTESIAN_POINT('',(-2.725,0.925,-0.12)); -#48194 = VECTOR('',#48195,1.); -#48195 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48196 = PCURVE('',#47059,#48197); -#48197 = DEFINITIONAL_REPRESENTATION('',(#48198),#48202); -#48198 = LINE('',#48199,#48200); -#48199 = CARTESIAN_POINT('',(0.475,2.23)); -#48200 = VECTOR('',#48201,1.); -#48201 = DIRECTION('',(0.E+000,1.)); -#48202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48203 = PCURVE('',#48204,#48209); -#48204 = PLANE('',#48205); -#48205 = AXIS2_PLACEMENT_3D('',#48206,#48207,#48208); -#48206 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); -#48207 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48208 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48209 = DEFINITIONAL_REPRESENTATION('',(#48210),#48214); -#48210 = LINE('',#48211,#48212); -#48211 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48212 = VECTOR('',#48213,1.); -#48213 = DIRECTION('',(1.,0.E+000)); -#48214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48215 = ORIENTED_EDGE('',*,*,#48216,.F.); -#48216 = EDGE_CURVE('',#48217,#48189,#48219,.T.); -#48217 = VERTEX_POINT('',#48218); -#48218 = CARTESIAN_POINT('',(-2.025,0.925,-0.12)); -#48219 = SURFACE_CURVE('',#48220,(#48224,#48231),.PCURVE_S1.); -#48220 = LINE('',#48221,#48222); -#48221 = CARTESIAN_POINT('',(-2.025,0.925,-0.12)); -#48222 = VECTOR('',#48223,1.); -#48223 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48224 = PCURVE('',#47059,#48225); -#48225 = DEFINITIONAL_REPRESENTATION('',(#48226),#48230); -#48226 = LINE('',#48227,#48228); -#48227 = CARTESIAN_POINT('',(1.175,2.23)); -#48228 = VECTOR('',#48229,1.); -#48229 = DIRECTION('',(-1.,0.E+000)); -#48230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48231 = PCURVE('',#48232,#48237); -#48232 = PLANE('',#48233); -#48233 = AXIS2_PLACEMENT_3D('',#48234,#48235,#48236); -#48234 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); -#48235 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48236 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48237 = DEFINITIONAL_REPRESENTATION('',(#48238),#48242); -#48238 = LINE('',#48239,#48240); -#48239 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48240 = VECTOR('',#48241,1.); -#48241 = DIRECTION('',(1.,0.E+000)); -#48242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48243 = ORIENTED_EDGE('',*,*,#48244,.F.); -#48244 = EDGE_CURVE('',#48245,#48217,#48247,.T.); -#48245 = VERTEX_POINT('',#48246); -#48246 = CARTESIAN_POINT('',(-2.025,0.925,1.1)); -#48247 = SURFACE_CURVE('',#48248,(#48252,#48259),.PCURVE_S1.); -#48248 = LINE('',#48249,#48250); -#48249 = CARTESIAN_POINT('',(-2.025,0.925,1.1)); -#48250 = VECTOR('',#48251,1.); -#48251 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48252 = PCURVE('',#47059,#48253); -#48253 = DEFINITIONAL_REPRESENTATION('',(#48254),#48258); -#48254 = LINE('',#48255,#48256); -#48255 = CARTESIAN_POINT('',(1.175,3.45)); -#48256 = VECTOR('',#48257,1.); -#48257 = DIRECTION('',(0.E+000,-1.)); -#48258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48259 = PCURVE('',#48260,#48265); -#48260 = PLANE('',#48261); -#48261 = AXIS2_PLACEMENT_3D('',#48262,#48263,#48264); -#48262 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); -#48263 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48264 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48265 = DEFINITIONAL_REPRESENTATION('',(#48266),#48270); -#48266 = LINE('',#48267,#48268); -#48267 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48268 = VECTOR('',#48269,1.); -#48269 = DIRECTION('',(1.,0.E+000)); -#48270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48271 = ORIENTED_EDGE('',*,*,#48272,.F.); -#48272 = EDGE_CURVE('',#48273,#48245,#48275,.T.); -#48273 = VERTEX_POINT('',#48274); -#48274 = CARTESIAN_POINT('',(-1.9,0.925,1.1)); -#48275 = SURFACE_CURVE('',#48276,(#48280,#48287),.PCURVE_S1.); -#48276 = LINE('',#48277,#48278); -#48277 = CARTESIAN_POINT('',(-1.9,0.925,1.1)); -#48278 = VECTOR('',#48279,1.); -#48279 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48280 = PCURVE('',#47059,#48281); -#48281 = DEFINITIONAL_REPRESENTATION('',(#48282),#48286); -#48282 = LINE('',#48283,#48284); -#48283 = CARTESIAN_POINT('',(1.3,3.45)); -#48284 = VECTOR('',#48285,1.); -#48285 = DIRECTION('',(-1.,0.E+000)); -#48286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48287 = PCURVE('',#48288,#48293); -#48288 = PLANE('',#48289); -#48289 = AXIS2_PLACEMENT_3D('',#48290,#48291,#48292); -#48290 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); -#48291 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48292 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48293 = DEFINITIONAL_REPRESENTATION('',(#48294),#48298); -#48294 = LINE('',#48295,#48296); -#48295 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48296 = VECTOR('',#48297,1.); -#48297 = DIRECTION('',(1.,0.E+000)); -#48298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48299 = ORIENTED_EDGE('',*,*,#48300,.F.); -#48300 = EDGE_CURVE('',#48301,#48273,#48303,.T.); -#48301 = VERTEX_POINT('',#48302); -#48302 = CARTESIAN_POINT('',(-1.9,0.925,1.35)); -#48303 = SURFACE_CURVE('',#48304,(#48309,#48320),.PCURVE_S1.); -#48304 = CIRCLE('',#48305,0.125); -#48305 = AXIS2_PLACEMENT_3D('',#48306,#48307,#48308); -#48306 = CARTESIAN_POINT('',(-1.9,0.925,1.225)); -#48307 = DIRECTION('',(0.E+000,1.,0.E+000)); -#48308 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48309 = PCURVE('',#47059,#48310); -#48310 = DEFINITIONAL_REPRESENTATION('',(#48311),#48319); -#48311 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#48312,#48313,#48314,#48315 - ,#48316,#48317,#48318),.UNSPECIFIED.,.T.,.F.) +#50203 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#50204 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#50205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50206 = ORIENTED_EDGE('',*,*,#50207,.F.); +#50207 = EDGE_CURVE('',#50208,#50176,#50210,.T.); +#50208 = VERTEX_POINT('',#50209); +#50209 = CARTESIAN_POINT('',(2.025,0.925,1.1)); +#50210 = SURFACE_CURVE('',#50211,(#50215,#50222),.PCURVE_S1.); +#50211 = LINE('',#50212,#50213); +#50212 = CARTESIAN_POINT('',(2.025,0.925,1.1)); +#50213 = VECTOR('',#50214,1.); +#50214 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50215 = PCURVE('',#49451,#50216); +#50216 = DEFINITIONAL_REPRESENTATION('',(#50217),#50221); +#50217 = LINE('',#50218,#50219); +#50218 = CARTESIAN_POINT('',(5.225,3.45)); +#50219 = VECTOR('',#50220,1.); +#50220 = DIRECTION('',(-1.,0.E+000)); +#50221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50222 = PCURVE('',#50223,#50228); +#50223 = PLANE('',#50224); +#50224 = AXIS2_PLACEMENT_3D('',#50225,#50226,#50227); +#50225 = CARTESIAN_POINT('',(2.025,1.225,1.1)); +#50226 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50227 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50228 = DEFINITIONAL_REPRESENTATION('',(#50229),#50233); +#50229 = LINE('',#50230,#50231); +#50230 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50231 = VECTOR('',#50232,1.); +#50232 = DIRECTION('',(1.,0.E+000)); +#50233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50234 = ORIENTED_EDGE('',*,*,#50235,.F.); +#50235 = EDGE_CURVE('',#50236,#50208,#50238,.T.); +#50236 = VERTEX_POINT('',#50237); +#50237 = CARTESIAN_POINT('',(2.025,0.925,-0.12)); +#50238 = SURFACE_CURVE('',#50239,(#50243,#50250),.PCURVE_S1.); +#50239 = LINE('',#50240,#50241); +#50240 = CARTESIAN_POINT('',(2.025,0.925,-0.12)); +#50241 = VECTOR('',#50242,1.); +#50242 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50243 = PCURVE('',#49451,#50244); +#50244 = DEFINITIONAL_REPRESENTATION('',(#50245),#50249); +#50245 = LINE('',#50246,#50247); +#50246 = CARTESIAN_POINT('',(5.225,2.23)); +#50247 = VECTOR('',#50248,1.); +#50248 = DIRECTION('',(0.E+000,1.)); +#50249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50250 = PCURVE('',#50251,#50256); +#50251 = PLANE('',#50252); +#50252 = AXIS2_PLACEMENT_3D('',#50253,#50254,#50255); +#50253 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); +#50254 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50255 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50256 = DEFINITIONAL_REPRESENTATION('',(#50257),#50261); +#50257 = LINE('',#50258,#50259); +#50258 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50259 = VECTOR('',#50260,1.); +#50260 = DIRECTION('',(1.,0.E+000)); +#50261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50262 = ORIENTED_EDGE('',*,*,#50263,.F.); +#50263 = EDGE_CURVE('',#50264,#50236,#50266,.T.); +#50264 = VERTEX_POINT('',#50265); +#50265 = CARTESIAN_POINT('',(2.725,0.925,-0.12)); +#50266 = SURFACE_CURVE('',#50267,(#50271,#50278),.PCURVE_S1.); +#50267 = LINE('',#50268,#50269); +#50268 = CARTESIAN_POINT('',(2.725,0.925,-0.12)); +#50269 = VECTOR('',#50270,1.); +#50270 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50271 = PCURVE('',#49451,#50272); +#50272 = DEFINITIONAL_REPRESENTATION('',(#50273),#50277); +#50273 = LINE('',#50274,#50275); +#50274 = CARTESIAN_POINT('',(5.925,2.23)); +#50275 = VECTOR('',#50276,1.); +#50276 = DIRECTION('',(-1.,0.E+000)); +#50277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50278 = PCURVE('',#50279,#50284); +#50279 = PLANE('',#50280); +#50280 = AXIS2_PLACEMENT_3D('',#50281,#50282,#50283); +#50281 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); +#50282 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50283 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50284 = DEFINITIONAL_REPRESENTATION('',(#50285),#50289); +#50285 = LINE('',#50286,#50287); +#50286 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50287 = VECTOR('',#50288,1.); +#50288 = DIRECTION('',(1.,0.E+000)); +#50289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50290 = ORIENTED_EDGE('',*,*,#50291,.F.); +#50291 = EDGE_CURVE('',#50292,#50264,#50294,.T.); +#50292 = VERTEX_POINT('',#50293); +#50293 = CARTESIAN_POINT('',(2.725,0.925,1.1)); +#50294 = SURFACE_CURVE('',#50295,(#50299,#50306),.PCURVE_S1.); +#50295 = LINE('',#50296,#50297); +#50296 = CARTESIAN_POINT('',(2.725,0.925,1.1)); +#50297 = VECTOR('',#50298,1.); +#50298 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50299 = PCURVE('',#49451,#50300); +#50300 = DEFINITIONAL_REPRESENTATION('',(#50301),#50305); +#50301 = LINE('',#50302,#50303); +#50302 = CARTESIAN_POINT('',(5.925,3.45)); +#50303 = VECTOR('',#50304,1.); +#50304 = DIRECTION('',(0.E+000,-1.)); +#50305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50306 = PCURVE('',#50307,#50312); +#50307 = PLANE('',#50308); +#50308 = AXIS2_PLACEMENT_3D('',#50309,#50310,#50311); +#50309 = CARTESIAN_POINT('',(2.725,1.225,1.1)); +#50310 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50311 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50312 = DEFINITIONAL_REPRESENTATION('',(#50313),#50317); +#50313 = LINE('',#50314,#50315); +#50314 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50315 = VECTOR('',#50316,1.); +#50316 = DIRECTION('',(1.,0.E+000)); +#50317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50318 = ORIENTED_EDGE('',*,*,#50319,.F.); +#50319 = EDGE_CURVE('',#50320,#50292,#50322,.T.); +#50320 = VERTEX_POINT('',#50321); +#50321 = CARTESIAN_POINT('',(2.85,0.925,1.1)); +#50322 = SURFACE_CURVE('',#50323,(#50327,#50334),.PCURVE_S1.); +#50323 = LINE('',#50324,#50325); +#50324 = CARTESIAN_POINT('',(2.85,0.925,1.1)); +#50325 = VECTOR('',#50326,1.); +#50326 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50327 = PCURVE('',#49451,#50328); +#50328 = DEFINITIONAL_REPRESENTATION('',(#50329),#50333); +#50329 = LINE('',#50330,#50331); +#50330 = CARTESIAN_POINT('',(6.05,3.45)); +#50331 = VECTOR('',#50332,1.); +#50332 = DIRECTION('',(-1.,0.E+000)); +#50333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50334 = PCURVE('',#50335,#50340); +#50335 = PLANE('',#50336); +#50336 = AXIS2_PLACEMENT_3D('',#50337,#50338,#50339); +#50337 = CARTESIAN_POINT('',(2.85,1.225,1.1)); +#50338 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50339 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50340 = DEFINITIONAL_REPRESENTATION('',(#50341),#50345); +#50341 = LINE('',#50342,#50343); +#50342 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50343 = VECTOR('',#50344,1.); +#50344 = DIRECTION('',(1.,0.E+000)); +#50345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50346 = ORIENTED_EDGE('',*,*,#50347,.F.); +#50347 = EDGE_CURVE('',#50348,#50320,#50350,.T.); +#50348 = VERTEX_POINT('',#50349); +#50349 = CARTESIAN_POINT('',(2.85,0.925,1.35)); +#50350 = SURFACE_CURVE('',#50351,(#50356,#50367),.PCURVE_S1.); +#50351 = CIRCLE('',#50352,0.125); +#50352 = AXIS2_PLACEMENT_3D('',#50353,#50354,#50355); +#50353 = CARTESIAN_POINT('',(2.85,0.925,1.225)); +#50354 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50355 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50356 = PCURVE('',#49451,#50357); +#50357 = DEFINITIONAL_REPRESENTATION('',(#50358),#50366); +#50358 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50359,#50360,#50361,#50362 + ,#50363,#50364,#50365),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#48312 = CARTESIAN_POINT('',(1.3,3.7)); -#48313 = CARTESIAN_POINT('',(1.516506350946,3.7)); -#48314 = CARTESIAN_POINT('',(1.408253175473,3.5125)); -#48315 = CARTESIAN_POINT('',(1.3,3.325)); -#48316 = CARTESIAN_POINT('',(1.191746824527,3.5125)); -#48317 = CARTESIAN_POINT('',(1.083493649054,3.7)); -#48318 = CARTESIAN_POINT('',(1.3,3.7)); -#48319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48320 = PCURVE('',#48321,#48326); -#48321 = CYLINDRICAL_SURFACE('',#48322,0.125); -#48322 = AXIS2_PLACEMENT_3D('',#48323,#48324,#48325); -#48323 = CARTESIAN_POINT('',(-1.9,1.225,1.225)); -#48324 = DIRECTION('',(0.E+000,1.,0.E+000)); -#48325 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48326 = DEFINITIONAL_REPRESENTATION('',(#48327),#48330); -#48327 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48328,#48329),.UNSPECIFIED., +#50359 = CARTESIAN_POINT('',(6.05,3.7)); +#50360 = CARTESIAN_POINT('',(6.266506350946,3.7)); +#50361 = CARTESIAN_POINT('',(6.158253175473,3.5125)); +#50362 = CARTESIAN_POINT('',(6.05,3.325)); +#50363 = CARTESIAN_POINT('',(5.941746824527,3.5125)); +#50364 = CARTESIAN_POINT('',(5.833493649054,3.7)); +#50365 = CARTESIAN_POINT('',(6.05,3.7)); +#50366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50367 = PCURVE('',#50368,#50373); +#50368 = CYLINDRICAL_SURFACE('',#50369,0.125); +#50369 = AXIS2_PLACEMENT_3D('',#50370,#50371,#50372); +#50370 = CARTESIAN_POINT('',(2.85,1.225,1.225)); +#50371 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50372 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50373 = DEFINITIONAL_REPRESENTATION('',(#50374),#50377); +#50374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50375,#50376),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#48328 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); -#48329 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#48330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#50375 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); +#50376 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#50377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50378 = ORIENTED_EDGE('',*,*,#50379,.F.); +#50379 = EDGE_CURVE('',#50065,#50348,#50380,.T.); +#50380 = SURFACE_CURVE('',#50381,(#50385,#50392),.PCURVE_S1.); +#50381 = LINE('',#50382,#50383); +#50382 = CARTESIAN_POINT('',(2.725,0.925,1.35)); +#50383 = VECTOR('',#50384,1.); +#50384 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50385 = PCURVE('',#49451,#50386); +#50386 = DEFINITIONAL_REPRESENTATION('',(#50387),#50391); +#50387 = LINE('',#50388,#50389); +#50388 = CARTESIAN_POINT('',(5.925,3.7)); +#50389 = VECTOR('',#50390,1.); +#50390 = DIRECTION('',(1.,0.E+000)); +#50391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50392 = PCURVE('',#50393,#50398); +#50393 = PLANE('',#50394); +#50394 = AXIS2_PLACEMENT_3D('',#50395,#50396,#50397); +#50395 = CARTESIAN_POINT('',(2.725,1.225,1.35)); +#50396 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50397 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50398 = DEFINITIONAL_REPRESENTATION('',(#50399),#50403); +#50399 = LINE('',#50400,#50401); +#50400 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50401 = VECTOR('',#50402,1.); +#50402 = DIRECTION('',(1.,0.E+000)); +#50403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50404 = FACE_BOUND('',#50405,.F.); +#50405 = EDGE_LOOP('',(#50406,#50436,#50463,#50491,#50519,#50551,#50579, + #50607,#50635,#50663,#50691,#50723)); +#50406 = ORIENTED_EDGE('',*,*,#50407,.F.); +#50407 = EDGE_CURVE('',#50408,#50410,#50412,.T.); +#50408 = VERTEX_POINT('',#50409); +#50409 = CARTESIAN_POINT('',(-2.025,0.925,1.752598183049)); +#50410 = VERTEX_POINT('',#50411); +#50411 = CARTESIAN_POINT('',(-2.025,0.925,1.35)); +#50412 = SURFACE_CURVE('',#50413,(#50417,#50424),.PCURVE_S1.); +#50413 = LINE('',#50414,#50415); +#50414 = CARTESIAN_POINT('',(-2.025,0.925,1.752598183049)); +#50415 = VECTOR('',#50416,1.); +#50416 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50417 = PCURVE('',#49451,#50418); +#50418 = DEFINITIONAL_REPRESENTATION('',(#50419),#50423); +#50419 = LINE('',#50420,#50421); +#50420 = CARTESIAN_POINT('',(1.175,4.102598183049)); +#50421 = VECTOR('',#50422,1.); +#50422 = DIRECTION('',(0.E+000,-1.)); +#50423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#48331 = ORIENTED_EDGE('',*,*,#48332,.F.); -#48332 = EDGE_CURVE('',#48018,#48301,#48333,.T.); -#48333 = SURFACE_CURVE('',#48334,(#48338,#48345),.PCURVE_S1.); -#48334 = LINE('',#48335,#48336); -#48335 = CARTESIAN_POINT('',(-2.025,0.925,1.35)); -#48336 = VECTOR('',#48337,1.); -#48337 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48338 = PCURVE('',#47059,#48339); -#48339 = DEFINITIONAL_REPRESENTATION('',(#48340),#48344); -#48340 = LINE('',#48341,#48342); -#48341 = CARTESIAN_POINT('',(1.175,3.7)); -#48342 = VECTOR('',#48343,1.); -#48343 = DIRECTION('',(1.,0.E+000)); -#48344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48345 = PCURVE('',#48346,#48351); -#48346 = PLANE('',#48347); -#48347 = AXIS2_PLACEMENT_3D('',#48348,#48349,#48350); -#48348 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); -#48349 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48351 = DEFINITIONAL_REPRESENTATION('',(#48352),#48356); -#48352 = LINE('',#48353,#48354); -#48353 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#48354 = VECTOR('',#48355,1.); -#48355 = DIRECTION('',(1.,0.E+000)); -#48356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48357 = FACE_BOUND('',#48358,.F.); -#48358 = EDGE_LOOP('',(#48359,#48382,#48402,#48403)); -#48359 = ORIENTED_EDGE('',*,*,#48360,.T.); -#48360 = EDGE_CURVE('',#47123,#48361,#48363,.T.); -#48361 = VERTEX_POINT('',#48362); -#48362 = CARTESIAN_POINT('',(0.41,0.925,-1.18)); -#48363 = SURFACE_CURVE('',#48364,(#48368,#48375),.PCURVE_S1.); -#48364 = LINE('',#48365,#48366); -#48365 = CARTESIAN_POINT('',(0.41,0.925,-1.75)); -#48366 = VECTOR('',#48367,1.); -#48367 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48368 = PCURVE('',#47059,#48369); -#48369 = DEFINITIONAL_REPRESENTATION('',(#48370),#48374); -#48370 = LINE('',#48371,#48372); -#48371 = CARTESIAN_POINT('',(3.61,0.6)); -#48372 = VECTOR('',#48373,1.); -#48373 = DIRECTION('',(0.E+000,1.)); -#48374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48375 = PCURVE('',#47183,#48376); -#48376 = DEFINITIONAL_REPRESENTATION('',(#48377),#48381); -#48377 = LINE('',#48378,#48379); -#48378 = CARTESIAN_POINT('',(1.75,0.925)); -#48379 = VECTOR('',#48380,1.); -#48380 = DIRECTION('',(-1.,0.E+000)); -#48381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#50424 = PCURVE('',#50425,#50430); +#50425 = PLANE('',#50426); +#50426 = AXIS2_PLACEMENT_3D('',#50427,#50428,#50429); +#50427 = CARTESIAN_POINT('',(-2.025,1.225,1.78)); +#50428 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50429 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50430 = DEFINITIONAL_REPRESENTATION('',(#50431),#50435); +#50431 = LINE('',#50432,#50433); +#50432 = CARTESIAN_POINT('',(2.7401816951E-002,-0.3)); +#50433 = VECTOR('',#50434,1.); +#50434 = DIRECTION('',(1.,0.E+000)); +#50435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50436 = ORIENTED_EDGE('',*,*,#50437,.F.); +#50437 = EDGE_CURVE('',#50438,#50408,#50440,.T.); +#50438 = VERTEX_POINT('',#50439); +#50439 = CARTESIAN_POINT('',(-2.725,0.925,1.752598183049)); +#50440 = SURFACE_CURVE('',#50441,(#50445,#50452),.PCURVE_S1.); +#50441 = LINE('',#50442,#50443); +#50442 = CARTESIAN_POINT('',(-2.725,0.925,1.752598183049)); +#50443 = VECTOR('',#50444,1.); +#50444 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50445 = PCURVE('',#49451,#50446); +#50446 = DEFINITIONAL_REPRESENTATION('',(#50447),#50451); +#50447 = LINE('',#50448,#50449); +#50448 = CARTESIAN_POINT('',(0.475,4.102598183049)); +#50449 = VECTOR('',#50450,1.); +#50450 = DIRECTION('',(1.,0.E+000)); +#50451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50452 = PCURVE('',#50453,#50458); +#50453 = CYLINDRICAL_SURFACE('',#50454,0.3); +#50454 = AXIS2_PLACEMENT_3D('',#50455,#50456,#50457); +#50455 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); +#50456 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50457 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50458 = DEFINITIONAL_REPRESENTATION('',(#50459),#50462); +#50459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50460,#50461),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); +#50460 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#50461 = CARTESIAN_POINT('',(4.712388980385,-0.7)); +#50462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#48382 = ORIENTED_EDGE('',*,*,#48383,.F.); -#48383 = EDGE_CURVE('',#47044,#48361,#48384,.T.); -#48384 = SURFACE_CURVE('',#48385,(#48389,#48396),.PCURVE_S1.); -#48385 = LINE('',#48386,#48387); -#48386 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); -#48387 = VECTOR('',#48388,1.); -#48388 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48389 = PCURVE('',#47059,#48390); -#48390 = DEFINITIONAL_REPRESENTATION('',(#48391),#48395); -#48391 = LINE('',#48392,#48393); -#48392 = CARTESIAN_POINT('',(2.79,1.17)); -#48393 = VECTOR('',#48394,1.); -#48394 = DIRECTION('',(1.,0.E+000)); -#48395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48396 = PCURVE('',#47086,#48397); -#48397 = DEFINITIONAL_REPRESENTATION('',(#48398),#48401); -#48398 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48399,#48400),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); -#48399 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#48400 = CARTESIAN_POINT('',(3.14159265359,0.82)); -#48401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48402 = ORIENTED_EDGE('',*,*,#47043,.T.); -#48403 = ORIENTED_EDGE('',*,*,#47122,.T.); -#48404 = ADVANCED_FACE('',(#48405),#47688,.F.); -#48405 = FACE_BOUND('',#48406,.F.); -#48406 = EDGE_LOOP('',(#48407,#48434,#48435,#48458,#48486)); -#48407 = ORIENTED_EDGE('',*,*,#48408,.T.); -#48408 = EDGE_CURVE('',#48409,#47671,#48411,.T.); -#48409 = VERTEX_POINT('',#48410); -#48410 = CARTESIAN_POINT('',(2.725,1.075,1.492790561914)); -#48411 = SURFACE_CURVE('',#48412,(#48417,#48428),.PCURVE_S1.); -#48412 = CIRCLE('',#48413,0.3); -#48413 = AXIS2_PLACEMENT_3D('',#48414,#48415,#48416); -#48414 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); -#48415 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48416 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#48417 = PCURVE('',#47688,#48418); -#48418 = DEFINITIONAL_REPRESENTATION('',(#48419),#48427); -#48419 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#48420,#48421,#48422,#48423 - ,#48424,#48425,#48426),.UNSPECIFIED.,.T.,.F.) +#50463 = ORIENTED_EDGE('',*,*,#50464,.F.); +#50464 = EDGE_CURVE('',#50465,#50438,#50467,.T.); +#50465 = VERTEX_POINT('',#50466); +#50466 = CARTESIAN_POINT('',(-2.725,0.925,1.35)); +#50467 = SURFACE_CURVE('',#50468,(#50472,#50479),.PCURVE_S1.); +#50468 = LINE('',#50469,#50470); +#50469 = CARTESIAN_POINT('',(-2.725,0.925,1.35)); +#50470 = VECTOR('',#50471,1.); +#50471 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50472 = PCURVE('',#49451,#50473); +#50473 = DEFINITIONAL_REPRESENTATION('',(#50474),#50478); +#50474 = LINE('',#50475,#50476); +#50475 = CARTESIAN_POINT('',(0.475,3.7)); +#50476 = VECTOR('',#50477,1.); +#50477 = DIRECTION('',(0.E+000,1.)); +#50478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50479 = PCURVE('',#50480,#50485); +#50480 = PLANE('',#50481); +#50481 = AXIS2_PLACEMENT_3D('',#50482,#50483,#50484); +#50482 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); +#50483 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50484 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50485 = DEFINITIONAL_REPRESENTATION('',(#50486),#50490); +#50486 = LINE('',#50487,#50488); +#50487 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50488 = VECTOR('',#50489,1.); +#50489 = DIRECTION('',(1.,0.E+000)); +#50490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50491 = ORIENTED_EDGE('',*,*,#50492,.F.); +#50492 = EDGE_CURVE('',#50493,#50465,#50495,.T.); +#50493 = VERTEX_POINT('',#50494); +#50494 = CARTESIAN_POINT('',(-2.85,0.925,1.35)); +#50495 = SURFACE_CURVE('',#50496,(#50500,#50507),.PCURVE_S1.); +#50496 = LINE('',#50497,#50498); +#50497 = CARTESIAN_POINT('',(-2.85,0.925,1.35)); +#50498 = VECTOR('',#50499,1.); +#50499 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50500 = PCURVE('',#49451,#50501); +#50501 = DEFINITIONAL_REPRESENTATION('',(#50502),#50506); +#50502 = LINE('',#50503,#50504); +#50503 = CARTESIAN_POINT('',(0.35,3.7)); +#50504 = VECTOR('',#50505,1.); +#50505 = DIRECTION('',(1.,0.E+000)); +#50506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50507 = PCURVE('',#50508,#50513); +#50508 = PLANE('',#50509); +#50509 = AXIS2_PLACEMENT_3D('',#50510,#50511,#50512); +#50510 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); +#50511 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50512 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50513 = DEFINITIONAL_REPRESENTATION('',(#50514),#50518); +#50514 = LINE('',#50515,#50516); +#50515 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50516 = VECTOR('',#50517,1.); +#50517 = DIRECTION('',(1.,0.E+000)); +#50518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50519 = ORIENTED_EDGE('',*,*,#50520,.F.); +#50520 = EDGE_CURVE('',#50521,#50493,#50523,.T.); +#50521 = VERTEX_POINT('',#50522); +#50522 = CARTESIAN_POINT('',(-2.85,0.925,1.1)); +#50523 = SURFACE_CURVE('',#50524,(#50529,#50540),.PCURVE_S1.); +#50524 = CIRCLE('',#50525,0.125); +#50525 = AXIS2_PLACEMENT_3D('',#50526,#50527,#50528); +#50526 = CARTESIAN_POINT('',(-2.85,0.925,1.225)); +#50527 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50528 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50529 = PCURVE('',#49451,#50530); +#50530 = DEFINITIONAL_REPRESENTATION('',(#50531),#50539); +#50531 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50532,#50533,#50534,#50535 + ,#50536,#50537,#50538),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#48420 = CARTESIAN_POINT('',(0.287209438086,-0.15)); -#48421 = CARTESIAN_POINT('',(2.740181695085E-002,-0.6)); -#48422 = CARTESIAN_POINT('',(-0.232405804184,-0.15)); -#48423 = CARTESIAN_POINT('',(-0.49221342532,0.3)); -#48424 = CARTESIAN_POINT('',(2.740181695107E-002,0.3)); -#48425 = CARTESIAN_POINT('',(0.547017059222,0.3)); -#48426 = CARTESIAN_POINT('',(0.287209438086,-0.15)); -#48427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48428 = PCURVE('',#47716,#48429); -#48429 = DEFINITIONAL_REPRESENTATION('',(#48430),#48433); -#48430 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48431,#48432),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); -#48431 = CARTESIAN_POINT('',(3.665191429188,0.E+000)); -#48432 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#48433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48434 = ORIENTED_EDGE('',*,*,#47670,.T.); -#48435 = ORIENTED_EDGE('',*,*,#48436,.F.); -#48436 = EDGE_CURVE('',#48437,#47673,#48439,.T.); -#48437 = VERTEX_POINT('',#48438); -#48438 = CARTESIAN_POINT('',(2.725,1.225,1.35)); -#48439 = SURFACE_CURVE('',#48440,(#48444,#48451),.PCURVE_S1.); -#48440 = LINE('',#48441,#48442); -#48441 = CARTESIAN_POINT('',(2.725,1.225,1.35)); -#48442 = VECTOR('',#48443,1.); -#48443 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#48444 = PCURVE('',#47688,#48445); -#48445 = DEFINITIONAL_REPRESENTATION('',(#48446),#48450); -#48446 = LINE('',#48447,#48448); -#48447 = CARTESIAN_POINT('',(0.43,0.E+000)); -#48448 = VECTOR('',#48449,1.); -#48449 = DIRECTION('',(0.E+000,-1.)); -#48450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48451 = PCURVE('',#48001,#48452); -#48452 = DEFINITIONAL_REPRESENTATION('',(#48453),#48457); -#48453 = LINE('',#48454,#48455); -#48454 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#48455 = VECTOR('',#48456,1.); -#48456 = DIRECTION('',(0.E+000,-1.)); -#48457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48458 = ORIENTED_EDGE('',*,*,#48459,.F.); -#48459 = EDGE_CURVE('',#48460,#48437,#48462,.T.); -#48460 = VERTEX_POINT('',#48461); -#48461 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); -#48462 = SURFACE_CURVE('',#48463,(#48467,#48474),.PCURVE_S1.); -#48463 = LINE('',#48464,#48465); -#48464 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); -#48465 = VECTOR('',#48466,1.); -#48466 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#48467 = PCURVE('',#47688,#48468); -#48468 = DEFINITIONAL_REPRESENTATION('',(#48469),#48473); -#48469 = LINE('',#48470,#48471); -#48470 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); -#48471 = VECTOR('',#48472,1.); -#48472 = DIRECTION('',(1.,0.E+000)); -#48473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48474 = PCURVE('',#48475,#48480); -#48475 = PLANE('',#48476); -#48476 = AXIS2_PLACEMENT_3D('',#48477,#48478,#48479); -#48477 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); -#48478 = DIRECTION('',(0.E+000,1.,0.E+000)); -#48479 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48480 = DEFINITIONAL_REPRESENTATION('',(#48481),#48485); -#48481 = LINE('',#48482,#48483); -#48482 = CARTESIAN_POINT('',(0.475,3.756188021535)); -#48483 = VECTOR('',#48484,1.); -#48484 = DIRECTION('',(0.E+000,-1.)); -#48485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48486 = ORIENTED_EDGE('',*,*,#48487,.T.); -#48487 = EDGE_CURVE('',#48460,#48409,#48488,.T.); -#48488 = SURFACE_CURVE('',#48489,(#48493,#48500),.PCURVE_S1.); -#48489 = LINE('',#48490,#48491); -#48490 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); -#48491 = VECTOR('',#48492,1.); -#48492 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48493 = PCURVE('',#47688,#48494); -#48494 = DEFINITIONAL_REPRESENTATION('',(#48495),#48499); -#48495 = LINE('',#48496,#48497); -#48496 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); -#48497 = VECTOR('',#48498,1.); -#48498 = DIRECTION('',(-0.5,-0.866025403784)); -#48499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48500 = PCURVE('',#48501,#48506); -#48501 = PLANE('',#48502); -#48502 = AXIS2_PLACEMENT_3D('',#48503,#48504,#48505); -#48503 = CARTESIAN_POINT('',(2.725,1.305,1.36)); -#48504 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#48505 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48506 = DEFINITIONAL_REPRESENTATION('',(#48507),#48511); -#48507 = LINE('',#48508,#48509); -#48508 = CARTESIAN_POINT('',(9.237604307025E-002,0.E+000)); -#48509 = VECTOR('',#48510,1.); -#48510 = DIRECTION('',(1.,0.E+000)); -#48511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48512 = ADVANCED_FACE('',(#48513),#47716,.T.); -#48513 = FACE_BOUND('',#48514,.T.); -#48514 = EDGE_LOOP('',(#48515,#48538,#48558,#48559)); -#48515 = ORIENTED_EDGE('',*,*,#48516,.F.); -#48516 = EDGE_CURVE('',#48517,#47701,#48519,.T.); -#48517 = VERTEX_POINT('',#48518); -#48518 = CARTESIAN_POINT('',(2.025,1.075,1.492790561914)); -#48519 = SURFACE_CURVE('',#48520,(#48525,#48531),.PCURVE_S1.); -#48520 = CIRCLE('',#48521,0.3); -#48521 = AXIS2_PLACEMENT_3D('',#48522,#48523,#48524); -#48522 = CARTESIAN_POINT('',(2.025,1.225,1.752598183049)); -#48523 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48524 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#48525 = PCURVE('',#47716,#48526); -#48526 = DEFINITIONAL_REPRESENTATION('',(#48527),#48530); -#48527 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48528,#48529),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); -#48528 = CARTESIAN_POINT('',(3.665191429188,0.7)); -#48529 = CARTESIAN_POINT('',(4.712388980385,0.7)); -#48530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48531 = PCURVE('',#47743,#48532); -#48532 = DEFINITIONAL_REPRESENTATION('',(#48533),#48537); -#48533 = CIRCLE('',#48534,0.3); -#48534 = AXIS2_PLACEMENT_2D('',#48535,#48536); -#48535 = CARTESIAN_POINT('',(0.402598183049,0.E+000)); -#48536 = DIRECTION('',(-0.866025403784,-0.5)); -#48537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48538 = ORIENTED_EDGE('',*,*,#48539,.F.); -#48539 = EDGE_CURVE('',#48409,#48517,#48540,.T.); -#48540 = SURFACE_CURVE('',#48541,(#48545,#48551),.PCURVE_S1.); -#48541 = LINE('',#48542,#48543); -#48542 = CARTESIAN_POINT('',(2.725,1.075,1.492790561914)); -#48543 = VECTOR('',#48544,1.); -#48544 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48545 = PCURVE('',#47716,#48546); -#48546 = DEFINITIONAL_REPRESENTATION('',(#48547),#48550); -#48547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48548,#48549),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#48548 = CARTESIAN_POINT('',(3.665191429189,0.E+000)); -#48549 = CARTESIAN_POINT('',(3.665191429189,0.7)); -#48550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48551 = PCURVE('',#48501,#48552); -#48552 = DEFINITIONAL_REPRESENTATION('',(#48553),#48557); -#48553 = LINE('',#48554,#48555); -#48554 = CARTESIAN_POINT('',(0.265581123827,0.E+000)); -#48555 = VECTOR('',#48556,1.); -#48556 = DIRECTION('',(0.E+000,1.)); -#48557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48558 = ORIENTED_EDGE('',*,*,#48408,.T.); -#48559 = ORIENTED_EDGE('',*,*,#47700,.T.); -#48560 = ADVANCED_FACE('',(#48561),#47743,.F.); -#48561 = FACE_BOUND('',#48562,.F.); -#48562 = EDGE_LOOP('',(#48563,#48564,#48587,#48610,#48631)); -#48563 = ORIENTED_EDGE('',*,*,#48516,.F.); -#48564 = ORIENTED_EDGE('',*,*,#48565,.F.); -#48565 = EDGE_CURVE('',#48566,#48517,#48568,.T.); -#48566 = VERTEX_POINT('',#48567); -#48567 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); -#48568 = SURFACE_CURVE('',#48569,(#48573,#48580),.PCURVE_S1.); -#48569 = LINE('',#48570,#48571); -#48570 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); -#48571 = VECTOR('',#48572,1.); -#48572 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48573 = PCURVE('',#47743,#48574); -#48574 = DEFINITIONAL_REPRESENTATION('',(#48575),#48579); -#48575 = LINE('',#48576,#48577); -#48576 = CARTESIAN_POINT('',(5.6188021535E-002,0.E+000)); -#48577 = VECTOR('',#48578,1.); -#48578 = DIRECTION('',(0.5,-0.866025403784)); -#48579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48580 = PCURVE('',#48501,#48581); -#48581 = DEFINITIONAL_REPRESENTATION('',(#48582),#48586); -#48582 = LINE('',#48583,#48584); -#48583 = CARTESIAN_POINT('',(9.237604307025E-002,0.7)); -#48584 = VECTOR('',#48585,1.); -#48585 = DIRECTION('',(1.,0.E+000)); -#48586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48587 = ORIENTED_EDGE('',*,*,#48588,.F.); -#48588 = EDGE_CURVE('',#48589,#48566,#48591,.T.); -#48589 = VERTEX_POINT('',#48590); -#48590 = CARTESIAN_POINT('',(2.025,1.225,1.35)); -#48591 = SURFACE_CURVE('',#48592,(#48596,#48603),.PCURVE_S1.); -#48592 = LINE('',#48593,#48594); -#48593 = CARTESIAN_POINT('',(2.025,1.225,1.35)); -#48594 = VECTOR('',#48595,1.); -#48595 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48596 = PCURVE('',#47743,#48597); -#48597 = DEFINITIONAL_REPRESENTATION('',(#48598),#48602); -#48598 = LINE('',#48599,#48600); -#48599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#48600 = VECTOR('',#48601,1.); -#48601 = DIRECTION('',(1.,0.E+000)); -#48602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48603 = PCURVE('',#48475,#48604); -#48604 = DEFINITIONAL_REPRESENTATION('',(#48605),#48609); -#48605 = LINE('',#48606,#48607); -#48606 = CARTESIAN_POINT('',(1.175,3.7)); -#48607 = VECTOR('',#48608,1.); -#48608 = DIRECTION('',(0.E+000,1.)); -#48609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#50532 = CARTESIAN_POINT('',(0.35,3.45)); +#50533 = CARTESIAN_POINT('',(0.133493649054,3.45)); +#50534 = CARTESIAN_POINT('',(0.241746824527,3.6375)); +#50535 = CARTESIAN_POINT('',(0.35,3.825)); +#50536 = CARTESIAN_POINT('',(0.458253175473,3.6375)); +#50537 = CARTESIAN_POINT('',(0.566506350946,3.45)); +#50538 = CARTESIAN_POINT('',(0.35,3.45)); +#50539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50540 = PCURVE('',#50541,#50546); +#50541 = CYLINDRICAL_SURFACE('',#50542,0.125); +#50542 = AXIS2_PLACEMENT_3D('',#50543,#50544,#50545); +#50543 = CARTESIAN_POINT('',(-2.85,1.225,1.225)); +#50544 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50545 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50546 = DEFINITIONAL_REPRESENTATION('',(#50547),#50550); +#50547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50548,#50549),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); +#50548 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#50549 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#50550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50551 = ORIENTED_EDGE('',*,*,#50552,.F.); +#50552 = EDGE_CURVE('',#50553,#50521,#50555,.T.); +#50553 = VERTEX_POINT('',#50554); +#50554 = CARTESIAN_POINT('',(-2.725,0.925,1.1)); +#50555 = SURFACE_CURVE('',#50556,(#50560,#50567),.PCURVE_S1.); +#50556 = LINE('',#50557,#50558); +#50557 = CARTESIAN_POINT('',(-2.725,0.925,1.1)); +#50558 = VECTOR('',#50559,1.); +#50559 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50560 = PCURVE('',#49451,#50561); +#50561 = DEFINITIONAL_REPRESENTATION('',(#50562),#50566); +#50562 = LINE('',#50563,#50564); +#50563 = CARTESIAN_POINT('',(0.475,3.45)); +#50564 = VECTOR('',#50565,1.); +#50565 = DIRECTION('',(-1.,0.E+000)); +#50566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50567 = PCURVE('',#50568,#50573); +#50568 = PLANE('',#50569); +#50569 = AXIS2_PLACEMENT_3D('',#50570,#50571,#50572); +#50570 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); +#50571 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50572 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50573 = DEFINITIONAL_REPRESENTATION('',(#50574),#50578); +#50574 = LINE('',#50575,#50576); +#50575 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50576 = VECTOR('',#50577,1.); +#50577 = DIRECTION('',(1.,0.E+000)); +#50578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50579 = ORIENTED_EDGE('',*,*,#50580,.F.); +#50580 = EDGE_CURVE('',#50581,#50553,#50583,.T.); +#50581 = VERTEX_POINT('',#50582); +#50582 = CARTESIAN_POINT('',(-2.725,0.925,-0.12)); +#50583 = SURFACE_CURVE('',#50584,(#50588,#50595),.PCURVE_S1.); +#50584 = LINE('',#50585,#50586); +#50585 = CARTESIAN_POINT('',(-2.725,0.925,-0.12)); +#50586 = VECTOR('',#50587,1.); +#50587 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50588 = PCURVE('',#49451,#50589); +#50589 = DEFINITIONAL_REPRESENTATION('',(#50590),#50594); +#50590 = LINE('',#50591,#50592); +#50591 = CARTESIAN_POINT('',(0.475,2.23)); +#50592 = VECTOR('',#50593,1.); +#50593 = DIRECTION('',(0.E+000,1.)); +#50594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50595 = PCURVE('',#50596,#50601); +#50596 = PLANE('',#50597); +#50597 = AXIS2_PLACEMENT_3D('',#50598,#50599,#50600); +#50598 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); +#50599 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50600 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50601 = DEFINITIONAL_REPRESENTATION('',(#50602),#50606); +#50602 = LINE('',#50603,#50604); +#50603 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50604 = VECTOR('',#50605,1.); +#50605 = DIRECTION('',(1.,0.E+000)); +#50606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50607 = ORIENTED_EDGE('',*,*,#50608,.F.); +#50608 = EDGE_CURVE('',#50609,#50581,#50611,.T.); +#50609 = VERTEX_POINT('',#50610); +#50610 = CARTESIAN_POINT('',(-2.025,0.925,-0.12)); +#50611 = SURFACE_CURVE('',#50612,(#50616,#50623),.PCURVE_S1.); +#50612 = LINE('',#50613,#50614); +#50613 = CARTESIAN_POINT('',(-2.025,0.925,-0.12)); +#50614 = VECTOR('',#50615,1.); +#50615 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50616 = PCURVE('',#49451,#50617); +#50617 = DEFINITIONAL_REPRESENTATION('',(#50618),#50622); +#50618 = LINE('',#50619,#50620); +#50619 = CARTESIAN_POINT('',(1.175,2.23)); +#50620 = VECTOR('',#50621,1.); +#50621 = DIRECTION('',(-1.,0.E+000)); +#50622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#48610 = ORIENTED_EDGE('',*,*,#48611,.T.); -#48611 = EDGE_CURVE('',#48589,#47728,#48612,.T.); -#48612 = SURFACE_CURVE('',#48613,(#48617,#48624),.PCURVE_S1.); -#48613 = LINE('',#48614,#48615); -#48614 = CARTESIAN_POINT('',(2.025,1.225,1.35)); -#48615 = VECTOR('',#48616,1.); -#48616 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#48617 = PCURVE('',#47743,#48618); -#48618 = DEFINITIONAL_REPRESENTATION('',(#48619),#48623); -#48619 = LINE('',#48620,#48621); -#48620 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#48621 = VECTOR('',#48622,1.); -#48622 = DIRECTION('',(0.E+000,-1.)); -#48623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48624 = PCURVE('',#47771,#48625); -#48625 = DEFINITIONAL_REPRESENTATION('',(#48626),#48630); -#48626 = LINE('',#48627,#48628); -#48627 = CARTESIAN_POINT('',(0.125,0.E+000)); -#48628 = VECTOR('',#48629,1.); -#48629 = DIRECTION('',(0.E+000,-1.)); -#48630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48631 = ORIENTED_EDGE('',*,*,#47727,.T.); -#48632 = ADVANCED_FACE('',(#48633),#48501,.T.); -#48633 = FACE_BOUND('',#48634,.F.); -#48634 = EDGE_LOOP('',(#48635,#48636,#48637,#48638,#48666,#48694)); -#48635 = ORIENTED_EDGE('',*,*,#48565,.T.); -#48636 = ORIENTED_EDGE('',*,*,#48539,.F.); -#48637 = ORIENTED_EDGE('',*,*,#48487,.F.); -#48638 = ORIENTED_EDGE('',*,*,#48639,.F.); -#48639 = EDGE_CURVE('',#48640,#48460,#48642,.T.); -#48640 = VERTEX_POINT('',#48641); -#48641 = CARTESIAN_POINT('',(2.725,1.305,1.36)); -#48642 = SURFACE_CURVE('',#48643,(#48647,#48654),.PCURVE_S1.); -#48643 = LINE('',#48644,#48645); -#48644 = CARTESIAN_POINT('',(2.725,1.305,1.36)); -#48645 = VECTOR('',#48646,1.); -#48646 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48647 = PCURVE('',#48501,#48648); -#48648 = DEFINITIONAL_REPRESENTATION('',(#48649),#48653); -#48649 = LINE('',#48650,#48651); -#48650 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#48651 = VECTOR('',#48652,1.); -#48652 = DIRECTION('',(1.,0.E+000)); -#48653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#50623 = PCURVE('',#50624,#50629); +#50624 = PLANE('',#50625); +#50625 = AXIS2_PLACEMENT_3D('',#50626,#50627,#50628); +#50626 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); +#50627 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50628 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50629 = DEFINITIONAL_REPRESENTATION('',(#50630),#50634); +#50630 = LINE('',#50631,#50632); +#50631 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50632 = VECTOR('',#50633,1.); +#50633 = DIRECTION('',(1.,0.E+000)); +#50634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#48654 = PCURVE('',#48655,#48660); -#48655 = PLANE('',#48656); -#48656 = AXIS2_PLACEMENT_3D('',#48657,#48658,#48659); -#48657 = CARTESIAN_POINT('',(2.725,0.E+000,0.E+000)); -#48658 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48659 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48660 = DEFINITIONAL_REPRESENTATION('',(#48661),#48665); -#48661 = LINE('',#48662,#48663); -#48662 = CARTESIAN_POINT('',(1.36,1.305)); -#48663 = VECTOR('',#48664,1.); -#48664 = DIRECTION('',(0.5,-0.866025403784)); -#48665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48666 = ORIENTED_EDGE('',*,*,#48667,.T.); -#48667 = EDGE_CURVE('',#48640,#48668,#48670,.T.); -#48668 = VERTEX_POINT('',#48669); -#48669 = CARTESIAN_POINT('',(2.025,1.305,1.36)); -#48670 = SURFACE_CURVE('',#48671,(#48675,#48682),.PCURVE_S1.); -#48671 = LINE('',#48672,#48673); -#48672 = CARTESIAN_POINT('',(2.725,1.305,1.36)); -#48673 = VECTOR('',#48674,1.); -#48674 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48675 = PCURVE('',#48501,#48676); -#48676 = DEFINITIONAL_REPRESENTATION('',(#48677),#48681); -#48677 = LINE('',#48678,#48679); -#48678 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#48679 = VECTOR('',#48680,1.); -#48680 = DIRECTION('',(0.E+000,1.)); -#48681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48682 = PCURVE('',#48683,#48688); -#48683 = PLANE('',#48684); -#48684 = AXIS2_PLACEMENT_3D('',#48685,#48686,#48687); -#48685 = CARTESIAN_POINT('',(2.725,1.455,1.619807621135)); -#48686 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#48687 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#48688 = DEFINITIONAL_REPRESENTATION('',(#48689),#48693); -#48689 = LINE('',#48690,#48691); -#48690 = CARTESIAN_POINT('',(0.3,0.E+000)); -#48691 = VECTOR('',#48692,1.); -#48692 = DIRECTION('',(0.E+000,1.)); -#48693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48694 = ORIENTED_EDGE('',*,*,#48695,.T.); -#48695 = EDGE_CURVE('',#48668,#48566,#48696,.T.); -#48696 = SURFACE_CURVE('',#48697,(#48701,#48708),.PCURVE_S1.); -#48697 = LINE('',#48698,#48699); -#48698 = CARTESIAN_POINT('',(2.025,1.305,1.36)); -#48699 = VECTOR('',#48700,1.); -#48700 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48701 = PCURVE('',#48501,#48702); -#48702 = DEFINITIONAL_REPRESENTATION('',(#48703),#48707); -#48703 = LINE('',#48704,#48705); -#48704 = CARTESIAN_POINT('',(0.E+000,0.7)); -#48705 = VECTOR('',#48706,1.); -#48706 = DIRECTION('',(1.,0.E+000)); -#48707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48708 = PCURVE('',#48709,#48714); -#48709 = PLANE('',#48710); -#48710 = AXIS2_PLACEMENT_3D('',#48711,#48712,#48713); -#48711 = CARTESIAN_POINT('',(2.025,0.E+000,0.E+000)); -#48712 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48713 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48714 = DEFINITIONAL_REPRESENTATION('',(#48715),#48719); -#48715 = LINE('',#48716,#48717); -#48716 = CARTESIAN_POINT('',(1.36,1.305)); -#48717 = VECTOR('',#48718,1.); -#48718 = DIRECTION('',(0.5,-0.866025403784)); -#48719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48720 = ADVANCED_FACE('',(#48721),#48655,.F.); -#48721 = FACE_BOUND('',#48722,.F.); -#48722 = EDGE_LOOP('',(#48723,#48775,#48796,#48797)); -#48723 = ORIENTED_EDGE('',*,*,#48724,.F.); -#48724 = EDGE_CURVE('',#48725,#48727,#48729,.T.); -#48725 = VERTEX_POINT('',#48726); -#48726 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); -#48727 = VERTEX_POINT('',#48728); -#48728 = CARTESIAN_POINT('',(2.725,1.225,1.521658075373)); -#48729 = SURFACE_CURVE('',#48730,(#48734,#48741),.PCURVE_S1.); -#48730 = LINE('',#48731,#48732); -#48731 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); -#48732 = VECTOR('',#48733,1.); -#48733 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48734 = PCURVE('',#48655,#48735); -#48735 = DEFINITIONAL_REPRESENTATION('',(#48736),#48740); -#48736 = LINE('',#48737,#48738); -#48737 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#48738 = VECTOR('',#48739,1.); -#48739 = DIRECTION('',(0.5,-0.866025403784)); -#48740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48741 = PCURVE('',#48742,#48747); -#48742 = CYLINDRICAL_SURFACE('',#48743,0.2); -#48743 = AXIS2_PLACEMENT_3D('',#48744,#48745,#48746); -#48744 = CARTESIAN_POINT('',(2.525,1.374406430719,1.435398232379)); -#48745 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48746 = DIRECTION('',(1.,0.E+000,0.E+000)); -#48747 = DEFINITIONAL_REPRESENTATION('',(#48748),#48774); -#48748 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48749,#48750,#48751,#48752, - #48753,#48754,#48755,#48756,#48757,#48758,#48759,#48760,#48761, - #48762,#48763,#48764,#48765,#48766,#48767,#48768,#48769,#48770, - #48771,#48772,#48773),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#50635 = ORIENTED_EDGE('',*,*,#50636,.F.); +#50636 = EDGE_CURVE('',#50637,#50609,#50639,.T.); +#50637 = VERTEX_POINT('',#50638); +#50638 = CARTESIAN_POINT('',(-2.025,0.925,1.1)); +#50639 = SURFACE_CURVE('',#50640,(#50644,#50651),.PCURVE_S1.); +#50640 = LINE('',#50641,#50642); +#50641 = CARTESIAN_POINT('',(-2.025,0.925,1.1)); +#50642 = VECTOR('',#50643,1.); +#50643 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50644 = PCURVE('',#49451,#50645); +#50645 = DEFINITIONAL_REPRESENTATION('',(#50646),#50650); +#50646 = LINE('',#50647,#50648); +#50647 = CARTESIAN_POINT('',(1.175,3.45)); +#50648 = VECTOR('',#50649,1.); +#50649 = DIRECTION('',(0.E+000,-1.)); +#50650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50651 = PCURVE('',#50652,#50657); +#50652 = PLANE('',#50653); +#50653 = AXIS2_PLACEMENT_3D('',#50654,#50655,#50656); +#50654 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); +#50655 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50656 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50657 = DEFINITIONAL_REPRESENTATION('',(#50658),#50662); +#50658 = LINE('',#50659,#50660); +#50659 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50660 = VECTOR('',#50661,1.); +#50661 = DIRECTION('',(1.,0.E+000)); +#50662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50663 = ORIENTED_EDGE('',*,*,#50664,.F.); +#50664 = EDGE_CURVE('',#50665,#50637,#50667,.T.); +#50665 = VERTEX_POINT('',#50666); +#50666 = CARTESIAN_POINT('',(-1.9,0.925,1.1)); +#50667 = SURFACE_CURVE('',#50668,(#50672,#50679),.PCURVE_S1.); +#50668 = LINE('',#50669,#50670); +#50669 = CARTESIAN_POINT('',(-1.9,0.925,1.1)); +#50670 = VECTOR('',#50671,1.); +#50671 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50672 = PCURVE('',#49451,#50673); +#50673 = DEFINITIONAL_REPRESENTATION('',(#50674),#50678); +#50674 = LINE('',#50675,#50676); +#50675 = CARTESIAN_POINT('',(1.3,3.45)); +#50676 = VECTOR('',#50677,1.); +#50677 = DIRECTION('',(-1.,0.E+000)); +#50678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50679 = PCURVE('',#50680,#50685); +#50680 = PLANE('',#50681); +#50681 = AXIS2_PLACEMENT_3D('',#50682,#50683,#50684); +#50682 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); +#50683 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50684 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50685 = DEFINITIONAL_REPRESENTATION('',(#50686),#50690); +#50686 = LINE('',#50687,#50688); +#50687 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50688 = VECTOR('',#50689,1.); +#50689 = DIRECTION('',(1.,0.E+000)); +#50690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50691 = ORIENTED_EDGE('',*,*,#50692,.F.); +#50692 = EDGE_CURVE('',#50693,#50665,#50695,.T.); +#50693 = VERTEX_POINT('',#50694); +#50694 = CARTESIAN_POINT('',(-1.9,0.925,1.35)); +#50695 = SURFACE_CURVE('',#50696,(#50701,#50712),.PCURVE_S1.); +#50696 = CIRCLE('',#50697,0.125); +#50697 = AXIS2_PLACEMENT_3D('',#50698,#50699,#50700); +#50698 = CARTESIAN_POINT('',(-1.9,0.925,1.225)); +#50699 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50700 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50701 = PCURVE('',#49451,#50702); +#50702 = DEFINITIONAL_REPRESENTATION('',(#50703),#50711); +#50703 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50704,#50705,#50706,#50707 + ,#50708,#50709,#50710),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#50704 = CARTESIAN_POINT('',(1.3,3.7)); +#50705 = CARTESIAN_POINT('',(1.516506350946,3.7)); +#50706 = CARTESIAN_POINT('',(1.408253175473,3.5125)); +#50707 = CARTESIAN_POINT('',(1.3,3.325)); +#50708 = CARTESIAN_POINT('',(1.191746824527,3.5125)); +#50709 = CARTESIAN_POINT('',(1.083493649054,3.7)); +#50710 = CARTESIAN_POINT('',(1.3,3.7)); +#50711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50712 = PCURVE('',#50713,#50718); +#50713 = CYLINDRICAL_SURFACE('',#50714,0.125); +#50714 = AXIS2_PLACEMENT_3D('',#50715,#50716,#50717); +#50715 = CARTESIAN_POINT('',(-1.9,1.225,1.225)); +#50716 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50717 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50718 = DEFINITIONAL_REPRESENTATION('',(#50719),#50722); +#50719 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50720,#50721),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); +#50720 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); +#50721 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#50722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50723 = ORIENTED_EDGE('',*,*,#50724,.F.); +#50724 = EDGE_CURVE('',#50410,#50693,#50725,.T.); +#50725 = SURFACE_CURVE('',#50726,(#50730,#50737),.PCURVE_S1.); +#50726 = LINE('',#50727,#50728); +#50727 = CARTESIAN_POINT('',(-2.025,0.925,1.35)); +#50728 = VECTOR('',#50729,1.); +#50729 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50730 = PCURVE('',#49451,#50731); +#50731 = DEFINITIONAL_REPRESENTATION('',(#50732),#50736); +#50732 = LINE('',#50733,#50734); +#50733 = CARTESIAN_POINT('',(1.175,3.7)); +#50734 = VECTOR('',#50735,1.); +#50735 = DIRECTION('',(1.,0.E+000)); +#50736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50737 = PCURVE('',#50738,#50743); +#50738 = PLANE('',#50739); +#50739 = AXIS2_PLACEMENT_3D('',#50740,#50741,#50742); +#50740 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); +#50741 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50743 = DEFINITIONAL_REPRESENTATION('',(#50744),#50748); +#50744 = LINE('',#50745,#50746); +#50745 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#50746 = VECTOR('',#50747,1.); +#50747 = DIRECTION('',(1.,0.E+000)); +#50748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50749 = FACE_BOUND('',#50750,.F.); +#50750 = EDGE_LOOP('',(#50751,#50774,#50794,#50795)); +#50751 = ORIENTED_EDGE('',*,*,#50752,.T.); +#50752 = EDGE_CURVE('',#49515,#50753,#50755,.T.); +#50753 = VERTEX_POINT('',#50754); +#50754 = CARTESIAN_POINT('',(0.41,0.925,-1.18)); +#50755 = SURFACE_CURVE('',#50756,(#50760,#50767),.PCURVE_S1.); +#50756 = LINE('',#50757,#50758); +#50757 = CARTESIAN_POINT('',(0.41,0.925,-1.75)); +#50758 = VECTOR('',#50759,1.); +#50759 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50760 = PCURVE('',#49451,#50761); +#50761 = DEFINITIONAL_REPRESENTATION('',(#50762),#50766); +#50762 = LINE('',#50763,#50764); +#50763 = CARTESIAN_POINT('',(3.61,0.6)); +#50764 = VECTOR('',#50765,1.); +#50765 = DIRECTION('',(0.E+000,1.)); +#50766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50767 = PCURVE('',#49575,#50768); +#50768 = DEFINITIONAL_REPRESENTATION('',(#50769),#50773); +#50769 = LINE('',#50770,#50771); +#50770 = CARTESIAN_POINT('',(1.75,0.925)); +#50771 = VECTOR('',#50772,1.); +#50772 = DIRECTION('',(-1.,0.E+000)); +#50773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50774 = ORIENTED_EDGE('',*,*,#50775,.F.); +#50775 = EDGE_CURVE('',#49436,#50753,#50776,.T.); +#50776 = SURFACE_CURVE('',#50777,(#50781,#50788),.PCURVE_S1.); +#50777 = LINE('',#50778,#50779); +#50778 = CARTESIAN_POINT('',(-0.41,0.925,-1.18)); +#50779 = VECTOR('',#50780,1.); +#50780 = DIRECTION('',(1.,0.E+000,0.E+000)); +#50781 = PCURVE('',#49451,#50782); +#50782 = DEFINITIONAL_REPRESENTATION('',(#50783),#50787); +#50783 = LINE('',#50784,#50785); +#50784 = CARTESIAN_POINT('',(2.79,1.17)); +#50785 = VECTOR('',#50786,1.); +#50786 = DIRECTION('',(1.,0.E+000)); +#50787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50788 = PCURVE('',#49478,#50789); +#50789 = DEFINITIONAL_REPRESENTATION('',(#50790),#50793); +#50790 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50791,#50792),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); +#50791 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#50792 = CARTESIAN_POINT('',(3.14159265359,0.82)); +#50793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50794 = ORIENTED_EDGE('',*,*,#49435,.T.); +#50795 = ORIENTED_EDGE('',*,*,#49514,.T.); +#50796 = ADVANCED_FACE('',(#50797),#50080,.F.); +#50797 = FACE_BOUND('',#50798,.F.); +#50798 = EDGE_LOOP('',(#50799,#50826,#50827,#50850,#50878)); +#50799 = ORIENTED_EDGE('',*,*,#50800,.T.); +#50800 = EDGE_CURVE('',#50801,#50063,#50803,.T.); +#50801 = VERTEX_POINT('',#50802); +#50802 = CARTESIAN_POINT('',(2.725,1.075,1.492790561914)); +#50803 = SURFACE_CURVE('',#50804,(#50809,#50820),.PCURVE_S1.); +#50804 = CIRCLE('',#50805,0.3); +#50805 = AXIS2_PLACEMENT_3D('',#50806,#50807,#50808); +#50806 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); +#50807 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50808 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#50809 = PCURVE('',#50080,#50810); +#50810 = DEFINITIONAL_REPRESENTATION('',(#50811),#50819); +#50811 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50812,#50813,#50814,#50815 + ,#50816,#50817,#50818),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#50812 = CARTESIAN_POINT('',(0.287209438086,-0.15)); +#50813 = CARTESIAN_POINT('',(2.740181695085E-002,-0.6)); +#50814 = CARTESIAN_POINT('',(-0.232405804184,-0.15)); +#50815 = CARTESIAN_POINT('',(-0.49221342532,0.3)); +#50816 = CARTESIAN_POINT('',(2.740181695107E-002,0.3)); +#50817 = CARTESIAN_POINT('',(0.547017059222,0.3)); +#50818 = CARTESIAN_POINT('',(0.287209438086,-0.15)); +#50819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50820 = PCURVE('',#50108,#50821); +#50821 = DEFINITIONAL_REPRESENTATION('',(#50822),#50825); +#50822 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50823,#50824),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); +#50823 = CARTESIAN_POINT('',(3.665191429188,0.E+000)); +#50824 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#50825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50826 = ORIENTED_EDGE('',*,*,#50062,.T.); +#50827 = ORIENTED_EDGE('',*,*,#50828,.F.); +#50828 = EDGE_CURVE('',#50829,#50065,#50831,.T.); +#50829 = VERTEX_POINT('',#50830); +#50830 = CARTESIAN_POINT('',(2.725,1.225,1.35)); +#50831 = SURFACE_CURVE('',#50832,(#50836,#50843),.PCURVE_S1.); +#50832 = LINE('',#50833,#50834); +#50833 = CARTESIAN_POINT('',(2.725,1.225,1.35)); +#50834 = VECTOR('',#50835,1.); +#50835 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#50836 = PCURVE('',#50080,#50837); +#50837 = DEFINITIONAL_REPRESENTATION('',(#50838),#50842); +#50838 = LINE('',#50839,#50840); +#50839 = CARTESIAN_POINT('',(0.43,0.E+000)); +#50840 = VECTOR('',#50841,1.); +#50841 = DIRECTION('',(0.E+000,-1.)); +#50842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50843 = PCURVE('',#50393,#50844); +#50844 = DEFINITIONAL_REPRESENTATION('',(#50845),#50849); +#50845 = LINE('',#50846,#50847); +#50846 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#50847 = VECTOR('',#50848,1.); +#50848 = DIRECTION('',(0.E+000,-1.)); +#50849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50850 = ORIENTED_EDGE('',*,*,#50851,.F.); +#50851 = EDGE_CURVE('',#50852,#50829,#50854,.T.); +#50852 = VERTEX_POINT('',#50853); +#50853 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); +#50854 = SURFACE_CURVE('',#50855,(#50859,#50866),.PCURVE_S1.); +#50855 = LINE('',#50856,#50857); +#50856 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); +#50857 = VECTOR('',#50858,1.); +#50858 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#50859 = PCURVE('',#50080,#50860); +#50860 = DEFINITIONAL_REPRESENTATION('',(#50861),#50865); +#50861 = LINE('',#50862,#50863); +#50862 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); +#50863 = VECTOR('',#50864,1.); +#50864 = DIRECTION('',(1.,0.E+000)); +#50865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50866 = PCURVE('',#50867,#50872); +#50867 = PLANE('',#50868); +#50868 = AXIS2_PLACEMENT_3D('',#50869,#50870,#50871); +#50869 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); +#50870 = DIRECTION('',(0.E+000,1.,0.E+000)); +#50871 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50872 = DEFINITIONAL_REPRESENTATION('',(#50873),#50877); +#50873 = LINE('',#50874,#50875); +#50874 = CARTESIAN_POINT('',(0.475,3.756188021535)); +#50875 = VECTOR('',#50876,1.); +#50876 = DIRECTION('',(0.E+000,-1.)); +#50877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50878 = ORIENTED_EDGE('',*,*,#50879,.T.); +#50879 = EDGE_CURVE('',#50852,#50801,#50880,.T.); +#50880 = SURFACE_CURVE('',#50881,(#50885,#50892),.PCURVE_S1.); +#50881 = LINE('',#50882,#50883); +#50882 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); +#50883 = VECTOR('',#50884,1.); +#50884 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#50885 = PCURVE('',#50080,#50886); +#50886 = DEFINITIONAL_REPRESENTATION('',(#50887),#50891); +#50887 = LINE('',#50888,#50889); +#50888 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); +#50889 = VECTOR('',#50890,1.); +#50890 = DIRECTION('',(-0.5,-0.866025403784)); +#50891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50892 = PCURVE('',#50893,#50898); +#50893 = PLANE('',#50894); +#50894 = AXIS2_PLACEMENT_3D('',#50895,#50896,#50897); +#50895 = CARTESIAN_POINT('',(2.725,1.305,1.36)); +#50896 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#50897 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#50898 = DEFINITIONAL_REPRESENTATION('',(#50899),#50903); +#50899 = LINE('',#50900,#50901); +#50900 = CARTESIAN_POINT('',(9.237604307025E-002,0.E+000)); +#50901 = VECTOR('',#50902,1.); +#50902 = DIRECTION('',(1.,0.E+000)); +#50903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50904 = ADVANCED_FACE('',(#50905),#50108,.T.); +#50905 = FACE_BOUND('',#50906,.T.); +#50906 = EDGE_LOOP('',(#50907,#50930,#50950,#50951)); +#50907 = ORIENTED_EDGE('',*,*,#50908,.F.); +#50908 = EDGE_CURVE('',#50909,#50093,#50911,.T.); +#50909 = VERTEX_POINT('',#50910); +#50910 = CARTESIAN_POINT('',(2.025,1.075,1.492790561914)); +#50911 = SURFACE_CURVE('',#50912,(#50917,#50923),.PCURVE_S1.); +#50912 = CIRCLE('',#50913,0.3); +#50913 = AXIS2_PLACEMENT_3D('',#50914,#50915,#50916); +#50914 = CARTESIAN_POINT('',(2.025,1.225,1.752598183049)); +#50915 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50916 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#50917 = PCURVE('',#50108,#50918); +#50918 = DEFINITIONAL_REPRESENTATION('',(#50919),#50922); +#50919 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50920,#50921),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); +#50920 = CARTESIAN_POINT('',(3.665191429188,0.7)); +#50921 = CARTESIAN_POINT('',(4.712388980385,0.7)); +#50922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50923 = PCURVE('',#50135,#50924); +#50924 = DEFINITIONAL_REPRESENTATION('',(#50925),#50929); +#50925 = CIRCLE('',#50926,0.3); +#50926 = AXIS2_PLACEMENT_2D('',#50927,#50928); +#50927 = CARTESIAN_POINT('',(0.402598183049,0.E+000)); +#50928 = DIRECTION('',(-0.866025403784,-0.5)); +#50929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50930 = ORIENTED_EDGE('',*,*,#50931,.F.); +#50931 = EDGE_CURVE('',#50801,#50909,#50932,.T.); +#50932 = SURFACE_CURVE('',#50933,(#50937,#50943),.PCURVE_S1.); +#50933 = LINE('',#50934,#50935); +#50934 = CARTESIAN_POINT('',(2.725,1.075,1.492790561914)); +#50935 = VECTOR('',#50936,1.); +#50936 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#50937 = PCURVE('',#50108,#50938); +#50938 = DEFINITIONAL_REPRESENTATION('',(#50939),#50942); +#50939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50940,#50941),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); +#50940 = CARTESIAN_POINT('',(3.665191429189,0.E+000)); +#50941 = CARTESIAN_POINT('',(3.665191429189,0.7)); +#50942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50943 = PCURVE('',#50893,#50944); +#50944 = DEFINITIONAL_REPRESENTATION('',(#50945),#50949); +#50945 = LINE('',#50946,#50947); +#50946 = CARTESIAN_POINT('',(0.265581123827,0.E+000)); +#50947 = VECTOR('',#50948,1.); +#50948 = DIRECTION('',(0.E+000,1.)); +#50949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50950 = ORIENTED_EDGE('',*,*,#50800,.T.); +#50951 = ORIENTED_EDGE('',*,*,#50092,.T.); +#50952 = ADVANCED_FACE('',(#50953),#50135,.F.); +#50953 = FACE_BOUND('',#50954,.F.); +#50954 = EDGE_LOOP('',(#50955,#50956,#50979,#51002,#51023)); +#50955 = ORIENTED_EDGE('',*,*,#50908,.F.); +#50956 = ORIENTED_EDGE('',*,*,#50957,.F.); +#50957 = EDGE_CURVE('',#50958,#50909,#50960,.T.); +#50958 = VERTEX_POINT('',#50959); +#50959 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); +#50960 = SURFACE_CURVE('',#50961,(#50965,#50972),.PCURVE_S1.); +#50961 = LINE('',#50962,#50963); +#50962 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); +#50963 = VECTOR('',#50964,1.); +#50964 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#50965 = PCURVE('',#50135,#50966); +#50966 = DEFINITIONAL_REPRESENTATION('',(#50967),#50971); +#50967 = LINE('',#50968,#50969); +#50968 = CARTESIAN_POINT('',(5.6188021535E-002,0.E+000)); +#50969 = VECTOR('',#50970,1.); +#50970 = DIRECTION('',(0.5,-0.866025403784)); +#50971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50972 = PCURVE('',#50893,#50973); +#50973 = DEFINITIONAL_REPRESENTATION('',(#50974),#50978); +#50974 = LINE('',#50975,#50976); +#50975 = CARTESIAN_POINT('',(9.237604307025E-002,0.7)); +#50976 = VECTOR('',#50977,1.); +#50977 = DIRECTION('',(1.,0.E+000)); +#50978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50979 = ORIENTED_EDGE('',*,*,#50980,.F.); +#50980 = EDGE_CURVE('',#50981,#50958,#50983,.T.); +#50981 = VERTEX_POINT('',#50982); +#50982 = CARTESIAN_POINT('',(2.025,1.225,1.35)); +#50983 = SURFACE_CURVE('',#50984,(#50988,#50995),.PCURVE_S1.); +#50984 = LINE('',#50985,#50986); +#50985 = CARTESIAN_POINT('',(2.025,1.225,1.35)); +#50986 = VECTOR('',#50987,1.); +#50987 = DIRECTION('',(0.E+000,0.E+000,1.)); +#50988 = PCURVE('',#50135,#50989); +#50989 = DEFINITIONAL_REPRESENTATION('',(#50990),#50994); +#50990 = LINE('',#50991,#50992); +#50991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#50992 = VECTOR('',#50993,1.); +#50993 = DIRECTION('',(1.,0.E+000)); +#50994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#50995 = PCURVE('',#50867,#50996); +#50996 = DEFINITIONAL_REPRESENTATION('',(#50997),#51001); +#50997 = LINE('',#50998,#50999); +#50998 = CARTESIAN_POINT('',(1.175,3.7)); +#50999 = VECTOR('',#51000,1.); +#51000 = DIRECTION('',(0.E+000,1.)); +#51001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51002 = ORIENTED_EDGE('',*,*,#51003,.T.); +#51003 = EDGE_CURVE('',#50981,#50120,#51004,.T.); +#51004 = SURFACE_CURVE('',#51005,(#51009,#51016),.PCURVE_S1.); +#51005 = LINE('',#51006,#51007); +#51006 = CARTESIAN_POINT('',(2.025,1.225,1.35)); +#51007 = VECTOR('',#51008,1.); +#51008 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#51009 = PCURVE('',#50135,#51010); +#51010 = DEFINITIONAL_REPRESENTATION('',(#51011),#51015); +#51011 = LINE('',#51012,#51013); +#51012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51013 = VECTOR('',#51014,1.); +#51014 = DIRECTION('',(0.E+000,-1.)); +#51015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51016 = PCURVE('',#50163,#51017); +#51017 = DEFINITIONAL_REPRESENTATION('',(#51018),#51022); +#51018 = LINE('',#51019,#51020); +#51019 = CARTESIAN_POINT('',(0.125,0.E+000)); +#51020 = VECTOR('',#51021,1.); +#51021 = DIRECTION('',(0.E+000,-1.)); +#51022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51023 = ORIENTED_EDGE('',*,*,#50119,.T.); +#51024 = ADVANCED_FACE('',(#51025),#50893,.T.); +#51025 = FACE_BOUND('',#51026,.F.); +#51026 = EDGE_LOOP('',(#51027,#51028,#51029,#51030,#51058,#51086)); +#51027 = ORIENTED_EDGE('',*,*,#50957,.T.); +#51028 = ORIENTED_EDGE('',*,*,#50931,.F.); +#51029 = ORIENTED_EDGE('',*,*,#50879,.F.); +#51030 = ORIENTED_EDGE('',*,*,#51031,.F.); +#51031 = EDGE_CURVE('',#51032,#50852,#51034,.T.); +#51032 = VERTEX_POINT('',#51033); +#51033 = CARTESIAN_POINT('',(2.725,1.305,1.36)); +#51034 = SURFACE_CURVE('',#51035,(#51039,#51046),.PCURVE_S1.); +#51035 = LINE('',#51036,#51037); +#51036 = CARTESIAN_POINT('',(2.725,1.305,1.36)); +#51037 = VECTOR('',#51038,1.); +#51038 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#51039 = PCURVE('',#50893,#51040); +#51040 = DEFINITIONAL_REPRESENTATION('',(#51041),#51045); +#51041 = LINE('',#51042,#51043); +#51042 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51043 = VECTOR('',#51044,1.); +#51044 = DIRECTION('',(1.,0.E+000)); +#51045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51046 = PCURVE('',#51047,#51052); +#51047 = PLANE('',#51048); +#51048 = AXIS2_PLACEMENT_3D('',#51049,#51050,#51051); +#51049 = CARTESIAN_POINT('',(2.725,0.E+000,0.E+000)); +#51050 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51051 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51052 = DEFINITIONAL_REPRESENTATION('',(#51053),#51057); +#51053 = LINE('',#51054,#51055); +#51054 = CARTESIAN_POINT('',(1.36,1.305)); +#51055 = VECTOR('',#51056,1.); +#51056 = DIRECTION('',(0.5,-0.866025403784)); +#51057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51058 = ORIENTED_EDGE('',*,*,#51059,.T.); +#51059 = EDGE_CURVE('',#51032,#51060,#51062,.T.); +#51060 = VERTEX_POINT('',#51061); +#51061 = CARTESIAN_POINT('',(2.025,1.305,1.36)); +#51062 = SURFACE_CURVE('',#51063,(#51067,#51074),.PCURVE_S1.); +#51063 = LINE('',#51064,#51065); +#51064 = CARTESIAN_POINT('',(2.725,1.305,1.36)); +#51065 = VECTOR('',#51066,1.); +#51066 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51067 = PCURVE('',#50893,#51068); +#51068 = DEFINITIONAL_REPRESENTATION('',(#51069),#51073); +#51069 = LINE('',#51070,#51071); +#51070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51071 = VECTOR('',#51072,1.); +#51072 = DIRECTION('',(0.E+000,1.)); +#51073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51074 = PCURVE('',#51075,#51080); +#51075 = PLANE('',#51076); +#51076 = AXIS2_PLACEMENT_3D('',#51077,#51078,#51079); +#51077 = CARTESIAN_POINT('',(2.725,1.455,1.619807621135)); +#51078 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#51079 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#51080 = DEFINITIONAL_REPRESENTATION('',(#51081),#51085); +#51081 = LINE('',#51082,#51083); +#51082 = CARTESIAN_POINT('',(0.3,0.E+000)); +#51083 = VECTOR('',#51084,1.); +#51084 = DIRECTION('',(0.E+000,1.)); +#51085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51086 = ORIENTED_EDGE('',*,*,#51087,.T.); +#51087 = EDGE_CURVE('',#51060,#50958,#51088,.T.); +#51088 = SURFACE_CURVE('',#51089,(#51093,#51100),.PCURVE_S1.); +#51089 = LINE('',#51090,#51091); +#51090 = CARTESIAN_POINT('',(2.025,1.305,1.36)); +#51091 = VECTOR('',#51092,1.); +#51092 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#51093 = PCURVE('',#50893,#51094); +#51094 = DEFINITIONAL_REPRESENTATION('',(#51095),#51099); +#51095 = LINE('',#51096,#51097); +#51096 = CARTESIAN_POINT('',(0.E+000,0.7)); +#51097 = VECTOR('',#51098,1.); +#51098 = DIRECTION('',(1.,0.E+000)); +#51099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51100 = PCURVE('',#51101,#51106); +#51101 = PLANE('',#51102); +#51102 = AXIS2_PLACEMENT_3D('',#51103,#51104,#51105); +#51103 = CARTESIAN_POINT('',(2.025,0.E+000,0.E+000)); +#51104 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51105 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51106 = DEFINITIONAL_REPRESENTATION('',(#51107),#51111); +#51107 = LINE('',#51108,#51109); +#51108 = CARTESIAN_POINT('',(1.36,1.305)); +#51109 = VECTOR('',#51110,1.); +#51110 = DIRECTION('',(0.5,-0.866025403784)); +#51111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51112 = ADVANCED_FACE('',(#51113),#51047,.F.); +#51113 = FACE_BOUND('',#51114,.F.); +#51114 = EDGE_LOOP('',(#51115,#51167,#51188,#51189)); +#51115 = ORIENTED_EDGE('',*,*,#51116,.F.); +#51116 = EDGE_CURVE('',#51117,#51119,#51121,.T.); +#51117 = VERTEX_POINT('',#51118); +#51118 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); +#51119 = VERTEX_POINT('',#51120); +#51120 = CARTESIAN_POINT('',(2.725,1.225,1.521658075373)); +#51121 = SURFACE_CURVE('',#51122,(#51126,#51133),.PCURVE_S1.); +#51122 = LINE('',#51123,#51124); +#51123 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); +#51124 = VECTOR('',#51125,1.); +#51125 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#51126 = PCURVE('',#51047,#51127); +#51127 = DEFINITIONAL_REPRESENTATION('',(#51128),#51132); +#51128 = LINE('',#51129,#51130); +#51129 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#51130 = VECTOR('',#51131,1.); +#51131 = DIRECTION('',(0.5,-0.866025403784)); +#51132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51133 = PCURVE('',#51134,#51139); +#51134 = CYLINDRICAL_SURFACE('',#51135,0.2); +#51135 = AXIS2_PLACEMENT_3D('',#51136,#51137,#51138); +#51136 = CARTESIAN_POINT('',(2.525,1.374406430719,1.435398232379)); +#51137 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#51138 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51139 = DEFINITIONAL_REPRESENTATION('',(#51140),#51166); +#51140 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51141,#51142,#51143,#51144, + #51145,#51146,#51147,#51148,#51149,#51150,#51151,#51152,#51153, + #51154,#51155,#51156,#51157,#51158,#51159,#51160,#51161,#51162, + #51163,#51164,#51165),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.823230454067E-003, 1.364646090813E-002,2.04696913622E-002,2.729292181627E-002, 3.411615227034E-002,4.09393827244E-002,4.776261317847E-002, @@ -60701,141 +63690,141 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 9.552522635694E-002,0.102348456811,0.109171687265,0.115994917719, 0.122818148173,0.129641378627,0.136464609081,0.143287839535, 0.150111069989),.QUASI_UNIFORM_KNOTS.); -#48749 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); -#48750 = CARTESIAN_POINT('',(-1.668887250617E-012,2.468302615029E-002)); -#48751 = CARTESIAN_POINT('',(-3.223199485092E-012,2.9231846453E-002)); -#48752 = CARTESIAN_POINT('',(-2.597033699203E-012,3.605507690707E-002)); -#48753 = CARTESIAN_POINT('',(-2.766675777366E-012,4.287830736114E-002)); -#48754 = CARTESIAN_POINT('',(-2.722266856381E-012,4.970153781521E-002)); -#48755 = CARTESIAN_POINT('',(-2.733813175837E-012,5.652476826927E-002)); -#48756 = CARTESIAN_POINT('',(-2.729372283738E-012,6.334799872334E-002)); -#48757 = CARTESIAN_POINT('',(-2.731148640578E-012,7.017122917741E-002)); -#48758 = CARTESIAN_POINT('',(-2.729372283738E-012,7.699445963147E-002)); -#48759 = CARTESIAN_POINT('',(-2.729372283738E-012,8.381769008554E-002)); -#48760 = CARTESIAN_POINT('',(-2.731148640578E-012,9.064092053961E-002)); -#48761 = CARTESIAN_POINT('',(-2.730260462158E-012,9.746415099368E-002)); -#48762 = CARTESIAN_POINT('',(-2.730260462158E-012,0.104287381448)); -#48763 = CARTESIAN_POINT('',(-2.731148640578E-012,0.111110611902)); -#48764 = CARTESIAN_POINT('',(-2.729372283738E-012,0.117933842356)); -#48765 = CARTESIAN_POINT('',(-2.729372283738E-012,0.12475707281)); -#48766 = CARTESIAN_POINT('',(-2.731148640578E-012,0.131580303264)); -#48767 = CARTESIAN_POINT('',(-2.731148640578E-012,0.138403533718)); -#48768 = CARTESIAN_POINT('',(-2.723155034801E-012,0.145226764172)); -#48769 = CARTESIAN_POINT('',(-2.765787598946E-012,0.152049994626)); -#48770 = CARTESIAN_POINT('',(-2.598810056043E-012,0.15887322508)); -#48771 = CARTESIAN_POINT('',(-3.224087663511E-012,0.165696455534)); -#48772 = CARTESIAN_POINT('',(-1.668887250617E-012,0.170245275837)); -#48773 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); -#48774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48775 = ORIENTED_EDGE('',*,*,#48776,.T.); -#48776 = EDGE_CURVE('',#48725,#48640,#48777,.T.); -#48777 = SURFACE_CURVE('',#48778,(#48782,#48789),.PCURVE_S1.); -#48778 = LINE('',#48779,#48780); -#48779 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); -#48780 = VECTOR('',#48781,1.); -#48781 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#48782 = PCURVE('',#48655,#48783); -#48783 = DEFINITIONAL_REPRESENTATION('',(#48784),#48788); -#48784 = LINE('',#48785,#48786); -#48785 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#48786 = VECTOR('',#48787,1.); -#48787 = DIRECTION('',(-0.866025403784,-0.5)); -#48788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48789 = PCURVE('',#48683,#48790); -#48790 = DEFINITIONAL_REPRESENTATION('',(#48791),#48795); -#48791 = LINE('',#48792,#48793); -#48792 = CARTESIAN_POINT('',(0.2,0.E+000)); -#48793 = VECTOR('',#48794,1.); -#48794 = DIRECTION('',(1.,0.E+000)); -#48795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48796 = ORIENTED_EDGE('',*,*,#48639,.T.); -#48797 = ORIENTED_EDGE('',*,*,#48798,.T.); -#48798 = EDGE_CURVE('',#48460,#48727,#48799,.T.); -#48799 = SURFACE_CURVE('',#48800,(#48804,#48811),.PCURVE_S1.); -#48800 = LINE('',#48801,#48802); -#48801 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); -#48802 = VECTOR('',#48803,1.); -#48803 = DIRECTION('',(0.E+000,0.E+000,1.)); -#48804 = PCURVE('',#48655,#48805); -#48805 = DEFINITIONAL_REPRESENTATION('',(#48806),#48810); -#48806 = LINE('',#48807,#48808); -#48807 = CARTESIAN_POINT('',(1.406188021535,1.225)); -#48808 = VECTOR('',#48809,1.); -#48809 = DIRECTION('',(1.,0.E+000)); -#48810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48811 = PCURVE('',#48475,#48812); -#48812 = DEFINITIONAL_REPRESENTATION('',(#48813),#48817); -#48813 = LINE('',#48814,#48815); -#48814 = CARTESIAN_POINT('',(0.475,3.756188021535)); -#48815 = VECTOR('',#48816,1.); -#48816 = DIRECTION('',(0.E+000,1.)); -#48817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48818 = ADVANCED_FACE('',(#48819),#48742,.T.); -#48819 = FACE_BOUND('',#48820,.T.); -#48820 = EDGE_LOOP('',(#48821,#48850,#48901,#48902)); -#48821 = ORIENTED_EDGE('',*,*,#48822,.T.); -#48822 = EDGE_CURVE('',#48823,#48825,#48827,.T.); -#48823 = VERTEX_POINT('',#48824); -#48824 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); -#48825 = VERTEX_POINT('',#48826); -#48826 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); -#48827 = SURFACE_CURVE('',#48828,(#48832,#48838),.PCURVE_S1.); -#48828 = LINE('',#48829,#48830); -#48829 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); -#48830 = VECTOR('',#48831,1.); -#48831 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#48832 = PCURVE('',#48742,#48833); -#48833 = DEFINITIONAL_REPRESENTATION('',(#48834),#48837); -#48834 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48835,#48836),.UNSPECIFIED., +#51141 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); +#51142 = CARTESIAN_POINT('',(-1.668887250617E-012,2.468302615029E-002)); +#51143 = CARTESIAN_POINT('',(-3.223199485092E-012,2.9231846453E-002)); +#51144 = CARTESIAN_POINT('',(-2.597033699203E-012,3.605507690707E-002)); +#51145 = CARTESIAN_POINT('',(-2.766675777366E-012,4.287830736114E-002)); +#51146 = CARTESIAN_POINT('',(-2.722266856381E-012,4.970153781521E-002)); +#51147 = CARTESIAN_POINT('',(-2.733813175837E-012,5.652476826927E-002)); +#51148 = CARTESIAN_POINT('',(-2.729372283738E-012,6.334799872334E-002)); +#51149 = CARTESIAN_POINT('',(-2.731148640578E-012,7.017122917741E-002)); +#51150 = CARTESIAN_POINT('',(-2.729372283738E-012,7.699445963147E-002)); +#51151 = CARTESIAN_POINT('',(-2.729372283738E-012,8.381769008554E-002)); +#51152 = CARTESIAN_POINT('',(-2.731148640578E-012,9.064092053961E-002)); +#51153 = CARTESIAN_POINT('',(-2.730260462158E-012,9.746415099368E-002)); +#51154 = CARTESIAN_POINT('',(-2.730260462158E-012,0.104287381448)); +#51155 = CARTESIAN_POINT('',(-2.731148640578E-012,0.111110611902)); +#51156 = CARTESIAN_POINT('',(-2.729372283738E-012,0.117933842356)); +#51157 = CARTESIAN_POINT('',(-2.729372283738E-012,0.12475707281)); +#51158 = CARTESIAN_POINT('',(-2.731148640578E-012,0.131580303264)); +#51159 = CARTESIAN_POINT('',(-2.731148640578E-012,0.138403533718)); +#51160 = CARTESIAN_POINT('',(-2.723155034801E-012,0.145226764172)); +#51161 = CARTESIAN_POINT('',(-2.765787598946E-012,0.152049994626)); +#51162 = CARTESIAN_POINT('',(-2.598810056043E-012,0.15887322508)); +#51163 = CARTESIAN_POINT('',(-3.224087663511E-012,0.165696455534)); +#51164 = CARTESIAN_POINT('',(-1.668887250617E-012,0.170245275837)); +#51165 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); +#51166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51167 = ORIENTED_EDGE('',*,*,#51168,.T.); +#51168 = EDGE_CURVE('',#51117,#51032,#51169,.T.); +#51169 = SURFACE_CURVE('',#51170,(#51174,#51181),.PCURVE_S1.); +#51170 = LINE('',#51171,#51172); +#51171 = CARTESIAN_POINT('',(2.725,1.355,1.446602540378)); +#51172 = VECTOR('',#51173,1.); +#51173 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#51174 = PCURVE('',#51047,#51175); +#51175 = DEFINITIONAL_REPRESENTATION('',(#51176),#51180); +#51176 = LINE('',#51177,#51178); +#51177 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#51178 = VECTOR('',#51179,1.); +#51179 = DIRECTION('',(-0.866025403784,-0.5)); +#51180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51181 = PCURVE('',#51075,#51182); +#51182 = DEFINITIONAL_REPRESENTATION('',(#51183),#51187); +#51183 = LINE('',#51184,#51185); +#51184 = CARTESIAN_POINT('',(0.2,0.E+000)); +#51185 = VECTOR('',#51186,1.); +#51186 = DIRECTION('',(1.,0.E+000)); +#51187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51188 = ORIENTED_EDGE('',*,*,#51031,.T.); +#51189 = ORIENTED_EDGE('',*,*,#51190,.T.); +#51190 = EDGE_CURVE('',#50852,#51119,#51191,.T.); +#51191 = SURFACE_CURVE('',#51192,(#51196,#51203),.PCURVE_S1.); +#51192 = LINE('',#51193,#51194); +#51193 = CARTESIAN_POINT('',(2.725,1.225,1.406188021535)); +#51194 = VECTOR('',#51195,1.); +#51195 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51196 = PCURVE('',#51047,#51197); +#51197 = DEFINITIONAL_REPRESENTATION('',(#51198),#51202); +#51198 = LINE('',#51199,#51200); +#51199 = CARTESIAN_POINT('',(1.406188021535,1.225)); +#51200 = VECTOR('',#51201,1.); +#51201 = DIRECTION('',(1.,0.E+000)); +#51202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51203 = PCURVE('',#50867,#51204); +#51204 = DEFINITIONAL_REPRESENTATION('',(#51205),#51209); +#51205 = LINE('',#51206,#51207); +#51206 = CARTESIAN_POINT('',(0.475,3.756188021535)); +#51207 = VECTOR('',#51208,1.); +#51208 = DIRECTION('',(0.E+000,1.)); +#51209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51210 = ADVANCED_FACE('',(#51211),#51134,.T.); +#51211 = FACE_BOUND('',#51212,.T.); +#51212 = EDGE_LOOP('',(#51213,#51242,#51293,#51294)); +#51213 = ORIENTED_EDGE('',*,*,#51214,.T.); +#51214 = EDGE_CURVE('',#51215,#51217,#51219,.T.); +#51215 = VERTEX_POINT('',#51216); +#51216 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); +#51217 = VERTEX_POINT('',#51218); +#51218 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); +#51219 = SURFACE_CURVE('',#51220,(#51224,#51230),.PCURVE_S1.); +#51220 = LINE('',#51221,#51222); +#51221 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); +#51222 = VECTOR('',#51223,1.); +#51223 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#51224 = PCURVE('',#51134,#51225); +#51225 = DEFINITIONAL_REPRESENTATION('',(#51226),#51229); +#51226 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51227,#51228),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.265581123827),.PIECEWISE_BEZIER_KNOTS.); -#48835 = CARTESIAN_POINT('',(1.570796326795,2.240861599904E-002)); -#48836 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); -#48837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48838 = PCURVE('',#48839,#48844); -#48839 = PLANE('',#48840); -#48840 = AXIS2_PLACEMENT_3D('',#48841,#48842,#48843); -#48841 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); -#48842 = DIRECTION('',(0.E+000,0.5,0.866025403784)); -#48843 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#48844 = DEFINITIONAL_REPRESENTATION('',(#48845),#48849); -#48845 = LINE('',#48846,#48847); -#48846 = CARTESIAN_POINT('',(0.265581123827,0.2)); -#48847 = VECTOR('',#48848,1.); -#48848 = DIRECTION('',(-1.,0.E+000)); -#48849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48850 = ORIENTED_EDGE('',*,*,#48851,.F.); -#48851 = EDGE_CURVE('',#48727,#48825,#48852,.T.); -#48852 = SURFACE_CURVE('',#48853,(#48861,#48890),.PCURVE_S1.); -#48853 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48854,#48855,#48856,#48857, - #48858,#48859,#48860),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#51227 = CARTESIAN_POINT('',(1.570796326795,2.240861599904E-002)); +#51228 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); +#51229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51230 = PCURVE('',#51231,#51236); +#51231 = PLANE('',#51232); +#51232 = AXIS2_PLACEMENT_3D('',#51233,#51234,#51235); +#51233 = CARTESIAN_POINT('',(2.725,1.225,1.752598183049)); +#51234 = DIRECTION('',(0.E+000,0.5,0.866025403784)); +#51235 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#51236 = DEFINITIONAL_REPRESENTATION('',(#51237),#51241); +#51237 = LINE('',#51238,#51239); +#51238 = CARTESIAN_POINT('',(0.265581123827,0.2)); +#51239 = VECTOR('',#51240,1.); +#51240 = DIRECTION('',(-1.,0.E+000)); +#51241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51242 = ORIENTED_EDGE('',*,*,#51243,.F.); +#51243 = EDGE_CURVE('',#51119,#51217,#51244,.T.); +#51244 = SURFACE_CURVE('',#51245,(#51253,#51282),.PCURVE_S1.); +#51245 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51246,#51247,#51248,#51249, + #51250,#51251,#51252),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#48854 = CARTESIAN_POINT('',(2.725,1.225,1.521658075373)); -#48855 = CARTESIAN_POINT('',(2.725,1.225,1.557569751013)); -#48856 = CARTESIAN_POINT('',(2.711998370797,1.225,1.616391473089)); -#48857 = CARTESIAN_POINT('',(2.672515852456,1.225,1.684643981667)); -#48858 = CARTESIAN_POINT('',(2.614109071322,1.225,1.733972227452)); -#48859 = CARTESIAN_POINT('',(2.56091167564,1.225,1.752598183049)); -#48860 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); -#48861 = PCURVE('',#48742,#48862); -#48862 = DEFINITIONAL_REPRESENTATION('',(#48863),#48889); -#48863 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48864,#48865,#48866,#48867, - #48868,#48869,#48870,#48871,#48872,#48873,#48874,#48875,#48876, - #48877,#48878,#48879,#48880,#48881,#48882,#48883,#48884,#48885, - #48886,#48887,#48888),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#51246 = CARTESIAN_POINT('',(2.725,1.225,1.521658075373)); +#51247 = CARTESIAN_POINT('',(2.725,1.225,1.557569751013)); +#51248 = CARTESIAN_POINT('',(2.711998370797,1.225,1.616391473089)); +#51249 = CARTESIAN_POINT('',(2.672515852456,1.225,1.684643981667)); +#51250 = CARTESIAN_POINT('',(2.614109071322,1.225,1.733972227452)); +#51251 = CARTESIAN_POINT('',(2.56091167564,1.225,1.752598183049)); +#51252 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); +#51253 = PCURVE('',#51134,#51254); +#51254 = DEFINITIONAL_REPRESENTATION('',(#51255),#51281); +#51255 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51256,#51257,#51258,#51259, + #51260,#51261,#51262,#51263,#51264,#51265,#51266,#51267,#51268, + #51269,#51270,#51271,#51272,#51273,#51274,#51275,#51276,#51277, + #51278,#51279,#51280),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -60843,64 +63832,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#48864 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); -#48865 = CARTESIAN_POINT('',(2.827076521565E-002,0.175784383774)); -#48866 = CARTESIAN_POINT('',(8.29580459432E-002,0.182098872442)); -#48867 = CARTESIAN_POINT('',(0.160334717441,0.190983094696)); -#48868 = CARTESIAN_POINT('',(0.233989615751,0.199336874302)); -#48869 = CARTESIAN_POINT('',(0.304771298167,0.207217775869)); -#48870 = CARTESIAN_POINT('',(0.373415877509,0.214681519824)); -#48871 = CARTESIAN_POINT('',(0.440551827004,0.221790706819)); -#48872 = CARTESIAN_POINT('',(0.506543398683,0.228575510601)); -#48873 = CARTESIAN_POINT('',(0.571633992932,0.235033677972)); -#48874 = CARTESIAN_POINT('',(0.636109891137,0.241169836099)); -#48875 = CARTESIAN_POINT('',(0.700253440979,0.246986767435)); -#48876 = CARTESIAN_POINT('',(0.764347001392,0.252487752932)); -#48877 = CARTESIAN_POINT('',(0.828660646629,0.257675924253)); -#48878 = CARTESIAN_POINT('',(0.893473353306,0.262543930626)); -#48879 = CARTESIAN_POINT('',(0.959080929042,0.267084175896)); -#48880 = CARTESIAN_POINT('',(1.025778930209,0.271289946776)); -#48881 = CARTESIAN_POINT('',(1.093878332084,0.275151243893)); -#48882 = CARTESIAN_POINT('',(1.163604914096,0.278670329348)); -#48883 = CARTESIAN_POINT('',(1.235488259695,0.281791675568)); -#48884 = CARTESIAN_POINT('',(1.310617785153,0.284401965263)); -#48885 = CARTESIAN_POINT('',(1.390269427501,0.286400142761)); -#48886 = CARTESIAN_POINT('',(1.475938790177,0.287681865769)); -#48887 = CARTESIAN_POINT('',(1.538150472706,0.287989739826)); -#48888 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); -#48889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48890 = PCURVE('',#48475,#48891); -#48891 = DEFINITIONAL_REPRESENTATION('',(#48892),#48900); -#48892 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48893,#48894,#48895,#48896, - #48897,#48898,#48899),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#51256 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); +#51257 = CARTESIAN_POINT('',(2.827076521565E-002,0.175784383774)); +#51258 = CARTESIAN_POINT('',(8.29580459432E-002,0.182098872442)); +#51259 = CARTESIAN_POINT('',(0.160334717441,0.190983094696)); +#51260 = CARTESIAN_POINT('',(0.233989615751,0.199336874302)); +#51261 = CARTESIAN_POINT('',(0.304771298167,0.207217775869)); +#51262 = CARTESIAN_POINT('',(0.373415877509,0.214681519824)); +#51263 = CARTESIAN_POINT('',(0.440551827004,0.221790706819)); +#51264 = CARTESIAN_POINT('',(0.506543398683,0.228575510601)); +#51265 = CARTESIAN_POINT('',(0.571633992932,0.235033677972)); +#51266 = CARTESIAN_POINT('',(0.636109891137,0.241169836099)); +#51267 = CARTESIAN_POINT('',(0.700253440979,0.246986767435)); +#51268 = CARTESIAN_POINT('',(0.764347001392,0.252487752932)); +#51269 = CARTESIAN_POINT('',(0.828660646629,0.257675924253)); +#51270 = CARTESIAN_POINT('',(0.893473353306,0.262543930626)); +#51271 = CARTESIAN_POINT('',(0.959080929042,0.267084175896)); +#51272 = CARTESIAN_POINT('',(1.025778930209,0.271289946776)); +#51273 = CARTESIAN_POINT('',(1.093878332084,0.275151243893)); +#51274 = CARTESIAN_POINT('',(1.163604914096,0.278670329348)); +#51275 = CARTESIAN_POINT('',(1.235488259695,0.281791675568)); +#51276 = CARTESIAN_POINT('',(1.310617785153,0.284401965263)); +#51277 = CARTESIAN_POINT('',(1.390269427501,0.286400142761)); +#51278 = CARTESIAN_POINT('',(1.475938790177,0.287681865769)); +#51279 = CARTESIAN_POINT('',(1.538150472706,0.287989739826)); +#51280 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); +#51281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51282 = PCURVE('',#50867,#51283); +#51283 = DEFINITIONAL_REPRESENTATION('',(#51284),#51292); +#51284 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51285,#51286,#51287,#51288, + #51289,#51290,#51291),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#48893 = CARTESIAN_POINT('',(0.475,3.871658075373)); -#48894 = CARTESIAN_POINT('',(0.475,3.907569751013)); -#48895 = CARTESIAN_POINT('',(0.488001629203,3.966391473089)); -#48896 = CARTESIAN_POINT('',(0.527484147544,4.034643981667)); -#48897 = CARTESIAN_POINT('',(0.585890928678,4.083972227452)); -#48898 = CARTESIAN_POINT('',(0.63908832436,4.102598183049)); -#48899 = CARTESIAN_POINT('',(0.675,4.102598183049)); -#48900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48901 = ORIENTED_EDGE('',*,*,#48724,.F.); -#48902 = ORIENTED_EDGE('',*,*,#48903,.F.); -#48903 = EDGE_CURVE('',#48823,#48725,#48904,.T.); -#48904 = SURFACE_CURVE('',#48905,(#48910,#48939),.PCURVE_S1.); -#48905 = CIRCLE('',#48906,0.2); -#48906 = AXIS2_PLACEMENT_3D('',#48907,#48908,#48909); -#48907 = CARTESIAN_POINT('',(2.525,1.355,1.446602540378)); -#48908 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#48909 = DIRECTION('',(0.E+000,0.5,0.866025403784)); -#48910 = PCURVE('',#48742,#48911); -#48911 = DEFINITIONAL_REPRESENTATION('',(#48912),#48938); -#48912 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#48913,#48914,#48915,#48916, - #48917,#48918,#48919,#48920,#48921,#48922,#48923,#48924,#48925, - #48926,#48927,#48928,#48929,#48930,#48931,#48932,#48933,#48934, - #48935,#48936,#48937),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#51285 = CARTESIAN_POINT('',(0.475,3.871658075373)); +#51286 = CARTESIAN_POINT('',(0.475,3.907569751013)); +#51287 = CARTESIAN_POINT('',(0.488001629203,3.966391473089)); +#51288 = CARTESIAN_POINT('',(0.527484147544,4.034643981667)); +#51289 = CARTESIAN_POINT('',(0.585890928678,4.083972227452)); +#51290 = CARTESIAN_POINT('',(0.63908832436,4.102598183049)); +#51291 = CARTESIAN_POINT('',(0.675,4.102598183049)); +#51292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51293 = ORIENTED_EDGE('',*,*,#51116,.F.); +#51294 = ORIENTED_EDGE('',*,*,#51295,.F.); +#51295 = EDGE_CURVE('',#51215,#51117,#51296,.T.); +#51296 = SURFACE_CURVE('',#51297,(#51302,#51331),.PCURVE_S1.); +#51297 = CIRCLE('',#51298,0.2); +#51298 = AXIS2_PLACEMENT_3D('',#51299,#51300,#51301); +#51299 = CARTESIAN_POINT('',(2.525,1.355,1.446602540378)); +#51300 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#51301 = DIRECTION('',(0.E+000,0.5,0.866025403784)); +#51302 = PCURVE('',#51134,#51303); +#51303 = DEFINITIONAL_REPRESENTATION('',(#51304),#51330); +#51304 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51305,#51306,#51307,#51308, + #51309,#51310,#51311,#51312,#51313,#51314,#51315,#51316,#51317, + #51318,#51319,#51320,#51321,#51322,#51323,#51324,#51325,#51326, + #51327,#51328,#51329),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -60908,647 +63897,647 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#48913 = CARTESIAN_POINT('',(1.570796326795,2.240861599894E-002)); -#48914 = CARTESIAN_POINT('',(1.546996382449,2.240861599894E-002)); -#48915 = CARTESIAN_POINT('',(1.499396493759,2.240861599894E-002)); -#48916 = CARTESIAN_POINT('',(1.427996660722,2.240861599894E-002)); -#48917 = CARTESIAN_POINT('',(1.356596827686,2.240861599894E-002)); -#48918 = CARTESIAN_POINT('',(1.28519699465,2.240861599894E-002)); -#48919 = CARTESIAN_POINT('',(1.213797161613,2.240861599894E-002)); -#48920 = CARTESIAN_POINT('',(1.142397328577,2.240861599894E-002)); -#48921 = CARTESIAN_POINT('',(1.070997495541,2.240861599894E-002)); -#48922 = CARTESIAN_POINT('',(0.999597662504,2.240861599894E-002)); -#48923 = CARTESIAN_POINT('',(0.928197829468,2.240861599894E-002)); -#48924 = CARTESIAN_POINT('',(0.856797996432,2.240861599894E-002)); -#48925 = CARTESIAN_POINT('',(0.785398163396,2.240861599894E-002)); -#48926 = CARTESIAN_POINT('',(0.713998330359,2.240861599894E-002)); -#48927 = CARTESIAN_POINT('',(0.642598497323,2.240861599894E-002)); -#48928 = CARTESIAN_POINT('',(0.571198664287,2.240861599894E-002)); -#48929 = CARTESIAN_POINT('',(0.499798831251,2.240861599894E-002)); -#48930 = CARTESIAN_POINT('',(0.428398998214,2.240861599894E-002)); -#48931 = CARTESIAN_POINT('',(0.356999165178,2.240861599894E-002)); -#48932 = CARTESIAN_POINT('',(0.285599332142,2.240861599894E-002)); -#48933 = CARTESIAN_POINT('',(0.214199499106,2.240861599894E-002)); -#48934 = CARTESIAN_POINT('',(0.14279966607,2.240861599894E-002)); -#48935 = CARTESIAN_POINT('',(7.139983303291E-002,2.240861599894E-002)); -#48936 = CARTESIAN_POINT('',(2.379994434371E-002,2.240861599894E-002)); -#48937 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); -#48938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48939 = PCURVE('',#48683,#48940); -#48940 = DEFINITIONAL_REPRESENTATION('',(#48941),#48945); -#48941 = CIRCLE('',#48942,0.2); -#48942 = AXIS2_PLACEMENT_2D('',#48943,#48944); -#48943 = CARTESIAN_POINT('',(0.2,0.2)); -#48944 = DIRECTION('',(-1.,0.E+000)); -#48945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48946 = ADVANCED_FACE('',(#48947),#48839,.T.); -#48947 = FACE_BOUND('',#48948,.F.); -#48948 = EDGE_LOOP('',(#48949,#48950,#48973,#49000)); -#48949 = ORIENTED_EDGE('',*,*,#48822,.T.); -#48950 = ORIENTED_EDGE('',*,*,#48951,.T.); -#48951 = EDGE_CURVE('',#48825,#48952,#48954,.T.); -#48952 = VERTEX_POINT('',#48953); -#48953 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); -#48954 = SURFACE_CURVE('',#48955,(#48959,#48966),.PCURVE_S1.); -#48955 = LINE('',#48956,#48957); -#48956 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); -#48957 = VECTOR('',#48958,1.); -#48958 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48959 = PCURVE('',#48839,#48960); -#48960 = DEFINITIONAL_REPRESENTATION('',(#48961),#48965); -#48961 = LINE('',#48962,#48963); -#48962 = CARTESIAN_POINT('',(0.E+000,0.2)); -#48963 = VECTOR('',#48964,1.); -#48964 = DIRECTION('',(0.E+000,1.)); -#48965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48966 = PCURVE('',#48475,#48967); -#48967 = DEFINITIONAL_REPRESENTATION('',(#48968),#48972); -#48968 = LINE('',#48969,#48970); -#48969 = CARTESIAN_POINT('',(0.675,4.102598183049)); -#48970 = VECTOR('',#48971,1.); -#48971 = DIRECTION('',(1.,0.E+000)); -#48972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48973 = ORIENTED_EDGE('',*,*,#48974,.T.); -#48974 = EDGE_CURVE('',#48952,#48975,#48977,.T.); -#48975 = VERTEX_POINT('',#48976); -#48976 = CARTESIAN_POINT('',(2.225,1.455,1.619807621135)); -#48977 = SURFACE_CURVE('',#48978,(#48982,#48989),.PCURVE_S1.); -#48978 = LINE('',#48979,#48980); -#48979 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); -#48980 = VECTOR('',#48981,1.); -#48981 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#48982 = PCURVE('',#48839,#48983); -#48983 = DEFINITIONAL_REPRESENTATION('',(#48984),#48988); -#48984 = LINE('',#48985,#48986); -#48985 = CARTESIAN_POINT('',(0.E+000,0.5)); -#48986 = VECTOR('',#48987,1.); -#48987 = DIRECTION('',(1.,0.E+000)); -#48988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#48989 = PCURVE('',#48990,#48995); -#48990 = CYLINDRICAL_SURFACE('',#48991,0.2); -#48991 = AXIS2_PLACEMENT_3D('',#48992,#48993,#48994); -#48992 = CARTESIAN_POINT('',(2.225,1.111328977094,1.587286071047)); -#48993 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#48994 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#48995 = DEFINITIONAL_REPRESENTATION('',(#48996),#48999); -#48996 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#48997,#48998),.UNSPECIFIED., +#51305 = CARTESIAN_POINT('',(1.570796326795,2.240861599894E-002)); +#51306 = CARTESIAN_POINT('',(1.546996382449,2.240861599894E-002)); +#51307 = CARTESIAN_POINT('',(1.499396493759,2.240861599894E-002)); +#51308 = CARTESIAN_POINT('',(1.427996660722,2.240861599894E-002)); +#51309 = CARTESIAN_POINT('',(1.356596827686,2.240861599894E-002)); +#51310 = CARTESIAN_POINT('',(1.28519699465,2.240861599894E-002)); +#51311 = CARTESIAN_POINT('',(1.213797161613,2.240861599894E-002)); +#51312 = CARTESIAN_POINT('',(1.142397328577,2.240861599894E-002)); +#51313 = CARTESIAN_POINT('',(1.070997495541,2.240861599894E-002)); +#51314 = CARTESIAN_POINT('',(0.999597662504,2.240861599894E-002)); +#51315 = CARTESIAN_POINT('',(0.928197829468,2.240861599894E-002)); +#51316 = CARTESIAN_POINT('',(0.856797996432,2.240861599894E-002)); +#51317 = CARTESIAN_POINT('',(0.785398163396,2.240861599894E-002)); +#51318 = CARTESIAN_POINT('',(0.713998330359,2.240861599894E-002)); +#51319 = CARTESIAN_POINT('',(0.642598497323,2.240861599894E-002)); +#51320 = CARTESIAN_POINT('',(0.571198664287,2.240861599894E-002)); +#51321 = CARTESIAN_POINT('',(0.499798831251,2.240861599894E-002)); +#51322 = CARTESIAN_POINT('',(0.428398998214,2.240861599894E-002)); +#51323 = CARTESIAN_POINT('',(0.356999165178,2.240861599894E-002)); +#51324 = CARTESIAN_POINT('',(0.285599332142,2.240861599894E-002)); +#51325 = CARTESIAN_POINT('',(0.214199499106,2.240861599894E-002)); +#51326 = CARTESIAN_POINT('',(0.14279966607,2.240861599894E-002)); +#51327 = CARTESIAN_POINT('',(7.139983303291E-002,2.240861599894E-002)); +#51328 = CARTESIAN_POINT('',(2.379994434371E-002,2.240861599894E-002)); +#51329 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); +#51330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51331 = PCURVE('',#51075,#51332); +#51332 = DEFINITIONAL_REPRESENTATION('',(#51333),#51337); +#51333 = CIRCLE('',#51334,0.2); +#51334 = AXIS2_PLACEMENT_2D('',#51335,#51336); +#51335 = CARTESIAN_POINT('',(0.2,0.2)); +#51336 = DIRECTION('',(-1.,0.E+000)); +#51337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51338 = ADVANCED_FACE('',(#51339),#51231,.T.); +#51339 = FACE_BOUND('',#51340,.F.); +#51340 = EDGE_LOOP('',(#51341,#51342,#51365,#51392)); +#51341 = ORIENTED_EDGE('',*,*,#51214,.T.); +#51342 = ORIENTED_EDGE('',*,*,#51343,.T.); +#51343 = EDGE_CURVE('',#51217,#51344,#51346,.T.); +#51344 = VERTEX_POINT('',#51345); +#51345 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); +#51346 = SURFACE_CURVE('',#51347,(#51351,#51358),.PCURVE_S1.); +#51347 = LINE('',#51348,#51349); +#51348 = CARTESIAN_POINT('',(2.525,1.225,1.752598183049)); +#51349 = VECTOR('',#51350,1.); +#51350 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51351 = PCURVE('',#51231,#51352); +#51352 = DEFINITIONAL_REPRESENTATION('',(#51353),#51357); +#51353 = LINE('',#51354,#51355); +#51354 = CARTESIAN_POINT('',(0.E+000,0.2)); +#51355 = VECTOR('',#51356,1.); +#51356 = DIRECTION('',(0.E+000,1.)); +#51357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51358 = PCURVE('',#50867,#51359); +#51359 = DEFINITIONAL_REPRESENTATION('',(#51360),#51364); +#51360 = LINE('',#51361,#51362); +#51361 = CARTESIAN_POINT('',(0.675,4.102598183049)); +#51362 = VECTOR('',#51363,1.); +#51363 = DIRECTION('',(1.,0.E+000)); +#51364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51365 = ORIENTED_EDGE('',*,*,#51366,.T.); +#51366 = EDGE_CURVE('',#51344,#51367,#51369,.T.); +#51367 = VERTEX_POINT('',#51368); +#51368 = CARTESIAN_POINT('',(2.225,1.455,1.619807621135)); +#51369 = SURFACE_CURVE('',#51370,(#51374,#51381),.PCURVE_S1.); +#51370 = LINE('',#51371,#51372); +#51371 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); +#51372 = VECTOR('',#51373,1.); +#51373 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#51374 = PCURVE('',#51231,#51375); +#51375 = DEFINITIONAL_REPRESENTATION('',(#51376),#51380); +#51376 = LINE('',#51377,#51378); +#51377 = CARTESIAN_POINT('',(0.E+000,0.5)); +#51378 = VECTOR('',#51379,1.); +#51379 = DIRECTION('',(1.,0.E+000)); +#51380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51381 = PCURVE('',#51382,#51387); +#51382 = CYLINDRICAL_SURFACE('',#51383,0.2); +#51383 = AXIS2_PLACEMENT_3D('',#51384,#51385,#51386); +#51384 = CARTESIAN_POINT('',(2.225,1.111328977094,1.587286071047)); +#51385 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#51386 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51387 = DEFINITIONAL_REPRESENTATION('',(#51388),#51391); +#51388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51389,#51390),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.265581123827),.PIECEWISE_BEZIER_KNOTS.); -#48997 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); -#48998 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); -#48999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49000 = ORIENTED_EDGE('',*,*,#49001,.F.); -#49001 = EDGE_CURVE('',#48823,#48975,#49002,.T.); -#49002 = SURFACE_CURVE('',#49003,(#49007,#49014),.PCURVE_S1.); -#49003 = LINE('',#49004,#49005); -#49004 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); -#49005 = VECTOR('',#49006,1.); -#49006 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49007 = PCURVE('',#48839,#49008); -#49008 = DEFINITIONAL_REPRESENTATION('',(#49009),#49013); -#49009 = LINE('',#49010,#49011); -#49010 = CARTESIAN_POINT('',(0.265581123827,0.2)); -#49011 = VECTOR('',#49012,1.); -#49012 = DIRECTION('',(0.E+000,1.)); -#49013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49014 = PCURVE('',#48683,#49015); -#49015 = DEFINITIONAL_REPRESENTATION('',(#49016),#49020); -#49016 = LINE('',#49017,#49018); -#49017 = CARTESIAN_POINT('',(0.E+000,0.2)); -#49018 = VECTOR('',#49019,1.); -#49019 = DIRECTION('',(0.E+000,1.)); -#49020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49021 = ADVANCED_FACE('',(#49022,#49403,#49689,#50144),#48475,.T.); -#49022 = FACE_BOUND('',#49023,.F.); -#49023 = EDGE_LOOP('',(#49024,#49053,#49076,#49099,#49122,#49145,#49172, - #49195,#49215,#49241,#49263,#49286,#49313,#49336,#49359,#49382)); -#49024 = ORIENTED_EDGE('',*,*,#49025,.T.); -#49025 = EDGE_CURVE('',#49026,#49028,#49030,.T.); -#49026 = VERTEX_POINT('',#49027); -#49027 = CARTESIAN_POINT('',(-1.21,1.225,-2.35)); -#49028 = VERTEX_POINT('',#49029); -#49029 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); -#49030 = SURFACE_CURVE('',#49031,(#49035,#49042),.PCURVE_S1.); -#49031 = LINE('',#49032,#49033); -#49032 = CARTESIAN_POINT('',(-1.21,1.225,-2.35)); -#49033 = VECTOR('',#49034,1.); -#49034 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49035 = PCURVE('',#48475,#49036); -#49036 = DEFINITIONAL_REPRESENTATION('',(#49037),#49041); -#49037 = LINE('',#49038,#49039); -#49038 = CARTESIAN_POINT('',(4.41,0.E+000)); -#49039 = VECTOR('',#49040,1.); -#49040 = DIRECTION('',(-1.,0.E+000)); -#49041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49042 = PCURVE('',#49043,#49048); -#49043 = CYLINDRICAL_SURFACE('',#49044,0.3); -#49044 = AXIS2_PLACEMENT_3D('',#49045,#49046,#49047); -#49045 = CARTESIAN_POINT('',(-3.01491772868,0.925,-2.35)); -#49046 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49047 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49048 = DEFINITIONAL_REPRESENTATION('',(#49049),#49052); -#49049 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49050,#49051),.UNSPECIFIED., +#51389 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); +#51390 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); +#51391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51392 = ORIENTED_EDGE('',*,*,#51393,.F.); +#51393 = EDGE_CURVE('',#51215,#51367,#51394,.T.); +#51394 = SURFACE_CURVE('',#51395,(#51399,#51406),.PCURVE_S1.); +#51395 = LINE('',#51396,#51397); +#51396 = CARTESIAN_POINT('',(2.525,1.455,1.619807621135)); +#51397 = VECTOR('',#51398,1.); +#51398 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51399 = PCURVE('',#51231,#51400); +#51400 = DEFINITIONAL_REPRESENTATION('',(#51401),#51405); +#51401 = LINE('',#51402,#51403); +#51402 = CARTESIAN_POINT('',(0.265581123827,0.2)); +#51403 = VECTOR('',#51404,1.); +#51404 = DIRECTION('',(0.E+000,1.)); +#51405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51406 = PCURVE('',#51075,#51407); +#51407 = DEFINITIONAL_REPRESENTATION('',(#51408),#51412); +#51408 = LINE('',#51409,#51410); +#51409 = CARTESIAN_POINT('',(0.E+000,0.2)); +#51410 = VECTOR('',#51411,1.); +#51411 = DIRECTION('',(0.E+000,1.)); +#51412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51413 = ADVANCED_FACE('',(#51414,#51795,#52081,#52536),#50867,.T.); +#51414 = FACE_BOUND('',#51415,.F.); +#51415 = EDGE_LOOP('',(#51416,#51445,#51468,#51491,#51514,#51537,#51564, + #51587,#51607,#51633,#51655,#51678,#51705,#51728,#51751,#51774)); +#51416 = ORIENTED_EDGE('',*,*,#51417,.T.); +#51417 = EDGE_CURVE('',#51418,#51420,#51422,.T.); +#51418 = VERTEX_POINT('',#51419); +#51419 = CARTESIAN_POINT('',(-1.21,1.225,-2.35)); +#51420 = VERTEX_POINT('',#51421); +#51421 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); +#51422 = SURFACE_CURVE('',#51423,(#51427,#51434),.PCURVE_S1.); +#51423 = LINE('',#51424,#51425); +#51424 = CARTESIAN_POINT('',(-1.21,1.225,-2.35)); +#51425 = VECTOR('',#51426,1.); +#51426 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51427 = PCURVE('',#50867,#51428); +#51428 = DEFINITIONAL_REPRESENTATION('',(#51429),#51433); +#51429 = LINE('',#51430,#51431); +#51430 = CARTESIAN_POINT('',(4.41,0.E+000)); +#51431 = VECTOR('',#51432,1.); +#51432 = DIRECTION('',(-1.,0.E+000)); +#51433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51434 = PCURVE('',#51435,#51440); +#51435 = CYLINDRICAL_SURFACE('',#51436,0.3); +#51436 = AXIS2_PLACEMENT_3D('',#51437,#51438,#51439); +#51437 = CARTESIAN_POINT('',(-3.01491772868,0.925,-2.35)); +#51438 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51439 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#51440 = DEFINITIONAL_REPRESENTATION('',(#51441),#51444); +#51441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51442,#51443),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.42),.PIECEWISE_BEZIER_KNOTS.); -#49050 = CARTESIAN_POINT('',(1.570796326795,1.80491772868)); -#49051 = CARTESIAN_POINT('',(1.570796326795,4.22491772868)); -#49052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49053 = ORIENTED_EDGE('',*,*,#49054,.T.); -#49054 = EDGE_CURVE('',#49028,#49055,#49057,.T.); -#49055 = VERTEX_POINT('',#49056); -#49056 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); -#49057 = SURFACE_CURVE('',#49058,(#49062,#49069),.PCURVE_S1.); -#49058 = LINE('',#49059,#49060); -#49059 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); -#49060 = VECTOR('',#49061,1.); -#49061 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49062 = PCURVE('',#48475,#49063); -#49063 = DEFINITIONAL_REPRESENTATION('',(#49064),#49068); -#49064 = LINE('',#49065,#49066); -#49065 = CARTESIAN_POINT('',(1.99,0.E+000)); -#49066 = VECTOR('',#49067,1.); -#49067 = DIRECTION('',(0.E+000,1.)); -#49068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#51442 = CARTESIAN_POINT('',(1.570796326795,1.80491772868)); +#51443 = CARTESIAN_POINT('',(1.570796326795,4.22491772868)); +#51444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51445 = ORIENTED_EDGE('',*,*,#51446,.T.); +#51446 = EDGE_CURVE('',#51420,#51447,#51449,.T.); +#51447 = VERTEX_POINT('',#51448); +#51448 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); +#51449 = SURFACE_CURVE('',#51450,(#51454,#51461),.PCURVE_S1.); +#51450 = LINE('',#51451,#51452); +#51451 = CARTESIAN_POINT('',(1.21,1.225,-2.35)); +#51452 = VECTOR('',#51453,1.); +#51453 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51454 = PCURVE('',#50867,#51455); +#51455 = DEFINITIONAL_REPRESENTATION('',(#51456),#51460); +#51456 = LINE('',#51457,#51458); +#51457 = CARTESIAN_POINT('',(1.99,0.E+000)); +#51458 = VECTOR('',#51459,1.); +#51459 = DIRECTION('',(0.E+000,1.)); +#51460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51461 = PCURVE('',#50022,#51462); +#51462 = DEFINITIONAL_REPRESENTATION('',(#51463),#51467); +#51463 = LINE('',#51464,#51465); +#51464 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51465 = VECTOR('',#51466,1.); +#51466 = DIRECTION('',(1.,0.E+000)); +#51467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51468 = ORIENTED_EDGE('',*,*,#51469,.T.); +#51469 = EDGE_CURVE('',#51447,#51470,#51472,.T.); +#51470 = VERTEX_POINT('',#51471); +#51471 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); +#51472 = SURFACE_CURVE('',#51473,(#51477,#51484),.PCURVE_S1.); +#51473 = LINE('',#51474,#51475); +#51474 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); +#51475 = VECTOR('',#51476,1.); +#51476 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51477 = PCURVE('',#50867,#51478); +#51478 = DEFINITIONAL_REPRESENTATION('',(#51479),#51483); +#51479 = LINE('',#51480,#51481); +#51480 = CARTESIAN_POINT('',(1.99,1.)); +#51481 = VECTOR('',#51482,1.); +#51482 = DIRECTION('',(-1.,0.E+000)); +#51483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51484 = PCURVE('',#49994,#51485); +#51485 = DEFINITIONAL_REPRESENTATION('',(#51486),#51490); +#51486 = LINE('',#51487,#51488); +#51487 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51488 = VECTOR('',#51489,1.); +#51489 = DIRECTION('',(1.,0.E+000)); +#51490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51491 = ORIENTED_EDGE('',*,*,#51492,.F.); +#51492 = EDGE_CURVE('',#51493,#51470,#51495,.T.); +#51493 = VERTEX_POINT('',#51494); +#51494 = CARTESIAN_POINT('',(2.37,1.225,-1.65)); +#51495 = SURFACE_CURVE('',#51496,(#51500,#51507),.PCURVE_S1.); +#51496 = LINE('',#51497,#51498); +#51497 = CARTESIAN_POINT('',(2.37,1.225,-1.65)); +#51498 = VECTOR('',#51499,1.); +#51499 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51500 = PCURVE('',#50867,#51501); +#51501 = DEFINITIONAL_REPRESENTATION('',(#51502),#51506); +#51502 = LINE('',#51503,#51504); +#51503 = CARTESIAN_POINT('',(0.83,0.7)); +#51504 = VECTOR('',#51505,1.); +#51505 = DIRECTION('',(0.E+000,1.)); +#51506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#49069 = PCURVE('',#47630,#49070); -#49070 = DEFINITIONAL_REPRESENTATION('',(#49071),#49075); -#49071 = LINE('',#49072,#49073); -#49072 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49073 = VECTOR('',#49074,1.); -#49074 = DIRECTION('',(1.,0.E+000)); -#49075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49076 = ORIENTED_EDGE('',*,*,#49077,.T.); -#49077 = EDGE_CURVE('',#49055,#49078,#49080,.T.); -#49078 = VERTEX_POINT('',#49079); -#49079 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); -#49080 = SURFACE_CURVE('',#49081,(#49085,#49092),.PCURVE_S1.); -#49081 = LINE('',#49082,#49083); -#49082 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); -#49083 = VECTOR('',#49084,1.); -#49084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49085 = PCURVE('',#48475,#49086); -#49086 = DEFINITIONAL_REPRESENTATION('',(#49087),#49091); -#49087 = LINE('',#49088,#49089); -#49088 = CARTESIAN_POINT('',(1.99,1.)); -#49089 = VECTOR('',#49090,1.); -#49090 = DIRECTION('',(-1.,0.E+000)); -#49091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49092 = PCURVE('',#47602,#49093); -#49093 = DEFINITIONAL_REPRESENTATION('',(#49094),#49098); -#49094 = LINE('',#49095,#49096); -#49095 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49096 = VECTOR('',#49097,1.); -#49097 = DIRECTION('',(1.,0.E+000)); -#49098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49099 = ORIENTED_EDGE('',*,*,#49100,.F.); -#49100 = EDGE_CURVE('',#49101,#49078,#49103,.T.); -#49101 = VERTEX_POINT('',#49102); -#49102 = CARTESIAN_POINT('',(2.37,1.225,-1.65)); -#49103 = SURFACE_CURVE('',#49104,(#49108,#49115),.PCURVE_S1.); -#49104 = LINE('',#49105,#49106); -#49105 = CARTESIAN_POINT('',(2.37,1.225,-1.65)); -#49106 = VECTOR('',#49107,1.); -#49107 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49108 = PCURVE('',#48475,#49109); -#49109 = DEFINITIONAL_REPRESENTATION('',(#49110),#49114); -#49110 = LINE('',#49111,#49112); -#49111 = CARTESIAN_POINT('',(0.83,0.7)); -#49112 = VECTOR('',#49113,1.); -#49113 = DIRECTION('',(0.E+000,1.)); -#49114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49115 = PCURVE('',#47574,#49116); -#49116 = DEFINITIONAL_REPRESENTATION('',(#49117),#49121); -#49117 = LINE('',#49118,#49119); -#49118 = CARTESIAN_POINT('',(0.3,0.E+000)); -#49119 = VECTOR('',#49120,1.); -#49120 = DIRECTION('',(-1.,0.E+000)); -#49121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49122 = ORIENTED_EDGE('',*,*,#49123,.F.); -#49123 = EDGE_CURVE('',#49124,#49101,#49126,.T.); -#49124 = VERTEX_POINT('',#49125); -#49125 = CARTESIAN_POINT('',(2.256940242224,1.225,-1.65)); -#49126 = SURFACE_CURVE('',#49127,(#49131,#49138),.PCURVE_S1.); -#49127 = LINE('',#49128,#49129); -#49128 = CARTESIAN_POINT('',(2.256940242224,1.225,-1.65)); -#49129 = VECTOR('',#49130,1.); -#49130 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49131 = PCURVE('',#48475,#49132); -#49132 = DEFINITIONAL_REPRESENTATION('',(#49133),#49137); -#49133 = LINE('',#49134,#49135); -#49134 = CARTESIAN_POINT('',(0.943059757776,0.7)); -#49135 = VECTOR('',#49136,1.); -#49136 = DIRECTION('',(-1.,0.E+000)); -#49137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49138 = PCURVE('',#47546,#49139); -#49139 = DEFINITIONAL_REPRESENTATION('',(#49140),#49144); -#49140 = LINE('',#49141,#49142); -#49141 = CARTESIAN_POINT('',(-2.256940242224,1.225)); -#49142 = VECTOR('',#49143,1.); -#49143 = DIRECTION('',(-1.,0.E+000)); -#49144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49145 = ORIENTED_EDGE('',*,*,#49146,.F.); -#49146 = EDGE_CURVE('',#49147,#49124,#49149,.T.); -#49147 = VERTEX_POINT('',#49148); -#49148 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); -#49149 = SURFACE_CURVE('',#49150,(#49154,#49161),.PCURVE_S1.); -#49150 = LINE('',#49151,#49152); -#49151 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); -#49152 = VECTOR('',#49153,1.); -#49153 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49154 = PCURVE('',#48475,#49155); -#49155 = DEFINITIONAL_REPRESENTATION('',(#49156),#49160); -#49156 = LINE('',#49157,#49158); -#49157 = CARTESIAN_POINT('',(0.943059757776,0.E+000)); -#49158 = VECTOR('',#49159,1.); -#49159 = DIRECTION('',(0.E+000,1.)); -#49160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49161 = PCURVE('',#49162,#49167); -#49162 = CYLINDRICAL_SURFACE('',#49163,0.2); -#49163 = AXIS2_PLACEMENT_3D('',#49164,#49165,#49166); -#49164 = CARTESIAN_POINT('',(2.256940242224,1.025,-2.35)); -#49165 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49166 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49167 = DEFINITIONAL_REPRESENTATION('',(#49168),#49171); -#49168 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49169,#49170),.UNSPECIFIED., +#51507 = PCURVE('',#49966,#51508); +#51508 = DEFINITIONAL_REPRESENTATION('',(#51509),#51513); +#51509 = LINE('',#51510,#51511); +#51510 = CARTESIAN_POINT('',(0.3,0.E+000)); +#51511 = VECTOR('',#51512,1.); +#51512 = DIRECTION('',(-1.,0.E+000)); +#51513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51514 = ORIENTED_EDGE('',*,*,#51515,.F.); +#51515 = EDGE_CURVE('',#51516,#51493,#51518,.T.); +#51516 = VERTEX_POINT('',#51517); +#51517 = CARTESIAN_POINT('',(2.256940242224,1.225,-1.65)); +#51518 = SURFACE_CURVE('',#51519,(#51523,#51530),.PCURVE_S1.); +#51519 = LINE('',#51520,#51521); +#51520 = CARTESIAN_POINT('',(2.256940242224,1.225,-1.65)); +#51521 = VECTOR('',#51522,1.); +#51522 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51523 = PCURVE('',#50867,#51524); +#51524 = DEFINITIONAL_REPRESENTATION('',(#51525),#51529); +#51525 = LINE('',#51526,#51527); +#51526 = CARTESIAN_POINT('',(0.943059757776,0.7)); +#51527 = VECTOR('',#51528,1.); +#51528 = DIRECTION('',(-1.,0.E+000)); +#51529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51530 = PCURVE('',#49938,#51531); +#51531 = DEFINITIONAL_REPRESENTATION('',(#51532),#51536); +#51532 = LINE('',#51533,#51534); +#51533 = CARTESIAN_POINT('',(-2.256940242224,1.225)); +#51534 = VECTOR('',#51535,1.); +#51535 = DIRECTION('',(-1.,0.E+000)); +#51536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51537 = ORIENTED_EDGE('',*,*,#51538,.F.); +#51538 = EDGE_CURVE('',#51539,#51516,#51541,.T.); +#51539 = VERTEX_POINT('',#51540); +#51540 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); +#51541 = SURFACE_CURVE('',#51542,(#51546,#51553),.PCURVE_S1.); +#51542 = LINE('',#51543,#51544); +#51543 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); +#51544 = VECTOR('',#51545,1.); +#51545 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51546 = PCURVE('',#50867,#51547); +#51547 = DEFINITIONAL_REPRESENTATION('',(#51548),#51552); +#51548 = LINE('',#51549,#51550); +#51549 = CARTESIAN_POINT('',(0.943059757776,0.E+000)); +#51550 = VECTOR('',#51551,1.); +#51551 = DIRECTION('',(0.E+000,1.)); +#51552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51553 = PCURVE('',#51554,#51559); +#51554 = CYLINDRICAL_SURFACE('',#51555,0.2); +#51555 = AXIS2_PLACEMENT_3D('',#51556,#51557,#51558); +#51556 = CARTESIAN_POINT('',(2.256940242224,1.025,-2.35)); +#51557 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#51558 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51559 = DEFINITIONAL_REPRESENTATION('',(#51560),#51563); +#51560 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51561,#51562),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#49169 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49170 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#49171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49172 = ORIENTED_EDGE('',*,*,#49173,.T.); -#49173 = EDGE_CURVE('',#49147,#49174,#49176,.T.); -#49174 = VERTEX_POINT('',#49175); -#49175 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); -#49176 = SURFACE_CURVE('',#49177,(#49181,#49188),.PCURVE_S1.); -#49177 = LINE('',#49178,#49179); -#49178 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); -#49179 = VECTOR('',#49180,1.); -#49180 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49181 = PCURVE('',#48475,#49182); -#49182 = DEFINITIONAL_REPRESENTATION('',(#49183),#49187); -#49183 = LINE('',#49184,#49185); -#49184 = CARTESIAN_POINT('',(0.943059757776,0.E+000)); -#49185 = VECTOR('',#49186,1.); -#49186 = DIRECTION('',(-1.,0.E+000)); -#49187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49188 = PCURVE('',#39747,#49189); -#49189 = DEFINITIONAL_REPRESENTATION('',(#49190),#49194); -#49190 = LINE('',#49191,#49192); -#49191 = CARTESIAN_POINT('',(2.256940242224,1.225)); -#49192 = VECTOR('',#49193,1.); -#49193 = DIRECTION('',(1.,0.E+000)); -#49194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49195 = ORIENTED_EDGE('',*,*,#49196,.T.); -#49196 = EDGE_CURVE('',#49174,#38597,#49197,.T.); -#49197 = SURFACE_CURVE('',#49198,(#49202,#49209),.PCURVE_S1.); -#49198 = LINE('',#49199,#49200); -#49199 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); -#49200 = VECTOR('',#49201,1.); -#49201 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49202 = PCURVE('',#48475,#49203); -#49203 = DEFINITIONAL_REPRESENTATION('',(#49204),#49208); -#49204 = LINE('',#49205,#49206); -#49205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49206 = VECTOR('',#49207,1.); -#49207 = DIRECTION('',(0.E+000,1.)); -#49208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49209 = PCURVE('',#38641,#49210); -#49210 = DEFINITIONAL_REPRESENTATION('',(#49211),#49214); -#49211 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49212,#49213),.UNSPECIFIED., +#51561 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#51562 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#51563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51564 = ORIENTED_EDGE('',*,*,#51565,.T.); +#51565 = EDGE_CURVE('',#51539,#51566,#51568,.T.); +#51566 = VERTEX_POINT('',#51567); +#51567 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); +#51568 = SURFACE_CURVE('',#51569,(#51573,#51580),.PCURVE_S1.); +#51569 = LINE('',#51570,#51571); +#51570 = CARTESIAN_POINT('',(2.256940242224,1.225,-2.35)); +#51571 = VECTOR('',#51572,1.); +#51572 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51573 = PCURVE('',#50867,#51574); +#51574 = DEFINITIONAL_REPRESENTATION('',(#51575),#51579); +#51575 = LINE('',#51576,#51577); +#51576 = CARTESIAN_POINT('',(0.943059757776,0.E+000)); +#51577 = VECTOR('',#51578,1.); +#51578 = DIRECTION('',(-1.,0.E+000)); +#51579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51580 = PCURVE('',#42139,#51581); +#51581 = DEFINITIONAL_REPRESENTATION('',(#51582),#51586); +#51582 = LINE('',#51583,#51584); +#51583 = CARTESIAN_POINT('',(2.256940242224,1.225)); +#51584 = VECTOR('',#51585,1.); +#51585 = DIRECTION('',(1.,0.E+000)); +#51586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51587 = ORIENTED_EDGE('',*,*,#51588,.T.); +#51588 = EDGE_CURVE('',#51566,#40989,#51589,.T.); +#51589 = SURFACE_CURVE('',#51590,(#51594,#51601),.PCURVE_S1.); +#51590 = LINE('',#51591,#51592); +#51591 = CARTESIAN_POINT('',(3.2,1.225,-2.35)); +#51592 = VECTOR('',#51593,1.); +#51593 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51594 = PCURVE('',#50867,#51595); +#51595 = DEFINITIONAL_REPRESENTATION('',(#51596),#51600); +#51596 = LINE('',#51597,#51598); +#51597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51598 = VECTOR('',#51599,1.); +#51599 = DIRECTION('',(0.E+000,1.)); +#51600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51601 = PCURVE('',#41033,#51602); +#51602 = DEFINITIONAL_REPRESENTATION('',(#51603),#51606); +#51603 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51604,#51605),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#49212 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49213 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#49214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49215 = ORIENTED_EDGE('',*,*,#49216,.T.); -#49216 = EDGE_CURVE('',#38597,#38395,#49217,.T.); -#49217 = SURFACE_CURVE('',#49218,(#49222,#49229),.PCURVE_S1.); -#49218 = LINE('',#49219,#49220); -#49219 = CARTESIAN_POINT('',(3.2,1.225,2.35)); -#49220 = VECTOR('',#49221,1.); -#49221 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49222 = PCURVE('',#48475,#49223); -#49223 = DEFINITIONAL_REPRESENTATION('',(#49224),#49228); -#49224 = LINE('',#49225,#49226); -#49225 = CARTESIAN_POINT('',(0.E+000,4.7)); -#49226 = VECTOR('',#49227,1.); -#49227 = DIRECTION('',(1.,0.E+000)); -#49228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49229 = PCURVE('',#49230,#49235); -#49230 = PLANE('',#49231); -#49231 = AXIS2_PLACEMENT_3D('',#49232,#49233,#49234); -#49232 = CARTESIAN_POINT('',(3.2,1.47,2.545511428091)); -#49233 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#49234 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); -#49235 = DEFINITIONAL_REPRESENTATION('',(#49236),#49240); -#49236 = LINE('',#49237,#49238); -#49237 = CARTESIAN_POINT('',(0.313448111358,0.E+000)); -#49238 = VECTOR('',#49239,1.); -#49239 = DIRECTION('',(0.E+000,1.)); -#49240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49241 = ORIENTED_EDGE('',*,*,#49242,.F.); -#49242 = EDGE_CURVE('',#49243,#38395,#49245,.T.); -#49243 = VERTEX_POINT('',#49244); -#49244 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); -#49245 = SURFACE_CURVE('',#49246,(#49250,#49257),.PCURVE_S1.); -#49246 = LINE('',#49247,#49248); -#49247 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); -#49248 = VECTOR('',#49249,1.); -#49249 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49250 = PCURVE('',#48475,#49251); -#49251 = DEFINITIONAL_REPRESENTATION('',(#49252),#49256); -#49252 = LINE('',#49253,#49254); -#49253 = CARTESIAN_POINT('',(6.4,0.E+000)); -#49254 = VECTOR('',#49255,1.); -#49255 = DIRECTION('',(0.E+000,1.)); -#49256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49257 = PCURVE('',#38411,#49258); -#49258 = DEFINITIONAL_REPRESENTATION('',(#49259),#49262); -#49259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49260,#49261),.UNSPECIFIED., +#51604 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#51605 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#51606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51607 = ORIENTED_EDGE('',*,*,#51608,.T.); +#51608 = EDGE_CURVE('',#40989,#40787,#51609,.T.); +#51609 = SURFACE_CURVE('',#51610,(#51614,#51621),.PCURVE_S1.); +#51610 = LINE('',#51611,#51612); +#51611 = CARTESIAN_POINT('',(3.2,1.225,2.35)); +#51612 = VECTOR('',#51613,1.); +#51613 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51614 = PCURVE('',#50867,#51615); +#51615 = DEFINITIONAL_REPRESENTATION('',(#51616),#51620); +#51616 = LINE('',#51617,#51618); +#51617 = CARTESIAN_POINT('',(0.E+000,4.7)); +#51618 = VECTOR('',#51619,1.); +#51619 = DIRECTION('',(1.,0.E+000)); +#51620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51621 = PCURVE('',#51622,#51627); +#51622 = PLANE('',#51623); +#51623 = AXIS2_PLACEMENT_3D('',#51624,#51625,#51626); +#51624 = CARTESIAN_POINT('',(3.2,1.47,2.545511428091)); +#51625 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#51626 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); +#51627 = DEFINITIONAL_REPRESENTATION('',(#51628),#51632); +#51628 = LINE('',#51629,#51630); +#51629 = CARTESIAN_POINT('',(0.313448111358,0.E+000)); +#51630 = VECTOR('',#51631,1.); +#51631 = DIRECTION('',(0.E+000,1.)); +#51632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51633 = ORIENTED_EDGE('',*,*,#51634,.F.); +#51634 = EDGE_CURVE('',#51635,#40787,#51637,.T.); +#51635 = VERTEX_POINT('',#51636); +#51636 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); +#51637 = SURFACE_CURVE('',#51638,(#51642,#51649),.PCURVE_S1.); +#51638 = LINE('',#51639,#51640); +#51639 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); +#51640 = VECTOR('',#51641,1.); +#51641 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51642 = PCURVE('',#50867,#51643); +#51643 = DEFINITIONAL_REPRESENTATION('',(#51644),#51648); +#51644 = LINE('',#51645,#51646); +#51645 = CARTESIAN_POINT('',(6.4,0.E+000)); +#51646 = VECTOR('',#51647,1.); +#51647 = DIRECTION('',(0.E+000,1.)); +#51648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51649 = PCURVE('',#40803,#51650); +#51650 = DEFINITIONAL_REPRESENTATION('',(#51651),#51654); +#51651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51652,#51653),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#49260 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49261 = CARTESIAN_POINT('',(1.570796326795,4.7)); -#49262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#51652 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#51653 = CARTESIAN_POINT('',(1.570796326795,4.7)); +#51654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51655 = ORIENTED_EDGE('',*,*,#51656,.T.); +#51656 = EDGE_CURVE('',#51635,#51657,#51659,.T.); +#51657 = VERTEX_POINT('',#51658); +#51658 = CARTESIAN_POINT('',(-2.256940242224,1.225,-2.35)); +#51659 = SURFACE_CURVE('',#51660,(#51664,#51671),.PCURVE_S1.); +#51660 = LINE('',#51661,#51662); +#51661 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); +#51662 = VECTOR('',#51663,1.); +#51663 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51664 = PCURVE('',#50867,#51665); +#51665 = DEFINITIONAL_REPRESENTATION('',(#51666),#51670); +#51666 = LINE('',#51667,#51668); +#51667 = CARTESIAN_POINT('',(6.4,0.E+000)); +#51668 = VECTOR('',#51669,1.); +#51669 = DIRECTION('',(-1.,0.E+000)); +#51670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51671 = PCURVE('',#49747,#51672); +#51672 = DEFINITIONAL_REPRESENTATION('',(#51673),#51677); +#51673 = LINE('',#51674,#51675); +#51674 = CARTESIAN_POINT('',(-3.2,1.225)); +#51675 = VECTOR('',#51676,1.); +#51676 = DIRECTION('',(1.,0.E+000)); +#51677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51678 = ORIENTED_EDGE('',*,*,#51679,.T.); +#51679 = EDGE_CURVE('',#51657,#51680,#51682,.T.); +#51680 = VERTEX_POINT('',#51681); +#51681 = CARTESIAN_POINT('',(-2.256940242224,1.225,-1.65)); +#51682 = SURFACE_CURVE('',#51683,(#51687,#51694),.PCURVE_S1.); +#51683 = LINE('',#51684,#51685); +#51684 = CARTESIAN_POINT('',(-2.256940242224,1.225,-2.35)); +#51685 = VECTOR('',#51686,1.); +#51686 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51687 = PCURVE('',#50867,#51688); +#51688 = DEFINITIONAL_REPRESENTATION('',(#51689),#51693); +#51689 = LINE('',#51690,#51691); +#51690 = CARTESIAN_POINT('',(5.456940242224,0.E+000)); +#51691 = VECTOR('',#51692,1.); +#51692 = DIRECTION('',(0.E+000,1.)); +#51693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51694 = PCURVE('',#51695,#51700); +#51695 = CYLINDRICAL_SURFACE('',#51696,0.2); +#51696 = AXIS2_PLACEMENT_3D('',#51697,#51698,#51699); +#51697 = CARTESIAN_POINT('',(-2.256940242224,1.025,-2.35)); +#51698 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#51699 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51700 = DEFINITIONAL_REPRESENTATION('',(#51701),#51704); +#51701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51702,#51703),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); +#51702 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#51703 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#51704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#49263 = ORIENTED_EDGE('',*,*,#49264,.T.); -#49264 = EDGE_CURVE('',#49243,#49265,#49267,.T.); -#49265 = VERTEX_POINT('',#49266); -#49266 = CARTESIAN_POINT('',(-2.256940242224,1.225,-2.35)); -#49267 = SURFACE_CURVE('',#49268,(#49272,#49279),.PCURVE_S1.); -#49268 = LINE('',#49269,#49270); -#49269 = CARTESIAN_POINT('',(-3.2,1.225,-2.35)); -#49270 = VECTOR('',#49271,1.); -#49271 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49272 = PCURVE('',#48475,#49273); -#49273 = DEFINITIONAL_REPRESENTATION('',(#49274),#49278); -#49274 = LINE('',#49275,#49276); -#49275 = CARTESIAN_POINT('',(6.4,0.E+000)); -#49276 = VECTOR('',#49277,1.); -#49277 = DIRECTION('',(-1.,0.E+000)); -#49278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49279 = PCURVE('',#47355,#49280); -#49280 = DEFINITIONAL_REPRESENTATION('',(#49281),#49285); -#49281 = LINE('',#49282,#49283); -#49282 = CARTESIAN_POINT('',(-3.2,1.225)); -#49283 = VECTOR('',#49284,1.); -#49284 = DIRECTION('',(1.,0.E+000)); -#49285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49286 = ORIENTED_EDGE('',*,*,#49287,.T.); -#49287 = EDGE_CURVE('',#49265,#49288,#49290,.T.); -#49288 = VERTEX_POINT('',#49289); -#49289 = CARTESIAN_POINT('',(-2.256940242224,1.225,-1.65)); -#49290 = SURFACE_CURVE('',#49291,(#49295,#49302),.PCURVE_S1.); -#49291 = LINE('',#49292,#49293); -#49292 = CARTESIAN_POINT('',(-2.256940242224,1.225,-2.35)); -#49293 = VECTOR('',#49294,1.); -#49294 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49295 = PCURVE('',#48475,#49296); -#49296 = DEFINITIONAL_REPRESENTATION('',(#49297),#49301); -#49297 = LINE('',#49298,#49299); -#49298 = CARTESIAN_POINT('',(5.456940242224,0.E+000)); -#49299 = VECTOR('',#49300,1.); -#49300 = DIRECTION('',(0.E+000,1.)); -#49301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49302 = PCURVE('',#49303,#49308); -#49303 = CYLINDRICAL_SURFACE('',#49304,0.2); -#49304 = AXIS2_PLACEMENT_3D('',#49305,#49306,#49307); -#49305 = CARTESIAN_POINT('',(-2.256940242224,1.025,-2.35)); -#49306 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49307 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49308 = DEFINITIONAL_REPRESENTATION('',(#49309),#49312); -#49309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49310,#49311),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#49310 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49311 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#49312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49313 = ORIENTED_EDGE('',*,*,#49314,.F.); -#49314 = EDGE_CURVE('',#49315,#49288,#49317,.T.); -#49315 = VERTEX_POINT('',#49316); -#49316 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); -#49317 = SURFACE_CURVE('',#49318,(#49322,#49329),.PCURVE_S1.); -#49318 = LINE('',#49319,#49320); -#49319 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); -#49320 = VECTOR('',#49321,1.); -#49321 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49322 = PCURVE('',#48475,#49323); -#49323 = DEFINITIONAL_REPRESENTATION('',(#49324),#49328); -#49324 = LINE('',#49325,#49326); -#49325 = CARTESIAN_POINT('',(5.57,0.7)); -#49326 = VECTOR('',#49327,1.); -#49327 = DIRECTION('',(-1.,0.E+000)); -#49328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49329 = PCURVE('',#47300,#49330); -#49330 = DEFINITIONAL_REPRESENTATION('',(#49331),#49335); -#49331 = LINE('',#49332,#49333); -#49332 = CARTESIAN_POINT('',(2.37,1.225)); -#49333 = VECTOR('',#49334,1.); -#49334 = DIRECTION('',(-1.,0.E+000)); -#49335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49336 = ORIENTED_EDGE('',*,*,#49337,.T.); -#49337 = EDGE_CURVE('',#49315,#49338,#49340,.T.); -#49338 = VERTEX_POINT('',#49339); -#49339 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); -#49340 = SURFACE_CURVE('',#49341,(#49345,#49352),.PCURVE_S1.); -#49341 = LINE('',#49342,#49343); -#49342 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); -#49343 = VECTOR('',#49344,1.); -#49344 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49345 = PCURVE('',#48475,#49346); -#49346 = DEFINITIONAL_REPRESENTATION('',(#49347),#49351); -#49347 = LINE('',#49348,#49349); -#49348 = CARTESIAN_POINT('',(5.57,0.7)); -#49349 = VECTOR('',#49350,1.); -#49350 = DIRECTION('',(0.E+000,1.)); -#49351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49352 = PCURVE('',#47272,#49353); -#49353 = DEFINITIONAL_REPRESENTATION('',(#49354),#49358); -#49354 = LINE('',#49355,#49356); -#49355 = CARTESIAN_POINT('',(0.7,0.E+000)); -#49356 = VECTOR('',#49357,1.); -#49357 = DIRECTION('',(1.,0.E+000)); -#49358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49359 = ORIENTED_EDGE('',*,*,#49360,.T.); -#49360 = EDGE_CURVE('',#49338,#49361,#49363,.T.); -#49361 = VERTEX_POINT('',#49362); -#49362 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); -#49363 = SURFACE_CURVE('',#49364,(#49368,#49375),.PCURVE_S1.); -#49364 = LINE('',#49365,#49366); -#49365 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); -#49366 = VECTOR('',#49367,1.); -#49367 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49368 = PCURVE('',#48475,#49369); -#49369 = DEFINITIONAL_REPRESENTATION('',(#49370),#49374); -#49370 = LINE('',#49371,#49372); -#49371 = CARTESIAN_POINT('',(5.57,1.)); -#49372 = VECTOR('',#49373,1.); -#49373 = DIRECTION('',(-1.,0.E+000)); -#49374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49375 = PCURVE('',#47244,#49376); -#49376 = DEFINITIONAL_REPRESENTATION('',(#49377),#49381); -#49377 = LINE('',#49378,#49379); -#49378 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49379 = VECTOR('',#49380,1.); -#49380 = DIRECTION('',(1.,0.E+000)); -#49381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49382 = ORIENTED_EDGE('',*,*,#49383,.T.); -#49383 = EDGE_CURVE('',#49361,#49026,#49384,.T.); -#49384 = SURFACE_CURVE('',#49385,(#49389,#49396),.PCURVE_S1.); -#49385 = LINE('',#49386,#49387); -#49386 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); -#49387 = VECTOR('',#49388,1.); -#49388 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49389 = PCURVE('',#48475,#49390); -#49390 = DEFINITIONAL_REPRESENTATION('',(#49391),#49395); -#49391 = LINE('',#49392,#49393); -#49392 = CARTESIAN_POINT('',(4.41,1.)); -#49393 = VECTOR('',#49394,1.); -#49394 = DIRECTION('',(0.E+000,-1.)); -#49395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49396 = PCURVE('',#47216,#49397); -#49397 = DEFINITIONAL_REPRESENTATION('',(#49398),#49402); -#49398 = LINE('',#49399,#49400); -#49399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49400 = VECTOR('',#49401,1.); -#49401 = DIRECTION('',(1.,0.E+000)); -#49402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49403 = FACE_BOUND('',#49404,.F.); -#49404 = EDGE_LOOP('',(#49405,#49428,#49479,#49480,#49481,#49482,#49483, - #49506,#49529,#49552,#49575,#49598,#49621,#49644,#49667,#49688)); -#49405 = ORIENTED_EDGE('',*,*,#49406,.T.); -#49406 = EDGE_CURVE('',#48566,#49407,#49409,.T.); -#49407 = VERTEX_POINT('',#49408); -#49408 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); -#49409 = SURFACE_CURVE('',#49410,(#49414,#49421),.PCURVE_S1.); -#49410 = LINE('',#49411,#49412); -#49411 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); -#49412 = VECTOR('',#49413,1.); -#49413 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49414 = PCURVE('',#48475,#49415); -#49415 = DEFINITIONAL_REPRESENTATION('',(#49416),#49420); -#49416 = LINE('',#49417,#49418); -#49417 = CARTESIAN_POINT('',(1.175,3.756188021535)); -#49418 = VECTOR('',#49419,1.); -#49419 = DIRECTION('',(0.E+000,1.)); -#49420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49421 = PCURVE('',#48709,#49422); -#49422 = DEFINITIONAL_REPRESENTATION('',(#49423),#49427); -#49423 = LINE('',#49424,#49425); -#49424 = CARTESIAN_POINT('',(1.406188021535,1.225)); -#49425 = VECTOR('',#49426,1.); -#49426 = DIRECTION('',(1.,0.E+000)); -#49427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49428 = ORIENTED_EDGE('',*,*,#49429,.F.); -#49429 = EDGE_CURVE('',#48952,#49407,#49430,.T.); -#49430 = SURFACE_CURVE('',#49431,(#49439,#49450),.PCURVE_S1.); -#49431 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49432,#49433,#49434,#49435, - #49436,#49437,#49438),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, - 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#49432 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); -#49433 = CARTESIAN_POINT('',(2.18908832436,1.225,1.752598183049)); -#49434 = CARTESIAN_POINT('',(2.135890928678,1.225,1.733972227452)); -#49435 = CARTESIAN_POINT('',(2.077484147545,1.225,1.684643981667)); -#49436 = CARTESIAN_POINT('',(2.038001629204,1.225,1.616391473089)); -#49437 = CARTESIAN_POINT('',(2.025,1.225,1.557569751013)); -#49438 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); -#49439 = PCURVE('',#48475,#49440); -#49440 = DEFINITIONAL_REPRESENTATION('',(#49441),#49449); -#49441 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49442,#49443,#49444,#49445, - #49446,#49447,#49448),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, - 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#49442 = CARTESIAN_POINT('',(0.975,4.102598183049)); -#49443 = CARTESIAN_POINT('',(1.01091167564,4.102598183049)); -#49444 = CARTESIAN_POINT('',(1.064109071322,4.083972227452)); -#49445 = CARTESIAN_POINT('',(1.122515852455,4.034643981667)); -#49446 = CARTESIAN_POINT('',(1.161998370796,3.966391473089)); -#49447 = CARTESIAN_POINT('',(1.175,3.907569751013)); -#49448 = CARTESIAN_POINT('',(1.175,3.871658075373)); -#49449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#51705 = ORIENTED_EDGE('',*,*,#51706,.F.); +#51706 = EDGE_CURVE('',#51707,#51680,#51709,.T.); +#51707 = VERTEX_POINT('',#51708); +#51708 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); +#51709 = SURFACE_CURVE('',#51710,(#51714,#51721),.PCURVE_S1.); +#51710 = LINE('',#51711,#51712); +#51711 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); +#51712 = VECTOR('',#51713,1.); +#51713 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51714 = PCURVE('',#50867,#51715); +#51715 = DEFINITIONAL_REPRESENTATION('',(#51716),#51720); +#51716 = LINE('',#51717,#51718); +#51717 = CARTESIAN_POINT('',(5.57,0.7)); +#51718 = VECTOR('',#51719,1.); +#51719 = DIRECTION('',(-1.,0.E+000)); +#51720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51721 = PCURVE('',#49692,#51722); +#51722 = DEFINITIONAL_REPRESENTATION('',(#51723),#51727); +#51723 = LINE('',#51724,#51725); +#51724 = CARTESIAN_POINT('',(2.37,1.225)); +#51725 = VECTOR('',#51726,1.); +#51726 = DIRECTION('',(-1.,0.E+000)); +#51727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#49450 = PCURVE('',#48990,#49451); -#49451 = DEFINITIONAL_REPRESENTATION('',(#49452),#49478); -#49452 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49453,#49454,#49455,#49456, - #49457,#49458,#49459,#49460,#49461,#49462,#49463,#49464,#49465, - #49466,#49467,#49468,#49469,#49470,#49471,#49472,#49473,#49474, - #49475,#49476,#49477),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#51728 = ORIENTED_EDGE('',*,*,#51729,.T.); +#51729 = EDGE_CURVE('',#51707,#51730,#51732,.T.); +#51730 = VERTEX_POINT('',#51731); +#51731 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); +#51732 = SURFACE_CURVE('',#51733,(#51737,#51744),.PCURVE_S1.); +#51733 = LINE('',#51734,#51735); +#51734 = CARTESIAN_POINT('',(-2.37,1.225,-1.65)); +#51735 = VECTOR('',#51736,1.); +#51736 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51737 = PCURVE('',#50867,#51738); +#51738 = DEFINITIONAL_REPRESENTATION('',(#51739),#51743); +#51739 = LINE('',#51740,#51741); +#51740 = CARTESIAN_POINT('',(5.57,0.7)); +#51741 = VECTOR('',#51742,1.); +#51742 = DIRECTION('',(0.E+000,1.)); +#51743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51744 = PCURVE('',#49664,#51745); +#51745 = DEFINITIONAL_REPRESENTATION('',(#51746),#51750); +#51746 = LINE('',#51747,#51748); +#51747 = CARTESIAN_POINT('',(0.7,0.E+000)); +#51748 = VECTOR('',#51749,1.); +#51749 = DIRECTION('',(1.,0.E+000)); +#51750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51751 = ORIENTED_EDGE('',*,*,#51752,.T.); +#51752 = EDGE_CURVE('',#51730,#51753,#51755,.T.); +#51753 = VERTEX_POINT('',#51754); +#51754 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); +#51755 = SURFACE_CURVE('',#51756,(#51760,#51767),.PCURVE_S1.); +#51756 = LINE('',#51757,#51758); +#51757 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); +#51758 = VECTOR('',#51759,1.); +#51759 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51760 = PCURVE('',#50867,#51761); +#51761 = DEFINITIONAL_REPRESENTATION('',(#51762),#51766); +#51762 = LINE('',#51763,#51764); +#51763 = CARTESIAN_POINT('',(5.57,1.)); +#51764 = VECTOR('',#51765,1.); +#51765 = DIRECTION('',(-1.,0.E+000)); +#51766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51767 = PCURVE('',#49636,#51768); +#51768 = DEFINITIONAL_REPRESENTATION('',(#51769),#51773); +#51769 = LINE('',#51770,#51771); +#51770 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51771 = VECTOR('',#51772,1.); +#51772 = DIRECTION('',(1.,0.E+000)); +#51773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51774 = ORIENTED_EDGE('',*,*,#51775,.T.); +#51775 = EDGE_CURVE('',#51753,#51418,#51776,.T.); +#51776 = SURFACE_CURVE('',#51777,(#51781,#51788),.PCURVE_S1.); +#51777 = LINE('',#51778,#51779); +#51778 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); +#51779 = VECTOR('',#51780,1.); +#51780 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#51781 = PCURVE('',#50867,#51782); +#51782 = DEFINITIONAL_REPRESENTATION('',(#51783),#51787); +#51783 = LINE('',#51784,#51785); +#51784 = CARTESIAN_POINT('',(4.41,1.)); +#51785 = VECTOR('',#51786,1.); +#51786 = DIRECTION('',(0.E+000,-1.)); +#51787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51788 = PCURVE('',#49608,#51789); +#51789 = DEFINITIONAL_REPRESENTATION('',(#51790),#51794); +#51790 = LINE('',#51791,#51792); +#51791 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51792 = VECTOR('',#51793,1.); +#51793 = DIRECTION('',(1.,0.E+000)); +#51794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51795 = FACE_BOUND('',#51796,.F.); +#51796 = EDGE_LOOP('',(#51797,#51820,#51871,#51872,#51873,#51874,#51875, + #51898,#51921,#51944,#51967,#51990,#52013,#52036,#52059,#52080)); +#51797 = ORIENTED_EDGE('',*,*,#51798,.T.); +#51798 = EDGE_CURVE('',#50958,#51799,#51801,.T.); +#51799 = VERTEX_POINT('',#51800); +#51800 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); +#51801 = SURFACE_CURVE('',#51802,(#51806,#51813),.PCURVE_S1.); +#51802 = LINE('',#51803,#51804); +#51803 = CARTESIAN_POINT('',(2.025,1.225,1.406188021535)); +#51804 = VECTOR('',#51805,1.); +#51805 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51806 = PCURVE('',#50867,#51807); +#51807 = DEFINITIONAL_REPRESENTATION('',(#51808),#51812); +#51808 = LINE('',#51809,#51810); +#51809 = CARTESIAN_POINT('',(1.175,3.756188021535)); +#51810 = VECTOR('',#51811,1.); +#51811 = DIRECTION('',(0.E+000,1.)); +#51812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51813 = PCURVE('',#51101,#51814); +#51814 = DEFINITIONAL_REPRESENTATION('',(#51815),#51819); +#51815 = LINE('',#51816,#51817); +#51816 = CARTESIAN_POINT('',(1.406188021535,1.225)); +#51817 = VECTOR('',#51818,1.); +#51818 = DIRECTION('',(1.,0.E+000)); +#51819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51820 = ORIENTED_EDGE('',*,*,#51821,.F.); +#51821 = EDGE_CURVE('',#51344,#51799,#51822,.T.); +#51822 = SURFACE_CURVE('',#51823,(#51831,#51842),.PCURVE_S1.); +#51823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51824,#51825,#51826,#51827, + #51828,#51829,#51830),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, + 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); +#51824 = CARTESIAN_POINT('',(2.225,1.225,1.752598183049)); +#51825 = CARTESIAN_POINT('',(2.18908832436,1.225,1.752598183049)); +#51826 = CARTESIAN_POINT('',(2.135890928678,1.225,1.733972227452)); +#51827 = CARTESIAN_POINT('',(2.077484147545,1.225,1.684643981667)); +#51828 = CARTESIAN_POINT('',(2.038001629204,1.225,1.616391473089)); +#51829 = CARTESIAN_POINT('',(2.025,1.225,1.557569751013)); +#51830 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); +#51831 = PCURVE('',#50867,#51832); +#51832 = DEFINITIONAL_REPRESENTATION('',(#51833),#51841); +#51833 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51834,#51835,#51836,#51837, + #51838,#51839,#51840),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, + 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); +#51834 = CARTESIAN_POINT('',(0.975,4.102598183049)); +#51835 = CARTESIAN_POINT('',(1.01091167564,4.102598183049)); +#51836 = CARTESIAN_POINT('',(1.064109071322,4.083972227452)); +#51837 = CARTESIAN_POINT('',(1.122515852455,4.034643981667)); +#51838 = CARTESIAN_POINT('',(1.161998370796,3.966391473089)); +#51839 = CARTESIAN_POINT('',(1.175,3.907569751013)); +#51840 = CARTESIAN_POINT('',(1.175,3.871658075373)); +#51841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51842 = PCURVE('',#51382,#51843); +#51843 = DEFINITIONAL_REPRESENTATION('',(#51844),#51870); +#51844 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#51845,#51846,#51847,#51848, + #51849,#51850,#51851,#51852,#51853,#51854,#51855,#51856,#51857, + #51858,#51859,#51860,#51861,#51862,#51863,#51864,#51865,#51866, + #51867,#51868,#51869),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -61556,360 +64545,360 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#49453 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); -#49454 = CARTESIAN_POINT('',(1.538150472706,1.578593750971E-002)); -#49455 = CARTESIAN_POINT('',(1.475938790177,1.609381156706E-002)); -#49456 = CARTESIAN_POINT('',(1.390269427501,1.73755345754E-002)); -#49457 = CARTESIAN_POINT('',(1.310617785153,1.937371207315E-002)); -#49458 = CARTESIAN_POINT('',(1.235488259696,2.198400176841E-002)); -#49459 = CARTESIAN_POINT('',(1.163604914097,2.510534798852E-002)); -#49460 = CARTESIAN_POINT('',(1.093878332085,2.862443344278E-002)); -#49461 = CARTESIAN_POINT('',(1.025778930211,3.248573056004E-002)); -#49462 = CARTESIAN_POINT('',(0.959080929045,3.669150144007E-002)); -#49463 = CARTESIAN_POINT('',(0.893473353309,4.123174671037E-002)); -#49464 = CARTESIAN_POINT('',(0.828660646633,4.60997530833E-002)); -#49465 = CARTESIAN_POINT('',(0.764347001395,5.128792440398E-002)); -#49466 = CARTESIAN_POINT('',(0.700253440983,5.678890990165E-002)); -#49467 = CARTESIAN_POINT('',(0.63610989114,6.260584123723E-002)); -#49468 = CARTESIAN_POINT('',(0.571633992936,6.874199936464E-002)); -#49469 = CARTESIAN_POINT('',(0.506543398686,7.520016673501E-002)); -#49470 = CARTESIAN_POINT('',(0.440551827007,8.198497051765E-002)); -#49471 = CARTESIAN_POINT('',(0.373415877511,8.909415751192E-002)); -#49472 = CARTESIAN_POINT('',(0.304771298168,9.655790146718E-002)); -#49473 = CARTESIAN_POINT('',(0.233989615752,0.104438803034)); -#49474 = CARTESIAN_POINT('',(0.160334717441,0.11279258264)); -#49475 = CARTESIAN_POINT('',(8.295804594423E-002,0.121676804894)); -#49476 = CARTESIAN_POINT('',(2.827076521617E-002,0.127991293562)); -#49477 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); -#49478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49479 = ORIENTED_EDGE('',*,*,#48951,.F.); -#49480 = ORIENTED_EDGE('',*,*,#48851,.F.); -#49481 = ORIENTED_EDGE('',*,*,#48798,.F.); -#49482 = ORIENTED_EDGE('',*,*,#48459,.T.); -#49483 = ORIENTED_EDGE('',*,*,#49484,.T.); -#49484 = EDGE_CURVE('',#48437,#49485,#49487,.T.); -#49485 = VERTEX_POINT('',#49486); -#49486 = CARTESIAN_POINT('',(2.85,1.225,1.35)); -#49487 = SURFACE_CURVE('',#49488,(#49492,#49499),.PCURVE_S1.); -#49488 = LINE('',#49489,#49490); -#49489 = CARTESIAN_POINT('',(2.725,1.225,1.35)); -#49490 = VECTOR('',#49491,1.); -#49491 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49492 = PCURVE('',#48475,#49493); -#49493 = DEFINITIONAL_REPRESENTATION('',(#49494),#49498); -#49494 = LINE('',#49495,#49496); -#49495 = CARTESIAN_POINT('',(0.475,3.7)); -#49496 = VECTOR('',#49497,1.); -#49497 = DIRECTION('',(-1.,0.E+000)); -#49498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49499 = PCURVE('',#48001,#49500); -#49500 = DEFINITIONAL_REPRESENTATION('',(#49501),#49505); -#49501 = LINE('',#49502,#49503); -#49502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49503 = VECTOR('',#49504,1.); -#49504 = DIRECTION('',(1.,0.E+000)); -#49505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49506 = ORIENTED_EDGE('',*,*,#49507,.T.); -#49507 = EDGE_CURVE('',#49485,#49508,#49510,.T.); -#49508 = VERTEX_POINT('',#49509); -#49509 = CARTESIAN_POINT('',(2.85,1.225,1.1)); -#49510 = SURFACE_CURVE('',#49511,(#49516,#49523),.PCURVE_S1.); -#49511 = CIRCLE('',#49512,0.125); -#49512 = AXIS2_PLACEMENT_3D('',#49513,#49514,#49515); -#49513 = CARTESIAN_POINT('',(2.85,1.225,1.225)); -#49514 = DIRECTION('',(0.E+000,1.,0.E+000)); -#49515 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49516 = PCURVE('',#48475,#49517); -#49517 = DEFINITIONAL_REPRESENTATION('',(#49518),#49522); -#49518 = CIRCLE('',#49519,0.125); -#49519 = AXIS2_PLACEMENT_2D('',#49520,#49521); -#49520 = CARTESIAN_POINT('',(0.35,3.575)); -#49521 = DIRECTION('',(0.E+000,1.)); -#49522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49523 = PCURVE('',#47976,#49524); -#49524 = DEFINITIONAL_REPRESENTATION('',(#49525),#49528); -#49525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49526,#49527),.UNSPECIFIED., +#51845 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); +#51846 = CARTESIAN_POINT('',(1.538150472706,1.578593750971E-002)); +#51847 = CARTESIAN_POINT('',(1.475938790177,1.609381156706E-002)); +#51848 = CARTESIAN_POINT('',(1.390269427501,1.73755345754E-002)); +#51849 = CARTESIAN_POINT('',(1.310617785153,1.937371207315E-002)); +#51850 = CARTESIAN_POINT('',(1.235488259696,2.198400176841E-002)); +#51851 = CARTESIAN_POINT('',(1.163604914097,2.510534798852E-002)); +#51852 = CARTESIAN_POINT('',(1.093878332085,2.862443344278E-002)); +#51853 = CARTESIAN_POINT('',(1.025778930211,3.248573056004E-002)); +#51854 = CARTESIAN_POINT('',(0.959080929045,3.669150144007E-002)); +#51855 = CARTESIAN_POINT('',(0.893473353309,4.123174671037E-002)); +#51856 = CARTESIAN_POINT('',(0.828660646633,4.60997530833E-002)); +#51857 = CARTESIAN_POINT('',(0.764347001395,5.128792440398E-002)); +#51858 = CARTESIAN_POINT('',(0.700253440983,5.678890990165E-002)); +#51859 = CARTESIAN_POINT('',(0.63610989114,6.260584123723E-002)); +#51860 = CARTESIAN_POINT('',(0.571633992936,6.874199936464E-002)); +#51861 = CARTESIAN_POINT('',(0.506543398686,7.520016673501E-002)); +#51862 = CARTESIAN_POINT('',(0.440551827007,8.198497051765E-002)); +#51863 = CARTESIAN_POINT('',(0.373415877511,8.909415751192E-002)); +#51864 = CARTESIAN_POINT('',(0.304771298168,9.655790146718E-002)); +#51865 = CARTESIAN_POINT('',(0.233989615752,0.104438803034)); +#51866 = CARTESIAN_POINT('',(0.160334717441,0.11279258264)); +#51867 = CARTESIAN_POINT('',(8.295804594423E-002,0.121676804894)); +#51868 = CARTESIAN_POINT('',(2.827076521617E-002,0.127991293562)); +#51869 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); +#51870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51871 = ORIENTED_EDGE('',*,*,#51343,.F.); +#51872 = ORIENTED_EDGE('',*,*,#51243,.F.); +#51873 = ORIENTED_EDGE('',*,*,#51190,.F.); +#51874 = ORIENTED_EDGE('',*,*,#50851,.T.); +#51875 = ORIENTED_EDGE('',*,*,#51876,.T.); +#51876 = EDGE_CURVE('',#50829,#51877,#51879,.T.); +#51877 = VERTEX_POINT('',#51878); +#51878 = CARTESIAN_POINT('',(2.85,1.225,1.35)); +#51879 = SURFACE_CURVE('',#51880,(#51884,#51891),.PCURVE_S1.); +#51880 = LINE('',#51881,#51882); +#51881 = CARTESIAN_POINT('',(2.725,1.225,1.35)); +#51882 = VECTOR('',#51883,1.); +#51883 = DIRECTION('',(1.,0.E+000,0.E+000)); +#51884 = PCURVE('',#50867,#51885); +#51885 = DEFINITIONAL_REPRESENTATION('',(#51886),#51890); +#51886 = LINE('',#51887,#51888); +#51887 = CARTESIAN_POINT('',(0.475,3.7)); +#51888 = VECTOR('',#51889,1.); +#51889 = DIRECTION('',(-1.,0.E+000)); +#51890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51891 = PCURVE('',#50393,#51892); +#51892 = DEFINITIONAL_REPRESENTATION('',(#51893),#51897); +#51893 = LINE('',#51894,#51895); +#51894 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51895 = VECTOR('',#51896,1.); +#51896 = DIRECTION('',(1.,0.E+000)); +#51897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51898 = ORIENTED_EDGE('',*,*,#51899,.T.); +#51899 = EDGE_CURVE('',#51877,#51900,#51902,.T.); +#51900 = VERTEX_POINT('',#51901); +#51901 = CARTESIAN_POINT('',(2.85,1.225,1.1)); +#51902 = SURFACE_CURVE('',#51903,(#51908,#51915),.PCURVE_S1.); +#51903 = CIRCLE('',#51904,0.125); +#51904 = AXIS2_PLACEMENT_3D('',#51905,#51906,#51907); +#51905 = CARTESIAN_POINT('',(2.85,1.225,1.225)); +#51906 = DIRECTION('',(0.E+000,1.,0.E+000)); +#51907 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51908 = PCURVE('',#50867,#51909); +#51909 = DEFINITIONAL_REPRESENTATION('',(#51910),#51914); +#51910 = CIRCLE('',#51911,0.125); +#51911 = AXIS2_PLACEMENT_2D('',#51912,#51913); +#51912 = CARTESIAN_POINT('',(0.35,3.575)); +#51913 = DIRECTION('',(0.E+000,1.)); +#51914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51915 = PCURVE('',#50368,#51916); +#51916 = DEFINITIONAL_REPRESENTATION('',(#51917),#51920); +#51917 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51918,#51919),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#49526 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); -#49527 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49529 = ORIENTED_EDGE('',*,*,#49530,.T.); -#49530 = EDGE_CURVE('',#49508,#49531,#49533,.T.); -#49531 = VERTEX_POINT('',#49532); -#49532 = CARTESIAN_POINT('',(2.725,1.225,1.1)); -#49533 = SURFACE_CURVE('',#49534,(#49538,#49545),.PCURVE_S1.); -#49534 = LINE('',#49535,#49536); -#49535 = CARTESIAN_POINT('',(2.85,1.225,1.1)); -#49536 = VECTOR('',#49537,1.); -#49537 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49538 = PCURVE('',#48475,#49539); -#49539 = DEFINITIONAL_REPRESENTATION('',(#49540),#49544); -#49540 = LINE('',#49541,#49542); -#49541 = CARTESIAN_POINT('',(0.35,3.45)); -#49542 = VECTOR('',#49543,1.); -#49543 = DIRECTION('',(1.,0.E+000)); -#49544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49545 = PCURVE('',#47943,#49546); -#49546 = DEFINITIONAL_REPRESENTATION('',(#49547),#49551); -#49547 = LINE('',#49548,#49549); -#49548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49549 = VECTOR('',#49550,1.); -#49550 = DIRECTION('',(1.,0.E+000)); -#49551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49552 = ORIENTED_EDGE('',*,*,#49553,.T.); -#49553 = EDGE_CURVE('',#49531,#49554,#49556,.T.); -#49554 = VERTEX_POINT('',#49555); -#49555 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); -#49556 = SURFACE_CURVE('',#49557,(#49561,#49568),.PCURVE_S1.); -#49557 = LINE('',#49558,#49559); -#49558 = CARTESIAN_POINT('',(2.725,1.225,1.1)); -#49559 = VECTOR('',#49560,1.); -#49560 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49561 = PCURVE('',#48475,#49562); -#49562 = DEFINITIONAL_REPRESENTATION('',(#49563),#49567); -#49563 = LINE('',#49564,#49565); -#49564 = CARTESIAN_POINT('',(0.475,3.45)); -#49565 = VECTOR('',#49566,1.); -#49566 = DIRECTION('',(0.E+000,-1.)); -#49567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49568 = PCURVE('',#47915,#49569); -#49569 = DEFINITIONAL_REPRESENTATION('',(#49570),#49574); -#49570 = LINE('',#49571,#49572); -#49571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49572 = VECTOR('',#49573,1.); -#49573 = DIRECTION('',(1.,0.E+000)); -#49574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49575 = ORIENTED_EDGE('',*,*,#49576,.T.); -#49576 = EDGE_CURVE('',#49554,#49577,#49579,.T.); -#49577 = VERTEX_POINT('',#49578); -#49578 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); -#49579 = SURFACE_CURVE('',#49580,(#49584,#49591),.PCURVE_S1.); -#49580 = LINE('',#49581,#49582); -#49581 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); -#49582 = VECTOR('',#49583,1.); -#49583 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49584 = PCURVE('',#48475,#49585); -#49585 = DEFINITIONAL_REPRESENTATION('',(#49586),#49590); -#49586 = LINE('',#49587,#49588); -#49587 = CARTESIAN_POINT('',(0.475,2.23)); -#49588 = VECTOR('',#49589,1.); -#49589 = DIRECTION('',(1.,0.E+000)); -#49590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49591 = PCURVE('',#47887,#49592); -#49592 = DEFINITIONAL_REPRESENTATION('',(#49593),#49597); -#49593 = LINE('',#49594,#49595); -#49594 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49595 = VECTOR('',#49596,1.); -#49596 = DIRECTION('',(1.,0.E+000)); -#49597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49598 = ORIENTED_EDGE('',*,*,#49599,.T.); -#49599 = EDGE_CURVE('',#49577,#49600,#49602,.T.); -#49600 = VERTEX_POINT('',#49601); -#49601 = CARTESIAN_POINT('',(2.025,1.225,1.1)); -#49602 = SURFACE_CURVE('',#49603,(#49607,#49614),.PCURVE_S1.); -#49603 = LINE('',#49604,#49605); -#49604 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); -#49605 = VECTOR('',#49606,1.); -#49606 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49607 = PCURVE('',#48475,#49608); -#49608 = DEFINITIONAL_REPRESENTATION('',(#49609),#49613); -#49609 = LINE('',#49610,#49611); -#49610 = CARTESIAN_POINT('',(1.175,2.23)); -#49611 = VECTOR('',#49612,1.); -#49612 = DIRECTION('',(0.E+000,1.)); -#49613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49614 = PCURVE('',#47859,#49615); -#49615 = DEFINITIONAL_REPRESENTATION('',(#49616),#49620); -#49616 = LINE('',#49617,#49618); -#49617 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49618 = VECTOR('',#49619,1.); -#49619 = DIRECTION('',(1.,0.E+000)); -#49620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49621 = ORIENTED_EDGE('',*,*,#49622,.T.); -#49622 = EDGE_CURVE('',#49600,#49623,#49625,.T.); -#49623 = VERTEX_POINT('',#49624); -#49624 = CARTESIAN_POINT('',(1.9,1.225,1.1)); -#49625 = SURFACE_CURVE('',#49626,(#49630,#49637),.PCURVE_S1.); -#49626 = LINE('',#49627,#49628); -#49627 = CARTESIAN_POINT('',(2.025,1.225,1.1)); -#49628 = VECTOR('',#49629,1.); -#49629 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49630 = PCURVE('',#48475,#49631); -#49631 = DEFINITIONAL_REPRESENTATION('',(#49632),#49636); -#49632 = LINE('',#49633,#49634); -#49633 = CARTESIAN_POINT('',(1.175,3.45)); -#49634 = VECTOR('',#49635,1.); -#49635 = DIRECTION('',(1.,0.E+000)); -#49636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49637 = PCURVE('',#47831,#49638); -#49638 = DEFINITIONAL_REPRESENTATION('',(#49639),#49643); -#49639 = LINE('',#49640,#49641); -#49640 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49641 = VECTOR('',#49642,1.); -#49642 = DIRECTION('',(1.,0.E+000)); -#49643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49644 = ORIENTED_EDGE('',*,*,#49645,.T.); -#49645 = EDGE_CURVE('',#49623,#49646,#49648,.T.); -#49646 = VERTEX_POINT('',#49647); -#49647 = CARTESIAN_POINT('',(1.9,1.225,1.35)); -#49648 = SURFACE_CURVE('',#49649,(#49654,#49661),.PCURVE_S1.); -#49649 = CIRCLE('',#49650,0.125); -#49650 = AXIS2_PLACEMENT_3D('',#49651,#49652,#49653); -#49651 = CARTESIAN_POINT('',(1.9,1.225,1.225)); -#49652 = DIRECTION('',(0.E+000,1.,0.E+000)); -#49653 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49654 = PCURVE('',#48475,#49655); -#49655 = DEFINITIONAL_REPRESENTATION('',(#49656),#49660); -#49656 = CIRCLE('',#49657,0.125); -#49657 = AXIS2_PLACEMENT_2D('',#49658,#49659); -#49658 = CARTESIAN_POINT('',(1.3,3.575)); -#49659 = DIRECTION('',(0.E+000,-1.)); -#49660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49661 = PCURVE('',#47804,#49662); -#49662 = DEFINITIONAL_REPRESENTATION('',(#49663),#49666); -#49663 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49664,#49665),.UNSPECIFIED., +#51918 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); +#51919 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#51920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51921 = ORIENTED_EDGE('',*,*,#51922,.T.); +#51922 = EDGE_CURVE('',#51900,#51923,#51925,.T.); +#51923 = VERTEX_POINT('',#51924); +#51924 = CARTESIAN_POINT('',(2.725,1.225,1.1)); +#51925 = SURFACE_CURVE('',#51926,(#51930,#51937),.PCURVE_S1.); +#51926 = LINE('',#51927,#51928); +#51927 = CARTESIAN_POINT('',(2.85,1.225,1.1)); +#51928 = VECTOR('',#51929,1.); +#51929 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51930 = PCURVE('',#50867,#51931); +#51931 = DEFINITIONAL_REPRESENTATION('',(#51932),#51936); +#51932 = LINE('',#51933,#51934); +#51933 = CARTESIAN_POINT('',(0.35,3.45)); +#51934 = VECTOR('',#51935,1.); +#51935 = DIRECTION('',(1.,0.E+000)); +#51936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51937 = PCURVE('',#50335,#51938); +#51938 = DEFINITIONAL_REPRESENTATION('',(#51939),#51943); +#51939 = LINE('',#51940,#51941); +#51940 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51941 = VECTOR('',#51942,1.); +#51942 = DIRECTION('',(1.,0.E+000)); +#51943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51944 = ORIENTED_EDGE('',*,*,#51945,.T.); +#51945 = EDGE_CURVE('',#51923,#51946,#51948,.T.); +#51946 = VERTEX_POINT('',#51947); +#51947 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); +#51948 = SURFACE_CURVE('',#51949,(#51953,#51960),.PCURVE_S1.); +#51949 = LINE('',#51950,#51951); +#51950 = CARTESIAN_POINT('',(2.725,1.225,1.1)); +#51951 = VECTOR('',#51952,1.); +#51952 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#51953 = PCURVE('',#50867,#51954); +#51954 = DEFINITIONAL_REPRESENTATION('',(#51955),#51959); +#51955 = LINE('',#51956,#51957); +#51956 = CARTESIAN_POINT('',(0.475,3.45)); +#51957 = VECTOR('',#51958,1.); +#51958 = DIRECTION('',(0.E+000,-1.)); +#51959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51960 = PCURVE('',#50307,#51961); +#51961 = DEFINITIONAL_REPRESENTATION('',(#51962),#51966); +#51962 = LINE('',#51963,#51964); +#51963 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51964 = VECTOR('',#51965,1.); +#51965 = DIRECTION('',(1.,0.E+000)); +#51966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51967 = ORIENTED_EDGE('',*,*,#51968,.T.); +#51968 = EDGE_CURVE('',#51946,#51969,#51971,.T.); +#51969 = VERTEX_POINT('',#51970); +#51970 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); +#51971 = SURFACE_CURVE('',#51972,(#51976,#51983),.PCURVE_S1.); +#51972 = LINE('',#51973,#51974); +#51973 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); +#51974 = VECTOR('',#51975,1.); +#51975 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#51976 = PCURVE('',#50867,#51977); +#51977 = DEFINITIONAL_REPRESENTATION('',(#51978),#51982); +#51978 = LINE('',#51979,#51980); +#51979 = CARTESIAN_POINT('',(0.475,2.23)); +#51980 = VECTOR('',#51981,1.); +#51981 = DIRECTION('',(1.,0.E+000)); +#51982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51983 = PCURVE('',#50279,#51984); +#51984 = DEFINITIONAL_REPRESENTATION('',(#51985),#51989); +#51985 = LINE('',#51986,#51987); +#51986 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#51987 = VECTOR('',#51988,1.); +#51988 = DIRECTION('',(1.,0.E+000)); +#51989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#51990 = ORIENTED_EDGE('',*,*,#51991,.T.); +#51991 = EDGE_CURVE('',#51969,#51992,#51994,.T.); +#51992 = VERTEX_POINT('',#51993); +#51993 = CARTESIAN_POINT('',(2.025,1.225,1.1)); +#51994 = SURFACE_CURVE('',#51995,(#51999,#52006),.PCURVE_S1.); +#51995 = LINE('',#51996,#51997); +#51996 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); +#51997 = VECTOR('',#51998,1.); +#51998 = DIRECTION('',(0.E+000,0.E+000,1.)); +#51999 = PCURVE('',#50867,#52000); +#52000 = DEFINITIONAL_REPRESENTATION('',(#52001),#52005); +#52001 = LINE('',#52002,#52003); +#52002 = CARTESIAN_POINT('',(1.175,2.23)); +#52003 = VECTOR('',#52004,1.); +#52004 = DIRECTION('',(0.E+000,1.)); +#52005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52006 = PCURVE('',#50251,#52007); +#52007 = DEFINITIONAL_REPRESENTATION('',(#52008),#52012); +#52008 = LINE('',#52009,#52010); +#52009 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52010 = VECTOR('',#52011,1.); +#52011 = DIRECTION('',(1.,0.E+000)); +#52012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52013 = ORIENTED_EDGE('',*,*,#52014,.T.); +#52014 = EDGE_CURVE('',#51992,#52015,#52017,.T.); +#52015 = VERTEX_POINT('',#52016); +#52016 = CARTESIAN_POINT('',(1.9,1.225,1.1)); +#52017 = SURFACE_CURVE('',#52018,(#52022,#52029),.PCURVE_S1.); +#52018 = LINE('',#52019,#52020); +#52019 = CARTESIAN_POINT('',(2.025,1.225,1.1)); +#52020 = VECTOR('',#52021,1.); +#52021 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52022 = PCURVE('',#50867,#52023); +#52023 = DEFINITIONAL_REPRESENTATION('',(#52024),#52028); +#52024 = LINE('',#52025,#52026); +#52025 = CARTESIAN_POINT('',(1.175,3.45)); +#52026 = VECTOR('',#52027,1.); +#52027 = DIRECTION('',(1.,0.E+000)); +#52028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52029 = PCURVE('',#50223,#52030); +#52030 = DEFINITIONAL_REPRESENTATION('',(#52031),#52035); +#52031 = LINE('',#52032,#52033); +#52032 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52033 = VECTOR('',#52034,1.); +#52034 = DIRECTION('',(1.,0.E+000)); +#52035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52036 = ORIENTED_EDGE('',*,*,#52037,.T.); +#52037 = EDGE_CURVE('',#52015,#52038,#52040,.T.); +#52038 = VERTEX_POINT('',#52039); +#52039 = CARTESIAN_POINT('',(1.9,1.225,1.35)); +#52040 = SURFACE_CURVE('',#52041,(#52046,#52053),.PCURVE_S1.); +#52041 = CIRCLE('',#52042,0.125); +#52042 = AXIS2_PLACEMENT_3D('',#52043,#52044,#52045); +#52043 = CARTESIAN_POINT('',(1.9,1.225,1.225)); +#52044 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52045 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52046 = PCURVE('',#50867,#52047); +#52047 = DEFINITIONAL_REPRESENTATION('',(#52048),#52052); +#52048 = CIRCLE('',#52049,0.125); +#52049 = AXIS2_PLACEMENT_2D('',#52050,#52051); +#52050 = CARTESIAN_POINT('',(1.3,3.575)); +#52051 = DIRECTION('',(0.E+000,-1.)); +#52052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52053 = PCURVE('',#50196,#52054); +#52054 = DEFINITIONAL_REPRESENTATION('',(#52055),#52058); +#52055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52056,#52057),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#49664 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49665 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#49666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#52056 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52057 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#52058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52059 = ORIENTED_EDGE('',*,*,#52060,.T.); +#52060 = EDGE_CURVE('',#52038,#50981,#52061,.T.); +#52061 = SURFACE_CURVE('',#52062,(#52066,#52073),.PCURVE_S1.); +#52062 = LINE('',#52063,#52064); +#52063 = CARTESIAN_POINT('',(1.9,1.225,1.35)); +#52064 = VECTOR('',#52065,1.); +#52065 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52066 = PCURVE('',#50867,#52067); +#52067 = DEFINITIONAL_REPRESENTATION('',(#52068),#52072); +#52068 = LINE('',#52069,#52070); +#52069 = CARTESIAN_POINT('',(1.3,3.7)); +#52070 = VECTOR('',#52071,1.); +#52071 = DIRECTION('',(-1.,0.E+000)); +#52072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#49667 = ORIENTED_EDGE('',*,*,#49668,.T.); -#49668 = EDGE_CURVE('',#49646,#48589,#49669,.T.); -#49669 = SURFACE_CURVE('',#49670,(#49674,#49681),.PCURVE_S1.); -#49670 = LINE('',#49671,#49672); -#49671 = CARTESIAN_POINT('',(1.9,1.225,1.35)); -#49672 = VECTOR('',#49673,1.); -#49673 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49674 = PCURVE('',#48475,#49675); -#49675 = DEFINITIONAL_REPRESENTATION('',(#49676),#49680); -#49676 = LINE('',#49677,#49678); -#49677 = CARTESIAN_POINT('',(1.3,3.7)); -#49678 = VECTOR('',#49679,1.); -#49679 = DIRECTION('',(-1.,0.E+000)); -#49680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49681 = PCURVE('',#47771,#49682); -#49682 = DEFINITIONAL_REPRESENTATION('',(#49683),#49687); -#49683 = LINE('',#49684,#49685); -#49684 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49685 = VECTOR('',#49686,1.); -#49686 = DIRECTION('',(1.,0.E+000)); -#49687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49688 = ORIENTED_EDGE('',*,*,#48588,.T.); -#49689 = FACE_BOUND('',#49690,.F.); -#49690 = EDGE_LOOP('',(#49691,#49721,#49779,#49807,#49830,#49853,#49876, - #49899,#49922,#49945,#49968,#49991,#50014,#50037,#50060,#50088)); -#49691 = ORIENTED_EDGE('',*,*,#49692,.T.); -#49692 = EDGE_CURVE('',#49693,#49695,#49697,.T.); -#49693 = VERTEX_POINT('',#49694); -#49694 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); -#49695 = VERTEX_POINT('',#49696); -#49696 = CARTESIAN_POINT('',(-2.225,1.225,1.752598183049)); -#49697 = SURFACE_CURVE('',#49698,(#49702,#49709),.PCURVE_S1.); -#49698 = LINE('',#49699,#49700); -#49699 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); -#49700 = VECTOR('',#49701,1.); -#49701 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49702 = PCURVE('',#48475,#49703); -#49703 = DEFINITIONAL_REPRESENTATION('',(#49704),#49708); -#49704 = LINE('',#49705,#49706); -#49705 = CARTESIAN_POINT('',(5.725,4.102598183049)); -#49706 = VECTOR('',#49707,1.); -#49707 = DIRECTION('',(-1.,0.E+000)); -#49708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49709 = PCURVE('',#49710,#49715); -#49710 = PLANE('',#49711); -#49711 = AXIS2_PLACEMENT_3D('',#49712,#49713,#49714); -#49712 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); -#49713 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#49714 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#49715 = DEFINITIONAL_REPRESENTATION('',(#49716),#49720); -#49716 = LINE('',#49717,#49718); -#49717 = CARTESIAN_POINT('',(0.E+000,0.2)); -#49718 = VECTOR('',#49719,1.); -#49719 = DIRECTION('',(0.E+000,1.)); -#49720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49721 = ORIENTED_EDGE('',*,*,#49722,.F.); -#49722 = EDGE_CURVE('',#49723,#49695,#49725,.T.); -#49723 = VERTEX_POINT('',#49724); -#49724 = CARTESIAN_POINT('',(-2.025,1.225,1.521658075373)); -#49725 = SURFACE_CURVE('',#49726,(#49734,#49745),.PCURVE_S1.); -#49726 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49727,#49728,#49729,#49730, - #49731,#49732,#49733),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#52073 = PCURVE('',#50163,#52074); +#52074 = DEFINITIONAL_REPRESENTATION('',(#52075),#52079); +#52075 = LINE('',#52076,#52077); +#52076 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52077 = VECTOR('',#52078,1.); +#52078 = DIRECTION('',(1.,0.E+000)); +#52079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52080 = ORIENTED_EDGE('',*,*,#50980,.T.); +#52081 = FACE_BOUND('',#52082,.F.); +#52082 = EDGE_LOOP('',(#52083,#52113,#52171,#52199,#52222,#52245,#52268, + #52291,#52314,#52337,#52360,#52383,#52406,#52429,#52452,#52480)); +#52083 = ORIENTED_EDGE('',*,*,#52084,.T.); +#52084 = EDGE_CURVE('',#52085,#52087,#52089,.T.); +#52085 = VERTEX_POINT('',#52086); +#52086 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); +#52087 = VERTEX_POINT('',#52088); +#52088 = CARTESIAN_POINT('',(-2.225,1.225,1.752598183049)); +#52089 = SURFACE_CURVE('',#52090,(#52094,#52101),.PCURVE_S1.); +#52090 = LINE('',#52091,#52092); +#52091 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); +#52092 = VECTOR('',#52093,1.); +#52093 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52094 = PCURVE('',#50867,#52095); +#52095 = DEFINITIONAL_REPRESENTATION('',(#52096),#52100); +#52096 = LINE('',#52097,#52098); +#52097 = CARTESIAN_POINT('',(5.725,4.102598183049)); +#52098 = VECTOR('',#52099,1.); +#52099 = DIRECTION('',(-1.,0.E+000)); +#52100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52101 = PCURVE('',#52102,#52107); +#52102 = PLANE('',#52103); +#52103 = AXIS2_PLACEMENT_3D('',#52104,#52105,#52106); +#52104 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); +#52105 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#52106 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#52107 = DEFINITIONAL_REPRESENTATION('',(#52108),#52112); +#52108 = LINE('',#52109,#52110); +#52109 = CARTESIAN_POINT('',(0.E+000,0.2)); +#52110 = VECTOR('',#52111,1.); +#52111 = DIRECTION('',(0.E+000,1.)); +#52112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52113 = ORIENTED_EDGE('',*,*,#52114,.F.); +#52114 = EDGE_CURVE('',#52115,#52087,#52117,.T.); +#52115 = VERTEX_POINT('',#52116); +#52116 = CARTESIAN_POINT('',(-2.025,1.225,1.521658075373)); +#52117 = SURFACE_CURVE('',#52118,(#52126,#52137),.PCURVE_S1.); +#52118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52119,#52120,#52121,#52122, + #52123,#52124,#52125),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#49727 = CARTESIAN_POINT('',(-2.025,1.225,1.521658075373)); -#49728 = CARTESIAN_POINT('',(-2.025,1.225,1.557569751013)); -#49729 = CARTESIAN_POINT('',(-2.038001629204,1.225,1.616391473089)); -#49730 = CARTESIAN_POINT('',(-2.077484147545,1.225,1.684643981667)); -#49731 = CARTESIAN_POINT('',(-2.135890928678,1.225,1.733972227452)); -#49732 = CARTESIAN_POINT('',(-2.18908832436,1.225,1.752598183049)); -#49733 = CARTESIAN_POINT('',(-2.225,1.225,1.752598183049)); -#49734 = PCURVE('',#48475,#49735); -#49735 = DEFINITIONAL_REPRESENTATION('',(#49736),#49744); -#49736 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49737,#49738,#49739,#49740, - #49741,#49742,#49743),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#52119 = CARTESIAN_POINT('',(-2.025,1.225,1.521658075373)); +#52120 = CARTESIAN_POINT('',(-2.025,1.225,1.557569751013)); +#52121 = CARTESIAN_POINT('',(-2.038001629204,1.225,1.616391473089)); +#52122 = CARTESIAN_POINT('',(-2.077484147545,1.225,1.684643981667)); +#52123 = CARTESIAN_POINT('',(-2.135890928678,1.225,1.733972227452)); +#52124 = CARTESIAN_POINT('',(-2.18908832436,1.225,1.752598183049)); +#52125 = CARTESIAN_POINT('',(-2.225,1.225,1.752598183049)); +#52126 = PCURVE('',#50867,#52127); +#52127 = DEFINITIONAL_REPRESENTATION('',(#52128),#52136); +#52128 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52129,#52130,#52131,#52132, + #52133,#52134,#52135),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#49737 = CARTESIAN_POINT('',(5.225,3.871658075373)); -#49738 = CARTESIAN_POINT('',(5.225,3.907569751013)); -#49739 = CARTESIAN_POINT('',(5.238001629204,3.966391473089)); -#49740 = CARTESIAN_POINT('',(5.277484147545,4.034643981667)); -#49741 = CARTESIAN_POINT('',(5.335890928678,4.083972227452)); -#49742 = CARTESIAN_POINT('',(5.38908832436,4.102598183049)); -#49743 = CARTESIAN_POINT('',(5.425,4.102598183049)); -#49744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49745 = PCURVE('',#49746,#49751); -#49746 = CYLINDRICAL_SURFACE('',#49747,0.2); -#49747 = AXIS2_PLACEMENT_3D('',#49748,#49749,#49750); -#49748 = CARTESIAN_POINT('',(-2.225,1.374406430719,1.435398232379)); -#49749 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#49750 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49751 = DEFINITIONAL_REPRESENTATION('',(#49752),#49778); -#49752 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#49753,#49754,#49755,#49756, - #49757,#49758,#49759,#49760,#49761,#49762,#49763,#49764,#49765, - #49766,#49767,#49768,#49769,#49770,#49771,#49772,#49773,#49774, - #49775,#49776,#49777),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#52129 = CARTESIAN_POINT('',(5.225,3.871658075373)); +#52130 = CARTESIAN_POINT('',(5.225,3.907569751013)); +#52131 = CARTESIAN_POINT('',(5.238001629204,3.966391473089)); +#52132 = CARTESIAN_POINT('',(5.277484147545,4.034643981667)); +#52133 = CARTESIAN_POINT('',(5.335890928678,4.083972227452)); +#52134 = CARTESIAN_POINT('',(5.38908832436,4.102598183049)); +#52135 = CARTESIAN_POINT('',(5.425,4.102598183049)); +#52136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52137 = PCURVE('',#52138,#52143); +#52138 = CYLINDRICAL_SURFACE('',#52139,0.2); +#52139 = AXIS2_PLACEMENT_3D('',#52140,#52141,#52142); +#52140 = CARTESIAN_POINT('',(-2.225,1.374406430719,1.435398232379)); +#52141 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#52142 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52143 = DEFINITIONAL_REPRESENTATION('',(#52144),#52170); +#52144 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52145,#52146,#52147,#52148, + #52149,#52150,#52151,#52152,#52153,#52154,#52155,#52156,#52157, + #52158,#52159,#52160,#52161,#52162,#52163,#52164,#52165,#52166, + #52167,#52168,#52169),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -61917,436 +64906,436 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#49753 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); -#49754 = CARTESIAN_POINT('',(2.827076521564E-002,0.175784383774)); -#49755 = CARTESIAN_POINT('',(8.295804594321E-002,0.182098872442)); -#49756 = CARTESIAN_POINT('',(0.160334717441,0.190983094696)); -#49757 = CARTESIAN_POINT('',(0.233989615751,0.199336874302)); -#49758 = CARTESIAN_POINT('',(0.304771298167,0.207217775869)); -#49759 = CARTESIAN_POINT('',(0.37341587751,0.214681519824)); -#49760 = CARTESIAN_POINT('',(0.440551827006,0.221790706819)); -#49761 = CARTESIAN_POINT('',(0.506543398685,0.228575510601)); -#49762 = CARTESIAN_POINT('',(0.571633992935,0.235033677972)); -#49763 = CARTESIAN_POINT('',(0.63610989114,0.241169836099)); -#49764 = CARTESIAN_POINT('',(0.700253440982,0.246986767435)); -#49765 = CARTESIAN_POINT('',(0.764347001395,0.252487752932)); -#49766 = CARTESIAN_POINT('',(0.828660646632,0.257675924253)); -#49767 = CARTESIAN_POINT('',(0.893473353308,0.262543930626)); -#49768 = CARTESIAN_POINT('',(0.959080929044,0.267084175896)); -#49769 = CARTESIAN_POINT('',(1.025778930211,0.271289946776)); -#49770 = CARTESIAN_POINT('',(1.093878332084,0.275151243893)); -#49771 = CARTESIAN_POINT('',(1.163604914097,0.278670329348)); -#49772 = CARTESIAN_POINT('',(1.235488259696,0.281791675568)); -#49773 = CARTESIAN_POINT('',(1.310617785153,0.284401965263)); -#49774 = CARTESIAN_POINT('',(1.390269427501,0.286400142761)); -#49775 = CARTESIAN_POINT('',(1.475938790177,0.287681865769)); -#49776 = CARTESIAN_POINT('',(1.538150472706,0.287989739826)); -#49777 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); -#49778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49779 = ORIENTED_EDGE('',*,*,#49780,.F.); -#49780 = EDGE_CURVE('',#49781,#49723,#49783,.T.); -#49781 = VERTEX_POINT('',#49782); -#49782 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); -#49783 = SURFACE_CURVE('',#49784,(#49788,#49795),.PCURVE_S1.); -#49784 = LINE('',#49785,#49786); -#49785 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); -#49786 = VECTOR('',#49787,1.); -#49787 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49788 = PCURVE('',#48475,#49789); -#49789 = DEFINITIONAL_REPRESENTATION('',(#49790),#49794); -#49790 = LINE('',#49791,#49792); -#49791 = CARTESIAN_POINT('',(5.225,3.756188021535)); -#49792 = VECTOR('',#49793,1.); -#49793 = DIRECTION('',(0.E+000,1.)); -#49794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49795 = PCURVE('',#49796,#49801); -#49796 = PLANE('',#49797); -#49797 = AXIS2_PLACEMENT_3D('',#49798,#49799,#49800); -#49798 = CARTESIAN_POINT('',(-2.025,0.E+000,0.E+000)); -#49799 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49800 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49801 = DEFINITIONAL_REPRESENTATION('',(#49802),#49806); -#49802 = LINE('',#49803,#49804); -#49803 = CARTESIAN_POINT('',(1.406188021535,1.225)); -#49804 = VECTOR('',#49805,1.); -#49805 = DIRECTION('',(1.,0.E+000)); -#49806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49807 = ORIENTED_EDGE('',*,*,#49808,.T.); -#49808 = EDGE_CURVE('',#49781,#49809,#49811,.T.); -#49809 = VERTEX_POINT('',#49810); -#49810 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); -#49811 = SURFACE_CURVE('',#49812,(#49816,#49823),.PCURVE_S1.); -#49812 = LINE('',#49813,#49814); -#49813 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); -#49814 = VECTOR('',#49815,1.); -#49815 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49816 = PCURVE('',#48475,#49817); -#49817 = DEFINITIONAL_REPRESENTATION('',(#49818),#49822); -#49818 = LINE('',#49819,#49820); -#49819 = CARTESIAN_POINT('',(5.225,3.756188021535)); -#49820 = VECTOR('',#49821,1.); -#49821 = DIRECTION('',(0.E+000,-1.)); -#49822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49823 = PCURVE('',#48033,#49824); -#49824 = DEFINITIONAL_REPRESENTATION('',(#49825),#49829); -#49825 = LINE('',#49826,#49827); -#49826 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); -#49827 = VECTOR('',#49828,1.); -#49828 = DIRECTION('',(1.,0.E+000)); -#49829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49830 = ORIENTED_EDGE('',*,*,#49831,.T.); -#49831 = EDGE_CURVE('',#49809,#49832,#49834,.T.); -#49832 = VERTEX_POINT('',#49833); -#49833 = CARTESIAN_POINT('',(-1.9,1.225,1.35)); -#49834 = SURFACE_CURVE('',#49835,(#49839,#49846),.PCURVE_S1.); -#49835 = LINE('',#49836,#49837); -#49836 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); -#49837 = VECTOR('',#49838,1.); -#49838 = DIRECTION('',(1.,0.E+000,0.E+000)); -#49839 = PCURVE('',#48475,#49840); -#49840 = DEFINITIONAL_REPRESENTATION('',(#49841),#49845); -#49841 = LINE('',#49842,#49843); -#49842 = CARTESIAN_POINT('',(5.225,3.7)); -#49843 = VECTOR('',#49844,1.); -#49844 = DIRECTION('',(-1.,0.E+000)); -#49845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49846 = PCURVE('',#48346,#49847); -#49847 = DEFINITIONAL_REPRESENTATION('',(#49848),#49852); -#49848 = LINE('',#49849,#49850); -#49849 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49850 = VECTOR('',#49851,1.); -#49851 = DIRECTION('',(1.,0.E+000)); -#49852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49853 = ORIENTED_EDGE('',*,*,#49854,.T.); -#49854 = EDGE_CURVE('',#49832,#49855,#49857,.T.); -#49855 = VERTEX_POINT('',#49856); -#49856 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); -#49857 = SURFACE_CURVE('',#49858,(#49863,#49870),.PCURVE_S1.); -#49858 = CIRCLE('',#49859,0.125); -#49859 = AXIS2_PLACEMENT_3D('',#49860,#49861,#49862); -#49860 = CARTESIAN_POINT('',(-1.9,1.225,1.225)); -#49861 = DIRECTION('',(0.E+000,1.,0.E+000)); -#49862 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49863 = PCURVE('',#48475,#49864); -#49864 = DEFINITIONAL_REPRESENTATION('',(#49865),#49869); -#49865 = CIRCLE('',#49866,0.125); -#49866 = AXIS2_PLACEMENT_2D('',#49867,#49868); -#49867 = CARTESIAN_POINT('',(5.1,3.575)); -#49868 = DIRECTION('',(0.E+000,1.)); -#49869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49870 = PCURVE('',#48321,#49871); -#49871 = DEFINITIONAL_REPRESENTATION('',(#49872),#49875); -#49872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#49873,#49874),.UNSPECIFIED., +#52145 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); +#52146 = CARTESIAN_POINT('',(2.827076521564E-002,0.175784383774)); +#52147 = CARTESIAN_POINT('',(8.295804594321E-002,0.182098872442)); +#52148 = CARTESIAN_POINT('',(0.160334717441,0.190983094696)); +#52149 = CARTESIAN_POINT('',(0.233989615751,0.199336874302)); +#52150 = CARTESIAN_POINT('',(0.304771298167,0.207217775869)); +#52151 = CARTESIAN_POINT('',(0.37341587751,0.214681519824)); +#52152 = CARTESIAN_POINT('',(0.440551827006,0.221790706819)); +#52153 = CARTESIAN_POINT('',(0.506543398685,0.228575510601)); +#52154 = CARTESIAN_POINT('',(0.571633992935,0.235033677972)); +#52155 = CARTESIAN_POINT('',(0.63610989114,0.241169836099)); +#52156 = CARTESIAN_POINT('',(0.700253440982,0.246986767435)); +#52157 = CARTESIAN_POINT('',(0.764347001395,0.252487752932)); +#52158 = CARTESIAN_POINT('',(0.828660646632,0.257675924253)); +#52159 = CARTESIAN_POINT('',(0.893473353308,0.262543930626)); +#52160 = CARTESIAN_POINT('',(0.959080929044,0.267084175896)); +#52161 = CARTESIAN_POINT('',(1.025778930211,0.271289946776)); +#52162 = CARTESIAN_POINT('',(1.093878332084,0.275151243893)); +#52163 = CARTESIAN_POINT('',(1.163604914097,0.278670329348)); +#52164 = CARTESIAN_POINT('',(1.235488259696,0.281791675568)); +#52165 = CARTESIAN_POINT('',(1.310617785153,0.284401965263)); +#52166 = CARTESIAN_POINT('',(1.390269427501,0.286400142761)); +#52167 = CARTESIAN_POINT('',(1.475938790177,0.287681865769)); +#52168 = CARTESIAN_POINT('',(1.538150472706,0.287989739826)); +#52169 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); +#52170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52171 = ORIENTED_EDGE('',*,*,#52172,.F.); +#52172 = EDGE_CURVE('',#52173,#52115,#52175,.T.); +#52173 = VERTEX_POINT('',#52174); +#52174 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); +#52175 = SURFACE_CURVE('',#52176,(#52180,#52187),.PCURVE_S1.); +#52176 = LINE('',#52177,#52178); +#52177 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); +#52178 = VECTOR('',#52179,1.); +#52179 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52180 = PCURVE('',#50867,#52181); +#52181 = DEFINITIONAL_REPRESENTATION('',(#52182),#52186); +#52182 = LINE('',#52183,#52184); +#52183 = CARTESIAN_POINT('',(5.225,3.756188021535)); +#52184 = VECTOR('',#52185,1.); +#52185 = DIRECTION('',(0.E+000,1.)); +#52186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52187 = PCURVE('',#52188,#52193); +#52188 = PLANE('',#52189); +#52189 = AXIS2_PLACEMENT_3D('',#52190,#52191,#52192); +#52190 = CARTESIAN_POINT('',(-2.025,0.E+000,0.E+000)); +#52191 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52192 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52193 = DEFINITIONAL_REPRESENTATION('',(#52194),#52198); +#52194 = LINE('',#52195,#52196); +#52195 = CARTESIAN_POINT('',(1.406188021535,1.225)); +#52196 = VECTOR('',#52197,1.); +#52197 = DIRECTION('',(1.,0.E+000)); +#52198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52199 = ORIENTED_EDGE('',*,*,#52200,.T.); +#52200 = EDGE_CURVE('',#52173,#52201,#52203,.T.); +#52201 = VERTEX_POINT('',#52202); +#52202 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); +#52203 = SURFACE_CURVE('',#52204,(#52208,#52215),.PCURVE_S1.); +#52204 = LINE('',#52205,#52206); +#52205 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); +#52206 = VECTOR('',#52207,1.); +#52207 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52208 = PCURVE('',#50867,#52209); +#52209 = DEFINITIONAL_REPRESENTATION('',(#52210),#52214); +#52210 = LINE('',#52211,#52212); +#52211 = CARTESIAN_POINT('',(5.225,3.756188021535)); +#52212 = VECTOR('',#52213,1.); +#52213 = DIRECTION('',(0.E+000,-1.)); +#52214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52215 = PCURVE('',#50425,#52216); +#52216 = DEFINITIONAL_REPRESENTATION('',(#52217),#52221); +#52217 = LINE('',#52218,#52219); +#52218 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); +#52219 = VECTOR('',#52220,1.); +#52220 = DIRECTION('',(1.,0.E+000)); +#52221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52222 = ORIENTED_EDGE('',*,*,#52223,.T.); +#52223 = EDGE_CURVE('',#52201,#52224,#52226,.T.); +#52224 = VERTEX_POINT('',#52225); +#52225 = CARTESIAN_POINT('',(-1.9,1.225,1.35)); +#52226 = SURFACE_CURVE('',#52227,(#52231,#52238),.PCURVE_S1.); +#52227 = LINE('',#52228,#52229); +#52228 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); +#52229 = VECTOR('',#52230,1.); +#52230 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52231 = PCURVE('',#50867,#52232); +#52232 = DEFINITIONAL_REPRESENTATION('',(#52233),#52237); +#52233 = LINE('',#52234,#52235); +#52234 = CARTESIAN_POINT('',(5.225,3.7)); +#52235 = VECTOR('',#52236,1.); +#52236 = DIRECTION('',(-1.,0.E+000)); +#52237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52238 = PCURVE('',#50738,#52239); +#52239 = DEFINITIONAL_REPRESENTATION('',(#52240),#52244); +#52240 = LINE('',#52241,#52242); +#52241 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52242 = VECTOR('',#52243,1.); +#52243 = DIRECTION('',(1.,0.E+000)); +#52244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52245 = ORIENTED_EDGE('',*,*,#52246,.T.); +#52246 = EDGE_CURVE('',#52224,#52247,#52249,.T.); +#52247 = VERTEX_POINT('',#52248); +#52248 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); +#52249 = SURFACE_CURVE('',#52250,(#52255,#52262),.PCURVE_S1.); +#52250 = CIRCLE('',#52251,0.125); +#52251 = AXIS2_PLACEMENT_3D('',#52252,#52253,#52254); +#52252 = CARTESIAN_POINT('',(-1.9,1.225,1.225)); +#52253 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52254 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52255 = PCURVE('',#50867,#52256); +#52256 = DEFINITIONAL_REPRESENTATION('',(#52257),#52261); +#52257 = CIRCLE('',#52258,0.125); +#52258 = AXIS2_PLACEMENT_2D('',#52259,#52260); +#52259 = CARTESIAN_POINT('',(5.1,3.575)); +#52260 = DIRECTION('',(0.E+000,1.)); +#52261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52262 = PCURVE('',#50713,#52263); +#52263 = DEFINITIONAL_REPRESENTATION('',(#52264),#52267); +#52264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52265,#52266),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#49873 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); -#49874 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#49875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49876 = ORIENTED_EDGE('',*,*,#49877,.T.); -#49877 = EDGE_CURVE('',#49855,#49878,#49880,.T.); -#49878 = VERTEX_POINT('',#49879); -#49879 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); -#49880 = SURFACE_CURVE('',#49881,(#49885,#49892),.PCURVE_S1.); -#49881 = LINE('',#49882,#49883); -#49882 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); -#49883 = VECTOR('',#49884,1.); -#49884 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49885 = PCURVE('',#48475,#49886); -#49886 = DEFINITIONAL_REPRESENTATION('',(#49887),#49891); -#49887 = LINE('',#49888,#49889); -#49888 = CARTESIAN_POINT('',(5.1,3.45)); -#49889 = VECTOR('',#49890,1.); -#49890 = DIRECTION('',(1.,0.E+000)); -#49891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49892 = PCURVE('',#48288,#49893); -#49893 = DEFINITIONAL_REPRESENTATION('',(#49894),#49898); -#49894 = LINE('',#49895,#49896); -#49895 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49896 = VECTOR('',#49897,1.); -#49897 = DIRECTION('',(1.,0.E+000)); -#49898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49899 = ORIENTED_EDGE('',*,*,#49900,.T.); -#49900 = EDGE_CURVE('',#49878,#49901,#49903,.T.); -#49901 = VERTEX_POINT('',#49902); -#49902 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); -#49903 = SURFACE_CURVE('',#49904,(#49908,#49915),.PCURVE_S1.); -#49904 = LINE('',#49905,#49906); -#49905 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); -#49906 = VECTOR('',#49907,1.); -#49907 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#49908 = PCURVE('',#48475,#49909); -#49909 = DEFINITIONAL_REPRESENTATION('',(#49910),#49914); -#49910 = LINE('',#49911,#49912); -#49911 = CARTESIAN_POINT('',(5.225,3.45)); -#49912 = VECTOR('',#49913,1.); -#49913 = DIRECTION('',(0.E+000,-1.)); -#49914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49915 = PCURVE('',#48260,#49916); -#49916 = DEFINITIONAL_REPRESENTATION('',(#49917),#49921); -#49917 = LINE('',#49918,#49919); -#49918 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49919 = VECTOR('',#49920,1.); -#49920 = DIRECTION('',(1.,0.E+000)); -#49921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49922 = ORIENTED_EDGE('',*,*,#49923,.T.); -#49923 = EDGE_CURVE('',#49901,#49924,#49926,.T.); -#49924 = VERTEX_POINT('',#49925); -#49925 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); -#49926 = SURFACE_CURVE('',#49927,(#49931,#49938),.PCURVE_S1.); -#49927 = LINE('',#49928,#49929); -#49928 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); -#49929 = VECTOR('',#49930,1.); -#49930 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49931 = PCURVE('',#48475,#49932); -#49932 = DEFINITIONAL_REPRESENTATION('',(#49933),#49937); -#49933 = LINE('',#49934,#49935); -#49934 = CARTESIAN_POINT('',(5.225,2.23)); -#49935 = VECTOR('',#49936,1.); -#49936 = DIRECTION('',(1.,0.E+000)); -#49937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49938 = PCURVE('',#48232,#49939); -#49939 = DEFINITIONAL_REPRESENTATION('',(#49940),#49944); -#49940 = LINE('',#49941,#49942); -#49941 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49942 = VECTOR('',#49943,1.); -#49943 = DIRECTION('',(1.,0.E+000)); -#49944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49945 = ORIENTED_EDGE('',*,*,#49946,.T.); -#49946 = EDGE_CURVE('',#49924,#49947,#49949,.T.); -#49947 = VERTEX_POINT('',#49948); -#49948 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); -#49949 = SURFACE_CURVE('',#49950,(#49954,#49961),.PCURVE_S1.); -#49950 = LINE('',#49951,#49952); -#49951 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); -#49952 = VECTOR('',#49953,1.); -#49953 = DIRECTION('',(0.E+000,0.E+000,1.)); -#49954 = PCURVE('',#48475,#49955); -#49955 = DEFINITIONAL_REPRESENTATION('',(#49956),#49960); -#49956 = LINE('',#49957,#49958); -#49957 = CARTESIAN_POINT('',(5.925,2.23)); -#49958 = VECTOR('',#49959,1.); -#49959 = DIRECTION('',(0.E+000,1.)); -#49960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49961 = PCURVE('',#48204,#49962); -#49962 = DEFINITIONAL_REPRESENTATION('',(#49963),#49967); -#49963 = LINE('',#49964,#49965); -#49964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49965 = VECTOR('',#49966,1.); -#49966 = DIRECTION('',(1.,0.E+000)); -#49967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49968 = ORIENTED_EDGE('',*,*,#49969,.T.); -#49969 = EDGE_CURVE('',#49947,#49970,#49972,.T.); -#49970 = VERTEX_POINT('',#49971); -#49971 = CARTESIAN_POINT('',(-2.85,1.225,1.1)); -#49972 = SURFACE_CURVE('',#49973,(#49977,#49984),.PCURVE_S1.); -#49973 = LINE('',#49974,#49975); -#49974 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); -#49975 = VECTOR('',#49976,1.); -#49976 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#49977 = PCURVE('',#48475,#49978); -#49978 = DEFINITIONAL_REPRESENTATION('',(#49979),#49983); -#49979 = LINE('',#49980,#49981); -#49980 = CARTESIAN_POINT('',(5.925,3.45)); -#49981 = VECTOR('',#49982,1.); -#49982 = DIRECTION('',(1.,0.E+000)); -#49983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49984 = PCURVE('',#48176,#49985); -#49985 = DEFINITIONAL_REPRESENTATION('',(#49986),#49990); -#49986 = LINE('',#49987,#49988); -#49987 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#49988 = VECTOR('',#49989,1.); -#49989 = DIRECTION('',(1.,0.E+000)); -#49990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#49991 = ORIENTED_EDGE('',*,*,#49992,.T.); -#49992 = EDGE_CURVE('',#49970,#49993,#49995,.T.); -#49993 = VERTEX_POINT('',#49994); -#49994 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); -#49995 = SURFACE_CURVE('',#49996,(#50001,#50008),.PCURVE_S1.); -#49996 = CIRCLE('',#49997,0.125); -#49997 = AXIS2_PLACEMENT_3D('',#49998,#49999,#50000); -#49998 = CARTESIAN_POINT('',(-2.85,1.225,1.225)); -#49999 = DIRECTION('',(0.E+000,1.,0.E+000)); -#50000 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50001 = PCURVE('',#48475,#50002); -#50002 = DEFINITIONAL_REPRESENTATION('',(#50003),#50007); -#50003 = CIRCLE('',#50004,0.125); -#50004 = AXIS2_PLACEMENT_2D('',#50005,#50006); -#50005 = CARTESIAN_POINT('',(6.05,3.575)); -#50006 = DIRECTION('',(0.E+000,-1.)); -#50007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50008 = PCURVE('',#48149,#50009); -#50009 = DEFINITIONAL_REPRESENTATION('',(#50010),#50013); -#50010 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50011,#50012),.UNSPECIFIED., +#52265 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); +#52266 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52268 = ORIENTED_EDGE('',*,*,#52269,.T.); +#52269 = EDGE_CURVE('',#52247,#52270,#52272,.T.); +#52270 = VERTEX_POINT('',#52271); +#52271 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); +#52272 = SURFACE_CURVE('',#52273,(#52277,#52284),.PCURVE_S1.); +#52273 = LINE('',#52274,#52275); +#52274 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); +#52275 = VECTOR('',#52276,1.); +#52276 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52277 = PCURVE('',#50867,#52278); +#52278 = DEFINITIONAL_REPRESENTATION('',(#52279),#52283); +#52279 = LINE('',#52280,#52281); +#52280 = CARTESIAN_POINT('',(5.1,3.45)); +#52281 = VECTOR('',#52282,1.); +#52282 = DIRECTION('',(1.,0.E+000)); +#52283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52284 = PCURVE('',#50680,#52285); +#52285 = DEFINITIONAL_REPRESENTATION('',(#52286),#52290); +#52286 = LINE('',#52287,#52288); +#52287 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52288 = VECTOR('',#52289,1.); +#52289 = DIRECTION('',(1.,0.E+000)); +#52290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52291 = ORIENTED_EDGE('',*,*,#52292,.T.); +#52292 = EDGE_CURVE('',#52270,#52293,#52295,.T.); +#52293 = VERTEX_POINT('',#52294); +#52294 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); +#52295 = SURFACE_CURVE('',#52296,(#52300,#52307),.PCURVE_S1.); +#52296 = LINE('',#52297,#52298); +#52297 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); +#52298 = VECTOR('',#52299,1.); +#52299 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52300 = PCURVE('',#50867,#52301); +#52301 = DEFINITIONAL_REPRESENTATION('',(#52302),#52306); +#52302 = LINE('',#52303,#52304); +#52303 = CARTESIAN_POINT('',(5.225,3.45)); +#52304 = VECTOR('',#52305,1.); +#52305 = DIRECTION('',(0.E+000,-1.)); +#52306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52307 = PCURVE('',#50652,#52308); +#52308 = DEFINITIONAL_REPRESENTATION('',(#52309),#52313); +#52309 = LINE('',#52310,#52311); +#52310 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52311 = VECTOR('',#52312,1.); +#52312 = DIRECTION('',(1.,0.E+000)); +#52313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52314 = ORIENTED_EDGE('',*,*,#52315,.T.); +#52315 = EDGE_CURVE('',#52293,#52316,#52318,.T.); +#52316 = VERTEX_POINT('',#52317); +#52317 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); +#52318 = SURFACE_CURVE('',#52319,(#52323,#52330),.PCURVE_S1.); +#52319 = LINE('',#52320,#52321); +#52320 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); +#52321 = VECTOR('',#52322,1.); +#52322 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52323 = PCURVE('',#50867,#52324); +#52324 = DEFINITIONAL_REPRESENTATION('',(#52325),#52329); +#52325 = LINE('',#52326,#52327); +#52326 = CARTESIAN_POINT('',(5.225,2.23)); +#52327 = VECTOR('',#52328,1.); +#52328 = DIRECTION('',(1.,0.E+000)); +#52329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52330 = PCURVE('',#50624,#52331); +#52331 = DEFINITIONAL_REPRESENTATION('',(#52332),#52336); +#52332 = LINE('',#52333,#52334); +#52333 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52334 = VECTOR('',#52335,1.); +#52335 = DIRECTION('',(1.,0.E+000)); +#52336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52337 = ORIENTED_EDGE('',*,*,#52338,.T.); +#52338 = EDGE_CURVE('',#52316,#52339,#52341,.T.); +#52339 = VERTEX_POINT('',#52340); +#52340 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); +#52341 = SURFACE_CURVE('',#52342,(#52346,#52353),.PCURVE_S1.); +#52342 = LINE('',#52343,#52344); +#52343 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); +#52344 = VECTOR('',#52345,1.); +#52345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52346 = PCURVE('',#50867,#52347); +#52347 = DEFINITIONAL_REPRESENTATION('',(#52348),#52352); +#52348 = LINE('',#52349,#52350); +#52349 = CARTESIAN_POINT('',(5.925,2.23)); +#52350 = VECTOR('',#52351,1.); +#52351 = DIRECTION('',(0.E+000,1.)); +#52352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52353 = PCURVE('',#50596,#52354); +#52354 = DEFINITIONAL_REPRESENTATION('',(#52355),#52359); +#52355 = LINE('',#52356,#52357); +#52356 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52357 = VECTOR('',#52358,1.); +#52358 = DIRECTION('',(1.,0.E+000)); +#52359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52360 = ORIENTED_EDGE('',*,*,#52361,.T.); +#52361 = EDGE_CURVE('',#52339,#52362,#52364,.T.); +#52362 = VERTEX_POINT('',#52363); +#52363 = CARTESIAN_POINT('',(-2.85,1.225,1.1)); +#52364 = SURFACE_CURVE('',#52365,(#52369,#52376),.PCURVE_S1.); +#52365 = LINE('',#52366,#52367); +#52366 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); +#52367 = VECTOR('',#52368,1.); +#52368 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52369 = PCURVE('',#50867,#52370); +#52370 = DEFINITIONAL_REPRESENTATION('',(#52371),#52375); +#52371 = LINE('',#52372,#52373); +#52372 = CARTESIAN_POINT('',(5.925,3.45)); +#52373 = VECTOR('',#52374,1.); +#52374 = DIRECTION('',(1.,0.E+000)); +#52375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52376 = PCURVE('',#50568,#52377); +#52377 = DEFINITIONAL_REPRESENTATION('',(#52378),#52382); +#52378 = LINE('',#52379,#52380); +#52379 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52380 = VECTOR('',#52381,1.); +#52381 = DIRECTION('',(1.,0.E+000)); +#52382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52383 = ORIENTED_EDGE('',*,*,#52384,.T.); +#52384 = EDGE_CURVE('',#52362,#52385,#52387,.T.); +#52385 = VERTEX_POINT('',#52386); +#52386 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); +#52387 = SURFACE_CURVE('',#52388,(#52393,#52400),.PCURVE_S1.); +#52388 = CIRCLE('',#52389,0.125); +#52389 = AXIS2_PLACEMENT_3D('',#52390,#52391,#52392); +#52390 = CARTESIAN_POINT('',(-2.85,1.225,1.225)); +#52391 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52392 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52393 = PCURVE('',#50867,#52394); +#52394 = DEFINITIONAL_REPRESENTATION('',(#52395),#52399); +#52395 = CIRCLE('',#52396,0.125); +#52396 = AXIS2_PLACEMENT_2D('',#52397,#52398); +#52397 = CARTESIAN_POINT('',(6.05,3.575)); +#52398 = DIRECTION('',(0.E+000,-1.)); +#52399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52400 = PCURVE('',#50541,#52401); +#52401 = DEFINITIONAL_REPRESENTATION('',(#52402),#52405); +#52402 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52403,#52404),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#50011 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50012 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#50013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50014 = ORIENTED_EDGE('',*,*,#50015,.T.); -#50015 = EDGE_CURVE('',#49993,#50016,#50018,.T.); -#50016 = VERTEX_POINT('',#50017); -#50017 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); -#50018 = SURFACE_CURVE('',#50019,(#50023,#50030),.PCURVE_S1.); -#50019 = LINE('',#50020,#50021); -#50020 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); -#50021 = VECTOR('',#50022,1.); -#50022 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50023 = PCURVE('',#48475,#50024); -#50024 = DEFINITIONAL_REPRESENTATION('',(#50025),#50029); -#50025 = LINE('',#50026,#50027); -#50026 = CARTESIAN_POINT('',(6.05,3.7)); -#50027 = VECTOR('',#50028,1.); -#50028 = DIRECTION('',(-1.,0.E+000)); -#50029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50030 = PCURVE('',#48116,#50031); -#50031 = DEFINITIONAL_REPRESENTATION('',(#50032),#50036); -#50032 = LINE('',#50033,#50034); -#50033 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50034 = VECTOR('',#50035,1.); -#50035 = DIRECTION('',(1.,0.E+000)); -#50036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50037 = ORIENTED_EDGE('',*,*,#50038,.T.); -#50038 = EDGE_CURVE('',#50016,#50039,#50041,.T.); -#50039 = VERTEX_POINT('',#50040); -#50040 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); -#50041 = SURFACE_CURVE('',#50042,(#50046,#50053),.PCURVE_S1.); -#50042 = LINE('',#50043,#50044); -#50043 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); -#50044 = VECTOR('',#50045,1.); -#50045 = DIRECTION('',(0.E+000,0.E+000,1.)); -#50046 = PCURVE('',#48475,#50047); -#50047 = DEFINITIONAL_REPRESENTATION('',(#50048),#50052); -#50048 = LINE('',#50049,#50050); -#50049 = CARTESIAN_POINT('',(5.925,3.7)); -#50050 = VECTOR('',#50051,1.); -#50051 = DIRECTION('',(0.E+000,1.)); -#50052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50053 = PCURVE('',#48088,#50054); -#50054 = DEFINITIONAL_REPRESENTATION('',(#50055),#50059); -#50055 = LINE('',#50056,#50057); -#50056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50057 = VECTOR('',#50058,1.); -#50058 = DIRECTION('',(1.,0.E+000)); -#50059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50060 = ORIENTED_EDGE('',*,*,#50061,.T.); -#50061 = EDGE_CURVE('',#50039,#50062,#50064,.T.); -#50062 = VERTEX_POINT('',#50063); -#50063 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); -#50064 = SURFACE_CURVE('',#50065,(#50069,#50076),.PCURVE_S1.); -#50065 = LINE('',#50066,#50067); -#50066 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); -#50067 = VECTOR('',#50068,1.); -#50068 = DIRECTION('',(0.E+000,0.E+000,1.)); -#50069 = PCURVE('',#48475,#50070); -#50070 = DEFINITIONAL_REPRESENTATION('',(#50071),#50075); -#50071 = LINE('',#50072,#50073); -#50072 = CARTESIAN_POINT('',(5.925,3.756188021535)); -#50073 = VECTOR('',#50074,1.); -#50074 = DIRECTION('',(0.E+000,1.)); -#50075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50076 = PCURVE('',#50077,#50082); -#50077 = PLANE('',#50078); -#50078 = AXIS2_PLACEMENT_3D('',#50079,#50080,#50081); -#50079 = CARTESIAN_POINT('',(-2.725,0.E+000,0.E+000)); -#50080 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50081 = DIRECTION('',(0.E+000,0.E+000,1.)); -#50082 = DEFINITIONAL_REPRESENTATION('',(#50083),#50087); -#50083 = LINE('',#50084,#50085); -#50084 = CARTESIAN_POINT('',(1.406188021535,1.225)); -#50085 = VECTOR('',#50086,1.); -#50086 = DIRECTION('',(1.,0.E+000)); -#50087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50088 = ORIENTED_EDGE('',*,*,#50089,.F.); -#50089 = EDGE_CURVE('',#49693,#50062,#50090,.T.); -#50090 = SURFACE_CURVE('',#50091,(#50099,#50110),.PCURVE_S1.); -#50091 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50092,#50093,#50094,#50095, - #50096,#50097,#50098),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#52403 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52404 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#52405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52406 = ORIENTED_EDGE('',*,*,#52407,.T.); +#52407 = EDGE_CURVE('',#52385,#52408,#52410,.T.); +#52408 = VERTEX_POINT('',#52409); +#52409 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); +#52410 = SURFACE_CURVE('',#52411,(#52415,#52422),.PCURVE_S1.); +#52411 = LINE('',#52412,#52413); +#52412 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); +#52413 = VECTOR('',#52414,1.); +#52414 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52415 = PCURVE('',#50867,#52416); +#52416 = DEFINITIONAL_REPRESENTATION('',(#52417),#52421); +#52417 = LINE('',#52418,#52419); +#52418 = CARTESIAN_POINT('',(6.05,3.7)); +#52419 = VECTOR('',#52420,1.); +#52420 = DIRECTION('',(-1.,0.E+000)); +#52421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52422 = PCURVE('',#50508,#52423); +#52423 = DEFINITIONAL_REPRESENTATION('',(#52424),#52428); +#52424 = LINE('',#52425,#52426); +#52425 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52426 = VECTOR('',#52427,1.); +#52427 = DIRECTION('',(1.,0.E+000)); +#52428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52429 = ORIENTED_EDGE('',*,*,#52430,.T.); +#52430 = EDGE_CURVE('',#52408,#52431,#52433,.T.); +#52431 = VERTEX_POINT('',#52432); +#52432 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); +#52433 = SURFACE_CURVE('',#52434,(#52438,#52445),.PCURVE_S1.); +#52434 = LINE('',#52435,#52436); +#52435 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); +#52436 = VECTOR('',#52437,1.); +#52437 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52438 = PCURVE('',#50867,#52439); +#52439 = DEFINITIONAL_REPRESENTATION('',(#52440),#52444); +#52440 = LINE('',#52441,#52442); +#52441 = CARTESIAN_POINT('',(5.925,3.7)); +#52442 = VECTOR('',#52443,1.); +#52443 = DIRECTION('',(0.E+000,1.)); +#52444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52445 = PCURVE('',#50480,#52446); +#52446 = DEFINITIONAL_REPRESENTATION('',(#52447),#52451); +#52447 = LINE('',#52448,#52449); +#52448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52449 = VECTOR('',#52450,1.); +#52450 = DIRECTION('',(1.,0.E+000)); +#52451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52452 = ORIENTED_EDGE('',*,*,#52453,.T.); +#52453 = EDGE_CURVE('',#52431,#52454,#52456,.T.); +#52454 = VERTEX_POINT('',#52455); +#52455 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); +#52456 = SURFACE_CURVE('',#52457,(#52461,#52468),.PCURVE_S1.); +#52457 = LINE('',#52458,#52459); +#52458 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); +#52459 = VECTOR('',#52460,1.); +#52460 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52461 = PCURVE('',#50867,#52462); +#52462 = DEFINITIONAL_REPRESENTATION('',(#52463),#52467); +#52463 = LINE('',#52464,#52465); +#52464 = CARTESIAN_POINT('',(5.925,3.756188021535)); +#52465 = VECTOR('',#52466,1.); +#52466 = DIRECTION('',(0.E+000,1.)); +#52467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52468 = PCURVE('',#52469,#52474); +#52469 = PLANE('',#52470); +#52470 = AXIS2_PLACEMENT_3D('',#52471,#52472,#52473); +#52471 = CARTESIAN_POINT('',(-2.725,0.E+000,0.E+000)); +#52472 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52473 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52474 = DEFINITIONAL_REPRESENTATION('',(#52475),#52479); +#52475 = LINE('',#52476,#52477); +#52476 = CARTESIAN_POINT('',(1.406188021535,1.225)); +#52477 = VECTOR('',#52478,1.); +#52478 = DIRECTION('',(1.,0.E+000)); +#52479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52480 = ORIENTED_EDGE('',*,*,#52481,.F.); +#52481 = EDGE_CURVE('',#52085,#52454,#52482,.T.); +#52482 = SURFACE_CURVE('',#52483,(#52491,#52502),.PCURVE_S1.); +#52483 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52484,#52485,#52486,#52487, + #52488,#52489,#52490),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#50092 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); -#50093 = CARTESIAN_POINT('',(-2.56091167564,1.225,1.752598183049)); -#50094 = CARTESIAN_POINT('',(-2.614109071322,1.225,1.733972227452)); -#50095 = CARTESIAN_POINT('',(-2.672515852456,1.225,1.684643981667)); -#50096 = CARTESIAN_POINT('',(-2.711998370797,1.225,1.616391473089)); -#50097 = CARTESIAN_POINT('',(-2.725,1.225,1.557569751013)); -#50098 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); -#50099 = PCURVE('',#48475,#50100); -#50100 = DEFINITIONAL_REPRESENTATION('',(#50101),#50109); -#50101 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50102,#50103,#50104,#50105, - #50106,#50107,#50108),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, +#52484 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); +#52485 = CARTESIAN_POINT('',(-2.56091167564,1.225,1.752598183049)); +#52486 = CARTESIAN_POINT('',(-2.614109071322,1.225,1.733972227452)); +#52487 = CARTESIAN_POINT('',(-2.672515852456,1.225,1.684643981667)); +#52488 = CARTESIAN_POINT('',(-2.711998370797,1.225,1.616391473089)); +#52489 = CARTESIAN_POINT('',(-2.725,1.225,1.557569751013)); +#52490 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); +#52491 = PCURVE('',#50867,#52492); +#52492 = DEFINITIONAL_REPRESENTATION('',(#52493),#52501); +#52493 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52494,#52495,#52496,#52497, + #52498,#52499,#52500),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,4),(0.E+000, 0.25,0.5,0.75,1.),.QUASI_UNIFORM_KNOTS.); -#50102 = CARTESIAN_POINT('',(5.725,4.102598183049)); -#50103 = CARTESIAN_POINT('',(5.76091167564,4.102598183049)); -#50104 = CARTESIAN_POINT('',(5.814109071322,4.083972227452)); -#50105 = CARTESIAN_POINT('',(5.872515852456,4.034643981667)); -#50106 = CARTESIAN_POINT('',(5.911998370797,3.966391473089)); -#50107 = CARTESIAN_POINT('',(5.925,3.907569751013)); -#50108 = CARTESIAN_POINT('',(5.925,3.871658075373)); -#50109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50110 = PCURVE('',#50111,#50116); -#50111 = CYLINDRICAL_SURFACE('',#50112,0.2); -#50112 = AXIS2_PLACEMENT_3D('',#50113,#50114,#50115); -#50113 = CARTESIAN_POINT('',(-2.525,1.111328977094,1.587286071047)); -#50114 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50115 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50116 = DEFINITIONAL_REPRESENTATION('',(#50117),#50143); -#50117 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50118,#50119,#50120,#50121, - #50122,#50123,#50124,#50125,#50126,#50127,#50128,#50129,#50130, - #50131,#50132,#50133,#50134,#50135,#50136,#50137,#50138,#50139, - #50140,#50141,#50142),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#52494 = CARTESIAN_POINT('',(5.725,4.102598183049)); +#52495 = CARTESIAN_POINT('',(5.76091167564,4.102598183049)); +#52496 = CARTESIAN_POINT('',(5.814109071322,4.083972227452)); +#52497 = CARTESIAN_POINT('',(5.872515852456,4.034643981667)); +#52498 = CARTESIAN_POINT('',(5.911998370797,3.966391473089)); +#52499 = CARTESIAN_POINT('',(5.925,3.907569751013)); +#52500 = CARTESIAN_POINT('',(5.925,3.871658075373)); +#52501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52502 = PCURVE('',#52503,#52508); +#52503 = CYLINDRICAL_SURFACE('',#52504,0.2); +#52504 = AXIS2_PLACEMENT_3D('',#52505,#52506,#52507); +#52505 = CARTESIAN_POINT('',(-2.525,1.111328977094,1.587286071047)); +#52506 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#52507 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52508 = DEFINITIONAL_REPRESENTATION('',(#52509),#52535); +#52509 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52510,#52511,#52512,#52513, + #52514,#52515,#52516,#52517,#52518,#52519,#52520,#52521,#52522, + #52523,#52524,#52525,#52526,#52527,#52528,#52529,#52530,#52531, + #52532,#52533,#52534),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -62354,257 +65343,257 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#50118 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); -#50119 = CARTESIAN_POINT('',(1.538150472706,1.578593750971E-002)); -#50120 = CARTESIAN_POINT('',(1.475938790177,1.609381156706E-002)); -#50121 = CARTESIAN_POINT('',(1.390269427501,1.73755345754E-002)); -#50122 = CARTESIAN_POINT('',(1.310617785153,1.937371207315E-002)); -#50123 = CARTESIAN_POINT('',(1.235488259696,2.198400176841E-002)); -#50124 = CARTESIAN_POINT('',(1.163604914096,2.510534798852E-002)); -#50125 = CARTESIAN_POINT('',(1.093878332084,2.862443344278E-002)); -#50126 = CARTESIAN_POINT('',(1.02577893021,3.248573056004E-002)); -#50127 = CARTESIAN_POINT('',(0.959080929043,3.669150144007E-002)); -#50128 = CARTESIAN_POINT('',(0.893473353307,4.123174671037E-002)); -#50129 = CARTESIAN_POINT('',(0.82866064663,4.60997530833E-002)); -#50130 = CARTESIAN_POINT('',(0.764347001392,5.128792440398E-002)); -#50131 = CARTESIAN_POINT('',(0.70025344098,5.678890990165E-002)); -#50132 = CARTESIAN_POINT('',(0.636109891137,6.260584123723E-002)); -#50133 = CARTESIAN_POINT('',(0.571633992933,6.874199936464E-002)); -#50134 = CARTESIAN_POINT('',(0.506543398684,7.520016673501E-002)); -#50135 = CARTESIAN_POINT('',(0.440551827005,8.198497051765E-002)); -#50136 = CARTESIAN_POINT('',(0.37341587751,8.909415751192E-002)); -#50137 = CARTESIAN_POINT('',(0.304771298167,9.655790146718E-002)); -#50138 = CARTESIAN_POINT('',(0.233989615752,0.104438803034)); -#50139 = CARTESIAN_POINT('',(0.160334717441,0.11279258264)); -#50140 = CARTESIAN_POINT('',(8.295804594422E-002,0.121676804894)); -#50141 = CARTESIAN_POINT('',(2.827076521617E-002,0.127991293562)); -#50142 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); -#50143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50144 = FACE_BOUND('',#50145,.F.); -#50145 = EDGE_LOOP('',(#50146,#50176,#50203,#50231,#50259,#50287)); -#50146 = ORIENTED_EDGE('',*,*,#50147,.T.); -#50147 = EDGE_CURVE('',#50148,#50150,#50152,.T.); -#50148 = VERTEX_POINT('',#50149); -#50149 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); -#50150 = VERTEX_POINT('',#50151); -#50151 = CARTESIAN_POINT('',(-0.41,1.225,-1.2)); -#50152 = SURFACE_CURVE('',#50153,(#50157,#50164),.PCURVE_S1.); -#50153 = LINE('',#50154,#50155); -#50154 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); -#50155 = VECTOR('',#50156,1.); -#50156 = DIRECTION('',(0.E+000,0.E+000,1.)); -#50157 = PCURVE('',#48475,#50158); -#50158 = DEFINITIONAL_REPRESENTATION('',(#50159),#50163); -#50159 = LINE('',#50160,#50161); -#50160 = CARTESIAN_POINT('',(3.61,0.85)); -#50161 = VECTOR('',#50162,1.); -#50162 = DIRECTION('',(0.E+000,1.)); -#50163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50164 = PCURVE('',#50165,#50170); -#50165 = PLANE('',#50166); -#50166 = AXIS2_PLACEMENT_3D('',#50167,#50168,#50169); -#50167 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); -#50168 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50169 = DIRECTION('',(0.E+000,0.E+000,1.)); -#50170 = DEFINITIONAL_REPRESENTATION('',(#50171),#50175); -#50171 = LINE('',#50172,#50173); -#50172 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50173 = VECTOR('',#50174,1.); -#50174 = DIRECTION('',(1.,0.E+000)); -#50175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50176 = ORIENTED_EDGE('',*,*,#50177,.T.); -#50177 = EDGE_CURVE('',#50150,#50178,#50180,.T.); -#50178 = VERTEX_POINT('',#50179); -#50179 = CARTESIAN_POINT('',(0.41,1.225,-1.2)); -#50180 = SURFACE_CURVE('',#50181,(#50185,#50192),.PCURVE_S1.); -#50181 = LINE('',#50182,#50183); -#50182 = CARTESIAN_POINT('',(-0.41,1.225,-1.2)); -#50183 = VECTOR('',#50184,1.); -#50184 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50185 = PCURVE('',#48475,#50186); -#50186 = DEFINITIONAL_REPRESENTATION('',(#50187),#50191); -#50187 = LINE('',#50188,#50189); -#50188 = CARTESIAN_POINT('',(3.61,1.15)); -#50189 = VECTOR('',#50190,1.); -#50190 = DIRECTION('',(-1.,0.E+000)); -#50191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50192 = PCURVE('',#50193,#50198); -#50193 = CYLINDRICAL_SURFACE('',#50194,0.2); -#50194 = AXIS2_PLACEMENT_3D('',#50195,#50196,#50197); -#50195 = CARTESIAN_POINT('',(-0.41,1.025,-1.2)); -#50196 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50197 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50198 = DEFINITIONAL_REPRESENTATION('',(#50199),#50202); -#50199 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50200,#50201),.UNSPECIFIED., +#52510 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); +#52511 = CARTESIAN_POINT('',(1.538150472706,1.578593750971E-002)); +#52512 = CARTESIAN_POINT('',(1.475938790177,1.609381156706E-002)); +#52513 = CARTESIAN_POINT('',(1.390269427501,1.73755345754E-002)); +#52514 = CARTESIAN_POINT('',(1.310617785153,1.937371207315E-002)); +#52515 = CARTESIAN_POINT('',(1.235488259696,2.198400176841E-002)); +#52516 = CARTESIAN_POINT('',(1.163604914096,2.510534798852E-002)); +#52517 = CARTESIAN_POINT('',(1.093878332084,2.862443344278E-002)); +#52518 = CARTESIAN_POINT('',(1.02577893021,3.248573056004E-002)); +#52519 = CARTESIAN_POINT('',(0.959080929043,3.669150144007E-002)); +#52520 = CARTESIAN_POINT('',(0.893473353307,4.123174671037E-002)); +#52521 = CARTESIAN_POINT('',(0.82866064663,4.60997530833E-002)); +#52522 = CARTESIAN_POINT('',(0.764347001392,5.128792440398E-002)); +#52523 = CARTESIAN_POINT('',(0.70025344098,5.678890990165E-002)); +#52524 = CARTESIAN_POINT('',(0.636109891137,6.260584123723E-002)); +#52525 = CARTESIAN_POINT('',(0.571633992933,6.874199936464E-002)); +#52526 = CARTESIAN_POINT('',(0.506543398684,7.520016673501E-002)); +#52527 = CARTESIAN_POINT('',(0.440551827005,8.198497051765E-002)); +#52528 = CARTESIAN_POINT('',(0.37341587751,8.909415751192E-002)); +#52529 = CARTESIAN_POINT('',(0.304771298167,9.655790146718E-002)); +#52530 = CARTESIAN_POINT('',(0.233989615752,0.104438803034)); +#52531 = CARTESIAN_POINT('',(0.160334717441,0.11279258264)); +#52532 = CARTESIAN_POINT('',(8.295804594422E-002,0.121676804894)); +#52533 = CARTESIAN_POINT('',(2.827076521617E-002,0.127991293562)); +#52534 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); +#52535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52536 = FACE_BOUND('',#52537,.F.); +#52537 = EDGE_LOOP('',(#52538,#52568,#52595,#52623,#52651,#52679)); +#52538 = ORIENTED_EDGE('',*,*,#52539,.T.); +#52539 = EDGE_CURVE('',#52540,#52542,#52544,.T.); +#52540 = VERTEX_POINT('',#52541); +#52541 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); +#52542 = VERTEX_POINT('',#52543); +#52543 = CARTESIAN_POINT('',(-0.41,1.225,-1.2)); +#52544 = SURFACE_CURVE('',#52545,(#52549,#52556),.PCURVE_S1.); +#52545 = LINE('',#52546,#52547); +#52546 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); +#52547 = VECTOR('',#52548,1.); +#52548 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52549 = PCURVE('',#50867,#52550); +#52550 = DEFINITIONAL_REPRESENTATION('',(#52551),#52555); +#52551 = LINE('',#52552,#52553); +#52552 = CARTESIAN_POINT('',(3.61,0.85)); +#52553 = VECTOR('',#52554,1.); +#52554 = DIRECTION('',(0.E+000,1.)); +#52555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52556 = PCURVE('',#52557,#52562); +#52557 = PLANE('',#52558); +#52558 = AXIS2_PLACEMENT_3D('',#52559,#52560,#52561); +#52559 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); +#52560 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52561 = DIRECTION('',(0.E+000,0.E+000,1.)); +#52562 = DEFINITIONAL_REPRESENTATION('',(#52563),#52567); +#52563 = LINE('',#52564,#52565); +#52564 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52565 = VECTOR('',#52566,1.); +#52566 = DIRECTION('',(1.,0.E+000)); +#52567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52568 = ORIENTED_EDGE('',*,*,#52569,.T.); +#52569 = EDGE_CURVE('',#52542,#52570,#52572,.T.); +#52570 = VERTEX_POINT('',#52571); +#52571 = CARTESIAN_POINT('',(0.41,1.225,-1.2)); +#52572 = SURFACE_CURVE('',#52573,(#52577,#52584),.PCURVE_S1.); +#52573 = LINE('',#52574,#52575); +#52574 = CARTESIAN_POINT('',(-0.41,1.225,-1.2)); +#52575 = VECTOR('',#52576,1.); +#52576 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52577 = PCURVE('',#50867,#52578); +#52578 = DEFINITIONAL_REPRESENTATION('',(#52579),#52583); +#52579 = LINE('',#52580,#52581); +#52580 = CARTESIAN_POINT('',(3.61,1.15)); +#52581 = VECTOR('',#52582,1.); +#52582 = DIRECTION('',(-1.,0.E+000)); +#52583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52584 = PCURVE('',#52585,#52590); +#52585 = CYLINDRICAL_SURFACE('',#52586,0.2); +#52586 = AXIS2_PLACEMENT_3D('',#52587,#52588,#52589); +#52587 = CARTESIAN_POINT('',(-0.41,1.025,-1.2)); +#52588 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52589 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52590 = DEFINITIONAL_REPRESENTATION('',(#52591),#52594); +#52591 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52592,#52593),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); -#50200 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50201 = CARTESIAN_POINT('',(1.570796326795,0.82)); -#50202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50203 = ORIENTED_EDGE('',*,*,#50204,.T.); -#50204 = EDGE_CURVE('',#50178,#50205,#50207,.T.); -#50205 = VERTEX_POINT('',#50206); -#50206 = CARTESIAN_POINT('',(0.41,1.225,-1.5)); -#50207 = SURFACE_CURVE('',#50208,(#50212,#50219),.PCURVE_S1.); -#50208 = LINE('',#50209,#50210); -#50209 = CARTESIAN_POINT('',(0.41,1.225,-1.2)); -#50210 = VECTOR('',#50211,1.); -#50211 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50212 = PCURVE('',#48475,#50213); -#50213 = DEFINITIONAL_REPRESENTATION('',(#50214),#50218); -#50214 = LINE('',#50215,#50216); -#50215 = CARTESIAN_POINT('',(2.79,1.15)); -#50216 = VECTOR('',#50217,1.); -#50217 = DIRECTION('',(0.E+000,-1.)); -#50218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50219 = PCURVE('',#50220,#50225); -#50220 = PLANE('',#50221); -#50221 = AXIS2_PLACEMENT_3D('',#50222,#50223,#50224); -#50222 = CARTESIAN_POINT('',(0.41,1.225,-1.1)); -#50223 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50224 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50225 = DEFINITIONAL_REPRESENTATION('',(#50226),#50230); -#50226 = LINE('',#50227,#50228); -#50227 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#50228 = VECTOR('',#50229,1.); -#50229 = DIRECTION('',(1.,0.E+000)); -#50230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50231 = ORIENTED_EDGE('',*,*,#50232,.T.); -#50232 = EDGE_CURVE('',#50205,#50233,#50235,.T.); -#50233 = VERTEX_POINT('',#50234); -#50234 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); -#50235 = SURFACE_CURVE('',#50236,(#50241,#50248),.PCURVE_S1.); -#50236 = CIRCLE('',#50237,0.25); -#50237 = AXIS2_PLACEMENT_3D('',#50238,#50239,#50240); -#50238 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); -#50239 = DIRECTION('',(0.E+000,1.,0.E+000)); -#50240 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50241 = PCURVE('',#48475,#50242); -#50242 = DEFINITIONAL_REPRESENTATION('',(#50243),#50247); -#50243 = CIRCLE('',#50244,0.25); -#50244 = AXIS2_PLACEMENT_2D('',#50245,#50246); -#50245 = CARTESIAN_POINT('',(3.04,0.85)); -#50246 = DIRECTION('',(-1.,0.E+000)); -#50247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50248 = PCURVE('',#50249,#50254); -#50249 = CYLINDRICAL_SURFACE('',#50250,0.25); -#50250 = AXIS2_PLACEMENT_3D('',#50251,#50252,#50253); -#50251 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); -#50252 = DIRECTION('',(0.E+000,1.,0.E+000)); -#50253 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50254 = DEFINITIONAL_REPRESENTATION('',(#50255),#50258); -#50255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50256,#50257),.UNSPECIFIED., +#52592 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52593 = CARTESIAN_POINT('',(1.570796326795,0.82)); +#52594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52595 = ORIENTED_EDGE('',*,*,#52596,.T.); +#52596 = EDGE_CURVE('',#52570,#52597,#52599,.T.); +#52597 = VERTEX_POINT('',#52598); +#52598 = CARTESIAN_POINT('',(0.41,1.225,-1.5)); +#52599 = SURFACE_CURVE('',#52600,(#52604,#52611),.PCURVE_S1.); +#52600 = LINE('',#52601,#52602); +#52601 = CARTESIAN_POINT('',(0.41,1.225,-1.2)); +#52602 = VECTOR('',#52603,1.); +#52603 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52604 = PCURVE('',#50867,#52605); +#52605 = DEFINITIONAL_REPRESENTATION('',(#52606),#52610); +#52606 = LINE('',#52607,#52608); +#52607 = CARTESIAN_POINT('',(2.79,1.15)); +#52608 = VECTOR('',#52609,1.); +#52609 = DIRECTION('',(0.E+000,-1.)); +#52610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52611 = PCURVE('',#52612,#52617); +#52612 = PLANE('',#52613); +#52613 = AXIS2_PLACEMENT_3D('',#52614,#52615,#52616); +#52614 = CARTESIAN_POINT('',(0.41,1.225,-1.1)); +#52615 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52616 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52617 = DEFINITIONAL_REPRESENTATION('',(#52618),#52622); +#52618 = LINE('',#52619,#52620); +#52619 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#52620 = VECTOR('',#52621,1.); +#52621 = DIRECTION('',(1.,0.E+000)); +#52622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52623 = ORIENTED_EDGE('',*,*,#52624,.T.); +#52624 = EDGE_CURVE('',#52597,#52625,#52627,.T.); +#52625 = VERTEX_POINT('',#52626); +#52626 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); +#52627 = SURFACE_CURVE('',#52628,(#52633,#52640),.PCURVE_S1.); +#52628 = CIRCLE('',#52629,0.25); +#52629 = AXIS2_PLACEMENT_3D('',#52630,#52631,#52632); +#52630 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); +#52631 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52632 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52633 = PCURVE('',#50867,#52634); +#52634 = DEFINITIONAL_REPRESENTATION('',(#52635),#52639); +#52635 = CIRCLE('',#52636,0.25); +#52636 = AXIS2_PLACEMENT_2D('',#52637,#52638); +#52637 = CARTESIAN_POINT('',(3.04,0.85)); +#52638 = DIRECTION('',(-1.,0.E+000)); +#52639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52640 = PCURVE('',#52641,#52646); +#52641 = CYLINDRICAL_SURFACE('',#52642,0.25); +#52642 = AXIS2_PLACEMENT_3D('',#52643,#52644,#52645); +#52643 = CARTESIAN_POINT('',(0.16,1.225,-1.5)); +#52644 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52645 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52646 = DEFINITIONAL_REPRESENTATION('',(#52647),#52650); +#52647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52648,#52649),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#50256 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50257 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50259 = ORIENTED_EDGE('',*,*,#50260,.T.); -#50260 = EDGE_CURVE('',#50233,#50261,#50263,.T.); -#50261 = VERTEX_POINT('',#50262); -#50262 = CARTESIAN_POINT('',(-0.16,1.225,-1.75)); -#50263 = SURFACE_CURVE('',#50264,(#50268,#50275),.PCURVE_S1.); -#50264 = LINE('',#50265,#50266); -#50265 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); -#50266 = VECTOR('',#50267,1.); -#50267 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50268 = PCURVE('',#48475,#50269); -#50269 = DEFINITIONAL_REPRESENTATION('',(#50270),#50274); -#50270 = LINE('',#50271,#50272); -#50271 = CARTESIAN_POINT('',(3.04,0.6)); -#50272 = VECTOR('',#50273,1.); -#50273 = DIRECTION('',(1.,0.E+000)); -#50274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50275 = PCURVE('',#50276,#50281); -#50276 = PLANE('',#50277); -#50277 = AXIS2_PLACEMENT_3D('',#50278,#50279,#50280); -#50278 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); -#50279 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50280 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50281 = DEFINITIONAL_REPRESENTATION('',(#50282),#50286); -#50282 = LINE('',#50283,#50284); -#50283 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50284 = VECTOR('',#50285,1.); -#50285 = DIRECTION('',(1.,0.E+000)); -#50286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50287 = ORIENTED_EDGE('',*,*,#50288,.T.); -#50288 = EDGE_CURVE('',#50261,#50148,#50289,.T.); -#50289 = SURFACE_CURVE('',#50290,(#50295,#50302),.PCURVE_S1.); -#50290 = CIRCLE('',#50291,0.25); -#50291 = AXIS2_PLACEMENT_3D('',#50292,#50293,#50294); -#50292 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); -#50293 = DIRECTION('',(0.E+000,1.,0.E+000)); -#50294 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#50295 = PCURVE('',#48475,#50296); -#50296 = DEFINITIONAL_REPRESENTATION('',(#50297),#50301); -#50297 = CIRCLE('',#50298,0.25); -#50298 = AXIS2_PLACEMENT_2D('',#50299,#50300); -#50299 = CARTESIAN_POINT('',(3.36,0.85)); -#50300 = DIRECTION('',(0.E+000,-1.)); -#50301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50302 = PCURVE('',#50303,#50308); -#50303 = CYLINDRICAL_SURFACE('',#50304,0.25); -#50304 = AXIS2_PLACEMENT_3D('',#50305,#50306,#50307); -#50305 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); -#50306 = DIRECTION('',(0.E+000,1.,0.E+000)); -#50307 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50308 = DEFINITIONAL_REPRESENTATION('',(#50309),#50312); -#50309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50310,#50311),.UNSPECIFIED., +#52648 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52649 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52651 = ORIENTED_EDGE('',*,*,#52652,.T.); +#52652 = EDGE_CURVE('',#52625,#52653,#52655,.T.); +#52653 = VERTEX_POINT('',#52654); +#52654 = CARTESIAN_POINT('',(-0.16,1.225,-1.75)); +#52655 = SURFACE_CURVE('',#52656,(#52660,#52667),.PCURVE_S1.); +#52656 = LINE('',#52657,#52658); +#52657 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); +#52658 = VECTOR('',#52659,1.); +#52659 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52660 = PCURVE('',#50867,#52661); +#52661 = DEFINITIONAL_REPRESENTATION('',(#52662),#52666); +#52662 = LINE('',#52663,#52664); +#52663 = CARTESIAN_POINT('',(3.04,0.6)); +#52664 = VECTOR('',#52665,1.); +#52665 = DIRECTION('',(1.,0.E+000)); +#52666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52667 = PCURVE('',#52668,#52673); +#52668 = PLANE('',#52669); +#52669 = AXIS2_PLACEMENT_3D('',#52670,#52671,#52672); +#52670 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); +#52671 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52672 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52673 = DEFINITIONAL_REPRESENTATION('',(#52674),#52678); +#52674 = LINE('',#52675,#52676); +#52675 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52676 = VECTOR('',#52677,1.); +#52677 = DIRECTION('',(1.,0.E+000)); +#52678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52679 = ORIENTED_EDGE('',*,*,#52680,.T.); +#52680 = EDGE_CURVE('',#52653,#52540,#52681,.T.); +#52681 = SURFACE_CURVE('',#52682,(#52687,#52694),.PCURVE_S1.); +#52682 = CIRCLE('',#52683,0.25); +#52683 = AXIS2_PLACEMENT_3D('',#52684,#52685,#52686); +#52684 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); +#52685 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52686 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#52687 = PCURVE('',#50867,#52688); +#52688 = DEFINITIONAL_REPRESENTATION('',(#52689),#52693); +#52689 = CIRCLE('',#52690,0.25); +#52690 = AXIS2_PLACEMENT_2D('',#52691,#52692); +#52691 = CARTESIAN_POINT('',(3.36,0.85)); +#52692 = DIRECTION('',(0.E+000,-1.)); +#52693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52694 = PCURVE('',#52695,#52700); +#52695 = CYLINDRICAL_SURFACE('',#52696,0.25); +#52696 = AXIS2_PLACEMENT_3D('',#52697,#52698,#52699); +#52697 = CARTESIAN_POINT('',(-0.16,1.225,-1.5)); +#52698 = DIRECTION('',(0.E+000,1.,0.E+000)); +#52699 = DIRECTION('',(1.,0.E+000,0.E+000)); +#52700 = DEFINITIONAL_REPRESENTATION('',(#52701),#52704); +#52701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52702,#52703),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#50310 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50311 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#50312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50313 = ADVANCED_FACE('',(#50314),#48709,.T.); -#50314 = FACE_BOUND('',#50315,.F.); -#50315 = EDGE_LOOP('',(#50316,#50361,#50362,#50363)); -#50316 = ORIENTED_EDGE('',*,*,#50317,.F.); -#50317 = EDGE_CURVE('',#49407,#50318,#50320,.T.); -#50318 = VERTEX_POINT('',#50319); -#50319 = CARTESIAN_POINT('',(2.025,1.355,1.446602540378)); -#50320 = SURFACE_CURVE('',#50321,(#50325,#50332),.PCURVE_S1.); -#50321 = LINE('',#50322,#50323); -#50322 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); -#50323 = VECTOR('',#50324,1.); -#50324 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50325 = PCURVE('',#48709,#50326); -#50326 = DEFINITIONAL_REPRESENTATION('',(#50327),#50331); -#50327 = LINE('',#50328,#50329); -#50328 = CARTESIAN_POINT('',(1.521658075373,1.225)); -#50329 = VECTOR('',#50330,1.); -#50330 = DIRECTION('',(-0.5,0.866025403784)); -#50331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50332 = PCURVE('',#48990,#50333); -#50333 = DEFINITIONAL_REPRESENTATION('',(#50334),#50360); -#50334 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50335,#50336,#50337,#50338, - #50339,#50340,#50341,#50342,#50343,#50344,#50345,#50346,#50347, - #50348,#50349,#50350,#50351,#50352,#50353,#50354,#50355,#50356, - #50357,#50358,#50359),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#52702 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52703 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#52704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52705 = ADVANCED_FACE('',(#52706),#51101,.T.); +#52706 = FACE_BOUND('',#52707,.F.); +#52707 = EDGE_LOOP('',(#52708,#52753,#52754,#52755)); +#52708 = ORIENTED_EDGE('',*,*,#52709,.F.); +#52709 = EDGE_CURVE('',#51799,#52710,#52712,.T.); +#52710 = VERTEX_POINT('',#52711); +#52711 = CARTESIAN_POINT('',(2.025,1.355,1.446602540378)); +#52712 = SURFACE_CURVE('',#52713,(#52717,#52724),.PCURVE_S1.); +#52713 = LINE('',#52714,#52715); +#52714 = CARTESIAN_POINT('',(2.025,1.225,1.521658075373)); +#52715 = VECTOR('',#52716,1.); +#52716 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#52717 = PCURVE('',#51101,#52718); +#52718 = DEFINITIONAL_REPRESENTATION('',(#52719),#52723); +#52719 = LINE('',#52720,#52721); +#52720 = CARTESIAN_POINT('',(1.521658075373,1.225)); +#52721 = VECTOR('',#52722,1.); +#52722 = DIRECTION('',(-0.5,0.866025403784)); +#52723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52724 = PCURVE('',#51382,#52725); +#52725 = DEFINITIONAL_REPRESENTATION('',(#52726),#52752); +#52726 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52727,#52728,#52729,#52730, + #52731,#52732,#52733,#52734,#52735,#52736,#52737,#52738,#52739, + #52740,#52741,#52742,#52743,#52744,#52745,#52746,#52747,#52748, + #52749,#52750,#52751),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.823230454067E-003, 1.364646090813E-002,2.04696913622E-002,2.729292181627E-002, 3.411615227034E-002,4.09393827244E-002,4.776261317847E-002, @@ -62613,78 +65602,78 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 9.552522635694E-002,0.102348456811,0.109171687265,0.115994917719, 0.122818148173,0.129641378627,0.136464609081,0.143287839535, 0.150111069989),.QUASI_UNIFORM_KNOTS.); -#50335 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); -#50336 = CARTESIAN_POINT('',(-3.277378368693E-013,0.133530401499)); -#50337 = CARTESIAN_POINT('',(-6.332712132462E-013,0.138079221802)); -#50338 = CARTESIAN_POINT('',(-5.107025913276E-013,0.144902452256)); -#50339 = CARTESIAN_POINT('',(-5.462297281156E-013,0.15172568271)); -#50340 = CARTESIAN_POINT('',(-5.337952302398E-013,0.158548913164)); -#50341 = CARTESIAN_POINT('',(-5.39124300758E-013,0.165372143618)); -#50342 = CARTESIAN_POINT('',(-5.373479439186E-013,0.172195374072)); -#50343 = CARTESIAN_POINT('',(-5.355715870792E-013,0.179018604526)); -#50344 = CARTESIAN_POINT('',(-5.373479439186E-013,0.18584183498)); -#50345 = CARTESIAN_POINT('',(-5.355715870792E-013,0.192665065434)); -#50346 = CARTESIAN_POINT('',(-5.355715870792E-013,0.199488295888)); -#50347 = CARTESIAN_POINT('',(-5.373479439186E-013,0.206311526342)); -#50348 = CARTESIAN_POINT('',(-5.373479439186E-013,0.213134756797)); -#50349 = CARTESIAN_POINT('',(-5.355715870792E-013,0.219957987251)); -#50350 = CARTESIAN_POINT('',(-5.364597654989E-013,0.226781217705)); -#50351 = CARTESIAN_POINT('',(-5.373479439186E-013,0.233604448159)); -#50352 = CARTESIAN_POINT('',(-5.355715870792E-013,0.240427678613)); -#50353 = CARTESIAN_POINT('',(-5.373479439186E-013,0.247250909067)); -#50354 = CARTESIAN_POINT('',(-5.346834086595E-013,0.254074139521)); -#50355 = CARTESIAN_POINT('',(-5.426770144368E-013,0.260897369975)); -#50356 = CARTESIAN_POINT('',(-5.12478948167E-013,0.267720600429)); -#50357 = CARTESIAN_POINT('',(-6.332712132462E-013,0.274543830883)); -#50358 = CARTESIAN_POINT('',(-3.277378368693E-013,0.279092651186)); -#50359 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); -#50360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50361 = ORIENTED_EDGE('',*,*,#49406,.F.); -#50362 = ORIENTED_EDGE('',*,*,#48695,.F.); -#50363 = ORIENTED_EDGE('',*,*,#50364,.F.); -#50364 = EDGE_CURVE('',#50318,#48668,#50365,.T.); -#50365 = SURFACE_CURVE('',#50366,(#50370,#50377),.PCURVE_S1.); -#50366 = LINE('',#50367,#50368); -#50367 = CARTESIAN_POINT('',(2.025,1.355,1.446602540378)); -#50368 = VECTOR('',#50369,1.); -#50369 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#50370 = PCURVE('',#48709,#50371); -#50371 = DEFINITIONAL_REPRESENTATION('',(#50372),#50376); -#50372 = LINE('',#50373,#50374); -#50373 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#50374 = VECTOR('',#50375,1.); -#50375 = DIRECTION('',(-0.866025403784,-0.5)); -#50376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50377 = PCURVE('',#48683,#50378); -#50378 = DEFINITIONAL_REPRESENTATION('',(#50379),#50383); -#50379 = LINE('',#50380,#50381); -#50380 = CARTESIAN_POINT('',(0.2,0.7)); -#50381 = VECTOR('',#50382,1.); -#50382 = DIRECTION('',(1.,0.E+000)); -#50383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50384 = ADVANCED_FACE('',(#50385),#48990,.T.); -#50385 = FACE_BOUND('',#50386,.T.); -#50386 = EDGE_LOOP('',(#50387,#50431,#50432,#50433)); -#50387 = ORIENTED_EDGE('',*,*,#50388,.F.); -#50388 = EDGE_CURVE('',#50318,#48975,#50389,.T.); -#50389 = SURFACE_CURVE('',#50390,(#50395,#50424),.PCURVE_S1.); -#50390 = CIRCLE('',#50391,0.2); -#50391 = AXIS2_PLACEMENT_3D('',#50392,#50393,#50394); -#50392 = CARTESIAN_POINT('',(2.225,1.355,1.446602540378)); -#50393 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50394 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50395 = PCURVE('',#48990,#50396); -#50396 = DEFINITIONAL_REPRESENTATION('',(#50397),#50423); -#50397 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50398,#50399,#50400,#50401, - #50402,#50403,#50404,#50405,#50406,#50407,#50408,#50409,#50410, - #50411,#50412,#50413,#50414,#50415,#50416,#50417,#50418,#50419, - #50420,#50421,#50422),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#52727 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); +#52728 = CARTESIAN_POINT('',(-3.277378368693E-013,0.133530401499)); +#52729 = CARTESIAN_POINT('',(-6.332712132462E-013,0.138079221802)); +#52730 = CARTESIAN_POINT('',(-5.107025913276E-013,0.144902452256)); +#52731 = CARTESIAN_POINT('',(-5.462297281156E-013,0.15172568271)); +#52732 = CARTESIAN_POINT('',(-5.337952302398E-013,0.158548913164)); +#52733 = CARTESIAN_POINT('',(-5.39124300758E-013,0.165372143618)); +#52734 = CARTESIAN_POINT('',(-5.373479439186E-013,0.172195374072)); +#52735 = CARTESIAN_POINT('',(-5.355715870792E-013,0.179018604526)); +#52736 = CARTESIAN_POINT('',(-5.373479439186E-013,0.18584183498)); +#52737 = CARTESIAN_POINT('',(-5.355715870792E-013,0.192665065434)); +#52738 = CARTESIAN_POINT('',(-5.355715870792E-013,0.199488295888)); +#52739 = CARTESIAN_POINT('',(-5.373479439186E-013,0.206311526342)); +#52740 = CARTESIAN_POINT('',(-5.373479439186E-013,0.213134756797)); +#52741 = CARTESIAN_POINT('',(-5.355715870792E-013,0.219957987251)); +#52742 = CARTESIAN_POINT('',(-5.364597654989E-013,0.226781217705)); +#52743 = CARTESIAN_POINT('',(-5.373479439186E-013,0.233604448159)); +#52744 = CARTESIAN_POINT('',(-5.355715870792E-013,0.240427678613)); +#52745 = CARTESIAN_POINT('',(-5.373479439186E-013,0.247250909067)); +#52746 = CARTESIAN_POINT('',(-5.346834086595E-013,0.254074139521)); +#52747 = CARTESIAN_POINT('',(-5.426770144368E-013,0.260897369975)); +#52748 = CARTESIAN_POINT('',(-5.12478948167E-013,0.267720600429)); +#52749 = CARTESIAN_POINT('',(-6.332712132462E-013,0.274543830883)); +#52750 = CARTESIAN_POINT('',(-3.277378368693E-013,0.279092651186)); +#52751 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); +#52752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52753 = ORIENTED_EDGE('',*,*,#51798,.F.); +#52754 = ORIENTED_EDGE('',*,*,#51087,.F.); +#52755 = ORIENTED_EDGE('',*,*,#52756,.F.); +#52756 = EDGE_CURVE('',#52710,#51060,#52757,.T.); +#52757 = SURFACE_CURVE('',#52758,(#52762,#52769),.PCURVE_S1.); +#52758 = LINE('',#52759,#52760); +#52759 = CARTESIAN_POINT('',(2.025,1.355,1.446602540378)); +#52760 = VECTOR('',#52761,1.); +#52761 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#52762 = PCURVE('',#51101,#52763); +#52763 = DEFINITIONAL_REPRESENTATION('',(#52764),#52768); +#52764 = LINE('',#52765,#52766); +#52765 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#52766 = VECTOR('',#52767,1.); +#52767 = DIRECTION('',(-0.866025403784,-0.5)); +#52768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52769 = PCURVE('',#51075,#52770); +#52770 = DEFINITIONAL_REPRESENTATION('',(#52771),#52775); +#52771 = LINE('',#52772,#52773); +#52772 = CARTESIAN_POINT('',(0.2,0.7)); +#52773 = VECTOR('',#52774,1.); +#52774 = DIRECTION('',(1.,0.E+000)); +#52775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52776 = ADVANCED_FACE('',(#52777),#51382,.T.); +#52777 = FACE_BOUND('',#52778,.T.); +#52778 = EDGE_LOOP('',(#52779,#52823,#52824,#52825)); +#52779 = ORIENTED_EDGE('',*,*,#52780,.F.); +#52780 = EDGE_CURVE('',#52710,#51367,#52781,.T.); +#52781 = SURFACE_CURVE('',#52782,(#52787,#52816),.PCURVE_S1.); +#52782 = CIRCLE('',#52783,0.2); +#52783 = AXIS2_PLACEMENT_3D('',#52784,#52785,#52786); +#52784 = CARTESIAN_POINT('',(2.225,1.355,1.446602540378)); +#52785 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#52786 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#52787 = PCURVE('',#51382,#52788); +#52788 = DEFINITIONAL_REPRESENTATION('',(#52789),#52815); +#52789 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52790,#52791,#52792,#52793, + #52794,#52795,#52796,#52797,#52798,#52799,#52800,#52801,#52802, + #52803,#52804,#52805,#52806,#52807,#52808,#52809,#52810,#52811, + #52812,#52813,#52814),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -62692,418 +65681,418 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#50398 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); -#50399 = CARTESIAN_POINT('',(2.379994434424E-002,0.281367061337)); -#50400 = CARTESIAN_POINT('',(7.139983303393E-002,0.281367061337)); -#50401 = CARTESIAN_POINT('',(0.142799666071,0.281367061337)); -#50402 = CARTESIAN_POINT('',(0.214199499107,0.281367061337)); -#50403 = CARTESIAN_POINT('',(0.285599332143,0.281367061337)); -#50404 = CARTESIAN_POINT('',(0.356999165179,0.281367061337)); -#50405 = CARTESIAN_POINT('',(0.428398998215,0.281367061337)); -#50406 = CARTESIAN_POINT('',(0.499798831251,0.281367061337)); -#50407 = CARTESIAN_POINT('',(0.571198664287,0.281367061337)); -#50408 = CARTESIAN_POINT('',(0.642598497324,0.281367061337)); -#50409 = CARTESIAN_POINT('',(0.71399833036,0.281367061337)); -#50410 = CARTESIAN_POINT('',(0.785398163396,0.281367061337)); -#50411 = CARTESIAN_POINT('',(0.856797996432,0.281367061337)); -#50412 = CARTESIAN_POINT('',(0.928197829469,0.281367061337)); -#50413 = CARTESIAN_POINT('',(0.999597662505,0.281367061337)); -#50414 = CARTESIAN_POINT('',(1.070997495541,0.281367061337)); -#50415 = CARTESIAN_POINT('',(1.142397328577,0.281367061337)); -#50416 = CARTESIAN_POINT('',(1.213797161614,0.281367061337)); -#50417 = CARTESIAN_POINT('',(1.28519699465,0.281367061337)); -#50418 = CARTESIAN_POINT('',(1.356596827686,0.281367061337)); -#50419 = CARTESIAN_POINT('',(1.427996660722,0.281367061337)); -#50420 = CARTESIAN_POINT('',(1.499396493759,0.281367061337)); -#50421 = CARTESIAN_POINT('',(1.546996382449,0.281367061337)); -#50422 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); -#50423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#52790 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); +#52791 = CARTESIAN_POINT('',(2.379994434424E-002,0.281367061337)); +#52792 = CARTESIAN_POINT('',(7.139983303393E-002,0.281367061337)); +#52793 = CARTESIAN_POINT('',(0.142799666071,0.281367061337)); +#52794 = CARTESIAN_POINT('',(0.214199499107,0.281367061337)); +#52795 = CARTESIAN_POINT('',(0.285599332143,0.281367061337)); +#52796 = CARTESIAN_POINT('',(0.356999165179,0.281367061337)); +#52797 = CARTESIAN_POINT('',(0.428398998215,0.281367061337)); +#52798 = CARTESIAN_POINT('',(0.499798831251,0.281367061337)); +#52799 = CARTESIAN_POINT('',(0.571198664287,0.281367061337)); +#52800 = CARTESIAN_POINT('',(0.642598497324,0.281367061337)); +#52801 = CARTESIAN_POINT('',(0.71399833036,0.281367061337)); +#52802 = CARTESIAN_POINT('',(0.785398163396,0.281367061337)); +#52803 = CARTESIAN_POINT('',(0.856797996432,0.281367061337)); +#52804 = CARTESIAN_POINT('',(0.928197829469,0.281367061337)); +#52805 = CARTESIAN_POINT('',(0.999597662505,0.281367061337)); +#52806 = CARTESIAN_POINT('',(1.070997495541,0.281367061337)); +#52807 = CARTESIAN_POINT('',(1.142397328577,0.281367061337)); +#52808 = CARTESIAN_POINT('',(1.213797161614,0.281367061337)); +#52809 = CARTESIAN_POINT('',(1.28519699465,0.281367061337)); +#52810 = CARTESIAN_POINT('',(1.356596827686,0.281367061337)); +#52811 = CARTESIAN_POINT('',(1.427996660722,0.281367061337)); +#52812 = CARTESIAN_POINT('',(1.499396493759,0.281367061337)); +#52813 = CARTESIAN_POINT('',(1.546996382449,0.281367061337)); +#52814 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); +#52815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#50424 = PCURVE('',#48683,#50425); -#50425 = DEFINITIONAL_REPRESENTATION('',(#50426),#50430); -#50426 = CIRCLE('',#50427,0.2); -#50427 = AXIS2_PLACEMENT_2D('',#50428,#50429); -#50428 = CARTESIAN_POINT('',(0.2,0.5)); -#50429 = DIRECTION('',(0.E+000,1.)); -#50430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50431 = ORIENTED_EDGE('',*,*,#50317,.F.); -#50432 = ORIENTED_EDGE('',*,*,#49429,.F.); -#50433 = ORIENTED_EDGE('',*,*,#48974,.T.); -#50434 = ADVANCED_FACE('',(#50435),#48683,.T.); -#50435 = FACE_BOUND('',#50436,.F.); -#50436 = EDGE_LOOP('',(#50437,#50438,#50439,#50440,#50441,#50442)); -#50437 = ORIENTED_EDGE('',*,*,#48903,.F.); -#50438 = ORIENTED_EDGE('',*,*,#49001,.T.); -#50439 = ORIENTED_EDGE('',*,*,#50388,.F.); -#50440 = ORIENTED_EDGE('',*,*,#50364,.T.); -#50441 = ORIENTED_EDGE('',*,*,#48667,.F.); -#50442 = ORIENTED_EDGE('',*,*,#48776,.F.); -#50443 = ADVANCED_FACE('',(#50444),#48001,.F.); -#50444 = FACE_BOUND('',#50445,.F.); -#50445 = EDGE_LOOP('',(#50446,#50447,#50448,#50449)); -#50446 = ORIENTED_EDGE('',*,*,#49484,.F.); -#50447 = ORIENTED_EDGE('',*,*,#48436,.T.); -#50448 = ORIENTED_EDGE('',*,*,#47987,.T.); -#50449 = ORIENTED_EDGE('',*,*,#50450,.F.); -#50450 = EDGE_CURVE('',#49485,#47956,#50451,.T.); -#50451 = SURFACE_CURVE('',#50452,(#50456,#50463),.PCURVE_S1.); -#50452 = LINE('',#50453,#50454); -#50453 = CARTESIAN_POINT('',(2.85,1.225,1.35)); -#50454 = VECTOR('',#50455,1.); -#50455 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50456 = PCURVE('',#48001,#50457); -#50457 = DEFINITIONAL_REPRESENTATION('',(#50458),#50462); -#50458 = LINE('',#50459,#50460); -#50459 = CARTESIAN_POINT('',(0.125,0.E+000)); -#50460 = VECTOR('',#50461,1.); -#50461 = DIRECTION('',(0.E+000,-1.)); -#50462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#52816 = PCURVE('',#51075,#52817); +#52817 = DEFINITIONAL_REPRESENTATION('',(#52818),#52822); +#52818 = CIRCLE('',#52819,0.2); +#52819 = AXIS2_PLACEMENT_2D('',#52820,#52821); +#52820 = CARTESIAN_POINT('',(0.2,0.5)); +#52821 = DIRECTION('',(0.E+000,1.)); +#52822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52823 = ORIENTED_EDGE('',*,*,#52709,.F.); +#52824 = ORIENTED_EDGE('',*,*,#51821,.F.); +#52825 = ORIENTED_EDGE('',*,*,#51366,.T.); +#52826 = ADVANCED_FACE('',(#52827),#51075,.T.); +#52827 = FACE_BOUND('',#52828,.F.); +#52828 = EDGE_LOOP('',(#52829,#52830,#52831,#52832,#52833,#52834)); +#52829 = ORIENTED_EDGE('',*,*,#51295,.F.); +#52830 = ORIENTED_EDGE('',*,*,#51393,.T.); +#52831 = ORIENTED_EDGE('',*,*,#52780,.F.); +#52832 = ORIENTED_EDGE('',*,*,#52756,.T.); +#52833 = ORIENTED_EDGE('',*,*,#51059,.F.); +#52834 = ORIENTED_EDGE('',*,*,#51168,.F.); +#52835 = ADVANCED_FACE('',(#52836),#50393,.F.); +#52836 = FACE_BOUND('',#52837,.F.); +#52837 = EDGE_LOOP('',(#52838,#52839,#52840,#52841)); +#52838 = ORIENTED_EDGE('',*,*,#51876,.F.); +#52839 = ORIENTED_EDGE('',*,*,#50828,.T.); +#52840 = ORIENTED_EDGE('',*,*,#50379,.T.); +#52841 = ORIENTED_EDGE('',*,*,#52842,.F.); +#52842 = EDGE_CURVE('',#51877,#50348,#52843,.T.); +#52843 = SURFACE_CURVE('',#52844,(#52848,#52855),.PCURVE_S1.); +#52844 = LINE('',#52845,#52846); +#52845 = CARTESIAN_POINT('',(2.85,1.225,1.35)); +#52846 = VECTOR('',#52847,1.); +#52847 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52848 = PCURVE('',#50393,#52849); +#52849 = DEFINITIONAL_REPRESENTATION('',(#52850),#52854); +#52850 = LINE('',#52851,#52852); +#52851 = CARTESIAN_POINT('',(0.125,0.E+000)); +#52852 = VECTOR('',#52853,1.); +#52853 = DIRECTION('',(0.E+000,-1.)); +#52854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#50463 = PCURVE('',#47976,#50464); -#50464 = DEFINITIONAL_REPRESENTATION('',(#50465),#50468); -#50465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50466,#50467),.UNSPECIFIED., +#52855 = PCURVE('',#50368,#52856); +#52856 = DEFINITIONAL_REPRESENTATION('',(#52857),#52860); +#52857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52858,#52859),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#50466 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); -#50467 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); -#50468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50469 = ADVANCED_FACE('',(#50470),#47976,.F.); -#50470 = FACE_BOUND('',#50471,.F.); -#50471 = EDGE_LOOP('',(#50472,#50473,#50474,#50475)); -#50472 = ORIENTED_EDGE('',*,*,#49507,.F.); -#50473 = ORIENTED_EDGE('',*,*,#50450,.T.); -#50474 = ORIENTED_EDGE('',*,*,#47955,.T.); -#50475 = ORIENTED_EDGE('',*,*,#50476,.F.); -#50476 = EDGE_CURVE('',#49508,#47928,#50477,.T.); -#50477 = SURFACE_CURVE('',#50478,(#50482,#50488),.PCURVE_S1.); -#50478 = LINE('',#50479,#50480); -#50479 = CARTESIAN_POINT('',(2.85,1.225,1.1)); -#50480 = VECTOR('',#50481,1.); -#50481 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50482 = PCURVE('',#47976,#50483); -#50483 = DEFINITIONAL_REPRESENTATION('',(#50484),#50487); -#50484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50485,#50486),.UNSPECIFIED., +#52858 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); +#52859 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); +#52860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52861 = ADVANCED_FACE('',(#52862),#50368,.F.); +#52862 = FACE_BOUND('',#52863,.F.); +#52863 = EDGE_LOOP('',(#52864,#52865,#52866,#52867)); +#52864 = ORIENTED_EDGE('',*,*,#51899,.F.); +#52865 = ORIENTED_EDGE('',*,*,#52842,.T.); +#52866 = ORIENTED_EDGE('',*,*,#50347,.T.); +#52867 = ORIENTED_EDGE('',*,*,#52868,.F.); +#52868 = EDGE_CURVE('',#51900,#50320,#52869,.T.); +#52869 = SURFACE_CURVE('',#52870,(#52874,#52880),.PCURVE_S1.); +#52870 = LINE('',#52871,#52872); +#52871 = CARTESIAN_POINT('',(2.85,1.225,1.1)); +#52872 = VECTOR('',#52873,1.); +#52873 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52874 = PCURVE('',#50368,#52875); +#52875 = DEFINITIONAL_REPRESENTATION('',(#52876),#52879); +#52876 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52877,#52878),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#50485 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50486 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#50487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50488 = PCURVE('',#47943,#50489); -#50489 = DEFINITIONAL_REPRESENTATION('',(#50490),#50494); -#50490 = LINE('',#50491,#50492); -#50491 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50492 = VECTOR('',#50493,1.); -#50493 = DIRECTION('',(0.E+000,-1.)); -#50494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50495 = ADVANCED_FACE('',(#50496),#47943,.F.); -#50496 = FACE_BOUND('',#50497,.F.); -#50497 = EDGE_LOOP('',(#50498,#50499,#50500,#50501)); -#50498 = ORIENTED_EDGE('',*,*,#49530,.F.); -#50499 = ORIENTED_EDGE('',*,*,#50476,.T.); -#50500 = ORIENTED_EDGE('',*,*,#47927,.T.); -#50501 = ORIENTED_EDGE('',*,*,#50502,.F.); -#50502 = EDGE_CURVE('',#49531,#47900,#50503,.T.); -#50503 = SURFACE_CURVE('',#50504,(#50508,#50515),.PCURVE_S1.); -#50504 = LINE('',#50505,#50506); -#50505 = CARTESIAN_POINT('',(2.725,1.225,1.1)); -#50506 = VECTOR('',#50507,1.); -#50507 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50508 = PCURVE('',#47943,#50509); -#50509 = DEFINITIONAL_REPRESENTATION('',(#50510),#50514); -#50510 = LINE('',#50511,#50512); -#50511 = CARTESIAN_POINT('',(0.125,0.E+000)); -#50512 = VECTOR('',#50513,1.); -#50513 = DIRECTION('',(0.E+000,-1.)); -#50514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50515 = PCURVE('',#47915,#50516); -#50516 = DEFINITIONAL_REPRESENTATION('',(#50517),#50521); -#50517 = LINE('',#50518,#50519); -#50518 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50519 = VECTOR('',#50520,1.); -#50520 = DIRECTION('',(0.E+000,-1.)); -#50521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50522 = ADVANCED_FACE('',(#50523),#47915,.F.); -#50523 = FACE_BOUND('',#50524,.F.); -#50524 = EDGE_LOOP('',(#50525,#50526,#50527,#50528)); -#50525 = ORIENTED_EDGE('',*,*,#49553,.F.); -#50526 = ORIENTED_EDGE('',*,*,#50502,.T.); -#50527 = ORIENTED_EDGE('',*,*,#47899,.T.); -#50528 = ORIENTED_EDGE('',*,*,#50529,.F.); -#50529 = EDGE_CURVE('',#49554,#47872,#50530,.T.); -#50530 = SURFACE_CURVE('',#50531,(#50535,#50542),.PCURVE_S1.); -#50531 = LINE('',#50532,#50533); -#50532 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); -#50533 = VECTOR('',#50534,1.); -#50534 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50535 = PCURVE('',#47915,#50536); -#50536 = DEFINITIONAL_REPRESENTATION('',(#50537),#50541); -#50537 = LINE('',#50538,#50539); -#50538 = CARTESIAN_POINT('',(1.22,0.E+000)); -#50539 = VECTOR('',#50540,1.); -#50540 = DIRECTION('',(0.E+000,-1.)); -#50541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50542 = PCURVE('',#47887,#50543); -#50543 = DEFINITIONAL_REPRESENTATION('',(#50544),#50548); -#50544 = LINE('',#50545,#50546); -#50545 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50546 = VECTOR('',#50547,1.); -#50547 = DIRECTION('',(0.E+000,-1.)); -#50548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50549 = ADVANCED_FACE('',(#50550),#47887,.F.); -#50550 = FACE_BOUND('',#50551,.F.); -#50551 = EDGE_LOOP('',(#50552,#50553,#50554,#50555)); -#50552 = ORIENTED_EDGE('',*,*,#49576,.F.); -#50553 = ORIENTED_EDGE('',*,*,#50529,.T.); -#50554 = ORIENTED_EDGE('',*,*,#47871,.T.); -#50555 = ORIENTED_EDGE('',*,*,#50556,.F.); -#50556 = EDGE_CURVE('',#49577,#47844,#50557,.T.); -#50557 = SURFACE_CURVE('',#50558,(#50562,#50569),.PCURVE_S1.); -#50558 = LINE('',#50559,#50560); -#50559 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); -#50560 = VECTOR('',#50561,1.); -#50561 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50562 = PCURVE('',#47887,#50563); -#50563 = DEFINITIONAL_REPRESENTATION('',(#50564),#50568); -#50564 = LINE('',#50565,#50566); -#50565 = CARTESIAN_POINT('',(0.7,0.E+000)); -#50566 = VECTOR('',#50567,1.); -#50567 = DIRECTION('',(0.E+000,-1.)); -#50568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50569 = PCURVE('',#47859,#50570); -#50570 = DEFINITIONAL_REPRESENTATION('',(#50571),#50575); -#50571 = LINE('',#50572,#50573); -#50572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50573 = VECTOR('',#50574,1.); -#50574 = DIRECTION('',(0.E+000,-1.)); -#50575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50576 = ADVANCED_FACE('',(#50577),#47859,.F.); -#50577 = FACE_BOUND('',#50578,.F.); -#50578 = EDGE_LOOP('',(#50579,#50580,#50581,#50582)); -#50579 = ORIENTED_EDGE('',*,*,#49599,.F.); -#50580 = ORIENTED_EDGE('',*,*,#50556,.T.); -#50581 = ORIENTED_EDGE('',*,*,#47843,.T.); -#50582 = ORIENTED_EDGE('',*,*,#50583,.F.); -#50583 = EDGE_CURVE('',#49600,#47816,#50584,.T.); -#50584 = SURFACE_CURVE('',#50585,(#50589,#50596),.PCURVE_S1.); -#50585 = LINE('',#50586,#50587); -#50586 = CARTESIAN_POINT('',(2.025,1.225,1.1)); -#50587 = VECTOR('',#50588,1.); -#50588 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50589 = PCURVE('',#47859,#50590); -#50590 = DEFINITIONAL_REPRESENTATION('',(#50591),#50595); -#50591 = LINE('',#50592,#50593); -#50592 = CARTESIAN_POINT('',(1.22,0.E+000)); -#50593 = VECTOR('',#50594,1.); -#50594 = DIRECTION('',(0.E+000,-1.)); -#50595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50596 = PCURVE('',#47831,#50597); -#50597 = DEFINITIONAL_REPRESENTATION('',(#50598),#50602); -#50598 = LINE('',#50599,#50600); -#50599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50600 = VECTOR('',#50601,1.); -#50601 = DIRECTION('',(0.E+000,-1.)); -#50602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50603 = ADVANCED_FACE('',(#50604),#47831,.F.); -#50604 = FACE_BOUND('',#50605,.F.); -#50605 = EDGE_LOOP('',(#50606,#50607,#50608,#50609)); -#50606 = ORIENTED_EDGE('',*,*,#49622,.F.); -#50607 = ORIENTED_EDGE('',*,*,#50583,.T.); -#50608 = ORIENTED_EDGE('',*,*,#47815,.T.); -#50609 = ORIENTED_EDGE('',*,*,#50610,.F.); -#50610 = EDGE_CURVE('',#49623,#47784,#50611,.T.); -#50611 = SURFACE_CURVE('',#50612,(#50616,#50623),.PCURVE_S1.); -#50612 = LINE('',#50613,#50614); -#50613 = CARTESIAN_POINT('',(1.9,1.225,1.1)); -#50614 = VECTOR('',#50615,1.); -#50615 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50616 = PCURVE('',#47831,#50617); -#50617 = DEFINITIONAL_REPRESENTATION('',(#50618),#50622); -#50618 = LINE('',#50619,#50620); -#50619 = CARTESIAN_POINT('',(0.125,0.E+000)); -#50620 = VECTOR('',#50621,1.); -#50621 = DIRECTION('',(0.E+000,-1.)); -#50622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50623 = PCURVE('',#47804,#50624); -#50624 = DEFINITIONAL_REPRESENTATION('',(#50625),#50628); -#50625 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50626,#50627),.UNSPECIFIED., +#52877 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#52878 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#52879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52880 = PCURVE('',#50335,#52881); +#52881 = DEFINITIONAL_REPRESENTATION('',(#52882),#52886); +#52882 = LINE('',#52883,#52884); +#52883 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52884 = VECTOR('',#52885,1.); +#52885 = DIRECTION('',(0.E+000,-1.)); +#52886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52887 = ADVANCED_FACE('',(#52888),#50335,.F.); +#52888 = FACE_BOUND('',#52889,.F.); +#52889 = EDGE_LOOP('',(#52890,#52891,#52892,#52893)); +#52890 = ORIENTED_EDGE('',*,*,#51922,.F.); +#52891 = ORIENTED_EDGE('',*,*,#52868,.T.); +#52892 = ORIENTED_EDGE('',*,*,#50319,.T.); +#52893 = ORIENTED_EDGE('',*,*,#52894,.F.); +#52894 = EDGE_CURVE('',#51923,#50292,#52895,.T.); +#52895 = SURFACE_CURVE('',#52896,(#52900,#52907),.PCURVE_S1.); +#52896 = LINE('',#52897,#52898); +#52897 = CARTESIAN_POINT('',(2.725,1.225,1.1)); +#52898 = VECTOR('',#52899,1.); +#52899 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52900 = PCURVE('',#50335,#52901); +#52901 = DEFINITIONAL_REPRESENTATION('',(#52902),#52906); +#52902 = LINE('',#52903,#52904); +#52903 = CARTESIAN_POINT('',(0.125,0.E+000)); +#52904 = VECTOR('',#52905,1.); +#52905 = DIRECTION('',(0.E+000,-1.)); +#52906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52907 = PCURVE('',#50307,#52908); +#52908 = DEFINITIONAL_REPRESENTATION('',(#52909),#52913); +#52909 = LINE('',#52910,#52911); +#52910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52911 = VECTOR('',#52912,1.); +#52912 = DIRECTION('',(0.E+000,-1.)); +#52913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52914 = ADVANCED_FACE('',(#52915),#50307,.F.); +#52915 = FACE_BOUND('',#52916,.F.); +#52916 = EDGE_LOOP('',(#52917,#52918,#52919,#52920)); +#52917 = ORIENTED_EDGE('',*,*,#51945,.F.); +#52918 = ORIENTED_EDGE('',*,*,#52894,.T.); +#52919 = ORIENTED_EDGE('',*,*,#50291,.T.); +#52920 = ORIENTED_EDGE('',*,*,#52921,.F.); +#52921 = EDGE_CURVE('',#51946,#50264,#52922,.T.); +#52922 = SURFACE_CURVE('',#52923,(#52927,#52934),.PCURVE_S1.); +#52923 = LINE('',#52924,#52925); +#52924 = CARTESIAN_POINT('',(2.725,1.225,-0.12)); +#52925 = VECTOR('',#52926,1.); +#52926 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52927 = PCURVE('',#50307,#52928); +#52928 = DEFINITIONAL_REPRESENTATION('',(#52929),#52933); +#52929 = LINE('',#52930,#52931); +#52930 = CARTESIAN_POINT('',(1.22,0.E+000)); +#52931 = VECTOR('',#52932,1.); +#52932 = DIRECTION('',(0.E+000,-1.)); +#52933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52934 = PCURVE('',#50279,#52935); +#52935 = DEFINITIONAL_REPRESENTATION('',(#52936),#52940); +#52936 = LINE('',#52937,#52938); +#52937 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52938 = VECTOR('',#52939,1.); +#52939 = DIRECTION('',(0.E+000,-1.)); +#52940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52941 = ADVANCED_FACE('',(#52942),#50279,.F.); +#52942 = FACE_BOUND('',#52943,.F.); +#52943 = EDGE_LOOP('',(#52944,#52945,#52946,#52947)); +#52944 = ORIENTED_EDGE('',*,*,#51968,.F.); +#52945 = ORIENTED_EDGE('',*,*,#52921,.T.); +#52946 = ORIENTED_EDGE('',*,*,#50263,.T.); +#52947 = ORIENTED_EDGE('',*,*,#52948,.F.); +#52948 = EDGE_CURVE('',#51969,#50236,#52949,.T.); +#52949 = SURFACE_CURVE('',#52950,(#52954,#52961),.PCURVE_S1.); +#52950 = LINE('',#52951,#52952); +#52951 = CARTESIAN_POINT('',(2.025,1.225,-0.12)); +#52952 = VECTOR('',#52953,1.); +#52953 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52954 = PCURVE('',#50279,#52955); +#52955 = DEFINITIONAL_REPRESENTATION('',(#52956),#52960); +#52956 = LINE('',#52957,#52958); +#52957 = CARTESIAN_POINT('',(0.7,0.E+000)); +#52958 = VECTOR('',#52959,1.); +#52959 = DIRECTION('',(0.E+000,-1.)); +#52960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52961 = PCURVE('',#50251,#52962); +#52962 = DEFINITIONAL_REPRESENTATION('',(#52963),#52967); +#52963 = LINE('',#52964,#52965); +#52964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52965 = VECTOR('',#52966,1.); +#52966 = DIRECTION('',(0.E+000,-1.)); +#52967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52968 = ADVANCED_FACE('',(#52969),#50251,.F.); +#52969 = FACE_BOUND('',#52970,.F.); +#52970 = EDGE_LOOP('',(#52971,#52972,#52973,#52974)); +#52971 = ORIENTED_EDGE('',*,*,#51991,.F.); +#52972 = ORIENTED_EDGE('',*,*,#52948,.T.); +#52973 = ORIENTED_EDGE('',*,*,#50235,.T.); +#52974 = ORIENTED_EDGE('',*,*,#52975,.F.); +#52975 = EDGE_CURVE('',#51992,#50208,#52976,.T.); +#52976 = SURFACE_CURVE('',#52977,(#52981,#52988),.PCURVE_S1.); +#52977 = LINE('',#52978,#52979); +#52978 = CARTESIAN_POINT('',(2.025,1.225,1.1)); +#52979 = VECTOR('',#52980,1.); +#52980 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#52981 = PCURVE('',#50251,#52982); +#52982 = DEFINITIONAL_REPRESENTATION('',(#52983),#52987); +#52983 = LINE('',#52984,#52985); +#52984 = CARTESIAN_POINT('',(1.22,0.E+000)); +#52985 = VECTOR('',#52986,1.); +#52986 = DIRECTION('',(0.E+000,-1.)); +#52987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52988 = PCURVE('',#50223,#52989); +#52989 = DEFINITIONAL_REPRESENTATION('',(#52990),#52994); +#52990 = LINE('',#52991,#52992); +#52991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#52992 = VECTOR('',#52993,1.); +#52993 = DIRECTION('',(0.E+000,-1.)); +#52994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#52995 = ADVANCED_FACE('',(#52996),#50223,.F.); +#52996 = FACE_BOUND('',#52997,.F.); +#52997 = EDGE_LOOP('',(#52998,#52999,#53000,#53001)); +#52998 = ORIENTED_EDGE('',*,*,#52014,.F.); +#52999 = ORIENTED_EDGE('',*,*,#52975,.T.); +#53000 = ORIENTED_EDGE('',*,*,#50207,.T.); +#53001 = ORIENTED_EDGE('',*,*,#53002,.F.); +#53002 = EDGE_CURVE('',#52015,#50176,#53003,.T.); +#53003 = SURFACE_CURVE('',#53004,(#53008,#53015),.PCURVE_S1.); +#53004 = LINE('',#53005,#53006); +#53005 = CARTESIAN_POINT('',(1.9,1.225,1.1)); +#53006 = VECTOR('',#53007,1.); +#53007 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53008 = PCURVE('',#50223,#53009); +#53009 = DEFINITIONAL_REPRESENTATION('',(#53010),#53014); +#53010 = LINE('',#53011,#53012); +#53011 = CARTESIAN_POINT('',(0.125,0.E+000)); +#53012 = VECTOR('',#53013,1.); +#53013 = DIRECTION('',(0.E+000,-1.)); +#53014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53015 = PCURVE('',#50196,#53016); +#53016 = DEFINITIONAL_REPRESENTATION('',(#53017),#53020); +#53017 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53018,#53019),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#50626 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#50627 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#50628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50629 = ADVANCED_FACE('',(#50630),#47804,.F.); -#50630 = FACE_BOUND('',#50631,.F.); -#50631 = EDGE_LOOP('',(#50632,#50633,#50634,#50635)); -#50632 = ORIENTED_EDGE('',*,*,#49645,.F.); -#50633 = ORIENTED_EDGE('',*,*,#50610,.T.); -#50634 = ORIENTED_EDGE('',*,*,#47783,.T.); -#50635 = ORIENTED_EDGE('',*,*,#50636,.F.); -#50636 = EDGE_CURVE('',#49646,#47756,#50637,.T.); -#50637 = SURFACE_CURVE('',#50638,(#50642,#50648),.PCURVE_S1.); -#50638 = LINE('',#50639,#50640); -#50639 = CARTESIAN_POINT('',(1.9,1.225,1.35)); -#50640 = VECTOR('',#50641,1.); -#50641 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#50642 = PCURVE('',#47804,#50643); -#50643 = DEFINITIONAL_REPRESENTATION('',(#50644),#50647); -#50644 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50645,#50646),.UNSPECIFIED., +#53018 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#53019 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#53020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53021 = ADVANCED_FACE('',(#53022),#50196,.F.); +#53022 = FACE_BOUND('',#53023,.F.); +#53023 = EDGE_LOOP('',(#53024,#53025,#53026,#53027)); +#53024 = ORIENTED_EDGE('',*,*,#52037,.F.); +#53025 = ORIENTED_EDGE('',*,*,#53002,.T.); +#53026 = ORIENTED_EDGE('',*,*,#50175,.T.); +#53027 = ORIENTED_EDGE('',*,*,#53028,.F.); +#53028 = EDGE_CURVE('',#52038,#50148,#53029,.T.); +#53029 = SURFACE_CURVE('',#53030,(#53034,#53040),.PCURVE_S1.); +#53030 = LINE('',#53031,#53032); +#53031 = CARTESIAN_POINT('',(1.9,1.225,1.35)); +#53032 = VECTOR('',#53033,1.); +#53033 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53034 = PCURVE('',#50196,#53035); +#53035 = DEFINITIONAL_REPRESENTATION('',(#53036),#53039); +#53036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53037,#53038),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#50645 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#50646 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#50647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50648 = PCURVE('',#47771,#50649); -#50649 = DEFINITIONAL_REPRESENTATION('',(#50650),#50654); -#50650 = LINE('',#50651,#50652); -#50651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50652 = VECTOR('',#50653,1.); -#50653 = DIRECTION('',(0.E+000,-1.)); -#50654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50655 = ADVANCED_FACE('',(#50656),#47771,.F.); -#50656 = FACE_BOUND('',#50657,.F.); -#50657 = EDGE_LOOP('',(#50658,#50659,#50660,#50661)); -#50658 = ORIENTED_EDGE('',*,*,#49668,.F.); -#50659 = ORIENTED_EDGE('',*,*,#50636,.T.); -#50660 = ORIENTED_EDGE('',*,*,#47755,.T.); -#50661 = ORIENTED_EDGE('',*,*,#48611,.F.); -#50662 = ADVANCED_FACE('',(#50663),#49710,.F.); -#50663 = FACE_BOUND('',#50664,.F.); -#50664 = EDGE_LOOP('',(#50665,#50687,#50688,#50710)); -#50665 = ORIENTED_EDGE('',*,*,#50666,.T.); -#50666 = EDGE_CURVE('',#50667,#49695,#50669,.T.); -#50667 = VERTEX_POINT('',#50668); -#50668 = CARTESIAN_POINT('',(-2.225,1.455,1.619807621135)); -#50669 = SURFACE_CURVE('',#50670,(#50674,#50681),.PCURVE_S1.); -#50670 = LINE('',#50671,#50672); -#50671 = CARTESIAN_POINT('',(-2.225,1.455,1.619807621135)); -#50672 = VECTOR('',#50673,1.); -#50673 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#50674 = PCURVE('',#49710,#50675); -#50675 = DEFINITIONAL_REPRESENTATION('',(#50676),#50680); -#50676 = LINE('',#50677,#50678); -#50677 = CARTESIAN_POINT('',(0.265581123827,0.5)); -#50678 = VECTOR('',#50679,1.); -#50679 = DIRECTION('',(-1.,0.E+000)); -#50680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50681 = PCURVE('',#49746,#50682); -#50682 = DEFINITIONAL_REPRESENTATION('',(#50683),#50686); -#50683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50684,#50685),.UNSPECIFIED., +#53037 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#53038 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#53039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53040 = PCURVE('',#50163,#53041); +#53041 = DEFINITIONAL_REPRESENTATION('',(#53042),#53046); +#53042 = LINE('',#53043,#53044); +#53043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53044 = VECTOR('',#53045,1.); +#53045 = DIRECTION('',(0.E+000,-1.)); +#53046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53047 = ADVANCED_FACE('',(#53048),#50163,.F.); +#53048 = FACE_BOUND('',#53049,.F.); +#53049 = EDGE_LOOP('',(#53050,#53051,#53052,#53053)); +#53050 = ORIENTED_EDGE('',*,*,#52060,.F.); +#53051 = ORIENTED_EDGE('',*,*,#53028,.T.); +#53052 = ORIENTED_EDGE('',*,*,#50147,.T.); +#53053 = ORIENTED_EDGE('',*,*,#51003,.F.); +#53054 = ADVANCED_FACE('',(#53055),#52102,.F.); +#53055 = FACE_BOUND('',#53056,.F.); +#53056 = EDGE_LOOP('',(#53057,#53079,#53080,#53102)); +#53057 = ORIENTED_EDGE('',*,*,#53058,.T.); +#53058 = EDGE_CURVE('',#53059,#52087,#53061,.T.); +#53059 = VERTEX_POINT('',#53060); +#53060 = CARTESIAN_POINT('',(-2.225,1.455,1.619807621135)); +#53061 = SURFACE_CURVE('',#53062,(#53066,#53073),.PCURVE_S1.); +#53062 = LINE('',#53063,#53064); +#53063 = CARTESIAN_POINT('',(-2.225,1.455,1.619807621135)); +#53064 = VECTOR('',#53065,1.); +#53065 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53066 = PCURVE('',#52102,#53067); +#53067 = DEFINITIONAL_REPRESENTATION('',(#53068),#53072); +#53068 = LINE('',#53069,#53070); +#53069 = CARTESIAN_POINT('',(0.265581123827,0.5)); +#53070 = VECTOR('',#53071,1.); +#53071 = DIRECTION('',(-1.,0.E+000)); +#53072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53073 = PCURVE('',#52138,#53074); +#53074 = DEFINITIONAL_REPRESENTATION('',(#53075),#53078); +#53075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53076,#53077),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.265581123827),.PIECEWISE_BEZIER_KNOTS.); -#50684 = CARTESIAN_POINT('',(1.570796326795,2.240861599904E-002)); -#50685 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); -#50686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50687 = ORIENTED_EDGE('',*,*,#49692,.F.); -#50688 = ORIENTED_EDGE('',*,*,#50689,.T.); -#50689 = EDGE_CURVE('',#49693,#50690,#50692,.T.); -#50690 = VERTEX_POINT('',#50691); -#50691 = CARTESIAN_POINT('',(-2.525,1.455,1.619807621135)); -#50692 = SURFACE_CURVE('',#50693,(#50697,#50704),.PCURVE_S1.); -#50693 = LINE('',#50694,#50695); -#50694 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); -#50695 = VECTOR('',#50696,1.); -#50696 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50697 = PCURVE('',#49710,#50698); -#50698 = DEFINITIONAL_REPRESENTATION('',(#50699),#50703); -#50699 = LINE('',#50700,#50701); -#50700 = CARTESIAN_POINT('',(0.E+000,0.2)); -#50701 = VECTOR('',#50702,1.); -#50702 = DIRECTION('',(1.,0.E+000)); -#50703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50704 = PCURVE('',#50111,#50705); -#50705 = DEFINITIONAL_REPRESENTATION('',(#50706),#50709); -#50706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#50707,#50708),.UNSPECIFIED., +#53076 = CARTESIAN_POINT('',(1.570796326795,2.240861599904E-002)); +#53077 = CARTESIAN_POINT('',(1.570796326795,0.287989739826)); +#53078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53079 = ORIENTED_EDGE('',*,*,#52084,.F.); +#53080 = ORIENTED_EDGE('',*,*,#53081,.T.); +#53081 = EDGE_CURVE('',#52085,#53082,#53084,.T.); +#53082 = VERTEX_POINT('',#53083); +#53083 = CARTESIAN_POINT('',(-2.525,1.455,1.619807621135)); +#53084 = SURFACE_CURVE('',#53085,(#53089,#53096),.PCURVE_S1.); +#53085 = LINE('',#53086,#53087); +#53086 = CARTESIAN_POINT('',(-2.525,1.225,1.752598183049)); +#53087 = VECTOR('',#53088,1.); +#53088 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#53089 = PCURVE('',#52102,#53090); +#53090 = DEFINITIONAL_REPRESENTATION('',(#53091),#53095); +#53091 = LINE('',#53092,#53093); +#53092 = CARTESIAN_POINT('',(0.E+000,0.2)); +#53093 = VECTOR('',#53094,1.); +#53094 = DIRECTION('',(1.,0.E+000)); +#53095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53096 = PCURVE('',#52503,#53097); +#53097 = DEFINITIONAL_REPRESENTATION('',(#53098),#53101); +#53098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53099,#53100),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.265581123827),.PIECEWISE_BEZIER_KNOTS.); -#50707 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); -#50708 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); -#50709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50710 = ORIENTED_EDGE('',*,*,#50711,.T.); -#50711 = EDGE_CURVE('',#50690,#50667,#50712,.T.); -#50712 = SURFACE_CURVE('',#50713,(#50717,#50724),.PCURVE_S1.); -#50713 = LINE('',#50714,#50715); -#50714 = CARTESIAN_POINT('',(-2.525,1.455,1.619807621135)); -#50715 = VECTOR('',#50716,1.); -#50716 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50717 = PCURVE('',#49710,#50718); -#50718 = DEFINITIONAL_REPRESENTATION('',(#50719),#50723); -#50719 = LINE('',#50720,#50721); -#50720 = CARTESIAN_POINT('',(0.265581123827,0.2)); -#50721 = VECTOR('',#50722,1.); -#50722 = DIRECTION('',(0.E+000,1.)); -#50723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50724 = PCURVE('',#50725,#50730); -#50725 = PLANE('',#50726); -#50726 = AXIS2_PLACEMENT_3D('',#50727,#50728,#50729); -#50727 = CARTESIAN_POINT('',(-2.725,1.455,1.619807621135)); -#50728 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#50729 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#50730 = DEFINITIONAL_REPRESENTATION('',(#50731),#50735); -#50731 = LINE('',#50732,#50733); -#50732 = CARTESIAN_POINT('',(0.E+000,0.2)); -#50733 = VECTOR('',#50734,1.); -#50734 = DIRECTION('',(0.E+000,1.)); -#50735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50736 = ADVANCED_FACE('',(#50737),#49746,.T.); -#50737 = FACE_BOUND('',#50738,.T.); -#50738 = EDGE_LOOP('',(#50739,#50740,#50741,#50786)); -#50739 = ORIENTED_EDGE('',*,*,#50666,.T.); -#50740 = ORIENTED_EDGE('',*,*,#49722,.F.); -#50741 = ORIENTED_EDGE('',*,*,#50742,.F.); -#50742 = EDGE_CURVE('',#50743,#49723,#50745,.T.); -#50743 = VERTEX_POINT('',#50744); -#50744 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); -#50745 = SURFACE_CURVE('',#50746,(#50750,#50779),.PCURVE_S1.); -#50746 = LINE('',#50747,#50748); -#50747 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); -#50748 = VECTOR('',#50749,1.); -#50749 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#50750 = PCURVE('',#49746,#50751); -#50751 = DEFINITIONAL_REPRESENTATION('',(#50752),#50778); -#50752 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50753,#50754,#50755,#50756, - #50757,#50758,#50759,#50760,#50761,#50762,#50763,#50764,#50765, - #50766,#50767,#50768,#50769,#50770,#50771,#50772,#50773,#50774, - #50775,#50776,#50777),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#53099 = CARTESIAN_POINT('',(1.570796326795,1.578593750971E-002)); +#53100 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); +#53101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53102 = ORIENTED_EDGE('',*,*,#53103,.T.); +#53103 = EDGE_CURVE('',#53082,#53059,#53104,.T.); +#53104 = SURFACE_CURVE('',#53105,(#53109,#53116),.PCURVE_S1.); +#53105 = LINE('',#53106,#53107); +#53106 = CARTESIAN_POINT('',(-2.525,1.455,1.619807621135)); +#53107 = VECTOR('',#53108,1.); +#53108 = DIRECTION('',(1.,0.E+000,0.E+000)); +#53109 = PCURVE('',#52102,#53110); +#53110 = DEFINITIONAL_REPRESENTATION('',(#53111),#53115); +#53111 = LINE('',#53112,#53113); +#53112 = CARTESIAN_POINT('',(0.265581123827,0.2)); +#53113 = VECTOR('',#53114,1.); +#53114 = DIRECTION('',(0.E+000,1.)); +#53115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53116 = PCURVE('',#53117,#53122); +#53117 = PLANE('',#53118); +#53118 = AXIS2_PLACEMENT_3D('',#53119,#53120,#53121); +#53119 = CARTESIAN_POINT('',(-2.725,1.455,1.619807621135)); +#53120 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53121 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#53122 = DEFINITIONAL_REPRESENTATION('',(#53123),#53127); +#53123 = LINE('',#53124,#53125); +#53124 = CARTESIAN_POINT('',(0.E+000,0.2)); +#53125 = VECTOR('',#53126,1.); +#53126 = DIRECTION('',(0.E+000,1.)); +#53127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53128 = ADVANCED_FACE('',(#53129),#52138,.T.); +#53129 = FACE_BOUND('',#53130,.T.); +#53130 = EDGE_LOOP('',(#53131,#53132,#53133,#53178)); +#53131 = ORIENTED_EDGE('',*,*,#53058,.T.); +#53132 = ORIENTED_EDGE('',*,*,#52114,.F.); +#53133 = ORIENTED_EDGE('',*,*,#53134,.F.); +#53134 = EDGE_CURVE('',#53135,#52115,#53137,.T.); +#53135 = VERTEX_POINT('',#53136); +#53136 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); +#53137 = SURFACE_CURVE('',#53138,(#53142,#53171),.PCURVE_S1.); +#53138 = LINE('',#53139,#53140); +#53139 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); +#53140 = VECTOR('',#53141,1.); +#53141 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53142 = PCURVE('',#52138,#53143); +#53143 = DEFINITIONAL_REPRESENTATION('',(#53144),#53170); +#53144 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53145,#53146,#53147,#53148, + #53149,#53150,#53151,#53152,#53153,#53154,#53155,#53156,#53157, + #53158,#53159,#53160,#53161,#53162,#53163,#53164,#53165,#53166, + #53167,#53168,#53169),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.823230454067E-003, 1.364646090813E-002,2.04696913622E-002,2.729292181627E-002, 3.411615227034E-002,4.09393827244E-002,4.776261317847E-002, @@ -63112,57 +66101,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 9.552522635694E-002,0.102348456811,0.109171687265,0.115994917719, 0.122818148173,0.129641378627,0.136464609081,0.143287839535, 0.150111069989),.QUASI_UNIFORM_KNOTS.); -#50753 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); -#50754 = CARTESIAN_POINT('',(-1.668887250617E-012,2.468302615029E-002)); -#50755 = CARTESIAN_POINT('',(-3.223199485092E-012,2.9231846453E-002)); -#50756 = CARTESIAN_POINT('',(-2.597033699203E-012,3.605507690707E-002)); -#50757 = CARTESIAN_POINT('',(-2.766675777366E-012,4.287830736114E-002)); -#50758 = CARTESIAN_POINT('',(-2.722266856381E-012,4.970153781521E-002)); -#50759 = CARTESIAN_POINT('',(-2.733813175837E-012,5.652476826927E-002)); -#50760 = CARTESIAN_POINT('',(-2.729372283738E-012,6.334799872334E-002)); -#50761 = CARTESIAN_POINT('',(-2.731148640578E-012,7.017122917741E-002)); -#50762 = CARTESIAN_POINT('',(-2.729372283738E-012,7.699445963147E-002)); -#50763 = CARTESIAN_POINT('',(-2.729372283738E-012,8.381769008554E-002)); -#50764 = CARTESIAN_POINT('',(-2.731148640578E-012,9.064092053961E-002)); -#50765 = CARTESIAN_POINT('',(-2.730260462158E-012,9.746415099368E-002)); -#50766 = CARTESIAN_POINT('',(-2.730260462158E-012,0.104287381448)); -#50767 = CARTESIAN_POINT('',(-2.731148640578E-012,0.111110611902)); -#50768 = CARTESIAN_POINT('',(-2.729372283738E-012,0.117933842356)); -#50769 = CARTESIAN_POINT('',(-2.729372283738E-012,0.12475707281)); -#50770 = CARTESIAN_POINT('',(-2.731148640578E-012,0.131580303264)); -#50771 = CARTESIAN_POINT('',(-2.731148640578E-012,0.138403533718)); -#50772 = CARTESIAN_POINT('',(-2.723155034801E-012,0.145226764172)); -#50773 = CARTESIAN_POINT('',(-2.765787598946E-012,0.152049994626)); -#50774 = CARTESIAN_POINT('',(-2.598810056043E-012,0.15887322508)); -#50775 = CARTESIAN_POINT('',(-3.224087663511E-012,0.165696455534)); -#50776 = CARTESIAN_POINT('',(-1.668887250617E-012,0.170245275837)); -#50777 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); -#50778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50779 = PCURVE('',#49796,#50780); -#50780 = DEFINITIONAL_REPRESENTATION('',(#50781),#50785); -#50781 = LINE('',#50782,#50783); -#50782 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#50783 = VECTOR('',#50784,1.); -#50784 = DIRECTION('',(0.5,-0.866025403784)); -#50785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50786 = ORIENTED_EDGE('',*,*,#50787,.F.); -#50787 = EDGE_CURVE('',#50667,#50743,#50788,.T.); -#50788 = SURFACE_CURVE('',#50789,(#50794,#50823),.PCURVE_S1.); -#50789 = CIRCLE('',#50790,0.2); -#50790 = AXIS2_PLACEMENT_3D('',#50791,#50792,#50793); -#50791 = CARTESIAN_POINT('',(-2.225,1.355,1.446602540378)); -#50792 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50793 = DIRECTION('',(0.E+000,0.5,0.866025403784)); -#50794 = PCURVE('',#49746,#50795); -#50795 = DEFINITIONAL_REPRESENTATION('',(#50796),#50822); -#50796 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50797,#50798,#50799,#50800, - #50801,#50802,#50803,#50804,#50805,#50806,#50807,#50808,#50809, - #50810,#50811,#50812,#50813,#50814,#50815,#50816,#50817,#50818, - #50819,#50820,#50821),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#53145 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); +#53146 = CARTESIAN_POINT('',(-1.668887250617E-012,2.468302615029E-002)); +#53147 = CARTESIAN_POINT('',(-3.223199485092E-012,2.9231846453E-002)); +#53148 = CARTESIAN_POINT('',(-2.597033699203E-012,3.605507690707E-002)); +#53149 = CARTESIAN_POINT('',(-2.766675777366E-012,4.287830736114E-002)); +#53150 = CARTESIAN_POINT('',(-2.722266856381E-012,4.970153781521E-002)); +#53151 = CARTESIAN_POINT('',(-2.733813175837E-012,5.652476826927E-002)); +#53152 = CARTESIAN_POINT('',(-2.729372283738E-012,6.334799872334E-002)); +#53153 = CARTESIAN_POINT('',(-2.731148640578E-012,7.017122917741E-002)); +#53154 = CARTESIAN_POINT('',(-2.729372283738E-012,7.699445963147E-002)); +#53155 = CARTESIAN_POINT('',(-2.729372283738E-012,8.381769008554E-002)); +#53156 = CARTESIAN_POINT('',(-2.731148640578E-012,9.064092053961E-002)); +#53157 = CARTESIAN_POINT('',(-2.730260462158E-012,9.746415099368E-002)); +#53158 = CARTESIAN_POINT('',(-2.730260462158E-012,0.104287381448)); +#53159 = CARTESIAN_POINT('',(-2.731148640578E-012,0.111110611902)); +#53160 = CARTESIAN_POINT('',(-2.729372283738E-012,0.117933842356)); +#53161 = CARTESIAN_POINT('',(-2.729372283738E-012,0.12475707281)); +#53162 = CARTESIAN_POINT('',(-2.731148640578E-012,0.131580303264)); +#53163 = CARTESIAN_POINT('',(-2.731148640578E-012,0.138403533718)); +#53164 = CARTESIAN_POINT('',(-2.723155034801E-012,0.145226764172)); +#53165 = CARTESIAN_POINT('',(-2.765787598946E-012,0.152049994626)); +#53166 = CARTESIAN_POINT('',(-2.598810056043E-012,0.15887322508)); +#53167 = CARTESIAN_POINT('',(-3.224087663511E-012,0.165696455534)); +#53168 = CARTESIAN_POINT('',(-1.668887250617E-012,0.170245275837)); +#53169 = CARTESIAN_POINT('',(0.E+000,0.172519685988)); +#53170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53171 = PCURVE('',#52188,#53172); +#53172 = DEFINITIONAL_REPRESENTATION('',(#53173),#53177); +#53173 = LINE('',#53174,#53175); +#53174 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#53175 = VECTOR('',#53176,1.); +#53176 = DIRECTION('',(0.5,-0.866025403784)); +#53177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53178 = ORIENTED_EDGE('',*,*,#53179,.F.); +#53179 = EDGE_CURVE('',#53059,#53135,#53180,.T.); +#53180 = SURFACE_CURVE('',#53181,(#53186,#53215),.PCURVE_S1.); +#53181 = CIRCLE('',#53182,0.2); +#53182 = AXIS2_PLACEMENT_3D('',#53183,#53184,#53185); +#53183 = CARTESIAN_POINT('',(-2.225,1.355,1.446602540378)); +#53184 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#53185 = DIRECTION('',(0.E+000,0.5,0.866025403784)); +#53186 = PCURVE('',#52138,#53187); +#53187 = DEFINITIONAL_REPRESENTATION('',(#53188),#53214); +#53188 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53189,#53190,#53191,#53192, + #53193,#53194,#53195,#53196,#53197,#53198,#53199,#53200,#53201, + #53202,#53203,#53204,#53205,#53206,#53207,#53208,#53209,#53210, + #53211,#53212,#53213),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -63170,93 +66159,93 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#50797 = CARTESIAN_POINT('',(1.570796326795,2.240861599894E-002)); -#50798 = CARTESIAN_POINT('',(1.546996382449,2.240861599894E-002)); -#50799 = CARTESIAN_POINT('',(1.499396493759,2.240861599894E-002)); -#50800 = CARTESIAN_POINT('',(1.427996660722,2.240861599894E-002)); -#50801 = CARTESIAN_POINT('',(1.356596827686,2.240861599894E-002)); -#50802 = CARTESIAN_POINT('',(1.28519699465,2.240861599894E-002)); -#50803 = CARTESIAN_POINT('',(1.213797161613,2.240861599894E-002)); -#50804 = CARTESIAN_POINT('',(1.142397328577,2.240861599894E-002)); -#50805 = CARTESIAN_POINT('',(1.070997495541,2.240861599894E-002)); -#50806 = CARTESIAN_POINT('',(0.999597662504,2.240861599894E-002)); -#50807 = CARTESIAN_POINT('',(0.928197829468,2.240861599894E-002)); -#50808 = CARTESIAN_POINT('',(0.856797996432,2.240861599894E-002)); -#50809 = CARTESIAN_POINT('',(0.785398163396,2.240861599894E-002)); -#50810 = CARTESIAN_POINT('',(0.713998330359,2.240861599894E-002)); -#50811 = CARTESIAN_POINT('',(0.642598497323,2.240861599894E-002)); -#50812 = CARTESIAN_POINT('',(0.571198664287,2.240861599894E-002)); -#50813 = CARTESIAN_POINT('',(0.499798831251,2.240861599894E-002)); -#50814 = CARTESIAN_POINT('',(0.428398998214,2.240861599894E-002)); -#50815 = CARTESIAN_POINT('',(0.356999165178,2.240861599894E-002)); -#50816 = CARTESIAN_POINT('',(0.285599332142,2.240861599894E-002)); -#50817 = CARTESIAN_POINT('',(0.214199499106,2.240861599894E-002)); -#50818 = CARTESIAN_POINT('',(0.14279966607,2.240861599894E-002)); -#50819 = CARTESIAN_POINT('',(7.139983303291E-002,2.240861599894E-002)); -#50820 = CARTESIAN_POINT('',(2.379994434371E-002,2.240861599894E-002)); -#50821 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); -#50822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50823 = PCURVE('',#50725,#50824); -#50824 = DEFINITIONAL_REPRESENTATION('',(#50825),#50833); -#50825 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50826,#50827,#50828,#50829 - ,#50830,#50831,#50832),.UNSPECIFIED.,.F.,.F.) +#53189 = CARTESIAN_POINT('',(1.570796326795,2.240861599894E-002)); +#53190 = CARTESIAN_POINT('',(1.546996382449,2.240861599894E-002)); +#53191 = CARTESIAN_POINT('',(1.499396493759,2.240861599894E-002)); +#53192 = CARTESIAN_POINT('',(1.427996660722,2.240861599894E-002)); +#53193 = CARTESIAN_POINT('',(1.356596827686,2.240861599894E-002)); +#53194 = CARTESIAN_POINT('',(1.28519699465,2.240861599894E-002)); +#53195 = CARTESIAN_POINT('',(1.213797161613,2.240861599894E-002)); +#53196 = CARTESIAN_POINT('',(1.142397328577,2.240861599894E-002)); +#53197 = CARTESIAN_POINT('',(1.070997495541,2.240861599894E-002)); +#53198 = CARTESIAN_POINT('',(0.999597662504,2.240861599894E-002)); +#53199 = CARTESIAN_POINT('',(0.928197829468,2.240861599894E-002)); +#53200 = CARTESIAN_POINT('',(0.856797996432,2.240861599894E-002)); +#53201 = CARTESIAN_POINT('',(0.785398163396,2.240861599894E-002)); +#53202 = CARTESIAN_POINT('',(0.713998330359,2.240861599894E-002)); +#53203 = CARTESIAN_POINT('',(0.642598497323,2.240861599894E-002)); +#53204 = CARTESIAN_POINT('',(0.571198664287,2.240861599894E-002)); +#53205 = CARTESIAN_POINT('',(0.499798831251,2.240861599894E-002)); +#53206 = CARTESIAN_POINT('',(0.428398998214,2.240861599894E-002)); +#53207 = CARTESIAN_POINT('',(0.356999165178,2.240861599894E-002)); +#53208 = CARTESIAN_POINT('',(0.285599332142,2.240861599894E-002)); +#53209 = CARTESIAN_POINT('',(0.214199499106,2.240861599894E-002)); +#53210 = CARTESIAN_POINT('',(0.14279966607,2.240861599894E-002)); +#53211 = CARTESIAN_POINT('',(7.139983303291E-002,2.240861599894E-002)); +#53212 = CARTESIAN_POINT('',(2.379994434371E-002,2.240861599894E-002)); +#53213 = CARTESIAN_POINT('',(0.E+000,2.240861599894E-002)); +#53214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53215 = PCURVE('',#53117,#53216); +#53216 = DEFINITIONAL_REPRESENTATION('',(#53217),#53225); +#53217 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53218,#53219,#53220,#53221 + ,#53222,#53223,#53224),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#50826 = CARTESIAN_POINT('',(9.720002580593E-014,0.5)); -#50827 = CARTESIAN_POINT('',(9.720002580593E-014,0.846410161514)); -#50828 = CARTESIAN_POINT('',(0.3,0.673205080757)); -#50829 = CARTESIAN_POINT('',(0.6,0.5)); -#50830 = CARTESIAN_POINT('',(0.3,0.326794919243)); -#50831 = CARTESIAN_POINT('',(9.744982598647E-014,0.153589838486)); -#50832 = CARTESIAN_POINT('',(9.720002580593E-014,0.5)); -#50833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50834 = ADVANCED_FACE('',(#50835),#50725,.F.); -#50835 = FACE_BOUND('',#50836,.F.); -#50836 = EDGE_LOOP('',(#50837,#50838,#50839,#50889,#50912,#50940)); -#50837 = ORIENTED_EDGE('',*,*,#50787,.F.); -#50838 = ORIENTED_EDGE('',*,*,#50711,.F.); -#50839 = ORIENTED_EDGE('',*,*,#50840,.F.); -#50840 = EDGE_CURVE('',#50841,#50690,#50843,.T.); -#50841 = VERTEX_POINT('',#50842); -#50842 = CARTESIAN_POINT('',(-2.725,1.355,1.446602540378)); -#50843 = SURFACE_CURVE('',#50844,(#50849,#50860),.PCURVE_S1.); -#50844 = CIRCLE('',#50845,0.2); -#50845 = AXIS2_PLACEMENT_3D('',#50846,#50847,#50848); -#50846 = CARTESIAN_POINT('',(-2.525,1.355,1.446602540378)); -#50847 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50848 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#50849 = PCURVE('',#50725,#50850); -#50850 = DEFINITIONAL_REPRESENTATION('',(#50851),#50859); -#50851 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#50852,#50853,#50854,#50855 - ,#50856,#50857,#50858),.UNSPECIFIED.,.F.,.F.) +#53218 = CARTESIAN_POINT('',(9.720002580593E-014,0.5)); +#53219 = CARTESIAN_POINT('',(9.720002580593E-014,0.846410161514)); +#53220 = CARTESIAN_POINT('',(0.3,0.673205080757)); +#53221 = CARTESIAN_POINT('',(0.6,0.5)); +#53222 = CARTESIAN_POINT('',(0.3,0.326794919243)); +#53223 = CARTESIAN_POINT('',(9.744982598647E-014,0.153589838486)); +#53224 = CARTESIAN_POINT('',(9.720002580593E-014,0.5)); +#53225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53226 = ADVANCED_FACE('',(#53227),#53117,.F.); +#53227 = FACE_BOUND('',#53228,.F.); +#53228 = EDGE_LOOP('',(#53229,#53230,#53231,#53281,#53304,#53332)); +#53229 = ORIENTED_EDGE('',*,*,#53179,.F.); +#53230 = ORIENTED_EDGE('',*,*,#53103,.F.); +#53231 = ORIENTED_EDGE('',*,*,#53232,.F.); +#53232 = EDGE_CURVE('',#53233,#53082,#53235,.T.); +#53233 = VERTEX_POINT('',#53234); +#53234 = CARTESIAN_POINT('',(-2.725,1.355,1.446602540378)); +#53235 = SURFACE_CURVE('',#53236,(#53241,#53252),.PCURVE_S1.); +#53236 = CIRCLE('',#53237,0.2); +#53237 = AXIS2_PLACEMENT_3D('',#53238,#53239,#53240); +#53238 = CARTESIAN_POINT('',(-2.525,1.355,1.446602540378)); +#53239 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#53240 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#53241 = PCURVE('',#53117,#53242); +#53242 = DEFINITIONAL_REPRESENTATION('',(#53243),#53251); +#53243 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53244,#53245,#53246,#53247 + ,#53248,#53249,#53250),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#50852 = CARTESIAN_POINT('',(0.2,0.E+000)); -#50853 = CARTESIAN_POINT('',(-0.146410161514,0.E+000)); -#50854 = CARTESIAN_POINT('',(2.679491924321E-002,0.3)); -#50855 = CARTESIAN_POINT('',(0.2,0.6)); -#50856 = CARTESIAN_POINT('',(0.373205080757,0.3)); -#50857 = CARTESIAN_POINT('',(0.546410161514,2.498001805407E-016)); -#50858 = CARTESIAN_POINT('',(0.2,0.E+000)); -#50859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50860 = PCURVE('',#50111,#50861); -#50861 = DEFINITIONAL_REPRESENTATION('',(#50862),#50888); -#50862 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50863,#50864,#50865,#50866, - #50867,#50868,#50869,#50870,#50871,#50872,#50873,#50874,#50875, - #50876,#50877,#50878,#50879,#50880,#50881,#50882,#50883,#50884, - #50885,#50886,#50887),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#53244 = CARTESIAN_POINT('',(0.2,0.E+000)); +#53245 = CARTESIAN_POINT('',(-0.146410161514,0.E+000)); +#53246 = CARTESIAN_POINT('',(2.679491924321E-002,0.3)); +#53247 = CARTESIAN_POINT('',(0.2,0.6)); +#53248 = CARTESIAN_POINT('',(0.373205080757,0.3)); +#53249 = CARTESIAN_POINT('',(0.546410161514,2.498001805407E-016)); +#53250 = CARTESIAN_POINT('',(0.2,0.E+000)); +#53251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53252 = PCURVE('',#52503,#53253); +#53253 = DEFINITIONAL_REPRESENTATION('',(#53254),#53280); +#53254 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53255,#53256,#53257,#53258, + #53259,#53260,#53261,#53262,#53263,#53264,#53265,#53266,#53267, + #53268,#53269,#53270,#53271,#53272,#53273,#53274,#53275,#53276, + #53277,#53278,#53279),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -63264,135 +66253,135 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#50863 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); -#50864 = CARTESIAN_POINT('',(2.379994434424E-002,0.281367061337)); -#50865 = CARTESIAN_POINT('',(7.139983303393E-002,0.281367061337)); -#50866 = CARTESIAN_POINT('',(0.142799666071,0.281367061337)); -#50867 = CARTESIAN_POINT('',(0.214199499107,0.281367061337)); -#50868 = CARTESIAN_POINT('',(0.285599332143,0.281367061337)); -#50869 = CARTESIAN_POINT('',(0.356999165179,0.281367061337)); -#50870 = CARTESIAN_POINT('',(0.428398998215,0.281367061337)); -#50871 = CARTESIAN_POINT('',(0.499798831251,0.281367061337)); -#50872 = CARTESIAN_POINT('',(0.571198664287,0.281367061337)); -#50873 = CARTESIAN_POINT('',(0.642598497324,0.281367061337)); -#50874 = CARTESIAN_POINT('',(0.71399833036,0.281367061337)); -#50875 = CARTESIAN_POINT('',(0.785398163396,0.281367061337)); -#50876 = CARTESIAN_POINT('',(0.856797996432,0.281367061337)); -#50877 = CARTESIAN_POINT('',(0.928197829469,0.281367061337)); -#50878 = CARTESIAN_POINT('',(0.999597662505,0.281367061337)); -#50879 = CARTESIAN_POINT('',(1.070997495541,0.281367061337)); -#50880 = CARTESIAN_POINT('',(1.142397328577,0.281367061337)); -#50881 = CARTESIAN_POINT('',(1.213797161614,0.281367061337)); -#50882 = CARTESIAN_POINT('',(1.28519699465,0.281367061337)); -#50883 = CARTESIAN_POINT('',(1.356596827686,0.281367061337)); -#50884 = CARTESIAN_POINT('',(1.427996660722,0.281367061337)); -#50885 = CARTESIAN_POINT('',(1.499396493759,0.281367061337)); -#50886 = CARTESIAN_POINT('',(1.546996382449,0.281367061337)); -#50887 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); -#50888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50889 = ORIENTED_EDGE('',*,*,#50890,.T.); -#50890 = EDGE_CURVE('',#50841,#50891,#50893,.T.); -#50891 = VERTEX_POINT('',#50892); -#50892 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); -#50893 = SURFACE_CURVE('',#50894,(#50898,#50905),.PCURVE_S1.); -#50894 = LINE('',#50895,#50896); -#50895 = CARTESIAN_POINT('',(-2.725,1.355,1.446602540378)); -#50896 = VECTOR('',#50897,1.); -#50897 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#50898 = PCURVE('',#50725,#50899); -#50899 = DEFINITIONAL_REPRESENTATION('',(#50900),#50904); -#50900 = LINE('',#50901,#50902); -#50901 = CARTESIAN_POINT('',(0.2,0.E+000)); -#50902 = VECTOR('',#50903,1.); -#50903 = DIRECTION('',(1.,0.E+000)); -#50904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50905 = PCURVE('',#50077,#50906); -#50906 = DEFINITIONAL_REPRESENTATION('',(#50907),#50911); -#50907 = LINE('',#50908,#50909); -#50908 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#50909 = VECTOR('',#50910,1.); -#50910 = DIRECTION('',(-0.866025403784,-0.5)); -#50911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50912 = ORIENTED_EDGE('',*,*,#50913,.T.); -#50913 = EDGE_CURVE('',#50891,#50914,#50916,.T.); -#50914 = VERTEX_POINT('',#50915); -#50915 = CARTESIAN_POINT('',(-2.025,1.305,1.36)); -#50916 = SURFACE_CURVE('',#50917,(#50921,#50928),.PCURVE_S1.); -#50917 = LINE('',#50918,#50919); -#50918 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); -#50919 = VECTOR('',#50920,1.); -#50920 = DIRECTION('',(1.,0.E+000,0.E+000)); -#50921 = PCURVE('',#50725,#50922); -#50922 = DEFINITIONAL_REPRESENTATION('',(#50923),#50927); -#50923 = LINE('',#50924,#50925); -#50924 = CARTESIAN_POINT('',(0.3,0.E+000)); -#50925 = VECTOR('',#50926,1.); -#50926 = DIRECTION('',(0.E+000,1.)); -#50927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50928 = PCURVE('',#50929,#50934); -#50929 = PLANE('',#50930); -#50930 = AXIS2_PLACEMENT_3D('',#50931,#50932,#50933); -#50931 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); -#50932 = DIRECTION('',(0.E+000,0.5,0.866025403784)); -#50933 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#50934 = DEFINITIONAL_REPRESENTATION('',(#50935),#50939); -#50935 = LINE('',#50936,#50937); -#50936 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#50937 = VECTOR('',#50938,1.); -#50938 = DIRECTION('',(0.E+000,1.)); -#50939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50940 = ORIENTED_EDGE('',*,*,#50941,.F.); -#50941 = EDGE_CURVE('',#50743,#50914,#50942,.T.); -#50942 = SURFACE_CURVE('',#50943,(#50947,#50954),.PCURVE_S1.); -#50943 = LINE('',#50944,#50945); -#50944 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); -#50945 = VECTOR('',#50946,1.); -#50946 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#50947 = PCURVE('',#50725,#50948); -#50948 = DEFINITIONAL_REPRESENTATION('',(#50949),#50953); -#50949 = LINE('',#50950,#50951); -#50950 = CARTESIAN_POINT('',(0.2,0.7)); -#50951 = VECTOR('',#50952,1.); -#50952 = DIRECTION('',(1.,0.E+000)); -#50953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50954 = PCURVE('',#49796,#50955); -#50955 = DEFINITIONAL_REPRESENTATION('',(#50956),#50960); -#50956 = LINE('',#50957,#50958); -#50957 = CARTESIAN_POINT('',(1.446602540378,1.355)); -#50958 = VECTOR('',#50959,1.); -#50959 = DIRECTION('',(-0.866025403784,-0.5)); -#50960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#50961 = ADVANCED_FACE('',(#50962),#50111,.T.); -#50962 = FACE_BOUND('',#50963,.T.); -#50963 = EDGE_LOOP('',(#50964,#50965,#51008,#51009)); -#50964 = ORIENTED_EDGE('',*,*,#50840,.F.); -#50965 = ORIENTED_EDGE('',*,*,#50966,.F.); -#50966 = EDGE_CURVE('',#50062,#50841,#50967,.T.); -#50967 = SURFACE_CURVE('',#50968,(#50972,#51001),.PCURVE_S1.); -#50968 = LINE('',#50969,#50970); -#50969 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); -#50970 = VECTOR('',#50971,1.); -#50971 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); -#50972 = PCURVE('',#50111,#50973); -#50973 = DEFINITIONAL_REPRESENTATION('',(#50974),#51000); -#50974 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#50975,#50976,#50977,#50978, - #50979,#50980,#50981,#50982,#50983,#50984,#50985,#50986,#50987, - #50988,#50989,#50990,#50991,#50992,#50993,#50994,#50995,#50996, - #50997,#50998,#50999),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#53255 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); +#53256 = CARTESIAN_POINT('',(2.379994434424E-002,0.281367061337)); +#53257 = CARTESIAN_POINT('',(7.139983303393E-002,0.281367061337)); +#53258 = CARTESIAN_POINT('',(0.142799666071,0.281367061337)); +#53259 = CARTESIAN_POINT('',(0.214199499107,0.281367061337)); +#53260 = CARTESIAN_POINT('',(0.285599332143,0.281367061337)); +#53261 = CARTESIAN_POINT('',(0.356999165179,0.281367061337)); +#53262 = CARTESIAN_POINT('',(0.428398998215,0.281367061337)); +#53263 = CARTESIAN_POINT('',(0.499798831251,0.281367061337)); +#53264 = CARTESIAN_POINT('',(0.571198664287,0.281367061337)); +#53265 = CARTESIAN_POINT('',(0.642598497324,0.281367061337)); +#53266 = CARTESIAN_POINT('',(0.71399833036,0.281367061337)); +#53267 = CARTESIAN_POINT('',(0.785398163396,0.281367061337)); +#53268 = CARTESIAN_POINT('',(0.856797996432,0.281367061337)); +#53269 = CARTESIAN_POINT('',(0.928197829469,0.281367061337)); +#53270 = CARTESIAN_POINT('',(0.999597662505,0.281367061337)); +#53271 = CARTESIAN_POINT('',(1.070997495541,0.281367061337)); +#53272 = CARTESIAN_POINT('',(1.142397328577,0.281367061337)); +#53273 = CARTESIAN_POINT('',(1.213797161614,0.281367061337)); +#53274 = CARTESIAN_POINT('',(1.28519699465,0.281367061337)); +#53275 = CARTESIAN_POINT('',(1.356596827686,0.281367061337)); +#53276 = CARTESIAN_POINT('',(1.427996660722,0.281367061337)); +#53277 = CARTESIAN_POINT('',(1.499396493759,0.281367061337)); +#53278 = CARTESIAN_POINT('',(1.546996382449,0.281367061337)); +#53279 = CARTESIAN_POINT('',(1.570796326795,0.281367061337)); +#53280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53281 = ORIENTED_EDGE('',*,*,#53282,.T.); +#53282 = EDGE_CURVE('',#53233,#53283,#53285,.T.); +#53283 = VERTEX_POINT('',#53284); +#53284 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); +#53285 = SURFACE_CURVE('',#53286,(#53290,#53297),.PCURVE_S1.); +#53286 = LINE('',#53287,#53288); +#53287 = CARTESIAN_POINT('',(-2.725,1.355,1.446602540378)); +#53288 = VECTOR('',#53289,1.); +#53289 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#53290 = PCURVE('',#53117,#53291); +#53291 = DEFINITIONAL_REPRESENTATION('',(#53292),#53296); +#53292 = LINE('',#53293,#53294); +#53293 = CARTESIAN_POINT('',(0.2,0.E+000)); +#53294 = VECTOR('',#53295,1.); +#53295 = DIRECTION('',(1.,0.E+000)); +#53296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53297 = PCURVE('',#52469,#53298); +#53298 = DEFINITIONAL_REPRESENTATION('',(#53299),#53303); +#53299 = LINE('',#53300,#53301); +#53300 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#53301 = VECTOR('',#53302,1.); +#53302 = DIRECTION('',(-0.866025403784,-0.5)); +#53303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53304 = ORIENTED_EDGE('',*,*,#53305,.T.); +#53305 = EDGE_CURVE('',#53283,#53306,#53308,.T.); +#53306 = VERTEX_POINT('',#53307); +#53307 = CARTESIAN_POINT('',(-2.025,1.305,1.36)); +#53308 = SURFACE_CURVE('',#53309,(#53313,#53320),.PCURVE_S1.); +#53309 = LINE('',#53310,#53311); +#53310 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); +#53311 = VECTOR('',#53312,1.); +#53312 = DIRECTION('',(1.,0.E+000,0.E+000)); +#53313 = PCURVE('',#53117,#53314); +#53314 = DEFINITIONAL_REPRESENTATION('',(#53315),#53319); +#53315 = LINE('',#53316,#53317); +#53316 = CARTESIAN_POINT('',(0.3,0.E+000)); +#53317 = VECTOR('',#53318,1.); +#53318 = DIRECTION('',(0.E+000,1.)); +#53319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53320 = PCURVE('',#53321,#53326); +#53321 = PLANE('',#53322); +#53322 = AXIS2_PLACEMENT_3D('',#53323,#53324,#53325); +#53323 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); +#53324 = DIRECTION('',(0.E+000,0.5,0.866025403784)); +#53325 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53326 = DEFINITIONAL_REPRESENTATION('',(#53327),#53331); +#53327 = LINE('',#53328,#53329); +#53328 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53329 = VECTOR('',#53330,1.); +#53330 = DIRECTION('',(0.E+000,1.)); +#53331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53332 = ORIENTED_EDGE('',*,*,#53333,.F.); +#53333 = EDGE_CURVE('',#53135,#53306,#53334,.T.); +#53334 = SURFACE_CURVE('',#53335,(#53339,#53346),.PCURVE_S1.); +#53335 = LINE('',#53336,#53337); +#53336 = CARTESIAN_POINT('',(-2.025,1.355,1.446602540378)); +#53337 = VECTOR('',#53338,1.); +#53338 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#53339 = PCURVE('',#53117,#53340); +#53340 = DEFINITIONAL_REPRESENTATION('',(#53341),#53345); +#53341 = LINE('',#53342,#53343); +#53342 = CARTESIAN_POINT('',(0.2,0.7)); +#53343 = VECTOR('',#53344,1.); +#53344 = DIRECTION('',(1.,0.E+000)); +#53345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53346 = PCURVE('',#52188,#53347); +#53347 = DEFINITIONAL_REPRESENTATION('',(#53348),#53352); +#53348 = LINE('',#53349,#53350); +#53349 = CARTESIAN_POINT('',(1.446602540378,1.355)); +#53350 = VECTOR('',#53351,1.); +#53351 = DIRECTION('',(-0.866025403784,-0.5)); +#53352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53353 = ADVANCED_FACE('',(#53354),#52503,.T.); +#53354 = FACE_BOUND('',#53355,.T.); +#53355 = EDGE_LOOP('',(#53356,#53357,#53400,#53401)); +#53356 = ORIENTED_EDGE('',*,*,#53232,.F.); +#53357 = ORIENTED_EDGE('',*,*,#53358,.F.); +#53358 = EDGE_CURVE('',#52454,#53233,#53359,.T.); +#53359 = SURFACE_CURVE('',#53360,(#53364,#53393),.PCURVE_S1.); +#53360 = LINE('',#53361,#53362); +#53361 = CARTESIAN_POINT('',(-2.725,1.225,1.521658075373)); +#53362 = VECTOR('',#53363,1.); +#53363 = DIRECTION('',(0.E+000,0.866025403784,-0.5)); +#53364 = PCURVE('',#52503,#53365); +#53365 = DEFINITIONAL_REPRESENTATION('',(#53366),#53392); +#53366 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53367,#53368,#53369,#53370, + #53371,#53372,#53373,#53374,#53375,#53376,#53377,#53378,#53379, + #53380,#53381,#53382,#53383,#53384,#53385,#53386,#53387,#53388, + #53389,#53390,#53391),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,6.823230454067E-003, 1.364646090813E-002,2.04696913622E-002,2.729292181627E-002, 3.411615227034E-002,4.09393827244E-002,4.776261317847E-002, @@ -63401,1676 +66390,1676 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 9.552522635694E-002,0.102348456811,0.109171687265,0.115994917719, 0.122818148173,0.129641378627,0.136464609081,0.143287839535, 0.150111069989),.QUASI_UNIFORM_KNOTS.); -#50975 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); -#50976 = CARTESIAN_POINT('',(-3.277378368693E-013,0.133530401499)); -#50977 = CARTESIAN_POINT('',(-6.332712132462E-013,0.138079221802)); -#50978 = CARTESIAN_POINT('',(-5.107025913276E-013,0.144902452256)); -#50979 = CARTESIAN_POINT('',(-5.462297281156E-013,0.15172568271)); -#50980 = CARTESIAN_POINT('',(-5.337952302398E-013,0.158548913164)); -#50981 = CARTESIAN_POINT('',(-5.39124300758E-013,0.165372143618)); -#50982 = CARTESIAN_POINT('',(-5.373479439186E-013,0.172195374072)); -#50983 = CARTESIAN_POINT('',(-5.355715870792E-013,0.179018604526)); -#50984 = CARTESIAN_POINT('',(-5.373479439186E-013,0.18584183498)); -#50985 = CARTESIAN_POINT('',(-5.355715870792E-013,0.192665065434)); -#50986 = CARTESIAN_POINT('',(-5.355715870792E-013,0.199488295888)); -#50987 = CARTESIAN_POINT('',(-5.373479439186E-013,0.206311526342)); -#50988 = CARTESIAN_POINT('',(-5.373479439186E-013,0.213134756797)); -#50989 = CARTESIAN_POINT('',(-5.355715870792E-013,0.219957987251)); -#50990 = CARTESIAN_POINT('',(-5.364597654989E-013,0.226781217705)); -#50991 = CARTESIAN_POINT('',(-5.373479439186E-013,0.233604448159)); -#50992 = CARTESIAN_POINT('',(-5.355715870792E-013,0.240427678613)); -#50993 = CARTESIAN_POINT('',(-5.373479439186E-013,0.247250909067)); -#50994 = CARTESIAN_POINT('',(-5.346834086595E-013,0.254074139521)); -#50995 = CARTESIAN_POINT('',(-5.426770144368E-013,0.260897369975)); -#50996 = CARTESIAN_POINT('',(-5.12478948167E-013,0.267720600429)); -#50997 = CARTESIAN_POINT('',(-6.332712132462E-013,0.274543830883)); -#50998 = CARTESIAN_POINT('',(-3.277378368693E-013,0.279092651186)); -#50999 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); -#51000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51001 = PCURVE('',#50077,#51002); -#51002 = DEFINITIONAL_REPRESENTATION('',(#51003),#51007); -#51003 = LINE('',#51004,#51005); -#51004 = CARTESIAN_POINT('',(1.521658075373,1.225)); -#51005 = VECTOR('',#51006,1.); -#51006 = DIRECTION('',(-0.5,0.866025403784)); -#51007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51008 = ORIENTED_EDGE('',*,*,#50089,.F.); -#51009 = ORIENTED_EDGE('',*,*,#50689,.T.); -#51010 = ADVANCED_FACE('',(#51011),#50077,.T.); -#51011 = FACE_BOUND('',#51012,.F.); -#51012 = EDGE_LOOP('',(#51013,#51014,#51015,#51036)); -#51013 = ORIENTED_EDGE('',*,*,#50966,.F.); -#51014 = ORIENTED_EDGE('',*,*,#50061,.F.); -#51015 = ORIENTED_EDGE('',*,*,#51016,.F.); -#51016 = EDGE_CURVE('',#50891,#50039,#51017,.T.); -#51017 = SURFACE_CURVE('',#51018,(#51022,#51029),.PCURVE_S1.); -#51018 = LINE('',#51019,#51020); -#51019 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); -#51020 = VECTOR('',#51021,1.); -#51021 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#51022 = PCURVE('',#50077,#51023); -#51023 = DEFINITIONAL_REPRESENTATION('',(#51024),#51028); -#51024 = LINE('',#51025,#51026); -#51025 = CARTESIAN_POINT('',(1.36,1.305)); -#51026 = VECTOR('',#51027,1.); -#51027 = DIRECTION('',(0.5,-0.866025403784)); -#51028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51029 = PCURVE('',#50929,#51030); -#51030 = DEFINITIONAL_REPRESENTATION('',(#51031),#51035); -#51031 = LINE('',#51032,#51033); -#51032 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51033 = VECTOR('',#51034,1.); -#51034 = DIRECTION('',(1.,0.E+000)); -#51035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51036 = ORIENTED_EDGE('',*,*,#50890,.F.); -#51037 = ADVANCED_FACE('',(#51038),#50929,.F.); -#51038 = FACE_BOUND('',#51039,.F.); -#51039 = EDGE_LOOP('',(#51040,#51063,#51085,#51106,#51127,#51128)); -#51040 = ORIENTED_EDGE('',*,*,#51041,.T.); -#51041 = EDGE_CURVE('',#50039,#51042,#51044,.T.); -#51042 = VERTEX_POINT('',#51043); -#51043 = CARTESIAN_POINT('',(-2.725,1.075,1.492790561914)); -#51044 = SURFACE_CURVE('',#51045,(#51049,#51056),.PCURVE_S1.); -#51045 = LINE('',#51046,#51047); -#51046 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); -#51047 = VECTOR('',#51048,1.); -#51048 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#51049 = PCURVE('',#50929,#51050); -#51050 = DEFINITIONAL_REPRESENTATION('',(#51051),#51055); -#51051 = LINE('',#51052,#51053); -#51052 = CARTESIAN_POINT('',(9.237604307025E-002,0.E+000)); -#51053 = VECTOR('',#51054,1.); -#51054 = DIRECTION('',(1.,0.E+000)); -#51055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51056 = PCURVE('',#48088,#51057); -#51057 = DEFINITIONAL_REPRESENTATION('',(#51058),#51062); -#51058 = LINE('',#51059,#51060); -#51059 = CARTESIAN_POINT('',(5.6188021535E-002,0.E+000)); -#51060 = VECTOR('',#51061,1.); -#51061 = DIRECTION('',(0.5,-0.866025403784)); -#51062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51063 = ORIENTED_EDGE('',*,*,#51064,.T.); -#51064 = EDGE_CURVE('',#51042,#51065,#51067,.T.); -#51065 = VERTEX_POINT('',#51066); -#51066 = CARTESIAN_POINT('',(-2.025,1.075,1.492790561914)); -#51067 = SURFACE_CURVE('',#51068,(#51072,#51079),.PCURVE_S1.); -#51068 = LINE('',#51069,#51070); -#51069 = CARTESIAN_POINT('',(-2.725,1.075,1.492790561914)); -#51070 = VECTOR('',#51071,1.); -#51071 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51072 = PCURVE('',#50929,#51073); -#51073 = DEFINITIONAL_REPRESENTATION('',(#51074),#51078); -#51074 = LINE('',#51075,#51076); -#51075 = CARTESIAN_POINT('',(0.265581123827,0.E+000)); -#51076 = VECTOR('',#51077,1.); -#51077 = DIRECTION('',(0.E+000,1.)); -#51078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51079 = PCURVE('',#48061,#51080); -#51080 = DEFINITIONAL_REPRESENTATION('',(#51081),#51084); -#51081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51082,#51083),.UNSPECIFIED., +#53367 = CARTESIAN_POINT('',(0.E+000,0.131255991348)); +#53368 = CARTESIAN_POINT('',(-3.277378368693E-013,0.133530401499)); +#53369 = CARTESIAN_POINT('',(-6.332712132462E-013,0.138079221802)); +#53370 = CARTESIAN_POINT('',(-5.107025913276E-013,0.144902452256)); +#53371 = CARTESIAN_POINT('',(-5.462297281156E-013,0.15172568271)); +#53372 = CARTESIAN_POINT('',(-5.337952302398E-013,0.158548913164)); +#53373 = CARTESIAN_POINT('',(-5.39124300758E-013,0.165372143618)); +#53374 = CARTESIAN_POINT('',(-5.373479439186E-013,0.172195374072)); +#53375 = CARTESIAN_POINT('',(-5.355715870792E-013,0.179018604526)); +#53376 = CARTESIAN_POINT('',(-5.373479439186E-013,0.18584183498)); +#53377 = CARTESIAN_POINT('',(-5.355715870792E-013,0.192665065434)); +#53378 = CARTESIAN_POINT('',(-5.355715870792E-013,0.199488295888)); +#53379 = CARTESIAN_POINT('',(-5.373479439186E-013,0.206311526342)); +#53380 = CARTESIAN_POINT('',(-5.373479439186E-013,0.213134756797)); +#53381 = CARTESIAN_POINT('',(-5.355715870792E-013,0.219957987251)); +#53382 = CARTESIAN_POINT('',(-5.364597654989E-013,0.226781217705)); +#53383 = CARTESIAN_POINT('',(-5.373479439186E-013,0.233604448159)); +#53384 = CARTESIAN_POINT('',(-5.355715870792E-013,0.240427678613)); +#53385 = CARTESIAN_POINT('',(-5.373479439186E-013,0.247250909067)); +#53386 = CARTESIAN_POINT('',(-5.346834086595E-013,0.254074139521)); +#53387 = CARTESIAN_POINT('',(-5.426770144368E-013,0.260897369975)); +#53388 = CARTESIAN_POINT('',(-5.12478948167E-013,0.267720600429)); +#53389 = CARTESIAN_POINT('',(-6.332712132462E-013,0.274543830883)); +#53390 = CARTESIAN_POINT('',(-3.277378368693E-013,0.279092651186)); +#53391 = CARTESIAN_POINT('',(0.E+000,0.281367061337)); +#53392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53393 = PCURVE('',#52469,#53394); +#53394 = DEFINITIONAL_REPRESENTATION('',(#53395),#53399); +#53395 = LINE('',#53396,#53397); +#53396 = CARTESIAN_POINT('',(1.521658075373,1.225)); +#53397 = VECTOR('',#53398,1.); +#53398 = DIRECTION('',(-0.5,0.866025403784)); +#53399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53400 = ORIENTED_EDGE('',*,*,#52481,.F.); +#53401 = ORIENTED_EDGE('',*,*,#53081,.T.); +#53402 = ADVANCED_FACE('',(#53403),#52469,.T.); +#53403 = FACE_BOUND('',#53404,.F.); +#53404 = EDGE_LOOP('',(#53405,#53406,#53407,#53428)); +#53405 = ORIENTED_EDGE('',*,*,#53358,.F.); +#53406 = ORIENTED_EDGE('',*,*,#52453,.F.); +#53407 = ORIENTED_EDGE('',*,*,#53408,.F.); +#53408 = EDGE_CURVE('',#53283,#52431,#53409,.T.); +#53409 = SURFACE_CURVE('',#53410,(#53414,#53421),.PCURVE_S1.); +#53410 = LINE('',#53411,#53412); +#53411 = CARTESIAN_POINT('',(-2.725,1.305,1.36)); +#53412 = VECTOR('',#53413,1.); +#53413 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53414 = PCURVE('',#52469,#53415); +#53415 = DEFINITIONAL_REPRESENTATION('',(#53416),#53420); +#53416 = LINE('',#53417,#53418); +#53417 = CARTESIAN_POINT('',(1.36,1.305)); +#53418 = VECTOR('',#53419,1.); +#53419 = DIRECTION('',(0.5,-0.866025403784)); +#53420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53421 = PCURVE('',#53321,#53422); +#53422 = DEFINITIONAL_REPRESENTATION('',(#53423),#53427); +#53423 = LINE('',#53424,#53425); +#53424 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53425 = VECTOR('',#53426,1.); +#53426 = DIRECTION('',(1.,0.E+000)); +#53427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53428 = ORIENTED_EDGE('',*,*,#53282,.F.); +#53429 = ADVANCED_FACE('',(#53430),#53321,.F.); +#53430 = FACE_BOUND('',#53431,.F.); +#53431 = EDGE_LOOP('',(#53432,#53455,#53477,#53498,#53519,#53520)); +#53432 = ORIENTED_EDGE('',*,*,#53433,.T.); +#53433 = EDGE_CURVE('',#52431,#53434,#53436,.T.); +#53434 = VERTEX_POINT('',#53435); +#53435 = CARTESIAN_POINT('',(-2.725,1.075,1.492790561914)); +#53436 = SURFACE_CURVE('',#53437,(#53441,#53448),.PCURVE_S1.); +#53437 = LINE('',#53438,#53439); +#53438 = CARTESIAN_POINT('',(-2.725,1.225,1.406188021535)); +#53439 = VECTOR('',#53440,1.); +#53440 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53441 = PCURVE('',#53321,#53442); +#53442 = DEFINITIONAL_REPRESENTATION('',(#53443),#53447); +#53443 = LINE('',#53444,#53445); +#53444 = CARTESIAN_POINT('',(9.237604307025E-002,0.E+000)); +#53445 = VECTOR('',#53446,1.); +#53446 = DIRECTION('',(1.,0.E+000)); +#53447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53448 = PCURVE('',#50480,#53449); +#53449 = DEFINITIONAL_REPRESENTATION('',(#53450),#53454); +#53450 = LINE('',#53451,#53452); +#53451 = CARTESIAN_POINT('',(5.6188021535E-002,0.E+000)); +#53452 = VECTOR('',#53453,1.); +#53453 = DIRECTION('',(0.5,-0.866025403784)); +#53454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53455 = ORIENTED_EDGE('',*,*,#53456,.T.); +#53456 = EDGE_CURVE('',#53434,#53457,#53459,.T.); +#53457 = VERTEX_POINT('',#53458); +#53458 = CARTESIAN_POINT('',(-2.025,1.075,1.492790561914)); +#53459 = SURFACE_CURVE('',#53460,(#53464,#53471),.PCURVE_S1.); +#53460 = LINE('',#53461,#53462); +#53461 = CARTESIAN_POINT('',(-2.725,1.075,1.492790561914)); +#53462 = VECTOR('',#53463,1.); +#53463 = DIRECTION('',(1.,0.E+000,0.E+000)); +#53464 = PCURVE('',#53321,#53465); +#53465 = DEFINITIONAL_REPRESENTATION('',(#53466),#53470); +#53466 = LINE('',#53467,#53468); +#53467 = CARTESIAN_POINT('',(0.265581123827,0.E+000)); +#53468 = VECTOR('',#53469,1.); +#53469 = DIRECTION('',(0.E+000,1.)); +#53470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53471 = PCURVE('',#50453,#53472); +#53472 = DEFINITIONAL_REPRESENTATION('',(#53473),#53476); +#53473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53474,#53475),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#51082 = CARTESIAN_POINT('',(3.665191429189,0.E+000)); -#51083 = CARTESIAN_POINT('',(3.665191429189,-0.7)); -#51084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51085 = ORIENTED_EDGE('',*,*,#51086,.F.); -#51086 = EDGE_CURVE('',#49781,#51065,#51087,.T.); -#51087 = SURFACE_CURVE('',#51088,(#51092,#51099),.PCURVE_S1.); -#51088 = LINE('',#51089,#51090); -#51089 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); -#51090 = VECTOR('',#51091,1.); -#51091 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#51092 = PCURVE('',#50929,#51093); -#51093 = DEFINITIONAL_REPRESENTATION('',(#51094),#51098); -#51094 = LINE('',#51095,#51096); -#51095 = CARTESIAN_POINT('',(9.237604307025E-002,0.7)); -#51096 = VECTOR('',#51097,1.); -#51097 = DIRECTION('',(1.,0.E+000)); -#51098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51099 = PCURVE('',#48033,#51100); -#51100 = DEFINITIONAL_REPRESENTATION('',(#51101),#51105); -#51101 = LINE('',#51102,#51103); -#51102 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); -#51103 = VECTOR('',#51104,1.); -#51104 = DIRECTION('',(-0.5,-0.866025403784)); -#51105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51106 = ORIENTED_EDGE('',*,*,#51107,.F.); -#51107 = EDGE_CURVE('',#50914,#49781,#51108,.T.); -#51108 = SURFACE_CURVE('',#51109,(#51113,#51120),.PCURVE_S1.); -#51109 = LINE('',#51110,#51111); -#51110 = CARTESIAN_POINT('',(-2.025,1.305,1.36)); -#51111 = VECTOR('',#51112,1.); -#51112 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); -#51113 = PCURVE('',#50929,#51114); -#51114 = DEFINITIONAL_REPRESENTATION('',(#51115),#51119); -#51115 = LINE('',#51116,#51117); -#51116 = CARTESIAN_POINT('',(0.E+000,0.7)); -#51117 = VECTOR('',#51118,1.); -#51118 = DIRECTION('',(1.,0.E+000)); -#51119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51120 = PCURVE('',#49796,#51121); -#51121 = DEFINITIONAL_REPRESENTATION('',(#51122),#51126); -#51122 = LINE('',#51123,#51124); -#51123 = CARTESIAN_POINT('',(1.36,1.305)); -#51124 = VECTOR('',#51125,1.); -#51125 = DIRECTION('',(0.5,-0.866025403784)); -#51126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51127 = ORIENTED_EDGE('',*,*,#50913,.F.); -#51128 = ORIENTED_EDGE('',*,*,#51016,.T.); -#51129 = ADVANCED_FACE('',(#51130),#48088,.F.); -#51130 = FACE_BOUND('',#51131,.F.); -#51131 = EDGE_LOOP('',(#51132,#51153,#51154,#51155,#51176)); -#51132 = ORIENTED_EDGE('',*,*,#51133,.F.); -#51133 = EDGE_CURVE('',#51042,#48046,#51134,.T.); -#51134 = SURFACE_CURVE('',#51135,(#51140,#51147),.PCURVE_S1.); -#51135 = CIRCLE('',#51136,0.3); -#51136 = AXIS2_PLACEMENT_3D('',#51137,#51138,#51139); -#51137 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); -#51138 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51139 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#51140 = PCURVE('',#48088,#51141); -#51141 = DEFINITIONAL_REPRESENTATION('',(#51142),#51146); -#51142 = CIRCLE('',#51143,0.3); -#51143 = AXIS2_PLACEMENT_2D('',#51144,#51145); -#51144 = CARTESIAN_POINT('',(0.402598183049,0.E+000)); -#51145 = DIRECTION('',(-0.866025403784,-0.5)); -#51146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51147 = PCURVE('',#48061,#51148); -#51148 = DEFINITIONAL_REPRESENTATION('',(#51149),#51152); -#51149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51150,#51151),.UNSPECIFIED., +#53474 = CARTESIAN_POINT('',(3.665191429189,0.E+000)); +#53475 = CARTESIAN_POINT('',(3.665191429189,-0.7)); +#53476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53477 = ORIENTED_EDGE('',*,*,#53478,.F.); +#53478 = EDGE_CURVE('',#52173,#53457,#53479,.T.); +#53479 = SURFACE_CURVE('',#53480,(#53484,#53491),.PCURVE_S1.); +#53480 = LINE('',#53481,#53482); +#53481 = CARTESIAN_POINT('',(-2.025,1.225,1.406188021535)); +#53482 = VECTOR('',#53483,1.); +#53483 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53484 = PCURVE('',#53321,#53485); +#53485 = DEFINITIONAL_REPRESENTATION('',(#53486),#53490); +#53486 = LINE('',#53487,#53488); +#53487 = CARTESIAN_POINT('',(9.237604307025E-002,0.7)); +#53488 = VECTOR('',#53489,1.); +#53489 = DIRECTION('',(1.,0.E+000)); +#53490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53491 = PCURVE('',#50425,#53492); +#53492 = DEFINITIONAL_REPRESENTATION('',(#53493),#53497); +#53493 = LINE('',#53494,#53495); +#53494 = CARTESIAN_POINT('',(0.373811978465,0.E+000)); +#53495 = VECTOR('',#53496,1.); +#53496 = DIRECTION('',(-0.5,-0.866025403784)); +#53497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53498 = ORIENTED_EDGE('',*,*,#53499,.F.); +#53499 = EDGE_CURVE('',#53306,#52173,#53500,.T.); +#53500 = SURFACE_CURVE('',#53501,(#53505,#53512),.PCURVE_S1.); +#53501 = LINE('',#53502,#53503); +#53502 = CARTESIAN_POINT('',(-2.025,1.305,1.36)); +#53503 = VECTOR('',#53504,1.); +#53504 = DIRECTION('',(0.E+000,-0.866025403784,0.5)); +#53505 = PCURVE('',#53321,#53506); +#53506 = DEFINITIONAL_REPRESENTATION('',(#53507),#53511); +#53507 = LINE('',#53508,#53509); +#53508 = CARTESIAN_POINT('',(0.E+000,0.7)); +#53509 = VECTOR('',#53510,1.); +#53510 = DIRECTION('',(1.,0.E+000)); +#53511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53512 = PCURVE('',#52188,#53513); +#53513 = DEFINITIONAL_REPRESENTATION('',(#53514),#53518); +#53514 = LINE('',#53515,#53516); +#53515 = CARTESIAN_POINT('',(1.36,1.305)); +#53516 = VECTOR('',#53517,1.); +#53517 = DIRECTION('',(0.5,-0.866025403784)); +#53518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53519 = ORIENTED_EDGE('',*,*,#53305,.F.); +#53520 = ORIENTED_EDGE('',*,*,#53408,.T.); +#53521 = ADVANCED_FACE('',(#53522),#50480,.F.); +#53522 = FACE_BOUND('',#53523,.F.); +#53523 = EDGE_LOOP('',(#53524,#53545,#53546,#53547,#53568)); +#53524 = ORIENTED_EDGE('',*,*,#53525,.F.); +#53525 = EDGE_CURVE('',#53434,#50438,#53526,.T.); +#53526 = SURFACE_CURVE('',#53527,(#53532,#53539),.PCURVE_S1.); +#53527 = CIRCLE('',#53528,0.3); +#53528 = AXIS2_PLACEMENT_3D('',#53529,#53530,#53531); +#53529 = CARTESIAN_POINT('',(-2.725,1.225,1.752598183049)); +#53530 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#53531 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#53532 = PCURVE('',#50480,#53533); +#53533 = DEFINITIONAL_REPRESENTATION('',(#53534),#53538); +#53534 = CIRCLE('',#53535,0.3); +#53535 = AXIS2_PLACEMENT_2D('',#53536,#53537); +#53536 = CARTESIAN_POINT('',(0.402598183049,0.E+000)); +#53537 = DIRECTION('',(-0.866025403784,-0.5)); +#53538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53539 = PCURVE('',#50453,#53540); +#53540 = DEFINITIONAL_REPRESENTATION('',(#53541),#53544); +#53541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53542,#53543),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); -#51150 = CARTESIAN_POINT('',(3.665191429188,0.E+000)); -#51151 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#51152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51153 = ORIENTED_EDGE('',*,*,#51041,.F.); -#51154 = ORIENTED_EDGE('',*,*,#50038,.F.); -#51155 = ORIENTED_EDGE('',*,*,#51156,.T.); -#51156 = EDGE_CURVE('',#50016,#48073,#51157,.T.); -#51157 = SURFACE_CURVE('',#51158,(#51162,#51169),.PCURVE_S1.); -#51158 = LINE('',#51159,#51160); -#51159 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); -#51160 = VECTOR('',#51161,1.); -#51161 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51162 = PCURVE('',#48088,#51163); -#51163 = DEFINITIONAL_REPRESENTATION('',(#51164),#51168); -#51164 = LINE('',#51165,#51166); -#51165 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51166 = VECTOR('',#51167,1.); -#51167 = DIRECTION('',(0.E+000,-1.)); -#51168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51169 = PCURVE('',#48116,#51170); -#51170 = DEFINITIONAL_REPRESENTATION('',(#51171),#51175); -#51171 = LINE('',#51172,#51173); -#51172 = CARTESIAN_POINT('',(0.125,0.E+000)); -#51173 = VECTOR('',#51174,1.); -#51174 = DIRECTION('',(0.E+000,-1.)); -#51175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51176 = ORIENTED_EDGE('',*,*,#48072,.T.); -#51177 = ADVANCED_FACE('',(#51178),#48061,.T.); -#51178 = FACE_BOUND('',#51179,.T.); -#51179 = EDGE_LOOP('',(#51180,#51181,#51182,#51207)); -#51180 = ORIENTED_EDGE('',*,*,#51133,.F.); -#51181 = ORIENTED_EDGE('',*,*,#51064,.T.); -#51182 = ORIENTED_EDGE('',*,*,#51183,.T.); -#51183 = EDGE_CURVE('',#51065,#48016,#51184,.T.); -#51184 = SURFACE_CURVE('',#51185,(#51190,#51196),.PCURVE_S1.); -#51185 = CIRCLE('',#51186,0.3); -#51186 = AXIS2_PLACEMENT_3D('',#51187,#51188,#51189); -#51187 = CARTESIAN_POINT('',(-2.025,1.225,1.752598183049)); -#51188 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51189 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); -#51190 = PCURVE('',#48061,#51191); -#51191 = DEFINITIONAL_REPRESENTATION('',(#51192),#51195); -#51192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51193,#51194),.UNSPECIFIED., +#53542 = CARTESIAN_POINT('',(3.665191429188,0.E+000)); +#53543 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#53544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53545 = ORIENTED_EDGE('',*,*,#53433,.F.); +#53546 = ORIENTED_EDGE('',*,*,#52430,.F.); +#53547 = ORIENTED_EDGE('',*,*,#53548,.T.); +#53548 = EDGE_CURVE('',#52408,#50465,#53549,.T.); +#53549 = SURFACE_CURVE('',#53550,(#53554,#53561),.PCURVE_S1.); +#53550 = LINE('',#53551,#53552); +#53551 = CARTESIAN_POINT('',(-2.725,1.225,1.35)); +#53552 = VECTOR('',#53553,1.); +#53553 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53554 = PCURVE('',#50480,#53555); +#53555 = DEFINITIONAL_REPRESENTATION('',(#53556),#53560); +#53556 = LINE('',#53557,#53558); +#53557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53558 = VECTOR('',#53559,1.); +#53559 = DIRECTION('',(0.E+000,-1.)); +#53560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53561 = PCURVE('',#50508,#53562); +#53562 = DEFINITIONAL_REPRESENTATION('',(#53563),#53567); +#53563 = LINE('',#53564,#53565); +#53564 = CARTESIAN_POINT('',(0.125,0.E+000)); +#53565 = VECTOR('',#53566,1.); +#53566 = DIRECTION('',(0.E+000,-1.)); +#53567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53568 = ORIENTED_EDGE('',*,*,#50464,.T.); +#53569 = ADVANCED_FACE('',(#53570),#50453,.T.); +#53570 = FACE_BOUND('',#53571,.T.); +#53571 = EDGE_LOOP('',(#53572,#53573,#53574,#53599)); +#53572 = ORIENTED_EDGE('',*,*,#53525,.F.); +#53573 = ORIENTED_EDGE('',*,*,#53456,.T.); +#53574 = ORIENTED_EDGE('',*,*,#53575,.T.); +#53575 = EDGE_CURVE('',#53457,#50408,#53576,.T.); +#53576 = SURFACE_CURVE('',#53577,(#53582,#53588),.PCURVE_S1.); +#53577 = CIRCLE('',#53578,0.3); +#53578 = AXIS2_PLACEMENT_3D('',#53579,#53580,#53581); +#53579 = CARTESIAN_POINT('',(-2.025,1.225,1.752598183049)); +#53580 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#53581 = DIRECTION('',(0.E+000,-0.5,-0.866025403784)); +#53582 = PCURVE('',#50453,#53583); +#53583 = DEFINITIONAL_REPRESENTATION('',(#53584),#53587); +#53584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53585,#53586),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.047197551196),.PIECEWISE_BEZIER_KNOTS.); -#51193 = CARTESIAN_POINT('',(3.665191429188,-0.7)); -#51194 = CARTESIAN_POINT('',(4.712388980385,-0.7)); -#51195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#53585 = CARTESIAN_POINT('',(3.665191429188,-0.7)); +#53586 = CARTESIAN_POINT('',(4.712388980385,-0.7)); +#53587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#51196 = PCURVE('',#48033,#51197); -#51197 = DEFINITIONAL_REPRESENTATION('',(#51198),#51206); -#51198 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#51199,#51200,#51201,#51202 - ,#51203,#51204,#51205),.UNSPECIFIED.,.T.,.F.) +#53588 = PCURVE('',#50425,#53589); +#53589 = DEFINITIONAL_REPRESENTATION('',(#53590),#53598); +#53590 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53591,#53592,#53593,#53594 + ,#53595,#53596,#53597),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#51199 = CARTESIAN_POINT('',(0.287209438086,-0.15)); -#51200 = CARTESIAN_POINT('',(2.740181695085E-002,-0.6)); -#51201 = CARTESIAN_POINT('',(-0.232405804184,-0.15)); -#51202 = CARTESIAN_POINT('',(-0.49221342532,0.3)); -#51203 = CARTESIAN_POINT('',(2.740181695107E-002,0.3)); -#51204 = CARTESIAN_POINT('',(0.547017059222,0.3)); -#51205 = CARTESIAN_POINT('',(0.287209438086,-0.15)); -#51206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51207 = ORIENTED_EDGE('',*,*,#48045,.F.); -#51208 = ADVANCED_FACE('',(#51209),#48033,.F.); -#51209 = FACE_BOUND('',#51210,.F.); -#51210 = EDGE_LOOP('',(#51211,#51212,#51213,#51234,#51235)); -#51211 = ORIENTED_EDGE('',*,*,#51183,.T.); -#51212 = ORIENTED_EDGE('',*,*,#48015,.T.); -#51213 = ORIENTED_EDGE('',*,*,#51214,.F.); -#51214 = EDGE_CURVE('',#49809,#48018,#51215,.T.); -#51215 = SURFACE_CURVE('',#51216,(#51220,#51227),.PCURVE_S1.); -#51216 = LINE('',#51217,#51218); -#51217 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); -#51218 = VECTOR('',#51219,1.); -#51219 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51220 = PCURVE('',#48033,#51221); -#51221 = DEFINITIONAL_REPRESENTATION('',(#51222),#51226); -#51222 = LINE('',#51223,#51224); -#51223 = CARTESIAN_POINT('',(0.43,0.E+000)); -#51224 = VECTOR('',#51225,1.); -#51225 = DIRECTION('',(0.E+000,-1.)); -#51226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51227 = PCURVE('',#48346,#51228); -#51228 = DEFINITIONAL_REPRESENTATION('',(#51229),#51233); -#51229 = LINE('',#51230,#51231); -#51230 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51231 = VECTOR('',#51232,1.); -#51232 = DIRECTION('',(0.E+000,-1.)); -#51233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51234 = ORIENTED_EDGE('',*,*,#49808,.F.); -#51235 = ORIENTED_EDGE('',*,*,#51086,.T.); -#51236 = ADVANCED_FACE('',(#51237),#48346,.F.); -#51237 = FACE_BOUND('',#51238,.F.); -#51238 = EDGE_LOOP('',(#51239,#51240,#51241,#51242)); -#51239 = ORIENTED_EDGE('',*,*,#49831,.F.); -#51240 = ORIENTED_EDGE('',*,*,#51214,.T.); -#51241 = ORIENTED_EDGE('',*,*,#48332,.T.); -#51242 = ORIENTED_EDGE('',*,*,#51243,.F.); -#51243 = EDGE_CURVE('',#49832,#48301,#51244,.T.); -#51244 = SURFACE_CURVE('',#51245,(#51249,#51256),.PCURVE_S1.); -#51245 = LINE('',#51246,#51247); -#51246 = CARTESIAN_POINT('',(-1.9,1.225,1.35)); -#51247 = VECTOR('',#51248,1.); -#51248 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51249 = PCURVE('',#48346,#51250); -#51250 = DEFINITIONAL_REPRESENTATION('',(#51251),#51255); -#51251 = LINE('',#51252,#51253); -#51252 = CARTESIAN_POINT('',(0.125,0.E+000)); -#51253 = VECTOR('',#51254,1.); -#51254 = DIRECTION('',(0.E+000,-1.)); -#51255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51256 = PCURVE('',#48321,#51257); -#51257 = DEFINITIONAL_REPRESENTATION('',(#51258),#51261); -#51258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51259,#51260),.UNSPECIFIED., +#53591 = CARTESIAN_POINT('',(0.287209438086,-0.15)); +#53592 = CARTESIAN_POINT('',(2.740181695085E-002,-0.6)); +#53593 = CARTESIAN_POINT('',(-0.232405804184,-0.15)); +#53594 = CARTESIAN_POINT('',(-0.49221342532,0.3)); +#53595 = CARTESIAN_POINT('',(2.740181695107E-002,0.3)); +#53596 = CARTESIAN_POINT('',(0.547017059222,0.3)); +#53597 = CARTESIAN_POINT('',(0.287209438086,-0.15)); +#53598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53599 = ORIENTED_EDGE('',*,*,#50437,.F.); +#53600 = ADVANCED_FACE('',(#53601),#50425,.F.); +#53601 = FACE_BOUND('',#53602,.F.); +#53602 = EDGE_LOOP('',(#53603,#53604,#53605,#53626,#53627)); +#53603 = ORIENTED_EDGE('',*,*,#53575,.T.); +#53604 = ORIENTED_EDGE('',*,*,#50407,.T.); +#53605 = ORIENTED_EDGE('',*,*,#53606,.F.); +#53606 = EDGE_CURVE('',#52201,#50410,#53607,.T.); +#53607 = SURFACE_CURVE('',#53608,(#53612,#53619),.PCURVE_S1.); +#53608 = LINE('',#53609,#53610); +#53609 = CARTESIAN_POINT('',(-2.025,1.225,1.35)); +#53610 = VECTOR('',#53611,1.); +#53611 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53612 = PCURVE('',#50425,#53613); +#53613 = DEFINITIONAL_REPRESENTATION('',(#53614),#53618); +#53614 = LINE('',#53615,#53616); +#53615 = CARTESIAN_POINT('',(0.43,0.E+000)); +#53616 = VECTOR('',#53617,1.); +#53617 = DIRECTION('',(0.E+000,-1.)); +#53618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53619 = PCURVE('',#50738,#53620); +#53620 = DEFINITIONAL_REPRESENTATION('',(#53621),#53625); +#53621 = LINE('',#53622,#53623); +#53622 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53623 = VECTOR('',#53624,1.); +#53624 = DIRECTION('',(0.E+000,-1.)); +#53625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53626 = ORIENTED_EDGE('',*,*,#52200,.F.); +#53627 = ORIENTED_EDGE('',*,*,#53478,.T.); +#53628 = ADVANCED_FACE('',(#53629),#50738,.F.); +#53629 = FACE_BOUND('',#53630,.F.); +#53630 = EDGE_LOOP('',(#53631,#53632,#53633,#53634)); +#53631 = ORIENTED_EDGE('',*,*,#52223,.F.); +#53632 = ORIENTED_EDGE('',*,*,#53606,.T.); +#53633 = ORIENTED_EDGE('',*,*,#50724,.T.); +#53634 = ORIENTED_EDGE('',*,*,#53635,.F.); +#53635 = EDGE_CURVE('',#52224,#50693,#53636,.T.); +#53636 = SURFACE_CURVE('',#53637,(#53641,#53648),.PCURVE_S1.); +#53637 = LINE('',#53638,#53639); +#53638 = CARTESIAN_POINT('',(-1.9,1.225,1.35)); +#53639 = VECTOR('',#53640,1.); +#53640 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53641 = PCURVE('',#50738,#53642); +#53642 = DEFINITIONAL_REPRESENTATION('',(#53643),#53647); +#53643 = LINE('',#53644,#53645); +#53644 = CARTESIAN_POINT('',(0.125,0.E+000)); +#53645 = VECTOR('',#53646,1.); +#53646 = DIRECTION('',(0.E+000,-1.)); +#53647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53648 = PCURVE('',#50713,#53649); +#53649 = DEFINITIONAL_REPRESENTATION('',(#53650),#53653); +#53650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53651,#53652),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#51259 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); -#51260 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); -#51261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51262 = ADVANCED_FACE('',(#51263),#48321,.F.); -#51263 = FACE_BOUND('',#51264,.F.); -#51264 = EDGE_LOOP('',(#51265,#51266,#51267,#51268)); -#51265 = ORIENTED_EDGE('',*,*,#49854,.F.); -#51266 = ORIENTED_EDGE('',*,*,#51243,.T.); -#51267 = ORIENTED_EDGE('',*,*,#48300,.T.); -#51268 = ORIENTED_EDGE('',*,*,#51269,.F.); -#51269 = EDGE_CURVE('',#49855,#48273,#51270,.T.); -#51270 = SURFACE_CURVE('',#51271,(#51275,#51281),.PCURVE_S1.); -#51271 = LINE('',#51272,#51273); -#51272 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); -#51273 = VECTOR('',#51274,1.); -#51274 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51275 = PCURVE('',#48321,#51276); -#51276 = DEFINITIONAL_REPRESENTATION('',(#51277),#51280); -#51277 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51278,#51279),.UNSPECIFIED., +#53651 = CARTESIAN_POINT('',(-1.570796326795,0.E+000)); +#53652 = CARTESIAN_POINT('',(-1.570796326795,-0.3)); +#53653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53654 = ADVANCED_FACE('',(#53655),#50713,.F.); +#53655 = FACE_BOUND('',#53656,.F.); +#53656 = EDGE_LOOP('',(#53657,#53658,#53659,#53660)); +#53657 = ORIENTED_EDGE('',*,*,#52246,.F.); +#53658 = ORIENTED_EDGE('',*,*,#53635,.T.); +#53659 = ORIENTED_EDGE('',*,*,#50692,.T.); +#53660 = ORIENTED_EDGE('',*,*,#53661,.F.); +#53661 = EDGE_CURVE('',#52247,#50665,#53662,.T.); +#53662 = SURFACE_CURVE('',#53663,(#53667,#53673),.PCURVE_S1.); +#53663 = LINE('',#53664,#53665); +#53664 = CARTESIAN_POINT('',(-1.9,1.225,1.1)); +#53665 = VECTOR('',#53666,1.); +#53666 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53667 = PCURVE('',#50713,#53668); +#53668 = DEFINITIONAL_REPRESENTATION('',(#53669),#53672); +#53669 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53670,#53671),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#51278 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#51279 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#51280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51281 = PCURVE('',#48288,#51282); -#51282 = DEFINITIONAL_REPRESENTATION('',(#51283),#51287); -#51283 = LINE('',#51284,#51285); -#51284 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51285 = VECTOR('',#51286,1.); -#51286 = DIRECTION('',(0.E+000,-1.)); -#51287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51288 = ADVANCED_FACE('',(#51289),#48288,.F.); -#51289 = FACE_BOUND('',#51290,.F.); -#51290 = EDGE_LOOP('',(#51291,#51292,#51293,#51294)); -#51291 = ORIENTED_EDGE('',*,*,#49877,.F.); -#51292 = ORIENTED_EDGE('',*,*,#51269,.T.); -#51293 = ORIENTED_EDGE('',*,*,#48272,.T.); -#51294 = ORIENTED_EDGE('',*,*,#51295,.F.); -#51295 = EDGE_CURVE('',#49878,#48245,#51296,.T.); -#51296 = SURFACE_CURVE('',#51297,(#51301,#51308),.PCURVE_S1.); -#51297 = LINE('',#51298,#51299); -#51298 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); -#51299 = VECTOR('',#51300,1.); -#51300 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51301 = PCURVE('',#48288,#51302); -#51302 = DEFINITIONAL_REPRESENTATION('',(#51303),#51307); -#51303 = LINE('',#51304,#51305); -#51304 = CARTESIAN_POINT('',(0.125,0.E+000)); -#51305 = VECTOR('',#51306,1.); -#51306 = DIRECTION('',(0.E+000,-1.)); -#51307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51308 = PCURVE('',#48260,#51309); -#51309 = DEFINITIONAL_REPRESENTATION('',(#51310),#51314); -#51310 = LINE('',#51311,#51312); -#51311 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51312 = VECTOR('',#51313,1.); -#51313 = DIRECTION('',(0.E+000,-1.)); -#51314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51315 = ADVANCED_FACE('',(#51316),#48260,.F.); -#51316 = FACE_BOUND('',#51317,.F.); -#51317 = EDGE_LOOP('',(#51318,#51319,#51320,#51321)); -#51318 = ORIENTED_EDGE('',*,*,#49900,.F.); -#51319 = ORIENTED_EDGE('',*,*,#51295,.T.); -#51320 = ORIENTED_EDGE('',*,*,#48244,.T.); -#51321 = ORIENTED_EDGE('',*,*,#51322,.F.); -#51322 = EDGE_CURVE('',#49901,#48217,#51323,.T.); -#51323 = SURFACE_CURVE('',#51324,(#51328,#51335),.PCURVE_S1.); -#51324 = LINE('',#51325,#51326); -#51325 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); -#51326 = VECTOR('',#51327,1.); -#51327 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51328 = PCURVE('',#48260,#51329); -#51329 = DEFINITIONAL_REPRESENTATION('',(#51330),#51334); -#51330 = LINE('',#51331,#51332); -#51331 = CARTESIAN_POINT('',(1.22,0.E+000)); -#51332 = VECTOR('',#51333,1.); -#51333 = DIRECTION('',(0.E+000,-1.)); -#51334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51335 = PCURVE('',#48232,#51336); -#51336 = DEFINITIONAL_REPRESENTATION('',(#51337),#51341); -#51337 = LINE('',#51338,#51339); -#51338 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51339 = VECTOR('',#51340,1.); -#51340 = DIRECTION('',(0.E+000,-1.)); -#51341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51342 = ADVANCED_FACE('',(#51343),#48232,.F.); -#51343 = FACE_BOUND('',#51344,.F.); -#51344 = EDGE_LOOP('',(#51345,#51346,#51347,#51348)); -#51345 = ORIENTED_EDGE('',*,*,#49923,.F.); -#51346 = ORIENTED_EDGE('',*,*,#51322,.T.); -#51347 = ORIENTED_EDGE('',*,*,#48216,.T.); -#51348 = ORIENTED_EDGE('',*,*,#51349,.F.); -#51349 = EDGE_CURVE('',#49924,#48189,#51350,.T.); -#51350 = SURFACE_CURVE('',#51351,(#51355,#51362),.PCURVE_S1.); -#51351 = LINE('',#51352,#51353); -#51352 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); -#51353 = VECTOR('',#51354,1.); -#51354 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51355 = PCURVE('',#48232,#51356); -#51356 = DEFINITIONAL_REPRESENTATION('',(#51357),#51361); -#51357 = LINE('',#51358,#51359); -#51358 = CARTESIAN_POINT('',(0.7,0.E+000)); -#51359 = VECTOR('',#51360,1.); -#51360 = DIRECTION('',(0.E+000,-1.)); -#51361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51362 = PCURVE('',#48204,#51363); -#51363 = DEFINITIONAL_REPRESENTATION('',(#51364),#51368); -#51364 = LINE('',#51365,#51366); -#51365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51366 = VECTOR('',#51367,1.); -#51367 = DIRECTION('',(0.E+000,-1.)); -#51368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51369 = ADVANCED_FACE('',(#51370),#48204,.F.); -#51370 = FACE_BOUND('',#51371,.F.); -#51371 = EDGE_LOOP('',(#51372,#51373,#51374,#51375)); -#51372 = ORIENTED_EDGE('',*,*,#49946,.F.); -#51373 = ORIENTED_EDGE('',*,*,#51349,.T.); -#51374 = ORIENTED_EDGE('',*,*,#48188,.T.); -#51375 = ORIENTED_EDGE('',*,*,#51376,.F.); -#51376 = EDGE_CURVE('',#49947,#48161,#51377,.T.); -#51377 = SURFACE_CURVE('',#51378,(#51382,#51389),.PCURVE_S1.); -#51378 = LINE('',#51379,#51380); -#51379 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); -#51380 = VECTOR('',#51381,1.); -#51381 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51382 = PCURVE('',#48204,#51383); -#51383 = DEFINITIONAL_REPRESENTATION('',(#51384),#51388); -#51384 = LINE('',#51385,#51386); -#51385 = CARTESIAN_POINT('',(1.22,0.E+000)); -#51386 = VECTOR('',#51387,1.); -#51387 = DIRECTION('',(0.E+000,-1.)); -#51388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51389 = PCURVE('',#48176,#51390); -#51390 = DEFINITIONAL_REPRESENTATION('',(#51391),#51395); -#51391 = LINE('',#51392,#51393); -#51392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51393 = VECTOR('',#51394,1.); -#51394 = DIRECTION('',(0.E+000,-1.)); -#51395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51396 = ADVANCED_FACE('',(#51397),#48176,.F.); -#51397 = FACE_BOUND('',#51398,.F.); -#51398 = EDGE_LOOP('',(#51399,#51400,#51401,#51402)); -#51399 = ORIENTED_EDGE('',*,*,#49969,.F.); -#51400 = ORIENTED_EDGE('',*,*,#51376,.T.); -#51401 = ORIENTED_EDGE('',*,*,#48160,.T.); -#51402 = ORIENTED_EDGE('',*,*,#51403,.F.); -#51403 = EDGE_CURVE('',#49970,#48129,#51404,.T.); -#51404 = SURFACE_CURVE('',#51405,(#51409,#51416),.PCURVE_S1.); -#51405 = LINE('',#51406,#51407); -#51406 = CARTESIAN_POINT('',(-2.85,1.225,1.1)); -#51407 = VECTOR('',#51408,1.); -#51408 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51409 = PCURVE('',#48176,#51410); -#51410 = DEFINITIONAL_REPRESENTATION('',(#51411),#51415); -#51411 = LINE('',#51412,#51413); -#51412 = CARTESIAN_POINT('',(0.125,0.E+000)); -#51413 = VECTOR('',#51414,1.); -#51414 = DIRECTION('',(0.E+000,-1.)); -#51415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51416 = PCURVE('',#48149,#51417); -#51417 = DEFINITIONAL_REPRESENTATION('',(#51418),#51421); -#51418 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51419,#51420),.UNSPECIFIED., +#53670 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#53671 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#53672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53673 = PCURVE('',#50680,#53674); +#53674 = DEFINITIONAL_REPRESENTATION('',(#53675),#53679); +#53675 = LINE('',#53676,#53677); +#53676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53677 = VECTOR('',#53678,1.); +#53678 = DIRECTION('',(0.E+000,-1.)); +#53679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53680 = ADVANCED_FACE('',(#53681),#50680,.F.); +#53681 = FACE_BOUND('',#53682,.F.); +#53682 = EDGE_LOOP('',(#53683,#53684,#53685,#53686)); +#53683 = ORIENTED_EDGE('',*,*,#52269,.F.); +#53684 = ORIENTED_EDGE('',*,*,#53661,.T.); +#53685 = ORIENTED_EDGE('',*,*,#50664,.T.); +#53686 = ORIENTED_EDGE('',*,*,#53687,.F.); +#53687 = EDGE_CURVE('',#52270,#50637,#53688,.T.); +#53688 = SURFACE_CURVE('',#53689,(#53693,#53700),.PCURVE_S1.); +#53689 = LINE('',#53690,#53691); +#53690 = CARTESIAN_POINT('',(-2.025,1.225,1.1)); +#53691 = VECTOR('',#53692,1.); +#53692 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53693 = PCURVE('',#50680,#53694); +#53694 = DEFINITIONAL_REPRESENTATION('',(#53695),#53699); +#53695 = LINE('',#53696,#53697); +#53696 = CARTESIAN_POINT('',(0.125,0.E+000)); +#53697 = VECTOR('',#53698,1.); +#53698 = DIRECTION('',(0.E+000,-1.)); +#53699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53700 = PCURVE('',#50652,#53701); +#53701 = DEFINITIONAL_REPRESENTATION('',(#53702),#53706); +#53702 = LINE('',#53703,#53704); +#53703 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53704 = VECTOR('',#53705,1.); +#53705 = DIRECTION('',(0.E+000,-1.)); +#53706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53707 = ADVANCED_FACE('',(#53708),#50652,.F.); +#53708 = FACE_BOUND('',#53709,.F.); +#53709 = EDGE_LOOP('',(#53710,#53711,#53712,#53713)); +#53710 = ORIENTED_EDGE('',*,*,#52292,.F.); +#53711 = ORIENTED_EDGE('',*,*,#53687,.T.); +#53712 = ORIENTED_EDGE('',*,*,#50636,.T.); +#53713 = ORIENTED_EDGE('',*,*,#53714,.F.); +#53714 = EDGE_CURVE('',#52293,#50609,#53715,.T.); +#53715 = SURFACE_CURVE('',#53716,(#53720,#53727),.PCURVE_S1.); +#53716 = LINE('',#53717,#53718); +#53717 = CARTESIAN_POINT('',(-2.025,1.225,-0.12)); +#53718 = VECTOR('',#53719,1.); +#53719 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53720 = PCURVE('',#50652,#53721); +#53721 = DEFINITIONAL_REPRESENTATION('',(#53722),#53726); +#53722 = LINE('',#53723,#53724); +#53723 = CARTESIAN_POINT('',(1.22,0.E+000)); +#53724 = VECTOR('',#53725,1.); +#53725 = DIRECTION('',(0.E+000,-1.)); +#53726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53727 = PCURVE('',#50624,#53728); +#53728 = DEFINITIONAL_REPRESENTATION('',(#53729),#53733); +#53729 = LINE('',#53730,#53731); +#53730 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53731 = VECTOR('',#53732,1.); +#53732 = DIRECTION('',(0.E+000,-1.)); +#53733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53734 = ADVANCED_FACE('',(#53735),#50624,.F.); +#53735 = FACE_BOUND('',#53736,.F.); +#53736 = EDGE_LOOP('',(#53737,#53738,#53739,#53740)); +#53737 = ORIENTED_EDGE('',*,*,#52315,.F.); +#53738 = ORIENTED_EDGE('',*,*,#53714,.T.); +#53739 = ORIENTED_EDGE('',*,*,#50608,.T.); +#53740 = ORIENTED_EDGE('',*,*,#53741,.F.); +#53741 = EDGE_CURVE('',#52316,#50581,#53742,.T.); +#53742 = SURFACE_CURVE('',#53743,(#53747,#53754),.PCURVE_S1.); +#53743 = LINE('',#53744,#53745); +#53744 = CARTESIAN_POINT('',(-2.725,1.225,-0.12)); +#53745 = VECTOR('',#53746,1.); +#53746 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53747 = PCURVE('',#50624,#53748); +#53748 = DEFINITIONAL_REPRESENTATION('',(#53749),#53753); +#53749 = LINE('',#53750,#53751); +#53750 = CARTESIAN_POINT('',(0.7,0.E+000)); +#53751 = VECTOR('',#53752,1.); +#53752 = DIRECTION('',(0.E+000,-1.)); +#53753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53754 = PCURVE('',#50596,#53755); +#53755 = DEFINITIONAL_REPRESENTATION('',(#53756),#53760); +#53756 = LINE('',#53757,#53758); +#53757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53758 = VECTOR('',#53759,1.); +#53759 = DIRECTION('',(0.E+000,-1.)); +#53760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53761 = ADVANCED_FACE('',(#53762),#50596,.F.); +#53762 = FACE_BOUND('',#53763,.F.); +#53763 = EDGE_LOOP('',(#53764,#53765,#53766,#53767)); +#53764 = ORIENTED_EDGE('',*,*,#52338,.F.); +#53765 = ORIENTED_EDGE('',*,*,#53741,.T.); +#53766 = ORIENTED_EDGE('',*,*,#50580,.T.); +#53767 = ORIENTED_EDGE('',*,*,#53768,.F.); +#53768 = EDGE_CURVE('',#52339,#50553,#53769,.T.); +#53769 = SURFACE_CURVE('',#53770,(#53774,#53781),.PCURVE_S1.); +#53770 = LINE('',#53771,#53772); +#53771 = CARTESIAN_POINT('',(-2.725,1.225,1.1)); +#53772 = VECTOR('',#53773,1.); +#53773 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53774 = PCURVE('',#50596,#53775); +#53775 = DEFINITIONAL_REPRESENTATION('',(#53776),#53780); +#53776 = LINE('',#53777,#53778); +#53777 = CARTESIAN_POINT('',(1.22,0.E+000)); +#53778 = VECTOR('',#53779,1.); +#53779 = DIRECTION('',(0.E+000,-1.)); +#53780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53781 = PCURVE('',#50568,#53782); +#53782 = DEFINITIONAL_REPRESENTATION('',(#53783),#53787); +#53783 = LINE('',#53784,#53785); +#53784 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53785 = VECTOR('',#53786,1.); +#53786 = DIRECTION('',(0.E+000,-1.)); +#53787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53788 = ADVANCED_FACE('',(#53789),#50568,.F.); +#53789 = FACE_BOUND('',#53790,.F.); +#53790 = EDGE_LOOP('',(#53791,#53792,#53793,#53794)); +#53791 = ORIENTED_EDGE('',*,*,#52361,.F.); +#53792 = ORIENTED_EDGE('',*,*,#53768,.T.); +#53793 = ORIENTED_EDGE('',*,*,#50552,.T.); +#53794 = ORIENTED_EDGE('',*,*,#53795,.F.); +#53795 = EDGE_CURVE('',#52362,#50521,#53796,.T.); +#53796 = SURFACE_CURVE('',#53797,(#53801,#53808),.PCURVE_S1.); +#53797 = LINE('',#53798,#53799); +#53798 = CARTESIAN_POINT('',(-2.85,1.225,1.1)); +#53799 = VECTOR('',#53800,1.); +#53800 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53801 = PCURVE('',#50568,#53802); +#53802 = DEFINITIONAL_REPRESENTATION('',(#53803),#53807); +#53803 = LINE('',#53804,#53805); +#53804 = CARTESIAN_POINT('',(0.125,0.E+000)); +#53805 = VECTOR('',#53806,1.); +#53806 = DIRECTION('',(0.E+000,-1.)); +#53807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53808 = PCURVE('',#50541,#53809); +#53809 = DEFINITIONAL_REPRESENTATION('',(#53810),#53813); +#53810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53811,#53812),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#51419 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#51420 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#51421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51422 = ADVANCED_FACE('',(#51423),#48149,.F.); -#51423 = FACE_BOUND('',#51424,.F.); -#51424 = EDGE_LOOP('',(#51425,#51426,#51427,#51428)); -#51425 = ORIENTED_EDGE('',*,*,#49992,.F.); -#51426 = ORIENTED_EDGE('',*,*,#51403,.T.); -#51427 = ORIENTED_EDGE('',*,*,#48128,.T.); -#51428 = ORIENTED_EDGE('',*,*,#51429,.F.); -#51429 = EDGE_CURVE('',#49993,#48101,#51430,.T.); -#51430 = SURFACE_CURVE('',#51431,(#51435,#51441),.PCURVE_S1.); -#51431 = LINE('',#51432,#51433); -#51432 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); -#51433 = VECTOR('',#51434,1.); -#51434 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51435 = PCURVE('',#48149,#51436); -#51436 = DEFINITIONAL_REPRESENTATION('',(#51437),#51440); -#51437 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51438,#51439),.UNSPECIFIED., +#53811 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#53812 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#53813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53814 = ADVANCED_FACE('',(#53815),#50541,.F.); +#53815 = FACE_BOUND('',#53816,.F.); +#53816 = EDGE_LOOP('',(#53817,#53818,#53819,#53820)); +#53817 = ORIENTED_EDGE('',*,*,#52384,.F.); +#53818 = ORIENTED_EDGE('',*,*,#53795,.T.); +#53819 = ORIENTED_EDGE('',*,*,#50520,.T.); +#53820 = ORIENTED_EDGE('',*,*,#53821,.F.); +#53821 = EDGE_CURVE('',#52385,#50493,#53822,.T.); +#53822 = SURFACE_CURVE('',#53823,(#53827,#53833),.PCURVE_S1.); +#53823 = LINE('',#53824,#53825); +#53824 = CARTESIAN_POINT('',(-2.85,1.225,1.35)); +#53825 = VECTOR('',#53826,1.); +#53826 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53827 = PCURVE('',#50541,#53828); +#53828 = DEFINITIONAL_REPRESENTATION('',(#53829),#53832); +#53829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53830,#53831),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#51438 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#51439 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#51440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51441 = PCURVE('',#48116,#51442); -#51442 = DEFINITIONAL_REPRESENTATION('',(#51443),#51447); -#51443 = LINE('',#51444,#51445); -#51444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51445 = VECTOR('',#51446,1.); -#51446 = DIRECTION('',(0.E+000,-1.)); -#51447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51448 = ADVANCED_FACE('',(#51449),#48116,.F.); -#51449 = FACE_BOUND('',#51450,.F.); -#51450 = EDGE_LOOP('',(#51451,#51452,#51453,#51454)); -#51451 = ORIENTED_EDGE('',*,*,#50015,.F.); -#51452 = ORIENTED_EDGE('',*,*,#51429,.T.); -#51453 = ORIENTED_EDGE('',*,*,#48100,.T.); -#51454 = ORIENTED_EDGE('',*,*,#51156,.F.); -#51455 = ADVANCED_FACE('',(#51456),#49796,.F.); -#51456 = FACE_BOUND('',#51457,.F.); -#51457 = EDGE_LOOP('',(#51458,#51459,#51460,#51461)); -#51458 = ORIENTED_EDGE('',*,*,#50742,.F.); -#51459 = ORIENTED_EDGE('',*,*,#50941,.T.); -#51460 = ORIENTED_EDGE('',*,*,#51107,.T.); -#51461 = ORIENTED_EDGE('',*,*,#49780,.T.); -#51462 = ADVANCED_FACE('',(#51463),#49043,.T.); -#51463 = FACE_BOUND('',#51464,.T.); -#51464 = EDGE_LOOP('',(#51465,#51492,#51519,#51544)); -#51465 = ORIENTED_EDGE('',*,*,#51466,.F.); -#51466 = EDGE_CURVE('',#51467,#49028,#51469,.T.); -#51467 = VERTEX_POINT('',#51468); -#51468 = CARTESIAN_POINT('',(1.21,0.925,-2.65)); -#51469 = SURFACE_CURVE('',#51470,(#51475,#51481),.PCURVE_S1.); -#51470 = CIRCLE('',#51471,0.3); -#51471 = AXIS2_PLACEMENT_3D('',#51472,#51473,#51474); -#51472 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); -#51473 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51474 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51475 = PCURVE('',#49043,#51476); -#51476 = DEFINITIONAL_REPRESENTATION('',(#51477),#51480); -#51477 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51478,#51479),.UNSPECIFIED., +#53830 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#53831 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#53832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53833 = PCURVE('',#50508,#53834); +#53834 = DEFINITIONAL_REPRESENTATION('',(#53835),#53839); +#53835 = LINE('',#53836,#53837); +#53836 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53837 = VECTOR('',#53838,1.); +#53838 = DIRECTION('',(0.E+000,-1.)); +#53839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53840 = ADVANCED_FACE('',(#53841),#50508,.F.); +#53841 = FACE_BOUND('',#53842,.F.); +#53842 = EDGE_LOOP('',(#53843,#53844,#53845,#53846)); +#53843 = ORIENTED_EDGE('',*,*,#52407,.F.); +#53844 = ORIENTED_EDGE('',*,*,#53821,.T.); +#53845 = ORIENTED_EDGE('',*,*,#50492,.T.); +#53846 = ORIENTED_EDGE('',*,*,#53548,.F.); +#53847 = ADVANCED_FACE('',(#53848),#52188,.F.); +#53848 = FACE_BOUND('',#53849,.F.); +#53849 = EDGE_LOOP('',(#53850,#53851,#53852,#53853)); +#53850 = ORIENTED_EDGE('',*,*,#53134,.F.); +#53851 = ORIENTED_EDGE('',*,*,#53333,.T.); +#53852 = ORIENTED_EDGE('',*,*,#53499,.T.); +#53853 = ORIENTED_EDGE('',*,*,#52172,.T.); +#53854 = ADVANCED_FACE('',(#53855),#51435,.T.); +#53855 = FACE_BOUND('',#53856,.T.); +#53856 = EDGE_LOOP('',(#53857,#53884,#53911,#53936)); +#53857 = ORIENTED_EDGE('',*,*,#53858,.F.); +#53858 = EDGE_CURVE('',#53859,#51420,#53861,.T.); +#53859 = VERTEX_POINT('',#53860); +#53860 = CARTESIAN_POINT('',(1.21,0.925,-2.65)); +#53861 = SURFACE_CURVE('',#53862,(#53867,#53873),.PCURVE_S1.); +#53862 = CIRCLE('',#53863,0.3); +#53863 = AXIS2_PLACEMENT_3D('',#53864,#53865,#53866); +#53864 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); +#53865 = DIRECTION('',(1.,0.E+000,0.E+000)); +#53866 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#53867 = PCURVE('',#51435,#53868); +#53868 = DEFINITIONAL_REPRESENTATION('',(#53869),#53872); +#53869 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53870,#53871),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#51478 = CARTESIAN_POINT('',(0.E+000,4.22491772868)); -#51479 = CARTESIAN_POINT('',(1.570796326795,4.22491772868)); -#51480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#53870 = CARTESIAN_POINT('',(0.E+000,4.22491772868)); +#53871 = CARTESIAN_POINT('',(1.570796326795,4.22491772868)); +#53872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#51481 = PCURVE('',#47630,#51482); -#51482 = DEFINITIONAL_REPRESENTATION('',(#51483),#51491); -#51483 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#51484,#51485,#51486,#51487 - ,#51488,#51489,#51490),.UNSPECIFIED.,.F.,.F.) +#53873 = PCURVE('',#50022,#53874); +#53874 = DEFINITIONAL_REPRESENTATION('',(#53875),#53883); +#53875 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53876,#53877,#53878,#53879 + ,#53880,#53881,#53882),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#51484 = CARTESIAN_POINT('',(-0.3,-0.3)); -#51485 = CARTESIAN_POINT('',(-0.3,0.219615242271)); -#51486 = CARTESIAN_POINT('',(0.15,-4.019237886467E-002)); -#51487 = CARTESIAN_POINT('',(0.6,-0.3)); -#51488 = CARTESIAN_POINT('',(0.15,-0.559807621135)); -#51489 = CARTESIAN_POINT('',(-0.3,-0.819615242271)); -#51490 = CARTESIAN_POINT('',(-0.3,-0.3)); -#51491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51492 = ORIENTED_EDGE('',*,*,#51493,.F.); -#51493 = EDGE_CURVE('',#51494,#51467,#51496,.T.); -#51494 = VERTEX_POINT('',#51495); -#51495 = CARTESIAN_POINT('',(-1.21,0.925,-2.65)); -#51496 = SURFACE_CURVE('',#51497,(#51501,#51507),.PCURVE_S1.); -#51497 = LINE('',#51498,#51499); -#51498 = CARTESIAN_POINT('',(-1.21,0.925,-2.65)); -#51499 = VECTOR('',#51500,1.); -#51500 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51501 = PCURVE('',#49043,#51502); -#51502 = DEFINITIONAL_REPRESENTATION('',(#51503),#51506); -#51503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51504,#51505),.UNSPECIFIED., +#53876 = CARTESIAN_POINT('',(-0.3,-0.3)); +#53877 = CARTESIAN_POINT('',(-0.3,0.219615242271)); +#53878 = CARTESIAN_POINT('',(0.15,-4.019237886467E-002)); +#53879 = CARTESIAN_POINT('',(0.6,-0.3)); +#53880 = CARTESIAN_POINT('',(0.15,-0.559807621135)); +#53881 = CARTESIAN_POINT('',(-0.3,-0.819615242271)); +#53882 = CARTESIAN_POINT('',(-0.3,-0.3)); +#53883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53884 = ORIENTED_EDGE('',*,*,#53885,.F.); +#53885 = EDGE_CURVE('',#53886,#53859,#53888,.T.); +#53886 = VERTEX_POINT('',#53887); +#53887 = CARTESIAN_POINT('',(-1.21,0.925,-2.65)); +#53888 = SURFACE_CURVE('',#53889,(#53893,#53899),.PCURVE_S1.); +#53889 = LINE('',#53890,#53891); +#53890 = CARTESIAN_POINT('',(-1.21,0.925,-2.65)); +#53891 = VECTOR('',#53892,1.); +#53892 = DIRECTION('',(1.,0.E+000,0.E+000)); +#53893 = PCURVE('',#51435,#53894); +#53894 = DEFINITIONAL_REPRESENTATION('',(#53895),#53898); +#53895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53896,#53897),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.42),.PIECEWISE_BEZIER_KNOTS.); -#51504 = CARTESIAN_POINT('',(0.E+000,1.80491772868)); -#51505 = CARTESIAN_POINT('',(0.E+000,4.22491772868)); -#51506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51507 = PCURVE('',#51508,#51513); -#51508 = PLANE('',#51509); -#51509 = AXIS2_PLACEMENT_3D('',#51510,#51511,#51512); -#51510 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.65)); -#51511 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51512 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51513 = DEFINITIONAL_REPRESENTATION('',(#51514),#51518); -#51514 = LINE('',#51515,#51516); -#51515 = CARTESIAN_POINT('',(1.21,0.925)); -#51516 = VECTOR('',#51517,1.); -#51517 = DIRECTION('',(-1.,0.E+000)); -#51518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51519 = ORIENTED_EDGE('',*,*,#51520,.F.); -#51520 = EDGE_CURVE('',#49026,#51494,#51521,.T.); -#51521 = SURFACE_CURVE('',#51522,(#51527,#51533),.PCURVE_S1.); -#51522 = CIRCLE('',#51523,0.3); -#51523 = AXIS2_PLACEMENT_3D('',#51524,#51525,#51526); -#51524 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); -#51525 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51526 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51527 = PCURVE('',#49043,#51528); -#51528 = DEFINITIONAL_REPRESENTATION('',(#51529),#51532); -#51529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51530,#51531),.UNSPECIFIED., +#53896 = CARTESIAN_POINT('',(0.E+000,1.80491772868)); +#53897 = CARTESIAN_POINT('',(0.E+000,4.22491772868)); +#53898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53899 = PCURVE('',#53900,#53905); +#53900 = PLANE('',#53901); +#53901 = AXIS2_PLACEMENT_3D('',#53902,#53903,#53904); +#53902 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.65)); +#53903 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#53904 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#53905 = DEFINITIONAL_REPRESENTATION('',(#53906),#53910); +#53906 = LINE('',#53907,#53908); +#53907 = CARTESIAN_POINT('',(1.21,0.925)); +#53908 = VECTOR('',#53909,1.); +#53909 = DIRECTION('',(-1.,0.E+000)); +#53910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53911 = ORIENTED_EDGE('',*,*,#53912,.F.); +#53912 = EDGE_CURVE('',#51418,#53886,#53913,.T.); +#53913 = SURFACE_CURVE('',#53914,(#53919,#53925),.PCURVE_S1.); +#53914 = CIRCLE('',#53915,0.3); +#53915 = AXIS2_PLACEMENT_3D('',#53916,#53917,#53918); +#53916 = CARTESIAN_POINT('',(-1.21,0.925,-2.35)); +#53917 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#53918 = DIRECTION('',(0.E+000,1.,0.E+000)); +#53919 = PCURVE('',#51435,#53920); +#53920 = DEFINITIONAL_REPRESENTATION('',(#53921),#53924); +#53921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53922,#53923),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#51530 = CARTESIAN_POINT('',(1.570796326795,1.80491772868)); -#51531 = CARTESIAN_POINT('',(0.E+000,1.80491772868)); -#51532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#53922 = CARTESIAN_POINT('',(1.570796326795,1.80491772868)); +#53923 = CARTESIAN_POINT('',(0.E+000,1.80491772868)); +#53924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#51533 = PCURVE('',#47216,#51534); -#51534 = DEFINITIONAL_REPRESENTATION('',(#51535),#51543); -#51535 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#51536,#51537,#51538,#51539 - ,#51540,#51541,#51542),.UNSPECIFIED.,.F.,.F.) +#53925 = PCURVE('',#49608,#53926); +#53926 = DEFINITIONAL_REPRESENTATION('',(#53927),#53935); +#53927 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53928,#53929,#53930,#53931 + ,#53932,#53933,#53934),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#51536 = CARTESIAN_POINT('',(1.,0.E+000)); -#51537 = CARTESIAN_POINT('',(1.519615242271,0.E+000)); -#51538 = CARTESIAN_POINT('',(1.259807621135,-0.45)); -#51539 = CARTESIAN_POINT('',(1.,-0.9)); -#51540 = CARTESIAN_POINT('',(0.740192378865,-0.45)); -#51541 = CARTESIAN_POINT('',(0.480384757729,-3.885780586188E-016)); -#51542 = CARTESIAN_POINT('',(1.,0.E+000)); -#51543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51544 = ORIENTED_EDGE('',*,*,#49025,.T.); -#51545 = ADVANCED_FACE('',(#51546),#47630,.F.); -#51546 = FACE_BOUND('',#51547,.F.); -#51547 = EDGE_LOOP('',(#51548,#51549,#51572,#51600,#51628,#51656,#51684, - #51707,#51728,#51729,#51750)); -#51548 = ORIENTED_EDGE('',*,*,#51466,.F.); -#51549 = ORIENTED_EDGE('',*,*,#51550,.T.); -#51550 = EDGE_CURVE('',#51467,#51551,#51553,.T.); -#51551 = VERTEX_POINT('',#51552); -#51552 = CARTESIAN_POINT('',(1.21,0.575,-2.65)); -#51553 = SURFACE_CURVE('',#51554,(#51558,#51565),.PCURVE_S1.); -#51554 = LINE('',#51555,#51556); -#51555 = CARTESIAN_POINT('',(1.21,0.925,-2.65)); -#51556 = VECTOR('',#51557,1.); -#51557 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51558 = PCURVE('',#47630,#51559); -#51559 = DEFINITIONAL_REPRESENTATION('',(#51560),#51564); -#51560 = LINE('',#51561,#51562); -#51561 = CARTESIAN_POINT('',(-0.3,-0.3)); -#51562 = VECTOR('',#51563,1.); -#51563 = DIRECTION('',(0.E+000,-1.)); -#51564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51565 = PCURVE('',#51508,#51566); -#51566 = DEFINITIONAL_REPRESENTATION('',(#51567),#51571); -#51567 = LINE('',#51568,#51569); -#51568 = CARTESIAN_POINT('',(-1.21,0.925)); -#51569 = VECTOR('',#51570,1.); -#51570 = DIRECTION('',(0.E+000,-1.)); -#51571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51572 = ORIENTED_EDGE('',*,*,#51573,.F.); -#51573 = EDGE_CURVE('',#51574,#51551,#51576,.T.); -#51574 = VERTEX_POINT('',#51575); -#51575 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); -#51576 = SURFACE_CURVE('',#51577,(#51581,#51588),.PCURVE_S1.); -#51577 = LINE('',#51578,#51579); -#51578 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); -#51579 = VECTOR('',#51580,1.); -#51580 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51581 = PCURVE('',#47630,#51582); -#51582 = DEFINITIONAL_REPRESENTATION('',(#51583),#51587); -#51583 = LINE('',#51584,#51585); -#51584 = CARTESIAN_POINT('',(0.E+000,-0.65)); -#51585 = VECTOR('',#51586,1.); -#51586 = DIRECTION('',(-1.,0.E+000)); -#51587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51588 = PCURVE('',#51589,#51594); -#51589 = PLANE('',#51590); -#51590 = AXIS2_PLACEMENT_3D('',#51591,#51592,#51593); -#51591 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); -#51592 = DIRECTION('',(0.5,0.866025403784,0.E+000)); -#51593 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); -#51594 = DEFINITIONAL_REPRESENTATION('',(#51595),#51599); -#51595 = LINE('',#51596,#51597); -#51596 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51597 = VECTOR('',#51598,1.); -#51598 = DIRECTION('',(0.E+000,1.)); -#51599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51600 = ORIENTED_EDGE('',*,*,#51601,.F.); -#51601 = EDGE_CURVE('',#51602,#51574,#51604,.T.); -#51602 = VERTEX_POINT('',#51603); -#51603 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); -#51604 = SURFACE_CURVE('',#51605,(#51609,#51616),.PCURVE_S1.); -#51605 = LINE('',#51606,#51607); -#51606 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); -#51607 = VECTOR('',#51608,1.); -#51608 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51609 = PCURVE('',#47630,#51610); -#51610 = DEFINITIONAL_REPRESENTATION('',(#51611),#51615); -#51611 = LINE('',#51612,#51613); -#51612 = CARTESIAN_POINT('',(0.E+000,-0.725)); -#51613 = VECTOR('',#51614,1.); -#51614 = DIRECTION('',(0.E+000,1.)); -#51615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51616 = PCURVE('',#51617,#51622); -#51617 = PLANE('',#51618); -#51618 = AXIS2_PLACEMENT_3D('',#51619,#51620,#51621); -#51619 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#51620 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51621 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51622 = DEFINITIONAL_REPRESENTATION('',(#51623),#51627); -#51623 = LINE('',#51624,#51625); -#51624 = CARTESIAN_POINT('',(-1.21,0.5)); -#51625 = VECTOR('',#51626,1.); -#51626 = DIRECTION('',(0.E+000,1.)); -#51627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51628 = ORIENTED_EDGE('',*,*,#51629,.T.); -#51629 = EDGE_CURVE('',#51602,#51630,#51632,.T.); -#51630 = VERTEX_POINT('',#51631); -#51631 = CARTESIAN_POINT('',(1.21,0.5,-1.63)); -#51632 = SURFACE_CURVE('',#51633,(#51637,#51644),.PCURVE_S1.); -#51633 = LINE('',#51634,#51635); -#51634 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); -#51635 = VECTOR('',#51636,1.); -#51636 = DIRECTION('',(0.E+000,0.E+000,1.)); -#51637 = PCURVE('',#47630,#51638); -#51638 = DEFINITIONAL_REPRESENTATION('',(#51639),#51643); -#51639 = LINE('',#51640,#51641); -#51640 = CARTESIAN_POINT('',(0.E+000,-0.725)); -#51641 = VECTOR('',#51642,1.); -#51642 = DIRECTION('',(1.,0.E+000)); -#51643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51644 = PCURVE('',#51645,#51650); -#51645 = PLANE('',#51646); -#51646 = AXIS2_PLACEMENT_3D('',#51647,#51648,#51649); -#51647 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); -#51648 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51649 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51650 = DEFINITIONAL_REPRESENTATION('',(#51651),#51655); -#51651 = LINE('',#51652,#51653); -#51652 = CARTESIAN_POINT('',(1.16,0.E+000)); -#51653 = VECTOR('',#51654,1.); -#51654 = DIRECTION('',(0.E+000,-1.)); -#51655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51656 = ORIENTED_EDGE('',*,*,#51657,.T.); -#51657 = EDGE_CURVE('',#51630,#51658,#51660,.T.); -#51658 = VERTEX_POINT('',#51659); -#51659 = CARTESIAN_POINT('',(1.21,0.92,-1.63)); -#51660 = SURFACE_CURVE('',#51661,(#51665,#51672),.PCURVE_S1.); -#51661 = LINE('',#51662,#51663); -#51662 = CARTESIAN_POINT('',(1.21,0.5,-1.63)); -#51663 = VECTOR('',#51664,1.); -#51664 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51665 = PCURVE('',#47630,#51666); -#51666 = DEFINITIONAL_REPRESENTATION('',(#51667),#51671); -#51667 = LINE('',#51668,#51669); -#51668 = CARTESIAN_POINT('',(0.72,-0.725)); -#51669 = VECTOR('',#51670,1.); -#51670 = DIRECTION('',(0.E+000,1.)); -#51671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51672 = PCURVE('',#51673,#51678); -#51673 = PLANE('',#51674); -#51674 = AXIS2_PLACEMENT_3D('',#51675,#51676,#51677); -#51675 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.63)); -#51676 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51677 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51678 = DEFINITIONAL_REPRESENTATION('',(#51679),#51683); -#51679 = LINE('',#51680,#51681); -#51680 = CARTESIAN_POINT('',(-1.21,0.5)); -#51681 = VECTOR('',#51682,1.); -#51682 = DIRECTION('',(0.E+000,1.)); -#51683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51684 = ORIENTED_EDGE('',*,*,#51685,.F.); -#51685 = EDGE_CURVE('',#51686,#51658,#51688,.T.); -#51686 = VERTEX_POINT('',#51687); -#51687 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); -#51688 = SURFACE_CURVE('',#51689,(#51693,#51700),.PCURVE_S1.); -#51689 = LINE('',#51690,#51691); -#51690 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); -#51691 = VECTOR('',#51692,1.); -#51692 = DIRECTION('',(0.E+000,0.E+000,1.)); -#51693 = PCURVE('',#47630,#51694); -#51694 = DEFINITIONAL_REPRESENTATION('',(#51695),#51699); -#51695 = LINE('',#51696,#51697); -#51696 = CARTESIAN_POINT('',(0.E+000,-0.305)); -#51697 = VECTOR('',#51698,1.); -#51698 = DIRECTION('',(1.,0.E+000)); -#51699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51700 = PCURVE('',#43400,#51701); -#51701 = DEFINITIONAL_REPRESENTATION('',(#51702),#51706); -#51702 = LINE('',#51703,#51704); -#51703 = CARTESIAN_POINT('',(1.885,0.E+000)); -#51704 = VECTOR('',#51705,1.); -#51705 = DIRECTION('',(0.E+000,1.)); -#51706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51707 = ORIENTED_EDGE('',*,*,#51708,.F.); -#51708 = EDGE_CURVE('',#47615,#51686,#51709,.T.); -#51709 = SURFACE_CURVE('',#51710,(#51714,#51721),.PCURVE_S1.); -#51710 = LINE('',#51711,#51712); -#51711 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); -#51712 = VECTOR('',#51713,1.); -#51713 = DIRECTION('',(-4.440892098501E-014,-1.,0.E+000)); -#51714 = PCURVE('',#47630,#51715); -#51715 = DEFINITIONAL_REPRESENTATION('',(#51716),#51720); -#51716 = LINE('',#51717,#51718); -#51717 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#51718 = VECTOR('',#51719,1.); -#51719 = DIRECTION('',(0.E+000,-1.)); -#51720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51721 = PCURVE('',#47656,#51722); -#51722 = DEFINITIONAL_REPRESENTATION('',(#51723),#51727); -#51723 = LINE('',#51724,#51725); -#51724 = CARTESIAN_POINT('',(-1.21,0.925)); -#51725 = VECTOR('',#51726,1.); -#51726 = DIRECTION('',(4.440892098501E-014,-1.)); -#51727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#53928 = CARTESIAN_POINT('',(1.,0.E+000)); +#53929 = CARTESIAN_POINT('',(1.519615242271,0.E+000)); +#53930 = CARTESIAN_POINT('',(1.259807621135,-0.45)); +#53931 = CARTESIAN_POINT('',(1.,-0.9)); +#53932 = CARTESIAN_POINT('',(0.740192378865,-0.45)); +#53933 = CARTESIAN_POINT('',(0.480384757729,-3.885780586188E-016)); +#53934 = CARTESIAN_POINT('',(1.,0.E+000)); +#53935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53936 = ORIENTED_EDGE('',*,*,#51417,.T.); +#53937 = ADVANCED_FACE('',(#53938),#50022,.F.); +#53938 = FACE_BOUND('',#53939,.F.); +#53939 = EDGE_LOOP('',(#53940,#53941,#53964,#53992,#54020,#54048,#54076, + #54099,#54120,#54121,#54142)); +#53940 = ORIENTED_EDGE('',*,*,#53858,.F.); +#53941 = ORIENTED_EDGE('',*,*,#53942,.T.); +#53942 = EDGE_CURVE('',#53859,#53943,#53945,.T.); +#53943 = VERTEX_POINT('',#53944); +#53944 = CARTESIAN_POINT('',(1.21,0.575,-2.65)); +#53945 = SURFACE_CURVE('',#53946,(#53950,#53957),.PCURVE_S1.); +#53946 = LINE('',#53947,#53948); +#53947 = CARTESIAN_POINT('',(1.21,0.925,-2.65)); +#53948 = VECTOR('',#53949,1.); +#53949 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#53950 = PCURVE('',#50022,#53951); +#53951 = DEFINITIONAL_REPRESENTATION('',(#53952),#53956); +#53952 = LINE('',#53953,#53954); +#53953 = CARTESIAN_POINT('',(-0.3,-0.3)); +#53954 = VECTOR('',#53955,1.); +#53955 = DIRECTION('',(0.E+000,-1.)); +#53956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53957 = PCURVE('',#53900,#53958); +#53958 = DEFINITIONAL_REPRESENTATION('',(#53959),#53963); +#53959 = LINE('',#53960,#53961); +#53960 = CARTESIAN_POINT('',(-1.21,0.925)); +#53961 = VECTOR('',#53962,1.); +#53962 = DIRECTION('',(0.E+000,-1.)); +#53963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53964 = ORIENTED_EDGE('',*,*,#53965,.F.); +#53965 = EDGE_CURVE('',#53966,#53943,#53968,.T.); +#53966 = VERTEX_POINT('',#53967); +#53967 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); +#53968 = SURFACE_CURVE('',#53969,(#53973,#53980),.PCURVE_S1.); +#53969 = LINE('',#53970,#53971); +#53970 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); +#53971 = VECTOR('',#53972,1.); +#53972 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#53973 = PCURVE('',#50022,#53974); +#53974 = DEFINITIONAL_REPRESENTATION('',(#53975),#53979); +#53975 = LINE('',#53976,#53977); +#53976 = CARTESIAN_POINT('',(0.E+000,-0.65)); +#53977 = VECTOR('',#53978,1.); +#53978 = DIRECTION('',(-1.,0.E+000)); +#53979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53980 = PCURVE('',#53981,#53986); +#53981 = PLANE('',#53982); +#53982 = AXIS2_PLACEMENT_3D('',#53983,#53984,#53985); +#53983 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); +#53984 = DIRECTION('',(0.5,0.866025403784,0.E+000)); +#53985 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); +#53986 = DEFINITIONAL_REPRESENTATION('',(#53987),#53991); +#53987 = LINE('',#53988,#53989); +#53988 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#53989 = VECTOR('',#53990,1.); +#53990 = DIRECTION('',(0.E+000,1.)); +#53991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#53992 = ORIENTED_EDGE('',*,*,#53993,.F.); +#53993 = EDGE_CURVE('',#53994,#53966,#53996,.T.); +#53994 = VERTEX_POINT('',#53995); +#53995 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); +#53996 = SURFACE_CURVE('',#53997,(#54001,#54008),.PCURVE_S1.); +#53997 = LINE('',#53998,#53999); +#53998 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); +#53999 = VECTOR('',#54000,1.); +#54000 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54001 = PCURVE('',#50022,#54002); +#54002 = DEFINITIONAL_REPRESENTATION('',(#54003),#54007); +#54003 = LINE('',#54004,#54005); +#54004 = CARTESIAN_POINT('',(0.E+000,-0.725)); +#54005 = VECTOR('',#54006,1.); +#54006 = DIRECTION('',(0.E+000,1.)); +#54007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54008 = PCURVE('',#54009,#54014); +#54009 = PLANE('',#54010); +#54010 = AXIS2_PLACEMENT_3D('',#54011,#54012,#54013); +#54011 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#54012 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54013 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54014 = DEFINITIONAL_REPRESENTATION('',(#54015),#54019); +#54015 = LINE('',#54016,#54017); +#54016 = CARTESIAN_POINT('',(-1.21,0.5)); +#54017 = VECTOR('',#54018,1.); +#54018 = DIRECTION('',(0.E+000,1.)); +#54019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54020 = ORIENTED_EDGE('',*,*,#54021,.T.); +#54021 = EDGE_CURVE('',#53994,#54022,#54024,.T.); +#54022 = VERTEX_POINT('',#54023); +#54023 = CARTESIAN_POINT('',(1.21,0.5,-1.63)); +#54024 = SURFACE_CURVE('',#54025,(#54029,#54036),.PCURVE_S1.); +#54025 = LINE('',#54026,#54027); +#54026 = CARTESIAN_POINT('',(1.21,0.5,-2.35)); +#54027 = VECTOR('',#54028,1.); +#54028 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54029 = PCURVE('',#50022,#54030); +#54030 = DEFINITIONAL_REPRESENTATION('',(#54031),#54035); +#54031 = LINE('',#54032,#54033); +#54032 = CARTESIAN_POINT('',(0.E+000,-0.725)); +#54033 = VECTOR('',#54034,1.); +#54034 = DIRECTION('',(1.,0.E+000)); +#54035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54036 = PCURVE('',#54037,#54042); +#54037 = PLANE('',#54038); +#54038 = AXIS2_PLACEMENT_3D('',#54039,#54040,#54041); +#54039 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); +#54040 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54041 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54042 = DEFINITIONAL_REPRESENTATION('',(#54043),#54047); +#54043 = LINE('',#54044,#54045); +#54044 = CARTESIAN_POINT('',(1.16,0.E+000)); +#54045 = VECTOR('',#54046,1.); +#54046 = DIRECTION('',(0.E+000,-1.)); +#54047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54048 = ORIENTED_EDGE('',*,*,#54049,.T.); +#54049 = EDGE_CURVE('',#54022,#54050,#54052,.T.); +#54050 = VERTEX_POINT('',#54051); +#54051 = CARTESIAN_POINT('',(1.21,0.92,-1.63)); +#54052 = SURFACE_CURVE('',#54053,(#54057,#54064),.PCURVE_S1.); +#54053 = LINE('',#54054,#54055); +#54054 = CARTESIAN_POINT('',(1.21,0.5,-1.63)); +#54055 = VECTOR('',#54056,1.); +#54056 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54057 = PCURVE('',#50022,#54058); +#54058 = DEFINITIONAL_REPRESENTATION('',(#54059),#54063); +#54059 = LINE('',#54060,#54061); +#54060 = CARTESIAN_POINT('',(0.72,-0.725)); +#54061 = VECTOR('',#54062,1.); +#54062 = DIRECTION('',(0.E+000,1.)); +#54063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54064 = PCURVE('',#54065,#54070); +#54065 = PLANE('',#54066); +#54066 = AXIS2_PLACEMENT_3D('',#54067,#54068,#54069); +#54067 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.63)); +#54068 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54069 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54070 = DEFINITIONAL_REPRESENTATION('',(#54071),#54075); +#54071 = LINE('',#54072,#54073); +#54072 = CARTESIAN_POINT('',(-1.21,0.5)); +#54073 = VECTOR('',#54074,1.); +#54074 = DIRECTION('',(0.E+000,1.)); +#54075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54076 = ORIENTED_EDGE('',*,*,#54077,.F.); +#54077 = EDGE_CURVE('',#54078,#54050,#54080,.T.); +#54078 = VERTEX_POINT('',#54079); +#54079 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); +#54080 = SURFACE_CURVE('',#54081,(#54085,#54092),.PCURVE_S1.); +#54081 = LINE('',#54082,#54083); +#54082 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); +#54083 = VECTOR('',#54084,1.); +#54084 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54085 = PCURVE('',#50022,#54086); +#54086 = DEFINITIONAL_REPRESENTATION('',(#54087),#54091); +#54087 = LINE('',#54088,#54089); +#54088 = CARTESIAN_POINT('',(0.E+000,-0.305)); +#54089 = VECTOR('',#54090,1.); +#54090 = DIRECTION('',(1.,0.E+000)); +#54091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54092 = PCURVE('',#45792,#54093); +#54093 = DEFINITIONAL_REPRESENTATION('',(#54094),#54098); +#54094 = LINE('',#54095,#54096); +#54095 = CARTESIAN_POINT('',(1.885,0.E+000)); +#54096 = VECTOR('',#54097,1.); +#54097 = DIRECTION('',(0.E+000,1.)); +#54098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54099 = ORIENTED_EDGE('',*,*,#54100,.F.); +#54100 = EDGE_CURVE('',#50007,#54078,#54101,.T.); +#54101 = SURFACE_CURVE('',#54102,(#54106,#54113),.PCURVE_S1.); +#54102 = LINE('',#54103,#54104); +#54103 = CARTESIAN_POINT('',(1.21,0.925,-2.35)); +#54104 = VECTOR('',#54105,1.); +#54105 = DIRECTION('',(-4.440892098501E-014,-1.,0.E+000)); +#54106 = PCURVE('',#50022,#54107); +#54107 = DEFINITIONAL_REPRESENTATION('',(#54108),#54112); +#54108 = LINE('',#54109,#54110); +#54109 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#54110 = VECTOR('',#54111,1.); +#54111 = DIRECTION('',(0.E+000,-1.)); +#54112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54113 = PCURVE('',#50048,#54114); +#54114 = DEFINITIONAL_REPRESENTATION('',(#54115),#54119); +#54115 = LINE('',#54116,#54117); +#54116 = CARTESIAN_POINT('',(-1.21,0.925)); +#54117 = VECTOR('',#54118,1.); +#54118 = DIRECTION('',(4.440892098501E-014,-1.)); +#54119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54120 = ORIENTED_EDGE('',*,*,#50006,.T.); +#54121 = ORIENTED_EDGE('',*,*,#54122,.F.); +#54122 = EDGE_CURVE('',#51447,#49979,#54123,.T.); +#54123 = SURFACE_CURVE('',#54124,(#54128,#54135),.PCURVE_S1.); +#54124 = LINE('',#54125,#54126); +#54125 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); +#54126 = VECTOR('',#54127,1.); +#54127 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54128 = PCURVE('',#50022,#54129); +#54129 = DEFINITIONAL_REPRESENTATION('',(#54130),#54134); +#54130 = LINE('',#54131,#54132); +#54131 = CARTESIAN_POINT('',(1.,0.E+000)); +#54132 = VECTOR('',#54133,1.); +#54133 = DIRECTION('',(0.E+000,-1.)); +#54134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54135 = PCURVE('',#49994,#54136); +#54136 = DEFINITIONAL_REPRESENTATION('',(#54137),#54141); +#54137 = LINE('',#54138,#54139); +#54138 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#54139 = VECTOR('',#54140,1.); +#54140 = DIRECTION('',(0.E+000,-1.)); +#54141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54142 = ORIENTED_EDGE('',*,*,#51446,.F.); +#54143 = ADVANCED_FACE('',(#54144),#53900,.T.); +#54144 = FACE_BOUND('',#54145,.F.); +#54145 = EDGE_LOOP('',(#54146,#54147,#54170,#54198,#54226,#54254,#54282, + #54309,#54337,#54365,#54393,#54420,#54448,#54476,#54504,#54525)); +#54146 = ORIENTED_EDGE('',*,*,#53885,.F.); +#54147 = ORIENTED_EDGE('',*,*,#54148,.F.); +#54148 = EDGE_CURVE('',#54149,#53886,#54151,.T.); +#54149 = VERTEX_POINT('',#54150); +#54150 = CARTESIAN_POINT('',(-1.21,0.575,-2.65)); +#54151 = SURFACE_CURVE('',#54152,(#54156,#54163),.PCURVE_S1.); +#54152 = LINE('',#54153,#54154); +#54153 = CARTESIAN_POINT('',(-1.21,0.575,-2.65)); +#54154 = VECTOR('',#54155,1.); +#54155 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54156 = PCURVE('',#53900,#54157); +#54157 = DEFINITIONAL_REPRESENTATION('',(#54158),#54162); +#54158 = LINE('',#54159,#54160); +#54159 = CARTESIAN_POINT('',(1.21,0.575)); +#54160 = VECTOR('',#54161,1.); +#54161 = DIRECTION('',(0.E+000,1.)); +#54162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54163 = PCURVE('',#49608,#54164); +#54164 = DEFINITIONAL_REPRESENTATION('',(#54165),#54169); +#54165 = LINE('',#54166,#54167); +#54166 = CARTESIAN_POINT('',(1.3,-0.65)); +#54167 = VECTOR('',#54168,1.); +#54168 = DIRECTION('',(0.E+000,1.)); +#54169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#51728 = ORIENTED_EDGE('',*,*,#47614,.T.); -#51729 = ORIENTED_EDGE('',*,*,#51730,.F.); -#51730 = EDGE_CURVE('',#49055,#47587,#51731,.T.); -#51731 = SURFACE_CURVE('',#51732,(#51736,#51743),.PCURVE_S1.); -#51732 = LINE('',#51733,#51734); -#51733 = CARTESIAN_POINT('',(1.21,1.225,-1.35)); -#51734 = VECTOR('',#51735,1.); -#51735 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51736 = PCURVE('',#47630,#51737); -#51737 = DEFINITIONAL_REPRESENTATION('',(#51738),#51742); -#51738 = LINE('',#51739,#51740); -#51739 = CARTESIAN_POINT('',(1.,0.E+000)); -#51740 = VECTOR('',#51741,1.); -#51741 = DIRECTION('',(0.E+000,-1.)); -#51742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51743 = PCURVE('',#47602,#51744); -#51744 = DEFINITIONAL_REPRESENTATION('',(#51745),#51749); -#51745 = LINE('',#51746,#51747); -#51746 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#51747 = VECTOR('',#51748,1.); -#51748 = DIRECTION('',(0.E+000,-1.)); -#51749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51750 = ORIENTED_EDGE('',*,*,#49054,.F.); -#51751 = ADVANCED_FACE('',(#51752),#51508,.T.); -#51752 = FACE_BOUND('',#51753,.F.); -#51753 = EDGE_LOOP('',(#51754,#51755,#51778,#51806,#51834,#51862,#51890, - #51917,#51945,#51973,#52001,#52028,#52056,#52084,#52112,#52133)); -#51754 = ORIENTED_EDGE('',*,*,#51493,.F.); -#51755 = ORIENTED_EDGE('',*,*,#51756,.F.); -#51756 = EDGE_CURVE('',#51757,#51494,#51759,.T.); -#51757 = VERTEX_POINT('',#51758); -#51758 = CARTESIAN_POINT('',(-1.21,0.575,-2.65)); -#51759 = SURFACE_CURVE('',#51760,(#51764,#51771),.PCURVE_S1.); -#51760 = LINE('',#51761,#51762); -#51761 = CARTESIAN_POINT('',(-1.21,0.575,-2.65)); -#51762 = VECTOR('',#51763,1.); -#51763 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51764 = PCURVE('',#51508,#51765); -#51765 = DEFINITIONAL_REPRESENTATION('',(#51766),#51770); -#51766 = LINE('',#51767,#51768); -#51767 = CARTESIAN_POINT('',(1.21,0.575)); -#51768 = VECTOR('',#51769,1.); -#51769 = DIRECTION('',(0.E+000,1.)); -#51770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51771 = PCURVE('',#47216,#51772); -#51772 = DEFINITIONAL_REPRESENTATION('',(#51773),#51777); -#51773 = LINE('',#51774,#51775); -#51774 = CARTESIAN_POINT('',(1.3,-0.65)); -#51775 = VECTOR('',#51776,1.); -#51776 = DIRECTION('',(0.E+000,1.)); -#51777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51778 = ORIENTED_EDGE('',*,*,#51779,.F.); -#51779 = EDGE_CURVE('',#51780,#51757,#51782,.T.); -#51780 = VERTEX_POINT('',#51781); -#51781 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.65)); -#51782 = SURFACE_CURVE('',#51783,(#51787,#51794),.PCURVE_S1.); -#51783 = LINE('',#51784,#51785); -#51784 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.65)); -#51785 = VECTOR('',#51786,1.); -#51786 = DIRECTION('',(0.866025403784,0.5,0.E+000)); -#51787 = PCURVE('',#51508,#51788); -#51788 = DEFINITIONAL_REPRESENTATION('',(#51789),#51793); -#51789 = LINE('',#51790,#51791); -#51790 = CARTESIAN_POINT('',(1.902820323028,0.175)); -#51791 = VECTOR('',#51792,1.); -#51792 = DIRECTION('',(-0.866025403784,0.5)); -#51793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51794 = PCURVE('',#51795,#51800); -#51795 = PLANE('',#51796); -#51796 = AXIS2_PLACEMENT_3D('',#51797,#51798,#51799); -#51797 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); -#51798 = DIRECTION('',(-0.5,0.866025403784,0.E+000)); -#51799 = DIRECTION('',(0.866025403784,0.5,0.E+000)); -#51800 = DEFINITIONAL_REPRESENTATION('',(#51801),#51805); -#51801 = LINE('',#51802,#51803); -#51802 = CARTESIAN_POINT('',(0.E+000,0.3)); -#51803 = VECTOR('',#51804,1.); -#51804 = DIRECTION('',(1.,0.E+000)); -#51805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51806 = ORIENTED_EDGE('',*,*,#51807,.F.); -#51807 = EDGE_CURVE('',#51808,#51780,#51810,.T.); -#51808 = VERTEX_POINT('',#51809); -#51809 = CARTESIAN_POINT('',(-2.45,0.175,-2.65)); -#51810 = SURFACE_CURVE('',#51811,(#51815,#51822),.PCURVE_S1.); -#51811 = LINE('',#51812,#51813); -#51812 = CARTESIAN_POINT('',(-2.45,0.175,-2.65)); -#51813 = VECTOR('',#51814,1.); -#51814 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51815 = PCURVE('',#51508,#51816); -#51816 = DEFINITIONAL_REPRESENTATION('',(#51817),#51821); -#51817 = LINE('',#51818,#51819); -#51818 = CARTESIAN_POINT('',(2.45,0.175)); -#51819 = VECTOR('',#51820,1.); -#51820 = DIRECTION('',(-1.,0.E+000)); -#51821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51822 = PCURVE('',#51823,#51828); -#51823 = PLANE('',#51824); -#51824 = AXIS2_PLACEMENT_3D('',#51825,#51826,#51827); -#51825 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); -#51826 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51827 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51828 = DEFINITIONAL_REPRESENTATION('',(#51829),#51833); -#51829 = LINE('',#51830,#51831); -#51830 = CARTESIAN_POINT('',(0.E+000,0.3)); -#51831 = VECTOR('',#51832,1.); -#51832 = DIRECTION('',(1.,0.E+000)); -#51833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51834 = ORIENTED_EDGE('',*,*,#51835,.F.); -#51835 = EDGE_CURVE('',#51836,#51808,#51838,.T.); -#51836 = VERTEX_POINT('',#51837); -#51837 = CARTESIAN_POINT('',(-3.,-0.375,-2.65)); -#51838 = SURFACE_CURVE('',#51839,(#51844,#51851),.PCURVE_S1.); -#51839 = CIRCLE('',#51840,0.55); -#51840 = AXIS2_PLACEMENT_3D('',#51841,#51842,#51843); -#51841 = CARTESIAN_POINT('',(-2.45,-0.375,-2.65)); -#51842 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51843 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51844 = PCURVE('',#51508,#51845); -#51845 = DEFINITIONAL_REPRESENTATION('',(#51846),#51850); -#51846 = CIRCLE('',#51847,0.55); -#51847 = AXIS2_PLACEMENT_2D('',#51848,#51849); -#51848 = CARTESIAN_POINT('',(2.45,-0.375)); -#51849 = DIRECTION('',(1.,0.E+000)); -#51850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51851 = PCURVE('',#51852,#51857); -#51852 = CYLINDRICAL_SURFACE('',#51853,0.55); -#51853 = AXIS2_PLACEMENT_3D('',#51854,#51855,#51856); -#51854 = CARTESIAN_POINT('',(-2.45,-0.375,-2.35)); -#51855 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51856 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51857 = DEFINITIONAL_REPRESENTATION('',(#51858),#51861); -#51858 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51859,#51860),.UNSPECIFIED., +#54170 = ORIENTED_EDGE('',*,*,#54171,.F.); +#54171 = EDGE_CURVE('',#54172,#54149,#54174,.T.); +#54172 = VERTEX_POINT('',#54173); +#54173 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.65)); +#54174 = SURFACE_CURVE('',#54175,(#54179,#54186),.PCURVE_S1.); +#54175 = LINE('',#54176,#54177); +#54176 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.65)); +#54177 = VECTOR('',#54178,1.); +#54178 = DIRECTION('',(0.866025403784,0.5,0.E+000)); +#54179 = PCURVE('',#53900,#54180); +#54180 = DEFINITIONAL_REPRESENTATION('',(#54181),#54185); +#54181 = LINE('',#54182,#54183); +#54182 = CARTESIAN_POINT('',(1.902820323028,0.175)); +#54183 = VECTOR('',#54184,1.); +#54184 = DIRECTION('',(-0.866025403784,0.5)); +#54185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54186 = PCURVE('',#54187,#54192); +#54187 = PLANE('',#54188); +#54188 = AXIS2_PLACEMENT_3D('',#54189,#54190,#54191); +#54189 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); +#54190 = DIRECTION('',(-0.5,0.866025403784,0.E+000)); +#54191 = DIRECTION('',(0.866025403784,0.5,0.E+000)); +#54192 = DEFINITIONAL_REPRESENTATION('',(#54193),#54197); +#54193 = LINE('',#54194,#54195); +#54194 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54195 = VECTOR('',#54196,1.); +#54196 = DIRECTION('',(1.,0.E+000)); +#54197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54198 = ORIENTED_EDGE('',*,*,#54199,.F.); +#54199 = EDGE_CURVE('',#54200,#54172,#54202,.T.); +#54200 = VERTEX_POINT('',#54201); +#54201 = CARTESIAN_POINT('',(-2.45,0.175,-2.65)); +#54202 = SURFACE_CURVE('',#54203,(#54207,#54214),.PCURVE_S1.); +#54203 = LINE('',#54204,#54205); +#54204 = CARTESIAN_POINT('',(-2.45,0.175,-2.65)); +#54205 = VECTOR('',#54206,1.); +#54206 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54207 = PCURVE('',#53900,#54208); +#54208 = DEFINITIONAL_REPRESENTATION('',(#54209),#54213); +#54209 = LINE('',#54210,#54211); +#54210 = CARTESIAN_POINT('',(2.45,0.175)); +#54211 = VECTOR('',#54212,1.); +#54212 = DIRECTION('',(-1.,0.E+000)); +#54213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54214 = PCURVE('',#54215,#54220); +#54215 = PLANE('',#54216); +#54216 = AXIS2_PLACEMENT_3D('',#54217,#54218,#54219); +#54217 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); +#54218 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54219 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54220 = DEFINITIONAL_REPRESENTATION('',(#54221),#54225); +#54221 = LINE('',#54222,#54223); +#54222 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54223 = VECTOR('',#54224,1.); +#54224 = DIRECTION('',(1.,0.E+000)); +#54225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54226 = ORIENTED_EDGE('',*,*,#54227,.F.); +#54227 = EDGE_CURVE('',#54228,#54200,#54230,.T.); +#54228 = VERTEX_POINT('',#54229); +#54229 = CARTESIAN_POINT('',(-3.,-0.375,-2.65)); +#54230 = SURFACE_CURVE('',#54231,(#54236,#54243),.PCURVE_S1.); +#54231 = CIRCLE('',#54232,0.55); +#54232 = AXIS2_PLACEMENT_3D('',#54233,#54234,#54235); +#54233 = CARTESIAN_POINT('',(-2.45,-0.375,-2.65)); +#54234 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54235 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54236 = PCURVE('',#53900,#54237); +#54237 = DEFINITIONAL_REPRESENTATION('',(#54238),#54242); +#54238 = CIRCLE('',#54239,0.55); +#54239 = AXIS2_PLACEMENT_2D('',#54240,#54241); +#54240 = CARTESIAN_POINT('',(2.45,-0.375)); +#54241 = DIRECTION('',(1.,0.E+000)); +#54242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54243 = PCURVE('',#54244,#54249); +#54244 = CYLINDRICAL_SURFACE('',#54245,0.55); +#54245 = AXIS2_PLACEMENT_3D('',#54246,#54247,#54248); +#54246 = CARTESIAN_POINT('',(-2.45,-0.375,-2.35)); +#54247 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54248 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54249 = DEFINITIONAL_REPRESENTATION('',(#54250),#54253); +#54250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54251,#54252),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#51859 = CARTESIAN_POINT('',(0.E+000,0.3)); -#51860 = CARTESIAN_POINT('',(1.570796326795,0.3)); -#51861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51862 = ORIENTED_EDGE('',*,*,#51863,.F.); -#51863 = EDGE_CURVE('',#51864,#51836,#51866,.T.); -#51864 = VERTEX_POINT('',#51865); -#51865 = CARTESIAN_POINT('',(-3.,-0.925,-2.65)); -#51866 = SURFACE_CURVE('',#51867,(#51871,#51878),.PCURVE_S1.); -#51867 = LINE('',#51868,#51869); -#51868 = CARTESIAN_POINT('',(-3.,-0.925,-2.65)); -#51869 = VECTOR('',#51870,1.); -#51870 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51871 = PCURVE('',#51508,#51872); -#51872 = DEFINITIONAL_REPRESENTATION('',(#51873),#51877); -#51873 = LINE('',#51874,#51875); -#51874 = CARTESIAN_POINT('',(3.,-0.925)); -#51875 = VECTOR('',#51876,1.); -#51876 = DIRECTION('',(0.E+000,1.)); -#51877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51878 = PCURVE('',#51879,#51884); -#51879 = PLANE('',#51880); -#51880 = AXIS2_PLACEMENT_3D('',#51881,#51882,#51883); -#51881 = CARTESIAN_POINT('',(-3.,-1.225,-2.35)); -#51882 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51883 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51884 = DEFINITIONAL_REPRESENTATION('',(#51885),#51889); -#51885 = LINE('',#51886,#51887); -#51886 = CARTESIAN_POINT('',(0.3,0.3)); -#51887 = VECTOR('',#51888,1.); -#51888 = DIRECTION('',(1.,0.E+000)); -#51889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51890 = ORIENTED_EDGE('',*,*,#51891,.F.); -#51891 = EDGE_CURVE('',#51892,#51864,#51894,.T.); -#51892 = VERTEX_POINT('',#51893); -#51893 = CARTESIAN_POINT('',(-1.925,-0.925,-2.65)); -#51894 = SURFACE_CURVE('',#51895,(#51899,#51906),.PCURVE_S1.); -#51895 = LINE('',#51896,#51897); -#51896 = CARTESIAN_POINT('',(-1.925,-0.925,-2.65)); -#51897 = VECTOR('',#51898,1.); -#51898 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51899 = PCURVE('',#51508,#51900); -#51900 = DEFINITIONAL_REPRESENTATION('',(#51901),#51905); -#51901 = LINE('',#51902,#51903); -#51902 = CARTESIAN_POINT('',(1.925,-0.925)); -#51903 = VECTOR('',#51904,1.); -#51904 = DIRECTION('',(1.,0.E+000)); -#51905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51906 = PCURVE('',#51907,#51912); -#51907 = CYLINDRICAL_SURFACE('',#51908,0.3); -#51908 = AXIS2_PLACEMENT_3D('',#51909,#51910,#51911); -#51909 = CARTESIAN_POINT('',(-1.909485368452,-0.925,-2.35)); -#51910 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51911 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#51912 = DEFINITIONAL_REPRESENTATION('',(#51913),#51916); -#51913 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#51914,#51915),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); -#51914 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#51915 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); -#51916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51917 = ORIENTED_EDGE('',*,*,#51918,.F.); -#51918 = EDGE_CURVE('',#51919,#51892,#51921,.T.); -#51919 = VERTEX_POINT('',#51920); -#51920 = CARTESIAN_POINT('',(-1.925,-0.725,-2.65)); -#51921 = SURFACE_CURVE('',#51922,(#51926,#51933),.PCURVE_S1.); -#51922 = LINE('',#51923,#51924); -#51923 = CARTESIAN_POINT('',(-1.925,-0.725,-2.65)); -#51924 = VECTOR('',#51925,1.); -#51925 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51926 = PCURVE('',#51508,#51927); -#51927 = DEFINITIONAL_REPRESENTATION('',(#51928),#51932); -#51928 = LINE('',#51929,#51930); -#51929 = CARTESIAN_POINT('',(1.925,-0.725)); -#51930 = VECTOR('',#51931,1.); -#51931 = DIRECTION('',(0.E+000,-1.)); -#51932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51933 = PCURVE('',#51934,#51939); -#51934 = PLANE('',#51935); -#51935 = AXIS2_PLACEMENT_3D('',#51936,#51937,#51938); -#51936 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); -#51937 = DIRECTION('',(1.,0.E+000,0.E+000)); -#51938 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51939 = DEFINITIONAL_REPRESENTATION('',(#51940),#51944); -#51940 = LINE('',#51941,#51942); -#51941 = CARTESIAN_POINT('',(0.E+000,0.3)); -#51942 = VECTOR('',#51943,1.); -#51943 = DIRECTION('',(1.,0.E+000)); -#51944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51945 = ORIENTED_EDGE('',*,*,#51946,.F.); -#51946 = EDGE_CURVE('',#51947,#51919,#51949,.T.); -#51947 = VERTEX_POINT('',#51948); -#51948 = CARTESIAN_POINT('',(1.925,-0.725,-2.65)); -#51949 = SURFACE_CURVE('',#51950,(#51954,#51961),.PCURVE_S1.); -#51950 = LINE('',#51951,#51952); -#51951 = CARTESIAN_POINT('',(1.925,-0.725,-2.65)); -#51952 = VECTOR('',#51953,1.); -#51953 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51954 = PCURVE('',#51508,#51955); -#51955 = DEFINITIONAL_REPRESENTATION('',(#51956),#51960); -#51956 = LINE('',#51957,#51958); -#51957 = CARTESIAN_POINT('',(-1.925,-0.725)); -#51958 = VECTOR('',#51959,1.); -#51959 = DIRECTION('',(1.,0.E+000)); -#51960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51961 = PCURVE('',#51962,#51967); -#51962 = PLANE('',#51963); -#51963 = AXIS2_PLACEMENT_3D('',#51964,#51965,#51966); -#51964 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); -#51965 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#51966 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51967 = DEFINITIONAL_REPRESENTATION('',(#51968),#51972); -#51968 = LINE('',#51969,#51970); -#51969 = CARTESIAN_POINT('',(0.E+000,0.3)); -#51970 = VECTOR('',#51971,1.); -#51971 = DIRECTION('',(1.,0.E+000)); -#51972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51973 = ORIENTED_EDGE('',*,*,#51974,.F.); -#51974 = EDGE_CURVE('',#51975,#51947,#51977,.T.); -#51975 = VERTEX_POINT('',#51976); -#51976 = CARTESIAN_POINT('',(1.925,-0.925,-2.65)); -#51977 = SURFACE_CURVE('',#51978,(#51982,#51989),.PCURVE_S1.); -#51978 = LINE('',#51979,#51980); -#51979 = CARTESIAN_POINT('',(1.925,-0.925,-2.65)); -#51980 = VECTOR('',#51981,1.); -#51981 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51982 = PCURVE('',#51508,#51983); -#51983 = DEFINITIONAL_REPRESENTATION('',(#51984),#51988); -#51984 = LINE('',#51985,#51986); -#51985 = CARTESIAN_POINT('',(-1.925,-0.925)); -#51986 = VECTOR('',#51987,1.); -#51987 = DIRECTION('',(0.E+000,1.)); -#51988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#51989 = PCURVE('',#51990,#51995); -#51990 = PLANE('',#51991); -#51991 = AXIS2_PLACEMENT_3D('',#51992,#51993,#51994); -#51992 = CARTESIAN_POINT('',(1.925,-1.225,-2.35)); -#51993 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#51994 = DIRECTION('',(0.E+000,1.,0.E+000)); -#51995 = DEFINITIONAL_REPRESENTATION('',(#51996),#52000); -#51996 = LINE('',#51997,#51998); -#51997 = CARTESIAN_POINT('',(0.3,0.3)); -#51998 = VECTOR('',#51999,1.); -#51999 = DIRECTION('',(1.,0.E+000)); -#52000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52001 = ORIENTED_EDGE('',*,*,#52002,.F.); -#52002 = EDGE_CURVE('',#52003,#51975,#52005,.T.); -#52003 = VERTEX_POINT('',#52004); -#52004 = CARTESIAN_POINT('',(3.,-0.925,-2.65)); -#52005 = SURFACE_CURVE('',#52006,(#52010,#52017),.PCURVE_S1.); -#52006 = LINE('',#52007,#52008); -#52007 = CARTESIAN_POINT('',(3.,-0.925,-2.65)); -#52008 = VECTOR('',#52009,1.); -#52009 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52010 = PCURVE('',#51508,#52011); -#52011 = DEFINITIONAL_REPRESENTATION('',(#52012),#52016); -#52012 = LINE('',#52013,#52014); -#52013 = CARTESIAN_POINT('',(-3.,-0.925)); -#52014 = VECTOR('',#52015,1.); -#52015 = DIRECTION('',(1.,0.E+000)); -#52016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52017 = PCURVE('',#52018,#52023); -#52018 = CYLINDRICAL_SURFACE('',#52019,0.3); -#52019 = AXIS2_PLACEMENT_3D('',#52020,#52021,#52022); -#52020 = CARTESIAN_POINT('',(3.015514631548,-0.925,-2.35)); -#52021 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52022 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52023 = DEFINITIONAL_REPRESENTATION('',(#52024),#52027); -#52024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52025,#52026),.UNSPECIFIED., +#54251 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54252 = CARTESIAN_POINT('',(1.570796326795,0.3)); +#54253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54254 = ORIENTED_EDGE('',*,*,#54255,.F.); +#54255 = EDGE_CURVE('',#54256,#54228,#54258,.T.); +#54256 = VERTEX_POINT('',#54257); +#54257 = CARTESIAN_POINT('',(-3.,-0.925,-2.65)); +#54258 = SURFACE_CURVE('',#54259,(#54263,#54270),.PCURVE_S1.); +#54259 = LINE('',#54260,#54261); +#54260 = CARTESIAN_POINT('',(-3.,-0.925,-2.65)); +#54261 = VECTOR('',#54262,1.); +#54262 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54263 = PCURVE('',#53900,#54264); +#54264 = DEFINITIONAL_REPRESENTATION('',(#54265),#54269); +#54265 = LINE('',#54266,#54267); +#54266 = CARTESIAN_POINT('',(3.,-0.925)); +#54267 = VECTOR('',#54268,1.); +#54268 = DIRECTION('',(0.E+000,1.)); +#54269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54270 = PCURVE('',#54271,#54276); +#54271 = PLANE('',#54272); +#54272 = AXIS2_PLACEMENT_3D('',#54273,#54274,#54275); +#54273 = CARTESIAN_POINT('',(-3.,-1.225,-2.35)); +#54274 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54275 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54276 = DEFINITIONAL_REPRESENTATION('',(#54277),#54281); +#54277 = LINE('',#54278,#54279); +#54278 = CARTESIAN_POINT('',(0.3,0.3)); +#54279 = VECTOR('',#54280,1.); +#54280 = DIRECTION('',(1.,0.E+000)); +#54281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54282 = ORIENTED_EDGE('',*,*,#54283,.F.); +#54283 = EDGE_CURVE('',#54284,#54256,#54286,.T.); +#54284 = VERTEX_POINT('',#54285); +#54285 = CARTESIAN_POINT('',(-1.925,-0.925,-2.65)); +#54286 = SURFACE_CURVE('',#54287,(#54291,#54298),.PCURVE_S1.); +#54287 = LINE('',#54288,#54289); +#54288 = CARTESIAN_POINT('',(-1.925,-0.925,-2.65)); +#54289 = VECTOR('',#54290,1.); +#54290 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54291 = PCURVE('',#53900,#54292); +#54292 = DEFINITIONAL_REPRESENTATION('',(#54293),#54297); +#54293 = LINE('',#54294,#54295); +#54294 = CARTESIAN_POINT('',(1.925,-0.925)); +#54295 = VECTOR('',#54296,1.); +#54296 = DIRECTION('',(1.,0.E+000)); +#54297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54298 = PCURVE('',#54299,#54304); +#54299 = CYLINDRICAL_SURFACE('',#54300,0.3); +#54300 = AXIS2_PLACEMENT_3D('',#54301,#54302,#54303); +#54301 = CARTESIAN_POINT('',(-1.909485368452,-0.925,-2.35)); +#54302 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54303 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54304 = DEFINITIONAL_REPRESENTATION('',(#54305),#54308); +#54305 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54306,#54307),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); -#52025 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#52026 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); -#52027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52028 = ORIENTED_EDGE('',*,*,#52029,.F.); -#52029 = EDGE_CURVE('',#52030,#52003,#52032,.T.); -#52030 = VERTEX_POINT('',#52031); -#52031 = CARTESIAN_POINT('',(3.,-0.375,-2.65)); -#52032 = SURFACE_CURVE('',#52033,(#52037,#52044),.PCURVE_S1.); -#52033 = LINE('',#52034,#52035); -#52034 = CARTESIAN_POINT('',(3.,-0.375,-2.65)); -#52035 = VECTOR('',#52036,1.); -#52036 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52037 = PCURVE('',#51508,#52038); -#52038 = DEFINITIONAL_REPRESENTATION('',(#52039),#52043); -#52039 = LINE('',#52040,#52041); -#52040 = CARTESIAN_POINT('',(-3.,-0.375)); -#52041 = VECTOR('',#52042,1.); -#52042 = DIRECTION('',(0.E+000,-1.)); -#52043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52044 = PCURVE('',#52045,#52050); -#52045 = PLANE('',#52046); -#52046 = AXIS2_PLACEMENT_3D('',#52047,#52048,#52049); -#52047 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); -#52048 = DIRECTION('',(1.,0.E+000,0.E+000)); -#52049 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52050 = DEFINITIONAL_REPRESENTATION('',(#52051),#52055); -#52051 = LINE('',#52052,#52053); -#52052 = CARTESIAN_POINT('',(0.E+000,0.3)); -#52053 = VECTOR('',#52054,1.); -#52054 = DIRECTION('',(1.,0.E+000)); -#52055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52056 = ORIENTED_EDGE('',*,*,#52057,.F.); -#52057 = EDGE_CURVE('',#52058,#52030,#52060,.T.); -#52058 = VERTEX_POINT('',#52059); -#52059 = CARTESIAN_POINT('',(2.45,0.175,-2.65)); -#52060 = SURFACE_CURVE('',#52061,(#52066,#52073),.PCURVE_S1.); -#52061 = CIRCLE('',#52062,0.55); -#52062 = AXIS2_PLACEMENT_3D('',#52063,#52064,#52065); -#52063 = CARTESIAN_POINT('',(2.45,-0.375,-2.65)); -#52064 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52065 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52066 = PCURVE('',#51508,#52067); -#52067 = DEFINITIONAL_REPRESENTATION('',(#52068),#52072); -#52068 = CIRCLE('',#52069,0.55); -#52069 = AXIS2_PLACEMENT_2D('',#52070,#52071); -#52070 = CARTESIAN_POINT('',(-2.45,-0.375)); -#52071 = DIRECTION('',(0.E+000,1.)); -#52072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#54306 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#54307 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); +#54308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54309 = ORIENTED_EDGE('',*,*,#54310,.F.); +#54310 = EDGE_CURVE('',#54311,#54284,#54313,.T.); +#54311 = VERTEX_POINT('',#54312); +#54312 = CARTESIAN_POINT('',(-1.925,-0.725,-2.65)); +#54313 = SURFACE_CURVE('',#54314,(#54318,#54325),.PCURVE_S1.); +#54314 = LINE('',#54315,#54316); +#54315 = CARTESIAN_POINT('',(-1.925,-0.725,-2.65)); +#54316 = VECTOR('',#54317,1.); +#54317 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54318 = PCURVE('',#53900,#54319); +#54319 = DEFINITIONAL_REPRESENTATION('',(#54320),#54324); +#54320 = LINE('',#54321,#54322); +#54321 = CARTESIAN_POINT('',(1.925,-0.725)); +#54322 = VECTOR('',#54323,1.); +#54323 = DIRECTION('',(0.E+000,-1.)); +#54324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52073 = PCURVE('',#52074,#52079); -#52074 = CYLINDRICAL_SURFACE('',#52075,0.55); -#52075 = AXIS2_PLACEMENT_3D('',#52076,#52077,#52078); -#52076 = CARTESIAN_POINT('',(2.45,-0.375,-2.35)); -#52077 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52078 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52079 = DEFINITIONAL_REPRESENTATION('',(#52080),#52083); -#52080 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52081,#52082),.UNSPECIFIED., +#54325 = PCURVE('',#54326,#54331); +#54326 = PLANE('',#54327); +#54327 = AXIS2_PLACEMENT_3D('',#54328,#54329,#54330); +#54328 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); +#54329 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54330 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54331 = DEFINITIONAL_REPRESENTATION('',(#54332),#54336); +#54332 = LINE('',#54333,#54334); +#54333 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54334 = VECTOR('',#54335,1.); +#54335 = DIRECTION('',(1.,0.E+000)); +#54336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54337 = ORIENTED_EDGE('',*,*,#54338,.F.); +#54338 = EDGE_CURVE('',#54339,#54311,#54341,.T.); +#54339 = VERTEX_POINT('',#54340); +#54340 = CARTESIAN_POINT('',(1.925,-0.725,-2.65)); +#54341 = SURFACE_CURVE('',#54342,(#54346,#54353),.PCURVE_S1.); +#54342 = LINE('',#54343,#54344); +#54343 = CARTESIAN_POINT('',(1.925,-0.725,-2.65)); +#54344 = VECTOR('',#54345,1.); +#54345 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54346 = PCURVE('',#53900,#54347); +#54347 = DEFINITIONAL_REPRESENTATION('',(#54348),#54352); +#54348 = LINE('',#54349,#54350); +#54349 = CARTESIAN_POINT('',(-1.925,-0.725)); +#54350 = VECTOR('',#54351,1.); +#54351 = DIRECTION('',(1.,0.E+000)); +#54352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54353 = PCURVE('',#54354,#54359); +#54354 = PLANE('',#54355); +#54355 = AXIS2_PLACEMENT_3D('',#54356,#54357,#54358); +#54356 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); +#54357 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54358 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54359 = DEFINITIONAL_REPRESENTATION('',(#54360),#54364); +#54360 = LINE('',#54361,#54362); +#54361 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54362 = VECTOR('',#54363,1.); +#54363 = DIRECTION('',(1.,0.E+000)); +#54364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54365 = ORIENTED_EDGE('',*,*,#54366,.F.); +#54366 = EDGE_CURVE('',#54367,#54339,#54369,.T.); +#54367 = VERTEX_POINT('',#54368); +#54368 = CARTESIAN_POINT('',(1.925,-0.925,-2.65)); +#54369 = SURFACE_CURVE('',#54370,(#54374,#54381),.PCURVE_S1.); +#54370 = LINE('',#54371,#54372); +#54371 = CARTESIAN_POINT('',(1.925,-0.925,-2.65)); +#54372 = VECTOR('',#54373,1.); +#54373 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54374 = PCURVE('',#53900,#54375); +#54375 = DEFINITIONAL_REPRESENTATION('',(#54376),#54380); +#54376 = LINE('',#54377,#54378); +#54377 = CARTESIAN_POINT('',(-1.925,-0.925)); +#54378 = VECTOR('',#54379,1.); +#54379 = DIRECTION('',(0.E+000,1.)); +#54380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54381 = PCURVE('',#54382,#54387); +#54382 = PLANE('',#54383); +#54383 = AXIS2_PLACEMENT_3D('',#54384,#54385,#54386); +#54384 = CARTESIAN_POINT('',(1.925,-1.225,-2.35)); +#54385 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54386 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54387 = DEFINITIONAL_REPRESENTATION('',(#54388),#54392); +#54388 = LINE('',#54389,#54390); +#54389 = CARTESIAN_POINT('',(0.3,0.3)); +#54390 = VECTOR('',#54391,1.); +#54391 = DIRECTION('',(1.,0.E+000)); +#54392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54393 = ORIENTED_EDGE('',*,*,#54394,.F.); +#54394 = EDGE_CURVE('',#54395,#54367,#54397,.T.); +#54395 = VERTEX_POINT('',#54396); +#54396 = CARTESIAN_POINT('',(3.,-0.925,-2.65)); +#54397 = SURFACE_CURVE('',#54398,(#54402,#54409),.PCURVE_S1.); +#54398 = LINE('',#54399,#54400); +#54399 = CARTESIAN_POINT('',(3.,-0.925,-2.65)); +#54400 = VECTOR('',#54401,1.); +#54401 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54402 = PCURVE('',#53900,#54403); +#54403 = DEFINITIONAL_REPRESENTATION('',(#54404),#54408); +#54404 = LINE('',#54405,#54406); +#54405 = CARTESIAN_POINT('',(-3.,-0.925)); +#54406 = VECTOR('',#54407,1.); +#54407 = DIRECTION('',(1.,0.E+000)); +#54408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54409 = PCURVE('',#54410,#54415); +#54410 = CYLINDRICAL_SURFACE('',#54411,0.3); +#54411 = AXIS2_PLACEMENT_3D('',#54412,#54413,#54414); +#54412 = CARTESIAN_POINT('',(3.015514631548,-0.925,-2.35)); +#54413 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54414 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54415 = DEFINITIONAL_REPRESENTATION('',(#54416),#54419); +#54416 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54417,#54418),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); +#54417 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#54418 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); +#54419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54420 = ORIENTED_EDGE('',*,*,#54421,.F.); +#54421 = EDGE_CURVE('',#54422,#54395,#54424,.T.); +#54422 = VERTEX_POINT('',#54423); +#54423 = CARTESIAN_POINT('',(3.,-0.375,-2.65)); +#54424 = SURFACE_CURVE('',#54425,(#54429,#54436),.PCURVE_S1.); +#54425 = LINE('',#54426,#54427); +#54426 = CARTESIAN_POINT('',(3.,-0.375,-2.65)); +#54427 = VECTOR('',#54428,1.); +#54428 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54429 = PCURVE('',#53900,#54430); +#54430 = DEFINITIONAL_REPRESENTATION('',(#54431),#54435); +#54431 = LINE('',#54432,#54433); +#54432 = CARTESIAN_POINT('',(-3.,-0.375)); +#54433 = VECTOR('',#54434,1.); +#54434 = DIRECTION('',(0.E+000,-1.)); +#54435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54436 = PCURVE('',#54437,#54442); +#54437 = PLANE('',#54438); +#54438 = AXIS2_PLACEMENT_3D('',#54439,#54440,#54441); +#54439 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); +#54440 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54441 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54442 = DEFINITIONAL_REPRESENTATION('',(#54443),#54447); +#54443 = LINE('',#54444,#54445); +#54444 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54445 = VECTOR('',#54446,1.); +#54446 = DIRECTION('',(1.,0.E+000)); +#54447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54448 = ORIENTED_EDGE('',*,*,#54449,.F.); +#54449 = EDGE_CURVE('',#54450,#54422,#54452,.T.); +#54450 = VERTEX_POINT('',#54451); +#54451 = CARTESIAN_POINT('',(2.45,0.175,-2.65)); +#54452 = SURFACE_CURVE('',#54453,(#54458,#54465),.PCURVE_S1.); +#54453 = CIRCLE('',#54454,0.55); +#54454 = AXIS2_PLACEMENT_3D('',#54455,#54456,#54457); +#54455 = CARTESIAN_POINT('',(2.45,-0.375,-2.65)); +#54456 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54457 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54458 = PCURVE('',#53900,#54459); +#54459 = DEFINITIONAL_REPRESENTATION('',(#54460),#54464); +#54460 = CIRCLE('',#54461,0.55); +#54461 = AXIS2_PLACEMENT_2D('',#54462,#54463); +#54462 = CARTESIAN_POINT('',(-2.45,-0.375)); +#54463 = DIRECTION('',(0.E+000,1.)); +#54464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54465 = PCURVE('',#54466,#54471); +#54466 = CYLINDRICAL_SURFACE('',#54467,0.55); +#54467 = AXIS2_PLACEMENT_3D('',#54468,#54469,#54470); +#54468 = CARTESIAN_POINT('',(2.45,-0.375,-2.35)); +#54469 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54470 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54471 = DEFINITIONAL_REPRESENTATION('',(#54472),#54475); +#54472 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54473,#54474),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#52081 = CARTESIAN_POINT('',(1.570796326795,0.3)); -#52082 = CARTESIAN_POINT('',(3.14159265359,0.3)); -#52083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52084 = ORIENTED_EDGE('',*,*,#52085,.F.); -#52085 = EDGE_CURVE('',#52086,#52058,#52088,.T.); -#52086 = VERTEX_POINT('',#52087); -#52087 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.65)); -#52088 = SURFACE_CURVE('',#52089,(#52093,#52100),.PCURVE_S1.); -#52089 = LINE('',#52090,#52091); -#52090 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.65)); -#52091 = VECTOR('',#52092,1.); -#52092 = DIRECTION('',(1.,0.E+000,0.E+000)); -#52093 = PCURVE('',#51508,#52094); -#52094 = DEFINITIONAL_REPRESENTATION('',(#52095),#52099); -#52095 = LINE('',#52096,#52097); -#52096 = CARTESIAN_POINT('',(-1.902820323028,0.175)); -#52097 = VECTOR('',#52098,1.); -#52098 = DIRECTION('',(-1.,0.E+000)); -#52099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52100 = PCURVE('',#52101,#52106); -#52101 = PLANE('',#52102); -#52102 = AXIS2_PLACEMENT_3D('',#52103,#52104,#52105); -#52103 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); -#52104 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52105 = DIRECTION('',(1.,0.E+000,0.E+000)); -#52106 = DEFINITIONAL_REPRESENTATION('',(#52107),#52111); -#52107 = LINE('',#52108,#52109); -#52108 = CARTESIAN_POINT('',(0.E+000,0.3)); -#52109 = VECTOR('',#52110,1.); -#52110 = DIRECTION('',(1.,0.E+000)); -#52111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52112 = ORIENTED_EDGE('',*,*,#52113,.F.); -#52113 = EDGE_CURVE('',#51551,#52086,#52114,.T.); -#52114 = SURFACE_CURVE('',#52115,(#52119,#52126),.PCURVE_S1.); -#52115 = LINE('',#52116,#52117); -#52116 = CARTESIAN_POINT('',(1.21,0.575,-2.65)); -#52117 = VECTOR('',#52118,1.); -#52118 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); -#52119 = PCURVE('',#51508,#52120); -#52120 = DEFINITIONAL_REPRESENTATION('',(#52121),#52125); -#52121 = LINE('',#52122,#52123); -#52122 = CARTESIAN_POINT('',(-1.21,0.575)); -#52123 = VECTOR('',#52124,1.); -#52124 = DIRECTION('',(-0.866025403784,-0.5)); -#52125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52126 = PCURVE('',#51589,#52127); -#52127 = DEFINITIONAL_REPRESENTATION('',(#52128),#52132); -#52128 = LINE('',#52129,#52130); -#52129 = CARTESIAN_POINT('',(0.E+000,0.3)); -#52130 = VECTOR('',#52131,1.); -#52131 = DIRECTION('',(1.,0.E+000)); -#52132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52133 = ORIENTED_EDGE('',*,*,#51550,.F.); -#52134 = ADVANCED_FACE('',(#52135),#47216,.F.); -#52135 = FACE_BOUND('',#52136,.F.); -#52136 = EDGE_LOOP('',(#52137,#52138,#52139,#52160,#52161,#52184,#52207, - #52235,#52263,#52291,#52312)); -#52137 = ORIENTED_EDGE('',*,*,#51520,.F.); -#52138 = ORIENTED_EDGE('',*,*,#49383,.F.); -#52139 = ORIENTED_EDGE('',*,*,#52140,.T.); -#52140 = EDGE_CURVE('',#49361,#47201,#52141,.T.); -#52141 = SURFACE_CURVE('',#52142,(#52146,#52153),.PCURVE_S1.); -#52142 = LINE('',#52143,#52144); -#52143 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); -#52144 = VECTOR('',#52145,1.); -#52145 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52146 = PCURVE('',#47216,#52147); -#52147 = DEFINITIONAL_REPRESENTATION('',(#52148),#52152); -#52148 = LINE('',#52149,#52150); -#52149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#52150 = VECTOR('',#52151,1.); -#52151 = DIRECTION('',(0.E+000,-1.)); -#52152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52153 = PCURVE('',#47244,#52154); -#52154 = DEFINITIONAL_REPRESENTATION('',(#52155),#52159); -#52155 = LINE('',#52156,#52157); -#52156 = CARTESIAN_POINT('',(1.16,0.E+000)); -#52157 = VECTOR('',#52158,1.); -#52158 = DIRECTION('',(0.E+000,-1.)); -#52159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52160 = ORIENTED_EDGE('',*,*,#47198,.F.); -#52161 = ORIENTED_EDGE('',*,*,#52162,.F.); -#52162 = EDGE_CURVE('',#52163,#47199,#52165,.T.); -#52163 = VERTEX_POINT('',#52164); -#52164 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); -#52165 = SURFACE_CURVE('',#52166,(#52170,#52177),.PCURVE_S1.); -#52166 = LINE('',#52167,#52168); -#52167 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); -#52168 = VECTOR('',#52169,1.); -#52169 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52170 = PCURVE('',#47216,#52171); -#52171 = DEFINITIONAL_REPRESENTATION('',(#52172),#52176); -#52172 = LINE('',#52173,#52174); -#52173 = CARTESIAN_POINT('',(1.,-0.305)); -#52174 = VECTOR('',#52175,1.); -#52175 = DIRECTION('',(0.E+000,1.)); -#52176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52177 = PCURVE('',#47656,#52178); -#52178 = DEFINITIONAL_REPRESENTATION('',(#52179),#52183); -#52179 = LINE('',#52180,#52181); -#52180 = CARTESIAN_POINT('',(1.21,0.92)); -#52181 = VECTOR('',#52182,1.); -#52182 = DIRECTION('',(0.E+000,1.)); -#52183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52184 = ORIENTED_EDGE('',*,*,#52185,.T.); -#52185 = EDGE_CURVE('',#52163,#52186,#52188,.T.); -#52186 = VERTEX_POINT('',#52187); -#52187 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); -#52188 = SURFACE_CURVE('',#52189,(#52193,#52200),.PCURVE_S1.); -#52189 = LINE('',#52190,#52191); -#52190 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); -#52191 = VECTOR('',#52192,1.); -#52192 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52193 = PCURVE('',#47216,#52194); -#52194 = DEFINITIONAL_REPRESENTATION('',(#52195),#52199); -#52195 = LINE('',#52196,#52197); -#52196 = CARTESIAN_POINT('',(1.,-0.305)); -#52197 = VECTOR('',#52198,1.); -#52198 = DIRECTION('',(-1.,0.E+000)); -#52199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52200 = PCURVE('',#43400,#52201); -#52201 = DEFINITIONAL_REPRESENTATION('',(#52202),#52206); -#52202 = LINE('',#52203,#52204); -#52203 = CARTESIAN_POINT('',(4.305,0.E+000)); -#52204 = VECTOR('',#52205,1.); -#52205 = DIRECTION('',(0.E+000,1.)); -#52206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52207 = ORIENTED_EDGE('',*,*,#52208,.T.); -#52208 = EDGE_CURVE('',#52186,#52209,#52211,.T.); -#52209 = VERTEX_POINT('',#52210); -#52210 = CARTESIAN_POINT('',(-1.21,0.5,-1.63)); -#52211 = SURFACE_CURVE('',#52212,(#52216,#52223),.PCURVE_S1.); -#52212 = LINE('',#52213,#52214); -#52213 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); -#52214 = VECTOR('',#52215,1.); -#52215 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52216 = PCURVE('',#47216,#52217); -#52217 = DEFINITIONAL_REPRESENTATION('',(#52218),#52222); -#52218 = LINE('',#52219,#52220); -#52219 = CARTESIAN_POINT('',(0.28,-0.305)); -#52220 = VECTOR('',#52221,1.); -#52221 = DIRECTION('',(0.E+000,-1.)); -#52222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52223 = PCURVE('',#52224,#52229); -#52224 = PLANE('',#52225); -#52225 = AXIS2_PLACEMENT_3D('',#52226,#52227,#52228); -#52226 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.63)); -#52227 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52228 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52229 = DEFINITIONAL_REPRESENTATION('',(#52230),#52234); -#52230 = LINE('',#52231,#52232); -#52231 = CARTESIAN_POINT('',(1.21,0.92)); -#52232 = VECTOR('',#52233,1.); -#52233 = DIRECTION('',(0.E+000,-1.)); -#52234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52235 = ORIENTED_EDGE('',*,*,#52236,.F.); -#52236 = EDGE_CURVE('',#52237,#52209,#52239,.T.); -#52237 = VERTEX_POINT('',#52238); -#52238 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); -#52239 = SURFACE_CURVE('',#52240,(#52244,#52251),.PCURVE_S1.); -#52240 = LINE('',#52241,#52242); -#52241 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); -#52242 = VECTOR('',#52243,1.); -#52243 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52244 = PCURVE('',#47216,#52245); -#52245 = DEFINITIONAL_REPRESENTATION('',(#52246),#52250); -#52246 = LINE('',#52247,#52248); -#52247 = CARTESIAN_POINT('',(1.,-0.725)); -#52248 = VECTOR('',#52249,1.); -#52249 = DIRECTION('',(-1.,0.E+000)); -#52250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52251 = PCURVE('',#52252,#52257); -#52252 = PLANE('',#52253); -#52253 = AXIS2_PLACEMENT_3D('',#52254,#52255,#52256); -#52254 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); -#52255 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52256 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52257 = DEFINITIONAL_REPRESENTATION('',(#52258),#52262); -#52258 = LINE('',#52259,#52260); -#52259 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#52260 = VECTOR('',#52261,1.); -#52261 = DIRECTION('',(0.E+000,-1.)); -#52262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52263 = ORIENTED_EDGE('',*,*,#52264,.F.); -#52264 = EDGE_CURVE('',#52265,#52237,#52267,.T.); -#52265 = VERTEX_POINT('',#52266); -#52266 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); -#52267 = SURFACE_CURVE('',#52268,(#52272,#52279),.PCURVE_S1.); -#52268 = LINE('',#52269,#52270); -#52269 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); -#52270 = VECTOR('',#52271,1.); -#52271 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52272 = PCURVE('',#47216,#52273); -#52273 = DEFINITIONAL_REPRESENTATION('',(#52274),#52278); -#52274 = LINE('',#52275,#52276); -#52275 = CARTESIAN_POINT('',(1.,-0.65)); -#52276 = VECTOR('',#52277,1.); -#52277 = DIRECTION('',(0.E+000,-1.)); -#52278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52279 = PCURVE('',#52280,#52285); -#52280 = PLANE('',#52281); -#52281 = AXIS2_PLACEMENT_3D('',#52282,#52283,#52284); -#52282 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#52283 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52284 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#52285 = DEFINITIONAL_REPRESENTATION('',(#52286),#52290); -#52286 = LINE('',#52287,#52288); -#52287 = CARTESIAN_POINT('',(1.21,0.575)); -#52288 = VECTOR('',#52289,1.); -#52289 = DIRECTION('',(0.E+000,-1.)); -#52290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#54473 = CARTESIAN_POINT('',(1.570796326795,0.3)); +#54474 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#54475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54476 = ORIENTED_EDGE('',*,*,#54477,.F.); +#54477 = EDGE_CURVE('',#54478,#54450,#54480,.T.); +#54478 = VERTEX_POINT('',#54479); +#54479 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.65)); +#54480 = SURFACE_CURVE('',#54481,(#54485,#54492),.PCURVE_S1.); +#54481 = LINE('',#54482,#54483); +#54482 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.65)); +#54483 = VECTOR('',#54484,1.); +#54484 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54485 = PCURVE('',#53900,#54486); +#54486 = DEFINITIONAL_REPRESENTATION('',(#54487),#54491); +#54487 = LINE('',#54488,#54489); +#54488 = CARTESIAN_POINT('',(-1.902820323028,0.175)); +#54489 = VECTOR('',#54490,1.); +#54490 = DIRECTION('',(-1.,0.E+000)); +#54491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54492 = PCURVE('',#54493,#54498); +#54493 = PLANE('',#54494); +#54494 = AXIS2_PLACEMENT_3D('',#54495,#54496,#54497); +#54495 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); +#54496 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54497 = DIRECTION('',(1.,0.E+000,0.E+000)); +#54498 = DEFINITIONAL_REPRESENTATION('',(#54499),#54503); +#54499 = LINE('',#54500,#54501); +#54500 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54501 = VECTOR('',#54502,1.); +#54502 = DIRECTION('',(1.,0.E+000)); +#54503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54504 = ORIENTED_EDGE('',*,*,#54505,.F.); +#54505 = EDGE_CURVE('',#53943,#54478,#54506,.T.); +#54506 = SURFACE_CURVE('',#54507,(#54511,#54518),.PCURVE_S1.); +#54507 = LINE('',#54508,#54509); +#54508 = CARTESIAN_POINT('',(1.21,0.575,-2.65)); +#54509 = VECTOR('',#54510,1.); +#54510 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); +#54511 = PCURVE('',#53900,#54512); +#54512 = DEFINITIONAL_REPRESENTATION('',(#54513),#54517); +#54513 = LINE('',#54514,#54515); +#54514 = CARTESIAN_POINT('',(-1.21,0.575)); +#54515 = VECTOR('',#54516,1.); +#54516 = DIRECTION('',(-0.866025403784,-0.5)); +#54517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54518 = PCURVE('',#53981,#54519); +#54519 = DEFINITIONAL_REPRESENTATION('',(#54520),#54524); +#54520 = LINE('',#54521,#54522); +#54521 = CARTESIAN_POINT('',(0.E+000,0.3)); +#54522 = VECTOR('',#54523,1.); +#54523 = DIRECTION('',(1.,0.E+000)); +#54524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54525 = ORIENTED_EDGE('',*,*,#53942,.F.); +#54526 = ADVANCED_FACE('',(#54527),#49608,.F.); +#54527 = FACE_BOUND('',#54528,.F.); +#54528 = EDGE_LOOP('',(#54529,#54530,#54531,#54552,#54553,#54576,#54599, + #54627,#54655,#54683,#54704)); +#54529 = ORIENTED_EDGE('',*,*,#53912,.F.); +#54530 = ORIENTED_EDGE('',*,*,#51775,.F.); +#54531 = ORIENTED_EDGE('',*,*,#54532,.T.); +#54532 = EDGE_CURVE('',#51753,#49593,#54533,.T.); +#54533 = SURFACE_CURVE('',#54534,(#54538,#54545),.PCURVE_S1.); +#54534 = LINE('',#54535,#54536); +#54535 = CARTESIAN_POINT('',(-1.21,1.225,-1.35)); +#54536 = VECTOR('',#54537,1.); +#54537 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54538 = PCURVE('',#49608,#54539); +#54539 = DEFINITIONAL_REPRESENTATION('',(#54540),#54544); +#54540 = LINE('',#54541,#54542); +#54541 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#54542 = VECTOR('',#54543,1.); +#54543 = DIRECTION('',(0.E+000,-1.)); +#54544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54545 = PCURVE('',#49636,#54546); +#54546 = DEFINITIONAL_REPRESENTATION('',(#54547),#54551); +#54547 = LINE('',#54548,#54549); +#54548 = CARTESIAN_POINT('',(1.16,0.E+000)); +#54549 = VECTOR('',#54550,1.); +#54550 = DIRECTION('',(0.E+000,-1.)); +#54551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54552 = ORIENTED_EDGE('',*,*,#49590,.F.); +#54553 = ORIENTED_EDGE('',*,*,#54554,.F.); +#54554 = EDGE_CURVE('',#54555,#49591,#54557,.T.); +#54555 = VERTEX_POINT('',#54556); +#54556 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); +#54557 = SURFACE_CURVE('',#54558,(#54562,#54569),.PCURVE_S1.); +#54558 = LINE('',#54559,#54560); +#54559 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); +#54560 = VECTOR('',#54561,1.); +#54561 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54562 = PCURVE('',#49608,#54563); +#54563 = DEFINITIONAL_REPRESENTATION('',(#54564),#54568); +#54564 = LINE('',#54565,#54566); +#54565 = CARTESIAN_POINT('',(1.,-0.305)); +#54566 = VECTOR('',#54567,1.); +#54567 = DIRECTION('',(0.E+000,1.)); +#54568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54569 = PCURVE('',#50048,#54570); +#54570 = DEFINITIONAL_REPRESENTATION('',(#54571),#54575); +#54571 = LINE('',#54572,#54573); +#54572 = CARTESIAN_POINT('',(1.21,0.92)); +#54573 = VECTOR('',#54574,1.); +#54574 = DIRECTION('',(0.E+000,1.)); +#54575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54576 = ORIENTED_EDGE('',*,*,#54577,.T.); +#54577 = EDGE_CURVE('',#54555,#54578,#54580,.T.); +#54578 = VERTEX_POINT('',#54579); +#54579 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); +#54580 = SURFACE_CURVE('',#54581,(#54585,#54592),.PCURVE_S1.); +#54581 = LINE('',#54582,#54583); +#54582 = CARTESIAN_POINT('',(-1.21,0.92,-2.35)); +#54583 = VECTOR('',#54584,1.); +#54584 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54585 = PCURVE('',#49608,#54586); +#54586 = DEFINITIONAL_REPRESENTATION('',(#54587),#54591); +#54587 = LINE('',#54588,#54589); +#54588 = CARTESIAN_POINT('',(1.,-0.305)); +#54589 = VECTOR('',#54590,1.); +#54590 = DIRECTION('',(-1.,0.E+000)); +#54591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52291 = ORIENTED_EDGE('',*,*,#52292,.T.); -#52292 = EDGE_CURVE('',#52265,#51757,#52293,.T.); -#52293 = SURFACE_CURVE('',#52294,(#52298,#52305),.PCURVE_S1.); -#52294 = LINE('',#52295,#52296); -#52295 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); -#52296 = VECTOR('',#52297,1.); -#52297 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52298 = PCURVE('',#47216,#52299); -#52299 = DEFINITIONAL_REPRESENTATION('',(#52300),#52304); -#52300 = LINE('',#52301,#52302); -#52301 = CARTESIAN_POINT('',(1.,-0.65)); -#52302 = VECTOR('',#52303,1.); -#52303 = DIRECTION('',(1.,0.E+000)); -#52304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52305 = PCURVE('',#51795,#52306); -#52306 = DEFINITIONAL_REPRESENTATION('',(#52307),#52311); -#52307 = LINE('',#52308,#52309); -#52308 = CARTESIAN_POINT('',(0.8,0.E+000)); -#52309 = VECTOR('',#52310,1.); -#52310 = DIRECTION('',(0.E+000,1.)); -#52311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52312 = ORIENTED_EDGE('',*,*,#51756,.T.); -#52313 = ADVANCED_FACE('',(#52314),#47244,.F.); -#52314 = FACE_BOUND('',#52315,.F.); -#52315 = EDGE_LOOP('',(#52316,#52317,#52338,#52339)); -#52316 = ORIENTED_EDGE('',*,*,#49360,.F.); -#52317 = ORIENTED_EDGE('',*,*,#52318,.T.); -#52318 = EDGE_CURVE('',#49338,#47229,#52319,.T.); -#52319 = SURFACE_CURVE('',#52320,(#52324,#52331),.PCURVE_S1.); -#52320 = LINE('',#52321,#52322); -#52321 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); -#52322 = VECTOR('',#52323,1.); -#52323 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#52324 = PCURVE('',#47244,#52325); -#52325 = DEFINITIONAL_REPRESENTATION('',(#52326),#52330); -#52326 = LINE('',#52327,#52328); -#52327 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#52328 = VECTOR('',#52329,1.); -#52329 = DIRECTION('',(0.E+000,-1.)); -#52330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52331 = PCURVE('',#47272,#52332); -#52332 = DEFINITIONAL_REPRESENTATION('',(#52333),#52337); -#52333 = LINE('',#52334,#52335); -#52334 = CARTESIAN_POINT('',(1.,0.E+000)); -#52335 = VECTOR('',#52336,1.); -#52336 = DIRECTION('',(0.E+000,-1.)); -#52337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52338 = ORIENTED_EDGE('',*,*,#47228,.T.); -#52339 = ORIENTED_EDGE('',*,*,#52140,.F.); -#52340 = ADVANCED_FACE('',(#52341),#47272,.F.); -#52341 = FACE_BOUND('',#52342,.F.); -#52342 = EDGE_LOOP('',(#52343,#52364,#52365,#52366)); -#52343 = ORIENTED_EDGE('',*,*,#52344,.F.); -#52344 = EDGE_CURVE('',#47257,#49315,#52345,.T.); -#52345 = SURFACE_CURVE('',#52346,(#52350,#52357),.PCURVE_S1.); -#52346 = LINE('',#52347,#52348); -#52347 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); -#52348 = VECTOR('',#52349,1.); -#52349 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52350 = PCURVE('',#47272,#52351); -#52351 = DEFINITIONAL_REPRESENTATION('',(#52352),#52356); -#52352 = LINE('',#52353,#52354); -#52353 = CARTESIAN_POINT('',(0.7,-0.3)); -#52354 = VECTOR('',#52355,1.); -#52355 = DIRECTION('',(0.E+000,1.)); -#52356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52357 = PCURVE('',#47300,#52358); -#52358 = DEFINITIONAL_REPRESENTATION('',(#52359),#52363); -#52359 = LINE('',#52360,#52361); -#52360 = CARTESIAN_POINT('',(2.37,0.925)); -#52361 = VECTOR('',#52362,1.); -#52362 = DIRECTION('',(0.E+000,1.)); -#52363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52364 = ORIENTED_EDGE('',*,*,#47256,.T.); -#52365 = ORIENTED_EDGE('',*,*,#52318,.F.); -#52366 = ORIENTED_EDGE('',*,*,#49337,.F.); -#52367 = ADVANCED_FACE('',(#52368),#47546,.F.); -#52368 = FACE_BOUND('',#52369,.F.); -#52369 = EDGE_LOOP('',(#52370,#52422,#52450,#52471,#52472,#52493,#52494, - #52521)); -#52370 = ORIENTED_EDGE('',*,*,#52371,.F.); -#52371 = EDGE_CURVE('',#52372,#52374,#52376,.T.); -#52372 = VERTEX_POINT('',#52373); -#52373 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); -#52374 = VERTEX_POINT('',#52375); -#52375 = CARTESIAN_POINT('',(1.819483496816,0.596612030348,-1.65)); -#52376 = SURFACE_CURVE('',#52377,(#52381,#52388),.PCURVE_S1.); -#52377 = LINE('',#52378,#52379); -#52378 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); -#52379 = VECTOR('',#52380,1.); -#52380 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52381 = PCURVE('',#47546,#52382); -#52382 = DEFINITIONAL_REPRESENTATION('',(#52383),#52387); -#52383 = LINE('',#52384,#52385); -#52384 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635)); -#52385 = VECTOR('',#52386,1.); -#52386 = DIRECTION('',(-0.573576436351,-0.819152044289)); -#52387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52388 = PCURVE('',#52389,#52394); -#52389 = CYLINDRICAL_SURFACE('',#52390,0.1); -#52390 = AXIS2_PLACEMENT_3D('',#52391,#52392,#52393); -#52391 = CARTESIAN_POINT('',(1.6347692869,0.860411261057,-1.75)); -#52392 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52393 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52394 = DEFINITIONAL_REPRESENTATION('',(#52395),#52421); -#52395 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52396,#52397,#52398,#52399, - #52400,#52401,#52402,#52403,#52404,#52405,#52406,#52407,#52408, - #52409,#52410,#52411,#52412,#52413,#52414,#52415,#52416,#52417, - #52418,#52419,#52420),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#54592 = PCURVE('',#45792,#54593); +#54593 = DEFINITIONAL_REPRESENTATION('',(#54594),#54598); +#54594 = LINE('',#54595,#54596); +#54595 = CARTESIAN_POINT('',(4.305,0.E+000)); +#54596 = VECTOR('',#54597,1.); +#54597 = DIRECTION('',(0.E+000,1.)); +#54598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54599 = ORIENTED_EDGE('',*,*,#54600,.T.); +#54600 = EDGE_CURVE('',#54578,#54601,#54603,.T.); +#54601 = VERTEX_POINT('',#54602); +#54602 = CARTESIAN_POINT('',(-1.21,0.5,-1.63)); +#54603 = SURFACE_CURVE('',#54604,(#54608,#54615),.PCURVE_S1.); +#54604 = LINE('',#54605,#54606); +#54605 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); +#54606 = VECTOR('',#54607,1.); +#54607 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54608 = PCURVE('',#49608,#54609); +#54609 = DEFINITIONAL_REPRESENTATION('',(#54610),#54614); +#54610 = LINE('',#54611,#54612); +#54611 = CARTESIAN_POINT('',(0.28,-0.305)); +#54612 = VECTOR('',#54613,1.); +#54613 = DIRECTION('',(0.E+000,-1.)); +#54614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54615 = PCURVE('',#54616,#54621); +#54616 = PLANE('',#54617); +#54617 = AXIS2_PLACEMENT_3D('',#54618,#54619,#54620); +#54618 = CARTESIAN_POINT('',(0.E+000,0.E+000,-1.63)); +#54619 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54620 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54621 = DEFINITIONAL_REPRESENTATION('',(#54622),#54626); +#54622 = LINE('',#54623,#54624); +#54623 = CARTESIAN_POINT('',(1.21,0.92)); +#54624 = VECTOR('',#54625,1.); +#54625 = DIRECTION('',(0.E+000,-1.)); +#54626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54627 = ORIENTED_EDGE('',*,*,#54628,.F.); +#54628 = EDGE_CURVE('',#54629,#54601,#54631,.T.); +#54629 = VERTEX_POINT('',#54630); +#54630 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); +#54631 = SURFACE_CURVE('',#54632,(#54636,#54643),.PCURVE_S1.); +#54632 = LINE('',#54633,#54634); +#54633 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); +#54634 = VECTOR('',#54635,1.); +#54635 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54636 = PCURVE('',#49608,#54637); +#54637 = DEFINITIONAL_REPRESENTATION('',(#54638),#54642); +#54638 = LINE('',#54639,#54640); +#54639 = CARTESIAN_POINT('',(1.,-0.725)); +#54640 = VECTOR('',#54641,1.); +#54641 = DIRECTION('',(-1.,0.E+000)); +#54642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54643 = PCURVE('',#54644,#54649); +#54644 = PLANE('',#54645); +#54645 = AXIS2_PLACEMENT_3D('',#54646,#54647,#54648); +#54646 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); +#54647 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54648 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54649 = DEFINITIONAL_REPRESENTATION('',(#54650),#54654); +#54650 = LINE('',#54651,#54652); +#54651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#54652 = VECTOR('',#54653,1.); +#54653 = DIRECTION('',(0.E+000,-1.)); +#54654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54655 = ORIENTED_EDGE('',*,*,#54656,.F.); +#54656 = EDGE_CURVE('',#54657,#54629,#54659,.T.); +#54657 = VERTEX_POINT('',#54658); +#54658 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); +#54659 = SURFACE_CURVE('',#54660,(#54664,#54671),.PCURVE_S1.); +#54660 = LINE('',#54661,#54662); +#54661 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); +#54662 = VECTOR('',#54663,1.); +#54663 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54664 = PCURVE('',#49608,#54665); +#54665 = DEFINITIONAL_REPRESENTATION('',(#54666),#54670); +#54666 = LINE('',#54667,#54668); +#54667 = CARTESIAN_POINT('',(1.,-0.65)); +#54668 = VECTOR('',#54669,1.); +#54669 = DIRECTION('',(0.E+000,-1.)); +#54670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54671 = PCURVE('',#54672,#54677); +#54672 = PLANE('',#54673); +#54673 = AXIS2_PLACEMENT_3D('',#54674,#54675,#54676); +#54674 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#54675 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54676 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#54677 = DEFINITIONAL_REPRESENTATION('',(#54678),#54682); +#54678 = LINE('',#54679,#54680); +#54679 = CARTESIAN_POINT('',(1.21,0.575)); +#54680 = VECTOR('',#54681,1.); +#54681 = DIRECTION('',(0.E+000,-1.)); +#54682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54683 = ORIENTED_EDGE('',*,*,#54684,.T.); +#54684 = EDGE_CURVE('',#54657,#54149,#54685,.T.); +#54685 = SURFACE_CURVE('',#54686,(#54690,#54697),.PCURVE_S1.); +#54686 = LINE('',#54687,#54688); +#54687 = CARTESIAN_POINT('',(-1.21,0.575,-2.35)); +#54688 = VECTOR('',#54689,1.); +#54689 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54690 = PCURVE('',#49608,#54691); +#54691 = DEFINITIONAL_REPRESENTATION('',(#54692),#54696); +#54692 = LINE('',#54693,#54694); +#54693 = CARTESIAN_POINT('',(1.,-0.65)); +#54694 = VECTOR('',#54695,1.); +#54695 = DIRECTION('',(1.,0.E+000)); +#54696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54697 = PCURVE('',#54187,#54698); +#54698 = DEFINITIONAL_REPRESENTATION('',(#54699),#54703); +#54699 = LINE('',#54700,#54701); +#54700 = CARTESIAN_POINT('',(0.8,0.E+000)); +#54701 = VECTOR('',#54702,1.); +#54702 = DIRECTION('',(0.E+000,1.)); +#54703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54704 = ORIENTED_EDGE('',*,*,#54148,.T.); +#54705 = ADVANCED_FACE('',(#54706),#49636,.F.); +#54706 = FACE_BOUND('',#54707,.F.); +#54707 = EDGE_LOOP('',(#54708,#54709,#54730,#54731)); +#54708 = ORIENTED_EDGE('',*,*,#51752,.F.); +#54709 = ORIENTED_EDGE('',*,*,#54710,.T.); +#54710 = EDGE_CURVE('',#51730,#49621,#54711,.T.); +#54711 = SURFACE_CURVE('',#54712,(#54716,#54723),.PCURVE_S1.); +#54712 = LINE('',#54713,#54714); +#54713 = CARTESIAN_POINT('',(-2.37,1.225,-1.35)); +#54714 = VECTOR('',#54715,1.); +#54715 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#54716 = PCURVE('',#49636,#54717); +#54717 = DEFINITIONAL_REPRESENTATION('',(#54718),#54722); +#54718 = LINE('',#54719,#54720); +#54719 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#54720 = VECTOR('',#54721,1.); +#54721 = DIRECTION('',(0.E+000,-1.)); +#54722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54723 = PCURVE('',#49664,#54724); +#54724 = DEFINITIONAL_REPRESENTATION('',(#54725),#54729); +#54725 = LINE('',#54726,#54727); +#54726 = CARTESIAN_POINT('',(1.,0.E+000)); +#54727 = VECTOR('',#54728,1.); +#54728 = DIRECTION('',(0.E+000,-1.)); +#54729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54730 = ORIENTED_EDGE('',*,*,#49620,.T.); +#54731 = ORIENTED_EDGE('',*,*,#54532,.F.); +#54732 = ADVANCED_FACE('',(#54733),#49664,.F.); +#54733 = FACE_BOUND('',#54734,.F.); +#54734 = EDGE_LOOP('',(#54735,#54756,#54757,#54758)); +#54735 = ORIENTED_EDGE('',*,*,#54736,.F.); +#54736 = EDGE_CURVE('',#49649,#51707,#54737,.T.); +#54737 = SURFACE_CURVE('',#54738,(#54742,#54749),.PCURVE_S1.); +#54738 = LINE('',#54739,#54740); +#54739 = CARTESIAN_POINT('',(-2.37,0.925,-1.65)); +#54740 = VECTOR('',#54741,1.); +#54741 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54742 = PCURVE('',#49664,#54743); +#54743 = DEFINITIONAL_REPRESENTATION('',(#54744),#54748); +#54744 = LINE('',#54745,#54746); +#54745 = CARTESIAN_POINT('',(0.7,-0.3)); +#54746 = VECTOR('',#54747,1.); +#54747 = DIRECTION('',(0.E+000,1.)); +#54748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54749 = PCURVE('',#49692,#54750); +#54750 = DEFINITIONAL_REPRESENTATION('',(#54751),#54755); +#54751 = LINE('',#54752,#54753); +#54752 = CARTESIAN_POINT('',(2.37,0.925)); +#54753 = VECTOR('',#54754,1.); +#54754 = DIRECTION('',(0.E+000,1.)); +#54755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54756 = ORIENTED_EDGE('',*,*,#49648,.T.); +#54757 = ORIENTED_EDGE('',*,*,#54710,.F.); +#54758 = ORIENTED_EDGE('',*,*,#51729,.F.); +#54759 = ADVANCED_FACE('',(#54760),#49938,.F.); +#54760 = FACE_BOUND('',#54761,.F.); +#54761 = EDGE_LOOP('',(#54762,#54814,#54842,#54863,#54864,#54885,#54886, + #54913)); +#54762 = ORIENTED_EDGE('',*,*,#54763,.F.); +#54763 = EDGE_CURVE('',#54764,#54766,#54768,.T.); +#54764 = VERTEX_POINT('',#54765); +#54765 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); +#54766 = VERTEX_POINT('',#54767); +#54767 = CARTESIAN_POINT('',(1.819483496816,0.596612030348,-1.65)); +#54768 = SURFACE_CURVE('',#54769,(#54773,#54780),.PCURVE_S1.); +#54769 = LINE('',#54770,#54771); +#54770 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); +#54771 = VECTOR('',#54772,1.); +#54772 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#54773 = PCURVE('',#49938,#54774); +#54774 = DEFINITIONAL_REPRESENTATION('',(#54775),#54779); +#54775 = LINE('',#54776,#54777); +#54776 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635)); +#54777 = VECTOR('',#54778,1.); +#54778 = DIRECTION('',(-0.573576436351,-0.819152044289)); +#54779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54780 = PCURVE('',#54781,#54786); +#54781 = CYLINDRICAL_SURFACE('',#54782,0.1); +#54782 = AXIS2_PLACEMENT_3D('',#54783,#54784,#54785); +#54783 = CARTESIAN_POINT('',(1.6347692869,0.860411261057,-1.75)); +#54784 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#54785 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54786 = DEFINITIONAL_REPRESENTATION('',(#54787),#54813); +#54787 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54788,#54789,#54790,#54791, + #54792,#54793,#54794,#54795,#54796,#54797,#54798,#54799,#54800, + #54801,#54802,#54803,#54804,#54805,#54806,#54807,#54808,#54809, + #54810,#54811,#54812),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363636E-002, 2.727272727271E-002,4.090909090907E-002,5.454545454542E-002, 6.818181818178E-002,8.181818181813E-002,9.545454545449E-002, @@ -65078,222 +68067,222 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#52396 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); -#52397 = CARTESIAN_POINT('',(-1.516120562428E-012,2.658485192938E-002)); -#52398 = CARTESIAN_POINT('',(-2.925659714492E-012,3.567576102028E-002)); -#52399 = CARTESIAN_POINT('',(-2.359001882724E-012,4.931212465664E-002)); -#52400 = CARTESIAN_POINT('',(-2.511768570912E-012,6.294848829299E-002)); -#52401 = CARTESIAN_POINT('',(-2.471800542025E-012,7.658485192935E-002)); -#52402 = CARTESIAN_POINT('',(-2.480682326222E-012,9.022121556571E-002)); -#52403 = CARTESIAN_POINT('',(-2.478905969383E-012,0.103857579202)); -#52404 = CARTESIAN_POINT('',(-2.481570504642E-012,0.117493942838)); -#52405 = CARTESIAN_POINT('',(-2.484235039901E-012,0.131130306475)); -#52406 = CARTESIAN_POINT('',(-2.478017790963E-012,0.144766670111)); -#52407 = CARTESIAN_POINT('',(-2.483346861482E-012,0.158403033747)); -#52408 = CARTESIAN_POINT('',(-2.478905969383E-012,0.172039397384)); -#52409 = CARTESIAN_POINT('',(-2.479794147803E-012,0.18567576102)); -#52410 = CARTESIAN_POINT('',(-2.478905969383E-012,0.199312124657)); -#52411 = CARTESIAN_POINT('',(-2.479794147803E-012,0.212948488293)); -#52412 = CARTESIAN_POINT('',(-2.478905969383E-012,0.226584851929)); -#52413 = CARTESIAN_POINT('',(-2.480682326222E-012,0.240221215566)); -#52414 = CARTESIAN_POINT('',(-2.480682326222E-012,0.253857579202)); -#52415 = CARTESIAN_POINT('',(-2.472688720445E-012,0.267493942838)); -#52416 = CARTESIAN_POINT('',(-2.510880392492E-012,0.281130306475)); -#52417 = CARTESIAN_POINT('',(-2.359890061143E-012,0.294766670111)); -#52418 = CARTESIAN_POINT('',(-2.926547892912E-012,0.308403033747)); -#52419 = CARTESIAN_POINT('',(-1.515232384008E-012,0.317493942838)); -#52420 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#52421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#54788 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); +#54789 = CARTESIAN_POINT('',(-1.516120562428E-012,2.658485192938E-002)); +#54790 = CARTESIAN_POINT('',(-2.925659714492E-012,3.567576102028E-002)); +#54791 = CARTESIAN_POINT('',(-2.359001882724E-012,4.931212465664E-002)); +#54792 = CARTESIAN_POINT('',(-2.511768570912E-012,6.294848829299E-002)); +#54793 = CARTESIAN_POINT('',(-2.471800542025E-012,7.658485192935E-002)); +#54794 = CARTESIAN_POINT('',(-2.480682326222E-012,9.022121556571E-002)); +#54795 = CARTESIAN_POINT('',(-2.478905969383E-012,0.103857579202)); +#54796 = CARTESIAN_POINT('',(-2.481570504642E-012,0.117493942838)); +#54797 = CARTESIAN_POINT('',(-2.484235039901E-012,0.131130306475)); +#54798 = CARTESIAN_POINT('',(-2.478017790963E-012,0.144766670111)); +#54799 = CARTESIAN_POINT('',(-2.483346861482E-012,0.158403033747)); +#54800 = CARTESIAN_POINT('',(-2.478905969383E-012,0.172039397384)); +#54801 = CARTESIAN_POINT('',(-2.479794147803E-012,0.18567576102)); +#54802 = CARTESIAN_POINT('',(-2.478905969383E-012,0.199312124657)); +#54803 = CARTESIAN_POINT('',(-2.479794147803E-012,0.212948488293)); +#54804 = CARTESIAN_POINT('',(-2.478905969383E-012,0.226584851929)); +#54805 = CARTESIAN_POINT('',(-2.480682326222E-012,0.240221215566)); +#54806 = CARTESIAN_POINT('',(-2.480682326222E-012,0.253857579202)); +#54807 = CARTESIAN_POINT('',(-2.472688720445E-012,0.267493942838)); +#54808 = CARTESIAN_POINT('',(-2.510880392492E-012,0.281130306475)); +#54809 = CARTESIAN_POINT('',(-2.359890061143E-012,0.294766670111)); +#54810 = CARTESIAN_POINT('',(-2.926547892912E-012,0.308403033747)); +#54811 = CARTESIAN_POINT('',(-1.515232384008E-012,0.317493942838)); +#54812 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#54813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54814 = ORIENTED_EDGE('',*,*,#54815,.T.); +#54815 = EDGE_CURVE('',#54764,#54816,#54818,.T.); +#54816 = VERTEX_POINT('',#54817); +#54817 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-1.65)); +#54818 = SURFACE_CURVE('',#54819,(#54823,#54830),.PCURVE_S1.); +#54819 = LINE('',#54820,#54821); +#54820 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); +#54821 = VECTOR('',#54822,1.); +#54822 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); +#54823 = PCURVE('',#49938,#54824); +#54824 = DEFINITIONAL_REPRESENTATION('',(#54825),#54829); +#54825 = LINE('',#54826,#54827); +#54826 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635)); +#54827 = VECTOR('',#54828,1.); +#54828 = DIRECTION('',(-0.819152044289,0.573576436351)); +#54829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52422 = ORIENTED_EDGE('',*,*,#52423,.T.); -#52423 = EDGE_CURVE('',#52372,#52424,#52426,.T.); -#52424 = VERTEX_POINT('',#52425); -#52425 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-1.65)); -#52426 = SURFACE_CURVE('',#52427,(#52431,#52438),.PCURVE_S1.); -#52427 = LINE('',#52428,#52429); -#52428 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.65)); -#52429 = VECTOR('',#52430,1.); -#52430 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); -#52431 = PCURVE('',#47546,#52432); -#52432 = DEFINITIONAL_REPRESENTATION('',(#52433),#52437); -#52433 = LINE('',#52434,#52435); -#52434 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635)); -#52435 = VECTOR('',#52436,1.); -#52436 = DIRECTION('',(-0.819152044289,0.573576436351)); -#52437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52438 = PCURVE('',#52439,#52444); -#52439 = PLANE('',#52440); -#52440 = AXIS2_PLACEMENT_3D('',#52441,#52442,#52443); -#52441 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.35)); -#52442 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#52443 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); -#52444 = DEFINITIONAL_REPRESENTATION('',(#52445),#52449); -#52445 = LINE('',#52446,#52447); -#52446 = CARTESIAN_POINT('',(0.1,-0.7)); -#52447 = VECTOR('',#52448,1.); -#52448 = DIRECTION('',(1.,0.E+000)); -#52449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52450 = ORIENTED_EDGE('',*,*,#52451,.T.); -#52451 = EDGE_CURVE('',#52424,#49124,#52452,.T.); -#52452 = SURFACE_CURVE('',#52453,(#52458,#52465),.PCURVE_S1.); -#52453 = CIRCLE('',#52454,0.2); -#52454 = AXIS2_PLACEMENT_3D('',#52455,#52456,#52457); -#52455 = CARTESIAN_POINT('',(2.256940242224,1.025,-1.65)); -#52456 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52457 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#52458 = PCURVE('',#47546,#52459); -#52459 = DEFINITIONAL_REPRESENTATION('',(#52460),#52464); -#52460 = CIRCLE('',#52461,0.2); -#52461 = AXIS2_PLACEMENT_2D('',#52462,#52463); -#52462 = CARTESIAN_POINT('',(-2.256940242224,1.025)); -#52463 = DIRECTION('',(0.573576436351,0.819152044289)); -#52464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52465 = PCURVE('',#49162,#52466); -#52466 = DEFINITIONAL_REPRESENTATION('',(#52467),#52470); -#52467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52468,#52469),.UNSPECIFIED., +#54830 = PCURVE('',#54831,#54836); +#54831 = PLANE('',#54832); +#54832 = AXIS2_PLACEMENT_3D('',#54833,#54834,#54835); +#54833 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.35)); +#54834 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#54835 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); +#54836 = DEFINITIONAL_REPRESENTATION('',(#54837),#54841); +#54837 = LINE('',#54838,#54839); +#54838 = CARTESIAN_POINT('',(0.1,-0.7)); +#54839 = VECTOR('',#54840,1.); +#54840 = DIRECTION('',(1.,0.E+000)); +#54841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54842 = ORIENTED_EDGE('',*,*,#54843,.T.); +#54843 = EDGE_CURVE('',#54816,#51516,#54844,.T.); +#54844 = SURFACE_CURVE('',#54845,(#54850,#54857),.PCURVE_S1.); +#54845 = CIRCLE('',#54846,0.2); +#54846 = AXIS2_PLACEMENT_3D('',#54847,#54848,#54849); +#54847 = CARTESIAN_POINT('',(2.256940242224,1.025,-1.65)); +#54848 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#54849 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#54850 = PCURVE('',#49938,#54851); +#54851 = DEFINITIONAL_REPRESENTATION('',(#54852),#54856); +#54852 = CIRCLE('',#54853,0.2); +#54853 = AXIS2_PLACEMENT_2D('',#54854,#54855); +#54854 = CARTESIAN_POINT('',(-2.256940242224,1.025)); +#54855 = DIRECTION('',(0.573576436351,0.819152044289)); +#54856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54857 = PCURVE('',#51554,#54858); +#54858 = DEFINITIONAL_REPRESENTATION('',(#54859),#54862); +#54859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54860,#54861),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238198),.PIECEWISE_BEZIER_KNOTS.); -#52468 = CARTESIAN_POINT('',(0.959931088597,-0.7)); -#52469 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#52470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52471 = ORIENTED_EDGE('',*,*,#49123,.T.); -#52472 = ORIENTED_EDGE('',*,*,#52473,.F.); -#52473 = EDGE_CURVE('',#47531,#49101,#52474,.T.); -#52474 = SURFACE_CURVE('',#52475,(#52479,#52486),.PCURVE_S1.); -#52475 = LINE('',#52476,#52477); -#52476 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); -#52477 = VECTOR('',#52478,1.); -#52478 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52479 = PCURVE('',#47546,#52480); -#52480 = DEFINITIONAL_REPRESENTATION('',(#52481),#52485); -#52481 = LINE('',#52482,#52483); -#52482 = CARTESIAN_POINT('',(-2.37,0.925)); -#52483 = VECTOR('',#52484,1.); -#52484 = DIRECTION('',(0.E+000,1.)); -#52485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52486 = PCURVE('',#47574,#52487); -#52487 = DEFINITIONAL_REPRESENTATION('',(#52488),#52492); -#52488 = LINE('',#52489,#52490); -#52489 = CARTESIAN_POINT('',(0.3,-0.3)); -#52490 = VECTOR('',#52491,1.); -#52491 = DIRECTION('',(0.E+000,1.)); -#52492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52493 = ORIENTED_EDGE('',*,*,#47530,.T.); -#52494 = ORIENTED_EDGE('',*,*,#52495,.T.); -#52495 = EDGE_CURVE('',#47504,#52496,#52498,.T.); -#52496 = VERTEX_POINT('',#52497); -#52497 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-1.65)); -#52498 = SURFACE_CURVE('',#52499,(#52504,#52515),.PCURVE_S1.); -#52499 = CIRCLE('',#52500,0.1); -#52500 = AXIS2_PLACEMENT_3D('',#52501,#52502,#52503); -#52501 = CARTESIAN_POINT('',(2.32,0.825,-1.65)); -#52502 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52503 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52504 = PCURVE('',#47546,#52505); -#52505 = DEFINITIONAL_REPRESENTATION('',(#52506),#52514); -#52506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#52507,#52508,#52509,#52510 - ,#52511,#52512,#52513),.UNSPECIFIED.,.F.,.F.) +#54860 = CARTESIAN_POINT('',(0.959931088597,-0.7)); +#54861 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#54862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54863 = ORIENTED_EDGE('',*,*,#51515,.T.); +#54864 = ORIENTED_EDGE('',*,*,#54865,.F.); +#54865 = EDGE_CURVE('',#49923,#51493,#54866,.T.); +#54866 = SURFACE_CURVE('',#54867,(#54871,#54878),.PCURVE_S1.); +#54867 = LINE('',#54868,#54869); +#54868 = CARTESIAN_POINT('',(2.37,0.925,-1.65)); +#54869 = VECTOR('',#54870,1.); +#54870 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54871 = PCURVE('',#49938,#54872); +#54872 = DEFINITIONAL_REPRESENTATION('',(#54873),#54877); +#54873 = LINE('',#54874,#54875); +#54874 = CARTESIAN_POINT('',(-2.37,0.925)); +#54875 = VECTOR('',#54876,1.); +#54876 = DIRECTION('',(0.E+000,1.)); +#54877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54878 = PCURVE('',#49966,#54879); +#54879 = DEFINITIONAL_REPRESENTATION('',(#54880),#54884); +#54880 = LINE('',#54881,#54882); +#54881 = CARTESIAN_POINT('',(0.3,-0.3)); +#54882 = VECTOR('',#54883,1.); +#54883 = DIRECTION('',(0.E+000,1.)); +#54884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54885 = ORIENTED_EDGE('',*,*,#49922,.T.); +#54886 = ORIENTED_EDGE('',*,*,#54887,.T.); +#54887 = EDGE_CURVE('',#49896,#54888,#54890,.T.); +#54888 = VERTEX_POINT('',#54889); +#54889 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-1.65)); +#54890 = SURFACE_CURVE('',#54891,(#54896,#54907),.PCURVE_S1.); +#54891 = CIRCLE('',#54892,0.1); +#54892 = AXIS2_PLACEMENT_3D('',#54893,#54894,#54895); +#54893 = CARTESIAN_POINT('',(2.32,0.825,-1.65)); +#54894 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54895 = DIRECTION('',(0.E+000,1.,0.E+000)); +#54896 = PCURVE('',#49938,#54897); +#54897 = DEFINITIONAL_REPRESENTATION('',(#54898),#54906); +#54898 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54899,#54900,#54901,#54902 + ,#54903,#54904,#54905),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#52507 = CARTESIAN_POINT('',(-2.32,0.925)); -#52508 = CARTESIAN_POINT('',(-2.146794919243,0.925)); -#52509 = CARTESIAN_POINT('',(-2.233397459622,0.775)); -#52510 = CARTESIAN_POINT('',(-2.32,0.625)); -#52511 = CARTESIAN_POINT('',(-2.406602540378,0.775)); -#52512 = CARTESIAN_POINT('',(-2.493205080757,0.925)); -#52513 = CARTESIAN_POINT('',(-2.32,0.925)); -#52514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52515 = PCURVE('',#47519,#52516); -#52516 = DEFINITIONAL_REPRESENTATION('',(#52517),#52520); -#52517 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52518,#52519),.UNSPECIFIED., +#54899 = CARTESIAN_POINT('',(-2.32,0.925)); +#54900 = CARTESIAN_POINT('',(-2.146794919243,0.925)); +#54901 = CARTESIAN_POINT('',(-2.233397459622,0.775)); +#54902 = CARTESIAN_POINT('',(-2.32,0.625)); +#54903 = CARTESIAN_POINT('',(-2.406602540378,0.775)); +#54904 = CARTESIAN_POINT('',(-2.493205080757,0.925)); +#54905 = CARTESIAN_POINT('',(-2.32,0.925)); +#54906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54907 = PCURVE('',#49911,#54908); +#54908 = DEFINITIONAL_REPRESENTATION('',(#54909),#54912); +#54909 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54910,#54911),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238197),.PIECEWISE_BEZIER_KNOTS.); -#52518 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#52519 = CARTESIAN_POINT('',(0.959931088598,-0.7)); -#52520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52521 = ORIENTED_EDGE('',*,*,#52522,.T.); -#52522 = EDGE_CURVE('',#52496,#52374,#52523,.T.); -#52523 = SURFACE_CURVE('',#52524,(#52528,#52535),.PCURVE_S1.); -#52524 = LINE('',#52525,#52526); -#52525 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-1.65)); -#52526 = VECTOR('',#52527,1.); -#52527 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52528 = PCURVE('',#47546,#52529); -#52529 = DEFINITIONAL_REPRESENTATION('',(#52530),#52534); -#52530 = LINE('',#52531,#52532); -#52531 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429)); -#52532 = VECTOR('',#52533,1.); -#52533 = DIRECTION('',(0.819152044289,-0.573576436351)); -#52534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52535 = PCURVE('',#52536,#52541); -#52536 = PLANE('',#52537); -#52537 = AXIS2_PLACEMENT_3D('',#52538,#52539,#52540); -#52538 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); -#52539 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52540 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52541 = DEFINITIONAL_REPRESENTATION('',(#52542),#52546); -#52542 = LINE('',#52543,#52544); -#52543 = CARTESIAN_POINT('',(0.E+000,-0.7)); -#52544 = VECTOR('',#52545,1.); -#52545 = DIRECTION('',(1.,0.E+000)); -#52546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52547 = ADVANCED_FACE('',(#52548),#47300,.F.); -#52548 = FACE_BOUND('',#52549,.F.); -#52549 = EDGE_LOOP('',(#52550,#52602,#52630,#52655,#52656,#52657,#52658, - #52681)); -#52550 = ORIENTED_EDGE('',*,*,#52551,.F.); -#52551 = EDGE_CURVE('',#52552,#52554,#52556,.T.); -#52552 = VERTEX_POINT('',#52553); -#52553 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); -#52554 = VERTEX_POINT('',#52555); -#52555 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635,-1.65)); -#52556 = SURFACE_CURVE('',#52557,(#52561,#52568),.PCURVE_S1.); -#52557 = LINE('',#52558,#52559); -#52558 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); -#52559 = VECTOR('',#52560,1.); -#52560 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#52561 = PCURVE('',#47300,#52562); -#52562 = DEFINITIONAL_REPRESENTATION('',(#52563),#52567); -#52563 = LINE('',#52564,#52565); -#52564 = CARTESIAN_POINT('',(1.819483496816,0.596612030348)); -#52565 = VECTOR('',#52566,1.); -#52566 = DIRECTION('',(-0.573576436351,0.819152044289)); -#52567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#54910 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#54911 = CARTESIAN_POINT('',(0.959931088598,-0.7)); +#54912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54913 = ORIENTED_EDGE('',*,*,#54914,.T.); +#54914 = EDGE_CURVE('',#54888,#54766,#54915,.T.); +#54915 = SURFACE_CURVE('',#54916,(#54920,#54927),.PCURVE_S1.); +#54916 = LINE('',#54917,#54918); +#54917 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-1.65)); +#54918 = VECTOR('',#54919,1.); +#54919 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#54920 = PCURVE('',#49938,#54921); +#54921 = DEFINITIONAL_REPRESENTATION('',(#54922),#54926); +#54922 = LINE('',#54923,#54924); +#54923 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429)); +#54924 = VECTOR('',#54925,1.); +#54925 = DIRECTION('',(0.819152044289,-0.573576436351)); +#54926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54927 = PCURVE('',#54928,#54933); +#54928 = PLANE('',#54929); +#54929 = AXIS2_PLACEMENT_3D('',#54930,#54931,#54932); +#54930 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); +#54931 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#54932 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#54933 = DEFINITIONAL_REPRESENTATION('',(#54934),#54938); +#54934 = LINE('',#54935,#54936); +#54935 = CARTESIAN_POINT('',(0.E+000,-0.7)); +#54936 = VECTOR('',#54937,1.); +#54937 = DIRECTION('',(1.,0.E+000)); +#54938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54939 = ADVANCED_FACE('',(#54940),#49692,.F.); +#54940 = FACE_BOUND('',#54941,.F.); +#54941 = EDGE_LOOP('',(#54942,#54994,#55022,#55047,#55048,#55049,#55050, + #55073)); +#54942 = ORIENTED_EDGE('',*,*,#54943,.F.); +#54943 = EDGE_CURVE('',#54944,#54946,#54948,.T.); +#54944 = VERTEX_POINT('',#54945); +#54945 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); +#54946 = VERTEX_POINT('',#54947); +#54947 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635,-1.65)); +#54948 = SURFACE_CURVE('',#54949,(#54953,#54960),.PCURVE_S1.); +#54949 = LINE('',#54950,#54951); +#54950 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); +#54951 = VECTOR('',#54952,1.); +#54952 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#54953 = PCURVE('',#49692,#54954); +#54954 = DEFINITIONAL_REPRESENTATION('',(#54955),#54959); +#54955 = LINE('',#54956,#54957); +#54956 = CARTESIAN_POINT('',(1.819483496816,0.596612030348)); +#54957 = VECTOR('',#54958,1.); +#54958 = DIRECTION('',(-0.573576436351,0.819152044289)); +#54959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52568 = PCURVE('',#52569,#52574); -#52569 = CYLINDRICAL_SURFACE('',#52570,0.1); -#52570 = AXIS2_PLACEMENT_3D('',#52571,#52572,#52573); -#52571 = CARTESIAN_POINT('',(-1.832124775827,0.578558412927,-1.75)); -#52572 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#52573 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52574 = DEFINITIONAL_REPRESENTATION('',(#52575),#52601); -#52575 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52576,#52577,#52578,#52579, - #52580,#52581,#52582,#52583,#52584,#52585,#52586,#52587,#52588, - #52589,#52590,#52591,#52592,#52593,#52594,#52595,#52596,#52597, - #52598,#52599,#52600),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#54960 = PCURVE('',#54961,#54966); +#54961 = CYLINDRICAL_SURFACE('',#54962,0.1); +#54962 = AXIS2_PLACEMENT_3D('',#54963,#54964,#54965); +#54963 = CARTESIAN_POINT('',(-1.832124775827,0.578558412927,-1.75)); +#54964 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#54965 = DIRECTION('',(0.E+000,0.E+000,1.)); +#54966 = DEFINITIONAL_REPRESENTATION('',(#54967),#54993); +#54967 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54968,#54969,#54970,#54971, + #54972,#54973,#54974,#54975,#54976,#54977,#54978,#54979,#54980, + #54981,#54982,#54983,#54984,#54985,#54986,#54987,#54988,#54989, + #54990,#54991,#54992),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363636E-002, 2.727272727271E-002,4.090909090907E-002,5.454545454542E-002, 6.818181818178E-002,8.181818181813E-002,9.545454545449E-002, @@ -65301,182 +68290,182 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#52576 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); -#52577 = CARTESIAN_POINT('',(1.513233982564E-012,2.658485192938E-002)); -#52578 = CARTESIAN_POINT('',(2.924672217808E-012,3.567576102028E-002)); -#52579 = CARTESIAN_POINT('',(2.361903009607E-012,4.931212465664E-002)); -#52580 = CARTESIAN_POINT('',(2.509145165839E-012,6.294848829299E-002)); -#52581 = CARTESIAN_POINT('',(2.469623072816E-012,7.658485192935E-002)); -#52582 = CARTESIAN_POINT('',(2.480469288675E-012,9.022121556571E-002)); -#52583 = CARTESIAN_POINT('',(2.476606518262E-012,0.103857579202)); -#52584 = CARTESIAN_POINT('',(2.481211384057E-012,0.117493942838)); -#52585 = CARTESIAN_POINT('',(2.479977367585E-012,0.131130306475)); -#52586 = CARTESIAN_POINT('',(2.480308567678E-012,0.144766670111)); -#52587 = CARTESIAN_POINT('',(2.480217783778E-012,0.158403033747)); -#52588 = CARTESIAN_POINT('',(2.480249719285E-012,0.172039397384)); -#52589 = CARTESIAN_POINT('',(2.480212761156E-012,0.18567576102)); -#52590 = CARTESIAN_POINT('',(2.480328658165E-012,0.199312124657)); -#52591 = CARTESIAN_POINT('',(2.479902028258E-012,0.212948488293)); -#52592 = CARTESIAN_POINT('',(2.481492650878E-012,0.226584851929)); -#52593 = CARTESIAN_POINT('',(2.475556790305E-012,0.240221215566)); -#52594 = CARTESIAN_POINT('',(2.484386933682E-012,0.253857579202)); -#52595 = CARTESIAN_POINT('',(2.468324897041E-012,0.267493942838)); -#52596 = CARTESIAN_POINT('',(2.510420223933E-012,0.281130306475)); -#52597 = CARTESIAN_POINT('',(2.358100953005E-012,0.294766670111)); -#52598 = CARTESIAN_POINT('',(2.925282709826E-012,0.308403033747)); -#52599 = CARTESIAN_POINT('',(1.514344205589E-012,0.317493942838)); -#52600 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#52601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52602 = ORIENTED_EDGE('',*,*,#52603,.T.); -#52603 = EDGE_CURVE('',#52552,#52604,#52606,.T.); -#52604 = VERTEX_POINT('',#52605); -#52605 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-1.65)); -#52606 = SURFACE_CURVE('',#52607,(#52611,#52618),.PCURVE_S1.); -#52607 = LINE('',#52608,#52609); -#52608 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); -#52609 = VECTOR('',#52610,1.); -#52610 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); -#52611 = PCURVE('',#47300,#52612); -#52612 = DEFINITIONAL_REPRESENTATION('',(#52613),#52617); -#52613 = LINE('',#52614,#52615); -#52614 = CARTESIAN_POINT('',(1.819483496816,0.596612030348)); -#52615 = VECTOR('',#52616,1.); -#52616 = DIRECTION('',(0.819152044289,0.573576436351)); -#52617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52618 = PCURVE('',#52619,#52624); -#52619 = PLANE('',#52620); -#52620 = AXIS2_PLACEMENT_3D('',#52621,#52622,#52623); -#52621 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.35)); -#52622 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#52623 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); -#52624 = DEFINITIONAL_REPRESENTATION('',(#52625),#52629); -#52625 = LINE('',#52626,#52627); -#52626 = CARTESIAN_POINT('',(0.1,-0.7)); -#52627 = VECTOR('',#52628,1.); -#52628 = DIRECTION('',(1.,0.E+000)); -#52629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52630 = ORIENTED_EDGE('',*,*,#52631,.T.); -#52631 = EDGE_CURVE('',#52604,#47285,#52632,.T.); -#52632 = SURFACE_CURVE('',#52633,(#52638,#52649),.PCURVE_S1.); -#52633 = CIRCLE('',#52634,0.1); -#52634 = AXIS2_PLACEMENT_3D('',#52635,#52636,#52637); -#52635 = CARTESIAN_POINT('',(-2.32,0.825,-1.65)); -#52636 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52637 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#52638 = PCURVE('',#47300,#52639); -#52639 = DEFINITIONAL_REPRESENTATION('',(#52640),#52648); -#52640 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#52641,#52642,#52643,#52644 - ,#52645,#52646,#52647),.UNSPECIFIED.,.F.,.F.) +#54968 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); +#54969 = CARTESIAN_POINT('',(1.513233982564E-012,2.658485192938E-002)); +#54970 = CARTESIAN_POINT('',(2.924672217808E-012,3.567576102028E-002)); +#54971 = CARTESIAN_POINT('',(2.361903009607E-012,4.931212465664E-002)); +#54972 = CARTESIAN_POINT('',(2.509145165839E-012,6.294848829299E-002)); +#54973 = CARTESIAN_POINT('',(2.469623072816E-012,7.658485192935E-002)); +#54974 = CARTESIAN_POINT('',(2.480469288675E-012,9.022121556571E-002)); +#54975 = CARTESIAN_POINT('',(2.476606518262E-012,0.103857579202)); +#54976 = CARTESIAN_POINT('',(2.481211384057E-012,0.117493942838)); +#54977 = CARTESIAN_POINT('',(2.479977367585E-012,0.131130306475)); +#54978 = CARTESIAN_POINT('',(2.480308567678E-012,0.144766670111)); +#54979 = CARTESIAN_POINT('',(2.480217783778E-012,0.158403033747)); +#54980 = CARTESIAN_POINT('',(2.480249719285E-012,0.172039397384)); +#54981 = CARTESIAN_POINT('',(2.480212761156E-012,0.18567576102)); +#54982 = CARTESIAN_POINT('',(2.480328658165E-012,0.199312124657)); +#54983 = CARTESIAN_POINT('',(2.479902028258E-012,0.212948488293)); +#54984 = CARTESIAN_POINT('',(2.481492650878E-012,0.226584851929)); +#54985 = CARTESIAN_POINT('',(2.475556790305E-012,0.240221215566)); +#54986 = CARTESIAN_POINT('',(2.484386933682E-012,0.253857579202)); +#54987 = CARTESIAN_POINT('',(2.468324897041E-012,0.267493942838)); +#54988 = CARTESIAN_POINT('',(2.510420223933E-012,0.281130306475)); +#54989 = CARTESIAN_POINT('',(2.358100953005E-012,0.294766670111)); +#54990 = CARTESIAN_POINT('',(2.925282709826E-012,0.308403033747)); +#54991 = CARTESIAN_POINT('',(1.514344205589E-012,0.317493942838)); +#54992 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#54993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#54994 = ORIENTED_EDGE('',*,*,#54995,.T.); +#54995 = EDGE_CURVE('',#54944,#54996,#54998,.T.); +#54996 = VERTEX_POINT('',#54997); +#54997 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-1.65)); +#54998 = SURFACE_CURVE('',#54999,(#55003,#55010),.PCURVE_S1.); +#54999 = LINE('',#55000,#55001); +#55000 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.65)); +#55001 = VECTOR('',#55002,1.); +#55002 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); +#55003 = PCURVE('',#49692,#55004); +#55004 = DEFINITIONAL_REPRESENTATION('',(#55005),#55009); +#55005 = LINE('',#55006,#55007); +#55006 = CARTESIAN_POINT('',(1.819483496816,0.596612030348)); +#55007 = VECTOR('',#55008,1.); +#55008 = DIRECTION('',(0.819152044289,0.573576436351)); +#55009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55010 = PCURVE('',#55011,#55016); +#55011 = PLANE('',#55012); +#55012 = AXIS2_PLACEMENT_3D('',#55013,#55014,#55015); +#55013 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.35)); +#55014 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#55015 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); +#55016 = DEFINITIONAL_REPRESENTATION('',(#55017),#55021); +#55017 = LINE('',#55018,#55019); +#55018 = CARTESIAN_POINT('',(0.1,-0.7)); +#55019 = VECTOR('',#55020,1.); +#55020 = DIRECTION('',(1.,0.E+000)); +#55021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55022 = ORIENTED_EDGE('',*,*,#55023,.T.); +#55023 = EDGE_CURVE('',#54996,#49677,#55024,.T.); +#55024 = SURFACE_CURVE('',#55025,(#55030,#55041),.PCURVE_S1.); +#55025 = CIRCLE('',#55026,0.1); +#55026 = AXIS2_PLACEMENT_3D('',#55027,#55028,#55029); +#55027 = CARTESIAN_POINT('',(-2.32,0.825,-1.65)); +#55028 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55029 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#55030 = PCURVE('',#49692,#55031); +#55031 = DEFINITIONAL_REPRESENTATION('',(#55032),#55040); +#55032 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55033,#55034,#55035,#55036 + ,#55037,#55038,#55039),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#52641 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); -#52642 = CARTESIAN_POINT('',(2.404523652348,1.006261557407)); -#52643 = CARTESIAN_POINT('',(2.419619469809,0.833715574275)); -#52644 = CARTESIAN_POINT('',(2.43471528727,0.661169591142)); -#52645 = CARTESIAN_POINT('',(2.277738173826,0.734369221296)); -#52646 = CARTESIAN_POINT('',(2.120761060382,0.80756885145)); -#52647 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); -#52648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52649 = PCURVE('',#47328,#52650); -#52650 = DEFINITIONAL_REPRESENTATION('',(#52651),#52654); -#52651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52652,#52653),.UNSPECIFIED., +#55033 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); +#55034 = CARTESIAN_POINT('',(2.404523652348,1.006261557407)); +#55035 = CARTESIAN_POINT('',(2.419619469809,0.833715574275)); +#55036 = CARTESIAN_POINT('',(2.43471528727,0.661169591142)); +#55037 = CARTESIAN_POINT('',(2.277738173826,0.734369221296)); +#55038 = CARTESIAN_POINT('',(2.120761060382,0.80756885145)); +#55039 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); +#55040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55041 = PCURVE('',#49720,#55042); +#55042 = DEFINITIONAL_REPRESENTATION('',(#55043),#55046); +#55043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55044,#55045),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238198),.PIECEWISE_BEZIER_KNOTS.); -#52652 = CARTESIAN_POINT('',(2.181661564993,-0.7)); -#52653 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#52654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52655 = ORIENTED_EDGE('',*,*,#47284,.T.); -#52656 = ORIENTED_EDGE('',*,*,#52344,.T.); -#52657 = ORIENTED_EDGE('',*,*,#49314,.T.); -#52658 = ORIENTED_EDGE('',*,*,#52659,.T.); -#52659 = EDGE_CURVE('',#49288,#52660,#52662,.T.); -#52660 = VERTEX_POINT('',#52661); -#52661 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-1.65)); -#52662 = SURFACE_CURVE('',#52663,(#52668,#52675),.PCURVE_S1.); -#52663 = CIRCLE('',#52664,0.2); -#52664 = AXIS2_PLACEMENT_3D('',#52665,#52666,#52667); -#52665 = CARTESIAN_POINT('',(-2.256940242224,1.025,-1.65)); -#52666 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52667 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52668 = PCURVE('',#47300,#52669); -#52669 = DEFINITIONAL_REPRESENTATION('',(#52670),#52674); -#52670 = CIRCLE('',#52671,0.2); -#52671 = AXIS2_PLACEMENT_2D('',#52672,#52673); -#52672 = CARTESIAN_POINT('',(2.256940242224,1.025)); -#52673 = DIRECTION('',(0.E+000,1.)); -#52674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52675 = PCURVE('',#49303,#52676); -#52676 = DEFINITIONAL_REPRESENTATION('',(#52677),#52680); -#52677 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52678,#52679),.UNSPECIFIED., +#55044 = CARTESIAN_POINT('',(2.181661564993,-0.7)); +#55045 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#55046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55047 = ORIENTED_EDGE('',*,*,#49676,.T.); +#55048 = ORIENTED_EDGE('',*,*,#54736,.T.); +#55049 = ORIENTED_EDGE('',*,*,#51706,.T.); +#55050 = ORIENTED_EDGE('',*,*,#55051,.T.); +#55051 = EDGE_CURVE('',#51680,#55052,#55054,.T.); +#55052 = VERTEX_POINT('',#55053); +#55053 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-1.65)); +#55054 = SURFACE_CURVE('',#55055,(#55060,#55067),.PCURVE_S1.); +#55055 = CIRCLE('',#55056,0.2); +#55056 = AXIS2_PLACEMENT_3D('',#55057,#55058,#55059); +#55057 = CARTESIAN_POINT('',(-2.256940242224,1.025,-1.65)); +#55058 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55059 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55060 = PCURVE('',#49692,#55061); +#55061 = DEFINITIONAL_REPRESENTATION('',(#55062),#55066); +#55062 = CIRCLE('',#55063,0.2); +#55063 = AXIS2_PLACEMENT_2D('',#55064,#55065); +#55064 = CARTESIAN_POINT('',(2.256940242224,1.025)); +#55065 = DIRECTION('',(0.E+000,1.)); +#55066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55067 = PCURVE('',#51695,#55068); +#55068 = DEFINITIONAL_REPRESENTATION('',(#55069),#55072); +#55069 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55070,#55071),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238197),.PIECEWISE_BEZIER_KNOTS.); -#52678 = CARTESIAN_POINT('',(1.570796326795,-0.7)); -#52679 = CARTESIAN_POINT('',(2.181661564991,-0.7)); -#52680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52681 = ORIENTED_EDGE('',*,*,#52682,.T.); -#52682 = EDGE_CURVE('',#52660,#52554,#52683,.T.); -#52683 = SURFACE_CURVE('',#52684,(#52688,#52695),.PCURVE_S1.); -#52684 = LINE('',#52685,#52686); -#52685 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-1.65)); -#52686 = VECTOR('',#52687,1.); -#52687 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#52688 = PCURVE('',#47300,#52689); -#52689 = DEFINITIONAL_REPRESENTATION('',(#52690),#52694); -#52690 = LINE('',#52691,#52692); -#52691 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); -#52692 = VECTOR('',#52693,1.); -#52693 = DIRECTION('',(-0.819152044289,-0.573576436351)); -#52694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52695 = PCURVE('',#52696,#52701); -#52696 = PLANE('',#52697); -#52697 = AXIS2_PLACEMENT_3D('',#52698,#52699,#52700); -#52698 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); -#52699 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#52700 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#52701 = DEFINITIONAL_REPRESENTATION('',(#52702),#52706); -#52702 = LINE('',#52703,#52704); -#52703 = CARTESIAN_POINT('',(0.E+000,-0.7)); -#52704 = VECTOR('',#52705,1.); -#52705 = DIRECTION('',(1.,0.E+000)); -#52706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52707 = ADVANCED_FACE('',(#52708),#52389,.T.); -#52708 = FACE_BOUND('',#52709,.T.); -#52709 = EDGE_LOOP('',(#52710,#52756,#52757,#52803)); -#52710 = ORIENTED_EDGE('',*,*,#52711,.F.); -#52711 = EDGE_CURVE('',#52374,#52712,#52714,.T.); -#52712 = VERTEX_POINT('',#52713); -#52713 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-1.75)); -#52714 = SURFACE_CURVE('',#52715,(#52720,#52749),.PCURVE_S1.); -#52715 = CIRCLE('',#52716,0.1); -#52716 = AXIS2_PLACEMENT_3D('',#52717,#52718,#52719); -#52717 = CARTESIAN_POINT('',(1.819483496816,0.596612030348,-1.75)); -#52718 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52719 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52720 = PCURVE('',#52389,#52721); -#52721 = DEFINITIONAL_REPRESENTATION('',(#52722),#52748); -#52722 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52723,#52724,#52725,#52726, - #52727,#52728,#52729,#52730,#52731,#52732,#52733,#52734,#52735, - #52736,#52737,#52738,#52739,#52740,#52741,#52742,#52743,#52744, - #52745,#52746,#52747),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55070 = CARTESIAN_POINT('',(1.570796326795,-0.7)); +#55071 = CARTESIAN_POINT('',(2.181661564991,-0.7)); +#55072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55073 = ORIENTED_EDGE('',*,*,#55074,.T.); +#55074 = EDGE_CURVE('',#55052,#54946,#55075,.T.); +#55075 = SURFACE_CURVE('',#55076,(#55080,#55087),.PCURVE_S1.); +#55076 = LINE('',#55077,#55078); +#55077 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-1.65)); +#55078 = VECTOR('',#55079,1.); +#55079 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#55080 = PCURVE('',#49692,#55081); +#55081 = DEFINITIONAL_REPRESENTATION('',(#55082),#55086); +#55082 = LINE('',#55083,#55084); +#55083 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); +#55084 = VECTOR('',#55085,1.); +#55085 = DIRECTION('',(-0.819152044289,-0.573576436351)); +#55086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55087 = PCURVE('',#55088,#55093); +#55088 = PLANE('',#55089); +#55089 = AXIS2_PLACEMENT_3D('',#55090,#55091,#55092); +#55090 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); +#55091 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#55092 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#55093 = DEFINITIONAL_REPRESENTATION('',(#55094),#55098); +#55094 = LINE('',#55095,#55096); +#55095 = CARTESIAN_POINT('',(0.E+000,-0.7)); +#55096 = VECTOR('',#55097,1.); +#55097 = DIRECTION('',(1.,0.E+000)); +#55098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55099 = ADVANCED_FACE('',(#55100),#54781,.T.); +#55100 = FACE_BOUND('',#55101,.T.); +#55101 = EDGE_LOOP('',(#55102,#55148,#55149,#55195)); +#55102 = ORIENTED_EDGE('',*,*,#55103,.F.); +#55103 = EDGE_CURVE('',#54766,#55104,#55106,.T.); +#55104 = VERTEX_POINT('',#55105); +#55105 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-1.75)); +#55106 = SURFACE_CURVE('',#55107,(#55112,#55141),.PCURVE_S1.); +#55107 = CIRCLE('',#55108,0.1); +#55108 = AXIS2_PLACEMENT_3D('',#55109,#55110,#55111); +#55109 = CARTESIAN_POINT('',(1.819483496816,0.596612030348,-1.75)); +#55110 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#55111 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55112 = PCURVE('',#54781,#55113); +#55113 = DEFINITIONAL_REPRESENTATION('',(#55114),#55140); +#55114 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55115,#55116,#55117,#55118, + #55119,#55120,#55121,#55122,#55123,#55124,#55125,#55126,#55127, + #55128,#55129,#55130,#55131,#55132,#55133,#55134,#55135,#55136, + #55137,#55138,#55139),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -65484,60 +68473,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#52723 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#52724 = CARTESIAN_POINT('',(2.379994434536E-002,0.322039397384)); -#52725 = CARTESIAN_POINT('',(7.13998330361E-002,0.322039397384)); -#52726 = CARTESIAN_POINT('',(0.142799666072,0.322039397384)); -#52727 = CARTESIAN_POINT('',(0.214199499108,0.322039397384)); -#52728 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); -#52729 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); -#52730 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); -#52731 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); -#52732 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); -#52733 = CARTESIAN_POINT('',(0.642598497325,0.322039397384)); -#52734 = CARTESIAN_POINT('',(0.713998330361,0.322039397384)); -#52735 = CARTESIAN_POINT('',(0.785398163397,0.322039397384)); -#52736 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); -#52737 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); -#52738 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); -#52739 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); -#52740 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); -#52741 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); -#52742 = CARTESIAN_POINT('',(1.28519699465,0.322039397384)); -#52743 = CARTESIAN_POINT('',(1.356596827686,0.322039397384)); -#52744 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); -#52745 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); -#52746 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); -#52747 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#52748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52749 = PCURVE('',#52536,#52750); -#52750 = DEFINITIONAL_REPRESENTATION('',(#52751),#52755); -#52751 = CIRCLE('',#52752,0.1); -#52752 = AXIS2_PLACEMENT_2D('',#52753,#52754); -#52753 = CARTESIAN_POINT('',(0.540997074522,-0.6)); -#52754 = DIRECTION('',(0.E+000,-1.)); -#52755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52756 = ORIENTED_EDGE('',*,*,#52371,.F.); -#52757 = ORIENTED_EDGE('',*,*,#52758,.F.); -#52758 = EDGE_CURVE('',#52759,#52372,#52761,.T.); -#52759 = VERTEX_POINT('',#52760); -#52760 = CARTESIAN_POINT('',(1.565495361482,0.785,-1.75)); -#52761 = SURFACE_CURVE('',#52762,(#52767,#52796),.PCURVE_S1.); -#52762 = CIRCLE('',#52763,0.1); -#52763 = AXIS2_PLACEMENT_3D('',#52764,#52765,#52766); -#52764 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.75)); -#52765 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#52766 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52767 = PCURVE('',#52389,#52768); -#52768 = DEFINITIONAL_REPRESENTATION('',(#52769),#52795); -#52769 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52770,#52771,#52772,#52773, - #52774,#52775,#52776,#52777,#52778,#52779,#52780,#52781,#52782, - #52783,#52784,#52785,#52786,#52787,#52788,#52789,#52790,#52791, - #52792,#52793,#52794),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55115 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#55116 = CARTESIAN_POINT('',(2.379994434536E-002,0.322039397384)); +#55117 = CARTESIAN_POINT('',(7.13998330361E-002,0.322039397384)); +#55118 = CARTESIAN_POINT('',(0.142799666072,0.322039397384)); +#55119 = CARTESIAN_POINT('',(0.214199499108,0.322039397384)); +#55120 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); +#55121 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); +#55122 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); +#55123 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); +#55124 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); +#55125 = CARTESIAN_POINT('',(0.642598497325,0.322039397384)); +#55126 = CARTESIAN_POINT('',(0.713998330361,0.322039397384)); +#55127 = CARTESIAN_POINT('',(0.785398163397,0.322039397384)); +#55128 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); +#55129 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); +#55130 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); +#55131 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); +#55132 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); +#55133 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); +#55134 = CARTESIAN_POINT('',(1.28519699465,0.322039397384)); +#55135 = CARTESIAN_POINT('',(1.356596827686,0.322039397384)); +#55136 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); +#55137 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); +#55138 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); +#55139 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#55140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55141 = PCURVE('',#54928,#55142); +#55142 = DEFINITIONAL_REPRESENTATION('',(#55143),#55147); +#55143 = CIRCLE('',#55144,0.1); +#55144 = AXIS2_PLACEMENT_2D('',#55145,#55146); +#55145 = CARTESIAN_POINT('',(0.540997074522,-0.6)); +#55146 = DIRECTION('',(0.E+000,-1.)); +#55147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55148 = ORIENTED_EDGE('',*,*,#54763,.F.); +#55149 = ORIENTED_EDGE('',*,*,#55150,.F.); +#55150 = EDGE_CURVE('',#55151,#54764,#55153,.T.); +#55151 = VERTEX_POINT('',#55152); +#55152 = CARTESIAN_POINT('',(1.565495361482,0.785,-1.75)); +#55153 = SURFACE_CURVE('',#55154,(#55159,#55188),.PCURVE_S1.); +#55154 = CIRCLE('',#55155,0.1); +#55155 = AXIS2_PLACEMENT_3D('',#55156,#55157,#55158); +#55156 = CARTESIAN_POINT('',(1.647410565911,0.842357643635,-1.75)); +#55157 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#55158 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#55159 = PCURVE('',#54781,#55160); +#55160 = DEFINITIONAL_REPRESENTATION('',(#55161),#55187); +#55161 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55162,#55163,#55164,#55165, + #55166,#55167,#55168,#55169,#55170,#55171,#55172,#55173,#55174, + #55175,#55176,#55177,#55178,#55179,#55180,#55181,#55182,#55183, + #55184,#55185,#55186),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -65545,162 +68534,162 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#52770 = CARTESIAN_POINT('',(1.570796326795,2.203939738393E-002)); -#52771 = CARTESIAN_POINT('',(1.546996382449,2.203939738393E-002)); -#52772 = CARTESIAN_POINT('',(1.499396493759,2.203939738393E-002)); -#52773 = CARTESIAN_POINT('',(1.427996660722,2.203939738393E-002)); -#52774 = CARTESIAN_POINT('',(1.356596827686,2.203939738393E-002)); -#52775 = CARTESIAN_POINT('',(1.28519699465,2.203939738393E-002)); -#52776 = CARTESIAN_POINT('',(1.213797161613,2.203939738393E-002)); -#52777 = CARTESIAN_POINT('',(1.142397328577,2.203939738393E-002)); -#52778 = CARTESIAN_POINT('',(1.070997495541,2.203939738393E-002)); -#52779 = CARTESIAN_POINT('',(0.999597662504,2.203939738393E-002)); -#52780 = CARTESIAN_POINT('',(0.928197829468,2.203939738393E-002)); -#52781 = CARTESIAN_POINT('',(0.856797996432,2.203939738393E-002)); -#52782 = CARTESIAN_POINT('',(0.785398163396,2.203939738393E-002)); -#52783 = CARTESIAN_POINT('',(0.713998330359,2.203939738393E-002)); -#52784 = CARTESIAN_POINT('',(0.642598497323,2.203939738393E-002)); -#52785 = CARTESIAN_POINT('',(0.571198664287,2.203939738393E-002)); -#52786 = CARTESIAN_POINT('',(0.499798831251,2.203939738393E-002)); -#52787 = CARTESIAN_POINT('',(0.428398998215,2.203939738393E-002)); -#52788 = CARTESIAN_POINT('',(0.356999165178,2.203939738393E-002)); -#52789 = CARTESIAN_POINT('',(0.285599332142,2.203939738393E-002)); -#52790 = CARTESIAN_POINT('',(0.214199499106,2.203939738393E-002)); -#52791 = CARTESIAN_POINT('',(0.14279966607,2.203939738393E-002)); -#52792 = CARTESIAN_POINT('',(7.139983303321E-002,2.203939738393E-002)); -#52793 = CARTESIAN_POINT('',(2.379994434386E-002,2.203939738393E-002)); -#52794 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); -#52795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52796 = PCURVE('',#52439,#52797); -#52797 = DEFINITIONAL_REPRESENTATION('',(#52798),#52802); -#52798 = CIRCLE('',#52799,1.E-001); -#52799 = AXIS2_PLACEMENT_2D('',#52800,#52801); -#52800 = CARTESIAN_POINT('',(0.1,-0.6)); -#52801 = DIRECTION('',(-1.,0.E+000)); -#52802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52803 = ORIENTED_EDGE('',*,*,#52804,.T.); -#52804 = EDGE_CURVE('',#52759,#52712,#52805,.T.); -#52805 = SURFACE_CURVE('',#52806,(#52810,#52816),.PCURVE_S1.); -#52806 = LINE('',#52807,#52808); -#52807 = CARTESIAN_POINT('',(1.565495361482,0.785,-1.75)); -#52808 = VECTOR('',#52809,1.); -#52809 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52810 = PCURVE('',#52389,#52811); -#52811 = DEFINITIONAL_REPRESENTATION('',(#52812),#52815); -#52812 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52813,#52814),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#52813 = CARTESIAN_POINT('',(1.570796326795,2.203939738387E-002)); -#52814 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#52815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52816 = PCURVE('',#52817,#52822); -#52817 = PLANE('',#52818); -#52818 = AXIS2_PLACEMENT_3D('',#52819,#52820,#52821); -#52819 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.35)); -#52820 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52821 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#52822 = DEFINITIONAL_REPRESENTATION('',(#52823),#52827); -#52823 = LINE('',#52824,#52825); -#52824 = CARTESIAN_POINT('',(0.3,-0.6)); -#52825 = VECTOR('',#52826,1.); -#52826 = DIRECTION('',(-1.,0.E+000)); -#52827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52828 = ADVANCED_FACE('',(#52829),#52536,.T.); -#52829 = FACE_BOUND('',#52830,.F.); -#52830 = EDGE_LOOP('',(#52831,#52832,#52833,#52855,#52878,#52929)); -#52831 = ORIENTED_EDGE('',*,*,#52711,.F.); -#52832 = ORIENTED_EDGE('',*,*,#52522,.F.); -#52833 = ORIENTED_EDGE('',*,*,#52834,.F.); -#52834 = EDGE_CURVE('',#52835,#52496,#52837,.T.); -#52835 = VERTEX_POINT('',#52836); -#52836 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); -#52837 = SURFACE_CURVE('',#52838,(#52842,#52849),.PCURVE_S1.); -#52838 = LINE('',#52839,#52840); -#52839 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); -#52840 = VECTOR('',#52841,1.); -#52841 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52842 = PCURVE('',#52536,#52843); -#52843 = DEFINITIONAL_REPRESENTATION('',(#52844),#52848); -#52844 = LINE('',#52845,#52846); -#52845 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#52846 = VECTOR('',#52847,1.); -#52847 = DIRECTION('',(0.E+000,-1.)); -#52848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#55162 = CARTESIAN_POINT('',(1.570796326795,2.203939738393E-002)); +#55163 = CARTESIAN_POINT('',(1.546996382449,2.203939738393E-002)); +#55164 = CARTESIAN_POINT('',(1.499396493759,2.203939738393E-002)); +#55165 = CARTESIAN_POINT('',(1.427996660722,2.203939738393E-002)); +#55166 = CARTESIAN_POINT('',(1.356596827686,2.203939738393E-002)); +#55167 = CARTESIAN_POINT('',(1.28519699465,2.203939738393E-002)); +#55168 = CARTESIAN_POINT('',(1.213797161613,2.203939738393E-002)); +#55169 = CARTESIAN_POINT('',(1.142397328577,2.203939738393E-002)); +#55170 = CARTESIAN_POINT('',(1.070997495541,2.203939738393E-002)); +#55171 = CARTESIAN_POINT('',(0.999597662504,2.203939738393E-002)); +#55172 = CARTESIAN_POINT('',(0.928197829468,2.203939738393E-002)); +#55173 = CARTESIAN_POINT('',(0.856797996432,2.203939738393E-002)); +#55174 = CARTESIAN_POINT('',(0.785398163396,2.203939738393E-002)); +#55175 = CARTESIAN_POINT('',(0.713998330359,2.203939738393E-002)); +#55176 = CARTESIAN_POINT('',(0.642598497323,2.203939738393E-002)); +#55177 = CARTESIAN_POINT('',(0.571198664287,2.203939738393E-002)); +#55178 = CARTESIAN_POINT('',(0.499798831251,2.203939738393E-002)); +#55179 = CARTESIAN_POINT('',(0.428398998215,2.203939738393E-002)); +#55180 = CARTESIAN_POINT('',(0.356999165178,2.203939738393E-002)); +#55181 = CARTESIAN_POINT('',(0.285599332142,2.203939738393E-002)); +#55182 = CARTESIAN_POINT('',(0.214199499106,2.203939738393E-002)); +#55183 = CARTESIAN_POINT('',(0.14279966607,2.203939738393E-002)); +#55184 = CARTESIAN_POINT('',(7.139983303321E-002,2.203939738393E-002)); +#55185 = CARTESIAN_POINT('',(2.379994434386E-002,2.203939738393E-002)); +#55186 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); +#55187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55188 = PCURVE('',#54831,#55189); +#55189 = DEFINITIONAL_REPRESENTATION('',(#55190),#55194); +#55190 = CIRCLE('',#55191,1.E-001); +#55191 = AXIS2_PLACEMENT_2D('',#55192,#55193); +#55192 = CARTESIAN_POINT('',(0.1,-0.6)); +#55193 = DIRECTION('',(-1.,0.E+000)); +#55194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52849 = PCURVE('',#47519,#52850); -#52850 = DEFINITIONAL_REPRESENTATION('',(#52851),#52854); -#52851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52852,#52853),.UNSPECIFIED., +#55195 = ORIENTED_EDGE('',*,*,#55196,.T.); +#55196 = EDGE_CURVE('',#55151,#55104,#55197,.T.); +#55197 = SURFACE_CURVE('',#55198,(#55202,#55208),.PCURVE_S1.); +#55198 = LINE('',#55199,#55200); +#55199 = CARTESIAN_POINT('',(1.565495361482,0.785,-1.75)); +#55200 = VECTOR('',#55201,1.); +#55201 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#55202 = PCURVE('',#54781,#55203); +#55203 = DEFINITIONAL_REPRESENTATION('',(#55204),#55207); +#55204 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55205,#55206),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#55205 = CARTESIAN_POINT('',(1.570796326795,2.203939738387E-002)); +#55206 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#55207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55208 = PCURVE('',#55209,#55214); +#55209 = PLANE('',#55210); +#55210 = AXIS2_PLACEMENT_3D('',#55211,#55212,#55213); +#55211 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.35)); +#55212 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#55213 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#55214 = DEFINITIONAL_REPRESENTATION('',(#55215),#55219); +#55215 = LINE('',#55216,#55217); +#55216 = CARTESIAN_POINT('',(0.3,-0.6)); +#55217 = VECTOR('',#55218,1.); +#55218 = DIRECTION('',(-1.,0.E+000)); +#55219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55220 = ADVANCED_FACE('',(#55221),#54928,.T.); +#55221 = FACE_BOUND('',#55222,.F.); +#55222 = EDGE_LOOP('',(#55223,#55224,#55225,#55247,#55270,#55321)); +#55223 = ORIENTED_EDGE('',*,*,#55103,.F.); +#55224 = ORIENTED_EDGE('',*,*,#54914,.F.); +#55225 = ORIENTED_EDGE('',*,*,#55226,.F.); +#55226 = EDGE_CURVE('',#55227,#54888,#55229,.T.); +#55227 = VERTEX_POINT('',#55228); +#55228 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); +#55229 = SURFACE_CURVE('',#55230,(#55234,#55241),.PCURVE_S1.); +#55230 = LINE('',#55231,#55232); +#55231 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); +#55232 = VECTOR('',#55233,1.); +#55233 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55234 = PCURVE('',#54928,#55235); +#55235 = DEFINITIONAL_REPRESENTATION('',(#55236),#55240); +#55236 = LINE('',#55237,#55238); +#55237 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55238 = VECTOR('',#55239,1.); +#55239 = DIRECTION('',(0.E+000,-1.)); +#55240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55241 = PCURVE('',#49911,#55242); +#55242 = DEFINITIONAL_REPRESENTATION('',(#55243),#55246); +#55243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55244,#55245),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#52852 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); -#52853 = CARTESIAN_POINT('',(0.959931088598,-0.7)); -#52854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#55244 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); +#55245 = CARTESIAN_POINT('',(0.959931088598,-0.7)); +#55246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#52855 = ORIENTED_EDGE('',*,*,#52856,.T.); -#52856 = EDGE_CURVE('',#52835,#52857,#52859,.T.); -#52857 = VERTEX_POINT('',#52858); -#52858 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.35)); -#52859 = SURFACE_CURVE('',#52860,(#52864,#52871),.PCURVE_S1.); -#52860 = LINE('',#52861,#52862); -#52861 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); -#52862 = VECTOR('',#52863,1.); -#52863 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52864 = PCURVE('',#52536,#52865); -#52865 = DEFINITIONAL_REPRESENTATION('',(#52866),#52870); -#52866 = LINE('',#52867,#52868); -#52867 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#52868 = VECTOR('',#52869,1.); -#52869 = DIRECTION('',(1.,0.E+000)); -#52870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52871 = PCURVE('',#39747,#52872); -#52872 = DEFINITIONAL_REPRESENTATION('',(#52873),#52877); -#52873 = LINE('',#52874,#52875); -#52874 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); -#52875 = VECTOR('',#52876,1.); -#52876 = DIRECTION('',(-0.819152044289,-0.573576436351)); -#52877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52878 = ORIENTED_EDGE('',*,*,#52879,.F.); -#52879 = EDGE_CURVE('',#52880,#52857,#52882,.T.); -#52880 = VERTEX_POINT('',#52881); -#52881 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); -#52882 = SURFACE_CURVE('',#52883,(#52888,#52895),.PCURVE_S1.); -#52883 = CIRCLE('',#52884,0.3); -#52884 = AXIS2_PLACEMENT_3D('',#52885,#52886,#52887); -#52885 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.05)); -#52886 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); -#52887 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); -#52888 = PCURVE('',#52536,#52889); -#52889 = DEFINITIONAL_REPRESENTATION('',(#52890),#52894); -#52890 = CIRCLE('',#52891,0.3); -#52891 = AXIS2_PLACEMENT_2D('',#52892,#52893); -#52892 = CARTESIAN_POINT('',(0.340997074522,-0.3)); -#52893 = DIRECTION('',(1.,0.E+000)); -#52894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52895 = PCURVE('',#52896,#52901); -#52896 = CYLINDRICAL_SURFACE('',#52897,0.3); -#52897 = AXIS2_PLACEMENT_3D('',#52898,#52899,#52900); -#52898 = CARTESIAN_POINT('',(1.992212732749,0.698618475469,-2.05)); -#52899 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#52900 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#52901 = DEFINITIONAL_REPRESENTATION('',(#52902),#52928); -#52902 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#52903,#52904,#52905,#52906, - #52907,#52908,#52909,#52910,#52911,#52912,#52913,#52914,#52915, - #52916,#52917,#52918,#52919,#52920,#52921,#52922,#52923,#52924, - #52925,#52926,#52927),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55247 = ORIENTED_EDGE('',*,*,#55248,.T.); +#55248 = EDGE_CURVE('',#55227,#55249,#55251,.T.); +#55249 = VERTEX_POINT('',#55250); +#55250 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.35)); +#55251 = SURFACE_CURVE('',#55252,(#55256,#55263),.PCURVE_S1.); +#55252 = LINE('',#55253,#55254); +#55253 = CARTESIAN_POINT('',(2.262642356365,0.906915204429,-2.35)); +#55254 = VECTOR('',#55255,1.); +#55255 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#55256 = PCURVE('',#54928,#55257); +#55257 = DEFINITIONAL_REPRESENTATION('',(#55258),#55262); +#55258 = LINE('',#55259,#55260); +#55259 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55260 = VECTOR('',#55261,1.); +#55261 = DIRECTION('',(1.,0.E+000)); +#55262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55263 = PCURVE('',#42139,#55264); +#55264 = DEFINITIONAL_REPRESENTATION('',(#55265),#55269); +#55265 = LINE('',#55266,#55267); +#55266 = CARTESIAN_POINT('',(2.262642356365,0.906915204429)); +#55267 = VECTOR('',#55268,1.); +#55268 = DIRECTION('',(-0.819152044289,-0.573576436351)); +#55269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55270 = ORIENTED_EDGE('',*,*,#55271,.F.); +#55271 = EDGE_CURVE('',#55272,#55249,#55274,.T.); +#55272 = VERTEX_POINT('',#55273); +#55273 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); +#55274 = SURFACE_CURVE('',#55275,(#55280,#55287),.PCURVE_S1.); +#55275 = CIRCLE('',#55276,0.3); +#55276 = AXIS2_PLACEMENT_3D('',#55277,#55278,#55279); +#55277 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.05)); +#55278 = DIRECTION('',(0.573576436351,-0.819152044289,0.E+000)); +#55279 = DIRECTION('',(-0.819152044289,-0.573576436351,0.E+000)); +#55280 = PCURVE('',#54928,#55281); +#55281 = DEFINITIONAL_REPRESENTATION('',(#55282),#55286); +#55282 = CIRCLE('',#55283,0.3); +#55283 = AXIS2_PLACEMENT_2D('',#55284,#55285); +#55284 = CARTESIAN_POINT('',(0.340997074522,-0.3)); +#55285 = DIRECTION('',(1.,0.E+000)); +#55286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55287 = PCURVE('',#55288,#55293); +#55288 = CYLINDRICAL_SURFACE('',#55289,0.3); +#55289 = AXIS2_PLACEMENT_3D('',#55290,#55291,#55292); +#55290 = CARTESIAN_POINT('',(1.992212732749,0.698618475469,-2.05)); +#55291 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#55292 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55293 = DEFINITIONAL_REPRESENTATION('',(#55294),#55320); +#55294 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55295,#55296,#55297,#55298, + #55299,#55300,#55301,#55302,#55303,#55304,#55305,#55306,#55307, + #55308,#55309,#55310,#55311,#55312,#55313,#55314,#55315,#55316, + #55317,#55318,#55319),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -65708,126 +68697,126 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#52903 = CARTESIAN_POINT('',(1.570796326795,1.551463154845E-002)); -#52904 = CARTESIAN_POINT('',(1.54699638245,1.551463154845E-002)); -#52905 = CARTESIAN_POINT('',(1.499396493759,1.551463154845E-002)); -#52906 = CARTESIAN_POINT('',(1.427996660723,1.551463154845E-002)); -#52907 = CARTESIAN_POINT('',(1.356596827687,1.551463154845E-002)); -#52908 = CARTESIAN_POINT('',(1.285196994651,1.551463154845E-002)); -#52909 = CARTESIAN_POINT('',(1.213797161614,1.551463154845E-002)); -#52910 = CARTESIAN_POINT('',(1.142397328578,1.551463154845E-002)); -#52911 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); -#52912 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); -#52913 = CARTESIAN_POINT('',(0.92819782947,1.551463154845E-002)); -#52914 = CARTESIAN_POINT('',(0.856797996434,1.551463154845E-002)); -#52915 = CARTESIAN_POINT('',(0.785398163398,1.551463154845E-002)); -#52916 = CARTESIAN_POINT('',(0.713998330362,1.551463154845E-002)); -#52917 = CARTESIAN_POINT('',(0.642598497326,1.551463154845E-002)); -#52918 = CARTESIAN_POINT('',(0.57119866429,1.551463154845E-002)); -#52919 = CARTESIAN_POINT('',(0.499798831253,1.551463154845E-002)); -#52920 = CARTESIAN_POINT('',(0.428398998217,1.551463154845E-002)); -#52921 = CARTESIAN_POINT('',(0.356999165181,1.551463154845E-002)); -#52922 = CARTESIAN_POINT('',(0.285599332145,1.551463154845E-002)); -#52923 = CARTESIAN_POINT('',(0.214199499109,1.551463154845E-002)); -#52924 = CARTESIAN_POINT('',(0.142799666073,1.551463154845E-002)); -#52925 = CARTESIAN_POINT('',(7.139983303682E-002,1.551463154845E-002)); -#52926 = CARTESIAN_POINT('',(2.379994434573E-002,1.551463154845E-002)); -#52927 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); -#52928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52929 = ORIENTED_EDGE('',*,*,#52930,.T.); -#52930 = EDGE_CURVE('',#52880,#52712,#52931,.T.); -#52931 = SURFACE_CURVE('',#52932,(#52936,#52943),.PCURVE_S1.); -#52932 = LINE('',#52933,#52934); -#52933 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); -#52934 = VECTOR('',#52935,1.); -#52935 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52936 = PCURVE('',#52536,#52937); -#52937 = DEFINITIONAL_REPRESENTATION('',(#52938),#52942); -#52938 = LINE('',#52939,#52940); -#52939 = CARTESIAN_POINT('',(0.640997074522,-0.3)); -#52940 = VECTOR('',#52941,1.); -#52941 = DIRECTION('',(0.E+000,-1.)); -#52942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52943 = PCURVE('',#52817,#52944); -#52944 = DEFINITIONAL_REPRESENTATION('',(#52945),#52949); -#52945 = LINE('',#52946,#52947); -#52946 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#52947 = VECTOR('',#52948,1.); -#52948 = DIRECTION('',(0.E+000,-1.)); -#52949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52950 = ADVANCED_FACE('',(#52951),#47519,.F.); -#52951 = FACE_BOUND('',#52952,.F.); -#52952 = EDGE_LOOP('',(#52953,#52974,#52975,#52976)); -#52953 = ORIENTED_EDGE('',*,*,#52954,.T.); -#52954 = EDGE_CURVE('',#47481,#52835,#52955,.T.); -#52955 = SURFACE_CURVE('',#52956,(#52961,#52967),.PCURVE_S1.); -#52956 = CIRCLE('',#52957,0.1); -#52957 = AXIS2_PLACEMENT_3D('',#52958,#52959,#52960); -#52958 = CARTESIAN_POINT('',(2.32,0.825,-2.35)); -#52959 = DIRECTION('',(0.E+000,0.E+000,1.)); -#52960 = DIRECTION('',(0.E+000,1.,0.E+000)); -#52961 = PCURVE('',#47519,#52962); -#52962 = DEFINITIONAL_REPRESENTATION('',(#52963),#52966); -#52963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#52964,#52965),.UNSPECIFIED., +#55295 = CARTESIAN_POINT('',(1.570796326795,1.551463154845E-002)); +#55296 = CARTESIAN_POINT('',(1.54699638245,1.551463154845E-002)); +#55297 = CARTESIAN_POINT('',(1.499396493759,1.551463154845E-002)); +#55298 = CARTESIAN_POINT('',(1.427996660723,1.551463154845E-002)); +#55299 = CARTESIAN_POINT('',(1.356596827687,1.551463154845E-002)); +#55300 = CARTESIAN_POINT('',(1.285196994651,1.551463154845E-002)); +#55301 = CARTESIAN_POINT('',(1.213797161614,1.551463154845E-002)); +#55302 = CARTESIAN_POINT('',(1.142397328578,1.551463154845E-002)); +#55303 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); +#55304 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); +#55305 = CARTESIAN_POINT('',(0.92819782947,1.551463154845E-002)); +#55306 = CARTESIAN_POINT('',(0.856797996434,1.551463154845E-002)); +#55307 = CARTESIAN_POINT('',(0.785398163398,1.551463154845E-002)); +#55308 = CARTESIAN_POINT('',(0.713998330362,1.551463154845E-002)); +#55309 = CARTESIAN_POINT('',(0.642598497326,1.551463154845E-002)); +#55310 = CARTESIAN_POINT('',(0.57119866429,1.551463154845E-002)); +#55311 = CARTESIAN_POINT('',(0.499798831253,1.551463154845E-002)); +#55312 = CARTESIAN_POINT('',(0.428398998217,1.551463154845E-002)); +#55313 = CARTESIAN_POINT('',(0.356999165181,1.551463154845E-002)); +#55314 = CARTESIAN_POINT('',(0.285599332145,1.551463154845E-002)); +#55315 = CARTESIAN_POINT('',(0.214199499109,1.551463154845E-002)); +#55316 = CARTESIAN_POINT('',(0.142799666073,1.551463154845E-002)); +#55317 = CARTESIAN_POINT('',(7.139983303682E-002,1.551463154845E-002)); +#55318 = CARTESIAN_POINT('',(2.379994434573E-002,1.551463154845E-002)); +#55319 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); +#55320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55321 = ORIENTED_EDGE('',*,*,#55322,.T.); +#55322 = EDGE_CURVE('',#55272,#55104,#55323,.T.); +#55323 = SURFACE_CURVE('',#55324,(#55328,#55335),.PCURVE_S1.); +#55324 = LINE('',#55325,#55326); +#55325 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); +#55326 = VECTOR('',#55327,1.); +#55327 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55328 = PCURVE('',#54928,#55329); +#55329 = DEFINITIONAL_REPRESENTATION('',(#55330),#55334); +#55330 = LINE('',#55331,#55332); +#55331 = CARTESIAN_POINT('',(0.640997074522,-0.3)); +#55332 = VECTOR('',#55333,1.); +#55333 = DIRECTION('',(0.E+000,-1.)); +#55334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55335 = PCURVE('',#55209,#55336); +#55336 = DEFINITIONAL_REPRESENTATION('',(#55337),#55341); +#55337 = LINE('',#55338,#55339); +#55338 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#55339 = VECTOR('',#55340,1.); +#55340 = DIRECTION('',(0.E+000,-1.)); +#55341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55342 = ADVANCED_FACE('',(#55343),#49911,.F.); +#55343 = FACE_BOUND('',#55344,.F.); +#55344 = EDGE_LOOP('',(#55345,#55366,#55367,#55368)); +#55345 = ORIENTED_EDGE('',*,*,#55346,.T.); +#55346 = EDGE_CURVE('',#49873,#55227,#55347,.T.); +#55347 = SURFACE_CURVE('',#55348,(#55353,#55359),.PCURVE_S1.); +#55348 = CIRCLE('',#55349,0.1); +#55349 = AXIS2_PLACEMENT_3D('',#55350,#55351,#55352); +#55350 = CARTESIAN_POINT('',(2.32,0.825,-2.35)); +#55351 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55352 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55353 = PCURVE('',#49911,#55354); +#55354 = DEFINITIONAL_REPRESENTATION('',(#55355),#55358); +#55355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55356,#55357),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238197),.PIECEWISE_BEZIER_KNOTS.); -#52964 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#52965 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); -#52966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52967 = PCURVE('',#39747,#52968); -#52968 = DEFINITIONAL_REPRESENTATION('',(#52969),#52973); -#52969 = CIRCLE('',#52970,1.E-001); -#52970 = AXIS2_PLACEMENT_2D('',#52971,#52972); -#52971 = CARTESIAN_POINT('',(2.32,0.825)); -#52972 = DIRECTION('',(0.E+000,1.)); -#52973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52974 = ORIENTED_EDGE('',*,*,#52834,.T.); -#52975 = ORIENTED_EDGE('',*,*,#52495,.F.); -#52976 = ORIENTED_EDGE('',*,*,#47503,.F.); -#52977 = ADVANCED_FACE('',(#52978),#47355,.F.); -#52978 = FACE_BOUND('',#52979,.F.); -#52979 = EDGE_LOOP('',(#52980,#53032,#53055,#53080,#53081,#53104,#53127, - #53155,#53183,#53210,#53238,#53270,#53293,#53318,#53319,#53342)); -#52980 = ORIENTED_EDGE('',*,*,#52981,.F.); -#52981 = EDGE_CURVE('',#52982,#52984,#52986,.T.); -#52982 = VERTEX_POINT('',#52983); -#52983 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.35)); -#52984 = VERTEX_POINT('',#52985); -#52985 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.35)); -#52986 = SURFACE_CURVE('',#52987,(#52991,#52998),.PCURVE_S1.); -#52987 = LINE('',#52988,#52989); -#52988 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.35)); -#52989 = VECTOR('',#52990,1.); -#52990 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#52991 = PCURVE('',#47355,#52992); -#52992 = DEFINITIONAL_REPRESENTATION('',(#52993),#52997); -#52993 = LINE('',#52994,#52995); -#52994 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905)); -#52995 = VECTOR('',#52996,1.); -#52996 = DIRECTION('',(-0.573576436351,-0.819152044289)); -#52997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#52998 = PCURVE('',#52999,#53004); -#52999 = CYLINDRICAL_SURFACE('',#53000,0.3); -#53000 = AXIS2_PLACEMENT_3D('',#53001,#53002,#53003); -#53001 = CARTESIAN_POINT('',(-1.802342147694,0.969781773054,-2.05)); -#53002 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#53003 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53004 = DEFINITIONAL_REPRESENTATION('',(#53005),#53031); -#53005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53006,#53007,#53008,#53009, - #53010,#53011,#53012,#53013,#53014,#53015,#53016,#53017,#53018, - #53019,#53020,#53021,#53022,#53023,#53024,#53025,#53026,#53027, - #53028,#53029,#53030),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55356 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55357 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); +#55358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55359 = PCURVE('',#42139,#55360); +#55360 = DEFINITIONAL_REPRESENTATION('',(#55361),#55365); +#55361 = CIRCLE('',#55362,1.E-001); +#55362 = AXIS2_PLACEMENT_2D('',#55363,#55364); +#55363 = CARTESIAN_POINT('',(2.32,0.825)); +#55364 = DIRECTION('',(0.E+000,1.)); +#55365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55366 = ORIENTED_EDGE('',*,*,#55226,.T.); +#55367 = ORIENTED_EDGE('',*,*,#54887,.F.); +#55368 = ORIENTED_EDGE('',*,*,#49895,.F.); +#55369 = ADVANCED_FACE('',(#55370),#49747,.F.); +#55370 = FACE_BOUND('',#55371,.F.); +#55371 = EDGE_LOOP('',(#55372,#55424,#55447,#55472,#55473,#55496,#55519, + #55547,#55575,#55602,#55630,#55662,#55685,#55710,#55711,#55734)); +#55372 = ORIENTED_EDGE('',*,*,#55373,.F.); +#55373 = EDGE_CURVE('',#55374,#55376,#55378,.T.); +#55374 = VERTEX_POINT('',#55375); +#55375 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.35)); +#55376 = VERTEX_POINT('',#55377); +#55377 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.35)); +#55378 = SURFACE_CURVE('',#55379,(#55383,#55390),.PCURVE_S1.); +#55379 = LINE('',#55380,#55381); +#55380 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.35)); +#55381 = VECTOR('',#55382,1.); +#55382 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#55383 = PCURVE('',#49747,#55384); +#55384 = DEFINITIONAL_REPRESENTATION('',(#55385),#55389); +#55385 = LINE('',#55386,#55387); +#55386 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905)); +#55387 = VECTOR('',#55388,1.); +#55388 = DIRECTION('',(-0.573576436351,-0.819152044289)); +#55389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55390 = PCURVE('',#55391,#55396); +#55391 = CYLINDRICAL_SURFACE('',#55392,0.3); +#55392 = AXIS2_PLACEMENT_3D('',#55393,#55394,#55395); +#55393 = CARTESIAN_POINT('',(-1.802342147694,0.969781773054,-2.05)); +#55394 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#55395 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55396 = DEFINITIONAL_REPRESENTATION('',(#55397),#55423); +#55397 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55398,#55399,#55400,#55401, + #55402,#55403,#55404,#55405,#55406,#55407,#55408,#55409,#55410, + #55411,#55412,#55413,#55414,#55415,#55416,#55417,#55418,#55419, + #55420,#55421,#55422),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363636E-002, 2.727272727271E-002,4.090909090907E-002,5.454545454542E-002, 6.818181818178E-002,8.181818181813E-002,9.545454545449E-002, @@ -65835,470 +68824,470 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#53006 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); -#53007 = CARTESIAN_POINT('',(-3.561595462998E-013,2.00600860939E-002)); -#53008 = CARTESIAN_POINT('',(-6.892264536873E-013,2.91509951848E-002)); -#53009 = CARTESIAN_POINT('',(-5.542233338929E-013,4.278735882116E-002)); -#53010 = CARTESIAN_POINT('',(-5.9241500594E-013,5.642372245751E-002)); -#53011 = CARTESIAN_POINT('',(-5.808686864839E-013,7.006008609387E-002)); -#53012 = CARTESIAN_POINT('',(-5.83533221743E-013,8.369644973022E-002)); -#53013 = CARTESIAN_POINT('',(-5.826450433233E-013,9.733281336658E-002)); -#53014 = CARTESIAN_POINT('',(-5.853095785824E-013,0.110969177003)); -#53015 = CARTESIAN_POINT('',(-5.83533221743E-013,0.124605540639)); -#53016 = CARTESIAN_POINT('',(-5.83533221743E-013,0.138241904276)); -#53017 = CARTESIAN_POINT('',(-5.844214001627E-013,0.151878267912)); -#53018 = CARTESIAN_POINT('',(-5.83533221743E-013,0.165514631548)); -#53019 = CARTESIAN_POINT('',(-5.826450433233E-013,0.179150995185)); -#53020 = CARTESIAN_POINT('',(-5.844214001627E-013,0.192787358821)); -#53021 = CARTESIAN_POINT('',(-5.83533221743E-013,0.206423722457)); -#53022 = CARTESIAN_POINT('',(-5.826450433233E-013,0.220060086094)); -#53023 = CARTESIAN_POINT('',(-5.83533221743E-013,0.23369644973)); -#53024 = CARTESIAN_POINT('',(-5.844214001627E-013,0.247332813366)); -#53025 = CARTESIAN_POINT('',(-5.826450433233E-013,0.260969177003)); -#53026 = CARTESIAN_POINT('',(-5.897504706809E-013,0.274605540639)); -#53027 = CARTESIAN_POINT('',(-5.559996907323E-013,0.288241904276)); -#53028 = CARTESIAN_POINT('',(-6.874500968479E-013,0.301878267912)); -#53029 = CARTESIAN_POINT('',(-3.570477247195E-013,0.310969177003)); -#53030 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#53031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53032 = ORIENTED_EDGE('',*,*,#53033,.F.); -#53033 = EDGE_CURVE('',#53034,#52982,#53036,.T.); -#53034 = VERTEX_POINT('',#53035); -#53035 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); -#53036 = SURFACE_CURVE('',#53037,(#53041,#53048),.PCURVE_S1.); -#53037 = LINE('',#53038,#53039); -#53038 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); -#53039 = VECTOR('',#53040,1.); -#53040 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#53041 = PCURVE('',#47355,#53042); -#53042 = DEFINITIONAL_REPRESENTATION('',(#53043),#53047); -#53043 = LINE('',#53044,#53045); -#53044 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858)); -#53045 = VECTOR('',#53046,1.); -#53046 = DIRECTION('',(0.819152044289,-0.573576436351)); -#53047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53048 = PCURVE('',#52696,#53049); -#53049 = DEFINITIONAL_REPRESENTATION('',(#53050),#53054); -#53050 = LINE('',#53051,#53052); -#53051 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53052 = VECTOR('',#53053,1.); -#53053 = DIRECTION('',(1.,0.E+000)); -#53054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53055 = ORIENTED_EDGE('',*,*,#53056,.F.); -#53056 = EDGE_CURVE('',#49265,#53034,#53057,.T.); -#53057 = SURFACE_CURVE('',#53058,(#53063,#53074),.PCURVE_S1.); -#53058 = CIRCLE('',#53059,0.2); -#53059 = AXIS2_PLACEMENT_3D('',#53060,#53061,#53062); -#53060 = CARTESIAN_POINT('',(-2.256940242224,1.025,-2.35)); -#53061 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53062 = DIRECTION('',(0.E+000,1.,0.E+000)); -#53063 = PCURVE('',#47355,#53064); -#53064 = DEFINITIONAL_REPRESENTATION('',(#53065),#53073); -#53065 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53066,#53067,#53068,#53069 - ,#53070,#53071,#53072),.UNSPECIFIED.,.T.,.F.) +#55398 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); +#55399 = CARTESIAN_POINT('',(-3.561595462998E-013,2.00600860939E-002)); +#55400 = CARTESIAN_POINT('',(-6.892264536873E-013,2.91509951848E-002)); +#55401 = CARTESIAN_POINT('',(-5.542233338929E-013,4.278735882116E-002)); +#55402 = CARTESIAN_POINT('',(-5.9241500594E-013,5.642372245751E-002)); +#55403 = CARTESIAN_POINT('',(-5.808686864839E-013,7.006008609387E-002)); +#55404 = CARTESIAN_POINT('',(-5.83533221743E-013,8.369644973022E-002)); +#55405 = CARTESIAN_POINT('',(-5.826450433233E-013,9.733281336658E-002)); +#55406 = CARTESIAN_POINT('',(-5.853095785824E-013,0.110969177003)); +#55407 = CARTESIAN_POINT('',(-5.83533221743E-013,0.124605540639)); +#55408 = CARTESIAN_POINT('',(-5.83533221743E-013,0.138241904276)); +#55409 = CARTESIAN_POINT('',(-5.844214001627E-013,0.151878267912)); +#55410 = CARTESIAN_POINT('',(-5.83533221743E-013,0.165514631548)); +#55411 = CARTESIAN_POINT('',(-5.826450433233E-013,0.179150995185)); +#55412 = CARTESIAN_POINT('',(-5.844214001627E-013,0.192787358821)); +#55413 = CARTESIAN_POINT('',(-5.83533221743E-013,0.206423722457)); +#55414 = CARTESIAN_POINT('',(-5.826450433233E-013,0.220060086094)); +#55415 = CARTESIAN_POINT('',(-5.83533221743E-013,0.23369644973)); +#55416 = CARTESIAN_POINT('',(-5.844214001627E-013,0.247332813366)); +#55417 = CARTESIAN_POINT('',(-5.826450433233E-013,0.260969177003)); +#55418 = CARTESIAN_POINT('',(-5.897504706809E-013,0.274605540639)); +#55419 = CARTESIAN_POINT('',(-5.559996907323E-013,0.288241904276)); +#55420 = CARTESIAN_POINT('',(-6.874500968479E-013,0.301878267912)); +#55421 = CARTESIAN_POINT('',(-3.570477247195E-013,0.310969177003)); +#55422 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#55423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55424 = ORIENTED_EDGE('',*,*,#55425,.F.); +#55425 = EDGE_CURVE('',#55426,#55374,#55428,.T.); +#55426 = VERTEX_POINT('',#55427); +#55427 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); +#55428 = SURFACE_CURVE('',#55429,(#55433,#55440),.PCURVE_S1.); +#55429 = LINE('',#55430,#55431); +#55430 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); +#55431 = VECTOR('',#55432,1.); +#55432 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#55433 = PCURVE('',#49747,#55434); +#55434 = DEFINITIONAL_REPRESENTATION('',(#55435),#55439); +#55435 = LINE('',#55436,#55437); +#55436 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858)); +#55437 = VECTOR('',#55438,1.); +#55438 = DIRECTION('',(0.819152044289,-0.573576436351)); +#55439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55440 = PCURVE('',#55088,#55441); +#55441 = DEFINITIONAL_REPRESENTATION('',(#55442),#55446); +#55442 = LINE('',#55443,#55444); +#55443 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55444 = VECTOR('',#55445,1.); +#55445 = DIRECTION('',(1.,0.E+000)); +#55446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55447 = ORIENTED_EDGE('',*,*,#55448,.F.); +#55448 = EDGE_CURVE('',#51657,#55426,#55449,.T.); +#55449 = SURFACE_CURVE('',#55450,(#55455,#55466),.PCURVE_S1.); +#55450 = CIRCLE('',#55451,0.2); +#55451 = AXIS2_PLACEMENT_3D('',#55452,#55453,#55454); +#55452 = CARTESIAN_POINT('',(-2.256940242224,1.025,-2.35)); +#55453 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55454 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55455 = PCURVE('',#49747,#55456); +#55456 = DEFINITIONAL_REPRESENTATION('',(#55457),#55465); +#55457 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55458,#55459,#55460,#55461 + ,#55462,#55463,#55464),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#53066 = CARTESIAN_POINT('',(-2.256940242224,1.225)); -#53067 = CARTESIAN_POINT('',(-1.91053008071,1.225)); -#53068 = CARTESIAN_POINT('',(-2.083735161467,0.925)); -#53069 = CARTESIAN_POINT('',(-2.256940242224,0.625)); -#53070 = CARTESIAN_POINT('',(-2.430145322981,0.925)); -#53071 = CARTESIAN_POINT('',(-2.603350403738,1.225)); -#53072 = CARTESIAN_POINT('',(-2.256940242224,1.225)); -#53073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53074 = PCURVE('',#49303,#53075); -#53075 = DEFINITIONAL_REPRESENTATION('',(#53076),#53079); -#53076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53077,#53078),.UNSPECIFIED., +#55458 = CARTESIAN_POINT('',(-2.256940242224,1.225)); +#55459 = CARTESIAN_POINT('',(-1.91053008071,1.225)); +#55460 = CARTESIAN_POINT('',(-2.083735161467,0.925)); +#55461 = CARTESIAN_POINT('',(-2.256940242224,0.625)); +#55462 = CARTESIAN_POINT('',(-2.430145322981,0.925)); +#55463 = CARTESIAN_POINT('',(-2.603350403738,1.225)); +#55464 = CARTESIAN_POINT('',(-2.256940242224,1.225)); +#55465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55466 = PCURVE('',#51695,#55467); +#55467 = DEFINITIONAL_REPRESENTATION('',(#55468),#55471); +#55468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55469,#55470),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238197),.PIECEWISE_BEZIER_KNOTS.); -#53077 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53078 = CARTESIAN_POINT('',(2.181661564991,0.E+000)); -#53079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53080 = ORIENTED_EDGE('',*,*,#49264,.F.); -#53081 = ORIENTED_EDGE('',*,*,#53082,.T.); -#53082 = EDGE_CURVE('',#49243,#53083,#53085,.T.); -#53083 = VERTEX_POINT('',#53084); -#53084 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); -#53085 = SURFACE_CURVE('',#53086,(#53091,#53098),.PCURVE_S1.); -#53086 = CIRCLE('',#53087,0.55); -#53087 = AXIS2_PLACEMENT_3D('',#53088,#53089,#53090); -#53088 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); -#53089 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53090 = DIRECTION('',(0.E+000,1.,0.E+000)); -#53091 = PCURVE('',#47355,#53092); -#53092 = DEFINITIONAL_REPRESENTATION('',(#53093),#53097); -#53093 = CIRCLE('',#53094,0.55); -#53094 = AXIS2_PLACEMENT_2D('',#53095,#53096); -#53095 = CARTESIAN_POINT('',(-3.2,0.675)); -#53096 = DIRECTION('',(0.E+000,1.)); -#53097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53098 = PCURVE('',#38411,#53099); -#53099 = DEFINITIONAL_REPRESENTATION('',(#53100),#53103); -#53100 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53101,#53102),.UNSPECIFIED., +#55469 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55470 = CARTESIAN_POINT('',(2.181661564991,0.E+000)); +#55471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55472 = ORIENTED_EDGE('',*,*,#51656,.F.); +#55473 = ORIENTED_EDGE('',*,*,#55474,.T.); +#55474 = EDGE_CURVE('',#51635,#55475,#55477,.T.); +#55475 = VERTEX_POINT('',#55476); +#55476 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); +#55477 = SURFACE_CURVE('',#55478,(#55483,#55490),.PCURVE_S1.); +#55478 = CIRCLE('',#55479,0.55); +#55479 = AXIS2_PLACEMENT_3D('',#55480,#55481,#55482); +#55480 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); +#55481 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55482 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55483 = PCURVE('',#49747,#55484); +#55484 = DEFINITIONAL_REPRESENTATION('',(#55485),#55489); +#55485 = CIRCLE('',#55486,0.55); +#55486 = AXIS2_PLACEMENT_2D('',#55487,#55488); +#55487 = CARTESIAN_POINT('',(-3.2,0.675)); +#55488 = DIRECTION('',(0.E+000,1.)); +#55489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55490 = PCURVE('',#40803,#55491); +#55491 = DEFINITIONAL_REPRESENTATION('',(#55492),#55495); +#55492 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55493,#55494),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#53101 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53102 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#53103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53104 = ORIENTED_EDGE('',*,*,#53105,.T.); -#53105 = EDGE_CURVE('',#53083,#53106,#53108,.T.); -#53106 = VERTEX_POINT('',#53107); -#53107 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-2.35)); -#53108 = SURFACE_CURVE('',#53109,(#53113,#53120),.PCURVE_S1.); -#53109 = LINE('',#53110,#53111); -#53110 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); -#53111 = VECTOR('',#53112,1.); -#53112 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#53113 = PCURVE('',#47355,#53114); -#53114 = DEFINITIONAL_REPRESENTATION('',(#53115),#53119); -#53115 = LINE('',#53116,#53117); -#53116 = CARTESIAN_POINT('',(-3.75,0.675)); -#53117 = VECTOR('',#53118,1.); -#53118 = DIRECTION('',(0.E+000,-1.)); -#53119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53120 = PCURVE('',#37969,#53121); -#53121 = DEFINITIONAL_REPRESENTATION('',(#53122),#53126); -#53122 = LINE('',#53123,#53124); -#53123 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53124 = VECTOR('',#53125,1.); -#53125 = DIRECTION('',(1.,0.E+000)); -#53126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53127 = ORIENTED_EDGE('',*,*,#53128,.T.); -#53128 = EDGE_CURVE('',#53106,#53129,#53131,.T.); -#53129 = VERTEX_POINT('',#53130); -#53130 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); -#53131 = SURFACE_CURVE('',#53132,(#53137,#53144),.PCURVE_S1.); -#53132 = CIRCLE('',#53133,0.55); -#53133 = AXIS2_PLACEMENT_3D('',#53134,#53135,#53136); -#53134 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#53135 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53136 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#53137 = PCURVE('',#47355,#53138); -#53138 = DEFINITIONAL_REPRESENTATION('',(#53139),#53143); -#53139 = CIRCLE('',#53140,0.55); -#53140 = AXIS2_PLACEMENT_2D('',#53141,#53142); -#53141 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002)); -#53142 = DIRECTION('',(-1.,0.E+000)); -#53143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53144 = PCURVE('',#53145,#53150); -#53145 = CYLINDRICAL_SURFACE('',#53146,0.55); -#53146 = AXIS2_PLACEMENT_3D('',#53147,#53148,#53149); -#53147 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#53148 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53149 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53150 = DEFINITIONAL_REPRESENTATION('',(#53151),#53154); -#53151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53152,#53153),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#53152 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#53153 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); -#53154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53155 = ORIENTED_EDGE('',*,*,#53156,.T.); -#53156 = EDGE_CURVE('',#53129,#53157,#53159,.T.); -#53157 = VERTEX_POINT('',#53158); -#53158 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); -#53159 = SURFACE_CURVE('',#53160,(#53164,#53171),.PCURVE_S1.); -#53160 = LINE('',#53161,#53162); -#53161 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); -#53162 = VECTOR('',#53163,1.); -#53163 = DIRECTION('',(0.707106781187,-0.707106781186,0.E+000)); -#53164 = PCURVE('',#47355,#53165); -#53165 = DEFINITIONAL_REPRESENTATION('',(#53166),#53170); -#53166 = LINE('',#53167,#53168); -#53167 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059)); -#53168 = VECTOR('',#53169,1.); -#53169 = DIRECTION('',(0.707106781187,-0.707106781186)); -#53170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#55493 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55494 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#55495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#53171 = PCURVE('',#53172,#53177); -#53172 = PLANE('',#53173); -#53173 = AXIS2_PLACEMENT_3D('',#53174,#53175,#53176); -#53174 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); -#53175 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#53176 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#53177 = DEFINITIONAL_REPRESENTATION('',(#53178),#53182); -#53178 = LINE('',#53179,#53180); -#53179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53180 = VECTOR('',#53181,1.); -#53181 = DIRECTION('',(1.,0.E+000)); -#53182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53183 = ORIENTED_EDGE('',*,*,#53184,.T.); -#53184 = EDGE_CURVE('',#53157,#53185,#53187,.T.); -#53185 = VERTEX_POINT('',#53186); -#53186 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); -#53187 = SURFACE_CURVE('',#53188,(#53192,#53199),.PCURVE_S1.); -#53188 = LINE('',#53189,#53190); -#53189 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); -#53190 = VECTOR('',#53191,1.); -#53191 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53192 = PCURVE('',#47355,#53193); -#53193 = DEFINITIONAL_REPRESENTATION('',(#53194),#53198); -#53194 = LINE('',#53195,#53196); -#53195 = CARTESIAN_POINT('',(-3.474264068712,-0.575)); -#53196 = VECTOR('',#53197,1.); -#53197 = DIRECTION('',(1.,0.E+000)); -#53198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53199 = PCURVE('',#53200,#53205); -#53200 = CYLINDRICAL_SURFACE('',#53201,0.15); -#53201 = AXIS2_PLACEMENT_3D('',#53202,#53203,#53204); -#53202 = CARTESIAN_POINT('',(-3.75,-0.575,-2.2)); -#53203 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53204 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53205 = DEFINITIONAL_REPRESENTATION('',(#53206),#53209); -#53206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53207,#53208),.UNSPECIFIED., +#55496 = ORIENTED_EDGE('',*,*,#55497,.T.); +#55497 = EDGE_CURVE('',#55475,#55498,#55500,.T.); +#55498 = VERTEX_POINT('',#55499); +#55499 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-2.35)); +#55500 = SURFACE_CURVE('',#55501,(#55505,#55512),.PCURVE_S1.); +#55501 = LINE('',#55502,#55503); +#55502 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); +#55503 = VECTOR('',#55504,1.); +#55504 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#55505 = PCURVE('',#49747,#55506); +#55506 = DEFINITIONAL_REPRESENTATION('',(#55507),#55511); +#55507 = LINE('',#55508,#55509); +#55508 = CARTESIAN_POINT('',(-3.75,0.675)); +#55509 = VECTOR('',#55510,1.); +#55510 = DIRECTION('',(0.E+000,-1.)); +#55511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55512 = PCURVE('',#40361,#55513); +#55513 = DEFINITIONAL_REPRESENTATION('',(#55514),#55518); +#55514 = LINE('',#55515,#55516); +#55515 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55516 = VECTOR('',#55517,1.); +#55517 = DIRECTION('',(1.,0.E+000)); +#55518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55519 = ORIENTED_EDGE('',*,*,#55520,.T.); +#55520 = EDGE_CURVE('',#55498,#55521,#55523,.T.); +#55521 = VERTEX_POINT('',#55522); +#55522 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); +#55523 = SURFACE_CURVE('',#55524,(#55529,#55536),.PCURVE_S1.); +#55524 = CIRCLE('',#55525,0.55); +#55525 = AXIS2_PLACEMENT_3D('',#55526,#55527,#55528); +#55526 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#55527 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55528 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#55529 = PCURVE('',#49747,#55530); +#55530 = DEFINITIONAL_REPRESENTATION('',(#55531),#55535); +#55531 = CIRCLE('',#55532,0.55); +#55532 = AXIS2_PLACEMENT_2D('',#55533,#55534); +#55533 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002)); +#55534 = DIRECTION('',(-1.,0.E+000)); +#55535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55536 = PCURVE('',#55537,#55542); +#55537 = CYLINDRICAL_SURFACE('',#55538,0.55); +#55538 = AXIS2_PLACEMENT_3D('',#55539,#55540,#55541); +#55539 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#55540 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55541 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55542 = DEFINITIONAL_REPRESENTATION('',(#55543),#55546); +#55543 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55544,#55545),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); +#55544 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#55545 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); +#55546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55547 = ORIENTED_EDGE('',*,*,#55548,.T.); +#55548 = EDGE_CURVE('',#55521,#55549,#55551,.T.); +#55549 = VERTEX_POINT('',#55550); +#55550 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); +#55551 = SURFACE_CURVE('',#55552,(#55556,#55563),.PCURVE_S1.); +#55552 = LINE('',#55553,#55554); +#55553 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); +#55554 = VECTOR('',#55555,1.); +#55555 = DIRECTION('',(0.707106781187,-0.707106781186,0.E+000)); +#55556 = PCURVE('',#49747,#55557); +#55557 = DEFINITIONAL_REPRESENTATION('',(#55558),#55562); +#55558 = LINE('',#55559,#55560); +#55559 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059)); +#55560 = VECTOR('',#55561,1.); +#55561 = DIRECTION('',(0.707106781187,-0.707106781186)); +#55562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55563 = PCURVE('',#55564,#55569); +#55564 = PLANE('',#55565); +#55565 = AXIS2_PLACEMENT_3D('',#55566,#55567,#55568); +#55566 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); +#55567 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#55568 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#55569 = DEFINITIONAL_REPRESENTATION('',(#55570),#55574); +#55570 = LINE('',#55571,#55572); +#55571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55572 = VECTOR('',#55573,1.); +#55573 = DIRECTION('',(1.,0.E+000)); +#55574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55575 = ORIENTED_EDGE('',*,*,#55576,.T.); +#55576 = EDGE_CURVE('',#55549,#55577,#55579,.T.); +#55577 = VERTEX_POINT('',#55578); +#55578 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); +#55579 = SURFACE_CURVE('',#55580,(#55584,#55591),.PCURVE_S1.); +#55580 = LINE('',#55581,#55582); +#55581 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); +#55582 = VECTOR('',#55583,1.); +#55583 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55584 = PCURVE('',#49747,#55585); +#55585 = DEFINITIONAL_REPRESENTATION('',(#55586),#55590); +#55586 = LINE('',#55587,#55588); +#55587 = CARTESIAN_POINT('',(-3.474264068712,-0.575)); +#55588 = VECTOR('',#55589,1.); +#55589 = DIRECTION('',(1.,0.E+000)); +#55590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55591 = PCURVE('',#55592,#55597); +#55592 = CYLINDRICAL_SURFACE('',#55593,0.15); +#55593 = AXIS2_PLACEMENT_3D('',#55594,#55595,#55596); +#55594 = CARTESIAN_POINT('',(-3.75,-0.575,-2.2)); +#55595 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55596 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55597 = DEFINITIONAL_REPRESENTATION('',(#55598),#55601); +#55598 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55599,#55600),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#53207 = CARTESIAN_POINT('',(6.28318530718,0.275735931288)); -#53208 = CARTESIAN_POINT('',(6.28318530718,0.7)); -#53209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53210 = ORIENTED_EDGE('',*,*,#53211,.T.); -#53211 = EDGE_CURVE('',#53185,#53212,#53214,.T.); -#53212 = VERTEX_POINT('',#53213); -#53213 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896,-2.35)); -#53214 = SURFACE_CURVE('',#53215,(#53219,#53226),.PCURVE_S1.); -#53215 = LINE('',#53216,#53217); -#53216 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); -#53217 = VECTOR('',#53218,1.); -#53218 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#53219 = PCURVE('',#47355,#53220); -#53220 = DEFINITIONAL_REPRESENTATION('',(#53221),#53225); -#53221 = LINE('',#53222,#53223); -#53222 = CARTESIAN_POINT('',(-3.05,-0.575)); -#53223 = VECTOR('',#53224,1.); -#53224 = DIRECTION('',(-0.707106781187,0.707106781187)); -#53225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#55599 = CARTESIAN_POINT('',(6.28318530718,0.275735931288)); +#55600 = CARTESIAN_POINT('',(6.28318530718,0.7)); +#55601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#53226 = PCURVE('',#53227,#53232); -#53227 = PLANE('',#53228); -#53228 = AXIS2_PLACEMENT_3D('',#53229,#53230,#53231); -#53229 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-2.35)); -#53230 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#53231 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#53232 = DEFINITIONAL_REPRESENTATION('',(#53233),#53237); -#53233 = LINE('',#53234,#53235); -#53234 = CARTESIAN_POINT('',(0.391421356238,0.E+000)); -#53235 = VECTOR('',#53236,1.); -#53236 = DIRECTION('',(1.,0.E+000)); -#53237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53238 = ORIENTED_EDGE('',*,*,#53239,.T.); -#53239 = EDGE_CURVE('',#53212,#53240,#53242,.T.); -#53240 = VERTEX_POINT('',#53241); -#53241 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); -#53242 = SURFACE_CURVE('',#53243,(#53248,#53259),.PCURVE_S1.); -#53243 = CIRCLE('',#53244,0.25); -#53244 = AXIS2_PLACEMENT_3D('',#53245,#53246,#53247); -#53245 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#53246 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53247 = DIRECTION('',(-0.70519837568,-0.709010049956,0.E+000)); -#53248 = PCURVE('',#47355,#53249); -#53249 = DEFINITIONAL_REPRESENTATION('',(#53250),#53258); -#53250 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53251,#53252,#53253,#53254 - ,#53255,#53256,#53257),.UNSPECIFIED.,.T.,.F.) +#55602 = ORIENTED_EDGE('',*,*,#55603,.T.); +#55603 = EDGE_CURVE('',#55577,#55604,#55606,.T.); +#55604 = VERTEX_POINT('',#55605); +#55605 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896,-2.35)); +#55606 = SURFACE_CURVE('',#55607,(#55611,#55618),.PCURVE_S1.); +#55607 = LINE('',#55608,#55609); +#55608 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); +#55609 = VECTOR('',#55610,1.); +#55610 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#55611 = PCURVE('',#49747,#55612); +#55612 = DEFINITIONAL_REPRESENTATION('',(#55613),#55617); +#55613 = LINE('',#55614,#55615); +#55614 = CARTESIAN_POINT('',(-3.05,-0.575)); +#55615 = VECTOR('',#55616,1.); +#55616 = DIRECTION('',(-0.707106781187,0.707106781187)); +#55617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55618 = PCURVE('',#55619,#55624); +#55619 = PLANE('',#55620); +#55620 = AXIS2_PLACEMENT_3D('',#55621,#55622,#55623); +#55621 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-2.35)); +#55622 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#55623 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#55624 = DEFINITIONAL_REPRESENTATION('',(#55625),#55629); +#55625 = LINE('',#55626,#55627); +#55626 = CARTESIAN_POINT('',(0.391421356238,0.E+000)); +#55627 = VECTOR('',#55628,1.); +#55628 = DIRECTION('',(1.,0.E+000)); +#55629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55630 = ORIENTED_EDGE('',*,*,#55631,.T.); +#55631 = EDGE_CURVE('',#55604,#55632,#55634,.T.); +#55632 = VERTEX_POINT('',#55633); +#55633 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); +#55634 = SURFACE_CURVE('',#55635,(#55640,#55651),.PCURVE_S1.); +#55635 = CIRCLE('',#55636,0.25); +#55636 = AXIS2_PLACEMENT_3D('',#55637,#55638,#55639); +#55637 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#55638 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55639 = DIRECTION('',(-0.70519837568,-0.709010049956,0.E+000)); +#55640 = PCURVE('',#49747,#55641); +#55641 = DEFINITIONAL_REPRESENTATION('',(#55642),#55650); +#55642 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55643,#55644,#55645,#55646 + ,#55647,#55648,#55649),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#53251 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896)); -#53252 = CARTESIAN_POINT('',(-3.68330995132,5.666073212728E-002)); -#53253 = CARTESIAN_POINT('',(-3.26535538174,0.169859573849)); -#53254 = CARTESIAN_POINT('',(-2.84740081216,0.283058415571)); -#53255 = CARTESIAN_POINT('',(-2.95834502434,-0.135500280174)); -#53256 = CARTESIAN_POINT('',(-3.06928923652,-0.554058975919)); -#53257 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896)); -#53258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53259 = PCURVE('',#53260,#53265); -#53260 = CYLINDRICAL_SURFACE('',#53261,0.25); -#53261 = AXIS2_PLACEMENT_3D('',#53262,#53263,#53264); -#53262 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); -#53263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53264 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53265 = DEFINITIONAL_REPRESENTATION('',(#53266),#53269); -#53266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53267,#53268),.UNSPECIFIED., +#55643 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896)); +#55644 = CARTESIAN_POINT('',(-3.68330995132,5.666073212728E-002)); +#55645 = CARTESIAN_POINT('',(-3.26535538174,0.169859573849)); +#55646 = CARTESIAN_POINT('',(-2.84740081216,0.283058415571)); +#55647 = CARTESIAN_POINT('',(-2.95834502434,-0.135500280174)); +#55648 = CARTESIAN_POINT('',(-3.06928923652,-0.554058975919)); +#55649 = CARTESIAN_POINT('',(-3.37629959392,-0.248699121896)); +#55650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55651 = PCURVE('',#55652,#55657); +#55652 = CYLINDRICAL_SURFACE('',#55653,0.25); +#55653 = AXIS2_PLACEMENT_3D('',#55654,#55655,#55656); +#55654 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-2.35)); +#55655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55656 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55657 = DEFINITIONAL_REPRESENTATION('',(#55658),#55661); +#55658 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55659,#55660),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.788093427389),.PIECEWISE_BEZIER_KNOTS.); -#53267 = CARTESIAN_POINT('',(3.929686080979,0.E+000)); -#53268 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#53269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53270 = ORIENTED_EDGE('',*,*,#53271,.T.); -#53271 = EDGE_CURVE('',#53240,#53272,#53274,.T.); -#53272 = VERTEX_POINT('',#53273); -#53273 = CARTESIAN_POINT('',(-3.45,0.675,-2.35)); -#53274 = SURFACE_CURVE('',#53275,(#53279,#53286),.PCURVE_S1.); -#53275 = LINE('',#53276,#53277); -#53276 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); -#53277 = VECTOR('',#53278,1.); -#53278 = DIRECTION('',(0.E+000,1.,0.E+000)); -#53279 = PCURVE('',#47355,#53280); -#53280 = DEFINITIONAL_REPRESENTATION('',(#53281),#53285); -#53281 = LINE('',#53282,#53283); -#53282 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002)); -#53283 = VECTOR('',#53284,1.); -#53284 = DIRECTION('',(0.E+000,1.)); -#53285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53286 = PCURVE('',#37683,#53287); -#53287 = DEFINITIONAL_REPRESENTATION('',(#53288),#53292); -#53288 = LINE('',#53289,#53290); -#53289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53290 = VECTOR('',#53291,1.); -#53291 = DIRECTION('',(1.,0.E+000)); -#53292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53293 = ORIENTED_EDGE('',*,*,#53294,.T.); -#53294 = EDGE_CURVE('',#53272,#47340,#53295,.T.); -#53295 = SURFACE_CURVE('',#53296,(#53301,#53312),.PCURVE_S1.); -#53296 = CIRCLE('',#53297,0.25); -#53297 = AXIS2_PLACEMENT_3D('',#53298,#53299,#53300); -#53298 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); -#53299 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53300 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#53301 = PCURVE('',#47355,#53302); -#53302 = DEFINITIONAL_REPRESENTATION('',(#53303),#53311); -#53303 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53304,#53305,#53306,#53307 - ,#53308,#53309,#53310),.UNSPECIFIED.,.T.,.F.) +#55659 = CARTESIAN_POINT('',(3.929686080979,0.E+000)); +#55660 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#55661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55662 = ORIENTED_EDGE('',*,*,#55663,.T.); +#55663 = EDGE_CURVE('',#55632,#55664,#55666,.T.); +#55664 = VERTEX_POINT('',#55665); +#55665 = CARTESIAN_POINT('',(-3.45,0.675,-2.35)); +#55666 = SURFACE_CURVE('',#55667,(#55671,#55678),.PCURVE_S1.); +#55667 = LINE('',#55668,#55669); +#55668 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-2.35)); +#55669 = VECTOR('',#55670,1.); +#55670 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55671 = PCURVE('',#49747,#55672); +#55672 = DEFINITIONAL_REPRESENTATION('',(#55673),#55677); +#55673 = LINE('',#55674,#55675); +#55674 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002)); +#55675 = VECTOR('',#55676,1.); +#55676 = DIRECTION('',(0.E+000,1.)); +#55677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55678 = PCURVE('',#40075,#55679); +#55679 = DEFINITIONAL_REPRESENTATION('',(#55680),#55684); +#55680 = LINE('',#55681,#55682); +#55681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55682 = VECTOR('',#55683,1.); +#55683 = DIRECTION('',(1.,0.E+000)); +#55684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55685 = ORIENTED_EDGE('',*,*,#55686,.T.); +#55686 = EDGE_CURVE('',#55664,#49732,#55687,.T.); +#55687 = SURFACE_CURVE('',#55688,(#55693,#55704),.PCURVE_S1.); +#55688 = CIRCLE('',#55689,0.25); +#55689 = AXIS2_PLACEMENT_3D('',#55690,#55691,#55692); +#55690 = CARTESIAN_POINT('',(-3.2,0.675,-2.35)); +#55691 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55692 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#55693 = PCURVE('',#49747,#55694); +#55694 = DEFINITIONAL_REPRESENTATION('',(#55695),#55703); +#55695 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55696,#55697,#55698,#55699 + ,#55700,#55701,#55702),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#53304 = CARTESIAN_POINT('',(-3.45,0.675)); -#53305 = CARTESIAN_POINT('',(-3.45,1.108012701892)); -#53306 = CARTESIAN_POINT('',(-3.075,0.891506350946)); -#53307 = CARTESIAN_POINT('',(-2.7,0.675)); -#53308 = CARTESIAN_POINT('',(-3.075,0.458493649054)); -#53309 = CARTESIAN_POINT('',(-3.45,0.241987298108)); -#53310 = CARTESIAN_POINT('',(-3.45,0.675)); -#53311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53312 = PCURVE('',#38471,#53313); -#53313 = DEFINITIONAL_REPRESENTATION('',(#53314),#53317); -#53314 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53315,#53316),.UNSPECIFIED., +#55696 = CARTESIAN_POINT('',(-3.45,0.675)); +#55697 = CARTESIAN_POINT('',(-3.45,1.108012701892)); +#55698 = CARTESIAN_POINT('',(-3.075,0.891506350946)); +#55699 = CARTESIAN_POINT('',(-2.7,0.675)); +#55700 = CARTESIAN_POINT('',(-3.075,0.458493649054)); +#55701 = CARTESIAN_POINT('',(-3.45,0.241987298108)); +#55702 = CARTESIAN_POINT('',(-3.45,0.675)); +#55703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55704 = PCURVE('',#40863,#55705); +#55705 = DEFINITIONAL_REPRESENTATION('',(#55706),#55709); +#55706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55707,#55708),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#53315 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#53316 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53318 = ORIENTED_EDGE('',*,*,#47339,.F.); -#53319 = ORIENTED_EDGE('',*,*,#53320,.F.); -#53320 = EDGE_CURVE('',#53321,#47313,#53323,.T.); -#53321 = VERTEX_POINT('',#53322); -#53322 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-2.35)); -#53323 = SURFACE_CURVE('',#53324,(#53329,#53336),.PCURVE_S1.); -#53324 = CIRCLE('',#53325,0.1); -#53325 = AXIS2_PLACEMENT_3D('',#53326,#53327,#53328); -#53326 = CARTESIAN_POINT('',(-2.32,0.825,-2.35)); -#53327 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53328 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#53329 = PCURVE('',#47355,#53330); -#53330 = DEFINITIONAL_REPRESENTATION('',(#53331),#53335); -#53331 = CIRCLE('',#53332,0.1); -#53332 = AXIS2_PLACEMENT_2D('',#53333,#53334); -#53333 = CARTESIAN_POINT('',(-2.32,0.825)); -#53334 = DIRECTION('',(0.573576436351,0.819152044289)); -#53335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53336 = PCURVE('',#47328,#53337); -#53337 = DEFINITIONAL_REPRESENTATION('',(#53338),#53341); -#53338 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53339,#53340),.UNSPECIFIED., +#55707 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#55708 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55710 = ORIENTED_EDGE('',*,*,#49731,.F.); +#55711 = ORIENTED_EDGE('',*,*,#55712,.F.); +#55712 = EDGE_CURVE('',#55713,#49705,#55715,.T.); +#55713 = VERTEX_POINT('',#55714); +#55714 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-2.35)); +#55715 = SURFACE_CURVE('',#55716,(#55721,#55728),.PCURVE_S1.); +#55716 = CIRCLE('',#55717,0.1); +#55717 = AXIS2_PLACEMENT_3D('',#55718,#55719,#55720); +#55718 = CARTESIAN_POINT('',(-2.32,0.825,-2.35)); +#55719 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55720 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#55721 = PCURVE('',#49747,#55722); +#55722 = DEFINITIONAL_REPRESENTATION('',(#55723),#55727); +#55723 = CIRCLE('',#55724,0.1); +#55724 = AXIS2_PLACEMENT_2D('',#55725,#55726); +#55725 = CARTESIAN_POINT('',(-2.32,0.825)); +#55726 = DIRECTION('',(0.573576436351,0.819152044289)); +#55727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55728 = PCURVE('',#49720,#55729); +#55729 = DEFINITIONAL_REPRESENTATION('',(#55730),#55733); +#55730 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55731,#55732),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238198),.PIECEWISE_BEZIER_KNOTS.); -#53339 = CARTESIAN_POINT('',(2.181661564993,0.E+000)); -#53340 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53342 = ORIENTED_EDGE('',*,*,#53343,.F.); -#53343 = EDGE_CURVE('',#52984,#53321,#53344,.T.); -#53344 = SURFACE_CURVE('',#53345,(#53349,#53356),.PCURVE_S1.); -#53345 = LINE('',#53346,#53347); -#53346 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.35)); -#53347 = VECTOR('',#53348,1.); -#53348 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); -#53349 = PCURVE('',#47355,#53350); -#53350 = DEFINITIONAL_REPRESENTATION('',(#53351),#53355); -#53351 = LINE('',#53352,#53353); -#53352 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619)); -#53353 = VECTOR('',#53354,1.); -#53354 = DIRECTION('',(-0.819152044289,0.573576436351)); -#53355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53356 = PCURVE('',#52619,#53357); -#53357 = DEFINITIONAL_REPRESENTATION('',(#53358),#53362); -#53358 = LINE('',#53359,#53360); -#53359 = CARTESIAN_POINT('',(0.3,0.E+000)); -#53360 = VECTOR('',#53361,1.); -#53361 = DIRECTION('',(1.,0.E+000)); -#53362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53363 = ADVANCED_FACE('',(#53364),#39747,.F.); -#53364 = FACE_BOUND('',#53365,.F.); -#53365 = EDGE_LOOP('',(#53366,#53411,#53412,#53413,#53414,#53439,#53440, - #53441,#53442,#53464,#53492,#53520,#53543,#53564,#53565,#53592)); -#53366 = ORIENTED_EDGE('',*,*,#53367,.F.); -#53367 = EDGE_CURVE('',#52857,#53368,#53370,.T.); -#53368 = VERTEX_POINT('',#53369); -#53369 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.35)); -#53370 = SURFACE_CURVE('',#53371,(#53375,#53382),.PCURVE_S1.); -#53371 = LINE('',#53372,#53373); -#53372 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.35)); -#53373 = VECTOR('',#53374,1.); -#53374 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#53375 = PCURVE('',#39747,#53376); -#53376 = DEFINITIONAL_REPRESENTATION('',(#53377),#53381); -#53377 = LINE('',#53378,#53379); -#53378 = CARTESIAN_POINT('',(1.983313905674,0.711327317619)); -#53379 = VECTOR('',#53380,1.); -#53380 = DIRECTION('',(-0.573576436351,0.819152044289)); -#53381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53382 = PCURVE('',#52896,#53383); -#53383 = DEFINITIONAL_REPRESENTATION('',(#53384),#53410); -#53384 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53385,#53386,#53387,#53388, - #53389,#53390,#53391,#53392,#53393,#53394,#53395,#53396,#53397, - #53398,#53399,#53400,#53401,#53402,#53403,#53404,#53405,#53406, - #53407,#53408,#53409),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55731 = CARTESIAN_POINT('',(2.181661564993,0.E+000)); +#55732 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55734 = ORIENTED_EDGE('',*,*,#55735,.F.); +#55735 = EDGE_CURVE('',#55376,#55713,#55736,.T.); +#55736 = SURFACE_CURVE('',#55737,(#55741,#55748),.PCURVE_S1.); +#55737 = LINE('',#55738,#55739); +#55738 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.35)); +#55739 = VECTOR('',#55740,1.); +#55740 = DIRECTION('',(-0.819152044289,0.573576436351,0.E+000)); +#55741 = PCURVE('',#49747,#55742); +#55742 = DEFINITIONAL_REPRESENTATION('',(#55743),#55747); +#55743 = LINE('',#55744,#55745); +#55744 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619)); +#55745 = VECTOR('',#55746,1.); +#55746 = DIRECTION('',(-0.819152044289,0.573576436351)); +#55747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55748 = PCURVE('',#55011,#55749); +#55749 = DEFINITIONAL_REPRESENTATION('',(#55750),#55754); +#55750 = LINE('',#55751,#55752); +#55751 = CARTESIAN_POINT('',(0.3,0.E+000)); +#55752 = VECTOR('',#55753,1.); +#55753 = DIRECTION('',(1.,0.E+000)); +#55754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55755 = ADVANCED_FACE('',(#55756),#42139,.F.); +#55756 = FACE_BOUND('',#55757,.F.); +#55757 = EDGE_LOOP('',(#55758,#55803,#55804,#55805,#55806,#55831,#55832, + #55833,#55834,#55856,#55884,#55912,#55935,#55956,#55957,#55984)); +#55758 = ORIENTED_EDGE('',*,*,#55759,.F.); +#55759 = EDGE_CURVE('',#55249,#55760,#55762,.T.); +#55760 = VERTEX_POINT('',#55761); +#55761 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.35)); +#55762 = SURFACE_CURVE('',#55763,(#55767,#55774),.PCURVE_S1.); +#55763 = LINE('',#55764,#55765); +#55764 = CARTESIAN_POINT('',(1.983313905674,0.711327317619,-2.35)); +#55765 = VECTOR('',#55766,1.); +#55766 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#55767 = PCURVE('',#42139,#55768); +#55768 = DEFINITIONAL_REPRESENTATION('',(#55769),#55773); +#55769 = LINE('',#55770,#55771); +#55770 = CARTESIAN_POINT('',(1.983313905674,0.711327317619)); +#55771 = VECTOR('',#55772,1.); +#55772 = DIRECTION('',(-0.573576436351,0.819152044289)); +#55773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55774 = PCURVE('',#55288,#55775); +#55775 = DEFINITIONAL_REPRESENTATION('',(#55776),#55802); +#55776 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55777,#55778,#55779,#55780, + #55781,#55782,#55783,#55784,#55785,#55786,#55787,#55788,#55789, + #55790,#55791,#55792,#55793,#55794,#55795,#55796,#55797,#55798, + #55799,#55800,#55801),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363636E-002, 2.727272727271E-002,4.090909090907E-002,5.454545454542E-002, 6.818181818178E-002,8.181818181813E-002,9.545454545449E-002, @@ -66306,304 +69295,304 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454545,0.218181818182, 0.231818181818,0.245454545454,0.259090909091,0.272727272727, 0.286363636363,0.3),.QUASI_UNIFORM_KNOTS.); -#53385 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); -#53386 = CARTESIAN_POINT('',(3.56422710276E-013,2.00600860939E-002)); -#53387 = CARTESIAN_POINT('',(6.885021157771E-013,2.91509951848E-002)); -#53388 = CARTESIAN_POINT('',(5.550315029848E-013,4.278735882116E-002)); -#53389 = CARTESIAN_POINT('',(5.907948459021E-013,5.642372245751E-002)); -#53390 = CARTESIAN_POINT('',(5.812120870253E-013,7.006008609387E-002)); -#53391 = CARTESIAN_POINT('',(5.837797796151E-013,8.369644973022E-002)); -#53392 = CARTESIAN_POINT('',(5.830917681328E-013,9.733281336658E-002)); -#53393 = CARTESIAN_POINT('',(5.832761214722E-013,0.110969177003)); -#53394 = CARTESIAN_POINT('',(5.832267195969E-013,0.124605540639)); -#53395 = CARTESIAN_POINT('',(5.832399737586E-013,0.138241904276)); -#53396 = CARTESIAN_POINT('',(5.832363589872E-013,0.151878267912)); -#53397 = CARTESIAN_POINT('',(5.83237563911E-013,0.165514631548)); -#53398 = CARTESIAN_POINT('',(5.832363589872E-013,0.179150995185)); -#53399 = CARTESIAN_POINT('',(5.832399737586E-013,0.192787358821)); -#53400 = CARTESIAN_POINT('',(5.832267195969E-013,0.206423722457)); -#53401 = CARTESIAN_POINT('',(5.832761214722E-013,0.220060086094)); -#53402 = CARTESIAN_POINT('',(5.830917681328E-013,0.23369644973)); -#53403 = CARTESIAN_POINT('',(5.837797796151E-013,0.247332813366)); -#53404 = CARTESIAN_POINT('',(5.812120870253E-013,0.260969177003)); -#53405 = CARTESIAN_POINT('',(5.907948459021E-013,0.274605540639)); -#53406 = CARTESIAN_POINT('',(5.550315029848E-013,0.288241904276)); -#53407 = CARTESIAN_POINT('',(6.885021157771E-013,0.301878267912)); -#53408 = CARTESIAN_POINT('',(3.56422710276E-013,0.310969177003)); -#53409 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#53410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53411 = ORIENTED_EDGE('',*,*,#52856,.F.); -#53412 = ORIENTED_EDGE('',*,*,#52954,.F.); -#53413 = ORIENTED_EDGE('',*,*,#47480,.F.); -#53414 = ORIENTED_EDGE('',*,*,#53415,.T.); -#53415 = EDGE_CURVE('',#47459,#39732,#53416,.T.); -#53416 = SURFACE_CURVE('',#53417,(#53422,#53433),.PCURVE_S1.); -#53417 = CIRCLE('',#53418,0.25); -#53418 = AXIS2_PLACEMENT_3D('',#53419,#53420,#53421); -#53419 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); -#53420 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53421 = DIRECTION('',(0.E+000,1.,0.E+000)); -#53422 = PCURVE('',#39747,#53423); -#53423 = DEFINITIONAL_REPRESENTATION('',(#53424),#53432); -#53424 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53425,#53426,#53427,#53428 - ,#53429,#53430,#53431),.UNSPECIFIED.,.F.,.F.) +#55777 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); +#55778 = CARTESIAN_POINT('',(3.56422710276E-013,2.00600860939E-002)); +#55779 = CARTESIAN_POINT('',(6.885021157771E-013,2.91509951848E-002)); +#55780 = CARTESIAN_POINT('',(5.550315029848E-013,4.278735882116E-002)); +#55781 = CARTESIAN_POINT('',(5.907948459021E-013,5.642372245751E-002)); +#55782 = CARTESIAN_POINT('',(5.812120870253E-013,7.006008609387E-002)); +#55783 = CARTESIAN_POINT('',(5.837797796151E-013,8.369644973022E-002)); +#55784 = CARTESIAN_POINT('',(5.830917681328E-013,9.733281336658E-002)); +#55785 = CARTESIAN_POINT('',(5.832761214722E-013,0.110969177003)); +#55786 = CARTESIAN_POINT('',(5.832267195969E-013,0.124605540639)); +#55787 = CARTESIAN_POINT('',(5.832399737586E-013,0.138241904276)); +#55788 = CARTESIAN_POINT('',(5.832363589872E-013,0.151878267912)); +#55789 = CARTESIAN_POINT('',(5.83237563911E-013,0.165514631548)); +#55790 = CARTESIAN_POINT('',(5.832363589872E-013,0.179150995185)); +#55791 = CARTESIAN_POINT('',(5.832399737586E-013,0.192787358821)); +#55792 = CARTESIAN_POINT('',(5.832267195969E-013,0.206423722457)); +#55793 = CARTESIAN_POINT('',(5.832761214722E-013,0.220060086094)); +#55794 = CARTESIAN_POINT('',(5.830917681328E-013,0.23369644973)); +#55795 = CARTESIAN_POINT('',(5.837797796151E-013,0.247332813366)); +#55796 = CARTESIAN_POINT('',(5.812120870253E-013,0.260969177003)); +#55797 = CARTESIAN_POINT('',(5.907948459021E-013,0.274605540639)); +#55798 = CARTESIAN_POINT('',(5.550315029848E-013,0.288241904276)); +#55799 = CARTESIAN_POINT('',(6.885021157771E-013,0.301878267912)); +#55800 = CARTESIAN_POINT('',(3.56422710276E-013,0.310969177003)); +#55801 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#55802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55803 = ORIENTED_EDGE('',*,*,#55248,.F.); +#55804 = ORIENTED_EDGE('',*,*,#55346,.F.); +#55805 = ORIENTED_EDGE('',*,*,#49872,.F.); +#55806 = ORIENTED_EDGE('',*,*,#55807,.T.); +#55807 = EDGE_CURVE('',#49851,#42124,#55808,.T.); +#55808 = SURFACE_CURVE('',#55809,(#55814,#55825),.PCURVE_S1.); +#55809 = CIRCLE('',#55810,0.25); +#55810 = AXIS2_PLACEMENT_3D('',#55811,#55812,#55813); +#55811 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); +#55812 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55813 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55814 = PCURVE('',#42139,#55815); +#55815 = DEFINITIONAL_REPRESENTATION('',(#55816),#55824); +#55816 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55817,#55818,#55819,#55820 + ,#55821,#55822,#55823),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#53425 = CARTESIAN_POINT('',(3.2,0.925)); -#53426 = CARTESIAN_POINT('',(3.633012701892,0.925)); -#53427 = CARTESIAN_POINT('',(3.416506350946,0.55)); -#53428 = CARTESIAN_POINT('',(3.2,0.175)); -#53429 = CARTESIAN_POINT('',(2.983493649054,0.55)); -#53430 = CARTESIAN_POINT('',(2.766987298108,0.925)); -#53431 = CARTESIAN_POINT('',(3.2,0.925)); -#53432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53433 = PCURVE('',#38585,#53434); -#53434 = DEFINITIONAL_REPRESENTATION('',(#53435),#53438); -#53435 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53436,#53437),.UNSPECIFIED., +#55817 = CARTESIAN_POINT('',(3.2,0.925)); +#55818 = CARTESIAN_POINT('',(3.633012701892,0.925)); +#55819 = CARTESIAN_POINT('',(3.416506350946,0.55)); +#55820 = CARTESIAN_POINT('',(3.2,0.175)); +#55821 = CARTESIAN_POINT('',(2.983493649054,0.55)); +#55822 = CARTESIAN_POINT('',(2.766987298108,0.925)); +#55823 = CARTESIAN_POINT('',(3.2,0.925)); +#55824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55825 = PCURVE('',#40977,#55826); +#55826 = DEFINITIONAL_REPRESENTATION('',(#55827),#55830); +#55827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55828,#55829),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#53436 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53437 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53439 = ORIENTED_EDGE('',*,*,#39731,.T.); -#53440 = ORIENTED_EDGE('',*,*,#40412,.T.); -#53441 = ORIENTED_EDGE('',*,*,#40719,.T.); -#53442 = ORIENTED_EDGE('',*,*,#53443,.T.); -#53443 = EDGE_CURVE('',#40660,#53444,#53446,.T.); -#53444 = VERTEX_POINT('',#53445); -#53445 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); -#53446 = SURFACE_CURVE('',#53447,(#53451,#53458),.PCURVE_S1.); -#53447 = LINE('',#53448,#53449); -#53448 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); -#53449 = VECTOR('',#53450,1.); -#53450 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53451 = PCURVE('',#39747,#53452); -#53452 = DEFINITIONAL_REPRESENTATION('',(#53453),#53457); -#53453 = LINE('',#53454,#53455); -#53454 = CARTESIAN_POINT('',(3.05,-0.575)); -#53455 = VECTOR('',#53456,1.); -#53456 = DIRECTION('',(1.,0.E+000)); -#53457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53458 = PCURVE('',#40685,#53459); -#53459 = DEFINITIONAL_REPRESENTATION('',(#53460),#53463); -#53460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53461,#53462),.UNSPECIFIED., +#55828 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55829 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55831 = ORIENTED_EDGE('',*,*,#42123,.T.); +#55832 = ORIENTED_EDGE('',*,*,#42804,.T.); +#55833 = ORIENTED_EDGE('',*,*,#43111,.T.); +#55834 = ORIENTED_EDGE('',*,*,#55835,.T.); +#55835 = EDGE_CURVE('',#43052,#55836,#55838,.T.); +#55836 = VERTEX_POINT('',#55837); +#55837 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); +#55838 = SURFACE_CURVE('',#55839,(#55843,#55850),.PCURVE_S1.); +#55839 = LINE('',#55840,#55841); +#55840 = CARTESIAN_POINT('',(3.05,-0.575,-2.35)); +#55841 = VECTOR('',#55842,1.); +#55842 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55843 = PCURVE('',#42139,#55844); +#55844 = DEFINITIONAL_REPRESENTATION('',(#55845),#55849); +#55845 = LINE('',#55846,#55847); +#55846 = CARTESIAN_POINT('',(3.05,-0.575)); +#55847 = VECTOR('',#55848,1.); +#55848 = DIRECTION('',(1.,0.E+000)); +#55849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55850 = PCURVE('',#43077,#55851); +#55851 = DEFINITIONAL_REPRESENTATION('',(#55852),#55855); +#55852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55853,#55854),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#53461 = CARTESIAN_POINT('',(6.28318530718,6.8)); -#53462 = CARTESIAN_POINT('',(6.28318530718,7.224264068712)); -#53463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53464 = ORIENTED_EDGE('',*,*,#53465,.T.); -#53465 = EDGE_CURVE('',#53444,#53466,#53468,.T.); -#53466 = VERTEX_POINT('',#53467); -#53467 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-2.35)); -#53468 = SURFACE_CURVE('',#53469,(#53473,#53480),.PCURVE_S1.); -#53469 = LINE('',#53470,#53471); -#53470 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); -#53471 = VECTOR('',#53472,1.); -#53472 = DIRECTION('',(0.707106781187,0.707106781186,0.E+000)); -#53473 = PCURVE('',#39747,#53474); -#53474 = DEFINITIONAL_REPRESENTATION('',(#53475),#53479); -#53475 = LINE('',#53476,#53477); -#53476 = CARTESIAN_POINT('',(3.474264068712,-0.575)); -#53477 = VECTOR('',#53478,1.); -#53478 = DIRECTION('',(0.707106781187,0.707106781186)); -#53479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53480 = PCURVE('',#53481,#53486); -#53481 = PLANE('',#53482); -#53482 = AXIS2_PLACEMENT_3D('',#53483,#53484,#53485); -#53483 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-2.35)); -#53484 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#53485 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#53486 = DEFINITIONAL_REPRESENTATION('',(#53487),#53491); -#53487 = LINE('',#53488,#53489); -#53488 = CARTESIAN_POINT('',(0.691421356238,0.E+000)); -#53489 = VECTOR('',#53490,1.); -#53490 = DIRECTION('',(1.,0.E+000)); -#53491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53492 = ORIENTED_EDGE('',*,*,#53493,.T.); -#53493 = EDGE_CURVE('',#53466,#53494,#53496,.T.); -#53494 = VERTEX_POINT('',#53495); -#53495 = CARTESIAN_POINT('',(3.75,-7.144660940672E-002,-2.35)); -#53496 = SURFACE_CURVE('',#53497,(#53502,#53509),.PCURVE_S1.); -#53497 = CIRCLE('',#53498,0.55); -#53498 = AXIS2_PLACEMENT_3D('',#53499,#53500,#53501); -#53499 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#53500 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53501 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#53502 = PCURVE('',#39747,#53503); -#53503 = DEFINITIONAL_REPRESENTATION('',(#53504),#53508); -#53504 = CIRCLE('',#53505,0.55); -#53505 = AXIS2_PLACEMENT_2D('',#53506,#53507); -#53506 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002)); -#53507 = DIRECTION('',(0.707106781187,-0.707106781187)); -#53508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53509 = PCURVE('',#53510,#53515); -#53510 = CYLINDRICAL_SURFACE('',#53511,0.55); -#53511 = AXIS2_PLACEMENT_3D('',#53512,#53513,#53514); -#53512 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); -#53513 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53514 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53515 = DEFINITIONAL_REPRESENTATION('',(#53516),#53519); -#53516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53517,#53518),.UNSPECIFIED., +#55853 = CARTESIAN_POINT('',(6.28318530718,6.8)); +#55854 = CARTESIAN_POINT('',(6.28318530718,7.224264068712)); +#55855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55856 = ORIENTED_EDGE('',*,*,#55857,.T.); +#55857 = EDGE_CURVE('',#55836,#55858,#55860,.T.); +#55858 = VERTEX_POINT('',#55859); +#55859 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-2.35)); +#55860 = SURFACE_CURVE('',#55861,(#55865,#55872),.PCURVE_S1.); +#55861 = LINE('',#55862,#55863); +#55862 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); +#55863 = VECTOR('',#55864,1.); +#55864 = DIRECTION('',(0.707106781187,0.707106781186,0.E+000)); +#55865 = PCURVE('',#42139,#55866); +#55866 = DEFINITIONAL_REPRESENTATION('',(#55867),#55871); +#55867 = LINE('',#55868,#55869); +#55868 = CARTESIAN_POINT('',(3.474264068712,-0.575)); +#55869 = VECTOR('',#55870,1.); +#55870 = DIRECTION('',(0.707106781187,0.707106781186)); +#55871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55872 = PCURVE('',#55873,#55878); +#55873 = PLANE('',#55874); +#55874 = AXIS2_PLACEMENT_3D('',#55875,#55876,#55877); +#55875 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-2.35)); +#55876 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#55877 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#55878 = DEFINITIONAL_REPRESENTATION('',(#55879),#55883); +#55879 = LINE('',#55880,#55881); +#55880 = CARTESIAN_POINT('',(0.691421356238,0.E+000)); +#55881 = VECTOR('',#55882,1.); +#55882 = DIRECTION('',(1.,0.E+000)); +#55883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55884 = ORIENTED_EDGE('',*,*,#55885,.T.); +#55885 = EDGE_CURVE('',#55858,#55886,#55888,.T.); +#55886 = VERTEX_POINT('',#55887); +#55887 = CARTESIAN_POINT('',(3.75,-7.144660940672E-002,-2.35)); +#55888 = SURFACE_CURVE('',#55889,(#55894,#55901),.PCURVE_S1.); +#55889 = CIRCLE('',#55890,0.55); +#55890 = AXIS2_PLACEMENT_3D('',#55891,#55892,#55893); +#55891 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#55892 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55893 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#55894 = PCURVE('',#42139,#55895); +#55895 = DEFINITIONAL_REPRESENTATION('',(#55896),#55900); +#55896 = CIRCLE('',#55897,0.55); +#55897 = AXIS2_PLACEMENT_2D('',#55898,#55899); +#55898 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002)); +#55899 = DIRECTION('',(0.707106781187,-0.707106781187)); +#55900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55901 = PCURVE('',#55902,#55907); +#55902 = CYLINDRICAL_SURFACE('',#55903,0.55); +#55903 = AXIS2_PLACEMENT_3D('',#55904,#55905,#55906); +#55904 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-2.35)); +#55905 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55906 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55907 = DEFINITIONAL_REPRESENTATION('',(#55908),#55911); +#55908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55909,#55910),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#53517 = CARTESIAN_POINT('',(5.497787143782,0.E+000)); -#53518 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#53519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53520 = ORIENTED_EDGE('',*,*,#53521,.T.); -#53521 = EDGE_CURVE('',#53494,#53522,#53524,.T.); -#53522 = VERTEX_POINT('',#53523); -#53523 = CARTESIAN_POINT('',(3.75,0.675,-2.35)); -#53524 = SURFACE_CURVE('',#53525,(#53529,#53536),.PCURVE_S1.); -#53525 = LINE('',#53526,#53527); -#53526 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); -#53527 = VECTOR('',#53528,1.); -#53528 = DIRECTION('',(0.E+000,1.,0.E+000)); -#53529 = PCURVE('',#39747,#53530); -#53530 = DEFINITIONAL_REPRESENTATION('',(#53531),#53535); -#53531 = LINE('',#53532,#53533); -#53532 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002)); -#53533 = VECTOR('',#53534,1.); -#53534 = DIRECTION('',(0.E+000,1.)); -#53535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53536 = PCURVE('',#38035,#53537); -#53537 = DEFINITIONAL_REPRESENTATION('',(#53538),#53542); -#53538 = LINE('',#53539,#53540); -#53539 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53540 = VECTOR('',#53541,1.); -#53541 = DIRECTION('',(1.,0.E+000)); -#53542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53543 = ORIENTED_EDGE('',*,*,#53544,.T.); -#53544 = EDGE_CURVE('',#53522,#49174,#53545,.T.); -#53545 = SURFACE_CURVE('',#53546,(#53551,#53558),.PCURVE_S1.); -#53546 = CIRCLE('',#53547,0.55); -#53547 = AXIS2_PLACEMENT_3D('',#53548,#53549,#53550); -#53548 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); -#53549 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#53551 = PCURVE('',#39747,#53552); -#53552 = DEFINITIONAL_REPRESENTATION('',(#53553),#53557); -#53553 = CIRCLE('',#53554,0.55); -#53554 = AXIS2_PLACEMENT_2D('',#53555,#53556); -#53555 = CARTESIAN_POINT('',(3.2,0.675)); -#53556 = DIRECTION('',(1.,0.E+000)); -#53557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53558 = PCURVE('',#38641,#53559); -#53559 = DEFINITIONAL_REPRESENTATION('',(#53560),#53563); -#53560 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53561,#53562),.UNSPECIFIED., +#55909 = CARTESIAN_POINT('',(5.497787143782,0.E+000)); +#55910 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#55911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55912 = ORIENTED_EDGE('',*,*,#55913,.T.); +#55913 = EDGE_CURVE('',#55886,#55914,#55916,.T.); +#55914 = VERTEX_POINT('',#55915); +#55915 = CARTESIAN_POINT('',(3.75,0.675,-2.35)); +#55916 = SURFACE_CURVE('',#55917,(#55921,#55928),.PCURVE_S1.); +#55917 = LINE('',#55918,#55919); +#55918 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); +#55919 = VECTOR('',#55920,1.); +#55920 = DIRECTION('',(0.E+000,1.,0.E+000)); +#55921 = PCURVE('',#42139,#55922); +#55922 = DEFINITIONAL_REPRESENTATION('',(#55923),#55927); +#55923 = LINE('',#55924,#55925); +#55924 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002)); +#55925 = VECTOR('',#55926,1.); +#55926 = DIRECTION('',(0.E+000,1.)); +#55927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55928 = PCURVE('',#40427,#55929); +#55929 = DEFINITIONAL_REPRESENTATION('',(#55930),#55934); +#55930 = LINE('',#55931,#55932); +#55931 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55932 = VECTOR('',#55933,1.); +#55933 = DIRECTION('',(1.,0.E+000)); +#55934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55935 = ORIENTED_EDGE('',*,*,#55936,.T.); +#55936 = EDGE_CURVE('',#55914,#51566,#55937,.T.); +#55937 = SURFACE_CURVE('',#55938,(#55943,#55950),.PCURVE_S1.); +#55938 = CIRCLE('',#55939,0.55); +#55939 = AXIS2_PLACEMENT_3D('',#55940,#55941,#55942); +#55940 = CARTESIAN_POINT('',(3.2,0.675,-2.35)); +#55941 = DIRECTION('',(0.E+000,0.E+000,1.)); +#55942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#55943 = PCURVE('',#42139,#55944); +#55944 = DEFINITIONAL_REPRESENTATION('',(#55945),#55949); +#55945 = CIRCLE('',#55946,0.55); +#55946 = AXIS2_PLACEMENT_2D('',#55947,#55948); +#55947 = CARTESIAN_POINT('',(3.2,0.675)); +#55948 = DIRECTION('',(1.,0.E+000)); +#55949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55950 = PCURVE('',#41033,#55951); +#55951 = DEFINITIONAL_REPRESENTATION('',(#55952),#55955); +#55952 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55953,#55954),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#53561 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53562 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53564 = ORIENTED_EDGE('',*,*,#49173,.F.); -#53565 = ORIENTED_EDGE('',*,*,#53566,.F.); -#53566 = EDGE_CURVE('',#53567,#49147,#53569,.T.); -#53567 = VERTEX_POINT('',#53568); -#53568 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-2.35)); -#53569 = SURFACE_CURVE('',#53570,(#53575,#53586),.PCURVE_S1.); -#53570 = CIRCLE('',#53571,0.2); -#53571 = AXIS2_PLACEMENT_3D('',#53572,#53573,#53574); -#53572 = CARTESIAN_POINT('',(2.256940242224,1.025,-2.35)); -#53573 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53574 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#53575 = PCURVE('',#39747,#53576); -#53576 = DEFINITIONAL_REPRESENTATION('',(#53577),#53585); -#53577 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#53578,#53579,#53580,#53581 - ,#53582,#53583,#53584),.UNSPECIFIED.,.T.,.F.) +#55953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#55954 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55956 = ORIENTED_EDGE('',*,*,#51565,.F.); +#55957 = ORIENTED_EDGE('',*,*,#55958,.F.); +#55958 = EDGE_CURVE('',#55959,#51539,#55961,.T.); +#55959 = VERTEX_POINT('',#55960); +#55960 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-2.35)); +#55961 = SURFACE_CURVE('',#55962,(#55967,#55978),.PCURVE_S1.); +#55962 = CIRCLE('',#55963,0.2); +#55963 = AXIS2_PLACEMENT_3D('',#55964,#55965,#55966); +#55964 = CARTESIAN_POINT('',(2.256940242224,1.025,-2.35)); +#55965 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#55966 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#55967 = PCURVE('',#42139,#55968); +#55968 = DEFINITIONAL_REPRESENTATION('',(#55969),#55977); +#55969 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55970,#55971,#55972,#55973 + ,#55974,#55975,#55976),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#53578 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); -#53579 = CARTESIAN_POINT('',(2.42598754692,1.387523114815)); -#53580 = CARTESIAN_POINT('',(2.456179181842,1.04243114855)); -#53581 = CARTESIAN_POINT('',(2.486370816764,0.697339182284)); -#53582 = CARTESIAN_POINT('',(2.172416589876,0.843738442593)); -#53583 = CARTESIAN_POINT('',(1.858462362987,0.990137702901)); -#53584 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); -#53585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53586 = PCURVE('',#49162,#53587); -#53587 = DEFINITIONAL_REPRESENTATION('',(#53588),#53591); -#53588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53589,#53590),.UNSPECIFIED., +#55970 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); +#55971 = CARTESIAN_POINT('',(2.42598754692,1.387523114815)); +#55972 = CARTESIAN_POINT('',(2.456179181842,1.04243114855)); +#55973 = CARTESIAN_POINT('',(2.486370816764,0.697339182284)); +#55974 = CARTESIAN_POINT('',(2.172416589876,0.843738442593)); +#55975 = CARTESIAN_POINT('',(1.858462362987,0.990137702901)); +#55976 = CARTESIAN_POINT('',(2.142224954954,1.188830408858)); +#55977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55978 = PCURVE('',#51554,#55979); +#55979 = DEFINITIONAL_REPRESENTATION('',(#55980),#55983); +#55980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55981,#55982),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.610865238198),.PIECEWISE_BEZIER_KNOTS.); -#53589 = CARTESIAN_POINT('',(0.959931088597,0.E+000)); -#53590 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#53591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53592 = ORIENTED_EDGE('',*,*,#53593,.F.); -#53593 = EDGE_CURVE('',#53368,#53567,#53594,.T.); -#53594 = SURFACE_CURVE('',#53595,(#53599,#53606),.PCURVE_S1.); -#53595 = LINE('',#53596,#53597); -#53596 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.35)); -#53597 = VECTOR('',#53598,1.); -#53598 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); -#53599 = PCURVE('',#39747,#53600); -#53600 = DEFINITIONAL_REPRESENTATION('',(#53601),#53605); -#53601 = LINE('',#53602,#53603); -#53602 = CARTESIAN_POINT('',(1.811240974769,0.957072930905)); -#53603 = VECTOR('',#53604,1.); -#53604 = DIRECTION('',(0.819152044289,0.573576436351)); -#53605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53606 = PCURVE('',#52439,#53607); -#53607 = DEFINITIONAL_REPRESENTATION('',(#53608),#53612); -#53608 = LINE('',#53609,#53610); -#53609 = CARTESIAN_POINT('',(0.3,0.E+000)); -#53610 = VECTOR('',#53611,1.); -#53611 = DIRECTION('',(1.,0.E+000)); -#53612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53613 = ADVANCED_FACE('',(#53614),#52999,.T.); -#53614 = FACE_BOUND('',#53615,.T.); -#53615 = EDGE_LOOP('',(#53616,#53662,#53663,#53709)); -#53616 = ORIENTED_EDGE('',*,*,#53617,.F.); -#53617 = EDGE_CURVE('',#52984,#53618,#53620,.T.); -#53618 = VERTEX_POINT('',#53619); -#53619 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.05)); -#53620 = SURFACE_CURVE('',#53621,(#53626,#53655),.PCURVE_S1.); -#53621 = CIRCLE('',#53622,0.3); -#53622 = AXIS2_PLACEMENT_3D('',#53623,#53624,#53625); -#53623 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.05)); -#53624 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#53625 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#53626 = PCURVE('',#52999,#53627); -#53627 = DEFINITIONAL_REPRESENTATION('',(#53628),#53654); -#53628 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53629,#53630,#53631,#53632, - #53633,#53634,#53635,#53636,#53637,#53638,#53639,#53640,#53641, - #53642,#53643,#53644,#53645,#53646,#53647,#53648,#53649,#53650, - #53651,#53652,#53653),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#55981 = CARTESIAN_POINT('',(0.959931088597,0.E+000)); +#55982 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#55983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55984 = ORIENTED_EDGE('',*,*,#55985,.F.); +#55985 = EDGE_CURVE('',#55760,#55959,#55986,.T.); +#55986 = SURFACE_CURVE('',#55987,(#55991,#55998),.PCURVE_S1.); +#55987 = LINE('',#55988,#55989); +#55988 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.35)); +#55989 = VECTOR('',#55990,1.); +#55990 = DIRECTION('',(0.819152044289,0.573576436351,0.E+000)); +#55991 = PCURVE('',#42139,#55992); +#55992 = DEFINITIONAL_REPRESENTATION('',(#55993),#55997); +#55993 = LINE('',#55994,#55995); +#55994 = CARTESIAN_POINT('',(1.811240974769,0.957072930905)); +#55995 = VECTOR('',#55996,1.); +#55996 = DIRECTION('',(0.819152044289,0.573576436351)); +#55997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#55998 = PCURVE('',#54831,#55999); +#55999 = DEFINITIONAL_REPRESENTATION('',(#56000),#56004); +#56000 = LINE('',#56001,#56002); +#56001 = CARTESIAN_POINT('',(0.3,0.E+000)); +#56002 = VECTOR('',#56003,1.); +#56003 = DIRECTION('',(1.,0.E+000)); +#56004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56005 = ADVANCED_FACE('',(#56006),#55391,.T.); +#56006 = FACE_BOUND('',#56007,.T.); +#56007 = EDGE_LOOP('',(#56008,#56054,#56055,#56101)); +#56008 = ORIENTED_EDGE('',*,*,#56009,.F.); +#56009 = EDGE_CURVE('',#55376,#56010,#56012,.T.); +#56010 = VERTEX_POINT('',#56011); +#56011 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.05)); +#56012 = SURFACE_CURVE('',#56013,(#56018,#56047),.PCURVE_S1.); +#56013 = CIRCLE('',#56014,0.3); +#56014 = AXIS2_PLACEMENT_3D('',#56015,#56016,#56017); +#56015 = CARTESIAN_POINT('',(-1.983313905674,0.711327317619,-2.05)); +#56016 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#56017 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#56018 = PCURVE('',#55391,#56019); +#56019 = DEFINITIONAL_REPRESENTATION('',(#56020),#56046); +#56020 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56021,#56022,#56023,#56024, + #56025,#56026,#56027,#56028,#56029,#56030,#56031,#56032,#56033, + #56034,#56035,#56036,#56037,#56038,#56039,#56040,#56041,#56042, + #56043,#56044,#56045),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -66611,60 +69600,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#53629 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#53630 = CARTESIAN_POINT('',(2.379994434552E-002,0.315514631548)); -#53631 = CARTESIAN_POINT('',(7.139983303641E-002,0.315514631548)); -#53632 = CARTESIAN_POINT('',(0.142799666072,0.315514631548)); -#53633 = CARTESIAN_POINT('',(0.214199499109,0.315514631548)); -#53634 = CARTESIAN_POINT('',(0.285599332145,0.315514631548)); -#53635 = CARTESIAN_POINT('',(0.356999165181,0.315514631548)); -#53636 = CARTESIAN_POINT('',(0.428398998217,0.315514631548)); -#53637 = CARTESIAN_POINT('',(0.499798831253,0.315514631548)); -#53638 = CARTESIAN_POINT('',(0.571198664289,0.315514631548)); -#53639 = CARTESIAN_POINT('',(0.642598497325,0.315514631548)); -#53640 = CARTESIAN_POINT('',(0.713998330361,0.315514631548)); -#53641 = CARTESIAN_POINT('',(0.785398163398,0.315514631548)); -#53642 = CARTESIAN_POINT('',(0.856797996434,0.315514631548)); -#53643 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); -#53644 = CARTESIAN_POINT('',(0.999597662506,0.315514631548)); -#53645 = CARTESIAN_POINT('',(1.070997495542,0.315514631548)); -#53646 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); -#53647 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); -#53648 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); -#53649 = CARTESIAN_POINT('',(1.356596827687,0.315514631548)); -#53650 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); -#53651 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); -#53652 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); -#53653 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#53654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53655 = PCURVE('',#52619,#53656); -#53656 = DEFINITIONAL_REPRESENTATION('',(#53657),#53661); -#53657 = CIRCLE('',#53658,0.3); -#53658 = AXIS2_PLACEMENT_2D('',#53659,#53660); -#53659 = CARTESIAN_POINT('',(0.3,-0.3)); -#53660 = DIRECTION('',(0.E+000,1.)); -#53661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53662 = ORIENTED_EDGE('',*,*,#52981,.F.); -#53663 = ORIENTED_EDGE('',*,*,#53664,.F.); -#53664 = EDGE_CURVE('',#53665,#52982,#53667,.T.); -#53665 = VERTEX_POINT('',#53666); -#53666 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); -#53667 = SURFACE_CURVE('',#53668,(#53673,#53702),.PCURVE_S1.); -#53668 = CIRCLE('',#53669,0.3); -#53669 = AXIS2_PLACEMENT_3D('',#53670,#53671,#53672); -#53670 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.05)); -#53671 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#53672 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#53673 = PCURVE('',#52999,#53674); -#53674 = DEFINITIONAL_REPRESENTATION('',(#53675),#53701); -#53675 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53676,#53677,#53678,#53679, - #53680,#53681,#53682,#53683,#53684,#53685,#53686,#53687,#53688, - #53689,#53690,#53691,#53692,#53693,#53694,#53695,#53696,#53697, - #53698,#53699,#53700),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56021 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#56022 = CARTESIAN_POINT('',(2.379994434552E-002,0.315514631548)); +#56023 = CARTESIAN_POINT('',(7.139983303641E-002,0.315514631548)); +#56024 = CARTESIAN_POINT('',(0.142799666072,0.315514631548)); +#56025 = CARTESIAN_POINT('',(0.214199499109,0.315514631548)); +#56026 = CARTESIAN_POINT('',(0.285599332145,0.315514631548)); +#56027 = CARTESIAN_POINT('',(0.356999165181,0.315514631548)); +#56028 = CARTESIAN_POINT('',(0.428398998217,0.315514631548)); +#56029 = CARTESIAN_POINT('',(0.499798831253,0.315514631548)); +#56030 = CARTESIAN_POINT('',(0.571198664289,0.315514631548)); +#56031 = CARTESIAN_POINT('',(0.642598497325,0.315514631548)); +#56032 = CARTESIAN_POINT('',(0.713998330361,0.315514631548)); +#56033 = CARTESIAN_POINT('',(0.785398163398,0.315514631548)); +#56034 = CARTESIAN_POINT('',(0.856797996434,0.315514631548)); +#56035 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); +#56036 = CARTESIAN_POINT('',(0.999597662506,0.315514631548)); +#56037 = CARTESIAN_POINT('',(1.070997495542,0.315514631548)); +#56038 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); +#56039 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); +#56040 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); +#56041 = CARTESIAN_POINT('',(1.356596827687,0.315514631548)); +#56042 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); +#56043 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); +#56044 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); +#56045 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#56046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56047 = PCURVE('',#55011,#56048); +#56048 = DEFINITIONAL_REPRESENTATION('',(#56049),#56053); +#56049 = CIRCLE('',#56050,0.3); +#56050 = AXIS2_PLACEMENT_2D('',#56051,#56052); +#56051 = CARTESIAN_POINT('',(0.3,-0.3)); +#56052 = DIRECTION('',(0.E+000,1.)); +#56053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56054 = ORIENTED_EDGE('',*,*,#55373,.F.); +#56055 = ORIENTED_EDGE('',*,*,#56056,.F.); +#56056 = EDGE_CURVE('',#56057,#55374,#56059,.T.); +#56057 = VERTEX_POINT('',#56058); +#56058 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); +#56059 = SURFACE_CURVE('',#56060,(#56065,#56094),.PCURVE_S1.); +#56060 = CIRCLE('',#56061,0.3); +#56061 = AXIS2_PLACEMENT_3D('',#56062,#56063,#56064); +#56062 = CARTESIAN_POINT('',(-1.811240974769,0.957072930905,-2.05)); +#56063 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#56064 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#56065 = PCURVE('',#55391,#56066); +#56066 = DEFINITIONAL_REPRESENTATION('',(#56067),#56093); +#56067 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56068,#56069,#56070,#56071, + #56072,#56073,#56074,#56075,#56076,#56077,#56078,#56079,#56080, + #56081,#56082,#56083,#56084,#56085,#56086,#56087,#56088,#56089, + #56090,#56091,#56092),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -66672,101 +69661,101 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#53676 = CARTESIAN_POINT('',(1.570796326795,1.551463154845E-002)); -#53677 = CARTESIAN_POINT('',(1.54699638245,1.551463154845E-002)); -#53678 = CARTESIAN_POINT('',(1.499396493759,1.551463154845E-002)); -#53679 = CARTESIAN_POINT('',(1.427996660723,1.551463154845E-002)); -#53680 = CARTESIAN_POINT('',(1.356596827686,1.551463154845E-002)); -#53681 = CARTESIAN_POINT('',(1.28519699465,1.551463154845E-002)); -#53682 = CARTESIAN_POINT('',(1.213797161614,1.551463154845E-002)); -#53683 = CARTESIAN_POINT('',(1.142397328578,1.551463154845E-002)); -#53684 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); -#53685 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); -#53686 = CARTESIAN_POINT('',(0.928197829469,1.551463154845E-002)); -#53687 = CARTESIAN_POINT('',(0.856797996433,1.551463154845E-002)); -#53688 = CARTESIAN_POINT('',(0.785398163397,1.551463154845E-002)); -#53689 = CARTESIAN_POINT('',(0.713998330361,1.551463154845E-002)); -#53690 = CARTESIAN_POINT('',(0.642598497325,1.551463154845E-002)); -#53691 = CARTESIAN_POINT('',(0.571198664289,1.551463154845E-002)); -#53692 = CARTESIAN_POINT('',(0.499798831252,1.551463154845E-002)); -#53693 = CARTESIAN_POINT('',(0.428398998216,1.551463154845E-002)); -#53694 = CARTESIAN_POINT('',(0.35699916518,1.551463154845E-002)); -#53695 = CARTESIAN_POINT('',(0.285599332144,1.551463154845E-002)); -#53696 = CARTESIAN_POINT('',(0.214199499108,1.551463154845E-002)); -#53697 = CARTESIAN_POINT('',(0.142799666072,1.551463154845E-002)); -#53698 = CARTESIAN_POINT('',(7.139983303544E-002,1.551463154845E-002)); -#53699 = CARTESIAN_POINT('',(2.379994434502E-002,1.551463154845E-002)); -#53700 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); -#53701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53702 = PCURVE('',#52696,#53703); -#53703 = DEFINITIONAL_REPRESENTATION('',(#53704),#53708); -#53704 = CIRCLE('',#53705,0.3); -#53705 = AXIS2_PLACEMENT_2D('',#53706,#53707); -#53706 = CARTESIAN_POINT('',(0.404056832297,-0.3)); -#53707 = DIRECTION('',(1.,0.E+000)); -#53708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53709 = ORIENTED_EDGE('',*,*,#53710,.T.); -#53710 = EDGE_CURVE('',#53665,#53618,#53711,.T.); -#53711 = SURFACE_CURVE('',#53712,(#53716,#53722),.PCURVE_S1.); -#53712 = LINE('',#53713,#53714); -#53713 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); -#53714 = VECTOR('',#53715,1.); -#53715 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#53716 = PCURVE('',#52999,#53717); -#53717 = DEFINITIONAL_REPRESENTATION('',(#53718),#53721); -#53718 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53719,#53720),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#53719 = CARTESIAN_POINT('',(1.570796326795,1.551463154827E-002)); -#53720 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#53721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53722 = PCURVE('',#53723,#53728); -#53723 = PLANE('',#53724); -#53724 = AXIS2_PLACEMENT_3D('',#53725,#53726,#53727); -#53725 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.35)); -#53726 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#53727 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#53728 = DEFINITIONAL_REPRESENTATION('',(#53729),#53733); -#53729 = LINE('',#53730,#53731); -#53730 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#53731 = VECTOR('',#53732,1.); -#53732 = DIRECTION('',(1.,0.E+000)); -#53733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56068 = CARTESIAN_POINT('',(1.570796326795,1.551463154845E-002)); +#56069 = CARTESIAN_POINT('',(1.54699638245,1.551463154845E-002)); +#56070 = CARTESIAN_POINT('',(1.499396493759,1.551463154845E-002)); +#56071 = CARTESIAN_POINT('',(1.427996660723,1.551463154845E-002)); +#56072 = CARTESIAN_POINT('',(1.356596827686,1.551463154845E-002)); +#56073 = CARTESIAN_POINT('',(1.28519699465,1.551463154845E-002)); +#56074 = CARTESIAN_POINT('',(1.213797161614,1.551463154845E-002)); +#56075 = CARTESIAN_POINT('',(1.142397328578,1.551463154845E-002)); +#56076 = CARTESIAN_POINT('',(1.070997495542,1.551463154845E-002)); +#56077 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); +#56078 = CARTESIAN_POINT('',(0.928197829469,1.551463154845E-002)); +#56079 = CARTESIAN_POINT('',(0.856797996433,1.551463154845E-002)); +#56080 = CARTESIAN_POINT('',(0.785398163397,1.551463154845E-002)); +#56081 = CARTESIAN_POINT('',(0.713998330361,1.551463154845E-002)); +#56082 = CARTESIAN_POINT('',(0.642598497325,1.551463154845E-002)); +#56083 = CARTESIAN_POINT('',(0.571198664289,1.551463154845E-002)); +#56084 = CARTESIAN_POINT('',(0.499798831252,1.551463154845E-002)); +#56085 = CARTESIAN_POINT('',(0.428398998216,1.551463154845E-002)); +#56086 = CARTESIAN_POINT('',(0.35699916518,1.551463154845E-002)); +#56087 = CARTESIAN_POINT('',(0.285599332144,1.551463154845E-002)); +#56088 = CARTESIAN_POINT('',(0.214199499108,1.551463154845E-002)); +#56089 = CARTESIAN_POINT('',(0.142799666072,1.551463154845E-002)); +#56090 = CARTESIAN_POINT('',(7.139983303544E-002,1.551463154845E-002)); +#56091 = CARTESIAN_POINT('',(2.379994434502E-002,1.551463154845E-002)); +#56092 = CARTESIAN_POINT('',(0.E+000,1.551463154845E-002)); +#56093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#53734 = ADVANCED_FACE('',(#53735),#52619,.T.); -#53735 = FACE_BOUND('',#53736,.F.); -#53736 = EDGE_LOOP('',(#53737,#53783,#53804,#53805,#53806,#53826)); -#53737 = ORIENTED_EDGE('',*,*,#53738,.F.); -#53738 = EDGE_CURVE('',#53739,#52552,#53741,.T.); -#53739 = VERTEX_POINT('',#53740); -#53740 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-1.75)); -#53741 = SURFACE_CURVE('',#53742,(#53747,#53754),.PCURVE_S1.); -#53742 = CIRCLE('',#53743,0.1); -#53743 = AXIS2_PLACEMENT_3D('',#53744,#53745,#53746); -#53744 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.75)); -#53745 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); -#53746 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); -#53747 = PCURVE('',#52619,#53748); -#53748 = DEFINITIONAL_REPRESENTATION('',(#53749),#53753); -#53749 = CIRCLE('',#53750,1.E-001); -#53750 = AXIS2_PLACEMENT_2D('',#53751,#53752); -#53751 = CARTESIAN_POINT('',(0.1,-0.6)); -#53752 = DIRECTION('',(-1.,0.E+000)); -#53753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56094 = PCURVE('',#55088,#56095); +#56095 = DEFINITIONAL_REPRESENTATION('',(#56096),#56100); +#56096 = CIRCLE('',#56097,0.3); +#56097 = AXIS2_PLACEMENT_2D('',#56098,#56099); +#56098 = CARTESIAN_POINT('',(0.404056832297,-0.3)); +#56099 = DIRECTION('',(1.,0.E+000)); +#56100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#53754 = PCURVE('',#52569,#53755); -#53755 = DEFINITIONAL_REPRESENTATION('',(#53756),#53782); -#53756 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53757,#53758,#53759,#53760, - #53761,#53762,#53763,#53764,#53765,#53766,#53767,#53768,#53769, - #53770,#53771,#53772,#53773,#53774,#53775,#53776,#53777,#53778, - #53779,#53780,#53781),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56101 = ORIENTED_EDGE('',*,*,#56102,.T.); +#56102 = EDGE_CURVE('',#56057,#56010,#56103,.T.); +#56103 = SURFACE_CURVE('',#56104,(#56108,#56114),.PCURVE_S1.); +#56104 = LINE('',#56105,#56106); +#56105 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); +#56106 = VECTOR('',#56107,1.); +#56107 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#56108 = PCURVE('',#55391,#56109); +#56109 = DEFINITIONAL_REPRESENTATION('',(#56110),#56113); +#56110 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56111,#56112),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#56111 = CARTESIAN_POINT('',(1.570796326795,1.551463154827E-002)); +#56112 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#56113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56114 = PCURVE('',#56115,#56120); +#56115 = PLANE('',#56116); +#56116 = AXIS2_PLACEMENT_3D('',#56117,#56118,#56119); +#56117 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.35)); +#56118 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#56119 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#56120 = DEFINITIONAL_REPRESENTATION('',(#56121),#56125); +#56121 = LINE('',#56122,#56123); +#56122 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#56123 = VECTOR('',#56124,1.); +#56124 = DIRECTION('',(1.,0.E+000)); +#56125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56126 = ADVANCED_FACE('',(#56127),#55011,.T.); +#56127 = FACE_BOUND('',#56128,.F.); +#56128 = EDGE_LOOP('',(#56129,#56175,#56196,#56197,#56198,#56218)); +#56129 = ORIENTED_EDGE('',*,*,#56130,.F.); +#56130 = EDGE_CURVE('',#56131,#54944,#56133,.T.); +#56131 = VERTEX_POINT('',#56132); +#56132 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-1.75)); +#56133 = SURFACE_CURVE('',#56134,(#56139,#56146),.PCURVE_S1.); +#56134 = CIRCLE('',#56135,0.1); +#56135 = AXIS2_PLACEMENT_3D('',#56136,#56137,#56138); +#56136 = CARTESIAN_POINT('',(-1.819483496816,0.596612030348,-1.75)); +#56137 = DIRECTION('',(-0.573576436351,-0.819152044289,0.E+000)); +#56138 = DIRECTION('',(0.819152044289,-0.573576436351,0.E+000)); +#56139 = PCURVE('',#55011,#56140); +#56140 = DEFINITIONAL_REPRESENTATION('',(#56141),#56145); +#56141 = CIRCLE('',#56142,1.E-001); +#56142 = AXIS2_PLACEMENT_2D('',#56143,#56144); +#56143 = CARTESIAN_POINT('',(0.1,-0.6)); +#56144 = DIRECTION('',(-1.,0.E+000)); +#56145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56146 = PCURVE('',#54961,#56147); +#56147 = DEFINITIONAL_REPRESENTATION('',(#56148),#56174); +#56148 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56149,#56150,#56151,#56152, + #56153,#56154,#56155,#56156,#56157,#56158,#56159,#56160,#56161, + #56162,#56163,#56164,#56165,#56166,#56167,#56168,#56169,#56170, + #56171,#56172,#56173),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -66774,106 +69763,106 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#53757 = CARTESIAN_POINT('',(1.570796326795,2.203939738393E-002)); -#53758 = CARTESIAN_POINT('',(1.54699638245,2.203939738393E-002)); -#53759 = CARTESIAN_POINT('',(1.499396493759,2.203939738393E-002)); -#53760 = CARTESIAN_POINT('',(1.427996660723,2.203939738393E-002)); -#53761 = CARTESIAN_POINT('',(1.356596827687,2.203939738393E-002)); -#53762 = CARTESIAN_POINT('',(1.285196994651,2.203939738393E-002)); -#53763 = CARTESIAN_POINT('',(1.213797161615,2.203939738393E-002)); -#53764 = CARTESIAN_POINT('',(1.142397328579,2.203939738393E-002)); -#53765 = CARTESIAN_POINT('',(1.070997495543,2.203939738393E-002)); -#53766 = CARTESIAN_POINT('',(0.999597662507,2.203939738393E-002)); -#53767 = CARTESIAN_POINT('',(0.928197829471,2.203939738393E-002)); -#53768 = CARTESIAN_POINT('',(0.856797996435,2.203939738393E-002)); -#53769 = CARTESIAN_POINT('',(0.785398163399,2.203939738393E-002)); -#53770 = CARTESIAN_POINT('',(0.713998330363,2.203939738393E-002)); -#53771 = CARTESIAN_POINT('',(0.642598497327,2.203939738393E-002)); -#53772 = CARTESIAN_POINT('',(0.571198664291,2.203939738393E-002)); -#53773 = CARTESIAN_POINT('',(0.499798831255,2.203939738393E-002)); -#53774 = CARTESIAN_POINT('',(0.428398998219,2.203939738393E-002)); -#53775 = CARTESIAN_POINT('',(0.356999165183,2.203939738393E-002)); -#53776 = CARTESIAN_POINT('',(0.285599332147,2.203939738393E-002)); -#53777 = CARTESIAN_POINT('',(0.214199499111,2.203939738393E-002)); -#53778 = CARTESIAN_POINT('',(0.142799666075,2.203939738393E-002)); -#53779 = CARTESIAN_POINT('',(7.139983303905E-002,2.203939738393E-002)); -#53780 = CARTESIAN_POINT('',(2.379994434689E-002,2.203939738393E-002)); -#53781 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); -#53782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53783 = ORIENTED_EDGE('',*,*,#53784,.F.); -#53784 = EDGE_CURVE('',#53618,#53739,#53785,.T.); -#53785 = SURFACE_CURVE('',#53786,(#53790,#53797),.PCURVE_S1.); -#53786 = LINE('',#53787,#53788); -#53787 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.05)); -#53788 = VECTOR('',#53789,1.); -#53789 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53790 = PCURVE('',#52619,#53791); -#53791 = DEFINITIONAL_REPRESENTATION('',(#53792),#53796); -#53792 = LINE('',#53793,#53794); -#53793 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#53794 = VECTOR('',#53795,1.); -#53795 = DIRECTION('',(0.E+000,-1.)); -#53796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53797 = PCURVE('',#53723,#53798); -#53798 = DEFINITIONAL_REPRESENTATION('',(#53799),#53803); -#53799 = LINE('',#53800,#53801); -#53800 = CARTESIAN_POINT('',(0.3,-0.3)); -#53801 = VECTOR('',#53802,1.); -#53802 = DIRECTION('',(0.E+000,-1.)); -#53803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53804 = ORIENTED_EDGE('',*,*,#53617,.F.); -#53805 = ORIENTED_EDGE('',*,*,#53343,.T.); -#53806 = ORIENTED_EDGE('',*,*,#53807,.T.); -#53807 = EDGE_CURVE('',#53321,#52604,#53808,.T.); -#53808 = SURFACE_CURVE('',#53809,(#53813,#53820),.PCURVE_S1.); -#53809 = LINE('',#53810,#53811); -#53810 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-2.35)); -#53811 = VECTOR('',#53812,1.); -#53812 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53813 = PCURVE('',#52619,#53814); -#53814 = DEFINITIONAL_REPRESENTATION('',(#53815),#53819); -#53815 = LINE('',#53816,#53817); -#53816 = CARTESIAN_POINT('',(0.640997074522,0.E+000)); -#53817 = VECTOR('',#53818,1.); -#53818 = DIRECTION('',(0.E+000,-1.)); -#53819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53820 = PCURVE('',#47328,#53821); -#53821 = DEFINITIONAL_REPRESENTATION('',(#53822),#53825); -#53822 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53823,#53824),.UNSPECIFIED., +#56149 = CARTESIAN_POINT('',(1.570796326795,2.203939738393E-002)); +#56150 = CARTESIAN_POINT('',(1.54699638245,2.203939738393E-002)); +#56151 = CARTESIAN_POINT('',(1.499396493759,2.203939738393E-002)); +#56152 = CARTESIAN_POINT('',(1.427996660723,2.203939738393E-002)); +#56153 = CARTESIAN_POINT('',(1.356596827687,2.203939738393E-002)); +#56154 = CARTESIAN_POINT('',(1.285196994651,2.203939738393E-002)); +#56155 = CARTESIAN_POINT('',(1.213797161615,2.203939738393E-002)); +#56156 = CARTESIAN_POINT('',(1.142397328579,2.203939738393E-002)); +#56157 = CARTESIAN_POINT('',(1.070997495543,2.203939738393E-002)); +#56158 = CARTESIAN_POINT('',(0.999597662507,2.203939738393E-002)); +#56159 = CARTESIAN_POINT('',(0.928197829471,2.203939738393E-002)); +#56160 = CARTESIAN_POINT('',(0.856797996435,2.203939738393E-002)); +#56161 = CARTESIAN_POINT('',(0.785398163399,2.203939738393E-002)); +#56162 = CARTESIAN_POINT('',(0.713998330363,2.203939738393E-002)); +#56163 = CARTESIAN_POINT('',(0.642598497327,2.203939738393E-002)); +#56164 = CARTESIAN_POINT('',(0.571198664291,2.203939738393E-002)); +#56165 = CARTESIAN_POINT('',(0.499798831255,2.203939738393E-002)); +#56166 = CARTESIAN_POINT('',(0.428398998219,2.203939738393E-002)); +#56167 = CARTESIAN_POINT('',(0.356999165183,2.203939738393E-002)); +#56168 = CARTESIAN_POINT('',(0.285599332147,2.203939738393E-002)); +#56169 = CARTESIAN_POINT('',(0.214199499111,2.203939738393E-002)); +#56170 = CARTESIAN_POINT('',(0.142799666075,2.203939738393E-002)); +#56171 = CARTESIAN_POINT('',(7.139983303905E-002,2.203939738393E-002)); +#56172 = CARTESIAN_POINT('',(2.379994434689E-002,2.203939738393E-002)); +#56173 = CARTESIAN_POINT('',(0.E+000,2.203939738393E-002)); +#56174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56175 = ORIENTED_EDGE('',*,*,#56176,.F.); +#56176 = EDGE_CURVE('',#56010,#56131,#56177,.T.); +#56177 = SURFACE_CURVE('',#56178,(#56182,#56189),.PCURVE_S1.); +#56178 = LINE('',#56179,#56180); +#56179 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-2.05)); +#56180 = VECTOR('',#56181,1.); +#56181 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56182 = PCURVE('',#55011,#56183); +#56183 = DEFINITIONAL_REPRESENTATION('',(#56184),#56188); +#56184 = LINE('',#56185,#56186); +#56185 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#56186 = VECTOR('',#56187,1.); +#56187 = DIRECTION('',(0.E+000,-1.)); +#56188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56189 = PCURVE('',#56115,#56190); +#56190 = DEFINITIONAL_REPRESENTATION('',(#56191),#56195); +#56191 = LINE('',#56192,#56193); +#56192 = CARTESIAN_POINT('',(0.3,-0.3)); +#56193 = VECTOR('',#56194,1.); +#56194 = DIRECTION('',(0.E+000,-1.)); +#56195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56196 = ORIENTED_EDGE('',*,*,#56009,.F.); +#56197 = ORIENTED_EDGE('',*,*,#55735,.T.); +#56198 = ORIENTED_EDGE('',*,*,#56199,.T.); +#56199 = EDGE_CURVE('',#55713,#54996,#56200,.T.); +#56200 = SURFACE_CURVE('',#56201,(#56205,#56212),.PCURVE_S1.); +#56201 = LINE('',#56202,#56203); +#56202 = CARTESIAN_POINT('',(-2.262642356365,0.906915204429,-2.35)); +#56203 = VECTOR('',#56204,1.); +#56204 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56205 = PCURVE('',#55011,#56206); +#56206 = DEFINITIONAL_REPRESENTATION('',(#56207),#56211); +#56207 = LINE('',#56208,#56209); +#56208 = CARTESIAN_POINT('',(0.640997074522,0.E+000)); +#56209 = VECTOR('',#56210,1.); +#56210 = DIRECTION('',(0.E+000,-1.)); +#56211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56212 = PCURVE('',#49720,#56213); +#56213 = DEFINITIONAL_REPRESENTATION('',(#56214),#56217); +#56214 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56215,#56216),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#53823 = CARTESIAN_POINT('',(2.181661564992,0.E+000)); -#53824 = CARTESIAN_POINT('',(2.181661564992,-0.7)); -#53825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53826 = ORIENTED_EDGE('',*,*,#52603,.F.); -#53827 = ADVANCED_FACE('',(#53828),#52569,.T.); -#53828 = FACE_BOUND('',#53829,.T.); -#53829 = EDGE_LOOP('',(#53830,#53876,#53877,#53878)); -#53830 = ORIENTED_EDGE('',*,*,#53831,.F.); -#53831 = EDGE_CURVE('',#52554,#53832,#53834,.T.); -#53832 = VERTEX_POINT('',#53833); -#53833 = CARTESIAN_POINT('',(-1.565495361482,0.785,-1.75)); -#53834 = SURFACE_CURVE('',#53835,(#53840,#53869),.PCURVE_S1.); -#53835 = CIRCLE('',#53836,0.1); -#53836 = AXIS2_PLACEMENT_3D('',#53837,#53838,#53839); -#53837 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635,-1.75)); -#53838 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#53839 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53840 = PCURVE('',#52569,#53841); -#53841 = DEFINITIONAL_REPRESENTATION('',(#53842),#53868); -#53842 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#53843,#53844,#53845,#53846, - #53847,#53848,#53849,#53850,#53851,#53852,#53853,#53854,#53855, - #53856,#53857,#53858,#53859,#53860,#53861,#53862,#53863,#53864, - #53865,#53866,#53867),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56215 = CARTESIAN_POINT('',(2.181661564992,0.E+000)); +#56216 = CARTESIAN_POINT('',(2.181661564992,-0.7)); +#56217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56218 = ORIENTED_EDGE('',*,*,#54995,.F.); +#56219 = ADVANCED_FACE('',(#56220),#54961,.T.); +#56220 = FACE_BOUND('',#56221,.T.); +#56221 = EDGE_LOOP('',(#56222,#56268,#56269,#56270)); +#56222 = ORIENTED_EDGE('',*,*,#56223,.F.); +#56223 = EDGE_CURVE('',#54946,#56224,#56226,.T.); +#56224 = VERTEX_POINT('',#56225); +#56225 = CARTESIAN_POINT('',(-1.565495361482,0.785,-1.75)); +#56226 = SURFACE_CURVE('',#56227,(#56232,#56261),.PCURVE_S1.); +#56227 = CIRCLE('',#56228,0.1); +#56228 = AXIS2_PLACEMENT_3D('',#56229,#56230,#56231); +#56229 = CARTESIAN_POINT('',(-1.647410565911,0.842357643635,-1.75)); +#56230 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#56231 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56232 = PCURVE('',#54961,#56233); +#56233 = DEFINITIONAL_REPRESENTATION('',(#56234),#56260); +#56234 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56235,#56236,#56237,#56238, + #56239,#56240,#56241,#56242,#56243,#56244,#56245,#56246,#56247, + #56248,#56249,#56250,#56251,#56252,#56253,#56254,#56255,#56256, + #56257,#56258,#56259),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -66881,432 +69870,432 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#53843 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#53844 = CARTESIAN_POINT('',(2.379994434539E-002,0.322039397384)); -#53845 = CARTESIAN_POINT('',(7.139983303616E-002,0.322039397384)); -#53846 = CARTESIAN_POINT('',(0.142799666072,0.322039397384)); -#53847 = CARTESIAN_POINT('',(0.214199499108,0.322039397384)); -#53848 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); -#53849 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); -#53850 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); -#53851 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); -#53852 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); -#53853 = CARTESIAN_POINT('',(0.642598497325,0.322039397384)); -#53854 = CARTESIAN_POINT('',(0.713998330361,0.322039397384)); -#53855 = CARTESIAN_POINT('',(0.785398163397,0.322039397384)); -#53856 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); -#53857 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); -#53858 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); -#53859 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); -#53860 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); -#53861 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); -#53862 = CARTESIAN_POINT('',(1.28519699465,0.322039397384)); -#53863 = CARTESIAN_POINT('',(1.356596827687,0.322039397384)); -#53864 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); -#53865 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); -#53866 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); -#53867 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#53868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53869 = PCURVE('',#52696,#53870); -#53870 = DEFINITIONAL_REPRESENTATION('',(#53871),#53875); -#53871 = CIRCLE('',#53872,0.1); -#53872 = AXIS2_PLACEMENT_2D('',#53873,#53874); -#53873 = CARTESIAN_POINT('',(0.604056832297,-0.6)); -#53874 = DIRECTION('',(0.E+000,-1.)); -#53875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53876 = ORIENTED_EDGE('',*,*,#52551,.F.); -#53877 = ORIENTED_EDGE('',*,*,#53738,.F.); -#53878 = ORIENTED_EDGE('',*,*,#53879,.T.); -#53879 = EDGE_CURVE('',#53739,#53832,#53880,.T.); -#53880 = SURFACE_CURVE('',#53881,(#53885,#53891),.PCURVE_S1.); -#53881 = LINE('',#53882,#53883); -#53882 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-1.75)); -#53883 = VECTOR('',#53884,1.); -#53884 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); -#53885 = PCURVE('',#52569,#53886); -#53886 = DEFINITIONAL_REPRESENTATION('',(#53887),#53890); -#53887 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53888,#53889),.UNSPECIFIED., +#56235 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#56236 = CARTESIAN_POINT('',(2.379994434539E-002,0.322039397384)); +#56237 = CARTESIAN_POINT('',(7.139983303616E-002,0.322039397384)); +#56238 = CARTESIAN_POINT('',(0.142799666072,0.322039397384)); +#56239 = CARTESIAN_POINT('',(0.214199499108,0.322039397384)); +#56240 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); +#56241 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); +#56242 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); +#56243 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); +#56244 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); +#56245 = CARTESIAN_POINT('',(0.642598497325,0.322039397384)); +#56246 = CARTESIAN_POINT('',(0.713998330361,0.322039397384)); +#56247 = CARTESIAN_POINT('',(0.785398163397,0.322039397384)); +#56248 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); +#56249 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); +#56250 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); +#56251 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); +#56252 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); +#56253 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); +#56254 = CARTESIAN_POINT('',(1.28519699465,0.322039397384)); +#56255 = CARTESIAN_POINT('',(1.356596827687,0.322039397384)); +#56256 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); +#56257 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); +#56258 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); +#56259 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#56260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56261 = PCURVE('',#55088,#56262); +#56262 = DEFINITIONAL_REPRESENTATION('',(#56263),#56267); +#56263 = CIRCLE('',#56264,0.1); +#56264 = AXIS2_PLACEMENT_2D('',#56265,#56266); +#56265 = CARTESIAN_POINT('',(0.604056832297,-0.6)); +#56266 = DIRECTION('',(0.E+000,-1.)); +#56267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56268 = ORIENTED_EDGE('',*,*,#54943,.F.); +#56269 = ORIENTED_EDGE('',*,*,#56130,.F.); +#56270 = ORIENTED_EDGE('',*,*,#56271,.T.); +#56271 = EDGE_CURVE('',#56131,#56224,#56272,.T.); +#56272 = SURFACE_CURVE('',#56273,(#56277,#56283),.PCURVE_S1.); +#56273 = LINE('',#56274,#56275); +#56274 = CARTESIAN_POINT('',(-1.737568292387,0.539254386713,-1.75)); +#56275 = VECTOR('',#56276,1.); +#56276 = DIRECTION('',(0.573576436351,0.819152044289,0.E+000)); +#56277 = PCURVE('',#54961,#56278); +#56278 = DEFINITIONAL_REPRESENTATION('',(#56279),#56282); +#56279 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56280,#56281),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#53888 = CARTESIAN_POINT('',(1.570796326795,2.203939738398E-002)); -#53889 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#53890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53891 = PCURVE('',#53723,#53892); -#53892 = DEFINITIONAL_REPRESENTATION('',(#53893),#53897); -#53893 = LINE('',#53894,#53895); -#53894 = CARTESIAN_POINT('',(0.3,-0.6)); -#53895 = VECTOR('',#53896,1.); -#53896 = DIRECTION('',(-1.,0.E+000)); -#53897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53898 = ADVANCED_FACE('',(#53899),#52696,.T.); -#53899 = FACE_BOUND('',#53900,.F.); -#53900 = EDGE_LOOP('',(#53901,#53902,#53903,#53923,#53924,#53925)); -#53901 = ORIENTED_EDGE('',*,*,#53831,.F.); -#53902 = ORIENTED_EDGE('',*,*,#52682,.F.); -#53903 = ORIENTED_EDGE('',*,*,#53904,.F.); -#53904 = EDGE_CURVE('',#53034,#52660,#53905,.T.); -#53905 = SURFACE_CURVE('',#53906,(#53910,#53917),.PCURVE_S1.); -#53906 = LINE('',#53907,#53908); -#53907 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); -#53908 = VECTOR('',#53909,1.); -#53909 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53910 = PCURVE('',#52696,#53911); -#53911 = DEFINITIONAL_REPRESENTATION('',(#53912),#53916); -#53912 = LINE('',#53913,#53914); -#53913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53914 = VECTOR('',#53915,1.); -#53915 = DIRECTION('',(0.E+000,-1.)); -#53916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53917 = PCURVE('',#49303,#53918); -#53918 = DEFINITIONAL_REPRESENTATION('',(#53919),#53922); -#53919 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53920,#53921),.UNSPECIFIED., +#56280 = CARTESIAN_POINT('',(1.570796326795,2.203939738398E-002)); +#56281 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#56282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56283 = PCURVE('',#56115,#56284); +#56284 = DEFINITIONAL_REPRESENTATION('',(#56285),#56289); +#56285 = LINE('',#56286,#56287); +#56286 = CARTESIAN_POINT('',(0.3,-0.6)); +#56287 = VECTOR('',#56288,1.); +#56288 = DIRECTION('',(-1.,0.E+000)); +#56289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56290 = ADVANCED_FACE('',(#56291),#55088,.T.); +#56291 = FACE_BOUND('',#56292,.F.); +#56292 = EDGE_LOOP('',(#56293,#56294,#56295,#56315,#56316,#56317)); +#56293 = ORIENTED_EDGE('',*,*,#56223,.F.); +#56294 = ORIENTED_EDGE('',*,*,#55074,.F.); +#56295 = ORIENTED_EDGE('',*,*,#56296,.F.); +#56296 = EDGE_CURVE('',#55426,#55052,#56297,.T.); +#56297 = SURFACE_CURVE('',#56298,(#56302,#56309),.PCURVE_S1.); +#56298 = LINE('',#56299,#56300); +#56299 = CARTESIAN_POINT('',(-2.142224954954,1.188830408858,-2.35)); +#56300 = VECTOR('',#56301,1.); +#56301 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56302 = PCURVE('',#55088,#56303); +#56303 = DEFINITIONAL_REPRESENTATION('',(#56304),#56308); +#56304 = LINE('',#56305,#56306); +#56305 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#56306 = VECTOR('',#56307,1.); +#56307 = DIRECTION('',(0.E+000,-1.)); +#56308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56309 = PCURVE('',#51695,#56310); +#56310 = DEFINITIONAL_REPRESENTATION('',(#56311),#56314); +#56311 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56312,#56313),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#53920 = CARTESIAN_POINT('',(2.181661564991,0.E+000)); -#53921 = CARTESIAN_POINT('',(2.181661564991,-0.7)); -#53922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53923 = ORIENTED_EDGE('',*,*,#53033,.T.); -#53924 = ORIENTED_EDGE('',*,*,#53664,.F.); -#53925 = ORIENTED_EDGE('',*,*,#53926,.T.); -#53926 = EDGE_CURVE('',#53665,#53832,#53927,.T.); -#53927 = SURFACE_CURVE('',#53928,(#53932,#53939),.PCURVE_S1.); -#53928 = LINE('',#53929,#53930); -#53929 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); -#53930 = VECTOR('',#53931,1.); -#53931 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53932 = PCURVE('',#52696,#53933); -#53933 = DEFINITIONAL_REPRESENTATION('',(#53934),#53938); -#53934 = LINE('',#53935,#53936); -#53935 = CARTESIAN_POINT('',(0.704056832298,-0.3)); -#53936 = VECTOR('',#53937,1.); -#53937 = DIRECTION('',(0.E+000,-1.)); -#53938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53939 = PCURVE('',#53723,#53940); -#53940 = DEFINITIONAL_REPRESENTATION('',(#53941),#53945); -#53941 = LINE('',#53942,#53943); -#53942 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#53943 = VECTOR('',#53944,1.); -#53944 = DIRECTION('',(0.E+000,-1.)); -#53945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53946 = ADVANCED_FACE('',(#53947),#49303,.T.); -#53947 = FACE_BOUND('',#53948,.T.); -#53948 = EDGE_LOOP('',(#53949,#53950,#53951,#53952)); -#53949 = ORIENTED_EDGE('',*,*,#53056,.F.); -#53950 = ORIENTED_EDGE('',*,*,#49287,.T.); -#53951 = ORIENTED_EDGE('',*,*,#52659,.T.); -#53952 = ORIENTED_EDGE('',*,*,#53904,.F.); -#53953 = ADVANCED_FACE('',(#53954),#53723,.T.); -#53954 = FACE_BOUND('',#53955,.F.); -#53955 = EDGE_LOOP('',(#53956,#53957,#53958,#53959)); -#53956 = ORIENTED_EDGE('',*,*,#53879,.T.); -#53957 = ORIENTED_EDGE('',*,*,#53926,.F.); -#53958 = ORIENTED_EDGE('',*,*,#53710,.T.); -#53959 = ORIENTED_EDGE('',*,*,#53784,.T.); -#53960 = ADVANCED_FACE('',(#53961),#47328,.F.); -#53961 = FACE_BOUND('',#53962,.F.); -#53962 = EDGE_LOOP('',(#53963,#53964,#53965,#53966)); -#53963 = ORIENTED_EDGE('',*,*,#53320,.T.); -#53964 = ORIENTED_EDGE('',*,*,#47312,.T.); -#53965 = ORIENTED_EDGE('',*,*,#52631,.F.); -#53966 = ORIENTED_EDGE('',*,*,#53807,.F.); -#53967 = ADVANCED_FACE('',(#53968),#38411,.T.); -#53968 = FACE_BOUND('',#53969,.T.); -#53969 = EDGE_LOOP('',(#53970,#53971,#53972,#53973)); -#53970 = ORIENTED_EDGE('',*,*,#38394,.F.); -#53971 = ORIENTED_EDGE('',*,*,#49242,.F.); -#53972 = ORIENTED_EDGE('',*,*,#53082,.T.); -#53973 = ORIENTED_EDGE('',*,*,#53974,.T.); -#53974 = EDGE_CURVE('',#53083,#38372,#53975,.T.); -#53975 = SURFACE_CURVE('',#53976,(#53980,#53986),.PCURVE_S1.); -#53976 = LINE('',#53977,#53978); -#53977 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); -#53978 = VECTOR('',#53979,1.); -#53979 = DIRECTION('',(0.E+000,0.E+000,1.)); -#53980 = PCURVE('',#38411,#53981); -#53981 = DEFINITIONAL_REPRESENTATION('',(#53982),#53985); -#53982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#53983,#53984),.UNSPECIFIED., +#56312 = CARTESIAN_POINT('',(2.181661564991,0.E+000)); +#56313 = CARTESIAN_POINT('',(2.181661564991,-0.7)); +#56314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56315 = ORIENTED_EDGE('',*,*,#55425,.T.); +#56316 = ORIENTED_EDGE('',*,*,#56056,.F.); +#56317 = ORIENTED_EDGE('',*,*,#56318,.T.); +#56318 = EDGE_CURVE('',#56057,#56224,#56319,.T.); +#56319 = SURFACE_CURVE('',#56320,(#56324,#56331),.PCURVE_S1.); +#56320 = LINE('',#56321,#56322); +#56321 = CARTESIAN_POINT('',(-1.565495361482,0.785,-2.05)); +#56322 = VECTOR('',#56323,1.); +#56323 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56324 = PCURVE('',#55088,#56325); +#56325 = DEFINITIONAL_REPRESENTATION('',(#56326),#56330); +#56326 = LINE('',#56327,#56328); +#56327 = CARTESIAN_POINT('',(0.704056832298,-0.3)); +#56328 = VECTOR('',#56329,1.); +#56329 = DIRECTION('',(0.E+000,-1.)); +#56330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56331 = PCURVE('',#56115,#56332); +#56332 = DEFINITIONAL_REPRESENTATION('',(#56333),#56337); +#56333 = LINE('',#56334,#56335); +#56334 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#56335 = VECTOR('',#56336,1.); +#56336 = DIRECTION('',(0.E+000,-1.)); +#56337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56338 = ADVANCED_FACE('',(#56339),#51695,.T.); +#56339 = FACE_BOUND('',#56340,.T.); +#56340 = EDGE_LOOP('',(#56341,#56342,#56343,#56344)); +#56341 = ORIENTED_EDGE('',*,*,#55448,.F.); +#56342 = ORIENTED_EDGE('',*,*,#51679,.T.); +#56343 = ORIENTED_EDGE('',*,*,#55051,.T.); +#56344 = ORIENTED_EDGE('',*,*,#56296,.F.); +#56345 = ADVANCED_FACE('',(#56346),#56115,.T.); +#56346 = FACE_BOUND('',#56347,.F.); +#56347 = EDGE_LOOP('',(#56348,#56349,#56350,#56351)); +#56348 = ORIENTED_EDGE('',*,*,#56271,.T.); +#56349 = ORIENTED_EDGE('',*,*,#56318,.F.); +#56350 = ORIENTED_EDGE('',*,*,#56102,.T.); +#56351 = ORIENTED_EDGE('',*,*,#56176,.T.); +#56352 = ADVANCED_FACE('',(#56353),#49720,.F.); +#56353 = FACE_BOUND('',#56354,.F.); +#56354 = EDGE_LOOP('',(#56355,#56356,#56357,#56358)); +#56355 = ORIENTED_EDGE('',*,*,#55712,.T.); +#56356 = ORIENTED_EDGE('',*,*,#49704,.T.); +#56357 = ORIENTED_EDGE('',*,*,#55023,.F.); +#56358 = ORIENTED_EDGE('',*,*,#56199,.F.); +#56359 = ADVANCED_FACE('',(#56360),#40803,.T.); +#56360 = FACE_BOUND('',#56361,.T.); +#56361 = EDGE_LOOP('',(#56362,#56363,#56364,#56365)); +#56362 = ORIENTED_EDGE('',*,*,#40786,.F.); +#56363 = ORIENTED_EDGE('',*,*,#51634,.F.); +#56364 = ORIENTED_EDGE('',*,*,#55474,.T.); +#56365 = ORIENTED_EDGE('',*,*,#56366,.T.); +#56366 = EDGE_CURVE('',#55475,#40764,#56367,.T.); +#56367 = SURFACE_CURVE('',#56368,(#56372,#56378),.PCURVE_S1.); +#56368 = LINE('',#56369,#56370); +#56369 = CARTESIAN_POINT('',(-3.75,0.675,-2.35)); +#56370 = VECTOR('',#56371,1.); +#56371 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56372 = PCURVE('',#40803,#56373); +#56373 = DEFINITIONAL_REPRESENTATION('',(#56374),#56377); +#56374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56375,#56376),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#53983 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#53984 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#53985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53986 = PCURVE('',#37969,#53987); -#53987 = DEFINITIONAL_REPRESENTATION('',(#53988),#53992); -#53988 = LINE('',#53989,#53990); -#53989 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#53990 = VECTOR('',#53991,1.); -#53991 = DIRECTION('',(0.E+000,1.)); -#53992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#53993 = ADVANCED_FACE('',(#53994),#37969,.T.); -#53994 = FACE_BOUND('',#53995,.F.); -#53995 = EDGE_LOOP('',(#53996,#54018,#54043,#54044,#54071,#54091,#54092, - #54093,#54094,#54115)); -#53996 = ORIENTED_EDGE('',*,*,#53997,.T.); -#53997 = EDGE_CURVE('',#37928,#53998,#54000,.T.); -#53998 = VERTEX_POINT('',#53999); -#53999 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,0.941561175052) - ); -#54000 = SURFACE_CURVE('',#54001,(#54005,#54012),.PCURVE_S1.); -#54001 = LINE('',#54002,#54003); -#54002 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,2.35)); -#54003 = VECTOR('',#54004,1.); -#54004 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#54005 = PCURVE('',#37969,#54006); -#54006 = DEFINITIONAL_REPRESENTATION('',(#54007),#54011); -#54007 = LINE('',#54008,#54009); -#54008 = CARTESIAN_POINT('',(0.746446609407,4.7)); -#54009 = VECTOR('',#54010,1.); -#54010 = DIRECTION('',(0.E+000,-1.)); -#54011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54012 = PCURVE('',#37944,#54013); -#54013 = DEFINITIONAL_REPRESENTATION('',(#54014),#54017); -#54014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54015,#54016),.UNSPECIFIED., +#56375 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#56376 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#56377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56378 = PCURVE('',#40361,#56379); +#56379 = DEFINITIONAL_REPRESENTATION('',(#56380),#56384); +#56380 = LINE('',#56381,#56382); +#56381 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#56382 = VECTOR('',#56383,1.); +#56383 = DIRECTION('',(0.E+000,1.)); +#56384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56385 = ADVANCED_FACE('',(#56386),#40361,.T.); +#56386 = FACE_BOUND('',#56387,.F.); +#56387 = EDGE_LOOP('',(#56388,#56410,#56435,#56436,#56463,#56483,#56484, + #56485,#56486,#56507)); +#56388 = ORIENTED_EDGE('',*,*,#56389,.T.); +#56389 = EDGE_CURVE('',#40320,#56390,#56392,.T.); +#56390 = VERTEX_POINT('',#56391); +#56391 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,0.941561175052) + ); +#56392 = SURFACE_CURVE('',#56393,(#56397,#56404),.PCURVE_S1.); +#56393 = LINE('',#56394,#56395); +#56394 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,2.35)); +#56395 = VECTOR('',#56396,1.); +#56396 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#56397 = PCURVE('',#40361,#56398); +#56398 = DEFINITIONAL_REPRESENTATION('',(#56399),#56403); +#56399 = LINE('',#56400,#56401); +#56400 = CARTESIAN_POINT('',(0.746446609407,4.7)); +#56401 = VECTOR('',#56402,1.); +#56402 = DIRECTION('',(0.E+000,-1.)); +#56403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56404 = PCURVE('',#40336,#56405); +#56405 = DEFINITIONAL_REPRESENTATION('',(#56406),#56409); +#56406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56407,#56408),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.408438824948),.PIECEWISE_BEZIER_KNOTS.); -#54015 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#54016 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); -#54017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54018 = ORIENTED_EDGE('',*,*,#54019,.F.); -#54019 = EDGE_CURVE('',#39943,#53998,#54020,.T.); -#54020 = SURFACE_CURVE('',#54021,(#54026,#54037),.PCURVE_S1.); -#54021 = CIRCLE('',#54022,0.3); -#54022 = AXIS2_PLACEMENT_3D('',#54023,#54024,#54025); -#54023 = CARTESIAN_POINT('',(-3.75,-0.175,0.66)); -#54024 = DIRECTION('',(1.,0.E+000,0.E+000)); -#54025 = DIRECTION('',(0.E+000,1.,0.E+000)); -#54026 = PCURVE('',#37969,#54027); -#54027 = DEFINITIONAL_REPRESENTATION('',(#54028),#54036); -#54028 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54029,#54030,#54031,#54032 - ,#54033,#54034,#54035),.UNSPECIFIED.,.F.,.F.) +#56407 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#56408 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); +#56409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56410 = ORIENTED_EDGE('',*,*,#56411,.F.); +#56411 = EDGE_CURVE('',#42335,#56390,#56412,.T.); +#56412 = SURFACE_CURVE('',#56413,(#56418,#56429),.PCURVE_S1.); +#56413 = CIRCLE('',#56414,0.3); +#56414 = AXIS2_PLACEMENT_3D('',#56415,#56416,#56417); +#56415 = CARTESIAN_POINT('',(-3.75,-0.175,0.66)); +#56416 = DIRECTION('',(1.,0.E+000,0.E+000)); +#56417 = DIRECTION('',(0.E+000,1.,0.E+000)); +#56418 = PCURVE('',#40361,#56419); +#56419 = DEFINITIONAL_REPRESENTATION('',(#56420),#56428); +#56420 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56421,#56422,#56423,#56424 + ,#56425,#56426,#56427),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#54029 = CARTESIAN_POINT('',(0.55,3.01)); -#54030 = CARTESIAN_POINT('',(0.55,3.529615242271)); -#54031 = CARTESIAN_POINT('',(1.,3.269807621135)); -#54032 = CARTESIAN_POINT('',(1.45,3.01)); -#54033 = CARTESIAN_POINT('',(1.,2.750192378865)); -#54034 = CARTESIAN_POINT('',(0.55,2.490384757729)); -#54035 = CARTESIAN_POINT('',(0.55,3.01)); -#54036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54037 = PCURVE('',#39981,#54038); -#54038 = DEFINITIONAL_REPRESENTATION('',(#54039),#54042); -#54039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54040,#54041),.UNSPECIFIED., +#56421 = CARTESIAN_POINT('',(0.55,3.01)); +#56422 = CARTESIAN_POINT('',(0.55,3.529615242271)); +#56423 = CARTESIAN_POINT('',(1.,3.269807621135)); +#56424 = CARTESIAN_POINT('',(1.45,3.01)); +#56425 = CARTESIAN_POINT('',(1.,2.750192378865)); +#56426 = CARTESIAN_POINT('',(0.55,2.490384757729)); +#56427 = CARTESIAN_POINT('',(0.55,3.01)); +#56428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56429 = PCURVE('',#42373,#56430); +#56430 = DEFINITIONAL_REPRESENTATION('',(#56431),#56434); +#56431 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56432,#56433),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#54040 = CARTESIAN_POINT('',(0.E+000,1.6262878957E-002)); -#54041 = CARTESIAN_POINT('',(1.218367924887,1.6262878957E-002)); -#54042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54043 = ORIENTED_EDGE('',*,*,#39942,.F.); -#54044 = ORIENTED_EDGE('',*,*,#54045,.F.); -#54045 = EDGE_CURVE('',#54046,#39911,#54048,.T.); -#54046 = VERTEX_POINT('',#54047); -#54047 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) - ); -#54048 = SURFACE_CURVE('',#54049,(#54054,#54065),.PCURVE_S1.); -#54049 = CIRCLE('',#54050,0.3); -#54050 = AXIS2_PLACEMENT_3D('',#54051,#54052,#54053); -#54051 = CARTESIAN_POINT('',(-3.75,-0.175,-0.26)); -#54052 = DIRECTION('',(1.,0.E+000,0.E+000)); -#54053 = DIRECTION('',(0.E+000,0.345177968644,-0.938537250173)); -#54054 = PCURVE('',#37969,#54055); -#54055 = DEFINITIONAL_REPRESENTATION('',(#54056),#54064); -#54056 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54057,#54058,#54059,#54060 - ,#54061,#54062,#54063),.UNSPECIFIED.,.T.,.F.) +#56432 = CARTESIAN_POINT('',(0.E+000,1.6262878957E-002)); +#56433 = CARTESIAN_POINT('',(1.218367924887,1.6262878957E-002)); +#56434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56435 = ORIENTED_EDGE('',*,*,#42334,.F.); +#56436 = ORIENTED_EDGE('',*,*,#56437,.F.); +#56437 = EDGE_CURVE('',#56438,#42303,#56440,.T.); +#56438 = VERTEX_POINT('',#56439); +#56439 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) + ); +#56440 = SURFACE_CURVE('',#56441,(#56446,#56457),.PCURVE_S1.); +#56441 = CIRCLE('',#56442,0.3); +#56442 = AXIS2_PLACEMENT_3D('',#56443,#56444,#56445); +#56443 = CARTESIAN_POINT('',(-3.75,-0.175,-0.26)); +#56444 = DIRECTION('',(1.,0.E+000,0.E+000)); +#56445 = DIRECTION('',(0.E+000,0.345177968644,-0.938537250173)); +#56446 = PCURVE('',#40361,#56447); +#56447 = DEFINITIONAL_REPRESENTATION('',(#56448),#56456); +#56448 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56449,#56450,#56451,#56452 + ,#56453,#56454,#56455),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#54057 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); -#54058 = CARTESIAN_POINT('',(0.258768348778,1.987798558752)); -#54059 = CARTESIAN_POINT('',(0.657937564982,2.320460454428)); -#54060 = CARTESIAN_POINT('',(1.057106781187,2.653122350104)); -#54061 = CARTESIAN_POINT('',(1.145615825611,2.141100720624)); -#54062 = CARTESIAN_POINT('',(1.234124870036,1.629079091144)); -#54063 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); -#54064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54065 = PCURVE('',#39931,#54066); -#54066 = DEFINITIONAL_REPRESENTATION('',(#54067),#54070); -#54067 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54068,#54069),.UNSPECIFIED., +#56449 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); +#56450 = CARTESIAN_POINT('',(0.258768348778,1.987798558752)); +#56451 = CARTESIAN_POINT('',(0.657937564982,2.320460454428)); +#56452 = CARTESIAN_POINT('',(1.057106781187,2.653122350104)); +#56453 = CARTESIAN_POINT('',(1.145615825611,2.141100720624)); +#56454 = CARTESIAN_POINT('',(1.234124870036,1.629079091144)); +#56455 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); +#56456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56457 = PCURVE('',#42323,#56458); +#56458 = DEFINITIONAL_REPRESENTATION('',(#56459),#56462); +#56459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56460,#56461),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#54068 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); -#54069 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); -#54070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54071 = ORIENTED_EDGE('',*,*,#54072,.T.); -#54072 = EDGE_CURVE('',#54046,#53106,#54073,.T.); -#54073 = SURFACE_CURVE('',#54074,(#54078,#54085),.PCURVE_S1.); -#54074 = LINE('',#54075,#54076); -#54075 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) - ); -#54076 = VECTOR('',#54077,1.); -#54077 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#54078 = PCURVE('',#37969,#54079); -#54079 = DEFINITIONAL_REPRESENTATION('',(#54080),#54084); -#54080 = LINE('',#54081,#54082); -#54081 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); -#54082 = VECTOR('',#54083,1.); -#54083 = DIRECTION('',(0.E+000,-1.)); -#54084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54085 = PCURVE('',#53145,#54086); -#54086 = DEFINITIONAL_REPRESENTATION('',(#54087),#54090); -#54087 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54088,#54089),.UNSPECIFIED., +#56460 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); +#56461 = CARTESIAN_POINT('',(0.E+000,1.372039397384)); +#56462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56463 = ORIENTED_EDGE('',*,*,#56464,.T.); +#56464 = EDGE_CURVE('',#56438,#55498,#56465,.T.); +#56465 = SURFACE_CURVE('',#56466,(#56470,#56477),.PCURVE_S1.); +#56466 = LINE('',#56467,#56468); +#56467 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) + ); +#56468 = VECTOR('',#56469,1.); +#56469 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#56470 = PCURVE('',#40361,#56471); +#56471 = DEFINITIONAL_REPRESENTATION('',(#56472),#56476); +#56472 = LINE('',#56473,#56474); +#56473 = CARTESIAN_POINT('',(0.746446609407,1.808438824948)); +#56474 = VECTOR('',#56475,1.); +#56475 = DIRECTION('',(0.E+000,-1.)); +#56476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56477 = PCURVE('',#55537,#56478); +#56478 = DEFINITIONAL_REPRESENTATION('',(#56479),#56482); +#56479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56480,#56481),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.808438824948),.PIECEWISE_BEZIER_KNOTS.); -#54088 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); -#54089 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#54090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54091 = ORIENTED_EDGE('',*,*,#53105,.F.); -#54092 = ORIENTED_EDGE('',*,*,#53974,.T.); -#54093 = ORIENTED_EDGE('',*,*,#38371,.T.); -#54094 = ORIENTED_EDGE('',*,*,#54095,.T.); -#54095 = EDGE_CURVE('',#38337,#37633,#54096,.T.); -#54096 = SURFACE_CURVE('',#54097,(#54101,#54108),.PCURVE_S1.); -#54097 = LINE('',#54098,#54099); -#54098 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); -#54099 = VECTOR('',#54100,1.); -#54100 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#54101 = PCURVE('',#37969,#54102); -#54102 = DEFINITIONAL_REPRESENTATION('',(#54103),#54107); -#54103 = LINE('',#54104,#54105); -#54104 = CARTESIAN_POINT('',(5.E-002,4.7)); -#54105 = VECTOR('',#54106,1.); -#54106 = DIRECTION('',(1.,0.E+000)); -#54107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54108 = PCURVE('',#38979,#54109); -#54109 = DEFINITIONAL_REPRESENTATION('',(#54110),#54114); -#54110 = LINE('',#54111,#54112); -#54111 = CARTESIAN_POINT('',(0.311844708748,-0.6)); -#54112 = VECTOR('',#54113,1.); -#54113 = DIRECTION('',(0.E+000,1.)); -#54114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54115 = ORIENTED_EDGE('',*,*,#37955,.T.); -#54116 = ADVANCED_FACE('',(#54117),#53145,.T.); -#54117 = FACE_BOUND('',#54118,.T.); -#54118 = EDGE_LOOP('',(#54119,#54120,#54121,#54143,#54170)); -#54119 = ORIENTED_EDGE('',*,*,#54072,.T.); -#54120 = ORIENTED_EDGE('',*,*,#53128,.T.); -#54121 = ORIENTED_EDGE('',*,*,#54122,.T.); -#54122 = EDGE_CURVE('',#53129,#54123,#54125,.T.); -#54123 = VERTEX_POINT('',#54124); -#54124 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-0.56)); -#54125 = SURFACE_CURVE('',#54126,(#54130,#54136),.PCURVE_S1.); -#54126 = LINE('',#54127,#54128); -#54127 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); -#54128 = VECTOR('',#54129,1.); -#54129 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54130 = PCURVE('',#53145,#54131); -#54131 = DEFINITIONAL_REPRESENTATION('',(#54132),#54135); -#54132 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54133,#54134),.UNSPECIFIED., +#56480 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); +#56481 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#56482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56483 = ORIENTED_EDGE('',*,*,#55497,.F.); +#56484 = ORIENTED_EDGE('',*,*,#56366,.T.); +#56485 = ORIENTED_EDGE('',*,*,#40763,.T.); +#56486 = ORIENTED_EDGE('',*,*,#56487,.T.); +#56487 = EDGE_CURVE('',#40729,#40025,#56488,.T.); +#56488 = SURFACE_CURVE('',#56489,(#56493,#56500),.PCURVE_S1.); +#56489 = LINE('',#56490,#56491); +#56490 = CARTESIAN_POINT('',(-3.75,0.625,2.35)); +#56491 = VECTOR('',#56492,1.); +#56492 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#56493 = PCURVE('',#40361,#56494); +#56494 = DEFINITIONAL_REPRESENTATION('',(#56495),#56499); +#56495 = LINE('',#56496,#56497); +#56496 = CARTESIAN_POINT('',(5.E-002,4.7)); +#56497 = VECTOR('',#56498,1.); +#56498 = DIRECTION('',(1.,0.E+000)); +#56499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56500 = PCURVE('',#41371,#56501); +#56501 = DEFINITIONAL_REPRESENTATION('',(#56502),#56506); +#56502 = LINE('',#56503,#56504); +#56503 = CARTESIAN_POINT('',(0.311844708748,-0.6)); +#56504 = VECTOR('',#56505,1.); +#56505 = DIRECTION('',(0.E+000,1.)); +#56506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56507 = ORIENTED_EDGE('',*,*,#40347,.T.); +#56508 = ADVANCED_FACE('',(#56509),#55537,.T.); +#56509 = FACE_BOUND('',#56510,.T.); +#56510 = EDGE_LOOP('',(#56511,#56512,#56513,#56535,#56562)); +#56511 = ORIENTED_EDGE('',*,*,#56464,.T.); +#56512 = ORIENTED_EDGE('',*,*,#55520,.T.); +#56513 = ORIENTED_EDGE('',*,*,#56514,.T.); +#56514 = EDGE_CURVE('',#55521,#56515,#56517,.T.); +#56515 = VERTEX_POINT('',#56516); +#56516 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-0.56)); +#56517 = SURFACE_CURVE('',#56518,(#56522,#56528),.PCURVE_S1.); +#56518 = LINE('',#56519,#56520); +#56519 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-2.35)); +#56520 = VECTOR('',#56521,1.); +#56521 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56522 = PCURVE('',#55537,#56523); +#56523 = DEFINITIONAL_REPRESENTATION('',(#56524),#56527); +#56524 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56525,#56526),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.79),.PIECEWISE_BEZIER_KNOTS.); -#54133 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); -#54134 = CARTESIAN_POINT('',(3.926990816987,1.79)); -#54135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54136 = PCURVE('',#53172,#54137); -#54137 = DEFINITIONAL_REPRESENTATION('',(#54138),#54142); -#54138 = LINE('',#54139,#54140); -#54139 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#54140 = VECTOR('',#54141,1.); -#54141 = DIRECTION('',(0.E+000,1.)); -#54142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54143 = ORIENTED_EDGE('',*,*,#54144,.F.); -#54144 = EDGE_CURVE('',#54145,#54123,#54147,.T.); -#54145 = VERTEX_POINT('',#54146); -#54146 = CARTESIAN_POINT('',(-3.740163581979,-0.175,-0.56)); -#54147 = SURFACE_CURVE('',#54148,(#54153,#54159),.PCURVE_S1.); -#54148 = CIRCLE('',#54149,0.55); -#54149 = AXIS2_PLACEMENT_3D('',#54150,#54151,#54152); -#54150 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-0.56)); -#54151 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54152 = DIRECTION('',(-0.982115603599,-0.188278891988,0.E+000)); -#54153 = PCURVE('',#53145,#54154); -#54154 = DEFINITIONAL_REPRESENTATION('',(#54155),#54158); -#54155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54156,#54157),.UNSPECIFIED., +#56525 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); +#56526 = CARTESIAN_POINT('',(3.926990816987,1.79)); +#56527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56528 = PCURVE('',#55564,#56529); +#56529 = DEFINITIONAL_REPRESENTATION('',(#56530),#56534); +#56530 = LINE('',#56531,#56532); +#56531 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#56532 = VECTOR('',#56533,1.); +#56533 = DIRECTION('',(0.E+000,1.)); +#56534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56535 = ORIENTED_EDGE('',*,*,#56536,.F.); +#56536 = EDGE_CURVE('',#56537,#56515,#56539,.T.); +#56537 = VERTEX_POINT('',#56538); +#56538 = CARTESIAN_POINT('',(-3.740163581979,-0.175,-0.56)); +#56539 = SURFACE_CURVE('',#56540,(#56545,#56551),.PCURVE_S1.); +#56540 = CIRCLE('',#56541,0.55); +#56541 = AXIS2_PLACEMENT_3D('',#56542,#56543,#56544); +#56542 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-0.56)); +#56543 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56544 = DIRECTION('',(-0.982115603599,-0.188278891988,0.E+000)); +#56545 = PCURVE('',#55537,#56546); +#56546 = DEFINITIONAL_REPRESENTATION('',(#56547),#56550); +#56547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56548,#56549),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.595988761751),.PIECEWISE_BEZIER_KNOTS.); -#54156 = CARTESIAN_POINT('',(3.331002055236,1.79)); -#54157 = CARTESIAN_POINT('',(3.926990816987,1.79)); -#54158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56548 = CARTESIAN_POINT('',(3.331002055236,1.79)); +#56549 = CARTESIAN_POINT('',(3.926990816987,1.79)); +#56550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54159 = PCURVE('',#42672,#54160); -#54160 = DEFINITIONAL_REPRESENTATION('',(#54161),#54169); -#54161 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54162,#54163,#54164,#54165 - ,#54166,#54167,#54168),.UNSPECIFIED.,.F.,.F.) +#56551 = PCURVE('',#45064,#56552); +#56552 = DEFINITIONAL_REPRESENTATION('',(#56553),#56561); +#56553 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56554,#56555,#56556,#56557 + ,#56558,#56559,#56560),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#54162 = CARTESIAN_POINT('',(9.836418020769E-003,-1.05)); -#54163 = CARTESIAN_POINT('',(0.189196151824,-0.114409231614)); -#54164 = CARTESIAN_POINT('',(0.909761657891,-0.737534701697)); -#54165 = CARTESIAN_POINT('',(1.630327163958,-1.36066017178)); -#54166 = CARTESIAN_POINT('',(0.730401924088,-1.673125470083)); -#54167 = CARTESIAN_POINT('',(-0.169523315783,-1.985590768386)); -#54168 = CARTESIAN_POINT('',(9.836418020769E-003,-1.05)); -#54169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54170 = ORIENTED_EDGE('',*,*,#54171,.T.); -#54171 = EDGE_CURVE('',#54145,#54046,#54172,.T.); -#54172 = SURFACE_CURVE('',#54173,(#54179,#54208),.PCURVE_S1.); -#54173 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54174,#54175,#54176,#54177, - #54178),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#56554 = CARTESIAN_POINT('',(9.836418020769E-003,-1.05)); +#56555 = CARTESIAN_POINT('',(0.189196151824,-0.114409231614)); +#56556 = CARTESIAN_POINT('',(0.909761657891,-0.737534701697)); +#56557 = CARTESIAN_POINT('',(1.630327163958,-1.36066017178)); +#56558 = CARTESIAN_POINT('',(0.730401924088,-1.673125470083)); +#56559 = CARTESIAN_POINT('',(-0.169523315783,-1.985590768386)); +#56560 = CARTESIAN_POINT('',(9.836418020769E-003,-1.05)); +#56561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56562 = ORIENTED_EDGE('',*,*,#56563,.T.); +#56563 = EDGE_CURVE('',#56537,#56438,#56564,.T.); +#56564 = SURFACE_CURVE('',#56565,(#56571,#56600),.PCURVE_S1.); +#56565 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56566,#56567,#56568,#56569, + #56570),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#54174 = CARTESIAN_POINT('',(-3.740163581979,-0.175,-0.56)); -#54175 = CARTESIAN_POINT('',(-3.743515634982,-0.15751474967,-0.56)); -#54176 = CARTESIAN_POINT('',(-3.748473630876,-0.122395129262, +#56566 = CARTESIAN_POINT('',(-3.740163581979,-0.175,-0.56)); +#56567 = CARTESIAN_POINT('',(-3.743515634982,-0.15751474967,-0.56)); +#56568 = CARTESIAN_POINT('',(-3.748473630876,-0.122395129262, -0.556933190905)); -#54177 = CARTESIAN_POINT('',(-3.75,-8.810864667122E-002,-0.547689187739) +#56569 = CARTESIAN_POINT('',(-3.75,-8.810864667122E-002,-0.547689187739) ); -#54178 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) +#56570 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,-0.541561175052) ); -#54179 = PCURVE('',#53145,#54180); -#54180 = DEFINITIONAL_REPRESENTATION('',(#54181),#54207); -#54181 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54182,#54183,#54184,#54185, - #54186,#54187,#54188,#54189,#54190,#54191,#54192,#54193,#54194, - #54195,#54196,#54197,#54198,#54199,#54200,#54201,#54202,#54203, - #54204,#54205,#54206),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56571 = PCURVE('',#55537,#56572); +#56572 = DEFINITIONAL_REPRESENTATION('',(#56573),#56599); +#56573 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56574,#56575,#56576,#56577, + #56578,#56579,#56580,#56581,#56582,#56583,#56584,#56585,#56586, + #56587,#56588,#56589,#56590,#56591,#56592,#56593,#56594,#56595, + #56596,#56597,#56598),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67314,40 +70303,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54182 = CARTESIAN_POINT('',(3.331002055236,1.79)); -#54183 = CARTESIAN_POINT('',(3.328059303027,1.79)); -#54184 = CARTESIAN_POINT('',(3.322176533423,1.79002534553)); -#54185 = CARTESIAN_POINT('',(3.313362155407,1.790139449522)); -#54186 = CARTESIAN_POINT('',(3.304559120502,1.790329688321)); -#54187 = CARTESIAN_POINT('',(3.295769013699,1.790596111036)); -#54188 = CARTESIAN_POINT('',(3.286993430111,1.790938766775)); -#54189 = CARTESIAN_POINT('',(3.278233975302,1.791357704648)); -#54190 = CARTESIAN_POINT('',(3.269492263358,1.791852973762)); -#54191 = CARTESIAN_POINT('',(3.260769915555,1.792424623227)); -#54192 = CARTESIAN_POINT('',(3.252068558935,1.793072702152)); -#54193 = CARTESIAN_POINT('',(3.243389824757,1.793797259645)); -#54194 = CARTESIAN_POINT('',(3.234735347606,1.794598344815)); -#54195 = CARTESIAN_POINT('',(3.226106762143,1.795476006771)); -#54196 = CARTESIAN_POINT('',(3.217505572673,1.796430072918)); -#54197 = CARTESIAN_POINT('',(3.208933306006,1.79746037066)); -#54198 = CARTESIAN_POINT('',(3.200391508188,1.798566727402)); -#54199 = CARTESIAN_POINT('',(3.191881743633,1.799748970548)); -#54200 = CARTESIAN_POINT('',(3.183405593628,1.801006927503)); -#54201 = CARTESIAN_POINT('',(3.174964655044,1.802340425672)); -#54202 = CARTESIAN_POINT('',(3.166560538919,1.803749292459)); -#54203 = CARTESIAN_POINT('',(3.158194869478,1.805233355269)); -#54204 = CARTESIAN_POINT('',(3.149869281661,1.806792441506)); -#54205 = CARTESIAN_POINT('',(3.144346710123,1.807881732886)); -#54206 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); -#54207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54208 = PCURVE('',#39931,#54209); -#54209 = DEFINITIONAL_REPRESENTATION('',(#54210),#54236); -#54210 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54211,#54212,#54213,#54214, - #54215,#54216,#54217,#54218,#54219,#54220,#54221,#54222,#54223, - #54224,#54225,#54226,#54227,#54228,#54229,#54230,#54231,#54232, - #54233,#54234,#54235),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56574 = CARTESIAN_POINT('',(3.331002055236,1.79)); +#56575 = CARTESIAN_POINT('',(3.328059303027,1.79)); +#56576 = CARTESIAN_POINT('',(3.322176533423,1.79002534553)); +#56577 = CARTESIAN_POINT('',(3.313362155407,1.790139449522)); +#56578 = CARTESIAN_POINT('',(3.304559120502,1.790329688321)); +#56579 = CARTESIAN_POINT('',(3.295769013699,1.790596111036)); +#56580 = CARTESIAN_POINT('',(3.286993430111,1.790938766775)); +#56581 = CARTESIAN_POINT('',(3.278233975302,1.791357704648)); +#56582 = CARTESIAN_POINT('',(3.269492263358,1.791852973762)); +#56583 = CARTESIAN_POINT('',(3.260769915555,1.792424623227)); +#56584 = CARTESIAN_POINT('',(3.252068558935,1.793072702152)); +#56585 = CARTESIAN_POINT('',(3.243389824757,1.793797259645)); +#56586 = CARTESIAN_POINT('',(3.234735347606,1.794598344815)); +#56587 = CARTESIAN_POINT('',(3.226106762143,1.795476006771)); +#56588 = CARTESIAN_POINT('',(3.217505572673,1.796430072918)); +#56589 = CARTESIAN_POINT('',(3.208933306006,1.79746037066)); +#56590 = CARTESIAN_POINT('',(3.200391508188,1.798566727402)); +#56591 = CARTESIAN_POINT('',(3.191881743633,1.799748970548)); +#56592 = CARTESIAN_POINT('',(3.183405593628,1.801006927503)); +#56593 = CARTESIAN_POINT('',(3.174964655044,1.802340425672)); +#56594 = CARTESIAN_POINT('',(3.166560538919,1.803749292459)); +#56595 = CARTESIAN_POINT('',(3.158194869478,1.805233355269)); +#56596 = CARTESIAN_POINT('',(3.149869281661,1.806792441506)); +#56597 = CARTESIAN_POINT('',(3.144346710123,1.807881732886)); +#56598 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); +#56599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56600 = PCURVE('',#42323,#56601); +#56601 = DEFINITIONAL_REPRESENTATION('',(#56602),#56628); +#56602 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56603,#56604,#56605,#56606, + #56607,#56608,#56609,#56610,#56611,#56612,#56613,#56614,#56615, + #56616,#56617,#56618,#56619,#56620,#56621,#56622,#56623,#56624, + #56625,#56626,#56627),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67355,114 +70344,114 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54211 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); -#54212 = CARTESIAN_POINT('',(1.565497766316,1.362507711454)); -#54213 = CARTESIAN_POINT('',(1.55489653639,1.363102744974)); -#54214 = CARTESIAN_POINT('',(1.538982567586,1.363952071556)); -#54215 = CARTESIAN_POINT('',(1.523056677848,1.364758242725)); -#54216 = CARTESIAN_POINT('',(1.507119070203,1.36552132677)); -#54217 = CARTESIAN_POINT('',(1.491169941901,1.366241391976)); -#54218 = CARTESIAN_POINT('',(1.475209480172,1.366918506633)); -#54219 = CARTESIAN_POINT('',(1.45923785757,1.367552739026)); -#54220 = CARTESIAN_POINT('',(1.44325522743,1.368144157442)); -#54221 = CARTESIAN_POINT('',(1.42726171941,1.368692830169)); -#54222 = CARTESIAN_POINT('',(1.411257434705,1.369198825495)); -#54223 = CARTESIAN_POINT('',(1.395242442678,1.369662211705)); -#54224 = CARTESIAN_POINT('',(1.379216772338,1.370083057088)); -#54225 = CARTESIAN_POINT('',(1.3631804176,1.37046178864)); -#54226 = CARTESIAN_POINT('',(1.347133378193,1.370798833358)); -#54227 = CARTESIAN_POINT('',(1.331075651332,1.371094618239)); -#54228 = CARTESIAN_POINT('',(1.315007228584,1.371349570279)); -#54229 = CARTESIAN_POINT('',(1.298928091379,1.371564116476)); -#54230 = CARTESIAN_POINT('',(1.282838206797,1.371738683825)); -#54231 = CARTESIAN_POINT('',(1.266737523668,1.371873699325)); -#54232 = CARTESIAN_POINT('',(1.250625967263,1.371969589972)); -#54233 = CARTESIAN_POINT('',(1.234503439472,1.372026782763)); -#54234 = CARTESIAN_POINT('',(1.223747678895,1.372039397384)); -#54235 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); -#54236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54237 = ADVANCED_FACE('',(#54238),#37944,.T.); -#54238 = FACE_BOUND('',#54239,.T.); -#54239 = EDGE_LOOP('',(#54240,#54265,#54285,#54286,#54287)); -#54240 = ORIENTED_EDGE('',*,*,#54241,.T.); -#54241 = EDGE_CURVE('',#54242,#54244,#54246,.T.); -#54242 = VERTEX_POINT('',#54243); -#54243 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); -#54244 = VERTEX_POINT('',#54245); -#54245 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); -#54246 = SURFACE_CURVE('',#54247,(#54252,#54258),.PCURVE_S1.); -#54247 = CIRCLE('',#54248,0.55); -#54248 = AXIS2_PLACEMENT_3D('',#54249,#54250,#54251); -#54249 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,0.96)); -#54250 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54251 = DIRECTION('',(-0.982115603599,-0.188278891988,0.E+000)); -#54252 = PCURVE('',#37944,#54253); -#54253 = DEFINITIONAL_REPRESENTATION('',(#54254),#54257); -#54254 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54255,#54256),.UNSPECIFIED., +#56603 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); +#56604 = CARTESIAN_POINT('',(1.565497766316,1.362507711454)); +#56605 = CARTESIAN_POINT('',(1.55489653639,1.363102744974)); +#56606 = CARTESIAN_POINT('',(1.538982567586,1.363952071556)); +#56607 = CARTESIAN_POINT('',(1.523056677848,1.364758242725)); +#56608 = CARTESIAN_POINT('',(1.507119070203,1.36552132677)); +#56609 = CARTESIAN_POINT('',(1.491169941901,1.366241391976)); +#56610 = CARTESIAN_POINT('',(1.475209480172,1.366918506633)); +#56611 = CARTESIAN_POINT('',(1.45923785757,1.367552739026)); +#56612 = CARTESIAN_POINT('',(1.44325522743,1.368144157442)); +#56613 = CARTESIAN_POINT('',(1.42726171941,1.368692830169)); +#56614 = CARTESIAN_POINT('',(1.411257434705,1.369198825495)); +#56615 = CARTESIAN_POINT('',(1.395242442678,1.369662211705)); +#56616 = CARTESIAN_POINT('',(1.379216772338,1.370083057088)); +#56617 = CARTESIAN_POINT('',(1.3631804176,1.37046178864)); +#56618 = CARTESIAN_POINT('',(1.347133378193,1.370798833358)); +#56619 = CARTESIAN_POINT('',(1.331075651332,1.371094618239)); +#56620 = CARTESIAN_POINT('',(1.315007228584,1.371349570279)); +#56621 = CARTESIAN_POINT('',(1.298928091379,1.371564116476)); +#56622 = CARTESIAN_POINT('',(1.282838206797,1.371738683825)); +#56623 = CARTESIAN_POINT('',(1.266737523668,1.371873699325)); +#56624 = CARTESIAN_POINT('',(1.250625967263,1.371969589972)); +#56625 = CARTESIAN_POINT('',(1.234503439472,1.372026782763)); +#56626 = CARTESIAN_POINT('',(1.223747678895,1.372039397384)); +#56627 = CARTESIAN_POINT('',(1.218367924887,1.372039397384)); +#56628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56629 = ADVANCED_FACE('',(#56630),#40336,.T.); +#56630 = FACE_BOUND('',#56631,.T.); +#56631 = EDGE_LOOP('',(#56632,#56657,#56677,#56678,#56679)); +#56632 = ORIENTED_EDGE('',*,*,#56633,.T.); +#56633 = EDGE_CURVE('',#56634,#56636,#56638,.T.); +#56634 = VERTEX_POINT('',#56635); +#56635 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); +#56636 = VERTEX_POINT('',#56637); +#56637 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); +#56638 = SURFACE_CURVE('',#56639,(#56644,#56650),.PCURVE_S1.); +#56639 = CIRCLE('',#56640,0.55); +#56640 = AXIS2_PLACEMENT_3D('',#56641,#56642,#56643); +#56641 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,0.96)); +#56642 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56643 = DIRECTION('',(-0.982115603599,-0.188278891988,0.E+000)); +#56644 = PCURVE('',#40336,#56645); +#56645 = DEFINITIONAL_REPRESENTATION('',(#56646),#56649); +#56646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56647,#56648),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.595988761751),.PIECEWISE_BEZIER_KNOTS.); -#54255 = CARTESIAN_POINT('',(3.331002055236,3.31)); -#54256 = CARTESIAN_POINT('',(3.926990816987,3.31)); -#54257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54258 = PCURVE('',#42320,#54259); -#54259 = DEFINITIONAL_REPRESENTATION('',(#54260),#54264); -#54260 = CIRCLE('',#54261,0.55); -#54261 = AXIS2_PLACEMENT_2D('',#54262,#54263); -#54262 = CARTESIAN_POINT('',(0.8,-1.153553390593)); -#54263 = DIRECTION('',(0.982115603599,0.188278891988)); -#54264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54265 = ORIENTED_EDGE('',*,*,#54266,.T.); -#54266 = EDGE_CURVE('',#54244,#37900,#54267,.T.); -#54267 = SURFACE_CURVE('',#54268,(#54272,#54278),.PCURVE_S1.); -#54268 = LINE('',#54269,#54270); -#54269 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); -#54270 = VECTOR('',#54271,1.); -#54271 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54272 = PCURVE('',#37944,#54273); -#54273 = DEFINITIONAL_REPRESENTATION('',(#54274),#54277); -#54274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54275,#54276),.UNSPECIFIED., +#56647 = CARTESIAN_POINT('',(3.331002055236,3.31)); +#56648 = CARTESIAN_POINT('',(3.926990816987,3.31)); +#56649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56650 = PCURVE('',#44712,#56651); +#56651 = DEFINITIONAL_REPRESENTATION('',(#56652),#56656); +#56652 = CIRCLE('',#56653,0.55); +#56653 = AXIS2_PLACEMENT_2D('',#56654,#56655); +#56654 = CARTESIAN_POINT('',(0.8,-1.153553390593)); +#56655 = DIRECTION('',(0.982115603599,0.188278891988)); +#56656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56657 = ORIENTED_EDGE('',*,*,#56658,.T.); +#56658 = EDGE_CURVE('',#56636,#40292,#56659,.T.); +#56659 = SURFACE_CURVE('',#56660,(#56664,#56670),.PCURVE_S1.); +#56660 = LINE('',#56661,#56662); +#56661 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); +#56662 = VECTOR('',#56663,1.); +#56663 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56664 = PCURVE('',#40336,#56665); +#56665 = DEFINITIONAL_REPRESENTATION('',(#56666),#56669); +#56666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56667,#56668),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#54275 = CARTESIAN_POINT('',(3.926990816987,3.31)); -#54276 = CARTESIAN_POINT('',(3.926990816987,4.7)); -#54277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54278 = PCURVE('',#37915,#54279); -#54279 = DEFINITIONAL_REPRESENTATION('',(#54280),#54284); -#54280 = LINE('',#54281,#54282); -#54281 = CARTESIAN_POINT('',(0.E+000,3.31)); -#54282 = VECTOR('',#54283,1.); -#54283 = DIRECTION('',(0.E+000,1.)); -#54284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54285 = ORIENTED_EDGE('',*,*,#37927,.F.); -#54286 = ORIENTED_EDGE('',*,*,#53997,.T.); -#54287 = ORIENTED_EDGE('',*,*,#54288,.T.); -#54288 = EDGE_CURVE('',#53998,#54242,#54289,.T.); -#54289 = SURFACE_CURVE('',#54290,(#54296,#54325),.PCURVE_S1.); -#54290 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54291,#54292,#54293,#54294, - #54295),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#56667 = CARTESIAN_POINT('',(3.926990816987,3.31)); +#56668 = CARTESIAN_POINT('',(3.926990816987,4.7)); +#56669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56670 = PCURVE('',#40307,#56671); +#56671 = DEFINITIONAL_REPRESENTATION('',(#56672),#56676); +#56672 = LINE('',#56673,#56674); +#56673 = CARTESIAN_POINT('',(0.E+000,3.31)); +#56674 = VECTOR('',#56675,1.); +#56675 = DIRECTION('',(0.E+000,1.)); +#56676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56677 = ORIENTED_EDGE('',*,*,#40319,.F.); +#56678 = ORIENTED_EDGE('',*,*,#56389,.T.); +#56679 = ORIENTED_EDGE('',*,*,#56680,.T.); +#56680 = EDGE_CURVE('',#56390,#56634,#56681,.T.); +#56681 = SURFACE_CURVE('',#56682,(#56688,#56717),.PCURVE_S1.); +#56682 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56683,#56684,#56685,#56686, + #56687),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#54291 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,0.941561175052) +#56683 = CARTESIAN_POINT('',(-3.75,-7.144660940673E-002,0.941561175052) ); -#54292 = CARTESIAN_POINT('',(-3.75,-8.810864667122E-002,0.947689187739) +#56684 = CARTESIAN_POINT('',(-3.75,-8.810864667122E-002,0.947689187739) ); -#54293 = CARTESIAN_POINT('',(-3.748473630876,-0.122395129262, +#56685 = CARTESIAN_POINT('',(-3.748473630876,-0.122395129262, 0.956933190905)); -#54294 = CARTESIAN_POINT('',(-3.743515634982,-0.15751474967,0.96)); -#54295 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); -#54296 = PCURVE('',#37944,#54297); -#54297 = DEFINITIONAL_REPRESENTATION('',(#54298),#54324); -#54298 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54299,#54300,#54301,#54302, - #54303,#54304,#54305,#54306,#54307,#54308,#54309,#54310,#54311, - #54312,#54313,#54314,#54315,#54316,#54317,#54318,#54319,#54320, - #54321,#54322,#54323),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56686 = CARTESIAN_POINT('',(-3.743515634982,-0.15751474967,0.96)); +#56687 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); +#56688 = PCURVE('',#40336,#56689); +#56689 = DEFINITIONAL_REPRESENTATION('',(#56690),#56716); +#56690 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56691,#56692,#56693,#56694, + #56695,#56696,#56697,#56698,#56699,#56700,#56701,#56702,#56703, + #56704,#56705,#56706,#56707,#56708,#56709,#56710,#56711,#56712, + #56713,#56714,#56715),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67470,40 +70459,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54299 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); -#54300 = CARTESIAN_POINT('',(3.144346710123,3.292118267114)); -#54301 = CARTESIAN_POINT('',(3.149869281661,3.293207558494)); -#54302 = CARTESIAN_POINT('',(3.158194869478,3.294766644731)); -#54303 = CARTESIAN_POINT('',(3.166560538919,3.296250707541)); -#54304 = CARTESIAN_POINT('',(3.174964655044,3.297659574328)); -#54305 = CARTESIAN_POINT('',(3.183405593628,3.298993072497)); -#54306 = CARTESIAN_POINT('',(3.191881743633,3.300251029452)); -#54307 = CARTESIAN_POINT('',(3.200391508188,3.301433272598)); -#54308 = CARTESIAN_POINT('',(3.208933306006,3.30253962934)); -#54309 = CARTESIAN_POINT('',(3.217505572673,3.303569927082)); -#54310 = CARTESIAN_POINT('',(3.226106762143,3.304523993229)); -#54311 = CARTESIAN_POINT('',(3.234735347606,3.305401655185)); -#54312 = CARTESIAN_POINT('',(3.243389824757,3.306202740355)); -#54313 = CARTESIAN_POINT('',(3.252068558935,3.306927297848)); -#54314 = CARTESIAN_POINT('',(3.260769915555,3.307575376773)); -#54315 = CARTESIAN_POINT('',(3.269492263358,3.308147026238)); -#54316 = CARTESIAN_POINT('',(3.278233975302,3.308642295352)); -#54317 = CARTESIAN_POINT('',(3.286993430111,3.309061233225)); -#54318 = CARTESIAN_POINT('',(3.295769013699,3.309403888964)); -#54319 = CARTESIAN_POINT('',(3.304559120502,3.309670311679)); -#54320 = CARTESIAN_POINT('',(3.313362155407,3.309860550478)); -#54321 = CARTESIAN_POINT('',(3.322176533423,3.30997465447)); -#54322 = CARTESIAN_POINT('',(3.328059303027,3.31)); -#54323 = CARTESIAN_POINT('',(3.331002055236,3.31)); -#54324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54325 = PCURVE('',#39981,#54326); -#54326 = DEFINITIONAL_REPRESENTATION('',(#54327),#54353); -#54327 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54328,#54329,#54330,#54331, - #54332,#54333,#54334,#54335,#54336,#54337,#54338,#54339,#54340, - #54341,#54342,#54343,#54344,#54345,#54346,#54347,#54348,#54349, - #54350,#54351,#54352),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56691 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); +#56692 = CARTESIAN_POINT('',(3.144346710123,3.292118267114)); +#56693 = CARTESIAN_POINT('',(3.149869281661,3.293207558494)); +#56694 = CARTESIAN_POINT('',(3.158194869478,3.294766644731)); +#56695 = CARTESIAN_POINT('',(3.166560538919,3.296250707541)); +#56696 = CARTESIAN_POINT('',(3.174964655044,3.297659574328)); +#56697 = CARTESIAN_POINT('',(3.183405593628,3.298993072497)); +#56698 = CARTESIAN_POINT('',(3.191881743633,3.300251029452)); +#56699 = CARTESIAN_POINT('',(3.200391508188,3.301433272598)); +#56700 = CARTESIAN_POINT('',(3.208933306006,3.30253962934)); +#56701 = CARTESIAN_POINT('',(3.217505572673,3.303569927082)); +#56702 = CARTESIAN_POINT('',(3.226106762143,3.304523993229)); +#56703 = CARTESIAN_POINT('',(3.234735347606,3.305401655185)); +#56704 = CARTESIAN_POINT('',(3.243389824757,3.306202740355)); +#56705 = CARTESIAN_POINT('',(3.252068558935,3.306927297848)); +#56706 = CARTESIAN_POINT('',(3.260769915555,3.307575376773)); +#56707 = CARTESIAN_POINT('',(3.269492263358,3.308147026238)); +#56708 = CARTESIAN_POINT('',(3.278233975302,3.308642295352)); +#56709 = CARTESIAN_POINT('',(3.286993430111,3.309061233225)); +#56710 = CARTESIAN_POINT('',(3.295769013699,3.309403888964)); +#56711 = CARTESIAN_POINT('',(3.304559120502,3.309670311679)); +#56712 = CARTESIAN_POINT('',(3.313362155407,3.309860550478)); +#56713 = CARTESIAN_POINT('',(3.322176533423,3.30997465447)); +#56714 = CARTESIAN_POINT('',(3.328059303027,3.31)); +#56715 = CARTESIAN_POINT('',(3.331002055236,3.31)); +#56716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56717 = PCURVE('',#42373,#56718); +#56718 = DEFINITIONAL_REPRESENTATION('',(#56719),#56745); +#56719 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56720,#56721,#56722,#56723, + #56724,#56725,#56726,#56727,#56728,#56729,#56730,#56731,#56732, + #56733,#56734,#56735,#56736,#56737,#56738,#56739,#56740,#56741, + #56742,#56743,#56744),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67511,99 +70500,99 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54328 = CARTESIAN_POINT('',(1.218367924887,1.6262878957E-002)); -#54329 = CARTESIAN_POINT('',(1.223747678895,1.6262878957E-002)); -#54330 = CARTESIAN_POINT('',(1.234503439472,1.627549357786E-002)); -#54331 = CARTESIAN_POINT('',(1.250625967263,1.633268636856E-002)); -#54332 = CARTESIAN_POINT('',(1.266737523668,1.64285770155E-002)); -#54333 = CARTESIAN_POINT('',(1.282838206797,1.656359251552E-002)); -#54334 = CARTESIAN_POINT('',(1.298928091379,1.673815986544E-002)); -#54335 = CARTESIAN_POINT('',(1.315007228584,1.695270606209E-002)); -#54336 = CARTESIAN_POINT('',(1.331075651332,1.720765810232E-002)); -#54337 = CARTESIAN_POINT('',(1.347133378193,1.750344298295E-002)); -#54338 = CARTESIAN_POINT('',(1.3631804176,1.78404877008E-002)); -#54339 = CARTESIAN_POINT('',(1.379216772338,1.821921925273E-002)); -#54340 = CARTESIAN_POINT('',(1.395242442678,1.864006463555E-002)); -#54341 = CARTESIAN_POINT('',(1.411257434705,1.910345084609E-002)); -#54342 = CARTESIAN_POINT('',(1.42726171941,1.96094461715E-002)); -#54343 = CARTESIAN_POINT('',(1.44325522743,2.015811889892E-002)); -#54344 = CARTESIAN_POINT('',(1.45923785757,2.074953731547E-002)); -#54345 = CARTESIAN_POINT('',(1.475209480172,2.138376970831E-002)); -#54346 = CARTESIAN_POINT('',(1.491169941901,2.206088436457E-002)); -#54347 = CARTESIAN_POINT('',(1.507119070203,2.278094957138E-002)); -#54348 = CARTESIAN_POINT('',(1.523056677848,2.354403361588E-002)); -#54349 = CARTESIAN_POINT('',(1.538982567586,2.435020478523E-002)); -#54350 = CARTESIAN_POINT('',(1.55489653639,2.519953136654E-002)); -#54351 = CARTESIAN_POINT('',(1.565497766316,2.579456488682E-002)); -#54352 = CARTESIAN_POINT('',(1.570796326795,2.6099296978E-002)); -#54353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54354 = ADVANCED_FACE('',(#54355),#39931,.F.); -#54355 = FACE_BOUND('',#54356,.F.); -#54356 = EDGE_LOOP('',(#54357,#54358,#54385,#54454,#54474,#54475)); -#54357 = ORIENTED_EDGE('',*,*,#39908,.F.); -#54358 = ORIENTED_EDGE('',*,*,#54359,.T.); -#54359 = EDGE_CURVE('',#39909,#54360,#54362,.T.); -#54360 = VERTEX_POINT('',#54361); -#54361 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) - ); -#54362 = SURFACE_CURVE('',#54363,(#54368,#54374),.PCURVE_S1.); -#54363 = CIRCLE('',#54364,0.3); -#54364 = AXIS2_PLACEMENT_3D('',#54365,#54366,#54367); -#54365 = CARTESIAN_POINT('',(-3.45,-0.175,-0.26)); -#54366 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#54367 = DIRECTION('',(0.E+000,1.,0.E+000)); -#54368 = PCURVE('',#39931,#54369); -#54369 = DEFINITIONAL_REPRESENTATION('',(#54370),#54373); -#54370 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54371,#54372),.UNSPECIFIED., +#56720 = CARTESIAN_POINT('',(1.218367924887,1.6262878957E-002)); +#56721 = CARTESIAN_POINT('',(1.223747678895,1.6262878957E-002)); +#56722 = CARTESIAN_POINT('',(1.234503439472,1.627549357786E-002)); +#56723 = CARTESIAN_POINT('',(1.250625967263,1.633268636856E-002)); +#56724 = CARTESIAN_POINT('',(1.266737523668,1.64285770155E-002)); +#56725 = CARTESIAN_POINT('',(1.282838206797,1.656359251552E-002)); +#56726 = CARTESIAN_POINT('',(1.298928091379,1.673815986544E-002)); +#56727 = CARTESIAN_POINT('',(1.315007228584,1.695270606209E-002)); +#56728 = CARTESIAN_POINT('',(1.331075651332,1.720765810232E-002)); +#56729 = CARTESIAN_POINT('',(1.347133378193,1.750344298295E-002)); +#56730 = CARTESIAN_POINT('',(1.3631804176,1.78404877008E-002)); +#56731 = CARTESIAN_POINT('',(1.379216772338,1.821921925273E-002)); +#56732 = CARTESIAN_POINT('',(1.395242442678,1.864006463555E-002)); +#56733 = CARTESIAN_POINT('',(1.411257434705,1.910345084609E-002)); +#56734 = CARTESIAN_POINT('',(1.42726171941,1.96094461715E-002)); +#56735 = CARTESIAN_POINT('',(1.44325522743,2.015811889892E-002)); +#56736 = CARTESIAN_POINT('',(1.45923785757,2.074953731547E-002)); +#56737 = CARTESIAN_POINT('',(1.475209480172,2.138376970831E-002)); +#56738 = CARTESIAN_POINT('',(1.491169941901,2.206088436457E-002)); +#56739 = CARTESIAN_POINT('',(1.507119070203,2.278094957138E-002)); +#56740 = CARTESIAN_POINT('',(1.523056677848,2.354403361588E-002)); +#56741 = CARTESIAN_POINT('',(1.538982567586,2.435020478523E-002)); +#56742 = CARTESIAN_POINT('',(1.55489653639,2.519953136654E-002)); +#56743 = CARTESIAN_POINT('',(1.565497766316,2.579456488682E-002)); +#56744 = CARTESIAN_POINT('',(1.570796326795,2.6099296978E-002)); +#56745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56746 = ADVANCED_FACE('',(#56747),#42323,.F.); +#56747 = FACE_BOUND('',#56748,.F.); +#56748 = EDGE_LOOP('',(#56749,#56750,#56777,#56846,#56866,#56867)); +#56749 = ORIENTED_EDGE('',*,*,#42300,.F.); +#56750 = ORIENTED_EDGE('',*,*,#56751,.T.); +#56751 = EDGE_CURVE('',#42301,#56752,#56754,.T.); +#56752 = VERTEX_POINT('',#56753); +#56753 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) + ); +#56754 = SURFACE_CURVE('',#56755,(#56760,#56766),.PCURVE_S1.); +#56755 = CIRCLE('',#56756,0.3); +#56756 = AXIS2_PLACEMENT_3D('',#56757,#56758,#56759); +#56757 = CARTESIAN_POINT('',(-3.45,-0.175,-0.26)); +#56758 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#56759 = DIRECTION('',(0.E+000,1.,0.E+000)); +#56760 = PCURVE('',#42323,#56761); +#56761 = DEFINITIONAL_REPRESENTATION('',(#56762),#56765); +#56762 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56763,#56764),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#54371 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); -#54372 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); -#54373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56763 = CARTESIAN_POINT('',(0.E+000,1.072039397384)); +#56764 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); +#56765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54374 = PCURVE('',#37683,#54375); -#54375 = DEFINITIONAL_REPRESENTATION('',(#54376),#54384); -#54376 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54377,#54378,#54379,#54380 - ,#54381,#54382,#54383),.UNSPECIFIED.,.T.,.F.) +#56766 = PCURVE('',#40075,#56767); +#56767 = DEFINITIONAL_REPRESENTATION('',(#56768),#56776); +#56768 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56769,#56770,#56771,#56772 + ,#56773,#56774,#56775),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#54377 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#54378 = CARTESIAN_POINT('',(0.196446609407,1.570384757729)); -#54379 = CARTESIAN_POINT('',(-0.253553390593,1.830192378865)); -#54380 = CARTESIAN_POINT('',(-0.703553390593,2.09)); -#54381 = CARTESIAN_POINT('',(-0.253553390593,2.349807621135)); -#54382 = CARTESIAN_POINT('',(0.196446609407,2.609615242271)); -#54383 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#54384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54385 = ORIENTED_EDGE('',*,*,#54386,.T.); -#54386 = EDGE_CURVE('',#54360,#54387,#54389,.T.); -#54387 = VERTEX_POINT('',#54388); -#54388 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); -#54389 = SURFACE_CURVE('',#54390,(#54396,#54425),.PCURVE_S1.); -#54390 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54391,#54392,#54393,#54394, - #54395),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#56769 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#56770 = CARTESIAN_POINT('',(0.196446609407,1.570384757729)); +#56771 = CARTESIAN_POINT('',(-0.253553390593,1.830192378865)); +#56772 = CARTESIAN_POINT('',(-0.703553390593,2.09)); +#56773 = CARTESIAN_POINT('',(-0.253553390593,2.349807621135)); +#56774 = CARTESIAN_POINT('',(0.196446609407,2.609615242271)); +#56775 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#56776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56777 = ORIENTED_EDGE('',*,*,#56778,.T.); +#56778 = EDGE_CURVE('',#56752,#56779,#56781,.T.); +#56779 = VERTEX_POINT('',#56780); +#56780 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); +#56781 = SURFACE_CURVE('',#56782,(#56788,#56817),.PCURVE_S1.); +#56782 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56783,#56784,#56785,#56786, + #56787),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#54391 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) +#56783 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) ); -#54392 = CARTESIAN_POINT('',(-3.45,-8.90562117489E-002,-0.548037685989) +#56784 = CARTESIAN_POINT('',(-3.45,-8.90562117489E-002,-0.548037685989) ); -#54393 = CARTESIAN_POINT('',(-3.446265168051,-0.124400657563, +#56785 = CARTESIAN_POINT('',(-3.446265168051,-0.124400657563, -0.55728045336)); -#54394 = CARTESIAN_POINT('',(-3.435043086846,-0.158523789004,-0.56)); -#54395 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); -#54396 = PCURVE('',#39931,#54397); -#54397 = DEFINITIONAL_REPRESENTATION('',(#54398),#54424); -#54398 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54399,#54400,#54401,#54402, - #54403,#54404,#54405,#54406,#54407,#54408,#54409,#54410,#54411, - #54412,#54413,#54414,#54415,#54416,#54417,#54418,#54419,#54420, - #54421,#54422,#54423),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56786 = CARTESIAN_POINT('',(-3.435043086846,-0.158523789004,-0.56)); +#56787 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); +#56788 = PCURVE('',#42323,#56789); +#56789 = DEFINITIONAL_REPRESENTATION('',(#56790),#56816); +#56790 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56791,#56792,#56793,#56794, + #56795,#56796,#56797,#56798,#56799,#56800,#56801,#56802,#56803, + #56804,#56805,#56806,#56807,#56808,#56809,#56810,#56811,#56812, + #56813,#56814,#56815),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67611,40 +70600,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54399 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); -#54400 = CARTESIAN_POINT('',(1.224053612371,1.072039397384)); -#54401 = CARTESIAN_POINT('',(1.235392999785,1.072008531004)); -#54402 = CARTESIAN_POINT('',(1.252306796147,1.071869612477)); -#54403 = CARTESIAN_POINT('',(1.269126053209,1.071638055174)); -#54404 = CARTESIAN_POINT('',(1.285851279991,1.071313839278)); -#54405 = CARTESIAN_POINT('',(1.302482835566,1.070896944969)); -#54406 = CARTESIAN_POINT('',(1.319020911304,1.07038735243)); -#54407 = CARTESIAN_POINT('',(1.335465541405,1.069785041843)); -#54408 = CARTESIAN_POINT('',(1.351816606196,1.069089993389)); -#54409 = CARTESIAN_POINT('',(1.368073837607,1.06830218725)); -#54410 = CARTESIAN_POINT('',(1.384236824553,1.067421603608)); -#54411 = CARTESIAN_POINT('',(1.400305017758,1.066448222644)); -#54412 = CARTESIAN_POINT('',(1.416277738007,1.065382024541)); -#54413 = CARTESIAN_POINT('',(1.432155585651,1.064222940312)); -#54414 = CARTESIAN_POINT('',(1.447939005713,1.062970900968)); -#54415 = CARTESIAN_POINT('',(1.463628293431,1.061625837524)); -#54416 = CARTESIAN_POINT('',(1.47922359688,1.060187680991)); -#54417 = CARTESIAN_POINT('',(1.494724920752,1.058656362383)); -#54418 = CARTESIAN_POINT('',(1.510132129763,1.057031812713)); -#54419 = CARTESIAN_POINT('',(1.525444953673,1.055313962993)); -#54420 = CARTESIAN_POINT('',(1.540662987321,1.053502744236)); -#54421 = CARTESIAN_POINT('',(1.555785710031,1.051598087456)); -#54422 = CARTESIAN_POINT('',(1.565803525627,1.050265978262)); -#54423 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); -#54424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54425 = PCURVE('',#53260,#54426); -#54426 = DEFINITIONAL_REPRESENTATION('',(#54427),#54453); -#54427 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54428,#54429,#54430,#54431, - #54432,#54433,#54434,#54435,#54436,#54437,#54438,#54439,#54440, - #54441,#54442,#54443,#54444,#54445,#54446,#54447,#54448,#54449, - #54450,#54451,#54452),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#56791 = CARTESIAN_POINT('',(1.218367924887,1.072039397384)); +#56792 = CARTESIAN_POINT('',(1.224053612371,1.072039397384)); +#56793 = CARTESIAN_POINT('',(1.235392999785,1.072008531004)); +#56794 = CARTESIAN_POINT('',(1.252306796147,1.071869612477)); +#56795 = CARTESIAN_POINT('',(1.269126053209,1.071638055174)); +#56796 = CARTESIAN_POINT('',(1.285851279991,1.071313839278)); +#56797 = CARTESIAN_POINT('',(1.302482835566,1.070896944969)); +#56798 = CARTESIAN_POINT('',(1.319020911304,1.07038735243)); +#56799 = CARTESIAN_POINT('',(1.335465541405,1.069785041843)); +#56800 = CARTESIAN_POINT('',(1.351816606196,1.069089993389)); +#56801 = CARTESIAN_POINT('',(1.368073837607,1.06830218725)); +#56802 = CARTESIAN_POINT('',(1.384236824553,1.067421603608)); +#56803 = CARTESIAN_POINT('',(1.400305017758,1.066448222644)); +#56804 = CARTESIAN_POINT('',(1.416277738007,1.065382024541)); +#56805 = CARTESIAN_POINT('',(1.432155585651,1.064222940312)); +#56806 = CARTESIAN_POINT('',(1.447939005713,1.062970900968)); +#56807 = CARTESIAN_POINT('',(1.463628293431,1.061625837524)); +#56808 = CARTESIAN_POINT('',(1.47922359688,1.060187680991)); +#56809 = CARTESIAN_POINT('',(1.494724920752,1.058656362383)); +#56810 = CARTESIAN_POINT('',(1.510132129763,1.057031812713)); +#56811 = CARTESIAN_POINT('',(1.525444953673,1.055313962993)); +#56812 = CARTESIAN_POINT('',(1.540662987321,1.053502744236)); +#56813 = CARTESIAN_POINT('',(1.555785710031,1.051598087456)); +#56814 = CARTESIAN_POINT('',(1.565803525627,1.050265978262)); +#56815 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); +#56816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56817 = PCURVE('',#55652,#56818); +#56818 = DEFINITIONAL_REPRESENTATION('',(#56819),#56845); +#56819 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#56820,#56821,#56822,#56823, + #56824,#56825,#56826,#56827,#56828,#56829,#56830,#56831,#56832, + #56833,#56834,#56835,#56836,#56837,#56838,#56839,#56840,#56841, + #56842,#56843,#56844),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67652,264 +70641,264 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54428 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); -#54429 = CARTESIAN_POINT('',(3.147996144438,1.807850051227)); -#54430 = CARTESIAN_POINT('',(3.160807270035,1.806703167044)); -#54431 = CARTESIAN_POINT('',(3.180036901209,1.805073819332)); -#54432 = CARTESIAN_POINT('',(3.199279988537,1.803534438963)); -#54433 = CARTESIAN_POINT('',(3.218537037341,1.802084014719)); -#54434 = CARTESIAN_POINT('',(3.23780855861,1.800721535379)); -#54435 = CARTESIAN_POINT('',(3.257095076257,1.799445989726)); -#54436 = CARTESIAN_POINT('',(3.276397136057,1.798256366541)); -#54437 = CARTESIAN_POINT('',(3.295715314083,1.797151654604)); -#54438 = CARTESIAN_POINT('',(3.31505022517,1.796130842696)); -#54439 = CARTESIAN_POINT('',(3.334402531361,1.795192919599)); -#54440 = CARTESIAN_POINT('',(3.353772949899,1.794336874094)); -#54441 = CARTESIAN_POINT('',(3.373162262436,1.793561694961)); -#54442 = CARTESIAN_POINT('',(3.392572907345,1.79286616042)); -#54443 = CARTESIAN_POINT('',(3.412007384851,1.792249048688)); -#54444 = CARTESIAN_POINT('',(3.431468259546,1.791709137985)); -#54445 = CARTESIAN_POINT('',(3.450958161705,1.791245206528)); -#54446 = CARTESIAN_POINT('',(3.470479788624,1.790856032536)); -#54447 = CARTESIAN_POINT('',(3.490035905876,1.790540394229)); -#54448 = CARTESIAN_POINT('',(3.509629347551,1.790297069823)); -#54449 = CARTESIAN_POINT('',(3.529263019249,1.790124837538)); -#54450 = CARTESIAN_POINT('',(3.548939889573,1.790022475592)); -#54451 = CARTESIAN_POINT('',(3.562088645338,1.79)); -#54452 = CARTESIAN_POINT('',(3.568671239982,1.79)); -#54453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54454 = ORIENTED_EDGE('',*,*,#54455,.T.); -#54455 = EDGE_CURVE('',#54387,#54145,#54456,.T.); -#54456 = SURFACE_CURVE('',#54457,(#54461,#54467),.PCURVE_S1.); -#54457 = LINE('',#54458,#54459); -#54458 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); -#54459 = VECTOR('',#54460,1.); -#54460 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#54461 = PCURVE('',#39931,#54462); -#54462 = DEFINITIONAL_REPRESENTATION('',(#54463),#54466); -#54463 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54464,#54465),.UNSPECIFIED., +#56820 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); +#56821 = CARTESIAN_POINT('',(3.147996144438,1.807850051227)); +#56822 = CARTESIAN_POINT('',(3.160807270035,1.806703167044)); +#56823 = CARTESIAN_POINT('',(3.180036901209,1.805073819332)); +#56824 = CARTESIAN_POINT('',(3.199279988537,1.803534438963)); +#56825 = CARTESIAN_POINT('',(3.218537037341,1.802084014719)); +#56826 = CARTESIAN_POINT('',(3.23780855861,1.800721535379)); +#56827 = CARTESIAN_POINT('',(3.257095076257,1.799445989726)); +#56828 = CARTESIAN_POINT('',(3.276397136057,1.798256366541)); +#56829 = CARTESIAN_POINT('',(3.295715314083,1.797151654604)); +#56830 = CARTESIAN_POINT('',(3.31505022517,1.796130842696)); +#56831 = CARTESIAN_POINT('',(3.334402531361,1.795192919599)); +#56832 = CARTESIAN_POINT('',(3.353772949899,1.794336874094)); +#56833 = CARTESIAN_POINT('',(3.373162262436,1.793561694961)); +#56834 = CARTESIAN_POINT('',(3.392572907345,1.79286616042)); +#56835 = CARTESIAN_POINT('',(3.412007384851,1.792249048688)); +#56836 = CARTESIAN_POINT('',(3.431468259546,1.791709137985)); +#56837 = CARTESIAN_POINT('',(3.450958161705,1.791245206528)); +#56838 = CARTESIAN_POINT('',(3.470479788624,1.790856032536)); +#56839 = CARTESIAN_POINT('',(3.490035905876,1.790540394229)); +#56840 = CARTESIAN_POINT('',(3.509629347551,1.790297069823)); +#56841 = CARTESIAN_POINT('',(3.529263019249,1.790124837538)); +#56842 = CARTESIAN_POINT('',(3.548939889573,1.790022475592)); +#56843 = CARTESIAN_POINT('',(3.562088645338,1.79)); +#56844 = CARTESIAN_POINT('',(3.568671239982,1.79)); +#56845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56846 = ORIENTED_EDGE('',*,*,#56847,.T.); +#56847 = EDGE_CURVE('',#56779,#56537,#56848,.T.); +#56848 = SURFACE_CURVE('',#56849,(#56853,#56859),.PCURVE_S1.); +#56849 = LINE('',#56850,#56851); +#56850 = CARTESIAN_POINT('',(-3.427544930281,-0.175,-0.56)); +#56851 = VECTOR('',#56852,1.); +#56852 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#56853 = PCURVE('',#42323,#56854); +#56854 = DEFINITIONAL_REPRESENTATION('',(#56855),#56858); +#56855 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56856,#56857),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.312618651698),.PIECEWISE_BEZIER_KNOTS.); -#54464 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); -#54465 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); -#54466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54467 = PCURVE('',#42672,#54468); -#54468 = DEFINITIONAL_REPRESENTATION('',(#54469),#54473); -#54469 = LINE('',#54470,#54471); -#54470 = CARTESIAN_POINT('',(0.322455069719,-1.05)); -#54471 = VECTOR('',#54472,1.); -#54472 = DIRECTION('',(-1.,0.E+000)); -#54473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54474 = ORIENTED_EDGE('',*,*,#54171,.T.); -#54475 = ORIENTED_EDGE('',*,*,#54045,.T.); -#54476 = ADVANCED_FACE('',(#54477),#37683,.T.); -#54477 = FACE_BOUND('',#54478,.F.); -#54478 = EDGE_LOOP('',(#54479,#54480,#54507,#54527,#54528,#54529,#54549, - #54550,#54551,#54571,#54572,#54592)); -#54479 = ORIENTED_EDGE('',*,*,#39992,.T.); -#54480 = ORIENTED_EDGE('',*,*,#54481,.F.); -#54481 = EDGE_CURVE('',#54482,#39966,#54484,.T.); -#54482 = VERTEX_POINT('',#54483); -#54483 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,0.941561175052) - ); -#54484 = SURFACE_CURVE('',#54485,(#54490,#54501),.PCURVE_S1.); -#54485 = CIRCLE('',#54486,0.3); -#54486 = AXIS2_PLACEMENT_3D('',#54487,#54488,#54489); -#54487 = CARTESIAN_POINT('',(-3.45,-0.175,0.66)); -#54488 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#54489 = DIRECTION('',(0.E+000,0.345177968644,0.938537250173)); -#54490 = PCURVE('',#37683,#54491); -#54491 = DEFINITIONAL_REPRESENTATION('',(#54492),#54500); -#54492 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#54493,#54494,#54495,#54496 - ,#54497,#54498,#54499),.UNSPECIFIED.,.F.,.F.) +#56856 = CARTESIAN_POINT('',(1.570796326795,1.049584327665)); +#56857 = CARTESIAN_POINT('',(1.570796326795,1.362202979363)); +#56858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56859 = PCURVE('',#45064,#56860); +#56860 = DEFINITIONAL_REPRESENTATION('',(#56861),#56865); +#56861 = LINE('',#56862,#56863); +#56862 = CARTESIAN_POINT('',(0.322455069719,-1.05)); +#56863 = VECTOR('',#56864,1.); +#56864 = DIRECTION('',(-1.,0.E+000)); +#56865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56866 = ORIENTED_EDGE('',*,*,#56563,.T.); +#56867 = ORIENTED_EDGE('',*,*,#56437,.T.); +#56868 = ADVANCED_FACE('',(#56869),#40075,.T.); +#56869 = FACE_BOUND('',#56870,.F.); +#56870 = EDGE_LOOP('',(#56871,#56872,#56899,#56919,#56920,#56921,#56941, + #56942,#56943,#56963,#56964,#56984)); +#56871 = ORIENTED_EDGE('',*,*,#42384,.T.); +#56872 = ORIENTED_EDGE('',*,*,#56873,.F.); +#56873 = EDGE_CURVE('',#56874,#42358,#56876,.T.); +#56874 = VERTEX_POINT('',#56875); +#56875 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,0.941561175052) + ); +#56876 = SURFACE_CURVE('',#56877,(#56882,#56893),.PCURVE_S1.); +#56877 = CIRCLE('',#56878,0.3); +#56878 = AXIS2_PLACEMENT_3D('',#56879,#56880,#56881); +#56879 = CARTESIAN_POINT('',(-3.45,-0.175,0.66)); +#56880 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#56881 = DIRECTION('',(0.E+000,0.345177968644,0.938537250173)); +#56882 = PCURVE('',#40075,#56883); +#56883 = DEFINITIONAL_REPRESENTATION('',(#56884),#56892); +#56884 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56885,#56886,#56887,#56888 + ,#56889,#56890,#56891),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#54493 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); -#54494 = CARTESIAN_POINT('',(0.487678260629,3.112201441248)); -#54495 = CARTESIAN_POINT('',(8.850904442449E-002,2.779539545572)); -#54496 = CARTESIAN_POINT('',(-0.31066017178,2.446877649896)); -#54497 = CARTESIAN_POINT('',(-0.399169216204,2.958899279376)); -#54498 = CARTESIAN_POINT('',(-0.487678260629,3.470920908856)); -#54499 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); -#54500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54501 = PCURVE('',#39981,#54502); -#54502 = DEFINITIONAL_REPRESENTATION('',(#54503),#54506); -#54503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54504,#54505),.UNSPECIFIED., +#56885 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); +#56886 = CARTESIAN_POINT('',(0.487678260629,3.112201441248)); +#56887 = CARTESIAN_POINT('',(8.850904442449E-002,2.779539545572)); +#56888 = CARTESIAN_POINT('',(-0.31066017178,2.446877649896)); +#56889 = CARTESIAN_POINT('',(-0.399169216204,2.958899279376)); +#56890 = CARTESIAN_POINT('',(-0.487678260629,3.470920908856)); +#56891 = CARTESIAN_POINT('',(-1.039446306805E-014,3.291561175052)); +#56892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56893 = PCURVE('',#42373,#56894); +#56894 = DEFINITIONAL_REPRESENTATION('',(#56895),#56898); +#56895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56896,#56897),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#54504 = CARTESIAN_POINT('',(1.218367924887,0.316262878957)); -#54505 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); -#54506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54507 = ORIENTED_EDGE('',*,*,#54508,.F.); -#54508 = EDGE_CURVE('',#37668,#54482,#54509,.T.); -#54509 = SURFACE_CURVE('',#54510,(#54514,#54521),.PCURVE_S1.); -#54510 = LINE('',#54511,#54512); -#54511 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); -#54512 = VECTOR('',#54513,1.); -#54513 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#54514 = PCURVE('',#37683,#54515); -#54515 = DEFINITIONAL_REPRESENTATION('',(#54516),#54520); -#54516 = LINE('',#54517,#54518); -#54517 = CARTESIAN_POINT('',(0.E+000,4.7)); -#54518 = VECTOR('',#54519,1.); -#54519 = DIRECTION('',(0.E+000,-1.)); -#54520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54521 = PCURVE('',#37716,#54522); -#54522 = DEFINITIONAL_REPRESENTATION('',(#54523),#54526); -#54523 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54524,#54525),.UNSPECIFIED., +#56896 = CARTESIAN_POINT('',(1.218367924887,0.316262878957)); +#56897 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); +#56898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56899 = ORIENTED_EDGE('',*,*,#56900,.F.); +#56900 = EDGE_CURVE('',#40060,#56874,#56901,.T.); +#56901 = SURFACE_CURVE('',#56902,(#56906,#56913),.PCURVE_S1.); +#56902 = LINE('',#56903,#56904); +#56903 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,2.35)); +#56904 = VECTOR('',#56905,1.); +#56905 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#56906 = PCURVE('',#40075,#56907); +#56907 = DEFINITIONAL_REPRESENTATION('',(#56908),#56912); +#56908 = LINE('',#56909,#56910); +#56909 = CARTESIAN_POINT('',(0.E+000,4.7)); +#56910 = VECTOR('',#56911,1.); +#56911 = DIRECTION('',(0.E+000,-1.)); +#56912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56913 = PCURVE('',#40108,#56914); +#56914 = DEFINITIONAL_REPRESENTATION('',(#56915),#56918); +#56915 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56916,#56917),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.408438824948),.PIECEWISE_BEZIER_KNOTS.); -#54524 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#54525 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); -#54526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54527 = ORIENTED_EDGE('',*,*,#37667,.T.); -#54528 = ORIENTED_EDGE('',*,*,#38943,.T.); -#54529 = ORIENTED_EDGE('',*,*,#54530,.T.); -#54530 = EDGE_CURVE('',#38916,#39547,#54531,.T.); -#54531 = SURFACE_CURVE('',#54532,(#54536,#54543),.PCURVE_S1.); -#54532 = LINE('',#54533,#54534); -#54533 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.354697035713)); -#54534 = VECTOR('',#54535,1.); -#54535 = DIRECTION('',(0.E+000,1.,0.E+000)); -#54536 = PCURVE('',#37683,#54537); -#54537 = DEFINITIONAL_REPRESENTATION('',(#54538),#54542); -#54538 = LINE('',#54539,#54540); -#54539 = CARTESIAN_POINT('',(9.644660940673E-002,4.704697035713)); -#54540 = VECTOR('',#54541,1.); -#54541 = DIRECTION('',(1.,0.E+000)); -#54542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54543 = PCURVE('',#38932,#54544); -#54544 = DEFINITIONAL_REPRESENTATION('',(#54545),#54548); -#54545 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54546,#54547),.UNSPECIFIED., +#56916 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#56917 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); +#56918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56919 = ORIENTED_EDGE('',*,*,#40059,.T.); +#56920 = ORIENTED_EDGE('',*,*,#41335,.T.); +#56921 = ORIENTED_EDGE('',*,*,#56922,.T.); +#56922 = EDGE_CURVE('',#41308,#41939,#56923,.T.); +#56923 = SURFACE_CURVE('',#56924,(#56928,#56935),.PCURVE_S1.); +#56924 = LINE('',#56925,#56926); +#56925 = CARTESIAN_POINT('',(-3.45,2.5E-002,2.354697035713)); +#56926 = VECTOR('',#56927,1.); +#56927 = DIRECTION('',(0.E+000,1.,0.E+000)); +#56928 = PCURVE('',#40075,#56929); +#56929 = DEFINITIONAL_REPRESENTATION('',(#56930),#56934); +#56930 = LINE('',#56931,#56932); +#56931 = CARTESIAN_POINT('',(9.644660940673E-002,4.704697035713)); +#56932 = VECTOR('',#56933,1.); +#56933 = DIRECTION('',(1.,0.E+000)); +#56934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56935 = PCURVE('',#41324,#56936); +#56936 = DEFINITIONAL_REPRESENTATION('',(#56937),#56940); +#56937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56938,#56939),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.6),.PIECEWISE_BEZIER_KNOTS.); -#54546 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#54547 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#54548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54549 = ORIENTED_EDGE('',*,*,#39546,.F.); -#54550 = ORIENTED_EDGE('',*,*,#38482,.T.); -#54551 = ORIENTED_EDGE('',*,*,#54552,.F.); -#54552 = EDGE_CURVE('',#53272,#38451,#54553,.T.); -#54553 = SURFACE_CURVE('',#54554,(#54558,#54565),.PCURVE_S1.); -#54554 = LINE('',#54555,#54556); -#54555 = CARTESIAN_POINT('',(-3.45,0.675,-2.35)); -#54556 = VECTOR('',#54557,1.); -#54557 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54558 = PCURVE('',#37683,#54559); -#54559 = DEFINITIONAL_REPRESENTATION('',(#54560),#54564); -#54560 = LINE('',#54561,#54562); -#54561 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); -#54562 = VECTOR('',#54563,1.); -#54563 = DIRECTION('',(0.E+000,1.)); -#54564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54565 = PCURVE('',#38471,#54566); -#54566 = DEFINITIONAL_REPRESENTATION('',(#54567),#54570); -#54567 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54568,#54569),.UNSPECIFIED., +#56938 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#56939 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#56940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56941 = ORIENTED_EDGE('',*,*,#41938,.F.); +#56942 = ORIENTED_EDGE('',*,*,#40874,.T.); +#56943 = ORIENTED_EDGE('',*,*,#56944,.F.); +#56944 = EDGE_CURVE('',#55664,#40843,#56945,.T.); +#56945 = SURFACE_CURVE('',#56946,(#56950,#56957),.PCURVE_S1.); +#56946 = LINE('',#56947,#56948); +#56947 = CARTESIAN_POINT('',(-3.45,0.675,-2.35)); +#56948 = VECTOR('',#56949,1.); +#56949 = DIRECTION('',(0.E+000,0.E+000,1.)); +#56950 = PCURVE('',#40075,#56951); +#56951 = DEFINITIONAL_REPRESENTATION('',(#56952),#56956); +#56952 = LINE('',#56953,#56954); +#56953 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); +#56954 = VECTOR('',#56955,1.); +#56955 = DIRECTION('',(0.E+000,1.)); +#56956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56957 = PCURVE('',#40863,#56958); +#56958 = DEFINITIONAL_REPRESENTATION('',(#56959),#56962); +#56959 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56960,#56961),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#54568 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#54569 = CARTESIAN_POINT('',(3.14159265359,4.7)); -#54570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54571 = ORIENTED_EDGE('',*,*,#53271,.F.); -#54572 = ORIENTED_EDGE('',*,*,#54573,.F.); -#54573 = EDGE_CURVE('',#54360,#53240,#54574,.T.); -#54574 = SURFACE_CURVE('',#54575,(#54579,#54586),.PCURVE_S1.); -#54575 = LINE('',#54576,#54577); -#54576 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) - ); -#54577 = VECTOR('',#54578,1.); -#54578 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#54579 = PCURVE('',#37683,#54580); -#54580 = DEFINITIONAL_REPRESENTATION('',(#54581),#54585); -#54581 = LINE('',#54582,#54583); -#54582 = CARTESIAN_POINT('',(0.E+000,1.808438824948)); -#54583 = VECTOR('',#54584,1.); -#54584 = DIRECTION('',(0.E+000,-1.)); -#54585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56960 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#56961 = CARTESIAN_POINT('',(3.14159265359,4.7)); +#56962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#56963 = ORIENTED_EDGE('',*,*,#55663,.F.); +#56964 = ORIENTED_EDGE('',*,*,#56965,.F.); +#56965 = EDGE_CURVE('',#56752,#55632,#56966,.T.); +#56966 = SURFACE_CURVE('',#56967,(#56971,#56978),.PCURVE_S1.); +#56967 = LINE('',#56968,#56969); +#56968 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,-0.541561175052) + ); +#56969 = VECTOR('',#56970,1.); +#56970 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#56971 = PCURVE('',#40075,#56972); +#56972 = DEFINITIONAL_REPRESENTATION('',(#56973),#56977); +#56973 = LINE('',#56974,#56975); +#56974 = CARTESIAN_POINT('',(0.E+000,1.808438824948)); +#56975 = VECTOR('',#56976,1.); +#56976 = DIRECTION('',(0.E+000,-1.)); +#56977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54586 = PCURVE('',#53260,#54587); -#54587 = DEFINITIONAL_REPRESENTATION('',(#54588),#54591); -#54588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54589,#54590),.UNSPECIFIED., +#56978 = PCURVE('',#55652,#56979); +#56979 = DEFINITIONAL_REPRESENTATION('',(#56980),#56983); +#56980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56981,#56982),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.808438824948),.PIECEWISE_BEZIER_KNOTS.); -#54589 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); -#54590 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#54591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#56981 = CARTESIAN_POINT('',(3.14159265359,1.808438824948)); +#56982 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#56983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54592 = ORIENTED_EDGE('',*,*,#54359,.F.); -#54593 = ADVANCED_FACE('',(#54594),#39981,.F.); -#54594 = FACE_BOUND('',#54595,.F.); -#54595 = EDGE_LOOP('',(#54596,#54597,#54598,#54599,#54621,#54688)); -#54596 = ORIENTED_EDGE('',*,*,#39965,.F.); -#54597 = ORIENTED_EDGE('',*,*,#54019,.T.); -#54598 = ORIENTED_EDGE('',*,*,#54288,.T.); -#54599 = ORIENTED_EDGE('',*,*,#54600,.T.); -#54600 = EDGE_CURVE('',#54242,#54601,#54603,.T.); -#54601 = VERTEX_POINT('',#54602); -#54602 = CARTESIAN_POINT('',(-3.427544930281,-0.175,0.96)); -#54603 = SURFACE_CURVE('',#54604,(#54608,#54614),.PCURVE_S1.); -#54604 = LINE('',#54605,#54606); -#54605 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); -#54606 = VECTOR('',#54607,1.); -#54607 = DIRECTION('',(1.,0.E+000,0.E+000)); -#54608 = PCURVE('',#39981,#54609); -#54609 = DEFINITIONAL_REPRESENTATION('',(#54610),#54613); -#54610 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54611,#54612),.UNSPECIFIED., +#56984 = ORIENTED_EDGE('',*,*,#56751,.F.); +#56985 = ADVANCED_FACE('',(#56986),#42373,.F.); +#56986 = FACE_BOUND('',#56987,.F.); +#56987 = EDGE_LOOP('',(#56988,#56989,#56990,#56991,#57013,#57080)); +#56988 = ORIENTED_EDGE('',*,*,#42357,.F.); +#56989 = ORIENTED_EDGE('',*,*,#56411,.T.); +#56990 = ORIENTED_EDGE('',*,*,#56680,.T.); +#56991 = ORIENTED_EDGE('',*,*,#56992,.T.); +#56992 = EDGE_CURVE('',#56634,#56993,#56995,.T.); +#56993 = VERTEX_POINT('',#56994); +#56994 = CARTESIAN_POINT('',(-3.427544930281,-0.175,0.96)); +#56995 = SURFACE_CURVE('',#56996,(#57000,#57006),.PCURVE_S1.); +#56996 = LINE('',#56997,#56998); +#56997 = CARTESIAN_POINT('',(-3.740163581979,-0.175,0.96)); +#56998 = VECTOR('',#56999,1.); +#56999 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57000 = PCURVE('',#42373,#57001); +#57001 = DEFINITIONAL_REPRESENTATION('',(#57002),#57005); +#57002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57003,#57004),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.312618651698),.PIECEWISE_BEZIER_KNOTS.); -#54611 = CARTESIAN_POINT('',(1.570796326795,2.6099296978E-002)); -#54612 = CARTESIAN_POINT('',(1.570796326795,0.338717948676)); -#54613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57003 = CARTESIAN_POINT('',(1.570796326795,2.6099296978E-002)); +#57004 = CARTESIAN_POINT('',(1.570796326795,0.338717948676)); +#57005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54614 = PCURVE('',#42320,#54615); -#54615 = DEFINITIONAL_REPRESENTATION('',(#54616),#54620); -#54616 = LINE('',#54617,#54618); -#54617 = CARTESIAN_POINT('',(1.340163581979,-1.05)); -#54618 = VECTOR('',#54619,1.); -#54619 = DIRECTION('',(-1.,0.E+000)); -#54620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57006 = PCURVE('',#44712,#57007); +#57007 = DEFINITIONAL_REPRESENTATION('',(#57008),#57012); +#57008 = LINE('',#57009,#57010); +#57009 = CARTESIAN_POINT('',(1.340163581979,-1.05)); +#57010 = VECTOR('',#57011,1.); +#57011 = DIRECTION('',(-1.,0.E+000)); +#57012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54621 = ORIENTED_EDGE('',*,*,#54622,.T.); -#54622 = EDGE_CURVE('',#54601,#54482,#54623,.T.); -#54623 = SURFACE_CURVE('',#54624,(#54630,#54659),.PCURVE_S1.); -#54624 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54625,#54626,#54627,#54628, - #54629),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#57013 = ORIENTED_EDGE('',*,*,#57014,.T.); +#57014 = EDGE_CURVE('',#56993,#56874,#57015,.T.); +#57015 = SURFACE_CURVE('',#57016,(#57022,#57051),.PCURVE_S1.); +#57016 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57017,#57018,#57019,#57020, + #57021),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#54625 = CARTESIAN_POINT('',(-3.427544930281,-0.175,0.96)); -#54626 = CARTESIAN_POINT('',(-3.435044082635,-0.158521600888,0.96)); -#54627 = CARTESIAN_POINT('',(-3.446266203969,-0.12439576155, +#57017 = CARTESIAN_POINT('',(-3.427544930281,-0.175,0.96)); +#57018 = CARTESIAN_POINT('',(-3.435044082635,-0.158521600888,0.96)); +#57019 = CARTESIAN_POINT('',(-3.446266203969,-0.12439576155, 0.957279642999)); -#54628 = CARTESIAN_POINT('',(-3.45,-8.905395158883E-002,0.94803685474)); -#54629 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,0.941561175052) - ); -#54630 = PCURVE('',#39981,#54631); -#54631 = DEFINITIONAL_REPRESENTATION('',(#54632),#54658); -#54632 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54633,#54634,#54635,#54636, - #54637,#54638,#54639,#54640,#54641,#54642,#54643,#54644,#54645, - #54646,#54647,#54648,#54649,#54650,#54651,#54652,#54653,#54654, - #54655,#54656,#54657),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#57020 = CARTESIAN_POINT('',(-3.45,-8.905395158883E-002,0.94803685474)); +#57021 = CARTESIAN_POINT('',(-3.45,-7.144660940673E-002,0.941561175052) + ); +#57022 = PCURVE('',#42373,#57023); +#57023 = DEFINITIONAL_REPRESENTATION('',(#57024),#57050); +#57024 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57025,#57026,#57027,#57028, + #57029,#57030,#57031,#57032,#57033,#57034,#57035,#57036,#57037, + #57038,#57039,#57040,#57041,#57042,#57043,#57044,#57045,#57046, + #57047,#57048,#57049),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67917,40 +70906,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54633 = CARTESIAN_POINT('',(1.570796326795,0.338717948676)); -#54634 = CARTESIAN_POINT('',(1.56580286259,0.338036207553)); -#54635 = CARTESIAN_POINT('',(1.555783766771,0.336703933434)); -#54636 = CARTESIAN_POINT('',(1.540659267699,0.334799074463)); -#54637 = CARTESIAN_POINT('',(1.525439607945,0.332987695528)); -#54638 = CARTESIAN_POINT('',(1.510125314923,0.331269724455)); -#54639 = CARTESIAN_POINT('',(1.49471680081,0.329645089072)); -#54640 = CARTESIAN_POINT('',(1.479214343164,0.328113717205)); -#54641 = CARTESIAN_POINT('',(1.463618084865,0.326675536682)); -#54642 = CARTESIAN_POINT('',(1.447928029069,0.32533047533)); -#54643 = CARTESIAN_POINT('',(1.432144035793,0.324078460975)); -#54644 = CARTESIAN_POINT('',(1.416265818105,0.322919421445)); -#54645 = CARTESIAN_POINT('',(1.400292939488,0.321853284567)); -#54646 = CARTESIAN_POINT('',(1.384224808252,0.320879978168)); -#54647 = CARTESIAN_POINT('',(1.368062099372,0.319999478882)); -#54648 = CARTESIAN_POINT('',(1.351805358236,0.319211763344)); -#54649 = CARTESIAN_POINT('',(1.335454992392,0.318516808187)); -#54650 = CARTESIAN_POINT('',(1.319011266734,0.317914590046)); -#54651 = CARTESIAN_POINT('',(1.302474298131,0.317405085555)); -#54652 = CARTESIAN_POINT('',(1.285844049961,0.316988271348)); -#54653 = CARTESIAN_POINT('',(1.269120328819,0.31666412406)); -#54654 = CARTESIAN_POINT('',(1.252302774006,0.316432620324)); -#54655 = CARTESIAN_POINT('',(1.235390875239,0.316293736775)); -#54656 = CARTESIAN_POINT('',(1.224052882656,0.316262878957)); -#54657 = CARTESIAN_POINT('',(1.218367924887,0.316262878957)); -#54658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54659 = PCURVE('',#37716,#54660); -#54660 = DEFINITIONAL_REPRESENTATION('',(#54661),#54687); -#54661 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54662,#54663,#54664,#54665, - #54666,#54667,#54668,#54669,#54670,#54671,#54672,#54673,#54674, - #54675,#54676,#54677,#54678,#54679,#54680,#54681,#54682,#54683, - #54684,#54685,#54686),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#57025 = CARTESIAN_POINT('',(1.570796326795,0.338717948676)); +#57026 = CARTESIAN_POINT('',(1.56580286259,0.338036207553)); +#57027 = CARTESIAN_POINT('',(1.555783766771,0.336703933434)); +#57028 = CARTESIAN_POINT('',(1.540659267699,0.334799074463)); +#57029 = CARTESIAN_POINT('',(1.525439607945,0.332987695528)); +#57030 = CARTESIAN_POINT('',(1.510125314923,0.331269724455)); +#57031 = CARTESIAN_POINT('',(1.49471680081,0.329645089072)); +#57032 = CARTESIAN_POINT('',(1.479214343164,0.328113717205)); +#57033 = CARTESIAN_POINT('',(1.463618084865,0.326675536682)); +#57034 = CARTESIAN_POINT('',(1.447928029069,0.32533047533)); +#57035 = CARTESIAN_POINT('',(1.432144035793,0.324078460975)); +#57036 = CARTESIAN_POINT('',(1.416265818105,0.322919421445)); +#57037 = CARTESIAN_POINT('',(1.400292939488,0.321853284567)); +#57038 = CARTESIAN_POINT('',(1.384224808252,0.320879978168)); +#57039 = CARTESIAN_POINT('',(1.368062099372,0.319999478882)); +#57040 = CARTESIAN_POINT('',(1.351805358236,0.319211763344)); +#57041 = CARTESIAN_POINT('',(1.335454992392,0.318516808187)); +#57042 = CARTESIAN_POINT('',(1.319011266734,0.317914590046)); +#57043 = CARTESIAN_POINT('',(1.302474298131,0.317405085555)); +#57044 = CARTESIAN_POINT('',(1.285844049961,0.316988271348)); +#57045 = CARTESIAN_POINT('',(1.269120328819,0.31666412406)); +#57046 = CARTESIAN_POINT('',(1.252302774006,0.316432620324)); +#57047 = CARTESIAN_POINT('',(1.235390875239,0.316293736775)); +#57048 = CARTESIAN_POINT('',(1.224052882656,0.316262878957)); +#57049 = CARTESIAN_POINT('',(1.218367924887,0.316262878957)); +#57050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57051 = PCURVE('',#40108,#57052); +#57052 = DEFINITIONAL_REPRESENTATION('',(#57053),#57079); +#57053 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57054,#57055,#57056,#57057, + #57058,#57059,#57060,#57061,#57062,#57063,#57064,#57065,#57066, + #57067,#57068,#57069,#57070,#57071,#57072,#57073,#57074,#57075, + #57076,#57077,#57078),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -67958,307 +70947,307 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54662 = CARTESIAN_POINT('',(3.568671239982,3.31)); -#54663 = CARTESIAN_POINT('',(3.562087771194,3.31)); -#54664 = CARTESIAN_POINT('',(3.54893734385,3.309977517711)); -#54665 = CARTESIAN_POINT('',(3.529258197005,3.309875128344)); -#54666 = CARTESIAN_POINT('',(3.50962248009,3.309702853978)); -#54667 = CARTESIAN_POINT('',(3.490027225862,3.30945947555)); -#54668 = CARTESIAN_POINT('',(3.470469530661,3.309143773992)); -#54669 = CARTESIAN_POINT('',(3.450946562988,3.30875453024)); -#54670 = CARTESIAN_POINT('',(3.431455560483,3.308290525228)); -#54671 = CARTESIAN_POINT('',(3.411993829671,3.307750539892)); -#54672 = CARTESIAN_POINT('',(3.392558744689,3.307133355166)); -#54673 = CARTESIAN_POINT('',(3.373147745934,3.306437751985)); -#54674 = CARTESIAN_POINT('',(3.353758338722,3.305662511282)); -#54675 = CARTESIAN_POINT('',(3.334388090766,3.304806413995)); -#54676 = CARTESIAN_POINT('',(3.315036210849,3.303868451806)); -#54677 = CARTESIAN_POINT('',(3.295701972544,3.302847616404)); -#54678 = CARTESIAN_POINT('',(3.276384705055,3.301742899472)); -#54679 = CARTESIAN_POINT('',(3.257083785249,3.300553292696)); -#54680 = CARTESIAN_POINT('',(3.23779862925,3.299277787763)); -#54681 = CARTESIAN_POINT('',(3.218528684003,3.297915376358)); -#54682 = CARTESIAN_POINT('',(3.199273418868,3.296465050166)); -#54683 = CARTESIAN_POINT('',(3.180032316721,3.294925800873)); -#54684 = CARTESIAN_POINT('',(3.160804866658,3.293296620164)); -#54685 = CARTESIAN_POINT('',(3.147995322616,3.292149873205)); -#54686 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); -#54687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54688 = ORIENTED_EDGE('',*,*,#54481,.T.); -#54689 = ADVANCED_FACE('',(#54690),#42320,.F.); -#54690 = FACE_BOUND('',#54691,.F.); -#54691 = EDGE_LOOP('',(#54692,#54693,#54694,#54717,#54740,#54763,#54783, - #54784,#54807,#54830)); -#54692 = ORIENTED_EDGE('',*,*,#54600,.F.); -#54693 = ORIENTED_EDGE('',*,*,#54241,.T.); -#54694 = ORIENTED_EDGE('',*,*,#54695,.T.); -#54695 = EDGE_CURVE('',#54244,#54696,#54698,.T.); -#54696 = VERTEX_POINT('',#54697); -#54697 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,0.96)); -#54698 = SURFACE_CURVE('',#54699,(#54703,#54710),.PCURVE_S1.); -#54699 = LINE('',#54700,#54701); -#54700 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); -#54701 = VECTOR('',#54702,1.); -#54702 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#54703 = PCURVE('',#42320,#54704); -#54704 = DEFINITIONAL_REPRESENTATION('',(#54705),#54709); -#54705 = LINE('',#54706,#54707); -#54706 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); -#54707 = VECTOR('',#54708,1.); -#54708 = DIRECTION('',(-0.707106781187,0.707106781187)); -#54709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54710 = PCURVE('',#37915,#54711); -#54711 = DEFINITIONAL_REPRESENTATION('',(#54712),#54716); -#54712 = LINE('',#54713,#54714); -#54713 = CARTESIAN_POINT('',(0.E+000,3.31)); -#54714 = VECTOR('',#54715,1.); -#54715 = DIRECTION('',(1.,0.E+000)); -#54716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54717 = ORIENTED_EDGE('',*,*,#54718,.T.); -#54718 = EDGE_CURVE('',#54696,#54719,#54721,.T.); -#54719 = VERTEX_POINT('',#54720); -#54720 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); -#54721 = SURFACE_CURVE('',#54722,(#54727,#54734),.PCURVE_S1.); -#54722 = CIRCLE('',#54723,0.55); -#54723 = AXIS2_PLACEMENT_3D('',#54724,#54725,#54726); -#54724 = CARTESIAN_POINT('',(-2.596446609407,-0.675,0.96)); -#54725 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54726 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); -#54727 = PCURVE('',#42320,#54728); -#54728 = DEFINITIONAL_REPRESENTATION('',(#54729),#54733); -#54729 = CIRCLE('',#54730,0.55); -#54730 = AXIS2_PLACEMENT_2D('',#54731,#54732); -#54731 = CARTESIAN_POINT('',(0.196446609407,-0.55)); -#54732 = DIRECTION('',(0.707106781187,0.707106781186)); -#54733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54734 = PCURVE('',#37888,#54735); -#54735 = DEFINITIONAL_REPRESENTATION('',(#54736),#54739); -#54736 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54737,#54738),.UNSPECIFIED., +#57054 = CARTESIAN_POINT('',(3.568671239982,3.31)); +#57055 = CARTESIAN_POINT('',(3.562087771194,3.31)); +#57056 = CARTESIAN_POINT('',(3.54893734385,3.309977517711)); +#57057 = CARTESIAN_POINT('',(3.529258197005,3.309875128344)); +#57058 = CARTESIAN_POINT('',(3.50962248009,3.309702853978)); +#57059 = CARTESIAN_POINT('',(3.490027225862,3.30945947555)); +#57060 = CARTESIAN_POINT('',(3.470469530661,3.309143773992)); +#57061 = CARTESIAN_POINT('',(3.450946562988,3.30875453024)); +#57062 = CARTESIAN_POINT('',(3.431455560483,3.308290525228)); +#57063 = CARTESIAN_POINT('',(3.411993829671,3.307750539892)); +#57064 = CARTESIAN_POINT('',(3.392558744689,3.307133355166)); +#57065 = CARTESIAN_POINT('',(3.373147745934,3.306437751985)); +#57066 = CARTESIAN_POINT('',(3.353758338722,3.305662511282)); +#57067 = CARTESIAN_POINT('',(3.334388090766,3.304806413995)); +#57068 = CARTESIAN_POINT('',(3.315036210849,3.303868451806)); +#57069 = CARTESIAN_POINT('',(3.295701972544,3.302847616404)); +#57070 = CARTESIAN_POINT('',(3.276384705055,3.301742899472)); +#57071 = CARTESIAN_POINT('',(3.257083785249,3.300553292696)); +#57072 = CARTESIAN_POINT('',(3.23779862925,3.299277787763)); +#57073 = CARTESIAN_POINT('',(3.218528684003,3.297915376358)); +#57074 = CARTESIAN_POINT('',(3.199273418868,3.296465050166)); +#57075 = CARTESIAN_POINT('',(3.180032316721,3.294925800873)); +#57076 = CARTESIAN_POINT('',(3.160804866658,3.293296620164)); +#57077 = CARTESIAN_POINT('',(3.147995322616,3.292149873205)); +#57078 = CARTESIAN_POINT('',(3.14159265359,3.291561175052)); +#57079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57080 = ORIENTED_EDGE('',*,*,#56873,.T.); +#57081 = ADVANCED_FACE('',(#57082),#44712,.F.); +#57082 = FACE_BOUND('',#57083,.F.); +#57083 = EDGE_LOOP('',(#57084,#57085,#57086,#57109,#57132,#57155,#57175, + #57176,#57199,#57222)); +#57084 = ORIENTED_EDGE('',*,*,#56992,.F.); +#57085 = ORIENTED_EDGE('',*,*,#56633,.T.); +#57086 = ORIENTED_EDGE('',*,*,#57087,.T.); +#57087 = EDGE_CURVE('',#56636,#57088,#57090,.T.); +#57088 = VERTEX_POINT('',#57089); +#57089 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,0.96)); +#57090 = SURFACE_CURVE('',#57091,(#57095,#57102),.PCURVE_S1.); +#57091 = LINE('',#57092,#57093); +#57092 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,0.96)); +#57093 = VECTOR('',#57094,1.); +#57094 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#57095 = PCURVE('',#44712,#57096); +#57096 = DEFINITIONAL_REPRESENTATION('',(#57097),#57101); +#57097 = LINE('',#57098,#57099); +#57098 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); +#57099 = VECTOR('',#57100,1.); +#57100 = DIRECTION('',(-0.707106781187,0.707106781187)); +#57101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57102 = PCURVE('',#40307,#57103); +#57103 = DEFINITIONAL_REPRESENTATION('',(#57104),#57108); +#57104 = LINE('',#57105,#57106); +#57105 = CARTESIAN_POINT('',(0.E+000,3.31)); +#57106 = VECTOR('',#57107,1.); +#57107 = DIRECTION('',(1.,0.E+000)); +#57108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57109 = ORIENTED_EDGE('',*,*,#57110,.T.); +#57110 = EDGE_CURVE('',#57088,#57111,#57113,.T.); +#57111 = VERTEX_POINT('',#57112); +#57112 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); +#57113 = SURFACE_CURVE('',#57114,(#57119,#57126),.PCURVE_S1.); +#57114 = CIRCLE('',#57115,0.55); +#57115 = AXIS2_PLACEMENT_3D('',#57116,#57117,#57118); +#57116 = CARTESIAN_POINT('',(-2.596446609407,-0.675,0.96)); +#57117 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57118 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); +#57119 = PCURVE('',#44712,#57120); +#57120 = DEFINITIONAL_REPRESENTATION('',(#57121),#57125); +#57121 = CIRCLE('',#57122,0.55); +#57122 = AXIS2_PLACEMENT_2D('',#57123,#57124); +#57123 = CARTESIAN_POINT('',(0.196446609407,-0.55)); +#57124 = DIRECTION('',(0.707106781187,0.707106781186)); +#57125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57126 = PCURVE('',#40280,#57127); +#57127 = DEFINITIONAL_REPRESENTATION('',(#57128),#57131); +#57128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57129,#57130),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163398),.PIECEWISE_BEZIER_KNOTS.); -#54737 = CARTESIAN_POINT('',(3.926990816987,3.31)); -#54738 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#54739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54740 = ORIENTED_EDGE('',*,*,#54741,.T.); -#54741 = EDGE_CURVE('',#54719,#54742,#54744,.T.); -#54742 = VERTEX_POINT('',#54743); -#54743 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); -#54744 = SURFACE_CURVE('',#54745,(#54749,#54756),.PCURVE_S1.); -#54745 = LINE('',#54746,#54747); -#54746 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); -#54747 = VECTOR('',#54748,1.); -#54748 = DIRECTION('',(1.,0.E+000,0.E+000)); -#54749 = PCURVE('',#42320,#54750); -#54750 = DEFINITIONAL_REPRESENTATION('',(#54751),#54755); -#54751 = LINE('',#54752,#54753); -#54752 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); -#54753 = VECTOR('',#54754,1.); -#54754 = DIRECTION('',(-1.,0.E+000)); -#54755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57129 = CARTESIAN_POINT('',(3.926990816987,3.31)); +#57130 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#57131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57132 = ORIENTED_EDGE('',*,*,#57133,.T.); +#57133 = EDGE_CURVE('',#57111,#57134,#57136,.T.); +#57134 = VERTEX_POINT('',#57135); +#57135 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); +#57136 = SURFACE_CURVE('',#57137,(#57141,#57148),.PCURVE_S1.); +#57137 = LINE('',#57138,#57139); +#57138 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); +#57139 = VECTOR('',#57140,1.); +#57140 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57141 = PCURVE('',#44712,#57142); +#57142 = DEFINITIONAL_REPRESENTATION('',(#57143),#57147); +#57143 = LINE('',#57144,#57145); +#57144 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); +#57145 = VECTOR('',#57146,1.); +#57146 = DIRECTION('',(-1.,0.E+000)); +#57147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57148 = PCURVE('',#40251,#57149); +#57149 = DEFINITIONAL_REPRESENTATION('',(#57150),#57154); +#57150 = LINE('',#57151,#57152); +#57151 = CARTESIAN_POINT('',(0.E+000,3.31)); +#57152 = VECTOR('',#57153,1.); +#57153 = DIRECTION('',(1.,0.E+000)); +#57154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57155 = ORIENTED_EDGE('',*,*,#57156,.T.); +#57156 = EDGE_CURVE('',#57134,#44697,#57157,.T.); +#57157 = SURFACE_CURVE('',#57158,(#57162,#57169),.PCURVE_S1.); +#57158 = LINE('',#57159,#57160); +#57159 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); +#57160 = VECTOR('',#57161,1.); +#57161 = DIRECTION('',(0.E+000,1.,0.E+000)); +#57162 = PCURVE('',#44712,#57163); +#57163 = DEFINITIONAL_REPRESENTATION('',(#57164),#57168); +#57164 = LINE('',#57165,#57166); +#57165 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57166 = VECTOR('',#57167,1.); +#57167 = DIRECTION('',(0.E+000,-1.)); +#57168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54756 = PCURVE('',#37859,#54757); -#54757 = DEFINITIONAL_REPRESENTATION('',(#54758),#54762); -#54758 = LINE('',#54759,#54760); -#54759 = CARTESIAN_POINT('',(0.E+000,3.31)); -#54760 = VECTOR('',#54761,1.); -#54761 = DIRECTION('',(1.,0.E+000)); -#54762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54763 = ORIENTED_EDGE('',*,*,#54764,.T.); -#54764 = EDGE_CURVE('',#54742,#42305,#54765,.T.); -#54765 = SURFACE_CURVE('',#54766,(#54770,#54777),.PCURVE_S1.); -#54766 = LINE('',#54767,#54768); -#54767 = CARTESIAN_POINT('',(-2.4,-1.225,0.96)); -#54768 = VECTOR('',#54769,1.); -#54769 = DIRECTION('',(0.E+000,1.,0.E+000)); -#54770 = PCURVE('',#42320,#54771); -#54771 = DEFINITIONAL_REPRESENTATION('',(#54772),#54776); -#54772 = LINE('',#54773,#54774); -#54773 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#54774 = VECTOR('',#54775,1.); -#54775 = DIRECTION('',(0.E+000,-1.)); -#54776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54777 = PCURVE('',#42353,#54778); -#54778 = DEFINITIONAL_REPRESENTATION('',(#54779),#54782); -#54779 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54780,#54781),.UNSPECIFIED., +#57169 = PCURVE('',#44745,#57170); +#57170 = DEFINITIONAL_REPRESENTATION('',(#57171),#57174); +#57171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57172,#57173),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#54780 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#54781 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#54782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54783 = ORIENTED_EDGE('',*,*,#42304,.F.); -#54784 = ORIENTED_EDGE('',*,*,#54785,.F.); -#54785 = EDGE_CURVE('',#54786,#42283,#54788,.T.); -#54786 = VERTEX_POINT('',#54787); -#54787 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); -#54788 = SURFACE_CURVE('',#54789,(#54794,#54801),.PCURVE_S1.); -#54789 = CIRCLE('',#54790,0.25); -#54790 = AXIS2_PLACEMENT_3D('',#54791,#54792,#54793); -#54791 = CARTESIAN_POINT('',(-2.596446609407,-0.675,0.96)); -#54792 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54793 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#54794 = PCURVE('',#42320,#54795); -#54795 = DEFINITIONAL_REPRESENTATION('',(#54796),#54800); -#54796 = CIRCLE('',#54797,0.25); -#54797 = AXIS2_PLACEMENT_2D('',#54798,#54799); -#54798 = CARTESIAN_POINT('',(0.196446609407,-0.55)); -#54799 = DIRECTION('',(0.707106781187,0.707106781187)); -#54800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54801 = PCURVE('',#37776,#54802); -#54802 = DEFINITIONAL_REPRESENTATION('',(#54803),#54806); -#54803 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54804,#54805),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#54804 = CARTESIAN_POINT('',(3.926990816987,3.31)); -#54805 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#54806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54807 = ORIENTED_EDGE('',*,*,#54808,.T.); -#54808 = EDGE_CURVE('',#54786,#54809,#54811,.T.); -#54809 = VERTEX_POINT('',#54810); -#54810 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,0.96)); -#54811 = SURFACE_CURVE('',#54812,(#54816,#54823),.PCURVE_S1.); -#54812 = LINE('',#54813,#54814); -#54813 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); -#54814 = VECTOR('',#54815,1.); -#54815 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#54816 = PCURVE('',#42320,#54817); -#54817 = DEFINITIONAL_REPRESENTATION('',(#54818),#54822); -#54818 = LINE('',#54819,#54820); -#54819 = CARTESIAN_POINT('',(0.373223304703,-0.373223304703)); -#54820 = VECTOR('',#54821,1.); -#54821 = DIRECTION('',(0.707106781187,-0.707106781187)); -#54822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54823 = PCURVE('',#37743,#54824); -#54824 = DEFINITIONAL_REPRESENTATION('',(#54825),#54829); -#54825 = LINE('',#54826,#54827); -#54826 = CARTESIAN_POINT('',(0.E+000,3.31)); -#54827 = VECTOR('',#54828,1.); -#54828 = DIRECTION('',(1.,0.E+000)); -#54829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57172 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#57173 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#57174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57175 = ORIENTED_EDGE('',*,*,#44696,.F.); +#57176 = ORIENTED_EDGE('',*,*,#57177,.F.); +#57177 = EDGE_CURVE('',#57178,#44675,#57180,.T.); +#57178 = VERTEX_POINT('',#57179); +#57179 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); +#57180 = SURFACE_CURVE('',#57181,(#57186,#57193),.PCURVE_S1.); +#57181 = CIRCLE('',#57182,0.25); +#57182 = AXIS2_PLACEMENT_3D('',#57183,#57184,#57185); +#57183 = CARTESIAN_POINT('',(-2.596446609407,-0.675,0.96)); +#57184 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57185 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#57186 = PCURVE('',#44712,#57187); +#57187 = DEFINITIONAL_REPRESENTATION('',(#57188),#57192); +#57188 = CIRCLE('',#57189,0.25); +#57189 = AXIS2_PLACEMENT_2D('',#57190,#57191); +#57190 = CARTESIAN_POINT('',(0.196446609407,-0.55)); +#57191 = DIRECTION('',(0.707106781187,0.707106781187)); +#57192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54830 = ORIENTED_EDGE('',*,*,#54831,.F.); -#54831 = EDGE_CURVE('',#54601,#54809,#54832,.T.); -#54832 = SURFACE_CURVE('',#54833,(#54838,#54845),.PCURVE_S1.); -#54833 = CIRCLE('',#54834,0.25); -#54834 = AXIS2_PLACEMENT_3D('',#54835,#54836,#54837); -#54835 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,0.96)); -#54836 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54837 = DIRECTION('',(-0.910179721124,-0.414213562373,0.E+000)); -#54838 = PCURVE('',#42320,#54839); -#54839 = DEFINITIONAL_REPRESENTATION('',(#54840),#54844); -#54840 = CIRCLE('',#54841,0.25); -#54841 = AXIS2_PLACEMENT_2D('',#54842,#54843); -#54842 = CARTESIAN_POINT('',(0.8,-1.153553390593)); -#54843 = DIRECTION('',(0.910179721124,0.414213562373)); -#54844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54845 = PCURVE('',#37716,#54846); -#54846 = DEFINITIONAL_REPRESENTATION('',(#54847),#54850); -#54847 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54848,#54849),.UNSPECIFIED., +#57193 = PCURVE('',#40168,#57194); +#57194 = DEFINITIONAL_REPRESENTATION('',(#57195),#57198); +#57195 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57196,#57197),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); +#57196 = CARTESIAN_POINT('',(3.926990816987,3.31)); +#57197 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#57198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57199 = ORIENTED_EDGE('',*,*,#57200,.T.); +#57200 = EDGE_CURVE('',#57178,#57201,#57203,.T.); +#57201 = VERTEX_POINT('',#57202); +#57202 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,0.96)); +#57203 = SURFACE_CURVE('',#57204,(#57208,#57215),.PCURVE_S1.); +#57204 = LINE('',#57205,#57206); +#57205 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); +#57206 = VECTOR('',#57207,1.); +#57207 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#57208 = PCURVE('',#44712,#57209); +#57209 = DEFINITIONAL_REPRESENTATION('',(#57210),#57214); +#57210 = LINE('',#57211,#57212); +#57211 = CARTESIAN_POINT('',(0.373223304703,-0.373223304703)); +#57212 = VECTOR('',#57213,1.); +#57213 = DIRECTION('',(0.707106781187,-0.707106781187)); +#57214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57215 = PCURVE('',#40135,#57216); +#57216 = DEFINITIONAL_REPRESENTATION('',(#57217),#57221); +#57217 = LINE('',#57218,#57219); +#57218 = CARTESIAN_POINT('',(0.E+000,3.31)); +#57219 = VECTOR('',#57220,1.); +#57220 = DIRECTION('',(1.,0.E+000)); +#57221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57222 = ORIENTED_EDGE('',*,*,#57223,.F.); +#57223 = EDGE_CURVE('',#56993,#57201,#57224,.T.); +#57224 = SURFACE_CURVE('',#57225,(#57230,#57237),.PCURVE_S1.); +#57225 = CIRCLE('',#57226,0.25); +#57226 = AXIS2_PLACEMENT_3D('',#57227,#57228,#57229); +#57227 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,0.96)); +#57228 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57229 = DIRECTION('',(-0.910179721124,-0.414213562373,0.E+000)); +#57230 = PCURVE('',#44712,#57231); +#57231 = DEFINITIONAL_REPRESENTATION('',(#57232),#57236); +#57232 = CIRCLE('',#57233,0.25); +#57233 = AXIS2_PLACEMENT_2D('',#57234,#57235); +#57234 = CARTESIAN_POINT('',(0.8,-1.153553390593)); +#57235 = DIRECTION('',(0.910179721124,0.414213562373)); +#57236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57237 = PCURVE('',#40108,#57238); +#57238 = DEFINITIONAL_REPRESENTATION('',(#57239),#57242); +#57239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57240,#57241),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.358319577004),.PIECEWISE_BEZIER_KNOTS.); -#54848 = CARTESIAN_POINT('',(3.568671239982,3.31)); -#54849 = CARTESIAN_POINT('',(3.926990816986,3.31)); -#54850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54851 = ADVANCED_FACE('',(#54852),#37915,.T.); -#54852 = FACE_BOUND('',#54853,.F.); -#54853 = EDGE_LOOP('',(#54854,#54855,#54856,#54857)); -#54854 = ORIENTED_EDGE('',*,*,#54695,.F.); -#54855 = ORIENTED_EDGE('',*,*,#54266,.T.); -#54856 = ORIENTED_EDGE('',*,*,#37899,.T.); -#54857 = ORIENTED_EDGE('',*,*,#54858,.F.); -#54858 = EDGE_CURVE('',#54696,#37872,#54859,.T.); -#54859 = SURFACE_CURVE('',#54860,(#54864,#54871),.PCURVE_S1.); -#54860 = LINE('',#54861,#54862); -#54861 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,0.96)); -#54862 = VECTOR('',#54863,1.); -#54863 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54864 = PCURVE('',#37915,#54865); -#54865 = DEFINITIONAL_REPRESENTATION('',(#54866),#54870); -#54866 = LINE('',#54867,#54868); -#54867 = CARTESIAN_POINT('',(0.853553390594,3.31)); -#54868 = VECTOR('',#54869,1.); -#54869 = DIRECTION('',(0.E+000,1.)); -#54870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54871 = PCURVE('',#37888,#54872); -#54872 = DEFINITIONAL_REPRESENTATION('',(#54873),#54876); -#54873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54874,#54875),.UNSPECIFIED., +#57240 = CARTESIAN_POINT('',(3.568671239982,3.31)); +#57241 = CARTESIAN_POINT('',(3.926990816986,3.31)); +#57242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57243 = ADVANCED_FACE('',(#57244),#40307,.T.); +#57244 = FACE_BOUND('',#57245,.F.); +#57245 = EDGE_LOOP('',(#57246,#57247,#57248,#57249)); +#57246 = ORIENTED_EDGE('',*,*,#57087,.F.); +#57247 = ORIENTED_EDGE('',*,*,#56658,.T.); +#57248 = ORIENTED_EDGE('',*,*,#40291,.T.); +#57249 = ORIENTED_EDGE('',*,*,#57250,.F.); +#57250 = EDGE_CURVE('',#57088,#40264,#57251,.T.); +#57251 = SURFACE_CURVE('',#57252,(#57256,#57263),.PCURVE_S1.); +#57252 = LINE('',#57253,#57254); +#57253 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,0.96)); +#57254 = VECTOR('',#57255,1.); +#57255 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57256 = PCURVE('',#40307,#57257); +#57257 = DEFINITIONAL_REPRESENTATION('',(#57258),#57262); +#57258 = LINE('',#57259,#57260); +#57259 = CARTESIAN_POINT('',(0.853553390594,3.31)); +#57260 = VECTOR('',#57261,1.); +#57261 = DIRECTION('',(0.E+000,1.)); +#57262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57263 = PCURVE('',#40280,#57264); +#57264 = DEFINITIONAL_REPRESENTATION('',(#57265),#57268); +#57265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57266,#57267),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#54874 = CARTESIAN_POINT('',(3.926990816989,3.31)); -#54875 = CARTESIAN_POINT('',(3.926990816989,4.7)); -#54876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54877 = ADVANCED_FACE('',(#54878),#53172,.T.); -#54878 = FACE_BOUND('',#54879,.F.); -#54879 = EDGE_LOOP('',(#54880,#54935,#54936,#54937,#54960,#54987,#55010, - #55070)); -#54880 = ORIENTED_EDGE('',*,*,#54881,.T.); -#54881 = EDGE_CURVE('',#54882,#53157,#54884,.T.); -#54882 = VERTEX_POINT('',#54883); -#54883 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); -#54884 = SURFACE_CURVE('',#54885,(#54894,#54906),.PCURVE_S1.); -#54885 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54886,#54887,#54888,#54889, - #54890,#54891,#54892,#54893),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#57266 = CARTESIAN_POINT('',(3.926990816989,3.31)); +#57267 = CARTESIAN_POINT('',(3.926990816989,4.7)); +#57268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57269 = ADVANCED_FACE('',(#57270),#55564,.T.); +#57270 = FACE_BOUND('',#57271,.F.); +#57271 = EDGE_LOOP('',(#57272,#57327,#57328,#57329,#57352,#57379,#57402, + #57462)); +#57272 = ORIENTED_EDGE('',*,*,#57273,.T.); +#57273 = EDGE_CURVE('',#57274,#55549,#57276,.T.); +#57274 = VERTEX_POINT('',#57275); +#57275 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); +#57276 = SURFACE_CURVE('',#57277,(#57286,#57298),.PCURVE_S1.); +#57277 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57278,#57279,#57280,#57281, + #57282,#57283,#57284,#57285),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#54886 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); -#54887 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.215088834765)); -#54888 = CARTESIAN_POINT('',(-3.328327844504,-0.720936224208, +#57278 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); +#57279 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.215088834765)); +#57280 = CARTESIAN_POINT('',(-3.328327844504,-0.720936224208, -2.239519457455)); -#54889 = CARTESIAN_POINT('',(-3.343621523704,-0.705642545008, +#57281 = CARTESIAN_POINT('',(-3.343621523704,-0.705642545008, -2.278246267971)); -#54890 = CARTESIAN_POINT('',(-3.371920174968,-0.677343893744, +#57282 = CARTESIAN_POINT('',(-3.371920174968,-0.677343893744, -2.313670105381)); -#54891 = CARTESIAN_POINT('',(-3.416186746343,-0.633077322369, +#57283 = CARTESIAN_POINT('',(-3.416186746343,-0.633077322369, -2.341600728372)); -#54892 = CARTESIAN_POINT('',(-3.452925233947,-0.596338834765,-2.35)); -#54893 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); -#54894 = PCURVE('',#53172,#54895); -#54895 = DEFINITIONAL_REPRESENTATION('',(#54896),#54905); -#54896 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54897,#54898,#54899,#54900, - #54901,#54902,#54903,#54904),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#57284 = CARTESIAN_POINT('',(-3.452925233947,-0.596338834765,-2.35)); +#57285 = CARTESIAN_POINT('',(-3.474264068712,-0.575,-2.35)); +#57286 = PCURVE('',#55564,#57287); +#57287 = DEFINITIONAL_REPRESENTATION('',(#57288),#57297); +#57288 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57289,#57290,#57291,#57292, + #57293,#57294,#57295,#57296),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#54897 = CARTESIAN_POINT('',(0.374264068712,0.15)); -#54898 = CARTESIAN_POINT('',(0.374264068712,0.134911165235)); -#54899 = CARTESIAN_POINT('',(0.368517021873,0.110480542545)); -#54900 = CARTESIAN_POINT('',(0.346888493329,7.1753732029E-002)); -#54901 = CARTESIAN_POINT('',(0.306868156915,3.6329894619E-002)); -#54902 = CARTESIAN_POINT('',(0.244265771317,8.399271628E-003)); -#54903 = CARTESIAN_POINT('',(0.192309703886,0.E+000)); -#54904 = CARTESIAN_POINT('',(0.162132034356,0.E+000)); -#54905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54906 = PCURVE('',#53200,#54907); -#54907 = DEFINITIONAL_REPRESENTATION('',(#54908),#54934); -#54908 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#54909,#54910,#54911,#54912, - #54913,#54914,#54915,#54916,#54917,#54918,#54919,#54920,#54921, - #54922,#54923,#54924,#54925,#54926,#54927,#54928,#54929,#54930, - #54931,#54932,#54933),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#57289 = CARTESIAN_POINT('',(0.374264068712,0.15)); +#57290 = CARTESIAN_POINT('',(0.374264068712,0.134911165235)); +#57291 = CARTESIAN_POINT('',(0.368517021873,0.110480542545)); +#57292 = CARTESIAN_POINT('',(0.346888493329,7.1753732029E-002)); +#57293 = CARTESIAN_POINT('',(0.306868156915,3.6329894619E-002)); +#57294 = CARTESIAN_POINT('',(0.244265771317,8.399271628E-003)); +#57295 = CARTESIAN_POINT('',(0.192309703886,0.E+000)); +#57296 = CARTESIAN_POINT('',(0.162132034356,0.E+000)); +#57297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57298 = PCURVE('',#55592,#57299); +#57299 = DEFINITIONAL_REPRESENTATION('',(#57300),#57326); +#57300 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57301,#57302,#57303,#57304, + #57305,#57306,#57307,#57308,#57309,#57310,#57311,#57312,#57313, + #57314,#57315,#57316,#57317,#57318,#57319,#57320,#57321,#57322, + #57323,#57324,#57325),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -68266,169 +71255,169 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#54909 = CARTESIAN_POINT('',(4.712388980385,0.425735931288)); -#54910 = CARTESIAN_POINT('',(4.748933560976,0.425735860125)); -#54911 = CARTESIAN_POINT('',(4.81707874687,0.425199099164)); -#54912 = CARTESIAN_POINT('',(4.907992270893,0.423106498153)); -#54913 = CARTESIAN_POINT('',(4.991501242609,0.42006779362)); -#54914 = CARTESIAN_POINT('',(5.070203254432,0.416357982616)); -#54915 = CARTESIAN_POINT('',(5.144906443438,0.412033560575)); -#54916 = CARTESIAN_POINT('',(5.216603945889,0.407188332156)); -#54917 = CARTESIAN_POINT('',(5.285913848235,0.401874674064)); -#54918 = CARTESIAN_POINT('',(5.353274617376,0.396113808413)); -#54919 = CARTESIAN_POINT('',(5.419136101421,0.389933446452)); -#54920 = CARTESIAN_POINT('',(5.483899443317,0.383359560217)); -#54921 = CARTESIAN_POINT('',(5.547920698644,0.376418589459)); -#54922 = CARTESIAN_POINT('',(5.611491697867,0.36913684228)); -#54923 = CARTESIAN_POINT('',(5.674841699303,0.361511142382)); -#54924 = CARTESIAN_POINT('',(5.738220831198,0.35353820958)); -#54925 = CARTESIAN_POINT('',(5.801885308441,0.345215120348)); -#54926 = CARTESIAN_POINT('',(5.866098193035,0.336537628411)); -#54927 = CARTESIAN_POINT('',(5.931103476771,0.327506421831)); -#54928 = CARTESIAN_POINT('',(5.997203324603,0.318098933044)); -#54929 = CARTESIAN_POINT('',(6.064845544964,0.308269338877)); -#54930 = CARTESIAN_POINT('',(6.13454852804,0.297976750449)); -#54931 = CARTESIAN_POINT('',(6.206898120521,0.287178956287)); -#54932 = CARTESIAN_POINT('',(6.257321803275,0.279615719427)); -#54933 = CARTESIAN_POINT('',(6.28318530718,0.275735931288)); -#54934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54935 = ORIENTED_EDGE('',*,*,#53156,.F.); -#54936 = ORIENTED_EDGE('',*,*,#54122,.T.); -#54937 = ORIENTED_EDGE('',*,*,#54938,.T.); -#54938 = EDGE_CURVE('',#54123,#54939,#54941,.T.); -#54939 = VERTEX_POINT('',#54940); -#54940 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-0.56)); -#54941 = SURFACE_CURVE('',#54942,(#54946,#54953),.PCURVE_S1.); -#54942 = LINE('',#54943,#54944); -#54943 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-0.56)); -#54944 = VECTOR('',#54945,1.); -#54945 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#54946 = PCURVE('',#53172,#54947); -#54947 = DEFINITIONAL_REPRESENTATION('',(#54948),#54952); -#54948 = LINE('',#54949,#54950); -#54949 = CARTESIAN_POINT('',(0.E+000,1.79)); -#54950 = VECTOR('',#54951,1.); -#54951 = DIRECTION('',(1.,0.E+000)); -#54952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54953 = PCURVE('',#42672,#54954); -#54954 = DEFINITIONAL_REPRESENTATION('',(#54955),#54959); -#54955 = LINE('',#54956,#54957); -#54956 = CARTESIAN_POINT('',(0.161091270347,-0.764644660941)); -#54957 = VECTOR('',#54958,1.); -#54958 = DIRECTION('',(0.707106781187,0.707106781187)); -#54959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57301 = CARTESIAN_POINT('',(4.712388980385,0.425735931288)); +#57302 = CARTESIAN_POINT('',(4.748933560976,0.425735860125)); +#57303 = CARTESIAN_POINT('',(4.81707874687,0.425199099164)); +#57304 = CARTESIAN_POINT('',(4.907992270893,0.423106498153)); +#57305 = CARTESIAN_POINT('',(4.991501242609,0.42006779362)); +#57306 = CARTESIAN_POINT('',(5.070203254432,0.416357982616)); +#57307 = CARTESIAN_POINT('',(5.144906443438,0.412033560575)); +#57308 = CARTESIAN_POINT('',(5.216603945889,0.407188332156)); +#57309 = CARTESIAN_POINT('',(5.285913848235,0.401874674064)); +#57310 = CARTESIAN_POINT('',(5.353274617376,0.396113808413)); +#57311 = CARTESIAN_POINT('',(5.419136101421,0.389933446452)); +#57312 = CARTESIAN_POINT('',(5.483899443317,0.383359560217)); +#57313 = CARTESIAN_POINT('',(5.547920698644,0.376418589459)); +#57314 = CARTESIAN_POINT('',(5.611491697867,0.36913684228)); +#57315 = CARTESIAN_POINT('',(5.674841699303,0.361511142382)); +#57316 = CARTESIAN_POINT('',(5.738220831198,0.35353820958)); +#57317 = CARTESIAN_POINT('',(5.801885308441,0.345215120348)); +#57318 = CARTESIAN_POINT('',(5.866098193035,0.336537628411)); +#57319 = CARTESIAN_POINT('',(5.931103476771,0.327506421831)); +#57320 = CARTESIAN_POINT('',(5.997203324603,0.318098933044)); +#57321 = CARTESIAN_POINT('',(6.064845544964,0.308269338877)); +#57322 = CARTESIAN_POINT('',(6.13454852804,0.297976750449)); +#57323 = CARTESIAN_POINT('',(6.206898120521,0.287178956287)); +#57324 = CARTESIAN_POINT('',(6.257321803275,0.279615719427)); +#57325 = CARTESIAN_POINT('',(6.28318530718,0.275735931288)); +#57326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57327 = ORIENTED_EDGE('',*,*,#55548,.F.); +#57328 = ORIENTED_EDGE('',*,*,#56514,.T.); +#57329 = ORIENTED_EDGE('',*,*,#57330,.T.); +#57330 = EDGE_CURVE('',#56515,#57331,#57333,.T.); +#57331 = VERTEX_POINT('',#57332); +#57332 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-0.56)); +#57333 = SURFACE_CURVE('',#57334,(#57338,#57345),.PCURVE_S1.); +#57334 = LINE('',#57335,#57336); +#57335 = CARTESIAN_POINT('',(-3.588908729653,-0.460355339059,-0.56)); +#57336 = VECTOR('',#57337,1.); +#57337 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#57338 = PCURVE('',#55564,#57339); +#57339 = DEFINITIONAL_REPRESENTATION('',(#57340),#57344); +#57340 = LINE('',#57341,#57342); +#57341 = CARTESIAN_POINT('',(0.E+000,1.79)); +#57342 = VECTOR('',#57343,1.); +#57343 = DIRECTION('',(1.,0.E+000)); +#57344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#54960 = ORIENTED_EDGE('',*,*,#54961,.F.); -#54961 = EDGE_CURVE('',#54962,#54939,#54964,.T.); -#54962 = VERTEX_POINT('',#54963); -#54963 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); -#54964 = SURFACE_CURVE('',#54965,(#54969,#54976),.PCURVE_S1.); -#54965 = LINE('',#54966,#54967); -#54966 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); -#54967 = VECTOR('',#54968,1.); -#54968 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54969 = PCURVE('',#53172,#54970); -#54970 = DEFINITIONAL_REPRESENTATION('',(#54971),#54975); -#54971 = LINE('',#54972,#54973); -#54972 = CARTESIAN_POINT('',(0.853553390594,0.82)); -#54973 = VECTOR('',#54974,1.); -#54974 = DIRECTION('',(0.E+000,1.)); -#54975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54976 = PCURVE('',#54977,#54982); -#54977 = CYLINDRICAL_SURFACE('',#54978,0.55); -#54978 = AXIS2_PLACEMENT_3D('',#54979,#54980,#54981); -#54979 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); -#54980 = DIRECTION('',(0.E+000,0.E+000,1.)); -#54981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#54982 = DEFINITIONAL_REPRESENTATION('',(#54983),#54986); -#54983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#54984,#54985),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#54984 = CARTESIAN_POINT('',(3.926990816989,0.82)); -#54985 = CARTESIAN_POINT('',(3.926990816989,1.79)); -#54986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#54987 = ORIENTED_EDGE('',*,*,#54988,.T.); -#54988 = EDGE_CURVE('',#54962,#54989,#54991,.T.); -#54989 = VERTEX_POINT('',#54990); -#54990 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); -#54991 = SURFACE_CURVE('',#54992,(#54996,#55003),.PCURVE_S1.); -#54992 = LINE('',#54993,#54994); -#54993 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); -#54994 = VECTOR('',#54995,1.); -#54995 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#54996 = PCURVE('',#53172,#54997); -#54997 = DEFINITIONAL_REPRESENTATION('',(#54998),#55002); -#54998 = LINE('',#54999,#55000); -#54999 = CARTESIAN_POINT('',(0.853553390594,0.82)); -#55000 = VECTOR('',#55001,1.); -#55001 = DIRECTION('',(-1.,0.E+000)); -#55002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55003 = PCURVE('',#40920,#55004); -#55004 = DEFINITIONAL_REPRESENTATION('',(#55005),#55009); -#55005 = LINE('',#55006,#55007); -#55006 = CARTESIAN_POINT('',(0.188908729653,0.764644660941)); -#55007 = VECTOR('',#55008,1.); -#55008 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#55009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57345 = PCURVE('',#45064,#57346); +#57346 = DEFINITIONAL_REPRESENTATION('',(#57347),#57351); +#57347 = LINE('',#57348,#57349); +#57348 = CARTESIAN_POINT('',(0.161091270347,-0.764644660941)); +#57349 = VECTOR('',#57350,1.); +#57350 = DIRECTION('',(0.707106781187,0.707106781187)); +#57351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55010 = ORIENTED_EDGE('',*,*,#55011,.F.); -#55011 = EDGE_CURVE('',#55012,#54989,#55014,.T.); -#55012 = VERTEX_POINT('',#55013); -#55013 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); -#55014 = SURFACE_CURVE('',#55015,(#55024,#55036),.PCURVE_S1.); -#55015 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55016,#55017,#55018,#55019, - #55020,#55021,#55022,#55023),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#57352 = ORIENTED_EDGE('',*,*,#57353,.F.); +#57353 = EDGE_CURVE('',#57354,#57331,#57356,.T.); +#57354 = VERTEX_POINT('',#57355); +#57355 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); +#57356 = SURFACE_CURVE('',#57357,(#57361,#57368),.PCURVE_S1.); +#57357 = LINE('',#57358,#57359); +#57358 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); +#57359 = VECTOR('',#57360,1.); +#57360 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57361 = PCURVE('',#55564,#57362); +#57362 = DEFINITIONAL_REPRESENTATION('',(#57363),#57367); +#57363 = LINE('',#57364,#57365); +#57364 = CARTESIAN_POINT('',(0.853553390594,0.82)); +#57365 = VECTOR('',#57366,1.); +#57366 = DIRECTION('',(0.E+000,1.)); +#57367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57368 = PCURVE('',#57369,#57374); +#57369 = CYLINDRICAL_SURFACE('',#57370,0.55); +#57370 = AXIS2_PLACEMENT_3D('',#57371,#57372,#57373); +#57371 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-2.35)); +#57372 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57374 = DEFINITIONAL_REPRESENTATION('',(#57375),#57378); +#57375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57376,#57377),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); +#57376 = CARTESIAN_POINT('',(3.926990816989,0.82)); +#57377 = CARTESIAN_POINT('',(3.926990816989,1.79)); +#57378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57379 = ORIENTED_EDGE('',*,*,#57380,.T.); +#57380 = EDGE_CURVE('',#57354,#57381,#57383,.T.); +#57381 = VERTEX_POINT('',#57382); +#57382 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); +#57383 = SURFACE_CURVE('',#57384,(#57388,#57395),.PCURVE_S1.); +#57384 = LINE('',#57385,#57386); +#57385 = CARTESIAN_POINT('',(-2.985355339059,-1.063908729653,-1.53)); +#57386 = VECTOR('',#57387,1.); +#57387 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#57388 = PCURVE('',#55564,#57389); +#57389 = DEFINITIONAL_REPRESENTATION('',(#57390),#57394); +#57390 = LINE('',#57391,#57392); +#57391 = CARTESIAN_POINT('',(0.853553390594,0.82)); +#57392 = VECTOR('',#57393,1.); +#57393 = DIRECTION('',(-1.,0.E+000)); +#57394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57395 = PCURVE('',#43312,#57396); +#57396 = DEFINITIONAL_REPRESENTATION('',(#57397),#57401); +#57397 = LINE('',#57398,#57399); +#57398 = CARTESIAN_POINT('',(0.188908729653,0.764644660941)); +#57399 = VECTOR('',#57400,1.); +#57400 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#57401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57402 = ORIENTED_EDGE('',*,*,#57403,.F.); +#57403 = EDGE_CURVE('',#57404,#57381,#57406,.T.); +#57404 = VERTEX_POINT('',#57405); +#57405 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); +#57406 = SURFACE_CURVE('',#57407,(#57416,#57428),.PCURVE_S1.); +#57407 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57408,#57409,#57410,#57411, + #57412,#57413,#57414,#57415),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#55016 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); -#55017 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.664911165235)); -#55018 = CARTESIAN_POINT('',(-3.32020029292,-0.729063775792, +#57408 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); +#57409 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.664911165235)); +#57410 = CARTESIAN_POINT('',(-3.32020029292,-0.729063775792, -1.640480542545)); -#55019 = CARTESIAN_POINT('',(-3.30490661372,-0.744357454992, +#57411 = CARTESIAN_POINT('',(-3.30490661372,-0.744357454992, -1.601753732029)); -#55020 = CARTESIAN_POINT('',(-3.276607962456,-0.772656106256, +#57412 = CARTESIAN_POINT('',(-3.276607962456,-0.772656106256, -1.566329894619)); -#55021 = CARTESIAN_POINT('',(-3.232341391081,-0.816922677631, +#57413 = CARTESIAN_POINT('',(-3.232341391081,-0.816922677631, -1.538399271628)); -#55022 = CARTESIAN_POINT('',(-3.195602903477,-0.853661165235,-1.53)); -#55023 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); -#55024 = PCURVE('',#53172,#55025); -#55025 = DEFINITIONAL_REPRESENTATION('',(#55026),#55035); -#55026 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55027,#55028,#55029,#55030, - #55031,#55032,#55033,#55034),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#57414 = CARTESIAN_POINT('',(-3.195602903477,-0.853661165235,-1.53)); +#57415 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); +#57416 = PCURVE('',#55564,#57417); +#57417 = DEFINITIONAL_REPRESENTATION('',(#57418),#57427); +#57418 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57419,#57420,#57421,#57422, + #57423,#57424,#57425,#57426),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#55027 = CARTESIAN_POINT('',(0.374264068712,0.67)); -#55028 = CARTESIAN_POINT('',(0.374264068712,0.685088834765)); -#55029 = CARTESIAN_POINT('',(0.380011115552,0.709519457455)); -#55030 = CARTESIAN_POINT('',(0.401639644095,0.748246267971)); -#55031 = CARTESIAN_POINT('',(0.441659980509,0.783670105381)); -#55032 = CARTESIAN_POINT('',(0.504262366107,0.811600728372)); -#55033 = CARTESIAN_POINT('',(0.556218433538,0.82)); -#55034 = CARTESIAN_POINT('',(0.586396103068,0.82)); -#55035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55036 = PCURVE('',#55037,#55042); -#55037 = CYLINDRICAL_SURFACE('',#55038,0.15); -#55038 = AXIS2_PLACEMENT_3D('',#55039,#55040,#55041); -#55039 = CARTESIAN_POINT('',(-3.75,-0.875,-1.68)); -#55040 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55041 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55042 = DEFINITIONAL_REPRESENTATION('',(#55043),#55069); -#55043 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#55044,#55045,#55046,#55047, - #55048,#55049,#55050,#55051,#55052,#55053,#55054,#55055,#55056, - #55057,#55058,#55059,#55060,#55061,#55062,#55063,#55064,#55065, - #55066,#55067,#55068),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#57419 = CARTESIAN_POINT('',(0.374264068712,0.67)); +#57420 = CARTESIAN_POINT('',(0.374264068712,0.685088834765)); +#57421 = CARTESIAN_POINT('',(0.380011115552,0.709519457455)); +#57422 = CARTESIAN_POINT('',(0.401639644095,0.748246267971)); +#57423 = CARTESIAN_POINT('',(0.441659980509,0.783670105381)); +#57424 = CARTESIAN_POINT('',(0.504262366107,0.811600728372)); +#57425 = CARTESIAN_POINT('',(0.556218433538,0.82)); +#57426 = CARTESIAN_POINT('',(0.586396103068,0.82)); +#57427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57428 = PCURVE('',#57429,#57434); +#57429 = CYLINDRICAL_SURFACE('',#57430,0.15); +#57430 = AXIS2_PLACEMENT_3D('',#57431,#57432,#57433); +#57431 = CARTESIAN_POINT('',(-3.75,-0.875,-1.68)); +#57432 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57433 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57434 = DEFINITIONAL_REPRESENTATION('',(#57435),#57461); +#57435 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#57436,#57437,#57438,#57439, + #57440,#57441,#57442,#57443,#57444,#57445,#57446,#57447,#57448, + #57449,#57450,#57451,#57452,#57453,#57454,#57455,#57456,#57457, + #57458,#57459,#57460),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -68436,3657 +71425,3657 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#55044 = CARTESIAN_POINT('',(1.570796326795,0.425735931288)); -#55045 = CARTESIAN_POINT('',(1.607340907387,0.425736002451)); -#55046 = CARTESIAN_POINT('',(1.67548609328,0.426272763412)); -#55047 = CARTESIAN_POINT('',(1.766399617303,0.428365364423)); -#55048 = CARTESIAN_POINT('',(1.849908589019,0.431404068956)); -#55049 = CARTESIAN_POINT('',(1.928610600842,0.43511387996)); -#55050 = CARTESIAN_POINT('',(2.003313789848,0.439438302001)); -#55051 = CARTESIAN_POINT('',(2.075011292299,0.44428353042)); -#55052 = CARTESIAN_POINT('',(2.144321194645,0.449597188512)); -#55053 = CARTESIAN_POINT('',(2.211681963786,0.455358054163)); -#55054 = CARTESIAN_POINT('',(2.277543447832,0.461538416124)); -#55055 = CARTESIAN_POINT('',(2.342306789727,0.468112302359)); -#55056 = CARTESIAN_POINT('',(2.406328045055,0.475053273117)); -#55057 = CARTESIAN_POINT('',(2.469899044277,0.482335020296)); -#55058 = CARTESIAN_POINT('',(2.533249045713,0.489960720194)); -#55059 = CARTESIAN_POINT('',(2.596628177608,0.497933652996)); -#55060 = CARTESIAN_POINT('',(2.660292654851,0.506256742228)); -#55061 = CARTESIAN_POINT('',(2.724505539445,0.514934234165)); -#55062 = CARTESIAN_POINT('',(2.789510823181,0.523965440745)); -#55063 = CARTESIAN_POINT('',(2.855610671013,0.533372929532)); -#55064 = CARTESIAN_POINT('',(2.923252891374,0.543202523699)); -#55065 = CARTESIAN_POINT('',(2.99295587445,0.553495112127)); -#55066 = CARTESIAN_POINT('',(3.065305466931,0.564292906289)); -#55067 = CARTESIAN_POINT('',(3.115729149685,0.571856143149)); -#55068 = CARTESIAN_POINT('',(3.14159265359,0.575735931288)); -#55069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55070 = ORIENTED_EDGE('',*,*,#55071,.F.); -#55071 = EDGE_CURVE('',#54882,#55012,#55072,.T.); -#55072 = SURFACE_CURVE('',#55073,(#55077,#55084),.PCURVE_S1.); -#55073 = LINE('',#55074,#55075); -#55074 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); -#55075 = VECTOR('',#55076,1.); -#55076 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55077 = PCURVE('',#53172,#55078); -#55078 = DEFINITIONAL_REPRESENTATION('',(#55079),#55083); -#55079 = LINE('',#55080,#55081); -#55080 = CARTESIAN_POINT('',(0.374264068712,0.15)); -#55081 = VECTOR('',#55082,1.); -#55082 = DIRECTION('',(0.E+000,1.)); -#55083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55084 = PCURVE('',#55085,#55090); -#55085 = PLANE('',#55086); -#55086 = AXIS2_PLACEMENT_3D('',#55087,#55088,#55089); -#55087 = CARTESIAN_POINT('',(-3.75,-0.725,-2.2)); -#55088 = DIRECTION('',(0.E+000,1.,0.E+000)); -#55089 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55090 = DEFINITIONAL_REPRESENTATION('',(#55091),#55095); -#55091 = LINE('',#55092,#55093); -#55092 = CARTESIAN_POINT('',(0.E+000,0.425735931288)); -#55093 = VECTOR('',#55094,1.); -#55094 = DIRECTION('',(1.,0.E+000)); -#55095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55096 = ADVANCED_FACE('',(#55097),#37888,.T.); -#55097 = FACE_BOUND('',#55098,.T.); -#55098 = EDGE_LOOP('',(#55099,#55100,#55120,#55121)); -#55099 = ORIENTED_EDGE('',*,*,#54718,.T.); -#55100 = ORIENTED_EDGE('',*,*,#55101,.T.); -#55101 = EDGE_CURVE('',#54719,#37844,#55102,.T.); -#55102 = SURFACE_CURVE('',#55103,(#55107,#55113),.PCURVE_S1.); -#55103 = LINE('',#55104,#55105); -#55104 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); -#55105 = VECTOR('',#55106,1.); -#55106 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55107 = PCURVE('',#37888,#55108); -#55108 = DEFINITIONAL_REPRESENTATION('',(#55109),#55112); -#55109 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55110,#55111),.UNSPECIFIED., +#57436 = CARTESIAN_POINT('',(1.570796326795,0.425735931288)); +#57437 = CARTESIAN_POINT('',(1.607340907387,0.425736002451)); +#57438 = CARTESIAN_POINT('',(1.67548609328,0.426272763412)); +#57439 = CARTESIAN_POINT('',(1.766399617303,0.428365364423)); +#57440 = CARTESIAN_POINT('',(1.849908589019,0.431404068956)); +#57441 = CARTESIAN_POINT('',(1.928610600842,0.43511387996)); +#57442 = CARTESIAN_POINT('',(2.003313789848,0.439438302001)); +#57443 = CARTESIAN_POINT('',(2.075011292299,0.44428353042)); +#57444 = CARTESIAN_POINT('',(2.144321194645,0.449597188512)); +#57445 = CARTESIAN_POINT('',(2.211681963786,0.455358054163)); +#57446 = CARTESIAN_POINT('',(2.277543447832,0.461538416124)); +#57447 = CARTESIAN_POINT('',(2.342306789727,0.468112302359)); +#57448 = CARTESIAN_POINT('',(2.406328045055,0.475053273117)); +#57449 = CARTESIAN_POINT('',(2.469899044277,0.482335020296)); +#57450 = CARTESIAN_POINT('',(2.533249045713,0.489960720194)); +#57451 = CARTESIAN_POINT('',(2.596628177608,0.497933652996)); +#57452 = CARTESIAN_POINT('',(2.660292654851,0.506256742228)); +#57453 = CARTESIAN_POINT('',(2.724505539445,0.514934234165)); +#57454 = CARTESIAN_POINT('',(2.789510823181,0.523965440745)); +#57455 = CARTESIAN_POINT('',(2.855610671013,0.533372929532)); +#57456 = CARTESIAN_POINT('',(2.923252891374,0.543202523699)); +#57457 = CARTESIAN_POINT('',(2.99295587445,0.553495112127)); +#57458 = CARTESIAN_POINT('',(3.065305466931,0.564292906289)); +#57459 = CARTESIAN_POINT('',(3.115729149685,0.571856143149)); +#57460 = CARTESIAN_POINT('',(3.14159265359,0.575735931288)); +#57461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57462 = ORIENTED_EDGE('',*,*,#57463,.F.); +#57463 = EDGE_CURVE('',#57274,#57404,#57464,.T.); +#57464 = SURFACE_CURVE('',#57465,(#57469,#57476),.PCURVE_S1.); +#57465 = LINE('',#57466,#57467); +#57466 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); +#57467 = VECTOR('',#57468,1.); +#57468 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57469 = PCURVE('',#55564,#57470); +#57470 = DEFINITIONAL_REPRESENTATION('',(#57471),#57475); +#57471 = LINE('',#57472,#57473); +#57472 = CARTESIAN_POINT('',(0.374264068712,0.15)); +#57473 = VECTOR('',#57474,1.); +#57474 = DIRECTION('',(0.E+000,1.)); +#57475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57476 = PCURVE('',#57477,#57482); +#57477 = PLANE('',#57478); +#57478 = AXIS2_PLACEMENT_3D('',#57479,#57480,#57481); +#57479 = CARTESIAN_POINT('',(-3.75,-0.725,-2.2)); +#57480 = DIRECTION('',(0.E+000,1.,0.E+000)); +#57481 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57482 = DEFINITIONAL_REPRESENTATION('',(#57483),#57487); +#57483 = LINE('',#57484,#57485); +#57484 = CARTESIAN_POINT('',(0.E+000,0.425735931288)); +#57485 = VECTOR('',#57486,1.); +#57486 = DIRECTION('',(1.,0.E+000)); +#57487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57488 = ADVANCED_FACE('',(#57489),#40280,.T.); +#57489 = FACE_BOUND('',#57490,.T.); +#57490 = EDGE_LOOP('',(#57491,#57492,#57512,#57513)); +#57491 = ORIENTED_EDGE('',*,*,#57110,.T.); +#57492 = ORIENTED_EDGE('',*,*,#57493,.T.); +#57493 = EDGE_CURVE('',#57111,#40236,#57494,.T.); +#57494 = SURFACE_CURVE('',#57495,(#57499,#57505),.PCURVE_S1.); +#57495 = LINE('',#57496,#57497); +#57496 = CARTESIAN_POINT('',(-2.596446609407,-1.225,0.96)); +#57497 = VECTOR('',#57498,1.); +#57498 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57499 = PCURVE('',#40280,#57500); +#57500 = DEFINITIONAL_REPRESENTATION('',(#57501),#57504); +#57501 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57502,#57503),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#55110 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#55111 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#55112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55113 = PCURVE('',#37859,#55114); -#55114 = DEFINITIONAL_REPRESENTATION('',(#55115),#55119); -#55115 = LINE('',#55116,#55117); -#55116 = CARTESIAN_POINT('',(0.E+000,3.31)); -#55117 = VECTOR('',#55118,1.); -#55118 = DIRECTION('',(0.E+000,1.)); -#55119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55120 = ORIENTED_EDGE('',*,*,#37871,.F.); -#55121 = ORIENTED_EDGE('',*,*,#54858,.F.); -#55122 = ADVANCED_FACE('',(#55123),#54977,.T.); -#55123 = FACE_BOUND('',#55124,.T.); -#55124 = EDGE_LOOP('',(#55125,#55148,#55170,#55195)); -#55125 = ORIENTED_EDGE('',*,*,#55126,.T.); -#55126 = EDGE_CURVE('',#54962,#55127,#55129,.T.); -#55127 = VERTEX_POINT('',#55128); -#55128 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); -#55129 = SURFACE_CURVE('',#55130,(#55135,#55141),.PCURVE_S1.); -#55130 = CIRCLE('',#55131,0.55); -#55131 = AXIS2_PLACEMENT_3D('',#55132,#55133,#55134); -#55132 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-1.53)); -#55133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55134 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); -#55135 = PCURVE('',#54977,#55136); -#55136 = DEFINITIONAL_REPRESENTATION('',(#55137),#55140); -#55137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55138,#55139),.UNSPECIFIED., +#57502 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#57503 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#57504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57505 = PCURVE('',#40251,#57506); +#57506 = DEFINITIONAL_REPRESENTATION('',(#57507),#57511); +#57507 = LINE('',#57508,#57509); +#57508 = CARTESIAN_POINT('',(0.E+000,3.31)); +#57509 = VECTOR('',#57510,1.); +#57510 = DIRECTION('',(0.E+000,1.)); +#57511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57512 = ORIENTED_EDGE('',*,*,#40263,.F.); +#57513 = ORIENTED_EDGE('',*,*,#57250,.F.); +#57514 = ADVANCED_FACE('',(#57515),#57369,.T.); +#57515 = FACE_BOUND('',#57516,.T.); +#57516 = EDGE_LOOP('',(#57517,#57540,#57562,#57587)); +#57517 = ORIENTED_EDGE('',*,*,#57518,.T.); +#57518 = EDGE_CURVE('',#57354,#57519,#57521,.T.); +#57519 = VERTEX_POINT('',#57520); +#57520 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); +#57521 = SURFACE_CURVE('',#57522,(#57527,#57533),.PCURVE_S1.); +#57522 = CIRCLE('',#57523,0.55); +#57523 = AXIS2_PLACEMENT_3D('',#57524,#57525,#57526); +#57524 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-1.53)); +#57525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57526 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); +#57527 = PCURVE('',#57369,#57528); +#57528 = DEFINITIONAL_REPRESENTATION('',(#57529),#57532); +#57529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57530,#57531),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163398),.PIECEWISE_BEZIER_KNOTS.); -#55138 = CARTESIAN_POINT('',(3.926990816987,0.82)); -#55139 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#55140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57530 = CARTESIAN_POINT('',(3.926990816987,0.82)); +#57531 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#57532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55141 = PCURVE('',#40920,#55142); -#55142 = DEFINITIONAL_REPRESENTATION('',(#55143),#55147); -#55143 = CIRCLE('',#55144,0.55); -#55144 = AXIS2_PLACEMENT_2D('',#55145,#55146); -#55145 = CARTESIAN_POINT('',(-0.2,1.153553390593)); -#55146 = DIRECTION('',(0.707106781186,-0.707106781187)); -#55147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57533 = PCURVE('',#43312,#57534); +#57534 = DEFINITIONAL_REPRESENTATION('',(#57535),#57539); +#57535 = CIRCLE('',#57536,0.55); +#57536 = AXIS2_PLACEMENT_2D('',#57537,#57538); +#57537 = CARTESIAN_POINT('',(-0.2,1.153553390593)); +#57538 = DIRECTION('',(0.707106781186,-0.707106781187)); +#57539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55148 = ORIENTED_EDGE('',*,*,#55149,.T.); -#55149 = EDGE_CURVE('',#55127,#55150,#55152,.T.); -#55150 = VERTEX_POINT('',#55151); -#55151 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-0.56)); -#55152 = SURFACE_CURVE('',#55153,(#55157,#55163),.PCURVE_S1.); -#55153 = LINE('',#55154,#55155); -#55154 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); -#55155 = VECTOR('',#55156,1.); -#55156 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55157 = PCURVE('',#54977,#55158); -#55158 = DEFINITIONAL_REPRESENTATION('',(#55159),#55162); -#55159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55160,#55161),.UNSPECIFIED., +#57540 = ORIENTED_EDGE('',*,*,#57541,.T.); +#57541 = EDGE_CURVE('',#57519,#57542,#57544,.T.); +#57542 = VERTEX_POINT('',#57543); +#57543 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-0.56)); +#57544 = SURFACE_CURVE('',#57545,(#57549,#57555),.PCURVE_S1.); +#57545 = LINE('',#57546,#57547); +#57546 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); +#57547 = VECTOR('',#57548,1.); +#57548 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57549 = PCURVE('',#57369,#57550); +#57550 = DEFINITIONAL_REPRESENTATION('',(#57551),#57554); +#57551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57552,#57553),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#55160 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#55161 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#55162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55163 = PCURVE('',#37859,#55164); -#55164 = DEFINITIONAL_REPRESENTATION('',(#55165),#55169); -#55165 = LINE('',#55166,#55167); -#55166 = CARTESIAN_POINT('',(0.E+000,0.82)); -#55167 = VECTOR('',#55168,1.); -#55168 = DIRECTION('',(0.E+000,1.)); -#55169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55170 = ORIENTED_EDGE('',*,*,#55171,.F.); -#55171 = EDGE_CURVE('',#54939,#55150,#55172,.T.); -#55172 = SURFACE_CURVE('',#55173,(#55178,#55184),.PCURVE_S1.); -#55173 = CIRCLE('',#55174,0.55); -#55174 = AXIS2_PLACEMENT_3D('',#55175,#55176,#55177); -#55175 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-0.56)); -#55176 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55177 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#55178 = PCURVE('',#54977,#55179); -#55179 = DEFINITIONAL_REPRESENTATION('',(#55180),#55183); -#55180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55181,#55182),.UNSPECIFIED., +#57552 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#57553 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#57554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57555 = PCURVE('',#40251,#57556); +#57556 = DEFINITIONAL_REPRESENTATION('',(#57557),#57561); +#57557 = LINE('',#57558,#57559); +#57558 = CARTESIAN_POINT('',(0.E+000,0.82)); +#57559 = VECTOR('',#57560,1.); +#57560 = DIRECTION('',(0.E+000,1.)); +#57561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57562 = ORIENTED_EDGE('',*,*,#57563,.F.); +#57563 = EDGE_CURVE('',#57331,#57542,#57564,.T.); +#57564 = SURFACE_CURVE('',#57565,(#57570,#57576),.PCURVE_S1.); +#57565 = CIRCLE('',#57566,0.55); +#57566 = AXIS2_PLACEMENT_3D('',#57567,#57568,#57569); +#57567 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-0.56)); +#57568 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57569 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#57570 = PCURVE('',#57369,#57571); +#57571 = DEFINITIONAL_REPRESENTATION('',(#57572),#57575); +#57572 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57573,#57574),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#55181 = CARTESIAN_POINT('',(3.926990816987,1.79)); -#55182 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#55183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57573 = CARTESIAN_POINT('',(3.926990816987,1.79)); +#57574 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#57575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55184 = PCURVE('',#42672,#55185); -#55185 = DEFINITIONAL_REPRESENTATION('',(#55186),#55194); -#55186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55187,#55188,#55189,#55190 - ,#55191,#55192,#55193),.UNSPECIFIED.,.F.,.F.) +#57576 = PCURVE('',#45064,#57577); +#57577 = DEFINITIONAL_REPRESENTATION('',(#57578),#57586); +#57578 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#57579,#57580,#57581,#57582 + ,#57583,#57584,#57585),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#55187 = CARTESIAN_POINT('',(0.76464466094,-0.161091270347)); -#55188 = CARTESIAN_POINT('',(1.438254340206,0.512518408918)); -#55189 = CARTESIAN_POINT('',(1.684812595052,-0.407649525194)); -#55190 = CARTESIAN_POINT('',(1.931370849898,-1.327817459305)); -#55191 = CARTESIAN_POINT('',(1.011202915787,-1.081259204459)); -#55192 = CARTESIAN_POINT('',(9.103498167503E-002,-0.834700949613)); -#55193 = CARTESIAN_POINT('',(0.76464466094,-0.161091270347)); -#55194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57579 = CARTESIAN_POINT('',(0.76464466094,-0.161091270347)); +#57580 = CARTESIAN_POINT('',(1.438254340206,0.512518408918)); +#57581 = CARTESIAN_POINT('',(1.684812595052,-0.407649525194)); +#57582 = CARTESIAN_POINT('',(1.931370849898,-1.327817459305)); +#57583 = CARTESIAN_POINT('',(1.011202915787,-1.081259204459)); +#57584 = CARTESIAN_POINT('',(9.103498167503E-002,-0.834700949613)); +#57585 = CARTESIAN_POINT('',(0.76464466094,-0.161091270347)); +#57586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57587 = ORIENTED_EDGE('',*,*,#57353,.F.); +#57588 = ADVANCED_FACE('',(#57589),#40251,.T.); +#57589 = FACE_BOUND('',#57590,.F.); +#57590 = EDGE_LOOP('',(#57591,#57621,#57649,#57672,#57700,#57728,#57756, + #57779,#57802,#57825,#57853,#57874,#57875,#57898,#57921,#57944, + #57971,#57994,#58017,#58040,#58063,#58086,#58113,#58136,#58157, + #58158,#58159,#58160,#58188,#58211)); +#57591 = ORIENTED_EDGE('',*,*,#57592,.T.); +#57592 = EDGE_CURVE('',#57593,#57595,#57597,.T.); +#57593 = VERTEX_POINT('',#57594); +#57594 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); +#57595 = VERTEX_POINT('',#57596); +#57596 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); +#57597 = SURFACE_CURVE('',#57598,(#57602,#57609),.PCURVE_S1.); +#57598 = LINE('',#57599,#57600); +#57599 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); +#57600 = VECTOR('',#57601,1.); +#57601 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57602 = PCURVE('',#40251,#57603); +#57603 = DEFINITIONAL_REPRESENTATION('',(#57604),#57608); +#57604 = LINE('',#57605,#57606); +#57605 = CARTESIAN_POINT('',(2.246446609407,4.35)); +#57606 = VECTOR('',#57607,1.); +#57607 = DIRECTION('',(0.E+000,-1.)); +#57608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57609 = PCURVE('',#57610,#57615); +#57610 = PLANE('',#57611); +#57611 = AXIS2_PLACEMENT_3D('',#57612,#57613,#57614); +#57612 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); +#57613 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57614 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57615 = DEFINITIONAL_REPRESENTATION('',(#57616),#57620); +#57616 = LINE('',#57617,#57618); +#57617 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57618 = VECTOR('',#57619,1.); +#57619 = DIRECTION('',(1.,0.E+000)); +#57620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57621 = ORIENTED_EDGE('',*,*,#57622,.T.); +#57622 = EDGE_CURVE('',#57595,#57623,#57625,.T.); +#57623 = VERTEX_POINT('',#57624); +#57624 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); +#57625 = SURFACE_CURVE('',#57626,(#57630,#57637),.PCURVE_S1.); +#57626 = LINE('',#57627,#57628); +#57627 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); +#57628 = VECTOR('',#57629,1.); +#57629 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57630 = PCURVE('',#40251,#57631); +#57631 = DEFINITIONAL_REPRESENTATION('',(#57632),#57636); +#57632 = LINE('',#57633,#57634); +#57633 = CARTESIAN_POINT('',(2.246446609407,3.9)); +#57634 = VECTOR('',#57635,1.); +#57635 = DIRECTION('',(1.,0.E+000)); +#57636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57637 = PCURVE('',#57638,#57643); +#57638 = PLANE('',#57639); +#57639 = AXIS2_PLACEMENT_3D('',#57640,#57641,#57642); +#57640 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); +#57641 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57642 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57643 = DEFINITIONAL_REPRESENTATION('',(#57644),#57648); +#57644 = LINE('',#57645,#57646); +#57645 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57646 = VECTOR('',#57647,1.); +#57647 = DIRECTION('',(1.,0.E+000)); +#57648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57649 = ORIENTED_EDGE('',*,*,#57650,.T.); +#57650 = EDGE_CURVE('',#57623,#57651,#57653,.T.); +#57651 = VERTEX_POINT('',#57652); +#57652 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); +#57653 = SURFACE_CURVE('',#57654,(#57658,#57665),.PCURVE_S1.); +#57654 = LINE('',#57655,#57656); +#57655 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); +#57656 = VECTOR('',#57657,1.); +#57657 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57658 = PCURVE('',#40251,#57659); +#57659 = DEFINITIONAL_REPRESENTATION('',(#57660),#57664); +#57660 = LINE('',#57661,#57662); +#57661 = CARTESIAN_POINT('',(3.386446609407,3.9)); +#57662 = VECTOR('',#57663,1.); +#57663 = DIRECTION('',(0.E+000,-1.)); +#57664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57665 = PCURVE('',#44493,#57666); +#57666 = DEFINITIONAL_REPRESENTATION('',(#57667),#57671); +#57667 = LINE('',#57668,#57669); +#57668 = CARTESIAN_POINT('',(0.17484542651,-0.3)); +#57669 = VECTOR('',#57670,1.); +#57670 = DIRECTION('',(1.,0.E+000)); +#57671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57672 = ORIENTED_EDGE('',*,*,#57673,.T.); +#57673 = EDGE_CURVE('',#57651,#57674,#57676,.T.); +#57674 = VERTEX_POINT('',#57675); +#57675 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); +#57676 = SURFACE_CURVE('',#57677,(#57681,#57688),.PCURVE_S1.); +#57677 = LINE('',#57678,#57679); +#57678 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); +#57679 = VECTOR('',#57680,1.); +#57680 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57681 = PCURVE('',#40251,#57682); +#57682 = DEFINITIONAL_REPRESENTATION('',(#57683),#57687); +#57683 = LINE('',#57684,#57685); +#57684 = CARTESIAN_POINT('',(3.386446609407,2.15)); +#57685 = VECTOR('',#57686,1.); +#57686 = DIRECTION('',(-1.,0.E+000)); +#57687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57688 = PCURVE('',#57689,#57694); +#57689 = PLANE('',#57690); +#57690 = AXIS2_PLACEMENT_3D('',#57691,#57692,#57693); +#57691 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); +#57692 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57693 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57694 = DEFINITIONAL_REPRESENTATION('',(#57695),#57699); +#57695 = LINE('',#57696,#57697); +#57696 = CARTESIAN_POINT('',(0.71,0.E+000)); +#57697 = VECTOR('',#57698,1.); +#57698 = DIRECTION('',(1.,0.E+000)); +#57699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57700 = ORIENTED_EDGE('',*,*,#57701,.T.); +#57701 = EDGE_CURVE('',#57674,#57702,#57704,.T.); +#57702 = VERTEX_POINT('',#57703); +#57703 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); +#57704 = SURFACE_CURVE('',#57705,(#57709,#57716),.PCURVE_S1.); +#57705 = LINE('',#57706,#57707); +#57706 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); +#57707 = VECTOR('',#57708,1.); +#57708 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57709 = PCURVE('',#40251,#57710); +#57710 = DEFINITIONAL_REPRESENTATION('',(#57711),#57715); +#57711 = LINE('',#57712,#57713); +#57712 = CARTESIAN_POINT('',(2.246446609407,2.15)); +#57713 = VECTOR('',#57714,1.); +#57714 = DIRECTION('',(0.E+000,-1.)); +#57715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57716 = PCURVE('',#57717,#57722); +#57717 = PLANE('',#57718); +#57718 = AXIS2_PLACEMENT_3D('',#57719,#57720,#57721); +#57719 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); +#57720 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57721 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57722 = DEFINITIONAL_REPRESENTATION('',(#57723),#57727); +#57723 = LINE('',#57724,#57725); +#57724 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57725 = VECTOR('',#57726,1.); +#57726 = DIRECTION('',(1.,0.E+000)); +#57727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57728 = ORIENTED_EDGE('',*,*,#57729,.T.); +#57729 = EDGE_CURVE('',#57702,#57730,#57732,.T.); +#57730 = VERTEX_POINT('',#57731); +#57731 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); +#57732 = SURFACE_CURVE('',#57733,(#57737,#57744),.PCURVE_S1.); +#57733 = LINE('',#57734,#57735); +#57734 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); +#57735 = VECTOR('',#57736,1.); +#57736 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57737 = PCURVE('',#40251,#57738); +#57738 = DEFINITIONAL_REPRESENTATION('',(#57739),#57743); +#57739 = LINE('',#57740,#57741); +#57740 = CARTESIAN_POINT('',(2.246446609407,1.7)); +#57741 = VECTOR('',#57742,1.); +#57742 = DIRECTION('',(1.,0.E+000)); +#57743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57744 = PCURVE('',#57745,#57750); +#57745 = PLANE('',#57746); +#57746 = AXIS2_PLACEMENT_3D('',#57747,#57748,#57749); +#57747 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); +#57748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57749 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57750 = DEFINITIONAL_REPRESENTATION('',(#57751),#57755); +#57751 = LINE('',#57752,#57753); +#57752 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57753 = VECTOR('',#57754,1.); +#57754 = DIRECTION('',(1.,0.E+000)); +#57755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57756 = ORIENTED_EDGE('',*,*,#57757,.T.); +#57757 = EDGE_CURVE('',#57730,#57758,#57760,.T.); +#57758 = VERTEX_POINT('',#57759); +#57759 = CARTESIAN_POINT('',(-1.E-002,-1.225,-1.13)); +#57760 = SURFACE_CURVE('',#57761,(#57765,#57772),.PCURVE_S1.); +#57761 = LINE('',#57762,#57763); +#57762 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); +#57763 = VECTOR('',#57764,1.); +#57764 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57765 = PCURVE('',#40251,#57766); +#57766 = DEFINITIONAL_REPRESENTATION('',(#57767),#57771); +#57767 = LINE('',#57768,#57769); +#57768 = CARTESIAN_POINT('',(2.586446609407,1.7)); +#57769 = VECTOR('',#57770,1.); +#57770 = DIRECTION('',(0.E+000,-1.)); +#57771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57772 = PCURVE('',#44373,#57773); +#57773 = DEFINITIONAL_REPRESENTATION('',(#57774),#57778); +#57774 = LINE('',#57775,#57776); +#57775 = CARTESIAN_POINT('',(0.22484542651,-0.3)); +#57776 = VECTOR('',#57777,1.); +#57777 = DIRECTION('',(1.,0.E+000)); +#57778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57779 = ORIENTED_EDGE('',*,*,#57780,.T.); +#57780 = EDGE_CURVE('',#57758,#57781,#57783,.T.); +#57781 = VERTEX_POINT('',#57782); +#57782 = CARTESIAN_POINT('',(-1.71,-1.225,-1.13)); +#57783 = SURFACE_CURVE('',#57784,(#57788,#57795),.PCURVE_S1.); +#57784 = LINE('',#57785,#57786); +#57785 = CARTESIAN_POINT('',(-1.E-002,-1.225,-1.13)); +#57786 = VECTOR('',#57787,1.); +#57787 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57788 = PCURVE('',#40251,#57789); +#57789 = DEFINITIONAL_REPRESENTATION('',(#57790),#57794); +#57790 = LINE('',#57791,#57792); +#57791 = CARTESIAN_POINT('',(2.586446609407,1.22)); +#57792 = VECTOR('',#57793,1.); +#57793 = DIRECTION('',(-1.,0.E+000)); +#57794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57795 = PCURVE('',#44345,#57796); +#57796 = DEFINITIONAL_REPRESENTATION('',(#57797),#57801); +#57797 = LINE('',#57798,#57799); +#57798 = CARTESIAN_POINT('',(1.72,0.E+000)); +#57799 = VECTOR('',#57800,1.); +#57800 = DIRECTION('',(1.,0.E+000)); +#57801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57802 = ORIENTED_EDGE('',*,*,#57803,.T.); +#57803 = EDGE_CURVE('',#57781,#57804,#57806,.T.); +#57804 = VERTEX_POINT('',#57805); +#57805 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); +#57806 = SURFACE_CURVE('',#57807,(#57812,#57819),.PCURVE_S1.); +#57807 = CIRCLE('',#57808,8.E-002); +#57808 = AXIS2_PLACEMENT_3D('',#57809,#57810,#57811); +#57809 = CARTESIAN_POINT('',(-1.71,-1.225,-1.21)); +#57810 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#57811 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57812 = PCURVE('',#40251,#57813); +#57813 = DEFINITIONAL_REPRESENTATION('',(#57814),#57818); +#57814 = CIRCLE('',#57815,8.E-002); +#57815 = AXIS2_PLACEMENT_2D('',#57816,#57817); +#57816 = CARTESIAN_POINT('',(0.886446609407,1.14)); +#57817 = DIRECTION('',(0.E+000,1.)); +#57818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57819 = PCURVE('',#44318,#57820); +#57820 = DEFINITIONAL_REPRESENTATION('',(#57821),#57824); +#57821 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57822,#57823),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#57822 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#57823 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#57824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57825 = ORIENTED_EDGE('',*,*,#57826,.F.); +#57826 = EDGE_CURVE('',#57827,#57804,#57829,.T.); +#57827 = VERTEX_POINT('',#57828); +#57828 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); +#57829 = SURFACE_CURVE('',#57830,(#57834,#57841),.PCURVE_S1.); +#57830 = LINE('',#57831,#57832); +#57831 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); +#57832 = VECTOR('',#57833,1.); +#57833 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57834 = PCURVE('',#40251,#57835); +#57835 = DEFINITIONAL_REPRESENTATION('',(#57836),#57840); +#57836 = LINE('',#57837,#57838); +#57837 = CARTESIAN_POINT('',(0.806446609407,0.82)); +#57838 = VECTOR('',#57839,1.); +#57839 = DIRECTION('',(0.E+000,1.)); +#57840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57841 = PCURVE('',#57842,#57847); +#57842 = PLANE('',#57843); +#57843 = AXIS2_PLACEMENT_3D('',#57844,#57845,#57846); +#57844 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); +#57845 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#57846 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57847 = DEFINITIONAL_REPRESENTATION('',(#57848),#57852); +#57848 = LINE('',#57849,#57850); +#57849 = CARTESIAN_POINT('',(0.32,0.E+000)); +#57850 = VECTOR('',#57851,1.); +#57851 = DIRECTION('',(-1.,0.E+000)); +#57852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55195 = ORIENTED_EDGE('',*,*,#54961,.F.); -#55196 = ADVANCED_FACE('',(#55197),#37859,.T.); -#55197 = FACE_BOUND('',#55198,.F.); -#55198 = EDGE_LOOP('',(#55199,#55229,#55257,#55280,#55308,#55336,#55364, - #55387,#55410,#55433,#55461,#55482,#55483,#55506,#55529,#55552, - #55579,#55602,#55625,#55648,#55671,#55694,#55721,#55744,#55765, - #55766,#55767,#55768,#55796,#55819)); -#55199 = ORIENTED_EDGE('',*,*,#55200,.T.); -#55200 = EDGE_CURVE('',#55201,#55203,#55205,.T.); -#55201 = VERTEX_POINT('',#55202); -#55202 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); -#55203 = VERTEX_POINT('',#55204); -#55204 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); -#55205 = SURFACE_CURVE('',#55206,(#55210,#55217),.PCURVE_S1.); -#55206 = LINE('',#55207,#55208); -#55207 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); -#55208 = VECTOR('',#55209,1.); -#55209 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55210 = PCURVE('',#37859,#55211); -#55211 = DEFINITIONAL_REPRESENTATION('',(#55212),#55216); -#55212 = LINE('',#55213,#55214); -#55213 = CARTESIAN_POINT('',(2.246446609407,4.35)); -#55214 = VECTOR('',#55215,1.); -#55215 = DIRECTION('',(0.E+000,-1.)); -#55216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55217 = PCURVE('',#55218,#55223); -#55218 = PLANE('',#55219); -#55219 = AXIS2_PLACEMENT_3D('',#55220,#55221,#55222); -#55220 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); -#55221 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55222 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55223 = DEFINITIONAL_REPRESENTATION('',(#55224),#55228); -#55224 = LINE('',#55225,#55226); -#55225 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55226 = VECTOR('',#55227,1.); -#55227 = DIRECTION('',(1.,0.E+000)); -#55228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55229 = ORIENTED_EDGE('',*,*,#55230,.T.); -#55230 = EDGE_CURVE('',#55203,#55231,#55233,.T.); -#55231 = VERTEX_POINT('',#55232); -#55232 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); -#55233 = SURFACE_CURVE('',#55234,(#55238,#55245),.PCURVE_S1.); -#55234 = LINE('',#55235,#55236); -#55235 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); -#55236 = VECTOR('',#55237,1.); -#55237 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55238 = PCURVE('',#37859,#55239); -#55239 = DEFINITIONAL_REPRESENTATION('',(#55240),#55244); -#55240 = LINE('',#55241,#55242); -#55241 = CARTESIAN_POINT('',(2.246446609407,3.9)); -#55242 = VECTOR('',#55243,1.); -#55243 = DIRECTION('',(1.,0.E+000)); -#55244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55245 = PCURVE('',#55246,#55251); -#55246 = PLANE('',#55247); -#55247 = AXIS2_PLACEMENT_3D('',#55248,#55249,#55250); -#55248 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); -#55249 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55250 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55251 = DEFINITIONAL_REPRESENTATION('',(#55252),#55256); -#55252 = LINE('',#55253,#55254); -#55253 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55254 = VECTOR('',#55255,1.); -#55255 = DIRECTION('',(1.,0.E+000)); -#55256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55257 = ORIENTED_EDGE('',*,*,#55258,.T.); -#55258 = EDGE_CURVE('',#55231,#55259,#55261,.T.); -#55259 = VERTEX_POINT('',#55260); -#55260 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); -#55261 = SURFACE_CURVE('',#55262,(#55266,#55273),.PCURVE_S1.); -#55262 = LINE('',#55263,#55264); -#55263 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); -#55264 = VECTOR('',#55265,1.); -#55265 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55266 = PCURVE('',#37859,#55267); -#55267 = DEFINITIONAL_REPRESENTATION('',(#55268),#55272); -#55268 = LINE('',#55269,#55270); -#55269 = CARTESIAN_POINT('',(3.386446609407,3.9)); -#55270 = VECTOR('',#55271,1.); -#55271 = DIRECTION('',(0.E+000,-1.)); -#55272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55273 = PCURVE('',#42101,#55274); -#55274 = DEFINITIONAL_REPRESENTATION('',(#55275),#55279); -#55275 = LINE('',#55276,#55277); -#55276 = CARTESIAN_POINT('',(0.17484542651,-0.3)); -#55277 = VECTOR('',#55278,1.); -#55278 = DIRECTION('',(1.,0.E+000)); -#55279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55280 = ORIENTED_EDGE('',*,*,#55281,.T.); -#55281 = EDGE_CURVE('',#55259,#55282,#55284,.T.); -#55282 = VERTEX_POINT('',#55283); -#55283 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); -#55284 = SURFACE_CURVE('',#55285,(#55289,#55296),.PCURVE_S1.); -#55285 = LINE('',#55286,#55287); -#55286 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); -#55287 = VECTOR('',#55288,1.); -#55288 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55289 = PCURVE('',#37859,#55290); -#55290 = DEFINITIONAL_REPRESENTATION('',(#55291),#55295); -#55291 = LINE('',#55292,#55293); -#55292 = CARTESIAN_POINT('',(3.386446609407,2.15)); -#55293 = VECTOR('',#55294,1.); -#55294 = DIRECTION('',(-1.,0.E+000)); -#55295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55296 = PCURVE('',#55297,#55302); -#55297 = PLANE('',#55298); -#55298 = AXIS2_PLACEMENT_3D('',#55299,#55300,#55301); -#55299 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); -#55300 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55301 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55302 = DEFINITIONAL_REPRESENTATION('',(#55303),#55307); -#55303 = LINE('',#55304,#55305); -#55304 = CARTESIAN_POINT('',(0.71,0.E+000)); -#55305 = VECTOR('',#55306,1.); -#55306 = DIRECTION('',(1.,0.E+000)); -#55307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55308 = ORIENTED_EDGE('',*,*,#55309,.T.); -#55309 = EDGE_CURVE('',#55282,#55310,#55312,.T.); -#55310 = VERTEX_POINT('',#55311); -#55311 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); -#55312 = SURFACE_CURVE('',#55313,(#55317,#55324),.PCURVE_S1.); -#55313 = LINE('',#55314,#55315); -#55314 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); -#55315 = VECTOR('',#55316,1.); -#55316 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55317 = PCURVE('',#37859,#55318); -#55318 = DEFINITIONAL_REPRESENTATION('',(#55319),#55323); -#55319 = LINE('',#55320,#55321); -#55320 = CARTESIAN_POINT('',(2.246446609407,2.15)); -#55321 = VECTOR('',#55322,1.); -#55322 = DIRECTION('',(0.E+000,-1.)); -#55323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55324 = PCURVE('',#55325,#55330); -#55325 = PLANE('',#55326); -#55326 = AXIS2_PLACEMENT_3D('',#55327,#55328,#55329); -#55327 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); -#55328 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55329 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55330 = DEFINITIONAL_REPRESENTATION('',(#55331),#55335); -#55331 = LINE('',#55332,#55333); -#55332 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55333 = VECTOR('',#55334,1.); -#55334 = DIRECTION('',(1.,0.E+000)); -#55335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55336 = ORIENTED_EDGE('',*,*,#55337,.T.); -#55337 = EDGE_CURVE('',#55310,#55338,#55340,.T.); -#55338 = VERTEX_POINT('',#55339); -#55339 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); -#55340 = SURFACE_CURVE('',#55341,(#55345,#55352),.PCURVE_S1.); -#55341 = LINE('',#55342,#55343); -#55342 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); -#55343 = VECTOR('',#55344,1.); -#55344 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55345 = PCURVE('',#37859,#55346); -#55346 = DEFINITIONAL_REPRESENTATION('',(#55347),#55351); -#55347 = LINE('',#55348,#55349); -#55348 = CARTESIAN_POINT('',(2.246446609407,1.7)); -#55349 = VECTOR('',#55350,1.); -#55350 = DIRECTION('',(1.,0.E+000)); -#55351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55352 = PCURVE('',#55353,#55358); -#55353 = PLANE('',#55354); -#55354 = AXIS2_PLACEMENT_3D('',#55355,#55356,#55357); -#55355 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); -#55356 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55357 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55358 = DEFINITIONAL_REPRESENTATION('',(#55359),#55363); -#55359 = LINE('',#55360,#55361); -#55360 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55361 = VECTOR('',#55362,1.); -#55362 = DIRECTION('',(1.,0.E+000)); -#55363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55364 = ORIENTED_EDGE('',*,*,#55365,.T.); -#55365 = EDGE_CURVE('',#55338,#55366,#55368,.T.); -#55366 = VERTEX_POINT('',#55367); -#55367 = CARTESIAN_POINT('',(-1.E-002,-1.225,-1.13)); -#55368 = SURFACE_CURVE('',#55369,(#55373,#55380),.PCURVE_S1.); -#55369 = LINE('',#55370,#55371); -#55370 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); -#55371 = VECTOR('',#55372,1.); -#55372 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55373 = PCURVE('',#37859,#55374); -#55374 = DEFINITIONAL_REPRESENTATION('',(#55375),#55379); -#55375 = LINE('',#55376,#55377); -#55376 = CARTESIAN_POINT('',(2.586446609407,1.7)); -#55377 = VECTOR('',#55378,1.); -#55378 = DIRECTION('',(0.E+000,-1.)); -#55379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55380 = PCURVE('',#41981,#55381); -#55381 = DEFINITIONAL_REPRESENTATION('',(#55382),#55386); -#55382 = LINE('',#55383,#55384); -#55383 = CARTESIAN_POINT('',(0.22484542651,-0.3)); -#55384 = VECTOR('',#55385,1.); -#55385 = DIRECTION('',(1.,0.E+000)); -#55386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55387 = ORIENTED_EDGE('',*,*,#55388,.T.); -#55388 = EDGE_CURVE('',#55366,#55389,#55391,.T.); -#55389 = VERTEX_POINT('',#55390); -#55390 = CARTESIAN_POINT('',(-1.71,-1.225,-1.13)); -#55391 = SURFACE_CURVE('',#55392,(#55396,#55403),.PCURVE_S1.); -#55392 = LINE('',#55393,#55394); -#55393 = CARTESIAN_POINT('',(-1.E-002,-1.225,-1.13)); -#55394 = VECTOR('',#55395,1.); -#55395 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55396 = PCURVE('',#37859,#55397); -#55397 = DEFINITIONAL_REPRESENTATION('',(#55398),#55402); -#55398 = LINE('',#55399,#55400); -#55399 = CARTESIAN_POINT('',(2.586446609407,1.22)); -#55400 = VECTOR('',#55401,1.); -#55401 = DIRECTION('',(-1.,0.E+000)); -#55402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55403 = PCURVE('',#41953,#55404); -#55404 = DEFINITIONAL_REPRESENTATION('',(#55405),#55409); -#55405 = LINE('',#55406,#55407); -#55406 = CARTESIAN_POINT('',(1.72,0.E+000)); -#55407 = VECTOR('',#55408,1.); -#55408 = DIRECTION('',(1.,0.E+000)); -#55409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55410 = ORIENTED_EDGE('',*,*,#55411,.T.); -#55411 = EDGE_CURVE('',#55389,#55412,#55414,.T.); -#55412 = VERTEX_POINT('',#55413); -#55413 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); -#55414 = SURFACE_CURVE('',#55415,(#55420,#55427),.PCURVE_S1.); -#55415 = CIRCLE('',#55416,8.E-002); -#55416 = AXIS2_PLACEMENT_3D('',#55417,#55418,#55419); -#55417 = CARTESIAN_POINT('',(-1.71,-1.225,-1.21)); -#55418 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#55419 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55420 = PCURVE('',#37859,#55421); -#55421 = DEFINITIONAL_REPRESENTATION('',(#55422),#55426); -#55422 = CIRCLE('',#55423,8.E-002); -#55423 = AXIS2_PLACEMENT_2D('',#55424,#55425); -#55424 = CARTESIAN_POINT('',(0.886446609407,1.14)); -#55425 = DIRECTION('',(0.E+000,1.)); -#55426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55427 = PCURVE('',#41926,#55428); -#55428 = DEFINITIONAL_REPRESENTATION('',(#55429),#55432); -#55429 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55430,#55431),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55430 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#55431 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#55432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55433 = ORIENTED_EDGE('',*,*,#55434,.F.); -#55434 = EDGE_CURVE('',#55435,#55412,#55437,.T.); -#55435 = VERTEX_POINT('',#55436); -#55436 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); -#55437 = SURFACE_CURVE('',#55438,(#55442,#55449),.PCURVE_S1.); -#55438 = LINE('',#55439,#55440); -#55439 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); -#55440 = VECTOR('',#55441,1.); -#55441 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55442 = PCURVE('',#37859,#55443); -#55443 = DEFINITIONAL_REPRESENTATION('',(#55444),#55448); -#55444 = LINE('',#55445,#55446); -#55445 = CARTESIAN_POINT('',(0.806446609407,0.82)); -#55446 = VECTOR('',#55447,1.); -#55447 = DIRECTION('',(0.E+000,1.)); -#55448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55449 = PCURVE('',#55450,#55455); -#55450 = PLANE('',#55451); -#55451 = AXIS2_PLACEMENT_3D('',#55452,#55453,#55454); -#55452 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); -#55453 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55454 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55455 = DEFINITIONAL_REPRESENTATION('',(#55456),#55460); -#55456 = LINE('',#55457,#55458); -#55457 = CARTESIAN_POINT('',(0.32,0.E+000)); -#55458 = VECTOR('',#55459,1.); -#55459 = DIRECTION('',(-1.,0.E+000)); -#55460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55461 = ORIENTED_EDGE('',*,*,#55462,.F.); -#55462 = EDGE_CURVE('',#55127,#55435,#55463,.T.); -#55463 = SURFACE_CURVE('',#55464,(#55468,#55475),.PCURVE_S1.); -#55464 = LINE('',#55465,#55466); -#55465 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); -#55466 = VECTOR('',#55467,1.); -#55467 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55468 = PCURVE('',#37859,#55469); -#55469 = DEFINITIONAL_REPRESENTATION('',(#55470),#55474); -#55470 = LINE('',#55471,#55472); -#55471 = CARTESIAN_POINT('',(0.E+000,0.82)); -#55472 = VECTOR('',#55473,1.); -#55473 = DIRECTION('',(1.,0.E+000)); -#55474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55475 = PCURVE('',#40920,#55476); -#55476 = DEFINITIONAL_REPRESENTATION('',(#55477),#55481); -#55477 = LINE('',#55478,#55479); -#55478 = CARTESIAN_POINT('',(0.35,1.153553390593)); -#55479 = VECTOR('',#55480,1.); -#55480 = DIRECTION('',(0.E+000,1.)); -#55481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55482 = ORIENTED_EDGE('',*,*,#55149,.T.); -#55483 = ORIENTED_EDGE('',*,*,#55484,.T.); -#55484 = EDGE_CURVE('',#55150,#55485,#55487,.T.); -#55485 = VERTEX_POINT('',#55486); -#55486 = CARTESIAN_POINT('',(-2.4,-1.225,-0.56)); -#55487 = SURFACE_CURVE('',#55488,(#55492,#55499),.PCURVE_S1.); -#55488 = LINE('',#55489,#55490); -#55489 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-0.56)); -#55490 = VECTOR('',#55491,1.); -#55491 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55492 = PCURVE('',#37859,#55493); -#55493 = DEFINITIONAL_REPRESENTATION('',(#55494),#55498); -#55494 = LINE('',#55495,#55496); -#55495 = CARTESIAN_POINT('',(0.E+000,1.79)); -#55496 = VECTOR('',#55497,1.); -#55497 = DIRECTION('',(1.,0.E+000)); -#55498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55499 = PCURVE('',#42672,#55500); -#55500 = DEFINITIONAL_REPRESENTATION('',(#55501),#55505); -#55501 = LINE('',#55502,#55503); -#55502 = CARTESIAN_POINT('',(1.153553390593,0.E+000)); -#55503 = VECTOR('',#55504,1.); -#55504 = DIRECTION('',(1.,0.E+000)); -#55505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55506 = ORIENTED_EDGE('',*,*,#55507,.T.); -#55507 = EDGE_CURVE('',#55485,#55508,#55510,.T.); -#55508 = VERTEX_POINT('',#55509); -#55509 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); -#55510 = SURFACE_CURVE('',#55511,(#55516,#55523),.PCURVE_S1.); -#55511 = CIRCLE('',#55512,0.15); -#55512 = AXIS2_PLACEMENT_3D('',#55513,#55514,#55515); -#55513 = CARTESIAN_POINT('',(-2.4,-1.225,-0.41)); -#55514 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#55515 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55516 = PCURVE('',#37859,#55517); -#55517 = DEFINITIONAL_REPRESENTATION('',(#55518),#55522); -#55518 = CIRCLE('',#55519,0.15); -#55519 = AXIS2_PLACEMENT_2D('',#55520,#55521); -#55520 = CARTESIAN_POINT('',(0.196446609407,1.94)); -#55521 = DIRECTION('',(0.E+000,-1.)); -#55522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55523 = PCURVE('',#42645,#55524); -#55524 = DEFINITIONAL_REPRESENTATION('',(#55525),#55528); -#55525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55526,#55527),.UNSPECIFIED., +#57853 = ORIENTED_EDGE('',*,*,#57854,.F.); +#57854 = EDGE_CURVE('',#57519,#57827,#57855,.T.); +#57855 = SURFACE_CURVE('',#57856,(#57860,#57867),.PCURVE_S1.); +#57856 = LINE('',#57857,#57858); +#57857 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-1.53)); +#57858 = VECTOR('',#57859,1.); +#57859 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57860 = PCURVE('',#40251,#57861); +#57861 = DEFINITIONAL_REPRESENTATION('',(#57862),#57866); +#57862 = LINE('',#57863,#57864); +#57863 = CARTESIAN_POINT('',(0.E+000,0.82)); +#57864 = VECTOR('',#57865,1.); +#57865 = DIRECTION('',(1.,0.E+000)); +#57866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57867 = PCURVE('',#43312,#57868); +#57868 = DEFINITIONAL_REPRESENTATION('',(#57869),#57873); +#57869 = LINE('',#57870,#57871); +#57870 = CARTESIAN_POINT('',(0.35,1.153553390593)); +#57871 = VECTOR('',#57872,1.); +#57872 = DIRECTION('',(0.E+000,1.)); +#57873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57874 = ORIENTED_EDGE('',*,*,#57541,.T.); +#57875 = ORIENTED_EDGE('',*,*,#57876,.T.); +#57876 = EDGE_CURVE('',#57542,#57877,#57879,.T.); +#57877 = VERTEX_POINT('',#57878); +#57878 = CARTESIAN_POINT('',(-2.4,-1.225,-0.56)); +#57879 = SURFACE_CURVE('',#57880,(#57884,#57891),.PCURVE_S1.); +#57880 = LINE('',#57881,#57882); +#57881 = CARTESIAN_POINT('',(-2.596446609407,-1.225,-0.56)); +#57882 = VECTOR('',#57883,1.); +#57883 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57884 = PCURVE('',#40251,#57885); +#57885 = DEFINITIONAL_REPRESENTATION('',(#57886),#57890); +#57886 = LINE('',#57887,#57888); +#57887 = CARTESIAN_POINT('',(0.E+000,1.79)); +#57888 = VECTOR('',#57889,1.); +#57889 = DIRECTION('',(1.,0.E+000)); +#57890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57891 = PCURVE('',#45064,#57892); +#57892 = DEFINITIONAL_REPRESENTATION('',(#57893),#57897); +#57893 = LINE('',#57894,#57895); +#57894 = CARTESIAN_POINT('',(1.153553390593,0.E+000)); +#57895 = VECTOR('',#57896,1.); +#57896 = DIRECTION('',(1.,0.E+000)); +#57897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57898 = ORIENTED_EDGE('',*,*,#57899,.T.); +#57899 = EDGE_CURVE('',#57877,#57900,#57902,.T.); +#57900 = VERTEX_POINT('',#57901); +#57901 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); +#57902 = SURFACE_CURVE('',#57903,(#57908,#57915),.PCURVE_S1.); +#57903 = CIRCLE('',#57904,0.15); +#57904 = AXIS2_PLACEMENT_3D('',#57905,#57906,#57907); +#57905 = CARTESIAN_POINT('',(-2.4,-1.225,-0.41)); +#57906 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#57907 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#57908 = PCURVE('',#40251,#57909); +#57909 = DEFINITIONAL_REPRESENTATION('',(#57910),#57914); +#57910 = CIRCLE('',#57911,0.15); +#57911 = AXIS2_PLACEMENT_2D('',#57912,#57913); +#57912 = CARTESIAN_POINT('',(0.196446609407,1.94)); +#57913 = DIRECTION('',(0.E+000,-1.)); +#57914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57915 = PCURVE('',#45037,#57916); +#57916 = DEFINITIONAL_REPRESENTATION('',(#57917),#57920); +#57917 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57918,#57919),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55526 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#55527 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#55528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55529 = ORIENTED_EDGE('',*,*,#55530,.T.); -#55530 = EDGE_CURVE('',#55508,#55531,#55533,.T.); -#55531 = VERTEX_POINT('',#55532); -#55532 = CARTESIAN_POINT('',(-2.25,-1.225,-0.4)); -#55533 = SURFACE_CURVE('',#55534,(#55538,#55545),.PCURVE_S1.); -#55534 = LINE('',#55535,#55536); -#55535 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); -#55536 = VECTOR('',#55537,1.); -#55537 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55538 = PCURVE('',#37859,#55539); -#55539 = DEFINITIONAL_REPRESENTATION('',(#55540),#55544); -#55540 = LINE('',#55541,#55542); -#55541 = CARTESIAN_POINT('',(0.346446609407,1.94)); -#55542 = VECTOR('',#55543,1.); -#55543 = DIRECTION('',(0.E+000,1.)); -#55544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55545 = PCURVE('',#42612,#55546); -#55546 = DEFINITIONAL_REPRESENTATION('',(#55547),#55551); -#55547 = LINE('',#55548,#55549); -#55548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55549 = VECTOR('',#55550,1.); -#55550 = DIRECTION('',(1.,0.E+000)); -#55551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55552 = ORIENTED_EDGE('',*,*,#55553,.F.); -#55553 = EDGE_CURVE('',#55554,#55531,#55556,.T.); -#55554 = VERTEX_POINT('',#55555); -#55555 = CARTESIAN_POINT('',(-2.4,-1.225,-0.25)); -#55556 = SURFACE_CURVE('',#55557,(#55562,#55573),.PCURVE_S1.); -#55557 = CIRCLE('',#55558,0.15); -#55558 = AXIS2_PLACEMENT_3D('',#55559,#55560,#55561); -#55559 = CARTESIAN_POINT('',(-2.4,-1.225,-0.4)); -#55560 = DIRECTION('',(0.E+000,1.,0.E+000)); -#55561 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55562 = PCURVE('',#37859,#55563); -#55563 = DEFINITIONAL_REPRESENTATION('',(#55564),#55572); -#55564 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55565,#55566,#55567,#55568 - ,#55569,#55570,#55571),.UNSPECIFIED.,.T.,.F.) +#57918 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#57919 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#57920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57921 = ORIENTED_EDGE('',*,*,#57922,.T.); +#57922 = EDGE_CURVE('',#57900,#57923,#57925,.T.); +#57923 = VERTEX_POINT('',#57924); +#57924 = CARTESIAN_POINT('',(-2.25,-1.225,-0.4)); +#57925 = SURFACE_CURVE('',#57926,(#57930,#57937),.PCURVE_S1.); +#57926 = LINE('',#57927,#57928); +#57927 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); +#57928 = VECTOR('',#57929,1.); +#57929 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57930 = PCURVE('',#40251,#57931); +#57931 = DEFINITIONAL_REPRESENTATION('',(#57932),#57936); +#57932 = LINE('',#57933,#57934); +#57933 = CARTESIAN_POINT('',(0.346446609407,1.94)); +#57934 = VECTOR('',#57935,1.); +#57935 = DIRECTION('',(0.E+000,1.)); +#57936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57937 = PCURVE('',#45004,#57938); +#57938 = DEFINITIONAL_REPRESENTATION('',(#57939),#57943); +#57939 = LINE('',#57940,#57941); +#57940 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57941 = VECTOR('',#57942,1.); +#57942 = DIRECTION('',(1.,0.E+000)); +#57943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57944 = ORIENTED_EDGE('',*,*,#57945,.F.); +#57945 = EDGE_CURVE('',#57946,#57923,#57948,.T.); +#57946 = VERTEX_POINT('',#57947); +#57947 = CARTESIAN_POINT('',(-2.4,-1.225,-0.25)); +#57948 = SURFACE_CURVE('',#57949,(#57954,#57965),.PCURVE_S1.); +#57949 = CIRCLE('',#57950,0.15); +#57950 = AXIS2_PLACEMENT_3D('',#57951,#57952,#57953); +#57951 = CARTESIAN_POINT('',(-2.4,-1.225,-0.4)); +#57952 = DIRECTION('',(0.E+000,1.,0.E+000)); +#57953 = DIRECTION('',(0.E+000,0.E+000,1.)); +#57954 = PCURVE('',#40251,#57955); +#57955 = DEFINITIONAL_REPRESENTATION('',(#57956),#57964); +#57956 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#57957,#57958,#57959,#57960 + ,#57961,#57962,#57963),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#55565 = CARTESIAN_POINT('',(0.196446609407,2.1)); -#55566 = CARTESIAN_POINT('',(0.456254230542,2.1)); -#55567 = CARTESIAN_POINT('',(0.326350419975,1.875)); -#55568 = CARTESIAN_POINT('',(0.196446609407,1.65)); -#55569 = CARTESIAN_POINT('',(6.654279883933E-002,1.875)); -#55570 = CARTESIAN_POINT('',(-6.336101172833E-002,2.1)); -#55571 = CARTESIAN_POINT('',(0.196446609407,2.1)); -#55572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55573 = PCURVE('',#42585,#55574); -#55574 = DEFINITIONAL_REPRESENTATION('',(#55575),#55578); -#55575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55576,#55577),.UNSPECIFIED., +#57957 = CARTESIAN_POINT('',(0.196446609407,2.1)); +#57958 = CARTESIAN_POINT('',(0.456254230542,2.1)); +#57959 = CARTESIAN_POINT('',(0.326350419975,1.875)); +#57960 = CARTESIAN_POINT('',(0.196446609407,1.65)); +#57961 = CARTESIAN_POINT('',(6.654279883933E-002,1.875)); +#57962 = CARTESIAN_POINT('',(-6.336101172833E-002,2.1)); +#57963 = CARTESIAN_POINT('',(0.196446609407,2.1)); +#57964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57965 = PCURVE('',#44977,#57966); +#57966 = DEFINITIONAL_REPRESENTATION('',(#57967),#57970); +#57967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57968,#57969),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55576 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#55577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55579 = ORIENTED_EDGE('',*,*,#55580,.F.); -#55580 = EDGE_CURVE('',#55581,#55554,#55583,.T.); -#55581 = VERTEX_POINT('',#55582); -#55582 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); -#55583 = SURFACE_CURVE('',#55584,(#55588,#55595),.PCURVE_S1.); -#55584 = LINE('',#55585,#55586); -#55585 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); -#55586 = VECTOR('',#55587,1.); -#55587 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55588 = PCURVE('',#37859,#55589); -#55589 = DEFINITIONAL_REPRESENTATION('',(#55590),#55594); -#55590 = LINE('',#55591,#55592); -#55591 = CARTESIAN_POINT('',(-1.103553390593,2.1)); -#55592 = VECTOR('',#55593,1.); -#55593 = DIRECTION('',(1.,0.E+000)); -#55594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55595 = PCURVE('',#42556,#55596); -#55596 = DEFINITIONAL_REPRESENTATION('',(#55597),#55601); -#55597 = LINE('',#55598,#55599); -#55598 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55599 = VECTOR('',#55600,1.); -#55600 = DIRECTION('',(1.,0.E+000)); -#55601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#57968 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#57969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57971 = ORIENTED_EDGE('',*,*,#57972,.F.); +#57972 = EDGE_CURVE('',#57973,#57946,#57975,.T.); +#57973 = VERTEX_POINT('',#57974); +#57974 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); +#57975 = SURFACE_CURVE('',#57976,(#57980,#57987),.PCURVE_S1.); +#57976 = LINE('',#57977,#57978); +#57977 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); +#57978 = VECTOR('',#57979,1.); +#57979 = DIRECTION('',(1.,0.E+000,0.E+000)); +#57980 = PCURVE('',#40251,#57981); +#57981 = DEFINITIONAL_REPRESENTATION('',(#57982),#57986); +#57982 = LINE('',#57983,#57984); +#57983 = CARTESIAN_POINT('',(-1.103553390593,2.1)); +#57984 = VECTOR('',#57985,1.); +#57985 = DIRECTION('',(1.,0.E+000)); +#57986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#55602 = ORIENTED_EDGE('',*,*,#55603,.F.); -#55603 = EDGE_CURVE('',#55604,#55581,#55606,.T.); -#55604 = VERTEX_POINT('',#55605); -#55605 = CARTESIAN_POINT('',(-3.9,-1.225,-5.E-002)); -#55606 = SURFACE_CURVE('',#55607,(#55612,#55619),.PCURVE_S1.); -#55607 = CIRCLE('',#55608,0.2); -#55608 = AXIS2_PLACEMENT_3D('',#55609,#55610,#55611); -#55609 = CARTESIAN_POINT('',(-3.7,-1.225,-5.E-002)); -#55610 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#55611 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55612 = PCURVE('',#37859,#55613); -#55613 = DEFINITIONAL_REPRESENTATION('',(#55614),#55618); -#55614 = CIRCLE('',#55615,0.2); -#55615 = AXIS2_PLACEMENT_2D('',#55616,#55617); -#55616 = CARTESIAN_POINT('',(-1.103553390593,2.3)); -#55617 = DIRECTION('',(-1.,0.E+000)); -#55618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55619 = PCURVE('',#42529,#55620); -#55620 = DEFINITIONAL_REPRESENTATION('',(#55621),#55624); -#55621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55622,#55623),.UNSPECIFIED., +#57987 = PCURVE('',#44948,#57988); +#57988 = DEFINITIONAL_REPRESENTATION('',(#57989),#57993); +#57989 = LINE('',#57990,#57991); +#57990 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#57991 = VECTOR('',#57992,1.); +#57992 = DIRECTION('',(1.,0.E+000)); +#57993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#57994 = ORIENTED_EDGE('',*,*,#57995,.F.); +#57995 = EDGE_CURVE('',#57996,#57973,#57998,.T.); +#57996 = VERTEX_POINT('',#57997); +#57997 = CARTESIAN_POINT('',(-3.9,-1.225,-5.E-002)); +#57998 = SURFACE_CURVE('',#57999,(#58004,#58011),.PCURVE_S1.); +#57999 = CIRCLE('',#58000,0.2); +#58000 = AXIS2_PLACEMENT_3D('',#58001,#58002,#58003); +#58001 = CARTESIAN_POINT('',(-3.7,-1.225,-5.E-002)); +#58002 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58003 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58004 = PCURVE('',#40251,#58005); +#58005 = DEFINITIONAL_REPRESENTATION('',(#58006),#58010); +#58006 = CIRCLE('',#58007,0.2); +#58007 = AXIS2_PLACEMENT_2D('',#58008,#58009); +#58008 = CARTESIAN_POINT('',(-1.103553390593,2.3)); +#58009 = DIRECTION('',(-1.,0.E+000)); +#58010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58011 = PCURVE('',#44921,#58012); +#58012 = DEFINITIONAL_REPRESENTATION('',(#58013),#58016); +#58013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58014,#58015),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55622 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#55623 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#55624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55625 = ORIENTED_EDGE('',*,*,#55626,.F.); -#55626 = EDGE_CURVE('',#55627,#55604,#55629,.T.); -#55627 = VERTEX_POINT('',#55628); -#55628 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); -#55629 = SURFACE_CURVE('',#55630,(#55634,#55641),.PCURVE_S1.); -#55630 = LINE('',#55631,#55632); -#55631 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); -#55632 = VECTOR('',#55633,1.); -#55633 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55634 = PCURVE('',#37859,#55635); -#55635 = DEFINITIONAL_REPRESENTATION('',(#55636),#55640); -#55636 = LINE('',#55637,#55638); -#55637 = CARTESIAN_POINT('',(-1.303553390593,2.8)); -#55638 = VECTOR('',#55639,1.); -#55639 = DIRECTION('',(0.E+000,-1.)); -#55640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55641 = PCURVE('',#42496,#55642); -#55642 = DEFINITIONAL_REPRESENTATION('',(#55643),#55647); -#55643 = LINE('',#55644,#55645); -#55644 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55645 = VECTOR('',#55646,1.); -#55646 = DIRECTION('',(1.,0.E+000)); -#55647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55648 = ORIENTED_EDGE('',*,*,#55649,.F.); -#55649 = EDGE_CURVE('',#55650,#55627,#55652,.T.); -#55650 = VERTEX_POINT('',#55651); -#55651 = CARTESIAN_POINT('',(-3.7,-1.225,0.65)); -#55652 = SURFACE_CURVE('',#55653,(#55658,#55665),.PCURVE_S1.); -#55653 = CIRCLE('',#55654,0.2); -#55654 = AXIS2_PLACEMENT_3D('',#55655,#55656,#55657); -#55655 = CARTESIAN_POINT('',(-3.7,-1.225,0.45)); -#55656 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#55657 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55658 = PCURVE('',#37859,#55659); -#55659 = DEFINITIONAL_REPRESENTATION('',(#55660),#55664); -#55660 = CIRCLE('',#55661,0.2); -#55661 = AXIS2_PLACEMENT_2D('',#55662,#55663); -#55662 = CARTESIAN_POINT('',(-1.103553390593,2.8)); -#55663 = DIRECTION('',(0.E+000,1.)); -#55664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55665 = PCURVE('',#42469,#55666); -#55666 = DEFINITIONAL_REPRESENTATION('',(#55667),#55670); -#55667 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55668,#55669),.UNSPECIFIED., +#58014 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58015 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#58016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58017 = ORIENTED_EDGE('',*,*,#58018,.F.); +#58018 = EDGE_CURVE('',#58019,#57996,#58021,.T.); +#58019 = VERTEX_POINT('',#58020); +#58020 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); +#58021 = SURFACE_CURVE('',#58022,(#58026,#58033),.PCURVE_S1.); +#58022 = LINE('',#58023,#58024); +#58023 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); +#58024 = VECTOR('',#58025,1.); +#58025 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58026 = PCURVE('',#40251,#58027); +#58027 = DEFINITIONAL_REPRESENTATION('',(#58028),#58032); +#58028 = LINE('',#58029,#58030); +#58029 = CARTESIAN_POINT('',(-1.303553390593,2.8)); +#58030 = VECTOR('',#58031,1.); +#58031 = DIRECTION('',(0.E+000,-1.)); +#58032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58033 = PCURVE('',#44888,#58034); +#58034 = DEFINITIONAL_REPRESENTATION('',(#58035),#58039); +#58035 = LINE('',#58036,#58037); +#58036 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58037 = VECTOR('',#58038,1.); +#58038 = DIRECTION('',(1.,0.E+000)); +#58039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58040 = ORIENTED_EDGE('',*,*,#58041,.F.); +#58041 = EDGE_CURVE('',#58042,#58019,#58044,.T.); +#58042 = VERTEX_POINT('',#58043); +#58043 = CARTESIAN_POINT('',(-3.7,-1.225,0.65)); +#58044 = SURFACE_CURVE('',#58045,(#58050,#58057),.PCURVE_S1.); +#58045 = CIRCLE('',#58046,0.2); +#58046 = AXIS2_PLACEMENT_3D('',#58047,#58048,#58049); +#58047 = CARTESIAN_POINT('',(-3.7,-1.225,0.45)); +#58048 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58049 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58050 = PCURVE('',#40251,#58051); +#58051 = DEFINITIONAL_REPRESENTATION('',(#58052),#58056); +#58052 = CIRCLE('',#58053,0.2); +#58053 = AXIS2_PLACEMENT_2D('',#58054,#58055); +#58054 = CARTESIAN_POINT('',(-1.103553390593,2.8)); +#58055 = DIRECTION('',(0.E+000,1.)); +#58056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58057 = PCURVE('',#44861,#58058); +#58058 = DEFINITIONAL_REPRESENTATION('',(#58059),#58062); +#58059 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58060,#58061),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55668 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#55669 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#55670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55671 = ORIENTED_EDGE('',*,*,#55672,.F.); -#55672 = EDGE_CURVE('',#55673,#55650,#55675,.T.); -#55673 = VERTEX_POINT('',#55674); -#55674 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); -#55675 = SURFACE_CURVE('',#55676,(#55680,#55687),.PCURVE_S1.); -#55676 = LINE('',#55677,#55678); -#55677 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); -#55678 = VECTOR('',#55679,1.); -#55679 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55680 = PCURVE('',#37859,#55681); -#55681 = DEFINITIONAL_REPRESENTATION('',(#55682),#55686); -#55682 = LINE('',#55683,#55684); -#55683 = CARTESIAN_POINT('',(0.196446609407,3.)); -#55684 = VECTOR('',#55685,1.); -#55685 = DIRECTION('',(-1.,0.E+000)); -#55686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55687 = PCURVE('',#42436,#55688); -#55688 = DEFINITIONAL_REPRESENTATION('',(#55689),#55693); -#55689 = LINE('',#55690,#55691); -#55690 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55691 = VECTOR('',#55692,1.); -#55692 = DIRECTION('',(1.,0.E+000)); -#55693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55694 = ORIENTED_EDGE('',*,*,#55695,.F.); -#55695 = EDGE_CURVE('',#55696,#55673,#55698,.T.); -#55696 = VERTEX_POINT('',#55697); -#55697 = CARTESIAN_POINT('',(-2.25,-1.225,0.8)); -#55698 = SURFACE_CURVE('',#55699,(#55704,#55715),.PCURVE_S1.); -#55699 = CIRCLE('',#55700,0.15); -#55700 = AXIS2_PLACEMENT_3D('',#55701,#55702,#55703); -#55701 = CARTESIAN_POINT('',(-2.4,-1.225,0.8)); -#55702 = DIRECTION('',(0.E+000,1.,0.E+000)); -#55703 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55704 = PCURVE('',#37859,#55705); -#55705 = DEFINITIONAL_REPRESENTATION('',(#55706),#55714); -#55706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#55707,#55708,#55709,#55710 - ,#55711,#55712,#55713),.UNSPECIFIED.,.T.,.F.) +#58060 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58061 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58063 = ORIENTED_EDGE('',*,*,#58064,.F.); +#58064 = EDGE_CURVE('',#58065,#58042,#58067,.T.); +#58065 = VERTEX_POINT('',#58066); +#58066 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); +#58067 = SURFACE_CURVE('',#58068,(#58072,#58079),.PCURVE_S1.); +#58068 = LINE('',#58069,#58070); +#58069 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); +#58070 = VECTOR('',#58071,1.); +#58071 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58072 = PCURVE('',#40251,#58073); +#58073 = DEFINITIONAL_REPRESENTATION('',(#58074),#58078); +#58074 = LINE('',#58075,#58076); +#58075 = CARTESIAN_POINT('',(0.196446609407,3.)); +#58076 = VECTOR('',#58077,1.); +#58077 = DIRECTION('',(-1.,0.E+000)); +#58078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58079 = PCURVE('',#44828,#58080); +#58080 = DEFINITIONAL_REPRESENTATION('',(#58081),#58085); +#58081 = LINE('',#58082,#58083); +#58082 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58083 = VECTOR('',#58084,1.); +#58084 = DIRECTION('',(1.,0.E+000)); +#58085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58086 = ORIENTED_EDGE('',*,*,#58087,.F.); +#58087 = EDGE_CURVE('',#58088,#58065,#58090,.T.); +#58088 = VERTEX_POINT('',#58089); +#58089 = CARTESIAN_POINT('',(-2.25,-1.225,0.8)); +#58090 = SURFACE_CURVE('',#58091,(#58096,#58107),.PCURVE_S1.); +#58091 = CIRCLE('',#58092,0.15); +#58092 = AXIS2_PLACEMENT_3D('',#58093,#58094,#58095); +#58093 = CARTESIAN_POINT('',(-2.4,-1.225,0.8)); +#58094 = DIRECTION('',(0.E+000,1.,0.E+000)); +#58095 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58096 = PCURVE('',#40251,#58097); +#58097 = DEFINITIONAL_REPRESENTATION('',(#58098),#58106); +#58098 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#58099,#58100,#58101,#58102 + ,#58103,#58104,#58105),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#55707 = CARTESIAN_POINT('',(0.346446609407,3.15)); -#55708 = CARTESIAN_POINT('',(0.346446609407,2.890192378865)); -#55709 = CARTESIAN_POINT('',(0.121446609407,3.020096189432)); -#55710 = CARTESIAN_POINT('',(-0.103553390593,3.15)); -#55711 = CARTESIAN_POINT('',(0.121446609407,3.279903810568)); -#55712 = CARTESIAN_POINT('',(0.346446609407,3.409807621135)); -#55713 = CARTESIAN_POINT('',(0.346446609407,3.15)); -#55714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55715 = PCURVE('',#42409,#55716); -#55716 = DEFINITIONAL_REPRESENTATION('',(#55717),#55720); -#55717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55718,#55719),.UNSPECIFIED., +#58099 = CARTESIAN_POINT('',(0.346446609407,3.15)); +#58100 = CARTESIAN_POINT('',(0.346446609407,2.890192378865)); +#58101 = CARTESIAN_POINT('',(0.121446609407,3.020096189432)); +#58102 = CARTESIAN_POINT('',(-0.103553390593,3.15)); +#58103 = CARTESIAN_POINT('',(0.121446609407,3.279903810568)); +#58104 = CARTESIAN_POINT('',(0.346446609407,3.409807621135)); +#58105 = CARTESIAN_POINT('',(0.346446609407,3.15)); +#58106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58107 = PCURVE('',#44801,#58108); +#58108 = DEFINITIONAL_REPRESENTATION('',(#58109),#58112); +#58109 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58110,#58111),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55718 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#55719 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#55720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55721 = ORIENTED_EDGE('',*,*,#55722,.T.); -#55722 = EDGE_CURVE('',#55696,#55723,#55725,.T.); -#55723 = VERTEX_POINT('',#55724); -#55724 = CARTESIAN_POINT('',(-2.25,-1.225,0.81)); -#55725 = SURFACE_CURVE('',#55726,(#55730,#55737),.PCURVE_S1.); -#55726 = LINE('',#55727,#55728); -#55727 = CARTESIAN_POINT('',(-2.25,-1.225,0.8)); -#55728 = VECTOR('',#55729,1.); -#55729 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55730 = PCURVE('',#37859,#55731); -#55731 = DEFINITIONAL_REPRESENTATION('',(#55732),#55736); -#55732 = LINE('',#55733,#55734); -#55733 = CARTESIAN_POINT('',(0.346446609407,3.15)); -#55734 = VECTOR('',#55735,1.); -#55735 = DIRECTION('',(0.E+000,1.)); -#55736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55737 = PCURVE('',#42380,#55738); -#55738 = DEFINITIONAL_REPRESENTATION('',(#55739),#55743); -#55739 = LINE('',#55740,#55741); -#55740 = CARTESIAN_POINT('',(1.21,0.E+000)); -#55741 = VECTOR('',#55742,1.); -#55742 = DIRECTION('',(1.,0.E+000)); -#55743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55744 = ORIENTED_EDGE('',*,*,#55745,.T.); -#55745 = EDGE_CURVE('',#55723,#54742,#55746,.T.); -#55746 = SURFACE_CURVE('',#55747,(#55752,#55759),.PCURVE_S1.); -#55747 = CIRCLE('',#55748,0.15); -#55748 = AXIS2_PLACEMENT_3D('',#55749,#55750,#55751); -#55749 = CARTESIAN_POINT('',(-2.4,-1.225,0.81)); -#55750 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#55751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55752 = PCURVE('',#37859,#55753); -#55753 = DEFINITIONAL_REPRESENTATION('',(#55754),#55758); -#55754 = CIRCLE('',#55755,0.15); -#55755 = AXIS2_PLACEMENT_2D('',#55756,#55757); -#55756 = CARTESIAN_POINT('',(0.196446609407,3.16)); -#55757 = DIRECTION('',(1.,0.E+000)); -#55758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55759 = PCURVE('',#42353,#55760); -#55760 = DEFINITIONAL_REPRESENTATION('',(#55761),#55764); -#55761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#55762,#55763),.UNSPECIFIED., +#58110 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#58111 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#58112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58113 = ORIENTED_EDGE('',*,*,#58114,.T.); +#58114 = EDGE_CURVE('',#58088,#58115,#58117,.T.); +#58115 = VERTEX_POINT('',#58116); +#58116 = CARTESIAN_POINT('',(-2.25,-1.225,0.81)); +#58117 = SURFACE_CURVE('',#58118,(#58122,#58129),.PCURVE_S1.); +#58118 = LINE('',#58119,#58120); +#58119 = CARTESIAN_POINT('',(-2.25,-1.225,0.8)); +#58120 = VECTOR('',#58121,1.); +#58121 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58122 = PCURVE('',#40251,#58123); +#58123 = DEFINITIONAL_REPRESENTATION('',(#58124),#58128); +#58124 = LINE('',#58125,#58126); +#58125 = CARTESIAN_POINT('',(0.346446609407,3.15)); +#58126 = VECTOR('',#58127,1.); +#58127 = DIRECTION('',(0.E+000,1.)); +#58128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58129 = PCURVE('',#44772,#58130); +#58130 = DEFINITIONAL_REPRESENTATION('',(#58131),#58135); +#58131 = LINE('',#58132,#58133); +#58132 = CARTESIAN_POINT('',(1.21,0.E+000)); +#58133 = VECTOR('',#58134,1.); +#58134 = DIRECTION('',(1.,0.E+000)); +#58135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58136 = ORIENTED_EDGE('',*,*,#58137,.T.); +#58137 = EDGE_CURVE('',#58115,#57134,#58138,.T.); +#58138 = SURFACE_CURVE('',#58139,(#58144,#58151),.PCURVE_S1.); +#58139 = CIRCLE('',#58140,0.15); +#58140 = AXIS2_PLACEMENT_3D('',#58141,#58142,#58143); +#58141 = CARTESIAN_POINT('',(-2.4,-1.225,0.81)); +#58142 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58144 = PCURVE('',#40251,#58145); +#58145 = DEFINITIONAL_REPRESENTATION('',(#58146),#58150); +#58146 = CIRCLE('',#58147,0.15); +#58147 = AXIS2_PLACEMENT_2D('',#58148,#58149); +#58148 = CARTESIAN_POINT('',(0.196446609407,3.16)); +#58149 = DIRECTION('',(1.,0.E+000)); +#58150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58151 = PCURVE('',#44745,#58152); +#58152 = DEFINITIONAL_REPRESENTATION('',(#58153),#58156); +#58153 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58154,#58155),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#55762 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55763 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#55764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55765 = ORIENTED_EDGE('',*,*,#54741,.F.); -#55766 = ORIENTED_EDGE('',*,*,#55101,.T.); -#55767 = ORIENTED_EDGE('',*,*,#37843,.T.); -#55768 = ORIENTED_EDGE('',*,*,#55769,.F.); -#55769 = EDGE_CURVE('',#55770,#37816,#55772,.T.); -#55770 = VERTEX_POINT('',#55771); -#55771 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); -#55772 = SURFACE_CURVE('',#55773,(#55777,#55784),.PCURVE_S1.); -#55773 = LINE('',#55774,#55775); -#55774 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); -#55775 = VECTOR('',#55776,1.); -#55776 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55777 = PCURVE('',#37859,#55778); -#55778 = DEFINITIONAL_REPRESENTATION('',(#55779),#55783); -#55779 = LINE('',#55780,#55781); -#55780 = CARTESIAN_POINT('',(2.586446609407,4.7)); -#55781 = VECTOR('',#55782,1.); -#55782 = DIRECTION('',(-1.,0.E+000)); -#55783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55784 = PCURVE('',#55785,#55790); -#55785 = PLANE('',#55786); -#55786 = AXIS2_PLACEMENT_3D('',#55787,#55788,#55789); -#55787 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#55788 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#55789 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#55790 = DEFINITIONAL_REPRESENTATION('',(#55791),#55795); -#55791 = LINE('',#55792,#55793); -#55792 = CARTESIAN_POINT('',(0.E+000,2.51)); -#55793 = VECTOR('',#55794,1.); -#55794 = DIRECTION('',(0.E+000,1.)); -#55795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55796 = ORIENTED_EDGE('',*,*,#55797,.T.); -#55797 = EDGE_CURVE('',#55770,#55798,#55800,.T.); -#55798 = VERTEX_POINT('',#55799); -#55799 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.)); -#55800 = SURFACE_CURVE('',#55801,(#55805,#55812),.PCURVE_S1.); -#55801 = LINE('',#55802,#55803); -#55802 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); -#55803 = VECTOR('',#55804,1.); -#55804 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55805 = PCURVE('',#37859,#55806); -#55806 = DEFINITIONAL_REPRESENTATION('',(#55807),#55811); -#55807 = LINE('',#55808,#55809); -#55808 = CARTESIAN_POINT('',(2.586446609407,4.7)); -#55809 = VECTOR('',#55810,1.); -#55810 = DIRECTION('',(0.E+000,-1.)); -#55811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55812 = PCURVE('',#42221,#55813); -#55813 = DEFINITIONAL_REPRESENTATION('',(#55814),#55818); -#55814 = LINE('',#55815,#55816); -#55815 = CARTESIAN_POINT('',(0.43,-0.3)); -#55816 = VECTOR('',#55817,1.); -#55817 = DIRECTION('',(1.,0.E+000)); -#55818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55819 = ORIENTED_EDGE('',*,*,#55820,.T.); -#55820 = EDGE_CURVE('',#55798,#55201,#55821,.T.); -#55821 = SURFACE_CURVE('',#55822,(#55826,#55833),.PCURVE_S1.); -#55822 = LINE('',#55823,#55824); -#55823 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.)); -#55824 = VECTOR('',#55825,1.); -#55825 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55826 = PCURVE('',#37859,#55827); -#55827 = DEFINITIONAL_REPRESENTATION('',(#55828),#55832); -#55828 = LINE('',#55829,#55830); -#55829 = CARTESIAN_POINT('',(2.586446609407,4.35)); -#55830 = VECTOR('',#55831,1.); -#55831 = DIRECTION('',(-1.,0.E+000)); -#55832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55833 = PCURVE('',#55834,#55839); -#55834 = PLANE('',#55835); -#55835 = AXIS2_PLACEMENT_3D('',#55836,#55837,#55838); -#55836 = CARTESIAN_POINT('',(1.5,-1.225,2.)); -#55837 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55838 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55839 = DEFINITIONAL_REPRESENTATION('',(#55840),#55844); -#55840 = LINE('',#55841,#55842); -#55841 = CARTESIAN_POINT('',(1.51,0.E+000)); -#55842 = VECTOR('',#55843,1.); -#55843 = DIRECTION('',(1.,0.E+000)); -#55844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55845 = ADVANCED_FACE('',(#55846),#38147,.T.); -#55846 = FACE_BOUND('',#55847,.F.); -#55847 = EDGE_LOOP('',(#55848,#55878,#55906,#55934,#55957,#55983,#55984, - #56004,#56005,#56028,#56051,#56078,#56101,#56124,#56147,#56170, - #56193,#56220,#56243,#56266,#56289,#56316,#56339,#56367,#56390, - #56413,#56436,#56464,#56492,#56520)); -#55848 = ORIENTED_EDGE('',*,*,#55849,.T.); -#55849 = EDGE_CURVE('',#55850,#55852,#55854,.T.); -#55850 = VERTEX_POINT('',#55851); -#55851 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); -#55852 = VERTEX_POINT('',#55853); -#55853 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); -#55854 = SURFACE_CURVE('',#55855,(#55859,#55866),.PCURVE_S1.); -#55855 = LINE('',#55856,#55857); -#55856 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); -#55857 = VECTOR('',#55858,1.); -#55858 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55859 = PCURVE('',#38147,#55860); -#55860 = DEFINITIONAL_REPRESENTATION('',(#55861),#55865); -#55861 = LINE('',#55862,#55863); -#55862 = CARTESIAN_POINT('',(3.406446609407,3.9)); -#55863 = VECTOR('',#55864,1.); -#55864 = DIRECTION('',(1.,0.E+000)); -#55865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55866 = PCURVE('',#55867,#55872); -#55867 = PLANE('',#55868); -#55868 = AXIS2_PLACEMENT_3D('',#55869,#55870,#55871); -#55869 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); -#55870 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55871 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55872 = DEFINITIONAL_REPRESENTATION('',(#55873),#55877); -#55873 = LINE('',#55874,#55875); -#55874 = CARTESIAN_POINT('',(1.16,0.E+000)); -#55875 = VECTOR('',#55876,1.); -#55876 = DIRECTION('',(1.,0.E+000)); -#55877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55878 = ORIENTED_EDGE('',*,*,#55879,.T.); -#55879 = EDGE_CURVE('',#55852,#55880,#55882,.T.); -#55880 = VERTEX_POINT('',#55881); -#55881 = CARTESIAN_POINT('',(1.5,-1.225,2.)); -#55882 = SURFACE_CURVE('',#55883,(#55887,#55894),.PCURVE_S1.); -#55883 = LINE('',#55884,#55885); -#55884 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); -#55885 = VECTOR('',#55886,1.); -#55886 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55887 = PCURVE('',#38147,#55888); -#55888 = DEFINITIONAL_REPRESENTATION('',(#55889),#55893); -#55889 = LINE('',#55890,#55891); -#55890 = CARTESIAN_POINT('',(4.096446609407,3.9)); -#55891 = VECTOR('',#55892,1.); -#55892 = DIRECTION('',(0.E+000,1.)); -#55893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55894 = PCURVE('',#55895,#55900); -#55895 = PLANE('',#55896); -#55896 = AXIS2_PLACEMENT_3D('',#55897,#55898,#55899); -#55897 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); -#55898 = DIRECTION('',(1.,0.E+000,0.E+000)); -#55899 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55900 = DEFINITIONAL_REPRESENTATION('',(#55901),#55905); -#55901 = LINE('',#55902,#55903); -#55902 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55903 = VECTOR('',#55904,1.); -#55904 = DIRECTION('',(1.,0.E+000)); -#55905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55906 = ORIENTED_EDGE('',*,*,#55907,.T.); -#55907 = EDGE_CURVE('',#55880,#55908,#55910,.T.); -#55908 = VERTEX_POINT('',#55909); -#55909 = CARTESIAN_POINT('',(1.E-002,-1.225,2.)); -#55910 = SURFACE_CURVE('',#55911,(#55915,#55922),.PCURVE_S1.); -#55911 = LINE('',#55912,#55913); -#55912 = CARTESIAN_POINT('',(1.5,-1.225,2.)); -#55913 = VECTOR('',#55914,1.); -#55914 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55915 = PCURVE('',#38147,#55916); -#55916 = DEFINITIONAL_REPRESENTATION('',(#55917),#55921); -#55917 = LINE('',#55918,#55919); -#55918 = CARTESIAN_POINT('',(4.096446609407,4.35)); -#55919 = VECTOR('',#55920,1.); -#55920 = DIRECTION('',(-1.,0.E+000)); -#55921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55922 = PCURVE('',#55923,#55928); -#55923 = PLANE('',#55924); -#55924 = AXIS2_PLACEMENT_3D('',#55925,#55926,#55927); -#55925 = CARTESIAN_POINT('',(1.5,-1.225,2.)); -#55926 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55927 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55928 = DEFINITIONAL_REPRESENTATION('',(#55929),#55933); -#55929 = LINE('',#55930,#55931); -#55930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55931 = VECTOR('',#55932,1.); -#55932 = DIRECTION('',(1.,0.E+000)); -#55933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55934 = ORIENTED_EDGE('',*,*,#55935,.F.); -#55935 = EDGE_CURVE('',#55936,#55908,#55938,.T.); -#55936 = VERTEX_POINT('',#55937); -#55937 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); -#55938 = SURFACE_CURVE('',#55939,(#55943,#55950),.PCURVE_S1.); -#55939 = LINE('',#55940,#55941); -#55940 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); -#55941 = VECTOR('',#55942,1.); -#55942 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#55943 = PCURVE('',#38147,#55944); -#55944 = DEFINITIONAL_REPRESENTATION('',(#55945),#55949); -#55945 = LINE('',#55946,#55947); -#55946 = CARTESIAN_POINT('',(2.606446609407,4.7)); -#55947 = VECTOR('',#55948,1.); -#55948 = DIRECTION('',(0.E+000,-1.)); -#55949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55950 = PCURVE('',#41511,#55951); -#55951 = DEFINITIONAL_REPRESENTATION('',(#55952),#55956); -#55952 = LINE('',#55953,#55954); -#55953 = CARTESIAN_POINT('',(0.60484542651,-0.3)); -#55954 = VECTOR('',#55955,1.); -#55955 = DIRECTION('',(-1.,0.E+000)); -#55956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55957 = ORIENTED_EDGE('',*,*,#55958,.F.); -#55958 = EDGE_CURVE('',#38132,#55936,#55959,.T.); -#55959 = SURFACE_CURVE('',#55960,(#55964,#55971),.PCURVE_S1.); -#55960 = LINE('',#55961,#55962); -#55961 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#55962 = VECTOR('',#55963,1.); -#55963 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#55964 = PCURVE('',#38147,#55965); -#55965 = DEFINITIONAL_REPRESENTATION('',(#55966),#55970); -#55966 = LINE('',#55967,#55968); -#55967 = CARTESIAN_POINT('',(5.096446609407,4.7)); -#55968 = VECTOR('',#55969,1.); -#55969 = DIRECTION('',(-1.,0.E+000)); -#55970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55971 = PCURVE('',#55972,#55977); -#55972 = PLANE('',#55973); -#55973 = AXIS2_PLACEMENT_3D('',#55974,#55975,#55976); -#55974 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#55975 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#55976 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#55977 = DEFINITIONAL_REPRESENTATION('',(#55978),#55982); -#55978 = LINE('',#55979,#55980); -#55979 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#55980 = VECTOR('',#55981,1.); -#55981 = DIRECTION('',(0.E+000,1.)); -#55982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55983 = ORIENTED_EDGE('',*,*,#38131,.T.); -#55984 = ORIENTED_EDGE('',*,*,#55985,.F.); -#55985 = EDGE_CURVE('',#40539,#38104,#55986,.T.); -#55986 = SURFACE_CURVE('',#55987,(#55991,#55998),.PCURVE_S1.); -#55987 = LINE('',#55988,#55989); -#55988 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); -#55989 = VECTOR('',#55990,1.); -#55990 = DIRECTION('',(0.E+000,0.E+000,1.)); -#55991 = PCURVE('',#38147,#55992); -#55992 = DEFINITIONAL_REPRESENTATION('',(#55993),#55997); -#55993 = LINE('',#55994,#55995); -#55994 = CARTESIAN_POINT('',(5.192893218814,3.31)); -#55995 = VECTOR('',#55996,1.); -#55996 = DIRECTION('',(0.E+000,1.)); -#55997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#55998 = PCURVE('',#38120,#55999); -#55999 = DEFINITIONAL_REPRESENTATION('',(#56000),#56003); -#56000 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56001,#56002),.UNSPECIFIED., +#58154 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58155 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58157 = ORIENTED_EDGE('',*,*,#57133,.F.); +#58158 = ORIENTED_EDGE('',*,*,#57493,.T.); +#58159 = ORIENTED_EDGE('',*,*,#40235,.T.); +#58160 = ORIENTED_EDGE('',*,*,#58161,.F.); +#58161 = EDGE_CURVE('',#58162,#40208,#58164,.T.); +#58162 = VERTEX_POINT('',#58163); +#58163 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); +#58164 = SURFACE_CURVE('',#58165,(#58169,#58176),.PCURVE_S1.); +#58165 = LINE('',#58166,#58167); +#58166 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); +#58167 = VECTOR('',#58168,1.); +#58168 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58169 = PCURVE('',#40251,#58170); +#58170 = DEFINITIONAL_REPRESENTATION('',(#58171),#58175); +#58171 = LINE('',#58172,#58173); +#58172 = CARTESIAN_POINT('',(2.586446609407,4.7)); +#58173 = VECTOR('',#58174,1.); +#58174 = DIRECTION('',(-1.,0.E+000)); +#58175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58176 = PCURVE('',#58177,#58182); +#58177 = PLANE('',#58178); +#58178 = AXIS2_PLACEMENT_3D('',#58179,#58180,#58181); +#58179 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#58180 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#58181 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#58182 = DEFINITIONAL_REPRESENTATION('',(#58183),#58187); +#58183 = LINE('',#58184,#58185); +#58184 = CARTESIAN_POINT('',(0.E+000,2.51)); +#58185 = VECTOR('',#58186,1.); +#58186 = DIRECTION('',(0.E+000,1.)); +#58187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58188 = ORIENTED_EDGE('',*,*,#58189,.T.); +#58189 = EDGE_CURVE('',#58162,#58190,#58192,.T.); +#58190 = VERTEX_POINT('',#58191); +#58191 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.)); +#58192 = SURFACE_CURVE('',#58193,(#58197,#58204),.PCURVE_S1.); +#58193 = LINE('',#58194,#58195); +#58194 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); +#58195 = VECTOR('',#58196,1.); +#58196 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58197 = PCURVE('',#40251,#58198); +#58198 = DEFINITIONAL_REPRESENTATION('',(#58199),#58203); +#58199 = LINE('',#58200,#58201); +#58200 = CARTESIAN_POINT('',(2.586446609407,4.7)); +#58201 = VECTOR('',#58202,1.); +#58202 = DIRECTION('',(0.E+000,-1.)); +#58203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58204 = PCURVE('',#44613,#58205); +#58205 = DEFINITIONAL_REPRESENTATION('',(#58206),#58210); +#58206 = LINE('',#58207,#58208); +#58207 = CARTESIAN_POINT('',(0.43,-0.3)); +#58208 = VECTOR('',#58209,1.); +#58209 = DIRECTION('',(1.,0.E+000)); +#58210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58211 = ORIENTED_EDGE('',*,*,#58212,.T.); +#58212 = EDGE_CURVE('',#58190,#57593,#58213,.T.); +#58213 = SURFACE_CURVE('',#58214,(#58218,#58225),.PCURVE_S1.); +#58214 = LINE('',#58215,#58216); +#58215 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.)); +#58216 = VECTOR('',#58217,1.); +#58217 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58218 = PCURVE('',#40251,#58219); +#58219 = DEFINITIONAL_REPRESENTATION('',(#58220),#58224); +#58220 = LINE('',#58221,#58222); +#58221 = CARTESIAN_POINT('',(2.586446609407,4.35)); +#58222 = VECTOR('',#58223,1.); +#58223 = DIRECTION('',(-1.,0.E+000)); +#58224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58225 = PCURVE('',#58226,#58231); +#58226 = PLANE('',#58227); +#58227 = AXIS2_PLACEMENT_3D('',#58228,#58229,#58230); +#58228 = CARTESIAN_POINT('',(1.5,-1.225,2.)); +#58229 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58230 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58231 = DEFINITIONAL_REPRESENTATION('',(#58232),#58236); +#58232 = LINE('',#58233,#58234); +#58233 = CARTESIAN_POINT('',(1.51,0.E+000)); +#58234 = VECTOR('',#58235,1.); +#58235 = DIRECTION('',(1.,0.E+000)); +#58236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58237 = ADVANCED_FACE('',(#58238),#40539,.T.); +#58238 = FACE_BOUND('',#58239,.F.); +#58239 = EDGE_LOOP('',(#58240,#58270,#58298,#58326,#58349,#58375,#58376, + #58396,#58397,#58420,#58443,#58470,#58493,#58516,#58539,#58562, + #58585,#58612,#58635,#58658,#58681,#58708,#58731,#58759,#58782, + #58805,#58828,#58856,#58884,#58912)); +#58240 = ORIENTED_EDGE('',*,*,#58241,.T.); +#58241 = EDGE_CURVE('',#58242,#58244,#58246,.T.); +#58242 = VERTEX_POINT('',#58243); +#58243 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); +#58244 = VERTEX_POINT('',#58245); +#58245 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); +#58246 = SURFACE_CURVE('',#58247,(#58251,#58258),.PCURVE_S1.); +#58247 = LINE('',#58248,#58249); +#58248 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); +#58249 = VECTOR('',#58250,1.); +#58250 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58251 = PCURVE('',#40539,#58252); +#58252 = DEFINITIONAL_REPRESENTATION('',(#58253),#58257); +#58253 = LINE('',#58254,#58255); +#58254 = CARTESIAN_POINT('',(3.406446609407,3.9)); +#58255 = VECTOR('',#58256,1.); +#58256 = DIRECTION('',(1.,0.E+000)); +#58257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58258 = PCURVE('',#58259,#58264); +#58259 = PLANE('',#58260); +#58260 = AXIS2_PLACEMENT_3D('',#58261,#58262,#58263); +#58261 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); +#58262 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58263 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58264 = DEFINITIONAL_REPRESENTATION('',(#58265),#58269); +#58265 = LINE('',#58266,#58267); +#58266 = CARTESIAN_POINT('',(1.16,0.E+000)); +#58267 = VECTOR('',#58268,1.); +#58268 = DIRECTION('',(1.,0.E+000)); +#58269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58270 = ORIENTED_EDGE('',*,*,#58271,.T.); +#58271 = EDGE_CURVE('',#58244,#58272,#58274,.T.); +#58272 = VERTEX_POINT('',#58273); +#58273 = CARTESIAN_POINT('',(1.5,-1.225,2.)); +#58274 = SURFACE_CURVE('',#58275,(#58279,#58286),.PCURVE_S1.); +#58275 = LINE('',#58276,#58277); +#58276 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); +#58277 = VECTOR('',#58278,1.); +#58278 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58279 = PCURVE('',#40539,#58280); +#58280 = DEFINITIONAL_REPRESENTATION('',(#58281),#58285); +#58281 = LINE('',#58282,#58283); +#58282 = CARTESIAN_POINT('',(4.096446609407,3.9)); +#58283 = VECTOR('',#58284,1.); +#58284 = DIRECTION('',(0.E+000,1.)); +#58285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58286 = PCURVE('',#58287,#58292); +#58287 = PLANE('',#58288); +#58288 = AXIS2_PLACEMENT_3D('',#58289,#58290,#58291); +#58289 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); +#58290 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58291 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58292 = DEFINITIONAL_REPRESENTATION('',(#58293),#58297); +#58293 = LINE('',#58294,#58295); +#58294 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58295 = VECTOR('',#58296,1.); +#58296 = DIRECTION('',(1.,0.E+000)); +#58297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58298 = ORIENTED_EDGE('',*,*,#58299,.T.); +#58299 = EDGE_CURVE('',#58272,#58300,#58302,.T.); +#58300 = VERTEX_POINT('',#58301); +#58301 = CARTESIAN_POINT('',(1.E-002,-1.225,2.)); +#58302 = SURFACE_CURVE('',#58303,(#58307,#58314),.PCURVE_S1.); +#58303 = LINE('',#58304,#58305); +#58304 = CARTESIAN_POINT('',(1.5,-1.225,2.)); +#58305 = VECTOR('',#58306,1.); +#58306 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58307 = PCURVE('',#40539,#58308); +#58308 = DEFINITIONAL_REPRESENTATION('',(#58309),#58313); +#58309 = LINE('',#58310,#58311); +#58310 = CARTESIAN_POINT('',(4.096446609407,4.35)); +#58311 = VECTOR('',#58312,1.); +#58312 = DIRECTION('',(-1.,0.E+000)); +#58313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58314 = PCURVE('',#58315,#58320); +#58315 = PLANE('',#58316); +#58316 = AXIS2_PLACEMENT_3D('',#58317,#58318,#58319); +#58317 = CARTESIAN_POINT('',(1.5,-1.225,2.)); +#58318 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58319 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58320 = DEFINITIONAL_REPRESENTATION('',(#58321),#58325); +#58321 = LINE('',#58322,#58323); +#58322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58323 = VECTOR('',#58324,1.); +#58324 = DIRECTION('',(1.,0.E+000)); +#58325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58326 = ORIENTED_EDGE('',*,*,#58327,.F.); +#58327 = EDGE_CURVE('',#58328,#58300,#58330,.T.); +#58328 = VERTEX_POINT('',#58329); +#58329 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); +#58330 = SURFACE_CURVE('',#58331,(#58335,#58342),.PCURVE_S1.); +#58331 = LINE('',#58332,#58333); +#58332 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); +#58333 = VECTOR('',#58334,1.); +#58334 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58335 = PCURVE('',#40539,#58336); +#58336 = DEFINITIONAL_REPRESENTATION('',(#58337),#58341); +#58337 = LINE('',#58338,#58339); +#58338 = CARTESIAN_POINT('',(2.606446609407,4.7)); +#58339 = VECTOR('',#58340,1.); +#58340 = DIRECTION('',(0.E+000,-1.)); +#58341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58342 = PCURVE('',#43903,#58343); +#58343 = DEFINITIONAL_REPRESENTATION('',(#58344),#58348); +#58344 = LINE('',#58345,#58346); +#58345 = CARTESIAN_POINT('',(0.60484542651,-0.3)); +#58346 = VECTOR('',#58347,1.); +#58347 = DIRECTION('',(-1.,0.E+000)); +#58348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58349 = ORIENTED_EDGE('',*,*,#58350,.F.); +#58350 = EDGE_CURVE('',#40524,#58328,#58351,.T.); +#58351 = SURFACE_CURVE('',#58352,(#58356,#58363),.PCURVE_S1.); +#58352 = LINE('',#58353,#58354); +#58353 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#58354 = VECTOR('',#58355,1.); +#58355 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58356 = PCURVE('',#40539,#58357); +#58357 = DEFINITIONAL_REPRESENTATION('',(#58358),#58362); +#58358 = LINE('',#58359,#58360); +#58359 = CARTESIAN_POINT('',(5.096446609407,4.7)); +#58360 = VECTOR('',#58361,1.); +#58361 = DIRECTION('',(-1.,0.E+000)); +#58362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58363 = PCURVE('',#58364,#58369); +#58364 = PLANE('',#58365); +#58365 = AXIS2_PLACEMENT_3D('',#58366,#58367,#58368); +#58366 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#58367 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#58368 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#58369 = DEFINITIONAL_REPRESENTATION('',(#58370),#58374); +#58370 = LINE('',#58371,#58372); +#58371 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58372 = VECTOR('',#58373,1.); +#58373 = DIRECTION('',(0.E+000,1.)); +#58374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58375 = ORIENTED_EDGE('',*,*,#40523,.T.); +#58376 = ORIENTED_EDGE('',*,*,#58377,.F.); +#58377 = EDGE_CURVE('',#42931,#40496,#58378,.T.); +#58378 = SURFACE_CURVE('',#58379,(#58383,#58390),.PCURVE_S1.); +#58379 = LINE('',#58380,#58381); +#58380 = CARTESIAN_POINT('',(2.596446609407,-1.225,0.96)); +#58381 = VECTOR('',#58382,1.); +#58382 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58383 = PCURVE('',#40539,#58384); +#58384 = DEFINITIONAL_REPRESENTATION('',(#58385),#58389); +#58385 = LINE('',#58386,#58387); +#58386 = CARTESIAN_POINT('',(5.192893218814,3.31)); +#58387 = VECTOR('',#58388,1.); +#58388 = DIRECTION('',(0.E+000,1.)); +#58389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58390 = PCURVE('',#40512,#58391); +#58391 = DEFINITIONAL_REPRESENTATION('',(#58392),#58395); +#58392 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58393,#58394),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#56001 = CARTESIAN_POINT('',(4.712388980385,3.31)); -#56002 = CARTESIAN_POINT('',(4.712388980385,4.7)); -#56003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56004 = ORIENTED_EDGE('',*,*,#40538,.T.); -#56005 = ORIENTED_EDGE('',*,*,#56006,.T.); -#56006 = EDGE_CURVE('',#40512,#56007,#56009,.T.); -#56007 = VERTEX_POINT('',#56008); -#56008 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); -#56009 = SURFACE_CURVE('',#56010,(#56015,#56022),.PCURVE_S1.); -#56010 = CIRCLE('',#56011,0.15); -#56011 = AXIS2_PLACEMENT_3D('',#56012,#56013,#56014); -#56012 = CARTESIAN_POINT('',(2.4,-1.225,0.81)); -#56013 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56014 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56015 = PCURVE('',#38147,#56016); -#56016 = DEFINITIONAL_REPRESENTATION('',(#56017),#56021); -#56017 = CIRCLE('',#56018,0.15); -#56018 = AXIS2_PLACEMENT_2D('',#56019,#56020); -#56019 = CARTESIAN_POINT('',(4.996446609407,3.16)); -#56020 = DIRECTION('',(0.E+000,1.)); -#56021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56022 = PCURVE('',#40527,#56023); -#56023 = DEFINITIONAL_REPRESENTATION('',(#56024),#56027); -#56024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56025,#56026),.UNSPECIFIED., +#58393 = CARTESIAN_POINT('',(4.712388980385,3.31)); +#58394 = CARTESIAN_POINT('',(4.712388980385,4.7)); +#58395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58396 = ORIENTED_EDGE('',*,*,#42930,.T.); +#58397 = ORIENTED_EDGE('',*,*,#58398,.T.); +#58398 = EDGE_CURVE('',#42904,#58399,#58401,.T.); +#58399 = VERTEX_POINT('',#58400); +#58400 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); +#58401 = SURFACE_CURVE('',#58402,(#58407,#58414),.PCURVE_S1.); +#58402 = CIRCLE('',#58403,0.15); +#58403 = AXIS2_PLACEMENT_3D('',#58404,#58405,#58406); +#58404 = CARTESIAN_POINT('',(2.4,-1.225,0.81)); +#58405 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58406 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58407 = PCURVE('',#40539,#58408); +#58408 = DEFINITIONAL_REPRESENTATION('',(#58409),#58413); +#58409 = CIRCLE('',#58410,0.15); +#58410 = AXIS2_PLACEMENT_2D('',#58411,#58412); +#58411 = CARTESIAN_POINT('',(4.996446609407,3.16)); +#58412 = DIRECTION('',(0.E+000,1.)); +#58413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58414 = PCURVE('',#42919,#58415); +#58415 = DEFINITIONAL_REPRESENTATION('',(#58416),#58419); +#58416 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58417,#58418),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56025 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#56026 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#56027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56028 = ORIENTED_EDGE('',*,*,#56029,.T.); -#56029 = EDGE_CURVE('',#56007,#56030,#56032,.T.); -#56030 = VERTEX_POINT('',#56031); -#56031 = CARTESIAN_POINT('',(2.25,-1.225,0.8)); -#56032 = SURFACE_CURVE('',#56033,(#56037,#56044),.PCURVE_S1.); -#56033 = LINE('',#56034,#56035); -#56034 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); -#56035 = VECTOR('',#56036,1.); -#56036 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56037 = PCURVE('',#38147,#56038); -#56038 = DEFINITIONAL_REPRESENTATION('',(#56039),#56043); -#56039 = LINE('',#56040,#56041); -#56040 = CARTESIAN_POINT('',(4.846446609407,3.16)); -#56041 = VECTOR('',#56042,1.); -#56042 = DIRECTION('',(0.E+000,-1.)); -#56043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56044 = PCURVE('',#41405,#56045); -#56045 = DEFINITIONAL_REPRESENTATION('',(#56046),#56050); -#56046 = LINE('',#56047,#56048); -#56047 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56048 = VECTOR('',#56049,1.); -#56049 = DIRECTION('',(1.,0.E+000)); -#56050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56051 = ORIENTED_EDGE('',*,*,#56052,.F.); -#56052 = EDGE_CURVE('',#56053,#56030,#56055,.T.); -#56053 = VERTEX_POINT('',#56054); -#56054 = CARTESIAN_POINT('',(2.4,-1.225,0.65)); -#56055 = SURFACE_CURVE('',#56056,(#56061,#56072),.PCURVE_S1.); -#56056 = CIRCLE('',#56057,0.15); -#56057 = AXIS2_PLACEMENT_3D('',#56058,#56059,#56060); -#56058 = CARTESIAN_POINT('',(2.4,-1.225,0.8)); -#56059 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56060 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56061 = PCURVE('',#38147,#56062); -#56062 = DEFINITIONAL_REPRESENTATION('',(#56063),#56071); -#56063 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56064,#56065,#56066,#56067 - ,#56068,#56069,#56070),.UNSPECIFIED.,.T.,.F.) +#58417 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58418 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58420 = ORIENTED_EDGE('',*,*,#58421,.T.); +#58421 = EDGE_CURVE('',#58399,#58422,#58424,.T.); +#58422 = VERTEX_POINT('',#58423); +#58423 = CARTESIAN_POINT('',(2.25,-1.225,0.8)); +#58424 = SURFACE_CURVE('',#58425,(#58429,#58436),.PCURVE_S1.); +#58425 = LINE('',#58426,#58427); +#58426 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); +#58427 = VECTOR('',#58428,1.); +#58428 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58429 = PCURVE('',#40539,#58430); +#58430 = DEFINITIONAL_REPRESENTATION('',(#58431),#58435); +#58431 = LINE('',#58432,#58433); +#58432 = CARTESIAN_POINT('',(4.846446609407,3.16)); +#58433 = VECTOR('',#58434,1.); +#58434 = DIRECTION('',(0.E+000,-1.)); +#58435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58436 = PCURVE('',#43797,#58437); +#58437 = DEFINITIONAL_REPRESENTATION('',(#58438),#58442); +#58438 = LINE('',#58439,#58440); +#58439 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58440 = VECTOR('',#58441,1.); +#58441 = DIRECTION('',(1.,0.E+000)); +#58442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58443 = ORIENTED_EDGE('',*,*,#58444,.F.); +#58444 = EDGE_CURVE('',#58445,#58422,#58447,.T.); +#58445 = VERTEX_POINT('',#58446); +#58446 = CARTESIAN_POINT('',(2.4,-1.225,0.65)); +#58447 = SURFACE_CURVE('',#58448,(#58453,#58464),.PCURVE_S1.); +#58448 = CIRCLE('',#58449,0.15); +#58449 = AXIS2_PLACEMENT_3D('',#58450,#58451,#58452); +#58450 = CARTESIAN_POINT('',(2.4,-1.225,0.8)); +#58451 = DIRECTION('',(0.E+000,1.,0.E+000)); +#58452 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58453 = PCURVE('',#40539,#58454); +#58454 = DEFINITIONAL_REPRESENTATION('',(#58455),#58463); +#58455 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#58456,#58457,#58458,#58459 + ,#58460,#58461,#58462),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#56064 = CARTESIAN_POINT('',(4.996446609407,3.)); -#56065 = CARTESIAN_POINT('',(4.736638988272,3.)); -#56066 = CARTESIAN_POINT('',(4.866542798839,3.225)); -#56067 = CARTESIAN_POINT('',(4.996446609407,3.45)); -#56068 = CARTESIAN_POINT('',(5.126350419975,3.225)); -#56069 = CARTESIAN_POINT('',(5.256254230542,3.)); -#56070 = CARTESIAN_POINT('',(4.996446609407,3.)); -#56071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56072 = PCURVE('',#41378,#56073); -#56073 = DEFINITIONAL_REPRESENTATION('',(#56074),#56077); -#56074 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56075,#56076),.UNSPECIFIED., +#58456 = CARTESIAN_POINT('',(4.996446609407,3.)); +#58457 = CARTESIAN_POINT('',(4.736638988272,3.)); +#58458 = CARTESIAN_POINT('',(4.866542798839,3.225)); +#58459 = CARTESIAN_POINT('',(4.996446609407,3.45)); +#58460 = CARTESIAN_POINT('',(5.126350419975,3.225)); +#58461 = CARTESIAN_POINT('',(5.256254230542,3.)); +#58462 = CARTESIAN_POINT('',(4.996446609407,3.)); +#58463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58464 = PCURVE('',#43770,#58465); +#58465 = DEFINITIONAL_REPRESENTATION('',(#58466),#58469); +#58466 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58467,#58468),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56075 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#56076 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#56077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56078 = ORIENTED_EDGE('',*,*,#56079,.F.); -#56079 = EDGE_CURVE('',#56080,#56053,#56082,.T.); -#56080 = VERTEX_POINT('',#56081); -#56081 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); -#56082 = SURFACE_CURVE('',#56083,(#56087,#56094),.PCURVE_S1.); -#56083 = LINE('',#56084,#56085); -#56084 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); -#56085 = VECTOR('',#56086,1.); -#56086 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56087 = PCURVE('',#38147,#56088); -#56088 = DEFINITIONAL_REPRESENTATION('',(#56089),#56093); -#56089 = LINE('',#56090,#56091); -#56090 = CARTESIAN_POINT('',(6.296446609407,3.)); -#56091 = VECTOR('',#56092,1.); -#56092 = DIRECTION('',(-1.,0.E+000)); -#56093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56094 = PCURVE('',#41349,#56095); -#56095 = DEFINITIONAL_REPRESENTATION('',(#56096),#56100); -#56096 = LINE('',#56097,#56098); -#56097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56098 = VECTOR('',#56099,1.); -#56099 = DIRECTION('',(1.,0.E+000)); -#56100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56101 = ORIENTED_EDGE('',*,*,#56102,.F.); -#56102 = EDGE_CURVE('',#56103,#56080,#56105,.T.); -#56103 = VERTEX_POINT('',#56104); -#56104 = CARTESIAN_POINT('',(3.9,-1.225,0.45)); -#56105 = SURFACE_CURVE('',#56106,(#56111,#56118),.PCURVE_S1.); -#56106 = CIRCLE('',#56107,0.2); -#56107 = AXIS2_PLACEMENT_3D('',#56108,#56109,#56110); -#56108 = CARTESIAN_POINT('',(3.7,-1.225,0.45)); -#56109 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56110 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56111 = PCURVE('',#38147,#56112); -#56112 = DEFINITIONAL_REPRESENTATION('',(#56113),#56117); -#56113 = CIRCLE('',#56114,0.2); -#56114 = AXIS2_PLACEMENT_2D('',#56115,#56116); -#56115 = CARTESIAN_POINT('',(6.296446609407,2.8)); -#56116 = DIRECTION('',(1.,0.E+000)); -#56117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56118 = PCURVE('',#41322,#56119); -#56119 = DEFINITIONAL_REPRESENTATION('',(#56120),#56123); -#56120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56121,#56122),.UNSPECIFIED., +#58467 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#58468 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58470 = ORIENTED_EDGE('',*,*,#58471,.F.); +#58471 = EDGE_CURVE('',#58472,#58445,#58474,.T.); +#58472 = VERTEX_POINT('',#58473); +#58473 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); +#58474 = SURFACE_CURVE('',#58475,(#58479,#58486),.PCURVE_S1.); +#58475 = LINE('',#58476,#58477); +#58476 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); +#58477 = VECTOR('',#58478,1.); +#58478 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58479 = PCURVE('',#40539,#58480); +#58480 = DEFINITIONAL_REPRESENTATION('',(#58481),#58485); +#58481 = LINE('',#58482,#58483); +#58482 = CARTESIAN_POINT('',(6.296446609407,3.)); +#58483 = VECTOR('',#58484,1.); +#58484 = DIRECTION('',(-1.,0.E+000)); +#58485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58486 = PCURVE('',#43741,#58487); +#58487 = DEFINITIONAL_REPRESENTATION('',(#58488),#58492); +#58488 = LINE('',#58489,#58490); +#58489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58490 = VECTOR('',#58491,1.); +#58491 = DIRECTION('',(1.,0.E+000)); +#58492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58493 = ORIENTED_EDGE('',*,*,#58494,.F.); +#58494 = EDGE_CURVE('',#58495,#58472,#58497,.T.); +#58495 = VERTEX_POINT('',#58496); +#58496 = CARTESIAN_POINT('',(3.9,-1.225,0.45)); +#58497 = SURFACE_CURVE('',#58498,(#58503,#58510),.PCURVE_S1.); +#58498 = CIRCLE('',#58499,0.2); +#58499 = AXIS2_PLACEMENT_3D('',#58500,#58501,#58502); +#58500 = CARTESIAN_POINT('',(3.7,-1.225,0.45)); +#58501 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58502 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58503 = PCURVE('',#40539,#58504); +#58504 = DEFINITIONAL_REPRESENTATION('',(#58505),#58509); +#58505 = CIRCLE('',#58506,0.2); +#58506 = AXIS2_PLACEMENT_2D('',#58507,#58508); +#58507 = CARTESIAN_POINT('',(6.296446609407,2.8)); +#58508 = DIRECTION('',(1.,0.E+000)); +#58509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58510 = PCURVE('',#43714,#58511); +#58511 = DEFINITIONAL_REPRESENTATION('',(#58512),#58515); +#58512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58513,#58514),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56121 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56122 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#56123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56124 = ORIENTED_EDGE('',*,*,#56125,.F.); -#56125 = EDGE_CURVE('',#56126,#56103,#56128,.T.); -#56126 = VERTEX_POINT('',#56127); -#56127 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); -#56128 = SURFACE_CURVE('',#56129,(#56133,#56140),.PCURVE_S1.); -#56129 = LINE('',#56130,#56131); -#56130 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); -#56131 = VECTOR('',#56132,1.); -#56132 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56133 = PCURVE('',#38147,#56134); -#56134 = DEFINITIONAL_REPRESENTATION('',(#56135),#56139); -#56135 = LINE('',#56136,#56137); -#56136 = CARTESIAN_POINT('',(6.496446609407,2.3)); -#56137 = VECTOR('',#56138,1.); -#56138 = DIRECTION('',(0.E+000,1.)); -#56139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56140 = PCURVE('',#41289,#56141); -#56141 = DEFINITIONAL_REPRESENTATION('',(#56142),#56146); -#56142 = LINE('',#56143,#56144); -#56143 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56144 = VECTOR('',#56145,1.); -#56145 = DIRECTION('',(1.,0.E+000)); -#56146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56147 = ORIENTED_EDGE('',*,*,#56148,.F.); -#56148 = EDGE_CURVE('',#56149,#56126,#56151,.T.); -#56149 = VERTEX_POINT('',#56150); -#56150 = CARTESIAN_POINT('',(3.7,-1.225,-0.25)); -#56151 = SURFACE_CURVE('',#56152,(#56157,#56164),.PCURVE_S1.); -#56152 = CIRCLE('',#56153,0.2); -#56153 = AXIS2_PLACEMENT_3D('',#56154,#56155,#56156); -#56154 = CARTESIAN_POINT('',(3.7,-1.225,-5.E-002)); -#56155 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56156 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56157 = PCURVE('',#38147,#56158); -#56158 = DEFINITIONAL_REPRESENTATION('',(#56159),#56163); -#56159 = CIRCLE('',#56160,0.2); -#56160 = AXIS2_PLACEMENT_2D('',#56161,#56162); -#56161 = CARTESIAN_POINT('',(6.296446609407,2.3)); -#56162 = DIRECTION('',(0.E+000,-1.)); -#56163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56164 = PCURVE('',#41262,#56165); -#56165 = DEFINITIONAL_REPRESENTATION('',(#56166),#56169); -#56166 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56167,#56168),.UNSPECIFIED., +#58513 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58514 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58516 = ORIENTED_EDGE('',*,*,#58517,.F.); +#58517 = EDGE_CURVE('',#58518,#58495,#58520,.T.); +#58518 = VERTEX_POINT('',#58519); +#58519 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); +#58520 = SURFACE_CURVE('',#58521,(#58525,#58532),.PCURVE_S1.); +#58521 = LINE('',#58522,#58523); +#58522 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); +#58523 = VECTOR('',#58524,1.); +#58524 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58525 = PCURVE('',#40539,#58526); +#58526 = DEFINITIONAL_REPRESENTATION('',(#58527),#58531); +#58527 = LINE('',#58528,#58529); +#58528 = CARTESIAN_POINT('',(6.496446609407,2.3)); +#58529 = VECTOR('',#58530,1.); +#58530 = DIRECTION('',(0.E+000,1.)); +#58531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58532 = PCURVE('',#43681,#58533); +#58533 = DEFINITIONAL_REPRESENTATION('',(#58534),#58538); +#58534 = LINE('',#58535,#58536); +#58535 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58536 = VECTOR('',#58537,1.); +#58537 = DIRECTION('',(1.,0.E+000)); +#58538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58539 = ORIENTED_EDGE('',*,*,#58540,.F.); +#58540 = EDGE_CURVE('',#58541,#58518,#58543,.T.); +#58541 = VERTEX_POINT('',#58542); +#58542 = CARTESIAN_POINT('',(3.7,-1.225,-0.25)); +#58543 = SURFACE_CURVE('',#58544,(#58549,#58556),.PCURVE_S1.); +#58544 = CIRCLE('',#58545,0.2); +#58545 = AXIS2_PLACEMENT_3D('',#58546,#58547,#58548); +#58546 = CARTESIAN_POINT('',(3.7,-1.225,-5.E-002)); +#58547 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58548 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58549 = PCURVE('',#40539,#58550); +#58550 = DEFINITIONAL_REPRESENTATION('',(#58551),#58555); +#58551 = CIRCLE('',#58552,0.2); +#58552 = AXIS2_PLACEMENT_2D('',#58553,#58554); +#58553 = CARTESIAN_POINT('',(6.296446609407,2.3)); +#58554 = DIRECTION('',(0.E+000,-1.)); +#58555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58556 = PCURVE('',#43654,#58557); +#58557 = DEFINITIONAL_REPRESENTATION('',(#58558),#58561); +#58558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58559,#58560),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56167 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#56168 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#56169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56170 = ORIENTED_EDGE('',*,*,#56171,.F.); -#56171 = EDGE_CURVE('',#56172,#56149,#56174,.T.); -#56172 = VERTEX_POINT('',#56173); -#56173 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); -#56174 = SURFACE_CURVE('',#56175,(#56179,#56186),.PCURVE_S1.); -#56175 = LINE('',#56176,#56177); -#56176 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); -#56177 = VECTOR('',#56178,1.); -#56178 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56179 = PCURVE('',#38147,#56180); -#56180 = DEFINITIONAL_REPRESENTATION('',(#56181),#56185); -#56181 = LINE('',#56182,#56183); -#56182 = CARTESIAN_POINT('',(4.996446609407,2.1)); -#56183 = VECTOR('',#56184,1.); -#56184 = DIRECTION('',(1.,0.E+000)); -#56185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56186 = PCURVE('',#41229,#56187); -#56187 = DEFINITIONAL_REPRESENTATION('',(#56188),#56192); -#56188 = LINE('',#56189,#56190); -#56189 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56190 = VECTOR('',#56191,1.); -#56191 = DIRECTION('',(1.,0.E+000)); -#56192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56193 = ORIENTED_EDGE('',*,*,#56194,.F.); -#56194 = EDGE_CURVE('',#56195,#56172,#56197,.T.); -#56195 = VERTEX_POINT('',#56196); -#56196 = CARTESIAN_POINT('',(2.25,-1.225,-0.4)); -#56197 = SURFACE_CURVE('',#56198,(#56203,#56214),.PCURVE_S1.); -#56198 = CIRCLE('',#56199,0.15); -#56199 = AXIS2_PLACEMENT_3D('',#56200,#56201,#56202); -#56200 = CARTESIAN_POINT('',(2.4,-1.225,-0.4)); -#56201 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56202 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56203 = PCURVE('',#38147,#56204); -#56204 = DEFINITIONAL_REPRESENTATION('',(#56205),#56213); -#56205 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#56206,#56207,#56208,#56209 - ,#56210,#56211,#56212),.UNSPECIFIED.,.T.,.F.) +#58559 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#58560 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#58561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58562 = ORIENTED_EDGE('',*,*,#58563,.F.); +#58563 = EDGE_CURVE('',#58564,#58541,#58566,.T.); +#58564 = VERTEX_POINT('',#58565); +#58565 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); +#58566 = SURFACE_CURVE('',#58567,(#58571,#58578),.PCURVE_S1.); +#58567 = LINE('',#58568,#58569); +#58568 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); +#58569 = VECTOR('',#58570,1.); +#58570 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58571 = PCURVE('',#40539,#58572); +#58572 = DEFINITIONAL_REPRESENTATION('',(#58573),#58577); +#58573 = LINE('',#58574,#58575); +#58574 = CARTESIAN_POINT('',(4.996446609407,2.1)); +#58575 = VECTOR('',#58576,1.); +#58576 = DIRECTION('',(1.,0.E+000)); +#58577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58578 = PCURVE('',#43621,#58579); +#58579 = DEFINITIONAL_REPRESENTATION('',(#58580),#58584); +#58580 = LINE('',#58581,#58582); +#58581 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58582 = VECTOR('',#58583,1.); +#58583 = DIRECTION('',(1.,0.E+000)); +#58584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58585 = ORIENTED_EDGE('',*,*,#58586,.F.); +#58586 = EDGE_CURVE('',#58587,#58564,#58589,.T.); +#58587 = VERTEX_POINT('',#58588); +#58588 = CARTESIAN_POINT('',(2.25,-1.225,-0.4)); +#58589 = SURFACE_CURVE('',#58590,(#58595,#58606),.PCURVE_S1.); +#58590 = CIRCLE('',#58591,0.15); +#58591 = AXIS2_PLACEMENT_3D('',#58592,#58593,#58594); +#58592 = CARTESIAN_POINT('',(2.4,-1.225,-0.4)); +#58593 = DIRECTION('',(0.E+000,1.,0.E+000)); +#58594 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58595 = PCURVE('',#40539,#58596); +#58596 = DEFINITIONAL_REPRESENTATION('',(#58597),#58605); +#58597 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#58598,#58599,#58600,#58601 + ,#58602,#58603,#58604),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#56206 = CARTESIAN_POINT('',(4.846446609407,1.95)); -#56207 = CARTESIAN_POINT('',(4.846446609407,2.209807621135)); -#56208 = CARTESIAN_POINT('',(5.071446609407,2.079903810568)); -#56209 = CARTESIAN_POINT('',(5.296446609407,1.95)); -#56210 = CARTESIAN_POINT('',(5.071446609407,1.820096189432)); -#56211 = CARTESIAN_POINT('',(4.846446609407,1.690192378865)); -#56212 = CARTESIAN_POINT('',(4.846446609407,1.95)); -#56213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56214 = PCURVE('',#41202,#56215); -#56215 = DEFINITIONAL_REPRESENTATION('',(#56216),#56219); -#56216 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56217,#56218),.UNSPECIFIED., +#58598 = CARTESIAN_POINT('',(4.846446609407,1.95)); +#58599 = CARTESIAN_POINT('',(4.846446609407,2.209807621135)); +#58600 = CARTESIAN_POINT('',(5.071446609407,2.079903810568)); +#58601 = CARTESIAN_POINT('',(5.296446609407,1.95)); +#58602 = CARTESIAN_POINT('',(5.071446609407,1.820096189432)); +#58603 = CARTESIAN_POINT('',(4.846446609407,1.690192378865)); +#58604 = CARTESIAN_POINT('',(4.846446609407,1.95)); +#58605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58606 = PCURVE('',#43594,#58607); +#58607 = DEFINITIONAL_REPRESENTATION('',(#58608),#58611); +#58608 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58609,#58610),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56217 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#56218 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#56219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56220 = ORIENTED_EDGE('',*,*,#56221,.T.); -#56221 = EDGE_CURVE('',#56195,#56222,#56224,.T.); -#56222 = VERTEX_POINT('',#56223); -#56223 = CARTESIAN_POINT('',(2.25,-1.225,-0.41)); -#56224 = SURFACE_CURVE('',#56225,(#56229,#56236),.PCURVE_S1.); -#56225 = LINE('',#56226,#56227); -#56226 = CARTESIAN_POINT('',(2.25,-1.225,-0.4)); -#56227 = VECTOR('',#56228,1.); -#56228 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56229 = PCURVE('',#38147,#56230); -#56230 = DEFINITIONAL_REPRESENTATION('',(#56231),#56235); -#56231 = LINE('',#56232,#56233); -#56232 = CARTESIAN_POINT('',(4.846446609407,1.95)); -#56233 = VECTOR('',#56234,1.); -#56234 = DIRECTION('',(0.E+000,-1.)); -#56235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56236 = PCURVE('',#41173,#56237); -#56237 = DEFINITIONAL_REPRESENTATION('',(#56238),#56242); -#56238 = LINE('',#56239,#56240); -#56239 = CARTESIAN_POINT('',(1.21,0.E+000)); -#56240 = VECTOR('',#56241,1.); -#56241 = DIRECTION('',(1.,0.E+000)); -#56242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56243 = ORIENTED_EDGE('',*,*,#56244,.T.); -#56244 = EDGE_CURVE('',#56222,#56245,#56247,.T.); -#56245 = VERTEX_POINT('',#56246); -#56246 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); -#56247 = SURFACE_CURVE('',#56248,(#56253,#56260),.PCURVE_S1.); -#56248 = CIRCLE('',#56249,0.15); -#56249 = AXIS2_PLACEMENT_3D('',#56250,#56251,#56252); -#56250 = CARTESIAN_POINT('',(2.4,-1.225,-0.41)); -#56251 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56252 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56253 = PCURVE('',#38147,#56254); -#56254 = DEFINITIONAL_REPRESENTATION('',(#56255),#56259); -#56255 = CIRCLE('',#56256,0.15); -#56256 = AXIS2_PLACEMENT_2D('',#56257,#56258); -#56257 = CARTESIAN_POINT('',(4.996446609407,1.94)); -#56258 = DIRECTION('',(-1.,0.E+000)); -#56259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56260 = PCURVE('',#41146,#56261); -#56261 = DEFINITIONAL_REPRESENTATION('',(#56262),#56265); -#56262 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56263,#56264),.UNSPECIFIED., +#58609 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58610 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58612 = ORIENTED_EDGE('',*,*,#58613,.T.); +#58613 = EDGE_CURVE('',#58587,#58614,#58616,.T.); +#58614 = VERTEX_POINT('',#58615); +#58615 = CARTESIAN_POINT('',(2.25,-1.225,-0.41)); +#58616 = SURFACE_CURVE('',#58617,(#58621,#58628),.PCURVE_S1.); +#58617 = LINE('',#58618,#58619); +#58618 = CARTESIAN_POINT('',(2.25,-1.225,-0.4)); +#58619 = VECTOR('',#58620,1.); +#58620 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58621 = PCURVE('',#40539,#58622); +#58622 = DEFINITIONAL_REPRESENTATION('',(#58623),#58627); +#58623 = LINE('',#58624,#58625); +#58624 = CARTESIAN_POINT('',(4.846446609407,1.95)); +#58625 = VECTOR('',#58626,1.); +#58626 = DIRECTION('',(0.E+000,-1.)); +#58627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58628 = PCURVE('',#43565,#58629); +#58629 = DEFINITIONAL_REPRESENTATION('',(#58630),#58634); +#58630 = LINE('',#58631,#58632); +#58631 = CARTESIAN_POINT('',(1.21,0.E+000)); +#58632 = VECTOR('',#58633,1.); +#58633 = DIRECTION('',(1.,0.E+000)); +#58634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58635 = ORIENTED_EDGE('',*,*,#58636,.T.); +#58636 = EDGE_CURVE('',#58614,#58637,#58639,.T.); +#58637 = VERTEX_POINT('',#58638); +#58638 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); +#58639 = SURFACE_CURVE('',#58640,(#58645,#58652),.PCURVE_S1.); +#58640 = CIRCLE('',#58641,0.15); +#58641 = AXIS2_PLACEMENT_3D('',#58642,#58643,#58644); +#58642 = CARTESIAN_POINT('',(2.4,-1.225,-0.41)); +#58643 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58644 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58645 = PCURVE('',#40539,#58646); +#58646 = DEFINITIONAL_REPRESENTATION('',(#58647),#58651); +#58647 = CIRCLE('',#58648,0.15); +#58648 = AXIS2_PLACEMENT_2D('',#58649,#58650); +#58649 = CARTESIAN_POINT('',(4.996446609407,1.94)); +#58650 = DIRECTION('',(-1.,0.E+000)); +#58651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58652 = PCURVE('',#43538,#58653); +#58653 = DEFINITIONAL_REPRESENTATION('',(#58654),#58657); +#58654 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58655,#58656),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56263 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#56264 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#56265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56266 = ORIENTED_EDGE('',*,*,#56267,.F.); -#56267 = EDGE_CURVE('',#56268,#56245,#56270,.T.); -#56268 = VERTEX_POINT('',#56269); -#56269 = CARTESIAN_POINT('',(2.596446609407,-1.225,-0.56)); -#56270 = SURFACE_CURVE('',#56271,(#56275,#56282),.PCURVE_S1.); -#56271 = LINE('',#56272,#56273); -#56272 = CARTESIAN_POINT('',(2.596446609407,-1.225,-0.56)); -#56273 = VECTOR('',#56274,1.); -#56274 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56275 = PCURVE('',#38147,#56276); -#56276 = DEFINITIONAL_REPRESENTATION('',(#56277),#56281); -#56277 = LINE('',#56278,#56279); -#56278 = CARTESIAN_POINT('',(5.192893218814,1.79)); -#56279 = VECTOR('',#56280,1.); -#56280 = DIRECTION('',(-1.,0.E+000)); -#56281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56282 = PCURVE('',#40346,#56283); -#56283 = DEFINITIONAL_REPRESENTATION('',(#56284),#56288); -#56284 = LINE('',#56285,#56286); -#56285 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); -#56286 = VECTOR('',#56287,1.); -#56287 = DIRECTION('',(-1.,0.E+000)); -#56288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56289 = ORIENTED_EDGE('',*,*,#56290,.F.); -#56290 = EDGE_CURVE('',#56291,#56268,#56293,.T.); -#56291 = VERTEX_POINT('',#56292); -#56292 = CARTESIAN_POINT('',(2.596446609407,-1.225,-1.53)); -#56293 = SURFACE_CURVE('',#56294,(#56298,#56305),.PCURVE_S1.); -#56294 = LINE('',#56295,#56296); -#56295 = CARTESIAN_POINT('',(2.596446609407,-1.225,-1.53)); -#56296 = VECTOR('',#56297,1.); -#56297 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56298 = PCURVE('',#38147,#56299); -#56299 = DEFINITIONAL_REPRESENTATION('',(#56300),#56304); -#56300 = LINE('',#56301,#56302); -#56301 = CARTESIAN_POINT('',(5.192893218814,0.82)); -#56302 = VECTOR('',#56303,1.); -#56303 = DIRECTION('',(0.E+000,1.)); -#56304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56305 = PCURVE('',#56306,#56311); -#56306 = CYLINDRICAL_SURFACE('',#56307,0.55); -#56307 = AXIS2_PLACEMENT_3D('',#56308,#56309,#56310); -#56308 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); -#56309 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56310 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56311 = DEFINITIONAL_REPRESENTATION('',(#56312),#56315); -#56312 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56313,#56314),.UNSPECIFIED., +#58655 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#58656 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#58657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58658 = ORIENTED_EDGE('',*,*,#58659,.F.); +#58659 = EDGE_CURVE('',#58660,#58637,#58662,.T.); +#58660 = VERTEX_POINT('',#58661); +#58661 = CARTESIAN_POINT('',(2.596446609407,-1.225,-0.56)); +#58662 = SURFACE_CURVE('',#58663,(#58667,#58674),.PCURVE_S1.); +#58663 = LINE('',#58664,#58665); +#58664 = CARTESIAN_POINT('',(2.596446609407,-1.225,-0.56)); +#58665 = VECTOR('',#58666,1.); +#58666 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58667 = PCURVE('',#40539,#58668); +#58668 = DEFINITIONAL_REPRESENTATION('',(#58669),#58673); +#58669 = LINE('',#58670,#58671); +#58670 = CARTESIAN_POINT('',(5.192893218814,1.79)); +#58671 = VECTOR('',#58672,1.); +#58672 = DIRECTION('',(-1.,0.E+000)); +#58673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58674 = PCURVE('',#42738,#58675); +#58675 = DEFINITIONAL_REPRESENTATION('',(#58676),#58680); +#58676 = LINE('',#58677,#58678); +#58677 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); +#58678 = VECTOR('',#58679,1.); +#58679 = DIRECTION('',(-1.,0.E+000)); +#58680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58681 = ORIENTED_EDGE('',*,*,#58682,.F.); +#58682 = EDGE_CURVE('',#58683,#58660,#58685,.T.); +#58683 = VERTEX_POINT('',#58684); +#58684 = CARTESIAN_POINT('',(2.596446609407,-1.225,-1.53)); +#58685 = SURFACE_CURVE('',#58686,(#58690,#58697),.PCURVE_S1.); +#58686 = LINE('',#58687,#58688); +#58687 = CARTESIAN_POINT('',(2.596446609407,-1.225,-1.53)); +#58688 = VECTOR('',#58689,1.); +#58689 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58690 = PCURVE('',#40539,#58691); +#58691 = DEFINITIONAL_REPRESENTATION('',(#58692),#58696); +#58692 = LINE('',#58693,#58694); +#58693 = CARTESIAN_POINT('',(5.192893218814,0.82)); +#58694 = VECTOR('',#58695,1.); +#58695 = DIRECTION('',(0.E+000,1.)); +#58696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58697 = PCURVE('',#58698,#58703); +#58698 = CYLINDRICAL_SURFACE('',#58699,0.55); +#58699 = AXIS2_PLACEMENT_3D('',#58700,#58701,#58702); +#58700 = CARTESIAN_POINT('',(2.596446609407,-0.675,-2.35)); +#58701 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58702 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58703 = DEFINITIONAL_REPRESENTATION('',(#58704),#58707); +#58704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58705,#58706),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#56313 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#56314 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#56315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56316 = ORIENTED_EDGE('',*,*,#56317,.F.); -#56317 = EDGE_CURVE('',#56318,#56291,#56320,.T.); -#56318 = VERTEX_POINT('',#56319); -#56319 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#56320 = SURFACE_CURVE('',#56321,(#56325,#56332),.PCURVE_S1.); -#56321 = LINE('',#56322,#56323); -#56322 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#56323 = VECTOR('',#56324,1.); -#56324 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56325 = PCURVE('',#38147,#56326); -#56326 = DEFINITIONAL_REPRESENTATION('',(#56327),#56331); -#56327 = LINE('',#56328,#56329); -#56328 = CARTESIAN_POINT('',(4.386446609407,0.82)); -#56329 = VECTOR('',#56330,1.); -#56330 = DIRECTION('',(1.,0.E+000)); -#56331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56332 = PCURVE('',#40920,#56333); -#56333 = DEFINITIONAL_REPRESENTATION('',(#56334),#56338); -#56334 = LINE('',#56335,#56336); -#56335 = CARTESIAN_POINT('',(0.35,5.54)); -#56336 = VECTOR('',#56337,1.); -#56337 = DIRECTION('',(0.E+000,1.)); -#56338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56339 = ORIENTED_EDGE('',*,*,#56340,.T.); -#56340 = EDGE_CURVE('',#56318,#56341,#56343,.T.); -#56341 = VERTEX_POINT('',#56342); -#56342 = CARTESIAN_POINT('',(1.79,-1.225,-1.21)); -#56343 = SURFACE_CURVE('',#56344,(#56348,#56355),.PCURVE_S1.); -#56344 = LINE('',#56345,#56346); -#56345 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#56346 = VECTOR('',#56347,1.); -#56347 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56348 = PCURVE('',#38147,#56349); -#56349 = DEFINITIONAL_REPRESENTATION('',(#56350),#56354); -#56350 = LINE('',#56351,#56352); -#56351 = CARTESIAN_POINT('',(4.386446609407,0.82)); -#56352 = VECTOR('',#56353,1.); -#56353 = DIRECTION('',(0.E+000,1.)); -#56354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56355 = PCURVE('',#56356,#56361); -#56356 = PLANE('',#56357); -#56357 = AXIS2_PLACEMENT_3D('',#56358,#56359,#56360); -#56358 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#56359 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56360 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56361 = DEFINITIONAL_REPRESENTATION('',(#56362),#56366); -#56362 = LINE('',#56363,#56364); -#56363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56364 = VECTOR('',#56365,1.); -#56365 = DIRECTION('',(1.,0.E+000)); -#56366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56367 = ORIENTED_EDGE('',*,*,#56368,.T.); -#56368 = EDGE_CURVE('',#56341,#56369,#56371,.T.); -#56369 = VERTEX_POINT('',#56370); -#56370 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); -#56371 = SURFACE_CURVE('',#56372,(#56377,#56384),.PCURVE_S1.); -#56372 = CIRCLE('',#56373,8.E-002); -#56373 = AXIS2_PLACEMENT_3D('',#56374,#56375,#56376); -#56374 = CARTESIAN_POINT('',(1.71,-1.225,-1.21)); -#56375 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56376 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56377 = PCURVE('',#38147,#56378); -#56378 = DEFINITIONAL_REPRESENTATION('',(#56379),#56383); -#56379 = CIRCLE('',#56380,8.E-002); -#56380 = AXIS2_PLACEMENT_2D('',#56381,#56382); -#56381 = CARTESIAN_POINT('',(4.306446609407,1.14)); -#56382 = DIRECTION('',(1.,0.E+000)); -#56383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56384 = PCURVE('',#41812,#56385); -#56385 = DEFINITIONAL_REPRESENTATION('',(#56386),#56389); -#56386 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#56387,#56388),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#56387 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56388 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#56389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56390 = ORIENTED_EDGE('',*,*,#56391,.T.); -#56391 = EDGE_CURVE('',#56369,#56392,#56394,.T.); -#56392 = VERTEX_POINT('',#56393); -#56393 = CARTESIAN_POINT('',(1.E-002,-1.225,-1.13)); -#56394 = SURFACE_CURVE('',#56395,(#56399,#56406),.PCURVE_S1.); -#56395 = LINE('',#56396,#56397); -#56396 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); -#56397 = VECTOR('',#56398,1.); -#56398 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56399 = PCURVE('',#38147,#56400); -#56400 = DEFINITIONAL_REPRESENTATION('',(#56401),#56405); -#56401 = LINE('',#56402,#56403); -#56402 = CARTESIAN_POINT('',(4.306446609407,1.22)); -#56403 = VECTOR('',#56404,1.); -#56404 = DIRECTION('',(-1.,0.E+000)); -#56405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56406 = PCURVE('',#41779,#56407); -#56407 = DEFINITIONAL_REPRESENTATION('',(#56408),#56412); -#56408 = LINE('',#56409,#56410); -#56409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56410 = VECTOR('',#56411,1.); -#56411 = DIRECTION('',(1.,0.E+000)); -#56412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56413 = ORIENTED_EDGE('',*,*,#56414,.T.); -#56414 = EDGE_CURVE('',#56392,#56415,#56417,.T.); -#56415 = VERTEX_POINT('',#56416); -#56416 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); -#56417 = SURFACE_CURVE('',#56418,(#56422,#56429),.PCURVE_S1.); -#56418 = LINE('',#56419,#56420); -#56419 = CARTESIAN_POINT('',(1.E-002,-1.225,-1.13)); -#56420 = VECTOR('',#56421,1.); -#56421 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56422 = PCURVE('',#38147,#56423); -#56423 = DEFINITIONAL_REPRESENTATION('',(#56424),#56428); -#56424 = LINE('',#56425,#56426); -#56425 = CARTESIAN_POINT('',(2.606446609407,1.22)); -#56426 = VECTOR('',#56427,1.); -#56427 = DIRECTION('',(0.E+000,1.)); -#56428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56429 = PCURVE('',#41751,#56430); -#56430 = DEFINITIONAL_REPRESENTATION('',(#56431),#56435); -#56431 = LINE('',#56432,#56433); -#56432 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#56433 = VECTOR('',#56434,1.); -#56434 = DIRECTION('',(1.,0.E+000)); -#56435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56436 = ORIENTED_EDGE('',*,*,#56437,.T.); -#56437 = EDGE_CURVE('',#56415,#56438,#56440,.T.); -#56438 = VERTEX_POINT('',#56439); -#56439 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); -#56440 = SURFACE_CURVE('',#56441,(#56445,#56452),.PCURVE_S1.); -#56441 = LINE('',#56442,#56443); -#56442 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); -#56443 = VECTOR('',#56444,1.); -#56444 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56445 = PCURVE('',#38147,#56446); -#56446 = DEFINITIONAL_REPRESENTATION('',(#56447),#56451); -#56447 = LINE('',#56448,#56449); -#56448 = CARTESIAN_POINT('',(2.606446609407,1.7)); -#56449 = VECTOR('',#56450,1.); -#56450 = DIRECTION('',(1.,0.E+000)); -#56451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56452 = PCURVE('',#56453,#56458); -#56453 = PLANE('',#56454); -#56454 = AXIS2_PLACEMENT_3D('',#56455,#56456,#56457); -#56455 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); -#56456 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56457 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56458 = DEFINITIONAL_REPRESENTATION('',(#56459),#56463); -#56459 = LINE('',#56460,#56461); -#56460 = CARTESIAN_POINT('',(0.36,0.E+000)); -#56461 = VECTOR('',#56462,1.); -#56462 = DIRECTION('',(1.,0.E+000)); -#56463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56464 = ORIENTED_EDGE('',*,*,#56465,.T.); -#56465 = EDGE_CURVE('',#56438,#56466,#56468,.T.); -#56466 = VERTEX_POINT('',#56467); -#56467 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); -#56468 = SURFACE_CURVE('',#56469,(#56473,#56480),.PCURVE_S1.); -#56469 = LINE('',#56470,#56471); -#56470 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); -#56471 = VECTOR('',#56472,1.); -#56472 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56473 = PCURVE('',#38147,#56474); -#56474 = DEFINITIONAL_REPRESENTATION('',(#56475),#56479); -#56475 = LINE('',#56476,#56477); -#56476 = CARTESIAN_POINT('',(4.096446609407,1.7)); -#56477 = VECTOR('',#56478,1.); -#56478 = DIRECTION('',(0.E+000,1.)); -#56479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56480 = PCURVE('',#56481,#56486); -#56481 = PLANE('',#56482); -#56482 = AXIS2_PLACEMENT_3D('',#56483,#56484,#56485); -#56483 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); -#56484 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56485 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56486 = DEFINITIONAL_REPRESENTATION('',(#56487),#56491); -#56487 = LINE('',#56488,#56489); -#56488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56489 = VECTOR('',#56490,1.); -#56490 = DIRECTION('',(1.,0.E+000)); -#56491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56492 = ORIENTED_EDGE('',*,*,#56493,.T.); -#56493 = EDGE_CURVE('',#56466,#56494,#56496,.T.); -#56494 = VERTEX_POINT('',#56495); -#56495 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); -#56496 = SURFACE_CURVE('',#56497,(#56501,#56508),.PCURVE_S1.); -#56497 = LINE('',#56498,#56499); -#56498 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); -#56499 = VECTOR('',#56500,1.); -#56500 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56501 = PCURVE('',#38147,#56502); -#56502 = DEFINITIONAL_REPRESENTATION('',(#56503),#56507); -#56503 = LINE('',#56504,#56505); -#56504 = CARTESIAN_POINT('',(4.096446609407,2.15)); -#56505 = VECTOR('',#56506,1.); -#56506 = DIRECTION('',(-1.,0.E+000)); -#56507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56508 = PCURVE('',#56509,#56514); -#56509 = PLANE('',#56510); -#56510 = AXIS2_PLACEMENT_3D('',#56511,#56512,#56513); -#56511 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); -#56512 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56513 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56514 = DEFINITIONAL_REPRESENTATION('',(#56515),#56519); -#56515 = LINE('',#56516,#56517); -#56516 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56517 = VECTOR('',#56518,1.); -#56518 = DIRECTION('',(1.,0.E+000)); -#56519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56520 = ORIENTED_EDGE('',*,*,#56521,.T.); -#56521 = EDGE_CURVE('',#56494,#55850,#56522,.T.); -#56522 = SURFACE_CURVE('',#56523,(#56527,#56534),.PCURVE_S1.); -#56523 = LINE('',#56524,#56525); -#56524 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); -#56525 = VECTOR('',#56526,1.); -#56526 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56527 = PCURVE('',#38147,#56528); -#56528 = DEFINITIONAL_REPRESENTATION('',(#56529),#56533); -#56529 = LINE('',#56530,#56531); -#56530 = CARTESIAN_POINT('',(3.406446609407,2.15)); -#56531 = VECTOR('',#56532,1.); -#56532 = DIRECTION('',(0.E+000,1.)); -#56533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56534 = PCURVE('',#41631,#56535); -#56535 = DEFINITIONAL_REPRESENTATION('',(#56536),#56540); -#56536 = LINE('',#56537,#56538); -#56537 = CARTESIAN_POINT('',(0.20484542651,-0.3)); -#56538 = VECTOR('',#56539,1.); -#56539 = DIRECTION('',(1.,0.E+000)); -#56540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56541 = ADVANCED_FACE('',(#56542),#55218,.F.); -#56542 = FACE_BOUND('',#56543,.F.); -#56543 = EDGE_LOOP('',(#56544,#56545,#56568,#56596)); -#56544 = ORIENTED_EDGE('',*,*,#55200,.F.); -#56545 = ORIENTED_EDGE('',*,*,#56546,.T.); -#56546 = EDGE_CURVE('',#55201,#56547,#56549,.T.); -#56547 = VERTEX_POINT('',#56548); -#56548 = CARTESIAN_POINT('',(-0.35,-1.125,2.)); -#56549 = SURFACE_CURVE('',#56550,(#56554,#56561),.PCURVE_S1.); -#56550 = LINE('',#56551,#56552); -#56551 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); -#56552 = VECTOR('',#56553,1.); -#56553 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56554 = PCURVE('',#55218,#56555); -#56555 = DEFINITIONAL_REPRESENTATION('',(#56556),#56560); -#56556 = LINE('',#56557,#56558); -#56557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56558 = VECTOR('',#56559,1.); -#56559 = DIRECTION('',(0.E+000,-1.)); -#56560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56561 = PCURVE('',#55834,#56562); -#56562 = DEFINITIONAL_REPRESENTATION('',(#56563),#56567); -#56563 = LINE('',#56564,#56565); -#56564 = CARTESIAN_POINT('',(1.85,0.E+000)); -#56565 = VECTOR('',#56566,1.); -#56566 = DIRECTION('',(0.E+000,-1.)); -#56567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56568 = ORIENTED_EDGE('',*,*,#56569,.T.); -#56569 = EDGE_CURVE('',#56547,#56570,#56572,.T.); -#56570 = VERTEX_POINT('',#56571); -#56571 = CARTESIAN_POINT('',(-0.35,-1.125,1.55)); -#56572 = SURFACE_CURVE('',#56573,(#56577,#56584),.PCURVE_S1.); -#56573 = LINE('',#56574,#56575); -#56574 = CARTESIAN_POINT('',(-0.35,-1.125,2.)); -#56575 = VECTOR('',#56576,1.); -#56576 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56577 = PCURVE('',#55218,#56578); -#56578 = DEFINITIONAL_REPRESENTATION('',(#56579),#56583); -#56579 = LINE('',#56580,#56581); -#56580 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56581 = VECTOR('',#56582,1.); -#56582 = DIRECTION('',(1.,0.E+000)); -#56583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56584 = PCURVE('',#56585,#56590); -#56585 = PLANE('',#56586); -#56586 = AXIS2_PLACEMENT_3D('',#56587,#56588,#56589); -#56587 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); -#56588 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56589 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56590 = DEFINITIONAL_REPRESENTATION('',(#56591),#56595); -#56591 = LINE('',#56592,#56593); -#56592 = CARTESIAN_POINT('',(-0.35,2.)); -#56593 = VECTOR('',#56594,1.); -#56594 = DIRECTION('',(0.E+000,-1.)); -#56595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56596 = ORIENTED_EDGE('',*,*,#56597,.F.); -#56597 = EDGE_CURVE('',#55203,#56570,#56598,.T.); -#56598 = SURFACE_CURVE('',#56599,(#56603,#56610),.PCURVE_S1.); -#56599 = LINE('',#56600,#56601); -#56600 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); -#56601 = VECTOR('',#56602,1.); -#56602 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56603 = PCURVE('',#55218,#56604); -#56604 = DEFINITIONAL_REPRESENTATION('',(#56605),#56609); -#56605 = LINE('',#56606,#56607); -#56606 = CARTESIAN_POINT('',(0.45,0.E+000)); -#56607 = VECTOR('',#56608,1.); -#56608 = DIRECTION('',(0.E+000,-1.)); -#56609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56610 = PCURVE('',#55246,#56611); -#56611 = DEFINITIONAL_REPRESENTATION('',(#56612),#56616); -#56612 = LINE('',#56613,#56614); -#56613 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56614 = VECTOR('',#56615,1.); -#56615 = DIRECTION('',(0.E+000,-1.)); -#56616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56617 = ADVANCED_FACE('',(#56618),#55923,.F.); -#56618 = FACE_BOUND('',#56619,.F.); -#56619 = EDGE_LOOP('',(#56620,#56621,#56644,#56672)); -#56620 = ORIENTED_EDGE('',*,*,#55907,.F.); -#56621 = ORIENTED_EDGE('',*,*,#56622,.T.); -#56622 = EDGE_CURVE('',#55880,#56623,#56625,.T.); -#56623 = VERTEX_POINT('',#56624); -#56624 = CARTESIAN_POINT('',(1.5,-1.125,2.)); -#56625 = SURFACE_CURVE('',#56626,(#56630,#56637),.PCURVE_S1.); -#56626 = LINE('',#56627,#56628); -#56627 = CARTESIAN_POINT('',(1.5,-1.225,2.)); -#56628 = VECTOR('',#56629,1.); -#56629 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56630 = PCURVE('',#55923,#56631); -#56631 = DEFINITIONAL_REPRESENTATION('',(#56632),#56636); -#56632 = LINE('',#56633,#56634); -#56633 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56634 = VECTOR('',#56635,1.); -#56635 = DIRECTION('',(0.E+000,-1.)); -#56636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56637 = PCURVE('',#55895,#56638); -#56638 = DEFINITIONAL_REPRESENTATION('',(#56639),#56643); -#56639 = LINE('',#56640,#56641); -#56640 = CARTESIAN_POINT('',(0.45,0.E+000)); -#56641 = VECTOR('',#56642,1.); -#56642 = DIRECTION('',(0.E+000,-1.)); -#56643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56644 = ORIENTED_EDGE('',*,*,#56645,.T.); -#56645 = EDGE_CURVE('',#56623,#56646,#56648,.T.); -#56646 = VERTEX_POINT('',#56647); -#56647 = CARTESIAN_POINT('',(1.E-002,-1.125,2.)); -#56648 = SURFACE_CURVE('',#56649,(#56653,#56660),.PCURVE_S1.); -#56649 = LINE('',#56650,#56651); -#56650 = CARTESIAN_POINT('',(1.5,-1.125,2.)); -#56651 = VECTOR('',#56652,1.); -#56652 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56653 = PCURVE('',#55923,#56654); -#56654 = DEFINITIONAL_REPRESENTATION('',(#56655),#56659); -#56655 = LINE('',#56656,#56657); -#56656 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56657 = VECTOR('',#56658,1.); -#56658 = DIRECTION('',(1.,0.E+000)); -#56659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56660 = PCURVE('',#56661,#56666); -#56661 = PLANE('',#56662); -#56662 = AXIS2_PLACEMENT_3D('',#56663,#56664,#56665); -#56663 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); -#56664 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56665 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56666 = DEFINITIONAL_REPRESENTATION('',(#56667),#56671); -#56667 = LINE('',#56668,#56669); -#56668 = CARTESIAN_POINT('',(1.5,2.)); -#56669 = VECTOR('',#56670,1.); -#56670 = DIRECTION('',(-1.,0.E+000)); -#56671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56672 = ORIENTED_EDGE('',*,*,#56673,.T.); -#56673 = EDGE_CURVE('',#56646,#55908,#56674,.T.); -#56674 = SURFACE_CURVE('',#56675,(#56679,#56686),.PCURVE_S1.); -#56675 = LINE('',#56676,#56677); -#56676 = CARTESIAN_POINT('',(1.E-002,-1.125,2.)); -#56677 = VECTOR('',#56678,1.); -#56678 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56679 = PCURVE('',#55923,#56680); -#56680 = DEFINITIONAL_REPRESENTATION('',(#56681),#56685); -#56681 = LINE('',#56682,#56683); -#56682 = CARTESIAN_POINT('',(1.49,-0.1)); -#56683 = VECTOR('',#56684,1.); -#56684 = DIRECTION('',(0.E+000,1.)); -#56685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56686 = PCURVE('',#41511,#56687); -#56687 = DEFINITIONAL_REPRESENTATION('',(#56688),#56692); -#56688 = LINE('',#56689,#56690); -#56689 = CARTESIAN_POINT('',(0.25484542651,-0.4)); -#56690 = VECTOR('',#56691,1.); -#56691 = DIRECTION('',(0.E+000,1.)); -#56692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56693 = ADVANCED_FACE('',(#56694),#55834,.F.); -#56694 = FACE_BOUND('',#56695,.F.); -#56695 = EDGE_LOOP('',(#56696,#56697,#56720,#56741)); -#56696 = ORIENTED_EDGE('',*,*,#55820,.F.); -#56697 = ORIENTED_EDGE('',*,*,#56698,.F.); -#56698 = EDGE_CURVE('',#56699,#55798,#56701,.T.); -#56699 = VERTEX_POINT('',#56700); -#56700 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); -#56701 = SURFACE_CURVE('',#56702,(#56706,#56713),.PCURVE_S1.); -#56702 = LINE('',#56703,#56704); -#56703 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); -#56704 = VECTOR('',#56705,1.); -#56705 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56706 = PCURVE('',#55834,#56707); -#56707 = DEFINITIONAL_REPRESENTATION('',(#56708),#56712); -#56708 = LINE('',#56709,#56710); -#56709 = CARTESIAN_POINT('',(1.51,-0.1)); -#56710 = VECTOR('',#56711,1.); -#56711 = DIRECTION('',(0.E+000,1.)); -#56712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56713 = PCURVE('',#42221,#56714); -#56714 = DEFINITIONAL_REPRESENTATION('',(#56715),#56719); -#56715 = LINE('',#56716,#56717); -#56716 = CARTESIAN_POINT('',(0.78,-0.4)); -#56717 = VECTOR('',#56718,1.); -#56718 = DIRECTION('',(0.E+000,1.)); -#56719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56720 = ORIENTED_EDGE('',*,*,#56721,.T.); -#56721 = EDGE_CURVE('',#56699,#56547,#56722,.T.); -#56722 = SURFACE_CURVE('',#56723,(#56727,#56734),.PCURVE_S1.); -#56723 = LINE('',#56724,#56725); -#56724 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); -#56725 = VECTOR('',#56726,1.); -#56726 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56727 = PCURVE('',#55834,#56728); -#56728 = DEFINITIONAL_REPRESENTATION('',(#56729),#56733); -#56729 = LINE('',#56730,#56731); -#56730 = CARTESIAN_POINT('',(1.51,-0.1)); -#56731 = VECTOR('',#56732,1.); -#56732 = DIRECTION('',(1.,0.E+000)); -#56733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56734 = PCURVE('',#56585,#56735); -#56735 = DEFINITIONAL_REPRESENTATION('',(#56736),#56740); -#56736 = LINE('',#56737,#56738); -#56737 = CARTESIAN_POINT('',(-1.E-002,2.)); -#56738 = VECTOR('',#56739,1.); -#56739 = DIRECTION('',(-1.,0.E+000)); -#56740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56741 = ORIENTED_EDGE('',*,*,#56546,.F.); -#56742 = ADVANCED_FACE('',(#56743),#55895,.F.); -#56743 = FACE_BOUND('',#56744,.F.); -#56744 = EDGE_LOOP('',(#56745,#56746,#56769,#56790)); -#56745 = ORIENTED_EDGE('',*,*,#55879,.F.); -#56746 = ORIENTED_EDGE('',*,*,#56747,.T.); -#56747 = EDGE_CURVE('',#55852,#56748,#56750,.T.); -#56748 = VERTEX_POINT('',#56749); -#56749 = CARTESIAN_POINT('',(1.5,-1.125,1.55)); -#56750 = SURFACE_CURVE('',#56751,(#56755,#56762),.PCURVE_S1.); -#56751 = LINE('',#56752,#56753); -#56752 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); -#56753 = VECTOR('',#56754,1.); -#56754 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56755 = PCURVE('',#55895,#56756); -#56756 = DEFINITIONAL_REPRESENTATION('',(#56757),#56761); -#56757 = LINE('',#56758,#56759); -#56758 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#56759 = VECTOR('',#56760,1.); -#56760 = DIRECTION('',(0.E+000,-1.)); -#56761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56762 = PCURVE('',#55867,#56763); -#56763 = DEFINITIONAL_REPRESENTATION('',(#56764),#56768); -#56764 = LINE('',#56765,#56766); -#56765 = CARTESIAN_POINT('',(1.85,0.E+000)); -#56766 = VECTOR('',#56767,1.); -#56767 = DIRECTION('',(0.E+000,-1.)); -#56768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56769 = ORIENTED_EDGE('',*,*,#56770,.T.); -#56770 = EDGE_CURVE('',#56748,#56623,#56771,.T.); -#56771 = SURFACE_CURVE('',#56772,(#56776,#56783),.PCURVE_S1.); -#56772 = LINE('',#56773,#56774); -#56773 = CARTESIAN_POINT('',(1.5,-1.125,1.55)); -#56774 = VECTOR('',#56775,1.); -#56775 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56776 = PCURVE('',#55895,#56777); -#56777 = DEFINITIONAL_REPRESENTATION('',(#56778),#56782); -#56778 = LINE('',#56779,#56780); -#56779 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56780 = VECTOR('',#56781,1.); -#56781 = DIRECTION('',(1.,0.E+000)); -#56782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56783 = PCURVE('',#56661,#56784); -#56784 = DEFINITIONAL_REPRESENTATION('',(#56785),#56789); -#56785 = LINE('',#56786,#56787); -#56786 = CARTESIAN_POINT('',(1.5,1.55)); -#56787 = VECTOR('',#56788,1.); -#56788 = DIRECTION('',(0.E+000,1.)); -#56789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56790 = ORIENTED_EDGE('',*,*,#56622,.F.); -#56791 = ADVANCED_FACE('',(#56792),#55246,.F.); -#56792 = FACE_BOUND('',#56793,.F.); -#56793 = EDGE_LOOP('',(#56794,#56795,#56796,#56819)); -#56794 = ORIENTED_EDGE('',*,*,#55230,.F.); -#56795 = ORIENTED_EDGE('',*,*,#56597,.T.); -#56796 = ORIENTED_EDGE('',*,*,#56797,.T.); -#56797 = EDGE_CURVE('',#56570,#56798,#56800,.T.); -#56798 = VERTEX_POINT('',#56799); -#56799 = CARTESIAN_POINT('',(0.79,-1.125,1.55)); -#56800 = SURFACE_CURVE('',#56801,(#56805,#56812),.PCURVE_S1.); -#56801 = LINE('',#56802,#56803); -#56802 = CARTESIAN_POINT('',(-0.35,-1.125,1.55)); -#56803 = VECTOR('',#56804,1.); -#56804 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56805 = PCURVE('',#55246,#56806); -#56806 = DEFINITIONAL_REPRESENTATION('',(#56807),#56811); -#56807 = LINE('',#56808,#56809); -#56808 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56809 = VECTOR('',#56810,1.); -#56810 = DIRECTION('',(1.,0.E+000)); -#56811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56812 = PCURVE('',#56585,#56813); -#56813 = DEFINITIONAL_REPRESENTATION('',(#56814),#56818); -#56814 = LINE('',#56815,#56816); -#56815 = CARTESIAN_POINT('',(-0.35,1.55)); -#56816 = VECTOR('',#56817,1.); -#56817 = DIRECTION('',(1.,0.E+000)); -#56818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56819 = ORIENTED_EDGE('',*,*,#56820,.F.); -#56820 = EDGE_CURVE('',#55231,#56798,#56821,.T.); -#56821 = SURFACE_CURVE('',#56822,(#56826,#56833),.PCURVE_S1.); -#56822 = LINE('',#56823,#56824); -#56823 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); -#56824 = VECTOR('',#56825,1.); -#56825 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56826 = PCURVE('',#55246,#56827); -#56827 = DEFINITIONAL_REPRESENTATION('',(#56828),#56832); -#56828 = LINE('',#56829,#56830); -#56829 = CARTESIAN_POINT('',(1.14,0.E+000)); -#56830 = VECTOR('',#56831,1.); -#56831 = DIRECTION('',(0.E+000,-1.)); -#56832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56833 = PCURVE('',#42101,#56834); -#56834 = DEFINITIONAL_REPRESENTATION('',(#56835),#56839); -#56835 = LINE('',#56836,#56837); -#56836 = CARTESIAN_POINT('',(0.17484542651,-0.3)); -#56837 = VECTOR('',#56838,1.); -#56838 = DIRECTION('',(0.E+000,-1.)); -#56839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56840 = ADVANCED_FACE('',(#56841),#55867,.F.); -#56841 = FACE_BOUND('',#56842,.F.); -#56842 = EDGE_LOOP('',(#56843,#56844,#56867,#56888)); -#56843 = ORIENTED_EDGE('',*,*,#55849,.F.); -#56844 = ORIENTED_EDGE('',*,*,#56845,.T.); -#56845 = EDGE_CURVE('',#55850,#56846,#56848,.T.); -#56846 = VERTEX_POINT('',#56847); -#56847 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); -#56848 = SURFACE_CURVE('',#56849,(#56853,#56860),.PCURVE_S1.); -#56849 = LINE('',#56850,#56851); -#56850 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); -#56851 = VECTOR('',#56852,1.); -#56852 = DIRECTION('',(0.E+000,1.,0.E+000)); -#56853 = PCURVE('',#55867,#56854); -#56854 = DEFINITIONAL_REPRESENTATION('',(#56855),#56859); -#56855 = LINE('',#56856,#56857); -#56856 = CARTESIAN_POINT('',(1.16,0.E+000)); -#56857 = VECTOR('',#56858,1.); -#56858 = DIRECTION('',(0.E+000,-1.)); -#56859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56860 = PCURVE('',#41631,#56861); -#56861 = DEFINITIONAL_REPRESENTATION('',(#56862),#56866); -#56862 = LINE('',#56863,#56864); -#56863 = CARTESIAN_POINT('',(1.95484542651,-0.3)); -#56864 = VECTOR('',#56865,1.); -#56865 = DIRECTION('',(0.E+000,-1.)); -#56866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56867 = ORIENTED_EDGE('',*,*,#56868,.T.); -#56868 = EDGE_CURVE('',#56846,#56748,#56869,.T.); -#56869 = SURFACE_CURVE('',#56870,(#56874,#56881),.PCURVE_S1.); -#56870 = LINE('',#56871,#56872); -#56871 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); -#56872 = VECTOR('',#56873,1.); -#56873 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56874 = PCURVE('',#55867,#56875); -#56875 = DEFINITIONAL_REPRESENTATION('',(#56876),#56880); -#56876 = LINE('',#56877,#56878); -#56877 = CARTESIAN_POINT('',(1.16,-0.1)); -#56878 = VECTOR('',#56879,1.); -#56879 = DIRECTION('',(1.,0.E+000)); -#56880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56881 = PCURVE('',#56661,#56882); -#56882 = DEFINITIONAL_REPRESENTATION('',(#56883),#56887); -#56883 = LINE('',#56884,#56885); -#56884 = CARTESIAN_POINT('',(0.81,1.55)); -#56885 = VECTOR('',#56886,1.); -#56886 = DIRECTION('',(1.,0.E+000)); -#56887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56888 = ORIENTED_EDGE('',*,*,#56747,.F.); -#56889 = ADVANCED_FACE('',(#56890),#56904,.T.); -#56890 = FACE_BOUND('',#56891,.F.); -#56891 = EDGE_LOOP('',(#56892,#56922,#56945,#56968,#56991,#57014,#57037, - #57060)); -#56892 = ORIENTED_EDGE('',*,*,#56893,.F.); -#56893 = EDGE_CURVE('',#56894,#56896,#56898,.T.); -#56894 = VERTEX_POINT('',#56895); -#56895 = CARTESIAN_POINT('',(0.81,-1.125,-0.2)); -#56896 = VERTEX_POINT('',#56897); -#56897 = CARTESIAN_POINT('',(0.81,-1.125,-0.40484542651)); -#56898 = SURFACE_CURVE('',#56899,(#56903,#56915),.PCURVE_S1.); -#56899 = LINE('',#56900,#56901); -#56900 = CARTESIAN_POINT('',(0.81,-1.125,-0.2)); -#56901 = VECTOR('',#56902,1.); -#56902 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#56903 = PCURVE('',#56904,#56909); -#56904 = PLANE('',#56905); -#56905 = AXIS2_PLACEMENT_3D('',#56906,#56907,#56908); -#56906 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); -#56907 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#56908 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56909 = DEFINITIONAL_REPRESENTATION('',(#56910),#56914); -#56910 = LINE('',#56911,#56912); -#56911 = CARTESIAN_POINT('',(0.81,-0.2)); -#56912 = VECTOR('',#56913,1.); -#56913 = DIRECTION('',(0.E+000,-1.)); -#56914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56915 = PCURVE('',#41631,#56916); -#56916 = DEFINITIONAL_REPRESENTATION('',(#56917),#56921); -#56917 = LINE('',#56918,#56919); -#56918 = CARTESIAN_POINT('',(0.20484542651,-0.4)); -#56919 = VECTOR('',#56920,1.); -#56920 = DIRECTION('',(-1.,0.E+000)); -#56921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56922 = ORIENTED_EDGE('',*,*,#56923,.F.); -#56923 = EDGE_CURVE('',#56924,#56894,#56926,.T.); -#56924 = VERTEX_POINT('',#56925); -#56925 = CARTESIAN_POINT('',(1.5,-1.125,-0.2)); -#56926 = SURFACE_CURVE('',#56927,(#56931,#56938),.PCURVE_S1.); -#56927 = LINE('',#56928,#56929); -#56928 = CARTESIAN_POINT('',(1.5,-1.125,-0.2)); -#56929 = VECTOR('',#56930,1.); -#56930 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#56931 = PCURVE('',#56904,#56932); -#56932 = DEFINITIONAL_REPRESENTATION('',(#56933),#56937); -#56933 = LINE('',#56934,#56935); -#56934 = CARTESIAN_POINT('',(1.5,-0.2)); -#56935 = VECTOR('',#56936,1.); -#56936 = DIRECTION('',(-1.,0.E+000)); -#56937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56938 = PCURVE('',#56509,#56939); -#56939 = DEFINITIONAL_REPRESENTATION('',(#56940),#56944); -#56940 = LINE('',#56941,#56942); -#56941 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56942 = VECTOR('',#56943,1.); -#56943 = DIRECTION('',(1.,0.E+000)); -#56944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56945 = ORIENTED_EDGE('',*,*,#56946,.F.); -#56946 = EDGE_CURVE('',#56947,#56924,#56949,.T.); -#56947 = VERTEX_POINT('',#56948); -#56948 = CARTESIAN_POINT('',(1.5,-1.125,-0.65)); -#56949 = SURFACE_CURVE('',#56950,(#56954,#56961),.PCURVE_S1.); -#56950 = LINE('',#56951,#56952); -#56951 = CARTESIAN_POINT('',(1.5,-1.125,-0.65)); -#56952 = VECTOR('',#56953,1.); -#56953 = DIRECTION('',(0.E+000,0.E+000,1.)); -#56954 = PCURVE('',#56904,#56955); -#56955 = DEFINITIONAL_REPRESENTATION('',(#56956),#56960); -#56956 = LINE('',#56957,#56958); -#56957 = CARTESIAN_POINT('',(1.5,-0.65)); -#56958 = VECTOR('',#56959,1.); -#56959 = DIRECTION('',(0.E+000,1.)); -#56960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56961 = PCURVE('',#56481,#56962); -#56962 = DEFINITIONAL_REPRESENTATION('',(#56963),#56967); -#56963 = LINE('',#56964,#56965); -#56964 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#56965 = VECTOR('',#56966,1.); -#56966 = DIRECTION('',(1.,0.E+000)); -#56967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#56968 = ORIENTED_EDGE('',*,*,#56969,.F.); -#56969 = EDGE_CURVE('',#56970,#56947,#56972,.T.); -#56970 = VERTEX_POINT('',#56971); -#56971 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.65)); -#56972 = SURFACE_CURVE('',#56973,(#56977,#56984),.PCURVE_S1.); -#56973 = LINE('',#56974,#56975); -#56974 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.65)); -#56975 = VECTOR('',#56976,1.); -#56976 = DIRECTION('',(1.,0.E+000,0.E+000)); -#56977 = PCURVE('',#56904,#56978); -#56978 = DEFINITIONAL_REPRESENTATION('',(#56979),#56983); -#56979 = LINE('',#56980,#56981); -#56980 = CARTESIAN_POINT('',(1.E-002,-0.65)); -#56981 = VECTOR('',#56982,1.); -#56982 = DIRECTION('',(1.,0.E+000)); -#56983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#58705 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#58706 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#58707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58708 = ORIENTED_EDGE('',*,*,#58709,.F.); +#58709 = EDGE_CURVE('',#58710,#58683,#58712,.T.); +#58710 = VERTEX_POINT('',#58711); +#58711 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#58712 = SURFACE_CURVE('',#58713,(#58717,#58724),.PCURVE_S1.); +#58713 = LINE('',#58714,#58715); +#58714 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#58715 = VECTOR('',#58716,1.); +#58716 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58717 = PCURVE('',#40539,#58718); +#58718 = DEFINITIONAL_REPRESENTATION('',(#58719),#58723); +#58719 = LINE('',#58720,#58721); +#58720 = CARTESIAN_POINT('',(4.386446609407,0.82)); +#58721 = VECTOR('',#58722,1.); +#58722 = DIRECTION('',(1.,0.E+000)); +#58723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58724 = PCURVE('',#43312,#58725); +#58725 = DEFINITIONAL_REPRESENTATION('',(#58726),#58730); +#58726 = LINE('',#58727,#58728); +#58727 = CARTESIAN_POINT('',(0.35,5.54)); +#58728 = VECTOR('',#58729,1.); +#58729 = DIRECTION('',(0.E+000,1.)); +#58730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58731 = ORIENTED_EDGE('',*,*,#58732,.T.); +#58732 = EDGE_CURVE('',#58710,#58733,#58735,.T.); +#58733 = VERTEX_POINT('',#58734); +#58734 = CARTESIAN_POINT('',(1.79,-1.225,-1.21)); +#58735 = SURFACE_CURVE('',#58736,(#58740,#58747),.PCURVE_S1.); +#58736 = LINE('',#58737,#58738); +#58737 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#58738 = VECTOR('',#58739,1.); +#58739 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58740 = PCURVE('',#40539,#58741); +#58741 = DEFINITIONAL_REPRESENTATION('',(#58742),#58746); +#58742 = LINE('',#58743,#58744); +#58743 = CARTESIAN_POINT('',(4.386446609407,0.82)); +#58744 = VECTOR('',#58745,1.); +#58745 = DIRECTION('',(0.E+000,1.)); +#58746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58747 = PCURVE('',#58748,#58753); +#58748 = PLANE('',#58749); +#58749 = AXIS2_PLACEMENT_3D('',#58750,#58751,#58752); +#58750 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#58751 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58752 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58753 = DEFINITIONAL_REPRESENTATION('',(#58754),#58758); +#58754 = LINE('',#58755,#58756); +#58755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58756 = VECTOR('',#58757,1.); +#58757 = DIRECTION('',(1.,0.E+000)); +#58758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58759 = ORIENTED_EDGE('',*,*,#58760,.T.); +#58760 = EDGE_CURVE('',#58733,#58761,#58763,.T.); +#58761 = VERTEX_POINT('',#58762); +#58762 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); +#58763 = SURFACE_CURVE('',#58764,(#58769,#58776),.PCURVE_S1.); +#58764 = CIRCLE('',#58765,8.E-002); +#58765 = AXIS2_PLACEMENT_3D('',#58766,#58767,#58768); +#58766 = CARTESIAN_POINT('',(1.71,-1.225,-1.21)); +#58767 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58768 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58769 = PCURVE('',#40539,#58770); +#58770 = DEFINITIONAL_REPRESENTATION('',(#58771),#58775); +#58771 = CIRCLE('',#58772,8.E-002); +#58772 = AXIS2_PLACEMENT_2D('',#58773,#58774); +#58773 = CARTESIAN_POINT('',(4.306446609407,1.14)); +#58774 = DIRECTION('',(1.,0.E+000)); +#58775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#56984 = PCURVE('',#56453,#56985); -#56985 = DEFINITIONAL_REPRESENTATION('',(#56986),#56990); -#56986 = LINE('',#56987,#56988); -#56987 = CARTESIAN_POINT('',(0.36,-0.1)); -#56988 = VECTOR('',#56989,1.); -#56989 = DIRECTION('',(1.,0.E+000)); -#56990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#58776 = PCURVE('',#44204,#58777); +#58777 = DEFINITIONAL_REPRESENTATION('',(#58778),#58781); +#58778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58779,#58780),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#58779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58780 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#58781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58782 = ORIENTED_EDGE('',*,*,#58783,.T.); +#58783 = EDGE_CURVE('',#58761,#58784,#58786,.T.); +#58784 = VERTEX_POINT('',#58785); +#58785 = CARTESIAN_POINT('',(1.E-002,-1.225,-1.13)); +#58786 = SURFACE_CURVE('',#58787,(#58791,#58798),.PCURVE_S1.); +#58787 = LINE('',#58788,#58789); +#58788 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); +#58789 = VECTOR('',#58790,1.); +#58790 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58791 = PCURVE('',#40539,#58792); +#58792 = DEFINITIONAL_REPRESENTATION('',(#58793),#58797); +#58793 = LINE('',#58794,#58795); +#58794 = CARTESIAN_POINT('',(4.306446609407,1.22)); +#58795 = VECTOR('',#58796,1.); +#58796 = DIRECTION('',(-1.,0.E+000)); +#58797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58798 = PCURVE('',#44171,#58799); +#58799 = DEFINITIONAL_REPRESENTATION('',(#58800),#58804); +#58800 = LINE('',#58801,#58802); +#58801 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58802 = VECTOR('',#58803,1.); +#58803 = DIRECTION('',(1.,0.E+000)); +#58804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#56991 = ORIENTED_EDGE('',*,*,#56992,.F.); -#56992 = EDGE_CURVE('',#56993,#56970,#56995,.T.); -#56993 = VERTEX_POINT('',#56994); -#56994 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); -#56995 = SURFACE_CURVE('',#56996,(#57000,#57007),.PCURVE_S1.); -#56996 = LINE('',#56997,#56998); -#56997 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); -#56998 = VECTOR('',#56999,1.); -#56999 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#57000 = PCURVE('',#56904,#57001); -#57001 = DEFINITIONAL_REPRESENTATION('',(#57002),#57006); -#57002 = LINE('',#57003,#57004); -#57003 = CARTESIAN_POINT('',(1.E-002,-0.42515457349)); -#57004 = VECTOR('',#57005,1.); -#57005 = DIRECTION('',(0.E+000,-1.)); -#57006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57007 = PCURVE('',#41751,#57008); -#57008 = DEFINITIONAL_REPRESENTATION('',(#57009),#57013); -#57009 = LINE('',#57010,#57011); -#57010 = CARTESIAN_POINT('',(0.70484542651,-0.4)); -#57011 = VECTOR('',#57012,1.); -#57012 = DIRECTION('',(-1.,0.E+000)); -#57013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57014 = ORIENTED_EDGE('',*,*,#57015,.F.); -#57015 = EDGE_CURVE('',#57016,#56993,#57018,.T.); -#57016 = VERTEX_POINT('',#57017); -#57017 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); -#57018 = SURFACE_CURVE('',#57019,(#57024,#57031),.PCURVE_S1.); -#57019 = CIRCLE('',#57020,0.14); -#57020 = AXIS2_PLACEMENT_3D('',#57021,#57022,#57023); -#57021 = CARTESIAN_POINT('',(0.15,-1.125,-0.42515457349)); -#57022 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57023 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); -#57024 = PCURVE('',#56904,#57025); -#57025 = DEFINITIONAL_REPRESENTATION('',(#57026),#57030); -#57026 = CIRCLE('',#57027,0.14); -#57027 = AXIS2_PLACEMENT_2D('',#57028,#57029); -#57028 = CARTESIAN_POINT('',(0.15,-0.42515457349)); -#57029 = DIRECTION('',(0.566528822887,0.824041924199)); -#57030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57031 = PCURVE('',#41724,#57032); -#57032 = DEFINITIONAL_REPRESENTATION('',(#57033),#57036); -#57033 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57034,#57035),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57034 = CARTESIAN_POINT('',(0.96850898066,-0.4)); -#57035 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57037 = ORIENTED_EDGE('',*,*,#57038,.T.); -#57038 = EDGE_CURVE('',#57016,#57039,#57041,.T.); -#57039 = VERTEX_POINT('',#57040); -#57040 = CARTESIAN_POINT('',(0.559355388338,-1.125,-0.536692134382)); -#57041 = SURFACE_CURVE('',#57042,(#57046,#57053),.PCURVE_S1.); -#57042 = LINE('',#57043,#57044); -#57043 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); -#57044 = VECTOR('',#57045,1.); -#57045 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); -#57046 = PCURVE('',#56904,#57047); -#57047 = DEFINITIONAL_REPRESENTATION('',(#57048),#57052); -#57048 = LINE('',#57049,#57050); -#57049 = CARTESIAN_POINT('',(0.229314035204,-0.309788704102)); -#57050 = VECTOR('',#57051,1.); -#57051 = DIRECTION('',(0.824041924199,-0.566528822887)); -#57052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57053 = PCURVE('',#41691,#57054); -#57054 = DEFINITIONAL_REPRESENTATION('',(#57055),#57059); -#57055 = LINE('',#57056,#57057); -#57056 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57057 = VECTOR('',#57058,1.); -#57058 = DIRECTION('',(1.,0.E+000)); -#57059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57060 = ORIENTED_EDGE('',*,*,#57061,.T.); -#57061 = EDGE_CURVE('',#57039,#56896,#57062,.T.); -#57062 = SURFACE_CURVE('',#57063,(#57068,#57075),.PCURVE_S1.); -#57063 = CIRCLE('',#57064,0.16); -#57064 = AXIS2_PLACEMENT_3D('',#57065,#57066,#57067); -#57065 = CARTESIAN_POINT('',(0.65,-1.125,-0.40484542651)); -#57066 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57067 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); -#57068 = PCURVE('',#56904,#57069); -#57069 = DEFINITIONAL_REPRESENTATION('',(#57070),#57074); -#57070 = CIRCLE('',#57071,0.16); -#57071 = AXIS2_PLACEMENT_2D('',#57072,#57073); -#57072 = CARTESIAN_POINT('',(0.65,-0.40484542651)); -#57073 = DIRECTION('',(-0.566528822887,-0.824041924199)); -#57074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57075 = PCURVE('',#41664,#57076); -#57076 = DEFINITIONAL_REPRESENTATION('',(#57077),#57080); -#57077 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57078,#57079),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57078 = CARTESIAN_POINT('',(4.11010163425,-0.4)); -#57079 = CARTESIAN_POINT('',(6.28318530718,-0.4)); -#57080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#58805 = ORIENTED_EDGE('',*,*,#58806,.T.); +#58806 = EDGE_CURVE('',#58784,#58807,#58809,.T.); +#58807 = VERTEX_POINT('',#58808); +#58808 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); +#58809 = SURFACE_CURVE('',#58810,(#58814,#58821),.PCURVE_S1.); +#58810 = LINE('',#58811,#58812); +#58811 = CARTESIAN_POINT('',(1.E-002,-1.225,-1.13)); +#58812 = VECTOR('',#58813,1.); +#58813 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58814 = PCURVE('',#40539,#58815); +#58815 = DEFINITIONAL_REPRESENTATION('',(#58816),#58820); +#58816 = LINE('',#58817,#58818); +#58817 = CARTESIAN_POINT('',(2.606446609407,1.22)); +#58818 = VECTOR('',#58819,1.); +#58819 = DIRECTION('',(0.E+000,1.)); +#58820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58821 = PCURVE('',#44143,#58822); +#58822 = DEFINITIONAL_REPRESENTATION('',(#58823),#58827); +#58823 = LINE('',#58824,#58825); +#58824 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#58825 = VECTOR('',#58826,1.); +#58826 = DIRECTION('',(1.,0.E+000)); +#58827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58828 = ORIENTED_EDGE('',*,*,#58829,.T.); +#58829 = EDGE_CURVE('',#58807,#58830,#58832,.T.); +#58830 = VERTEX_POINT('',#58831); +#58831 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); +#58832 = SURFACE_CURVE('',#58833,(#58837,#58844),.PCURVE_S1.); +#58833 = LINE('',#58834,#58835); +#58834 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); +#58835 = VECTOR('',#58836,1.); +#58836 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58837 = PCURVE('',#40539,#58838); +#58838 = DEFINITIONAL_REPRESENTATION('',(#58839),#58843); +#58839 = LINE('',#58840,#58841); +#58840 = CARTESIAN_POINT('',(2.606446609407,1.7)); +#58841 = VECTOR('',#58842,1.); +#58842 = DIRECTION('',(1.,0.E+000)); +#58843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58844 = PCURVE('',#58845,#58850); +#58845 = PLANE('',#58846); +#58846 = AXIS2_PLACEMENT_3D('',#58847,#58848,#58849); +#58847 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); +#58848 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58849 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58850 = DEFINITIONAL_REPRESENTATION('',(#58851),#58855); +#58851 = LINE('',#58852,#58853); +#58852 = CARTESIAN_POINT('',(0.36,0.E+000)); +#58853 = VECTOR('',#58854,1.); +#58854 = DIRECTION('',(1.,0.E+000)); +#58855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58856 = ORIENTED_EDGE('',*,*,#58857,.T.); +#58857 = EDGE_CURVE('',#58830,#58858,#58860,.T.); +#58858 = VERTEX_POINT('',#58859); +#58859 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); +#58860 = SURFACE_CURVE('',#58861,(#58865,#58872),.PCURVE_S1.); +#58861 = LINE('',#58862,#58863); +#58862 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); +#58863 = VECTOR('',#58864,1.); +#58864 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58865 = PCURVE('',#40539,#58866); +#58866 = DEFINITIONAL_REPRESENTATION('',(#58867),#58871); +#58867 = LINE('',#58868,#58869); +#58868 = CARTESIAN_POINT('',(4.096446609407,1.7)); +#58869 = VECTOR('',#58870,1.); +#58870 = DIRECTION('',(0.E+000,1.)); +#58871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57081 = ADVANCED_FACE('',(#57082),#56661,.T.); -#57082 = FACE_BOUND('',#57083,.F.); -#57083 = EDGE_LOOP('',(#57084,#57109,#57132,#57155,#57176,#57177,#57178, - #57179)); -#57084 = ORIENTED_EDGE('',*,*,#57085,.T.); -#57085 = EDGE_CURVE('',#57086,#57088,#57090,.T.); -#57086 = VERTEX_POINT('',#57087); -#57087 = CARTESIAN_POINT('',(0.81,-1.125,1.72484542651)); -#57088 = VERTEX_POINT('',#57089); -#57089 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); -#57090 = SURFACE_CURVE('',#57091,(#57096,#57103),.PCURVE_S1.); -#57091 = CIRCLE('',#57092,0.16); -#57092 = AXIS2_PLACEMENT_3D('',#57093,#57094,#57095); -#57093 = CARTESIAN_POINT('',(0.65,-1.125,1.72484542651)); -#57094 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57095 = DIRECTION('',(1.,0.E+000,0.E+000)); -#57096 = PCURVE('',#56661,#57097); -#57097 = DEFINITIONAL_REPRESENTATION('',(#57098),#57102); -#57098 = CIRCLE('',#57099,0.16); -#57099 = AXIS2_PLACEMENT_2D('',#57100,#57101); -#57100 = CARTESIAN_POINT('',(0.65,1.72484542651)); -#57101 = DIRECTION('',(1.,0.E+000)); -#57102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57103 = PCURVE('',#41604,#57104); -#57104 = DEFINITIONAL_REPRESENTATION('',(#57105),#57108); -#57105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57106,#57107),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.173083672929),.PIECEWISE_BEZIER_KNOTS.); -#57106 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57107 = CARTESIAN_POINT('',(2.173083672929,-0.4)); -#57108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#58872 = PCURVE('',#58873,#58878); +#58873 = PLANE('',#58874); +#58874 = AXIS2_PLACEMENT_3D('',#58875,#58876,#58877); +#58875 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); +#58876 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58877 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58878 = DEFINITIONAL_REPRESENTATION('',(#58879),#58883); +#58879 = LINE('',#58880,#58881); +#58880 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58881 = VECTOR('',#58882,1.); +#58882 = DIRECTION('',(1.,0.E+000)); +#58883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57109 = ORIENTED_EDGE('',*,*,#57110,.T.); -#57110 = EDGE_CURVE('',#57088,#57111,#57113,.T.); -#57111 = VERTEX_POINT('',#57112); -#57112 = CARTESIAN_POINT('',(0.229314035204,-1.125,1.629788704102)); -#57113 = SURFACE_CURVE('',#57114,(#57118,#57125),.PCURVE_S1.); -#57114 = LINE('',#57115,#57116); -#57115 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); -#57116 = VECTOR('',#57117,1.); -#57117 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); -#57118 = PCURVE('',#56661,#57119); -#57119 = DEFINITIONAL_REPRESENTATION('',(#57120),#57124); -#57120 = LINE('',#57121,#57122); -#57121 = CARTESIAN_POINT('',(0.559355388338,1.856692134382)); -#57122 = VECTOR('',#57123,1.); -#57123 = DIRECTION('',(-0.824041924199,-0.566528822887)); -#57124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57125 = PCURVE('',#41571,#57126); -#57126 = DEFINITIONAL_REPRESENTATION('',(#57127),#57131); -#57127 = LINE('',#57128,#57129); -#57128 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57129 = VECTOR('',#57130,1.); -#57130 = DIRECTION('',(1.,0.E+000)); -#57131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#58884 = ORIENTED_EDGE('',*,*,#58885,.T.); +#58885 = EDGE_CURVE('',#58858,#58886,#58888,.T.); +#58886 = VERTEX_POINT('',#58887); +#58887 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); +#58888 = SURFACE_CURVE('',#58889,(#58893,#58900),.PCURVE_S1.); +#58889 = LINE('',#58890,#58891); +#58890 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); +#58891 = VECTOR('',#58892,1.); +#58892 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58893 = PCURVE('',#40539,#58894); +#58894 = DEFINITIONAL_REPRESENTATION('',(#58895),#58899); +#58895 = LINE('',#58896,#58897); +#58896 = CARTESIAN_POINT('',(4.096446609407,2.15)); +#58897 = VECTOR('',#58898,1.); +#58898 = DIRECTION('',(-1.,0.E+000)); +#58899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58900 = PCURVE('',#58901,#58906); +#58901 = PLANE('',#58902); +#58902 = AXIS2_PLACEMENT_3D('',#58903,#58904,#58905); +#58903 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); +#58904 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58905 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#58906 = DEFINITIONAL_REPRESENTATION('',(#58907),#58911); +#58907 = LINE('',#58908,#58909); +#58908 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58909 = VECTOR('',#58910,1.); +#58910 = DIRECTION('',(1.,0.E+000)); +#58911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58912 = ORIENTED_EDGE('',*,*,#58913,.T.); +#58913 = EDGE_CURVE('',#58886,#58242,#58914,.T.); +#58914 = SURFACE_CURVE('',#58915,(#58919,#58926),.PCURVE_S1.); +#58915 = LINE('',#58916,#58917); +#58916 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); +#58917 = VECTOR('',#58918,1.); +#58918 = DIRECTION('',(0.E+000,0.E+000,1.)); +#58919 = PCURVE('',#40539,#58920); +#58920 = DEFINITIONAL_REPRESENTATION('',(#58921),#58925); +#58921 = LINE('',#58922,#58923); +#58922 = CARTESIAN_POINT('',(3.406446609407,2.15)); +#58923 = VECTOR('',#58924,1.); +#58924 = DIRECTION('',(0.E+000,1.)); +#58925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58926 = PCURVE('',#44023,#58927); +#58927 = DEFINITIONAL_REPRESENTATION('',(#58928),#58932); +#58928 = LINE('',#58929,#58930); +#58929 = CARTESIAN_POINT('',(0.20484542651,-0.3)); +#58930 = VECTOR('',#58931,1.); +#58931 = DIRECTION('',(1.,0.E+000)); +#58932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58933 = ADVANCED_FACE('',(#58934),#57610,.F.); +#58934 = FACE_BOUND('',#58935,.F.); +#58935 = EDGE_LOOP('',(#58936,#58937,#58960,#58988)); +#58936 = ORIENTED_EDGE('',*,*,#57592,.F.); +#58937 = ORIENTED_EDGE('',*,*,#58938,.T.); +#58938 = EDGE_CURVE('',#57593,#58939,#58941,.T.); +#58939 = VERTEX_POINT('',#58940); +#58940 = CARTESIAN_POINT('',(-0.35,-1.125,2.)); +#58941 = SURFACE_CURVE('',#58942,(#58946,#58953),.PCURVE_S1.); +#58942 = LINE('',#58943,#58944); +#58943 = CARTESIAN_POINT('',(-0.35,-1.225,2.)); +#58944 = VECTOR('',#58945,1.); +#58945 = DIRECTION('',(0.E+000,1.,0.E+000)); +#58946 = PCURVE('',#57610,#58947); +#58947 = DEFINITIONAL_REPRESENTATION('',(#58948),#58952); +#58948 = LINE('',#58949,#58950); +#58949 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#58950 = VECTOR('',#58951,1.); +#58951 = DIRECTION('',(0.E+000,-1.)); +#58952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58953 = PCURVE('',#58226,#58954); +#58954 = DEFINITIONAL_REPRESENTATION('',(#58955),#58959); +#58955 = LINE('',#58956,#58957); +#58956 = CARTESIAN_POINT('',(1.85,0.E+000)); +#58957 = VECTOR('',#58958,1.); +#58958 = DIRECTION('',(0.E+000,-1.)); +#58959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58960 = ORIENTED_EDGE('',*,*,#58961,.T.); +#58961 = EDGE_CURVE('',#58939,#58962,#58964,.T.); +#58962 = VERTEX_POINT('',#58963); +#58963 = CARTESIAN_POINT('',(-0.35,-1.125,1.55)); +#58964 = SURFACE_CURVE('',#58965,(#58969,#58976),.PCURVE_S1.); +#58965 = LINE('',#58966,#58967); +#58966 = CARTESIAN_POINT('',(-0.35,-1.125,2.)); +#58967 = VECTOR('',#58968,1.); +#58968 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#58969 = PCURVE('',#57610,#58970); +#58970 = DEFINITIONAL_REPRESENTATION('',(#58971),#58975); +#58971 = LINE('',#58972,#58973); +#58972 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#58973 = VECTOR('',#58974,1.); +#58974 = DIRECTION('',(1.,0.E+000)); +#58975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58976 = PCURVE('',#58977,#58982); +#58977 = PLANE('',#58978); +#58978 = AXIS2_PLACEMENT_3D('',#58979,#58980,#58981); +#58979 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); +#58980 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#58981 = DIRECTION('',(1.,0.E+000,0.E+000)); +#58982 = DEFINITIONAL_REPRESENTATION('',(#58983),#58987); +#58983 = LINE('',#58984,#58985); +#58984 = CARTESIAN_POINT('',(-0.35,2.)); +#58985 = VECTOR('',#58986,1.); +#58986 = DIRECTION('',(0.E+000,-1.)); +#58987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#58988 = ORIENTED_EDGE('',*,*,#58989,.F.); +#58989 = EDGE_CURVE('',#57595,#58962,#58990,.T.); +#58990 = SURFACE_CURVE('',#58991,(#58995,#59002),.PCURVE_S1.); +#58991 = LINE('',#58992,#58993); +#58992 = CARTESIAN_POINT('',(-0.35,-1.225,1.55)); +#58993 = VECTOR('',#58994,1.); +#58994 = DIRECTION('',(0.E+000,1.,0.E+000)); +#58995 = PCURVE('',#57610,#58996); +#58996 = DEFINITIONAL_REPRESENTATION('',(#58997),#59001); +#58997 = LINE('',#58998,#58999); +#58998 = CARTESIAN_POINT('',(0.45,0.E+000)); +#58999 = VECTOR('',#59000,1.); +#59000 = DIRECTION('',(0.E+000,-1.)); +#59001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59002 = PCURVE('',#57638,#59003); +#59003 = DEFINITIONAL_REPRESENTATION('',(#59004),#59008); +#59004 = LINE('',#59005,#59006); +#59005 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#59006 = VECTOR('',#59007,1.); +#59007 = DIRECTION('',(0.E+000,-1.)); +#59008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59009 = ADVANCED_FACE('',(#59010),#58315,.F.); +#59010 = FACE_BOUND('',#59011,.F.); +#59011 = EDGE_LOOP('',(#59012,#59013,#59036,#59064)); +#59012 = ORIENTED_EDGE('',*,*,#58299,.F.); +#59013 = ORIENTED_EDGE('',*,*,#59014,.T.); +#59014 = EDGE_CURVE('',#58272,#59015,#59017,.T.); +#59015 = VERTEX_POINT('',#59016); +#59016 = CARTESIAN_POINT('',(1.5,-1.125,2.)); +#59017 = SURFACE_CURVE('',#59018,(#59022,#59029),.PCURVE_S1.); +#59018 = LINE('',#59019,#59020); +#59019 = CARTESIAN_POINT('',(1.5,-1.225,2.)); +#59020 = VECTOR('',#59021,1.); +#59021 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59022 = PCURVE('',#58315,#59023); +#59023 = DEFINITIONAL_REPRESENTATION('',(#59024),#59028); +#59024 = LINE('',#59025,#59026); +#59025 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#59026 = VECTOR('',#59027,1.); +#59027 = DIRECTION('',(0.E+000,-1.)); +#59028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59029 = PCURVE('',#58287,#59030); +#59030 = DEFINITIONAL_REPRESENTATION('',(#59031),#59035); +#59031 = LINE('',#59032,#59033); +#59032 = CARTESIAN_POINT('',(0.45,0.E+000)); +#59033 = VECTOR('',#59034,1.); +#59034 = DIRECTION('',(0.E+000,-1.)); +#59035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57132 = ORIENTED_EDGE('',*,*,#57133,.F.); -#57133 = EDGE_CURVE('',#57134,#57111,#57136,.T.); -#57134 = VERTEX_POINT('',#57135); -#57135 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); -#57136 = SURFACE_CURVE('',#57137,(#57142,#57149),.PCURVE_S1.); -#57137 = CIRCLE('',#57138,0.14); -#57138 = AXIS2_PLACEMENT_3D('',#57139,#57140,#57141); -#57139 = CARTESIAN_POINT('',(0.15,-1.125,1.74515457349)); -#57140 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57141 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#57142 = PCURVE('',#56661,#57143); -#57143 = DEFINITIONAL_REPRESENTATION('',(#57144),#57148); -#57144 = CIRCLE('',#57145,0.14); -#57145 = AXIS2_PLACEMENT_2D('',#57146,#57147); -#57146 = CARTESIAN_POINT('',(0.15,1.74515457349)); -#57147 = DIRECTION('',(-1.,0.E+000)); -#57148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57149 = PCURVE('',#41544,#57150); -#57150 = DEFINITIONAL_REPRESENTATION('',(#57151),#57154); -#57151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57152,#57153),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57152 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57153 = CARTESIAN_POINT('',(5.314676326519,-0.4)); -#57154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59036 = ORIENTED_EDGE('',*,*,#59037,.T.); +#59037 = EDGE_CURVE('',#59015,#59038,#59040,.T.); +#59038 = VERTEX_POINT('',#59039); +#59039 = CARTESIAN_POINT('',(1.E-002,-1.125,2.)); +#59040 = SURFACE_CURVE('',#59041,(#59045,#59052),.PCURVE_S1.); +#59041 = LINE('',#59042,#59043); +#59042 = CARTESIAN_POINT('',(1.5,-1.125,2.)); +#59043 = VECTOR('',#59044,1.); +#59044 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59045 = PCURVE('',#58315,#59046); +#59046 = DEFINITIONAL_REPRESENTATION('',(#59047),#59051); +#59047 = LINE('',#59048,#59049); +#59048 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59049 = VECTOR('',#59050,1.); +#59050 = DIRECTION('',(1.,0.E+000)); +#59051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59052 = PCURVE('',#59053,#59058); +#59053 = PLANE('',#59054); +#59054 = AXIS2_PLACEMENT_3D('',#59055,#59056,#59057); +#59055 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); +#59056 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59057 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59058 = DEFINITIONAL_REPRESENTATION('',(#59059),#59063); +#59059 = LINE('',#59060,#59061); +#59060 = CARTESIAN_POINT('',(1.5,2.)); +#59061 = VECTOR('',#59062,1.); +#59062 = DIRECTION('',(-1.,0.E+000)); +#59063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59064 = ORIENTED_EDGE('',*,*,#59065,.T.); +#59065 = EDGE_CURVE('',#59038,#58300,#59066,.T.); +#59066 = SURFACE_CURVE('',#59067,(#59071,#59078),.PCURVE_S1.); +#59067 = LINE('',#59068,#59069); +#59068 = CARTESIAN_POINT('',(1.E-002,-1.125,2.)); +#59069 = VECTOR('',#59070,1.); +#59070 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59071 = PCURVE('',#58315,#59072); +#59072 = DEFINITIONAL_REPRESENTATION('',(#59073),#59077); +#59073 = LINE('',#59074,#59075); +#59074 = CARTESIAN_POINT('',(1.49,-0.1)); +#59075 = VECTOR('',#59076,1.); +#59076 = DIRECTION('',(0.E+000,1.)); +#59077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59078 = PCURVE('',#43903,#59079); +#59079 = DEFINITIONAL_REPRESENTATION('',(#59080),#59084); +#59080 = LINE('',#59081,#59082); +#59081 = CARTESIAN_POINT('',(0.25484542651,-0.4)); +#59082 = VECTOR('',#59083,1.); +#59083 = DIRECTION('',(0.E+000,1.)); +#59084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59085 = ADVANCED_FACE('',(#59086),#58226,.F.); +#59086 = FACE_BOUND('',#59087,.F.); +#59087 = EDGE_LOOP('',(#59088,#59089,#59112,#59133)); +#59088 = ORIENTED_EDGE('',*,*,#58212,.F.); +#59089 = ORIENTED_EDGE('',*,*,#59090,.F.); +#59090 = EDGE_CURVE('',#59091,#58190,#59093,.T.); +#59091 = VERTEX_POINT('',#59092); +#59092 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); +#59093 = SURFACE_CURVE('',#59094,(#59098,#59105),.PCURVE_S1.); +#59094 = LINE('',#59095,#59096); +#59095 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); +#59096 = VECTOR('',#59097,1.); +#59097 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59098 = PCURVE('',#58226,#59099); +#59099 = DEFINITIONAL_REPRESENTATION('',(#59100),#59104); +#59100 = LINE('',#59101,#59102); +#59101 = CARTESIAN_POINT('',(1.51,-0.1)); +#59102 = VECTOR('',#59103,1.); +#59103 = DIRECTION('',(0.E+000,1.)); +#59104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59105 = PCURVE('',#44613,#59106); +#59106 = DEFINITIONAL_REPRESENTATION('',(#59107),#59111); +#59107 = LINE('',#59108,#59109); +#59108 = CARTESIAN_POINT('',(0.78,-0.4)); +#59109 = VECTOR('',#59110,1.); +#59110 = DIRECTION('',(0.E+000,1.)); +#59111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59112 = ORIENTED_EDGE('',*,*,#59113,.T.); +#59113 = EDGE_CURVE('',#59091,#58939,#59114,.T.); +#59114 = SURFACE_CURVE('',#59115,(#59119,#59126),.PCURVE_S1.); +#59115 = LINE('',#59116,#59117); +#59116 = CARTESIAN_POINT('',(-1.E-002,-1.125,2.)); +#59117 = VECTOR('',#59118,1.); +#59118 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59119 = PCURVE('',#58226,#59120); +#59120 = DEFINITIONAL_REPRESENTATION('',(#59121),#59125); +#59121 = LINE('',#59122,#59123); +#59122 = CARTESIAN_POINT('',(1.51,-0.1)); +#59123 = VECTOR('',#59124,1.); +#59124 = DIRECTION('',(1.,0.E+000)); +#59125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59126 = PCURVE('',#58977,#59127); +#59127 = DEFINITIONAL_REPRESENTATION('',(#59128),#59132); +#59128 = LINE('',#59129,#59130); +#59129 = CARTESIAN_POINT('',(-1.E-002,2.)); +#59130 = VECTOR('',#59131,1.); +#59131 = DIRECTION('',(-1.,0.E+000)); +#59132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59133 = ORIENTED_EDGE('',*,*,#58938,.F.); +#59134 = ADVANCED_FACE('',(#59135),#58287,.F.); +#59135 = FACE_BOUND('',#59136,.F.); +#59136 = EDGE_LOOP('',(#59137,#59138,#59161,#59182)); +#59137 = ORIENTED_EDGE('',*,*,#58271,.F.); +#59138 = ORIENTED_EDGE('',*,*,#59139,.T.); +#59139 = EDGE_CURVE('',#58244,#59140,#59142,.T.); +#59140 = VERTEX_POINT('',#59141); +#59141 = CARTESIAN_POINT('',(1.5,-1.125,1.55)); +#59142 = SURFACE_CURVE('',#59143,(#59147,#59154),.PCURVE_S1.); +#59143 = LINE('',#59144,#59145); +#59144 = CARTESIAN_POINT('',(1.5,-1.225,1.55)); +#59145 = VECTOR('',#59146,1.); +#59146 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59147 = PCURVE('',#58287,#59148); +#59148 = DEFINITIONAL_REPRESENTATION('',(#59149),#59153); +#59149 = LINE('',#59150,#59151); +#59150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#59151 = VECTOR('',#59152,1.); +#59152 = DIRECTION('',(0.E+000,-1.)); +#59153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59154 = PCURVE('',#58259,#59155); +#59155 = DEFINITIONAL_REPRESENTATION('',(#59156),#59160); +#59156 = LINE('',#59157,#59158); +#59157 = CARTESIAN_POINT('',(1.85,0.E+000)); +#59158 = VECTOR('',#59159,1.); +#59159 = DIRECTION('',(0.E+000,-1.)); +#59160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59161 = ORIENTED_EDGE('',*,*,#59162,.T.); +#59162 = EDGE_CURVE('',#59140,#59015,#59163,.T.); +#59163 = SURFACE_CURVE('',#59164,(#59168,#59175),.PCURVE_S1.); +#59164 = LINE('',#59165,#59166); +#59165 = CARTESIAN_POINT('',(1.5,-1.125,1.55)); +#59166 = VECTOR('',#59167,1.); +#59167 = DIRECTION('',(0.E+000,0.E+000,1.)); +#59168 = PCURVE('',#58287,#59169); +#59169 = DEFINITIONAL_REPRESENTATION('',(#59170),#59174); +#59170 = LINE('',#59171,#59172); +#59171 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59172 = VECTOR('',#59173,1.); +#59173 = DIRECTION('',(1.,0.E+000)); +#59174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57155 = ORIENTED_EDGE('',*,*,#57156,.T.); -#57156 = EDGE_CURVE('',#57134,#56646,#57157,.T.); -#57157 = SURFACE_CURVE('',#57158,(#57162,#57169),.PCURVE_S1.); -#57158 = LINE('',#57159,#57160); -#57159 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); -#57160 = VECTOR('',#57161,1.); -#57161 = DIRECTION('',(0.E+000,0.E+000,1.)); -#57162 = PCURVE('',#56661,#57163); -#57163 = DEFINITIONAL_REPRESENTATION('',(#57164),#57168); -#57164 = LINE('',#57165,#57166); -#57165 = CARTESIAN_POINT('',(1.E-002,1.74515457349)); -#57166 = VECTOR('',#57167,1.); -#57167 = DIRECTION('',(0.E+000,1.)); -#57168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59175 = PCURVE('',#59053,#59176); +#59176 = DEFINITIONAL_REPRESENTATION('',(#59177),#59181); +#59177 = LINE('',#59178,#59179); +#59178 = CARTESIAN_POINT('',(1.5,1.55)); +#59179 = VECTOR('',#59180,1.); +#59180 = DIRECTION('',(0.E+000,1.)); +#59181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57169 = PCURVE('',#41511,#57170); -#57170 = DEFINITIONAL_REPRESENTATION('',(#57171),#57175); -#57171 = LINE('',#57172,#57173); -#57172 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57173 = VECTOR('',#57174,1.); -#57174 = DIRECTION('',(1.,0.E+000)); -#57175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57176 = ORIENTED_EDGE('',*,*,#56645,.F.); -#57177 = ORIENTED_EDGE('',*,*,#56770,.F.); -#57178 = ORIENTED_EDGE('',*,*,#56868,.F.); -#57179 = ORIENTED_EDGE('',*,*,#57180,.T.); -#57180 = EDGE_CURVE('',#56846,#57086,#57181,.T.); -#57181 = SURFACE_CURVE('',#57182,(#57186,#57193),.PCURVE_S1.); -#57182 = LINE('',#57183,#57184); -#57183 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); -#57184 = VECTOR('',#57185,1.); -#57185 = DIRECTION('',(0.E+000,0.E+000,1.)); -#57186 = PCURVE('',#56661,#57187); -#57187 = DEFINITIONAL_REPRESENTATION('',(#57188),#57192); -#57188 = LINE('',#57189,#57190); -#57189 = CARTESIAN_POINT('',(0.81,1.55)); -#57190 = VECTOR('',#57191,1.); -#57191 = DIRECTION('',(0.E+000,1.)); -#57192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59182 = ORIENTED_EDGE('',*,*,#59014,.F.); +#59183 = ADVANCED_FACE('',(#59184),#57638,.F.); +#59184 = FACE_BOUND('',#59185,.F.); +#59185 = EDGE_LOOP('',(#59186,#59187,#59188,#59211)); +#59186 = ORIENTED_EDGE('',*,*,#57622,.F.); +#59187 = ORIENTED_EDGE('',*,*,#58989,.T.); +#59188 = ORIENTED_EDGE('',*,*,#59189,.T.); +#59189 = EDGE_CURVE('',#58962,#59190,#59192,.T.); +#59190 = VERTEX_POINT('',#59191); +#59191 = CARTESIAN_POINT('',(0.79,-1.125,1.55)); +#59192 = SURFACE_CURVE('',#59193,(#59197,#59204),.PCURVE_S1.); +#59193 = LINE('',#59194,#59195); +#59194 = CARTESIAN_POINT('',(-0.35,-1.125,1.55)); +#59195 = VECTOR('',#59196,1.); +#59196 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59197 = PCURVE('',#57638,#59198); +#59198 = DEFINITIONAL_REPRESENTATION('',(#59199),#59203); +#59199 = LINE('',#59200,#59201); +#59200 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59201 = VECTOR('',#59202,1.); +#59202 = DIRECTION('',(1.,0.E+000)); +#59203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59204 = PCURVE('',#58977,#59205); +#59205 = DEFINITIONAL_REPRESENTATION('',(#59206),#59210); +#59206 = LINE('',#59207,#59208); +#59207 = CARTESIAN_POINT('',(-0.35,1.55)); +#59208 = VECTOR('',#59209,1.); +#59209 = DIRECTION('',(1.,0.E+000)); +#59210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59211 = ORIENTED_EDGE('',*,*,#59212,.F.); +#59212 = EDGE_CURVE('',#57623,#59190,#59213,.T.); +#59213 = SURFACE_CURVE('',#59214,(#59218,#59225),.PCURVE_S1.); +#59214 = LINE('',#59215,#59216); +#59215 = CARTESIAN_POINT('',(0.79,-1.225,1.55)); +#59216 = VECTOR('',#59217,1.); +#59217 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59218 = PCURVE('',#57638,#59219); +#59219 = DEFINITIONAL_REPRESENTATION('',(#59220),#59224); +#59220 = LINE('',#59221,#59222); +#59221 = CARTESIAN_POINT('',(1.14,0.E+000)); +#59222 = VECTOR('',#59223,1.); +#59223 = DIRECTION('',(0.E+000,-1.)); +#59224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59225 = PCURVE('',#44493,#59226); +#59226 = DEFINITIONAL_REPRESENTATION('',(#59227),#59231); +#59227 = LINE('',#59228,#59229); +#59228 = CARTESIAN_POINT('',(0.17484542651,-0.3)); +#59229 = VECTOR('',#59230,1.); +#59230 = DIRECTION('',(0.E+000,-1.)); +#59231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57193 = PCURVE('',#41631,#57194); -#57194 = DEFINITIONAL_REPRESENTATION('',(#57195),#57199); -#57195 = LINE('',#57196,#57197); -#57196 = CARTESIAN_POINT('',(1.95484542651,-0.4)); -#57197 = VECTOR('',#57198,1.); -#57198 = DIRECTION('',(1.,0.E+000)); -#57199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57200 = ADVANCED_FACE('',(#57201),#56585,.T.); -#57201 = FACE_BOUND('',#57202,.F.); -#57202 = EDGE_LOOP('',(#57203,#57226,#57249,#57272,#57295,#57316,#57317, - #57318)); -#57203 = ORIENTED_EDGE('',*,*,#57204,.F.); -#57204 = EDGE_CURVE('',#57205,#56699,#57207,.T.); -#57205 = VERTEX_POINT('',#57206); -#57206 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); -#57207 = SURFACE_CURVE('',#57208,(#57212,#57219),.PCURVE_S1.); -#57208 = LINE('',#57209,#57210); -#57209 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); -#57210 = VECTOR('',#57211,1.); -#57211 = DIRECTION('',(0.E+000,0.E+000,1.)); -#57212 = PCURVE('',#56585,#57213); -#57213 = DEFINITIONAL_REPRESENTATION('',(#57214),#57218); -#57214 = LINE('',#57215,#57216); -#57215 = CARTESIAN_POINT('',(-1.E-002,1.74515457349)); -#57216 = VECTOR('',#57217,1.); -#57217 = DIRECTION('',(0.E+000,1.)); -#57218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57219 = PCURVE('',#42221,#57220); -#57220 = DEFINITIONAL_REPRESENTATION('',(#57221),#57225); -#57221 = LINE('',#57222,#57223); -#57222 = CARTESIAN_POINT('',(1.03484542651,-0.4)); -#57223 = VECTOR('',#57224,1.); -#57224 = DIRECTION('',(-1.,0.E+000)); -#57225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57226 = ORIENTED_EDGE('',*,*,#57227,.T.); -#57227 = EDGE_CURVE('',#57205,#57228,#57230,.T.); -#57228 = VERTEX_POINT('',#57229); -#57229 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); -#57230 = SURFACE_CURVE('',#57231,(#57236,#57243),.PCURVE_S1.); -#57231 = CIRCLE('',#57232,0.16); -#57232 = AXIS2_PLACEMENT_3D('',#57233,#57234,#57235); -#57233 = CARTESIAN_POINT('',(0.15,-1.125,1.74515457349)); -#57234 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57235 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#57236 = PCURVE('',#56585,#57237); -#57237 = DEFINITIONAL_REPRESENTATION('',(#57238),#57242); -#57238 = CIRCLE('',#57239,0.16); -#57239 = AXIS2_PLACEMENT_2D('',#57240,#57241); -#57240 = CARTESIAN_POINT('',(0.15,1.74515457349)); -#57241 = DIRECTION('',(-1.,0.E+000)); -#57242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59232 = ADVANCED_FACE('',(#59233),#58259,.F.); +#59233 = FACE_BOUND('',#59234,.F.); +#59234 = EDGE_LOOP('',(#59235,#59236,#59259,#59280)); +#59235 = ORIENTED_EDGE('',*,*,#58241,.F.); +#59236 = ORIENTED_EDGE('',*,*,#59237,.T.); +#59237 = EDGE_CURVE('',#58242,#59238,#59240,.T.); +#59238 = VERTEX_POINT('',#59239); +#59239 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); +#59240 = SURFACE_CURVE('',#59241,(#59245,#59252),.PCURVE_S1.); +#59241 = LINE('',#59242,#59243); +#59242 = CARTESIAN_POINT('',(0.81,-1.225,1.55)); +#59243 = VECTOR('',#59244,1.); +#59244 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59245 = PCURVE('',#58259,#59246); +#59246 = DEFINITIONAL_REPRESENTATION('',(#59247),#59251); +#59247 = LINE('',#59248,#59249); +#59248 = CARTESIAN_POINT('',(1.16,0.E+000)); +#59249 = VECTOR('',#59250,1.); +#59250 = DIRECTION('',(0.E+000,-1.)); +#59251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59252 = PCURVE('',#44023,#59253); +#59253 = DEFINITIONAL_REPRESENTATION('',(#59254),#59258); +#59254 = LINE('',#59255,#59256); +#59255 = CARTESIAN_POINT('',(1.95484542651,-0.3)); +#59256 = VECTOR('',#59257,1.); +#59257 = DIRECTION('',(0.E+000,-1.)); +#59258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59259 = ORIENTED_EDGE('',*,*,#59260,.T.); +#59260 = EDGE_CURVE('',#59238,#59140,#59261,.T.); +#59261 = SURFACE_CURVE('',#59262,(#59266,#59273),.PCURVE_S1.); +#59262 = LINE('',#59263,#59264); +#59263 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); +#59264 = VECTOR('',#59265,1.); +#59265 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59266 = PCURVE('',#58259,#59267); +#59267 = DEFINITIONAL_REPRESENTATION('',(#59268),#59272); +#59268 = LINE('',#59269,#59270); +#59269 = CARTESIAN_POINT('',(1.16,-0.1)); +#59270 = VECTOR('',#59271,1.); +#59271 = DIRECTION('',(1.,0.E+000)); +#59272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59273 = PCURVE('',#59053,#59274); +#59274 = DEFINITIONAL_REPRESENTATION('',(#59275),#59279); +#59275 = LINE('',#59276,#59277); +#59276 = CARTESIAN_POINT('',(0.81,1.55)); +#59277 = VECTOR('',#59278,1.); +#59278 = DIRECTION('',(1.,0.E+000)); +#59279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59280 = ORIENTED_EDGE('',*,*,#59139,.F.); +#59281 = ADVANCED_FACE('',(#59282),#59296,.T.); +#59282 = FACE_BOUND('',#59283,.F.); +#59283 = EDGE_LOOP('',(#59284,#59314,#59337,#59360,#59383,#59406,#59429, + #59452)); +#59284 = ORIENTED_EDGE('',*,*,#59285,.F.); +#59285 = EDGE_CURVE('',#59286,#59288,#59290,.T.); +#59286 = VERTEX_POINT('',#59287); +#59287 = CARTESIAN_POINT('',(0.81,-1.125,-0.2)); +#59288 = VERTEX_POINT('',#59289); +#59289 = CARTESIAN_POINT('',(0.81,-1.125,-0.40484542651)); +#59290 = SURFACE_CURVE('',#59291,(#59295,#59307),.PCURVE_S1.); +#59291 = LINE('',#59292,#59293); +#59292 = CARTESIAN_POINT('',(0.81,-1.125,-0.2)); +#59293 = VECTOR('',#59294,1.); +#59294 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59295 = PCURVE('',#59296,#59301); +#59296 = PLANE('',#59297); +#59297 = AXIS2_PLACEMENT_3D('',#59298,#59299,#59300); +#59298 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); +#59299 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59300 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59301 = DEFINITIONAL_REPRESENTATION('',(#59302),#59306); +#59302 = LINE('',#59303,#59304); +#59303 = CARTESIAN_POINT('',(0.81,-0.2)); +#59304 = VECTOR('',#59305,1.); +#59305 = DIRECTION('',(0.E+000,-1.)); +#59306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59307 = PCURVE('',#44023,#59308); +#59308 = DEFINITIONAL_REPRESENTATION('',(#59309),#59313); +#59309 = LINE('',#59310,#59311); +#59310 = CARTESIAN_POINT('',(0.20484542651,-0.4)); +#59311 = VECTOR('',#59312,1.); +#59312 = DIRECTION('',(-1.,0.E+000)); +#59313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59314 = ORIENTED_EDGE('',*,*,#59315,.F.); +#59315 = EDGE_CURVE('',#59316,#59286,#59318,.T.); +#59316 = VERTEX_POINT('',#59317); +#59317 = CARTESIAN_POINT('',(1.5,-1.125,-0.2)); +#59318 = SURFACE_CURVE('',#59319,(#59323,#59330),.PCURVE_S1.); +#59319 = LINE('',#59320,#59321); +#59320 = CARTESIAN_POINT('',(1.5,-1.125,-0.2)); +#59321 = VECTOR('',#59322,1.); +#59322 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59323 = PCURVE('',#59296,#59324); +#59324 = DEFINITIONAL_REPRESENTATION('',(#59325),#59329); +#59325 = LINE('',#59326,#59327); +#59326 = CARTESIAN_POINT('',(1.5,-0.2)); +#59327 = VECTOR('',#59328,1.); +#59328 = DIRECTION('',(-1.,0.E+000)); +#59329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59330 = PCURVE('',#58901,#59331); +#59331 = DEFINITIONAL_REPRESENTATION('',(#59332),#59336); +#59332 = LINE('',#59333,#59334); +#59333 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59334 = VECTOR('',#59335,1.); +#59335 = DIRECTION('',(1.,0.E+000)); +#59336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59337 = ORIENTED_EDGE('',*,*,#59338,.F.); +#59338 = EDGE_CURVE('',#59339,#59316,#59341,.T.); +#59339 = VERTEX_POINT('',#59340); +#59340 = CARTESIAN_POINT('',(1.5,-1.125,-0.65)); +#59341 = SURFACE_CURVE('',#59342,(#59346,#59353),.PCURVE_S1.); +#59342 = LINE('',#59343,#59344); +#59343 = CARTESIAN_POINT('',(1.5,-1.125,-0.65)); +#59344 = VECTOR('',#59345,1.); +#59345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#59346 = PCURVE('',#59296,#59347); +#59347 = DEFINITIONAL_REPRESENTATION('',(#59348),#59352); +#59348 = LINE('',#59349,#59350); +#59349 = CARTESIAN_POINT('',(1.5,-0.65)); +#59350 = VECTOR('',#59351,1.); +#59351 = DIRECTION('',(0.E+000,1.)); +#59352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59353 = PCURVE('',#58873,#59354); +#59354 = DEFINITIONAL_REPRESENTATION('',(#59355),#59359); +#59355 = LINE('',#59356,#59357); +#59356 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59357 = VECTOR('',#59358,1.); +#59358 = DIRECTION('',(1.,0.E+000)); +#59359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59360 = ORIENTED_EDGE('',*,*,#59361,.F.); +#59361 = EDGE_CURVE('',#59362,#59339,#59364,.T.); +#59362 = VERTEX_POINT('',#59363); +#59363 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.65)); +#59364 = SURFACE_CURVE('',#59365,(#59369,#59376),.PCURVE_S1.); +#59365 = LINE('',#59366,#59367); +#59366 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.65)); +#59367 = VECTOR('',#59368,1.); +#59368 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59369 = PCURVE('',#59296,#59370); +#59370 = DEFINITIONAL_REPRESENTATION('',(#59371),#59375); +#59371 = LINE('',#59372,#59373); +#59372 = CARTESIAN_POINT('',(1.E-002,-0.65)); +#59373 = VECTOR('',#59374,1.); +#59374 = DIRECTION('',(1.,0.E+000)); +#59375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59376 = PCURVE('',#58845,#59377); +#59377 = DEFINITIONAL_REPRESENTATION('',(#59378),#59382); +#59378 = LINE('',#59379,#59380); +#59379 = CARTESIAN_POINT('',(0.36,-0.1)); +#59380 = VECTOR('',#59381,1.); +#59381 = DIRECTION('',(1.,0.E+000)); +#59382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59383 = ORIENTED_EDGE('',*,*,#59384,.F.); +#59384 = EDGE_CURVE('',#59385,#59362,#59387,.T.); +#59385 = VERTEX_POINT('',#59386); +#59386 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); +#59387 = SURFACE_CURVE('',#59388,(#59392,#59399),.PCURVE_S1.); +#59388 = LINE('',#59389,#59390); +#59389 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); +#59390 = VECTOR('',#59391,1.); +#59391 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59392 = PCURVE('',#59296,#59393); +#59393 = DEFINITIONAL_REPRESENTATION('',(#59394),#59398); +#59394 = LINE('',#59395,#59396); +#59395 = CARTESIAN_POINT('',(1.E-002,-0.42515457349)); +#59396 = VECTOR('',#59397,1.); +#59397 = DIRECTION('',(0.E+000,-1.)); +#59398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59399 = PCURVE('',#44143,#59400); +#59400 = DEFINITIONAL_REPRESENTATION('',(#59401),#59405); +#59401 = LINE('',#59402,#59403); +#59402 = CARTESIAN_POINT('',(0.70484542651,-0.4)); +#59403 = VECTOR('',#59404,1.); +#59404 = DIRECTION('',(-1.,0.E+000)); +#59405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59406 = ORIENTED_EDGE('',*,*,#59407,.F.); +#59407 = EDGE_CURVE('',#59408,#59385,#59410,.T.); +#59408 = VERTEX_POINT('',#59409); +#59409 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); +#59410 = SURFACE_CURVE('',#59411,(#59416,#59423),.PCURVE_S1.); +#59411 = CIRCLE('',#59412,0.14); +#59412 = AXIS2_PLACEMENT_3D('',#59413,#59414,#59415); +#59413 = CARTESIAN_POINT('',(0.15,-1.125,-0.42515457349)); +#59414 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59415 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); +#59416 = PCURVE('',#59296,#59417); +#59417 = DEFINITIONAL_REPRESENTATION('',(#59418),#59422); +#59418 = CIRCLE('',#59419,0.14); +#59419 = AXIS2_PLACEMENT_2D('',#59420,#59421); +#59420 = CARTESIAN_POINT('',(0.15,-0.42515457349)); +#59421 = DIRECTION('',(0.566528822887,0.824041924199)); +#59422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59423 = PCURVE('',#44116,#59424); +#59424 = DEFINITIONAL_REPRESENTATION('',(#59425),#59428); +#59425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59426,#59427),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); +#59426 = CARTESIAN_POINT('',(0.96850898066,-0.4)); +#59427 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#59428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59429 = ORIENTED_EDGE('',*,*,#59430,.T.); +#59430 = EDGE_CURVE('',#59408,#59431,#59433,.T.); +#59431 = VERTEX_POINT('',#59432); +#59432 = CARTESIAN_POINT('',(0.559355388338,-1.125,-0.536692134382)); +#59433 = SURFACE_CURVE('',#59434,(#59438,#59445),.PCURVE_S1.); +#59434 = LINE('',#59435,#59436); +#59435 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); +#59436 = VECTOR('',#59437,1.); +#59437 = DIRECTION('',(0.824041924199,0.E+000,-0.566528822887)); +#59438 = PCURVE('',#59296,#59439); +#59439 = DEFINITIONAL_REPRESENTATION('',(#59440),#59444); +#59440 = LINE('',#59441,#59442); +#59441 = CARTESIAN_POINT('',(0.229314035204,-0.309788704102)); +#59442 = VECTOR('',#59443,1.); +#59443 = DIRECTION('',(0.824041924199,-0.566528822887)); +#59444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59445 = PCURVE('',#44083,#59446); +#59446 = DEFINITIONAL_REPRESENTATION('',(#59447),#59451); +#59447 = LINE('',#59448,#59449); +#59448 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59449 = VECTOR('',#59450,1.); +#59450 = DIRECTION('',(1.,0.E+000)); +#59451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59452 = ORIENTED_EDGE('',*,*,#59453,.T.); +#59453 = EDGE_CURVE('',#59431,#59288,#59454,.T.); +#59454 = SURFACE_CURVE('',#59455,(#59460,#59467),.PCURVE_S1.); +#59455 = CIRCLE('',#59456,0.16); +#59456 = AXIS2_PLACEMENT_3D('',#59457,#59458,#59459); +#59457 = CARTESIAN_POINT('',(0.65,-1.125,-0.40484542651)); +#59458 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59459 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); +#59460 = PCURVE('',#59296,#59461); +#59461 = DEFINITIONAL_REPRESENTATION('',(#59462),#59466); +#59462 = CIRCLE('',#59463,0.16); +#59463 = AXIS2_PLACEMENT_2D('',#59464,#59465); +#59464 = CARTESIAN_POINT('',(0.65,-0.40484542651)); +#59465 = DIRECTION('',(-0.566528822887,-0.824041924199)); +#59466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59467 = PCURVE('',#44056,#59468); +#59468 = DEFINITIONAL_REPRESENTATION('',(#59469),#59472); +#59469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59470,#59471),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); +#59470 = CARTESIAN_POINT('',(4.11010163425,-0.4)); +#59471 = CARTESIAN_POINT('',(6.28318530718,-0.4)); +#59472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57243 = PCURVE('',#42194,#57244); -#57244 = DEFINITIONAL_REPRESENTATION('',(#57245),#57248); -#57245 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57246,#57247),.UNSPECIFIED., +#59473 = ADVANCED_FACE('',(#59474),#59053,.T.); +#59474 = FACE_BOUND('',#59475,.F.); +#59475 = EDGE_LOOP('',(#59476,#59501,#59524,#59547,#59568,#59569,#59570, + #59571)); +#59476 = ORIENTED_EDGE('',*,*,#59477,.T.); +#59477 = EDGE_CURVE('',#59478,#59480,#59482,.T.); +#59478 = VERTEX_POINT('',#59479); +#59479 = CARTESIAN_POINT('',(0.81,-1.125,1.72484542651)); +#59480 = VERTEX_POINT('',#59481); +#59481 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); +#59482 = SURFACE_CURVE('',#59483,(#59488,#59495),.PCURVE_S1.); +#59483 = CIRCLE('',#59484,0.16); +#59484 = AXIS2_PLACEMENT_3D('',#59485,#59486,#59487); +#59485 = CARTESIAN_POINT('',(0.65,-1.125,1.72484542651)); +#59486 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59487 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59488 = PCURVE('',#59053,#59489); +#59489 = DEFINITIONAL_REPRESENTATION('',(#59490),#59494); +#59490 = CIRCLE('',#59491,0.16); +#59491 = AXIS2_PLACEMENT_2D('',#59492,#59493); +#59492 = CARTESIAN_POINT('',(0.65,1.72484542651)); +#59493 = DIRECTION('',(1.,0.E+000)); +#59494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59495 = PCURVE('',#43996,#59496); +#59496 = DEFINITIONAL_REPRESENTATION('',(#59497),#59500); +#59497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59498,#59499),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.173083672929),.PIECEWISE_BEZIER_KNOTS.); -#57246 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57247 = CARTESIAN_POINT('',(5.314676326519,-0.4)); -#57248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57249 = ORIENTED_EDGE('',*,*,#57250,.T.); -#57250 = EDGE_CURVE('',#57228,#57251,#57253,.T.); -#57251 = VERTEX_POINT('',#57252); -#57252 = CARTESIAN_POINT('',(0.570685964796,-1.125,1.840211295898)); -#57253 = SURFACE_CURVE('',#57254,(#57258,#57265),.PCURVE_S1.); -#57254 = LINE('',#57255,#57256); -#57255 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); -#57256 = VECTOR('',#57257,1.); -#57257 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); -#57258 = PCURVE('',#56585,#57259); -#57259 = DEFINITIONAL_REPRESENTATION('',(#57260),#57264); -#57260 = LINE('',#57261,#57262); -#57261 = CARTESIAN_POINT('',(0.240644611662,1.613307865618)); -#57262 = VECTOR('',#57263,1.); -#57263 = DIRECTION('',(0.824041924199,0.566528822887)); -#57264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57265 = PCURVE('',#42161,#57266); -#57266 = DEFINITIONAL_REPRESENTATION('',(#57267),#57271); -#57267 = LINE('',#57268,#57269); -#57268 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57269 = VECTOR('',#57270,1.); -#57270 = DIRECTION('',(1.,0.E+000)); -#57271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57272 = ORIENTED_EDGE('',*,*,#57273,.F.); -#57273 = EDGE_CURVE('',#57274,#57251,#57276,.T.); -#57274 = VERTEX_POINT('',#57275); -#57275 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); -#57276 = SURFACE_CURVE('',#57277,(#57282,#57289),.PCURVE_S1.); -#57277 = CIRCLE('',#57278,0.14); -#57278 = AXIS2_PLACEMENT_3D('',#57279,#57280,#57281); -#57279 = CARTESIAN_POINT('',(0.65,-1.125,1.72484542651)); -#57280 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57281 = DIRECTION('',(1.,0.E+000,0.E+000)); -#57282 = PCURVE('',#56585,#57283); -#57283 = DEFINITIONAL_REPRESENTATION('',(#57284),#57288); -#57284 = CIRCLE('',#57285,0.14); -#57285 = AXIS2_PLACEMENT_2D('',#57286,#57287); -#57286 = CARTESIAN_POINT('',(0.65,1.72484542651)); -#57287 = DIRECTION('',(1.,0.E+000)); -#57288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57289 = PCURVE('',#42134,#57290); -#57290 = DEFINITIONAL_REPRESENTATION('',(#57291),#57294); -#57291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57292,#57293),.UNSPECIFIED., +#59498 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59499 = CARTESIAN_POINT('',(2.173083672929,-0.4)); +#59500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59501 = ORIENTED_EDGE('',*,*,#59502,.T.); +#59502 = EDGE_CURVE('',#59480,#59503,#59505,.T.); +#59503 = VERTEX_POINT('',#59504); +#59504 = CARTESIAN_POINT('',(0.229314035204,-1.125,1.629788704102)); +#59505 = SURFACE_CURVE('',#59506,(#59510,#59517),.PCURVE_S1.); +#59506 = LINE('',#59507,#59508); +#59507 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); +#59508 = VECTOR('',#59509,1.); +#59509 = DIRECTION('',(-0.824041924199,0.E+000,-0.566528822887)); +#59510 = PCURVE('',#59053,#59511); +#59511 = DEFINITIONAL_REPRESENTATION('',(#59512),#59516); +#59512 = LINE('',#59513,#59514); +#59513 = CARTESIAN_POINT('',(0.559355388338,1.856692134382)); +#59514 = VECTOR('',#59515,1.); +#59515 = DIRECTION('',(-0.824041924199,-0.566528822887)); +#59516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59517 = PCURVE('',#43963,#59518); +#59518 = DEFINITIONAL_REPRESENTATION('',(#59519),#59523); +#59519 = LINE('',#59520,#59521); +#59520 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59521 = VECTOR('',#59522,1.); +#59522 = DIRECTION('',(1.,0.E+000)); +#59523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59524 = ORIENTED_EDGE('',*,*,#59525,.F.); +#59525 = EDGE_CURVE('',#59526,#59503,#59528,.T.); +#59526 = VERTEX_POINT('',#59527); +#59527 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); +#59528 = SURFACE_CURVE('',#59529,(#59534,#59541),.PCURVE_S1.); +#59529 = CIRCLE('',#59530,0.14); +#59530 = AXIS2_PLACEMENT_3D('',#59531,#59532,#59533); +#59531 = CARTESIAN_POINT('',(0.15,-1.125,1.74515457349)); +#59532 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59533 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59534 = PCURVE('',#59053,#59535); +#59535 = DEFINITIONAL_REPRESENTATION('',(#59536),#59540); +#59536 = CIRCLE('',#59537,0.14); +#59537 = AXIS2_PLACEMENT_2D('',#59538,#59539); +#59538 = CARTESIAN_POINT('',(0.15,1.74515457349)); +#59539 = DIRECTION('',(-1.,0.E+000)); +#59540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59541 = PCURVE('',#43936,#59542); +#59542 = DEFINITIONAL_REPRESENTATION('',(#59543),#59546); +#59543 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59544,#59545),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57292 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57293 = CARTESIAN_POINT('',(2.17308367293,-0.4)); -#57294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57295 = ORIENTED_EDGE('',*,*,#57296,.T.); -#57296 = EDGE_CURVE('',#57274,#56798,#57297,.T.); -#57297 = SURFACE_CURVE('',#57298,(#57302,#57309),.PCURVE_S1.); -#57298 = LINE('',#57299,#57300); -#57299 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); -#57300 = VECTOR('',#57301,1.); -#57301 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#57302 = PCURVE('',#56585,#57303); -#57303 = DEFINITIONAL_REPRESENTATION('',(#57304),#57308); -#57304 = LINE('',#57305,#57306); -#57305 = CARTESIAN_POINT('',(0.79,1.72484542651)); -#57306 = VECTOR('',#57307,1.); -#57307 = DIRECTION('',(0.E+000,-1.)); -#57308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57309 = PCURVE('',#42101,#57310); -#57310 = DEFINITIONAL_REPRESENTATION('',(#57311),#57315); -#57311 = LINE('',#57312,#57313); -#57312 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57313 = VECTOR('',#57314,1.); -#57314 = DIRECTION('',(1.,0.E+000)); -#57315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57316 = ORIENTED_EDGE('',*,*,#56797,.F.); -#57317 = ORIENTED_EDGE('',*,*,#56569,.F.); -#57318 = ORIENTED_EDGE('',*,*,#56721,.F.); -#57319 = ADVANCED_FACE('',(#57320),#57334,.T.); -#57320 = FACE_BOUND('',#57321,.F.); -#57321 = EDGE_LOOP('',(#57322,#57352,#57375,#57398,#57421,#57444,#57467, - #57490)); -#57322 = ORIENTED_EDGE('',*,*,#57323,.T.); -#57323 = EDGE_CURVE('',#57324,#57326,#57328,.T.); -#57324 = VERTEX_POINT('',#57325); -#57325 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); -#57326 = VERTEX_POINT('',#57327); -#57327 = CARTESIAN_POINT('',(0.79,-1.125,-0.40484542651)); -#57328 = SURFACE_CURVE('',#57329,(#57333,#57345),.PCURVE_S1.); -#57329 = LINE('',#57330,#57331); -#57330 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); -#57331 = VECTOR('',#57332,1.); -#57332 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#57333 = PCURVE('',#57334,#57339); -#57334 = PLANE('',#57335); -#57335 = AXIS2_PLACEMENT_3D('',#57336,#57337,#57338); -#57336 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); -#57337 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57338 = DIRECTION('',(1.,0.E+000,0.E+000)); -#57339 = DEFINITIONAL_REPRESENTATION('',(#57340),#57344); -#57340 = LINE('',#57341,#57342); -#57341 = CARTESIAN_POINT('',(0.79,-0.2)); -#57342 = VECTOR('',#57343,1.); -#57343 = DIRECTION('',(0.E+000,-1.)); -#57344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59544 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#59545 = CARTESIAN_POINT('',(5.314676326519,-0.4)); +#59546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59547 = ORIENTED_EDGE('',*,*,#59548,.T.); +#59548 = EDGE_CURVE('',#59526,#59038,#59549,.T.); +#59549 = SURFACE_CURVE('',#59550,(#59554,#59561),.PCURVE_S1.); +#59550 = LINE('',#59551,#59552); +#59551 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); +#59552 = VECTOR('',#59553,1.); +#59553 = DIRECTION('',(0.E+000,0.E+000,1.)); +#59554 = PCURVE('',#59053,#59555); +#59555 = DEFINITIONAL_REPRESENTATION('',(#59556),#59560); +#59556 = LINE('',#59557,#59558); +#59557 = CARTESIAN_POINT('',(1.E-002,1.74515457349)); +#59558 = VECTOR('',#59559,1.); +#59559 = DIRECTION('',(0.E+000,1.)); +#59560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59561 = PCURVE('',#43903,#59562); +#59562 = DEFINITIONAL_REPRESENTATION('',(#59563),#59567); +#59563 = LINE('',#59564,#59565); +#59564 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59565 = VECTOR('',#59566,1.); +#59566 = DIRECTION('',(1.,0.E+000)); +#59567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59568 = ORIENTED_EDGE('',*,*,#59037,.F.); +#59569 = ORIENTED_EDGE('',*,*,#59162,.F.); +#59570 = ORIENTED_EDGE('',*,*,#59260,.F.); +#59571 = ORIENTED_EDGE('',*,*,#59572,.T.); +#59572 = EDGE_CURVE('',#59238,#59478,#59573,.T.); +#59573 = SURFACE_CURVE('',#59574,(#59578,#59585),.PCURVE_S1.); +#59574 = LINE('',#59575,#59576); +#59575 = CARTESIAN_POINT('',(0.81,-1.125,1.55)); +#59576 = VECTOR('',#59577,1.); +#59577 = DIRECTION('',(0.E+000,0.E+000,1.)); +#59578 = PCURVE('',#59053,#59579); +#59579 = DEFINITIONAL_REPRESENTATION('',(#59580),#59584); +#59580 = LINE('',#59581,#59582); +#59581 = CARTESIAN_POINT('',(0.81,1.55)); +#59582 = VECTOR('',#59583,1.); +#59583 = DIRECTION('',(0.E+000,1.)); +#59584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59585 = PCURVE('',#44023,#59586); +#59586 = DEFINITIONAL_REPRESENTATION('',(#59587),#59591); +#59587 = LINE('',#59588,#59589); +#59588 = CARTESIAN_POINT('',(1.95484542651,-0.4)); +#59589 = VECTOR('',#59590,1.); +#59590 = DIRECTION('',(1.,0.E+000)); +#59591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59592 = ADVANCED_FACE('',(#59593),#58977,.T.); +#59593 = FACE_BOUND('',#59594,.F.); +#59594 = EDGE_LOOP('',(#59595,#59618,#59641,#59664,#59687,#59708,#59709, + #59710)); +#59595 = ORIENTED_EDGE('',*,*,#59596,.F.); +#59596 = EDGE_CURVE('',#59597,#59091,#59599,.T.); +#59597 = VERTEX_POINT('',#59598); +#59598 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); +#59599 = SURFACE_CURVE('',#59600,(#59604,#59611),.PCURVE_S1.); +#59600 = LINE('',#59601,#59602); +#59601 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); +#59602 = VECTOR('',#59603,1.); +#59603 = DIRECTION('',(0.E+000,0.E+000,1.)); +#59604 = PCURVE('',#58977,#59605); +#59605 = DEFINITIONAL_REPRESENTATION('',(#59606),#59610); +#59606 = LINE('',#59607,#59608); +#59607 = CARTESIAN_POINT('',(-1.E-002,1.74515457349)); +#59608 = VECTOR('',#59609,1.); +#59609 = DIRECTION('',(0.E+000,1.)); +#59610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59611 = PCURVE('',#44613,#59612); +#59612 = DEFINITIONAL_REPRESENTATION('',(#59613),#59617); +#59613 = LINE('',#59614,#59615); +#59614 = CARTESIAN_POINT('',(1.03484542651,-0.4)); +#59615 = VECTOR('',#59616,1.); +#59616 = DIRECTION('',(-1.,0.E+000)); +#59617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57345 = PCURVE('',#42101,#57346); -#57346 = DEFINITIONAL_REPRESENTATION('',(#57347),#57351); -#57347 = LINE('',#57348,#57349); -#57348 = CARTESIAN_POINT('',(1.92484542651,-0.4)); -#57349 = VECTOR('',#57350,1.); -#57350 = DIRECTION('',(1.,0.E+000)); -#57351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#59618 = ORIENTED_EDGE('',*,*,#59619,.T.); +#59619 = EDGE_CURVE('',#59597,#59620,#59622,.T.); +#59620 = VERTEX_POINT('',#59621); +#59621 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); +#59622 = SURFACE_CURVE('',#59623,(#59628,#59635),.PCURVE_S1.); +#59623 = CIRCLE('',#59624,0.16); +#59624 = AXIS2_PLACEMENT_3D('',#59625,#59626,#59627); +#59625 = CARTESIAN_POINT('',(0.15,-1.125,1.74515457349)); +#59626 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59627 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59628 = PCURVE('',#58977,#59629); +#59629 = DEFINITIONAL_REPRESENTATION('',(#59630),#59634); +#59630 = CIRCLE('',#59631,0.16); +#59631 = AXIS2_PLACEMENT_2D('',#59632,#59633); +#59632 = CARTESIAN_POINT('',(0.15,1.74515457349)); +#59633 = DIRECTION('',(-1.,0.E+000)); +#59634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59635 = PCURVE('',#44586,#59636); +#59636 = DEFINITIONAL_REPRESENTATION('',(#59637),#59640); +#59637 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59638,#59639),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.173083672929),.PIECEWISE_BEZIER_KNOTS.); +#59638 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#59639 = CARTESIAN_POINT('',(5.314676326519,-0.4)); +#59640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57352 = ORIENTED_EDGE('',*,*,#57353,.F.); -#57353 = EDGE_CURVE('',#57354,#57326,#57356,.T.); -#57354 = VERTEX_POINT('',#57355); -#57355 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); -#57356 = SURFACE_CURVE('',#57357,(#57362,#57369),.PCURVE_S1.); -#57357 = CIRCLE('',#57358,0.14); -#57358 = AXIS2_PLACEMENT_3D('',#57359,#57360,#57361); -#57359 = CARTESIAN_POINT('',(0.65,-1.125,-0.40484542651)); -#57360 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57361 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); -#57362 = PCURVE('',#57334,#57363); -#57363 = DEFINITIONAL_REPRESENTATION('',(#57364),#57368); -#57364 = CIRCLE('',#57365,0.14); -#57365 = AXIS2_PLACEMENT_2D('',#57366,#57367); -#57366 = CARTESIAN_POINT('',(0.65,-0.40484542651)); -#57367 = DIRECTION('',(-0.566528822887,-0.824041924199)); -#57368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57369 = PCURVE('',#42074,#57370); -#57370 = DEFINITIONAL_REPRESENTATION('',(#57371),#57374); -#57371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57372,#57373),.UNSPECIFIED., +#59641 = ORIENTED_EDGE('',*,*,#59642,.T.); +#59642 = EDGE_CURVE('',#59620,#59643,#59645,.T.); +#59643 = VERTEX_POINT('',#59644); +#59644 = CARTESIAN_POINT('',(0.570685964796,-1.125,1.840211295898)); +#59645 = SURFACE_CURVE('',#59646,(#59650,#59657),.PCURVE_S1.); +#59646 = LINE('',#59647,#59648); +#59647 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); +#59648 = VECTOR('',#59649,1.); +#59649 = DIRECTION('',(0.824041924199,0.E+000,0.566528822887)); +#59650 = PCURVE('',#58977,#59651); +#59651 = DEFINITIONAL_REPRESENTATION('',(#59652),#59656); +#59652 = LINE('',#59653,#59654); +#59653 = CARTESIAN_POINT('',(0.240644611662,1.613307865618)); +#59654 = VECTOR('',#59655,1.); +#59655 = DIRECTION('',(0.824041924199,0.566528822887)); +#59656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59657 = PCURVE('',#44553,#59658); +#59658 = DEFINITIONAL_REPRESENTATION('',(#59659),#59663); +#59659 = LINE('',#59660,#59661); +#59660 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59661 = VECTOR('',#59662,1.); +#59662 = DIRECTION('',(1.,0.E+000)); +#59663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59664 = ORIENTED_EDGE('',*,*,#59665,.F.); +#59665 = EDGE_CURVE('',#59666,#59643,#59668,.T.); +#59666 = VERTEX_POINT('',#59667); +#59667 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); +#59668 = SURFACE_CURVE('',#59669,(#59674,#59681),.PCURVE_S1.); +#59669 = CIRCLE('',#59670,0.14); +#59670 = AXIS2_PLACEMENT_3D('',#59671,#59672,#59673); +#59671 = CARTESIAN_POINT('',(0.65,-1.125,1.72484542651)); +#59672 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59673 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59674 = PCURVE('',#58977,#59675); +#59675 = DEFINITIONAL_REPRESENTATION('',(#59676),#59680); +#59676 = CIRCLE('',#59677,0.14); +#59677 = AXIS2_PLACEMENT_2D('',#59678,#59679); +#59678 = CARTESIAN_POINT('',(0.65,1.72484542651)); +#59679 = DIRECTION('',(1.,0.E+000)); +#59680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59681 = PCURVE('',#44526,#59682); +#59682 = DEFINITIONAL_REPRESENTATION('',(#59683),#59686); +#59683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59684,#59685),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57372 = CARTESIAN_POINT('',(4.11010163425,-0.4)); -#57373 = CARTESIAN_POINT('',(6.28318530718,-0.4)); -#57374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57375 = ORIENTED_EDGE('',*,*,#57376,.T.); -#57376 = EDGE_CURVE('',#57354,#57377,#57379,.T.); -#57377 = VERTEX_POINT('',#57378); -#57378 = CARTESIAN_POINT('',(0.240644611662,-1.125,-0.293307865618)); -#57379 = SURFACE_CURVE('',#57380,(#57384,#57391),.PCURVE_S1.); -#57380 = LINE('',#57381,#57382); -#57381 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); -#57382 = VECTOR('',#57383,1.); -#57383 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); -#57384 = PCURVE('',#57334,#57385); -#57385 = DEFINITIONAL_REPRESENTATION('',(#57386),#57390); -#57386 = LINE('',#57387,#57388); -#57387 = CARTESIAN_POINT('',(0.570685964796,-0.520211295898)); -#57388 = VECTOR('',#57389,1.); -#57389 = DIRECTION('',(-0.824041924199,0.566528822887)); -#57390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57391 = PCURVE('',#42041,#57392); -#57392 = DEFINITIONAL_REPRESENTATION('',(#57393),#57397); -#57393 = LINE('',#57394,#57395); -#57394 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57395 = VECTOR('',#57396,1.); -#57396 = DIRECTION('',(1.,0.E+000)); -#57397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57398 = ORIENTED_EDGE('',*,*,#57399,.T.); -#57399 = EDGE_CURVE('',#57377,#57400,#57402,.T.); -#57400 = VERTEX_POINT('',#57401); -#57401 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); -#57402 = SURFACE_CURVE('',#57403,(#57408,#57415),.PCURVE_S1.); -#57403 = CIRCLE('',#57404,0.16); -#57404 = AXIS2_PLACEMENT_3D('',#57405,#57406,#57407); -#57405 = CARTESIAN_POINT('',(0.15,-1.125,-0.42515457349)); -#57406 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57407 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); -#57408 = PCURVE('',#57334,#57409); -#57409 = DEFINITIONAL_REPRESENTATION('',(#57410),#57414); -#57410 = CIRCLE('',#57411,0.16); -#57411 = AXIS2_PLACEMENT_2D('',#57412,#57413); -#57412 = CARTESIAN_POINT('',(0.15,-0.42515457349)); -#57413 = DIRECTION('',(0.566528822887,0.824041924199)); -#57414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57415 = PCURVE('',#42014,#57416); -#57416 = DEFINITIONAL_REPRESENTATION('',(#57417),#57420); -#57417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57418,#57419),.UNSPECIFIED., +#59684 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59685 = CARTESIAN_POINT('',(2.17308367293,-0.4)); +#59686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59687 = ORIENTED_EDGE('',*,*,#59688,.T.); +#59688 = EDGE_CURVE('',#59666,#59190,#59689,.T.); +#59689 = SURFACE_CURVE('',#59690,(#59694,#59701),.PCURVE_S1.); +#59690 = LINE('',#59691,#59692); +#59691 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); +#59692 = VECTOR('',#59693,1.); +#59693 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59694 = PCURVE('',#58977,#59695); +#59695 = DEFINITIONAL_REPRESENTATION('',(#59696),#59700); +#59696 = LINE('',#59697,#59698); +#59697 = CARTESIAN_POINT('',(0.79,1.72484542651)); +#59698 = VECTOR('',#59699,1.); +#59699 = DIRECTION('',(0.E+000,-1.)); +#59700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59701 = PCURVE('',#44493,#59702); +#59702 = DEFINITIONAL_REPRESENTATION('',(#59703),#59707); +#59703 = LINE('',#59704,#59705); +#59704 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59705 = VECTOR('',#59706,1.); +#59706 = DIRECTION('',(1.,0.E+000)); +#59707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59708 = ORIENTED_EDGE('',*,*,#59189,.F.); +#59709 = ORIENTED_EDGE('',*,*,#58961,.F.); +#59710 = ORIENTED_EDGE('',*,*,#59113,.F.); +#59711 = ADVANCED_FACE('',(#59712),#59726,.T.); +#59712 = FACE_BOUND('',#59713,.F.); +#59713 = EDGE_LOOP('',(#59714,#59744,#59767,#59790,#59813,#59836,#59859, + #59882)); +#59714 = ORIENTED_EDGE('',*,*,#59715,.T.); +#59715 = EDGE_CURVE('',#59716,#59718,#59720,.T.); +#59716 = VERTEX_POINT('',#59717); +#59717 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); +#59718 = VERTEX_POINT('',#59719); +#59719 = CARTESIAN_POINT('',(0.79,-1.125,-0.40484542651)); +#59720 = SURFACE_CURVE('',#59721,(#59725,#59737),.PCURVE_S1.); +#59721 = LINE('',#59722,#59723); +#59722 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); +#59723 = VECTOR('',#59724,1.); +#59724 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59725 = PCURVE('',#59726,#59731); +#59726 = PLANE('',#59727); +#59727 = AXIS2_PLACEMENT_3D('',#59728,#59729,#59730); +#59728 = CARTESIAN_POINT('',(0.E+000,-1.125,0.E+000)); +#59729 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59730 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59731 = DEFINITIONAL_REPRESENTATION('',(#59732),#59736); +#59732 = LINE('',#59733,#59734); +#59733 = CARTESIAN_POINT('',(0.79,-0.2)); +#59734 = VECTOR('',#59735,1.); +#59735 = DIRECTION('',(0.E+000,-1.)); +#59736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59737 = PCURVE('',#44493,#59738); +#59738 = DEFINITIONAL_REPRESENTATION('',(#59739),#59743); +#59739 = LINE('',#59740,#59741); +#59740 = CARTESIAN_POINT('',(1.92484542651,-0.4)); +#59741 = VECTOR('',#59742,1.); +#59742 = DIRECTION('',(1.,0.E+000)); +#59743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59744 = ORIENTED_EDGE('',*,*,#59745,.F.); +#59745 = EDGE_CURVE('',#59746,#59718,#59748,.T.); +#59746 = VERTEX_POINT('',#59747); +#59747 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); +#59748 = SURFACE_CURVE('',#59749,(#59754,#59761),.PCURVE_S1.); +#59749 = CIRCLE('',#59750,0.14); +#59750 = AXIS2_PLACEMENT_3D('',#59751,#59752,#59753); +#59751 = CARTESIAN_POINT('',(0.65,-1.125,-0.40484542651)); +#59752 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59753 = DIRECTION('',(-0.566528822887,0.E+000,-0.824041924199)); +#59754 = PCURVE('',#59726,#59755); +#59755 = DEFINITIONAL_REPRESENTATION('',(#59756),#59760); +#59756 = CIRCLE('',#59757,0.14); +#59757 = AXIS2_PLACEMENT_2D('',#59758,#59759); +#59758 = CARTESIAN_POINT('',(0.65,-0.40484542651)); +#59759 = DIRECTION('',(-0.566528822887,-0.824041924199)); +#59760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59761 = PCURVE('',#44466,#59762); +#59762 = DEFINITIONAL_REPRESENTATION('',(#59763),#59766); +#59763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59764,#59765),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); -#57418 = CARTESIAN_POINT('',(0.96850898066,-0.4)); -#57419 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57421 = ORIENTED_EDGE('',*,*,#57422,.T.); -#57422 = EDGE_CURVE('',#57400,#57423,#57425,.T.); -#57423 = VERTEX_POINT('',#57424); -#57424 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.65)); -#57425 = SURFACE_CURVE('',#57426,(#57430,#57437),.PCURVE_S1.); -#57426 = LINE('',#57427,#57428); -#57427 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); -#57428 = VECTOR('',#57429,1.); -#57429 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#57430 = PCURVE('',#57334,#57431); -#57431 = DEFINITIONAL_REPRESENTATION('',(#57432),#57436); -#57432 = LINE('',#57433,#57434); -#57433 = CARTESIAN_POINT('',(-1.E-002,-0.42515457349)); -#57434 = VECTOR('',#57435,1.); -#57435 = DIRECTION('',(0.E+000,-1.)); -#57436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57437 = PCURVE('',#41981,#57438); -#57438 = DEFINITIONAL_REPRESENTATION('',(#57439),#57443); -#57439 = LINE('',#57440,#57441); -#57440 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57441 = VECTOR('',#57442,1.); -#57442 = DIRECTION('',(1.,0.E+000)); -#57443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57444 = ORIENTED_EDGE('',*,*,#57445,.F.); -#57445 = EDGE_CURVE('',#57446,#57423,#57448,.T.); -#57446 = VERTEX_POINT('',#57447); -#57447 = CARTESIAN_POINT('',(-0.35,-1.125,-0.65)); -#57448 = SURFACE_CURVE('',#57449,(#57453,#57460),.PCURVE_S1.); -#57449 = LINE('',#57450,#57451); -#57450 = CARTESIAN_POINT('',(-0.35,-1.125,-0.65)); -#57451 = VECTOR('',#57452,1.); -#57452 = DIRECTION('',(1.,0.E+000,0.E+000)); -#57453 = PCURVE('',#57334,#57454); -#57454 = DEFINITIONAL_REPRESENTATION('',(#57455),#57459); -#57455 = LINE('',#57456,#57457); -#57456 = CARTESIAN_POINT('',(-0.35,-0.65)); -#57457 = VECTOR('',#57458,1.); -#57458 = DIRECTION('',(1.,0.E+000)); -#57459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57460 = PCURVE('',#55353,#57461); -#57461 = DEFINITIONAL_REPRESENTATION('',(#57462),#57466); -#57462 = LINE('',#57463,#57464); -#57463 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#57464 = VECTOR('',#57465,1.); -#57465 = DIRECTION('',(1.,0.E+000)); -#57466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57467 = ORIENTED_EDGE('',*,*,#57468,.F.); -#57468 = EDGE_CURVE('',#57469,#57446,#57471,.T.); -#57469 = VERTEX_POINT('',#57470); -#57470 = CARTESIAN_POINT('',(-0.35,-1.125,-0.2)); -#57471 = SURFACE_CURVE('',#57472,(#57476,#57483),.PCURVE_S1.); -#57472 = LINE('',#57473,#57474); -#57473 = CARTESIAN_POINT('',(-0.35,-1.125,-0.2)); -#57474 = VECTOR('',#57475,1.); -#57475 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#57476 = PCURVE('',#57334,#57477); -#57477 = DEFINITIONAL_REPRESENTATION('',(#57478),#57482); -#57478 = LINE('',#57479,#57480); -#57479 = CARTESIAN_POINT('',(-0.35,-0.2)); -#57480 = VECTOR('',#57481,1.); -#57481 = DIRECTION('',(0.E+000,-1.)); -#57482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57483 = PCURVE('',#55325,#57484); -#57484 = DEFINITIONAL_REPRESENTATION('',(#57485),#57489); -#57485 = LINE('',#57486,#57487); -#57486 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#57487 = VECTOR('',#57488,1.); -#57488 = DIRECTION('',(1.,0.E+000)); -#57489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57490 = ORIENTED_EDGE('',*,*,#57491,.F.); -#57491 = EDGE_CURVE('',#57324,#57469,#57492,.T.); -#57492 = SURFACE_CURVE('',#57493,(#57497,#57504),.PCURVE_S1.); -#57493 = LINE('',#57494,#57495); -#57494 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); -#57495 = VECTOR('',#57496,1.); -#57496 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#57497 = PCURVE('',#57334,#57498); -#57498 = DEFINITIONAL_REPRESENTATION('',(#57499),#57503); -#57499 = LINE('',#57500,#57501); -#57500 = CARTESIAN_POINT('',(0.79,-0.2)); -#57501 = VECTOR('',#57502,1.); -#57502 = DIRECTION('',(-1.,0.E+000)); -#57503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57504 = PCURVE('',#55297,#57505); -#57505 = DEFINITIONAL_REPRESENTATION('',(#57506),#57510); -#57506 = LINE('',#57507,#57508); -#57507 = CARTESIAN_POINT('',(0.71,-0.1)); -#57508 = VECTOR('',#57509,1.); -#57509 = DIRECTION('',(1.,0.E+000)); -#57510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57511 = ADVANCED_FACE('',(#57512),#41631,.F.); -#57512 = FACE_BOUND('',#57513,.F.); -#57513 = EDGE_LOOP('',(#57514,#57515,#57535,#57536,#57556,#57557,#57558, - #57559)); -#57514 = ORIENTED_EDGE('',*,*,#56893,.T.); -#57515 = ORIENTED_EDGE('',*,*,#57516,.T.); -#57516 = EDGE_CURVE('',#56896,#41616,#57517,.T.); -#57517 = SURFACE_CURVE('',#57518,(#57522,#57529),.PCURVE_S1.); -#57518 = LINE('',#57519,#57520); -#57519 = CARTESIAN_POINT('',(0.81,-1.125,-0.40484542651)); -#57520 = VECTOR('',#57521,1.); -#57521 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57522 = PCURVE('',#41631,#57523); -#57523 = DEFINITIONAL_REPRESENTATION('',(#57524),#57528); -#57524 = LINE('',#57525,#57526); -#57525 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57526 = VECTOR('',#57527,1.); -#57527 = DIRECTION('',(0.E+000,-1.)); -#57528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57529 = PCURVE('',#41664,#57530); -#57530 = DEFINITIONAL_REPRESENTATION('',(#57531),#57534); -#57531 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57532,#57533),.UNSPECIFIED., +#59764 = CARTESIAN_POINT('',(4.11010163425,-0.4)); +#59765 = CARTESIAN_POINT('',(6.28318530718,-0.4)); +#59766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59767 = ORIENTED_EDGE('',*,*,#59768,.T.); +#59768 = EDGE_CURVE('',#59746,#59769,#59771,.T.); +#59769 = VERTEX_POINT('',#59770); +#59770 = CARTESIAN_POINT('',(0.240644611662,-1.125,-0.293307865618)); +#59771 = SURFACE_CURVE('',#59772,(#59776,#59783),.PCURVE_S1.); +#59772 = LINE('',#59773,#59774); +#59773 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); +#59774 = VECTOR('',#59775,1.); +#59775 = DIRECTION('',(-0.824041924199,0.E+000,0.566528822887)); +#59776 = PCURVE('',#59726,#59777); +#59777 = DEFINITIONAL_REPRESENTATION('',(#59778),#59782); +#59778 = LINE('',#59779,#59780); +#59779 = CARTESIAN_POINT('',(0.570685964796,-0.520211295898)); +#59780 = VECTOR('',#59781,1.); +#59781 = DIRECTION('',(-0.824041924199,0.566528822887)); +#59782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59783 = PCURVE('',#44433,#59784); +#59784 = DEFINITIONAL_REPRESENTATION('',(#59785),#59789); +#59785 = LINE('',#59786,#59787); +#59786 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59787 = VECTOR('',#59788,1.); +#59788 = DIRECTION('',(1.,0.E+000)); +#59789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59790 = ORIENTED_EDGE('',*,*,#59791,.T.); +#59791 = EDGE_CURVE('',#59769,#59792,#59794,.T.); +#59792 = VERTEX_POINT('',#59793); +#59793 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); +#59794 = SURFACE_CURVE('',#59795,(#59800,#59807),.PCURVE_S1.); +#59795 = CIRCLE('',#59796,0.16); +#59796 = AXIS2_PLACEMENT_3D('',#59797,#59798,#59799); +#59797 = CARTESIAN_POINT('',(0.15,-1.125,-0.42515457349)); +#59798 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#59799 = DIRECTION('',(0.566528822887,0.E+000,0.824041924199)); +#59800 = PCURVE('',#59726,#59801); +#59801 = DEFINITIONAL_REPRESENTATION('',(#59802),#59806); +#59802 = CIRCLE('',#59803,0.16); +#59803 = AXIS2_PLACEMENT_2D('',#59804,#59805); +#59804 = CARTESIAN_POINT('',(0.15,-0.42515457349)); +#59805 = DIRECTION('',(0.566528822887,0.824041924199)); +#59806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59807 = PCURVE('',#44406,#59808); +#59808 = DEFINITIONAL_REPRESENTATION('',(#59809),#59812); +#59809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59810,#59811),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.17308367293),.PIECEWISE_BEZIER_KNOTS.); +#59810 = CARTESIAN_POINT('',(0.96850898066,-0.4)); +#59811 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#59812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59813 = ORIENTED_EDGE('',*,*,#59814,.T.); +#59814 = EDGE_CURVE('',#59792,#59815,#59817,.T.); +#59815 = VERTEX_POINT('',#59816); +#59816 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.65)); +#59817 = SURFACE_CURVE('',#59818,(#59822,#59829),.PCURVE_S1.); +#59818 = LINE('',#59819,#59820); +#59819 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); +#59820 = VECTOR('',#59821,1.); +#59821 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59822 = PCURVE('',#59726,#59823); +#59823 = DEFINITIONAL_REPRESENTATION('',(#59824),#59828); +#59824 = LINE('',#59825,#59826); +#59825 = CARTESIAN_POINT('',(-1.E-002,-0.42515457349)); +#59826 = VECTOR('',#59827,1.); +#59827 = DIRECTION('',(0.E+000,-1.)); +#59828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59829 = PCURVE('',#44373,#59830); +#59830 = DEFINITIONAL_REPRESENTATION('',(#59831),#59835); +#59831 = LINE('',#59832,#59833); +#59832 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59833 = VECTOR('',#59834,1.); +#59834 = DIRECTION('',(1.,0.E+000)); +#59835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59836 = ORIENTED_EDGE('',*,*,#59837,.F.); +#59837 = EDGE_CURVE('',#59838,#59815,#59840,.T.); +#59838 = VERTEX_POINT('',#59839); +#59839 = CARTESIAN_POINT('',(-0.35,-1.125,-0.65)); +#59840 = SURFACE_CURVE('',#59841,(#59845,#59852),.PCURVE_S1.); +#59841 = LINE('',#59842,#59843); +#59842 = CARTESIAN_POINT('',(-0.35,-1.125,-0.65)); +#59843 = VECTOR('',#59844,1.); +#59844 = DIRECTION('',(1.,0.E+000,0.E+000)); +#59845 = PCURVE('',#59726,#59846); +#59846 = DEFINITIONAL_REPRESENTATION('',(#59847),#59851); +#59847 = LINE('',#59848,#59849); +#59848 = CARTESIAN_POINT('',(-0.35,-0.65)); +#59849 = VECTOR('',#59850,1.); +#59850 = DIRECTION('',(1.,0.E+000)); +#59851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59852 = PCURVE('',#57745,#59853); +#59853 = DEFINITIONAL_REPRESENTATION('',(#59854),#59858); +#59854 = LINE('',#59855,#59856); +#59855 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59856 = VECTOR('',#59857,1.); +#59857 = DIRECTION('',(1.,0.E+000)); +#59858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59859 = ORIENTED_EDGE('',*,*,#59860,.F.); +#59860 = EDGE_CURVE('',#59861,#59838,#59863,.T.); +#59861 = VERTEX_POINT('',#59862); +#59862 = CARTESIAN_POINT('',(-0.35,-1.125,-0.2)); +#59863 = SURFACE_CURVE('',#59864,(#59868,#59875),.PCURVE_S1.); +#59864 = LINE('',#59865,#59866); +#59865 = CARTESIAN_POINT('',(-0.35,-1.125,-0.2)); +#59866 = VECTOR('',#59867,1.); +#59867 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#59868 = PCURVE('',#59726,#59869); +#59869 = DEFINITIONAL_REPRESENTATION('',(#59870),#59874); +#59870 = LINE('',#59871,#59872); +#59871 = CARTESIAN_POINT('',(-0.35,-0.2)); +#59872 = VECTOR('',#59873,1.); +#59873 = DIRECTION('',(0.E+000,-1.)); +#59874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59875 = PCURVE('',#57717,#59876); +#59876 = DEFINITIONAL_REPRESENTATION('',(#59877),#59881); +#59877 = LINE('',#59878,#59879); +#59878 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#59879 = VECTOR('',#59880,1.); +#59880 = DIRECTION('',(1.,0.E+000)); +#59881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59882 = ORIENTED_EDGE('',*,*,#59883,.F.); +#59883 = EDGE_CURVE('',#59716,#59861,#59884,.T.); +#59884 = SURFACE_CURVE('',#59885,(#59889,#59896),.PCURVE_S1.); +#59885 = LINE('',#59886,#59887); +#59886 = CARTESIAN_POINT('',(0.79,-1.125,-0.2)); +#59887 = VECTOR('',#59888,1.); +#59888 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#59889 = PCURVE('',#59726,#59890); +#59890 = DEFINITIONAL_REPRESENTATION('',(#59891),#59895); +#59891 = LINE('',#59892,#59893); +#59892 = CARTESIAN_POINT('',(0.79,-0.2)); +#59893 = VECTOR('',#59894,1.); +#59894 = DIRECTION('',(-1.,0.E+000)); +#59895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59896 = PCURVE('',#57689,#59897); +#59897 = DEFINITIONAL_REPRESENTATION('',(#59898),#59902); +#59898 = LINE('',#59899,#59900); +#59899 = CARTESIAN_POINT('',(0.71,-0.1)); +#59900 = VECTOR('',#59901,1.); +#59901 = DIRECTION('',(1.,0.E+000)); +#59902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59903 = ADVANCED_FACE('',(#59904),#44023,.F.); +#59904 = FACE_BOUND('',#59905,.F.); +#59905 = EDGE_LOOP('',(#59906,#59907,#59927,#59928,#59948,#59949,#59950, + #59951)); +#59906 = ORIENTED_EDGE('',*,*,#59285,.T.); +#59907 = ORIENTED_EDGE('',*,*,#59908,.T.); +#59908 = EDGE_CURVE('',#59288,#44008,#59909,.T.); +#59909 = SURFACE_CURVE('',#59910,(#59914,#59921),.PCURVE_S1.); +#59910 = LINE('',#59911,#59912); +#59911 = CARTESIAN_POINT('',(0.81,-1.125,-0.40484542651)); +#59912 = VECTOR('',#59913,1.); +#59913 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59914 = PCURVE('',#44023,#59915); +#59915 = DEFINITIONAL_REPRESENTATION('',(#59916),#59920); +#59916 = LINE('',#59917,#59918); +#59917 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59918 = VECTOR('',#59919,1.); +#59919 = DIRECTION('',(0.E+000,-1.)); +#59920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59921 = PCURVE('',#44056,#59922); +#59922 = DEFINITIONAL_REPRESENTATION('',(#59923),#59926); +#59923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59924,#59925),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57532 = CARTESIAN_POINT('',(6.28318530718,-0.4)); -#57533 = CARTESIAN_POINT('',(6.28318530718,-0.6)); -#57534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57535 = ORIENTED_EDGE('',*,*,#41615,.T.); -#57536 = ORIENTED_EDGE('',*,*,#57537,.F.); -#57537 = EDGE_CURVE('',#57086,#41584,#57538,.T.); -#57538 = SURFACE_CURVE('',#57539,(#57543,#57550),.PCURVE_S1.); -#57539 = LINE('',#57540,#57541); -#57540 = CARTESIAN_POINT('',(0.81,-1.125,1.72484542651)); -#57541 = VECTOR('',#57542,1.); -#57542 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57543 = PCURVE('',#41631,#57544); -#57544 = DEFINITIONAL_REPRESENTATION('',(#57545),#57549); -#57545 = LINE('',#57546,#57547); -#57546 = CARTESIAN_POINT('',(2.12969085302,-0.4)); -#57547 = VECTOR('',#57548,1.); -#57548 = DIRECTION('',(0.E+000,-1.)); -#57549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57550 = PCURVE('',#41604,#57551); -#57551 = DEFINITIONAL_REPRESENTATION('',(#57552),#57555); -#57552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57553,#57554),.UNSPECIFIED., +#59924 = CARTESIAN_POINT('',(6.28318530718,-0.4)); +#59925 = CARTESIAN_POINT('',(6.28318530718,-0.6)); +#59926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59927 = ORIENTED_EDGE('',*,*,#44007,.T.); +#59928 = ORIENTED_EDGE('',*,*,#59929,.F.); +#59929 = EDGE_CURVE('',#59478,#43976,#59930,.T.); +#59930 = SURFACE_CURVE('',#59931,(#59935,#59942),.PCURVE_S1.); +#59931 = LINE('',#59932,#59933); +#59932 = CARTESIAN_POINT('',(0.81,-1.125,1.72484542651)); +#59933 = VECTOR('',#59934,1.); +#59934 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59935 = PCURVE('',#44023,#59936); +#59936 = DEFINITIONAL_REPRESENTATION('',(#59937),#59941); +#59937 = LINE('',#59938,#59939); +#59938 = CARTESIAN_POINT('',(2.12969085302,-0.4)); +#59939 = VECTOR('',#59940,1.); +#59940 = DIRECTION('',(0.E+000,-1.)); +#59941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59942 = PCURVE('',#43996,#59943); +#59943 = DEFINITIONAL_REPRESENTATION('',(#59944),#59947); +#59944 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59945,#59946),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57553 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57554 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#57555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57556 = ORIENTED_EDGE('',*,*,#57180,.F.); -#57557 = ORIENTED_EDGE('',*,*,#56845,.F.); -#57558 = ORIENTED_EDGE('',*,*,#56521,.F.); -#57559 = ORIENTED_EDGE('',*,*,#57560,.T.); -#57560 = EDGE_CURVE('',#56494,#56894,#57561,.T.); -#57561 = SURFACE_CURVE('',#57562,(#57566,#57573),.PCURVE_S1.); -#57562 = LINE('',#57563,#57564); -#57563 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); -#57564 = VECTOR('',#57565,1.); -#57565 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57566 = PCURVE('',#41631,#57567); -#57567 = DEFINITIONAL_REPRESENTATION('',(#57568),#57572); -#57568 = LINE('',#57569,#57570); -#57569 = CARTESIAN_POINT('',(0.20484542651,-0.3)); -#57570 = VECTOR('',#57571,1.); -#57571 = DIRECTION('',(0.E+000,-1.)); -#57572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57573 = PCURVE('',#56509,#57574); -#57574 = DEFINITIONAL_REPRESENTATION('',(#57575),#57579); -#57575 = LINE('',#57576,#57577); -#57576 = CARTESIAN_POINT('',(0.69,0.E+000)); -#57577 = VECTOR('',#57578,1.); -#57578 = DIRECTION('',(0.E+000,-1.)); -#57579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57580 = ADVANCED_FACE('',(#57581),#41664,.F.); -#57581 = FACE_BOUND('',#57582,.F.); -#57582 = EDGE_LOOP('',(#57583,#57584,#57604,#57605)); -#57583 = ORIENTED_EDGE('',*,*,#57061,.F.); -#57584 = ORIENTED_EDGE('',*,*,#57585,.T.); -#57585 = EDGE_CURVE('',#57039,#41644,#57586,.T.); -#57586 = SURFACE_CURVE('',#57587,(#57591,#57597),.PCURVE_S1.); -#57587 = LINE('',#57588,#57589); -#57588 = CARTESIAN_POINT('',(0.559355388338,-1.125,-0.536692134382)); -#57589 = VECTOR('',#57590,1.); -#57590 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57591 = PCURVE('',#41664,#57592); -#57592 = DEFINITIONAL_REPRESENTATION('',(#57593),#57596); -#57593 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57594,#57595),.UNSPECIFIED., +#59945 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#59946 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#59947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59948 = ORIENTED_EDGE('',*,*,#59572,.F.); +#59949 = ORIENTED_EDGE('',*,*,#59237,.F.); +#59950 = ORIENTED_EDGE('',*,*,#58913,.F.); +#59951 = ORIENTED_EDGE('',*,*,#59952,.T.); +#59952 = EDGE_CURVE('',#58886,#59286,#59953,.T.); +#59953 = SURFACE_CURVE('',#59954,(#59958,#59965),.PCURVE_S1.); +#59954 = LINE('',#59955,#59956); +#59955 = CARTESIAN_POINT('',(0.81,-1.225,-0.2)); +#59956 = VECTOR('',#59957,1.); +#59957 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59958 = PCURVE('',#44023,#59959); +#59959 = DEFINITIONAL_REPRESENTATION('',(#59960),#59964); +#59960 = LINE('',#59961,#59962); +#59961 = CARTESIAN_POINT('',(0.20484542651,-0.3)); +#59962 = VECTOR('',#59963,1.); +#59963 = DIRECTION('',(0.E+000,-1.)); +#59964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59965 = PCURVE('',#58901,#59966); +#59966 = DEFINITIONAL_REPRESENTATION('',(#59967),#59971); +#59967 = LINE('',#59968,#59969); +#59968 = CARTESIAN_POINT('',(0.69,0.E+000)); +#59969 = VECTOR('',#59970,1.); +#59970 = DIRECTION('',(0.E+000,-1.)); +#59971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59972 = ADVANCED_FACE('',(#59973),#44056,.F.); +#59973 = FACE_BOUND('',#59974,.F.); +#59974 = EDGE_LOOP('',(#59975,#59976,#59996,#59997)); +#59975 = ORIENTED_EDGE('',*,*,#59453,.F.); +#59976 = ORIENTED_EDGE('',*,*,#59977,.T.); +#59977 = EDGE_CURVE('',#59431,#44036,#59978,.T.); +#59978 = SURFACE_CURVE('',#59979,(#59983,#59989),.PCURVE_S1.); +#59979 = LINE('',#59980,#59981); +#59980 = CARTESIAN_POINT('',(0.559355388338,-1.125,-0.536692134382)); +#59981 = VECTOR('',#59982,1.); +#59982 = DIRECTION('',(0.E+000,1.,0.E+000)); +#59983 = PCURVE('',#44056,#59984); +#59984 = DEFINITIONAL_REPRESENTATION('',(#59985),#59988); +#59985 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59986,#59987),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57594 = CARTESIAN_POINT('',(4.11010163425,-0.4)); -#57595 = CARTESIAN_POINT('',(4.11010163425,-0.6)); -#57596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57597 = PCURVE('',#41691,#57598); -#57598 = DEFINITIONAL_REPRESENTATION('',(#57599),#57603); -#57599 = LINE('',#57600,#57601); -#57600 = CARTESIAN_POINT('',(0.400515244967,-0.4)); -#57601 = VECTOR('',#57602,1.); -#57602 = DIRECTION('',(0.E+000,-1.)); -#57603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57604 = ORIENTED_EDGE('',*,*,#41643,.T.); -#57605 = ORIENTED_EDGE('',*,*,#57516,.F.); -#57606 = ADVANCED_FACE('',(#57607),#41691,.F.); -#57607 = FACE_BOUND('',#57608,.F.); -#57608 = EDGE_LOOP('',(#57609,#57610,#57630,#57631)); -#57609 = ORIENTED_EDGE('',*,*,#57038,.F.); -#57610 = ORIENTED_EDGE('',*,*,#57611,.T.); -#57611 = EDGE_CURVE('',#57016,#41676,#57612,.T.); -#57612 = SURFACE_CURVE('',#57613,(#57617,#57624),.PCURVE_S1.); -#57613 = LINE('',#57614,#57615); -#57614 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); -#57615 = VECTOR('',#57616,1.); -#57616 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57617 = PCURVE('',#41691,#57618); -#57618 = DEFINITIONAL_REPRESENTATION('',(#57619),#57623); -#57619 = LINE('',#57620,#57621); -#57620 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57621 = VECTOR('',#57622,1.); -#57622 = DIRECTION('',(0.E+000,-1.)); -#57623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57624 = PCURVE('',#41724,#57625); -#57625 = DEFINITIONAL_REPRESENTATION('',(#57626),#57629); -#57626 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57627,#57628),.UNSPECIFIED., +#59986 = CARTESIAN_POINT('',(4.11010163425,-0.4)); +#59987 = CARTESIAN_POINT('',(4.11010163425,-0.6)); +#59988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59989 = PCURVE('',#44083,#59990); +#59990 = DEFINITIONAL_REPRESENTATION('',(#59991),#59995); +#59991 = LINE('',#59992,#59993); +#59992 = CARTESIAN_POINT('',(0.400515244967,-0.4)); +#59993 = VECTOR('',#59994,1.); +#59994 = DIRECTION('',(0.E+000,-1.)); +#59995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#59996 = ORIENTED_EDGE('',*,*,#44035,.T.); +#59997 = ORIENTED_EDGE('',*,*,#59908,.F.); +#59998 = ADVANCED_FACE('',(#59999),#44083,.F.); +#59999 = FACE_BOUND('',#60000,.F.); +#60000 = EDGE_LOOP('',(#60001,#60002,#60022,#60023)); +#60001 = ORIENTED_EDGE('',*,*,#59430,.F.); +#60002 = ORIENTED_EDGE('',*,*,#60003,.T.); +#60003 = EDGE_CURVE('',#59408,#44068,#60004,.T.); +#60004 = SURFACE_CURVE('',#60005,(#60009,#60016),.PCURVE_S1.); +#60005 = LINE('',#60006,#60007); +#60006 = CARTESIAN_POINT('',(0.229314035204,-1.125,-0.309788704102)); +#60007 = VECTOR('',#60008,1.); +#60008 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60009 = PCURVE('',#44083,#60010); +#60010 = DEFINITIONAL_REPRESENTATION('',(#60011),#60015); +#60011 = LINE('',#60012,#60013); +#60012 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#60013 = VECTOR('',#60014,1.); +#60014 = DIRECTION('',(0.E+000,-1.)); +#60015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60016 = PCURVE('',#44116,#60017); +#60017 = DEFINITIONAL_REPRESENTATION('',(#60018),#60021); +#60018 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60019,#60020),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57627 = CARTESIAN_POINT('',(0.96850898066,-0.4)); -#57628 = CARTESIAN_POINT('',(0.96850898066,-0.6)); -#57629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57630 = ORIENTED_EDGE('',*,*,#41675,.T.); -#57631 = ORIENTED_EDGE('',*,*,#57585,.F.); -#57632 = ADVANCED_FACE('',(#57633),#41724,.T.); -#57633 = FACE_BOUND('',#57634,.T.); -#57634 = EDGE_LOOP('',(#57635,#57636,#57637,#57638)); -#57635 = ORIENTED_EDGE('',*,*,#57015,.F.); -#57636 = ORIENTED_EDGE('',*,*,#57611,.T.); -#57637 = ORIENTED_EDGE('',*,*,#41703,.T.); -#57638 = ORIENTED_EDGE('',*,*,#57639,.F.); -#57639 = EDGE_CURVE('',#56993,#41704,#57640,.T.); -#57640 = SURFACE_CURVE('',#57641,(#57645,#57651),.PCURVE_S1.); -#57641 = LINE('',#57642,#57643); -#57642 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); -#57643 = VECTOR('',#57644,1.); -#57644 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57645 = PCURVE('',#41724,#57646); -#57646 = DEFINITIONAL_REPRESENTATION('',(#57647),#57650); -#57647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57648,#57649),.UNSPECIFIED., +#60019 = CARTESIAN_POINT('',(0.96850898066,-0.4)); +#60020 = CARTESIAN_POINT('',(0.96850898066,-0.6)); +#60021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60022 = ORIENTED_EDGE('',*,*,#44067,.T.); +#60023 = ORIENTED_EDGE('',*,*,#59977,.F.); +#60024 = ADVANCED_FACE('',(#60025),#44116,.T.); +#60025 = FACE_BOUND('',#60026,.T.); +#60026 = EDGE_LOOP('',(#60027,#60028,#60029,#60030)); +#60027 = ORIENTED_EDGE('',*,*,#59407,.F.); +#60028 = ORIENTED_EDGE('',*,*,#60003,.T.); +#60029 = ORIENTED_EDGE('',*,*,#44095,.T.); +#60030 = ORIENTED_EDGE('',*,*,#60031,.F.); +#60031 = EDGE_CURVE('',#59385,#44096,#60032,.T.); +#60032 = SURFACE_CURVE('',#60033,(#60037,#60043),.PCURVE_S1.); +#60033 = LINE('',#60034,#60035); +#60034 = CARTESIAN_POINT('',(1.E-002,-1.125,-0.42515457349)); +#60035 = VECTOR('',#60036,1.); +#60036 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60037 = PCURVE('',#44116,#60038); +#60038 = DEFINITIONAL_REPRESENTATION('',(#60039),#60042); +#60039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60040,#60041),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57648 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57649 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#57650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57651 = PCURVE('',#41751,#57652); -#57652 = DEFINITIONAL_REPRESENTATION('',(#57653),#57657); -#57653 = LINE('',#57654,#57655); -#57654 = CARTESIAN_POINT('',(0.70484542651,-0.4)); -#57655 = VECTOR('',#57656,1.); -#57656 = DIRECTION('',(0.E+000,-1.)); -#57657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57658 = ADVANCED_FACE('',(#57659),#41751,.F.); -#57659 = FACE_BOUND('',#57660,.F.); -#57660 = EDGE_LOOP('',(#57661,#57662,#57683,#57684,#57705,#57706)); -#57661 = ORIENTED_EDGE('',*,*,#56992,.T.); -#57662 = ORIENTED_EDGE('',*,*,#57663,.F.); -#57663 = EDGE_CURVE('',#56415,#56970,#57664,.T.); -#57664 = SURFACE_CURVE('',#57665,(#57669,#57676),.PCURVE_S1.); -#57665 = LINE('',#57666,#57667); -#57666 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); -#57667 = VECTOR('',#57668,1.); -#57668 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57669 = PCURVE('',#41751,#57670); -#57670 = DEFINITIONAL_REPRESENTATION('',(#57671),#57675); -#57671 = LINE('',#57672,#57673); -#57672 = CARTESIAN_POINT('',(0.48,-0.3)); -#57673 = VECTOR('',#57674,1.); -#57674 = DIRECTION('',(0.E+000,-1.)); -#57675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57676 = PCURVE('',#56453,#57677); -#57677 = DEFINITIONAL_REPRESENTATION('',(#57678),#57682); -#57678 = LINE('',#57679,#57680); -#57679 = CARTESIAN_POINT('',(0.36,0.E+000)); -#57680 = VECTOR('',#57681,1.); -#57681 = DIRECTION('',(0.E+000,-1.)); -#57682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57683 = ORIENTED_EDGE('',*,*,#56414,.F.); -#57684 = ORIENTED_EDGE('',*,*,#57685,.F.); -#57685 = EDGE_CURVE('',#41736,#56392,#57686,.T.); -#57686 = SURFACE_CURVE('',#57687,(#57691,#57698),.PCURVE_S1.); -#57687 = LINE('',#57688,#57689); -#57688 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); -#57689 = VECTOR('',#57690,1.); -#57690 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#57691 = PCURVE('',#41751,#57692); -#57692 = DEFINITIONAL_REPRESENTATION('',(#57693),#57697); -#57693 = LINE('',#57694,#57695); -#57694 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#57695 = VECTOR('',#57696,1.); -#57696 = DIRECTION('',(0.E+000,1.)); -#57697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57698 = PCURVE('',#41779,#57699); -#57699 = DEFINITIONAL_REPRESENTATION('',(#57700),#57704); -#57700 = LINE('',#57701,#57702); -#57701 = CARTESIAN_POINT('',(1.7,-0.3)); -#57702 = VECTOR('',#57703,1.); -#57703 = DIRECTION('',(0.E+000,1.)); -#57704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57705 = ORIENTED_EDGE('',*,*,#41735,.T.); -#57706 = ORIENTED_EDGE('',*,*,#57639,.F.); -#57707 = ADVANCED_FACE('',(#57708),#55353,.F.); -#57708 = FACE_BOUND('',#57709,.F.); -#57709 = EDGE_LOOP('',(#57710,#57711,#57732,#57733)); -#57710 = ORIENTED_EDGE('',*,*,#55337,.F.); -#57711 = ORIENTED_EDGE('',*,*,#57712,.T.); -#57712 = EDGE_CURVE('',#55310,#57446,#57713,.T.); -#57713 = SURFACE_CURVE('',#57714,(#57718,#57725),.PCURVE_S1.); -#57714 = LINE('',#57715,#57716); -#57715 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); -#57716 = VECTOR('',#57717,1.); -#57717 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57718 = PCURVE('',#55353,#57719); -#57719 = DEFINITIONAL_REPRESENTATION('',(#57720),#57724); -#57720 = LINE('',#57721,#57722); -#57721 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#57722 = VECTOR('',#57723,1.); -#57723 = DIRECTION('',(0.E+000,-1.)); -#57724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57725 = PCURVE('',#55325,#57726); -#57726 = DEFINITIONAL_REPRESENTATION('',(#57727),#57731); -#57727 = LINE('',#57728,#57729); -#57728 = CARTESIAN_POINT('',(0.45,0.E+000)); -#57729 = VECTOR('',#57730,1.); -#57730 = DIRECTION('',(0.E+000,-1.)); -#57731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57732 = ORIENTED_EDGE('',*,*,#57445,.T.); -#57733 = ORIENTED_EDGE('',*,*,#57734,.F.); -#57734 = EDGE_CURVE('',#55338,#57423,#57735,.T.); -#57735 = SURFACE_CURVE('',#57736,(#57740,#57747),.PCURVE_S1.); -#57736 = LINE('',#57737,#57738); -#57737 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); -#57738 = VECTOR('',#57739,1.); -#57739 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57740 = PCURVE('',#55353,#57741); -#57741 = DEFINITIONAL_REPRESENTATION('',(#57742),#57746); -#57742 = LINE('',#57743,#57744); -#57743 = CARTESIAN_POINT('',(0.34,0.E+000)); -#57744 = VECTOR('',#57745,1.); -#57745 = DIRECTION('',(0.E+000,-1.)); -#57746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57747 = PCURVE('',#41981,#57748); -#57748 = DEFINITIONAL_REPRESENTATION('',(#57749),#57753); -#57749 = LINE('',#57750,#57751); -#57750 = CARTESIAN_POINT('',(0.22484542651,-0.3)); -#57751 = VECTOR('',#57752,1.); -#57752 = DIRECTION('',(0.E+000,-1.)); -#57753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57754 = ADVANCED_FACE('',(#57755),#56453,.F.); -#57755 = FACE_BOUND('',#57756,.F.); -#57756 = EDGE_LOOP('',(#57757,#57758,#57759,#57760)); -#57757 = ORIENTED_EDGE('',*,*,#56437,.F.); -#57758 = ORIENTED_EDGE('',*,*,#57663,.T.); -#57759 = ORIENTED_EDGE('',*,*,#56969,.T.); -#57760 = ORIENTED_EDGE('',*,*,#57761,.F.); -#57761 = EDGE_CURVE('',#56438,#56947,#57762,.T.); -#57762 = SURFACE_CURVE('',#57763,(#57767,#57774),.PCURVE_S1.); -#57763 = LINE('',#57764,#57765); -#57764 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); -#57765 = VECTOR('',#57766,1.); -#57766 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57767 = PCURVE('',#56453,#57768); -#57768 = DEFINITIONAL_REPRESENTATION('',(#57769),#57773); -#57769 = LINE('',#57770,#57771); -#57770 = CARTESIAN_POINT('',(1.85,0.E+000)); -#57771 = VECTOR('',#57772,1.); -#57772 = DIRECTION('',(0.E+000,-1.)); -#57773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57774 = PCURVE('',#56481,#57775); -#57775 = DEFINITIONAL_REPRESENTATION('',(#57776),#57780); -#57776 = LINE('',#57777,#57778); -#57777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#57778 = VECTOR('',#57779,1.); -#57779 = DIRECTION('',(0.E+000,-1.)); -#57780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57781 = ADVANCED_FACE('',(#57782),#55325,.F.); -#57782 = FACE_BOUND('',#57783,.F.); -#57783 = EDGE_LOOP('',(#57784,#57785,#57806,#57807)); -#57784 = ORIENTED_EDGE('',*,*,#55309,.F.); -#57785 = ORIENTED_EDGE('',*,*,#57786,.T.); -#57786 = EDGE_CURVE('',#55282,#57469,#57787,.T.); -#57787 = SURFACE_CURVE('',#57788,(#57792,#57799),.PCURVE_S1.); -#57788 = LINE('',#57789,#57790); -#57789 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); -#57790 = VECTOR('',#57791,1.); -#57791 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57792 = PCURVE('',#55325,#57793); -#57793 = DEFINITIONAL_REPRESENTATION('',(#57794),#57798); -#57794 = LINE('',#57795,#57796); -#57795 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#57796 = VECTOR('',#57797,1.); -#57797 = DIRECTION('',(0.E+000,-1.)); -#57798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57799 = PCURVE('',#55297,#57800); -#57800 = DEFINITIONAL_REPRESENTATION('',(#57801),#57805); -#57801 = LINE('',#57802,#57803); -#57802 = CARTESIAN_POINT('',(1.85,0.E+000)); -#57803 = VECTOR('',#57804,1.); -#57804 = DIRECTION('',(0.E+000,-1.)); -#57805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57806 = ORIENTED_EDGE('',*,*,#57468,.T.); -#57807 = ORIENTED_EDGE('',*,*,#57712,.F.); -#57808 = ADVANCED_FACE('',(#57809),#56509,.F.); -#57809 = FACE_BOUND('',#57810,.F.); -#57810 = EDGE_LOOP('',(#57811,#57812,#57833,#57834)); -#57811 = ORIENTED_EDGE('',*,*,#56493,.F.); -#57812 = ORIENTED_EDGE('',*,*,#57813,.T.); -#57813 = EDGE_CURVE('',#56466,#56924,#57814,.T.); -#57814 = SURFACE_CURVE('',#57815,(#57819,#57826),.PCURVE_S1.); -#57815 = LINE('',#57816,#57817); -#57816 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); -#57817 = VECTOR('',#57818,1.); -#57818 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57819 = PCURVE('',#56509,#57820); -#57820 = DEFINITIONAL_REPRESENTATION('',(#57821),#57825); -#57821 = LINE('',#57822,#57823); -#57822 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#57823 = VECTOR('',#57824,1.); -#57824 = DIRECTION('',(0.E+000,-1.)); -#57825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57826 = PCURVE('',#56481,#57827); -#57827 = DEFINITIONAL_REPRESENTATION('',(#57828),#57832); -#57828 = LINE('',#57829,#57830); -#57829 = CARTESIAN_POINT('',(0.45,0.E+000)); -#57830 = VECTOR('',#57831,1.); -#57831 = DIRECTION('',(0.E+000,-1.)); -#57832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57833 = ORIENTED_EDGE('',*,*,#56923,.T.); -#57834 = ORIENTED_EDGE('',*,*,#57560,.F.); -#57835 = ADVANCED_FACE('',(#57836),#55297,.F.); -#57836 = FACE_BOUND('',#57837,.F.); -#57837 = EDGE_LOOP('',(#57838,#57839,#57860,#57861)); -#57838 = ORIENTED_EDGE('',*,*,#55281,.F.); -#57839 = ORIENTED_EDGE('',*,*,#57840,.T.); -#57840 = EDGE_CURVE('',#55259,#57324,#57841,.T.); -#57841 = SURFACE_CURVE('',#57842,(#57846,#57853),.PCURVE_S1.); -#57842 = LINE('',#57843,#57844); -#57843 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); -#57844 = VECTOR('',#57845,1.); -#57845 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57846 = PCURVE('',#55297,#57847); -#57847 = DEFINITIONAL_REPRESENTATION('',(#57848),#57852); -#57848 = LINE('',#57849,#57850); -#57849 = CARTESIAN_POINT('',(0.71,0.E+000)); -#57850 = VECTOR('',#57851,1.); -#57851 = DIRECTION('',(0.E+000,-1.)); -#57852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#60040 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#60041 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#60042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60043 = PCURVE('',#44143,#60044); +#60044 = DEFINITIONAL_REPRESENTATION('',(#60045),#60049); +#60045 = LINE('',#60046,#60047); +#60046 = CARTESIAN_POINT('',(0.70484542651,-0.4)); +#60047 = VECTOR('',#60048,1.); +#60048 = DIRECTION('',(0.E+000,-1.)); +#60049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60050 = ADVANCED_FACE('',(#60051),#44143,.F.); +#60051 = FACE_BOUND('',#60052,.F.); +#60052 = EDGE_LOOP('',(#60053,#60054,#60075,#60076,#60097,#60098)); +#60053 = ORIENTED_EDGE('',*,*,#59384,.T.); +#60054 = ORIENTED_EDGE('',*,*,#60055,.F.); +#60055 = EDGE_CURVE('',#58807,#59362,#60056,.T.); +#60056 = SURFACE_CURVE('',#60057,(#60061,#60068),.PCURVE_S1.); +#60057 = LINE('',#60058,#60059); +#60058 = CARTESIAN_POINT('',(1.E-002,-1.225,-0.65)); +#60059 = VECTOR('',#60060,1.); +#60060 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60061 = PCURVE('',#44143,#60062); +#60062 = DEFINITIONAL_REPRESENTATION('',(#60063),#60067); +#60063 = LINE('',#60064,#60065); +#60064 = CARTESIAN_POINT('',(0.48,-0.3)); +#60065 = VECTOR('',#60066,1.); +#60066 = DIRECTION('',(0.E+000,-1.)); +#60067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60068 = PCURVE('',#58845,#60069); +#60069 = DEFINITIONAL_REPRESENTATION('',(#60070),#60074); +#60070 = LINE('',#60071,#60072); +#60071 = CARTESIAN_POINT('',(0.36,0.E+000)); +#60072 = VECTOR('',#60073,1.); +#60073 = DIRECTION('',(0.E+000,-1.)); +#60074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60075 = ORIENTED_EDGE('',*,*,#58806,.F.); +#60076 = ORIENTED_EDGE('',*,*,#60077,.F.); +#60077 = EDGE_CURVE('',#44128,#58784,#60078,.T.); +#60078 = SURFACE_CURVE('',#60079,(#60083,#60090),.PCURVE_S1.); +#60079 = LINE('',#60080,#60081); +#60080 = CARTESIAN_POINT('',(1.E-002,-0.925,-1.13)); +#60081 = VECTOR('',#60082,1.); +#60082 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#60083 = PCURVE('',#44143,#60084); +#60084 = DEFINITIONAL_REPRESENTATION('',(#60085),#60089); +#60085 = LINE('',#60086,#60087); +#60086 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#60087 = VECTOR('',#60088,1.); +#60088 = DIRECTION('',(0.E+000,1.)); +#60089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#57853 = PCURVE('',#42101,#57854); -#57854 = DEFINITIONAL_REPRESENTATION('',(#57855),#57859); -#57855 = LINE('',#57856,#57857); -#57856 = CARTESIAN_POINT('',(1.92484542651,-0.3)); -#57857 = VECTOR('',#57858,1.); -#57858 = DIRECTION('',(0.E+000,-1.)); -#57859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57860 = ORIENTED_EDGE('',*,*,#57491,.T.); -#57861 = ORIENTED_EDGE('',*,*,#57786,.F.); -#57862 = ADVANCED_FACE('',(#57863),#56481,.F.); -#57863 = FACE_BOUND('',#57864,.F.); -#57864 = EDGE_LOOP('',(#57865,#57866,#57867,#57868)); -#57865 = ORIENTED_EDGE('',*,*,#56465,.F.); -#57866 = ORIENTED_EDGE('',*,*,#57761,.T.); -#57867 = ORIENTED_EDGE('',*,*,#56946,.T.); -#57868 = ORIENTED_EDGE('',*,*,#57813,.F.); -#57869 = ADVANCED_FACE('',(#57870),#42101,.F.); -#57870 = FACE_BOUND('',#57871,.F.); -#57871 = EDGE_LOOP('',(#57872,#57873,#57893,#57894,#57914,#57915,#57916, - #57917)); -#57872 = ORIENTED_EDGE('',*,*,#57296,.F.); -#57873 = ORIENTED_EDGE('',*,*,#57874,.T.); -#57874 = EDGE_CURVE('',#57274,#42086,#57875,.T.); -#57875 = SURFACE_CURVE('',#57876,(#57880,#57887),.PCURVE_S1.); -#57876 = LINE('',#57877,#57878); -#57877 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); -#57878 = VECTOR('',#57879,1.); -#57879 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57880 = PCURVE('',#42101,#57881); -#57881 = DEFINITIONAL_REPRESENTATION('',(#57882),#57886); -#57882 = LINE('',#57883,#57884); -#57883 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57884 = VECTOR('',#57885,1.); -#57885 = DIRECTION('',(0.E+000,-1.)); -#57886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57887 = PCURVE('',#42134,#57888); -#57888 = DEFINITIONAL_REPRESENTATION('',(#57889),#57892); -#57889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57890,#57891),.UNSPECIFIED., +#60090 = PCURVE('',#44171,#60091); +#60091 = DEFINITIONAL_REPRESENTATION('',(#60092),#60096); +#60092 = LINE('',#60093,#60094); +#60093 = CARTESIAN_POINT('',(1.7,-0.3)); +#60094 = VECTOR('',#60095,1.); +#60095 = DIRECTION('',(0.E+000,1.)); +#60096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60097 = ORIENTED_EDGE('',*,*,#44127,.T.); +#60098 = ORIENTED_EDGE('',*,*,#60031,.F.); +#60099 = ADVANCED_FACE('',(#60100),#57745,.F.); +#60100 = FACE_BOUND('',#60101,.F.); +#60101 = EDGE_LOOP('',(#60102,#60103,#60124,#60125)); +#60102 = ORIENTED_EDGE('',*,*,#57729,.F.); +#60103 = ORIENTED_EDGE('',*,*,#60104,.T.); +#60104 = EDGE_CURVE('',#57702,#59838,#60105,.T.); +#60105 = SURFACE_CURVE('',#60106,(#60110,#60117),.PCURVE_S1.); +#60106 = LINE('',#60107,#60108); +#60107 = CARTESIAN_POINT('',(-0.35,-1.225,-0.65)); +#60108 = VECTOR('',#60109,1.); +#60109 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60110 = PCURVE('',#57745,#60111); +#60111 = DEFINITIONAL_REPRESENTATION('',(#60112),#60116); +#60112 = LINE('',#60113,#60114); +#60113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#60114 = VECTOR('',#60115,1.); +#60115 = DIRECTION('',(0.E+000,-1.)); +#60116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60117 = PCURVE('',#57717,#60118); +#60118 = DEFINITIONAL_REPRESENTATION('',(#60119),#60123); +#60119 = LINE('',#60120,#60121); +#60120 = CARTESIAN_POINT('',(0.45,0.E+000)); +#60121 = VECTOR('',#60122,1.); +#60122 = DIRECTION('',(0.E+000,-1.)); +#60123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60124 = ORIENTED_EDGE('',*,*,#59837,.T.); +#60125 = ORIENTED_EDGE('',*,*,#60126,.F.); +#60126 = EDGE_CURVE('',#57730,#59815,#60127,.T.); +#60127 = SURFACE_CURVE('',#60128,(#60132,#60139),.PCURVE_S1.); +#60128 = LINE('',#60129,#60130); +#60129 = CARTESIAN_POINT('',(-1.E-002,-1.225,-0.65)); +#60130 = VECTOR('',#60131,1.); +#60131 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60132 = PCURVE('',#57745,#60133); +#60133 = DEFINITIONAL_REPRESENTATION('',(#60134),#60138); +#60134 = LINE('',#60135,#60136); +#60135 = CARTESIAN_POINT('',(0.34,0.E+000)); +#60136 = VECTOR('',#60137,1.); +#60137 = DIRECTION('',(0.E+000,-1.)); +#60138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60139 = PCURVE('',#44373,#60140); +#60140 = DEFINITIONAL_REPRESENTATION('',(#60141),#60145); +#60141 = LINE('',#60142,#60143); +#60142 = CARTESIAN_POINT('',(0.22484542651,-0.3)); +#60143 = VECTOR('',#60144,1.); +#60144 = DIRECTION('',(0.E+000,-1.)); +#60145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60146 = ADVANCED_FACE('',(#60147),#58845,.F.); +#60147 = FACE_BOUND('',#60148,.F.); +#60148 = EDGE_LOOP('',(#60149,#60150,#60151,#60152)); +#60149 = ORIENTED_EDGE('',*,*,#58829,.F.); +#60150 = ORIENTED_EDGE('',*,*,#60055,.T.); +#60151 = ORIENTED_EDGE('',*,*,#59361,.T.); +#60152 = ORIENTED_EDGE('',*,*,#60153,.F.); +#60153 = EDGE_CURVE('',#58830,#59339,#60154,.T.); +#60154 = SURFACE_CURVE('',#60155,(#60159,#60166),.PCURVE_S1.); +#60155 = LINE('',#60156,#60157); +#60156 = CARTESIAN_POINT('',(1.5,-1.225,-0.65)); +#60157 = VECTOR('',#60158,1.); +#60158 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60159 = PCURVE('',#58845,#60160); +#60160 = DEFINITIONAL_REPRESENTATION('',(#60161),#60165); +#60161 = LINE('',#60162,#60163); +#60162 = CARTESIAN_POINT('',(1.85,0.E+000)); +#60163 = VECTOR('',#60164,1.); +#60164 = DIRECTION('',(0.E+000,-1.)); +#60165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60166 = PCURVE('',#58873,#60167); +#60167 = DEFINITIONAL_REPRESENTATION('',(#60168),#60172); +#60168 = LINE('',#60169,#60170); +#60169 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#60170 = VECTOR('',#60171,1.); +#60171 = DIRECTION('',(0.E+000,-1.)); +#60172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60173 = ADVANCED_FACE('',(#60174),#57717,.F.); +#60174 = FACE_BOUND('',#60175,.F.); +#60175 = EDGE_LOOP('',(#60176,#60177,#60198,#60199)); +#60176 = ORIENTED_EDGE('',*,*,#57701,.F.); +#60177 = ORIENTED_EDGE('',*,*,#60178,.T.); +#60178 = EDGE_CURVE('',#57674,#59861,#60179,.T.); +#60179 = SURFACE_CURVE('',#60180,(#60184,#60191),.PCURVE_S1.); +#60180 = LINE('',#60181,#60182); +#60181 = CARTESIAN_POINT('',(-0.35,-1.225,-0.2)); +#60182 = VECTOR('',#60183,1.); +#60183 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60184 = PCURVE('',#57717,#60185); +#60185 = DEFINITIONAL_REPRESENTATION('',(#60186),#60190); +#60186 = LINE('',#60187,#60188); +#60187 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#60188 = VECTOR('',#60189,1.); +#60189 = DIRECTION('',(0.E+000,-1.)); +#60190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60191 = PCURVE('',#57689,#60192); +#60192 = DEFINITIONAL_REPRESENTATION('',(#60193),#60197); +#60193 = LINE('',#60194,#60195); +#60194 = CARTESIAN_POINT('',(1.85,0.E+000)); +#60195 = VECTOR('',#60196,1.); +#60196 = DIRECTION('',(0.E+000,-1.)); +#60197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60198 = ORIENTED_EDGE('',*,*,#59860,.T.); +#60199 = ORIENTED_EDGE('',*,*,#60104,.F.); +#60200 = ADVANCED_FACE('',(#60201),#58901,.F.); +#60201 = FACE_BOUND('',#60202,.F.); +#60202 = EDGE_LOOP('',(#60203,#60204,#60225,#60226)); +#60203 = ORIENTED_EDGE('',*,*,#58885,.F.); +#60204 = ORIENTED_EDGE('',*,*,#60205,.T.); +#60205 = EDGE_CURVE('',#58858,#59316,#60206,.T.); +#60206 = SURFACE_CURVE('',#60207,(#60211,#60218),.PCURVE_S1.); +#60207 = LINE('',#60208,#60209); +#60208 = CARTESIAN_POINT('',(1.5,-1.225,-0.2)); +#60209 = VECTOR('',#60210,1.); +#60210 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60211 = PCURVE('',#58901,#60212); +#60212 = DEFINITIONAL_REPRESENTATION('',(#60213),#60217); +#60213 = LINE('',#60214,#60215); +#60214 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#60215 = VECTOR('',#60216,1.); +#60216 = DIRECTION('',(0.E+000,-1.)); +#60217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60218 = PCURVE('',#58873,#60219); +#60219 = DEFINITIONAL_REPRESENTATION('',(#60220),#60224); +#60220 = LINE('',#60221,#60222); +#60221 = CARTESIAN_POINT('',(0.45,0.E+000)); +#60222 = VECTOR('',#60223,1.); +#60223 = DIRECTION('',(0.E+000,-1.)); +#60224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60225 = ORIENTED_EDGE('',*,*,#59315,.T.); +#60226 = ORIENTED_EDGE('',*,*,#59952,.F.); +#60227 = ADVANCED_FACE('',(#60228),#57689,.F.); +#60228 = FACE_BOUND('',#60229,.F.); +#60229 = EDGE_LOOP('',(#60230,#60231,#60252,#60253)); +#60230 = ORIENTED_EDGE('',*,*,#57673,.F.); +#60231 = ORIENTED_EDGE('',*,*,#60232,.T.); +#60232 = EDGE_CURVE('',#57651,#59716,#60233,.T.); +#60233 = SURFACE_CURVE('',#60234,(#60238,#60245),.PCURVE_S1.); +#60234 = LINE('',#60235,#60236); +#60235 = CARTESIAN_POINT('',(0.79,-1.225,-0.2)); +#60236 = VECTOR('',#60237,1.); +#60237 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60238 = PCURVE('',#57689,#60239); +#60239 = DEFINITIONAL_REPRESENTATION('',(#60240),#60244); +#60240 = LINE('',#60241,#60242); +#60241 = CARTESIAN_POINT('',(0.71,0.E+000)); +#60242 = VECTOR('',#60243,1.); +#60243 = DIRECTION('',(0.E+000,-1.)); +#60244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60245 = PCURVE('',#44493,#60246); +#60246 = DEFINITIONAL_REPRESENTATION('',(#60247),#60251); +#60247 = LINE('',#60248,#60249); +#60248 = CARTESIAN_POINT('',(1.92484542651,-0.3)); +#60249 = VECTOR('',#60250,1.); +#60250 = DIRECTION('',(0.E+000,-1.)); +#60251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60252 = ORIENTED_EDGE('',*,*,#59883,.T.); +#60253 = ORIENTED_EDGE('',*,*,#60178,.F.); +#60254 = ADVANCED_FACE('',(#60255),#58873,.F.); +#60255 = FACE_BOUND('',#60256,.F.); +#60256 = EDGE_LOOP('',(#60257,#60258,#60259,#60260)); +#60257 = ORIENTED_EDGE('',*,*,#58857,.F.); +#60258 = ORIENTED_EDGE('',*,*,#60153,.T.); +#60259 = ORIENTED_EDGE('',*,*,#59338,.T.); +#60260 = ORIENTED_EDGE('',*,*,#60205,.F.); +#60261 = ADVANCED_FACE('',(#60262),#44493,.F.); +#60262 = FACE_BOUND('',#60263,.F.); +#60263 = EDGE_LOOP('',(#60264,#60265,#60285,#60286,#60306,#60307,#60308, + #60309)); +#60264 = ORIENTED_EDGE('',*,*,#59688,.F.); +#60265 = ORIENTED_EDGE('',*,*,#60266,.T.); +#60266 = EDGE_CURVE('',#59666,#44478,#60267,.T.); +#60267 = SURFACE_CURVE('',#60268,(#60272,#60279),.PCURVE_S1.); +#60268 = LINE('',#60269,#60270); +#60269 = CARTESIAN_POINT('',(0.79,-1.125,1.72484542651)); +#60270 = VECTOR('',#60271,1.); +#60271 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60272 = PCURVE('',#44493,#60273); +#60273 = DEFINITIONAL_REPRESENTATION('',(#60274),#60278); +#60274 = LINE('',#60275,#60276); +#60275 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#60276 = VECTOR('',#60277,1.); +#60277 = DIRECTION('',(0.E+000,-1.)); +#60278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60279 = PCURVE('',#44526,#60280); +#60280 = DEFINITIONAL_REPRESENTATION('',(#60281),#60284); +#60281 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60282,#60283),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57890 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57891 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#57892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57893 = ORIENTED_EDGE('',*,*,#42085,.T.); -#57894 = ORIENTED_EDGE('',*,*,#57895,.F.); -#57895 = EDGE_CURVE('',#57326,#42054,#57896,.T.); -#57896 = SURFACE_CURVE('',#57897,(#57901,#57908),.PCURVE_S1.); -#57897 = LINE('',#57898,#57899); -#57898 = CARTESIAN_POINT('',(0.79,-1.125,-0.40484542651)); -#57899 = VECTOR('',#57900,1.); -#57900 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57901 = PCURVE('',#42101,#57902); -#57902 = DEFINITIONAL_REPRESENTATION('',(#57903),#57907); -#57903 = LINE('',#57904,#57905); -#57904 = CARTESIAN_POINT('',(2.12969085302,-0.4)); -#57905 = VECTOR('',#57906,1.); -#57906 = DIRECTION('',(0.E+000,-1.)); -#57907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57908 = PCURVE('',#42074,#57909); -#57909 = DEFINITIONAL_REPRESENTATION('',(#57910),#57913); -#57910 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57911,#57912),.UNSPECIFIED., +#60282 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#60283 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#60284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60285 = ORIENTED_EDGE('',*,*,#44477,.T.); +#60286 = ORIENTED_EDGE('',*,*,#60287,.F.); +#60287 = EDGE_CURVE('',#59718,#44446,#60288,.T.); +#60288 = SURFACE_CURVE('',#60289,(#60293,#60300),.PCURVE_S1.); +#60289 = LINE('',#60290,#60291); +#60290 = CARTESIAN_POINT('',(0.79,-1.125,-0.40484542651)); +#60291 = VECTOR('',#60292,1.); +#60292 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60293 = PCURVE('',#44493,#60294); +#60294 = DEFINITIONAL_REPRESENTATION('',(#60295),#60299); +#60295 = LINE('',#60296,#60297); +#60296 = CARTESIAN_POINT('',(2.12969085302,-0.4)); +#60297 = VECTOR('',#60298,1.); +#60298 = DIRECTION('',(0.E+000,-1.)); +#60299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60300 = PCURVE('',#44466,#60301); +#60301 = DEFINITIONAL_REPRESENTATION('',(#60302),#60305); +#60302 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60303,#60304),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57911 = CARTESIAN_POINT('',(6.28318530718,-0.4)); -#57912 = CARTESIAN_POINT('',(6.28318530718,-0.6)); -#57913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57914 = ORIENTED_EDGE('',*,*,#57323,.F.); -#57915 = ORIENTED_EDGE('',*,*,#57840,.F.); -#57916 = ORIENTED_EDGE('',*,*,#55258,.F.); -#57917 = ORIENTED_EDGE('',*,*,#56820,.T.); -#57918 = ADVANCED_FACE('',(#57919),#42134,.T.); -#57919 = FACE_BOUND('',#57920,.T.); -#57920 = EDGE_LOOP('',(#57921,#57922,#57923,#57924)); -#57921 = ORIENTED_EDGE('',*,*,#57273,.F.); -#57922 = ORIENTED_EDGE('',*,*,#57874,.T.); -#57923 = ORIENTED_EDGE('',*,*,#42113,.T.); -#57924 = ORIENTED_EDGE('',*,*,#57925,.F.); -#57925 = EDGE_CURVE('',#57251,#42114,#57926,.T.); -#57926 = SURFACE_CURVE('',#57927,(#57931,#57937),.PCURVE_S1.); -#57927 = LINE('',#57928,#57929); -#57928 = CARTESIAN_POINT('',(0.570685964796,-1.125,1.840211295898)); -#57929 = VECTOR('',#57930,1.); -#57930 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57931 = PCURVE('',#42134,#57932); -#57932 = DEFINITIONAL_REPRESENTATION('',(#57933),#57936); -#57933 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57934,#57935),.UNSPECIFIED., +#60303 = CARTESIAN_POINT('',(6.28318530718,-0.4)); +#60304 = CARTESIAN_POINT('',(6.28318530718,-0.6)); +#60305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60306 = ORIENTED_EDGE('',*,*,#59715,.F.); +#60307 = ORIENTED_EDGE('',*,*,#60232,.F.); +#60308 = ORIENTED_EDGE('',*,*,#57650,.F.); +#60309 = ORIENTED_EDGE('',*,*,#59212,.T.); +#60310 = ADVANCED_FACE('',(#60311),#44526,.T.); +#60311 = FACE_BOUND('',#60312,.T.); +#60312 = EDGE_LOOP('',(#60313,#60314,#60315,#60316)); +#60313 = ORIENTED_EDGE('',*,*,#59665,.F.); +#60314 = ORIENTED_EDGE('',*,*,#60266,.T.); +#60315 = ORIENTED_EDGE('',*,*,#44505,.T.); +#60316 = ORIENTED_EDGE('',*,*,#60317,.F.); +#60317 = EDGE_CURVE('',#59643,#44506,#60318,.T.); +#60318 = SURFACE_CURVE('',#60319,(#60323,#60329),.PCURVE_S1.); +#60319 = LINE('',#60320,#60321); +#60320 = CARTESIAN_POINT('',(0.570685964796,-1.125,1.840211295898)); +#60321 = VECTOR('',#60322,1.); +#60322 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60323 = PCURVE('',#44526,#60324); +#60324 = DEFINITIONAL_REPRESENTATION('',(#60325),#60328); +#60325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60326,#60327),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57934 = CARTESIAN_POINT('',(2.17308367293,-0.4)); -#57935 = CARTESIAN_POINT('',(2.17308367293,-0.6)); -#57936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57937 = PCURVE('',#42161,#57938); -#57938 = DEFINITIONAL_REPRESENTATION('',(#57939),#57943); -#57939 = LINE('',#57940,#57941); -#57940 = CARTESIAN_POINT('',(0.400515244967,-0.4)); -#57941 = VECTOR('',#57942,1.); -#57942 = DIRECTION('',(0.E+000,-1.)); -#57943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57944 = ADVANCED_FACE('',(#57945),#42161,.F.); -#57945 = FACE_BOUND('',#57946,.F.); -#57946 = EDGE_LOOP('',(#57947,#57948,#57968,#57969)); -#57947 = ORIENTED_EDGE('',*,*,#57250,.F.); -#57948 = ORIENTED_EDGE('',*,*,#57949,.T.); -#57949 = EDGE_CURVE('',#57228,#42146,#57950,.T.); -#57950 = SURFACE_CURVE('',#57951,(#57955,#57962),.PCURVE_S1.); -#57951 = LINE('',#57952,#57953); -#57952 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); -#57953 = VECTOR('',#57954,1.); -#57954 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57955 = PCURVE('',#42161,#57956); -#57956 = DEFINITIONAL_REPRESENTATION('',(#57957),#57961); -#57957 = LINE('',#57958,#57959); -#57958 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#57959 = VECTOR('',#57960,1.); -#57960 = DIRECTION('',(0.E+000,-1.)); -#57961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57962 = PCURVE('',#42194,#57963); -#57963 = DEFINITIONAL_REPRESENTATION('',(#57964),#57967); -#57964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57965,#57966),.UNSPECIFIED., +#60326 = CARTESIAN_POINT('',(2.17308367293,-0.4)); +#60327 = CARTESIAN_POINT('',(2.17308367293,-0.6)); +#60328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60329 = PCURVE('',#44553,#60330); +#60330 = DEFINITIONAL_REPRESENTATION('',(#60331),#60335); +#60331 = LINE('',#60332,#60333); +#60332 = CARTESIAN_POINT('',(0.400515244967,-0.4)); +#60333 = VECTOR('',#60334,1.); +#60334 = DIRECTION('',(0.E+000,-1.)); +#60335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60336 = ADVANCED_FACE('',(#60337),#44553,.F.); +#60337 = FACE_BOUND('',#60338,.F.); +#60338 = EDGE_LOOP('',(#60339,#60340,#60360,#60361)); +#60339 = ORIENTED_EDGE('',*,*,#59642,.F.); +#60340 = ORIENTED_EDGE('',*,*,#60341,.T.); +#60341 = EDGE_CURVE('',#59620,#44538,#60342,.T.); +#60342 = SURFACE_CURVE('',#60343,(#60347,#60354),.PCURVE_S1.); +#60343 = LINE('',#60344,#60345); +#60344 = CARTESIAN_POINT('',(0.240644611662,-1.125,1.613307865618)); +#60345 = VECTOR('',#60346,1.); +#60346 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60347 = PCURVE('',#44553,#60348); +#60348 = DEFINITIONAL_REPRESENTATION('',(#60349),#60353); +#60349 = LINE('',#60350,#60351); +#60350 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#60351 = VECTOR('',#60352,1.); +#60352 = DIRECTION('',(0.E+000,-1.)); +#60353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60354 = PCURVE('',#44586,#60355); +#60355 = DEFINITIONAL_REPRESENTATION('',(#60356),#60359); +#60356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60357,#60358),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57965 = CARTESIAN_POINT('',(5.314676326519,-0.4)); -#57966 = CARTESIAN_POINT('',(5.314676326519,-0.6)); -#57967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57968 = ORIENTED_EDGE('',*,*,#42145,.T.); -#57969 = ORIENTED_EDGE('',*,*,#57925,.F.); -#57970 = ADVANCED_FACE('',(#57971),#42194,.F.); -#57971 = FACE_BOUND('',#57972,.F.); -#57972 = EDGE_LOOP('',(#57973,#57974,#57994,#57995)); -#57973 = ORIENTED_EDGE('',*,*,#57227,.F.); -#57974 = ORIENTED_EDGE('',*,*,#57975,.T.); -#57975 = EDGE_CURVE('',#57205,#42174,#57976,.T.); -#57976 = SURFACE_CURVE('',#57977,(#57981,#57987),.PCURVE_S1.); -#57977 = LINE('',#57978,#57979); -#57978 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); -#57979 = VECTOR('',#57980,1.); -#57980 = DIRECTION('',(0.E+000,1.,0.E+000)); -#57981 = PCURVE('',#42194,#57982); -#57982 = DEFINITIONAL_REPRESENTATION('',(#57983),#57986); -#57983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#57984,#57985),.UNSPECIFIED., +#60357 = CARTESIAN_POINT('',(5.314676326519,-0.4)); +#60358 = CARTESIAN_POINT('',(5.314676326519,-0.6)); +#60359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60360 = ORIENTED_EDGE('',*,*,#44537,.T.); +#60361 = ORIENTED_EDGE('',*,*,#60317,.F.); +#60362 = ADVANCED_FACE('',(#60363),#44586,.F.); +#60363 = FACE_BOUND('',#60364,.F.); +#60364 = EDGE_LOOP('',(#60365,#60366,#60386,#60387)); +#60365 = ORIENTED_EDGE('',*,*,#59619,.F.); +#60366 = ORIENTED_EDGE('',*,*,#60367,.T.); +#60367 = EDGE_CURVE('',#59597,#44566,#60368,.T.); +#60368 = SURFACE_CURVE('',#60369,(#60373,#60379),.PCURVE_S1.); +#60369 = LINE('',#60370,#60371); +#60370 = CARTESIAN_POINT('',(-1.E-002,-1.125,1.74515457349)); +#60371 = VECTOR('',#60372,1.); +#60372 = DIRECTION('',(0.E+000,1.,0.E+000)); +#60373 = PCURVE('',#44586,#60374); +#60374 = DEFINITIONAL_REPRESENTATION('',(#60375),#60378); +#60375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60376,#60377),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#57984 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#57985 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#57986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57987 = PCURVE('',#42221,#57988); -#57988 = DEFINITIONAL_REPRESENTATION('',(#57989),#57993); -#57989 = LINE('',#57990,#57991); -#57990 = CARTESIAN_POINT('',(1.03484542651,-0.4)); -#57991 = VECTOR('',#57992,1.); -#57992 = DIRECTION('',(0.E+000,-1.)); -#57993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#57994 = ORIENTED_EDGE('',*,*,#42173,.T.); -#57995 = ORIENTED_EDGE('',*,*,#57949,.F.); -#57996 = ADVANCED_FACE('',(#57997),#42221,.F.); -#57997 = FACE_BOUND('',#57998,.F.); -#57998 = EDGE_LOOP('',(#57999,#58028,#58056,#58077,#58078,#58079,#58080, - #58081,#58082)); -#57999 = ORIENTED_EDGE('',*,*,#58000,.T.); -#58000 = EDGE_CURVE('',#58001,#58003,#58005,.T.); -#58001 = VERTEX_POINT('',#58002); -#58002 = CARTESIAN_POINT('',(-1.E-002,-1.313674285394,2.420762596622)); -#58003 = VERTEX_POINT('',#58004); -#58004 = CARTESIAN_POINT('',(-1.E-002,-1.12655103819,2.655251168531)); -#58005 = SURFACE_CURVE('',#58006,(#58010,#58017),.PCURVE_S1.); -#58006 = LINE('',#58007,#58008); -#58007 = CARTESIAN_POINT('',(-1.E-002,-1.313674285394,2.420762596622)); -#58008 = VECTOR('',#58009,1.); -#58009 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58010 = PCURVE('',#42221,#58011); -#58011 = DEFINITIONAL_REPRESENTATION('',(#58012),#58016); -#58012 = LINE('',#58013,#58014); -#58013 = CARTESIAN_POINT('',(0.359237403378,-0.211325714606)); -#58014 = VECTOR('',#58015,1.); -#58015 = DIRECTION('',(-0.78162857303,-0.623744157346)); -#58016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58017 = PCURVE('',#58018,#58023); -#58018 = CYLINDRICAL_SURFACE('',#58019,0.2); -#58019 = AXIS2_PLACEMENT_3D('',#58020,#58021,#58022); -#58020 = CARTESIAN_POINT('',(-0.21,-1.323818161125,2.408051065749)); -#58021 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58022 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58023 = DEFINITIONAL_REPRESENTATION('',(#58024),#58027); -#58024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58025,#58026),.UNSPECIFIED., +#60376 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#60377 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#60378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60379 = PCURVE('',#44613,#60380); +#60380 = DEFINITIONAL_REPRESENTATION('',(#60381),#60385); +#60381 = LINE('',#60382,#60383); +#60382 = CARTESIAN_POINT('',(1.03484542651,-0.4)); +#60383 = VECTOR('',#60384,1.); +#60384 = DIRECTION('',(0.E+000,-1.)); +#60385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60386 = ORIENTED_EDGE('',*,*,#44565,.T.); +#60387 = ORIENTED_EDGE('',*,*,#60341,.F.); +#60388 = ADVANCED_FACE('',(#60389),#44613,.F.); +#60389 = FACE_BOUND('',#60390,.F.); +#60390 = EDGE_LOOP('',(#60391,#60420,#60448,#60469,#60470,#60471,#60472, + #60473,#60474)); +#60391 = ORIENTED_EDGE('',*,*,#60392,.T.); +#60392 = EDGE_CURVE('',#60393,#60395,#60397,.T.); +#60393 = VERTEX_POINT('',#60394); +#60394 = CARTESIAN_POINT('',(-1.E-002,-1.313674285394,2.420762596622)); +#60395 = VERTEX_POINT('',#60396); +#60396 = CARTESIAN_POINT('',(-1.E-002,-1.12655103819,2.655251168531)); +#60397 = SURFACE_CURVE('',#60398,(#60402,#60409),.PCURVE_S1.); +#60398 = LINE('',#60399,#60400); +#60399 = CARTESIAN_POINT('',(-1.E-002,-1.313674285394,2.420762596622)); +#60400 = VECTOR('',#60401,1.); +#60401 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60402 = PCURVE('',#44613,#60403); +#60403 = DEFINITIONAL_REPRESENTATION('',(#60404),#60408); +#60404 = LINE('',#60405,#60406); +#60405 = CARTESIAN_POINT('',(0.359237403378,-0.211325714606)); +#60406 = VECTOR('',#60407,1.); +#60407 = DIRECTION('',(-0.78162857303,-0.623744157346)); +#60408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60409 = PCURVE('',#60410,#60415); +#60410 = CYLINDRICAL_SURFACE('',#60411,0.2); +#60411 = AXIS2_PLACEMENT_3D('',#60412,#60413,#60414); +#60412 = CARTESIAN_POINT('',(-0.21,-1.323818161125,2.408051065749)); +#60413 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60414 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60415 = DEFINITIONAL_REPRESENTATION('',(#60416),#60419); +#60416 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60417,#60418),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#58025 = CARTESIAN_POINT('',(1.570796326793,1.626287895734E-002)); -#58026 = CARTESIAN_POINT('',(1.570796326793,0.316262878957)); -#58027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58028 = ORIENTED_EDGE('',*,*,#58029,.F.); -#58029 = EDGE_CURVE('',#58030,#58003,#58032,.T.); -#58030 = VERTEX_POINT('',#58031); -#58031 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); -#58032 = SURFACE_CURVE('',#58033,(#58037,#58044),.PCURVE_S1.); -#58033 = LINE('',#58034,#58035); -#58034 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); -#58035 = VECTOR('',#58036,1.); -#58036 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58037 = PCURVE('',#42221,#58038); -#58038 = DEFINITIONAL_REPRESENTATION('',(#58039),#58043); -#58039 = LINE('',#58040,#58041); -#58040 = CARTESIAN_POINT('',(0.198513971647,-0.49088580563)); -#58041 = VECTOR('',#58042,1.); -#58042 = DIRECTION('',(-0.623744157346,0.78162857303)); -#58043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58044 = PCURVE('',#58045,#58050); -#58045 = PLANE('',#58046); -#58046 = AXIS2_PLACEMENT_3D('',#58047,#58048,#58049); -#58047 = CARTESIAN_POINT('',(2.5,-1.282876752796,2.78)); -#58048 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58049 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); -#58050 = DEFINITIONAL_REPRESENTATION('',(#58051),#58055); -#58051 = LINE('',#58052,#58053); -#58052 = CARTESIAN_POINT('',(0.318261853532,2.51)); -#58053 = VECTOR('',#58054,1.); -#58054 = DIRECTION('',(-1.,0.E+000)); -#58055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58056 = ORIENTED_EDGE('',*,*,#58057,.T.); -#58057 = EDGE_CURVE('',#58030,#42206,#58058,.T.); -#58058 = SURFACE_CURVE('',#58059,(#58064,#58071),.PCURVE_S1.); -#58059 = CIRCLE('',#58060,0.29); -#58060 = AXIS2_PLACEMENT_3D('',#58061,#58062,#58063); -#58061 = CARTESIAN_POINT('',(-1.E-002,-1.215,2.354813742174)); -#58062 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58063 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58064 = PCURVE('',#42221,#58065); -#58065 = DEFINITIONAL_REPRESENTATION('',(#58066),#58070); -#58066 = CIRCLE('',#58067,0.29); -#58067 = AXIS2_PLACEMENT_2D('',#58068,#58069); -#58068 = CARTESIAN_POINT('',(0.425186257826,-0.31)); -#58069 = DIRECTION('',(-0.78162857303,-0.623744157346)); -#58070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58071 = PCURVE('',#42249,#58072); -#58072 = DEFINITIONAL_REPRESENTATION('',(#58073),#58076); -#58073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58074,#58075),.UNSPECIFIED., +#60417 = CARTESIAN_POINT('',(1.570796326793,1.626287895734E-002)); +#60418 = CARTESIAN_POINT('',(1.570796326793,0.316262878957)); +#60419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60420 = ORIENTED_EDGE('',*,*,#60421,.F.); +#60421 = EDGE_CURVE('',#60422,#60395,#60424,.T.); +#60422 = VERTEX_POINT('',#60423); +#60423 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); +#60424 = SURFACE_CURVE('',#60425,(#60429,#60436),.PCURVE_S1.); +#60425 = LINE('',#60426,#60427); +#60426 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); +#60427 = VECTOR('',#60428,1.); +#60428 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60429 = PCURVE('',#44613,#60430); +#60430 = DEFINITIONAL_REPRESENTATION('',(#60431),#60435); +#60431 = LINE('',#60432,#60433); +#60432 = CARTESIAN_POINT('',(0.198513971647,-0.49088580563)); +#60433 = VECTOR('',#60434,1.); +#60434 = DIRECTION('',(-0.623744157346,0.78162857303)); +#60435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60436 = PCURVE('',#60437,#60442); +#60437 = PLANE('',#60438); +#60438 = AXIS2_PLACEMENT_3D('',#60439,#60440,#60441); +#60439 = CARTESIAN_POINT('',(2.5,-1.282876752796,2.78)); +#60440 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60441 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); +#60442 = DEFINITIONAL_REPRESENTATION('',(#60443),#60447); +#60443 = LINE('',#60444,#60445); +#60444 = CARTESIAN_POINT('',(0.318261853532,2.51)); +#60445 = VECTOR('',#60446,1.); +#60446 = DIRECTION('',(-1.,0.E+000)); +#60447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60448 = ORIENTED_EDGE('',*,*,#60449,.T.); +#60449 = EDGE_CURVE('',#60422,#44598,#60450,.T.); +#60450 = SURFACE_CURVE('',#60451,(#60456,#60463),.PCURVE_S1.); +#60451 = CIRCLE('',#60452,0.29); +#60452 = AXIS2_PLACEMENT_3D('',#60453,#60454,#60455); +#60453 = CARTESIAN_POINT('',(-1.E-002,-1.215,2.354813742174)); +#60454 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60455 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60456 = PCURVE('',#44613,#60457); +#60457 = DEFINITIONAL_REPRESENTATION('',(#60458),#60462); +#60458 = CIRCLE('',#60459,0.29); +#60459 = AXIS2_PLACEMENT_2D('',#60460,#60461); +#60460 = CARTESIAN_POINT('',(0.425186257826,-0.31)); +#60461 = DIRECTION('',(-0.78162857303,-0.623744157346)); +#60462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60463 = PCURVE('',#44641,#60464); +#60464 = DEFINITIONAL_REPRESENTATION('',(#60465),#60468); +#60465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60466,#60467),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525926),.PIECEWISE_BEZIER_KNOTS.); -#58074 = CARTESIAN_POINT('',(0.673523800868,2.51)); -#58075 = CARTESIAN_POINT('',(1.570796326795,2.51)); -#58076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58077 = ORIENTED_EDGE('',*,*,#42205,.T.); -#58078 = ORIENTED_EDGE('',*,*,#57975,.F.); -#58079 = ORIENTED_EDGE('',*,*,#57204,.T.); -#58080 = ORIENTED_EDGE('',*,*,#56698,.T.); -#58081 = ORIENTED_EDGE('',*,*,#55797,.F.); -#58082 = ORIENTED_EDGE('',*,*,#58083,.T.); -#58083 = EDGE_CURVE('',#55770,#58001,#58084,.T.); -#58084 = SURFACE_CURVE('',#58085,(#58089,#58096),.PCURVE_S1.); -#58085 = LINE('',#58086,#58087); -#58086 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); -#58087 = VECTOR('',#58088,1.); -#58088 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58089 = PCURVE('',#42221,#58090); -#58090 = DEFINITIONAL_REPRESENTATION('',(#58091),#58095); -#58091 = LINE('',#58092,#58093); -#58092 = CARTESIAN_POINT('',(0.43,-0.3)); -#58093 = VECTOR('',#58094,1.); -#58094 = DIRECTION('',(-0.623744157346,0.78162857303)); -#58095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58096 = PCURVE('',#55785,#58097); -#58097 = DEFINITIONAL_REPRESENTATION('',(#58098),#58102); -#58098 = LINE('',#58099,#58100); -#58099 = CARTESIAN_POINT('',(0.E+000,2.51)); -#58100 = VECTOR('',#58101,1.); -#58101 = DIRECTION('',(1.,0.E+000)); -#58102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58103 = ADVANCED_FACE('',(#58104),#58018,.T.); -#58104 = FACE_BOUND('',#58105,.T.); -#58105 = EDGE_LOOP('',(#58106,#58152,#58179,#58223)); -#58106 = ORIENTED_EDGE('',*,*,#58107,.F.); -#58107 = EDGE_CURVE('',#58108,#58003,#58110,.T.); -#58108 = VERTEX_POINT('',#58109); -#58109 = CARTESIAN_POINT('',(-0.21,-1.282876752796,2.78)); -#58110 = SURFACE_CURVE('',#58111,(#58116,#58145),.PCURVE_S1.); -#58111 = CIRCLE('',#58112,0.2); -#58112 = AXIS2_PLACEMENT_3D('',#58113,#58114,#58115); -#58113 = CARTESIAN_POINT('',(-0.21,-1.12655103819,2.655251168531)); -#58114 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58115 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58116 = PCURVE('',#58018,#58117); -#58117 = DEFINITIONAL_REPRESENTATION('',(#58118),#58144); -#58118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58119,#58120,#58121,#58122, - #58123,#58124,#58125,#58126,#58127,#58128,#58129,#58130,#58131, - #58132,#58133,#58134,#58135,#58136,#58137,#58138,#58139,#58140, - #58141,#58142,#58143),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60466 = CARTESIAN_POINT('',(0.673523800868,2.51)); +#60467 = CARTESIAN_POINT('',(1.570796326795,2.51)); +#60468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60469 = ORIENTED_EDGE('',*,*,#44597,.T.); +#60470 = ORIENTED_EDGE('',*,*,#60367,.F.); +#60471 = ORIENTED_EDGE('',*,*,#59596,.T.); +#60472 = ORIENTED_EDGE('',*,*,#59090,.T.); +#60473 = ORIENTED_EDGE('',*,*,#58189,.F.); +#60474 = ORIENTED_EDGE('',*,*,#60475,.T.); +#60475 = EDGE_CURVE('',#58162,#60393,#60476,.T.); +#60476 = SURFACE_CURVE('',#60477,(#60481,#60488),.PCURVE_S1.); +#60477 = LINE('',#60478,#60479); +#60478 = CARTESIAN_POINT('',(-1.E-002,-1.225,2.35)); +#60479 = VECTOR('',#60480,1.); +#60480 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60481 = PCURVE('',#44613,#60482); +#60482 = DEFINITIONAL_REPRESENTATION('',(#60483),#60487); +#60483 = LINE('',#60484,#60485); +#60484 = CARTESIAN_POINT('',(0.43,-0.3)); +#60485 = VECTOR('',#60486,1.); +#60486 = DIRECTION('',(-0.623744157346,0.78162857303)); +#60487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60488 = PCURVE('',#58177,#60489); +#60489 = DEFINITIONAL_REPRESENTATION('',(#60490),#60494); +#60490 = LINE('',#60491,#60492); +#60491 = CARTESIAN_POINT('',(0.E+000,2.51)); +#60492 = VECTOR('',#60493,1.); +#60493 = DIRECTION('',(1.,0.E+000)); +#60494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60495 = ADVANCED_FACE('',(#60496),#60410,.T.); +#60496 = FACE_BOUND('',#60497,.T.); +#60497 = EDGE_LOOP('',(#60498,#60544,#60571,#60615)); +#60498 = ORIENTED_EDGE('',*,*,#60499,.F.); +#60499 = EDGE_CURVE('',#60500,#60395,#60502,.T.); +#60500 = VERTEX_POINT('',#60501); +#60501 = CARTESIAN_POINT('',(-0.21,-1.282876752796,2.78)); +#60502 = SURFACE_CURVE('',#60503,(#60508,#60537),.PCURVE_S1.); +#60503 = CIRCLE('',#60504,0.2); +#60504 = AXIS2_PLACEMENT_3D('',#60505,#60506,#60507); +#60505 = CARTESIAN_POINT('',(-0.21,-1.12655103819,2.655251168531)); +#60506 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60507 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60508 = PCURVE('',#60410,#60509); +#60509 = DEFINITIONAL_REPRESENTATION('',(#60510),#60536); +#60510 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60511,#60512,#60513,#60514, + #60515,#60516,#60517,#60518,#60519,#60520,#60521,#60522,#60523, + #60524,#60525,#60526,#60527,#60528,#60529,#60530,#60531,#60532, + #60533,#60534,#60535),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72094,89 +75083,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58119 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); -#58120 = CARTESIAN_POINT('',(2.379994434534E-002,0.316262878957)); -#58121 = CARTESIAN_POINT('',(7.139983303602E-002,0.316262878957)); -#58122 = CARTESIAN_POINT('',(0.142799666072,0.316262878957)); -#58123 = CARTESIAN_POINT('',(0.214199499108,0.316262878957)); -#58124 = CARTESIAN_POINT('',(0.285599332144,0.316262878957)); -#58125 = CARTESIAN_POINT('',(0.35699916518,0.316262878957)); -#58126 = CARTESIAN_POINT('',(0.428398998216,0.316262878957)); -#58127 = CARTESIAN_POINT('',(0.499798831252,0.316262878957)); -#58128 = CARTESIAN_POINT('',(0.571198664288,0.316262878957)); -#58129 = CARTESIAN_POINT('',(0.642598497324,0.316262878957)); -#58130 = CARTESIAN_POINT('',(0.71399833036,0.316262878957)); -#58131 = CARTESIAN_POINT('',(0.785398163396,0.316262878957)); -#58132 = CARTESIAN_POINT('',(0.856797996432,0.316262878957)); -#58133 = CARTESIAN_POINT('',(0.928197829468,0.316262878957)); -#58134 = CARTESIAN_POINT('',(0.999597662505,0.316262878957)); -#58135 = CARTESIAN_POINT('',(1.070997495541,0.316262878957)); -#58136 = CARTESIAN_POINT('',(1.142397328577,0.316262878957)); -#58137 = CARTESIAN_POINT('',(1.213797161613,0.316262878957)); -#58138 = CARTESIAN_POINT('',(1.285196994649,0.316262878957)); -#58139 = CARTESIAN_POINT('',(1.356596827685,0.316262878957)); -#58140 = CARTESIAN_POINT('',(1.427996660721,0.316262878957)); -#58141 = CARTESIAN_POINT('',(1.499396493757,0.316262878957)); -#58142 = CARTESIAN_POINT('',(1.546996382448,0.316262878957)); -#58143 = CARTESIAN_POINT('',(1.570796326793,0.316262878957)); -#58144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58145 = PCURVE('',#58045,#58146); -#58146 = DEFINITIONAL_REPRESENTATION('',(#58147),#58151); -#58147 = CIRCLE('',#58148,0.2); -#58148 = AXIS2_PLACEMENT_2D('',#58149,#58150); -#58149 = CARTESIAN_POINT('',(0.2,2.71)); -#58150 = DIRECTION('',(-1.,0.E+000)); -#58151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58152 = ORIENTED_EDGE('',*,*,#58153,.F.); -#58153 = EDGE_CURVE('',#58154,#58108,#58156,.T.); -#58154 = VERTEX_POINT('',#58155); -#58155 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); -#58156 = SURFACE_CURVE('',#58157,(#58161,#58167),.PCURVE_S1.); -#58157 = LINE('',#58158,#58159); -#58158 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); -#58159 = VECTOR('',#58160,1.); -#58160 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58161 = PCURVE('',#58018,#58162); -#58162 = DEFINITIONAL_REPRESENTATION('',(#58163),#58166); -#58163 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58164,#58165),.UNSPECIFIED., +#60511 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); +#60512 = CARTESIAN_POINT('',(2.379994434534E-002,0.316262878957)); +#60513 = CARTESIAN_POINT('',(7.139983303602E-002,0.316262878957)); +#60514 = CARTESIAN_POINT('',(0.142799666072,0.316262878957)); +#60515 = CARTESIAN_POINT('',(0.214199499108,0.316262878957)); +#60516 = CARTESIAN_POINT('',(0.285599332144,0.316262878957)); +#60517 = CARTESIAN_POINT('',(0.35699916518,0.316262878957)); +#60518 = CARTESIAN_POINT('',(0.428398998216,0.316262878957)); +#60519 = CARTESIAN_POINT('',(0.499798831252,0.316262878957)); +#60520 = CARTESIAN_POINT('',(0.571198664288,0.316262878957)); +#60521 = CARTESIAN_POINT('',(0.642598497324,0.316262878957)); +#60522 = CARTESIAN_POINT('',(0.71399833036,0.316262878957)); +#60523 = CARTESIAN_POINT('',(0.785398163396,0.316262878957)); +#60524 = CARTESIAN_POINT('',(0.856797996432,0.316262878957)); +#60525 = CARTESIAN_POINT('',(0.928197829468,0.316262878957)); +#60526 = CARTESIAN_POINT('',(0.999597662505,0.316262878957)); +#60527 = CARTESIAN_POINT('',(1.070997495541,0.316262878957)); +#60528 = CARTESIAN_POINT('',(1.142397328577,0.316262878957)); +#60529 = CARTESIAN_POINT('',(1.213797161613,0.316262878957)); +#60530 = CARTESIAN_POINT('',(1.285196994649,0.316262878957)); +#60531 = CARTESIAN_POINT('',(1.356596827685,0.316262878957)); +#60532 = CARTESIAN_POINT('',(1.427996660721,0.316262878957)); +#60533 = CARTESIAN_POINT('',(1.499396493757,0.316262878957)); +#60534 = CARTESIAN_POINT('',(1.546996382448,0.316262878957)); +#60535 = CARTESIAN_POINT('',(1.570796326793,0.316262878957)); +#60536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60537 = PCURVE('',#60437,#60538); +#60538 = DEFINITIONAL_REPRESENTATION('',(#60539),#60543); +#60539 = CIRCLE('',#60540,0.2); +#60540 = AXIS2_PLACEMENT_2D('',#60541,#60542); +#60541 = CARTESIAN_POINT('',(0.2,2.71)); +#60542 = DIRECTION('',(-1.,0.E+000)); +#60543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60544 = ORIENTED_EDGE('',*,*,#60545,.F.); +#60545 = EDGE_CURVE('',#60546,#60500,#60548,.T.); +#60546 = VERTEX_POINT('',#60547); +#60547 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); +#60548 = SURFACE_CURVE('',#60549,(#60553,#60559),.PCURVE_S1.); +#60549 = LINE('',#60550,#60551); +#60550 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); +#60551 = VECTOR('',#60552,1.); +#60552 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60553 = PCURVE('',#60410,#60554); +#60554 = DEFINITIONAL_REPRESENTATION('',(#60555),#60558); +#60555 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60556,#60557),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#58164 = CARTESIAN_POINT('',(0.E+000,1.62628789571E-002)); -#58165 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); -#58166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58167 = PCURVE('',#58168,#58173); -#58168 = PLANE('',#58169); -#58169 = AXIS2_PLACEMENT_3D('',#58170,#58171,#58172); -#58170 = CARTESIAN_POINT('',(2.5,-1.47,2.545511428091)); -#58171 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58172 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58173 = DEFINITIONAL_REPRESENTATION('',(#58174),#58178); -#58174 = LINE('',#58175,#58176); -#58175 = CARTESIAN_POINT('',(0.E+000,2.71)); -#58176 = VECTOR('',#58177,1.); -#58177 = DIRECTION('',(1.,0.E+000)); -#58178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58179 = ORIENTED_EDGE('',*,*,#58180,.F.); -#58180 = EDGE_CURVE('',#58001,#58154,#58181,.T.); -#58181 = SURFACE_CURVE('',#58182,(#58187,#58216),.PCURVE_S1.); -#58182 = CIRCLE('',#58183,0.2); -#58183 = AXIS2_PLACEMENT_3D('',#58184,#58185,#58186); -#58184 = CARTESIAN_POINT('',(-0.21,-1.313674285394,2.420762596622)); -#58185 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58186 = DIRECTION('',(1.,0.E+000,0.E+000)); -#58187 = PCURVE('',#58018,#58188); -#58188 = DEFINITIONAL_REPRESENTATION('',(#58189),#58215); -#58189 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58190,#58191,#58192,#58193, - #58194,#58195,#58196,#58197,#58198,#58199,#58200,#58201,#58202, - #58203,#58204,#58205,#58206,#58207,#58208,#58209,#58210,#58211, - #58212,#58213,#58214),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60556 = CARTESIAN_POINT('',(0.E+000,1.62628789571E-002)); +#60557 = CARTESIAN_POINT('',(0.E+000,0.316262878957)); +#60558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60559 = PCURVE('',#60560,#60565); +#60560 = PLANE('',#60561); +#60561 = AXIS2_PLACEMENT_3D('',#60562,#60563,#60564); +#60562 = CARTESIAN_POINT('',(2.5,-1.47,2.545511428091)); +#60563 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60564 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60565 = DEFINITIONAL_REPRESENTATION('',(#60566),#60570); +#60566 = LINE('',#60567,#60568); +#60567 = CARTESIAN_POINT('',(0.E+000,2.71)); +#60568 = VECTOR('',#60569,1.); +#60569 = DIRECTION('',(1.,0.E+000)); +#60570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60571 = ORIENTED_EDGE('',*,*,#60572,.F.); +#60572 = EDGE_CURVE('',#60393,#60546,#60573,.T.); +#60573 = SURFACE_CURVE('',#60574,(#60579,#60608),.PCURVE_S1.); +#60574 = CIRCLE('',#60575,0.2); +#60575 = AXIS2_PLACEMENT_3D('',#60576,#60577,#60578); +#60576 = CARTESIAN_POINT('',(-0.21,-1.313674285394,2.420762596622)); +#60577 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#60578 = DIRECTION('',(1.,0.E+000,0.E+000)); +#60579 = PCURVE('',#60410,#60580); +#60580 = DEFINITIONAL_REPRESENTATION('',(#60581),#60607); +#60581 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60582,#60583,#60584,#60585, + #60586,#60587,#60588,#60589,#60590,#60591,#60592,#60593,#60594, + #60595,#60596,#60597,#60598,#60599,#60600,#60601,#60602,#60603, + #60604,#60605,#60606),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72184,84 +75173,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58190 = CARTESIAN_POINT('',(1.570796326793,1.626287895734E-002)); -#58191 = CARTESIAN_POINT('',(1.546996382448,1.626287895734E-002)); -#58192 = CARTESIAN_POINT('',(1.499396493757,1.626287895734E-002)); -#58193 = CARTESIAN_POINT('',(1.427996660721,1.626287895734E-002)); -#58194 = CARTESIAN_POINT('',(1.356596827685,1.626287895734E-002)); -#58195 = CARTESIAN_POINT('',(1.285196994649,1.626287895734E-002)); -#58196 = CARTESIAN_POINT('',(1.213797161613,1.626287895734E-002)); -#58197 = CARTESIAN_POINT('',(1.142397328577,1.626287895734E-002)); -#58198 = CARTESIAN_POINT('',(1.07099749554,1.626287895734E-002)); -#58199 = CARTESIAN_POINT('',(0.999597662504,1.626287895734E-002)); -#58200 = CARTESIAN_POINT('',(0.928197829468,1.626287895734E-002)); -#58201 = CARTESIAN_POINT('',(0.856797996432,1.626287895734E-002)); -#58202 = CARTESIAN_POINT('',(0.785398163396,1.626287895734E-002)); -#58203 = CARTESIAN_POINT('',(0.71399833036,1.626287895734E-002)); -#58204 = CARTESIAN_POINT('',(0.642598497324,1.626287895734E-002)); -#58205 = CARTESIAN_POINT('',(0.571198664288,1.626287895734E-002)); -#58206 = CARTESIAN_POINT('',(0.499798831252,1.626287895734E-002)); -#58207 = CARTESIAN_POINT('',(0.428398998216,1.626287895734E-002)); -#58208 = CARTESIAN_POINT('',(0.35699916518,1.626287895734E-002)); -#58209 = CARTESIAN_POINT('',(0.285599332144,1.626287895734E-002)); -#58210 = CARTESIAN_POINT('',(0.214199499108,1.626287895734E-002)); -#58211 = CARTESIAN_POINT('',(0.142799666072,1.626287895734E-002)); -#58212 = CARTESIAN_POINT('',(7.139983303601E-002,1.626287895734E-002)); -#58213 = CARTESIAN_POINT('',(2.379994434534E-002,1.626287895734E-002)); -#58214 = CARTESIAN_POINT('',(0.E+000,1.626287895734E-002)); -#58215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58216 = PCURVE('',#55785,#58217); -#58217 = DEFINITIONAL_REPRESENTATION('',(#58218),#58222); -#58218 = CIRCLE('',#58219,0.2); -#58219 = AXIS2_PLACEMENT_2D('',#58220,#58221); -#58220 = CARTESIAN_POINT('',(0.113448111359,2.71)); -#58221 = DIRECTION('',(0.E+000,-1.)); -#58222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58223 = ORIENTED_EDGE('',*,*,#58000,.T.); -#58224 = ADVANCED_FACE('',(#58225),#58240,.T.); -#58225 = FACE_BOUND('',#58226,.F.); -#58226 = EDGE_LOOP('',(#58227,#58285,#58313,#58364,#58387,#58409)); -#58227 = ORIENTED_EDGE('',*,*,#58228,.F.); -#58228 = EDGE_CURVE('',#58229,#58231,#58233,.T.); -#58229 = VERTEX_POINT('',#58230); -#58230 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); -#58231 = VERTEX_POINT('',#58232); -#58232 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); -#58233 = SURFACE_CURVE('',#58234,(#58239,#58251),.PCURVE_S1.); -#58234 = CIRCLE('',#58235,0.2); -#58235 = AXIS2_PLACEMENT_3D('',#58236,#58237,#58238); -#58236 = CARTESIAN_POINT('',(2.3,-1.12655103819,2.655251168531)); -#58237 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58238 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58239 = PCURVE('',#58240,#58245); -#58240 = PLANE('',#58241); -#58241 = AXIS2_PLACEMENT_3D('',#58242,#58243,#58244); -#58242 = CARTESIAN_POINT('',(2.5,-1.282876752796,2.78)); -#58243 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58244 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); -#58245 = DEFINITIONAL_REPRESENTATION('',(#58246),#58250); -#58246 = CIRCLE('',#58247,0.2); -#58247 = AXIS2_PLACEMENT_2D('',#58248,#58249); -#58248 = CARTESIAN_POINT('',(0.2,0.2)); -#58249 = DIRECTION('',(-1.,0.E+000)); -#58250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58251 = PCURVE('',#58252,#58257); -#58252 = CYLINDRICAL_SURFACE('',#58253,0.2); -#58253 = AXIS2_PLACEMENT_3D('',#58254,#58255,#58256); -#58254 = CARTESIAN_POINT('',(2.3,-1.112804092841,2.672477791258)); -#58255 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58256 = DIRECTION('',(1.,0.E+000,0.E+000)); -#58257 = DEFINITIONAL_REPRESENTATION('',(#58258),#58284); -#58258 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58259,#58260,#58261,#58262, - #58263,#58264,#58265,#58266,#58267,#58268,#58269,#58270,#58271, - #58272,#58273,#58274,#58275,#58276,#58277,#58278,#58279,#58280, - #58281,#58282,#58283),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60582 = CARTESIAN_POINT('',(1.570796326793,1.626287895734E-002)); +#60583 = CARTESIAN_POINT('',(1.546996382448,1.626287895734E-002)); +#60584 = CARTESIAN_POINT('',(1.499396493757,1.626287895734E-002)); +#60585 = CARTESIAN_POINT('',(1.427996660721,1.626287895734E-002)); +#60586 = CARTESIAN_POINT('',(1.356596827685,1.626287895734E-002)); +#60587 = CARTESIAN_POINT('',(1.285196994649,1.626287895734E-002)); +#60588 = CARTESIAN_POINT('',(1.213797161613,1.626287895734E-002)); +#60589 = CARTESIAN_POINT('',(1.142397328577,1.626287895734E-002)); +#60590 = CARTESIAN_POINT('',(1.07099749554,1.626287895734E-002)); +#60591 = CARTESIAN_POINT('',(0.999597662504,1.626287895734E-002)); +#60592 = CARTESIAN_POINT('',(0.928197829468,1.626287895734E-002)); +#60593 = CARTESIAN_POINT('',(0.856797996432,1.626287895734E-002)); +#60594 = CARTESIAN_POINT('',(0.785398163396,1.626287895734E-002)); +#60595 = CARTESIAN_POINT('',(0.71399833036,1.626287895734E-002)); +#60596 = CARTESIAN_POINT('',(0.642598497324,1.626287895734E-002)); +#60597 = CARTESIAN_POINT('',(0.571198664288,1.626287895734E-002)); +#60598 = CARTESIAN_POINT('',(0.499798831252,1.626287895734E-002)); +#60599 = CARTESIAN_POINT('',(0.428398998216,1.626287895734E-002)); +#60600 = CARTESIAN_POINT('',(0.35699916518,1.626287895734E-002)); +#60601 = CARTESIAN_POINT('',(0.285599332144,1.626287895734E-002)); +#60602 = CARTESIAN_POINT('',(0.214199499108,1.626287895734E-002)); +#60603 = CARTESIAN_POINT('',(0.142799666072,1.626287895734E-002)); +#60604 = CARTESIAN_POINT('',(7.139983303601E-002,1.626287895734E-002)); +#60605 = CARTESIAN_POINT('',(2.379994434534E-002,1.626287895734E-002)); +#60606 = CARTESIAN_POINT('',(0.E+000,1.626287895734E-002)); +#60607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60608 = PCURVE('',#58177,#60609); +#60609 = DEFINITIONAL_REPRESENTATION('',(#60610),#60614); +#60610 = CIRCLE('',#60611,0.2); +#60611 = AXIS2_PLACEMENT_2D('',#60612,#60613); +#60612 = CARTESIAN_POINT('',(0.113448111359,2.71)); +#60613 = DIRECTION('',(0.E+000,-1.)); +#60614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60615 = ORIENTED_EDGE('',*,*,#60392,.T.); +#60616 = ADVANCED_FACE('',(#60617),#60632,.T.); +#60617 = FACE_BOUND('',#60618,.F.); +#60618 = EDGE_LOOP('',(#60619,#60677,#60705,#60756,#60779,#60801)); +#60619 = ORIENTED_EDGE('',*,*,#60620,.F.); +#60620 = EDGE_CURVE('',#60621,#60623,#60625,.T.); +#60621 = VERTEX_POINT('',#60622); +#60622 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); +#60623 = VERTEX_POINT('',#60624); +#60624 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); +#60625 = SURFACE_CURVE('',#60626,(#60631,#60643),.PCURVE_S1.); +#60626 = CIRCLE('',#60627,0.2); +#60627 = AXIS2_PLACEMENT_3D('',#60628,#60629,#60630); +#60628 = CARTESIAN_POINT('',(2.3,-1.12655103819,2.655251168531)); +#60629 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60630 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60631 = PCURVE('',#60632,#60637); +#60632 = PLANE('',#60633); +#60633 = AXIS2_PLACEMENT_3D('',#60634,#60635,#60636); +#60634 = CARTESIAN_POINT('',(2.5,-1.282876752796,2.78)); +#60635 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60636 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); +#60637 = DEFINITIONAL_REPRESENTATION('',(#60638),#60642); +#60638 = CIRCLE('',#60639,0.2); +#60639 = AXIS2_PLACEMENT_2D('',#60640,#60641); +#60640 = CARTESIAN_POINT('',(0.2,0.2)); +#60641 = DIRECTION('',(-1.,0.E+000)); +#60642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60643 = PCURVE('',#60644,#60649); +#60644 = CYLINDRICAL_SURFACE('',#60645,0.2); +#60645 = AXIS2_PLACEMENT_3D('',#60646,#60647,#60648); +#60646 = CARTESIAN_POINT('',(2.3,-1.112804092841,2.672477791258)); +#60647 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#60648 = DIRECTION('',(1.,0.E+000,0.E+000)); +#60649 = DEFINITIONAL_REPRESENTATION('',(#60650),#60676); +#60650 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60651,#60652,#60653,#60654, + #60655,#60656,#60657,#60658,#60659,#60660,#60661,#60662,#60663, + #60664,#60665,#60666,#60667,#60668,#60669,#60670,#60671,#60672, + #60673,#60674,#60675),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72269,96 +75258,96 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58259 = CARTESIAN_POINT('',(1.570796326795,2.203939738302E-002)); -#58260 = CARTESIAN_POINT('',(1.54699638245,2.203939738302E-002)); -#58261 = CARTESIAN_POINT('',(1.499396493759,2.203939738302E-002)); -#58262 = CARTESIAN_POINT('',(1.427996660723,2.203939738302E-002)); -#58263 = CARTESIAN_POINT('',(1.356596827686,2.203939738302E-002)); -#58264 = CARTESIAN_POINT('',(1.28519699465,2.203939738302E-002)); -#58265 = CARTESIAN_POINT('',(1.213797161614,2.203939738302E-002)); -#58266 = CARTESIAN_POINT('',(1.142397328578,2.203939738302E-002)); -#58267 = CARTESIAN_POINT('',(1.070997495542,2.203939738302E-002)); -#58268 = CARTESIAN_POINT('',(0.999597662506,2.203939738302E-002)); -#58269 = CARTESIAN_POINT('',(0.928197829469,2.203939738302E-002)); -#58270 = CARTESIAN_POINT('',(0.856797996433,2.203939738302E-002)); -#58271 = CARTESIAN_POINT('',(0.785398163397,2.203939738302E-002)); -#58272 = CARTESIAN_POINT('',(0.713998330361,2.203939738302E-002)); -#58273 = CARTESIAN_POINT('',(0.642598497325,2.203939738302E-002)); -#58274 = CARTESIAN_POINT('',(0.571198664289,2.203939738302E-002)); -#58275 = CARTESIAN_POINT('',(0.499798831252,2.203939738302E-002)); -#58276 = CARTESIAN_POINT('',(0.428398998216,2.203939738302E-002)); -#58277 = CARTESIAN_POINT('',(0.35699916518,2.203939738302E-002)); -#58278 = CARTESIAN_POINT('',(0.285599332144,2.203939738302E-002)); -#58279 = CARTESIAN_POINT('',(0.214199499108,2.203939738302E-002)); -#58280 = CARTESIAN_POINT('',(0.142799666072,2.203939738302E-002)); -#58281 = CARTESIAN_POINT('',(7.139983303543E-002,2.203939738302E-002)); -#58282 = CARTESIAN_POINT('',(2.379994434502E-002,2.203939738302E-002)); -#58283 = CARTESIAN_POINT('',(0.E+000,2.203939738302E-002)); -#58284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58285 = ORIENTED_EDGE('',*,*,#58286,.T.); -#58286 = EDGE_CURVE('',#58229,#58287,#58289,.T.); -#58287 = VERTEX_POINT('',#58288); -#58288 = CARTESIAN_POINT('',(0.21,-1.282876752796,2.78)); -#58289 = SURFACE_CURVE('',#58290,(#58294,#58301),.PCURVE_S1.); -#58290 = LINE('',#58291,#58292); -#58291 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); -#58292 = VECTOR('',#58293,1.); -#58293 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58294 = PCURVE('',#58240,#58295); -#58295 = DEFINITIONAL_REPRESENTATION('',(#58296),#58300); -#58296 = LINE('',#58297,#58298); -#58297 = CARTESIAN_POINT('',(0.E+000,0.2)); -#58298 = VECTOR('',#58299,1.); -#58299 = DIRECTION('',(0.E+000,1.)); -#58300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58301 = PCURVE('',#58302,#58307); -#58302 = PLANE('',#58303); -#58303 = AXIS2_PLACEMENT_3D('',#58304,#58305,#58306); -#58304 = CARTESIAN_POINT('',(2.5,-1.47,2.545511428091)); -#58305 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58306 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58307 = DEFINITIONAL_REPRESENTATION('',(#58308),#58312); -#58308 = LINE('',#58309,#58310); -#58309 = CARTESIAN_POINT('',(0.3,0.2)); -#58310 = VECTOR('',#58311,1.); -#58311 = DIRECTION('',(0.E+000,1.)); -#58312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58313 = ORIENTED_EDGE('',*,*,#58314,.F.); -#58314 = EDGE_CURVE('',#58315,#58287,#58317,.T.); -#58315 = VERTEX_POINT('',#58316); -#58316 = CARTESIAN_POINT('',(1.E-002,-1.12655103819,2.655251168531)); -#58317 = SURFACE_CURVE('',#58318,(#58323,#58330),.PCURVE_S1.); -#58318 = CIRCLE('',#58319,0.2); -#58319 = AXIS2_PLACEMENT_3D('',#58320,#58321,#58322); -#58320 = CARTESIAN_POINT('',(0.21,-1.12655103819,2.655251168531)); -#58321 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58322 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58323 = PCURVE('',#58240,#58324); -#58324 = DEFINITIONAL_REPRESENTATION('',(#58325),#58329); -#58325 = CIRCLE('',#58326,0.2); -#58326 = AXIS2_PLACEMENT_2D('',#58327,#58328); -#58327 = CARTESIAN_POINT('',(0.2,2.29)); -#58328 = DIRECTION('',(0.E+000,1.)); -#58329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58330 = PCURVE('',#58331,#58336); -#58331 = CYLINDRICAL_SURFACE('',#58332,0.2); -#58332 = AXIS2_PLACEMENT_3D('',#58333,#58334,#58335); -#58333 = CARTESIAN_POINT('',(0.21,-1.117246192085,2.666911291512)); -#58334 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58335 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58336 = DEFINITIONAL_REPRESENTATION('',(#58337),#58363); -#58337 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58338,#58339,#58340,#58341, - #58342,#58343,#58344,#58345,#58346,#58347,#58348,#58349,#58350, - #58351,#58352,#58353,#58354,#58355,#58356,#58357,#58358,#58359, - #58360,#58361,#58362),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60651 = CARTESIAN_POINT('',(1.570796326795,2.203939738302E-002)); +#60652 = CARTESIAN_POINT('',(1.54699638245,2.203939738302E-002)); +#60653 = CARTESIAN_POINT('',(1.499396493759,2.203939738302E-002)); +#60654 = CARTESIAN_POINT('',(1.427996660723,2.203939738302E-002)); +#60655 = CARTESIAN_POINT('',(1.356596827686,2.203939738302E-002)); +#60656 = CARTESIAN_POINT('',(1.28519699465,2.203939738302E-002)); +#60657 = CARTESIAN_POINT('',(1.213797161614,2.203939738302E-002)); +#60658 = CARTESIAN_POINT('',(1.142397328578,2.203939738302E-002)); +#60659 = CARTESIAN_POINT('',(1.070997495542,2.203939738302E-002)); +#60660 = CARTESIAN_POINT('',(0.999597662506,2.203939738302E-002)); +#60661 = CARTESIAN_POINT('',(0.928197829469,2.203939738302E-002)); +#60662 = CARTESIAN_POINT('',(0.856797996433,2.203939738302E-002)); +#60663 = CARTESIAN_POINT('',(0.785398163397,2.203939738302E-002)); +#60664 = CARTESIAN_POINT('',(0.713998330361,2.203939738302E-002)); +#60665 = CARTESIAN_POINT('',(0.642598497325,2.203939738302E-002)); +#60666 = CARTESIAN_POINT('',(0.571198664289,2.203939738302E-002)); +#60667 = CARTESIAN_POINT('',(0.499798831252,2.203939738302E-002)); +#60668 = CARTESIAN_POINT('',(0.428398998216,2.203939738302E-002)); +#60669 = CARTESIAN_POINT('',(0.35699916518,2.203939738302E-002)); +#60670 = CARTESIAN_POINT('',(0.285599332144,2.203939738302E-002)); +#60671 = CARTESIAN_POINT('',(0.214199499108,2.203939738302E-002)); +#60672 = CARTESIAN_POINT('',(0.142799666072,2.203939738302E-002)); +#60673 = CARTESIAN_POINT('',(7.139983303543E-002,2.203939738302E-002)); +#60674 = CARTESIAN_POINT('',(2.379994434502E-002,2.203939738302E-002)); +#60675 = CARTESIAN_POINT('',(0.E+000,2.203939738302E-002)); +#60676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60677 = ORIENTED_EDGE('',*,*,#60678,.T.); +#60678 = EDGE_CURVE('',#60621,#60679,#60681,.T.); +#60679 = VERTEX_POINT('',#60680); +#60680 = CARTESIAN_POINT('',(0.21,-1.282876752796,2.78)); +#60681 = SURFACE_CURVE('',#60682,(#60686,#60693),.PCURVE_S1.); +#60682 = LINE('',#60683,#60684); +#60683 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); +#60684 = VECTOR('',#60685,1.); +#60685 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60686 = PCURVE('',#60632,#60687); +#60687 = DEFINITIONAL_REPRESENTATION('',(#60688),#60692); +#60688 = LINE('',#60689,#60690); +#60689 = CARTESIAN_POINT('',(0.E+000,0.2)); +#60690 = VECTOR('',#60691,1.); +#60691 = DIRECTION('',(0.E+000,1.)); +#60692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60693 = PCURVE('',#60694,#60699); +#60694 = PLANE('',#60695); +#60695 = AXIS2_PLACEMENT_3D('',#60696,#60697,#60698); +#60696 = CARTESIAN_POINT('',(2.5,-1.47,2.545511428091)); +#60697 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60698 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60699 = DEFINITIONAL_REPRESENTATION('',(#60700),#60704); +#60700 = LINE('',#60701,#60702); +#60701 = CARTESIAN_POINT('',(0.3,0.2)); +#60702 = VECTOR('',#60703,1.); +#60703 = DIRECTION('',(0.E+000,1.)); +#60704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60705 = ORIENTED_EDGE('',*,*,#60706,.F.); +#60706 = EDGE_CURVE('',#60707,#60679,#60709,.T.); +#60707 = VERTEX_POINT('',#60708); +#60708 = CARTESIAN_POINT('',(1.E-002,-1.12655103819,2.655251168531)); +#60709 = SURFACE_CURVE('',#60710,(#60715,#60722),.PCURVE_S1.); +#60710 = CIRCLE('',#60711,0.2); +#60711 = AXIS2_PLACEMENT_3D('',#60712,#60713,#60714); +#60712 = CARTESIAN_POINT('',(0.21,-1.12655103819,2.655251168531)); +#60713 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60714 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60715 = PCURVE('',#60632,#60716); +#60716 = DEFINITIONAL_REPRESENTATION('',(#60717),#60721); +#60717 = CIRCLE('',#60718,0.2); +#60718 = AXIS2_PLACEMENT_2D('',#60719,#60720); +#60719 = CARTESIAN_POINT('',(0.2,2.29)); +#60720 = DIRECTION('',(0.E+000,1.)); +#60721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60722 = PCURVE('',#60723,#60728); +#60723 = CYLINDRICAL_SURFACE('',#60724,0.2); +#60724 = AXIS2_PLACEMENT_3D('',#60725,#60726,#60727); +#60725 = CARTESIAN_POINT('',(0.21,-1.117246192085,2.666911291512)); +#60726 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#60727 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60728 = DEFINITIONAL_REPRESENTATION('',(#60729),#60755); +#60729 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60730,#60731,#60732,#60733, + #60734,#60735,#60736,#60737,#60738,#60739,#60740,#60741,#60742, + #60743,#60744,#60745,#60746,#60747,#60748,#60749,#60750,#60751, + #60752,#60753,#60754),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72366,174 +75355,174 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58338 = CARTESIAN_POINT('',(1.570796326795,1.491772867999E-002)); -#58339 = CARTESIAN_POINT('',(1.54699638245,1.491772867999E-002)); -#58340 = CARTESIAN_POINT('',(1.499396493759,1.491772867999E-002)); -#58341 = CARTESIAN_POINT('',(1.427996660723,1.491772867999E-002)); -#58342 = CARTESIAN_POINT('',(1.356596827687,1.491772867999E-002)); -#58343 = CARTESIAN_POINT('',(1.28519699465,1.491772867999E-002)); -#58344 = CARTESIAN_POINT('',(1.213797161614,1.491772867999E-002)); -#58345 = CARTESIAN_POINT('',(1.142397328578,1.491772867999E-002)); -#58346 = CARTESIAN_POINT('',(1.070997495542,1.491772867999E-002)); -#58347 = CARTESIAN_POINT('',(0.999597662506,1.491772867999E-002)); -#58348 = CARTESIAN_POINT('',(0.92819782947,1.491772867999E-002)); -#58349 = CARTESIAN_POINT('',(0.856797996434,1.491772867999E-002)); -#58350 = CARTESIAN_POINT('',(0.785398163398,1.491772867999E-002)); -#58351 = CARTESIAN_POINT('',(0.713998330361,1.491772867999E-002)); -#58352 = CARTESIAN_POINT('',(0.642598497325,1.491772867999E-002)); -#58353 = CARTESIAN_POINT('',(0.571198664289,1.491772867999E-002)); -#58354 = CARTESIAN_POINT('',(0.499798831253,1.491772867999E-002)); -#58355 = CARTESIAN_POINT('',(0.428398998217,1.491772867999E-002)); -#58356 = CARTESIAN_POINT('',(0.356999165181,1.491772867999E-002)); -#58357 = CARTESIAN_POINT('',(0.285599332145,1.491772867999E-002)); -#58358 = CARTESIAN_POINT('',(0.214199499108,1.491772867999E-002)); -#58359 = CARTESIAN_POINT('',(0.142799666072,1.491772867999E-002)); -#58360 = CARTESIAN_POINT('',(7.139983303614E-002,1.491772867999E-002)); -#58361 = CARTESIAN_POINT('',(2.379994434538E-002,1.491772867999E-002)); -#58362 = CARTESIAN_POINT('',(0.E+000,1.491772867999E-002)); -#58363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58364 = ORIENTED_EDGE('',*,*,#58365,.F.); -#58365 = EDGE_CURVE('',#58366,#58315,#58368,.T.); -#58366 = VERTEX_POINT('',#58367); -#58367 = CARTESIAN_POINT('',(1.E-002,-1.03411419437,2.581486028353)); -#58368 = SURFACE_CURVE('',#58369,(#58373,#58380),.PCURVE_S1.); -#58369 = LINE('',#58370,#58371); -#58370 = CARTESIAN_POINT('',(1.E-002,-1.03411419437,2.581486028353)); -#58371 = VECTOR('',#58372,1.); -#58372 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58373 = PCURVE('',#58240,#58374); -#58374 = DEFINITIONAL_REPRESENTATION('',(#58375),#58379); -#58375 = LINE('',#58376,#58377); -#58376 = CARTESIAN_POINT('',(0.318261853532,2.49)); -#58377 = VECTOR('',#58378,1.); -#58378 = DIRECTION('',(-1.,0.E+000)); -#58379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58380 = PCURVE('',#41511,#58381); -#58381 = DEFINITIONAL_REPRESENTATION('',(#58382),#58386); -#58382 = LINE('',#58383,#58384); -#58383 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); -#58384 = VECTOR('',#58385,1.); -#58385 = DIRECTION('',(0.623744157346,0.78162857303)); -#58386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58387 = ORIENTED_EDGE('',*,*,#58388,.F.); -#58388 = EDGE_CURVE('',#58389,#58366,#58391,.T.); -#58389 = VERTEX_POINT('',#58390); -#58390 = CARTESIAN_POINT('',(2.5,-1.03411419437,2.581486028353)); -#58391 = SURFACE_CURVE('',#58392,(#58396,#58403),.PCURVE_S1.); -#58392 = LINE('',#58393,#58394); -#58393 = CARTESIAN_POINT('',(2.5,-1.03411419437,2.581486028353)); -#58394 = VECTOR('',#58395,1.); -#58395 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58396 = PCURVE('',#58240,#58397); -#58397 = DEFINITIONAL_REPRESENTATION('',(#58398),#58402); -#58398 = LINE('',#58399,#58400); -#58399 = CARTESIAN_POINT('',(0.318261853532,0.E+000)); -#58400 = VECTOR('',#58401,1.); -#58401 = DIRECTION('',(0.E+000,1.)); -#58402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58403 = PCURVE('',#41484,#58404); -#58404 = DEFINITIONAL_REPRESENTATION('',(#58405),#58408); -#58405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58406,#58407),.UNSPECIFIED., +#60730 = CARTESIAN_POINT('',(1.570796326795,1.491772867999E-002)); +#60731 = CARTESIAN_POINT('',(1.54699638245,1.491772867999E-002)); +#60732 = CARTESIAN_POINT('',(1.499396493759,1.491772867999E-002)); +#60733 = CARTESIAN_POINT('',(1.427996660723,1.491772867999E-002)); +#60734 = CARTESIAN_POINT('',(1.356596827687,1.491772867999E-002)); +#60735 = CARTESIAN_POINT('',(1.28519699465,1.491772867999E-002)); +#60736 = CARTESIAN_POINT('',(1.213797161614,1.491772867999E-002)); +#60737 = CARTESIAN_POINT('',(1.142397328578,1.491772867999E-002)); +#60738 = CARTESIAN_POINT('',(1.070997495542,1.491772867999E-002)); +#60739 = CARTESIAN_POINT('',(0.999597662506,1.491772867999E-002)); +#60740 = CARTESIAN_POINT('',(0.92819782947,1.491772867999E-002)); +#60741 = CARTESIAN_POINT('',(0.856797996434,1.491772867999E-002)); +#60742 = CARTESIAN_POINT('',(0.785398163398,1.491772867999E-002)); +#60743 = CARTESIAN_POINT('',(0.713998330361,1.491772867999E-002)); +#60744 = CARTESIAN_POINT('',(0.642598497325,1.491772867999E-002)); +#60745 = CARTESIAN_POINT('',(0.571198664289,1.491772867999E-002)); +#60746 = CARTESIAN_POINT('',(0.499798831253,1.491772867999E-002)); +#60747 = CARTESIAN_POINT('',(0.428398998217,1.491772867999E-002)); +#60748 = CARTESIAN_POINT('',(0.356999165181,1.491772867999E-002)); +#60749 = CARTESIAN_POINT('',(0.285599332145,1.491772867999E-002)); +#60750 = CARTESIAN_POINT('',(0.214199499108,1.491772867999E-002)); +#60751 = CARTESIAN_POINT('',(0.142799666072,1.491772867999E-002)); +#60752 = CARTESIAN_POINT('',(7.139983303614E-002,1.491772867999E-002)); +#60753 = CARTESIAN_POINT('',(2.379994434538E-002,1.491772867999E-002)); +#60754 = CARTESIAN_POINT('',(0.E+000,1.491772867999E-002)); +#60755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60756 = ORIENTED_EDGE('',*,*,#60757,.F.); +#60757 = EDGE_CURVE('',#60758,#60707,#60760,.T.); +#60758 = VERTEX_POINT('',#60759); +#60759 = CARTESIAN_POINT('',(1.E-002,-1.03411419437,2.581486028353)); +#60760 = SURFACE_CURVE('',#60761,(#60765,#60772),.PCURVE_S1.); +#60761 = LINE('',#60762,#60763); +#60762 = CARTESIAN_POINT('',(1.E-002,-1.03411419437,2.581486028353)); +#60763 = VECTOR('',#60764,1.); +#60764 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#60765 = PCURVE('',#60632,#60766); +#60766 = DEFINITIONAL_REPRESENTATION('',(#60767),#60771); +#60767 = LINE('',#60768,#60769); +#60768 = CARTESIAN_POINT('',(0.318261853532,2.49)); +#60769 = VECTOR('',#60770,1.); +#60770 = DIRECTION('',(-1.,0.E+000)); +#60771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60772 = PCURVE('',#43903,#60773); +#60773 = DEFINITIONAL_REPRESENTATION('',(#60774),#60778); +#60774 = LINE('',#60775,#60776); +#60775 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); +#60776 = VECTOR('',#60777,1.); +#60777 = DIRECTION('',(0.623744157346,0.78162857303)); +#60778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60779 = ORIENTED_EDGE('',*,*,#60780,.F.); +#60780 = EDGE_CURVE('',#60781,#60758,#60783,.T.); +#60781 = VERTEX_POINT('',#60782); +#60782 = CARTESIAN_POINT('',(2.5,-1.03411419437,2.581486028353)); +#60783 = SURFACE_CURVE('',#60784,(#60788,#60795),.PCURVE_S1.); +#60784 = LINE('',#60785,#60786); +#60785 = CARTESIAN_POINT('',(2.5,-1.03411419437,2.581486028353)); +#60786 = VECTOR('',#60787,1.); +#60787 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60788 = PCURVE('',#60632,#60789); +#60789 = DEFINITIONAL_REPRESENTATION('',(#60790),#60794); +#60790 = LINE('',#60791,#60792); +#60791 = CARTESIAN_POINT('',(0.318261853532,0.E+000)); +#60792 = VECTOR('',#60793,1.); +#60793 = DIRECTION('',(0.E+000,1.)); +#60794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60795 = PCURVE('',#43876,#60796); +#60796 = DEFINITIONAL_REPRESENTATION('',(#60797),#60800); +#60797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60798,#60799),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.49),.PIECEWISE_BEZIER_KNOTS.); -#58406 = CARTESIAN_POINT('',(0.673523800866,0.E+000)); -#58407 = CARTESIAN_POINT('',(0.673523800866,2.49)); -#58408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58409 = ORIENTED_EDGE('',*,*,#58410,.F.); -#58410 = EDGE_CURVE('',#58231,#58389,#58411,.T.); -#58411 = SURFACE_CURVE('',#58412,(#58416,#58423),.PCURVE_S1.); -#58412 = LINE('',#58413,#58414); -#58413 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); -#58414 = VECTOR('',#58415,1.); -#58415 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); -#58416 = PCURVE('',#58240,#58417); -#58417 = DEFINITIONAL_REPRESENTATION('',(#58418),#58422); -#58418 = LINE('',#58419,#58420); -#58419 = CARTESIAN_POINT('',(0.2,0.E+000)); -#58420 = VECTOR('',#58421,1.); -#58421 = DIRECTION('',(1.,0.E+000)); -#58422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58423 = PCURVE('',#38175,#58424); -#58424 = DEFINITIONAL_REPRESENTATION('',(#58425),#58429); -#58425 = LINE('',#58426,#58427); -#58426 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); -#58427 = VECTOR('',#58428,1.); -#58428 = DIRECTION('',(-0.623744157346,0.78162857303)); -#58429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58430 = ADVANCED_FACE('',(#58431),#58045,.T.); -#58431 = FACE_BOUND('',#58432,.F.); -#58432 = EDGE_LOOP('',(#58433,#58434,#58457,#58508,#58531,#58551)); -#58433 = ORIENTED_EDGE('',*,*,#58107,.F.); -#58434 = ORIENTED_EDGE('',*,*,#58435,.T.); -#58435 = EDGE_CURVE('',#58108,#58436,#58438,.T.); -#58436 = VERTEX_POINT('',#58437); -#58437 = CARTESIAN_POINT('',(-2.3,-1.282876752796,2.78)); -#58438 = SURFACE_CURVE('',#58439,(#58443,#58450),.PCURVE_S1.); -#58439 = LINE('',#58440,#58441); -#58440 = CARTESIAN_POINT('',(-0.21,-1.282876752796,2.78)); -#58441 = VECTOR('',#58442,1.); -#58442 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58443 = PCURVE('',#58045,#58444); -#58444 = DEFINITIONAL_REPRESENTATION('',(#58445),#58449); -#58445 = LINE('',#58446,#58447); -#58446 = CARTESIAN_POINT('',(0.E+000,2.71)); -#58447 = VECTOR('',#58448,1.); -#58448 = DIRECTION('',(0.E+000,1.)); -#58449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58450 = PCURVE('',#58168,#58451); -#58451 = DEFINITIONAL_REPRESENTATION('',(#58452),#58456); -#58452 = LINE('',#58453,#58454); -#58453 = CARTESIAN_POINT('',(0.3,2.71)); -#58454 = VECTOR('',#58455,1.); -#58455 = DIRECTION('',(0.E+000,1.)); -#58456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58457 = ORIENTED_EDGE('',*,*,#58458,.F.); -#58458 = EDGE_CURVE('',#58459,#58436,#58461,.T.); -#58459 = VERTEX_POINT('',#58460); -#58460 = CARTESIAN_POINT('',(-2.5,-1.12655103819,2.655251168531)); -#58461 = SURFACE_CURVE('',#58462,(#58467,#58474),.PCURVE_S1.); -#58462 = CIRCLE('',#58463,0.2); -#58463 = AXIS2_PLACEMENT_3D('',#58464,#58465,#58466); -#58464 = CARTESIAN_POINT('',(-2.3,-1.12655103819,2.655251168531)); -#58465 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58466 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58467 = PCURVE('',#58045,#58468); -#58468 = DEFINITIONAL_REPRESENTATION('',(#58469),#58473); -#58469 = CIRCLE('',#58470,0.2); -#58470 = AXIS2_PLACEMENT_2D('',#58471,#58472); -#58471 = CARTESIAN_POINT('',(0.2,4.8)); -#58472 = DIRECTION('',(0.E+000,1.)); -#58473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58474 = PCURVE('',#58475,#58480); -#58475 = CYLINDRICAL_SURFACE('',#58476,0.2); -#58476 = AXIS2_PLACEMENT_3D('',#58477,#58478,#58479); -#58477 = CARTESIAN_POINT('',(-2.3,-1.323351446176,2.408635917304)); -#58478 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58479 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58480 = DEFINITIONAL_REPRESENTATION('',(#58481),#58507); -#58481 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58482,#58483,#58484,#58485, - #58486,#58487,#58488,#58489,#58490,#58491,#58492,#58493,#58494, - #58495,#58496,#58497,#58498,#58499,#58500,#58501,#58502,#58503, - #58504,#58505,#58506),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60798 = CARTESIAN_POINT('',(0.673523800866,0.E+000)); +#60799 = CARTESIAN_POINT('',(0.673523800866,2.49)); +#60800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60801 = ORIENTED_EDGE('',*,*,#60802,.F.); +#60802 = EDGE_CURVE('',#60623,#60781,#60803,.T.); +#60803 = SURFACE_CURVE('',#60804,(#60808,#60815),.PCURVE_S1.); +#60804 = LINE('',#60805,#60806); +#60805 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); +#60806 = VECTOR('',#60807,1.); +#60807 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); +#60808 = PCURVE('',#60632,#60809); +#60809 = DEFINITIONAL_REPRESENTATION('',(#60810),#60814); +#60810 = LINE('',#60811,#60812); +#60811 = CARTESIAN_POINT('',(0.2,0.E+000)); +#60812 = VECTOR('',#60813,1.); +#60813 = DIRECTION('',(1.,0.E+000)); +#60814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60815 = PCURVE('',#40567,#60816); +#60816 = DEFINITIONAL_REPRESENTATION('',(#60817),#60821); +#60817 = LINE('',#60818,#60819); +#60818 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); +#60819 = VECTOR('',#60820,1.); +#60820 = DIRECTION('',(-0.623744157346,0.78162857303)); +#60821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60822 = ADVANCED_FACE('',(#60823),#60437,.T.); +#60823 = FACE_BOUND('',#60824,.F.); +#60824 = EDGE_LOOP('',(#60825,#60826,#60849,#60900,#60923,#60943)); +#60825 = ORIENTED_EDGE('',*,*,#60499,.F.); +#60826 = ORIENTED_EDGE('',*,*,#60827,.T.); +#60827 = EDGE_CURVE('',#60500,#60828,#60830,.T.); +#60828 = VERTEX_POINT('',#60829); +#60829 = CARTESIAN_POINT('',(-2.3,-1.282876752796,2.78)); +#60830 = SURFACE_CURVE('',#60831,(#60835,#60842),.PCURVE_S1.); +#60831 = LINE('',#60832,#60833); +#60832 = CARTESIAN_POINT('',(-0.21,-1.282876752796,2.78)); +#60833 = VECTOR('',#60834,1.); +#60834 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60835 = PCURVE('',#60437,#60836); +#60836 = DEFINITIONAL_REPRESENTATION('',(#60837),#60841); +#60837 = LINE('',#60838,#60839); +#60838 = CARTESIAN_POINT('',(0.E+000,2.71)); +#60839 = VECTOR('',#60840,1.); +#60840 = DIRECTION('',(0.E+000,1.)); +#60841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60842 = PCURVE('',#60560,#60843); +#60843 = DEFINITIONAL_REPRESENTATION('',(#60844),#60848); +#60844 = LINE('',#60845,#60846); +#60845 = CARTESIAN_POINT('',(0.3,2.71)); +#60846 = VECTOR('',#60847,1.); +#60847 = DIRECTION('',(0.E+000,1.)); +#60848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60849 = ORIENTED_EDGE('',*,*,#60850,.F.); +#60850 = EDGE_CURVE('',#60851,#60828,#60853,.T.); +#60851 = VERTEX_POINT('',#60852); +#60852 = CARTESIAN_POINT('',(-2.5,-1.12655103819,2.655251168531)); +#60853 = SURFACE_CURVE('',#60854,(#60859,#60866),.PCURVE_S1.); +#60854 = CIRCLE('',#60855,0.2); +#60855 = AXIS2_PLACEMENT_3D('',#60856,#60857,#60858); +#60856 = CARTESIAN_POINT('',(-2.3,-1.12655103819,2.655251168531)); +#60857 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60858 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60859 = PCURVE('',#60437,#60860); +#60860 = DEFINITIONAL_REPRESENTATION('',(#60861),#60865); +#60861 = CIRCLE('',#60862,0.2); +#60862 = AXIS2_PLACEMENT_2D('',#60863,#60864); +#60863 = CARTESIAN_POINT('',(0.2,4.8)); +#60864 = DIRECTION('',(0.E+000,1.)); +#60865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60866 = PCURVE('',#60867,#60872); +#60867 = CYLINDRICAL_SURFACE('',#60868,0.2); +#60868 = AXIS2_PLACEMENT_3D('',#60869,#60870,#60871); +#60869 = CARTESIAN_POINT('',(-2.3,-1.323351446176,2.408635917304)); +#60870 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#60871 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60872 = DEFINITIONAL_REPRESENTATION('',(#60873),#60899); +#60873 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60874,#60875,#60876,#60877, + #60878,#60879,#60880,#60881,#60882,#60883,#60884,#60885,#60886, + #60887,#60888,#60889,#60890,#60891,#60892,#60893,#60894,#60895, + #60896,#60897,#60898),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72541,108 +75530,108 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58482 = CARTESIAN_POINT('',(0.E+000,0.315514631549)); -#58483 = CARTESIAN_POINT('',(2.379994434407E-002,0.315514631549)); -#58484 = CARTESIAN_POINT('',(7.13998330336E-002,0.315514631549)); -#58485 = CARTESIAN_POINT('',(0.14279966607,0.315514631549)); -#58486 = CARTESIAN_POINT('',(0.214199499106,0.315514631549)); -#58487 = CARTESIAN_POINT('',(0.285599332142,0.315514631549)); -#58488 = CARTESIAN_POINT('',(0.356999165179,0.315514631549)); -#58489 = CARTESIAN_POINT('',(0.428398998215,0.315514631549)); -#58490 = CARTESIAN_POINT('',(0.499798831251,0.315514631549)); -#58491 = CARTESIAN_POINT('',(0.571198664287,0.315514631549)); -#58492 = CARTESIAN_POINT('',(0.642598497323,0.315514631549)); -#58493 = CARTESIAN_POINT('',(0.71399833036,0.315514631549)); -#58494 = CARTESIAN_POINT('',(0.785398163396,0.315514631549)); -#58495 = CARTESIAN_POINT('',(0.856797996432,0.315514631549)); -#58496 = CARTESIAN_POINT('',(0.928197829468,0.315514631549)); -#58497 = CARTESIAN_POINT('',(0.999597662505,0.315514631549)); -#58498 = CARTESIAN_POINT('',(1.070997495541,0.315514631549)); -#58499 = CARTESIAN_POINT('',(1.142397328577,0.315514631549)); -#58500 = CARTESIAN_POINT('',(1.213797161613,0.315514631549)); -#58501 = CARTESIAN_POINT('',(1.28519699465,0.315514631549)); -#58502 = CARTESIAN_POINT('',(1.356596827686,0.315514631549)); -#58503 = CARTESIAN_POINT('',(1.427996660722,0.315514631549)); -#58504 = CARTESIAN_POINT('',(1.499396493759,0.315514631549)); -#58505 = CARTESIAN_POINT('',(1.546996382449,0.315514631549)); -#58506 = CARTESIAN_POINT('',(1.570796326795,0.315514631549)); -#58507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58508 = ORIENTED_EDGE('',*,*,#58509,.T.); -#58509 = EDGE_CURVE('',#58459,#58510,#58512,.T.); -#58510 = VERTEX_POINT('',#58511); -#58511 = CARTESIAN_POINT('',(-2.5,-1.03411419437,2.581486028353)); -#58512 = SURFACE_CURVE('',#58513,(#58517,#58524),.PCURVE_S1.); -#58513 = LINE('',#58514,#58515); -#58514 = CARTESIAN_POINT('',(-2.5,-1.12655103819,2.655251168531)); -#58515 = VECTOR('',#58516,1.); -#58516 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); -#58517 = PCURVE('',#58045,#58518); -#58518 = DEFINITIONAL_REPRESENTATION('',(#58519),#58523); -#58519 = LINE('',#58520,#58521); -#58520 = CARTESIAN_POINT('',(0.2,5.)); -#58521 = VECTOR('',#58522,1.); -#58522 = DIRECTION('',(1.,0.E+000)); -#58523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58524 = PCURVE('',#37831,#58525); -#58525 = DEFINITIONAL_REPRESENTATION('',(#58526),#58530); -#58526 = LINE('',#58527,#58528); -#58527 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); -#58528 = VECTOR('',#58529,1.); -#58529 = DIRECTION('',(-0.623744157346,0.78162857303)); -#58530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58531 = ORIENTED_EDGE('',*,*,#58532,.F.); -#58532 = EDGE_CURVE('',#58030,#58510,#58533,.T.); -#58533 = SURFACE_CURVE('',#58534,(#58538,#58545),.PCURVE_S1.); -#58534 = LINE('',#58535,#58536); -#58535 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); -#58536 = VECTOR('',#58537,1.); -#58537 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58538 = PCURVE('',#58045,#58539); -#58539 = DEFINITIONAL_REPRESENTATION('',(#58540),#58544); -#58540 = LINE('',#58541,#58542); -#58541 = CARTESIAN_POINT('',(0.318261853532,2.51)); -#58542 = VECTOR('',#58543,1.); -#58543 = DIRECTION('',(0.E+000,1.)); -#58544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58545 = PCURVE('',#42249,#58546); -#58546 = DEFINITIONAL_REPRESENTATION('',(#58547),#58550); -#58547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58548,#58549),.UNSPECIFIED., +#60874 = CARTESIAN_POINT('',(0.E+000,0.315514631549)); +#60875 = CARTESIAN_POINT('',(2.379994434407E-002,0.315514631549)); +#60876 = CARTESIAN_POINT('',(7.13998330336E-002,0.315514631549)); +#60877 = CARTESIAN_POINT('',(0.14279966607,0.315514631549)); +#60878 = CARTESIAN_POINT('',(0.214199499106,0.315514631549)); +#60879 = CARTESIAN_POINT('',(0.285599332142,0.315514631549)); +#60880 = CARTESIAN_POINT('',(0.356999165179,0.315514631549)); +#60881 = CARTESIAN_POINT('',(0.428398998215,0.315514631549)); +#60882 = CARTESIAN_POINT('',(0.499798831251,0.315514631549)); +#60883 = CARTESIAN_POINT('',(0.571198664287,0.315514631549)); +#60884 = CARTESIAN_POINT('',(0.642598497323,0.315514631549)); +#60885 = CARTESIAN_POINT('',(0.71399833036,0.315514631549)); +#60886 = CARTESIAN_POINT('',(0.785398163396,0.315514631549)); +#60887 = CARTESIAN_POINT('',(0.856797996432,0.315514631549)); +#60888 = CARTESIAN_POINT('',(0.928197829468,0.315514631549)); +#60889 = CARTESIAN_POINT('',(0.999597662505,0.315514631549)); +#60890 = CARTESIAN_POINT('',(1.070997495541,0.315514631549)); +#60891 = CARTESIAN_POINT('',(1.142397328577,0.315514631549)); +#60892 = CARTESIAN_POINT('',(1.213797161613,0.315514631549)); +#60893 = CARTESIAN_POINT('',(1.28519699465,0.315514631549)); +#60894 = CARTESIAN_POINT('',(1.356596827686,0.315514631549)); +#60895 = CARTESIAN_POINT('',(1.427996660722,0.315514631549)); +#60896 = CARTESIAN_POINT('',(1.499396493759,0.315514631549)); +#60897 = CARTESIAN_POINT('',(1.546996382449,0.315514631549)); +#60898 = CARTESIAN_POINT('',(1.570796326795,0.315514631549)); +#60899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60900 = ORIENTED_EDGE('',*,*,#60901,.T.); +#60901 = EDGE_CURVE('',#60851,#60902,#60904,.T.); +#60902 = VERTEX_POINT('',#60903); +#60903 = CARTESIAN_POINT('',(-2.5,-1.03411419437,2.581486028353)); +#60904 = SURFACE_CURVE('',#60905,(#60909,#60916),.PCURVE_S1.); +#60905 = LINE('',#60906,#60907); +#60906 = CARTESIAN_POINT('',(-2.5,-1.12655103819,2.655251168531)); +#60907 = VECTOR('',#60908,1.); +#60908 = DIRECTION('',(0.E+000,0.78162857303,-0.623744157346)); +#60909 = PCURVE('',#60437,#60910); +#60910 = DEFINITIONAL_REPRESENTATION('',(#60911),#60915); +#60911 = LINE('',#60912,#60913); +#60912 = CARTESIAN_POINT('',(0.2,5.)); +#60913 = VECTOR('',#60914,1.); +#60914 = DIRECTION('',(1.,0.E+000)); +#60915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60916 = PCURVE('',#40223,#60917); +#60917 = DEFINITIONAL_REPRESENTATION('',(#60918),#60922); +#60918 = LINE('',#60919,#60920); +#60919 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); +#60920 = VECTOR('',#60921,1.); +#60921 = DIRECTION('',(-0.623744157346,0.78162857303)); +#60922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60923 = ORIENTED_EDGE('',*,*,#60924,.F.); +#60924 = EDGE_CURVE('',#60422,#60902,#60925,.T.); +#60925 = SURFACE_CURVE('',#60926,(#60930,#60937),.PCURVE_S1.); +#60926 = LINE('',#60927,#60928); +#60927 = CARTESIAN_POINT('',(-1.E-002,-1.03411419437,2.581486028353)); +#60928 = VECTOR('',#60929,1.); +#60929 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#60930 = PCURVE('',#60437,#60931); +#60931 = DEFINITIONAL_REPRESENTATION('',(#60932),#60936); +#60932 = LINE('',#60933,#60934); +#60933 = CARTESIAN_POINT('',(0.318261853532,2.51)); +#60934 = VECTOR('',#60935,1.); +#60935 = DIRECTION('',(0.E+000,1.)); +#60936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60937 = PCURVE('',#44641,#60938); +#60938 = DEFINITIONAL_REPRESENTATION('',(#60939),#60942); +#60939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#60940,#60941),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.49),.PIECEWISE_BEZIER_KNOTS.); -#58548 = CARTESIAN_POINT('',(0.673523800866,2.51)); -#58549 = CARTESIAN_POINT('',(0.673523800866,5.)); -#58550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58551 = ORIENTED_EDGE('',*,*,#58029,.T.); -#58552 = ADVANCED_FACE('',(#58553),#58252,.T.); -#58553 = FACE_BOUND('',#58554,.T.); -#58554 = EDGE_LOOP('',(#58555,#58603,#58646,#58647)); -#58555 = ORIENTED_EDGE('',*,*,#58556,.F.); -#58556 = EDGE_CURVE('',#58557,#58559,#58561,.T.); -#58557 = VERTEX_POINT('',#58558); -#58558 = CARTESIAN_POINT('',(2.5,-1.313674285394,2.420762596622)); -#58559 = VERTEX_POINT('',#58560); -#58560 = CARTESIAN_POINT('',(2.3,-1.47,2.545511428091)); -#58561 = SURFACE_CURVE('',#58562,(#58567,#58596),.PCURVE_S1.); -#58562 = CIRCLE('',#58563,0.2); -#58563 = AXIS2_PLACEMENT_3D('',#58564,#58565,#58566); -#58564 = CARTESIAN_POINT('',(2.3,-1.313674285394,2.420762596622)); -#58565 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58566 = DIRECTION('',(1.,0.E+000,0.E+000)); -#58567 = PCURVE('',#58252,#58568); -#58568 = DEFINITIONAL_REPRESENTATION('',(#58569),#58595); -#58569 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58570,#58571,#58572,#58573, - #58574,#58575,#58576,#58577,#58578,#58579,#58580,#58581,#58582, - #58583,#58584,#58585,#58586,#58587,#58588,#58589,#58590,#58591, - #58592,#58593,#58594),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60940 = CARTESIAN_POINT('',(0.673523800866,2.51)); +#60941 = CARTESIAN_POINT('',(0.673523800866,5.)); +#60942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60943 = ORIENTED_EDGE('',*,*,#60421,.T.); +#60944 = ADVANCED_FACE('',(#60945),#60644,.T.); +#60945 = FACE_BOUND('',#60946,.T.); +#60946 = EDGE_LOOP('',(#60947,#60995,#61038,#61039)); +#60947 = ORIENTED_EDGE('',*,*,#60948,.F.); +#60948 = EDGE_CURVE('',#60949,#60951,#60953,.T.); +#60949 = VERTEX_POINT('',#60950); +#60950 = CARTESIAN_POINT('',(2.5,-1.313674285394,2.420762596622)); +#60951 = VERTEX_POINT('',#60952); +#60952 = CARTESIAN_POINT('',(2.3,-1.47,2.545511428091)); +#60953 = SURFACE_CURVE('',#60954,(#60959,#60988),.PCURVE_S1.); +#60954 = CIRCLE('',#60955,0.2); +#60955 = AXIS2_PLACEMENT_3D('',#60956,#60957,#60958); +#60956 = CARTESIAN_POINT('',(2.3,-1.313674285394,2.420762596622)); +#60957 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#60958 = DIRECTION('',(1.,0.E+000,0.E+000)); +#60959 = PCURVE('',#60644,#60960); +#60960 = DEFINITIONAL_REPRESENTATION('',(#60961),#60987); +#60961 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#60962,#60963,#60964,#60965, + #60966,#60967,#60968,#60969,#60970,#60971,#60972,#60973,#60974, + #60975,#60976,#60977,#60978,#60979,#60980,#60981,#60982,#60983, + #60984,#60985,#60986),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72650,56 +75639,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58570 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); -#58571 = CARTESIAN_POINT('',(2.379994434511E-002,0.322039397383)); -#58572 = CARTESIAN_POINT('',(7.139983303561E-002,0.322039397383)); -#58573 = CARTESIAN_POINT('',(0.142799666072,0.322039397383)); -#58574 = CARTESIAN_POINT('',(0.214199499108,0.322039397383)); -#58575 = CARTESIAN_POINT('',(0.285599332144,0.322039397383)); -#58576 = CARTESIAN_POINT('',(0.35699916518,0.322039397383)); -#58577 = CARTESIAN_POINT('',(0.428398998216,0.322039397383)); -#58578 = CARTESIAN_POINT('',(0.499798831253,0.322039397383)); -#58579 = CARTESIAN_POINT('',(0.571198664289,0.322039397383)); -#58580 = CARTESIAN_POINT('',(0.642598497325,0.322039397383)); -#58581 = CARTESIAN_POINT('',(0.713998330361,0.322039397383)); -#58582 = CARTESIAN_POINT('',(0.785398163397,0.322039397383)); -#58583 = CARTESIAN_POINT('',(0.856797996433,0.322039397383)); -#58584 = CARTESIAN_POINT('',(0.928197829469,0.322039397383)); -#58585 = CARTESIAN_POINT('',(0.999597662506,0.322039397383)); -#58586 = CARTESIAN_POINT('',(1.070997495542,0.322039397383)); -#58587 = CARTESIAN_POINT('',(1.142397328578,0.322039397383)); -#58588 = CARTESIAN_POINT('',(1.213797161614,0.322039397383)); -#58589 = CARTESIAN_POINT('',(1.28519699465,0.322039397383)); -#58590 = CARTESIAN_POINT('',(1.356596827686,0.322039397383)); -#58591 = CARTESIAN_POINT('',(1.427996660723,0.322039397383)); -#58592 = CARTESIAN_POINT('',(1.499396493759,0.322039397383)); -#58593 = CARTESIAN_POINT('',(1.54699638245,0.322039397383)); -#58594 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); -#58595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58596 = PCURVE('',#55972,#58597); -#58597 = DEFINITIONAL_REPRESENTATION('',(#58598),#58602); -#58598 = CIRCLE('',#58599,0.2); -#58599 = AXIS2_PLACEMENT_2D('',#58600,#58601); -#58600 = CARTESIAN_POINT('',(0.113448111359,0.2)); -#58601 = DIRECTION('',(0.E+000,-1.)); -#58602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58603 = ORIENTED_EDGE('',*,*,#58604,.F.); -#58604 = EDGE_CURVE('',#58231,#58557,#58605,.T.); -#58605 = SURFACE_CURVE('',#58606,(#58610,#58639),.PCURVE_S1.); -#58606 = LINE('',#58607,#58608); -#58607 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); -#58608 = VECTOR('',#58609,1.); -#58609 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58610 = PCURVE('',#58252,#58611); -#58611 = DEFINITIONAL_REPRESENTATION('',(#58612),#58638); -#58612 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58613,#58614,#58615,#58616, - #58617,#58618,#58619,#58620,#58621,#58622,#58623,#58624,#58625, - #58626,#58627,#58628,#58629,#58630,#58631,#58632,#58633,#58634, - #58635,#58636,#58637),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#60962 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); +#60963 = CARTESIAN_POINT('',(2.379994434511E-002,0.322039397383)); +#60964 = CARTESIAN_POINT('',(7.139983303561E-002,0.322039397383)); +#60965 = CARTESIAN_POINT('',(0.142799666072,0.322039397383)); +#60966 = CARTESIAN_POINT('',(0.214199499108,0.322039397383)); +#60967 = CARTESIAN_POINT('',(0.285599332144,0.322039397383)); +#60968 = CARTESIAN_POINT('',(0.35699916518,0.322039397383)); +#60969 = CARTESIAN_POINT('',(0.428398998216,0.322039397383)); +#60970 = CARTESIAN_POINT('',(0.499798831253,0.322039397383)); +#60971 = CARTESIAN_POINT('',(0.571198664289,0.322039397383)); +#60972 = CARTESIAN_POINT('',(0.642598497325,0.322039397383)); +#60973 = CARTESIAN_POINT('',(0.713998330361,0.322039397383)); +#60974 = CARTESIAN_POINT('',(0.785398163397,0.322039397383)); +#60975 = CARTESIAN_POINT('',(0.856797996433,0.322039397383)); +#60976 = CARTESIAN_POINT('',(0.928197829469,0.322039397383)); +#60977 = CARTESIAN_POINT('',(0.999597662506,0.322039397383)); +#60978 = CARTESIAN_POINT('',(1.070997495542,0.322039397383)); +#60979 = CARTESIAN_POINT('',(1.142397328578,0.322039397383)); +#60980 = CARTESIAN_POINT('',(1.213797161614,0.322039397383)); +#60981 = CARTESIAN_POINT('',(1.28519699465,0.322039397383)); +#60982 = CARTESIAN_POINT('',(1.356596827686,0.322039397383)); +#60983 = CARTESIAN_POINT('',(1.427996660723,0.322039397383)); +#60984 = CARTESIAN_POINT('',(1.499396493759,0.322039397383)); +#60985 = CARTESIAN_POINT('',(1.54699638245,0.322039397383)); +#60986 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); +#60987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60988 = PCURVE('',#58364,#60989); +#60989 = DEFINITIONAL_REPRESENTATION('',(#60990),#60994); +#60990 = CIRCLE('',#60991,0.2); +#60991 = AXIS2_PLACEMENT_2D('',#60992,#60993); +#60992 = CARTESIAN_POINT('',(0.113448111359,0.2)); +#60993 = DIRECTION('',(0.E+000,-1.)); +#60994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#60995 = ORIENTED_EDGE('',*,*,#60996,.F.); +#60996 = EDGE_CURVE('',#60623,#60949,#60997,.T.); +#60997 = SURFACE_CURVE('',#60998,(#61002,#61031),.PCURVE_S1.); +#60998 = LINE('',#60999,#61000); +#60999 = CARTESIAN_POINT('',(2.5,-1.12655103819,2.655251168531)); +#61000 = VECTOR('',#61001,1.); +#61001 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61002 = PCURVE('',#60644,#61003); +#61003 = DEFINITIONAL_REPRESENTATION('',(#61004),#61030); +#61004 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#61005,#61006,#61007,#61008, + #61009,#61010,#61011,#61012,#61013,#61014,#61015,#61016,#61017, + #61018,#61019,#61020,#61021,#61022,#61023,#61024,#61025,#61026, + #61027,#61028,#61029),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363637E-002, 2.727272727274E-002,4.090909090911E-002,5.454545454548E-002, 6.818181818185E-002,8.181818181822E-002,9.545454545459E-002, @@ -72707,151 +75696,151 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454546,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#58613 = CARTESIAN_POINT('',(0.E+000,2.203939738302E-002)); -#58614 = CARTESIAN_POINT('',(-3.623767952377E-013,2.658485192848E-002)); -#58615 = CARTESIAN_POINT('',(-6.998845947237E-013,3.567576101939E-002)); -#58616 = CARTESIAN_POINT('',(-5.648814749293E-013,4.931212465576E-002)); -#58617 = CARTESIAN_POINT('',(-6.021849685567E-013,6.294848829213E-002)); -#58618 = CARTESIAN_POINT('',(-5.906386491006E-013,7.65848519285E-002)); -#58619 = CARTESIAN_POINT('',(-5.933031843597E-013,9.022121556488E-002)); -#58620 = CARTESIAN_POINT('',(-5.933031843597E-013,0.103857579201)); -#58621 = CARTESIAN_POINT('',(-5.933031843597E-013,0.117493942838)); -#58622 = CARTESIAN_POINT('',(-5.933031843597E-013,0.131130306474)); -#58623 = CARTESIAN_POINT('',(-5.9241500594E-013,0.14476667011)); -#58624 = CARTESIAN_POINT('',(-5.968558980385E-013,0.158403033747)); -#58625 = CARTESIAN_POINT('',(-5.915268275203E-013,0.172039397383)); -#58626 = CARTESIAN_POINT('',(-5.9241500594E-013,0.185675761019)); -#58627 = CARTESIAN_POINT('',(-5.933031843597E-013,0.199312124656)); -#58628 = CARTESIAN_POINT('',(-5.933031843597E-013,0.212948488292)); -#58629 = CARTESIAN_POINT('',(-5.941913627794E-013,0.226584851929)); -#58630 = CARTESIAN_POINT('',(-5.915268275203E-013,0.240221215565)); -#58631 = CARTESIAN_POINT('',(-5.950795411991E-013,0.253857579201)); -#58632 = CARTESIAN_POINT('',(-5.888622922612E-013,0.267493942838)); -#58633 = CARTESIAN_POINT('',(-6.01296790137E-013,0.281130306474)); -#58634 = CARTESIAN_POINT('',(-5.648814749293E-013,0.29476667011)); -#58635 = CARTESIAN_POINT('',(-6.98996416304E-013,0.308403033747)); -#58636 = CARTESIAN_POINT('',(-3.632649736574E-013,0.317493942838)); -#58637 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); -#58638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58639 = PCURVE('',#38175,#58640); -#58640 = DEFINITIONAL_REPRESENTATION('',(#58641),#58645); -#58641 = LINE('',#58642,#58643); -#58642 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); -#58643 = VECTOR('',#58644,1.); -#58644 = DIRECTION('',(-0.78162857303,-0.623744157346)); -#58645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58646 = ORIENTED_EDGE('',*,*,#58228,.F.); -#58647 = ORIENTED_EDGE('',*,*,#58648,.T.); -#58648 = EDGE_CURVE('',#58229,#58559,#58649,.T.); -#58649 = SURFACE_CURVE('',#58650,(#58654,#58660),.PCURVE_S1.); -#58650 = LINE('',#58651,#58652); -#58651 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); -#58652 = VECTOR('',#58653,1.); -#58653 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58654 = PCURVE('',#58252,#58655); -#58655 = DEFINITIONAL_REPRESENTATION('',(#58656),#58659); -#58656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58657,#58658),.UNSPECIFIED., +#61005 = CARTESIAN_POINT('',(0.E+000,2.203939738302E-002)); +#61006 = CARTESIAN_POINT('',(-3.623767952377E-013,2.658485192848E-002)); +#61007 = CARTESIAN_POINT('',(-6.998845947237E-013,3.567576101939E-002)); +#61008 = CARTESIAN_POINT('',(-5.648814749293E-013,4.931212465576E-002)); +#61009 = CARTESIAN_POINT('',(-6.021849685567E-013,6.294848829213E-002)); +#61010 = CARTESIAN_POINT('',(-5.906386491006E-013,7.65848519285E-002)); +#61011 = CARTESIAN_POINT('',(-5.933031843597E-013,9.022121556488E-002)); +#61012 = CARTESIAN_POINT('',(-5.933031843597E-013,0.103857579201)); +#61013 = CARTESIAN_POINT('',(-5.933031843597E-013,0.117493942838)); +#61014 = CARTESIAN_POINT('',(-5.933031843597E-013,0.131130306474)); +#61015 = CARTESIAN_POINT('',(-5.9241500594E-013,0.14476667011)); +#61016 = CARTESIAN_POINT('',(-5.968558980385E-013,0.158403033747)); +#61017 = CARTESIAN_POINT('',(-5.915268275203E-013,0.172039397383)); +#61018 = CARTESIAN_POINT('',(-5.9241500594E-013,0.185675761019)); +#61019 = CARTESIAN_POINT('',(-5.933031843597E-013,0.199312124656)); +#61020 = CARTESIAN_POINT('',(-5.933031843597E-013,0.212948488292)); +#61021 = CARTESIAN_POINT('',(-5.941913627794E-013,0.226584851929)); +#61022 = CARTESIAN_POINT('',(-5.915268275203E-013,0.240221215565)); +#61023 = CARTESIAN_POINT('',(-5.950795411991E-013,0.253857579201)); +#61024 = CARTESIAN_POINT('',(-5.888622922612E-013,0.267493942838)); +#61025 = CARTESIAN_POINT('',(-6.01296790137E-013,0.281130306474)); +#61026 = CARTESIAN_POINT('',(-5.648814749293E-013,0.29476667011)); +#61027 = CARTESIAN_POINT('',(-6.98996416304E-013,0.308403033747)); +#61028 = CARTESIAN_POINT('',(-3.632649736574E-013,0.317493942838)); +#61029 = CARTESIAN_POINT('',(0.E+000,0.322039397383)); +#61030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61031 = PCURVE('',#40567,#61032); +#61032 = DEFINITIONAL_REPRESENTATION('',(#61033),#61037); +#61033 = LINE('',#61034,#61035); +#61034 = CARTESIAN_POINT('',(2.655251168531,-1.12655103819)); +#61035 = VECTOR('',#61036,1.); +#61036 = DIRECTION('',(-0.78162857303,-0.623744157346)); +#61037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61038 = ORIENTED_EDGE('',*,*,#60620,.F.); +#61039 = ORIENTED_EDGE('',*,*,#61040,.T.); +#61040 = EDGE_CURVE('',#60621,#60951,#61041,.T.); +#61041 = SURFACE_CURVE('',#61042,(#61046,#61052),.PCURVE_S1.); +#61042 = LINE('',#61043,#61044); +#61043 = CARTESIAN_POINT('',(2.3,-1.282876752796,2.78)); +#61044 = VECTOR('',#61045,1.); +#61045 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61046 = PCURVE('',#60644,#61047); +#61047 = DEFINITIONAL_REPRESENTATION('',(#61048),#61051); +#61048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61049,#61050),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#58657 = CARTESIAN_POINT('',(1.570796326795,2.203939738326E-002)); -#58658 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); -#58659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58660 = PCURVE('',#58302,#58661); -#58661 = DEFINITIONAL_REPRESENTATION('',(#58662),#58666); -#58662 = LINE('',#58663,#58664); -#58663 = CARTESIAN_POINT('',(0.3,0.2)); -#58664 = VECTOR('',#58665,1.); -#58665 = DIRECTION('',(-1.,0.E+000)); -#58666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58667 = ADVANCED_FACE('',(#58668),#55972,.T.); -#58668 = FACE_BOUND('',#58669,.F.); -#58669 = EDGE_LOOP('',(#58670,#58671,#58692,#58693,#58716,#58762)); -#58670 = ORIENTED_EDGE('',*,*,#58556,.F.); -#58671 = ORIENTED_EDGE('',*,*,#58672,.F.); -#58672 = EDGE_CURVE('',#38132,#58557,#58673,.T.); -#58673 = SURFACE_CURVE('',#58674,(#58678,#58685),.PCURVE_S1.); -#58674 = LINE('',#58675,#58676); -#58675 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); -#58676 = VECTOR('',#58677,1.); -#58677 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58678 = PCURVE('',#55972,#58679); -#58679 = DEFINITIONAL_REPRESENTATION('',(#58680),#58684); -#58680 = LINE('',#58681,#58682); -#58681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#58682 = VECTOR('',#58683,1.); -#58683 = DIRECTION('',(1.,0.E+000)); -#58684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58685 = PCURVE('',#38175,#58686); -#58686 = DEFINITIONAL_REPRESENTATION('',(#58687),#58691); -#58687 = LINE('',#58688,#58689); -#58688 = CARTESIAN_POINT('',(2.35,-1.225)); -#58689 = VECTOR('',#58690,1.); -#58690 = DIRECTION('',(0.623744157346,-0.78162857303)); -#58691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58692 = ORIENTED_EDGE('',*,*,#55958,.T.); -#58693 = ORIENTED_EDGE('',*,*,#58694,.T.); -#58694 = EDGE_CURVE('',#55936,#58695,#58697,.T.); -#58695 = VERTEX_POINT('',#58696); -#58696 = CARTESIAN_POINT('',(1.E-002,-1.313674285394,2.420762596622)); -#58697 = SURFACE_CURVE('',#58698,(#58702,#58709),.PCURVE_S1.); -#58698 = LINE('',#58699,#58700); -#58699 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); -#58700 = VECTOR('',#58701,1.); -#58701 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58702 = PCURVE('',#55972,#58703); -#58703 = DEFINITIONAL_REPRESENTATION('',(#58704),#58708); -#58704 = LINE('',#58705,#58706); -#58705 = CARTESIAN_POINT('',(0.E+000,2.49)); -#58706 = VECTOR('',#58707,1.); -#58707 = DIRECTION('',(1.,0.E+000)); -#58708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58709 = PCURVE('',#41511,#58710); -#58710 = DEFINITIONAL_REPRESENTATION('',(#58711),#58715); -#58711 = LINE('',#58712,#58713); -#58712 = CARTESIAN_POINT('',(0.60484542651,-0.3)); -#58713 = VECTOR('',#58714,1.); -#58714 = DIRECTION('',(0.623744157346,0.78162857303)); -#58715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58716 = ORIENTED_EDGE('',*,*,#58717,.F.); -#58717 = EDGE_CURVE('',#58718,#58695,#58720,.T.); -#58718 = VERTEX_POINT('',#58719); -#58719 = CARTESIAN_POINT('',(0.21,-1.47,2.545511428091)); -#58720 = SURFACE_CURVE('',#58721,(#58726,#58733),.PCURVE_S1.); -#58721 = CIRCLE('',#58722,0.2); -#58722 = AXIS2_PLACEMENT_3D('',#58723,#58724,#58725); -#58723 = CARTESIAN_POINT('',(0.21,-1.313674285394,2.420762596622)); -#58724 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58725 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58726 = PCURVE('',#55972,#58727); -#58727 = DEFINITIONAL_REPRESENTATION('',(#58728),#58732); -#58728 = CIRCLE('',#58729,0.2); -#58729 = AXIS2_PLACEMENT_2D('',#58730,#58731); -#58730 = CARTESIAN_POINT('',(0.113448111359,2.29)); -#58731 = DIRECTION('',(1.,0.E+000)); -#58732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58733 = PCURVE('',#58331,#58734); -#58734 = DEFINITIONAL_REPRESENTATION('',(#58735),#58761); -#58735 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58736,#58737,#58738,#58739, - #58740,#58741,#58742,#58743,#58744,#58745,#58746,#58747,#58748, - #58749,#58750,#58751,#58752,#58753,#58754,#58755,#58756,#58757, - #58758,#58759,#58760),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#61049 = CARTESIAN_POINT('',(1.570796326795,2.203939738326E-002)); +#61050 = CARTESIAN_POINT('',(1.570796326795,0.322039397383)); +#61051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61052 = PCURVE('',#60694,#61053); +#61053 = DEFINITIONAL_REPRESENTATION('',(#61054),#61058); +#61054 = LINE('',#61055,#61056); +#61055 = CARTESIAN_POINT('',(0.3,0.2)); +#61056 = VECTOR('',#61057,1.); +#61057 = DIRECTION('',(-1.,0.E+000)); +#61058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61059 = ADVANCED_FACE('',(#61060),#58364,.T.); +#61060 = FACE_BOUND('',#61061,.F.); +#61061 = EDGE_LOOP('',(#61062,#61063,#61084,#61085,#61108,#61154)); +#61062 = ORIENTED_EDGE('',*,*,#60948,.F.); +#61063 = ORIENTED_EDGE('',*,*,#61064,.F.); +#61064 = EDGE_CURVE('',#40524,#60949,#61065,.T.); +#61065 = SURFACE_CURVE('',#61066,(#61070,#61077),.PCURVE_S1.); +#61066 = LINE('',#61067,#61068); +#61067 = CARTESIAN_POINT('',(2.5,-1.225,2.35)); +#61068 = VECTOR('',#61069,1.); +#61069 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#61070 = PCURVE('',#58364,#61071); +#61071 = DEFINITIONAL_REPRESENTATION('',(#61072),#61076); +#61072 = LINE('',#61073,#61074); +#61073 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#61074 = VECTOR('',#61075,1.); +#61075 = DIRECTION('',(1.,0.E+000)); +#61076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61077 = PCURVE('',#40567,#61078); +#61078 = DEFINITIONAL_REPRESENTATION('',(#61079),#61083); +#61079 = LINE('',#61080,#61081); +#61080 = CARTESIAN_POINT('',(2.35,-1.225)); +#61081 = VECTOR('',#61082,1.); +#61082 = DIRECTION('',(0.623744157346,-0.78162857303)); +#61083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61084 = ORIENTED_EDGE('',*,*,#58350,.T.); +#61085 = ORIENTED_EDGE('',*,*,#61086,.T.); +#61086 = EDGE_CURVE('',#58328,#61087,#61089,.T.); +#61087 = VERTEX_POINT('',#61088); +#61088 = CARTESIAN_POINT('',(1.E-002,-1.313674285394,2.420762596622)); +#61089 = SURFACE_CURVE('',#61090,(#61094,#61101),.PCURVE_S1.); +#61090 = LINE('',#61091,#61092); +#61091 = CARTESIAN_POINT('',(1.E-002,-1.225,2.35)); +#61092 = VECTOR('',#61093,1.); +#61093 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#61094 = PCURVE('',#58364,#61095); +#61095 = DEFINITIONAL_REPRESENTATION('',(#61096),#61100); +#61096 = LINE('',#61097,#61098); +#61097 = CARTESIAN_POINT('',(0.E+000,2.49)); +#61098 = VECTOR('',#61099,1.); +#61099 = DIRECTION('',(1.,0.E+000)); +#61100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61101 = PCURVE('',#43903,#61102); +#61102 = DEFINITIONAL_REPRESENTATION('',(#61103),#61107); +#61103 = LINE('',#61104,#61105); +#61104 = CARTESIAN_POINT('',(0.60484542651,-0.3)); +#61105 = VECTOR('',#61106,1.); +#61106 = DIRECTION('',(0.623744157346,0.78162857303)); +#61107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61108 = ORIENTED_EDGE('',*,*,#61109,.F.); +#61109 = EDGE_CURVE('',#61110,#61087,#61112,.T.); +#61110 = VERTEX_POINT('',#61111); +#61111 = CARTESIAN_POINT('',(0.21,-1.47,2.545511428091)); +#61112 = SURFACE_CURVE('',#61113,(#61118,#61125),.PCURVE_S1.); +#61113 = CIRCLE('',#61114,0.2); +#61114 = AXIS2_PLACEMENT_3D('',#61115,#61116,#61117); +#61115 = CARTESIAN_POINT('',(0.21,-1.313674285394,2.420762596622)); +#61116 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61117 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#61118 = PCURVE('',#58364,#61119); +#61119 = DEFINITIONAL_REPRESENTATION('',(#61120),#61124); +#61120 = CIRCLE('',#61121,0.2); +#61121 = AXIS2_PLACEMENT_2D('',#61122,#61123); +#61122 = CARTESIAN_POINT('',(0.113448111359,2.29)); +#61123 = DIRECTION('',(1.,0.E+000)); +#61124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61125 = PCURVE('',#60723,#61126); +#61126 = DEFINITIONAL_REPRESENTATION('',(#61127),#61153); +#61127 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#61128,#61129,#61130,#61131, + #61132,#61133,#61134,#61135,#61136,#61137,#61138,#61139,#61140, + #61141,#61142,#61143,#61144,#61145,#61146,#61147,#61148,#61149, + #61150,#61151,#61152),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72859,117 +75848,117 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58736 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); -#58737 = CARTESIAN_POINT('',(2.379994434538E-002,0.31491772868)); -#58738 = CARTESIAN_POINT('',(7.139983303613E-002,0.31491772868)); -#58739 = CARTESIAN_POINT('',(0.142799666072,0.31491772868)); -#58740 = CARTESIAN_POINT('',(0.214199499108,0.31491772868)); -#58741 = CARTESIAN_POINT('',(0.285599332145,0.31491772868)); -#58742 = CARTESIAN_POINT('',(0.356999165181,0.31491772868)); -#58743 = CARTESIAN_POINT('',(0.428398998217,0.31491772868)); -#58744 = CARTESIAN_POINT('',(0.499798831253,0.31491772868)); -#58745 = CARTESIAN_POINT('',(0.571198664289,0.31491772868)); -#58746 = CARTESIAN_POINT('',(0.642598497325,0.31491772868)); -#58747 = CARTESIAN_POINT('',(0.713998330361,0.31491772868)); -#58748 = CARTESIAN_POINT('',(0.785398163397,0.31491772868)); -#58749 = CARTESIAN_POINT('',(0.856797996434,0.31491772868)); -#58750 = CARTESIAN_POINT('',(0.92819782947,0.31491772868)); -#58751 = CARTESIAN_POINT('',(0.999597662506,0.31491772868)); -#58752 = CARTESIAN_POINT('',(1.070997495542,0.31491772868)); -#58753 = CARTESIAN_POINT('',(1.142397328578,0.31491772868)); -#58754 = CARTESIAN_POINT('',(1.213797161614,0.31491772868)); -#58755 = CARTESIAN_POINT('',(1.28519699465,0.31491772868)); -#58756 = CARTESIAN_POINT('',(1.356596827686,0.31491772868)); -#58757 = CARTESIAN_POINT('',(1.427996660723,0.31491772868)); -#58758 = CARTESIAN_POINT('',(1.499396493759,0.31491772868)); -#58759 = CARTESIAN_POINT('',(1.54699638245,0.31491772868)); -#58760 = CARTESIAN_POINT('',(1.570796326795,0.31491772868)); -#58761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58762 = ORIENTED_EDGE('',*,*,#58763,.F.); -#58763 = EDGE_CURVE('',#58559,#58718,#58764,.T.); -#58764 = SURFACE_CURVE('',#58765,(#58769,#58776),.PCURVE_S1.); -#58765 = LINE('',#58766,#58767); -#58766 = CARTESIAN_POINT('',(2.3,-1.47,2.545511428091)); -#58767 = VECTOR('',#58768,1.); -#58768 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58769 = PCURVE('',#55972,#58770); -#58770 = DEFINITIONAL_REPRESENTATION('',(#58771),#58775); -#58771 = LINE('',#58772,#58773); -#58772 = CARTESIAN_POINT('',(0.313448111358,0.2)); -#58773 = VECTOR('',#58774,1.); -#58774 = DIRECTION('',(0.E+000,1.)); -#58775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58776 = PCURVE('',#58302,#58777); -#58777 = DEFINITIONAL_REPRESENTATION('',(#58778),#58782); -#58778 = LINE('',#58779,#58780); -#58779 = CARTESIAN_POINT('',(0.E+000,0.2)); -#58780 = VECTOR('',#58781,1.); -#58781 = DIRECTION('',(0.E+000,1.)); -#58782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58783 = ADVANCED_FACE('',(#58784),#55785,.T.); -#58784 = FACE_BOUND('',#58785,.F.); -#58785 = EDGE_LOOP('',(#58786,#58787,#58788,#58789,#58812,#58858)); -#58786 = ORIENTED_EDGE('',*,*,#58180,.F.); -#58787 = ORIENTED_EDGE('',*,*,#58083,.F.); -#58788 = ORIENTED_EDGE('',*,*,#55769,.T.); -#58789 = ORIENTED_EDGE('',*,*,#58790,.T.); -#58790 = EDGE_CURVE('',#37816,#58791,#58793,.T.); -#58791 = VERTEX_POINT('',#58792); -#58792 = CARTESIAN_POINT('',(-2.5,-1.313674285394,2.420762596622)); -#58793 = SURFACE_CURVE('',#58794,(#58798,#58805),.PCURVE_S1.); -#58794 = LINE('',#58795,#58796); -#58795 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); -#58796 = VECTOR('',#58797,1.); -#58797 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58798 = PCURVE('',#55785,#58799); -#58799 = DEFINITIONAL_REPRESENTATION('',(#58800),#58804); -#58800 = LINE('',#58801,#58802); -#58801 = CARTESIAN_POINT('',(0.E+000,5.)); -#58802 = VECTOR('',#58803,1.); -#58803 = DIRECTION('',(1.,0.E+000)); -#58804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58805 = PCURVE('',#37831,#58806); -#58806 = DEFINITIONAL_REPRESENTATION('',(#58807),#58811); -#58807 = LINE('',#58808,#58809); -#58808 = CARTESIAN_POINT('',(2.35,-1.225)); -#58809 = VECTOR('',#58810,1.); -#58810 = DIRECTION('',(0.623744157346,-0.78162857303)); -#58811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58812 = ORIENTED_EDGE('',*,*,#58813,.F.); -#58813 = EDGE_CURVE('',#58814,#58791,#58816,.T.); -#58814 = VERTEX_POINT('',#58815); -#58815 = CARTESIAN_POINT('',(-2.3,-1.47,2.545511428091)); -#58816 = SURFACE_CURVE('',#58817,(#58822,#58829),.PCURVE_S1.); -#58817 = CIRCLE('',#58818,0.2); -#58818 = AXIS2_PLACEMENT_3D('',#58819,#58820,#58821); -#58819 = CARTESIAN_POINT('',(-2.3,-1.313674285394,2.420762596622)); -#58820 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58821 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); -#58822 = PCURVE('',#55785,#58823); -#58823 = DEFINITIONAL_REPRESENTATION('',(#58824),#58828); -#58824 = CIRCLE('',#58825,0.2); -#58825 = AXIS2_PLACEMENT_2D('',#58826,#58827); -#58826 = CARTESIAN_POINT('',(0.113448111359,4.8)); -#58827 = DIRECTION('',(1.,0.E+000)); -#58828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58829 = PCURVE('',#58475,#58830); -#58830 = DEFINITIONAL_REPRESENTATION('',(#58831),#58857); -#58831 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58832,#58833,#58834,#58835, - #58836,#58837,#58838,#58839,#58840,#58841,#58842,#58843,#58844, - #58845,#58846,#58847,#58848,#58849,#58850,#58851,#58852,#58853, - #58854,#58855,#58856),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#61128 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); +#61129 = CARTESIAN_POINT('',(2.379994434538E-002,0.31491772868)); +#61130 = CARTESIAN_POINT('',(7.139983303613E-002,0.31491772868)); +#61131 = CARTESIAN_POINT('',(0.142799666072,0.31491772868)); +#61132 = CARTESIAN_POINT('',(0.214199499108,0.31491772868)); +#61133 = CARTESIAN_POINT('',(0.285599332145,0.31491772868)); +#61134 = CARTESIAN_POINT('',(0.356999165181,0.31491772868)); +#61135 = CARTESIAN_POINT('',(0.428398998217,0.31491772868)); +#61136 = CARTESIAN_POINT('',(0.499798831253,0.31491772868)); +#61137 = CARTESIAN_POINT('',(0.571198664289,0.31491772868)); +#61138 = CARTESIAN_POINT('',(0.642598497325,0.31491772868)); +#61139 = CARTESIAN_POINT('',(0.713998330361,0.31491772868)); +#61140 = CARTESIAN_POINT('',(0.785398163397,0.31491772868)); +#61141 = CARTESIAN_POINT('',(0.856797996434,0.31491772868)); +#61142 = CARTESIAN_POINT('',(0.92819782947,0.31491772868)); +#61143 = CARTESIAN_POINT('',(0.999597662506,0.31491772868)); +#61144 = CARTESIAN_POINT('',(1.070997495542,0.31491772868)); +#61145 = CARTESIAN_POINT('',(1.142397328578,0.31491772868)); +#61146 = CARTESIAN_POINT('',(1.213797161614,0.31491772868)); +#61147 = CARTESIAN_POINT('',(1.28519699465,0.31491772868)); +#61148 = CARTESIAN_POINT('',(1.356596827686,0.31491772868)); +#61149 = CARTESIAN_POINT('',(1.427996660723,0.31491772868)); +#61150 = CARTESIAN_POINT('',(1.499396493759,0.31491772868)); +#61151 = CARTESIAN_POINT('',(1.54699638245,0.31491772868)); +#61152 = CARTESIAN_POINT('',(1.570796326795,0.31491772868)); +#61153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61154 = ORIENTED_EDGE('',*,*,#61155,.F.); +#61155 = EDGE_CURVE('',#60951,#61110,#61156,.T.); +#61156 = SURFACE_CURVE('',#61157,(#61161,#61168),.PCURVE_S1.); +#61157 = LINE('',#61158,#61159); +#61158 = CARTESIAN_POINT('',(2.3,-1.47,2.545511428091)); +#61159 = VECTOR('',#61160,1.); +#61160 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61161 = PCURVE('',#58364,#61162); +#61162 = DEFINITIONAL_REPRESENTATION('',(#61163),#61167); +#61163 = LINE('',#61164,#61165); +#61164 = CARTESIAN_POINT('',(0.313448111358,0.2)); +#61165 = VECTOR('',#61166,1.); +#61166 = DIRECTION('',(0.E+000,1.)); +#61167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61168 = PCURVE('',#60694,#61169); +#61169 = DEFINITIONAL_REPRESENTATION('',(#61170),#61174); +#61170 = LINE('',#61171,#61172); +#61171 = CARTESIAN_POINT('',(0.E+000,0.2)); +#61172 = VECTOR('',#61173,1.); +#61173 = DIRECTION('',(0.E+000,1.)); +#61174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61175 = ADVANCED_FACE('',(#61176),#58177,.T.); +#61176 = FACE_BOUND('',#61177,.F.); +#61177 = EDGE_LOOP('',(#61178,#61179,#61180,#61181,#61204,#61250)); +#61178 = ORIENTED_EDGE('',*,*,#60572,.F.); +#61179 = ORIENTED_EDGE('',*,*,#60475,.F.); +#61180 = ORIENTED_EDGE('',*,*,#58161,.T.); +#61181 = ORIENTED_EDGE('',*,*,#61182,.T.); +#61182 = EDGE_CURVE('',#40208,#61183,#61185,.T.); +#61183 = VERTEX_POINT('',#61184); +#61184 = CARTESIAN_POINT('',(-2.5,-1.313674285394,2.420762596622)); +#61185 = SURFACE_CURVE('',#61186,(#61190,#61197),.PCURVE_S1.); +#61186 = LINE('',#61187,#61188); +#61187 = CARTESIAN_POINT('',(-2.5,-1.225,2.35)); +#61188 = VECTOR('',#61189,1.); +#61189 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#61190 = PCURVE('',#58177,#61191); +#61191 = DEFINITIONAL_REPRESENTATION('',(#61192),#61196); +#61192 = LINE('',#61193,#61194); +#61193 = CARTESIAN_POINT('',(0.E+000,5.)); +#61194 = VECTOR('',#61195,1.); +#61195 = DIRECTION('',(1.,0.E+000)); +#61196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61197 = PCURVE('',#40223,#61198); +#61198 = DEFINITIONAL_REPRESENTATION('',(#61199),#61203); +#61199 = LINE('',#61200,#61201); +#61200 = CARTESIAN_POINT('',(2.35,-1.225)); +#61201 = VECTOR('',#61202,1.); +#61202 = DIRECTION('',(0.623744157346,-0.78162857303)); +#61203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61204 = ORIENTED_EDGE('',*,*,#61205,.F.); +#61205 = EDGE_CURVE('',#61206,#61183,#61208,.T.); +#61206 = VERTEX_POINT('',#61207); +#61207 = CARTESIAN_POINT('',(-2.3,-1.47,2.545511428091)); +#61208 = SURFACE_CURVE('',#61209,(#61214,#61221),.PCURVE_S1.); +#61209 = CIRCLE('',#61210,0.2); +#61210 = AXIS2_PLACEMENT_3D('',#61211,#61212,#61213); +#61211 = CARTESIAN_POINT('',(-2.3,-1.313674285394,2.420762596622)); +#61212 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61213 = DIRECTION('',(0.E+000,-0.78162857303,0.623744157346)); +#61214 = PCURVE('',#58177,#61215); +#61215 = DEFINITIONAL_REPRESENTATION('',(#61216),#61220); +#61216 = CIRCLE('',#61217,0.2); +#61217 = AXIS2_PLACEMENT_2D('',#61218,#61219); +#61218 = CARTESIAN_POINT('',(0.113448111359,4.8)); +#61219 = DIRECTION('',(1.,0.E+000)); +#61220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61221 = PCURVE('',#60867,#61222); +#61222 = DEFINITIONAL_REPRESENTATION('',(#61223),#61249); +#61223 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#61224,#61225,#61226,#61227, + #61228,#61229,#61230,#61231,#61232,#61233,#61234,#61235,#61236, + #61237,#61238,#61239,#61240,#61241,#61242,#61243,#61244,#61245, + #61246,#61247,#61248),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -72977,193 +75966,193 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#58832 = CARTESIAN_POINT('',(1.570796326795,1.551463154839E-002)); -#58833 = CARTESIAN_POINT('',(1.546996382449,1.551463154839E-002)); -#58834 = CARTESIAN_POINT('',(1.499396493759,1.551463154839E-002)); -#58835 = CARTESIAN_POINT('',(1.427996660722,1.551463154839E-002)); -#58836 = CARTESIAN_POINT('',(1.356596827686,1.551463154839E-002)); -#58837 = CARTESIAN_POINT('',(1.28519699465,1.551463154839E-002)); -#58838 = CARTESIAN_POINT('',(1.213797161614,1.551463154839E-002)); -#58839 = CARTESIAN_POINT('',(1.142397328577,1.551463154839E-002)); -#58840 = CARTESIAN_POINT('',(1.070997495541,1.551463154839E-002)); -#58841 = CARTESIAN_POINT('',(0.999597662505,1.551463154839E-002)); -#58842 = CARTESIAN_POINT('',(0.928197829469,1.551463154839E-002)); -#58843 = CARTESIAN_POINT('',(0.856797996432,1.551463154839E-002)); -#58844 = CARTESIAN_POINT('',(0.785398163396,1.551463154839E-002)); -#58845 = CARTESIAN_POINT('',(0.71399833036,1.551463154839E-002)); -#58846 = CARTESIAN_POINT('',(0.642598497324,1.551463154839E-002)); -#58847 = CARTESIAN_POINT('',(0.571198664287,1.551463154839E-002)); -#58848 = CARTESIAN_POINT('',(0.499798831251,1.551463154839E-002)); -#58849 = CARTESIAN_POINT('',(0.428398998215,1.551463154839E-002)); -#58850 = CARTESIAN_POINT('',(0.356999165179,1.551463154839E-002)); -#58851 = CARTESIAN_POINT('',(0.285599332143,1.551463154839E-002)); -#58852 = CARTESIAN_POINT('',(0.214199499106,1.551463154839E-002)); -#58853 = CARTESIAN_POINT('',(0.14279966607,1.551463154839E-002)); -#58854 = CARTESIAN_POINT('',(7.139983303378E-002,1.551463154839E-002)); -#58855 = CARTESIAN_POINT('',(2.379994434416E-002,1.551463154839E-002)); -#58856 = CARTESIAN_POINT('',(0.E+000,1.551463154839E-002)); -#58857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58858 = ORIENTED_EDGE('',*,*,#58859,.F.); -#58859 = EDGE_CURVE('',#58154,#58814,#58860,.T.); -#58860 = SURFACE_CURVE('',#58861,(#58865,#58872),.PCURVE_S1.); -#58861 = LINE('',#58862,#58863); -#58862 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); -#58863 = VECTOR('',#58864,1.); -#58864 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58865 = PCURVE('',#55785,#58866); -#58866 = DEFINITIONAL_REPRESENTATION('',(#58867),#58871); -#58867 = LINE('',#58868,#58869); -#58868 = CARTESIAN_POINT('',(0.313448111358,2.71)); -#58869 = VECTOR('',#58870,1.); -#58870 = DIRECTION('',(0.E+000,1.)); -#58871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58872 = PCURVE('',#58168,#58873); -#58873 = DEFINITIONAL_REPRESENTATION('',(#58874),#58878); -#58874 = LINE('',#58875,#58876); -#58875 = CARTESIAN_POINT('',(0.E+000,2.71)); -#58876 = VECTOR('',#58877,1.); -#58877 = DIRECTION('',(0.E+000,1.)); -#58878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58879 = ADVANCED_FACE('',(#58880),#38175,.F.); -#58880 = FACE_BOUND('',#58881,.F.); -#58881 = EDGE_LOOP('',(#58882,#58883,#58884,#58905,#58906,#58907)); -#58882 = ORIENTED_EDGE('',*,*,#58604,.F.); -#58883 = ORIENTED_EDGE('',*,*,#58410,.T.); -#58884 = ORIENTED_EDGE('',*,*,#58885,.T.); -#58885 = EDGE_CURVE('',#58389,#41446,#58886,.T.); -#58886 = SURFACE_CURVE('',#58887,(#58892,#58899),.PCURVE_S1.); -#58887 = CIRCLE('',#58888,0.29); -#58888 = AXIS2_PLACEMENT_3D('',#58889,#58890,#58891); -#58889 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); -#58890 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58891 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58892 = PCURVE('',#38175,#58893); -#58893 = DEFINITIONAL_REPRESENTATION('',(#58894),#58898); -#58894 = CIRCLE('',#58895,0.29); -#58895 = AXIS2_PLACEMENT_2D('',#58896,#58897); -#58896 = CARTESIAN_POINT('',(2.354813742174,-1.215)); -#58897 = DIRECTION('',(0.78162857303,0.623744157346)); -#58898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58899 = PCURVE('',#41484,#58900); -#58900 = DEFINITIONAL_REPRESENTATION('',(#58901),#58904); -#58901 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58902,#58903),.UNSPECIFIED., +#61224 = CARTESIAN_POINT('',(1.570796326795,1.551463154839E-002)); +#61225 = CARTESIAN_POINT('',(1.546996382449,1.551463154839E-002)); +#61226 = CARTESIAN_POINT('',(1.499396493759,1.551463154839E-002)); +#61227 = CARTESIAN_POINT('',(1.427996660722,1.551463154839E-002)); +#61228 = CARTESIAN_POINT('',(1.356596827686,1.551463154839E-002)); +#61229 = CARTESIAN_POINT('',(1.28519699465,1.551463154839E-002)); +#61230 = CARTESIAN_POINT('',(1.213797161614,1.551463154839E-002)); +#61231 = CARTESIAN_POINT('',(1.142397328577,1.551463154839E-002)); +#61232 = CARTESIAN_POINT('',(1.070997495541,1.551463154839E-002)); +#61233 = CARTESIAN_POINT('',(0.999597662505,1.551463154839E-002)); +#61234 = CARTESIAN_POINT('',(0.928197829469,1.551463154839E-002)); +#61235 = CARTESIAN_POINT('',(0.856797996432,1.551463154839E-002)); +#61236 = CARTESIAN_POINT('',(0.785398163396,1.551463154839E-002)); +#61237 = CARTESIAN_POINT('',(0.71399833036,1.551463154839E-002)); +#61238 = CARTESIAN_POINT('',(0.642598497324,1.551463154839E-002)); +#61239 = CARTESIAN_POINT('',(0.571198664287,1.551463154839E-002)); +#61240 = CARTESIAN_POINT('',(0.499798831251,1.551463154839E-002)); +#61241 = CARTESIAN_POINT('',(0.428398998215,1.551463154839E-002)); +#61242 = CARTESIAN_POINT('',(0.356999165179,1.551463154839E-002)); +#61243 = CARTESIAN_POINT('',(0.285599332143,1.551463154839E-002)); +#61244 = CARTESIAN_POINT('',(0.214199499106,1.551463154839E-002)); +#61245 = CARTESIAN_POINT('',(0.14279966607,1.551463154839E-002)); +#61246 = CARTESIAN_POINT('',(7.139983303378E-002,1.551463154839E-002)); +#61247 = CARTESIAN_POINT('',(2.379994434416E-002,1.551463154839E-002)); +#61248 = CARTESIAN_POINT('',(0.E+000,1.551463154839E-002)); +#61249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61250 = ORIENTED_EDGE('',*,*,#61251,.F.); +#61251 = EDGE_CURVE('',#60546,#61206,#61252,.T.); +#61252 = SURFACE_CURVE('',#61253,(#61257,#61264),.PCURVE_S1.); +#61253 = LINE('',#61254,#61255); +#61254 = CARTESIAN_POINT('',(-0.21,-1.47,2.545511428091)); +#61255 = VECTOR('',#61256,1.); +#61256 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61257 = PCURVE('',#58177,#61258); +#61258 = DEFINITIONAL_REPRESENTATION('',(#61259),#61263); +#61259 = LINE('',#61260,#61261); +#61260 = CARTESIAN_POINT('',(0.313448111358,2.71)); +#61261 = VECTOR('',#61262,1.); +#61262 = DIRECTION('',(0.E+000,1.)); +#61263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61264 = PCURVE('',#60560,#61265); +#61265 = DEFINITIONAL_REPRESENTATION('',(#61266),#61270); +#61266 = LINE('',#61267,#61268); +#61267 = CARTESIAN_POINT('',(0.E+000,2.71)); +#61268 = VECTOR('',#61269,1.); +#61269 = DIRECTION('',(0.E+000,1.)); +#61270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61271 = ADVANCED_FACE('',(#61272),#40567,.F.); +#61272 = FACE_BOUND('',#61273,.F.); +#61273 = EDGE_LOOP('',(#61274,#61275,#61276,#61297,#61298,#61299)); +#61274 = ORIENTED_EDGE('',*,*,#60996,.F.); +#61275 = ORIENTED_EDGE('',*,*,#60802,.T.); +#61276 = ORIENTED_EDGE('',*,*,#61277,.T.); +#61277 = EDGE_CURVE('',#60781,#43838,#61278,.T.); +#61278 = SURFACE_CURVE('',#61279,(#61284,#61291),.PCURVE_S1.); +#61279 = CIRCLE('',#61280,0.29); +#61280 = AXIS2_PLACEMENT_3D('',#61281,#61282,#61283); +#61281 = CARTESIAN_POINT('',(2.5,-1.215,2.354813742174)); +#61282 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61283 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#61284 = PCURVE('',#40567,#61285); +#61285 = DEFINITIONAL_REPRESENTATION('',(#61286),#61290); +#61286 = CIRCLE('',#61287,0.29); +#61287 = AXIS2_PLACEMENT_2D('',#61288,#61289); +#61288 = CARTESIAN_POINT('',(2.354813742174,-1.215)); +#61289 = DIRECTION('',(0.78162857303,0.623744157346)); +#61290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61291 = PCURVE('',#43876,#61292); +#61292 = DEFINITIONAL_REPRESENTATION('',(#61293),#61296); +#61293 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61294,#61295),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525926),.PIECEWISE_BEZIER_KNOTS.); -#58902 = CARTESIAN_POINT('',(0.673523800868,0.E+000)); -#58903 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#58904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58905 = ORIENTED_EDGE('',*,*,#41445,.T.); -#58906 = ORIENTED_EDGE('',*,*,#38159,.F.); -#58907 = ORIENTED_EDGE('',*,*,#58672,.T.); -#58908 = ADVANCED_FACE('',(#58909),#41484,.T.); -#58909 = FACE_BOUND('',#58910,.T.); -#58910 = EDGE_LOOP('',(#58911,#58936,#58937,#58938)); -#58911 = ORIENTED_EDGE('',*,*,#58912,.F.); -#58912 = EDGE_CURVE('',#58366,#41469,#58913,.T.); -#58913 = SURFACE_CURVE('',#58914,(#58919,#58925),.PCURVE_S1.); -#58914 = CIRCLE('',#58915,0.29); -#58915 = AXIS2_PLACEMENT_3D('',#58916,#58917,#58918); -#58916 = CARTESIAN_POINT('',(1.E-002,-1.215,2.354813742174)); -#58917 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58918 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58919 = PCURVE('',#41484,#58920); -#58920 = DEFINITIONAL_REPRESENTATION('',(#58921),#58924); -#58921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58922,#58923),.UNSPECIFIED., +#61294 = CARTESIAN_POINT('',(0.673523800868,0.E+000)); +#61295 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#61296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61297 = ORIENTED_EDGE('',*,*,#43837,.T.); +#61298 = ORIENTED_EDGE('',*,*,#40551,.F.); +#61299 = ORIENTED_EDGE('',*,*,#61064,.T.); +#61300 = ADVANCED_FACE('',(#61301),#43876,.T.); +#61301 = FACE_BOUND('',#61302,.T.); +#61302 = EDGE_LOOP('',(#61303,#61328,#61329,#61330)); +#61303 = ORIENTED_EDGE('',*,*,#61304,.F.); +#61304 = EDGE_CURVE('',#60758,#43861,#61305,.T.); +#61305 = SURFACE_CURVE('',#61306,(#61311,#61317),.PCURVE_S1.); +#61306 = CIRCLE('',#61307,0.29); +#61307 = AXIS2_PLACEMENT_3D('',#61308,#61309,#61310); +#61308 = CARTESIAN_POINT('',(1.E-002,-1.215,2.354813742174)); +#61309 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61310 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#61311 = PCURVE('',#43876,#61312); +#61312 = DEFINITIONAL_REPRESENTATION('',(#61313),#61316); +#61313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61314,#61315),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525926),.PIECEWISE_BEZIER_KNOTS.); -#58922 = CARTESIAN_POINT('',(0.673523800868,2.49)); -#58923 = CARTESIAN_POINT('',(1.570796326795,2.49)); -#58924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#61314 = CARTESIAN_POINT('',(0.673523800868,2.49)); +#61315 = CARTESIAN_POINT('',(1.570796326795,2.49)); +#61316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#58925 = PCURVE('',#41511,#58926); -#58926 = DEFINITIONAL_REPRESENTATION('',(#58927),#58935); -#58927 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#58928,#58929,#58930,#58931 - ,#58932,#58933,#58934),.UNSPECIFIED.,.T.,.F.) +#61317 = PCURVE('',#43903,#61318); +#61318 = DEFINITIONAL_REPRESENTATION('',(#61319),#61327); +#61319 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#61320,#61321,#61322,#61323 + ,#61324,#61325,#61326),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#58928 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); -#58929 = CARTESIAN_POINT('',(0.523028049143,-0.88349372196)); -#58930 = CARTESIAN_POINT('',(0.339671322735,-0.415861055349)); -#58931 = CARTESIAN_POINT('',(0.156314596327,5.177161126084E-002)); -#58932 = CARTESIAN_POINT('',(0.652974728455,-2.325313902022E-002)); -#58933 = CARTESIAN_POINT('',(1.149634860583,-9.827788930129E-002)); -#58934 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); -#58935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58936 = ORIENTED_EDGE('',*,*,#58388,.F.); -#58937 = ORIENTED_EDGE('',*,*,#58885,.T.); -#58938 = ORIENTED_EDGE('',*,*,#41468,.T.); -#58939 = ADVANCED_FACE('',(#58940),#42249,.T.); -#58940 = FACE_BOUND('',#58941,.T.); -#58941 = EDGE_LOOP('',(#58942,#58943,#58944,#58965)); -#58942 = ORIENTED_EDGE('',*,*,#58057,.T.); -#58943 = ORIENTED_EDGE('',*,*,#42233,.T.); -#58944 = ORIENTED_EDGE('',*,*,#58945,.F.); -#58945 = EDGE_CURVE('',#58510,#42234,#58946,.T.); -#58946 = SURFACE_CURVE('',#58947,(#58952,#58958),.PCURVE_S1.); -#58947 = CIRCLE('',#58948,0.29); -#58948 = AXIS2_PLACEMENT_3D('',#58949,#58950,#58951); -#58949 = CARTESIAN_POINT('',(-2.5,-1.215,2.354813742174)); -#58950 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#58951 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#58952 = PCURVE('',#42249,#58953); -#58953 = DEFINITIONAL_REPRESENTATION('',(#58954),#58957); -#58954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#58955,#58956),.UNSPECIFIED., +#61320 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); +#61321 = CARTESIAN_POINT('',(0.523028049143,-0.88349372196)); +#61322 = CARTESIAN_POINT('',(0.339671322735,-0.415861055349)); +#61323 = CARTESIAN_POINT('',(0.156314596327,5.177161126084E-002)); +#61324 = CARTESIAN_POINT('',(0.652974728455,-2.325313902022E-002)); +#61325 = CARTESIAN_POINT('',(1.149634860583,-9.827788930129E-002)); +#61326 = CARTESIAN_POINT('',(0.836331454863,-0.49088580563)); +#61327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61328 = ORIENTED_EDGE('',*,*,#60780,.F.); +#61329 = ORIENTED_EDGE('',*,*,#61277,.T.); +#61330 = ORIENTED_EDGE('',*,*,#43860,.T.); +#61331 = ADVANCED_FACE('',(#61332),#44641,.T.); +#61332 = FACE_BOUND('',#61333,.T.); +#61333 = EDGE_LOOP('',(#61334,#61335,#61336,#61357)); +#61334 = ORIENTED_EDGE('',*,*,#60449,.T.); +#61335 = ORIENTED_EDGE('',*,*,#44625,.T.); +#61336 = ORIENTED_EDGE('',*,*,#61337,.F.); +#61337 = EDGE_CURVE('',#60902,#44626,#61338,.T.); +#61338 = SURFACE_CURVE('',#61339,(#61344,#61350),.PCURVE_S1.); +#61339 = CIRCLE('',#61340,0.29); +#61340 = AXIS2_PLACEMENT_3D('',#61341,#61342,#61343); +#61341 = CARTESIAN_POINT('',(-2.5,-1.215,2.354813742174)); +#61342 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61343 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#61344 = PCURVE('',#44641,#61345); +#61345 = DEFINITIONAL_REPRESENTATION('',(#61346),#61349); +#61346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61347,#61348),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525926),.PIECEWISE_BEZIER_KNOTS.); -#58955 = CARTESIAN_POINT('',(0.673523800868,5.)); -#58956 = CARTESIAN_POINT('',(1.570796326795,5.)); -#58957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58958 = PCURVE('',#37831,#58959); -#58959 = DEFINITIONAL_REPRESENTATION('',(#58960),#58964); -#58960 = CIRCLE('',#58961,0.29); -#58961 = AXIS2_PLACEMENT_2D('',#58962,#58963); -#58962 = CARTESIAN_POINT('',(2.354813742174,-1.215)); -#58963 = DIRECTION('',(0.78162857303,0.623744157346)); -#58964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58965 = ORIENTED_EDGE('',*,*,#58532,.F.); -#58966 = ADVANCED_FACE('',(#58967),#41511,.F.); -#58967 = FACE_BOUND('',#58968,.F.); -#58968 = EDGE_LOOP('',(#58969,#59012,#59013,#59014,#59015,#59016,#59036, - #59037,#59038)); -#58969 = ORIENTED_EDGE('',*,*,#58970,.T.); -#58970 = EDGE_CURVE('',#58315,#58695,#58971,.T.); -#58971 = SURFACE_CURVE('',#58972,(#58976,#58983),.PCURVE_S1.); -#58972 = LINE('',#58973,#58974); -#58973 = CARTESIAN_POINT('',(1.E-002,-1.12655103819,2.655251168531)); -#58974 = VECTOR('',#58975,1.); -#58975 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#58976 = PCURVE('',#41511,#58977); -#58977 = DEFINITIONAL_REPRESENTATION('',(#58978),#58982); -#58978 = LINE('',#58979,#58980); -#58979 = CARTESIAN_POINT('',(0.910096595041,-0.39844896181)); -#58980 = VECTOR('',#58981,1.); -#58981 = DIRECTION('',(-0.78162857303,0.623744157346)); -#58982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#58983 = PCURVE('',#58331,#58984); -#58984 = DEFINITIONAL_REPRESENTATION('',(#58985),#59011); -#58985 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#58986,#58987,#58988,#58989, - #58990,#58991,#58992,#58993,#58994,#58995,#58996,#58997,#58998, - #58999,#59000,#59001,#59002,#59003,#59004,#59005,#59006,#59007, - #59008,#59009,#59010),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#61347 = CARTESIAN_POINT('',(0.673523800868,5.)); +#61348 = CARTESIAN_POINT('',(1.570796326795,5.)); +#61349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61350 = PCURVE('',#40223,#61351); +#61351 = DEFINITIONAL_REPRESENTATION('',(#61352),#61356); +#61352 = CIRCLE('',#61353,0.29); +#61353 = AXIS2_PLACEMENT_2D('',#61354,#61355); +#61354 = CARTESIAN_POINT('',(2.354813742174,-1.215)); +#61355 = DIRECTION('',(0.78162857303,0.623744157346)); +#61356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61357 = ORIENTED_EDGE('',*,*,#60924,.F.); +#61358 = ADVANCED_FACE('',(#61359),#43903,.F.); +#61359 = FACE_BOUND('',#61360,.F.); +#61360 = EDGE_LOOP('',(#61361,#61404,#61405,#61406,#61407,#61408,#61428, + #61429,#61430)); +#61361 = ORIENTED_EDGE('',*,*,#61362,.T.); +#61362 = EDGE_CURVE('',#60707,#61087,#61363,.T.); +#61363 = SURFACE_CURVE('',#61364,(#61368,#61375),.PCURVE_S1.); +#61364 = LINE('',#61365,#61366); +#61365 = CARTESIAN_POINT('',(1.E-002,-1.12655103819,2.655251168531)); +#61366 = VECTOR('',#61367,1.); +#61367 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61368 = PCURVE('',#43903,#61369); +#61369 = DEFINITIONAL_REPRESENTATION('',(#61370),#61374); +#61370 = LINE('',#61371,#61372); +#61371 = CARTESIAN_POINT('',(0.910096595041,-0.39844896181)); +#61372 = VECTOR('',#61373,1.); +#61373 = DIRECTION('',(-0.78162857303,0.623744157346)); +#61374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61375 = PCURVE('',#60723,#61376); +#61376 = DEFINITIONAL_REPRESENTATION('',(#61377),#61403); +#61377 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#61378,#61379,#61380,#61381, + #61382,#61383,#61384,#61385,#61386,#61387,#61388,#61389,#61390, + #61391,#61392,#61393,#61394,#61395,#61396,#61397,#61398,#61399, + #61400,#61401,#61402),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363637E-002, 2.727272727274E-002,4.090909090911E-002,5.454545454548E-002, 6.818181818185E-002,8.181818181822E-002,9.545454545459E-002, @@ -73171,152 +76160,152 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454546,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#58986 = CARTESIAN_POINT('',(1.570796326795,1.491772867999E-002)); -#58987 = CARTESIAN_POINT('',(1.570796326795,1.946318322545E-002)); -#58988 = CARTESIAN_POINT('',(1.570796326795,2.855409231636E-002)); -#58989 = CARTESIAN_POINT('',(1.570796326795,4.219045595273E-002)); -#58990 = CARTESIAN_POINT('',(1.570796326795,5.58268195891E-002)); -#58991 = CARTESIAN_POINT('',(1.570796326795,6.946318322547E-002)); -#58992 = CARTESIAN_POINT('',(1.570796326795,8.309954686184E-002)); -#58993 = CARTESIAN_POINT('',(1.570796326795,9.673591049821E-002)); -#58994 = CARTESIAN_POINT('',(1.570796326795,0.110372274135)); -#58995 = CARTESIAN_POINT('',(1.570796326795,0.124008637771)); -#58996 = CARTESIAN_POINT('',(1.570796326795,0.137645001407)); -#58997 = CARTESIAN_POINT('',(1.570796326795,0.151281365044)); -#58998 = CARTESIAN_POINT('',(1.570796326795,0.16491772868)); -#58999 = CARTESIAN_POINT('',(1.570796326795,0.178554092316)); -#59000 = CARTESIAN_POINT('',(1.570796326795,0.192190455953)); -#59001 = CARTESIAN_POINT('',(1.570796326795,0.205826819589)); -#59002 = CARTESIAN_POINT('',(1.570796326795,0.219463183226)); -#59003 = CARTESIAN_POINT('',(1.570796326795,0.233099546862)); -#59004 = CARTESIAN_POINT('',(1.570796326795,0.246735910498)); -#59005 = CARTESIAN_POINT('',(1.570796326795,0.260372274135)); -#59006 = CARTESIAN_POINT('',(1.570796326795,0.274008637771)); -#59007 = CARTESIAN_POINT('',(1.570796326795,0.287645001407)); -#59008 = CARTESIAN_POINT('',(1.570796326795,0.301281365044)); -#59009 = CARTESIAN_POINT('',(1.570796326795,0.310372274135)); -#59010 = CARTESIAN_POINT('',(1.570796326795,0.31491772868)); -#59011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59012 = ORIENTED_EDGE('',*,*,#58694,.F.); -#59013 = ORIENTED_EDGE('',*,*,#55935,.T.); -#59014 = ORIENTED_EDGE('',*,*,#56673,.F.); -#59015 = ORIENTED_EDGE('',*,*,#57156,.F.); -#59016 = ORIENTED_EDGE('',*,*,#59017,.T.); -#59017 = EDGE_CURVE('',#57134,#41496,#59018,.T.); -#59018 = SURFACE_CURVE('',#59019,(#59023,#59030),.PCURVE_S1.); -#59019 = LINE('',#59020,#59021); -#59020 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); -#59021 = VECTOR('',#59022,1.); -#59022 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59023 = PCURVE('',#41511,#59024); -#59024 = DEFINITIONAL_REPRESENTATION('',(#59025),#59029); -#59025 = LINE('',#59026,#59027); -#59026 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#59027 = VECTOR('',#59028,1.); -#59028 = DIRECTION('',(0.E+000,-1.)); -#59029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59030 = PCURVE('',#41544,#59031); -#59031 = DEFINITIONAL_REPRESENTATION('',(#59032),#59035); -#59032 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59033,#59034),.UNSPECIFIED., +#61378 = CARTESIAN_POINT('',(1.570796326795,1.491772867999E-002)); +#61379 = CARTESIAN_POINT('',(1.570796326795,1.946318322545E-002)); +#61380 = CARTESIAN_POINT('',(1.570796326795,2.855409231636E-002)); +#61381 = CARTESIAN_POINT('',(1.570796326795,4.219045595273E-002)); +#61382 = CARTESIAN_POINT('',(1.570796326795,5.58268195891E-002)); +#61383 = CARTESIAN_POINT('',(1.570796326795,6.946318322547E-002)); +#61384 = CARTESIAN_POINT('',(1.570796326795,8.309954686184E-002)); +#61385 = CARTESIAN_POINT('',(1.570796326795,9.673591049821E-002)); +#61386 = CARTESIAN_POINT('',(1.570796326795,0.110372274135)); +#61387 = CARTESIAN_POINT('',(1.570796326795,0.124008637771)); +#61388 = CARTESIAN_POINT('',(1.570796326795,0.137645001407)); +#61389 = CARTESIAN_POINT('',(1.570796326795,0.151281365044)); +#61390 = CARTESIAN_POINT('',(1.570796326795,0.16491772868)); +#61391 = CARTESIAN_POINT('',(1.570796326795,0.178554092316)); +#61392 = CARTESIAN_POINT('',(1.570796326795,0.192190455953)); +#61393 = CARTESIAN_POINT('',(1.570796326795,0.205826819589)); +#61394 = CARTESIAN_POINT('',(1.570796326795,0.219463183226)); +#61395 = CARTESIAN_POINT('',(1.570796326795,0.233099546862)); +#61396 = CARTESIAN_POINT('',(1.570796326795,0.246735910498)); +#61397 = CARTESIAN_POINT('',(1.570796326795,0.260372274135)); +#61398 = CARTESIAN_POINT('',(1.570796326795,0.274008637771)); +#61399 = CARTESIAN_POINT('',(1.570796326795,0.287645001407)); +#61400 = CARTESIAN_POINT('',(1.570796326795,0.301281365044)); +#61401 = CARTESIAN_POINT('',(1.570796326795,0.310372274135)); +#61402 = CARTESIAN_POINT('',(1.570796326795,0.31491772868)); +#61403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61404 = ORIENTED_EDGE('',*,*,#61086,.F.); +#61405 = ORIENTED_EDGE('',*,*,#58327,.T.); +#61406 = ORIENTED_EDGE('',*,*,#59065,.F.); +#61407 = ORIENTED_EDGE('',*,*,#59548,.F.); +#61408 = ORIENTED_EDGE('',*,*,#61409,.T.); +#61409 = EDGE_CURVE('',#59526,#43888,#61410,.T.); +#61410 = SURFACE_CURVE('',#61411,(#61415,#61422),.PCURVE_S1.); +#61411 = LINE('',#61412,#61413); +#61412 = CARTESIAN_POINT('',(1.E-002,-1.125,1.74515457349)); +#61413 = VECTOR('',#61414,1.); +#61414 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61415 = PCURVE('',#43903,#61416); +#61416 = DEFINITIONAL_REPRESENTATION('',(#61417),#61421); +#61417 = LINE('',#61418,#61419); +#61418 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#61419 = VECTOR('',#61420,1.); +#61420 = DIRECTION('',(0.E+000,-1.)); +#61421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61422 = PCURVE('',#43936,#61423); +#61423 = DEFINITIONAL_REPRESENTATION('',(#61424),#61427); +#61424 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61425,#61426),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59033 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#59034 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#59035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59036 = ORIENTED_EDGE('',*,*,#41495,.F.); -#59037 = ORIENTED_EDGE('',*,*,#58912,.F.); -#59038 = ORIENTED_EDGE('',*,*,#58365,.T.); -#59039 = ADVANCED_FACE('',(#59040),#58331,.T.); -#59040 = FACE_BOUND('',#59041,.T.); -#59041 = EDGE_LOOP('',(#59042,#59043,#59063,#59064)); -#59042 = ORIENTED_EDGE('',*,*,#58717,.F.); -#59043 = ORIENTED_EDGE('',*,*,#59044,.F.); -#59044 = EDGE_CURVE('',#58287,#58718,#59045,.T.); -#59045 = SURFACE_CURVE('',#59046,(#59050,#59056),.PCURVE_S1.); -#59046 = LINE('',#59047,#59048); -#59047 = CARTESIAN_POINT('',(0.21,-1.282876752796,2.78)); -#59048 = VECTOR('',#59049,1.); -#59049 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); -#59050 = PCURVE('',#58331,#59051); -#59051 = DEFINITIONAL_REPRESENTATION('',(#59052),#59055); -#59052 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59053,#59054),.UNSPECIFIED., +#61425 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#61426 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#61427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61428 = ORIENTED_EDGE('',*,*,#43887,.F.); +#61429 = ORIENTED_EDGE('',*,*,#61304,.F.); +#61430 = ORIENTED_EDGE('',*,*,#60757,.T.); +#61431 = ADVANCED_FACE('',(#61432),#60723,.T.); +#61432 = FACE_BOUND('',#61433,.T.); +#61433 = EDGE_LOOP('',(#61434,#61435,#61455,#61456)); +#61434 = ORIENTED_EDGE('',*,*,#61109,.F.); +#61435 = ORIENTED_EDGE('',*,*,#61436,.F.); +#61436 = EDGE_CURVE('',#60679,#61110,#61437,.T.); +#61437 = SURFACE_CURVE('',#61438,(#61442,#61448),.PCURVE_S1.); +#61438 = LINE('',#61439,#61440); +#61439 = CARTESIAN_POINT('',(0.21,-1.282876752796,2.78)); +#61440 = VECTOR('',#61441,1.); +#61441 = DIRECTION('',(0.E+000,-0.623744157346,-0.78162857303)); +#61442 = PCURVE('',#60723,#61443); +#61443 = DEFINITIONAL_REPRESENTATION('',(#61444),#61447); +#61444 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61445,#61446),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#59053 = CARTESIAN_POINT('',(0.E+000,1.491772868023E-002)); -#59054 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); -#59055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59056 = PCURVE('',#58302,#59057); -#59057 = DEFINITIONAL_REPRESENTATION('',(#59058),#59062); -#59058 = LINE('',#59059,#59060); -#59059 = CARTESIAN_POINT('',(0.3,2.29)); -#59060 = VECTOR('',#59061,1.); -#59061 = DIRECTION('',(-1.,0.E+000)); -#59062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59063 = ORIENTED_EDGE('',*,*,#58314,.F.); -#59064 = ORIENTED_EDGE('',*,*,#58970,.T.); -#59065 = ADVANCED_FACE('',(#59066),#58302,.T.); -#59066 = FACE_BOUND('',#59067,.F.); -#59067 = EDGE_LOOP('',(#59068,#59069,#59070,#59071)); -#59068 = ORIENTED_EDGE('',*,*,#58648,.T.); -#59069 = ORIENTED_EDGE('',*,*,#58763,.T.); -#59070 = ORIENTED_EDGE('',*,*,#59044,.F.); -#59071 = ORIENTED_EDGE('',*,*,#58286,.F.); -#59072 = ADVANCED_FACE('',(#59073),#58168,.T.); -#59073 = FACE_BOUND('',#59074,.F.); -#59074 = EDGE_LOOP('',(#59075,#59076,#59077,#59097)); -#59075 = ORIENTED_EDGE('',*,*,#58153,.F.); -#59076 = ORIENTED_EDGE('',*,*,#58859,.T.); -#59077 = ORIENTED_EDGE('',*,*,#59078,.T.); -#59078 = EDGE_CURVE('',#58814,#58436,#59079,.T.); -#59079 = SURFACE_CURVE('',#59080,(#59084,#59091),.PCURVE_S1.); -#59080 = LINE('',#59081,#59082); -#59081 = CARTESIAN_POINT('',(-2.3,-1.47,2.545511428091)); -#59082 = VECTOR('',#59083,1.); -#59083 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#59084 = PCURVE('',#58168,#59085); -#59085 = DEFINITIONAL_REPRESENTATION('',(#59086),#59090); -#59086 = LINE('',#59087,#59088); -#59087 = CARTESIAN_POINT('',(0.E+000,4.8)); -#59088 = VECTOR('',#59089,1.); -#59089 = DIRECTION('',(1.,0.E+000)); -#59090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59091 = PCURVE('',#58475,#59092); -#59092 = DEFINITIONAL_REPRESENTATION('',(#59093),#59096); -#59093 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59094,#59095),.UNSPECIFIED., +#61445 = CARTESIAN_POINT('',(0.E+000,1.491772868023E-002)); +#61446 = CARTESIAN_POINT('',(0.E+000,0.31491772868)); +#61447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61448 = PCURVE('',#60694,#61449); +#61449 = DEFINITIONAL_REPRESENTATION('',(#61450),#61454); +#61450 = LINE('',#61451,#61452); +#61451 = CARTESIAN_POINT('',(0.3,2.29)); +#61452 = VECTOR('',#61453,1.); +#61453 = DIRECTION('',(-1.,0.E+000)); +#61454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61455 = ORIENTED_EDGE('',*,*,#60706,.F.); +#61456 = ORIENTED_EDGE('',*,*,#61362,.T.); +#61457 = ADVANCED_FACE('',(#61458),#60694,.T.); +#61458 = FACE_BOUND('',#61459,.F.); +#61459 = EDGE_LOOP('',(#61460,#61461,#61462,#61463)); +#61460 = ORIENTED_EDGE('',*,*,#61040,.T.); +#61461 = ORIENTED_EDGE('',*,*,#61155,.T.); +#61462 = ORIENTED_EDGE('',*,*,#61436,.F.); +#61463 = ORIENTED_EDGE('',*,*,#60678,.F.); +#61464 = ADVANCED_FACE('',(#61465),#60560,.T.); +#61465 = FACE_BOUND('',#61466,.F.); +#61466 = EDGE_LOOP('',(#61467,#61468,#61469,#61489)); +#61467 = ORIENTED_EDGE('',*,*,#60545,.F.); +#61468 = ORIENTED_EDGE('',*,*,#61251,.T.); +#61469 = ORIENTED_EDGE('',*,*,#61470,.T.); +#61470 = EDGE_CURVE('',#61206,#60828,#61471,.T.); +#61471 = SURFACE_CURVE('',#61472,(#61476,#61483),.PCURVE_S1.); +#61472 = LINE('',#61473,#61474); +#61473 = CARTESIAN_POINT('',(-2.3,-1.47,2.545511428091)); +#61474 = VECTOR('',#61475,1.); +#61475 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#61476 = PCURVE('',#60560,#61477); +#61477 = DEFINITIONAL_REPRESENTATION('',(#61478),#61482); +#61478 = LINE('',#61479,#61480); +#61479 = CARTESIAN_POINT('',(0.E+000,4.8)); +#61480 = VECTOR('',#61481,1.); +#61481 = DIRECTION('',(1.,0.E+000)); +#61482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61483 = PCURVE('',#60867,#61484); +#61484 = DEFINITIONAL_REPRESENTATION('',(#61485),#61488); +#61485 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61486,#61487),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#59094 = CARTESIAN_POINT('',(1.570796326795,1.551463154815E-002)); -#59095 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#59096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59097 = ORIENTED_EDGE('',*,*,#58435,.F.); -#59098 = ADVANCED_FACE('',(#59099),#58475,.T.); -#59099 = FACE_BOUND('',#59100,.T.); -#59100 = EDGE_LOOP('',(#59101,#59102,#59145,#59146)); -#59101 = ORIENTED_EDGE('',*,*,#58458,.F.); -#59102 = ORIENTED_EDGE('',*,*,#59103,.F.); -#59103 = EDGE_CURVE('',#58791,#58459,#59104,.T.); -#59104 = SURFACE_CURVE('',#59105,(#59109,#59138),.PCURVE_S1.); -#59105 = LINE('',#59106,#59107); -#59106 = CARTESIAN_POINT('',(-2.5,-1.313674285394,2.420762596622)); -#59107 = VECTOR('',#59108,1.); -#59108 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); -#59109 = PCURVE('',#58475,#59110); -#59110 = DEFINITIONAL_REPRESENTATION('',(#59111),#59137); -#59111 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#59112,#59113,#59114,#59115, - #59116,#59117,#59118,#59119,#59120,#59121,#59122,#59123,#59124, - #59125,#59126,#59127,#59128,#59129,#59130,#59131,#59132,#59133, - #59134,#59135,#59136),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#61486 = CARTESIAN_POINT('',(1.570796326795,1.551463154815E-002)); +#61487 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#61488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61489 = ORIENTED_EDGE('',*,*,#60827,.F.); +#61490 = ADVANCED_FACE('',(#61491),#60867,.T.); +#61491 = FACE_BOUND('',#61492,.T.); +#61492 = EDGE_LOOP('',(#61493,#61494,#61537,#61538)); +#61493 = ORIENTED_EDGE('',*,*,#60850,.F.); +#61494 = ORIENTED_EDGE('',*,*,#61495,.F.); +#61495 = EDGE_CURVE('',#61183,#60851,#61496,.T.); +#61496 = SURFACE_CURVE('',#61497,(#61501,#61530),.PCURVE_S1.); +#61497 = LINE('',#61498,#61499); +#61498 = CARTESIAN_POINT('',(-2.5,-1.313674285394,2.420762596622)); +#61499 = VECTOR('',#61500,1.); +#61500 = DIRECTION('',(0.E+000,0.623744157346,0.78162857303)); +#61501 = PCURVE('',#60867,#61502); +#61502 = DEFINITIONAL_REPRESENTATION('',(#61503),#61529); +#61503 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#61504,#61505,#61506,#61507, + #61508,#61509,#61510,#61511,#61512,#61513,#61514,#61515,#61516, + #61517,#61518,#61519,#61520,#61521,#61522,#61523,#61524,#61525, + #61526,#61527,#61528),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363637E-002, 2.727272727274E-002,4.090909090911E-002,5.454545454548E-002, 6.818181818185E-002,8.181818181822E-002,9.545454545459E-002, @@ -73324,9472 +76313,9472 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454546,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#59112 = CARTESIAN_POINT('',(0.E+000,1.551463154839E-002)); -#59113 = CARTESIAN_POINT('',(-1.220357148668E-012,2.006008609385E-002)); -#59114 = CARTESIAN_POINT('',(-2.354560990625E-012,2.915099518476E-002)); -#59115 = CARTESIAN_POINT('',(-1.900701818158E-012,4.278735882113E-002)); -#59116 = CARTESIAN_POINT('',(-2.024158618497E-012,5.64237224575E-002)); -#59117 = CARTESIAN_POINT('',(-1.989519660128E-012,7.006008609387E-002)); -#59118 = CARTESIAN_POINT('',(-1.998401444325E-012,8.369644973024E-002)); -#59119 = CARTESIAN_POINT('',(-1.996625087486E-012,9.733281336661E-002)); -#59120 = CARTESIAN_POINT('',(-1.995736909066E-012,0.110969177003)); -#59121 = CARTESIAN_POINT('',(-1.996625087486E-012,0.124605540639)); -#59122 = CARTESIAN_POINT('',(-1.996625087486E-012,0.138241904276)); -#59123 = CARTESIAN_POINT('',(-1.996625087486E-012,0.151878267912)); -#59124 = CARTESIAN_POINT('',(-1.995736909066E-012,0.165514631548)); -#59125 = CARTESIAN_POINT('',(-1.996625087486E-012,0.179150995185)); -#59126 = CARTESIAN_POINT('',(-1.996625087486E-012,0.192787358821)); -#59127 = CARTESIAN_POINT('',(-1.996625087486E-012,0.206423722458)); -#59128 = CARTESIAN_POINT('',(-1.996625087486E-012,0.220060086094)); -#59129 = CARTESIAN_POINT('',(-1.995736909066E-012,0.23369644973)); -#59130 = CARTESIAN_POINT('',(-1.998401444325E-012,0.247332813367)); -#59131 = CARTESIAN_POINT('',(-1.989519660128E-012,0.260969177003)); -#59132 = CARTESIAN_POINT('',(-2.022382261657E-012,0.274605540639)); -#59133 = CARTESIAN_POINT('',(-1.900701818158E-012,0.288241904276)); -#59134 = CARTESIAN_POINT('',(-2.355449169045E-012,0.301878267912)); -#59135 = CARTESIAN_POINT('',(-1.219468970248E-012,0.310969177003)); -#59136 = CARTESIAN_POINT('',(0.E+000,0.315514631549)); -#59137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59138 = PCURVE('',#37831,#59139); -#59139 = DEFINITIONAL_REPRESENTATION('',(#59140),#59144); -#59140 = LINE('',#59141,#59142); -#59141 = CARTESIAN_POINT('',(2.420762596622,-1.313674285394)); -#59142 = VECTOR('',#59143,1.); -#59143 = DIRECTION('',(0.78162857303,0.623744157346)); -#59144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59145 = ORIENTED_EDGE('',*,*,#58813,.F.); -#59146 = ORIENTED_EDGE('',*,*,#59078,.T.); -#59147 = ADVANCED_FACE('',(#59148),#37831,.T.); -#59148 = FACE_BOUND('',#59149,.F.); -#59149 = EDGE_LOOP('',(#59150,#59151,#59152,#59153,#59154,#59155)); -#59150 = ORIENTED_EDGE('',*,*,#59103,.F.); -#59151 = ORIENTED_EDGE('',*,*,#58790,.F.); -#59152 = ORIENTED_EDGE('',*,*,#37815,.T.); -#59153 = ORIENTED_EDGE('',*,*,#42260,.F.); -#59154 = ORIENTED_EDGE('',*,*,#58945,.F.); -#59155 = ORIENTED_EDGE('',*,*,#58509,.F.); -#59156 = ADVANCED_FACE('',(#59157),#41544,.T.); -#59157 = FACE_BOUND('',#59158,.T.); -#59158 = EDGE_LOOP('',(#59159,#59160,#59161,#59162)); -#59159 = ORIENTED_EDGE('',*,*,#57133,.F.); -#59160 = ORIENTED_EDGE('',*,*,#59017,.T.); -#59161 = ORIENTED_EDGE('',*,*,#41523,.T.); -#59162 = ORIENTED_EDGE('',*,*,#59163,.F.); -#59163 = EDGE_CURVE('',#57111,#41524,#59164,.T.); -#59164 = SURFACE_CURVE('',#59165,(#59169,#59175),.PCURVE_S1.); -#59165 = LINE('',#59166,#59167); -#59166 = CARTESIAN_POINT('',(0.229314035204,-1.125,1.629788704102)); -#59167 = VECTOR('',#59168,1.); -#59168 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59169 = PCURVE('',#41544,#59170); -#59170 = DEFINITIONAL_REPRESENTATION('',(#59171),#59174); -#59171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59172,#59173),.UNSPECIFIED., +#61504 = CARTESIAN_POINT('',(0.E+000,1.551463154839E-002)); +#61505 = CARTESIAN_POINT('',(-1.220357148668E-012,2.006008609385E-002)); +#61506 = CARTESIAN_POINT('',(-2.354560990625E-012,2.915099518476E-002)); +#61507 = CARTESIAN_POINT('',(-1.900701818158E-012,4.278735882113E-002)); +#61508 = CARTESIAN_POINT('',(-2.024158618497E-012,5.64237224575E-002)); +#61509 = CARTESIAN_POINT('',(-1.989519660128E-012,7.006008609387E-002)); +#61510 = CARTESIAN_POINT('',(-1.998401444325E-012,8.369644973024E-002)); +#61511 = CARTESIAN_POINT('',(-1.996625087486E-012,9.733281336661E-002)); +#61512 = CARTESIAN_POINT('',(-1.995736909066E-012,0.110969177003)); +#61513 = CARTESIAN_POINT('',(-1.996625087486E-012,0.124605540639)); +#61514 = CARTESIAN_POINT('',(-1.996625087486E-012,0.138241904276)); +#61515 = CARTESIAN_POINT('',(-1.996625087486E-012,0.151878267912)); +#61516 = CARTESIAN_POINT('',(-1.995736909066E-012,0.165514631548)); +#61517 = CARTESIAN_POINT('',(-1.996625087486E-012,0.179150995185)); +#61518 = CARTESIAN_POINT('',(-1.996625087486E-012,0.192787358821)); +#61519 = CARTESIAN_POINT('',(-1.996625087486E-012,0.206423722458)); +#61520 = CARTESIAN_POINT('',(-1.996625087486E-012,0.220060086094)); +#61521 = CARTESIAN_POINT('',(-1.995736909066E-012,0.23369644973)); +#61522 = CARTESIAN_POINT('',(-1.998401444325E-012,0.247332813367)); +#61523 = CARTESIAN_POINT('',(-1.989519660128E-012,0.260969177003)); +#61524 = CARTESIAN_POINT('',(-2.022382261657E-012,0.274605540639)); +#61525 = CARTESIAN_POINT('',(-1.900701818158E-012,0.288241904276)); +#61526 = CARTESIAN_POINT('',(-2.355449169045E-012,0.301878267912)); +#61527 = CARTESIAN_POINT('',(-1.219468970248E-012,0.310969177003)); +#61528 = CARTESIAN_POINT('',(0.E+000,0.315514631549)); +#61529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61530 = PCURVE('',#40223,#61531); +#61531 = DEFINITIONAL_REPRESENTATION('',(#61532),#61536); +#61532 = LINE('',#61533,#61534); +#61533 = CARTESIAN_POINT('',(2.420762596622,-1.313674285394)); +#61534 = VECTOR('',#61535,1.); +#61535 = DIRECTION('',(0.78162857303,0.623744157346)); +#61536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61537 = ORIENTED_EDGE('',*,*,#61205,.F.); +#61538 = ORIENTED_EDGE('',*,*,#61470,.T.); +#61539 = ADVANCED_FACE('',(#61540),#40223,.T.); +#61540 = FACE_BOUND('',#61541,.F.); +#61541 = EDGE_LOOP('',(#61542,#61543,#61544,#61545,#61546,#61547)); +#61542 = ORIENTED_EDGE('',*,*,#61495,.F.); +#61543 = ORIENTED_EDGE('',*,*,#61182,.F.); +#61544 = ORIENTED_EDGE('',*,*,#40207,.T.); +#61545 = ORIENTED_EDGE('',*,*,#44652,.F.); +#61546 = ORIENTED_EDGE('',*,*,#61337,.F.); +#61547 = ORIENTED_EDGE('',*,*,#60901,.F.); +#61548 = ADVANCED_FACE('',(#61549),#43936,.T.); +#61549 = FACE_BOUND('',#61550,.T.); +#61550 = EDGE_LOOP('',(#61551,#61552,#61553,#61554)); +#61551 = ORIENTED_EDGE('',*,*,#59525,.F.); +#61552 = ORIENTED_EDGE('',*,*,#61409,.T.); +#61553 = ORIENTED_EDGE('',*,*,#43915,.T.); +#61554 = ORIENTED_EDGE('',*,*,#61555,.F.); +#61555 = EDGE_CURVE('',#59503,#43916,#61556,.T.); +#61556 = SURFACE_CURVE('',#61557,(#61561,#61567),.PCURVE_S1.); +#61557 = LINE('',#61558,#61559); +#61558 = CARTESIAN_POINT('',(0.229314035204,-1.125,1.629788704102)); +#61559 = VECTOR('',#61560,1.); +#61560 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61561 = PCURVE('',#43936,#61562); +#61562 = DEFINITIONAL_REPRESENTATION('',(#61563),#61566); +#61563 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61564,#61565),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59172 = CARTESIAN_POINT('',(5.314676326519,-0.4)); -#59173 = CARTESIAN_POINT('',(5.314676326519,-0.6)); -#59174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59175 = PCURVE('',#41571,#59176); -#59176 = DEFINITIONAL_REPRESENTATION('',(#59177),#59181); -#59177 = LINE('',#59178,#59179); -#59178 = CARTESIAN_POINT('',(0.400515244967,-0.4)); -#59179 = VECTOR('',#59180,1.); -#59180 = DIRECTION('',(0.E+000,-1.)); -#59181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59182 = ADVANCED_FACE('',(#59183),#41571,.F.); -#59183 = FACE_BOUND('',#59184,.F.); -#59184 = EDGE_LOOP('',(#59185,#59186,#59206,#59207)); -#59185 = ORIENTED_EDGE('',*,*,#57110,.F.); -#59186 = ORIENTED_EDGE('',*,*,#59187,.T.); -#59187 = EDGE_CURVE('',#57088,#41556,#59188,.T.); -#59188 = SURFACE_CURVE('',#59189,(#59193,#59200),.PCURVE_S1.); -#59189 = LINE('',#59190,#59191); -#59190 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); -#59191 = VECTOR('',#59192,1.); -#59192 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59193 = PCURVE('',#41571,#59194); -#59194 = DEFINITIONAL_REPRESENTATION('',(#59195),#59199); -#59195 = LINE('',#59196,#59197); -#59196 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#59197 = VECTOR('',#59198,1.); -#59198 = DIRECTION('',(0.E+000,-1.)); -#59199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59200 = PCURVE('',#41604,#59201); -#59201 = DEFINITIONAL_REPRESENTATION('',(#59202),#59205); -#59202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59203,#59204),.UNSPECIFIED., +#61564 = CARTESIAN_POINT('',(5.314676326519,-0.4)); +#61565 = CARTESIAN_POINT('',(5.314676326519,-0.6)); +#61566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61567 = PCURVE('',#43963,#61568); +#61568 = DEFINITIONAL_REPRESENTATION('',(#61569),#61573); +#61569 = LINE('',#61570,#61571); +#61570 = CARTESIAN_POINT('',(0.400515244967,-0.4)); +#61571 = VECTOR('',#61572,1.); +#61572 = DIRECTION('',(0.E+000,-1.)); +#61573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61574 = ADVANCED_FACE('',(#61575),#43963,.F.); +#61575 = FACE_BOUND('',#61576,.F.); +#61576 = EDGE_LOOP('',(#61577,#61578,#61598,#61599)); +#61577 = ORIENTED_EDGE('',*,*,#59502,.F.); +#61578 = ORIENTED_EDGE('',*,*,#61579,.T.); +#61579 = EDGE_CURVE('',#59480,#43948,#61580,.T.); +#61580 = SURFACE_CURVE('',#61581,(#61585,#61592),.PCURVE_S1.); +#61581 = LINE('',#61582,#61583); +#61582 = CARTESIAN_POINT('',(0.559355388338,-1.125,1.856692134382)); +#61583 = VECTOR('',#61584,1.); +#61584 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61585 = PCURVE('',#43963,#61586); +#61586 = DEFINITIONAL_REPRESENTATION('',(#61587),#61591); +#61587 = LINE('',#61588,#61589); +#61588 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#61589 = VECTOR('',#61590,1.); +#61590 = DIRECTION('',(0.E+000,-1.)); +#61591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61592 = PCURVE('',#43996,#61593); +#61593 = DEFINITIONAL_REPRESENTATION('',(#61594),#61597); +#61594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61595,#61596),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59203 = CARTESIAN_POINT('',(2.173083672929,-0.4)); -#59204 = CARTESIAN_POINT('',(2.173083672929,-0.6)); -#59205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59206 = ORIENTED_EDGE('',*,*,#41555,.T.); -#59207 = ORIENTED_EDGE('',*,*,#59163,.F.); -#59208 = ADVANCED_FACE('',(#59209),#41604,.F.); -#59209 = FACE_BOUND('',#59210,.F.); -#59210 = EDGE_LOOP('',(#59211,#59212,#59213,#59214)); -#59211 = ORIENTED_EDGE('',*,*,#57085,.F.); -#59212 = ORIENTED_EDGE('',*,*,#57537,.T.); -#59213 = ORIENTED_EDGE('',*,*,#41583,.T.); -#59214 = ORIENTED_EDGE('',*,*,#59187,.F.); -#59215 = ADVANCED_FACE('',(#59216),#42074,.T.); -#59216 = FACE_BOUND('',#59217,.T.); -#59217 = EDGE_LOOP('',(#59218,#59219,#59239,#59240)); -#59218 = ORIENTED_EDGE('',*,*,#57353,.F.); -#59219 = ORIENTED_EDGE('',*,*,#59220,.T.); -#59220 = EDGE_CURVE('',#57354,#42026,#59221,.T.); -#59221 = SURFACE_CURVE('',#59222,(#59226,#59232),.PCURVE_S1.); -#59222 = LINE('',#59223,#59224); -#59223 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); -#59224 = VECTOR('',#59225,1.); -#59225 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59226 = PCURVE('',#42074,#59227); -#59227 = DEFINITIONAL_REPRESENTATION('',(#59228),#59231); -#59228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59229,#59230),.UNSPECIFIED., +#61595 = CARTESIAN_POINT('',(2.173083672929,-0.4)); +#61596 = CARTESIAN_POINT('',(2.173083672929,-0.6)); +#61597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61598 = ORIENTED_EDGE('',*,*,#43947,.T.); +#61599 = ORIENTED_EDGE('',*,*,#61555,.F.); +#61600 = ADVANCED_FACE('',(#61601),#43996,.F.); +#61601 = FACE_BOUND('',#61602,.F.); +#61602 = EDGE_LOOP('',(#61603,#61604,#61605,#61606)); +#61603 = ORIENTED_EDGE('',*,*,#59477,.F.); +#61604 = ORIENTED_EDGE('',*,*,#59929,.T.); +#61605 = ORIENTED_EDGE('',*,*,#43975,.T.); +#61606 = ORIENTED_EDGE('',*,*,#61579,.F.); +#61607 = ADVANCED_FACE('',(#61608),#44466,.T.); +#61608 = FACE_BOUND('',#61609,.T.); +#61609 = EDGE_LOOP('',(#61610,#61611,#61631,#61632)); +#61610 = ORIENTED_EDGE('',*,*,#59745,.F.); +#61611 = ORIENTED_EDGE('',*,*,#61612,.T.); +#61612 = EDGE_CURVE('',#59746,#44418,#61613,.T.); +#61613 = SURFACE_CURVE('',#61614,(#61618,#61624),.PCURVE_S1.); +#61614 = LINE('',#61615,#61616); +#61615 = CARTESIAN_POINT('',(0.570685964796,-1.125,-0.520211295898)); +#61616 = VECTOR('',#61617,1.); +#61617 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61618 = PCURVE('',#44466,#61619); +#61619 = DEFINITIONAL_REPRESENTATION('',(#61620),#61623); +#61620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61621,#61622),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59229 = CARTESIAN_POINT('',(4.11010163425,-0.4)); -#59230 = CARTESIAN_POINT('',(4.11010163425,-0.6)); -#59231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59232 = PCURVE('',#42041,#59233); -#59233 = DEFINITIONAL_REPRESENTATION('',(#59234),#59238); -#59234 = LINE('',#59235,#59236); -#59235 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#59236 = VECTOR('',#59237,1.); -#59237 = DIRECTION('',(0.E+000,-1.)); -#59238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59239 = ORIENTED_EDGE('',*,*,#42053,.T.); -#59240 = ORIENTED_EDGE('',*,*,#57895,.F.); -#59241 = ADVANCED_FACE('',(#59242),#42041,.F.); -#59242 = FACE_BOUND('',#59243,.F.); -#59243 = EDGE_LOOP('',(#59244,#59245,#59246,#59247)); -#59244 = ORIENTED_EDGE('',*,*,#57376,.F.); -#59245 = ORIENTED_EDGE('',*,*,#59220,.T.); -#59246 = ORIENTED_EDGE('',*,*,#42025,.T.); -#59247 = ORIENTED_EDGE('',*,*,#59248,.F.); -#59248 = EDGE_CURVE('',#57377,#41994,#59249,.T.); -#59249 = SURFACE_CURVE('',#59250,(#59254,#59261),.PCURVE_S1.); -#59250 = LINE('',#59251,#59252); -#59251 = CARTESIAN_POINT('',(0.240644611662,-1.125,-0.293307865618)); -#59252 = VECTOR('',#59253,1.); -#59253 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59254 = PCURVE('',#42041,#59255); -#59255 = DEFINITIONAL_REPRESENTATION('',(#59256),#59260); -#59256 = LINE('',#59257,#59258); -#59257 = CARTESIAN_POINT('',(0.400515244967,-0.4)); -#59258 = VECTOR('',#59259,1.); -#59259 = DIRECTION('',(0.E+000,-1.)); -#59260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59261 = PCURVE('',#42014,#59262); -#59262 = DEFINITIONAL_REPRESENTATION('',(#59263),#59266); -#59263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59264,#59265),.UNSPECIFIED., +#61621 = CARTESIAN_POINT('',(4.11010163425,-0.4)); +#61622 = CARTESIAN_POINT('',(4.11010163425,-0.6)); +#61623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61624 = PCURVE('',#44433,#61625); +#61625 = DEFINITIONAL_REPRESENTATION('',(#61626),#61630); +#61626 = LINE('',#61627,#61628); +#61627 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#61628 = VECTOR('',#61629,1.); +#61629 = DIRECTION('',(0.E+000,-1.)); +#61630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61631 = ORIENTED_EDGE('',*,*,#44445,.T.); +#61632 = ORIENTED_EDGE('',*,*,#60287,.F.); +#61633 = ADVANCED_FACE('',(#61634),#44433,.F.); +#61634 = FACE_BOUND('',#61635,.F.); +#61635 = EDGE_LOOP('',(#61636,#61637,#61638,#61639)); +#61636 = ORIENTED_EDGE('',*,*,#59768,.F.); +#61637 = ORIENTED_EDGE('',*,*,#61612,.T.); +#61638 = ORIENTED_EDGE('',*,*,#44417,.T.); +#61639 = ORIENTED_EDGE('',*,*,#61640,.F.); +#61640 = EDGE_CURVE('',#59769,#44386,#61641,.T.); +#61641 = SURFACE_CURVE('',#61642,(#61646,#61653),.PCURVE_S1.); +#61642 = LINE('',#61643,#61644); +#61643 = CARTESIAN_POINT('',(0.240644611662,-1.125,-0.293307865618)); +#61644 = VECTOR('',#61645,1.); +#61645 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61646 = PCURVE('',#44433,#61647); +#61647 = DEFINITIONAL_REPRESENTATION('',(#61648),#61652); +#61648 = LINE('',#61649,#61650); +#61649 = CARTESIAN_POINT('',(0.400515244967,-0.4)); +#61650 = VECTOR('',#61651,1.); +#61651 = DIRECTION('',(0.E+000,-1.)); +#61652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61653 = PCURVE('',#44406,#61654); +#61654 = DEFINITIONAL_REPRESENTATION('',(#61655),#61658); +#61655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61656,#61657),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59264 = CARTESIAN_POINT('',(0.96850898066,-0.4)); -#59265 = CARTESIAN_POINT('',(0.96850898066,-0.6)); -#59266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59267 = ADVANCED_FACE('',(#59268),#42014,.F.); -#59268 = FACE_BOUND('',#59269,.F.); -#59269 = EDGE_LOOP('',(#59270,#59271,#59272,#59273)); -#59270 = ORIENTED_EDGE('',*,*,#57399,.F.); -#59271 = ORIENTED_EDGE('',*,*,#59248,.T.); -#59272 = ORIENTED_EDGE('',*,*,#41993,.T.); -#59273 = ORIENTED_EDGE('',*,*,#59274,.F.); -#59274 = EDGE_CURVE('',#57400,#41966,#59275,.T.); -#59275 = SURFACE_CURVE('',#59276,(#59280,#59286),.PCURVE_S1.); -#59276 = LINE('',#59277,#59278); -#59277 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); -#59278 = VECTOR('',#59279,1.); -#59279 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59280 = PCURVE('',#42014,#59281); -#59281 = DEFINITIONAL_REPRESENTATION('',(#59282),#59285); -#59282 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59283,#59284),.UNSPECIFIED., +#61656 = CARTESIAN_POINT('',(0.96850898066,-0.4)); +#61657 = CARTESIAN_POINT('',(0.96850898066,-0.6)); +#61658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61659 = ADVANCED_FACE('',(#61660),#44406,.F.); +#61660 = FACE_BOUND('',#61661,.F.); +#61661 = EDGE_LOOP('',(#61662,#61663,#61664,#61665)); +#61662 = ORIENTED_EDGE('',*,*,#59791,.F.); +#61663 = ORIENTED_EDGE('',*,*,#61640,.T.); +#61664 = ORIENTED_EDGE('',*,*,#44385,.T.); +#61665 = ORIENTED_EDGE('',*,*,#61666,.F.); +#61666 = EDGE_CURVE('',#59792,#44358,#61667,.T.); +#61667 = SURFACE_CURVE('',#61668,(#61672,#61678),.PCURVE_S1.); +#61668 = LINE('',#61669,#61670); +#61669 = CARTESIAN_POINT('',(-1.E-002,-1.125,-0.42515457349)); +#61670 = VECTOR('',#61671,1.); +#61671 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61672 = PCURVE('',#44406,#61673); +#61673 = DEFINITIONAL_REPRESENTATION('',(#61674),#61677); +#61674 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61675,#61676),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#59283 = CARTESIAN_POINT('',(3.14159265359,-0.4)); -#59284 = CARTESIAN_POINT('',(3.14159265359,-0.6)); -#59285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59286 = PCURVE('',#41981,#59287); -#59287 = DEFINITIONAL_REPRESENTATION('',(#59288),#59292); -#59288 = LINE('',#59289,#59290); -#59289 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#59290 = VECTOR('',#59291,1.); -#59291 = DIRECTION('',(0.E+000,-1.)); -#59292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59293 = ADVANCED_FACE('',(#59294),#41981,.F.); -#59294 = FACE_BOUND('',#59295,.F.); -#59295 = EDGE_LOOP('',(#59296,#59297,#59298,#59299,#59320,#59321)); -#59296 = ORIENTED_EDGE('',*,*,#57422,.F.); -#59297 = ORIENTED_EDGE('',*,*,#59274,.T.); -#59298 = ORIENTED_EDGE('',*,*,#41965,.T.); -#59299 = ORIENTED_EDGE('',*,*,#59300,.T.); -#59300 = EDGE_CURVE('',#41938,#55366,#59301,.T.); -#59301 = SURFACE_CURVE('',#59302,(#59306,#59313),.PCURVE_S1.); -#59302 = LINE('',#59303,#59304); -#59303 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); -#59304 = VECTOR('',#59305,1.); -#59305 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59306 = PCURVE('',#41981,#59307); -#59307 = DEFINITIONAL_REPRESENTATION('',(#59308),#59312); -#59308 = LINE('',#59309,#59310); -#59309 = CARTESIAN_POINT('',(0.70484542651,-0.6)); -#59310 = VECTOR('',#59311,1.); -#59311 = DIRECTION('',(0.E+000,1.)); -#59312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59313 = PCURVE('',#41953,#59314); -#59314 = DEFINITIONAL_REPRESENTATION('',(#59315),#59319); -#59315 = LINE('',#59316,#59317); -#59316 = CARTESIAN_POINT('',(1.72,-0.3)); -#59317 = VECTOR('',#59318,1.); -#59318 = DIRECTION('',(0.E+000,1.)); -#59319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59320 = ORIENTED_EDGE('',*,*,#55365,.F.); -#59321 = ORIENTED_EDGE('',*,*,#57734,.T.); -#59322 = ADVANCED_FACE('',(#59323),#41779,.F.); -#59323 = FACE_BOUND('',#59324,.F.); -#59324 = EDGE_LOOP('',(#59325,#59326,#59327,#59347)); -#59325 = ORIENTED_EDGE('',*,*,#57685,.T.); -#59326 = ORIENTED_EDGE('',*,*,#56391,.F.); -#59327 = ORIENTED_EDGE('',*,*,#59328,.T.); -#59328 = EDGE_CURVE('',#56369,#41764,#59329,.T.); -#59329 = SURFACE_CURVE('',#59330,(#59334,#59341),.PCURVE_S1.); -#59330 = LINE('',#59331,#59332); -#59331 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); -#59332 = VECTOR('',#59333,1.); -#59333 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59334 = PCURVE('',#41779,#59335); -#59335 = DEFINITIONAL_REPRESENTATION('',(#59336),#59340); -#59336 = LINE('',#59337,#59338); -#59337 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59338 = VECTOR('',#59339,1.); -#59339 = DIRECTION('',(0.E+000,-1.)); -#59340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59341 = PCURVE('',#41812,#59342); -#59342 = DEFINITIONAL_REPRESENTATION('',(#59343),#59346); -#59343 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59344,#59345),.UNSPECIFIED., +#61675 = CARTESIAN_POINT('',(3.14159265359,-0.4)); +#61676 = CARTESIAN_POINT('',(3.14159265359,-0.6)); +#61677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61678 = PCURVE('',#44373,#61679); +#61679 = DEFINITIONAL_REPRESENTATION('',(#61680),#61684); +#61680 = LINE('',#61681,#61682); +#61681 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#61682 = VECTOR('',#61683,1.); +#61683 = DIRECTION('',(0.E+000,-1.)); +#61684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61685 = ADVANCED_FACE('',(#61686),#44373,.F.); +#61686 = FACE_BOUND('',#61687,.F.); +#61687 = EDGE_LOOP('',(#61688,#61689,#61690,#61691,#61712,#61713)); +#61688 = ORIENTED_EDGE('',*,*,#59814,.F.); +#61689 = ORIENTED_EDGE('',*,*,#61666,.T.); +#61690 = ORIENTED_EDGE('',*,*,#44357,.T.); +#61691 = ORIENTED_EDGE('',*,*,#61692,.T.); +#61692 = EDGE_CURVE('',#44330,#57758,#61693,.T.); +#61693 = SURFACE_CURVE('',#61694,(#61698,#61705),.PCURVE_S1.); +#61694 = LINE('',#61695,#61696); +#61695 = CARTESIAN_POINT('',(-1.E-002,-0.925,-1.13)); +#61696 = VECTOR('',#61697,1.); +#61697 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#61698 = PCURVE('',#44373,#61699); +#61699 = DEFINITIONAL_REPRESENTATION('',(#61700),#61704); +#61700 = LINE('',#61701,#61702); +#61701 = CARTESIAN_POINT('',(0.70484542651,-0.6)); +#61702 = VECTOR('',#61703,1.); +#61703 = DIRECTION('',(0.E+000,1.)); +#61704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61705 = PCURVE('',#44345,#61706); +#61706 = DEFINITIONAL_REPRESENTATION('',(#61707),#61711); +#61707 = LINE('',#61708,#61709); +#61708 = CARTESIAN_POINT('',(1.72,-0.3)); +#61709 = VECTOR('',#61710,1.); +#61710 = DIRECTION('',(0.E+000,1.)); +#61711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61712 = ORIENTED_EDGE('',*,*,#57757,.F.); +#61713 = ORIENTED_EDGE('',*,*,#60126,.T.); +#61714 = ADVANCED_FACE('',(#61715),#44171,.F.); +#61715 = FACE_BOUND('',#61716,.F.); +#61716 = EDGE_LOOP('',(#61717,#61718,#61719,#61739)); +#61717 = ORIENTED_EDGE('',*,*,#60077,.T.); +#61718 = ORIENTED_EDGE('',*,*,#58783,.F.); +#61719 = ORIENTED_EDGE('',*,*,#61720,.T.); +#61720 = EDGE_CURVE('',#58761,#44156,#61721,.T.); +#61721 = SURFACE_CURVE('',#61722,(#61726,#61733),.PCURVE_S1.); +#61722 = LINE('',#61723,#61724); +#61723 = CARTESIAN_POINT('',(1.71,-1.225,-1.13)); +#61724 = VECTOR('',#61725,1.); +#61725 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61726 = PCURVE('',#44171,#61727); +#61727 = DEFINITIONAL_REPRESENTATION('',(#61728),#61732); +#61728 = LINE('',#61729,#61730); +#61729 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#61730 = VECTOR('',#61731,1.); +#61731 = DIRECTION('',(0.E+000,-1.)); +#61732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61733 = PCURVE('',#44204,#61734); +#61734 = DEFINITIONAL_REPRESENTATION('',(#61735),#61738); +#61735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61736,#61737),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#59344 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#59345 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#59346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59347 = ORIENTED_EDGE('',*,*,#41763,.T.); -#59348 = ADVANCED_FACE('',(#59349),#41953,.F.); -#59349 = FACE_BOUND('',#59350,.F.); -#59350 = EDGE_LOOP('',(#59351,#59352,#59353,#59373)); -#59351 = ORIENTED_EDGE('',*,*,#59300,.F.); -#59352 = ORIENTED_EDGE('',*,*,#41937,.T.); -#59353 = ORIENTED_EDGE('',*,*,#59354,.F.); -#59354 = EDGE_CURVE('',#55389,#41906,#59355,.T.); -#59355 = SURFACE_CURVE('',#59356,(#59360,#59367),.PCURVE_S1.); -#59356 = LINE('',#59357,#59358); -#59357 = CARTESIAN_POINT('',(-1.71,-1.225,-1.13)); -#59358 = VECTOR('',#59359,1.); -#59359 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59360 = PCURVE('',#41953,#59361); -#59361 = DEFINITIONAL_REPRESENTATION('',(#59362),#59366); -#59362 = LINE('',#59363,#59364); -#59363 = CARTESIAN_POINT('',(3.42,0.E+000)); -#59364 = VECTOR('',#59365,1.); -#59365 = DIRECTION('',(0.E+000,-1.)); -#59366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59367 = PCURVE('',#41926,#59368); -#59368 = DEFINITIONAL_REPRESENTATION('',(#59369),#59372); -#59369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59370,#59371),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#59370 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#59371 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#59372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59373 = ORIENTED_EDGE('',*,*,#55388,.F.); -#59374 = ADVANCED_FACE('',(#59375),#41812,.F.); -#59375 = FACE_BOUND('',#59376,.F.); -#59376 = EDGE_LOOP('',(#59377,#59378,#59379,#59380,#59381,#59403)); -#59377 = ORIENTED_EDGE('',*,*,#43548,.F.); -#59378 = ORIENTED_EDGE('',*,*,#41791,.T.); -#59379 = ORIENTED_EDGE('',*,*,#59328,.F.); -#59380 = ORIENTED_EDGE('',*,*,#56368,.F.); -#59381 = ORIENTED_EDGE('',*,*,#59382,.T.); -#59382 = EDGE_CURVE('',#56341,#59383,#59385,.T.); -#59383 = VERTEX_POINT('',#59384); -#59384 = CARTESIAN_POINT('',(1.79,-1.2,-1.21)); -#59385 = SURFACE_CURVE('',#59386,(#59390,#59396),.PCURVE_S1.); -#59386 = LINE('',#59387,#59388); -#59387 = CARTESIAN_POINT('',(1.79,-1.225,-1.21)); -#59388 = VECTOR('',#59389,1.); -#59389 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59390 = PCURVE('',#41812,#59391); -#59391 = DEFINITIONAL_REPRESENTATION('',(#59392),#59395); -#59392 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59393,#59394),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,2.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#59393 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59394 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#59395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59396 = PCURVE('',#56356,#59397); -#59397 = DEFINITIONAL_REPRESENTATION('',(#59398),#59402); -#59398 = LINE('',#59399,#59400); -#59399 = CARTESIAN_POINT('',(0.32,0.E+000)); -#59400 = VECTOR('',#59401,1.); -#59401 = DIRECTION('',(0.E+000,-1.)); -#59402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59403 = ORIENTED_EDGE('',*,*,#59404,.T.); -#59404 = EDGE_CURVE('',#59383,#43549,#59405,.T.); -#59405 = SURFACE_CURVE('',#59406,(#59411,#59417),.PCURVE_S1.); -#59406 = CIRCLE('',#59407,8.E-002); -#59407 = AXIS2_PLACEMENT_3D('',#59408,#59409,#59410); -#59408 = CARTESIAN_POINT('',(1.71,-1.2,-1.21)); -#59409 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59410 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59411 = PCURVE('',#41812,#59412); -#59412 = DEFINITIONAL_REPRESENTATION('',(#59413),#59416); -#59413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59414,#59415),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.848062078984),.PIECEWISE_BEZIER_KNOTS.); -#59414 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#59415 = CARTESIAN_POINT('',(0.848062078984,-2.5E-002)); -#59416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59417 = PCURVE('',#43586,#59418); -#59418 = DEFINITIONAL_REPRESENTATION('',(#59419),#59423); -#59419 = CIRCLE('',#59420,8.E-002); -#59420 = AXIS2_PLACEMENT_2D('',#59421,#59422); -#59421 = CARTESIAN_POINT('',(6.E-002,-8.E-002)); -#59422 = DIRECTION('',(0.E+000,1.)); -#59423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59424 = ADVANCED_FACE('',(#59425),#56356,.F.); -#59425 = FACE_BOUND('',#59426,.F.); -#59426 = EDGE_LOOP('',(#59427,#59450,#59451,#59452)); -#59427 = ORIENTED_EDGE('',*,*,#59428,.T.); -#59428 = EDGE_CURVE('',#59429,#59383,#59431,.T.); -#59429 = VERTEX_POINT('',#59430); -#59430 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); -#59431 = SURFACE_CURVE('',#59432,(#59436,#59443),.PCURVE_S1.); -#59432 = LINE('',#59433,#59434); -#59433 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); -#59434 = VECTOR('',#59435,1.); -#59435 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59436 = PCURVE('',#56356,#59437); -#59437 = DEFINITIONAL_REPRESENTATION('',(#59438),#59442); -#59438 = LINE('',#59439,#59440); -#59439 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#59440 = VECTOR('',#59441,1.); -#59441 = DIRECTION('',(1.,0.E+000)); -#59442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59443 = PCURVE('',#43586,#59444); -#59444 = DEFINITIONAL_REPRESENTATION('',(#59445),#59449); -#59445 = LINE('',#59446,#59447); -#59446 = CARTESIAN_POINT('',(0.38,0.E+000)); -#59447 = VECTOR('',#59448,1.); -#59448 = DIRECTION('',(-1.,0.E+000)); -#59449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59450 = ORIENTED_EDGE('',*,*,#59382,.F.); -#59451 = ORIENTED_EDGE('',*,*,#56340,.F.); -#59452 = ORIENTED_EDGE('',*,*,#59453,.T.); -#59453 = EDGE_CURVE('',#56318,#59429,#59454,.T.); -#59454 = SURFACE_CURVE('',#59455,(#59459,#59466),.PCURVE_S1.); -#59455 = LINE('',#59456,#59457); -#59456 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); -#59457 = VECTOR('',#59458,1.); -#59458 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59459 = PCURVE('',#56356,#59460); -#59460 = DEFINITIONAL_REPRESENTATION('',(#59461),#59465); -#59461 = LINE('',#59462,#59463); -#59462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59463 = VECTOR('',#59464,1.); -#59464 = DIRECTION('',(0.E+000,-1.)); -#59465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59466 = PCURVE('',#40920,#59467); -#59467 = DEFINITIONAL_REPRESENTATION('',(#59468),#59472); -#59468 = LINE('',#59469,#59470); -#59469 = CARTESIAN_POINT('',(0.35,5.54)); -#59470 = VECTOR('',#59471,1.); -#59471 = DIRECTION('',(-1.,0.E+000)); -#59472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59473 = ADVANCED_FACE('',(#59474),#43586,.T.); -#59474 = FACE_BOUND('',#59475,.F.); -#59475 = EDGE_LOOP('',(#59476,#59477,#59500,#59523,#59544,#59545)); -#59476 = ORIENTED_EDGE('',*,*,#59428,.F.); -#59477 = ORIENTED_EDGE('',*,*,#59478,.T.); -#59478 = EDGE_CURVE('',#59429,#59479,#59481,.T.); -#59479 = VERTEX_POINT('',#59480); -#59480 = CARTESIAN_POINT('',(-1.79,-1.2,-1.53)); -#59481 = SURFACE_CURVE('',#59482,(#59486,#59493),.PCURVE_S1.); -#59482 = LINE('',#59483,#59484); -#59483 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); -#59484 = VECTOR('',#59485,1.); -#59485 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#59486 = PCURVE('',#43586,#59487); -#59487 = DEFINITIONAL_REPRESENTATION('',(#59488),#59492); -#59488 = LINE('',#59489,#59490); -#59489 = CARTESIAN_POINT('',(0.38,0.E+000)); -#59490 = VECTOR('',#59491,1.); -#59491 = DIRECTION('',(0.E+000,-1.)); -#59492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59493 = PCURVE('',#40920,#59494); -#59494 = DEFINITIONAL_REPRESENTATION('',(#59495),#59499); -#59495 = LINE('',#59496,#59497); -#59496 = CARTESIAN_POINT('',(0.325,5.54)); -#59497 = VECTOR('',#59498,1.); -#59498 = DIRECTION('',(0.E+000,-1.)); -#59499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59500 = ORIENTED_EDGE('',*,*,#59501,.F.); -#59501 = EDGE_CURVE('',#59502,#59479,#59504,.T.); -#59502 = VERTEX_POINT('',#59503); -#59503 = CARTESIAN_POINT('',(-1.79,-1.2,-1.21)); -#59504 = SURFACE_CURVE('',#59505,(#59509,#59516),.PCURVE_S1.); -#59505 = LINE('',#59506,#59507); -#59506 = CARTESIAN_POINT('',(-1.79,-1.2,-1.21)); -#59507 = VECTOR('',#59508,1.); -#59508 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59509 = PCURVE('',#43586,#59510); -#59510 = DEFINITIONAL_REPRESENTATION('',(#59511),#59515); -#59511 = LINE('',#59512,#59513); -#59512 = CARTESIAN_POINT('',(6.E-002,-3.58)); -#59513 = VECTOR('',#59514,1.); -#59514 = DIRECTION('',(1.,0.E+000)); -#59515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59516 = PCURVE('',#55450,#59517); -#59517 = DEFINITIONAL_REPRESENTATION('',(#59518),#59522); -#59518 = LINE('',#59519,#59520); -#59519 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#59520 = VECTOR('',#59521,1.); -#59521 = DIRECTION('',(1.,0.E+000)); -#59522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59523 = ORIENTED_EDGE('',*,*,#59524,.F.); -#59524 = EDGE_CURVE('',#43571,#59502,#59525,.T.); -#59525 = SURFACE_CURVE('',#59526,(#59531,#59538),.PCURVE_S1.); -#59526 = CIRCLE('',#59527,8.E-002); -#59527 = AXIS2_PLACEMENT_3D('',#59528,#59529,#59530); -#59528 = CARTESIAN_POINT('',(-1.71,-1.2,-1.21)); -#59529 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59530 = DIRECTION('',(-0.661437827766,0.E+000,0.75)); -#59531 = PCURVE('',#43586,#59532); -#59532 = DEFINITIONAL_REPRESENTATION('',(#59533),#59537); -#59533 = CIRCLE('',#59534,8.E-002); -#59534 = AXIS2_PLACEMENT_2D('',#59535,#59536); -#59535 = CARTESIAN_POINT('',(6.E-002,-3.5)); -#59536 = DIRECTION('',(-0.75,-0.661437827766)); -#59537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59538 = PCURVE('',#41926,#59539); -#59539 = DEFINITIONAL_REPRESENTATION('',(#59540),#59543); -#59540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59541,#59542),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.848062078982),.PIECEWISE_BEZIER_KNOTS.); -#59541 = CARTESIAN_POINT('',(2.293530574608,-2.5E-002)); -#59542 = CARTESIAN_POINT('',(3.14159265359,-2.5E-002)); -#59543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59544 = ORIENTED_EDGE('',*,*,#43570,.F.); -#59545 = ORIENTED_EDGE('',*,*,#59404,.F.); -#59546 = ADVANCED_FACE('',(#59547),#40920,.F.); -#59547 = FACE_BOUND('',#59548,.F.); -#59548 = EDGE_LOOP('',(#59549,#59550,#59573,#59594,#59595,#59618,#59638, - #59639,#59640,#59641,#59662,#59663,#59664,#59665,#59688,#59711, - #59731,#59732)); -#59549 = ORIENTED_EDGE('',*,*,#42877,.T.); -#59550 = ORIENTED_EDGE('',*,*,#59551,.T.); -#59551 = EDGE_CURVE('',#42850,#59552,#59554,.T.); -#59552 = VERTEX_POINT('',#59553); -#59553 = CARTESIAN_POINT('',(-1.79,-0.985,-1.53)); -#59554 = SURFACE_CURVE('',#59555,(#59559,#59566),.PCURVE_S1.); -#59555 = LINE('',#59556,#59557); -#59556 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); -#59557 = VECTOR('',#59558,1.); -#59558 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#59559 = PCURVE('',#40920,#59560); -#59560 = DEFINITIONAL_REPRESENTATION('',(#59561),#59565); -#59561 = LINE('',#59562,#59563); -#59562 = CARTESIAN_POINT('',(0.11,5.54)); -#59563 = VECTOR('',#59564,1.); -#59564 = DIRECTION('',(0.E+000,-1.)); -#59565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59566 = PCURVE('',#42865,#59567); -#59567 = DEFINITIONAL_REPRESENTATION('',(#59568),#59572); -#59568 = LINE('',#59569,#59570); -#59569 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59570 = VECTOR('',#59571,1.); -#59571 = DIRECTION('',(0.E+000,-1.)); -#59572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59573 = ORIENTED_EDGE('',*,*,#59574,.F.); -#59574 = EDGE_CURVE('',#41853,#59552,#59575,.T.); -#59575 = SURFACE_CURVE('',#59576,(#59580,#59587),.PCURVE_S1.); -#59576 = LINE('',#59577,#59578); -#59577 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); -#59578 = VECTOR('',#59579,1.); -#59579 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59580 = PCURVE('',#40920,#59581); -#59581 = DEFINITIONAL_REPRESENTATION('',(#59582),#59586); -#59582 = LINE('',#59583,#59584); -#59583 = CARTESIAN_POINT('',(5.E-002,1.96)); -#59584 = VECTOR('',#59585,1.); -#59585 = DIRECTION('',(1.,0.E+000)); -#59586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59587 = PCURVE('',#41870,#59588); -#59588 = DEFINITIONAL_REPRESENTATION('',(#59589),#59593); -#59589 = LINE('',#59590,#59591); -#59590 = CARTESIAN_POINT('',(0.32,-0.3)); -#59591 = VECTOR('',#59592,1.); -#59592 = DIRECTION('',(0.E+000,1.)); -#59593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59594 = ORIENTED_EDGE('',*,*,#42711,.F.); -#59595 = ORIENTED_EDGE('',*,*,#59596,.F.); -#59596 = EDGE_CURVE('',#59597,#42685,#59599,.T.); -#59597 = VERTEX_POINT('',#59598); -#59598 = CARTESIAN_POINT('',(-2.746446609407,-0.875,-1.53)); -#59599 = SURFACE_CURVE('',#59600,(#59605,#59612),.PCURVE_S1.); -#59600 = CIRCLE('',#59601,0.25); -#59601 = AXIS2_PLACEMENT_3D('',#59602,#59603,#59604); -#59602 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-1.53)); -#59603 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59604 = DIRECTION('',(-0.6,-0.8,0.E+000)); -#59605 = PCURVE('',#40920,#59606); -#59606 = DEFINITIONAL_REPRESENTATION('',(#59607),#59611); -#59607 = CIRCLE('',#59608,0.25); -#59608 = AXIS2_PLACEMENT_2D('',#59609,#59610); -#59609 = CARTESIAN_POINT('',(-0.2,1.153553390593)); -#59610 = DIRECTION('',(0.8,-0.6)); -#59611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59612 = PCURVE('',#42700,#59613); -#59613 = DEFINITIONAL_REPRESENTATION('',(#59614),#59617); -#59614 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59615,#59616),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.643501108793),.PIECEWISE_BEZIER_KNOTS.); -#59615 = CARTESIAN_POINT('',(4.068887871591,0.82)); -#59616 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#59617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59618 = ORIENTED_EDGE('',*,*,#59619,.F.); -#59619 = EDGE_CURVE('',#54989,#59597,#59620,.T.); -#59620 = SURFACE_CURVE('',#59621,(#59625,#59632),.PCURVE_S1.); -#59621 = LINE('',#59622,#59623); -#59622 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); -#59623 = VECTOR('',#59624,1.); -#59624 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59625 = PCURVE('',#40920,#59626); -#59626 = DEFINITIONAL_REPRESENTATION('',(#59627),#59631); -#59627 = LINE('',#59628,#59629); -#59628 = CARTESIAN_POINT('',(0.E+000,0.575735931288)); -#59629 = VECTOR('',#59630,1.); -#59630 = DIRECTION('',(0.E+000,1.)); -#59631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59632 = PCURVE('',#55037,#59633); -#59633 = DEFINITIONAL_REPRESENTATION('',(#59634),#59637); -#59634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59635,#59636),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.427817459305),.PIECEWISE_BEZIER_KNOTS.); -#59635 = CARTESIAN_POINT('',(3.14159265359,0.575735931288)); -#59636 = CARTESIAN_POINT('',(3.14159265359,1.003553390593)); -#59637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59638 = ORIENTED_EDGE('',*,*,#54988,.F.); -#59639 = ORIENTED_EDGE('',*,*,#55126,.T.); -#59640 = ORIENTED_EDGE('',*,*,#55462,.T.); -#59641 = ORIENTED_EDGE('',*,*,#59642,.T.); -#59642 = EDGE_CURVE('',#55435,#59479,#59643,.T.); -#59643 = SURFACE_CURVE('',#59644,(#59648,#59655),.PCURVE_S1.); -#59644 = LINE('',#59645,#59646); -#59645 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); -#59646 = VECTOR('',#59647,1.); -#59647 = DIRECTION('',(0.E+000,1.,0.E+000)); -#59648 = PCURVE('',#40920,#59649); -#59649 = DEFINITIONAL_REPRESENTATION('',(#59650),#59654); -#59650 = LINE('',#59651,#59652); -#59651 = CARTESIAN_POINT('',(0.35,1.96)); -#59652 = VECTOR('',#59653,1.); -#59653 = DIRECTION('',(-1.,0.E+000)); -#59654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59655 = PCURVE('',#55450,#59656); -#59656 = DEFINITIONAL_REPRESENTATION('',(#59657),#59661); -#59657 = LINE('',#59658,#59659); -#59658 = CARTESIAN_POINT('',(0.32,0.E+000)); -#59659 = VECTOR('',#59660,1.); -#59660 = DIRECTION('',(0.E+000,-1.)); -#59661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59662 = ORIENTED_EDGE('',*,*,#59478,.F.); -#59663 = ORIENTED_EDGE('',*,*,#59453,.F.); -#59664 = ORIENTED_EDGE('',*,*,#56317,.T.); -#59665 = ORIENTED_EDGE('',*,*,#59666,.T.); -#59666 = EDGE_CURVE('',#56291,#59667,#59669,.T.); -#59667 = VERTEX_POINT('',#59668); -#59668 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); -#59669 = SURFACE_CURVE('',#59670,(#59675,#59682),.PCURVE_S1.); -#59670 = CIRCLE('',#59671,0.55); -#59671 = AXIS2_PLACEMENT_3D('',#59672,#59673,#59674); -#59672 = CARTESIAN_POINT('',(2.596446609407,-0.675,-1.53)); -#59673 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59674 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59675 = PCURVE('',#40920,#59676); -#59676 = DEFINITIONAL_REPRESENTATION('',(#59677),#59681); -#59677 = CIRCLE('',#59678,0.55); -#59678 = AXIS2_PLACEMENT_2D('',#59679,#59680); -#59679 = CARTESIAN_POINT('',(-0.2,6.346446609407)); -#59680 = DIRECTION('',(1.,0.E+000)); -#59681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59682 = PCURVE('',#56306,#59683); -#59683 = DEFINITIONAL_REPRESENTATION('',(#59684),#59687); -#59684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59685,#59686),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#59685 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#59686 = CARTESIAN_POINT('',(5.497787143781,0.82)); -#59687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59688 = ORIENTED_EDGE('',*,*,#59689,.T.); -#59689 = EDGE_CURVE('',#59667,#59690,#59692,.T.); -#59690 = VERTEX_POINT('',#59691); -#59691 = CARTESIAN_POINT('',(3.174264068712,-0.875,-1.53)); -#59692 = SURFACE_CURVE('',#59693,(#59697,#59704),.PCURVE_S1.); -#59693 = LINE('',#59694,#59695); -#59694 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); -#59695 = VECTOR('',#59696,1.); -#59696 = DIRECTION('',(0.707106781186,0.707106781187,0.E+000)); -#59697 = PCURVE('',#40920,#59698); -#59698 = DEFINITIONAL_REPRESENTATION('',(#59699),#59703); -#59699 = LINE('',#59700,#59701); -#59700 = CARTESIAN_POINT('',(0.188908729653,6.735355339059)); -#59701 = VECTOR('',#59702,1.); -#59702 = DIRECTION('',(-0.707106781187,0.707106781186)); -#59703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59704 = PCURVE('',#53481,#59705); -#59705 = DEFINITIONAL_REPRESENTATION('',(#59706),#59710); -#59706 = LINE('',#59707,#59708); -#59707 = CARTESIAN_POINT('',(0.E+000,0.82)); -#59708 = VECTOR('',#59709,1.); -#59709 = DIRECTION('',(1.,0.E+000)); -#59710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59711 = ORIENTED_EDGE('',*,*,#59712,.F.); -#59712 = EDGE_CURVE('',#40905,#59690,#59713,.T.); -#59713 = SURFACE_CURVE('',#59714,(#59718,#59725),.PCURVE_S1.); -#59714 = LINE('',#59715,#59716); -#59715 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); -#59716 = VECTOR('',#59717,1.); -#59717 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59718 = PCURVE('',#40920,#59719); -#59719 = DEFINITIONAL_REPRESENTATION('',(#59720),#59724); -#59720 = LINE('',#59721,#59722); -#59721 = CARTESIAN_POINT('',(0.E+000,6.496446609407)); -#59722 = VECTOR('',#59723,1.); -#59723 = DIRECTION('',(0.E+000,1.)); -#59724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59725 = PCURVE('',#40813,#59726); -#59726 = DEFINITIONAL_REPRESENTATION('',(#59727),#59730); -#59727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#59728,#59729),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.427817459305),.PIECEWISE_BEZIER_KNOTS.); -#59728 = CARTESIAN_POINT('',(3.14159265359,6.496446609407)); -#59729 = CARTESIAN_POINT('',(3.14159265359,6.924264068712)); -#59730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59731 = ORIENTED_EDGE('',*,*,#40902,.F.); -#59732 = ORIENTED_EDGE('',*,*,#41080,.F.); -#59733 = ADVANCED_FACE('',(#59734),#42865,.T.); -#59734 = FACE_BOUND('',#59735,.F.); -#59735 = EDGE_LOOP('',(#59736,#59766,#59794,#59822,#59850,#59878,#59906, - #59934,#59962,#59990,#60018,#60046,#60074,#60102,#60130,#60158, - #60186,#60214,#60242,#60263,#60264,#60265,#60288,#60316)); -#59736 = ORIENTED_EDGE('',*,*,#59737,.T.); -#59737 = EDGE_CURVE('',#59738,#59740,#59742,.T.); -#59738 = VERTEX_POINT('',#59739); -#59739 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); -#59740 = VERTEX_POINT('',#59741); -#59741 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); -#59742 = SURFACE_CURVE('',#59743,(#59747,#59754),.PCURVE_S1.); -#59743 = LINE('',#59744,#59745); -#59744 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); -#59745 = VECTOR('',#59746,1.); -#59746 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59747 = PCURVE('',#42865,#59748); -#59748 = DEFINITIONAL_REPRESENTATION('',(#59749),#59753); -#59749 = LINE('',#59750,#59751); -#59750 = CARTESIAN_POINT('',(0.32,-0.615)); -#59751 = VECTOR('',#59752,1.); -#59752 = DIRECTION('',(-1.,0.E+000)); -#59753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59754 = PCURVE('',#59755,#59760); -#59755 = PLANE('',#59756); -#59756 = AXIS2_PLACEMENT_3D('',#59757,#59758,#59759); -#59757 = CARTESIAN_POINT('',(1.175,0.E+000,0.E+000)); -#59758 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59759 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59760 = DEFINITIONAL_REPRESENTATION('',(#59761),#59765); -#59761 = LINE('',#59762,#59763); -#59762 = CARTESIAN_POINT('',(1.85,-0.985)); -#59763 = VECTOR('',#59764,1.); -#59764 = DIRECTION('',(-1.,0.E+000)); -#59765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59766 = ORIENTED_EDGE('',*,*,#59767,.T.); -#59767 = EDGE_CURVE('',#59740,#59768,#59770,.T.); -#59768 = VERTEX_POINT('',#59769); -#59769 = CARTESIAN_POINT('',(0.775,-0.985,-1.71)); -#59770 = SURFACE_CURVE('',#59771,(#59775,#59782),.PCURVE_S1.); -#59771 = LINE('',#59772,#59773); -#59772 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); -#59773 = VECTOR('',#59774,1.); -#59774 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#59775 = PCURVE('',#42865,#59776); -#59776 = DEFINITIONAL_REPRESENTATION('',(#59777),#59781); -#59777 = LINE('',#59778,#59779); -#59778 = CARTESIAN_POINT('',(0.18,-0.615)); -#59779 = VECTOR('',#59780,1.); -#59780 = DIRECTION('',(0.E+000,-1.)); -#59781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59782 = PCURVE('',#59783,#59788); -#59783 = PLANE('',#59784); -#59784 = AXIS2_PLACEMENT_3D('',#59785,#59786,#59787); -#59785 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#59786 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59787 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59788 = DEFINITIONAL_REPRESENTATION('',(#59789),#59793); -#59789 = LINE('',#59790,#59791); -#59790 = CARTESIAN_POINT('',(0.E+000,-0.615)); -#59791 = VECTOR('',#59792,1.); -#59792 = DIRECTION('',(0.E+000,-1.)); -#59793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59794 = ORIENTED_EDGE('',*,*,#59795,.F.); -#59795 = EDGE_CURVE('',#59796,#59768,#59798,.T.); -#59796 = VERTEX_POINT('',#59797); -#59797 = CARTESIAN_POINT('',(0.775,-0.985,-1.85)); -#59798 = SURFACE_CURVE('',#59799,(#59803,#59810),.PCURVE_S1.); -#59799 = LINE('',#59800,#59801); -#59800 = CARTESIAN_POINT('',(0.775,-0.985,-1.85)); -#59801 = VECTOR('',#59802,1.); -#59802 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59803 = PCURVE('',#42865,#59804); -#59804 = DEFINITIONAL_REPRESENTATION('',(#59805),#59809); -#59805 = LINE('',#59806,#59807); -#59806 = CARTESIAN_POINT('',(0.32,-1.015)); -#59807 = VECTOR('',#59808,1.); -#59808 = DIRECTION('',(-1.,0.E+000)); -#59809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59810 = PCURVE('',#59811,#59816); -#59811 = PLANE('',#59812); -#59812 = AXIS2_PLACEMENT_3D('',#59813,#59814,#59815); -#59813 = CARTESIAN_POINT('',(0.775,0.E+000,0.E+000)); -#59814 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59815 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59816 = DEFINITIONAL_REPRESENTATION('',(#59817),#59821); -#59817 = LINE('',#59818,#59819); -#59818 = CARTESIAN_POINT('',(1.85,-0.985)); -#59819 = VECTOR('',#59820,1.); -#59820 = DIRECTION('',(-1.,0.E+000)); -#59821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59822 = ORIENTED_EDGE('',*,*,#59823,.F.); -#59823 = EDGE_CURVE('',#59824,#59796,#59826,.T.); -#59824 = VERTEX_POINT('',#59825); -#59825 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); -#59826 = SURFACE_CURVE('',#59827,(#59831,#59838),.PCURVE_S1.); -#59827 = LINE('',#59828,#59829); -#59828 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); -#59829 = VECTOR('',#59830,1.); -#59830 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59831 = PCURVE('',#42865,#59832); -#59832 = DEFINITIONAL_REPRESENTATION('',(#59833),#59837); -#59833 = LINE('',#59834,#59835); -#59834 = CARTESIAN_POINT('',(0.32,-1.265)); -#59835 = VECTOR('',#59836,1.); -#59836 = DIRECTION('',(0.E+000,1.)); -#59837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59838 = PCURVE('',#59839,#59844); -#59839 = PLANE('',#59840); -#59840 = AXIS2_PLACEMENT_3D('',#59841,#59842,#59843); -#59841 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); -#59842 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#59843 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#59844 = DEFINITIONAL_REPRESENTATION('',(#59845),#59849); -#59845 = LINE('',#59846,#59847); -#59846 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59847 = VECTOR('',#59848,1.); -#59848 = DIRECTION('',(0.E+000,1.)); -#59849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59850 = ORIENTED_EDGE('',*,*,#59851,.T.); -#59851 = EDGE_CURVE('',#59824,#59852,#59854,.T.); -#59852 = VERTEX_POINT('',#59853); -#59853 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); -#59854 = SURFACE_CURVE('',#59855,(#59859,#59866),.PCURVE_S1.); -#59855 = LINE('',#59856,#59857); -#59856 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); -#59857 = VECTOR('',#59858,1.); -#59858 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59859 = PCURVE('',#42865,#59860); -#59860 = DEFINITIONAL_REPRESENTATION('',(#59861),#59865); -#59861 = LINE('',#59862,#59863); -#59862 = CARTESIAN_POINT('',(0.32,-1.265)); -#59863 = VECTOR('',#59864,1.); -#59864 = DIRECTION('',(-1.,0.E+000)); -#59865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59866 = PCURVE('',#59867,#59872); -#59867 = PLANE('',#59868); -#59868 = AXIS2_PLACEMENT_3D('',#59869,#59870,#59871); -#59869 = CARTESIAN_POINT('',(0.525,0.E+000,0.E+000)); -#59870 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59871 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59872 = DEFINITIONAL_REPRESENTATION('',(#59873),#59877); -#59873 = LINE('',#59874,#59875); -#59874 = CARTESIAN_POINT('',(1.85,-0.985)); -#59875 = VECTOR('',#59876,1.); -#59876 = DIRECTION('',(-1.,0.E+000)); -#59877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59878 = ORIENTED_EDGE('',*,*,#59879,.T.); -#59879 = EDGE_CURVE('',#59852,#59880,#59882,.T.); -#59880 = VERTEX_POINT('',#59881); -#59881 = CARTESIAN_POINT('',(0.125,-0.985,-1.71)); -#59882 = SURFACE_CURVE('',#59883,(#59887,#59894),.PCURVE_S1.); -#59883 = LINE('',#59884,#59885); -#59884 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); -#59885 = VECTOR('',#59886,1.); -#59886 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#59887 = PCURVE('',#42865,#59888); -#59888 = DEFINITIONAL_REPRESENTATION('',(#59889),#59893); -#59889 = LINE('',#59890,#59891); -#59890 = CARTESIAN_POINT('',(0.18,-1.265)); -#59891 = VECTOR('',#59892,1.); -#59892 = DIRECTION('',(0.E+000,-1.)); -#59893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59894 = PCURVE('',#59895,#59900); -#59895 = PLANE('',#59896); -#59896 = AXIS2_PLACEMENT_3D('',#59897,#59898,#59899); -#59897 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#59898 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59899 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#59900 = DEFINITIONAL_REPRESENTATION('',(#59901),#59905); -#59901 = LINE('',#59902,#59903); -#59902 = CARTESIAN_POINT('',(0.E+000,-1.265)); -#59903 = VECTOR('',#59904,1.); -#59904 = DIRECTION('',(0.E+000,-1.)); -#59905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59906 = ORIENTED_EDGE('',*,*,#59907,.F.); -#59907 = EDGE_CURVE('',#59908,#59880,#59910,.T.); -#59908 = VERTEX_POINT('',#59909); -#59909 = CARTESIAN_POINT('',(0.125,-0.985,-1.85)); -#59910 = SURFACE_CURVE('',#59911,(#59915,#59922),.PCURVE_S1.); -#59911 = LINE('',#59912,#59913); -#59912 = CARTESIAN_POINT('',(0.125,-0.985,-1.85)); -#59913 = VECTOR('',#59914,1.); -#59914 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59915 = PCURVE('',#42865,#59916); -#59916 = DEFINITIONAL_REPRESENTATION('',(#59917),#59921); -#59917 = LINE('',#59918,#59919); -#59918 = CARTESIAN_POINT('',(0.32,-1.665)); -#59919 = VECTOR('',#59920,1.); -#59920 = DIRECTION('',(-1.,0.E+000)); -#59921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59922 = PCURVE('',#59923,#59928); -#59923 = PLANE('',#59924); -#59924 = AXIS2_PLACEMENT_3D('',#59925,#59926,#59927); -#59925 = CARTESIAN_POINT('',(0.125,0.E+000,0.E+000)); -#59926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59927 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59928 = DEFINITIONAL_REPRESENTATION('',(#59929),#59933); -#59929 = LINE('',#59930,#59931); -#59930 = CARTESIAN_POINT('',(1.85,-0.985)); -#59931 = VECTOR('',#59932,1.); -#59932 = DIRECTION('',(-1.,0.E+000)); -#59933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59934 = ORIENTED_EDGE('',*,*,#59935,.F.); -#59935 = EDGE_CURVE('',#59936,#59908,#59938,.T.); -#59936 = VERTEX_POINT('',#59937); -#59937 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); -#59938 = SURFACE_CURVE('',#59939,(#59943,#59950),.PCURVE_S1.); -#59939 = LINE('',#59940,#59941); -#59940 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); -#59941 = VECTOR('',#59942,1.); -#59942 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59943 = PCURVE('',#42865,#59944); -#59944 = DEFINITIONAL_REPRESENTATION('',(#59945),#59949); -#59945 = LINE('',#59946,#59947); -#59946 = CARTESIAN_POINT('',(0.32,-1.915)); -#59947 = VECTOR('',#59948,1.); -#59948 = DIRECTION('',(0.E+000,1.)); -#59949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59950 = PCURVE('',#59951,#59956); -#59951 = PLANE('',#59952); -#59952 = AXIS2_PLACEMENT_3D('',#59953,#59954,#59955); -#59953 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); -#59954 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#59955 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#59956 = DEFINITIONAL_REPRESENTATION('',(#59957),#59961); -#59957 = LINE('',#59958,#59959); -#59958 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#59959 = VECTOR('',#59960,1.); -#59960 = DIRECTION('',(0.E+000,1.)); -#59961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59962 = ORIENTED_EDGE('',*,*,#59963,.T.); -#59963 = EDGE_CURVE('',#59936,#59964,#59966,.T.); -#59964 = VERTEX_POINT('',#59965); -#59965 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); -#59966 = SURFACE_CURVE('',#59967,(#59971,#59978),.PCURVE_S1.); -#59967 = LINE('',#59968,#59969); -#59968 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); -#59969 = VECTOR('',#59970,1.); -#59970 = DIRECTION('',(0.E+000,0.E+000,1.)); -#59971 = PCURVE('',#42865,#59972); -#59972 = DEFINITIONAL_REPRESENTATION('',(#59973),#59977); -#59973 = LINE('',#59974,#59975); -#59974 = CARTESIAN_POINT('',(0.32,-1.915)); -#59975 = VECTOR('',#59976,1.); -#59976 = DIRECTION('',(-1.,0.E+000)); -#59977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59978 = PCURVE('',#59979,#59984); -#59979 = PLANE('',#59980); -#59980 = AXIS2_PLACEMENT_3D('',#59981,#59982,#59983); -#59981 = CARTESIAN_POINT('',(-0.125,0.E+000,0.E+000)); -#59982 = DIRECTION('',(1.,0.E+000,0.E+000)); -#59983 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#59984 = DEFINITIONAL_REPRESENTATION('',(#59985),#59989); -#59985 = LINE('',#59986,#59987); -#59986 = CARTESIAN_POINT('',(1.85,-0.985)); -#59987 = VECTOR('',#59988,1.); -#59988 = DIRECTION('',(-1.,0.E+000)); -#59989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#59990 = ORIENTED_EDGE('',*,*,#59991,.T.); -#59991 = EDGE_CURVE('',#59964,#59992,#59994,.T.); -#59992 = VERTEX_POINT('',#59993); -#59993 = CARTESIAN_POINT('',(-0.525,-0.985,-1.71)); -#59994 = SURFACE_CURVE('',#59995,(#59999,#60006),.PCURVE_S1.); -#59995 = LINE('',#59996,#59997); -#59996 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); -#59997 = VECTOR('',#59998,1.); -#59998 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#59999 = PCURVE('',#42865,#60000); -#60000 = DEFINITIONAL_REPRESENTATION('',(#60001),#60005); -#60001 = LINE('',#60002,#60003); -#60002 = CARTESIAN_POINT('',(0.18,-1.915)); -#60003 = VECTOR('',#60004,1.); -#60004 = DIRECTION('',(0.E+000,-1.)); -#60005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60006 = PCURVE('',#60007,#60012); -#60007 = PLANE('',#60008); -#60008 = AXIS2_PLACEMENT_3D('',#60009,#60010,#60011); -#60009 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#60010 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60011 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60012 = DEFINITIONAL_REPRESENTATION('',(#60013),#60017); -#60013 = LINE('',#60014,#60015); -#60014 = CARTESIAN_POINT('',(0.E+000,-1.915)); -#60015 = VECTOR('',#60016,1.); -#60016 = DIRECTION('',(0.E+000,-1.)); -#60017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60018 = ORIENTED_EDGE('',*,*,#60019,.F.); -#60019 = EDGE_CURVE('',#60020,#59992,#60022,.T.); -#60020 = VERTEX_POINT('',#60021); -#60021 = CARTESIAN_POINT('',(-0.525,-0.985,-1.85)); -#60022 = SURFACE_CURVE('',#60023,(#60027,#60034),.PCURVE_S1.); -#60023 = LINE('',#60024,#60025); -#60024 = CARTESIAN_POINT('',(-0.525,-0.985,-1.85)); -#60025 = VECTOR('',#60026,1.); -#60026 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60027 = PCURVE('',#42865,#60028); -#60028 = DEFINITIONAL_REPRESENTATION('',(#60029),#60033); -#60029 = LINE('',#60030,#60031); -#60030 = CARTESIAN_POINT('',(0.32,-2.315)); -#60031 = VECTOR('',#60032,1.); -#60032 = DIRECTION('',(-1.,0.E+000)); -#60033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60034 = PCURVE('',#60035,#60040); -#60035 = PLANE('',#60036); -#60036 = AXIS2_PLACEMENT_3D('',#60037,#60038,#60039); -#60037 = CARTESIAN_POINT('',(-0.525,0.E+000,0.E+000)); -#60038 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60039 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60040 = DEFINITIONAL_REPRESENTATION('',(#60041),#60045); -#60041 = LINE('',#60042,#60043); -#60042 = CARTESIAN_POINT('',(1.85,-0.985)); -#60043 = VECTOR('',#60044,1.); -#60044 = DIRECTION('',(-1.,0.E+000)); -#60045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60046 = ORIENTED_EDGE('',*,*,#60047,.F.); -#60047 = EDGE_CURVE('',#60048,#60020,#60050,.T.); -#60048 = VERTEX_POINT('',#60049); -#60049 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); -#60050 = SURFACE_CURVE('',#60051,(#60055,#60062),.PCURVE_S1.); -#60051 = LINE('',#60052,#60053); -#60052 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); -#60053 = VECTOR('',#60054,1.); -#60054 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60055 = PCURVE('',#42865,#60056); -#60056 = DEFINITIONAL_REPRESENTATION('',(#60057),#60061); -#60057 = LINE('',#60058,#60059); -#60058 = CARTESIAN_POINT('',(0.32,-2.565)); -#60059 = VECTOR('',#60060,1.); -#60060 = DIRECTION('',(0.E+000,1.)); -#60061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60062 = PCURVE('',#60063,#60068); -#60063 = PLANE('',#60064); -#60064 = AXIS2_PLACEMENT_3D('',#60065,#60066,#60067); -#60065 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); -#60066 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#60067 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#60068 = DEFINITIONAL_REPRESENTATION('',(#60069),#60073); -#60069 = LINE('',#60070,#60071); -#60070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#60071 = VECTOR('',#60072,1.); -#60072 = DIRECTION('',(0.E+000,1.)); -#60073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60074 = ORIENTED_EDGE('',*,*,#60075,.T.); -#60075 = EDGE_CURVE('',#60048,#60076,#60078,.T.); -#60076 = VERTEX_POINT('',#60077); -#60077 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); -#60078 = SURFACE_CURVE('',#60079,(#60083,#60090),.PCURVE_S1.); -#60079 = LINE('',#60080,#60081); -#60080 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); -#60081 = VECTOR('',#60082,1.); -#60082 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60083 = PCURVE('',#42865,#60084); -#60084 = DEFINITIONAL_REPRESENTATION('',(#60085),#60089); -#60085 = LINE('',#60086,#60087); -#60086 = CARTESIAN_POINT('',(0.32,-2.565)); -#60087 = VECTOR('',#60088,1.); -#60088 = DIRECTION('',(-1.,0.E+000)); -#60089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60090 = PCURVE('',#60091,#60096); -#60091 = PLANE('',#60092); -#60092 = AXIS2_PLACEMENT_3D('',#60093,#60094,#60095); -#60093 = CARTESIAN_POINT('',(-0.775,0.E+000,0.E+000)); -#60094 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60095 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60096 = DEFINITIONAL_REPRESENTATION('',(#60097),#60101); -#60097 = LINE('',#60098,#60099); -#60098 = CARTESIAN_POINT('',(1.85,-0.985)); -#60099 = VECTOR('',#60100,1.); -#60100 = DIRECTION('',(-1.,0.E+000)); -#60101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60102 = ORIENTED_EDGE('',*,*,#60103,.T.); -#60103 = EDGE_CURVE('',#60076,#60104,#60106,.T.); -#60104 = VERTEX_POINT('',#60105); -#60105 = CARTESIAN_POINT('',(-1.175,-0.985,-1.71)); -#60106 = SURFACE_CURVE('',#60107,(#60111,#60118),.PCURVE_S1.); -#60107 = LINE('',#60108,#60109); -#60108 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); -#60109 = VECTOR('',#60110,1.); -#60110 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60111 = PCURVE('',#42865,#60112); -#60112 = DEFINITIONAL_REPRESENTATION('',(#60113),#60117); -#60113 = LINE('',#60114,#60115); -#60114 = CARTESIAN_POINT('',(0.18,-2.565)); -#60115 = VECTOR('',#60116,1.); -#60116 = DIRECTION('',(0.E+000,-1.)); -#60117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60118 = PCURVE('',#60119,#60124); -#60119 = PLANE('',#60120); -#60120 = AXIS2_PLACEMENT_3D('',#60121,#60122,#60123); -#60121 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#60122 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60123 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60124 = DEFINITIONAL_REPRESENTATION('',(#60125),#60129); -#60125 = LINE('',#60126,#60127); -#60126 = CARTESIAN_POINT('',(0.E+000,-2.565)); -#60127 = VECTOR('',#60128,1.); -#60128 = DIRECTION('',(0.E+000,-1.)); -#60129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60130 = ORIENTED_EDGE('',*,*,#60131,.F.); -#60131 = EDGE_CURVE('',#60132,#60104,#60134,.T.); -#60132 = VERTEX_POINT('',#60133); -#60133 = CARTESIAN_POINT('',(-1.175,-0.985,-1.85)); -#60134 = SURFACE_CURVE('',#60135,(#60139,#60146),.PCURVE_S1.); -#60135 = LINE('',#60136,#60137); -#60136 = CARTESIAN_POINT('',(-1.175,-0.985,-1.85)); -#60137 = VECTOR('',#60138,1.); -#60138 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60139 = PCURVE('',#42865,#60140); -#60140 = DEFINITIONAL_REPRESENTATION('',(#60141),#60145); -#60141 = LINE('',#60142,#60143); -#60142 = CARTESIAN_POINT('',(0.32,-2.965)); -#60143 = VECTOR('',#60144,1.); -#60144 = DIRECTION('',(-1.,0.E+000)); -#60145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60146 = PCURVE('',#60147,#60152); -#60147 = PLANE('',#60148); -#60148 = AXIS2_PLACEMENT_3D('',#60149,#60150,#60151); -#60149 = CARTESIAN_POINT('',(-1.175,0.E+000,0.E+000)); -#60150 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60151 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60152 = DEFINITIONAL_REPRESENTATION('',(#60153),#60157); -#60153 = LINE('',#60154,#60155); -#60154 = CARTESIAN_POINT('',(1.85,-0.985)); -#60155 = VECTOR('',#60156,1.); -#60156 = DIRECTION('',(-1.,0.E+000)); -#60157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60158 = ORIENTED_EDGE('',*,*,#60159,.F.); -#60159 = EDGE_CURVE('',#60160,#60132,#60162,.T.); -#60160 = VERTEX_POINT('',#60161); -#60161 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); -#60162 = SURFACE_CURVE('',#60163,(#60167,#60174),.PCURVE_S1.); -#60163 = LINE('',#60164,#60165); -#60164 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); -#60165 = VECTOR('',#60166,1.); -#60166 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60167 = PCURVE('',#42865,#60168); -#60168 = DEFINITIONAL_REPRESENTATION('',(#60169),#60173); -#60169 = LINE('',#60170,#60171); -#60170 = CARTESIAN_POINT('',(0.32,-3.215)); -#60171 = VECTOR('',#60172,1.); -#60172 = DIRECTION('',(0.E+000,1.)); -#60173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60174 = PCURVE('',#60175,#60180); -#60175 = PLANE('',#60176); -#60176 = AXIS2_PLACEMENT_3D('',#60177,#60178,#60179); -#60177 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); -#60178 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#60179 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#60180 = DEFINITIONAL_REPRESENTATION('',(#60181),#60185); -#60181 = LINE('',#60182,#60183); -#60182 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#60183 = VECTOR('',#60184,1.); -#60184 = DIRECTION('',(0.E+000,1.)); -#60185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60186 = ORIENTED_EDGE('',*,*,#60187,.T.); -#60187 = EDGE_CURVE('',#60160,#60188,#60190,.T.); -#60188 = VERTEX_POINT('',#60189); -#60189 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); -#60190 = SURFACE_CURVE('',#60191,(#60195,#60202),.PCURVE_S1.); -#60191 = LINE('',#60192,#60193); -#60192 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); -#60193 = VECTOR('',#60194,1.); -#60194 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60195 = PCURVE('',#42865,#60196); -#60196 = DEFINITIONAL_REPRESENTATION('',(#60197),#60201); -#60197 = LINE('',#60198,#60199); -#60198 = CARTESIAN_POINT('',(0.32,-3.215)); -#60199 = VECTOR('',#60200,1.); -#60200 = DIRECTION('',(-1.,0.E+000)); -#60201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60202 = PCURVE('',#60203,#60208); -#60203 = PLANE('',#60204); -#60204 = AXIS2_PLACEMENT_3D('',#60205,#60206,#60207); -#60205 = CARTESIAN_POINT('',(-1.425,0.E+000,0.E+000)); -#60206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60207 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60208 = DEFINITIONAL_REPRESENTATION('',(#60209),#60213); -#60209 = LINE('',#60210,#60211); -#60210 = CARTESIAN_POINT('',(1.85,-0.985)); -#60211 = VECTOR('',#60212,1.); -#60212 = DIRECTION('',(-1.,0.E+000)); -#60213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60214 = ORIENTED_EDGE('',*,*,#60215,.T.); -#60215 = EDGE_CURVE('',#60188,#60216,#60218,.T.); -#60216 = VERTEX_POINT('',#60217); -#60217 = CARTESIAN_POINT('',(-1.79,-0.985,-1.71)); -#60218 = SURFACE_CURVE('',#60219,(#60223,#60230),.PCURVE_S1.); -#60219 = LINE('',#60220,#60221); -#60220 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); -#60221 = VECTOR('',#60222,1.); -#60222 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60223 = PCURVE('',#42865,#60224); -#60224 = DEFINITIONAL_REPRESENTATION('',(#60225),#60229); -#60225 = LINE('',#60226,#60227); -#60226 = CARTESIAN_POINT('',(0.18,-3.215)); -#60227 = VECTOR('',#60228,1.); -#60228 = DIRECTION('',(0.E+000,-1.)); -#60229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60230 = PCURVE('',#60231,#60236); -#60231 = PLANE('',#60232); -#60232 = AXIS2_PLACEMENT_3D('',#60233,#60234,#60235); -#60233 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#60234 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60235 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60236 = DEFINITIONAL_REPRESENTATION('',(#60237),#60241); -#60237 = LINE('',#60238,#60239); -#60238 = CARTESIAN_POINT('',(0.E+000,-3.215)); -#60239 = VECTOR('',#60240,1.); -#60240 = DIRECTION('',(0.E+000,-1.)); -#60241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60242 = ORIENTED_EDGE('',*,*,#60243,.F.); -#60243 = EDGE_CURVE('',#59552,#60216,#60244,.T.); -#60244 = SURFACE_CURVE('',#60245,(#60249,#60256),.PCURVE_S1.); -#60245 = LINE('',#60246,#60247); -#60246 = CARTESIAN_POINT('',(-1.79,-0.985,-1.53)); -#60247 = VECTOR('',#60248,1.); -#60248 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60249 = PCURVE('',#42865,#60250); -#60250 = DEFINITIONAL_REPRESENTATION('',(#60251),#60255); -#60251 = LINE('',#60252,#60253); -#60252 = CARTESIAN_POINT('',(0.E+000,-3.58)); -#60253 = VECTOR('',#60254,1.); -#60254 = DIRECTION('',(1.,0.E+000)); -#60255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60256 = PCURVE('',#41870,#60257); -#60257 = DEFINITIONAL_REPRESENTATION('',(#60258),#60262); -#60258 = LINE('',#60259,#60260); -#60259 = CARTESIAN_POINT('',(0.32,-0.24)); -#60260 = VECTOR('',#60261,1.); -#60261 = DIRECTION('',(1.,0.E+000)); -#60262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60263 = ORIENTED_EDGE('',*,*,#59551,.F.); -#60264 = ORIENTED_EDGE('',*,*,#42849,.T.); -#60265 = ORIENTED_EDGE('',*,*,#60266,.T.); -#60266 = EDGE_CURVE('',#42822,#60267,#60269,.T.); -#60267 = VERTEX_POINT('',#60268); -#60268 = CARTESIAN_POINT('',(1.425,-0.985,-1.71)); -#60269 = SURFACE_CURVE('',#60270,(#60274,#60281),.PCURVE_S1.); -#60270 = LINE('',#60271,#60272); -#60271 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); -#60272 = VECTOR('',#60273,1.); -#60273 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60274 = PCURVE('',#42865,#60275); -#60275 = DEFINITIONAL_REPRESENTATION('',(#60276),#60280); -#60276 = LINE('',#60277,#60278); -#60277 = CARTESIAN_POINT('',(0.18,0.E+000)); -#60278 = VECTOR('',#60279,1.); -#60279 = DIRECTION('',(0.E+000,-1.)); -#60280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60281 = PCURVE('',#42837,#60282); -#60282 = DEFINITIONAL_REPRESENTATION('',(#60283),#60287); -#60283 = LINE('',#60284,#60285); -#60284 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#60285 = VECTOR('',#60286,1.); -#60286 = DIRECTION('',(0.E+000,-1.)); -#60287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60288 = ORIENTED_EDGE('',*,*,#60289,.F.); -#60289 = EDGE_CURVE('',#60290,#60267,#60292,.T.); -#60290 = VERTEX_POINT('',#60291); -#60291 = CARTESIAN_POINT('',(1.425,-0.985,-1.85)); -#60292 = SURFACE_CURVE('',#60293,(#60297,#60304),.PCURVE_S1.); -#60293 = LINE('',#60294,#60295); -#60294 = CARTESIAN_POINT('',(1.425,-0.985,-1.85)); -#60295 = VECTOR('',#60296,1.); -#60296 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60297 = PCURVE('',#42865,#60298); -#60298 = DEFINITIONAL_REPRESENTATION('',(#60299),#60303); -#60299 = LINE('',#60300,#60301); -#60300 = CARTESIAN_POINT('',(0.32,-0.365)); -#60301 = VECTOR('',#60302,1.); -#60302 = DIRECTION('',(-1.,0.E+000)); -#60303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60304 = PCURVE('',#60305,#60310); -#60305 = PLANE('',#60306); -#60306 = AXIS2_PLACEMENT_3D('',#60307,#60308,#60309); -#60307 = CARTESIAN_POINT('',(1.425,0.E+000,0.E+000)); -#60308 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60309 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60310 = DEFINITIONAL_REPRESENTATION('',(#60311),#60315); -#60311 = LINE('',#60312,#60313); -#60312 = CARTESIAN_POINT('',(1.85,-0.985)); -#60313 = VECTOR('',#60314,1.); -#60314 = DIRECTION('',(-1.,0.E+000)); -#60315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60316 = ORIENTED_EDGE('',*,*,#60317,.F.); -#60317 = EDGE_CURVE('',#59738,#60290,#60318,.T.); -#60318 = SURFACE_CURVE('',#60319,(#60323,#60330),.PCURVE_S1.); -#60319 = LINE('',#60320,#60321); -#60320 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); -#60321 = VECTOR('',#60322,1.); -#60322 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60323 = PCURVE('',#42865,#60324); -#60324 = DEFINITIONAL_REPRESENTATION('',(#60325),#60329); -#60325 = LINE('',#60326,#60327); -#60326 = CARTESIAN_POINT('',(0.32,-0.615)); -#60327 = VECTOR('',#60328,1.); -#60328 = DIRECTION('',(0.E+000,1.)); -#60329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60330 = PCURVE('',#60331,#60336); -#60331 = PLANE('',#60332); -#60332 = AXIS2_PLACEMENT_3D('',#60333,#60334,#60335); -#60333 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); -#60334 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#60335 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#60336 = DEFINITIONAL_REPRESENTATION('',(#60337),#60341); -#60337 = LINE('',#60338,#60339); -#60338 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#60339 = VECTOR('',#60340,1.); -#60340 = DIRECTION('',(0.E+000,1.)); -#60341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60342 = ADVANCED_FACE('',(#60343),#59755,.T.); -#60343 = FACE_BOUND('',#60344,.F.); -#60344 = EDGE_LOOP('',(#60345,#60375,#60396,#60397)); -#60345 = ORIENTED_EDGE('',*,*,#60346,.F.); -#60346 = EDGE_CURVE('',#60347,#60349,#60351,.T.); -#60347 = VERTEX_POINT('',#60348); -#60348 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); -#60349 = VERTEX_POINT('',#60350); -#60350 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); -#60351 = SURFACE_CURVE('',#60352,(#60356,#60363),.PCURVE_S1.); -#60352 = LINE('',#60353,#60354); -#60353 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); -#60354 = VECTOR('',#60355,1.); -#60355 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60356 = PCURVE('',#59755,#60357); -#60357 = DEFINITIONAL_REPRESENTATION('',(#60358),#60362); -#60358 = LINE('',#60359,#60360); -#60359 = CARTESIAN_POINT('',(1.71,-1.105)); -#60360 = VECTOR('',#60361,1.); -#60361 = DIRECTION('',(1.,0.E+000)); -#60362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60363 = PCURVE('',#60364,#60369); -#60364 = PLANE('',#60365); -#60365 = AXIS2_PLACEMENT_3D('',#60366,#60367,#60368); -#60366 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#60367 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60368 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60369 = DEFINITIONAL_REPRESENTATION('',(#60370),#60374); -#60370 = LINE('',#60371,#60372); -#60371 = CARTESIAN_POINT('',(0.E+000,-0.615)); -#60372 = VECTOR('',#60373,1.); -#60373 = DIRECTION('',(1.,0.E+000)); -#60374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60375 = ORIENTED_EDGE('',*,*,#60376,.F.); -#60376 = EDGE_CURVE('',#59740,#60347,#60377,.T.); -#60377 = SURFACE_CURVE('',#60378,(#60382,#60389),.PCURVE_S1.); -#60378 = LINE('',#60379,#60380); -#60379 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); -#60380 = VECTOR('',#60381,1.); -#60381 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60382 = PCURVE('',#59755,#60383); -#60383 = DEFINITIONAL_REPRESENTATION('',(#60384),#60388); -#60384 = LINE('',#60385,#60386); -#60385 = CARTESIAN_POINT('',(1.71,-0.985)); -#60386 = VECTOR('',#60387,1.); -#60387 = DIRECTION('',(0.E+000,-1.)); -#60388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60389 = PCURVE('',#59783,#60390); -#60390 = DEFINITIONAL_REPRESENTATION('',(#60391),#60395); -#60391 = LINE('',#60392,#60393); -#60392 = CARTESIAN_POINT('',(0.E+000,-0.615)); -#60393 = VECTOR('',#60394,1.); -#60394 = DIRECTION('',(1.,0.E+000)); -#60395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60396 = ORIENTED_EDGE('',*,*,#59737,.F.); -#60397 = ORIENTED_EDGE('',*,*,#60398,.F.); -#60398 = EDGE_CURVE('',#60349,#59738,#60399,.T.); -#60399 = SURFACE_CURVE('',#60400,(#60404,#60411),.PCURVE_S1.); -#60400 = LINE('',#60401,#60402); -#60401 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); -#60402 = VECTOR('',#60403,1.); -#60403 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#60404 = PCURVE('',#59755,#60405); -#60405 = DEFINITIONAL_REPRESENTATION('',(#60406),#60410); -#60406 = LINE('',#60407,#60408); -#60407 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#60408 = VECTOR('',#60409,1.); -#60409 = DIRECTION('',(-0.258819045102,0.965925826289)); -#60410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60411 = PCURVE('',#60331,#60412); -#60412 = DEFINITIONAL_REPRESENTATION('',(#60413),#60417); -#60413 = LINE('',#60414,#60415); -#60414 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#60415 = VECTOR('',#60416,1.); -#60416 = DIRECTION('',(-1.,0.E+000)); -#60417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60418 = ADVANCED_FACE('',(#60419),#60433,.T.); -#60419 = FACE_BOUND('',#60420,.F.); -#60420 = EDGE_LOOP('',(#60421,#60451,#60479,#60502,#60525)); -#60421 = ORIENTED_EDGE('',*,*,#60422,.T.); -#60422 = EDGE_CURVE('',#60423,#60425,#60427,.T.); -#60423 = VERTEX_POINT('',#60424); -#60424 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); -#60425 = VERTEX_POINT('',#60426); -#60426 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); -#60427 = SURFACE_CURVE('',#60428,(#60432,#60444),.PCURVE_S1.); -#60428 = LINE('',#60429,#60430); -#60429 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); -#60430 = VECTOR('',#60431,1.); -#60431 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60432 = PCURVE('',#60433,#60438); -#60433 = PLANE('',#60434); -#60434 = AXIS2_PLACEMENT_3D('',#60435,#60436,#60437); -#60435 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#60436 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60437 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60438 = DEFINITIONAL_REPRESENTATION('',(#60439),#60443); -#60439 = LINE('',#60440,#60441); -#60440 = CARTESIAN_POINT('',(0.E+000,-3.215)); -#60441 = VECTOR('',#60442,1.); -#60442 = DIRECTION('',(1.,0.E+000)); -#60443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60444 = PCURVE('',#60203,#60445); -#60445 = DEFINITIONAL_REPRESENTATION('',(#60446),#60450); -#60446 = LINE('',#60447,#60448); -#60447 = CARTESIAN_POINT('',(1.71,-1.105)); -#60448 = VECTOR('',#60449,1.); -#60449 = DIRECTION('',(1.,0.E+000)); -#60450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60451 = ORIENTED_EDGE('',*,*,#60452,.T.); -#60452 = EDGE_CURVE('',#60425,#60453,#60455,.T.); -#60453 = VERTEX_POINT('',#60454); -#60454 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); -#60455 = SURFACE_CURVE('',#60456,(#60460,#60467),.PCURVE_S1.); -#60456 = LINE('',#60457,#60458); -#60457 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); -#60458 = VECTOR('',#60459,1.); -#60459 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60460 = PCURVE('',#60433,#60461); -#60461 = DEFINITIONAL_REPRESENTATION('',(#60462),#60466); -#60462 = LINE('',#60463,#60464); -#60463 = CARTESIAN_POINT('',(0.172153903092,-3.215)); -#60464 = VECTOR('',#60465,1.); -#60465 = DIRECTION('',(1.,0.E+000)); -#60466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60467 = PCURVE('',#60468,#60473); -#60468 = PLANE('',#60469); -#60469 = AXIS2_PLACEMENT_3D('',#60470,#60471,#60472); -#60470 = CARTESIAN_POINT('',(-1.425,0.E+000,0.E+000)); -#60471 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60472 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60473 = DEFINITIONAL_REPRESENTATION('',(#60474),#60478); -#60474 = LINE('',#60475,#60476); -#60475 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#60476 = VECTOR('',#60477,1.); -#60477 = DIRECTION('',(1.,0.E+000)); -#60478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60479 = ORIENTED_EDGE('',*,*,#60480,.T.); -#60480 = EDGE_CURVE('',#60453,#60481,#60483,.T.); -#60481 = VERTEX_POINT('',#60482); -#60482 = CARTESIAN_POINT('',(-1.79,-1.105,-2.35)); -#60483 = SURFACE_CURVE('',#60484,(#60488,#60495),.PCURVE_S1.); -#60484 = LINE('',#60485,#60486); -#60485 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); -#60486 = VECTOR('',#60487,1.); -#60487 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60488 = PCURVE('',#60433,#60489); -#60489 = DEFINITIONAL_REPRESENTATION('',(#60490),#60494); -#60490 = LINE('',#60491,#60492); -#60491 = CARTESIAN_POINT('',(0.64,-3.215)); -#60492 = VECTOR('',#60493,1.); -#60493 = DIRECTION('',(0.E+000,-1.)); -#60494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60495 = PCURVE('',#42781,#60496); -#60496 = DEFINITIONAL_REPRESENTATION('',(#60497),#60501); -#60497 = LINE('',#60498,#60499); -#60498 = CARTESIAN_POINT('',(-1.425,-1.105)); -#60499 = VECTOR('',#60500,1.); -#60500 = DIRECTION('',(-1.,0.E+000)); -#60501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60502 = ORIENTED_EDGE('',*,*,#60503,.F.); -#60503 = EDGE_CURVE('',#60504,#60481,#60506,.T.); -#60504 = VERTEX_POINT('',#60505); -#60505 = CARTESIAN_POINT('',(-1.79,-1.105,-1.71)); -#60506 = SURFACE_CURVE('',#60507,(#60511,#60518),.PCURVE_S1.); -#60507 = LINE('',#60508,#60509); -#60508 = CARTESIAN_POINT('',(-1.79,-1.105,-1.71)); -#60509 = VECTOR('',#60510,1.); -#60510 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60511 = PCURVE('',#60433,#60512); -#60512 = DEFINITIONAL_REPRESENTATION('',(#60513),#60517); -#60513 = LINE('',#60514,#60515); -#60514 = CARTESIAN_POINT('',(0.E+000,-3.58)); -#60515 = VECTOR('',#60516,1.); -#60516 = DIRECTION('',(1.,0.E+000)); -#60517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60518 = PCURVE('',#41870,#60519); -#60519 = DEFINITIONAL_REPRESENTATION('',(#60520),#60524); -#60520 = LINE('',#60521,#60522); -#60521 = CARTESIAN_POINT('',(0.5,-0.12)); -#60522 = VECTOR('',#60523,1.); -#60523 = DIRECTION('',(1.,0.E+000)); -#60524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60525 = ORIENTED_EDGE('',*,*,#60526,.F.); -#60526 = EDGE_CURVE('',#60423,#60504,#60527,.T.); -#60527 = SURFACE_CURVE('',#60528,(#60532,#60539),.PCURVE_S1.); -#60528 = LINE('',#60529,#60530); -#60529 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); -#60530 = VECTOR('',#60531,1.); -#60531 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60532 = PCURVE('',#60433,#60533); -#60533 = DEFINITIONAL_REPRESENTATION('',(#60534),#60538); -#60534 = LINE('',#60535,#60536); -#60535 = CARTESIAN_POINT('',(0.E+000,-3.215)); -#60536 = VECTOR('',#60537,1.); -#60537 = DIRECTION('',(0.E+000,-1.)); -#60538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60539 = PCURVE('',#60231,#60540); -#60540 = DEFINITIONAL_REPRESENTATION('',(#60541),#60545); -#60541 = LINE('',#60542,#60543); -#60542 = CARTESIAN_POINT('',(0.12,-3.215)); -#60543 = VECTOR('',#60544,1.); -#60544 = DIRECTION('',(0.E+000,-1.)); -#60545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60546 = ADVANCED_FACE('',(#60547),#60561,.T.); -#60547 = FACE_BOUND('',#60548,.F.); -#60548 = EDGE_LOOP('',(#60549,#60579,#60607,#60630,#60658,#60681)); -#60549 = ORIENTED_EDGE('',*,*,#60550,.T.); -#60550 = EDGE_CURVE('',#60551,#60553,#60555,.T.); -#60551 = VERTEX_POINT('',#60552); -#60552 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); -#60553 = VERTEX_POINT('',#60554); -#60554 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); -#60555 = SURFACE_CURVE('',#60556,(#60560,#60572),.PCURVE_S1.); -#60556 = LINE('',#60557,#60558); -#60557 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); -#60558 = VECTOR('',#60559,1.); -#60559 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60560 = PCURVE('',#60561,#60566); -#60561 = PLANE('',#60562); -#60562 = AXIS2_PLACEMENT_3D('',#60563,#60564,#60565); -#60563 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#60564 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60565 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60566 = DEFINITIONAL_REPRESENTATION('',(#60567),#60571); -#60567 = LINE('',#60568,#60569); -#60568 = CARTESIAN_POINT('',(0.E+000,-2.565)); -#60569 = VECTOR('',#60570,1.); -#60570 = DIRECTION('',(1.,0.E+000)); -#60571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60572 = PCURVE('',#60091,#60573); -#60573 = DEFINITIONAL_REPRESENTATION('',(#60574),#60578); -#60574 = LINE('',#60575,#60576); -#60575 = CARTESIAN_POINT('',(1.71,-1.105)); -#60576 = VECTOR('',#60577,1.); -#60577 = DIRECTION('',(1.,0.E+000)); -#60578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60579 = ORIENTED_EDGE('',*,*,#60580,.T.); -#60580 = EDGE_CURVE('',#60553,#60581,#60583,.T.); -#60581 = VERTEX_POINT('',#60582); -#60582 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); -#60583 = SURFACE_CURVE('',#60584,(#60588,#60595),.PCURVE_S1.); -#60584 = LINE('',#60585,#60586); -#60585 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); -#60586 = VECTOR('',#60587,1.); -#60587 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60588 = PCURVE('',#60561,#60589); -#60589 = DEFINITIONAL_REPRESENTATION('',(#60590),#60594); -#60590 = LINE('',#60591,#60592); -#60591 = CARTESIAN_POINT('',(0.172153903092,-2.565)); -#60592 = VECTOR('',#60593,1.); -#60593 = DIRECTION('',(1.,0.E+000)); -#60594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60595 = PCURVE('',#60596,#60601); -#60596 = PLANE('',#60597); -#60597 = AXIS2_PLACEMENT_3D('',#60598,#60599,#60600); -#60598 = CARTESIAN_POINT('',(-0.775,0.E+000,0.E+000)); -#60599 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60600 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60601 = DEFINITIONAL_REPRESENTATION('',(#60602),#60606); -#60602 = LINE('',#60603,#60604); -#60603 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#60604 = VECTOR('',#60605,1.); -#60605 = DIRECTION('',(1.,0.E+000)); -#60606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60607 = ORIENTED_EDGE('',*,*,#60608,.T.); -#60608 = EDGE_CURVE('',#60581,#60609,#60611,.T.); -#60609 = VERTEX_POINT('',#60610); -#60610 = CARTESIAN_POINT('',(-1.175,-1.105,-2.35)); -#60611 = SURFACE_CURVE('',#60612,(#60616,#60623),.PCURVE_S1.); -#60612 = LINE('',#60613,#60614); -#60613 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); -#60614 = VECTOR('',#60615,1.); -#60615 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60616 = PCURVE('',#60561,#60617); -#60617 = DEFINITIONAL_REPRESENTATION('',(#60618),#60622); -#60618 = LINE('',#60619,#60620); -#60619 = CARTESIAN_POINT('',(0.64,-2.565)); -#60620 = VECTOR('',#60621,1.); -#60621 = DIRECTION('',(0.E+000,-1.)); -#60622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60623 = PCURVE('',#42781,#60624); -#60624 = DEFINITIONAL_REPRESENTATION('',(#60625),#60629); -#60625 = LINE('',#60626,#60627); -#60626 = CARTESIAN_POINT('',(-0.775,-1.105)); -#60627 = VECTOR('',#60628,1.); -#60628 = DIRECTION('',(-1.,0.E+000)); -#60629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60630 = ORIENTED_EDGE('',*,*,#60631,.T.); -#60631 = EDGE_CURVE('',#60609,#60632,#60634,.T.); -#60632 = VERTEX_POINT('',#60633); -#60633 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); -#60634 = SURFACE_CURVE('',#60635,(#60639,#60646),.PCURVE_S1.); -#60635 = LINE('',#60636,#60637); -#60636 = CARTESIAN_POINT('',(-1.175,-1.105,-2.35)); -#60637 = VECTOR('',#60638,1.); -#60638 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60639 = PCURVE('',#60561,#60640); -#60640 = DEFINITIONAL_REPRESENTATION('',(#60641),#60645); -#60641 = LINE('',#60642,#60643); -#60642 = CARTESIAN_POINT('',(0.64,-2.965)); -#60643 = VECTOR('',#60644,1.); -#60644 = DIRECTION('',(-1.,0.E+000)); -#60645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60646 = PCURVE('',#60647,#60652); -#60647 = PLANE('',#60648); -#60648 = AXIS2_PLACEMENT_3D('',#60649,#60650,#60651); -#60649 = CARTESIAN_POINT('',(-1.175,0.E+000,0.E+000)); -#60650 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60651 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60652 = DEFINITIONAL_REPRESENTATION('',(#60653),#60657); -#60653 = LINE('',#60654,#60655); -#60654 = CARTESIAN_POINT('',(2.35,-1.105)); -#60655 = VECTOR('',#60656,1.); -#60656 = DIRECTION('',(-1.,0.E+000)); -#60657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60658 = ORIENTED_EDGE('',*,*,#60659,.F.); -#60659 = EDGE_CURVE('',#60660,#60632,#60662,.T.); -#60660 = VERTEX_POINT('',#60661); -#60661 = CARTESIAN_POINT('',(-1.175,-1.105,-1.71)); -#60662 = SURFACE_CURVE('',#60663,(#60667,#60674),.PCURVE_S1.); -#60663 = LINE('',#60664,#60665); -#60664 = CARTESIAN_POINT('',(-1.175,-1.105,-1.71)); -#60665 = VECTOR('',#60666,1.); -#60666 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60667 = PCURVE('',#60561,#60668); -#60668 = DEFINITIONAL_REPRESENTATION('',(#60669),#60673); -#60669 = LINE('',#60670,#60671); -#60670 = CARTESIAN_POINT('',(0.E+000,-2.965)); -#60671 = VECTOR('',#60672,1.); -#60672 = DIRECTION('',(1.,0.E+000)); -#60673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60674 = PCURVE('',#60147,#60675); -#60675 = DEFINITIONAL_REPRESENTATION('',(#60676),#60680); -#60676 = LINE('',#60677,#60678); -#60677 = CARTESIAN_POINT('',(1.71,-1.105)); -#60678 = VECTOR('',#60679,1.); -#60679 = DIRECTION('',(1.,0.E+000)); -#60680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60681 = ORIENTED_EDGE('',*,*,#60682,.F.); -#60682 = EDGE_CURVE('',#60551,#60660,#60683,.T.); -#60683 = SURFACE_CURVE('',#60684,(#60688,#60695),.PCURVE_S1.); -#60684 = LINE('',#60685,#60686); -#60685 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); -#60686 = VECTOR('',#60687,1.); -#60687 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60688 = PCURVE('',#60561,#60689); -#60689 = DEFINITIONAL_REPRESENTATION('',(#60690),#60694); -#60690 = LINE('',#60691,#60692); -#60691 = CARTESIAN_POINT('',(0.E+000,-2.565)); -#60692 = VECTOR('',#60693,1.); -#60693 = DIRECTION('',(0.E+000,-1.)); -#60694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60695 = PCURVE('',#60119,#60696); -#60696 = DEFINITIONAL_REPRESENTATION('',(#60697),#60701); -#60697 = LINE('',#60698,#60699); -#60698 = CARTESIAN_POINT('',(0.12,-2.565)); -#60699 = VECTOR('',#60700,1.); -#60700 = DIRECTION('',(0.E+000,-1.)); -#60701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60702 = ADVANCED_FACE('',(#60703),#60717,.T.); -#60703 = FACE_BOUND('',#60704,.F.); -#60704 = EDGE_LOOP('',(#60705,#60735,#60763,#60786,#60814,#60837)); -#60705 = ORIENTED_EDGE('',*,*,#60706,.T.); -#60706 = EDGE_CURVE('',#60707,#60709,#60711,.T.); -#60707 = VERTEX_POINT('',#60708); -#60708 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); -#60709 = VERTEX_POINT('',#60710); -#60710 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); -#60711 = SURFACE_CURVE('',#60712,(#60716,#60728),.PCURVE_S1.); -#60712 = LINE('',#60713,#60714); -#60713 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); -#60714 = VECTOR('',#60715,1.); -#60715 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60716 = PCURVE('',#60717,#60722); -#60717 = PLANE('',#60718); -#60718 = AXIS2_PLACEMENT_3D('',#60719,#60720,#60721); -#60719 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#60720 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60721 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60722 = DEFINITIONAL_REPRESENTATION('',(#60723),#60727); -#60723 = LINE('',#60724,#60725); -#60724 = CARTESIAN_POINT('',(0.E+000,-1.915)); -#60725 = VECTOR('',#60726,1.); -#60726 = DIRECTION('',(1.,0.E+000)); -#60727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60728 = PCURVE('',#59979,#60729); -#60729 = DEFINITIONAL_REPRESENTATION('',(#60730),#60734); -#60730 = LINE('',#60731,#60732); -#60731 = CARTESIAN_POINT('',(1.71,-1.105)); -#60732 = VECTOR('',#60733,1.); -#60733 = DIRECTION('',(1.,0.E+000)); -#60734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60735 = ORIENTED_EDGE('',*,*,#60736,.T.); -#60736 = EDGE_CURVE('',#60709,#60737,#60739,.T.); -#60737 = VERTEX_POINT('',#60738); -#60738 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); -#60739 = SURFACE_CURVE('',#60740,(#60744,#60751),.PCURVE_S1.); -#60740 = LINE('',#60741,#60742); -#60741 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); -#60742 = VECTOR('',#60743,1.); -#60743 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60744 = PCURVE('',#60717,#60745); -#60745 = DEFINITIONAL_REPRESENTATION('',(#60746),#60750); -#60746 = LINE('',#60747,#60748); -#60747 = CARTESIAN_POINT('',(0.172153903092,-1.915)); -#60748 = VECTOR('',#60749,1.); -#60749 = DIRECTION('',(1.,0.E+000)); -#60750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60751 = PCURVE('',#60752,#60757); -#60752 = PLANE('',#60753); -#60753 = AXIS2_PLACEMENT_3D('',#60754,#60755,#60756); -#60754 = CARTESIAN_POINT('',(-0.125,0.E+000,0.E+000)); -#60755 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60756 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60757 = DEFINITIONAL_REPRESENTATION('',(#60758),#60762); -#60758 = LINE('',#60759,#60760); -#60759 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#60760 = VECTOR('',#60761,1.); -#60761 = DIRECTION('',(1.,0.E+000)); -#60762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60763 = ORIENTED_EDGE('',*,*,#60764,.T.); -#60764 = EDGE_CURVE('',#60737,#60765,#60767,.T.); -#60765 = VERTEX_POINT('',#60766); -#60766 = CARTESIAN_POINT('',(-0.525,-1.105,-2.35)); -#60767 = SURFACE_CURVE('',#60768,(#60772,#60779),.PCURVE_S1.); -#60768 = LINE('',#60769,#60770); -#60769 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); -#60770 = VECTOR('',#60771,1.); -#60771 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60772 = PCURVE('',#60717,#60773); -#60773 = DEFINITIONAL_REPRESENTATION('',(#60774),#60778); -#60774 = LINE('',#60775,#60776); -#60775 = CARTESIAN_POINT('',(0.64,-1.915)); -#60776 = VECTOR('',#60777,1.); -#60777 = DIRECTION('',(0.E+000,-1.)); -#60778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60779 = PCURVE('',#42781,#60780); -#60780 = DEFINITIONAL_REPRESENTATION('',(#60781),#60785); -#60781 = LINE('',#60782,#60783); -#60782 = CARTESIAN_POINT('',(-0.125,-1.105)); -#60783 = VECTOR('',#60784,1.); -#60784 = DIRECTION('',(-1.,0.E+000)); -#60785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60786 = ORIENTED_EDGE('',*,*,#60787,.T.); -#60787 = EDGE_CURVE('',#60765,#60788,#60790,.T.); -#60788 = VERTEX_POINT('',#60789); -#60789 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); -#60790 = SURFACE_CURVE('',#60791,(#60795,#60802),.PCURVE_S1.); -#60791 = LINE('',#60792,#60793); -#60792 = CARTESIAN_POINT('',(-0.525,-1.105,-2.35)); -#60793 = VECTOR('',#60794,1.); -#60794 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60795 = PCURVE('',#60717,#60796); -#60796 = DEFINITIONAL_REPRESENTATION('',(#60797),#60801); -#60797 = LINE('',#60798,#60799); -#60798 = CARTESIAN_POINT('',(0.64,-2.315)); -#60799 = VECTOR('',#60800,1.); -#60800 = DIRECTION('',(-1.,0.E+000)); -#60801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60802 = PCURVE('',#60803,#60808); -#60803 = PLANE('',#60804); -#60804 = AXIS2_PLACEMENT_3D('',#60805,#60806,#60807); -#60805 = CARTESIAN_POINT('',(-0.525,0.E+000,0.E+000)); -#60806 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60807 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60808 = DEFINITIONAL_REPRESENTATION('',(#60809),#60813); -#60809 = LINE('',#60810,#60811); -#60810 = CARTESIAN_POINT('',(2.35,-1.105)); -#60811 = VECTOR('',#60812,1.); -#60812 = DIRECTION('',(-1.,0.E+000)); -#60813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60814 = ORIENTED_EDGE('',*,*,#60815,.F.); -#60815 = EDGE_CURVE('',#60816,#60788,#60818,.T.); -#60816 = VERTEX_POINT('',#60817); -#60817 = CARTESIAN_POINT('',(-0.525,-1.105,-1.71)); -#60818 = SURFACE_CURVE('',#60819,(#60823,#60830),.PCURVE_S1.); -#60819 = LINE('',#60820,#60821); -#60820 = CARTESIAN_POINT('',(-0.525,-1.105,-1.71)); -#60821 = VECTOR('',#60822,1.); -#60822 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60823 = PCURVE('',#60717,#60824); -#60824 = DEFINITIONAL_REPRESENTATION('',(#60825),#60829); -#60825 = LINE('',#60826,#60827); -#60826 = CARTESIAN_POINT('',(0.E+000,-2.315)); -#60827 = VECTOR('',#60828,1.); -#60828 = DIRECTION('',(1.,0.E+000)); -#60829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60830 = PCURVE('',#60035,#60831); -#60831 = DEFINITIONAL_REPRESENTATION('',(#60832),#60836); -#60832 = LINE('',#60833,#60834); -#60833 = CARTESIAN_POINT('',(1.71,-1.105)); -#60834 = VECTOR('',#60835,1.); -#60835 = DIRECTION('',(1.,0.E+000)); -#60836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60837 = ORIENTED_EDGE('',*,*,#60838,.F.); -#60838 = EDGE_CURVE('',#60707,#60816,#60839,.T.); -#60839 = SURFACE_CURVE('',#60840,(#60844,#60851),.PCURVE_S1.); -#60840 = LINE('',#60841,#60842); -#60841 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); -#60842 = VECTOR('',#60843,1.); -#60843 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60844 = PCURVE('',#60717,#60845); -#60845 = DEFINITIONAL_REPRESENTATION('',(#60846),#60850); -#60846 = LINE('',#60847,#60848); -#60847 = CARTESIAN_POINT('',(0.E+000,-1.915)); -#60848 = VECTOR('',#60849,1.); -#60849 = DIRECTION('',(0.E+000,-1.)); -#60850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60851 = PCURVE('',#60007,#60852); -#60852 = DEFINITIONAL_REPRESENTATION('',(#60853),#60857); -#60853 = LINE('',#60854,#60855); -#60854 = CARTESIAN_POINT('',(0.12,-1.915)); -#60855 = VECTOR('',#60856,1.); -#60856 = DIRECTION('',(0.E+000,-1.)); -#60857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60858 = ADVANCED_FACE('',(#60859),#60873,.T.); -#60859 = FACE_BOUND('',#60860,.F.); -#60860 = EDGE_LOOP('',(#60861,#60891,#60919,#60942,#60970,#60993)); -#60861 = ORIENTED_EDGE('',*,*,#60862,.T.); -#60862 = EDGE_CURVE('',#60863,#60865,#60867,.T.); -#60863 = VERTEX_POINT('',#60864); -#60864 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); -#60865 = VERTEX_POINT('',#60866); -#60866 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); -#60867 = SURFACE_CURVE('',#60868,(#60872,#60884),.PCURVE_S1.); -#60868 = LINE('',#60869,#60870); -#60869 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); -#60870 = VECTOR('',#60871,1.); -#60871 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60872 = PCURVE('',#60873,#60878); -#60873 = PLANE('',#60874); -#60874 = AXIS2_PLACEMENT_3D('',#60875,#60876,#60877); -#60875 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#60876 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#60877 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60878 = DEFINITIONAL_REPRESENTATION('',(#60879),#60883); -#60879 = LINE('',#60880,#60881); -#60880 = CARTESIAN_POINT('',(0.E+000,-1.265)); -#60881 = VECTOR('',#60882,1.); -#60882 = DIRECTION('',(1.,0.E+000)); -#60883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60884 = PCURVE('',#59867,#60885); -#60885 = DEFINITIONAL_REPRESENTATION('',(#60886),#60890); -#60886 = LINE('',#60887,#60888); -#60887 = CARTESIAN_POINT('',(1.71,-1.105)); -#60888 = VECTOR('',#60889,1.); -#60889 = DIRECTION('',(1.,0.E+000)); -#60890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60891 = ORIENTED_EDGE('',*,*,#60892,.T.); -#60892 = EDGE_CURVE('',#60865,#60893,#60895,.T.); -#60893 = VERTEX_POINT('',#60894); -#60894 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); -#60895 = SURFACE_CURVE('',#60896,(#60900,#60907),.PCURVE_S1.); -#60896 = LINE('',#60897,#60898); -#60897 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); -#60898 = VECTOR('',#60899,1.); -#60899 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60900 = PCURVE('',#60873,#60901); -#60901 = DEFINITIONAL_REPRESENTATION('',(#60902),#60906); -#60902 = LINE('',#60903,#60904); -#60903 = CARTESIAN_POINT('',(0.172153903092,-1.265)); -#60904 = VECTOR('',#60905,1.); -#60905 = DIRECTION('',(1.,0.E+000)); -#60906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60907 = PCURVE('',#60908,#60913); -#60908 = PLANE('',#60909); -#60909 = AXIS2_PLACEMENT_3D('',#60910,#60911,#60912); -#60910 = CARTESIAN_POINT('',(0.525,0.E+000,0.E+000)); -#60911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60913 = DEFINITIONAL_REPRESENTATION('',(#60914),#60918); -#60914 = LINE('',#60915,#60916); -#60915 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#60916 = VECTOR('',#60917,1.); -#60917 = DIRECTION('',(1.,0.E+000)); -#60918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60919 = ORIENTED_EDGE('',*,*,#60920,.T.); -#60920 = EDGE_CURVE('',#60893,#60921,#60923,.T.); -#60921 = VERTEX_POINT('',#60922); -#60922 = CARTESIAN_POINT('',(0.125,-1.105,-2.35)); -#60923 = SURFACE_CURVE('',#60924,(#60928,#60935),.PCURVE_S1.); -#60924 = LINE('',#60925,#60926); -#60925 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); -#60926 = VECTOR('',#60927,1.); -#60927 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#60928 = PCURVE('',#60873,#60929); -#60929 = DEFINITIONAL_REPRESENTATION('',(#60930),#60934); -#60930 = LINE('',#60931,#60932); -#60931 = CARTESIAN_POINT('',(0.64,-1.265)); -#60932 = VECTOR('',#60933,1.); -#60933 = DIRECTION('',(0.E+000,-1.)); -#60934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60935 = PCURVE('',#42781,#60936); -#60936 = DEFINITIONAL_REPRESENTATION('',(#60937),#60941); -#60937 = LINE('',#60938,#60939); -#60938 = CARTESIAN_POINT('',(0.525,-1.105)); -#60939 = VECTOR('',#60940,1.); -#60940 = DIRECTION('',(-1.,0.E+000)); -#60941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60942 = ORIENTED_EDGE('',*,*,#60943,.T.); -#60943 = EDGE_CURVE('',#60921,#60944,#60946,.T.); -#60944 = VERTEX_POINT('',#60945); -#60945 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); -#60946 = SURFACE_CURVE('',#60947,(#60951,#60958),.PCURVE_S1.); -#60947 = LINE('',#60948,#60949); -#60948 = CARTESIAN_POINT('',(0.125,-1.105,-2.35)); -#60949 = VECTOR('',#60950,1.); -#60950 = DIRECTION('',(0.E+000,0.E+000,1.)); -#60951 = PCURVE('',#60873,#60952); -#60952 = DEFINITIONAL_REPRESENTATION('',(#60953),#60957); -#60953 = LINE('',#60954,#60955); -#60954 = CARTESIAN_POINT('',(0.64,-1.665)); -#60955 = VECTOR('',#60956,1.); -#60956 = DIRECTION('',(-1.,0.E+000)); -#60957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60958 = PCURVE('',#60959,#60964); -#60959 = PLANE('',#60960); -#60960 = AXIS2_PLACEMENT_3D('',#60961,#60962,#60963); -#60961 = CARTESIAN_POINT('',(0.125,0.E+000,0.E+000)); -#60962 = DIRECTION('',(1.,0.E+000,0.E+000)); -#60963 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60964 = DEFINITIONAL_REPRESENTATION('',(#60965),#60969); -#60965 = LINE('',#60966,#60967); -#60966 = CARTESIAN_POINT('',(2.35,-1.105)); -#60967 = VECTOR('',#60968,1.); -#60968 = DIRECTION('',(-1.,0.E+000)); -#60969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60970 = ORIENTED_EDGE('',*,*,#60971,.F.); -#60971 = EDGE_CURVE('',#60972,#60944,#60974,.T.); -#60972 = VERTEX_POINT('',#60973); -#60973 = CARTESIAN_POINT('',(0.125,-1.105,-1.71)); -#60974 = SURFACE_CURVE('',#60975,(#60979,#60986),.PCURVE_S1.); -#60975 = LINE('',#60976,#60977); -#60976 = CARTESIAN_POINT('',(0.125,-1.105,-1.71)); -#60977 = VECTOR('',#60978,1.); -#60978 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#60979 = PCURVE('',#60873,#60980); -#60980 = DEFINITIONAL_REPRESENTATION('',(#60981),#60985); -#60981 = LINE('',#60982,#60983); -#60982 = CARTESIAN_POINT('',(0.E+000,-1.665)); -#60983 = VECTOR('',#60984,1.); -#60984 = DIRECTION('',(1.,0.E+000)); -#60985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60986 = PCURVE('',#59923,#60987); -#60987 = DEFINITIONAL_REPRESENTATION('',(#60988),#60992); -#60988 = LINE('',#60989,#60990); -#60989 = CARTESIAN_POINT('',(1.71,-1.105)); -#60990 = VECTOR('',#60991,1.); -#60991 = DIRECTION('',(1.,0.E+000)); -#60992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#60993 = ORIENTED_EDGE('',*,*,#60994,.F.); -#60994 = EDGE_CURVE('',#60863,#60972,#60995,.T.); -#60995 = SURFACE_CURVE('',#60996,(#61000,#61007),.PCURVE_S1.); -#60996 = LINE('',#60997,#60998); -#60997 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); -#60998 = VECTOR('',#60999,1.); -#60999 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61000 = PCURVE('',#60873,#61001); -#61001 = DEFINITIONAL_REPRESENTATION('',(#61002),#61006); -#61002 = LINE('',#61003,#61004); -#61003 = CARTESIAN_POINT('',(0.E+000,-1.265)); -#61004 = VECTOR('',#61005,1.); -#61005 = DIRECTION('',(0.E+000,-1.)); -#61006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61007 = PCURVE('',#59895,#61008); -#61008 = DEFINITIONAL_REPRESENTATION('',(#61009),#61013); -#61009 = LINE('',#61010,#61011); -#61010 = CARTESIAN_POINT('',(0.12,-1.265)); -#61011 = VECTOR('',#61012,1.); -#61012 = DIRECTION('',(0.E+000,-1.)); -#61013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61014 = ADVANCED_FACE('',(#61015),#60364,.T.); -#61015 = FACE_BOUND('',#61016,.F.); -#61016 = EDGE_LOOP('',(#61017,#61018,#61046,#61069,#61097,#61120)); -#61017 = ORIENTED_EDGE('',*,*,#60346,.T.); -#61018 = ORIENTED_EDGE('',*,*,#61019,.T.); -#61019 = EDGE_CURVE('',#60349,#61020,#61022,.T.); -#61020 = VERTEX_POINT('',#61021); -#61021 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); -#61022 = SURFACE_CURVE('',#61023,(#61027,#61034),.PCURVE_S1.); -#61023 = LINE('',#61024,#61025); -#61024 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); -#61025 = VECTOR('',#61026,1.); -#61026 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61027 = PCURVE('',#60364,#61028); -#61028 = DEFINITIONAL_REPRESENTATION('',(#61029),#61033); -#61029 = LINE('',#61030,#61031); -#61030 = CARTESIAN_POINT('',(0.172153903092,-0.615)); -#61031 = VECTOR('',#61032,1.); -#61032 = DIRECTION('',(1.,0.E+000)); -#61033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61034 = PCURVE('',#61035,#61040); -#61035 = PLANE('',#61036); -#61036 = AXIS2_PLACEMENT_3D('',#61037,#61038,#61039); -#61037 = CARTESIAN_POINT('',(1.175,0.E+000,0.E+000)); -#61038 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61039 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61040 = DEFINITIONAL_REPRESENTATION('',(#61041),#61045); -#61041 = LINE('',#61042,#61043); -#61042 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#61043 = VECTOR('',#61044,1.); -#61044 = DIRECTION('',(1.,0.E+000)); -#61045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61046 = ORIENTED_EDGE('',*,*,#61047,.T.); -#61047 = EDGE_CURVE('',#61020,#61048,#61050,.T.); -#61048 = VERTEX_POINT('',#61049); -#61049 = CARTESIAN_POINT('',(0.775,-1.105,-2.35)); -#61050 = SURFACE_CURVE('',#61051,(#61055,#61062),.PCURVE_S1.); -#61051 = LINE('',#61052,#61053); -#61052 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); -#61053 = VECTOR('',#61054,1.); -#61054 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61055 = PCURVE('',#60364,#61056); -#61056 = DEFINITIONAL_REPRESENTATION('',(#61057),#61061); -#61057 = LINE('',#61058,#61059); -#61058 = CARTESIAN_POINT('',(0.64,-0.615)); -#61059 = VECTOR('',#61060,1.); -#61060 = DIRECTION('',(0.E+000,-1.)); -#61061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61062 = PCURVE('',#42781,#61063); -#61063 = DEFINITIONAL_REPRESENTATION('',(#61064),#61068); -#61064 = LINE('',#61065,#61066); -#61065 = CARTESIAN_POINT('',(1.175,-1.105)); -#61066 = VECTOR('',#61067,1.); -#61067 = DIRECTION('',(-1.,0.E+000)); -#61068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61069 = ORIENTED_EDGE('',*,*,#61070,.T.); -#61070 = EDGE_CURVE('',#61048,#61071,#61073,.T.); -#61071 = VERTEX_POINT('',#61072); -#61072 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); -#61073 = SURFACE_CURVE('',#61074,(#61078,#61085),.PCURVE_S1.); -#61074 = LINE('',#61075,#61076); -#61075 = CARTESIAN_POINT('',(0.775,-1.105,-2.35)); -#61076 = VECTOR('',#61077,1.); -#61077 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61078 = PCURVE('',#60364,#61079); -#61079 = DEFINITIONAL_REPRESENTATION('',(#61080),#61084); -#61080 = LINE('',#61081,#61082); -#61081 = CARTESIAN_POINT('',(0.64,-1.015)); -#61082 = VECTOR('',#61083,1.); -#61083 = DIRECTION('',(-1.,0.E+000)); -#61084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61085 = PCURVE('',#61086,#61091); -#61086 = PLANE('',#61087); -#61087 = AXIS2_PLACEMENT_3D('',#61088,#61089,#61090); -#61088 = CARTESIAN_POINT('',(0.775,0.E+000,0.E+000)); -#61089 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61090 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61091 = DEFINITIONAL_REPRESENTATION('',(#61092),#61096); -#61092 = LINE('',#61093,#61094); -#61093 = CARTESIAN_POINT('',(2.35,-1.105)); -#61094 = VECTOR('',#61095,1.); -#61095 = DIRECTION('',(-1.,0.E+000)); -#61096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61097 = ORIENTED_EDGE('',*,*,#61098,.F.); -#61098 = EDGE_CURVE('',#61099,#61071,#61101,.T.); -#61099 = VERTEX_POINT('',#61100); -#61100 = CARTESIAN_POINT('',(0.775,-1.105,-1.71)); -#61101 = SURFACE_CURVE('',#61102,(#61106,#61113),.PCURVE_S1.); -#61102 = LINE('',#61103,#61104); -#61103 = CARTESIAN_POINT('',(0.775,-1.105,-1.71)); -#61104 = VECTOR('',#61105,1.); -#61105 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61106 = PCURVE('',#60364,#61107); -#61107 = DEFINITIONAL_REPRESENTATION('',(#61108),#61112); -#61108 = LINE('',#61109,#61110); -#61109 = CARTESIAN_POINT('',(0.E+000,-1.015)); -#61110 = VECTOR('',#61111,1.); -#61111 = DIRECTION('',(1.,0.E+000)); -#61112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61113 = PCURVE('',#59811,#61114); -#61114 = DEFINITIONAL_REPRESENTATION('',(#61115),#61119); -#61115 = LINE('',#61116,#61117); -#61116 = CARTESIAN_POINT('',(1.71,-1.105)); -#61117 = VECTOR('',#61118,1.); -#61118 = DIRECTION('',(1.,0.E+000)); -#61119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61120 = ORIENTED_EDGE('',*,*,#61121,.F.); -#61121 = EDGE_CURVE('',#60347,#61099,#61122,.T.); -#61122 = SURFACE_CURVE('',#61123,(#61127,#61134),.PCURVE_S1.); -#61123 = LINE('',#61124,#61125); -#61124 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); -#61125 = VECTOR('',#61126,1.); -#61126 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61127 = PCURVE('',#60364,#61128); -#61128 = DEFINITIONAL_REPRESENTATION('',(#61129),#61133); -#61129 = LINE('',#61130,#61131); -#61130 = CARTESIAN_POINT('',(0.E+000,-0.615)); -#61131 = VECTOR('',#61132,1.); -#61132 = DIRECTION('',(0.E+000,-1.)); -#61133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61134 = PCURVE('',#59783,#61135); -#61135 = DEFINITIONAL_REPRESENTATION('',(#61136),#61140); -#61136 = LINE('',#61137,#61138); -#61137 = CARTESIAN_POINT('',(0.12,-0.615)); -#61138 = VECTOR('',#61139,1.); -#61139 = DIRECTION('',(0.E+000,-1.)); -#61140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61141 = ADVANCED_FACE('',(#61142),#42809,.T.); -#61142 = FACE_BOUND('',#61143,.F.); -#61143 = EDGE_LOOP('',(#61144,#61169,#61190,#61191,#61214)); -#61144 = ORIENTED_EDGE('',*,*,#61145,.F.); -#61145 = EDGE_CURVE('',#61146,#61148,#61150,.T.); -#61146 = VERTEX_POINT('',#61147); -#61147 = CARTESIAN_POINT('',(1.425,-1.105,-1.71)); -#61148 = VERTEX_POINT('',#61149); -#61149 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); -#61150 = SURFACE_CURVE('',#61151,(#61155,#61162),.PCURVE_S1.); -#61151 = LINE('',#61152,#61153); -#61152 = CARTESIAN_POINT('',(1.425,-1.105,-1.71)); -#61153 = VECTOR('',#61154,1.); -#61154 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61155 = PCURVE('',#42809,#61156); -#61156 = DEFINITIONAL_REPRESENTATION('',(#61157),#61161); -#61157 = LINE('',#61158,#61159); -#61158 = CARTESIAN_POINT('',(0.E+000,-0.365)); -#61159 = VECTOR('',#61160,1.); -#61160 = DIRECTION('',(1.,0.E+000)); -#61161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61162 = PCURVE('',#60305,#61163); -#61163 = DEFINITIONAL_REPRESENTATION('',(#61164),#61168); -#61164 = LINE('',#61165,#61166); -#61165 = CARTESIAN_POINT('',(1.71,-1.105)); -#61166 = VECTOR('',#61167,1.); -#61167 = DIRECTION('',(1.,0.E+000)); -#61168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61169 = ORIENTED_EDGE('',*,*,#61170,.F.); -#61170 = EDGE_CURVE('',#42794,#61146,#61171,.T.); -#61171 = SURFACE_CURVE('',#61172,(#61176,#61183),.PCURVE_S1.); -#61172 = LINE('',#61173,#61174); -#61173 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); -#61174 = VECTOR('',#61175,1.); -#61175 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61176 = PCURVE('',#42809,#61177); -#61177 = DEFINITIONAL_REPRESENTATION('',(#61178),#61182); -#61178 = LINE('',#61179,#61180); -#61179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61180 = VECTOR('',#61181,1.); -#61181 = DIRECTION('',(0.E+000,-1.)); -#61182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61183 = PCURVE('',#42837,#61184); -#61184 = DEFINITIONAL_REPRESENTATION('',(#61185),#61189); -#61185 = LINE('',#61186,#61187); -#61186 = CARTESIAN_POINT('',(0.12,0.E+000)); -#61187 = VECTOR('',#61188,1.); -#61188 = DIRECTION('',(0.E+000,-1.)); -#61189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61190 = ORIENTED_EDGE('',*,*,#42793,.T.); -#61191 = ORIENTED_EDGE('',*,*,#61192,.T.); -#61192 = EDGE_CURVE('',#42766,#61193,#61195,.T.); -#61193 = VERTEX_POINT('',#61194); -#61194 = CARTESIAN_POINT('',(1.425,-1.105,-2.35)); -#61195 = SURFACE_CURVE('',#61196,(#61200,#61207),.PCURVE_S1.); -#61196 = LINE('',#61197,#61198); -#61197 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); -#61198 = VECTOR('',#61199,1.); -#61199 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61200 = PCURVE('',#42809,#61201); -#61201 = DEFINITIONAL_REPRESENTATION('',(#61202),#61206); -#61202 = LINE('',#61203,#61204); -#61203 = CARTESIAN_POINT('',(0.64,0.E+000)); -#61204 = VECTOR('',#61205,1.); -#61205 = DIRECTION('',(0.E+000,-1.)); -#61206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61207 = PCURVE('',#42781,#61208); -#61208 = DEFINITIONAL_REPRESENTATION('',(#61209),#61213); -#61209 = LINE('',#61210,#61211); -#61210 = CARTESIAN_POINT('',(1.79,-1.105)); -#61211 = VECTOR('',#61212,1.); -#61212 = DIRECTION('',(-1.,0.E+000)); -#61213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61214 = ORIENTED_EDGE('',*,*,#61215,.T.); -#61215 = EDGE_CURVE('',#61193,#61148,#61216,.T.); -#61216 = SURFACE_CURVE('',#61217,(#61221,#61228),.PCURVE_S1.); -#61217 = LINE('',#61218,#61219); -#61218 = CARTESIAN_POINT('',(1.425,-1.105,-2.35)); -#61219 = VECTOR('',#61220,1.); -#61220 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61221 = PCURVE('',#42809,#61222); -#61222 = DEFINITIONAL_REPRESENTATION('',(#61223),#61227); -#61223 = LINE('',#61224,#61225); -#61224 = CARTESIAN_POINT('',(0.64,-0.365)); -#61225 = VECTOR('',#61226,1.); -#61226 = DIRECTION('',(-1.,0.E+000)); -#61227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61228 = PCURVE('',#61229,#61234); -#61229 = PLANE('',#61230); -#61230 = AXIS2_PLACEMENT_3D('',#61231,#61232,#61233); -#61231 = CARTESIAN_POINT('',(1.425,0.E+000,0.E+000)); -#61232 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61233 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61234 = DEFINITIONAL_REPRESENTATION('',(#61235),#61239); -#61235 = LINE('',#61236,#61237); -#61236 = CARTESIAN_POINT('',(2.35,-1.105)); -#61237 = VECTOR('',#61238,1.); -#61238 = DIRECTION('',(-1.,0.E+000)); -#61239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61240 = ADVANCED_FACE('',(#61241),#60203,.T.); -#61241 = FACE_BOUND('',#61242,.F.); -#61242 = EDGE_LOOP('',(#61243,#61244,#61265,#61266)); -#61243 = ORIENTED_EDGE('',*,*,#60422,.F.); -#61244 = ORIENTED_EDGE('',*,*,#61245,.F.); -#61245 = EDGE_CURVE('',#60188,#60423,#61246,.T.); -#61246 = SURFACE_CURVE('',#61247,(#61251,#61258),.PCURVE_S1.); -#61247 = LINE('',#61248,#61249); -#61248 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); -#61249 = VECTOR('',#61250,1.); -#61250 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61251 = PCURVE('',#60203,#61252); -#61252 = DEFINITIONAL_REPRESENTATION('',(#61253),#61257); -#61253 = LINE('',#61254,#61255); -#61254 = CARTESIAN_POINT('',(1.71,-0.985)); -#61255 = VECTOR('',#61256,1.); -#61256 = DIRECTION('',(0.E+000,-1.)); -#61257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61258 = PCURVE('',#60231,#61259); -#61259 = DEFINITIONAL_REPRESENTATION('',(#61260),#61264); -#61260 = LINE('',#61261,#61262); -#61261 = CARTESIAN_POINT('',(0.E+000,-3.215)); -#61262 = VECTOR('',#61263,1.); -#61263 = DIRECTION('',(1.,0.E+000)); -#61264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61265 = ORIENTED_EDGE('',*,*,#60187,.F.); -#61266 = ORIENTED_EDGE('',*,*,#61267,.F.); -#61267 = EDGE_CURVE('',#60425,#60160,#61268,.T.); -#61268 = SURFACE_CURVE('',#61269,(#61273,#61280),.PCURVE_S1.); -#61269 = LINE('',#61270,#61271); -#61270 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); -#61271 = VECTOR('',#61272,1.); -#61272 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#61273 = PCURVE('',#60203,#61274); -#61274 = DEFINITIONAL_REPRESENTATION('',(#61275),#61279); -#61275 = LINE('',#61276,#61277); -#61276 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#61277 = VECTOR('',#61278,1.); -#61278 = DIRECTION('',(-0.258819045102,0.965925826289)); -#61279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61280 = PCURVE('',#60175,#61281); -#61281 = DEFINITIONAL_REPRESENTATION('',(#61282),#61286); -#61282 = LINE('',#61283,#61284); -#61283 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#61284 = VECTOR('',#61285,1.); -#61285 = DIRECTION('',(-1.,0.E+000)); -#61286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61287 = ADVANCED_FACE('',(#61288),#60231,.T.); -#61288 = FACE_BOUND('',#61289,.F.); -#61289 = EDGE_LOOP('',(#61290,#61291,#61292,#61313)); -#61290 = ORIENTED_EDGE('',*,*,#61245,.T.); -#61291 = ORIENTED_EDGE('',*,*,#60526,.T.); -#61292 = ORIENTED_EDGE('',*,*,#61293,.F.); -#61293 = EDGE_CURVE('',#60216,#60504,#61294,.T.); -#61294 = SURFACE_CURVE('',#61295,(#61299,#61306),.PCURVE_S1.); -#61295 = LINE('',#61296,#61297); -#61296 = CARTESIAN_POINT('',(-1.79,-0.985,-1.71)); -#61297 = VECTOR('',#61298,1.); -#61298 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61299 = PCURVE('',#60231,#61300); -#61300 = DEFINITIONAL_REPRESENTATION('',(#61301),#61305); -#61301 = LINE('',#61302,#61303); -#61302 = CARTESIAN_POINT('',(0.E+000,-3.58)); -#61303 = VECTOR('',#61304,1.); -#61304 = DIRECTION('',(1.,0.E+000)); -#61305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61306 = PCURVE('',#41870,#61307); -#61307 = DEFINITIONAL_REPRESENTATION('',(#61308),#61312); -#61308 = LINE('',#61309,#61310); -#61309 = CARTESIAN_POINT('',(0.5,-0.24)); -#61310 = VECTOR('',#61311,1.); -#61311 = DIRECTION('',(0.E+000,1.)); -#61312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61313 = ORIENTED_EDGE('',*,*,#60215,.F.); -#61314 = ADVANCED_FACE('',(#61315),#60119,.T.); -#61315 = FACE_BOUND('',#61316,.F.); -#61316 = EDGE_LOOP('',(#61317,#61338,#61339,#61360)); -#61317 = ORIENTED_EDGE('',*,*,#61318,.T.); -#61318 = EDGE_CURVE('',#60076,#60551,#61319,.T.); -#61319 = SURFACE_CURVE('',#61320,(#61324,#61331),.PCURVE_S1.); -#61320 = LINE('',#61321,#61322); -#61321 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); -#61322 = VECTOR('',#61323,1.); -#61323 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61324 = PCURVE('',#60119,#61325); -#61325 = DEFINITIONAL_REPRESENTATION('',(#61326),#61330); -#61326 = LINE('',#61327,#61328); -#61327 = CARTESIAN_POINT('',(0.E+000,-2.565)); -#61328 = VECTOR('',#61329,1.); -#61329 = DIRECTION('',(1.,0.E+000)); -#61330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61331 = PCURVE('',#60091,#61332); -#61332 = DEFINITIONAL_REPRESENTATION('',(#61333),#61337); -#61333 = LINE('',#61334,#61335); -#61334 = CARTESIAN_POINT('',(1.71,-0.985)); -#61335 = VECTOR('',#61336,1.); -#61336 = DIRECTION('',(0.E+000,-1.)); -#61337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61338 = ORIENTED_EDGE('',*,*,#60682,.T.); -#61339 = ORIENTED_EDGE('',*,*,#61340,.F.); -#61340 = EDGE_CURVE('',#60104,#60660,#61341,.T.); -#61341 = SURFACE_CURVE('',#61342,(#61346,#61353),.PCURVE_S1.); -#61342 = LINE('',#61343,#61344); -#61343 = CARTESIAN_POINT('',(-1.175,-0.985,-1.71)); -#61344 = VECTOR('',#61345,1.); -#61345 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61346 = PCURVE('',#60119,#61347); -#61347 = DEFINITIONAL_REPRESENTATION('',(#61348),#61352); -#61348 = LINE('',#61349,#61350); -#61349 = CARTESIAN_POINT('',(0.E+000,-2.965)); -#61350 = VECTOR('',#61351,1.); -#61351 = DIRECTION('',(1.,0.E+000)); -#61352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61353 = PCURVE('',#60147,#61354); -#61354 = DEFINITIONAL_REPRESENTATION('',(#61355),#61359); -#61355 = LINE('',#61356,#61357); -#61356 = CARTESIAN_POINT('',(1.71,-0.985)); -#61357 = VECTOR('',#61358,1.); -#61358 = DIRECTION('',(0.E+000,-1.)); -#61359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61360 = ORIENTED_EDGE('',*,*,#60103,.F.); -#61361 = ADVANCED_FACE('',(#61362),#60007,.T.); -#61362 = FACE_BOUND('',#61363,.F.); -#61363 = EDGE_LOOP('',(#61364,#61385,#61386,#61407)); -#61364 = ORIENTED_EDGE('',*,*,#61365,.T.); -#61365 = EDGE_CURVE('',#59964,#60707,#61366,.T.); -#61366 = SURFACE_CURVE('',#61367,(#61371,#61378),.PCURVE_S1.); -#61367 = LINE('',#61368,#61369); -#61368 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); -#61369 = VECTOR('',#61370,1.); -#61370 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61371 = PCURVE('',#60007,#61372); -#61372 = DEFINITIONAL_REPRESENTATION('',(#61373),#61377); -#61373 = LINE('',#61374,#61375); -#61374 = CARTESIAN_POINT('',(0.E+000,-1.915)); -#61375 = VECTOR('',#61376,1.); -#61376 = DIRECTION('',(1.,0.E+000)); -#61377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61378 = PCURVE('',#59979,#61379); -#61379 = DEFINITIONAL_REPRESENTATION('',(#61380),#61384); -#61380 = LINE('',#61381,#61382); -#61381 = CARTESIAN_POINT('',(1.71,-0.985)); -#61382 = VECTOR('',#61383,1.); -#61383 = DIRECTION('',(0.E+000,-1.)); -#61384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61385 = ORIENTED_EDGE('',*,*,#60838,.T.); -#61386 = ORIENTED_EDGE('',*,*,#61387,.F.); -#61387 = EDGE_CURVE('',#59992,#60816,#61388,.T.); -#61388 = SURFACE_CURVE('',#61389,(#61393,#61400),.PCURVE_S1.); -#61389 = LINE('',#61390,#61391); -#61390 = CARTESIAN_POINT('',(-0.525,-0.985,-1.71)); -#61391 = VECTOR('',#61392,1.); -#61392 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61393 = PCURVE('',#60007,#61394); -#61394 = DEFINITIONAL_REPRESENTATION('',(#61395),#61399); -#61395 = LINE('',#61396,#61397); -#61396 = CARTESIAN_POINT('',(0.E+000,-2.315)); -#61397 = VECTOR('',#61398,1.); -#61398 = DIRECTION('',(1.,0.E+000)); -#61399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61400 = PCURVE('',#60035,#61401); -#61401 = DEFINITIONAL_REPRESENTATION('',(#61402),#61406); -#61402 = LINE('',#61403,#61404); -#61403 = CARTESIAN_POINT('',(1.71,-0.985)); -#61404 = VECTOR('',#61405,1.); -#61405 = DIRECTION('',(0.E+000,-1.)); -#61406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61407 = ORIENTED_EDGE('',*,*,#59991,.F.); -#61408 = ADVANCED_FACE('',(#61409),#59895,.T.); -#61409 = FACE_BOUND('',#61410,.F.); -#61410 = EDGE_LOOP('',(#61411,#61432,#61433,#61454)); -#61411 = ORIENTED_EDGE('',*,*,#61412,.T.); -#61412 = EDGE_CURVE('',#59852,#60863,#61413,.T.); -#61413 = SURFACE_CURVE('',#61414,(#61418,#61425),.PCURVE_S1.); -#61414 = LINE('',#61415,#61416); -#61415 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); -#61416 = VECTOR('',#61417,1.); -#61417 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61418 = PCURVE('',#59895,#61419); -#61419 = DEFINITIONAL_REPRESENTATION('',(#61420),#61424); -#61420 = LINE('',#61421,#61422); -#61421 = CARTESIAN_POINT('',(0.E+000,-1.265)); -#61422 = VECTOR('',#61423,1.); -#61423 = DIRECTION('',(1.,0.E+000)); -#61424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61425 = PCURVE('',#59867,#61426); -#61426 = DEFINITIONAL_REPRESENTATION('',(#61427),#61431); -#61427 = LINE('',#61428,#61429); -#61428 = CARTESIAN_POINT('',(1.71,-0.985)); -#61429 = VECTOR('',#61430,1.); -#61430 = DIRECTION('',(0.E+000,-1.)); -#61431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61432 = ORIENTED_EDGE('',*,*,#60994,.T.); -#61433 = ORIENTED_EDGE('',*,*,#61434,.F.); -#61434 = EDGE_CURVE('',#59880,#60972,#61435,.T.); -#61435 = SURFACE_CURVE('',#61436,(#61440,#61447),.PCURVE_S1.); -#61436 = LINE('',#61437,#61438); -#61437 = CARTESIAN_POINT('',(0.125,-0.985,-1.71)); -#61438 = VECTOR('',#61439,1.); -#61439 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61440 = PCURVE('',#59895,#61441); -#61441 = DEFINITIONAL_REPRESENTATION('',(#61442),#61446); -#61442 = LINE('',#61443,#61444); -#61443 = CARTESIAN_POINT('',(0.E+000,-1.665)); -#61444 = VECTOR('',#61445,1.); -#61445 = DIRECTION('',(1.,0.E+000)); -#61446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61447 = PCURVE('',#59923,#61448); -#61448 = DEFINITIONAL_REPRESENTATION('',(#61449),#61453); -#61449 = LINE('',#61450,#61451); -#61450 = CARTESIAN_POINT('',(1.71,-0.985)); -#61451 = VECTOR('',#61452,1.); -#61452 = DIRECTION('',(0.E+000,-1.)); -#61453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61454 = ORIENTED_EDGE('',*,*,#59879,.F.); -#61455 = ADVANCED_FACE('',(#61456),#59783,.T.); -#61456 = FACE_BOUND('',#61457,.F.); -#61457 = EDGE_LOOP('',(#61458,#61459,#61460,#61481)); -#61458 = ORIENTED_EDGE('',*,*,#60376,.T.); -#61459 = ORIENTED_EDGE('',*,*,#61121,.T.); -#61460 = ORIENTED_EDGE('',*,*,#61461,.F.); -#61461 = EDGE_CURVE('',#59768,#61099,#61462,.T.); -#61462 = SURFACE_CURVE('',#61463,(#61467,#61474),.PCURVE_S1.); -#61463 = LINE('',#61464,#61465); -#61464 = CARTESIAN_POINT('',(0.775,-0.985,-1.71)); -#61465 = VECTOR('',#61466,1.); -#61466 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61467 = PCURVE('',#59783,#61468); -#61468 = DEFINITIONAL_REPRESENTATION('',(#61469),#61473); -#61469 = LINE('',#61470,#61471); -#61470 = CARTESIAN_POINT('',(0.E+000,-1.015)); -#61471 = VECTOR('',#61472,1.); -#61472 = DIRECTION('',(1.,0.E+000)); -#61473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61474 = PCURVE('',#59811,#61475); -#61475 = DEFINITIONAL_REPRESENTATION('',(#61476),#61480); -#61476 = LINE('',#61477,#61478); -#61477 = CARTESIAN_POINT('',(1.71,-0.985)); -#61478 = VECTOR('',#61479,1.); -#61479 = DIRECTION('',(0.E+000,-1.)); -#61480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61481 = ORIENTED_EDGE('',*,*,#59767,.F.); -#61482 = ADVANCED_FACE('',(#61483),#42837,.T.); -#61483 = FACE_BOUND('',#61484,.F.); -#61484 = EDGE_LOOP('',(#61485,#61506,#61507,#61508)); -#61485 = ORIENTED_EDGE('',*,*,#61486,.F.); -#61486 = EDGE_CURVE('',#60267,#61146,#61487,.T.); -#61487 = SURFACE_CURVE('',#61488,(#61492,#61499),.PCURVE_S1.); -#61488 = LINE('',#61489,#61490); -#61489 = CARTESIAN_POINT('',(1.425,-0.985,-1.71)); -#61490 = VECTOR('',#61491,1.); -#61491 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61492 = PCURVE('',#42837,#61493); -#61493 = DEFINITIONAL_REPRESENTATION('',(#61494),#61498); -#61494 = LINE('',#61495,#61496); -#61495 = CARTESIAN_POINT('',(0.E+000,-0.365)); -#61496 = VECTOR('',#61497,1.); -#61497 = DIRECTION('',(1.,0.E+000)); -#61498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61499 = PCURVE('',#60305,#61500); -#61500 = DEFINITIONAL_REPRESENTATION('',(#61501),#61505); -#61501 = LINE('',#61502,#61503); -#61502 = CARTESIAN_POINT('',(1.71,-0.985)); -#61503 = VECTOR('',#61504,1.); -#61504 = DIRECTION('',(0.E+000,-1.)); -#61505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61506 = ORIENTED_EDGE('',*,*,#60266,.F.); -#61507 = ORIENTED_EDGE('',*,*,#42821,.T.); -#61508 = ORIENTED_EDGE('',*,*,#61170,.T.); -#61509 = ADVANCED_FACE('',(#61510),#41870,.T.); -#61510 = FACE_BOUND('',#61511,.F.); -#61511 = EDGE_LOOP('',(#61512,#61513,#61514,#61515,#61516,#61517,#61518, - #61519)); -#61512 = ORIENTED_EDGE('',*,*,#43026,.T.); -#61513 = ORIENTED_EDGE('',*,*,#43619,.T.); -#61514 = ORIENTED_EDGE('',*,*,#41852,.F.); -#61515 = ORIENTED_EDGE('',*,*,#59574,.T.); -#61516 = ORIENTED_EDGE('',*,*,#60243,.T.); -#61517 = ORIENTED_EDGE('',*,*,#61293,.T.); -#61518 = ORIENTED_EDGE('',*,*,#60503,.T.); -#61519 = ORIENTED_EDGE('',*,*,#61520,.T.); -#61520 = EDGE_CURVE('',#60481,#43027,#61521,.T.); -#61521 = SURFACE_CURVE('',#61522,(#61526,#61533),.PCURVE_S1.); -#61522 = LINE('',#61523,#61524); -#61523 = CARTESIAN_POINT('',(-1.79,-1.105,-2.35)); -#61524 = VECTOR('',#61525,1.); -#61525 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61526 = PCURVE('',#41870,#61527); -#61527 = DEFINITIONAL_REPRESENTATION('',(#61528),#61532); -#61528 = LINE('',#61529,#61530); -#61529 = CARTESIAN_POINT('',(1.14,-0.12)); -#61530 = VECTOR('',#61531,1.); -#61531 = DIRECTION('',(0.E+000,-1.)); -#61532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61533 = PCURVE('',#42781,#61534); -#61534 = DEFINITIONAL_REPRESENTATION('',(#61535),#61539); -#61535 = LINE('',#61536,#61537); -#61536 = CARTESIAN_POINT('',(-1.79,-1.105)); -#61537 = VECTOR('',#61538,1.); -#61538 = DIRECTION('',(0.E+000,1.)); -#61539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61540 = ADVANCED_FACE('',(#61541),#61555,.F.); -#61541 = FACE_BOUND('',#61542,.F.); -#61542 = EDGE_LOOP('',(#61543,#61573,#61596,#61623,#61646,#61669,#61692, - #61715,#61738,#61761,#61789)); -#61543 = ORIENTED_EDGE('',*,*,#61544,.T.); -#61544 = EDGE_CURVE('',#61545,#61547,#61549,.T.); -#61545 = VERTEX_POINT('',#61546); -#61546 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); -#61547 = VERTEX_POINT('',#61548); -#61548 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); -#61549 = SURFACE_CURVE('',#61550,(#61554,#61566),.PCURVE_S1.); -#61550 = LINE('',#61551,#61552); -#61551 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); -#61552 = VECTOR('',#61553,1.); -#61553 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); -#61554 = PCURVE('',#61555,#61560); -#61555 = PLANE('',#61556); -#61556 = AXIS2_PLACEMENT_3D('',#61557,#61558,#61559); -#61557 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#61558 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61559 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61560 = DEFINITIONAL_REPRESENTATION('',(#61561),#61565); -#61561 = LINE('',#61562,#61563); -#61562 = CARTESIAN_POINT('',(1.339903810568,0.5)); -#61563 = VECTOR('',#61564,1.); -#61564 = DIRECTION('',(0.866025403784,-0.5)); -#61565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61566 = PCURVE('',#51589,#61567); -#61567 = DEFINITIONAL_REPRESENTATION('',(#61568),#61572); -#61568 = LINE('',#61569,#61570); -#61569 = CARTESIAN_POINT('',(0.15,0.E+000)); -#61570 = VECTOR('',#61571,1.); -#61571 = DIRECTION('',(1.,0.E+000)); -#61572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61573 = ORIENTED_EDGE('',*,*,#61574,.T.); -#61574 = EDGE_CURVE('',#61547,#61575,#61577,.T.); -#61575 = VERTEX_POINT('',#61576); -#61576 = CARTESIAN_POINT('',(2.45,0.175,-2.35)); -#61577 = SURFACE_CURVE('',#61578,(#61582,#61589),.PCURVE_S1.); -#61578 = LINE('',#61579,#61580); -#61579 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); -#61580 = VECTOR('',#61581,1.); -#61581 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61582 = PCURVE('',#61555,#61583); -#61583 = DEFINITIONAL_REPRESENTATION('',(#61584),#61588); -#61584 = LINE('',#61585,#61586); -#61585 = CARTESIAN_POINT('',(1.902820323028,0.175)); -#61586 = VECTOR('',#61587,1.); -#61587 = DIRECTION('',(1.,0.E+000)); -#61588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61589 = PCURVE('',#52101,#61590); -#61590 = DEFINITIONAL_REPRESENTATION('',(#61591),#61595); -#61591 = LINE('',#61592,#61593); -#61592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61593 = VECTOR('',#61594,1.); -#61594 = DIRECTION('',(1.,0.E+000)); -#61595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61596 = ORIENTED_EDGE('',*,*,#61597,.T.); -#61597 = EDGE_CURVE('',#61575,#61598,#61600,.T.); -#61598 = VERTEX_POINT('',#61599); -#61599 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); -#61600 = SURFACE_CURVE('',#61601,(#61606,#61617),.PCURVE_S1.); -#61601 = CIRCLE('',#61602,0.55); -#61602 = AXIS2_PLACEMENT_3D('',#61603,#61604,#61605); -#61603 = CARTESIAN_POINT('',(2.45,-0.375,-2.35)); -#61604 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61605 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61606 = PCURVE('',#61555,#61607); -#61607 = DEFINITIONAL_REPRESENTATION('',(#61608),#61616); -#61608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#61609,#61610,#61611,#61612 - ,#61613,#61614,#61615),.UNSPECIFIED.,.F.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#61609 = CARTESIAN_POINT('',(2.45,0.175)); -#61610 = CARTESIAN_POINT('',(3.402627944163,0.175)); -#61611 = CARTESIAN_POINT('',(2.926313972081,-0.65)); -#61612 = CARTESIAN_POINT('',(2.45,-1.475)); -#61613 = CARTESIAN_POINT('',(1.973686027919,-0.65)); -#61614 = CARTESIAN_POINT('',(1.497372055837,0.175)); -#61615 = CARTESIAN_POINT('',(2.45,0.175)); -#61616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61617 = PCURVE('',#52074,#61618); -#61618 = DEFINITIONAL_REPRESENTATION('',(#61619),#61622); -#61619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61620,#61621),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#61620 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#61621 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#61622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61623 = ORIENTED_EDGE('',*,*,#61624,.F.); -#61624 = EDGE_CURVE('',#61625,#61598,#61627,.T.); -#61625 = VERTEX_POINT('',#61626); -#61626 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); -#61627 = SURFACE_CURVE('',#61628,(#61632,#61639),.PCURVE_S1.); -#61628 = LINE('',#61629,#61630); -#61629 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); -#61630 = VECTOR('',#61631,1.); -#61631 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61632 = PCURVE('',#61555,#61633); -#61633 = DEFINITIONAL_REPRESENTATION('',(#61634),#61638); -#61634 = LINE('',#61635,#61636); -#61635 = CARTESIAN_POINT('',(3.,-0.617928932188)); -#61636 = VECTOR('',#61637,1.); -#61637 = DIRECTION('',(0.E+000,1.)); -#61638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61639 = PCURVE('',#52045,#61640); -#61640 = DEFINITIONAL_REPRESENTATION('',(#61641),#61645); -#61641 = LINE('',#61642,#61643); -#61642 = CARTESIAN_POINT('',(0.242928932188,0.E+000)); -#61643 = VECTOR('',#61644,1.); -#61644 = DIRECTION('',(-1.,0.E+000)); -#61645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61646 = ORIENTED_EDGE('',*,*,#61647,.T.); -#61647 = EDGE_CURVE('',#61625,#61648,#61650,.T.); -#61648 = VERTEX_POINT('',#61649); -#61649 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-2.35)); -#61650 = SURFACE_CURVE('',#61651,(#61655,#61662),.PCURVE_S1.); -#61651 = LINE('',#61652,#61653); -#61652 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); -#61653 = VECTOR('',#61654,1.); -#61654 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#61655 = PCURVE('',#61555,#61656); -#61656 = DEFINITIONAL_REPRESENTATION('',(#61657),#61661); -#61657 = LINE('',#61658,#61659); -#61658 = CARTESIAN_POINT('',(3.,-0.617928932188)); -#61659 = VECTOR('',#61660,1.); -#61660 = DIRECTION('',(0.707106781187,0.707106781187)); -#61661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61662 = PCURVE('',#43512,#61663); -#61663 = DEFINITIONAL_REPRESENTATION('',(#61664),#61668); -#61664 = LINE('',#61665,#61666); -#61665 = CARTESIAN_POINT('',(0.323639610307,0.E+000)); -#61666 = VECTOR('',#61667,1.); -#61667 = DIRECTION('',(1.,0.E+000)); -#61668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61669 = ORIENTED_EDGE('',*,*,#61670,.T.); -#61670 = EDGE_CURVE('',#61648,#61671,#61673,.T.); -#61671 = VERTEX_POINT('',#61672); -#61672 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); -#61673 = SURFACE_CURVE('',#61674,(#61679,#61686),.PCURVE_S1.); -#61674 = CIRCLE('',#61675,0.25); -#61675 = AXIS2_PLACEMENT_3D('',#61676,#61677,#61678); -#61676 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-2.35)); -#61677 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61678 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#61679 = PCURVE('',#61555,#61680); -#61680 = DEFINITIONAL_REPRESENTATION('',(#61681),#61685); -#61681 = CIRCLE('',#61682,0.25); -#61682 = AXIS2_PLACEMENT_2D('',#61683,#61684); -#61683 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002)); -#61684 = DIRECTION('',(0.707106781187,-0.707106781187)); -#61685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61686 = PCURVE('',#43485,#61687); -#61687 = DEFINITIONAL_REPRESENTATION('',(#61688),#61691); -#61688 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61689,#61690),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#61689 = CARTESIAN_POINT('',(5.497787143782,0.E+000)); -#61690 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#61691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61692 = ORIENTED_EDGE('',*,*,#61693,.T.); -#61693 = EDGE_CURVE('',#61671,#61694,#61696,.T.); -#61694 = VERTEX_POINT('',#61695); -#61695 = CARTESIAN_POINT('',(3.445,0.57,-2.35)); -#61696 = SURFACE_CURVE('',#61697,(#61701,#61708),.PCURVE_S1.); -#61697 = LINE('',#61698,#61699); -#61698 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); -#61699 = VECTOR('',#61700,1.); -#61700 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61701 = PCURVE('',#61555,#61702); -#61702 = DEFINITIONAL_REPRESENTATION('',(#61703),#61707); -#61703 = LINE('',#61704,#61705); -#61704 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002)); -#61705 = VECTOR('',#61706,1.); -#61706 = DIRECTION('',(0.E+000,1.)); -#61707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61708 = PCURVE('',#43456,#61709); -#61709 = DEFINITIONAL_REPRESENTATION('',(#61710),#61714); -#61710 = LINE('',#61711,#61712); -#61711 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61712 = VECTOR('',#61713,1.); -#61713 = DIRECTION('',(1.,0.E+000)); -#61714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61715 = ORIENTED_EDGE('',*,*,#61716,.T.); -#61716 = EDGE_CURVE('',#61694,#61717,#61719,.T.); -#61717 = VERTEX_POINT('',#61718); -#61718 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); -#61719 = SURFACE_CURVE('',#61720,(#61725,#61732),.PCURVE_S1.); -#61720 = CIRCLE('',#61721,0.35); -#61721 = AXIS2_PLACEMENT_3D('',#61722,#61723,#61724); -#61722 = CARTESIAN_POINT('',(3.095,0.57,-2.35)); -#61723 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61724 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61725 = PCURVE('',#61555,#61726); -#61726 = DEFINITIONAL_REPRESENTATION('',(#61727),#61731); -#61727 = CIRCLE('',#61728,0.35); -#61728 = AXIS2_PLACEMENT_2D('',#61729,#61730); -#61729 = CARTESIAN_POINT('',(3.095,0.57)); -#61730 = DIRECTION('',(1.,0.E+000)); -#61731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61732 = PCURVE('',#43429,#61733); -#61733 = DEFINITIONAL_REPRESENTATION('',(#61734),#61737); -#61734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61735,#61736),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#61735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #61736 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#61737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61738 = ORIENTED_EDGE('',*,*,#61739,.T.); -#61739 = EDGE_CURVE('',#61717,#61740,#61742,.T.); -#61740 = VERTEX_POINT('',#61741); -#61741 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); -#61742 = SURFACE_CURVE('',#61743,(#61747,#61754),.PCURVE_S1.); -#61743 = LINE('',#61744,#61745); -#61744 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); -#61745 = VECTOR('',#61746,1.); -#61746 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61747 = PCURVE('',#61555,#61748); -#61748 = DEFINITIONAL_REPRESENTATION('',(#61749),#61753); -#61749 = LINE('',#61750,#61751); -#61750 = CARTESIAN_POINT('',(3.095,0.92)); -#61751 = VECTOR('',#61752,1.); -#61752 = DIRECTION('',(-1.,0.E+000)); -#61753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61754 = PCURVE('',#43400,#61755); -#61755 = DEFINITIONAL_REPRESENTATION('',(#61756),#61760); -#61756 = LINE('',#61757,#61758); -#61757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61758 = VECTOR('',#61759,1.); -#61759 = DIRECTION('',(1.,0.E+000)); -#61760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61761 = ORIENTED_EDGE('',*,*,#61762,.T.); -#61762 = EDGE_CURVE('',#61740,#61763,#61765,.T.); -#61763 = VERTEX_POINT('',#61764); -#61764 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); -#61765 = SURFACE_CURVE('',#61766,(#61770,#61777),.PCURVE_S1.); -#61766 = LINE('',#61767,#61768); -#61767 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); -#61768 = VECTOR('',#61769,1.); -#61769 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61770 = PCURVE('',#61555,#61771); -#61771 = DEFINITIONAL_REPRESENTATION('',(#61772),#61776); -#61772 = LINE('',#61773,#61774); -#61773 = CARTESIAN_POINT('',(2.37,0.92)); -#61774 = VECTOR('',#61775,1.); -#61775 = DIRECTION('',(0.E+000,-1.)); -#61776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61777 = PCURVE('',#61778,#61783); -#61778 = PLANE('',#61779); -#61779 = AXIS2_PLACEMENT_3D('',#61780,#61781,#61782); -#61780 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); -#61781 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61782 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61783 = DEFINITIONAL_REPRESENTATION('',(#61784),#61788); -#61784 = LINE('',#61785,#61786); -#61785 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61786 = VECTOR('',#61787,1.); -#61787 = DIRECTION('',(1.,0.E+000)); -#61788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61789 = ORIENTED_EDGE('',*,*,#61790,.T.); -#61790 = EDGE_CURVE('',#61763,#61545,#61791,.T.); -#61791 = SURFACE_CURVE('',#61792,(#61796,#61803),.PCURVE_S1.); -#61792 = LINE('',#61793,#61794); -#61793 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); -#61794 = VECTOR('',#61795,1.); -#61795 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61796 = PCURVE('',#61555,#61797); -#61797 = DEFINITIONAL_REPRESENTATION('',(#61798),#61802); -#61798 = LINE('',#61799,#61800); -#61799 = CARTESIAN_POINT('',(2.37,0.5)); -#61800 = VECTOR('',#61801,1.); -#61801 = DIRECTION('',(-1.,0.E+000)); -#61802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61803 = PCURVE('',#51645,#61804); -#61804 = DEFINITIONAL_REPRESENTATION('',(#61805),#61809); -#61805 = LINE('',#61806,#61807); -#61806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61807 = VECTOR('',#61808,1.); -#61808 = DIRECTION('',(1.,0.E+000)); -#61809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61810 = ADVANCED_FACE('',(#61811),#61825,.F.); -#61811 = FACE_BOUND('',#61812,.F.); -#61812 = EDGE_LOOP('',(#61813,#61843,#61870,#61893,#61916,#61939,#61967, - #61990,#62013,#62036,#62059)); -#61813 = ORIENTED_EDGE('',*,*,#61814,.T.); -#61814 = EDGE_CURVE('',#61815,#61817,#61819,.T.); -#61815 = VERTEX_POINT('',#61816); -#61816 = CARTESIAN_POINT('',(-3.,-0.617928932188,-2.35)); -#61817 = VERTEX_POINT('',#61818); -#61818 = CARTESIAN_POINT('',(-3.,-0.375,-2.35)); -#61819 = SURFACE_CURVE('',#61820,(#61824,#61836),.PCURVE_S1.); -#61820 = LINE('',#61821,#61822); -#61821 = CARTESIAN_POINT('',(-3.,-0.617928932188,-2.35)); -#61822 = VECTOR('',#61823,1.); -#61823 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61824 = PCURVE('',#61825,#61830); -#61825 = PLANE('',#61826); -#61826 = AXIS2_PLACEMENT_3D('',#61827,#61828,#61829); -#61827 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); -#61828 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61829 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61830 = DEFINITIONAL_REPRESENTATION('',(#61831),#61835); -#61831 = LINE('',#61832,#61833); -#61832 = CARTESIAN_POINT('',(-3.,-0.617928932188)); -#61833 = VECTOR('',#61834,1.); -#61834 = DIRECTION('',(0.E+000,1.)); -#61835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61836 = PCURVE('',#51879,#61837); -#61837 = DEFINITIONAL_REPRESENTATION('',(#61838),#61842); -#61838 = LINE('',#61839,#61840); -#61839 = CARTESIAN_POINT('',(0.607071067812,0.E+000)); -#61840 = VECTOR('',#61841,1.); -#61841 = DIRECTION('',(1.,0.E+000)); -#61842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61843 = ORIENTED_EDGE('',*,*,#61844,.T.); -#61844 = EDGE_CURVE('',#61817,#61845,#61847,.T.); -#61845 = VERTEX_POINT('',#61846); -#61846 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); -#61847 = SURFACE_CURVE('',#61848,(#61853,#61864),.PCURVE_S1.); -#61848 = CIRCLE('',#61849,0.55); -#61849 = AXIS2_PLACEMENT_3D('',#61850,#61851,#61852); -#61850 = CARTESIAN_POINT('',(-2.45,-0.375,-2.35)); -#61851 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#61852 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61853 = PCURVE('',#61825,#61854); -#61854 = DEFINITIONAL_REPRESENTATION('',(#61855),#61863); -#61855 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#61856,#61857,#61858,#61859 - ,#61860,#61861,#61862),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#61856 = CARTESIAN_POINT('',(-3.,-0.375)); -#61857 = CARTESIAN_POINT('',(-3.,0.577627944163)); -#61858 = CARTESIAN_POINT('',(-2.175,0.101313972081)); -#61859 = CARTESIAN_POINT('',(-1.35,-0.375)); -#61860 = CARTESIAN_POINT('',(-2.175,-0.851313972081)); -#61861 = CARTESIAN_POINT('',(-3.,-1.327627944163)); -#61862 = CARTESIAN_POINT('',(-3.,-0.375)); -#61863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61864 = PCURVE('',#51852,#61865); -#61865 = DEFINITIONAL_REPRESENTATION('',(#61866),#61869); -#61866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61867,#61868),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#61867 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61868 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#61869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61870 = ORIENTED_EDGE('',*,*,#61871,.T.); -#61871 = EDGE_CURVE('',#61845,#61872,#61874,.T.); -#61872 = VERTEX_POINT('',#61873); -#61873 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); -#61874 = SURFACE_CURVE('',#61875,(#61879,#61886),.PCURVE_S1.); -#61875 = LINE('',#61876,#61877); -#61876 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); -#61877 = VECTOR('',#61878,1.); -#61878 = DIRECTION('',(1.,0.E+000,0.E+000)); -#61879 = PCURVE('',#61825,#61880); -#61880 = DEFINITIONAL_REPRESENTATION('',(#61881),#61885); -#61881 = LINE('',#61882,#61883); -#61882 = CARTESIAN_POINT('',(-2.45,0.175)); -#61883 = VECTOR('',#61884,1.); -#61884 = DIRECTION('',(1.,0.E+000)); -#61885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61886 = PCURVE('',#51823,#61887); -#61887 = DEFINITIONAL_REPRESENTATION('',(#61888),#61892); -#61888 = LINE('',#61889,#61890); -#61889 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61890 = VECTOR('',#61891,1.); -#61891 = DIRECTION('',(1.,0.E+000)); -#61892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61893 = ORIENTED_EDGE('',*,*,#61894,.T.); -#61894 = EDGE_CURVE('',#61872,#61895,#61897,.T.); -#61895 = VERTEX_POINT('',#61896); -#61896 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); -#61897 = SURFACE_CURVE('',#61898,(#61902,#61909),.PCURVE_S1.); -#61898 = LINE('',#61899,#61900); -#61899 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); -#61900 = VECTOR('',#61901,1.); -#61901 = DIRECTION('',(0.866025403784,0.5,0.E+000)); -#61902 = PCURVE('',#61825,#61903); -#61903 = DEFINITIONAL_REPRESENTATION('',(#61904),#61908); -#61904 = LINE('',#61905,#61906); -#61905 = CARTESIAN_POINT('',(-1.902820323028,0.175)); -#61906 = VECTOR('',#61907,1.); -#61907 = DIRECTION('',(0.866025403784,0.5)); -#61908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61909 = PCURVE('',#51795,#61910); -#61910 = DEFINITIONAL_REPRESENTATION('',(#61911),#61915); -#61911 = LINE('',#61912,#61913); -#61912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#61913 = VECTOR('',#61914,1.); -#61914 = DIRECTION('',(1.,0.E+000)); -#61915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61916 = ORIENTED_EDGE('',*,*,#61917,.T.); -#61917 = EDGE_CURVE('',#61895,#61918,#61920,.T.); -#61918 = VERTEX_POINT('',#61919); -#61919 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); -#61920 = SURFACE_CURVE('',#61921,(#61925,#61932),.PCURVE_S1.); -#61921 = LINE('',#61922,#61923); -#61922 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); -#61923 = VECTOR('',#61924,1.); -#61924 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61925 = PCURVE('',#61825,#61926); -#61926 = DEFINITIONAL_REPRESENTATION('',(#61927),#61931); -#61927 = LINE('',#61928,#61929); -#61928 = CARTESIAN_POINT('',(-1.339903810568,0.5)); -#61929 = VECTOR('',#61930,1.); -#61930 = DIRECTION('',(-1.,0.E+000)); -#61931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61932 = PCURVE('',#52252,#61933); -#61933 = DEFINITIONAL_REPRESENTATION('',(#61934),#61938); -#61934 = LINE('',#61935,#61936); -#61935 = CARTESIAN_POINT('',(0.129903810568,0.E+000)); -#61936 = VECTOR('',#61937,1.); -#61937 = DIRECTION('',(1.,0.E+000)); -#61938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61939 = ORIENTED_EDGE('',*,*,#61940,.F.); -#61940 = EDGE_CURVE('',#61941,#61918,#61943,.T.); -#61941 = VERTEX_POINT('',#61942); -#61942 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); -#61943 = SURFACE_CURVE('',#61944,(#61948,#61955),.PCURVE_S1.); -#61944 = LINE('',#61945,#61946); -#61945 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); -#61946 = VECTOR('',#61947,1.); -#61947 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#61948 = PCURVE('',#61825,#61949); -#61949 = DEFINITIONAL_REPRESENTATION('',(#61950),#61954); -#61950 = LINE('',#61951,#61952); -#61951 = CARTESIAN_POINT('',(-2.37,0.92)); -#61952 = VECTOR('',#61953,1.); -#61953 = DIRECTION('',(0.E+000,-1.)); -#61954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61955 = PCURVE('',#61956,#61961); -#61956 = PLANE('',#61957); -#61957 = AXIS2_PLACEMENT_3D('',#61958,#61959,#61960); -#61958 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); -#61959 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61960 = DIRECTION('',(0.E+000,1.,0.E+000)); -#61961 = DEFINITIONAL_REPRESENTATION('',(#61962),#61966); -#61962 = LINE('',#61963,#61964); -#61963 = CARTESIAN_POINT('',(0.42,0.E+000)); -#61964 = VECTOR('',#61965,1.); -#61965 = DIRECTION('',(-1.,0.E+000)); -#61966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61967 = ORIENTED_EDGE('',*,*,#61968,.T.); -#61968 = EDGE_CURVE('',#61941,#61969,#61971,.T.); -#61969 = VERTEX_POINT('',#61970); -#61970 = CARTESIAN_POINT('',(-3.095,0.92,-2.35)); -#61971 = SURFACE_CURVE('',#61972,(#61976,#61983),.PCURVE_S1.); -#61972 = LINE('',#61973,#61974); -#61973 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); -#61974 = VECTOR('',#61975,1.); -#61975 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#61976 = PCURVE('',#61825,#61977); -#61977 = DEFINITIONAL_REPRESENTATION('',(#61978),#61982); -#61978 = LINE('',#61979,#61980); -#61979 = CARTESIAN_POINT('',(-2.37,0.92)); -#61980 = VECTOR('',#61981,1.); -#61981 = DIRECTION('',(-1.,0.E+000)); -#61982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61983 = PCURVE('',#43400,#61984); -#61984 = DEFINITIONAL_REPRESENTATION('',(#61985),#61989); -#61985 = LINE('',#61986,#61987); -#61986 = CARTESIAN_POINT('',(5.465,0.E+000)); -#61987 = VECTOR('',#61988,1.); -#61988 = DIRECTION('',(1.,0.E+000)); -#61989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#61990 = ORIENTED_EDGE('',*,*,#61991,.T.); -#61991 = EDGE_CURVE('',#61969,#61992,#61994,.T.); -#61992 = VERTEX_POINT('',#61993); -#61993 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); -#61994 = SURFACE_CURVE('',#61995,(#62000,#62007),.PCURVE_S1.); -#61995 = CIRCLE('',#61996,0.35); -#61996 = AXIS2_PLACEMENT_3D('',#61997,#61998,#61999); -#61997 = CARTESIAN_POINT('',(-3.095,0.57,-2.35)); -#61998 = DIRECTION('',(0.E+000,0.E+000,1.)); -#61999 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62000 = PCURVE('',#61825,#62001); -#62001 = DEFINITIONAL_REPRESENTATION('',(#62002),#62006); -#62002 = CIRCLE('',#62003,0.35); -#62003 = AXIS2_PLACEMENT_2D('',#62004,#62005); -#62004 = CARTESIAN_POINT('',(-3.095,0.57)); -#62005 = DIRECTION('',(0.E+000,1.)); -#62006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62007 = PCURVE('',#43765,#62008); -#62008 = DEFINITIONAL_REPRESENTATION('',(#62009),#62012); -#62009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62010,#62011),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62010 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#62011 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62013 = ORIENTED_EDGE('',*,*,#62014,.T.); -#62014 = EDGE_CURVE('',#61992,#62015,#62017,.T.); -#62015 = VERTEX_POINT('',#62016); -#62016 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-2.35)); -#62017 = SURFACE_CURVE('',#62018,(#62022,#62029),.PCURVE_S1.); -#62018 = LINE('',#62019,#62020); -#62019 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); -#62020 = VECTOR('',#62021,1.); -#62021 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62022 = PCURVE('',#61825,#62023); -#62023 = DEFINITIONAL_REPRESENTATION('',(#62024),#62028); -#62024 = LINE('',#62025,#62026); -#62025 = CARTESIAN_POINT('',(-3.445,0.57)); -#62026 = VECTOR('',#62027,1.); -#62027 = DIRECTION('',(0.E+000,-1.)); -#62028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62029 = PCURVE('',#43736,#62030); -#62030 = DEFINITIONAL_REPRESENTATION('',(#62031),#62035); -#62031 = LINE('',#62032,#62033); -#62032 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62033 = VECTOR('',#62034,1.); -#62034 = DIRECTION('',(1.,0.E+000)); -#62035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62036 = ORIENTED_EDGE('',*,*,#62037,.T.); -#62037 = EDGE_CURVE('',#62015,#62038,#62040,.T.); -#62038 = VERTEX_POINT('',#62039); -#62039 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); -#62040 = SURFACE_CURVE('',#62041,(#62046,#62053),.PCURVE_S1.); -#62041 = CIRCLE('',#62042,0.25); -#62042 = AXIS2_PLACEMENT_3D('',#62043,#62044,#62045); -#62043 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-2.35)); -#62044 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62045 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62046 = PCURVE('',#61825,#62047); -#62047 = DEFINITIONAL_REPRESENTATION('',(#62048),#62052); -#62048 = CIRCLE('',#62049,0.25); -#62049 = AXIS2_PLACEMENT_2D('',#62050,#62051); -#62050 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002)); -#62051 = DIRECTION('',(-1.,0.E+000)); -#62052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62053 = PCURVE('',#43709,#62054); -#62054 = DEFINITIONAL_REPRESENTATION('',(#62055),#62058); -#62055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62056,#62057),.UNSPECIFIED., +#61737 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#61738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61739 = ORIENTED_EDGE('',*,*,#44155,.T.); +#61740 = ADVANCED_FACE('',(#61741),#44345,.F.); +#61741 = FACE_BOUND('',#61742,.F.); +#61742 = EDGE_LOOP('',(#61743,#61744,#61745,#61765)); +#61743 = ORIENTED_EDGE('',*,*,#61692,.F.); +#61744 = ORIENTED_EDGE('',*,*,#44329,.T.); +#61745 = ORIENTED_EDGE('',*,*,#61746,.F.); +#61746 = EDGE_CURVE('',#57781,#44298,#61747,.T.); +#61747 = SURFACE_CURVE('',#61748,(#61752,#61759),.PCURVE_S1.); +#61748 = LINE('',#61749,#61750); +#61749 = CARTESIAN_POINT('',(-1.71,-1.225,-1.13)); +#61750 = VECTOR('',#61751,1.); +#61751 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61752 = PCURVE('',#44345,#61753); +#61753 = DEFINITIONAL_REPRESENTATION('',(#61754),#61758); +#61754 = LINE('',#61755,#61756); +#61755 = CARTESIAN_POINT('',(3.42,0.E+000)); +#61756 = VECTOR('',#61757,1.); +#61757 = DIRECTION('',(0.E+000,-1.)); +#61758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61759 = PCURVE('',#44318,#61760); +#61760 = DEFINITIONAL_REPRESENTATION('',(#61761),#61764); +#61761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61762,#61763),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#61762 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#61763 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#61764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61765 = ORIENTED_EDGE('',*,*,#57780,.F.); +#61766 = ADVANCED_FACE('',(#61767),#44204,.F.); +#61767 = FACE_BOUND('',#61768,.F.); +#61768 = EDGE_LOOP('',(#61769,#61770,#61771,#61772,#61773,#61795)); +#61769 = ORIENTED_EDGE('',*,*,#45940,.F.); +#61770 = ORIENTED_EDGE('',*,*,#44183,.T.); +#61771 = ORIENTED_EDGE('',*,*,#61720,.F.); +#61772 = ORIENTED_EDGE('',*,*,#58760,.F.); +#61773 = ORIENTED_EDGE('',*,*,#61774,.T.); +#61774 = EDGE_CURVE('',#58733,#61775,#61777,.T.); +#61775 = VERTEX_POINT('',#61776); +#61776 = CARTESIAN_POINT('',(1.79,-1.2,-1.21)); +#61777 = SURFACE_CURVE('',#61778,(#61782,#61788),.PCURVE_S1.); +#61778 = LINE('',#61779,#61780); +#61779 = CARTESIAN_POINT('',(1.79,-1.225,-1.21)); +#61780 = VECTOR('',#61781,1.); +#61781 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61782 = PCURVE('',#44204,#61783); +#61783 = DEFINITIONAL_REPRESENTATION('',(#61784),#61787); +#61784 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61785,#61786),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,2.5E-002),.PIECEWISE_BEZIER_KNOTS.); +#61785 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#61786 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#61787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61788 = PCURVE('',#58748,#61789); +#61789 = DEFINITIONAL_REPRESENTATION('',(#61790),#61794); +#61790 = LINE('',#61791,#61792); +#61791 = CARTESIAN_POINT('',(0.32,0.E+000)); +#61792 = VECTOR('',#61793,1.); +#61793 = DIRECTION('',(0.E+000,-1.)); +#61794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61795 = ORIENTED_EDGE('',*,*,#61796,.T.); +#61796 = EDGE_CURVE('',#61775,#45941,#61797,.T.); +#61797 = SURFACE_CURVE('',#61798,(#61803,#61809),.PCURVE_S1.); +#61798 = CIRCLE('',#61799,8.E-002); +#61799 = AXIS2_PLACEMENT_3D('',#61800,#61801,#61802); +#61800 = CARTESIAN_POINT('',(1.71,-1.2,-1.21)); +#61801 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#61802 = DIRECTION('',(1.,0.E+000,0.E+000)); +#61803 = PCURVE('',#44204,#61804); +#61804 = DEFINITIONAL_REPRESENTATION('',(#61805),#61808); +#61805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61806,#61807),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.848062078984),.PIECEWISE_BEZIER_KNOTS.); +#61806 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#61807 = CARTESIAN_POINT('',(0.848062078984,-2.5E-002)); +#61808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61809 = PCURVE('',#45978,#61810); +#61810 = DEFINITIONAL_REPRESENTATION('',(#61811),#61815); +#61811 = CIRCLE('',#61812,8.E-002); +#61812 = AXIS2_PLACEMENT_2D('',#61813,#61814); +#61813 = CARTESIAN_POINT('',(6.E-002,-8.E-002)); +#61814 = DIRECTION('',(0.E+000,1.)); +#61815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61816 = ADVANCED_FACE('',(#61817),#58748,.F.); +#61817 = FACE_BOUND('',#61818,.F.); +#61818 = EDGE_LOOP('',(#61819,#61842,#61843,#61844)); +#61819 = ORIENTED_EDGE('',*,*,#61820,.T.); +#61820 = EDGE_CURVE('',#61821,#61775,#61823,.T.); +#61821 = VERTEX_POINT('',#61822); +#61822 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); +#61823 = SURFACE_CURVE('',#61824,(#61828,#61835),.PCURVE_S1.); +#61824 = LINE('',#61825,#61826); +#61825 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); +#61826 = VECTOR('',#61827,1.); +#61827 = DIRECTION('',(0.E+000,0.E+000,1.)); +#61828 = PCURVE('',#58748,#61829); +#61829 = DEFINITIONAL_REPRESENTATION('',(#61830),#61834); +#61830 = LINE('',#61831,#61832); +#61831 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#61832 = VECTOR('',#61833,1.); +#61833 = DIRECTION('',(1.,0.E+000)); +#61834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61835 = PCURVE('',#45978,#61836); +#61836 = DEFINITIONAL_REPRESENTATION('',(#61837),#61841); +#61837 = LINE('',#61838,#61839); +#61838 = CARTESIAN_POINT('',(0.38,0.E+000)); +#61839 = VECTOR('',#61840,1.); +#61840 = DIRECTION('',(-1.,0.E+000)); +#61841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61842 = ORIENTED_EDGE('',*,*,#61774,.F.); +#61843 = ORIENTED_EDGE('',*,*,#58732,.F.); +#61844 = ORIENTED_EDGE('',*,*,#61845,.T.); +#61845 = EDGE_CURVE('',#58710,#61821,#61846,.T.); +#61846 = SURFACE_CURVE('',#61847,(#61851,#61858),.PCURVE_S1.); +#61847 = LINE('',#61848,#61849); +#61848 = CARTESIAN_POINT('',(1.79,-1.225,-1.53)); +#61849 = VECTOR('',#61850,1.); +#61850 = DIRECTION('',(0.E+000,1.,0.E+000)); +#61851 = PCURVE('',#58748,#61852); +#61852 = DEFINITIONAL_REPRESENTATION('',(#61853),#61857); +#61853 = LINE('',#61854,#61855); +#61854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#61855 = VECTOR('',#61856,1.); +#61856 = DIRECTION('',(0.E+000,-1.)); +#61857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61858 = PCURVE('',#43312,#61859); +#61859 = DEFINITIONAL_REPRESENTATION('',(#61860),#61864); +#61860 = LINE('',#61861,#61862); +#61861 = CARTESIAN_POINT('',(0.35,5.54)); +#61862 = VECTOR('',#61863,1.); +#61863 = DIRECTION('',(-1.,0.E+000)); +#61864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61865 = ADVANCED_FACE('',(#61866),#45978,.T.); +#61866 = FACE_BOUND('',#61867,.F.); +#61867 = EDGE_LOOP('',(#61868,#61869,#61892,#61915,#61936,#61937)); +#61868 = ORIENTED_EDGE('',*,*,#61820,.F.); +#61869 = ORIENTED_EDGE('',*,*,#61870,.T.); +#61870 = EDGE_CURVE('',#61821,#61871,#61873,.T.); +#61871 = VERTEX_POINT('',#61872); +#61872 = CARTESIAN_POINT('',(-1.79,-1.2,-1.53)); +#61873 = SURFACE_CURVE('',#61874,(#61878,#61885),.PCURVE_S1.); +#61874 = LINE('',#61875,#61876); +#61875 = CARTESIAN_POINT('',(1.79,-1.2,-1.53)); +#61876 = VECTOR('',#61877,1.); +#61877 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61878 = PCURVE('',#45978,#61879); +#61879 = DEFINITIONAL_REPRESENTATION('',(#61880),#61884); +#61880 = LINE('',#61881,#61882); +#61881 = CARTESIAN_POINT('',(0.38,0.E+000)); +#61882 = VECTOR('',#61883,1.); +#61883 = DIRECTION('',(0.E+000,-1.)); +#61884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61885 = PCURVE('',#43312,#61886); +#61886 = DEFINITIONAL_REPRESENTATION('',(#61887),#61891); +#61887 = LINE('',#61888,#61889); +#61888 = CARTESIAN_POINT('',(0.325,5.54)); +#61889 = VECTOR('',#61890,1.); +#61890 = DIRECTION('',(0.E+000,-1.)); +#61891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61892 = ORIENTED_EDGE('',*,*,#61893,.F.); +#61893 = EDGE_CURVE('',#61894,#61871,#61896,.T.); +#61894 = VERTEX_POINT('',#61895); +#61895 = CARTESIAN_POINT('',(-1.79,-1.2,-1.21)); +#61896 = SURFACE_CURVE('',#61897,(#61901,#61908),.PCURVE_S1.); +#61897 = LINE('',#61898,#61899); +#61898 = CARTESIAN_POINT('',(-1.79,-1.2,-1.21)); +#61899 = VECTOR('',#61900,1.); +#61900 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#61901 = PCURVE('',#45978,#61902); +#61902 = DEFINITIONAL_REPRESENTATION('',(#61903),#61907); +#61903 = LINE('',#61904,#61905); +#61904 = CARTESIAN_POINT('',(6.E-002,-3.58)); +#61905 = VECTOR('',#61906,1.); +#61906 = DIRECTION('',(1.,0.E+000)); +#61907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61908 = PCURVE('',#57842,#61909); +#61909 = DEFINITIONAL_REPRESENTATION('',(#61910),#61914); +#61910 = LINE('',#61911,#61912); +#61911 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#61912 = VECTOR('',#61913,1.); +#61913 = DIRECTION('',(1.,0.E+000)); +#61914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61915 = ORIENTED_EDGE('',*,*,#61916,.F.); +#61916 = EDGE_CURVE('',#45963,#61894,#61917,.T.); +#61917 = SURFACE_CURVE('',#61918,(#61923,#61930),.PCURVE_S1.); +#61918 = CIRCLE('',#61919,8.E-002); +#61919 = AXIS2_PLACEMENT_3D('',#61920,#61921,#61922); +#61920 = CARTESIAN_POINT('',(-1.71,-1.2,-1.21)); +#61921 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#61922 = DIRECTION('',(-0.661437827766,0.E+000,0.75)); +#61923 = PCURVE('',#45978,#61924); +#61924 = DEFINITIONAL_REPRESENTATION('',(#61925),#61929); +#61925 = CIRCLE('',#61926,8.E-002); +#61926 = AXIS2_PLACEMENT_2D('',#61927,#61928); +#61927 = CARTESIAN_POINT('',(6.E-002,-3.5)); +#61928 = DIRECTION('',(-0.75,-0.661437827766)); +#61929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61930 = PCURVE('',#44318,#61931); +#61931 = DEFINITIONAL_REPRESENTATION('',(#61932),#61935); +#61932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#61933,#61934),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.848062078982),.PIECEWISE_BEZIER_KNOTS.); +#61933 = CARTESIAN_POINT('',(2.293530574608,-2.5E-002)); +#61934 = CARTESIAN_POINT('',(3.14159265359,-2.5E-002)); +#61935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61936 = ORIENTED_EDGE('',*,*,#45962,.F.); +#61937 = ORIENTED_EDGE('',*,*,#61796,.F.); +#61938 = ADVANCED_FACE('',(#61939),#43312,.F.); +#61939 = FACE_BOUND('',#61940,.F.); +#61940 = EDGE_LOOP('',(#61941,#61942,#61965,#61986,#61987,#62010,#62030, + #62031,#62032,#62033,#62054,#62055,#62056,#62057,#62080,#62103, + #62123,#62124)); +#61941 = ORIENTED_EDGE('',*,*,#45269,.T.); +#61942 = ORIENTED_EDGE('',*,*,#61943,.T.); +#61943 = EDGE_CURVE('',#45242,#61944,#61946,.T.); +#61944 = VERTEX_POINT('',#61945); +#61945 = CARTESIAN_POINT('',(-1.79,-0.985,-1.53)); +#61946 = SURFACE_CURVE('',#61947,(#61951,#61958),.PCURVE_S1.); +#61947 = LINE('',#61948,#61949); +#61948 = CARTESIAN_POINT('',(1.79,-0.985,-1.53)); +#61949 = VECTOR('',#61950,1.); +#61950 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#61951 = PCURVE('',#43312,#61952); +#61952 = DEFINITIONAL_REPRESENTATION('',(#61953),#61957); +#61953 = LINE('',#61954,#61955); +#61954 = CARTESIAN_POINT('',(0.11,5.54)); +#61955 = VECTOR('',#61956,1.); +#61956 = DIRECTION('',(0.E+000,-1.)); +#61957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61958 = PCURVE('',#45257,#61959); +#61959 = DEFINITIONAL_REPRESENTATION('',(#61960),#61964); +#61960 = LINE('',#61961,#61962); +#61961 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#61962 = VECTOR('',#61963,1.); +#61963 = DIRECTION('',(0.E+000,-1.)); +#61964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61965 = ORIENTED_EDGE('',*,*,#61966,.F.); +#61966 = EDGE_CURVE('',#44245,#61944,#61967,.T.); +#61967 = SURFACE_CURVE('',#61968,(#61972,#61979),.PCURVE_S1.); +#61968 = LINE('',#61969,#61970); +#61969 = CARTESIAN_POINT('',(-1.79,-0.925,-1.53)); +#61970 = VECTOR('',#61971,1.); +#61971 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#61972 = PCURVE('',#43312,#61973); +#61973 = DEFINITIONAL_REPRESENTATION('',(#61974),#61978); +#61974 = LINE('',#61975,#61976); +#61975 = CARTESIAN_POINT('',(5.E-002,1.96)); +#61976 = VECTOR('',#61977,1.); +#61977 = DIRECTION('',(1.,0.E+000)); +#61978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61979 = PCURVE('',#44262,#61980); +#61980 = DEFINITIONAL_REPRESENTATION('',(#61981),#61985); +#61981 = LINE('',#61982,#61983); +#61982 = CARTESIAN_POINT('',(0.32,-0.3)); +#61983 = VECTOR('',#61984,1.); +#61984 = DIRECTION('',(0.E+000,1.)); +#61985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#61986 = ORIENTED_EDGE('',*,*,#45103,.F.); +#61987 = ORIENTED_EDGE('',*,*,#61988,.F.); +#61988 = EDGE_CURVE('',#61989,#45077,#61991,.T.); +#61989 = VERTEX_POINT('',#61990); +#61990 = CARTESIAN_POINT('',(-2.746446609407,-0.875,-1.53)); +#61991 = SURFACE_CURVE('',#61992,(#61997,#62004),.PCURVE_S1.); +#61992 = CIRCLE('',#61993,0.25); +#61993 = AXIS2_PLACEMENT_3D('',#61994,#61995,#61996); +#61994 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-1.53)); +#61995 = DIRECTION('',(0.E+000,0.E+000,1.)); +#61996 = DIRECTION('',(-0.6,-0.8,0.E+000)); +#61997 = PCURVE('',#43312,#61998); +#61998 = DEFINITIONAL_REPRESENTATION('',(#61999),#62003); +#61999 = CIRCLE('',#62000,0.25); +#62000 = AXIS2_PLACEMENT_2D('',#62001,#62002); +#62001 = CARTESIAN_POINT('',(-0.2,1.153553390593)); +#62002 = DIRECTION('',(0.8,-0.6)); +#62003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62004 = PCURVE('',#45092,#62005); +#62005 = DEFINITIONAL_REPRESENTATION('',(#62006),#62009); +#62006 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62007,#62008),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.643501108793),.PIECEWISE_BEZIER_KNOTS.); +#62007 = CARTESIAN_POINT('',(4.068887871591,0.82)); +#62008 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#62009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62010 = ORIENTED_EDGE('',*,*,#62011,.F.); +#62011 = EDGE_CURVE('',#57381,#61989,#62012,.T.); +#62012 = SURFACE_CURVE('',#62013,(#62017,#62024),.PCURVE_S1.); +#62013 = LINE('',#62014,#62015); +#62014 = CARTESIAN_POINT('',(-3.174264068712,-0.875,-1.53)); +#62015 = VECTOR('',#62016,1.); +#62016 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62017 = PCURVE('',#43312,#62018); +#62018 = DEFINITIONAL_REPRESENTATION('',(#62019),#62023); +#62019 = LINE('',#62020,#62021); +#62020 = CARTESIAN_POINT('',(0.E+000,0.575735931288)); +#62021 = VECTOR('',#62022,1.); +#62022 = DIRECTION('',(0.E+000,1.)); +#62023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62024 = PCURVE('',#57429,#62025); +#62025 = DEFINITIONAL_REPRESENTATION('',(#62026),#62029); +#62026 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62027,#62028),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.427817459305),.PIECEWISE_BEZIER_KNOTS.); +#62027 = CARTESIAN_POINT('',(3.14159265359,0.575735931288)); +#62028 = CARTESIAN_POINT('',(3.14159265359,1.003553390593)); +#62029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62030 = ORIENTED_EDGE('',*,*,#57380,.F.); +#62031 = ORIENTED_EDGE('',*,*,#57518,.T.); +#62032 = ORIENTED_EDGE('',*,*,#57854,.T.); +#62033 = ORIENTED_EDGE('',*,*,#62034,.T.); +#62034 = EDGE_CURVE('',#57827,#61871,#62035,.T.); +#62035 = SURFACE_CURVE('',#62036,(#62040,#62047),.PCURVE_S1.); +#62036 = LINE('',#62037,#62038); +#62037 = CARTESIAN_POINT('',(-1.79,-1.225,-1.53)); +#62038 = VECTOR('',#62039,1.); +#62039 = DIRECTION('',(0.E+000,1.,0.E+000)); +#62040 = PCURVE('',#43312,#62041); +#62041 = DEFINITIONAL_REPRESENTATION('',(#62042),#62046); +#62042 = LINE('',#62043,#62044); +#62043 = CARTESIAN_POINT('',(0.35,1.96)); +#62044 = VECTOR('',#62045,1.); +#62045 = DIRECTION('',(-1.,0.E+000)); +#62046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62047 = PCURVE('',#57842,#62048); +#62048 = DEFINITIONAL_REPRESENTATION('',(#62049),#62053); +#62049 = LINE('',#62050,#62051); +#62050 = CARTESIAN_POINT('',(0.32,0.E+000)); +#62051 = VECTOR('',#62052,1.); +#62052 = DIRECTION('',(0.E+000,-1.)); +#62053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62054 = ORIENTED_EDGE('',*,*,#61870,.F.); +#62055 = ORIENTED_EDGE('',*,*,#61845,.F.); +#62056 = ORIENTED_EDGE('',*,*,#58709,.T.); +#62057 = ORIENTED_EDGE('',*,*,#62058,.T.); +#62058 = EDGE_CURVE('',#58683,#62059,#62061,.T.); +#62059 = VERTEX_POINT('',#62060); +#62060 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); +#62061 = SURFACE_CURVE('',#62062,(#62067,#62074),.PCURVE_S1.); +#62062 = CIRCLE('',#62063,0.55); +#62063 = AXIS2_PLACEMENT_3D('',#62064,#62065,#62066); +#62064 = CARTESIAN_POINT('',(2.596446609407,-0.675,-1.53)); +#62065 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62066 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62067 = PCURVE('',#43312,#62068); +#62068 = DEFINITIONAL_REPRESENTATION('',(#62069),#62073); +#62069 = CIRCLE('',#62070,0.55); +#62070 = AXIS2_PLACEMENT_2D('',#62071,#62072); +#62071 = CARTESIAN_POINT('',(-0.2,6.346446609407)); +#62072 = DIRECTION('',(1.,0.E+000)); +#62073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62074 = PCURVE('',#58698,#62075); +#62075 = DEFINITIONAL_REPRESENTATION('',(#62076),#62079); +#62076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62077,#62078),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#62056 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62057 = CARTESIAN_POINT('',(3.926990816986,0.E+000)); -#62058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62059 = ORIENTED_EDGE('',*,*,#62060,.T.); -#62060 = EDGE_CURVE('',#62038,#61815,#62061,.T.); -#62061 = SURFACE_CURVE('',#62062,(#62066,#62073),.PCURVE_S1.); -#62062 = LINE('',#62063,#62064); -#62063 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); -#62064 = VECTOR('',#62065,1.); -#62065 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#62066 = PCURVE('',#61825,#62067); -#62067 = DEFINITIONAL_REPRESENTATION('',(#62068),#62072); -#62068 = LINE('',#62069,#62070); -#62069 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892)); -#62070 = VECTOR('',#62071,1.); -#62071 = DIRECTION('',(0.707106781187,-0.707106781187)); -#62072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62073 = PCURVE('',#43680,#62074); -#62074 = DEFINITIONAL_REPRESENTATION('',(#62075),#62079); -#62075 = LINE('',#62076,#62077); -#62076 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62077 = VECTOR('',#62078,1.); -#62078 = DIRECTION('',(1.,0.E+000)); +#62077 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#62078 = CARTESIAN_POINT('',(5.497787143781,0.82)); #62079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62080 = ADVANCED_FACE('',(#62081),#42781,.F.); -#62081 = FACE_BOUND('',#62082,.F.); -#62082 = EDGE_LOOP('',(#62083,#62084,#62085,#62086,#62109,#62132,#62153, - #62154,#62155,#62156,#62182,#62183,#62209,#62210,#62236,#62237, - #62263,#62264)); -#62083 = ORIENTED_EDGE('',*,*,#61192,.F.); -#62084 = ORIENTED_EDGE('',*,*,#42765,.T.); -#62085 = ORIENTED_EDGE('',*,*,#43002,.T.); -#62086 = ORIENTED_EDGE('',*,*,#62087,.T.); -#62087 = EDGE_CURVE('',#42975,#62088,#62090,.T.); -#62088 = VERTEX_POINT('',#62089); -#62089 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); -#62090 = SURFACE_CURVE('',#62091,(#62095,#62102),.PCURVE_S1.); +#62080 = ORIENTED_EDGE('',*,*,#62081,.T.); +#62081 = EDGE_CURVE('',#62059,#62082,#62084,.T.); +#62082 = VERTEX_POINT('',#62083); +#62083 = CARTESIAN_POINT('',(3.174264068712,-0.875,-1.53)); +#62084 = SURFACE_CURVE('',#62085,(#62089,#62096),.PCURVE_S1.); +#62085 = LINE('',#62086,#62087); +#62086 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); +#62087 = VECTOR('',#62088,1.); +#62088 = DIRECTION('',(0.707106781186,0.707106781187,0.E+000)); +#62089 = PCURVE('',#43312,#62090); +#62090 = DEFINITIONAL_REPRESENTATION('',(#62091),#62095); #62091 = LINE('',#62092,#62093); -#62092 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); +#62092 = CARTESIAN_POINT('',(0.188908729653,6.735355339059)); #62093 = VECTOR('',#62094,1.); -#62094 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62095 = PCURVE('',#42781,#62096); -#62096 = DEFINITIONAL_REPRESENTATION('',(#62097),#62101); -#62097 = LINE('',#62098,#62099); -#62098 = CARTESIAN_POINT('',(1.925,-0.92)); -#62099 = VECTOR('',#62100,1.); -#62100 = DIRECTION('',(0.E+000,1.)); -#62101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62102 = PCURVE('',#51990,#62103); -#62103 = DEFINITIONAL_REPRESENTATION('',(#62104),#62108); -#62104 = LINE('',#62105,#62106); -#62105 = CARTESIAN_POINT('',(0.305,0.E+000)); -#62106 = VECTOR('',#62107,1.); -#62107 = DIRECTION('',(1.,0.E+000)); -#62108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62109 = ORIENTED_EDGE('',*,*,#62110,.T.); -#62110 = EDGE_CURVE('',#62088,#62111,#62113,.T.); -#62111 = VERTEX_POINT('',#62112); -#62112 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); -#62113 = SURFACE_CURVE('',#62114,(#62118,#62125),.PCURVE_S1.); -#62114 = LINE('',#62115,#62116); -#62115 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); -#62116 = VECTOR('',#62117,1.); -#62117 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62118 = PCURVE('',#42781,#62119); -#62119 = DEFINITIONAL_REPRESENTATION('',(#62120),#62124); -#62120 = LINE('',#62121,#62122); -#62121 = CARTESIAN_POINT('',(1.925,-0.725)); -#62122 = VECTOR('',#62123,1.); -#62123 = DIRECTION('',(-1.,0.E+000)); -#62124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62125 = PCURVE('',#51962,#62126); -#62126 = DEFINITIONAL_REPRESENTATION('',(#62127),#62131); -#62127 = LINE('',#62128,#62129); -#62128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62129 = VECTOR('',#62130,1.); -#62130 = DIRECTION('',(1.,0.E+000)); -#62131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62132 = ORIENTED_EDGE('',*,*,#62133,.F.); -#62133 = EDGE_CURVE('',#43057,#62111,#62134,.T.); +#62094 = DIRECTION('',(-0.707106781187,0.707106781186)); +#62095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62096 = PCURVE('',#55873,#62097); +#62097 = DEFINITIONAL_REPRESENTATION('',(#62098),#62102); +#62098 = LINE('',#62099,#62100); +#62099 = CARTESIAN_POINT('',(0.E+000,0.82)); +#62100 = VECTOR('',#62101,1.); +#62101 = DIRECTION('',(1.,0.E+000)); +#62102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62103 = ORIENTED_EDGE('',*,*,#62104,.F.); +#62104 = EDGE_CURVE('',#43297,#62082,#62105,.T.); +#62105 = SURFACE_CURVE('',#62106,(#62110,#62117),.PCURVE_S1.); +#62106 = LINE('',#62107,#62108); +#62107 = CARTESIAN_POINT('',(2.746446609407,-0.875,-1.53)); +#62108 = VECTOR('',#62109,1.); +#62109 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62110 = PCURVE('',#43312,#62111); +#62111 = DEFINITIONAL_REPRESENTATION('',(#62112),#62116); +#62112 = LINE('',#62113,#62114); +#62113 = CARTESIAN_POINT('',(0.E+000,6.496446609407)); +#62114 = VECTOR('',#62115,1.); +#62115 = DIRECTION('',(0.E+000,1.)); +#62116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62117 = PCURVE('',#43205,#62118); +#62118 = DEFINITIONAL_REPRESENTATION('',(#62119),#62122); +#62119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62120,#62121),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.427817459305),.PIECEWISE_BEZIER_KNOTS.); +#62120 = CARTESIAN_POINT('',(3.14159265359,6.496446609407)); +#62121 = CARTESIAN_POINT('',(3.14159265359,6.924264068712)); +#62122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62123 = ORIENTED_EDGE('',*,*,#43294,.F.); +#62124 = ORIENTED_EDGE('',*,*,#43472,.F.); +#62125 = ADVANCED_FACE('',(#62126),#45257,.T.); +#62126 = FACE_BOUND('',#62127,.F.); +#62127 = EDGE_LOOP('',(#62128,#62158,#62186,#62214,#62242,#62270,#62298, + #62326,#62354,#62382,#62410,#62438,#62466,#62494,#62522,#62550, + #62578,#62606,#62634,#62655,#62656,#62657,#62680,#62708)); +#62128 = ORIENTED_EDGE('',*,*,#62129,.T.); +#62129 = EDGE_CURVE('',#62130,#62132,#62134,.T.); +#62130 = VERTEX_POINT('',#62131); +#62131 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); +#62132 = VERTEX_POINT('',#62133); +#62133 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); #62134 = SURFACE_CURVE('',#62135,(#62139,#62146),.PCURVE_S1.); #62135 = LINE('',#62136,#62137); -#62136 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); +#62136 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); #62137 = VECTOR('',#62138,1.); -#62138 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62139 = PCURVE('',#42781,#62140); +#62138 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62139 = PCURVE('',#45257,#62140); #62140 = DEFINITIONAL_REPRESENTATION('',(#62141),#62145); #62141 = LINE('',#62142,#62143); -#62142 = CARTESIAN_POINT('',(-1.925,-0.92)); +#62142 = CARTESIAN_POINT('',(0.32,-0.615)); #62143 = VECTOR('',#62144,1.); -#62144 = DIRECTION('',(0.E+000,1.)); +#62144 = DIRECTION('',(-1.,0.E+000)); #62145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62146 = PCURVE('',#51934,#62147); -#62147 = DEFINITIONAL_REPRESENTATION('',(#62148),#62152); -#62148 = LINE('',#62149,#62150); -#62149 = CARTESIAN_POINT('',(0.195,0.E+000)); -#62150 = VECTOR('',#62151,1.); -#62151 = DIRECTION('',(-1.,0.E+000)); -#62152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62153 = ORIENTED_EDGE('',*,*,#43056,.T.); -#62154 = ORIENTED_EDGE('',*,*,#61520,.F.); -#62155 = ORIENTED_EDGE('',*,*,#60480,.F.); -#62156 = ORIENTED_EDGE('',*,*,#62157,.T.); -#62157 = EDGE_CURVE('',#60453,#60609,#62158,.T.); -#62158 = SURFACE_CURVE('',#62159,(#62163,#62170),.PCURVE_S1.); -#62159 = LINE('',#62160,#62161); -#62160 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); -#62161 = VECTOR('',#62162,1.); -#62162 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62163 = PCURVE('',#42781,#62164); -#62164 = DEFINITIONAL_REPRESENTATION('',(#62165),#62169); -#62165 = LINE('',#62166,#62167); -#62166 = CARTESIAN_POINT('',(-1.425,-1.105)); -#62167 = VECTOR('',#62168,1.); -#62168 = DIRECTION('',(1.,0.E+000)); -#62169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62170 = PCURVE('',#62171,#62176); -#62171 = PLANE('',#62172); -#62172 = AXIS2_PLACEMENT_3D('',#62173,#62174,#62175); -#62173 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); -#62174 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62175 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62176 = DEFINITIONAL_REPRESENTATION('',(#62177),#62181); -#62177 = LINE('',#62178,#62179); -#62178 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62179 = VECTOR('',#62180,1.); -#62180 = DIRECTION('',(0.E+000,1.)); -#62181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62182 = ORIENTED_EDGE('',*,*,#60608,.F.); -#62183 = ORIENTED_EDGE('',*,*,#62184,.T.); -#62184 = EDGE_CURVE('',#60581,#60765,#62185,.T.); -#62185 = SURFACE_CURVE('',#62186,(#62190,#62197),.PCURVE_S1.); -#62186 = LINE('',#62187,#62188); -#62187 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); -#62188 = VECTOR('',#62189,1.); -#62189 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62190 = PCURVE('',#42781,#62191); -#62191 = DEFINITIONAL_REPRESENTATION('',(#62192),#62196); -#62192 = LINE('',#62193,#62194); -#62193 = CARTESIAN_POINT('',(-0.775,-1.105)); -#62194 = VECTOR('',#62195,1.); -#62195 = DIRECTION('',(1.,0.E+000)); -#62196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62197 = PCURVE('',#62198,#62203); -#62198 = PLANE('',#62199); -#62199 = AXIS2_PLACEMENT_3D('',#62200,#62201,#62202); -#62200 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); -#62201 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62202 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62203 = DEFINITIONAL_REPRESENTATION('',(#62204),#62208); -#62204 = LINE('',#62205,#62206); -#62205 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62206 = VECTOR('',#62207,1.); -#62207 = DIRECTION('',(0.E+000,1.)); -#62208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62209 = ORIENTED_EDGE('',*,*,#60764,.F.); -#62210 = ORIENTED_EDGE('',*,*,#62211,.T.); -#62211 = EDGE_CURVE('',#60737,#60921,#62212,.T.); -#62212 = SURFACE_CURVE('',#62213,(#62217,#62224),.PCURVE_S1.); -#62213 = LINE('',#62214,#62215); -#62214 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); -#62215 = VECTOR('',#62216,1.); -#62216 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62217 = PCURVE('',#42781,#62218); -#62218 = DEFINITIONAL_REPRESENTATION('',(#62219),#62223); +#62146 = PCURVE('',#62147,#62152); +#62147 = PLANE('',#62148); +#62148 = AXIS2_PLACEMENT_3D('',#62149,#62150,#62151); +#62149 = CARTESIAN_POINT('',(1.175,0.E+000,0.E+000)); +#62150 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62151 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62152 = DEFINITIONAL_REPRESENTATION('',(#62153),#62157); +#62153 = LINE('',#62154,#62155); +#62154 = CARTESIAN_POINT('',(1.85,-0.985)); +#62155 = VECTOR('',#62156,1.); +#62156 = DIRECTION('',(-1.,0.E+000)); +#62157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62158 = ORIENTED_EDGE('',*,*,#62159,.T.); +#62159 = EDGE_CURVE('',#62132,#62160,#62162,.T.); +#62160 = VERTEX_POINT('',#62161); +#62161 = CARTESIAN_POINT('',(0.775,-0.985,-1.71)); +#62162 = SURFACE_CURVE('',#62163,(#62167,#62174),.PCURVE_S1.); +#62163 = LINE('',#62164,#62165); +#62164 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); +#62165 = VECTOR('',#62166,1.); +#62166 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62167 = PCURVE('',#45257,#62168); +#62168 = DEFINITIONAL_REPRESENTATION('',(#62169),#62173); +#62169 = LINE('',#62170,#62171); +#62170 = CARTESIAN_POINT('',(0.18,-0.615)); +#62171 = VECTOR('',#62172,1.); +#62172 = DIRECTION('',(0.E+000,-1.)); +#62173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62174 = PCURVE('',#62175,#62180); +#62175 = PLANE('',#62176); +#62176 = AXIS2_PLACEMENT_3D('',#62177,#62178,#62179); +#62177 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62178 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62179 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62180 = DEFINITIONAL_REPRESENTATION('',(#62181),#62185); +#62181 = LINE('',#62182,#62183); +#62182 = CARTESIAN_POINT('',(0.E+000,-0.615)); +#62183 = VECTOR('',#62184,1.); +#62184 = DIRECTION('',(0.E+000,-1.)); +#62185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62186 = ORIENTED_EDGE('',*,*,#62187,.F.); +#62187 = EDGE_CURVE('',#62188,#62160,#62190,.T.); +#62188 = VERTEX_POINT('',#62189); +#62189 = CARTESIAN_POINT('',(0.775,-0.985,-1.85)); +#62190 = SURFACE_CURVE('',#62191,(#62195,#62202),.PCURVE_S1.); +#62191 = LINE('',#62192,#62193); +#62192 = CARTESIAN_POINT('',(0.775,-0.985,-1.85)); +#62193 = VECTOR('',#62194,1.); +#62194 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62195 = PCURVE('',#45257,#62196); +#62196 = DEFINITIONAL_REPRESENTATION('',(#62197),#62201); +#62197 = LINE('',#62198,#62199); +#62198 = CARTESIAN_POINT('',(0.32,-1.015)); +#62199 = VECTOR('',#62200,1.); +#62200 = DIRECTION('',(-1.,0.E+000)); +#62201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62202 = PCURVE('',#62203,#62208); +#62203 = PLANE('',#62204); +#62204 = AXIS2_PLACEMENT_3D('',#62205,#62206,#62207); +#62205 = CARTESIAN_POINT('',(0.775,0.E+000,0.E+000)); +#62206 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62207 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62208 = DEFINITIONAL_REPRESENTATION('',(#62209),#62213); +#62209 = LINE('',#62210,#62211); +#62210 = CARTESIAN_POINT('',(1.85,-0.985)); +#62211 = VECTOR('',#62212,1.); +#62212 = DIRECTION('',(-1.,0.E+000)); +#62213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62214 = ORIENTED_EDGE('',*,*,#62215,.F.); +#62215 = EDGE_CURVE('',#62216,#62188,#62218,.T.); +#62216 = VERTEX_POINT('',#62217); +#62217 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); +#62218 = SURFACE_CURVE('',#62219,(#62223,#62230),.PCURVE_S1.); #62219 = LINE('',#62220,#62221); -#62220 = CARTESIAN_POINT('',(-0.125,-1.105)); +#62220 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); #62221 = VECTOR('',#62222,1.); -#62222 = DIRECTION('',(1.,0.E+000)); -#62223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62224 = PCURVE('',#62225,#62230); -#62225 = PLANE('',#62226); -#62226 = AXIS2_PLACEMENT_3D('',#62227,#62228,#62229); -#62227 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); -#62228 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62229 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62230 = DEFINITIONAL_REPRESENTATION('',(#62231),#62235); -#62231 = LINE('',#62232,#62233); -#62232 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62233 = VECTOR('',#62234,1.); -#62234 = DIRECTION('',(0.E+000,1.)); -#62235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62236 = ORIENTED_EDGE('',*,*,#60920,.F.); -#62237 = ORIENTED_EDGE('',*,*,#62238,.T.); -#62238 = EDGE_CURVE('',#60893,#61048,#62239,.T.); -#62239 = SURFACE_CURVE('',#62240,(#62244,#62251),.PCURVE_S1.); -#62240 = LINE('',#62241,#62242); -#62241 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); -#62242 = VECTOR('',#62243,1.); -#62243 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62244 = PCURVE('',#42781,#62245); -#62245 = DEFINITIONAL_REPRESENTATION('',(#62246),#62250); -#62246 = LINE('',#62247,#62248); -#62247 = CARTESIAN_POINT('',(0.525,-1.105)); -#62248 = VECTOR('',#62249,1.); -#62249 = DIRECTION('',(1.,0.E+000)); -#62250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62251 = PCURVE('',#62252,#62257); -#62252 = PLANE('',#62253); -#62253 = AXIS2_PLACEMENT_3D('',#62254,#62255,#62256); -#62254 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); -#62255 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62256 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62257 = DEFINITIONAL_REPRESENTATION('',(#62258),#62262); -#62258 = LINE('',#62259,#62260); -#62259 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62260 = VECTOR('',#62261,1.); -#62261 = DIRECTION('',(0.E+000,1.)); -#62262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62263 = ORIENTED_EDGE('',*,*,#61047,.F.); -#62264 = ORIENTED_EDGE('',*,*,#62265,.T.); -#62265 = EDGE_CURVE('',#61020,#61193,#62266,.T.); -#62266 = SURFACE_CURVE('',#62267,(#62271,#62278),.PCURVE_S1.); -#62267 = LINE('',#62268,#62269); -#62268 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); -#62269 = VECTOR('',#62270,1.); -#62270 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62271 = PCURVE('',#42781,#62272); -#62272 = DEFINITIONAL_REPRESENTATION('',(#62273),#62277); -#62273 = LINE('',#62274,#62275); -#62274 = CARTESIAN_POINT('',(1.175,-1.105)); -#62275 = VECTOR('',#62276,1.); -#62276 = DIRECTION('',(1.,0.E+000)); -#62277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62278 = PCURVE('',#62279,#62284); -#62279 = PLANE('',#62280); -#62280 = AXIS2_PLACEMENT_3D('',#62281,#62282,#62283); -#62281 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); -#62282 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62283 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62284 = DEFINITIONAL_REPRESENTATION('',(#62285),#62289); -#62285 = LINE('',#62286,#62287); -#62286 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62287 = VECTOR('',#62288,1.); -#62288 = DIRECTION('',(0.E+000,1.)); -#62289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62290 = ADVANCED_FACE('',(#62291),#51589,.T.); -#62291 = FACE_BOUND('',#62292,.F.); -#62292 = EDGE_LOOP('',(#62293,#62294,#62295,#62316,#62317)); -#62293 = ORIENTED_EDGE('',*,*,#51573,.T.); -#62294 = ORIENTED_EDGE('',*,*,#52113,.T.); -#62295 = ORIENTED_EDGE('',*,*,#62296,.F.); -#62296 = EDGE_CURVE('',#61547,#52086,#62297,.T.); -#62297 = SURFACE_CURVE('',#62298,(#62302,#62309),.PCURVE_S1.); -#62298 = LINE('',#62299,#62300); -#62299 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); -#62300 = VECTOR('',#62301,1.); -#62301 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62302 = PCURVE('',#51589,#62303); -#62303 = DEFINITIONAL_REPRESENTATION('',(#62304),#62308); -#62304 = LINE('',#62305,#62306); -#62305 = CARTESIAN_POINT('',(0.8,0.E+000)); -#62306 = VECTOR('',#62307,1.); -#62307 = DIRECTION('',(0.E+000,1.)); -#62308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62309 = PCURVE('',#52101,#62310); -#62310 = DEFINITIONAL_REPRESENTATION('',(#62311),#62315); -#62311 = LINE('',#62312,#62313); -#62312 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62313 = VECTOR('',#62314,1.); -#62314 = DIRECTION('',(0.E+000,1.)); -#62315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62316 = ORIENTED_EDGE('',*,*,#61544,.F.); -#62317 = ORIENTED_EDGE('',*,*,#62318,.F.); -#62318 = EDGE_CURVE('',#51574,#61545,#62319,.T.); -#62319 = SURFACE_CURVE('',#62320,(#62324,#62331),.PCURVE_S1.); -#62320 = LINE('',#62321,#62322); -#62321 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); -#62322 = VECTOR('',#62323,1.); -#62323 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); -#62324 = PCURVE('',#51589,#62325); -#62325 = DEFINITIONAL_REPRESENTATION('',(#62326),#62330); -#62326 = LINE('',#62327,#62328); -#62327 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62328 = VECTOR('',#62329,1.); -#62329 = DIRECTION('',(1.,0.E+000)); -#62330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62331 = PCURVE('',#51617,#62332); -#62332 = DEFINITIONAL_REPRESENTATION('',(#62333),#62337); -#62333 = LINE('',#62334,#62335); -#62334 = CARTESIAN_POINT('',(-1.21,0.575)); -#62335 = VECTOR('',#62336,1.); -#62336 = DIRECTION('',(-0.866025403784,-0.5)); -#62337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62338 = ADVANCED_FACE('',(#62339),#52101,.T.); -#62339 = FACE_BOUND('',#62340,.F.); -#62340 = EDGE_LOOP('',(#62341,#62342,#62343,#62363)); -#62341 = ORIENTED_EDGE('',*,*,#62296,.T.); -#62342 = ORIENTED_EDGE('',*,*,#52085,.T.); -#62343 = ORIENTED_EDGE('',*,*,#62344,.F.); -#62344 = EDGE_CURVE('',#61575,#52058,#62345,.T.); -#62345 = SURFACE_CURVE('',#62346,(#62350,#62357),.PCURVE_S1.); -#62346 = LINE('',#62347,#62348); -#62347 = CARTESIAN_POINT('',(2.45,0.175,-2.35)); -#62348 = VECTOR('',#62349,1.); -#62349 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62350 = PCURVE('',#52101,#62351); -#62351 = DEFINITIONAL_REPRESENTATION('',(#62352),#62356); -#62352 = LINE('',#62353,#62354); -#62353 = CARTESIAN_POINT('',(0.547179676972,0.E+000)); -#62354 = VECTOR('',#62355,1.); -#62355 = DIRECTION('',(0.E+000,1.)); -#62356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62357 = PCURVE('',#52074,#62358); -#62358 = DEFINITIONAL_REPRESENTATION('',(#62359),#62362); -#62359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62360,#62361),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#62360 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#62361 = CARTESIAN_POINT('',(1.570796326795,0.3)); -#62362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62363 = ORIENTED_EDGE('',*,*,#61574,.F.); -#62364 = ADVANCED_FACE('',(#62365),#52074,.T.); -#62365 = FACE_BOUND('',#62366,.T.); -#62366 = EDGE_LOOP('',(#62367,#62368,#62369,#62389)); -#62367 = ORIENTED_EDGE('',*,*,#62344,.F.); -#62368 = ORIENTED_EDGE('',*,*,#61597,.T.); -#62369 = ORIENTED_EDGE('',*,*,#62370,.T.); -#62370 = EDGE_CURVE('',#61598,#52030,#62371,.T.); -#62371 = SURFACE_CURVE('',#62372,(#62376,#62382),.PCURVE_S1.); -#62372 = LINE('',#62373,#62374); -#62373 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); -#62374 = VECTOR('',#62375,1.); +#62222 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62223 = PCURVE('',#45257,#62224); +#62224 = DEFINITIONAL_REPRESENTATION('',(#62225),#62229); +#62225 = LINE('',#62226,#62227); +#62226 = CARTESIAN_POINT('',(0.32,-1.265)); +#62227 = VECTOR('',#62228,1.); +#62228 = DIRECTION('',(0.E+000,1.)); +#62229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62230 = PCURVE('',#62231,#62236); +#62231 = PLANE('',#62232); +#62232 = AXIS2_PLACEMENT_3D('',#62233,#62234,#62235); +#62233 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); +#62234 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#62235 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#62236 = DEFINITIONAL_REPRESENTATION('',(#62237),#62241); +#62237 = LINE('',#62238,#62239); +#62238 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62239 = VECTOR('',#62240,1.); +#62240 = DIRECTION('',(0.E+000,1.)); +#62241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62242 = ORIENTED_EDGE('',*,*,#62243,.T.); +#62243 = EDGE_CURVE('',#62216,#62244,#62246,.T.); +#62244 = VERTEX_POINT('',#62245); +#62245 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); +#62246 = SURFACE_CURVE('',#62247,(#62251,#62258),.PCURVE_S1.); +#62247 = LINE('',#62248,#62249); +#62248 = CARTESIAN_POINT('',(0.525,-0.985,-1.85)); +#62249 = VECTOR('',#62250,1.); +#62250 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62251 = PCURVE('',#45257,#62252); +#62252 = DEFINITIONAL_REPRESENTATION('',(#62253),#62257); +#62253 = LINE('',#62254,#62255); +#62254 = CARTESIAN_POINT('',(0.32,-1.265)); +#62255 = VECTOR('',#62256,1.); +#62256 = DIRECTION('',(-1.,0.E+000)); +#62257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62258 = PCURVE('',#62259,#62264); +#62259 = PLANE('',#62260); +#62260 = AXIS2_PLACEMENT_3D('',#62261,#62262,#62263); +#62261 = CARTESIAN_POINT('',(0.525,0.E+000,0.E+000)); +#62262 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62263 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62264 = DEFINITIONAL_REPRESENTATION('',(#62265),#62269); +#62265 = LINE('',#62266,#62267); +#62266 = CARTESIAN_POINT('',(1.85,-0.985)); +#62267 = VECTOR('',#62268,1.); +#62268 = DIRECTION('',(-1.,0.E+000)); +#62269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62270 = ORIENTED_EDGE('',*,*,#62271,.T.); +#62271 = EDGE_CURVE('',#62244,#62272,#62274,.T.); +#62272 = VERTEX_POINT('',#62273); +#62273 = CARTESIAN_POINT('',(0.125,-0.985,-1.71)); +#62274 = SURFACE_CURVE('',#62275,(#62279,#62286),.PCURVE_S1.); +#62275 = LINE('',#62276,#62277); +#62276 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); +#62277 = VECTOR('',#62278,1.); +#62278 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62279 = PCURVE('',#45257,#62280); +#62280 = DEFINITIONAL_REPRESENTATION('',(#62281),#62285); +#62281 = LINE('',#62282,#62283); +#62282 = CARTESIAN_POINT('',(0.18,-1.265)); +#62283 = VECTOR('',#62284,1.); +#62284 = DIRECTION('',(0.E+000,-1.)); +#62285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62286 = PCURVE('',#62287,#62292); +#62287 = PLANE('',#62288); +#62288 = AXIS2_PLACEMENT_3D('',#62289,#62290,#62291); +#62289 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62290 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62291 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62292 = DEFINITIONAL_REPRESENTATION('',(#62293),#62297); +#62293 = LINE('',#62294,#62295); +#62294 = CARTESIAN_POINT('',(0.E+000,-1.265)); +#62295 = VECTOR('',#62296,1.); +#62296 = DIRECTION('',(0.E+000,-1.)); +#62297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62298 = ORIENTED_EDGE('',*,*,#62299,.F.); +#62299 = EDGE_CURVE('',#62300,#62272,#62302,.T.); +#62300 = VERTEX_POINT('',#62301); +#62301 = CARTESIAN_POINT('',(0.125,-0.985,-1.85)); +#62302 = SURFACE_CURVE('',#62303,(#62307,#62314),.PCURVE_S1.); +#62303 = LINE('',#62304,#62305); +#62304 = CARTESIAN_POINT('',(0.125,-0.985,-1.85)); +#62305 = VECTOR('',#62306,1.); +#62306 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62307 = PCURVE('',#45257,#62308); +#62308 = DEFINITIONAL_REPRESENTATION('',(#62309),#62313); +#62309 = LINE('',#62310,#62311); +#62310 = CARTESIAN_POINT('',(0.32,-1.665)); +#62311 = VECTOR('',#62312,1.); +#62312 = DIRECTION('',(-1.,0.E+000)); +#62313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62314 = PCURVE('',#62315,#62320); +#62315 = PLANE('',#62316); +#62316 = AXIS2_PLACEMENT_3D('',#62317,#62318,#62319); +#62317 = CARTESIAN_POINT('',(0.125,0.E+000,0.E+000)); +#62318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62319 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62320 = DEFINITIONAL_REPRESENTATION('',(#62321),#62325); +#62321 = LINE('',#62322,#62323); +#62322 = CARTESIAN_POINT('',(1.85,-0.985)); +#62323 = VECTOR('',#62324,1.); +#62324 = DIRECTION('',(-1.,0.E+000)); +#62325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62326 = ORIENTED_EDGE('',*,*,#62327,.F.); +#62327 = EDGE_CURVE('',#62328,#62300,#62330,.T.); +#62328 = VERTEX_POINT('',#62329); +#62329 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); +#62330 = SURFACE_CURVE('',#62331,(#62335,#62342),.PCURVE_S1.); +#62331 = LINE('',#62332,#62333); +#62332 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); +#62333 = VECTOR('',#62334,1.); +#62334 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62335 = PCURVE('',#45257,#62336); +#62336 = DEFINITIONAL_REPRESENTATION('',(#62337),#62341); +#62337 = LINE('',#62338,#62339); +#62338 = CARTESIAN_POINT('',(0.32,-1.915)); +#62339 = VECTOR('',#62340,1.); +#62340 = DIRECTION('',(0.E+000,1.)); +#62341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62342 = PCURVE('',#62343,#62348); +#62343 = PLANE('',#62344); +#62344 = AXIS2_PLACEMENT_3D('',#62345,#62346,#62347); +#62345 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); +#62346 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#62347 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#62348 = DEFINITIONAL_REPRESENTATION('',(#62349),#62353); +#62349 = LINE('',#62350,#62351); +#62350 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62351 = VECTOR('',#62352,1.); +#62352 = DIRECTION('',(0.E+000,1.)); +#62353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62354 = ORIENTED_EDGE('',*,*,#62355,.T.); +#62355 = EDGE_CURVE('',#62328,#62356,#62358,.T.); +#62356 = VERTEX_POINT('',#62357); +#62357 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); +#62358 = SURFACE_CURVE('',#62359,(#62363,#62370),.PCURVE_S1.); +#62359 = LINE('',#62360,#62361); +#62360 = CARTESIAN_POINT('',(-0.125,-0.985,-1.85)); +#62361 = VECTOR('',#62362,1.); +#62362 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62363 = PCURVE('',#45257,#62364); +#62364 = DEFINITIONAL_REPRESENTATION('',(#62365),#62369); +#62365 = LINE('',#62366,#62367); +#62366 = CARTESIAN_POINT('',(0.32,-1.915)); +#62367 = VECTOR('',#62368,1.); +#62368 = DIRECTION('',(-1.,0.E+000)); +#62369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62370 = PCURVE('',#62371,#62376); +#62371 = PLANE('',#62372); +#62372 = AXIS2_PLACEMENT_3D('',#62373,#62374,#62375); +#62373 = CARTESIAN_POINT('',(-0.125,0.E+000,0.E+000)); +#62374 = DIRECTION('',(1.,0.E+000,0.E+000)); #62375 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62376 = PCURVE('',#52074,#62377); -#62377 = DEFINITIONAL_REPRESENTATION('',(#62378),#62381); -#62378 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62379,#62380),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#62379 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62380 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#62376 = DEFINITIONAL_REPRESENTATION('',(#62377),#62381); +#62377 = LINE('',#62378,#62379); +#62378 = CARTESIAN_POINT('',(1.85,-0.985)); +#62379 = VECTOR('',#62380,1.); +#62380 = DIRECTION('',(-1.,0.E+000)); #62381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62382 = PCURVE('',#52045,#62383); -#62383 = DEFINITIONAL_REPRESENTATION('',(#62384),#62388); -#62384 = LINE('',#62385,#62386); -#62385 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62386 = VECTOR('',#62387,1.); -#62387 = DIRECTION('',(0.E+000,1.)); -#62388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62389 = ORIENTED_EDGE('',*,*,#52057,.F.); -#62390 = ADVANCED_FACE('',(#62391),#52045,.T.); -#62391 = FACE_BOUND('',#62392,.F.); -#62392 = EDGE_LOOP('',(#62393,#62416,#62444,#62471,#62499,#62520,#62521, - #62522)); -#62393 = ORIENTED_EDGE('',*,*,#62394,.F.); -#62394 = EDGE_CURVE('',#62395,#52003,#62397,.T.); -#62395 = VERTEX_POINT('',#62396); -#62396 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); -#62397 = SURFACE_CURVE('',#62398,(#62403,#62410),.PCURVE_S1.); -#62398 = CIRCLE('',#62399,0.3); -#62399 = AXIS2_PLACEMENT_3D('',#62400,#62401,#62402); -#62400 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); -#62401 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62402 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62403 = PCURVE('',#52045,#62404); +#62382 = ORIENTED_EDGE('',*,*,#62383,.T.); +#62383 = EDGE_CURVE('',#62356,#62384,#62386,.T.); +#62384 = VERTEX_POINT('',#62385); +#62385 = CARTESIAN_POINT('',(-0.525,-0.985,-1.71)); +#62386 = SURFACE_CURVE('',#62387,(#62391,#62398),.PCURVE_S1.); +#62387 = LINE('',#62388,#62389); +#62388 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); +#62389 = VECTOR('',#62390,1.); +#62390 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62391 = PCURVE('',#45257,#62392); +#62392 = DEFINITIONAL_REPRESENTATION('',(#62393),#62397); +#62393 = LINE('',#62394,#62395); +#62394 = CARTESIAN_POINT('',(0.18,-1.915)); +#62395 = VECTOR('',#62396,1.); +#62396 = DIRECTION('',(0.E+000,-1.)); +#62397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62398 = PCURVE('',#62399,#62404); +#62399 = PLANE('',#62400); +#62400 = AXIS2_PLACEMENT_3D('',#62401,#62402,#62403); +#62401 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62402 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62403 = DIRECTION('',(0.E+000,-1.,0.E+000)); #62404 = DEFINITIONAL_REPRESENTATION('',(#62405),#62409); -#62405 = CIRCLE('',#62406,0.3); -#62406 = AXIS2_PLACEMENT_2D('',#62407,#62408); -#62407 = CARTESIAN_POINT('',(0.55,0.E+000)); -#62408 = DIRECTION('',(1.,0.E+000)); +#62405 = LINE('',#62406,#62407); +#62406 = CARTESIAN_POINT('',(0.E+000,-1.915)); +#62407 = VECTOR('',#62408,1.); +#62408 = DIRECTION('',(0.E+000,-1.)); #62409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62410 = PCURVE('',#52018,#62411); -#62411 = DEFINITIONAL_REPRESENTATION('',(#62412),#62415); -#62412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62413,#62414),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62413 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#62414 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); -#62415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62416 = ORIENTED_EDGE('',*,*,#62417,.T.); -#62417 = EDGE_CURVE('',#62395,#62418,#62420,.T.); -#62418 = VERTEX_POINT('',#62419); -#62419 = CARTESIAN_POINT('',(3.,-1.225,-1.95)); -#62420 = SURFACE_CURVE('',#62421,(#62425,#62432),.PCURVE_S1.); +#62410 = ORIENTED_EDGE('',*,*,#62411,.F.); +#62411 = EDGE_CURVE('',#62412,#62384,#62414,.T.); +#62412 = VERTEX_POINT('',#62413); +#62413 = CARTESIAN_POINT('',(-0.525,-0.985,-1.85)); +#62414 = SURFACE_CURVE('',#62415,(#62419,#62426),.PCURVE_S1.); +#62415 = LINE('',#62416,#62417); +#62416 = CARTESIAN_POINT('',(-0.525,-0.985,-1.85)); +#62417 = VECTOR('',#62418,1.); +#62418 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62419 = PCURVE('',#45257,#62420); +#62420 = DEFINITIONAL_REPRESENTATION('',(#62421),#62425); #62421 = LINE('',#62422,#62423); -#62422 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); +#62422 = CARTESIAN_POINT('',(0.32,-2.315)); #62423 = VECTOR('',#62424,1.); -#62424 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62425 = PCURVE('',#52045,#62426); -#62426 = DEFINITIONAL_REPRESENTATION('',(#62427),#62431); -#62427 = LINE('',#62428,#62429); -#62428 = CARTESIAN_POINT('',(0.85,0.E+000)); -#62429 = VECTOR('',#62430,1.); -#62430 = DIRECTION('',(0.E+000,-1.)); -#62431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62432 = PCURVE('',#62433,#62438); -#62433 = PLANE('',#62434); -#62434 = AXIS2_PLACEMENT_3D('',#62435,#62436,#62437); -#62435 = CARTESIAN_POINT('',(0.E+000,-1.225,0.E+000)); -#62436 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62437 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62438 = DEFINITIONAL_REPRESENTATION('',(#62439),#62443); -#62439 = LINE('',#62440,#62441); -#62440 = CARTESIAN_POINT('',(3.,-2.35)); -#62441 = VECTOR('',#62442,1.); -#62442 = DIRECTION('',(0.E+000,1.)); -#62443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62444 = ORIENTED_EDGE('',*,*,#62445,.T.); -#62445 = EDGE_CURVE('',#62418,#62446,#62448,.T.); -#62446 = VERTEX_POINT('',#62447); -#62447 = CARTESIAN_POINT('',(3.,-0.925,-1.95)); -#62448 = SURFACE_CURVE('',#62449,(#62453,#62460),.PCURVE_S1.); +#62424 = DIRECTION('',(-1.,0.E+000)); +#62425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62426 = PCURVE('',#62427,#62432); +#62427 = PLANE('',#62428); +#62428 = AXIS2_PLACEMENT_3D('',#62429,#62430,#62431); +#62429 = CARTESIAN_POINT('',(-0.525,0.E+000,0.E+000)); +#62430 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62431 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62432 = DEFINITIONAL_REPRESENTATION('',(#62433),#62437); +#62433 = LINE('',#62434,#62435); +#62434 = CARTESIAN_POINT('',(1.85,-0.985)); +#62435 = VECTOR('',#62436,1.); +#62436 = DIRECTION('',(-1.,0.E+000)); +#62437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62438 = ORIENTED_EDGE('',*,*,#62439,.F.); +#62439 = EDGE_CURVE('',#62440,#62412,#62442,.T.); +#62440 = VERTEX_POINT('',#62441); +#62441 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); +#62442 = SURFACE_CURVE('',#62443,(#62447,#62454),.PCURVE_S1.); +#62443 = LINE('',#62444,#62445); +#62444 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); +#62445 = VECTOR('',#62446,1.); +#62446 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62447 = PCURVE('',#45257,#62448); +#62448 = DEFINITIONAL_REPRESENTATION('',(#62449),#62453); #62449 = LINE('',#62450,#62451); -#62450 = CARTESIAN_POINT('',(3.,-1.225,-1.95)); +#62450 = CARTESIAN_POINT('',(0.32,-2.565)); #62451 = VECTOR('',#62452,1.); -#62452 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62453 = PCURVE('',#52045,#62454); -#62454 = DEFINITIONAL_REPRESENTATION('',(#62455),#62459); -#62455 = LINE('',#62456,#62457); -#62456 = CARTESIAN_POINT('',(0.85,-0.4)); -#62457 = VECTOR('',#62458,1.); -#62458 = DIRECTION('',(-1.,0.E+000)); -#62459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62460 = PCURVE('',#62461,#62466); -#62461 = CYLINDRICAL_SURFACE('',#62462,0.2); -#62462 = AXIS2_PLACEMENT_3D('',#62463,#62464,#62465); -#62463 = CARTESIAN_POINT('',(2.8,-1.225,-1.95)); -#62464 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62465 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62466 = DEFINITIONAL_REPRESENTATION('',(#62467),#62470); -#62467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62468,#62469),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#62468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62469 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#62470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62471 = ORIENTED_EDGE('',*,*,#62472,.F.); -#62472 = EDGE_CURVE('',#62473,#62446,#62475,.T.); -#62473 = VERTEX_POINT('',#62474); -#62474 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); -#62475 = SURFACE_CURVE('',#62476,(#62480,#62487),.PCURVE_S1.); -#62476 = LINE('',#62477,#62478); -#62477 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); -#62478 = VECTOR('',#62479,1.); -#62479 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62480 = PCURVE('',#52045,#62481); -#62481 = DEFINITIONAL_REPRESENTATION('',(#62482),#62486); -#62482 = LINE('',#62483,#62484); -#62483 = CARTESIAN_POINT('',(0.55,0.E+000)); -#62484 = VECTOR('',#62485,1.); -#62485 = DIRECTION('',(0.E+000,-1.)); -#62486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62487 = PCURVE('',#62488,#62493); -#62488 = PLANE('',#62489); -#62489 = AXIS2_PLACEMENT_3D('',#62490,#62491,#62492); -#62490 = CARTESIAN_POINT('',(0.E+000,-0.925,0.E+000)); -#62491 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62492 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62493 = DEFINITIONAL_REPRESENTATION('',(#62494),#62498); -#62494 = LINE('',#62495,#62496); -#62495 = CARTESIAN_POINT('',(3.,-2.35)); -#62496 = VECTOR('',#62497,1.); -#62497 = DIRECTION('',(0.E+000,1.)); -#62498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62499 = ORIENTED_EDGE('',*,*,#62500,.F.); -#62500 = EDGE_CURVE('',#61625,#62473,#62501,.T.); -#62501 = SURFACE_CURVE('',#62502,(#62506,#62513),.PCURVE_S1.); -#62502 = LINE('',#62503,#62504); -#62503 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); -#62504 = VECTOR('',#62505,1.); -#62505 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62506 = PCURVE('',#52045,#62507); -#62507 = DEFINITIONAL_REPRESENTATION('',(#62508),#62512); -#62508 = LINE('',#62509,#62510); -#62509 = CARTESIAN_POINT('',(0.242928932188,0.E+000)); -#62510 = VECTOR('',#62511,1.); -#62511 = DIRECTION('',(1.,0.E+000)); -#62512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62513 = PCURVE('',#42990,#62514); -#62514 = DEFINITIONAL_REPRESENTATION('',(#62515),#62519); -#62515 = LINE('',#62516,#62517); -#62516 = CARTESIAN_POINT('',(-3.,-0.617928932188)); -#62517 = VECTOR('',#62518,1.); -#62518 = DIRECTION('',(0.E+000,-1.)); -#62519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62520 = ORIENTED_EDGE('',*,*,#61624,.T.); -#62521 = ORIENTED_EDGE('',*,*,#62370,.T.); -#62522 = ORIENTED_EDGE('',*,*,#52029,.T.); -#62523 = ADVANCED_FACE('',(#62524),#52018,.T.); -#62524 = FACE_BOUND('',#62525,.T.); -#62525 = EDGE_LOOP('',(#62526,#62548,#62569,#62570)); -#62526 = ORIENTED_EDGE('',*,*,#62527,.T.); -#62527 = EDGE_CURVE('',#62395,#62528,#62530,.T.); -#62528 = VERTEX_POINT('',#62529); -#62529 = CARTESIAN_POINT('',(1.925,-1.225,-2.35)); -#62530 = SURFACE_CURVE('',#62531,(#62535,#62541),.PCURVE_S1.); -#62531 = LINE('',#62532,#62533); -#62532 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); -#62533 = VECTOR('',#62534,1.); -#62534 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62535 = PCURVE('',#52018,#62536); -#62536 = DEFINITIONAL_REPRESENTATION('',(#62537),#62540); -#62537 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62538,#62539),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); -#62538 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#62539 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); -#62540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62541 = PCURVE('',#62433,#62542); -#62542 = DEFINITIONAL_REPRESENTATION('',(#62543),#62547); -#62543 = LINE('',#62544,#62545); -#62544 = CARTESIAN_POINT('',(3.,-2.35)); -#62545 = VECTOR('',#62546,1.); -#62546 = DIRECTION('',(-1.,0.E+000)); -#62547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62548 = ORIENTED_EDGE('',*,*,#62549,.F.); -#62549 = EDGE_CURVE('',#51975,#62528,#62550,.T.); -#62550 = SURFACE_CURVE('',#62551,(#62556,#62562),.PCURVE_S1.); -#62551 = CIRCLE('',#62552,0.3); -#62552 = AXIS2_PLACEMENT_3D('',#62553,#62554,#62555); -#62553 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); -#62554 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62555 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62556 = PCURVE('',#52018,#62557); -#62557 = DEFINITIONAL_REPRESENTATION('',(#62558),#62561); -#62558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62559,#62560),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62559 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); -#62560 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); -#62561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62562 = PCURVE('',#51990,#62563); -#62563 = DEFINITIONAL_REPRESENTATION('',(#62564),#62568); -#62564 = CIRCLE('',#62565,0.3); -#62565 = AXIS2_PLACEMENT_2D('',#62566,#62567); -#62566 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62567 = DIRECTION('',(0.E+000,1.)); -#62568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62569 = ORIENTED_EDGE('',*,*,#52002,.F.); -#62570 = ORIENTED_EDGE('',*,*,#62394,.F.); -#62571 = ADVANCED_FACE('',(#62572),#62433,.T.); -#62572 = FACE_BOUND('',#62573,.F.); -#62573 = EDGE_LOOP('',(#62574,#62575,#62576,#62599,#62627,#62655)); -#62574 = ORIENTED_EDGE('',*,*,#62417,.F.); -#62575 = ORIENTED_EDGE('',*,*,#62527,.T.); -#62576 = ORIENTED_EDGE('',*,*,#62577,.F.); -#62577 = EDGE_CURVE('',#62578,#62528,#62580,.T.); -#62578 = VERTEX_POINT('',#62579); -#62579 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); -#62580 = SURFACE_CURVE('',#62581,(#62585,#62592),.PCURVE_S1.); -#62581 = LINE('',#62582,#62583); -#62582 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); -#62583 = VECTOR('',#62584,1.); -#62584 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62585 = PCURVE('',#62433,#62586); -#62586 = DEFINITIONAL_REPRESENTATION('',(#62587),#62591); -#62587 = LINE('',#62588,#62589); -#62588 = CARTESIAN_POINT('',(1.925,-1.95)); -#62589 = VECTOR('',#62590,1.); -#62590 = DIRECTION('',(0.E+000,-1.)); -#62591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62592 = PCURVE('',#51990,#62593); -#62593 = DEFINITIONAL_REPRESENTATION('',(#62594),#62598); -#62594 = LINE('',#62595,#62596); -#62595 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#62596 = VECTOR('',#62597,1.); -#62597 = DIRECTION('',(0.E+000,1.)); -#62598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62599 = ORIENTED_EDGE('',*,*,#62600,.F.); -#62600 = EDGE_CURVE('',#62601,#62578,#62603,.T.); -#62601 = VERTEX_POINT('',#62602); -#62602 = CARTESIAN_POINT('',(2.125,-1.225,-1.75)); -#62603 = SURFACE_CURVE('',#62604,(#62609,#62616),.PCURVE_S1.); -#62604 = CIRCLE('',#62605,0.2); -#62605 = AXIS2_PLACEMENT_3D('',#62606,#62607,#62608); -#62606 = CARTESIAN_POINT('',(2.125,-1.225,-1.95)); -#62607 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62608 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62609 = PCURVE('',#62433,#62610); -#62610 = DEFINITIONAL_REPRESENTATION('',(#62611),#62615); -#62611 = CIRCLE('',#62612,0.2); -#62612 = AXIS2_PLACEMENT_2D('',#62613,#62614); -#62613 = CARTESIAN_POINT('',(2.125,-1.95)); -#62614 = DIRECTION('',(0.E+000,1.)); -#62615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62616 = PCURVE('',#62617,#62622); -#62617 = CYLINDRICAL_SURFACE('',#62618,0.2); -#62618 = AXIS2_PLACEMENT_3D('',#62619,#62620,#62621); -#62619 = CARTESIAN_POINT('',(2.125,-1.225,-1.95)); -#62620 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62621 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62622 = DEFINITIONAL_REPRESENTATION('',(#62623),#62626); -#62623 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62624,#62625),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62624 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#62625 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62627 = ORIENTED_EDGE('',*,*,#62628,.F.); -#62628 = EDGE_CURVE('',#62629,#62601,#62631,.T.); -#62629 = VERTEX_POINT('',#62630); -#62630 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); -#62631 = SURFACE_CURVE('',#62632,(#62636,#62643),.PCURVE_S1.); -#62632 = LINE('',#62633,#62634); -#62633 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); -#62634 = VECTOR('',#62635,1.); -#62635 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62636 = PCURVE('',#62433,#62637); -#62637 = DEFINITIONAL_REPRESENTATION('',(#62638),#62642); -#62638 = LINE('',#62639,#62640); -#62639 = CARTESIAN_POINT('',(2.8,-1.75)); -#62640 = VECTOR('',#62641,1.); -#62641 = DIRECTION('',(-1.,0.E+000)); -#62642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62643 = PCURVE('',#62644,#62649); -#62644 = PLANE('',#62645); -#62645 = AXIS2_PLACEMENT_3D('',#62646,#62647,#62648); -#62646 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); -#62647 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62648 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62452 = DIRECTION('',(0.E+000,1.)); +#62453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62454 = PCURVE('',#62455,#62460); +#62455 = PLANE('',#62456); +#62456 = AXIS2_PLACEMENT_3D('',#62457,#62458,#62459); +#62457 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); +#62458 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#62459 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#62460 = DEFINITIONAL_REPRESENTATION('',(#62461),#62465); +#62461 = LINE('',#62462,#62463); +#62462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62463 = VECTOR('',#62464,1.); +#62464 = DIRECTION('',(0.E+000,1.)); +#62465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62466 = ORIENTED_EDGE('',*,*,#62467,.T.); +#62467 = EDGE_CURVE('',#62440,#62468,#62470,.T.); +#62468 = VERTEX_POINT('',#62469); +#62469 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); +#62470 = SURFACE_CURVE('',#62471,(#62475,#62482),.PCURVE_S1.); +#62471 = LINE('',#62472,#62473); +#62472 = CARTESIAN_POINT('',(-0.775,-0.985,-1.85)); +#62473 = VECTOR('',#62474,1.); +#62474 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62475 = PCURVE('',#45257,#62476); +#62476 = DEFINITIONAL_REPRESENTATION('',(#62477),#62481); +#62477 = LINE('',#62478,#62479); +#62478 = CARTESIAN_POINT('',(0.32,-2.565)); +#62479 = VECTOR('',#62480,1.); +#62480 = DIRECTION('',(-1.,0.E+000)); +#62481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62482 = PCURVE('',#62483,#62488); +#62483 = PLANE('',#62484); +#62484 = AXIS2_PLACEMENT_3D('',#62485,#62486,#62487); +#62485 = CARTESIAN_POINT('',(-0.775,0.E+000,0.E+000)); +#62486 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62487 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62488 = DEFINITIONAL_REPRESENTATION('',(#62489),#62493); +#62489 = LINE('',#62490,#62491); +#62490 = CARTESIAN_POINT('',(1.85,-0.985)); +#62491 = VECTOR('',#62492,1.); +#62492 = DIRECTION('',(-1.,0.E+000)); +#62493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62494 = ORIENTED_EDGE('',*,*,#62495,.T.); +#62495 = EDGE_CURVE('',#62468,#62496,#62498,.T.); +#62496 = VERTEX_POINT('',#62497); +#62497 = CARTESIAN_POINT('',(-1.175,-0.985,-1.71)); +#62498 = SURFACE_CURVE('',#62499,(#62503,#62510),.PCURVE_S1.); +#62499 = LINE('',#62500,#62501); +#62500 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); +#62501 = VECTOR('',#62502,1.); +#62502 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62503 = PCURVE('',#45257,#62504); +#62504 = DEFINITIONAL_REPRESENTATION('',(#62505),#62509); +#62505 = LINE('',#62506,#62507); +#62506 = CARTESIAN_POINT('',(0.18,-2.565)); +#62507 = VECTOR('',#62508,1.); +#62508 = DIRECTION('',(0.E+000,-1.)); +#62509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62510 = PCURVE('',#62511,#62516); +#62511 = PLANE('',#62512); +#62512 = AXIS2_PLACEMENT_3D('',#62513,#62514,#62515); +#62513 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62514 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62515 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62516 = DEFINITIONAL_REPRESENTATION('',(#62517),#62521); +#62517 = LINE('',#62518,#62519); +#62518 = CARTESIAN_POINT('',(0.E+000,-2.565)); +#62519 = VECTOR('',#62520,1.); +#62520 = DIRECTION('',(0.E+000,-1.)); +#62521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62522 = ORIENTED_EDGE('',*,*,#62523,.F.); +#62523 = EDGE_CURVE('',#62524,#62496,#62526,.T.); +#62524 = VERTEX_POINT('',#62525); +#62525 = CARTESIAN_POINT('',(-1.175,-0.985,-1.85)); +#62526 = SURFACE_CURVE('',#62527,(#62531,#62538),.PCURVE_S1.); +#62527 = LINE('',#62528,#62529); +#62528 = CARTESIAN_POINT('',(-1.175,-0.985,-1.85)); +#62529 = VECTOR('',#62530,1.); +#62530 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62531 = PCURVE('',#45257,#62532); +#62532 = DEFINITIONAL_REPRESENTATION('',(#62533),#62537); +#62533 = LINE('',#62534,#62535); +#62534 = CARTESIAN_POINT('',(0.32,-2.965)); +#62535 = VECTOR('',#62536,1.); +#62536 = DIRECTION('',(-1.,0.E+000)); +#62537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62538 = PCURVE('',#62539,#62544); +#62539 = PLANE('',#62540); +#62540 = AXIS2_PLACEMENT_3D('',#62541,#62542,#62543); +#62541 = CARTESIAN_POINT('',(-1.175,0.E+000,0.E+000)); +#62542 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62543 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62544 = DEFINITIONAL_REPRESENTATION('',(#62545),#62549); +#62545 = LINE('',#62546,#62547); +#62546 = CARTESIAN_POINT('',(1.85,-0.985)); +#62547 = VECTOR('',#62548,1.); +#62548 = DIRECTION('',(-1.,0.E+000)); +#62549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62550 = ORIENTED_EDGE('',*,*,#62551,.F.); +#62551 = EDGE_CURVE('',#62552,#62524,#62554,.T.); +#62552 = VERTEX_POINT('',#62553); +#62553 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); +#62554 = SURFACE_CURVE('',#62555,(#62559,#62566),.PCURVE_S1.); +#62555 = LINE('',#62556,#62557); +#62556 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); +#62557 = VECTOR('',#62558,1.); +#62558 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62559 = PCURVE('',#45257,#62560); +#62560 = DEFINITIONAL_REPRESENTATION('',(#62561),#62565); +#62561 = LINE('',#62562,#62563); +#62562 = CARTESIAN_POINT('',(0.32,-3.215)); +#62563 = VECTOR('',#62564,1.); +#62564 = DIRECTION('',(0.E+000,1.)); +#62565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62566 = PCURVE('',#62567,#62572); +#62567 = PLANE('',#62568); +#62568 = AXIS2_PLACEMENT_3D('',#62569,#62570,#62571); +#62569 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); +#62570 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#62571 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#62572 = DEFINITIONAL_REPRESENTATION('',(#62573),#62577); +#62573 = LINE('',#62574,#62575); +#62574 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62575 = VECTOR('',#62576,1.); +#62576 = DIRECTION('',(0.E+000,1.)); +#62577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62578 = ORIENTED_EDGE('',*,*,#62579,.T.); +#62579 = EDGE_CURVE('',#62552,#62580,#62582,.T.); +#62580 = VERTEX_POINT('',#62581); +#62581 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); +#62582 = SURFACE_CURVE('',#62583,(#62587,#62594),.PCURVE_S1.); +#62583 = LINE('',#62584,#62585); +#62584 = CARTESIAN_POINT('',(-1.425,-0.985,-1.85)); +#62585 = VECTOR('',#62586,1.); +#62586 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62587 = PCURVE('',#45257,#62588); +#62588 = DEFINITIONAL_REPRESENTATION('',(#62589),#62593); +#62589 = LINE('',#62590,#62591); +#62590 = CARTESIAN_POINT('',(0.32,-3.215)); +#62591 = VECTOR('',#62592,1.); +#62592 = DIRECTION('',(-1.,0.E+000)); +#62593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62594 = PCURVE('',#62595,#62600); +#62595 = PLANE('',#62596); +#62596 = AXIS2_PLACEMENT_3D('',#62597,#62598,#62599); +#62597 = CARTESIAN_POINT('',(-1.425,0.E+000,0.E+000)); +#62598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62599 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62600 = DEFINITIONAL_REPRESENTATION('',(#62601),#62605); +#62601 = LINE('',#62602,#62603); +#62602 = CARTESIAN_POINT('',(1.85,-0.985)); +#62603 = VECTOR('',#62604,1.); +#62604 = DIRECTION('',(-1.,0.E+000)); +#62605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62606 = ORIENTED_EDGE('',*,*,#62607,.T.); +#62607 = EDGE_CURVE('',#62580,#62608,#62610,.T.); +#62608 = VERTEX_POINT('',#62609); +#62609 = CARTESIAN_POINT('',(-1.79,-0.985,-1.71)); +#62610 = SURFACE_CURVE('',#62611,(#62615,#62622),.PCURVE_S1.); +#62611 = LINE('',#62612,#62613); +#62612 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); +#62613 = VECTOR('',#62614,1.); +#62614 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62615 = PCURVE('',#45257,#62616); +#62616 = DEFINITIONAL_REPRESENTATION('',(#62617),#62621); +#62617 = LINE('',#62618,#62619); +#62618 = CARTESIAN_POINT('',(0.18,-3.215)); +#62619 = VECTOR('',#62620,1.); +#62620 = DIRECTION('',(0.E+000,-1.)); +#62621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62622 = PCURVE('',#62623,#62628); +#62623 = PLANE('',#62624); +#62624 = AXIS2_PLACEMENT_3D('',#62625,#62626,#62627); +#62625 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62626 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62627 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62628 = DEFINITIONAL_REPRESENTATION('',(#62629),#62633); +#62629 = LINE('',#62630,#62631); +#62630 = CARTESIAN_POINT('',(0.E+000,-3.215)); +#62631 = VECTOR('',#62632,1.); +#62632 = DIRECTION('',(0.E+000,-1.)); +#62633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62634 = ORIENTED_EDGE('',*,*,#62635,.F.); +#62635 = EDGE_CURVE('',#61944,#62608,#62636,.T.); +#62636 = SURFACE_CURVE('',#62637,(#62641,#62648),.PCURVE_S1.); +#62637 = LINE('',#62638,#62639); +#62638 = CARTESIAN_POINT('',(-1.79,-0.985,-1.53)); +#62639 = VECTOR('',#62640,1.); +#62640 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62641 = PCURVE('',#45257,#62642); +#62642 = DEFINITIONAL_REPRESENTATION('',(#62643),#62647); +#62643 = LINE('',#62644,#62645); +#62644 = CARTESIAN_POINT('',(0.E+000,-3.58)); +#62645 = VECTOR('',#62646,1.); +#62646 = DIRECTION('',(1.,0.E+000)); +#62647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62648 = PCURVE('',#44262,#62649); #62649 = DEFINITIONAL_REPRESENTATION('',(#62650),#62654); #62650 = LINE('',#62651,#62652); -#62651 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62651 = CARTESIAN_POINT('',(0.32,-0.24)); #62652 = VECTOR('',#62653,1.); #62653 = DIRECTION('',(1.,0.E+000)); #62654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62655 = ORIENTED_EDGE('',*,*,#62656,.F.); -#62656 = EDGE_CURVE('',#62418,#62629,#62657,.T.); -#62657 = SURFACE_CURVE('',#62658,(#62663,#62670),.PCURVE_S1.); -#62658 = CIRCLE('',#62659,0.2); -#62659 = AXIS2_PLACEMENT_3D('',#62660,#62661,#62662); -#62660 = CARTESIAN_POINT('',(2.8,-1.225,-1.95)); -#62661 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62662 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62663 = PCURVE('',#62433,#62664); -#62664 = DEFINITIONAL_REPRESENTATION('',(#62665),#62669); -#62665 = CIRCLE('',#62666,0.2); -#62666 = AXIS2_PLACEMENT_2D('',#62667,#62668); -#62667 = CARTESIAN_POINT('',(2.8,-1.95)); -#62668 = DIRECTION('',(1.,0.E+000)); -#62669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62670 = PCURVE('',#62461,#62671); -#62671 = DEFINITIONAL_REPRESENTATION('',(#62672),#62675); -#62672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62673,#62674),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62674 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#62675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62676 = ADVANCED_FACE('',(#62677),#62691,.T.); -#62677 = FACE_BOUND('',#62678,.F.); -#62678 = EDGE_LOOP('',(#62679,#62709,#62731,#62754,#62782,#62810)); -#62679 = ORIENTED_EDGE('',*,*,#62680,.F.); -#62680 = EDGE_CURVE('',#62681,#62683,#62685,.T.); -#62681 = VERTEX_POINT('',#62682); -#62682 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); -#62683 = VERTEX_POINT('',#62684); -#62684 = CARTESIAN_POINT('',(-1.925,-1.225,-1.95)); -#62685 = SURFACE_CURVE('',#62686,(#62690,#62702),.PCURVE_S1.); -#62686 = LINE('',#62687,#62688); -#62687 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); -#62688 = VECTOR('',#62689,1.); -#62689 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62690 = PCURVE('',#62691,#62696); -#62691 = PLANE('',#62692); -#62692 = AXIS2_PLACEMENT_3D('',#62693,#62694,#62695); -#62693 = CARTESIAN_POINT('',(0.E+000,-1.225,0.E+000)); -#62694 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62695 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62696 = DEFINITIONAL_REPRESENTATION('',(#62697),#62701); -#62697 = LINE('',#62698,#62699); -#62698 = CARTESIAN_POINT('',(-1.925,-2.35)); -#62699 = VECTOR('',#62700,1.); -#62700 = DIRECTION('',(0.E+000,1.)); -#62701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62702 = PCURVE('',#51934,#62703); -#62703 = DEFINITIONAL_REPRESENTATION('',(#62704),#62708); -#62704 = LINE('',#62705,#62706); -#62705 = CARTESIAN_POINT('',(0.5,0.E+000)); -#62706 = VECTOR('',#62707,1.); -#62707 = DIRECTION('',(0.E+000,-1.)); -#62708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62709 = ORIENTED_EDGE('',*,*,#62710,.T.); -#62710 = EDGE_CURVE('',#62681,#62711,#62713,.T.); -#62711 = VERTEX_POINT('',#62712); -#62712 = CARTESIAN_POINT('',(-3.,-1.225,-2.35)); -#62713 = SURFACE_CURVE('',#62714,(#62718,#62725),.PCURVE_S1.); -#62714 = LINE('',#62715,#62716); -#62715 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); -#62716 = VECTOR('',#62717,1.); -#62717 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62718 = PCURVE('',#62691,#62719); -#62719 = DEFINITIONAL_REPRESENTATION('',(#62720),#62724); -#62720 = LINE('',#62721,#62722); -#62721 = CARTESIAN_POINT('',(-1.925,-2.35)); -#62722 = VECTOR('',#62723,1.); -#62723 = DIRECTION('',(-1.,0.E+000)); -#62724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62725 = PCURVE('',#51907,#62726); -#62726 = DEFINITIONAL_REPRESENTATION('',(#62727),#62730); -#62727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62728,#62729),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); -#62728 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#62729 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); -#62730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62731 = ORIENTED_EDGE('',*,*,#62732,.F.); -#62732 = EDGE_CURVE('',#62733,#62711,#62735,.T.); -#62733 = VERTEX_POINT('',#62734); -#62734 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); -#62735 = SURFACE_CURVE('',#62736,(#62740,#62747),.PCURVE_S1.); -#62736 = LINE('',#62737,#62738); -#62737 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); -#62738 = VECTOR('',#62739,1.); -#62739 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62740 = PCURVE('',#62691,#62741); -#62741 = DEFINITIONAL_REPRESENTATION('',(#62742),#62746); -#62742 = LINE('',#62743,#62744); -#62743 = CARTESIAN_POINT('',(-3.,-1.95)); -#62744 = VECTOR('',#62745,1.); -#62745 = DIRECTION('',(0.E+000,-1.)); -#62746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62747 = PCURVE('',#51879,#62748); -#62748 = DEFINITIONAL_REPRESENTATION('',(#62749),#62753); -#62749 = LINE('',#62750,#62751); -#62750 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#62751 = VECTOR('',#62752,1.); -#62752 = DIRECTION('',(0.E+000,1.)); -#62753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62754 = ORIENTED_EDGE('',*,*,#62755,.F.); -#62755 = EDGE_CURVE('',#62756,#62733,#62758,.T.); -#62756 = VERTEX_POINT('',#62757); -#62757 = CARTESIAN_POINT('',(-2.8,-1.225,-1.75)); -#62758 = SURFACE_CURVE('',#62759,(#62764,#62771),.PCURVE_S1.); -#62759 = CIRCLE('',#62760,0.2); -#62760 = AXIS2_PLACEMENT_3D('',#62761,#62762,#62763); -#62761 = CARTESIAN_POINT('',(-2.8,-1.225,-1.95)); -#62762 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62763 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62764 = PCURVE('',#62691,#62765); -#62765 = DEFINITIONAL_REPRESENTATION('',(#62766),#62770); -#62766 = CIRCLE('',#62767,0.2); -#62767 = AXIS2_PLACEMENT_2D('',#62768,#62769); -#62768 = CARTESIAN_POINT('',(-2.8,-1.95)); -#62769 = DIRECTION('',(0.E+000,1.)); -#62770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62771 = PCURVE('',#62772,#62777); -#62772 = CYLINDRICAL_SURFACE('',#62773,0.2); -#62773 = AXIS2_PLACEMENT_3D('',#62774,#62775,#62776); -#62774 = CARTESIAN_POINT('',(-2.8,-1.225,-1.95)); -#62775 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62776 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62777 = DEFINITIONAL_REPRESENTATION('',(#62778),#62781); -#62778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62779,#62780),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62779 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#62780 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62782 = ORIENTED_EDGE('',*,*,#62783,.F.); -#62783 = EDGE_CURVE('',#62784,#62756,#62786,.T.); -#62784 = VERTEX_POINT('',#62785); -#62785 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); -#62786 = SURFACE_CURVE('',#62787,(#62791,#62798),.PCURVE_S1.); -#62787 = LINE('',#62788,#62789); -#62788 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); -#62789 = VECTOR('',#62790,1.); -#62790 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62791 = PCURVE('',#62691,#62792); -#62792 = DEFINITIONAL_REPRESENTATION('',(#62793),#62797); -#62793 = LINE('',#62794,#62795); -#62794 = CARTESIAN_POINT('',(-2.125,-1.75)); -#62795 = VECTOR('',#62796,1.); -#62796 = DIRECTION('',(-1.,0.E+000)); -#62797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62798 = PCURVE('',#62799,#62804); -#62799 = PLANE('',#62800); -#62800 = AXIS2_PLACEMENT_3D('',#62801,#62802,#62803); -#62801 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); -#62802 = DIRECTION('',(0.E+000,0.E+000,1.)); -#62803 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62655 = ORIENTED_EDGE('',*,*,#61943,.F.); +#62656 = ORIENTED_EDGE('',*,*,#45241,.T.); +#62657 = ORIENTED_EDGE('',*,*,#62658,.T.); +#62658 = EDGE_CURVE('',#45214,#62659,#62661,.T.); +#62659 = VERTEX_POINT('',#62660); +#62660 = CARTESIAN_POINT('',(1.425,-0.985,-1.71)); +#62661 = SURFACE_CURVE('',#62662,(#62666,#62673),.PCURVE_S1.); +#62662 = LINE('',#62663,#62664); +#62663 = CARTESIAN_POINT('',(1.79,-0.985,-1.71)); +#62664 = VECTOR('',#62665,1.); +#62665 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62666 = PCURVE('',#45257,#62667); +#62667 = DEFINITIONAL_REPRESENTATION('',(#62668),#62672); +#62668 = LINE('',#62669,#62670); +#62669 = CARTESIAN_POINT('',(0.18,0.E+000)); +#62670 = VECTOR('',#62671,1.); +#62671 = DIRECTION('',(0.E+000,-1.)); +#62672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62673 = PCURVE('',#45229,#62674); +#62674 = DEFINITIONAL_REPRESENTATION('',(#62675),#62679); +#62675 = LINE('',#62676,#62677); +#62676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62677 = VECTOR('',#62678,1.); +#62678 = DIRECTION('',(0.E+000,-1.)); +#62679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62680 = ORIENTED_EDGE('',*,*,#62681,.F.); +#62681 = EDGE_CURVE('',#62682,#62659,#62684,.T.); +#62682 = VERTEX_POINT('',#62683); +#62683 = CARTESIAN_POINT('',(1.425,-0.985,-1.85)); +#62684 = SURFACE_CURVE('',#62685,(#62689,#62696),.PCURVE_S1.); +#62685 = LINE('',#62686,#62687); +#62686 = CARTESIAN_POINT('',(1.425,-0.985,-1.85)); +#62687 = VECTOR('',#62688,1.); +#62688 = DIRECTION('',(0.E+000,0.E+000,1.)); +#62689 = PCURVE('',#45257,#62690); +#62690 = DEFINITIONAL_REPRESENTATION('',(#62691),#62695); +#62691 = LINE('',#62692,#62693); +#62692 = CARTESIAN_POINT('',(0.32,-0.365)); +#62693 = VECTOR('',#62694,1.); +#62694 = DIRECTION('',(-1.,0.E+000)); +#62695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62696 = PCURVE('',#62697,#62702); +#62697 = PLANE('',#62698); +#62698 = AXIS2_PLACEMENT_3D('',#62699,#62700,#62701); +#62699 = CARTESIAN_POINT('',(1.425,0.E+000,0.E+000)); +#62700 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62701 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62702 = DEFINITIONAL_REPRESENTATION('',(#62703),#62707); +#62703 = LINE('',#62704,#62705); +#62704 = CARTESIAN_POINT('',(1.85,-0.985)); +#62705 = VECTOR('',#62706,1.); +#62706 = DIRECTION('',(-1.,0.E+000)); +#62707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62708 = ORIENTED_EDGE('',*,*,#62709,.F.); +#62709 = EDGE_CURVE('',#62130,#62682,#62710,.T.); +#62710 = SURFACE_CURVE('',#62711,(#62715,#62722),.PCURVE_S1.); +#62711 = LINE('',#62712,#62713); +#62712 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); +#62713 = VECTOR('',#62714,1.); +#62714 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62715 = PCURVE('',#45257,#62716); +#62716 = DEFINITIONAL_REPRESENTATION('',(#62717),#62721); +#62717 = LINE('',#62718,#62719); +#62718 = CARTESIAN_POINT('',(0.32,-0.615)); +#62719 = VECTOR('',#62720,1.); +#62720 = DIRECTION('',(0.E+000,1.)); +#62721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62722 = PCURVE('',#62723,#62728); +#62723 = PLANE('',#62724); +#62724 = AXIS2_PLACEMENT_3D('',#62725,#62726,#62727); +#62725 = CARTESIAN_POINT('',(1.175,-0.985,-1.85)); +#62726 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#62727 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#62728 = DEFINITIONAL_REPRESENTATION('',(#62729),#62733); +#62729 = LINE('',#62730,#62731); +#62730 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62731 = VECTOR('',#62732,1.); +#62732 = DIRECTION('',(0.E+000,1.)); +#62733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62734 = ADVANCED_FACE('',(#62735),#62147,.T.); +#62735 = FACE_BOUND('',#62736,.F.); +#62736 = EDGE_LOOP('',(#62737,#62767,#62788,#62789)); +#62737 = ORIENTED_EDGE('',*,*,#62738,.F.); +#62738 = EDGE_CURVE('',#62739,#62741,#62743,.T.); +#62739 = VERTEX_POINT('',#62740); +#62740 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); +#62741 = VERTEX_POINT('',#62742); +#62742 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); +#62743 = SURFACE_CURVE('',#62744,(#62748,#62755),.PCURVE_S1.); +#62744 = LINE('',#62745,#62746); +#62745 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); +#62746 = VECTOR('',#62747,1.); +#62747 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62748 = PCURVE('',#62147,#62749); +#62749 = DEFINITIONAL_REPRESENTATION('',(#62750),#62754); +#62750 = LINE('',#62751,#62752); +#62751 = CARTESIAN_POINT('',(1.71,-1.105)); +#62752 = VECTOR('',#62753,1.); +#62753 = DIRECTION('',(1.,0.E+000)); +#62754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62755 = PCURVE('',#62756,#62761); +#62756 = PLANE('',#62757); +#62757 = AXIS2_PLACEMENT_3D('',#62758,#62759,#62760); +#62758 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#62759 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62760 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62761 = DEFINITIONAL_REPRESENTATION('',(#62762),#62766); +#62762 = LINE('',#62763,#62764); +#62763 = CARTESIAN_POINT('',(0.E+000,-0.615)); +#62764 = VECTOR('',#62765,1.); +#62765 = DIRECTION('',(1.,0.E+000)); +#62766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62767 = ORIENTED_EDGE('',*,*,#62768,.F.); +#62768 = EDGE_CURVE('',#62132,#62739,#62769,.T.); +#62769 = SURFACE_CURVE('',#62770,(#62774,#62781),.PCURVE_S1.); +#62770 = LINE('',#62771,#62772); +#62771 = CARTESIAN_POINT('',(1.175,-0.985,-1.71)); +#62772 = VECTOR('',#62773,1.); +#62773 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62774 = PCURVE('',#62147,#62775); +#62775 = DEFINITIONAL_REPRESENTATION('',(#62776),#62780); +#62776 = LINE('',#62777,#62778); +#62777 = CARTESIAN_POINT('',(1.71,-0.985)); +#62778 = VECTOR('',#62779,1.); +#62779 = DIRECTION('',(0.E+000,-1.)); +#62780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62781 = PCURVE('',#62175,#62782); +#62782 = DEFINITIONAL_REPRESENTATION('',(#62783),#62787); +#62783 = LINE('',#62784,#62785); +#62784 = CARTESIAN_POINT('',(0.E+000,-0.615)); +#62785 = VECTOR('',#62786,1.); +#62786 = DIRECTION('',(1.,0.E+000)); +#62787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62788 = ORIENTED_EDGE('',*,*,#62129,.F.); +#62789 = ORIENTED_EDGE('',*,*,#62790,.F.); +#62790 = EDGE_CURVE('',#62741,#62130,#62791,.T.); +#62791 = SURFACE_CURVE('',#62792,(#62796,#62803),.PCURVE_S1.); +#62792 = LINE('',#62793,#62794); +#62793 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); +#62794 = VECTOR('',#62795,1.); +#62795 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#62796 = PCURVE('',#62147,#62797); +#62797 = DEFINITIONAL_REPRESENTATION('',(#62798),#62802); +#62798 = LINE('',#62799,#62800); +#62799 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#62800 = VECTOR('',#62801,1.); +#62801 = DIRECTION('',(-0.258819045102,0.965925826289)); +#62802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62803 = PCURVE('',#62723,#62804); #62804 = DEFINITIONAL_REPRESENTATION('',(#62805),#62809); #62805 = LINE('',#62806,#62807); -#62806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#62806 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); #62807 = VECTOR('',#62808,1.); -#62808 = DIRECTION('',(1.,0.E+000)); +#62808 = DIRECTION('',(-1.,0.E+000)); #62809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62810 = ORIENTED_EDGE('',*,*,#62811,.F.); -#62811 = EDGE_CURVE('',#62683,#62784,#62812,.T.); -#62812 = SURFACE_CURVE('',#62813,(#62818,#62825),.PCURVE_S1.); -#62813 = CIRCLE('',#62814,0.2); -#62814 = AXIS2_PLACEMENT_3D('',#62815,#62816,#62817); -#62815 = CARTESIAN_POINT('',(-2.125,-1.225,-1.95)); -#62816 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62817 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62818 = PCURVE('',#62691,#62819); -#62819 = DEFINITIONAL_REPRESENTATION('',(#62820),#62824); -#62820 = CIRCLE('',#62821,0.2); -#62821 = AXIS2_PLACEMENT_2D('',#62822,#62823); -#62822 = CARTESIAN_POINT('',(-2.125,-1.95)); -#62823 = DIRECTION('',(1.,0.E+000)); -#62824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62825 = PCURVE('',#62826,#62831); -#62826 = CYLINDRICAL_SURFACE('',#62827,0.2); -#62827 = AXIS2_PLACEMENT_3D('',#62828,#62829,#62830); -#62828 = CARTESIAN_POINT('',(-2.125,-1.225,-1.95)); -#62829 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#62830 = DIRECTION('',(1.,0.E+000,0.E+000)); -#62831 = DEFINITIONAL_REPRESENTATION('',(#62832),#62835); -#62832 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62833,#62834),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#62833 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62834 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#62810 = ADVANCED_FACE('',(#62811),#62825,.T.); +#62811 = FACE_BOUND('',#62812,.F.); +#62812 = EDGE_LOOP('',(#62813,#62843,#62871,#62894,#62917)); +#62813 = ORIENTED_EDGE('',*,*,#62814,.T.); +#62814 = EDGE_CURVE('',#62815,#62817,#62819,.T.); +#62815 = VERTEX_POINT('',#62816); +#62816 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); +#62817 = VERTEX_POINT('',#62818); +#62818 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); +#62819 = SURFACE_CURVE('',#62820,(#62824,#62836),.PCURVE_S1.); +#62820 = LINE('',#62821,#62822); +#62821 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); +#62822 = VECTOR('',#62823,1.); +#62823 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62824 = PCURVE('',#62825,#62830); +#62825 = PLANE('',#62826); +#62826 = AXIS2_PLACEMENT_3D('',#62827,#62828,#62829); +#62827 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#62828 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62829 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62830 = DEFINITIONAL_REPRESENTATION('',(#62831),#62835); +#62831 = LINE('',#62832,#62833); +#62832 = CARTESIAN_POINT('',(0.E+000,-3.215)); +#62833 = VECTOR('',#62834,1.); +#62834 = DIRECTION('',(1.,0.E+000)); #62835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#62836 = ADVANCED_FACE('',(#62837),#51990,.T.); -#62837 = FACE_BOUND('',#62838,.F.); -#62838 = EDGE_LOOP('',(#62839,#62862,#62885,#62905,#62906,#62907,#62908, - #62929)); -#62839 = ORIENTED_EDGE('',*,*,#62840,.F.); -#62840 = EDGE_CURVE('',#62841,#42975,#62843,.T.); -#62841 = VERTEX_POINT('',#62842); -#62842 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); -#62843 = SURFACE_CURVE('',#62844,(#62848,#62855),.PCURVE_S1.); -#62844 = LINE('',#62845,#62846); -#62845 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); -#62846 = VECTOR('',#62847,1.); -#62847 = DIRECTION('',(4.440892098502E-014,1.,0.E+000)); -#62848 = PCURVE('',#51990,#62849); -#62849 = DEFINITIONAL_REPRESENTATION('',(#62850),#62854); -#62850 = LINE('',#62851,#62852); -#62851 = CARTESIAN_POINT('',(0.3,0.E+000)); -#62852 = VECTOR('',#62853,1.); -#62853 = DIRECTION('',(1.,0.E+000)); -#62854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62855 = PCURVE('',#42990,#62856); -#62856 = DEFINITIONAL_REPRESENTATION('',(#62857),#62861); -#62857 = LINE('',#62858,#62859); -#62858 = CARTESIAN_POINT('',(-1.925,-0.925)); -#62859 = VECTOR('',#62860,1.); -#62860 = DIRECTION('',(-4.440892098502E-014,1.)); -#62861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62862 = ORIENTED_EDGE('',*,*,#62863,.F.); -#62863 = EDGE_CURVE('',#62864,#62841,#62866,.T.); -#62864 = VERTEX_POINT('',#62865); -#62865 = CARTESIAN_POINT('',(1.925,-0.925,-1.95)); -#62866 = SURFACE_CURVE('',#62867,(#62871,#62878),.PCURVE_S1.); -#62867 = LINE('',#62868,#62869); -#62868 = CARTESIAN_POINT('',(1.925,-0.925,-1.95)); -#62869 = VECTOR('',#62870,1.); -#62870 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62871 = PCURVE('',#51990,#62872); -#62872 = DEFINITIONAL_REPRESENTATION('',(#62873),#62877); -#62873 = LINE('',#62874,#62875); -#62874 = CARTESIAN_POINT('',(0.3,-0.4)); -#62875 = VECTOR('',#62876,1.); -#62876 = DIRECTION('',(0.E+000,1.)); -#62877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62878 = PCURVE('',#62488,#62879); -#62879 = DEFINITIONAL_REPRESENTATION('',(#62880),#62884); -#62880 = LINE('',#62881,#62882); -#62881 = CARTESIAN_POINT('',(1.925,-1.95)); -#62882 = VECTOR('',#62883,1.); -#62883 = DIRECTION('',(0.E+000,-1.)); -#62884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62885 = ORIENTED_EDGE('',*,*,#62886,.F.); -#62886 = EDGE_CURVE('',#62578,#62864,#62887,.T.); -#62887 = SURFACE_CURVE('',#62888,(#62892,#62899),.PCURVE_S1.); -#62888 = LINE('',#62889,#62890); -#62889 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); -#62890 = VECTOR('',#62891,1.); -#62891 = DIRECTION('',(0.E+000,1.,0.E+000)); -#62892 = PCURVE('',#51990,#62893); -#62893 = DEFINITIONAL_REPRESENTATION('',(#62894),#62898); -#62894 = LINE('',#62895,#62896); -#62895 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#62896 = VECTOR('',#62897,1.); -#62897 = DIRECTION('',(1.,0.E+000)); -#62898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62899 = PCURVE('',#62617,#62900); -#62900 = DEFINITIONAL_REPRESENTATION('',(#62901),#62904); -#62901 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#62902,#62903),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#62902 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#62903 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#62904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62905 = ORIENTED_EDGE('',*,*,#62577,.T.); -#62906 = ORIENTED_EDGE('',*,*,#62549,.F.); -#62907 = ORIENTED_EDGE('',*,*,#51974,.T.); -#62908 = ORIENTED_EDGE('',*,*,#62909,.F.); -#62909 = EDGE_CURVE('',#62088,#51947,#62910,.T.); -#62910 = SURFACE_CURVE('',#62911,(#62915,#62922),.PCURVE_S1.); -#62911 = LINE('',#62912,#62913); -#62912 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); -#62913 = VECTOR('',#62914,1.); -#62914 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#62915 = PCURVE('',#51990,#62916); -#62916 = DEFINITIONAL_REPRESENTATION('',(#62917),#62921); -#62917 = LINE('',#62918,#62919); -#62918 = CARTESIAN_POINT('',(0.5,0.E+000)); -#62919 = VECTOR('',#62920,1.); -#62920 = DIRECTION('',(0.E+000,1.)); -#62921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62922 = PCURVE('',#51962,#62923); -#62923 = DEFINITIONAL_REPRESENTATION('',(#62924),#62928); -#62924 = LINE('',#62925,#62926); -#62925 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#62926 = VECTOR('',#62927,1.); -#62927 = DIRECTION('',(0.E+000,1.)); -#62928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62929 = ORIENTED_EDGE('',*,*,#62087,.F.); -#62930 = ADVANCED_FACE('',(#62931),#47656,.F.); -#62931 = FACE_BOUND('',#62932,.F.); -#62932 = EDGE_LOOP('',(#62933,#62934,#62935,#62956)); -#62933 = ORIENTED_EDGE('',*,*,#47642,.F.); -#62934 = ORIENTED_EDGE('',*,*,#51708,.T.); -#62935 = ORIENTED_EDGE('',*,*,#62936,.T.); -#62936 = EDGE_CURVE('',#51686,#52163,#62937,.T.); -#62937 = SURFACE_CURVE('',#62938,(#62942,#62949),.PCURVE_S1.); -#62938 = LINE('',#62939,#62940); -#62939 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); -#62940 = VECTOR('',#62941,1.); -#62941 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62942 = PCURVE('',#47656,#62943); -#62943 = DEFINITIONAL_REPRESENTATION('',(#62944),#62948); -#62944 = LINE('',#62945,#62946); -#62945 = CARTESIAN_POINT('',(-1.21,0.92)); -#62946 = VECTOR('',#62947,1.); -#62947 = DIRECTION('',(1.,0.E+000)); -#62948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62949 = PCURVE('',#43400,#62950); -#62950 = DEFINITIONAL_REPRESENTATION('',(#62951),#62955); -#62951 = LINE('',#62952,#62953); -#62952 = CARTESIAN_POINT('',(1.885,0.E+000)); -#62953 = VECTOR('',#62954,1.); -#62954 = DIRECTION('',(1.,0.E+000)); -#62955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62956 = ORIENTED_EDGE('',*,*,#52162,.T.); -#62957 = ADVANCED_FACE('',(#62958),#51617,.F.); -#62958 = FACE_BOUND('',#62959,.F.); -#62959 = EDGE_LOOP('',(#62960,#62981,#62982)); -#62960 = ORIENTED_EDGE('',*,*,#62961,.T.); -#62961 = EDGE_CURVE('',#61545,#51602,#62962,.T.); -#62962 = SURFACE_CURVE('',#62963,(#62967,#62974),.PCURVE_S1.); -#62963 = LINE('',#62964,#62965); -#62964 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); -#62965 = VECTOR('',#62966,1.); -#62966 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62967 = PCURVE('',#51617,#62968); -#62968 = DEFINITIONAL_REPRESENTATION('',(#62969),#62973); -#62969 = LINE('',#62970,#62971); -#62970 = CARTESIAN_POINT('',(-1.339903810568,0.5)); -#62971 = VECTOR('',#62972,1.); -#62972 = DIRECTION('',(1.,0.E+000)); -#62973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62974 = PCURVE('',#51645,#62975); -#62975 = DEFINITIONAL_REPRESENTATION('',(#62976),#62980); +#62836 = PCURVE('',#62595,#62837); +#62837 = DEFINITIONAL_REPRESENTATION('',(#62838),#62842); +#62838 = LINE('',#62839,#62840); +#62839 = CARTESIAN_POINT('',(1.71,-1.105)); +#62840 = VECTOR('',#62841,1.); +#62841 = DIRECTION('',(1.,0.E+000)); +#62842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62843 = ORIENTED_EDGE('',*,*,#62844,.T.); +#62844 = EDGE_CURVE('',#62817,#62845,#62847,.T.); +#62845 = VERTEX_POINT('',#62846); +#62846 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); +#62847 = SURFACE_CURVE('',#62848,(#62852,#62859),.PCURVE_S1.); +#62848 = LINE('',#62849,#62850); +#62849 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); +#62850 = VECTOR('',#62851,1.); +#62851 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62852 = PCURVE('',#62825,#62853); +#62853 = DEFINITIONAL_REPRESENTATION('',(#62854),#62858); +#62854 = LINE('',#62855,#62856); +#62855 = CARTESIAN_POINT('',(0.172153903092,-3.215)); +#62856 = VECTOR('',#62857,1.); +#62857 = DIRECTION('',(1.,0.E+000)); +#62858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62859 = PCURVE('',#62860,#62865); +#62860 = PLANE('',#62861); +#62861 = AXIS2_PLACEMENT_3D('',#62862,#62863,#62864); +#62862 = CARTESIAN_POINT('',(-1.425,0.E+000,0.E+000)); +#62863 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62864 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62865 = DEFINITIONAL_REPRESENTATION('',(#62866),#62870); +#62866 = LINE('',#62867,#62868); +#62867 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#62868 = VECTOR('',#62869,1.); +#62869 = DIRECTION('',(1.,0.E+000)); +#62870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62871 = ORIENTED_EDGE('',*,*,#62872,.T.); +#62872 = EDGE_CURVE('',#62845,#62873,#62875,.T.); +#62873 = VERTEX_POINT('',#62874); +#62874 = CARTESIAN_POINT('',(-1.79,-1.105,-2.35)); +#62875 = SURFACE_CURVE('',#62876,(#62880,#62887),.PCURVE_S1.); +#62876 = LINE('',#62877,#62878); +#62877 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); +#62878 = VECTOR('',#62879,1.); +#62879 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62880 = PCURVE('',#62825,#62881); +#62881 = DEFINITIONAL_REPRESENTATION('',(#62882),#62886); +#62882 = LINE('',#62883,#62884); +#62883 = CARTESIAN_POINT('',(0.64,-3.215)); +#62884 = VECTOR('',#62885,1.); +#62885 = DIRECTION('',(0.E+000,-1.)); +#62886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62887 = PCURVE('',#45173,#62888); +#62888 = DEFINITIONAL_REPRESENTATION('',(#62889),#62893); +#62889 = LINE('',#62890,#62891); +#62890 = CARTESIAN_POINT('',(-1.425,-1.105)); +#62891 = VECTOR('',#62892,1.); +#62892 = DIRECTION('',(-1.,0.E+000)); +#62893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62894 = ORIENTED_EDGE('',*,*,#62895,.F.); +#62895 = EDGE_CURVE('',#62896,#62873,#62898,.T.); +#62896 = VERTEX_POINT('',#62897); +#62897 = CARTESIAN_POINT('',(-1.79,-1.105,-1.71)); +#62898 = SURFACE_CURVE('',#62899,(#62903,#62910),.PCURVE_S1.); +#62899 = LINE('',#62900,#62901); +#62900 = CARTESIAN_POINT('',(-1.79,-1.105,-1.71)); +#62901 = VECTOR('',#62902,1.); +#62902 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62903 = PCURVE('',#62825,#62904); +#62904 = DEFINITIONAL_REPRESENTATION('',(#62905),#62909); +#62905 = LINE('',#62906,#62907); +#62906 = CARTESIAN_POINT('',(0.E+000,-3.58)); +#62907 = VECTOR('',#62908,1.); +#62908 = DIRECTION('',(1.,0.E+000)); +#62909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62910 = PCURVE('',#44262,#62911); +#62911 = DEFINITIONAL_REPRESENTATION('',(#62912),#62916); +#62912 = LINE('',#62913,#62914); +#62913 = CARTESIAN_POINT('',(0.5,-0.12)); +#62914 = VECTOR('',#62915,1.); +#62915 = DIRECTION('',(1.,0.E+000)); +#62916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62917 = ORIENTED_EDGE('',*,*,#62918,.F.); +#62918 = EDGE_CURVE('',#62815,#62896,#62919,.T.); +#62919 = SURFACE_CURVE('',#62920,(#62924,#62931),.PCURVE_S1.); +#62920 = LINE('',#62921,#62922); +#62921 = CARTESIAN_POINT('',(-1.425,-1.105,-1.71)); +#62922 = VECTOR('',#62923,1.); +#62923 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#62924 = PCURVE('',#62825,#62925); +#62925 = DEFINITIONAL_REPRESENTATION('',(#62926),#62930); +#62926 = LINE('',#62927,#62928); +#62927 = CARTESIAN_POINT('',(0.E+000,-3.215)); +#62928 = VECTOR('',#62929,1.); +#62929 = DIRECTION('',(0.E+000,-1.)); +#62930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62931 = PCURVE('',#62623,#62932); +#62932 = DEFINITIONAL_REPRESENTATION('',(#62933),#62937); +#62933 = LINE('',#62934,#62935); +#62934 = CARTESIAN_POINT('',(0.12,-3.215)); +#62935 = VECTOR('',#62936,1.); +#62936 = DIRECTION('',(0.E+000,-1.)); +#62937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62938 = ADVANCED_FACE('',(#62939),#62953,.T.); +#62939 = FACE_BOUND('',#62940,.F.); +#62940 = EDGE_LOOP('',(#62941,#62971,#62999,#63022,#63050,#63073)); +#62941 = ORIENTED_EDGE('',*,*,#62942,.T.); +#62942 = EDGE_CURVE('',#62943,#62945,#62947,.T.); +#62943 = VERTEX_POINT('',#62944); +#62944 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); +#62945 = VERTEX_POINT('',#62946); +#62946 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); +#62947 = SURFACE_CURVE('',#62948,(#62952,#62964),.PCURVE_S1.); +#62948 = LINE('',#62949,#62950); +#62949 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); +#62950 = VECTOR('',#62951,1.); +#62951 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62952 = PCURVE('',#62953,#62958); +#62953 = PLANE('',#62954); +#62954 = AXIS2_PLACEMENT_3D('',#62955,#62956,#62957); +#62955 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#62956 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#62957 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62958 = DEFINITIONAL_REPRESENTATION('',(#62959),#62963); +#62959 = LINE('',#62960,#62961); +#62960 = CARTESIAN_POINT('',(0.E+000,-2.565)); +#62961 = VECTOR('',#62962,1.); +#62962 = DIRECTION('',(1.,0.E+000)); +#62963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62964 = PCURVE('',#62483,#62965); +#62965 = DEFINITIONAL_REPRESENTATION('',(#62966),#62970); +#62966 = LINE('',#62967,#62968); +#62967 = CARTESIAN_POINT('',(1.71,-1.105)); +#62968 = VECTOR('',#62969,1.); +#62969 = DIRECTION('',(1.,0.E+000)); +#62970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62971 = ORIENTED_EDGE('',*,*,#62972,.T.); +#62972 = EDGE_CURVE('',#62945,#62973,#62975,.T.); +#62973 = VERTEX_POINT('',#62974); +#62974 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); +#62975 = SURFACE_CURVE('',#62976,(#62980,#62987),.PCURVE_S1.); #62976 = LINE('',#62977,#62978); -#62977 = CARTESIAN_POINT('',(1.030096189432,0.E+000)); +#62977 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); #62978 = VECTOR('',#62979,1.); -#62979 = DIRECTION('',(1.,0.E+000)); -#62980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#62981 = ORIENTED_EDGE('',*,*,#51601,.T.); -#62982 = ORIENTED_EDGE('',*,*,#62318,.T.); -#62983 = ADVANCED_FACE('',(#62984),#52280,.F.); -#62984 = FACE_BOUND('',#62985,.F.); -#62985 = EDGE_LOOP('',(#62986,#62987,#63008)); -#62986 = ORIENTED_EDGE('',*,*,#52264,.T.); -#62987 = ORIENTED_EDGE('',*,*,#62988,.T.); -#62988 = EDGE_CURVE('',#52237,#61895,#62989,.T.); -#62989 = SURFACE_CURVE('',#62990,(#62994,#63001),.PCURVE_S1.); -#62990 = LINE('',#62991,#62992); -#62991 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); -#62992 = VECTOR('',#62993,1.); -#62993 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#62994 = PCURVE('',#52280,#62995); -#62995 = DEFINITIONAL_REPRESENTATION('',(#62996),#63000); -#62996 = LINE('',#62997,#62998); -#62997 = CARTESIAN_POINT('',(1.21,0.5)); -#62998 = VECTOR('',#62999,1.); -#62999 = DIRECTION('',(1.,0.E+000)); -#63000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63001 = PCURVE('',#52252,#63002); -#63002 = DEFINITIONAL_REPRESENTATION('',(#63003),#63007); -#63003 = LINE('',#63004,#63005); -#63004 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63005 = VECTOR('',#63006,1.); -#63006 = DIRECTION('',(1.,0.E+000)); -#63007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63008 = ORIENTED_EDGE('',*,*,#63009,.T.); -#63009 = EDGE_CURVE('',#61895,#52265,#63010,.T.); -#63010 = SURFACE_CURVE('',#63011,(#63015,#63022),.PCURVE_S1.); -#63011 = LINE('',#63012,#63013); -#63012 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); -#63013 = VECTOR('',#63014,1.); -#63014 = DIRECTION('',(0.866025403784,0.5,0.E+000)); -#63015 = PCURVE('',#52280,#63016); +#62979 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62980 = PCURVE('',#62953,#62981); +#62981 = DEFINITIONAL_REPRESENTATION('',(#62982),#62986); +#62982 = LINE('',#62983,#62984); +#62983 = CARTESIAN_POINT('',(0.172153903092,-2.565)); +#62984 = VECTOR('',#62985,1.); +#62985 = DIRECTION('',(1.,0.E+000)); +#62986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62987 = PCURVE('',#62988,#62993); +#62988 = PLANE('',#62989); +#62989 = AXIS2_PLACEMENT_3D('',#62990,#62991,#62992); +#62990 = CARTESIAN_POINT('',(-0.775,0.E+000,0.E+000)); +#62991 = DIRECTION('',(1.,0.E+000,0.E+000)); +#62992 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#62993 = DEFINITIONAL_REPRESENTATION('',(#62994),#62998); +#62994 = LINE('',#62995,#62996); +#62995 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#62996 = VECTOR('',#62997,1.); +#62997 = DIRECTION('',(1.,0.E+000)); +#62998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#62999 = ORIENTED_EDGE('',*,*,#63000,.T.); +#63000 = EDGE_CURVE('',#62973,#63001,#63003,.T.); +#63001 = VERTEX_POINT('',#63002); +#63002 = CARTESIAN_POINT('',(-1.175,-1.105,-2.35)); +#63003 = SURFACE_CURVE('',#63004,(#63008,#63015),.PCURVE_S1.); +#63004 = LINE('',#63005,#63006); +#63005 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); +#63006 = VECTOR('',#63007,1.); +#63007 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63008 = PCURVE('',#62953,#63009); +#63009 = DEFINITIONAL_REPRESENTATION('',(#63010),#63014); +#63010 = LINE('',#63011,#63012); +#63011 = CARTESIAN_POINT('',(0.64,-2.565)); +#63012 = VECTOR('',#63013,1.); +#63013 = DIRECTION('',(0.E+000,-1.)); +#63014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63015 = PCURVE('',#45173,#63016); #63016 = DEFINITIONAL_REPRESENTATION('',(#63017),#63021); #63017 = LINE('',#63018,#63019); -#63018 = CARTESIAN_POINT('',(1.339903810568,0.5)); +#63018 = CARTESIAN_POINT('',(-0.775,-1.105)); #63019 = VECTOR('',#63020,1.); -#63020 = DIRECTION('',(-0.866025403784,0.5)); +#63020 = DIRECTION('',(-1.,0.E+000)); #63021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63022 = PCURVE('',#51795,#63023); -#63023 = DEFINITIONAL_REPRESENTATION('',(#63024),#63028); -#63024 = LINE('',#63025,#63026); -#63025 = CARTESIAN_POINT('',(0.65,0.E+000)); -#63026 = VECTOR('',#63027,1.); -#63027 = DIRECTION('',(1.,0.E+000)); -#63028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63029 = ADVANCED_FACE('',(#63030),#42990,.F.); -#63030 = FACE_BOUND('',#63031,.F.); -#63031 = EDGE_LOOP('',(#63032,#63053,#63054,#63055,#63082,#63103)); -#63032 = ORIENTED_EDGE('',*,*,#63033,.T.); -#63033 = EDGE_CURVE('',#62473,#62841,#63034,.T.); -#63034 = SURFACE_CURVE('',#63035,(#63039,#63046),.PCURVE_S1.); -#63035 = LINE('',#63036,#63037); -#63036 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); -#63037 = VECTOR('',#63038,1.); -#63038 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63039 = PCURVE('',#42990,#63040); -#63040 = DEFINITIONAL_REPRESENTATION('',(#63041),#63045); -#63041 = LINE('',#63042,#63043); -#63042 = CARTESIAN_POINT('',(-3.,-0.925)); -#63043 = VECTOR('',#63044,1.); -#63044 = DIRECTION('',(1.,0.E+000)); -#63045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63046 = PCURVE('',#62488,#63047); -#63047 = DEFINITIONAL_REPRESENTATION('',(#63048),#63052); -#63048 = LINE('',#63049,#63050); -#63049 = CARTESIAN_POINT('',(3.,-2.35)); -#63050 = VECTOR('',#63051,1.); -#63051 = DIRECTION('',(-1.,0.E+000)); -#63052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63053 = ORIENTED_EDGE('',*,*,#62840,.T.); -#63054 = ORIENTED_EDGE('',*,*,#42974,.T.); -#63055 = ORIENTED_EDGE('',*,*,#63056,.T.); -#63056 = EDGE_CURVE('',#42948,#63057,#63059,.T.); -#63057 = VERTEX_POINT('',#63058); -#63058 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); -#63059 = SURFACE_CURVE('',#63060,(#63065,#63076),.PCURVE_S1.); -#63060 = CIRCLE('',#63061,0.25); -#63061 = AXIS2_PLACEMENT_3D('',#63062,#63063,#63064); -#63062 = CARTESIAN_POINT('',(2.594375541595,-0.67,-2.35)); -#63063 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63064 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63065 = PCURVE('',#42990,#63066); -#63066 = DEFINITIONAL_REPRESENTATION('',(#63067),#63075); -#63067 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#63068,#63069,#63070,#63071 - ,#63072,#63073,#63074),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#63068 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); -#63069 = CARTESIAN_POINT('',(-3.027388243487,-0.92)); -#63070 = CARTESIAN_POINT('',(-2.810881892541,-0.545)); -#63071 = CARTESIAN_POINT('',(-2.594375541595,-0.17)); -#63072 = CARTESIAN_POINT('',(-2.377869190649,-0.545)); -#63073 = CARTESIAN_POINT('',(-2.161362839703,-0.92)); -#63074 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); -#63075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63076 = PCURVE('',#42963,#63077); -#63077 = DEFINITIONAL_REPRESENTATION('',(#63078),#63081); -#63078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63079,#63080),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#63079 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#63080 = CARTESIAN_POINT('',(5.49778714378,0.E+000)); -#63081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63082 = ORIENTED_EDGE('',*,*,#63083,.T.); -#63083 = EDGE_CURVE('',#63057,#61625,#63084,.T.); -#63084 = SURFACE_CURVE('',#63085,(#63089,#63096),.PCURVE_S1.); -#63085 = LINE('',#63086,#63087); -#63086 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); -#63087 = VECTOR('',#63088,1.); -#63088 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#63089 = PCURVE('',#42990,#63090); -#63090 = DEFINITIONAL_REPRESENTATION('',(#63091),#63095); -#63091 = LINE('',#63092,#63093); -#63092 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297)); -#63093 = VECTOR('',#63094,1.); -#63094 = DIRECTION('',(-0.707106781187,0.707106781187)); -#63095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63096 = PCURVE('',#43512,#63097); -#63097 = DEFINITIONAL_REPRESENTATION('',(#63098),#63102); -#63098 = LINE('',#63099,#63100); -#63099 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63100 = VECTOR('',#63101,1.); -#63101 = DIRECTION('',(1.,0.E+000)); -#63102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63103 = ORIENTED_EDGE('',*,*,#62500,.T.); -#63104 = ADVANCED_FACE('',(#63105),#43095,.F.); -#63105 = FACE_BOUND('',#63106,.F.); -#63106 = EDGE_LOOP('',(#63107,#63137,#63158,#63181,#63206,#63207)); -#63107 = ORIENTED_EDGE('',*,*,#63108,.T.); -#63108 = EDGE_CURVE('',#63109,#63111,#63113,.T.); -#63109 = VERTEX_POINT('',#63110); -#63110 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); -#63111 = VERTEX_POINT('',#63112); -#63112 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); -#63113 = SURFACE_CURVE('',#63114,(#63118,#63125),.PCURVE_S1.); -#63114 = LINE('',#63115,#63116); -#63115 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); -#63116 = VECTOR('',#63117,1.); -#63117 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63118 = PCURVE('',#43095,#63119); -#63119 = DEFINITIONAL_REPRESENTATION('',(#63120),#63124); -#63120 = LINE('',#63121,#63122); -#63121 = CARTESIAN_POINT('',(1.925,-0.925)); -#63122 = VECTOR('',#63123,1.); -#63123 = DIRECTION('',(1.,0.E+000)); -#63124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63125 = PCURVE('',#63126,#63131); -#63126 = PLANE('',#63127); -#63127 = AXIS2_PLACEMENT_3D('',#63128,#63129,#63130); -#63128 = CARTESIAN_POINT('',(0.E+000,-0.925,0.E+000)); -#63129 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63130 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63131 = DEFINITIONAL_REPRESENTATION('',(#63132),#63136); +#63022 = ORIENTED_EDGE('',*,*,#63023,.T.); +#63023 = EDGE_CURVE('',#63001,#63024,#63026,.T.); +#63024 = VERTEX_POINT('',#63025); +#63025 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); +#63026 = SURFACE_CURVE('',#63027,(#63031,#63038),.PCURVE_S1.); +#63027 = LINE('',#63028,#63029); +#63028 = CARTESIAN_POINT('',(-1.175,-1.105,-2.35)); +#63029 = VECTOR('',#63030,1.); +#63030 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63031 = PCURVE('',#62953,#63032); +#63032 = DEFINITIONAL_REPRESENTATION('',(#63033),#63037); +#63033 = LINE('',#63034,#63035); +#63034 = CARTESIAN_POINT('',(0.64,-2.965)); +#63035 = VECTOR('',#63036,1.); +#63036 = DIRECTION('',(-1.,0.E+000)); +#63037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63038 = PCURVE('',#63039,#63044); +#63039 = PLANE('',#63040); +#63040 = AXIS2_PLACEMENT_3D('',#63041,#63042,#63043); +#63041 = CARTESIAN_POINT('',(-1.175,0.E+000,0.E+000)); +#63042 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63043 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63044 = DEFINITIONAL_REPRESENTATION('',(#63045),#63049); +#63045 = LINE('',#63046,#63047); +#63046 = CARTESIAN_POINT('',(2.35,-1.105)); +#63047 = VECTOR('',#63048,1.); +#63048 = DIRECTION('',(-1.,0.E+000)); +#63049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63050 = ORIENTED_EDGE('',*,*,#63051,.F.); +#63051 = EDGE_CURVE('',#63052,#63024,#63054,.T.); +#63052 = VERTEX_POINT('',#63053); +#63053 = CARTESIAN_POINT('',(-1.175,-1.105,-1.71)); +#63054 = SURFACE_CURVE('',#63055,(#63059,#63066),.PCURVE_S1.); +#63055 = LINE('',#63056,#63057); +#63056 = CARTESIAN_POINT('',(-1.175,-1.105,-1.71)); +#63057 = VECTOR('',#63058,1.); +#63058 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63059 = PCURVE('',#62953,#63060); +#63060 = DEFINITIONAL_REPRESENTATION('',(#63061),#63065); +#63061 = LINE('',#63062,#63063); +#63062 = CARTESIAN_POINT('',(0.E+000,-2.965)); +#63063 = VECTOR('',#63064,1.); +#63064 = DIRECTION('',(1.,0.E+000)); +#63065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63066 = PCURVE('',#62539,#63067); +#63067 = DEFINITIONAL_REPRESENTATION('',(#63068),#63072); +#63068 = LINE('',#63069,#63070); +#63069 = CARTESIAN_POINT('',(1.71,-1.105)); +#63070 = VECTOR('',#63071,1.); +#63071 = DIRECTION('',(1.,0.E+000)); +#63072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63073 = ORIENTED_EDGE('',*,*,#63074,.F.); +#63074 = EDGE_CURVE('',#62943,#63052,#63075,.T.); +#63075 = SURFACE_CURVE('',#63076,(#63080,#63087),.PCURVE_S1.); +#63076 = LINE('',#63077,#63078); +#63077 = CARTESIAN_POINT('',(-0.775,-1.105,-1.71)); +#63078 = VECTOR('',#63079,1.); +#63079 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63080 = PCURVE('',#62953,#63081); +#63081 = DEFINITIONAL_REPRESENTATION('',(#63082),#63086); +#63082 = LINE('',#63083,#63084); +#63083 = CARTESIAN_POINT('',(0.E+000,-2.565)); +#63084 = VECTOR('',#63085,1.); +#63085 = DIRECTION('',(0.E+000,-1.)); +#63086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63087 = PCURVE('',#62511,#63088); +#63088 = DEFINITIONAL_REPRESENTATION('',(#63089),#63093); +#63089 = LINE('',#63090,#63091); +#63090 = CARTESIAN_POINT('',(0.12,-2.565)); +#63091 = VECTOR('',#63092,1.); +#63092 = DIRECTION('',(0.E+000,-1.)); +#63093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63094 = ADVANCED_FACE('',(#63095),#63109,.T.); +#63095 = FACE_BOUND('',#63096,.F.); +#63096 = EDGE_LOOP('',(#63097,#63127,#63155,#63178,#63206,#63229)); +#63097 = ORIENTED_EDGE('',*,*,#63098,.T.); +#63098 = EDGE_CURVE('',#63099,#63101,#63103,.T.); +#63099 = VERTEX_POINT('',#63100); +#63100 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); +#63101 = VERTEX_POINT('',#63102); +#63102 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); +#63103 = SURFACE_CURVE('',#63104,(#63108,#63120),.PCURVE_S1.); +#63104 = LINE('',#63105,#63106); +#63105 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); +#63106 = VECTOR('',#63107,1.); +#63107 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63108 = PCURVE('',#63109,#63114); +#63109 = PLANE('',#63110); +#63110 = AXIS2_PLACEMENT_3D('',#63111,#63112,#63113); +#63111 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#63112 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63113 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63114 = DEFINITIONAL_REPRESENTATION('',(#63115),#63119); +#63115 = LINE('',#63116,#63117); +#63116 = CARTESIAN_POINT('',(0.E+000,-1.915)); +#63117 = VECTOR('',#63118,1.); +#63118 = DIRECTION('',(1.,0.E+000)); +#63119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63120 = PCURVE('',#62371,#63121); +#63121 = DEFINITIONAL_REPRESENTATION('',(#63122),#63126); +#63122 = LINE('',#63123,#63124); +#63123 = CARTESIAN_POINT('',(1.71,-1.105)); +#63124 = VECTOR('',#63125,1.); +#63125 = DIRECTION('',(1.,0.E+000)); +#63126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63127 = ORIENTED_EDGE('',*,*,#63128,.T.); +#63128 = EDGE_CURVE('',#63101,#63129,#63131,.T.); +#63129 = VERTEX_POINT('',#63130); +#63130 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); +#63131 = SURFACE_CURVE('',#63132,(#63136,#63143),.PCURVE_S1.); #63132 = LINE('',#63133,#63134); -#63133 = CARTESIAN_POINT('',(-1.925,-2.35)); +#63133 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); #63134 = VECTOR('',#63135,1.); -#63135 = DIRECTION('',(-1.,0.E+000)); -#63136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63137 = ORIENTED_EDGE('',*,*,#63138,.T.); -#63138 = EDGE_CURVE('',#63111,#61815,#63139,.T.); -#63139 = SURFACE_CURVE('',#63140,(#63144,#63151),.PCURVE_S1.); -#63140 = LINE('',#63141,#63142); -#63141 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); -#63142 = VECTOR('',#63143,1.); -#63143 = DIRECTION('',(0.E+000,1.,0.E+000)); -#63144 = PCURVE('',#43095,#63145); -#63145 = DEFINITIONAL_REPRESENTATION('',(#63146),#63150); -#63146 = LINE('',#63147,#63148); -#63147 = CARTESIAN_POINT('',(3.,-0.925)); -#63148 = VECTOR('',#63149,1.); -#63149 = DIRECTION('',(0.E+000,1.)); -#63150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63151 = PCURVE('',#51879,#63152); -#63152 = DEFINITIONAL_REPRESENTATION('',(#63153),#63157); -#63153 = LINE('',#63154,#63155); -#63154 = CARTESIAN_POINT('',(0.3,0.E+000)); -#63155 = VECTOR('',#63156,1.); -#63156 = DIRECTION('',(1.,0.E+000)); -#63157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63158 = ORIENTED_EDGE('',*,*,#63159,.F.); -#63159 = EDGE_CURVE('',#63160,#61815,#63162,.T.); -#63160 = VERTEX_POINT('',#63161); -#63161 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); -#63162 = SURFACE_CURVE('',#63163,(#63167,#63174),.PCURVE_S1.); -#63163 = LINE('',#63164,#63165); -#63164 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); -#63165 = VECTOR('',#63166,1.); -#63166 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#63167 = PCURVE('',#43095,#63168); -#63168 = DEFINITIONAL_REPRESENTATION('',(#63169),#63173); -#63169 = LINE('',#63170,#63171); -#63170 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297)); -#63171 = VECTOR('',#63172,1.); -#63172 = DIRECTION('',(0.707106781187,0.707106781187)); -#63173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63174 = PCURVE('',#43680,#63175); -#63175 = DEFINITIONAL_REPRESENTATION('',(#63176),#63180); -#63176 = LINE('',#63177,#63178); -#63177 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); -#63178 = VECTOR('',#63179,1.); -#63179 = DIRECTION('',(-1.,0.E+000)); -#63180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63181 = ORIENTED_EDGE('',*,*,#63182,.T.); -#63182 = EDGE_CURVE('',#63160,#43080,#63183,.T.); -#63183 = SURFACE_CURVE('',#63184,(#63189,#63200),.PCURVE_S1.); -#63184 = CIRCLE('',#63185,0.25); -#63185 = AXIS2_PLACEMENT_3D('',#63186,#63187,#63188); -#63186 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-2.35)); -#63187 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63188 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); -#63189 = PCURVE('',#43095,#63190); -#63190 = DEFINITIONAL_REPRESENTATION('',(#63191),#63199); -#63191 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#63192,#63193,#63194,#63195 - ,#63196,#63197,#63198),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#63192 = CARTESIAN_POINT('',(2.771152236892,-0.846776695297)); -#63193 = CARTESIAN_POINT('',(2.464966019044,-1.152962913145)); -#63194 = CARTESIAN_POINT('',(2.352894085023,-0.734704761276)); -#63195 = CARTESIAN_POINT('',(2.240822151002,-0.316446609407)); -#63196 = CARTESIAN_POINT('',(2.659080302871,-0.428518543428)); -#63197 = CARTESIAN_POINT('',(3.07733845474,-0.540590477449)); -#63198 = CARTESIAN_POINT('',(2.771152236892,-0.846776695297)); -#63199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63200 = PCURVE('',#43123,#63201); -#63201 = DEFINITIONAL_REPRESENTATION('',(#63202),#63205); -#63202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63203,#63204),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.785398163398),.PIECEWISE_BEZIER_KNOTS.); -#63203 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); -#63204 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#63135 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63136 = PCURVE('',#63109,#63137); +#63137 = DEFINITIONAL_REPRESENTATION('',(#63138),#63142); +#63138 = LINE('',#63139,#63140); +#63139 = CARTESIAN_POINT('',(0.172153903092,-1.915)); +#63140 = VECTOR('',#63141,1.); +#63141 = DIRECTION('',(1.,0.E+000)); +#63142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63143 = PCURVE('',#63144,#63149); +#63144 = PLANE('',#63145); +#63145 = AXIS2_PLACEMENT_3D('',#63146,#63147,#63148); +#63146 = CARTESIAN_POINT('',(-0.125,0.E+000,0.E+000)); +#63147 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63148 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63149 = DEFINITIONAL_REPRESENTATION('',(#63150),#63154); +#63150 = LINE('',#63151,#63152); +#63151 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#63152 = VECTOR('',#63153,1.); +#63153 = DIRECTION('',(1.,0.E+000)); +#63154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63155 = ORIENTED_EDGE('',*,*,#63156,.T.); +#63156 = EDGE_CURVE('',#63129,#63157,#63159,.T.); +#63157 = VERTEX_POINT('',#63158); +#63158 = CARTESIAN_POINT('',(-0.525,-1.105,-2.35)); +#63159 = SURFACE_CURVE('',#63160,(#63164,#63171),.PCURVE_S1.); +#63160 = LINE('',#63161,#63162); +#63161 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); +#63162 = VECTOR('',#63163,1.); +#63163 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63164 = PCURVE('',#63109,#63165); +#63165 = DEFINITIONAL_REPRESENTATION('',(#63166),#63170); +#63166 = LINE('',#63167,#63168); +#63167 = CARTESIAN_POINT('',(0.64,-1.915)); +#63168 = VECTOR('',#63169,1.); +#63169 = DIRECTION('',(0.E+000,-1.)); +#63170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63171 = PCURVE('',#45173,#63172); +#63172 = DEFINITIONAL_REPRESENTATION('',(#63173),#63177); +#63173 = LINE('',#63174,#63175); +#63174 = CARTESIAN_POINT('',(-0.125,-1.105)); +#63175 = VECTOR('',#63176,1.); +#63176 = DIRECTION('',(-1.,0.E+000)); +#63177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63178 = ORIENTED_EDGE('',*,*,#63179,.T.); +#63179 = EDGE_CURVE('',#63157,#63180,#63182,.T.); +#63180 = VERTEX_POINT('',#63181); +#63181 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); +#63182 = SURFACE_CURVE('',#63183,(#63187,#63194),.PCURVE_S1.); +#63183 = LINE('',#63184,#63185); +#63184 = CARTESIAN_POINT('',(-0.525,-1.105,-2.35)); +#63185 = VECTOR('',#63186,1.); +#63186 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63187 = PCURVE('',#63109,#63188); +#63188 = DEFINITIONAL_REPRESENTATION('',(#63189),#63193); +#63189 = LINE('',#63190,#63191); +#63190 = CARTESIAN_POINT('',(0.64,-2.315)); +#63191 = VECTOR('',#63192,1.); +#63192 = DIRECTION('',(-1.,0.E+000)); +#63193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63194 = PCURVE('',#63195,#63200); +#63195 = PLANE('',#63196); +#63196 = AXIS2_PLACEMENT_3D('',#63197,#63198,#63199); +#63197 = CARTESIAN_POINT('',(-0.525,0.E+000,0.E+000)); +#63198 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63199 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63200 = DEFINITIONAL_REPRESENTATION('',(#63201),#63205); +#63201 = LINE('',#63202,#63203); +#63202 = CARTESIAN_POINT('',(2.35,-1.105)); +#63203 = VECTOR('',#63204,1.); +#63204 = DIRECTION('',(-1.,0.E+000)); #63205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63206 = ORIENTED_EDGE('',*,*,#43079,.T.); -#63207 = ORIENTED_EDGE('',*,*,#63208,.T.); -#63208 = EDGE_CURVE('',#43057,#63109,#63209,.T.); -#63209 = SURFACE_CURVE('',#63210,(#63214,#63221),.PCURVE_S1.); -#63210 = LINE('',#63211,#63212); -#63211 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); -#63212 = VECTOR('',#63213,1.); -#63213 = DIRECTION('',(4.440892098502E-014,-1.,0.E+000)); -#63214 = PCURVE('',#43095,#63215); -#63215 = DEFINITIONAL_REPRESENTATION('',(#63216),#63220); -#63216 = LINE('',#63217,#63218); -#63217 = CARTESIAN_POINT('',(1.925,-0.92)); -#63218 = VECTOR('',#63219,1.); -#63219 = DIRECTION('',(-4.440892098502E-014,-1.)); -#63220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63221 = PCURVE('',#51934,#63222); -#63222 = DEFINITIONAL_REPRESENTATION('',(#63223),#63227); -#63223 = LINE('',#63224,#63225); -#63224 = CARTESIAN_POINT('',(0.195,0.E+000)); -#63225 = VECTOR('',#63226,1.); -#63226 = DIRECTION('',(1.,0.E+000)); -#63227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63228 = ADVANCED_FACE('',(#63229),#43400,.T.); -#63229 = FACE_BOUND('',#63230,.F.); -#63230 = EDGE_LOOP('',(#63231,#63232,#63233,#63234,#63235,#63255,#63256, - #63279,#63300,#63301,#63302,#63303,#63326,#63347,#63348,#63368, - #63369,#63392)); -#63231 = ORIENTED_EDGE('',*,*,#47146,.T.); -#63232 = ORIENTED_EDGE('',*,*,#47098,.T.); -#63233 = ORIENTED_EDGE('',*,*,#46989,.F.); -#63234 = ORIENTED_EDGE('',*,*,#43776,.T.); -#63235 = ORIENTED_EDGE('',*,*,#63236,.F.); -#63236 = EDGE_CURVE('',#61969,#43749,#63237,.T.); -#63237 = SURFACE_CURVE('',#63238,(#63242,#63249),.PCURVE_S1.); +#63206 = ORIENTED_EDGE('',*,*,#63207,.F.); +#63207 = EDGE_CURVE('',#63208,#63180,#63210,.T.); +#63208 = VERTEX_POINT('',#63209); +#63209 = CARTESIAN_POINT('',(-0.525,-1.105,-1.71)); +#63210 = SURFACE_CURVE('',#63211,(#63215,#63222),.PCURVE_S1.); +#63211 = LINE('',#63212,#63213); +#63212 = CARTESIAN_POINT('',(-0.525,-1.105,-1.71)); +#63213 = VECTOR('',#63214,1.); +#63214 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63215 = PCURVE('',#63109,#63216); +#63216 = DEFINITIONAL_REPRESENTATION('',(#63217),#63221); +#63217 = LINE('',#63218,#63219); +#63218 = CARTESIAN_POINT('',(0.E+000,-2.315)); +#63219 = VECTOR('',#63220,1.); +#63220 = DIRECTION('',(1.,0.E+000)); +#63221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63222 = PCURVE('',#62427,#63223); +#63223 = DEFINITIONAL_REPRESENTATION('',(#63224),#63228); +#63224 = LINE('',#63225,#63226); +#63225 = CARTESIAN_POINT('',(1.71,-1.105)); +#63226 = VECTOR('',#63227,1.); +#63227 = DIRECTION('',(1.,0.E+000)); +#63228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63229 = ORIENTED_EDGE('',*,*,#63230,.F.); +#63230 = EDGE_CURVE('',#63099,#63208,#63231,.T.); +#63231 = SURFACE_CURVE('',#63232,(#63236,#63243),.PCURVE_S1.); +#63232 = LINE('',#63233,#63234); +#63233 = CARTESIAN_POINT('',(-0.125,-1.105,-1.71)); +#63234 = VECTOR('',#63235,1.); +#63235 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63236 = PCURVE('',#63109,#63237); +#63237 = DEFINITIONAL_REPRESENTATION('',(#63238),#63242); #63238 = LINE('',#63239,#63240); -#63239 = CARTESIAN_POINT('',(-3.095,0.92,-2.35)); +#63239 = CARTESIAN_POINT('',(0.E+000,-1.915)); #63240 = VECTOR('',#63241,1.); -#63241 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63242 = PCURVE('',#43400,#63243); -#63243 = DEFINITIONAL_REPRESENTATION('',(#63244),#63248); -#63244 = LINE('',#63245,#63246); -#63245 = CARTESIAN_POINT('',(6.19,0.E+000)); -#63246 = VECTOR('',#63247,1.); -#63247 = DIRECTION('',(0.E+000,1.)); -#63248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63249 = PCURVE('',#43765,#63250); -#63250 = DEFINITIONAL_REPRESENTATION('',(#63251),#63254); -#63251 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63252,#63253),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63252 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#63253 = CARTESIAN_POINT('',(1.570796326795,1.2)); -#63254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63255 = ORIENTED_EDGE('',*,*,#61968,.F.); -#63256 = ORIENTED_EDGE('',*,*,#63257,.T.); -#63257 = EDGE_CURVE('',#61941,#63258,#63260,.T.); -#63258 = VERTEX_POINT('',#63259); -#63259 = CARTESIAN_POINT('',(-2.37,0.92,-1.63)); -#63260 = SURFACE_CURVE('',#63261,(#63265,#63272),.PCURVE_S1.); -#63261 = LINE('',#63262,#63263); -#63262 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); -#63263 = VECTOR('',#63264,1.); -#63264 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63265 = PCURVE('',#43400,#63266); -#63266 = DEFINITIONAL_REPRESENTATION('',(#63267),#63271); -#63267 = LINE('',#63268,#63269); -#63268 = CARTESIAN_POINT('',(5.465,0.E+000)); -#63269 = VECTOR('',#63270,1.); -#63270 = DIRECTION('',(0.E+000,1.)); -#63271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63272 = PCURVE('',#61956,#63273); -#63273 = DEFINITIONAL_REPRESENTATION('',(#63274),#63278); -#63274 = LINE('',#63275,#63276); -#63275 = CARTESIAN_POINT('',(0.42,0.E+000)); -#63276 = VECTOR('',#63277,1.); -#63277 = DIRECTION('',(0.E+000,-1.)); -#63278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63279 = ORIENTED_EDGE('',*,*,#63280,.F.); -#63280 = EDGE_CURVE('',#52186,#63258,#63281,.T.); -#63281 = SURFACE_CURVE('',#63282,(#63286,#63293),.PCURVE_S1.); -#63282 = LINE('',#63283,#63284); -#63283 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); -#63284 = VECTOR('',#63285,1.); -#63285 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63286 = PCURVE('',#43400,#63287); -#63287 = DEFINITIONAL_REPRESENTATION('',(#63288),#63292); +#63241 = DIRECTION('',(0.E+000,-1.)); +#63242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63243 = PCURVE('',#62399,#63244); +#63244 = DEFINITIONAL_REPRESENTATION('',(#63245),#63249); +#63245 = LINE('',#63246,#63247); +#63246 = CARTESIAN_POINT('',(0.12,-1.915)); +#63247 = VECTOR('',#63248,1.); +#63248 = DIRECTION('',(0.E+000,-1.)); +#63249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63250 = ADVANCED_FACE('',(#63251),#63265,.T.); +#63251 = FACE_BOUND('',#63252,.F.); +#63252 = EDGE_LOOP('',(#63253,#63283,#63311,#63334,#63362,#63385)); +#63253 = ORIENTED_EDGE('',*,*,#63254,.T.); +#63254 = EDGE_CURVE('',#63255,#63257,#63259,.T.); +#63255 = VERTEX_POINT('',#63256); +#63256 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); +#63257 = VERTEX_POINT('',#63258); +#63258 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); +#63259 = SURFACE_CURVE('',#63260,(#63264,#63276),.PCURVE_S1.); +#63260 = LINE('',#63261,#63262); +#63261 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); +#63262 = VECTOR('',#63263,1.); +#63263 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63264 = PCURVE('',#63265,#63270); +#63265 = PLANE('',#63266); +#63266 = AXIS2_PLACEMENT_3D('',#63267,#63268,#63269); +#63267 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#63268 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63269 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63270 = DEFINITIONAL_REPRESENTATION('',(#63271),#63275); +#63271 = LINE('',#63272,#63273); +#63272 = CARTESIAN_POINT('',(0.E+000,-1.265)); +#63273 = VECTOR('',#63274,1.); +#63274 = DIRECTION('',(1.,0.E+000)); +#63275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63276 = PCURVE('',#62259,#63277); +#63277 = DEFINITIONAL_REPRESENTATION('',(#63278),#63282); +#63278 = LINE('',#63279,#63280); +#63279 = CARTESIAN_POINT('',(1.71,-1.105)); +#63280 = VECTOR('',#63281,1.); +#63281 = DIRECTION('',(1.,0.E+000)); +#63282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63283 = ORIENTED_EDGE('',*,*,#63284,.T.); +#63284 = EDGE_CURVE('',#63257,#63285,#63287,.T.); +#63285 = VERTEX_POINT('',#63286); +#63286 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); +#63287 = SURFACE_CURVE('',#63288,(#63292,#63299),.PCURVE_S1.); #63288 = LINE('',#63289,#63290); -#63289 = CARTESIAN_POINT('',(4.305,0.72)); +#63289 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); #63290 = VECTOR('',#63291,1.); -#63291 = DIRECTION('',(1.,0.E+000)); -#63292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63293 = PCURVE('',#52224,#63294); -#63294 = DEFINITIONAL_REPRESENTATION('',(#63295),#63299); -#63295 = LINE('',#63296,#63297); -#63296 = CARTESIAN_POINT('',(1.21,0.92)); -#63297 = VECTOR('',#63298,1.); -#63298 = DIRECTION('',(1.,0.E+000)); -#63299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63300 = ORIENTED_EDGE('',*,*,#52185,.F.); -#63301 = ORIENTED_EDGE('',*,*,#62936,.F.); -#63302 = ORIENTED_EDGE('',*,*,#51685,.T.); -#63303 = ORIENTED_EDGE('',*,*,#63304,.F.); -#63304 = EDGE_CURVE('',#63305,#51658,#63307,.T.); -#63305 = VERTEX_POINT('',#63306); -#63306 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); -#63307 = SURFACE_CURVE('',#63308,(#63312,#63319),.PCURVE_S1.); -#63308 = LINE('',#63309,#63310); -#63309 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); -#63310 = VECTOR('',#63311,1.); -#63311 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63312 = PCURVE('',#43400,#63313); -#63313 = DEFINITIONAL_REPRESENTATION('',(#63314),#63318); -#63314 = LINE('',#63315,#63316); -#63315 = CARTESIAN_POINT('',(0.725,0.72)); -#63316 = VECTOR('',#63317,1.); -#63317 = DIRECTION('',(1.,0.E+000)); -#63318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63319 = PCURVE('',#51673,#63320); -#63320 = DEFINITIONAL_REPRESENTATION('',(#63321),#63325); -#63321 = LINE('',#63322,#63323); -#63322 = CARTESIAN_POINT('',(-2.37,0.92)); -#63323 = VECTOR('',#63324,1.); -#63324 = DIRECTION('',(1.,0.E+000)); -#63325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63326 = ORIENTED_EDGE('',*,*,#63327,.F.); -#63327 = EDGE_CURVE('',#61740,#63305,#63328,.T.); -#63328 = SURFACE_CURVE('',#63329,(#63333,#63340),.PCURVE_S1.); +#63291 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63292 = PCURVE('',#63265,#63293); +#63293 = DEFINITIONAL_REPRESENTATION('',(#63294),#63298); +#63294 = LINE('',#63295,#63296); +#63295 = CARTESIAN_POINT('',(0.172153903092,-1.265)); +#63296 = VECTOR('',#63297,1.); +#63297 = DIRECTION('',(1.,0.E+000)); +#63298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63299 = PCURVE('',#63300,#63305); +#63300 = PLANE('',#63301); +#63301 = AXIS2_PLACEMENT_3D('',#63302,#63303,#63304); +#63302 = CARTESIAN_POINT('',(0.525,0.E+000,0.E+000)); +#63303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63305 = DEFINITIONAL_REPRESENTATION('',(#63306),#63310); +#63306 = LINE('',#63307,#63308); +#63307 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#63308 = VECTOR('',#63309,1.); +#63309 = DIRECTION('',(1.,0.E+000)); +#63310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63311 = ORIENTED_EDGE('',*,*,#63312,.T.); +#63312 = EDGE_CURVE('',#63285,#63313,#63315,.T.); +#63313 = VERTEX_POINT('',#63314); +#63314 = CARTESIAN_POINT('',(0.125,-1.105,-2.35)); +#63315 = SURFACE_CURVE('',#63316,(#63320,#63327),.PCURVE_S1.); +#63316 = LINE('',#63317,#63318); +#63317 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); +#63318 = VECTOR('',#63319,1.); +#63319 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63320 = PCURVE('',#63265,#63321); +#63321 = DEFINITIONAL_REPRESENTATION('',(#63322),#63326); +#63322 = LINE('',#63323,#63324); +#63323 = CARTESIAN_POINT('',(0.64,-1.265)); +#63324 = VECTOR('',#63325,1.); +#63325 = DIRECTION('',(0.E+000,-1.)); +#63326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63327 = PCURVE('',#45173,#63328); +#63328 = DEFINITIONAL_REPRESENTATION('',(#63329),#63333); #63329 = LINE('',#63330,#63331); -#63330 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); +#63330 = CARTESIAN_POINT('',(0.525,-1.105)); #63331 = VECTOR('',#63332,1.); -#63332 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63333 = PCURVE('',#43400,#63334); -#63334 = DEFINITIONAL_REPRESENTATION('',(#63335),#63339); -#63335 = LINE('',#63336,#63337); -#63336 = CARTESIAN_POINT('',(0.725,0.E+000)); -#63337 = VECTOR('',#63338,1.); -#63338 = DIRECTION('',(0.E+000,1.)); -#63339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63340 = PCURVE('',#61778,#63341); -#63341 = DEFINITIONAL_REPRESENTATION('',(#63342),#63346); -#63342 = LINE('',#63343,#63344); -#63343 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63344 = VECTOR('',#63345,1.); -#63345 = DIRECTION('',(0.E+000,-1.)); -#63346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63347 = ORIENTED_EDGE('',*,*,#61739,.F.); -#63348 = ORIENTED_EDGE('',*,*,#63349,.T.); -#63349 = EDGE_CURVE('',#61717,#43385,#63350,.T.); -#63350 = SURFACE_CURVE('',#63351,(#63355,#63362),.PCURVE_S1.); -#63351 = LINE('',#63352,#63353); -#63352 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); -#63353 = VECTOR('',#63354,1.); -#63354 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63355 = PCURVE('',#43400,#63356); +#63332 = DIRECTION('',(-1.,0.E+000)); +#63333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63334 = ORIENTED_EDGE('',*,*,#63335,.T.); +#63335 = EDGE_CURVE('',#63313,#63336,#63338,.T.); +#63336 = VERTEX_POINT('',#63337); +#63337 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); +#63338 = SURFACE_CURVE('',#63339,(#63343,#63350),.PCURVE_S1.); +#63339 = LINE('',#63340,#63341); +#63340 = CARTESIAN_POINT('',(0.125,-1.105,-2.35)); +#63341 = VECTOR('',#63342,1.); +#63342 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63343 = PCURVE('',#63265,#63344); +#63344 = DEFINITIONAL_REPRESENTATION('',(#63345),#63349); +#63345 = LINE('',#63346,#63347); +#63346 = CARTESIAN_POINT('',(0.64,-1.665)); +#63347 = VECTOR('',#63348,1.); +#63348 = DIRECTION('',(-1.,0.E+000)); +#63349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63350 = PCURVE('',#63351,#63356); +#63351 = PLANE('',#63352); +#63352 = AXIS2_PLACEMENT_3D('',#63353,#63354,#63355); +#63353 = CARTESIAN_POINT('',(0.125,0.E+000,0.E+000)); +#63354 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63355 = DIRECTION('',(0.E+000,0.E+000,-1.)); #63356 = DEFINITIONAL_REPRESENTATION('',(#63357),#63361); #63357 = LINE('',#63358,#63359); -#63358 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#63358 = CARTESIAN_POINT('',(2.35,-1.105)); #63359 = VECTOR('',#63360,1.); -#63360 = DIRECTION('',(0.E+000,1.)); +#63360 = DIRECTION('',(-1.,0.E+000)); #63361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63362 = PCURVE('',#43429,#63363); -#63363 = DEFINITIONAL_REPRESENTATION('',(#63364),#63367); -#63364 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63365,#63366),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63365 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#63366 = CARTESIAN_POINT('',(1.570796326795,1.2)); -#63367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63368 = ORIENTED_EDGE('',*,*,#43384,.T.); -#63369 = ORIENTED_EDGE('',*,*,#63370,.F.); -#63370 = EDGE_CURVE('',#63371,#43357,#63373,.T.); -#63371 = VERTEX_POINT('',#63372); -#63372 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); -#63373 = SURFACE_CURVE('',#63374,(#63378,#63385),.PCURVE_S1.); -#63374 = LINE('',#63375,#63376); -#63375 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); -#63376 = VECTOR('',#63377,1.); -#63377 = DIRECTION('',(0.707106781187,0.E+000,0.707106781187)); -#63378 = PCURVE('',#43400,#63379); +#63362 = ORIENTED_EDGE('',*,*,#63363,.F.); +#63363 = EDGE_CURVE('',#63364,#63336,#63366,.T.); +#63364 = VERTEX_POINT('',#63365); +#63365 = CARTESIAN_POINT('',(0.125,-1.105,-1.71)); +#63366 = SURFACE_CURVE('',#63367,(#63371,#63378),.PCURVE_S1.); +#63367 = LINE('',#63368,#63369); +#63368 = CARTESIAN_POINT('',(0.125,-1.105,-1.71)); +#63369 = VECTOR('',#63370,1.); +#63370 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63371 = PCURVE('',#63265,#63372); +#63372 = DEFINITIONAL_REPRESENTATION('',(#63373),#63377); +#63373 = LINE('',#63374,#63375); +#63374 = CARTESIAN_POINT('',(0.E+000,-1.665)); +#63375 = VECTOR('',#63376,1.); +#63376 = DIRECTION('',(1.,0.E+000)); +#63377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63378 = PCURVE('',#62315,#63379); #63379 = DEFINITIONAL_REPRESENTATION('',(#63380),#63384); #63380 = LINE('',#63381,#63382); -#63381 = CARTESIAN_POINT('',(2.685,1.1)); +#63381 = CARTESIAN_POINT('',(1.71,-1.105)); #63382 = VECTOR('',#63383,1.); -#63383 = DIRECTION('',(-0.707106781187,0.707106781187)); +#63383 = DIRECTION('',(1.,0.E+000)); #63384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63385 = PCURVE('',#43372,#63386); -#63386 = DEFINITIONAL_REPRESENTATION('',(#63387),#63391); -#63387 = LINE('',#63388,#63389); -#63388 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); -#63389 = VECTOR('',#63390,1.); -#63390 = DIRECTION('',(0.E+000,1.)); -#63391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#63385 = ORIENTED_EDGE('',*,*,#63386,.F.); +#63386 = EDGE_CURVE('',#63255,#63364,#63387,.T.); +#63387 = SURFACE_CURVE('',#63388,(#63392,#63399),.PCURVE_S1.); +#63388 = LINE('',#63389,#63390); +#63389 = CARTESIAN_POINT('',(0.525,-1.105,-1.71)); +#63390 = VECTOR('',#63391,1.); +#63391 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63392 = PCURVE('',#63265,#63393); +#63393 = DEFINITIONAL_REPRESENTATION('',(#63394),#63398); +#63394 = LINE('',#63395,#63396); +#63395 = CARTESIAN_POINT('',(0.E+000,-1.265)); +#63396 = VECTOR('',#63397,1.); +#63397 = DIRECTION('',(0.E+000,-1.)); +#63398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63392 = ORIENTED_EDGE('',*,*,#63393,.T.); -#63393 = EDGE_CURVE('',#63371,#47147,#63394,.T.); -#63394 = SURFACE_CURVE('',#63395,(#63399,#63406),.PCURVE_S1.); -#63395 = LINE('',#63396,#63397); -#63396 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); -#63397 = VECTOR('',#63398,1.); -#63398 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#63399 = PCURVE('',#43400,#63400); +#63399 = PCURVE('',#62287,#63400); #63400 = DEFINITIONAL_REPRESENTATION('',(#63401),#63405); #63401 = LINE('',#63402,#63403); -#63402 = CARTESIAN_POINT('',(2.685,1.1)); +#63402 = CARTESIAN_POINT('',(0.12,-1.265)); #63403 = VECTOR('',#63404,1.); #63404 = DIRECTION('',(0.E+000,-1.)); #63405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63406 = PCURVE('',#47183,#63407); -#63407 = DEFINITIONAL_REPRESENTATION('',(#63408),#63412); -#63408 = LINE('',#63409,#63410); -#63409 = CARTESIAN_POINT('',(1.25,0.92)); -#63410 = VECTOR('',#63411,1.); -#63411 = DIRECTION('',(1.,0.E+000)); -#63412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63413 = ADVANCED_FACE('',(#63414),#43765,.T.); -#63414 = FACE_BOUND('',#63415,.T.); -#63415 = EDGE_LOOP('',(#63416,#63417,#63437,#63438)); -#63416 = ORIENTED_EDGE('',*,*,#61991,.T.); -#63417 = ORIENTED_EDGE('',*,*,#63418,.T.); -#63418 = EDGE_CURVE('',#61992,#43721,#63419,.T.); -#63419 = SURFACE_CURVE('',#63420,(#63424,#63430),.PCURVE_S1.); -#63420 = LINE('',#63421,#63422); -#63421 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); -#63422 = VECTOR('',#63423,1.); -#63423 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63424 = PCURVE('',#43765,#63425); -#63425 = DEFINITIONAL_REPRESENTATION('',(#63426),#63429); -#63426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63427,#63428),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63427 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#63428 = CARTESIAN_POINT('',(3.14159265359,1.2)); -#63429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63430 = PCURVE('',#43736,#63431); -#63431 = DEFINITIONAL_REPRESENTATION('',(#63432),#63436); -#63432 = LINE('',#63433,#63434); -#63433 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63434 = VECTOR('',#63435,1.); -#63435 = DIRECTION('',(0.E+000,1.)); -#63436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63437 = ORIENTED_EDGE('',*,*,#43748,.F.); -#63438 = ORIENTED_EDGE('',*,*,#63236,.F.); -#63439 = ADVANCED_FACE('',(#63440),#43736,.T.); -#63440 = FACE_BOUND('',#63441,.F.); -#63441 = EDGE_LOOP('',(#63442,#63443,#63444,#63445)); -#63442 = ORIENTED_EDGE('',*,*,#62014,.F.); -#63443 = ORIENTED_EDGE('',*,*,#63418,.T.); -#63444 = ORIENTED_EDGE('',*,*,#43720,.T.); -#63445 = ORIENTED_EDGE('',*,*,#63446,.F.); -#63446 = EDGE_CURVE('',#62015,#43693,#63447,.T.); -#63447 = SURFACE_CURVE('',#63448,(#63452,#63459),.PCURVE_S1.); -#63448 = LINE('',#63449,#63450); -#63449 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-2.35)); -#63450 = VECTOR('',#63451,1.); -#63451 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63452 = PCURVE('',#43736,#63453); -#63453 = DEFINITIONAL_REPRESENTATION('',(#63454),#63458); -#63454 = LINE('',#63455,#63456); -#63455 = CARTESIAN_POINT('',(0.639375541595,0.E+000)); -#63456 = VECTOR('',#63457,1.); -#63457 = DIRECTION('',(0.E+000,1.)); -#63458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63459 = PCURVE('',#43709,#63460); -#63460 = DEFINITIONAL_REPRESENTATION('',(#63461),#63464); -#63461 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63462,#63463),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63462 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#63463 = CARTESIAN_POINT('',(3.14159265359,1.2)); -#63464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63465 = ADVANCED_FACE('',(#63466),#43709,.T.); -#63466 = FACE_BOUND('',#63467,.T.); -#63467 = EDGE_LOOP('',(#63468,#63469,#63489,#63490)); -#63468 = ORIENTED_EDGE('',*,*,#62037,.T.); -#63469 = ORIENTED_EDGE('',*,*,#63470,.T.); -#63470 = EDGE_CURVE('',#62038,#43665,#63471,.T.); -#63471 = SURFACE_CURVE('',#63472,(#63476,#63482),.PCURVE_S1.); +#63406 = ADVANCED_FACE('',(#63407),#62756,.T.); +#63407 = FACE_BOUND('',#63408,.F.); +#63408 = EDGE_LOOP('',(#63409,#63410,#63438,#63461,#63489,#63512)); +#63409 = ORIENTED_EDGE('',*,*,#62738,.T.); +#63410 = ORIENTED_EDGE('',*,*,#63411,.T.); +#63411 = EDGE_CURVE('',#62741,#63412,#63414,.T.); +#63412 = VERTEX_POINT('',#63413); +#63413 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); +#63414 = SURFACE_CURVE('',#63415,(#63419,#63426),.PCURVE_S1.); +#63415 = LINE('',#63416,#63417); +#63416 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); +#63417 = VECTOR('',#63418,1.); +#63418 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63419 = PCURVE('',#62756,#63420); +#63420 = DEFINITIONAL_REPRESENTATION('',(#63421),#63425); +#63421 = LINE('',#63422,#63423); +#63422 = CARTESIAN_POINT('',(0.172153903092,-0.615)); +#63423 = VECTOR('',#63424,1.); +#63424 = DIRECTION('',(1.,0.E+000)); +#63425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63426 = PCURVE('',#63427,#63432); +#63427 = PLANE('',#63428); +#63428 = AXIS2_PLACEMENT_3D('',#63429,#63430,#63431); +#63429 = CARTESIAN_POINT('',(1.175,0.E+000,0.E+000)); +#63430 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63431 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63432 = DEFINITIONAL_REPRESENTATION('',(#63433),#63437); +#63433 = LINE('',#63434,#63435); +#63434 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#63435 = VECTOR('',#63436,1.); +#63436 = DIRECTION('',(1.,0.E+000)); +#63437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63438 = ORIENTED_EDGE('',*,*,#63439,.T.); +#63439 = EDGE_CURVE('',#63412,#63440,#63442,.T.); +#63440 = VERTEX_POINT('',#63441); +#63441 = CARTESIAN_POINT('',(0.775,-1.105,-2.35)); +#63442 = SURFACE_CURVE('',#63443,(#63447,#63454),.PCURVE_S1.); +#63443 = LINE('',#63444,#63445); +#63444 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); +#63445 = VECTOR('',#63446,1.); +#63446 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63447 = PCURVE('',#62756,#63448); +#63448 = DEFINITIONAL_REPRESENTATION('',(#63449),#63453); +#63449 = LINE('',#63450,#63451); +#63450 = CARTESIAN_POINT('',(0.64,-0.615)); +#63451 = VECTOR('',#63452,1.); +#63452 = DIRECTION('',(0.E+000,-1.)); +#63453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63454 = PCURVE('',#45173,#63455); +#63455 = DEFINITIONAL_REPRESENTATION('',(#63456),#63460); +#63456 = LINE('',#63457,#63458); +#63457 = CARTESIAN_POINT('',(1.175,-1.105)); +#63458 = VECTOR('',#63459,1.); +#63459 = DIRECTION('',(-1.,0.E+000)); +#63460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63461 = ORIENTED_EDGE('',*,*,#63462,.T.); +#63462 = EDGE_CURVE('',#63440,#63463,#63465,.T.); +#63463 = VERTEX_POINT('',#63464); +#63464 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); +#63465 = SURFACE_CURVE('',#63466,(#63470,#63477),.PCURVE_S1.); +#63466 = LINE('',#63467,#63468); +#63467 = CARTESIAN_POINT('',(0.775,-1.105,-2.35)); +#63468 = VECTOR('',#63469,1.); +#63469 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63470 = PCURVE('',#62756,#63471); +#63471 = DEFINITIONAL_REPRESENTATION('',(#63472),#63476); #63472 = LINE('',#63473,#63474); -#63473 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); +#63473 = CARTESIAN_POINT('',(0.64,-1.015)); #63474 = VECTOR('',#63475,1.); -#63475 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63476 = PCURVE('',#43709,#63477); -#63477 = DEFINITIONAL_REPRESENTATION('',(#63478),#63481); -#63478 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63479,#63480),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63479 = CARTESIAN_POINT('',(3.926990816986,0.E+000)); -#63480 = CARTESIAN_POINT('',(3.926990816986,1.2)); -#63481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#63475 = DIRECTION('',(-1.,0.E+000)); +#63476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63482 = PCURVE('',#43680,#63483); +#63477 = PCURVE('',#63478,#63483); +#63478 = PLANE('',#63479); +#63479 = AXIS2_PLACEMENT_3D('',#63480,#63481,#63482); +#63480 = CARTESIAN_POINT('',(0.775,0.E+000,0.E+000)); +#63481 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63482 = DIRECTION('',(0.E+000,0.E+000,-1.)); #63483 = DEFINITIONAL_REPRESENTATION('',(#63484),#63488); #63484 = LINE('',#63485,#63486); -#63485 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#63485 = CARTESIAN_POINT('',(2.35,-1.105)); #63486 = VECTOR('',#63487,1.); -#63487 = DIRECTION('',(0.E+000,1.)); +#63487 = DIRECTION('',(-1.,0.E+000)); #63488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63489 = ORIENTED_EDGE('',*,*,#43692,.F.); -#63490 = ORIENTED_EDGE('',*,*,#63446,.F.); -#63491 = ADVANCED_FACE('',(#63492),#43680,.T.); -#63492 = FACE_BOUND('',#63493,.F.); -#63493 = EDGE_LOOP('',(#63494,#63495,#63496,#63497,#63498)); -#63494 = ORIENTED_EDGE('',*,*,#63159,.T.); -#63495 = ORIENTED_EDGE('',*,*,#62060,.F.); -#63496 = ORIENTED_EDGE('',*,*,#63470,.T.); -#63497 = ORIENTED_EDGE('',*,*,#43664,.T.); -#63498 = ORIENTED_EDGE('',*,*,#63499,.F.); -#63499 = EDGE_CURVE('',#63160,#43642,#63500,.T.); -#63500 = SURFACE_CURVE('',#63501,(#63505,#63512),.PCURVE_S1.); -#63501 = LINE('',#63502,#63503); -#63502 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); -#63503 = VECTOR('',#63504,1.); -#63504 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63505 = PCURVE('',#43680,#63506); +#63489 = ORIENTED_EDGE('',*,*,#63490,.F.); +#63490 = EDGE_CURVE('',#63491,#63463,#63493,.T.); +#63491 = VERTEX_POINT('',#63492); +#63492 = CARTESIAN_POINT('',(0.775,-1.105,-1.71)); +#63493 = SURFACE_CURVE('',#63494,(#63498,#63505),.PCURVE_S1.); +#63494 = LINE('',#63495,#63496); +#63495 = CARTESIAN_POINT('',(0.775,-1.105,-1.71)); +#63496 = VECTOR('',#63497,1.); +#63497 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63498 = PCURVE('',#62756,#63499); +#63499 = DEFINITIONAL_REPRESENTATION('',(#63500),#63504); +#63500 = LINE('',#63501,#63502); +#63501 = CARTESIAN_POINT('',(0.E+000,-1.015)); +#63502 = VECTOR('',#63503,1.); +#63503 = DIRECTION('',(1.,0.E+000)); +#63504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63505 = PCURVE('',#62203,#63506); #63506 = DEFINITIONAL_REPRESENTATION('',(#63507),#63511); #63507 = LINE('',#63508,#63509); -#63508 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); +#63508 = CARTESIAN_POINT('',(1.71,-1.105)); #63509 = VECTOR('',#63510,1.); -#63510 = DIRECTION('',(0.E+000,1.)); +#63510 = DIRECTION('',(1.,0.E+000)); #63511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63512 = PCURVE('',#43123,#63513); -#63513 = DEFINITIONAL_REPRESENTATION('',(#63514),#63517); -#63514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63515,#63516),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63515 = CARTESIAN_POINT('',(3.926990816989,0.E+000)); -#63516 = CARTESIAN_POINT('',(3.926990816989,1.2)); -#63517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63518 = ADVANCED_FACE('',(#63519),#43123,.T.); -#63519 = FACE_BOUND('',#63520,.T.); -#63520 = EDGE_LOOP('',(#63521,#63522,#63523,#63524)); -#63521 = ORIENTED_EDGE('',*,*,#63182,.T.); -#63522 = ORIENTED_EDGE('',*,*,#43107,.T.); -#63523 = ORIENTED_EDGE('',*,*,#43641,.F.); -#63524 = ORIENTED_EDGE('',*,*,#63499,.F.); -#63525 = ADVANCED_FACE('',(#63526),#61956,.F.); -#63526 = FACE_BOUND('',#63527,.F.); -#63527 = EDGE_LOOP('',(#63528,#63529,#63552,#63573)); -#63528 = ORIENTED_EDGE('',*,*,#61940,.T.); -#63529 = ORIENTED_EDGE('',*,*,#63530,.T.); -#63530 = EDGE_CURVE('',#61918,#63531,#63533,.T.); -#63531 = VERTEX_POINT('',#63532); -#63532 = CARTESIAN_POINT('',(-2.37,0.5,-1.63)); -#63533 = SURFACE_CURVE('',#63534,(#63538,#63545),.PCURVE_S1.); -#63534 = LINE('',#63535,#63536); -#63535 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); -#63536 = VECTOR('',#63537,1.); -#63537 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63538 = PCURVE('',#61956,#63539); -#63539 = DEFINITIONAL_REPRESENTATION('',(#63540),#63544); -#63540 = LINE('',#63541,#63542); -#63541 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63542 = VECTOR('',#63543,1.); -#63543 = DIRECTION('',(0.E+000,-1.)); -#63544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63545 = PCURVE('',#52252,#63546); -#63546 = DEFINITIONAL_REPRESENTATION('',(#63547),#63551); -#63547 = LINE('',#63548,#63549); -#63548 = CARTESIAN_POINT('',(1.16,0.E+000)); -#63549 = VECTOR('',#63550,1.); -#63550 = DIRECTION('',(0.E+000,-1.)); -#63551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63552 = ORIENTED_EDGE('',*,*,#63553,.T.); -#63553 = EDGE_CURVE('',#63531,#63258,#63554,.T.); -#63554 = SURFACE_CURVE('',#63555,(#63559,#63566),.PCURVE_S1.); -#63555 = LINE('',#63556,#63557); -#63556 = CARTESIAN_POINT('',(-2.37,0.5,-1.63)); -#63557 = VECTOR('',#63558,1.); -#63558 = DIRECTION('',(0.E+000,1.,0.E+000)); -#63559 = PCURVE('',#61956,#63560); -#63560 = DEFINITIONAL_REPRESENTATION('',(#63561),#63565); -#63561 = LINE('',#63562,#63563); -#63562 = CARTESIAN_POINT('',(0.E+000,-0.72)); -#63563 = VECTOR('',#63564,1.); -#63564 = DIRECTION('',(1.,0.E+000)); -#63565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63566 = PCURVE('',#52224,#63567); -#63567 = DEFINITIONAL_REPRESENTATION('',(#63568),#63572); -#63568 = LINE('',#63569,#63570); -#63569 = CARTESIAN_POINT('',(2.37,0.5)); -#63570 = VECTOR('',#63571,1.); -#63571 = DIRECTION('',(0.E+000,1.)); -#63572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63573 = ORIENTED_EDGE('',*,*,#63257,.F.); -#63574 = ADVANCED_FACE('',(#63575),#52252,.F.); -#63575 = FACE_BOUND('',#63576,.F.); -#63576 = EDGE_LOOP('',(#63577,#63578,#63579,#63600,#63601)); -#63577 = ORIENTED_EDGE('',*,*,#62988,.F.); -#63578 = ORIENTED_EDGE('',*,*,#52236,.T.); -#63579 = ORIENTED_EDGE('',*,*,#63580,.T.); -#63580 = EDGE_CURVE('',#52209,#63531,#63581,.T.); -#63581 = SURFACE_CURVE('',#63582,(#63586,#63593),.PCURVE_S1.); -#63582 = LINE('',#63583,#63584); -#63583 = CARTESIAN_POINT('',(-1.21,0.5,-1.63)); -#63584 = VECTOR('',#63585,1.); -#63585 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63586 = PCURVE('',#52252,#63587); -#63587 = DEFINITIONAL_REPRESENTATION('',(#63588),#63592); +#63512 = ORIENTED_EDGE('',*,*,#63513,.F.); +#63513 = EDGE_CURVE('',#62739,#63491,#63514,.T.); +#63514 = SURFACE_CURVE('',#63515,(#63519,#63526),.PCURVE_S1.); +#63515 = LINE('',#63516,#63517); +#63516 = CARTESIAN_POINT('',(1.175,-1.105,-1.71)); +#63517 = VECTOR('',#63518,1.); +#63518 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63519 = PCURVE('',#62756,#63520); +#63520 = DEFINITIONAL_REPRESENTATION('',(#63521),#63525); +#63521 = LINE('',#63522,#63523); +#63522 = CARTESIAN_POINT('',(0.E+000,-0.615)); +#63523 = VECTOR('',#63524,1.); +#63524 = DIRECTION('',(0.E+000,-1.)); +#63525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63526 = PCURVE('',#62175,#63527); +#63527 = DEFINITIONAL_REPRESENTATION('',(#63528),#63532); +#63528 = LINE('',#63529,#63530); +#63529 = CARTESIAN_POINT('',(0.12,-0.615)); +#63530 = VECTOR('',#63531,1.); +#63531 = DIRECTION('',(0.E+000,-1.)); +#63532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63533 = ADVANCED_FACE('',(#63534),#45201,.T.); +#63534 = FACE_BOUND('',#63535,.F.); +#63535 = EDGE_LOOP('',(#63536,#63561,#63582,#63583,#63606)); +#63536 = ORIENTED_EDGE('',*,*,#63537,.F.); +#63537 = EDGE_CURVE('',#63538,#63540,#63542,.T.); +#63538 = VERTEX_POINT('',#63539); +#63539 = CARTESIAN_POINT('',(1.425,-1.105,-1.71)); +#63540 = VERTEX_POINT('',#63541); +#63541 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); +#63542 = SURFACE_CURVE('',#63543,(#63547,#63554),.PCURVE_S1.); +#63543 = LINE('',#63544,#63545); +#63544 = CARTESIAN_POINT('',(1.425,-1.105,-1.71)); +#63545 = VECTOR('',#63546,1.); +#63546 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63547 = PCURVE('',#45201,#63548); +#63548 = DEFINITIONAL_REPRESENTATION('',(#63549),#63553); +#63549 = LINE('',#63550,#63551); +#63550 = CARTESIAN_POINT('',(0.E+000,-0.365)); +#63551 = VECTOR('',#63552,1.); +#63552 = DIRECTION('',(1.,0.E+000)); +#63553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63554 = PCURVE('',#62697,#63555); +#63555 = DEFINITIONAL_REPRESENTATION('',(#63556),#63560); +#63556 = LINE('',#63557,#63558); +#63557 = CARTESIAN_POINT('',(1.71,-1.105)); +#63558 = VECTOR('',#63559,1.); +#63559 = DIRECTION('',(1.,0.E+000)); +#63560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63561 = ORIENTED_EDGE('',*,*,#63562,.F.); +#63562 = EDGE_CURVE('',#45186,#63538,#63563,.T.); +#63563 = SURFACE_CURVE('',#63564,(#63568,#63575),.PCURVE_S1.); +#63564 = LINE('',#63565,#63566); +#63565 = CARTESIAN_POINT('',(1.79,-1.105,-1.71)); +#63566 = VECTOR('',#63567,1.); +#63567 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63568 = PCURVE('',#45201,#63569); +#63569 = DEFINITIONAL_REPRESENTATION('',(#63570),#63574); +#63570 = LINE('',#63571,#63572); +#63571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#63572 = VECTOR('',#63573,1.); +#63573 = DIRECTION('',(0.E+000,-1.)); +#63574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63575 = PCURVE('',#45229,#63576); +#63576 = DEFINITIONAL_REPRESENTATION('',(#63577),#63581); +#63577 = LINE('',#63578,#63579); +#63578 = CARTESIAN_POINT('',(0.12,0.E+000)); +#63579 = VECTOR('',#63580,1.); +#63580 = DIRECTION('',(0.E+000,-1.)); +#63581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63582 = ORIENTED_EDGE('',*,*,#45185,.T.); +#63583 = ORIENTED_EDGE('',*,*,#63584,.T.); +#63584 = EDGE_CURVE('',#45158,#63585,#63587,.T.); +#63585 = VERTEX_POINT('',#63586); +#63586 = CARTESIAN_POINT('',(1.425,-1.105,-2.35)); +#63587 = SURFACE_CURVE('',#63588,(#63592,#63599),.PCURVE_S1.); #63588 = LINE('',#63589,#63590); -#63589 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#63589 = CARTESIAN_POINT('',(1.79,-1.105,-2.35)); #63590 = VECTOR('',#63591,1.); -#63591 = DIRECTION('',(1.,0.E+000)); -#63592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63593 = PCURVE('',#52224,#63594); -#63594 = DEFINITIONAL_REPRESENTATION('',(#63595),#63599); -#63595 = LINE('',#63596,#63597); -#63596 = CARTESIAN_POINT('',(1.21,0.5)); -#63597 = VECTOR('',#63598,1.); -#63598 = DIRECTION('',(1.,0.E+000)); -#63599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63600 = ORIENTED_EDGE('',*,*,#63530,.F.); -#63601 = ORIENTED_EDGE('',*,*,#61917,.F.); -#63602 = ADVANCED_FACE('',(#63603),#51673,.T.); -#63603 = FACE_BOUND('',#63604,.F.); -#63604 = EDGE_LOOP('',(#63605,#63606,#63607,#63630)); -#63605 = ORIENTED_EDGE('',*,*,#63304,.T.); -#63606 = ORIENTED_EDGE('',*,*,#51657,.F.); -#63607 = ORIENTED_EDGE('',*,*,#63608,.F.); -#63608 = EDGE_CURVE('',#63609,#51630,#63611,.T.); -#63609 = VERTEX_POINT('',#63610); -#63610 = CARTESIAN_POINT('',(2.37,0.5,-1.63)); -#63611 = SURFACE_CURVE('',#63612,(#63616,#63623),.PCURVE_S1.); -#63612 = LINE('',#63613,#63614); -#63613 = CARTESIAN_POINT('',(2.37,0.5,-1.63)); -#63614 = VECTOR('',#63615,1.); -#63615 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#63616 = PCURVE('',#51673,#63617); -#63617 = DEFINITIONAL_REPRESENTATION('',(#63618),#63622); -#63618 = LINE('',#63619,#63620); -#63619 = CARTESIAN_POINT('',(-2.37,0.5)); -#63620 = VECTOR('',#63621,1.); -#63621 = DIRECTION('',(1.,0.E+000)); -#63622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63623 = PCURVE('',#51645,#63624); -#63624 = DEFINITIONAL_REPRESENTATION('',(#63625),#63629); -#63625 = LINE('',#63626,#63627); -#63626 = CARTESIAN_POINT('',(0.E+000,-0.72)); -#63627 = VECTOR('',#63628,1.); -#63628 = DIRECTION('',(1.,0.E+000)); -#63629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63630 = ORIENTED_EDGE('',*,*,#63631,.F.); -#63631 = EDGE_CURVE('',#63305,#63609,#63632,.T.); -#63632 = SURFACE_CURVE('',#63633,(#63637,#63644),.PCURVE_S1.); -#63633 = LINE('',#63634,#63635); -#63634 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); -#63635 = VECTOR('',#63636,1.); -#63636 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63637 = PCURVE('',#51673,#63638); -#63638 = DEFINITIONAL_REPRESENTATION('',(#63639),#63643); +#63591 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#63592 = PCURVE('',#45201,#63593); +#63593 = DEFINITIONAL_REPRESENTATION('',(#63594),#63598); +#63594 = LINE('',#63595,#63596); +#63595 = CARTESIAN_POINT('',(0.64,0.E+000)); +#63596 = VECTOR('',#63597,1.); +#63597 = DIRECTION('',(0.E+000,-1.)); +#63598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63599 = PCURVE('',#45173,#63600); +#63600 = DEFINITIONAL_REPRESENTATION('',(#63601),#63605); +#63601 = LINE('',#63602,#63603); +#63602 = CARTESIAN_POINT('',(1.79,-1.105)); +#63603 = VECTOR('',#63604,1.); +#63604 = DIRECTION('',(-1.,0.E+000)); +#63605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63606 = ORIENTED_EDGE('',*,*,#63607,.T.); +#63607 = EDGE_CURVE('',#63585,#63540,#63608,.T.); +#63608 = SURFACE_CURVE('',#63609,(#63613,#63620),.PCURVE_S1.); +#63609 = LINE('',#63610,#63611); +#63610 = CARTESIAN_POINT('',(1.425,-1.105,-2.35)); +#63611 = VECTOR('',#63612,1.); +#63612 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63613 = PCURVE('',#45201,#63614); +#63614 = DEFINITIONAL_REPRESENTATION('',(#63615),#63619); +#63615 = LINE('',#63616,#63617); +#63616 = CARTESIAN_POINT('',(0.64,-0.365)); +#63617 = VECTOR('',#63618,1.); +#63618 = DIRECTION('',(-1.,0.E+000)); +#63619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63620 = PCURVE('',#63621,#63626); +#63621 = PLANE('',#63622); +#63622 = AXIS2_PLACEMENT_3D('',#63623,#63624,#63625); +#63623 = CARTESIAN_POINT('',(1.425,0.E+000,0.E+000)); +#63624 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63625 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63626 = DEFINITIONAL_REPRESENTATION('',(#63627),#63631); +#63627 = LINE('',#63628,#63629); +#63628 = CARTESIAN_POINT('',(2.35,-1.105)); +#63629 = VECTOR('',#63630,1.); +#63630 = DIRECTION('',(-1.,0.E+000)); +#63631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63632 = ADVANCED_FACE('',(#63633),#62595,.T.); +#63633 = FACE_BOUND('',#63634,.F.); +#63634 = EDGE_LOOP('',(#63635,#63636,#63657,#63658)); +#63635 = ORIENTED_EDGE('',*,*,#62814,.F.); +#63636 = ORIENTED_EDGE('',*,*,#63637,.F.); +#63637 = EDGE_CURVE('',#62580,#62815,#63638,.T.); +#63638 = SURFACE_CURVE('',#63639,(#63643,#63650),.PCURVE_S1.); #63639 = LINE('',#63640,#63641); -#63640 = CARTESIAN_POINT('',(-2.37,0.92)); +#63640 = CARTESIAN_POINT('',(-1.425,-0.985,-1.71)); #63641 = VECTOR('',#63642,1.); -#63642 = DIRECTION('',(0.E+000,-1.)); -#63643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63644 = PCURVE('',#61778,#63645); -#63645 = DEFINITIONAL_REPRESENTATION('',(#63646),#63650); -#63646 = LINE('',#63647,#63648); -#63647 = CARTESIAN_POINT('',(0.E+000,-0.72)); -#63648 = VECTOR('',#63649,1.); -#63649 = DIRECTION('',(1.,0.E+000)); -#63650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63651 = ADVANCED_FACE('',(#63652),#52224,.T.); -#63652 = FACE_BOUND('',#63653,.F.); -#63653 = EDGE_LOOP('',(#63654,#63655,#63656,#63657)); -#63654 = ORIENTED_EDGE('',*,*,#63280,.T.); -#63655 = ORIENTED_EDGE('',*,*,#63553,.F.); -#63656 = ORIENTED_EDGE('',*,*,#63580,.F.); -#63657 = ORIENTED_EDGE('',*,*,#52208,.F.); -#63658 = ADVANCED_FACE('',(#63659),#51645,.F.); -#63659 = FACE_BOUND('',#63660,.F.); -#63660 = EDGE_LOOP('',(#63661,#63662,#63663,#63684,#63685)); -#63661 = ORIENTED_EDGE('',*,*,#62961,.F.); -#63662 = ORIENTED_EDGE('',*,*,#61790,.F.); -#63663 = ORIENTED_EDGE('',*,*,#63664,.T.); -#63664 = EDGE_CURVE('',#61763,#63609,#63665,.T.); -#63665 = SURFACE_CURVE('',#63666,(#63670,#63677),.PCURVE_S1.); -#63666 = LINE('',#63667,#63668); -#63667 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); -#63668 = VECTOR('',#63669,1.); -#63669 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63670 = PCURVE('',#51645,#63671); -#63671 = DEFINITIONAL_REPRESENTATION('',(#63672),#63676); -#63672 = LINE('',#63673,#63674); -#63673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63674 = VECTOR('',#63675,1.); -#63675 = DIRECTION('',(0.E+000,-1.)); -#63676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63677 = PCURVE('',#61778,#63678); -#63678 = DEFINITIONAL_REPRESENTATION('',(#63679),#63683); -#63679 = LINE('',#63680,#63681); -#63680 = CARTESIAN_POINT('',(0.42,0.E+000)); -#63681 = VECTOR('',#63682,1.); -#63682 = DIRECTION('',(0.E+000,-1.)); -#63683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63684 = ORIENTED_EDGE('',*,*,#63608,.T.); -#63685 = ORIENTED_EDGE('',*,*,#51629,.F.); -#63686 = ADVANCED_FACE('',(#63687),#61778,.F.); -#63687 = FACE_BOUND('',#63688,.F.); -#63688 = EDGE_LOOP('',(#63689,#63690,#63691,#63692)); -#63689 = ORIENTED_EDGE('',*,*,#61762,.F.); -#63690 = ORIENTED_EDGE('',*,*,#63327,.T.); -#63691 = ORIENTED_EDGE('',*,*,#63631,.T.); -#63692 = ORIENTED_EDGE('',*,*,#63664,.F.); -#63693 = ADVANCED_FACE('',(#63694),#43429,.T.); -#63694 = FACE_BOUND('',#63695,.T.); -#63695 = EDGE_LOOP('',(#63696,#63697,#63698,#63699)); -#63696 = ORIENTED_EDGE('',*,*,#61716,.T.); -#63697 = ORIENTED_EDGE('',*,*,#63349,.T.); -#63698 = ORIENTED_EDGE('',*,*,#43412,.F.); -#63699 = ORIENTED_EDGE('',*,*,#63700,.F.); -#63700 = EDGE_CURVE('',#61694,#43413,#63701,.T.); -#63701 = SURFACE_CURVE('',#63702,(#63706,#63712),.PCURVE_S1.); -#63702 = LINE('',#63703,#63704); -#63703 = CARTESIAN_POINT('',(3.445,0.57,-2.35)); -#63704 = VECTOR('',#63705,1.); -#63705 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63706 = PCURVE('',#43429,#63707); -#63707 = DEFINITIONAL_REPRESENTATION('',(#63708),#63711); -#63708 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63709,#63710),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63710 = CARTESIAN_POINT('',(0.E+000,1.2)); -#63711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63712 = PCURVE('',#43456,#63713); -#63713 = DEFINITIONAL_REPRESENTATION('',(#63714),#63718); -#63714 = LINE('',#63715,#63716); -#63715 = CARTESIAN_POINT('',(0.639375541595,0.E+000)); -#63716 = VECTOR('',#63717,1.); -#63717 = DIRECTION('',(0.E+000,1.)); -#63718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63719 = ADVANCED_FACE('',(#63720),#43456,.T.); -#63720 = FACE_BOUND('',#63721,.F.); -#63721 = EDGE_LOOP('',(#63722,#63723,#63743,#63744)); -#63722 = ORIENTED_EDGE('',*,*,#61693,.F.); -#63723 = ORIENTED_EDGE('',*,*,#63724,.T.); -#63724 = EDGE_CURVE('',#61671,#43441,#63725,.T.); -#63725 = SURFACE_CURVE('',#63726,(#63730,#63737),.PCURVE_S1.); -#63726 = LINE('',#63727,#63728); -#63727 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); -#63728 = VECTOR('',#63729,1.); -#63729 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63730 = PCURVE('',#43456,#63731); -#63731 = DEFINITIONAL_REPRESENTATION('',(#63732),#63736); -#63732 = LINE('',#63733,#63734); -#63733 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63734 = VECTOR('',#63735,1.); -#63735 = DIRECTION('',(0.E+000,1.)); -#63736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63737 = PCURVE('',#43485,#63738); -#63738 = DEFINITIONAL_REPRESENTATION('',(#63739),#63742); -#63739 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63740,#63741),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63740 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#63741 = CARTESIAN_POINT('',(6.28318530718,1.2)); -#63742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63743 = ORIENTED_EDGE('',*,*,#43440,.T.); -#63744 = ORIENTED_EDGE('',*,*,#63700,.F.); -#63745 = ADVANCED_FACE('',(#63746),#43485,.T.); -#63746 = FACE_BOUND('',#63747,.T.); -#63747 = EDGE_LOOP('',(#63748,#63749,#63750,#63751)); -#63748 = ORIENTED_EDGE('',*,*,#61670,.T.); -#63749 = ORIENTED_EDGE('',*,*,#63724,.T.); -#63750 = ORIENTED_EDGE('',*,*,#43468,.F.); -#63751 = ORIENTED_EDGE('',*,*,#63752,.F.); -#63752 = EDGE_CURVE('',#61648,#43469,#63753,.T.); -#63753 = SURFACE_CURVE('',#63754,(#63758,#63764),.PCURVE_S1.); -#63754 = LINE('',#63755,#63756); -#63755 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-2.35)); -#63756 = VECTOR('',#63757,1.); -#63757 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63758 = PCURVE('',#43485,#63759); -#63759 = DEFINITIONAL_REPRESENTATION('',(#63760),#63763); -#63760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63761,#63762),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63761 = CARTESIAN_POINT('',(5.497787143783,0.E+000)); -#63762 = CARTESIAN_POINT('',(5.497787143783,1.2)); -#63763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63764 = PCURVE('',#43512,#63765); -#63765 = DEFINITIONAL_REPRESENTATION('',(#63766),#63770); -#63766 = LINE('',#63767,#63768); -#63767 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); -#63768 = VECTOR('',#63769,1.); -#63769 = DIRECTION('',(0.E+000,1.)); -#63770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63771 = ADVANCED_FACE('',(#63772),#43512,.T.); -#63772 = FACE_BOUND('',#63773,.F.); -#63773 = EDGE_LOOP('',(#63774,#63775,#63795,#63796,#63797)); -#63774 = ORIENTED_EDGE('',*,*,#63083,.F.); -#63775 = ORIENTED_EDGE('',*,*,#63776,.T.); -#63776 = EDGE_CURVE('',#63057,#43497,#63777,.T.); -#63777 = SURFACE_CURVE('',#63778,(#63782,#63789),.PCURVE_S1.); -#63778 = LINE('',#63779,#63780); -#63779 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); -#63780 = VECTOR('',#63781,1.); -#63781 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63782 = PCURVE('',#43512,#63783); -#63783 = DEFINITIONAL_REPRESENTATION('',(#63784),#63788); -#63784 = LINE('',#63785,#63786); -#63785 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63786 = VECTOR('',#63787,1.); -#63787 = DIRECTION('',(0.E+000,1.)); -#63788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63789 = PCURVE('',#42963,#63790); -#63790 = DEFINITIONAL_REPRESENTATION('',(#63791),#63794); -#63791 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63792,#63793),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); -#63792 = CARTESIAN_POINT('',(5.49778714378,0.E+000)); -#63793 = CARTESIAN_POINT('',(5.49778714378,1.2)); -#63794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63795 = ORIENTED_EDGE('',*,*,#43496,.T.); -#63796 = ORIENTED_EDGE('',*,*,#63752,.F.); -#63797 = ORIENTED_EDGE('',*,*,#61647,.F.); -#63798 = ADVANCED_FACE('',(#63799),#42963,.T.); -#63799 = FACE_BOUND('',#63800,.T.); -#63800 = EDGE_LOOP('',(#63801,#63802,#63803,#63804)); -#63801 = ORIENTED_EDGE('',*,*,#63056,.T.); -#63802 = ORIENTED_EDGE('',*,*,#63776,.T.); -#63803 = ORIENTED_EDGE('',*,*,#43524,.F.); -#63804 = ORIENTED_EDGE('',*,*,#42947,.F.); -#63805 = ADVANCED_FACE('',(#63806),#43372,.T.); -#63806 = FACE_BOUND('',#63807,.F.); -#63807 = EDGE_LOOP('',(#63808,#63831,#63832,#63833,#63834)); -#63808 = ORIENTED_EDGE('',*,*,#63809,.F.); -#63809 = EDGE_CURVE('',#63371,#63810,#63812,.T.); -#63810 = VERTEX_POINT('',#63811); -#63811 = CARTESIAN_POINT('',(0.41,0.773013158464,-1.25)); -#63812 = SURFACE_CURVE('',#63813,(#63817,#63824),.PCURVE_S1.); -#63813 = LINE('',#63814,#63815); -#63814 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); -#63815 = VECTOR('',#63816,1.); -#63816 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63817 = PCURVE('',#43372,#63818); +#63642 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63643 = PCURVE('',#62595,#63644); +#63644 = DEFINITIONAL_REPRESENTATION('',(#63645),#63649); +#63645 = LINE('',#63646,#63647); +#63646 = CARTESIAN_POINT('',(1.71,-0.985)); +#63647 = VECTOR('',#63648,1.); +#63648 = DIRECTION('',(0.E+000,-1.)); +#63649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63650 = PCURVE('',#62623,#63651); +#63651 = DEFINITIONAL_REPRESENTATION('',(#63652),#63656); +#63652 = LINE('',#63653,#63654); +#63653 = CARTESIAN_POINT('',(0.E+000,-3.215)); +#63654 = VECTOR('',#63655,1.); +#63655 = DIRECTION('',(1.,0.E+000)); +#63656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63657 = ORIENTED_EDGE('',*,*,#62579,.F.); +#63658 = ORIENTED_EDGE('',*,*,#63659,.F.); +#63659 = EDGE_CURVE('',#62817,#62552,#63660,.T.); +#63660 = SURFACE_CURVE('',#63661,(#63665,#63672),.PCURVE_S1.); +#63661 = LINE('',#63662,#63663); +#63662 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); +#63663 = VECTOR('',#63664,1.); +#63664 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#63665 = PCURVE('',#62595,#63666); +#63666 = DEFINITIONAL_REPRESENTATION('',(#63667),#63671); +#63667 = LINE('',#63668,#63669); +#63668 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#63669 = VECTOR('',#63670,1.); +#63670 = DIRECTION('',(-0.258819045102,0.965925826289)); +#63671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63672 = PCURVE('',#62567,#63673); +#63673 = DEFINITIONAL_REPRESENTATION('',(#63674),#63678); +#63674 = LINE('',#63675,#63676); +#63675 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#63676 = VECTOR('',#63677,1.); +#63677 = DIRECTION('',(-1.,0.E+000)); +#63678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63679 = ADVANCED_FACE('',(#63680),#62623,.T.); +#63680 = FACE_BOUND('',#63681,.F.); +#63681 = EDGE_LOOP('',(#63682,#63683,#63684,#63705)); +#63682 = ORIENTED_EDGE('',*,*,#63637,.T.); +#63683 = ORIENTED_EDGE('',*,*,#62918,.T.); +#63684 = ORIENTED_EDGE('',*,*,#63685,.F.); +#63685 = EDGE_CURVE('',#62608,#62896,#63686,.T.); +#63686 = SURFACE_CURVE('',#63687,(#63691,#63698),.PCURVE_S1.); +#63687 = LINE('',#63688,#63689); +#63688 = CARTESIAN_POINT('',(-1.79,-0.985,-1.71)); +#63689 = VECTOR('',#63690,1.); +#63690 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63691 = PCURVE('',#62623,#63692); +#63692 = DEFINITIONAL_REPRESENTATION('',(#63693),#63697); +#63693 = LINE('',#63694,#63695); +#63694 = CARTESIAN_POINT('',(0.E+000,-3.58)); +#63695 = VECTOR('',#63696,1.); +#63696 = DIRECTION('',(1.,0.E+000)); +#63697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63698 = PCURVE('',#44262,#63699); +#63699 = DEFINITIONAL_REPRESENTATION('',(#63700),#63704); +#63700 = LINE('',#63701,#63702); +#63701 = CARTESIAN_POINT('',(0.5,-0.24)); +#63702 = VECTOR('',#63703,1.); +#63703 = DIRECTION('',(0.E+000,1.)); +#63704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63705 = ORIENTED_EDGE('',*,*,#62607,.F.); +#63706 = ADVANCED_FACE('',(#63707),#62511,.T.); +#63707 = FACE_BOUND('',#63708,.F.); +#63708 = EDGE_LOOP('',(#63709,#63730,#63731,#63752)); +#63709 = ORIENTED_EDGE('',*,*,#63710,.T.); +#63710 = EDGE_CURVE('',#62468,#62943,#63711,.T.); +#63711 = SURFACE_CURVE('',#63712,(#63716,#63723),.PCURVE_S1.); +#63712 = LINE('',#63713,#63714); +#63713 = CARTESIAN_POINT('',(-0.775,-0.985,-1.71)); +#63714 = VECTOR('',#63715,1.); +#63715 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63716 = PCURVE('',#62511,#63717); +#63717 = DEFINITIONAL_REPRESENTATION('',(#63718),#63722); +#63718 = LINE('',#63719,#63720); +#63719 = CARTESIAN_POINT('',(0.E+000,-2.565)); +#63720 = VECTOR('',#63721,1.); +#63721 = DIRECTION('',(1.,0.E+000)); +#63722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63723 = PCURVE('',#62483,#63724); +#63724 = DEFINITIONAL_REPRESENTATION('',(#63725),#63729); +#63725 = LINE('',#63726,#63727); +#63726 = CARTESIAN_POINT('',(1.71,-0.985)); +#63727 = VECTOR('',#63728,1.); +#63728 = DIRECTION('',(0.E+000,-1.)); +#63729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63730 = ORIENTED_EDGE('',*,*,#63074,.T.); +#63731 = ORIENTED_EDGE('',*,*,#63732,.F.); +#63732 = EDGE_CURVE('',#62496,#63052,#63733,.T.); +#63733 = SURFACE_CURVE('',#63734,(#63738,#63745),.PCURVE_S1.); +#63734 = LINE('',#63735,#63736); +#63735 = CARTESIAN_POINT('',(-1.175,-0.985,-1.71)); +#63736 = VECTOR('',#63737,1.); +#63737 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63738 = PCURVE('',#62511,#63739); +#63739 = DEFINITIONAL_REPRESENTATION('',(#63740),#63744); +#63740 = LINE('',#63741,#63742); +#63741 = CARTESIAN_POINT('',(0.E+000,-2.965)); +#63742 = VECTOR('',#63743,1.); +#63743 = DIRECTION('',(1.,0.E+000)); +#63744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63745 = PCURVE('',#62539,#63746); +#63746 = DEFINITIONAL_REPRESENTATION('',(#63747),#63751); +#63747 = LINE('',#63748,#63749); +#63748 = CARTESIAN_POINT('',(1.71,-0.985)); +#63749 = VECTOR('',#63750,1.); +#63750 = DIRECTION('',(0.E+000,-1.)); +#63751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63752 = ORIENTED_EDGE('',*,*,#62495,.F.); +#63753 = ADVANCED_FACE('',(#63754),#62399,.T.); +#63754 = FACE_BOUND('',#63755,.F.); +#63755 = EDGE_LOOP('',(#63756,#63777,#63778,#63799)); +#63756 = ORIENTED_EDGE('',*,*,#63757,.T.); +#63757 = EDGE_CURVE('',#62356,#63099,#63758,.T.); +#63758 = SURFACE_CURVE('',#63759,(#63763,#63770),.PCURVE_S1.); +#63759 = LINE('',#63760,#63761); +#63760 = CARTESIAN_POINT('',(-0.125,-0.985,-1.71)); +#63761 = VECTOR('',#63762,1.); +#63762 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63763 = PCURVE('',#62399,#63764); +#63764 = DEFINITIONAL_REPRESENTATION('',(#63765),#63769); +#63765 = LINE('',#63766,#63767); +#63766 = CARTESIAN_POINT('',(0.E+000,-1.915)); +#63767 = VECTOR('',#63768,1.); +#63768 = DIRECTION('',(1.,0.E+000)); +#63769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63770 = PCURVE('',#62371,#63771); +#63771 = DEFINITIONAL_REPRESENTATION('',(#63772),#63776); +#63772 = LINE('',#63773,#63774); +#63773 = CARTESIAN_POINT('',(1.71,-0.985)); +#63774 = VECTOR('',#63775,1.); +#63775 = DIRECTION('',(0.E+000,-1.)); +#63776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63777 = ORIENTED_EDGE('',*,*,#63230,.T.); +#63778 = ORIENTED_EDGE('',*,*,#63779,.F.); +#63779 = EDGE_CURVE('',#62384,#63208,#63780,.T.); +#63780 = SURFACE_CURVE('',#63781,(#63785,#63792),.PCURVE_S1.); +#63781 = LINE('',#63782,#63783); +#63782 = CARTESIAN_POINT('',(-0.525,-0.985,-1.71)); +#63783 = VECTOR('',#63784,1.); +#63784 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63785 = PCURVE('',#62399,#63786); +#63786 = DEFINITIONAL_REPRESENTATION('',(#63787),#63791); +#63787 = LINE('',#63788,#63789); +#63788 = CARTESIAN_POINT('',(0.E+000,-2.315)); +#63789 = VECTOR('',#63790,1.); +#63790 = DIRECTION('',(1.,0.E+000)); +#63791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63792 = PCURVE('',#62427,#63793); +#63793 = DEFINITIONAL_REPRESENTATION('',(#63794),#63798); +#63794 = LINE('',#63795,#63796); +#63795 = CARTESIAN_POINT('',(1.71,-0.985)); +#63796 = VECTOR('',#63797,1.); +#63797 = DIRECTION('',(0.E+000,-1.)); +#63798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63799 = ORIENTED_EDGE('',*,*,#62383,.F.); +#63800 = ADVANCED_FACE('',(#63801),#62287,.T.); +#63801 = FACE_BOUND('',#63802,.F.); +#63802 = EDGE_LOOP('',(#63803,#63824,#63825,#63846)); +#63803 = ORIENTED_EDGE('',*,*,#63804,.T.); +#63804 = EDGE_CURVE('',#62244,#63255,#63805,.T.); +#63805 = SURFACE_CURVE('',#63806,(#63810,#63817),.PCURVE_S1.); +#63806 = LINE('',#63807,#63808); +#63807 = CARTESIAN_POINT('',(0.525,-0.985,-1.71)); +#63808 = VECTOR('',#63809,1.); +#63809 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63810 = PCURVE('',#62287,#63811); +#63811 = DEFINITIONAL_REPRESENTATION('',(#63812),#63816); +#63812 = LINE('',#63813,#63814); +#63813 = CARTESIAN_POINT('',(0.E+000,-1.265)); +#63814 = VECTOR('',#63815,1.); +#63815 = DIRECTION('',(1.,0.E+000)); +#63816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63817 = PCURVE('',#62259,#63818); #63818 = DEFINITIONAL_REPRESENTATION('',(#63819),#63823); #63819 = LINE('',#63820,#63821); -#63820 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); +#63820 = CARTESIAN_POINT('',(1.71,-0.985)); #63821 = VECTOR('',#63822,1.); -#63822 = DIRECTION('',(1.,0.E+000)); +#63822 = DIRECTION('',(0.E+000,-1.)); #63823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63824 = PCURVE('',#47183,#63825); -#63825 = DEFINITIONAL_REPRESENTATION('',(#63826),#63830); -#63826 = LINE('',#63827,#63828); -#63827 = CARTESIAN_POINT('',(1.25,0.92)); -#63828 = VECTOR('',#63829,1.); -#63829 = DIRECTION('',(0.E+000,-1.)); -#63830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63831 = ORIENTED_EDGE('',*,*,#63370,.T.); -#63832 = ORIENTED_EDGE('',*,*,#43356,.T.); -#63833 = ORIENTED_EDGE('',*,*,#46868,.T.); -#63834 = ORIENTED_EDGE('',*,*,#63835,.F.); -#63835 = EDGE_CURVE('',#63810,#46841,#63836,.T.); -#63836 = SURFACE_CURVE('',#63837,(#63841,#63848),.PCURVE_S1.); -#63837 = LINE('',#63838,#63839); -#63838 = CARTESIAN_POINT('',(0.41,0.773013158464,-1.25)); -#63839 = VECTOR('',#63840,1.); -#63840 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63841 = PCURVE('',#43372,#63842); -#63842 = DEFINITIONAL_REPRESENTATION('',(#63843),#63847); -#63843 = LINE('',#63844,#63845); -#63844 = CARTESIAN_POINT('',(9.4868415357E-003,-7.071067811865E-002)); -#63845 = VECTOR('',#63846,1.); -#63846 = DIRECTION('',(1.,0.E+000)); -#63847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63848 = PCURVE('',#46856,#63849); -#63849 = DEFINITIONAL_REPRESENTATION('',(#63850),#63854); -#63850 = LINE('',#63851,#63852); -#63851 = CARTESIAN_POINT('',(0.15,-0.451986841536)); -#63852 = VECTOR('',#63853,1.); -#63853 = DIRECTION('',(0.E+000,-1.)); -#63854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63855 = ADVANCED_FACE('',(#63856),#47183,.T.); -#63856 = FACE_BOUND('',#63857,.F.); -#63857 = EDGE_LOOP('',(#63858,#63859,#63860,#63861,#63882)); -#63858 = ORIENTED_EDGE('',*,*,#47169,.F.); -#63859 = ORIENTED_EDGE('',*,*,#63393,.F.); -#63860 = ORIENTED_EDGE('',*,*,#63809,.T.); -#63861 = ORIENTED_EDGE('',*,*,#63862,.F.); -#63862 = EDGE_CURVE('',#48361,#63810,#63863,.T.); -#63863 = SURFACE_CURVE('',#63864,(#63869,#63876),.PCURVE_S1.); -#63864 = CIRCLE('',#63865,0.2); -#63865 = AXIS2_PLACEMENT_3D('',#63866,#63867,#63868); -#63866 = CARTESIAN_POINT('',(0.41,0.925,-1.38)); -#63867 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63868 = DIRECTION('',(0.E+000,0.E+000,1.)); -#63869 = PCURVE('',#47183,#63870); -#63870 = DEFINITIONAL_REPRESENTATION('',(#63871),#63875); -#63871 = CIRCLE('',#63872,0.2); -#63872 = AXIS2_PLACEMENT_2D('',#63873,#63874); -#63873 = CARTESIAN_POINT('',(1.38,0.925)); -#63874 = DIRECTION('',(-1.,0.E+000)); -#63875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63876 = PCURVE('',#47086,#63877); -#63877 = DEFINITIONAL_REPRESENTATION('',(#63878),#63881); -#63878 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63879,#63880),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.86321189007),.PIECEWISE_BEZIER_KNOTS.); -#63879 = CARTESIAN_POINT('',(3.14159265359,0.82)); -#63880 = CARTESIAN_POINT('',(4.004804543659,0.82)); -#63881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63882 = ORIENTED_EDGE('',*,*,#48360,.F.); -#63883 = ADVANCED_FACE('',(#63884),#47086,.T.); -#63884 = FACE_BOUND('',#63885,.T.); -#63885 = EDGE_LOOP('',(#63886,#63913,#63940,#63961,#63962,#63963)); -#63886 = ORIENTED_EDGE('',*,*,#63887,.T.); -#63887 = EDGE_CURVE('',#46939,#63888,#63890,.T.); -#63888 = VERTEX_POINT('',#63889); -#63889 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); -#63890 = SURFACE_CURVE('',#63891,(#63896,#63902),.PCURVE_S1.); -#63891 = CIRCLE('',#63892,0.2); -#63892 = AXIS2_PLACEMENT_3D('',#63893,#63894,#63895); -#63893 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); -#63894 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63895 = DIRECTION('',(0.E+000,-0.759934207679,0.65)); -#63896 = PCURVE('',#47086,#63897); -#63897 = DEFINITIONAL_REPRESENTATION('',(#63898),#63901); -#63898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63899,#63900),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.707584436725),.PIECEWISE_BEZIER_KNOTS.); -#63899 = CARTESIAN_POINT('',(4.004804543659,0.E+000)); -#63900 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#63901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#63824 = ORIENTED_EDGE('',*,*,#63386,.T.); +#63825 = ORIENTED_EDGE('',*,*,#63826,.F.); +#63826 = EDGE_CURVE('',#62272,#63364,#63827,.T.); +#63827 = SURFACE_CURVE('',#63828,(#63832,#63839),.PCURVE_S1.); +#63828 = LINE('',#63829,#63830); +#63829 = CARTESIAN_POINT('',(0.125,-0.985,-1.71)); +#63830 = VECTOR('',#63831,1.); +#63831 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63832 = PCURVE('',#62287,#63833); +#63833 = DEFINITIONAL_REPRESENTATION('',(#63834),#63838); +#63834 = LINE('',#63835,#63836); +#63835 = CARTESIAN_POINT('',(0.E+000,-1.665)); +#63836 = VECTOR('',#63837,1.); +#63837 = DIRECTION('',(1.,0.E+000)); +#63838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63839 = PCURVE('',#62315,#63840); +#63840 = DEFINITIONAL_REPRESENTATION('',(#63841),#63845); +#63841 = LINE('',#63842,#63843); +#63842 = CARTESIAN_POINT('',(1.71,-0.985)); +#63843 = VECTOR('',#63844,1.); +#63844 = DIRECTION('',(0.E+000,-1.)); +#63845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63846 = ORIENTED_EDGE('',*,*,#62271,.F.); +#63847 = ADVANCED_FACE('',(#63848),#62175,.T.); +#63848 = FACE_BOUND('',#63849,.F.); +#63849 = EDGE_LOOP('',(#63850,#63851,#63852,#63873)); +#63850 = ORIENTED_EDGE('',*,*,#62768,.T.); +#63851 = ORIENTED_EDGE('',*,*,#63513,.T.); +#63852 = ORIENTED_EDGE('',*,*,#63853,.F.); +#63853 = EDGE_CURVE('',#62160,#63491,#63854,.T.); +#63854 = SURFACE_CURVE('',#63855,(#63859,#63866),.PCURVE_S1.); +#63855 = LINE('',#63856,#63857); +#63856 = CARTESIAN_POINT('',(0.775,-0.985,-1.71)); +#63857 = VECTOR('',#63858,1.); +#63858 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63859 = PCURVE('',#62175,#63860); +#63860 = DEFINITIONAL_REPRESENTATION('',(#63861),#63865); +#63861 = LINE('',#63862,#63863); +#63862 = CARTESIAN_POINT('',(0.E+000,-1.015)); +#63863 = VECTOR('',#63864,1.); +#63864 = DIRECTION('',(1.,0.E+000)); +#63865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63866 = PCURVE('',#62203,#63867); +#63867 = DEFINITIONAL_REPRESENTATION('',(#63868),#63872); +#63868 = LINE('',#63869,#63870); +#63869 = CARTESIAN_POINT('',(1.71,-0.985)); +#63870 = VECTOR('',#63871,1.); +#63871 = DIRECTION('',(0.E+000,-1.)); +#63872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63873 = ORIENTED_EDGE('',*,*,#62159,.F.); +#63874 = ADVANCED_FACE('',(#63875),#45229,.T.); +#63875 = FACE_BOUND('',#63876,.F.); +#63876 = EDGE_LOOP('',(#63877,#63898,#63899,#63900)); +#63877 = ORIENTED_EDGE('',*,*,#63878,.F.); +#63878 = EDGE_CURVE('',#62659,#63538,#63879,.T.); +#63879 = SURFACE_CURVE('',#63880,(#63884,#63891),.PCURVE_S1.); +#63880 = LINE('',#63881,#63882); +#63881 = CARTESIAN_POINT('',(1.425,-0.985,-1.71)); +#63882 = VECTOR('',#63883,1.); +#63883 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#63884 = PCURVE('',#45229,#63885); +#63885 = DEFINITIONAL_REPRESENTATION('',(#63886),#63890); +#63886 = LINE('',#63887,#63888); +#63887 = CARTESIAN_POINT('',(0.E+000,-0.365)); +#63888 = VECTOR('',#63889,1.); +#63889 = DIRECTION('',(1.,0.E+000)); +#63890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63891 = PCURVE('',#62697,#63892); +#63892 = DEFINITIONAL_REPRESENTATION('',(#63893),#63897); +#63893 = LINE('',#63894,#63895); +#63894 = CARTESIAN_POINT('',(1.71,-0.985)); +#63895 = VECTOR('',#63896,1.); +#63896 = DIRECTION('',(0.E+000,-1.)); +#63897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63898 = ORIENTED_EDGE('',*,*,#62658,.F.); +#63899 = ORIENTED_EDGE('',*,*,#45213,.T.); +#63900 = ORIENTED_EDGE('',*,*,#63562,.T.); +#63901 = ADVANCED_FACE('',(#63902),#44262,.T.); +#63902 = FACE_BOUND('',#63903,.F.); +#63903 = EDGE_LOOP('',(#63904,#63905,#63906,#63907,#63908,#63909,#63910, + #63911)); +#63904 = ORIENTED_EDGE('',*,*,#45418,.T.); +#63905 = ORIENTED_EDGE('',*,*,#46011,.T.); +#63906 = ORIENTED_EDGE('',*,*,#44244,.F.); +#63907 = ORIENTED_EDGE('',*,*,#61966,.T.); +#63908 = ORIENTED_EDGE('',*,*,#62635,.T.); +#63909 = ORIENTED_EDGE('',*,*,#63685,.T.); +#63910 = ORIENTED_EDGE('',*,*,#62895,.T.); +#63911 = ORIENTED_EDGE('',*,*,#63912,.T.); +#63912 = EDGE_CURVE('',#62873,#45419,#63913,.T.); +#63913 = SURFACE_CURVE('',#63914,(#63918,#63925),.PCURVE_S1.); +#63914 = LINE('',#63915,#63916); +#63915 = CARTESIAN_POINT('',(-1.79,-1.105,-2.35)); +#63916 = VECTOR('',#63917,1.); +#63917 = DIRECTION('',(0.E+000,1.,0.E+000)); +#63918 = PCURVE('',#44262,#63919); +#63919 = DEFINITIONAL_REPRESENTATION('',(#63920),#63924); +#63920 = LINE('',#63921,#63922); +#63921 = CARTESIAN_POINT('',(1.14,-0.12)); +#63922 = VECTOR('',#63923,1.); +#63923 = DIRECTION('',(0.E+000,-1.)); +#63924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63925 = PCURVE('',#45173,#63926); +#63926 = DEFINITIONAL_REPRESENTATION('',(#63927),#63931); +#63927 = LINE('',#63928,#63929); +#63928 = CARTESIAN_POINT('',(-1.79,-1.105)); +#63929 = VECTOR('',#63930,1.); +#63930 = DIRECTION('',(0.E+000,1.)); +#63931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63932 = ADVANCED_FACE('',(#63933),#63947,.F.); +#63933 = FACE_BOUND('',#63934,.F.); +#63934 = EDGE_LOOP('',(#63935,#63965,#63988,#64015,#64038,#64061,#64084, + #64107,#64130,#64153,#64181)); +#63935 = ORIENTED_EDGE('',*,*,#63936,.T.); +#63936 = EDGE_CURVE('',#63937,#63939,#63941,.T.); +#63937 = VERTEX_POINT('',#63938); +#63938 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); +#63939 = VERTEX_POINT('',#63940); +#63940 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); +#63941 = SURFACE_CURVE('',#63942,(#63946,#63958),.PCURVE_S1.); +#63942 = LINE('',#63943,#63944); +#63943 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); +#63944 = VECTOR('',#63945,1.); +#63945 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); +#63946 = PCURVE('',#63947,#63952); +#63947 = PLANE('',#63948); +#63948 = AXIS2_PLACEMENT_3D('',#63949,#63950,#63951); +#63949 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#63950 = DIRECTION('',(0.E+000,0.E+000,1.)); +#63951 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63952 = DEFINITIONAL_REPRESENTATION('',(#63953),#63957); +#63953 = LINE('',#63954,#63955); +#63954 = CARTESIAN_POINT('',(1.339903810568,0.5)); +#63955 = VECTOR('',#63956,1.); +#63956 = DIRECTION('',(0.866025403784,-0.5)); +#63957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63958 = PCURVE('',#53981,#63959); +#63959 = DEFINITIONAL_REPRESENTATION('',(#63960),#63964); +#63960 = LINE('',#63961,#63962); +#63961 = CARTESIAN_POINT('',(0.15,0.E+000)); +#63962 = VECTOR('',#63963,1.); +#63963 = DIRECTION('',(1.,0.E+000)); +#63964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63965 = ORIENTED_EDGE('',*,*,#63966,.T.); +#63966 = EDGE_CURVE('',#63939,#63967,#63969,.T.); +#63967 = VERTEX_POINT('',#63968); +#63968 = CARTESIAN_POINT('',(2.45,0.175,-2.35)); +#63969 = SURFACE_CURVE('',#63970,(#63974,#63981),.PCURVE_S1.); +#63970 = LINE('',#63971,#63972); +#63971 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); +#63972 = VECTOR('',#63973,1.); +#63973 = DIRECTION('',(1.,0.E+000,0.E+000)); +#63974 = PCURVE('',#63947,#63975); +#63975 = DEFINITIONAL_REPRESENTATION('',(#63976),#63980); +#63976 = LINE('',#63977,#63978); +#63977 = CARTESIAN_POINT('',(1.902820323028,0.175)); +#63978 = VECTOR('',#63979,1.); +#63979 = DIRECTION('',(1.,0.E+000)); +#63980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#63981 = PCURVE('',#54493,#63982); +#63982 = DEFINITIONAL_REPRESENTATION('',(#63983),#63987); +#63983 = LINE('',#63984,#63985); +#63984 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#63985 = VECTOR('',#63986,1.); +#63986 = DIRECTION('',(1.,0.E+000)); +#63987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#63902 = PCURVE('',#46744,#63903); -#63903 = DEFINITIONAL_REPRESENTATION('',(#63904),#63912); -#63904 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#63905,#63906,#63907,#63908 - ,#63909,#63910,#63911),.UNSPECIFIED.,.T.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#63905 = CARTESIAN_POINT('',(0.25,-0.451986841536)); -#63906 = CARTESIAN_POINT('',(-1.324893162176E-002,-0.67715344652)); -#63907 = CARTESIAN_POINT('',(-7.662446581088E-002,-0.336589881724)); -#63908 = CARTESIAN_POINT('',(-0.14,3.973683071407E-003)); -#63909 = CARTESIAN_POINT('',(0.186624465811,-0.11142327674)); -#63910 = CARTESIAN_POINT('',(0.513248931622,-0.226820236552)); -#63911 = CARTESIAN_POINT('',(0.25,-0.451986841536)); -#63912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63913 = ORIENTED_EDGE('',*,*,#63914,.T.); -#63914 = EDGE_CURVE('',#63888,#63915,#63917,.T.); -#63915 = VERTEX_POINT('',#63916); -#63916 = CARTESIAN_POINT('',(0.41,0.725,-1.38)); -#63917 = SURFACE_CURVE('',#63918,(#63922,#63928),.PCURVE_S1.); -#63918 = LINE('',#63919,#63920); -#63919 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); -#63920 = VECTOR('',#63921,1.); -#63921 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63922 = PCURVE('',#47086,#63923); -#63923 = DEFINITIONAL_REPRESENTATION('',(#63924),#63927); -#63924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63925,#63926),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); -#63925 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#63926 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#63927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63928 = PCURVE('',#63929,#63934); -#63929 = PLANE('',#63930); -#63930 = AXIS2_PLACEMENT_3D('',#63931,#63932,#63933); -#63931 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); -#63932 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#63933 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#63934 = DEFINITIONAL_REPRESENTATION('',(#63935),#63939); -#63935 = LINE('',#63936,#63937); -#63936 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63937 = VECTOR('',#63938,1.); -#63938 = DIRECTION('',(0.E+000,1.)); -#63939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63940 = ORIENTED_EDGE('',*,*,#63941,.F.); -#63941 = EDGE_CURVE('',#63810,#63915,#63942,.T.); -#63942 = SURFACE_CURVE('',#63943,(#63948,#63954),.PCURVE_S1.); -#63943 = CIRCLE('',#63944,0.2); -#63944 = AXIS2_PLACEMENT_3D('',#63945,#63946,#63947); -#63945 = CARTESIAN_POINT('',(0.41,0.925,-1.38)); -#63946 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63947 = DIRECTION('',(0.E+000,-0.759934207679,0.65)); -#63948 = PCURVE('',#47086,#63949); -#63949 = DEFINITIONAL_REPRESENTATION('',(#63950),#63953); -#63950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63951,#63952),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.707584436725),.PIECEWISE_BEZIER_KNOTS.); -#63951 = CARTESIAN_POINT('',(4.004804543659,0.82)); -#63952 = CARTESIAN_POINT('',(4.712388980385,0.82)); -#63953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63954 = PCURVE('',#46856,#63955); -#63955 = DEFINITIONAL_REPRESENTATION('',(#63956),#63960); -#63956 = CIRCLE('',#63957,0.2); -#63957 = AXIS2_PLACEMENT_2D('',#63958,#63959); -#63958 = CARTESIAN_POINT('',(0.28,-0.3)); -#63959 = DIRECTION('',(-0.65,-0.759934207679)); -#63960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63961 = ORIENTED_EDGE('',*,*,#63862,.F.); -#63962 = ORIENTED_EDGE('',*,*,#48383,.F.); -#63963 = ORIENTED_EDGE('',*,*,#47071,.T.); -#63964 = ADVANCED_FACE('',(#63965),#50165,.F.); -#63965 = FACE_BOUND('',#63966,.F.); -#63966 = EDGE_LOOP('',(#63967,#63994,#63995,#64017)); -#63967 = ORIENTED_EDGE('',*,*,#63968,.T.); -#63968 = EDGE_CURVE('',#63969,#50150,#63971,.T.); -#63969 = VERTEX_POINT('',#63970); -#63970 = CARTESIAN_POINT('',(-0.41,1.025,-1.4)); -#63971 = SURFACE_CURVE('',#63972,(#63977,#63988),.PCURVE_S1.); -#63972 = CIRCLE('',#63973,0.2); -#63973 = AXIS2_PLACEMENT_3D('',#63974,#63975,#63976); -#63974 = CARTESIAN_POINT('',(-0.41,1.025,-1.2)); -#63975 = DIRECTION('',(1.,0.E+000,0.E+000)); -#63976 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#63977 = PCURVE('',#50165,#63978); -#63978 = DEFINITIONAL_REPRESENTATION('',(#63979),#63987); -#63979 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#63980,#63981,#63982,#63983 - ,#63984,#63985,#63986),.UNSPECIFIED.,.F.,.F.) +#63988 = ORIENTED_EDGE('',*,*,#63989,.T.); +#63989 = EDGE_CURVE('',#63967,#63990,#63992,.T.); +#63990 = VERTEX_POINT('',#63991); +#63991 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); +#63992 = SURFACE_CURVE('',#63993,(#63998,#64009),.PCURVE_S1.); +#63993 = CIRCLE('',#63994,0.55); +#63994 = AXIS2_PLACEMENT_3D('',#63995,#63996,#63997); +#63995 = CARTESIAN_POINT('',(2.45,-0.375,-2.35)); +#63996 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#63997 = DIRECTION('',(0.E+000,1.,0.E+000)); +#63998 = PCURVE('',#63947,#63999); +#63999 = DEFINITIONAL_REPRESENTATION('',(#64000),#64008); +#64000 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#64001,#64002,#64003,#64004 + ,#64005,#64006,#64007),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#63980 = CARTESIAN_POINT('',(0.1,-0.2)); -#63981 = CARTESIAN_POINT('',(0.1,0.146410161514)); -#63982 = CARTESIAN_POINT('',(0.4,-2.679491924311E-002)); -#63983 = CARTESIAN_POINT('',(0.7,-0.2)); -#63984 = CARTESIAN_POINT('',(0.4,-0.373205080757)); -#63985 = CARTESIAN_POINT('',(0.1,-0.546410161514)); -#63986 = CARTESIAN_POINT('',(0.1,-0.2)); -#63987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63988 = PCURVE('',#50193,#63989); -#63989 = DEFINITIONAL_REPRESENTATION('',(#63990),#63993); -#63990 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#63991,#63992),.UNSPECIFIED., +#64001 = CARTESIAN_POINT('',(2.45,0.175)); +#64002 = CARTESIAN_POINT('',(3.402627944163,0.175)); +#64003 = CARTESIAN_POINT('',(2.926313972081,-0.65)); +#64004 = CARTESIAN_POINT('',(2.45,-1.475)); +#64005 = CARTESIAN_POINT('',(1.973686027919,-0.65)); +#64006 = CARTESIAN_POINT('',(1.497372055837,0.175)); +#64007 = CARTESIAN_POINT('',(2.45,0.175)); +#64008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64009 = PCURVE('',#54466,#64010); +#64010 = DEFINITIONAL_REPRESENTATION('',(#64011),#64014); +#64011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64012,#64013),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#63991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#63992 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#63993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#63994 = ORIENTED_EDGE('',*,*,#50147,.F.); -#63995 = ORIENTED_EDGE('',*,*,#63996,.T.); -#63996 = EDGE_CURVE('',#50148,#63997,#63999,.T.); -#63997 = VERTEX_POINT('',#63998); -#63998 = CARTESIAN_POINT('',(-0.41,1.025,-1.5)); -#63999 = SURFACE_CURVE('',#64000,(#64004,#64011),.PCURVE_S1.); -#64000 = LINE('',#64001,#64002); -#64001 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); -#64002 = VECTOR('',#64003,1.); -#64003 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64004 = PCURVE('',#50165,#64005); -#64005 = DEFINITIONAL_REPRESENTATION('',(#64006),#64010); -#64006 = LINE('',#64007,#64008); -#64007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64008 = VECTOR('',#64009,1.); -#64009 = DIRECTION('',(0.E+000,-1.)); -#64010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64011 = PCURVE('',#50303,#64012); -#64012 = DEFINITIONAL_REPRESENTATION('',(#64013),#64016); -#64013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64014,#64015),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#64014 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#64015 = CARTESIAN_POINT('',(3.14159265359,-0.2)); -#64016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#64012 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#64013 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#64014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64017 = ORIENTED_EDGE('',*,*,#64018,.T.); -#64018 = EDGE_CURVE('',#63997,#63969,#64019,.T.); +#64015 = ORIENTED_EDGE('',*,*,#64016,.F.); +#64016 = EDGE_CURVE('',#64017,#63990,#64019,.T.); +#64017 = VERTEX_POINT('',#64018); +#64018 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); #64019 = SURFACE_CURVE('',#64020,(#64024,#64031),.PCURVE_S1.); #64020 = LINE('',#64021,#64022); -#64021 = CARTESIAN_POINT('',(-0.41,1.025,-1.5)); +#64021 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); #64022 = VECTOR('',#64023,1.); -#64023 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64024 = PCURVE('',#50165,#64025); +#64023 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64024 = PCURVE('',#63947,#64025); #64025 = DEFINITIONAL_REPRESENTATION('',(#64026),#64030); #64026 = LINE('',#64027,#64028); -#64027 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#64027 = CARTESIAN_POINT('',(3.,-0.617928932188)); #64028 = VECTOR('',#64029,1.); -#64029 = DIRECTION('',(1.,0.E+000)); +#64029 = DIRECTION('',(0.E+000,1.)); #64030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64031 = PCURVE('',#64032,#64037); -#64032 = PLANE('',#64033); -#64033 = AXIS2_PLACEMENT_3D('',#64034,#64035,#64036); -#64034 = CARTESIAN_POINT('',(-0.41,1.025,-1.75)); -#64035 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64036 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64037 = DEFINITIONAL_REPRESENTATION('',(#64038),#64042); -#64038 = LINE('',#64039,#64040); -#64039 = CARTESIAN_POINT('',(0.25,0.E+000)); -#64040 = VECTOR('',#64041,1.); -#64041 = DIRECTION('',(1.,0.E+000)); -#64042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64043 = ADVANCED_FACE('',(#64044),#46744,.F.); -#64044 = FACE_BOUND('',#64045,.F.); -#64045 = EDGE_LOOP('',(#64046,#64047,#64070,#64090,#64091)); -#64046 = ORIENTED_EDGE('',*,*,#63887,.T.); -#64047 = ORIENTED_EDGE('',*,*,#64048,.F.); -#64048 = EDGE_CURVE('',#64049,#63888,#64051,.T.); -#64049 = VERTEX_POINT('',#64050); -#64050 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); -#64051 = SURFACE_CURVE('',#64052,(#64056,#64063),.PCURVE_S1.); -#64052 = LINE('',#64053,#64054); -#64053 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); -#64054 = VECTOR('',#64055,1.); -#64055 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64056 = PCURVE('',#46744,#64057); -#64057 = DEFINITIONAL_REPRESENTATION('',(#64058),#64062); -#64058 = LINE('',#64059,#64060); -#64059 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64060 = VECTOR('',#64061,1.); -#64061 = DIRECTION('',(1.,0.E+000)); -#64062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64063 = PCURVE('',#63929,#64064); -#64064 = DEFINITIONAL_REPRESENTATION('',(#64065),#64069); -#64065 = LINE('',#64066,#64067); -#64066 = CARTESIAN_POINT('',(0.12,0.E+000)); -#64067 = VECTOR('',#64068,1.); -#64068 = DIRECTION('',(-1.,0.E+000)); -#64069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64070 = ORIENTED_EDGE('',*,*,#64071,.T.); -#64071 = EDGE_CURVE('',#64049,#46729,#64072,.T.); -#64072 = SURFACE_CURVE('',#64073,(#64077,#64084),.PCURVE_S1.); -#64073 = LINE('',#64074,#64075); -#64074 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); -#64075 = VECTOR('',#64076,1.); -#64076 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64077 = PCURVE('',#46744,#64078); -#64078 = DEFINITIONAL_REPRESENTATION('',(#64079),#64083); -#64079 = LINE('',#64080,#64081); -#64080 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64081 = VECTOR('',#64082,1.); -#64082 = DIRECTION('',(0.E+000,-1.)); +#64031 = PCURVE('',#54437,#64032); +#64032 = DEFINITIONAL_REPRESENTATION('',(#64033),#64037); +#64033 = LINE('',#64034,#64035); +#64034 = CARTESIAN_POINT('',(0.242928932188,0.E+000)); +#64035 = VECTOR('',#64036,1.); +#64036 = DIRECTION('',(-1.,0.E+000)); +#64037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64038 = ORIENTED_EDGE('',*,*,#64039,.T.); +#64039 = EDGE_CURVE('',#64017,#64040,#64042,.T.); +#64040 = VERTEX_POINT('',#64041); +#64041 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-2.35)); +#64042 = SURFACE_CURVE('',#64043,(#64047,#64054),.PCURVE_S1.); +#64043 = LINE('',#64044,#64045); +#64044 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); +#64045 = VECTOR('',#64046,1.); +#64046 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#64047 = PCURVE('',#63947,#64048); +#64048 = DEFINITIONAL_REPRESENTATION('',(#64049),#64053); +#64049 = LINE('',#64050,#64051); +#64050 = CARTESIAN_POINT('',(3.,-0.617928932188)); +#64051 = VECTOR('',#64052,1.); +#64052 = DIRECTION('',(0.707106781187,0.707106781187)); +#64053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64054 = PCURVE('',#45904,#64055); +#64055 = DEFINITIONAL_REPRESENTATION('',(#64056),#64060); +#64056 = LINE('',#64057,#64058); +#64057 = CARTESIAN_POINT('',(0.323639610307,0.E+000)); +#64058 = VECTOR('',#64059,1.); +#64059 = DIRECTION('',(1.,0.E+000)); +#64060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64061 = ORIENTED_EDGE('',*,*,#64062,.T.); +#64062 = EDGE_CURVE('',#64040,#64063,#64065,.T.); +#64063 = VERTEX_POINT('',#64064); +#64064 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); +#64065 = SURFACE_CURVE('',#64066,(#64071,#64078),.PCURVE_S1.); +#64066 = CIRCLE('',#64067,0.25); +#64067 = AXIS2_PLACEMENT_3D('',#64068,#64069,#64070); +#64068 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002,-2.35)); +#64069 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64070 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#64071 = PCURVE('',#63947,#64072); +#64072 = DEFINITIONAL_REPRESENTATION('',(#64073),#64077); +#64073 = CIRCLE('',#64074,0.25); +#64074 = AXIS2_PLACEMENT_2D('',#64075,#64076); +#64075 = CARTESIAN_POINT('',(3.195,-6.937554159486E-002)); +#64076 = DIRECTION('',(0.707106781187,-0.707106781187)); +#64077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64078 = PCURVE('',#45877,#64079); +#64079 = DEFINITIONAL_REPRESENTATION('',(#64080),#64083); +#64080 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64081,#64082),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); +#64081 = CARTESIAN_POINT('',(5.497787143782,0.E+000)); +#64082 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); #64083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64084 = PCURVE('',#46773,#64085); -#64085 = DEFINITIONAL_REPRESENTATION('',(#64086),#64089); -#64086 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64087,#64088),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); -#64087 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#64088 = CARTESIAN_POINT('',(3.14159265359,-0.58)); -#64089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64090 = ORIENTED_EDGE('',*,*,#46728,.T.); -#64091 = ORIENTED_EDGE('',*,*,#46966,.T.); -#64092 = ADVANCED_FACE('',(#64093),#50193,.T.); -#64093 = FACE_BOUND('',#64094,.T.); -#64094 = EDGE_LOOP('',(#64095,#64096,#64097,#64120)); -#64095 = ORIENTED_EDGE('',*,*,#63968,.T.); -#64096 = ORIENTED_EDGE('',*,*,#50177,.T.); -#64097 = ORIENTED_EDGE('',*,*,#64098,.F.); -#64098 = EDGE_CURVE('',#64099,#50178,#64101,.T.); -#64099 = VERTEX_POINT('',#64100); -#64100 = CARTESIAN_POINT('',(0.41,1.025,-1.4)); -#64101 = SURFACE_CURVE('',#64102,(#64107,#64113),.PCURVE_S1.); -#64102 = CIRCLE('',#64103,0.2); -#64103 = AXIS2_PLACEMENT_3D('',#64104,#64105,#64106); -#64104 = CARTESIAN_POINT('',(0.41,1.025,-1.2)); -#64105 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64106 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64107 = PCURVE('',#50193,#64108); -#64108 = DEFINITIONAL_REPRESENTATION('',(#64109),#64112); -#64109 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64110,#64111),.UNSPECIFIED., +#64084 = ORIENTED_EDGE('',*,*,#64085,.T.); +#64085 = EDGE_CURVE('',#64063,#64086,#64088,.T.); +#64086 = VERTEX_POINT('',#64087); +#64087 = CARTESIAN_POINT('',(3.445,0.57,-2.35)); +#64088 = SURFACE_CURVE('',#64089,(#64093,#64100),.PCURVE_S1.); +#64089 = LINE('',#64090,#64091); +#64090 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); +#64091 = VECTOR('',#64092,1.); +#64092 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64093 = PCURVE('',#63947,#64094); +#64094 = DEFINITIONAL_REPRESENTATION('',(#64095),#64099); +#64095 = LINE('',#64096,#64097); +#64096 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002)); +#64097 = VECTOR('',#64098,1.); +#64098 = DIRECTION('',(0.E+000,1.)); +#64099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64100 = PCURVE('',#45848,#64101); +#64101 = DEFINITIONAL_REPRESENTATION('',(#64102),#64106); +#64102 = LINE('',#64103,#64104); +#64103 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64104 = VECTOR('',#64105,1.); +#64105 = DIRECTION('',(1.,0.E+000)); +#64106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64107 = ORIENTED_EDGE('',*,*,#64108,.T.); +#64108 = EDGE_CURVE('',#64086,#64109,#64111,.T.); +#64109 = VERTEX_POINT('',#64110); +#64110 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); +#64111 = SURFACE_CURVE('',#64112,(#64117,#64124),.PCURVE_S1.); +#64112 = CIRCLE('',#64113,0.35); +#64113 = AXIS2_PLACEMENT_3D('',#64114,#64115,#64116); +#64114 = CARTESIAN_POINT('',(3.095,0.57,-2.35)); +#64115 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64116 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64117 = PCURVE('',#63947,#64118); +#64118 = DEFINITIONAL_REPRESENTATION('',(#64119),#64123); +#64119 = CIRCLE('',#64120,0.35); +#64120 = AXIS2_PLACEMENT_2D('',#64121,#64122); +#64121 = CARTESIAN_POINT('',(3.095,0.57)); +#64122 = DIRECTION('',(1.,0.E+000)); +#64123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64124 = PCURVE('',#45821,#64125); +#64125 = DEFINITIONAL_REPRESENTATION('',(#64126),#64129); +#64126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64127,#64128),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64110 = CARTESIAN_POINT('',(0.E+000,0.82)); -#64111 = CARTESIAN_POINT('',(1.570796326795,0.82)); -#64112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64113 = PCURVE('',#50220,#64114); -#64114 = DEFINITIONAL_REPRESENTATION('',(#64115),#64119); -#64115 = CIRCLE('',#64116,0.2); -#64116 = AXIS2_PLACEMENT_2D('',#64117,#64118); -#64117 = CARTESIAN_POINT('',(1.E-001,-0.2)); -#64118 = DIRECTION('',(1.,0.E+000)); -#64119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64120 = ORIENTED_EDGE('',*,*,#64121,.F.); -#64121 = EDGE_CURVE('',#63969,#64099,#64122,.T.); -#64122 = SURFACE_CURVE('',#64123,(#64127,#64133),.PCURVE_S1.); -#64123 = LINE('',#64124,#64125); -#64124 = CARTESIAN_POINT('',(-0.41,1.025,-1.4)); -#64125 = VECTOR('',#64126,1.); -#64126 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64127 = PCURVE('',#50193,#64128); -#64128 = DEFINITIONAL_REPRESENTATION('',(#64129),#64132); -#64129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64130,#64131),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); -#64130 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64131 = CARTESIAN_POINT('',(0.E+000,0.82)); -#64132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#64127 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64128 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#64129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64133 = PCURVE('',#64032,#64134); -#64134 = DEFINITIONAL_REPRESENTATION('',(#64135),#64139); +#64130 = ORIENTED_EDGE('',*,*,#64131,.T.); +#64131 = EDGE_CURVE('',#64109,#64132,#64134,.T.); +#64132 = VERTEX_POINT('',#64133); +#64133 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); +#64134 = SURFACE_CURVE('',#64135,(#64139,#64146),.PCURVE_S1.); #64135 = LINE('',#64136,#64137); -#64136 = CARTESIAN_POINT('',(0.35,0.E+000)); +#64136 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); #64137 = VECTOR('',#64138,1.); -#64138 = DIRECTION('',(0.E+000,1.)); -#64139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64140 = ADVANCED_FACE('',(#64141),#64032,.T.); -#64141 = FACE_BOUND('',#64142,.F.); -#64142 = EDGE_LOOP('',(#64143,#64166,#64189,#64212,#64233,#64234)); -#64143 = ORIENTED_EDGE('',*,*,#64144,.F.); -#64144 = EDGE_CURVE('',#64145,#63997,#64147,.T.); -#64145 = VERTEX_POINT('',#64146); -#64146 = CARTESIAN_POINT('',(-0.16,1.025,-1.75)); -#64147 = SURFACE_CURVE('',#64148,(#64153,#64160),.PCURVE_S1.); -#64148 = CIRCLE('',#64149,0.25); -#64149 = AXIS2_PLACEMENT_3D('',#64150,#64151,#64152); -#64150 = CARTESIAN_POINT('',(-0.16,1.025,-1.5)); -#64151 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64152 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64153 = PCURVE('',#64032,#64154); -#64154 = DEFINITIONAL_REPRESENTATION('',(#64155),#64159); -#64155 = CIRCLE('',#64156,0.25); -#64156 = AXIS2_PLACEMENT_2D('',#64157,#64158); -#64157 = CARTESIAN_POINT('',(0.25,0.25)); -#64158 = DIRECTION('',(-1.,0.E+000)); -#64159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64160 = PCURVE('',#50303,#64161); -#64161 = DEFINITIONAL_REPRESENTATION('',(#64162),#64165); -#64162 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64163,#64164),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64163 = CARTESIAN_POINT('',(1.570796326795,-0.2)); -#64164 = CARTESIAN_POINT('',(3.14159265359,-0.2)); -#64165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64166 = ORIENTED_EDGE('',*,*,#64167,.F.); -#64167 = EDGE_CURVE('',#64168,#64145,#64170,.T.); -#64168 = VERTEX_POINT('',#64169); -#64169 = CARTESIAN_POINT('',(0.16,1.025,-1.75)); -#64170 = SURFACE_CURVE('',#64171,(#64175,#64182),.PCURVE_S1.); -#64171 = LINE('',#64172,#64173); -#64172 = CARTESIAN_POINT('',(0.16,1.025,-1.75)); -#64173 = VECTOR('',#64174,1.); -#64174 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#64175 = PCURVE('',#64032,#64176); -#64176 = DEFINITIONAL_REPRESENTATION('',(#64177),#64181); -#64177 = LINE('',#64178,#64179); -#64178 = CARTESIAN_POINT('',(0.E+000,0.57)); -#64179 = VECTOR('',#64180,1.); -#64180 = DIRECTION('',(0.E+000,-1.)); -#64181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64182 = PCURVE('',#50276,#64183); -#64183 = DEFINITIONAL_REPRESENTATION('',(#64184),#64188); +#64138 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64139 = PCURVE('',#63947,#64140); +#64140 = DEFINITIONAL_REPRESENTATION('',(#64141),#64145); +#64141 = LINE('',#64142,#64143); +#64142 = CARTESIAN_POINT('',(3.095,0.92)); +#64143 = VECTOR('',#64144,1.); +#64144 = DIRECTION('',(-1.,0.E+000)); +#64145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64146 = PCURVE('',#45792,#64147); +#64147 = DEFINITIONAL_REPRESENTATION('',(#64148),#64152); +#64148 = LINE('',#64149,#64150); +#64149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64150 = VECTOR('',#64151,1.); +#64151 = DIRECTION('',(1.,0.E+000)); +#64152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64153 = ORIENTED_EDGE('',*,*,#64154,.T.); +#64154 = EDGE_CURVE('',#64132,#64155,#64157,.T.); +#64155 = VERTEX_POINT('',#64156); +#64156 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); +#64157 = SURFACE_CURVE('',#64158,(#64162,#64169),.PCURVE_S1.); +#64158 = LINE('',#64159,#64160); +#64159 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); +#64160 = VECTOR('',#64161,1.); +#64161 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64162 = PCURVE('',#63947,#64163); +#64163 = DEFINITIONAL_REPRESENTATION('',(#64164),#64168); +#64164 = LINE('',#64165,#64166); +#64165 = CARTESIAN_POINT('',(2.37,0.92)); +#64166 = VECTOR('',#64167,1.); +#64167 = DIRECTION('',(0.E+000,-1.)); +#64168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64169 = PCURVE('',#64170,#64175); +#64170 = PLANE('',#64171); +#64171 = AXIS2_PLACEMENT_3D('',#64172,#64173,#64174); +#64172 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); +#64173 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64174 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64175 = DEFINITIONAL_REPRESENTATION('',(#64176),#64180); +#64176 = LINE('',#64177,#64178); +#64177 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64178 = VECTOR('',#64179,1.); +#64179 = DIRECTION('',(1.,0.E+000)); +#64180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64181 = ORIENTED_EDGE('',*,*,#64182,.T.); +#64182 = EDGE_CURVE('',#64155,#63937,#64183,.T.); +#64183 = SURFACE_CURVE('',#64184,(#64188,#64195),.PCURVE_S1.); #64184 = LINE('',#64185,#64186); -#64185 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#64185 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); #64186 = VECTOR('',#64187,1.); -#64187 = DIRECTION('',(1.,0.E+000)); -#64188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64189 = ORIENTED_EDGE('',*,*,#64190,.F.); -#64190 = EDGE_CURVE('',#64191,#64168,#64193,.T.); -#64191 = VERTEX_POINT('',#64192); -#64192 = CARTESIAN_POINT('',(0.41,1.025,-1.5)); -#64193 = SURFACE_CURVE('',#64194,(#64199,#64206),.PCURVE_S1.); -#64194 = CIRCLE('',#64195,0.25); -#64195 = AXIS2_PLACEMENT_3D('',#64196,#64197,#64198); -#64196 = CARTESIAN_POINT('',(0.16,1.025,-1.5)); -#64197 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64198 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64199 = PCURVE('',#64032,#64200); -#64200 = DEFINITIONAL_REPRESENTATION('',(#64201),#64205); -#64201 = CIRCLE('',#64202,0.25); -#64202 = AXIS2_PLACEMENT_2D('',#64203,#64204); -#64203 = CARTESIAN_POINT('',(0.25,0.57)); -#64204 = DIRECTION('',(0.E+000,1.)); -#64205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64206 = PCURVE('',#50249,#64207); -#64207 = DEFINITIONAL_REPRESENTATION('',(#64208),#64211); -#64208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64209,#64210),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64209 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#64210 = CARTESIAN_POINT('',(1.570796326795,-0.2)); -#64211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64212 = ORIENTED_EDGE('',*,*,#64213,.T.); -#64213 = EDGE_CURVE('',#64191,#64099,#64214,.T.); -#64214 = SURFACE_CURVE('',#64215,(#64219,#64226),.PCURVE_S1.); -#64215 = LINE('',#64216,#64217); -#64216 = CARTESIAN_POINT('',(0.41,1.025,-1.5)); -#64217 = VECTOR('',#64218,1.); -#64218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64219 = PCURVE('',#64032,#64220); -#64220 = DEFINITIONAL_REPRESENTATION('',(#64221),#64225); -#64221 = LINE('',#64222,#64223); -#64222 = CARTESIAN_POINT('',(0.25,0.82)); -#64223 = VECTOR('',#64224,1.); -#64224 = DIRECTION('',(1.,0.E+000)); -#64225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64226 = PCURVE('',#50220,#64227); -#64227 = DEFINITIONAL_REPRESENTATION('',(#64228),#64232); -#64228 = LINE('',#64229,#64230); -#64229 = CARTESIAN_POINT('',(0.4,-0.2)); -#64230 = VECTOR('',#64231,1.); -#64231 = DIRECTION('',(-1.,0.E+000)); -#64232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64233 = ORIENTED_EDGE('',*,*,#64121,.F.); -#64234 = ORIENTED_EDGE('',*,*,#64018,.F.); -#64235 = ADVANCED_FACE('',(#64236),#46773,.F.); -#64236 = FACE_BOUND('',#64237,.F.); -#64237 = EDGE_LOOP('',(#64238,#64265,#64285,#64286)); -#64238 = ORIENTED_EDGE('',*,*,#64239,.F.); -#64239 = EDGE_CURVE('',#64240,#64049,#64242,.T.); -#64240 = VERTEX_POINT('',#64241); -#64241 = CARTESIAN_POINT('',(-0.16,0.725,-1.75)); -#64242 = SURFACE_CURVE('',#64243,(#64248,#64254),.PCURVE_S1.); -#64243 = CIRCLE('',#64244,0.25); -#64244 = AXIS2_PLACEMENT_3D('',#64245,#64246,#64247); -#64245 = CARTESIAN_POINT('',(-0.16,0.725,-1.5)); -#64246 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64247 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64248 = PCURVE('',#46773,#64249); -#64249 = DEFINITIONAL_REPRESENTATION('',(#64250),#64253); -#64250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64251,#64252),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64251 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#64252 = CARTESIAN_POINT('',(3.14159265359,-0.5)); -#64253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64254 = PCURVE('',#63929,#64255); -#64255 = DEFINITIONAL_REPRESENTATION('',(#64256),#64264); -#64256 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#64257,#64258,#64259,#64260 - ,#64261,#64262,#64263),.UNSPECIFIED.,.T.,.F.) +#64187 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64188 = PCURVE('',#63947,#64189); +#64189 = DEFINITIONAL_REPRESENTATION('',(#64190),#64194); +#64190 = LINE('',#64191,#64192); +#64191 = CARTESIAN_POINT('',(2.37,0.5)); +#64192 = VECTOR('',#64193,1.); +#64193 = DIRECTION('',(-1.,0.E+000)); +#64194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64195 = PCURVE('',#54037,#64196); +#64196 = DEFINITIONAL_REPRESENTATION('',(#64197),#64201); +#64197 = LINE('',#64198,#64199); +#64198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64199 = VECTOR('',#64200,1.); +#64200 = DIRECTION('',(1.,0.E+000)); +#64201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64202 = ADVANCED_FACE('',(#64203),#64217,.F.); +#64203 = FACE_BOUND('',#64204,.F.); +#64204 = EDGE_LOOP('',(#64205,#64235,#64262,#64285,#64308,#64331,#64359, + #64382,#64405,#64428,#64451)); +#64205 = ORIENTED_EDGE('',*,*,#64206,.T.); +#64206 = EDGE_CURVE('',#64207,#64209,#64211,.T.); +#64207 = VERTEX_POINT('',#64208); +#64208 = CARTESIAN_POINT('',(-3.,-0.617928932188,-2.35)); +#64209 = VERTEX_POINT('',#64210); +#64210 = CARTESIAN_POINT('',(-3.,-0.375,-2.35)); +#64211 = SURFACE_CURVE('',#64212,(#64216,#64228),.PCURVE_S1.); +#64212 = LINE('',#64213,#64214); +#64213 = CARTESIAN_POINT('',(-3.,-0.617928932188,-2.35)); +#64214 = VECTOR('',#64215,1.); +#64215 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64216 = PCURVE('',#64217,#64222); +#64217 = PLANE('',#64218); +#64218 = AXIS2_PLACEMENT_3D('',#64219,#64220,#64221); +#64219 = CARTESIAN_POINT('',(0.E+000,0.E+000,-2.35)); +#64220 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64221 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64222 = DEFINITIONAL_REPRESENTATION('',(#64223),#64227); +#64223 = LINE('',#64224,#64225); +#64224 = CARTESIAN_POINT('',(-3.,-0.617928932188)); +#64225 = VECTOR('',#64226,1.); +#64226 = DIRECTION('',(0.E+000,1.)); +#64227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64228 = PCURVE('',#54271,#64229); +#64229 = DEFINITIONAL_REPRESENTATION('',(#64230),#64234); +#64230 = LINE('',#64231,#64232); +#64231 = CARTESIAN_POINT('',(0.607071067812,0.E+000)); +#64232 = VECTOR('',#64233,1.); +#64233 = DIRECTION('',(1.,0.E+000)); +#64234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64235 = ORIENTED_EDGE('',*,*,#64236,.T.); +#64236 = EDGE_CURVE('',#64209,#64237,#64239,.T.); +#64237 = VERTEX_POINT('',#64238); +#64238 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); +#64239 = SURFACE_CURVE('',#64240,(#64245,#64256),.PCURVE_S1.); +#64240 = CIRCLE('',#64241,0.55); +#64241 = AXIS2_PLACEMENT_3D('',#64242,#64243,#64244); +#64242 = CARTESIAN_POINT('',(-2.45,-0.375,-2.35)); +#64243 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64244 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64245 = PCURVE('',#64217,#64246); +#64246 = DEFINITIONAL_REPRESENTATION('',(#64247),#64255); +#64247 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#64248,#64249,#64250,#64251 + ,#64252,#64253,#64254),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#64257 = CARTESIAN_POINT('',(0.37,0.25)); -#64258 = CARTESIAN_POINT('',(0.37,-0.183012701892)); -#64259 = CARTESIAN_POINT('',(-5.E-003,3.349364905389E-002)); -#64260 = CARTESIAN_POINT('',(-0.38,0.25)); -#64261 = CARTESIAN_POINT('',(-5.E-003,0.466506350946)); -#64262 = CARTESIAN_POINT('',(0.37,0.683012701892)); -#64263 = CARTESIAN_POINT('',(0.37,0.25)); -#64264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64265 = ORIENTED_EDGE('',*,*,#64266,.T.); -#64266 = EDGE_CURVE('',#64240,#46757,#64267,.T.); -#64267 = SURFACE_CURVE('',#64268,(#64272,#64278),.PCURVE_S1.); -#64268 = LINE('',#64269,#64270); -#64269 = CARTESIAN_POINT('',(-0.16,0.725,-1.75)); -#64270 = VECTOR('',#64271,1.); -#64271 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64272 = PCURVE('',#46773,#64273); -#64273 = DEFINITIONAL_REPRESENTATION('',(#64274),#64277); -#64274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64275,#64276),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); -#64275 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#64276 = CARTESIAN_POINT('',(1.570796326795,-0.58)); +#64248 = CARTESIAN_POINT('',(-3.,-0.375)); +#64249 = CARTESIAN_POINT('',(-3.,0.577627944163)); +#64250 = CARTESIAN_POINT('',(-2.175,0.101313972081)); +#64251 = CARTESIAN_POINT('',(-1.35,-0.375)); +#64252 = CARTESIAN_POINT('',(-2.175,-0.851313972081)); +#64253 = CARTESIAN_POINT('',(-3.,-1.327627944163)); +#64254 = CARTESIAN_POINT('',(-3.,-0.375)); +#64255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64256 = PCURVE('',#54244,#64257); +#64257 = DEFINITIONAL_REPRESENTATION('',(#64258),#64261); +#64258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64259,#64260),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#64259 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64260 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#64261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64262 = ORIENTED_EDGE('',*,*,#64263,.T.); +#64263 = EDGE_CURVE('',#64237,#64264,#64266,.T.); +#64264 = VERTEX_POINT('',#64265); +#64265 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); +#64266 = SURFACE_CURVE('',#64267,(#64271,#64278),.PCURVE_S1.); +#64267 = LINE('',#64268,#64269); +#64268 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); +#64269 = VECTOR('',#64270,1.); +#64270 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64271 = PCURVE('',#64217,#64272); +#64272 = DEFINITIONAL_REPRESENTATION('',(#64273),#64277); +#64273 = LINE('',#64274,#64275); +#64274 = CARTESIAN_POINT('',(-2.45,0.175)); +#64275 = VECTOR('',#64276,1.); +#64276 = DIRECTION('',(1.,0.E+000)); #64277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64278 = PCURVE('',#46800,#64279); +#64278 = PCURVE('',#54215,#64279); #64279 = DEFINITIONAL_REPRESENTATION('',(#64280),#64284); #64280 = LINE('',#64281,#64282); -#64281 = CARTESIAN_POINT('',(0.32,-0.5)); +#64281 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #64282 = VECTOR('',#64283,1.); -#64283 = DIRECTION('',(0.E+000,-1.)); +#64283 = DIRECTION('',(1.,0.E+000)); #64284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64285 = ORIENTED_EDGE('',*,*,#46756,.T.); -#64286 = ORIENTED_EDGE('',*,*,#64071,.F.); -#64287 = ADVANCED_FACE('',(#64288),#50303,.F.); -#64288 = FACE_BOUND('',#64289,.F.); -#64289 = EDGE_LOOP('',(#64290,#64291,#64292,#64293)); -#64290 = ORIENTED_EDGE('',*,*,#64144,.T.); -#64291 = ORIENTED_EDGE('',*,*,#63996,.F.); -#64292 = ORIENTED_EDGE('',*,*,#50288,.F.); -#64293 = ORIENTED_EDGE('',*,*,#64294,.T.); -#64294 = EDGE_CURVE('',#50261,#64145,#64295,.T.); -#64295 = SURFACE_CURVE('',#64296,(#64300,#64306),.PCURVE_S1.); +#64285 = ORIENTED_EDGE('',*,*,#64286,.T.); +#64286 = EDGE_CURVE('',#64264,#64287,#64289,.T.); +#64287 = VERTEX_POINT('',#64288); +#64288 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); +#64289 = SURFACE_CURVE('',#64290,(#64294,#64301),.PCURVE_S1.); +#64290 = LINE('',#64291,#64292); +#64291 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); +#64292 = VECTOR('',#64293,1.); +#64293 = DIRECTION('',(0.866025403784,0.5,0.E+000)); +#64294 = PCURVE('',#64217,#64295); +#64295 = DEFINITIONAL_REPRESENTATION('',(#64296),#64300); #64296 = LINE('',#64297,#64298); -#64297 = CARTESIAN_POINT('',(-0.16,1.225,-1.75)); +#64297 = CARTESIAN_POINT('',(-1.902820323028,0.175)); #64298 = VECTOR('',#64299,1.); -#64299 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64300 = PCURVE('',#50303,#64301); -#64301 = DEFINITIONAL_REPRESENTATION('',(#64302),#64305); -#64302 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64303,#64304),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#64303 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64304 = CARTESIAN_POINT('',(1.570796326795,-0.2)); -#64305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64306 = PCURVE('',#50276,#64307); -#64307 = DEFINITIONAL_REPRESENTATION('',(#64308),#64312); -#64308 = LINE('',#64309,#64310); -#64309 = CARTESIAN_POINT('',(0.32,0.E+000)); -#64310 = VECTOR('',#64311,1.); -#64311 = DIRECTION('',(0.E+000,-1.)); -#64312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64313 = ADVANCED_FACE('',(#64314),#63929,.T.); -#64314 = FACE_BOUND('',#64315,.F.); -#64315 = EDGE_LOOP('',(#64316,#64317,#64318,#64319,#64342,#64369)); -#64316 = ORIENTED_EDGE('',*,*,#64239,.T.); -#64317 = ORIENTED_EDGE('',*,*,#64048,.T.); -#64318 = ORIENTED_EDGE('',*,*,#63914,.T.); -#64319 = ORIENTED_EDGE('',*,*,#64320,.F.); -#64320 = EDGE_CURVE('',#64321,#63915,#64323,.T.); -#64321 = VERTEX_POINT('',#64322); -#64322 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); -#64323 = SURFACE_CURVE('',#64324,(#64328,#64335),.PCURVE_S1.); -#64324 = LINE('',#64325,#64326); -#64325 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); -#64326 = VECTOR('',#64327,1.); -#64327 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64328 = PCURVE('',#63929,#64329); -#64329 = DEFINITIONAL_REPRESENTATION('',(#64330),#64334); -#64330 = LINE('',#64331,#64332); -#64331 = CARTESIAN_POINT('',(0.12,0.82)); -#64332 = VECTOR('',#64333,1.); -#64333 = DIRECTION('',(-1.,0.E+000)); -#64334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64335 = PCURVE('',#46856,#64336); -#64336 = DEFINITIONAL_REPRESENTATION('',(#64337),#64341); -#64337 = LINE('',#64338,#64339); -#64338 = CARTESIAN_POINT('',(0.4,-0.5)); -#64339 = VECTOR('',#64340,1.); -#64340 = DIRECTION('',(-1.,0.E+000)); -#64341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64342 = ORIENTED_EDGE('',*,*,#64343,.T.); -#64343 = EDGE_CURVE('',#64321,#64344,#64346,.T.); -#64344 = VERTEX_POINT('',#64345); -#64345 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); -#64346 = SURFACE_CURVE('',#64347,(#64352,#64363),.PCURVE_S1.); -#64347 = CIRCLE('',#64348,0.25); -#64348 = AXIS2_PLACEMENT_3D('',#64349,#64350,#64351); -#64349 = CARTESIAN_POINT('',(0.16,0.725,-1.5)); -#64350 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64351 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64352 = PCURVE('',#63929,#64353); -#64353 = DEFINITIONAL_REPRESENTATION('',(#64354),#64362); -#64354 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#64355,#64356,#64357,#64358 - ,#64359,#64360,#64361),.UNSPECIFIED.,.F.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#64355 = CARTESIAN_POINT('',(0.12,0.82)); -#64356 = CARTESIAN_POINT('',(0.553012701892,0.82)); -#64357 = CARTESIAN_POINT('',(0.336506350946,0.445)); -#64358 = CARTESIAN_POINT('',(0.12,7.E-002)); -#64359 = CARTESIAN_POINT('',(-9.650635094611E-002,0.445)); -#64360 = CARTESIAN_POINT('',(-0.313012701892,0.82)); -#64361 = CARTESIAN_POINT('',(0.12,0.82)); -#64362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64363 = PCURVE('',#46829,#64364); -#64364 = DEFINITIONAL_REPRESENTATION('',(#64365),#64368); -#64365 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64366,#64367),.UNSPECIFIED., +#64299 = DIRECTION('',(0.866025403784,0.5)); +#64300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64301 = PCURVE('',#54187,#64302); +#64302 = DEFINITIONAL_REPRESENTATION('',(#64303),#64307); +#64303 = LINE('',#64304,#64305); +#64304 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64305 = VECTOR('',#64306,1.); +#64306 = DIRECTION('',(1.,0.E+000)); +#64307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64308 = ORIENTED_EDGE('',*,*,#64309,.T.); +#64309 = EDGE_CURVE('',#64287,#64310,#64312,.T.); +#64310 = VERTEX_POINT('',#64311); +#64311 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); +#64312 = SURFACE_CURVE('',#64313,(#64317,#64324),.PCURVE_S1.); +#64313 = LINE('',#64314,#64315); +#64314 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); +#64315 = VECTOR('',#64316,1.); +#64316 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64317 = PCURVE('',#64217,#64318); +#64318 = DEFINITIONAL_REPRESENTATION('',(#64319),#64323); +#64319 = LINE('',#64320,#64321); +#64320 = CARTESIAN_POINT('',(-1.339903810568,0.5)); +#64321 = VECTOR('',#64322,1.); +#64322 = DIRECTION('',(-1.,0.E+000)); +#64323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64324 = PCURVE('',#54644,#64325); +#64325 = DEFINITIONAL_REPRESENTATION('',(#64326),#64330); +#64326 = LINE('',#64327,#64328); +#64327 = CARTESIAN_POINT('',(0.129903810568,0.E+000)); +#64328 = VECTOR('',#64329,1.); +#64329 = DIRECTION('',(1.,0.E+000)); +#64330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64331 = ORIENTED_EDGE('',*,*,#64332,.F.); +#64332 = EDGE_CURVE('',#64333,#64310,#64335,.T.); +#64333 = VERTEX_POINT('',#64334); +#64334 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); +#64335 = SURFACE_CURVE('',#64336,(#64340,#64347),.PCURVE_S1.); +#64336 = LINE('',#64337,#64338); +#64337 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); +#64338 = VECTOR('',#64339,1.); +#64339 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64340 = PCURVE('',#64217,#64341); +#64341 = DEFINITIONAL_REPRESENTATION('',(#64342),#64346); +#64342 = LINE('',#64343,#64344); +#64343 = CARTESIAN_POINT('',(-2.37,0.92)); +#64344 = VECTOR('',#64345,1.); +#64345 = DIRECTION('',(0.E+000,-1.)); +#64346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64347 = PCURVE('',#64348,#64353); +#64348 = PLANE('',#64349); +#64349 = AXIS2_PLACEMENT_3D('',#64350,#64351,#64352); +#64350 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); +#64351 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64352 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64353 = DEFINITIONAL_REPRESENTATION('',(#64354),#64358); +#64354 = LINE('',#64355,#64356); +#64355 = CARTESIAN_POINT('',(0.42,0.E+000)); +#64356 = VECTOR('',#64357,1.); +#64357 = DIRECTION('',(-1.,0.E+000)); +#64358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64359 = ORIENTED_EDGE('',*,*,#64360,.T.); +#64360 = EDGE_CURVE('',#64333,#64361,#64363,.T.); +#64361 = VERTEX_POINT('',#64362); +#64362 = CARTESIAN_POINT('',(-3.095,0.92,-2.35)); +#64363 = SURFACE_CURVE('',#64364,(#64368,#64375),.PCURVE_S1.); +#64364 = LINE('',#64365,#64366); +#64365 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); +#64366 = VECTOR('',#64367,1.); +#64367 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64368 = PCURVE('',#64217,#64369); +#64369 = DEFINITIONAL_REPRESENTATION('',(#64370),#64374); +#64370 = LINE('',#64371,#64372); +#64371 = CARTESIAN_POINT('',(-2.37,0.92)); +#64372 = VECTOR('',#64373,1.); +#64373 = DIRECTION('',(-1.,0.E+000)); +#64374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64375 = PCURVE('',#45792,#64376); +#64376 = DEFINITIONAL_REPRESENTATION('',(#64377),#64381); +#64377 = LINE('',#64378,#64379); +#64378 = CARTESIAN_POINT('',(5.465,0.E+000)); +#64379 = VECTOR('',#64380,1.); +#64380 = DIRECTION('',(1.,0.E+000)); +#64381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64382 = ORIENTED_EDGE('',*,*,#64383,.T.); +#64383 = EDGE_CURVE('',#64361,#64384,#64386,.T.); +#64384 = VERTEX_POINT('',#64385); +#64385 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); +#64386 = SURFACE_CURVE('',#64387,(#64392,#64399),.PCURVE_S1.); +#64387 = CIRCLE('',#64388,0.35); +#64388 = AXIS2_PLACEMENT_3D('',#64389,#64390,#64391); +#64389 = CARTESIAN_POINT('',(-3.095,0.57,-2.35)); +#64390 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64391 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64392 = PCURVE('',#64217,#64393); +#64393 = DEFINITIONAL_REPRESENTATION('',(#64394),#64398); +#64394 = CIRCLE('',#64395,0.35); +#64395 = AXIS2_PLACEMENT_2D('',#64396,#64397); +#64396 = CARTESIAN_POINT('',(-3.095,0.57)); +#64397 = DIRECTION('',(0.E+000,1.)); +#64398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64399 = PCURVE('',#46157,#64400); +#64400 = DEFINITIONAL_REPRESENTATION('',(#64401),#64404); +#64401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64402,#64403),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64366 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64367 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#64368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64369 = ORIENTED_EDGE('',*,*,#64370,.T.); -#64370 = EDGE_CURVE('',#64344,#64240,#64371,.T.); -#64371 = SURFACE_CURVE('',#64372,(#64376,#64383),.PCURVE_S1.); -#64372 = LINE('',#64373,#64374); -#64373 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); -#64374 = VECTOR('',#64375,1.); -#64375 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#64376 = PCURVE('',#63929,#64377); -#64377 = DEFINITIONAL_REPRESENTATION('',(#64378),#64382); -#64378 = LINE('',#64379,#64380); -#64379 = CARTESIAN_POINT('',(0.37,0.57)); -#64380 = VECTOR('',#64381,1.); -#64381 = DIRECTION('',(0.E+000,-1.)); -#64382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64383 = PCURVE('',#46800,#64384); -#64384 = DEFINITIONAL_REPRESENTATION('',(#64385),#64389); -#64385 = LINE('',#64386,#64387); -#64386 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64387 = VECTOR('',#64388,1.); -#64388 = DIRECTION('',(1.,0.E+000)); -#64389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64390 = ADVANCED_FACE('',(#64391),#50220,.F.); -#64391 = FACE_BOUND('',#64392,.F.); -#64392 = EDGE_LOOP('',(#64393,#64394,#64395,#64415)); -#64393 = ORIENTED_EDGE('',*,*,#64098,.F.); -#64394 = ORIENTED_EDGE('',*,*,#64213,.F.); -#64395 = ORIENTED_EDGE('',*,*,#64396,.F.); -#64396 = EDGE_CURVE('',#50205,#64191,#64397,.T.); -#64397 = SURFACE_CURVE('',#64398,(#64402,#64409),.PCURVE_S1.); -#64398 = LINE('',#64399,#64400); -#64399 = CARTESIAN_POINT('',(0.41,1.225,-1.5)); -#64400 = VECTOR('',#64401,1.); -#64401 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64402 = PCURVE('',#50220,#64403); -#64403 = DEFINITIONAL_REPRESENTATION('',(#64404),#64408); -#64404 = LINE('',#64405,#64406); -#64405 = CARTESIAN_POINT('',(0.4,0.E+000)); -#64406 = VECTOR('',#64407,1.); -#64407 = DIRECTION('',(0.E+000,-1.)); -#64408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64409 = PCURVE('',#50249,#64410); -#64410 = DEFINITIONAL_REPRESENTATION('',(#64411),#64414); -#64411 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64412,#64413),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#64412 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64413 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#64414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64415 = ORIENTED_EDGE('',*,*,#50204,.F.); -#64416 = ADVANCED_FACE('',(#64417),#46856,.F.); -#64417 = FACE_BOUND('',#64418,.F.); -#64418 = EDGE_LOOP('',(#64419,#64420,#64421,#64422,#64442)); -#64419 = ORIENTED_EDGE('',*,*,#63941,.F.); -#64420 = ORIENTED_EDGE('',*,*,#63835,.T.); -#64421 = ORIENTED_EDGE('',*,*,#46840,.T.); -#64422 = ORIENTED_EDGE('',*,*,#64423,.F.); -#64423 = EDGE_CURVE('',#64321,#46813,#64424,.T.); -#64424 = SURFACE_CURVE('',#64425,(#64429,#64436),.PCURVE_S1.); -#64425 = LINE('',#64426,#64427); -#64426 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); -#64427 = VECTOR('',#64428,1.); -#64428 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64429 = PCURVE('',#46856,#64430); -#64430 = DEFINITIONAL_REPRESENTATION('',(#64431),#64435); -#64431 = LINE('',#64432,#64433); -#64432 = CARTESIAN_POINT('',(0.4,-0.5)); -#64433 = VECTOR('',#64434,1.); -#64434 = DIRECTION('',(0.E+000,-1.)); -#64435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64436 = PCURVE('',#46829,#64437); -#64437 = DEFINITIONAL_REPRESENTATION('',(#64438),#64441); -#64438 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64439,#64440),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); -#64439 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64440 = CARTESIAN_POINT('',(0.E+000,-0.58)); -#64441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64442 = ORIENTED_EDGE('',*,*,#64320,.T.); -#64443 = ADVANCED_FACE('',(#64444),#46829,.F.); -#64444 = FACE_BOUND('',#64445,.F.); -#64445 = EDGE_LOOP('',(#64446,#64447,#64448,#64449)); -#64446 = ORIENTED_EDGE('',*,*,#64343,.F.); -#64447 = ORIENTED_EDGE('',*,*,#64423,.T.); -#64448 = ORIENTED_EDGE('',*,*,#46812,.T.); -#64449 = ORIENTED_EDGE('',*,*,#64450,.F.); -#64450 = EDGE_CURVE('',#64344,#46785,#64451,.T.); -#64451 = SURFACE_CURVE('',#64452,(#64456,#64462),.PCURVE_S1.); -#64452 = LINE('',#64453,#64454); -#64453 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); -#64454 = VECTOR('',#64455,1.); -#64455 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64456 = PCURVE('',#46829,#64457); -#64457 = DEFINITIONAL_REPRESENTATION('',(#64458),#64461); -#64458 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64459,#64460),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); -#64459 = CARTESIAN_POINT('',(1.570796326795,-0.5)); -#64460 = CARTESIAN_POINT('',(1.570796326795,-0.58)); -#64461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64462 = PCURVE('',#46800,#64463); -#64463 = DEFINITIONAL_REPRESENTATION('',(#64464),#64468); -#64464 = LINE('',#64465,#64466); -#64465 = CARTESIAN_POINT('',(0.E+000,-0.5)); -#64466 = VECTOR('',#64467,1.); -#64467 = DIRECTION('',(0.E+000,-1.)); -#64468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64469 = ADVANCED_FACE('',(#64470),#50249,.F.); -#64470 = FACE_BOUND('',#64471,.F.); -#64471 = EDGE_LOOP('',(#64472,#64473,#64493,#64494)); -#64472 = ORIENTED_EDGE('',*,*,#64190,.T.); -#64473 = ORIENTED_EDGE('',*,*,#64474,.F.); -#64474 = EDGE_CURVE('',#50233,#64168,#64475,.T.); -#64475 = SURFACE_CURVE('',#64476,(#64480,#64486),.PCURVE_S1.); -#64476 = LINE('',#64477,#64478); -#64477 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); -#64478 = VECTOR('',#64479,1.); -#64479 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64480 = PCURVE('',#50249,#64481); -#64481 = DEFINITIONAL_REPRESENTATION('',(#64482),#64485); -#64482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64483,#64484),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#64483 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64484 = CARTESIAN_POINT('',(1.570796326795,-0.2)); -#64485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64486 = PCURVE('',#50276,#64487); -#64487 = DEFINITIONAL_REPRESENTATION('',(#64488),#64492); -#64488 = LINE('',#64489,#64490); -#64489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64490 = VECTOR('',#64491,1.); -#64491 = DIRECTION('',(0.E+000,-1.)); -#64492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64493 = ORIENTED_EDGE('',*,*,#50232,.F.); -#64494 = ORIENTED_EDGE('',*,*,#64396,.T.); -#64495 = ADVANCED_FACE('',(#64496),#46800,.F.); -#64496 = FACE_BOUND('',#64497,.F.); -#64497 = EDGE_LOOP('',(#64498,#64499,#64500,#64501)); -#64498 = ORIENTED_EDGE('',*,*,#64370,.F.); -#64499 = ORIENTED_EDGE('',*,*,#64450,.T.); -#64500 = ORIENTED_EDGE('',*,*,#46784,.T.); -#64501 = ORIENTED_EDGE('',*,*,#64266,.F.); -#64502 = ADVANCED_FACE('',(#64503),#50276,.F.); -#64503 = FACE_BOUND('',#64504,.F.); -#64504 = EDGE_LOOP('',(#64505,#64506,#64507,#64508)); -#64505 = ORIENTED_EDGE('',*,*,#64167,.T.); -#64506 = ORIENTED_EDGE('',*,*,#64294,.F.); -#64507 = ORIENTED_EDGE('',*,*,#50260,.F.); -#64508 = ORIENTED_EDGE('',*,*,#64474,.T.); -#64509 = ADVANCED_FACE('',(#64510),#51795,.T.); -#64510 = FACE_BOUND('',#64511,.F.); -#64511 = EDGE_LOOP('',(#64512,#64533,#64534,#64535,#64536)); -#64512 = ORIENTED_EDGE('',*,*,#64513,.T.); -#64513 = EDGE_CURVE('',#61872,#51780,#64514,.T.); -#64514 = SURFACE_CURVE('',#64515,(#64519,#64526),.PCURVE_S1.); -#64515 = LINE('',#64516,#64517); -#64516 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); -#64517 = VECTOR('',#64518,1.); -#64518 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64519 = PCURVE('',#51795,#64520); -#64520 = DEFINITIONAL_REPRESENTATION('',(#64521),#64525); -#64521 = LINE('',#64522,#64523); -#64522 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64523 = VECTOR('',#64524,1.); -#64524 = DIRECTION('',(0.E+000,1.)); -#64525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64526 = PCURVE('',#51823,#64527); -#64527 = DEFINITIONAL_REPRESENTATION('',(#64528),#64532); -#64528 = LINE('',#64529,#64530); -#64529 = CARTESIAN_POINT('',(0.547179676972,0.E+000)); -#64530 = VECTOR('',#64531,1.); -#64531 = DIRECTION('',(0.E+000,1.)); -#64532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64533 = ORIENTED_EDGE('',*,*,#51779,.T.); -#64534 = ORIENTED_EDGE('',*,*,#52292,.F.); -#64535 = ORIENTED_EDGE('',*,*,#63009,.F.); -#64536 = ORIENTED_EDGE('',*,*,#61894,.F.); -#64537 = ADVANCED_FACE('',(#64538),#51823,.T.); -#64538 = FACE_BOUND('',#64539,.F.); -#64539 = EDGE_LOOP('',(#64540,#64560,#64561,#64562)); -#64540 = ORIENTED_EDGE('',*,*,#64541,.T.); -#64541 = EDGE_CURVE('',#61845,#51808,#64542,.T.); -#64542 = SURFACE_CURVE('',#64543,(#64547,#64554),.PCURVE_S1.); -#64543 = LINE('',#64544,#64545); -#64544 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); -#64545 = VECTOR('',#64546,1.); -#64546 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64547 = PCURVE('',#51823,#64548); -#64548 = DEFINITIONAL_REPRESENTATION('',(#64549),#64553); -#64549 = LINE('',#64550,#64551); -#64550 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64551 = VECTOR('',#64552,1.); -#64552 = DIRECTION('',(0.E+000,1.)); -#64553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64554 = PCURVE('',#51852,#64555); -#64555 = DEFINITIONAL_REPRESENTATION('',(#64556),#64559); -#64556 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64557,#64558),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64557 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64558 = CARTESIAN_POINT('',(1.570796326795,0.3)); -#64559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64560 = ORIENTED_EDGE('',*,*,#51807,.T.); -#64561 = ORIENTED_EDGE('',*,*,#64513,.F.); -#64562 = ORIENTED_EDGE('',*,*,#61871,.F.); -#64563 = ADVANCED_FACE('',(#64564),#51852,.T.); -#64564 = FACE_BOUND('',#64565,.T.); -#64565 = EDGE_LOOP('',(#64566,#64586,#64587,#64588)); -#64566 = ORIENTED_EDGE('',*,*,#64567,.F.); -#64567 = EDGE_CURVE('',#61817,#51836,#64568,.T.); -#64568 = SURFACE_CURVE('',#64569,(#64573,#64579),.PCURVE_S1.); +#64402 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#64403 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#64404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64405 = ORIENTED_EDGE('',*,*,#64406,.T.); +#64406 = EDGE_CURVE('',#64384,#64407,#64409,.T.); +#64407 = VERTEX_POINT('',#64408); +#64408 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-2.35)); +#64409 = SURFACE_CURVE('',#64410,(#64414,#64421),.PCURVE_S1.); +#64410 = LINE('',#64411,#64412); +#64411 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); +#64412 = VECTOR('',#64413,1.); +#64413 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64414 = PCURVE('',#64217,#64415); +#64415 = DEFINITIONAL_REPRESENTATION('',(#64416),#64420); +#64416 = LINE('',#64417,#64418); +#64417 = CARTESIAN_POINT('',(-3.445,0.57)); +#64418 = VECTOR('',#64419,1.); +#64419 = DIRECTION('',(0.E+000,-1.)); +#64420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64421 = PCURVE('',#46128,#64422); +#64422 = DEFINITIONAL_REPRESENTATION('',(#64423),#64427); +#64423 = LINE('',#64424,#64425); +#64424 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64425 = VECTOR('',#64426,1.); +#64426 = DIRECTION('',(1.,0.E+000)); +#64427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64428 = ORIENTED_EDGE('',*,*,#64429,.T.); +#64429 = EDGE_CURVE('',#64407,#64430,#64432,.T.); +#64430 = VERTEX_POINT('',#64431); +#64431 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); +#64432 = SURFACE_CURVE('',#64433,(#64438,#64445),.PCURVE_S1.); +#64433 = CIRCLE('',#64434,0.25); +#64434 = AXIS2_PLACEMENT_3D('',#64435,#64436,#64437); +#64435 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002,-2.35)); +#64436 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64437 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64438 = PCURVE('',#64217,#64439); +#64439 = DEFINITIONAL_REPRESENTATION('',(#64440),#64444); +#64440 = CIRCLE('',#64441,0.25); +#64441 = AXIS2_PLACEMENT_2D('',#64442,#64443); +#64442 = CARTESIAN_POINT('',(-3.195,-6.937554159486E-002)); +#64443 = DIRECTION('',(-1.,0.E+000)); +#64444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64445 = PCURVE('',#46101,#64446); +#64446 = DEFINITIONAL_REPRESENTATION('',(#64447),#64450); +#64447 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64448,#64449),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); +#64448 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#64449 = CARTESIAN_POINT('',(3.926990816986,0.E+000)); +#64450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64451 = ORIENTED_EDGE('',*,*,#64452,.T.); +#64452 = EDGE_CURVE('',#64430,#64207,#64453,.T.); +#64453 = SURFACE_CURVE('',#64454,(#64458,#64465),.PCURVE_S1.); +#64454 = LINE('',#64455,#64456); +#64455 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); +#64456 = VECTOR('',#64457,1.); +#64457 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#64458 = PCURVE('',#64217,#64459); +#64459 = DEFINITIONAL_REPRESENTATION('',(#64460),#64464); +#64460 = LINE('',#64461,#64462); +#64461 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892)); +#64462 = VECTOR('',#64463,1.); +#64463 = DIRECTION('',(0.707106781187,-0.707106781187)); +#64464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64465 = PCURVE('',#46072,#64466); +#64466 = DEFINITIONAL_REPRESENTATION('',(#64467),#64471); +#64467 = LINE('',#64468,#64469); +#64468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64469 = VECTOR('',#64470,1.); +#64470 = DIRECTION('',(1.,0.E+000)); +#64471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64472 = ADVANCED_FACE('',(#64473),#45173,.F.); +#64473 = FACE_BOUND('',#64474,.F.); +#64474 = EDGE_LOOP('',(#64475,#64476,#64477,#64478,#64501,#64524,#64545, + #64546,#64547,#64548,#64574,#64575,#64601,#64602,#64628,#64629, + #64655,#64656)); +#64475 = ORIENTED_EDGE('',*,*,#63584,.F.); +#64476 = ORIENTED_EDGE('',*,*,#45157,.T.); +#64477 = ORIENTED_EDGE('',*,*,#45394,.T.); +#64478 = ORIENTED_EDGE('',*,*,#64479,.T.); +#64479 = EDGE_CURVE('',#45367,#64480,#64482,.T.); +#64480 = VERTEX_POINT('',#64481); +#64481 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); +#64482 = SURFACE_CURVE('',#64483,(#64487,#64494),.PCURVE_S1.); +#64483 = LINE('',#64484,#64485); +#64484 = CARTESIAN_POINT('',(1.925,-0.92,-2.35)); +#64485 = VECTOR('',#64486,1.); +#64486 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64487 = PCURVE('',#45173,#64488); +#64488 = DEFINITIONAL_REPRESENTATION('',(#64489),#64493); +#64489 = LINE('',#64490,#64491); +#64490 = CARTESIAN_POINT('',(1.925,-0.92)); +#64491 = VECTOR('',#64492,1.); +#64492 = DIRECTION('',(0.E+000,1.)); +#64493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64494 = PCURVE('',#54382,#64495); +#64495 = DEFINITIONAL_REPRESENTATION('',(#64496),#64500); +#64496 = LINE('',#64497,#64498); +#64497 = CARTESIAN_POINT('',(0.305,0.E+000)); +#64498 = VECTOR('',#64499,1.); +#64499 = DIRECTION('',(1.,0.E+000)); +#64500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64501 = ORIENTED_EDGE('',*,*,#64502,.T.); +#64502 = EDGE_CURVE('',#64480,#64503,#64505,.T.); +#64503 = VERTEX_POINT('',#64504); +#64504 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); +#64505 = SURFACE_CURVE('',#64506,(#64510,#64517),.PCURVE_S1.); +#64506 = LINE('',#64507,#64508); +#64507 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); +#64508 = VECTOR('',#64509,1.); +#64509 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64510 = PCURVE('',#45173,#64511); +#64511 = DEFINITIONAL_REPRESENTATION('',(#64512),#64516); +#64512 = LINE('',#64513,#64514); +#64513 = CARTESIAN_POINT('',(1.925,-0.725)); +#64514 = VECTOR('',#64515,1.); +#64515 = DIRECTION('',(-1.,0.E+000)); +#64516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64517 = PCURVE('',#54354,#64518); +#64518 = DEFINITIONAL_REPRESENTATION('',(#64519),#64523); +#64519 = LINE('',#64520,#64521); +#64520 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64521 = VECTOR('',#64522,1.); +#64522 = DIRECTION('',(1.,0.E+000)); +#64523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64524 = ORIENTED_EDGE('',*,*,#64525,.F.); +#64525 = EDGE_CURVE('',#45449,#64503,#64526,.T.); +#64526 = SURFACE_CURVE('',#64527,(#64531,#64538),.PCURVE_S1.); +#64527 = LINE('',#64528,#64529); +#64528 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); +#64529 = VECTOR('',#64530,1.); +#64530 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64531 = PCURVE('',#45173,#64532); +#64532 = DEFINITIONAL_REPRESENTATION('',(#64533),#64537); +#64533 = LINE('',#64534,#64535); +#64534 = CARTESIAN_POINT('',(-1.925,-0.92)); +#64535 = VECTOR('',#64536,1.); +#64536 = DIRECTION('',(0.E+000,1.)); +#64537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64538 = PCURVE('',#54326,#64539); +#64539 = DEFINITIONAL_REPRESENTATION('',(#64540),#64544); +#64540 = LINE('',#64541,#64542); +#64541 = CARTESIAN_POINT('',(0.195,0.E+000)); +#64542 = VECTOR('',#64543,1.); +#64543 = DIRECTION('',(-1.,0.E+000)); +#64544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64545 = ORIENTED_EDGE('',*,*,#45448,.T.); +#64546 = ORIENTED_EDGE('',*,*,#63912,.F.); +#64547 = ORIENTED_EDGE('',*,*,#62872,.F.); +#64548 = ORIENTED_EDGE('',*,*,#64549,.T.); +#64549 = EDGE_CURVE('',#62845,#63001,#64550,.T.); +#64550 = SURFACE_CURVE('',#64551,(#64555,#64562),.PCURVE_S1.); +#64551 = LINE('',#64552,#64553); +#64552 = CARTESIAN_POINT('',(-1.425,-1.105,-2.35)); +#64553 = VECTOR('',#64554,1.); +#64554 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64555 = PCURVE('',#45173,#64556); +#64556 = DEFINITIONAL_REPRESENTATION('',(#64557),#64561); +#64557 = LINE('',#64558,#64559); +#64558 = CARTESIAN_POINT('',(-1.425,-1.105)); +#64559 = VECTOR('',#64560,1.); +#64560 = DIRECTION('',(1.,0.E+000)); +#64561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64562 = PCURVE('',#64563,#64568); +#64563 = PLANE('',#64564); +#64564 = AXIS2_PLACEMENT_3D('',#64565,#64566,#64567); +#64565 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); +#64566 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64567 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64568 = DEFINITIONAL_REPRESENTATION('',(#64569),#64573); #64569 = LINE('',#64570,#64571); -#64570 = CARTESIAN_POINT('',(-3.,-0.375,-2.35)); +#64570 = CARTESIAN_POINT('',(0.3,0.E+000)); #64571 = VECTOR('',#64572,1.); -#64572 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64573 = PCURVE('',#51852,#64574); -#64574 = DEFINITIONAL_REPRESENTATION('',(#64575),#64578); -#64575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64576,#64577),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64577 = CARTESIAN_POINT('',(0.E+000,0.3)); -#64578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64579 = PCURVE('',#51879,#64580); -#64580 = DEFINITIONAL_REPRESENTATION('',(#64581),#64585); -#64581 = LINE('',#64582,#64583); -#64582 = CARTESIAN_POINT('',(0.85,0.E+000)); -#64583 = VECTOR('',#64584,1.); -#64584 = DIRECTION('',(0.E+000,1.)); -#64585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64586 = ORIENTED_EDGE('',*,*,#61844,.T.); -#64587 = ORIENTED_EDGE('',*,*,#64541,.T.); -#64588 = ORIENTED_EDGE('',*,*,#51835,.F.); -#64589 = ADVANCED_FACE('',(#64590),#51879,.T.); -#64590 = FACE_BOUND('',#64591,.F.); -#64591 = EDGE_LOOP('',(#64592,#64593,#64616,#64636,#64637,#64658,#64659, - #64660)); -#64592 = ORIENTED_EDGE('',*,*,#63138,.F.); -#64593 = ORIENTED_EDGE('',*,*,#64594,.F.); -#64594 = EDGE_CURVE('',#64595,#63111,#64597,.T.); -#64595 = VERTEX_POINT('',#64596); -#64596 = CARTESIAN_POINT('',(-3.,-0.925,-1.95)); -#64597 = SURFACE_CURVE('',#64598,(#64602,#64609),.PCURVE_S1.); -#64598 = LINE('',#64599,#64600); -#64599 = CARTESIAN_POINT('',(-3.,-0.925,-1.95)); -#64600 = VECTOR('',#64601,1.); -#64601 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64602 = PCURVE('',#51879,#64603); -#64603 = DEFINITIONAL_REPRESENTATION('',(#64604),#64608); -#64604 = LINE('',#64605,#64606); -#64605 = CARTESIAN_POINT('',(0.3,-0.4)); -#64606 = VECTOR('',#64607,1.); -#64607 = DIRECTION('',(0.E+000,1.)); -#64608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64609 = PCURVE('',#63126,#64610); +#64572 = DIRECTION('',(0.E+000,1.)); +#64573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64574 = ORIENTED_EDGE('',*,*,#63000,.F.); +#64575 = ORIENTED_EDGE('',*,*,#64576,.T.); +#64576 = EDGE_CURVE('',#62973,#63157,#64577,.T.); +#64577 = SURFACE_CURVE('',#64578,(#64582,#64589),.PCURVE_S1.); +#64578 = LINE('',#64579,#64580); +#64579 = CARTESIAN_POINT('',(-0.775,-1.105,-2.35)); +#64580 = VECTOR('',#64581,1.); +#64581 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64582 = PCURVE('',#45173,#64583); +#64583 = DEFINITIONAL_REPRESENTATION('',(#64584),#64588); +#64584 = LINE('',#64585,#64586); +#64585 = CARTESIAN_POINT('',(-0.775,-1.105)); +#64586 = VECTOR('',#64587,1.); +#64587 = DIRECTION('',(1.,0.E+000)); +#64588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64589 = PCURVE('',#64590,#64595); +#64590 = PLANE('',#64591); +#64591 = AXIS2_PLACEMENT_3D('',#64592,#64593,#64594); +#64592 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); +#64593 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64594 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64595 = DEFINITIONAL_REPRESENTATION('',(#64596),#64600); +#64596 = LINE('',#64597,#64598); +#64597 = CARTESIAN_POINT('',(0.3,0.E+000)); +#64598 = VECTOR('',#64599,1.); +#64599 = DIRECTION('',(0.E+000,1.)); +#64600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64601 = ORIENTED_EDGE('',*,*,#63156,.F.); +#64602 = ORIENTED_EDGE('',*,*,#64603,.T.); +#64603 = EDGE_CURVE('',#63129,#63313,#64604,.T.); +#64604 = SURFACE_CURVE('',#64605,(#64609,#64616),.PCURVE_S1.); +#64605 = LINE('',#64606,#64607); +#64606 = CARTESIAN_POINT('',(-0.125,-1.105,-2.35)); +#64607 = VECTOR('',#64608,1.); +#64608 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64609 = PCURVE('',#45173,#64610); #64610 = DEFINITIONAL_REPRESENTATION('',(#64611),#64615); #64611 = LINE('',#64612,#64613); -#64612 = CARTESIAN_POINT('',(-3.,-1.95)); +#64612 = CARTESIAN_POINT('',(-0.125,-1.105)); #64613 = VECTOR('',#64614,1.); -#64614 = DIRECTION('',(0.E+000,-1.)); +#64614 = DIRECTION('',(1.,0.E+000)); #64615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64616 = ORIENTED_EDGE('',*,*,#64617,.F.); -#64617 = EDGE_CURVE('',#62733,#64595,#64618,.T.); -#64618 = SURFACE_CURVE('',#64619,(#64623,#64630),.PCURVE_S1.); -#64619 = LINE('',#64620,#64621); -#64620 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); -#64621 = VECTOR('',#64622,1.); -#64622 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64623 = PCURVE('',#51879,#64624); -#64624 = DEFINITIONAL_REPRESENTATION('',(#64625),#64629); -#64625 = LINE('',#64626,#64627); -#64626 = CARTESIAN_POINT('',(0.E+000,-0.4)); -#64627 = VECTOR('',#64628,1.); -#64628 = DIRECTION('',(1.,0.E+000)); -#64629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64630 = PCURVE('',#62772,#64631); -#64631 = DEFINITIONAL_REPRESENTATION('',(#64632),#64635); -#64632 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64633,#64634),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64633 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#64634 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#64635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64636 = ORIENTED_EDGE('',*,*,#62732,.T.); -#64637 = ORIENTED_EDGE('',*,*,#64638,.F.); -#64638 = EDGE_CURVE('',#51864,#62711,#64639,.T.); -#64639 = SURFACE_CURVE('',#64640,(#64645,#64652),.PCURVE_S1.); -#64640 = CIRCLE('',#64641,0.3); -#64641 = AXIS2_PLACEMENT_3D('',#64642,#64643,#64644); -#64642 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); -#64643 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#64644 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64645 = PCURVE('',#51879,#64646); -#64646 = DEFINITIONAL_REPRESENTATION('',(#64647),#64651); -#64647 = CIRCLE('',#64648,0.3); -#64648 = AXIS2_PLACEMENT_2D('',#64649,#64650); -#64649 = CARTESIAN_POINT('',(0.3,0.E+000)); -#64650 = DIRECTION('',(0.E+000,1.)); -#64651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64652 = PCURVE('',#51907,#64653); -#64653 = DEFINITIONAL_REPRESENTATION('',(#64654),#64657); -#64654 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64655,#64656),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64655 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); -#64656 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); -#64657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64658 = ORIENTED_EDGE('',*,*,#51863,.T.); -#64659 = ORIENTED_EDGE('',*,*,#64567,.F.); -#64660 = ORIENTED_EDGE('',*,*,#61814,.F.); -#64661 = ADVANCED_FACE('',(#64662),#62488,.F.); -#64662 = FACE_BOUND('',#64663,.F.); -#64663 = EDGE_LOOP('',(#64664,#64665,#64666,#64689,#64712,#64733)); -#64664 = ORIENTED_EDGE('',*,*,#63033,.F.); -#64665 = ORIENTED_EDGE('',*,*,#62472,.T.); -#64666 = ORIENTED_EDGE('',*,*,#64667,.T.); -#64667 = EDGE_CURVE('',#62446,#64668,#64670,.T.); -#64668 = VERTEX_POINT('',#64669); -#64669 = CARTESIAN_POINT('',(2.8,-0.925,-1.75)); -#64670 = SURFACE_CURVE('',#64671,(#64676,#64683),.PCURVE_S1.); -#64671 = CIRCLE('',#64672,0.2); +#64616 = PCURVE('',#64617,#64622); +#64617 = PLANE('',#64618); +#64618 = AXIS2_PLACEMENT_3D('',#64619,#64620,#64621); +#64619 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); +#64620 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64621 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64622 = DEFINITIONAL_REPRESENTATION('',(#64623),#64627); +#64623 = LINE('',#64624,#64625); +#64624 = CARTESIAN_POINT('',(0.3,0.E+000)); +#64625 = VECTOR('',#64626,1.); +#64626 = DIRECTION('',(0.E+000,1.)); +#64627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64628 = ORIENTED_EDGE('',*,*,#63312,.F.); +#64629 = ORIENTED_EDGE('',*,*,#64630,.T.); +#64630 = EDGE_CURVE('',#63285,#63440,#64631,.T.); +#64631 = SURFACE_CURVE('',#64632,(#64636,#64643),.PCURVE_S1.); +#64632 = LINE('',#64633,#64634); +#64633 = CARTESIAN_POINT('',(0.525,-1.105,-2.35)); +#64634 = VECTOR('',#64635,1.); +#64635 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64636 = PCURVE('',#45173,#64637); +#64637 = DEFINITIONAL_REPRESENTATION('',(#64638),#64642); +#64638 = LINE('',#64639,#64640); +#64639 = CARTESIAN_POINT('',(0.525,-1.105)); +#64640 = VECTOR('',#64641,1.); +#64641 = DIRECTION('',(1.,0.E+000)); +#64642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64643 = PCURVE('',#64644,#64649); +#64644 = PLANE('',#64645); +#64645 = AXIS2_PLACEMENT_3D('',#64646,#64647,#64648); +#64646 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); +#64647 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64648 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64649 = DEFINITIONAL_REPRESENTATION('',(#64650),#64654); +#64650 = LINE('',#64651,#64652); +#64651 = CARTESIAN_POINT('',(0.3,0.E+000)); +#64652 = VECTOR('',#64653,1.); +#64653 = DIRECTION('',(0.E+000,1.)); +#64654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64655 = ORIENTED_EDGE('',*,*,#63439,.F.); +#64656 = ORIENTED_EDGE('',*,*,#64657,.T.); +#64657 = EDGE_CURVE('',#63412,#63585,#64658,.T.); +#64658 = SURFACE_CURVE('',#64659,(#64663,#64670),.PCURVE_S1.); +#64659 = LINE('',#64660,#64661); +#64660 = CARTESIAN_POINT('',(1.175,-1.105,-2.35)); +#64661 = VECTOR('',#64662,1.); +#64662 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64663 = PCURVE('',#45173,#64664); +#64664 = DEFINITIONAL_REPRESENTATION('',(#64665),#64669); +#64665 = LINE('',#64666,#64667); +#64666 = CARTESIAN_POINT('',(1.175,-1.105)); +#64667 = VECTOR('',#64668,1.); +#64668 = DIRECTION('',(1.,0.E+000)); +#64669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64670 = PCURVE('',#64671,#64676); +#64671 = PLANE('',#64672); #64672 = AXIS2_PLACEMENT_3D('',#64673,#64674,#64675); -#64673 = CARTESIAN_POINT('',(2.8,-0.925,-1.95)); -#64674 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64675 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64676 = PCURVE('',#62488,#64677); -#64677 = DEFINITIONAL_REPRESENTATION('',(#64678),#64682); -#64678 = CIRCLE('',#64679,0.2); -#64679 = AXIS2_PLACEMENT_2D('',#64680,#64681); -#64680 = CARTESIAN_POINT('',(2.8,-1.95)); -#64681 = DIRECTION('',(1.,0.E+000)); -#64682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64683 = PCURVE('',#62461,#64684); -#64684 = DEFINITIONAL_REPRESENTATION('',(#64685),#64688); -#64685 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64686,#64687),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64686 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#64687 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64689 = ORIENTED_EDGE('',*,*,#64690,.T.); -#64690 = EDGE_CURVE('',#64668,#64691,#64693,.T.); -#64691 = VERTEX_POINT('',#64692); -#64692 = CARTESIAN_POINT('',(2.125,-0.925,-1.75)); -#64693 = SURFACE_CURVE('',#64694,(#64698,#64705),.PCURVE_S1.); -#64694 = LINE('',#64695,#64696); -#64695 = CARTESIAN_POINT('',(2.8,-0.925,-1.75)); -#64696 = VECTOR('',#64697,1.); -#64697 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#64698 = PCURVE('',#62488,#64699); -#64699 = DEFINITIONAL_REPRESENTATION('',(#64700),#64704); -#64700 = LINE('',#64701,#64702); -#64701 = CARTESIAN_POINT('',(2.8,-1.75)); -#64702 = VECTOR('',#64703,1.); -#64703 = DIRECTION('',(-1.,0.E+000)); -#64704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64705 = PCURVE('',#62644,#64706); -#64706 = DEFINITIONAL_REPRESENTATION('',(#64707),#64711); -#64707 = LINE('',#64708,#64709); -#64708 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#64709 = VECTOR('',#64710,1.); -#64710 = DIRECTION('',(1.,0.E+000)); -#64711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64712 = ORIENTED_EDGE('',*,*,#64713,.T.); -#64713 = EDGE_CURVE('',#64691,#62864,#64714,.T.); -#64714 = SURFACE_CURVE('',#64715,(#64720,#64727),.PCURVE_S1.); -#64715 = CIRCLE('',#64716,0.2); -#64716 = AXIS2_PLACEMENT_3D('',#64717,#64718,#64719); -#64717 = CARTESIAN_POINT('',(2.125,-0.925,-1.95)); -#64718 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64719 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64720 = PCURVE('',#62488,#64721); -#64721 = DEFINITIONAL_REPRESENTATION('',(#64722),#64726); -#64722 = CIRCLE('',#64723,0.2); -#64723 = AXIS2_PLACEMENT_2D('',#64724,#64725); -#64724 = CARTESIAN_POINT('',(2.125,-1.95)); -#64725 = DIRECTION('',(0.E+000,1.)); -#64726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64727 = PCURVE('',#62617,#64728); -#64728 = DEFINITIONAL_REPRESENTATION('',(#64729),#64732); -#64729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64730,#64731),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64730 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64731 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#64732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64733 = ORIENTED_EDGE('',*,*,#62863,.T.); -#64734 = ADVANCED_FACE('',(#64735),#63126,.F.); -#64735 = FACE_BOUND('',#64736,.F.); -#64736 = EDGE_LOOP('',(#64737,#64738,#64761,#64784,#64807,#64828)); -#64737 = ORIENTED_EDGE('',*,*,#63108,.F.); -#64738 = ORIENTED_EDGE('',*,*,#64739,.T.); -#64739 = EDGE_CURVE('',#63109,#64740,#64742,.T.); -#64740 = VERTEX_POINT('',#64741); -#64741 = CARTESIAN_POINT('',(-1.925,-0.925,-1.95)); -#64742 = SURFACE_CURVE('',#64743,(#64747,#64754),.PCURVE_S1.); -#64743 = LINE('',#64744,#64745); -#64744 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); -#64745 = VECTOR('',#64746,1.); -#64746 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64747 = PCURVE('',#63126,#64748); -#64748 = DEFINITIONAL_REPRESENTATION('',(#64749),#64753); -#64749 = LINE('',#64750,#64751); -#64750 = CARTESIAN_POINT('',(-1.925,-2.35)); -#64751 = VECTOR('',#64752,1.); -#64752 = DIRECTION('',(0.E+000,1.)); -#64753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64754 = PCURVE('',#51934,#64755); -#64755 = DEFINITIONAL_REPRESENTATION('',(#64756),#64760); -#64756 = LINE('',#64757,#64758); -#64757 = CARTESIAN_POINT('',(0.2,0.E+000)); -#64758 = VECTOR('',#64759,1.); -#64759 = DIRECTION('',(0.E+000,-1.)); -#64760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#64673 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); +#64674 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64675 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64676 = DEFINITIONAL_REPRESENTATION('',(#64677),#64681); +#64677 = LINE('',#64678,#64679); +#64678 = CARTESIAN_POINT('',(0.3,0.E+000)); +#64679 = VECTOR('',#64680,1.); +#64680 = DIRECTION('',(0.E+000,1.)); +#64681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64682 = ADVANCED_FACE('',(#64683),#53981,.T.); +#64683 = FACE_BOUND('',#64684,.F.); +#64684 = EDGE_LOOP('',(#64685,#64686,#64687,#64708,#64709)); +#64685 = ORIENTED_EDGE('',*,*,#53965,.T.); +#64686 = ORIENTED_EDGE('',*,*,#54505,.T.); +#64687 = ORIENTED_EDGE('',*,*,#64688,.F.); +#64688 = EDGE_CURVE('',#63939,#54478,#64689,.T.); +#64689 = SURFACE_CURVE('',#64690,(#64694,#64701),.PCURVE_S1.); +#64690 = LINE('',#64691,#64692); +#64691 = CARTESIAN_POINT('',(1.902820323028,0.175,-2.35)); +#64692 = VECTOR('',#64693,1.); +#64693 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64694 = PCURVE('',#53981,#64695); +#64695 = DEFINITIONAL_REPRESENTATION('',(#64696),#64700); +#64696 = LINE('',#64697,#64698); +#64697 = CARTESIAN_POINT('',(0.8,0.E+000)); +#64698 = VECTOR('',#64699,1.); +#64699 = DIRECTION('',(0.E+000,1.)); +#64700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64701 = PCURVE('',#54493,#64702); +#64702 = DEFINITIONAL_REPRESENTATION('',(#64703),#64707); +#64703 = LINE('',#64704,#64705); +#64704 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64705 = VECTOR('',#64706,1.); +#64706 = DIRECTION('',(0.E+000,1.)); +#64707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64708 = ORIENTED_EDGE('',*,*,#63936,.F.); +#64709 = ORIENTED_EDGE('',*,*,#64710,.F.); +#64710 = EDGE_CURVE('',#53966,#63937,#64711,.T.); +#64711 = SURFACE_CURVE('',#64712,(#64716,#64723),.PCURVE_S1.); +#64712 = LINE('',#64713,#64714); +#64713 = CARTESIAN_POINT('',(1.21,0.575,-2.35)); +#64714 = VECTOR('',#64715,1.); +#64715 = DIRECTION('',(0.866025403784,-0.5,0.E+000)); +#64716 = PCURVE('',#53981,#64717); +#64717 = DEFINITIONAL_REPRESENTATION('',(#64718),#64722); +#64718 = LINE('',#64719,#64720); +#64719 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64720 = VECTOR('',#64721,1.); +#64721 = DIRECTION('',(1.,0.E+000)); +#64722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64723 = PCURVE('',#54009,#64724); +#64724 = DEFINITIONAL_REPRESENTATION('',(#64725),#64729); +#64725 = LINE('',#64726,#64727); +#64726 = CARTESIAN_POINT('',(-1.21,0.575)); +#64727 = VECTOR('',#64728,1.); +#64728 = DIRECTION('',(-0.866025403784,-0.5)); +#64729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64730 = ADVANCED_FACE('',(#64731),#54493,.T.); +#64731 = FACE_BOUND('',#64732,.F.); +#64732 = EDGE_LOOP('',(#64733,#64734,#64735,#64755)); +#64733 = ORIENTED_EDGE('',*,*,#64688,.T.); +#64734 = ORIENTED_EDGE('',*,*,#54477,.T.); +#64735 = ORIENTED_EDGE('',*,*,#64736,.F.); +#64736 = EDGE_CURVE('',#63967,#54450,#64737,.T.); +#64737 = SURFACE_CURVE('',#64738,(#64742,#64749),.PCURVE_S1.); +#64738 = LINE('',#64739,#64740); +#64739 = CARTESIAN_POINT('',(2.45,0.175,-2.35)); +#64740 = VECTOR('',#64741,1.); +#64741 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64742 = PCURVE('',#54493,#64743); +#64743 = DEFINITIONAL_REPRESENTATION('',(#64744),#64748); +#64744 = LINE('',#64745,#64746); +#64745 = CARTESIAN_POINT('',(0.547179676972,0.E+000)); +#64746 = VECTOR('',#64747,1.); +#64747 = DIRECTION('',(0.E+000,1.)); +#64748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64749 = PCURVE('',#54466,#64750); +#64750 = DEFINITIONAL_REPRESENTATION('',(#64751),#64754); +#64751 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64752,#64753),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#64752 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#64753 = CARTESIAN_POINT('',(1.570796326795,0.3)); +#64754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); +#64755 = ORIENTED_EDGE('',*,*,#63966,.F.); +#64756 = ADVANCED_FACE('',(#64757),#54466,.T.); +#64757 = FACE_BOUND('',#64758,.T.); +#64758 = EDGE_LOOP('',(#64759,#64760,#64761,#64781)); +#64759 = ORIENTED_EDGE('',*,*,#64736,.F.); +#64760 = ORIENTED_EDGE('',*,*,#63989,.T.); #64761 = ORIENTED_EDGE('',*,*,#64762,.T.); -#64762 = EDGE_CURVE('',#64740,#64763,#64765,.T.); -#64763 = VERTEX_POINT('',#64764); -#64764 = CARTESIAN_POINT('',(-2.125,-0.925,-1.75)); -#64765 = SURFACE_CURVE('',#64766,(#64771,#64778),.PCURVE_S1.); -#64766 = CIRCLE('',#64767,0.2); -#64767 = AXIS2_PLACEMENT_3D('',#64768,#64769,#64770); -#64768 = CARTESIAN_POINT('',(-2.125,-0.925,-1.95)); -#64769 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64770 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64771 = PCURVE('',#63126,#64772); -#64772 = DEFINITIONAL_REPRESENTATION('',(#64773),#64777); -#64773 = CIRCLE('',#64774,0.2); -#64774 = AXIS2_PLACEMENT_2D('',#64775,#64776); -#64775 = CARTESIAN_POINT('',(-2.125,-1.95)); -#64776 = DIRECTION('',(1.,0.E+000)); -#64777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64778 = PCURVE('',#62826,#64779); -#64779 = DEFINITIONAL_REPRESENTATION('',(#64780),#64783); -#64780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64781,#64782),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64781 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#64782 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64784 = ORIENTED_EDGE('',*,*,#64785,.T.); -#64785 = EDGE_CURVE('',#64763,#64786,#64788,.T.); -#64786 = VERTEX_POINT('',#64787); -#64787 = CARTESIAN_POINT('',(-2.8,-0.925,-1.75)); -#64788 = SURFACE_CURVE('',#64789,(#64793,#64800),.PCURVE_S1.); -#64789 = LINE('',#64790,#64791); -#64790 = CARTESIAN_POINT('',(-2.125,-0.925,-1.75)); -#64791 = VECTOR('',#64792,1.); -#64792 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#64793 = PCURVE('',#63126,#64794); -#64794 = DEFINITIONAL_REPRESENTATION('',(#64795),#64799); -#64795 = LINE('',#64796,#64797); -#64796 = CARTESIAN_POINT('',(-2.125,-1.75)); -#64797 = VECTOR('',#64798,1.); -#64798 = DIRECTION('',(-1.,0.E+000)); -#64799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64800 = PCURVE('',#62799,#64801); -#64801 = DEFINITIONAL_REPRESENTATION('',(#64802),#64806); -#64802 = LINE('',#64803,#64804); -#64803 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#64804 = VECTOR('',#64805,1.); -#64805 = DIRECTION('',(1.,0.E+000)); -#64806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64807 = ORIENTED_EDGE('',*,*,#64808,.T.); -#64808 = EDGE_CURVE('',#64786,#64595,#64809,.T.); -#64809 = SURFACE_CURVE('',#64810,(#64815,#64822),.PCURVE_S1.); -#64810 = CIRCLE('',#64811,0.2); -#64811 = AXIS2_PLACEMENT_3D('',#64812,#64813,#64814); -#64812 = CARTESIAN_POINT('',(-2.8,-0.925,-1.95)); -#64813 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64814 = DIRECTION('',(0.E+000,0.E+000,1.)); -#64815 = PCURVE('',#63126,#64816); -#64816 = DEFINITIONAL_REPRESENTATION('',(#64817),#64821); -#64817 = CIRCLE('',#64818,0.2); -#64818 = AXIS2_PLACEMENT_2D('',#64819,#64820); -#64819 = CARTESIAN_POINT('',(-2.8,-1.95)); -#64820 = DIRECTION('',(0.E+000,1.)); -#64821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64822 = PCURVE('',#62772,#64823); -#64823 = DEFINITIONAL_REPRESENTATION('',(#64824),#64827); -#64824 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64825,#64826),.UNSPECIFIED., +#64762 = EDGE_CURVE('',#63990,#54422,#64763,.T.); +#64763 = SURFACE_CURVE('',#64764,(#64768,#64774),.PCURVE_S1.); +#64764 = LINE('',#64765,#64766); +#64765 = CARTESIAN_POINT('',(3.,-0.375,-2.35)); +#64766 = VECTOR('',#64767,1.); +#64767 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64768 = PCURVE('',#54466,#64769); +#64769 = DEFINITIONAL_REPRESENTATION('',(#64770),#64773); +#64770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64771,#64772),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#64771 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#64772 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#64773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64774 = PCURVE('',#54437,#64775); +#64775 = DEFINITIONAL_REPRESENTATION('',(#64776),#64780); +#64776 = LINE('',#64777,#64778); +#64777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64778 = VECTOR('',#64779,1.); +#64779 = DIRECTION('',(0.E+000,1.)); +#64780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64781 = ORIENTED_EDGE('',*,*,#54449,.F.); +#64782 = ADVANCED_FACE('',(#64783),#54437,.T.); +#64783 = FACE_BOUND('',#64784,.F.); +#64784 = EDGE_LOOP('',(#64785,#64808,#64836,#64863,#64891,#64912,#64913, + #64914)); +#64785 = ORIENTED_EDGE('',*,*,#64786,.F.); +#64786 = EDGE_CURVE('',#64787,#54395,#64789,.T.); +#64787 = VERTEX_POINT('',#64788); +#64788 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); +#64789 = SURFACE_CURVE('',#64790,(#64795,#64802),.PCURVE_S1.); +#64790 = CIRCLE('',#64791,0.3); +#64791 = AXIS2_PLACEMENT_3D('',#64792,#64793,#64794); +#64792 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); +#64793 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64794 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64795 = PCURVE('',#54437,#64796); +#64796 = DEFINITIONAL_REPRESENTATION('',(#64797),#64801); +#64797 = CIRCLE('',#64798,0.3); +#64798 = AXIS2_PLACEMENT_2D('',#64799,#64800); +#64799 = CARTESIAN_POINT('',(0.55,0.E+000)); +#64800 = DIRECTION('',(1.,0.E+000)); +#64801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64802 = PCURVE('',#54410,#64803); +#64803 = DEFINITIONAL_REPRESENTATION('',(#64804),#64807); +#64804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64805,#64806),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64825 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64826 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#64827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64828 = ORIENTED_EDGE('',*,*,#64594,.T.); -#64829 = ADVANCED_FACE('',(#64830),#62461,.T.); -#64830 = FACE_BOUND('',#64831,.T.); -#64831 = EDGE_LOOP('',(#64832,#64833,#64834,#64835)); -#64832 = ORIENTED_EDGE('',*,*,#62656,.F.); -#64833 = ORIENTED_EDGE('',*,*,#62445,.T.); -#64834 = ORIENTED_EDGE('',*,*,#64667,.T.); -#64835 = ORIENTED_EDGE('',*,*,#64836,.F.); -#64836 = EDGE_CURVE('',#62629,#64668,#64837,.T.); -#64837 = SURFACE_CURVE('',#64838,(#64842,#64848),.PCURVE_S1.); -#64838 = LINE('',#64839,#64840); -#64839 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); -#64840 = VECTOR('',#64841,1.); -#64841 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64842 = PCURVE('',#62461,#64843); -#64843 = DEFINITIONAL_REPRESENTATION('',(#64844),#64847); -#64844 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64845,#64846),.UNSPECIFIED., +#64805 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#64806 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#64807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64808 = ORIENTED_EDGE('',*,*,#64809,.T.); +#64809 = EDGE_CURVE('',#64787,#64810,#64812,.T.); +#64810 = VERTEX_POINT('',#64811); +#64811 = CARTESIAN_POINT('',(3.,-1.225,-1.95)); +#64812 = SURFACE_CURVE('',#64813,(#64817,#64824),.PCURVE_S1.); +#64813 = LINE('',#64814,#64815); +#64814 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); +#64815 = VECTOR('',#64816,1.); +#64816 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64817 = PCURVE('',#54437,#64818); +#64818 = DEFINITIONAL_REPRESENTATION('',(#64819),#64823); +#64819 = LINE('',#64820,#64821); +#64820 = CARTESIAN_POINT('',(0.85,0.E+000)); +#64821 = VECTOR('',#64822,1.); +#64822 = DIRECTION('',(0.E+000,-1.)); +#64823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64824 = PCURVE('',#64825,#64830); +#64825 = PLANE('',#64826); +#64826 = AXIS2_PLACEMENT_3D('',#64827,#64828,#64829); +#64827 = CARTESIAN_POINT('',(0.E+000,-1.225,0.E+000)); +#64828 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64829 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64830 = DEFINITIONAL_REPRESENTATION('',(#64831),#64835); +#64831 = LINE('',#64832,#64833); +#64832 = CARTESIAN_POINT('',(3.,-2.35)); +#64833 = VECTOR('',#64834,1.); +#64834 = DIRECTION('',(0.E+000,1.)); +#64835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64836 = ORIENTED_EDGE('',*,*,#64837,.T.); +#64837 = EDGE_CURVE('',#64810,#64838,#64840,.T.); +#64838 = VERTEX_POINT('',#64839); +#64839 = CARTESIAN_POINT('',(3.,-0.925,-1.95)); +#64840 = SURFACE_CURVE('',#64841,(#64845,#64852),.PCURVE_S1.); +#64841 = LINE('',#64842,#64843); +#64842 = CARTESIAN_POINT('',(3.,-1.225,-1.95)); +#64843 = VECTOR('',#64844,1.); +#64844 = DIRECTION('',(0.E+000,1.,0.E+000)); +#64845 = PCURVE('',#54437,#64846); +#64846 = DEFINITIONAL_REPRESENTATION('',(#64847),#64851); +#64847 = LINE('',#64848,#64849); +#64848 = CARTESIAN_POINT('',(0.85,-0.4)); +#64849 = VECTOR('',#64850,1.); +#64850 = DIRECTION('',(-1.,0.E+000)); +#64851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64852 = PCURVE('',#64853,#64858); +#64853 = CYLINDRICAL_SURFACE('',#64854,0.2); +#64854 = AXIS2_PLACEMENT_3D('',#64855,#64856,#64857); +#64855 = CARTESIAN_POINT('',(2.8,-1.225,-1.95)); +#64856 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64857 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64858 = DEFINITIONAL_REPRESENTATION('',(#64859),#64862); +#64859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64860,#64861),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64845 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64846 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64848 = PCURVE('',#62644,#64849); -#64849 = DEFINITIONAL_REPRESENTATION('',(#64850),#64854); -#64850 = LINE('',#64851,#64852); -#64851 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64852 = VECTOR('',#64853,1.); -#64853 = DIRECTION('',(0.E+000,-1.)); -#64854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64855 = ADVANCED_FACE('',(#64856),#62644,.T.); -#64856 = FACE_BOUND('',#64857,.F.); -#64857 = EDGE_LOOP('',(#64858,#64859,#64879,#64880)); -#64858 = ORIENTED_EDGE('',*,*,#62628,.T.); -#64859 = ORIENTED_EDGE('',*,*,#64860,.T.); -#64860 = EDGE_CURVE('',#62601,#64691,#64861,.T.); -#64861 = SURFACE_CURVE('',#64862,(#64866,#64873),.PCURVE_S1.); -#64862 = LINE('',#64863,#64864); -#64863 = CARTESIAN_POINT('',(2.125,-1.225,-1.75)); -#64864 = VECTOR('',#64865,1.); -#64865 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64866 = PCURVE('',#62644,#64867); -#64867 = DEFINITIONAL_REPRESENTATION('',(#64868),#64872); +#64860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64861 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#64862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64863 = ORIENTED_EDGE('',*,*,#64864,.F.); +#64864 = EDGE_CURVE('',#64865,#64838,#64867,.T.); +#64865 = VERTEX_POINT('',#64866); +#64866 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); +#64867 = SURFACE_CURVE('',#64868,(#64872,#64879),.PCURVE_S1.); #64868 = LINE('',#64869,#64870); -#64869 = CARTESIAN_POINT('',(0.675,0.E+000)); +#64869 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); #64870 = VECTOR('',#64871,1.); -#64871 = DIRECTION('',(0.E+000,-1.)); -#64872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#64871 = DIRECTION('',(0.E+000,0.E+000,1.)); +#64872 = PCURVE('',#54437,#64873); +#64873 = DEFINITIONAL_REPRESENTATION('',(#64874),#64878); +#64874 = LINE('',#64875,#64876); +#64875 = CARTESIAN_POINT('',(0.55,0.E+000)); +#64876 = VECTOR('',#64877,1.); +#64877 = DIRECTION('',(0.E+000,-1.)); +#64878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64873 = PCURVE('',#62617,#64874); -#64874 = DEFINITIONAL_REPRESENTATION('',(#64875),#64878); -#64875 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64876,#64877),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64876 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64877 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#64878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#64879 = PCURVE('',#64880,#64885); +#64880 = PLANE('',#64881); +#64881 = AXIS2_PLACEMENT_3D('',#64882,#64883,#64884); +#64882 = CARTESIAN_POINT('',(0.E+000,-0.925,0.E+000)); +#64883 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64884 = DIRECTION('',(1.,0.E+000,0.E+000)); +#64885 = DEFINITIONAL_REPRESENTATION('',(#64886),#64890); +#64886 = LINE('',#64887,#64888); +#64887 = CARTESIAN_POINT('',(3.,-2.35)); +#64888 = VECTOR('',#64889,1.); +#64889 = DIRECTION('',(0.E+000,1.)); +#64890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64879 = ORIENTED_EDGE('',*,*,#64690,.F.); -#64880 = ORIENTED_EDGE('',*,*,#64836,.F.); -#64881 = ADVANCED_FACE('',(#64882),#62617,.T.); -#64882 = FACE_BOUND('',#64883,.T.); -#64883 = EDGE_LOOP('',(#64884,#64885,#64886,#64887)); -#64884 = ORIENTED_EDGE('',*,*,#62600,.F.); -#64885 = ORIENTED_EDGE('',*,*,#64860,.T.); -#64886 = ORIENTED_EDGE('',*,*,#64713,.T.); -#64887 = ORIENTED_EDGE('',*,*,#62886,.F.); -#64888 = ADVANCED_FACE('',(#64889),#51934,.T.); -#64889 = FACE_BOUND('',#64890,.F.); -#64890 = EDGE_LOOP('',(#64891,#64912,#64913,#64933,#64934,#64935,#64936, - #64957)); #64891 = ORIENTED_EDGE('',*,*,#64892,.F.); -#64892 = EDGE_CURVE('',#62681,#51892,#64893,.T.); -#64893 = SURFACE_CURVE('',#64894,(#64899,#64906),.PCURVE_S1.); -#64894 = CIRCLE('',#64895,0.3); -#64895 = AXIS2_PLACEMENT_3D('',#64896,#64897,#64898); -#64896 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); -#64897 = DIRECTION('',(1.,0.E+000,0.E+000)); -#64898 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#64899 = PCURVE('',#51934,#64900); -#64900 = DEFINITIONAL_REPRESENTATION('',(#64901),#64905); -#64901 = CIRCLE('',#64902,0.3); -#64902 = AXIS2_PLACEMENT_2D('',#64903,#64904); -#64903 = CARTESIAN_POINT('',(0.2,0.E+000)); -#64904 = DIRECTION('',(1.,0.E+000)); -#64905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64906 = PCURVE('',#51907,#64907); -#64907 = DEFINITIONAL_REPRESENTATION('',(#64908),#64911); -#64908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64909,#64910),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#64909 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); -#64910 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#64892 = EDGE_CURVE('',#64017,#64865,#64893,.T.); +#64893 = SURFACE_CURVE('',#64894,(#64898,#64905),.PCURVE_S1.); +#64894 = LINE('',#64895,#64896); +#64895 = CARTESIAN_POINT('',(3.,-0.617928932188,-2.35)); +#64896 = VECTOR('',#64897,1.); +#64897 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#64898 = PCURVE('',#54437,#64899); +#64899 = DEFINITIONAL_REPRESENTATION('',(#64900),#64904); +#64900 = LINE('',#64901,#64902); +#64901 = CARTESIAN_POINT('',(0.242928932188,0.E+000)); +#64902 = VECTOR('',#64903,1.); +#64903 = DIRECTION('',(1.,0.E+000)); +#64904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64905 = PCURVE('',#45382,#64906); +#64906 = DEFINITIONAL_REPRESENTATION('',(#64907),#64911); +#64907 = LINE('',#64908,#64909); +#64908 = CARTESIAN_POINT('',(-3.,-0.617928932188)); +#64909 = VECTOR('',#64910,1.); +#64910 = DIRECTION('',(0.E+000,-1.)); #64911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64912 = ORIENTED_EDGE('',*,*,#62680,.T.); -#64913 = ORIENTED_EDGE('',*,*,#64914,.T.); -#64914 = EDGE_CURVE('',#62683,#64740,#64915,.T.); -#64915 = SURFACE_CURVE('',#64916,(#64920,#64927),.PCURVE_S1.); -#64916 = LINE('',#64917,#64918); -#64917 = CARTESIAN_POINT('',(-1.925,-1.225,-1.95)); -#64918 = VECTOR('',#64919,1.); -#64919 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64920 = PCURVE('',#51934,#64921); -#64921 = DEFINITIONAL_REPRESENTATION('',(#64922),#64926); -#64922 = LINE('',#64923,#64924); -#64923 = CARTESIAN_POINT('',(0.5,-0.4)); -#64924 = VECTOR('',#64925,1.); -#64925 = DIRECTION('',(-1.,0.E+000)); -#64926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64927 = PCURVE('',#62826,#64928); +#64912 = ORIENTED_EDGE('',*,*,#64016,.T.); +#64913 = ORIENTED_EDGE('',*,*,#64762,.T.); +#64914 = ORIENTED_EDGE('',*,*,#54421,.T.); +#64915 = ADVANCED_FACE('',(#64916),#54410,.T.); +#64916 = FACE_BOUND('',#64917,.T.); +#64917 = EDGE_LOOP('',(#64918,#64940,#64961,#64962)); +#64918 = ORIENTED_EDGE('',*,*,#64919,.T.); +#64919 = EDGE_CURVE('',#64787,#64920,#64922,.T.); +#64920 = VERTEX_POINT('',#64921); +#64921 = CARTESIAN_POINT('',(1.925,-1.225,-2.35)); +#64922 = SURFACE_CURVE('',#64923,(#64927,#64933),.PCURVE_S1.); +#64923 = LINE('',#64924,#64925); +#64924 = CARTESIAN_POINT('',(3.,-1.225,-2.35)); +#64925 = VECTOR('',#64926,1.); +#64926 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64927 = PCURVE('',#54410,#64928); #64928 = DEFINITIONAL_REPRESENTATION('',(#64929),#64932); #64929 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64930,#64931),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64931 = CARTESIAN_POINT('',(0.E+000,-0.3)); + .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); +#64930 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#64931 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); #64932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64933 = ORIENTED_EDGE('',*,*,#64739,.F.); -#64934 = ORIENTED_EDGE('',*,*,#63208,.F.); -#64935 = ORIENTED_EDGE('',*,*,#62133,.T.); -#64936 = ORIENTED_EDGE('',*,*,#64937,.T.); -#64937 = EDGE_CURVE('',#62111,#51919,#64938,.T.); -#64938 = SURFACE_CURVE('',#64939,(#64943,#64950),.PCURVE_S1.); -#64939 = LINE('',#64940,#64941); -#64940 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); -#64941 = VECTOR('',#64942,1.); -#64942 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#64943 = PCURVE('',#51934,#64944); -#64944 = DEFINITIONAL_REPRESENTATION('',(#64945),#64949); -#64945 = LINE('',#64946,#64947); -#64946 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#64947 = VECTOR('',#64948,1.); -#64948 = DIRECTION('',(0.E+000,1.)); -#64949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64950 = PCURVE('',#51962,#64951); -#64951 = DEFINITIONAL_REPRESENTATION('',(#64952),#64956); -#64952 = LINE('',#64953,#64954); -#64953 = CARTESIAN_POINT('',(3.85,0.E+000)); -#64954 = VECTOR('',#64955,1.); -#64955 = DIRECTION('',(0.E+000,1.)); -#64956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#64957 = ORIENTED_EDGE('',*,*,#51918,.T.); -#64958 = ADVANCED_FACE('',(#64959),#51907,.T.); -#64959 = FACE_BOUND('',#64960,.T.); -#64960 = EDGE_LOOP('',(#64961,#64962,#64963,#64964)); -#64961 = ORIENTED_EDGE('',*,*,#62710,.T.); -#64962 = ORIENTED_EDGE('',*,*,#64638,.F.); -#64963 = ORIENTED_EDGE('',*,*,#51891,.F.); -#64964 = ORIENTED_EDGE('',*,*,#64892,.F.); -#64965 = ADVANCED_FACE('',(#64966),#62826,.T.); -#64966 = FACE_BOUND('',#64967,.T.); -#64967 = EDGE_LOOP('',(#64968,#64969,#64970,#64971)); -#64968 = ORIENTED_EDGE('',*,*,#62811,.F.); -#64969 = ORIENTED_EDGE('',*,*,#64914,.T.); -#64970 = ORIENTED_EDGE('',*,*,#64762,.T.); -#64971 = ORIENTED_EDGE('',*,*,#64972,.F.); -#64972 = EDGE_CURVE('',#62784,#64763,#64973,.T.); -#64973 = SURFACE_CURVE('',#64974,(#64978,#64984),.PCURVE_S1.); -#64974 = LINE('',#64975,#64976); -#64975 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); -#64976 = VECTOR('',#64977,1.); -#64977 = DIRECTION('',(0.E+000,1.,0.E+000)); -#64978 = PCURVE('',#62826,#64979); -#64979 = DEFINITIONAL_REPRESENTATION('',(#64980),#64983); -#64980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64981,#64982),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#64981 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#64982 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#64933 = PCURVE('',#64825,#64934); +#64934 = DEFINITIONAL_REPRESENTATION('',(#64935),#64939); +#64935 = LINE('',#64936,#64937); +#64936 = CARTESIAN_POINT('',(3.,-2.35)); +#64937 = VECTOR('',#64938,1.); +#64938 = DIRECTION('',(-1.,0.E+000)); +#64939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64940 = ORIENTED_EDGE('',*,*,#64941,.F.); +#64941 = EDGE_CURVE('',#54367,#64920,#64942,.T.); +#64942 = SURFACE_CURVE('',#64943,(#64948,#64954),.PCURVE_S1.); +#64943 = CIRCLE('',#64944,0.3); +#64944 = AXIS2_PLACEMENT_3D('',#64945,#64946,#64947); +#64945 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); +#64946 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#64947 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64948 = PCURVE('',#54410,#64949); +#64949 = DEFINITIONAL_REPRESENTATION('',(#64950),#64953); +#64950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#64951,#64952),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#64951 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); +#64952 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); +#64953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64954 = PCURVE('',#54382,#64955); +#64955 = DEFINITIONAL_REPRESENTATION('',(#64956),#64960); +#64956 = CIRCLE('',#64957,0.3); +#64957 = AXIS2_PLACEMENT_2D('',#64958,#64959); +#64958 = CARTESIAN_POINT('',(0.3,0.E+000)); +#64959 = DIRECTION('',(0.E+000,1.)); +#64960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#64961 = ORIENTED_EDGE('',*,*,#54394,.F.); +#64962 = ORIENTED_EDGE('',*,*,#64786,.F.); +#64963 = ADVANCED_FACE('',(#64964),#64825,.T.); +#64964 = FACE_BOUND('',#64965,.F.); +#64965 = EDGE_LOOP('',(#64966,#64967,#64968,#64991,#65019,#65047)); +#64966 = ORIENTED_EDGE('',*,*,#64809,.F.); +#64967 = ORIENTED_EDGE('',*,*,#64919,.T.); +#64968 = ORIENTED_EDGE('',*,*,#64969,.F.); +#64969 = EDGE_CURVE('',#64970,#64920,#64972,.T.); +#64970 = VERTEX_POINT('',#64971); +#64971 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); +#64972 = SURFACE_CURVE('',#64973,(#64977,#64984),.PCURVE_S1.); +#64973 = LINE('',#64974,#64975); +#64974 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); +#64975 = VECTOR('',#64976,1.); +#64976 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#64977 = PCURVE('',#64825,#64978); +#64978 = DEFINITIONAL_REPRESENTATION('',(#64979),#64983); +#64979 = LINE('',#64980,#64981); +#64980 = CARTESIAN_POINT('',(1.925,-1.95)); +#64981 = VECTOR('',#64982,1.); +#64982 = DIRECTION('',(0.E+000,-1.)); #64983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64984 = PCURVE('',#62799,#64985); +#64984 = PCURVE('',#54382,#64985); #64985 = DEFINITIONAL_REPRESENTATION('',(#64986),#64990); #64986 = LINE('',#64987,#64988); -#64987 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#64987 = CARTESIAN_POINT('',(0.E+000,-0.4)); #64988 = VECTOR('',#64989,1.); -#64989 = DIRECTION('',(0.E+000,-1.)); +#64989 = DIRECTION('',(0.E+000,1.)); #64990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#64991 = ADVANCED_FACE('',(#64992),#62799,.T.); -#64992 = FACE_BOUND('',#64993,.F.); -#64993 = EDGE_LOOP('',(#64994,#64995,#65015,#65016)); -#64994 = ORIENTED_EDGE('',*,*,#62783,.T.); -#64995 = ORIENTED_EDGE('',*,*,#64996,.T.); -#64996 = EDGE_CURVE('',#62756,#64786,#64997,.T.); -#64997 = SURFACE_CURVE('',#64998,(#65002,#65009),.PCURVE_S1.); -#64998 = LINE('',#64999,#65000); -#64999 = CARTESIAN_POINT('',(-2.8,-1.225,-1.75)); -#65000 = VECTOR('',#65001,1.); -#65001 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65002 = PCURVE('',#62799,#65003); -#65003 = DEFINITIONAL_REPRESENTATION('',(#65004),#65008); -#65004 = LINE('',#65005,#65006); -#65005 = CARTESIAN_POINT('',(0.675,0.E+000)); -#65006 = VECTOR('',#65007,1.); -#65007 = DIRECTION('',(0.E+000,-1.)); -#65008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65009 = PCURVE('',#62772,#65010); -#65010 = DEFINITIONAL_REPRESENTATION('',(#65011),#65014); -#65011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65012,#65013),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#65012 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#65013 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#65014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65015 = ORIENTED_EDGE('',*,*,#64785,.F.); -#65016 = ORIENTED_EDGE('',*,*,#64972,.F.); -#65017 = ADVANCED_FACE('',(#65018),#62772,.T.); -#65018 = FACE_BOUND('',#65019,.T.); -#65019 = EDGE_LOOP('',(#65020,#65021,#65022,#65023)); -#65020 = ORIENTED_EDGE('',*,*,#62755,.F.); -#65021 = ORIENTED_EDGE('',*,*,#64996,.T.); -#65022 = ORIENTED_EDGE('',*,*,#64808,.T.); -#65023 = ORIENTED_EDGE('',*,*,#64617,.F.); -#65024 = ADVANCED_FACE('',(#65025),#51962,.T.); -#65025 = FACE_BOUND('',#65026,.F.); -#65026 = EDGE_LOOP('',(#65027,#65028,#65029,#65030)); -#65027 = ORIENTED_EDGE('',*,*,#62909,.T.); -#65028 = ORIENTED_EDGE('',*,*,#51946,.T.); -#65029 = ORIENTED_EDGE('',*,*,#64937,.F.); -#65030 = ORIENTED_EDGE('',*,*,#62110,.F.); -#65031 = ADVANCED_FACE('',(#65032),#62171,.T.); -#65032 = FACE_BOUND('',#65033,.F.); -#65033 = EDGE_LOOP('',(#65034,#65057,#65085,#65106)); -#65034 = ORIENTED_EDGE('',*,*,#65035,.F.); -#65035 = EDGE_CURVE('',#65036,#60453,#65038,.T.); -#65036 = VERTEX_POINT('',#65037); -#65037 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); -#65038 = SURFACE_CURVE('',#65039,(#65043,#65050),.PCURVE_S1.); -#65039 = LINE('',#65040,#65041); -#65040 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); -#65041 = VECTOR('',#65042,1.); -#65042 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65043 = PCURVE('',#62171,#65044); -#65044 = DEFINITIONAL_REPRESENTATION('',(#65045),#65049); -#65045 = LINE('',#65046,#65047); -#65046 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65047 = VECTOR('',#65048,1.); -#65048 = DIRECTION('',(1.,0.E+000)); -#65049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65050 = PCURVE('',#60468,#65051); -#65051 = DEFINITIONAL_REPRESENTATION('',(#65052),#65056); -#65052 = LINE('',#65053,#65054); -#65053 = CARTESIAN_POINT('',(2.65,-1.105)); -#65054 = VECTOR('',#65055,1.); -#65055 = DIRECTION('',(-1.,0.E+000)); -#65056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65057 = ORIENTED_EDGE('',*,*,#65058,.T.); -#65058 = EDGE_CURVE('',#65036,#65059,#65061,.T.); -#65059 = VERTEX_POINT('',#65060); -#65060 = CARTESIAN_POINT('',(-1.175,-1.105,-2.65)); -#65061 = SURFACE_CURVE('',#65062,(#65066,#65073),.PCURVE_S1.); -#65062 = LINE('',#65063,#65064); -#65063 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); -#65064 = VECTOR('',#65065,1.); -#65065 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65066 = PCURVE('',#62171,#65067); -#65067 = DEFINITIONAL_REPRESENTATION('',(#65068),#65072); -#65068 = LINE('',#65069,#65070); -#65069 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65070 = VECTOR('',#65071,1.); -#65071 = DIRECTION('',(0.E+000,1.)); -#65072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65073 = PCURVE('',#65074,#65079); -#65074 = PLANE('',#65075); -#65075 = AXIS2_PLACEMENT_3D('',#65076,#65077,#65078); -#65076 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); -#65077 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65078 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65079 = DEFINITIONAL_REPRESENTATION('',(#65080),#65084); -#65080 = LINE('',#65081,#65082); -#65081 = CARTESIAN_POINT('',(0.15,0.E+000)); -#65082 = VECTOR('',#65083,1.); -#65083 = DIRECTION('',(0.E+000,1.)); -#65084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65085 = ORIENTED_EDGE('',*,*,#65086,.T.); -#65086 = EDGE_CURVE('',#65059,#60609,#65087,.T.); -#65087 = SURFACE_CURVE('',#65088,(#65092,#65099),.PCURVE_S1.); -#65088 = LINE('',#65089,#65090); -#65089 = CARTESIAN_POINT('',(-1.175,-1.105,-2.65)); -#65090 = VECTOR('',#65091,1.); -#65091 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65092 = PCURVE('',#62171,#65093); -#65093 = DEFINITIONAL_REPRESENTATION('',(#65094),#65098); -#65094 = LINE('',#65095,#65096); -#65095 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65096 = VECTOR('',#65097,1.); -#65097 = DIRECTION('',(1.,0.E+000)); -#65098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65099 = PCURVE('',#60647,#65100); -#65100 = DEFINITIONAL_REPRESENTATION('',(#65101),#65105); -#65101 = LINE('',#65102,#65103); -#65102 = CARTESIAN_POINT('',(2.65,-1.105)); -#65103 = VECTOR('',#65104,1.); -#65104 = DIRECTION('',(-1.,0.E+000)); -#65105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65106 = ORIENTED_EDGE('',*,*,#62157,.F.); -#65107 = ADVANCED_FACE('',(#65108),#60468,.F.); -#65108 = FACE_BOUND('',#65109,.F.); -#65109 = EDGE_LOOP('',(#65110,#65111,#65112,#65135,#65163,#65191)); -#65110 = ORIENTED_EDGE('',*,*,#65035,.T.); -#65111 = ORIENTED_EDGE('',*,*,#60452,.F.); -#65112 = ORIENTED_EDGE('',*,*,#65113,.T.); -#65113 = EDGE_CURVE('',#60425,#65114,#65116,.T.); -#65114 = VERTEX_POINT('',#65115); -#65115 = CARTESIAN_POINT('',(-1.425,-1.18088190451,-1.902486398125)); -#65116 = SURFACE_CURVE('',#65117,(#65121,#65128),.PCURVE_S1.); -#65117 = LINE('',#65118,#65119); -#65118 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); -#65119 = VECTOR('',#65120,1.); -#65120 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#65121 = PCURVE('',#60468,#65122); -#65122 = DEFINITIONAL_REPRESENTATION('',(#65123),#65127); -#65123 = LINE('',#65124,#65125); -#65124 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65125 = VECTOR('',#65126,1.); -#65126 = DIRECTION('',(0.258819045102,-0.965925826289)); -#65127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65128 = PCURVE('',#60175,#65129); -#65129 = DEFINITIONAL_REPRESENTATION('',(#65130),#65134); -#65130 = LINE('',#65131,#65132); -#65131 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#65132 = VECTOR('',#65133,1.); -#65133 = DIRECTION('',(1.,0.E+000)); -#65134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65135 = ORIENTED_EDGE('',*,*,#65136,.T.); -#65136 = EDGE_CURVE('',#65114,#65137,#65139,.T.); -#65137 = VERTEX_POINT('',#65138); -#65138 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); -#65139 = SURFACE_CURVE('',#65140,(#65145,#65152),.PCURVE_S1.); -#65140 = CIRCLE('',#65141,0.1); -#65141 = AXIS2_PLACEMENT_3D('',#65142,#65143,#65144); -#65142 = CARTESIAN_POINT('',(-1.425,-1.155,-1.999078980754)); -#65143 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65144 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#65145 = PCURVE('',#60468,#65146); -#65146 = DEFINITIONAL_REPRESENTATION('',(#65147),#65151); -#65147 = CIRCLE('',#65148,0.1); -#65148 = AXIS2_PLACEMENT_2D('',#65149,#65150); -#65149 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#65150 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#65151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65152 = PCURVE('',#65153,#65158); -#65153 = CYLINDRICAL_SURFACE('',#65154,0.1); -#65154 = AXIS2_PLACEMENT_3D('',#65155,#65156,#65157); -#65155 = CARTESIAN_POINT('',(-1.425,-1.155,-1.999078980754)); -#65156 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65157 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65158 = DEFINITIONAL_REPRESENTATION('',(#65159),#65162); -#65159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65160,#65161),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#65160 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); -#65161 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#64991 = ORIENTED_EDGE('',*,*,#64992,.F.); +#64992 = EDGE_CURVE('',#64993,#64970,#64995,.T.); +#64993 = VERTEX_POINT('',#64994); +#64994 = CARTESIAN_POINT('',(2.125,-1.225,-1.75)); +#64995 = SURFACE_CURVE('',#64996,(#65001,#65008),.PCURVE_S1.); +#64996 = CIRCLE('',#64997,0.2); +#64997 = AXIS2_PLACEMENT_3D('',#64998,#64999,#65000); +#64998 = CARTESIAN_POINT('',(2.125,-1.225,-1.95)); +#64999 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65000 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65001 = PCURVE('',#64825,#65002); +#65002 = DEFINITIONAL_REPRESENTATION('',(#65003),#65007); +#65003 = CIRCLE('',#65004,0.2); +#65004 = AXIS2_PLACEMENT_2D('',#65005,#65006); +#65005 = CARTESIAN_POINT('',(2.125,-1.95)); +#65006 = DIRECTION('',(0.E+000,1.)); +#65007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65008 = PCURVE('',#65009,#65014); +#65009 = CYLINDRICAL_SURFACE('',#65010,0.2); +#65010 = AXIS2_PLACEMENT_3D('',#65011,#65012,#65013); +#65011 = CARTESIAN_POINT('',(2.125,-1.225,-1.95)); +#65012 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65013 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65014 = DEFINITIONAL_REPRESENTATION('',(#65015),#65018); +#65015 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65016,#65017),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#65016 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65017 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#65018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65019 = ORIENTED_EDGE('',*,*,#65020,.F.); +#65020 = EDGE_CURVE('',#65021,#64993,#65023,.T.); +#65021 = VERTEX_POINT('',#65022); +#65022 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); +#65023 = SURFACE_CURVE('',#65024,(#65028,#65035),.PCURVE_S1.); +#65024 = LINE('',#65025,#65026); +#65025 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); +#65026 = VECTOR('',#65027,1.); +#65027 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65028 = PCURVE('',#64825,#65029); +#65029 = DEFINITIONAL_REPRESENTATION('',(#65030),#65034); +#65030 = LINE('',#65031,#65032); +#65031 = CARTESIAN_POINT('',(2.8,-1.75)); +#65032 = VECTOR('',#65033,1.); +#65033 = DIRECTION('',(-1.,0.E+000)); +#65034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65035 = PCURVE('',#65036,#65041); +#65036 = PLANE('',#65037); +#65037 = AXIS2_PLACEMENT_3D('',#65038,#65039,#65040); +#65038 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); +#65039 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65040 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65041 = DEFINITIONAL_REPRESENTATION('',(#65042),#65046); +#65042 = LINE('',#65043,#65044); +#65043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65044 = VECTOR('',#65045,1.); +#65045 = DIRECTION('',(1.,0.E+000)); +#65046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65047 = ORIENTED_EDGE('',*,*,#65048,.F.); +#65048 = EDGE_CURVE('',#64810,#65021,#65049,.T.); +#65049 = SURFACE_CURVE('',#65050,(#65055,#65062),.PCURVE_S1.); +#65050 = CIRCLE('',#65051,0.2); +#65051 = AXIS2_PLACEMENT_3D('',#65052,#65053,#65054); +#65052 = CARTESIAN_POINT('',(2.8,-1.225,-1.95)); +#65053 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65054 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65055 = PCURVE('',#64825,#65056); +#65056 = DEFINITIONAL_REPRESENTATION('',(#65057),#65061); +#65057 = CIRCLE('',#65058,0.2); +#65058 = AXIS2_PLACEMENT_2D('',#65059,#65060); +#65059 = CARTESIAN_POINT('',(2.8,-1.95)); +#65060 = DIRECTION('',(1.,0.E+000)); +#65061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65062 = PCURVE('',#64853,#65063); +#65063 = DEFINITIONAL_REPRESENTATION('',(#65064),#65067); +#65064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65065,#65066),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#65065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65066 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65068 = ADVANCED_FACE('',(#65069),#65083,.T.); +#65069 = FACE_BOUND('',#65070,.F.); +#65070 = EDGE_LOOP('',(#65071,#65101,#65123,#65146,#65174,#65202)); +#65071 = ORIENTED_EDGE('',*,*,#65072,.F.); +#65072 = EDGE_CURVE('',#65073,#65075,#65077,.T.); +#65073 = VERTEX_POINT('',#65074); +#65074 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); +#65075 = VERTEX_POINT('',#65076); +#65076 = CARTESIAN_POINT('',(-1.925,-1.225,-1.95)); +#65077 = SURFACE_CURVE('',#65078,(#65082,#65094),.PCURVE_S1.); +#65078 = LINE('',#65079,#65080); +#65079 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); +#65080 = VECTOR('',#65081,1.); +#65081 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65082 = PCURVE('',#65083,#65088); +#65083 = PLANE('',#65084); +#65084 = AXIS2_PLACEMENT_3D('',#65085,#65086,#65087); +#65085 = CARTESIAN_POINT('',(0.E+000,-1.225,0.E+000)); +#65086 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65087 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65088 = DEFINITIONAL_REPRESENTATION('',(#65089),#65093); +#65089 = LINE('',#65090,#65091); +#65090 = CARTESIAN_POINT('',(-1.925,-2.35)); +#65091 = VECTOR('',#65092,1.); +#65092 = DIRECTION('',(0.E+000,1.)); +#65093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65094 = PCURVE('',#54326,#65095); +#65095 = DEFINITIONAL_REPRESENTATION('',(#65096),#65100); +#65096 = LINE('',#65097,#65098); +#65097 = CARTESIAN_POINT('',(0.5,0.E+000)); +#65098 = VECTOR('',#65099,1.); +#65099 = DIRECTION('',(0.E+000,-1.)); +#65100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65101 = ORIENTED_EDGE('',*,*,#65102,.T.); +#65102 = EDGE_CURVE('',#65073,#65103,#65105,.T.); +#65103 = VERTEX_POINT('',#65104); +#65104 = CARTESIAN_POINT('',(-3.,-1.225,-2.35)); +#65105 = SURFACE_CURVE('',#65106,(#65110,#65117),.PCURVE_S1.); +#65106 = LINE('',#65107,#65108); +#65107 = CARTESIAN_POINT('',(-1.925,-1.225,-2.35)); +#65108 = VECTOR('',#65109,1.); +#65109 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65110 = PCURVE('',#65083,#65111); +#65111 = DEFINITIONAL_REPRESENTATION('',(#65112),#65116); +#65112 = LINE('',#65113,#65114); +#65113 = CARTESIAN_POINT('',(-1.925,-2.35)); +#65114 = VECTOR('',#65115,1.); +#65115 = DIRECTION('',(-1.,0.E+000)); +#65116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65117 = PCURVE('',#54299,#65118); +#65118 = DEFINITIONAL_REPRESENTATION('',(#65119),#65122); +#65119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65120,#65121),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.075),.PIECEWISE_BEZIER_KNOTS.); +#65120 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#65121 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); +#65122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65123 = ORIENTED_EDGE('',*,*,#65124,.F.); +#65124 = EDGE_CURVE('',#65125,#65103,#65127,.T.); +#65125 = VERTEX_POINT('',#65126); +#65126 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); +#65127 = SURFACE_CURVE('',#65128,(#65132,#65139),.PCURVE_S1.); +#65128 = LINE('',#65129,#65130); +#65129 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); +#65130 = VECTOR('',#65131,1.); +#65131 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#65132 = PCURVE('',#65083,#65133); +#65133 = DEFINITIONAL_REPRESENTATION('',(#65134),#65138); +#65134 = LINE('',#65135,#65136); +#65135 = CARTESIAN_POINT('',(-3.,-1.95)); +#65136 = VECTOR('',#65137,1.); +#65137 = DIRECTION('',(0.E+000,-1.)); +#65138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65139 = PCURVE('',#54271,#65140); +#65140 = DEFINITIONAL_REPRESENTATION('',(#65141),#65145); +#65141 = LINE('',#65142,#65143); +#65142 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#65143 = VECTOR('',#65144,1.); +#65144 = DIRECTION('',(0.E+000,1.)); +#65145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65146 = ORIENTED_EDGE('',*,*,#65147,.F.); +#65147 = EDGE_CURVE('',#65148,#65125,#65150,.T.); +#65148 = VERTEX_POINT('',#65149); +#65149 = CARTESIAN_POINT('',(-2.8,-1.225,-1.75)); +#65150 = SURFACE_CURVE('',#65151,(#65156,#65163),.PCURVE_S1.); +#65151 = CIRCLE('',#65152,0.2); +#65152 = AXIS2_PLACEMENT_3D('',#65153,#65154,#65155); +#65153 = CARTESIAN_POINT('',(-2.8,-1.225,-1.95)); +#65154 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65155 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65156 = PCURVE('',#65083,#65157); +#65157 = DEFINITIONAL_REPRESENTATION('',(#65158),#65162); +#65158 = CIRCLE('',#65159,0.2); +#65159 = AXIS2_PLACEMENT_2D('',#65160,#65161); +#65160 = CARTESIAN_POINT('',(-2.8,-1.95)); +#65161 = DIRECTION('',(0.E+000,1.)); #65162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#65163 = ORIENTED_EDGE('',*,*,#65164,.T.); -#65164 = EDGE_CURVE('',#65137,#65165,#65167,.T.); -#65165 = VERTEX_POINT('',#65166); -#65166 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); -#65167 = SURFACE_CURVE('',#65168,(#65172,#65179),.PCURVE_S1.); -#65168 = LINE('',#65169,#65170); -#65169 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); -#65170 = VECTOR('',#65171,1.); -#65171 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65172 = PCURVE('',#60468,#65173); -#65173 = DEFINITIONAL_REPRESENTATION('',(#65174),#65178); -#65174 = LINE('',#65175,#65176); -#65175 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#65176 = VECTOR('',#65177,1.); -#65177 = DIRECTION('',(1.,0.E+000)); -#65178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65179 = PCURVE('',#65180,#65185); -#65180 = PLANE('',#65181); -#65181 = AXIS2_PLACEMENT_3D('',#65182,#65183,#65184); -#65182 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); -#65183 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#65184 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65185 = DEFINITIONAL_REPRESENTATION('',(#65186),#65190); -#65186 = LINE('',#65187,#65188); -#65187 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65188 = VECTOR('',#65189,1.); -#65189 = DIRECTION('',(1.,0.E+000)); -#65190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65191 = ORIENTED_EDGE('',*,*,#65192,.T.); -#65192 = EDGE_CURVE('',#65165,#65036,#65193,.T.); -#65193 = SURFACE_CURVE('',#65194,(#65198,#65205),.PCURVE_S1.); -#65194 = LINE('',#65195,#65196); -#65195 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); -#65196 = VECTOR('',#65197,1.); -#65197 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65198 = PCURVE('',#60468,#65199); -#65199 = DEFINITIONAL_REPRESENTATION('',(#65200),#65204); -#65200 = LINE('',#65201,#65202); -#65201 = CARTESIAN_POINT('',(2.65,-1.255)); -#65202 = VECTOR('',#65203,1.); -#65203 = DIRECTION('',(0.E+000,1.)); -#65204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65205 = PCURVE('',#65074,#65206); -#65206 = DEFINITIONAL_REPRESENTATION('',(#65207),#65211); -#65207 = LINE('',#65208,#65209); -#65208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65209 = VECTOR('',#65210,1.); -#65210 = DIRECTION('',(1.,0.E+000)); -#65211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65212 = ADVANCED_FACE('',(#65213),#60175,.T.); -#65213 = FACE_BOUND('',#65214,.F.); -#65214 = EDGE_LOOP('',(#65215,#65216,#65237,#65260,#65280,#65281)); -#65215 = ORIENTED_EDGE('',*,*,#60159,.T.); -#65216 = ORIENTED_EDGE('',*,*,#65217,.F.); -#65217 = EDGE_CURVE('',#60632,#60132,#65218,.T.); -#65218 = SURFACE_CURVE('',#65219,(#65223,#65230),.PCURVE_S1.); -#65219 = LINE('',#65220,#65221); -#65220 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); -#65221 = VECTOR('',#65222,1.); -#65222 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#65223 = PCURVE('',#60175,#65224); -#65224 = DEFINITIONAL_REPRESENTATION('',(#65225),#65229); -#65225 = LINE('',#65226,#65227); -#65226 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#65227 = VECTOR('',#65228,1.); -#65228 = DIRECTION('',(-1.,0.E+000)); -#65229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65230 = PCURVE('',#60147,#65231); -#65231 = DEFINITIONAL_REPRESENTATION('',(#65232),#65236); -#65232 = LINE('',#65233,#65234); -#65233 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65234 = VECTOR('',#65235,1.); -#65235 = DIRECTION('',(-0.258819045102,0.965925826289)); -#65236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65237 = ORIENTED_EDGE('',*,*,#65238,.T.); -#65238 = EDGE_CURVE('',#60632,#65239,#65241,.T.); -#65239 = VERTEX_POINT('',#65240); -#65240 = CARTESIAN_POINT('',(-1.175,-1.18088190451,-1.902486398125)); -#65241 = SURFACE_CURVE('',#65242,(#65246,#65253),.PCURVE_S1.); +#65163 = PCURVE('',#65164,#65169); +#65164 = CYLINDRICAL_SURFACE('',#65165,0.2); +#65165 = AXIS2_PLACEMENT_3D('',#65166,#65167,#65168); +#65166 = CARTESIAN_POINT('',(-2.8,-1.225,-1.95)); +#65167 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65168 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65169 = DEFINITIONAL_REPRESENTATION('',(#65170),#65173); +#65170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65171,#65172),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#65171 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65172 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#65173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65174 = ORIENTED_EDGE('',*,*,#65175,.F.); +#65175 = EDGE_CURVE('',#65176,#65148,#65178,.T.); +#65176 = VERTEX_POINT('',#65177); +#65177 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); +#65178 = SURFACE_CURVE('',#65179,(#65183,#65190),.PCURVE_S1.); +#65179 = LINE('',#65180,#65181); +#65180 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); +#65181 = VECTOR('',#65182,1.); +#65182 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65183 = PCURVE('',#65083,#65184); +#65184 = DEFINITIONAL_REPRESENTATION('',(#65185),#65189); +#65185 = LINE('',#65186,#65187); +#65186 = CARTESIAN_POINT('',(-2.125,-1.75)); +#65187 = VECTOR('',#65188,1.); +#65188 = DIRECTION('',(-1.,0.E+000)); +#65189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65190 = PCURVE('',#65191,#65196); +#65191 = PLANE('',#65192); +#65192 = AXIS2_PLACEMENT_3D('',#65193,#65194,#65195); +#65193 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); +#65194 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65195 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65196 = DEFINITIONAL_REPRESENTATION('',(#65197),#65201); +#65197 = LINE('',#65198,#65199); +#65198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65199 = VECTOR('',#65200,1.); +#65200 = DIRECTION('',(1.,0.E+000)); +#65201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65202 = ORIENTED_EDGE('',*,*,#65203,.F.); +#65203 = EDGE_CURVE('',#65075,#65176,#65204,.T.); +#65204 = SURFACE_CURVE('',#65205,(#65210,#65217),.PCURVE_S1.); +#65205 = CIRCLE('',#65206,0.2); +#65206 = AXIS2_PLACEMENT_3D('',#65207,#65208,#65209); +#65207 = CARTESIAN_POINT('',(-2.125,-1.225,-1.95)); +#65208 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65209 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65210 = PCURVE('',#65083,#65211); +#65211 = DEFINITIONAL_REPRESENTATION('',(#65212),#65216); +#65212 = CIRCLE('',#65213,0.2); +#65213 = AXIS2_PLACEMENT_2D('',#65214,#65215); +#65214 = CARTESIAN_POINT('',(-2.125,-1.95)); +#65215 = DIRECTION('',(1.,0.E+000)); +#65216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65217 = PCURVE('',#65218,#65223); +#65218 = CYLINDRICAL_SURFACE('',#65219,0.2); +#65219 = AXIS2_PLACEMENT_3D('',#65220,#65221,#65222); +#65220 = CARTESIAN_POINT('',(-2.125,-1.225,-1.95)); +#65221 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65222 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65223 = DEFINITIONAL_REPRESENTATION('',(#65224),#65227); +#65224 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65225,#65226),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#65225 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65226 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65228 = ADVANCED_FACE('',(#65229),#54382,.T.); +#65229 = FACE_BOUND('',#65230,.F.); +#65230 = EDGE_LOOP('',(#65231,#65254,#65277,#65297,#65298,#65299,#65300, + #65321)); +#65231 = ORIENTED_EDGE('',*,*,#65232,.F.); +#65232 = EDGE_CURVE('',#65233,#45367,#65235,.T.); +#65233 = VERTEX_POINT('',#65234); +#65234 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); +#65235 = SURFACE_CURVE('',#65236,(#65240,#65247),.PCURVE_S1.); +#65236 = LINE('',#65237,#65238); +#65237 = CARTESIAN_POINT('',(1.925,-0.925,-2.35)); +#65238 = VECTOR('',#65239,1.); +#65239 = DIRECTION('',(4.440892098502E-014,1.,0.E+000)); +#65240 = PCURVE('',#54382,#65241); +#65241 = DEFINITIONAL_REPRESENTATION('',(#65242),#65246); #65242 = LINE('',#65243,#65244); -#65243 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); +#65243 = CARTESIAN_POINT('',(0.3,0.E+000)); #65244 = VECTOR('',#65245,1.); -#65245 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#65246 = PCURVE('',#60175,#65247); -#65247 = DEFINITIONAL_REPRESENTATION('',(#65248),#65252); -#65248 = LINE('',#65249,#65250); -#65249 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#65250 = VECTOR('',#65251,1.); -#65251 = DIRECTION('',(1.,0.E+000)); -#65252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65253 = PCURVE('',#60647,#65254); -#65254 = DEFINITIONAL_REPRESENTATION('',(#65255),#65259); -#65255 = LINE('',#65256,#65257); -#65256 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65257 = VECTOR('',#65258,1.); -#65258 = DIRECTION('',(0.258819045102,-0.965925826289)); -#65259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65260 = ORIENTED_EDGE('',*,*,#65261,.F.); -#65261 = EDGE_CURVE('',#65114,#65239,#65262,.T.); -#65262 = SURFACE_CURVE('',#65263,(#65267,#65274),.PCURVE_S1.); -#65263 = LINE('',#65264,#65265); -#65264 = CARTESIAN_POINT('',(-1.425,-1.18088190451,-1.902486398125)); -#65265 = VECTOR('',#65266,1.); -#65266 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65267 = PCURVE('',#60175,#65268); -#65268 = DEFINITIONAL_REPRESENTATION('',(#65269),#65273); -#65269 = LINE('',#65270,#65271); -#65270 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); -#65271 = VECTOR('',#65272,1.); -#65272 = DIRECTION('',(0.E+000,1.)); -#65273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65274 = PCURVE('',#65153,#65275); -#65275 = DEFINITIONAL_REPRESENTATION('',(#65276),#65279); -#65276 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65277,#65278),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#65277 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); -#65278 = CARTESIAN_POINT('',(3.403392041386,0.25)); -#65279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65280 = ORIENTED_EDGE('',*,*,#65113,.F.); -#65281 = ORIENTED_EDGE('',*,*,#61267,.T.); -#65282 = ADVANCED_FACE('',(#65283),#60147,.F.); -#65283 = FACE_BOUND('',#65284,.F.); -#65284 = EDGE_LOOP('',(#65285,#65286,#65287,#65288)); -#65285 = ORIENTED_EDGE('',*,*,#60659,.T.); -#65286 = ORIENTED_EDGE('',*,*,#65217,.T.); -#65287 = ORIENTED_EDGE('',*,*,#60131,.T.); -#65288 = ORIENTED_EDGE('',*,*,#61340,.T.); -#65289 = ADVANCED_FACE('',(#65290),#60647,.T.); -#65290 = FACE_BOUND('',#65291,.F.); -#65291 = EDGE_LOOP('',(#65292,#65293,#65316,#65339,#65360,#65361)); -#65292 = ORIENTED_EDGE('',*,*,#65086,.F.); -#65293 = ORIENTED_EDGE('',*,*,#65294,.F.); -#65294 = EDGE_CURVE('',#65295,#65059,#65297,.T.); -#65295 = VERTEX_POINT('',#65296); -#65296 = CARTESIAN_POINT('',(-1.175,-1.255,-2.65)); -#65297 = SURFACE_CURVE('',#65298,(#65302,#65309),.PCURVE_S1.); -#65298 = LINE('',#65299,#65300); -#65299 = CARTESIAN_POINT('',(-1.175,-1.255,-2.65)); -#65300 = VECTOR('',#65301,1.); -#65301 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65302 = PCURVE('',#60647,#65303); -#65303 = DEFINITIONAL_REPRESENTATION('',(#65304),#65308); -#65304 = LINE('',#65305,#65306); -#65305 = CARTESIAN_POINT('',(2.65,-1.255)); -#65306 = VECTOR('',#65307,1.); -#65307 = DIRECTION('',(0.E+000,1.)); -#65308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65309 = PCURVE('',#65074,#65310); -#65310 = DEFINITIONAL_REPRESENTATION('',(#65311),#65315); -#65311 = LINE('',#65312,#65313); -#65312 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65313 = VECTOR('',#65314,1.); -#65314 = DIRECTION('',(1.,0.E+000)); -#65315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65316 = ORIENTED_EDGE('',*,*,#65317,.F.); -#65317 = EDGE_CURVE('',#65318,#65295,#65320,.T.); -#65318 = VERTEX_POINT('',#65319); -#65319 = CARTESIAN_POINT('',(-1.175,-1.255,-1.999078980754)); -#65320 = SURFACE_CURVE('',#65321,(#65325,#65332),.PCURVE_S1.); -#65321 = LINE('',#65322,#65323); -#65322 = CARTESIAN_POINT('',(-1.175,-1.255,-1.999078980754)); -#65323 = VECTOR('',#65324,1.); -#65324 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65325 = PCURVE('',#60647,#65326); -#65326 = DEFINITIONAL_REPRESENTATION('',(#65327),#65331); -#65327 = LINE('',#65328,#65329); -#65328 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#65329 = VECTOR('',#65330,1.); -#65330 = DIRECTION('',(1.,0.E+000)); -#65331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65332 = PCURVE('',#65180,#65333); -#65333 = DEFINITIONAL_REPRESENTATION('',(#65334),#65338); -#65334 = LINE('',#65335,#65336); -#65335 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65336 = VECTOR('',#65337,1.); -#65337 = DIRECTION('',(1.,0.E+000)); -#65338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65339 = ORIENTED_EDGE('',*,*,#65340,.F.); -#65340 = EDGE_CURVE('',#65239,#65318,#65341,.T.); -#65341 = SURFACE_CURVE('',#65342,(#65347,#65354),.PCURVE_S1.); -#65342 = CIRCLE('',#65343,0.1); -#65343 = AXIS2_PLACEMENT_3D('',#65344,#65345,#65346); -#65344 = CARTESIAN_POINT('',(-1.175,-1.155,-1.999078980754)); -#65345 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65346 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#65347 = PCURVE('',#60647,#65348); -#65348 = DEFINITIONAL_REPRESENTATION('',(#65349),#65353); -#65349 = CIRCLE('',#65350,0.1); -#65350 = AXIS2_PLACEMENT_2D('',#65351,#65352); -#65351 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#65352 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#65353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65354 = PCURVE('',#65153,#65355); -#65355 = DEFINITIONAL_REPRESENTATION('',(#65356),#65359); -#65356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65357,#65358),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#65357 = CARTESIAN_POINT('',(3.403392041389,0.25)); -#65358 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#65359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65360 = ORIENTED_EDGE('',*,*,#65238,.F.); -#65361 = ORIENTED_EDGE('',*,*,#60631,.F.); -#65362 = ADVANCED_FACE('',(#65363),#65074,.T.); -#65363 = FACE_BOUND('',#65364,.F.); -#65364 = EDGE_LOOP('',(#65365,#65366,#65387,#65388)); -#65365 = ORIENTED_EDGE('',*,*,#65192,.F.); -#65366 = ORIENTED_EDGE('',*,*,#65367,.T.); -#65367 = EDGE_CURVE('',#65165,#65295,#65368,.T.); -#65368 = SURFACE_CURVE('',#65369,(#65373,#65380),.PCURVE_S1.); -#65369 = LINE('',#65370,#65371); -#65370 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); -#65371 = VECTOR('',#65372,1.); -#65372 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65373 = PCURVE('',#65074,#65374); -#65374 = DEFINITIONAL_REPRESENTATION('',(#65375),#65379); -#65375 = LINE('',#65376,#65377); -#65376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65377 = VECTOR('',#65378,1.); -#65378 = DIRECTION('',(0.E+000,1.)); -#65379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65380 = PCURVE('',#65180,#65381); -#65381 = DEFINITIONAL_REPRESENTATION('',(#65382),#65386); +#65245 = DIRECTION('',(1.,0.E+000)); +#65246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65247 = PCURVE('',#45382,#65248); +#65248 = DEFINITIONAL_REPRESENTATION('',(#65249),#65253); +#65249 = LINE('',#65250,#65251); +#65250 = CARTESIAN_POINT('',(-1.925,-0.925)); +#65251 = VECTOR('',#65252,1.); +#65252 = DIRECTION('',(-4.440892098502E-014,1.)); +#65253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65254 = ORIENTED_EDGE('',*,*,#65255,.F.); +#65255 = EDGE_CURVE('',#65256,#65233,#65258,.T.); +#65256 = VERTEX_POINT('',#65257); +#65257 = CARTESIAN_POINT('',(1.925,-0.925,-1.95)); +#65258 = SURFACE_CURVE('',#65259,(#65263,#65270),.PCURVE_S1.); +#65259 = LINE('',#65260,#65261); +#65260 = CARTESIAN_POINT('',(1.925,-0.925,-1.95)); +#65261 = VECTOR('',#65262,1.); +#65262 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#65263 = PCURVE('',#54382,#65264); +#65264 = DEFINITIONAL_REPRESENTATION('',(#65265),#65269); +#65265 = LINE('',#65266,#65267); +#65266 = CARTESIAN_POINT('',(0.3,-0.4)); +#65267 = VECTOR('',#65268,1.); +#65268 = DIRECTION('',(0.E+000,1.)); +#65269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65270 = PCURVE('',#64880,#65271); +#65271 = DEFINITIONAL_REPRESENTATION('',(#65272),#65276); +#65272 = LINE('',#65273,#65274); +#65273 = CARTESIAN_POINT('',(1.925,-1.95)); +#65274 = VECTOR('',#65275,1.); +#65275 = DIRECTION('',(0.E+000,-1.)); +#65276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65277 = ORIENTED_EDGE('',*,*,#65278,.F.); +#65278 = EDGE_CURVE('',#64970,#65256,#65279,.T.); +#65279 = SURFACE_CURVE('',#65280,(#65284,#65291),.PCURVE_S1.); +#65280 = LINE('',#65281,#65282); +#65281 = CARTESIAN_POINT('',(1.925,-1.225,-1.95)); +#65282 = VECTOR('',#65283,1.); +#65283 = DIRECTION('',(0.E+000,1.,0.E+000)); +#65284 = PCURVE('',#54382,#65285); +#65285 = DEFINITIONAL_REPRESENTATION('',(#65286),#65290); +#65286 = LINE('',#65287,#65288); +#65287 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#65288 = VECTOR('',#65289,1.); +#65289 = DIRECTION('',(1.,0.E+000)); +#65290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65291 = PCURVE('',#65009,#65292); +#65292 = DEFINITIONAL_REPRESENTATION('',(#65293),#65296); +#65293 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65294,#65295),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#65294 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#65295 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#65296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65297 = ORIENTED_EDGE('',*,*,#64969,.T.); +#65298 = ORIENTED_EDGE('',*,*,#64941,.F.); +#65299 = ORIENTED_EDGE('',*,*,#54366,.T.); +#65300 = ORIENTED_EDGE('',*,*,#65301,.F.); +#65301 = EDGE_CURVE('',#64480,#54339,#65302,.T.); +#65302 = SURFACE_CURVE('',#65303,(#65307,#65314),.PCURVE_S1.); +#65303 = LINE('',#65304,#65305); +#65304 = CARTESIAN_POINT('',(1.925,-0.725,-2.35)); +#65305 = VECTOR('',#65306,1.); +#65306 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#65307 = PCURVE('',#54382,#65308); +#65308 = DEFINITIONAL_REPRESENTATION('',(#65309),#65313); +#65309 = LINE('',#65310,#65311); +#65310 = CARTESIAN_POINT('',(0.5,0.E+000)); +#65311 = VECTOR('',#65312,1.); +#65312 = DIRECTION('',(0.E+000,1.)); +#65313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65314 = PCURVE('',#54354,#65315); +#65315 = DEFINITIONAL_REPRESENTATION('',(#65316),#65320); +#65316 = LINE('',#65317,#65318); +#65317 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65318 = VECTOR('',#65319,1.); +#65319 = DIRECTION('',(0.E+000,1.)); +#65320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65321 = ORIENTED_EDGE('',*,*,#64479,.F.); +#65322 = ADVANCED_FACE('',(#65323),#50048,.F.); +#65323 = FACE_BOUND('',#65324,.F.); +#65324 = EDGE_LOOP('',(#65325,#65326,#65327,#65348)); +#65325 = ORIENTED_EDGE('',*,*,#50034,.F.); +#65326 = ORIENTED_EDGE('',*,*,#54100,.T.); +#65327 = ORIENTED_EDGE('',*,*,#65328,.T.); +#65328 = EDGE_CURVE('',#54078,#54555,#65329,.T.); +#65329 = SURFACE_CURVE('',#65330,(#65334,#65341),.PCURVE_S1.); +#65330 = LINE('',#65331,#65332); +#65331 = CARTESIAN_POINT('',(1.21,0.92,-2.35)); +#65332 = VECTOR('',#65333,1.); +#65333 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65334 = PCURVE('',#50048,#65335); +#65335 = DEFINITIONAL_REPRESENTATION('',(#65336),#65340); +#65336 = LINE('',#65337,#65338); +#65337 = CARTESIAN_POINT('',(-1.21,0.92)); +#65338 = VECTOR('',#65339,1.); +#65339 = DIRECTION('',(1.,0.E+000)); +#65340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65341 = PCURVE('',#45792,#65342); +#65342 = DEFINITIONAL_REPRESENTATION('',(#65343),#65347); +#65343 = LINE('',#65344,#65345); +#65344 = CARTESIAN_POINT('',(1.885,0.E+000)); +#65345 = VECTOR('',#65346,1.); +#65346 = DIRECTION('',(1.,0.E+000)); +#65347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65348 = ORIENTED_EDGE('',*,*,#54554,.T.); +#65349 = ADVANCED_FACE('',(#65350),#54009,.F.); +#65350 = FACE_BOUND('',#65351,.F.); +#65351 = EDGE_LOOP('',(#65352,#65373,#65374)); +#65352 = ORIENTED_EDGE('',*,*,#65353,.T.); +#65353 = EDGE_CURVE('',#63937,#53994,#65354,.T.); +#65354 = SURFACE_CURVE('',#65355,(#65359,#65366),.PCURVE_S1.); +#65355 = LINE('',#65356,#65357); +#65356 = CARTESIAN_POINT('',(1.339903810568,0.5,-2.35)); +#65357 = VECTOR('',#65358,1.); +#65358 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65359 = PCURVE('',#54009,#65360); +#65360 = DEFINITIONAL_REPRESENTATION('',(#65361),#65365); +#65361 = LINE('',#65362,#65363); +#65362 = CARTESIAN_POINT('',(-1.339903810568,0.5)); +#65363 = VECTOR('',#65364,1.); +#65364 = DIRECTION('',(1.,0.E+000)); +#65365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65366 = PCURVE('',#54037,#65367); +#65367 = DEFINITIONAL_REPRESENTATION('',(#65368),#65372); +#65368 = LINE('',#65369,#65370); +#65369 = CARTESIAN_POINT('',(1.030096189432,0.E+000)); +#65370 = VECTOR('',#65371,1.); +#65371 = DIRECTION('',(1.,0.E+000)); +#65372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65373 = ORIENTED_EDGE('',*,*,#53993,.T.); +#65374 = ORIENTED_EDGE('',*,*,#64710,.T.); +#65375 = ADVANCED_FACE('',(#65376),#54672,.F.); +#65376 = FACE_BOUND('',#65377,.F.); +#65377 = EDGE_LOOP('',(#65378,#65379,#65400)); +#65378 = ORIENTED_EDGE('',*,*,#54656,.T.); +#65379 = ORIENTED_EDGE('',*,*,#65380,.T.); +#65380 = EDGE_CURVE('',#54629,#64287,#65381,.T.); +#65381 = SURFACE_CURVE('',#65382,(#65386,#65393),.PCURVE_S1.); #65382 = LINE('',#65383,#65384); -#65383 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#65383 = CARTESIAN_POINT('',(-1.21,0.5,-2.35)); #65384 = VECTOR('',#65385,1.); -#65385 = DIRECTION('',(0.E+000,1.)); -#65386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65387 = ORIENTED_EDGE('',*,*,#65294,.T.); -#65388 = ORIENTED_EDGE('',*,*,#65058,.F.); -#65389 = ADVANCED_FACE('',(#65390),#65180,.T.); -#65390 = FACE_BOUND('',#65391,.F.); -#65391 = EDGE_LOOP('',(#65392,#65393,#65413,#65414)); -#65392 = ORIENTED_EDGE('',*,*,#65164,.F.); -#65393 = ORIENTED_EDGE('',*,*,#65394,.T.); -#65394 = EDGE_CURVE('',#65137,#65318,#65395,.T.); -#65395 = SURFACE_CURVE('',#65396,(#65400,#65407),.PCURVE_S1.); -#65396 = LINE('',#65397,#65398); -#65397 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); -#65398 = VECTOR('',#65399,1.); -#65399 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65400 = PCURVE('',#65180,#65401); -#65401 = DEFINITIONAL_REPRESENTATION('',(#65402),#65406); -#65402 = LINE('',#65403,#65404); -#65403 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65404 = VECTOR('',#65405,1.); -#65405 = DIRECTION('',(0.E+000,1.)); -#65406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65407 = PCURVE('',#65153,#65408); -#65408 = DEFINITIONAL_REPRESENTATION('',(#65409),#65412); -#65409 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65410,#65411),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#65410 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#65411 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#65412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65413 = ORIENTED_EDGE('',*,*,#65317,.T.); -#65414 = ORIENTED_EDGE('',*,*,#65367,.F.); -#65415 = ADVANCED_FACE('',(#65416),#65153,.T.); -#65416 = FACE_BOUND('',#65417,.T.); -#65417 = EDGE_LOOP('',(#65418,#65419,#65420,#65421)); -#65418 = ORIENTED_EDGE('',*,*,#65136,.T.); -#65419 = ORIENTED_EDGE('',*,*,#65394,.T.); -#65420 = ORIENTED_EDGE('',*,*,#65340,.F.); -#65421 = ORIENTED_EDGE('',*,*,#65261,.F.); -#65422 = ADVANCED_FACE('',(#65423),#62198,.T.); -#65423 = FACE_BOUND('',#65424,.F.); -#65424 = EDGE_LOOP('',(#65425,#65448,#65476,#65497)); -#65425 = ORIENTED_EDGE('',*,*,#65426,.F.); -#65426 = EDGE_CURVE('',#65427,#60581,#65429,.T.); -#65427 = VERTEX_POINT('',#65428); -#65428 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); -#65429 = SURFACE_CURVE('',#65430,(#65434,#65441),.PCURVE_S1.); -#65430 = LINE('',#65431,#65432); -#65431 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); -#65432 = VECTOR('',#65433,1.); -#65433 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65434 = PCURVE('',#62198,#65435); -#65435 = DEFINITIONAL_REPRESENTATION('',(#65436),#65440); -#65436 = LINE('',#65437,#65438); -#65437 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65438 = VECTOR('',#65439,1.); -#65439 = DIRECTION('',(1.,0.E+000)); -#65440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65441 = PCURVE('',#60596,#65442); -#65442 = DEFINITIONAL_REPRESENTATION('',(#65443),#65447); -#65443 = LINE('',#65444,#65445); -#65444 = CARTESIAN_POINT('',(2.65,-1.105)); -#65445 = VECTOR('',#65446,1.); -#65446 = DIRECTION('',(-1.,0.E+000)); -#65447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65448 = ORIENTED_EDGE('',*,*,#65449,.T.); -#65449 = EDGE_CURVE('',#65427,#65450,#65452,.T.); -#65450 = VERTEX_POINT('',#65451); -#65451 = CARTESIAN_POINT('',(-0.525,-1.105,-2.65)); -#65452 = SURFACE_CURVE('',#65453,(#65457,#65464),.PCURVE_S1.); -#65453 = LINE('',#65454,#65455); -#65454 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); -#65455 = VECTOR('',#65456,1.); -#65456 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65457 = PCURVE('',#62198,#65458); -#65458 = DEFINITIONAL_REPRESENTATION('',(#65459),#65463); -#65459 = LINE('',#65460,#65461); -#65460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65461 = VECTOR('',#65462,1.); -#65462 = DIRECTION('',(0.E+000,1.)); -#65463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65464 = PCURVE('',#65465,#65470); -#65465 = PLANE('',#65466); -#65466 = AXIS2_PLACEMENT_3D('',#65467,#65468,#65469); -#65467 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); -#65468 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65469 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65470 = DEFINITIONAL_REPRESENTATION('',(#65471),#65475); -#65471 = LINE('',#65472,#65473); -#65472 = CARTESIAN_POINT('',(0.15,0.E+000)); -#65473 = VECTOR('',#65474,1.); -#65474 = DIRECTION('',(0.E+000,1.)); -#65475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65476 = ORIENTED_EDGE('',*,*,#65477,.T.); -#65477 = EDGE_CURVE('',#65450,#60765,#65478,.T.); -#65478 = SURFACE_CURVE('',#65479,(#65483,#65490),.PCURVE_S1.); -#65479 = LINE('',#65480,#65481); -#65480 = CARTESIAN_POINT('',(-0.525,-1.105,-2.65)); -#65481 = VECTOR('',#65482,1.); -#65482 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65483 = PCURVE('',#62198,#65484); -#65484 = DEFINITIONAL_REPRESENTATION('',(#65485),#65489); -#65485 = LINE('',#65486,#65487); -#65486 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65487 = VECTOR('',#65488,1.); -#65488 = DIRECTION('',(1.,0.E+000)); -#65489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65490 = PCURVE('',#60803,#65491); -#65491 = DEFINITIONAL_REPRESENTATION('',(#65492),#65496); -#65492 = LINE('',#65493,#65494); -#65493 = CARTESIAN_POINT('',(2.65,-1.105)); -#65494 = VECTOR('',#65495,1.); -#65495 = DIRECTION('',(-1.,0.E+000)); -#65496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65497 = ORIENTED_EDGE('',*,*,#62184,.F.); -#65498 = ADVANCED_FACE('',(#65499),#60596,.F.); -#65499 = FACE_BOUND('',#65500,.F.); -#65500 = EDGE_LOOP('',(#65501,#65502,#65503,#65526,#65554,#65582)); -#65501 = ORIENTED_EDGE('',*,*,#65426,.T.); -#65502 = ORIENTED_EDGE('',*,*,#60580,.F.); -#65503 = ORIENTED_EDGE('',*,*,#65504,.T.); -#65504 = EDGE_CURVE('',#60553,#65505,#65507,.T.); -#65505 = VERTEX_POINT('',#65506); -#65506 = CARTESIAN_POINT('',(-0.775,-1.18088190451,-1.902486398125)); -#65507 = SURFACE_CURVE('',#65508,(#65512,#65519),.PCURVE_S1.); -#65508 = LINE('',#65509,#65510); -#65509 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); -#65510 = VECTOR('',#65511,1.); -#65511 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#65512 = PCURVE('',#60596,#65513); -#65513 = DEFINITIONAL_REPRESENTATION('',(#65514),#65518); -#65514 = LINE('',#65515,#65516); -#65515 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65516 = VECTOR('',#65517,1.); -#65517 = DIRECTION('',(0.258819045102,-0.965925826289)); -#65518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65519 = PCURVE('',#60063,#65520); -#65520 = DEFINITIONAL_REPRESENTATION('',(#65521),#65525); -#65521 = LINE('',#65522,#65523); -#65522 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#65523 = VECTOR('',#65524,1.); -#65524 = DIRECTION('',(1.,0.E+000)); -#65525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65526 = ORIENTED_EDGE('',*,*,#65527,.T.); -#65527 = EDGE_CURVE('',#65505,#65528,#65530,.T.); -#65528 = VERTEX_POINT('',#65529); -#65529 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); -#65530 = SURFACE_CURVE('',#65531,(#65536,#65543),.PCURVE_S1.); -#65531 = CIRCLE('',#65532,0.1); -#65532 = AXIS2_PLACEMENT_3D('',#65533,#65534,#65535); -#65533 = CARTESIAN_POINT('',(-0.775,-1.155,-1.999078980754)); -#65534 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65535 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#65536 = PCURVE('',#60596,#65537); +#65385 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65386 = PCURVE('',#54672,#65387); +#65387 = DEFINITIONAL_REPRESENTATION('',(#65388),#65392); +#65388 = LINE('',#65389,#65390); +#65389 = CARTESIAN_POINT('',(1.21,0.5)); +#65390 = VECTOR('',#65391,1.); +#65391 = DIRECTION('',(1.,0.E+000)); +#65392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65393 = PCURVE('',#54644,#65394); +#65394 = DEFINITIONAL_REPRESENTATION('',(#65395),#65399); +#65395 = LINE('',#65396,#65397); +#65396 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65397 = VECTOR('',#65398,1.); +#65398 = DIRECTION('',(1.,0.E+000)); +#65399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65400 = ORIENTED_EDGE('',*,*,#65401,.T.); +#65401 = EDGE_CURVE('',#64287,#54657,#65402,.T.); +#65402 = SURFACE_CURVE('',#65403,(#65407,#65414),.PCURVE_S1.); +#65403 = LINE('',#65404,#65405); +#65404 = CARTESIAN_POINT('',(-1.339903810568,0.5,-2.35)); +#65405 = VECTOR('',#65406,1.); +#65406 = DIRECTION('',(0.866025403784,0.5,0.E+000)); +#65407 = PCURVE('',#54672,#65408); +#65408 = DEFINITIONAL_REPRESENTATION('',(#65409),#65413); +#65409 = LINE('',#65410,#65411); +#65410 = CARTESIAN_POINT('',(1.339903810568,0.5)); +#65411 = VECTOR('',#65412,1.); +#65412 = DIRECTION('',(-0.866025403784,0.5)); +#65413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65414 = PCURVE('',#54187,#65415); +#65415 = DEFINITIONAL_REPRESENTATION('',(#65416),#65420); +#65416 = LINE('',#65417,#65418); +#65417 = CARTESIAN_POINT('',(0.65,0.E+000)); +#65418 = VECTOR('',#65419,1.); +#65419 = DIRECTION('',(1.,0.E+000)); +#65420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65421 = ADVANCED_FACE('',(#65422),#45382,.F.); +#65422 = FACE_BOUND('',#65423,.F.); +#65423 = EDGE_LOOP('',(#65424,#65445,#65446,#65447,#65474,#65495)); +#65424 = ORIENTED_EDGE('',*,*,#65425,.T.); +#65425 = EDGE_CURVE('',#64865,#65233,#65426,.T.); +#65426 = SURFACE_CURVE('',#65427,(#65431,#65438),.PCURVE_S1.); +#65427 = LINE('',#65428,#65429); +#65428 = CARTESIAN_POINT('',(3.,-0.925,-2.35)); +#65429 = VECTOR('',#65430,1.); +#65430 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65431 = PCURVE('',#45382,#65432); +#65432 = DEFINITIONAL_REPRESENTATION('',(#65433),#65437); +#65433 = LINE('',#65434,#65435); +#65434 = CARTESIAN_POINT('',(-3.,-0.925)); +#65435 = VECTOR('',#65436,1.); +#65436 = DIRECTION('',(1.,0.E+000)); +#65437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65438 = PCURVE('',#64880,#65439); +#65439 = DEFINITIONAL_REPRESENTATION('',(#65440),#65444); +#65440 = LINE('',#65441,#65442); +#65441 = CARTESIAN_POINT('',(3.,-2.35)); +#65442 = VECTOR('',#65443,1.); +#65443 = DIRECTION('',(-1.,0.E+000)); +#65444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65445 = ORIENTED_EDGE('',*,*,#65232,.T.); +#65446 = ORIENTED_EDGE('',*,*,#45366,.T.); +#65447 = ORIENTED_EDGE('',*,*,#65448,.T.); +#65448 = EDGE_CURVE('',#45340,#65449,#65451,.T.); +#65449 = VERTEX_POINT('',#65450); +#65450 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); +#65451 = SURFACE_CURVE('',#65452,(#65457,#65468),.PCURVE_S1.); +#65452 = CIRCLE('',#65453,0.25); +#65453 = AXIS2_PLACEMENT_3D('',#65454,#65455,#65456); +#65454 = CARTESIAN_POINT('',(2.594375541595,-0.67,-2.35)); +#65455 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65456 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65457 = PCURVE('',#45382,#65458); +#65458 = DEFINITIONAL_REPRESENTATION('',(#65459),#65467); +#65459 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#65460,#65461,#65462,#65463 + ,#65464,#65465,#65466),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#65460 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); +#65461 = CARTESIAN_POINT('',(-3.027388243487,-0.92)); +#65462 = CARTESIAN_POINT('',(-2.810881892541,-0.545)); +#65463 = CARTESIAN_POINT('',(-2.594375541595,-0.17)); +#65464 = CARTESIAN_POINT('',(-2.377869190649,-0.545)); +#65465 = CARTESIAN_POINT('',(-2.161362839703,-0.92)); +#65466 = CARTESIAN_POINT('',(-2.594375541595,-0.92)); +#65467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65468 = PCURVE('',#45355,#65469); +#65469 = DEFINITIONAL_REPRESENTATION('',(#65470),#65473); +#65470 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65471,#65472),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); +#65471 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#65472 = CARTESIAN_POINT('',(5.49778714378,0.E+000)); +#65473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65474 = ORIENTED_EDGE('',*,*,#65475,.T.); +#65475 = EDGE_CURVE('',#65449,#64017,#65476,.T.); +#65476 = SURFACE_CURVE('',#65477,(#65481,#65488),.PCURVE_S1.); +#65477 = LINE('',#65478,#65479); +#65478 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); +#65479 = VECTOR('',#65480,1.); +#65480 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#65481 = PCURVE('',#45382,#65482); +#65482 = DEFINITIONAL_REPRESENTATION('',(#65483),#65487); +#65483 = LINE('',#65484,#65485); +#65484 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297)); +#65485 = VECTOR('',#65486,1.); +#65486 = DIRECTION('',(-0.707106781187,0.707106781187)); +#65487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65488 = PCURVE('',#45904,#65489); +#65489 = DEFINITIONAL_REPRESENTATION('',(#65490),#65494); +#65490 = LINE('',#65491,#65492); +#65491 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65492 = VECTOR('',#65493,1.); +#65493 = DIRECTION('',(1.,0.E+000)); +#65494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65495 = ORIENTED_EDGE('',*,*,#64892,.T.); +#65496 = ADVANCED_FACE('',(#65497),#45487,.F.); +#65497 = FACE_BOUND('',#65498,.F.); +#65498 = EDGE_LOOP('',(#65499,#65529,#65550,#65573,#65598,#65599)); +#65499 = ORIENTED_EDGE('',*,*,#65500,.T.); +#65500 = EDGE_CURVE('',#65501,#65503,#65505,.T.); +#65501 = VERTEX_POINT('',#65502); +#65502 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); +#65503 = VERTEX_POINT('',#65504); +#65504 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); +#65505 = SURFACE_CURVE('',#65506,(#65510,#65517),.PCURVE_S1.); +#65506 = LINE('',#65507,#65508); +#65507 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); +#65508 = VECTOR('',#65509,1.); +#65509 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65510 = PCURVE('',#45487,#65511); +#65511 = DEFINITIONAL_REPRESENTATION('',(#65512),#65516); +#65512 = LINE('',#65513,#65514); +#65513 = CARTESIAN_POINT('',(1.925,-0.925)); +#65514 = VECTOR('',#65515,1.); +#65515 = DIRECTION('',(1.,0.E+000)); +#65516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65517 = PCURVE('',#65518,#65523); +#65518 = PLANE('',#65519); +#65519 = AXIS2_PLACEMENT_3D('',#65520,#65521,#65522); +#65520 = CARTESIAN_POINT('',(0.E+000,-0.925,0.E+000)); +#65521 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#65522 = DIRECTION('',(1.,0.E+000,0.E+000)); +#65523 = DEFINITIONAL_REPRESENTATION('',(#65524),#65528); +#65524 = LINE('',#65525,#65526); +#65525 = CARTESIAN_POINT('',(-1.925,-2.35)); +#65526 = VECTOR('',#65527,1.); +#65527 = DIRECTION('',(-1.,0.E+000)); +#65528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65529 = ORIENTED_EDGE('',*,*,#65530,.T.); +#65530 = EDGE_CURVE('',#65503,#64207,#65531,.T.); +#65531 = SURFACE_CURVE('',#65532,(#65536,#65543),.PCURVE_S1.); +#65532 = LINE('',#65533,#65534); +#65533 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); +#65534 = VECTOR('',#65535,1.); +#65535 = DIRECTION('',(0.E+000,1.,0.E+000)); +#65536 = PCURVE('',#45487,#65537); #65537 = DEFINITIONAL_REPRESENTATION('',(#65538),#65542); -#65538 = CIRCLE('',#65539,0.1); -#65539 = AXIS2_PLACEMENT_2D('',#65540,#65541); -#65540 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#65541 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#65538 = LINE('',#65539,#65540); +#65539 = CARTESIAN_POINT('',(3.,-0.925)); +#65540 = VECTOR('',#65541,1.); +#65541 = DIRECTION('',(0.E+000,1.)); #65542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#65543 = PCURVE('',#65544,#65549); -#65544 = CYLINDRICAL_SURFACE('',#65545,0.1); -#65545 = AXIS2_PLACEMENT_3D('',#65546,#65547,#65548); -#65546 = CARTESIAN_POINT('',(-0.775,-1.155,-1.999078980754)); -#65547 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65548 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65549 = DEFINITIONAL_REPRESENTATION('',(#65550),#65553); -#65550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65551,#65552),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#65551 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); -#65552 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#65553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65554 = ORIENTED_EDGE('',*,*,#65555,.T.); -#65555 = EDGE_CURVE('',#65528,#65556,#65558,.T.); -#65556 = VERTEX_POINT('',#65557); -#65557 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); -#65558 = SURFACE_CURVE('',#65559,(#65563,#65570),.PCURVE_S1.); -#65559 = LINE('',#65560,#65561); -#65560 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); -#65561 = VECTOR('',#65562,1.); -#65562 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65563 = PCURVE('',#60596,#65564); -#65564 = DEFINITIONAL_REPRESENTATION('',(#65565),#65569); -#65565 = LINE('',#65566,#65567); -#65566 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#65567 = VECTOR('',#65568,1.); -#65568 = DIRECTION('',(1.,0.E+000)); -#65569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65570 = PCURVE('',#65571,#65576); -#65571 = PLANE('',#65572); -#65572 = AXIS2_PLACEMENT_3D('',#65573,#65574,#65575); -#65573 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); -#65574 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#65575 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65576 = DEFINITIONAL_REPRESENTATION('',(#65577),#65581); -#65577 = LINE('',#65578,#65579); -#65578 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65579 = VECTOR('',#65580,1.); -#65580 = DIRECTION('',(1.,0.E+000)); -#65581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65582 = ORIENTED_EDGE('',*,*,#65583,.T.); -#65583 = EDGE_CURVE('',#65556,#65427,#65584,.T.); -#65584 = SURFACE_CURVE('',#65585,(#65589,#65596),.PCURVE_S1.); -#65585 = LINE('',#65586,#65587); -#65586 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); -#65587 = VECTOR('',#65588,1.); -#65588 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65589 = PCURVE('',#60596,#65590); -#65590 = DEFINITIONAL_REPRESENTATION('',(#65591),#65595); -#65591 = LINE('',#65592,#65593); -#65592 = CARTESIAN_POINT('',(2.65,-1.255)); -#65593 = VECTOR('',#65594,1.); -#65594 = DIRECTION('',(0.E+000,1.)); -#65595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65596 = PCURVE('',#65465,#65597); -#65597 = DEFINITIONAL_REPRESENTATION('',(#65598),#65602); -#65598 = LINE('',#65599,#65600); -#65599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65600 = VECTOR('',#65601,1.); -#65601 = DIRECTION('',(1.,0.E+000)); -#65602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65603 = ADVANCED_FACE('',(#65604),#60063,.T.); -#65604 = FACE_BOUND('',#65605,.F.); -#65605 = EDGE_LOOP('',(#65606,#65607,#65628,#65651,#65671,#65672)); -#65606 = ORIENTED_EDGE('',*,*,#60047,.T.); -#65607 = ORIENTED_EDGE('',*,*,#65608,.F.); -#65608 = EDGE_CURVE('',#60788,#60020,#65609,.T.); -#65609 = SURFACE_CURVE('',#65610,(#65614,#65621),.PCURVE_S1.); -#65610 = LINE('',#65611,#65612); -#65611 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); -#65612 = VECTOR('',#65613,1.); -#65613 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#65614 = PCURVE('',#60063,#65615); -#65615 = DEFINITIONAL_REPRESENTATION('',(#65616),#65620); -#65616 = LINE('',#65617,#65618); -#65617 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#65618 = VECTOR('',#65619,1.); -#65619 = DIRECTION('',(-1.,0.E+000)); -#65620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65621 = PCURVE('',#60035,#65622); -#65622 = DEFINITIONAL_REPRESENTATION('',(#65623),#65627); -#65623 = LINE('',#65624,#65625); -#65624 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65625 = VECTOR('',#65626,1.); -#65626 = DIRECTION('',(-0.258819045102,0.965925826289)); -#65627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65628 = ORIENTED_EDGE('',*,*,#65629,.T.); -#65629 = EDGE_CURVE('',#60788,#65630,#65632,.T.); -#65630 = VERTEX_POINT('',#65631); -#65631 = CARTESIAN_POINT('',(-0.525,-1.18088190451,-1.902486398125)); -#65632 = SURFACE_CURVE('',#65633,(#65637,#65644),.PCURVE_S1.); -#65633 = LINE('',#65634,#65635); -#65634 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); -#65635 = VECTOR('',#65636,1.); -#65636 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#65637 = PCURVE('',#60063,#65638); -#65638 = DEFINITIONAL_REPRESENTATION('',(#65639),#65643); -#65639 = LINE('',#65640,#65641); -#65640 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#65641 = VECTOR('',#65642,1.); -#65642 = DIRECTION('',(1.,0.E+000)); -#65643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65644 = PCURVE('',#60803,#65645); -#65645 = DEFINITIONAL_REPRESENTATION('',(#65646),#65650); -#65646 = LINE('',#65647,#65648); -#65647 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65648 = VECTOR('',#65649,1.); -#65649 = DIRECTION('',(0.258819045102,-0.965925826289)); -#65650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65651 = ORIENTED_EDGE('',*,*,#65652,.F.); -#65652 = EDGE_CURVE('',#65505,#65630,#65653,.T.); -#65653 = SURFACE_CURVE('',#65654,(#65658,#65665),.PCURVE_S1.); -#65654 = LINE('',#65655,#65656); -#65655 = CARTESIAN_POINT('',(-0.775,-1.18088190451,-1.902486398125)); -#65656 = VECTOR('',#65657,1.); -#65657 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65658 = PCURVE('',#60063,#65659); -#65659 = DEFINITIONAL_REPRESENTATION('',(#65660),#65664); -#65660 = LINE('',#65661,#65662); -#65661 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); -#65662 = VECTOR('',#65663,1.); -#65663 = DIRECTION('',(0.E+000,1.)); -#65664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65665 = PCURVE('',#65544,#65666); -#65666 = DEFINITIONAL_REPRESENTATION('',(#65667),#65670); -#65667 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65668,#65669),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#65668 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); -#65669 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#65543 = PCURVE('',#54271,#65544); +#65544 = DEFINITIONAL_REPRESENTATION('',(#65545),#65549); +#65545 = LINE('',#65546,#65547); +#65546 = CARTESIAN_POINT('',(0.3,0.E+000)); +#65547 = VECTOR('',#65548,1.); +#65548 = DIRECTION('',(1.,0.E+000)); +#65549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65550 = ORIENTED_EDGE('',*,*,#65551,.F.); +#65551 = EDGE_CURVE('',#65552,#64207,#65554,.T.); +#65552 = VERTEX_POINT('',#65553); +#65553 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); +#65554 = SURFACE_CURVE('',#65555,(#65559,#65566),.PCURVE_S1.); +#65555 = LINE('',#65556,#65557); +#65556 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); +#65557 = VECTOR('',#65558,1.); +#65558 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#65559 = PCURVE('',#45487,#65560); +#65560 = DEFINITIONAL_REPRESENTATION('',(#65561),#65565); +#65561 = LINE('',#65562,#65563); +#65562 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297)); +#65563 = VECTOR('',#65564,1.); +#65564 = DIRECTION('',(0.707106781187,0.707106781187)); +#65565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65566 = PCURVE('',#46072,#65567); +#65567 = DEFINITIONAL_REPRESENTATION('',(#65568),#65572); +#65568 = LINE('',#65569,#65570); +#65569 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); +#65570 = VECTOR('',#65571,1.); +#65571 = DIRECTION('',(-1.,0.E+000)); +#65572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65573 = ORIENTED_EDGE('',*,*,#65574,.T.); +#65574 = EDGE_CURVE('',#65552,#45472,#65575,.T.); +#65575 = SURFACE_CURVE('',#65576,(#65581,#65592),.PCURVE_S1.); +#65576 = CIRCLE('',#65577,0.25); +#65577 = AXIS2_PLACEMENT_3D('',#65578,#65579,#65580); +#65578 = CARTESIAN_POINT('',(-2.594375541595,-0.67,-2.35)); +#65579 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65580 = DIRECTION('',(-0.707106781187,-0.707106781186,0.E+000)); +#65581 = PCURVE('',#45487,#65582); +#65582 = DEFINITIONAL_REPRESENTATION('',(#65583),#65591); +#65583 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#65584,#65585,#65586,#65587 + ,#65588,#65589,#65590),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#65584 = CARTESIAN_POINT('',(2.771152236892,-0.846776695297)); +#65585 = CARTESIAN_POINT('',(2.464966019044,-1.152962913145)); +#65586 = CARTESIAN_POINT('',(2.352894085023,-0.734704761276)); +#65587 = CARTESIAN_POINT('',(2.240822151002,-0.316446609407)); +#65588 = CARTESIAN_POINT('',(2.659080302871,-0.428518543428)); +#65589 = CARTESIAN_POINT('',(3.07733845474,-0.540590477449)); +#65590 = CARTESIAN_POINT('',(2.771152236892,-0.846776695297)); +#65591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65592 = PCURVE('',#45515,#65593); +#65593 = DEFINITIONAL_REPRESENTATION('',(#65594),#65597); +#65594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65595,#65596),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.785398163398),.PIECEWISE_BEZIER_KNOTS.); +#65595 = CARTESIAN_POINT('',(3.926990816987,0.E+000)); +#65596 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#65597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65598 = ORIENTED_EDGE('',*,*,#45471,.T.); +#65599 = ORIENTED_EDGE('',*,*,#65600,.T.); +#65600 = EDGE_CURVE('',#45449,#65501,#65601,.T.); +#65601 = SURFACE_CURVE('',#65602,(#65606,#65613),.PCURVE_S1.); +#65602 = LINE('',#65603,#65604); +#65603 = CARTESIAN_POINT('',(-1.925,-0.92,-2.35)); +#65604 = VECTOR('',#65605,1.); +#65605 = DIRECTION('',(4.440892098502E-014,-1.,0.E+000)); +#65606 = PCURVE('',#45487,#65607); +#65607 = DEFINITIONAL_REPRESENTATION('',(#65608),#65612); +#65608 = LINE('',#65609,#65610); +#65609 = CARTESIAN_POINT('',(1.925,-0.92)); +#65610 = VECTOR('',#65611,1.); +#65611 = DIRECTION('',(-4.440892098502E-014,-1.)); +#65612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65613 = PCURVE('',#54326,#65614); +#65614 = DEFINITIONAL_REPRESENTATION('',(#65615),#65619); +#65615 = LINE('',#65616,#65617); +#65616 = CARTESIAN_POINT('',(0.195,0.E+000)); +#65617 = VECTOR('',#65618,1.); +#65618 = DIRECTION('',(1.,0.E+000)); +#65619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65620 = ADVANCED_FACE('',(#65621),#45792,.T.); +#65621 = FACE_BOUND('',#65622,.F.); +#65622 = EDGE_LOOP('',(#65623,#65624,#65625,#65626,#65627,#65647,#65648, + #65671,#65692,#65693,#65694,#65695,#65718,#65739,#65740,#65760, + #65761,#65784)); +#65623 = ORIENTED_EDGE('',*,*,#49538,.T.); +#65624 = ORIENTED_EDGE('',*,*,#49490,.T.); +#65625 = ORIENTED_EDGE('',*,*,#49381,.F.); +#65626 = ORIENTED_EDGE('',*,*,#46168,.T.); +#65627 = ORIENTED_EDGE('',*,*,#65628,.F.); +#65628 = EDGE_CURVE('',#64361,#46141,#65629,.T.); +#65629 = SURFACE_CURVE('',#65630,(#65634,#65641),.PCURVE_S1.); +#65630 = LINE('',#65631,#65632); +#65631 = CARTESIAN_POINT('',(-3.095,0.92,-2.35)); +#65632 = VECTOR('',#65633,1.); +#65633 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65634 = PCURVE('',#45792,#65635); +#65635 = DEFINITIONAL_REPRESENTATION('',(#65636),#65640); +#65636 = LINE('',#65637,#65638); +#65637 = CARTESIAN_POINT('',(6.19,0.E+000)); +#65638 = VECTOR('',#65639,1.); +#65639 = DIRECTION('',(0.E+000,1.)); +#65640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65641 = PCURVE('',#46157,#65642); +#65642 = DEFINITIONAL_REPRESENTATION('',(#65643),#65646); +#65643 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65644,#65645),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65644 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65645 = CARTESIAN_POINT('',(1.570796326795,1.2)); +#65646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65647 = ORIENTED_EDGE('',*,*,#64360,.F.); +#65648 = ORIENTED_EDGE('',*,*,#65649,.T.); +#65649 = EDGE_CURVE('',#64333,#65650,#65652,.T.); +#65650 = VERTEX_POINT('',#65651); +#65651 = CARTESIAN_POINT('',(-2.37,0.92,-1.63)); +#65652 = SURFACE_CURVE('',#65653,(#65657,#65664),.PCURVE_S1.); +#65653 = LINE('',#65654,#65655); +#65654 = CARTESIAN_POINT('',(-2.37,0.92,-2.35)); +#65655 = VECTOR('',#65656,1.); +#65656 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65657 = PCURVE('',#45792,#65658); +#65658 = DEFINITIONAL_REPRESENTATION('',(#65659),#65663); +#65659 = LINE('',#65660,#65661); +#65660 = CARTESIAN_POINT('',(5.465,0.E+000)); +#65661 = VECTOR('',#65662,1.); +#65662 = DIRECTION('',(0.E+000,1.)); +#65663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65664 = PCURVE('',#64348,#65665); +#65665 = DEFINITIONAL_REPRESENTATION('',(#65666),#65670); +#65666 = LINE('',#65667,#65668); +#65667 = CARTESIAN_POINT('',(0.42,0.E+000)); +#65668 = VECTOR('',#65669,1.); +#65669 = DIRECTION('',(0.E+000,-1.)); #65670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#65671 = ORIENTED_EDGE('',*,*,#65504,.F.); -#65672 = ORIENTED_EDGE('',*,*,#65673,.T.); -#65673 = EDGE_CURVE('',#60553,#60048,#65674,.T.); -#65674 = SURFACE_CURVE('',#65675,(#65679,#65686),.PCURVE_S1.); -#65675 = LINE('',#65676,#65677); -#65676 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); -#65677 = VECTOR('',#65678,1.); -#65678 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#65679 = PCURVE('',#60063,#65680); -#65680 = DEFINITIONAL_REPRESENTATION('',(#65681),#65685); -#65681 = LINE('',#65682,#65683); -#65682 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#65683 = VECTOR('',#65684,1.); -#65684 = DIRECTION('',(-1.,0.E+000)); -#65685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65686 = PCURVE('',#60091,#65687); -#65687 = DEFINITIONAL_REPRESENTATION('',(#65688),#65692); -#65688 = LINE('',#65689,#65690); -#65689 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#65690 = VECTOR('',#65691,1.); -#65691 = DIRECTION('',(-0.258819045102,0.965925826289)); -#65692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65693 = ADVANCED_FACE('',(#65694),#60035,.F.); -#65694 = FACE_BOUND('',#65695,.F.); -#65695 = EDGE_LOOP('',(#65696,#65697,#65698,#65699)); -#65696 = ORIENTED_EDGE('',*,*,#60815,.T.); -#65697 = ORIENTED_EDGE('',*,*,#65608,.T.); -#65698 = ORIENTED_EDGE('',*,*,#60019,.T.); -#65699 = ORIENTED_EDGE('',*,*,#61387,.T.); -#65700 = ADVANCED_FACE('',(#65701),#60803,.T.); -#65701 = FACE_BOUND('',#65702,.F.); -#65702 = EDGE_LOOP('',(#65703,#65704,#65727,#65750,#65771,#65772)); -#65703 = ORIENTED_EDGE('',*,*,#65477,.F.); -#65704 = ORIENTED_EDGE('',*,*,#65705,.F.); -#65705 = EDGE_CURVE('',#65706,#65450,#65708,.T.); -#65706 = VERTEX_POINT('',#65707); -#65707 = CARTESIAN_POINT('',(-0.525,-1.255,-2.65)); -#65708 = SURFACE_CURVE('',#65709,(#65713,#65720),.PCURVE_S1.); -#65709 = LINE('',#65710,#65711); -#65710 = CARTESIAN_POINT('',(-0.525,-1.255,-2.65)); -#65711 = VECTOR('',#65712,1.); -#65712 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65713 = PCURVE('',#60803,#65714); -#65714 = DEFINITIONAL_REPRESENTATION('',(#65715),#65719); -#65715 = LINE('',#65716,#65717); -#65716 = CARTESIAN_POINT('',(2.65,-1.255)); -#65717 = VECTOR('',#65718,1.); -#65718 = DIRECTION('',(0.E+000,1.)); -#65719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65720 = PCURVE('',#65465,#65721); -#65721 = DEFINITIONAL_REPRESENTATION('',(#65722),#65726); -#65722 = LINE('',#65723,#65724); -#65723 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65724 = VECTOR('',#65725,1.); -#65725 = DIRECTION('',(1.,0.E+000)); -#65726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65727 = ORIENTED_EDGE('',*,*,#65728,.F.); -#65728 = EDGE_CURVE('',#65729,#65706,#65731,.T.); -#65729 = VERTEX_POINT('',#65730); -#65730 = CARTESIAN_POINT('',(-0.525,-1.255,-1.999078980754)); -#65731 = SURFACE_CURVE('',#65732,(#65736,#65743),.PCURVE_S1.); -#65732 = LINE('',#65733,#65734); -#65733 = CARTESIAN_POINT('',(-0.525,-1.255,-1.999078980754)); -#65734 = VECTOR('',#65735,1.); -#65735 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65736 = PCURVE('',#60803,#65737); -#65737 = DEFINITIONAL_REPRESENTATION('',(#65738),#65742); -#65738 = LINE('',#65739,#65740); -#65739 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#65740 = VECTOR('',#65741,1.); -#65741 = DIRECTION('',(1.,0.E+000)); -#65742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65743 = PCURVE('',#65571,#65744); -#65744 = DEFINITIONAL_REPRESENTATION('',(#65745),#65749); -#65745 = LINE('',#65746,#65747); -#65746 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65747 = VECTOR('',#65748,1.); -#65748 = DIRECTION('',(1.,0.E+000)); -#65749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65750 = ORIENTED_EDGE('',*,*,#65751,.F.); -#65751 = EDGE_CURVE('',#65630,#65729,#65752,.T.); -#65752 = SURFACE_CURVE('',#65753,(#65758,#65765),.PCURVE_S1.); -#65753 = CIRCLE('',#65754,0.1); -#65754 = AXIS2_PLACEMENT_3D('',#65755,#65756,#65757); -#65755 = CARTESIAN_POINT('',(-0.525,-1.155,-1.999078980754)); -#65756 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65757 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#65758 = PCURVE('',#60803,#65759); -#65759 = DEFINITIONAL_REPRESENTATION('',(#65760),#65764); -#65760 = CIRCLE('',#65761,0.1); -#65761 = AXIS2_PLACEMENT_2D('',#65762,#65763); -#65762 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#65763 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#65764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65765 = PCURVE('',#65544,#65766); -#65766 = DEFINITIONAL_REPRESENTATION('',(#65767),#65770); -#65767 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65768,#65769),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#65768 = CARTESIAN_POINT('',(3.403392041389,0.25)); -#65769 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#65770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65771 = ORIENTED_EDGE('',*,*,#65629,.F.); -#65772 = ORIENTED_EDGE('',*,*,#60787,.F.); -#65773 = ADVANCED_FACE('',(#65774),#65465,.T.); -#65774 = FACE_BOUND('',#65775,.F.); -#65775 = EDGE_LOOP('',(#65776,#65777,#65798,#65799)); -#65776 = ORIENTED_EDGE('',*,*,#65583,.F.); -#65777 = ORIENTED_EDGE('',*,*,#65778,.T.); -#65778 = EDGE_CURVE('',#65556,#65706,#65779,.T.); -#65779 = SURFACE_CURVE('',#65780,(#65784,#65791),.PCURVE_S1.); -#65780 = LINE('',#65781,#65782); -#65781 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); -#65782 = VECTOR('',#65783,1.); -#65783 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65784 = PCURVE('',#65465,#65785); -#65785 = DEFINITIONAL_REPRESENTATION('',(#65786),#65790); -#65786 = LINE('',#65787,#65788); -#65787 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65788 = VECTOR('',#65789,1.); -#65789 = DIRECTION('',(0.E+000,1.)); -#65790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65791 = PCURVE('',#65571,#65792); +#65671 = ORIENTED_EDGE('',*,*,#65672,.F.); +#65672 = EDGE_CURVE('',#54578,#65650,#65673,.T.); +#65673 = SURFACE_CURVE('',#65674,(#65678,#65685),.PCURVE_S1.); +#65674 = LINE('',#65675,#65676); +#65675 = CARTESIAN_POINT('',(-1.21,0.92,-1.63)); +#65676 = VECTOR('',#65677,1.); +#65677 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65678 = PCURVE('',#45792,#65679); +#65679 = DEFINITIONAL_REPRESENTATION('',(#65680),#65684); +#65680 = LINE('',#65681,#65682); +#65681 = CARTESIAN_POINT('',(4.305,0.72)); +#65682 = VECTOR('',#65683,1.); +#65683 = DIRECTION('',(1.,0.E+000)); +#65684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65685 = PCURVE('',#54616,#65686); +#65686 = DEFINITIONAL_REPRESENTATION('',(#65687),#65691); +#65687 = LINE('',#65688,#65689); +#65688 = CARTESIAN_POINT('',(1.21,0.92)); +#65689 = VECTOR('',#65690,1.); +#65690 = DIRECTION('',(1.,0.E+000)); +#65691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65692 = ORIENTED_EDGE('',*,*,#54577,.F.); +#65693 = ORIENTED_EDGE('',*,*,#65328,.F.); +#65694 = ORIENTED_EDGE('',*,*,#54077,.T.); +#65695 = ORIENTED_EDGE('',*,*,#65696,.F.); +#65696 = EDGE_CURVE('',#65697,#54050,#65699,.T.); +#65697 = VERTEX_POINT('',#65698); +#65698 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); +#65699 = SURFACE_CURVE('',#65700,(#65704,#65711),.PCURVE_S1.); +#65700 = LINE('',#65701,#65702); +#65701 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); +#65702 = VECTOR('',#65703,1.); +#65703 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65704 = PCURVE('',#45792,#65705); +#65705 = DEFINITIONAL_REPRESENTATION('',(#65706),#65710); +#65706 = LINE('',#65707,#65708); +#65707 = CARTESIAN_POINT('',(0.725,0.72)); +#65708 = VECTOR('',#65709,1.); +#65709 = DIRECTION('',(1.,0.E+000)); +#65710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65711 = PCURVE('',#54065,#65712); +#65712 = DEFINITIONAL_REPRESENTATION('',(#65713),#65717); +#65713 = LINE('',#65714,#65715); +#65714 = CARTESIAN_POINT('',(-2.37,0.92)); +#65715 = VECTOR('',#65716,1.); +#65716 = DIRECTION('',(1.,0.E+000)); +#65717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65718 = ORIENTED_EDGE('',*,*,#65719,.F.); +#65719 = EDGE_CURVE('',#64132,#65697,#65720,.T.); +#65720 = SURFACE_CURVE('',#65721,(#65725,#65732),.PCURVE_S1.); +#65721 = LINE('',#65722,#65723); +#65722 = CARTESIAN_POINT('',(2.37,0.92,-2.35)); +#65723 = VECTOR('',#65724,1.); +#65724 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65725 = PCURVE('',#45792,#65726); +#65726 = DEFINITIONAL_REPRESENTATION('',(#65727),#65731); +#65727 = LINE('',#65728,#65729); +#65728 = CARTESIAN_POINT('',(0.725,0.E+000)); +#65729 = VECTOR('',#65730,1.); +#65730 = DIRECTION('',(0.E+000,1.)); +#65731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65732 = PCURVE('',#64170,#65733); +#65733 = DEFINITIONAL_REPRESENTATION('',(#65734),#65738); +#65734 = LINE('',#65735,#65736); +#65735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65736 = VECTOR('',#65737,1.); +#65737 = DIRECTION('',(0.E+000,-1.)); +#65738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65739 = ORIENTED_EDGE('',*,*,#64131,.F.); +#65740 = ORIENTED_EDGE('',*,*,#65741,.T.); +#65741 = EDGE_CURVE('',#64109,#45777,#65742,.T.); +#65742 = SURFACE_CURVE('',#65743,(#65747,#65754),.PCURVE_S1.); +#65743 = LINE('',#65744,#65745); +#65744 = CARTESIAN_POINT('',(3.095,0.92,-2.35)); +#65745 = VECTOR('',#65746,1.); +#65746 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65747 = PCURVE('',#45792,#65748); +#65748 = DEFINITIONAL_REPRESENTATION('',(#65749),#65753); +#65749 = LINE('',#65750,#65751); +#65750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65751 = VECTOR('',#65752,1.); +#65752 = DIRECTION('',(0.E+000,1.)); +#65753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65754 = PCURVE('',#45821,#65755); +#65755 = DEFINITIONAL_REPRESENTATION('',(#65756),#65759); +#65756 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65757,#65758),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65757 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#65758 = CARTESIAN_POINT('',(1.570796326795,1.2)); +#65759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65760 = ORIENTED_EDGE('',*,*,#45776,.T.); +#65761 = ORIENTED_EDGE('',*,*,#65762,.F.); +#65762 = EDGE_CURVE('',#65763,#45749,#65765,.T.); +#65763 = VERTEX_POINT('',#65764); +#65764 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); +#65765 = SURFACE_CURVE('',#65766,(#65770,#65777),.PCURVE_S1.); +#65766 = LINE('',#65767,#65768); +#65767 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); +#65768 = VECTOR('',#65769,1.); +#65769 = DIRECTION('',(0.707106781187,0.E+000,0.707106781187)); +#65770 = PCURVE('',#45792,#65771); +#65771 = DEFINITIONAL_REPRESENTATION('',(#65772),#65776); +#65772 = LINE('',#65773,#65774); +#65773 = CARTESIAN_POINT('',(2.685,1.1)); +#65774 = VECTOR('',#65775,1.); +#65775 = DIRECTION('',(-0.707106781187,0.707106781187)); +#65776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65777 = PCURVE('',#45764,#65778); +#65778 = DEFINITIONAL_REPRESENTATION('',(#65779),#65783); +#65779 = LINE('',#65780,#65781); +#65780 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); +#65781 = VECTOR('',#65782,1.); +#65782 = DIRECTION('',(0.E+000,1.)); +#65783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65784 = ORIENTED_EDGE('',*,*,#65785,.T.); +#65785 = EDGE_CURVE('',#65763,#49539,#65786,.T.); +#65786 = SURFACE_CURVE('',#65787,(#65791,#65798),.PCURVE_S1.); +#65787 = LINE('',#65788,#65789); +#65788 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); +#65789 = VECTOR('',#65790,1.); +#65790 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#65791 = PCURVE('',#45792,#65792); #65792 = DEFINITIONAL_REPRESENTATION('',(#65793),#65797); #65793 = LINE('',#65794,#65795); -#65794 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#65794 = CARTESIAN_POINT('',(2.685,1.1)); #65795 = VECTOR('',#65796,1.); -#65796 = DIRECTION('',(0.E+000,1.)); +#65796 = DIRECTION('',(0.E+000,-1.)); #65797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#65798 = ORIENTED_EDGE('',*,*,#65705,.T.); -#65799 = ORIENTED_EDGE('',*,*,#65449,.F.); -#65800 = ADVANCED_FACE('',(#65801),#65571,.T.); -#65801 = FACE_BOUND('',#65802,.F.); -#65802 = EDGE_LOOP('',(#65803,#65804,#65824,#65825)); -#65803 = ORIENTED_EDGE('',*,*,#65555,.F.); -#65804 = ORIENTED_EDGE('',*,*,#65805,.T.); -#65805 = EDGE_CURVE('',#65528,#65729,#65806,.T.); -#65806 = SURFACE_CURVE('',#65807,(#65811,#65818),.PCURVE_S1.); -#65807 = LINE('',#65808,#65809); -#65808 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); -#65809 = VECTOR('',#65810,1.); -#65810 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65811 = PCURVE('',#65571,#65812); -#65812 = DEFINITIONAL_REPRESENTATION('',(#65813),#65817); -#65813 = LINE('',#65814,#65815); -#65814 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65815 = VECTOR('',#65816,1.); -#65816 = DIRECTION('',(0.E+000,1.)); -#65817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65818 = PCURVE('',#65544,#65819); -#65819 = DEFINITIONAL_REPRESENTATION('',(#65820),#65823); -#65820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65821,#65822),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#65821 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#65822 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#65823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65824 = ORIENTED_EDGE('',*,*,#65728,.T.); -#65825 = ORIENTED_EDGE('',*,*,#65778,.F.); -#65826 = ADVANCED_FACE('',(#65827),#65544,.T.); -#65827 = FACE_BOUND('',#65828,.T.); -#65828 = EDGE_LOOP('',(#65829,#65830,#65831,#65832)); -#65829 = ORIENTED_EDGE('',*,*,#65527,.T.); -#65830 = ORIENTED_EDGE('',*,*,#65805,.T.); -#65831 = ORIENTED_EDGE('',*,*,#65751,.F.); -#65832 = ORIENTED_EDGE('',*,*,#65652,.F.); -#65833 = ADVANCED_FACE('',(#65834),#60091,.T.); -#65834 = FACE_BOUND('',#65835,.F.); -#65835 = EDGE_LOOP('',(#65836,#65837,#65838,#65839)); -#65836 = ORIENTED_EDGE('',*,*,#60550,.F.); -#65837 = ORIENTED_EDGE('',*,*,#61318,.F.); -#65838 = ORIENTED_EDGE('',*,*,#60075,.F.); -#65839 = ORIENTED_EDGE('',*,*,#65673,.F.); -#65840 = ADVANCED_FACE('',(#65841),#62225,.T.); -#65841 = FACE_BOUND('',#65842,.F.); -#65842 = EDGE_LOOP('',(#65843,#65866,#65894,#65915)); -#65843 = ORIENTED_EDGE('',*,*,#65844,.F.); -#65844 = EDGE_CURVE('',#65845,#60737,#65847,.T.); -#65845 = VERTEX_POINT('',#65846); -#65846 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); -#65847 = SURFACE_CURVE('',#65848,(#65852,#65859),.PCURVE_S1.); -#65848 = LINE('',#65849,#65850); -#65849 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); -#65850 = VECTOR('',#65851,1.); -#65851 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65852 = PCURVE('',#62225,#65853); -#65853 = DEFINITIONAL_REPRESENTATION('',(#65854),#65858); -#65854 = LINE('',#65855,#65856); -#65855 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65856 = VECTOR('',#65857,1.); -#65857 = DIRECTION('',(1.,0.E+000)); -#65858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65859 = PCURVE('',#60752,#65860); -#65860 = DEFINITIONAL_REPRESENTATION('',(#65861),#65865); -#65861 = LINE('',#65862,#65863); -#65862 = CARTESIAN_POINT('',(2.65,-1.105)); -#65863 = VECTOR('',#65864,1.); -#65864 = DIRECTION('',(-1.,0.E+000)); -#65865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65866 = ORIENTED_EDGE('',*,*,#65867,.T.); -#65867 = EDGE_CURVE('',#65845,#65868,#65870,.T.); -#65868 = VERTEX_POINT('',#65869); -#65869 = CARTESIAN_POINT('',(0.125,-1.105,-2.65)); -#65870 = SURFACE_CURVE('',#65871,(#65875,#65882),.PCURVE_S1.); -#65871 = LINE('',#65872,#65873); -#65872 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); -#65873 = VECTOR('',#65874,1.); -#65874 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65875 = PCURVE('',#62225,#65876); -#65876 = DEFINITIONAL_REPRESENTATION('',(#65877),#65881); -#65877 = LINE('',#65878,#65879); -#65878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65879 = VECTOR('',#65880,1.); -#65880 = DIRECTION('',(0.E+000,1.)); -#65881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65882 = PCURVE('',#65883,#65888); -#65883 = PLANE('',#65884); -#65884 = AXIS2_PLACEMENT_3D('',#65885,#65886,#65887); -#65885 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); -#65886 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65887 = DIRECTION('',(0.E+000,1.,0.E+000)); -#65888 = DEFINITIONAL_REPRESENTATION('',(#65889),#65893); -#65889 = LINE('',#65890,#65891); -#65890 = CARTESIAN_POINT('',(0.15,0.E+000)); -#65891 = VECTOR('',#65892,1.); -#65892 = DIRECTION('',(0.E+000,1.)); -#65893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65894 = ORIENTED_EDGE('',*,*,#65895,.T.); -#65895 = EDGE_CURVE('',#65868,#60921,#65896,.T.); -#65896 = SURFACE_CURVE('',#65897,(#65901,#65908),.PCURVE_S1.); -#65897 = LINE('',#65898,#65899); -#65898 = CARTESIAN_POINT('',(0.125,-1.105,-2.65)); -#65899 = VECTOR('',#65900,1.); -#65900 = DIRECTION('',(0.E+000,0.E+000,1.)); -#65901 = PCURVE('',#62225,#65902); -#65902 = DEFINITIONAL_REPRESENTATION('',(#65903),#65907); -#65903 = LINE('',#65904,#65905); -#65904 = CARTESIAN_POINT('',(0.E+000,0.25)); -#65905 = VECTOR('',#65906,1.); -#65906 = DIRECTION('',(1.,0.E+000)); -#65907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65908 = PCURVE('',#60959,#65909); -#65909 = DEFINITIONAL_REPRESENTATION('',(#65910),#65914); -#65910 = LINE('',#65911,#65912); -#65911 = CARTESIAN_POINT('',(2.65,-1.105)); -#65912 = VECTOR('',#65913,1.); -#65913 = DIRECTION('',(-1.,0.E+000)); -#65914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65915 = ORIENTED_EDGE('',*,*,#62211,.F.); -#65916 = ADVANCED_FACE('',(#65917),#60752,.F.); -#65917 = FACE_BOUND('',#65918,.F.); -#65918 = EDGE_LOOP('',(#65919,#65920,#65921,#65944,#65972,#66000)); -#65919 = ORIENTED_EDGE('',*,*,#65844,.T.); -#65920 = ORIENTED_EDGE('',*,*,#60736,.F.); +#65798 = PCURVE('',#49575,#65799); +#65799 = DEFINITIONAL_REPRESENTATION('',(#65800),#65804); +#65800 = LINE('',#65801,#65802); +#65801 = CARTESIAN_POINT('',(1.25,0.92)); +#65802 = VECTOR('',#65803,1.); +#65803 = DIRECTION('',(1.,0.E+000)); +#65804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65805 = ADVANCED_FACE('',(#65806),#46157,.T.); +#65806 = FACE_BOUND('',#65807,.T.); +#65807 = EDGE_LOOP('',(#65808,#65809,#65829,#65830)); +#65808 = ORIENTED_EDGE('',*,*,#64383,.T.); +#65809 = ORIENTED_EDGE('',*,*,#65810,.T.); +#65810 = EDGE_CURVE('',#64384,#46113,#65811,.T.); +#65811 = SURFACE_CURVE('',#65812,(#65816,#65822),.PCURVE_S1.); +#65812 = LINE('',#65813,#65814); +#65813 = CARTESIAN_POINT('',(-3.445,0.57,-2.35)); +#65814 = VECTOR('',#65815,1.); +#65815 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65816 = PCURVE('',#46157,#65817); +#65817 = DEFINITIONAL_REPRESENTATION('',(#65818),#65821); +#65818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65819,#65820),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65819 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#65820 = CARTESIAN_POINT('',(3.14159265359,1.2)); +#65821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65822 = PCURVE('',#46128,#65823); +#65823 = DEFINITIONAL_REPRESENTATION('',(#65824),#65828); +#65824 = LINE('',#65825,#65826); +#65825 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65826 = VECTOR('',#65827,1.); +#65827 = DIRECTION('',(0.E+000,1.)); +#65828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65829 = ORIENTED_EDGE('',*,*,#46140,.F.); +#65830 = ORIENTED_EDGE('',*,*,#65628,.F.); +#65831 = ADVANCED_FACE('',(#65832),#46128,.T.); +#65832 = FACE_BOUND('',#65833,.F.); +#65833 = EDGE_LOOP('',(#65834,#65835,#65836,#65837)); +#65834 = ORIENTED_EDGE('',*,*,#64406,.F.); +#65835 = ORIENTED_EDGE('',*,*,#65810,.T.); +#65836 = ORIENTED_EDGE('',*,*,#46112,.T.); +#65837 = ORIENTED_EDGE('',*,*,#65838,.F.); +#65838 = EDGE_CURVE('',#64407,#46085,#65839,.T.); +#65839 = SURFACE_CURVE('',#65840,(#65844,#65851),.PCURVE_S1.); +#65840 = LINE('',#65841,#65842); +#65841 = CARTESIAN_POINT('',(-3.445,-6.937554159486E-002,-2.35)); +#65842 = VECTOR('',#65843,1.); +#65843 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65844 = PCURVE('',#46128,#65845); +#65845 = DEFINITIONAL_REPRESENTATION('',(#65846),#65850); +#65846 = LINE('',#65847,#65848); +#65847 = CARTESIAN_POINT('',(0.639375541595,0.E+000)); +#65848 = VECTOR('',#65849,1.); +#65849 = DIRECTION('',(0.E+000,1.)); +#65850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65851 = PCURVE('',#46101,#65852); +#65852 = DEFINITIONAL_REPRESENTATION('',(#65853),#65856); +#65853 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65854,#65855),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65854 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#65855 = CARTESIAN_POINT('',(3.14159265359,1.2)); +#65856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65857 = ADVANCED_FACE('',(#65858),#46101,.T.); +#65858 = FACE_BOUND('',#65859,.T.); +#65859 = EDGE_LOOP('',(#65860,#65861,#65881,#65882)); +#65860 = ORIENTED_EDGE('',*,*,#64429,.T.); +#65861 = ORIENTED_EDGE('',*,*,#65862,.T.); +#65862 = EDGE_CURVE('',#64430,#46057,#65863,.T.); +#65863 = SURFACE_CURVE('',#65864,(#65868,#65874),.PCURVE_S1.); +#65864 = LINE('',#65865,#65866); +#65865 = CARTESIAN_POINT('',(-3.371776695297,-0.246152236892,-2.35)); +#65866 = VECTOR('',#65867,1.); +#65867 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65868 = PCURVE('',#46101,#65869); +#65869 = DEFINITIONAL_REPRESENTATION('',(#65870),#65873); +#65870 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65871,#65872),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65871 = CARTESIAN_POINT('',(3.926990816986,0.E+000)); +#65872 = CARTESIAN_POINT('',(3.926990816986,1.2)); +#65873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65874 = PCURVE('',#46072,#65875); +#65875 = DEFINITIONAL_REPRESENTATION('',(#65876),#65880); +#65876 = LINE('',#65877,#65878); +#65877 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#65878 = VECTOR('',#65879,1.); +#65879 = DIRECTION('',(0.E+000,1.)); +#65880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65881 = ORIENTED_EDGE('',*,*,#46084,.F.); +#65882 = ORIENTED_EDGE('',*,*,#65838,.F.); +#65883 = ADVANCED_FACE('',(#65884),#46072,.T.); +#65884 = FACE_BOUND('',#65885,.F.); +#65885 = EDGE_LOOP('',(#65886,#65887,#65888,#65889,#65890)); +#65886 = ORIENTED_EDGE('',*,*,#65551,.T.); +#65887 = ORIENTED_EDGE('',*,*,#64452,.F.); +#65888 = ORIENTED_EDGE('',*,*,#65862,.T.); +#65889 = ORIENTED_EDGE('',*,*,#46056,.T.); +#65890 = ORIENTED_EDGE('',*,*,#65891,.F.); +#65891 = EDGE_CURVE('',#65552,#46034,#65892,.T.); +#65892 = SURFACE_CURVE('',#65893,(#65897,#65904),.PCURVE_S1.); +#65893 = LINE('',#65894,#65895); +#65894 = CARTESIAN_POINT('',(-2.771152236891,-0.846776695297,-2.35)); +#65895 = VECTOR('',#65896,1.); +#65896 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65897 = PCURVE('',#46072,#65898); +#65898 = DEFINITIONAL_REPRESENTATION('',(#65899),#65903); +#65899 = LINE('',#65900,#65901); +#65900 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); +#65901 = VECTOR('',#65902,1.); +#65902 = DIRECTION('',(0.E+000,1.)); +#65903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65904 = PCURVE('',#45515,#65905); +#65905 = DEFINITIONAL_REPRESENTATION('',(#65906),#65909); +#65906 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65907,#65908),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#65907 = CARTESIAN_POINT('',(3.926990816989,0.E+000)); +#65908 = CARTESIAN_POINT('',(3.926990816989,1.2)); +#65909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65910 = ADVANCED_FACE('',(#65911),#45515,.T.); +#65911 = FACE_BOUND('',#65912,.T.); +#65912 = EDGE_LOOP('',(#65913,#65914,#65915,#65916)); +#65913 = ORIENTED_EDGE('',*,*,#65574,.T.); +#65914 = ORIENTED_EDGE('',*,*,#45499,.T.); +#65915 = ORIENTED_EDGE('',*,*,#46033,.F.); +#65916 = ORIENTED_EDGE('',*,*,#65891,.F.); +#65917 = ADVANCED_FACE('',(#65918),#64348,.F.); +#65918 = FACE_BOUND('',#65919,.F.); +#65919 = EDGE_LOOP('',(#65920,#65921,#65944,#65965)); +#65920 = ORIENTED_EDGE('',*,*,#64332,.T.); #65921 = ORIENTED_EDGE('',*,*,#65922,.T.); -#65922 = EDGE_CURVE('',#60709,#65923,#65925,.T.); +#65922 = EDGE_CURVE('',#64310,#65923,#65925,.T.); #65923 = VERTEX_POINT('',#65924); -#65924 = CARTESIAN_POINT('',(-0.125,-1.18088190451,-1.902486398125)); +#65924 = CARTESIAN_POINT('',(-2.37,0.5,-1.63)); #65925 = SURFACE_CURVE('',#65926,(#65930,#65937),.PCURVE_S1.); #65926 = LINE('',#65927,#65928); -#65927 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); +#65927 = CARTESIAN_POINT('',(-2.37,0.5,-2.35)); #65928 = VECTOR('',#65929,1.); -#65929 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#65930 = PCURVE('',#60752,#65931); +#65929 = DIRECTION('',(0.E+000,0.E+000,1.)); +#65930 = PCURVE('',#64348,#65931); #65931 = DEFINITIONAL_REPRESENTATION('',(#65932),#65936); #65932 = LINE('',#65933,#65934); -#65933 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#65933 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #65934 = VECTOR('',#65935,1.); -#65935 = DIRECTION('',(0.258819045102,-0.965925826289)); +#65935 = DIRECTION('',(0.E+000,-1.)); #65936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#65937 = PCURVE('',#59951,#65938); +#65937 = PCURVE('',#54644,#65938); #65938 = DEFINITIONAL_REPRESENTATION('',(#65939),#65943); #65939 = LINE('',#65940,#65941); -#65940 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#65940 = CARTESIAN_POINT('',(1.16,0.E+000)); #65941 = VECTOR('',#65942,1.); -#65942 = DIRECTION('',(1.,0.E+000)); +#65942 = DIRECTION('',(0.E+000,-1.)); #65943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); #65944 = ORIENTED_EDGE('',*,*,#65945,.T.); -#65945 = EDGE_CURVE('',#65923,#65946,#65948,.T.); -#65946 = VERTEX_POINT('',#65947); -#65947 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); -#65948 = SURFACE_CURVE('',#65949,(#65954,#65961),.PCURVE_S1.); -#65949 = CIRCLE('',#65950,0.1); -#65950 = AXIS2_PLACEMENT_3D('',#65951,#65952,#65953); -#65951 = CARTESIAN_POINT('',(-0.125,-1.155,-1.999078980754)); -#65952 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65953 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#65954 = PCURVE('',#60752,#65955); -#65955 = DEFINITIONAL_REPRESENTATION('',(#65956),#65960); -#65956 = CIRCLE('',#65957,0.1); -#65957 = AXIS2_PLACEMENT_2D('',#65958,#65959); -#65958 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#65959 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#65960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65961 = PCURVE('',#65962,#65967); -#65962 = CYLINDRICAL_SURFACE('',#65963,0.1); -#65963 = AXIS2_PLACEMENT_3D('',#65964,#65965,#65966); -#65964 = CARTESIAN_POINT('',(-0.125,-1.155,-1.999078980754)); -#65965 = DIRECTION('',(1.,0.E+000,0.E+000)); -#65966 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65967 = DEFINITIONAL_REPRESENTATION('',(#65968),#65971); -#65968 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#65969,#65970),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#65969 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); -#65970 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#65971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65972 = ORIENTED_EDGE('',*,*,#65973,.T.); -#65973 = EDGE_CURVE('',#65946,#65974,#65976,.T.); -#65974 = VERTEX_POINT('',#65975); -#65975 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); -#65976 = SURFACE_CURVE('',#65977,(#65981,#65988),.PCURVE_S1.); -#65977 = LINE('',#65978,#65979); -#65978 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); -#65979 = VECTOR('',#65980,1.); -#65980 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65981 = PCURVE('',#60752,#65982); -#65982 = DEFINITIONAL_REPRESENTATION('',(#65983),#65987); -#65983 = LINE('',#65984,#65985); -#65984 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#65985 = VECTOR('',#65986,1.); -#65986 = DIRECTION('',(1.,0.E+000)); -#65987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#65988 = PCURVE('',#65989,#65994); -#65989 = PLANE('',#65990); -#65990 = AXIS2_PLACEMENT_3D('',#65991,#65992,#65993); -#65991 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); -#65992 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#65993 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#65994 = DEFINITIONAL_REPRESENTATION('',(#65995),#65999); -#65995 = LINE('',#65996,#65997); -#65996 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#65997 = VECTOR('',#65998,1.); -#65998 = DIRECTION('',(1.,0.E+000)); -#65999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66000 = ORIENTED_EDGE('',*,*,#66001,.T.); -#66001 = EDGE_CURVE('',#65974,#65845,#66002,.T.); -#66002 = SURFACE_CURVE('',#66003,(#66007,#66014),.PCURVE_S1.); -#66003 = LINE('',#66004,#66005); -#66004 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); -#66005 = VECTOR('',#66006,1.); -#66006 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66007 = PCURVE('',#60752,#66008); -#66008 = DEFINITIONAL_REPRESENTATION('',(#66009),#66013); -#66009 = LINE('',#66010,#66011); -#66010 = CARTESIAN_POINT('',(2.65,-1.255)); -#66011 = VECTOR('',#66012,1.); -#66012 = DIRECTION('',(0.E+000,1.)); -#66013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66014 = PCURVE('',#65883,#66015); -#66015 = DEFINITIONAL_REPRESENTATION('',(#66016),#66020); -#66016 = LINE('',#66017,#66018); -#66017 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66018 = VECTOR('',#66019,1.); -#66019 = DIRECTION('',(1.,0.E+000)); -#66020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66021 = ADVANCED_FACE('',(#66022),#59951,.T.); -#66022 = FACE_BOUND('',#66023,.F.); -#66023 = EDGE_LOOP('',(#66024,#66025,#66046,#66069,#66089,#66090)); -#66024 = ORIENTED_EDGE('',*,*,#59935,.T.); -#66025 = ORIENTED_EDGE('',*,*,#66026,.F.); -#66026 = EDGE_CURVE('',#60944,#59908,#66027,.T.); -#66027 = SURFACE_CURVE('',#66028,(#66032,#66039),.PCURVE_S1.); -#66028 = LINE('',#66029,#66030); -#66029 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); -#66030 = VECTOR('',#66031,1.); -#66031 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#66032 = PCURVE('',#59951,#66033); -#66033 = DEFINITIONAL_REPRESENTATION('',(#66034),#66038); -#66034 = LINE('',#66035,#66036); -#66035 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66036 = VECTOR('',#66037,1.); -#66037 = DIRECTION('',(-1.,0.E+000)); -#66038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66039 = PCURVE('',#59923,#66040); -#66040 = DEFINITIONAL_REPRESENTATION('',(#66041),#66045); -#66041 = LINE('',#66042,#66043); -#66042 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66043 = VECTOR('',#66044,1.); -#66044 = DIRECTION('',(-0.258819045102,0.965925826289)); -#66045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66046 = ORIENTED_EDGE('',*,*,#66047,.T.); -#66047 = EDGE_CURVE('',#60944,#66048,#66050,.T.); -#66048 = VERTEX_POINT('',#66049); -#66049 = CARTESIAN_POINT('',(0.125,-1.18088190451,-1.902486398125)); -#66050 = SURFACE_CURVE('',#66051,(#66055,#66062),.PCURVE_S1.); -#66051 = LINE('',#66052,#66053); -#66052 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); -#66053 = VECTOR('',#66054,1.); -#66054 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#66055 = PCURVE('',#59951,#66056); -#66056 = DEFINITIONAL_REPRESENTATION('',(#66057),#66061); -#66057 = LINE('',#66058,#66059); -#66058 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66059 = VECTOR('',#66060,1.); -#66060 = DIRECTION('',(1.,0.E+000)); -#66061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66062 = PCURVE('',#60959,#66063); +#65945 = EDGE_CURVE('',#65923,#65650,#65946,.T.); +#65946 = SURFACE_CURVE('',#65947,(#65951,#65958),.PCURVE_S1.); +#65947 = LINE('',#65948,#65949); +#65948 = CARTESIAN_POINT('',(-2.37,0.5,-1.63)); +#65949 = VECTOR('',#65950,1.); +#65950 = DIRECTION('',(0.E+000,1.,0.E+000)); +#65951 = PCURVE('',#64348,#65952); +#65952 = DEFINITIONAL_REPRESENTATION('',(#65953),#65957); +#65953 = LINE('',#65954,#65955); +#65954 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#65955 = VECTOR('',#65956,1.); +#65956 = DIRECTION('',(1.,0.E+000)); +#65957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65958 = PCURVE('',#54616,#65959); +#65959 = DEFINITIONAL_REPRESENTATION('',(#65960),#65964); +#65960 = LINE('',#65961,#65962); +#65961 = CARTESIAN_POINT('',(2.37,0.5)); +#65962 = VECTOR('',#65963,1.); +#65963 = DIRECTION('',(0.E+000,1.)); +#65964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65965 = ORIENTED_EDGE('',*,*,#65649,.F.); +#65966 = ADVANCED_FACE('',(#65967),#54644,.F.); +#65967 = FACE_BOUND('',#65968,.F.); +#65968 = EDGE_LOOP('',(#65969,#65970,#65971,#65992,#65993)); +#65969 = ORIENTED_EDGE('',*,*,#65380,.F.); +#65970 = ORIENTED_EDGE('',*,*,#54628,.T.); +#65971 = ORIENTED_EDGE('',*,*,#65972,.T.); +#65972 = EDGE_CURVE('',#54601,#65923,#65973,.T.); +#65973 = SURFACE_CURVE('',#65974,(#65978,#65985),.PCURVE_S1.); +#65974 = LINE('',#65975,#65976); +#65975 = CARTESIAN_POINT('',(-1.21,0.5,-1.63)); +#65976 = VECTOR('',#65977,1.); +#65977 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#65978 = PCURVE('',#54644,#65979); +#65979 = DEFINITIONAL_REPRESENTATION('',(#65980),#65984); +#65980 = LINE('',#65981,#65982); +#65981 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#65982 = VECTOR('',#65983,1.); +#65983 = DIRECTION('',(1.,0.E+000)); +#65984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65985 = PCURVE('',#54616,#65986); +#65986 = DEFINITIONAL_REPRESENTATION('',(#65987),#65991); +#65987 = LINE('',#65988,#65989); +#65988 = CARTESIAN_POINT('',(1.21,0.5)); +#65989 = VECTOR('',#65990,1.); +#65990 = DIRECTION('',(1.,0.E+000)); +#65991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#65992 = ORIENTED_EDGE('',*,*,#65922,.F.); +#65993 = ORIENTED_EDGE('',*,*,#64309,.F.); +#65994 = ADVANCED_FACE('',(#65995),#54065,.T.); +#65995 = FACE_BOUND('',#65996,.F.); +#65996 = EDGE_LOOP('',(#65997,#65998,#65999,#66022)); +#65997 = ORIENTED_EDGE('',*,*,#65696,.T.); +#65998 = ORIENTED_EDGE('',*,*,#54049,.F.); +#65999 = ORIENTED_EDGE('',*,*,#66000,.F.); +#66000 = EDGE_CURVE('',#66001,#54022,#66003,.T.); +#66001 = VERTEX_POINT('',#66002); +#66002 = CARTESIAN_POINT('',(2.37,0.5,-1.63)); +#66003 = SURFACE_CURVE('',#66004,(#66008,#66015),.PCURVE_S1.); +#66004 = LINE('',#66005,#66006); +#66005 = CARTESIAN_POINT('',(2.37,0.5,-1.63)); +#66006 = VECTOR('',#66007,1.); +#66007 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#66008 = PCURVE('',#54065,#66009); +#66009 = DEFINITIONAL_REPRESENTATION('',(#66010),#66014); +#66010 = LINE('',#66011,#66012); +#66011 = CARTESIAN_POINT('',(-2.37,0.5)); +#66012 = VECTOR('',#66013,1.); +#66013 = DIRECTION('',(1.,0.E+000)); +#66014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66015 = PCURVE('',#54037,#66016); +#66016 = DEFINITIONAL_REPRESENTATION('',(#66017),#66021); +#66017 = LINE('',#66018,#66019); +#66018 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#66019 = VECTOR('',#66020,1.); +#66020 = DIRECTION('',(1.,0.E+000)); +#66021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66022 = ORIENTED_EDGE('',*,*,#66023,.F.); +#66023 = EDGE_CURVE('',#65697,#66001,#66024,.T.); +#66024 = SURFACE_CURVE('',#66025,(#66029,#66036),.PCURVE_S1.); +#66025 = LINE('',#66026,#66027); +#66026 = CARTESIAN_POINT('',(2.37,0.92,-1.63)); +#66027 = VECTOR('',#66028,1.); +#66028 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66029 = PCURVE('',#54065,#66030); +#66030 = DEFINITIONAL_REPRESENTATION('',(#66031),#66035); +#66031 = LINE('',#66032,#66033); +#66032 = CARTESIAN_POINT('',(-2.37,0.92)); +#66033 = VECTOR('',#66034,1.); +#66034 = DIRECTION('',(0.E+000,-1.)); +#66035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66036 = PCURVE('',#64170,#66037); +#66037 = DEFINITIONAL_REPRESENTATION('',(#66038),#66042); +#66038 = LINE('',#66039,#66040); +#66039 = CARTESIAN_POINT('',(0.E+000,-0.72)); +#66040 = VECTOR('',#66041,1.); +#66041 = DIRECTION('',(1.,0.E+000)); +#66042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66043 = ADVANCED_FACE('',(#66044),#54616,.T.); +#66044 = FACE_BOUND('',#66045,.F.); +#66045 = EDGE_LOOP('',(#66046,#66047,#66048,#66049)); +#66046 = ORIENTED_EDGE('',*,*,#65672,.T.); +#66047 = ORIENTED_EDGE('',*,*,#65945,.F.); +#66048 = ORIENTED_EDGE('',*,*,#65972,.F.); +#66049 = ORIENTED_EDGE('',*,*,#54600,.F.); +#66050 = ADVANCED_FACE('',(#66051),#54037,.F.); +#66051 = FACE_BOUND('',#66052,.F.); +#66052 = EDGE_LOOP('',(#66053,#66054,#66055,#66076,#66077)); +#66053 = ORIENTED_EDGE('',*,*,#65353,.F.); +#66054 = ORIENTED_EDGE('',*,*,#64182,.F.); +#66055 = ORIENTED_EDGE('',*,*,#66056,.T.); +#66056 = EDGE_CURVE('',#64155,#66001,#66057,.T.); +#66057 = SURFACE_CURVE('',#66058,(#66062,#66069),.PCURVE_S1.); +#66058 = LINE('',#66059,#66060); +#66059 = CARTESIAN_POINT('',(2.37,0.5,-2.35)); +#66060 = VECTOR('',#66061,1.); +#66061 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66062 = PCURVE('',#54037,#66063); #66063 = DEFINITIONAL_REPRESENTATION('',(#66064),#66068); #66064 = LINE('',#66065,#66066); -#66065 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#66065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); #66066 = VECTOR('',#66067,1.); -#66067 = DIRECTION('',(0.258819045102,-0.965925826289)); +#66067 = DIRECTION('',(0.E+000,-1.)); #66068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#66069 = ORIENTED_EDGE('',*,*,#66070,.F.); -#66070 = EDGE_CURVE('',#65923,#66048,#66071,.T.); -#66071 = SURFACE_CURVE('',#66072,(#66076,#66083),.PCURVE_S1.); -#66072 = LINE('',#66073,#66074); -#66073 = CARTESIAN_POINT('',(-0.125,-1.18088190451,-1.902486398125)); -#66074 = VECTOR('',#66075,1.); -#66075 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66076 = PCURVE('',#59951,#66077); -#66077 = DEFINITIONAL_REPRESENTATION('',(#66078),#66082); -#66078 = LINE('',#66079,#66080); -#66079 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); -#66080 = VECTOR('',#66081,1.); -#66081 = DIRECTION('',(0.E+000,1.)); -#66082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66083 = PCURVE('',#65962,#66084); -#66084 = DEFINITIONAL_REPRESENTATION('',(#66085),#66088); -#66085 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66086,#66087),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#66086 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); -#66087 = CARTESIAN_POINT('',(3.403392041386,0.25)); -#66088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66089 = ORIENTED_EDGE('',*,*,#65922,.F.); -#66090 = ORIENTED_EDGE('',*,*,#66091,.T.); -#66091 = EDGE_CURVE('',#60709,#59936,#66092,.T.); -#66092 = SURFACE_CURVE('',#66093,(#66097,#66104),.PCURVE_S1.); -#66093 = LINE('',#66094,#66095); -#66094 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); -#66095 = VECTOR('',#66096,1.); -#66096 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#66097 = PCURVE('',#59951,#66098); -#66098 = DEFINITIONAL_REPRESENTATION('',(#66099),#66103); -#66099 = LINE('',#66100,#66101); -#66100 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#66101 = VECTOR('',#66102,1.); -#66102 = DIRECTION('',(-1.,0.E+000)); +#66069 = PCURVE('',#64170,#66070); +#66070 = DEFINITIONAL_REPRESENTATION('',(#66071),#66075); +#66071 = LINE('',#66072,#66073); +#66072 = CARTESIAN_POINT('',(0.42,0.E+000)); +#66073 = VECTOR('',#66074,1.); +#66074 = DIRECTION('',(0.E+000,-1.)); +#66075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66076 = ORIENTED_EDGE('',*,*,#66000,.T.); +#66077 = ORIENTED_EDGE('',*,*,#54021,.F.); +#66078 = ADVANCED_FACE('',(#66079),#64170,.F.); +#66079 = FACE_BOUND('',#66080,.F.); +#66080 = EDGE_LOOP('',(#66081,#66082,#66083,#66084)); +#66081 = ORIENTED_EDGE('',*,*,#64154,.F.); +#66082 = ORIENTED_EDGE('',*,*,#65719,.T.); +#66083 = ORIENTED_EDGE('',*,*,#66023,.T.); +#66084 = ORIENTED_EDGE('',*,*,#66056,.F.); +#66085 = ADVANCED_FACE('',(#66086),#45821,.T.); +#66086 = FACE_BOUND('',#66087,.T.); +#66087 = EDGE_LOOP('',(#66088,#66089,#66090,#66091)); +#66088 = ORIENTED_EDGE('',*,*,#64108,.T.); +#66089 = ORIENTED_EDGE('',*,*,#65741,.T.); +#66090 = ORIENTED_EDGE('',*,*,#45804,.F.); +#66091 = ORIENTED_EDGE('',*,*,#66092,.F.); +#66092 = EDGE_CURVE('',#64086,#45805,#66093,.T.); +#66093 = SURFACE_CURVE('',#66094,(#66098,#66104),.PCURVE_S1.); +#66094 = LINE('',#66095,#66096); +#66095 = CARTESIAN_POINT('',(3.445,0.57,-2.35)); +#66096 = VECTOR('',#66097,1.); +#66097 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66098 = PCURVE('',#45821,#66099); +#66099 = DEFINITIONAL_REPRESENTATION('',(#66100),#66103); +#66100 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66101,#66102),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#66101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66102 = CARTESIAN_POINT('',(0.E+000,1.2)); #66103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#66104 = PCURVE('',#59979,#66105); +#66104 = PCURVE('',#45848,#66105); #66105 = DEFINITIONAL_REPRESENTATION('',(#66106),#66110); #66106 = LINE('',#66107,#66108); -#66107 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#66107 = CARTESIAN_POINT('',(0.639375541595,0.E+000)); #66108 = VECTOR('',#66109,1.); -#66109 = DIRECTION('',(-0.258819045102,0.965925826289)); +#66109 = DIRECTION('',(0.E+000,1.)); #66110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#66111 = ADVANCED_FACE('',(#66112),#59923,.F.); +#66111 = ADVANCED_FACE('',(#66112),#45848,.T.); #66112 = FACE_BOUND('',#66113,.F.); -#66113 = EDGE_LOOP('',(#66114,#66115,#66116,#66117)); -#66114 = ORIENTED_EDGE('',*,*,#60971,.T.); -#66115 = ORIENTED_EDGE('',*,*,#66026,.T.); -#66116 = ORIENTED_EDGE('',*,*,#59907,.T.); -#66117 = ORIENTED_EDGE('',*,*,#61434,.T.); -#66118 = ADVANCED_FACE('',(#66119),#60959,.T.); -#66119 = FACE_BOUND('',#66120,.F.); -#66120 = EDGE_LOOP('',(#66121,#66122,#66145,#66168,#66189,#66190)); -#66121 = ORIENTED_EDGE('',*,*,#65895,.F.); -#66122 = ORIENTED_EDGE('',*,*,#66123,.F.); -#66123 = EDGE_CURVE('',#66124,#65868,#66126,.T.); -#66124 = VERTEX_POINT('',#66125); -#66125 = CARTESIAN_POINT('',(0.125,-1.255,-2.65)); -#66126 = SURFACE_CURVE('',#66127,(#66131,#66138),.PCURVE_S1.); -#66127 = LINE('',#66128,#66129); -#66128 = CARTESIAN_POINT('',(0.125,-1.255,-2.65)); -#66129 = VECTOR('',#66130,1.); -#66130 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66131 = PCURVE('',#60959,#66132); -#66132 = DEFINITIONAL_REPRESENTATION('',(#66133),#66137); -#66133 = LINE('',#66134,#66135); -#66134 = CARTESIAN_POINT('',(2.65,-1.255)); -#66135 = VECTOR('',#66136,1.); -#66136 = DIRECTION('',(0.E+000,1.)); -#66137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66138 = PCURVE('',#65883,#66139); -#66139 = DEFINITIONAL_REPRESENTATION('',(#66140),#66144); -#66140 = LINE('',#66141,#66142); -#66141 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66142 = VECTOR('',#66143,1.); -#66143 = DIRECTION('',(1.,0.E+000)); -#66144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66145 = ORIENTED_EDGE('',*,*,#66146,.F.); -#66146 = EDGE_CURVE('',#66147,#66124,#66149,.T.); -#66147 = VERTEX_POINT('',#66148); -#66148 = CARTESIAN_POINT('',(0.125,-1.255,-1.999078980754)); -#66149 = SURFACE_CURVE('',#66150,(#66154,#66161),.PCURVE_S1.); -#66150 = LINE('',#66151,#66152); -#66151 = CARTESIAN_POINT('',(0.125,-1.255,-1.999078980754)); -#66152 = VECTOR('',#66153,1.); -#66153 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66154 = PCURVE('',#60959,#66155); -#66155 = DEFINITIONAL_REPRESENTATION('',(#66156),#66160); -#66156 = LINE('',#66157,#66158); -#66157 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#66158 = VECTOR('',#66159,1.); -#66159 = DIRECTION('',(1.,0.E+000)); -#66160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66161 = PCURVE('',#65989,#66162); -#66162 = DEFINITIONAL_REPRESENTATION('',(#66163),#66167); -#66163 = LINE('',#66164,#66165); -#66164 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66165 = VECTOR('',#66166,1.); -#66166 = DIRECTION('',(1.,0.E+000)); -#66167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66168 = ORIENTED_EDGE('',*,*,#66169,.F.); -#66169 = EDGE_CURVE('',#66048,#66147,#66170,.T.); -#66170 = SURFACE_CURVE('',#66171,(#66176,#66183),.PCURVE_S1.); -#66171 = CIRCLE('',#66172,0.1); -#66172 = AXIS2_PLACEMENT_3D('',#66173,#66174,#66175); -#66173 = CARTESIAN_POINT('',(0.125,-1.155,-1.999078980754)); -#66174 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66175 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#66176 = PCURVE('',#60959,#66177); -#66177 = DEFINITIONAL_REPRESENTATION('',(#66178),#66182); -#66178 = CIRCLE('',#66179,0.1); -#66179 = AXIS2_PLACEMENT_2D('',#66180,#66181); -#66180 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#66181 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#66182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66183 = PCURVE('',#65962,#66184); -#66184 = DEFINITIONAL_REPRESENTATION('',(#66185),#66188); -#66185 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66186,#66187),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#66186 = CARTESIAN_POINT('',(3.403392041389,0.25)); -#66187 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#66188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66189 = ORIENTED_EDGE('',*,*,#66047,.F.); -#66190 = ORIENTED_EDGE('',*,*,#60943,.F.); -#66191 = ADVANCED_FACE('',(#66192),#65883,.T.); -#66192 = FACE_BOUND('',#66193,.F.); -#66193 = EDGE_LOOP('',(#66194,#66195,#66216,#66217)); -#66194 = ORIENTED_EDGE('',*,*,#66001,.F.); -#66195 = ORIENTED_EDGE('',*,*,#66196,.T.); -#66196 = EDGE_CURVE('',#65974,#66124,#66197,.T.); -#66197 = SURFACE_CURVE('',#66198,(#66202,#66209),.PCURVE_S1.); -#66198 = LINE('',#66199,#66200); -#66199 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); -#66200 = VECTOR('',#66201,1.); -#66201 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66202 = PCURVE('',#65883,#66203); -#66203 = DEFINITIONAL_REPRESENTATION('',(#66204),#66208); -#66204 = LINE('',#66205,#66206); -#66205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66206 = VECTOR('',#66207,1.); -#66207 = DIRECTION('',(0.E+000,1.)); -#66208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66209 = PCURVE('',#65989,#66210); +#66113 = EDGE_LOOP('',(#66114,#66115,#66135,#66136)); +#66114 = ORIENTED_EDGE('',*,*,#64085,.F.); +#66115 = ORIENTED_EDGE('',*,*,#66116,.T.); +#66116 = EDGE_CURVE('',#64063,#45833,#66117,.T.); +#66117 = SURFACE_CURVE('',#66118,(#66122,#66129),.PCURVE_S1.); +#66118 = LINE('',#66119,#66120); +#66119 = CARTESIAN_POINT('',(3.445,-6.937554159486E-002,-2.35)); +#66120 = VECTOR('',#66121,1.); +#66121 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66122 = PCURVE('',#45848,#66123); +#66123 = DEFINITIONAL_REPRESENTATION('',(#66124),#66128); +#66124 = LINE('',#66125,#66126); +#66125 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66126 = VECTOR('',#66127,1.); +#66127 = DIRECTION('',(0.E+000,1.)); +#66128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66129 = PCURVE('',#45877,#66130); +#66130 = DEFINITIONAL_REPRESENTATION('',(#66131),#66134); +#66131 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66132,#66133),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#66132 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#66133 = CARTESIAN_POINT('',(6.28318530718,1.2)); +#66134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66135 = ORIENTED_EDGE('',*,*,#45832,.T.); +#66136 = ORIENTED_EDGE('',*,*,#66092,.F.); +#66137 = ADVANCED_FACE('',(#66138),#45877,.T.); +#66138 = FACE_BOUND('',#66139,.T.); +#66139 = EDGE_LOOP('',(#66140,#66141,#66142,#66143)); +#66140 = ORIENTED_EDGE('',*,*,#64062,.T.); +#66141 = ORIENTED_EDGE('',*,*,#66116,.T.); +#66142 = ORIENTED_EDGE('',*,*,#45860,.F.); +#66143 = ORIENTED_EDGE('',*,*,#66144,.F.); +#66144 = EDGE_CURVE('',#64040,#45861,#66145,.T.); +#66145 = SURFACE_CURVE('',#66146,(#66150,#66156),.PCURVE_S1.); +#66146 = LINE('',#66147,#66148); +#66147 = CARTESIAN_POINT('',(3.371776695297,-0.246152236892,-2.35)); +#66148 = VECTOR('',#66149,1.); +#66149 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66150 = PCURVE('',#45877,#66151); +#66151 = DEFINITIONAL_REPRESENTATION('',(#66152),#66155); +#66152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66153,#66154),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#66153 = CARTESIAN_POINT('',(5.497787143783,0.E+000)); +#66154 = CARTESIAN_POINT('',(5.497787143783,1.2)); +#66155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66156 = PCURVE('',#45904,#66157); +#66157 = DEFINITIONAL_REPRESENTATION('',(#66158),#66162); +#66158 = LINE('',#66159,#66160); +#66159 = CARTESIAN_POINT('',(0.84941125497,0.E+000)); +#66160 = VECTOR('',#66161,1.); +#66161 = DIRECTION('',(0.E+000,1.)); +#66162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66163 = ADVANCED_FACE('',(#66164),#45904,.T.); +#66164 = FACE_BOUND('',#66165,.F.); +#66165 = EDGE_LOOP('',(#66166,#66167,#66187,#66188,#66189)); +#66166 = ORIENTED_EDGE('',*,*,#65475,.F.); +#66167 = ORIENTED_EDGE('',*,*,#66168,.T.); +#66168 = EDGE_CURVE('',#65449,#45889,#66169,.T.); +#66169 = SURFACE_CURVE('',#66170,(#66174,#66181),.PCURVE_S1.); +#66170 = LINE('',#66171,#66172); +#66171 = CARTESIAN_POINT('',(2.771152236891,-0.846776695297,-2.35)); +#66172 = VECTOR('',#66173,1.); +#66173 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66174 = PCURVE('',#45904,#66175); +#66175 = DEFINITIONAL_REPRESENTATION('',(#66176),#66180); +#66176 = LINE('',#66177,#66178); +#66177 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66178 = VECTOR('',#66179,1.); +#66179 = DIRECTION('',(0.E+000,1.)); +#66180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66181 = PCURVE('',#45355,#66182); +#66182 = DEFINITIONAL_REPRESENTATION('',(#66183),#66186); +#66183 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66184,#66185),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.2),.PIECEWISE_BEZIER_KNOTS.); +#66184 = CARTESIAN_POINT('',(5.49778714378,0.E+000)); +#66185 = CARTESIAN_POINT('',(5.49778714378,1.2)); +#66186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66187 = ORIENTED_EDGE('',*,*,#45888,.T.); +#66188 = ORIENTED_EDGE('',*,*,#66144,.F.); +#66189 = ORIENTED_EDGE('',*,*,#64039,.F.); +#66190 = ADVANCED_FACE('',(#66191),#45355,.T.); +#66191 = FACE_BOUND('',#66192,.T.); +#66192 = EDGE_LOOP('',(#66193,#66194,#66195,#66196)); +#66193 = ORIENTED_EDGE('',*,*,#65448,.T.); +#66194 = ORIENTED_EDGE('',*,*,#66168,.T.); +#66195 = ORIENTED_EDGE('',*,*,#45916,.F.); +#66196 = ORIENTED_EDGE('',*,*,#45339,.F.); +#66197 = ADVANCED_FACE('',(#66198),#45764,.T.); +#66198 = FACE_BOUND('',#66199,.F.); +#66199 = EDGE_LOOP('',(#66200,#66223,#66224,#66225,#66226)); +#66200 = ORIENTED_EDGE('',*,*,#66201,.F.); +#66201 = EDGE_CURVE('',#65763,#66202,#66204,.T.); +#66202 = VERTEX_POINT('',#66203); +#66203 = CARTESIAN_POINT('',(0.41,0.773013158464,-1.25)); +#66204 = SURFACE_CURVE('',#66205,(#66209,#66216),.PCURVE_S1.); +#66205 = LINE('',#66206,#66207); +#66206 = CARTESIAN_POINT('',(0.41,0.92,-1.25)); +#66207 = VECTOR('',#66208,1.); +#66208 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66209 = PCURVE('',#45764,#66210); #66210 = DEFINITIONAL_REPRESENTATION('',(#66211),#66215); #66211 = LINE('',#66212,#66213); -#66212 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#66212 = CARTESIAN_POINT('',(-0.1375,-7.071067811865E-002)); #66213 = VECTOR('',#66214,1.); -#66214 = DIRECTION('',(0.E+000,1.)); +#66214 = DIRECTION('',(1.,0.E+000)); #66215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#66216 = ORIENTED_EDGE('',*,*,#66123,.T.); -#66217 = ORIENTED_EDGE('',*,*,#65867,.F.); -#66218 = ADVANCED_FACE('',(#66219),#65989,.T.); -#66219 = FACE_BOUND('',#66220,.F.); -#66220 = EDGE_LOOP('',(#66221,#66222,#66242,#66243)); -#66221 = ORIENTED_EDGE('',*,*,#65973,.F.); -#66222 = ORIENTED_EDGE('',*,*,#66223,.T.); -#66223 = EDGE_CURVE('',#65946,#66147,#66224,.T.); -#66224 = SURFACE_CURVE('',#66225,(#66229,#66236),.PCURVE_S1.); -#66225 = LINE('',#66226,#66227); -#66226 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); -#66227 = VECTOR('',#66228,1.); -#66228 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66229 = PCURVE('',#65989,#66230); -#66230 = DEFINITIONAL_REPRESENTATION('',(#66231),#66235); -#66231 = LINE('',#66232,#66233); -#66232 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66233 = VECTOR('',#66234,1.); -#66234 = DIRECTION('',(0.E+000,1.)); -#66235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66236 = PCURVE('',#65962,#66237); -#66237 = DEFINITIONAL_REPRESENTATION('',(#66238),#66241); -#66238 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66239,#66240),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#66239 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#66240 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#66241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66242 = ORIENTED_EDGE('',*,*,#66146,.T.); -#66243 = ORIENTED_EDGE('',*,*,#66196,.F.); -#66244 = ADVANCED_FACE('',(#66245),#65962,.T.); -#66245 = FACE_BOUND('',#66246,.T.); -#66246 = EDGE_LOOP('',(#66247,#66248,#66249,#66250)); -#66247 = ORIENTED_EDGE('',*,*,#65945,.T.); -#66248 = ORIENTED_EDGE('',*,*,#66223,.T.); -#66249 = ORIENTED_EDGE('',*,*,#66169,.F.); -#66250 = ORIENTED_EDGE('',*,*,#66070,.F.); -#66251 = ADVANCED_FACE('',(#66252),#59979,.T.); -#66252 = FACE_BOUND('',#66253,.F.); -#66253 = EDGE_LOOP('',(#66254,#66255,#66256,#66257)); -#66254 = ORIENTED_EDGE('',*,*,#60706,.F.); -#66255 = ORIENTED_EDGE('',*,*,#61365,.F.); -#66256 = ORIENTED_EDGE('',*,*,#59963,.F.); -#66257 = ORIENTED_EDGE('',*,*,#66091,.F.); -#66258 = ADVANCED_FACE('',(#66259),#62252,.T.); -#66259 = FACE_BOUND('',#66260,.F.); -#66260 = EDGE_LOOP('',(#66261,#66284,#66312,#66333)); -#66261 = ORIENTED_EDGE('',*,*,#66262,.F.); -#66262 = EDGE_CURVE('',#66263,#60893,#66265,.T.); -#66263 = VERTEX_POINT('',#66264); -#66264 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); -#66265 = SURFACE_CURVE('',#66266,(#66270,#66277),.PCURVE_S1.); -#66266 = LINE('',#66267,#66268); -#66267 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); -#66268 = VECTOR('',#66269,1.); -#66269 = DIRECTION('',(0.E+000,0.E+000,1.)); -#66270 = PCURVE('',#62252,#66271); -#66271 = DEFINITIONAL_REPRESENTATION('',(#66272),#66276); -#66272 = LINE('',#66273,#66274); -#66273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66274 = VECTOR('',#66275,1.); -#66275 = DIRECTION('',(1.,0.E+000)); -#66276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66277 = PCURVE('',#60908,#66278); -#66278 = DEFINITIONAL_REPRESENTATION('',(#66279),#66283); -#66279 = LINE('',#66280,#66281); -#66280 = CARTESIAN_POINT('',(2.65,-1.105)); -#66281 = VECTOR('',#66282,1.); -#66282 = DIRECTION('',(-1.,0.E+000)); -#66283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66284 = ORIENTED_EDGE('',*,*,#66285,.T.); -#66285 = EDGE_CURVE('',#66263,#66286,#66288,.T.); -#66286 = VERTEX_POINT('',#66287); -#66287 = CARTESIAN_POINT('',(0.775,-1.105,-2.65)); -#66288 = SURFACE_CURVE('',#66289,(#66293,#66300),.PCURVE_S1.); -#66289 = LINE('',#66290,#66291); -#66290 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); -#66291 = VECTOR('',#66292,1.); -#66292 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66293 = PCURVE('',#62252,#66294); -#66294 = DEFINITIONAL_REPRESENTATION('',(#66295),#66299); -#66295 = LINE('',#66296,#66297); -#66296 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66297 = VECTOR('',#66298,1.); -#66298 = DIRECTION('',(0.E+000,1.)); -#66299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66300 = PCURVE('',#66301,#66306); -#66301 = PLANE('',#66302); -#66302 = AXIS2_PLACEMENT_3D('',#66303,#66304,#66305); -#66303 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); -#66304 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66305 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66306 = DEFINITIONAL_REPRESENTATION('',(#66307),#66311); -#66307 = LINE('',#66308,#66309); -#66308 = CARTESIAN_POINT('',(0.15,0.E+000)); -#66309 = VECTOR('',#66310,1.); -#66310 = DIRECTION('',(0.E+000,1.)); -#66311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66312 = ORIENTED_EDGE('',*,*,#66313,.T.); -#66313 = EDGE_CURVE('',#66286,#61048,#66314,.T.); -#66314 = SURFACE_CURVE('',#66315,(#66319,#66326),.PCURVE_S1.); -#66315 = LINE('',#66316,#66317); -#66316 = CARTESIAN_POINT('',(0.775,-1.105,-2.65)); -#66317 = VECTOR('',#66318,1.); -#66318 = DIRECTION('',(0.E+000,0.E+000,1.)); -#66319 = PCURVE('',#62252,#66320); -#66320 = DEFINITIONAL_REPRESENTATION('',(#66321),#66325); -#66321 = LINE('',#66322,#66323); -#66322 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66323 = VECTOR('',#66324,1.); -#66324 = DIRECTION('',(1.,0.E+000)); -#66325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66326 = PCURVE('',#61086,#66327); -#66327 = DEFINITIONAL_REPRESENTATION('',(#66328),#66332); -#66328 = LINE('',#66329,#66330); -#66329 = CARTESIAN_POINT('',(2.65,-1.105)); -#66330 = VECTOR('',#66331,1.); -#66331 = DIRECTION('',(-1.,0.E+000)); -#66332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66333 = ORIENTED_EDGE('',*,*,#62238,.F.); -#66334 = ADVANCED_FACE('',(#66335),#60908,.F.); -#66335 = FACE_BOUND('',#66336,.F.); -#66336 = EDGE_LOOP('',(#66337,#66338,#66339,#66362,#66390,#66418)); -#66337 = ORIENTED_EDGE('',*,*,#66262,.T.); -#66338 = ORIENTED_EDGE('',*,*,#60892,.F.); -#66339 = ORIENTED_EDGE('',*,*,#66340,.T.); -#66340 = EDGE_CURVE('',#60865,#66341,#66343,.T.); -#66341 = VERTEX_POINT('',#66342); -#66342 = CARTESIAN_POINT('',(0.525,-1.18088190451,-1.902486398125)); -#66343 = SURFACE_CURVE('',#66344,(#66348,#66355),.PCURVE_S1.); -#66344 = LINE('',#66345,#66346); -#66345 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); -#66346 = VECTOR('',#66347,1.); -#66347 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#66348 = PCURVE('',#60908,#66349); -#66349 = DEFINITIONAL_REPRESENTATION('',(#66350),#66354); -#66350 = LINE('',#66351,#66352); -#66351 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66352 = VECTOR('',#66353,1.); -#66353 = DIRECTION('',(0.258819045102,-0.965925826289)); -#66354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66355 = PCURVE('',#59839,#66356); -#66356 = DEFINITIONAL_REPRESENTATION('',(#66357),#66361); -#66357 = LINE('',#66358,#66359); -#66358 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#66359 = VECTOR('',#66360,1.); -#66360 = DIRECTION('',(1.,0.E+000)); -#66361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66362 = ORIENTED_EDGE('',*,*,#66363,.T.); -#66363 = EDGE_CURVE('',#66341,#66364,#66366,.T.); -#66364 = VERTEX_POINT('',#66365); -#66365 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); -#66366 = SURFACE_CURVE('',#66367,(#66372,#66379),.PCURVE_S1.); -#66367 = CIRCLE('',#66368,0.1); -#66368 = AXIS2_PLACEMENT_3D('',#66369,#66370,#66371); -#66369 = CARTESIAN_POINT('',(0.525,-1.155,-1.999078980754)); -#66370 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66371 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#66372 = PCURVE('',#60908,#66373); -#66373 = DEFINITIONAL_REPRESENTATION('',(#66374),#66378); -#66374 = CIRCLE('',#66375,0.1); -#66375 = AXIS2_PLACEMENT_2D('',#66376,#66377); -#66376 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#66377 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#66378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66379 = PCURVE('',#66380,#66385); -#66380 = CYLINDRICAL_SURFACE('',#66381,0.1); -#66381 = AXIS2_PLACEMENT_3D('',#66382,#66383,#66384); -#66382 = CARTESIAN_POINT('',(0.525,-1.155,-1.999078980754)); -#66383 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66384 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66385 = DEFINITIONAL_REPRESENTATION('',(#66386),#66389); -#66386 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66387,#66388),.UNSPECIFIED., +#66216 = PCURVE('',#49575,#66217); +#66217 = DEFINITIONAL_REPRESENTATION('',(#66218),#66222); +#66218 = LINE('',#66219,#66220); +#66219 = CARTESIAN_POINT('',(1.25,0.92)); +#66220 = VECTOR('',#66221,1.); +#66221 = DIRECTION('',(0.E+000,-1.)); +#66222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66223 = ORIENTED_EDGE('',*,*,#65762,.T.); +#66224 = ORIENTED_EDGE('',*,*,#45748,.T.); +#66225 = ORIENTED_EDGE('',*,*,#49260,.T.); +#66226 = ORIENTED_EDGE('',*,*,#66227,.F.); +#66227 = EDGE_CURVE('',#66202,#49233,#66228,.T.); +#66228 = SURFACE_CURVE('',#66229,(#66233,#66240),.PCURVE_S1.); +#66229 = LINE('',#66230,#66231); +#66230 = CARTESIAN_POINT('',(0.41,0.773013158464,-1.25)); +#66231 = VECTOR('',#66232,1.); +#66232 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66233 = PCURVE('',#45764,#66234); +#66234 = DEFINITIONAL_REPRESENTATION('',(#66235),#66239); +#66235 = LINE('',#66236,#66237); +#66236 = CARTESIAN_POINT('',(9.4868415357E-003,-7.071067811865E-002)); +#66237 = VECTOR('',#66238,1.); +#66238 = DIRECTION('',(1.,0.E+000)); +#66239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66240 = PCURVE('',#49248,#66241); +#66241 = DEFINITIONAL_REPRESENTATION('',(#66242),#66246); +#66242 = LINE('',#66243,#66244); +#66243 = CARTESIAN_POINT('',(0.15,-0.451986841536)); +#66244 = VECTOR('',#66245,1.); +#66245 = DIRECTION('',(0.E+000,-1.)); +#66246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66247 = ADVANCED_FACE('',(#66248),#49575,.T.); +#66248 = FACE_BOUND('',#66249,.F.); +#66249 = EDGE_LOOP('',(#66250,#66251,#66252,#66253,#66274)); +#66250 = ORIENTED_EDGE('',*,*,#49561,.F.); +#66251 = ORIENTED_EDGE('',*,*,#65785,.F.); +#66252 = ORIENTED_EDGE('',*,*,#66201,.T.); +#66253 = ORIENTED_EDGE('',*,*,#66254,.F.); +#66254 = EDGE_CURVE('',#50753,#66202,#66255,.T.); +#66255 = SURFACE_CURVE('',#66256,(#66261,#66268),.PCURVE_S1.); +#66256 = CIRCLE('',#66257,0.2); +#66257 = AXIS2_PLACEMENT_3D('',#66258,#66259,#66260); +#66258 = CARTESIAN_POINT('',(0.41,0.925,-1.38)); +#66259 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66260 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66261 = PCURVE('',#49575,#66262); +#66262 = DEFINITIONAL_REPRESENTATION('',(#66263),#66267); +#66263 = CIRCLE('',#66264,0.2); +#66264 = AXIS2_PLACEMENT_2D('',#66265,#66266); +#66265 = CARTESIAN_POINT('',(1.38,0.925)); +#66266 = DIRECTION('',(-1.,0.E+000)); +#66267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66268 = PCURVE('',#49478,#66269); +#66269 = DEFINITIONAL_REPRESENTATION('',(#66270),#66273); +#66270 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66271,#66272),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.86321189007),.PIECEWISE_BEZIER_KNOTS.); +#66271 = CARTESIAN_POINT('',(3.14159265359,0.82)); +#66272 = CARTESIAN_POINT('',(4.004804543659,0.82)); +#66273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66274 = ORIENTED_EDGE('',*,*,#50752,.F.); +#66275 = ADVANCED_FACE('',(#66276),#49478,.T.); +#66276 = FACE_BOUND('',#66277,.T.); +#66277 = EDGE_LOOP('',(#66278,#66305,#66332,#66353,#66354,#66355)); +#66278 = ORIENTED_EDGE('',*,*,#66279,.T.); +#66279 = EDGE_CURVE('',#49331,#66280,#66282,.T.); +#66280 = VERTEX_POINT('',#66281); +#66281 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); +#66282 = SURFACE_CURVE('',#66283,(#66288,#66294),.PCURVE_S1.); +#66283 = CIRCLE('',#66284,0.2); +#66284 = AXIS2_PLACEMENT_3D('',#66285,#66286,#66287); +#66285 = CARTESIAN_POINT('',(-0.41,0.925,-1.38)); +#66286 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66287 = DIRECTION('',(0.E+000,-0.759934207679,0.65)); +#66288 = PCURVE('',#49478,#66289); +#66289 = DEFINITIONAL_REPRESENTATION('',(#66290),#66293); +#66290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66291,#66292),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.707584436725),.PIECEWISE_BEZIER_KNOTS.); +#66291 = CARTESIAN_POINT('',(4.004804543659,0.E+000)); +#66292 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#66293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66294 = PCURVE('',#49136,#66295); +#66295 = DEFINITIONAL_REPRESENTATION('',(#66296),#66304); +#66296 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#66297,#66298,#66299,#66300 + ,#66301,#66302,#66303),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#66297 = CARTESIAN_POINT('',(0.25,-0.451986841536)); +#66298 = CARTESIAN_POINT('',(-1.324893162176E-002,-0.67715344652)); +#66299 = CARTESIAN_POINT('',(-7.662446581088E-002,-0.336589881724)); +#66300 = CARTESIAN_POINT('',(-0.14,3.973683071407E-003)); +#66301 = CARTESIAN_POINT('',(0.186624465811,-0.11142327674)); +#66302 = CARTESIAN_POINT('',(0.513248931622,-0.226820236552)); +#66303 = CARTESIAN_POINT('',(0.25,-0.451986841536)); +#66304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66305 = ORIENTED_EDGE('',*,*,#66306,.T.); +#66306 = EDGE_CURVE('',#66280,#66307,#66309,.T.); +#66307 = VERTEX_POINT('',#66308); +#66308 = CARTESIAN_POINT('',(0.41,0.725,-1.38)); +#66309 = SURFACE_CURVE('',#66310,(#66314,#66320),.PCURVE_S1.); +#66310 = LINE('',#66311,#66312); +#66311 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); +#66312 = VECTOR('',#66313,1.); +#66313 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66314 = PCURVE('',#49478,#66315); +#66315 = DEFINITIONAL_REPRESENTATION('',(#66316),#66319); +#66316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66317,#66318),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); +#66317 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#66318 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#66319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66320 = PCURVE('',#66321,#66326); +#66321 = PLANE('',#66322); +#66322 = AXIS2_PLACEMENT_3D('',#66323,#66324,#66325); +#66323 = CARTESIAN_POINT('',(-0.41,0.725,-1.38)); +#66324 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66325 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66326 = DEFINITIONAL_REPRESENTATION('',(#66327),#66331); +#66327 = LINE('',#66328,#66329); +#66328 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66329 = VECTOR('',#66330,1.); +#66330 = DIRECTION('',(0.E+000,1.)); +#66331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66332 = ORIENTED_EDGE('',*,*,#66333,.F.); +#66333 = EDGE_CURVE('',#66202,#66307,#66334,.T.); +#66334 = SURFACE_CURVE('',#66335,(#66340,#66346),.PCURVE_S1.); +#66335 = CIRCLE('',#66336,0.2); +#66336 = AXIS2_PLACEMENT_3D('',#66337,#66338,#66339); +#66337 = CARTESIAN_POINT('',(0.41,0.925,-1.38)); +#66338 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66339 = DIRECTION('',(0.E+000,-0.759934207679,0.65)); +#66340 = PCURVE('',#49478,#66341); +#66341 = DEFINITIONAL_REPRESENTATION('',(#66342),#66345); +#66342 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66343,#66344),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.707584436725),.PIECEWISE_BEZIER_KNOTS.); +#66343 = CARTESIAN_POINT('',(4.004804543659,0.82)); +#66344 = CARTESIAN_POINT('',(4.712388980385,0.82)); +#66345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66346 = PCURVE('',#49248,#66347); +#66347 = DEFINITIONAL_REPRESENTATION('',(#66348),#66352); +#66348 = CIRCLE('',#66349,0.2); +#66349 = AXIS2_PLACEMENT_2D('',#66350,#66351); +#66350 = CARTESIAN_POINT('',(0.28,-0.3)); +#66351 = DIRECTION('',(-0.65,-0.759934207679)); +#66352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66353 = ORIENTED_EDGE('',*,*,#66254,.F.); +#66354 = ORIENTED_EDGE('',*,*,#50775,.F.); +#66355 = ORIENTED_EDGE('',*,*,#49463,.T.); +#66356 = ADVANCED_FACE('',(#66357),#52557,.F.); +#66357 = FACE_BOUND('',#66358,.F.); +#66358 = EDGE_LOOP('',(#66359,#66386,#66387,#66409)); +#66359 = ORIENTED_EDGE('',*,*,#66360,.T.); +#66360 = EDGE_CURVE('',#66361,#52542,#66363,.T.); +#66361 = VERTEX_POINT('',#66362); +#66362 = CARTESIAN_POINT('',(-0.41,1.025,-1.4)); +#66363 = SURFACE_CURVE('',#66364,(#66369,#66380),.PCURVE_S1.); +#66364 = CIRCLE('',#66365,0.2); +#66365 = AXIS2_PLACEMENT_3D('',#66366,#66367,#66368); +#66366 = CARTESIAN_POINT('',(-0.41,1.025,-1.2)); +#66367 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66368 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66369 = PCURVE('',#52557,#66370); +#66370 = DEFINITIONAL_REPRESENTATION('',(#66371),#66379); +#66371 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#66372,#66373,#66374,#66375 + ,#66376,#66377,#66378),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#66372 = CARTESIAN_POINT('',(0.1,-0.2)); +#66373 = CARTESIAN_POINT('',(0.1,0.146410161514)); +#66374 = CARTESIAN_POINT('',(0.4,-2.679491924311E-002)); +#66375 = CARTESIAN_POINT('',(0.7,-0.2)); +#66376 = CARTESIAN_POINT('',(0.4,-0.373205080757)); +#66377 = CARTESIAN_POINT('',(0.1,-0.546410161514)); +#66378 = CARTESIAN_POINT('',(0.1,-0.2)); +#66379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66380 = PCURVE('',#52585,#66381); +#66381 = DEFINITIONAL_REPRESENTATION('',(#66382),#66385); +#66382 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66383,#66384),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66383 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66384 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#66385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66386 = ORIENTED_EDGE('',*,*,#52539,.F.); +#66387 = ORIENTED_EDGE('',*,*,#66388,.T.); +#66388 = EDGE_CURVE('',#52540,#66389,#66391,.T.); +#66389 = VERTEX_POINT('',#66390); +#66390 = CARTESIAN_POINT('',(-0.41,1.025,-1.5)); +#66391 = SURFACE_CURVE('',#66392,(#66396,#66403),.PCURVE_S1.); +#66392 = LINE('',#66393,#66394); +#66393 = CARTESIAN_POINT('',(-0.41,1.225,-1.5)); +#66394 = VECTOR('',#66395,1.); +#66395 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66396 = PCURVE('',#52557,#66397); +#66397 = DEFINITIONAL_REPRESENTATION('',(#66398),#66402); +#66398 = LINE('',#66399,#66400); +#66399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66400 = VECTOR('',#66401,1.); +#66401 = DIRECTION('',(0.E+000,-1.)); +#66402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66403 = PCURVE('',#52695,#66404); +#66404 = DEFINITIONAL_REPRESENTATION('',(#66405),#66408); +#66405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66406,#66407),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#66406 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#66407 = CARTESIAN_POINT('',(3.14159265359,-0.2)); +#66408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66409 = ORIENTED_EDGE('',*,*,#66410,.T.); +#66410 = EDGE_CURVE('',#66389,#66361,#66411,.T.); +#66411 = SURFACE_CURVE('',#66412,(#66416,#66423),.PCURVE_S1.); +#66412 = LINE('',#66413,#66414); +#66413 = CARTESIAN_POINT('',(-0.41,1.025,-1.5)); +#66414 = VECTOR('',#66415,1.); +#66415 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66416 = PCURVE('',#52557,#66417); +#66417 = DEFINITIONAL_REPRESENTATION('',(#66418),#66422); +#66418 = LINE('',#66419,#66420); +#66419 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#66420 = VECTOR('',#66421,1.); +#66421 = DIRECTION('',(1.,0.E+000)); +#66422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66423 = PCURVE('',#66424,#66429); +#66424 = PLANE('',#66425); +#66425 = AXIS2_PLACEMENT_3D('',#66426,#66427,#66428); +#66426 = CARTESIAN_POINT('',(-0.41,1.025,-1.75)); +#66427 = DIRECTION('',(0.E+000,1.,0.E+000)); +#66428 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66429 = DEFINITIONAL_REPRESENTATION('',(#66430),#66434); +#66430 = LINE('',#66431,#66432); +#66431 = CARTESIAN_POINT('',(0.25,0.E+000)); +#66432 = VECTOR('',#66433,1.); +#66433 = DIRECTION('',(1.,0.E+000)); +#66434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66435 = ADVANCED_FACE('',(#66436),#49136,.F.); +#66436 = FACE_BOUND('',#66437,.F.); +#66437 = EDGE_LOOP('',(#66438,#66439,#66462,#66482,#66483)); +#66438 = ORIENTED_EDGE('',*,*,#66279,.T.); +#66439 = ORIENTED_EDGE('',*,*,#66440,.F.); +#66440 = EDGE_CURVE('',#66441,#66280,#66443,.T.); +#66441 = VERTEX_POINT('',#66442); +#66442 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); +#66443 = SURFACE_CURVE('',#66444,(#66448,#66455),.PCURVE_S1.); +#66444 = LINE('',#66445,#66446); +#66445 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); +#66446 = VECTOR('',#66447,1.); +#66447 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66448 = PCURVE('',#49136,#66449); +#66449 = DEFINITIONAL_REPRESENTATION('',(#66450),#66454); +#66450 = LINE('',#66451,#66452); +#66451 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66452 = VECTOR('',#66453,1.); +#66453 = DIRECTION('',(1.,0.E+000)); +#66454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66455 = PCURVE('',#66321,#66456); +#66456 = DEFINITIONAL_REPRESENTATION('',(#66457),#66461); +#66457 = LINE('',#66458,#66459); +#66458 = CARTESIAN_POINT('',(0.12,0.E+000)); +#66459 = VECTOR('',#66460,1.); +#66460 = DIRECTION('',(-1.,0.E+000)); +#66461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66462 = ORIENTED_EDGE('',*,*,#66463,.T.); +#66463 = EDGE_CURVE('',#66441,#49121,#66464,.T.); +#66464 = SURFACE_CURVE('',#66465,(#66469,#66476),.PCURVE_S1.); +#66465 = LINE('',#66466,#66467); +#66466 = CARTESIAN_POINT('',(-0.41,0.725,-1.5)); +#66467 = VECTOR('',#66468,1.); +#66468 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66469 = PCURVE('',#49136,#66470); +#66470 = DEFINITIONAL_REPRESENTATION('',(#66471),#66475); +#66471 = LINE('',#66472,#66473); +#66472 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66473 = VECTOR('',#66474,1.); +#66474 = DIRECTION('',(0.E+000,-1.)); +#66475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66476 = PCURVE('',#49165,#66477); +#66477 = DEFINITIONAL_REPRESENTATION('',(#66478),#66481); +#66478 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66479,#66480),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); +#66479 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#66480 = CARTESIAN_POINT('',(3.14159265359,-0.58)); +#66481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66482 = ORIENTED_EDGE('',*,*,#49120,.T.); +#66483 = ORIENTED_EDGE('',*,*,#49358,.T.); +#66484 = ADVANCED_FACE('',(#66485),#52585,.T.); +#66485 = FACE_BOUND('',#66486,.T.); +#66486 = EDGE_LOOP('',(#66487,#66488,#66489,#66512)); +#66487 = ORIENTED_EDGE('',*,*,#66360,.T.); +#66488 = ORIENTED_EDGE('',*,*,#52569,.T.); +#66489 = ORIENTED_EDGE('',*,*,#66490,.F.); +#66490 = EDGE_CURVE('',#66491,#52570,#66493,.T.); +#66491 = VERTEX_POINT('',#66492); +#66492 = CARTESIAN_POINT('',(0.41,1.025,-1.4)); +#66493 = SURFACE_CURVE('',#66494,(#66499,#66505),.PCURVE_S1.); +#66494 = CIRCLE('',#66495,0.2); +#66495 = AXIS2_PLACEMENT_3D('',#66496,#66497,#66498); +#66496 = CARTESIAN_POINT('',(0.41,1.025,-1.2)); +#66497 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66498 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66499 = PCURVE('',#52585,#66500); +#66500 = DEFINITIONAL_REPRESENTATION('',(#66501),#66504); +#66501 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66502,#66503),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66502 = CARTESIAN_POINT('',(0.E+000,0.82)); +#66503 = CARTESIAN_POINT('',(1.570796326795,0.82)); +#66504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66505 = PCURVE('',#52612,#66506); +#66506 = DEFINITIONAL_REPRESENTATION('',(#66507),#66511); +#66507 = CIRCLE('',#66508,0.2); +#66508 = AXIS2_PLACEMENT_2D('',#66509,#66510); +#66509 = CARTESIAN_POINT('',(1.E-001,-0.2)); +#66510 = DIRECTION('',(1.,0.E+000)); +#66511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66512 = ORIENTED_EDGE('',*,*,#66513,.F.); +#66513 = EDGE_CURVE('',#66361,#66491,#66514,.T.); +#66514 = SURFACE_CURVE('',#66515,(#66519,#66525),.PCURVE_S1.); +#66515 = LINE('',#66516,#66517); +#66516 = CARTESIAN_POINT('',(-0.41,1.025,-1.4)); +#66517 = VECTOR('',#66518,1.); +#66518 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66519 = PCURVE('',#52585,#66520); +#66520 = DEFINITIONAL_REPRESENTATION('',(#66521),#66524); +#66521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66522,#66523),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.82),.PIECEWISE_BEZIER_KNOTS.); +#66522 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66523 = CARTESIAN_POINT('',(0.E+000,0.82)); +#66524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66525 = PCURVE('',#66424,#66526); +#66526 = DEFINITIONAL_REPRESENTATION('',(#66527),#66531); +#66527 = LINE('',#66528,#66529); +#66528 = CARTESIAN_POINT('',(0.35,0.E+000)); +#66529 = VECTOR('',#66530,1.); +#66530 = DIRECTION('',(0.E+000,1.)); +#66531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66532 = ADVANCED_FACE('',(#66533),#66424,.T.); +#66533 = FACE_BOUND('',#66534,.F.); +#66534 = EDGE_LOOP('',(#66535,#66558,#66581,#66604,#66625,#66626)); +#66535 = ORIENTED_EDGE('',*,*,#66536,.F.); +#66536 = EDGE_CURVE('',#66537,#66389,#66539,.T.); +#66537 = VERTEX_POINT('',#66538); +#66538 = CARTESIAN_POINT('',(-0.16,1.025,-1.75)); +#66539 = SURFACE_CURVE('',#66540,(#66545,#66552),.PCURVE_S1.); +#66540 = CIRCLE('',#66541,0.25); +#66541 = AXIS2_PLACEMENT_3D('',#66542,#66543,#66544); +#66542 = CARTESIAN_POINT('',(-0.16,1.025,-1.5)); +#66543 = DIRECTION('',(0.E+000,1.,0.E+000)); +#66544 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66545 = PCURVE('',#66424,#66546); +#66546 = DEFINITIONAL_REPRESENTATION('',(#66547),#66551); +#66547 = CIRCLE('',#66548,0.25); +#66548 = AXIS2_PLACEMENT_2D('',#66549,#66550); +#66549 = CARTESIAN_POINT('',(0.25,0.25)); +#66550 = DIRECTION('',(-1.,0.E+000)); +#66551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66552 = PCURVE('',#52695,#66553); +#66553 = DEFINITIONAL_REPRESENTATION('',(#66554),#66557); +#66554 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66555,#66556),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66555 = CARTESIAN_POINT('',(1.570796326795,-0.2)); +#66556 = CARTESIAN_POINT('',(3.14159265359,-0.2)); +#66557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66558 = ORIENTED_EDGE('',*,*,#66559,.F.); +#66559 = EDGE_CURVE('',#66560,#66537,#66562,.T.); +#66560 = VERTEX_POINT('',#66561); +#66561 = CARTESIAN_POINT('',(0.16,1.025,-1.75)); +#66562 = SURFACE_CURVE('',#66563,(#66567,#66574),.PCURVE_S1.); +#66563 = LINE('',#66564,#66565); +#66564 = CARTESIAN_POINT('',(0.16,1.025,-1.75)); +#66565 = VECTOR('',#66566,1.); +#66566 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#66567 = PCURVE('',#66424,#66568); +#66568 = DEFINITIONAL_REPRESENTATION('',(#66569),#66573); +#66569 = LINE('',#66570,#66571); +#66570 = CARTESIAN_POINT('',(0.E+000,0.57)); +#66571 = VECTOR('',#66572,1.); +#66572 = DIRECTION('',(0.E+000,-1.)); +#66573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66574 = PCURVE('',#52668,#66575); +#66575 = DEFINITIONAL_REPRESENTATION('',(#66576),#66580); +#66576 = LINE('',#66577,#66578); +#66577 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#66578 = VECTOR('',#66579,1.); +#66579 = DIRECTION('',(1.,0.E+000)); +#66580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66581 = ORIENTED_EDGE('',*,*,#66582,.F.); +#66582 = EDGE_CURVE('',#66583,#66560,#66585,.T.); +#66583 = VERTEX_POINT('',#66584); +#66584 = CARTESIAN_POINT('',(0.41,1.025,-1.5)); +#66585 = SURFACE_CURVE('',#66586,(#66591,#66598),.PCURVE_S1.); +#66586 = CIRCLE('',#66587,0.25); +#66587 = AXIS2_PLACEMENT_3D('',#66588,#66589,#66590); +#66588 = CARTESIAN_POINT('',(0.16,1.025,-1.5)); +#66589 = DIRECTION('',(0.E+000,1.,0.E+000)); +#66590 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66591 = PCURVE('',#66424,#66592); +#66592 = DEFINITIONAL_REPRESENTATION('',(#66593),#66597); +#66593 = CIRCLE('',#66594,0.25); +#66594 = AXIS2_PLACEMENT_2D('',#66595,#66596); +#66595 = CARTESIAN_POINT('',(0.25,0.57)); +#66596 = DIRECTION('',(0.E+000,1.)); +#66597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66598 = PCURVE('',#52641,#66599); +#66599 = DEFINITIONAL_REPRESENTATION('',(#66600),#66603); +#66600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66601,#66602),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66601 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#66602 = CARTESIAN_POINT('',(1.570796326795,-0.2)); +#66603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66604 = ORIENTED_EDGE('',*,*,#66605,.T.); +#66605 = EDGE_CURVE('',#66583,#66491,#66606,.T.); +#66606 = SURFACE_CURVE('',#66607,(#66611,#66618),.PCURVE_S1.); +#66607 = LINE('',#66608,#66609); +#66608 = CARTESIAN_POINT('',(0.41,1.025,-1.5)); +#66609 = VECTOR('',#66610,1.); +#66610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66611 = PCURVE('',#66424,#66612); +#66612 = DEFINITIONAL_REPRESENTATION('',(#66613),#66617); +#66613 = LINE('',#66614,#66615); +#66614 = CARTESIAN_POINT('',(0.25,0.82)); +#66615 = VECTOR('',#66616,1.); +#66616 = DIRECTION('',(1.,0.E+000)); +#66617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66618 = PCURVE('',#52612,#66619); +#66619 = DEFINITIONAL_REPRESENTATION('',(#66620),#66624); +#66620 = LINE('',#66621,#66622); +#66621 = CARTESIAN_POINT('',(0.4,-0.2)); +#66622 = VECTOR('',#66623,1.); +#66623 = DIRECTION('',(-1.,0.E+000)); +#66624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66625 = ORIENTED_EDGE('',*,*,#66513,.F.); +#66626 = ORIENTED_EDGE('',*,*,#66410,.F.); +#66627 = ADVANCED_FACE('',(#66628),#49165,.F.); +#66628 = FACE_BOUND('',#66629,.F.); +#66629 = EDGE_LOOP('',(#66630,#66657,#66677,#66678)); +#66630 = ORIENTED_EDGE('',*,*,#66631,.F.); +#66631 = EDGE_CURVE('',#66632,#66441,#66634,.T.); +#66632 = VERTEX_POINT('',#66633); +#66633 = CARTESIAN_POINT('',(-0.16,0.725,-1.75)); +#66634 = SURFACE_CURVE('',#66635,(#66640,#66646),.PCURVE_S1.); +#66635 = CIRCLE('',#66636,0.25); +#66636 = AXIS2_PLACEMENT_3D('',#66637,#66638,#66639); +#66637 = CARTESIAN_POINT('',(-0.16,0.725,-1.5)); +#66638 = DIRECTION('',(0.E+000,1.,0.E+000)); +#66639 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66640 = PCURVE('',#49165,#66641); +#66641 = DEFINITIONAL_REPRESENTATION('',(#66642),#66645); +#66642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66643,#66644),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66643 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#66644 = CARTESIAN_POINT('',(3.14159265359,-0.5)); +#66645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66646 = PCURVE('',#66321,#66647); +#66647 = DEFINITIONAL_REPRESENTATION('',(#66648),#66656); +#66648 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#66649,#66650,#66651,#66652 + ,#66653,#66654,#66655),.UNSPECIFIED.,.T.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#66649 = CARTESIAN_POINT('',(0.37,0.25)); +#66650 = CARTESIAN_POINT('',(0.37,-0.183012701892)); +#66651 = CARTESIAN_POINT('',(-5.E-003,3.349364905389E-002)); +#66652 = CARTESIAN_POINT('',(-0.38,0.25)); +#66653 = CARTESIAN_POINT('',(-5.E-003,0.466506350946)); +#66654 = CARTESIAN_POINT('',(0.37,0.683012701892)); +#66655 = CARTESIAN_POINT('',(0.37,0.25)); +#66656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66657 = ORIENTED_EDGE('',*,*,#66658,.T.); +#66658 = EDGE_CURVE('',#66632,#49149,#66659,.T.); +#66659 = SURFACE_CURVE('',#66660,(#66664,#66670),.PCURVE_S1.); +#66660 = LINE('',#66661,#66662); +#66661 = CARTESIAN_POINT('',(-0.16,0.725,-1.75)); +#66662 = VECTOR('',#66663,1.); +#66663 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66664 = PCURVE('',#49165,#66665); +#66665 = DEFINITIONAL_REPRESENTATION('',(#66666),#66669); +#66666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66667,#66668),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); +#66667 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#66668 = CARTESIAN_POINT('',(1.570796326795,-0.58)); +#66669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66670 = PCURVE('',#49192,#66671); +#66671 = DEFINITIONAL_REPRESENTATION('',(#66672),#66676); +#66672 = LINE('',#66673,#66674); +#66673 = CARTESIAN_POINT('',(0.32,-0.5)); +#66674 = VECTOR('',#66675,1.); +#66675 = DIRECTION('',(0.E+000,-1.)); +#66676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66677 = ORIENTED_EDGE('',*,*,#49148,.T.); +#66678 = ORIENTED_EDGE('',*,*,#66463,.F.); +#66679 = ADVANCED_FACE('',(#66680),#52695,.F.); +#66680 = FACE_BOUND('',#66681,.F.); +#66681 = EDGE_LOOP('',(#66682,#66683,#66684,#66685)); +#66682 = ORIENTED_EDGE('',*,*,#66536,.T.); +#66683 = ORIENTED_EDGE('',*,*,#66388,.F.); +#66684 = ORIENTED_EDGE('',*,*,#52680,.F.); +#66685 = ORIENTED_EDGE('',*,*,#66686,.T.); +#66686 = EDGE_CURVE('',#52653,#66537,#66687,.T.); +#66687 = SURFACE_CURVE('',#66688,(#66692,#66698),.PCURVE_S1.); +#66688 = LINE('',#66689,#66690); +#66689 = CARTESIAN_POINT('',(-0.16,1.225,-1.75)); +#66690 = VECTOR('',#66691,1.); +#66691 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66692 = PCURVE('',#52695,#66693); +#66693 = DEFINITIONAL_REPRESENTATION('',(#66694),#66697); +#66694 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66695,#66696),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#66695 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#66696 = CARTESIAN_POINT('',(1.570796326795,-0.2)); +#66697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66698 = PCURVE('',#52668,#66699); +#66699 = DEFINITIONAL_REPRESENTATION('',(#66700),#66704); +#66700 = LINE('',#66701,#66702); +#66701 = CARTESIAN_POINT('',(0.32,0.E+000)); +#66702 = VECTOR('',#66703,1.); +#66703 = DIRECTION('',(0.E+000,-1.)); +#66704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66705 = ADVANCED_FACE('',(#66706),#66321,.T.); +#66706 = FACE_BOUND('',#66707,.F.); +#66707 = EDGE_LOOP('',(#66708,#66709,#66710,#66711,#66734,#66761)); +#66708 = ORIENTED_EDGE('',*,*,#66631,.T.); +#66709 = ORIENTED_EDGE('',*,*,#66440,.T.); +#66710 = ORIENTED_EDGE('',*,*,#66306,.T.); +#66711 = ORIENTED_EDGE('',*,*,#66712,.F.); +#66712 = EDGE_CURVE('',#66713,#66307,#66715,.T.); +#66713 = VERTEX_POINT('',#66714); +#66714 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); +#66715 = SURFACE_CURVE('',#66716,(#66720,#66727),.PCURVE_S1.); +#66716 = LINE('',#66717,#66718); +#66717 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); +#66718 = VECTOR('',#66719,1.); +#66719 = DIRECTION('',(0.E+000,0.E+000,1.)); +#66720 = PCURVE('',#66321,#66721); +#66721 = DEFINITIONAL_REPRESENTATION('',(#66722),#66726); +#66722 = LINE('',#66723,#66724); +#66723 = CARTESIAN_POINT('',(0.12,0.82)); +#66724 = VECTOR('',#66725,1.); +#66725 = DIRECTION('',(-1.,0.E+000)); +#66726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66727 = PCURVE('',#49248,#66728); +#66728 = DEFINITIONAL_REPRESENTATION('',(#66729),#66733); +#66729 = LINE('',#66730,#66731); +#66730 = CARTESIAN_POINT('',(0.4,-0.5)); +#66731 = VECTOR('',#66732,1.); +#66732 = DIRECTION('',(-1.,0.E+000)); +#66733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66734 = ORIENTED_EDGE('',*,*,#66735,.T.); +#66735 = EDGE_CURVE('',#66713,#66736,#66738,.T.); +#66736 = VERTEX_POINT('',#66737); +#66737 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); +#66738 = SURFACE_CURVE('',#66739,(#66744,#66755),.PCURVE_S1.); +#66739 = CIRCLE('',#66740,0.25); +#66740 = AXIS2_PLACEMENT_3D('',#66741,#66742,#66743); +#66741 = CARTESIAN_POINT('',(0.16,0.725,-1.5)); +#66742 = DIRECTION('',(0.E+000,1.,0.E+000)); +#66743 = DIRECTION('',(1.,0.E+000,0.E+000)); +#66744 = PCURVE('',#66321,#66745); +#66745 = DEFINITIONAL_REPRESENTATION('',(#66746),#66754); +#66746 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#66747,#66748,#66749,#66750 + ,#66751,#66752,#66753),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#66747 = CARTESIAN_POINT('',(0.12,0.82)); +#66748 = CARTESIAN_POINT('',(0.553012701892,0.82)); +#66749 = CARTESIAN_POINT('',(0.336506350946,0.445)); +#66750 = CARTESIAN_POINT('',(0.12,7.E-002)); +#66751 = CARTESIAN_POINT('',(-9.650635094611E-002,0.445)); +#66752 = CARTESIAN_POINT('',(-0.313012701892,0.82)); +#66753 = CARTESIAN_POINT('',(0.12,0.82)); +#66754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66755 = PCURVE('',#49221,#66756); +#66756 = DEFINITIONAL_REPRESENTATION('',(#66757),#66760); +#66757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66758,#66759),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#66758 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66759 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#66760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66761 = ORIENTED_EDGE('',*,*,#66762,.T.); +#66762 = EDGE_CURVE('',#66736,#66632,#66763,.T.); +#66763 = SURFACE_CURVE('',#66764,(#66768,#66775),.PCURVE_S1.); +#66764 = LINE('',#66765,#66766); +#66765 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); +#66766 = VECTOR('',#66767,1.); +#66767 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#66768 = PCURVE('',#66321,#66769); +#66769 = DEFINITIONAL_REPRESENTATION('',(#66770),#66774); +#66770 = LINE('',#66771,#66772); +#66771 = CARTESIAN_POINT('',(0.37,0.57)); +#66772 = VECTOR('',#66773,1.); +#66773 = DIRECTION('',(0.E+000,-1.)); +#66774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66775 = PCURVE('',#49192,#66776); +#66776 = DEFINITIONAL_REPRESENTATION('',(#66777),#66781); +#66777 = LINE('',#66778,#66779); +#66778 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66779 = VECTOR('',#66780,1.); +#66780 = DIRECTION('',(1.,0.E+000)); +#66781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66782 = ADVANCED_FACE('',(#66783),#52612,.F.); +#66783 = FACE_BOUND('',#66784,.F.); +#66784 = EDGE_LOOP('',(#66785,#66786,#66787,#66807)); +#66785 = ORIENTED_EDGE('',*,*,#66490,.F.); +#66786 = ORIENTED_EDGE('',*,*,#66605,.F.); +#66787 = ORIENTED_EDGE('',*,*,#66788,.F.); +#66788 = EDGE_CURVE('',#52597,#66583,#66789,.T.); +#66789 = SURFACE_CURVE('',#66790,(#66794,#66801),.PCURVE_S1.); +#66790 = LINE('',#66791,#66792); +#66791 = CARTESIAN_POINT('',(0.41,1.225,-1.5)); +#66792 = VECTOR('',#66793,1.); +#66793 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66794 = PCURVE('',#52612,#66795); +#66795 = DEFINITIONAL_REPRESENTATION('',(#66796),#66800); +#66796 = LINE('',#66797,#66798); +#66797 = CARTESIAN_POINT('',(0.4,0.E+000)); +#66798 = VECTOR('',#66799,1.); +#66799 = DIRECTION('',(0.E+000,-1.)); +#66800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66801 = PCURVE('',#52641,#66802); +#66802 = DEFINITIONAL_REPRESENTATION('',(#66803),#66806); +#66803 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66804,#66805),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#66804 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66805 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#66806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66807 = ORIENTED_EDGE('',*,*,#52596,.F.); +#66808 = ADVANCED_FACE('',(#66809),#49248,.F.); +#66809 = FACE_BOUND('',#66810,.F.); +#66810 = EDGE_LOOP('',(#66811,#66812,#66813,#66814,#66834)); +#66811 = ORIENTED_EDGE('',*,*,#66333,.F.); +#66812 = ORIENTED_EDGE('',*,*,#66227,.T.); +#66813 = ORIENTED_EDGE('',*,*,#49232,.T.); +#66814 = ORIENTED_EDGE('',*,*,#66815,.F.); +#66815 = EDGE_CURVE('',#66713,#49205,#66816,.T.); +#66816 = SURFACE_CURVE('',#66817,(#66821,#66828),.PCURVE_S1.); +#66817 = LINE('',#66818,#66819); +#66818 = CARTESIAN_POINT('',(0.41,0.725,-1.5)); +#66819 = VECTOR('',#66820,1.); +#66820 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66821 = PCURVE('',#49248,#66822); +#66822 = DEFINITIONAL_REPRESENTATION('',(#66823),#66827); +#66823 = LINE('',#66824,#66825); +#66824 = CARTESIAN_POINT('',(0.4,-0.5)); +#66825 = VECTOR('',#66826,1.); +#66826 = DIRECTION('',(0.E+000,-1.)); +#66827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66828 = PCURVE('',#49221,#66829); +#66829 = DEFINITIONAL_REPRESENTATION('',(#66830),#66833); +#66830 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66831,#66832),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); +#66831 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66832 = CARTESIAN_POINT('',(0.E+000,-0.58)); +#66833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66834 = ORIENTED_EDGE('',*,*,#66712,.T.); +#66835 = ADVANCED_FACE('',(#66836),#49221,.F.); +#66836 = FACE_BOUND('',#66837,.F.); +#66837 = EDGE_LOOP('',(#66838,#66839,#66840,#66841)); +#66838 = ORIENTED_EDGE('',*,*,#66735,.F.); +#66839 = ORIENTED_EDGE('',*,*,#66815,.T.); +#66840 = ORIENTED_EDGE('',*,*,#49204,.T.); +#66841 = ORIENTED_EDGE('',*,*,#66842,.F.); +#66842 = EDGE_CURVE('',#66736,#49177,#66843,.T.); +#66843 = SURFACE_CURVE('',#66844,(#66848,#66854),.PCURVE_S1.); +#66844 = LINE('',#66845,#66846); +#66845 = CARTESIAN_POINT('',(0.16,0.725,-1.75)); +#66846 = VECTOR('',#66847,1.); +#66847 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66848 = PCURVE('',#49221,#66849); +#66849 = DEFINITIONAL_REPRESENTATION('',(#66850),#66853); +#66850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66851,#66852),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,8.E-002),.PIECEWISE_BEZIER_KNOTS.); +#66851 = CARTESIAN_POINT('',(1.570796326795,-0.5)); +#66852 = CARTESIAN_POINT('',(1.570796326795,-0.58)); +#66853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66854 = PCURVE('',#49192,#66855); +#66855 = DEFINITIONAL_REPRESENTATION('',(#66856),#66860); +#66856 = LINE('',#66857,#66858); +#66857 = CARTESIAN_POINT('',(0.E+000,-0.5)); +#66858 = VECTOR('',#66859,1.); +#66859 = DIRECTION('',(0.E+000,-1.)); +#66860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66861 = ADVANCED_FACE('',(#66862),#52641,.F.); +#66862 = FACE_BOUND('',#66863,.F.); +#66863 = EDGE_LOOP('',(#66864,#66865,#66885,#66886)); +#66864 = ORIENTED_EDGE('',*,*,#66582,.T.); +#66865 = ORIENTED_EDGE('',*,*,#66866,.F.); +#66866 = EDGE_CURVE('',#52625,#66560,#66867,.T.); +#66867 = SURFACE_CURVE('',#66868,(#66872,#66878),.PCURVE_S1.); +#66868 = LINE('',#66869,#66870); +#66869 = CARTESIAN_POINT('',(0.16,1.225,-1.75)); +#66870 = VECTOR('',#66871,1.); +#66871 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#66872 = PCURVE('',#52641,#66873); +#66873 = DEFINITIONAL_REPRESENTATION('',(#66874),#66877); +#66874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66875,#66876),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#66875 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#66876 = CARTESIAN_POINT('',(1.570796326795,-0.2)); +#66877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66878 = PCURVE('',#52668,#66879); +#66879 = DEFINITIONAL_REPRESENTATION('',(#66880),#66884); +#66880 = LINE('',#66881,#66882); +#66881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66882 = VECTOR('',#66883,1.); +#66883 = DIRECTION('',(0.E+000,-1.)); +#66884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66885 = ORIENTED_EDGE('',*,*,#52624,.F.); +#66886 = ORIENTED_EDGE('',*,*,#66788,.T.); +#66887 = ADVANCED_FACE('',(#66888),#49192,.F.); +#66888 = FACE_BOUND('',#66889,.F.); +#66889 = EDGE_LOOP('',(#66890,#66891,#66892,#66893)); +#66890 = ORIENTED_EDGE('',*,*,#66762,.F.); +#66891 = ORIENTED_EDGE('',*,*,#66842,.T.); +#66892 = ORIENTED_EDGE('',*,*,#49176,.T.); +#66893 = ORIENTED_EDGE('',*,*,#66658,.F.); +#66894 = ADVANCED_FACE('',(#66895),#52668,.F.); +#66895 = FACE_BOUND('',#66896,.F.); +#66896 = EDGE_LOOP('',(#66897,#66898,#66899,#66900)); +#66897 = ORIENTED_EDGE('',*,*,#66559,.T.); +#66898 = ORIENTED_EDGE('',*,*,#66686,.F.); +#66899 = ORIENTED_EDGE('',*,*,#52652,.F.); +#66900 = ORIENTED_EDGE('',*,*,#66866,.T.); +#66901 = ADVANCED_FACE('',(#66902),#54187,.T.); +#66902 = FACE_BOUND('',#66903,.F.); +#66903 = EDGE_LOOP('',(#66904,#66925,#66926,#66927,#66928)); +#66904 = ORIENTED_EDGE('',*,*,#66905,.T.); +#66905 = EDGE_CURVE('',#64264,#54172,#66906,.T.); +#66906 = SURFACE_CURVE('',#66907,(#66911,#66918),.PCURVE_S1.); +#66907 = LINE('',#66908,#66909); +#66908 = CARTESIAN_POINT('',(-1.902820323028,0.175,-2.35)); +#66909 = VECTOR('',#66910,1.); +#66910 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66911 = PCURVE('',#54187,#66912); +#66912 = DEFINITIONAL_REPRESENTATION('',(#66913),#66917); +#66913 = LINE('',#66914,#66915); +#66914 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66915 = VECTOR('',#66916,1.); +#66916 = DIRECTION('',(0.E+000,1.)); +#66917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66918 = PCURVE('',#54215,#66919); +#66919 = DEFINITIONAL_REPRESENTATION('',(#66920),#66924); +#66920 = LINE('',#66921,#66922); +#66921 = CARTESIAN_POINT('',(0.547179676972,0.E+000)); +#66922 = VECTOR('',#66923,1.); +#66923 = DIRECTION('',(0.E+000,1.)); +#66924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66925 = ORIENTED_EDGE('',*,*,#54171,.T.); +#66926 = ORIENTED_EDGE('',*,*,#54684,.F.); +#66927 = ORIENTED_EDGE('',*,*,#65401,.F.); +#66928 = ORIENTED_EDGE('',*,*,#64286,.F.); +#66929 = ADVANCED_FACE('',(#66930),#54215,.T.); +#66930 = FACE_BOUND('',#66931,.F.); +#66931 = EDGE_LOOP('',(#66932,#66952,#66953,#66954)); +#66932 = ORIENTED_EDGE('',*,*,#66933,.T.); +#66933 = EDGE_CURVE('',#64237,#54200,#66934,.T.); +#66934 = SURFACE_CURVE('',#66935,(#66939,#66946),.PCURVE_S1.); +#66935 = LINE('',#66936,#66937); +#66936 = CARTESIAN_POINT('',(-2.45,0.175,-2.35)); +#66937 = VECTOR('',#66938,1.); +#66938 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66939 = PCURVE('',#54215,#66940); +#66940 = DEFINITIONAL_REPRESENTATION('',(#66941),#66945); +#66941 = LINE('',#66942,#66943); +#66942 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66943 = VECTOR('',#66944,1.); +#66944 = DIRECTION('',(0.E+000,1.)); +#66945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66946 = PCURVE('',#54244,#66947); +#66947 = DEFINITIONAL_REPRESENTATION('',(#66948),#66951); +#66948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66949,#66950),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#66949 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#66950 = CARTESIAN_POINT('',(1.570796326795,0.3)); +#66951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66952 = ORIENTED_EDGE('',*,*,#54199,.T.); +#66953 = ORIENTED_EDGE('',*,*,#66905,.F.); +#66954 = ORIENTED_EDGE('',*,*,#64263,.F.); +#66955 = ADVANCED_FACE('',(#66956),#54244,.T.); +#66956 = FACE_BOUND('',#66957,.T.); +#66957 = EDGE_LOOP('',(#66958,#66978,#66979,#66980)); +#66958 = ORIENTED_EDGE('',*,*,#66959,.F.); +#66959 = EDGE_CURVE('',#64209,#54228,#66960,.T.); +#66960 = SURFACE_CURVE('',#66961,(#66965,#66971),.PCURVE_S1.); +#66961 = LINE('',#66962,#66963); +#66962 = CARTESIAN_POINT('',(-3.,-0.375,-2.35)); +#66963 = VECTOR('',#66964,1.); +#66964 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66965 = PCURVE('',#54244,#66966); +#66966 = DEFINITIONAL_REPRESENTATION('',(#66967),#66970); +#66967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66968,#66969),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#66968 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#66969 = CARTESIAN_POINT('',(0.E+000,0.3)); +#66970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66971 = PCURVE('',#54271,#66972); +#66972 = DEFINITIONAL_REPRESENTATION('',(#66973),#66977); +#66973 = LINE('',#66974,#66975); +#66974 = CARTESIAN_POINT('',(0.85,0.E+000)); +#66975 = VECTOR('',#66976,1.); +#66976 = DIRECTION('',(0.E+000,1.)); +#66977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#66978 = ORIENTED_EDGE('',*,*,#64236,.T.); +#66979 = ORIENTED_EDGE('',*,*,#66933,.T.); +#66980 = ORIENTED_EDGE('',*,*,#54227,.F.); +#66981 = ADVANCED_FACE('',(#66982),#54271,.T.); +#66982 = FACE_BOUND('',#66983,.F.); +#66983 = EDGE_LOOP('',(#66984,#66985,#67008,#67028,#67029,#67050,#67051, + #67052)); +#66984 = ORIENTED_EDGE('',*,*,#65530,.F.); +#66985 = ORIENTED_EDGE('',*,*,#66986,.F.); +#66986 = EDGE_CURVE('',#66987,#65503,#66989,.T.); +#66987 = VERTEX_POINT('',#66988); +#66988 = CARTESIAN_POINT('',(-3.,-0.925,-1.95)); +#66989 = SURFACE_CURVE('',#66990,(#66994,#67001),.PCURVE_S1.); +#66990 = LINE('',#66991,#66992); +#66991 = CARTESIAN_POINT('',(-3.,-0.925,-1.95)); +#66992 = VECTOR('',#66993,1.); +#66993 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#66994 = PCURVE('',#54271,#66995); +#66995 = DEFINITIONAL_REPRESENTATION('',(#66996),#67000); +#66996 = LINE('',#66997,#66998); +#66997 = CARTESIAN_POINT('',(0.3,-0.4)); +#66998 = VECTOR('',#66999,1.); +#66999 = DIRECTION('',(0.E+000,1.)); +#67000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67001 = PCURVE('',#65518,#67002); +#67002 = DEFINITIONAL_REPRESENTATION('',(#67003),#67007); +#67003 = LINE('',#67004,#67005); +#67004 = CARTESIAN_POINT('',(-3.,-1.95)); +#67005 = VECTOR('',#67006,1.); +#67006 = DIRECTION('',(0.E+000,-1.)); +#67007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67008 = ORIENTED_EDGE('',*,*,#67009,.F.); +#67009 = EDGE_CURVE('',#65125,#66987,#67010,.T.); +#67010 = SURFACE_CURVE('',#67011,(#67015,#67022),.PCURVE_S1.); +#67011 = LINE('',#67012,#67013); +#67012 = CARTESIAN_POINT('',(-3.,-1.225,-1.95)); +#67013 = VECTOR('',#67014,1.); +#67014 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67015 = PCURVE('',#54271,#67016); +#67016 = DEFINITIONAL_REPRESENTATION('',(#67017),#67021); +#67017 = LINE('',#67018,#67019); +#67018 = CARTESIAN_POINT('',(0.E+000,-0.4)); +#67019 = VECTOR('',#67020,1.); +#67020 = DIRECTION('',(1.,0.E+000)); +#67021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67022 = PCURVE('',#65164,#67023); +#67023 = DEFINITIONAL_REPRESENTATION('',(#67024),#67027); +#67024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67025,#67026),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67025 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#67026 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#67027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67028 = ORIENTED_EDGE('',*,*,#65124,.T.); +#67029 = ORIENTED_EDGE('',*,*,#67030,.F.); +#67030 = EDGE_CURVE('',#54256,#65103,#67031,.T.); +#67031 = SURFACE_CURVE('',#67032,(#67037,#67044),.PCURVE_S1.); +#67032 = CIRCLE('',#67033,0.3); +#67033 = AXIS2_PLACEMENT_3D('',#67034,#67035,#67036); +#67034 = CARTESIAN_POINT('',(-3.,-0.925,-2.35)); +#67035 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#67036 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67037 = PCURVE('',#54271,#67038); +#67038 = DEFINITIONAL_REPRESENTATION('',(#67039),#67043); +#67039 = CIRCLE('',#67040,0.3); +#67040 = AXIS2_PLACEMENT_2D('',#67041,#67042); +#67041 = CARTESIAN_POINT('',(0.3,0.E+000)); +#67042 = DIRECTION('',(0.E+000,1.)); +#67043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67044 = PCURVE('',#54299,#67045); +#67045 = DEFINITIONAL_REPRESENTATION('',(#67046),#67049); +#67046 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67047,#67048),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67047 = CARTESIAN_POINT('',(0.E+000,1.090514631548)); +#67048 = CARTESIAN_POINT('',(1.570796326795,1.090514631548)); +#67049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67050 = ORIENTED_EDGE('',*,*,#54255,.T.); +#67051 = ORIENTED_EDGE('',*,*,#66959,.F.); +#67052 = ORIENTED_EDGE('',*,*,#64206,.F.); +#67053 = ADVANCED_FACE('',(#67054),#64880,.F.); +#67054 = FACE_BOUND('',#67055,.F.); +#67055 = EDGE_LOOP('',(#67056,#67057,#67058,#67081,#67104,#67125)); +#67056 = ORIENTED_EDGE('',*,*,#65425,.F.); +#67057 = ORIENTED_EDGE('',*,*,#64864,.T.); +#67058 = ORIENTED_EDGE('',*,*,#67059,.T.); +#67059 = EDGE_CURVE('',#64838,#67060,#67062,.T.); +#67060 = VERTEX_POINT('',#67061); +#67061 = CARTESIAN_POINT('',(2.8,-0.925,-1.75)); +#67062 = SURFACE_CURVE('',#67063,(#67068,#67075),.PCURVE_S1.); +#67063 = CIRCLE('',#67064,0.2); +#67064 = AXIS2_PLACEMENT_3D('',#67065,#67066,#67067); +#67065 = CARTESIAN_POINT('',(2.8,-0.925,-1.95)); +#67066 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67067 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67068 = PCURVE('',#64880,#67069); +#67069 = DEFINITIONAL_REPRESENTATION('',(#67070),#67074); +#67070 = CIRCLE('',#67071,0.2); +#67071 = AXIS2_PLACEMENT_2D('',#67072,#67073); +#67072 = CARTESIAN_POINT('',(2.8,-1.95)); +#67073 = DIRECTION('',(1.,0.E+000)); +#67074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67075 = PCURVE('',#64853,#67076); +#67076 = DEFINITIONAL_REPRESENTATION('',(#67077),#67080); +#67077 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67078,#67079),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67078 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#67079 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67081 = ORIENTED_EDGE('',*,*,#67082,.T.); +#67082 = EDGE_CURVE('',#67060,#67083,#67085,.T.); +#67083 = VERTEX_POINT('',#67084); +#67084 = CARTESIAN_POINT('',(2.125,-0.925,-1.75)); +#67085 = SURFACE_CURVE('',#67086,(#67090,#67097),.PCURVE_S1.); +#67086 = LINE('',#67087,#67088); +#67087 = CARTESIAN_POINT('',(2.8,-0.925,-1.75)); +#67088 = VECTOR('',#67089,1.); +#67089 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#67090 = PCURVE('',#64880,#67091); +#67091 = DEFINITIONAL_REPRESENTATION('',(#67092),#67096); +#67092 = LINE('',#67093,#67094); +#67093 = CARTESIAN_POINT('',(2.8,-1.75)); +#67094 = VECTOR('',#67095,1.); +#67095 = DIRECTION('',(-1.,0.E+000)); +#67096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67097 = PCURVE('',#65036,#67098); +#67098 = DEFINITIONAL_REPRESENTATION('',(#67099),#67103); +#67099 = LINE('',#67100,#67101); +#67100 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#67101 = VECTOR('',#67102,1.); +#67102 = DIRECTION('',(1.,0.E+000)); +#67103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67104 = ORIENTED_EDGE('',*,*,#67105,.T.); +#67105 = EDGE_CURVE('',#67083,#65256,#67106,.T.); +#67106 = SURFACE_CURVE('',#67107,(#67112,#67119),.PCURVE_S1.); +#67107 = CIRCLE('',#67108,0.2); +#67108 = AXIS2_PLACEMENT_3D('',#67109,#67110,#67111); +#67109 = CARTESIAN_POINT('',(2.125,-0.925,-1.95)); +#67110 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67111 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67112 = PCURVE('',#64880,#67113); +#67113 = DEFINITIONAL_REPRESENTATION('',(#67114),#67118); +#67114 = CIRCLE('',#67115,0.2); +#67115 = AXIS2_PLACEMENT_2D('',#67116,#67117); +#67116 = CARTESIAN_POINT('',(2.125,-1.95)); +#67117 = DIRECTION('',(0.E+000,1.)); +#67118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67119 = PCURVE('',#65009,#67120); +#67120 = DEFINITIONAL_REPRESENTATION('',(#67121),#67124); +#67121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67122,#67123),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67122 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67123 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#67124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67125 = ORIENTED_EDGE('',*,*,#65255,.T.); +#67126 = ADVANCED_FACE('',(#67127),#65518,.F.); +#67127 = FACE_BOUND('',#67128,.F.); +#67128 = EDGE_LOOP('',(#67129,#67130,#67153,#67176,#67199,#67220)); +#67129 = ORIENTED_EDGE('',*,*,#65500,.F.); +#67130 = ORIENTED_EDGE('',*,*,#67131,.T.); +#67131 = EDGE_CURVE('',#65501,#67132,#67134,.T.); +#67132 = VERTEX_POINT('',#67133); +#67133 = CARTESIAN_POINT('',(-1.925,-0.925,-1.95)); +#67134 = SURFACE_CURVE('',#67135,(#67139,#67146),.PCURVE_S1.); +#67135 = LINE('',#67136,#67137); +#67136 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); +#67137 = VECTOR('',#67138,1.); +#67138 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67139 = PCURVE('',#65518,#67140); +#67140 = DEFINITIONAL_REPRESENTATION('',(#67141),#67145); +#67141 = LINE('',#67142,#67143); +#67142 = CARTESIAN_POINT('',(-1.925,-2.35)); +#67143 = VECTOR('',#67144,1.); +#67144 = DIRECTION('',(0.E+000,1.)); +#67145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67146 = PCURVE('',#54326,#67147); +#67147 = DEFINITIONAL_REPRESENTATION('',(#67148),#67152); +#67148 = LINE('',#67149,#67150); +#67149 = CARTESIAN_POINT('',(0.2,0.E+000)); +#67150 = VECTOR('',#67151,1.); +#67151 = DIRECTION('',(0.E+000,-1.)); +#67152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67153 = ORIENTED_EDGE('',*,*,#67154,.T.); +#67154 = EDGE_CURVE('',#67132,#67155,#67157,.T.); +#67155 = VERTEX_POINT('',#67156); +#67156 = CARTESIAN_POINT('',(-2.125,-0.925,-1.75)); +#67157 = SURFACE_CURVE('',#67158,(#67163,#67170),.PCURVE_S1.); +#67158 = CIRCLE('',#67159,0.2); +#67159 = AXIS2_PLACEMENT_3D('',#67160,#67161,#67162); +#67160 = CARTESIAN_POINT('',(-2.125,-0.925,-1.95)); +#67161 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67162 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67163 = PCURVE('',#65518,#67164); +#67164 = DEFINITIONAL_REPRESENTATION('',(#67165),#67169); +#67165 = CIRCLE('',#67166,0.2); +#67166 = AXIS2_PLACEMENT_2D('',#67167,#67168); +#67167 = CARTESIAN_POINT('',(-2.125,-1.95)); +#67168 = DIRECTION('',(1.,0.E+000)); +#67169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67170 = PCURVE('',#65218,#67171); +#67171 = DEFINITIONAL_REPRESENTATION('',(#67172),#67175); +#67172 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67173,#67174),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67173 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#67174 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67176 = ORIENTED_EDGE('',*,*,#67177,.T.); +#67177 = EDGE_CURVE('',#67155,#67178,#67180,.T.); +#67178 = VERTEX_POINT('',#67179); +#67179 = CARTESIAN_POINT('',(-2.8,-0.925,-1.75)); +#67180 = SURFACE_CURVE('',#67181,(#67185,#67192),.PCURVE_S1.); +#67181 = LINE('',#67182,#67183); +#67182 = CARTESIAN_POINT('',(-2.125,-0.925,-1.75)); +#67183 = VECTOR('',#67184,1.); +#67184 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#67185 = PCURVE('',#65518,#67186); +#67186 = DEFINITIONAL_REPRESENTATION('',(#67187),#67191); +#67187 = LINE('',#67188,#67189); +#67188 = CARTESIAN_POINT('',(-2.125,-1.75)); +#67189 = VECTOR('',#67190,1.); +#67190 = DIRECTION('',(-1.,0.E+000)); +#67191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67192 = PCURVE('',#65191,#67193); +#67193 = DEFINITIONAL_REPRESENTATION('',(#67194),#67198); +#67194 = LINE('',#67195,#67196); +#67195 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#67196 = VECTOR('',#67197,1.); +#67197 = DIRECTION('',(1.,0.E+000)); +#67198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67199 = ORIENTED_EDGE('',*,*,#67200,.T.); +#67200 = EDGE_CURVE('',#67178,#66987,#67201,.T.); +#67201 = SURFACE_CURVE('',#67202,(#67207,#67214),.PCURVE_S1.); +#67202 = CIRCLE('',#67203,0.2); +#67203 = AXIS2_PLACEMENT_3D('',#67204,#67205,#67206); +#67204 = CARTESIAN_POINT('',(-2.8,-0.925,-1.95)); +#67205 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67206 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67207 = PCURVE('',#65518,#67208); +#67208 = DEFINITIONAL_REPRESENTATION('',(#67209),#67213); +#67209 = CIRCLE('',#67210,0.2); +#67210 = AXIS2_PLACEMENT_2D('',#67211,#67212); +#67211 = CARTESIAN_POINT('',(-2.8,-1.95)); +#67212 = DIRECTION('',(0.E+000,1.)); +#67213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67214 = PCURVE('',#65164,#67215); +#67215 = DEFINITIONAL_REPRESENTATION('',(#67216),#67219); +#67216 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67217,#67218),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67217 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67218 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#67219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67220 = ORIENTED_EDGE('',*,*,#66986,.T.); +#67221 = ADVANCED_FACE('',(#67222),#64853,.T.); +#67222 = FACE_BOUND('',#67223,.T.); +#67223 = EDGE_LOOP('',(#67224,#67225,#67226,#67227)); +#67224 = ORIENTED_EDGE('',*,*,#65048,.F.); +#67225 = ORIENTED_EDGE('',*,*,#64837,.T.); +#67226 = ORIENTED_EDGE('',*,*,#67059,.T.); +#67227 = ORIENTED_EDGE('',*,*,#67228,.F.); +#67228 = EDGE_CURVE('',#65021,#67060,#67229,.T.); +#67229 = SURFACE_CURVE('',#67230,(#67234,#67240),.PCURVE_S1.); +#67230 = LINE('',#67231,#67232); +#67231 = CARTESIAN_POINT('',(2.8,-1.225,-1.75)); +#67232 = VECTOR('',#67233,1.); +#67233 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67234 = PCURVE('',#64853,#67235); +#67235 = DEFINITIONAL_REPRESENTATION('',(#67236),#67239); +#67236 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67237,#67238),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67237 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#67238 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67240 = PCURVE('',#65036,#67241); +#67241 = DEFINITIONAL_REPRESENTATION('',(#67242),#67246); +#67242 = LINE('',#67243,#67244); +#67243 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67244 = VECTOR('',#67245,1.); +#67245 = DIRECTION('',(0.E+000,-1.)); +#67246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67247 = ADVANCED_FACE('',(#67248),#65036,.T.); +#67248 = FACE_BOUND('',#67249,.F.); +#67249 = EDGE_LOOP('',(#67250,#67251,#67271,#67272)); +#67250 = ORIENTED_EDGE('',*,*,#65020,.T.); +#67251 = ORIENTED_EDGE('',*,*,#67252,.T.); +#67252 = EDGE_CURVE('',#64993,#67083,#67253,.T.); +#67253 = SURFACE_CURVE('',#67254,(#67258,#67265),.PCURVE_S1.); +#67254 = LINE('',#67255,#67256); +#67255 = CARTESIAN_POINT('',(2.125,-1.225,-1.75)); +#67256 = VECTOR('',#67257,1.); +#67257 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67258 = PCURVE('',#65036,#67259); +#67259 = DEFINITIONAL_REPRESENTATION('',(#67260),#67264); +#67260 = LINE('',#67261,#67262); +#67261 = CARTESIAN_POINT('',(0.675,0.E+000)); +#67262 = VECTOR('',#67263,1.); +#67263 = DIRECTION('',(0.E+000,-1.)); +#67264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67265 = PCURVE('',#65009,#67266); +#67266 = DEFINITIONAL_REPRESENTATION('',(#67267),#67270); +#67267 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67268,#67269),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67268 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#67269 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67271 = ORIENTED_EDGE('',*,*,#67082,.F.); +#67272 = ORIENTED_EDGE('',*,*,#67228,.F.); +#67273 = ADVANCED_FACE('',(#67274),#65009,.T.); +#67274 = FACE_BOUND('',#67275,.T.); +#67275 = EDGE_LOOP('',(#67276,#67277,#67278,#67279)); +#67276 = ORIENTED_EDGE('',*,*,#64992,.F.); +#67277 = ORIENTED_EDGE('',*,*,#67252,.T.); +#67278 = ORIENTED_EDGE('',*,*,#67105,.T.); +#67279 = ORIENTED_EDGE('',*,*,#65278,.F.); +#67280 = ADVANCED_FACE('',(#67281),#54326,.T.); +#67281 = FACE_BOUND('',#67282,.F.); +#67282 = EDGE_LOOP('',(#67283,#67304,#67305,#67325,#67326,#67327,#67328, + #67349)); +#67283 = ORIENTED_EDGE('',*,*,#67284,.F.); +#67284 = EDGE_CURVE('',#65073,#54284,#67285,.T.); +#67285 = SURFACE_CURVE('',#67286,(#67291,#67298),.PCURVE_S1.); +#67286 = CIRCLE('',#67287,0.3); +#67287 = AXIS2_PLACEMENT_3D('',#67288,#67289,#67290); +#67288 = CARTESIAN_POINT('',(-1.925,-0.925,-2.35)); +#67289 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67290 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67291 = PCURVE('',#54326,#67292); +#67292 = DEFINITIONAL_REPRESENTATION('',(#67293),#67297); +#67293 = CIRCLE('',#67294,0.3); +#67294 = AXIS2_PLACEMENT_2D('',#67295,#67296); +#67295 = CARTESIAN_POINT('',(0.2,0.E+000)); +#67296 = DIRECTION('',(1.,0.E+000)); +#67297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67298 = PCURVE('',#54299,#67299); +#67299 = DEFINITIONAL_REPRESENTATION('',(#67300),#67303); +#67300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67301,#67302),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#67301 = CARTESIAN_POINT('',(1.570796326795,1.5514631548E-002)); +#67302 = CARTESIAN_POINT('',(0.E+000,1.5514631548E-002)); +#67303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67304 = ORIENTED_EDGE('',*,*,#65072,.T.); +#67305 = ORIENTED_EDGE('',*,*,#67306,.T.); +#67306 = EDGE_CURVE('',#65075,#67132,#67307,.T.); +#67307 = SURFACE_CURVE('',#67308,(#67312,#67319),.PCURVE_S1.); +#67308 = LINE('',#67309,#67310); +#67309 = CARTESIAN_POINT('',(-1.925,-1.225,-1.95)); +#67310 = VECTOR('',#67311,1.); +#67311 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67312 = PCURVE('',#54326,#67313); +#67313 = DEFINITIONAL_REPRESENTATION('',(#67314),#67318); +#67314 = LINE('',#67315,#67316); +#67315 = CARTESIAN_POINT('',(0.5,-0.4)); +#67316 = VECTOR('',#67317,1.); +#67317 = DIRECTION('',(-1.,0.E+000)); +#67318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67319 = PCURVE('',#65218,#67320); +#67320 = DEFINITIONAL_REPRESENTATION('',(#67321),#67324); +#67321 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67322,#67323),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67323 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#67324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67325 = ORIENTED_EDGE('',*,*,#67131,.F.); +#67326 = ORIENTED_EDGE('',*,*,#65600,.F.); +#67327 = ORIENTED_EDGE('',*,*,#64525,.T.); +#67328 = ORIENTED_EDGE('',*,*,#67329,.T.); +#67329 = EDGE_CURVE('',#64503,#54311,#67330,.T.); +#67330 = SURFACE_CURVE('',#67331,(#67335,#67342),.PCURVE_S1.); +#67331 = LINE('',#67332,#67333); +#67332 = CARTESIAN_POINT('',(-1.925,-0.725,-2.35)); +#67333 = VECTOR('',#67334,1.); +#67334 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67335 = PCURVE('',#54326,#67336); +#67336 = DEFINITIONAL_REPRESENTATION('',(#67337),#67341); +#67337 = LINE('',#67338,#67339); +#67338 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67339 = VECTOR('',#67340,1.); +#67340 = DIRECTION('',(0.E+000,1.)); +#67341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67342 = PCURVE('',#54354,#67343); +#67343 = DEFINITIONAL_REPRESENTATION('',(#67344),#67348); +#67344 = LINE('',#67345,#67346); +#67345 = CARTESIAN_POINT('',(3.85,0.E+000)); +#67346 = VECTOR('',#67347,1.); +#67347 = DIRECTION('',(0.E+000,1.)); +#67348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67349 = ORIENTED_EDGE('',*,*,#54310,.T.); +#67350 = ADVANCED_FACE('',(#67351),#54299,.T.); +#67351 = FACE_BOUND('',#67352,.T.); +#67352 = EDGE_LOOP('',(#67353,#67354,#67355,#67356)); +#67353 = ORIENTED_EDGE('',*,*,#65102,.T.); +#67354 = ORIENTED_EDGE('',*,*,#67030,.F.); +#67355 = ORIENTED_EDGE('',*,*,#54283,.F.); +#67356 = ORIENTED_EDGE('',*,*,#67284,.F.); +#67357 = ADVANCED_FACE('',(#67358),#65218,.T.); +#67358 = FACE_BOUND('',#67359,.T.); +#67359 = EDGE_LOOP('',(#67360,#67361,#67362,#67363)); +#67360 = ORIENTED_EDGE('',*,*,#65203,.F.); +#67361 = ORIENTED_EDGE('',*,*,#67306,.T.); +#67362 = ORIENTED_EDGE('',*,*,#67154,.T.); +#67363 = ORIENTED_EDGE('',*,*,#67364,.F.); +#67364 = EDGE_CURVE('',#65176,#67155,#67365,.T.); +#67365 = SURFACE_CURVE('',#67366,(#67370,#67376),.PCURVE_S1.); +#67366 = LINE('',#67367,#67368); +#67367 = CARTESIAN_POINT('',(-2.125,-1.225,-1.75)); +#67368 = VECTOR('',#67369,1.); +#67369 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67370 = PCURVE('',#65218,#67371); +#67371 = DEFINITIONAL_REPRESENTATION('',(#67372),#67375); +#67372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67373,#67374),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67373 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#67374 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67376 = PCURVE('',#65191,#67377); +#67377 = DEFINITIONAL_REPRESENTATION('',(#67378),#67382); +#67378 = LINE('',#67379,#67380); +#67379 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67380 = VECTOR('',#67381,1.); +#67381 = DIRECTION('',(0.E+000,-1.)); +#67382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67383 = ADVANCED_FACE('',(#67384),#65191,.T.); +#67384 = FACE_BOUND('',#67385,.F.); +#67385 = EDGE_LOOP('',(#67386,#67387,#67407,#67408)); +#67386 = ORIENTED_EDGE('',*,*,#65175,.T.); +#67387 = ORIENTED_EDGE('',*,*,#67388,.T.); +#67388 = EDGE_CURVE('',#65148,#67178,#67389,.T.); +#67389 = SURFACE_CURVE('',#67390,(#67394,#67401),.PCURVE_S1.); +#67390 = LINE('',#67391,#67392); +#67391 = CARTESIAN_POINT('',(-2.8,-1.225,-1.75)); +#67392 = VECTOR('',#67393,1.); +#67393 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67394 = PCURVE('',#65191,#67395); +#67395 = DEFINITIONAL_REPRESENTATION('',(#67396),#67400); +#67396 = LINE('',#67397,#67398); +#67397 = CARTESIAN_POINT('',(0.675,0.E+000)); +#67398 = VECTOR('',#67399,1.); +#67399 = DIRECTION('',(0.E+000,-1.)); +#67400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67401 = PCURVE('',#65164,#67402); +#67402 = DEFINITIONAL_REPRESENTATION('',(#67403),#67406); +#67403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67404,#67405),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#67404 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#67405 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#67406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67407 = ORIENTED_EDGE('',*,*,#67177,.F.); +#67408 = ORIENTED_EDGE('',*,*,#67364,.F.); +#67409 = ADVANCED_FACE('',(#67410),#65164,.T.); +#67410 = FACE_BOUND('',#67411,.T.); +#67411 = EDGE_LOOP('',(#67412,#67413,#67414,#67415)); +#67412 = ORIENTED_EDGE('',*,*,#65147,.F.); +#67413 = ORIENTED_EDGE('',*,*,#67388,.T.); +#67414 = ORIENTED_EDGE('',*,*,#67200,.T.); +#67415 = ORIENTED_EDGE('',*,*,#67009,.F.); +#67416 = ADVANCED_FACE('',(#67417),#54354,.T.); +#67417 = FACE_BOUND('',#67418,.F.); +#67418 = EDGE_LOOP('',(#67419,#67420,#67421,#67422)); +#67419 = ORIENTED_EDGE('',*,*,#65301,.T.); +#67420 = ORIENTED_EDGE('',*,*,#54338,.T.); +#67421 = ORIENTED_EDGE('',*,*,#67329,.F.); +#67422 = ORIENTED_EDGE('',*,*,#64502,.F.); +#67423 = ADVANCED_FACE('',(#67424),#64563,.T.); +#67424 = FACE_BOUND('',#67425,.F.); +#67425 = EDGE_LOOP('',(#67426,#67449,#67477,#67498)); +#67426 = ORIENTED_EDGE('',*,*,#67427,.F.); +#67427 = EDGE_CURVE('',#67428,#62845,#67430,.T.); +#67428 = VERTEX_POINT('',#67429); +#67429 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); +#67430 = SURFACE_CURVE('',#67431,(#67435,#67442),.PCURVE_S1.); +#67431 = LINE('',#67432,#67433); +#67432 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); +#67433 = VECTOR('',#67434,1.); +#67434 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67435 = PCURVE('',#64563,#67436); +#67436 = DEFINITIONAL_REPRESENTATION('',(#67437),#67441); +#67437 = LINE('',#67438,#67439); +#67438 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67439 = VECTOR('',#67440,1.); +#67440 = DIRECTION('',(1.,0.E+000)); +#67441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67442 = PCURVE('',#62860,#67443); +#67443 = DEFINITIONAL_REPRESENTATION('',(#67444),#67448); +#67444 = LINE('',#67445,#67446); +#67445 = CARTESIAN_POINT('',(2.65,-1.105)); +#67446 = VECTOR('',#67447,1.); +#67447 = DIRECTION('',(-1.,0.E+000)); +#67448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67449 = ORIENTED_EDGE('',*,*,#67450,.T.); +#67450 = EDGE_CURVE('',#67428,#67451,#67453,.T.); +#67451 = VERTEX_POINT('',#67452); +#67452 = CARTESIAN_POINT('',(-1.175,-1.105,-2.65)); +#67453 = SURFACE_CURVE('',#67454,(#67458,#67465),.PCURVE_S1.); +#67454 = LINE('',#67455,#67456); +#67455 = CARTESIAN_POINT('',(-1.425,-1.105,-2.65)); +#67456 = VECTOR('',#67457,1.); +#67457 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67458 = PCURVE('',#64563,#67459); +#67459 = DEFINITIONAL_REPRESENTATION('',(#67460),#67464); +#67460 = LINE('',#67461,#67462); +#67461 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67462 = VECTOR('',#67463,1.); +#67463 = DIRECTION('',(0.E+000,1.)); +#67464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67465 = PCURVE('',#67466,#67471); +#67466 = PLANE('',#67467); +#67467 = AXIS2_PLACEMENT_3D('',#67468,#67469,#67470); +#67468 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); +#67469 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67470 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67471 = DEFINITIONAL_REPRESENTATION('',(#67472),#67476); +#67472 = LINE('',#67473,#67474); +#67473 = CARTESIAN_POINT('',(0.15,0.E+000)); +#67474 = VECTOR('',#67475,1.); +#67475 = DIRECTION('',(0.E+000,1.)); +#67476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67477 = ORIENTED_EDGE('',*,*,#67478,.T.); +#67478 = EDGE_CURVE('',#67451,#63001,#67479,.T.); +#67479 = SURFACE_CURVE('',#67480,(#67484,#67491),.PCURVE_S1.); +#67480 = LINE('',#67481,#67482); +#67481 = CARTESIAN_POINT('',(-1.175,-1.105,-2.65)); +#67482 = VECTOR('',#67483,1.); +#67483 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67484 = PCURVE('',#64563,#67485); +#67485 = DEFINITIONAL_REPRESENTATION('',(#67486),#67490); +#67486 = LINE('',#67487,#67488); +#67487 = CARTESIAN_POINT('',(0.E+000,0.25)); +#67488 = VECTOR('',#67489,1.); +#67489 = DIRECTION('',(1.,0.E+000)); +#67490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67491 = PCURVE('',#63039,#67492); +#67492 = DEFINITIONAL_REPRESENTATION('',(#67493),#67497); +#67493 = LINE('',#67494,#67495); +#67494 = CARTESIAN_POINT('',(2.65,-1.105)); +#67495 = VECTOR('',#67496,1.); +#67496 = DIRECTION('',(-1.,0.E+000)); +#67497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67498 = ORIENTED_EDGE('',*,*,#64549,.F.); +#67499 = ADVANCED_FACE('',(#67500),#62860,.F.); +#67500 = FACE_BOUND('',#67501,.F.); +#67501 = EDGE_LOOP('',(#67502,#67503,#67504,#67527,#67555,#67583)); +#67502 = ORIENTED_EDGE('',*,*,#67427,.T.); +#67503 = ORIENTED_EDGE('',*,*,#62844,.F.); +#67504 = ORIENTED_EDGE('',*,*,#67505,.T.); +#67505 = EDGE_CURVE('',#62817,#67506,#67508,.T.); +#67506 = VERTEX_POINT('',#67507); +#67507 = CARTESIAN_POINT('',(-1.425,-1.18088190451,-1.902486398125)); +#67508 = SURFACE_CURVE('',#67509,(#67513,#67520),.PCURVE_S1.); +#67509 = LINE('',#67510,#67511); +#67510 = CARTESIAN_POINT('',(-1.425,-1.105,-1.882153903092)); +#67511 = VECTOR('',#67512,1.); +#67512 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#67513 = PCURVE('',#62860,#67514); +#67514 = DEFINITIONAL_REPRESENTATION('',(#67515),#67519); +#67515 = LINE('',#67516,#67517); +#67516 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#67517 = VECTOR('',#67518,1.); +#67518 = DIRECTION('',(0.258819045102,-0.965925826289)); +#67519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67520 = PCURVE('',#62567,#67521); +#67521 = DEFINITIONAL_REPRESENTATION('',(#67522),#67526); +#67522 = LINE('',#67523,#67524); +#67523 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#67524 = VECTOR('',#67525,1.); +#67525 = DIRECTION('',(1.,0.E+000)); +#67526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67527 = ORIENTED_EDGE('',*,*,#67528,.T.); +#67528 = EDGE_CURVE('',#67506,#67529,#67531,.T.); +#67529 = VERTEX_POINT('',#67530); +#67530 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); +#67531 = SURFACE_CURVE('',#67532,(#67537,#67544),.PCURVE_S1.); +#67532 = CIRCLE('',#67533,0.1); +#67533 = AXIS2_PLACEMENT_3D('',#67534,#67535,#67536); +#67534 = CARTESIAN_POINT('',(-1.425,-1.155,-1.999078980754)); +#67535 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67536 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#67537 = PCURVE('',#62860,#67538); +#67538 = DEFINITIONAL_REPRESENTATION('',(#67539),#67543); +#67539 = CIRCLE('',#67540,0.1); +#67540 = AXIS2_PLACEMENT_2D('',#67541,#67542); +#67541 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#67542 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#67543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67544 = PCURVE('',#67545,#67550); +#67545 = CYLINDRICAL_SURFACE('',#67546,0.1); +#67546 = AXIS2_PLACEMENT_3D('',#67547,#67548,#67549); +#67547 = CARTESIAN_POINT('',(-1.425,-1.155,-1.999078980754)); +#67548 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67549 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67550 = DEFINITIONAL_REPRESENTATION('',(#67551),#67554); +#67551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67552,#67553),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#67552 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); +#67553 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#67554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67555 = ORIENTED_EDGE('',*,*,#67556,.T.); +#67556 = EDGE_CURVE('',#67529,#67557,#67559,.T.); +#67557 = VERTEX_POINT('',#67558); +#67558 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); +#67559 = SURFACE_CURVE('',#67560,(#67564,#67571),.PCURVE_S1.); +#67560 = LINE('',#67561,#67562); +#67561 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); +#67562 = VECTOR('',#67563,1.); +#67563 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67564 = PCURVE('',#62860,#67565); +#67565 = DEFINITIONAL_REPRESENTATION('',(#67566),#67570); +#67566 = LINE('',#67567,#67568); +#67567 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#67568 = VECTOR('',#67569,1.); +#67569 = DIRECTION('',(1.,0.E+000)); +#67570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67571 = PCURVE('',#67572,#67577); +#67572 = PLANE('',#67573); +#67573 = AXIS2_PLACEMENT_3D('',#67574,#67575,#67576); +#67574 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); +#67575 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67576 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67577 = DEFINITIONAL_REPRESENTATION('',(#67578),#67582); +#67578 = LINE('',#67579,#67580); +#67579 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67580 = VECTOR('',#67581,1.); +#67581 = DIRECTION('',(1.,0.E+000)); +#67582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67583 = ORIENTED_EDGE('',*,*,#67584,.T.); +#67584 = EDGE_CURVE('',#67557,#67428,#67585,.T.); +#67585 = SURFACE_CURVE('',#67586,(#67590,#67597),.PCURVE_S1.); +#67586 = LINE('',#67587,#67588); +#67587 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); +#67588 = VECTOR('',#67589,1.); +#67589 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67590 = PCURVE('',#62860,#67591); +#67591 = DEFINITIONAL_REPRESENTATION('',(#67592),#67596); +#67592 = LINE('',#67593,#67594); +#67593 = CARTESIAN_POINT('',(2.65,-1.255)); +#67594 = VECTOR('',#67595,1.); +#67595 = DIRECTION('',(0.E+000,1.)); +#67596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67597 = PCURVE('',#67466,#67598); +#67598 = DEFINITIONAL_REPRESENTATION('',(#67599),#67603); +#67599 = LINE('',#67600,#67601); +#67600 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67601 = VECTOR('',#67602,1.); +#67602 = DIRECTION('',(1.,0.E+000)); +#67603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67604 = ADVANCED_FACE('',(#67605),#62567,.T.); +#67605 = FACE_BOUND('',#67606,.F.); +#67606 = EDGE_LOOP('',(#67607,#67608,#67629,#67652,#67672,#67673)); +#67607 = ORIENTED_EDGE('',*,*,#62551,.T.); +#67608 = ORIENTED_EDGE('',*,*,#67609,.F.); +#67609 = EDGE_CURVE('',#63024,#62524,#67610,.T.); +#67610 = SURFACE_CURVE('',#67611,(#67615,#67622),.PCURVE_S1.); +#67611 = LINE('',#67612,#67613); +#67612 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); +#67613 = VECTOR('',#67614,1.); +#67614 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#67615 = PCURVE('',#62567,#67616); +#67616 = DEFINITIONAL_REPRESENTATION('',(#67617),#67621); +#67617 = LINE('',#67618,#67619); +#67618 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#67619 = VECTOR('',#67620,1.); +#67620 = DIRECTION('',(-1.,0.E+000)); +#67621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67622 = PCURVE('',#62539,#67623); +#67623 = DEFINITIONAL_REPRESENTATION('',(#67624),#67628); +#67624 = LINE('',#67625,#67626); +#67625 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#67626 = VECTOR('',#67627,1.); +#67627 = DIRECTION('',(-0.258819045102,0.965925826289)); +#67628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67629 = ORIENTED_EDGE('',*,*,#67630,.T.); +#67630 = EDGE_CURVE('',#63024,#67631,#67633,.T.); +#67631 = VERTEX_POINT('',#67632); +#67632 = CARTESIAN_POINT('',(-1.175,-1.18088190451,-1.902486398125)); +#67633 = SURFACE_CURVE('',#67634,(#67638,#67645),.PCURVE_S1.); +#67634 = LINE('',#67635,#67636); +#67635 = CARTESIAN_POINT('',(-1.175,-1.105,-1.882153903092)); +#67636 = VECTOR('',#67637,1.); +#67637 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#67638 = PCURVE('',#62567,#67639); +#67639 = DEFINITIONAL_REPRESENTATION('',(#67640),#67644); +#67640 = LINE('',#67641,#67642); +#67641 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#67642 = VECTOR('',#67643,1.); +#67643 = DIRECTION('',(1.,0.E+000)); +#67644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67645 = PCURVE('',#63039,#67646); +#67646 = DEFINITIONAL_REPRESENTATION('',(#67647),#67651); +#67647 = LINE('',#67648,#67649); +#67648 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#67649 = VECTOR('',#67650,1.); +#67650 = DIRECTION('',(0.258819045102,-0.965925826289)); +#67651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67652 = ORIENTED_EDGE('',*,*,#67653,.F.); +#67653 = EDGE_CURVE('',#67506,#67631,#67654,.T.); +#67654 = SURFACE_CURVE('',#67655,(#67659,#67666),.PCURVE_S1.); +#67655 = LINE('',#67656,#67657); +#67656 = CARTESIAN_POINT('',(-1.425,-1.18088190451,-1.902486398125)); +#67657 = VECTOR('',#67658,1.); +#67658 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67659 = PCURVE('',#62567,#67660); +#67660 = DEFINITIONAL_REPRESENTATION('',(#67661),#67665); +#67661 = LINE('',#67662,#67663); +#67662 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); +#67663 = VECTOR('',#67664,1.); +#67664 = DIRECTION('',(0.E+000,1.)); +#67665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67666 = PCURVE('',#67545,#67667); +#67667 = DEFINITIONAL_REPRESENTATION('',(#67668),#67671); +#67668 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67669,#67670),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#67669 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); +#67670 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#67671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67672 = ORIENTED_EDGE('',*,*,#67505,.F.); +#67673 = ORIENTED_EDGE('',*,*,#63659,.T.); +#67674 = ADVANCED_FACE('',(#67675),#62539,.F.); +#67675 = FACE_BOUND('',#67676,.F.); +#67676 = EDGE_LOOP('',(#67677,#67678,#67679,#67680)); +#67677 = ORIENTED_EDGE('',*,*,#63051,.T.); +#67678 = ORIENTED_EDGE('',*,*,#67609,.T.); +#67679 = ORIENTED_EDGE('',*,*,#62523,.T.); +#67680 = ORIENTED_EDGE('',*,*,#63732,.T.); +#67681 = ADVANCED_FACE('',(#67682),#63039,.T.); +#67682 = FACE_BOUND('',#67683,.F.); +#67683 = EDGE_LOOP('',(#67684,#67685,#67708,#67731,#67752,#67753)); +#67684 = ORIENTED_EDGE('',*,*,#67478,.F.); +#67685 = ORIENTED_EDGE('',*,*,#67686,.F.); +#67686 = EDGE_CURVE('',#67687,#67451,#67689,.T.); +#67687 = VERTEX_POINT('',#67688); +#67688 = CARTESIAN_POINT('',(-1.175,-1.255,-2.65)); +#67689 = SURFACE_CURVE('',#67690,(#67694,#67701),.PCURVE_S1.); +#67690 = LINE('',#67691,#67692); +#67691 = CARTESIAN_POINT('',(-1.175,-1.255,-2.65)); +#67692 = VECTOR('',#67693,1.); +#67693 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67694 = PCURVE('',#63039,#67695); +#67695 = DEFINITIONAL_REPRESENTATION('',(#67696),#67700); +#67696 = LINE('',#67697,#67698); +#67697 = CARTESIAN_POINT('',(2.65,-1.255)); +#67698 = VECTOR('',#67699,1.); +#67699 = DIRECTION('',(0.E+000,1.)); +#67700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67701 = PCURVE('',#67466,#67702); +#67702 = DEFINITIONAL_REPRESENTATION('',(#67703),#67707); +#67703 = LINE('',#67704,#67705); +#67704 = CARTESIAN_POINT('',(0.E+000,0.25)); +#67705 = VECTOR('',#67706,1.); +#67706 = DIRECTION('',(1.,0.E+000)); +#67707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67708 = ORIENTED_EDGE('',*,*,#67709,.F.); +#67709 = EDGE_CURVE('',#67710,#67687,#67712,.T.); +#67710 = VERTEX_POINT('',#67711); +#67711 = CARTESIAN_POINT('',(-1.175,-1.255,-1.999078980754)); +#67712 = SURFACE_CURVE('',#67713,(#67717,#67724),.PCURVE_S1.); +#67713 = LINE('',#67714,#67715); +#67714 = CARTESIAN_POINT('',(-1.175,-1.255,-1.999078980754)); +#67715 = VECTOR('',#67716,1.); +#67716 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67717 = PCURVE('',#63039,#67718); +#67718 = DEFINITIONAL_REPRESENTATION('',(#67719),#67723); +#67719 = LINE('',#67720,#67721); +#67720 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#67721 = VECTOR('',#67722,1.); +#67722 = DIRECTION('',(1.,0.E+000)); +#67723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67724 = PCURVE('',#67572,#67725); +#67725 = DEFINITIONAL_REPRESENTATION('',(#67726),#67730); +#67726 = LINE('',#67727,#67728); +#67727 = CARTESIAN_POINT('',(0.E+000,0.25)); +#67728 = VECTOR('',#67729,1.); +#67729 = DIRECTION('',(1.,0.E+000)); +#67730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67731 = ORIENTED_EDGE('',*,*,#67732,.F.); +#67732 = EDGE_CURVE('',#67631,#67710,#67733,.T.); +#67733 = SURFACE_CURVE('',#67734,(#67739,#67746),.PCURVE_S1.); +#67734 = CIRCLE('',#67735,0.1); +#67735 = AXIS2_PLACEMENT_3D('',#67736,#67737,#67738); +#67736 = CARTESIAN_POINT('',(-1.175,-1.155,-1.999078980754)); +#67737 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67738 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#67739 = PCURVE('',#63039,#67740); +#67740 = DEFINITIONAL_REPRESENTATION('',(#67741),#67745); +#67741 = CIRCLE('',#67742,0.1); +#67742 = AXIS2_PLACEMENT_2D('',#67743,#67744); +#67743 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#67744 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#67745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67746 = PCURVE('',#67545,#67747); +#67747 = DEFINITIONAL_REPRESENTATION('',(#67748),#67751); +#67748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67749,#67750),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#67749 = CARTESIAN_POINT('',(3.403392041389,0.25)); +#67750 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#67751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67752 = ORIENTED_EDGE('',*,*,#67630,.F.); +#67753 = ORIENTED_EDGE('',*,*,#63023,.F.); +#67754 = ADVANCED_FACE('',(#67755),#67466,.T.); +#67755 = FACE_BOUND('',#67756,.F.); +#67756 = EDGE_LOOP('',(#67757,#67758,#67779,#67780)); +#67757 = ORIENTED_EDGE('',*,*,#67584,.F.); +#67758 = ORIENTED_EDGE('',*,*,#67759,.T.); +#67759 = EDGE_CURVE('',#67557,#67687,#67760,.T.); +#67760 = SURFACE_CURVE('',#67761,(#67765,#67772),.PCURVE_S1.); +#67761 = LINE('',#67762,#67763); +#67762 = CARTESIAN_POINT('',(-1.425,-1.255,-2.65)); +#67763 = VECTOR('',#67764,1.); +#67764 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67765 = PCURVE('',#67466,#67766); +#67766 = DEFINITIONAL_REPRESENTATION('',(#67767),#67771); +#67767 = LINE('',#67768,#67769); +#67768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67769 = VECTOR('',#67770,1.); +#67770 = DIRECTION('',(0.E+000,1.)); +#67771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67772 = PCURVE('',#67572,#67773); +#67773 = DEFINITIONAL_REPRESENTATION('',(#67774),#67778); +#67774 = LINE('',#67775,#67776); +#67775 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#67776 = VECTOR('',#67777,1.); +#67777 = DIRECTION('',(0.E+000,1.)); +#67778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67779 = ORIENTED_EDGE('',*,*,#67686,.T.); +#67780 = ORIENTED_EDGE('',*,*,#67450,.F.); +#67781 = ADVANCED_FACE('',(#67782),#67572,.T.); +#67782 = FACE_BOUND('',#67783,.F.); +#67783 = EDGE_LOOP('',(#67784,#67785,#67805,#67806)); +#67784 = ORIENTED_EDGE('',*,*,#67556,.F.); +#67785 = ORIENTED_EDGE('',*,*,#67786,.T.); +#67786 = EDGE_CURVE('',#67529,#67710,#67787,.T.); +#67787 = SURFACE_CURVE('',#67788,(#67792,#67799),.PCURVE_S1.); +#67788 = LINE('',#67789,#67790); +#67789 = CARTESIAN_POINT('',(-1.425,-1.255,-1.999078980754)); +#67790 = VECTOR('',#67791,1.); +#67791 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67792 = PCURVE('',#67572,#67793); +#67793 = DEFINITIONAL_REPRESENTATION('',(#67794),#67798); +#67794 = LINE('',#67795,#67796); +#67795 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67796 = VECTOR('',#67797,1.); +#67797 = DIRECTION('',(0.E+000,1.)); +#67798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67799 = PCURVE('',#67545,#67800); +#67800 = DEFINITIONAL_REPRESENTATION('',(#67801),#67804); +#67801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67802,#67803),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#67802 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#67803 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#67804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67805 = ORIENTED_EDGE('',*,*,#67709,.T.); +#67806 = ORIENTED_EDGE('',*,*,#67759,.F.); +#67807 = ADVANCED_FACE('',(#67808),#67545,.T.); +#67808 = FACE_BOUND('',#67809,.T.); +#67809 = EDGE_LOOP('',(#67810,#67811,#67812,#67813)); +#67810 = ORIENTED_EDGE('',*,*,#67528,.T.); +#67811 = ORIENTED_EDGE('',*,*,#67786,.T.); +#67812 = ORIENTED_EDGE('',*,*,#67732,.F.); +#67813 = ORIENTED_EDGE('',*,*,#67653,.F.); +#67814 = ADVANCED_FACE('',(#67815),#64590,.T.); +#67815 = FACE_BOUND('',#67816,.F.); +#67816 = EDGE_LOOP('',(#67817,#67840,#67868,#67889)); +#67817 = ORIENTED_EDGE('',*,*,#67818,.F.); +#67818 = EDGE_CURVE('',#67819,#62973,#67821,.T.); +#67819 = VERTEX_POINT('',#67820); +#67820 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); +#67821 = SURFACE_CURVE('',#67822,(#67826,#67833),.PCURVE_S1.); +#67822 = LINE('',#67823,#67824); +#67823 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); +#67824 = VECTOR('',#67825,1.); +#67825 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67826 = PCURVE('',#64590,#67827); +#67827 = DEFINITIONAL_REPRESENTATION('',(#67828),#67832); +#67828 = LINE('',#67829,#67830); +#67829 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67830 = VECTOR('',#67831,1.); +#67831 = DIRECTION('',(1.,0.E+000)); +#67832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67833 = PCURVE('',#62988,#67834); +#67834 = DEFINITIONAL_REPRESENTATION('',(#67835),#67839); +#67835 = LINE('',#67836,#67837); +#67836 = CARTESIAN_POINT('',(2.65,-1.105)); +#67837 = VECTOR('',#67838,1.); +#67838 = DIRECTION('',(-1.,0.E+000)); +#67839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67840 = ORIENTED_EDGE('',*,*,#67841,.T.); +#67841 = EDGE_CURVE('',#67819,#67842,#67844,.T.); +#67842 = VERTEX_POINT('',#67843); +#67843 = CARTESIAN_POINT('',(-0.525,-1.105,-2.65)); +#67844 = SURFACE_CURVE('',#67845,(#67849,#67856),.PCURVE_S1.); +#67845 = LINE('',#67846,#67847); +#67846 = CARTESIAN_POINT('',(-0.775,-1.105,-2.65)); +#67847 = VECTOR('',#67848,1.); +#67848 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67849 = PCURVE('',#64590,#67850); +#67850 = DEFINITIONAL_REPRESENTATION('',(#67851),#67855); +#67851 = LINE('',#67852,#67853); +#67852 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67853 = VECTOR('',#67854,1.); +#67854 = DIRECTION('',(0.E+000,1.)); +#67855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67856 = PCURVE('',#67857,#67862); +#67857 = PLANE('',#67858); +#67858 = AXIS2_PLACEMENT_3D('',#67859,#67860,#67861); +#67859 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); +#67860 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67861 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67862 = DEFINITIONAL_REPRESENTATION('',(#67863),#67867); +#67863 = LINE('',#67864,#67865); +#67864 = CARTESIAN_POINT('',(0.15,0.E+000)); +#67865 = VECTOR('',#67866,1.); +#67866 = DIRECTION('',(0.E+000,1.)); +#67867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67868 = ORIENTED_EDGE('',*,*,#67869,.T.); +#67869 = EDGE_CURVE('',#67842,#63157,#67870,.T.); +#67870 = SURFACE_CURVE('',#67871,(#67875,#67882),.PCURVE_S1.); +#67871 = LINE('',#67872,#67873); +#67872 = CARTESIAN_POINT('',(-0.525,-1.105,-2.65)); +#67873 = VECTOR('',#67874,1.); +#67874 = DIRECTION('',(0.E+000,0.E+000,1.)); +#67875 = PCURVE('',#64590,#67876); +#67876 = DEFINITIONAL_REPRESENTATION('',(#67877),#67881); +#67877 = LINE('',#67878,#67879); +#67878 = CARTESIAN_POINT('',(0.E+000,0.25)); +#67879 = VECTOR('',#67880,1.); +#67880 = DIRECTION('',(1.,0.E+000)); +#67881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67882 = PCURVE('',#63195,#67883); +#67883 = DEFINITIONAL_REPRESENTATION('',(#67884),#67888); +#67884 = LINE('',#67885,#67886); +#67885 = CARTESIAN_POINT('',(2.65,-1.105)); +#67886 = VECTOR('',#67887,1.); +#67887 = DIRECTION('',(-1.,0.E+000)); +#67888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67889 = ORIENTED_EDGE('',*,*,#64576,.F.); +#67890 = ADVANCED_FACE('',(#67891),#62988,.F.); +#67891 = FACE_BOUND('',#67892,.F.); +#67892 = EDGE_LOOP('',(#67893,#67894,#67895,#67918,#67946,#67974)); +#67893 = ORIENTED_EDGE('',*,*,#67818,.T.); +#67894 = ORIENTED_EDGE('',*,*,#62972,.F.); +#67895 = ORIENTED_EDGE('',*,*,#67896,.T.); +#67896 = EDGE_CURVE('',#62945,#67897,#67899,.T.); +#67897 = VERTEX_POINT('',#67898); +#67898 = CARTESIAN_POINT('',(-0.775,-1.18088190451,-1.902486398125)); +#67899 = SURFACE_CURVE('',#67900,(#67904,#67911),.PCURVE_S1.); +#67900 = LINE('',#67901,#67902); +#67901 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); +#67902 = VECTOR('',#67903,1.); +#67903 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#67904 = PCURVE('',#62988,#67905); +#67905 = DEFINITIONAL_REPRESENTATION('',(#67906),#67910); +#67906 = LINE('',#67907,#67908); +#67907 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#67908 = VECTOR('',#67909,1.); +#67909 = DIRECTION('',(0.258819045102,-0.965925826289)); +#67910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67911 = PCURVE('',#62455,#67912); +#67912 = DEFINITIONAL_REPRESENTATION('',(#67913),#67917); +#67913 = LINE('',#67914,#67915); +#67914 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#67915 = VECTOR('',#67916,1.); +#67916 = DIRECTION('',(1.,0.E+000)); +#67917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67918 = ORIENTED_EDGE('',*,*,#67919,.T.); +#67919 = EDGE_CURVE('',#67897,#67920,#67922,.T.); +#67920 = VERTEX_POINT('',#67921); +#67921 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); +#67922 = SURFACE_CURVE('',#67923,(#67928,#67935),.PCURVE_S1.); +#67923 = CIRCLE('',#67924,0.1); +#67924 = AXIS2_PLACEMENT_3D('',#67925,#67926,#67927); +#67925 = CARTESIAN_POINT('',(-0.775,-1.155,-1.999078980754)); +#67926 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67927 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#67928 = PCURVE('',#62988,#67929); +#67929 = DEFINITIONAL_REPRESENTATION('',(#67930),#67934); +#67930 = CIRCLE('',#67931,0.1); +#67931 = AXIS2_PLACEMENT_2D('',#67932,#67933); +#67932 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#67933 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#67934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67935 = PCURVE('',#67936,#67941); +#67936 = CYLINDRICAL_SURFACE('',#67937,0.1); +#67937 = AXIS2_PLACEMENT_3D('',#67938,#67939,#67940); +#67938 = CARTESIAN_POINT('',(-0.775,-1.155,-1.999078980754)); +#67939 = DIRECTION('',(1.,0.E+000,0.E+000)); +#67940 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67941 = DEFINITIONAL_REPRESENTATION('',(#67942),#67945); +#67942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67943,#67944),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#67943 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); +#67944 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#67945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67946 = ORIENTED_EDGE('',*,*,#67947,.T.); +#67947 = EDGE_CURVE('',#67920,#67948,#67950,.T.); +#67948 = VERTEX_POINT('',#67949); +#67949 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); +#67950 = SURFACE_CURVE('',#67951,(#67955,#67962),.PCURVE_S1.); +#67951 = LINE('',#67952,#67953); +#67952 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); +#67953 = VECTOR('',#67954,1.); +#67954 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67955 = PCURVE('',#62988,#67956); +#67956 = DEFINITIONAL_REPRESENTATION('',(#67957),#67961); +#67957 = LINE('',#67958,#67959); +#67958 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#67959 = VECTOR('',#67960,1.); +#67960 = DIRECTION('',(1.,0.E+000)); +#67961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67962 = PCURVE('',#67963,#67968); +#67963 = PLANE('',#67964); +#67964 = AXIS2_PLACEMENT_3D('',#67965,#67966,#67967); +#67965 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); +#67966 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#67967 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#67968 = DEFINITIONAL_REPRESENTATION('',(#67969),#67973); +#67969 = LINE('',#67970,#67971); +#67970 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67971 = VECTOR('',#67972,1.); +#67972 = DIRECTION('',(1.,0.E+000)); +#67973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67974 = ORIENTED_EDGE('',*,*,#67975,.T.); +#67975 = EDGE_CURVE('',#67948,#67819,#67976,.T.); +#67976 = SURFACE_CURVE('',#67977,(#67981,#67988),.PCURVE_S1.); +#67977 = LINE('',#67978,#67979); +#67978 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); +#67979 = VECTOR('',#67980,1.); +#67980 = DIRECTION('',(0.E+000,1.,0.E+000)); +#67981 = PCURVE('',#62988,#67982); +#67982 = DEFINITIONAL_REPRESENTATION('',(#67983),#67987); +#67983 = LINE('',#67984,#67985); +#67984 = CARTESIAN_POINT('',(2.65,-1.255)); +#67985 = VECTOR('',#67986,1.); +#67986 = DIRECTION('',(0.E+000,1.)); +#67987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67988 = PCURVE('',#67857,#67989); +#67989 = DEFINITIONAL_REPRESENTATION('',(#67990),#67994); +#67990 = LINE('',#67991,#67992); +#67991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#67992 = VECTOR('',#67993,1.); +#67993 = DIRECTION('',(1.,0.E+000)); +#67994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#67995 = ADVANCED_FACE('',(#67996),#62455,.T.); +#67996 = FACE_BOUND('',#67997,.F.); +#67997 = EDGE_LOOP('',(#67998,#67999,#68020,#68043,#68063,#68064)); +#67998 = ORIENTED_EDGE('',*,*,#62439,.T.); +#67999 = ORIENTED_EDGE('',*,*,#68000,.F.); +#68000 = EDGE_CURVE('',#63180,#62412,#68001,.T.); +#68001 = SURFACE_CURVE('',#68002,(#68006,#68013),.PCURVE_S1.); +#68002 = LINE('',#68003,#68004); +#68003 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); +#68004 = VECTOR('',#68005,1.); +#68005 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68006 = PCURVE('',#62455,#68007); +#68007 = DEFINITIONAL_REPRESENTATION('',(#68008),#68012); +#68008 = LINE('',#68009,#68010); +#68009 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68010 = VECTOR('',#68011,1.); +#68011 = DIRECTION('',(-1.,0.E+000)); +#68012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68013 = PCURVE('',#62427,#68014); +#68014 = DEFINITIONAL_REPRESENTATION('',(#68015),#68019); +#68015 = LINE('',#68016,#68017); +#68016 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68017 = VECTOR('',#68018,1.); +#68018 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68020 = ORIENTED_EDGE('',*,*,#68021,.T.); +#68021 = EDGE_CURVE('',#63180,#68022,#68024,.T.); +#68022 = VERTEX_POINT('',#68023); +#68023 = CARTESIAN_POINT('',(-0.525,-1.18088190451,-1.902486398125)); +#68024 = SURFACE_CURVE('',#68025,(#68029,#68036),.PCURVE_S1.); +#68025 = LINE('',#68026,#68027); +#68026 = CARTESIAN_POINT('',(-0.525,-1.105,-1.882153903092)); +#68027 = VECTOR('',#68028,1.); +#68028 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#68029 = PCURVE('',#62455,#68030); +#68030 = DEFINITIONAL_REPRESENTATION('',(#68031),#68035); +#68031 = LINE('',#68032,#68033); +#68032 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68033 = VECTOR('',#68034,1.); +#68034 = DIRECTION('',(1.,0.E+000)); +#68035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68036 = PCURVE('',#63195,#68037); +#68037 = DEFINITIONAL_REPRESENTATION('',(#68038),#68042); +#68038 = LINE('',#68039,#68040); +#68039 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68040 = VECTOR('',#68041,1.); +#68041 = DIRECTION('',(0.258819045102,-0.965925826289)); +#68042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68043 = ORIENTED_EDGE('',*,*,#68044,.F.); +#68044 = EDGE_CURVE('',#67897,#68022,#68045,.T.); +#68045 = SURFACE_CURVE('',#68046,(#68050,#68057),.PCURVE_S1.); +#68046 = LINE('',#68047,#68048); +#68047 = CARTESIAN_POINT('',(-0.775,-1.18088190451,-1.902486398125)); +#68048 = VECTOR('',#68049,1.); +#68049 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68050 = PCURVE('',#62455,#68051); +#68051 = DEFINITIONAL_REPRESENTATION('',(#68052),#68056); +#68052 = LINE('',#68053,#68054); +#68053 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); +#68054 = VECTOR('',#68055,1.); +#68055 = DIRECTION('',(0.E+000,1.)); +#68056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68057 = PCURVE('',#67936,#68058); +#68058 = DEFINITIONAL_REPRESENTATION('',(#68059),#68062); +#68059 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68060,#68061),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#68060 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); +#68061 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#68062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68063 = ORIENTED_EDGE('',*,*,#67896,.F.); +#68064 = ORIENTED_EDGE('',*,*,#68065,.T.); +#68065 = EDGE_CURVE('',#62945,#62440,#68066,.T.); +#68066 = SURFACE_CURVE('',#68067,(#68071,#68078),.PCURVE_S1.); +#68067 = LINE('',#68068,#68069); +#68068 = CARTESIAN_POINT('',(-0.775,-1.105,-1.882153903092)); +#68069 = VECTOR('',#68070,1.); +#68070 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68071 = PCURVE('',#62455,#68072); +#68072 = DEFINITIONAL_REPRESENTATION('',(#68073),#68077); +#68073 = LINE('',#68074,#68075); +#68074 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#68075 = VECTOR('',#68076,1.); +#68076 = DIRECTION('',(-1.,0.E+000)); +#68077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68078 = PCURVE('',#62483,#68079); +#68079 = DEFINITIONAL_REPRESENTATION('',(#68080),#68084); +#68080 = LINE('',#68081,#68082); +#68081 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68082 = VECTOR('',#68083,1.); +#68083 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68085 = ADVANCED_FACE('',(#68086),#62427,.F.); +#68086 = FACE_BOUND('',#68087,.F.); +#68087 = EDGE_LOOP('',(#68088,#68089,#68090,#68091)); +#68088 = ORIENTED_EDGE('',*,*,#63207,.T.); +#68089 = ORIENTED_EDGE('',*,*,#68000,.T.); +#68090 = ORIENTED_EDGE('',*,*,#62411,.T.); +#68091 = ORIENTED_EDGE('',*,*,#63779,.T.); +#68092 = ADVANCED_FACE('',(#68093),#63195,.T.); +#68093 = FACE_BOUND('',#68094,.F.); +#68094 = EDGE_LOOP('',(#68095,#68096,#68119,#68142,#68163,#68164)); +#68095 = ORIENTED_EDGE('',*,*,#67869,.F.); +#68096 = ORIENTED_EDGE('',*,*,#68097,.F.); +#68097 = EDGE_CURVE('',#68098,#67842,#68100,.T.); +#68098 = VERTEX_POINT('',#68099); +#68099 = CARTESIAN_POINT('',(-0.525,-1.255,-2.65)); +#68100 = SURFACE_CURVE('',#68101,(#68105,#68112),.PCURVE_S1.); +#68101 = LINE('',#68102,#68103); +#68102 = CARTESIAN_POINT('',(-0.525,-1.255,-2.65)); +#68103 = VECTOR('',#68104,1.); +#68104 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68105 = PCURVE('',#63195,#68106); +#68106 = DEFINITIONAL_REPRESENTATION('',(#68107),#68111); +#68107 = LINE('',#68108,#68109); +#68108 = CARTESIAN_POINT('',(2.65,-1.255)); +#68109 = VECTOR('',#68110,1.); +#68110 = DIRECTION('',(0.E+000,1.)); +#68111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68112 = PCURVE('',#67857,#68113); +#68113 = DEFINITIONAL_REPRESENTATION('',(#68114),#68118); +#68114 = LINE('',#68115,#68116); +#68115 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68116 = VECTOR('',#68117,1.); +#68117 = DIRECTION('',(1.,0.E+000)); +#68118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68119 = ORIENTED_EDGE('',*,*,#68120,.F.); +#68120 = EDGE_CURVE('',#68121,#68098,#68123,.T.); +#68121 = VERTEX_POINT('',#68122); +#68122 = CARTESIAN_POINT('',(-0.525,-1.255,-1.999078980754)); +#68123 = SURFACE_CURVE('',#68124,(#68128,#68135),.PCURVE_S1.); +#68124 = LINE('',#68125,#68126); +#68125 = CARTESIAN_POINT('',(-0.525,-1.255,-1.999078980754)); +#68126 = VECTOR('',#68127,1.); +#68127 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68128 = PCURVE('',#63195,#68129); +#68129 = DEFINITIONAL_REPRESENTATION('',(#68130),#68134); +#68130 = LINE('',#68131,#68132); +#68131 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#68132 = VECTOR('',#68133,1.); +#68133 = DIRECTION('',(1.,0.E+000)); +#68134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68135 = PCURVE('',#67963,#68136); +#68136 = DEFINITIONAL_REPRESENTATION('',(#68137),#68141); +#68137 = LINE('',#68138,#68139); +#68138 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68139 = VECTOR('',#68140,1.); +#68140 = DIRECTION('',(1.,0.E+000)); +#68141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68142 = ORIENTED_EDGE('',*,*,#68143,.F.); +#68143 = EDGE_CURVE('',#68022,#68121,#68144,.T.); +#68144 = SURFACE_CURVE('',#68145,(#68150,#68157),.PCURVE_S1.); +#68145 = CIRCLE('',#68146,0.1); +#68146 = AXIS2_PLACEMENT_3D('',#68147,#68148,#68149); +#68147 = CARTESIAN_POINT('',(-0.525,-1.155,-1.999078980754)); +#68148 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68149 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#68150 = PCURVE('',#63195,#68151); +#68151 = DEFINITIONAL_REPRESENTATION('',(#68152),#68156); +#68152 = CIRCLE('',#68153,0.1); +#68153 = AXIS2_PLACEMENT_2D('',#68154,#68155); +#68154 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#68155 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#68156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68157 = PCURVE('',#67936,#68158); +#68158 = DEFINITIONAL_REPRESENTATION('',(#68159),#68162); +#68159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68160,#68161),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#68160 = CARTESIAN_POINT('',(3.403392041389,0.25)); +#68161 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#68162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68163 = ORIENTED_EDGE('',*,*,#68021,.F.); +#68164 = ORIENTED_EDGE('',*,*,#63179,.F.); +#68165 = ADVANCED_FACE('',(#68166),#67857,.T.); +#68166 = FACE_BOUND('',#68167,.F.); +#68167 = EDGE_LOOP('',(#68168,#68169,#68190,#68191)); +#68168 = ORIENTED_EDGE('',*,*,#67975,.F.); +#68169 = ORIENTED_EDGE('',*,*,#68170,.T.); +#68170 = EDGE_CURVE('',#67948,#68098,#68171,.T.); +#68171 = SURFACE_CURVE('',#68172,(#68176,#68183),.PCURVE_S1.); +#68172 = LINE('',#68173,#68174); +#68173 = CARTESIAN_POINT('',(-0.775,-1.255,-2.65)); +#68174 = VECTOR('',#68175,1.); +#68175 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68176 = PCURVE('',#67857,#68177); +#68177 = DEFINITIONAL_REPRESENTATION('',(#68178),#68182); +#68178 = LINE('',#68179,#68180); +#68179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68180 = VECTOR('',#68181,1.); +#68181 = DIRECTION('',(0.E+000,1.)); +#68182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68183 = PCURVE('',#67963,#68184); +#68184 = DEFINITIONAL_REPRESENTATION('',(#68185),#68189); +#68185 = LINE('',#68186,#68187); +#68186 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#68187 = VECTOR('',#68188,1.); +#68188 = DIRECTION('',(0.E+000,1.)); +#68189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68190 = ORIENTED_EDGE('',*,*,#68097,.T.); +#68191 = ORIENTED_EDGE('',*,*,#67841,.F.); +#68192 = ADVANCED_FACE('',(#68193),#67963,.T.); +#68193 = FACE_BOUND('',#68194,.F.); +#68194 = EDGE_LOOP('',(#68195,#68196,#68216,#68217)); +#68195 = ORIENTED_EDGE('',*,*,#67947,.F.); +#68196 = ORIENTED_EDGE('',*,*,#68197,.T.); +#68197 = EDGE_CURVE('',#67920,#68121,#68198,.T.); +#68198 = SURFACE_CURVE('',#68199,(#68203,#68210),.PCURVE_S1.); +#68199 = LINE('',#68200,#68201); +#68200 = CARTESIAN_POINT('',(-0.775,-1.255,-1.999078980754)); +#68201 = VECTOR('',#68202,1.); +#68202 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68203 = PCURVE('',#67963,#68204); +#68204 = DEFINITIONAL_REPRESENTATION('',(#68205),#68209); +#68205 = LINE('',#68206,#68207); +#68206 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68207 = VECTOR('',#68208,1.); +#68208 = DIRECTION('',(0.E+000,1.)); +#68209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68210 = PCURVE('',#67936,#68211); +#68211 = DEFINITIONAL_REPRESENTATION('',(#68212),#68215); +#68212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68213,#68214),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#68213 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#68214 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#68215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68216 = ORIENTED_EDGE('',*,*,#68120,.T.); +#68217 = ORIENTED_EDGE('',*,*,#68170,.F.); +#68218 = ADVANCED_FACE('',(#68219),#67936,.T.); +#68219 = FACE_BOUND('',#68220,.T.); +#68220 = EDGE_LOOP('',(#68221,#68222,#68223,#68224)); +#68221 = ORIENTED_EDGE('',*,*,#67919,.T.); +#68222 = ORIENTED_EDGE('',*,*,#68197,.T.); +#68223 = ORIENTED_EDGE('',*,*,#68143,.F.); +#68224 = ORIENTED_EDGE('',*,*,#68044,.F.); +#68225 = ADVANCED_FACE('',(#68226),#62483,.T.); +#68226 = FACE_BOUND('',#68227,.F.); +#68227 = EDGE_LOOP('',(#68228,#68229,#68230,#68231)); +#68228 = ORIENTED_EDGE('',*,*,#62942,.F.); +#68229 = ORIENTED_EDGE('',*,*,#63710,.F.); +#68230 = ORIENTED_EDGE('',*,*,#62467,.F.); +#68231 = ORIENTED_EDGE('',*,*,#68065,.F.); +#68232 = ADVANCED_FACE('',(#68233),#64617,.T.); +#68233 = FACE_BOUND('',#68234,.F.); +#68234 = EDGE_LOOP('',(#68235,#68258,#68286,#68307)); +#68235 = ORIENTED_EDGE('',*,*,#68236,.F.); +#68236 = EDGE_CURVE('',#68237,#63129,#68239,.T.); +#68237 = VERTEX_POINT('',#68238); +#68238 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); +#68239 = SURFACE_CURVE('',#68240,(#68244,#68251),.PCURVE_S1.); +#68240 = LINE('',#68241,#68242); +#68241 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); +#68242 = VECTOR('',#68243,1.); +#68243 = DIRECTION('',(0.E+000,0.E+000,1.)); +#68244 = PCURVE('',#64617,#68245); +#68245 = DEFINITIONAL_REPRESENTATION('',(#68246),#68250); +#68246 = LINE('',#68247,#68248); +#68247 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68248 = VECTOR('',#68249,1.); +#68249 = DIRECTION('',(1.,0.E+000)); +#68250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68251 = PCURVE('',#63144,#68252); +#68252 = DEFINITIONAL_REPRESENTATION('',(#68253),#68257); +#68253 = LINE('',#68254,#68255); +#68254 = CARTESIAN_POINT('',(2.65,-1.105)); +#68255 = VECTOR('',#68256,1.); +#68256 = DIRECTION('',(-1.,0.E+000)); +#68257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68258 = ORIENTED_EDGE('',*,*,#68259,.T.); +#68259 = EDGE_CURVE('',#68237,#68260,#68262,.T.); +#68260 = VERTEX_POINT('',#68261); +#68261 = CARTESIAN_POINT('',(0.125,-1.105,-2.65)); +#68262 = SURFACE_CURVE('',#68263,(#68267,#68274),.PCURVE_S1.); +#68263 = LINE('',#68264,#68265); +#68264 = CARTESIAN_POINT('',(-0.125,-1.105,-2.65)); +#68265 = VECTOR('',#68266,1.); +#68266 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68267 = PCURVE('',#64617,#68268); +#68268 = DEFINITIONAL_REPRESENTATION('',(#68269),#68273); +#68269 = LINE('',#68270,#68271); +#68270 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68271 = VECTOR('',#68272,1.); +#68272 = DIRECTION('',(0.E+000,1.)); +#68273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68274 = PCURVE('',#68275,#68280); +#68275 = PLANE('',#68276); +#68276 = AXIS2_PLACEMENT_3D('',#68277,#68278,#68279); +#68277 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); +#68278 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68279 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68280 = DEFINITIONAL_REPRESENTATION('',(#68281),#68285); +#68281 = LINE('',#68282,#68283); +#68282 = CARTESIAN_POINT('',(0.15,0.E+000)); +#68283 = VECTOR('',#68284,1.); +#68284 = DIRECTION('',(0.E+000,1.)); +#68285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68286 = ORIENTED_EDGE('',*,*,#68287,.T.); +#68287 = EDGE_CURVE('',#68260,#63313,#68288,.T.); +#68288 = SURFACE_CURVE('',#68289,(#68293,#68300),.PCURVE_S1.); +#68289 = LINE('',#68290,#68291); +#68290 = CARTESIAN_POINT('',(0.125,-1.105,-2.65)); +#68291 = VECTOR('',#68292,1.); +#68292 = DIRECTION('',(0.E+000,0.E+000,1.)); +#68293 = PCURVE('',#64617,#68294); +#68294 = DEFINITIONAL_REPRESENTATION('',(#68295),#68299); +#68295 = LINE('',#68296,#68297); +#68296 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68297 = VECTOR('',#68298,1.); +#68298 = DIRECTION('',(1.,0.E+000)); +#68299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68300 = PCURVE('',#63351,#68301); +#68301 = DEFINITIONAL_REPRESENTATION('',(#68302),#68306); +#68302 = LINE('',#68303,#68304); +#68303 = CARTESIAN_POINT('',(2.65,-1.105)); +#68304 = VECTOR('',#68305,1.); +#68305 = DIRECTION('',(-1.,0.E+000)); +#68306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68307 = ORIENTED_EDGE('',*,*,#64603,.F.); +#68308 = ADVANCED_FACE('',(#68309),#63144,.F.); +#68309 = FACE_BOUND('',#68310,.F.); +#68310 = EDGE_LOOP('',(#68311,#68312,#68313,#68336,#68364,#68392)); +#68311 = ORIENTED_EDGE('',*,*,#68236,.T.); +#68312 = ORIENTED_EDGE('',*,*,#63128,.F.); +#68313 = ORIENTED_EDGE('',*,*,#68314,.T.); +#68314 = EDGE_CURVE('',#63101,#68315,#68317,.T.); +#68315 = VERTEX_POINT('',#68316); +#68316 = CARTESIAN_POINT('',(-0.125,-1.18088190451,-1.902486398125)); +#68317 = SURFACE_CURVE('',#68318,(#68322,#68329),.PCURVE_S1.); +#68318 = LINE('',#68319,#68320); +#68319 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); +#68320 = VECTOR('',#68321,1.); +#68321 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#68322 = PCURVE('',#63144,#68323); +#68323 = DEFINITIONAL_REPRESENTATION('',(#68324),#68328); +#68324 = LINE('',#68325,#68326); +#68325 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68326 = VECTOR('',#68327,1.); +#68327 = DIRECTION('',(0.258819045102,-0.965925826289)); +#68328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68329 = PCURVE('',#62343,#68330); +#68330 = DEFINITIONAL_REPRESENTATION('',(#68331),#68335); +#68331 = LINE('',#68332,#68333); +#68332 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#68333 = VECTOR('',#68334,1.); +#68334 = DIRECTION('',(1.,0.E+000)); +#68335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68336 = ORIENTED_EDGE('',*,*,#68337,.T.); +#68337 = EDGE_CURVE('',#68315,#68338,#68340,.T.); +#68338 = VERTEX_POINT('',#68339); +#68339 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); +#68340 = SURFACE_CURVE('',#68341,(#68346,#68353),.PCURVE_S1.); +#68341 = CIRCLE('',#68342,0.1); +#68342 = AXIS2_PLACEMENT_3D('',#68343,#68344,#68345); +#68343 = CARTESIAN_POINT('',(-0.125,-1.155,-1.999078980754)); +#68344 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68345 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#68346 = PCURVE('',#63144,#68347); +#68347 = DEFINITIONAL_REPRESENTATION('',(#68348),#68352); +#68348 = CIRCLE('',#68349,0.1); +#68349 = AXIS2_PLACEMENT_2D('',#68350,#68351); +#68350 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#68351 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#68352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68353 = PCURVE('',#68354,#68359); +#68354 = CYLINDRICAL_SURFACE('',#68355,0.1); +#68355 = AXIS2_PLACEMENT_3D('',#68356,#68357,#68358); +#68356 = CARTESIAN_POINT('',(-0.125,-1.155,-1.999078980754)); +#68357 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68358 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68359 = DEFINITIONAL_REPRESENTATION('',(#68360),#68363); +#68360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68361,#68362),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#68361 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); +#68362 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#68363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68364 = ORIENTED_EDGE('',*,*,#68365,.T.); +#68365 = EDGE_CURVE('',#68338,#68366,#68368,.T.); +#68366 = VERTEX_POINT('',#68367); +#68367 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); +#68368 = SURFACE_CURVE('',#68369,(#68373,#68380),.PCURVE_S1.); +#68369 = LINE('',#68370,#68371); +#68370 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); +#68371 = VECTOR('',#68372,1.); +#68372 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68373 = PCURVE('',#63144,#68374); +#68374 = DEFINITIONAL_REPRESENTATION('',(#68375),#68379); +#68375 = LINE('',#68376,#68377); +#68376 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#68377 = VECTOR('',#68378,1.); +#68378 = DIRECTION('',(1.,0.E+000)); +#68379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68380 = PCURVE('',#68381,#68386); +#68381 = PLANE('',#68382); +#68382 = AXIS2_PLACEMENT_3D('',#68383,#68384,#68385); +#68383 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); +#68384 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#68385 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68386 = DEFINITIONAL_REPRESENTATION('',(#68387),#68391); +#68387 = LINE('',#68388,#68389); +#68388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68389 = VECTOR('',#68390,1.); +#68390 = DIRECTION('',(1.,0.E+000)); +#68391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68392 = ORIENTED_EDGE('',*,*,#68393,.T.); +#68393 = EDGE_CURVE('',#68366,#68237,#68394,.T.); +#68394 = SURFACE_CURVE('',#68395,(#68399,#68406),.PCURVE_S1.); +#68395 = LINE('',#68396,#68397); +#68396 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); +#68397 = VECTOR('',#68398,1.); +#68398 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68399 = PCURVE('',#63144,#68400); +#68400 = DEFINITIONAL_REPRESENTATION('',(#68401),#68405); +#68401 = LINE('',#68402,#68403); +#68402 = CARTESIAN_POINT('',(2.65,-1.255)); +#68403 = VECTOR('',#68404,1.); +#68404 = DIRECTION('',(0.E+000,1.)); +#68405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68406 = PCURVE('',#68275,#68407); +#68407 = DEFINITIONAL_REPRESENTATION('',(#68408),#68412); +#68408 = LINE('',#68409,#68410); +#68409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68410 = VECTOR('',#68411,1.); +#68411 = DIRECTION('',(1.,0.E+000)); +#68412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68413 = ADVANCED_FACE('',(#68414),#62343,.T.); +#68414 = FACE_BOUND('',#68415,.F.); +#68415 = EDGE_LOOP('',(#68416,#68417,#68438,#68461,#68481,#68482)); +#68416 = ORIENTED_EDGE('',*,*,#62327,.T.); +#68417 = ORIENTED_EDGE('',*,*,#68418,.F.); +#68418 = EDGE_CURVE('',#63336,#62300,#68419,.T.); +#68419 = SURFACE_CURVE('',#68420,(#68424,#68431),.PCURVE_S1.); +#68420 = LINE('',#68421,#68422); +#68421 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); +#68422 = VECTOR('',#68423,1.); +#68423 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68424 = PCURVE('',#62343,#68425); +#68425 = DEFINITIONAL_REPRESENTATION('',(#68426),#68430); +#68426 = LINE('',#68427,#68428); +#68427 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68428 = VECTOR('',#68429,1.); +#68429 = DIRECTION('',(-1.,0.E+000)); +#68430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68431 = PCURVE('',#62315,#68432); +#68432 = DEFINITIONAL_REPRESENTATION('',(#68433),#68437); +#68433 = LINE('',#68434,#68435); +#68434 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68435 = VECTOR('',#68436,1.); +#68436 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68438 = ORIENTED_EDGE('',*,*,#68439,.T.); +#68439 = EDGE_CURVE('',#63336,#68440,#68442,.T.); +#68440 = VERTEX_POINT('',#68441); +#68441 = CARTESIAN_POINT('',(0.125,-1.18088190451,-1.902486398125)); +#68442 = SURFACE_CURVE('',#68443,(#68447,#68454),.PCURVE_S1.); +#68443 = LINE('',#68444,#68445); +#68444 = CARTESIAN_POINT('',(0.125,-1.105,-1.882153903092)); +#68445 = VECTOR('',#68446,1.); +#68446 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#68447 = PCURVE('',#62343,#68448); +#68448 = DEFINITIONAL_REPRESENTATION('',(#68449),#68453); +#68449 = LINE('',#68450,#68451); +#68450 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68451 = VECTOR('',#68452,1.); +#68452 = DIRECTION('',(1.,0.E+000)); +#68453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68454 = PCURVE('',#63351,#68455); +#68455 = DEFINITIONAL_REPRESENTATION('',(#68456),#68460); +#68456 = LINE('',#68457,#68458); +#68457 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68458 = VECTOR('',#68459,1.); +#68459 = DIRECTION('',(0.258819045102,-0.965925826289)); +#68460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68461 = ORIENTED_EDGE('',*,*,#68462,.F.); +#68462 = EDGE_CURVE('',#68315,#68440,#68463,.T.); +#68463 = SURFACE_CURVE('',#68464,(#68468,#68475),.PCURVE_S1.); +#68464 = LINE('',#68465,#68466); +#68465 = CARTESIAN_POINT('',(-0.125,-1.18088190451,-1.902486398125)); +#68466 = VECTOR('',#68467,1.); +#68467 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68468 = PCURVE('',#62343,#68469); +#68469 = DEFINITIONAL_REPRESENTATION('',(#68470),#68474); +#68470 = LINE('',#68471,#68472); +#68471 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); +#68472 = VECTOR('',#68473,1.); +#68473 = DIRECTION('',(0.E+000,1.)); +#68474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68475 = PCURVE('',#68354,#68476); +#68476 = DEFINITIONAL_REPRESENTATION('',(#68477),#68480); +#68477 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68478,#68479),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#68478 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); +#68479 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#68480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68481 = ORIENTED_EDGE('',*,*,#68314,.F.); +#68482 = ORIENTED_EDGE('',*,*,#68483,.T.); +#68483 = EDGE_CURVE('',#63101,#62328,#68484,.T.); +#68484 = SURFACE_CURVE('',#68485,(#68489,#68496),.PCURVE_S1.); +#68485 = LINE('',#68486,#68487); +#68486 = CARTESIAN_POINT('',(-0.125,-1.105,-1.882153903092)); +#68487 = VECTOR('',#68488,1.); +#68488 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68489 = PCURVE('',#62343,#68490); +#68490 = DEFINITIONAL_REPRESENTATION('',(#68491),#68495); +#68491 = LINE('',#68492,#68493); +#68492 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#68493 = VECTOR('',#68494,1.); +#68494 = DIRECTION('',(-1.,0.E+000)); +#68495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68496 = PCURVE('',#62371,#68497); +#68497 = DEFINITIONAL_REPRESENTATION('',(#68498),#68502); +#68498 = LINE('',#68499,#68500); +#68499 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68500 = VECTOR('',#68501,1.); +#68501 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68503 = ADVANCED_FACE('',(#68504),#62315,.F.); +#68504 = FACE_BOUND('',#68505,.F.); +#68505 = EDGE_LOOP('',(#68506,#68507,#68508,#68509)); +#68506 = ORIENTED_EDGE('',*,*,#63363,.T.); +#68507 = ORIENTED_EDGE('',*,*,#68418,.T.); +#68508 = ORIENTED_EDGE('',*,*,#62299,.T.); +#68509 = ORIENTED_EDGE('',*,*,#63826,.T.); +#68510 = ADVANCED_FACE('',(#68511),#63351,.T.); +#68511 = FACE_BOUND('',#68512,.F.); +#68512 = EDGE_LOOP('',(#68513,#68514,#68537,#68560,#68581,#68582)); +#68513 = ORIENTED_EDGE('',*,*,#68287,.F.); +#68514 = ORIENTED_EDGE('',*,*,#68515,.F.); +#68515 = EDGE_CURVE('',#68516,#68260,#68518,.T.); +#68516 = VERTEX_POINT('',#68517); +#68517 = CARTESIAN_POINT('',(0.125,-1.255,-2.65)); +#68518 = SURFACE_CURVE('',#68519,(#68523,#68530),.PCURVE_S1.); +#68519 = LINE('',#68520,#68521); +#68520 = CARTESIAN_POINT('',(0.125,-1.255,-2.65)); +#68521 = VECTOR('',#68522,1.); +#68522 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68523 = PCURVE('',#63351,#68524); +#68524 = DEFINITIONAL_REPRESENTATION('',(#68525),#68529); +#68525 = LINE('',#68526,#68527); +#68526 = CARTESIAN_POINT('',(2.65,-1.255)); +#68527 = VECTOR('',#68528,1.); +#68528 = DIRECTION('',(0.E+000,1.)); +#68529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68530 = PCURVE('',#68275,#68531); +#68531 = DEFINITIONAL_REPRESENTATION('',(#68532),#68536); +#68532 = LINE('',#68533,#68534); +#68533 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68534 = VECTOR('',#68535,1.); +#68535 = DIRECTION('',(1.,0.E+000)); +#68536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68537 = ORIENTED_EDGE('',*,*,#68538,.F.); +#68538 = EDGE_CURVE('',#68539,#68516,#68541,.T.); +#68539 = VERTEX_POINT('',#68540); +#68540 = CARTESIAN_POINT('',(0.125,-1.255,-1.999078980754)); +#68541 = SURFACE_CURVE('',#68542,(#68546,#68553),.PCURVE_S1.); +#68542 = LINE('',#68543,#68544); +#68543 = CARTESIAN_POINT('',(0.125,-1.255,-1.999078980754)); +#68544 = VECTOR('',#68545,1.); +#68545 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68546 = PCURVE('',#63351,#68547); +#68547 = DEFINITIONAL_REPRESENTATION('',(#68548),#68552); +#68548 = LINE('',#68549,#68550); +#68549 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#68550 = VECTOR('',#68551,1.); +#68551 = DIRECTION('',(1.,0.E+000)); +#68552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68553 = PCURVE('',#68381,#68554); +#68554 = DEFINITIONAL_REPRESENTATION('',(#68555),#68559); +#68555 = LINE('',#68556,#68557); +#68556 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68557 = VECTOR('',#68558,1.); +#68558 = DIRECTION('',(1.,0.E+000)); +#68559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68560 = ORIENTED_EDGE('',*,*,#68561,.F.); +#68561 = EDGE_CURVE('',#68440,#68539,#68562,.T.); +#68562 = SURFACE_CURVE('',#68563,(#68568,#68575),.PCURVE_S1.); +#68563 = CIRCLE('',#68564,0.1); +#68564 = AXIS2_PLACEMENT_3D('',#68565,#68566,#68567); +#68565 = CARTESIAN_POINT('',(0.125,-1.155,-1.999078980754)); +#68566 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68567 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#68568 = PCURVE('',#63351,#68569); +#68569 = DEFINITIONAL_REPRESENTATION('',(#68570),#68574); +#68570 = CIRCLE('',#68571,0.1); +#68571 = AXIS2_PLACEMENT_2D('',#68572,#68573); +#68572 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#68573 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#68574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68575 = PCURVE('',#68354,#68576); +#68576 = DEFINITIONAL_REPRESENTATION('',(#68577),#68580); +#68577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68578,#68579),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#68578 = CARTESIAN_POINT('',(3.403392041389,0.25)); +#68579 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#68580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68581 = ORIENTED_EDGE('',*,*,#68439,.F.); +#68582 = ORIENTED_EDGE('',*,*,#63335,.F.); +#68583 = ADVANCED_FACE('',(#68584),#68275,.T.); +#68584 = FACE_BOUND('',#68585,.F.); +#68585 = EDGE_LOOP('',(#68586,#68587,#68608,#68609)); +#68586 = ORIENTED_EDGE('',*,*,#68393,.F.); +#68587 = ORIENTED_EDGE('',*,*,#68588,.T.); +#68588 = EDGE_CURVE('',#68366,#68516,#68589,.T.); +#68589 = SURFACE_CURVE('',#68590,(#68594,#68601),.PCURVE_S1.); +#68590 = LINE('',#68591,#68592); +#68591 = CARTESIAN_POINT('',(-0.125,-1.255,-2.65)); +#68592 = VECTOR('',#68593,1.); +#68593 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68594 = PCURVE('',#68275,#68595); +#68595 = DEFINITIONAL_REPRESENTATION('',(#68596),#68600); +#68596 = LINE('',#68597,#68598); +#68597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68598 = VECTOR('',#68599,1.); +#68599 = DIRECTION('',(0.E+000,1.)); +#68600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68601 = PCURVE('',#68381,#68602); +#68602 = DEFINITIONAL_REPRESENTATION('',(#68603),#68607); +#68603 = LINE('',#68604,#68605); +#68604 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#68605 = VECTOR('',#68606,1.); +#68606 = DIRECTION('',(0.E+000,1.)); +#68607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68608 = ORIENTED_EDGE('',*,*,#68515,.T.); +#68609 = ORIENTED_EDGE('',*,*,#68259,.F.); +#68610 = ADVANCED_FACE('',(#68611),#68381,.T.); +#68611 = FACE_BOUND('',#68612,.F.); +#68612 = EDGE_LOOP('',(#68613,#68614,#68634,#68635)); +#68613 = ORIENTED_EDGE('',*,*,#68365,.F.); +#68614 = ORIENTED_EDGE('',*,*,#68615,.T.); +#68615 = EDGE_CURVE('',#68338,#68539,#68616,.T.); +#68616 = SURFACE_CURVE('',#68617,(#68621,#68628),.PCURVE_S1.); +#68617 = LINE('',#68618,#68619); +#68618 = CARTESIAN_POINT('',(-0.125,-1.255,-1.999078980754)); +#68619 = VECTOR('',#68620,1.); +#68620 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68621 = PCURVE('',#68381,#68622); +#68622 = DEFINITIONAL_REPRESENTATION('',(#68623),#68627); +#68623 = LINE('',#68624,#68625); +#68624 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68625 = VECTOR('',#68626,1.); +#68626 = DIRECTION('',(0.E+000,1.)); +#68627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68628 = PCURVE('',#68354,#68629); +#68629 = DEFINITIONAL_REPRESENTATION('',(#68630),#68633); +#68630 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68631,#68632),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#68631 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#68632 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#68633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68634 = ORIENTED_EDGE('',*,*,#68538,.T.); +#68635 = ORIENTED_EDGE('',*,*,#68588,.F.); +#68636 = ADVANCED_FACE('',(#68637),#68354,.T.); +#68637 = FACE_BOUND('',#68638,.T.); +#68638 = EDGE_LOOP('',(#68639,#68640,#68641,#68642)); +#68639 = ORIENTED_EDGE('',*,*,#68337,.T.); +#68640 = ORIENTED_EDGE('',*,*,#68615,.T.); +#68641 = ORIENTED_EDGE('',*,*,#68561,.F.); +#68642 = ORIENTED_EDGE('',*,*,#68462,.F.); +#68643 = ADVANCED_FACE('',(#68644),#62371,.T.); +#68644 = FACE_BOUND('',#68645,.F.); +#68645 = EDGE_LOOP('',(#68646,#68647,#68648,#68649)); +#68646 = ORIENTED_EDGE('',*,*,#63098,.F.); +#68647 = ORIENTED_EDGE('',*,*,#63757,.F.); +#68648 = ORIENTED_EDGE('',*,*,#62355,.F.); +#68649 = ORIENTED_EDGE('',*,*,#68483,.F.); +#68650 = ADVANCED_FACE('',(#68651),#64644,.T.); +#68651 = FACE_BOUND('',#68652,.F.); +#68652 = EDGE_LOOP('',(#68653,#68676,#68704,#68725)); +#68653 = ORIENTED_EDGE('',*,*,#68654,.F.); +#68654 = EDGE_CURVE('',#68655,#63285,#68657,.T.); +#68655 = VERTEX_POINT('',#68656); +#68656 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); +#68657 = SURFACE_CURVE('',#68658,(#68662,#68669),.PCURVE_S1.); +#68658 = LINE('',#68659,#68660); +#68659 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); +#68660 = VECTOR('',#68661,1.); +#68661 = DIRECTION('',(0.E+000,0.E+000,1.)); +#68662 = PCURVE('',#64644,#68663); +#68663 = DEFINITIONAL_REPRESENTATION('',(#68664),#68668); +#68664 = LINE('',#68665,#68666); +#68665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68666 = VECTOR('',#68667,1.); +#68667 = DIRECTION('',(1.,0.E+000)); +#68668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68669 = PCURVE('',#63300,#68670); +#68670 = DEFINITIONAL_REPRESENTATION('',(#68671),#68675); +#68671 = LINE('',#68672,#68673); +#68672 = CARTESIAN_POINT('',(2.65,-1.105)); +#68673 = VECTOR('',#68674,1.); +#68674 = DIRECTION('',(-1.,0.E+000)); +#68675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68676 = ORIENTED_EDGE('',*,*,#68677,.T.); +#68677 = EDGE_CURVE('',#68655,#68678,#68680,.T.); +#68678 = VERTEX_POINT('',#68679); +#68679 = CARTESIAN_POINT('',(0.775,-1.105,-2.65)); +#68680 = SURFACE_CURVE('',#68681,(#68685,#68692),.PCURVE_S1.); +#68681 = LINE('',#68682,#68683); +#68682 = CARTESIAN_POINT('',(0.525,-1.105,-2.65)); +#68683 = VECTOR('',#68684,1.); +#68684 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68685 = PCURVE('',#64644,#68686); +#68686 = DEFINITIONAL_REPRESENTATION('',(#68687),#68691); +#68687 = LINE('',#68688,#68689); +#68688 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68689 = VECTOR('',#68690,1.); +#68690 = DIRECTION('',(0.E+000,1.)); +#68691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68692 = PCURVE('',#68693,#68698); +#68693 = PLANE('',#68694); +#68694 = AXIS2_PLACEMENT_3D('',#68695,#68696,#68697); +#68695 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); +#68696 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68697 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68698 = DEFINITIONAL_REPRESENTATION('',(#68699),#68703); +#68699 = LINE('',#68700,#68701); +#68700 = CARTESIAN_POINT('',(0.15,0.E+000)); +#68701 = VECTOR('',#68702,1.); +#68702 = DIRECTION('',(0.E+000,1.)); +#68703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68704 = ORIENTED_EDGE('',*,*,#68705,.T.); +#68705 = EDGE_CURVE('',#68678,#63440,#68706,.T.); +#68706 = SURFACE_CURVE('',#68707,(#68711,#68718),.PCURVE_S1.); +#68707 = LINE('',#68708,#68709); +#68708 = CARTESIAN_POINT('',(0.775,-1.105,-2.65)); +#68709 = VECTOR('',#68710,1.); +#68710 = DIRECTION('',(0.E+000,0.E+000,1.)); +#68711 = PCURVE('',#64644,#68712); +#68712 = DEFINITIONAL_REPRESENTATION('',(#68713),#68717); +#68713 = LINE('',#68714,#68715); +#68714 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68715 = VECTOR('',#68716,1.); +#68716 = DIRECTION('',(1.,0.E+000)); +#68717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68718 = PCURVE('',#63478,#68719); +#68719 = DEFINITIONAL_REPRESENTATION('',(#68720),#68724); +#68720 = LINE('',#68721,#68722); +#68721 = CARTESIAN_POINT('',(2.65,-1.105)); +#68722 = VECTOR('',#68723,1.); +#68723 = DIRECTION('',(-1.,0.E+000)); +#68724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68725 = ORIENTED_EDGE('',*,*,#64630,.F.); +#68726 = ADVANCED_FACE('',(#68727),#63300,.F.); +#68727 = FACE_BOUND('',#68728,.F.); +#68728 = EDGE_LOOP('',(#68729,#68730,#68731,#68754,#68782,#68810)); +#68729 = ORIENTED_EDGE('',*,*,#68654,.T.); +#68730 = ORIENTED_EDGE('',*,*,#63284,.F.); +#68731 = ORIENTED_EDGE('',*,*,#68732,.T.); +#68732 = EDGE_CURVE('',#63257,#68733,#68735,.T.); +#68733 = VERTEX_POINT('',#68734); +#68734 = CARTESIAN_POINT('',(0.525,-1.18088190451,-1.902486398125)); +#68735 = SURFACE_CURVE('',#68736,(#68740,#68747),.PCURVE_S1.); +#68736 = LINE('',#68737,#68738); +#68737 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); +#68738 = VECTOR('',#68739,1.); +#68739 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#68740 = PCURVE('',#63300,#68741); +#68741 = DEFINITIONAL_REPRESENTATION('',(#68742),#68746); +#68742 = LINE('',#68743,#68744); +#68743 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68744 = VECTOR('',#68745,1.); +#68745 = DIRECTION('',(0.258819045102,-0.965925826289)); +#68746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68747 = PCURVE('',#62231,#68748); +#68748 = DEFINITIONAL_REPRESENTATION('',(#68749),#68753); +#68749 = LINE('',#68750,#68751); +#68750 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#68751 = VECTOR('',#68752,1.); +#68752 = DIRECTION('',(1.,0.E+000)); +#68753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68754 = ORIENTED_EDGE('',*,*,#68755,.T.); +#68755 = EDGE_CURVE('',#68733,#68756,#68758,.T.); +#68756 = VERTEX_POINT('',#68757); +#68757 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); +#68758 = SURFACE_CURVE('',#68759,(#68764,#68771),.PCURVE_S1.); +#68759 = CIRCLE('',#68760,0.1); +#68760 = AXIS2_PLACEMENT_3D('',#68761,#68762,#68763); +#68761 = CARTESIAN_POINT('',(0.525,-1.155,-1.999078980754)); +#68762 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68763 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#68764 = PCURVE('',#63300,#68765); +#68765 = DEFINITIONAL_REPRESENTATION('',(#68766),#68770); +#68766 = CIRCLE('',#68767,0.1); +#68767 = AXIS2_PLACEMENT_2D('',#68768,#68769); +#68768 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#68769 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#68770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68771 = PCURVE('',#68772,#68777); +#68772 = CYLINDRICAL_SURFACE('',#68773,0.1); +#68773 = AXIS2_PLACEMENT_3D('',#68774,#68775,#68776); +#68774 = CARTESIAN_POINT('',(0.525,-1.155,-1.999078980754)); +#68775 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68776 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68777 = DEFINITIONAL_REPRESENTATION('',(#68778),#68781); +#68778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68779,#68780),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); +#68779 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); +#68780 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#68781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68782 = ORIENTED_EDGE('',*,*,#68783,.T.); +#68783 = EDGE_CURVE('',#68756,#68784,#68786,.T.); +#68784 = VERTEX_POINT('',#68785); +#68785 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); +#68786 = SURFACE_CURVE('',#68787,(#68791,#68798),.PCURVE_S1.); +#68787 = LINE('',#68788,#68789); +#68788 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); +#68789 = VECTOR('',#68790,1.); +#68790 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68791 = PCURVE('',#63300,#68792); +#68792 = DEFINITIONAL_REPRESENTATION('',(#68793),#68797); +#68793 = LINE('',#68794,#68795); +#68794 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#68795 = VECTOR('',#68796,1.); +#68796 = DIRECTION('',(1.,0.E+000)); +#68797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68798 = PCURVE('',#68799,#68804); +#68799 = PLANE('',#68800); +#68800 = AXIS2_PLACEMENT_3D('',#68801,#68802,#68803); +#68801 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); +#68802 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#68803 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68804 = DEFINITIONAL_REPRESENTATION('',(#68805),#68809); +#68805 = LINE('',#68806,#68807); +#68806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68807 = VECTOR('',#68808,1.); +#68808 = DIRECTION('',(1.,0.E+000)); +#68809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68810 = ORIENTED_EDGE('',*,*,#68811,.T.); +#68811 = EDGE_CURVE('',#68784,#68655,#68812,.T.); +#68812 = SURFACE_CURVE('',#68813,(#68817,#68824),.PCURVE_S1.); +#68813 = LINE('',#68814,#68815); +#68814 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); +#68815 = VECTOR('',#68816,1.); +#68816 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68817 = PCURVE('',#63300,#68818); +#68818 = DEFINITIONAL_REPRESENTATION('',(#68819),#68823); +#68819 = LINE('',#68820,#68821); +#68820 = CARTESIAN_POINT('',(2.65,-1.255)); +#68821 = VECTOR('',#68822,1.); +#68822 = DIRECTION('',(0.E+000,1.)); +#68823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68824 = PCURVE('',#68693,#68825); +#68825 = DEFINITIONAL_REPRESENTATION('',(#68826),#68830); +#68826 = LINE('',#68827,#68828); +#68827 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#68828 = VECTOR('',#68829,1.); +#68829 = DIRECTION('',(1.,0.E+000)); +#68830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68831 = ADVANCED_FACE('',(#68832),#62231,.T.); +#68832 = FACE_BOUND('',#68833,.F.); +#68833 = EDGE_LOOP('',(#68834,#68835,#68856,#68879,#68899,#68900)); +#68834 = ORIENTED_EDGE('',*,*,#62215,.T.); +#68835 = ORIENTED_EDGE('',*,*,#68836,.F.); +#68836 = EDGE_CURVE('',#63463,#62188,#68837,.T.); +#68837 = SURFACE_CURVE('',#68838,(#68842,#68849),.PCURVE_S1.); +#68838 = LINE('',#68839,#68840); +#68839 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); +#68840 = VECTOR('',#68841,1.); +#68841 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68842 = PCURVE('',#62231,#68843); +#68843 = DEFINITIONAL_REPRESENTATION('',(#68844),#68848); +#68844 = LINE('',#68845,#68846); +#68845 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68846 = VECTOR('',#68847,1.); +#68847 = DIRECTION('',(-1.,0.E+000)); +#68848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68849 = PCURVE('',#62203,#68850); +#68850 = DEFINITIONAL_REPRESENTATION('',(#68851),#68855); +#68851 = LINE('',#68852,#68853); +#68852 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68853 = VECTOR('',#68854,1.); +#68854 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68856 = ORIENTED_EDGE('',*,*,#68857,.T.); +#68857 = EDGE_CURVE('',#63463,#68858,#68860,.T.); +#68858 = VERTEX_POINT('',#68859); +#68859 = CARTESIAN_POINT('',(0.775,-1.18088190451,-1.902486398125)); +#68860 = SURFACE_CURVE('',#68861,(#68865,#68872),.PCURVE_S1.); +#68861 = LINE('',#68862,#68863); +#68862 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); +#68863 = VECTOR('',#68864,1.); +#68864 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#68865 = PCURVE('',#62231,#68866); +#68866 = DEFINITIONAL_REPRESENTATION('',(#68867),#68871); +#68867 = LINE('',#68868,#68869); +#68868 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#68869 = VECTOR('',#68870,1.); +#68870 = DIRECTION('',(1.,0.E+000)); +#68871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68872 = PCURVE('',#63478,#68873); +#68873 = DEFINITIONAL_REPRESENTATION('',(#68874),#68878); +#68874 = LINE('',#68875,#68876); +#68875 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68876 = VECTOR('',#68877,1.); +#68877 = DIRECTION('',(0.258819045102,-0.965925826289)); +#68878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68879 = ORIENTED_EDGE('',*,*,#68880,.F.); +#68880 = EDGE_CURVE('',#68733,#68858,#68881,.T.); +#68881 = SURFACE_CURVE('',#68882,(#68886,#68893),.PCURVE_S1.); +#68882 = LINE('',#68883,#68884); +#68883 = CARTESIAN_POINT('',(0.525,-1.18088190451,-1.902486398125)); +#68884 = VECTOR('',#68885,1.); +#68885 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68886 = PCURVE('',#62231,#68887); +#68887 = DEFINITIONAL_REPRESENTATION('',(#68888),#68892); +#68888 = LINE('',#68889,#68890); +#68889 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); +#68890 = VECTOR('',#68891,1.); +#68891 = DIRECTION('',(0.E+000,1.)); +#68892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68893 = PCURVE('',#68772,#68894); +#68894 = DEFINITIONAL_REPRESENTATION('',(#68895),#68898); +#68895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68896,#68897),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); +#68896 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); +#68897 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#68898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68899 = ORIENTED_EDGE('',*,*,#68732,.F.); +#68900 = ORIENTED_EDGE('',*,*,#68901,.T.); +#68901 = EDGE_CURVE('',#63257,#62216,#68902,.T.); +#68902 = SURFACE_CURVE('',#68903,(#68907,#68914),.PCURVE_S1.); +#68903 = LINE('',#68904,#68905); +#68904 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); +#68905 = VECTOR('',#68906,1.); +#68906 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#68907 = PCURVE('',#62231,#68908); +#68908 = DEFINITIONAL_REPRESENTATION('',(#68909),#68913); +#68909 = LINE('',#68910,#68911); +#68910 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#68911 = VECTOR('',#68912,1.); +#68912 = DIRECTION('',(-1.,0.E+000)); +#68913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68914 = PCURVE('',#62259,#68915); +#68915 = DEFINITIONAL_REPRESENTATION('',(#68916),#68920); +#68916 = LINE('',#68917,#68918); +#68917 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#68918 = VECTOR('',#68919,1.); +#68919 = DIRECTION('',(-0.258819045102,0.965925826289)); +#68920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68921 = ADVANCED_FACE('',(#68922),#62203,.F.); +#68922 = FACE_BOUND('',#68923,.F.); +#68923 = EDGE_LOOP('',(#68924,#68925,#68926,#68927)); +#68924 = ORIENTED_EDGE('',*,*,#63490,.T.); +#68925 = ORIENTED_EDGE('',*,*,#68836,.T.); +#68926 = ORIENTED_EDGE('',*,*,#62187,.T.); +#68927 = ORIENTED_EDGE('',*,*,#63853,.T.); +#68928 = ADVANCED_FACE('',(#68929),#63478,.T.); +#68929 = FACE_BOUND('',#68930,.F.); +#68930 = EDGE_LOOP('',(#68931,#68932,#68955,#68978,#68999,#69000)); +#68931 = ORIENTED_EDGE('',*,*,#68705,.F.); +#68932 = ORIENTED_EDGE('',*,*,#68933,.F.); +#68933 = EDGE_CURVE('',#68934,#68678,#68936,.T.); +#68934 = VERTEX_POINT('',#68935); +#68935 = CARTESIAN_POINT('',(0.775,-1.255,-2.65)); +#68936 = SURFACE_CURVE('',#68937,(#68941,#68948),.PCURVE_S1.); +#68937 = LINE('',#68938,#68939); +#68938 = CARTESIAN_POINT('',(0.775,-1.255,-2.65)); +#68939 = VECTOR('',#68940,1.); +#68940 = DIRECTION('',(0.E+000,1.,0.E+000)); +#68941 = PCURVE('',#63478,#68942); +#68942 = DEFINITIONAL_REPRESENTATION('',(#68943),#68947); +#68943 = LINE('',#68944,#68945); +#68944 = CARTESIAN_POINT('',(2.65,-1.255)); +#68945 = VECTOR('',#68946,1.); +#68946 = DIRECTION('',(0.E+000,1.)); +#68947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68948 = PCURVE('',#68693,#68949); +#68949 = DEFINITIONAL_REPRESENTATION('',(#68950),#68954); +#68950 = LINE('',#68951,#68952); +#68951 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68952 = VECTOR('',#68953,1.); +#68953 = DIRECTION('',(1.,0.E+000)); +#68954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68955 = ORIENTED_EDGE('',*,*,#68956,.F.); +#68956 = EDGE_CURVE('',#68957,#68934,#68959,.T.); +#68957 = VERTEX_POINT('',#68958); +#68958 = CARTESIAN_POINT('',(0.775,-1.255,-1.999078980754)); +#68959 = SURFACE_CURVE('',#68960,(#68964,#68971),.PCURVE_S1.); +#68960 = LINE('',#68961,#68962); +#68961 = CARTESIAN_POINT('',(0.775,-1.255,-1.999078980754)); +#68962 = VECTOR('',#68963,1.); +#68963 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#68964 = PCURVE('',#63478,#68965); +#68965 = DEFINITIONAL_REPRESENTATION('',(#68966),#68970); +#68966 = LINE('',#68967,#68968); +#68967 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#68968 = VECTOR('',#68969,1.); +#68969 = DIRECTION('',(1.,0.E+000)); +#68970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68971 = PCURVE('',#68799,#68972); +#68972 = DEFINITIONAL_REPRESENTATION('',(#68973),#68977); +#68973 = LINE('',#68974,#68975); +#68974 = CARTESIAN_POINT('',(0.E+000,0.25)); +#68975 = VECTOR('',#68976,1.); +#68976 = DIRECTION('',(1.,0.E+000)); +#68977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68978 = ORIENTED_EDGE('',*,*,#68979,.F.); +#68979 = EDGE_CURVE('',#68858,#68957,#68980,.T.); +#68980 = SURFACE_CURVE('',#68981,(#68986,#68993),.PCURVE_S1.); +#68981 = CIRCLE('',#68982,0.1); +#68982 = AXIS2_PLACEMENT_3D('',#68983,#68984,#68985); +#68983 = CARTESIAN_POINT('',(0.775,-1.155,-1.999078980754)); +#68984 = DIRECTION('',(1.,0.E+000,0.E+000)); +#68985 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#68986 = PCURVE('',#63478,#68987); +#68987 = DEFINITIONAL_REPRESENTATION('',(#68988),#68992); +#68988 = CIRCLE('',#68989,0.1); +#68989 = AXIS2_PLACEMENT_2D('',#68990,#68991); +#68990 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#68991 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#68992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68993 = PCURVE('',#68772,#68994); +#68994 = DEFINITIONAL_REPRESENTATION('',(#68995),#68998); +#68995 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68996,#68997),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#66387 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); -#66388 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#66389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66390 = ORIENTED_EDGE('',*,*,#66391,.T.); -#66391 = EDGE_CURVE('',#66364,#66392,#66394,.T.); -#66392 = VERTEX_POINT('',#66393); -#66393 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); -#66394 = SURFACE_CURVE('',#66395,(#66399,#66406),.PCURVE_S1.); -#66395 = LINE('',#66396,#66397); -#66396 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); -#66397 = VECTOR('',#66398,1.); -#66398 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66399 = PCURVE('',#60908,#66400); -#66400 = DEFINITIONAL_REPRESENTATION('',(#66401),#66405); -#66401 = LINE('',#66402,#66403); -#66402 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#66403 = VECTOR('',#66404,1.); -#66404 = DIRECTION('',(1.,0.E+000)); -#66405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66406 = PCURVE('',#66407,#66412); -#66407 = PLANE('',#66408); -#66408 = AXIS2_PLACEMENT_3D('',#66409,#66410,#66411); -#66409 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); -#66410 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#66411 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66412 = DEFINITIONAL_REPRESENTATION('',(#66413),#66417); -#66413 = LINE('',#66414,#66415); -#66414 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66415 = VECTOR('',#66416,1.); -#66416 = DIRECTION('',(1.,0.E+000)); -#66417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66418 = ORIENTED_EDGE('',*,*,#66419,.T.); -#66419 = EDGE_CURVE('',#66392,#66263,#66420,.T.); -#66420 = SURFACE_CURVE('',#66421,(#66425,#66432),.PCURVE_S1.); -#66421 = LINE('',#66422,#66423); -#66422 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); -#66423 = VECTOR('',#66424,1.); -#66424 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66425 = PCURVE('',#60908,#66426); -#66426 = DEFINITIONAL_REPRESENTATION('',(#66427),#66431); -#66427 = LINE('',#66428,#66429); -#66428 = CARTESIAN_POINT('',(2.65,-1.255)); -#66429 = VECTOR('',#66430,1.); -#66430 = DIRECTION('',(0.E+000,1.)); -#66431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66432 = PCURVE('',#66301,#66433); -#66433 = DEFINITIONAL_REPRESENTATION('',(#66434),#66438); -#66434 = LINE('',#66435,#66436); -#66435 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66436 = VECTOR('',#66437,1.); -#66437 = DIRECTION('',(1.,0.E+000)); -#66438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66439 = ADVANCED_FACE('',(#66440),#59839,.T.); -#66440 = FACE_BOUND('',#66441,.F.); -#66441 = EDGE_LOOP('',(#66442,#66443,#66464,#66487,#66507,#66508)); -#66442 = ORIENTED_EDGE('',*,*,#59823,.T.); -#66443 = ORIENTED_EDGE('',*,*,#66444,.F.); -#66444 = EDGE_CURVE('',#61071,#59796,#66445,.T.); -#66445 = SURFACE_CURVE('',#66446,(#66450,#66457),.PCURVE_S1.); -#66446 = LINE('',#66447,#66448); -#66447 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); -#66448 = VECTOR('',#66449,1.); -#66449 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#66450 = PCURVE('',#59839,#66451); -#66451 = DEFINITIONAL_REPRESENTATION('',(#66452),#66456); -#66452 = LINE('',#66453,#66454); -#66453 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66454 = VECTOR('',#66455,1.); -#66455 = DIRECTION('',(-1.,0.E+000)); -#66456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66457 = PCURVE('',#59811,#66458); -#66458 = DEFINITIONAL_REPRESENTATION('',(#66459),#66463); -#66459 = LINE('',#66460,#66461); -#66460 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66461 = VECTOR('',#66462,1.); -#66462 = DIRECTION('',(-0.258819045102,0.965925826289)); -#66463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66464 = ORIENTED_EDGE('',*,*,#66465,.T.); -#66465 = EDGE_CURVE('',#61071,#66466,#66468,.T.); -#66466 = VERTEX_POINT('',#66467); -#66467 = CARTESIAN_POINT('',(0.775,-1.18088190451,-1.902486398125)); -#66468 = SURFACE_CURVE('',#66469,(#66473,#66480),.PCURVE_S1.); -#66469 = LINE('',#66470,#66471); -#66470 = CARTESIAN_POINT('',(0.775,-1.105,-1.882153903092)); -#66471 = VECTOR('',#66472,1.); -#66472 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#66473 = PCURVE('',#59839,#66474); -#66474 = DEFINITIONAL_REPRESENTATION('',(#66475),#66479); -#66475 = LINE('',#66476,#66477); -#66476 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66477 = VECTOR('',#66478,1.); -#66478 = DIRECTION('',(1.,0.E+000)); -#66479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66480 = PCURVE('',#61086,#66481); -#66481 = DEFINITIONAL_REPRESENTATION('',(#66482),#66486); -#66482 = LINE('',#66483,#66484); -#66483 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66484 = VECTOR('',#66485,1.); -#66485 = DIRECTION('',(0.258819045102,-0.965925826289)); -#66486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66487 = ORIENTED_EDGE('',*,*,#66488,.F.); -#66488 = EDGE_CURVE('',#66341,#66466,#66489,.T.); -#66489 = SURFACE_CURVE('',#66490,(#66494,#66501),.PCURVE_S1.); -#66490 = LINE('',#66491,#66492); -#66491 = CARTESIAN_POINT('',(0.525,-1.18088190451,-1.902486398125)); -#66492 = VECTOR('',#66493,1.); -#66493 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66494 = PCURVE('',#59839,#66495); -#66495 = DEFINITIONAL_REPRESENTATION('',(#66496),#66500); -#66496 = LINE('',#66497,#66498); -#66497 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); -#66498 = VECTOR('',#66499,1.); -#66499 = DIRECTION('',(0.E+000,1.)); -#66500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66501 = PCURVE('',#66380,#66502); -#66502 = DEFINITIONAL_REPRESENTATION('',(#66503),#66506); -#66503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66504,#66505),.UNSPECIFIED., +#68996 = CARTESIAN_POINT('',(3.403392041389,0.25)); +#68997 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#68998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#68999 = ORIENTED_EDGE('',*,*,#68857,.F.); +#69000 = ORIENTED_EDGE('',*,*,#63462,.F.); +#69001 = ADVANCED_FACE('',(#69002),#68693,.T.); +#69002 = FACE_BOUND('',#69003,.F.); +#69003 = EDGE_LOOP('',(#69004,#69005,#69026,#69027)); +#69004 = ORIENTED_EDGE('',*,*,#68811,.F.); +#69005 = ORIENTED_EDGE('',*,*,#69006,.T.); +#69006 = EDGE_CURVE('',#68784,#68934,#69007,.T.); +#69007 = SURFACE_CURVE('',#69008,(#69012,#69019),.PCURVE_S1.); +#69008 = LINE('',#69009,#69010); +#69009 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); +#69010 = VECTOR('',#69011,1.); +#69011 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69012 = PCURVE('',#68693,#69013); +#69013 = DEFINITIONAL_REPRESENTATION('',(#69014),#69018); +#69014 = LINE('',#69015,#69016); +#69015 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69016 = VECTOR('',#69017,1.); +#69017 = DIRECTION('',(0.E+000,1.)); +#69018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69019 = PCURVE('',#68799,#69020); +#69020 = DEFINITIONAL_REPRESENTATION('',(#69021),#69025); +#69021 = LINE('',#69022,#69023); +#69022 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#69023 = VECTOR('',#69024,1.); +#69024 = DIRECTION('',(0.E+000,1.)); +#69025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69026 = ORIENTED_EDGE('',*,*,#68933,.T.); +#69027 = ORIENTED_EDGE('',*,*,#68677,.F.); +#69028 = ADVANCED_FACE('',(#69029),#68799,.T.); +#69029 = FACE_BOUND('',#69030,.F.); +#69030 = EDGE_LOOP('',(#69031,#69032,#69052,#69053)); +#69031 = ORIENTED_EDGE('',*,*,#68783,.F.); +#69032 = ORIENTED_EDGE('',*,*,#69033,.T.); +#69033 = EDGE_CURVE('',#68756,#68957,#69034,.T.); +#69034 = SURFACE_CURVE('',#69035,(#69039,#69046),.PCURVE_S1.); +#69035 = LINE('',#69036,#69037); +#69036 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); +#69037 = VECTOR('',#69038,1.); +#69038 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69039 = PCURVE('',#68799,#69040); +#69040 = DEFINITIONAL_REPRESENTATION('',(#69041),#69045); +#69041 = LINE('',#69042,#69043); +#69042 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69043 = VECTOR('',#69044,1.); +#69044 = DIRECTION('',(0.E+000,1.)); +#69045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69046 = PCURVE('',#68772,#69047); +#69047 = DEFINITIONAL_REPRESENTATION('',(#69048),#69051); +#69048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69049,#69050),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#66504 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); -#66505 = CARTESIAN_POINT('',(3.403392041386,0.25)); -#66506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66507 = ORIENTED_EDGE('',*,*,#66340,.F.); -#66508 = ORIENTED_EDGE('',*,*,#66509,.T.); -#66509 = EDGE_CURVE('',#60865,#59824,#66510,.T.); -#66510 = SURFACE_CURVE('',#66511,(#66515,#66522),.PCURVE_S1.); -#66511 = LINE('',#66512,#66513); -#66512 = CARTESIAN_POINT('',(0.525,-1.105,-1.882153903092)); -#66513 = VECTOR('',#66514,1.); -#66514 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#66515 = PCURVE('',#59839,#66516); -#66516 = DEFINITIONAL_REPRESENTATION('',(#66517),#66521); -#66517 = LINE('',#66518,#66519); -#66518 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#66519 = VECTOR('',#66520,1.); -#66520 = DIRECTION('',(-1.,0.E+000)); -#66521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66522 = PCURVE('',#59867,#66523); -#66523 = DEFINITIONAL_REPRESENTATION('',(#66524),#66528); -#66524 = LINE('',#66525,#66526); -#66525 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66526 = VECTOR('',#66527,1.); -#66527 = DIRECTION('',(-0.258819045102,0.965925826289)); -#66528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66529 = ADVANCED_FACE('',(#66530),#59811,.F.); -#66530 = FACE_BOUND('',#66531,.F.); -#66531 = EDGE_LOOP('',(#66532,#66533,#66534,#66535)); -#66532 = ORIENTED_EDGE('',*,*,#61098,.T.); -#66533 = ORIENTED_EDGE('',*,*,#66444,.T.); -#66534 = ORIENTED_EDGE('',*,*,#59795,.T.); -#66535 = ORIENTED_EDGE('',*,*,#61461,.T.); -#66536 = ADVANCED_FACE('',(#66537),#61086,.T.); -#66537 = FACE_BOUND('',#66538,.F.); -#66538 = EDGE_LOOP('',(#66539,#66540,#66563,#66586,#66607,#66608)); -#66539 = ORIENTED_EDGE('',*,*,#66313,.F.); -#66540 = ORIENTED_EDGE('',*,*,#66541,.F.); -#66541 = EDGE_CURVE('',#66542,#66286,#66544,.T.); -#66542 = VERTEX_POINT('',#66543); -#66543 = CARTESIAN_POINT('',(0.775,-1.255,-2.65)); -#66544 = SURFACE_CURVE('',#66545,(#66549,#66556),.PCURVE_S1.); -#66545 = LINE('',#66546,#66547); -#66546 = CARTESIAN_POINT('',(0.775,-1.255,-2.65)); -#66547 = VECTOR('',#66548,1.); -#66548 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66549 = PCURVE('',#61086,#66550); -#66550 = DEFINITIONAL_REPRESENTATION('',(#66551),#66555); -#66551 = LINE('',#66552,#66553); -#66552 = CARTESIAN_POINT('',(2.65,-1.255)); -#66553 = VECTOR('',#66554,1.); -#66554 = DIRECTION('',(0.E+000,1.)); -#66555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66556 = PCURVE('',#66301,#66557); -#66557 = DEFINITIONAL_REPRESENTATION('',(#66558),#66562); -#66558 = LINE('',#66559,#66560); -#66559 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66560 = VECTOR('',#66561,1.); -#66561 = DIRECTION('',(1.,0.E+000)); -#66562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66563 = ORIENTED_EDGE('',*,*,#66564,.F.); -#66564 = EDGE_CURVE('',#66565,#66542,#66567,.T.); -#66565 = VERTEX_POINT('',#66566); -#66566 = CARTESIAN_POINT('',(0.775,-1.255,-1.999078980754)); -#66567 = SURFACE_CURVE('',#66568,(#66572,#66579),.PCURVE_S1.); -#66568 = LINE('',#66569,#66570); -#66569 = CARTESIAN_POINT('',(0.775,-1.255,-1.999078980754)); -#66570 = VECTOR('',#66571,1.); -#66571 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66572 = PCURVE('',#61086,#66573); -#66573 = DEFINITIONAL_REPRESENTATION('',(#66574),#66578); -#66574 = LINE('',#66575,#66576); -#66575 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#66576 = VECTOR('',#66577,1.); -#66577 = DIRECTION('',(1.,0.E+000)); -#66578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66579 = PCURVE('',#66407,#66580); -#66580 = DEFINITIONAL_REPRESENTATION('',(#66581),#66585); -#66581 = LINE('',#66582,#66583); -#66582 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66583 = VECTOR('',#66584,1.); -#66584 = DIRECTION('',(1.,0.E+000)); -#66585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66586 = ORIENTED_EDGE('',*,*,#66587,.F.); -#66587 = EDGE_CURVE('',#66466,#66565,#66588,.T.); -#66588 = SURFACE_CURVE('',#66589,(#66594,#66601),.PCURVE_S1.); -#66589 = CIRCLE('',#66590,0.1); -#66590 = AXIS2_PLACEMENT_3D('',#66591,#66592,#66593); -#66591 = CARTESIAN_POINT('',(0.775,-1.155,-1.999078980754)); -#66592 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66593 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#66594 = PCURVE('',#61086,#66595); -#66595 = DEFINITIONAL_REPRESENTATION('',(#66596),#66600); -#66596 = CIRCLE('',#66597,0.1); -#66597 = AXIS2_PLACEMENT_2D('',#66598,#66599); -#66598 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#66599 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#66600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66601 = PCURVE('',#66380,#66602); -#66602 = DEFINITIONAL_REPRESENTATION('',(#66603),#66606); -#66603 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66604,#66605),.UNSPECIFIED., +#69049 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#69050 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#69051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69052 = ORIENTED_EDGE('',*,*,#68956,.T.); +#69053 = ORIENTED_EDGE('',*,*,#69006,.F.); +#69054 = ADVANCED_FACE('',(#69055),#68772,.T.); +#69055 = FACE_BOUND('',#69056,.T.); +#69056 = EDGE_LOOP('',(#69057,#69058,#69059,#69060)); +#69057 = ORIENTED_EDGE('',*,*,#68755,.T.); +#69058 = ORIENTED_EDGE('',*,*,#69033,.T.); +#69059 = ORIENTED_EDGE('',*,*,#68979,.F.); +#69060 = ORIENTED_EDGE('',*,*,#68880,.F.); +#69061 = ADVANCED_FACE('',(#69062),#62259,.T.); +#69062 = FACE_BOUND('',#69063,.F.); +#69063 = EDGE_LOOP('',(#69064,#69065,#69066,#69067)); +#69064 = ORIENTED_EDGE('',*,*,#63254,.F.); +#69065 = ORIENTED_EDGE('',*,*,#63804,.F.); +#69066 = ORIENTED_EDGE('',*,*,#62243,.F.); +#69067 = ORIENTED_EDGE('',*,*,#68901,.F.); +#69068 = ADVANCED_FACE('',(#69069),#64671,.T.); +#69069 = FACE_BOUND('',#69070,.F.); +#69070 = EDGE_LOOP('',(#69071,#69094,#69122,#69143)); +#69071 = ORIENTED_EDGE('',*,*,#69072,.F.); +#69072 = EDGE_CURVE('',#69073,#63412,#69075,.T.); +#69073 = VERTEX_POINT('',#69074); +#69074 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); +#69075 = SURFACE_CURVE('',#69076,(#69080,#69087),.PCURVE_S1.); +#69076 = LINE('',#69077,#69078); +#69077 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); +#69078 = VECTOR('',#69079,1.); +#69079 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69080 = PCURVE('',#64671,#69081); +#69081 = DEFINITIONAL_REPRESENTATION('',(#69082),#69086); +#69082 = LINE('',#69083,#69084); +#69083 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69084 = VECTOR('',#69085,1.); +#69085 = DIRECTION('',(1.,0.E+000)); +#69086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69087 = PCURVE('',#63427,#69088); +#69088 = DEFINITIONAL_REPRESENTATION('',(#69089),#69093); +#69089 = LINE('',#69090,#69091); +#69090 = CARTESIAN_POINT('',(2.65,-1.105)); +#69091 = VECTOR('',#69092,1.); +#69092 = DIRECTION('',(-1.,0.E+000)); +#69093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69094 = ORIENTED_EDGE('',*,*,#69095,.T.); +#69095 = EDGE_CURVE('',#69073,#69096,#69098,.T.); +#69096 = VERTEX_POINT('',#69097); +#69097 = CARTESIAN_POINT('',(1.425,-1.105,-2.65)); +#69098 = SURFACE_CURVE('',#69099,(#69103,#69110),.PCURVE_S1.); +#69099 = LINE('',#69100,#69101); +#69100 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); +#69101 = VECTOR('',#69102,1.); +#69102 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69103 = PCURVE('',#64671,#69104); +#69104 = DEFINITIONAL_REPRESENTATION('',(#69105),#69109); +#69105 = LINE('',#69106,#69107); +#69106 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69107 = VECTOR('',#69108,1.); +#69108 = DIRECTION('',(0.E+000,1.)); +#69109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69110 = PCURVE('',#69111,#69116); +#69111 = PLANE('',#69112); +#69112 = AXIS2_PLACEMENT_3D('',#69113,#69114,#69115); +#69113 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); +#69114 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#69115 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69116 = DEFINITIONAL_REPRESENTATION('',(#69117),#69121); +#69117 = LINE('',#69118,#69119); +#69118 = CARTESIAN_POINT('',(0.15,0.E+000)); +#69119 = VECTOR('',#69120,1.); +#69120 = DIRECTION('',(0.E+000,1.)); +#69121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69122 = ORIENTED_EDGE('',*,*,#69123,.T.); +#69123 = EDGE_CURVE('',#69096,#63585,#69124,.T.); +#69124 = SURFACE_CURVE('',#69125,(#69129,#69136),.PCURVE_S1.); +#69125 = LINE('',#69126,#69127); +#69126 = CARTESIAN_POINT('',(1.425,-1.105,-2.65)); +#69127 = VECTOR('',#69128,1.); +#69128 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69129 = PCURVE('',#64671,#69130); +#69130 = DEFINITIONAL_REPRESENTATION('',(#69131),#69135); +#69131 = LINE('',#69132,#69133); +#69132 = CARTESIAN_POINT('',(0.E+000,0.25)); +#69133 = VECTOR('',#69134,1.); +#69134 = DIRECTION('',(1.,0.E+000)); +#69135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69136 = PCURVE('',#63621,#69137); +#69137 = DEFINITIONAL_REPRESENTATION('',(#69138),#69142); +#69138 = LINE('',#69139,#69140); +#69139 = CARTESIAN_POINT('',(2.65,-1.105)); +#69140 = VECTOR('',#69141,1.); +#69141 = DIRECTION('',(-1.,0.E+000)); +#69142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69143 = ORIENTED_EDGE('',*,*,#64657,.F.); +#69144 = ADVANCED_FACE('',(#69145),#63427,.F.); +#69145 = FACE_BOUND('',#69146,.F.); +#69146 = EDGE_LOOP('',(#69147,#69148,#69149,#69172,#69200,#69228)); +#69147 = ORIENTED_EDGE('',*,*,#69072,.T.); +#69148 = ORIENTED_EDGE('',*,*,#63411,.F.); +#69149 = ORIENTED_EDGE('',*,*,#69150,.T.); +#69150 = EDGE_CURVE('',#62741,#69151,#69153,.T.); +#69151 = VERTEX_POINT('',#69152); +#69152 = CARTESIAN_POINT('',(1.175,-1.18088190451,-1.902486398125)); +#69153 = SURFACE_CURVE('',#69154,(#69158,#69165),.PCURVE_S1.); +#69154 = LINE('',#69155,#69156); +#69155 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); +#69156 = VECTOR('',#69157,1.); +#69157 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#69158 = PCURVE('',#63427,#69159); +#69159 = DEFINITIONAL_REPRESENTATION('',(#69160),#69164); +#69160 = LINE('',#69161,#69162); +#69161 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#69162 = VECTOR('',#69163,1.); +#69163 = DIRECTION('',(0.258819045102,-0.965925826289)); +#69164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69165 = PCURVE('',#62723,#69166); +#69166 = DEFINITIONAL_REPRESENTATION('',(#69167),#69171); +#69167 = LINE('',#69168,#69169); +#69168 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); +#69169 = VECTOR('',#69170,1.); +#69170 = DIRECTION('',(1.,0.E+000)); +#69171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69172 = ORIENTED_EDGE('',*,*,#69173,.T.); +#69173 = EDGE_CURVE('',#69151,#69174,#69176,.T.); +#69174 = VERTEX_POINT('',#69175); +#69175 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); +#69176 = SURFACE_CURVE('',#69177,(#69182,#69189),.PCURVE_S1.); +#69177 = CIRCLE('',#69178,0.1); +#69178 = AXIS2_PLACEMENT_3D('',#69179,#69180,#69181); +#69179 = CARTESIAN_POINT('',(1.175,-1.155,-1.999078980754)); +#69180 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69181 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#69182 = PCURVE('',#63427,#69183); +#69183 = DEFINITIONAL_REPRESENTATION('',(#69184),#69188); +#69184 = CIRCLE('',#69185,0.1); +#69185 = AXIS2_PLACEMENT_2D('',#69186,#69187); +#69186 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#69187 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#69188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69189 = PCURVE('',#69190,#69195); +#69190 = CYLINDRICAL_SURFACE('',#69191,0.1); +#69191 = AXIS2_PLACEMENT_3D('',#69192,#69193,#69194); +#69192 = CARTESIAN_POINT('',(1.175,-1.155,-1.999078980754)); +#69193 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69194 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#69195 = DEFINITIONAL_REPRESENTATION('',(#69196),#69199); +#69196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69197,#69198),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#66604 = CARTESIAN_POINT('',(3.403392041389,0.25)); -#66605 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#66606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66607 = ORIENTED_EDGE('',*,*,#66465,.F.); -#66608 = ORIENTED_EDGE('',*,*,#61070,.F.); -#66609 = ADVANCED_FACE('',(#66610),#66301,.T.); -#66610 = FACE_BOUND('',#66611,.F.); -#66611 = EDGE_LOOP('',(#66612,#66613,#66634,#66635)); -#66612 = ORIENTED_EDGE('',*,*,#66419,.F.); -#66613 = ORIENTED_EDGE('',*,*,#66614,.T.); -#66614 = EDGE_CURVE('',#66392,#66542,#66615,.T.); -#66615 = SURFACE_CURVE('',#66616,(#66620,#66627),.PCURVE_S1.); -#66616 = LINE('',#66617,#66618); -#66617 = CARTESIAN_POINT('',(0.525,-1.255,-2.65)); -#66618 = VECTOR('',#66619,1.); -#66619 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66620 = PCURVE('',#66301,#66621); -#66621 = DEFINITIONAL_REPRESENTATION('',(#66622),#66626); -#66622 = LINE('',#66623,#66624); -#66623 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66624 = VECTOR('',#66625,1.); -#66625 = DIRECTION('',(0.E+000,1.)); -#66626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66627 = PCURVE('',#66407,#66628); -#66628 = DEFINITIONAL_REPRESENTATION('',(#66629),#66633); -#66629 = LINE('',#66630,#66631); -#66630 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); -#66631 = VECTOR('',#66632,1.); -#66632 = DIRECTION('',(0.E+000,1.)); -#66633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66634 = ORIENTED_EDGE('',*,*,#66541,.T.); -#66635 = ORIENTED_EDGE('',*,*,#66285,.F.); -#66636 = ADVANCED_FACE('',(#66637),#66407,.T.); -#66637 = FACE_BOUND('',#66638,.F.); -#66638 = EDGE_LOOP('',(#66639,#66640,#66660,#66661)); -#66639 = ORIENTED_EDGE('',*,*,#66391,.F.); -#66640 = ORIENTED_EDGE('',*,*,#66641,.T.); -#66641 = EDGE_CURVE('',#66364,#66565,#66642,.T.); -#66642 = SURFACE_CURVE('',#66643,(#66647,#66654),.PCURVE_S1.); -#66643 = LINE('',#66644,#66645); -#66644 = CARTESIAN_POINT('',(0.525,-1.255,-1.999078980754)); -#66645 = VECTOR('',#66646,1.); -#66646 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66647 = PCURVE('',#66407,#66648); -#66648 = DEFINITIONAL_REPRESENTATION('',(#66649),#66653); -#66649 = LINE('',#66650,#66651); -#66650 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66651 = VECTOR('',#66652,1.); -#66652 = DIRECTION('',(0.E+000,1.)); -#66653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66654 = PCURVE('',#66380,#66655); -#66655 = DEFINITIONAL_REPRESENTATION('',(#66656),#66659); -#66656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66657,#66658),.UNSPECIFIED., +#69197 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); +#69198 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#69199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69200 = ORIENTED_EDGE('',*,*,#69201,.T.); +#69201 = EDGE_CURVE('',#69174,#69202,#69204,.T.); +#69202 = VERTEX_POINT('',#69203); +#69203 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); +#69204 = SURFACE_CURVE('',#69205,(#69209,#69216),.PCURVE_S1.); +#69205 = LINE('',#69206,#69207); +#69206 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); +#69207 = VECTOR('',#69208,1.); +#69208 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#69209 = PCURVE('',#63427,#69210); +#69210 = DEFINITIONAL_REPRESENTATION('',(#69211),#69215); +#69211 = LINE('',#69212,#69213); +#69212 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#69213 = VECTOR('',#69214,1.); +#69214 = DIRECTION('',(1.,0.E+000)); +#69215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69216 = PCURVE('',#69217,#69222); +#69217 = PLANE('',#69218); +#69218 = AXIS2_PLACEMENT_3D('',#69219,#69220,#69221); +#69219 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); +#69220 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#69221 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#69222 = DEFINITIONAL_REPRESENTATION('',(#69223),#69227); +#69223 = LINE('',#69224,#69225); +#69224 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69225 = VECTOR('',#69226,1.); +#69226 = DIRECTION('',(1.,0.E+000)); +#69227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69228 = ORIENTED_EDGE('',*,*,#69229,.T.); +#69229 = EDGE_CURVE('',#69202,#69073,#69230,.T.); +#69230 = SURFACE_CURVE('',#69231,(#69235,#69242),.PCURVE_S1.); +#69231 = LINE('',#69232,#69233); +#69232 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); +#69233 = VECTOR('',#69234,1.); +#69234 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69235 = PCURVE('',#63427,#69236); +#69236 = DEFINITIONAL_REPRESENTATION('',(#69237),#69241); +#69237 = LINE('',#69238,#69239); +#69238 = CARTESIAN_POINT('',(2.65,-1.255)); +#69239 = VECTOR('',#69240,1.); +#69240 = DIRECTION('',(0.E+000,1.)); +#69241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69242 = PCURVE('',#69111,#69243); +#69243 = DEFINITIONAL_REPRESENTATION('',(#69244),#69248); +#69244 = LINE('',#69245,#69246); +#69245 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69246 = VECTOR('',#69247,1.); +#69247 = DIRECTION('',(1.,0.E+000)); +#69248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69249 = ADVANCED_FACE('',(#69250),#62723,.T.); +#69250 = FACE_BOUND('',#69251,.F.); +#69251 = EDGE_LOOP('',(#69252,#69253,#69274,#69297,#69317,#69318)); +#69252 = ORIENTED_EDGE('',*,*,#62709,.T.); +#69253 = ORIENTED_EDGE('',*,*,#69254,.F.); +#69254 = EDGE_CURVE('',#63540,#62682,#69255,.T.); +#69255 = SURFACE_CURVE('',#69256,(#69260,#69267),.PCURVE_S1.); +#69256 = LINE('',#69257,#69258); +#69257 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); +#69258 = VECTOR('',#69259,1.); +#69259 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); +#69260 = PCURVE('',#62723,#69261); +#69261 = DEFINITIONAL_REPRESENTATION('',(#69262),#69266); +#69262 = LINE('',#69263,#69264); +#69263 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#69264 = VECTOR('',#69265,1.); +#69265 = DIRECTION('',(-1.,0.E+000)); +#69266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69267 = PCURVE('',#62697,#69268); +#69268 = DEFINITIONAL_REPRESENTATION('',(#69269),#69273); +#69269 = LINE('',#69270,#69271); +#69270 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#69271 = VECTOR('',#69272,1.); +#69272 = DIRECTION('',(-0.258819045102,0.965925826289)); +#69273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69274 = ORIENTED_EDGE('',*,*,#69275,.T.); +#69275 = EDGE_CURVE('',#63540,#69276,#69278,.T.); +#69276 = VERTEX_POINT('',#69277); +#69277 = CARTESIAN_POINT('',(1.425,-1.18088190451,-1.902486398125)); +#69278 = SURFACE_CURVE('',#69279,(#69283,#69290),.PCURVE_S1.); +#69279 = LINE('',#69280,#69281); +#69280 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); +#69281 = VECTOR('',#69282,1.); +#69282 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); +#69283 = PCURVE('',#62723,#69284); +#69284 = DEFINITIONAL_REPRESENTATION('',(#69285),#69289); +#69285 = LINE('',#69286,#69287); +#69286 = CARTESIAN_POINT('',(0.124233141649,0.25)); +#69287 = VECTOR('',#69288,1.); +#69288 = DIRECTION('',(1.,0.E+000)); +#69289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69290 = PCURVE('',#63621,#69291); +#69291 = DEFINITIONAL_REPRESENTATION('',(#69292),#69296); +#69292 = LINE('',#69293,#69294); +#69293 = CARTESIAN_POINT('',(1.882153903092,-1.105)); +#69294 = VECTOR('',#69295,1.); +#69295 = DIRECTION('',(0.258819045102,-0.965925826289)); +#69296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69297 = ORIENTED_EDGE('',*,*,#69298,.F.); +#69298 = EDGE_CURVE('',#69151,#69276,#69299,.T.); +#69299 = SURFACE_CURVE('',#69300,(#69304,#69311),.PCURVE_S1.); +#69300 = LINE('',#69301,#69302); +#69301 = CARTESIAN_POINT('',(1.175,-1.18088190451,-1.902486398125)); +#69302 = VECTOR('',#69303,1.); +#69303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69304 = PCURVE('',#62723,#69305); +#69305 = DEFINITIONAL_REPRESENTATION('',(#69306),#69310); +#69306 = LINE('',#69307,#69308); +#69307 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); +#69308 = VECTOR('',#69309,1.); +#69309 = DIRECTION('',(0.E+000,1.)); +#69310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69311 = PCURVE('',#69190,#69312); +#69312 = DEFINITIONAL_REPRESENTATION('',(#69313),#69316); +#69313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69314,#69315),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#66657 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#66658 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#66659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66660 = ORIENTED_EDGE('',*,*,#66564,.T.); -#66661 = ORIENTED_EDGE('',*,*,#66614,.F.); -#66662 = ADVANCED_FACE('',(#66663),#66380,.T.); -#66663 = FACE_BOUND('',#66664,.T.); -#66664 = EDGE_LOOP('',(#66665,#66666,#66667,#66668)); -#66665 = ORIENTED_EDGE('',*,*,#66363,.T.); -#66666 = ORIENTED_EDGE('',*,*,#66641,.T.); -#66667 = ORIENTED_EDGE('',*,*,#66587,.F.); -#66668 = ORIENTED_EDGE('',*,*,#66488,.F.); -#66669 = ADVANCED_FACE('',(#66670),#59867,.T.); -#66670 = FACE_BOUND('',#66671,.F.); -#66671 = EDGE_LOOP('',(#66672,#66673,#66674,#66675)); -#66672 = ORIENTED_EDGE('',*,*,#60862,.F.); -#66673 = ORIENTED_EDGE('',*,*,#61412,.F.); -#66674 = ORIENTED_EDGE('',*,*,#59851,.F.); -#66675 = ORIENTED_EDGE('',*,*,#66509,.F.); -#66676 = ADVANCED_FACE('',(#66677),#62279,.T.); -#66677 = FACE_BOUND('',#66678,.F.); -#66678 = EDGE_LOOP('',(#66679,#66702,#66730,#66751)); -#66679 = ORIENTED_EDGE('',*,*,#66680,.F.); -#66680 = EDGE_CURVE('',#66681,#61020,#66683,.T.); -#66681 = VERTEX_POINT('',#66682); -#66682 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); -#66683 = SURFACE_CURVE('',#66684,(#66688,#66695),.PCURVE_S1.); -#66684 = LINE('',#66685,#66686); -#66685 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); -#66686 = VECTOR('',#66687,1.); -#66687 = DIRECTION('',(0.E+000,0.E+000,1.)); -#66688 = PCURVE('',#62279,#66689); -#66689 = DEFINITIONAL_REPRESENTATION('',(#66690),#66694); -#66690 = LINE('',#66691,#66692); -#66691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66692 = VECTOR('',#66693,1.); -#66693 = DIRECTION('',(1.,0.E+000)); -#66694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66695 = PCURVE('',#61035,#66696); -#66696 = DEFINITIONAL_REPRESENTATION('',(#66697),#66701); -#66697 = LINE('',#66698,#66699); -#66698 = CARTESIAN_POINT('',(2.65,-1.105)); -#66699 = VECTOR('',#66700,1.); -#66700 = DIRECTION('',(-1.,0.E+000)); -#66701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66702 = ORIENTED_EDGE('',*,*,#66703,.T.); -#66703 = EDGE_CURVE('',#66681,#66704,#66706,.T.); -#66704 = VERTEX_POINT('',#66705); -#66705 = CARTESIAN_POINT('',(1.425,-1.105,-2.65)); -#66706 = SURFACE_CURVE('',#66707,(#66711,#66718),.PCURVE_S1.); -#66707 = LINE('',#66708,#66709); -#66708 = CARTESIAN_POINT('',(1.175,-1.105,-2.65)); -#66709 = VECTOR('',#66710,1.); -#66710 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66711 = PCURVE('',#62279,#66712); -#66712 = DEFINITIONAL_REPRESENTATION('',(#66713),#66717); -#66713 = LINE('',#66714,#66715); -#66714 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66715 = VECTOR('',#66716,1.); -#66716 = DIRECTION('',(0.E+000,1.)); -#66717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66718 = PCURVE('',#66719,#66724); -#66719 = PLANE('',#66720); -#66720 = AXIS2_PLACEMENT_3D('',#66721,#66722,#66723); -#66721 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); -#66722 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66723 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66724 = DEFINITIONAL_REPRESENTATION('',(#66725),#66729); -#66725 = LINE('',#66726,#66727); -#66726 = CARTESIAN_POINT('',(0.15,0.E+000)); -#66727 = VECTOR('',#66728,1.); -#66728 = DIRECTION('',(0.E+000,1.)); -#66729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66730 = ORIENTED_EDGE('',*,*,#66731,.T.); -#66731 = EDGE_CURVE('',#66704,#61193,#66732,.T.); -#66732 = SURFACE_CURVE('',#66733,(#66737,#66744),.PCURVE_S1.); -#66733 = LINE('',#66734,#66735); -#66734 = CARTESIAN_POINT('',(1.425,-1.105,-2.65)); -#66735 = VECTOR('',#66736,1.); -#66736 = DIRECTION('',(0.E+000,0.E+000,1.)); -#66737 = PCURVE('',#62279,#66738); -#66738 = DEFINITIONAL_REPRESENTATION('',(#66739),#66743); -#66739 = LINE('',#66740,#66741); -#66740 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66741 = VECTOR('',#66742,1.); -#66742 = DIRECTION('',(1.,0.E+000)); -#66743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66744 = PCURVE('',#61229,#66745); -#66745 = DEFINITIONAL_REPRESENTATION('',(#66746),#66750); -#66746 = LINE('',#66747,#66748); -#66747 = CARTESIAN_POINT('',(2.65,-1.105)); -#66748 = VECTOR('',#66749,1.); -#66749 = DIRECTION('',(-1.,0.E+000)); -#66750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66751 = ORIENTED_EDGE('',*,*,#62265,.F.); -#66752 = ADVANCED_FACE('',(#66753),#61035,.F.); -#66753 = FACE_BOUND('',#66754,.F.); -#66754 = EDGE_LOOP('',(#66755,#66756,#66757,#66780,#66808,#66836)); -#66755 = ORIENTED_EDGE('',*,*,#66680,.T.); -#66756 = ORIENTED_EDGE('',*,*,#61019,.F.); -#66757 = ORIENTED_EDGE('',*,*,#66758,.T.); -#66758 = EDGE_CURVE('',#60349,#66759,#66761,.T.); -#66759 = VERTEX_POINT('',#66760); -#66760 = CARTESIAN_POINT('',(1.175,-1.18088190451,-1.902486398125)); -#66761 = SURFACE_CURVE('',#66762,(#66766,#66773),.PCURVE_S1.); -#66762 = LINE('',#66763,#66764); -#66763 = CARTESIAN_POINT('',(1.175,-1.105,-1.882153903092)); -#66764 = VECTOR('',#66765,1.); -#66765 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#66766 = PCURVE('',#61035,#66767); -#66767 = DEFINITIONAL_REPRESENTATION('',(#66768),#66772); -#66768 = LINE('',#66769,#66770); -#66769 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66770 = VECTOR('',#66771,1.); -#66771 = DIRECTION('',(0.258819045102,-0.965925826289)); -#66772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66773 = PCURVE('',#60331,#66774); -#66774 = DEFINITIONAL_REPRESENTATION('',(#66775),#66779); -#66775 = LINE('',#66776,#66777); -#66776 = CARTESIAN_POINT('',(0.124233141649,0.E+000)); -#66777 = VECTOR('',#66778,1.); -#66778 = DIRECTION('',(1.,0.E+000)); -#66779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66780 = ORIENTED_EDGE('',*,*,#66781,.T.); -#66781 = EDGE_CURVE('',#66759,#66782,#66784,.T.); -#66782 = VERTEX_POINT('',#66783); -#66783 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); -#66784 = SURFACE_CURVE('',#66785,(#66790,#66797),.PCURVE_S1.); -#66785 = CIRCLE('',#66786,0.1); -#66786 = AXIS2_PLACEMENT_3D('',#66787,#66788,#66789); -#66787 = CARTESIAN_POINT('',(1.175,-1.155,-1.999078980754)); -#66788 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66789 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#66790 = PCURVE('',#61035,#66791); -#66791 = DEFINITIONAL_REPRESENTATION('',(#66792),#66796); -#66792 = CIRCLE('',#66793,0.1); -#66793 = AXIS2_PLACEMENT_2D('',#66794,#66795); -#66794 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#66795 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#66796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66797 = PCURVE('',#66798,#66803); -#66798 = CYLINDRICAL_SURFACE('',#66799,0.1); -#66799 = AXIS2_PLACEMENT_3D('',#66800,#66801,#66802); -#66800 = CARTESIAN_POINT('',(1.175,-1.155,-1.999078980754)); -#66801 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66802 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66803 = DEFINITIONAL_REPRESENTATION('',(#66804),#66807); -#66804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66805,#66806),.UNSPECIFIED., +#69314 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); +#69315 = CARTESIAN_POINT('',(3.403392041386,0.25)); +#69316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69317 = ORIENTED_EDGE('',*,*,#69150,.F.); +#69318 = ORIENTED_EDGE('',*,*,#62790,.T.); +#69319 = ADVANCED_FACE('',(#69320),#62697,.F.); +#69320 = FACE_BOUND('',#69321,.F.); +#69321 = EDGE_LOOP('',(#69322,#69323,#69324,#69325)); +#69322 = ORIENTED_EDGE('',*,*,#63537,.T.); +#69323 = ORIENTED_EDGE('',*,*,#69254,.T.); +#69324 = ORIENTED_EDGE('',*,*,#62681,.T.); +#69325 = ORIENTED_EDGE('',*,*,#63878,.T.); +#69326 = ADVANCED_FACE('',(#69327),#63621,.T.); +#69327 = FACE_BOUND('',#69328,.F.); +#69328 = EDGE_LOOP('',(#69329,#69330,#69353,#69376,#69397,#69398)); +#69329 = ORIENTED_EDGE('',*,*,#69123,.F.); +#69330 = ORIENTED_EDGE('',*,*,#69331,.F.); +#69331 = EDGE_CURVE('',#69332,#69096,#69334,.T.); +#69332 = VERTEX_POINT('',#69333); +#69333 = CARTESIAN_POINT('',(1.425,-1.255,-2.65)); +#69334 = SURFACE_CURVE('',#69335,(#69339,#69346),.PCURVE_S1.); +#69335 = LINE('',#69336,#69337); +#69336 = CARTESIAN_POINT('',(1.425,-1.255,-2.65)); +#69337 = VECTOR('',#69338,1.); +#69338 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69339 = PCURVE('',#63621,#69340); +#69340 = DEFINITIONAL_REPRESENTATION('',(#69341),#69345); +#69341 = LINE('',#69342,#69343); +#69342 = CARTESIAN_POINT('',(2.65,-1.255)); +#69343 = VECTOR('',#69344,1.); +#69344 = DIRECTION('',(0.E+000,1.)); +#69345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69346 = PCURVE('',#69111,#69347); +#69347 = DEFINITIONAL_REPRESENTATION('',(#69348),#69352); +#69348 = LINE('',#69349,#69350); +#69349 = CARTESIAN_POINT('',(0.E+000,0.25)); +#69350 = VECTOR('',#69351,1.); +#69351 = DIRECTION('',(1.,0.E+000)); +#69352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69353 = ORIENTED_EDGE('',*,*,#69354,.F.); +#69354 = EDGE_CURVE('',#69355,#69332,#69357,.T.); +#69355 = VERTEX_POINT('',#69356); +#69356 = CARTESIAN_POINT('',(1.425,-1.255,-1.999078980754)); +#69357 = SURFACE_CURVE('',#69358,(#69362,#69369),.PCURVE_S1.); +#69358 = LINE('',#69359,#69360); +#69359 = CARTESIAN_POINT('',(1.425,-1.255,-1.999078980754)); +#69360 = VECTOR('',#69361,1.); +#69361 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#69362 = PCURVE('',#63621,#69363); +#69363 = DEFINITIONAL_REPRESENTATION('',(#69364),#69368); +#69364 = LINE('',#69365,#69366); +#69365 = CARTESIAN_POINT('',(1.999078980754,-1.255)); +#69366 = VECTOR('',#69367,1.); +#69367 = DIRECTION('',(1.,0.E+000)); +#69368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69369 = PCURVE('',#69217,#69370); +#69370 = DEFINITIONAL_REPRESENTATION('',(#69371),#69375); +#69371 = LINE('',#69372,#69373); +#69372 = CARTESIAN_POINT('',(0.E+000,0.25)); +#69373 = VECTOR('',#69374,1.); +#69374 = DIRECTION('',(1.,0.E+000)); +#69375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69376 = ORIENTED_EDGE('',*,*,#69377,.F.); +#69377 = EDGE_CURVE('',#69276,#69355,#69378,.T.); +#69378 = SURFACE_CURVE('',#69379,(#69384,#69391),.PCURVE_S1.); +#69379 = CIRCLE('',#69380,0.1); +#69380 = AXIS2_PLACEMENT_3D('',#69381,#69382,#69383); +#69381 = CARTESIAN_POINT('',(1.425,-1.155,-1.999078980754)); +#69382 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69383 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); +#69384 = PCURVE('',#63621,#69385); +#69385 = DEFINITIONAL_REPRESENTATION('',(#69386),#69390); +#69386 = CIRCLE('',#69387,0.1); +#69387 = AXIS2_PLACEMENT_2D('',#69388,#69389); +#69388 = CARTESIAN_POINT('',(1.999078980754,-1.155)); +#69389 = DIRECTION('',(-0.965925826289,-0.258819045102)); +#69390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69391 = PCURVE('',#69190,#69392); +#69392 = DEFINITIONAL_REPRESENTATION('',(#69393),#69396); +#69393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69394,#69395),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#66805 = CARTESIAN_POINT('',(3.403392041389,0.E+000)); -#66806 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#66807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66808 = ORIENTED_EDGE('',*,*,#66809,.T.); -#66809 = EDGE_CURVE('',#66782,#66810,#66812,.T.); -#66810 = VERTEX_POINT('',#66811); -#66811 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); -#66812 = SURFACE_CURVE('',#66813,(#66817,#66824),.PCURVE_S1.); -#66813 = LINE('',#66814,#66815); -#66814 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); -#66815 = VECTOR('',#66816,1.); -#66816 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66817 = PCURVE('',#61035,#66818); -#66818 = DEFINITIONAL_REPRESENTATION('',(#66819),#66823); -#66819 = LINE('',#66820,#66821); -#66820 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#66821 = VECTOR('',#66822,1.); -#66822 = DIRECTION('',(1.,0.E+000)); -#66823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66824 = PCURVE('',#66825,#66830); -#66825 = PLANE('',#66826); -#66826 = AXIS2_PLACEMENT_3D('',#66827,#66828,#66829); -#66827 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); -#66828 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#66829 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66830 = DEFINITIONAL_REPRESENTATION('',(#66831),#66835); -#66831 = LINE('',#66832,#66833); -#66832 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66833 = VECTOR('',#66834,1.); -#66834 = DIRECTION('',(1.,0.E+000)); -#66835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66836 = ORIENTED_EDGE('',*,*,#66837,.T.); -#66837 = EDGE_CURVE('',#66810,#66681,#66838,.T.); -#66838 = SURFACE_CURVE('',#66839,(#66843,#66850),.PCURVE_S1.); -#66839 = LINE('',#66840,#66841); -#66840 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); -#66841 = VECTOR('',#66842,1.); -#66842 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66843 = PCURVE('',#61035,#66844); -#66844 = DEFINITIONAL_REPRESENTATION('',(#66845),#66849); -#66845 = LINE('',#66846,#66847); -#66846 = CARTESIAN_POINT('',(2.65,-1.255)); -#66847 = VECTOR('',#66848,1.); -#66848 = DIRECTION('',(0.E+000,1.)); -#66849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66850 = PCURVE('',#66719,#66851); -#66851 = DEFINITIONAL_REPRESENTATION('',(#66852),#66856); -#66852 = LINE('',#66853,#66854); -#66853 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#66854 = VECTOR('',#66855,1.); -#66855 = DIRECTION('',(1.,0.E+000)); -#66856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66857 = ADVANCED_FACE('',(#66858),#60331,.T.); -#66858 = FACE_BOUND('',#66859,.F.); -#66859 = EDGE_LOOP('',(#66860,#66861,#66882,#66905,#66925,#66926)); -#66860 = ORIENTED_EDGE('',*,*,#60317,.T.); -#66861 = ORIENTED_EDGE('',*,*,#66862,.F.); -#66862 = EDGE_CURVE('',#61148,#60290,#66863,.T.); -#66863 = SURFACE_CURVE('',#66864,(#66868,#66875),.PCURVE_S1.); -#66864 = LINE('',#66865,#66866); -#66865 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); -#66866 = VECTOR('',#66867,1.); -#66867 = DIRECTION('',(0.E+000,0.965925826289,0.258819045102)); -#66868 = PCURVE('',#60331,#66869); -#66869 = DEFINITIONAL_REPRESENTATION('',(#66870),#66874); -#66870 = LINE('',#66871,#66872); -#66871 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66872 = VECTOR('',#66873,1.); -#66873 = DIRECTION('',(-1.,0.E+000)); -#66874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66875 = PCURVE('',#60305,#66876); -#66876 = DEFINITIONAL_REPRESENTATION('',(#66877),#66881); -#66877 = LINE('',#66878,#66879); -#66878 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66879 = VECTOR('',#66880,1.); -#66880 = DIRECTION('',(-0.258819045102,0.965925826289)); -#66881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66882 = ORIENTED_EDGE('',*,*,#66883,.T.); -#66883 = EDGE_CURVE('',#61148,#66884,#66886,.T.); -#66884 = VERTEX_POINT('',#66885); -#66885 = CARTESIAN_POINT('',(1.425,-1.18088190451,-1.902486398125)); -#66886 = SURFACE_CURVE('',#66887,(#66891,#66898),.PCURVE_S1.); -#66887 = LINE('',#66888,#66889); -#66888 = CARTESIAN_POINT('',(1.425,-1.105,-1.882153903092)); -#66889 = VECTOR('',#66890,1.); -#66890 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045102)); -#66891 = PCURVE('',#60331,#66892); -#66892 = DEFINITIONAL_REPRESENTATION('',(#66893),#66897); -#66893 = LINE('',#66894,#66895); -#66894 = CARTESIAN_POINT('',(0.124233141649,0.25)); -#66895 = VECTOR('',#66896,1.); -#66896 = DIRECTION('',(1.,0.E+000)); -#66897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66898 = PCURVE('',#61229,#66899); -#66899 = DEFINITIONAL_REPRESENTATION('',(#66900),#66904); -#66900 = LINE('',#66901,#66902); -#66901 = CARTESIAN_POINT('',(1.882153903092,-1.105)); -#66902 = VECTOR('',#66903,1.); -#66903 = DIRECTION('',(0.258819045102,-0.965925826289)); -#66904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66905 = ORIENTED_EDGE('',*,*,#66906,.F.); -#66906 = EDGE_CURVE('',#66759,#66884,#66907,.T.); -#66907 = SURFACE_CURVE('',#66908,(#66912,#66919),.PCURVE_S1.); -#66908 = LINE('',#66909,#66910); -#66909 = CARTESIAN_POINT('',(1.175,-1.18088190451,-1.902486398125)); -#66910 = VECTOR('',#66911,1.); -#66911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66912 = PCURVE('',#60331,#66913); -#66913 = DEFINITIONAL_REPRESENTATION('',(#66914),#66918); -#66914 = LINE('',#66915,#66916); -#66915 = CARTESIAN_POINT('',(0.202791869912,0.E+000)); -#66916 = VECTOR('',#66917,1.); -#66917 = DIRECTION('',(0.E+000,1.)); -#66918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66919 = PCURVE('',#66798,#66920); -#66920 = DEFINITIONAL_REPRESENTATION('',(#66921),#66924); -#66921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#66922,#66923),.UNSPECIFIED., +#69394 = CARTESIAN_POINT('',(3.403392041389,0.25)); +#69395 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#69396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69397 = ORIENTED_EDGE('',*,*,#69275,.F.); +#69398 = ORIENTED_EDGE('',*,*,#63607,.F.); +#69399 = ADVANCED_FACE('',(#69400),#69111,.T.); +#69400 = FACE_BOUND('',#69401,.F.); +#69401 = EDGE_LOOP('',(#69402,#69403,#69424,#69425)); +#69402 = ORIENTED_EDGE('',*,*,#69229,.F.); +#69403 = ORIENTED_EDGE('',*,*,#69404,.T.); +#69404 = EDGE_CURVE('',#69202,#69332,#69405,.T.); +#69405 = SURFACE_CURVE('',#69406,(#69410,#69417),.PCURVE_S1.); +#69406 = LINE('',#69407,#69408); +#69407 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); +#69408 = VECTOR('',#69409,1.); +#69409 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69410 = PCURVE('',#69111,#69411); +#69411 = DEFINITIONAL_REPRESENTATION('',(#69412),#69416); +#69412 = LINE('',#69413,#69414); +#69413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69414 = VECTOR('',#69415,1.); +#69415 = DIRECTION('',(0.E+000,1.)); +#69416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69417 = PCURVE('',#69217,#69418); +#69418 = DEFINITIONAL_REPRESENTATION('',(#69419),#69423); +#69419 = LINE('',#69420,#69421); +#69420 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); +#69421 = VECTOR('',#69422,1.); +#69422 = DIRECTION('',(0.E+000,1.)); +#69423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69424 = ORIENTED_EDGE('',*,*,#69331,.T.); +#69425 = ORIENTED_EDGE('',*,*,#69095,.F.); +#69426 = ADVANCED_FACE('',(#69427),#69217,.T.); +#69427 = FACE_BOUND('',#69428,.F.); +#69428 = EDGE_LOOP('',(#69429,#69430,#69450,#69451)); +#69429 = ORIENTED_EDGE('',*,*,#69201,.F.); +#69430 = ORIENTED_EDGE('',*,*,#69431,.T.); +#69431 = EDGE_CURVE('',#69174,#69355,#69432,.T.); +#69432 = SURFACE_CURVE('',#69433,(#69437,#69444),.PCURVE_S1.); +#69433 = LINE('',#69434,#69435); +#69434 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); +#69435 = VECTOR('',#69436,1.); +#69436 = DIRECTION('',(1.,0.E+000,0.E+000)); +#69437 = PCURVE('',#69217,#69438); +#69438 = DEFINITIONAL_REPRESENTATION('',(#69439),#69443); +#69439 = LINE('',#69440,#69441); +#69440 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69441 = VECTOR('',#69442,1.); +#69442 = DIRECTION('',(0.E+000,1.)); +#69443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69444 = PCURVE('',#69190,#69445); +#69445 = DEFINITIONAL_REPRESENTATION('',(#69446),#69449); +#69446 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69447,#69448),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#66922 = CARTESIAN_POINT('',(3.403392041386,0.E+000)); -#66923 = CARTESIAN_POINT('',(3.403392041386,0.25)); -#66924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#69447 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#69448 = CARTESIAN_POINT('',(4.712388980385,0.25)); +#69449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69450 = ORIENTED_EDGE('',*,*,#69354,.T.); +#69451 = ORIENTED_EDGE('',*,*,#69404,.F.); +#69452 = ADVANCED_FACE('',(#69453),#69190,.T.); +#69453 = FACE_BOUND('',#69454,.T.); +#69454 = EDGE_LOOP('',(#69455,#69456,#69457,#69458)); +#69455 = ORIENTED_EDGE('',*,*,#69173,.T.); +#69456 = ORIENTED_EDGE('',*,*,#69431,.T.); +#69457 = ORIENTED_EDGE('',*,*,#69377,.F.); +#69458 = ORIENTED_EDGE('',*,*,#69298,.F.); +#69459 = ADVANCED_FACE('',(#69460),#40168,.F.); +#69460 = FACE_BOUND('',#69461,.F.); +#69461 = EDGE_LOOP('',(#69462,#69463,#69464,#69465)); +#69462 = ORIENTED_EDGE('',*,*,#57177,.T.); +#69463 = ORIENTED_EDGE('',*,*,#44674,.T.); +#69464 = ORIENTED_EDGE('',*,*,#40147,.T.); +#69465 = ORIENTED_EDGE('',*,*,#69466,.F.); +#69466 = EDGE_CURVE('',#57178,#40120,#69467,.T.); +#69467 = SURFACE_CURVE('',#69468,(#69472,#69478),.PCURVE_S1.); +#69468 = LINE('',#69469,#69470); +#69469 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); +#69470 = VECTOR('',#69471,1.); +#69471 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69472 = PCURVE('',#40168,#69473); +#69473 = DEFINITIONAL_REPRESENTATION('',(#69474),#69477); +#69474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69475,#69476),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); +#69475 = CARTESIAN_POINT('',(3.926990816989,3.31)); +#69476 = CARTESIAN_POINT('',(3.926990816989,4.7)); +#69477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#66925 = ORIENTED_EDGE('',*,*,#66758,.F.); -#66926 = ORIENTED_EDGE('',*,*,#60398,.T.); -#66927 = ADVANCED_FACE('',(#66928),#60305,.F.); -#66928 = FACE_BOUND('',#66929,.F.); -#66929 = EDGE_LOOP('',(#66930,#66931,#66932,#66933)); -#66930 = ORIENTED_EDGE('',*,*,#61145,.T.); -#66931 = ORIENTED_EDGE('',*,*,#66862,.T.); -#66932 = ORIENTED_EDGE('',*,*,#60289,.T.); -#66933 = ORIENTED_EDGE('',*,*,#61486,.T.); -#66934 = ADVANCED_FACE('',(#66935),#61229,.T.); -#66935 = FACE_BOUND('',#66936,.F.); -#66936 = EDGE_LOOP('',(#66937,#66938,#66961,#66984,#67005,#67006)); -#66937 = ORIENTED_EDGE('',*,*,#66731,.F.); -#66938 = ORIENTED_EDGE('',*,*,#66939,.F.); -#66939 = EDGE_CURVE('',#66940,#66704,#66942,.T.); -#66940 = VERTEX_POINT('',#66941); -#66941 = CARTESIAN_POINT('',(1.425,-1.255,-2.65)); -#66942 = SURFACE_CURVE('',#66943,(#66947,#66954),.PCURVE_S1.); -#66943 = LINE('',#66944,#66945); -#66944 = CARTESIAN_POINT('',(1.425,-1.255,-2.65)); -#66945 = VECTOR('',#66946,1.); -#66946 = DIRECTION('',(0.E+000,1.,0.E+000)); -#66947 = PCURVE('',#61229,#66948); -#66948 = DEFINITIONAL_REPRESENTATION('',(#66949),#66953); -#66949 = LINE('',#66950,#66951); -#66950 = CARTESIAN_POINT('',(2.65,-1.255)); -#66951 = VECTOR('',#66952,1.); -#66952 = DIRECTION('',(0.E+000,1.)); -#66953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66954 = PCURVE('',#66719,#66955); -#66955 = DEFINITIONAL_REPRESENTATION('',(#66956),#66960); -#66956 = LINE('',#66957,#66958); -#66957 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66958 = VECTOR('',#66959,1.); -#66959 = DIRECTION('',(1.,0.E+000)); -#66960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66961 = ORIENTED_EDGE('',*,*,#66962,.F.); -#66962 = EDGE_CURVE('',#66963,#66940,#66965,.T.); -#66963 = VERTEX_POINT('',#66964); -#66964 = CARTESIAN_POINT('',(1.425,-1.255,-1.999078980754)); -#66965 = SURFACE_CURVE('',#66966,(#66970,#66977),.PCURVE_S1.); -#66966 = LINE('',#66967,#66968); -#66967 = CARTESIAN_POINT('',(1.425,-1.255,-1.999078980754)); -#66968 = VECTOR('',#66969,1.); -#66969 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#66970 = PCURVE('',#61229,#66971); -#66971 = DEFINITIONAL_REPRESENTATION('',(#66972),#66976); -#66972 = LINE('',#66973,#66974); -#66973 = CARTESIAN_POINT('',(1.999078980754,-1.255)); -#66974 = VECTOR('',#66975,1.); -#66975 = DIRECTION('',(1.,0.E+000)); -#66976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66977 = PCURVE('',#66825,#66978); -#66978 = DEFINITIONAL_REPRESENTATION('',(#66979),#66983); -#66979 = LINE('',#66980,#66981); -#66980 = CARTESIAN_POINT('',(0.E+000,0.25)); -#66981 = VECTOR('',#66982,1.); -#66982 = DIRECTION('',(1.,0.E+000)); -#66983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66984 = ORIENTED_EDGE('',*,*,#66985,.F.); -#66985 = EDGE_CURVE('',#66884,#66963,#66986,.T.); -#66986 = SURFACE_CURVE('',#66987,(#66992,#66999),.PCURVE_S1.); -#66987 = CIRCLE('',#66988,0.1); -#66988 = AXIS2_PLACEMENT_3D('',#66989,#66990,#66991); -#66989 = CARTESIAN_POINT('',(1.425,-1.155,-1.999078980754)); -#66990 = DIRECTION('',(1.,0.E+000,0.E+000)); -#66991 = DIRECTION('',(0.E+000,-0.258819045102,0.965925826289)); -#66992 = PCURVE('',#61229,#66993); -#66993 = DEFINITIONAL_REPRESENTATION('',(#66994),#66998); -#66994 = CIRCLE('',#66995,0.1); -#66995 = AXIS2_PLACEMENT_2D('',#66996,#66997); -#66996 = CARTESIAN_POINT('',(1.999078980754,-1.155)); -#66997 = DIRECTION('',(-0.965925826289,-0.258819045102)); -#66998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#66999 = PCURVE('',#66798,#67000); -#67000 = DEFINITIONAL_REPRESENTATION('',(#67001),#67004); -#67001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67002,#67003),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#67002 = CARTESIAN_POINT('',(3.403392041389,0.25)); -#67003 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#67004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67005 = ORIENTED_EDGE('',*,*,#66883,.F.); -#67006 = ORIENTED_EDGE('',*,*,#61215,.F.); -#67007 = ADVANCED_FACE('',(#67008),#66719,.T.); -#67008 = FACE_BOUND('',#67009,.F.); -#67009 = EDGE_LOOP('',(#67010,#67011,#67032,#67033)); -#67010 = ORIENTED_EDGE('',*,*,#66837,.F.); -#67011 = ORIENTED_EDGE('',*,*,#67012,.T.); -#67012 = EDGE_CURVE('',#66810,#66940,#67013,.T.); -#67013 = SURFACE_CURVE('',#67014,(#67018,#67025),.PCURVE_S1.); -#67014 = LINE('',#67015,#67016); -#67015 = CARTESIAN_POINT('',(1.175,-1.255,-2.65)); -#67016 = VECTOR('',#67017,1.); -#67017 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67018 = PCURVE('',#66719,#67019); -#67019 = DEFINITIONAL_REPRESENTATION('',(#67020),#67024); -#67020 = LINE('',#67021,#67022); -#67021 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67022 = VECTOR('',#67023,1.); -#67023 = DIRECTION('',(0.E+000,1.)); -#67024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67025 = PCURVE('',#66825,#67026); -#67026 = DEFINITIONAL_REPRESENTATION('',(#67027),#67031); -#67027 = LINE('',#67028,#67029); -#67028 = CARTESIAN_POINT('',(0.650921019246,0.E+000)); -#67029 = VECTOR('',#67030,1.); -#67030 = DIRECTION('',(0.E+000,1.)); -#67031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67032 = ORIENTED_EDGE('',*,*,#66939,.T.); -#67033 = ORIENTED_EDGE('',*,*,#66703,.F.); -#67034 = ADVANCED_FACE('',(#67035),#66825,.T.); -#67035 = FACE_BOUND('',#67036,.F.); -#67036 = EDGE_LOOP('',(#67037,#67038,#67058,#67059)); -#67037 = ORIENTED_EDGE('',*,*,#66809,.F.); -#67038 = ORIENTED_EDGE('',*,*,#67039,.T.); -#67039 = EDGE_CURVE('',#66782,#66963,#67040,.T.); -#67040 = SURFACE_CURVE('',#67041,(#67045,#67052),.PCURVE_S1.); -#67041 = LINE('',#67042,#67043); -#67042 = CARTESIAN_POINT('',(1.175,-1.255,-1.999078980754)); -#67043 = VECTOR('',#67044,1.); -#67044 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67045 = PCURVE('',#66825,#67046); -#67046 = DEFINITIONAL_REPRESENTATION('',(#67047),#67051); -#67047 = LINE('',#67048,#67049); -#67048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67049 = VECTOR('',#67050,1.); -#67050 = DIRECTION('',(0.E+000,1.)); -#67051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67052 = PCURVE('',#66798,#67053); -#67053 = DEFINITIONAL_REPRESENTATION('',(#67054),#67057); -#67054 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67055,#67056),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.25),.PIECEWISE_BEZIER_KNOTS.); -#67055 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#67056 = CARTESIAN_POINT('',(4.712388980385,0.25)); -#67057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67058 = ORIENTED_EDGE('',*,*,#66962,.T.); -#67059 = ORIENTED_EDGE('',*,*,#67012,.F.); -#67060 = ADVANCED_FACE('',(#67061),#66798,.T.); -#67061 = FACE_BOUND('',#67062,.T.); -#67062 = EDGE_LOOP('',(#67063,#67064,#67065,#67066)); -#67063 = ORIENTED_EDGE('',*,*,#66781,.T.); -#67064 = ORIENTED_EDGE('',*,*,#67039,.T.); -#67065 = ORIENTED_EDGE('',*,*,#66985,.F.); -#67066 = ORIENTED_EDGE('',*,*,#66906,.F.); -#67067 = ADVANCED_FACE('',(#67068),#37776,.F.); -#67068 = FACE_BOUND('',#67069,.F.); -#67069 = EDGE_LOOP('',(#67070,#67071,#67072,#67073)); -#67070 = ORIENTED_EDGE('',*,*,#54785,.T.); -#67071 = ORIENTED_EDGE('',*,*,#42282,.T.); -#67072 = ORIENTED_EDGE('',*,*,#37755,.T.); -#67073 = ORIENTED_EDGE('',*,*,#67074,.F.); -#67074 = EDGE_CURVE('',#54786,#37728,#67075,.T.); -#67075 = SURFACE_CURVE('',#67076,(#67080,#67086),.PCURVE_S1.); -#67076 = LINE('',#67077,#67078); -#67077 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,0.96)); -#67078 = VECTOR('',#67079,1.); -#67079 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67080 = PCURVE('',#37776,#67081); -#67081 = DEFINITIONAL_REPRESENTATION('',(#67082),#67085); -#67082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67083,#67084),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#67083 = CARTESIAN_POINT('',(3.926990816989,3.31)); -#67084 = CARTESIAN_POINT('',(3.926990816989,4.7)); -#67085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67086 = PCURVE('',#37743,#67087); -#67087 = DEFINITIONAL_REPRESENTATION('',(#67088),#67092); -#67088 = LINE('',#67089,#67090); -#67089 = CARTESIAN_POINT('',(0.E+000,3.31)); -#67090 = VECTOR('',#67091,1.); -#67091 = DIRECTION('',(0.E+000,1.)); -#67092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67093 = ADVANCED_FACE('',(#67094),#42700,.F.); -#67094 = FACE_BOUND('',#67095,.F.); -#67095 = EDGE_LOOP('',(#67096,#67097,#67098,#67125,#67147)); -#67096 = ORIENTED_EDGE('',*,*,#59596,.T.); -#67097 = ORIENTED_EDGE('',*,*,#42684,.T.); -#67098 = ORIENTED_EDGE('',*,*,#67099,.F.); -#67099 = EDGE_CURVE('',#67100,#42657,#67102,.T.); -#67100 = VERTEX_POINT('',#67101); -#67101 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-0.56)); -#67102 = SURFACE_CURVE('',#67103,(#67108,#67114),.PCURVE_S1.); -#67103 = CIRCLE('',#67104,0.25); -#67104 = AXIS2_PLACEMENT_3D('',#67105,#67106,#67107); -#67105 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-0.56)); -#67106 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67107 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#67108 = PCURVE('',#42700,#67109); -#67109 = DEFINITIONAL_REPRESENTATION('',(#67110),#67113); -#67110 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67111,#67112),.UNSPECIFIED., +#69478 = PCURVE('',#40135,#69479); +#69479 = DEFINITIONAL_REPRESENTATION('',(#69480),#69484); +#69480 = LINE('',#69481,#69482); +#69481 = CARTESIAN_POINT('',(0.E+000,3.31)); +#69482 = VECTOR('',#69483,1.); +#69483 = DIRECTION('',(0.E+000,1.)); +#69484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69485 = ADVANCED_FACE('',(#69486),#45092,.F.); +#69486 = FACE_BOUND('',#69487,.F.); +#69487 = EDGE_LOOP('',(#69488,#69489,#69490,#69517,#69539)); +#69488 = ORIENTED_EDGE('',*,*,#61988,.T.); +#69489 = ORIENTED_EDGE('',*,*,#45076,.T.); +#69490 = ORIENTED_EDGE('',*,*,#69491,.F.); +#69491 = EDGE_CURVE('',#69492,#45049,#69494,.T.); +#69492 = VERTEX_POINT('',#69493); +#69493 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-0.56)); +#69494 = SURFACE_CURVE('',#69495,(#69500,#69506),.PCURVE_S1.); +#69495 = CIRCLE('',#69496,0.25); +#69496 = AXIS2_PLACEMENT_3D('',#69497,#69498,#69499); +#69497 = CARTESIAN_POINT('',(-2.596446609407,-0.675,-0.56)); +#69498 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69499 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#69500 = PCURVE('',#45092,#69501); +#69501 = DEFINITIONAL_REPRESENTATION('',(#69502),#69505); +#69502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69503,#69504),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163397),.PIECEWISE_BEZIER_KNOTS.); -#67111 = CARTESIAN_POINT('',(3.926990816987,1.79)); -#67112 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#67113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#69503 = CARTESIAN_POINT('',(3.926990816987,1.79)); +#69504 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#69505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#67114 = PCURVE('',#42672,#67115); -#67115 = DEFINITIONAL_REPRESENTATION('',(#67116),#67124); -#67116 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#67117,#67118,#67119,#67120 - ,#67121,#67122,#67123),.UNSPECIFIED.,.F.,.F.) +#69506 = PCURVE('',#45064,#69507); +#69507 = DEFINITIONAL_REPRESENTATION('',(#69508),#69516); +#69508 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#69509,#69510,#69511,#69512 + ,#69513,#69514,#69515),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#67117 = CARTESIAN_POINT('',(0.976776695296,-0.373223304703)); -#67118 = CARTESIAN_POINT('',(1.282962913144,-6.703708685547E-002)); -#67119 = CARTESIAN_POINT('',(1.395034847165,-0.485295238724)); -#67120 = CARTESIAN_POINT('',(1.507106781186,-0.903553390593)); -#67121 = CARTESIAN_POINT('',(1.088848629317,-0.791481456572)); -#67122 = CARTESIAN_POINT('',(0.670590477448,-0.679409522551)); -#67123 = CARTESIAN_POINT('',(0.976776695296,-0.373223304703)); -#67124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67125 = ORIENTED_EDGE('',*,*,#67126,.F.); -#67126 = EDGE_CURVE('',#67127,#67100,#67129,.T.); -#67127 = VERTEX_POINT('',#67128); -#67128 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, +#69509 = CARTESIAN_POINT('',(0.976776695296,-0.373223304703)); +#69510 = CARTESIAN_POINT('',(1.282962913144,-6.703708685547E-002)); +#69511 = CARTESIAN_POINT('',(1.395034847165,-0.485295238724)); +#69512 = CARTESIAN_POINT('',(1.507106781186,-0.903553390593)); +#69513 = CARTESIAN_POINT('',(1.088848629317,-0.791481456572)); +#69514 = CARTESIAN_POINT('',(0.670590477448,-0.679409522551)); +#69515 = CARTESIAN_POINT('',(0.976776695296,-0.373223304703)); +#69516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69517 = ORIENTED_EDGE('',*,*,#69518,.F.); +#69518 = EDGE_CURVE('',#69519,#69492,#69521,.T.); +#69519 = VERTEX_POINT('',#69520); +#69520 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, -1.531808643576)); -#67129 = SURFACE_CURVE('',#67130,(#67134,#67140),.PCURVE_S1.); -#67130 = LINE('',#67131,#67132); -#67131 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, +#69521 = SURFACE_CURVE('',#69522,(#69526,#69532),.PCURVE_S1.); +#69522 = LINE('',#69523,#69524); +#69523 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, -1.531808643576)); -#67132 = VECTOR('',#67133,1.); -#67133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67134 = PCURVE('',#42700,#67135); -#67135 = DEFINITIONAL_REPRESENTATION('',(#67136),#67139); -#67136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67137,#67138),.UNSPECIFIED., +#69524 = VECTOR('',#69525,1.); +#69525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69526 = PCURVE('',#45092,#69527); +#69527 = DEFINITIONAL_REPRESENTATION('',(#69528),#69531); +#69528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69529,#69530),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.971808643576),.PIECEWISE_BEZIER_KNOTS.); -#67137 = CARTESIAN_POINT('',(3.926990816989,0.818191356424)); -#67138 = CARTESIAN_POINT('',(3.926990816989,1.79)); -#67139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#69529 = CARTESIAN_POINT('',(3.926990816989,0.818191356424)); +#69530 = CARTESIAN_POINT('',(3.926990816989,1.79)); +#69531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#67140 = PCURVE('',#53227,#67141); -#67141 = DEFINITIONAL_REPRESENTATION('',(#67142),#67146); -#67142 = LINE('',#67143,#67144); -#67143 = CARTESIAN_POINT('',(0.E+000,0.818191356424)); -#67144 = VECTOR('',#67145,1.); -#67145 = DIRECTION('',(0.E+000,1.)); -#67146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#69532 = PCURVE('',#55619,#69533); +#69533 = DEFINITIONAL_REPRESENTATION('',(#69534),#69538); +#69534 = LINE('',#69535,#69536); +#69535 = CARTESIAN_POINT('',(0.E+000,0.818191356424)); +#69536 = VECTOR('',#69537,1.); +#69537 = DIRECTION('',(0.E+000,1.)); +#69538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#67147 = ORIENTED_EDGE('',*,*,#67148,.F.); -#67148 = EDGE_CURVE('',#59597,#67127,#67149,.T.); -#67149 = SURFACE_CURVE('',#67150,(#67156,#67185),.PCURVE_S1.); -#67150 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67151,#67152,#67153,#67154, - #67155),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#69539 = ORIENTED_EDGE('',*,*,#69540,.F.); +#69540 = EDGE_CURVE('',#61989,#69519,#69541,.T.); +#69541 = SURFACE_CURVE('',#69542,(#69548,#69577),.PCURVE_S1.); +#69542 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69543,#69544,#69545,#69546, + #69547),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#67151 = CARTESIAN_POINT('',(-2.746446609407,-0.875,-1.53)); -#67152 = CARTESIAN_POINT('',(-2.751418506165,-0.871271077432,-1.53)); -#67153 = CARTESIAN_POINT('',(-2.760841262569,-0.863624825256, +#69543 = CARTESIAN_POINT('',(-2.746446609407,-0.875,-1.53)); +#69544 = CARTESIAN_POINT('',(-2.751418506165,-0.871271077432,-1.53)); +#69545 = CARTESIAN_POINT('',(-2.760841262569,-0.863624825256, -1.530279311124)); -#67154 = CARTESIAN_POINT('',(-2.769257147991,-0.855742852009, +#69546 = CARTESIAN_POINT('',(-2.769257147991,-0.855742852009, -1.531187100809)); -#67155 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, +#69547 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, -1.531808643576)); -#67156 = PCURVE('',#42700,#67157); -#67157 = DEFINITIONAL_REPRESENTATION('',(#67158),#67184); -#67158 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67159,#67160,#67161,#67162, - #67163,#67164,#67165,#67166,#67167,#67168,#67169,#67170,#67171, - #67172,#67173,#67174,#67175,#67176,#67177,#67178,#67179,#67180, - #67181,#67182,#67183),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#69548 = PCURVE('',#45092,#69549); +#69549 = DEFINITIONAL_REPRESENTATION('',(#69550),#69576); +#69550 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69551,#69552,#69553,#69554, + #69555,#69556,#69557,#69558,#69559,#69560,#69561,#69562,#69563, + #69564,#69565,#69566,#69567,#69568,#69569,#69570,#69571,#69572, + #69573,#69574,#69575),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -82797,40 +85786,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67159 = CARTESIAN_POINT('',(4.068887871591,0.82)); -#67160 = CARTESIAN_POINT('',(4.066627919189,0.82)); -#67161 = CARTESIAN_POINT('',(4.062118054336,0.819997691644)); -#67162 = CARTESIAN_POINT('',(4.055383333081,0.819987225314)); -#67163 = CARTESIAN_POINT('',(4.048678640876,0.819969676462)); -#67164 = CARTESIAN_POINT('',(4.042003941746,0.819944966363)); -#67165 = CARTESIAN_POINT('',(4.035359206887,0.819913016291)); -#67166 = CARTESIAN_POINT('',(4.028744415636,0.819873747518)); -#67167 = CARTESIAN_POINT('',(4.022159555161,0.81982708132)); -#67168 = CARTESIAN_POINT('',(4.015604620489,0.81977293897)); -#67169 = CARTESIAN_POINT('',(4.009079614435,0.819711241741)); -#67170 = CARTESIAN_POINT('',(4.002584547562,0.819641910908)); -#67171 = CARTESIAN_POINT('',(3.996119438121,0.819564867745)); -#67172 = CARTESIAN_POINT('',(3.98968431201,0.819480033525)); -#67173 = CARTESIAN_POINT('',(3.983279169322,0.819387360789)); -#67174 = CARTESIAN_POINT('',(3.976904017491,0.819286802075)); -#67175 = CARTESIAN_POINT('',(3.970558871255,0.819178309923)); -#67176 = CARTESIAN_POINT('',(3.964243752613,0.819061836874)); -#67177 = CARTESIAN_POINT('',(3.957958690767,0.818937335467)); -#67178 = CARTESIAN_POINT('',(3.95170372209,0.818804758241)); -#67179 = CARTESIAN_POINT('',(3.945478890006,0.818664057736)); -#67180 = CARTESIAN_POINT('',(3.939284245171,0.818515186491)); -#67181 = CARTESIAN_POINT('',(3.933119844546,0.818358097048)); -#67182 = CARTESIAN_POINT('',(3.92903045124,0.818247860312)); -#67183 = CARTESIAN_POINT('',(3.926990816989,0.818191356424)); -#67184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67185 = PCURVE('',#55037,#67186); -#67186 = DEFINITIONAL_REPRESENTATION('',(#67187),#67213); -#67187 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67188,#67189,#67190,#67191, - #67192,#67193,#67194,#67195,#67196,#67197,#67198,#67199,#67200, - #67201,#67202,#67203,#67204,#67205,#67206,#67207,#67208,#67209, - #67210,#67211,#67212),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#69551 = CARTESIAN_POINT('',(4.068887871591,0.82)); +#69552 = CARTESIAN_POINT('',(4.066627919189,0.82)); +#69553 = CARTESIAN_POINT('',(4.062118054336,0.819997691644)); +#69554 = CARTESIAN_POINT('',(4.055383333081,0.819987225314)); +#69555 = CARTESIAN_POINT('',(4.048678640876,0.819969676462)); +#69556 = CARTESIAN_POINT('',(4.042003941746,0.819944966363)); +#69557 = CARTESIAN_POINT('',(4.035359206887,0.819913016291)); +#69558 = CARTESIAN_POINT('',(4.028744415636,0.819873747518)); +#69559 = CARTESIAN_POINT('',(4.022159555161,0.81982708132)); +#69560 = CARTESIAN_POINT('',(4.015604620489,0.81977293897)); +#69561 = CARTESIAN_POINT('',(4.009079614435,0.819711241741)); +#69562 = CARTESIAN_POINT('',(4.002584547562,0.819641910908)); +#69563 = CARTESIAN_POINT('',(3.996119438121,0.819564867745)); +#69564 = CARTESIAN_POINT('',(3.98968431201,0.819480033525)); +#69565 = CARTESIAN_POINT('',(3.983279169322,0.819387360789)); +#69566 = CARTESIAN_POINT('',(3.976904017491,0.819286802075)); +#69567 = CARTESIAN_POINT('',(3.970558871255,0.819178309923)); +#69568 = CARTESIAN_POINT('',(3.964243752613,0.819061836874)); +#69569 = CARTESIAN_POINT('',(3.957958690767,0.818937335467)); +#69570 = CARTESIAN_POINT('',(3.95170372209,0.818804758241)); +#69571 = CARTESIAN_POINT('',(3.945478890006,0.818664057736)); +#69572 = CARTESIAN_POINT('',(3.939284245171,0.818515186491)); +#69573 = CARTESIAN_POINT('',(3.933119844546,0.818358097048)); +#69574 = CARTESIAN_POINT('',(3.92903045124,0.818247860312)); +#69575 = CARTESIAN_POINT('',(3.926990816989,0.818191356424)); +#69576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69577 = PCURVE('',#57429,#69578); +#69578 = DEFINITIONAL_REPRESENTATION('',(#69579),#69605); +#69579 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69580,#69581,#69582,#69583, + #69584,#69585,#69586,#69587,#69588,#69589,#69590,#69591,#69592, + #69593,#69594,#69595,#69596,#69597,#69598,#69599,#69600,#69601, + #69602,#69603,#69604),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -82838,111 +85827,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67188 = CARTESIAN_POINT('',(3.14159265359,1.003553390593)); -#67189 = CARTESIAN_POINT('',(3.139332700007,1.003101399979)); -#67190 = CARTESIAN_POINT('',(3.134802414219,1.002201724842)); -#67191 = CARTESIAN_POINT('',(3.12797658438,1.000865090739)); -#67192 = CARTESIAN_POINT('',(3.121121090593,0.999541295565)); -#67193 = CARTESIAN_POINT('',(3.114236661346,0.998230299648)); -#67194 = CARTESIAN_POINT('',(3.107324018927,0.996932063314)); -#67195 = CARTESIAN_POINT('',(3.100383878249,0.99564654689)); -#67196 = CARTESIAN_POINT('',(3.093416946663,0.994373710703)); -#67197 = CARTESIAN_POINT('',(3.086423923496,0.99311351508)); -#67198 = CARTESIAN_POINT('',(3.079405499661,0.991865920348)); -#67199 = CARTESIAN_POINT('',(3.072362357206,0.990630886834)); -#67200 = CARTESIAN_POINT('',(3.06529516903,0.989408374865)); -#67201 = CARTESIAN_POINT('',(3.058204597954,0.988198344767)); -#67202 = CARTESIAN_POINT('',(3.051091270244,0.98700075177)); -#67203 = CARTESIAN_POINT('',(3.04395580808,0.985815551101)); -#67204 = CARTESIAN_POINT('',(3.036798828681,0.984642697992)); -#67205 = CARTESIAN_POINT('',(3.029620944063,0.983482147668)); -#67206 = CARTESIAN_POINT('',(3.022422760624,0.982333855361)); -#67207 = CARTESIAN_POINT('',(3.015204878757,0.981197776298)); -#67208 = CARTESIAN_POINT('',(3.007967892524,0.980073865708)); -#67209 = CARTESIAN_POINT('',(3.000712389003,0.97896207882)); -#67210 = CARTESIAN_POINT('',(2.993438948887,0.977862370863)); -#67211 = CARTESIAN_POINT('',(2.98857841121,0.977137254998)); -#67212 = CARTESIAN_POINT('',(2.986145343503,0.976776695297)); -#67213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67214 = ADVANCED_FACE('',(#67215),#37743,.T.); -#67215 = FACE_BOUND('',#67216,.F.); -#67216 = EDGE_LOOP('',(#67217,#67218,#67219,#67220)); -#67217 = ORIENTED_EDGE('',*,*,#54808,.F.); -#67218 = ORIENTED_EDGE('',*,*,#67074,.T.); -#67219 = ORIENTED_EDGE('',*,*,#37727,.T.); -#67220 = ORIENTED_EDGE('',*,*,#67221,.F.); -#67221 = EDGE_CURVE('',#54809,#37696,#67222,.T.); -#67222 = SURFACE_CURVE('',#67223,(#67227,#67234),.PCURVE_S1.); -#67223 = LINE('',#67224,#67225); -#67224 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,0.96)); -#67225 = VECTOR('',#67226,1.); -#67226 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67227 = PCURVE('',#37743,#67228); -#67228 = DEFINITIONAL_REPRESENTATION('',(#67229),#67233); -#67229 = LINE('',#67230,#67231); -#67230 = CARTESIAN_POINT('',(0.853553390594,3.31)); -#67231 = VECTOR('',#67232,1.); -#67232 = DIRECTION('',(0.E+000,1.)); -#67233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67234 = PCURVE('',#37716,#67235); -#67235 = DEFINITIONAL_REPRESENTATION('',(#67236),#67239); -#67236 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67237,#67238),.UNSPECIFIED., +#69580 = CARTESIAN_POINT('',(3.14159265359,1.003553390593)); +#69581 = CARTESIAN_POINT('',(3.139332700007,1.003101399979)); +#69582 = CARTESIAN_POINT('',(3.134802414219,1.002201724842)); +#69583 = CARTESIAN_POINT('',(3.12797658438,1.000865090739)); +#69584 = CARTESIAN_POINT('',(3.121121090593,0.999541295565)); +#69585 = CARTESIAN_POINT('',(3.114236661346,0.998230299648)); +#69586 = CARTESIAN_POINT('',(3.107324018927,0.996932063314)); +#69587 = CARTESIAN_POINT('',(3.100383878249,0.99564654689)); +#69588 = CARTESIAN_POINT('',(3.093416946663,0.994373710703)); +#69589 = CARTESIAN_POINT('',(3.086423923496,0.99311351508)); +#69590 = CARTESIAN_POINT('',(3.079405499661,0.991865920348)); +#69591 = CARTESIAN_POINT('',(3.072362357206,0.990630886834)); +#69592 = CARTESIAN_POINT('',(3.06529516903,0.989408374865)); +#69593 = CARTESIAN_POINT('',(3.058204597954,0.988198344767)); +#69594 = CARTESIAN_POINT('',(3.051091270244,0.98700075177)); +#69595 = CARTESIAN_POINT('',(3.04395580808,0.985815551101)); +#69596 = CARTESIAN_POINT('',(3.036798828681,0.984642697992)); +#69597 = CARTESIAN_POINT('',(3.029620944063,0.983482147668)); +#69598 = CARTESIAN_POINT('',(3.022422760624,0.982333855361)); +#69599 = CARTESIAN_POINT('',(3.015204878757,0.981197776298)); +#69600 = CARTESIAN_POINT('',(3.007967892524,0.980073865708)); +#69601 = CARTESIAN_POINT('',(3.000712389003,0.97896207882)); +#69602 = CARTESIAN_POINT('',(2.993438948887,0.977862370863)); +#69603 = CARTESIAN_POINT('',(2.98857841121,0.977137254998)); +#69604 = CARTESIAN_POINT('',(2.986145343503,0.976776695297)); +#69605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69606 = ADVANCED_FACE('',(#69607),#40135,.T.); +#69607 = FACE_BOUND('',#69608,.F.); +#69608 = EDGE_LOOP('',(#69609,#69610,#69611,#69612)); +#69609 = ORIENTED_EDGE('',*,*,#57200,.F.); +#69610 = ORIENTED_EDGE('',*,*,#69466,.T.); +#69611 = ORIENTED_EDGE('',*,*,#40119,.T.); +#69612 = ORIENTED_EDGE('',*,*,#69613,.F.); +#69613 = EDGE_CURVE('',#57201,#40088,#69614,.T.); +#69614 = SURFACE_CURVE('',#69615,(#69619,#69626),.PCURVE_S1.); +#69615 = LINE('',#69616,#69617); +#69616 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,0.96)); +#69617 = VECTOR('',#69618,1.); +#69618 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69619 = PCURVE('',#40135,#69620); +#69620 = DEFINITIONAL_REPRESENTATION('',(#69621),#69625); +#69621 = LINE('',#69622,#69623); +#69622 = CARTESIAN_POINT('',(0.853553390594,3.31)); +#69623 = VECTOR('',#69624,1.); +#69624 = DIRECTION('',(0.E+000,1.)); +#69625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69626 = PCURVE('',#40108,#69627); +#69627 = DEFINITIONAL_REPRESENTATION('',(#69628),#69631); +#69628 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69629,#69630),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#67237 = CARTESIAN_POINT('',(3.926990816986,3.31)); -#67238 = CARTESIAN_POINT('',(3.926990816986,4.7)); -#67239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67240 = ADVANCED_FACE('',(#67241),#53227,.T.); -#67241 = FACE_BOUND('',#67242,.F.); -#67242 = EDGE_LOOP('',(#67243,#67298,#67321,#67370,#67371,#67394,#67437) - ); -#67243 = ORIENTED_EDGE('',*,*,#67244,.F.); -#67244 = EDGE_CURVE('',#67245,#53185,#67247,.T.); -#67245 = VERTEX_POINT('',#67246); -#67246 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); -#67247 = SURFACE_CURVE('',#67248,(#67257,#67269),.PCURVE_S1.); -#67248 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67249,#67250,#67251,#67252, - #67253,#67254,#67255,#67256),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#69629 = CARTESIAN_POINT('',(3.926990816986,3.31)); +#69630 = CARTESIAN_POINT('',(3.926990816986,4.7)); +#69631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69632 = ADVANCED_FACE('',(#69633),#55619,.T.); +#69633 = FACE_BOUND('',#69634,.F.); +#69634 = EDGE_LOOP('',(#69635,#69690,#69713,#69762,#69763,#69786,#69829) + ); +#69635 = ORIENTED_EDGE('',*,*,#69636,.F.); +#69636 = EDGE_CURVE('',#69637,#55577,#69639,.T.); +#69637 = VERTEX_POINT('',#69638); +#69638 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); +#69639 = SURFACE_CURVE('',#69640,(#69649,#69661),.PCURVE_S1.); +#69640 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69641,#69642,#69643,#69644, + #69645,#69646,#69647,#69648),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#67249 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); -#67250 = CARTESIAN_POINT('',(-2.9,-0.725,-2.215088834765)); -#67251 = CARTESIAN_POINT('',(-2.904063775792,-0.720936224208, +#69641 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); +#69642 = CARTESIAN_POINT('',(-2.9,-0.725,-2.215088834765)); +#69643 = CARTESIAN_POINT('',(-2.904063775792,-0.720936224208, -2.239519457455)); -#67252 = CARTESIAN_POINT('',(-2.919357454992,-0.705642545008, +#69644 = CARTESIAN_POINT('',(-2.919357454992,-0.705642545008, -2.278246267971)); -#67253 = CARTESIAN_POINT('',(-2.947656106256,-0.677343893744, +#69645 = CARTESIAN_POINT('',(-2.947656106256,-0.677343893744, -2.313670105381)); -#67254 = CARTESIAN_POINT('',(-2.991922677631,-0.633077322369, +#69646 = CARTESIAN_POINT('',(-2.991922677631,-0.633077322369, -2.341600728372)); -#67255 = CARTESIAN_POINT('',(-3.028661165235,-0.596338834765,-2.35)); -#67256 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); -#67257 = PCURVE('',#53227,#67258); -#67258 = DEFINITIONAL_REPRESENTATION('',(#67259),#67268); -#67259 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67260,#67261,#67262,#67263, - #67264,#67265,#67266,#67267),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#69647 = CARTESIAN_POINT('',(-3.028661165235,-0.596338834765,-2.35)); +#69648 = CARTESIAN_POINT('',(-3.05,-0.575,-2.35)); +#69649 = PCURVE('',#55619,#69650); +#69650 = DEFINITIONAL_REPRESENTATION('',(#69651),#69660); +#69651 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69652,#69653,#69654,#69655, + #69656,#69657,#69658,#69659),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#67260 = CARTESIAN_POINT('',(0.179289321882,0.15)); -#67261 = CARTESIAN_POINT('',(0.179289321882,0.134911165235)); -#67262 = CARTESIAN_POINT('',(0.185036368721,0.110480542545)); -#67263 = CARTESIAN_POINT('',(0.206664897265,7.1753732029E-002)); -#67264 = CARTESIAN_POINT('',(0.246685233679,3.6329894619E-002)); -#67265 = CARTESIAN_POINT('',(0.309287619277,8.399271628E-003)); -#67266 = CARTESIAN_POINT('',(0.361243686708,0.E+000)); -#67267 = CARTESIAN_POINT('',(0.391421356238,0.E+000)); -#67268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67269 = PCURVE('',#53200,#67270); -#67270 = DEFINITIONAL_REPRESENTATION('',(#67271),#67297); -#67271 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67272,#67273,#67274,#67275, - #67276,#67277,#67278,#67279,#67280,#67281,#67282,#67283,#67284, - #67285,#67286,#67287,#67288,#67289,#67290,#67291,#67292,#67293, - #67294,#67295,#67296),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#69652 = CARTESIAN_POINT('',(0.179289321882,0.15)); +#69653 = CARTESIAN_POINT('',(0.179289321882,0.134911165235)); +#69654 = CARTESIAN_POINT('',(0.185036368721,0.110480542545)); +#69655 = CARTESIAN_POINT('',(0.206664897265,7.1753732029E-002)); +#69656 = CARTESIAN_POINT('',(0.246685233679,3.6329894619E-002)); +#69657 = CARTESIAN_POINT('',(0.309287619277,8.399271628E-003)); +#69658 = CARTESIAN_POINT('',(0.361243686708,0.E+000)); +#69659 = CARTESIAN_POINT('',(0.391421356238,0.E+000)); +#69660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69661 = PCURVE('',#55592,#69662); +#69662 = DEFINITIONAL_REPRESENTATION('',(#69663),#69689); +#69663 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69664,#69665,#69666,#69667, + #69668,#69669,#69670,#69671,#69672,#69673,#69674,#69675,#69676, + #69677,#69678,#69679,#69680,#69681,#69682,#69683,#69684,#69685, + #69686,#69687,#69688),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -82950,97 +85939,97 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67272 = CARTESIAN_POINT('',(4.712388980385,0.85)); -#67273 = CARTESIAN_POINT('',(4.748933560976,0.849999928837)); -#67274 = CARTESIAN_POINT('',(4.81707874687,0.849463167876)); -#67275 = CARTESIAN_POINT('',(4.907992270893,0.847370566865)); -#67276 = CARTESIAN_POINT('',(4.991501242609,0.844331862332)); -#67277 = CARTESIAN_POINT('',(5.070203254432,0.840622051328)); -#67278 = CARTESIAN_POINT('',(5.144906443438,0.836297629287)); -#67279 = CARTESIAN_POINT('',(5.216603945889,0.831452400868)); -#67280 = CARTESIAN_POINT('',(5.285913848235,0.826138742776)); -#67281 = CARTESIAN_POINT('',(5.353274617376,0.820377877125)); -#67282 = CARTESIAN_POINT('',(5.419136101421,0.814197515164)); -#67283 = CARTESIAN_POINT('',(5.483899443317,0.807623628929)); -#67284 = CARTESIAN_POINT('',(5.547920698644,0.800682658171)); -#67285 = CARTESIAN_POINT('',(5.611491697867,0.793400910992)); -#67286 = CARTESIAN_POINT('',(5.674841699303,0.785775211094)); -#67287 = CARTESIAN_POINT('',(5.738220831198,0.777802278292)); -#67288 = CARTESIAN_POINT('',(5.801885308441,0.76947918906)); -#67289 = CARTESIAN_POINT('',(5.866098193035,0.760801697123)); -#67290 = CARTESIAN_POINT('',(5.931103476771,0.751770490543)); -#67291 = CARTESIAN_POINT('',(5.997203324603,0.742363001756)); -#67292 = CARTESIAN_POINT('',(6.064845544964,0.732533407589)); -#67293 = CARTESIAN_POINT('',(6.13454852804,0.722240819161)); -#67294 = CARTESIAN_POINT('',(6.206898120521,0.711443024999)); -#67295 = CARTESIAN_POINT('',(6.257321803275,0.703879788139)); -#67296 = CARTESIAN_POINT('',(6.28318530718,0.7)); -#67297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67298 = ORIENTED_EDGE('',*,*,#67299,.T.); -#67299 = EDGE_CURVE('',#67245,#67300,#67302,.T.); -#67300 = VERTEX_POINT('',#67301); -#67301 = CARTESIAN_POINT('',(-2.9,-0.725,-1.68)); -#67302 = SURFACE_CURVE('',#67303,(#67307,#67314),.PCURVE_S1.); -#67303 = LINE('',#67304,#67305); -#67304 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); -#67305 = VECTOR('',#67306,1.); -#67306 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67307 = PCURVE('',#53227,#67308); -#67308 = DEFINITIONAL_REPRESENTATION('',(#67309),#67313); -#67309 = LINE('',#67310,#67311); -#67310 = CARTESIAN_POINT('',(0.179289321882,0.15)); -#67311 = VECTOR('',#67312,1.); -#67312 = DIRECTION('',(0.E+000,1.)); -#67313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67314 = PCURVE('',#55085,#67315); -#67315 = DEFINITIONAL_REPRESENTATION('',(#67316),#67320); -#67316 = LINE('',#67317,#67318); -#67317 = CARTESIAN_POINT('',(0.E+000,0.85)); -#67318 = VECTOR('',#67319,1.); -#67319 = DIRECTION('',(1.,0.E+000)); -#67320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67321 = ORIENTED_EDGE('',*,*,#67322,.T.); -#67322 = EDGE_CURVE('',#67300,#67127,#67323,.T.); -#67323 = SURFACE_CURVE('',#67324,(#67331,#67341),.PCURVE_S1.); -#67324 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67325,#67326,#67327,#67328, - #67329,#67330),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) +#69664 = CARTESIAN_POINT('',(4.712388980385,0.85)); +#69665 = CARTESIAN_POINT('',(4.748933560976,0.849999928837)); +#69666 = CARTESIAN_POINT('',(4.81707874687,0.849463167876)); +#69667 = CARTESIAN_POINT('',(4.907992270893,0.847370566865)); +#69668 = CARTESIAN_POINT('',(4.991501242609,0.844331862332)); +#69669 = CARTESIAN_POINT('',(5.070203254432,0.840622051328)); +#69670 = CARTESIAN_POINT('',(5.144906443438,0.836297629287)); +#69671 = CARTESIAN_POINT('',(5.216603945889,0.831452400868)); +#69672 = CARTESIAN_POINT('',(5.285913848235,0.826138742776)); +#69673 = CARTESIAN_POINT('',(5.353274617376,0.820377877125)); +#69674 = CARTESIAN_POINT('',(5.419136101421,0.814197515164)); +#69675 = CARTESIAN_POINT('',(5.483899443317,0.807623628929)); +#69676 = CARTESIAN_POINT('',(5.547920698644,0.800682658171)); +#69677 = CARTESIAN_POINT('',(5.611491697867,0.793400910992)); +#69678 = CARTESIAN_POINT('',(5.674841699303,0.785775211094)); +#69679 = CARTESIAN_POINT('',(5.738220831198,0.777802278292)); +#69680 = CARTESIAN_POINT('',(5.801885308441,0.76947918906)); +#69681 = CARTESIAN_POINT('',(5.866098193035,0.760801697123)); +#69682 = CARTESIAN_POINT('',(5.931103476771,0.751770490543)); +#69683 = CARTESIAN_POINT('',(5.997203324603,0.742363001756)); +#69684 = CARTESIAN_POINT('',(6.064845544964,0.732533407589)); +#69685 = CARTESIAN_POINT('',(6.13454852804,0.722240819161)); +#69686 = CARTESIAN_POINT('',(6.206898120521,0.711443024999)); +#69687 = CARTESIAN_POINT('',(6.257321803275,0.703879788139)); +#69688 = CARTESIAN_POINT('',(6.28318530718,0.7)); +#69689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69690 = ORIENTED_EDGE('',*,*,#69691,.T.); +#69691 = EDGE_CURVE('',#69637,#69692,#69694,.T.); +#69692 = VERTEX_POINT('',#69693); +#69693 = CARTESIAN_POINT('',(-2.9,-0.725,-1.68)); +#69694 = SURFACE_CURVE('',#69695,(#69699,#69706),.PCURVE_S1.); +#69695 = LINE('',#69696,#69697); +#69696 = CARTESIAN_POINT('',(-2.9,-0.725,-2.2)); +#69697 = VECTOR('',#69698,1.); +#69698 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69699 = PCURVE('',#55619,#69700); +#69700 = DEFINITIONAL_REPRESENTATION('',(#69701),#69705); +#69701 = LINE('',#69702,#69703); +#69702 = CARTESIAN_POINT('',(0.179289321882,0.15)); +#69703 = VECTOR('',#69704,1.); +#69704 = DIRECTION('',(0.E+000,1.)); +#69705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69706 = PCURVE('',#57477,#69707); +#69707 = DEFINITIONAL_REPRESENTATION('',(#69708),#69712); +#69708 = LINE('',#69709,#69710); +#69709 = CARTESIAN_POINT('',(0.E+000,0.85)); +#69710 = VECTOR('',#69711,1.); +#69711 = DIRECTION('',(1.,0.E+000)); +#69712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69713 = ORIENTED_EDGE('',*,*,#69714,.T.); +#69714 = EDGE_CURVE('',#69692,#69519,#69715,.T.); +#69715 = SURFACE_CURVE('',#69716,(#69723,#69733),.PCURVE_S1.); +#69716 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69717,#69718,#69719,#69720, + #69721,#69722),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) ,.UNSPECIFIED.); -#67325 = CARTESIAN_POINT('',(-2.9,-0.725,-1.68)); -#67326 = CARTESIAN_POINT('',(-2.9,-0.725,-1.654274107399)); -#67327 = CARTESIAN_POINT('',(-2.889099431951,-0.735900568049, +#69717 = CARTESIAN_POINT('',(-2.9,-0.725,-1.68)); +#69718 = CARTESIAN_POINT('',(-2.9,-0.725,-1.654274107399)); +#69719 = CARTESIAN_POINT('',(-2.889099431951,-0.735900568049, -1.616624166029)); -#67328 = CARTESIAN_POINT('',(-2.851332144966,-0.773667855034, +#69720 = CARTESIAN_POINT('',(-2.851332144966,-0.773667855034, -1.561539956467)); -#67329 = CARTESIAN_POINT('',(-2.80938387573,-0.81561612427, +#69721 = CARTESIAN_POINT('',(-2.80938387573,-0.81561612427, -1.537475424551)); -#67330 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, +#69722 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297, -1.531808643576)); -#67331 = PCURVE('',#53227,#67332); -#67332 = DEFINITIONAL_REPRESENTATION('',(#67333),#67340); -#67333 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67334,#67335,#67336,#67337, - #67338,#67339),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) +#69723 = PCURVE('',#55619,#69724); +#69724 = DEFINITIONAL_REPRESENTATION('',(#69725),#69732); +#69725 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69726,#69727,#69728,#69729, + #69730,#69731),.UNSPECIFIED.,.F.,.F.,(4,1,1,4),(0.E+000,0.25,0.5,1.) ,.UNSPECIFIED.); -#67334 = CARTESIAN_POINT('',(0.179289321882,0.67)); -#67335 = CARTESIAN_POINT('',(0.179289321882,0.695725892601)); -#67336 = CARTESIAN_POINT('',(0.163873590709,0.733375833971)); -#67337 = CARTESIAN_POINT('',(0.110462581241,0.788460043533)); -#67338 = CARTESIAN_POINT('',(5.113876996933E-002,0.812524575449)); -#67339 = CARTESIAN_POINT('',(0.E+000,0.818191356424)); -#67340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67341 = PCURVE('',#55037,#67342); -#67342 = DEFINITIONAL_REPRESENTATION('',(#67343),#67369); -#67343 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67344,#67345,#67346,#67347, - #67348,#67349,#67350,#67351,#67352,#67353,#67354,#67355,#67356, - #67357,#67358,#67359,#67360,#67361,#67362,#67363,#67364,#67365, - #67366,#67367,#67368),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#69726 = CARTESIAN_POINT('',(0.179289321882,0.67)); +#69727 = CARTESIAN_POINT('',(0.179289321882,0.695725892601)); +#69728 = CARTESIAN_POINT('',(0.163873590709,0.733375833971)); +#69729 = CARTESIAN_POINT('',(0.110462581241,0.788460043533)); +#69730 = CARTESIAN_POINT('',(5.113876996933E-002,0.812524575449)); +#69731 = CARTESIAN_POINT('',(0.E+000,0.818191356424)); +#69732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69733 = PCURVE('',#57429,#69734); +#69734 = DEFINITIONAL_REPRESENTATION('',(#69735),#69761); +#69735 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69736,#69737,#69738,#69739, + #69740,#69741,#69742,#69743,#69744,#69745,#69746,#69747,#69748, + #69749,#69750,#69751,#69752,#69753,#69754,#69755,#69756,#69757, + #69758,#69759,#69760),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -83048,85 +86037,85 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67344 = CARTESIAN_POINT('',(1.570796326795,0.85)); -#67345 = CARTESIAN_POINT('',(1.601978784657,0.85)); -#67346 = CARTESIAN_POINT('',(1.661298490424,0.850360357179)); -#67347 = CARTESIAN_POINT('',(1.742667831779,0.851857313524)); -#67348 = CARTESIAN_POINT('',(1.817984715493,0.85418632108)); -#67349 = CARTESIAN_POINT('',(1.888693686444,0.8572220249)); -#67350 = CARTESIAN_POINT('',(1.956042754055,0.860842730767)); -#67351 = CARTESIAN_POINT('',(2.021127727696,0.864913087121)); -#67352 = CARTESIAN_POINT('',(2.084500361835,0.869362110258)); -#67353 = CARTESIAN_POINT('',(2.146376278772,0.874183184202)); -#67354 = CARTESIAN_POINT('',(2.207037995137,0.879356036006)); -#67355 = CARTESIAN_POINT('',(2.266733448662,0.884864052096)); -#67356 = CARTESIAN_POINT('',(2.325694965596,0.890689638373)); -#67357 = CARTESIAN_POINT('',(2.384121053951,0.896815463469)); -#67358 = CARTESIAN_POINT('',(2.442168868974,0.903251161546)); -#67359 = CARTESIAN_POINT('',(2.500030317521,0.91000638563)); -#67360 = CARTESIAN_POINT('',(2.557922172611,0.917090783693)); -#67361 = CARTESIAN_POINT('',(2.616083543492,0.924514005061)); -#67362 = CARTESIAN_POINT('',(2.674771534703,0.932285698696)); -#67363 = CARTESIAN_POINT('',(2.734257156083,0.94041551366)); -#67364 = CARTESIAN_POINT('',(2.794820792471,0.948913098986)); -#67365 = CARTESIAN_POINT('',(2.856745683084,0.957788103716)); -#67366 = CARTESIAN_POINT('',(2.920313481355,0.967050176888)); -#67367 = CARTESIAN_POINT('',(2.96396043223,0.973489370658)); -#67368 = CARTESIAN_POINT('',(2.986145343503,0.976776695297)); -#67369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67370 = ORIENTED_EDGE('',*,*,#67126,.T.); -#67371 = ORIENTED_EDGE('',*,*,#67372,.T.); -#67372 = EDGE_CURVE('',#67100,#67373,#67375,.T.); -#67373 = VERTEX_POINT('',#67374); -#67374 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,-0.56)); -#67375 = SURFACE_CURVE('',#67376,(#67380,#67387),.PCURVE_S1.); -#67376 = LINE('',#67377,#67378); -#67377 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-0.56)); -#67378 = VECTOR('',#67379,1.); -#67379 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#67380 = PCURVE('',#53227,#67381); -#67381 = DEFINITIONAL_REPRESENTATION('',(#67382),#67386); -#67382 = LINE('',#67383,#67384); -#67383 = CARTESIAN_POINT('',(0.E+000,1.79)); -#67384 = VECTOR('',#67385,1.); -#67385 = DIRECTION('',(1.,0.E+000)); -#67386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67387 = PCURVE('',#42672,#67388); -#67388 = DEFINITIONAL_REPRESENTATION('',(#67389),#67393); -#67389 = LINE('',#67390,#67391); -#67390 = CARTESIAN_POINT('',(0.976776695297,-0.373223304703)); -#67391 = VECTOR('',#67392,1.); -#67392 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#67393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67394 = ORIENTED_EDGE('',*,*,#67395,.F.); -#67395 = EDGE_CURVE('',#53212,#67373,#67396,.T.); -#67396 = SURFACE_CURVE('',#67397,(#67401,#67408),.PCURVE_S1.); -#67397 = LINE('',#67398,#67399); -#67398 = CARTESIAN_POINT('',(-3.376617874958,-0.248382125042,-2.35)); -#67399 = VECTOR('',#67400,1.); -#67400 = DIRECTION('',(-8.872644533068E-005,8.872644533057E-005, +#69736 = CARTESIAN_POINT('',(1.570796326795,0.85)); +#69737 = CARTESIAN_POINT('',(1.601978784657,0.85)); +#69738 = CARTESIAN_POINT('',(1.661298490424,0.850360357179)); +#69739 = CARTESIAN_POINT('',(1.742667831779,0.851857313524)); +#69740 = CARTESIAN_POINT('',(1.817984715493,0.85418632108)); +#69741 = CARTESIAN_POINT('',(1.888693686444,0.8572220249)); +#69742 = CARTESIAN_POINT('',(1.956042754055,0.860842730767)); +#69743 = CARTESIAN_POINT('',(2.021127727696,0.864913087121)); +#69744 = CARTESIAN_POINT('',(2.084500361835,0.869362110258)); +#69745 = CARTESIAN_POINT('',(2.146376278772,0.874183184202)); +#69746 = CARTESIAN_POINT('',(2.207037995137,0.879356036006)); +#69747 = CARTESIAN_POINT('',(2.266733448662,0.884864052096)); +#69748 = CARTESIAN_POINT('',(2.325694965596,0.890689638373)); +#69749 = CARTESIAN_POINT('',(2.384121053951,0.896815463469)); +#69750 = CARTESIAN_POINT('',(2.442168868974,0.903251161546)); +#69751 = CARTESIAN_POINT('',(2.500030317521,0.91000638563)); +#69752 = CARTESIAN_POINT('',(2.557922172611,0.917090783693)); +#69753 = CARTESIAN_POINT('',(2.616083543492,0.924514005061)); +#69754 = CARTESIAN_POINT('',(2.674771534703,0.932285698696)); +#69755 = CARTESIAN_POINT('',(2.734257156083,0.94041551366)); +#69756 = CARTESIAN_POINT('',(2.794820792471,0.948913098986)); +#69757 = CARTESIAN_POINT('',(2.856745683084,0.957788103716)); +#69758 = CARTESIAN_POINT('',(2.920313481355,0.967050176888)); +#69759 = CARTESIAN_POINT('',(2.96396043223,0.973489370658)); +#69760 = CARTESIAN_POINT('',(2.986145343503,0.976776695297)); +#69761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69762 = ORIENTED_EDGE('',*,*,#69518,.T.); +#69763 = ORIENTED_EDGE('',*,*,#69764,.T.); +#69764 = EDGE_CURVE('',#69492,#69765,#69767,.T.); +#69765 = VERTEX_POINT('',#69766); +#69766 = CARTESIAN_POINT('',(-3.376776695297,-0.248223304703,-0.56)); +#69767 = SURFACE_CURVE('',#69768,(#69772,#69779),.PCURVE_S1.); +#69768 = LINE('',#69769,#69770); +#69769 = CARTESIAN_POINT('',(-2.773223304703,-0.851776695297,-0.56)); +#69770 = VECTOR('',#69771,1.); +#69771 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#69772 = PCURVE('',#55619,#69773); +#69773 = DEFINITIONAL_REPRESENTATION('',(#69774),#69778); +#69774 = LINE('',#69775,#69776); +#69775 = CARTESIAN_POINT('',(0.E+000,1.79)); +#69776 = VECTOR('',#69777,1.); +#69777 = DIRECTION('',(1.,0.E+000)); +#69778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69779 = PCURVE('',#45064,#69780); +#69780 = DEFINITIONAL_REPRESENTATION('',(#69781),#69785); +#69781 = LINE('',#69782,#69783); +#69782 = CARTESIAN_POINT('',(0.976776695297,-0.373223304703)); +#69783 = VECTOR('',#69784,1.); +#69784 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#69785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69786 = ORIENTED_EDGE('',*,*,#69787,.F.); +#69787 = EDGE_CURVE('',#55604,#69765,#69788,.T.); +#69788 = SURFACE_CURVE('',#69789,(#69793,#69800),.PCURVE_S1.); +#69789 = LINE('',#69790,#69791); +#69790 = CARTESIAN_POINT('',(-3.376617874958,-0.248382125042,-2.35)); +#69791 = VECTOR('',#69792,1.); +#69792 = DIRECTION('',(-8.872644533068E-005,8.872644533057E-005, 0.999999992128)); -#67401 = PCURVE('',#53227,#67402); -#67402 = DEFINITIONAL_REPRESENTATION('',(#67403),#67407); -#67403 = LINE('',#67404,#67405); -#67404 = CARTESIAN_POINT('',(0.853328784717,0.E+000)); -#67405 = VECTOR('',#67406,1.); -#67406 = DIRECTION('',(1.254781423277E-004,0.999999992128)); -#67407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67408 = PCURVE('',#53260,#67409); -#67409 = DEFINITIONAL_REPRESENTATION('',(#67410),#67436); -#67410 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67411,#67412,#67413,#67414, - #67415,#67416,#67417,#67418,#67419,#67420,#67421,#67422,#67423, - #67424,#67425,#67426,#67427,#67428,#67429,#67430,#67431,#67432, - #67433,#67434,#67435),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#69793 = PCURVE('',#55619,#69794); +#69794 = DEFINITIONAL_REPRESENTATION('',(#69795),#69799); +#69795 = LINE('',#69796,#69797); +#69796 = CARTESIAN_POINT('',(0.853328784717,0.E+000)); +#69797 = VECTOR('',#69798,1.); +#69798 = DIRECTION('',(1.254781423277E-004,0.999999992128)); +#69799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69800 = PCURVE('',#55652,#69801); +#69801 = DEFINITIONAL_REPRESENTATION('',(#69802),#69828); +#69802 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69803,#69804,#69805,#69806, + #69807,#69808,#69809,#69810,#69811,#69812,#69813,#69814,#69815, + #69816,#69817,#69818,#69819,#69820,#69821,#69822,#69823,#69824, + #69825,#69826,#69827),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-5.63659491543E-008,8.13635832003E-002, 0.162727222767,0.244090862333,0.325454501899,0.406818141465, 0.488181781032,0.569545420598,0.650909060164,0.73227269973, @@ -83134,502 +86123,502 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.139090897562,1.220454537128,1.301818176694,1.38318181626, 1.464545455827,1.545909095393,1.627272734959,1.708636374525, 1.790000014092),.UNSPECIFIED.); -#67411 = CARTESIAN_POINT('',(3.927889240281,-5.636594879732E-008)); -#67412 = CARTESIAN_POINT('',(3.927875627814,2.712115660929E-002)); -#67413 = CARTESIAN_POINT('',(3.927848402879,8.136358255978E-002)); -#67414 = CARTESIAN_POINT('',(3.927807565475,0.162727221486)); -#67415 = CARTESIAN_POINT('',(3.927766728067,0.244090860411)); -#67416 = CARTESIAN_POINT('',(3.927725890657,0.325454499337)); -#67417 = CARTESIAN_POINT('',(3.927685053244,0.406818138263)); -#67418 = CARTESIAN_POINT('',(3.92764421583,0.488181777188)); -#67419 = CARTESIAN_POINT('',(3.927603378413,0.569545416114)); -#67420 = CARTESIAN_POINT('',(3.927562540993,0.65090905504)); -#67421 = CARTESIAN_POINT('',(3.927521703572,0.732272693966)); -#67422 = CARTESIAN_POINT('',(3.92748086615,0.813636332891)); -#67423 = CARTESIAN_POINT('',(3.927440028725,0.894999971817)); -#67424 = CARTESIAN_POINT('',(3.927399191299,0.976363610743)); -#67425 = CARTESIAN_POINT('',(3.927358353872,1.057727249668)); -#67426 = CARTESIAN_POINT('',(3.927317516444,1.139090888594)); -#67427 = CARTESIAN_POINT('',(3.927276679014,1.22045452752)); -#67428 = CARTESIAN_POINT('',(3.927235841584,1.301818166446)); -#67429 = CARTESIAN_POINT('',(3.927195004152,1.383181805371)); -#67430 = CARTESIAN_POINT('',(3.92715416672,1.464545444297)); -#67431 = CARTESIAN_POINT('',(3.927113329288,1.545909083223)); -#67432 = CARTESIAN_POINT('',(3.927072491855,1.627272722149)); -#67433 = CARTESIAN_POINT('',(3.927031654421,1.708636361074)); -#67434 = CARTESIAN_POINT('',(3.927004429466,1.762878787025)); -#67435 = CARTESIAN_POINT('',(3.926990816988,1.79)); -#67436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67437 = ORIENTED_EDGE('',*,*,#53211,.F.); -#67438 = ADVANCED_FACE('',(#67439),#53260,.F.); -#67439 = FACE_BOUND('',#67440,.F.); -#67440 = EDGE_LOOP('',(#67441,#67466,#67467,#67468,#67469)); -#67441 = ORIENTED_EDGE('',*,*,#67442,.F.); -#67442 = EDGE_CURVE('',#54387,#67373,#67443,.T.); -#67443 = SURFACE_CURVE('',#67444,(#67449,#67455),.PCURVE_S1.); -#67444 = CIRCLE('',#67445,0.25); -#67445 = AXIS2_PLACEMENT_3D('',#67446,#67447,#67448); -#67446 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-0.56)); -#67447 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67448 = DIRECTION('',(-0.910179721124,-0.414213562373,0.E+000)); -#67449 = PCURVE('',#53260,#67450); -#67450 = DEFINITIONAL_REPRESENTATION('',(#67451),#67454); -#67451 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67452,#67453),.UNSPECIFIED., +#69803 = CARTESIAN_POINT('',(3.927889240281,-5.636594879732E-008)); +#69804 = CARTESIAN_POINT('',(3.927875627814,2.712115660929E-002)); +#69805 = CARTESIAN_POINT('',(3.927848402879,8.136358255978E-002)); +#69806 = CARTESIAN_POINT('',(3.927807565475,0.162727221486)); +#69807 = CARTESIAN_POINT('',(3.927766728067,0.244090860411)); +#69808 = CARTESIAN_POINT('',(3.927725890657,0.325454499337)); +#69809 = CARTESIAN_POINT('',(3.927685053244,0.406818138263)); +#69810 = CARTESIAN_POINT('',(3.92764421583,0.488181777188)); +#69811 = CARTESIAN_POINT('',(3.927603378413,0.569545416114)); +#69812 = CARTESIAN_POINT('',(3.927562540993,0.65090905504)); +#69813 = CARTESIAN_POINT('',(3.927521703572,0.732272693966)); +#69814 = CARTESIAN_POINT('',(3.92748086615,0.813636332891)); +#69815 = CARTESIAN_POINT('',(3.927440028725,0.894999971817)); +#69816 = CARTESIAN_POINT('',(3.927399191299,0.976363610743)); +#69817 = CARTESIAN_POINT('',(3.927358353872,1.057727249668)); +#69818 = CARTESIAN_POINT('',(3.927317516444,1.139090888594)); +#69819 = CARTESIAN_POINT('',(3.927276679014,1.22045452752)); +#69820 = CARTESIAN_POINT('',(3.927235841584,1.301818166446)); +#69821 = CARTESIAN_POINT('',(3.927195004152,1.383181805371)); +#69822 = CARTESIAN_POINT('',(3.92715416672,1.464545444297)); +#69823 = CARTESIAN_POINT('',(3.927113329288,1.545909083223)); +#69824 = CARTESIAN_POINT('',(3.927072491855,1.627272722149)); +#69825 = CARTESIAN_POINT('',(3.927031654421,1.708636361074)); +#69826 = CARTESIAN_POINT('',(3.927004429466,1.762878787025)); +#69827 = CARTESIAN_POINT('',(3.926990816988,1.79)); +#69828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69829 = ORIENTED_EDGE('',*,*,#55603,.F.); +#69830 = ADVANCED_FACE('',(#69831),#55652,.F.); +#69831 = FACE_BOUND('',#69832,.F.); +#69832 = EDGE_LOOP('',(#69833,#69858,#69859,#69860,#69861)); +#69833 = ORIENTED_EDGE('',*,*,#69834,.F.); +#69834 = EDGE_CURVE('',#56779,#69765,#69835,.T.); +#69835 = SURFACE_CURVE('',#69836,(#69841,#69847),.PCURVE_S1.); +#69836 = CIRCLE('',#69837,0.25); +#69837 = AXIS2_PLACEMENT_3D('',#69838,#69839,#69840); +#69838 = CARTESIAN_POINT('',(-3.2,-7.144660940673E-002,-0.56)); +#69839 = DIRECTION('',(0.E+000,0.E+000,1.)); +#69840 = DIRECTION('',(-0.910179721124,-0.414213562373,0.E+000)); +#69841 = PCURVE('',#55652,#69842); +#69842 = DEFINITIONAL_REPRESENTATION('',(#69843),#69846); +#69843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69844,#69845),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.358319577004),.PIECEWISE_BEZIER_KNOTS.); -#67452 = CARTESIAN_POINT('',(3.568671239982,1.79)); -#67453 = CARTESIAN_POINT('',(3.926990816986,1.79)); -#67454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#69844 = CARTESIAN_POINT('',(3.568671239982,1.79)); +#69845 = CARTESIAN_POINT('',(3.926990816986,1.79)); +#69846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#67455 = PCURVE('',#42672,#67456); -#67456 = DEFINITIONAL_REPRESENTATION('',(#67457),#67465); -#67457 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#67458,#67459,#67460,#67461 - ,#67462,#67463,#67464),.UNSPECIFIED.,.F.,.F.) +#69847 = PCURVE('',#45064,#69848); +#69848 = DEFINITIONAL_REPRESENTATION('',(#69849),#69857); +#69849 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#69850,#69851,#69852,#69853 + ,#69854,#69855,#69856),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#67458 = CARTESIAN_POINT('',(0.322455069719,-1.05)); -#67459 = CARTESIAN_POINT('',(0.501814803522,-0.655880619748)); -#67460 = CARTESIAN_POINT('',(0.753452332042,-1.008270395764)); -#67461 = CARTESIAN_POINT('',(1.005089860562,-1.36066017178)); -#67462 = CARTESIAN_POINT('',(0.574092598239,-1.402389776016)); -#67463 = CARTESIAN_POINT('',(0.143095335915,-1.444119380252)); -#67464 = CARTESIAN_POINT('',(0.322455069719,-1.05)); -#67465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67466 = ORIENTED_EDGE('',*,*,#54386,.F.); -#67467 = ORIENTED_EDGE('',*,*,#54573,.T.); -#67468 = ORIENTED_EDGE('',*,*,#53239,.F.); -#67469 = ORIENTED_EDGE('',*,*,#67395,.T.); -#67470 = ADVANCED_FACE('',(#67471),#37716,.F.); -#67471 = FACE_BOUND('',#67472,.F.); -#67472 = EDGE_LOOP('',(#67473,#67474,#67475,#67476,#67477)); -#67473 = ORIENTED_EDGE('',*,*,#54508,.T.); -#67474 = ORIENTED_EDGE('',*,*,#54622,.F.); -#67475 = ORIENTED_EDGE('',*,*,#54831,.T.); -#67476 = ORIENTED_EDGE('',*,*,#67221,.T.); -#67477 = ORIENTED_EDGE('',*,*,#37695,.T.); -#67478 = ADVANCED_FACE('',(#67479),#42672,.F.); -#67479 = FACE_BOUND('',#67480,.F.); -#67480 = EDGE_LOOP('',(#67481,#67482,#67483,#67484,#67485,#67486,#67506, - #67507,#67508,#67509)); -#67481 = ORIENTED_EDGE('',*,*,#54455,.F.); -#67482 = ORIENTED_EDGE('',*,*,#67442,.T.); -#67483 = ORIENTED_EDGE('',*,*,#67372,.F.); -#67484 = ORIENTED_EDGE('',*,*,#67099,.T.); -#67485 = ORIENTED_EDGE('',*,*,#42656,.T.); -#67486 = ORIENTED_EDGE('',*,*,#67487,.F.); -#67487 = EDGE_CURVE('',#55485,#42625,#67488,.T.); -#67488 = SURFACE_CURVE('',#67489,(#67493,#67500),.PCURVE_S1.); -#67489 = LINE('',#67490,#67491); -#67490 = CARTESIAN_POINT('',(-2.4,-1.225,-0.56)); -#67491 = VECTOR('',#67492,1.); -#67492 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67493 = PCURVE('',#42672,#67494); -#67494 = DEFINITIONAL_REPRESENTATION('',(#67495),#67499); -#67495 = LINE('',#67496,#67497); -#67496 = CARTESIAN_POINT('',(1.35,0.E+000)); -#67497 = VECTOR('',#67498,1.); -#67498 = DIRECTION('',(0.E+000,-1.)); -#67499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67500 = PCURVE('',#42645,#67501); -#67501 = DEFINITIONAL_REPRESENTATION('',(#67502),#67505); -#67502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67503,#67504),.UNSPECIFIED., +#69850 = CARTESIAN_POINT('',(0.322455069719,-1.05)); +#69851 = CARTESIAN_POINT('',(0.501814803522,-0.655880619748)); +#69852 = CARTESIAN_POINT('',(0.753452332042,-1.008270395764)); +#69853 = CARTESIAN_POINT('',(1.005089860562,-1.36066017178)); +#69854 = CARTESIAN_POINT('',(0.574092598239,-1.402389776016)); +#69855 = CARTESIAN_POINT('',(0.143095335915,-1.444119380252)); +#69856 = CARTESIAN_POINT('',(0.322455069719,-1.05)); +#69857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69858 = ORIENTED_EDGE('',*,*,#56778,.F.); +#69859 = ORIENTED_EDGE('',*,*,#56965,.T.); +#69860 = ORIENTED_EDGE('',*,*,#55631,.F.); +#69861 = ORIENTED_EDGE('',*,*,#69787,.T.); +#69862 = ADVANCED_FACE('',(#69863),#40108,.F.); +#69863 = FACE_BOUND('',#69864,.F.); +#69864 = EDGE_LOOP('',(#69865,#69866,#69867,#69868,#69869)); +#69865 = ORIENTED_EDGE('',*,*,#56900,.T.); +#69866 = ORIENTED_EDGE('',*,*,#57014,.F.); +#69867 = ORIENTED_EDGE('',*,*,#57223,.T.); +#69868 = ORIENTED_EDGE('',*,*,#69613,.T.); +#69869 = ORIENTED_EDGE('',*,*,#40087,.T.); +#69870 = ADVANCED_FACE('',(#69871),#45064,.F.); +#69871 = FACE_BOUND('',#69872,.F.); +#69872 = EDGE_LOOP('',(#69873,#69874,#69875,#69876,#69877,#69878,#69898, + #69899,#69900,#69901)); +#69873 = ORIENTED_EDGE('',*,*,#56847,.F.); +#69874 = ORIENTED_EDGE('',*,*,#69834,.T.); +#69875 = ORIENTED_EDGE('',*,*,#69764,.F.); +#69876 = ORIENTED_EDGE('',*,*,#69491,.T.); +#69877 = ORIENTED_EDGE('',*,*,#45048,.T.); +#69878 = ORIENTED_EDGE('',*,*,#69879,.F.); +#69879 = EDGE_CURVE('',#57877,#45017,#69880,.T.); +#69880 = SURFACE_CURVE('',#69881,(#69885,#69892),.PCURVE_S1.); +#69881 = LINE('',#69882,#69883); +#69882 = CARTESIAN_POINT('',(-2.4,-1.225,-0.56)); +#69883 = VECTOR('',#69884,1.); +#69884 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69885 = PCURVE('',#45064,#69886); +#69886 = DEFINITIONAL_REPRESENTATION('',(#69887),#69891); +#69887 = LINE('',#69888,#69889); +#69888 = CARTESIAN_POINT('',(1.35,0.E+000)); +#69889 = VECTOR('',#69890,1.); +#69890 = DIRECTION('',(0.E+000,-1.)); +#69891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69892 = PCURVE('',#45037,#69893); +#69893 = DEFINITIONAL_REPRESENTATION('',(#69894),#69897); +#69894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69895,#69896),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67503 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#67504 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#67505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67506 = ORIENTED_EDGE('',*,*,#55484,.F.); -#67507 = ORIENTED_EDGE('',*,*,#55171,.F.); -#67508 = ORIENTED_EDGE('',*,*,#54938,.F.); -#67509 = ORIENTED_EDGE('',*,*,#54144,.F.); -#67510 = ADVANCED_FACE('',(#67511),#42645,.F.); -#67511 = FACE_BOUND('',#67512,.F.); -#67512 = EDGE_LOOP('',(#67513,#67514,#67515,#67516)); -#67513 = ORIENTED_EDGE('',*,*,#55507,.F.); -#67514 = ORIENTED_EDGE('',*,*,#67487,.T.); -#67515 = ORIENTED_EDGE('',*,*,#42624,.T.); -#67516 = ORIENTED_EDGE('',*,*,#67517,.F.); -#67517 = EDGE_CURVE('',#55508,#42597,#67518,.T.); -#67518 = SURFACE_CURVE('',#67519,(#67523,#67529),.PCURVE_S1.); -#67519 = LINE('',#67520,#67521); -#67520 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); -#67521 = VECTOR('',#67522,1.); -#67522 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67523 = PCURVE('',#42645,#67524); -#67524 = DEFINITIONAL_REPRESENTATION('',(#67525),#67528); -#67525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67526,#67527),.UNSPECIFIED., +#69895 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#69896 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#69897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69898 = ORIENTED_EDGE('',*,*,#57876,.F.); +#69899 = ORIENTED_EDGE('',*,*,#57563,.F.); +#69900 = ORIENTED_EDGE('',*,*,#57330,.F.); +#69901 = ORIENTED_EDGE('',*,*,#56536,.F.); +#69902 = ADVANCED_FACE('',(#69903),#45037,.F.); +#69903 = FACE_BOUND('',#69904,.F.); +#69904 = EDGE_LOOP('',(#69905,#69906,#69907,#69908)); +#69905 = ORIENTED_EDGE('',*,*,#57899,.F.); +#69906 = ORIENTED_EDGE('',*,*,#69879,.T.); +#69907 = ORIENTED_EDGE('',*,*,#45016,.T.); +#69908 = ORIENTED_EDGE('',*,*,#69909,.F.); +#69909 = EDGE_CURVE('',#57900,#44989,#69910,.T.); +#69910 = SURFACE_CURVE('',#69911,(#69915,#69921),.PCURVE_S1.); +#69911 = LINE('',#69912,#69913); +#69912 = CARTESIAN_POINT('',(-2.25,-1.225,-0.41)); +#69913 = VECTOR('',#69914,1.); +#69914 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69915 = PCURVE('',#45037,#69916); +#69916 = DEFINITIONAL_REPRESENTATION('',(#69917),#69920); +#69917 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69918,#69919),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67526 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#67527 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#67528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67529 = PCURVE('',#42612,#67530); -#67530 = DEFINITIONAL_REPRESENTATION('',(#67531),#67535); -#67531 = LINE('',#67532,#67533); -#67532 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67533 = VECTOR('',#67534,1.); -#67534 = DIRECTION('',(0.E+000,-1.)); -#67535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67536 = ADVANCED_FACE('',(#67537),#42612,.F.); -#67537 = FACE_BOUND('',#67538,.F.); -#67538 = EDGE_LOOP('',(#67539,#67559,#67560,#67561)); -#67539 = ORIENTED_EDGE('',*,*,#67540,.T.); -#67540 = EDGE_CURVE('',#42569,#55531,#67541,.T.); -#67541 = SURFACE_CURVE('',#67542,(#67546,#67553),.PCURVE_S1.); -#67542 = LINE('',#67543,#67544); -#67543 = CARTESIAN_POINT('',(-2.25,-0.925,-0.4)); -#67544 = VECTOR('',#67545,1.); -#67545 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#67546 = PCURVE('',#42612,#67547); -#67547 = DEFINITIONAL_REPRESENTATION('',(#67548),#67552); -#67548 = LINE('',#67549,#67550); -#67549 = CARTESIAN_POINT('',(1.E-002,-0.3)); -#67550 = VECTOR('',#67551,1.); -#67551 = DIRECTION('',(0.E+000,1.)); -#67552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67553 = PCURVE('',#42585,#67554); -#67554 = DEFINITIONAL_REPRESENTATION('',(#67555),#67558); -#67555 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67556,#67557),.UNSPECIFIED., +#69918 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#69919 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#69920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69921 = PCURVE('',#45004,#69922); +#69922 = DEFINITIONAL_REPRESENTATION('',(#69923),#69927); +#69923 = LINE('',#69924,#69925); +#69924 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69925 = VECTOR('',#69926,1.); +#69926 = DIRECTION('',(0.E+000,-1.)); +#69927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69928 = ADVANCED_FACE('',(#69929),#45004,.F.); +#69929 = FACE_BOUND('',#69930,.F.); +#69930 = EDGE_LOOP('',(#69931,#69951,#69952,#69953)); +#69931 = ORIENTED_EDGE('',*,*,#69932,.T.); +#69932 = EDGE_CURVE('',#44961,#57923,#69933,.T.); +#69933 = SURFACE_CURVE('',#69934,(#69938,#69945),.PCURVE_S1.); +#69934 = LINE('',#69935,#69936); +#69935 = CARTESIAN_POINT('',(-2.25,-0.925,-0.4)); +#69936 = VECTOR('',#69937,1.); +#69937 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#69938 = PCURVE('',#45004,#69939); +#69939 = DEFINITIONAL_REPRESENTATION('',(#69940),#69944); +#69940 = LINE('',#69941,#69942); +#69941 = CARTESIAN_POINT('',(1.E-002,-0.3)); +#69942 = VECTOR('',#69943,1.); +#69943 = DIRECTION('',(0.E+000,1.)); +#69944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69945 = PCURVE('',#44977,#69946); +#69946 = DEFINITIONAL_REPRESENTATION('',(#69947),#69950); +#69947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69948,#69949),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67556 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#67557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67559 = ORIENTED_EDGE('',*,*,#55530,.F.); -#67560 = ORIENTED_EDGE('',*,*,#67517,.T.); -#67561 = ORIENTED_EDGE('',*,*,#42596,.T.); -#67562 = ADVANCED_FACE('',(#67563),#42380,.F.); -#67563 = FACE_BOUND('',#67564,.F.); -#67564 = EDGE_LOOP('',(#67565,#67585,#67586,#67606)); -#67565 = ORIENTED_EDGE('',*,*,#67566,.F.); -#67566 = EDGE_CURVE('',#42365,#55696,#67567,.T.); -#67567 = SURFACE_CURVE('',#67568,(#67572,#67579),.PCURVE_S1.); -#67568 = LINE('',#67569,#67570); -#67569 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); -#67570 = VECTOR('',#67571,1.); -#67571 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#67572 = PCURVE('',#42380,#67573); -#67573 = DEFINITIONAL_REPRESENTATION('',(#67574),#67578); -#67574 = LINE('',#67575,#67576); -#67575 = CARTESIAN_POINT('',(1.21,-0.3)); -#67576 = VECTOR('',#67577,1.); -#67577 = DIRECTION('',(0.E+000,1.)); -#67578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67579 = PCURVE('',#42409,#67580); -#67580 = DEFINITIONAL_REPRESENTATION('',(#67581),#67584); -#67581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67582,#67583),.UNSPECIFIED., +#69948 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#69949 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69951 = ORIENTED_EDGE('',*,*,#57922,.F.); +#69952 = ORIENTED_EDGE('',*,*,#69909,.T.); +#69953 = ORIENTED_EDGE('',*,*,#44988,.T.); +#69954 = ADVANCED_FACE('',(#69955),#44772,.F.); +#69955 = FACE_BOUND('',#69956,.F.); +#69956 = EDGE_LOOP('',(#69957,#69977,#69978,#69998)); +#69957 = ORIENTED_EDGE('',*,*,#69958,.F.); +#69958 = EDGE_CURVE('',#44757,#58088,#69959,.T.); +#69959 = SURFACE_CURVE('',#69960,(#69964,#69971),.PCURVE_S1.); +#69960 = LINE('',#69961,#69962); +#69961 = CARTESIAN_POINT('',(-2.25,-0.925,0.8)); +#69962 = VECTOR('',#69963,1.); +#69963 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#69964 = PCURVE('',#44772,#69965); +#69965 = DEFINITIONAL_REPRESENTATION('',(#69966),#69970); +#69966 = LINE('',#69967,#69968); +#69967 = CARTESIAN_POINT('',(1.21,-0.3)); +#69968 = VECTOR('',#69969,1.); +#69969 = DIRECTION('',(0.E+000,1.)); +#69970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69971 = PCURVE('',#44801,#69972); +#69972 = DEFINITIONAL_REPRESENTATION('',(#69973),#69976); +#69973 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69974,#69975),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67582 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#67583 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#67584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67585 = ORIENTED_EDGE('',*,*,#42364,.T.); -#67586 = ORIENTED_EDGE('',*,*,#67587,.F.); -#67587 = EDGE_CURVE('',#55723,#42333,#67588,.T.); -#67588 = SURFACE_CURVE('',#67589,(#67593,#67600),.PCURVE_S1.); -#67589 = LINE('',#67590,#67591); -#67590 = CARTESIAN_POINT('',(-2.25,-1.225,0.81)); -#67591 = VECTOR('',#67592,1.); -#67592 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67593 = PCURVE('',#42380,#67594); -#67594 = DEFINITIONAL_REPRESENTATION('',(#67595),#67599); -#67595 = LINE('',#67596,#67597); -#67596 = CARTESIAN_POINT('',(1.22,0.E+000)); -#67597 = VECTOR('',#67598,1.); -#67598 = DIRECTION('',(0.E+000,-1.)); -#67599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67600 = PCURVE('',#42353,#67601); -#67601 = DEFINITIONAL_REPRESENTATION('',(#67602),#67605); -#67602 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67603,#67604),.UNSPECIFIED., +#69974 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#69975 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#69976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69977 = ORIENTED_EDGE('',*,*,#44756,.T.); +#69978 = ORIENTED_EDGE('',*,*,#69979,.F.); +#69979 = EDGE_CURVE('',#58115,#44725,#69980,.T.); +#69980 = SURFACE_CURVE('',#69981,(#69985,#69992),.PCURVE_S1.); +#69981 = LINE('',#69982,#69983); +#69982 = CARTESIAN_POINT('',(-2.25,-1.225,0.81)); +#69983 = VECTOR('',#69984,1.); +#69984 = DIRECTION('',(0.E+000,1.,0.E+000)); +#69985 = PCURVE('',#44772,#69986); +#69986 = DEFINITIONAL_REPRESENTATION('',(#69987),#69991); +#69987 = LINE('',#69988,#69989); +#69988 = CARTESIAN_POINT('',(1.22,0.E+000)); +#69989 = VECTOR('',#69990,1.); +#69990 = DIRECTION('',(0.E+000,-1.)); +#69991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69992 = PCURVE('',#44745,#69993); +#69993 = DEFINITIONAL_REPRESENTATION('',(#69994),#69997); +#69994 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69995,#69996),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67603 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67604 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#67605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67606 = ORIENTED_EDGE('',*,*,#55722,.F.); -#67607 = ADVANCED_FACE('',(#67608),#42585,.F.); -#67608 = FACE_BOUND('',#67609,.F.); -#67609 = EDGE_LOOP('',(#67610,#67611,#67612,#67632)); -#67610 = ORIENTED_EDGE('',*,*,#67540,.F.); -#67611 = ORIENTED_EDGE('',*,*,#42568,.F.); -#67612 = ORIENTED_EDGE('',*,*,#67613,.F.); -#67613 = EDGE_CURVE('',#55554,#42541,#67614,.T.); -#67614 = SURFACE_CURVE('',#67615,(#67619,#67625),.PCURVE_S1.); -#67615 = LINE('',#67616,#67617); -#67616 = CARTESIAN_POINT('',(-2.4,-1.225,-0.25)); -#67617 = VECTOR('',#67618,1.); -#67618 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67619 = PCURVE('',#42585,#67620); -#67620 = DEFINITIONAL_REPRESENTATION('',(#67621),#67624); -#67621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67622,#67623),.UNSPECIFIED., +#69995 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#69996 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#69997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#69998 = ORIENTED_EDGE('',*,*,#58114,.F.); +#69999 = ADVANCED_FACE('',(#70000),#44977,.F.); +#70000 = FACE_BOUND('',#70001,.F.); +#70001 = EDGE_LOOP('',(#70002,#70003,#70004,#70024)); +#70002 = ORIENTED_EDGE('',*,*,#69932,.F.); +#70003 = ORIENTED_EDGE('',*,*,#44960,.F.); +#70004 = ORIENTED_EDGE('',*,*,#70005,.F.); +#70005 = EDGE_CURVE('',#57946,#44933,#70006,.T.); +#70006 = SURFACE_CURVE('',#70007,(#70011,#70017),.PCURVE_S1.); +#70007 = LINE('',#70008,#70009); +#70008 = CARTESIAN_POINT('',(-2.4,-1.225,-0.25)); +#70009 = VECTOR('',#70010,1.); +#70010 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70011 = PCURVE('',#44977,#70012); +#70012 = DEFINITIONAL_REPRESENTATION('',(#70013),#70016); +#70013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70014,#70015),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67622 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#67623 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#67624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67625 = PCURVE('',#42556,#67626); -#67626 = DEFINITIONAL_REPRESENTATION('',(#67627),#67631); -#67627 = LINE('',#67628,#67629); -#67628 = CARTESIAN_POINT('',(1.3,0.E+000)); -#67629 = VECTOR('',#67630,1.); -#67630 = DIRECTION('',(0.E+000,-1.)); -#67631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67632 = ORIENTED_EDGE('',*,*,#55553,.T.); -#67633 = ADVANCED_FACE('',(#67634),#42556,.T.); -#67634 = FACE_BOUND('',#67635,.F.); -#67635 = EDGE_LOOP('',(#67636,#67637,#67638,#67639)); -#67636 = ORIENTED_EDGE('',*,*,#55580,.T.); -#67637 = ORIENTED_EDGE('',*,*,#67613,.T.); -#67638 = ORIENTED_EDGE('',*,*,#42540,.F.); -#67639 = ORIENTED_EDGE('',*,*,#67640,.F.); -#67640 = EDGE_CURVE('',#55581,#42509,#67641,.T.); -#67641 = SURFACE_CURVE('',#67642,(#67646,#67653),.PCURVE_S1.); -#67642 = LINE('',#67643,#67644); -#67643 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); -#67644 = VECTOR('',#67645,1.); -#67645 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67646 = PCURVE('',#42556,#67647); -#67647 = DEFINITIONAL_REPRESENTATION('',(#67648),#67652); -#67648 = LINE('',#67649,#67650); -#67649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67650 = VECTOR('',#67651,1.); -#67651 = DIRECTION('',(0.E+000,-1.)); -#67652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67653 = PCURVE('',#42529,#67654); -#67654 = DEFINITIONAL_REPRESENTATION('',(#67655),#67658); -#67655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67656,#67657),.UNSPECIFIED., +#70014 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#70015 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#70016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70017 = PCURVE('',#44948,#70018); +#70018 = DEFINITIONAL_REPRESENTATION('',(#70019),#70023); +#70019 = LINE('',#70020,#70021); +#70020 = CARTESIAN_POINT('',(1.3,0.E+000)); +#70021 = VECTOR('',#70022,1.); +#70022 = DIRECTION('',(0.E+000,-1.)); +#70023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70024 = ORIENTED_EDGE('',*,*,#57945,.T.); +#70025 = ADVANCED_FACE('',(#70026),#44948,.T.); +#70026 = FACE_BOUND('',#70027,.F.); +#70027 = EDGE_LOOP('',(#70028,#70029,#70030,#70031)); +#70028 = ORIENTED_EDGE('',*,*,#57972,.T.); +#70029 = ORIENTED_EDGE('',*,*,#70005,.T.); +#70030 = ORIENTED_EDGE('',*,*,#44932,.F.); +#70031 = ORIENTED_EDGE('',*,*,#70032,.F.); +#70032 = EDGE_CURVE('',#57973,#44901,#70033,.T.); +#70033 = SURFACE_CURVE('',#70034,(#70038,#70045),.PCURVE_S1.); +#70034 = LINE('',#70035,#70036); +#70035 = CARTESIAN_POINT('',(-3.7,-1.225,-0.25)); +#70036 = VECTOR('',#70037,1.); +#70037 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70038 = PCURVE('',#44948,#70039); +#70039 = DEFINITIONAL_REPRESENTATION('',(#70040),#70044); +#70040 = LINE('',#70041,#70042); +#70041 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70042 = VECTOR('',#70043,1.); +#70043 = DIRECTION('',(0.E+000,-1.)); +#70044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70045 = PCURVE('',#44921,#70046); +#70046 = DEFINITIONAL_REPRESENTATION('',(#70047),#70050); +#70047 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70048,#70049),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67656 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#67657 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#67658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67659 = ADVANCED_FACE('',(#67660),#42529,.T.); -#67660 = FACE_BOUND('',#67661,.T.); -#67661 = EDGE_LOOP('',(#67662,#67663,#67683,#67684)); -#67662 = ORIENTED_EDGE('',*,*,#55603,.F.); -#67663 = ORIENTED_EDGE('',*,*,#67664,.T.); -#67664 = EDGE_CURVE('',#55604,#42481,#67665,.T.); -#67665 = SURFACE_CURVE('',#67666,(#67670,#67676),.PCURVE_S1.); -#67666 = LINE('',#67667,#67668); -#67667 = CARTESIAN_POINT('',(-3.9,-1.225,-5.E-002)); -#67668 = VECTOR('',#67669,1.); -#67669 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67670 = PCURVE('',#42529,#67671); -#67671 = DEFINITIONAL_REPRESENTATION('',(#67672),#67675); -#67672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67673,#67674),.UNSPECIFIED., +#70048 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#70049 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#70050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70051 = ADVANCED_FACE('',(#70052),#44921,.T.); +#70052 = FACE_BOUND('',#70053,.T.); +#70053 = EDGE_LOOP('',(#70054,#70055,#70075,#70076)); +#70054 = ORIENTED_EDGE('',*,*,#57995,.F.); +#70055 = ORIENTED_EDGE('',*,*,#70056,.T.); +#70056 = EDGE_CURVE('',#57996,#44873,#70057,.T.); +#70057 = SURFACE_CURVE('',#70058,(#70062,#70068),.PCURVE_S1.); +#70058 = LINE('',#70059,#70060); +#70059 = CARTESIAN_POINT('',(-3.9,-1.225,-5.E-002)); +#70060 = VECTOR('',#70061,1.); +#70061 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70062 = PCURVE('',#44921,#70063); +#70063 = DEFINITIONAL_REPRESENTATION('',(#70064),#70067); +#70064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70065,#70066),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67673 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#67674 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#67675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67676 = PCURVE('',#42496,#67677); -#67677 = DEFINITIONAL_REPRESENTATION('',(#67678),#67682); -#67678 = LINE('',#67679,#67680); -#67679 = CARTESIAN_POINT('',(0.5,0.E+000)); -#67680 = VECTOR('',#67681,1.); -#67681 = DIRECTION('',(0.E+000,-1.)); -#67682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67683 = ORIENTED_EDGE('',*,*,#42508,.T.); -#67684 = ORIENTED_EDGE('',*,*,#67640,.F.); -#67685 = ADVANCED_FACE('',(#67686),#42496,.T.); -#67686 = FACE_BOUND('',#67687,.F.); -#67687 = EDGE_LOOP('',(#67688,#67689,#67690,#67691)); -#67688 = ORIENTED_EDGE('',*,*,#55626,.T.); -#67689 = ORIENTED_EDGE('',*,*,#67664,.T.); -#67690 = ORIENTED_EDGE('',*,*,#42480,.F.); -#67691 = ORIENTED_EDGE('',*,*,#67692,.F.); -#67692 = EDGE_CURVE('',#55627,#42449,#67693,.T.); -#67693 = SURFACE_CURVE('',#67694,(#67698,#67705),.PCURVE_S1.); -#67694 = LINE('',#67695,#67696); -#67695 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); -#67696 = VECTOR('',#67697,1.); -#67697 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67698 = PCURVE('',#42496,#67699); -#67699 = DEFINITIONAL_REPRESENTATION('',(#67700),#67704); -#67700 = LINE('',#67701,#67702); -#67701 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67702 = VECTOR('',#67703,1.); -#67703 = DIRECTION('',(0.E+000,-1.)); -#67704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67705 = PCURVE('',#42469,#67706); -#67706 = DEFINITIONAL_REPRESENTATION('',(#67707),#67710); -#67707 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67708,#67709),.UNSPECIFIED., +#70065 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70066 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70068 = PCURVE('',#44888,#70069); +#70069 = DEFINITIONAL_REPRESENTATION('',(#70070),#70074); +#70070 = LINE('',#70071,#70072); +#70071 = CARTESIAN_POINT('',(0.5,0.E+000)); +#70072 = VECTOR('',#70073,1.); +#70073 = DIRECTION('',(0.E+000,-1.)); +#70074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70075 = ORIENTED_EDGE('',*,*,#44900,.T.); +#70076 = ORIENTED_EDGE('',*,*,#70032,.F.); +#70077 = ADVANCED_FACE('',(#70078),#44888,.T.); +#70078 = FACE_BOUND('',#70079,.F.); +#70079 = EDGE_LOOP('',(#70080,#70081,#70082,#70083)); +#70080 = ORIENTED_EDGE('',*,*,#58018,.T.); +#70081 = ORIENTED_EDGE('',*,*,#70056,.T.); +#70082 = ORIENTED_EDGE('',*,*,#44872,.F.); +#70083 = ORIENTED_EDGE('',*,*,#70084,.F.); +#70084 = EDGE_CURVE('',#58019,#44841,#70085,.T.); +#70085 = SURFACE_CURVE('',#70086,(#70090,#70097),.PCURVE_S1.); +#70086 = LINE('',#70087,#70088); +#70087 = CARTESIAN_POINT('',(-3.9,-1.225,0.45)); +#70088 = VECTOR('',#70089,1.); +#70089 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70090 = PCURVE('',#44888,#70091); +#70091 = DEFINITIONAL_REPRESENTATION('',(#70092),#70096); +#70092 = LINE('',#70093,#70094); +#70093 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70094 = VECTOR('',#70095,1.); +#70095 = DIRECTION('',(0.E+000,-1.)); +#70096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70097 = PCURVE('',#44861,#70098); +#70098 = DEFINITIONAL_REPRESENTATION('',(#70099),#70102); +#70099 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70100,#70101),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67708 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#67709 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#67710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67711 = ADVANCED_FACE('',(#67712),#42469,.T.); -#67712 = FACE_BOUND('',#67713,.T.); -#67713 = EDGE_LOOP('',(#67714,#67715,#67735,#67736)); -#67714 = ORIENTED_EDGE('',*,*,#55649,.F.); -#67715 = ORIENTED_EDGE('',*,*,#67716,.T.); -#67716 = EDGE_CURVE('',#55650,#42421,#67717,.T.); -#67717 = SURFACE_CURVE('',#67718,(#67722,#67728),.PCURVE_S1.); -#67718 = LINE('',#67719,#67720); -#67719 = CARTESIAN_POINT('',(-3.7,-1.225,0.65)); -#67720 = VECTOR('',#67721,1.); -#67721 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67722 = PCURVE('',#42469,#67723); -#67723 = DEFINITIONAL_REPRESENTATION('',(#67724),#67727); -#67724 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67725,#67726),.UNSPECIFIED., +#70100 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70101 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70103 = ADVANCED_FACE('',(#70104),#44861,.T.); +#70104 = FACE_BOUND('',#70105,.T.); +#70105 = EDGE_LOOP('',(#70106,#70107,#70127,#70128)); +#70106 = ORIENTED_EDGE('',*,*,#58041,.F.); +#70107 = ORIENTED_EDGE('',*,*,#70108,.T.); +#70108 = EDGE_CURVE('',#58042,#44813,#70109,.T.); +#70109 = SURFACE_CURVE('',#70110,(#70114,#70120),.PCURVE_S1.); +#70110 = LINE('',#70111,#70112); +#70111 = CARTESIAN_POINT('',(-3.7,-1.225,0.65)); +#70112 = VECTOR('',#70113,1.); +#70113 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70114 = PCURVE('',#44861,#70115); +#70115 = DEFINITIONAL_REPRESENTATION('',(#70116),#70119); +#70116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70117,#70118),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67725 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#67726 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#67727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67728 = PCURVE('',#42436,#67729); -#67729 = DEFINITIONAL_REPRESENTATION('',(#67730),#67734); -#67730 = LINE('',#67731,#67732); -#67731 = CARTESIAN_POINT('',(1.3,0.E+000)); -#67732 = VECTOR('',#67733,1.); -#67733 = DIRECTION('',(0.E+000,-1.)); -#67734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67735 = ORIENTED_EDGE('',*,*,#42448,.T.); -#67736 = ORIENTED_EDGE('',*,*,#67692,.F.); -#67737 = ADVANCED_FACE('',(#67738),#42436,.T.); -#67738 = FACE_BOUND('',#67739,.F.); -#67739 = EDGE_LOOP('',(#67740,#67741,#67742,#67743)); -#67740 = ORIENTED_EDGE('',*,*,#55672,.T.); -#67741 = ORIENTED_EDGE('',*,*,#67716,.T.); -#67742 = ORIENTED_EDGE('',*,*,#42420,.F.); -#67743 = ORIENTED_EDGE('',*,*,#67744,.F.); -#67744 = EDGE_CURVE('',#55673,#42393,#67745,.T.); -#67745 = SURFACE_CURVE('',#67746,(#67750,#67757),.PCURVE_S1.); -#67746 = LINE('',#67747,#67748); -#67747 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); -#67748 = VECTOR('',#67749,1.); -#67749 = DIRECTION('',(0.E+000,1.,0.E+000)); -#67750 = PCURVE('',#42436,#67751); -#67751 = DEFINITIONAL_REPRESENTATION('',(#67752),#67756); -#67752 = LINE('',#67753,#67754); -#67753 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#67754 = VECTOR('',#67755,1.); -#67755 = DIRECTION('',(0.E+000,-1.)); -#67756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67757 = PCURVE('',#42409,#67758); -#67758 = DEFINITIONAL_REPRESENTATION('',(#67759),#67762); -#67759 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67760,#67761),.UNSPECIFIED., +#70117 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#70118 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#70119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70120 = PCURVE('',#44828,#70121); +#70121 = DEFINITIONAL_REPRESENTATION('',(#70122),#70126); +#70122 = LINE('',#70123,#70124); +#70123 = CARTESIAN_POINT('',(1.3,0.E+000)); +#70124 = VECTOR('',#70125,1.); +#70125 = DIRECTION('',(0.E+000,-1.)); +#70126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70127 = ORIENTED_EDGE('',*,*,#44840,.T.); +#70128 = ORIENTED_EDGE('',*,*,#70084,.F.); +#70129 = ADVANCED_FACE('',(#70130),#44828,.T.); +#70130 = FACE_BOUND('',#70131,.F.); +#70131 = EDGE_LOOP('',(#70132,#70133,#70134,#70135)); +#70132 = ORIENTED_EDGE('',*,*,#58064,.T.); +#70133 = ORIENTED_EDGE('',*,*,#70108,.T.); +#70134 = ORIENTED_EDGE('',*,*,#44812,.F.); +#70135 = ORIENTED_EDGE('',*,*,#70136,.F.); +#70136 = EDGE_CURVE('',#58065,#44785,#70137,.T.); +#70137 = SURFACE_CURVE('',#70138,(#70142,#70149),.PCURVE_S1.); +#70138 = LINE('',#70139,#70140); +#70139 = CARTESIAN_POINT('',(-2.4,-1.225,0.65)); +#70140 = VECTOR('',#70141,1.); +#70141 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70142 = PCURVE('',#44828,#70143); +#70143 = DEFINITIONAL_REPRESENTATION('',(#70144),#70148); +#70144 = LINE('',#70145,#70146); +#70145 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70146 = VECTOR('',#70147,1.); +#70147 = DIRECTION('',(0.E+000,-1.)); +#70148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70149 = PCURVE('',#44801,#70150); +#70150 = DEFINITIONAL_REPRESENTATION('',(#70151),#70154); +#70151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70152,#70153),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#67760 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#67761 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#67762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67763 = ADVANCED_FACE('',(#67764),#42409,.F.); -#67764 = FACE_BOUND('',#67765,.F.); -#67765 = EDGE_LOOP('',(#67766,#67767,#67768,#67769)); -#67766 = ORIENTED_EDGE('',*,*,#67566,.T.); -#67767 = ORIENTED_EDGE('',*,*,#55695,.T.); -#67768 = ORIENTED_EDGE('',*,*,#67744,.T.); -#67769 = ORIENTED_EDGE('',*,*,#42392,.F.); -#67770 = ADVANCED_FACE('',(#67771),#42353,.F.); -#67771 = FACE_BOUND('',#67772,.F.); -#67772 = EDGE_LOOP('',(#67773,#67774,#67775,#67776)); -#67773 = ORIENTED_EDGE('',*,*,#55745,.F.); -#67774 = ORIENTED_EDGE('',*,*,#67587,.T.); -#67775 = ORIENTED_EDGE('',*,*,#42332,.T.); -#67776 = ORIENTED_EDGE('',*,*,#54764,.F.); -#67777 = ADVANCED_FACE('',(#67778),#53200,.T.); -#67778 = FACE_BOUND('',#67779,.T.); -#67779 = EDGE_LOOP('',(#67780,#67781,#67782,#67802)); -#67780 = ORIENTED_EDGE('',*,*,#53184,.T.); -#67781 = ORIENTED_EDGE('',*,*,#67244,.F.); -#67782 = ORIENTED_EDGE('',*,*,#67783,.F.); -#67783 = EDGE_CURVE('',#54882,#67245,#67784,.T.); -#67784 = SURFACE_CURVE('',#67785,(#67789,#67795),.PCURVE_S1.); -#67785 = LINE('',#67786,#67787); -#67786 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); -#67787 = VECTOR('',#67788,1.); -#67788 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67789 = PCURVE('',#53200,#67790); -#67790 = DEFINITIONAL_REPRESENTATION('',(#67791),#67794); -#67791 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67792,#67793),.UNSPECIFIED., +#70152 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#70153 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#70154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70155 = ADVANCED_FACE('',(#70156),#44801,.F.); +#70156 = FACE_BOUND('',#70157,.F.); +#70157 = EDGE_LOOP('',(#70158,#70159,#70160,#70161)); +#70158 = ORIENTED_EDGE('',*,*,#69958,.T.); +#70159 = ORIENTED_EDGE('',*,*,#58087,.T.); +#70160 = ORIENTED_EDGE('',*,*,#70136,.T.); +#70161 = ORIENTED_EDGE('',*,*,#44784,.F.); +#70162 = ADVANCED_FACE('',(#70163),#44745,.F.); +#70163 = FACE_BOUND('',#70164,.F.); +#70164 = EDGE_LOOP('',(#70165,#70166,#70167,#70168)); +#70165 = ORIENTED_EDGE('',*,*,#58137,.F.); +#70166 = ORIENTED_EDGE('',*,*,#69979,.T.); +#70167 = ORIENTED_EDGE('',*,*,#44724,.T.); +#70168 = ORIENTED_EDGE('',*,*,#57156,.F.); +#70169 = ADVANCED_FACE('',(#70170),#55592,.T.); +#70170 = FACE_BOUND('',#70171,.T.); +#70171 = EDGE_LOOP('',(#70172,#70173,#70174,#70194)); +#70172 = ORIENTED_EDGE('',*,*,#55576,.T.); +#70173 = ORIENTED_EDGE('',*,*,#69636,.F.); +#70174 = ORIENTED_EDGE('',*,*,#70175,.F.); +#70175 = EDGE_CURVE('',#57274,#69637,#70176,.T.); +#70176 = SURFACE_CURVE('',#70177,(#70181,#70187),.PCURVE_S1.); +#70177 = LINE('',#70178,#70179); +#70178 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-2.2)); +#70179 = VECTOR('',#70180,1.); +#70180 = DIRECTION('',(1.,0.E+000,0.E+000)); +#70181 = PCURVE('',#55592,#70182); +#70182 = DEFINITIONAL_REPRESENTATION('',(#70183),#70186); +#70183 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70184,#70185),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#67792 = CARTESIAN_POINT('',(4.712388980385,0.425735931288)); -#67793 = CARTESIAN_POINT('',(4.712388980385,0.85)); -#67794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67795 = PCURVE('',#55085,#67796); -#67796 = DEFINITIONAL_REPRESENTATION('',(#67797),#67801); -#67797 = LINE('',#67798,#67799); -#67798 = CARTESIAN_POINT('',(0.E+000,0.425735931288)); -#67799 = VECTOR('',#67800,1.); -#67800 = DIRECTION('',(0.E+000,1.)); -#67801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67802 = ORIENTED_EDGE('',*,*,#54881,.T.); -#67803 = ADVANCED_FACE('',(#67804),#40685,.T.); -#67804 = FACE_BOUND('',#67805,.T.); -#67805 = EDGE_LOOP('',(#67806,#67807,#67862,#67882)); -#67806 = ORIENTED_EDGE('',*,*,#53443,.T.); -#67807 = ORIENTED_EDGE('',*,*,#67808,.F.); -#67808 = EDGE_CURVE('',#67809,#53444,#67811,.T.); -#67809 = VERTEX_POINT('',#67810); -#67810 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); -#67811 = SURFACE_CURVE('',#67812,(#67821,#67850),.PCURVE_S1.); -#67812 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67813,#67814,#67815,#67816, - #67817,#67818,#67819,#67820),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#70184 = CARTESIAN_POINT('',(4.712388980385,0.425735931288)); +#70185 = CARTESIAN_POINT('',(4.712388980385,0.85)); +#70186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70187 = PCURVE('',#57477,#70188); +#70188 = DEFINITIONAL_REPRESENTATION('',(#70189),#70193); +#70189 = LINE('',#70190,#70191); +#70190 = CARTESIAN_POINT('',(0.E+000,0.425735931288)); +#70191 = VECTOR('',#70192,1.); +#70192 = DIRECTION('',(0.E+000,1.)); +#70193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70194 = ORIENTED_EDGE('',*,*,#57273,.T.); +#70195 = ADVANCED_FACE('',(#70196),#43077,.T.); +#70196 = FACE_BOUND('',#70197,.T.); +#70197 = EDGE_LOOP('',(#70198,#70199,#70254,#70274)); +#70198 = ORIENTED_EDGE('',*,*,#55835,.T.); +#70199 = ORIENTED_EDGE('',*,*,#70200,.F.); +#70200 = EDGE_CURVE('',#70201,#55836,#70203,.T.); +#70201 = VERTEX_POINT('',#70202); +#70202 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); +#70203 = SURFACE_CURVE('',#70204,(#70213,#70242),.PCURVE_S1.); +#70204 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70205,#70206,#70207,#70208, + #70209,#70210,#70211,#70212),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#67813 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); -#67814 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.215088834765)); -#67815 = CARTESIAN_POINT('',(3.328327844504,-0.720936224208, +#70205 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); +#70206 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.215088834765)); +#70207 = CARTESIAN_POINT('',(3.328327844504,-0.720936224208, -2.239519457455)); -#67816 = CARTESIAN_POINT('',(3.343621523704,-0.705642545008, +#70208 = CARTESIAN_POINT('',(3.343621523704,-0.705642545008, -2.278246267971)); -#67817 = CARTESIAN_POINT('',(3.371920174968,-0.677343893744, +#70209 = CARTESIAN_POINT('',(3.371920174968,-0.677343893744, -2.313670105381)); -#67818 = CARTESIAN_POINT('',(3.416186746343,-0.633077322369, +#70210 = CARTESIAN_POINT('',(3.416186746343,-0.633077322369, -2.341600728372)); -#67819 = CARTESIAN_POINT('',(3.452925233947,-0.596338834765,-2.35)); -#67820 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); -#67821 = PCURVE('',#40685,#67822); -#67822 = DEFINITIONAL_REPRESENTATION('',(#67823),#67849); -#67823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67824,#67825,#67826,#67827, - #67828,#67829,#67830,#67831,#67832,#67833,#67834,#67835,#67836, - #67837,#67838,#67839,#67840,#67841,#67842,#67843,#67844,#67845, - #67846,#67847,#67848),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#70211 = CARTESIAN_POINT('',(3.452925233947,-0.596338834765,-2.35)); +#70212 = CARTESIAN_POINT('',(3.474264068712,-0.575,-2.35)); +#70213 = PCURVE('',#43077,#70214); +#70214 = DEFINITIONAL_REPRESENTATION('',(#70215),#70241); +#70215 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70216,#70217,#70218,#70219, + #70220,#70221,#70222,#70223,#70224,#70225,#70226,#70227,#70228, + #70229,#70230,#70231,#70232,#70233,#70234,#70235,#70236,#70237, + #70238,#70239,#70240),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -83637,199 +86626,199 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67824 = CARTESIAN_POINT('',(4.712388980385,7.074264068712)); -#67825 = CARTESIAN_POINT('',(4.748933560976,7.074264139875)); -#67826 = CARTESIAN_POINT('',(4.81707874687,7.074800900836)); -#67827 = CARTESIAN_POINT('',(4.907992270893,7.076893501847)); -#67828 = CARTESIAN_POINT('',(4.991501242609,7.07993220638)); -#67829 = CARTESIAN_POINT('',(5.070203254432,7.083642017384)); -#67830 = CARTESIAN_POINT('',(5.144906443438,7.087966439425)); -#67831 = CARTESIAN_POINT('',(5.216603945889,7.092811667844)); -#67832 = CARTESIAN_POINT('',(5.285913848235,7.098125325936)); -#67833 = CARTESIAN_POINT('',(5.353274617376,7.103886191587)); -#67834 = CARTESIAN_POINT('',(5.419136101421,7.110066553548)); -#67835 = CARTESIAN_POINT('',(5.483899443317,7.116640439783)); -#67836 = CARTESIAN_POINT('',(5.547920698644,7.123581410541)); -#67837 = CARTESIAN_POINT('',(5.611491697867,7.13086315772)); -#67838 = CARTESIAN_POINT('',(5.674841699303,7.138488857618)); -#67839 = CARTESIAN_POINT('',(5.738220831198,7.14646179042)); -#67840 = CARTESIAN_POINT('',(5.801885308441,7.154784879652)); -#67841 = CARTESIAN_POINT('',(5.866098193035,7.163462371589)); -#67842 = CARTESIAN_POINT('',(5.931103476771,7.172493578169)); -#67843 = CARTESIAN_POINT('',(5.997203324603,7.181901066956)); -#67844 = CARTESIAN_POINT('',(6.064845544964,7.191730661123)); -#67845 = CARTESIAN_POINT('',(6.13454852804,7.202023249551)); -#67846 = CARTESIAN_POINT('',(6.206898120521,7.212821043713)); -#67847 = CARTESIAN_POINT('',(6.257321803275,7.220384280573)); -#67848 = CARTESIAN_POINT('',(6.28318530718,7.224264068712)); -#67849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67850 = PCURVE('',#53481,#67851); -#67851 = DEFINITIONAL_REPRESENTATION('',(#67852),#67861); -#67852 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67853,#67854,#67855,#67856, - #67857,#67858,#67859,#67860),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#70216 = CARTESIAN_POINT('',(4.712388980385,7.074264068712)); +#70217 = CARTESIAN_POINT('',(4.748933560976,7.074264139875)); +#70218 = CARTESIAN_POINT('',(4.81707874687,7.074800900836)); +#70219 = CARTESIAN_POINT('',(4.907992270893,7.076893501847)); +#70220 = CARTESIAN_POINT('',(4.991501242609,7.07993220638)); +#70221 = CARTESIAN_POINT('',(5.070203254432,7.083642017384)); +#70222 = CARTESIAN_POINT('',(5.144906443438,7.087966439425)); +#70223 = CARTESIAN_POINT('',(5.216603945889,7.092811667844)); +#70224 = CARTESIAN_POINT('',(5.285913848235,7.098125325936)); +#70225 = CARTESIAN_POINT('',(5.353274617376,7.103886191587)); +#70226 = CARTESIAN_POINT('',(5.419136101421,7.110066553548)); +#70227 = CARTESIAN_POINT('',(5.483899443317,7.116640439783)); +#70228 = CARTESIAN_POINT('',(5.547920698644,7.123581410541)); +#70229 = CARTESIAN_POINT('',(5.611491697867,7.13086315772)); +#70230 = CARTESIAN_POINT('',(5.674841699303,7.138488857618)); +#70231 = CARTESIAN_POINT('',(5.738220831198,7.14646179042)); +#70232 = CARTESIAN_POINT('',(5.801885308441,7.154784879652)); +#70233 = CARTESIAN_POINT('',(5.866098193035,7.163462371589)); +#70234 = CARTESIAN_POINT('',(5.931103476771,7.172493578169)); +#70235 = CARTESIAN_POINT('',(5.997203324603,7.181901066956)); +#70236 = CARTESIAN_POINT('',(6.064845544964,7.191730661123)); +#70237 = CARTESIAN_POINT('',(6.13454852804,7.202023249551)); +#70238 = CARTESIAN_POINT('',(6.206898120521,7.212821043713)); +#70239 = CARTESIAN_POINT('',(6.257321803275,7.220384280573)); +#70240 = CARTESIAN_POINT('',(6.28318530718,7.224264068712)); +#70241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70242 = PCURVE('',#55873,#70243); +#70243 = DEFINITIONAL_REPRESENTATION('',(#70244),#70253); +#70244 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70245,#70246,#70247,#70248, + #70249,#70250,#70251,#70252),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#67853 = CARTESIAN_POINT('',(0.479289321882,0.15)); -#67854 = CARTESIAN_POINT('',(0.479289321882,0.134911165235)); -#67855 = CARTESIAN_POINT('',(0.485036368722,0.110480542545)); -#67856 = CARTESIAN_POINT('',(0.506664897265,7.1753732029E-002)); -#67857 = CARTESIAN_POINT('',(0.546685233679,3.6329894619E-002)); -#67858 = CARTESIAN_POINT('',(0.609287619277,8.399271628E-003)); -#67859 = CARTESIAN_POINT('',(0.661243686708,0.E+000)); -#67860 = CARTESIAN_POINT('',(0.691421356238,0.E+000)); -#67861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67862 = ORIENTED_EDGE('',*,*,#67863,.F.); -#67863 = EDGE_CURVE('',#40658,#67809,#67864,.T.); -#67864 = SURFACE_CURVE('',#67865,(#67869,#67875),.PCURVE_S1.); -#67865 = LINE('',#67866,#67867); -#67866 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); -#67867 = VECTOR('',#67868,1.); -#67868 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67869 = PCURVE('',#40685,#67870); -#67870 = DEFINITIONAL_REPRESENTATION('',(#67871),#67874); -#67871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67872,#67873),.UNSPECIFIED., +#70245 = CARTESIAN_POINT('',(0.479289321882,0.15)); +#70246 = CARTESIAN_POINT('',(0.479289321882,0.134911165235)); +#70247 = CARTESIAN_POINT('',(0.485036368722,0.110480542545)); +#70248 = CARTESIAN_POINT('',(0.506664897265,7.1753732029E-002)); +#70249 = CARTESIAN_POINT('',(0.546685233679,3.6329894619E-002)); +#70250 = CARTESIAN_POINT('',(0.609287619277,8.399271628E-003)); +#70251 = CARTESIAN_POINT('',(0.661243686708,0.E+000)); +#70252 = CARTESIAN_POINT('',(0.691421356238,0.E+000)); +#70253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70254 = ORIENTED_EDGE('',*,*,#70255,.F.); +#70255 = EDGE_CURVE('',#43050,#70201,#70256,.T.); +#70256 = SURFACE_CURVE('',#70257,(#70261,#70267),.PCURVE_S1.); +#70257 = LINE('',#70258,#70259); +#70258 = CARTESIAN_POINT('',(2.9,-0.725,-2.2)); +#70259 = VECTOR('',#70260,1.); +#70260 = DIRECTION('',(1.,0.E+000,0.E+000)); +#70261 = PCURVE('',#43077,#70262); +#70262 = DEFINITIONAL_REPRESENTATION('',(#70263),#70266); +#70263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70264,#70265),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#67872 = CARTESIAN_POINT('',(4.712388980385,6.65)); -#67873 = CARTESIAN_POINT('',(4.712388980385,7.074264068712)); -#67874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67875 = PCURVE('',#40861,#67876); -#67876 = DEFINITIONAL_REPRESENTATION('',(#67877),#67881); -#67877 = LINE('',#67878,#67879); -#67878 = CARTESIAN_POINT('',(0.E+000,6.65)); -#67879 = VECTOR('',#67880,1.); -#67880 = DIRECTION('',(0.E+000,1.)); -#67881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67882 = ORIENTED_EDGE('',*,*,#40657,.T.); -#67883 = ADVANCED_FACE('',(#67884),#55085,.F.); -#67884 = FACE_BOUND('',#67885,.F.); -#67885 = EDGE_LOOP('',(#67886,#67887,#67907,#67908)); -#67886 = ORIENTED_EDGE('',*,*,#55071,.T.); -#67887 = ORIENTED_EDGE('',*,*,#67888,.T.); -#67888 = EDGE_CURVE('',#55012,#67300,#67889,.T.); -#67889 = SURFACE_CURVE('',#67890,(#67894,#67901),.PCURVE_S1.); -#67890 = LINE('',#67891,#67892); -#67891 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); -#67892 = VECTOR('',#67893,1.); -#67893 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67894 = PCURVE('',#55085,#67895); -#67895 = DEFINITIONAL_REPRESENTATION('',(#67896),#67900); -#67896 = LINE('',#67897,#67898); -#67897 = CARTESIAN_POINT('',(0.52,0.425735931288)); -#67898 = VECTOR('',#67899,1.); -#67899 = DIRECTION('',(0.E+000,1.)); -#67900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67901 = PCURVE('',#55037,#67902); -#67902 = DEFINITIONAL_REPRESENTATION('',(#67903),#67906); -#67903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67904,#67905),.UNSPECIFIED., +#70264 = CARTESIAN_POINT('',(4.712388980385,6.65)); +#70265 = CARTESIAN_POINT('',(4.712388980385,7.074264068712)); +#70266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70267 = PCURVE('',#43253,#70268); +#70268 = DEFINITIONAL_REPRESENTATION('',(#70269),#70273); +#70269 = LINE('',#70270,#70271); +#70270 = CARTESIAN_POINT('',(0.E+000,6.65)); +#70271 = VECTOR('',#70272,1.); +#70272 = DIRECTION('',(0.E+000,1.)); +#70273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70274 = ORIENTED_EDGE('',*,*,#43049,.T.); +#70275 = ADVANCED_FACE('',(#70276),#57477,.F.); +#70276 = FACE_BOUND('',#70277,.F.); +#70277 = EDGE_LOOP('',(#70278,#70279,#70299,#70300)); +#70278 = ORIENTED_EDGE('',*,*,#57463,.T.); +#70279 = ORIENTED_EDGE('',*,*,#70280,.T.); +#70280 = EDGE_CURVE('',#57404,#69692,#70281,.T.); +#70281 = SURFACE_CURVE('',#70282,(#70286,#70293),.PCURVE_S1.); +#70282 = LINE('',#70283,#70284); +#70283 = CARTESIAN_POINT('',(-3.324264068712,-0.725,-1.68)); +#70284 = VECTOR('',#70285,1.); +#70285 = DIRECTION('',(1.,0.E+000,0.E+000)); +#70286 = PCURVE('',#57477,#70287); +#70287 = DEFINITIONAL_REPRESENTATION('',(#70288),#70292); +#70288 = LINE('',#70289,#70290); +#70289 = CARTESIAN_POINT('',(0.52,0.425735931288)); +#70290 = VECTOR('',#70291,1.); +#70291 = DIRECTION('',(0.E+000,1.)); +#70292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70293 = PCURVE('',#57429,#70294); +#70294 = DEFINITIONAL_REPRESENTATION('',(#70295),#70298); +#70295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70296,#70297),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#67904 = CARTESIAN_POINT('',(1.570796326795,0.425735931288)); -#67905 = CARTESIAN_POINT('',(1.570796326795,0.85)); -#67906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67907 = ORIENTED_EDGE('',*,*,#67299,.F.); -#67908 = ORIENTED_EDGE('',*,*,#67783,.F.); -#67909 = ADVANCED_FACE('',(#67910),#40861,.F.); -#67910 = FACE_BOUND('',#67911,.F.); -#67911 = EDGE_LOOP('',(#67912,#67935,#67936,#67937)); -#67912 = ORIENTED_EDGE('',*,*,#67913,.F.); -#67913 = EDGE_CURVE('',#67809,#67914,#67916,.T.); -#67914 = VERTEX_POINT('',#67915); -#67915 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.68)); -#67916 = SURFACE_CURVE('',#67917,(#67921,#67928),.PCURVE_S1.); -#67917 = LINE('',#67918,#67919); -#67918 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); -#67919 = VECTOR('',#67920,1.); -#67920 = DIRECTION('',(0.E+000,0.E+000,1.)); -#67921 = PCURVE('',#40861,#67922); -#67922 = DEFINITIONAL_REPRESENTATION('',(#67923),#67927); -#67923 = LINE('',#67924,#67925); -#67924 = CARTESIAN_POINT('',(0.E+000,7.074264068712)); -#67925 = VECTOR('',#67926,1.); -#67926 = DIRECTION('',(1.,0.E+000)); -#67927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67928 = PCURVE('',#53481,#67929); -#67929 = DEFINITIONAL_REPRESENTATION('',(#67930),#67934); -#67930 = LINE('',#67931,#67932); -#67931 = CARTESIAN_POINT('',(0.479289321882,0.15)); -#67932 = VECTOR('',#67933,1.); -#67933 = DIRECTION('',(0.E+000,1.)); -#67934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#70296 = CARTESIAN_POINT('',(1.570796326795,0.425735931288)); +#70297 = CARTESIAN_POINT('',(1.570796326795,0.85)); +#70298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70299 = ORIENTED_EDGE('',*,*,#69691,.F.); +#70300 = ORIENTED_EDGE('',*,*,#70175,.F.); +#70301 = ADVANCED_FACE('',(#70302),#43253,.F.); +#70302 = FACE_BOUND('',#70303,.F.); +#70303 = EDGE_LOOP('',(#70304,#70327,#70328,#70329)); +#70304 = ORIENTED_EDGE('',*,*,#70305,.F.); +#70305 = EDGE_CURVE('',#70201,#70306,#70308,.T.); +#70306 = VERTEX_POINT('',#70307); +#70307 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.68)); +#70308 = SURFACE_CURVE('',#70309,(#70313,#70320),.PCURVE_S1.); +#70309 = LINE('',#70310,#70311); +#70310 = CARTESIAN_POINT('',(3.324264068712,-0.725,-2.2)); +#70311 = VECTOR('',#70312,1.); +#70312 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70313 = PCURVE('',#43253,#70314); +#70314 = DEFINITIONAL_REPRESENTATION('',(#70315),#70319); +#70315 = LINE('',#70316,#70317); +#70316 = CARTESIAN_POINT('',(0.E+000,7.074264068712)); +#70317 = VECTOR('',#70318,1.); +#70318 = DIRECTION('',(1.,0.E+000)); +#70319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70320 = PCURVE('',#55873,#70321); +#70321 = DEFINITIONAL_REPRESENTATION('',(#70322),#70326); +#70322 = LINE('',#70323,#70324); +#70323 = CARTESIAN_POINT('',(0.479289321882,0.15)); +#70324 = VECTOR('',#70325,1.); +#70325 = DIRECTION('',(0.E+000,1.)); +#70326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70327 = ORIENTED_EDGE('',*,*,#70255,.F.); +#70328 = ORIENTED_EDGE('',*,*,#43239,.T.); +#70329 = ORIENTED_EDGE('',*,*,#70330,.T.); +#70330 = EDGE_CURVE('',#43184,#70306,#70331,.T.); +#70331 = SURFACE_CURVE('',#70332,(#70336,#70343),.PCURVE_S1.); +#70332 = LINE('',#70333,#70334); +#70333 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); +#70334 = VECTOR('',#70335,1.); +#70335 = DIRECTION('',(1.,0.E+000,0.E+000)); +#70336 = PCURVE('',#43253,#70337); +#70337 = DEFINITIONAL_REPRESENTATION('',(#70338),#70342); +#70338 = LINE('',#70339,#70340); +#70339 = CARTESIAN_POINT('',(0.52,6.65)); +#70340 = VECTOR('',#70341,1.); +#70341 = DIRECTION('',(0.E+000,1.)); +#70342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#67935 = ORIENTED_EDGE('',*,*,#67863,.F.); -#67936 = ORIENTED_EDGE('',*,*,#40847,.T.); -#67937 = ORIENTED_EDGE('',*,*,#67938,.T.); -#67938 = EDGE_CURVE('',#40792,#67914,#67939,.T.); -#67939 = SURFACE_CURVE('',#67940,(#67944,#67951),.PCURVE_S1.); -#67940 = LINE('',#67941,#67942); -#67941 = CARTESIAN_POINT('',(2.9,-0.725,-1.68)); -#67942 = VECTOR('',#67943,1.); -#67943 = DIRECTION('',(1.,0.E+000,0.E+000)); -#67944 = PCURVE('',#40861,#67945); -#67945 = DEFINITIONAL_REPRESENTATION('',(#67946),#67950); -#67946 = LINE('',#67947,#67948); -#67947 = CARTESIAN_POINT('',(0.52,6.65)); -#67948 = VECTOR('',#67949,1.); -#67949 = DIRECTION('',(0.E+000,1.)); -#67950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67951 = PCURVE('',#40813,#67952); -#67952 = DEFINITIONAL_REPRESENTATION('',(#67953),#67956); -#67953 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#67954,#67955),.UNSPECIFIED., +#70343 = PCURVE('',#43205,#70344); +#70344 = DEFINITIONAL_REPRESENTATION('',(#70345),#70348); +#70345 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70346,#70347),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.424264068712),.PIECEWISE_BEZIER_KNOTS.); -#67954 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#67955 = CARTESIAN_POINT('',(1.570796326795,7.074264068712)); -#67956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#67957 = ADVANCED_FACE('',(#67958),#55037,.F.); -#67958 = FACE_BOUND('',#67959,.F.); -#67959 = EDGE_LOOP('',(#67960,#67961,#67962,#67963,#67964)); -#67960 = ORIENTED_EDGE('',*,*,#55011,.T.); -#67961 = ORIENTED_EDGE('',*,*,#59619,.T.); -#67962 = ORIENTED_EDGE('',*,*,#67148,.T.); -#67963 = ORIENTED_EDGE('',*,*,#67322,.F.); -#67964 = ORIENTED_EDGE('',*,*,#67888,.F.); -#67965 = ADVANCED_FACE('',(#67966),#40813,.F.); -#67966 = FACE_BOUND('',#67967,.F.); -#67967 = EDGE_LOOP('',(#67968,#68021,#68022,#68023,#68024)); -#67968 = ORIENTED_EDGE('',*,*,#67969,.F.); -#67969 = EDGE_CURVE('',#67914,#59690,#67970,.T.); -#67970 = SURFACE_CURVE('',#67971,(#67980,#68009),.PCURVE_S1.); -#67971 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67972,#67973,#67974,#67975, - #67976,#67977,#67978,#67979),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#70346 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#70347 = CARTESIAN_POINT('',(1.570796326795,7.074264068712)); +#70348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70349 = ADVANCED_FACE('',(#70350),#57429,.F.); +#70350 = FACE_BOUND('',#70351,.F.); +#70351 = EDGE_LOOP('',(#70352,#70353,#70354,#70355,#70356)); +#70352 = ORIENTED_EDGE('',*,*,#57403,.T.); +#70353 = ORIENTED_EDGE('',*,*,#62011,.T.); +#70354 = ORIENTED_EDGE('',*,*,#69540,.T.); +#70355 = ORIENTED_EDGE('',*,*,#69714,.F.); +#70356 = ORIENTED_EDGE('',*,*,#70280,.F.); +#70357 = ADVANCED_FACE('',(#70358),#43205,.F.); +#70358 = FACE_BOUND('',#70359,.F.); +#70359 = EDGE_LOOP('',(#70360,#70413,#70414,#70415,#70416)); +#70360 = ORIENTED_EDGE('',*,*,#70361,.F.); +#70361 = EDGE_CURVE('',#70306,#62082,#70362,.T.); +#70362 = SURFACE_CURVE('',#70363,(#70372,#70401),.PCURVE_S1.); +#70363 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70364,#70365,#70366,#70367, + #70368,#70369,#70370,#70371),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#67972 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.68)); -#67973 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.664911165235)); -#67974 = CARTESIAN_POINT('',(3.32020029292,-0.729063775792, +#70364 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.68)); +#70365 = CARTESIAN_POINT('',(3.324264068712,-0.725,-1.664911165235)); +#70366 = CARTESIAN_POINT('',(3.32020029292,-0.729063775792, -1.640480542545)); -#67975 = CARTESIAN_POINT('',(3.30490661372,-0.744357454992, +#70367 = CARTESIAN_POINT('',(3.30490661372,-0.744357454992, -1.601753732029)); -#67976 = CARTESIAN_POINT('',(3.276607962456,-0.772656106256, +#70368 = CARTESIAN_POINT('',(3.276607962456,-0.772656106256, -1.566329894619)); -#67977 = CARTESIAN_POINT('',(3.232341391081,-0.816922677631, +#70369 = CARTESIAN_POINT('',(3.232341391081,-0.816922677631, -1.538399271628)); -#67978 = CARTESIAN_POINT('',(3.195602903477,-0.853661165235,-1.53)); -#67979 = CARTESIAN_POINT('',(3.174264068712,-0.875,-1.53)); -#67980 = PCURVE('',#40813,#67981); -#67981 = DEFINITIONAL_REPRESENTATION('',(#67982),#68008); -#67982 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#67983,#67984,#67985,#67986, - #67987,#67988,#67989,#67990,#67991,#67992,#67993,#67994,#67995, - #67996,#67997,#67998,#67999,#68000,#68001,#68002,#68003,#68004, - #68005,#68006,#68007),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#70370 = CARTESIAN_POINT('',(3.195602903477,-0.853661165235,-1.53)); +#70371 = CARTESIAN_POINT('',(3.174264068712,-0.875,-1.53)); +#70372 = PCURVE('',#43205,#70373); +#70373 = DEFINITIONAL_REPRESENTATION('',(#70374),#70400); +#70374 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70375,#70376,#70377,#70378, + #70379,#70380,#70381,#70382,#70383,#70384,#70385,#70386,#70387, + #70388,#70389,#70390,#70391,#70392,#70393,#70394,#70395,#70396, + #70397,#70398,#70399),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -83837,408 +86826,408 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#67983 = CARTESIAN_POINT('',(1.570796326795,7.074264068712)); -#67984 = CARTESIAN_POINT('',(1.607340907387,7.074263997549)); -#67985 = CARTESIAN_POINT('',(1.67548609328,7.073727236588)); -#67986 = CARTESIAN_POINT('',(1.766399617303,7.071634635577)); -#67987 = CARTESIAN_POINT('',(1.849908589019,7.068595931044)); -#67988 = CARTESIAN_POINT('',(1.928610600842,7.06488612004)); -#67989 = CARTESIAN_POINT('',(2.003313789848,7.060561697999)); -#67990 = CARTESIAN_POINT('',(2.075011292299,7.05571646958)); -#67991 = CARTESIAN_POINT('',(2.144321194645,7.050402811488)); -#67992 = CARTESIAN_POINT('',(2.211681963786,7.044641945837)); -#67993 = CARTESIAN_POINT('',(2.277543447832,7.038461583876)); -#67994 = CARTESIAN_POINT('',(2.342306789727,7.031887697641)); -#67995 = CARTESIAN_POINT('',(2.406328045055,7.024946726883)); -#67996 = CARTESIAN_POINT('',(2.469899044277,7.017664979704)); -#67997 = CARTESIAN_POINT('',(2.533249045713,7.010039279806)); -#67998 = CARTESIAN_POINT('',(2.596628177608,7.002066347004)); -#67999 = CARTESIAN_POINT('',(2.660292654851,6.993743257772)); -#68000 = CARTESIAN_POINT('',(2.724505539445,6.985065765835)); -#68001 = CARTESIAN_POINT('',(2.789510823181,6.976034559255)); -#68002 = CARTESIAN_POINT('',(2.855610671013,6.966627070468)); -#68003 = CARTESIAN_POINT('',(2.923252891374,6.956797476301)); -#68004 = CARTESIAN_POINT('',(2.99295587445,6.946504887873)); -#68005 = CARTESIAN_POINT('',(3.065305466931,6.935707093711)); -#68006 = CARTESIAN_POINT('',(3.115729149685,6.928143856851)); -#68007 = CARTESIAN_POINT('',(3.14159265359,6.924264068712)); -#68008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68009 = PCURVE('',#53481,#68010); -#68010 = DEFINITIONAL_REPRESENTATION('',(#68011),#68020); -#68011 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68012,#68013,#68014,#68015, - #68016,#68017,#68018,#68019),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( +#70375 = CARTESIAN_POINT('',(1.570796326795,7.074264068712)); +#70376 = CARTESIAN_POINT('',(1.607340907387,7.074263997549)); +#70377 = CARTESIAN_POINT('',(1.67548609328,7.073727236588)); +#70378 = CARTESIAN_POINT('',(1.766399617303,7.071634635577)); +#70379 = CARTESIAN_POINT('',(1.849908589019,7.068595931044)); +#70380 = CARTESIAN_POINT('',(1.928610600842,7.06488612004)); +#70381 = CARTESIAN_POINT('',(2.003313789848,7.060561697999)); +#70382 = CARTESIAN_POINT('',(2.075011292299,7.05571646958)); +#70383 = CARTESIAN_POINT('',(2.144321194645,7.050402811488)); +#70384 = CARTESIAN_POINT('',(2.211681963786,7.044641945837)); +#70385 = CARTESIAN_POINT('',(2.277543447832,7.038461583876)); +#70386 = CARTESIAN_POINT('',(2.342306789727,7.031887697641)); +#70387 = CARTESIAN_POINT('',(2.406328045055,7.024946726883)); +#70388 = CARTESIAN_POINT('',(2.469899044277,7.017664979704)); +#70389 = CARTESIAN_POINT('',(2.533249045713,7.010039279806)); +#70390 = CARTESIAN_POINT('',(2.596628177608,7.002066347004)); +#70391 = CARTESIAN_POINT('',(2.660292654851,6.993743257772)); +#70392 = CARTESIAN_POINT('',(2.724505539445,6.985065765835)); +#70393 = CARTESIAN_POINT('',(2.789510823181,6.976034559255)); +#70394 = CARTESIAN_POINT('',(2.855610671013,6.966627070468)); +#70395 = CARTESIAN_POINT('',(2.923252891374,6.956797476301)); +#70396 = CARTESIAN_POINT('',(2.99295587445,6.946504887873)); +#70397 = CARTESIAN_POINT('',(3.065305466931,6.935707093711)); +#70398 = CARTESIAN_POINT('',(3.115729149685,6.928143856851)); +#70399 = CARTESIAN_POINT('',(3.14159265359,6.924264068712)); +#70400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70401 = PCURVE('',#55873,#70402); +#70402 = DEFINITIONAL_REPRESENTATION('',(#70403),#70412); +#70403 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70404,#70405,#70406,#70407, + #70408,#70409,#70410,#70411),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,4),( 0.E+000,0.125,0.25,0.5,0.75,1.),.UNSPECIFIED.); -#68012 = CARTESIAN_POINT('',(0.479289321882,0.67)); -#68013 = CARTESIAN_POINT('',(0.479289321882,0.685088834765)); -#68014 = CARTESIAN_POINT('',(0.473542275042,0.709519457455)); -#68015 = CARTESIAN_POINT('',(0.451913746499,0.748246267971)); -#68016 = CARTESIAN_POINT('',(0.411893410085,0.783670105381)); -#68017 = CARTESIAN_POINT('',(0.349291024487,0.811600728372)); -#68018 = CARTESIAN_POINT('',(0.297334957056,0.82)); -#68019 = CARTESIAN_POINT('',(0.267157287526,0.82)); -#68020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68021 = ORIENTED_EDGE('',*,*,#67938,.F.); -#68022 = ORIENTED_EDGE('',*,*,#40791,.T.); -#68023 = ORIENTED_EDGE('',*,*,#40932,.T.); -#68024 = ORIENTED_EDGE('',*,*,#59712,.T.); -#68025 = ADVANCED_FACE('',(#68026),#38091,.T.); -#68026 = FACE_BOUND('',#68027,.F.); -#68027 = EDGE_LOOP('',(#68028,#68029,#68049,#68050)); -#68028 = ORIENTED_EDGE('',*,*,#40584,.F.); -#68029 = ORIENTED_EDGE('',*,*,#68030,.T.); -#68030 = EDGE_CURVE('',#40562,#38076,#68031,.T.); -#68031 = SURFACE_CURVE('',#68032,(#68036,#68043),.PCURVE_S1.); -#68032 = LINE('',#68033,#68034); -#68033 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); -#68034 = VECTOR('',#68035,1.); -#68035 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68036 = PCURVE('',#38091,#68037); -#68037 = DEFINITIONAL_REPRESENTATION('',(#68038),#68042); -#68038 = LINE('',#68039,#68040); -#68039 = CARTESIAN_POINT('',(0.E+000,3.31)); -#68040 = VECTOR('',#68041,1.); -#68041 = DIRECTION('',(0.E+000,1.)); -#68042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68043 = PCURVE('',#38120,#68044); -#68044 = DEFINITIONAL_REPRESENTATION('',(#68045),#68048); -#68045 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68046,#68047),.UNSPECIFIED., +#70404 = CARTESIAN_POINT('',(0.479289321882,0.67)); +#70405 = CARTESIAN_POINT('',(0.479289321882,0.685088834765)); +#70406 = CARTESIAN_POINT('',(0.473542275042,0.709519457455)); +#70407 = CARTESIAN_POINT('',(0.451913746499,0.748246267971)); +#70408 = CARTESIAN_POINT('',(0.411893410085,0.783670105381)); +#70409 = CARTESIAN_POINT('',(0.349291024487,0.811600728372)); +#70410 = CARTESIAN_POINT('',(0.297334957056,0.82)); +#70411 = CARTESIAN_POINT('',(0.267157287526,0.82)); +#70412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70413 = ORIENTED_EDGE('',*,*,#70330,.F.); +#70414 = ORIENTED_EDGE('',*,*,#43183,.T.); +#70415 = ORIENTED_EDGE('',*,*,#43324,.T.); +#70416 = ORIENTED_EDGE('',*,*,#62104,.T.); +#70417 = ADVANCED_FACE('',(#70418),#40483,.T.); +#70418 = FACE_BOUND('',#70419,.F.); +#70419 = EDGE_LOOP('',(#70420,#70421,#70441,#70442)); +#70420 = ORIENTED_EDGE('',*,*,#42976,.F.); +#70421 = ORIENTED_EDGE('',*,*,#70422,.T.); +#70422 = EDGE_CURVE('',#42954,#40468,#70423,.T.); +#70423 = SURFACE_CURVE('',#70424,(#70428,#70435),.PCURVE_S1.); +#70424 = LINE('',#70425,#70426); +#70425 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,0.96)); +#70426 = VECTOR('',#70427,1.); +#70427 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70428 = PCURVE('',#40483,#70429); +#70429 = DEFINITIONAL_REPRESENTATION('',(#70430),#70434); +#70430 = LINE('',#70431,#70432); +#70431 = CARTESIAN_POINT('',(0.E+000,3.31)); +#70432 = VECTOR('',#70433,1.); +#70433 = DIRECTION('',(0.E+000,1.)); +#70434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70435 = PCURVE('',#40512,#70436); +#70436 = DEFINITIONAL_REPRESENTATION('',(#70437),#70440); +#70437 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70438,#70439),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#68046 = CARTESIAN_POINT('',(5.497787143781,3.31)); -#68047 = CARTESIAN_POINT('',(5.497787143781,4.7)); -#68048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68049 = ORIENTED_EDGE('',*,*,#38075,.T.); -#68050 = ORIENTED_EDGE('',*,*,#68051,.F.); -#68051 = EDGE_CURVE('',#40585,#38048,#68052,.T.); -#68052 = SURFACE_CURVE('',#68053,(#68057,#68064),.PCURVE_S1.); -#68053 = LINE('',#68054,#68055); -#68054 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,0.96)); -#68055 = VECTOR('',#68056,1.); -#68056 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68057 = PCURVE('',#38091,#68058); -#68058 = DEFINITIONAL_REPRESENTATION('',(#68059),#68063); -#68059 = LINE('',#68060,#68061); -#68060 = CARTESIAN_POINT('',(0.853553390594,3.31)); -#68061 = VECTOR('',#68062,1.); -#68062 = DIRECTION('',(0.E+000,1.)); -#68063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68064 = PCURVE('',#38064,#68065); -#68065 = DEFINITIONAL_REPRESENTATION('',(#68066),#68069); -#68066 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68067,#68068),.UNSPECIFIED., +#70438 = CARTESIAN_POINT('',(5.497787143781,3.31)); +#70439 = CARTESIAN_POINT('',(5.497787143781,4.7)); +#70440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70441 = ORIENTED_EDGE('',*,*,#40467,.T.); +#70442 = ORIENTED_EDGE('',*,*,#70443,.F.); +#70443 = EDGE_CURVE('',#42977,#40440,#70444,.T.); +#70444 = SURFACE_CURVE('',#70445,(#70449,#70456),.PCURVE_S1.); +#70445 = LINE('',#70446,#70447); +#70446 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,0.96)); +#70447 = VECTOR('',#70448,1.); +#70448 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70449 = PCURVE('',#40483,#70450); +#70450 = DEFINITIONAL_REPRESENTATION('',(#70451),#70455); +#70451 = LINE('',#70452,#70453); +#70452 = CARTESIAN_POINT('',(0.853553390594,3.31)); +#70453 = VECTOR('',#70454,1.); +#70454 = DIRECTION('',(0.E+000,1.)); +#70455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70456 = PCURVE('',#40456,#70457); +#70457 = DEFINITIONAL_REPRESENTATION('',(#70458),#70461); +#70458 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70459,#70460),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.39),.PIECEWISE_BEZIER_KNOTS.); -#68067 = CARTESIAN_POINT('',(5.497787143783,3.31)); -#68068 = CARTESIAN_POINT('',(5.497787143783,4.7)); -#68069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68070 = ADVANCED_FACE('',(#68071),#53481,.T.); -#68071 = FACE_BOUND('',#68072,.F.); -#68072 = EDGE_LOOP('',(#68073,#68074,#68075,#68076,#68077,#68099,#68122, - #68142)); -#68073 = ORIENTED_EDGE('',*,*,#67808,.F.); -#68074 = ORIENTED_EDGE('',*,*,#67913,.T.); -#68075 = ORIENTED_EDGE('',*,*,#67969,.T.); -#68076 = ORIENTED_EDGE('',*,*,#59689,.F.); -#68077 = ORIENTED_EDGE('',*,*,#68078,.T.); -#68078 = EDGE_CURVE('',#59667,#68079,#68081,.T.); -#68079 = VERTEX_POINT('',#68080); -#68080 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-0.56)); -#68081 = SURFACE_CURVE('',#68082,(#68086,#68093),.PCURVE_S1.); -#68082 = LINE('',#68083,#68084); -#68083 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); -#68084 = VECTOR('',#68085,1.); -#68085 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68086 = PCURVE('',#53481,#68087); -#68087 = DEFINITIONAL_REPRESENTATION('',(#68088),#68092); -#68088 = LINE('',#68089,#68090); -#68089 = CARTESIAN_POINT('',(0.E+000,0.82)); -#68090 = VECTOR('',#68091,1.); -#68091 = DIRECTION('',(0.E+000,1.)); -#68092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68093 = PCURVE('',#56306,#68094); -#68094 = DEFINITIONAL_REPRESENTATION('',(#68095),#68098); -#68095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68096,#68097),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); -#68096 = CARTESIAN_POINT('',(5.497787143781,0.82)); -#68097 = CARTESIAN_POINT('',(5.497787143781,1.79)); -#68098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68099 = ORIENTED_EDGE('',*,*,#68100,.T.); -#68100 = EDGE_CURVE('',#68079,#68101,#68103,.T.); -#68101 = VERTEX_POINT('',#68102); -#68102 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-0.56)); -#68103 = SURFACE_CURVE('',#68104,(#68108,#68115),.PCURVE_S1.); -#68104 = LINE('',#68105,#68106); -#68105 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-0.56)); -#68106 = VECTOR('',#68107,1.); -#68107 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#68108 = PCURVE('',#53481,#68109); -#68109 = DEFINITIONAL_REPRESENTATION('',(#68110),#68114); -#68110 = LINE('',#68111,#68112); -#68111 = CARTESIAN_POINT('',(0.E+000,1.79)); -#68112 = VECTOR('',#68113,1.); -#68113 = DIRECTION('',(1.,0.E+000)); -#68114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68115 = PCURVE('',#40346,#68116); -#68116 = DEFINITIONAL_REPRESENTATION('',(#68117),#68121); -#68117 = LINE('',#68118,#68119); -#68118 = CARTESIAN_POINT('',(0.585355339059,-0.161091270347)); -#68119 = VECTOR('',#68120,1.); -#68120 = DIRECTION('',(0.707106781187,-0.707106781187)); -#68121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68122 = ORIENTED_EDGE('',*,*,#68123,.F.); -#68123 = EDGE_CURVE('',#53466,#68101,#68124,.T.); -#68124 = SURFACE_CURVE('',#68125,(#68129,#68136),.PCURVE_S1.); -#68125 = LINE('',#68126,#68127); -#68126 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-2.35)); -#68127 = VECTOR('',#68128,1.); -#68128 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68129 = PCURVE('',#53481,#68130); -#68130 = DEFINITIONAL_REPRESENTATION('',(#68131),#68135); -#68131 = LINE('',#68132,#68133); -#68132 = CARTESIAN_POINT('',(0.853553390594,0.E+000)); -#68133 = VECTOR('',#68134,1.); -#68134 = DIRECTION('',(0.E+000,1.)); -#68135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68136 = PCURVE('',#53510,#68137); -#68137 = DEFINITIONAL_REPRESENTATION('',(#68138),#68141); -#68138 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68139,#68140),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.79),.PIECEWISE_BEZIER_KNOTS.); -#68139 = CARTESIAN_POINT('',(5.497787143783,0.E+000)); -#68140 = CARTESIAN_POINT('',(5.497787143783,1.79)); -#68141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#70459 = CARTESIAN_POINT('',(5.497787143783,3.31)); +#70460 = CARTESIAN_POINT('',(5.497787143783,4.7)); +#70461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68142 = ORIENTED_EDGE('',*,*,#53465,.F.); -#68143 = ADVANCED_FACE('',(#68144),#38120,.T.); -#68144 = FACE_BOUND('',#68145,.T.); -#68145 = EDGE_LOOP('',(#68146,#68147,#68148,#68149)); -#68146 = ORIENTED_EDGE('',*,*,#40561,.T.); -#68147 = ORIENTED_EDGE('',*,*,#68030,.T.); -#68148 = ORIENTED_EDGE('',*,*,#38103,.F.); -#68149 = ORIENTED_EDGE('',*,*,#55985,.F.); -#68150 = ADVANCED_FACE('',(#68151),#56306,.T.); -#68151 = FACE_BOUND('',#68152,.T.); -#68152 = EDGE_LOOP('',(#68153,#68154,#68155,#68180)); -#68153 = ORIENTED_EDGE('',*,*,#59666,.T.); -#68154 = ORIENTED_EDGE('',*,*,#68078,.T.); -#68155 = ORIENTED_EDGE('',*,*,#68156,.F.); -#68156 = EDGE_CURVE('',#56268,#68079,#68157,.T.); -#68157 = SURFACE_CURVE('',#68158,(#68163,#68169),.PCURVE_S1.); -#68158 = CIRCLE('',#68159,0.55); -#68159 = AXIS2_PLACEMENT_3D('',#68160,#68161,#68162); -#68160 = CARTESIAN_POINT('',(2.596446609407,-0.675,-0.56)); -#68161 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68162 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#68163 = PCURVE('',#56306,#68164); -#68164 = DEFINITIONAL_REPRESENTATION('',(#68165),#68168); -#68165 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68166,#68167),.UNSPECIFIED., +#70462 = ADVANCED_FACE('',(#70463),#55873,.T.); +#70463 = FACE_BOUND('',#70464,.F.); +#70464 = EDGE_LOOP('',(#70465,#70466,#70467,#70468,#70469,#70491,#70514, + #70534)); +#70465 = ORIENTED_EDGE('',*,*,#70200,.F.); +#70466 = ORIENTED_EDGE('',*,*,#70305,.T.); +#70467 = ORIENTED_EDGE('',*,*,#70361,.T.); +#70468 = ORIENTED_EDGE('',*,*,#62081,.F.); +#70469 = ORIENTED_EDGE('',*,*,#70470,.T.); +#70470 = EDGE_CURVE('',#62059,#70471,#70473,.T.); +#70471 = VERTEX_POINT('',#70472); +#70472 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-0.56)); +#70473 = SURFACE_CURVE('',#70474,(#70478,#70485),.PCURVE_S1.); +#70474 = LINE('',#70475,#70476); +#70475 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-1.53)); +#70476 = VECTOR('',#70477,1.); +#70477 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70478 = PCURVE('',#55873,#70479); +#70479 = DEFINITIONAL_REPRESENTATION('',(#70480),#70484); +#70480 = LINE('',#70481,#70482); +#70481 = CARTESIAN_POINT('',(0.E+000,0.82)); +#70482 = VECTOR('',#70483,1.); +#70483 = DIRECTION('',(0.E+000,1.)); +#70484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70485 = PCURVE('',#58698,#70486); +#70486 = DEFINITIONAL_REPRESENTATION('',(#70487),#70490); +#70487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70488,#70489),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.97),.PIECEWISE_BEZIER_KNOTS.); +#70488 = CARTESIAN_POINT('',(5.497787143781,0.82)); +#70489 = CARTESIAN_POINT('',(5.497787143781,1.79)); +#70490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70491 = ORIENTED_EDGE('',*,*,#70492,.T.); +#70492 = EDGE_CURVE('',#70471,#70493,#70495,.T.); +#70493 = VERTEX_POINT('',#70494); +#70494 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-0.56)); +#70495 = SURFACE_CURVE('',#70496,(#70500,#70507),.PCURVE_S1.); +#70496 = LINE('',#70497,#70498); +#70497 = CARTESIAN_POINT('',(2.985355339059,-1.063908729653,-0.56)); +#70498 = VECTOR('',#70499,1.); +#70499 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#70500 = PCURVE('',#55873,#70501); +#70501 = DEFINITIONAL_REPRESENTATION('',(#70502),#70506); +#70502 = LINE('',#70503,#70504); +#70503 = CARTESIAN_POINT('',(0.E+000,1.79)); +#70504 = VECTOR('',#70505,1.); +#70505 = DIRECTION('',(1.,0.E+000)); +#70506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70507 = PCURVE('',#42738,#70508); +#70508 = DEFINITIONAL_REPRESENTATION('',(#70509),#70513); +#70509 = LINE('',#70510,#70511); +#70510 = CARTESIAN_POINT('',(0.585355339059,-0.161091270347)); +#70511 = VECTOR('',#70512,1.); +#70512 = DIRECTION('',(0.707106781187,-0.707106781187)); +#70513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70514 = ORIENTED_EDGE('',*,*,#70515,.F.); +#70515 = EDGE_CURVE('',#55858,#70493,#70516,.T.); +#70516 = SURFACE_CURVE('',#70517,(#70521,#70528),.PCURVE_S1.); +#70517 = LINE('',#70518,#70519); +#70518 = CARTESIAN_POINT('',(3.588908729653,-0.460355339059,-2.35)); +#70519 = VECTOR('',#70520,1.); +#70520 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70521 = PCURVE('',#55873,#70522); +#70522 = DEFINITIONAL_REPRESENTATION('',(#70523),#70527); +#70523 = LINE('',#70524,#70525); +#70524 = CARTESIAN_POINT('',(0.853553390594,0.E+000)); +#70525 = VECTOR('',#70526,1.); +#70526 = DIRECTION('',(0.E+000,1.)); +#70527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70528 = PCURVE('',#55902,#70529); +#70529 = DEFINITIONAL_REPRESENTATION('',(#70530),#70533); +#70530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70531,#70532),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.79),.PIECEWISE_BEZIER_KNOTS.); +#70531 = CARTESIAN_POINT('',(5.497787143783,0.E+000)); +#70532 = CARTESIAN_POINT('',(5.497787143783,1.79)); +#70533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70534 = ORIENTED_EDGE('',*,*,#55857,.F.); +#70535 = ADVANCED_FACE('',(#70536),#40512,.T.); +#70536 = FACE_BOUND('',#70537,.T.); +#70537 = EDGE_LOOP('',(#70538,#70539,#70540,#70541)); +#70538 = ORIENTED_EDGE('',*,*,#42953,.T.); +#70539 = ORIENTED_EDGE('',*,*,#70422,.T.); +#70540 = ORIENTED_EDGE('',*,*,#40495,.F.); +#70541 = ORIENTED_EDGE('',*,*,#58377,.F.); +#70542 = ADVANCED_FACE('',(#70543),#58698,.T.); +#70543 = FACE_BOUND('',#70544,.T.); +#70544 = EDGE_LOOP('',(#70545,#70546,#70547,#70572)); +#70545 = ORIENTED_EDGE('',*,*,#62058,.T.); +#70546 = ORIENTED_EDGE('',*,*,#70470,.T.); +#70547 = ORIENTED_EDGE('',*,*,#70548,.F.); +#70548 = EDGE_CURVE('',#58660,#70471,#70549,.T.); +#70549 = SURFACE_CURVE('',#70550,(#70555,#70561),.PCURVE_S1.); +#70550 = CIRCLE('',#70551,0.55); +#70551 = AXIS2_PLACEMENT_3D('',#70552,#70553,#70554); +#70552 = CARTESIAN_POINT('',(2.596446609407,-0.675,-0.56)); +#70553 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70554 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#70555 = PCURVE('',#58698,#70556); +#70556 = DEFINITIONAL_REPRESENTATION('',(#70557),#70560); +#70557 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70558,#70559),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.785398163396),.PIECEWISE_BEZIER_KNOTS.); -#68166 = CARTESIAN_POINT('',(4.712388980385,1.79)); -#68167 = CARTESIAN_POINT('',(5.497787143781,1.79)); -#68168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#70558 = CARTESIAN_POINT('',(4.712388980385,1.79)); +#70559 = CARTESIAN_POINT('',(5.497787143781,1.79)); +#70560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68169 = PCURVE('',#40346,#68170); -#68170 = DEFINITIONAL_REPRESENTATION('',(#68171),#68179); -#68171 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#68172,#68173,#68174,#68175 - ,#68176,#68177,#68178),.UNSPECIFIED.,.F.,.F.) +#70561 = PCURVE('',#42738,#70562); +#70562 = DEFINITIONAL_REPRESENTATION('',(#70563),#70571); +#70563 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#70564,#70565,#70566,#70567 + ,#70568,#70569,#70570),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#68172 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); -#68173 = CARTESIAN_POINT('',(1.14907455357,0.E+000)); -#68174 = CARTESIAN_POINT('',(0.672760581488,-0.825)); -#68175 = CARTESIAN_POINT('',(0.196446609407,-1.65)); -#68176 = CARTESIAN_POINT('',(-0.279867362674,-0.825)); -#68177 = CARTESIAN_POINT('',(-0.756181334756,-6.661338147751E-016)); -#68178 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); -#68179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68180 = ORIENTED_EDGE('',*,*,#56290,.F.); -#68181 = ADVANCED_FACE('',(#68182),#40346,.F.); -#68182 = FACE_BOUND('',#68183,.F.); -#68183 = EDGE_LOOP('',(#68184,#68206,#68231,#68232,#68233,#68234,#68254, - #68255,#68256,#68257)); -#68184 = ORIENTED_EDGE('',*,*,#68185,.F.); -#68185 = EDGE_CURVE('',#68186,#40262,#68188,.T.); -#68186 = VERTEX_POINT('',#68187); -#68187 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); -#68188 = SURFACE_CURVE('',#68189,(#68193,#68200),.PCURVE_S1.); -#68189 = LINE('',#68190,#68191); -#68190 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); -#68191 = VECTOR('',#68192,1.); -#68192 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#68193 = PCURVE('',#40346,#68194); -#68194 = DEFINITIONAL_REPRESENTATION('',(#68195),#68199); -#68195 = LINE('',#68196,#68197); -#68196 = CARTESIAN_POINT('',(1.340163581979,-1.05)); -#68197 = VECTOR('',#68198,1.); -#68198 = DIRECTION('',(-1.,0.E+000)); -#68199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68200 = PCURVE('',#39693,#68201); -#68201 = DEFINITIONAL_REPRESENTATION('',(#68202),#68205); -#68202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68203,#68204),.UNSPECIFIED., +#70564 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); +#70565 = CARTESIAN_POINT('',(1.14907455357,0.E+000)); +#70566 = CARTESIAN_POINT('',(0.672760581488,-0.825)); +#70567 = CARTESIAN_POINT('',(0.196446609407,-1.65)); +#70568 = CARTESIAN_POINT('',(-0.279867362674,-0.825)); +#70569 = CARTESIAN_POINT('',(-0.756181334756,-6.661338147751E-016)); +#70570 = CARTESIAN_POINT('',(0.196446609407,0.E+000)); +#70571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70572 = ORIENTED_EDGE('',*,*,#58682,.F.); +#70573 = ADVANCED_FACE('',(#70574),#42738,.F.); +#70574 = FACE_BOUND('',#70575,.F.); +#70575 = EDGE_LOOP('',(#70576,#70598,#70623,#70624,#70625,#70626,#70646, + #70647,#70648,#70649)); +#70576 = ORIENTED_EDGE('',*,*,#70577,.F.); +#70577 = EDGE_CURVE('',#70578,#42654,#70580,.T.); +#70578 = VERTEX_POINT('',#70579); +#70579 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); +#70580 = SURFACE_CURVE('',#70581,(#70585,#70592),.PCURVE_S1.); +#70581 = LINE('',#70582,#70583); +#70582 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); +#70583 = VECTOR('',#70584,1.); +#70584 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#70585 = PCURVE('',#42738,#70586); +#70586 = DEFINITIONAL_REPRESENTATION('',(#70587),#70591); +#70587 = LINE('',#70588,#70589); +#70588 = CARTESIAN_POINT('',(1.340163581979,-1.05)); +#70589 = VECTOR('',#70590,1.); +#70590 = DIRECTION('',(-1.,0.E+000)); +#70591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70592 = PCURVE('',#42085,#70593); +#70593 = DEFINITIONAL_REPRESENTATION('',(#70594),#70597); +#70594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70595,#70596),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.312618651698),.PIECEWISE_BEZIER_KNOTS.); -#68203 = CARTESIAN_POINT('',(1.570796326795,2.4754146701E-002)); -#68204 = CARTESIAN_POINT('',(1.570796326795,0.337372798399)); -#68205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68206 = ORIENTED_EDGE('',*,*,#68207,.F.); -#68207 = EDGE_CURVE('',#68101,#68186,#68208,.T.); -#68208 = SURFACE_CURVE('',#68209,(#68214,#68225),.PCURVE_S1.); -#68209 = CIRCLE('',#68210,0.55); -#68210 = AXIS2_PLACEMENT_3D('',#68211,#68212,#68213); -#68211 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-0.56)); -#68212 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68213 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#68214 = PCURVE('',#40346,#68215); -#68215 = DEFINITIONAL_REPRESENTATION('',(#68216),#68224); -#68216 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#68217,#68218,#68219,#68220 - ,#68221,#68222,#68223),.UNSPECIFIED.,.F.,.F.) +#70595 = CARTESIAN_POINT('',(1.570796326795,2.4754146701E-002)); +#70596 = CARTESIAN_POINT('',(1.570796326795,0.337372798399)); +#70597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70598 = ORIENTED_EDGE('',*,*,#70599,.F.); +#70599 = EDGE_CURVE('',#70493,#70578,#70600,.T.); +#70600 = SURFACE_CURVE('',#70601,(#70606,#70617),.PCURVE_S1.); +#70601 = CIRCLE('',#70602,0.55); +#70602 = AXIS2_PLACEMENT_3D('',#70603,#70604,#70605); +#70603 = CARTESIAN_POINT('',(3.2,-7.144660940673E-002,-0.56)); +#70604 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70605 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#70606 = PCURVE('',#42738,#70607); +#70607 = DEFINITIONAL_REPRESENTATION('',(#70608),#70616); +#70608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#70609,#70610,#70611,#70612 + ,#70613,#70614,#70615),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#68217 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); -#68218 = CARTESIAN_POINT('',(1.862518408918,-1.438254340206)); -#68219 = CARTESIAN_POINT('',(0.942350474806,-1.684812595052)); -#68220 = CARTESIAN_POINT('',(2.21825406948E-002,-1.931370849898)); -#68221 = CARTESIAN_POINT('',(0.268740795541,-1.011202915787)); -#68222 = CARTESIAN_POINT('',(0.515299050387,-9.10349816753E-002)); -#68223 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); -#68224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68225 = PCURVE('',#53510,#68226); -#68226 = DEFINITIONAL_REPRESENTATION('',(#68227),#68230); -#68227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68228,#68229),.UNSPECIFIED., +#70609 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); +#70610 = CARTESIAN_POINT('',(1.862518408918,-1.438254340206)); +#70611 = CARTESIAN_POINT('',(0.942350474806,-1.684812595052)); +#70612 = CARTESIAN_POINT('',(2.21825406948E-002,-1.931370849898)); +#70613 = CARTESIAN_POINT('',(0.268740795541,-1.011202915787)); +#70614 = CARTESIAN_POINT('',(0.515299050387,-9.10349816753E-002)); +#70615 = CARTESIAN_POINT('',(1.188908729653,-0.764644660941)); +#70616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70617 = PCURVE('',#55902,#70618); +#70618 = DEFINITIONAL_REPRESENTATION('',(#70619),#70622); +#70619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70620,#70621),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.595988761751),.PIECEWISE_BEZIER_KNOTS.); -#68228 = CARTESIAN_POINT('',(5.497787143782,1.79)); -#68229 = CARTESIAN_POINT('',(6.093775905533,1.79)); -#68230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68231 = ORIENTED_EDGE('',*,*,#68100,.F.); -#68232 = ORIENTED_EDGE('',*,*,#68156,.F.); -#68233 = ORIENTED_EDGE('',*,*,#56267,.T.); -#68234 = ORIENTED_EDGE('',*,*,#68235,.T.); -#68235 = EDGE_CURVE('',#56245,#41103,#68236,.T.); -#68236 = SURFACE_CURVE('',#68237,(#68241,#68248),.PCURVE_S1.); -#68237 = LINE('',#68238,#68239); -#68238 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); -#68239 = VECTOR('',#68240,1.); -#68240 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68241 = PCURVE('',#40346,#68242); -#68242 = DEFINITIONAL_REPRESENTATION('',(#68243),#68247); -#68243 = LINE('',#68244,#68245); -#68244 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68245 = VECTOR('',#68246,1.); -#68246 = DIRECTION('',(0.E+000,-1.)); -#68247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68248 = PCURVE('',#41146,#68249); -#68249 = DEFINITIONAL_REPRESENTATION('',(#68250),#68253); -#68250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68251,#68252),.UNSPECIFIED., +#70620 = CARTESIAN_POINT('',(5.497787143782,1.79)); +#70621 = CARTESIAN_POINT('',(6.093775905533,1.79)); +#70622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70623 = ORIENTED_EDGE('',*,*,#70492,.F.); +#70624 = ORIENTED_EDGE('',*,*,#70548,.F.); +#70625 = ORIENTED_EDGE('',*,*,#58659,.T.); +#70626 = ORIENTED_EDGE('',*,*,#70627,.T.); +#70627 = EDGE_CURVE('',#58637,#43495,#70628,.T.); +#70628 = SURFACE_CURVE('',#70629,(#70633,#70640),.PCURVE_S1.); +#70629 = LINE('',#70630,#70631); +#70630 = CARTESIAN_POINT('',(2.4,-1.225,-0.56)); +#70631 = VECTOR('',#70632,1.); +#70632 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70633 = PCURVE('',#42738,#70634); +#70634 = DEFINITIONAL_REPRESENTATION('',(#70635),#70639); +#70635 = LINE('',#70636,#70637); +#70636 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70637 = VECTOR('',#70638,1.); +#70638 = DIRECTION('',(0.E+000,-1.)); +#70639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70640 = PCURVE('',#43538,#70641); +#70641 = DEFINITIONAL_REPRESENTATION('',(#70642),#70645); +#70642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70643,#70644),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68251 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#68252 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#68253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68254 = ORIENTED_EDGE('',*,*,#41102,.F.); -#68255 = ORIENTED_EDGE('',*,*,#41000,.T.); -#68256 = ORIENTED_EDGE('',*,*,#40741,.F.); -#68257 = ORIENTED_EDGE('',*,*,#40330,.T.); -#68258 = ADVANCED_FACE('',(#68259),#39693,.F.); -#68259 = FACE_BOUND('',#68260,.F.); -#68260 = EDGE_LOOP('',(#68261,#68262,#68289,#68356,#68357,#68358)); -#68261 = ORIENTED_EDGE('',*,*,#39884,.F.); -#68262 = ORIENTED_EDGE('',*,*,#68263,.T.); -#68263 = EDGE_CURVE('',#39862,#68264,#68266,.T.); -#68264 = VERTEX_POINT('',#68265); -#68265 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-0.541561175052) - ); -#68266 = SURFACE_CURVE('',#68267,(#68272,#68278),.PCURVE_S1.); -#68267 = CIRCLE('',#68268,0.3); -#68268 = AXIS2_PLACEMENT_3D('',#68269,#68270,#68271); -#68269 = CARTESIAN_POINT('',(3.75,-0.175,-0.26)); -#68270 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#68271 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68272 = PCURVE('',#39693,#68273); -#68273 = DEFINITIONAL_REPRESENTATION('',(#68274),#68277); -#68274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68275,#68276),.UNSPECIFIED., +#70643 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#70644 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#70645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70646 = ORIENTED_EDGE('',*,*,#43494,.F.); +#70647 = ORIENTED_EDGE('',*,*,#43392,.T.); +#70648 = ORIENTED_EDGE('',*,*,#43133,.F.); +#70649 = ORIENTED_EDGE('',*,*,#42722,.T.); +#70650 = ADVANCED_FACE('',(#70651),#42085,.F.); +#70651 = FACE_BOUND('',#70652,.F.); +#70652 = EDGE_LOOP('',(#70653,#70654,#70681,#70748,#70749,#70750)); +#70653 = ORIENTED_EDGE('',*,*,#42276,.F.); +#70654 = ORIENTED_EDGE('',*,*,#70655,.T.); +#70655 = EDGE_CURVE('',#42254,#70656,#70658,.T.); +#70656 = VERTEX_POINT('',#70657); +#70657 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-0.541561175052) + ); +#70658 = SURFACE_CURVE('',#70659,(#70664,#70670),.PCURVE_S1.); +#70659 = CIRCLE('',#70660,0.3); +#70660 = AXIS2_PLACEMENT_3D('',#70661,#70662,#70663); +#70661 = CARTESIAN_POINT('',(3.75,-0.175,-0.26)); +#70662 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#70663 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70664 = PCURVE('',#42085,#70665); +#70665 = DEFINITIONAL_REPRESENTATION('',(#70666),#70669); +#70666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70667,#70668),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.218367924887),.PIECEWISE_BEZIER_KNOTS.); -#68275 = CARTESIAN_POINT('',(0.E+000,1.491772868E-002)); -#68276 = CARTESIAN_POINT('',(1.218367924887,1.491772868E-002)); -#68277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#70667 = CARTESIAN_POINT('',(0.E+000,1.491772868E-002)); +#70668 = CARTESIAN_POINT('',(1.218367924887,1.491772868E-002)); +#70669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68278 = PCURVE('',#38035,#68279); -#68279 = DEFINITIONAL_REPRESENTATION('',(#68280),#68288); -#68280 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#68281,#68282,#68283,#68284 - ,#68285,#68286,#68287),.UNSPECIFIED.,.T.,.F.) +#70670 = PCURVE('',#40427,#70671); +#70671 = DEFINITIONAL_REPRESENTATION('',(#70672),#70680); +#70672 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#70673,#70674,#70675,#70676 + ,#70677,#70678,#70679),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#68281 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#68282 = CARTESIAN_POINT('',(0.196446609407,1.570384757729)); -#68283 = CARTESIAN_POINT('',(-0.253553390593,1.830192378865)); -#68284 = CARTESIAN_POINT('',(-0.703553390593,2.09)); -#68285 = CARTESIAN_POINT('',(-0.253553390593,2.349807621135)); -#68286 = CARTESIAN_POINT('',(0.196446609407,2.609615242271)); -#68287 = CARTESIAN_POINT('',(0.196446609407,2.09)); -#68288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68289 = ORIENTED_EDGE('',*,*,#68290,.T.); -#68290 = EDGE_CURVE('',#68264,#68186,#68291,.T.); -#68291 = SURFACE_CURVE('',#68292,(#68298,#68327),.PCURVE_S1.); -#68292 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68293,#68294,#68295,#68296, - #68297),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), +#70673 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#70674 = CARTESIAN_POINT('',(0.196446609407,1.570384757729)); +#70675 = CARTESIAN_POINT('',(-0.253553390593,1.830192378865)); +#70676 = CARTESIAN_POINT('',(-0.703553390593,2.09)); +#70677 = CARTESIAN_POINT('',(-0.253553390593,2.349807621135)); +#70678 = CARTESIAN_POINT('',(0.196446609407,2.609615242271)); +#70679 = CARTESIAN_POINT('',(0.196446609407,2.09)); +#70680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70681 = ORIENTED_EDGE('',*,*,#70682,.T.); +#70682 = EDGE_CURVE('',#70656,#70578,#70683,.T.); +#70683 = SURFACE_CURVE('',#70684,(#70690,#70719),.PCURVE_S1.); +#70684 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70685,#70686,#70687,#70688, + #70689),.UNSPECIFIED.,.F.,.F.,(4,1,4),(0.E+000,0.5,1.), .QUASI_UNIFORM_KNOTS.); -#68293 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-0.541561175052) +#70685 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-0.541561175052) ); -#68294 = CARTESIAN_POINT('',(3.75,-8.810914429415E-002,-0.547689370756) +#70686 = CARTESIAN_POINT('',(3.75,-8.810914429415E-002,-0.547689370756) ); -#68295 = CARTESIAN_POINT('',(3.748473534432,-0.122396186728, +#70687 = CARTESIAN_POINT('',(3.748473534432,-0.122396186728, -0.55693337728)); -#68296 = CARTESIAN_POINT('',(3.743515535172,-0.157515270308,-0.56)); -#68297 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); -#68298 = PCURVE('',#39693,#68299); -#68299 = DEFINITIONAL_REPRESENTATION('',(#68300),#68326); -#68300 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68301,#68302,#68303,#68304, - #68305,#68306,#68307,#68308,#68309,#68310,#68311,#68312,#68313, - #68314,#68315,#68316,#68317,#68318,#68319,#68320,#68321,#68322, - #68323,#68324,#68325),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#70688 = CARTESIAN_POINT('',(3.743515535172,-0.157515270308,-0.56)); +#70689 = CARTESIAN_POINT('',(3.740163581979,-0.175,-0.56)); +#70690 = PCURVE('',#42085,#70691); +#70691 = DEFINITIONAL_REPRESENTATION('',(#70692),#70718); +#70692 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70693,#70694,#70695,#70696, + #70697,#70698,#70699,#70700,#70701,#70702,#70703,#70704,#70705, + #70706,#70707,#70708,#70709,#70710,#70711,#70712,#70713,#70714, + #70715,#70716,#70717),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -84246,40 +87235,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#68301 = CARTESIAN_POINT('',(1.218367924887,1.491772868E-002)); -#68302 = CARTESIAN_POINT('',(1.223747839559,1.491772868E-002)); -#68303 = CARTESIAN_POINT('',(1.234503906781,1.493034409792E-002)); -#68304 = CARTESIAN_POINT('',(1.250626850657,1.49875401531E-002)); -#68305 = CARTESIAN_POINT('',(1.26673877946,1.508343581115E-002)); -#68306 = CARTESIAN_POINT('',(1.282839791397,1.521845774662E-002)); -#68307 = CARTESIAN_POINT('',(1.298929961228,1.539303263406E-002)); -#68308 = CARTESIAN_POINT('',(1.31500934008,1.560758714804E-002)); -#68309 = CARTESIAN_POINT('',(1.331077960761,1.58625479631E-002)); -#68310 = CARTESIAN_POINT('',(1.347135841657,1.615834175381E-002)); -#68311 = CARTESIAN_POINT('',(1.363182990948,1.649539519472E-002)); -#68312 = CARTESIAN_POINT('',(1.379219411097,1.687413496038E-002)); -#68313 = CARTESIAN_POINT('',(1.395245101983,1.729498772536E-002)); -#68314 = CARTESIAN_POINT('',(1.411260069235,1.77583801642E-002)); -#68315 = CARTESIAN_POINT('',(1.427264284498,1.826438021142E-002)); -#68316 = CARTESIAN_POINT('',(1.443257679003,1.881305580155E-002)); -#68317 = CARTESIAN_POINT('',(1.459240152088,1.940447486909E-002)); -#68318 = CARTESIAN_POINT('',(1.475211574561,2.003870534856E-002)); -#68319 = CARTESIAN_POINT('',(1.491171793493,2.071581517447E-002)); -#68320 = CARTESIAN_POINT('',(1.507120636663,2.143587228134E-002)); -#68321 = CARTESIAN_POINT('',(1.523057917113,2.219894460369E-002)); -#68322 = CARTESIAN_POINT('',(1.538983437791,2.300510007603E-002)); -#68323 = CARTESIAN_POINT('',(1.554896995806,2.385440663288E-002)); -#68324 = CARTESIAN_POINT('',(1.56549792408,2.444942368345E-002)); -#68325 = CARTESIAN_POINT('',(1.570796326795,2.4754146701E-002)); -#68326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68327 = PCURVE('',#53510,#68328); -#68328 = DEFINITIONAL_REPRESENTATION('',(#68329),#68355); -#68329 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68330,#68331,#68332,#68333, - #68334,#68335,#68336,#68337,#68338,#68339,#68340,#68341,#68342, - #68343,#68344,#68345,#68346,#68347,#68348,#68349,#68350,#68351, - #68352,#68353,#68354),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#70693 = CARTESIAN_POINT('',(1.218367924887,1.491772868E-002)); +#70694 = CARTESIAN_POINT('',(1.223747839559,1.491772868E-002)); +#70695 = CARTESIAN_POINT('',(1.234503906781,1.493034409792E-002)); +#70696 = CARTESIAN_POINT('',(1.250626850657,1.49875401531E-002)); +#70697 = CARTESIAN_POINT('',(1.26673877946,1.508343581115E-002)); +#70698 = CARTESIAN_POINT('',(1.282839791397,1.521845774662E-002)); +#70699 = CARTESIAN_POINT('',(1.298929961228,1.539303263406E-002)); +#70700 = CARTESIAN_POINT('',(1.31500934008,1.560758714804E-002)); +#70701 = CARTESIAN_POINT('',(1.331077960761,1.58625479631E-002)); +#70702 = CARTESIAN_POINT('',(1.347135841657,1.615834175381E-002)); +#70703 = CARTESIAN_POINT('',(1.363182990948,1.649539519472E-002)); +#70704 = CARTESIAN_POINT('',(1.379219411097,1.687413496038E-002)); +#70705 = CARTESIAN_POINT('',(1.395245101983,1.729498772536E-002)); +#70706 = CARTESIAN_POINT('',(1.411260069235,1.77583801642E-002)); +#70707 = CARTESIAN_POINT('',(1.427264284498,1.826438021142E-002)); +#70708 = CARTESIAN_POINT('',(1.443257679003,1.881305580155E-002)); +#70709 = CARTESIAN_POINT('',(1.459240152088,1.940447486909E-002)); +#70710 = CARTESIAN_POINT('',(1.475211574561,2.003870534856E-002)); +#70711 = CARTESIAN_POINT('',(1.491171793493,2.071581517447E-002)); +#70712 = CARTESIAN_POINT('',(1.507120636663,2.143587228134E-002)); +#70713 = CARTESIAN_POINT('',(1.523057917113,2.219894460369E-002)); +#70714 = CARTESIAN_POINT('',(1.538983437791,2.300510007603E-002)); +#70715 = CARTESIAN_POINT('',(1.554896995806,2.385440663288E-002)); +#70716 = CARTESIAN_POINT('',(1.56549792408,2.444942368345E-002)); +#70717 = CARTESIAN_POINT('',(1.570796326795,2.4754146701E-002)); +#70718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70719 = PCURVE('',#55902,#70720); +#70720 = DEFINITIONAL_REPRESENTATION('',(#70721),#70747); +#70721 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70722,#70723,#70724,#70725, + #70726,#70727,#70728,#70729,#70730,#70731,#70732,#70733,#70734, + #70735,#70736,#70737,#70738,#70739,#70740,#70741,#70742,#70743, + #70744,#70745,#70746),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,4.545454545455E-002, 9.090909090909E-002,0.136363636364,0.181818181818,0.227272727273, 0.272727272727,0.318181818182,0.363636363636,0.409090909091, @@ -84287,562 +87276,562 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.681818181818,0.727272727273,0.772727272727,0.818181818182, 0.863636363636,0.909090909091,0.954545454545,1.), .QUASI_UNIFORM_KNOTS.); -#68330 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); -#68331 = CARTESIAN_POINT('',(6.280431168395,1.807881716248)); -#68332 = CARTESIAN_POINT('',(6.274908438895,1.80679239459)); -#68333 = CARTESIAN_POINT('',(6.266582634174,1.805233271323)); -#68334 = CARTESIAN_POINT('',(6.258216768288,1.803749179269)); -#68335 = CARTESIAN_POINT('',(6.249812476611,1.802340290418)); -#68336 = CARTESIAN_POINT('',(6.241371383812,1.801006776763)); -#68337 = CARTESIAN_POINT('',(6.232895101381,1.799748810296)); -#68338 = CARTESIAN_POINT('',(6.224385226653,1.798566563007)); -#68339 = CARTESIAN_POINT('',(6.215843341388,1.79746020689)); -#68340 = CARTESIAN_POINT('',(6.207271010483,1.796429913935)); -#68341 = CARTESIAN_POINT('',(6.198669780474,1.795475856135)); -#68342 = CARTESIAN_POINT('',(6.190041178667,1.794598205481)); -#68343 = CARTESIAN_POINT('',(6.181386709876,1.793797133966)); -#68344 = CARTESIAN_POINT('',(6.172708008643,1.793072591845)); -#68345 = CARTESIAN_POINT('',(6.164006709447,1.792424529377)); -#68346 = CARTESIAN_POINT('',(6.155284443453,1.79185289682)); -#68347 = CARTESIAN_POINT('',(6.146542837619,1.791357644429)); -#68348 = CARTESIAN_POINT('',(6.13778351315,1.790938722463)); -#68349 = CARTESIAN_POINT('',(6.129008084074,1.790596081179)); -#68350 = CARTESIAN_POINT('',(6.120218155906,1.790329670833)); -#68351 = CARTESIAN_POINT('',(6.111415323724,1.790139441685)); -#68352 = CARTESIAN_POINT('',(6.102601172495,1.790025343989)); -#68353 = CARTESIAN_POINT('',(6.096718570121,1.79)); -#68354 = CARTESIAN_POINT('',(6.093775905533,1.79)); -#68355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68356 = ORIENTED_EDGE('',*,*,#68185,.T.); -#68357 = ORIENTED_EDGE('',*,*,#40261,.T.); -#68358 = ORIENTED_EDGE('',*,*,#39672,.T.); -#68359 = ADVANCED_FACE('',(#68360),#38035,.T.); -#68360 = FACE_BOUND('',#68361,.F.); -#68361 = EDGE_LOOP('',(#68362,#68382,#68383,#68384,#68385,#68405,#68406, - #68407,#68408,#68428)); -#68362 = ORIENTED_EDGE('',*,*,#68363,.T.); -#68363 = EDGE_CURVE('',#53494,#68264,#68364,.T.); -#68364 = SURFACE_CURVE('',#68365,(#68369,#68376),.PCURVE_S1.); -#68365 = LINE('',#68366,#68367); -#68366 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); -#68367 = VECTOR('',#68368,1.); -#68368 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68369 = PCURVE('',#38035,#68370); -#68370 = DEFINITIONAL_REPRESENTATION('',(#68371),#68375); -#68371 = LINE('',#68372,#68373); -#68372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68373 = VECTOR('',#68374,1.); -#68374 = DIRECTION('',(0.E+000,1.)); -#68375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68376 = PCURVE('',#53510,#68377); -#68377 = DEFINITIONAL_REPRESENTATION('',(#68378),#68381); -#68378 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68379,#68380),.UNSPECIFIED., +#70722 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); +#70723 = CARTESIAN_POINT('',(6.280431168395,1.807881716248)); +#70724 = CARTESIAN_POINT('',(6.274908438895,1.80679239459)); +#70725 = CARTESIAN_POINT('',(6.266582634174,1.805233271323)); +#70726 = CARTESIAN_POINT('',(6.258216768288,1.803749179269)); +#70727 = CARTESIAN_POINT('',(6.249812476611,1.802340290418)); +#70728 = CARTESIAN_POINT('',(6.241371383812,1.801006776763)); +#70729 = CARTESIAN_POINT('',(6.232895101381,1.799748810296)); +#70730 = CARTESIAN_POINT('',(6.224385226653,1.798566563007)); +#70731 = CARTESIAN_POINT('',(6.215843341388,1.79746020689)); +#70732 = CARTESIAN_POINT('',(6.207271010483,1.796429913935)); +#70733 = CARTESIAN_POINT('',(6.198669780474,1.795475856135)); +#70734 = CARTESIAN_POINT('',(6.190041178667,1.794598205481)); +#70735 = CARTESIAN_POINT('',(6.181386709876,1.793797133966)); +#70736 = CARTESIAN_POINT('',(6.172708008643,1.793072591845)); +#70737 = CARTESIAN_POINT('',(6.164006709447,1.792424529377)); +#70738 = CARTESIAN_POINT('',(6.155284443453,1.79185289682)); +#70739 = CARTESIAN_POINT('',(6.146542837619,1.791357644429)); +#70740 = CARTESIAN_POINT('',(6.13778351315,1.790938722463)); +#70741 = CARTESIAN_POINT('',(6.129008084074,1.790596081179)); +#70742 = CARTESIAN_POINT('',(6.120218155906,1.790329670833)); +#70743 = CARTESIAN_POINT('',(6.111415323724,1.790139441685)); +#70744 = CARTESIAN_POINT('',(6.102601172495,1.790025343989)); +#70745 = CARTESIAN_POINT('',(6.096718570121,1.79)); +#70746 = CARTESIAN_POINT('',(6.093775905533,1.79)); +#70747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70748 = ORIENTED_EDGE('',*,*,#70577,.T.); +#70749 = ORIENTED_EDGE('',*,*,#42653,.T.); +#70750 = ORIENTED_EDGE('',*,*,#42064,.T.); +#70751 = ADVANCED_FACE('',(#70752),#40427,.T.); +#70752 = FACE_BOUND('',#70753,.F.); +#70753 = EDGE_LOOP('',(#70754,#70774,#70775,#70776,#70777,#70797,#70798, + #70799,#70800,#70820)); +#70754 = ORIENTED_EDGE('',*,*,#70755,.T.); +#70755 = EDGE_CURVE('',#55886,#70656,#70756,.T.); +#70756 = SURFACE_CURVE('',#70757,(#70761,#70768),.PCURVE_S1.); +#70757 = LINE('',#70758,#70759); +#70758 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,-2.35)); +#70759 = VECTOR('',#70760,1.); +#70760 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70761 = PCURVE('',#40427,#70762); +#70762 = DEFINITIONAL_REPRESENTATION('',(#70763),#70767); +#70763 = LINE('',#70764,#70765); +#70764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70765 = VECTOR('',#70766,1.); +#70766 = DIRECTION('',(0.E+000,1.)); +#70767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70768 = PCURVE('',#55902,#70769); +#70769 = DEFINITIONAL_REPRESENTATION('',(#70770),#70773); +#70770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70771,#70772),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.808438824948),.PIECEWISE_BEZIER_KNOTS.); -#68379 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#68380 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); -#68381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68382 = ORIENTED_EDGE('',*,*,#68263,.F.); -#68383 = ORIENTED_EDGE('',*,*,#39861,.T.); -#68384 = ORIENTED_EDGE('',*,*,#40183,.F.); -#68385 = ORIENTED_EDGE('',*,*,#68386,.T.); -#68386 = EDGE_CURVE('',#40115,#38020,#68387,.T.); -#68387 = SURFACE_CURVE('',#68388,(#68392,#68399),.PCURVE_S1.); -#68388 = LINE('',#68389,#68390); -#68389 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); -#68390 = VECTOR('',#68391,1.); -#68391 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68392 = PCURVE('',#38035,#68393); -#68393 = DEFINITIONAL_REPRESENTATION('',(#68394),#68398); -#68394 = LINE('',#68395,#68396); -#68395 = CARTESIAN_POINT('',(0.E+000,3.291561175052)); -#68396 = VECTOR('',#68397,1.); -#68397 = DIRECTION('',(0.E+000,1.)); -#68398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68399 = PCURVE('',#38064,#68400); -#68400 = DEFINITIONAL_REPRESENTATION('',(#68401),#68404); -#68401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68402,#68403),.UNSPECIFIED., +#70771 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#70772 = CARTESIAN_POINT('',(6.28318530718,1.808438824948)); +#70773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70774 = ORIENTED_EDGE('',*,*,#70655,.F.); +#70775 = ORIENTED_EDGE('',*,*,#42253,.T.); +#70776 = ORIENTED_EDGE('',*,*,#42575,.F.); +#70777 = ORIENTED_EDGE('',*,*,#70778,.T.); +#70778 = EDGE_CURVE('',#42507,#40412,#70779,.T.); +#70779 = SURFACE_CURVE('',#70780,(#70784,#70791),.PCURVE_S1.); +#70780 = LINE('',#70781,#70782); +#70781 = CARTESIAN_POINT('',(3.75,-7.144660940673E-002,0.941561175052)); +#70782 = VECTOR('',#70783,1.); +#70783 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70784 = PCURVE('',#40427,#70785); +#70785 = DEFINITIONAL_REPRESENTATION('',(#70786),#70790); +#70786 = LINE('',#70787,#70788); +#70787 = CARTESIAN_POINT('',(0.E+000,3.291561175052)); +#70788 = VECTOR('',#70789,1.); +#70789 = DIRECTION('',(0.E+000,1.)); +#70790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70791 = PCURVE('',#40456,#70792); +#70792 = DEFINITIONAL_REPRESENTATION('',(#70793),#70796); +#70793 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70794,#70795),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.408438824948),.PIECEWISE_BEZIER_KNOTS.); -#68402 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); -#68403 = CARTESIAN_POINT('',(6.28318530718,4.7)); -#68404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68405 = ORIENTED_EDGE('',*,*,#38019,.T.); -#68406 = ORIENTED_EDGE('',*,*,#39374,.F.); -#68407 = ORIENTED_EDGE('',*,*,#38652,.T.); -#68408 = ORIENTED_EDGE('',*,*,#68409,.F.); -#68409 = EDGE_CURVE('',#53522,#38625,#68410,.T.); -#68410 = SURFACE_CURVE('',#68411,(#68415,#68422),.PCURVE_S1.); -#68411 = LINE('',#68412,#68413); -#68412 = CARTESIAN_POINT('',(3.75,0.675,-2.35)); -#68413 = VECTOR('',#68414,1.); -#68414 = DIRECTION('',(0.E+000,0.E+000,1.)); -#68415 = PCURVE('',#38035,#68416); -#68416 = DEFINITIONAL_REPRESENTATION('',(#68417),#68421); -#68417 = LINE('',#68418,#68419); -#68418 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); -#68419 = VECTOR('',#68420,1.); -#68420 = DIRECTION('',(0.E+000,1.)); -#68421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68422 = PCURVE('',#38641,#68423); -#68423 = DEFINITIONAL_REPRESENTATION('',(#68424),#68427); -#68424 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68425,#68426),.UNSPECIFIED., +#70794 = CARTESIAN_POINT('',(6.28318530718,3.291561175052)); +#70795 = CARTESIAN_POINT('',(6.28318530718,4.7)); +#70796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70797 = ORIENTED_EDGE('',*,*,#40411,.T.); +#70798 = ORIENTED_EDGE('',*,*,#41766,.F.); +#70799 = ORIENTED_EDGE('',*,*,#41044,.T.); +#70800 = ORIENTED_EDGE('',*,*,#70801,.F.); +#70801 = EDGE_CURVE('',#55914,#41017,#70802,.T.); +#70802 = SURFACE_CURVE('',#70803,(#70807,#70814),.PCURVE_S1.); +#70803 = LINE('',#70804,#70805); +#70804 = CARTESIAN_POINT('',(3.75,0.675,-2.35)); +#70805 = VECTOR('',#70806,1.); +#70806 = DIRECTION('',(0.E+000,0.E+000,1.)); +#70807 = PCURVE('',#40427,#70808); +#70808 = DEFINITIONAL_REPRESENTATION('',(#70809),#70813); +#70809 = LINE('',#70810,#70811); +#70810 = CARTESIAN_POINT('',(0.746446609407,0.E+000)); +#70811 = VECTOR('',#70812,1.); +#70812 = DIRECTION('',(0.E+000,1.)); +#70813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70814 = PCURVE('',#41033,#70815); +#70815 = DEFINITIONAL_REPRESENTATION('',(#70816),#70819); +#70816 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70817,#70818),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,4.7),.PIECEWISE_BEZIER_KNOTS.); -#68425 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68426 = CARTESIAN_POINT('',(0.E+000,4.7)); -#68427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68428 = ORIENTED_EDGE('',*,*,#53521,.F.); -#68429 = ADVANCED_FACE('',(#68430),#38064,.T.); -#68430 = FACE_BOUND('',#68431,.T.); -#68431 = EDGE_LOOP('',(#68432,#68433,#68434,#68435,#68436)); -#68432 = ORIENTED_EDGE('',*,*,#68386,.T.); -#68433 = ORIENTED_EDGE('',*,*,#38047,.F.); -#68434 = ORIENTED_EDGE('',*,*,#68051,.F.); -#68435 = ORIENTED_EDGE('',*,*,#40607,.T.); -#68436 = ORIENTED_EDGE('',*,*,#40114,.T.); -#68437 = ADVANCED_FACE('',(#68438),#53510,.T.); -#68438 = FACE_BOUND('',#68439,.T.); -#68439 = EDGE_LOOP('',(#68440,#68441,#68442,#68443,#68444)); -#68440 = ORIENTED_EDGE('',*,*,#68207,.F.); -#68441 = ORIENTED_EDGE('',*,*,#68123,.F.); -#68442 = ORIENTED_EDGE('',*,*,#53493,.T.); -#68443 = ORIENTED_EDGE('',*,*,#68363,.T.); -#68444 = ORIENTED_EDGE('',*,*,#68290,.T.); -#68445 = ADVANCED_FACE('',(#68446),#38641,.T.); -#68446 = FACE_BOUND('',#68447,.T.); -#68447 = EDGE_LOOP('',(#68448,#68449,#68450,#68451)); -#68448 = ORIENTED_EDGE('',*,*,#38624,.F.); -#68449 = ORIENTED_EDGE('',*,*,#68409,.F.); -#68450 = ORIENTED_EDGE('',*,*,#53544,.T.); -#68451 = ORIENTED_EDGE('',*,*,#49196,.T.); -#68452 = ADVANCED_FACE('',(#68453),#41146,.F.); -#68453 = FACE_BOUND('',#68454,.F.); -#68454 = EDGE_LOOP('',(#68455,#68456,#68476,#68477)); -#68455 = ORIENTED_EDGE('',*,*,#56244,.F.); -#68456 = ORIENTED_EDGE('',*,*,#68457,.T.); -#68457 = EDGE_CURVE('',#56222,#41126,#68458,.T.); -#68458 = SURFACE_CURVE('',#68459,(#68463,#68469),.PCURVE_S1.); -#68459 = LINE('',#68460,#68461); -#68460 = CARTESIAN_POINT('',(2.25,-1.225,-0.41)); -#68461 = VECTOR('',#68462,1.); -#68462 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68463 = PCURVE('',#41146,#68464); -#68464 = DEFINITIONAL_REPRESENTATION('',(#68465),#68468); -#68465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68466,#68467),.UNSPECIFIED., +#70817 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70818 = CARTESIAN_POINT('',(0.E+000,4.7)); +#70819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70820 = ORIENTED_EDGE('',*,*,#55913,.F.); +#70821 = ADVANCED_FACE('',(#70822),#40456,.T.); +#70822 = FACE_BOUND('',#70823,.T.); +#70823 = EDGE_LOOP('',(#70824,#70825,#70826,#70827,#70828)); +#70824 = ORIENTED_EDGE('',*,*,#70778,.T.); +#70825 = ORIENTED_EDGE('',*,*,#40439,.F.); +#70826 = ORIENTED_EDGE('',*,*,#70443,.F.); +#70827 = ORIENTED_EDGE('',*,*,#42999,.T.); +#70828 = ORIENTED_EDGE('',*,*,#42506,.T.); +#70829 = ADVANCED_FACE('',(#70830),#55902,.T.); +#70830 = FACE_BOUND('',#70831,.T.); +#70831 = EDGE_LOOP('',(#70832,#70833,#70834,#70835,#70836)); +#70832 = ORIENTED_EDGE('',*,*,#70599,.F.); +#70833 = ORIENTED_EDGE('',*,*,#70515,.F.); +#70834 = ORIENTED_EDGE('',*,*,#55885,.T.); +#70835 = ORIENTED_EDGE('',*,*,#70755,.T.); +#70836 = ORIENTED_EDGE('',*,*,#70682,.T.); +#70837 = ADVANCED_FACE('',(#70838),#41033,.T.); +#70838 = FACE_BOUND('',#70839,.T.); +#70839 = EDGE_LOOP('',(#70840,#70841,#70842,#70843)); +#70840 = ORIENTED_EDGE('',*,*,#41016,.F.); +#70841 = ORIENTED_EDGE('',*,*,#70801,.F.); +#70842 = ORIENTED_EDGE('',*,*,#55936,.T.); +#70843 = ORIENTED_EDGE('',*,*,#51588,.T.); +#70844 = ADVANCED_FACE('',(#70845),#43538,.F.); +#70845 = FACE_BOUND('',#70846,.F.); +#70846 = EDGE_LOOP('',(#70847,#70848,#70868,#70869)); +#70847 = ORIENTED_EDGE('',*,*,#58636,.F.); +#70848 = ORIENTED_EDGE('',*,*,#70849,.T.); +#70849 = EDGE_CURVE('',#58614,#43518,#70850,.T.); +#70850 = SURFACE_CURVE('',#70851,(#70855,#70861),.PCURVE_S1.); +#70851 = LINE('',#70852,#70853); +#70852 = CARTESIAN_POINT('',(2.25,-1.225,-0.41)); +#70853 = VECTOR('',#70854,1.); +#70854 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70855 = PCURVE('',#43538,#70856); +#70856 = DEFINITIONAL_REPRESENTATION('',(#70857),#70860); +#70857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70858,#70859),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68466 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#68467 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#68468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68469 = PCURVE('',#41173,#68470); -#68470 = DEFINITIONAL_REPRESENTATION('',(#68471),#68475); -#68471 = LINE('',#68472,#68473); -#68472 = CARTESIAN_POINT('',(1.22,0.E+000)); -#68473 = VECTOR('',#68474,1.); -#68474 = DIRECTION('',(0.E+000,-1.)); -#68475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68476 = ORIENTED_EDGE('',*,*,#41125,.T.); -#68477 = ORIENTED_EDGE('',*,*,#68235,.F.); -#68478 = ADVANCED_FACE('',(#68479),#41405,.F.); -#68479 = FACE_BOUND('',#68480,.F.); -#68480 = EDGE_LOOP('',(#68481,#68501,#68502,#68522)); -#68481 = ORIENTED_EDGE('',*,*,#68482,.T.); -#68482 = EDGE_CURVE('',#41362,#56030,#68483,.T.); -#68483 = SURFACE_CURVE('',#68484,(#68488,#68495),.PCURVE_S1.); -#68484 = LINE('',#68485,#68486); -#68485 = CARTESIAN_POINT('',(2.25,-0.925,0.8)); -#68486 = VECTOR('',#68487,1.); -#68487 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#68488 = PCURVE('',#41405,#68489); -#68489 = DEFINITIONAL_REPRESENTATION('',(#68490),#68494); -#68490 = LINE('',#68491,#68492); -#68491 = CARTESIAN_POINT('',(1.E-002,-0.3)); -#68492 = VECTOR('',#68493,1.); -#68493 = DIRECTION('',(0.E+000,1.)); -#68494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68495 = PCURVE('',#41378,#68496); -#68496 = DEFINITIONAL_REPRESENTATION('',(#68497),#68500); -#68497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68498,#68499),.UNSPECIFIED., +#70858 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70859 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70861 = PCURVE('',#43565,#70862); +#70862 = DEFINITIONAL_REPRESENTATION('',(#70863),#70867); +#70863 = LINE('',#70864,#70865); +#70864 = CARTESIAN_POINT('',(1.22,0.E+000)); +#70865 = VECTOR('',#70866,1.); +#70866 = DIRECTION('',(0.E+000,-1.)); +#70867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70868 = ORIENTED_EDGE('',*,*,#43517,.T.); +#70869 = ORIENTED_EDGE('',*,*,#70627,.F.); +#70870 = ADVANCED_FACE('',(#70871),#43797,.F.); +#70871 = FACE_BOUND('',#70872,.F.); +#70872 = EDGE_LOOP('',(#70873,#70893,#70894,#70914)); +#70873 = ORIENTED_EDGE('',*,*,#70874,.T.); +#70874 = EDGE_CURVE('',#43754,#58422,#70875,.T.); +#70875 = SURFACE_CURVE('',#70876,(#70880,#70887),.PCURVE_S1.); +#70876 = LINE('',#70877,#70878); +#70877 = CARTESIAN_POINT('',(2.25,-0.925,0.8)); +#70878 = VECTOR('',#70879,1.); +#70879 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#70880 = PCURVE('',#43797,#70881); +#70881 = DEFINITIONAL_REPRESENTATION('',(#70882),#70886); +#70882 = LINE('',#70883,#70884); +#70883 = CARTESIAN_POINT('',(1.E-002,-0.3)); +#70884 = VECTOR('',#70885,1.); +#70885 = DIRECTION('',(0.E+000,1.)); +#70886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70887 = PCURVE('',#43770,#70888); +#70888 = DEFINITIONAL_REPRESENTATION('',(#70889),#70892); +#70889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70890,#70891),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68498 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#68499 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#68500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68501 = ORIENTED_EDGE('',*,*,#56029,.F.); -#68502 = ORIENTED_EDGE('',*,*,#68503,.T.); -#68503 = EDGE_CURVE('',#56007,#41390,#68504,.T.); -#68504 = SURFACE_CURVE('',#68505,(#68509,#68516),.PCURVE_S1.); -#68505 = LINE('',#68506,#68507); -#68506 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); -#68507 = VECTOR('',#68508,1.); -#68508 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68509 = PCURVE('',#41405,#68510); -#68510 = DEFINITIONAL_REPRESENTATION('',(#68511),#68515); -#68511 = LINE('',#68512,#68513); -#68512 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68513 = VECTOR('',#68514,1.); -#68514 = DIRECTION('',(0.E+000,-1.)); -#68515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68516 = PCURVE('',#40527,#68517); -#68517 = DEFINITIONAL_REPRESENTATION('',(#68518),#68521); -#68518 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68519,#68520),.UNSPECIFIED., +#70890 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70891 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70893 = ORIENTED_EDGE('',*,*,#58421,.F.); +#70894 = ORIENTED_EDGE('',*,*,#70895,.T.); +#70895 = EDGE_CURVE('',#58399,#43782,#70896,.T.); +#70896 = SURFACE_CURVE('',#70897,(#70901,#70908),.PCURVE_S1.); +#70897 = LINE('',#70898,#70899); +#70898 = CARTESIAN_POINT('',(2.25,-1.225,0.81)); +#70899 = VECTOR('',#70900,1.); +#70900 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70901 = PCURVE('',#43797,#70902); +#70902 = DEFINITIONAL_REPRESENTATION('',(#70903),#70907); +#70903 = LINE('',#70904,#70905); +#70904 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70905 = VECTOR('',#70906,1.); +#70906 = DIRECTION('',(0.E+000,-1.)); +#70907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70908 = PCURVE('',#42919,#70909); +#70909 = DEFINITIONAL_REPRESENTATION('',(#70910),#70913); +#70910 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70911,#70912),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68519 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#68520 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#68521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68522 = ORIENTED_EDGE('',*,*,#41389,.T.); -#68523 = ADVANCED_FACE('',(#68524),#41173,.F.); -#68524 = FACE_BOUND('',#68525,.F.); -#68525 = EDGE_LOOP('',(#68526,#68546,#68547,#68548)); -#68526 = ORIENTED_EDGE('',*,*,#68527,.F.); -#68527 = EDGE_CURVE('',#41158,#56195,#68528,.T.); -#68528 = SURFACE_CURVE('',#68529,(#68533,#68540),.PCURVE_S1.); -#68529 = LINE('',#68530,#68531); -#68530 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); -#68531 = VECTOR('',#68532,1.); -#68532 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#68533 = PCURVE('',#41173,#68534); -#68534 = DEFINITIONAL_REPRESENTATION('',(#68535),#68539); -#68535 = LINE('',#68536,#68537); -#68536 = CARTESIAN_POINT('',(1.21,-0.3)); -#68537 = VECTOR('',#68538,1.); -#68538 = DIRECTION('',(0.E+000,1.)); -#68539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68540 = PCURVE('',#41202,#68541); -#68541 = DEFINITIONAL_REPRESENTATION('',(#68542),#68545); -#68542 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68543,#68544),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68543 = CARTESIAN_POINT('',(3.14159265359,-0.3)); -#68544 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#68545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68546 = ORIENTED_EDGE('',*,*,#41157,.T.); -#68547 = ORIENTED_EDGE('',*,*,#68457,.F.); -#68548 = ORIENTED_EDGE('',*,*,#56221,.F.); -#68549 = ADVANCED_FACE('',(#68550),#41378,.F.); -#68550 = FACE_BOUND('',#68551,.F.); -#68551 = EDGE_LOOP('',(#68552,#68553,#68554,#68574)); -#68552 = ORIENTED_EDGE('',*,*,#68482,.F.); -#68553 = ORIENTED_EDGE('',*,*,#41361,.F.); -#68554 = ORIENTED_EDGE('',*,*,#68555,.F.); -#68555 = EDGE_CURVE('',#56053,#41334,#68556,.T.); -#68556 = SURFACE_CURVE('',#68557,(#68561,#68567),.PCURVE_S1.); -#68557 = LINE('',#68558,#68559); -#68558 = CARTESIAN_POINT('',(2.4,-1.225,0.65)); -#68559 = VECTOR('',#68560,1.); -#68560 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68561 = PCURVE('',#41378,#68562); -#68562 = DEFINITIONAL_REPRESENTATION('',(#68563),#68566); -#68563 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68564,#68565),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68564 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#68565 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#68566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68567 = PCURVE('',#41349,#68568); -#68568 = DEFINITIONAL_REPRESENTATION('',(#68569),#68573); -#68569 = LINE('',#68570,#68571); -#68570 = CARTESIAN_POINT('',(1.3,0.E+000)); -#68571 = VECTOR('',#68572,1.); -#68572 = DIRECTION('',(0.E+000,-1.)); -#68573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68574 = ORIENTED_EDGE('',*,*,#56052,.T.); -#68575 = ADVANCED_FACE('',(#68576),#41349,.T.); -#68576 = FACE_BOUND('',#68577,.F.); -#68577 = EDGE_LOOP('',(#68578,#68579,#68580,#68581)); -#68578 = ORIENTED_EDGE('',*,*,#56079,.T.); -#68579 = ORIENTED_EDGE('',*,*,#68555,.T.); -#68580 = ORIENTED_EDGE('',*,*,#41333,.F.); -#68581 = ORIENTED_EDGE('',*,*,#68582,.F.); -#68582 = EDGE_CURVE('',#56080,#41302,#68583,.T.); -#68583 = SURFACE_CURVE('',#68584,(#68588,#68595),.PCURVE_S1.); -#68584 = LINE('',#68585,#68586); -#68585 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); -#68586 = VECTOR('',#68587,1.); -#68587 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68588 = PCURVE('',#41349,#68589); -#68589 = DEFINITIONAL_REPRESENTATION('',(#68590),#68594); -#68590 = LINE('',#68591,#68592); -#68591 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68592 = VECTOR('',#68593,1.); -#68593 = DIRECTION('',(0.E+000,-1.)); -#68594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#70911 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70912 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70914 = ORIENTED_EDGE('',*,*,#43781,.T.); +#70915 = ADVANCED_FACE('',(#70916),#43565,.F.); +#70916 = FACE_BOUND('',#70917,.F.); +#70917 = EDGE_LOOP('',(#70918,#70938,#70939,#70940)); +#70918 = ORIENTED_EDGE('',*,*,#70919,.F.); +#70919 = EDGE_CURVE('',#43550,#58587,#70920,.T.); +#70920 = SURFACE_CURVE('',#70921,(#70925,#70932),.PCURVE_S1.); +#70921 = LINE('',#70922,#70923); +#70922 = CARTESIAN_POINT('',(2.25,-0.925,-0.4)); +#70923 = VECTOR('',#70924,1.); +#70924 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#70925 = PCURVE('',#43565,#70926); +#70926 = DEFINITIONAL_REPRESENTATION('',(#70927),#70931); +#70927 = LINE('',#70928,#70929); +#70928 = CARTESIAN_POINT('',(1.21,-0.3)); +#70929 = VECTOR('',#70930,1.); +#70930 = DIRECTION('',(0.E+000,1.)); +#70931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68595 = PCURVE('',#41322,#68596); -#68596 = DEFINITIONAL_REPRESENTATION('',(#68597),#68600); -#68597 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68598,#68599),.UNSPECIFIED., +#70932 = PCURVE('',#43594,#70933); +#70933 = DEFINITIONAL_REPRESENTATION('',(#70934),#70937); +#70934 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70935,#70936),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68598 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#68599 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#68600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68601 = ADVANCED_FACE('',(#68602),#41322,.T.); -#68602 = FACE_BOUND('',#68603,.T.); -#68603 = EDGE_LOOP('',(#68604,#68605,#68625,#68626)); -#68604 = ORIENTED_EDGE('',*,*,#56102,.F.); -#68605 = ORIENTED_EDGE('',*,*,#68606,.T.); -#68606 = EDGE_CURVE('',#56103,#41274,#68607,.T.); -#68607 = SURFACE_CURVE('',#68608,(#68612,#68618),.PCURVE_S1.); -#68608 = LINE('',#68609,#68610); -#68609 = CARTESIAN_POINT('',(3.9,-1.225,0.45)); -#68610 = VECTOR('',#68611,1.); -#68611 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68612 = PCURVE('',#41322,#68613); -#68613 = DEFINITIONAL_REPRESENTATION('',(#68614),#68617); -#68614 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68615,#68616),.UNSPECIFIED., +#70935 = CARTESIAN_POINT('',(3.14159265359,-0.3)); +#70936 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#70937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70938 = ORIENTED_EDGE('',*,*,#43549,.T.); +#70939 = ORIENTED_EDGE('',*,*,#70849,.F.); +#70940 = ORIENTED_EDGE('',*,*,#58613,.F.); +#70941 = ADVANCED_FACE('',(#70942),#43770,.F.); +#70942 = FACE_BOUND('',#70943,.F.); +#70943 = EDGE_LOOP('',(#70944,#70945,#70946,#70966)); +#70944 = ORIENTED_EDGE('',*,*,#70874,.F.); +#70945 = ORIENTED_EDGE('',*,*,#43753,.F.); +#70946 = ORIENTED_EDGE('',*,*,#70947,.F.); +#70947 = EDGE_CURVE('',#58445,#43726,#70948,.T.); +#70948 = SURFACE_CURVE('',#70949,(#70953,#70959),.PCURVE_S1.); +#70949 = LINE('',#70950,#70951); +#70950 = CARTESIAN_POINT('',(2.4,-1.225,0.65)); +#70951 = VECTOR('',#70952,1.); +#70952 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70953 = PCURVE('',#43770,#70954); +#70954 = DEFINITIONAL_REPRESENTATION('',(#70955),#70958); +#70955 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70956,#70957),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#70956 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#70957 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#70958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70959 = PCURVE('',#43741,#70960); +#70960 = DEFINITIONAL_REPRESENTATION('',(#70961),#70965); +#70961 = LINE('',#70962,#70963); +#70962 = CARTESIAN_POINT('',(1.3,0.E+000)); +#70963 = VECTOR('',#70964,1.); +#70964 = DIRECTION('',(0.E+000,-1.)); +#70965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70966 = ORIENTED_EDGE('',*,*,#58444,.T.); +#70967 = ADVANCED_FACE('',(#70968),#43741,.T.); +#70968 = FACE_BOUND('',#70969,.F.); +#70969 = EDGE_LOOP('',(#70970,#70971,#70972,#70973)); +#70970 = ORIENTED_EDGE('',*,*,#58471,.T.); +#70971 = ORIENTED_EDGE('',*,*,#70947,.T.); +#70972 = ORIENTED_EDGE('',*,*,#43725,.F.); +#70973 = ORIENTED_EDGE('',*,*,#70974,.F.); +#70974 = EDGE_CURVE('',#58472,#43694,#70975,.T.); +#70975 = SURFACE_CURVE('',#70976,(#70980,#70987),.PCURVE_S1.); +#70976 = LINE('',#70977,#70978); +#70977 = CARTESIAN_POINT('',(3.7,-1.225,0.65)); +#70978 = VECTOR('',#70979,1.); +#70979 = DIRECTION('',(0.E+000,1.,0.E+000)); +#70980 = PCURVE('',#43741,#70981); +#70981 = DEFINITIONAL_REPRESENTATION('',(#70982),#70986); +#70982 = LINE('',#70983,#70984); +#70983 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#70984 = VECTOR('',#70985,1.); +#70985 = DIRECTION('',(0.E+000,-1.)); +#70986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70987 = PCURVE('',#43714,#70988); +#70988 = DEFINITIONAL_REPRESENTATION('',(#70989),#70992); +#70989 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70990,#70991),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68615 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68616 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#68617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68618 = PCURVE('',#41289,#68619); -#68619 = DEFINITIONAL_REPRESENTATION('',(#68620),#68624); -#68620 = LINE('',#68621,#68622); -#68621 = CARTESIAN_POINT('',(0.5,0.E+000)); -#68622 = VECTOR('',#68623,1.); -#68623 = DIRECTION('',(0.E+000,-1.)); -#68624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68625 = ORIENTED_EDGE('',*,*,#41301,.T.); -#68626 = ORIENTED_EDGE('',*,*,#68582,.F.); -#68627 = ADVANCED_FACE('',(#68628),#41289,.T.); -#68628 = FACE_BOUND('',#68629,.F.); -#68629 = EDGE_LOOP('',(#68630,#68631,#68632,#68633)); -#68630 = ORIENTED_EDGE('',*,*,#56125,.T.); -#68631 = ORIENTED_EDGE('',*,*,#68606,.T.); -#68632 = ORIENTED_EDGE('',*,*,#41273,.F.); -#68633 = ORIENTED_EDGE('',*,*,#68634,.F.); -#68634 = EDGE_CURVE('',#56126,#41242,#68635,.T.); -#68635 = SURFACE_CURVE('',#68636,(#68640,#68647),.PCURVE_S1.); -#68636 = LINE('',#68637,#68638); -#68637 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); -#68638 = VECTOR('',#68639,1.); -#68639 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68640 = PCURVE('',#41289,#68641); -#68641 = DEFINITIONAL_REPRESENTATION('',(#68642),#68646); -#68642 = LINE('',#68643,#68644); -#68643 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68644 = VECTOR('',#68645,1.); -#68645 = DIRECTION('',(0.E+000,-1.)); -#68646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68647 = PCURVE('',#41262,#68648); -#68648 = DEFINITIONAL_REPRESENTATION('',(#68649),#68652); -#68649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68650,#68651),.UNSPECIFIED., +#70990 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#70991 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#70992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#70993 = ADVANCED_FACE('',(#70994),#43714,.T.); +#70994 = FACE_BOUND('',#70995,.T.); +#70995 = EDGE_LOOP('',(#70996,#70997,#71017,#71018)); +#70996 = ORIENTED_EDGE('',*,*,#58494,.F.); +#70997 = ORIENTED_EDGE('',*,*,#70998,.T.); +#70998 = EDGE_CURVE('',#58495,#43666,#70999,.T.); +#70999 = SURFACE_CURVE('',#71000,(#71004,#71010),.PCURVE_S1.); +#71000 = LINE('',#71001,#71002); +#71001 = CARTESIAN_POINT('',(3.9,-1.225,0.45)); +#71002 = VECTOR('',#71003,1.); +#71003 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71004 = PCURVE('',#43714,#71005); +#71005 = DEFINITIONAL_REPRESENTATION('',(#71006),#71009); +#71006 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71007,#71008),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68650 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#68651 = CARTESIAN_POINT('',(6.28318530718,-0.3)); -#68652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68653 = ADVANCED_FACE('',(#68654),#41262,.T.); -#68654 = FACE_BOUND('',#68655,.T.); -#68655 = EDGE_LOOP('',(#68656,#68657,#68677,#68678)); -#68656 = ORIENTED_EDGE('',*,*,#56148,.F.); -#68657 = ORIENTED_EDGE('',*,*,#68658,.T.); -#68658 = EDGE_CURVE('',#56149,#41214,#68659,.T.); -#68659 = SURFACE_CURVE('',#68660,(#68664,#68670),.PCURVE_S1.); -#68660 = LINE('',#68661,#68662); -#68661 = CARTESIAN_POINT('',(3.7,-1.225,-0.25)); -#68662 = VECTOR('',#68663,1.); -#68663 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68664 = PCURVE('',#41262,#68665); -#68665 = DEFINITIONAL_REPRESENTATION('',(#68666),#68669); -#68666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68667,#68668),.UNSPECIFIED., +#71007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71008 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#71009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71010 = PCURVE('',#43681,#71011); +#71011 = DEFINITIONAL_REPRESENTATION('',(#71012),#71016); +#71012 = LINE('',#71013,#71014); +#71013 = CARTESIAN_POINT('',(0.5,0.E+000)); +#71014 = VECTOR('',#71015,1.); +#71015 = DIRECTION('',(0.E+000,-1.)); +#71016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71017 = ORIENTED_EDGE('',*,*,#43693,.T.); +#71018 = ORIENTED_EDGE('',*,*,#70974,.F.); +#71019 = ADVANCED_FACE('',(#71020),#43681,.T.); +#71020 = FACE_BOUND('',#71021,.F.); +#71021 = EDGE_LOOP('',(#71022,#71023,#71024,#71025)); +#71022 = ORIENTED_EDGE('',*,*,#58517,.T.); +#71023 = ORIENTED_EDGE('',*,*,#70998,.T.); +#71024 = ORIENTED_EDGE('',*,*,#43665,.F.); +#71025 = ORIENTED_EDGE('',*,*,#71026,.F.); +#71026 = EDGE_CURVE('',#58518,#43634,#71027,.T.); +#71027 = SURFACE_CURVE('',#71028,(#71032,#71039),.PCURVE_S1.); +#71028 = LINE('',#71029,#71030); +#71029 = CARTESIAN_POINT('',(3.9,-1.225,-5.E-002)); +#71030 = VECTOR('',#71031,1.); +#71031 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71032 = PCURVE('',#43681,#71033); +#71033 = DEFINITIONAL_REPRESENTATION('',(#71034),#71038); +#71034 = LINE('',#71035,#71036); +#71035 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71036 = VECTOR('',#71037,1.); +#71037 = DIRECTION('',(0.E+000,-1.)); +#71038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71039 = PCURVE('',#43654,#71040); +#71040 = DEFINITIONAL_REPRESENTATION('',(#71041),#71044); +#71041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71042,#71043),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68667 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#68668 = CARTESIAN_POINT('',(4.712388980385,-0.3)); -#68669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68670 = PCURVE('',#41229,#68671); -#68671 = DEFINITIONAL_REPRESENTATION('',(#68672),#68676); -#68672 = LINE('',#68673,#68674); -#68673 = CARTESIAN_POINT('',(1.3,0.E+000)); -#68674 = VECTOR('',#68675,1.); -#68675 = DIRECTION('',(0.E+000,-1.)); -#68676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68677 = ORIENTED_EDGE('',*,*,#41241,.T.); -#68678 = ORIENTED_EDGE('',*,*,#68634,.F.); -#68679 = ADVANCED_FACE('',(#68680),#41229,.T.); -#68680 = FACE_BOUND('',#68681,.F.); -#68681 = EDGE_LOOP('',(#68682,#68683,#68684,#68685)); -#68682 = ORIENTED_EDGE('',*,*,#56171,.T.); -#68683 = ORIENTED_EDGE('',*,*,#68658,.T.); -#68684 = ORIENTED_EDGE('',*,*,#41213,.F.); -#68685 = ORIENTED_EDGE('',*,*,#68686,.F.); -#68686 = EDGE_CURVE('',#56172,#41186,#68687,.T.); -#68687 = SURFACE_CURVE('',#68688,(#68692,#68699),.PCURVE_S1.); -#68688 = LINE('',#68689,#68690); -#68689 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); -#68690 = VECTOR('',#68691,1.); -#68691 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68692 = PCURVE('',#41229,#68693); -#68693 = DEFINITIONAL_REPRESENTATION('',(#68694),#68698); -#68694 = LINE('',#68695,#68696); -#68695 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68696 = VECTOR('',#68697,1.); -#68697 = DIRECTION('',(0.E+000,-1.)); -#68698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68699 = PCURVE('',#41202,#68700); -#68700 = DEFINITIONAL_REPRESENTATION('',(#68701),#68704); -#68701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68702,#68703),.UNSPECIFIED., +#71042 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#71043 = CARTESIAN_POINT('',(6.28318530718,-0.3)); +#71044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71045 = ADVANCED_FACE('',(#71046),#43654,.T.); +#71046 = FACE_BOUND('',#71047,.T.); +#71047 = EDGE_LOOP('',(#71048,#71049,#71069,#71070)); +#71048 = ORIENTED_EDGE('',*,*,#58540,.F.); +#71049 = ORIENTED_EDGE('',*,*,#71050,.T.); +#71050 = EDGE_CURVE('',#58541,#43606,#71051,.T.); +#71051 = SURFACE_CURVE('',#71052,(#71056,#71062),.PCURVE_S1.); +#71052 = LINE('',#71053,#71054); +#71053 = CARTESIAN_POINT('',(3.7,-1.225,-0.25)); +#71054 = VECTOR('',#71055,1.); +#71055 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71056 = PCURVE('',#43654,#71057); +#71057 = DEFINITIONAL_REPRESENTATION('',(#71058),#71061); +#71058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71059,#71060),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#71059 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#71060 = CARTESIAN_POINT('',(4.712388980385,-0.3)); +#71061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71062 = PCURVE('',#43621,#71063); +#71063 = DEFINITIONAL_REPRESENTATION('',(#71064),#71068); +#71064 = LINE('',#71065,#71066); +#71065 = CARTESIAN_POINT('',(1.3,0.E+000)); +#71066 = VECTOR('',#71067,1.); +#71067 = DIRECTION('',(0.E+000,-1.)); +#71068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71069 = ORIENTED_EDGE('',*,*,#43633,.T.); +#71070 = ORIENTED_EDGE('',*,*,#71026,.F.); +#71071 = ADVANCED_FACE('',(#71072),#43621,.T.); +#71072 = FACE_BOUND('',#71073,.F.); +#71073 = EDGE_LOOP('',(#71074,#71075,#71076,#71077)); +#71074 = ORIENTED_EDGE('',*,*,#58563,.T.); +#71075 = ORIENTED_EDGE('',*,*,#71050,.T.); +#71076 = ORIENTED_EDGE('',*,*,#43605,.F.); +#71077 = ORIENTED_EDGE('',*,*,#71078,.F.); +#71078 = EDGE_CURVE('',#58564,#43578,#71079,.T.); +#71079 = SURFACE_CURVE('',#71080,(#71084,#71091),.PCURVE_S1.); +#71080 = LINE('',#71081,#71082); +#71081 = CARTESIAN_POINT('',(2.4,-1.225,-0.25)); +#71082 = VECTOR('',#71083,1.); +#71083 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71084 = PCURVE('',#43621,#71085); +#71085 = DEFINITIONAL_REPRESENTATION('',(#71086),#71090); +#71086 = LINE('',#71087,#71088); +#71087 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71088 = VECTOR('',#71089,1.); +#71089 = DIRECTION('',(0.E+000,-1.)); +#71090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71091 = PCURVE('',#43594,#71092); +#71092 = DEFINITIONAL_REPRESENTATION('',(#71093),#71096); +#71093 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71094,#71095),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68702 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#68703 = CARTESIAN_POINT('',(1.570796326795,-0.3)); -#68704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68705 = ADVANCED_FACE('',(#68706),#41202,.F.); -#68706 = FACE_BOUND('',#68707,.F.); -#68707 = EDGE_LOOP('',(#68708,#68709,#68710,#68711)); -#68708 = ORIENTED_EDGE('',*,*,#68527,.T.); -#68709 = ORIENTED_EDGE('',*,*,#56194,.T.); -#68710 = ORIENTED_EDGE('',*,*,#68686,.T.); -#68711 = ORIENTED_EDGE('',*,*,#41185,.F.); -#68712 = ADVANCED_FACE('',(#68713),#40527,.F.); -#68713 = FACE_BOUND('',#68714,.F.); -#68714 = EDGE_LOOP('',(#68715,#68716,#68717,#68718)); -#68715 = ORIENTED_EDGE('',*,*,#56006,.F.); -#68716 = ORIENTED_EDGE('',*,*,#40511,.T.); -#68717 = ORIENTED_EDGE('',*,*,#41417,.T.); -#68718 = ORIENTED_EDGE('',*,*,#68503,.F.); -#68719 = ADVANCED_FACE('',(#68720),#55450,.F.); -#68720 = FACE_BOUND('',#68721,.F.); -#68721 = EDGE_LOOP('',(#68722,#68723,#68724,#68725)); -#68722 = ORIENTED_EDGE('',*,*,#59501,.T.); -#68723 = ORIENTED_EDGE('',*,*,#59642,.F.); -#68724 = ORIENTED_EDGE('',*,*,#55434,.T.); -#68725 = ORIENTED_EDGE('',*,*,#68726,.T.); -#68726 = EDGE_CURVE('',#55412,#59502,#68727,.T.); -#68727 = SURFACE_CURVE('',#68728,(#68732,#68739),.PCURVE_S1.); -#68728 = LINE('',#68729,#68730); -#68729 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); -#68730 = VECTOR('',#68731,1.); -#68731 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68732 = PCURVE('',#55450,#68733); -#68733 = DEFINITIONAL_REPRESENTATION('',(#68734),#68738); -#68734 = LINE('',#68735,#68736); -#68735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68736 = VECTOR('',#68737,1.); -#68737 = DIRECTION('',(0.E+000,-1.)); -#68738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68739 = PCURVE('',#41926,#68740); -#68740 = DEFINITIONAL_REPRESENTATION('',(#68741),#68744); -#68741 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68742,#68743),.UNSPECIFIED., +#71094 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#71095 = CARTESIAN_POINT('',(1.570796326795,-0.3)); +#71096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71097 = ADVANCED_FACE('',(#71098),#43594,.F.); +#71098 = FACE_BOUND('',#71099,.F.); +#71099 = EDGE_LOOP('',(#71100,#71101,#71102,#71103)); +#71100 = ORIENTED_EDGE('',*,*,#70919,.T.); +#71101 = ORIENTED_EDGE('',*,*,#58586,.T.); +#71102 = ORIENTED_EDGE('',*,*,#71078,.T.); +#71103 = ORIENTED_EDGE('',*,*,#43577,.F.); +#71104 = ADVANCED_FACE('',(#71105),#42919,.F.); +#71105 = FACE_BOUND('',#71106,.F.); +#71106 = EDGE_LOOP('',(#71107,#71108,#71109,#71110)); +#71107 = ORIENTED_EDGE('',*,*,#58398,.F.); +#71108 = ORIENTED_EDGE('',*,*,#42903,.T.); +#71109 = ORIENTED_EDGE('',*,*,#43809,.T.); +#71110 = ORIENTED_EDGE('',*,*,#70895,.F.); +#71111 = ADVANCED_FACE('',(#71112),#57842,.F.); +#71112 = FACE_BOUND('',#71113,.F.); +#71113 = EDGE_LOOP('',(#71114,#71115,#71116,#71117)); +#71114 = ORIENTED_EDGE('',*,*,#61893,.T.); +#71115 = ORIENTED_EDGE('',*,*,#62034,.F.); +#71116 = ORIENTED_EDGE('',*,*,#57826,.T.); +#71117 = ORIENTED_EDGE('',*,*,#71118,.T.); +#71118 = EDGE_CURVE('',#57804,#61894,#71119,.T.); +#71119 = SURFACE_CURVE('',#71120,(#71124,#71131),.PCURVE_S1.); +#71120 = LINE('',#71121,#71122); +#71121 = CARTESIAN_POINT('',(-1.79,-1.225,-1.21)); +#71122 = VECTOR('',#71123,1.); +#71123 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71124 = PCURVE('',#57842,#71125); +#71125 = DEFINITIONAL_REPRESENTATION('',(#71126),#71130); +#71126 = LINE('',#71127,#71128); +#71127 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71128 = VECTOR('',#71129,1.); +#71129 = DIRECTION('',(0.E+000,-1.)); +#71130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71131 = PCURVE('',#44318,#71132); +#71132 = DEFINITIONAL_REPRESENTATION('',(#71133),#71136); +#71133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71134,#71135),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,2.5E-002),.PIECEWISE_BEZIER_KNOTS.); -#68742 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#68743 = CARTESIAN_POINT('',(3.14159265359,-2.5E-002)); -#68744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68745 = ADVANCED_FACE('',(#68746),#41926,.F.); -#68746 = FACE_BOUND('',#68747,.F.); -#68747 = EDGE_LOOP('',(#68748,#68749,#68750,#68751,#68752,#68753)); -#68748 = ORIENTED_EDGE('',*,*,#43598,.T.); -#68749 = ORIENTED_EDGE('',*,*,#59524,.T.); -#68750 = ORIENTED_EDGE('',*,*,#68726,.F.); -#68751 = ORIENTED_EDGE('',*,*,#55411,.F.); -#68752 = ORIENTED_EDGE('',*,*,#59354,.T.); -#68753 = ORIENTED_EDGE('',*,*,#41905,.T.); -#68754 = ADVANCED_FACE('',(#68755),#38932,.T.); -#68755 = FACE_BOUND('',#68756,.T.); -#68756 = EDGE_LOOP('',(#68757,#68758,#68759,#68760)); -#68757 = ORIENTED_EDGE('',*,*,#38915,.F.); -#68758 = ORIENTED_EDGE('',*,*,#54530,.T.); -#68759 = ORIENTED_EDGE('',*,*,#39569,.T.); -#68760 = ORIENTED_EDGE('',*,*,#68761,.F.); -#68761 = EDGE_CURVE('',#38888,#39570,#68762,.T.); -#68762 = SURFACE_CURVE('',#68763,(#68767,#68773),.PCURVE_S1.); -#68763 = LINE('',#68764,#68765); -#68764 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); -#68765 = VECTOR('',#68766,1.); -#68766 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68767 = PCURVE('',#38932,#68768); -#68768 = DEFINITIONAL_REPRESENTATION('',(#68769),#68772); -#68769 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68770,#68771),.UNSPECIFIED., +#71134 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#71135 = CARTESIAN_POINT('',(3.14159265359,-2.5E-002)); +#71136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71137 = ADVANCED_FACE('',(#71138),#44318,.F.); +#71138 = FACE_BOUND('',#71139,.F.); +#71139 = EDGE_LOOP('',(#71140,#71141,#71142,#71143,#71144,#71145)); +#71140 = ORIENTED_EDGE('',*,*,#45990,.T.); +#71141 = ORIENTED_EDGE('',*,*,#61916,.T.); +#71142 = ORIENTED_EDGE('',*,*,#71118,.F.); +#71143 = ORIENTED_EDGE('',*,*,#57803,.F.); +#71144 = ORIENTED_EDGE('',*,*,#61746,.T.); +#71145 = ORIENTED_EDGE('',*,*,#44297,.T.); +#71146 = ADVANCED_FACE('',(#71147),#41324,.T.); +#71147 = FACE_BOUND('',#71148,.T.); +#71148 = EDGE_LOOP('',(#71149,#71150,#71151,#71152)); +#71149 = ORIENTED_EDGE('',*,*,#41307,.F.); +#71150 = ORIENTED_EDGE('',*,*,#56922,.T.); +#71151 = ORIENTED_EDGE('',*,*,#41961,.T.); +#71152 = ORIENTED_EDGE('',*,*,#71153,.F.); +#71153 = EDGE_CURVE('',#41280,#41962,#71154,.T.); +#71154 = SURFACE_CURVE('',#71155,(#71159,#71165),.PCURVE_S1.); +#71155 = LINE('',#71156,#71157); +#71156 = CARTESIAN_POINT('',(-3.554832205403,2.5E-002,2.577885045795)); +#71157 = VECTOR('',#71158,1.); +#71158 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71159 = PCURVE('',#41324,#71160); +#71160 = DEFINITIONAL_REPRESENTATION('',(#71161),#71164); +#71161 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71162,#71163),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.6),.PIECEWISE_BEZIER_KNOTS.); -#68770 = CARTESIAN_POINT('',(0.878236128669,0.E+000)); -#68771 = CARTESIAN_POINT('',(0.878236128669,-0.6)); -#68772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68773 = PCURVE('',#38903,#68774); -#68774 = DEFINITIONAL_REPRESENTATION('',(#68775),#68779); -#68775 = LINE('',#68776,#68777); -#68776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#68777 = VECTOR('',#68778,1.); -#68778 = DIRECTION('',(0.E+000,-1.)); -#68779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68780 = ADVANCED_FACE('',(#68781),#38903,.T.); -#68781 = FACE_BOUND('',#68782,.F.); -#68782 = EDGE_LOOP('',(#68783,#68829,#68830,#68831,#68832,#68878)); -#68783 = ORIENTED_EDGE('',*,*,#68784,.F.); -#68784 = EDGE_CURVE('',#39475,#68785,#68787,.T.); -#68785 = VERTEX_POINT('',#68786); -#68786 = CARTESIAN_POINT('',(-3.798447109038,0.425,2.78)); -#68787 = SURFACE_CURVE('',#68788,(#68793,#68800),.PCURVE_S1.); -#68788 = CIRCLE('',#68789,0.2); -#68789 = AXIS2_PLACEMENT_3D('',#68790,#68791,#68792); -#68790 = CARTESIAN_POINT('',(-3.644524343464,0.425,2.652298072692)); -#68791 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#68792 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68793 = PCURVE('',#38903,#68794); -#68794 = DEFINITIONAL_REPRESENTATION('',(#68795),#68799); -#68795 = CIRCLE('',#68796,0.2); -#68796 = AXIS2_PLACEMENT_2D('',#68797,#68798); -#68797 = CARTESIAN_POINT('',(0.116541744461,-0.4)); -#68798 = DIRECTION('',(0.E+000,-1.)); -#68799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68800 = PCURVE('',#39490,#68801); -#68801 = DEFINITIONAL_REPRESENTATION('',(#68802),#68828); -#68802 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68803,#68804,#68805,#68806, - #68807,#68808,#68809,#68810,#68811,#68812,#68813,#68814,#68815, - #68816,#68817,#68818,#68819,#68820,#68821,#68822,#68823,#68824, - #68825,#68826,#68827),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71162 = CARTESIAN_POINT('',(0.878236128669,0.E+000)); +#71163 = CARTESIAN_POINT('',(0.878236128669,-0.6)); +#71164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71165 = PCURVE('',#41295,#71166); +#71166 = DEFINITIONAL_REPRESENTATION('',(#71167),#71171); +#71167 = LINE('',#71168,#71169); +#71168 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71169 = VECTOR('',#71170,1.); +#71170 = DIRECTION('',(0.E+000,-1.)); +#71171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71172 = ADVANCED_FACE('',(#71173),#41295,.T.); +#71173 = FACE_BOUND('',#71174,.F.); +#71174 = EDGE_LOOP('',(#71175,#71221,#71222,#71223,#71224,#71270)); +#71175 = ORIENTED_EDGE('',*,*,#71176,.F.); +#71176 = EDGE_CURVE('',#41867,#71177,#71179,.T.); +#71177 = VERTEX_POINT('',#71178); +#71178 = CARTESIAN_POINT('',(-3.798447109038,0.425,2.78)); +#71179 = SURFACE_CURVE('',#71180,(#71185,#71192),.PCURVE_S1.); +#71180 = CIRCLE('',#71181,0.2); +#71181 = AXIS2_PLACEMENT_3D('',#71182,#71183,#71184); +#71182 = CARTESIAN_POINT('',(-3.644524343464,0.425,2.652298072692)); +#71183 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#71184 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71185 = PCURVE('',#41295,#71186); +#71186 = DEFINITIONAL_REPRESENTATION('',(#71187),#71191); +#71187 = CIRCLE('',#71188,0.2); +#71188 = AXIS2_PLACEMENT_2D('',#71189,#71190); +#71189 = CARTESIAN_POINT('',(0.116541744461,-0.4)); +#71190 = DIRECTION('',(0.E+000,-1.)); +#71191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71192 = PCURVE('',#41882,#71193); +#71193 = DEFINITIONAL_REPRESENTATION('',(#71194),#71220); +#71194 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71195,#71196,#71197,#71198, + #71199,#71200,#71201,#71202,#71203,#71204,#71205,#71206,#71207, + #71208,#71209,#71210,#71211,#71212,#71213,#71214,#71215,#71216, + #71217,#71218,#71219),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -84850,62 +87839,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#68803 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); -#68804 = CARTESIAN_POINT('',(2.379994434567E-002,0.322039397384)); -#68805 = CARTESIAN_POINT('',(7.139983303669E-002,0.322039397384)); -#68806 = CARTESIAN_POINT('',(0.142799666073,0.322039397384)); -#68807 = CARTESIAN_POINT('',(0.214199499109,0.322039397384)); -#68808 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); -#68809 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); -#68810 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); -#68811 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); -#68812 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); -#68813 = CARTESIAN_POINT('',(0.642598497326,0.322039397384)); -#68814 = CARTESIAN_POINT('',(0.713998330362,0.322039397384)); -#68815 = CARTESIAN_POINT('',(0.785398163398,0.322039397384)); -#68816 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); -#68817 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); -#68818 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); -#68819 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); -#68820 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); -#68821 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); -#68822 = CARTESIAN_POINT('',(1.285196994651,0.322039397384)); -#68823 = CARTESIAN_POINT('',(1.356596827687,0.322039397384)); -#68824 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); -#68825 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); -#68826 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); -#68827 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#68828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68829 = ORIENTED_EDGE('',*,*,#39592,.F.); -#68830 = ORIENTED_EDGE('',*,*,#68761,.F.); -#68831 = ORIENTED_EDGE('',*,*,#38887,.T.); -#68832 = ORIENTED_EDGE('',*,*,#68833,.F.); -#68833 = EDGE_CURVE('',#68834,#38836,#68836,.T.); -#68834 = VERTEX_POINT('',#68835); -#68835 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); -#68836 = SURFACE_CURVE('',#68837,(#68842,#68849),.PCURVE_S1.); -#68837 = CIRCLE('',#68838,0.2); -#68838 = AXIS2_PLACEMENT_3D('',#68839,#68840,#68841); -#68839 = CARTESIAN_POINT('',(-3.644524343464,0.225,2.652298072692)); -#68840 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#68841 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#68842 = PCURVE('',#38903,#68843); -#68843 = DEFINITIONAL_REPRESENTATION('',(#68844),#68848); -#68844 = CIRCLE('',#68845,0.2); -#68845 = AXIS2_PLACEMENT_2D('',#68846,#68847); -#68846 = CARTESIAN_POINT('',(0.116541744461,-0.2)); -#68847 = DIRECTION('',(1.,0.E+000)); -#68848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#71195 = CARTESIAN_POINT('',(0.E+000,0.322039397384)); +#71196 = CARTESIAN_POINT('',(2.379994434567E-002,0.322039397384)); +#71197 = CARTESIAN_POINT('',(7.139983303669E-002,0.322039397384)); +#71198 = CARTESIAN_POINT('',(0.142799666073,0.322039397384)); +#71199 = CARTESIAN_POINT('',(0.214199499109,0.322039397384)); +#71200 = CARTESIAN_POINT('',(0.285599332145,0.322039397384)); +#71201 = CARTESIAN_POINT('',(0.356999165181,0.322039397384)); +#71202 = CARTESIAN_POINT('',(0.428398998217,0.322039397384)); +#71203 = CARTESIAN_POINT('',(0.499798831253,0.322039397384)); +#71204 = CARTESIAN_POINT('',(0.571198664289,0.322039397384)); +#71205 = CARTESIAN_POINT('',(0.642598497326,0.322039397384)); +#71206 = CARTESIAN_POINT('',(0.713998330362,0.322039397384)); +#71207 = CARTESIAN_POINT('',(0.785398163398,0.322039397384)); +#71208 = CARTESIAN_POINT('',(0.856797996434,0.322039397384)); +#71209 = CARTESIAN_POINT('',(0.92819782947,0.322039397384)); +#71210 = CARTESIAN_POINT('',(0.999597662506,0.322039397384)); +#71211 = CARTESIAN_POINT('',(1.070997495542,0.322039397384)); +#71212 = CARTESIAN_POINT('',(1.142397328578,0.322039397384)); +#71213 = CARTESIAN_POINT('',(1.213797161614,0.322039397384)); +#71214 = CARTESIAN_POINT('',(1.285196994651,0.322039397384)); +#71215 = CARTESIAN_POINT('',(1.356596827687,0.322039397384)); +#71216 = CARTESIAN_POINT('',(1.427996660723,0.322039397384)); +#71217 = CARTESIAN_POINT('',(1.499396493759,0.322039397384)); +#71218 = CARTESIAN_POINT('',(1.54699638245,0.322039397384)); +#71219 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#71220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71221 = ORIENTED_EDGE('',*,*,#41984,.F.); +#71222 = ORIENTED_EDGE('',*,*,#71153,.F.); +#71223 = ORIENTED_EDGE('',*,*,#41279,.T.); +#71224 = ORIENTED_EDGE('',*,*,#71225,.F.); +#71225 = EDGE_CURVE('',#71226,#41228,#71228,.T.); +#71226 = VERTEX_POINT('',#71227); +#71227 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); +#71228 = SURFACE_CURVE('',#71229,(#71234,#71241),.PCURVE_S1.); +#71229 = CIRCLE('',#71230,0.2); +#71230 = AXIS2_PLACEMENT_3D('',#71231,#71232,#71233); +#71231 = CARTESIAN_POINT('',(-3.644524343464,0.225,2.652298072692)); +#71232 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#71233 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#71234 = PCURVE('',#41295,#71235); +#71235 = DEFINITIONAL_REPRESENTATION('',(#71236),#71240); +#71236 = CIRCLE('',#71237,0.2); +#71237 = AXIS2_PLACEMENT_2D('',#71238,#71239); +#71238 = CARTESIAN_POINT('',(0.116541744461,-0.2)); +#71239 = DIRECTION('',(1.,0.E+000)); +#71240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68849 = PCURVE('',#38853,#68850); -#68850 = DEFINITIONAL_REPRESENTATION('',(#68851),#68877); -#68851 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68852,#68853,#68854,#68855, - #68856,#68857,#68858,#68859,#68860,#68861,#68862,#68863,#68864, - #68865,#68866,#68867,#68868,#68869,#68870,#68871,#68872,#68873, - #68874,#68875,#68876),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71241 = PCURVE('',#41245,#71242); +#71242 = DEFINITIONAL_REPRESENTATION('',(#71243),#71269); +#71243 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71244,#71245,#71246,#71247, + #71248,#71249,#71250,#71251,#71252,#71253,#71254,#71255,#71256, + #71257,#71258,#71259,#71260,#71261,#71262,#71263,#71264,#71265, + #71266,#71267,#71268),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -84913,85 +87902,85 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#68852 = CARTESIAN_POINT('',(1.570796326795,1.551463154844E-002)); -#68853 = CARTESIAN_POINT('',(1.54699638245,1.551463154844E-002)); -#68854 = CARTESIAN_POINT('',(1.499396493759,1.551463154844E-002)); -#68855 = CARTESIAN_POINT('',(1.427996660723,1.551463154844E-002)); -#68856 = CARTESIAN_POINT('',(1.356596827686,1.551463154844E-002)); -#68857 = CARTESIAN_POINT('',(1.28519699465,1.551463154844E-002)); -#68858 = CARTESIAN_POINT('',(1.213797161614,1.551463154844E-002)); -#68859 = CARTESIAN_POINT('',(1.142397328578,1.551463154844E-002)); -#68860 = CARTESIAN_POINT('',(1.070997495542,1.551463154844E-002)); -#68861 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); -#68862 = CARTESIAN_POINT('',(0.92819782947,1.551463154844E-002)); -#68863 = CARTESIAN_POINT('',(0.856797996433,1.551463154844E-002)); -#68864 = CARTESIAN_POINT('',(0.785398163397,1.551463154844E-002)); -#68865 = CARTESIAN_POINT('',(0.713998330361,1.551463154844E-002)); -#68866 = CARTESIAN_POINT('',(0.642598497325,1.551463154844E-002)); -#68867 = CARTESIAN_POINT('',(0.571198664289,1.551463154844E-002)); -#68868 = CARTESIAN_POINT('',(0.499798831253,1.551463154844E-002)); -#68869 = CARTESIAN_POINT('',(0.428398998217,1.551463154844E-002)); -#68870 = CARTESIAN_POINT('',(0.35699916518,1.551463154844E-002)); -#68871 = CARTESIAN_POINT('',(0.285599332144,1.551463154844E-002)); -#68872 = CARTESIAN_POINT('',(0.214199499108,1.551463154844E-002)); -#68873 = CARTESIAN_POINT('',(0.142799666072,1.551463154844E-002)); -#68874 = CARTESIAN_POINT('',(7.139983303578E-002,1.551463154844E-002)); -#68875 = CARTESIAN_POINT('',(2.379994434519E-002,1.551463154844E-002)); -#68876 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); -#68877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68878 = ORIENTED_EDGE('',*,*,#68879,.T.); -#68879 = EDGE_CURVE('',#68834,#68785,#68880,.T.); -#68880 = SURFACE_CURVE('',#68881,(#68885,#68892),.PCURVE_S1.); -#68881 = LINE('',#68882,#68883); -#68882 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); -#68883 = VECTOR('',#68884,1.); -#68884 = DIRECTION('',(0.E+000,1.,0.E+000)); -#68885 = PCURVE('',#38903,#68886); -#68886 = DEFINITIONAL_REPRESENTATION('',(#68887),#68891); -#68887 = LINE('',#68888,#68889); -#68888 = CARTESIAN_POINT('',(0.316541744461,-0.2)); -#68889 = VECTOR('',#68890,1.); -#68890 = DIRECTION('',(0.E+000,-1.)); -#68891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68892 = PCURVE('',#68893,#68898); -#68893 = PLANE('',#68894); -#68894 = AXIS2_PLACEMENT_3D('',#68895,#68896,#68897); -#68895 = CARTESIAN_POINT('',(-3.798447109038,2.5E-002,2.78)); -#68896 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#68897 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#68898 = DEFINITIONAL_REPRESENTATION('',(#68899),#68903); -#68899 = LINE('',#68900,#68901); -#68900 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#68901 = VECTOR('',#68902,1.); -#68902 = DIRECTION('',(0.E+000,-1.)); -#68903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68904 = ADVANCED_FACE('',(#68905),#39490,.T.); -#68905 = FACE_BOUND('',#68906,.T.); -#68906 = EDGE_LOOP('',(#68907,#68908,#68909,#68955)); -#68907 = ORIENTED_EDGE('',*,*,#68784,.F.); -#68908 = ORIENTED_EDGE('',*,*,#39472,.F.); -#68909 = ORIENTED_EDGE('',*,*,#68910,.F.); -#68910 = EDGE_CURVE('',#68911,#39473,#68913,.T.); -#68911 = VERTEX_POINT('',#68912); -#68912 = CARTESIAN_POINT('',(-3.99,0.425,2.54911585164)); -#68913 = SURFACE_CURVE('',#68914,(#68919,#68948),.PCURVE_S1.); -#68914 = CIRCLE('',#68915,0.2); -#68915 = AXIS2_PLACEMENT_3D('',#68916,#68917,#68918); -#68916 = CARTESIAN_POINT('',(-3.836077234426,0.425,2.421413924332)); -#68917 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#68918 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); -#68919 = PCURVE('',#39490,#68920); -#68920 = DEFINITIONAL_REPRESENTATION('',(#68921),#68947); -#68921 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#68922,#68923,#68924,#68925, - #68926,#68927,#68928,#68929,#68930,#68931,#68932,#68933,#68934, - #68935,#68936,#68937,#68938,#68939,#68940,#68941,#68942,#68943, - #68944,#68945,#68946),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71244 = CARTESIAN_POINT('',(1.570796326795,1.551463154844E-002)); +#71245 = CARTESIAN_POINT('',(1.54699638245,1.551463154844E-002)); +#71246 = CARTESIAN_POINT('',(1.499396493759,1.551463154844E-002)); +#71247 = CARTESIAN_POINT('',(1.427996660723,1.551463154844E-002)); +#71248 = CARTESIAN_POINT('',(1.356596827686,1.551463154844E-002)); +#71249 = CARTESIAN_POINT('',(1.28519699465,1.551463154844E-002)); +#71250 = CARTESIAN_POINT('',(1.213797161614,1.551463154844E-002)); +#71251 = CARTESIAN_POINT('',(1.142397328578,1.551463154844E-002)); +#71252 = CARTESIAN_POINT('',(1.070997495542,1.551463154844E-002)); +#71253 = CARTESIAN_POINT('',(0.999597662506,1.551463154845E-002)); +#71254 = CARTESIAN_POINT('',(0.92819782947,1.551463154844E-002)); +#71255 = CARTESIAN_POINT('',(0.856797996433,1.551463154844E-002)); +#71256 = CARTESIAN_POINT('',(0.785398163397,1.551463154844E-002)); +#71257 = CARTESIAN_POINT('',(0.713998330361,1.551463154844E-002)); +#71258 = CARTESIAN_POINT('',(0.642598497325,1.551463154844E-002)); +#71259 = CARTESIAN_POINT('',(0.571198664289,1.551463154844E-002)); +#71260 = CARTESIAN_POINT('',(0.499798831253,1.551463154844E-002)); +#71261 = CARTESIAN_POINT('',(0.428398998217,1.551463154844E-002)); +#71262 = CARTESIAN_POINT('',(0.35699916518,1.551463154844E-002)); +#71263 = CARTESIAN_POINT('',(0.285599332144,1.551463154844E-002)); +#71264 = CARTESIAN_POINT('',(0.214199499108,1.551463154844E-002)); +#71265 = CARTESIAN_POINT('',(0.142799666072,1.551463154844E-002)); +#71266 = CARTESIAN_POINT('',(7.139983303578E-002,1.551463154844E-002)); +#71267 = CARTESIAN_POINT('',(2.379994434519E-002,1.551463154844E-002)); +#71268 = CARTESIAN_POINT('',(0.E+000,1.551463154844E-002)); +#71269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71270 = ORIENTED_EDGE('',*,*,#71271,.T.); +#71271 = EDGE_CURVE('',#71226,#71177,#71272,.T.); +#71272 = SURFACE_CURVE('',#71273,(#71277,#71284),.PCURVE_S1.); +#71273 = LINE('',#71274,#71275); +#71274 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); +#71275 = VECTOR('',#71276,1.); +#71276 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71277 = PCURVE('',#41295,#71278); +#71278 = DEFINITIONAL_REPRESENTATION('',(#71279),#71283); +#71279 = LINE('',#71280,#71281); +#71280 = CARTESIAN_POINT('',(0.316541744461,-0.2)); +#71281 = VECTOR('',#71282,1.); +#71282 = DIRECTION('',(0.E+000,-1.)); +#71283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71284 = PCURVE('',#71285,#71290); +#71285 = PLANE('',#71286); +#71286 = AXIS2_PLACEMENT_3D('',#71287,#71288,#71289); +#71287 = CARTESIAN_POINT('',(-3.798447109038,2.5E-002,2.78)); +#71288 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#71289 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#71290 = DEFINITIONAL_REPRESENTATION('',(#71291),#71295); +#71291 = LINE('',#71292,#71293); +#71292 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#71293 = VECTOR('',#71294,1.); +#71294 = DIRECTION('',(0.E+000,-1.)); +#71295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71296 = ADVANCED_FACE('',(#71297),#41882,.T.); +#71297 = FACE_BOUND('',#71298,.T.); +#71298 = EDGE_LOOP('',(#71299,#71300,#71301,#71347)); +#71299 = ORIENTED_EDGE('',*,*,#71176,.F.); +#71300 = ORIENTED_EDGE('',*,*,#41864,.F.); +#71301 = ORIENTED_EDGE('',*,*,#71302,.F.); +#71302 = EDGE_CURVE('',#71303,#41865,#71305,.T.); +#71303 = VERTEX_POINT('',#71304); +#71304 = CARTESIAN_POINT('',(-3.99,0.425,2.54911585164)); +#71305 = SURFACE_CURVE('',#71306,(#71311,#71340),.PCURVE_S1.); +#71306 = CIRCLE('',#71307,0.2); +#71307 = AXIS2_PLACEMENT_3D('',#71308,#71309,#71310); +#71308 = CARTESIAN_POINT('',(-3.836077234426,0.425,2.421413924332)); +#71309 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#71310 = DIRECTION('',(-0.769613827868,0.E+000,0.63850963654)); +#71311 = PCURVE('',#41882,#71312); +#71312 = DEFINITIONAL_REPRESENTATION('',(#71313),#71339); +#71313 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71314,#71315,#71316,#71317, + #71318,#71319,#71320,#71321,#71322,#71323,#71324,#71325,#71326, + #71327,#71328,#71329,#71330,#71331,#71332,#71333,#71334,#71335, + #71336,#71337,#71338),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -84999,142 +87988,142 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#68922 = CARTESIAN_POINT('',(1.570796326795,2.203939738417E-002)); -#68923 = CARTESIAN_POINT('',(1.54699638245,2.203939738417E-002)); -#68924 = CARTESIAN_POINT('',(1.499396493759,2.203939738417E-002)); -#68925 = CARTESIAN_POINT('',(1.427996660723,2.203939738417E-002)); -#68926 = CARTESIAN_POINT('',(1.356596827687,2.203939738417E-002)); -#68927 = CARTESIAN_POINT('',(1.285196994651,2.203939738417E-002)); -#68928 = CARTESIAN_POINT('',(1.213797161615,2.203939738417E-002)); -#68929 = CARTESIAN_POINT('',(1.142397328579,2.203939738417E-002)); -#68930 = CARTESIAN_POINT('',(1.070997495543,2.203939738417E-002)); -#68931 = CARTESIAN_POINT('',(0.999597662507,2.203939738417E-002)); -#68932 = CARTESIAN_POINT('',(0.928197829471,2.203939738417E-002)); -#68933 = CARTESIAN_POINT('',(0.856797996435,2.203939738417E-002)); -#68934 = CARTESIAN_POINT('',(0.785398163399,2.203939738417E-002)); -#68935 = CARTESIAN_POINT('',(0.713998330363,2.203939738417E-002)); -#68936 = CARTESIAN_POINT('',(0.642598497327,2.203939738417E-002)); -#68937 = CARTESIAN_POINT('',(0.571198664291,2.203939738417E-002)); -#68938 = CARTESIAN_POINT('',(0.499798831255,2.203939738417E-002)); -#68939 = CARTESIAN_POINT('',(0.428398998219,2.203939738417E-002)); -#68940 = CARTESIAN_POINT('',(0.356999165183,2.203939738417E-002)); -#68941 = CARTESIAN_POINT('',(0.285599332147,2.203939738417E-002)); -#68942 = CARTESIAN_POINT('',(0.21419949911,2.203939738417E-002)); -#68943 = CARTESIAN_POINT('',(0.142799666074,2.203939738417E-002)); -#68944 = CARTESIAN_POINT('',(7.139983303858E-002,2.203939738417E-002)); -#68945 = CARTESIAN_POINT('',(2.379994434665E-002,2.203939738417E-002)); -#68946 = CARTESIAN_POINT('',(0.E+000,2.203939738417E-002)); -#68947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#71314 = CARTESIAN_POINT('',(1.570796326795,2.203939738417E-002)); +#71315 = CARTESIAN_POINT('',(1.54699638245,2.203939738417E-002)); +#71316 = CARTESIAN_POINT('',(1.499396493759,2.203939738417E-002)); +#71317 = CARTESIAN_POINT('',(1.427996660723,2.203939738417E-002)); +#71318 = CARTESIAN_POINT('',(1.356596827687,2.203939738417E-002)); +#71319 = CARTESIAN_POINT('',(1.285196994651,2.203939738417E-002)); +#71320 = CARTESIAN_POINT('',(1.213797161615,2.203939738417E-002)); +#71321 = CARTESIAN_POINT('',(1.142397328579,2.203939738417E-002)); +#71322 = CARTESIAN_POINT('',(1.070997495543,2.203939738417E-002)); +#71323 = CARTESIAN_POINT('',(0.999597662507,2.203939738417E-002)); +#71324 = CARTESIAN_POINT('',(0.928197829471,2.203939738417E-002)); +#71325 = CARTESIAN_POINT('',(0.856797996435,2.203939738417E-002)); +#71326 = CARTESIAN_POINT('',(0.785398163399,2.203939738417E-002)); +#71327 = CARTESIAN_POINT('',(0.713998330363,2.203939738417E-002)); +#71328 = CARTESIAN_POINT('',(0.642598497327,2.203939738417E-002)); +#71329 = CARTESIAN_POINT('',(0.571198664291,2.203939738417E-002)); +#71330 = CARTESIAN_POINT('',(0.499798831255,2.203939738417E-002)); +#71331 = CARTESIAN_POINT('',(0.428398998219,2.203939738417E-002)); +#71332 = CARTESIAN_POINT('',(0.356999165183,2.203939738417E-002)); +#71333 = CARTESIAN_POINT('',(0.285599332147,2.203939738417E-002)); +#71334 = CARTESIAN_POINT('',(0.21419949911,2.203939738417E-002)); +#71335 = CARTESIAN_POINT('',(0.142799666074,2.203939738417E-002)); +#71336 = CARTESIAN_POINT('',(7.139983303858E-002,2.203939738417E-002)); +#71337 = CARTESIAN_POINT('',(2.379994434665E-002,2.203939738417E-002)); +#71338 = CARTESIAN_POINT('',(0.E+000,2.203939738417E-002)); +#71339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71340 = PCURVE('',#41371,#71341); +#71341 = DEFINITIONAL_REPRESENTATION('',(#71342),#71346); +#71342 = CIRCLE('',#71343,0.2); +#71343 = AXIS2_PLACEMENT_2D('',#71344,#71345); +#71344 = CARTESIAN_POINT('',(0.2,-0.4)); +#71345 = DIRECTION('',(-1.,0.E+000)); +#71346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71347 = ORIENTED_EDGE('',*,*,#71348,.T.); +#71348 = EDGE_CURVE('',#71303,#71177,#71349,.T.); +#71349 = SURFACE_CURVE('',#71350,(#71354,#71360),.PCURVE_S1.); +#71350 = LINE('',#71351,#71352); +#71351 = CARTESIAN_POINT('',(-3.99,0.425,2.54911585164)); +#71352 = VECTOR('',#71353,1.); +#71353 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); +#71354 = PCURVE('',#41882,#71355); +#71355 = DEFINITIONAL_REPRESENTATION('',(#71356),#71359); +#71356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71357,#71358),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#71357 = CARTESIAN_POINT('',(1.570796326795,2.203939738395E-002)); +#71358 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#71359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68948 = PCURVE('',#38979,#68949); -#68949 = DEFINITIONAL_REPRESENTATION('',(#68950),#68954); -#68950 = CIRCLE('',#68951,0.2); -#68951 = AXIS2_PLACEMENT_2D('',#68952,#68953); -#68952 = CARTESIAN_POINT('',(0.2,-0.4)); -#68953 = DIRECTION('',(-1.,0.E+000)); -#68954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#71360 = PCURVE('',#71285,#71361); +#71361 = DEFINITIONAL_REPRESENTATION('',(#71362),#71366); +#71362 = LINE('',#71363,#71364); +#71363 = CARTESIAN_POINT('',(0.3,-0.4)); +#71364 = VECTOR('',#71365,1.); +#71365 = DIRECTION('',(-1.,0.E+000)); +#71366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71367 = ADVANCED_FACE('',(#71368),#71285,.T.); +#71368 = FACE_BOUND('',#71369,.F.); +#71369 = EDGE_LOOP('',(#71370,#71371,#71372,#71394)); +#71370 = ORIENTED_EDGE('',*,*,#71348,.T.); +#71371 = ORIENTED_EDGE('',*,*,#71271,.F.); +#71372 = ORIENTED_EDGE('',*,*,#71373,.T.); +#71373 = EDGE_CURVE('',#71226,#71374,#71376,.T.); +#71374 = VERTEX_POINT('',#71375); +#71375 = CARTESIAN_POINT('',(-3.99,0.225,2.54911585164)); +#71376 = SURFACE_CURVE('',#71377,(#71381,#71388),.PCURVE_S1.); +#71377 = LINE('',#71378,#71379); +#71378 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); +#71379 = VECTOR('',#71380,1.); +#71380 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#71381 = PCURVE('',#71285,#71382); +#71382 = DEFINITIONAL_REPRESENTATION('',(#71383),#71387); +#71383 = LINE('',#71384,#71385); +#71384 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#71385 = VECTOR('',#71386,1.); +#71386 = DIRECTION('',(1.,0.E+000)); +#71387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71388 = PCURVE('',#41245,#71389); +#71389 = DEFINITIONAL_REPRESENTATION('',(#71390),#71393); +#71390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71391,#71392),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); +#71391 = CARTESIAN_POINT('',(1.570796326795,1.551463154866E-002)); +#71392 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71394 = ORIENTED_EDGE('',*,*,#71395,.T.); +#71395 = EDGE_CURVE('',#71374,#71303,#71396,.T.); +#71396 = SURFACE_CURVE('',#71397,(#71401,#71408),.PCURVE_S1.); +#71397 = LINE('',#71398,#71399); +#71398 = CARTESIAN_POINT('',(-3.99,0.225,2.54911585164)); +#71399 = VECTOR('',#71400,1.); +#71400 = DIRECTION('',(0.E+000,1.,0.E+000)); +#71401 = PCURVE('',#71285,#71402); +#71402 = DEFINITIONAL_REPRESENTATION('',(#71403),#71407); +#71403 = LINE('',#71404,#71405); +#71404 = CARTESIAN_POINT('',(0.3,-0.2)); +#71405 = VECTOR('',#71406,1.); +#71406 = DIRECTION('',(0.E+000,-1.)); +#71407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#68955 = ORIENTED_EDGE('',*,*,#68956,.T.); -#68956 = EDGE_CURVE('',#68911,#68785,#68957,.T.); -#68957 = SURFACE_CURVE('',#68958,(#68962,#68968),.PCURVE_S1.); -#68958 = LINE('',#68959,#68960); -#68959 = CARTESIAN_POINT('',(-3.99,0.425,2.54911585164)); -#68960 = VECTOR('',#68961,1.); -#68961 = DIRECTION('',(0.63850963654,0.E+000,0.769613827868)); -#68962 = PCURVE('',#39490,#68963); -#68963 = DEFINITIONAL_REPRESENTATION('',(#68964),#68967); -#68964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68965,#68966),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68965 = CARTESIAN_POINT('',(1.570796326795,2.203939738395E-002)); -#68966 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#68967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68968 = PCURVE('',#68893,#68969); -#68969 = DEFINITIONAL_REPRESENTATION('',(#68970),#68974); -#68970 = LINE('',#68971,#68972); -#68971 = CARTESIAN_POINT('',(0.3,-0.4)); -#68972 = VECTOR('',#68973,1.); -#68973 = DIRECTION('',(-1.,0.E+000)); -#68974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68975 = ADVANCED_FACE('',(#68976),#68893,.T.); -#68976 = FACE_BOUND('',#68977,.F.); -#68977 = EDGE_LOOP('',(#68978,#68979,#68980,#69002)); -#68978 = ORIENTED_EDGE('',*,*,#68956,.T.); -#68979 = ORIENTED_EDGE('',*,*,#68879,.F.); -#68980 = ORIENTED_EDGE('',*,*,#68981,.T.); -#68981 = EDGE_CURVE('',#68834,#68982,#68984,.T.); -#68982 = VERTEX_POINT('',#68983); -#68983 = CARTESIAN_POINT('',(-3.99,0.225,2.54911585164)); -#68984 = SURFACE_CURVE('',#68985,(#68989,#68996),.PCURVE_S1.); -#68985 = LINE('',#68986,#68987); -#68986 = CARTESIAN_POINT('',(-3.798447109038,0.225,2.78)); -#68987 = VECTOR('',#68988,1.); -#68988 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#68989 = PCURVE('',#68893,#68990); -#68990 = DEFINITIONAL_REPRESENTATION('',(#68991),#68995); -#68991 = LINE('',#68992,#68993); -#68992 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#68993 = VECTOR('',#68994,1.); -#68994 = DIRECTION('',(1.,0.E+000)); -#68995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#68996 = PCURVE('',#38853,#68997); -#68997 = DEFINITIONAL_REPRESENTATION('',(#68998),#69001); -#68998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#68999,#69000),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#68999 = CARTESIAN_POINT('',(1.570796326795,1.551463154866E-002)); -#69000 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69002 = ORIENTED_EDGE('',*,*,#69003,.T.); -#69003 = EDGE_CURVE('',#68982,#68911,#69004,.T.); -#69004 = SURFACE_CURVE('',#69005,(#69009,#69016),.PCURVE_S1.); -#69005 = LINE('',#69006,#69007); -#69006 = CARTESIAN_POINT('',(-3.99,0.225,2.54911585164)); -#69007 = VECTOR('',#69008,1.); -#69008 = DIRECTION('',(0.E+000,1.,0.E+000)); -#69009 = PCURVE('',#68893,#69010); -#69010 = DEFINITIONAL_REPRESENTATION('',(#69011),#69015); -#69011 = LINE('',#69012,#69013); -#69012 = CARTESIAN_POINT('',(0.3,-0.2)); -#69013 = VECTOR('',#69014,1.); -#69014 = DIRECTION('',(0.E+000,-1.)); -#69015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69016 = PCURVE('',#38979,#69017); -#69017 = DEFINITIONAL_REPRESENTATION('',(#69018),#69022); -#69018 = LINE('',#69019,#69020); -#69019 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#69020 = VECTOR('',#69021,1.); -#69021 = DIRECTION('',(0.E+000,-1.)); -#69022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69023 = ADVANCED_FACE('',(#69024),#38853,.T.); -#69024 = FACE_BOUND('',#69025,.T.); -#69025 = EDGE_LOOP('',(#69026,#69070,#69071,#69072)); -#69026 = ORIENTED_EDGE('',*,*,#69027,.F.); -#69027 = EDGE_CURVE('',#38838,#68982,#69028,.T.); -#69028 = SURFACE_CURVE('',#69029,(#69034,#69063),.PCURVE_S1.); -#69029 = CIRCLE('',#69030,0.2); -#69030 = AXIS2_PLACEMENT_3D('',#69031,#69032,#69033); -#69031 = CARTESIAN_POINT('',(-3.836077234426,0.225,2.421413924332)); -#69032 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); -#69033 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#69034 = PCURVE('',#38853,#69035); -#69035 = DEFINITIONAL_REPRESENTATION('',(#69036),#69062); -#69036 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69037,#69038,#69039,#69040, - #69041,#69042,#69043,#69044,#69045,#69046,#69047,#69048,#69049, - #69050,#69051,#69052,#69053,#69054,#69055,#69056,#69057,#69058, - #69059,#69060,#69061),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71408 = PCURVE('',#41371,#71409); +#71409 = DEFINITIONAL_REPRESENTATION('',(#71410),#71414); +#71410 = LINE('',#71411,#71412); +#71411 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#71412 = VECTOR('',#71413,1.); +#71413 = DIRECTION('',(0.E+000,-1.)); +#71414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71415 = ADVANCED_FACE('',(#71416),#41245,.T.); +#71416 = FACE_BOUND('',#71417,.T.); +#71417 = EDGE_LOOP('',(#71418,#71462,#71463,#71464)); +#71418 = ORIENTED_EDGE('',*,*,#71419,.F.); +#71419 = EDGE_CURVE('',#41230,#71374,#71420,.T.); +#71420 = SURFACE_CURVE('',#71421,(#71426,#71455),.PCURVE_S1.); +#71421 = CIRCLE('',#71422,0.2); +#71422 = AXIS2_PLACEMENT_3D('',#71423,#71424,#71425); +#71423 = CARTESIAN_POINT('',(-3.836077234426,0.225,2.421413924332)); +#71424 = DIRECTION('',(-0.63850963654,0.E+000,-0.769613827868)); +#71425 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#71426 = PCURVE('',#41245,#71427); +#71427 = DEFINITIONAL_REPRESENTATION('',(#71428),#71454); +#71428 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71429,#71430,#71431,#71432, + #71433,#71434,#71435,#71436,#71437,#71438,#71439,#71440,#71441, + #71442,#71443,#71444,#71445,#71446,#71447,#71448,#71449,#71450, + #71451,#71452,#71453),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85142,81 +88131,81 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69037 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#69038 = CARTESIAN_POINT('',(2.379994434617E-002,0.315514631548)); -#69039 = CARTESIAN_POINT('',(7.139983303767E-002,0.315514631548)); -#69040 = CARTESIAN_POINT('',(0.142799666073,0.315514631548)); -#69041 = CARTESIAN_POINT('',(0.21419949911,0.315514631548)); -#69042 = CARTESIAN_POINT('',(0.285599332146,0.315514631548)); -#69043 = CARTESIAN_POINT('',(0.356999165182,0.315514631548)); -#69044 = CARTESIAN_POINT('',(0.428398998218,0.315514631548)); -#69045 = CARTESIAN_POINT('',(0.499798831254,0.315514631548)); -#69046 = CARTESIAN_POINT('',(0.57119866429,0.315514631548)); -#69047 = CARTESIAN_POINT('',(0.642598497326,0.315514631548)); -#69048 = CARTESIAN_POINT('',(0.713998330362,0.315514631548)); -#69049 = CARTESIAN_POINT('',(0.785398163398,0.315514631548)); -#69050 = CARTESIAN_POINT('',(0.856797996434,0.315514631548)); -#69051 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); -#69052 = CARTESIAN_POINT('',(0.999597662507,0.315514631548)); -#69053 = CARTESIAN_POINT('',(1.070997495543,0.315514631548)); -#69054 = CARTESIAN_POINT('',(1.142397328579,0.315514631548)); -#69055 = CARTESIAN_POINT('',(1.213797161615,0.315514631548)); -#69056 = CARTESIAN_POINT('',(1.285196994651,0.315514631548)); -#69057 = CARTESIAN_POINT('',(1.356596827687,0.315514631548)); -#69058 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); -#69059 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); -#69060 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); -#69061 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69063 = PCURVE('',#38979,#69064); -#69064 = DEFINITIONAL_REPRESENTATION('',(#69065),#69069); -#69065 = CIRCLE('',#69066,0.2); -#69066 = AXIS2_PLACEMENT_2D('',#69067,#69068); -#69067 = CARTESIAN_POINT('',(0.2,-0.2)); -#69068 = DIRECTION('',(0.E+000,1.)); -#69069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69070 = ORIENTED_EDGE('',*,*,#38835,.F.); -#69071 = ORIENTED_EDGE('',*,*,#68833,.F.); -#69072 = ORIENTED_EDGE('',*,*,#68981,.T.); -#69073 = ADVANCED_FACE('',(#69074),#38979,.T.); -#69074 = FACE_BOUND('',#69075,.F.); -#69075 = EDGE_LOOP('',(#69076,#69077,#69078,#69079,#69080,#69081)); -#69076 = ORIENTED_EDGE('',*,*,#68910,.F.); -#69077 = ORIENTED_EDGE('',*,*,#69003,.F.); -#69078 = ORIENTED_EDGE('',*,*,#69027,.F.); -#69079 = ORIENTED_EDGE('',*,*,#38965,.T.); -#69080 = ORIENTED_EDGE('',*,*,#54095,.F.); -#69081 = ORIENTED_EDGE('',*,*,#39524,.F.); -#69082 = ADVANCED_FACE('',(#69083),#38471,.F.); -#69083 = FACE_BOUND('',#69084,.F.); -#69084 = EDGE_LOOP('',(#69085,#69086,#69087,#69088)); -#69085 = ORIENTED_EDGE('',*,*,#38450,.T.); -#69086 = ORIENTED_EDGE('',*,*,#47367,.F.); -#69087 = ORIENTED_EDGE('',*,*,#53294,.F.); -#69088 = ORIENTED_EDGE('',*,*,#54552,.T.); -#69089 = ADVANCED_FACE('',(#69090),#52896,.T.); -#69090 = FACE_BOUND('',#69091,.T.); -#69091 = EDGE_LOOP('',(#69092,#69138,#69139,#69140)); -#69092 = ORIENTED_EDGE('',*,*,#69093,.F.); -#69093 = EDGE_CURVE('',#53368,#69094,#69096,.T.); -#69094 = VERTEX_POINT('',#69095); -#69095 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.05)); -#69096 = SURFACE_CURVE('',#69097,(#69102,#69131),.PCURVE_S1.); -#69097 = CIRCLE('',#69098,0.3); -#69098 = AXIS2_PLACEMENT_3D('',#69099,#69100,#69101); -#69099 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.05)); -#69100 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#69101 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#69102 = PCURVE('',#52896,#69103); -#69103 = DEFINITIONAL_REPRESENTATION('',(#69104),#69130); -#69104 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69105,#69106,#69107,#69108, - #69109,#69110,#69111,#69112,#69113,#69114,#69115,#69116,#69117, - #69118,#69119,#69120,#69121,#69122,#69123,#69124,#69125,#69126, - #69127,#69128,#69129),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71429 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#71430 = CARTESIAN_POINT('',(2.379994434617E-002,0.315514631548)); +#71431 = CARTESIAN_POINT('',(7.139983303767E-002,0.315514631548)); +#71432 = CARTESIAN_POINT('',(0.142799666073,0.315514631548)); +#71433 = CARTESIAN_POINT('',(0.21419949911,0.315514631548)); +#71434 = CARTESIAN_POINT('',(0.285599332146,0.315514631548)); +#71435 = CARTESIAN_POINT('',(0.356999165182,0.315514631548)); +#71436 = CARTESIAN_POINT('',(0.428398998218,0.315514631548)); +#71437 = CARTESIAN_POINT('',(0.499798831254,0.315514631548)); +#71438 = CARTESIAN_POINT('',(0.57119866429,0.315514631548)); +#71439 = CARTESIAN_POINT('',(0.642598497326,0.315514631548)); +#71440 = CARTESIAN_POINT('',(0.713998330362,0.315514631548)); +#71441 = CARTESIAN_POINT('',(0.785398163398,0.315514631548)); +#71442 = CARTESIAN_POINT('',(0.856797996434,0.315514631548)); +#71443 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); +#71444 = CARTESIAN_POINT('',(0.999597662507,0.315514631548)); +#71445 = CARTESIAN_POINT('',(1.070997495543,0.315514631548)); +#71446 = CARTESIAN_POINT('',(1.142397328579,0.315514631548)); +#71447 = CARTESIAN_POINT('',(1.213797161615,0.315514631548)); +#71448 = CARTESIAN_POINT('',(1.285196994651,0.315514631548)); +#71449 = CARTESIAN_POINT('',(1.356596827687,0.315514631548)); +#71450 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); +#71451 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); +#71452 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); +#71453 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71455 = PCURVE('',#41371,#71456); +#71456 = DEFINITIONAL_REPRESENTATION('',(#71457),#71461); +#71457 = CIRCLE('',#71458,0.2); +#71458 = AXIS2_PLACEMENT_2D('',#71459,#71460); +#71459 = CARTESIAN_POINT('',(0.2,-0.2)); +#71460 = DIRECTION('',(0.E+000,1.)); +#71461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71462 = ORIENTED_EDGE('',*,*,#41227,.F.); +#71463 = ORIENTED_EDGE('',*,*,#71225,.F.); +#71464 = ORIENTED_EDGE('',*,*,#71373,.T.); +#71465 = ADVANCED_FACE('',(#71466),#41371,.T.); +#71466 = FACE_BOUND('',#71467,.F.); +#71467 = EDGE_LOOP('',(#71468,#71469,#71470,#71471,#71472,#71473)); +#71468 = ORIENTED_EDGE('',*,*,#71302,.F.); +#71469 = ORIENTED_EDGE('',*,*,#71395,.F.); +#71470 = ORIENTED_EDGE('',*,*,#71419,.F.); +#71471 = ORIENTED_EDGE('',*,*,#41357,.T.); +#71472 = ORIENTED_EDGE('',*,*,#56487,.F.); +#71473 = ORIENTED_EDGE('',*,*,#41916,.F.); +#71474 = ADVANCED_FACE('',(#71475),#40863,.F.); +#71475 = FACE_BOUND('',#71476,.F.); +#71476 = EDGE_LOOP('',(#71477,#71478,#71479,#71480)); +#71477 = ORIENTED_EDGE('',*,*,#40842,.T.); +#71478 = ORIENTED_EDGE('',*,*,#49759,.F.); +#71479 = ORIENTED_EDGE('',*,*,#55686,.F.); +#71480 = ORIENTED_EDGE('',*,*,#56944,.T.); +#71481 = ADVANCED_FACE('',(#71482),#55288,.T.); +#71482 = FACE_BOUND('',#71483,.T.); +#71483 = EDGE_LOOP('',(#71484,#71530,#71531,#71532)); +#71484 = ORIENTED_EDGE('',*,*,#71485,.F.); +#71485 = EDGE_CURVE('',#55760,#71486,#71488,.T.); +#71486 = VERTEX_POINT('',#71487); +#71487 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.05)); +#71488 = SURFACE_CURVE('',#71489,(#71494,#71523),.PCURVE_S1.); +#71489 = CIRCLE('',#71490,0.3); +#71490 = AXIS2_PLACEMENT_3D('',#71491,#71492,#71493); +#71491 = CARTESIAN_POINT('',(1.811240974769,0.957072930905,-2.05)); +#71492 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#71493 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#71494 = PCURVE('',#55288,#71495); +#71495 = DEFINITIONAL_REPRESENTATION('',(#71496),#71522); +#71496 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71497,#71498,#71499,#71500, + #71501,#71502,#71503,#71504,#71505,#71506,#71507,#71508,#71509, + #71510,#71511,#71512,#71513,#71514,#71515,#71516,#71517,#71518, + #71519,#71520,#71521),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85224,221 +88213,221 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69105 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#69106 = CARTESIAN_POINT('',(2.379994434523E-002,0.315514631548)); -#69107 = CARTESIAN_POINT('',(7.139983303585E-002,0.315514631548)); -#69108 = CARTESIAN_POINT('',(0.142799666072,0.315514631548)); -#69109 = CARTESIAN_POINT('',(0.214199499108,0.315514631548)); -#69110 = CARTESIAN_POINT('',(0.285599332144,0.315514631548)); -#69111 = CARTESIAN_POINT('',(0.35699916518,0.315514631548)); -#69112 = CARTESIAN_POINT('',(0.428398998217,0.315514631548)); -#69113 = CARTESIAN_POINT('',(0.499798831253,0.315514631548)); -#69114 = CARTESIAN_POINT('',(0.571198664289,0.315514631548)); -#69115 = CARTESIAN_POINT('',(0.642598497325,0.315514631548)); -#69116 = CARTESIAN_POINT('',(0.713998330361,0.315514631548)); -#69117 = CARTESIAN_POINT('',(0.785398163397,0.315514631548)); -#69118 = CARTESIAN_POINT('',(0.856797996433,0.315514631548)); -#69119 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); -#69120 = CARTESIAN_POINT('',(0.999597662506,0.315514631548)); -#69121 = CARTESIAN_POINT('',(1.070997495542,0.315514631548)); -#69122 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); -#69123 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); -#69124 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); -#69125 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); -#69126 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); -#69127 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); -#69128 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); -#69129 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69131 = PCURVE('',#52439,#69132); -#69132 = DEFINITIONAL_REPRESENTATION('',(#69133),#69137); -#69133 = CIRCLE('',#69134,0.3); -#69134 = AXIS2_PLACEMENT_2D('',#69135,#69136); -#69135 = CARTESIAN_POINT('',(0.3,-0.3)); -#69136 = DIRECTION('',(0.E+000,1.)); -#69137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69138 = ORIENTED_EDGE('',*,*,#53367,.F.); -#69139 = ORIENTED_EDGE('',*,*,#52879,.F.); -#69140 = ORIENTED_EDGE('',*,*,#69141,.T.); -#69141 = EDGE_CURVE('',#52880,#69094,#69142,.T.); -#69142 = SURFACE_CURVE('',#69143,(#69147,#69153),.PCURVE_S1.); -#69143 = LINE('',#69144,#69145); -#69144 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); -#69145 = VECTOR('',#69146,1.); -#69146 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); -#69147 = PCURVE('',#52896,#69148); -#69148 = DEFINITIONAL_REPRESENTATION('',(#69149),#69152); -#69149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69150,#69151),.UNSPECIFIED., +#71497 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#71498 = CARTESIAN_POINT('',(2.379994434523E-002,0.315514631548)); +#71499 = CARTESIAN_POINT('',(7.139983303585E-002,0.315514631548)); +#71500 = CARTESIAN_POINT('',(0.142799666072,0.315514631548)); +#71501 = CARTESIAN_POINT('',(0.214199499108,0.315514631548)); +#71502 = CARTESIAN_POINT('',(0.285599332144,0.315514631548)); +#71503 = CARTESIAN_POINT('',(0.35699916518,0.315514631548)); +#71504 = CARTESIAN_POINT('',(0.428398998217,0.315514631548)); +#71505 = CARTESIAN_POINT('',(0.499798831253,0.315514631548)); +#71506 = CARTESIAN_POINT('',(0.571198664289,0.315514631548)); +#71507 = CARTESIAN_POINT('',(0.642598497325,0.315514631548)); +#71508 = CARTESIAN_POINT('',(0.713998330361,0.315514631548)); +#71509 = CARTESIAN_POINT('',(0.785398163397,0.315514631548)); +#71510 = CARTESIAN_POINT('',(0.856797996433,0.315514631548)); +#71511 = CARTESIAN_POINT('',(0.92819782947,0.315514631548)); +#71512 = CARTESIAN_POINT('',(0.999597662506,0.315514631548)); +#71513 = CARTESIAN_POINT('',(1.070997495542,0.315514631548)); +#71514 = CARTESIAN_POINT('',(1.142397328578,0.315514631548)); +#71515 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); +#71516 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); +#71517 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); +#71518 = CARTESIAN_POINT('',(1.427996660723,0.315514631548)); +#71519 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); +#71520 = CARTESIAN_POINT('',(1.54699638245,0.315514631548)); +#71521 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71523 = PCURVE('',#54831,#71524); +#71524 = DEFINITIONAL_REPRESENTATION('',(#71525),#71529); +#71525 = CIRCLE('',#71526,0.3); +#71526 = AXIS2_PLACEMENT_2D('',#71527,#71528); +#71527 = CARTESIAN_POINT('',(0.3,-0.3)); +#71528 = DIRECTION('',(0.E+000,1.)); +#71529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71530 = ORIENTED_EDGE('',*,*,#55759,.F.); +#71531 = ORIENTED_EDGE('',*,*,#55271,.F.); +#71532 = ORIENTED_EDGE('',*,*,#71533,.T.); +#71533 = EDGE_CURVE('',#55272,#71486,#71534,.T.); +#71534 = SURFACE_CURVE('',#71535,(#71539,#71545),.PCURVE_S1.); +#71535 = LINE('',#71536,#71537); +#71536 = CARTESIAN_POINT('',(1.737568292387,0.539254386713,-2.05)); +#71537 = VECTOR('',#71538,1.); +#71538 = DIRECTION('',(-0.573576436351,0.819152044289,0.E+000)); +#71539 = PCURVE('',#55288,#71540); +#71540 = DEFINITIONAL_REPRESENTATION('',(#71541),#71544); +#71541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71542,#71543),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#69150 = CARTESIAN_POINT('',(1.570796326795,1.551463154862E-002)); -#69151 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69153 = PCURVE('',#52817,#69154); -#69154 = DEFINITIONAL_REPRESENTATION('',(#69155),#69159); -#69155 = LINE('',#69156,#69157); -#69156 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#69157 = VECTOR('',#69158,1.); -#69158 = DIRECTION('',(1.,0.E+000)); -#69159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69160 = ADVANCED_FACE('',(#69161),#52439,.T.); -#69161 = FACE_BOUND('',#69162,.F.); -#69162 = EDGE_LOOP('',(#69163,#69164,#69185,#69186,#69187,#69207)); -#69163 = ORIENTED_EDGE('',*,*,#52758,.F.); -#69164 = ORIENTED_EDGE('',*,*,#69165,.F.); -#69165 = EDGE_CURVE('',#69094,#52759,#69166,.T.); -#69166 = SURFACE_CURVE('',#69167,(#69171,#69178),.PCURVE_S1.); -#69167 = LINE('',#69168,#69169); -#69168 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.05)); -#69169 = VECTOR('',#69170,1.); -#69170 = DIRECTION('',(0.E+000,0.E+000,1.)); -#69171 = PCURVE('',#52439,#69172); -#69172 = DEFINITIONAL_REPRESENTATION('',(#69173),#69177); -#69173 = LINE('',#69174,#69175); -#69174 = CARTESIAN_POINT('',(0.E+000,-0.3)); -#69175 = VECTOR('',#69176,1.); -#69176 = DIRECTION('',(0.E+000,-1.)); -#69177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69178 = PCURVE('',#52817,#69179); -#69179 = DEFINITIONAL_REPRESENTATION('',(#69180),#69184); -#69180 = LINE('',#69181,#69182); -#69181 = CARTESIAN_POINT('',(0.3,-0.3)); -#69182 = VECTOR('',#69183,1.); -#69183 = DIRECTION('',(0.E+000,-1.)); -#69184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69185 = ORIENTED_EDGE('',*,*,#69093,.F.); -#69186 = ORIENTED_EDGE('',*,*,#53593,.T.); -#69187 = ORIENTED_EDGE('',*,*,#69188,.T.); -#69188 = EDGE_CURVE('',#53567,#52424,#69189,.T.); -#69189 = SURFACE_CURVE('',#69190,(#69194,#69201),.PCURVE_S1.); -#69190 = LINE('',#69191,#69192); -#69191 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-2.35)); -#69192 = VECTOR('',#69193,1.); -#69193 = DIRECTION('',(0.E+000,0.E+000,1.)); -#69194 = PCURVE('',#52439,#69195); -#69195 = DEFINITIONAL_REPRESENTATION('',(#69196),#69200); -#69196 = LINE('',#69197,#69198); -#69197 = CARTESIAN_POINT('',(0.704056832298,0.E+000)); -#69198 = VECTOR('',#69199,1.); -#69199 = DIRECTION('',(0.E+000,-1.)); -#69200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69201 = PCURVE('',#49162,#69202); -#69202 = DEFINITIONAL_REPRESENTATION('',(#69203),#69206); -#69203 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69204,#69205),.UNSPECIFIED., +#71542 = CARTESIAN_POINT('',(1.570796326795,1.551463154862E-002)); +#71543 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71545 = PCURVE('',#55209,#71546); +#71546 = DEFINITIONAL_REPRESENTATION('',(#71547),#71551); +#71547 = LINE('',#71548,#71549); +#71548 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#71549 = VECTOR('',#71550,1.); +#71550 = DIRECTION('',(1.,0.E+000)); +#71551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71552 = ADVANCED_FACE('',(#71553),#54831,.T.); +#71553 = FACE_BOUND('',#71554,.F.); +#71554 = EDGE_LOOP('',(#71555,#71556,#71577,#71578,#71579,#71599)); +#71555 = ORIENTED_EDGE('',*,*,#55150,.F.); +#71556 = ORIENTED_EDGE('',*,*,#71557,.F.); +#71557 = EDGE_CURVE('',#71486,#55151,#71558,.T.); +#71558 = SURFACE_CURVE('',#71559,(#71563,#71570),.PCURVE_S1.); +#71559 = LINE('',#71560,#71561); +#71560 = CARTESIAN_POINT('',(1.565495361482,0.785,-2.05)); +#71561 = VECTOR('',#71562,1.); +#71562 = DIRECTION('',(0.E+000,0.E+000,1.)); +#71563 = PCURVE('',#54831,#71564); +#71564 = DEFINITIONAL_REPRESENTATION('',(#71565),#71569); +#71565 = LINE('',#71566,#71567); +#71566 = CARTESIAN_POINT('',(0.E+000,-0.3)); +#71567 = VECTOR('',#71568,1.); +#71568 = DIRECTION('',(0.E+000,-1.)); +#71569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71570 = PCURVE('',#55209,#71571); +#71571 = DEFINITIONAL_REPRESENTATION('',(#71572),#71576); +#71572 = LINE('',#71573,#71574); +#71573 = CARTESIAN_POINT('',(0.3,-0.3)); +#71574 = VECTOR('',#71575,1.); +#71575 = DIRECTION('',(0.E+000,-1.)); +#71576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71577 = ORIENTED_EDGE('',*,*,#71485,.F.); +#71578 = ORIENTED_EDGE('',*,*,#55985,.T.); +#71579 = ORIENTED_EDGE('',*,*,#71580,.T.); +#71580 = EDGE_CURVE('',#55959,#54816,#71581,.T.); +#71581 = SURFACE_CURVE('',#71582,(#71586,#71593),.PCURVE_S1.); +#71582 = LINE('',#71583,#71584); +#71583 = CARTESIAN_POINT('',(2.142224954954,1.188830408858,-2.35)); +#71584 = VECTOR('',#71585,1.); +#71585 = DIRECTION('',(0.E+000,0.E+000,1.)); +#71586 = PCURVE('',#54831,#71587); +#71587 = DEFINITIONAL_REPRESENTATION('',(#71588),#71592); +#71588 = LINE('',#71589,#71590); +#71589 = CARTESIAN_POINT('',(0.704056832298,0.E+000)); +#71590 = VECTOR('',#71591,1.); +#71591 = DIRECTION('',(0.E+000,-1.)); +#71592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71593 = PCURVE('',#51554,#71594); +#71594 = DEFINITIONAL_REPRESENTATION('',(#71595),#71598); +#71595 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71596,#71597),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.7),.PIECEWISE_BEZIER_KNOTS.); -#69204 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); -#69205 = CARTESIAN_POINT('',(0.959931088598,-0.7)); -#69206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69207 = ORIENTED_EDGE('',*,*,#52423,.F.); -#69208 = ADVANCED_FACE('',(#69209),#52817,.T.); -#69209 = FACE_BOUND('',#69210,.F.); -#69210 = EDGE_LOOP('',(#69211,#69212,#69213,#69214)); -#69211 = ORIENTED_EDGE('',*,*,#52804,.T.); -#69212 = ORIENTED_EDGE('',*,*,#52930,.F.); -#69213 = ORIENTED_EDGE('',*,*,#69141,.T.); -#69214 = ORIENTED_EDGE('',*,*,#69165,.T.); -#69215 = ADVANCED_FACE('',(#69216),#49162,.T.); -#69216 = FACE_BOUND('',#69217,.T.); -#69217 = EDGE_LOOP('',(#69218,#69219,#69220,#69221)); -#69218 = ORIENTED_EDGE('',*,*,#53566,.F.); -#69219 = ORIENTED_EDGE('',*,*,#69188,.T.); -#69220 = ORIENTED_EDGE('',*,*,#52451,.T.); -#69221 = ORIENTED_EDGE('',*,*,#49146,.F.); -#69222 = ADVANCED_FACE('',(#69223),#38585,.F.); -#69223 = FACE_BOUND('',#69224,.F.); -#69224 = EDGE_LOOP('',(#69225,#69226,#69227,#69228)); -#69225 = ORIENTED_EDGE('',*,*,#38564,.T.); -#69226 = ORIENTED_EDGE('',*,*,#39759,.F.); -#69227 = ORIENTED_EDGE('',*,*,#53415,.F.); -#69228 = ORIENTED_EDGE('',*,*,#47458,.T.); -#69229 = ADVANCED_FACE('',(#69230),#47574,.F.); -#69230 = FACE_BOUND('',#69231,.F.); -#69231 = EDGE_LOOP('',(#69232,#69233,#69234,#69255)); -#69232 = ORIENTED_EDGE('',*,*,#52473,.T.); -#69233 = ORIENTED_EDGE('',*,*,#49100,.T.); -#69234 = ORIENTED_EDGE('',*,*,#69235,.T.); -#69235 = EDGE_CURVE('',#49078,#47559,#69236,.T.); -#69236 = SURFACE_CURVE('',#69237,(#69241,#69248),.PCURVE_S1.); -#69237 = LINE('',#69238,#69239); -#69238 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); -#69239 = VECTOR('',#69240,1.); -#69240 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#69241 = PCURVE('',#47574,#69242); -#69242 = DEFINITIONAL_REPRESENTATION('',(#69243),#69247); -#69243 = LINE('',#69244,#69245); -#69244 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#69245 = VECTOR('',#69246,1.); -#69246 = DIRECTION('',(0.E+000,-1.)); -#69247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69248 = PCURVE('',#47602,#69249); -#69249 = DEFINITIONAL_REPRESENTATION('',(#69250),#69254); -#69250 = LINE('',#69251,#69252); -#69251 = CARTESIAN_POINT('',(1.16,0.E+000)); -#69252 = VECTOR('',#69253,1.); -#69253 = DIRECTION('',(0.E+000,-1.)); -#69254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69255 = ORIENTED_EDGE('',*,*,#47558,.F.); -#69256 = ADVANCED_FACE('',(#69257),#47602,.F.); -#69257 = FACE_BOUND('',#69258,.F.); -#69258 = EDGE_LOOP('',(#69259,#69260,#69261,#69262)); -#69259 = ORIENTED_EDGE('',*,*,#49077,.F.); -#69260 = ORIENTED_EDGE('',*,*,#51730,.T.); -#69261 = ORIENTED_EDGE('',*,*,#47586,.T.); -#69262 = ORIENTED_EDGE('',*,*,#69235,.F.); -#69263 = ADVANCED_FACE('',(#69264),#49230,.T.); -#69264 = FACE_BOUND('',#69265,.F.); -#69265 = EDGE_LOOP('',(#69266,#69319,#69340,#69341,#69364,#69415)); -#69266 = ORIENTED_EDGE('',*,*,#69267,.F.); -#69267 = EDGE_CURVE('',#69268,#69270,#69272,.T.); -#69268 = VERTEX_POINT('',#69269); -#69269 = CARTESIAN_POINT('',(-3.2,1.313674285394,2.420762596622)); -#69270 = VERTEX_POINT('',#69271); -#69271 = CARTESIAN_POINT('',(-3.,1.47,2.545511428091)); -#69272 = SURFACE_CURVE('',#69273,(#69278,#69285),.PCURVE_S1.); -#69273 = CIRCLE('',#69274,0.2); -#69274 = AXIS2_PLACEMENT_3D('',#69275,#69276,#69277); -#69275 = CARTESIAN_POINT('',(-3.,1.313674285394,2.420762596622)); -#69276 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69277 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69278 = PCURVE('',#49230,#69279); -#69279 = DEFINITIONAL_REPRESENTATION('',(#69280),#69284); -#69280 = CIRCLE('',#69281,0.2); -#69281 = AXIS2_PLACEMENT_2D('',#69282,#69283); -#69282 = CARTESIAN_POINT('',(0.2,6.2)); -#69283 = DIRECTION('',(0.E+000,1.)); -#69284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69285 = PCURVE('',#69286,#69291); -#69286 = CYLINDRICAL_SURFACE('',#69287,0.2); -#69287 = AXIS2_PLACEMENT_3D('',#69288,#69289,#69290); -#69288 = CARTESIAN_POINT('',(-3.,1.116873877409,2.667377847849)); -#69289 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69290 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69291 = DEFINITIONAL_REPRESENTATION('',(#69292),#69318); -#69292 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69293,#69294,#69295,#69296, - #69297,#69298,#69299,#69300,#69301,#69302,#69303,#69304,#69305, - #69306,#69307,#69308,#69309,#69310,#69311,#69312,#69313,#69314, - #69315,#69316,#69317),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71596 = CARTESIAN_POINT('',(0.959931088598,0.E+000)); +#71597 = CARTESIAN_POINT('',(0.959931088598,-0.7)); +#71598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71599 = ORIENTED_EDGE('',*,*,#54815,.F.); +#71600 = ADVANCED_FACE('',(#71601),#55209,.T.); +#71601 = FACE_BOUND('',#71602,.F.); +#71602 = EDGE_LOOP('',(#71603,#71604,#71605,#71606)); +#71603 = ORIENTED_EDGE('',*,*,#55196,.T.); +#71604 = ORIENTED_EDGE('',*,*,#55322,.F.); +#71605 = ORIENTED_EDGE('',*,*,#71533,.T.); +#71606 = ORIENTED_EDGE('',*,*,#71557,.T.); +#71607 = ADVANCED_FACE('',(#71608),#51554,.T.); +#71608 = FACE_BOUND('',#71609,.T.); +#71609 = EDGE_LOOP('',(#71610,#71611,#71612,#71613)); +#71610 = ORIENTED_EDGE('',*,*,#55958,.F.); +#71611 = ORIENTED_EDGE('',*,*,#71580,.T.); +#71612 = ORIENTED_EDGE('',*,*,#54843,.T.); +#71613 = ORIENTED_EDGE('',*,*,#51538,.F.); +#71614 = ADVANCED_FACE('',(#71615),#40977,.F.); +#71615 = FACE_BOUND('',#71616,.F.); +#71616 = EDGE_LOOP('',(#71617,#71618,#71619,#71620)); +#71617 = ORIENTED_EDGE('',*,*,#40956,.T.); +#71618 = ORIENTED_EDGE('',*,*,#42151,.F.); +#71619 = ORIENTED_EDGE('',*,*,#55807,.F.); +#71620 = ORIENTED_EDGE('',*,*,#49850,.T.); +#71621 = ADVANCED_FACE('',(#71622),#49966,.F.); +#71622 = FACE_BOUND('',#71623,.F.); +#71623 = EDGE_LOOP('',(#71624,#71625,#71626,#71647)); +#71624 = ORIENTED_EDGE('',*,*,#54865,.T.); +#71625 = ORIENTED_EDGE('',*,*,#51492,.T.); +#71626 = ORIENTED_EDGE('',*,*,#71627,.T.); +#71627 = EDGE_CURVE('',#51470,#49951,#71628,.T.); +#71628 = SURFACE_CURVE('',#71629,(#71633,#71640),.PCURVE_S1.); +#71629 = LINE('',#71630,#71631); +#71630 = CARTESIAN_POINT('',(2.37,1.225,-1.35)); +#71631 = VECTOR('',#71632,1.); +#71632 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#71633 = PCURVE('',#49966,#71634); +#71634 = DEFINITIONAL_REPRESENTATION('',(#71635),#71639); +#71635 = LINE('',#71636,#71637); +#71636 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#71637 = VECTOR('',#71638,1.); +#71638 = DIRECTION('',(0.E+000,-1.)); +#71639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71640 = PCURVE('',#49994,#71641); +#71641 = DEFINITIONAL_REPRESENTATION('',(#71642),#71646); +#71642 = LINE('',#71643,#71644); +#71643 = CARTESIAN_POINT('',(1.16,0.E+000)); +#71644 = VECTOR('',#71645,1.); +#71645 = DIRECTION('',(0.E+000,-1.)); +#71646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71647 = ORIENTED_EDGE('',*,*,#49950,.F.); +#71648 = ADVANCED_FACE('',(#71649),#49994,.F.); +#71649 = FACE_BOUND('',#71650,.F.); +#71650 = EDGE_LOOP('',(#71651,#71652,#71653,#71654)); +#71651 = ORIENTED_EDGE('',*,*,#51469,.F.); +#71652 = ORIENTED_EDGE('',*,*,#54122,.T.); +#71653 = ORIENTED_EDGE('',*,*,#49978,.T.); +#71654 = ORIENTED_EDGE('',*,*,#71627,.F.); +#71655 = ADVANCED_FACE('',(#71656),#51622,.T.); +#71656 = FACE_BOUND('',#71657,.F.); +#71657 = EDGE_LOOP('',(#71658,#71711,#71732,#71733,#71756,#71807)); +#71658 = ORIENTED_EDGE('',*,*,#71659,.F.); +#71659 = EDGE_CURVE('',#71660,#71662,#71664,.T.); +#71660 = VERTEX_POINT('',#71661); +#71661 = CARTESIAN_POINT('',(-3.2,1.313674285394,2.420762596622)); +#71662 = VERTEX_POINT('',#71663); +#71663 = CARTESIAN_POINT('',(-3.,1.47,2.545511428091)); +#71664 = SURFACE_CURVE('',#71665,(#71670,#71677),.PCURVE_S1.); +#71665 = CIRCLE('',#71666,0.2); +#71666 = AXIS2_PLACEMENT_3D('',#71667,#71668,#71669); +#71667 = CARTESIAN_POINT('',(-3.,1.313674285394,2.420762596622)); +#71668 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71669 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#71670 = PCURVE('',#51622,#71671); +#71671 = DEFINITIONAL_REPRESENTATION('',(#71672),#71676); +#71672 = CIRCLE('',#71673,0.2); +#71673 = AXIS2_PLACEMENT_2D('',#71674,#71675); +#71674 = CARTESIAN_POINT('',(0.2,6.2)); +#71675 = DIRECTION('',(0.E+000,1.)); +#71676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71677 = PCURVE('',#71678,#71683); +#71678 = CYLINDRICAL_SURFACE('',#71679,0.2); +#71679 = AXIS2_PLACEMENT_3D('',#71680,#71681,#71682); +#71680 = CARTESIAN_POINT('',(-3.,1.116873877409,2.667377847849)); +#71681 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71682 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#71683 = DEFINITIONAL_REPRESENTATION('',(#71684),#71710); +#71684 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71685,#71686,#71687,#71688, + #71689,#71690,#71691,#71692,#71693,#71694,#71695,#71696,#71697, + #71698,#71699,#71700,#71701,#71702,#71703,#71704,#71705,#71706, + #71707,#71708,#71709),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85446,117 +88435,117 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69293 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#69294 = CARTESIAN_POINT('',(2.37999443443E-002,0.315514631548)); -#69295 = CARTESIAN_POINT('',(7.139983303405E-002,0.315514631548)); -#69296 = CARTESIAN_POINT('',(0.142799666071,0.315514631548)); -#69297 = CARTESIAN_POINT('',(0.214199499107,0.315514631548)); -#69298 = CARTESIAN_POINT('',(0.285599332143,0.315514631548)); -#69299 = CARTESIAN_POINT('',(0.356999165179,0.315514631548)); -#69300 = CARTESIAN_POINT('',(0.428398998215,0.315514631548)); -#69301 = CARTESIAN_POINT('',(0.499798831251,0.315514631548)); -#69302 = CARTESIAN_POINT('',(0.571198664288,0.315514631548)); -#69303 = CARTESIAN_POINT('',(0.642598497324,0.315514631548)); -#69304 = CARTESIAN_POINT('',(0.71399833036,0.315514631548)); -#69305 = CARTESIAN_POINT('',(0.785398163396,0.315514631548)); -#69306 = CARTESIAN_POINT('',(0.856797996432,0.315514631548)); -#69307 = CARTESIAN_POINT('',(0.928197829469,0.315514631548)); -#69308 = CARTESIAN_POINT('',(0.999597662505,0.315514631548)); -#69309 = CARTESIAN_POINT('',(1.070997495541,0.315514631548)); -#69310 = CARTESIAN_POINT('',(1.142397328577,0.315514631548)); -#69311 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); -#69312 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); -#69313 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); -#69314 = CARTESIAN_POINT('',(1.427996660722,0.315514631548)); -#69315 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); -#69316 = CARTESIAN_POINT('',(1.546996382449,0.315514631548)); -#69317 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69319 = ORIENTED_EDGE('',*,*,#69320,.T.); -#69320 = EDGE_CURVE('',#69268,#38395,#69321,.T.); -#69321 = SURFACE_CURVE('',#69322,(#69326,#69333),.PCURVE_S1.); -#69322 = LINE('',#69323,#69324); -#69323 = CARTESIAN_POINT('',(-3.2,1.313674285394,2.420762596622)); -#69324 = VECTOR('',#69325,1.); -#69325 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); -#69326 = PCURVE('',#49230,#69327); -#69327 = DEFINITIONAL_REPRESENTATION('',(#69328),#69332); -#69328 = LINE('',#69329,#69330); -#69329 = CARTESIAN_POINT('',(0.2,6.4)); -#69330 = VECTOR('',#69331,1.); -#69331 = DIRECTION('',(1.,0.E+000)); -#69332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69333 = PCURVE('',#38438,#69334); -#69334 = DEFINITIONAL_REPRESENTATION('',(#69335),#69339); -#69335 = LINE('',#69336,#69337); -#69336 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); -#69337 = VECTOR('',#69338,1.); -#69338 = DIRECTION('',(-0.623744157346,-0.78162857303)); -#69339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69340 = ORIENTED_EDGE('',*,*,#49216,.F.); -#69341 = ORIENTED_EDGE('',*,*,#69342,.F.); -#69342 = EDGE_CURVE('',#69343,#38597,#69345,.T.); -#69343 = VERTEX_POINT('',#69344); -#69344 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); -#69345 = SURFACE_CURVE('',#69346,(#69350,#69357),.PCURVE_S1.); -#69346 = LINE('',#69347,#69348); -#69347 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); -#69348 = VECTOR('',#69349,1.); -#69349 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); -#69350 = PCURVE('',#49230,#69351); -#69351 = DEFINITIONAL_REPRESENTATION('',(#69352),#69356); -#69352 = LINE('',#69353,#69354); -#69353 = CARTESIAN_POINT('',(0.2,0.E+000)); -#69354 = VECTOR('',#69355,1.); -#69355 = DIRECTION('',(1.,0.E+000)); -#69356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69357 = PCURVE('',#38612,#69358); -#69358 = DEFINITIONAL_REPRESENTATION('',(#69359),#69363); -#69359 = LINE('',#69360,#69361); -#69360 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); -#69361 = VECTOR('',#69362,1.); -#69362 = DIRECTION('',(-0.623744157346,-0.78162857303)); -#69363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69364 = ORIENTED_EDGE('',*,*,#69365,.F.); -#69365 = EDGE_CURVE('',#69366,#69343,#69368,.T.); -#69366 = VERTEX_POINT('',#69367); -#69367 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); -#69368 = SURFACE_CURVE('',#69369,(#69374,#69381),.PCURVE_S1.); -#69369 = CIRCLE('',#69370,0.2); -#69370 = AXIS2_PLACEMENT_3D('',#69371,#69372,#69373); -#69371 = CARTESIAN_POINT('',(3.,1.313674285394,2.420762596622)); -#69372 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69373 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69374 = PCURVE('',#49230,#69375); -#69375 = DEFINITIONAL_REPRESENTATION('',(#69376),#69380); -#69376 = CIRCLE('',#69377,0.2); -#69377 = AXIS2_PLACEMENT_2D('',#69378,#69379); -#69378 = CARTESIAN_POINT('',(0.2,0.2)); -#69379 = DIRECTION('',(-1.,0.E+000)); -#69380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69381 = PCURVE('',#69382,#69387); -#69382 = CYLINDRICAL_SURFACE('',#69383,0.2); -#69383 = AXIS2_PLACEMENT_3D('',#69384,#69385,#69386); -#69384 = CARTESIAN_POINT('',(3.,1.327421230744,2.403535973894)); -#69385 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69386 = DIRECTION('',(1.,0.E+000,0.E+000)); -#69387 = DEFINITIONAL_REPRESENTATION('',(#69388),#69414); -#69388 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69389,#69390,#69391,#69392, - #69393,#69394,#69395,#69396,#69397,#69398,#69399,#69400,#69401, - #69402,#69403,#69404,#69405,#69406,#69407,#69408,#69409,#69410, - #69411,#69412,#69413),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71685 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#71686 = CARTESIAN_POINT('',(2.37999443443E-002,0.315514631548)); +#71687 = CARTESIAN_POINT('',(7.139983303405E-002,0.315514631548)); +#71688 = CARTESIAN_POINT('',(0.142799666071,0.315514631548)); +#71689 = CARTESIAN_POINT('',(0.214199499107,0.315514631548)); +#71690 = CARTESIAN_POINT('',(0.285599332143,0.315514631548)); +#71691 = CARTESIAN_POINT('',(0.356999165179,0.315514631548)); +#71692 = CARTESIAN_POINT('',(0.428398998215,0.315514631548)); +#71693 = CARTESIAN_POINT('',(0.499798831251,0.315514631548)); +#71694 = CARTESIAN_POINT('',(0.571198664288,0.315514631548)); +#71695 = CARTESIAN_POINT('',(0.642598497324,0.315514631548)); +#71696 = CARTESIAN_POINT('',(0.71399833036,0.315514631548)); +#71697 = CARTESIAN_POINT('',(0.785398163396,0.315514631548)); +#71698 = CARTESIAN_POINT('',(0.856797996432,0.315514631548)); +#71699 = CARTESIAN_POINT('',(0.928197829469,0.315514631548)); +#71700 = CARTESIAN_POINT('',(0.999597662505,0.315514631548)); +#71701 = CARTESIAN_POINT('',(1.070997495541,0.315514631548)); +#71702 = CARTESIAN_POINT('',(1.142397328577,0.315514631548)); +#71703 = CARTESIAN_POINT('',(1.213797161614,0.315514631548)); +#71704 = CARTESIAN_POINT('',(1.28519699465,0.315514631548)); +#71705 = CARTESIAN_POINT('',(1.356596827686,0.315514631548)); +#71706 = CARTESIAN_POINT('',(1.427996660722,0.315514631548)); +#71707 = CARTESIAN_POINT('',(1.499396493759,0.315514631548)); +#71708 = CARTESIAN_POINT('',(1.546996382449,0.315514631548)); +#71709 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71711 = ORIENTED_EDGE('',*,*,#71712,.T.); +#71712 = EDGE_CURVE('',#71660,#40787,#71713,.T.); +#71713 = SURFACE_CURVE('',#71714,(#71718,#71725),.PCURVE_S1.); +#71714 = LINE('',#71715,#71716); +#71715 = CARTESIAN_POINT('',(-3.2,1.313674285394,2.420762596622)); +#71716 = VECTOR('',#71717,1.); +#71717 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); +#71718 = PCURVE('',#51622,#71719); +#71719 = DEFINITIONAL_REPRESENTATION('',(#71720),#71724); +#71720 = LINE('',#71721,#71722); +#71721 = CARTESIAN_POINT('',(0.2,6.4)); +#71722 = VECTOR('',#71723,1.); +#71723 = DIRECTION('',(1.,0.E+000)); +#71724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71725 = PCURVE('',#40830,#71726); +#71726 = DEFINITIONAL_REPRESENTATION('',(#71727),#71731); +#71727 = LINE('',#71728,#71729); +#71728 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); +#71729 = VECTOR('',#71730,1.); +#71730 = DIRECTION('',(-0.623744157346,-0.78162857303)); +#71731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71732 = ORIENTED_EDGE('',*,*,#51608,.F.); +#71733 = ORIENTED_EDGE('',*,*,#71734,.F.); +#71734 = EDGE_CURVE('',#71735,#40989,#71737,.T.); +#71735 = VERTEX_POINT('',#71736); +#71736 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); +#71737 = SURFACE_CURVE('',#71738,(#71742,#71749),.PCURVE_S1.); +#71738 = LINE('',#71739,#71740); +#71739 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); +#71740 = VECTOR('',#71741,1.); +#71741 = DIRECTION('',(0.E+000,-0.78162857303,-0.623744157346)); +#71742 = PCURVE('',#51622,#71743); +#71743 = DEFINITIONAL_REPRESENTATION('',(#71744),#71748); +#71744 = LINE('',#71745,#71746); +#71745 = CARTESIAN_POINT('',(0.2,0.E+000)); +#71746 = VECTOR('',#71747,1.); +#71747 = DIRECTION('',(1.,0.E+000)); +#71748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71749 = PCURVE('',#41004,#71750); +#71750 = DEFINITIONAL_REPRESENTATION('',(#71751),#71755); +#71751 = LINE('',#71752,#71753); +#71752 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); +#71753 = VECTOR('',#71754,1.); +#71754 = DIRECTION('',(-0.623744157346,-0.78162857303)); +#71755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71756 = ORIENTED_EDGE('',*,*,#71757,.F.); +#71757 = EDGE_CURVE('',#71758,#71735,#71760,.T.); +#71758 = VERTEX_POINT('',#71759); +#71759 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); +#71760 = SURFACE_CURVE('',#71761,(#71766,#71773),.PCURVE_S1.); +#71761 = CIRCLE('',#71762,0.2); +#71762 = AXIS2_PLACEMENT_3D('',#71763,#71764,#71765); +#71763 = CARTESIAN_POINT('',(3.,1.313674285394,2.420762596622)); +#71764 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71765 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#71766 = PCURVE('',#51622,#71767); +#71767 = DEFINITIONAL_REPRESENTATION('',(#71768),#71772); +#71768 = CIRCLE('',#71769,0.2); +#71769 = AXIS2_PLACEMENT_2D('',#71770,#71771); +#71770 = CARTESIAN_POINT('',(0.2,0.2)); +#71771 = DIRECTION('',(-1.,0.E+000)); +#71772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71773 = PCURVE('',#71774,#71779); +#71774 = CYLINDRICAL_SURFACE('',#71775,0.2); +#71775 = AXIS2_PLACEMENT_3D('',#71776,#71777,#71778); +#71776 = CARTESIAN_POINT('',(3.,1.327421230744,2.403535973894)); +#71777 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#71778 = DIRECTION('',(1.,0.E+000,0.E+000)); +#71779 = DEFINITIONAL_REPRESENTATION('',(#71780),#71806); +#71780 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71781,#71782,#71783,#71784, + #71785,#71786,#71787,#71788,#71789,#71790,#71791,#71792,#71793, + #71794,#71795,#71796,#71797,#71798,#71799,#71800,#71801,#71802, + #71803,#71804,#71805),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85564,83 +88553,83 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69389 = CARTESIAN_POINT('',(1.570796326795,2.203939738443E-002)); -#69390 = CARTESIAN_POINT('',(1.54699638245,2.203939738443E-002)); -#69391 = CARTESIAN_POINT('',(1.499396493759,2.203939738443E-002)); -#69392 = CARTESIAN_POINT('',(1.427996660723,2.203939738443E-002)); -#69393 = CARTESIAN_POINT('',(1.356596827686,2.203939738443E-002)); -#69394 = CARTESIAN_POINT('',(1.28519699465,2.203939738443E-002)); -#69395 = CARTESIAN_POINT('',(1.213797161614,2.203939738443E-002)); -#69396 = CARTESIAN_POINT('',(1.142397328578,2.203939738443E-002)); -#69397 = CARTESIAN_POINT('',(1.070997495542,2.203939738443E-002)); -#69398 = CARTESIAN_POINT('',(0.999597662506,2.203939738443E-002)); -#69399 = CARTESIAN_POINT('',(0.92819782947,2.203939738443E-002)); -#69400 = CARTESIAN_POINT('',(0.856797996433,2.203939738443E-002)); -#69401 = CARTESIAN_POINT('',(0.785398163397,2.203939738443E-002)); -#69402 = CARTESIAN_POINT('',(0.713998330361,2.203939738443E-002)); -#69403 = CARTESIAN_POINT('',(0.642598497325,2.203939738443E-002)); -#69404 = CARTESIAN_POINT('',(0.571198664289,2.203939738443E-002)); -#69405 = CARTESIAN_POINT('',(0.499798831253,2.203939738443E-002)); -#69406 = CARTESIAN_POINT('',(0.428398998217,2.203939738443E-002)); -#69407 = CARTESIAN_POINT('',(0.35699916518,2.203939738443E-002)); -#69408 = CARTESIAN_POINT('',(0.285599332144,2.203939738443E-002)); -#69409 = CARTESIAN_POINT('',(0.214199499108,2.203939738443E-002)); -#69410 = CARTESIAN_POINT('',(0.142799666072,2.203939738443E-002)); -#69411 = CARTESIAN_POINT('',(7.13998330359E-002,2.203939738443E-002)); -#69412 = CARTESIAN_POINT('',(2.379994434526E-002,2.203939738443E-002)); -#69413 = CARTESIAN_POINT('',(0.E+000,2.203939738443E-002)); -#69414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69415 = ORIENTED_EDGE('',*,*,#69416,.T.); -#69416 = EDGE_CURVE('',#69366,#69270,#69417,.T.); -#69417 = SURFACE_CURVE('',#69418,(#69422,#69429),.PCURVE_S1.); -#69418 = LINE('',#69419,#69420); -#69419 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); -#69420 = VECTOR('',#69421,1.); -#69421 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69422 = PCURVE('',#49230,#69423); -#69423 = DEFINITIONAL_REPRESENTATION('',(#69424),#69428); -#69424 = LINE('',#69425,#69426); -#69425 = CARTESIAN_POINT('',(0.E+000,0.2)); -#69426 = VECTOR('',#69427,1.); -#69427 = DIRECTION('',(0.E+000,1.)); -#69428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69429 = PCURVE('',#69430,#69435); -#69430 = PLANE('',#69431); -#69431 = AXIS2_PLACEMENT_3D('',#69432,#69433,#69434); -#69432 = CARTESIAN_POINT('',(3.2,1.282876752796,2.78)); -#69433 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69434 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69435 = DEFINITIONAL_REPRESENTATION('',(#69436),#69440); -#69436 = LINE('',#69437,#69438); -#69437 = CARTESIAN_POINT('',(0.3,0.2)); -#69438 = VECTOR('',#69439,1.); -#69439 = DIRECTION('',(0.E+000,1.)); -#69440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69441 = ADVANCED_FACE('',(#69442),#69286,.T.); -#69442 = FACE_BOUND('',#69443,.T.); -#69443 = EDGE_LOOP('',(#69444,#69445,#69490,#69541)); -#69444 = ORIENTED_EDGE('',*,*,#69267,.F.); -#69445 = ORIENTED_EDGE('',*,*,#69446,.F.); -#69446 = EDGE_CURVE('',#69447,#69268,#69449,.T.); -#69447 = VERTEX_POINT('',#69448); -#69448 = CARTESIAN_POINT('',(-3.2,1.12655103819,2.655251168531)); -#69449 = SURFACE_CURVE('',#69450,(#69454,#69483),.PCURVE_S1.); -#69450 = LINE('',#69451,#69452); -#69451 = CARTESIAN_POINT('',(-3.2,1.12655103819,2.655251168531)); -#69452 = VECTOR('',#69453,1.); -#69453 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69454 = PCURVE('',#69286,#69455); -#69455 = DEFINITIONAL_REPRESENTATION('',(#69456),#69482); -#69456 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69457,#69458,#69459,#69460, - #69461,#69462,#69463,#69464,#69465,#69466,#69467,#69468,#69469, - #69470,#69471,#69472,#69473,#69474,#69475,#69476,#69477,#69478, - #69479,#69480,#69481),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71781 = CARTESIAN_POINT('',(1.570796326795,2.203939738443E-002)); +#71782 = CARTESIAN_POINT('',(1.54699638245,2.203939738443E-002)); +#71783 = CARTESIAN_POINT('',(1.499396493759,2.203939738443E-002)); +#71784 = CARTESIAN_POINT('',(1.427996660723,2.203939738443E-002)); +#71785 = CARTESIAN_POINT('',(1.356596827686,2.203939738443E-002)); +#71786 = CARTESIAN_POINT('',(1.28519699465,2.203939738443E-002)); +#71787 = CARTESIAN_POINT('',(1.213797161614,2.203939738443E-002)); +#71788 = CARTESIAN_POINT('',(1.142397328578,2.203939738443E-002)); +#71789 = CARTESIAN_POINT('',(1.070997495542,2.203939738443E-002)); +#71790 = CARTESIAN_POINT('',(0.999597662506,2.203939738443E-002)); +#71791 = CARTESIAN_POINT('',(0.92819782947,2.203939738443E-002)); +#71792 = CARTESIAN_POINT('',(0.856797996433,2.203939738443E-002)); +#71793 = CARTESIAN_POINT('',(0.785398163397,2.203939738443E-002)); +#71794 = CARTESIAN_POINT('',(0.713998330361,2.203939738443E-002)); +#71795 = CARTESIAN_POINT('',(0.642598497325,2.203939738443E-002)); +#71796 = CARTESIAN_POINT('',(0.571198664289,2.203939738443E-002)); +#71797 = CARTESIAN_POINT('',(0.499798831253,2.203939738443E-002)); +#71798 = CARTESIAN_POINT('',(0.428398998217,2.203939738443E-002)); +#71799 = CARTESIAN_POINT('',(0.35699916518,2.203939738443E-002)); +#71800 = CARTESIAN_POINT('',(0.285599332144,2.203939738443E-002)); +#71801 = CARTESIAN_POINT('',(0.214199499108,2.203939738443E-002)); +#71802 = CARTESIAN_POINT('',(0.142799666072,2.203939738443E-002)); +#71803 = CARTESIAN_POINT('',(7.13998330359E-002,2.203939738443E-002)); +#71804 = CARTESIAN_POINT('',(2.379994434526E-002,2.203939738443E-002)); +#71805 = CARTESIAN_POINT('',(0.E+000,2.203939738443E-002)); +#71806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71807 = ORIENTED_EDGE('',*,*,#71808,.T.); +#71808 = EDGE_CURVE('',#71758,#71662,#71809,.T.); +#71809 = SURFACE_CURVE('',#71810,(#71814,#71821),.PCURVE_S1.); +#71810 = LINE('',#71811,#71812); +#71811 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); +#71812 = VECTOR('',#71813,1.); +#71813 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#71814 = PCURVE('',#51622,#71815); +#71815 = DEFINITIONAL_REPRESENTATION('',(#71816),#71820); +#71816 = LINE('',#71817,#71818); +#71817 = CARTESIAN_POINT('',(0.E+000,0.2)); +#71818 = VECTOR('',#71819,1.); +#71819 = DIRECTION('',(0.E+000,1.)); +#71820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71821 = PCURVE('',#71822,#71827); +#71822 = PLANE('',#71823); +#71823 = AXIS2_PLACEMENT_3D('',#71824,#71825,#71826); +#71824 = CARTESIAN_POINT('',(3.2,1.282876752796,2.78)); +#71825 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#71826 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71827 = DEFINITIONAL_REPRESENTATION('',(#71828),#71832); +#71828 = LINE('',#71829,#71830); +#71829 = CARTESIAN_POINT('',(0.3,0.2)); +#71830 = VECTOR('',#71831,1.); +#71831 = DIRECTION('',(0.E+000,1.)); +#71832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71833 = ADVANCED_FACE('',(#71834),#71678,.T.); +#71834 = FACE_BOUND('',#71835,.T.); +#71835 = EDGE_LOOP('',(#71836,#71837,#71882,#71933)); +#71836 = ORIENTED_EDGE('',*,*,#71659,.F.); +#71837 = ORIENTED_EDGE('',*,*,#71838,.F.); +#71838 = EDGE_CURVE('',#71839,#71660,#71841,.T.); +#71839 = VERTEX_POINT('',#71840); +#71840 = CARTESIAN_POINT('',(-3.2,1.12655103819,2.655251168531)); +#71841 = SURFACE_CURVE('',#71842,(#71846,#71875),.PCURVE_S1.); +#71842 = LINE('',#71843,#71844); +#71843 = CARTESIAN_POINT('',(-3.2,1.12655103819,2.655251168531)); +#71844 = VECTOR('',#71845,1.); +#71845 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71846 = PCURVE('',#71678,#71847); +#71847 = DEFINITIONAL_REPRESENTATION('',(#71848),#71874); +#71848 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71849,#71850,#71851,#71852, + #71853,#71854,#71855,#71856,#71857,#71858,#71859,#71860,#71861, + #71862,#71863,#71864,#71865,#71866,#71867,#71868,#71869,#71870, + #71871,#71872,#71873),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363637E-002, 2.727272727274E-002,4.090909090911E-002,5.454545454548E-002, 6.818181818185E-002,8.181818181822E-002,9.545454545459E-002, @@ -85648,59 +88637,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454546,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#69457 = CARTESIAN_POINT('',(0.E+000,1.551463154777E-002)); -#69458 = CARTESIAN_POINT('',(-1.167954621906E-012,2.006008609322E-002)); -#69459 = CARTESIAN_POINT('',(-2.255085007619E-012,2.915099518414E-002)); -#69460 = CARTESIAN_POINT('',(-1.818989403546E-012,4.278735882051E-002)); -#69461 = CARTESIAN_POINT('',(-1.937117133366E-012,5.642372245688E-002)); -#69462 = CARTESIAN_POINT('',(-1.903366353417E-012,7.006008609325E-002)); -#69463 = CARTESIAN_POINT('',(-1.914024494454E-012,8.369644972962E-002)); -#69464 = CARTESIAN_POINT('',(-1.910471780775E-012,9.733281336599E-002)); -#69465 = CARTESIAN_POINT('',(-1.911359959195E-012,0.110969177002)); -#69466 = CARTESIAN_POINT('',(-1.911359959195E-012,0.124605540639)); -#69467 = CARTESIAN_POINT('',(-1.909583602355E-012,0.138241904275)); -#69468 = CARTESIAN_POINT('',(-1.915800851293E-012,0.151878267911)); -#69469 = CARTESIAN_POINT('',(-1.908695423936E-012,0.165514631548)); -#69470 = CARTESIAN_POINT('',(-1.912248137614E-012,0.179150995184)); -#69471 = CARTESIAN_POINT('',(-1.911359959195E-012,0.192787358821)); -#69472 = CARTESIAN_POINT('',(-1.911359959195E-012,0.206423722457)); -#69473 = CARTESIAN_POINT('',(-1.911359959195E-012,0.220060086093)); -#69474 = CARTESIAN_POINT('',(-1.910471780775E-012,0.23369644973)); -#69475 = CARTESIAN_POINT('',(-1.912248137614E-012,0.247332813366)); -#69476 = CARTESIAN_POINT('',(-1.903366353417E-012,0.260969177002)); -#69477 = CARTESIAN_POINT('',(-1.938005311786E-012,0.274605540639)); -#69478 = CARTESIAN_POINT('',(-1.818989403546E-012,0.288241904275)); -#69479 = CARTESIAN_POINT('',(-2.255973186038E-012,0.301878267912)); -#69480 = CARTESIAN_POINT('',(-1.167954621906E-012,0.310969177002)); -#69481 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); -#69482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69483 = PCURVE('',#38438,#69484); -#69484 = DEFINITIONAL_REPRESENTATION('',(#69485),#69489); -#69485 = LINE('',#69486,#69487); -#69486 = CARTESIAN_POINT('',(2.655251168531,1.12655103819)); -#69487 = VECTOR('',#69488,1.); -#69488 = DIRECTION('',(-0.78162857303,0.623744157346)); -#69489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69490 = ORIENTED_EDGE('',*,*,#69491,.F.); -#69491 = EDGE_CURVE('',#69492,#69447,#69494,.T.); -#69492 = VERTEX_POINT('',#69493); -#69493 = CARTESIAN_POINT('',(-3.,1.282876752796,2.78)); -#69494 = SURFACE_CURVE('',#69495,(#69500,#69529),.PCURVE_S1.); -#69495 = CIRCLE('',#69496,0.2); -#69496 = AXIS2_PLACEMENT_3D('',#69497,#69498,#69499); -#69497 = CARTESIAN_POINT('',(-3.,1.12655103819,2.655251168531)); -#69498 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69499 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69500 = PCURVE('',#69286,#69501); -#69501 = DEFINITIONAL_REPRESENTATION('',(#69502),#69528); -#69502 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69503,#69504,#69505,#69506, - #69507,#69508,#69509,#69510,#69511,#69512,#69513,#69514,#69515, - #69516,#69517,#69518,#69519,#69520,#69521,#69522,#69523,#69524, - #69525,#69526,#69527),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71849 = CARTESIAN_POINT('',(0.E+000,1.551463154777E-002)); +#71850 = CARTESIAN_POINT('',(-1.167954621906E-012,2.006008609322E-002)); +#71851 = CARTESIAN_POINT('',(-2.255085007619E-012,2.915099518414E-002)); +#71852 = CARTESIAN_POINT('',(-1.818989403546E-012,4.278735882051E-002)); +#71853 = CARTESIAN_POINT('',(-1.937117133366E-012,5.642372245688E-002)); +#71854 = CARTESIAN_POINT('',(-1.903366353417E-012,7.006008609325E-002)); +#71855 = CARTESIAN_POINT('',(-1.914024494454E-012,8.369644972962E-002)); +#71856 = CARTESIAN_POINT('',(-1.910471780775E-012,9.733281336599E-002)); +#71857 = CARTESIAN_POINT('',(-1.911359959195E-012,0.110969177002)); +#71858 = CARTESIAN_POINT('',(-1.911359959195E-012,0.124605540639)); +#71859 = CARTESIAN_POINT('',(-1.909583602355E-012,0.138241904275)); +#71860 = CARTESIAN_POINT('',(-1.915800851293E-012,0.151878267911)); +#71861 = CARTESIAN_POINT('',(-1.908695423936E-012,0.165514631548)); +#71862 = CARTESIAN_POINT('',(-1.912248137614E-012,0.179150995184)); +#71863 = CARTESIAN_POINT('',(-1.911359959195E-012,0.192787358821)); +#71864 = CARTESIAN_POINT('',(-1.911359959195E-012,0.206423722457)); +#71865 = CARTESIAN_POINT('',(-1.911359959195E-012,0.220060086093)); +#71866 = CARTESIAN_POINT('',(-1.910471780775E-012,0.23369644973)); +#71867 = CARTESIAN_POINT('',(-1.912248137614E-012,0.247332813366)); +#71868 = CARTESIAN_POINT('',(-1.903366353417E-012,0.260969177002)); +#71869 = CARTESIAN_POINT('',(-1.938005311786E-012,0.274605540639)); +#71870 = CARTESIAN_POINT('',(-1.818989403546E-012,0.288241904275)); +#71871 = CARTESIAN_POINT('',(-2.255973186038E-012,0.301878267912)); +#71872 = CARTESIAN_POINT('',(-1.167954621906E-012,0.310969177002)); +#71873 = CARTESIAN_POINT('',(0.E+000,0.315514631548)); +#71874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71875 = PCURVE('',#40830,#71876); +#71876 = DEFINITIONAL_REPRESENTATION('',(#71877),#71881); +#71877 = LINE('',#71878,#71879); +#71878 = CARTESIAN_POINT('',(2.655251168531,1.12655103819)); +#71879 = VECTOR('',#71880,1.); +#71880 = DIRECTION('',(-0.78162857303,0.623744157346)); +#71881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71882 = ORIENTED_EDGE('',*,*,#71883,.F.); +#71883 = EDGE_CURVE('',#71884,#71839,#71886,.T.); +#71884 = VERTEX_POINT('',#71885); +#71885 = CARTESIAN_POINT('',(-3.,1.282876752796,2.78)); +#71886 = SURFACE_CURVE('',#71887,(#71892,#71921),.PCURVE_S1.); +#71887 = CIRCLE('',#71888,0.2); +#71888 = AXIS2_PLACEMENT_3D('',#71889,#71890,#71891); +#71889 = CARTESIAN_POINT('',(-3.,1.12655103819,2.655251168531)); +#71890 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#71891 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#71892 = PCURVE('',#71678,#71893); +#71893 = DEFINITIONAL_REPRESENTATION('',(#71894),#71920); +#71894 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71895,#71896,#71897,#71898, + #71899,#71900,#71901,#71902,#71903,#71904,#71905,#71906,#71907, + #71908,#71909,#71910,#71911,#71912,#71913,#71914,#71915,#71916, + #71917,#71918,#71919),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85708,149 +88697,149 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69503 = CARTESIAN_POINT('',(1.570796326795,1.551463154777E-002)); -#69504 = CARTESIAN_POINT('',(1.546996382449,1.551463154777E-002)); -#69505 = CARTESIAN_POINT('',(1.499396493759,1.551463154777E-002)); -#69506 = CARTESIAN_POINT('',(1.427996660722,1.551463154777E-002)); -#69507 = CARTESIAN_POINT('',(1.356596827686,1.551463154777E-002)); -#69508 = CARTESIAN_POINT('',(1.28519699465,1.551463154777E-002)); -#69509 = CARTESIAN_POINT('',(1.213797161614,1.551463154777E-002)); -#69510 = CARTESIAN_POINT('',(1.142397328577,1.551463154777E-002)); -#69511 = CARTESIAN_POINT('',(1.070997495541,1.551463154777E-002)); -#69512 = CARTESIAN_POINT('',(0.999597662505,1.551463154777E-002)); -#69513 = CARTESIAN_POINT('',(0.928197829469,1.551463154777E-002)); -#69514 = CARTESIAN_POINT('',(0.856797996432,1.551463154777E-002)); -#69515 = CARTESIAN_POINT('',(0.785398163396,1.551463154777E-002)); -#69516 = CARTESIAN_POINT('',(0.71399833036,1.551463154777E-002)); -#69517 = CARTESIAN_POINT('',(0.642598497324,1.551463154777E-002)); -#69518 = CARTESIAN_POINT('',(0.571198664287,1.551463154777E-002)); -#69519 = CARTESIAN_POINT('',(0.499798831251,1.551463154777E-002)); -#69520 = CARTESIAN_POINT('',(0.428398998215,1.551463154777E-002)); -#69521 = CARTESIAN_POINT('',(0.356999165179,1.551463154777E-002)); -#69522 = CARTESIAN_POINT('',(0.285599332143,1.551463154777E-002)); -#69523 = CARTESIAN_POINT('',(0.214199499106,1.551463154777E-002)); -#69524 = CARTESIAN_POINT('',(0.14279966607,1.551463154777E-002)); -#69525 = CARTESIAN_POINT('',(7.139983303388E-002,1.551463154777E-002)); -#69526 = CARTESIAN_POINT('',(2.379994434421E-002,1.551463154777E-002)); -#69527 = CARTESIAN_POINT('',(0.E+000,1.551463154777E-002)); -#69528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69529 = PCURVE('',#69530,#69535); -#69530 = PLANE('',#69531); -#69531 = AXIS2_PLACEMENT_3D('',#69532,#69533,#69534); -#69532 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); -#69533 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69534 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69535 = DEFINITIONAL_REPRESENTATION('',(#69536),#69540); -#69536 = CIRCLE('',#69537,0.2); -#69537 = AXIS2_PLACEMENT_2D('',#69538,#69539); -#69538 = CARTESIAN_POINT('',(0.118261853532,6.2)); -#69539 = DIRECTION('',(1.,0.E+000)); -#69540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69541 = ORIENTED_EDGE('',*,*,#69542,.T.); -#69542 = EDGE_CURVE('',#69492,#69270,#69543,.T.); -#69543 = SURFACE_CURVE('',#69544,(#69548,#69554),.PCURVE_S1.); -#69544 = LINE('',#69545,#69546); -#69545 = CARTESIAN_POINT('',(-3.,1.282876752796,2.78)); -#69546 = VECTOR('',#69547,1.); -#69547 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); -#69548 = PCURVE('',#69286,#69549); -#69549 = DEFINITIONAL_REPRESENTATION('',(#69550),#69553); -#69550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69551,#69552),.UNSPECIFIED., +#71895 = CARTESIAN_POINT('',(1.570796326795,1.551463154777E-002)); +#71896 = CARTESIAN_POINT('',(1.546996382449,1.551463154777E-002)); +#71897 = CARTESIAN_POINT('',(1.499396493759,1.551463154777E-002)); +#71898 = CARTESIAN_POINT('',(1.427996660722,1.551463154777E-002)); +#71899 = CARTESIAN_POINT('',(1.356596827686,1.551463154777E-002)); +#71900 = CARTESIAN_POINT('',(1.28519699465,1.551463154777E-002)); +#71901 = CARTESIAN_POINT('',(1.213797161614,1.551463154777E-002)); +#71902 = CARTESIAN_POINT('',(1.142397328577,1.551463154777E-002)); +#71903 = CARTESIAN_POINT('',(1.070997495541,1.551463154777E-002)); +#71904 = CARTESIAN_POINT('',(0.999597662505,1.551463154777E-002)); +#71905 = CARTESIAN_POINT('',(0.928197829469,1.551463154777E-002)); +#71906 = CARTESIAN_POINT('',(0.856797996432,1.551463154777E-002)); +#71907 = CARTESIAN_POINT('',(0.785398163396,1.551463154777E-002)); +#71908 = CARTESIAN_POINT('',(0.71399833036,1.551463154777E-002)); +#71909 = CARTESIAN_POINT('',(0.642598497324,1.551463154777E-002)); +#71910 = CARTESIAN_POINT('',(0.571198664287,1.551463154777E-002)); +#71911 = CARTESIAN_POINT('',(0.499798831251,1.551463154777E-002)); +#71912 = CARTESIAN_POINT('',(0.428398998215,1.551463154777E-002)); +#71913 = CARTESIAN_POINT('',(0.356999165179,1.551463154777E-002)); +#71914 = CARTESIAN_POINT('',(0.285599332143,1.551463154777E-002)); +#71915 = CARTESIAN_POINT('',(0.214199499106,1.551463154777E-002)); +#71916 = CARTESIAN_POINT('',(0.14279966607,1.551463154777E-002)); +#71917 = CARTESIAN_POINT('',(7.139983303388E-002,1.551463154777E-002)); +#71918 = CARTESIAN_POINT('',(2.379994434421E-002,1.551463154777E-002)); +#71919 = CARTESIAN_POINT('',(0.E+000,1.551463154777E-002)); +#71920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71921 = PCURVE('',#71922,#71927); +#71922 = PLANE('',#71923); +#71923 = AXIS2_PLACEMENT_3D('',#71924,#71925,#71926); +#71924 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); +#71925 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#71926 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#71927 = DEFINITIONAL_REPRESENTATION('',(#71928),#71932); +#71928 = CIRCLE('',#71929,0.2); +#71929 = AXIS2_PLACEMENT_2D('',#71930,#71931); +#71930 = CARTESIAN_POINT('',(0.118261853532,6.2)); +#71931 = DIRECTION('',(1.,0.E+000)); +#71932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71933 = ORIENTED_EDGE('',*,*,#71934,.T.); +#71934 = EDGE_CURVE('',#71884,#71662,#71935,.T.); +#71935 = SURFACE_CURVE('',#71936,(#71940,#71946),.PCURVE_S1.); +#71936 = LINE('',#71937,#71938); +#71937 = CARTESIAN_POINT('',(-3.,1.282876752796,2.78)); +#71938 = VECTOR('',#71939,1.); +#71939 = DIRECTION('',(0.E+000,0.623744157346,-0.78162857303)); +#71940 = PCURVE('',#71678,#71941); +#71941 = DEFINITIONAL_REPRESENTATION('',(#71942),#71945); +#71942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71943,#71944),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#69551 = CARTESIAN_POINT('',(1.570796326795,1.551463154801E-002)); -#69552 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); -#69553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69554 = PCURVE('',#69430,#69555); -#69555 = DEFINITIONAL_REPRESENTATION('',(#69556),#69560); -#69556 = LINE('',#69557,#69558); -#69557 = CARTESIAN_POINT('',(0.E+000,6.2)); -#69558 = VECTOR('',#69559,1.); -#69559 = DIRECTION('',(1.,0.E+000)); -#69560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69561 = ADVANCED_FACE('',(#69562),#69430,.T.); -#69562 = FACE_BOUND('',#69563,.F.); -#69563 = EDGE_LOOP('',(#69564,#69565,#69566,#69588)); -#69564 = ORIENTED_EDGE('',*,*,#69542,.T.); -#69565 = ORIENTED_EDGE('',*,*,#69416,.F.); -#69566 = ORIENTED_EDGE('',*,*,#69567,.T.); -#69567 = EDGE_CURVE('',#69366,#69568,#69570,.T.); -#69568 = VERTEX_POINT('',#69569); -#69569 = CARTESIAN_POINT('',(3.,1.282876752796,2.78)); -#69570 = SURFACE_CURVE('',#69571,(#69575,#69582),.PCURVE_S1.); -#69571 = LINE('',#69572,#69573); -#69572 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); -#69573 = VECTOR('',#69574,1.); -#69574 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69575 = PCURVE('',#69430,#69576); -#69576 = DEFINITIONAL_REPRESENTATION('',(#69577),#69581); -#69577 = LINE('',#69578,#69579); -#69578 = CARTESIAN_POINT('',(0.3,0.2)); -#69579 = VECTOR('',#69580,1.); -#69580 = DIRECTION('',(-1.,0.E+000)); -#69581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69582 = PCURVE('',#69382,#69583); -#69583 = DEFINITIONAL_REPRESENTATION('',(#69584),#69587); -#69584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69585,#69586),.UNSPECIFIED., +#71943 = CARTESIAN_POINT('',(1.570796326795,1.551463154801E-002)); +#71944 = CARTESIAN_POINT('',(1.570796326795,0.315514631548)); +#71945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71946 = PCURVE('',#71822,#71947); +#71947 = DEFINITIONAL_REPRESENTATION('',(#71948),#71952); +#71948 = LINE('',#71949,#71950); +#71949 = CARTESIAN_POINT('',(0.E+000,6.2)); +#71950 = VECTOR('',#71951,1.); +#71951 = DIRECTION('',(1.,0.E+000)); +#71952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71953 = ADVANCED_FACE('',(#71954),#71822,.T.); +#71954 = FACE_BOUND('',#71955,.F.); +#71955 = EDGE_LOOP('',(#71956,#71957,#71958,#71980)); +#71956 = ORIENTED_EDGE('',*,*,#71934,.T.); +#71957 = ORIENTED_EDGE('',*,*,#71808,.F.); +#71958 = ORIENTED_EDGE('',*,*,#71959,.T.); +#71959 = EDGE_CURVE('',#71758,#71960,#71962,.T.); +#71960 = VERTEX_POINT('',#71961); +#71961 = CARTESIAN_POINT('',(3.,1.282876752796,2.78)); +#71962 = SURFACE_CURVE('',#71963,(#71967,#71974),.PCURVE_S1.); +#71963 = LINE('',#71964,#71965); +#71964 = CARTESIAN_POINT('',(3.,1.47,2.545511428091)); +#71965 = VECTOR('',#71966,1.); +#71966 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#71967 = PCURVE('',#71822,#71968); +#71968 = DEFINITIONAL_REPRESENTATION('',(#71969),#71973); +#71969 = LINE('',#71970,#71971); +#71970 = CARTESIAN_POINT('',(0.3,0.2)); +#71971 = VECTOR('',#71972,1.); +#71972 = DIRECTION('',(-1.,0.E+000)); +#71973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71974 = PCURVE('',#71774,#71975); +#71975 = DEFINITIONAL_REPRESENTATION('',(#71976),#71979); +#71976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71977,#71978),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#69585 = CARTESIAN_POINT('',(1.570796326795,2.203939738419E-002)); -#69586 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); -#69587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69588 = ORIENTED_EDGE('',*,*,#69589,.T.); -#69589 = EDGE_CURVE('',#69568,#69492,#69590,.T.); -#69590 = SURFACE_CURVE('',#69591,(#69595,#69602),.PCURVE_S1.); -#69591 = LINE('',#69592,#69593); -#69592 = CARTESIAN_POINT('',(3.,1.282876752796,2.78)); -#69593 = VECTOR('',#69594,1.); -#69594 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69595 = PCURVE('',#69430,#69596); -#69596 = DEFINITIONAL_REPRESENTATION('',(#69597),#69601); -#69597 = LINE('',#69598,#69599); -#69598 = CARTESIAN_POINT('',(0.E+000,0.2)); -#69599 = VECTOR('',#69600,1.); -#69600 = DIRECTION('',(0.E+000,1.)); -#69601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69602 = PCURVE('',#69530,#69603); -#69603 = DEFINITIONAL_REPRESENTATION('',(#69604),#69608); -#69604 = LINE('',#69605,#69606); -#69605 = CARTESIAN_POINT('',(0.318261853532,0.2)); -#69606 = VECTOR('',#69607,1.); -#69607 = DIRECTION('',(0.E+000,1.)); -#69608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69609 = ADVANCED_FACE('',(#69610),#69382,.T.); -#69610 = FACE_BOUND('',#69611,.T.); -#69611 = EDGE_LOOP('',(#69612,#69658,#69701,#69702)); -#69612 = ORIENTED_EDGE('',*,*,#69613,.F.); -#69613 = EDGE_CURVE('',#69614,#69568,#69616,.T.); -#69614 = VERTEX_POINT('',#69615); -#69615 = CARTESIAN_POINT('',(3.2,1.12655103819,2.655251168531)); -#69616 = SURFACE_CURVE('',#69617,(#69622,#69651),.PCURVE_S1.); -#69617 = CIRCLE('',#69618,0.2); -#69618 = AXIS2_PLACEMENT_3D('',#69619,#69620,#69621); -#69619 = CARTESIAN_POINT('',(3.,1.12655103819,2.655251168531)); -#69620 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69621 = DIRECTION('',(1.,0.E+000,0.E+000)); -#69622 = PCURVE('',#69382,#69623); -#69623 = DEFINITIONAL_REPRESENTATION('',(#69624),#69650); -#69624 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69625,#69626,#69627,#69628, - #69629,#69630,#69631,#69632,#69633,#69634,#69635,#69636,#69637, - #69638,#69639,#69640,#69641,#69642,#69643,#69644,#69645,#69646, - #69647,#69648,#69649),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#71977 = CARTESIAN_POINT('',(1.570796326795,2.203939738419E-002)); +#71978 = CARTESIAN_POINT('',(1.570796326795,0.322039397384)); +#71979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71980 = ORIENTED_EDGE('',*,*,#71981,.T.); +#71981 = EDGE_CURVE('',#71960,#71884,#71982,.T.); +#71982 = SURFACE_CURVE('',#71983,(#71987,#71994),.PCURVE_S1.); +#71983 = LINE('',#71984,#71985); +#71984 = CARTESIAN_POINT('',(3.,1.282876752796,2.78)); +#71985 = VECTOR('',#71986,1.); +#71986 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#71987 = PCURVE('',#71822,#71988); +#71988 = DEFINITIONAL_REPRESENTATION('',(#71989),#71993); +#71989 = LINE('',#71990,#71991); +#71990 = CARTESIAN_POINT('',(0.E+000,0.2)); +#71991 = VECTOR('',#71992,1.); +#71992 = DIRECTION('',(0.E+000,1.)); +#71993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#71994 = PCURVE('',#71922,#71995); +#71995 = DEFINITIONAL_REPRESENTATION('',(#71996),#72000); +#71996 = LINE('',#71997,#71998); +#71997 = CARTESIAN_POINT('',(0.318261853532,0.2)); +#71998 = VECTOR('',#71999,1.); +#71999 = DIRECTION('',(0.E+000,1.)); +#72000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72001 = ADVANCED_FACE('',(#72002),#71774,.T.); +#72002 = FACE_BOUND('',#72003,.T.); +#72003 = EDGE_LOOP('',(#72004,#72050,#72093,#72094)); +#72004 = ORIENTED_EDGE('',*,*,#72005,.F.); +#72005 = EDGE_CURVE('',#72006,#71960,#72008,.T.); +#72006 = VERTEX_POINT('',#72007); +#72007 = CARTESIAN_POINT('',(3.2,1.12655103819,2.655251168531)); +#72008 = SURFACE_CURVE('',#72009,(#72014,#72043),.PCURVE_S1.); +#72009 = CIRCLE('',#72010,0.2); +#72010 = AXIS2_PLACEMENT_3D('',#72011,#72012,#72013); +#72011 = CARTESIAN_POINT('',(3.,1.12655103819,2.655251168531)); +#72012 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#72013 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72014 = PCURVE('',#71774,#72015); +#72015 = DEFINITIONAL_REPRESENTATION('',(#72016),#72042); +#72016 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72017,#72018,#72019,#72020, + #72021,#72022,#72023,#72024,#72025,#72026,#72027,#72028,#72029, + #72030,#72031,#72032,#72033,#72034,#72035,#72036,#72037,#72038, + #72039,#72040,#72041),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -85858,56 +88847,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69625 = CARTESIAN_POINT('',(0.E+000,0.322039397385)); -#69626 = CARTESIAN_POINT('',(2.379994434517E-002,0.322039397385)); -#69627 = CARTESIAN_POINT('',(7.139983303573E-002,0.322039397385)); -#69628 = CARTESIAN_POINT('',(0.142799666072,0.322039397385)); -#69629 = CARTESIAN_POINT('',(0.214199499108,0.322039397385)); -#69630 = CARTESIAN_POINT('',(0.285599332144,0.322039397385)); -#69631 = CARTESIAN_POINT('',(0.35699916518,0.322039397385)); -#69632 = CARTESIAN_POINT('',(0.428398998216,0.322039397385)); -#69633 = CARTESIAN_POINT('',(0.499798831253,0.322039397385)); -#69634 = CARTESIAN_POINT('',(0.571198664289,0.322039397385)); -#69635 = CARTESIAN_POINT('',(0.642598497325,0.322039397385)); -#69636 = CARTESIAN_POINT('',(0.713998330361,0.322039397385)); -#69637 = CARTESIAN_POINT('',(0.785398163397,0.322039397385)); -#69638 = CARTESIAN_POINT('',(0.856797996433,0.322039397385)); -#69639 = CARTESIAN_POINT('',(0.92819782947,0.322039397385)); -#69640 = CARTESIAN_POINT('',(0.999597662506,0.322039397385)); -#69641 = CARTESIAN_POINT('',(1.070997495542,0.322039397385)); -#69642 = CARTESIAN_POINT('',(1.142397328578,0.322039397385)); -#69643 = CARTESIAN_POINT('',(1.213797161614,0.322039397385)); -#69644 = CARTESIAN_POINT('',(1.28519699465,0.322039397385)); -#69645 = CARTESIAN_POINT('',(1.356596827686,0.322039397385)); -#69646 = CARTESIAN_POINT('',(1.427996660723,0.322039397385)); -#69647 = CARTESIAN_POINT('',(1.499396493759,0.322039397385)); -#69648 = CARTESIAN_POINT('',(1.54699638245,0.322039397385)); -#69649 = CARTESIAN_POINT('',(1.570796326795,0.322039397385)); -#69650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69651 = PCURVE('',#69530,#69652); -#69652 = DEFINITIONAL_REPRESENTATION('',(#69653),#69657); -#69653 = CIRCLE('',#69654,0.2); -#69654 = AXIS2_PLACEMENT_2D('',#69655,#69656); -#69655 = CARTESIAN_POINT('',(0.118261853532,0.2)); -#69656 = DIRECTION('',(0.E+000,-1.)); -#69657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69658 = ORIENTED_EDGE('',*,*,#69659,.F.); -#69659 = EDGE_CURVE('',#69343,#69614,#69660,.T.); -#69660 = SURFACE_CURVE('',#69661,(#69665,#69694),.PCURVE_S1.); -#69661 = LINE('',#69662,#69663); -#69662 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); -#69663 = VECTOR('',#69664,1.); -#69664 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); -#69665 = PCURVE('',#69382,#69666); -#69666 = DEFINITIONAL_REPRESENTATION('',(#69667),#69693); -#69667 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69668,#69669,#69670,#69671, - #69672,#69673,#69674,#69675,#69676,#69677,#69678,#69679,#69680, - #69681,#69682,#69683,#69684,#69685,#69686,#69687,#69688,#69689, - #69690,#69691,#69692),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#72017 = CARTESIAN_POINT('',(0.E+000,0.322039397385)); +#72018 = CARTESIAN_POINT('',(2.379994434517E-002,0.322039397385)); +#72019 = CARTESIAN_POINT('',(7.139983303573E-002,0.322039397385)); +#72020 = CARTESIAN_POINT('',(0.142799666072,0.322039397385)); +#72021 = CARTESIAN_POINT('',(0.214199499108,0.322039397385)); +#72022 = CARTESIAN_POINT('',(0.285599332144,0.322039397385)); +#72023 = CARTESIAN_POINT('',(0.35699916518,0.322039397385)); +#72024 = CARTESIAN_POINT('',(0.428398998216,0.322039397385)); +#72025 = CARTESIAN_POINT('',(0.499798831253,0.322039397385)); +#72026 = CARTESIAN_POINT('',(0.571198664289,0.322039397385)); +#72027 = CARTESIAN_POINT('',(0.642598497325,0.322039397385)); +#72028 = CARTESIAN_POINT('',(0.713998330361,0.322039397385)); +#72029 = CARTESIAN_POINT('',(0.785398163397,0.322039397385)); +#72030 = CARTESIAN_POINT('',(0.856797996433,0.322039397385)); +#72031 = CARTESIAN_POINT('',(0.92819782947,0.322039397385)); +#72032 = CARTESIAN_POINT('',(0.999597662506,0.322039397385)); +#72033 = CARTESIAN_POINT('',(1.070997495542,0.322039397385)); +#72034 = CARTESIAN_POINT('',(1.142397328578,0.322039397385)); +#72035 = CARTESIAN_POINT('',(1.213797161614,0.322039397385)); +#72036 = CARTESIAN_POINT('',(1.28519699465,0.322039397385)); +#72037 = CARTESIAN_POINT('',(1.356596827686,0.322039397385)); +#72038 = CARTESIAN_POINT('',(1.427996660723,0.322039397385)); +#72039 = CARTESIAN_POINT('',(1.499396493759,0.322039397385)); +#72040 = CARTESIAN_POINT('',(1.54699638245,0.322039397385)); +#72041 = CARTESIAN_POINT('',(1.570796326795,0.322039397385)); +#72042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72043 = PCURVE('',#71922,#72044); +#72044 = DEFINITIONAL_REPRESENTATION('',(#72045),#72049); +#72045 = CIRCLE('',#72046,0.2); +#72046 = AXIS2_PLACEMENT_2D('',#72047,#72048); +#72047 = CARTESIAN_POINT('',(0.118261853532,0.2)); +#72048 = DIRECTION('',(0.E+000,-1.)); +#72049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72050 = ORIENTED_EDGE('',*,*,#72051,.F.); +#72051 = EDGE_CURVE('',#71735,#72006,#72052,.T.); +#72052 = SURFACE_CURVE('',#72053,(#72057,#72086),.PCURVE_S1.); +#72053 = LINE('',#72054,#72055); +#72054 = CARTESIAN_POINT('',(3.2,1.313674285394,2.420762596622)); +#72055 = VECTOR('',#72056,1.); +#72056 = DIRECTION('',(0.E+000,-0.623744157346,0.78162857303)); +#72057 = PCURVE('',#71774,#72058); +#72058 = DEFINITIONAL_REPRESENTATION('',(#72059),#72085); +#72059 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72060,#72061,#72062,#72063, + #72064,#72065,#72066,#72067,#72068,#72069,#72070,#72071,#72072, + #72073,#72074,#72075,#72076,#72077,#72078,#72079,#72080,#72081, + #72082,#72083,#72084),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.363636363637E-002, 2.727272727274E-002,4.090909090911E-002,5.454545454548E-002, 6.818181818185E-002,8.181818181822E-002,9.545454545459E-002, @@ -85915,313 +88904,313 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.177272727273,0.190909090909,0.204545454546,0.218181818182, 0.231818181818,0.245454545455,0.259090909091,0.272727272727, 0.286363636364,0.3),.QUASI_UNIFORM_KNOTS.); -#69668 = CARTESIAN_POINT('',(0.E+000,2.203939738443E-002)); -#69669 = CARTESIAN_POINT('',(-1.190159082398E-013,2.658485192988E-002)); -#69670 = CARTESIAN_POINT('',(-2.264854970235E-013,3.56757610208E-002)); -#69671 = CARTESIAN_POINT('',(-1.847411112976E-013,4.931212465717E-002)); -#69672 = CARTESIAN_POINT('',(-1.971756091734E-013,6.294848829354E-002)); -#69673 = CARTESIAN_POINT('',(-1.927347170749E-013,7.658485192991E-002)); -#69674 = CARTESIAN_POINT('',(-1.936228954946E-013,9.022121556628E-002)); -#69675 = CARTESIAN_POINT('',(-1.936228954946E-013,0.103857579203)); -#69676 = CARTESIAN_POINT('',(-1.927347170749E-013,0.117493942839)); -#69677 = CARTESIAN_POINT('',(-1.936228954946E-013,0.131130306475)); -#69678 = CARTESIAN_POINT('',(-1.936228954946E-013,0.144766670112)); -#69679 = CARTESIAN_POINT('',(-1.936228954946E-013,0.158403033748)); -#69680 = CARTESIAN_POINT('',(-1.927347170749E-013,0.172039397385)); -#69681 = CARTESIAN_POINT('',(-1.927347170749E-013,0.185675761021)); -#69682 = CARTESIAN_POINT('',(-1.936228954946E-013,0.199312124657)); -#69683 = CARTESIAN_POINT('',(-1.936228954946E-013,0.212948488294)); -#69684 = CARTESIAN_POINT('',(-1.936228954946E-013,0.22658485193)); -#69685 = CARTESIAN_POINT('',(-1.936228954946E-013,0.240221215566)); -#69686 = CARTESIAN_POINT('',(-1.936228954946E-013,0.253857579203)); -#69687 = CARTESIAN_POINT('',(-1.927347170749E-013,0.267493942839)); -#69688 = CARTESIAN_POINT('',(-1.962874307537E-013,0.281130306475)); -#69689 = CARTESIAN_POINT('',(-1.847411112976E-013,0.294766670112)); -#69690 = CARTESIAN_POINT('',(-2.273736754432E-013,0.308403033748)); -#69691 = CARTESIAN_POINT('',(-1.181277298201E-013,0.317493942839)); -#69692 = CARTESIAN_POINT('',(0.E+000,0.322039397385)); -#69693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69694 = PCURVE('',#38612,#69695); -#69695 = DEFINITIONAL_REPRESENTATION('',(#69696),#69700); -#69696 = LINE('',#69697,#69698); -#69697 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); -#69698 = VECTOR('',#69699,1.); -#69699 = DIRECTION('',(0.78162857303,-0.623744157346)); -#69700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69701 = ORIENTED_EDGE('',*,*,#69365,.F.); -#69702 = ORIENTED_EDGE('',*,*,#69567,.T.); -#69703 = ADVANCED_FACE('',(#69704),#69530,.T.); -#69704 = FACE_BOUND('',#69705,.F.); -#69705 = EDGE_LOOP('',(#69706,#69707,#69708,#69709,#69732,#69754)); -#69706 = ORIENTED_EDGE('',*,*,#69491,.F.); -#69707 = ORIENTED_EDGE('',*,*,#69589,.F.); -#69708 = ORIENTED_EDGE('',*,*,#69613,.F.); -#69709 = ORIENTED_EDGE('',*,*,#69710,.F.); -#69710 = EDGE_CURVE('',#69711,#69614,#69713,.T.); -#69711 = VERTEX_POINT('',#69712); -#69712 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); -#69713 = SURFACE_CURVE('',#69714,(#69718,#69725),.PCURVE_S1.); -#69714 = LINE('',#69715,#69716); -#69715 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); -#69716 = VECTOR('',#69717,1.); -#69717 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69718 = PCURVE('',#69530,#69719); -#69719 = DEFINITIONAL_REPRESENTATION('',(#69720),#69724); -#69720 = LINE('',#69721,#69722); -#69721 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#69722 = VECTOR('',#69723,1.); -#69723 = DIRECTION('',(1.,0.E+000)); -#69724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69725 = PCURVE('',#38612,#69726); -#69726 = DEFINITIONAL_REPRESENTATION('',(#69727),#69731); -#69727 = LINE('',#69728,#69729); -#69728 = CARTESIAN_POINT('',(2.581486028353,1.03411419437)); -#69729 = VECTOR('',#69730,1.); -#69730 = DIRECTION('',(0.623744157346,0.78162857303)); -#69731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69732 = ORIENTED_EDGE('',*,*,#69733,.T.); -#69733 = EDGE_CURVE('',#69711,#69734,#69736,.T.); -#69734 = VERTEX_POINT('',#69735); -#69735 = CARTESIAN_POINT('',(-3.2,1.03411419437,2.581486028353)); -#69736 = SURFACE_CURVE('',#69737,(#69741,#69748),.PCURVE_S1.); -#69737 = LINE('',#69738,#69739); -#69738 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); -#69739 = VECTOR('',#69740,1.); -#69740 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69741 = PCURVE('',#69530,#69742); -#69742 = DEFINITIONAL_REPRESENTATION('',(#69743),#69747); -#69743 = LINE('',#69744,#69745); -#69744 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#69745 = VECTOR('',#69746,1.); -#69746 = DIRECTION('',(0.E+000,1.)); -#69747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69748 = PCURVE('',#47426,#69749); -#69749 = DEFINITIONAL_REPRESENTATION('',(#69750),#69753); -#69750 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69751,#69752),.UNSPECIFIED., +#72060 = CARTESIAN_POINT('',(0.E+000,2.203939738443E-002)); +#72061 = CARTESIAN_POINT('',(-1.190159082398E-013,2.658485192988E-002)); +#72062 = CARTESIAN_POINT('',(-2.264854970235E-013,3.56757610208E-002)); +#72063 = CARTESIAN_POINT('',(-1.847411112976E-013,4.931212465717E-002)); +#72064 = CARTESIAN_POINT('',(-1.971756091734E-013,6.294848829354E-002)); +#72065 = CARTESIAN_POINT('',(-1.927347170749E-013,7.658485192991E-002)); +#72066 = CARTESIAN_POINT('',(-1.936228954946E-013,9.022121556628E-002)); +#72067 = CARTESIAN_POINT('',(-1.936228954946E-013,0.103857579203)); +#72068 = CARTESIAN_POINT('',(-1.927347170749E-013,0.117493942839)); +#72069 = CARTESIAN_POINT('',(-1.936228954946E-013,0.131130306475)); +#72070 = CARTESIAN_POINT('',(-1.936228954946E-013,0.144766670112)); +#72071 = CARTESIAN_POINT('',(-1.936228954946E-013,0.158403033748)); +#72072 = CARTESIAN_POINT('',(-1.927347170749E-013,0.172039397385)); +#72073 = CARTESIAN_POINT('',(-1.927347170749E-013,0.185675761021)); +#72074 = CARTESIAN_POINT('',(-1.936228954946E-013,0.199312124657)); +#72075 = CARTESIAN_POINT('',(-1.936228954946E-013,0.212948488294)); +#72076 = CARTESIAN_POINT('',(-1.936228954946E-013,0.22658485193)); +#72077 = CARTESIAN_POINT('',(-1.936228954946E-013,0.240221215566)); +#72078 = CARTESIAN_POINT('',(-1.936228954946E-013,0.253857579203)); +#72079 = CARTESIAN_POINT('',(-1.927347170749E-013,0.267493942839)); +#72080 = CARTESIAN_POINT('',(-1.962874307537E-013,0.281130306475)); +#72081 = CARTESIAN_POINT('',(-1.847411112976E-013,0.294766670112)); +#72082 = CARTESIAN_POINT('',(-2.273736754432E-013,0.308403033748)); +#72083 = CARTESIAN_POINT('',(-1.181277298201E-013,0.317493942839)); +#72084 = CARTESIAN_POINT('',(0.E+000,0.322039397385)); +#72085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72086 = PCURVE('',#41004,#72087); +#72087 = DEFINITIONAL_REPRESENTATION('',(#72088),#72092); +#72088 = LINE('',#72089,#72090); +#72089 = CARTESIAN_POINT('',(2.420762596622,1.313674285394)); +#72090 = VECTOR('',#72091,1.); +#72091 = DIRECTION('',(0.78162857303,-0.623744157346)); +#72092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72093 = ORIENTED_EDGE('',*,*,#71757,.F.); +#72094 = ORIENTED_EDGE('',*,*,#71959,.T.); +#72095 = ADVANCED_FACE('',(#72096),#71922,.T.); +#72096 = FACE_BOUND('',#72097,.F.); +#72097 = EDGE_LOOP('',(#72098,#72099,#72100,#72101,#72124,#72146)); +#72098 = ORIENTED_EDGE('',*,*,#71883,.F.); +#72099 = ORIENTED_EDGE('',*,*,#71981,.F.); +#72100 = ORIENTED_EDGE('',*,*,#72005,.F.); +#72101 = ORIENTED_EDGE('',*,*,#72102,.F.); +#72102 = EDGE_CURVE('',#72103,#72006,#72105,.T.); +#72103 = VERTEX_POINT('',#72104); +#72104 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); +#72105 = SURFACE_CURVE('',#72106,(#72110,#72117),.PCURVE_S1.); +#72106 = LINE('',#72107,#72108); +#72107 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); +#72108 = VECTOR('',#72109,1.); +#72109 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#72110 = PCURVE('',#71922,#72111); +#72111 = DEFINITIONAL_REPRESENTATION('',(#72112),#72116); +#72112 = LINE('',#72113,#72114); +#72113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72114 = VECTOR('',#72115,1.); +#72115 = DIRECTION('',(1.,0.E+000)); +#72116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72117 = PCURVE('',#41004,#72118); +#72118 = DEFINITIONAL_REPRESENTATION('',(#72119),#72123); +#72119 = LINE('',#72120,#72121); +#72120 = CARTESIAN_POINT('',(2.581486028353,1.03411419437)); +#72121 = VECTOR('',#72122,1.); +#72122 = DIRECTION('',(0.623744157346,0.78162857303)); +#72123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72124 = ORIENTED_EDGE('',*,*,#72125,.T.); +#72125 = EDGE_CURVE('',#72103,#72126,#72128,.T.); +#72126 = VERTEX_POINT('',#72127); +#72127 = CARTESIAN_POINT('',(-3.2,1.03411419437,2.581486028353)); +#72128 = SURFACE_CURVE('',#72129,(#72133,#72140),.PCURVE_S1.); +#72129 = LINE('',#72130,#72131); +#72130 = CARTESIAN_POINT('',(3.2,1.03411419437,2.581486028353)); +#72131 = VECTOR('',#72132,1.); +#72132 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#72133 = PCURVE('',#71922,#72134); +#72134 = DEFINITIONAL_REPRESENTATION('',(#72135),#72139); +#72135 = LINE('',#72136,#72137); +#72136 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72137 = VECTOR('',#72138,1.); +#72138 = DIRECTION('',(0.E+000,1.)); +#72139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72140 = PCURVE('',#49818,#72141); +#72141 = DEFINITIONAL_REPRESENTATION('',(#72142),#72145); +#72142 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72143,#72144),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,6.4),.PIECEWISE_BEZIER_KNOTS.); -#69751 = CARTESIAN_POINT('',(5.609661506313,0.E+000)); -#69752 = CARTESIAN_POINT('',(5.609661506313,6.4)); -#69753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69754 = ORIENTED_EDGE('',*,*,#69755,.T.); -#69755 = EDGE_CURVE('',#69734,#69447,#69756,.T.); -#69756 = SURFACE_CURVE('',#69757,(#69761,#69768),.PCURVE_S1.); -#69757 = LINE('',#69758,#69759); -#69758 = CARTESIAN_POINT('',(-3.2,1.03411419437,2.581486028353)); -#69759 = VECTOR('',#69760,1.); -#69760 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); -#69761 = PCURVE('',#69530,#69762); -#69762 = DEFINITIONAL_REPRESENTATION('',(#69763),#69767); -#69763 = LINE('',#69764,#69765); -#69764 = CARTESIAN_POINT('',(0.E+000,6.4)); -#69765 = VECTOR('',#69766,1.); -#69766 = DIRECTION('',(1.,0.E+000)); -#69767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69768 = PCURVE('',#38438,#69769); -#69769 = DEFINITIONAL_REPRESENTATION('',(#69770),#69774); -#69770 = LINE('',#69771,#69772); -#69771 = CARTESIAN_POINT('',(2.581486028353,1.03411419437)); -#69772 = VECTOR('',#69773,1.); -#69773 = DIRECTION('',(0.623744157346,0.78162857303)); -#69774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69775 = ADVANCED_FACE('',(#69776),#38612,.F.); -#69776 = FACE_BOUND('',#69777,.F.); -#69777 = EDGE_LOOP('',(#69778,#69779,#69780,#69781,#69782,#69803)); -#69778 = ORIENTED_EDGE('',*,*,#69659,.F.); -#69779 = ORIENTED_EDGE('',*,*,#69342,.T.); -#69780 = ORIENTED_EDGE('',*,*,#38596,.T.); -#69781 = ORIENTED_EDGE('',*,*,#47437,.T.); -#69782 = ORIENTED_EDGE('',*,*,#69783,.T.); -#69783 = EDGE_CURVE('',#47411,#69711,#69784,.T.); -#69784 = SURFACE_CURVE('',#69785,(#69790,#69797),.PCURVE_S1.); -#69785 = CIRCLE('',#69786,0.29); -#69786 = AXIS2_PLACEMENT_3D('',#69787,#69788,#69789); -#69787 = CARTESIAN_POINT('',(3.2,1.215,2.354813742174)); -#69788 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69789 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#69790 = PCURVE('',#38612,#69791); -#69791 = DEFINITIONAL_REPRESENTATION('',(#69792),#69796); -#69792 = CIRCLE('',#69793,0.29); -#69793 = AXIS2_PLACEMENT_2D('',#69794,#69795); -#69794 = CARTESIAN_POINT('',(2.354813742174,1.215)); -#69795 = DIRECTION('',(0.E+000,-1.)); -#69796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69797 = PCURVE('',#47426,#69798); -#69798 = DEFINITIONAL_REPRESENTATION('',(#69799),#69802); -#69799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69800,#69801),.UNSPECIFIED., +#72143 = CARTESIAN_POINT('',(5.609661506313,0.E+000)); +#72144 = CARTESIAN_POINT('',(5.609661506313,6.4)); +#72145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72146 = ORIENTED_EDGE('',*,*,#72147,.T.); +#72147 = EDGE_CURVE('',#72126,#71839,#72148,.T.); +#72148 = SURFACE_CURVE('',#72149,(#72153,#72160),.PCURVE_S1.); +#72149 = LINE('',#72150,#72151); +#72150 = CARTESIAN_POINT('',(-3.2,1.03411419437,2.581486028353)); +#72151 = VECTOR('',#72152,1.); +#72152 = DIRECTION('',(0.E+000,0.78162857303,0.623744157346)); +#72153 = PCURVE('',#71922,#72154); +#72154 = DEFINITIONAL_REPRESENTATION('',(#72155),#72159); +#72155 = LINE('',#72156,#72157); +#72156 = CARTESIAN_POINT('',(0.E+000,6.4)); +#72157 = VECTOR('',#72158,1.); +#72158 = DIRECTION('',(1.,0.E+000)); +#72159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72160 = PCURVE('',#40830,#72161); +#72161 = DEFINITIONAL_REPRESENTATION('',(#72162),#72166); +#72162 = LINE('',#72163,#72164); +#72163 = CARTESIAN_POINT('',(2.581486028353,1.03411419437)); +#72164 = VECTOR('',#72165,1.); +#72165 = DIRECTION('',(0.623744157346,0.78162857303)); +#72166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72167 = ADVANCED_FACE('',(#72168),#41004,.F.); +#72168 = FACE_BOUND('',#72169,.F.); +#72169 = EDGE_LOOP('',(#72170,#72171,#72172,#72173,#72174,#72195)); +#72170 = ORIENTED_EDGE('',*,*,#72051,.F.); +#72171 = ORIENTED_EDGE('',*,*,#71734,.T.); +#72172 = ORIENTED_EDGE('',*,*,#40988,.T.); +#72173 = ORIENTED_EDGE('',*,*,#49829,.T.); +#72174 = ORIENTED_EDGE('',*,*,#72175,.T.); +#72175 = EDGE_CURVE('',#49803,#72103,#72176,.T.); +#72176 = SURFACE_CURVE('',#72177,(#72182,#72189),.PCURVE_S1.); +#72177 = CIRCLE('',#72178,0.29); +#72178 = AXIS2_PLACEMENT_3D('',#72179,#72180,#72181); +#72179 = CARTESIAN_POINT('',(3.2,1.215,2.354813742174)); +#72180 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#72181 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#72182 = PCURVE('',#41004,#72183); +#72183 = DEFINITIONAL_REPRESENTATION('',(#72184),#72188); +#72184 = CIRCLE('',#72185,0.29); +#72185 = AXIS2_PLACEMENT_2D('',#72186,#72187); +#72186 = CARTESIAN_POINT('',(2.354813742174,1.215)); +#72187 = DIRECTION('',(0.E+000,-1.)); +#72188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72189 = PCURVE('',#49818,#72190); +#72190 = DEFINITIONAL_REPRESENTATION('',(#72191),#72194); +#72191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72192,#72193),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525928),.PIECEWISE_BEZIER_KNOTS.); -#69800 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#69801 = CARTESIAN_POINT('',(5.609661506313,0.E+000)); -#69802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69803 = ORIENTED_EDGE('',*,*,#69710,.T.); -#69804 = ADVANCED_FACE('',(#69805),#47426,.T.); -#69805 = FACE_BOUND('',#69806,.T.); -#69806 = EDGE_LOOP('',(#69807,#69808,#69809,#69830)); -#69807 = ORIENTED_EDGE('',*,*,#69783,.T.); -#69808 = ORIENTED_EDGE('',*,*,#69733,.T.); -#69809 = ORIENTED_EDGE('',*,*,#69810,.F.); -#69810 = EDGE_CURVE('',#47388,#69734,#69811,.T.); -#69811 = SURFACE_CURVE('',#69812,(#69817,#69823),.PCURVE_S1.); -#69812 = CIRCLE('',#69813,0.29); -#69813 = AXIS2_PLACEMENT_3D('',#69814,#69815,#69816); -#69814 = CARTESIAN_POINT('',(-3.2,1.215,2.354813742174)); -#69815 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#69816 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#69817 = PCURVE('',#47426,#69818); -#69818 = DEFINITIONAL_REPRESENTATION('',(#69819),#69822); -#69819 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69820,#69821),.UNSPECIFIED., +#72192 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72193 = CARTESIAN_POINT('',(5.609661506313,0.E+000)); +#72194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72195 = ORIENTED_EDGE('',*,*,#72102,.T.); +#72196 = ADVANCED_FACE('',(#72197),#49818,.T.); +#72197 = FACE_BOUND('',#72198,.T.); +#72198 = EDGE_LOOP('',(#72199,#72200,#72201,#72222)); +#72199 = ORIENTED_EDGE('',*,*,#72175,.T.); +#72200 = ORIENTED_EDGE('',*,*,#72125,.T.); +#72201 = ORIENTED_EDGE('',*,*,#72202,.F.); +#72202 = EDGE_CURVE('',#49780,#72126,#72203,.T.); +#72203 = SURFACE_CURVE('',#72204,(#72209,#72215),.PCURVE_S1.); +#72204 = CIRCLE('',#72205,0.29); +#72205 = AXIS2_PLACEMENT_3D('',#72206,#72207,#72208); +#72206 = CARTESIAN_POINT('',(-3.2,1.215,2.354813742174)); +#72207 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#72208 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#72209 = PCURVE('',#49818,#72210); +#72210 = DEFINITIONAL_REPRESENTATION('',(#72211),#72214); +#72211 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72212,#72213),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.897272525928),.PIECEWISE_BEZIER_KNOTS.); -#69820 = CARTESIAN_POINT('',(4.712388980385,6.4)); -#69821 = CARTESIAN_POINT('',(5.609661506313,6.4)); -#69822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69823 = PCURVE('',#38438,#69824); -#69824 = DEFINITIONAL_REPRESENTATION('',(#69825),#69829); -#69825 = CIRCLE('',#69826,0.29); -#69826 = AXIS2_PLACEMENT_2D('',#69827,#69828); -#69827 = CARTESIAN_POINT('',(2.354813742174,1.215)); -#69828 = DIRECTION('',(0.E+000,-1.)); -#69829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69830 = ORIENTED_EDGE('',*,*,#47410,.F.); -#69831 = ADVANCED_FACE('',(#69832),#38438,.T.); -#69832 = FACE_BOUND('',#69833,.F.); -#69833 = EDGE_LOOP('',(#69834,#69835,#69836,#69837,#69838,#69839)); -#69834 = ORIENTED_EDGE('',*,*,#69446,.F.); -#69835 = ORIENTED_EDGE('',*,*,#69755,.F.); -#69836 = ORIENTED_EDGE('',*,*,#69810,.F.); -#69837 = ORIENTED_EDGE('',*,*,#47387,.F.); -#69838 = ORIENTED_EDGE('',*,*,#38422,.F.); -#69839 = ORIENTED_EDGE('',*,*,#69320,.F.); -#69840 = ADVANCED_FACE('',(#69841),#43317,.T.); -#69841 = FACE_BOUND('',#69842,.T.); -#69842 = EDGE_LOOP('',(#69843,#69865,#69908,#69909)); -#69843 = ORIENTED_EDGE('',*,*,#69844,.F.); -#69844 = EDGE_CURVE('',#69845,#46629,#69847,.T.); -#69845 = VERTEX_POINT('',#69846); -#69846 = CARTESIAN_POINT('',(1.75,0.444999999747,1.35)); -#69847 = SURFACE_CURVE('',#69848,(#69853,#69859),.PCURVE_S1.); -#69848 = CIRCLE('',#69849,0.2); -#69849 = AXIS2_PLACEMENT_3D('',#69850,#69851,#69852); -#69850 = CARTESIAN_POINT('',(1.55,0.445,1.35)); -#69851 = DIRECTION('',(0.E+000,0.E+000,1.)); -#69852 = DIRECTION('',(1.,0.E+000,0.E+000)); -#69853 = PCURVE('',#43317,#69854); -#69854 = DEFINITIONAL_REPRESENTATION('',(#69855),#69858); -#69855 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69856,#69857),.UNSPECIFIED., +#72212 = CARTESIAN_POINT('',(4.712388980385,6.4)); +#72213 = CARTESIAN_POINT('',(5.609661506313,6.4)); +#72214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72215 = PCURVE('',#40830,#72216); +#72216 = DEFINITIONAL_REPRESENTATION('',(#72217),#72221); +#72217 = CIRCLE('',#72218,0.29); +#72218 = AXIS2_PLACEMENT_2D('',#72219,#72220); +#72219 = CARTESIAN_POINT('',(2.354813742174,1.215)); +#72220 = DIRECTION('',(0.E+000,-1.)); +#72221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72222 = ORIENTED_EDGE('',*,*,#49802,.F.); +#72223 = ADVANCED_FACE('',(#72224),#40830,.T.); +#72224 = FACE_BOUND('',#72225,.F.); +#72225 = EDGE_LOOP('',(#72226,#72227,#72228,#72229,#72230,#72231)); +#72226 = ORIENTED_EDGE('',*,*,#71838,.F.); +#72227 = ORIENTED_EDGE('',*,*,#72147,.F.); +#72228 = ORIENTED_EDGE('',*,*,#72202,.F.); +#72229 = ORIENTED_EDGE('',*,*,#49779,.F.); +#72230 = ORIENTED_EDGE('',*,*,#40814,.F.); +#72231 = ORIENTED_EDGE('',*,*,#71712,.F.); +#72232 = ADVANCED_FACE('',(#72233),#45709,.T.); +#72233 = FACE_BOUND('',#72234,.T.); +#72234 = EDGE_LOOP('',(#72235,#72257,#72300,#72301)); +#72235 = ORIENTED_EDGE('',*,*,#72236,.F.); +#72236 = EDGE_CURVE('',#72237,#49021,#72239,.T.); +#72237 = VERTEX_POINT('',#72238); +#72238 = CARTESIAN_POINT('',(1.75,0.444999999747,1.35)); +#72239 = SURFACE_CURVE('',#72240,(#72245,#72251),.PCURVE_S1.); +#72240 = CIRCLE('',#72241,0.2); +#72241 = AXIS2_PLACEMENT_3D('',#72242,#72243,#72244); +#72242 = CARTESIAN_POINT('',(1.55,0.445,1.35)); +#72243 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72244 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72245 = PCURVE('',#45709,#72246); +#72246 = DEFINITIONAL_REPRESENTATION('',(#72247),#72250); +#72247 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72248,#72249),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.57079632725),.PIECEWISE_BEZIER_KNOTS.); -#69856 = CARTESIAN_POINT('',(0.E+000,2.5)); -#69857 = CARTESIAN_POINT('',(1.57079632725,2.5)); -#69858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72248 = CARTESIAN_POINT('',(0.E+000,2.5)); +#72249 = CARTESIAN_POINT('',(1.57079632725,2.5)); +#72250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#69859 = PCURVE('',#46644,#69860); -#69860 = DEFINITIONAL_REPRESENTATION('',(#69861),#69864); -#69861 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69862,#69863),.UNSPECIFIED., +#72251 = PCURVE('',#49036,#72252); +#72252 = DEFINITIONAL_REPRESENTATION('',(#72253),#72256); +#72253 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72254,#72255),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.57079632725),.PIECEWISE_BEZIER_KNOTS.); -#69862 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#69863 = CARTESIAN_POINT('',(0.E+000,-0.785400764451)); -#69864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69865 = ORIENTED_EDGE('',*,*,#69866,.F.); -#69866 = EDGE_CURVE('',#43273,#69845,#69867,.T.); -#69867 = SURFACE_CURVE('',#69868,(#69872,#69901),.PCURVE_S1.); -#69868 = LINE('',#69869,#69870); -#69869 = CARTESIAN_POINT('',(1.75,0.445,-1.15)); -#69870 = VECTOR('',#69871,1.); -#69871 = DIRECTION('',(0.E+000,-1.011120076555E-010,1.)); -#69872 = PCURVE('',#43317,#69873); -#69873 = DEFINITIONAL_REPRESENTATION('',(#69874),#69900); -#69874 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69875,#69876,#69877,#69878, - #69879,#69880,#69881,#69882,#69883,#69884,#69885,#69886,#69887, - #69888,#69889,#69890,#69891,#69892,#69893,#69894,#69895,#69896, - #69897,#69898,#69899),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#72254 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#72255 = CARTESIAN_POINT('',(0.E+000,-0.785400764451)); +#72256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72257 = ORIENTED_EDGE('',*,*,#72258,.F.); +#72258 = EDGE_CURVE('',#45665,#72237,#72259,.T.); +#72259 = SURFACE_CURVE('',#72260,(#72264,#72293),.PCURVE_S1.); +#72260 = LINE('',#72261,#72262); +#72261 = CARTESIAN_POINT('',(1.75,0.445,-1.15)); +#72262 = VECTOR('',#72263,1.); +#72263 = DIRECTION('',(0.E+000,-1.011120076555E-010,1.)); +#72264 = PCURVE('',#45709,#72265); +#72265 = DEFINITIONAL_REPRESENTATION('',(#72266),#72292); +#72266 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72267,#72268,#72269,#72270, + #72271,#72272,#72273,#72274,#72275,#72276,#72277,#72278,#72279, + #72280,#72281,#72282,#72283,#72284,#72285,#72286,#72287,#72288, + #72289,#72290,#72291),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#69875 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#69876 = CARTESIAN_POINT('',(-1.915001490715E-011,3.787878787879E-002)); -#69877 = CARTESIAN_POINT('',(-5.745004472146E-011,0.113636363636)); -#69878 = CARTESIAN_POINT('',(-1.148992012645E-010,0.227272727273)); -#69879 = CARTESIAN_POINT('',(-1.723501341644E-010,0.340909090909)); -#69880 = CARTESIAN_POINT('',(-2.298010670643E-010,0.454545454545)); -#69881 = CARTESIAN_POINT('',(-2.872502236073E-010,0.568181818182)); -#69882 = CARTESIAN_POINT('',(-3.447011565072E-010,0.681818181818)); -#69883 = CARTESIAN_POINT('',(-4.021503130502E-010,0.795454545455)); -#69884 = CARTESIAN_POINT('',(-4.595976932364E-010,0.909090909091)); -#69885 = CARTESIAN_POINT('',(-5.170512906716E-010,1.022727272727)); -#69886 = CARTESIAN_POINT('',(-5.745004472146E-010,1.136363636364)); -#69887 = CARTESIAN_POINT('',(-6.319487155793E-010,1.25)); -#69888 = CARTESIAN_POINT('',(-6.893978721223E-010,1.363636363636)); -#69889 = CARTESIAN_POINT('',(-7.468550222711E-010,1.477272727273)); -#69890 = CARTESIAN_POINT('',(-8.042775334616E-010,1.590909090909)); -#69891 = CARTESIAN_POINT('',(-8.61833271415E-010,1.704545454545)); -#69892 = CARTESIAN_POINT('',(-9.18884524026E-010,1.818181818182)); -#69893 = CARTESIAN_POINT('',(-9.778258203141E-010,1.931818181818)); -#69894 = CARTESIAN_POINT('',(-1.029710539058E-009,2.045454545455)); -#69895 = CARTESIAN_POINT('',(-1.107927971589E-009,2.159090909091)); -#69896 = CARTESIAN_POINT('',(-1.087876455586E-009,2.272727272727)); -#69897 = CARTESIAN_POINT('',(-1.434562690861E-009,2.386363636364)); -#69898 = CARTESIAN_POINT('',(-7.532339196814E-010,2.462121212121)); -#69899 = CARTESIAN_POINT('',(0.E+000,2.5)); -#69900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69901 = PCURVE('',#43288,#69902); -#69902 = DEFINITIONAL_REPRESENTATION('',(#69903),#69907); -#69903 = LINE('',#69904,#69905); -#69904 = CARTESIAN_POINT('',(0.2,0.E+000)); -#69905 = VECTOR('',#69906,1.); -#69906 = DIRECTION('',(-1.011120076555E-010,1.)); -#69907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69908 = ORIENTED_EDGE('',*,*,#43300,.T.); -#69909 = ORIENTED_EDGE('',*,*,#46890,.T.); -#69910 = ADVANCED_FACE('',(#69911),#46644,.T.); -#69911 = FACE_BOUND('',#69912,.T.); -#69912 = EDGE_LOOP('',(#69913,#69914,#69915)); -#69913 = ORIENTED_EDGE('',*,*,#69844,.T.); -#69914 = ORIENTED_EDGE('',*,*,#46628,.F.); -#69915 = ORIENTED_EDGE('',*,*,#69916,.T.); -#69916 = EDGE_CURVE('',#45199,#69845,#69917,.T.); -#69917 = SURFACE_CURVE('',#69918,(#69923,#69952),.PCURVE_S1.); -#69918 = CIRCLE('',#69919,0.2); -#69919 = AXIS2_PLACEMENT_3D('',#69920,#69921,#69922); -#69920 = CARTESIAN_POINT('',(1.55,0.445,1.35)); -#69921 = DIRECTION('',(0.E+000,1.,0.E+000)); -#69922 = DIRECTION('',(0.E+000,0.E+000,1.)); -#69923 = PCURVE('',#46644,#69924); -#69924 = DEFINITIONAL_REPRESENTATION('',(#69925),#69951); -#69925 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69926,#69927,#69928,#69929, - #69930,#69931,#69932,#69933,#69934,#69935,#69936,#69937,#69938, - #69939,#69940,#69941,#69942,#69943,#69944,#69945,#69946,#69947, - #69948,#69949,#69950),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#72267 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72268 = CARTESIAN_POINT('',(-1.915001490715E-011,3.787878787879E-002)); +#72269 = CARTESIAN_POINT('',(-5.745004472146E-011,0.113636363636)); +#72270 = CARTESIAN_POINT('',(-1.148992012645E-010,0.227272727273)); +#72271 = CARTESIAN_POINT('',(-1.723501341644E-010,0.340909090909)); +#72272 = CARTESIAN_POINT('',(-2.298010670643E-010,0.454545454545)); +#72273 = CARTESIAN_POINT('',(-2.872502236073E-010,0.568181818182)); +#72274 = CARTESIAN_POINT('',(-3.447011565072E-010,0.681818181818)); +#72275 = CARTESIAN_POINT('',(-4.021503130502E-010,0.795454545455)); +#72276 = CARTESIAN_POINT('',(-4.595976932364E-010,0.909090909091)); +#72277 = CARTESIAN_POINT('',(-5.170512906716E-010,1.022727272727)); +#72278 = CARTESIAN_POINT('',(-5.745004472146E-010,1.136363636364)); +#72279 = CARTESIAN_POINT('',(-6.319487155793E-010,1.25)); +#72280 = CARTESIAN_POINT('',(-6.893978721223E-010,1.363636363636)); +#72281 = CARTESIAN_POINT('',(-7.468550222711E-010,1.477272727273)); +#72282 = CARTESIAN_POINT('',(-8.042775334616E-010,1.590909090909)); +#72283 = CARTESIAN_POINT('',(-8.61833271415E-010,1.704545454545)); +#72284 = CARTESIAN_POINT('',(-9.18884524026E-010,1.818181818182)); +#72285 = CARTESIAN_POINT('',(-9.778258203141E-010,1.931818181818)); +#72286 = CARTESIAN_POINT('',(-1.029710539058E-009,2.045454545455)); +#72287 = CARTESIAN_POINT('',(-1.107927971589E-009,2.159090909091)); +#72288 = CARTESIAN_POINT('',(-1.087876455586E-009,2.272727272727)); +#72289 = CARTESIAN_POINT('',(-1.434562690861E-009,2.386363636364)); +#72290 = CARTESIAN_POINT('',(-7.532339196814E-010,2.462121212121)); +#72291 = CARTESIAN_POINT('',(0.E+000,2.5)); +#72292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72293 = PCURVE('',#45680,#72294); +#72294 = DEFINITIONAL_REPRESENTATION('',(#72295),#72299); +#72295 = LINE('',#72296,#72297); +#72296 = CARTESIAN_POINT('',(0.2,0.E+000)); +#72297 = VECTOR('',#72298,1.); +#72298 = DIRECTION('',(-1.011120076555E-010,1.)); +#72299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72300 = ORIENTED_EDGE('',*,*,#45692,.T.); +#72301 = ORIENTED_EDGE('',*,*,#49282,.T.); +#72302 = ADVANCED_FACE('',(#72303),#49036,.T.); +#72303 = FACE_BOUND('',#72304,.T.); +#72304 = EDGE_LOOP('',(#72305,#72306,#72307)); +#72305 = ORIENTED_EDGE('',*,*,#72236,.T.); +#72306 = ORIENTED_EDGE('',*,*,#49020,.F.); +#72307 = ORIENTED_EDGE('',*,*,#72308,.T.); +#72308 = EDGE_CURVE('',#47591,#72237,#72309,.T.); +#72309 = SURFACE_CURVE('',#72310,(#72315,#72344),.PCURVE_S1.); +#72310 = CIRCLE('',#72311,0.2); +#72311 = AXIS2_PLACEMENT_3D('',#72312,#72313,#72314); +#72312 = CARTESIAN_POINT('',(1.55,0.445,1.35)); +#72313 = DIRECTION('',(0.E+000,1.,0.E+000)); +#72314 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72315 = PCURVE('',#49036,#72316); +#72316 = DEFINITIONAL_REPRESENTATION('',(#72317),#72343); +#72317 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72318,#72319,#72320,#72321, + #72322,#72323,#72324,#72325,#72326,#72327,#72328,#72329,#72330, + #72331,#72332,#72333,#72334,#72335,#72336,#72337,#72338,#72339, + #72340,#72341,#72342),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -86229,72 +89218,72 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69926 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#69927 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); -#69928 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); -#69929 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); -#69930 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); -#69931 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); -#69932 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); -#69933 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); -#69934 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); -#69935 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); -#69936 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); -#69937 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); -#69938 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); -#69939 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); -#69940 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); -#69941 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); -#69942 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); -#69943 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); -#69944 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); -#69945 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); -#69946 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); -#69947 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); -#69948 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); -#69949 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); -#69950 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#69951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69952 = PCURVE('',#45241,#69953); -#69953 = DEFINITIONAL_REPRESENTATION('',(#69954),#69957); -#69954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69955,#69956),.UNSPECIFIED., +#72318 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#72319 = CARTESIAN_POINT('',(1.553966922022,1.682882720771E-002)); +#72320 = CARTESIAN_POINT('',(1.520309026475,5.048729675432E-002)); +#72321 = CARTESIAN_POINT('',(1.469563849108,0.100845463732)); +#72322 = CARTESIAN_POINT('',(1.418301061513,0.150943739087)); +#72323 = CARTESIAN_POINT('',(1.366255087971,0.200646068947)); +#72324 = CARTESIAN_POINT('',(1.313153258009,0.249809615412)); +#72325 = CARTESIAN_POINT('',(1.258713489033,0.298281872349)); +#72326 = CARTESIAN_POINT('',(1.202643080377,0.345898113237)); +#72327 = CARTESIAN_POINT('',(1.14463829297,0.392478602449)); +#72328 = CARTESIAN_POINT('',(1.084385330685,0.437825766199)); +#72329 = CARTESIAN_POINT('',(1.0215632724,0.481721377103)); +#72330 = CARTESIAN_POINT('',(0.955849731145,0.523923935729)); +#72331 = CARTESIAN_POINT('',(0.88693015618,0.564166524826)); +#72332 = CARTESIAN_POINT('',(0.814511777583,0.602155551941)); +#72333 = CARTESIAN_POINT('',(0.73834309497,0.637570957959)); +#72334 = CARTESIAN_POINT('',(0.658239370331,0.67006861946)); +#72335 = CARTESIAN_POINT('',(0.574113669819,0.699285813622)); +#72336 = CARTESIAN_POINT('',(0.486011264442,0.724850455568)); +#72337 = CARTESIAN_POINT('',(0.394143459672,0.746395015155)); +#72338 = CARTESIAN_POINT('',(0.298912753813,0.763573611315)); +#72339 = CARTESIAN_POINT('',(0.200926272835,0.77608643309)); +#72340 = CARTESIAN_POINT('',(0.100970159821,0.78368965162)); +#72341 = CARTESIAN_POINT('',(3.366595593241E-002,0.785403559439)); +#72342 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#72343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72344 = PCURVE('',#47633,#72345); +#72345 = DEFINITIONAL_REPRESENTATION('',(#72346),#72349); +#72346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72347,#72348),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#69955 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); -#69956 = CARTESIAN_POINT('',(1.570796326795,0.215514631548)); -#69957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#69958 = ADVANCED_FACE('',(#69959),#45241,.T.); -#69959 = FACE_BOUND('',#69960,.T.); -#69960 = EDGE_LOOP('',(#69961,#69962,#70007,#70027)); -#69961 = ORIENTED_EDGE('',*,*,#45225,.F.); -#69962 = ORIENTED_EDGE('',*,*,#69963,.T.); -#69963 = EDGE_CURVE('',#45226,#69964,#69966,.T.); -#69964 = VERTEX_POINT('',#69965); -#69965 = CARTESIAN_POINT('',(1.75,0.245,1.35)); -#69966 = SURFACE_CURVE('',#69967,(#69972,#69978),.PCURVE_S1.); -#69967 = CIRCLE('',#69968,0.2); -#69968 = AXIS2_PLACEMENT_3D('',#69969,#69970,#69971); -#69969 = CARTESIAN_POINT('',(1.55,0.245,1.35)); -#69970 = DIRECTION('',(0.E+000,1.,0.E+000)); -#69971 = DIRECTION('',(0.E+000,0.E+000,1.)); -#69972 = PCURVE('',#45241,#69973); -#69973 = DEFINITIONAL_REPRESENTATION('',(#69974),#69977); -#69974 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#69975,#69976),.UNSPECIFIED., +#72347 = CARTESIAN_POINT('',(0.E+000,0.215514631548)); +#72348 = CARTESIAN_POINT('',(1.570796326795,0.215514631548)); +#72349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72350 = ADVANCED_FACE('',(#72351),#47633,.T.); +#72351 = FACE_BOUND('',#72352,.T.); +#72352 = EDGE_LOOP('',(#72353,#72354,#72399,#72419)); +#72353 = ORIENTED_EDGE('',*,*,#47617,.F.); +#72354 = ORIENTED_EDGE('',*,*,#72355,.T.); +#72355 = EDGE_CURVE('',#47618,#72356,#72358,.T.); +#72356 = VERTEX_POINT('',#72357); +#72357 = CARTESIAN_POINT('',(1.75,0.245,1.35)); +#72358 = SURFACE_CURVE('',#72359,(#72364,#72370),.PCURVE_S1.); +#72359 = CIRCLE('',#72360,0.2); +#72360 = AXIS2_PLACEMENT_3D('',#72361,#72362,#72363); +#72361 = CARTESIAN_POINT('',(1.55,0.245,1.35)); +#72362 = DIRECTION('',(0.E+000,1.,0.E+000)); +#72363 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72364 = PCURVE('',#47633,#72365); +#72365 = DEFINITIONAL_REPRESENTATION('',(#72366),#72369); +#72366 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72367,#72368),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#69975 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); -#69976 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); -#69977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72367 = CARTESIAN_POINT('',(0.E+000,1.55146315484E-002)); +#72368 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); +#72369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#69978 = PCURVE('',#45718,#69979); -#69979 = DEFINITIONAL_REPRESENTATION('',(#69980),#70006); -#69980 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#69981,#69982,#69983,#69984, - #69985,#69986,#69987,#69988,#69989,#69990,#69991,#69992,#69993, - #69994,#69995,#69996,#69997,#69998,#69999,#70000,#70001,#70002, - #70003,#70004,#70005),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#72370 = PCURVE('',#48110,#72371); +#72371 = DEFINITIONAL_REPRESENTATION('',(#72372),#72398); +#72372 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72373,#72374,#72375,#72376, + #72377,#72378,#72379,#72380,#72381,#72382,#72383,#72384,#72385, + #72386,#72387,#72388,#72389,#72390,#72391,#72392,#72393,#72394, + #72395,#72396,#72397),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,7.139983303613E-002,0.142799666072, 0.214199499108,0.285599332145,0.356999165181,0.428398998217, 0.499798831253,0.571198664289,0.642598497325,0.713998330361, @@ -86302,6884 +89291,6884 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.070997495542,1.142397328578,1.213797161614,1.28519699465, 1.356596827687,1.427996660723,1.499396493759,1.570796326795), .QUASI_UNIFORM_KNOTS.); -#69981 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#69982 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); -#69983 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); -#69984 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); -#69985 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); -#69986 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); -#69987 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); -#69988 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); -#69989 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); -#69990 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); -#69991 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); -#69992 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); -#69993 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); -#69994 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); -#69995 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); -#69996 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); -#69997 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); -#69998 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); -#69999 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); -#70000 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); -#70001 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); -#70002 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); -#70003 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); -#70004 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); -#70005 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#70006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70007 = ORIENTED_EDGE('',*,*,#70008,.T.); -#70008 = EDGE_CURVE('',#69964,#69845,#70009,.T.); -#70009 = SURFACE_CURVE('',#70010,(#70014,#70020),.PCURVE_S1.); -#70010 = LINE('',#70011,#70012); -#70011 = CARTESIAN_POINT('',(1.75,0.245000000091,1.35)); -#70012 = VECTOR('',#70013,1.); -#70013 = DIRECTION('',(0.E+000,1.,0.E+000)); -#70014 = PCURVE('',#45241,#70015); -#70015 = DEFINITIONAL_REPRESENTATION('',(#70016),#70019); -#70016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70017,#70018),.UNSPECIFIED., +#72373 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#72374 = CARTESIAN_POINT('',(1.553967009543,-1.682891473722E-002)); +#72375 = CARTESIAN_POINT('',(1.520309289075,-5.048755934974E-002)); +#72376 = CARTESIAN_POINT('',(1.46956437295,-0.100845989589)); +#72377 = CARTESIAN_POINT('',(1.418301843815,-0.150944529522)); +#72378 = CARTESIAN_POINT('',(1.366256124304,-0.200647125886)); +#72379 = CARTESIAN_POINT('',(1.313154542003,-0.249810941321)); +#72380 = CARTESIAN_POINT('',(1.258715011959,-0.298283470138)); +#72381 = CARTESIAN_POINT('',(1.2026448306,-0.345899986119)); +#72382 = CARTESIAN_POINT('',(1.144640255268,-0.39248075374)); +#72383 = CARTESIAN_POINT('',(1.084387485434,-0.437828199055)); +#72384 = CARTESIAN_POINT('',(1.021565594624,-0.481724094158)); +#72385 = CARTESIAN_POINT('',(0.955852189481,-0.523926938631)); +#72386 = CARTESIAN_POINT('',(0.886932711819,-0.564169813636)); +#72387 = CARTESIAN_POINT('',(0.81451438333,-0.602159124396)); +#72388 = CARTESIAN_POINT('',(0.738345694612,-0.637574808588)); +#72389 = CARTESIAN_POINT('',(0.658241898625,-0.670072738588)); +#72390 = CARTESIAN_POINT('',(0.574116053437,-0.699290186326)); +#72391 = CARTESIAN_POINT('',(0.486013424267,-0.724855060691)); +#72392 = CARTESIAN_POINT('',(0.394145314716,-0.746399824572)); +#72393 = CARTESIAN_POINT('',(0.298914226725,-0.763578589621)); +#72394 = CARTESIAN_POINT('',(0.200927296733,-0.776091538025)); +#72395 = CARTESIAN_POINT('',(0.10097068484,-0.783694834972)); +#72396 = CARTESIAN_POINT('',(3.366613131264E-002,-0.785408760833)); +#72397 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#72398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72399 = ORIENTED_EDGE('',*,*,#72400,.T.); +#72400 = EDGE_CURVE('',#72356,#72237,#72401,.T.); +#72401 = SURFACE_CURVE('',#72402,(#72406,#72412),.PCURVE_S1.); +#72402 = LINE('',#72403,#72404); +#72403 = CARTESIAN_POINT('',(1.75,0.245000000091,1.35)); +#72404 = VECTOR('',#72405,1.); +#72405 = DIRECTION('',(0.E+000,1.,0.E+000)); +#72406 = PCURVE('',#47633,#72407); +#72407 = DEFINITIONAL_REPRESENTATION('',(#72408),#72411); +#72408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72409,#72410),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.199999999747),.PIECEWISE_BEZIER_KNOTS.); -#70017 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); -#70018 = CARTESIAN_POINT('',(1.570796326795,0.215514631296)); -#70019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70020 = PCURVE('',#43288,#70021); -#70021 = DEFINITIONAL_REPRESENTATION('',(#70022),#70026); -#70022 = LINE('',#70023,#70024); -#70023 = CARTESIAN_POINT('',(9.059999972472E-011,2.5)); -#70024 = VECTOR('',#70025,1.); -#70025 = DIRECTION('',(1.,0.E+000)); -#70026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70027 = ORIENTED_EDGE('',*,*,#69916,.F.); -#70028 = ADVANCED_FACE('',(#70029),#43288,.T.); -#70029 = FACE_BOUND('',#70030,.F.); -#70030 = EDGE_LOOP('',(#70031,#70032,#70033,#70034)); -#70031 = ORIENTED_EDGE('',*,*,#70008,.T.); -#70032 = ORIENTED_EDGE('',*,*,#69866,.F.); -#70033 = ORIENTED_EDGE('',*,*,#43272,.F.); -#70034 = ORIENTED_EDGE('',*,*,#70035,.T.); -#70035 = EDGE_CURVE('',#43245,#69964,#70036,.T.); -#70036 = SURFACE_CURVE('',#70037,(#70041,#70048),.PCURVE_S1.); -#70037 = LINE('',#70038,#70039); -#70038 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); -#70039 = VECTOR('',#70040,1.); -#70040 = DIRECTION('',(0.E+000,3.625455491374E-011,1.)); -#70041 = PCURVE('',#43288,#70042); -#70042 = DEFINITIONAL_REPRESENTATION('',(#70043),#70047); -#70043 = LINE('',#70044,#70045); -#70044 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#70045 = VECTOR('',#70046,1.); -#70046 = DIRECTION('',(3.625455491374E-011,1.)); -#70047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70048 = PCURVE('',#43261,#70049); -#70049 = DEFINITIONAL_REPRESENTATION('',(#70050),#70076); -#70050 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#70051,#70052,#70053,#70054, - #70055,#70056,#70057,#70058,#70059,#70060,#70061,#70062,#70063, - #70064,#70065,#70066,#70067,#70068,#70069,#70070,#70071,#70072, - #70073,#70074,#70075),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#72409 = CARTESIAN_POINT('',(1.570796326795,1.55146315484E-002)); +#72410 = CARTESIAN_POINT('',(1.570796326795,0.215514631296)); +#72411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72412 = PCURVE('',#45680,#72413); +#72413 = DEFINITIONAL_REPRESENTATION('',(#72414),#72418); +#72414 = LINE('',#72415,#72416); +#72415 = CARTESIAN_POINT('',(9.059999972472E-011,2.5)); +#72416 = VECTOR('',#72417,1.); +#72417 = DIRECTION('',(1.,0.E+000)); +#72418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72419 = ORIENTED_EDGE('',*,*,#72308,.F.); +#72420 = ADVANCED_FACE('',(#72421),#45680,.T.); +#72421 = FACE_BOUND('',#72422,.F.); +#72422 = EDGE_LOOP('',(#72423,#72424,#72425,#72426)); +#72423 = ORIENTED_EDGE('',*,*,#72400,.T.); +#72424 = ORIENTED_EDGE('',*,*,#72258,.F.); +#72425 = ORIENTED_EDGE('',*,*,#45664,.F.); +#72426 = ORIENTED_EDGE('',*,*,#72427,.T.); +#72427 = EDGE_CURVE('',#45637,#72356,#72428,.T.); +#72428 = SURFACE_CURVE('',#72429,(#72433,#72440),.PCURVE_S1.); +#72429 = LINE('',#72430,#72431); +#72430 = CARTESIAN_POINT('',(1.75,0.245,-1.15)); +#72431 = VECTOR('',#72432,1.); +#72432 = DIRECTION('',(0.E+000,3.625455491374E-011,1.)); +#72433 = PCURVE('',#45680,#72434); +#72434 = DEFINITIONAL_REPRESENTATION('',(#72435),#72439); +#72435 = LINE('',#72436,#72437); +#72436 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72437 = VECTOR('',#72438,1.); +#72438 = DIRECTION('',(3.625455491374E-011,1.)); +#72439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72440 = PCURVE('',#45653,#72441); +#72441 = DEFINITIONAL_REPRESENTATION('',(#72442),#72468); +#72442 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72443,#72444,#72445,#72446, + #72447,#72448,#72449,#72450,#72451,#72452,#72453,#72454,#72455, + #72456,#72457,#72458,#72459,#72460,#72461,#72462,#72463,#72464, + #72465,#72466,#72467),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,0.113636363636,0.227272727273, 0.340909090909,0.454545454545,0.568181818182,0.681818181818, 0.795454545455,0.909090909091,1.022727272727,1.136363636364,1.25, 1.363636363636,1.477272727273,1.590909090909,1.704545454545, 1.818181818182,1.931818181818,2.045454545455,2.159090909091, 2.272727272727,2.386363636364,2.5),.QUASI_UNIFORM_KNOTS.); -#70051 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#70052 = CARTESIAN_POINT('',(6.283185307186,3.787878787879E-002)); -#70053 = CARTESIAN_POINT('',(6.2831853072,0.113636363636)); -#70054 = CARTESIAN_POINT('',(6.283185307221,0.227272727273)); -#70055 = CARTESIAN_POINT('',(6.283185307241,0.340909090909)); -#70056 = CARTESIAN_POINT('',(6.283185307262,0.454545454545)); -#70057 = CARTESIAN_POINT('',(6.283185307283,0.568181818182)); -#70058 = CARTESIAN_POINT('',(6.283185307303,0.681818181818)); -#70059 = CARTESIAN_POINT('',(6.283185307324,0.795454545455)); -#70060 = CARTESIAN_POINT('',(6.283185307344,0.909090909091)); -#70061 = CARTESIAN_POINT('',(6.283185307365,1.022727272727)); -#70062 = CARTESIAN_POINT('',(6.283185307386,1.136363636364)); -#70063 = CARTESIAN_POINT('',(6.283185307406,1.25)); -#70064 = CARTESIAN_POINT('',(6.283185307427,1.363636363636)); -#70065 = CARTESIAN_POINT('',(6.283185307447,1.477272727273)); -#70066 = CARTESIAN_POINT('',(6.283185307468,1.590909090909)); -#70067 = CARTESIAN_POINT('',(6.283185307489,1.704545454545)); -#70068 = CARTESIAN_POINT('',(6.283185307509,1.818181818182)); -#70069 = CARTESIAN_POINT('',(6.28318530753,1.931818181818)); -#70070 = CARTESIAN_POINT('',(6.283185307549,2.045454545455)); -#70071 = CARTESIAN_POINT('',(6.283185307577,2.159090909091)); -#70072 = CARTESIAN_POINT('',(6.28318530757,2.272727272727)); -#70073 = CARTESIAN_POINT('',(6.283185307694,2.386363636364)); -#70074 = CARTESIAN_POINT('',(6.28318530745,2.462121212121)); -#70075 = CARTESIAN_POINT('',(6.28318530718,2.5)); -#70076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70077 = ADVANCED_FACE('',(#70078),#43261,.T.); -#70078 = FACE_BOUND('',#70079,.T.); -#70079 = EDGE_LOOP('',(#70080,#70100,#70101,#70102)); -#70080 = ORIENTED_EDGE('',*,*,#70081,.F.); -#70081 = EDGE_CURVE('',#45683,#69964,#70082,.T.); -#70082 = SURFACE_CURVE('',#70083,(#70088,#70094),.PCURVE_S1.); -#70083 = CIRCLE('',#70084,0.2); -#70084 = AXIS2_PLACEMENT_3D('',#70085,#70086,#70087); -#70085 = CARTESIAN_POINT('',(1.55,0.245,1.35)); -#70086 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70087 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#70088 = PCURVE('',#43261,#70089); -#70089 = DEFINITIONAL_REPRESENTATION('',(#70090),#70093); -#70090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70091,#70092),.UNSPECIFIED., +#72443 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#72444 = CARTESIAN_POINT('',(6.283185307186,3.787878787879E-002)); +#72445 = CARTESIAN_POINT('',(6.2831853072,0.113636363636)); +#72446 = CARTESIAN_POINT('',(6.283185307221,0.227272727273)); +#72447 = CARTESIAN_POINT('',(6.283185307241,0.340909090909)); +#72448 = CARTESIAN_POINT('',(6.283185307262,0.454545454545)); +#72449 = CARTESIAN_POINT('',(6.283185307283,0.568181818182)); +#72450 = CARTESIAN_POINT('',(6.283185307303,0.681818181818)); +#72451 = CARTESIAN_POINT('',(6.283185307324,0.795454545455)); +#72452 = CARTESIAN_POINT('',(6.283185307344,0.909090909091)); +#72453 = CARTESIAN_POINT('',(6.283185307365,1.022727272727)); +#72454 = CARTESIAN_POINT('',(6.283185307386,1.136363636364)); +#72455 = CARTESIAN_POINT('',(6.283185307406,1.25)); +#72456 = CARTESIAN_POINT('',(6.283185307427,1.363636363636)); +#72457 = CARTESIAN_POINT('',(6.283185307447,1.477272727273)); +#72458 = CARTESIAN_POINT('',(6.283185307468,1.590909090909)); +#72459 = CARTESIAN_POINT('',(6.283185307489,1.704545454545)); +#72460 = CARTESIAN_POINT('',(6.283185307509,1.818181818182)); +#72461 = CARTESIAN_POINT('',(6.28318530753,1.931818181818)); +#72462 = CARTESIAN_POINT('',(6.283185307549,2.045454545455)); +#72463 = CARTESIAN_POINT('',(6.283185307577,2.159090909091)); +#72464 = CARTESIAN_POINT('',(6.28318530757,2.272727272727)); +#72465 = CARTESIAN_POINT('',(6.283185307694,2.386363636364)); +#72466 = CARTESIAN_POINT('',(6.28318530745,2.462121212121)); +#72467 = CARTESIAN_POINT('',(6.28318530718,2.5)); +#72468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72469 = ADVANCED_FACE('',(#72470),#45653,.T.); +#72470 = FACE_BOUND('',#72471,.T.); +#72471 = EDGE_LOOP('',(#72472,#72492,#72493,#72494)); +#72472 = ORIENTED_EDGE('',*,*,#72473,.F.); +#72473 = EDGE_CURVE('',#48075,#72356,#72474,.T.); +#72474 = SURFACE_CURVE('',#72475,(#72480,#72486),.PCURVE_S1.); +#72475 = CIRCLE('',#72476,0.2); +#72476 = AXIS2_PLACEMENT_3D('',#72477,#72478,#72479); +#72477 = CARTESIAN_POINT('',(1.55,0.245,1.35)); +#72478 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72479 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#72480 = PCURVE('',#45653,#72481); +#72481 = DEFINITIONAL_REPRESENTATION('',(#72482),#72485); +#72482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72483,#72484),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70091 = CARTESIAN_POINT('',(4.712388980385,2.5)); -#70092 = CARTESIAN_POINT('',(6.28318530718,2.5)); -#70093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72483 = CARTESIAN_POINT('',(4.712388980385,2.5)); +#72484 = CARTESIAN_POINT('',(6.28318530718,2.5)); +#72485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70094 = PCURVE('',#45718,#70095); -#70095 = DEFINITIONAL_REPRESENTATION('',(#70096),#70099); -#70096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70097,#70098),.UNSPECIFIED., +#72486 = PCURVE('',#48110,#72487); +#72487 = DEFINITIONAL_REPRESENTATION('',(#72488),#72491); +#72488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72489,#72490),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70097 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); -#70098 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); -#70099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72489 = CARTESIAN_POINT('',(0.E+000,0.785395562799)); +#72490 = CARTESIAN_POINT('',(0.E+000,-0.785400763996)); +#72491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72492 = ORIENTED_EDGE('',*,*,#48612,.F.); +#72493 = ORIENTED_EDGE('',*,*,#45636,.T.); +#72494 = ORIENTED_EDGE('',*,*,#72427,.T.); +#72495 = ADVANCED_FACE('',(#72496),#48110,.T.); +#72496 = FACE_BOUND('',#72497,.T.); +#72497 = EDGE_LOOP('',(#72498,#72499,#72500)); +#72498 = ORIENTED_EDGE('',*,*,#72473,.T.); +#72499 = ORIENTED_EDGE('',*,*,#72355,.F.); +#72500 = ORIENTED_EDGE('',*,*,#48096,.T.); +#72501 = ADVANCED_FACE('',(#72502),#46482,.T.); +#72502 = FACE_BOUND('',#72503,.F.); +#72503 = EDGE_LOOP('',(#72504,#72534,#72555,#72556,#72557,#72558,#72559) + ); +#72504 = ORIENTED_EDGE('',*,*,#72505,.T.); +#72505 = EDGE_CURVE('',#72506,#72508,#72510,.T.); +#72506 = VERTEX_POINT('',#72507); +#72507 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); +#72508 = VERTEX_POINT('',#72509); +#72509 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); +#72510 = SURFACE_CURVE('',#72511,(#72516,#72523),.PCURVE_S1.); +#72511 = CIRCLE('',#72512,0.1); +#72512 = AXIS2_PLACEMENT_3D('',#72513,#72514,#72515); +#72513 = CARTESIAN_POINT('',(-0.835,0.265,1.05)); +#72514 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72515 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72516 = PCURVE('',#46482,#72517); +#72517 = DEFINITIONAL_REPRESENTATION('',(#72518),#72522); +#72518 = CIRCLE('',#72519,0.1); +#72519 = AXIS2_PLACEMENT_2D('',#72520,#72521); +#72520 = CARTESIAN_POINT('',(-1.05,0.265)); +#72521 = DIRECTION('',(-1.,0.E+000)); +#72522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72523 = PCURVE('',#72524,#72529); +#72524 = CYLINDRICAL_SURFACE('',#72525,0.1); +#72525 = AXIS2_PLACEMENT_3D('',#72526,#72527,#72528); +#72526 = CARTESIAN_POINT('',(-0.835,0.265,1.05)); +#72527 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72528 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#72529 = DEFINITIONAL_REPRESENTATION('',(#72530),#72533); +#72530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72531,#72532),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#72531 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#72532 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72534 = ORIENTED_EDGE('',*,*,#72535,.F.); +#72535 = EDGE_CURVE('',#46467,#72508,#72536,.T.); +#72536 = SURFACE_CURVE('',#72537,(#72541,#72548),.PCURVE_S1.); +#72537 = LINE('',#72538,#72539); +#72538 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); +#72539 = VECTOR('',#72540,1.); +#72540 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72541 = PCURVE('',#46482,#72542); +#72542 = DEFINITIONAL_REPRESENTATION('',(#72543),#72547); +#72543 = LINE('',#72544,#72545); +#72544 = CARTESIAN_POINT('',(1.15,0.165)); +#72545 = VECTOR('',#72546,1.); +#72546 = DIRECTION('',(-1.,0.E+000)); +#72547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72548 = PCURVE('',#46510,#72549); +#72549 = DEFINITIONAL_REPRESENTATION('',(#72550),#72554); +#72550 = LINE('',#72551,#72552); +#72551 = CARTESIAN_POINT('',(2.2,0.E+000)); +#72552 = VECTOR('',#72553,1.); +#72553 = DIRECTION('',(-1.,0.E+000)); +#72554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70100 = ORIENTED_EDGE('',*,*,#46220,.F.); -#70101 = ORIENTED_EDGE('',*,*,#43244,.T.); -#70102 = ORIENTED_EDGE('',*,*,#70035,.T.); -#70103 = ADVANCED_FACE('',(#70104),#45718,.T.); -#70104 = FACE_BOUND('',#70105,.T.); -#70105 = EDGE_LOOP('',(#70106,#70107,#70108)); -#70106 = ORIENTED_EDGE('',*,*,#70081,.T.); -#70107 = ORIENTED_EDGE('',*,*,#69963,.F.); -#70108 = ORIENTED_EDGE('',*,*,#45704,.T.); -#70109 = ADVANCED_FACE('',(#70110),#44090,.T.); -#70110 = FACE_BOUND('',#70111,.F.); -#70111 = EDGE_LOOP('',(#70112,#70142,#70163,#70164,#70165,#70166,#70167) - ); -#70112 = ORIENTED_EDGE('',*,*,#70113,.T.); -#70113 = EDGE_CURVE('',#70114,#70116,#70118,.T.); -#70114 = VERTEX_POINT('',#70115); -#70115 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); -#70116 = VERTEX_POINT('',#70117); -#70117 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); -#70118 = SURFACE_CURVE('',#70119,(#70124,#70131),.PCURVE_S1.); -#70119 = CIRCLE('',#70120,0.1); -#70120 = AXIS2_PLACEMENT_3D('',#70121,#70122,#70123); -#70121 = CARTESIAN_POINT('',(-0.835,0.265,1.05)); -#70122 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70123 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70124 = PCURVE('',#44090,#70125); -#70125 = DEFINITIONAL_REPRESENTATION('',(#70126),#70130); -#70126 = CIRCLE('',#70127,0.1); -#70127 = AXIS2_PLACEMENT_2D('',#70128,#70129); -#70128 = CARTESIAN_POINT('',(-1.05,0.265)); -#70129 = DIRECTION('',(-1.,0.E+000)); -#70130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70131 = PCURVE('',#70132,#70137); -#70132 = CYLINDRICAL_SURFACE('',#70133,0.1); -#70133 = AXIS2_PLACEMENT_3D('',#70134,#70135,#70136); -#70134 = CARTESIAN_POINT('',(-0.835,0.265,1.05)); -#70135 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70136 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70137 = DEFINITIONAL_REPRESENTATION('',(#70138),#70141); -#70138 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70139,#70140),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70139 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70140 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70142 = ORIENTED_EDGE('',*,*,#70143,.F.); -#70143 = EDGE_CURVE('',#44075,#70116,#70144,.T.); -#70144 = SURFACE_CURVE('',#70145,(#70149,#70156),.PCURVE_S1.); -#70145 = LINE('',#70146,#70147); -#70146 = CARTESIAN_POINT('',(-0.835,0.165,-1.15)); -#70147 = VECTOR('',#70148,1.); -#70148 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70149 = PCURVE('',#44090,#70150); -#70150 = DEFINITIONAL_REPRESENTATION('',(#70151),#70155); -#70151 = LINE('',#70152,#70153); -#70152 = CARTESIAN_POINT('',(1.15,0.165)); -#70153 = VECTOR('',#70154,1.); -#70154 = DIRECTION('',(-1.,0.E+000)); -#70155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70156 = PCURVE('',#44118,#70157); -#70157 = DEFINITIONAL_REPRESENTATION('',(#70158),#70162); -#70158 = LINE('',#70159,#70160); -#70159 = CARTESIAN_POINT('',(2.2,0.E+000)); -#70160 = VECTOR('',#70161,1.); -#70161 = DIRECTION('',(-1.,0.E+000)); -#70162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70163 = ORIENTED_EDGE('',*,*,#44074,.F.); -#70164 = ORIENTED_EDGE('',*,*,#46050,.T.); -#70165 = ORIENTED_EDGE('',*,*,#45401,.F.); -#70166 = ORIENTED_EDGE('',*,*,#45020,.T.); -#70167 = ORIENTED_EDGE('',*,*,#70168,.F.); -#70168 = EDGE_CURVE('',#70114,#44993,#70169,.T.); -#70169 = SURFACE_CURVE('',#70170,(#70174,#70181),.PCURVE_S1.); -#70170 = LINE('',#70171,#70172); -#70171 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); -#70172 = VECTOR('',#70173,1.); -#70173 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70174 = PCURVE('',#44090,#70175); -#70175 = DEFINITIONAL_REPRESENTATION('',(#70176),#70180); -#70176 = LINE('',#70177,#70178); -#70177 = CARTESIAN_POINT('',(-1.15,0.265)); -#70178 = VECTOR('',#70179,1.); -#70179 = DIRECTION('',(-1.,0.E+000)); -#70180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70181 = PCURVE('',#45008,#70182); -#70182 = DEFINITIONAL_REPRESENTATION('',(#70183),#70187); -#70183 = LINE('',#70184,#70185); -#70184 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70185 = VECTOR('',#70186,1.); -#70186 = DIRECTION('',(1.,0.E+000)); -#70187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70188 = ADVANCED_FACE('',(#70189),#70132,.T.); -#70189 = FACE_BOUND('',#70190,.T.); -#70190 = EDGE_LOOP('',(#70191,#70192,#70214,#70237)); -#70191 = ORIENTED_EDGE('',*,*,#70113,.T.); -#70192 = ORIENTED_EDGE('',*,*,#70193,.T.); -#70193 = EDGE_CURVE('',#70116,#70194,#70196,.T.); -#70194 = VERTEX_POINT('',#70195); -#70195 = CARTESIAN_POINT('',(-0.465,0.165,1.05)); -#70196 = SURFACE_CURVE('',#70197,(#70201,#70207),.PCURVE_S1.); -#70197 = LINE('',#70198,#70199); -#70198 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); -#70199 = VECTOR('',#70200,1.); -#70200 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70201 = PCURVE('',#70132,#70202); -#70202 = DEFINITIONAL_REPRESENTATION('',(#70203),#70206); -#70203 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70204,#70205),.UNSPECIFIED., +#72555 = ORIENTED_EDGE('',*,*,#46466,.F.); +#72556 = ORIENTED_EDGE('',*,*,#48442,.T.); +#72557 = ORIENTED_EDGE('',*,*,#47793,.F.); +#72558 = ORIENTED_EDGE('',*,*,#47412,.T.); +#72559 = ORIENTED_EDGE('',*,*,#72560,.F.); +#72560 = EDGE_CURVE('',#72506,#47385,#72561,.T.); +#72561 = SURFACE_CURVE('',#72562,(#72566,#72573),.PCURVE_S1.); +#72562 = LINE('',#72563,#72564); +#72563 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); +#72564 = VECTOR('',#72565,1.); +#72565 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72566 = PCURVE('',#46482,#72567); +#72567 = DEFINITIONAL_REPRESENTATION('',(#72568),#72572); +#72568 = LINE('',#72569,#72570); +#72569 = CARTESIAN_POINT('',(-1.15,0.265)); +#72570 = VECTOR('',#72571,1.); +#72571 = DIRECTION('',(-1.,0.E+000)); +#72572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72573 = PCURVE('',#47400,#72574); +#72574 = DEFINITIONAL_REPRESENTATION('',(#72575),#72579); +#72575 = LINE('',#72576,#72577); +#72576 = CARTESIAN_POINT('',(2.3,0.E+000)); +#72577 = VECTOR('',#72578,1.); +#72578 = DIRECTION('',(1.,0.E+000)); +#72579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72580 = ADVANCED_FACE('',(#72581),#72524,.T.); +#72581 = FACE_BOUND('',#72582,.T.); +#72582 = EDGE_LOOP('',(#72583,#72584,#72606,#72629)); +#72583 = ORIENTED_EDGE('',*,*,#72505,.T.); +#72584 = ORIENTED_EDGE('',*,*,#72585,.T.); +#72585 = EDGE_CURVE('',#72508,#72586,#72588,.T.); +#72586 = VERTEX_POINT('',#72587); +#72587 = CARTESIAN_POINT('',(-0.465,0.165,1.05)); +#72588 = SURFACE_CURVE('',#72589,(#72593,#72599),.PCURVE_S1.); +#72589 = LINE('',#72590,#72591); +#72590 = CARTESIAN_POINT('',(-0.835,0.165,1.05)); +#72591 = VECTOR('',#72592,1.); +#72592 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72593 = PCURVE('',#72524,#72594); +#72594 = DEFINITIONAL_REPRESENTATION('',(#72595),#72598); +#72595 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72596,#72597),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70204 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70205 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70207 = PCURVE('',#44118,#70208); -#70208 = DEFINITIONAL_REPRESENTATION('',(#70209),#70213); -#70209 = LINE('',#70210,#70211); -#70210 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#70211 = VECTOR('',#70212,1.); -#70212 = DIRECTION('',(0.E+000,1.)); -#70213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70214 = ORIENTED_EDGE('',*,*,#70215,.F.); -#70215 = EDGE_CURVE('',#70216,#70194,#70218,.T.); -#70216 = VERTEX_POINT('',#70217); -#70217 = CARTESIAN_POINT('',(-0.465,0.265,1.15)); -#70218 = SURFACE_CURVE('',#70219,(#70224,#70230),.PCURVE_S1.); -#70219 = CIRCLE('',#70220,0.1); -#70220 = AXIS2_PLACEMENT_3D('',#70221,#70222,#70223); -#70221 = CARTESIAN_POINT('',(-0.465,0.265,1.05)); -#70222 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70223 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70224 = PCURVE('',#70132,#70225); -#70225 = DEFINITIONAL_REPRESENTATION('',(#70226),#70229); -#70226 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70227,#70228),.UNSPECIFIED., +#72596 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72597 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#72598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72599 = PCURVE('',#46510,#72600); +#72600 = DEFINITIONAL_REPRESENTATION('',(#72601),#72605); +#72601 = LINE('',#72602,#72603); +#72602 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72603 = VECTOR('',#72604,1.); +#72604 = DIRECTION('',(0.E+000,1.)); +#72605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72606 = ORIENTED_EDGE('',*,*,#72607,.F.); +#72607 = EDGE_CURVE('',#72608,#72586,#72610,.T.); +#72608 = VERTEX_POINT('',#72609); +#72609 = CARTESIAN_POINT('',(-0.465,0.265,1.15)); +#72610 = SURFACE_CURVE('',#72611,(#72616,#72622),.PCURVE_S1.); +#72611 = CIRCLE('',#72612,0.1); +#72612 = AXIS2_PLACEMENT_3D('',#72613,#72614,#72615); +#72613 = CARTESIAN_POINT('',(-0.465,0.265,1.05)); +#72614 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72615 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72616 = PCURVE('',#72524,#72617); +#72617 = DEFINITIONAL_REPRESENTATION('',(#72618),#72621); +#72618 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72619,#72620),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70227 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70228 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70230 = PCURVE('',#44146,#70231); -#70231 = DEFINITIONAL_REPRESENTATION('',(#70232),#70236); -#70232 = CIRCLE('',#70233,0.1); -#70233 = AXIS2_PLACEMENT_2D('',#70234,#70235); -#70234 = CARTESIAN_POINT('',(-1.05,0.265)); -#70235 = DIRECTION('',(-1.,0.E+000)); -#70236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70237 = ORIENTED_EDGE('',*,*,#70238,.F.); -#70238 = EDGE_CURVE('',#70114,#70216,#70239,.T.); -#70239 = SURFACE_CURVE('',#70240,(#70244,#70250),.PCURVE_S1.); -#70240 = LINE('',#70241,#70242); -#70241 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); -#70242 = VECTOR('',#70243,1.); -#70243 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70244 = PCURVE('',#70132,#70245); -#70245 = DEFINITIONAL_REPRESENTATION('',(#70246),#70249); -#70246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70247,#70248),.UNSPECIFIED., +#72619 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#72620 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#72621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72622 = PCURVE('',#46538,#72623); +#72623 = DEFINITIONAL_REPRESENTATION('',(#72624),#72628); +#72624 = CIRCLE('',#72625,0.1); +#72625 = AXIS2_PLACEMENT_2D('',#72626,#72627); +#72626 = CARTESIAN_POINT('',(-1.05,0.265)); +#72627 = DIRECTION('',(-1.,0.E+000)); +#72628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72629 = ORIENTED_EDGE('',*,*,#72630,.F.); +#72630 = EDGE_CURVE('',#72506,#72608,#72631,.T.); +#72631 = SURFACE_CURVE('',#72632,(#72636,#72642),.PCURVE_S1.); +#72632 = LINE('',#72633,#72634); +#72633 = CARTESIAN_POINT('',(-0.835,0.265,1.15)); +#72634 = VECTOR('',#72635,1.); +#72635 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72636 = PCURVE('',#72524,#72637); +#72637 = DEFINITIONAL_REPRESENTATION('',(#72638),#72641); +#72638 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72639,#72640),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70247 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70248 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70250 = PCURVE('',#45008,#70251); -#70251 = DEFINITIONAL_REPRESENTATION('',(#70252),#70256); -#70252 = LINE('',#70253,#70254); -#70253 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70254 = VECTOR('',#70255,1.); -#70255 = DIRECTION('',(0.E+000,1.)); -#70256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70257 = ADVANCED_FACE('',(#70258),#45008,.F.); -#70258 = FACE_BOUND('',#70259,.F.); -#70259 = EDGE_LOOP('',(#70260,#70261,#70262,#70263)); -#70260 = ORIENTED_EDGE('',*,*,#70238,.F.); -#70261 = ORIENTED_EDGE('',*,*,#70168,.T.); -#70262 = ORIENTED_EDGE('',*,*,#44992,.T.); -#70263 = ORIENTED_EDGE('',*,*,#70264,.F.); -#70264 = EDGE_CURVE('',#70216,#44970,#70265,.T.); -#70265 = SURFACE_CURVE('',#70266,(#70270,#70277),.PCURVE_S1.); -#70266 = LINE('',#70267,#70268); -#70267 = CARTESIAN_POINT('',(-0.465,0.265,1.15)); -#70268 = VECTOR('',#70269,1.); -#70269 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70270 = PCURVE('',#45008,#70271); -#70271 = DEFINITIONAL_REPRESENTATION('',(#70272),#70276); -#70272 = LINE('',#70273,#70274); -#70273 = CARTESIAN_POINT('',(2.3,0.37)); -#70274 = VECTOR('',#70275,1.); -#70275 = DIRECTION('',(1.,0.E+000)); -#70276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70277 = PCURVE('',#44146,#70278); -#70278 = DEFINITIONAL_REPRESENTATION('',(#70279),#70283); -#70279 = LINE('',#70280,#70281); -#70280 = CARTESIAN_POINT('',(-1.15,0.265)); -#70281 = VECTOR('',#70282,1.); -#70282 = DIRECTION('',(-1.,0.E+000)); -#70283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70284 = ADVANCED_FACE('',(#70285),#44146,.F.); -#70285 = FACE_BOUND('',#70286,.F.); -#70286 = EDGE_LOOP('',(#70287,#70288,#70289,#70290,#70291,#70292,#70293) - ); -#70287 = ORIENTED_EDGE('',*,*,#70215,.F.); -#70288 = ORIENTED_EDGE('',*,*,#70264,.T.); -#70289 = ORIENTED_EDGE('',*,*,#44969,.F.); -#70290 = ORIENTED_EDGE('',*,*,#45495,.T.); -#70291 = ORIENTED_EDGE('',*,*,#46099,.F.); -#70292 = ORIENTED_EDGE('',*,*,#44130,.T.); -#70293 = ORIENTED_EDGE('',*,*,#70294,.T.); -#70294 = EDGE_CURVE('',#44103,#70194,#70295,.T.); -#70295 = SURFACE_CURVE('',#70296,(#70300,#70307),.PCURVE_S1.); -#70296 = LINE('',#70297,#70298); -#70297 = CARTESIAN_POINT('',(-0.465,0.165,-1.15)); -#70298 = VECTOR('',#70299,1.); -#70299 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70300 = PCURVE('',#44146,#70301); -#70301 = DEFINITIONAL_REPRESENTATION('',(#70302),#70306); -#70302 = LINE('',#70303,#70304); -#70303 = CARTESIAN_POINT('',(1.15,0.165)); -#70304 = VECTOR('',#70305,1.); -#70305 = DIRECTION('',(-1.,0.E+000)); -#70306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70307 = PCURVE('',#44118,#70308); -#70308 = DEFINITIONAL_REPRESENTATION('',(#70309),#70313); -#70309 = LINE('',#70310,#70311); -#70310 = CARTESIAN_POINT('',(2.2,0.37)); -#70311 = VECTOR('',#70312,1.); -#70312 = DIRECTION('',(-1.,0.E+000)); -#70313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70314 = ADVANCED_FACE('',(#70315),#44118,.T.); -#70315 = FACE_BOUND('',#70316,.F.); -#70316 = EDGE_LOOP('',(#70317,#70318,#70319,#70320)); -#70317 = ORIENTED_EDGE('',*,*,#44102,.F.); -#70318 = ORIENTED_EDGE('',*,*,#70143,.T.); -#70319 = ORIENTED_EDGE('',*,*,#70193,.T.); -#70320 = ORIENTED_EDGE('',*,*,#70294,.F.); -#70321 = ADVANCED_FACE('',(#70322),#44202,.T.); -#70322 = FACE_BOUND('',#70323,.F.); -#70323 = EDGE_LOOP('',(#70324,#70354,#70375,#70376,#70377,#70378,#70379) - ); -#70324 = ORIENTED_EDGE('',*,*,#70325,.T.); -#70325 = EDGE_CURVE('',#70326,#70328,#70330,.T.); -#70326 = VERTEX_POINT('',#70327); -#70327 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); -#70328 = VERTEX_POINT('',#70329); -#70329 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); -#70330 = SURFACE_CURVE('',#70331,(#70336,#70343),.PCURVE_S1.); -#70331 = CIRCLE('',#70332,0.1); -#70332 = AXIS2_PLACEMENT_3D('',#70333,#70334,#70335); -#70333 = CARTESIAN_POINT('',(-0.185,0.265,1.05)); -#70334 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70335 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70336 = PCURVE('',#44202,#70337); -#70337 = DEFINITIONAL_REPRESENTATION('',(#70338),#70342); -#70338 = CIRCLE('',#70339,0.1); -#70339 = AXIS2_PLACEMENT_2D('',#70340,#70341); -#70340 = CARTESIAN_POINT('',(-1.05,0.265)); -#70341 = DIRECTION('',(-1.,0.E+000)); -#70342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72639 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#72640 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#72641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72642 = PCURVE('',#47400,#72643); +#72643 = DEFINITIONAL_REPRESENTATION('',(#72644),#72648); +#72644 = LINE('',#72645,#72646); +#72645 = CARTESIAN_POINT('',(2.3,0.E+000)); +#72646 = VECTOR('',#72647,1.); +#72647 = DIRECTION('',(0.E+000,1.)); +#72648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72649 = ADVANCED_FACE('',(#72650),#47400,.F.); +#72650 = FACE_BOUND('',#72651,.F.); +#72651 = EDGE_LOOP('',(#72652,#72653,#72654,#72655)); +#72652 = ORIENTED_EDGE('',*,*,#72630,.F.); +#72653 = ORIENTED_EDGE('',*,*,#72560,.T.); +#72654 = ORIENTED_EDGE('',*,*,#47384,.T.); +#72655 = ORIENTED_EDGE('',*,*,#72656,.F.); +#72656 = EDGE_CURVE('',#72608,#47362,#72657,.T.); +#72657 = SURFACE_CURVE('',#72658,(#72662,#72669),.PCURVE_S1.); +#72658 = LINE('',#72659,#72660); +#72659 = CARTESIAN_POINT('',(-0.465,0.265,1.15)); +#72660 = VECTOR('',#72661,1.); +#72661 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72662 = PCURVE('',#47400,#72663); +#72663 = DEFINITIONAL_REPRESENTATION('',(#72664),#72668); +#72664 = LINE('',#72665,#72666); +#72665 = CARTESIAN_POINT('',(2.3,0.37)); +#72666 = VECTOR('',#72667,1.); +#72667 = DIRECTION('',(1.,0.E+000)); +#72668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72669 = PCURVE('',#46538,#72670); +#72670 = DEFINITIONAL_REPRESENTATION('',(#72671),#72675); +#72671 = LINE('',#72672,#72673); +#72672 = CARTESIAN_POINT('',(-1.15,0.265)); +#72673 = VECTOR('',#72674,1.); +#72674 = DIRECTION('',(-1.,0.E+000)); +#72675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72676 = ADVANCED_FACE('',(#72677),#46538,.F.); +#72677 = FACE_BOUND('',#72678,.F.); +#72678 = EDGE_LOOP('',(#72679,#72680,#72681,#72682,#72683,#72684,#72685) + ); +#72679 = ORIENTED_EDGE('',*,*,#72607,.F.); +#72680 = ORIENTED_EDGE('',*,*,#72656,.T.); +#72681 = ORIENTED_EDGE('',*,*,#47361,.F.); +#72682 = ORIENTED_EDGE('',*,*,#47887,.T.); +#72683 = ORIENTED_EDGE('',*,*,#48491,.F.); +#72684 = ORIENTED_EDGE('',*,*,#46522,.T.); +#72685 = ORIENTED_EDGE('',*,*,#72686,.T.); +#72686 = EDGE_CURVE('',#46495,#72586,#72687,.T.); +#72687 = SURFACE_CURVE('',#72688,(#72692,#72699),.PCURVE_S1.); +#72688 = LINE('',#72689,#72690); +#72689 = CARTESIAN_POINT('',(-0.465,0.165,-1.15)); +#72690 = VECTOR('',#72691,1.); +#72691 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72692 = PCURVE('',#46538,#72693); +#72693 = DEFINITIONAL_REPRESENTATION('',(#72694),#72698); +#72694 = LINE('',#72695,#72696); +#72695 = CARTESIAN_POINT('',(1.15,0.165)); +#72696 = VECTOR('',#72697,1.); +#72697 = DIRECTION('',(-1.,0.E+000)); +#72698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72699 = PCURVE('',#46510,#72700); +#72700 = DEFINITIONAL_REPRESENTATION('',(#72701),#72705); +#72701 = LINE('',#72702,#72703); +#72702 = CARTESIAN_POINT('',(2.2,0.37)); +#72703 = VECTOR('',#72704,1.); +#72704 = DIRECTION('',(-1.,0.E+000)); +#72705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70343 = PCURVE('',#70344,#70349); -#70344 = CYLINDRICAL_SURFACE('',#70345,0.1); -#70345 = AXIS2_PLACEMENT_3D('',#70346,#70347,#70348); -#70346 = CARTESIAN_POINT('',(-0.185,0.265,1.05)); -#70347 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70348 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70349 = DEFINITIONAL_REPRESENTATION('',(#70350),#70353); -#70350 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70351,#70352),.UNSPECIFIED., +#72706 = ADVANCED_FACE('',(#72707),#46510,.T.); +#72707 = FACE_BOUND('',#72708,.F.); +#72708 = EDGE_LOOP('',(#72709,#72710,#72711,#72712)); +#72709 = ORIENTED_EDGE('',*,*,#46494,.F.); +#72710 = ORIENTED_EDGE('',*,*,#72535,.T.); +#72711 = ORIENTED_EDGE('',*,*,#72585,.T.); +#72712 = ORIENTED_EDGE('',*,*,#72686,.F.); +#72713 = ADVANCED_FACE('',(#72714),#46594,.T.); +#72714 = FACE_BOUND('',#72715,.F.); +#72715 = EDGE_LOOP('',(#72716,#72746,#72767,#72768,#72769,#72770,#72771) + ); +#72716 = ORIENTED_EDGE('',*,*,#72717,.T.); +#72717 = EDGE_CURVE('',#72718,#72720,#72722,.T.); +#72718 = VERTEX_POINT('',#72719); +#72719 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); +#72720 = VERTEX_POINT('',#72721); +#72721 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); +#72722 = SURFACE_CURVE('',#72723,(#72728,#72735),.PCURVE_S1.); +#72723 = CIRCLE('',#72724,0.1); +#72724 = AXIS2_PLACEMENT_3D('',#72725,#72726,#72727); +#72725 = CARTESIAN_POINT('',(-0.185,0.265,1.05)); +#72726 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72727 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72728 = PCURVE('',#46594,#72729); +#72729 = DEFINITIONAL_REPRESENTATION('',(#72730),#72734); +#72730 = CIRCLE('',#72731,0.1); +#72731 = AXIS2_PLACEMENT_2D('',#72732,#72733); +#72732 = CARTESIAN_POINT('',(-1.05,0.265)); +#72733 = DIRECTION('',(-1.,0.E+000)); +#72734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72735 = PCURVE('',#72736,#72741); +#72736 = CYLINDRICAL_SURFACE('',#72737,0.1); +#72737 = AXIS2_PLACEMENT_3D('',#72738,#72739,#72740); +#72738 = CARTESIAN_POINT('',(-0.185,0.265,1.05)); +#72739 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72740 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#72741 = DEFINITIONAL_REPRESENTATION('',(#72742),#72745); +#72742 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72743,#72744),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70351 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70352 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70354 = ORIENTED_EDGE('',*,*,#70355,.F.); -#70355 = EDGE_CURVE('',#44187,#70328,#70356,.T.); -#70356 = SURFACE_CURVE('',#70357,(#70361,#70368),.PCURVE_S1.); -#70357 = LINE('',#70358,#70359); -#70358 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); -#70359 = VECTOR('',#70360,1.); -#70360 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70361 = PCURVE('',#44202,#70362); -#70362 = DEFINITIONAL_REPRESENTATION('',(#70363),#70367); -#70363 = LINE('',#70364,#70365); -#70364 = CARTESIAN_POINT('',(1.15,0.165)); -#70365 = VECTOR('',#70366,1.); -#70366 = DIRECTION('',(-1.,0.E+000)); -#70367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70368 = PCURVE('',#44230,#70369); -#70369 = DEFINITIONAL_REPRESENTATION('',(#70370),#70374); -#70370 = LINE('',#70371,#70372); -#70371 = CARTESIAN_POINT('',(2.2,0.E+000)); -#70372 = VECTOR('',#70373,1.); -#70373 = DIRECTION('',(-1.,0.E+000)); -#70374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70375 = ORIENTED_EDGE('',*,*,#44186,.F.); -#70376 = ORIENTED_EDGE('',*,*,#46077,.T.); -#70377 = ORIENTED_EDGE('',*,*,#45471,.F.); -#70378 = ORIENTED_EDGE('',*,*,#44919,.T.); -#70379 = ORIENTED_EDGE('',*,*,#70380,.F.); -#70380 = EDGE_CURVE('',#70326,#44892,#70381,.T.); -#70381 = SURFACE_CURVE('',#70382,(#70386,#70393),.PCURVE_S1.); -#70382 = LINE('',#70383,#70384); -#70383 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); -#70384 = VECTOR('',#70385,1.); -#70385 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70386 = PCURVE('',#44202,#70387); -#70387 = DEFINITIONAL_REPRESENTATION('',(#70388),#70392); -#70388 = LINE('',#70389,#70390); -#70389 = CARTESIAN_POINT('',(-1.15,0.265)); -#70390 = VECTOR('',#70391,1.); -#70391 = DIRECTION('',(-1.,0.E+000)); -#70392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70393 = PCURVE('',#44907,#70394); -#70394 = DEFINITIONAL_REPRESENTATION('',(#70395),#70399); -#70395 = LINE('',#70396,#70397); -#70396 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70397 = VECTOR('',#70398,1.); -#70398 = DIRECTION('',(1.,0.E+000)); -#70399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70400 = ADVANCED_FACE('',(#70401),#70344,.T.); -#70401 = FACE_BOUND('',#70402,.T.); -#70402 = EDGE_LOOP('',(#70403,#70404,#70426,#70449)); -#70403 = ORIENTED_EDGE('',*,*,#70325,.T.); -#70404 = ORIENTED_EDGE('',*,*,#70405,.T.); -#70405 = EDGE_CURVE('',#70328,#70406,#70408,.T.); -#70406 = VERTEX_POINT('',#70407); -#70407 = CARTESIAN_POINT('',(0.185,0.165,1.05)); -#70408 = SURFACE_CURVE('',#70409,(#70413,#70419),.PCURVE_S1.); -#70409 = LINE('',#70410,#70411); -#70410 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); -#70411 = VECTOR('',#70412,1.); -#70412 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70413 = PCURVE('',#70344,#70414); -#70414 = DEFINITIONAL_REPRESENTATION('',(#70415),#70418); -#70415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70416,#70417),.UNSPECIFIED., +#72743 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#72744 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72746 = ORIENTED_EDGE('',*,*,#72747,.F.); +#72747 = EDGE_CURVE('',#46579,#72720,#72748,.T.); +#72748 = SURFACE_CURVE('',#72749,(#72753,#72760),.PCURVE_S1.); +#72749 = LINE('',#72750,#72751); +#72750 = CARTESIAN_POINT('',(-0.185,0.165,-1.15)); +#72751 = VECTOR('',#72752,1.); +#72752 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72753 = PCURVE('',#46594,#72754); +#72754 = DEFINITIONAL_REPRESENTATION('',(#72755),#72759); +#72755 = LINE('',#72756,#72757); +#72756 = CARTESIAN_POINT('',(1.15,0.165)); +#72757 = VECTOR('',#72758,1.); +#72758 = DIRECTION('',(-1.,0.E+000)); +#72759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72760 = PCURVE('',#46622,#72761); +#72761 = DEFINITIONAL_REPRESENTATION('',(#72762),#72766); +#72762 = LINE('',#72763,#72764); +#72763 = CARTESIAN_POINT('',(2.2,0.E+000)); +#72764 = VECTOR('',#72765,1.); +#72765 = DIRECTION('',(-1.,0.E+000)); +#72766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72767 = ORIENTED_EDGE('',*,*,#46578,.F.); +#72768 = ORIENTED_EDGE('',*,*,#48469,.T.); +#72769 = ORIENTED_EDGE('',*,*,#47863,.F.); +#72770 = ORIENTED_EDGE('',*,*,#47311,.T.); +#72771 = ORIENTED_EDGE('',*,*,#72772,.F.); +#72772 = EDGE_CURVE('',#72718,#47284,#72773,.T.); +#72773 = SURFACE_CURVE('',#72774,(#72778,#72785),.PCURVE_S1.); +#72774 = LINE('',#72775,#72776); +#72775 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); +#72776 = VECTOR('',#72777,1.); +#72777 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72778 = PCURVE('',#46594,#72779); +#72779 = DEFINITIONAL_REPRESENTATION('',(#72780),#72784); +#72780 = LINE('',#72781,#72782); +#72781 = CARTESIAN_POINT('',(-1.15,0.265)); +#72782 = VECTOR('',#72783,1.); +#72783 = DIRECTION('',(-1.,0.E+000)); +#72784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72785 = PCURVE('',#47299,#72786); +#72786 = DEFINITIONAL_REPRESENTATION('',(#72787),#72791); +#72787 = LINE('',#72788,#72789); +#72788 = CARTESIAN_POINT('',(2.3,0.E+000)); +#72789 = VECTOR('',#72790,1.); +#72790 = DIRECTION('',(1.,0.E+000)); +#72791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72792 = ADVANCED_FACE('',(#72793),#72736,.T.); +#72793 = FACE_BOUND('',#72794,.T.); +#72794 = EDGE_LOOP('',(#72795,#72796,#72818,#72841)); +#72795 = ORIENTED_EDGE('',*,*,#72717,.T.); +#72796 = ORIENTED_EDGE('',*,*,#72797,.T.); +#72797 = EDGE_CURVE('',#72720,#72798,#72800,.T.); +#72798 = VERTEX_POINT('',#72799); +#72799 = CARTESIAN_POINT('',(0.185,0.165,1.05)); +#72800 = SURFACE_CURVE('',#72801,(#72805,#72811),.PCURVE_S1.); +#72801 = LINE('',#72802,#72803); +#72802 = CARTESIAN_POINT('',(-0.185,0.165,1.05)); +#72803 = VECTOR('',#72804,1.); +#72804 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72805 = PCURVE('',#72736,#72806); +#72806 = DEFINITIONAL_REPRESENTATION('',(#72807),#72810); +#72807 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72808,#72809),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70416 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70417 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70419 = PCURVE('',#44230,#70420); -#70420 = DEFINITIONAL_REPRESENTATION('',(#70421),#70425); -#70421 = LINE('',#70422,#70423); -#70422 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#70423 = VECTOR('',#70424,1.); -#70424 = DIRECTION('',(0.E+000,1.)); -#70425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70426 = ORIENTED_EDGE('',*,*,#70427,.F.); -#70427 = EDGE_CURVE('',#70428,#70406,#70430,.T.); -#70428 = VERTEX_POINT('',#70429); -#70429 = CARTESIAN_POINT('',(0.185,0.265,1.15)); -#70430 = SURFACE_CURVE('',#70431,(#70436,#70442),.PCURVE_S1.); -#70431 = CIRCLE('',#70432,0.1); -#70432 = AXIS2_PLACEMENT_3D('',#70433,#70434,#70435); -#70433 = CARTESIAN_POINT('',(0.185,0.265,1.05)); -#70434 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70435 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70436 = PCURVE('',#70344,#70437); -#70437 = DEFINITIONAL_REPRESENTATION('',(#70438),#70441); -#70438 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70439,#70440),.UNSPECIFIED., +#72808 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72809 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#72810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72811 = PCURVE('',#46622,#72812); +#72812 = DEFINITIONAL_REPRESENTATION('',(#72813),#72817); +#72813 = LINE('',#72814,#72815); +#72814 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#72815 = VECTOR('',#72816,1.); +#72816 = DIRECTION('',(0.E+000,1.)); +#72817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72818 = ORIENTED_EDGE('',*,*,#72819,.F.); +#72819 = EDGE_CURVE('',#72820,#72798,#72822,.T.); +#72820 = VERTEX_POINT('',#72821); +#72821 = CARTESIAN_POINT('',(0.185,0.265,1.15)); +#72822 = SURFACE_CURVE('',#72823,(#72828,#72834),.PCURVE_S1.); +#72823 = CIRCLE('',#72824,0.1); +#72824 = AXIS2_PLACEMENT_3D('',#72825,#72826,#72827); +#72825 = CARTESIAN_POINT('',(0.185,0.265,1.05)); +#72826 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72827 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72828 = PCURVE('',#72736,#72829); +#72829 = DEFINITIONAL_REPRESENTATION('',(#72830),#72833); +#72830 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72831,#72832),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70439 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70440 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70442 = PCURVE('',#44258,#70443); -#70443 = DEFINITIONAL_REPRESENTATION('',(#70444),#70448); -#70444 = CIRCLE('',#70445,0.1); -#70445 = AXIS2_PLACEMENT_2D('',#70446,#70447); -#70446 = CARTESIAN_POINT('',(-1.05,0.265)); -#70447 = DIRECTION('',(-1.,0.E+000)); -#70448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70449 = ORIENTED_EDGE('',*,*,#70450,.F.); -#70450 = EDGE_CURVE('',#70326,#70428,#70451,.T.); -#70451 = SURFACE_CURVE('',#70452,(#70456,#70462),.PCURVE_S1.); -#70452 = LINE('',#70453,#70454); -#70453 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); -#70454 = VECTOR('',#70455,1.); -#70455 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70456 = PCURVE('',#70344,#70457); -#70457 = DEFINITIONAL_REPRESENTATION('',(#70458),#70461); -#70458 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70459,#70460),.UNSPECIFIED., +#72831 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#72832 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#72833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72834 = PCURVE('',#46650,#72835); +#72835 = DEFINITIONAL_REPRESENTATION('',(#72836),#72840); +#72836 = CIRCLE('',#72837,0.1); +#72837 = AXIS2_PLACEMENT_2D('',#72838,#72839); +#72838 = CARTESIAN_POINT('',(-1.05,0.265)); +#72839 = DIRECTION('',(-1.,0.E+000)); +#72840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72841 = ORIENTED_EDGE('',*,*,#72842,.F.); +#72842 = EDGE_CURVE('',#72718,#72820,#72843,.T.); +#72843 = SURFACE_CURVE('',#72844,(#72848,#72854),.PCURVE_S1.); +#72844 = LINE('',#72845,#72846); +#72845 = CARTESIAN_POINT('',(-0.185,0.265,1.15)); +#72846 = VECTOR('',#72847,1.); +#72847 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72848 = PCURVE('',#72736,#72849); +#72849 = DEFINITIONAL_REPRESENTATION('',(#72850),#72853); +#72850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72851,#72852),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70459 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70460 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#72851 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#72852 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#72853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72854 = PCURVE('',#47299,#72855); +#72855 = DEFINITIONAL_REPRESENTATION('',(#72856),#72860); +#72856 = LINE('',#72857,#72858); +#72857 = CARTESIAN_POINT('',(2.3,0.E+000)); +#72858 = VECTOR('',#72859,1.); +#72859 = DIRECTION('',(0.E+000,1.)); +#72860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72861 = ADVANCED_FACE('',(#72862),#47299,.F.); +#72862 = FACE_BOUND('',#72863,.F.); +#72863 = EDGE_LOOP('',(#72864,#72865,#72866,#72867)); +#72864 = ORIENTED_EDGE('',*,*,#72842,.F.); +#72865 = ORIENTED_EDGE('',*,*,#72772,.T.); +#72866 = ORIENTED_EDGE('',*,*,#47283,.T.); +#72867 = ORIENTED_EDGE('',*,*,#72868,.F.); +#72868 = EDGE_CURVE('',#72820,#47261,#72869,.T.); +#72869 = SURFACE_CURVE('',#72870,(#72874,#72881),.PCURVE_S1.); +#72870 = LINE('',#72871,#72872); +#72871 = CARTESIAN_POINT('',(0.185,0.265,1.15)); +#72872 = VECTOR('',#72873,1.); +#72873 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72874 = PCURVE('',#47299,#72875); +#72875 = DEFINITIONAL_REPRESENTATION('',(#72876),#72880); +#72876 = LINE('',#72877,#72878); +#72877 = CARTESIAN_POINT('',(2.3,0.37)); +#72878 = VECTOR('',#72879,1.); +#72879 = DIRECTION('',(1.,0.E+000)); +#72880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72881 = PCURVE('',#46650,#72882); +#72882 = DEFINITIONAL_REPRESENTATION('',(#72883),#72887); +#72883 = LINE('',#72884,#72885); +#72884 = CARTESIAN_POINT('',(-1.15,0.265)); +#72885 = VECTOR('',#72886,1.); +#72886 = DIRECTION('',(-1.,0.E+000)); +#72887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72888 = ADVANCED_FACE('',(#72889),#46650,.F.); +#72889 = FACE_BOUND('',#72890,.F.); +#72890 = EDGE_LOOP('',(#72891,#72892,#72893,#72894,#72895,#72896,#72897) + ); +#72891 = ORIENTED_EDGE('',*,*,#72819,.F.); +#72892 = ORIENTED_EDGE('',*,*,#72868,.T.); +#72893 = ORIENTED_EDGE('',*,*,#47260,.F.); +#72894 = ORIENTED_EDGE('',*,*,#47957,.T.); +#72895 = ORIENTED_EDGE('',*,*,#48538,.F.); +#72896 = ORIENTED_EDGE('',*,*,#46634,.T.); +#72897 = ORIENTED_EDGE('',*,*,#72898,.T.); +#72898 = EDGE_CURVE('',#46607,#72798,#72899,.T.); +#72899 = SURFACE_CURVE('',#72900,(#72904,#72911),.PCURVE_S1.); +#72900 = LINE('',#72901,#72902); +#72901 = CARTESIAN_POINT('',(0.185,0.165,-1.15)); +#72902 = VECTOR('',#72903,1.); +#72903 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72904 = PCURVE('',#46650,#72905); +#72905 = DEFINITIONAL_REPRESENTATION('',(#72906),#72910); +#72906 = LINE('',#72907,#72908); +#72907 = CARTESIAN_POINT('',(1.15,0.165)); +#72908 = VECTOR('',#72909,1.); +#72909 = DIRECTION('',(-1.,0.E+000)); +#72910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72911 = PCURVE('',#46622,#72912); +#72912 = DEFINITIONAL_REPRESENTATION('',(#72913),#72917); +#72913 = LINE('',#72914,#72915); +#72914 = CARTESIAN_POINT('',(2.2,0.37)); +#72915 = VECTOR('',#72916,1.); +#72916 = DIRECTION('',(-1.,0.E+000)); +#72917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70462 = PCURVE('',#44907,#70463); -#70463 = DEFINITIONAL_REPRESENTATION('',(#70464),#70468); -#70464 = LINE('',#70465,#70466); -#70465 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70466 = VECTOR('',#70467,1.); -#70467 = DIRECTION('',(0.E+000,1.)); -#70468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70469 = ADVANCED_FACE('',(#70470),#44907,.F.); -#70470 = FACE_BOUND('',#70471,.F.); -#70471 = EDGE_LOOP('',(#70472,#70473,#70474,#70475)); -#70472 = ORIENTED_EDGE('',*,*,#70450,.F.); -#70473 = ORIENTED_EDGE('',*,*,#70380,.T.); -#70474 = ORIENTED_EDGE('',*,*,#44891,.T.); -#70475 = ORIENTED_EDGE('',*,*,#70476,.F.); -#70476 = EDGE_CURVE('',#70428,#44869,#70477,.T.); -#70477 = SURFACE_CURVE('',#70478,(#70482,#70489),.PCURVE_S1.); -#70478 = LINE('',#70479,#70480); -#70479 = CARTESIAN_POINT('',(0.185,0.265,1.15)); -#70480 = VECTOR('',#70481,1.); -#70481 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70482 = PCURVE('',#44907,#70483); -#70483 = DEFINITIONAL_REPRESENTATION('',(#70484),#70488); -#70484 = LINE('',#70485,#70486); -#70485 = CARTESIAN_POINT('',(2.3,0.37)); -#70486 = VECTOR('',#70487,1.); -#70487 = DIRECTION('',(1.,0.E+000)); -#70488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70489 = PCURVE('',#44258,#70490); -#70490 = DEFINITIONAL_REPRESENTATION('',(#70491),#70495); -#70491 = LINE('',#70492,#70493); -#70492 = CARTESIAN_POINT('',(-1.15,0.265)); -#70493 = VECTOR('',#70494,1.); -#70494 = DIRECTION('',(-1.,0.E+000)); -#70495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70496 = ADVANCED_FACE('',(#70497),#44258,.F.); -#70497 = FACE_BOUND('',#70498,.F.); -#70498 = EDGE_LOOP('',(#70499,#70500,#70501,#70502,#70503,#70504,#70505) - ); -#70499 = ORIENTED_EDGE('',*,*,#70427,.F.); -#70500 = ORIENTED_EDGE('',*,*,#70476,.T.); -#70501 = ORIENTED_EDGE('',*,*,#44868,.F.); -#70502 = ORIENTED_EDGE('',*,*,#45565,.T.); -#70503 = ORIENTED_EDGE('',*,*,#46146,.F.); -#70504 = ORIENTED_EDGE('',*,*,#44242,.T.); -#70505 = ORIENTED_EDGE('',*,*,#70506,.T.); -#70506 = EDGE_CURVE('',#44215,#70406,#70507,.T.); -#70507 = SURFACE_CURVE('',#70508,(#70512,#70519),.PCURVE_S1.); -#70508 = LINE('',#70509,#70510); -#70509 = CARTESIAN_POINT('',(0.185,0.165,-1.15)); -#70510 = VECTOR('',#70511,1.); -#70511 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70512 = PCURVE('',#44258,#70513); -#70513 = DEFINITIONAL_REPRESENTATION('',(#70514),#70518); -#70514 = LINE('',#70515,#70516); -#70515 = CARTESIAN_POINT('',(1.15,0.165)); -#70516 = VECTOR('',#70517,1.); -#70517 = DIRECTION('',(-1.,0.E+000)); -#70518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70519 = PCURVE('',#44230,#70520); -#70520 = DEFINITIONAL_REPRESENTATION('',(#70521),#70525); -#70521 = LINE('',#70522,#70523); -#70522 = CARTESIAN_POINT('',(2.2,0.37)); -#70523 = VECTOR('',#70524,1.); -#70524 = DIRECTION('',(-1.,0.E+000)); -#70525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70526 = ADVANCED_FACE('',(#70527),#44230,.T.); -#70527 = FACE_BOUND('',#70528,.F.); -#70528 = EDGE_LOOP('',(#70529,#70530,#70531,#70532)); -#70529 = ORIENTED_EDGE('',*,*,#44214,.F.); -#70530 = ORIENTED_EDGE('',*,*,#70355,.T.); -#70531 = ORIENTED_EDGE('',*,*,#70405,.T.); -#70532 = ORIENTED_EDGE('',*,*,#70506,.F.); -#70533 = ADVANCED_FACE('',(#70534),#44314,.T.); -#70534 = FACE_BOUND('',#70535,.F.); -#70535 = EDGE_LOOP('',(#70536,#70566,#70587,#70588,#70589,#70590,#70591) - ); -#70536 = ORIENTED_EDGE('',*,*,#70537,.T.); -#70537 = EDGE_CURVE('',#70538,#70540,#70542,.T.); -#70538 = VERTEX_POINT('',#70539); -#70539 = CARTESIAN_POINT('',(0.465,0.265,1.15)); -#70540 = VERTEX_POINT('',#70541); -#70541 = CARTESIAN_POINT('',(0.465,0.165,1.05)); -#70542 = SURFACE_CURVE('',#70543,(#70548,#70555),.PCURVE_S1.); -#70543 = CIRCLE('',#70544,0.1); -#70544 = AXIS2_PLACEMENT_3D('',#70545,#70546,#70547); -#70545 = CARTESIAN_POINT('',(0.465,0.265,1.05)); -#70546 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70547 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70548 = PCURVE('',#44314,#70549); -#70549 = DEFINITIONAL_REPRESENTATION('',(#70550),#70554); -#70550 = CIRCLE('',#70551,0.1); -#70551 = AXIS2_PLACEMENT_2D('',#70552,#70553); -#70552 = CARTESIAN_POINT('',(-1.05,0.265)); -#70553 = DIRECTION('',(-1.,0.E+000)); -#70554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70555 = PCURVE('',#70556,#70561); -#70556 = CYLINDRICAL_SURFACE('',#70557,0.1); -#70557 = AXIS2_PLACEMENT_3D('',#70558,#70559,#70560); -#70558 = CARTESIAN_POINT('',(0.465,0.265,1.05)); -#70559 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70560 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70561 = DEFINITIONAL_REPRESENTATION('',(#70562),#70565); -#70562 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70563,#70564),.UNSPECIFIED., +#72918 = ADVANCED_FACE('',(#72919),#46622,.T.); +#72919 = FACE_BOUND('',#72920,.F.); +#72920 = EDGE_LOOP('',(#72921,#72922,#72923,#72924)); +#72921 = ORIENTED_EDGE('',*,*,#46606,.F.); +#72922 = ORIENTED_EDGE('',*,*,#72747,.T.); +#72923 = ORIENTED_EDGE('',*,*,#72797,.T.); +#72924 = ORIENTED_EDGE('',*,*,#72898,.F.); +#72925 = ADVANCED_FACE('',(#72926),#46706,.T.); +#72926 = FACE_BOUND('',#72927,.F.); +#72927 = EDGE_LOOP('',(#72928,#72958,#72979,#72980,#72981,#72982,#72983) + ); +#72928 = ORIENTED_EDGE('',*,*,#72929,.T.); +#72929 = EDGE_CURVE('',#72930,#72932,#72934,.T.); +#72930 = VERTEX_POINT('',#72931); +#72931 = CARTESIAN_POINT('',(0.465,0.265,1.15)); +#72932 = VERTEX_POINT('',#72933); +#72933 = CARTESIAN_POINT('',(0.465,0.165,1.05)); +#72934 = SURFACE_CURVE('',#72935,(#72940,#72947),.PCURVE_S1.); +#72935 = CIRCLE('',#72936,0.1); +#72936 = AXIS2_PLACEMENT_3D('',#72937,#72938,#72939); +#72937 = CARTESIAN_POINT('',(0.465,0.265,1.05)); +#72938 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72939 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72940 = PCURVE('',#46706,#72941); +#72941 = DEFINITIONAL_REPRESENTATION('',(#72942),#72946); +#72942 = CIRCLE('',#72943,0.1); +#72943 = AXIS2_PLACEMENT_2D('',#72944,#72945); +#72944 = CARTESIAN_POINT('',(-1.05,0.265)); +#72945 = DIRECTION('',(-1.,0.E+000)); +#72946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72947 = PCURVE('',#72948,#72953); +#72948 = CYLINDRICAL_SURFACE('',#72949,0.1); +#72949 = AXIS2_PLACEMENT_3D('',#72950,#72951,#72952); +#72950 = CARTESIAN_POINT('',(0.465,0.265,1.05)); +#72951 = DIRECTION('',(1.,0.E+000,0.E+000)); +#72952 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#72953 = DEFINITIONAL_REPRESENTATION('',(#72954),#72957); +#72954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72955,#72956),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70563 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70564 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70566 = ORIENTED_EDGE('',*,*,#70567,.F.); -#70567 = EDGE_CURVE('',#44299,#70540,#70568,.T.); -#70568 = SURFACE_CURVE('',#70569,(#70573,#70580),.PCURVE_S1.); -#70569 = LINE('',#70570,#70571); -#70570 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); -#70571 = VECTOR('',#70572,1.); -#70572 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70573 = PCURVE('',#44314,#70574); -#70574 = DEFINITIONAL_REPRESENTATION('',(#70575),#70579); -#70575 = LINE('',#70576,#70577); -#70576 = CARTESIAN_POINT('',(1.15,0.165)); -#70577 = VECTOR('',#70578,1.); -#70578 = DIRECTION('',(-1.,0.E+000)); -#70579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70580 = PCURVE('',#44342,#70581); -#70581 = DEFINITIONAL_REPRESENTATION('',(#70582),#70586); -#70582 = LINE('',#70583,#70584); -#70583 = CARTESIAN_POINT('',(2.2,0.E+000)); -#70584 = VECTOR('',#70585,1.); -#70585 = DIRECTION('',(-1.,0.E+000)); -#70586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70587 = ORIENTED_EDGE('',*,*,#44298,.F.); -#70588 = ORIENTED_EDGE('',*,*,#46124,.T.); -#70589 = ORIENTED_EDGE('',*,*,#45541,.F.); -#70590 = ORIENTED_EDGE('',*,*,#44818,.T.); -#70591 = ORIENTED_EDGE('',*,*,#70592,.F.); -#70592 = EDGE_CURVE('',#70538,#44791,#70593,.T.); -#70593 = SURFACE_CURVE('',#70594,(#70598,#70605),.PCURVE_S1.); -#70594 = LINE('',#70595,#70596); -#70595 = CARTESIAN_POINT('',(0.465,0.265,1.15)); -#70596 = VECTOR('',#70597,1.); -#70597 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70598 = PCURVE('',#44314,#70599); -#70599 = DEFINITIONAL_REPRESENTATION('',(#70600),#70604); -#70600 = LINE('',#70601,#70602); -#70601 = CARTESIAN_POINT('',(-1.15,0.265)); -#70602 = VECTOR('',#70603,1.); -#70603 = DIRECTION('',(-1.,0.E+000)); -#70604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70605 = PCURVE('',#44806,#70606); -#70606 = DEFINITIONAL_REPRESENTATION('',(#70607),#70611); -#70607 = LINE('',#70608,#70609); -#70608 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70609 = VECTOR('',#70610,1.); -#70610 = DIRECTION('',(1.,0.E+000)); -#70611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70612 = ADVANCED_FACE('',(#70613),#70556,.T.); -#70613 = FACE_BOUND('',#70614,.T.); -#70614 = EDGE_LOOP('',(#70615,#70616,#70638,#70661)); -#70615 = ORIENTED_EDGE('',*,*,#70537,.T.); -#70616 = ORIENTED_EDGE('',*,*,#70617,.T.); -#70617 = EDGE_CURVE('',#70540,#70618,#70620,.T.); -#70618 = VERTEX_POINT('',#70619); -#70619 = CARTESIAN_POINT('',(0.835,0.165,1.05)); -#70620 = SURFACE_CURVE('',#70621,(#70625,#70631),.PCURVE_S1.); -#70621 = LINE('',#70622,#70623); -#70622 = CARTESIAN_POINT('',(0.465,0.165,1.05)); -#70623 = VECTOR('',#70624,1.); -#70624 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70625 = PCURVE('',#70556,#70626); -#70626 = DEFINITIONAL_REPRESENTATION('',(#70627),#70630); -#70627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70628,#70629),.UNSPECIFIED., +#72955 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#72956 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#72957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72958 = ORIENTED_EDGE('',*,*,#72959,.F.); +#72959 = EDGE_CURVE('',#46691,#72932,#72960,.T.); +#72960 = SURFACE_CURVE('',#72961,(#72965,#72972),.PCURVE_S1.); +#72961 = LINE('',#72962,#72963); +#72962 = CARTESIAN_POINT('',(0.465,0.165,-1.15)); +#72963 = VECTOR('',#72964,1.); +#72964 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72965 = PCURVE('',#46706,#72966); +#72966 = DEFINITIONAL_REPRESENTATION('',(#72967),#72971); +#72967 = LINE('',#72968,#72969); +#72968 = CARTESIAN_POINT('',(1.15,0.165)); +#72969 = VECTOR('',#72970,1.); +#72970 = DIRECTION('',(-1.,0.E+000)); +#72971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72972 = PCURVE('',#46734,#72973); +#72973 = DEFINITIONAL_REPRESENTATION('',(#72974),#72978); +#72974 = LINE('',#72975,#72976); +#72975 = CARTESIAN_POINT('',(2.2,0.E+000)); +#72976 = VECTOR('',#72977,1.); +#72977 = DIRECTION('',(-1.,0.E+000)); +#72978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72979 = ORIENTED_EDGE('',*,*,#46690,.F.); +#72980 = ORIENTED_EDGE('',*,*,#48516,.T.); +#72981 = ORIENTED_EDGE('',*,*,#47933,.F.); +#72982 = ORIENTED_EDGE('',*,*,#47210,.T.); +#72983 = ORIENTED_EDGE('',*,*,#72984,.F.); +#72984 = EDGE_CURVE('',#72930,#47183,#72985,.T.); +#72985 = SURFACE_CURVE('',#72986,(#72990,#72997),.PCURVE_S1.); +#72986 = LINE('',#72987,#72988); +#72987 = CARTESIAN_POINT('',(0.465,0.265,1.15)); +#72988 = VECTOR('',#72989,1.); +#72989 = DIRECTION('',(0.E+000,0.E+000,1.)); +#72990 = PCURVE('',#46706,#72991); +#72991 = DEFINITIONAL_REPRESENTATION('',(#72992),#72996); +#72992 = LINE('',#72993,#72994); +#72993 = CARTESIAN_POINT('',(-1.15,0.265)); +#72994 = VECTOR('',#72995,1.); +#72995 = DIRECTION('',(-1.,0.E+000)); +#72996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#72997 = PCURVE('',#47198,#72998); +#72998 = DEFINITIONAL_REPRESENTATION('',(#72999),#73003); +#72999 = LINE('',#73000,#73001); +#73000 = CARTESIAN_POINT('',(2.3,0.E+000)); +#73001 = VECTOR('',#73002,1.); +#73002 = DIRECTION('',(1.,0.E+000)); +#73003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73004 = ADVANCED_FACE('',(#73005),#72948,.T.); +#73005 = FACE_BOUND('',#73006,.T.); +#73006 = EDGE_LOOP('',(#73007,#73008,#73030,#73053)); +#73007 = ORIENTED_EDGE('',*,*,#72929,.T.); +#73008 = ORIENTED_EDGE('',*,*,#73009,.T.); +#73009 = EDGE_CURVE('',#72932,#73010,#73012,.T.); +#73010 = VERTEX_POINT('',#73011); +#73011 = CARTESIAN_POINT('',(0.835,0.165,1.05)); +#73012 = SURFACE_CURVE('',#73013,(#73017,#73023),.PCURVE_S1.); +#73013 = LINE('',#73014,#73015); +#73014 = CARTESIAN_POINT('',(0.465,0.165,1.05)); +#73015 = VECTOR('',#73016,1.); +#73016 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73017 = PCURVE('',#72948,#73018); +#73018 = DEFINITIONAL_REPRESENTATION('',(#73019),#73022); +#73019 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73020,#73021),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70628 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); -#70629 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70631 = PCURVE('',#44342,#70632); -#70632 = DEFINITIONAL_REPRESENTATION('',(#70633),#70637); -#70633 = LINE('',#70634,#70635); -#70634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#70635 = VECTOR('',#70636,1.); -#70636 = DIRECTION('',(0.E+000,1.)); -#70637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70638 = ORIENTED_EDGE('',*,*,#70639,.F.); -#70639 = EDGE_CURVE('',#70640,#70618,#70642,.T.); -#70640 = VERTEX_POINT('',#70641); -#70641 = CARTESIAN_POINT('',(0.835,0.265,1.15)); -#70642 = SURFACE_CURVE('',#70643,(#70648,#70654),.PCURVE_S1.); -#70643 = CIRCLE('',#70644,0.1); -#70644 = AXIS2_PLACEMENT_3D('',#70645,#70646,#70647); -#70645 = CARTESIAN_POINT('',(0.835,0.265,1.05)); -#70646 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70647 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70648 = PCURVE('',#70556,#70649); -#70649 = DEFINITIONAL_REPRESENTATION('',(#70650),#70653); -#70650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70651,#70652),.UNSPECIFIED., +#73020 = CARTESIAN_POINT('',(4.712388980385,0.E+000)); +#73021 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#73022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73023 = PCURVE('',#46734,#73024); +#73024 = DEFINITIONAL_REPRESENTATION('',(#73025),#73029); +#73025 = LINE('',#73026,#73027); +#73026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#73027 = VECTOR('',#73028,1.); +#73028 = DIRECTION('',(0.E+000,1.)); +#73029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73030 = ORIENTED_EDGE('',*,*,#73031,.F.); +#73031 = EDGE_CURVE('',#73032,#73010,#73034,.T.); +#73032 = VERTEX_POINT('',#73033); +#73033 = CARTESIAN_POINT('',(0.835,0.265,1.15)); +#73034 = SURFACE_CURVE('',#73035,(#73040,#73046),.PCURVE_S1.); +#73035 = CIRCLE('',#73036,0.1); +#73036 = AXIS2_PLACEMENT_3D('',#73037,#73038,#73039); +#73037 = CARTESIAN_POINT('',(0.835,0.265,1.05)); +#73038 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73039 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73040 = PCURVE('',#72948,#73041); +#73041 = DEFINITIONAL_REPRESENTATION('',(#73042),#73045); +#73042 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73043,#73044),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#70651 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70652 = CARTESIAN_POINT('',(4.712388980385,0.37)); -#70653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70654 = PCURVE('',#44370,#70655); -#70655 = DEFINITIONAL_REPRESENTATION('',(#70656),#70660); -#70656 = CIRCLE('',#70657,0.1); -#70657 = AXIS2_PLACEMENT_2D('',#70658,#70659); -#70658 = CARTESIAN_POINT('',(-1.05,0.265)); -#70659 = DIRECTION('',(-1.,0.E+000)); -#70660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70661 = ORIENTED_EDGE('',*,*,#70662,.F.); -#70662 = EDGE_CURVE('',#70538,#70640,#70663,.T.); -#70663 = SURFACE_CURVE('',#70664,(#70668,#70674),.PCURVE_S1.); -#70664 = LINE('',#70665,#70666); -#70665 = CARTESIAN_POINT('',(0.465,0.265,1.15)); -#70666 = VECTOR('',#70667,1.); -#70667 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70668 = PCURVE('',#70556,#70669); -#70669 = DEFINITIONAL_REPRESENTATION('',(#70670),#70673); -#70670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#70671,#70672),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); -#70671 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#70672 = CARTESIAN_POINT('',(3.14159265359,0.37)); -#70673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#73043 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#73044 = CARTESIAN_POINT('',(4.712388980385,0.37)); +#73045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70674 = PCURVE('',#44806,#70675); -#70675 = DEFINITIONAL_REPRESENTATION('',(#70676),#70680); -#70676 = LINE('',#70677,#70678); -#70677 = CARTESIAN_POINT('',(2.3,0.E+000)); -#70678 = VECTOR('',#70679,1.); -#70679 = DIRECTION('',(0.E+000,1.)); -#70680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#73046 = PCURVE('',#46762,#73047); +#73047 = DEFINITIONAL_REPRESENTATION('',(#73048),#73052); +#73048 = CIRCLE('',#73049,0.1); +#73049 = AXIS2_PLACEMENT_2D('',#73050,#73051); +#73050 = CARTESIAN_POINT('',(-1.05,0.265)); +#73051 = DIRECTION('',(-1.,0.E+000)); +#73052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#70681 = ADVANCED_FACE('',(#70682),#44806,.F.); -#70682 = FACE_BOUND('',#70683,.F.); -#70683 = EDGE_LOOP('',(#70684,#70685,#70686,#70687)); -#70684 = ORIENTED_EDGE('',*,*,#70662,.F.); -#70685 = ORIENTED_EDGE('',*,*,#70592,.T.); -#70686 = ORIENTED_EDGE('',*,*,#44790,.T.); -#70687 = ORIENTED_EDGE('',*,*,#70688,.F.); -#70688 = EDGE_CURVE('',#70640,#44768,#70689,.T.); -#70689 = SURFACE_CURVE('',#70690,(#70694,#70701),.PCURVE_S1.); -#70690 = LINE('',#70691,#70692); -#70691 = CARTESIAN_POINT('',(0.835,0.265,1.15)); -#70692 = VECTOR('',#70693,1.); -#70693 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70694 = PCURVE('',#44806,#70695); -#70695 = DEFINITIONAL_REPRESENTATION('',(#70696),#70700); -#70696 = LINE('',#70697,#70698); -#70697 = CARTESIAN_POINT('',(2.3,0.37)); -#70698 = VECTOR('',#70699,1.); -#70699 = DIRECTION('',(1.,0.E+000)); -#70700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70701 = PCURVE('',#44370,#70702); -#70702 = DEFINITIONAL_REPRESENTATION('',(#70703),#70707); -#70703 = LINE('',#70704,#70705); -#70704 = CARTESIAN_POINT('',(-1.15,0.265)); -#70705 = VECTOR('',#70706,1.); -#70706 = DIRECTION('',(-1.,0.E+000)); -#70707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70708 = ADVANCED_FACE('',(#70709),#44370,.F.); -#70709 = FACE_BOUND('',#70710,.F.); -#70710 = EDGE_LOOP('',(#70711,#70712,#70713,#70714,#70715,#70716,#70717) - ); -#70711 = ORIENTED_EDGE('',*,*,#70639,.F.); -#70712 = ORIENTED_EDGE('',*,*,#70688,.T.); -#70713 = ORIENTED_EDGE('',*,*,#44767,.F.); -#70714 = ORIENTED_EDGE('',*,*,#45613,.T.); -#70715 = ORIENTED_EDGE('',*,*,#46173,.F.); -#70716 = ORIENTED_EDGE('',*,*,#44354,.T.); -#70717 = ORIENTED_EDGE('',*,*,#70718,.T.); -#70718 = EDGE_CURVE('',#44327,#70618,#70719,.T.); -#70719 = SURFACE_CURVE('',#70720,(#70724,#70731),.PCURVE_S1.); -#70720 = LINE('',#70721,#70722); -#70721 = CARTESIAN_POINT('',(0.835,0.165,-1.15)); -#70722 = VECTOR('',#70723,1.); -#70723 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70724 = PCURVE('',#44370,#70725); -#70725 = DEFINITIONAL_REPRESENTATION('',(#70726),#70730); -#70726 = LINE('',#70727,#70728); -#70727 = CARTESIAN_POINT('',(1.15,0.165)); -#70728 = VECTOR('',#70729,1.); -#70729 = DIRECTION('',(-1.,0.E+000)); -#70730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70731 = PCURVE('',#44342,#70732); -#70732 = DEFINITIONAL_REPRESENTATION('',(#70733),#70737); -#70733 = LINE('',#70734,#70735); -#70734 = CARTESIAN_POINT('',(2.2,0.37)); -#70735 = VECTOR('',#70736,1.); -#70736 = DIRECTION('',(-1.,0.E+000)); -#70737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#70738 = ADVANCED_FACE('',(#70739),#44342,.T.); -#70739 = FACE_BOUND('',#70740,.F.); -#70740 = EDGE_LOOP('',(#70741,#70742,#70743,#70744)); -#70741 = ORIENTED_EDGE('',*,*,#44326,.F.); -#70742 = ORIENTED_EDGE('',*,*,#70567,.T.); -#70743 = ORIENTED_EDGE('',*,*,#70617,.T.); -#70744 = ORIENTED_EDGE('',*,*,#70718,.F.); -#70745 = ADVANCED_FACE('',(#70746),#43204,.F.); -#70746 = FACE_BOUND('',#70747,.F.); -#70747 = EDGE_LOOP('',(#70748,#70749,#70750,#70751,#70752,#70753,#70754) - ); -#70748 = ORIENTED_EDGE('',*,*,#44649,.F.); -#70749 = ORIENTED_EDGE('',*,*,#44720,.T.); -#70750 = ORIENTED_EDGE('',*,*,#45279,.F.); -#70751 = ORIENTED_EDGE('',*,*,#45659,.T.); -#70752 = ORIENTED_EDGE('',*,*,#46198,.F.); -#70753 = ORIENTED_EDGE('',*,*,#43188,.T.); -#70754 = ORIENTED_EDGE('',*,*,#44490,.T.); -#70755 = ADVANCED_FACE('',(#70756),#44006,.T.); -#70756 = FACE_BOUND('',#70757,.F.); -#70757 = EDGE_LOOP('',(#70758,#70759,#70760,#70761)); -#70758 = ORIENTED_EDGE('',*,*,#43990,.F.); -#70759 = ORIENTED_EDGE('',*,*,#45786,.T.); -#70760 = ORIENTED_EDGE('',*,*,#45856,.T.); -#70761 = ORIENTED_EDGE('',*,*,#45977,.F.); -#70762 = ADVANCED_FACE('',(#70763),#39100,.T.); -#70763 = FACE_BOUND('',#70764,.F.); -#70764 = EDGE_LOOP('',(#70765,#70766,#70767,#70768)); -#70765 = ORIENTED_EDGE('',*,*,#39329,.T.); -#70766 = ORIENTED_EDGE('',*,*,#39397,.F.); -#70767 = ORIENTED_EDGE('',*,*,#39087,.T.); -#70768 = ORIENTED_EDGE('',*,*,#39168,.T.); -#70769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#70773)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#70770,#70771,#70772)) +#73053 = ORIENTED_EDGE('',*,*,#73054,.F.); +#73054 = EDGE_CURVE('',#72930,#73032,#73055,.T.); +#73055 = SURFACE_CURVE('',#73056,(#73060,#73066),.PCURVE_S1.); +#73056 = LINE('',#73057,#73058); +#73057 = CARTESIAN_POINT('',(0.465,0.265,1.15)); +#73058 = VECTOR('',#73059,1.); +#73059 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73060 = PCURVE('',#72948,#73061); +#73061 = DEFINITIONAL_REPRESENTATION('',(#73062),#73065); +#73062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73063,#73064),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.37),.PIECEWISE_BEZIER_KNOTS.); +#73063 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#73064 = CARTESIAN_POINT('',(3.14159265359,0.37)); +#73065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73066 = PCURVE('',#47198,#73067); +#73067 = DEFINITIONAL_REPRESENTATION('',(#73068),#73072); +#73068 = LINE('',#73069,#73070); +#73069 = CARTESIAN_POINT('',(2.3,0.E+000)); +#73070 = VECTOR('',#73071,1.); +#73071 = DIRECTION('',(0.E+000,1.)); +#73072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73073 = ADVANCED_FACE('',(#73074),#47198,.F.); +#73074 = FACE_BOUND('',#73075,.F.); +#73075 = EDGE_LOOP('',(#73076,#73077,#73078,#73079)); +#73076 = ORIENTED_EDGE('',*,*,#73054,.F.); +#73077 = ORIENTED_EDGE('',*,*,#72984,.T.); +#73078 = ORIENTED_EDGE('',*,*,#47182,.T.); +#73079 = ORIENTED_EDGE('',*,*,#73080,.F.); +#73080 = EDGE_CURVE('',#73032,#47160,#73081,.T.); +#73081 = SURFACE_CURVE('',#73082,(#73086,#73093),.PCURVE_S1.); +#73082 = LINE('',#73083,#73084); +#73083 = CARTESIAN_POINT('',(0.835,0.265,1.15)); +#73084 = VECTOR('',#73085,1.); +#73085 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73086 = PCURVE('',#47198,#73087); +#73087 = DEFINITIONAL_REPRESENTATION('',(#73088),#73092); +#73088 = LINE('',#73089,#73090); +#73089 = CARTESIAN_POINT('',(2.3,0.37)); +#73090 = VECTOR('',#73091,1.); +#73091 = DIRECTION('',(1.,0.E+000)); +#73092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73093 = PCURVE('',#46762,#73094); +#73094 = DEFINITIONAL_REPRESENTATION('',(#73095),#73099); +#73095 = LINE('',#73096,#73097); +#73096 = CARTESIAN_POINT('',(-1.15,0.265)); +#73097 = VECTOR('',#73098,1.); +#73098 = DIRECTION('',(-1.,0.E+000)); +#73099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73100 = ADVANCED_FACE('',(#73101),#46762,.F.); +#73101 = FACE_BOUND('',#73102,.F.); +#73102 = EDGE_LOOP('',(#73103,#73104,#73105,#73106,#73107,#73108,#73109) + ); +#73103 = ORIENTED_EDGE('',*,*,#73031,.F.); +#73104 = ORIENTED_EDGE('',*,*,#73080,.T.); +#73105 = ORIENTED_EDGE('',*,*,#47159,.F.); +#73106 = ORIENTED_EDGE('',*,*,#48005,.T.); +#73107 = ORIENTED_EDGE('',*,*,#48565,.F.); +#73108 = ORIENTED_EDGE('',*,*,#46746,.T.); +#73109 = ORIENTED_EDGE('',*,*,#73110,.T.); +#73110 = EDGE_CURVE('',#46719,#73010,#73111,.T.); +#73111 = SURFACE_CURVE('',#73112,(#73116,#73123),.PCURVE_S1.); +#73112 = LINE('',#73113,#73114); +#73113 = CARTESIAN_POINT('',(0.835,0.165,-1.15)); +#73114 = VECTOR('',#73115,1.); +#73115 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73116 = PCURVE('',#46762,#73117); +#73117 = DEFINITIONAL_REPRESENTATION('',(#73118),#73122); +#73118 = LINE('',#73119,#73120); +#73119 = CARTESIAN_POINT('',(1.15,0.165)); +#73120 = VECTOR('',#73121,1.); +#73121 = DIRECTION('',(-1.,0.E+000)); +#73122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73123 = PCURVE('',#46734,#73124); +#73124 = DEFINITIONAL_REPRESENTATION('',(#73125),#73129); +#73125 = LINE('',#73126,#73127); +#73126 = CARTESIAN_POINT('',(2.2,0.37)); +#73127 = VECTOR('',#73128,1.); +#73128 = DIRECTION('',(-1.,0.E+000)); +#73129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73130 = ADVANCED_FACE('',(#73131),#46734,.T.); +#73131 = FACE_BOUND('',#73132,.F.); +#73132 = EDGE_LOOP('',(#73133,#73134,#73135,#73136)); +#73133 = ORIENTED_EDGE('',*,*,#46718,.F.); +#73134 = ORIENTED_EDGE('',*,*,#72959,.T.); +#73135 = ORIENTED_EDGE('',*,*,#73009,.T.); +#73136 = ORIENTED_EDGE('',*,*,#73110,.F.); +#73137 = ADVANCED_FACE('',(#73138),#45596,.F.); +#73138 = FACE_BOUND('',#73139,.F.); +#73139 = EDGE_LOOP('',(#73140,#73141,#73142,#73143,#73144,#73145,#73146) + ); +#73140 = ORIENTED_EDGE('',*,*,#47041,.F.); +#73141 = ORIENTED_EDGE('',*,*,#47112,.T.); +#73142 = ORIENTED_EDGE('',*,*,#47671,.F.); +#73143 = ORIENTED_EDGE('',*,*,#48051,.T.); +#73144 = ORIENTED_EDGE('',*,*,#48590,.F.); +#73145 = ORIENTED_EDGE('',*,*,#45580,.T.); +#73146 = ORIENTED_EDGE('',*,*,#46882,.T.); +#73147 = ADVANCED_FACE('',(#73148),#46398,.T.); +#73148 = FACE_BOUND('',#73149,.F.); +#73149 = EDGE_LOOP('',(#73150,#73151,#73152,#73153)); +#73150 = ORIENTED_EDGE('',*,*,#46382,.F.); +#73151 = ORIENTED_EDGE('',*,*,#48178,.T.); +#73152 = ORIENTED_EDGE('',*,*,#48248,.T.); +#73153 = ORIENTED_EDGE('',*,*,#48369,.F.); +#73154 = ADVANCED_FACE('',(#73155),#41492,.T.); +#73155 = FACE_BOUND('',#73156,.F.); +#73156 = EDGE_LOOP('',(#73157,#73158,#73159,#73160)); +#73157 = ORIENTED_EDGE('',*,*,#41721,.T.); +#73158 = ORIENTED_EDGE('',*,*,#41789,.F.); +#73159 = ORIENTED_EDGE('',*,*,#41479,.T.); +#73160 = ORIENTED_EDGE('',*,*,#41560,.T.); +#73161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#73165)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#73162,#73163,#73164)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#70770 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#70771 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#70772 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#70773 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#70770, +#73162 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#73163 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#73164 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#73165 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-006),#73162, 'distance_accuracy_value','confusion accuracy'); -#70774 = SHAPE_DEFINITION_REPRESENTATION(#70775,#37625); -#70775 = PRODUCT_DEFINITION_SHAPE('','',#70776); -#70776 = PRODUCT_DEFINITION('design','',#70777,#70780); -#70777 = PRODUCT_DEFINITION_FORMATION('','',#70778); -#70778 = PRODUCT('Open CASCADE STEP translator 6.2 133.37.1.1', - 'Open CASCADE STEP translator 6.2 133.37.1.1','',(#70779)); -#70779 = PRODUCT_CONTEXT('',#2,'mechanical'); -#70780 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#70781 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#70782,#70784); -#70782 = ( REPRESENTATION_RELATIONSHIP('','',#37625,#37611) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#70783) +#73166 = SHAPE_DEFINITION_REPRESENTATION(#73167,#40017); +#73167 = PRODUCT_DEFINITION_SHAPE('','',#73168); +#73168 = PRODUCT_DEFINITION('design','',#73169,#73172); +#73169 = PRODUCT_DEFINITION_FORMATION('','',#73170); +#73170 = PRODUCT('Open CASCADE STEP translator 6.2 36.37.1.1', + 'Open CASCADE STEP translator 6.2 36.37.1.1','',(#73171)); +#73171 = PRODUCT_CONTEXT('',#2,'mechanical'); +#73172 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#73173 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#73174,#73176); +#73174 = ( REPRESENTATION_RELATIONSHIP('','',#40017,#40003) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#73175) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#70783 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37612); -#70784 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #70785); -#70785 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('214','=>[0:1:1:56]','',#37606, - #70776,$); -#70786 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#70778)); -#70787 = SHAPE_REPRESENTATION('',(#11,#70788,#70817,#70846,#70875,#70904 - ,#70933,#70962,#70991,#71020,#71049,#71078),#71107); -#70788 = GEOMETRIC_CURVE_SET('',(#70789,#70796,#70803,#70810)); -#70789 = TRIMMED_CURVE('',#70790,(#70794,PARAMETER_VALUE(0.E+000)),( - #70795,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); -#70790 = LINE('',#70791,#70792); -#70791 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); -#70792 = VECTOR('',#70793,1.); -#70793 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70794 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); -#70795 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); -#70796 = TRIMMED_CURVE('',#70797,(#70801,PARAMETER_VALUE(0.E+000)),( - #70802,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#70797 = LINE('',#70798,#70799); -#70798 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); -#70799 = VECTOR('',#70800,1.); -#70800 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70801 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); -#70802 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); -#70803 = TRIMMED_CURVE('',#70804,(#70808,PARAMETER_VALUE(0.E+000)),( - #70809,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); -#70804 = LINE('',#70805,#70806); -#70805 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); -#70806 = VECTOR('',#70807,1.); -#70807 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70808 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); -#70809 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); -#70810 = TRIMMED_CURVE('',#70811,(#70815,PARAMETER_VALUE(0.E+000)),( - #70816,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#70811 = LINE('',#70812,#70813); -#70812 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); -#70813 = VECTOR('',#70814,1.); -#70814 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70815 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); -#70816 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); -#70817 = GEOMETRIC_CURVE_SET('',(#70818,#70825,#70832,#70839)); -#70818 = TRIMMED_CURVE('',#70819,(#70823,PARAMETER_VALUE(0.E+000)),( - #70824,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); -#70819 = LINE('',#70820,#70821); -#70820 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); -#70821 = VECTOR('',#70822,1.); -#70822 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70823 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); -#70824 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); -#70825 = TRIMMED_CURVE('',#70826,(#70830,PARAMETER_VALUE(0.E+000)),( - #70831,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#70826 = LINE('',#70827,#70828); -#70827 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); -#70828 = VECTOR('',#70829,1.); -#70829 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70830 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); -#70831 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); -#70832 = TRIMMED_CURVE('',#70833,(#70837,PARAMETER_VALUE(0.E+000)),( - #70838,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); -#70833 = LINE('',#70834,#70835); -#70834 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); -#70835 = VECTOR('',#70836,1.); -#70836 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70837 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); -#70838 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); -#70839 = TRIMMED_CURVE('',#70840,(#70844,PARAMETER_VALUE(0.E+000)),( - #70845,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#70840 = LINE('',#70841,#70842); -#70841 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); -#70842 = VECTOR('',#70843,1.); -#70843 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70844 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); -#70845 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); -#70846 = GEOMETRIC_CURVE_SET('',(#70847,#70854,#70861,#70868)); -#70847 = TRIMMED_CURVE('',#70848,(#70852,PARAMETER_VALUE(0.E+000)),( - #70853,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70848 = LINE('',#70849,#70850); -#70849 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); -#70850 = VECTOR('',#70851,1.); -#70851 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70852 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); -#70853 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); -#70854 = TRIMMED_CURVE('',#70855,(#70859,PARAMETER_VALUE(0.E+000)),( - #70860,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70855 = LINE('',#70856,#70857); -#70856 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); -#70857 = VECTOR('',#70858,1.); -#70858 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70859 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); -#70860 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); -#70861 = TRIMMED_CURVE('',#70862,(#70866,PARAMETER_VALUE(0.E+000)),( - #70867,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70862 = LINE('',#70863,#70864); -#70863 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); -#70864 = VECTOR('',#70865,1.); -#70865 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70866 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); -#70867 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); -#70868 = TRIMMED_CURVE('',#70869,(#70873,PARAMETER_VALUE(0.E+000)),( - #70874,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70869 = LINE('',#70870,#70871); -#70870 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); -#70871 = VECTOR('',#70872,1.); -#70872 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70873 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); -#70874 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); -#70875 = GEOMETRIC_CURVE_SET('',(#70876,#70883,#70890,#70897)); -#70876 = TRIMMED_CURVE('',#70877,(#70881,PARAMETER_VALUE(0.E+000)),( - #70882,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70877 = LINE('',#70878,#70879); -#70878 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); -#70879 = VECTOR('',#70880,1.); -#70880 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70881 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); -#70882 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); -#70883 = TRIMMED_CURVE('',#70884,(#70888,PARAMETER_VALUE(0.E+000)),( - #70889,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70884 = LINE('',#70885,#70886); -#70885 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); -#70886 = VECTOR('',#70887,1.); -#70887 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70888 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); -#70889 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); -#70890 = TRIMMED_CURVE('',#70891,(#70895,PARAMETER_VALUE(0.E+000)),( - #70896,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70891 = LINE('',#70892,#70893); -#70892 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); -#70893 = VECTOR('',#70894,1.); -#70894 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70895 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); -#70896 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); -#70897 = TRIMMED_CURVE('',#70898,(#70902,PARAMETER_VALUE(0.E+000)),( - #70903,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70898 = LINE('',#70899,#70900); -#70899 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); -#70900 = VECTOR('',#70901,1.); -#70901 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70902 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); -#70903 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); -#70904 = GEOMETRIC_CURVE_SET('',(#70905,#70912,#70919,#70926)); -#70905 = TRIMMED_CURVE('',#70906,(#70910,PARAMETER_VALUE(0.E+000)),( - #70911,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70906 = LINE('',#70907,#70908); -#70907 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); -#70908 = VECTOR('',#70909,1.); -#70909 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70910 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); -#70911 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); -#70912 = TRIMMED_CURVE('',#70913,(#70917,PARAMETER_VALUE(0.E+000)),( - #70918,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70913 = LINE('',#70914,#70915); -#70914 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); -#70915 = VECTOR('',#70916,1.); -#70916 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70917 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); -#70918 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); -#70919 = TRIMMED_CURVE('',#70920,(#70924,PARAMETER_VALUE(0.E+000)),( - #70925,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70920 = LINE('',#70921,#70922); -#70921 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); -#70922 = VECTOR('',#70923,1.); -#70923 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70924 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); -#70925 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); -#70926 = TRIMMED_CURVE('',#70927,(#70931,PARAMETER_VALUE(0.E+000)),( - #70932,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70927 = LINE('',#70928,#70929); -#70928 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); -#70929 = VECTOR('',#70930,1.); -#70930 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70931 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); -#70932 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); -#70933 = GEOMETRIC_CURVE_SET('',(#70934,#70941,#70948,#70955)); -#70934 = TRIMMED_CURVE('',#70935,(#70939,PARAMETER_VALUE(0.E+000)),( - #70940,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70935 = LINE('',#70936,#70937); -#70936 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); -#70937 = VECTOR('',#70938,1.); -#70938 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70939 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); -#70940 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); -#70941 = TRIMMED_CURVE('',#70942,(#70946,PARAMETER_VALUE(0.E+000)),( - #70947,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70942 = LINE('',#70943,#70944); -#70943 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); -#70944 = VECTOR('',#70945,1.); -#70945 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70946 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); -#70947 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); -#70948 = TRIMMED_CURVE('',#70949,(#70953,PARAMETER_VALUE(0.E+000)),( - #70954,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70949 = LINE('',#70950,#70951); -#70950 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); -#70951 = VECTOR('',#70952,1.); -#70952 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70953 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); -#70954 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); -#70955 = TRIMMED_CURVE('',#70956,(#70960,PARAMETER_VALUE(0.E+000)),( - #70961,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70956 = LINE('',#70957,#70958); -#70957 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); -#70958 = VECTOR('',#70959,1.); -#70959 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70960 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); -#70961 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); -#70962 = GEOMETRIC_CURVE_SET('',(#70963,#70970,#70977,#70984)); -#70963 = TRIMMED_CURVE('',#70964,(#70968,PARAMETER_VALUE(0.E+000)),( - #70969,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70964 = LINE('',#70965,#70966); -#70965 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); -#70966 = VECTOR('',#70967,1.); -#70967 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#70968 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); -#70969 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); -#70970 = TRIMMED_CURVE('',#70971,(#70975,PARAMETER_VALUE(0.E+000)),( - #70976,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70971 = LINE('',#70972,#70973); -#70972 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); -#70973 = VECTOR('',#70974,1.); -#70974 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#70975 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); -#70976 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); -#70977 = TRIMMED_CURVE('',#70978,(#70982,PARAMETER_VALUE(0.E+000)),( - #70983,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); -#70978 = LINE('',#70979,#70980); -#70979 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); -#70980 = VECTOR('',#70981,1.); -#70981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70982 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); -#70983 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); -#70984 = TRIMMED_CURVE('',#70985,(#70989,PARAMETER_VALUE(0.E+000)),( - #70990,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); -#70985 = LINE('',#70986,#70987); -#70986 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); -#70987 = VECTOR('',#70988,1.); -#70988 = DIRECTION('',(0.E+000,0.E+000,1.)); -#70989 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); -#70990 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); -#70991 = GEOMETRIC_CURVE_SET('',(#70992,#70999,#71006,#71013)); -#70992 = TRIMMED_CURVE('',#70993,(#70997,PARAMETER_VALUE(0.E+000)),( - #70998,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); -#70993 = LINE('',#70994,#70995); -#70994 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); -#70995 = VECTOR('',#70996,1.); -#70996 = DIRECTION('',(1.,0.E+000,0.E+000)); -#70997 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); -#70998 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); -#70999 = TRIMMED_CURVE('',#71000,(#71004,PARAMETER_VALUE(0.E+000)),( - #71005,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); -#71000 = LINE('',#71001,#71002); -#71001 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); -#71002 = VECTOR('',#71003,1.); -#71003 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71004 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); -#71005 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); -#71006 = TRIMMED_CURVE('',#71007,(#71011,PARAMETER_VALUE(0.E+000)),( - #71012,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); -#71007 = LINE('',#71008,#71009); -#71008 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); -#71009 = VECTOR('',#71010,1.); -#71010 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71011 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); -#71012 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); -#71013 = TRIMMED_CURVE('',#71014,(#71018,PARAMETER_VALUE(0.E+000)),( - #71019,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); -#71014 = LINE('',#71015,#71016); -#71015 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); -#71016 = VECTOR('',#71017,1.); -#71017 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71018 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); -#71019 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); -#71020 = GEOMETRIC_CURVE_SET('',(#71021,#71028,#71035,#71042)); -#71021 = TRIMMED_CURVE('',#71022,(#71026,PARAMETER_VALUE(0.E+000)),( - #71027,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); -#71022 = LINE('',#71023,#71024); -#71023 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); -#71024 = VECTOR('',#71025,1.); -#71025 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71026 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); -#71027 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); -#71028 = TRIMMED_CURVE('',#71029,(#71033,PARAMETER_VALUE(0.E+000)),( - #71034,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); -#71029 = LINE('',#71030,#71031); -#71030 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); -#71031 = VECTOR('',#71032,1.); -#71032 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71033 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); -#71034 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); -#71035 = TRIMMED_CURVE('',#71036,(#71040,PARAMETER_VALUE(0.E+000)),( - #71041,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); -#71036 = LINE('',#71037,#71038); -#71037 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); -#71038 = VECTOR('',#71039,1.); -#71039 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71040 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); -#71041 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); -#71042 = TRIMMED_CURVE('',#71043,(#71047,PARAMETER_VALUE(0.E+000)),( - #71048,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); -#71043 = LINE('',#71044,#71045); -#71044 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); -#71045 = VECTOR('',#71046,1.); -#71046 = DIRECTION('',(1.,0.E+000,0.E+000)); -#71047 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); -#71048 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); -#71049 = GEOMETRIC_CURVE_SET('',(#71050,#71057,#71064,#71071)); -#71050 = TRIMMED_CURVE('',#71051,(#71055,PARAMETER_VALUE(0.E+000)),( - #71056,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); -#71051 = LINE('',#71052,#71053); -#71052 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); -#71053 = VECTOR('',#71054,1.); -#71054 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71055 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); -#71056 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); -#71057 = TRIMMED_CURVE('',#71058,(#71062,PARAMETER_VALUE(0.E+000)),( - #71063,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#71058 = LINE('',#71059,#71060); -#71059 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); -#71060 = VECTOR('',#71061,1.); -#71061 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71062 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); -#71063 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); -#71064 = TRIMMED_CURVE('',#71065,(#71069,PARAMETER_VALUE(0.E+000)),( - #71070,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); -#71065 = LINE('',#71066,#71067); -#71066 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); -#71067 = VECTOR('',#71068,1.); -#71068 = DIRECTION('',(1.,0.E+000,0.E+000)); -#71069 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); -#71070 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); -#71071 = TRIMMED_CURVE('',#71072,(#71076,PARAMETER_VALUE(0.E+000)),( - #71077,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#71072 = LINE('',#71073,#71074); -#71073 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); -#71074 = VECTOR('',#71075,1.); -#71075 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71076 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); -#71077 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); -#71078 = GEOMETRIC_CURVE_SET('',(#71079,#71086,#71093,#71100)); -#71079 = TRIMMED_CURVE('',#71080,(#71084,PARAMETER_VALUE(0.E+000)),( - #71085,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); -#71080 = LINE('',#71081,#71082); -#71081 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); -#71082 = VECTOR('',#71083,1.); -#71083 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71084 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); -#71085 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); -#71086 = TRIMMED_CURVE('',#71087,(#71091,PARAMETER_VALUE(0.E+000)),( - #71092,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#71087 = LINE('',#71088,#71089); -#71088 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); -#71089 = VECTOR('',#71090,1.); -#71090 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71091 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); -#71092 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); -#71093 = TRIMMED_CURVE('',#71094,(#71098,PARAMETER_VALUE(0.E+000)),( - #71099,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); -#71094 = LINE('',#71095,#71096); -#71095 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); -#71096 = VECTOR('',#71097,1.); -#71097 = DIRECTION('',(1.,0.E+000,0.E+000)); -#71098 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); -#71099 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); -#71100 = TRIMMED_CURVE('',#71101,(#71105,PARAMETER_VALUE(0.E+000)),( - #71106,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); -#71101 = LINE('',#71102,#71103); -#71102 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); -#71103 = VECTOR('',#71104,1.); -#71104 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71105 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); -#71106 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); -#71107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#71111)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#71108,#71109,#71110)) +#73175 = ITEM_DEFINED_TRANSFORMATION('','',#11,#40004); +#73176 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #73177); +#73177 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('315','=>[0:1:1:56]','',#39998, + #73168,$); +#73178 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#73170)); +#73179 = SHAPE_REPRESENTATION('',(#11,#73180,#73209,#73238,#73267,#73296 + ,#73325,#73354,#73383,#73412,#73441,#73470),#73499); +#73180 = GEOMETRIC_CURVE_SET('',(#73181,#73188,#73195,#73202)); +#73181 = TRIMMED_CURVE('',#73182,(#73186,PARAMETER_VALUE(0.E+000)),( + #73187,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); +#73182 = LINE('',#73183,#73184); +#73183 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); +#73184 = VECTOR('',#73185,1.); +#73185 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73186 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); +#73187 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); +#73188 = TRIMMED_CURVE('',#73189,(#73193,PARAMETER_VALUE(0.E+000)),( + #73194,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73189 = LINE('',#73190,#73191); +#73190 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); +#73191 = VECTOR('',#73192,1.); +#73192 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73193 = CARTESIAN_POINT('',(1.725,-1.225,1.15)); +#73194 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); +#73195 = TRIMMED_CURVE('',#73196,(#73200,PARAMETER_VALUE(0.E+000)),( + #73201,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); +#73196 = LINE('',#73197,#73198); +#73197 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); +#73198 = VECTOR('',#73199,1.); +#73199 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73200 = CARTESIAN_POINT('',(1.725,-1.225,-0.75)); +#73201 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); +#73202 = TRIMMED_CURVE('',#73203,(#73207,PARAMETER_VALUE(0.E+000)),( + #73208,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73203 = LINE('',#73204,#73205); +#73204 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); +#73205 = VECTOR('',#73206,1.); +#73206 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73207 = CARTESIAN_POINT('',(4.1,-1.225,-0.75)); +#73208 = CARTESIAN_POINT('',(4.1,-1.225,1.15)); +#73209 = GEOMETRIC_CURVE_SET('',(#73210,#73217,#73224,#73231)); +#73210 = TRIMMED_CURVE('',#73211,(#73215,PARAMETER_VALUE(0.E+000)),( + #73216,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); +#73211 = LINE('',#73212,#73213); +#73212 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); +#73213 = VECTOR('',#73214,1.); +#73214 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73215 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); +#73216 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); +#73217 = TRIMMED_CURVE('',#73218,(#73222,PARAMETER_VALUE(0.E+000)),( + #73223,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73218 = LINE('',#73219,#73220); +#73219 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); +#73220 = VECTOR('',#73221,1.); +#73221 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73222 = CARTESIAN_POINT('',(-4.1,-1.225,1.15)); +#73223 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); +#73224 = TRIMMED_CURVE('',#73225,(#73229,PARAMETER_VALUE(0.E+000)),( + #73230,PARAMETER_VALUE(2.375)),.T.,.PARAMETER.); +#73225 = LINE('',#73226,#73227); +#73226 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); +#73227 = VECTOR('',#73228,1.); +#73228 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73229 = CARTESIAN_POINT('',(-4.1,-1.225,-0.75)); +#73230 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); +#73231 = TRIMMED_CURVE('',#73232,(#73236,PARAMETER_VALUE(0.E+000)),( + #73237,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73232 = LINE('',#73233,#73234); +#73233 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); +#73234 = VECTOR('',#73235,1.); +#73235 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73236 = CARTESIAN_POINT('',(-1.725,-1.225,-0.75)); +#73237 = CARTESIAN_POINT('',(-1.725,-1.225,1.15)); +#73238 = GEOMETRIC_CURVE_SET('',(#73239,#73246,#73253,#73260)); +#73239 = TRIMMED_CURVE('',#73240,(#73244,PARAMETER_VALUE(0.E+000)),( + #73245,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73240 = LINE('',#73241,#73242); +#73241 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); +#73242 = VECTOR('',#73243,1.); +#73243 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73244 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); +#73245 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); +#73246 = TRIMMED_CURVE('',#73247,(#73251,PARAMETER_VALUE(0.E+000)),( + #73252,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73247 = LINE('',#73248,#73249); +#73248 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); +#73249 = VECTOR('',#73250,1.); +#73250 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73251 = CARTESIAN_POINT('',(1.075,-1.225,-1.77)); +#73252 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); +#73253 = TRIMMED_CURVE('',#73254,(#73258,PARAMETER_VALUE(0.E+000)),( + #73259,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73254 = LINE('',#73255,#73256); +#73255 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); +#73256 = VECTOR('',#73257,1.); +#73257 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73258 = CARTESIAN_POINT('',(1.075,-1.225,-3.15)); +#73259 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); +#73260 = TRIMMED_CURVE('',#73261,(#73265,PARAMETER_VALUE(0.E+000)),( + #73266,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73261 = LINE('',#73262,#73263); +#73262 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); +#73263 = VECTOR('',#73264,1.); +#73264 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73265 = CARTESIAN_POINT('',(1.525,-1.225,-3.15)); +#73266 = CARTESIAN_POINT('',(1.525,-1.225,-1.77)); +#73267 = GEOMETRIC_CURVE_SET('',(#73268,#73275,#73282,#73289)); +#73268 = TRIMMED_CURVE('',#73269,(#73273,PARAMETER_VALUE(0.E+000)),( + #73274,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73269 = LINE('',#73270,#73271); +#73270 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); +#73271 = VECTOR('',#73272,1.); +#73272 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73273 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); +#73274 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); +#73275 = TRIMMED_CURVE('',#73276,(#73280,PARAMETER_VALUE(0.E+000)),( + #73281,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73276 = LINE('',#73277,#73278); +#73277 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); +#73278 = VECTOR('',#73279,1.); +#73279 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73280 = CARTESIAN_POINT('',(0.425,-1.225,-1.77)); +#73281 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); +#73282 = TRIMMED_CURVE('',#73283,(#73287,PARAMETER_VALUE(0.E+000)),( + #73288,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73283 = LINE('',#73284,#73285); +#73284 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); +#73285 = VECTOR('',#73286,1.); +#73286 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73287 = CARTESIAN_POINT('',(0.425,-1.225,-3.15)); +#73288 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); +#73289 = TRIMMED_CURVE('',#73290,(#73294,PARAMETER_VALUE(0.E+000)),( + #73295,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73290 = LINE('',#73291,#73292); +#73291 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); +#73292 = VECTOR('',#73293,1.); +#73293 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73294 = CARTESIAN_POINT('',(0.875,-1.225,-3.15)); +#73295 = CARTESIAN_POINT('',(0.875,-1.225,-1.77)); +#73296 = GEOMETRIC_CURVE_SET('',(#73297,#73304,#73311,#73318)); +#73297 = TRIMMED_CURVE('',#73298,(#73302,PARAMETER_VALUE(0.E+000)),( + #73303,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73298 = LINE('',#73299,#73300); +#73299 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); +#73300 = VECTOR('',#73301,1.); +#73301 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73302 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); +#73303 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); +#73304 = TRIMMED_CURVE('',#73305,(#73309,PARAMETER_VALUE(0.E+000)),( + #73310,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73305 = LINE('',#73306,#73307); +#73306 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); +#73307 = VECTOR('',#73308,1.); +#73308 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73309 = CARTESIAN_POINT('',(-0.225,-1.225,-1.77)); +#73310 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); +#73311 = TRIMMED_CURVE('',#73312,(#73316,PARAMETER_VALUE(0.E+000)),( + #73317,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73312 = LINE('',#73313,#73314); +#73313 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); +#73314 = VECTOR('',#73315,1.); +#73315 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73316 = CARTESIAN_POINT('',(-0.225,-1.225,-3.15)); +#73317 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); +#73318 = TRIMMED_CURVE('',#73319,(#73323,PARAMETER_VALUE(0.E+000)),( + #73324,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73319 = LINE('',#73320,#73321); +#73320 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); +#73321 = VECTOR('',#73322,1.); +#73322 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73323 = CARTESIAN_POINT('',(0.225,-1.225,-3.15)); +#73324 = CARTESIAN_POINT('',(0.225,-1.225,-1.77)); +#73325 = GEOMETRIC_CURVE_SET('',(#73326,#73333,#73340,#73347)); +#73326 = TRIMMED_CURVE('',#73327,(#73331,PARAMETER_VALUE(0.E+000)),( + #73332,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73327 = LINE('',#73328,#73329); +#73328 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); +#73329 = VECTOR('',#73330,1.); +#73330 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73331 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); +#73332 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); +#73333 = TRIMMED_CURVE('',#73334,(#73338,PARAMETER_VALUE(0.E+000)),( + #73339,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73334 = LINE('',#73335,#73336); +#73335 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); +#73336 = VECTOR('',#73337,1.); +#73337 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73338 = CARTESIAN_POINT('',(-0.875,-1.225,-1.77)); +#73339 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); +#73340 = TRIMMED_CURVE('',#73341,(#73345,PARAMETER_VALUE(0.E+000)),( + #73346,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73341 = LINE('',#73342,#73343); +#73342 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); +#73343 = VECTOR('',#73344,1.); +#73344 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73345 = CARTESIAN_POINT('',(-0.875,-1.225,-3.15)); +#73346 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); +#73347 = TRIMMED_CURVE('',#73348,(#73352,PARAMETER_VALUE(0.E+000)),( + #73353,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73348 = LINE('',#73349,#73350); +#73349 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); +#73350 = VECTOR('',#73351,1.); +#73351 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73352 = CARTESIAN_POINT('',(-0.425,-1.225,-3.15)); +#73353 = CARTESIAN_POINT('',(-0.425,-1.225,-1.77)); +#73354 = GEOMETRIC_CURVE_SET('',(#73355,#73362,#73369,#73376)); +#73355 = TRIMMED_CURVE('',#73356,(#73360,PARAMETER_VALUE(0.E+000)),( + #73361,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73356 = LINE('',#73357,#73358); +#73357 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); +#73358 = VECTOR('',#73359,1.); +#73359 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73360 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); +#73361 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); +#73362 = TRIMMED_CURVE('',#73363,(#73367,PARAMETER_VALUE(0.E+000)),( + #73368,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73363 = LINE('',#73364,#73365); +#73364 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); +#73365 = VECTOR('',#73366,1.); +#73366 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73367 = CARTESIAN_POINT('',(-1.525,-1.225,-1.77)); +#73368 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); +#73369 = TRIMMED_CURVE('',#73370,(#73374,PARAMETER_VALUE(0.E+000)),( + #73375,PARAMETER_VALUE(0.45)),.T.,.PARAMETER.); +#73370 = LINE('',#73371,#73372); +#73371 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); +#73372 = VECTOR('',#73373,1.); +#73373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73374 = CARTESIAN_POINT('',(-1.525,-1.225,-3.15)); +#73375 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); +#73376 = TRIMMED_CURVE('',#73377,(#73381,PARAMETER_VALUE(0.E+000)),( + #73382,PARAMETER_VALUE(1.38)),.T.,.PARAMETER.); +#73377 = LINE('',#73378,#73379); +#73378 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); +#73379 = VECTOR('',#73380,1.); +#73380 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73381 = CARTESIAN_POINT('',(-1.075,-1.225,-3.15)); +#73382 = CARTESIAN_POINT('',(-1.075,-1.225,-1.77)); +#73383 = GEOMETRIC_CURVE_SET('',(#73384,#73391,#73398,#73405)); +#73384 = TRIMMED_CURVE('',#73385,(#73389,PARAMETER_VALUE(0.E+000)),( + #73390,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); +#73385 = LINE('',#73386,#73387); +#73386 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); +#73387 = VECTOR('',#73388,1.); +#73388 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73389 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); +#73390 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); +#73391 = TRIMMED_CURVE('',#73392,(#73396,PARAMETER_VALUE(0.E+000)),( + #73397,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); +#73392 = LINE('',#73393,#73394); +#73393 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); +#73394 = VECTOR('',#73395,1.); +#73395 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73396 = CARTESIAN_POINT('',(3.2,-1.225,-3.15)); +#73397 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); +#73398 = TRIMMED_CURVE('',#73399,(#73403,PARAMETER_VALUE(0.E+000)),( + #73404,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); +#73399 = LINE('',#73400,#73401); +#73400 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); +#73401 = VECTOR('',#73402,1.); +#73402 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73403 = CARTESIAN_POINT('',(3.2,-1.225,-1.05)); +#73404 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); +#73405 = TRIMMED_CURVE('',#73406,(#73410,PARAMETER_VALUE(0.E+000)),( + #73411,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); +#73406 = LINE('',#73407,#73408); +#73407 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); +#73408 = VECTOR('',#73409,1.); +#73409 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73410 = CARTESIAN_POINT('',(1.725,-1.225,-1.05)); +#73411 = CARTESIAN_POINT('',(1.725,-1.225,-3.15)); +#73412 = GEOMETRIC_CURVE_SET('',(#73413,#73420,#73427,#73434)); +#73413 = TRIMMED_CURVE('',#73414,(#73418,PARAMETER_VALUE(0.E+000)),( + #73419,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); +#73414 = LINE('',#73415,#73416); +#73415 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); +#73416 = VECTOR('',#73417,1.); +#73417 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73418 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); +#73419 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); +#73420 = TRIMMED_CURVE('',#73421,(#73425,PARAMETER_VALUE(0.E+000)),( + #73426,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); +#73421 = LINE('',#73422,#73423); +#73422 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); +#73423 = VECTOR('',#73424,1.); +#73424 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73425 = CARTESIAN_POINT('',(-1.725,-1.225,-1.05)); +#73426 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); +#73427 = TRIMMED_CURVE('',#73428,(#73432,PARAMETER_VALUE(0.E+000)),( + #73433,PARAMETER_VALUE(2.1)),.T.,.PARAMETER.); +#73428 = LINE('',#73429,#73430); +#73429 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); +#73430 = VECTOR('',#73431,1.); +#73431 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73432 = CARTESIAN_POINT('',(-3.2,-1.225,-1.05)); +#73433 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); +#73434 = TRIMMED_CURVE('',#73435,(#73439,PARAMETER_VALUE(0.E+000)),( + #73440,PARAMETER_VALUE(1.475)),.T.,.PARAMETER.); +#73435 = LINE('',#73436,#73437); +#73436 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); +#73437 = VECTOR('',#73438,1.); +#73438 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73439 = CARTESIAN_POINT('',(-3.2,-1.225,-3.15)); +#73440 = CARTESIAN_POINT('',(-1.725,-1.225,-3.15)); +#73441 = GEOMETRIC_CURVE_SET('',(#73442,#73449,#73456,#73463)); +#73442 = TRIMMED_CURVE('',#73443,(#73447,PARAMETER_VALUE(0.E+000)),( + #73448,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); +#73443 = LINE('',#73444,#73445); +#73444 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); +#73445 = VECTOR('',#73446,1.); +#73446 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73447 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); +#73448 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); +#73449 = TRIMMED_CURVE('',#73450,(#73454,PARAMETER_VALUE(0.E+000)),( + #73455,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73450 = LINE('',#73451,#73452); +#73451 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); +#73452 = VECTOR('',#73453,1.); +#73453 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73454 = CARTESIAN_POINT('',(0.25,-1.225,1.15)); +#73455 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); +#73456 = TRIMMED_CURVE('',#73457,(#73461,PARAMETER_VALUE(0.E+000)),( + #73462,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); +#73457 = LINE('',#73458,#73459); +#73458 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); +#73459 = VECTOR('',#73460,1.); +#73460 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73461 = CARTESIAN_POINT('',(0.25,-1.225,-0.75)); +#73462 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); +#73463 = TRIMMED_CURVE('',#73464,(#73468,PARAMETER_VALUE(0.E+000)),( + #73469,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73464 = LINE('',#73465,#73466); +#73465 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); +#73466 = VECTOR('',#73467,1.); +#73467 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73468 = CARTESIAN_POINT('',(1.425,-1.225,-0.75)); +#73469 = CARTESIAN_POINT('',(1.425,-1.225,1.15)); +#73470 = GEOMETRIC_CURVE_SET('',(#73471,#73478,#73485,#73492)); +#73471 = TRIMMED_CURVE('',#73472,(#73476,PARAMETER_VALUE(0.E+000)),( + #73477,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); +#73472 = LINE('',#73473,#73474); +#73473 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); +#73474 = VECTOR('',#73475,1.); +#73475 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73476 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); +#73477 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); +#73478 = TRIMMED_CURVE('',#73479,(#73483,PARAMETER_VALUE(0.E+000)),( + #73484,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73479 = LINE('',#73480,#73481); +#73480 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); +#73481 = VECTOR('',#73482,1.); +#73482 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73483 = CARTESIAN_POINT('',(-1.425,-1.225,1.15)); +#73484 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); +#73485 = TRIMMED_CURVE('',#73486,(#73490,PARAMETER_VALUE(0.E+000)),( + #73491,PARAMETER_VALUE(1.175)),.T.,.PARAMETER.); +#73486 = LINE('',#73487,#73488); +#73487 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); +#73488 = VECTOR('',#73489,1.); +#73489 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73490 = CARTESIAN_POINT('',(-1.425,-1.225,-0.75)); +#73491 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); +#73492 = TRIMMED_CURVE('',#73493,(#73497,PARAMETER_VALUE(0.E+000)),( + #73498,PARAMETER_VALUE(1.9)),.T.,.PARAMETER.); +#73493 = LINE('',#73494,#73495); +#73494 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); +#73495 = VECTOR('',#73496,1.); +#73496 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73497 = CARTESIAN_POINT('',(-0.25,-1.225,-0.75)); +#73498 = CARTESIAN_POINT('',(-0.25,-1.225,1.15)); +#73499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#73503)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#73500,#73501,#73502)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#71108 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#71109 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#71110 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#71111 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#71108, +#73500 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#73501 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#73502 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#73503 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#73500, 'distance_accuracy_value','confusion accuracy'); -#71112 = SHAPE_DEFINITION_REPRESENTATION(#71113,#70787); -#71113 = PRODUCT_DEFINITION_SHAPE('','',#71114); -#71114 = PRODUCT_DEFINITION('design','',#71115,#71118); -#71115 = PRODUCT_DEFINITION_FORMATION('','',#71116); -#71116 = PRODUCT('Open CASCADE STEP translator 6.2 133.37.1.2', - 'Open CASCADE STEP translator 6.2 133.37.1.2','',(#71117)); -#71117 = PRODUCT_CONTEXT('',#2,'mechanical'); -#71118 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#71119 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#71120,#71122); -#71120 = ( REPRESENTATION_RELATIONSHIP('','',#70787,#37611) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#71121) +#73504 = SHAPE_DEFINITION_REPRESENTATION(#73505,#73179); +#73505 = PRODUCT_DEFINITION_SHAPE('','',#73506); +#73506 = PRODUCT_DEFINITION('design','',#73507,#73510); +#73507 = PRODUCT_DEFINITION_FORMATION('','',#73508); +#73508 = PRODUCT('Open CASCADE STEP translator 6.2 36.37.1.2', + 'Open CASCADE STEP translator 6.2 36.37.1.2','',(#73509)); +#73509 = PRODUCT_CONTEXT('',#2,'mechanical'); +#73510 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#73511 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#73512,#73514); +#73512 = ( REPRESENTATION_RELATIONSHIP('','',#73179,#40003) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#73513) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#71121 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37616); -#71122 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #71123); -#71123 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('215','=>[0:1:1:57]','',#37606, - #71114,$); -#71124 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#71116)); -#71125 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#71126,#71128); -#71126 = ( REPRESENTATION_RELATIONSHIP('','',#37611,#37594) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#71127) +#73513 = ITEM_DEFINED_TRANSFORMATION('','',#11,#40008); +#73514 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #73515); +#73515 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('316','=>[0:1:1:57]','',#39998, + #73506,$); +#73516 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#73508)); +#73517 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#73518,#73520); +#73518 = ( REPRESENTATION_RELATIONSHIP('','',#40003,#39986) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#73519) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#71127 = ITEM_DEFINED_TRANSFORMATION('','',#11,#37595); -#71128 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #71129); -#71129 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('216','=>[0:1:1:55]','',#37589, - #37606,$); -#71130 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37608)); -#71131 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#71132,#71134); -#71132 = ( REPRESENTATION_RELATIONSHIP('','',#37594,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#71133) +#73519 = ITEM_DEFINED_TRANSFORMATION('','',#11,#39987); +#73520 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #73521); +#73521 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('317','=>[0:1:1:55]','',#39981, + #39998,$); +#73522 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#40000)); +#73523 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#73524,#73526); +#73524 = ( REPRESENTATION_RELATIONSHIP('','',#39986,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#73525) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#71133 = ITEM_DEFINED_TRANSFORMATION('','',#11,#159); -#71134 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #71135); -#71135 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('217','=>[0:1:1:54]','',#5, - #37589,$); -#71136 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#37591)); -#71137 = SHAPE_DEFINITION_REPRESENTATION(#71138,#71144); -#71138 = PRODUCT_DEFINITION_SHAPE('','',#71139); -#71139 = PRODUCT_DEFINITION('design','',#71140,#71143); -#71140 = PRODUCT_DEFINITION_FORMATION('','',#71141); -#71141 = PRODUCT('D1','D1','',(#71142)); -#71142 = PRODUCT_CONTEXT('',#2,'mechanical'); -#71143 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#71144 = SHAPE_REPRESENTATION('',(#11,#71145),#71149); -#71145 = AXIS2_PLACEMENT_3D('',#71146,#71147,#71148); -#71146 = CARTESIAN_POINT('',(27.30508128,30.73391872,0.5207)); -#71147 = DIRECTION('',(1.,-1.110223024625E-016,1.110223024625E-016)); -#71148 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#71149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#71153)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#71150,#71151,#71152)) +#73525 = ITEM_DEFINED_TRANSFORMATION('','',#11,#159); +#73526 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #73527); +#73527 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('318','=>[0:1:1:54]','',#5, + #39981,$); +#73528 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#39983)); +#73529 = SHAPE_DEFINITION_REPRESENTATION(#73530,#73536); +#73530 = PRODUCT_DEFINITION_SHAPE('','',#73531); +#73531 = PRODUCT_DEFINITION('design','',#73532,#73535); +#73532 = PRODUCT_DEFINITION_FORMATION('','',#73533); +#73533 = PRODUCT('D1','D1','',(#73534)); +#73534 = PRODUCT_CONTEXT('',#2,'mechanical'); +#73535 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#73536 = SHAPE_REPRESENTATION('',(#11,#73537),#73541); +#73537 = AXIS2_PLACEMENT_3D('',#73538,#73539,#73540); +#73538 = CARTESIAN_POINT('',(27.30508128,30.73391872,0.5207)); +#73539 = DIRECTION('',(1.,-1.110223024625E-016,1.110223024625E-016)); +#73540 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#73541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#73545)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#73542,#73543,#73544)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#71150 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#71151 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#71152 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#71153 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#71150, +#73542 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#73543 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#73544 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#73545 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#73542, 'distance_accuracy_value','confusion accuracy'); -#71154 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#71155),#75004); -#71155 = MANIFOLD_SOLID_BREP('',#71156); -#71156 = CLOSED_SHELL('',(#71157,#71283,#71381,#71456,#71532,#71608, - #71683,#71766,#71841,#71916,#71992,#72168,#72253,#72328,#72403, - #72486,#72562,#72638,#72713,#72788,#72886,#72969,#73147,#73223, - #73299,#73370,#73630,#73713,#73811,#73886,#73962,#74038,#74113, - #74196,#74271,#74346,#74417,#74556,#74603,#74638,#74665,#74700, - #74727,#74762,#74797,#74804,#74839,#74866,#74901,#74928,#74955, - #74982,#74993)); -#71157 = ADVANCED_FACE('',(#71158),#71172,.F.); -#71158 = FACE_BOUND('',#71159,.F.); -#71159 = EDGE_LOOP('',(#71160,#71194,#71226,#71253)); -#71160 = ORIENTED_EDGE('',*,*,#71161,.F.); -#71161 = EDGE_CURVE('',#71162,#71164,#71166,.T.); -#71162 = VERTEX_POINT('',#71163); -#71163 = CARTESIAN_POINT('',(0.8509,-0.127,-0.7239)); -#71164 = VERTEX_POINT('',#71165); -#71165 = CARTESIAN_POINT('',(0.8509,-0.127,-1.1811)); -#71166 = SURFACE_CURVE('',#71167,(#71171,#71182),.PCURVE_S1.); -#71167 = LINE('',#71168,#71169); -#71168 = CARTESIAN_POINT('',(0.8509,-0.127,1.4478)); -#71169 = VECTOR('',#71170,1.); -#71170 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71171 = PCURVE('',#71172,#71177); -#71172 = CYLINDRICAL_SURFACE('',#71173,0.127); -#71173 = AXIS2_PLACEMENT_3D('',#71174,#71175,#71176); -#71174 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); -#71175 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71176 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71177 = DEFINITIONAL_REPRESENTATION('',(#71178),#71181); -#71178 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71179,#71180),.UNSPECIFIED., +#73546 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#73547),#77396); +#73547 = MANIFOLD_SOLID_BREP('',#73548); +#73548 = CLOSED_SHELL('',(#73549,#73675,#73773,#73848,#73924,#74000, + #74075,#74158,#74233,#74308,#74384,#74560,#74645,#74720,#74795, + #74878,#74954,#75030,#75105,#75180,#75278,#75361,#75539,#75615, + #75691,#75762,#76022,#76105,#76203,#76278,#76354,#76430,#76505, + #76588,#76663,#76738,#76809,#76948,#76995,#77030,#77057,#77092, + #77119,#77154,#77189,#77196,#77231,#77258,#77293,#77320,#77347, + #77374,#77385)); +#73549 = ADVANCED_FACE('',(#73550),#73564,.F.); +#73550 = FACE_BOUND('',#73551,.F.); +#73551 = EDGE_LOOP('',(#73552,#73586,#73618,#73645)); +#73552 = ORIENTED_EDGE('',*,*,#73553,.F.); +#73553 = EDGE_CURVE('',#73554,#73556,#73558,.T.); +#73554 = VERTEX_POINT('',#73555); +#73555 = CARTESIAN_POINT('',(0.8509,-0.127,-0.7239)); +#73556 = VERTEX_POINT('',#73557); +#73557 = CARTESIAN_POINT('',(0.8509,-0.127,-1.1811)); +#73558 = SURFACE_CURVE('',#73559,(#73563,#73574),.PCURVE_S1.); +#73559 = LINE('',#73560,#73561); +#73560 = CARTESIAN_POINT('',(0.8509,-0.127,1.4478)); +#73561 = VECTOR('',#73562,1.); +#73562 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73563 = PCURVE('',#73564,#73569); +#73564 = CYLINDRICAL_SURFACE('',#73565,0.127); +#73565 = AXIS2_PLACEMENT_3D('',#73566,#73567,#73568); +#73566 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); +#73567 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73568 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73569 = DEFINITIONAL_REPRESENTATION('',(#73570),#73573); +#73570 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73571,#73572),.UNSPECIFIED., .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71179 = CARTESIAN_POINT('',(1.570796326795,2.1717)); -#71180 = CARTESIAN_POINT('',(1.570796326795,2.6289)); -#71181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71182 = PCURVE('',#71183,#71188); -#71183 = PLANE('',#71184); -#71184 = AXIS2_PLACEMENT_3D('',#71185,#71186,#71187); -#71185 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); -#71186 = DIRECTION('',(0.E+000,1.,0.E+000)); -#71187 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71188 = DEFINITIONAL_REPRESENTATION('',(#71189),#71193); -#71189 = LINE('',#71190,#71191); -#71190 = CARTESIAN_POINT('',(0.E+000,0.216548237879)); -#71191 = VECTOR('',#71192,1.); -#71192 = DIRECTION('',(-1.,0.E+000)); -#71193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71194 = ORIENTED_EDGE('',*,*,#71195,.F.); -#71195 = EDGE_CURVE('',#71196,#71162,#71198,.T.); -#71196 = VERTEX_POINT('',#71197); -#71197 = CARTESIAN_POINT('',(0.9779,-0.254,-0.7239)); -#71198 = SURFACE_CURVE('',#71199,(#71204,#71210),.PCURVE_S1.); -#71199 = CIRCLE('',#71200,0.127); -#71200 = AXIS2_PLACEMENT_3D('',#71201,#71202,#71203); -#71201 = CARTESIAN_POINT('',(0.8509,-0.254,-0.7239)); -#71202 = DIRECTION('',(-1.928281419412E-016,1.304309178525E-048,1.)); -#71203 = DIRECTION('',(-1.,1.70740499604E-015,-1.928281419412E-016)); -#71204 = PCURVE('',#71172,#71205); -#71205 = DEFINITIONAL_REPRESENTATION('',(#71206),#71209); -#71206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71207,#71208),.UNSPECIFIED., +#73571 = CARTESIAN_POINT('',(1.570796326795,2.1717)); +#73572 = CARTESIAN_POINT('',(1.570796326795,2.6289)); +#73573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73574 = PCURVE('',#73575,#73580); +#73575 = PLANE('',#73576); +#73576 = AXIS2_PLACEMENT_3D('',#73577,#73578,#73579); +#73577 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); +#73578 = DIRECTION('',(0.E+000,1.,0.E+000)); +#73579 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73580 = DEFINITIONAL_REPRESENTATION('',(#73581),#73585); +#73581 = LINE('',#73582,#73583); +#73582 = CARTESIAN_POINT('',(0.E+000,0.216548237879)); +#73583 = VECTOR('',#73584,1.); +#73584 = DIRECTION('',(-1.,0.E+000)); +#73585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73586 = ORIENTED_EDGE('',*,*,#73587,.F.); +#73587 = EDGE_CURVE('',#73588,#73554,#73590,.T.); +#73588 = VERTEX_POINT('',#73589); +#73589 = CARTESIAN_POINT('',(0.9779,-0.254,-0.7239)); +#73590 = SURFACE_CURVE('',#73591,(#73596,#73602),.PCURVE_S1.); +#73591 = CIRCLE('',#73592,0.127); +#73592 = AXIS2_PLACEMENT_3D('',#73593,#73594,#73595); +#73593 = CARTESIAN_POINT('',(0.8509,-0.254,-0.7239)); +#73594 = DIRECTION('',(-1.928281419412E-016,1.304309178525E-048,1.)); +#73595 = DIRECTION('',(-1.,1.70740499604E-015,-1.928281419412E-016)); +#73596 = PCURVE('',#73564,#73597); +#73597 = DEFINITIONAL_REPRESENTATION('',(#73598),#73601); +#73598 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73599,#73600),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#71207 = CARTESIAN_POINT('',(3.14159265359,2.1717)); -#71208 = CARTESIAN_POINT('',(1.570796326795,2.1717)); -#71209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#73599 = CARTESIAN_POINT('',(3.14159265359,2.1717)); +#73600 = CARTESIAN_POINT('',(1.570796326795,2.1717)); +#73601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#71210 = PCURVE('',#71211,#71216); -#71211 = PLANE('',#71212); -#71212 = AXIS2_PLACEMENT_3D('',#71213,#71214,#71215); -#71213 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); -#71214 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); -#71215 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); -#71216 = DEFINITIONAL_REPRESENTATION('',(#71217),#71225); -#71217 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#71218,#71219,#71220,#71221 - ,#71222,#71223,#71224),.UNSPECIFIED.,.F.,.F.) +#73602 = PCURVE('',#73603,#73608); +#73603 = PLANE('',#73604); +#73604 = AXIS2_PLACEMENT_3D('',#73605,#73606,#73607); +#73605 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); +#73606 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); +#73607 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); +#73608 = DEFINITIONAL_REPRESENTATION('',(#73609),#73617); +#73609 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#73610,#73611,#73612,#73613 + ,#73614,#73615,#73616),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#71218 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); -#71219 = CARTESIAN_POINT('',(-7.62E-002,4.076565618857E-002)); -#71220 = CARTESIAN_POINT('',(-0.2667,0.150750882469)); -#71221 = CARTESIAN_POINT('',(-0.4572,0.26073610875)); -#71222 = CARTESIAN_POINT('',(-0.2667,0.37072133503)); -#71223 = CARTESIAN_POINT('',(-7.62E-002,0.480706561311)); -#71224 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); -#71225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71226 = ORIENTED_EDGE('',*,*,#71227,.T.); -#71227 = EDGE_CURVE('',#71196,#71228,#71230,.T.); -#71228 = VERTEX_POINT('',#71229); -#71229 = CARTESIAN_POINT('',(0.9779,-0.254,-1.1811)); -#71230 = SURFACE_CURVE('',#71231,(#71235,#71241),.PCURVE_S1.); -#71231 = LINE('',#71232,#71233); -#71232 = CARTESIAN_POINT('',(0.9779,-0.254,1.4478)); -#71233 = VECTOR('',#71234,1.); -#71234 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71235 = PCURVE('',#71172,#71236); -#71236 = DEFINITIONAL_REPRESENTATION('',(#71237),#71240); -#71237 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71238,#71239),.UNSPECIFIED., - .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71238 = CARTESIAN_POINT('',(3.14159265359,2.1717)); -#71239 = CARTESIAN_POINT('',(3.14159265359,2.6289)); -#71240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#73610 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); +#73611 = CARTESIAN_POINT('',(-7.62E-002,4.076565618857E-002)); +#73612 = CARTESIAN_POINT('',(-0.2667,0.150750882469)); +#73613 = CARTESIAN_POINT('',(-0.4572,0.26073610875)); +#73614 = CARTESIAN_POINT('',(-0.2667,0.37072133503)); +#73615 = CARTESIAN_POINT('',(-7.62E-002,0.480706561311)); +#73616 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); +#73617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#71241 = PCURVE('',#71242,#71247); -#71242 = PLANE('',#71243); -#71243 = AXIS2_PLACEMENT_3D('',#71244,#71245,#71246); -#71244 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); -#71245 = DIRECTION('',(1.,0.E+000,0.E+000)); -#71246 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71247 = DEFINITIONAL_REPRESENTATION('',(#71248),#71252); -#71248 = LINE('',#71249,#71250); -#71249 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); -#71250 = VECTOR('',#71251,1.); -#71251 = DIRECTION('',(1.,0.E+000)); -#71252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71253 = ORIENTED_EDGE('',*,*,#71254,.F.); -#71254 = EDGE_CURVE('',#71164,#71228,#71255,.T.); -#71255 = SURFACE_CURVE('',#71256,(#71261,#71267),.PCURVE_S1.); -#71256 = CIRCLE('',#71257,0.127); -#71257 = AXIS2_PLACEMENT_3D('',#71258,#71259,#71260); -#71258 = CARTESIAN_POINT('',(0.8509,-0.254,-1.1811)); -#71259 = DIRECTION('',(-3.856562838825E-016,8.766668249102E-048,-1.)); -#71260 = DIRECTION('',(1.,-8.537024980201E-016,-3.856562838825E-016)); -#71261 = PCURVE('',#71172,#71262); -#71262 = DEFINITIONAL_REPRESENTATION('',(#71263),#71266); -#71263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71264,#71265),.UNSPECIFIED., +#73618 = ORIENTED_EDGE('',*,*,#73619,.T.); +#73619 = EDGE_CURVE('',#73588,#73620,#73622,.T.); +#73620 = VERTEX_POINT('',#73621); +#73621 = CARTESIAN_POINT('',(0.9779,-0.254,-1.1811)); +#73622 = SURFACE_CURVE('',#73623,(#73627,#73633),.PCURVE_S1.); +#73623 = LINE('',#73624,#73625); +#73624 = CARTESIAN_POINT('',(0.9779,-0.254,1.4478)); +#73625 = VECTOR('',#73626,1.); +#73626 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73627 = PCURVE('',#73564,#73628); +#73628 = DEFINITIONAL_REPRESENTATION('',(#73629),#73632); +#73629 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73630,#73631),.UNSPECIFIED., + .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); +#73630 = CARTESIAN_POINT('',(3.14159265359,2.1717)); +#73631 = CARTESIAN_POINT('',(3.14159265359,2.6289)); +#73632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73633 = PCURVE('',#73634,#73639); +#73634 = PLANE('',#73635); +#73635 = AXIS2_PLACEMENT_3D('',#73636,#73637,#73638); +#73636 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); +#73637 = DIRECTION('',(1.,0.E+000,0.E+000)); +#73638 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73639 = DEFINITIONAL_REPRESENTATION('',(#73640),#73644); +#73640 = LINE('',#73641,#73642); +#73641 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); +#73642 = VECTOR('',#73643,1.); +#73643 = DIRECTION('',(1.,0.E+000)); +#73644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73645 = ORIENTED_EDGE('',*,*,#73646,.F.); +#73646 = EDGE_CURVE('',#73556,#73620,#73647,.T.); +#73647 = SURFACE_CURVE('',#73648,(#73653,#73659),.PCURVE_S1.); +#73648 = CIRCLE('',#73649,0.127); +#73649 = AXIS2_PLACEMENT_3D('',#73650,#73651,#73652); +#73650 = CARTESIAN_POINT('',(0.8509,-0.254,-1.1811)); +#73651 = DIRECTION('',(-3.856562838825E-016,8.766668249102E-048,-1.)); +#73652 = DIRECTION('',(1.,-8.537024980201E-016,-3.856562838825E-016)); +#73653 = PCURVE('',#73564,#73654); +#73654 = DEFINITIONAL_REPRESENTATION('',(#73655),#73658); +#73655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73656,#73657),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#71264 = CARTESIAN_POINT('',(1.570796326795,2.6289)); -#71265 = CARTESIAN_POINT('',(3.14159265359,2.6289)); -#71266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#73656 = CARTESIAN_POINT('',(1.570796326795,2.6289)); +#73657 = CARTESIAN_POINT('',(3.14159265359,2.6289)); +#73658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#71267 = PCURVE('',#71268,#71273); -#71268 = PLANE('',#71269); -#71269 = AXIS2_PLACEMENT_3D('',#71270,#71271,#71272); -#71270 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.1811)); -#71271 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); -#71272 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); -#71273 = DEFINITIONAL_REPRESENTATION('',(#71274),#71282); -#71274 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#71275,#71276,#71277,#71278 - ,#71279,#71280,#71281),.UNSPECIFIED.,.T.,.F.) +#73659 = PCURVE('',#73660,#73665); +#73660 = PLANE('',#73661); +#73661 = AXIS2_PLACEMENT_3D('',#73662,#73663,#73664); +#73662 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.1811)); +#73663 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); +#73664 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); +#73665 = DEFINITIONAL_REPRESENTATION('',(#73666),#73674); +#73666 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#73667,#73668,#73669,#73670 + ,#73671,#73672,#73673),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#71275 = CARTESIAN_POINT('',(0.3302,0.26073610875)); -#71276 = CARTESIAN_POINT('',(0.3302,4.076565618857E-002)); -#71277 = CARTESIAN_POINT('',(0.1397,0.150750882469)); -#71278 = CARTESIAN_POINT('',(-5.08E-002,0.26073610875)); -#71279 = CARTESIAN_POINT('',(0.1397,0.37072133503)); -#71280 = CARTESIAN_POINT('',(0.3302,0.480706561311)); -#71281 = CARTESIAN_POINT('',(0.3302,0.26073610875)); -#71282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71283 = ADVANCED_FACE('',(#71284),#71242,.F.); -#71284 = FACE_BOUND('',#71285,.T.); -#71285 = EDGE_LOOP('',(#71286,#71287,#71310,#71360)); -#71286 = ORIENTED_EDGE('',*,*,#71227,.T.); -#71287 = ORIENTED_EDGE('',*,*,#71288,.T.); -#71288 = EDGE_CURVE('',#71228,#71289,#71291,.T.); -#71289 = VERTEX_POINT('',#71290); -#71290 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-1.1811)); -#71291 = SURFACE_CURVE('',#71292,(#71296,#71303),.PCURVE_S1.); -#71292 = LINE('',#71293,#71294); -#71293 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-1.1811)); -#71294 = VECTOR('',#71295,1.); -#71295 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#71296 = PCURVE('',#71242,#71297); -#71297 = DEFINITIONAL_REPRESENTATION('',(#71298),#71302); -#71298 = LINE('',#71299,#71300); -#71299 = CARTESIAN_POINT('',(2.6289,0.E+000)); -#71300 = VECTOR('',#71301,1.); -#71301 = DIRECTION('',(0.E+000,-1.)); -#71302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71303 = PCURVE('',#71268,#71304); -#71304 = DEFINITIONAL_REPRESENTATION('',(#71305),#71309); -#71305 = LINE('',#71306,#71307); -#71306 = CARTESIAN_POINT('',(0.3302,0.154932254901)); -#71307 = VECTOR('',#71308,1.); -#71308 = DIRECTION('',(0.E+000,-1.)); -#71309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71310 = ORIENTED_EDGE('',*,*,#71311,.F.); -#71311 = EDGE_CURVE('',#71312,#71289,#71314,.T.); -#71312 = VERTEX_POINT('',#71313); -#71313 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-0.7239)); -#71314 = SURFACE_CURVE('',#71315,(#71319,#71326),.PCURVE_S1.); -#71315 = LINE('',#71316,#71317); -#71316 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); -#71317 = VECTOR('',#71318,1.); -#71318 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71319 = PCURVE('',#71242,#71320); -#71320 = DEFINITIONAL_REPRESENTATION('',(#71321),#71325); -#71321 = LINE('',#71322,#71323); -#71322 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); -#71323 = VECTOR('',#71324,1.); -#71324 = DIRECTION('',(1.,0.E+000)); -#71325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71326 = PCURVE('',#71327,#71332); -#71327 = CYLINDRICAL_SURFACE('',#71328,0.127); -#71328 = AXIS2_PLACEMENT_3D('',#71329,#71330,#71331); -#71329 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.4478)); -#71330 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71331 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71332 = DEFINITIONAL_REPRESENTATION('',(#71333),#71359); -#71333 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#71334,#71335,#71336,#71337, - #71338,#71339,#71340,#71341,#71342,#71343,#71344,#71345,#71346, - #71347,#71348,#71349,#71350,#71351,#71352,#71353,#71354,#71355, - #71356,#71357,#71358),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#73667 = CARTESIAN_POINT('',(0.3302,0.26073610875)); +#73668 = CARTESIAN_POINT('',(0.3302,4.076565618857E-002)); +#73669 = CARTESIAN_POINT('',(0.1397,0.150750882469)); +#73670 = CARTESIAN_POINT('',(-5.08E-002,0.26073610875)); +#73671 = CARTESIAN_POINT('',(0.1397,0.37072133503)); +#73672 = CARTESIAN_POINT('',(0.3302,0.480706561311)); +#73673 = CARTESIAN_POINT('',(0.3302,0.26073610875)); +#73674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73675 = ADVANCED_FACE('',(#73676),#73634,.F.); +#73676 = FACE_BOUND('',#73677,.T.); +#73677 = EDGE_LOOP('',(#73678,#73679,#73702,#73752)); +#73678 = ORIENTED_EDGE('',*,*,#73619,.T.); +#73679 = ORIENTED_EDGE('',*,*,#73680,.T.); +#73680 = EDGE_CURVE('',#73620,#73681,#73683,.T.); +#73681 = VERTEX_POINT('',#73682); +#73682 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-1.1811)); +#73683 = SURFACE_CURVE('',#73684,(#73688,#73695),.PCURVE_S1.); +#73684 = LINE('',#73685,#73686); +#73685 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-1.1811)); +#73686 = VECTOR('',#73687,1.); +#73687 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#73688 = PCURVE('',#73634,#73689); +#73689 = DEFINITIONAL_REPRESENTATION('',(#73690),#73694); +#73690 = LINE('',#73691,#73692); +#73691 = CARTESIAN_POINT('',(2.6289,0.E+000)); +#73692 = VECTOR('',#73693,1.); +#73693 = DIRECTION('',(0.E+000,-1.)); +#73694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73695 = PCURVE('',#73660,#73696); +#73696 = DEFINITIONAL_REPRESENTATION('',(#73697),#73701); +#73697 = LINE('',#73698,#73699); +#73698 = CARTESIAN_POINT('',(0.3302,0.154932254901)); +#73699 = VECTOR('',#73700,1.); +#73700 = DIRECTION('',(0.E+000,-1.)); +#73701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73702 = ORIENTED_EDGE('',*,*,#73703,.F.); +#73703 = EDGE_CURVE('',#73704,#73681,#73706,.T.); +#73704 = VERTEX_POINT('',#73705); +#73705 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-0.7239)); +#73706 = SURFACE_CURVE('',#73707,(#73711,#73718),.PCURVE_S1.); +#73707 = LINE('',#73708,#73709); +#73708 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); +#73709 = VECTOR('',#73710,1.); +#73710 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73711 = PCURVE('',#73634,#73712); +#73712 = DEFINITIONAL_REPRESENTATION('',(#73713),#73717); +#73713 = LINE('',#73714,#73715); +#73714 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); +#73715 = VECTOR('',#73716,1.); +#73716 = DIRECTION('',(1.,0.E+000)); +#73717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73718 = PCURVE('',#73719,#73724); +#73719 = CYLINDRICAL_SURFACE('',#73720,0.127); +#73720 = AXIS2_PLACEMENT_3D('',#73721,#73722,#73723); +#73721 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.4478)); +#73722 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73723 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73724 = DEFINITIONAL_REPRESENTATION('',(#73725),#73751); +#73725 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#73726,#73727,#73728,#73729, + #73730,#73731,#73732,#73733,#73734,#73735,#73736,#73737,#73738, + #73739,#73740,#73741,#73742,#73743,#73744,#73745,#73746,#73747, + #73748,#73749,#73750),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(2.1717,2.192481818182,2.213263636364, 2.234045454545,2.254827272727,2.275609090909,2.296390909091, 2.317172727273,2.337954545455,2.358736363636,2.379518181818,2.4003, 2.421081818182,2.441863636364,2.462645454545,2.483427272727, - 2.504209090909,2.524990909091,2.545772727273,2.566554545455, - 2.587336363636,2.608118181818,2.6289),.QUASI_UNIFORM_KNOTS.); -#71334 = CARTESIAN_POINT('',(6.28318530718,2.1717)); -#71335 = CARTESIAN_POINT('',(6.28318530718,2.178627272727)); -#71336 = CARTESIAN_POINT('',(6.28318530718,2.192481818182)); -#71337 = CARTESIAN_POINT('',(6.28318530718,2.213263636364)); -#71338 = CARTESIAN_POINT('',(6.28318530718,2.234045454545)); -#71339 = CARTESIAN_POINT('',(6.28318530718,2.254827272727)); -#71340 = CARTESIAN_POINT('',(6.28318530718,2.275609090909)); -#71341 = CARTESIAN_POINT('',(6.28318530718,2.296390909091)); -#71342 = CARTESIAN_POINT('',(6.28318530718,2.317172727273)); -#71343 = CARTESIAN_POINT('',(6.28318530718,2.337954545455)); -#71344 = CARTESIAN_POINT('',(6.28318530718,2.358736363636)); -#71345 = CARTESIAN_POINT('',(6.28318530718,2.379518181818)); -#71346 = CARTESIAN_POINT('',(6.28318530718,2.4003)); -#71347 = CARTESIAN_POINT('',(6.28318530718,2.421081818182)); -#71348 = CARTESIAN_POINT('',(6.28318530718,2.441863636364)); -#71349 = CARTESIAN_POINT('',(6.28318530718,2.462645454545)); -#71350 = CARTESIAN_POINT('',(6.28318530718,2.483427272727)); -#71351 = CARTESIAN_POINT('',(6.28318530718,2.504209090909)); -#71352 = CARTESIAN_POINT('',(6.28318530718,2.524990909091)); -#71353 = CARTESIAN_POINT('',(6.28318530718,2.545772727273)); -#71354 = CARTESIAN_POINT('',(6.28318530718,2.566554545455)); -#71355 = CARTESIAN_POINT('',(6.28318530718,2.587336363636)); -#71356 = CARTESIAN_POINT('',(6.28318530718,2.608118181818)); -#71357 = CARTESIAN_POINT('',(6.28318530718,2.621972727273)); -#71358 = CARTESIAN_POINT('',(6.28318530718,2.6289)); -#71359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71360 = ORIENTED_EDGE('',*,*,#71361,.T.); -#71361 = EDGE_CURVE('',#71312,#71196,#71362,.T.); -#71362 = SURFACE_CURVE('',#71363,(#71367,#71374),.PCURVE_S1.); -#71363 = LINE('',#71364,#71365); -#71364 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-0.7239)); -#71365 = VECTOR('',#71366,1.); -#71366 = DIRECTION('',(0.E+000,1.,0.E+000)); -#71367 = PCURVE('',#71242,#71368); -#71368 = DEFINITIONAL_REPRESENTATION('',(#71369),#71373); -#71369 = LINE('',#71370,#71371); -#71370 = CARTESIAN_POINT('',(2.1717,0.E+000)); -#71371 = VECTOR('',#71372,1.); -#71372 = DIRECTION('',(0.E+000,1.)); -#71373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71374 = PCURVE('',#71211,#71375); -#71375 = DEFINITIONAL_REPRESENTATION('',(#71376),#71380); -#71376 = LINE('',#71377,#71378); -#71377 = CARTESIAN_POINT('',(-0.3302,0.154932254901)); -#71378 = VECTOR('',#71379,1.); -#71379 = DIRECTION('',(0.E+000,1.)); -#71380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71381 = ADVANCED_FACE('',(#71382),#71327,.T.); -#71382 = FACE_BOUND('',#71383,.T.); -#71383 = EDGE_LOOP('',(#71384,#71385,#71408,#71435)); -#71384 = ORIENTED_EDGE('',*,*,#71311,.T.); -#71385 = ORIENTED_EDGE('',*,*,#71386,.T.); -#71386 = EDGE_CURVE('',#71289,#71387,#71389,.T.); -#71387 = VERTEX_POINT('',#71388); -#71388 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,-1.1811)); -#71389 = SURFACE_CURVE('',#71390,(#71395,#71401),.PCURVE_S1.); -#71390 = CIRCLE('',#71391,0.127); -#71391 = AXIS2_PLACEMENT_3D('',#71392,#71393,#71394); -#71392 = CARTESIAN_POINT('',(1.1049,-0.359803853849,-1.1811)); -#71393 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); -#71394 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); -#71395 = PCURVE('',#71327,#71396); -#71396 = DEFINITIONAL_REPRESENTATION('',(#71397),#71400); -#71397 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71398,#71399),.UNSPECIFIED., - .F.,.F.,(2,2),(3.14159265359,4.483114246145), - .PIECEWISE_BEZIER_KNOTS.); -#71398 = CARTESIAN_POINT('',(6.28318530718,2.6289)); -#71399 = CARTESIAN_POINT('',(4.941663714624,2.6289)); -#71400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71401 = PCURVE('',#71268,#71402); -#71402 = DEFINITIONAL_REPRESENTATION('',(#71403),#71407); -#71403 = CIRCLE('',#71404,0.127); -#71404 = AXIS2_PLACEMENT_2D('',#71405,#71406); -#71405 = CARTESIAN_POINT('',(0.4572,0.154932254901)); -#71406 = DIRECTION('',(1.,0.E+000)); -#71407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71408 = ORIENTED_EDGE('',*,*,#71409,.F.); -#71409 = EDGE_CURVE('',#71410,#71387,#71412,.T.); -#71410 = VERTEX_POINT('',#71411); -#71411 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,-0.7239)); -#71412 = SURFACE_CURVE('',#71413,(#71417,#71423),.PCURVE_S1.); -#71413 = LINE('',#71414,#71415); -#71414 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.4478)); -#71415 = VECTOR('',#71416,1.); -#71416 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71417 = PCURVE('',#71327,#71418); -#71418 = DEFINITIONAL_REPRESENTATION('',(#71419),#71422); -#71419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71420,#71421),.UNSPECIFIED., - .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71420 = CARTESIAN_POINT('',(4.941663714624,2.1717)); -#71421 = CARTESIAN_POINT('',(4.941663714624,2.6289)); -#71422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71423 = PCURVE('',#71424,#71429); -#71424 = PLANE('',#71425); -#71425 = AXIS2_PLACEMENT_3D('',#71426,#71427,#71428); -#71426 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); -#71427 = DIRECTION('',(0.22727129674,0.973831483203,0.E+000)); -#71428 = DIRECTION('',(-0.973831483203,0.22727129674,0.E+000)); -#71429 = DEFINITIONAL_REPRESENTATION('',(#71430),#71434); -#71430 = LINE('',#71431,#71432); -#71431 = CARTESIAN_POINT('',(0.137525754385,0.E+000)); -#71432 = VECTOR('',#71433,1.); -#71433 = DIRECTION('',(0.E+000,-1.)); -#71434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71435 = ORIENTED_EDGE('',*,*,#71436,.T.); -#71436 = EDGE_CURVE('',#71410,#71312,#71437,.T.); -#71437 = SURFACE_CURVE('',#71438,(#71443,#71449),.PCURVE_S1.); -#71438 = CIRCLE('',#71439,0.127); -#71439 = AXIS2_PLACEMENT_3D('',#71440,#71441,#71442); -#71440 = CARTESIAN_POINT('',(1.1049,-0.359803853849,-0.7239)); -#71441 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); -#71442 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); -#71443 = PCURVE('',#71327,#71444); -#71444 = DEFINITIONAL_REPRESENTATION('',(#71445),#71448); -#71445 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71446,#71447),.UNSPECIFIED., - .F.,.F.,(2,2),(4.941663714624,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#71446 = CARTESIAN_POINT('',(4.941663714624,2.1717)); -#71447 = CARTESIAN_POINT('',(6.28318530718,2.1717)); -#71448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71449 = PCURVE('',#71211,#71450); -#71450 = DEFINITIONAL_REPRESENTATION('',(#71451),#71455); -#71451 = CIRCLE('',#71452,0.127); -#71452 = AXIS2_PLACEMENT_2D('',#71453,#71454); -#71453 = CARTESIAN_POINT('',(-0.4572,0.154932254901)); -#71454 = DIRECTION('',(1.,0.E+000)); -#71455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71456 = ADVANCED_FACE('',(#71457),#71424,.F.); -#71457 = FACE_BOUND('',#71458,.T.); -#71458 = EDGE_LOOP('',(#71459,#71460,#71483,#71511)); -#71459 = ORIENTED_EDGE('',*,*,#71409,.T.); -#71460 = ORIENTED_EDGE('',*,*,#71461,.T.); -#71461 = EDGE_CURVE('',#71387,#71462,#71464,.T.); -#71462 = VERTEX_POINT('',#71463); -#71463 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); -#71464 = SURFACE_CURVE('',#71465,(#71469,#71476),.PCURVE_S1.); -#71465 = LINE('',#71466,#71467); -#71466 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); -#71467 = VECTOR('',#71468,1.); -#71468 = DIRECTION('',(0.973831483203,-0.22727129674,-3.7556423094E-016) - ); -#71469 = PCURVE('',#71424,#71470); -#71470 = DEFINITIONAL_REPRESENTATION('',(#71471),#71475); -#71471 = LINE('',#71472,#71473); -#71472 = CARTESIAN_POINT('',(9.154004731012E-016,-2.6289)); -#71473 = VECTOR('',#71474,1.); -#71474 = DIRECTION('',(-1.,-3.7556423094E-016)); -#71475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71476 = PCURVE('',#71268,#71477); -#71477 = DEFINITIONAL_REPRESENTATION('',(#71478),#71482); -#71478 = LINE('',#71479,#71480); -#71479 = CARTESIAN_POINT('',(0.562263454686,2.22044604925E-016)); -#71480 = VECTOR('',#71481,1.); -#71481 = DIRECTION('',(0.973831483203,-0.22727129674)); -#71482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71483 = ORIENTED_EDGE('',*,*,#71484,.F.); -#71484 = EDGE_CURVE('',#71485,#71462,#71487,.T.); -#71485 = VERTEX_POINT('',#71486); -#71486 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); -#71487 = SURFACE_CURVE('',#71488,(#71492,#71499),.PCURVE_S1.); -#71488 = LINE('',#71489,#71490); -#71489 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); -#71490 = VECTOR('',#71491,1.); -#71491 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71492 = PCURVE('',#71424,#71493); -#71493 = DEFINITIONAL_REPRESENTATION('',(#71494),#71498); -#71494 = LINE('',#71495,#71496); -#71495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#71496 = VECTOR('',#71497,1.); -#71497 = DIRECTION('',(0.E+000,-1.)); -#71498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71499 = PCURVE('',#71500,#71505); -#71500 = PLANE('',#71501); -#71501 = AXIS2_PLACEMENT_3D('',#71502,#71503,#71504); -#71502 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); -#71503 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71504 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71505 = DEFINITIONAL_REPRESENTATION('',(#71506),#71510); -#71506 = LINE('',#71507,#71508); -#71507 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); -#71508 = VECTOR('',#71509,1.); -#71509 = DIRECTION('',(-1.,0.E+000)); -#71510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71511 = ORIENTED_EDGE('',*,*,#71512,.T.); -#71512 = EDGE_CURVE('',#71485,#71410,#71513,.T.); -#71513 = SURFACE_CURVE('',#71514,(#71518,#71525),.PCURVE_S1.); -#71514 = LINE('',#71515,#71516); -#71515 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); -#71516 = VECTOR('',#71517,1.); -#71517 = DIRECTION('',(-0.973831483203,0.22727129674,-1.8778211547E-016) - ); -#71518 = PCURVE('',#71424,#71519); -#71519 = DEFINITIONAL_REPRESENTATION('',(#71520),#71524); -#71520 = LINE('',#71521,#71522); -#71521 = CARTESIAN_POINT('',(-4.577002365506E-016,-2.1717)); -#71522 = VECTOR('',#71523,1.); -#71523 = DIRECTION('',(1.,-1.8778211547E-016)); -#71524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71525 = PCURVE('',#71211,#71526); -#71526 = DEFINITIONAL_REPRESENTATION('',(#71527),#71531); -#71527 = LINE('',#71528,#71529); -#71528 = CARTESIAN_POINT('',(-0.562263454686,-1.110223024625E-016)); -#71529 = VECTOR('',#71530,1.); -#71530 = DIRECTION('',(0.973831483203,0.22727129674)); -#71531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71532 = ADVANCED_FACE('',(#71533),#71500,.F.); -#71533 = FACE_BOUND('',#71534,.T.); -#71534 = EDGE_LOOP('',(#71535,#71536,#71559,#71587)); -#71535 = ORIENTED_EDGE('',*,*,#71484,.T.); -#71536 = ORIENTED_EDGE('',*,*,#71537,.T.); -#71537 = EDGE_CURVE('',#71462,#71538,#71540,.T.); -#71538 = VERTEX_POINT('',#71539); -#71539 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,-1.1811)); -#71540 = SURFACE_CURVE('',#71541,(#71545,#71552),.PCURVE_S1.); -#71541 = LINE('',#71542,#71543); -#71542 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); -#71543 = VECTOR('',#71544,1.); -#71544 = DIRECTION('',(0.E+000,1.,0.E+000)); -#71545 = PCURVE('',#71500,#71546); -#71546 = DEFINITIONAL_REPRESENTATION('',(#71547),#71551); -#71547 = LINE('',#71548,#71549); -#71548 = CARTESIAN_POINT('',(-2.6289,-0.130412707117)); -#71549 = VECTOR('',#71550,1.); -#71550 = DIRECTION('',(0.E+000,1.)); -#71551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71552 = PCURVE('',#71268,#71553); -#71553 = DEFINITIONAL_REPRESENTATION('',(#71554),#71558); -#71554 = LINE('',#71555,#71556); -#71555 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); -#71556 = VECTOR('',#71557,1.); -#71557 = DIRECTION('',(0.E+000,1.)); -#71558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71559 = ORIENTED_EDGE('',*,*,#71560,.F.); -#71560 = EDGE_CURVE('',#71561,#71538,#71563,.T.); -#71561 = VERTEX_POINT('',#71562); -#71562 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,-0.7239)); -#71563 = SURFACE_CURVE('',#71564,(#71568,#71575),.PCURVE_S1.); -#71564 = LINE('',#71565,#71566); -#71565 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); -#71566 = VECTOR('',#71567,1.); -#71567 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71568 = PCURVE('',#71500,#71569); -#71569 = DEFINITIONAL_REPRESENTATION('',(#71570),#71574); -#71570 = LINE('',#71571,#71572); -#71571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#71572 = VECTOR('',#71573,1.); -#71573 = DIRECTION('',(-1.,0.E+000)); -#71574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71575 = PCURVE('',#71576,#71581); -#71576 = PLANE('',#71577); -#71577 = AXIS2_PLACEMENT_3D('',#71578,#71579,#71580); -#71578 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); -#71579 = DIRECTION('',(-0.22727129674,-0.973831483203,0.E+000)); -#71580 = DIRECTION('',(0.973831483203,-0.22727129674,0.E+000)); -#71581 = DEFINITIONAL_REPRESENTATION('',(#71582),#71586); -#71582 = LINE('',#71583,#71584); -#71583 = CARTESIAN_POINT('',(6.62031185561E-002,0.E+000)); -#71584 = VECTOR('',#71585,1.); -#71585 = DIRECTION('',(0.E+000,-1.)); -#71586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71587 = ORIENTED_EDGE('',*,*,#71588,.F.); -#71588 = EDGE_CURVE('',#71485,#71561,#71589,.T.); -#71589 = SURFACE_CURVE('',#71590,(#71594,#71601),.PCURVE_S1.); -#71590 = LINE('',#71591,#71592); -#71591 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); -#71592 = VECTOR('',#71593,1.); -#71593 = DIRECTION('',(0.E+000,1.,0.E+000)); -#71594 = PCURVE('',#71500,#71595); -#71595 = DEFINITIONAL_REPRESENTATION('',(#71596),#71600); -#71596 = LINE('',#71597,#71598); -#71597 = CARTESIAN_POINT('',(-2.1717,-0.130412707117)); -#71598 = VECTOR('',#71599,1.); -#71599 = DIRECTION('',(0.E+000,1.)); -#71600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71601 = PCURVE('',#71211,#71602); -#71602 = DEFINITIONAL_REPRESENTATION('',(#71603),#71607); -#71603 = LINE('',#71604,#71605); -#71604 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); -#71605 = VECTOR('',#71606,1.); -#71606 = DIRECTION('',(0.E+000,1.)); -#71607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71608 = ADVANCED_FACE('',(#71609),#71576,.F.); -#71609 = FACE_BOUND('',#71610,.T.); -#71610 = EDGE_LOOP('',(#71611,#71612,#71635,#71662)); -#71611 = ORIENTED_EDGE('',*,*,#71560,.T.); -#71612 = ORIENTED_EDGE('',*,*,#71613,.T.); -#71613 = EDGE_CURVE('',#71538,#71614,#71616,.T.); -#71614 = VERTEX_POINT('',#71615); -#71615 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-1.1811)); -#71616 = SURFACE_CURVE('',#71617,(#71621,#71628),.PCURVE_S1.); -#71617 = LINE('',#71618,#71619); -#71618 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-1.1811)); -#71619 = VECTOR('',#71620,1.); -#71620 = DIRECTION('',(-0.973831483203,0.22727129674,3.7556423094E-016) - ); -#71621 = PCURVE('',#71576,#71622); -#71622 = DEFINITIONAL_REPRESENTATION('',(#71623),#71627); -#71623 = LINE('',#71624,#71625); -#71624 = CARTESIAN_POINT('',(-9.154004731012E-016,-2.6289)); -#71625 = VECTOR('',#71626,1.); -#71626 = DIRECTION('',(-1.,3.7556423094E-016)); -#71627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71628 = PCURVE('',#71268,#71629); -#71629 = DEFINITIONAL_REPRESENTATION('',(#71630),#71634); -#71630 = LINE('',#71631,#71632); -#71631 = CARTESIAN_POINT('',(0.49779277355,0.145458775719)); -#71632 = VECTOR('',#71633,1.); -#71633 = DIRECTION('',(-0.973831483203,0.22727129674)); -#71634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71635 = ORIENTED_EDGE('',*,*,#71636,.F.); -#71636 = EDGE_CURVE('',#71637,#71614,#71639,.T.); -#71637 = VERTEX_POINT('',#71638); -#71638 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-0.7239)); -#71639 = SURFACE_CURVE('',#71640,(#71644,#71651),.PCURVE_S1.); -#71640 = LINE('',#71641,#71642); -#71641 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); -#71642 = VECTOR('',#71643,1.); -#71643 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71644 = PCURVE('',#71576,#71645); -#71645 = DEFINITIONAL_REPRESENTATION('',(#71646),#71650); -#71646 = LINE('',#71647,#71648); -#71647 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#71648 = VECTOR('',#71649,1.); -#71649 = DIRECTION('',(0.E+000,-1.)); -#71650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71651 = PCURVE('',#71652,#71657); -#71652 = CYLINDRICAL_SURFACE('',#71653,5.253172734297E-002); -#71653 = AXIS2_PLACEMENT_3D('',#71654,#71655,#71656); -#71654 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.4478)); -#71655 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71656 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71657 = DEFINITIONAL_REPRESENTATION('',(#71658),#71661); -#71658 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71659,#71660),.UNSPECIFIED., + 2.504209090909,2.524990909091,2.545772727273,2.566554545455, + 2.587336363636,2.608118181818,2.6289),.QUASI_UNIFORM_KNOTS.); +#73726 = CARTESIAN_POINT('',(6.28318530718,2.1717)); +#73727 = CARTESIAN_POINT('',(6.28318530718,2.178627272727)); +#73728 = CARTESIAN_POINT('',(6.28318530718,2.192481818182)); +#73729 = CARTESIAN_POINT('',(6.28318530718,2.213263636364)); +#73730 = CARTESIAN_POINT('',(6.28318530718,2.234045454545)); +#73731 = CARTESIAN_POINT('',(6.28318530718,2.254827272727)); +#73732 = CARTESIAN_POINT('',(6.28318530718,2.275609090909)); +#73733 = CARTESIAN_POINT('',(6.28318530718,2.296390909091)); +#73734 = CARTESIAN_POINT('',(6.28318530718,2.317172727273)); +#73735 = CARTESIAN_POINT('',(6.28318530718,2.337954545455)); +#73736 = CARTESIAN_POINT('',(6.28318530718,2.358736363636)); +#73737 = CARTESIAN_POINT('',(6.28318530718,2.379518181818)); +#73738 = CARTESIAN_POINT('',(6.28318530718,2.4003)); +#73739 = CARTESIAN_POINT('',(6.28318530718,2.421081818182)); +#73740 = CARTESIAN_POINT('',(6.28318530718,2.441863636364)); +#73741 = CARTESIAN_POINT('',(6.28318530718,2.462645454545)); +#73742 = CARTESIAN_POINT('',(6.28318530718,2.483427272727)); +#73743 = CARTESIAN_POINT('',(6.28318530718,2.504209090909)); +#73744 = CARTESIAN_POINT('',(6.28318530718,2.524990909091)); +#73745 = CARTESIAN_POINT('',(6.28318530718,2.545772727273)); +#73746 = CARTESIAN_POINT('',(6.28318530718,2.566554545455)); +#73747 = CARTESIAN_POINT('',(6.28318530718,2.587336363636)); +#73748 = CARTESIAN_POINT('',(6.28318530718,2.608118181818)); +#73749 = CARTESIAN_POINT('',(6.28318530718,2.621972727273)); +#73750 = CARTESIAN_POINT('',(6.28318530718,2.6289)); +#73751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73752 = ORIENTED_EDGE('',*,*,#73753,.T.); +#73753 = EDGE_CURVE('',#73704,#73588,#73754,.T.); +#73754 = SURFACE_CURVE('',#73755,(#73759,#73766),.PCURVE_S1.); +#73755 = LINE('',#73756,#73757); +#73756 = CARTESIAN_POINT('',(0.9779,-0.359803853849,-0.7239)); +#73757 = VECTOR('',#73758,1.); +#73758 = DIRECTION('',(0.E+000,1.,0.E+000)); +#73759 = PCURVE('',#73634,#73760); +#73760 = DEFINITIONAL_REPRESENTATION('',(#73761),#73765); +#73761 = LINE('',#73762,#73763); +#73762 = CARTESIAN_POINT('',(2.1717,0.E+000)); +#73763 = VECTOR('',#73764,1.); +#73764 = DIRECTION('',(0.E+000,1.)); +#73765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73766 = PCURVE('',#73603,#73767); +#73767 = DEFINITIONAL_REPRESENTATION('',(#73768),#73772); +#73768 = LINE('',#73769,#73770); +#73769 = CARTESIAN_POINT('',(-0.3302,0.154932254901)); +#73770 = VECTOR('',#73771,1.); +#73771 = DIRECTION('',(0.E+000,1.)); +#73772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73773 = ADVANCED_FACE('',(#73774),#73719,.T.); +#73774 = FACE_BOUND('',#73775,.T.); +#73775 = EDGE_LOOP('',(#73776,#73777,#73800,#73827)); +#73776 = ORIENTED_EDGE('',*,*,#73703,.T.); +#73777 = ORIENTED_EDGE('',*,*,#73778,.T.); +#73778 = EDGE_CURVE('',#73681,#73779,#73781,.T.); +#73779 = VERTEX_POINT('',#73780); +#73780 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,-1.1811)); +#73781 = SURFACE_CURVE('',#73782,(#73787,#73793),.PCURVE_S1.); +#73782 = CIRCLE('',#73783,0.127); +#73783 = AXIS2_PLACEMENT_3D('',#73784,#73785,#73786); +#73784 = CARTESIAN_POINT('',(1.1049,-0.359803853849,-1.1811)); +#73785 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); +#73786 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); +#73787 = PCURVE('',#73719,#73788); +#73788 = DEFINITIONAL_REPRESENTATION('',(#73789),#73792); +#73789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73790,#73791),.UNSPECIFIED., + .F.,.F.,(2,2),(3.14159265359,4.483114246145), + .PIECEWISE_BEZIER_KNOTS.); +#73790 = CARTESIAN_POINT('',(6.28318530718,2.6289)); +#73791 = CARTESIAN_POINT('',(4.941663714624,2.6289)); +#73792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73793 = PCURVE('',#73660,#73794); +#73794 = DEFINITIONAL_REPRESENTATION('',(#73795),#73799); +#73795 = CIRCLE('',#73796,0.127); +#73796 = AXIS2_PLACEMENT_2D('',#73797,#73798); +#73797 = CARTESIAN_POINT('',(0.4572,0.154932254901)); +#73798 = DIRECTION('',(1.,0.E+000)); +#73799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73800 = ORIENTED_EDGE('',*,*,#73801,.F.); +#73801 = EDGE_CURVE('',#73802,#73779,#73804,.T.); +#73802 = VERTEX_POINT('',#73803); +#73803 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,-0.7239)); +#73804 = SURFACE_CURVE('',#73805,(#73809,#73815),.PCURVE_S1.); +#73805 = LINE('',#73806,#73807); +#73806 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.4478)); +#73807 = VECTOR('',#73808,1.); +#73808 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73809 = PCURVE('',#73719,#73810); +#73810 = DEFINITIONAL_REPRESENTATION('',(#73811),#73814); +#73811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73812,#73813),.UNSPECIFIED., .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71659 = CARTESIAN_POINT('',(4.941663714624,2.1717)); -#71660 = CARTESIAN_POINT('',(4.941663714624,2.6289)); -#71661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71662 = ORIENTED_EDGE('',*,*,#71663,.T.); -#71663 = EDGE_CURVE('',#71637,#71561,#71664,.T.); -#71664 = SURFACE_CURVE('',#71665,(#71669,#71676),.PCURVE_S1.); -#71665 = LINE('',#71666,#71667); -#71666 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-0.7239)); -#71667 = VECTOR('',#71668,1.); -#71668 = DIRECTION('',(0.973831483203,-0.22727129674,1.8778211547E-016) - ); -#71669 = PCURVE('',#71576,#71670); -#71670 = DEFINITIONAL_REPRESENTATION('',(#71671),#71675); -#71671 = LINE('',#71672,#71673); -#71672 = CARTESIAN_POINT('',(4.577002365506E-016,-2.1717)); -#71673 = VECTOR('',#71674,1.); -#71674 = DIRECTION('',(1.,1.8778211547E-016)); -#71675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71676 = PCURVE('',#71211,#71677); -#71677 = DEFINITIONAL_REPRESENTATION('',(#71678),#71682); -#71678 = LINE('',#71679,#71680); -#71679 = CARTESIAN_POINT('',(-0.49779277355,0.145458775719)); -#71680 = VECTOR('',#71681,1.); -#71681 = DIRECTION('',(-0.973831483203,-0.22727129674)); -#71682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71683 = ADVANCED_FACE('',(#71684),#71652,.F.); -#71684 = FACE_BOUND('',#71685,.F.); -#71685 = EDGE_LOOP('',(#71686,#71687,#71714,#71741)); -#71686 = ORIENTED_EDGE('',*,*,#71636,.F.); -#71687 = ORIENTED_EDGE('',*,*,#71688,.F.); -#71688 = EDGE_CURVE('',#71689,#71637,#71691,.T.); -#71689 = VERTEX_POINT('',#71690); -#71690 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-0.7239)); -#71691 = SURFACE_CURVE('',#71692,(#71697,#71703),.PCURVE_S1.); -#71692 = CIRCLE('',#71693,5.253172734297E-002); -#71693 = AXIS2_PLACEMENT_3D('',#71694,#71695,#71696); -#71694 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,-0.7239)); -#71695 = DIRECTION('',(-1.928281419412E-016,0.E+000,1.)); -#71696 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); -#71697 = PCURVE('',#71652,#71698); -#71698 = DEFINITIONAL_REPRESENTATION('',(#71699),#71702); -#71699 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71700,#71701),.UNSPECIFIED., +#73812 = CARTESIAN_POINT('',(4.941663714624,2.1717)); +#73813 = CARTESIAN_POINT('',(4.941663714624,2.6289)); +#73814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73815 = PCURVE('',#73816,#73821); +#73816 = PLANE('',#73817); +#73817 = AXIS2_PLACEMENT_3D('',#73818,#73819,#73820); +#73818 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); +#73819 = DIRECTION('',(0.22727129674,0.973831483203,0.E+000)); +#73820 = DIRECTION('',(-0.973831483203,0.22727129674,0.E+000)); +#73821 = DEFINITIONAL_REPRESENTATION('',(#73822),#73826); +#73822 = LINE('',#73823,#73824); +#73823 = CARTESIAN_POINT('',(0.137525754385,0.E+000)); +#73824 = VECTOR('',#73825,1.); +#73825 = DIRECTION('',(0.E+000,-1.)); +#73826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73827 = ORIENTED_EDGE('',*,*,#73828,.T.); +#73828 = EDGE_CURVE('',#73802,#73704,#73829,.T.); +#73829 = SURFACE_CURVE('',#73830,(#73835,#73841),.PCURVE_S1.); +#73830 = CIRCLE('',#73831,0.127); +#73831 = AXIS2_PLACEMENT_3D('',#73832,#73833,#73834); +#73832 = CARTESIAN_POINT('',(1.1049,-0.359803853849,-0.7239)); +#73833 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); +#73834 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); +#73835 = PCURVE('',#73719,#73836); +#73836 = DEFINITIONAL_REPRESENTATION('',(#73837),#73840); +#73837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73838,#73839),.UNSPECIFIED., + .F.,.F.,(2,2),(4.941663714624,6.28318530718), + .PIECEWISE_BEZIER_KNOTS.); +#73838 = CARTESIAN_POINT('',(4.941663714624,2.1717)); +#73839 = CARTESIAN_POINT('',(6.28318530718,2.1717)); +#73840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73841 = PCURVE('',#73603,#73842); +#73842 = DEFINITIONAL_REPRESENTATION('',(#73843),#73847); +#73843 = CIRCLE('',#73844,0.127); +#73844 = AXIS2_PLACEMENT_2D('',#73845,#73846); +#73845 = CARTESIAN_POINT('',(-0.4572,0.154932254901)); +#73846 = DIRECTION('',(1.,0.E+000)); +#73847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73848 = ADVANCED_FACE('',(#73849),#73816,.F.); +#73849 = FACE_BOUND('',#73850,.T.); +#73850 = EDGE_LOOP('',(#73851,#73852,#73875,#73903)); +#73851 = ORIENTED_EDGE('',*,*,#73801,.T.); +#73852 = ORIENTED_EDGE('',*,*,#73853,.T.); +#73853 = EDGE_CURVE('',#73779,#73854,#73856,.T.); +#73854 = VERTEX_POINT('',#73855); +#73855 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); +#73856 = SURFACE_CURVE('',#73857,(#73861,#73868),.PCURVE_S1.); +#73857 = LINE('',#73858,#73859); +#73858 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); +#73859 = VECTOR('',#73860,1.); +#73860 = DIRECTION('',(0.973831483203,-0.22727129674,-3.7556423094E-016) + ); +#73861 = PCURVE('',#73816,#73862); +#73862 = DEFINITIONAL_REPRESENTATION('',(#73863),#73867); +#73863 = LINE('',#73864,#73865); +#73864 = CARTESIAN_POINT('',(9.154004731012E-016,-2.6289)); +#73865 = VECTOR('',#73866,1.); +#73866 = DIRECTION('',(-1.,-3.7556423094E-016)); +#73867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73868 = PCURVE('',#73660,#73869); +#73869 = DEFINITIONAL_REPRESENTATION('',(#73870),#73874); +#73870 = LINE('',#73871,#73872); +#73871 = CARTESIAN_POINT('',(0.562263454686,2.22044604925E-016)); +#73872 = VECTOR('',#73873,1.); +#73873 = DIRECTION('',(0.973831483203,-0.22727129674)); +#73874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73875 = ORIENTED_EDGE('',*,*,#73876,.F.); +#73876 = EDGE_CURVE('',#73877,#73854,#73879,.T.); +#73877 = VERTEX_POINT('',#73878); +#73878 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); +#73879 = SURFACE_CURVE('',#73880,(#73884,#73891),.PCURVE_S1.); +#73880 = LINE('',#73881,#73882); +#73881 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); +#73882 = VECTOR('',#73883,1.); +#73883 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73884 = PCURVE('',#73816,#73885); +#73885 = DEFINITIONAL_REPRESENTATION('',(#73886),#73890); +#73886 = LINE('',#73887,#73888); +#73887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#73888 = VECTOR('',#73889,1.); +#73889 = DIRECTION('',(0.E+000,-1.)); +#73890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73891 = PCURVE('',#73892,#73897); +#73892 = PLANE('',#73893); +#73893 = AXIS2_PLACEMENT_3D('',#73894,#73895,#73896); +#73894 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); +#73895 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#73896 = DIRECTION('',(0.E+000,0.E+000,1.)); +#73897 = DEFINITIONAL_REPRESENTATION('',(#73898),#73902); +#73898 = LINE('',#73899,#73900); +#73899 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); +#73900 = VECTOR('',#73901,1.); +#73901 = DIRECTION('',(-1.,0.E+000)); +#73902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73903 = ORIENTED_EDGE('',*,*,#73904,.T.); +#73904 = EDGE_CURVE('',#73877,#73802,#73905,.T.); +#73905 = SURFACE_CURVE('',#73906,(#73910,#73917),.PCURVE_S1.); +#73906 = LINE('',#73907,#73908); +#73907 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); +#73908 = VECTOR('',#73909,1.); +#73909 = DIRECTION('',(-0.973831483203,0.22727129674,-1.8778211547E-016) + ); +#73910 = PCURVE('',#73816,#73911); +#73911 = DEFINITIONAL_REPRESENTATION('',(#73912),#73916); +#73912 = LINE('',#73913,#73914); +#73913 = CARTESIAN_POINT('',(-4.577002365506E-016,-2.1717)); +#73914 = VECTOR('',#73915,1.); +#73915 = DIRECTION('',(1.,-1.8778211547E-016)); +#73916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73917 = PCURVE('',#73603,#73918); +#73918 = DEFINITIONAL_REPRESENTATION('',(#73919),#73923); +#73919 = LINE('',#73920,#73921); +#73920 = CARTESIAN_POINT('',(-0.562263454686,-1.110223024625E-016)); +#73921 = VECTOR('',#73922,1.); +#73922 = DIRECTION('',(0.973831483203,0.22727129674)); +#73923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73924 = ADVANCED_FACE('',(#73925),#73892,.F.); +#73925 = FACE_BOUND('',#73926,.T.); +#73926 = EDGE_LOOP('',(#73927,#73928,#73951,#73979)); +#73927 = ORIENTED_EDGE('',*,*,#73876,.T.); +#73928 = ORIENTED_EDGE('',*,*,#73929,.T.); +#73929 = EDGE_CURVE('',#73854,#73930,#73932,.T.); +#73930 = VERTEX_POINT('',#73931); +#73931 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,-1.1811)); +#73932 = SURFACE_CURVE('',#73933,(#73937,#73944),.PCURVE_S1.); +#73933 = LINE('',#73934,#73935); +#73934 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-1.1811)); +#73935 = VECTOR('',#73936,1.); +#73936 = DIRECTION('',(0.E+000,1.,0.E+000)); +#73937 = PCURVE('',#73892,#73938); +#73938 = DEFINITIONAL_REPRESENTATION('',(#73939),#73943); +#73939 = LINE('',#73940,#73941); +#73940 = CARTESIAN_POINT('',(-2.6289,-0.130412707117)); +#73941 = VECTOR('',#73942,1.); +#73942 = DIRECTION('',(0.E+000,1.)); +#73943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73944 = PCURVE('',#73660,#73945); +#73945 = DEFINITIONAL_REPRESENTATION('',(#73946),#73950); +#73946 = LINE('',#73947,#73948); +#73947 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); +#73948 = VECTOR('',#73949,1.); +#73949 = DIRECTION('',(0.E+000,1.)); +#73950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73951 = ORIENTED_EDGE('',*,*,#73952,.F.); +#73952 = EDGE_CURVE('',#73953,#73930,#73955,.T.); +#73953 = VERTEX_POINT('',#73954); +#73954 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,-0.7239)); +#73955 = SURFACE_CURVE('',#73956,(#73960,#73967),.PCURVE_S1.); +#73956 = LINE('',#73957,#73958); +#73957 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); +#73958 = VECTOR('',#73959,1.); +#73959 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#73960 = PCURVE('',#73892,#73961); +#73961 = DEFINITIONAL_REPRESENTATION('',(#73962),#73966); +#73962 = LINE('',#73963,#73964); +#73963 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#73964 = VECTOR('',#73965,1.); +#73965 = DIRECTION('',(-1.,0.E+000)); +#73966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73967 = PCURVE('',#73968,#73973); +#73968 = PLANE('',#73969); +#73969 = AXIS2_PLACEMENT_3D('',#73970,#73971,#73972); +#73970 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); +#73971 = DIRECTION('',(-0.22727129674,-0.973831483203,0.E+000)); +#73972 = DIRECTION('',(0.973831483203,-0.22727129674,0.E+000)); +#73973 = DEFINITIONAL_REPRESENTATION('',(#73974),#73978); +#73974 = LINE('',#73975,#73976); +#73975 = CARTESIAN_POINT('',(6.62031185561E-002,0.E+000)); +#73976 = VECTOR('',#73977,1.); +#73977 = DIRECTION('',(0.E+000,-1.)); +#73978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73979 = ORIENTED_EDGE('',*,*,#73980,.F.); +#73980 = EDGE_CURVE('',#73877,#73953,#73981,.T.); +#73981 = SURFACE_CURVE('',#73982,(#73986,#73993),.PCURVE_S1.); +#73982 = LINE('',#73983,#73984); +#73983 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,-0.7239)); +#73984 = VECTOR('',#73985,1.); +#73985 = DIRECTION('',(0.E+000,1.,0.E+000)); +#73986 = PCURVE('',#73892,#73987); +#73987 = DEFINITIONAL_REPRESENTATION('',(#73988),#73992); +#73988 = LINE('',#73989,#73990); +#73989 = CARTESIAN_POINT('',(-2.1717,-0.130412707117)); +#73990 = VECTOR('',#73991,1.); +#73991 = DIRECTION('',(0.E+000,1.)); +#73992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#73993 = PCURVE('',#73603,#73994); +#73994 = DEFINITIONAL_REPRESENTATION('',(#73995),#73999); +#73995 = LINE('',#73996,#73997); +#73996 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); +#73997 = VECTOR('',#73998,1.); +#73998 = DIRECTION('',(0.E+000,1.)); +#73999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74000 = ADVANCED_FACE('',(#74001),#73968,.F.); +#74001 = FACE_BOUND('',#74002,.T.); +#74002 = EDGE_LOOP('',(#74003,#74004,#74027,#74054)); +#74003 = ORIENTED_EDGE('',*,*,#73952,.T.); +#74004 = ORIENTED_EDGE('',*,*,#74005,.T.); +#74005 = EDGE_CURVE('',#73930,#74006,#74008,.T.); +#74006 = VERTEX_POINT('',#74007); +#74007 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-1.1811)); +#74008 = SURFACE_CURVE('',#74009,(#74013,#74020),.PCURVE_S1.); +#74009 = LINE('',#74010,#74011); +#74010 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-1.1811)); +#74011 = VECTOR('',#74012,1.); +#74012 = DIRECTION('',(-0.973831483203,0.22727129674,3.7556423094E-016) + ); +#74013 = PCURVE('',#73968,#74014); +#74014 = DEFINITIONAL_REPRESENTATION('',(#74015),#74019); +#74015 = LINE('',#74016,#74017); +#74016 = CARTESIAN_POINT('',(-9.154004731012E-016,-2.6289)); +#74017 = VECTOR('',#74018,1.); +#74018 = DIRECTION('',(-1.,3.7556423094E-016)); +#74019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74020 = PCURVE('',#73660,#74021); +#74021 = DEFINITIONAL_REPRESENTATION('',(#74022),#74026); +#74022 = LINE('',#74023,#74024); +#74023 = CARTESIAN_POINT('',(0.49779277355,0.145458775719)); +#74024 = VECTOR('',#74025,1.); +#74025 = DIRECTION('',(-0.973831483203,0.22727129674)); +#74026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74027 = ORIENTED_EDGE('',*,*,#74028,.F.); +#74028 = EDGE_CURVE('',#74029,#74006,#74031,.T.); +#74029 = VERTEX_POINT('',#74030); +#74030 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-0.7239)); +#74031 = SURFACE_CURVE('',#74032,(#74036,#74043),.PCURVE_S1.); +#74032 = LINE('',#74033,#74034); +#74033 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); +#74034 = VECTOR('',#74035,1.); +#74035 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74036 = PCURVE('',#73968,#74037); +#74037 = DEFINITIONAL_REPRESENTATION('',(#74038),#74042); +#74038 = LINE('',#74039,#74040); +#74039 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74040 = VECTOR('',#74041,1.); +#74041 = DIRECTION('',(0.E+000,-1.)); +#74042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74043 = PCURVE('',#74044,#74049); +#74044 = CYLINDRICAL_SURFACE('',#74045,5.253172734297E-002); +#74045 = AXIS2_PLACEMENT_3D('',#74046,#74047,#74048); +#74046 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.4478)); +#74047 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74048 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74049 = DEFINITIONAL_REPRESENTATION('',(#74050),#74053); +#74050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74051,#74052),.UNSPECIFIED., + .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); +#74051 = CARTESIAN_POINT('',(4.941663714624,2.1717)); +#74052 = CARTESIAN_POINT('',(4.941663714624,2.6289)); +#74053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74054 = ORIENTED_EDGE('',*,*,#74055,.T.); +#74055 = EDGE_CURVE('',#74029,#73953,#74056,.T.); +#74056 = SURFACE_CURVE('',#74057,(#74061,#74068),.PCURVE_S1.); +#74057 = LINE('',#74058,#74059); +#74058 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,-0.7239)); +#74059 = VECTOR('',#74060,1.); +#74060 = DIRECTION('',(0.973831483203,-0.22727129674,1.8778211547E-016) + ); +#74061 = PCURVE('',#73968,#74062); +#74062 = DEFINITIONAL_REPRESENTATION('',(#74063),#74067); +#74063 = LINE('',#74064,#74065); +#74064 = CARTESIAN_POINT('',(4.577002365506E-016,-2.1717)); +#74065 = VECTOR('',#74066,1.); +#74066 = DIRECTION('',(1.,1.8778211547E-016)); +#74067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74068 = PCURVE('',#73603,#74069); +#74069 = DEFINITIONAL_REPRESENTATION('',(#74070),#74074); +#74070 = LINE('',#74071,#74072); +#74071 = CARTESIAN_POINT('',(-0.49779277355,0.145458775719)); +#74072 = VECTOR('',#74073,1.); +#74073 = DIRECTION('',(-0.973831483203,-0.22727129674)); +#74074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74075 = ADVANCED_FACE('',(#74076),#74044,.F.); +#74076 = FACE_BOUND('',#74077,.F.); +#74077 = EDGE_LOOP('',(#74078,#74079,#74106,#74133)); +#74078 = ORIENTED_EDGE('',*,*,#74028,.F.); +#74079 = ORIENTED_EDGE('',*,*,#74080,.F.); +#74080 = EDGE_CURVE('',#74081,#74029,#74083,.T.); +#74081 = VERTEX_POINT('',#74082); +#74082 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-0.7239)); +#74083 = SURFACE_CURVE('',#74084,(#74089,#74095),.PCURVE_S1.); +#74084 = CIRCLE('',#74085,5.253172734297E-002); +#74085 = AXIS2_PLACEMENT_3D('',#74086,#74087,#74088); +#74086 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,-0.7239)); +#74087 = DIRECTION('',(-1.928281419412E-016,0.E+000,1.)); +#74088 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); +#74089 = PCURVE('',#74044,#74090); +#74090 = DEFINITIONAL_REPRESENTATION('',(#74091),#74094); +#74091 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74092,#74093),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.341521592555),.PIECEWISE_BEZIER_KNOTS.); -#71700 = CARTESIAN_POINT('',(6.28318530718,2.1717)); -#71701 = CARTESIAN_POINT('',(4.941663714624,2.1717)); -#71702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74092 = CARTESIAN_POINT('',(6.28318530718,2.1717)); +#74093 = CARTESIAN_POINT('',(4.941663714624,2.1717)); +#74094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#71703 = PCURVE('',#71211,#71704); -#71704 = DEFINITIONAL_REPRESENTATION('',(#71705),#71713); -#71705 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#71706,#71707,#71708,#71709 - ,#71710,#71711,#71712),.UNSPECIFIED.,.T.,.F.) +#74095 = PCURVE('',#73603,#74096); +#74096 = DEFINITIONAL_REPRESENTATION('',(#74097),#74105); +#74097 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74098,#74099,#74100,#74101 + ,#74102,#74103,#74104),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#71706 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#71707 = CARTESIAN_POINT('',(-0.4572,0.105628204905)); -#71708 = CARTESIAN_POINT('',(-0.535997591014,0.151122015289)); -#71709 = CARTESIAN_POINT('',(-0.614795182029,0.196615825673)); -#71710 = CARTESIAN_POINT('',(-0.535997591014,0.242109636056)); -#71711 = CARTESIAN_POINT('',(-0.4572,0.28760344644)); -#71712 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#71713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71714 = ORIENTED_EDGE('',*,*,#71715,.T.); -#71715 = EDGE_CURVE('',#71689,#71716,#71718,.T.); -#71716 = VERTEX_POINT('',#71717); -#71717 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-1.1811)); -#71718 = SURFACE_CURVE('',#71719,(#71723,#71729),.PCURVE_S1.); -#71719 = LINE('',#71720,#71721); -#71720 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); -#71721 = VECTOR('',#71722,1.); -#71722 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71723 = PCURVE('',#71652,#71724); -#71724 = DEFINITIONAL_REPRESENTATION('',(#71725),#71728); -#71725 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71726,#71727),.UNSPECIFIED., +#74098 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#74099 = CARTESIAN_POINT('',(-0.4572,0.105628204905)); +#74100 = CARTESIAN_POINT('',(-0.535997591014,0.151122015289)); +#74101 = CARTESIAN_POINT('',(-0.614795182029,0.196615825673)); +#74102 = CARTESIAN_POINT('',(-0.535997591014,0.242109636056)); +#74103 = CARTESIAN_POINT('',(-0.4572,0.28760344644)); +#74104 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#74105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74106 = ORIENTED_EDGE('',*,*,#74107,.T.); +#74107 = EDGE_CURVE('',#74081,#74108,#74110,.T.); +#74108 = VERTEX_POINT('',#74109); +#74109 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-1.1811)); +#74110 = SURFACE_CURVE('',#74111,(#74115,#74121),.PCURVE_S1.); +#74111 = LINE('',#74112,#74113); +#74112 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); +#74113 = VECTOR('',#74114,1.); +#74114 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74115 = PCURVE('',#74044,#74116); +#74116 = DEFINITIONAL_REPRESENTATION('',(#74117),#74120); +#74117 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74118,#74119),.UNSPECIFIED., .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71726 = CARTESIAN_POINT('',(6.28318530718,2.1717)); -#71727 = CARTESIAN_POINT('',(6.28318530718,2.6289)); -#71728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71729 = PCURVE('',#71730,#71735); -#71730 = PLANE('',#71731); -#71731 = AXIS2_PLACEMENT_3D('',#71732,#71733,#71734); -#71732 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); -#71733 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71734 = DIRECTION('',(0.E+000,0.E+000,1.)); -#71735 = DEFINITIONAL_REPRESENTATION('',(#71736),#71740); -#71736 = LINE('',#71737,#71738); -#71737 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#71738 = VECTOR('',#71739,1.); -#71739 = DIRECTION('',(-1.,0.E+000)); -#71740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71741 = ORIENTED_EDGE('',*,*,#71742,.F.); -#71742 = EDGE_CURVE('',#71614,#71716,#71743,.T.); -#71743 = SURFACE_CURVE('',#71744,(#71749,#71755),.PCURVE_S1.); -#71744 = CIRCLE('',#71745,5.253172734297E-002); -#71745 = AXIS2_PLACEMENT_3D('',#71746,#71747,#71748); -#71746 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,-1.1811)); -#71747 = DIRECTION('',(-3.856562838825E-016,-1.971431250164E-047,-1.)); -#71748 = DIRECTION('',(1.,-1.031949858994E-015,-3.856562838825E-016)); -#71749 = PCURVE('',#71652,#71750); -#71750 = DEFINITIONAL_REPRESENTATION('',(#71751),#71754); -#71751 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71752,#71753),.UNSPECIFIED., +#74118 = CARTESIAN_POINT('',(6.28318530718,2.1717)); +#74119 = CARTESIAN_POINT('',(6.28318530718,2.6289)); +#74120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74121 = PCURVE('',#74122,#74127); +#74122 = PLANE('',#74123); +#74123 = AXIS2_PLACEMENT_3D('',#74124,#74125,#74126); +#74124 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); +#74125 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74126 = DIRECTION('',(0.E+000,0.E+000,1.)); +#74127 = DEFINITIONAL_REPRESENTATION('',(#74128),#74132); +#74128 = LINE('',#74129,#74130); +#74129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74130 = VECTOR('',#74131,1.); +#74131 = DIRECTION('',(-1.,0.E+000)); +#74132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74133 = ORIENTED_EDGE('',*,*,#74134,.F.); +#74134 = EDGE_CURVE('',#74006,#74108,#74135,.T.); +#74135 = SURFACE_CURVE('',#74136,(#74141,#74147),.PCURVE_S1.); +#74136 = CIRCLE('',#74137,5.253172734297E-002); +#74137 = AXIS2_PLACEMENT_3D('',#74138,#74139,#74140); +#74138 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,-1.1811)); +#74139 = DIRECTION('',(-3.856562838825E-016,-1.971431250164E-047,-1.)); +#74140 = DIRECTION('',(1.,-1.031949858994E-015,-3.856562838825E-016)); +#74141 = PCURVE('',#74044,#74142); +#74142 = DEFINITIONAL_REPRESENTATION('',(#74143),#74146); +#74143 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74144,#74145),.UNSPECIFIED., .F.,.F.,(2,2),(1.800071061035,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#71752 = CARTESIAN_POINT('',(4.941663714624,2.6289)); -#71753 = CARTESIAN_POINT('',(6.28318530718,2.6289)); -#71754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74144 = CARTESIAN_POINT('',(4.941663714624,2.6289)); +#74145 = CARTESIAN_POINT('',(6.28318530718,2.6289)); +#74146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#71755 = PCURVE('',#71268,#71756); -#71756 = DEFINITIONAL_REPRESENTATION('',(#71757),#71765); -#71757 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#71758,#71759,#71760,#71761 - ,#71762,#71763,#71764),.UNSPECIFIED.,.T.,.F.) +#74147 = PCURVE('',#73660,#74148); +#74148 = DEFINITIONAL_REPRESENTATION('',(#74149),#74157); +#74149 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74150,#74151,#74152,#74153 + ,#74154,#74155,#74156),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#71758 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); -#71759 = CARTESIAN_POINT('',(0.562263454686,0.105628204905)); -#71760 = CARTESIAN_POINT('',(0.483465863671,0.151122015289)); -#71761 = CARTESIAN_POINT('',(0.404668272657,0.196615825673)); -#71762 = CARTESIAN_POINT('',(0.483465863671,0.242109636056)); -#71763 = CARTESIAN_POINT('',(0.562263454686,0.28760344644)); -#71764 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); -#71765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71766 = ADVANCED_FACE('',(#71767),#71730,.F.); -#71767 = FACE_BOUND('',#71768,.T.); -#71768 = EDGE_LOOP('',(#71769,#71770,#71793,#71820)); -#71769 = ORIENTED_EDGE('',*,*,#71715,.T.); -#71770 = ORIENTED_EDGE('',*,*,#71771,.T.); -#71771 = EDGE_CURVE('',#71716,#71772,#71774,.T.); -#71772 = VERTEX_POINT('',#71773); -#71773 = CARTESIAN_POINT('',(1.1049,-0.254,-1.1811)); -#71774 = SURFACE_CURVE('',#71775,(#71779,#71786),.PCURVE_S1.); -#71775 = LINE('',#71776,#71777); -#71776 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-1.1811)); -#71777 = VECTOR('',#71778,1.); -#71778 = DIRECTION('',(0.E+000,1.,0.E+000)); -#71779 = PCURVE('',#71730,#71780); -#71780 = DEFINITIONAL_REPRESENTATION('',(#71781),#71785); -#71781 = LINE('',#71782,#71783); -#71782 = CARTESIAN_POINT('',(-2.6289,0.E+000)); -#71783 = VECTOR('',#71784,1.); -#71784 = DIRECTION('',(0.E+000,1.)); -#71785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71786 = PCURVE('',#71268,#71787); -#71787 = DEFINITIONAL_REPRESENTATION('',(#71788),#71792); -#71788 = LINE('',#71789,#71790); -#71789 = CARTESIAN_POINT('',(0.4572,0.196615825673)); -#71790 = VECTOR('',#71791,1.); -#71791 = DIRECTION('',(0.E+000,1.)); -#71792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71793 = ORIENTED_EDGE('',*,*,#71794,.F.); -#71794 = EDGE_CURVE('',#71795,#71772,#71797,.T.); -#71795 = VERTEX_POINT('',#71796); -#71796 = CARTESIAN_POINT('',(1.1049,-0.254,-0.7239)); -#71797 = SURFACE_CURVE('',#71798,(#71802,#71809),.PCURVE_S1.); -#71798 = LINE('',#71799,#71800); -#71799 = CARTESIAN_POINT('',(1.1049,-0.254,1.4478)); -#71800 = VECTOR('',#71801,1.); -#71801 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71802 = PCURVE('',#71730,#71803); -#71803 = DEFINITIONAL_REPRESENTATION('',(#71804),#71808); -#71804 = LINE('',#71805,#71806); -#71805 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); -#71806 = VECTOR('',#71807,1.); -#71807 = DIRECTION('',(-1.,0.E+000)); -#71808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71809 = PCURVE('',#71810,#71815); -#71810 = CYLINDRICAL_SURFACE('',#71811,0.254); -#71811 = AXIS2_PLACEMENT_3D('',#71812,#71813,#71814); -#71812 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); -#71813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71814 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#71815 = DEFINITIONAL_REPRESENTATION('',(#71816),#71819); -#71816 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71817,#71818),.UNSPECIFIED., +#74150 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); +#74151 = CARTESIAN_POINT('',(0.562263454686,0.105628204905)); +#74152 = CARTESIAN_POINT('',(0.483465863671,0.151122015289)); +#74153 = CARTESIAN_POINT('',(0.404668272657,0.196615825673)); +#74154 = CARTESIAN_POINT('',(0.483465863671,0.242109636056)); +#74155 = CARTESIAN_POINT('',(0.562263454686,0.28760344644)); +#74156 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); +#74157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74158 = ADVANCED_FACE('',(#74159),#74122,.F.); +#74159 = FACE_BOUND('',#74160,.T.); +#74160 = EDGE_LOOP('',(#74161,#74162,#74185,#74212)); +#74161 = ORIENTED_EDGE('',*,*,#74107,.T.); +#74162 = ORIENTED_EDGE('',*,*,#74163,.T.); +#74163 = EDGE_CURVE('',#74108,#74164,#74166,.T.); +#74164 = VERTEX_POINT('',#74165); +#74165 = CARTESIAN_POINT('',(1.1049,-0.254,-1.1811)); +#74166 = SURFACE_CURVE('',#74167,(#74171,#74178),.PCURVE_S1.); +#74167 = LINE('',#74168,#74169); +#74168 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-1.1811)); +#74169 = VECTOR('',#74170,1.); +#74170 = DIRECTION('',(0.E+000,1.,0.E+000)); +#74171 = PCURVE('',#74122,#74172); +#74172 = DEFINITIONAL_REPRESENTATION('',(#74173),#74177); +#74173 = LINE('',#74174,#74175); +#74174 = CARTESIAN_POINT('',(-2.6289,0.E+000)); +#74175 = VECTOR('',#74176,1.); +#74176 = DIRECTION('',(0.E+000,1.)); +#74177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74178 = PCURVE('',#73660,#74179); +#74179 = DEFINITIONAL_REPRESENTATION('',(#74180),#74184); +#74180 = LINE('',#74181,#74182); +#74181 = CARTESIAN_POINT('',(0.4572,0.196615825673)); +#74182 = VECTOR('',#74183,1.); +#74183 = DIRECTION('',(0.E+000,1.)); +#74184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74185 = ORIENTED_EDGE('',*,*,#74186,.F.); +#74186 = EDGE_CURVE('',#74187,#74164,#74189,.T.); +#74187 = VERTEX_POINT('',#74188); +#74188 = CARTESIAN_POINT('',(1.1049,-0.254,-0.7239)); +#74189 = SURFACE_CURVE('',#74190,(#74194,#74201),.PCURVE_S1.); +#74190 = LINE('',#74191,#74192); +#74191 = CARTESIAN_POINT('',(1.1049,-0.254,1.4478)); +#74192 = VECTOR('',#74193,1.); +#74193 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74194 = PCURVE('',#74122,#74195); +#74195 = DEFINITIONAL_REPRESENTATION('',(#74196),#74200); +#74196 = LINE('',#74197,#74198); +#74197 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); +#74198 = VECTOR('',#74199,1.); +#74199 = DIRECTION('',(-1.,0.E+000)); +#74200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74201 = PCURVE('',#74202,#74207); +#74202 = CYLINDRICAL_SURFACE('',#74203,0.254); +#74203 = AXIS2_PLACEMENT_3D('',#74204,#74205,#74206); +#74204 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); +#74205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74206 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74207 = DEFINITIONAL_REPRESENTATION('',(#74208),#74211); +#74208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74209,#74210),.UNSPECIFIED., .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71817 = CARTESIAN_POINT('',(3.14159265359,2.1717)); -#71818 = CARTESIAN_POINT('',(3.14159265359,2.6289)); -#71819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71820 = ORIENTED_EDGE('',*,*,#71821,.T.); -#71821 = EDGE_CURVE('',#71795,#71689,#71822,.T.); -#71822 = SURFACE_CURVE('',#71823,(#71827,#71834),.PCURVE_S1.); -#71823 = LINE('',#71824,#71825); -#71824 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-0.7239)); -#71825 = VECTOR('',#71826,1.); -#71826 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#71827 = PCURVE('',#71730,#71828); -#71828 = DEFINITIONAL_REPRESENTATION('',(#71829),#71833); -#71829 = LINE('',#71830,#71831); -#71830 = CARTESIAN_POINT('',(-2.1717,0.E+000)); -#71831 = VECTOR('',#71832,1.); -#71832 = DIRECTION('',(0.E+000,-1.)); -#71833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71834 = PCURVE('',#71211,#71835); -#71835 = DEFINITIONAL_REPRESENTATION('',(#71836),#71840); -#71836 = LINE('',#71837,#71838); -#71837 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#71838 = VECTOR('',#71839,1.); -#71839 = DIRECTION('',(0.E+000,-1.)); -#71840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71841 = ADVANCED_FACE('',(#71842),#71810,.T.); -#71842 = FACE_BOUND('',#71843,.T.); -#71843 = EDGE_LOOP('',(#71844,#71845,#71868,#71895)); -#71844 = ORIENTED_EDGE('',*,*,#71794,.T.); -#71845 = ORIENTED_EDGE('',*,*,#71846,.T.); -#71846 = EDGE_CURVE('',#71772,#71847,#71849,.T.); -#71847 = VERTEX_POINT('',#71848); -#71848 = CARTESIAN_POINT('',(0.8509,0.E+000,-1.1811)); -#71849 = SURFACE_CURVE('',#71850,(#71855,#71861),.PCURVE_S1.); -#71850 = CIRCLE('',#71851,0.254); -#71851 = AXIS2_PLACEMENT_3D('',#71852,#71853,#71854); -#71852 = CARTESIAN_POINT('',(0.8509,-0.254,-1.1811)); -#71853 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); -#71854 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); -#71855 = PCURVE('',#71810,#71856); -#71856 = DEFINITIONAL_REPRESENTATION('',(#71857),#71860); -#71857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71858,#71859),.UNSPECIFIED., +#74209 = CARTESIAN_POINT('',(3.14159265359,2.1717)); +#74210 = CARTESIAN_POINT('',(3.14159265359,2.6289)); +#74211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74212 = ORIENTED_EDGE('',*,*,#74213,.T.); +#74213 = EDGE_CURVE('',#74187,#74081,#74214,.T.); +#74214 = SURFACE_CURVE('',#74215,(#74219,#74226),.PCURVE_S1.); +#74215 = LINE('',#74216,#74217); +#74216 = CARTESIAN_POINT('',(1.1049,-0.318120283077,-0.7239)); +#74217 = VECTOR('',#74218,1.); +#74218 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#74219 = PCURVE('',#74122,#74220); +#74220 = DEFINITIONAL_REPRESENTATION('',(#74221),#74225); +#74221 = LINE('',#74222,#74223); +#74222 = CARTESIAN_POINT('',(-2.1717,0.E+000)); +#74223 = VECTOR('',#74224,1.); +#74224 = DIRECTION('',(0.E+000,-1.)); +#74225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74226 = PCURVE('',#73603,#74227); +#74227 = DEFINITIONAL_REPRESENTATION('',(#74228),#74232); +#74228 = LINE('',#74229,#74230); +#74229 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#74230 = VECTOR('',#74231,1.); +#74231 = DIRECTION('',(0.E+000,-1.)); +#74232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74233 = ADVANCED_FACE('',(#74234),#74202,.T.); +#74234 = FACE_BOUND('',#74235,.T.); +#74235 = EDGE_LOOP('',(#74236,#74237,#74260,#74287)); +#74236 = ORIENTED_EDGE('',*,*,#74186,.T.); +#74237 = ORIENTED_EDGE('',*,*,#74238,.T.); +#74238 = EDGE_CURVE('',#74164,#74239,#74241,.T.); +#74239 = VERTEX_POINT('',#74240); +#74240 = CARTESIAN_POINT('',(0.8509,0.E+000,-1.1811)); +#74241 = SURFACE_CURVE('',#74242,(#74247,#74253),.PCURVE_S1.); +#74242 = CIRCLE('',#74243,0.254); +#74243 = AXIS2_PLACEMENT_3D('',#74244,#74245,#74246); +#74244 = CARTESIAN_POINT('',(0.8509,-0.254,-1.1811)); +#74245 = DIRECTION('',(3.856562838825E-016,0.E+000,1.)); +#74246 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); +#74247 = PCURVE('',#74202,#74248); +#74248 = DEFINITIONAL_REPRESENTATION('',(#74249),#74252); +#74249 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74250,#74251),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#71858 = CARTESIAN_POINT('',(3.14159265359,2.6289)); -#71859 = CARTESIAN_POINT('',(1.570796326795,2.6289)); -#71860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71861 = PCURVE('',#71268,#71862); -#71862 = DEFINITIONAL_REPRESENTATION('',(#71863),#71867); -#71863 = CIRCLE('',#71864,0.254); -#71864 = AXIS2_PLACEMENT_2D('',#71865,#71866); -#71865 = CARTESIAN_POINT('',(0.2032,0.26073610875)); -#71866 = DIRECTION('',(1.,0.E+000)); -#71867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71868 = ORIENTED_EDGE('',*,*,#71869,.F.); -#71869 = EDGE_CURVE('',#71870,#71847,#71872,.T.); -#71870 = VERTEX_POINT('',#71871); -#71871 = CARTESIAN_POINT('',(0.8509,0.E+000,-0.7239)); -#71872 = SURFACE_CURVE('',#71873,(#71877,#71883),.PCURVE_S1.); -#71873 = LINE('',#71874,#71875); -#71874 = CARTESIAN_POINT('',(0.8509,0.E+000,1.4478)); -#71875 = VECTOR('',#71876,1.); -#71876 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71877 = PCURVE('',#71810,#71878); -#71878 = DEFINITIONAL_REPRESENTATION('',(#71879),#71882); -#71879 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71880,#71881),.UNSPECIFIED., +#74250 = CARTESIAN_POINT('',(3.14159265359,2.6289)); +#74251 = CARTESIAN_POINT('',(1.570796326795,2.6289)); +#74252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74253 = PCURVE('',#73660,#74254); +#74254 = DEFINITIONAL_REPRESENTATION('',(#74255),#74259); +#74255 = CIRCLE('',#74256,0.254); +#74256 = AXIS2_PLACEMENT_2D('',#74257,#74258); +#74257 = CARTESIAN_POINT('',(0.2032,0.26073610875)); +#74258 = DIRECTION('',(1.,0.E+000)); +#74259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74260 = ORIENTED_EDGE('',*,*,#74261,.F.); +#74261 = EDGE_CURVE('',#74262,#74239,#74264,.T.); +#74262 = VERTEX_POINT('',#74263); +#74263 = CARTESIAN_POINT('',(0.8509,0.E+000,-0.7239)); +#74264 = SURFACE_CURVE('',#74265,(#74269,#74275),.PCURVE_S1.); +#74265 = LINE('',#74266,#74267); +#74266 = CARTESIAN_POINT('',(0.8509,0.E+000,1.4478)); +#74267 = VECTOR('',#74268,1.); +#74268 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74269 = PCURVE('',#74202,#74270); +#74270 = DEFINITIONAL_REPRESENTATION('',(#74271),#74274); +#74271 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74272,#74273),.UNSPECIFIED., .F.,.F.,(2,2),(2.1717,2.6289),.PIECEWISE_BEZIER_KNOTS.); -#71880 = CARTESIAN_POINT('',(1.570796326795,2.1717)); -#71881 = CARTESIAN_POINT('',(1.570796326795,2.6289)); -#71882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71883 = PCURVE('',#71884,#71889); -#71884 = PLANE('',#71885); -#71885 = AXIS2_PLACEMENT_3D('',#71886,#71887,#71888); -#71886 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#71887 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#71888 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71889 = DEFINITIONAL_REPRESENTATION('',(#71890),#71894); -#71890 = LINE('',#71891,#71892); -#71891 = CARTESIAN_POINT('',(0.E+000,0.2032)); -#71892 = VECTOR('',#71893,1.); -#71893 = DIRECTION('',(1.,0.E+000)); -#71894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71895 = ORIENTED_EDGE('',*,*,#71896,.T.); -#71896 = EDGE_CURVE('',#71870,#71795,#71897,.T.); -#71897 = SURFACE_CURVE('',#71898,(#71903,#71909),.PCURVE_S1.); -#71898 = CIRCLE('',#71899,0.254); -#71899 = AXIS2_PLACEMENT_3D('',#71900,#71901,#71902); -#71900 = CARTESIAN_POINT('',(0.8509,-0.254,-0.7239)); -#71901 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); -#71902 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); -#71903 = PCURVE('',#71810,#71904); -#71904 = DEFINITIONAL_REPRESENTATION('',(#71905),#71908); -#71905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#71906,#71907),.UNSPECIFIED., +#74272 = CARTESIAN_POINT('',(1.570796326795,2.1717)); +#74273 = CARTESIAN_POINT('',(1.570796326795,2.6289)); +#74274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74275 = PCURVE('',#74276,#74281); +#74276 = PLANE('',#74277); +#74277 = AXIS2_PLACEMENT_3D('',#74278,#74279,#74280); +#74278 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#74279 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#74280 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74281 = DEFINITIONAL_REPRESENTATION('',(#74282),#74286); +#74282 = LINE('',#74283,#74284); +#74283 = CARTESIAN_POINT('',(0.E+000,0.2032)); +#74284 = VECTOR('',#74285,1.); +#74285 = DIRECTION('',(1.,0.E+000)); +#74286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74287 = ORIENTED_EDGE('',*,*,#74288,.T.); +#74288 = EDGE_CURVE('',#74262,#74187,#74289,.T.); +#74289 = SURFACE_CURVE('',#74290,(#74295,#74301),.PCURVE_S1.); +#74290 = CIRCLE('',#74291,0.254); +#74291 = AXIS2_PLACEMENT_3D('',#74292,#74293,#74294); +#74292 = CARTESIAN_POINT('',(0.8509,-0.254,-0.7239)); +#74293 = DIRECTION('',(1.928281419412E-016,0.E+000,-1.)); +#74294 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); +#74295 = PCURVE('',#74202,#74296); +#74296 = DEFINITIONAL_REPRESENTATION('',(#74297),#74300); +#74297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74298,#74299),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#71906 = CARTESIAN_POINT('',(1.570796326795,2.1717)); -#71907 = CARTESIAN_POINT('',(3.14159265359,2.1717)); -#71908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71909 = PCURVE('',#71211,#71910); -#71910 = DEFINITIONAL_REPRESENTATION('',(#71911),#71915); -#71911 = CIRCLE('',#71912,0.254); -#71912 = AXIS2_PLACEMENT_2D('',#71913,#71914); -#71913 = CARTESIAN_POINT('',(-0.2032,0.26073610875)); -#71914 = DIRECTION('',(1.,0.E+000)); -#71915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71916 = ADVANCED_FACE('',(#71917),#71884,.F.); -#71917 = FACE_BOUND('',#71918,.T.); -#71918 = EDGE_LOOP('',(#71919,#71920,#71943,#71971)); -#71919 = ORIENTED_EDGE('',*,*,#71869,.T.); -#71920 = ORIENTED_EDGE('',*,*,#71921,.T.); -#71921 = EDGE_CURVE('',#71847,#71922,#71924,.T.); -#71922 = VERTEX_POINT('',#71923); -#71923 = CARTESIAN_POINT('',(0.6477,0.E+000,-1.1811)); -#71924 = SURFACE_CURVE('',#71925,(#71929,#71936),.PCURVE_S1.); -#71925 = LINE('',#71926,#71927); -#71926 = CARTESIAN_POINT('',(0.6477,0.E+000,-1.1811)); -#71927 = VECTOR('',#71928,1.); -#71928 = DIRECTION('',(-1.,0.E+000,3.856562838825E-016)); -#71929 = PCURVE('',#71884,#71930); -#71930 = DEFINITIONAL_REPRESENTATION('',(#71931),#71935); -#71931 = LINE('',#71932,#71933); -#71932 = CARTESIAN_POINT('',(2.6289,-9.992007221626E-016)); -#71933 = VECTOR('',#71934,1.); -#71934 = DIRECTION('',(-3.856562838825E-016,-1.)); -#71935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71936 = PCURVE('',#71268,#71937); -#71937 = DEFINITIONAL_REPRESENTATION('',(#71938),#71942); -#71938 = LINE('',#71939,#71940); -#71939 = CARTESIAN_POINT('',(-9.992007221626E-016,0.51473610875)); -#71940 = VECTOR('',#71941,1.); -#71941 = DIRECTION('',(-1.,0.E+000)); -#71942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71943 = ORIENTED_EDGE('',*,*,#71944,.F.); -#71944 = EDGE_CURVE('',#71945,#71922,#71947,.T.); -#71945 = VERTEX_POINT('',#71946); -#71946 = CARTESIAN_POINT('',(0.6477,0.E+000,-0.7239)); -#71947 = SURFACE_CURVE('',#71948,(#71952,#71959),.PCURVE_S1.); -#71948 = LINE('',#71949,#71950); -#71949 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#71950 = VECTOR('',#71951,1.); -#71951 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#71952 = PCURVE('',#71884,#71953); -#71953 = DEFINITIONAL_REPRESENTATION('',(#71954),#71958); -#71954 = LINE('',#71955,#71956); -#71955 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#71956 = VECTOR('',#71957,1.); -#71957 = DIRECTION('',(1.,0.E+000)); -#71958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71959 = PCURVE('',#71960,#71965); -#71960 = PLANE('',#71961); -#71961 = AXIS2_PLACEMENT_3D('',#71962,#71963,#71964); -#71962 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.4478)); -#71963 = DIRECTION('',(-0.994521895368,-0.104528463268,0.E+000)); -#71964 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); -#71965 = DEFINITIONAL_REPRESENTATION('',(#71966),#71970); -#71966 = LINE('',#71967,#71968); -#71967 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#71968 = VECTOR('',#71969,1.); -#71969 = DIRECTION('',(0.E+000,-1.)); -#71970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71971 = ORIENTED_EDGE('',*,*,#71972,.T.); -#71972 = EDGE_CURVE('',#71945,#71870,#71973,.T.); -#71973 = SURFACE_CURVE('',#71974,(#71978,#71985),.PCURVE_S1.); -#71974 = LINE('',#71975,#71976); -#71975 = CARTESIAN_POINT('',(0.6477,0.E+000,-0.7239)); -#71976 = VECTOR('',#71977,1.); -#71977 = DIRECTION('',(1.,0.E+000,1.928281419412E-016)); -#71978 = PCURVE('',#71884,#71979); -#71979 = DEFINITIONAL_REPRESENTATION('',(#71980),#71984); -#71980 = LINE('',#71981,#71982); -#71981 = CARTESIAN_POINT('',(2.1717,4.440892098501E-016)); -#71982 = VECTOR('',#71983,1.); -#71983 = DIRECTION('',(-1.928281419412E-016,1.)); -#71984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71985 = PCURVE('',#71211,#71986); -#71986 = DEFINITIONAL_REPRESENTATION('',(#71987),#71991); -#71987 = LINE('',#71988,#71989); -#71988 = CARTESIAN_POINT('',(-3.330669073875E-016,0.51473610875)); -#71989 = VECTOR('',#71990,1.); -#71990 = DIRECTION('',(-1.,0.E+000)); -#71991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#71992 = ADVANCED_FACE('',(#71993),#72007,.F.); -#71993 = FACE_BOUND('',#71994,.T.); -#71994 = EDGE_LOOP('',(#71995,#72030,#72058,#72086,#72114,#72142)); -#71995 = ORIENTED_EDGE('',*,*,#71996,.T.); -#71996 = EDGE_CURVE('',#71997,#71999,#72001,.T.); -#71997 = VERTEX_POINT('',#71998); -#71998 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.414053320556)); -#71999 = VERTEX_POINT('',#72000); -#72000 = CARTESIAN_POINT('',(-0.596976696061,0.4826,-1.414053320556)); -#72001 = SURFACE_CURVE('',#72002,(#72006,#72018),.PCURVE_S1.); -#72002 = LINE('',#72003,#72004); -#72003 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.4478)); -#72004 = VECTOR('',#72005,1.); -#72005 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72006 = PCURVE('',#72007,#72012); -#72007 = PLANE('',#72008); -#72008 = AXIS2_PLACEMENT_3D('',#72009,#72010,#72011); -#72009 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72010 = DIRECTION('',(0.994521895368,-0.104528463268,0.E+000)); -#72011 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); -#72012 = DEFINITIONAL_REPRESENTATION('',(#72013),#72017); -#72013 = LINE('',#72014,#72015); -#72014 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#72015 = VECTOR('',#72016,1.); -#72016 = DIRECTION('',(0.E+000,-1.)); -#72017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72018 = PCURVE('',#72019,#72024); -#72019 = PLANE('',#72020); -#72020 = AXIS2_PLACEMENT_3D('',#72021,#72022,#72023); -#72021 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.4478)); -#72022 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#72023 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72024 = DEFINITIONAL_REPRESENTATION('',(#72025),#72029); -#72025 = LINE('',#72026,#72027); -#72026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72027 = VECTOR('',#72028,1.); -#72028 = DIRECTION('',(1.,0.E+000)); -#72029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72030 = ORIENTED_EDGE('',*,*,#72031,.T.); -#72031 = EDGE_CURVE('',#71999,#72032,#72034,.T.); -#72032 = VERTEX_POINT('',#72033); -#72033 = CARTESIAN_POINT('',(-0.6477,-1.029992063861E-014,-1.4478)); -#72034 = SURFACE_CURVE('',#72035,(#72039,#72046),.PCURVE_S1.); -#72035 = LINE('',#72036,#72037); -#72036 = CARTESIAN_POINT('',(-0.626752322387,0.19930383928, +#74298 = CARTESIAN_POINT('',(1.570796326795,2.1717)); +#74299 = CARTESIAN_POINT('',(3.14159265359,2.1717)); +#74300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74301 = PCURVE('',#73603,#74302); +#74302 = DEFINITIONAL_REPRESENTATION('',(#74303),#74307); +#74303 = CIRCLE('',#74304,0.254); +#74304 = AXIS2_PLACEMENT_2D('',#74305,#74306); +#74305 = CARTESIAN_POINT('',(-0.2032,0.26073610875)); +#74306 = DIRECTION('',(1.,0.E+000)); +#74307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74308 = ADVANCED_FACE('',(#74309),#74276,.F.); +#74309 = FACE_BOUND('',#74310,.T.); +#74310 = EDGE_LOOP('',(#74311,#74312,#74335,#74363)); +#74311 = ORIENTED_EDGE('',*,*,#74261,.T.); +#74312 = ORIENTED_EDGE('',*,*,#74313,.T.); +#74313 = EDGE_CURVE('',#74239,#74314,#74316,.T.); +#74314 = VERTEX_POINT('',#74315); +#74315 = CARTESIAN_POINT('',(0.6477,0.E+000,-1.1811)); +#74316 = SURFACE_CURVE('',#74317,(#74321,#74328),.PCURVE_S1.); +#74317 = LINE('',#74318,#74319); +#74318 = CARTESIAN_POINT('',(0.6477,0.E+000,-1.1811)); +#74319 = VECTOR('',#74320,1.); +#74320 = DIRECTION('',(-1.,0.E+000,3.856562838825E-016)); +#74321 = PCURVE('',#74276,#74322); +#74322 = DEFINITIONAL_REPRESENTATION('',(#74323),#74327); +#74323 = LINE('',#74324,#74325); +#74324 = CARTESIAN_POINT('',(2.6289,-9.992007221626E-016)); +#74325 = VECTOR('',#74326,1.); +#74326 = DIRECTION('',(-3.856562838825E-016,-1.)); +#74327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74328 = PCURVE('',#73660,#74329); +#74329 = DEFINITIONAL_REPRESENTATION('',(#74330),#74334); +#74330 = LINE('',#74331,#74332); +#74331 = CARTESIAN_POINT('',(-9.992007221626E-016,0.51473610875)); +#74332 = VECTOR('',#74333,1.); +#74333 = DIRECTION('',(-1.,0.E+000)); +#74334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74335 = ORIENTED_EDGE('',*,*,#74336,.F.); +#74336 = EDGE_CURVE('',#74337,#74314,#74339,.T.); +#74337 = VERTEX_POINT('',#74338); +#74338 = CARTESIAN_POINT('',(0.6477,0.E+000,-0.7239)); +#74339 = SURFACE_CURVE('',#74340,(#74344,#74351),.PCURVE_S1.); +#74340 = LINE('',#74341,#74342); +#74341 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#74342 = VECTOR('',#74343,1.); +#74343 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74344 = PCURVE('',#74276,#74345); +#74345 = DEFINITIONAL_REPRESENTATION('',(#74346),#74350); +#74346 = LINE('',#74347,#74348); +#74347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74348 = VECTOR('',#74349,1.); +#74349 = DIRECTION('',(1.,0.E+000)); +#74350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74351 = PCURVE('',#74352,#74357); +#74352 = PLANE('',#74353); +#74353 = AXIS2_PLACEMENT_3D('',#74354,#74355,#74356); +#74354 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.4478)); +#74355 = DIRECTION('',(-0.994521895368,-0.104528463268,0.E+000)); +#74356 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); +#74357 = DEFINITIONAL_REPRESENTATION('',(#74358),#74362); +#74358 = LINE('',#74359,#74360); +#74359 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#74360 = VECTOR('',#74361,1.); +#74361 = DIRECTION('',(0.E+000,-1.)); +#74362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74363 = ORIENTED_EDGE('',*,*,#74364,.T.); +#74364 = EDGE_CURVE('',#74337,#74262,#74365,.T.); +#74365 = SURFACE_CURVE('',#74366,(#74370,#74377),.PCURVE_S1.); +#74366 = LINE('',#74367,#74368); +#74367 = CARTESIAN_POINT('',(0.6477,0.E+000,-0.7239)); +#74368 = VECTOR('',#74369,1.); +#74369 = DIRECTION('',(1.,0.E+000,1.928281419412E-016)); +#74370 = PCURVE('',#74276,#74371); +#74371 = DEFINITIONAL_REPRESENTATION('',(#74372),#74376); +#74372 = LINE('',#74373,#74374); +#74373 = CARTESIAN_POINT('',(2.1717,4.440892098501E-016)); +#74374 = VECTOR('',#74375,1.); +#74375 = DIRECTION('',(-1.928281419412E-016,1.)); +#74376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74377 = PCURVE('',#73603,#74378); +#74378 = DEFINITIONAL_REPRESENTATION('',(#74379),#74383); +#74379 = LINE('',#74380,#74381); +#74380 = CARTESIAN_POINT('',(-3.330669073875E-016,0.51473610875)); +#74381 = VECTOR('',#74382,1.); +#74382 = DIRECTION('',(-1.,0.E+000)); +#74383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74384 = ADVANCED_FACE('',(#74385),#74399,.F.); +#74385 = FACE_BOUND('',#74386,.T.); +#74386 = EDGE_LOOP('',(#74387,#74422,#74450,#74478,#74506,#74534)); +#74387 = ORIENTED_EDGE('',*,*,#74388,.T.); +#74388 = EDGE_CURVE('',#74389,#74391,#74393,.T.); +#74389 = VERTEX_POINT('',#74390); +#74390 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.414053320556)); +#74391 = VERTEX_POINT('',#74392); +#74392 = CARTESIAN_POINT('',(-0.596976696061,0.4826,-1.414053320556)); +#74393 = SURFACE_CURVE('',#74394,(#74398,#74410),.PCURVE_S1.); +#74394 = LINE('',#74395,#74396); +#74395 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.4478)); +#74396 = VECTOR('',#74397,1.); +#74397 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74398 = PCURVE('',#74399,#74404); +#74399 = PLANE('',#74400); +#74400 = AXIS2_PLACEMENT_3D('',#74401,#74402,#74403); +#74401 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74402 = DIRECTION('',(0.994521895368,-0.104528463268,0.E+000)); +#74403 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); +#74404 = DEFINITIONAL_REPRESENTATION('',(#74405),#74409); +#74405 = LINE('',#74406,#74407); +#74406 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#74407 = VECTOR('',#74408,1.); +#74408 = DIRECTION('',(0.E+000,-1.)); +#74409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74410 = PCURVE('',#74411,#74416); +#74411 = PLANE('',#74412); +#74412 = AXIS2_PLACEMENT_3D('',#74413,#74414,#74415); +#74413 = CARTESIAN_POINT('',(-0.596976696061,0.4826,1.4478)); +#74414 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#74415 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74416 = DEFINITIONAL_REPRESENTATION('',(#74417),#74421); +#74417 = LINE('',#74418,#74419); +#74418 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74419 = VECTOR('',#74420,1.); +#74420 = DIRECTION('',(1.,0.E+000)); +#74421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74422 = ORIENTED_EDGE('',*,*,#74423,.T.); +#74423 = EDGE_CURVE('',#74391,#74424,#74426,.T.); +#74424 = VERTEX_POINT('',#74425); +#74425 = CARTESIAN_POINT('',(-0.6477,-1.029992063861E-014,-1.4478)); +#74426 = SURFACE_CURVE('',#74427,(#74431,#74438),.PCURVE_S1.); +#74427 = LINE('',#74428,#74429); +#74428 = CARTESIAN_POINT('',(-0.626752322387,0.19930383928, -1.433863317911)); -#72037 = VECTOR('',#72038,1.); -#72038 = DIRECTION('',(-0.104276609233,-0.992125664297, +#74429 = VECTOR('',#74430,1.); +#74430 = DIRECTION('',(-0.104276609233,-0.992125664297, -6.93761847516E-002)); -#72039 = PCURVE('',#72007,#72040); -#72040 = DEFINITIONAL_REPRESENTATION('',(#72041),#72045); -#72041 = LINE('',#72042,#72043); -#72042 = CARTESIAN_POINT('',(0.200401660545,-2.881663317911)); -#72043 = VECTOR('',#72044,1.); -#72044 = DIRECTION('',(-0.997590569818,-6.93761847516E-002)); -#72045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72046 = PCURVE('',#72047,#72052); -#72047 = PLANE('',#72048); -#72048 = AXIS2_PLACEMENT_3D('',#72049,#72050,#72051); -#72049 = CARTESIAN_POINT('',(-0.762,0.4826,-1.414053320556)); -#72050 = DIRECTION('',(0.E+000,-6.975647374412E-002,0.99756405026)); -#72051 = DIRECTION('',(0.E+000,-0.99756405026,-6.975647374412E-002)); -#72052 = DEFINITIONAL_REPRESENTATION('',(#72053),#72057); -#72053 = LINE('',#72054,#72055); -#72054 = CARTESIAN_POINT('',(0.283987941071,0.135247677613)); -#72055 = VECTOR('',#72056,1.); -#72056 = DIRECTION('',(0.994548334053,-0.104276609233)); -#72057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72058 = ORIENTED_EDGE('',*,*,#72059,.T.); -#72059 = EDGE_CURVE('',#72032,#72060,#72062,.T.); -#72060 = VERTEX_POINT('',#72061); -#72061 = CARTESIAN_POINT('',(-0.6477,0.E+000,-0.2286)); -#72062 = SURFACE_CURVE('',#72063,(#72067,#72074),.PCURVE_S1.); -#72063 = LINE('',#72064,#72065); -#72064 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72065 = VECTOR('',#72066,1.); -#72066 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72067 = PCURVE('',#72007,#72068); -#72068 = DEFINITIONAL_REPRESENTATION('',(#72069),#72073); -#72069 = LINE('',#72070,#72071); -#72070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72071 = VECTOR('',#72072,1.); -#72072 = DIRECTION('',(0.E+000,1.)); -#72073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72074 = PCURVE('',#72075,#72080); -#72075 = PLANE('',#72076); -#72076 = AXIS2_PLACEMENT_3D('',#72077,#72078,#72079); -#72077 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,-1.4478)); -#72078 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72079 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72080 = DEFINITIONAL_REPRESENTATION('',(#72081),#72085); -#72081 = LINE('',#72082,#72083); -#72082 = CARTESIAN_POINT('',(-2.8956,0.51473610875)); -#72083 = VECTOR('',#72084,1.); -#72084 = DIRECTION('',(-1.,0.E+000)); -#72085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74431 = PCURVE('',#74399,#74432); +#74432 = DEFINITIONAL_REPRESENTATION('',(#74433),#74437); +#74433 = LINE('',#74434,#74435); +#74434 = CARTESIAN_POINT('',(0.200401660545,-2.881663317911)); +#74435 = VECTOR('',#74436,1.); +#74436 = DIRECTION('',(-0.997590569818,-6.93761847516E-002)); +#74437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74438 = PCURVE('',#74439,#74444); +#74439 = PLANE('',#74440); +#74440 = AXIS2_PLACEMENT_3D('',#74441,#74442,#74443); +#74441 = CARTESIAN_POINT('',(-0.762,0.4826,-1.414053320556)); +#74442 = DIRECTION('',(0.E+000,-6.975647374412E-002,0.99756405026)); +#74443 = DIRECTION('',(0.E+000,-0.99756405026,-6.975647374412E-002)); +#74444 = DEFINITIONAL_REPRESENTATION('',(#74445),#74449); +#74445 = LINE('',#74446,#74447); +#74446 = CARTESIAN_POINT('',(0.283987941071,0.135247677613)); +#74447 = VECTOR('',#74448,1.); +#74448 = DIRECTION('',(0.994548334053,-0.104276609233)); +#74449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74450 = ORIENTED_EDGE('',*,*,#74451,.T.); +#74451 = EDGE_CURVE('',#74424,#74452,#74454,.T.); +#74452 = VERTEX_POINT('',#74453); +#74453 = CARTESIAN_POINT('',(-0.6477,0.E+000,-0.2286)); +#74454 = SURFACE_CURVE('',#74455,(#74459,#74466),.PCURVE_S1.); +#74455 = LINE('',#74456,#74457); +#74456 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74457 = VECTOR('',#74458,1.); +#74458 = DIRECTION('',(0.E+000,0.E+000,1.)); +#74459 = PCURVE('',#74399,#74460); +#74460 = DEFINITIONAL_REPRESENTATION('',(#74461),#74465); +#74461 = LINE('',#74462,#74463); +#74462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74463 = VECTOR('',#74464,1.); +#74464 = DIRECTION('',(0.E+000,1.)); +#74465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72086 = ORIENTED_EDGE('',*,*,#72087,.F.); -#72087 = EDGE_CURVE('',#72088,#72060,#72090,.T.); -#72088 = VERTEX_POINT('',#72089); -#72089 = CARTESIAN_POINT('',(-0.6477,0.E+000,0.2286)); -#72090 = SURFACE_CURVE('',#72091,(#72095,#72102),.PCURVE_S1.); -#72091 = LINE('',#72092,#72093); -#72092 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72093 = VECTOR('',#72094,1.); -#72094 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72095 = PCURVE('',#72007,#72096); -#72096 = DEFINITIONAL_REPRESENTATION('',(#72097),#72101); -#72097 = LINE('',#72098,#72099); -#72098 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72099 = VECTOR('',#72100,1.); -#72100 = DIRECTION('',(0.E+000,-1.)); -#72101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72102 = PCURVE('',#72103,#72108); -#72103 = PLANE('',#72104); -#72104 = AXIS2_PLACEMENT_3D('',#72105,#72106,#72107); -#72105 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72106 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#72107 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72108 = DEFINITIONAL_REPRESENTATION('',(#72109),#72113); -#72109 = LINE('',#72110,#72111); -#72110 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72111 = VECTOR('',#72112,1.); -#72112 = DIRECTION('',(1.,0.E+000)); -#72113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72114 = ORIENTED_EDGE('',*,*,#72115,.F.); -#72115 = EDGE_CURVE('',#72116,#72088,#72118,.T.); -#72116 = VERTEX_POINT('',#72117); -#72117 = CARTESIAN_POINT('',(-0.6477,3.903127820948E-015,1.4478)); -#72118 = SURFACE_CURVE('',#72119,(#72123,#72130),.PCURVE_S1.); -#72119 = LINE('',#72120,#72121); -#72120 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72121 = VECTOR('',#72122,1.); -#72122 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72123 = PCURVE('',#72007,#72124); -#72124 = DEFINITIONAL_REPRESENTATION('',(#72125),#72129); -#72125 = LINE('',#72126,#72127); -#72126 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72127 = VECTOR('',#72128,1.); -#72128 = DIRECTION('',(0.E+000,-1.)); -#72129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72130 = PCURVE('',#72131,#72136); -#72131 = PLANE('',#72132); -#72132 = AXIS2_PLACEMENT_3D('',#72133,#72134,#72135); -#72133 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,1.4478)); -#72134 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72135 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72136 = DEFINITIONAL_REPRESENTATION('',(#72137),#72141); -#72137 = LINE('',#72138,#72139); -#72138 = CARTESIAN_POINT('',(0.E+000,0.51473610875)); -#72139 = VECTOR('',#72140,1.); -#72140 = DIRECTION('',(1.,0.E+000)); -#72141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72142 = ORIENTED_EDGE('',*,*,#72143,.T.); -#72143 = EDGE_CURVE('',#72116,#71997,#72144,.T.); -#72144 = SURFACE_CURVE('',#72145,(#72149,#72156),.PCURVE_S1.); -#72145 = LINE('',#72146,#72147); -#72146 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); -#72147 = VECTOR('',#72148,1.); -#72148 = DIRECTION('',(0.104276609233,0.992125664297,-6.93761847516E-002 - )); -#72149 = PCURVE('',#72007,#72150); -#72150 = DEFINITIONAL_REPRESENTATION('',(#72151),#72155); -#72151 = LINE('',#72152,#72153); -#72152 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72153 = VECTOR('',#72154,1.); -#72154 = DIRECTION('',(0.997590569818,-6.93761847516E-002)); -#72155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72156 = PCURVE('',#72157,#72162); -#72157 = PLANE('',#72158); -#72158 = AXIS2_PLACEMENT_3D('',#72159,#72160,#72161); -#72159 = CARTESIAN_POINT('',(-0.762,0.4826,1.414053320556)); -#72160 = DIRECTION('',(0.E+000,-6.975647374412E-002,-0.99756405026)); -#72161 = DIRECTION('',(0.E+000,0.99756405026,-6.975647374412E-002)); -#72162 = DEFINITIONAL_REPRESENTATION('',(#72163),#72167); -#72163 = LINE('',#72164,#72165); -#72164 = CARTESIAN_POINT('',(-0.483778460014,0.1143)); -#72165 = VECTOR('',#72166,1.); -#72166 = DIRECTION('',(0.994548334053,0.104276609233)); -#72167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72168 = ADVANCED_FACE('',(#72169),#72103,.F.); -#72169 = FACE_BOUND('',#72170,.T.); -#72170 = EDGE_LOOP('',(#72171,#72200,#72226,#72227)); -#72171 = ORIENTED_EDGE('',*,*,#72172,.F.); -#72172 = EDGE_CURVE('',#72173,#72175,#72177,.T.); -#72173 = VERTEX_POINT('',#72174); -#72174 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,0.2286)); -#72175 = VERTEX_POINT('',#72176); -#72176 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,-0.2286)); -#72177 = SURFACE_CURVE('',#72178,(#72182,#72189),.PCURVE_S1.); -#72178 = LINE('',#72179,#72180); -#72179 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,1.4478)); -#72180 = VECTOR('',#72181,1.); -#72181 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72182 = PCURVE('',#72103,#72183); -#72183 = DEFINITIONAL_REPRESENTATION('',(#72184),#72188); -#72184 = LINE('',#72185,#72186); -#72185 = CARTESIAN_POINT('',(0.E+000,-0.2032)); -#72186 = VECTOR('',#72187,1.); -#72187 = DIRECTION('',(1.,0.E+000)); -#72188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74466 = PCURVE('',#74467,#74472); +#74467 = PLANE('',#74468); +#74468 = AXIS2_PLACEMENT_3D('',#74469,#74470,#74471); +#74469 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,-1.4478)); +#74470 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74471 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74472 = DEFINITIONAL_REPRESENTATION('',(#74473),#74477); +#74473 = LINE('',#74474,#74475); +#74474 = CARTESIAN_POINT('',(-2.8956,0.51473610875)); +#74475 = VECTOR('',#74476,1.); +#74476 = DIRECTION('',(-1.,0.E+000)); +#74477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74478 = ORIENTED_EDGE('',*,*,#74479,.F.); +#74479 = EDGE_CURVE('',#74480,#74452,#74482,.T.); +#74480 = VERTEX_POINT('',#74481); +#74481 = CARTESIAN_POINT('',(-0.6477,0.E+000,0.2286)); +#74482 = SURFACE_CURVE('',#74483,(#74487,#74494),.PCURVE_S1.); +#74483 = LINE('',#74484,#74485); +#74484 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74485 = VECTOR('',#74486,1.); +#74486 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74487 = PCURVE('',#74399,#74488); +#74488 = DEFINITIONAL_REPRESENTATION('',(#74489),#74493); +#74489 = LINE('',#74490,#74491); +#74490 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74491 = VECTOR('',#74492,1.); +#74492 = DIRECTION('',(0.E+000,-1.)); +#74493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74494 = PCURVE('',#74495,#74500); +#74495 = PLANE('',#74496); +#74496 = AXIS2_PLACEMENT_3D('',#74497,#74498,#74499); +#74497 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74498 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#74499 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74500 = DEFINITIONAL_REPRESENTATION('',(#74501),#74505); +#74501 = LINE('',#74502,#74503); +#74502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74503 = VECTOR('',#74504,1.); +#74504 = DIRECTION('',(1.,0.E+000)); +#74505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74506 = ORIENTED_EDGE('',*,*,#74507,.F.); +#74507 = EDGE_CURVE('',#74508,#74480,#74510,.T.); +#74508 = VERTEX_POINT('',#74509); +#74509 = CARTESIAN_POINT('',(-0.6477,3.903127820948E-015,1.4478)); +#74510 = SURFACE_CURVE('',#74511,(#74515,#74522),.PCURVE_S1.); +#74511 = LINE('',#74512,#74513); +#74512 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74513 = VECTOR('',#74514,1.); +#74514 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74515 = PCURVE('',#74399,#74516); +#74516 = DEFINITIONAL_REPRESENTATION('',(#74517),#74521); +#74517 = LINE('',#74518,#74519); +#74518 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74519 = VECTOR('',#74520,1.); +#74520 = DIRECTION('',(0.E+000,-1.)); +#74521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74522 = PCURVE('',#74523,#74528); +#74523 = PLANE('',#74524); +#74524 = AXIS2_PLACEMENT_3D('',#74525,#74526,#74527); +#74525 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,1.4478)); +#74526 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74527 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74528 = DEFINITIONAL_REPRESENTATION('',(#74529),#74533); +#74529 = LINE('',#74530,#74531); +#74530 = CARTESIAN_POINT('',(0.E+000,0.51473610875)); +#74531 = VECTOR('',#74532,1.); +#74532 = DIRECTION('',(1.,0.E+000)); +#74533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72189 = PCURVE('',#72190,#72195); -#72190 = CYLINDRICAL_SURFACE('',#72191,0.254); -#72191 = AXIS2_PLACEMENT_3D('',#72192,#72193,#72194); -#72192 = CARTESIAN_POINT('',(-0.8509,-0.254,1.4478)); -#72193 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72194 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72195 = DEFINITIONAL_REPRESENTATION('',(#72196),#72199); -#72196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72197,#72198),.UNSPECIFIED., - .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72197 = CARTESIAN_POINT('',(1.570796326795,1.2192)); -#72198 = CARTESIAN_POINT('',(1.570796326795,1.6764)); -#72199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72200 = ORIENTED_EDGE('',*,*,#72201,.T.); -#72201 = EDGE_CURVE('',#72173,#72088,#72202,.T.); -#72202 = SURFACE_CURVE('',#72203,(#72207,#72214),.PCURVE_S1.); -#72203 = LINE('',#72204,#72205); -#72204 = CARTESIAN_POINT('',(-0.6477,0.E+000,0.2286)); -#72205 = VECTOR('',#72206,1.); -#72206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72207 = PCURVE('',#72103,#72208); -#72208 = DEFINITIONAL_REPRESENTATION('',(#72209),#72213); -#72209 = LINE('',#72210,#72211); -#72210 = CARTESIAN_POINT('',(1.2192,0.E+000)); -#72211 = VECTOR('',#72212,1.); -#72212 = DIRECTION('',(0.E+000,1.)); -#72213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72214 = PCURVE('',#72215,#72220); -#72215 = PLANE('',#72216); -#72216 = AXIS2_PLACEMENT_3D('',#72217,#72218,#72219); -#72217 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); -#72218 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72219 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72220 = DEFINITIONAL_REPRESENTATION('',(#72221),#72225); -#72221 = LINE('',#72222,#72223); -#72222 = CARTESIAN_POINT('',(-0.562263454686,0.51473610875)); -#72223 = VECTOR('',#72224,1.); -#72224 = DIRECTION('',(-1.,0.E+000)); -#72225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72226 = ORIENTED_EDGE('',*,*,#72087,.T.); -#72227 = ORIENTED_EDGE('',*,*,#72228,.T.); -#72228 = EDGE_CURVE('',#72060,#72175,#72229,.T.); -#72229 = SURFACE_CURVE('',#72230,(#72234,#72241),.PCURVE_S1.); -#72230 = LINE('',#72231,#72232); -#72231 = CARTESIAN_POINT('',(-0.6477,0.E+000,-0.2286)); -#72232 = VECTOR('',#72233,1.); -#72233 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72234 = PCURVE('',#72103,#72235); -#72235 = DEFINITIONAL_REPRESENTATION('',(#72236),#72240); -#72236 = LINE('',#72237,#72238); -#72237 = CARTESIAN_POINT('',(1.6764,0.E+000)); -#72238 = VECTOR('',#72239,1.); -#72239 = DIRECTION('',(0.E+000,-1.)); -#72240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72241 = PCURVE('',#72242,#72247); -#72242 = PLANE('',#72243); -#72243 = AXIS2_PLACEMENT_3D('',#72244,#72245,#72246); -#72244 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); -#72245 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72246 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72247 = DEFINITIONAL_REPRESENTATION('',(#72248),#72252); -#72248 = LINE('',#72249,#72250); -#72249 = CARTESIAN_POINT('',(0.562263454686,0.51473610875)); -#72250 = VECTOR('',#72251,1.); -#72251 = DIRECTION('',(-1.,0.E+000)); -#72252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72253 = ADVANCED_FACE('',(#72254),#72190,.T.); -#72254 = FACE_BOUND('',#72255,.T.); -#72255 = EDGE_LOOP('',(#72256,#72285,#72306,#72307)); -#72256 = ORIENTED_EDGE('',*,*,#72257,.F.); -#72257 = EDGE_CURVE('',#72258,#72260,#72262,.T.); -#72258 = VERTEX_POINT('',#72259); -#72259 = CARTESIAN_POINT('',(-1.1049,-0.254,0.2286)); -#72260 = VERTEX_POINT('',#72261); -#72261 = CARTESIAN_POINT('',(-1.1049,-0.254,-0.2286)); -#72262 = SURFACE_CURVE('',#72263,(#72267,#72273),.PCURVE_S1.); -#72263 = LINE('',#72264,#72265); -#72264 = CARTESIAN_POINT('',(-1.1049,-0.254,1.4478)); -#72265 = VECTOR('',#72266,1.); -#72266 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72267 = PCURVE('',#72190,#72268); -#72268 = DEFINITIONAL_REPRESENTATION('',(#72269),#72272); -#72269 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72270,#72271),.UNSPECIFIED., - .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72270 = CARTESIAN_POINT('',(0.E+000,1.2192)); -#72271 = CARTESIAN_POINT('',(0.E+000,1.6764)); -#72272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72273 = PCURVE('',#72274,#72279); -#72274 = PLANE('',#72275); -#72275 = AXIS2_PLACEMENT_3D('',#72276,#72277,#72278); -#72276 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,1.4478)); -#72277 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72278 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72279 = DEFINITIONAL_REPRESENTATION('',(#72280),#72284); -#72280 = LINE('',#72281,#72282); -#72281 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); -#72282 = VECTOR('',#72283,1.); -#72283 = DIRECTION('',(1.,0.E+000)); -#72284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72285 = ORIENTED_EDGE('',*,*,#72286,.T.); -#72286 = EDGE_CURVE('',#72258,#72173,#72287,.T.); -#72287 = SURFACE_CURVE('',#72288,(#72293,#72299),.PCURVE_S1.); -#72288 = CIRCLE('',#72289,0.254); -#72289 = AXIS2_PLACEMENT_3D('',#72290,#72291,#72292); -#72290 = CARTESIAN_POINT('',(-0.8509,-0.254,0.2286)); -#72291 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72292 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72293 = PCURVE('',#72190,#72294); -#72294 = DEFINITIONAL_REPRESENTATION('',(#72295),#72298); -#72295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72296,#72297),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#72296 = CARTESIAN_POINT('',(0.E+000,1.2192)); -#72297 = CARTESIAN_POINT('',(1.570796326795,1.2192)); -#72298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74534 = ORIENTED_EDGE('',*,*,#74535,.T.); +#74535 = EDGE_CURVE('',#74508,#74389,#74536,.T.); +#74536 = SURFACE_CURVE('',#74537,(#74541,#74548),.PCURVE_S1.); +#74537 = LINE('',#74538,#74539); +#74538 = CARTESIAN_POINT('',(-0.6477,0.E+000,1.4478)); +#74539 = VECTOR('',#74540,1.); +#74540 = DIRECTION('',(0.104276609233,0.992125664297,-6.93761847516E-002 + )); +#74541 = PCURVE('',#74399,#74542); +#74542 = DEFINITIONAL_REPRESENTATION('',(#74543),#74547); +#74543 = LINE('',#74544,#74545); +#74544 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74545 = VECTOR('',#74546,1.); +#74546 = DIRECTION('',(0.997590569818,-6.93761847516E-002)); +#74547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72299 = PCURVE('',#72215,#72300); -#72300 = DEFINITIONAL_REPRESENTATION('',(#72301),#72305); -#72301 = CIRCLE('',#72302,0.254); -#72302 = AXIS2_PLACEMENT_2D('',#72303,#72304); -#72303 = CARTESIAN_POINT('',(-0.359063454686,0.26073610875)); -#72304 = DIRECTION('',(1.,0.E+000)); -#72305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74548 = PCURVE('',#74549,#74554); +#74549 = PLANE('',#74550); +#74550 = AXIS2_PLACEMENT_3D('',#74551,#74552,#74553); +#74551 = CARTESIAN_POINT('',(-0.762,0.4826,1.414053320556)); +#74552 = DIRECTION('',(0.E+000,-6.975647374412E-002,-0.99756405026)); +#74553 = DIRECTION('',(0.E+000,0.99756405026,-6.975647374412E-002)); +#74554 = DEFINITIONAL_REPRESENTATION('',(#74555),#74559); +#74555 = LINE('',#74556,#74557); +#74556 = CARTESIAN_POINT('',(-0.483778460014,0.1143)); +#74557 = VECTOR('',#74558,1.); +#74558 = DIRECTION('',(0.994548334053,0.104276609233)); +#74559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74560 = ADVANCED_FACE('',(#74561),#74495,.F.); +#74561 = FACE_BOUND('',#74562,.T.); +#74562 = EDGE_LOOP('',(#74563,#74592,#74618,#74619)); +#74563 = ORIENTED_EDGE('',*,*,#74564,.F.); +#74564 = EDGE_CURVE('',#74565,#74567,#74569,.T.); +#74565 = VERTEX_POINT('',#74566); +#74566 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,0.2286)); +#74567 = VERTEX_POINT('',#74568); +#74568 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,-0.2286)); +#74569 = SURFACE_CURVE('',#74570,(#74574,#74581),.PCURVE_S1.); +#74570 = LINE('',#74571,#74572); +#74571 = CARTESIAN_POINT('',(-0.8509,-5.421010862428E-017,1.4478)); +#74572 = VECTOR('',#74573,1.); +#74573 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74574 = PCURVE('',#74495,#74575); +#74575 = DEFINITIONAL_REPRESENTATION('',(#74576),#74580); +#74576 = LINE('',#74577,#74578); +#74577 = CARTESIAN_POINT('',(0.E+000,-0.2032)); +#74578 = VECTOR('',#74579,1.); +#74579 = DIRECTION('',(1.,0.E+000)); +#74580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72306 = ORIENTED_EDGE('',*,*,#72172,.T.); -#72307 = ORIENTED_EDGE('',*,*,#72308,.T.); -#72308 = EDGE_CURVE('',#72175,#72260,#72309,.T.); -#72309 = SURFACE_CURVE('',#72310,(#72315,#72321),.PCURVE_S1.); -#72310 = CIRCLE('',#72311,0.254); -#72311 = AXIS2_PLACEMENT_3D('',#72312,#72313,#72314); -#72312 = CARTESIAN_POINT('',(-0.8509,-0.254,-0.2286)); -#72313 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72314 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72315 = PCURVE('',#72190,#72316); -#72316 = DEFINITIONAL_REPRESENTATION('',(#72317),#72320); -#72317 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72318,#72319),.UNSPECIFIED., +#74581 = PCURVE('',#74582,#74587); +#74582 = CYLINDRICAL_SURFACE('',#74583,0.254); +#74583 = AXIS2_PLACEMENT_3D('',#74584,#74585,#74586); +#74584 = CARTESIAN_POINT('',(-0.8509,-0.254,1.4478)); +#74585 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74586 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74587 = DEFINITIONAL_REPRESENTATION('',(#74588),#74591); +#74588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74589,#74590),.UNSPECIFIED., + .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); +#74589 = CARTESIAN_POINT('',(1.570796326795,1.2192)); +#74590 = CARTESIAN_POINT('',(1.570796326795,1.6764)); +#74591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74592 = ORIENTED_EDGE('',*,*,#74593,.T.); +#74593 = EDGE_CURVE('',#74565,#74480,#74594,.T.); +#74594 = SURFACE_CURVE('',#74595,(#74599,#74606),.PCURVE_S1.); +#74595 = LINE('',#74596,#74597); +#74596 = CARTESIAN_POINT('',(-0.6477,0.E+000,0.2286)); +#74597 = VECTOR('',#74598,1.); +#74598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74599 = PCURVE('',#74495,#74600); +#74600 = DEFINITIONAL_REPRESENTATION('',(#74601),#74605); +#74601 = LINE('',#74602,#74603); +#74602 = CARTESIAN_POINT('',(1.2192,0.E+000)); +#74603 = VECTOR('',#74604,1.); +#74604 = DIRECTION('',(0.E+000,1.)); +#74605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74606 = PCURVE('',#74607,#74612); +#74607 = PLANE('',#74608); +#74608 = AXIS2_PLACEMENT_3D('',#74609,#74610,#74611); +#74609 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); +#74610 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74611 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74612 = DEFINITIONAL_REPRESENTATION('',(#74613),#74617); +#74613 = LINE('',#74614,#74615); +#74614 = CARTESIAN_POINT('',(-0.562263454686,0.51473610875)); +#74615 = VECTOR('',#74616,1.); +#74616 = DIRECTION('',(-1.,0.E+000)); +#74617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74618 = ORIENTED_EDGE('',*,*,#74479,.T.); +#74619 = ORIENTED_EDGE('',*,*,#74620,.T.); +#74620 = EDGE_CURVE('',#74452,#74567,#74621,.T.); +#74621 = SURFACE_CURVE('',#74622,(#74626,#74633),.PCURVE_S1.); +#74622 = LINE('',#74623,#74624); +#74623 = CARTESIAN_POINT('',(-0.6477,0.E+000,-0.2286)); +#74624 = VECTOR('',#74625,1.); +#74625 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74626 = PCURVE('',#74495,#74627); +#74627 = DEFINITIONAL_REPRESENTATION('',(#74628),#74632); +#74628 = LINE('',#74629,#74630); +#74629 = CARTESIAN_POINT('',(1.6764,0.E+000)); +#74630 = VECTOR('',#74631,1.); +#74631 = DIRECTION('',(0.E+000,-1.)); +#74632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74633 = PCURVE('',#74634,#74639); +#74634 = PLANE('',#74635); +#74635 = AXIS2_PLACEMENT_3D('',#74636,#74637,#74638); +#74636 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); +#74637 = DIRECTION('',(0.E+000,0.E+000,1.)); +#74638 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74639 = DEFINITIONAL_REPRESENTATION('',(#74640),#74644); +#74640 = LINE('',#74641,#74642); +#74641 = CARTESIAN_POINT('',(0.562263454686,0.51473610875)); +#74642 = VECTOR('',#74643,1.); +#74643 = DIRECTION('',(-1.,0.E+000)); +#74644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74645 = ADVANCED_FACE('',(#74646),#74582,.T.); +#74646 = FACE_BOUND('',#74647,.T.); +#74647 = EDGE_LOOP('',(#74648,#74677,#74698,#74699)); +#74648 = ORIENTED_EDGE('',*,*,#74649,.F.); +#74649 = EDGE_CURVE('',#74650,#74652,#74654,.T.); +#74650 = VERTEX_POINT('',#74651); +#74651 = CARTESIAN_POINT('',(-1.1049,-0.254,0.2286)); +#74652 = VERTEX_POINT('',#74653); +#74653 = CARTESIAN_POINT('',(-1.1049,-0.254,-0.2286)); +#74654 = SURFACE_CURVE('',#74655,(#74659,#74665),.PCURVE_S1.); +#74655 = LINE('',#74656,#74657); +#74656 = CARTESIAN_POINT('',(-1.1049,-0.254,1.4478)); +#74657 = VECTOR('',#74658,1.); +#74658 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74659 = PCURVE('',#74582,#74660); +#74660 = DEFINITIONAL_REPRESENTATION('',(#74661),#74664); +#74661 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74662,#74663),.UNSPECIFIED., + .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); +#74662 = CARTESIAN_POINT('',(0.E+000,1.2192)); +#74663 = CARTESIAN_POINT('',(0.E+000,1.6764)); +#74664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74665 = PCURVE('',#74666,#74671); +#74666 = PLANE('',#74667); +#74667 = AXIS2_PLACEMENT_3D('',#74668,#74669,#74670); +#74668 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,1.4478)); +#74669 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74670 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74671 = DEFINITIONAL_REPRESENTATION('',(#74672),#74676); +#74672 = LINE('',#74673,#74674); +#74673 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); +#74674 = VECTOR('',#74675,1.); +#74675 = DIRECTION('',(1.,0.E+000)); +#74676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74677 = ORIENTED_EDGE('',*,*,#74678,.T.); +#74678 = EDGE_CURVE('',#74650,#74565,#74679,.T.); +#74679 = SURFACE_CURVE('',#74680,(#74685,#74691),.PCURVE_S1.); +#74680 = CIRCLE('',#74681,0.254); +#74681 = AXIS2_PLACEMENT_3D('',#74682,#74683,#74684); +#74682 = CARTESIAN_POINT('',(-0.8509,-0.254,0.2286)); +#74683 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74684 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74685 = PCURVE('',#74582,#74686); +#74686 = DEFINITIONAL_REPRESENTATION('',(#74687),#74690); +#74687 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74688,#74689),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); +#74688 = CARTESIAN_POINT('',(0.E+000,1.2192)); +#74689 = CARTESIAN_POINT('',(1.570796326795,1.2192)); +#74690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74691 = PCURVE('',#74607,#74692); +#74692 = DEFINITIONAL_REPRESENTATION('',(#74693),#74697); +#74693 = CIRCLE('',#74694,0.254); +#74694 = AXIS2_PLACEMENT_2D('',#74695,#74696); +#74695 = CARTESIAN_POINT('',(-0.359063454686,0.26073610875)); +#74696 = DIRECTION('',(1.,0.E+000)); +#74697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74698 = ORIENTED_EDGE('',*,*,#74564,.T.); +#74699 = ORIENTED_EDGE('',*,*,#74700,.T.); +#74700 = EDGE_CURVE('',#74567,#74652,#74701,.T.); +#74701 = SURFACE_CURVE('',#74702,(#74707,#74713),.PCURVE_S1.); +#74702 = CIRCLE('',#74703,0.254); +#74703 = AXIS2_PLACEMENT_3D('',#74704,#74705,#74706); +#74704 = CARTESIAN_POINT('',(-0.8509,-0.254,-0.2286)); +#74705 = DIRECTION('',(0.E+000,0.E+000,1.)); +#74706 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74707 = PCURVE('',#74582,#74708); +#74708 = DEFINITIONAL_REPRESENTATION('',(#74709),#74712); +#74709 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74710,#74711),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#72318 = CARTESIAN_POINT('',(1.570796326795,1.6764)); -#72319 = CARTESIAN_POINT('',(0.E+000,1.6764)); -#72320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72321 = PCURVE('',#72242,#72322); -#72322 = DEFINITIONAL_REPRESENTATION('',(#72323),#72327); -#72323 = CIRCLE('',#72324,0.254); -#72324 = AXIS2_PLACEMENT_2D('',#72325,#72326); -#72325 = CARTESIAN_POINT('',(0.359063454686,0.26073610875)); -#72326 = DIRECTION('',(1.,0.E+000)); -#72327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72328 = ADVANCED_FACE('',(#72329),#72274,.F.); -#72329 = FACE_BOUND('',#72330,.T.); -#72330 = EDGE_LOOP('',(#72331,#72360,#72381,#72382)); -#72331 = ORIENTED_EDGE('',*,*,#72332,.F.); -#72332 = EDGE_CURVE('',#72333,#72335,#72337,.T.); -#72333 = VERTEX_POINT('',#72334); -#72334 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,0.2286)); -#72335 = VERTEX_POINT('',#72336); -#72336 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,-0.2286)); -#72337 = SURFACE_CURVE('',#72338,(#72342,#72349),.PCURVE_S1.); -#72338 = LINE('',#72339,#72340); -#72339 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,1.4478)); -#72340 = VECTOR('',#72341,1.); -#72341 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72342 = PCURVE('',#72274,#72343); -#72343 = DEFINITIONAL_REPRESENTATION('',(#72344),#72348); -#72344 = LINE('',#72345,#72346); -#72345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72346 = VECTOR('',#72347,1.); -#72347 = DIRECTION('',(1.,0.E+000)); -#72348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72349 = PCURVE('',#72350,#72355); -#72350 = CYLINDRICAL_SURFACE('',#72351,5.253172734297E-002); -#72351 = AXIS2_PLACEMENT_3D('',#72352,#72353,#72354); -#72352 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,1.4478)); -#72353 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72354 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72355 = DEFINITIONAL_REPRESENTATION('',(#72356),#72359); -#72356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72357,#72358),.UNSPECIFIED., +#74710 = CARTESIAN_POINT('',(1.570796326795,1.6764)); +#74711 = CARTESIAN_POINT('',(0.E+000,1.6764)); +#74712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74713 = PCURVE('',#74634,#74714); +#74714 = DEFINITIONAL_REPRESENTATION('',(#74715),#74719); +#74715 = CIRCLE('',#74716,0.254); +#74716 = AXIS2_PLACEMENT_2D('',#74717,#74718); +#74717 = CARTESIAN_POINT('',(0.359063454686,0.26073610875)); +#74718 = DIRECTION('',(1.,0.E+000)); +#74719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74720 = ADVANCED_FACE('',(#74721),#74666,.F.); +#74721 = FACE_BOUND('',#74722,.T.); +#74722 = EDGE_LOOP('',(#74723,#74752,#74773,#74774)); +#74723 = ORIENTED_EDGE('',*,*,#74724,.F.); +#74724 = EDGE_CURVE('',#74725,#74727,#74729,.T.); +#74725 = VERTEX_POINT('',#74726); +#74726 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,0.2286)); +#74727 = VERTEX_POINT('',#74728); +#74728 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,-0.2286)); +#74729 = SURFACE_CURVE('',#74730,(#74734,#74741),.PCURVE_S1.); +#74730 = LINE('',#74731,#74732); +#74731 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,1.4478)); +#74732 = VECTOR('',#74733,1.); +#74733 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74734 = PCURVE('',#74666,#74735); +#74735 = DEFINITIONAL_REPRESENTATION('',(#74736),#74740); +#74736 = LINE('',#74737,#74738); +#74737 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74738 = VECTOR('',#74739,1.); +#74739 = DIRECTION('',(1.,0.E+000)); +#74740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74741 = PCURVE('',#74742,#74747); +#74742 = CYLINDRICAL_SURFACE('',#74743,5.253172734297E-002); +#74743 = AXIS2_PLACEMENT_3D('',#74744,#74745,#74746); +#74744 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,1.4478)); +#74745 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74746 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#74747 = DEFINITIONAL_REPRESENTATION('',(#74748),#74751); +#74748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74749,#74750),.UNSPECIFIED., .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72357 = CARTESIAN_POINT('',(3.14159265359,1.2192)); -#72358 = CARTESIAN_POINT('',(3.14159265359,1.6764)); -#72359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72360 = ORIENTED_EDGE('',*,*,#72361,.T.); -#72361 = EDGE_CURVE('',#72333,#72258,#72362,.T.); -#72362 = SURFACE_CURVE('',#72363,(#72367,#72374),.PCURVE_S1.); -#72363 = LINE('',#72364,#72365); -#72364 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,0.2286)); -#72365 = VECTOR('',#72366,1.); -#72366 = DIRECTION('',(0.E+000,1.,0.E+000)); -#72367 = PCURVE('',#72274,#72368); -#72368 = DEFINITIONAL_REPRESENTATION('',(#72369),#72373); -#72369 = LINE('',#72370,#72371); -#72370 = CARTESIAN_POINT('',(1.2192,0.E+000)); -#72371 = VECTOR('',#72372,1.); -#72372 = DIRECTION('',(0.E+000,1.)); -#72373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72374 = PCURVE('',#72215,#72375); -#72375 = DEFINITIONAL_REPRESENTATION('',(#72376),#72380); -#72376 = LINE('',#72377,#72378); -#72377 = CARTESIAN_POINT('',(-0.105063454686,0.196615825673)); -#72378 = VECTOR('',#72379,1.); -#72379 = DIRECTION('',(0.E+000,1.)); -#72380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72381 = ORIENTED_EDGE('',*,*,#72257,.T.); -#72382 = ORIENTED_EDGE('',*,*,#72383,.T.); -#72383 = EDGE_CURVE('',#72260,#72335,#72384,.T.); -#72384 = SURFACE_CURVE('',#72385,(#72389,#72396),.PCURVE_S1.); -#72385 = LINE('',#72386,#72387); -#72386 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,-0.2286)); -#72387 = VECTOR('',#72388,1.); -#72388 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#72389 = PCURVE('',#72274,#72390); -#72390 = DEFINITIONAL_REPRESENTATION('',(#72391),#72395); -#72391 = LINE('',#72392,#72393); -#72392 = CARTESIAN_POINT('',(1.6764,0.E+000)); -#72393 = VECTOR('',#72394,1.); -#72394 = DIRECTION('',(0.E+000,-1.)); -#72395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72396 = PCURVE('',#72242,#72397); -#72397 = DEFINITIONAL_REPRESENTATION('',(#72398),#72402); -#72398 = LINE('',#72399,#72400); -#72399 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); -#72400 = VECTOR('',#72401,1.); -#72401 = DIRECTION('',(0.E+000,-1.)); -#72402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72403 = ADVANCED_FACE('',(#72404),#72350,.F.); -#72404 = FACE_BOUND('',#72405,.F.); -#72405 = EDGE_LOOP('',(#72406,#72435,#72460,#72461)); -#72406 = ORIENTED_EDGE('',*,*,#72407,.T.); -#72407 = EDGE_CURVE('',#72408,#72410,#72412,.T.); -#72408 = VERTEX_POINT('',#72409); -#72409 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,0.2286)); -#72410 = VERTEX_POINT('',#72411); -#72411 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,-0.2286)); -#72412 = SURFACE_CURVE('',#72413,(#72417,#72423),.PCURVE_S1.); -#72413 = LINE('',#72414,#72415); -#72414 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,1.4478)); -#72415 = VECTOR('',#72416,1.); -#72416 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72417 = PCURVE('',#72350,#72418); -#72418 = DEFINITIONAL_REPRESENTATION('',(#72419),#72422); -#72419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72420,#72421),.UNSPECIFIED., +#74749 = CARTESIAN_POINT('',(3.14159265359,1.2192)); +#74750 = CARTESIAN_POINT('',(3.14159265359,1.6764)); +#74751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74752 = ORIENTED_EDGE('',*,*,#74753,.T.); +#74753 = EDGE_CURVE('',#74725,#74650,#74754,.T.); +#74754 = SURFACE_CURVE('',#74755,(#74759,#74766),.PCURVE_S1.); +#74755 = LINE('',#74756,#74757); +#74756 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,0.2286)); +#74757 = VECTOR('',#74758,1.); +#74758 = DIRECTION('',(0.E+000,1.,0.E+000)); +#74759 = PCURVE('',#74666,#74760); +#74760 = DEFINITIONAL_REPRESENTATION('',(#74761),#74765); +#74761 = LINE('',#74762,#74763); +#74762 = CARTESIAN_POINT('',(1.2192,0.E+000)); +#74763 = VECTOR('',#74764,1.); +#74764 = DIRECTION('',(0.E+000,1.)); +#74765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74766 = PCURVE('',#74607,#74767); +#74767 = DEFINITIONAL_REPRESENTATION('',(#74768),#74772); +#74768 = LINE('',#74769,#74770); +#74769 = CARTESIAN_POINT('',(-0.105063454686,0.196615825673)); +#74770 = VECTOR('',#74771,1.); +#74771 = DIRECTION('',(0.E+000,1.)); +#74772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74773 = ORIENTED_EDGE('',*,*,#74649,.T.); +#74774 = ORIENTED_EDGE('',*,*,#74775,.T.); +#74775 = EDGE_CURVE('',#74652,#74727,#74776,.T.); +#74776 = SURFACE_CURVE('',#74777,(#74781,#74788),.PCURVE_S1.); +#74777 = LINE('',#74778,#74779); +#74778 = CARTESIAN_POINT('',(-1.1049,-0.318120283077,-0.2286)); +#74779 = VECTOR('',#74780,1.); +#74780 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#74781 = PCURVE('',#74666,#74782); +#74782 = DEFINITIONAL_REPRESENTATION('',(#74783),#74787); +#74783 = LINE('',#74784,#74785); +#74784 = CARTESIAN_POINT('',(1.6764,0.E+000)); +#74785 = VECTOR('',#74786,1.); +#74786 = DIRECTION('',(0.E+000,-1.)); +#74787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74788 = PCURVE('',#74634,#74789); +#74789 = DEFINITIONAL_REPRESENTATION('',(#74790),#74794); +#74790 = LINE('',#74791,#74792); +#74791 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); +#74792 = VECTOR('',#74793,1.); +#74793 = DIRECTION('',(0.E+000,-1.)); +#74794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74795 = ADVANCED_FACE('',(#74796),#74742,.F.); +#74796 = FACE_BOUND('',#74797,.F.); +#74797 = EDGE_LOOP('',(#74798,#74827,#74852,#74853)); +#74798 = ORIENTED_EDGE('',*,*,#74799,.T.); +#74799 = EDGE_CURVE('',#74800,#74802,#74804,.T.); +#74800 = VERTEX_POINT('',#74801); +#74801 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,0.2286)); +#74802 = VERTEX_POINT('',#74803); +#74803 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,-0.2286)); +#74804 = SURFACE_CURVE('',#74805,(#74809,#74815),.PCURVE_S1.); +#74805 = LINE('',#74806,#74807); +#74806 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,1.4478)); +#74807 = VECTOR('',#74808,1.); +#74808 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74809 = PCURVE('',#74742,#74810); +#74810 = DEFINITIONAL_REPRESENTATION('',(#74811),#74814); +#74811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74812,#74813),.UNSPECIFIED., .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72420 = CARTESIAN_POINT('',(4.483114246145,1.2192)); -#72421 = CARTESIAN_POINT('',(4.483114246145,1.6764)); -#72422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72423 = PCURVE('',#72424,#72429); -#72424 = PLANE('',#72425); -#72425 = AXIS2_PLACEMENT_3D('',#72426,#72427,#72428); -#72426 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,1.4478)); -#72427 = DIRECTION('',(0.22727129674,-0.973831483203,0.E+000)); -#72428 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); -#72429 = DEFINITIONAL_REPRESENTATION('',(#72430),#72434); -#72430 = LINE('',#72431,#72432); -#72431 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72432 = VECTOR('',#72433,1.); -#72433 = DIRECTION('',(0.E+000,-1.)); -#72434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72435 = ORIENTED_EDGE('',*,*,#72436,.F.); -#72436 = EDGE_CURVE('',#72335,#72410,#72437,.T.); -#72437 = SURFACE_CURVE('',#72438,(#72443,#72449),.PCURVE_S1.); -#72438 = CIRCLE('',#72439,5.253172734297E-002); -#72439 = AXIS2_PLACEMENT_3D('',#72440,#72441,#72442); -#72440 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,-0.2286)); -#72441 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72442 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72443 = PCURVE('',#72350,#72444); -#72444 = DEFINITIONAL_REPRESENTATION('',(#72445),#72448); -#72445 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72446,#72447),.UNSPECIFIED., +#74812 = CARTESIAN_POINT('',(4.483114246145,1.2192)); +#74813 = CARTESIAN_POINT('',(4.483114246145,1.6764)); +#74814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74815 = PCURVE('',#74816,#74821); +#74816 = PLANE('',#74817); +#74817 = AXIS2_PLACEMENT_3D('',#74818,#74819,#74820); +#74818 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,1.4478)); +#74819 = DIRECTION('',(0.22727129674,-0.973831483203,0.E+000)); +#74820 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); +#74821 = DEFINITIONAL_REPRESENTATION('',(#74822),#74826); +#74822 = LINE('',#74823,#74824); +#74823 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74824 = VECTOR('',#74825,1.); +#74825 = DIRECTION('',(0.E+000,-1.)); +#74826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74827 = ORIENTED_EDGE('',*,*,#74828,.F.); +#74828 = EDGE_CURVE('',#74727,#74802,#74829,.T.); +#74829 = SURFACE_CURVE('',#74830,(#74835,#74841),.PCURVE_S1.); +#74830 = CIRCLE('',#74831,5.253172734297E-002); +#74831 = AXIS2_PLACEMENT_3D('',#74832,#74833,#74834); +#74832 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,-0.2286)); +#74833 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74834 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74835 = PCURVE('',#74742,#74836); +#74836 = DEFINITIONAL_REPRESENTATION('',(#74837),#74840); +#74837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74838,#74839),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.341521592555),.PIECEWISE_BEZIER_KNOTS.); -#72446 = CARTESIAN_POINT('',(3.14159265359,1.6764)); -#72447 = CARTESIAN_POINT('',(4.483114246145,1.6764)); -#72448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74838 = CARTESIAN_POINT('',(3.14159265359,1.6764)); +#74839 = CARTESIAN_POINT('',(4.483114246145,1.6764)); +#74840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72449 = PCURVE('',#72242,#72450); -#72450 = DEFINITIONAL_REPRESENTATION('',(#72451),#72459); -#72451 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#72452,#72453,#72454,#72455 - ,#72456,#72457,#72458),.UNSPECIFIED.,.T.,.F.) +#74841 = PCURVE('',#74634,#74842); +#74842 = DEFINITIONAL_REPRESENTATION('',(#74843),#74851); +#74843 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74844,#74845,#74846,#74847 + ,#74848,#74849,#74850),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#72452 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); -#72453 = CARTESIAN_POINT('',(0.105063454686,0.105628204905)); -#72454 = CARTESIAN_POINT('',(2.626586367148E-002,0.151122015289)); -#72455 = CARTESIAN_POINT('',(-5.253172734297E-002,0.196615825673)); -#72456 = CARTESIAN_POINT('',(2.626586367148E-002,0.242109636056)); -#72457 = CARTESIAN_POINT('',(0.105063454686,0.28760344644)); -#72458 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); -#72459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72460 = ORIENTED_EDGE('',*,*,#72332,.F.); -#72461 = ORIENTED_EDGE('',*,*,#72462,.F.); -#72462 = EDGE_CURVE('',#72408,#72333,#72463,.T.); -#72463 = SURFACE_CURVE('',#72464,(#72469,#72475),.PCURVE_S1.); -#72464 = CIRCLE('',#72465,5.253172734297E-002); -#72465 = AXIS2_PLACEMENT_3D('',#72466,#72467,#72468); -#72466 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,0.2286)); -#72467 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72468 = DIRECTION('',(-1.,-1.031949858994E-015,0.E+000)); -#72469 = PCURVE('',#72350,#72470); -#72470 = DEFINITIONAL_REPRESENTATION('',(#72471),#72474); -#72471 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72472,#72473),.UNSPECIFIED., +#74844 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); +#74845 = CARTESIAN_POINT('',(0.105063454686,0.105628204905)); +#74846 = CARTESIAN_POINT('',(2.626586367148E-002,0.151122015289)); +#74847 = CARTESIAN_POINT('',(-5.253172734297E-002,0.196615825673)); +#74848 = CARTESIAN_POINT('',(2.626586367148E-002,0.242109636056)); +#74849 = CARTESIAN_POINT('',(0.105063454686,0.28760344644)); +#74850 = CARTESIAN_POINT('',(0.105063454686,0.196615825673)); +#74851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74852 = ORIENTED_EDGE('',*,*,#74724,.F.); +#74853 = ORIENTED_EDGE('',*,*,#74854,.F.); +#74854 = EDGE_CURVE('',#74800,#74725,#74855,.T.); +#74855 = SURFACE_CURVE('',#74856,(#74861,#74867),.PCURVE_S1.); +#74856 = CIRCLE('',#74857,5.253172734297E-002); +#74857 = AXIS2_PLACEMENT_3D('',#74858,#74859,#74860); +#74858 = CARTESIAN_POINT('',(-1.157431727343,-0.318120283077,0.2286)); +#74859 = DIRECTION('',(0.E+000,0.E+000,1.)); +#74860 = DIRECTION('',(-1.,-1.031949858994E-015,0.E+000)); +#74861 = PCURVE('',#74742,#74862); +#74862 = DEFINITIONAL_REPRESENTATION('',(#74863),#74866); +#74863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74864,#74865),.UNSPECIFIED., .F.,.F.,(2,2),(1.800071061035,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#72472 = CARTESIAN_POINT('',(4.483114246145,1.2192)); -#72473 = CARTESIAN_POINT('',(3.14159265359,1.2192)); -#72474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#74864 = CARTESIAN_POINT('',(4.483114246145,1.2192)); +#74865 = CARTESIAN_POINT('',(3.14159265359,1.2192)); +#74866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72475 = PCURVE('',#72215,#72476); -#72476 = DEFINITIONAL_REPRESENTATION('',(#72477),#72485); -#72477 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#72478,#72479,#72480,#72481 - ,#72482,#72483,#72484),.UNSPECIFIED.,.F.,.F.) +#74867 = PCURVE('',#74607,#74868); +#74868 = DEFINITIONAL_REPRESENTATION('',(#74869),#74877); +#74869 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74870,#74871,#74872,#74873 + ,#74874,#74875,#74876),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#72478 = CARTESIAN_POINT('',(-6.661338147751E-016,0.196615825673)); -#72479 = CARTESIAN_POINT('',(-7.632783294298E-016,0.105628204905)); -#72480 = CARTESIAN_POINT('',(-7.879759101445E-002,0.151122015289)); -#72481 = CARTESIAN_POINT('',(-0.157595182029,0.196615825673)); -#72482 = CARTESIAN_POINT('',(-7.879759101445E-002,0.242109636056)); -#72483 = CARTESIAN_POINT('',(-6.314393452556E-016,0.28760344644)); -#72484 = CARTESIAN_POINT('',(-6.661338147751E-016,0.196615825673)); -#72485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72486 = ADVANCED_FACE('',(#72487),#72424,.F.); -#72487 = FACE_BOUND('',#72488,.T.); -#72488 = EDGE_LOOP('',(#72489,#72519,#72540,#72541)); -#72489 = ORIENTED_EDGE('',*,*,#72490,.F.); -#72490 = EDGE_CURVE('',#72491,#72493,#72495,.T.); -#72491 = VERTEX_POINT('',#72492); -#72492 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,0.2286)); -#72493 = VERTEX_POINT('',#72494); -#72494 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,-0.2286)); -#72495 = SURFACE_CURVE('',#72496,(#72500,#72507),.PCURVE_S1.); -#72496 = LINE('',#72497,#72498); -#72497 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,1.4478)); -#72498 = VECTOR('',#72499,1.); -#72499 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72500 = PCURVE('',#72424,#72501); -#72501 = DEFINITIONAL_REPRESENTATION('',(#72502),#72506); -#72502 = LINE('',#72503,#72504); -#72503 = CARTESIAN_POINT('',(-6.62031185561E-002,0.E+000)); -#72504 = VECTOR('',#72505,1.); -#72505 = DIRECTION('',(0.E+000,-1.)); -#72506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72507 = PCURVE('',#72508,#72513); -#72508 = PLANE('',#72509); -#72509 = AXIS2_PLACEMENT_3D('',#72510,#72511,#72512); -#72510 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,1.4478)); -#72511 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72512 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72513 = DEFINITIONAL_REPRESENTATION('',(#72514),#72518); -#72514 = LINE('',#72515,#72516); -#72515 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72516 = VECTOR('',#72517,1.); -#72517 = DIRECTION('',(1.,0.E+000)); -#72518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72519 = ORIENTED_EDGE('',*,*,#72520,.T.); -#72520 = EDGE_CURVE('',#72491,#72408,#72521,.T.); -#72521 = SURFACE_CURVE('',#72522,(#72526,#72533),.PCURVE_S1.); -#72522 = LINE('',#72523,#72524); -#72523 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,0.2286)); -#72524 = VECTOR('',#72525,1.); -#72525 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); -#72526 = PCURVE('',#72424,#72527); -#72527 = DEFINITIONAL_REPRESENTATION('',(#72528),#72532); -#72528 = LINE('',#72529,#72530); -#72529 = CARTESIAN_POINT('',(0.E+000,-1.2192)); -#72530 = VECTOR('',#72531,1.); -#72531 = DIRECTION('',(1.,0.E+000)); -#72532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72533 = PCURVE('',#72215,#72534); -#72534 = DEFINITIONAL_REPRESENTATION('',(#72535),#72539); -#72535 = LINE('',#72536,#72537); -#72536 = CARTESIAN_POINT('',(-6.447068113618E-002,0.145458775719)); -#72537 = VECTOR('',#72538,1.); -#72538 = DIRECTION('',(-0.973831483203,0.22727129674)); -#72539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72540 = ORIENTED_EDGE('',*,*,#72407,.T.); -#72541 = ORIENTED_EDGE('',*,*,#72542,.T.); -#72542 = EDGE_CURVE('',#72410,#72493,#72543,.T.); -#72543 = SURFACE_CURVE('',#72544,(#72548,#72555),.PCURVE_S1.); -#72544 = LINE('',#72545,#72546); -#72545 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,-0.2286)); -#72546 = VECTOR('',#72547,1.); -#72547 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); -#72548 = PCURVE('',#72424,#72549); -#72549 = DEFINITIONAL_REPRESENTATION('',(#72550),#72554); -#72550 = LINE('',#72551,#72552); -#72551 = CARTESIAN_POINT('',(0.E+000,-1.6764)); -#72552 = VECTOR('',#72553,1.); -#72553 = DIRECTION('',(-1.,0.E+000)); -#72554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72555 = PCURVE('',#72242,#72556); -#72556 = DEFINITIONAL_REPRESENTATION('',(#72557),#72561); -#72557 = LINE('',#72558,#72559); -#72558 = CARTESIAN_POINT('',(6.447068113618E-002,0.145458775719)); -#72559 = VECTOR('',#72560,1.); -#72560 = DIRECTION('',(-0.973831483203,-0.22727129674)); -#72561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72562 = ADVANCED_FACE('',(#72563),#72508,.F.); -#72563 = FACE_BOUND('',#72564,.T.); -#72564 = EDGE_LOOP('',(#72565,#72595,#72616,#72617)); -#72565 = ORIENTED_EDGE('',*,*,#72566,.F.); -#72566 = EDGE_CURVE('',#72567,#72569,#72571,.T.); -#72567 = VERTEX_POINT('',#72568); -#72568 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); -#72569 = VERTEX_POINT('',#72570); -#72570 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); -#72571 = SURFACE_CURVE('',#72572,(#72576,#72583),.PCURVE_S1.); -#72572 = LINE('',#72573,#72574); -#72573 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,1.4478)); -#72574 = VECTOR('',#72575,1.); -#72575 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72576 = PCURVE('',#72508,#72577); -#72577 = DEFINITIONAL_REPRESENTATION('',(#72578),#72582); -#72578 = LINE('',#72579,#72580); -#72579 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); -#72580 = VECTOR('',#72581,1.); -#72581 = DIRECTION('',(1.,0.E+000)); -#72582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72583 = PCURVE('',#72584,#72589); -#72584 = PLANE('',#72585); -#72585 = AXIS2_PLACEMENT_3D('',#72586,#72587,#72588); -#72586 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,1.4478)); -#72587 = DIRECTION('',(-0.22727129674,0.973831483203,0.E+000)); -#72588 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); -#72589 = DEFINITIONAL_REPRESENTATION('',(#72590),#72594); -#72590 = LINE('',#72591,#72592); -#72591 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72592 = VECTOR('',#72593,1.); -#72593 = DIRECTION('',(0.E+000,-1.)); -#72594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72595 = ORIENTED_EDGE('',*,*,#72596,.T.); -#72596 = EDGE_CURVE('',#72567,#72491,#72597,.T.); -#72597 = SURFACE_CURVE('',#72598,(#72602,#72609),.PCURVE_S1.); -#72598 = LINE('',#72599,#72600); -#72599 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); -#72600 = VECTOR('',#72601,1.); -#72601 = DIRECTION('',(0.E+000,1.,0.E+000)); -#72602 = PCURVE('',#72508,#72603); -#72603 = DEFINITIONAL_REPRESENTATION('',(#72604),#72608); -#72604 = LINE('',#72605,#72606); -#72605 = CARTESIAN_POINT('',(1.2192,-0.130412707117)); -#72606 = VECTOR('',#72607,1.); -#72607 = DIRECTION('',(0.E+000,1.)); -#72608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72609 = PCURVE('',#72215,#72610); -#72610 = DEFINITIONAL_REPRESENTATION('',(#72611),#72615); -#72611 = LINE('',#72612,#72613); -#72612 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72613 = VECTOR('',#72614,1.); -#72614 = DIRECTION('',(0.E+000,1.)); -#72615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72616 = ORIENTED_EDGE('',*,*,#72490,.T.); -#72617 = ORIENTED_EDGE('',*,*,#72618,.F.); -#72618 = EDGE_CURVE('',#72569,#72493,#72619,.T.); -#72619 = SURFACE_CURVE('',#72620,(#72624,#72631),.PCURVE_S1.); -#72620 = LINE('',#72621,#72622); -#72621 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); -#72622 = VECTOR('',#72623,1.); -#72623 = DIRECTION('',(0.E+000,1.,0.E+000)); -#72624 = PCURVE('',#72508,#72625); -#72625 = DEFINITIONAL_REPRESENTATION('',(#72626),#72630); -#72626 = LINE('',#72627,#72628); -#72627 = CARTESIAN_POINT('',(1.6764,-0.130412707117)); -#72628 = VECTOR('',#72629,1.); -#72629 = DIRECTION('',(0.E+000,1.)); -#72630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72631 = PCURVE('',#72242,#72632); -#72632 = DEFINITIONAL_REPRESENTATION('',(#72633),#72637); -#72633 = LINE('',#72634,#72635); -#72634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72635 = VECTOR('',#72636,1.); -#72636 = DIRECTION('',(0.E+000,1.)); -#72637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72638 = ADVANCED_FACE('',(#72639),#72584,.F.); -#72639 = FACE_BOUND('',#72640,.T.); -#72640 = EDGE_LOOP('',(#72641,#72670,#72691,#72692)); -#72641 = ORIENTED_EDGE('',*,*,#72642,.F.); -#72642 = EDGE_CURVE('',#72643,#72645,#72647,.T.); -#72643 = VERTEX_POINT('',#72644); -#72644 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,0.2286)); -#72645 = VERTEX_POINT('',#72646); -#72646 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,-0.2286)); -#72647 = SURFACE_CURVE('',#72648,(#72652,#72659),.PCURVE_S1.); -#72648 = LINE('',#72649,#72650); -#72649 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,1.4478)); -#72650 = VECTOR('',#72651,1.); -#72651 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72652 = PCURVE('',#72584,#72653); -#72653 = DEFINITIONAL_REPRESENTATION('',(#72654),#72658); -#72654 = LINE('',#72655,#72656); -#72655 = CARTESIAN_POINT('',(-0.137525754385,0.E+000)); -#72656 = VECTOR('',#72657,1.); -#72657 = DIRECTION('',(0.E+000,-1.)); -#72658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72659 = PCURVE('',#72660,#72665); -#72660 = CYLINDRICAL_SURFACE('',#72661,0.127); -#72661 = AXIS2_PLACEMENT_3D('',#72662,#72663,#72664); -#72662 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,1.4478)); -#72663 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72664 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72665 = DEFINITIONAL_REPRESENTATION('',(#72666),#72669); -#72666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72667,#72668),.UNSPECIFIED., +#74870 = CARTESIAN_POINT('',(-6.661338147751E-016,0.196615825673)); +#74871 = CARTESIAN_POINT('',(-7.632783294298E-016,0.105628204905)); +#74872 = CARTESIAN_POINT('',(-7.879759101445E-002,0.151122015289)); +#74873 = CARTESIAN_POINT('',(-0.157595182029,0.196615825673)); +#74874 = CARTESIAN_POINT('',(-7.879759101445E-002,0.242109636056)); +#74875 = CARTESIAN_POINT('',(-6.314393452556E-016,0.28760344644)); +#74876 = CARTESIAN_POINT('',(-6.661338147751E-016,0.196615825673)); +#74877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74878 = ADVANCED_FACE('',(#74879),#74816,.F.); +#74879 = FACE_BOUND('',#74880,.T.); +#74880 = EDGE_LOOP('',(#74881,#74911,#74932,#74933)); +#74881 = ORIENTED_EDGE('',*,*,#74882,.F.); +#74882 = EDGE_CURVE('',#74883,#74885,#74887,.T.); +#74883 = VERTEX_POINT('',#74884); +#74884 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,0.2286)); +#74885 = VERTEX_POINT('',#74886); +#74886 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,-0.2286)); +#74887 = SURFACE_CURVE('',#74888,(#74892,#74899),.PCURVE_S1.); +#74888 = LINE('',#74889,#74890); +#74889 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,1.4478)); +#74890 = VECTOR('',#74891,1.); +#74891 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74892 = PCURVE('',#74816,#74893); +#74893 = DEFINITIONAL_REPRESENTATION('',(#74894),#74898); +#74894 = LINE('',#74895,#74896); +#74895 = CARTESIAN_POINT('',(-6.62031185561E-002,0.E+000)); +#74896 = VECTOR('',#74897,1.); +#74897 = DIRECTION('',(0.E+000,-1.)); +#74898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74899 = PCURVE('',#74900,#74905); +#74900 = PLANE('',#74901); +#74901 = AXIS2_PLACEMENT_3D('',#74902,#74903,#74904); +#74902 = CARTESIAN_POINT('',(-1.209963454686,-0.384323401633,1.4478)); +#74903 = DIRECTION('',(1.,0.E+000,0.E+000)); +#74904 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74905 = DEFINITIONAL_REPRESENTATION('',(#74906),#74910); +#74906 = LINE('',#74907,#74908); +#74907 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74908 = VECTOR('',#74909,1.); +#74909 = DIRECTION('',(1.,0.E+000)); +#74910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74911 = ORIENTED_EDGE('',*,*,#74912,.T.); +#74912 = EDGE_CURVE('',#74883,#74800,#74913,.T.); +#74913 = SURFACE_CURVE('',#74914,(#74918,#74925),.PCURVE_S1.); +#74914 = LINE('',#74915,#74916); +#74915 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,0.2286)); +#74916 = VECTOR('',#74917,1.); +#74917 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); +#74918 = PCURVE('',#74816,#74919); +#74919 = DEFINITIONAL_REPRESENTATION('',(#74920),#74924); +#74920 = LINE('',#74921,#74922); +#74921 = CARTESIAN_POINT('',(0.E+000,-1.2192)); +#74922 = VECTOR('',#74923,1.); +#74923 = DIRECTION('',(1.,0.E+000)); +#74924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74925 = PCURVE('',#74607,#74926); +#74926 = DEFINITIONAL_REPRESENTATION('',(#74927),#74931); +#74927 = LINE('',#74928,#74929); +#74928 = CARTESIAN_POINT('',(-6.447068113618E-002,0.145458775719)); +#74929 = VECTOR('',#74930,1.); +#74930 = DIRECTION('',(-0.973831483203,0.22727129674)); +#74931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74932 = ORIENTED_EDGE('',*,*,#74799,.T.); +#74933 = ORIENTED_EDGE('',*,*,#74934,.T.); +#74934 = EDGE_CURVE('',#74802,#74885,#74935,.T.); +#74935 = SURFACE_CURVE('',#74936,(#74940,#74947),.PCURVE_S1.); +#74936 = LINE('',#74937,#74938); +#74937 = CARTESIAN_POINT('',(-1.14549277355,-0.369277333031,-0.2286)); +#74938 = VECTOR('',#74939,1.); +#74939 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); +#74940 = PCURVE('',#74816,#74941); +#74941 = DEFINITIONAL_REPRESENTATION('',(#74942),#74946); +#74942 = LINE('',#74943,#74944); +#74943 = CARTESIAN_POINT('',(0.E+000,-1.6764)); +#74944 = VECTOR('',#74945,1.); +#74945 = DIRECTION('',(-1.,0.E+000)); +#74946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74947 = PCURVE('',#74634,#74948); +#74948 = DEFINITIONAL_REPRESENTATION('',(#74949),#74953); +#74949 = LINE('',#74950,#74951); +#74950 = CARTESIAN_POINT('',(6.447068113618E-002,0.145458775719)); +#74951 = VECTOR('',#74952,1.); +#74952 = DIRECTION('',(-0.973831483203,-0.22727129674)); +#74953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74954 = ADVANCED_FACE('',(#74955),#74900,.F.); +#74955 = FACE_BOUND('',#74956,.T.); +#74956 = EDGE_LOOP('',(#74957,#74987,#75008,#75009)); +#74957 = ORIENTED_EDGE('',*,*,#74958,.F.); +#74958 = EDGE_CURVE('',#74959,#74961,#74963,.T.); +#74959 = VERTEX_POINT('',#74960); +#74960 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); +#74961 = VERTEX_POINT('',#74962); +#74962 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); +#74963 = SURFACE_CURVE('',#74964,(#74968,#74975),.PCURVE_S1.); +#74964 = LINE('',#74965,#74966); +#74965 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,1.4478)); +#74966 = VECTOR('',#74967,1.); +#74967 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#74968 = PCURVE('',#74900,#74969); +#74969 = DEFINITIONAL_REPRESENTATION('',(#74970),#74974); +#74970 = LINE('',#74971,#74972); +#74971 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); +#74972 = VECTOR('',#74973,1.); +#74973 = DIRECTION('',(1.,0.E+000)); +#74974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74975 = PCURVE('',#74976,#74981); +#74976 = PLANE('',#74977); +#74977 = AXIS2_PLACEMENT_3D('',#74978,#74979,#74980); +#74978 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,1.4478)); +#74979 = DIRECTION('',(-0.22727129674,0.973831483203,0.E+000)); +#74980 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); +#74981 = DEFINITIONAL_REPRESENTATION('',(#74982),#74986); +#74982 = LINE('',#74983,#74984); +#74983 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#74984 = VECTOR('',#74985,1.); +#74985 = DIRECTION('',(0.E+000,-1.)); +#74986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#74987 = ORIENTED_EDGE('',*,*,#74988,.T.); +#74988 = EDGE_CURVE('',#74959,#74883,#74989,.T.); +#74989 = SURFACE_CURVE('',#74990,(#74994,#75001),.PCURVE_S1.); +#74990 = LINE('',#74991,#74992); +#74991 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); +#74992 = VECTOR('',#74993,1.); +#74993 = DIRECTION('',(0.E+000,1.,0.E+000)); +#74994 = PCURVE('',#74900,#74995); +#74995 = DEFINITIONAL_REPRESENTATION('',(#74996),#75000); +#74996 = LINE('',#74997,#74998); +#74997 = CARTESIAN_POINT('',(1.2192,-0.130412707117)); +#74998 = VECTOR('',#74999,1.); +#74999 = DIRECTION('',(0.E+000,1.)); +#75000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75001 = PCURVE('',#74607,#75002); +#75002 = DEFINITIONAL_REPRESENTATION('',(#75003),#75007); +#75003 = LINE('',#75004,#75005); +#75004 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75005 = VECTOR('',#75006,1.); +#75006 = DIRECTION('',(0.E+000,1.)); +#75007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75008 = ORIENTED_EDGE('',*,*,#74882,.T.); +#75009 = ORIENTED_EDGE('',*,*,#75010,.F.); +#75010 = EDGE_CURVE('',#74961,#74885,#75011,.T.); +#75011 = SURFACE_CURVE('',#75012,(#75016,#75023),.PCURVE_S1.); +#75012 = LINE('',#75013,#75014); +#75013 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); +#75014 = VECTOR('',#75015,1.); +#75015 = DIRECTION('',(0.E+000,1.,0.E+000)); +#75016 = PCURVE('',#74900,#75017); +#75017 = DEFINITIONAL_REPRESENTATION('',(#75018),#75022); +#75018 = LINE('',#75019,#75020); +#75019 = CARTESIAN_POINT('',(1.6764,-0.130412707117)); +#75020 = VECTOR('',#75021,1.); +#75021 = DIRECTION('',(0.E+000,1.)); +#75022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75023 = PCURVE('',#74634,#75024); +#75024 = DEFINITIONAL_REPRESENTATION('',(#75025),#75029); +#75025 = LINE('',#75026,#75027); +#75026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75027 = VECTOR('',#75028,1.); +#75028 = DIRECTION('',(0.E+000,1.)); +#75029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75030 = ADVANCED_FACE('',(#75031),#74976,.F.); +#75031 = FACE_BOUND('',#75032,.T.); +#75032 = EDGE_LOOP('',(#75033,#75062,#75083,#75084)); +#75033 = ORIENTED_EDGE('',*,*,#75034,.F.); +#75034 = EDGE_CURVE('',#75035,#75037,#75039,.T.); +#75035 = VERTEX_POINT('',#75036); +#75036 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,0.2286)); +#75037 = VERTEX_POINT('',#75038); +#75038 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,-0.2286)); +#75039 = SURFACE_CURVE('',#75040,(#75044,#75051),.PCURVE_S1.); +#75040 = LINE('',#75041,#75042); +#75041 = CARTESIAN_POINT('',(-1.076036545314,-0.483480452216,1.4478)); +#75042 = VECTOR('',#75043,1.); +#75043 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75044 = PCURVE('',#74976,#75045); +#75045 = DEFINITIONAL_REPRESENTATION('',(#75046),#75050); +#75046 = LINE('',#75047,#75048); +#75047 = CARTESIAN_POINT('',(-0.137525754385,0.E+000)); +#75048 = VECTOR('',#75049,1.); +#75049 = DIRECTION('',(0.E+000,-1.)); +#75050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75051 = PCURVE('',#75052,#75057); +#75052 = CYLINDRICAL_SURFACE('',#75053,0.127); +#75053 = AXIS2_PLACEMENT_3D('',#75054,#75055,#75056); +#75054 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,1.4478)); +#75055 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75056 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75057 = DEFINITIONAL_REPRESENTATION('',(#75058),#75061); +#75058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75059,#75060),.UNSPECIFIED., .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72667 = CARTESIAN_POINT('',(4.483114246145,1.2192)); -#72668 = CARTESIAN_POINT('',(4.483114246145,1.6764)); -#72669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72670 = ORIENTED_EDGE('',*,*,#72671,.T.); -#72671 = EDGE_CURVE('',#72643,#72567,#72672,.T.); -#72672 = SURFACE_CURVE('',#72673,(#72677,#72684),.PCURVE_S1.); -#72673 = LINE('',#72674,#72675); -#72674 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); -#72675 = VECTOR('',#72676,1.); -#72676 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); -#72677 = PCURVE('',#72584,#72678); -#72678 = DEFINITIONAL_REPRESENTATION('',(#72679),#72683); -#72679 = LINE('',#72680,#72681); -#72680 = CARTESIAN_POINT('',(0.E+000,-1.2192)); -#72681 = VECTOR('',#72682,1.); -#72682 = DIRECTION('',(1.,0.E+000)); -#72683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72684 = PCURVE('',#72215,#72685); -#72685 = DEFINITIONAL_REPRESENTATION('',(#72686),#72690); -#72686 = LINE('',#72687,#72688); -#72687 = CARTESIAN_POINT('',(-2.22044604925E-016,0.E+000)); -#72688 = VECTOR('',#72689,1.); -#72689 = DIRECTION('',(0.973831483203,-0.22727129674)); -#72690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72691 = ORIENTED_EDGE('',*,*,#72566,.T.); -#72692 = ORIENTED_EDGE('',*,*,#72693,.T.); -#72693 = EDGE_CURVE('',#72569,#72645,#72694,.T.); -#72694 = SURFACE_CURVE('',#72695,(#72699,#72706),.PCURVE_S1.); -#72695 = LINE('',#72696,#72697); -#72696 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); -#72697 = VECTOR('',#72698,1.); -#72698 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); -#72699 = PCURVE('',#72584,#72700); -#72700 = DEFINITIONAL_REPRESENTATION('',(#72701),#72705); -#72701 = LINE('',#72702,#72703); -#72702 = CARTESIAN_POINT('',(0.E+000,-1.6764)); -#72703 = VECTOR('',#72704,1.); -#72704 = DIRECTION('',(-1.,0.E+000)); -#72705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72706 = PCURVE('',#72242,#72707); -#72707 = DEFINITIONAL_REPRESENTATION('',(#72708),#72712); -#72708 = LINE('',#72709,#72710); -#72709 = CARTESIAN_POINT('',(-2.22044604925E-016,0.E+000)); -#72710 = VECTOR('',#72711,1.); -#72711 = DIRECTION('',(0.973831483203,0.22727129674)); -#72712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#75059 = CARTESIAN_POINT('',(4.483114246145,1.2192)); +#75060 = CARTESIAN_POINT('',(4.483114246145,1.6764)); +#75061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75062 = ORIENTED_EDGE('',*,*,#75063,.T.); +#75063 = EDGE_CURVE('',#75035,#74959,#75064,.T.); +#75064 = SURFACE_CURVE('',#75065,(#75069,#75076),.PCURVE_S1.); +#75065 = LINE('',#75066,#75067); +#75066 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,0.2286)); +#75067 = VECTOR('',#75068,1.); +#75068 = DIRECTION('',(-0.973831483203,-0.22727129674,0.E+000)); +#75069 = PCURVE('',#74976,#75070); +#75070 = DEFINITIONAL_REPRESENTATION('',(#75071),#75075); +#75071 = LINE('',#75072,#75073); +#75072 = CARTESIAN_POINT('',(0.E+000,-1.2192)); +#75073 = VECTOR('',#75074,1.); +#75074 = DIRECTION('',(1.,0.E+000)); +#75075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75076 = PCURVE('',#74607,#75077); +#75077 = DEFINITIONAL_REPRESENTATION('',(#75078),#75082); +#75078 = LINE('',#75079,#75080); +#75079 = CARTESIAN_POINT('',(-2.22044604925E-016,0.E+000)); +#75080 = VECTOR('',#75081,1.); +#75081 = DIRECTION('',(0.973831483203,-0.22727129674)); +#75082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75083 = ORIENTED_EDGE('',*,*,#74958,.T.); +#75084 = ORIENTED_EDGE('',*,*,#75085,.T.); +#75085 = EDGE_CURVE('',#74961,#75037,#75086,.T.); +#75086 = SURFACE_CURVE('',#75087,(#75091,#75098),.PCURVE_S1.); +#75087 = LINE('',#75088,#75089); +#75088 = CARTESIAN_POINT('',(-1.209963454686,-0.51473610875,-0.2286)); +#75089 = VECTOR('',#75090,1.); +#75090 = DIRECTION('',(0.973831483203,0.22727129674,0.E+000)); +#75091 = PCURVE('',#74976,#75092); +#75092 = DEFINITIONAL_REPRESENTATION('',(#75093),#75097); +#75093 = LINE('',#75094,#75095); +#75094 = CARTESIAN_POINT('',(0.E+000,-1.6764)); +#75095 = VECTOR('',#75096,1.); +#75096 = DIRECTION('',(-1.,0.E+000)); +#75097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75098 = PCURVE('',#74634,#75099); +#75099 = DEFINITIONAL_REPRESENTATION('',(#75100),#75104); +#75100 = LINE('',#75101,#75102); +#75101 = CARTESIAN_POINT('',(-2.22044604925E-016,0.E+000)); +#75102 = VECTOR('',#75103,1.); +#75103 = DIRECTION('',(0.973831483203,0.22727129674)); +#75104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75105 = ADVANCED_FACE('',(#75106),#75052,.T.); +#75106 = FACE_BOUND('',#75107,.T.); +#75107 = EDGE_LOOP('',(#75108,#75137,#75158,#75159)); +#75108 = ORIENTED_EDGE('',*,*,#75109,.F.); +#75109 = EDGE_CURVE('',#75110,#75112,#75114,.T.); +#75110 = VERTEX_POINT('',#75111); +#75111 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,0.2286)); +#75112 = VERTEX_POINT('',#75113); +#75113 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,-0.2286)); +#75114 = SURFACE_CURVE('',#75115,(#75119,#75125),.PCURVE_S1.); +#75115 = LINE('',#75116,#75117); +#75116 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,1.4478)); +#75117 = VECTOR('',#75118,1.); +#75118 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75119 = PCURVE('',#75052,#75120); +#75120 = DEFINITIONAL_REPRESENTATION('',(#75121),#75124); +#75121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75122,#75123),.UNSPECIFIED., + .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); +#75122 = CARTESIAN_POINT('',(3.14159265359,1.2192)); +#75123 = CARTESIAN_POINT('',(3.14159265359,1.6764)); +#75124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72713 = ADVANCED_FACE('',(#72714),#72660,.T.); -#72714 = FACE_BOUND('',#72715,.T.); -#72715 = EDGE_LOOP('',(#72716,#72745,#72766,#72767)); -#72716 = ORIENTED_EDGE('',*,*,#72717,.F.); -#72717 = EDGE_CURVE('',#72718,#72720,#72722,.T.); -#72718 = VERTEX_POINT('',#72719); -#72719 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,0.2286)); -#72720 = VERTEX_POINT('',#72721); -#72721 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,-0.2286)); -#72722 = SURFACE_CURVE('',#72723,(#72727,#72733),.PCURVE_S1.); -#72723 = LINE('',#72724,#72725); -#72724 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,1.4478)); -#72725 = VECTOR('',#72726,1.); -#72726 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72727 = PCURVE('',#72660,#72728); -#72728 = DEFINITIONAL_REPRESENTATION('',(#72729),#72732); -#72729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72730,#72731),.UNSPECIFIED., - .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72730 = CARTESIAN_POINT('',(3.14159265359,1.2192)); -#72731 = CARTESIAN_POINT('',(3.14159265359,1.6764)); -#72732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72733 = PCURVE('',#72734,#72739); -#72734 = PLANE('',#72735); -#72735 = AXIS2_PLACEMENT_3D('',#72736,#72737,#72738); -#72736 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,1.4478)); -#72737 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72738 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72739 = DEFINITIONAL_REPRESENTATION('',(#72740),#72744); -#72740 = LINE('',#72741,#72742); -#72741 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72742 = VECTOR('',#72743,1.); -#72743 = DIRECTION('',(-1.,0.E+000)); -#72744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72745 = ORIENTED_EDGE('',*,*,#72746,.T.); -#72746 = EDGE_CURVE('',#72718,#72643,#72747,.T.); -#72747 = SURFACE_CURVE('',#72748,(#72753,#72759),.PCURVE_S1.); -#72748 = CIRCLE('',#72749,0.127); -#72749 = AXIS2_PLACEMENT_3D('',#72750,#72751,#72752); -#72750 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,0.2286)); -#72751 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72752 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72753 = PCURVE('',#72660,#72754); -#72754 = DEFINITIONAL_REPRESENTATION('',(#72755),#72758); -#72755 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72756,#72757),.UNSPECIFIED., +#75125 = PCURVE('',#75126,#75131); +#75126 = PLANE('',#75127); +#75127 = AXIS2_PLACEMENT_3D('',#75128,#75129,#75130); +#75128 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,1.4478)); +#75129 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75130 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75131 = DEFINITIONAL_REPRESENTATION('',(#75132),#75136); +#75132 = LINE('',#75133,#75134); +#75133 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75134 = VECTOR('',#75135,1.); +#75135 = DIRECTION('',(-1.,0.E+000)); +#75136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75137 = ORIENTED_EDGE('',*,*,#75138,.T.); +#75138 = EDGE_CURVE('',#75110,#75035,#75139,.T.); +#75139 = SURFACE_CURVE('',#75140,(#75145,#75151),.PCURVE_S1.); +#75140 = CIRCLE('',#75141,0.127); +#75141 = AXIS2_PLACEMENT_3D('',#75142,#75143,#75144); +#75142 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,0.2286)); +#75143 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75144 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75145 = PCURVE('',#75052,#75146); +#75146 = DEFINITIONAL_REPRESENTATION('',(#75147),#75150); +#75147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75148,#75149),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.483114246145), .PIECEWISE_BEZIER_KNOTS.); -#72756 = CARTESIAN_POINT('',(3.14159265359,1.2192)); -#72757 = CARTESIAN_POINT('',(4.483114246145,1.2192)); -#72758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72759 = PCURVE('',#72215,#72760); -#72760 = DEFINITIONAL_REPRESENTATION('',(#72761),#72765); -#72761 = CIRCLE('',#72762,0.127); -#72762 = AXIS2_PLACEMENT_2D('',#72763,#72764); -#72763 = CARTESIAN_POINT('',(-0.105063454686,0.154932254901)); -#72764 = DIRECTION('',(1.,0.E+000)); -#72765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72766 = ORIENTED_EDGE('',*,*,#72642,.T.); -#72767 = ORIENTED_EDGE('',*,*,#72768,.T.); -#72768 = EDGE_CURVE('',#72645,#72720,#72769,.T.); -#72769 = SURFACE_CURVE('',#72770,(#72775,#72781),.PCURVE_S1.); -#72770 = CIRCLE('',#72771,0.127); -#72771 = AXIS2_PLACEMENT_3D('',#72772,#72773,#72774); -#72772 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,-0.2286)); -#72773 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72774 = DIRECTION('',(1.,0.E+000,0.E+000)); -#72775 = PCURVE('',#72660,#72776); -#72776 = DEFINITIONAL_REPRESENTATION('',(#72777),#72780); -#72777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72778,#72779),.UNSPECIFIED., +#75148 = CARTESIAN_POINT('',(3.14159265359,1.2192)); +#75149 = CARTESIAN_POINT('',(4.483114246145,1.2192)); +#75150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75151 = PCURVE('',#74607,#75152); +#75152 = DEFINITIONAL_REPRESENTATION('',(#75153),#75157); +#75153 = CIRCLE('',#75154,0.127); +#75154 = AXIS2_PLACEMENT_2D('',#75155,#75156); +#75155 = CARTESIAN_POINT('',(-0.105063454686,0.154932254901)); +#75156 = DIRECTION('',(1.,0.E+000)); +#75157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75158 = ORIENTED_EDGE('',*,*,#75034,.T.); +#75159 = ORIENTED_EDGE('',*,*,#75160,.T.); +#75160 = EDGE_CURVE('',#75037,#75112,#75161,.T.); +#75161 = SURFACE_CURVE('',#75162,(#75167,#75173),.PCURVE_S1.); +#75162 = CIRCLE('',#75163,0.127); +#75163 = AXIS2_PLACEMENT_3D('',#75164,#75165,#75166); +#75164 = CARTESIAN_POINT('',(-1.1049,-0.359803853849,-0.2286)); +#75165 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75166 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75167 = PCURVE('',#75052,#75168); +#75168 = DEFINITIONAL_REPRESENTATION('',(#75169),#75172); +#75169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75170,#75171),.UNSPECIFIED., .F.,.F.,(2,2),(4.941663714624,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#72778 = CARTESIAN_POINT('',(4.483114246145,1.6764)); -#72779 = CARTESIAN_POINT('',(3.14159265359,1.6764)); -#72780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72781 = PCURVE('',#72242,#72782); -#72782 = DEFINITIONAL_REPRESENTATION('',(#72783),#72787); -#72783 = CIRCLE('',#72784,0.127); -#72784 = AXIS2_PLACEMENT_2D('',#72785,#72786); -#72785 = CARTESIAN_POINT('',(0.105063454686,0.154932254901)); -#72786 = DIRECTION('',(1.,0.E+000)); -#72787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72788 = ADVANCED_FACE('',(#72789),#72734,.F.); -#72789 = FACE_BOUND('',#72790,.T.); -#72790 = EDGE_LOOP('',(#72791,#72843,#72864,#72865)); -#72791 = ORIENTED_EDGE('',*,*,#72792,.F.); -#72792 = EDGE_CURVE('',#72793,#72795,#72797,.T.); -#72793 = VERTEX_POINT('',#72794); -#72794 = CARTESIAN_POINT('',(-0.9779,-0.254,0.2286)); -#72795 = VERTEX_POINT('',#72796); -#72796 = CARTESIAN_POINT('',(-0.9779,-0.254,-0.2286)); -#72797 = SURFACE_CURVE('',#72798,(#72802,#72809),.PCURVE_S1.); -#72798 = LINE('',#72799,#72800); -#72799 = CARTESIAN_POINT('',(-0.9779,-0.254,1.4478)); -#72800 = VECTOR('',#72801,1.); -#72801 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72802 = PCURVE('',#72734,#72803); -#72803 = DEFINITIONAL_REPRESENTATION('',(#72804),#72808); -#72804 = LINE('',#72805,#72806); -#72805 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); -#72806 = VECTOR('',#72807,1.); -#72807 = DIRECTION('',(-1.,0.E+000)); -#72808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72809 = PCURVE('',#72810,#72815); -#72810 = CYLINDRICAL_SURFACE('',#72811,0.127); -#72811 = AXIS2_PLACEMENT_3D('',#72812,#72813,#72814); -#72812 = CARTESIAN_POINT('',(-0.8509,-0.254,1.4478)); -#72813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72814 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72815 = DEFINITIONAL_REPRESENTATION('',(#72816),#72842); -#72816 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#72817,#72818,#72819,#72820, - #72821,#72822,#72823,#72824,#72825,#72826,#72827,#72828,#72829, - #72830,#72831,#72832,#72833,#72834,#72835,#72836,#72837,#72838, - #72839,#72840,#72841),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#75170 = CARTESIAN_POINT('',(4.483114246145,1.6764)); +#75171 = CARTESIAN_POINT('',(3.14159265359,1.6764)); +#75172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75173 = PCURVE('',#74634,#75174); +#75174 = DEFINITIONAL_REPRESENTATION('',(#75175),#75179); +#75175 = CIRCLE('',#75176,0.127); +#75176 = AXIS2_PLACEMENT_2D('',#75177,#75178); +#75177 = CARTESIAN_POINT('',(0.105063454686,0.154932254901)); +#75178 = DIRECTION('',(1.,0.E+000)); +#75179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75180 = ADVANCED_FACE('',(#75181),#75126,.F.); +#75181 = FACE_BOUND('',#75182,.T.); +#75182 = EDGE_LOOP('',(#75183,#75235,#75256,#75257)); +#75183 = ORIENTED_EDGE('',*,*,#75184,.F.); +#75184 = EDGE_CURVE('',#75185,#75187,#75189,.T.); +#75185 = VERTEX_POINT('',#75186); +#75186 = CARTESIAN_POINT('',(-0.9779,-0.254,0.2286)); +#75187 = VERTEX_POINT('',#75188); +#75188 = CARTESIAN_POINT('',(-0.9779,-0.254,-0.2286)); +#75189 = SURFACE_CURVE('',#75190,(#75194,#75201),.PCURVE_S1.); +#75190 = LINE('',#75191,#75192); +#75191 = CARTESIAN_POINT('',(-0.9779,-0.254,1.4478)); +#75192 = VECTOR('',#75193,1.); +#75193 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75194 = PCURVE('',#75126,#75195); +#75195 = DEFINITIONAL_REPRESENTATION('',(#75196),#75200); +#75196 = LINE('',#75197,#75198); +#75197 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); +#75198 = VECTOR('',#75199,1.); +#75199 = DIRECTION('',(-1.,0.E+000)); +#75200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75201 = PCURVE('',#75202,#75207); +#75202 = CYLINDRICAL_SURFACE('',#75203,0.127); +#75203 = AXIS2_PLACEMENT_3D('',#75204,#75205,#75206); +#75204 = CARTESIAN_POINT('',(-0.8509,-0.254,1.4478)); +#75205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75206 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75207 = DEFINITIONAL_REPRESENTATION('',(#75208),#75234); +#75208 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75209,#75210,#75211,#75212, + #75213,#75214,#75215,#75216,#75217,#75218,#75219,#75220,#75221, + #75222,#75223,#75224,#75225,#75226,#75227,#75228,#75229,#75230, + #75231,#75232,#75233),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.2192,1.239981818182,1.260763636364, 1.281545454545,1.302327272727,1.323109090909,1.343890909091, 1.364672727273,1.385454545455,1.406236363636,1.427018181818,1.4478, 1.468581818182,1.489363636364,1.510145454545,1.530927272727, 1.551709090909,1.572490909091,1.593272727273,1.614054545455, 1.634836363636,1.655618181818,1.6764),.QUASI_UNIFORM_KNOTS.); -#72817 = CARTESIAN_POINT('',(0.E+000,1.2192)); -#72818 = CARTESIAN_POINT('',(-4.440892098501E-015,1.226127272727)); -#72819 = CARTESIAN_POINT('',(-7.993605777301E-015,1.239981818182)); -#72820 = CARTESIAN_POINT('',(-6.217248937901E-015,1.260763636364)); -#72821 = CARTESIAN_POINT('',(-7.105427357601E-015,1.281545454545)); -#72822 = CARTESIAN_POINT('',(-6.217248937901E-015,1.302327272727)); -#72823 = CARTESIAN_POINT('',(-5.329070518201E-015,1.323109090909)); -#72824 = CARTESIAN_POINT('',(-7.993605777301E-015,1.343890909091)); -#72825 = CARTESIAN_POINT('',(-6.217248937901E-015,1.364672727273)); -#72826 = CARTESIAN_POINT('',(-7.105427357601E-015,1.385454545455)); -#72827 = CARTESIAN_POINT('',(-6.217248937901E-015,1.406236363636)); -#72828 = CARTESIAN_POINT('',(-6.217248937901E-015,1.427018181818)); -#72829 = CARTESIAN_POINT('',(-5.329070518201E-015,1.4478)); -#72830 = CARTESIAN_POINT('',(-7.105427357601E-015,1.468581818182)); -#72831 = CARTESIAN_POINT('',(-6.217248937901E-015,1.489363636364)); -#72832 = CARTESIAN_POINT('',(-6.217248937901E-015,1.510145454545)); -#72833 = CARTESIAN_POINT('',(-7.105427357601E-015,1.530927272727)); -#72834 = CARTESIAN_POINT('',(-5.329070518201E-015,1.551709090909)); -#72835 = CARTESIAN_POINT('',(-5.329070518201E-015,1.572490909091)); -#72836 = CARTESIAN_POINT('',(-7.993605777301E-015,1.593272727273)); -#72837 = CARTESIAN_POINT('',(-5.329070518201E-015,1.614054545455)); -#72838 = CARTESIAN_POINT('',(-7.105427357601E-015,1.634836363636)); -#72839 = CARTESIAN_POINT('',(-6.217248937901E-015,1.655618181818)); -#72840 = CARTESIAN_POINT('',(-4.440892098501E-015,1.669472727273)); -#72841 = CARTESIAN_POINT('',(0.E+000,1.6764)); -#72842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72843 = ORIENTED_EDGE('',*,*,#72844,.T.); -#72844 = EDGE_CURVE('',#72793,#72718,#72845,.T.); -#72845 = SURFACE_CURVE('',#72846,(#72850,#72857),.PCURVE_S1.); -#72846 = LINE('',#72847,#72848); -#72847 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,0.2286)); -#72848 = VECTOR('',#72849,1.); -#72849 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#72850 = PCURVE('',#72734,#72851); -#72851 = DEFINITIONAL_REPRESENTATION('',(#72852),#72856); -#72852 = LINE('',#72853,#72854); -#72853 = CARTESIAN_POINT('',(-1.2192,0.E+000)); -#72854 = VECTOR('',#72855,1.); -#72855 = DIRECTION('',(0.E+000,-1.)); -#72856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72857 = PCURVE('',#72215,#72858); -#72858 = DEFINITIONAL_REPRESENTATION('',(#72859),#72863); -#72859 = LINE('',#72860,#72861); -#72860 = CARTESIAN_POINT('',(-0.232063454686,0.154932254901)); -#72861 = VECTOR('',#72862,1.); -#72862 = DIRECTION('',(0.E+000,-1.)); -#72863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72864 = ORIENTED_EDGE('',*,*,#72717,.T.); -#72865 = ORIENTED_EDGE('',*,*,#72866,.T.); -#72866 = EDGE_CURVE('',#72720,#72795,#72867,.T.); -#72867 = SURFACE_CURVE('',#72868,(#72872,#72879),.PCURVE_S1.); -#72868 = LINE('',#72869,#72870); -#72869 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,-0.2286)); -#72870 = VECTOR('',#72871,1.); -#72871 = DIRECTION('',(0.E+000,1.,0.E+000)); -#72872 = PCURVE('',#72734,#72873); -#72873 = DEFINITIONAL_REPRESENTATION('',(#72874),#72878); -#72874 = LINE('',#72875,#72876); -#72875 = CARTESIAN_POINT('',(-1.6764,0.E+000)); -#72876 = VECTOR('',#72877,1.); -#72877 = DIRECTION('',(0.E+000,1.)); -#72878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72879 = PCURVE('',#72242,#72880); -#72880 = DEFINITIONAL_REPRESENTATION('',(#72881),#72885); -#72881 = LINE('',#72882,#72883); -#72882 = CARTESIAN_POINT('',(0.232063454686,0.154932254901)); -#72883 = VECTOR('',#72884,1.); -#72884 = DIRECTION('',(0.E+000,1.)); -#72885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72886 = ADVANCED_FACE('',(#72887),#72810,.F.); -#72887 = FACE_BOUND('',#72888,.F.); -#72888 = EDGE_LOOP('',(#72889,#72918,#72943,#72944)); -#72889 = ORIENTED_EDGE('',*,*,#72890,.T.); -#72890 = EDGE_CURVE('',#72891,#72893,#72895,.T.); -#72891 = VERTEX_POINT('',#72892); -#72892 = CARTESIAN_POINT('',(-0.8509,-0.127,0.2286)); -#72893 = VERTEX_POINT('',#72894); -#72894 = CARTESIAN_POINT('',(-0.8509,-0.127,-0.2286)); -#72895 = SURFACE_CURVE('',#72896,(#72900,#72906),.PCURVE_S1.); -#72896 = LINE('',#72897,#72898); -#72897 = CARTESIAN_POINT('',(-0.8509,-0.127,1.4478)); -#72898 = VECTOR('',#72899,1.); -#72899 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72900 = PCURVE('',#72810,#72901); -#72901 = DEFINITIONAL_REPRESENTATION('',(#72902),#72905); -#72902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72903,#72904),.UNSPECIFIED., +#75209 = CARTESIAN_POINT('',(0.E+000,1.2192)); +#75210 = CARTESIAN_POINT('',(-4.440892098501E-015,1.226127272727)); +#75211 = CARTESIAN_POINT('',(-7.993605777301E-015,1.239981818182)); +#75212 = CARTESIAN_POINT('',(-6.217248937901E-015,1.260763636364)); +#75213 = CARTESIAN_POINT('',(-7.105427357601E-015,1.281545454545)); +#75214 = CARTESIAN_POINT('',(-6.217248937901E-015,1.302327272727)); +#75215 = CARTESIAN_POINT('',(-5.329070518201E-015,1.323109090909)); +#75216 = CARTESIAN_POINT('',(-7.993605777301E-015,1.343890909091)); +#75217 = CARTESIAN_POINT('',(-6.217248937901E-015,1.364672727273)); +#75218 = CARTESIAN_POINT('',(-7.105427357601E-015,1.385454545455)); +#75219 = CARTESIAN_POINT('',(-6.217248937901E-015,1.406236363636)); +#75220 = CARTESIAN_POINT('',(-6.217248937901E-015,1.427018181818)); +#75221 = CARTESIAN_POINT('',(-5.329070518201E-015,1.4478)); +#75222 = CARTESIAN_POINT('',(-7.105427357601E-015,1.468581818182)); +#75223 = CARTESIAN_POINT('',(-6.217248937901E-015,1.489363636364)); +#75224 = CARTESIAN_POINT('',(-6.217248937901E-015,1.510145454545)); +#75225 = CARTESIAN_POINT('',(-7.105427357601E-015,1.530927272727)); +#75226 = CARTESIAN_POINT('',(-5.329070518201E-015,1.551709090909)); +#75227 = CARTESIAN_POINT('',(-5.329070518201E-015,1.572490909091)); +#75228 = CARTESIAN_POINT('',(-7.993605777301E-015,1.593272727273)); +#75229 = CARTESIAN_POINT('',(-5.329070518201E-015,1.614054545455)); +#75230 = CARTESIAN_POINT('',(-7.105427357601E-015,1.634836363636)); +#75231 = CARTESIAN_POINT('',(-6.217248937901E-015,1.655618181818)); +#75232 = CARTESIAN_POINT('',(-4.440892098501E-015,1.669472727273)); +#75233 = CARTESIAN_POINT('',(0.E+000,1.6764)); +#75234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75235 = ORIENTED_EDGE('',*,*,#75236,.T.); +#75236 = EDGE_CURVE('',#75185,#75110,#75237,.T.); +#75237 = SURFACE_CURVE('',#75238,(#75242,#75249),.PCURVE_S1.); +#75238 = LINE('',#75239,#75240); +#75239 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,0.2286)); +#75240 = VECTOR('',#75241,1.); +#75241 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#75242 = PCURVE('',#75126,#75243); +#75243 = DEFINITIONAL_REPRESENTATION('',(#75244),#75248); +#75244 = LINE('',#75245,#75246); +#75245 = CARTESIAN_POINT('',(-1.2192,0.E+000)); +#75246 = VECTOR('',#75247,1.); +#75247 = DIRECTION('',(0.E+000,-1.)); +#75248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75249 = PCURVE('',#74607,#75250); +#75250 = DEFINITIONAL_REPRESENTATION('',(#75251),#75255); +#75251 = LINE('',#75252,#75253); +#75252 = CARTESIAN_POINT('',(-0.232063454686,0.154932254901)); +#75253 = VECTOR('',#75254,1.); +#75254 = DIRECTION('',(0.E+000,-1.)); +#75255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75256 = ORIENTED_EDGE('',*,*,#75109,.T.); +#75257 = ORIENTED_EDGE('',*,*,#75258,.T.); +#75258 = EDGE_CURVE('',#75112,#75187,#75259,.T.); +#75259 = SURFACE_CURVE('',#75260,(#75264,#75271),.PCURVE_S1.); +#75260 = LINE('',#75261,#75262); +#75261 = CARTESIAN_POINT('',(-0.9779,-0.359803853849,-0.2286)); +#75262 = VECTOR('',#75263,1.); +#75263 = DIRECTION('',(0.E+000,1.,0.E+000)); +#75264 = PCURVE('',#75126,#75265); +#75265 = DEFINITIONAL_REPRESENTATION('',(#75266),#75270); +#75266 = LINE('',#75267,#75268); +#75267 = CARTESIAN_POINT('',(-1.6764,0.E+000)); +#75268 = VECTOR('',#75269,1.); +#75269 = DIRECTION('',(0.E+000,1.)); +#75270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75271 = PCURVE('',#74634,#75272); +#75272 = DEFINITIONAL_REPRESENTATION('',(#75273),#75277); +#75273 = LINE('',#75274,#75275); +#75274 = CARTESIAN_POINT('',(0.232063454686,0.154932254901)); +#75275 = VECTOR('',#75276,1.); +#75276 = DIRECTION('',(0.E+000,1.)); +#75277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75278 = ADVANCED_FACE('',(#75279),#75202,.F.); +#75279 = FACE_BOUND('',#75280,.F.); +#75280 = EDGE_LOOP('',(#75281,#75310,#75335,#75336)); +#75281 = ORIENTED_EDGE('',*,*,#75282,.T.); +#75282 = EDGE_CURVE('',#75283,#75285,#75287,.T.); +#75283 = VERTEX_POINT('',#75284); +#75284 = CARTESIAN_POINT('',(-0.8509,-0.127,0.2286)); +#75285 = VERTEX_POINT('',#75286); +#75286 = CARTESIAN_POINT('',(-0.8509,-0.127,-0.2286)); +#75287 = SURFACE_CURVE('',#75288,(#75292,#75298),.PCURVE_S1.); +#75288 = LINE('',#75289,#75290); +#75289 = CARTESIAN_POINT('',(-0.8509,-0.127,1.4478)); +#75290 = VECTOR('',#75291,1.); +#75291 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75292 = PCURVE('',#75202,#75293); +#75293 = DEFINITIONAL_REPRESENTATION('',(#75294),#75297); +#75294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75295,#75296),.UNSPECIFIED., .F.,.F.,(2,2),(1.2192,1.6764),.PIECEWISE_BEZIER_KNOTS.); -#72903 = CARTESIAN_POINT('',(1.570796326795,1.2192)); -#72904 = CARTESIAN_POINT('',(1.570796326795,1.6764)); -#72905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72906 = PCURVE('',#72907,#72912); -#72907 = PLANE('',#72908); -#72908 = AXIS2_PLACEMENT_3D('',#72909,#72910,#72911); -#72909 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.4478)); -#72910 = DIRECTION('',(0.E+000,1.,0.E+000)); -#72911 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72912 = DEFINITIONAL_REPRESENTATION('',(#72913),#72917); -#72913 = LINE('',#72914,#72915); -#72914 = CARTESIAN_POINT('',(0.E+000,-0.216548237879)); -#72915 = VECTOR('',#72916,1.); -#72916 = DIRECTION('',(-1.,0.E+000)); -#72917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72918 = ORIENTED_EDGE('',*,*,#72919,.F.); -#72919 = EDGE_CURVE('',#72795,#72893,#72920,.T.); -#72920 = SURFACE_CURVE('',#72921,(#72926,#72932),.PCURVE_S1.); -#72921 = CIRCLE('',#72922,0.127); -#72922 = AXIS2_PLACEMENT_3D('',#72923,#72924,#72925); -#72923 = CARTESIAN_POINT('',(-0.8509,-0.254,-0.2286)); -#72924 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72925 = DIRECTION('',(1.,8.537024980201E-016,0.E+000)); -#72926 = PCURVE('',#72810,#72927); -#72927 = DEFINITIONAL_REPRESENTATION('',(#72928),#72931); -#72928 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72929,#72930),.UNSPECIFIED., +#75295 = CARTESIAN_POINT('',(1.570796326795,1.2192)); +#75296 = CARTESIAN_POINT('',(1.570796326795,1.6764)); +#75297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75298 = PCURVE('',#75299,#75304); +#75299 = PLANE('',#75300); +#75300 = AXIS2_PLACEMENT_3D('',#75301,#75302,#75303); +#75301 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.4478)); +#75302 = DIRECTION('',(0.E+000,1.,0.E+000)); +#75303 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75304 = DEFINITIONAL_REPRESENTATION('',(#75305),#75309); +#75305 = LINE('',#75306,#75307); +#75306 = CARTESIAN_POINT('',(0.E+000,-0.216548237879)); +#75307 = VECTOR('',#75308,1.); +#75308 = DIRECTION('',(-1.,0.E+000)); +#75309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75310 = ORIENTED_EDGE('',*,*,#75311,.F.); +#75311 = EDGE_CURVE('',#75187,#75285,#75312,.T.); +#75312 = SURFACE_CURVE('',#75313,(#75318,#75324),.PCURVE_S1.); +#75313 = CIRCLE('',#75314,0.127); +#75314 = AXIS2_PLACEMENT_3D('',#75315,#75316,#75317); +#75315 = CARTESIAN_POINT('',(-0.8509,-0.254,-0.2286)); +#75316 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75317 = DIRECTION('',(1.,8.537024980201E-016,0.E+000)); +#75318 = PCURVE('',#75202,#75319); +#75319 = DEFINITIONAL_REPRESENTATION('',(#75320),#75323); +#75320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75321,#75322),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#72929 = CARTESIAN_POINT('',(0.E+000,1.6764)); -#72930 = CARTESIAN_POINT('',(1.570796326795,1.6764)); -#72931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#75321 = CARTESIAN_POINT('',(0.E+000,1.6764)); +#75322 = CARTESIAN_POINT('',(1.570796326795,1.6764)); +#75323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72932 = PCURVE('',#72242,#72933); -#72933 = DEFINITIONAL_REPRESENTATION('',(#72934),#72942); -#72934 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#72935,#72936,#72937,#72938 - ,#72939,#72940,#72941),.UNSPECIFIED.,.T.,.F.) +#75324 = PCURVE('',#74634,#75325); +#75325 = DEFINITIONAL_REPRESENTATION('',(#75326),#75334); +#75326 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#75327,#75328,#75329,#75330 + ,#75331,#75332,#75333),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#72935 = CARTESIAN_POINT('',(0.486063454686,0.26073610875)); -#72936 = CARTESIAN_POINT('',(0.486063454686,4.076565618857E-002)); -#72937 = CARTESIAN_POINT('',(0.295563454686,0.150750882469)); -#72938 = CARTESIAN_POINT('',(0.105063454686,0.26073610875)); -#72939 = CARTESIAN_POINT('',(0.295563454686,0.37072133503)); -#72940 = CARTESIAN_POINT('',(0.486063454686,0.480706561311)); -#72941 = CARTESIAN_POINT('',(0.486063454686,0.26073610875)); -#72942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72943 = ORIENTED_EDGE('',*,*,#72792,.F.); -#72944 = ORIENTED_EDGE('',*,*,#72945,.F.); -#72945 = EDGE_CURVE('',#72891,#72793,#72946,.T.); -#72946 = SURFACE_CURVE('',#72947,(#72952,#72958),.PCURVE_S1.); -#72947 = CIRCLE('',#72948,0.127); -#72948 = AXIS2_PLACEMENT_3D('',#72949,#72950,#72951); -#72949 = CARTESIAN_POINT('',(-0.8509,-0.254,0.2286)); -#72950 = DIRECTION('',(0.E+000,0.E+000,1.)); -#72951 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#72952 = PCURVE('',#72810,#72953); -#72953 = DEFINITIONAL_REPRESENTATION('',(#72954),#72957); -#72954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#72955,#72956),.UNSPECIFIED., +#75327 = CARTESIAN_POINT('',(0.486063454686,0.26073610875)); +#75328 = CARTESIAN_POINT('',(0.486063454686,4.076565618857E-002)); +#75329 = CARTESIAN_POINT('',(0.295563454686,0.150750882469)); +#75330 = CARTESIAN_POINT('',(0.105063454686,0.26073610875)); +#75331 = CARTESIAN_POINT('',(0.295563454686,0.37072133503)); +#75332 = CARTESIAN_POINT('',(0.486063454686,0.480706561311)); +#75333 = CARTESIAN_POINT('',(0.486063454686,0.26073610875)); +#75334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75335 = ORIENTED_EDGE('',*,*,#75184,.F.); +#75336 = ORIENTED_EDGE('',*,*,#75337,.F.); +#75337 = EDGE_CURVE('',#75283,#75185,#75338,.T.); +#75338 = SURFACE_CURVE('',#75339,(#75344,#75350),.PCURVE_S1.); +#75339 = CIRCLE('',#75340,0.127); +#75340 = AXIS2_PLACEMENT_3D('',#75341,#75342,#75343); +#75341 = CARTESIAN_POINT('',(-0.8509,-0.254,0.2286)); +#75342 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75343 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75344 = PCURVE('',#75202,#75345); +#75345 = DEFINITIONAL_REPRESENTATION('',(#75346),#75349); +#75346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75347,#75348),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#72955 = CARTESIAN_POINT('',(1.570796326795,1.2192)); -#72956 = CARTESIAN_POINT('',(0.E+000,1.2192)); -#72957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#75347 = CARTESIAN_POINT('',(1.570796326795,1.2192)); +#75348 = CARTESIAN_POINT('',(0.E+000,1.2192)); +#75349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#72958 = PCURVE('',#72215,#72959); -#72959 = DEFINITIONAL_REPRESENTATION('',(#72960),#72968); -#72960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#72961,#72962,#72963,#72964 - ,#72965,#72966,#72967),.UNSPECIFIED.,.F.,.F.) +#75350 = PCURVE('',#74607,#75351); +#75351 = DEFINITIONAL_REPRESENTATION('',(#75352),#75360); +#75352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#75353,#75354,#75355,#75356 + ,#75357,#75358,#75359),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#72961 = CARTESIAN_POINT('',(-0.232063454686,0.26073610875)); -#72962 = CARTESIAN_POINT('',(-0.232063454686,4.076565618857E-002)); -#72963 = CARTESIAN_POINT('',(-0.422563454686,0.150750882469)); -#72964 = CARTESIAN_POINT('',(-0.613063454686,0.26073610875)); -#72965 = CARTESIAN_POINT('',(-0.422563454686,0.37072133503)); -#72966 = CARTESIAN_POINT('',(-0.232063454686,0.480706561311)); -#72967 = CARTESIAN_POINT('',(-0.232063454686,0.26073610875)); -#72968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72969 = ADVANCED_FACE('',(#72970),#72907,.F.); -#72970 = FACE_BOUND('',#72971,.T.); -#72971 = EDGE_LOOP('',(#72972,#73002,#73030,#73053,#73074,#73075,#73098, - #73121)); -#72972 = ORIENTED_EDGE('',*,*,#72973,.F.); -#72973 = EDGE_CURVE('',#72974,#72976,#72978,.T.); -#72974 = VERTEX_POINT('',#72975); -#72975 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.438919294883)); -#72976 = VERTEX_POINT('',#72977); -#72977 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-1.438919294883)); -#72978 = SURFACE_CURVE('',#72979,(#72983,#72990),.PCURVE_S1.); -#72979 = LINE('',#72980,#72981); -#72980 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.4478)); -#72981 = VECTOR('',#72982,1.); -#72982 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#72983 = PCURVE('',#72907,#72984); -#72984 = DEFINITIONAL_REPRESENTATION('',(#72985),#72989); -#72985 = LINE('',#72986,#72987); -#72986 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#72987 = VECTOR('',#72988,1.); -#72988 = DIRECTION('',(-1.,0.E+000)); -#72989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#72990 = PCURVE('',#72991,#72996); -#72991 = PLANE('',#72992); -#72992 = AXIS2_PLACEMENT_3D('',#72993,#72994,#72995); -#72993 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.4478)); -#72994 = DIRECTION('',(0.994521895368,0.104528463268,0.E+000)); -#72995 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); -#72996 = DEFINITIONAL_REPRESENTATION('',(#72997),#73001); -#72997 = LINE('',#72998,#72999); -#72998 = CARTESIAN_POINT('',(0.357558744213,0.E+000)); -#72999 = VECTOR('',#73000,1.); -#73000 = DIRECTION('',(0.E+000,-1.)); -#73001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73002 = ORIENTED_EDGE('',*,*,#73003,.T.); -#73003 = EDGE_CURVE('',#72974,#73004,#73006,.T.); -#73004 = VERTEX_POINT('',#73005); -#73005 = CARTESIAN_POINT('',(-0.6477,-0.127,1.438919294883)); -#73006 = SURFACE_CURVE('',#73007,(#73011,#73018),.PCURVE_S1.); -#73007 = LINE('',#73008,#73009); -#73008 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.438919294883)); -#73009 = VECTOR('',#73010,1.); -#73010 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73011 = PCURVE('',#72907,#73012); -#73012 = DEFINITIONAL_REPRESENTATION('',(#73013),#73017); -#73013 = LINE('',#73014,#73015); -#73014 = CARTESIAN_POINT('',(-8.880705116825E-003,0.E+000)); -#73015 = VECTOR('',#73016,1.); -#73016 = DIRECTION('',(0.E+000,-1.)); -#73017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73018 = PCURVE('',#73019,#73024); -#73019 = PLANE('',#73020); -#73020 = AXIS2_PLACEMENT_3D('',#73021,#73022,#73023); -#73021 = CARTESIAN_POINT('',(-0.762,3.903127820948E-015,1.4478)); -#73022 = DIRECTION('',(0.E+000,6.975647374412E-002,-0.99756405026)); -#73023 = DIRECTION('',(0.E+000,0.99756405026,6.975647374412E-002)); -#73024 = DEFINITIONAL_REPRESENTATION('',(#73025),#73029); -#73025 = LINE('',#73026,#73027); -#73026 = CARTESIAN_POINT('',(-0.127310121056,0.127648237879)); -#73027 = VECTOR('',#73028,1.); -#73028 = DIRECTION('',(0.E+000,-1.)); -#73029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73030 = ORIENTED_EDGE('',*,*,#73031,.T.); -#73031 = EDGE_CURVE('',#73004,#73032,#73034,.T.); -#73032 = VERTEX_POINT('',#73033); -#73033 = CARTESIAN_POINT('',(-0.6477,-0.127,0.2286)); -#73034 = SURFACE_CURVE('',#73035,(#73039,#73046),.PCURVE_S1.); -#73035 = LINE('',#73036,#73037); -#73036 = CARTESIAN_POINT('',(-0.6477,-0.127,1.4478)); -#73037 = VECTOR('',#73038,1.); -#73038 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73039 = PCURVE('',#72907,#73040); -#73040 = DEFINITIONAL_REPRESENTATION('',(#73041),#73045); -#73041 = LINE('',#73042,#73043); -#73042 = CARTESIAN_POINT('',(0.E+000,-1.334823787874E-002)); -#73043 = VECTOR('',#73044,1.); -#73044 = DIRECTION('',(-1.,0.E+000)); -#73045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73046 = PCURVE('',#72131,#73047); -#73047 = DEFINITIONAL_REPRESENTATION('',(#73048),#73052); -#73048 = LINE('',#73049,#73050); -#73049 = CARTESIAN_POINT('',(0.E+000,0.38773610875)); -#73050 = VECTOR('',#73051,1.); -#73051 = DIRECTION('',(1.,0.E+000)); -#73052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73053 = ORIENTED_EDGE('',*,*,#73054,.T.); -#73054 = EDGE_CURVE('',#73032,#72891,#73055,.T.); -#73055 = SURFACE_CURVE('',#73056,(#73060,#73067),.PCURVE_S1.); -#73056 = LINE('',#73057,#73058); -#73057 = CARTESIAN_POINT('',(-0.634351762121,-0.127,0.2286)); -#73058 = VECTOR('',#73059,1.); -#73059 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73060 = PCURVE('',#72907,#73061); -#73061 = DEFINITIONAL_REPRESENTATION('',(#73062),#73066); -#73062 = LINE('',#73063,#73064); -#73063 = CARTESIAN_POINT('',(-1.2192,0.E+000)); -#73064 = VECTOR('',#73065,1.); -#73065 = DIRECTION('',(0.E+000,-1.)); -#73066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73067 = PCURVE('',#72215,#73068); -#73068 = DEFINITIONAL_REPRESENTATION('',(#73069),#73073); -#73069 = LINE('',#73070,#73071); -#73070 = CARTESIAN_POINT('',(-0.575611692565,0.38773610875)); -#73071 = VECTOR('',#73072,1.); -#73072 = DIRECTION('',(1.,0.E+000)); -#73073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73074 = ORIENTED_EDGE('',*,*,#72890,.T.); -#73075 = ORIENTED_EDGE('',*,*,#73076,.T.); -#73076 = EDGE_CURVE('',#72893,#73077,#73079,.T.); -#73077 = VERTEX_POINT('',#73078); -#73078 = CARTESIAN_POINT('',(-0.6477,-0.127,-0.2286)); -#73079 = SURFACE_CURVE('',#73080,(#73084,#73091),.PCURVE_S1.); -#73080 = LINE('',#73081,#73082); -#73081 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-0.2286)); -#73082 = VECTOR('',#73083,1.); -#73083 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73084 = PCURVE('',#72907,#73085); -#73085 = DEFINITIONAL_REPRESENTATION('',(#73086),#73090); -#73086 = LINE('',#73087,#73088); -#73087 = CARTESIAN_POINT('',(-1.6764,0.E+000)); -#73088 = VECTOR('',#73089,1.); -#73089 = DIRECTION('',(0.E+000,1.)); -#73090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73091 = PCURVE('',#72242,#73092); -#73092 = DEFINITIONAL_REPRESENTATION('',(#73093),#73097); -#73093 = LINE('',#73094,#73095); -#73094 = CARTESIAN_POINT('',(0.575611692565,0.38773610875)); -#73095 = VECTOR('',#73096,1.); -#73096 = DIRECTION('',(1.,0.E+000)); -#73097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73098 = ORIENTED_EDGE('',*,*,#73099,.T.); -#73099 = EDGE_CURVE('',#73077,#73100,#73102,.T.); -#73100 = VERTEX_POINT('',#73101); -#73101 = CARTESIAN_POINT('',(-0.6477,-0.127,-1.438919294883)); -#73102 = SURFACE_CURVE('',#73103,(#73107,#73114),.PCURVE_S1.); -#73103 = LINE('',#73104,#73105); -#73104 = CARTESIAN_POINT('',(-0.6477,-0.127,1.4478)); -#73105 = VECTOR('',#73106,1.); -#73106 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73107 = PCURVE('',#72907,#73108); -#73108 = DEFINITIONAL_REPRESENTATION('',(#73109),#73113); -#73109 = LINE('',#73110,#73111); -#73110 = CARTESIAN_POINT('',(0.E+000,-1.334823787874E-002)); -#73111 = VECTOR('',#73112,1.); -#73112 = DIRECTION('',(-1.,0.E+000)); -#73113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73114 = PCURVE('',#72075,#73115); -#73115 = DEFINITIONAL_REPRESENTATION('',(#73116),#73120); -#73116 = LINE('',#73117,#73118); -#73117 = CARTESIAN_POINT('',(-2.8956,0.38773610875)); -#73118 = VECTOR('',#73119,1.); -#73119 = DIRECTION('',(1.,0.E+000)); -#73120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73121 = ORIENTED_EDGE('',*,*,#73122,.T.); -#73122 = EDGE_CURVE('',#73100,#72976,#73123,.T.); -#73123 = SURFACE_CURVE('',#73124,(#73128,#73135),.PCURVE_S1.); -#73124 = LINE('',#73125,#73126); -#73125 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-1.438919294883)); -#73126 = VECTOR('',#73127,1.); -#73127 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73128 = PCURVE('',#72907,#73129); -#73129 = DEFINITIONAL_REPRESENTATION('',(#73130),#73134); -#73130 = LINE('',#73131,#73132); -#73131 = CARTESIAN_POINT('',(-2.886719294883,0.E+000)); -#73132 = VECTOR('',#73133,1.); -#73133 = DIRECTION('',(0.E+000,1.)); -#73134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73135 = PCURVE('',#73136,#73141); -#73136 = PLANE('',#73137); -#73137 = AXIS2_PLACEMENT_3D('',#73138,#73139,#73140); -#73138 = CARTESIAN_POINT('',(-0.762,4.336808689942E-015,-1.4478)); -#73139 = DIRECTION('',(0.E+000,6.975647374412E-002,0.99756405026)); -#73140 = DIRECTION('',(0.E+000,-0.99756405026,6.975647374412E-002)); -#73141 = DEFINITIONAL_REPRESENTATION('',(#73142),#73146); -#73142 = LINE('',#73143,#73144); -#73143 = CARTESIAN_POINT('',(0.127310121056,0.127648237879)); -#73144 = VECTOR('',#73145,1.); -#73145 = DIRECTION('',(0.E+000,1.)); -#73146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73147 = ADVANCED_FACE('',(#73148),#72991,.F.); -#73148 = FACE_BOUND('',#73149,.T.); -#73149 = EDGE_LOOP('',(#73150,#73180,#73201,#73202)); -#73150 = ORIENTED_EDGE('',*,*,#73151,.F.); -#73151 = EDGE_CURVE('',#73152,#73154,#73156,.T.); -#73152 = VERTEX_POINT('',#73153); -#73153 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.414053320556)); -#73154 = VERTEX_POINT('',#73155); -#73155 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,-1.414053320556)); -#73156 = SURFACE_CURVE('',#73157,(#73161,#73168),.PCURVE_S1.); -#73157 = LINE('',#73158,#73159); -#73158 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.4478)); -#73159 = VECTOR('',#73160,1.); -#73160 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73161 = PCURVE('',#72991,#73162); -#73162 = DEFINITIONAL_REPRESENTATION('',(#73163),#73167); -#73163 = LINE('',#73164,#73165); -#73164 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73165 = VECTOR('',#73166,1.); -#73166 = DIRECTION('',(0.E+000,-1.)); -#73167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73168 = PCURVE('',#73169,#73174); -#73169 = PLANE('',#73170); -#73170 = AXIS2_PLACEMENT_3D('',#73171,#73172,#73173); -#73171 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.4478)); -#73172 = DIRECTION('',(0.E+000,1.,0.E+000)); -#73173 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73174 = DEFINITIONAL_REPRESENTATION('',(#73175),#73179); -#73175 = LINE('',#73176,#73177); -#73176 = CARTESIAN_POINT('',(0.E+000,-1.193953392122)); -#73177 = VECTOR('',#73178,1.); -#73178 = DIRECTION('',(-1.,0.E+000)); -#73179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73180 = ORIENTED_EDGE('',*,*,#73181,.T.); -#73181 = EDGE_CURVE('',#73152,#72974,#73182,.T.); -#73182 = SURFACE_CURVE('',#73183,(#73187,#73194),.PCURVE_S1.); -#73183 = LINE('',#73184,#73185); -#73184 = CARTESIAN_POINT('',(-0.597220830113,-0.480277219652, +#75353 = CARTESIAN_POINT('',(-0.232063454686,0.26073610875)); +#75354 = CARTESIAN_POINT('',(-0.232063454686,4.076565618857E-002)); +#75355 = CARTESIAN_POINT('',(-0.422563454686,0.150750882469)); +#75356 = CARTESIAN_POINT('',(-0.613063454686,0.26073610875)); +#75357 = CARTESIAN_POINT('',(-0.422563454686,0.37072133503)); +#75358 = CARTESIAN_POINT('',(-0.232063454686,0.480706561311)); +#75359 = CARTESIAN_POINT('',(-0.232063454686,0.26073610875)); +#75360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75361 = ADVANCED_FACE('',(#75362),#75299,.F.); +#75362 = FACE_BOUND('',#75363,.T.); +#75363 = EDGE_LOOP('',(#75364,#75394,#75422,#75445,#75466,#75467,#75490, + #75513)); +#75364 = ORIENTED_EDGE('',*,*,#75365,.F.); +#75365 = EDGE_CURVE('',#75366,#75368,#75370,.T.); +#75366 = VERTEX_POINT('',#75367); +#75367 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.438919294883)); +#75368 = VERTEX_POINT('',#75369); +#75369 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-1.438919294883)); +#75370 = SURFACE_CURVE('',#75371,(#75375,#75382),.PCURVE_S1.); +#75371 = LINE('',#75372,#75373); +#75372 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.4478)); +#75373 = VECTOR('',#75374,1.); +#75374 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75375 = PCURVE('',#75299,#75376); +#75376 = DEFINITIONAL_REPRESENTATION('',(#75377),#75381); +#75377 = LINE('',#75378,#75379); +#75378 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75379 = VECTOR('',#75380,1.); +#75380 = DIRECTION('',(-1.,0.E+000)); +#75381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75382 = PCURVE('',#75383,#75388); +#75383 = PLANE('',#75384); +#75384 = AXIS2_PLACEMENT_3D('',#75385,#75386,#75387); +#75385 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.4478)); +#75386 = DIRECTION('',(0.994521895368,0.104528463268,0.E+000)); +#75387 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); +#75388 = DEFINITIONAL_REPRESENTATION('',(#75389),#75393); +#75389 = LINE('',#75390,#75391); +#75390 = CARTESIAN_POINT('',(0.357558744213,0.E+000)); +#75391 = VECTOR('',#75392,1.); +#75392 = DIRECTION('',(0.E+000,-1.)); +#75393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75394 = ORIENTED_EDGE('',*,*,#75395,.T.); +#75395 = EDGE_CURVE('',#75366,#75396,#75398,.T.); +#75396 = VERTEX_POINT('',#75397); +#75397 = CARTESIAN_POINT('',(-0.6477,-0.127,1.438919294883)); +#75398 = SURFACE_CURVE('',#75399,(#75403,#75410),.PCURVE_S1.); +#75399 = LINE('',#75400,#75401); +#75400 = CARTESIAN_POINT('',(-0.634351762121,-0.127,1.438919294883)); +#75401 = VECTOR('',#75402,1.); +#75402 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75403 = PCURVE('',#75299,#75404); +#75404 = DEFINITIONAL_REPRESENTATION('',(#75405),#75409); +#75405 = LINE('',#75406,#75407); +#75406 = CARTESIAN_POINT('',(-8.880705116825E-003,0.E+000)); +#75407 = VECTOR('',#75408,1.); +#75408 = DIRECTION('',(0.E+000,-1.)); +#75409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75410 = PCURVE('',#75411,#75416); +#75411 = PLANE('',#75412); +#75412 = AXIS2_PLACEMENT_3D('',#75413,#75414,#75415); +#75413 = CARTESIAN_POINT('',(-0.762,3.903127820948E-015,1.4478)); +#75414 = DIRECTION('',(0.E+000,6.975647374412E-002,-0.99756405026)); +#75415 = DIRECTION('',(0.E+000,0.99756405026,6.975647374412E-002)); +#75416 = DEFINITIONAL_REPRESENTATION('',(#75417),#75421); +#75417 = LINE('',#75418,#75419); +#75418 = CARTESIAN_POINT('',(-0.127310121056,0.127648237879)); +#75419 = VECTOR('',#75420,1.); +#75420 = DIRECTION('',(0.E+000,-1.)); +#75421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75422 = ORIENTED_EDGE('',*,*,#75423,.T.); +#75423 = EDGE_CURVE('',#75396,#75424,#75426,.T.); +#75424 = VERTEX_POINT('',#75425); +#75425 = CARTESIAN_POINT('',(-0.6477,-0.127,0.2286)); +#75426 = SURFACE_CURVE('',#75427,(#75431,#75438),.PCURVE_S1.); +#75427 = LINE('',#75428,#75429); +#75428 = CARTESIAN_POINT('',(-0.6477,-0.127,1.4478)); +#75429 = VECTOR('',#75430,1.); +#75430 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75431 = PCURVE('',#75299,#75432); +#75432 = DEFINITIONAL_REPRESENTATION('',(#75433),#75437); +#75433 = LINE('',#75434,#75435); +#75434 = CARTESIAN_POINT('',(0.E+000,-1.334823787874E-002)); +#75435 = VECTOR('',#75436,1.); +#75436 = DIRECTION('',(-1.,0.E+000)); +#75437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75438 = PCURVE('',#74523,#75439); +#75439 = DEFINITIONAL_REPRESENTATION('',(#75440),#75444); +#75440 = LINE('',#75441,#75442); +#75441 = CARTESIAN_POINT('',(0.E+000,0.38773610875)); +#75442 = VECTOR('',#75443,1.); +#75443 = DIRECTION('',(1.,0.E+000)); +#75444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75445 = ORIENTED_EDGE('',*,*,#75446,.T.); +#75446 = EDGE_CURVE('',#75424,#75283,#75447,.T.); +#75447 = SURFACE_CURVE('',#75448,(#75452,#75459),.PCURVE_S1.); +#75448 = LINE('',#75449,#75450); +#75449 = CARTESIAN_POINT('',(-0.634351762121,-0.127,0.2286)); +#75450 = VECTOR('',#75451,1.); +#75451 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75452 = PCURVE('',#75299,#75453); +#75453 = DEFINITIONAL_REPRESENTATION('',(#75454),#75458); +#75454 = LINE('',#75455,#75456); +#75455 = CARTESIAN_POINT('',(-1.2192,0.E+000)); +#75456 = VECTOR('',#75457,1.); +#75457 = DIRECTION('',(0.E+000,-1.)); +#75458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75459 = PCURVE('',#74607,#75460); +#75460 = DEFINITIONAL_REPRESENTATION('',(#75461),#75465); +#75461 = LINE('',#75462,#75463); +#75462 = CARTESIAN_POINT('',(-0.575611692565,0.38773610875)); +#75463 = VECTOR('',#75464,1.); +#75464 = DIRECTION('',(1.,0.E+000)); +#75465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75466 = ORIENTED_EDGE('',*,*,#75282,.T.); +#75467 = ORIENTED_EDGE('',*,*,#75468,.T.); +#75468 = EDGE_CURVE('',#75285,#75469,#75471,.T.); +#75469 = VERTEX_POINT('',#75470); +#75470 = CARTESIAN_POINT('',(-0.6477,-0.127,-0.2286)); +#75471 = SURFACE_CURVE('',#75472,(#75476,#75483),.PCURVE_S1.); +#75472 = LINE('',#75473,#75474); +#75473 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-0.2286)); +#75474 = VECTOR('',#75475,1.); +#75475 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75476 = PCURVE('',#75299,#75477); +#75477 = DEFINITIONAL_REPRESENTATION('',(#75478),#75482); +#75478 = LINE('',#75479,#75480); +#75479 = CARTESIAN_POINT('',(-1.6764,0.E+000)); +#75480 = VECTOR('',#75481,1.); +#75481 = DIRECTION('',(0.E+000,1.)); +#75482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75483 = PCURVE('',#74634,#75484); +#75484 = DEFINITIONAL_REPRESENTATION('',(#75485),#75489); +#75485 = LINE('',#75486,#75487); +#75486 = CARTESIAN_POINT('',(0.575611692565,0.38773610875)); +#75487 = VECTOR('',#75488,1.); +#75488 = DIRECTION('',(1.,0.E+000)); +#75489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75490 = ORIENTED_EDGE('',*,*,#75491,.T.); +#75491 = EDGE_CURVE('',#75469,#75492,#75494,.T.); +#75492 = VERTEX_POINT('',#75493); +#75493 = CARTESIAN_POINT('',(-0.6477,-0.127,-1.438919294883)); +#75494 = SURFACE_CURVE('',#75495,(#75499,#75506),.PCURVE_S1.); +#75495 = LINE('',#75496,#75497); +#75496 = CARTESIAN_POINT('',(-0.6477,-0.127,1.4478)); +#75497 = VECTOR('',#75498,1.); +#75498 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75499 = PCURVE('',#75299,#75500); +#75500 = DEFINITIONAL_REPRESENTATION('',(#75501),#75505); +#75501 = LINE('',#75502,#75503); +#75502 = CARTESIAN_POINT('',(0.E+000,-1.334823787874E-002)); +#75503 = VECTOR('',#75504,1.); +#75504 = DIRECTION('',(-1.,0.E+000)); +#75505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75506 = PCURVE('',#74467,#75507); +#75507 = DEFINITIONAL_REPRESENTATION('',(#75508),#75512); +#75508 = LINE('',#75509,#75510); +#75509 = CARTESIAN_POINT('',(-2.8956,0.38773610875)); +#75510 = VECTOR('',#75511,1.); +#75511 = DIRECTION('',(1.,0.E+000)); +#75512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75513 = ORIENTED_EDGE('',*,*,#75514,.T.); +#75514 = EDGE_CURVE('',#75492,#75368,#75515,.T.); +#75515 = SURFACE_CURVE('',#75516,(#75520,#75527),.PCURVE_S1.); +#75516 = LINE('',#75517,#75518); +#75517 = CARTESIAN_POINT('',(-0.634351762121,-0.127,-1.438919294883)); +#75518 = VECTOR('',#75519,1.); +#75519 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75520 = PCURVE('',#75299,#75521); +#75521 = DEFINITIONAL_REPRESENTATION('',(#75522),#75526); +#75522 = LINE('',#75523,#75524); +#75523 = CARTESIAN_POINT('',(-2.886719294883,0.E+000)); +#75524 = VECTOR('',#75525,1.); +#75525 = DIRECTION('',(0.E+000,1.)); +#75526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75527 = PCURVE('',#75528,#75533); +#75528 = PLANE('',#75529); +#75529 = AXIS2_PLACEMENT_3D('',#75530,#75531,#75532); +#75530 = CARTESIAN_POINT('',(-0.762,4.336808689942E-015,-1.4478)); +#75531 = DIRECTION('',(0.E+000,6.975647374412E-002,0.99756405026)); +#75532 = DIRECTION('',(0.E+000,-0.99756405026,6.975647374412E-002)); +#75533 = DEFINITIONAL_REPRESENTATION('',(#75534),#75538); +#75534 = LINE('',#75535,#75536); +#75535 = CARTESIAN_POINT('',(0.127310121056,0.127648237879)); +#75536 = VECTOR('',#75537,1.); +#75537 = DIRECTION('',(0.E+000,1.)); +#75538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75539 = ADVANCED_FACE('',(#75540),#75383,.F.); +#75540 = FACE_BOUND('',#75541,.T.); +#75541 = EDGE_LOOP('',(#75542,#75572,#75593,#75594)); +#75542 = ORIENTED_EDGE('',*,*,#75543,.F.); +#75543 = EDGE_CURVE('',#75544,#75546,#75548,.T.); +#75544 = VERTEX_POINT('',#75545); +#75545 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.414053320556)); +#75546 = VERTEX_POINT('',#75547); +#75547 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,-1.414053320556)); +#75548 = SURFACE_CURVE('',#75549,(#75553,#75560),.PCURVE_S1.); +#75549 = LINE('',#75550,#75551); +#75550 = CARTESIAN_POINT('',(-0.596976696061,-0.4826,1.4478)); +#75551 = VECTOR('',#75552,1.); +#75552 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75553 = PCURVE('',#75383,#75554); +#75554 = DEFINITIONAL_REPRESENTATION('',(#75555),#75559); +#75555 = LINE('',#75556,#75557); +#75556 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75557 = VECTOR('',#75558,1.); +#75558 = DIRECTION('',(0.E+000,-1.)); +#75559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75560 = PCURVE('',#75561,#75566); +#75561 = PLANE('',#75562); +#75562 = AXIS2_PLACEMENT_3D('',#75563,#75564,#75565); +#75563 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.4478)); +#75564 = DIRECTION('',(0.E+000,1.,0.E+000)); +#75565 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75566 = DEFINITIONAL_REPRESENTATION('',(#75567),#75571); +#75567 = LINE('',#75568,#75569); +#75568 = CARTESIAN_POINT('',(0.E+000,-1.193953392122)); +#75569 = VECTOR('',#75570,1.); +#75570 = DIRECTION('',(-1.,0.E+000)); +#75571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75572 = ORIENTED_EDGE('',*,*,#75573,.T.); +#75573 = EDGE_CURVE('',#75544,#75366,#75574,.T.); +#75574 = SURFACE_CURVE('',#75575,(#75579,#75586),.PCURVE_S1.); +#75575 = LINE('',#75576,#75577); +#75576 = CARTESIAN_POINT('',(-0.597220830113,-0.480277219652, 1.414215745181)); -#73185 = VECTOR('',#73186,1.); -#73186 = DIRECTION('',(-0.104276609233,0.992125664297,6.93761847516E-002 +#75577 = VECTOR('',#75578,1.); +#75578 = DIRECTION('',(-0.104276609233,0.992125664297,6.93761847516E-002 )); -#73187 = PCURVE('',#72991,#73188); -#73188 = DEFINITIONAL_REPRESENTATION('',(#73189),#73193); -#73189 = LINE('',#73190,#73191); -#73190 = CARTESIAN_POINT('',(2.33557487168E-003,-3.358425481934E-002)); -#73191 = VECTOR('',#73192,1.); -#73192 = DIRECTION('',(0.997590569818,6.93761847516E-002)); -#73193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73194 = PCURVE('',#73019,#73195); -#73195 = DEFINITIONAL_REPRESENTATION('',(#73196),#73200); -#73196 = LINE('',#73197,#73198); -#73197 = CARTESIAN_POINT('',(-0.481450007673,0.164779169887)); -#73198 = VECTOR('',#73199,1.); -#73199 = DIRECTION('',(0.994548334053,-0.104276609233)); -#73200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73201 = ORIENTED_EDGE('',*,*,#72973,.T.); -#73202 = ORIENTED_EDGE('',*,*,#73203,.T.); -#73203 = EDGE_CURVE('',#72976,#73154,#73204,.T.); -#73204 = SURFACE_CURVE('',#73205,(#73209,#73216),.PCURVE_S1.); -#73205 = LINE('',#73206,#73207); -#73206 = CARTESIAN_POINT('',(-0.5762731525,-0.679581058932, +#75579 = PCURVE('',#75383,#75580); +#75580 = DEFINITIONAL_REPRESENTATION('',(#75581),#75585); +#75581 = LINE('',#75582,#75583); +#75582 = CARTESIAN_POINT('',(2.33557487168E-003,-3.358425481934E-002)); +#75583 = VECTOR('',#75584,1.); +#75584 = DIRECTION('',(0.997590569818,6.93761847516E-002)); +#75585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75586 = PCURVE('',#75411,#75587); +#75587 = DEFINITIONAL_REPRESENTATION('',(#75588),#75592); +#75588 = LINE('',#75589,#75590); +#75589 = CARTESIAN_POINT('',(-0.481450007673,0.164779169887)); +#75590 = VECTOR('',#75591,1.); +#75591 = DIRECTION('',(0.994548334053,-0.104276609233)); +#75592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75593 = ORIENTED_EDGE('',*,*,#75365,.T.); +#75594 = ORIENTED_EDGE('',*,*,#75595,.T.); +#75595 = EDGE_CURVE('',#75368,#75546,#75596,.T.); +#75596 = SURFACE_CURVE('',#75597,(#75601,#75608),.PCURVE_S1.); +#75597 = LINE('',#75598,#75599); +#75598 = CARTESIAN_POINT('',(-0.5762731525,-0.679581058932, -1.400279063092)); -#73207 = VECTOR('',#73208,1.); -#73208 = DIRECTION('',(0.104276609233,-0.992125664297,6.93761847516E-002 +#75599 = VECTOR('',#75600,1.); +#75600 = DIRECTION('',(0.104276609233,-0.992125664297,6.93761847516E-002 )); -#73209 = PCURVE('',#72991,#73210); -#73210 = DEFINITIONAL_REPRESENTATION('',(#73211),#73215); -#73211 = LINE('',#73212,#73213); -#73212 = CARTESIAN_POINT('',(-0.198066085673,-2.848079063092)); -#73213 = VECTOR('',#73214,1.); -#73214 = DIRECTION('',(-0.997590569818,6.93761847516E-002)); -#73215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73216 = PCURVE('',#73136,#73217); -#73217 = DEFINITIONAL_REPRESENTATION('',(#73218),#73222); -#73218 = LINE('',#73219,#73220); -#73219 = CARTESIAN_POINT('',(0.681240526616,0.1857268475)); -#73220 = VECTOR('',#73221,1.); -#73221 = DIRECTION('',(0.994548334053,0.104276609233)); -#73222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73223 = ADVANCED_FACE('',(#73224),#73169,.F.); -#73224 = FACE_BOUND('',#73225,.T.); -#73225 = EDGE_LOOP('',(#73226,#73256,#73277,#73278)); -#73226 = ORIENTED_EDGE('',*,*,#73227,.F.); -#73227 = EDGE_CURVE('',#73228,#73230,#73232,.T.); -#73228 = VERTEX_POINT('',#73229); -#73229 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.414053320556)); -#73230 = VERTEX_POINT('',#73231); -#73231 = CARTESIAN_POINT('',(0.596976696061,-0.4826,-1.414053320556)); -#73232 = SURFACE_CURVE('',#73233,(#73237,#73244),.PCURVE_S1.); -#73233 = LINE('',#73234,#73235); -#73234 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.4478)); -#73235 = VECTOR('',#73236,1.); -#73236 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73237 = PCURVE('',#73169,#73238); -#73238 = DEFINITIONAL_REPRESENTATION('',(#73239),#73243); -#73239 = LINE('',#73240,#73241); -#73240 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73241 = VECTOR('',#73242,1.); -#73242 = DIRECTION('',(-1.,0.E+000)); -#73243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73244 = PCURVE('',#73245,#73250); -#73245 = PLANE('',#73246); -#73246 = AXIS2_PLACEMENT_3D('',#73247,#73248,#73249); -#73247 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); -#73248 = DIRECTION('',(-0.994521895368,0.104528463268,0.E+000)); -#73249 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#73250 = DEFINITIONAL_REPRESENTATION('',(#73251),#73255); -#73251 = LINE('',#73252,#73253); -#73252 = CARTESIAN_POINT('',(0.357558744213,0.E+000)); -#73253 = VECTOR('',#73254,1.); -#73254 = DIRECTION('',(0.E+000,-1.)); -#73255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73256 = ORIENTED_EDGE('',*,*,#73257,.F.); -#73257 = EDGE_CURVE('',#73152,#73228,#73258,.T.); -#73258 = SURFACE_CURVE('',#73259,(#73263,#73270),.PCURVE_S1.); -#73259 = LINE('',#73260,#73261); -#73260 = CARTESIAN_POINT('',(-0.762,-0.4826,1.414053320556)); -#73261 = VECTOR('',#73262,1.); -#73262 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73263 = PCURVE('',#73169,#73264); -#73264 = DEFINITIONAL_REPRESENTATION('',(#73265),#73269); -#73265 = LINE('',#73266,#73267); -#73266 = CARTESIAN_POINT('',(-3.374667944393E-002,-1.358976696061)); -#73267 = VECTOR('',#73268,1.); -#73268 = DIRECTION('',(0.E+000,1.)); -#73269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73270 = PCURVE('',#73019,#73271); -#73271 = DEFINITIONAL_REPRESENTATION('',(#73272),#73276); -#73272 = LINE('',#73273,#73274); -#73273 = CARTESIAN_POINT('',(-0.483778460014,0.E+000)); -#73274 = VECTOR('',#73275,1.); -#73275 = DIRECTION('',(0.E+000,1.)); -#73276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73277 = ORIENTED_EDGE('',*,*,#73151,.T.); -#73278 = ORIENTED_EDGE('',*,*,#73279,.T.); -#73279 = EDGE_CURVE('',#73154,#73230,#73280,.T.); -#73280 = SURFACE_CURVE('',#73281,(#73285,#73292),.PCURVE_S1.); -#73281 = LINE('',#73282,#73283); -#73282 = CARTESIAN_POINT('',(-0.762,-0.4826,-1.414053320556)); -#73283 = VECTOR('',#73284,1.); -#73284 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73285 = PCURVE('',#73169,#73286); -#73286 = DEFINITIONAL_REPRESENTATION('',(#73287),#73291); -#73287 = LINE('',#73288,#73289); -#73288 = CARTESIAN_POINT('',(-2.861853320556,-1.358976696061)); -#73289 = VECTOR('',#73290,1.); -#73290 = DIRECTION('',(0.E+000,1.)); -#73291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73292 = PCURVE('',#73136,#73293); -#73293 = DEFINITIONAL_REPRESENTATION('',(#73294),#73298); -#73294 = LINE('',#73295,#73296); -#73295 = CARTESIAN_POINT('',(0.483778460014,0.E+000)); -#73296 = VECTOR('',#73297,1.); -#73297 = DIRECTION('',(0.E+000,1.)); -#73298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73299 = ADVANCED_FACE('',(#73300),#73245,.F.); -#73300 = FACE_BOUND('',#73301,.T.); -#73301 = EDGE_LOOP('',(#73302,#73327,#73348,#73349)); -#73302 = ORIENTED_EDGE('',*,*,#73303,.F.); -#73303 = EDGE_CURVE('',#73304,#73306,#73308,.T.); -#73304 = VERTEX_POINT('',#73305); -#73305 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.438919294883)); -#73306 = VERTEX_POINT('',#73307); -#73307 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.438919294883)); -#73308 = SURFACE_CURVE('',#73309,(#73313,#73320),.PCURVE_S1.); -#73309 = LINE('',#73310,#73311); -#73310 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); -#73311 = VECTOR('',#73312,1.); -#73312 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73313 = PCURVE('',#73245,#73314); -#73314 = DEFINITIONAL_REPRESENTATION('',(#73315),#73319); -#73315 = LINE('',#73316,#73317); -#73316 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73317 = VECTOR('',#73318,1.); -#73318 = DIRECTION('',(0.E+000,-1.)); -#73319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73320 = PCURVE('',#71183,#73321); -#73321 = DEFINITIONAL_REPRESENTATION('',(#73322),#73326); -#73322 = LINE('',#73323,#73324); -#73323 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73324 = VECTOR('',#73325,1.); -#73325 = DIRECTION('',(-1.,0.E+000)); -#73326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73327 = ORIENTED_EDGE('',*,*,#73328,.T.); -#73328 = EDGE_CURVE('',#73304,#73228,#73329,.T.); -#73329 = SURFACE_CURVE('',#73330,(#73334,#73341),.PCURVE_S1.); -#73330 = LINE('',#73331,#73332); -#73331 = CARTESIAN_POINT('',(0.634416007924,-0.126388742014, +#75601 = PCURVE('',#75383,#75602); +#75602 = DEFINITIONAL_REPRESENTATION('',(#75603),#75607); +#75603 = LINE('',#75604,#75605); +#75604 = CARTESIAN_POINT('',(-0.198066085673,-2.848079063092)); +#75605 = VECTOR('',#75606,1.); +#75606 = DIRECTION('',(-0.997590569818,6.93761847516E-002)); +#75607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75608 = PCURVE('',#75528,#75609); +#75609 = DEFINITIONAL_REPRESENTATION('',(#75610),#75614); +#75610 = LINE('',#75611,#75612); +#75611 = CARTESIAN_POINT('',(0.681240526616,0.1857268475)); +#75612 = VECTOR('',#75613,1.); +#75613 = DIRECTION('',(0.994548334053,0.104276609233)); +#75614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75615 = ADVANCED_FACE('',(#75616),#75561,.F.); +#75616 = FACE_BOUND('',#75617,.T.); +#75617 = EDGE_LOOP('',(#75618,#75648,#75669,#75670)); +#75618 = ORIENTED_EDGE('',*,*,#75619,.F.); +#75619 = EDGE_CURVE('',#75620,#75622,#75624,.T.); +#75620 = VERTEX_POINT('',#75621); +#75621 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.414053320556)); +#75622 = VERTEX_POINT('',#75623); +#75623 = CARTESIAN_POINT('',(0.596976696061,-0.4826,-1.414053320556)); +#75624 = SURFACE_CURVE('',#75625,(#75629,#75636),.PCURVE_S1.); +#75625 = LINE('',#75626,#75627); +#75626 = CARTESIAN_POINT('',(0.596976696061,-0.4826,1.4478)); +#75627 = VECTOR('',#75628,1.); +#75628 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75629 = PCURVE('',#75561,#75630); +#75630 = DEFINITIONAL_REPRESENTATION('',(#75631),#75635); +#75631 = LINE('',#75632,#75633); +#75632 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75633 = VECTOR('',#75634,1.); +#75634 = DIRECTION('',(-1.,0.E+000)); +#75635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75636 = PCURVE('',#75637,#75642); +#75637 = PLANE('',#75638); +#75638 = AXIS2_PLACEMENT_3D('',#75639,#75640,#75641); +#75639 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); +#75640 = DIRECTION('',(-0.994521895368,0.104528463268,0.E+000)); +#75641 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#75642 = DEFINITIONAL_REPRESENTATION('',(#75643),#75647); +#75643 = LINE('',#75644,#75645); +#75644 = CARTESIAN_POINT('',(0.357558744213,0.E+000)); +#75645 = VECTOR('',#75646,1.); +#75646 = DIRECTION('',(0.E+000,-1.)); +#75647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75648 = ORIENTED_EDGE('',*,*,#75649,.F.); +#75649 = EDGE_CURVE('',#75544,#75620,#75650,.T.); +#75650 = SURFACE_CURVE('',#75651,(#75655,#75662),.PCURVE_S1.); +#75651 = LINE('',#75652,#75653); +#75652 = CARTESIAN_POINT('',(-0.762,-0.4826,1.414053320556)); +#75653 = VECTOR('',#75654,1.); +#75654 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75655 = PCURVE('',#75561,#75656); +#75656 = DEFINITIONAL_REPRESENTATION('',(#75657),#75661); +#75657 = LINE('',#75658,#75659); +#75658 = CARTESIAN_POINT('',(-3.374667944393E-002,-1.358976696061)); +#75659 = VECTOR('',#75660,1.); +#75660 = DIRECTION('',(0.E+000,1.)); +#75661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75662 = PCURVE('',#75411,#75663); +#75663 = DEFINITIONAL_REPRESENTATION('',(#75664),#75668); +#75664 = LINE('',#75665,#75666); +#75665 = CARTESIAN_POINT('',(-0.483778460014,0.E+000)); +#75666 = VECTOR('',#75667,1.); +#75667 = DIRECTION('',(0.E+000,1.)); +#75668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75669 = ORIENTED_EDGE('',*,*,#75543,.T.); +#75670 = ORIENTED_EDGE('',*,*,#75671,.T.); +#75671 = EDGE_CURVE('',#75546,#75622,#75672,.T.); +#75672 = SURFACE_CURVE('',#75673,(#75677,#75684),.PCURVE_S1.); +#75673 = LINE('',#75674,#75675); +#75674 = CARTESIAN_POINT('',(-0.762,-0.4826,-1.414053320556)); +#75675 = VECTOR('',#75676,1.); +#75676 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75677 = PCURVE('',#75561,#75678); +#75678 = DEFINITIONAL_REPRESENTATION('',(#75679),#75683); +#75679 = LINE('',#75680,#75681); +#75680 = CARTESIAN_POINT('',(-2.861853320556,-1.358976696061)); +#75681 = VECTOR('',#75682,1.); +#75682 = DIRECTION('',(0.E+000,1.)); +#75683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75684 = PCURVE('',#75528,#75685); +#75685 = DEFINITIONAL_REPRESENTATION('',(#75686),#75690); +#75686 = LINE('',#75687,#75688); +#75687 = CARTESIAN_POINT('',(0.483778460014,0.E+000)); +#75688 = VECTOR('',#75689,1.); +#75689 = DIRECTION('',(0.E+000,1.)); +#75690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75691 = ADVANCED_FACE('',(#75692),#75637,.F.); +#75692 = FACE_BOUND('',#75693,.T.); +#75693 = EDGE_LOOP('',(#75694,#75719,#75740,#75741)); +#75694 = ORIENTED_EDGE('',*,*,#75695,.F.); +#75695 = EDGE_CURVE('',#75696,#75698,#75700,.T.); +#75696 = VERTEX_POINT('',#75697); +#75697 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.438919294883)); +#75698 = VERTEX_POINT('',#75699); +#75699 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.438919294883)); +#75700 = SURFACE_CURVE('',#75701,(#75705,#75712),.PCURVE_S1.); +#75701 = LINE('',#75702,#75703); +#75702 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.4478)); +#75703 = VECTOR('',#75704,1.); +#75704 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75705 = PCURVE('',#75637,#75706); +#75706 = DEFINITIONAL_REPRESENTATION('',(#75707),#75711); +#75707 = LINE('',#75708,#75709); +#75708 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75709 = VECTOR('',#75710,1.); +#75710 = DIRECTION('',(0.E+000,-1.)); +#75711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75712 = PCURVE('',#73575,#75713); +#75713 = DEFINITIONAL_REPRESENTATION('',(#75714),#75718); +#75714 = LINE('',#75715,#75716); +#75715 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#75716 = VECTOR('',#75717,1.); +#75717 = DIRECTION('',(-1.,0.E+000)); +#75718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75719 = ORIENTED_EDGE('',*,*,#75720,.T.); +#75720 = EDGE_CURVE('',#75696,#75620,#75721,.T.); +#75721 = SURFACE_CURVE('',#75722,(#75726,#75733),.PCURVE_S1.); +#75722 = LINE('',#75723,#75724); +#75723 = CARTESIAN_POINT('',(0.634416007924,-0.126388742014, 1.438962038205)); -#73332 = VECTOR('',#73333,1.); -#73333 = DIRECTION('',(-0.104276609233,-0.992125664297, +#75724 = VECTOR('',#75725,1.); +#75725 = DIRECTION('',(-0.104276609233,-0.992125664297, -6.93761847516E-002)); -#73334 = PCURVE('',#73245,#73335); -#73335 = DEFINITIONAL_REPRESENTATION('',(#73336),#73340); -#73336 = LINE('',#73337,#73338); -#73337 = CARTESIAN_POINT('',(-6.146249662316E-004,-8.837961794564E-003) - ); -#73338 = VECTOR('',#73339,1.); -#73339 = DIRECTION('',(0.997590569818,-6.93761847516E-002)); -#73340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73341 = PCURVE('',#73019,#73342); -#73342 = DEFINITIONAL_REPRESENTATION('',(#73343),#73347); -#73343 = LINE('',#73344,#73345); -#73344 = CARTESIAN_POINT('',(-0.12669737044,1.396416007924)); -#73345 = VECTOR('',#73346,1.); -#73346 = DIRECTION('',(-0.994548334053,-0.104276609233)); -#73347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73348 = ORIENTED_EDGE('',*,*,#73227,.T.); -#73349 = ORIENTED_EDGE('',*,*,#73350,.T.); -#73350 = EDGE_CURVE('',#73230,#73306,#73351,.T.); -#73351 = SURFACE_CURVE('',#73352,(#73356,#73363),.PCURVE_S1.); -#73352 = LINE('',#73353,#73354); -#73353 = CARTESIAN_POINT('',(0.613468330311,-0.325692581294, +#75726 = PCURVE('',#75637,#75727); +#75727 = DEFINITIONAL_REPRESENTATION('',(#75728),#75732); +#75728 = LINE('',#75729,#75730); +#75729 = CARTESIAN_POINT('',(-6.146249662316E-004,-8.837961794564E-003) + ); +#75730 = VECTOR('',#75731,1.); +#75731 = DIRECTION('',(0.997590569818,-6.93761847516E-002)); +#75732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75733 = PCURVE('',#75411,#75734); +#75734 = DEFINITIONAL_REPRESENTATION('',(#75735),#75739); +#75735 = LINE('',#75736,#75737); +#75736 = CARTESIAN_POINT('',(-0.12669737044,1.396416007924)); +#75737 = VECTOR('',#75738,1.); +#75738 = DIRECTION('',(-0.994548334053,-0.104276609233)); +#75739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75740 = ORIENTED_EDGE('',*,*,#75619,.T.); +#75741 = ORIENTED_EDGE('',*,*,#75742,.T.); +#75742 = EDGE_CURVE('',#75622,#75698,#75743,.T.); +#75743 = SURFACE_CURVE('',#75744,(#75748,#75755),.PCURVE_S1.); +#75744 = LINE('',#75745,#75746); +#75745 = CARTESIAN_POINT('',(0.613468330311,-0.325692581294, -1.425025356116)); -#73354 = VECTOR('',#73355,1.); -#73355 = DIRECTION('',(0.104276609233,0.992125664297,-6.93761847516E-002 +#75746 = VECTOR('',#75747,1.); +#75747 = DIRECTION('',(0.104276609233,0.992125664297,-6.93761847516E-002 )); -#73356 = PCURVE('',#73245,#73357); -#73357 = DEFINITIONAL_REPRESENTATION('',(#73358),#73362); -#73358 = LINE('',#73359,#73360); -#73359 = CARTESIAN_POINT('',(0.199787035579,-2.872825356116)); -#73360 = VECTOR('',#73361,1.); -#73361 = DIRECTION('',(-0.997590569818,-6.93761847516E-002)); -#73362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73363 = PCURVE('',#73136,#73364); -#73364 = DEFINITIONAL_REPRESENTATION('',(#73365),#73369); -#73365 = LINE('',#73366,#73367); -#73366 = CARTESIAN_POINT('',(0.326487889383,1.375468330311)); -#73367 = VECTOR('',#73368,1.); -#73368 = DIRECTION('',(-0.994548334053,0.104276609233)); -#73369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73370 = ADVANCED_FACE('',(#73371),#71183,.F.); -#73371 = FACE_BOUND('',#73372,.T.); -#73372 = EDGE_LOOP('',(#73373,#73403,#73424,#73425,#73448,#73476,#73497, - #73498,#73521,#73549,#73577,#73604)); -#73373 = ORIENTED_EDGE('',*,*,#73374,.T.); -#73374 = EDGE_CURVE('',#73375,#73377,#73379,.T.); -#73375 = VERTEX_POINT('',#73376); -#73376 = CARTESIAN_POINT('',(0.6477,-0.127,1.1811)); -#73377 = VERTEX_POINT('',#73378); -#73378 = CARTESIAN_POINT('',(0.6477,-0.127,1.438919294883)); -#73379 = SURFACE_CURVE('',#73380,(#73384,#73391),.PCURVE_S1.); -#73380 = LINE('',#73381,#73382); -#73381 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); -#73382 = VECTOR('',#73383,1.); -#73383 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73384 = PCURVE('',#71183,#73385); -#73385 = DEFINITIONAL_REPRESENTATION('',(#73386),#73390); -#73386 = LINE('',#73387,#73388); -#73387 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); -#73388 = VECTOR('',#73389,1.); -#73389 = DIRECTION('',(1.,0.E+000)); -#73390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73391 = PCURVE('',#73392,#73397); -#73392 = PLANE('',#73393); -#73393 = AXIS2_PLACEMENT_3D('',#73394,#73395,#73396); -#73394 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.4478)); -#73395 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73396 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73397 = DEFINITIONAL_REPRESENTATION('',(#73398),#73402); -#73398 = LINE('',#73399,#73400); -#73399 = CARTESIAN_POINT('',(0.E+000,0.38773610875)); -#73400 = VECTOR('',#73401,1.); -#73401 = DIRECTION('',(1.,0.E+000)); -#73402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73403 = ORIENTED_EDGE('',*,*,#73404,.T.); -#73404 = EDGE_CURVE('',#73377,#73304,#73405,.T.); -#73405 = SURFACE_CURVE('',#73406,(#73410,#73417),.PCURVE_S1.); -#73406 = LINE('',#73407,#73408); -#73407 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.438919294883)); -#73408 = VECTOR('',#73409,1.); -#73409 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73410 = PCURVE('',#71183,#73411); -#73411 = DEFINITIONAL_REPRESENTATION('',(#73412),#73416); -#73412 = LINE('',#73413,#73414); -#73413 = CARTESIAN_POINT('',(-8.880705116825E-003,0.E+000)); -#73414 = VECTOR('',#73415,1.); -#73415 = DIRECTION('',(0.E+000,-1.)); -#73416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73417 = PCURVE('',#73019,#73418); -#73418 = DEFINITIONAL_REPRESENTATION('',(#73419),#73423); -#73419 = LINE('',#73420,#73421); -#73420 = CARTESIAN_POINT('',(-0.127310121056,1.396351762121)); -#73421 = VECTOR('',#73422,1.); -#73422 = DIRECTION('',(0.E+000,-1.)); -#73423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73424 = ORIENTED_EDGE('',*,*,#73303,.T.); -#73425 = ORIENTED_EDGE('',*,*,#73426,.T.); -#73426 = EDGE_CURVE('',#73306,#73427,#73429,.T.); -#73427 = VERTEX_POINT('',#73428); -#73428 = CARTESIAN_POINT('',(0.6477,-0.127,-1.438919294883)); -#73429 = SURFACE_CURVE('',#73430,(#73434,#73441),.PCURVE_S1.); -#73430 = LINE('',#73431,#73432); -#73431 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.438919294883)); -#73432 = VECTOR('',#73433,1.); -#73433 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73434 = PCURVE('',#71183,#73435); -#73435 = DEFINITIONAL_REPRESENTATION('',(#73436),#73440); -#73436 = LINE('',#73437,#73438); -#73437 = CARTESIAN_POINT('',(-2.886719294883,0.E+000)); -#73438 = VECTOR('',#73439,1.); -#73439 = DIRECTION('',(0.E+000,1.)); -#73440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73441 = PCURVE('',#73136,#73442); -#73442 = DEFINITIONAL_REPRESENTATION('',(#73443),#73447); -#73443 = LINE('',#73444,#73445); -#73444 = CARTESIAN_POINT('',(0.127310121056,1.396351762121)); -#73445 = VECTOR('',#73446,1.); -#73446 = DIRECTION('',(0.E+000,1.)); -#73447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73448 = ORIENTED_EDGE('',*,*,#73449,.T.); -#73449 = EDGE_CURVE('',#73427,#73450,#73452,.T.); -#73450 = VERTEX_POINT('',#73451); -#73451 = CARTESIAN_POINT('',(0.6477,-0.127,-1.1811)); -#73452 = SURFACE_CURVE('',#73453,(#73457,#73464),.PCURVE_S1.); -#73453 = LINE('',#73454,#73455); -#73454 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); -#73455 = VECTOR('',#73456,1.); -#73456 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73457 = PCURVE('',#71183,#73458); -#73458 = DEFINITIONAL_REPRESENTATION('',(#73459),#73463); -#73459 = LINE('',#73460,#73461); -#73460 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); -#73461 = VECTOR('',#73462,1.); -#73462 = DIRECTION('',(1.,0.E+000)); -#73463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73464 = PCURVE('',#73465,#73470); -#73465 = PLANE('',#73466); -#73466 = AXIS2_PLACEMENT_3D('',#73467,#73468,#73469); -#73467 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.4478)); -#73468 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73469 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73470 = DEFINITIONAL_REPRESENTATION('',(#73471),#73475); -#73471 = LINE('',#73472,#73473); -#73472 = CARTESIAN_POINT('',(2.8956,0.38773610875)); -#73473 = VECTOR('',#73474,1.); -#73474 = DIRECTION('',(1.,0.E+000)); -#73475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73476 = ORIENTED_EDGE('',*,*,#73477,.T.); -#73477 = EDGE_CURVE('',#73450,#71164,#73478,.T.); -#73478 = SURFACE_CURVE('',#73479,(#73483,#73490),.PCURVE_S1.); -#73479 = LINE('',#73480,#73481); -#73480 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.1811)); -#73481 = VECTOR('',#73482,1.); -#73482 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); -#73483 = PCURVE('',#71183,#73484); -#73484 = DEFINITIONAL_REPRESENTATION('',(#73485),#73489); -#73485 = LINE('',#73486,#73487); -#73486 = CARTESIAN_POINT('',(-2.6289,-1.110223024625E-015)); -#73487 = VECTOR('',#73488,1.); -#73488 = DIRECTION('',(-3.856562838825E-016,1.)); -#73489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73490 = PCURVE('',#71268,#73491); -#73491 = DEFINITIONAL_REPRESENTATION('',(#73492),#73496); -#73492 = LINE('',#73493,#73494); -#73493 = CARTESIAN_POINT('',(-1.334823787874E-002,0.38773610875)); -#73494 = VECTOR('',#73495,1.); -#73495 = DIRECTION('',(1.,0.E+000)); -#73496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73497 = ORIENTED_EDGE('',*,*,#71161,.F.); -#73498 = ORIENTED_EDGE('',*,*,#73499,.T.); -#73499 = EDGE_CURVE('',#71162,#73500,#73502,.T.); -#73500 = VERTEX_POINT('',#73501); -#73501 = CARTESIAN_POINT('',(0.6477,-0.127,-0.7239)); -#73502 = SURFACE_CURVE('',#73503,(#73507,#73514),.PCURVE_S1.); -#73503 = LINE('',#73504,#73505); -#73504 = CARTESIAN_POINT('',(0.634351762121,-0.127,-0.7239)); -#73505 = VECTOR('',#73506,1.); -#73506 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); -#73507 = PCURVE('',#71183,#73508); -#73508 = DEFINITIONAL_REPRESENTATION('',(#73509),#73513); -#73509 = LINE('',#73510,#73511); -#73510 = CARTESIAN_POINT('',(-2.1717,3.330669073875E-016)); -#73511 = VECTOR('',#73512,1.); -#73512 = DIRECTION('',(-1.928281419412E-016,-1.)); -#73513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73514 = PCURVE('',#71211,#73515); -#73515 = DEFINITIONAL_REPRESENTATION('',(#73516),#73520); -#73516 = LINE('',#73517,#73518); -#73517 = CARTESIAN_POINT('',(1.334823787874E-002,0.38773610875)); -#73518 = VECTOR('',#73519,1.); -#73519 = DIRECTION('',(1.,0.E+000)); -#73520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73521 = ORIENTED_EDGE('',*,*,#73522,.T.); -#73522 = EDGE_CURVE('',#73500,#73523,#73525,.T.); -#73523 = VERTEX_POINT('',#73524); -#73524 = CARTESIAN_POINT('',(0.6477,-0.127,0.7239)); -#73525 = SURFACE_CURVE('',#73526,(#73530,#73537),.PCURVE_S1.); -#73526 = LINE('',#73527,#73528); -#73527 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); -#73528 = VECTOR('',#73529,1.); -#73529 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73530 = PCURVE('',#71183,#73531); -#73531 = DEFINITIONAL_REPRESENTATION('',(#73532),#73536); -#73532 = LINE('',#73533,#73534); -#73533 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); -#73534 = VECTOR('',#73535,1.); -#73535 = DIRECTION('',(1.,0.E+000)); -#73536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73537 = PCURVE('',#73538,#73543); -#73538 = PLANE('',#73539); -#73539 = AXIS2_PLACEMENT_3D('',#73540,#73541,#73542); -#73540 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); -#73541 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73542 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73543 = DEFINITIONAL_REPRESENTATION('',(#73544),#73548); -#73544 = LINE('',#73545,#73546); -#73545 = CARTESIAN_POINT('',(2.1717,0.38773610875)); -#73546 = VECTOR('',#73547,1.); -#73547 = DIRECTION('',(1.,0.E+000)); -#73548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73549 = ORIENTED_EDGE('',*,*,#73550,.T.); -#73550 = EDGE_CURVE('',#73523,#73551,#73553,.T.); -#73551 = VERTEX_POINT('',#73552); -#73552 = CARTESIAN_POINT('',(0.8509,-0.127,0.7239)); -#73553 = SURFACE_CURVE('',#73554,(#73558,#73565),.PCURVE_S1.); -#73554 = LINE('',#73555,#73556); -#73555 = CARTESIAN_POINT('',(0.634351762121,-0.127,0.7239)); -#73556 = VECTOR('',#73557,1.); -#73557 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); -#73558 = PCURVE('',#71183,#73559); -#73559 = DEFINITIONAL_REPRESENTATION('',(#73560),#73564); -#73560 = LINE('',#73561,#73562); -#73561 = CARTESIAN_POINT('',(-0.7239,-2.22044604925E-016)); -#73562 = VECTOR('',#73563,1.); -#73563 = DIRECTION('',(-1.928281419412E-016,1.)); -#73564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73565 = PCURVE('',#73566,#73571); -#73566 = PLANE('',#73567); -#73567 = AXIS2_PLACEMENT_3D('',#73568,#73569,#73570); -#73568 = CARTESIAN_POINT('',(0.6477,-0.51473610875,0.7239)); -#73569 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); -#73570 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); -#73571 = DEFINITIONAL_REPRESENTATION('',(#73572),#73576); -#73572 = LINE('',#73573,#73574); -#73573 = CARTESIAN_POINT('',(-1.334823787874E-002,0.38773610875)); -#73574 = VECTOR('',#73575,1.); -#73575 = DIRECTION('',(1.,0.E+000)); -#73576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73577 = ORIENTED_EDGE('',*,*,#73578,.F.); -#73578 = EDGE_CURVE('',#73579,#73551,#73581,.T.); -#73579 = VERTEX_POINT('',#73580); -#73580 = CARTESIAN_POINT('',(0.8509,-0.127,1.1811)); -#73581 = SURFACE_CURVE('',#73582,(#73586,#73593),.PCURVE_S1.); -#73582 = LINE('',#73583,#73584); -#73583 = CARTESIAN_POINT('',(0.8509,-0.127,1.4478)); -#73584 = VECTOR('',#73585,1.); -#73585 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73586 = PCURVE('',#71183,#73587); -#73587 = DEFINITIONAL_REPRESENTATION('',(#73588),#73592); -#73588 = LINE('',#73589,#73590); -#73589 = CARTESIAN_POINT('',(0.E+000,0.216548237879)); -#73590 = VECTOR('',#73591,1.); -#73591 = DIRECTION('',(-1.,0.E+000)); -#73592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73593 = PCURVE('',#73594,#73599); -#73594 = CYLINDRICAL_SURFACE('',#73595,0.127); -#73595 = AXIS2_PLACEMENT_3D('',#73596,#73597,#73598); -#73596 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); -#73597 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73598 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73599 = DEFINITIONAL_REPRESENTATION('',(#73600),#73603); -#73600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73601,#73602),.UNSPECIFIED., +#75748 = PCURVE('',#75637,#75749); +#75749 = DEFINITIONAL_REPRESENTATION('',(#75750),#75754); +#75750 = LINE('',#75751,#75752); +#75751 = CARTESIAN_POINT('',(0.199787035579,-2.872825356116)); +#75752 = VECTOR('',#75753,1.); +#75753 = DIRECTION('',(-0.997590569818,-6.93761847516E-002)); +#75754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75755 = PCURVE('',#75528,#75756); +#75756 = DEFINITIONAL_REPRESENTATION('',(#75757),#75761); +#75757 = LINE('',#75758,#75759); +#75758 = CARTESIAN_POINT('',(0.326487889383,1.375468330311)); +#75759 = VECTOR('',#75760,1.); +#75760 = DIRECTION('',(-0.994548334053,0.104276609233)); +#75761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75762 = ADVANCED_FACE('',(#75763),#73575,.F.); +#75763 = FACE_BOUND('',#75764,.T.); +#75764 = EDGE_LOOP('',(#75765,#75795,#75816,#75817,#75840,#75868,#75889, + #75890,#75913,#75941,#75969,#75996)); +#75765 = ORIENTED_EDGE('',*,*,#75766,.T.); +#75766 = EDGE_CURVE('',#75767,#75769,#75771,.T.); +#75767 = VERTEX_POINT('',#75768); +#75768 = CARTESIAN_POINT('',(0.6477,-0.127,1.1811)); +#75769 = VERTEX_POINT('',#75770); +#75770 = CARTESIAN_POINT('',(0.6477,-0.127,1.438919294883)); +#75771 = SURFACE_CURVE('',#75772,(#75776,#75783),.PCURVE_S1.); +#75772 = LINE('',#75773,#75774); +#75773 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); +#75774 = VECTOR('',#75775,1.); +#75775 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75776 = PCURVE('',#73575,#75777); +#75777 = DEFINITIONAL_REPRESENTATION('',(#75778),#75782); +#75778 = LINE('',#75779,#75780); +#75779 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); +#75780 = VECTOR('',#75781,1.); +#75781 = DIRECTION('',(1.,0.E+000)); +#75782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75783 = PCURVE('',#75784,#75789); +#75784 = PLANE('',#75785); +#75785 = AXIS2_PLACEMENT_3D('',#75786,#75787,#75788); +#75786 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.4478)); +#75787 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75788 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75789 = DEFINITIONAL_REPRESENTATION('',(#75790),#75794); +#75790 = LINE('',#75791,#75792); +#75791 = CARTESIAN_POINT('',(0.E+000,0.38773610875)); +#75792 = VECTOR('',#75793,1.); +#75793 = DIRECTION('',(1.,0.E+000)); +#75794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75795 = ORIENTED_EDGE('',*,*,#75796,.T.); +#75796 = EDGE_CURVE('',#75769,#75696,#75797,.T.); +#75797 = SURFACE_CURVE('',#75798,(#75802,#75809),.PCURVE_S1.); +#75798 = LINE('',#75799,#75800); +#75799 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.438919294883)); +#75800 = VECTOR('',#75801,1.); +#75801 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75802 = PCURVE('',#73575,#75803); +#75803 = DEFINITIONAL_REPRESENTATION('',(#75804),#75808); +#75804 = LINE('',#75805,#75806); +#75805 = CARTESIAN_POINT('',(-8.880705116825E-003,0.E+000)); +#75806 = VECTOR('',#75807,1.); +#75807 = DIRECTION('',(0.E+000,-1.)); +#75808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75809 = PCURVE('',#75411,#75810); +#75810 = DEFINITIONAL_REPRESENTATION('',(#75811),#75815); +#75811 = LINE('',#75812,#75813); +#75812 = CARTESIAN_POINT('',(-0.127310121056,1.396351762121)); +#75813 = VECTOR('',#75814,1.); +#75814 = DIRECTION('',(0.E+000,-1.)); +#75815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75816 = ORIENTED_EDGE('',*,*,#75695,.T.); +#75817 = ORIENTED_EDGE('',*,*,#75818,.T.); +#75818 = EDGE_CURVE('',#75698,#75819,#75821,.T.); +#75819 = VERTEX_POINT('',#75820); +#75820 = CARTESIAN_POINT('',(0.6477,-0.127,-1.438919294883)); +#75821 = SURFACE_CURVE('',#75822,(#75826,#75833),.PCURVE_S1.); +#75822 = LINE('',#75823,#75824); +#75823 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.438919294883)); +#75824 = VECTOR('',#75825,1.); +#75825 = DIRECTION('',(1.,0.E+000,0.E+000)); +#75826 = PCURVE('',#73575,#75827); +#75827 = DEFINITIONAL_REPRESENTATION('',(#75828),#75832); +#75828 = LINE('',#75829,#75830); +#75829 = CARTESIAN_POINT('',(-2.886719294883,0.E+000)); +#75830 = VECTOR('',#75831,1.); +#75831 = DIRECTION('',(0.E+000,1.)); +#75832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75833 = PCURVE('',#75528,#75834); +#75834 = DEFINITIONAL_REPRESENTATION('',(#75835),#75839); +#75835 = LINE('',#75836,#75837); +#75836 = CARTESIAN_POINT('',(0.127310121056,1.396351762121)); +#75837 = VECTOR('',#75838,1.); +#75838 = DIRECTION('',(0.E+000,1.)); +#75839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75840 = ORIENTED_EDGE('',*,*,#75841,.T.); +#75841 = EDGE_CURVE('',#75819,#75842,#75844,.T.); +#75842 = VERTEX_POINT('',#75843); +#75843 = CARTESIAN_POINT('',(0.6477,-0.127,-1.1811)); +#75844 = SURFACE_CURVE('',#75845,(#75849,#75856),.PCURVE_S1.); +#75845 = LINE('',#75846,#75847); +#75846 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); +#75847 = VECTOR('',#75848,1.); +#75848 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75849 = PCURVE('',#73575,#75850); +#75850 = DEFINITIONAL_REPRESENTATION('',(#75851),#75855); +#75851 = LINE('',#75852,#75853); +#75852 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); +#75853 = VECTOR('',#75854,1.); +#75854 = DIRECTION('',(1.,0.E+000)); +#75855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75856 = PCURVE('',#75857,#75862); +#75857 = PLANE('',#75858); +#75858 = AXIS2_PLACEMENT_3D('',#75859,#75860,#75861); +#75859 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.4478)); +#75860 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75861 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75862 = DEFINITIONAL_REPRESENTATION('',(#75863),#75867); +#75863 = LINE('',#75864,#75865); +#75864 = CARTESIAN_POINT('',(2.8956,0.38773610875)); +#75865 = VECTOR('',#75866,1.); +#75866 = DIRECTION('',(1.,0.E+000)); +#75867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75868 = ORIENTED_EDGE('',*,*,#75869,.T.); +#75869 = EDGE_CURVE('',#75842,#73556,#75870,.T.); +#75870 = SURFACE_CURVE('',#75871,(#75875,#75882),.PCURVE_S1.); +#75871 = LINE('',#75872,#75873); +#75872 = CARTESIAN_POINT('',(0.634351762121,-0.127,-1.1811)); +#75873 = VECTOR('',#75874,1.); +#75874 = DIRECTION('',(1.,0.E+000,-3.856562838825E-016)); +#75875 = PCURVE('',#73575,#75876); +#75876 = DEFINITIONAL_REPRESENTATION('',(#75877),#75881); +#75877 = LINE('',#75878,#75879); +#75878 = CARTESIAN_POINT('',(-2.6289,-1.110223024625E-015)); +#75879 = VECTOR('',#75880,1.); +#75880 = DIRECTION('',(-3.856562838825E-016,1.)); +#75881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75882 = PCURVE('',#73660,#75883); +#75883 = DEFINITIONAL_REPRESENTATION('',(#75884),#75888); +#75884 = LINE('',#75885,#75886); +#75885 = CARTESIAN_POINT('',(-1.334823787874E-002,0.38773610875)); +#75886 = VECTOR('',#75887,1.); +#75887 = DIRECTION('',(1.,0.E+000)); +#75888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75889 = ORIENTED_EDGE('',*,*,#73553,.F.); +#75890 = ORIENTED_EDGE('',*,*,#75891,.T.); +#75891 = EDGE_CURVE('',#73554,#75892,#75894,.T.); +#75892 = VERTEX_POINT('',#75893); +#75893 = CARTESIAN_POINT('',(0.6477,-0.127,-0.7239)); +#75894 = SURFACE_CURVE('',#75895,(#75899,#75906),.PCURVE_S1.); +#75895 = LINE('',#75896,#75897); +#75896 = CARTESIAN_POINT('',(0.634351762121,-0.127,-0.7239)); +#75897 = VECTOR('',#75898,1.); +#75898 = DIRECTION('',(-1.,0.E+000,-1.928281419412E-016)); +#75899 = PCURVE('',#73575,#75900); +#75900 = DEFINITIONAL_REPRESENTATION('',(#75901),#75905); +#75901 = LINE('',#75902,#75903); +#75902 = CARTESIAN_POINT('',(-2.1717,3.330669073875E-016)); +#75903 = VECTOR('',#75904,1.); +#75904 = DIRECTION('',(-1.928281419412E-016,-1.)); +#75905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75906 = PCURVE('',#73603,#75907); +#75907 = DEFINITIONAL_REPRESENTATION('',(#75908),#75912); +#75908 = LINE('',#75909,#75910); +#75909 = CARTESIAN_POINT('',(1.334823787874E-002,0.38773610875)); +#75910 = VECTOR('',#75911,1.); +#75911 = DIRECTION('',(1.,0.E+000)); +#75912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75913 = ORIENTED_EDGE('',*,*,#75914,.T.); +#75914 = EDGE_CURVE('',#75892,#75915,#75917,.T.); +#75915 = VERTEX_POINT('',#75916); +#75916 = CARTESIAN_POINT('',(0.6477,-0.127,0.7239)); +#75917 = SURFACE_CURVE('',#75918,(#75922,#75929),.PCURVE_S1.); +#75918 = LINE('',#75919,#75920); +#75919 = CARTESIAN_POINT('',(0.6477,-0.127,1.4478)); +#75920 = VECTOR('',#75921,1.); +#75921 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75922 = PCURVE('',#73575,#75923); +#75923 = DEFINITIONAL_REPRESENTATION('',(#75924),#75928); +#75924 = LINE('',#75925,#75926); +#75925 = CARTESIAN_POINT('',(0.E+000,1.334823787874E-002)); +#75926 = VECTOR('',#75927,1.); +#75927 = DIRECTION('',(1.,0.E+000)); +#75928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75929 = PCURVE('',#75930,#75935); +#75930 = PLANE('',#75931); +#75931 = AXIS2_PLACEMENT_3D('',#75932,#75933,#75934); +#75932 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); +#75933 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75934 = DIRECTION('',(0.E+000,0.E+000,1.)); +#75935 = DEFINITIONAL_REPRESENTATION('',(#75936),#75940); +#75936 = LINE('',#75937,#75938); +#75937 = CARTESIAN_POINT('',(2.1717,0.38773610875)); +#75938 = VECTOR('',#75939,1.); +#75939 = DIRECTION('',(1.,0.E+000)); +#75940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75941 = ORIENTED_EDGE('',*,*,#75942,.T.); +#75942 = EDGE_CURVE('',#75915,#75943,#75945,.T.); +#75943 = VERTEX_POINT('',#75944); +#75944 = CARTESIAN_POINT('',(0.8509,-0.127,0.7239)); +#75945 = SURFACE_CURVE('',#75946,(#75950,#75957),.PCURVE_S1.); +#75946 = LINE('',#75947,#75948); +#75947 = CARTESIAN_POINT('',(0.634351762121,-0.127,0.7239)); +#75948 = VECTOR('',#75949,1.); +#75949 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); +#75950 = PCURVE('',#73575,#75951); +#75951 = DEFINITIONAL_REPRESENTATION('',(#75952),#75956); +#75952 = LINE('',#75953,#75954); +#75953 = CARTESIAN_POINT('',(-0.7239,-2.22044604925E-016)); +#75954 = VECTOR('',#75955,1.); +#75955 = DIRECTION('',(-1.928281419412E-016,1.)); +#75956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75957 = PCURVE('',#75958,#75963); +#75958 = PLANE('',#75959); +#75959 = AXIS2_PLACEMENT_3D('',#75960,#75961,#75962); +#75960 = CARTESIAN_POINT('',(0.6477,-0.51473610875,0.7239)); +#75961 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); +#75962 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); +#75963 = DEFINITIONAL_REPRESENTATION('',(#75964),#75968); +#75964 = LINE('',#75965,#75966); +#75965 = CARTESIAN_POINT('',(-1.334823787874E-002,0.38773610875)); +#75966 = VECTOR('',#75967,1.); +#75967 = DIRECTION('',(1.,0.E+000)); +#75968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75969 = ORIENTED_EDGE('',*,*,#75970,.F.); +#75970 = EDGE_CURVE('',#75971,#75943,#75973,.T.); +#75971 = VERTEX_POINT('',#75972); +#75972 = CARTESIAN_POINT('',(0.8509,-0.127,1.1811)); +#75973 = SURFACE_CURVE('',#75974,(#75978,#75985),.PCURVE_S1.); +#75974 = LINE('',#75975,#75976); +#75975 = CARTESIAN_POINT('',(0.8509,-0.127,1.4478)); +#75976 = VECTOR('',#75977,1.); +#75977 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75978 = PCURVE('',#73575,#75979); +#75979 = DEFINITIONAL_REPRESENTATION('',(#75980),#75984); +#75980 = LINE('',#75981,#75982); +#75981 = CARTESIAN_POINT('',(0.E+000,0.216548237879)); +#75982 = VECTOR('',#75983,1.); +#75983 = DIRECTION('',(-1.,0.E+000)); +#75984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75985 = PCURVE('',#75986,#75991); +#75986 = CYLINDRICAL_SURFACE('',#75987,0.127); +#75987 = AXIS2_PLACEMENT_3D('',#75988,#75989,#75990); +#75988 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); +#75989 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#75990 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#75991 = DEFINITIONAL_REPRESENTATION('',(#75992),#75995); +#75992 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75993,#75994),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#73601 = CARTESIAN_POINT('',(1.570796326795,0.2667)); -#73602 = CARTESIAN_POINT('',(1.570796326795,0.7239)); -#73603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73604 = ORIENTED_EDGE('',*,*,#73605,.T.); -#73605 = EDGE_CURVE('',#73579,#73375,#73606,.T.); -#73606 = SURFACE_CURVE('',#73607,(#73611,#73618),.PCURVE_S1.); -#73607 = LINE('',#73608,#73609); -#73608 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.1811)); -#73609 = VECTOR('',#73610,1.); -#73610 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); -#73611 = PCURVE('',#71183,#73612); -#73612 = DEFINITIONAL_REPRESENTATION('',(#73613),#73617); -#73613 = LINE('',#73614,#73615); -#73614 = CARTESIAN_POINT('',(-0.2667,1.110223024625E-016)); -#73615 = VECTOR('',#73616,1.); -#73616 = DIRECTION('',(-3.856562838825E-016,-1.)); -#73617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73618 = PCURVE('',#73619,#73624); -#73619 = PLANE('',#73620); -#73620 = AXIS2_PLACEMENT_3D('',#73621,#73622,#73623); -#73621 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.1811)); -#73622 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); -#73623 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); -#73624 = DEFINITIONAL_REPRESENTATION('',(#73625),#73629); -#73625 = LINE('',#73626,#73627); -#73626 = CARTESIAN_POINT('',(1.334823787874E-002,0.38773610875)); -#73627 = VECTOR('',#73628,1.); -#73628 = DIRECTION('',(1.,0.E+000)); -#73629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73630 = ADVANCED_FACE('',(#73631),#73594,.F.); -#73631 = FACE_BOUND('',#73632,.F.); -#73632 = EDGE_LOOP('',(#73633,#73662,#73687,#73688)); -#73633 = ORIENTED_EDGE('',*,*,#73634,.T.); -#73634 = EDGE_CURVE('',#73635,#73637,#73639,.T.); -#73635 = VERTEX_POINT('',#73636); -#73636 = CARTESIAN_POINT('',(0.9779,-0.254,1.1811)); -#73637 = VERTEX_POINT('',#73638); -#73638 = CARTESIAN_POINT('',(0.9779,-0.254,0.7239)); -#73639 = SURFACE_CURVE('',#73640,(#73644,#73650),.PCURVE_S1.); -#73640 = LINE('',#73641,#73642); -#73641 = CARTESIAN_POINT('',(0.9779,-0.254,1.4478)); -#73642 = VECTOR('',#73643,1.); -#73643 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73644 = PCURVE('',#73594,#73645); -#73645 = DEFINITIONAL_REPRESENTATION('',(#73646),#73649); -#73646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73647,#73648),.UNSPECIFIED., +#75993 = CARTESIAN_POINT('',(1.570796326795,0.2667)); +#75994 = CARTESIAN_POINT('',(1.570796326795,0.7239)); +#75995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#75996 = ORIENTED_EDGE('',*,*,#75997,.T.); +#75997 = EDGE_CURVE('',#75971,#75767,#75998,.T.); +#75998 = SURFACE_CURVE('',#75999,(#76003,#76010),.PCURVE_S1.); +#75999 = LINE('',#76000,#76001); +#76000 = CARTESIAN_POINT('',(0.634351762121,-0.127,1.1811)); +#76001 = VECTOR('',#76002,1.); +#76002 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); +#76003 = PCURVE('',#73575,#76004); +#76004 = DEFINITIONAL_REPRESENTATION('',(#76005),#76009); +#76005 = LINE('',#76006,#76007); +#76006 = CARTESIAN_POINT('',(-0.2667,1.110223024625E-016)); +#76007 = VECTOR('',#76008,1.); +#76008 = DIRECTION('',(-3.856562838825E-016,-1.)); +#76009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76010 = PCURVE('',#76011,#76016); +#76011 = PLANE('',#76012); +#76012 = AXIS2_PLACEMENT_3D('',#76013,#76014,#76015); +#76013 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.1811)); +#76014 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); +#76015 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); +#76016 = DEFINITIONAL_REPRESENTATION('',(#76017),#76021); +#76017 = LINE('',#76018,#76019); +#76018 = CARTESIAN_POINT('',(1.334823787874E-002,0.38773610875)); +#76019 = VECTOR('',#76020,1.); +#76020 = DIRECTION('',(1.,0.E+000)); +#76021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76022 = ADVANCED_FACE('',(#76023),#75986,.F.); +#76023 = FACE_BOUND('',#76024,.F.); +#76024 = EDGE_LOOP('',(#76025,#76054,#76079,#76080)); +#76025 = ORIENTED_EDGE('',*,*,#76026,.T.); +#76026 = EDGE_CURVE('',#76027,#76029,#76031,.T.); +#76027 = VERTEX_POINT('',#76028); +#76028 = CARTESIAN_POINT('',(0.9779,-0.254,1.1811)); +#76029 = VERTEX_POINT('',#76030); +#76030 = CARTESIAN_POINT('',(0.9779,-0.254,0.7239)); +#76031 = SURFACE_CURVE('',#76032,(#76036,#76042),.PCURVE_S1.); +#76032 = LINE('',#76033,#76034); +#76033 = CARTESIAN_POINT('',(0.9779,-0.254,1.4478)); +#76034 = VECTOR('',#76035,1.); +#76035 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76036 = PCURVE('',#75986,#76037); +#76037 = DEFINITIONAL_REPRESENTATION('',(#76038),#76041); +#76038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76039,#76040),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#73647 = CARTESIAN_POINT('',(3.14159265359,0.2667)); -#73648 = CARTESIAN_POINT('',(3.14159265359,0.7239)); -#73649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73650 = PCURVE('',#73651,#73656); -#73651 = PLANE('',#73652); -#73652 = AXIS2_PLACEMENT_3D('',#73653,#73654,#73655); -#73653 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); -#73654 = DIRECTION('',(1.,0.E+000,0.E+000)); -#73655 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73656 = DEFINITIONAL_REPRESENTATION('',(#73657),#73661); -#73657 = LINE('',#73658,#73659); -#73658 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); -#73659 = VECTOR('',#73660,1.); -#73660 = DIRECTION('',(1.,0.E+000)); -#73661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73662 = ORIENTED_EDGE('',*,*,#73663,.F.); -#73663 = EDGE_CURVE('',#73551,#73637,#73664,.T.); -#73664 = SURFACE_CURVE('',#73665,(#73670,#73676),.PCURVE_S1.); -#73665 = CIRCLE('',#73666,0.127); -#73666 = AXIS2_PLACEMENT_3D('',#73667,#73668,#73669); -#73667 = CARTESIAN_POINT('',(0.8509,-0.254,0.7239)); -#73668 = DIRECTION('',(-1.928281419412E-016,0.E+000,-1.)); -#73669 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); -#73670 = PCURVE('',#73594,#73671); -#73671 = DEFINITIONAL_REPRESENTATION('',(#73672),#73675); -#73672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73673,#73674),.UNSPECIFIED., +#76039 = CARTESIAN_POINT('',(3.14159265359,0.2667)); +#76040 = CARTESIAN_POINT('',(3.14159265359,0.7239)); +#76041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76042 = PCURVE('',#76043,#76048); +#76043 = PLANE('',#76044); +#76044 = AXIS2_PLACEMENT_3D('',#76045,#76046,#76047); +#76045 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); +#76046 = DIRECTION('',(1.,0.E+000,0.E+000)); +#76047 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76048 = DEFINITIONAL_REPRESENTATION('',(#76049),#76053); +#76049 = LINE('',#76050,#76051); +#76050 = CARTESIAN_POINT('',(0.E+000,0.105803853849)); +#76051 = VECTOR('',#76052,1.); +#76052 = DIRECTION('',(1.,0.E+000)); +#76053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76054 = ORIENTED_EDGE('',*,*,#76055,.F.); +#76055 = EDGE_CURVE('',#75943,#76029,#76056,.T.); +#76056 = SURFACE_CURVE('',#76057,(#76062,#76068),.PCURVE_S1.); +#76057 = CIRCLE('',#76058,0.127); +#76058 = AXIS2_PLACEMENT_3D('',#76059,#76060,#76061); +#76059 = CARTESIAN_POINT('',(0.8509,-0.254,0.7239)); +#76060 = DIRECTION('',(-1.928281419412E-016,0.E+000,-1.)); +#76061 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); +#76062 = PCURVE('',#75986,#76063); +#76063 = DEFINITIONAL_REPRESENTATION('',(#76064),#76067); +#76064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76065,#76066),.UNSPECIFIED., .F.,.F.,(2,2),(4.712388980385,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#73673 = CARTESIAN_POINT('',(1.570796326795,0.7239)); -#73674 = CARTESIAN_POINT('',(3.14159265359,0.7239)); -#73675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#76065 = CARTESIAN_POINT('',(1.570796326795,0.7239)); +#76066 = CARTESIAN_POINT('',(3.14159265359,0.7239)); +#76067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#73676 = PCURVE('',#73566,#73677); -#73677 = DEFINITIONAL_REPRESENTATION('',(#73678),#73686); -#73678 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#73679,#73680,#73681,#73682 - ,#73683,#73684,#73685),.UNSPECIFIED.,.T.,.F.) +#76068 = PCURVE('',#75958,#76069); +#76069 = DEFINITIONAL_REPRESENTATION('',(#76070),#76078); +#76070 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#76071,#76072,#76073,#76074 + ,#76075,#76076,#76077),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#73679 = CARTESIAN_POINT('',(0.3302,0.26073610875)); -#73680 = CARTESIAN_POINT('',(0.3302,4.076565618857E-002)); -#73681 = CARTESIAN_POINT('',(0.1397,0.150750882469)); -#73682 = CARTESIAN_POINT('',(-5.08E-002,0.26073610875)); -#73683 = CARTESIAN_POINT('',(0.1397,0.37072133503)); -#73684 = CARTESIAN_POINT('',(0.3302,0.480706561311)); -#73685 = CARTESIAN_POINT('',(0.3302,0.26073610875)); -#73686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73687 = ORIENTED_EDGE('',*,*,#73578,.F.); -#73688 = ORIENTED_EDGE('',*,*,#73689,.F.); -#73689 = EDGE_CURVE('',#73635,#73579,#73690,.T.); -#73690 = SURFACE_CURVE('',#73691,(#73696,#73702),.PCURVE_S1.); -#73691 = CIRCLE('',#73692,0.127); -#73692 = AXIS2_PLACEMENT_3D('',#73693,#73694,#73695); -#73693 = CARTESIAN_POINT('',(0.8509,-0.254,1.1811)); -#73694 = DIRECTION('',(-3.856562838825E-016,5.986992950607E-048,1.)); -#73695 = DIRECTION('',(-1.,1.70740499604E-015,-3.856562838825E-016)); -#73696 = PCURVE('',#73594,#73697); -#73697 = DEFINITIONAL_REPRESENTATION('',(#73698),#73701); -#73698 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73699,#73700),.UNSPECIFIED., +#76071 = CARTESIAN_POINT('',(0.3302,0.26073610875)); +#76072 = CARTESIAN_POINT('',(0.3302,4.076565618857E-002)); +#76073 = CARTESIAN_POINT('',(0.1397,0.150750882469)); +#76074 = CARTESIAN_POINT('',(-5.08E-002,0.26073610875)); +#76075 = CARTESIAN_POINT('',(0.1397,0.37072133503)); +#76076 = CARTESIAN_POINT('',(0.3302,0.480706561311)); +#76077 = CARTESIAN_POINT('',(0.3302,0.26073610875)); +#76078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76079 = ORIENTED_EDGE('',*,*,#75970,.F.); +#76080 = ORIENTED_EDGE('',*,*,#76081,.F.); +#76081 = EDGE_CURVE('',#76027,#75971,#76082,.T.); +#76082 = SURFACE_CURVE('',#76083,(#76088,#76094),.PCURVE_S1.); +#76083 = CIRCLE('',#76084,0.127); +#76084 = AXIS2_PLACEMENT_3D('',#76085,#76086,#76087); +#76085 = CARTESIAN_POINT('',(0.8509,-0.254,1.1811)); +#76086 = DIRECTION('',(-3.856562838825E-016,5.986992950607E-048,1.)); +#76087 = DIRECTION('',(-1.,1.70740499604E-015,-3.856562838825E-016)); +#76088 = PCURVE('',#75986,#76089); +#76089 = DEFINITIONAL_REPRESENTATION('',(#76090),#76093); +#76090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76091,#76092),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#73699 = CARTESIAN_POINT('',(3.14159265359,0.2667)); -#73700 = CARTESIAN_POINT('',(1.570796326795,0.2667)); -#73701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#76091 = CARTESIAN_POINT('',(3.14159265359,0.2667)); +#76092 = CARTESIAN_POINT('',(1.570796326795,0.2667)); +#76093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#73702 = PCURVE('',#73619,#73703); -#73703 = DEFINITIONAL_REPRESENTATION('',(#73704),#73712); -#73704 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#73705,#73706,#73707,#73708 - ,#73709,#73710,#73711),.UNSPECIFIED.,.F.,.F.) +#76094 = PCURVE('',#76011,#76095); +#76095 = DEFINITIONAL_REPRESENTATION('',(#76096),#76104); +#76096 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#76097,#76098,#76099,#76100 + ,#76101,#76102,#76103),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#73705 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); -#73706 = CARTESIAN_POINT('',(-7.62E-002,4.076565618857E-002)); -#73707 = CARTESIAN_POINT('',(-0.2667,0.150750882469)); -#73708 = CARTESIAN_POINT('',(-0.4572,0.26073610875)); -#73709 = CARTESIAN_POINT('',(-0.2667,0.37072133503)); -#73710 = CARTESIAN_POINT('',(-7.62E-002,0.480706561311)); -#73711 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); -#73712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73713 = ADVANCED_FACE('',(#73714),#73651,.F.); -#73714 = FACE_BOUND('',#73715,.T.); -#73715 = EDGE_LOOP('',(#73716,#73768,#73789,#73790)); -#73716 = ORIENTED_EDGE('',*,*,#73717,.F.); -#73717 = EDGE_CURVE('',#73718,#73720,#73722,.T.); -#73718 = VERTEX_POINT('',#73719); -#73719 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.1811)); -#73720 = VERTEX_POINT('',#73721); -#73721 = CARTESIAN_POINT('',(0.9779,-0.359803853849,0.7239)); -#73722 = SURFACE_CURVE('',#73723,(#73727,#73734),.PCURVE_S1.); -#73723 = LINE('',#73724,#73725); -#73724 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); -#73725 = VECTOR('',#73726,1.); -#73726 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73727 = PCURVE('',#73651,#73728); -#73728 = DEFINITIONAL_REPRESENTATION('',(#73729),#73733); -#73729 = LINE('',#73730,#73731); -#73730 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); -#73731 = VECTOR('',#73732,1.); -#73732 = DIRECTION('',(1.,0.E+000)); -#73733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73734 = PCURVE('',#73735,#73740); -#73735 = CYLINDRICAL_SURFACE('',#73736,0.127); -#73736 = AXIS2_PLACEMENT_3D('',#73737,#73738,#73739); -#73737 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.4478)); -#73738 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73739 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73740 = DEFINITIONAL_REPRESENTATION('',(#73741),#73767); -#73741 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#73742,#73743,#73744,#73745, - #73746,#73747,#73748,#73749,#73750,#73751,#73752,#73753,#73754, - #73755,#73756,#73757,#73758,#73759,#73760,#73761,#73762,#73763, - #73764,#73765,#73766),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#76097 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); +#76098 = CARTESIAN_POINT('',(-7.62E-002,4.076565618857E-002)); +#76099 = CARTESIAN_POINT('',(-0.2667,0.150750882469)); +#76100 = CARTESIAN_POINT('',(-0.4572,0.26073610875)); +#76101 = CARTESIAN_POINT('',(-0.2667,0.37072133503)); +#76102 = CARTESIAN_POINT('',(-7.62E-002,0.480706561311)); +#76103 = CARTESIAN_POINT('',(-7.62E-002,0.26073610875)); +#76104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76105 = ADVANCED_FACE('',(#76106),#76043,.F.); +#76106 = FACE_BOUND('',#76107,.T.); +#76107 = EDGE_LOOP('',(#76108,#76160,#76181,#76182)); +#76108 = ORIENTED_EDGE('',*,*,#76109,.F.); +#76109 = EDGE_CURVE('',#76110,#76112,#76114,.T.); +#76110 = VERTEX_POINT('',#76111); +#76111 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.1811)); +#76112 = VERTEX_POINT('',#76113); +#76113 = CARTESIAN_POINT('',(0.9779,-0.359803853849,0.7239)); +#76114 = SURFACE_CURVE('',#76115,(#76119,#76126),.PCURVE_S1.); +#76115 = LINE('',#76116,#76117); +#76116 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.4478)); +#76117 = VECTOR('',#76118,1.); +#76118 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76119 = PCURVE('',#76043,#76120); +#76120 = DEFINITIONAL_REPRESENTATION('',(#76121),#76125); +#76121 = LINE('',#76122,#76123); +#76122 = CARTESIAN_POINT('',(0.E+000,-5.551115123126E-017)); +#76123 = VECTOR('',#76124,1.); +#76124 = DIRECTION('',(1.,0.E+000)); +#76125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76126 = PCURVE('',#76127,#76132); +#76127 = CYLINDRICAL_SURFACE('',#76128,0.127); +#76128 = AXIS2_PLACEMENT_3D('',#76129,#76130,#76131); +#76129 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.4478)); +#76130 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76131 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#76132 = DEFINITIONAL_REPRESENTATION('',(#76133),#76159); +#76133 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76134,#76135,#76136,#76137, + #76138,#76139,#76140,#76141,#76142,#76143,#76144,#76145,#76146, + #76147,#76148,#76149,#76150,#76151,#76152,#76153,#76154,#76155, + #76156,#76157,#76158),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.2667,0.287481818182,0.308263636364, 0.329045454545,0.349827272727,0.370609090909,0.391390909091, 0.412172727273,0.432954545455,0.453736363636,0.474518181818,0.4953, 0.516081818182,0.536863636364,0.557645454545,0.578427272727, 0.599209090909,0.619990909091,0.640772727273,0.661554545455, 0.682336363636,0.703118181818,0.7239),.QUASI_UNIFORM_KNOTS.); -#73742 = CARTESIAN_POINT('',(6.28318530718,0.2667)); -#73743 = CARTESIAN_POINT('',(6.28318530718,0.273627272727)); -#73744 = CARTESIAN_POINT('',(6.28318530718,0.287481818182)); -#73745 = CARTESIAN_POINT('',(6.28318530718,0.308263636364)); -#73746 = CARTESIAN_POINT('',(6.28318530718,0.329045454545)); -#73747 = CARTESIAN_POINT('',(6.28318530718,0.349827272727)); -#73748 = CARTESIAN_POINT('',(6.28318530718,0.370609090909)); -#73749 = CARTESIAN_POINT('',(6.28318530718,0.391390909091)); -#73750 = CARTESIAN_POINT('',(6.28318530718,0.412172727273)); -#73751 = CARTESIAN_POINT('',(6.28318530718,0.432954545455)); -#73752 = CARTESIAN_POINT('',(6.28318530718,0.453736363636)); -#73753 = CARTESIAN_POINT('',(6.28318530718,0.474518181818)); -#73754 = CARTESIAN_POINT('',(6.28318530718,0.4953)); -#73755 = CARTESIAN_POINT('',(6.28318530718,0.516081818182)); -#73756 = CARTESIAN_POINT('',(6.28318530718,0.536863636364)); -#73757 = CARTESIAN_POINT('',(6.28318530718,0.557645454545)); -#73758 = CARTESIAN_POINT('',(6.28318530718,0.578427272727)); -#73759 = CARTESIAN_POINT('',(6.28318530718,0.599209090909)); -#73760 = CARTESIAN_POINT('',(6.28318530718,0.619990909091)); -#73761 = CARTESIAN_POINT('',(6.28318530718,0.640772727273)); -#73762 = CARTESIAN_POINT('',(6.28318530718,0.661554545455)); -#73763 = CARTESIAN_POINT('',(6.28318530718,0.682336363636)); -#73764 = CARTESIAN_POINT('',(6.28318530718,0.703118181818)); -#73765 = CARTESIAN_POINT('',(6.28318530718,0.716972727273)); -#73766 = CARTESIAN_POINT('',(6.28318530718,0.7239)); -#73767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73768 = ORIENTED_EDGE('',*,*,#73769,.T.); -#73769 = EDGE_CURVE('',#73718,#73635,#73770,.T.); -#73770 = SURFACE_CURVE('',#73771,(#73775,#73782),.PCURVE_S1.); -#73771 = LINE('',#73772,#73773); -#73772 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.1811)); -#73773 = VECTOR('',#73774,1.); -#73774 = DIRECTION('',(0.E+000,1.,0.E+000)); -#73775 = PCURVE('',#73651,#73776); -#73776 = DEFINITIONAL_REPRESENTATION('',(#73777),#73781); -#73777 = LINE('',#73778,#73779); -#73778 = CARTESIAN_POINT('',(0.2667,0.E+000)); -#73779 = VECTOR('',#73780,1.); -#73780 = DIRECTION('',(0.E+000,1.)); -#73781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73782 = PCURVE('',#73619,#73783); -#73783 = DEFINITIONAL_REPRESENTATION('',(#73784),#73788); -#73784 = LINE('',#73785,#73786); -#73785 = CARTESIAN_POINT('',(-0.3302,0.154932254901)); -#73786 = VECTOR('',#73787,1.); -#73787 = DIRECTION('',(0.E+000,1.)); -#73788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73789 = ORIENTED_EDGE('',*,*,#73634,.T.); -#73790 = ORIENTED_EDGE('',*,*,#73791,.T.); -#73791 = EDGE_CURVE('',#73637,#73720,#73792,.T.); -#73792 = SURFACE_CURVE('',#73793,(#73797,#73804),.PCURVE_S1.); -#73793 = LINE('',#73794,#73795); -#73794 = CARTESIAN_POINT('',(0.9779,-0.359803853849,0.7239)); -#73795 = VECTOR('',#73796,1.); -#73796 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#73797 = PCURVE('',#73651,#73798); -#73798 = DEFINITIONAL_REPRESENTATION('',(#73799),#73803); -#73799 = LINE('',#73800,#73801); -#73800 = CARTESIAN_POINT('',(0.7239,0.E+000)); -#73801 = VECTOR('',#73802,1.); -#73802 = DIRECTION('',(0.E+000,-1.)); -#73803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73804 = PCURVE('',#73566,#73805); -#73805 = DEFINITIONAL_REPRESENTATION('',(#73806),#73810); -#73806 = LINE('',#73807,#73808); -#73807 = CARTESIAN_POINT('',(0.3302,0.154932254901)); -#73808 = VECTOR('',#73809,1.); -#73809 = DIRECTION('',(0.E+000,-1.)); -#73810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73811 = ADVANCED_FACE('',(#73812),#73735,.T.); -#73812 = FACE_BOUND('',#73813,.T.); -#73813 = EDGE_LOOP('',(#73814,#73843,#73864,#73865)); -#73814 = ORIENTED_EDGE('',*,*,#73815,.F.); -#73815 = EDGE_CURVE('',#73816,#73818,#73820,.T.); -#73816 = VERTEX_POINT('',#73817); -#73817 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.1811)); -#73818 = VERTEX_POINT('',#73819); -#73819 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,0.7239)); -#73820 = SURFACE_CURVE('',#73821,(#73825,#73831),.PCURVE_S1.); -#73821 = LINE('',#73822,#73823); -#73822 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.4478)); -#73823 = VECTOR('',#73824,1.); -#73824 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73825 = PCURVE('',#73735,#73826); -#73826 = DEFINITIONAL_REPRESENTATION('',(#73827),#73830); -#73827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73828,#73829),.UNSPECIFIED., +#76134 = CARTESIAN_POINT('',(6.28318530718,0.2667)); +#76135 = CARTESIAN_POINT('',(6.28318530718,0.273627272727)); +#76136 = CARTESIAN_POINT('',(6.28318530718,0.287481818182)); +#76137 = CARTESIAN_POINT('',(6.28318530718,0.308263636364)); +#76138 = CARTESIAN_POINT('',(6.28318530718,0.329045454545)); +#76139 = CARTESIAN_POINT('',(6.28318530718,0.349827272727)); +#76140 = CARTESIAN_POINT('',(6.28318530718,0.370609090909)); +#76141 = CARTESIAN_POINT('',(6.28318530718,0.391390909091)); +#76142 = CARTESIAN_POINT('',(6.28318530718,0.412172727273)); +#76143 = CARTESIAN_POINT('',(6.28318530718,0.432954545455)); +#76144 = CARTESIAN_POINT('',(6.28318530718,0.453736363636)); +#76145 = CARTESIAN_POINT('',(6.28318530718,0.474518181818)); +#76146 = CARTESIAN_POINT('',(6.28318530718,0.4953)); +#76147 = CARTESIAN_POINT('',(6.28318530718,0.516081818182)); +#76148 = CARTESIAN_POINT('',(6.28318530718,0.536863636364)); +#76149 = CARTESIAN_POINT('',(6.28318530718,0.557645454545)); +#76150 = CARTESIAN_POINT('',(6.28318530718,0.578427272727)); +#76151 = CARTESIAN_POINT('',(6.28318530718,0.599209090909)); +#76152 = CARTESIAN_POINT('',(6.28318530718,0.619990909091)); +#76153 = CARTESIAN_POINT('',(6.28318530718,0.640772727273)); +#76154 = CARTESIAN_POINT('',(6.28318530718,0.661554545455)); +#76155 = CARTESIAN_POINT('',(6.28318530718,0.682336363636)); +#76156 = CARTESIAN_POINT('',(6.28318530718,0.703118181818)); +#76157 = CARTESIAN_POINT('',(6.28318530718,0.716972727273)); +#76158 = CARTESIAN_POINT('',(6.28318530718,0.7239)); +#76159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76160 = ORIENTED_EDGE('',*,*,#76161,.T.); +#76161 = EDGE_CURVE('',#76110,#76027,#76162,.T.); +#76162 = SURFACE_CURVE('',#76163,(#76167,#76174),.PCURVE_S1.); +#76163 = LINE('',#76164,#76165); +#76164 = CARTESIAN_POINT('',(0.9779,-0.359803853849,1.1811)); +#76165 = VECTOR('',#76166,1.); +#76166 = DIRECTION('',(0.E+000,1.,0.E+000)); +#76167 = PCURVE('',#76043,#76168); +#76168 = DEFINITIONAL_REPRESENTATION('',(#76169),#76173); +#76169 = LINE('',#76170,#76171); +#76170 = CARTESIAN_POINT('',(0.2667,0.E+000)); +#76171 = VECTOR('',#76172,1.); +#76172 = DIRECTION('',(0.E+000,1.)); +#76173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76174 = PCURVE('',#76011,#76175); +#76175 = DEFINITIONAL_REPRESENTATION('',(#76176),#76180); +#76176 = LINE('',#76177,#76178); +#76177 = CARTESIAN_POINT('',(-0.3302,0.154932254901)); +#76178 = VECTOR('',#76179,1.); +#76179 = DIRECTION('',(0.E+000,1.)); +#76180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76181 = ORIENTED_EDGE('',*,*,#76026,.T.); +#76182 = ORIENTED_EDGE('',*,*,#76183,.T.); +#76183 = EDGE_CURVE('',#76029,#76112,#76184,.T.); +#76184 = SURFACE_CURVE('',#76185,(#76189,#76196),.PCURVE_S1.); +#76185 = LINE('',#76186,#76187); +#76186 = CARTESIAN_POINT('',(0.9779,-0.359803853849,0.7239)); +#76187 = VECTOR('',#76188,1.); +#76188 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#76189 = PCURVE('',#76043,#76190); +#76190 = DEFINITIONAL_REPRESENTATION('',(#76191),#76195); +#76191 = LINE('',#76192,#76193); +#76192 = CARTESIAN_POINT('',(0.7239,0.E+000)); +#76193 = VECTOR('',#76194,1.); +#76194 = DIRECTION('',(0.E+000,-1.)); +#76195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76196 = PCURVE('',#75958,#76197); +#76197 = DEFINITIONAL_REPRESENTATION('',(#76198),#76202); +#76198 = LINE('',#76199,#76200); +#76199 = CARTESIAN_POINT('',(0.3302,0.154932254901)); +#76200 = VECTOR('',#76201,1.); +#76201 = DIRECTION('',(0.E+000,-1.)); +#76202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76203 = ADVANCED_FACE('',(#76204),#76127,.T.); +#76204 = FACE_BOUND('',#76205,.T.); +#76205 = EDGE_LOOP('',(#76206,#76235,#76256,#76257)); +#76206 = ORIENTED_EDGE('',*,*,#76207,.F.); +#76207 = EDGE_CURVE('',#76208,#76210,#76212,.T.); +#76208 = VERTEX_POINT('',#76209); +#76209 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.1811)); +#76210 = VERTEX_POINT('',#76211); +#76211 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,0.7239)); +#76212 = SURFACE_CURVE('',#76213,(#76217,#76223),.PCURVE_S1.); +#76213 = LINE('',#76214,#76215); +#76214 = CARTESIAN_POINT('',(1.076036545314,-0.483480452216,1.4478)); +#76215 = VECTOR('',#76216,1.); +#76216 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76217 = PCURVE('',#76127,#76218); +#76218 = DEFINITIONAL_REPRESENTATION('',(#76219),#76222); +#76219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76220,#76221),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#73828 = CARTESIAN_POINT('',(4.941663714624,0.2667)); -#73829 = CARTESIAN_POINT('',(4.941663714624,0.7239)); -#73830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73831 = PCURVE('',#73832,#73837); -#73832 = PLANE('',#73833); -#73833 = AXIS2_PLACEMENT_3D('',#73834,#73835,#73836); -#73834 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); -#73835 = DIRECTION('',(0.22727129674,0.973831483203,0.E+000)); -#73836 = DIRECTION('',(-0.973831483203,0.22727129674,0.E+000)); -#73837 = DEFINITIONAL_REPRESENTATION('',(#73838),#73842); -#73838 = LINE('',#73839,#73840); -#73839 = CARTESIAN_POINT('',(0.137525754385,0.E+000)); -#73840 = VECTOR('',#73841,1.); -#73841 = DIRECTION('',(0.E+000,-1.)); -#73842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73843 = ORIENTED_EDGE('',*,*,#73844,.T.); -#73844 = EDGE_CURVE('',#73816,#73718,#73845,.T.); -#73845 = SURFACE_CURVE('',#73846,(#73851,#73857),.PCURVE_S1.); -#73846 = CIRCLE('',#73847,0.127); -#73847 = AXIS2_PLACEMENT_3D('',#73848,#73849,#73850); -#73848 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.1811)); -#73849 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); -#73850 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); -#73851 = PCURVE('',#73735,#73852); -#73852 = DEFINITIONAL_REPRESENTATION('',(#73853),#73856); -#73853 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73854,#73855),.UNSPECIFIED., +#76220 = CARTESIAN_POINT('',(4.941663714624,0.2667)); +#76221 = CARTESIAN_POINT('',(4.941663714624,0.7239)); +#76222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76223 = PCURVE('',#76224,#76229); +#76224 = PLANE('',#76225); +#76225 = AXIS2_PLACEMENT_3D('',#76226,#76227,#76228); +#76226 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); +#76227 = DIRECTION('',(0.22727129674,0.973831483203,0.E+000)); +#76228 = DIRECTION('',(-0.973831483203,0.22727129674,0.E+000)); +#76229 = DEFINITIONAL_REPRESENTATION('',(#76230),#76234); +#76230 = LINE('',#76231,#76232); +#76231 = CARTESIAN_POINT('',(0.137525754385,0.E+000)); +#76232 = VECTOR('',#76233,1.); +#76233 = DIRECTION('',(0.E+000,-1.)); +#76234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76235 = ORIENTED_EDGE('',*,*,#76236,.T.); +#76236 = EDGE_CURVE('',#76208,#76110,#76237,.T.); +#76237 = SURFACE_CURVE('',#76238,(#76243,#76249),.PCURVE_S1.); +#76238 = CIRCLE('',#76239,0.127); +#76239 = AXIS2_PLACEMENT_3D('',#76240,#76241,#76242); +#76240 = CARTESIAN_POINT('',(1.1049,-0.359803853849,1.1811)); +#76241 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); +#76242 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); +#76243 = PCURVE('',#76127,#76244); +#76244 = DEFINITIONAL_REPRESENTATION('',(#76245),#76248); +#76245 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76246,#76247),.UNSPECIFIED., .F.,.F.,(2,2),(4.941663714624,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#73854 = CARTESIAN_POINT('',(4.941663714624,0.2667)); -#73855 = CARTESIAN_POINT('',(6.28318530718,0.2667)); -#73856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73857 = PCURVE('',#73619,#73858); -#73858 = DEFINITIONAL_REPRESENTATION('',(#73859),#73863); -#73859 = CIRCLE('',#73860,0.127); -#73860 = AXIS2_PLACEMENT_2D('',#73861,#73862); -#73861 = CARTESIAN_POINT('',(-0.4572,0.154932254901)); -#73862 = DIRECTION('',(1.,0.E+000)); -#73863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73864 = ORIENTED_EDGE('',*,*,#73717,.T.); -#73865 = ORIENTED_EDGE('',*,*,#73866,.T.); -#73866 = EDGE_CURVE('',#73720,#73818,#73867,.T.); -#73867 = SURFACE_CURVE('',#73868,(#73873,#73879),.PCURVE_S1.); -#73868 = CIRCLE('',#73869,0.127); -#73869 = AXIS2_PLACEMENT_3D('',#73870,#73871,#73872); -#73870 = CARTESIAN_POINT('',(1.1049,-0.359803853849,0.7239)); -#73871 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); -#73872 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); -#73873 = PCURVE('',#73735,#73874); -#73874 = DEFINITIONAL_REPRESENTATION('',(#73875),#73878); -#73875 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#73876,#73877),.UNSPECIFIED., +#76246 = CARTESIAN_POINT('',(4.941663714624,0.2667)); +#76247 = CARTESIAN_POINT('',(6.28318530718,0.2667)); +#76248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76249 = PCURVE('',#76011,#76250); +#76250 = DEFINITIONAL_REPRESENTATION('',(#76251),#76255); +#76251 = CIRCLE('',#76252,0.127); +#76252 = AXIS2_PLACEMENT_2D('',#76253,#76254); +#76253 = CARTESIAN_POINT('',(-0.4572,0.154932254901)); +#76254 = DIRECTION('',(1.,0.E+000)); +#76255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76256 = ORIENTED_EDGE('',*,*,#76109,.T.); +#76257 = ORIENTED_EDGE('',*,*,#76258,.T.); +#76258 = EDGE_CURVE('',#76112,#76210,#76259,.T.); +#76259 = SURFACE_CURVE('',#76260,(#76265,#76271),.PCURVE_S1.); +#76260 = CIRCLE('',#76261,0.127); +#76261 = AXIS2_PLACEMENT_3D('',#76262,#76263,#76264); +#76262 = CARTESIAN_POINT('',(1.1049,-0.359803853849,0.7239)); +#76263 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); +#76264 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); +#76265 = PCURVE('',#76127,#76266); +#76266 = DEFINITIONAL_REPRESENTATION('',(#76267),#76270); +#76267 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76268,#76269),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.483114246145), .PIECEWISE_BEZIER_KNOTS.); -#73876 = CARTESIAN_POINT('',(6.28318530718,0.7239)); -#73877 = CARTESIAN_POINT('',(4.941663714624,0.7239)); -#73878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73879 = PCURVE('',#73566,#73880); -#73880 = DEFINITIONAL_REPRESENTATION('',(#73881),#73885); -#73881 = CIRCLE('',#73882,0.127); -#73882 = AXIS2_PLACEMENT_2D('',#73883,#73884); -#73883 = CARTESIAN_POINT('',(0.4572,0.154932254901)); -#73884 = DIRECTION('',(1.,0.E+000)); -#73885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73886 = ADVANCED_FACE('',(#73887),#73832,.F.); -#73887 = FACE_BOUND('',#73888,.T.); -#73888 = EDGE_LOOP('',(#73889,#73919,#73940,#73941)); -#73889 = ORIENTED_EDGE('',*,*,#73890,.F.); -#73890 = EDGE_CURVE('',#73891,#73893,#73895,.T.); -#73891 = VERTEX_POINT('',#73892); -#73892 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); -#73893 = VERTEX_POINT('',#73894); -#73894 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); -#73895 = SURFACE_CURVE('',#73896,(#73900,#73907),.PCURVE_S1.); -#73896 = LINE('',#73897,#73898); -#73897 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); -#73898 = VECTOR('',#73899,1.); -#73899 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73900 = PCURVE('',#73832,#73901); -#73901 = DEFINITIONAL_REPRESENTATION('',(#73902),#73906); -#73902 = LINE('',#73903,#73904); -#73903 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73904 = VECTOR('',#73905,1.); -#73905 = DIRECTION('',(0.E+000,-1.)); -#73906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73907 = PCURVE('',#73908,#73913); -#73908 = PLANE('',#73909); -#73909 = AXIS2_PLACEMENT_3D('',#73910,#73911,#73912); -#73910 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); -#73911 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#73912 = DIRECTION('',(0.E+000,0.E+000,1.)); -#73913 = DEFINITIONAL_REPRESENTATION('',(#73914),#73918); -#73914 = LINE('',#73915,#73916); -#73915 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); -#73916 = VECTOR('',#73917,1.); -#73917 = DIRECTION('',(-1.,0.E+000)); -#73918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73919 = ORIENTED_EDGE('',*,*,#73920,.T.); -#73920 = EDGE_CURVE('',#73891,#73816,#73921,.T.); -#73921 = SURFACE_CURVE('',#73922,(#73926,#73933),.PCURVE_S1.); -#73922 = LINE('',#73923,#73924); -#73923 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); -#73924 = VECTOR('',#73925,1.); -#73925 = DIRECTION('',(-0.973831483203,0.22727129674,-3.7556423094E-016) - ); -#73926 = PCURVE('',#73832,#73927); -#73927 = DEFINITIONAL_REPRESENTATION('',(#73928),#73932); -#73928 = LINE('',#73929,#73930); -#73929 = CARTESIAN_POINT('',(0.E+000,-0.2667)); -#73930 = VECTOR('',#73931,1.); -#73931 = DIRECTION('',(1.,-3.7556423094E-016)); -#73932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73933 = PCURVE('',#73619,#73934); -#73934 = DEFINITIONAL_REPRESENTATION('',(#73935),#73939); -#73935 = LINE('',#73936,#73937); -#73936 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); -#73937 = VECTOR('',#73938,1.); -#73938 = DIRECTION('',(0.973831483203,0.22727129674)); -#73939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73940 = ORIENTED_EDGE('',*,*,#73815,.T.); -#73941 = ORIENTED_EDGE('',*,*,#73942,.T.); -#73942 = EDGE_CURVE('',#73818,#73893,#73943,.T.); -#73943 = SURFACE_CURVE('',#73944,(#73948,#73955),.PCURVE_S1.); -#73944 = LINE('',#73945,#73946); -#73945 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); -#73946 = VECTOR('',#73947,1.); -#73947 = DIRECTION('',(0.973831483203,-0.22727129674,-1.8778211547E-016) - ); -#73948 = PCURVE('',#73832,#73949); -#73949 = DEFINITIONAL_REPRESENTATION('',(#73950),#73954); -#73950 = LINE('',#73951,#73952); -#73951 = CARTESIAN_POINT('',(2.162340269515E-016,-0.7239)); -#73952 = VECTOR('',#73953,1.); -#73953 = DIRECTION('',(-1.,-1.8778211547E-016)); -#73954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73955 = PCURVE('',#73566,#73956); -#73956 = DEFINITIONAL_REPRESENTATION('',(#73957),#73961); -#73957 = LINE('',#73958,#73959); -#73958 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); -#73959 = VECTOR('',#73960,1.); -#73960 = DIRECTION('',(0.973831483203,-0.22727129674)); -#73961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73962 = ADVANCED_FACE('',(#73963),#73908,.F.); -#73963 = FACE_BOUND('',#73964,.T.); -#73964 = EDGE_LOOP('',(#73965,#73995,#74016,#74017)); -#73965 = ORIENTED_EDGE('',*,*,#73966,.F.); -#73966 = EDGE_CURVE('',#73967,#73969,#73971,.T.); -#73967 = VERTEX_POINT('',#73968); -#73968 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.1811)); -#73969 = VERTEX_POINT('',#73970); -#73970 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,0.7239)); -#73971 = SURFACE_CURVE('',#73972,(#73976,#73983),.PCURVE_S1.); -#73972 = LINE('',#73973,#73974); -#73973 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); -#73974 = VECTOR('',#73975,1.); -#73975 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#73976 = PCURVE('',#73908,#73977); -#73977 = DEFINITIONAL_REPRESENTATION('',(#73978),#73982); -#73978 = LINE('',#73979,#73980); -#73979 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#73980 = VECTOR('',#73981,1.); -#73981 = DIRECTION('',(-1.,0.E+000)); -#73982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73983 = PCURVE('',#73984,#73989); -#73984 = PLANE('',#73985); -#73985 = AXIS2_PLACEMENT_3D('',#73986,#73987,#73988); -#73986 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); -#73987 = DIRECTION('',(-0.22727129674,-0.973831483203,0.E+000)); -#73988 = DIRECTION('',(0.973831483203,-0.22727129674,0.E+000)); -#73989 = DEFINITIONAL_REPRESENTATION('',(#73990),#73994); -#73990 = LINE('',#73991,#73992); -#73991 = CARTESIAN_POINT('',(6.62031185561E-002,0.E+000)); -#73992 = VECTOR('',#73993,1.); -#73993 = DIRECTION('',(0.E+000,-1.)); -#73994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#73995 = ORIENTED_EDGE('',*,*,#73996,.F.); -#73996 = EDGE_CURVE('',#73891,#73967,#73997,.T.); -#73997 = SURFACE_CURVE('',#73998,(#74002,#74009),.PCURVE_S1.); -#73998 = LINE('',#73999,#74000); -#73999 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); -#74000 = VECTOR('',#74001,1.); -#74001 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74002 = PCURVE('',#73908,#74003); -#74003 = DEFINITIONAL_REPRESENTATION('',(#74004),#74008); -#74004 = LINE('',#74005,#74006); -#74005 = CARTESIAN_POINT('',(-0.2667,-0.130412707117)); -#74006 = VECTOR('',#74007,1.); -#74007 = DIRECTION('',(0.E+000,1.)); -#74008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74009 = PCURVE('',#73619,#74010); -#74010 = DEFINITIONAL_REPRESENTATION('',(#74011),#74015); -#74011 = LINE('',#74012,#74013); -#74012 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); -#74013 = VECTOR('',#74014,1.); -#74014 = DIRECTION('',(0.E+000,1.)); -#74015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74016 = ORIENTED_EDGE('',*,*,#73890,.T.); -#74017 = ORIENTED_EDGE('',*,*,#74018,.T.); -#74018 = EDGE_CURVE('',#73893,#73969,#74019,.T.); -#74019 = SURFACE_CURVE('',#74020,(#74024,#74031),.PCURVE_S1.); -#74020 = LINE('',#74021,#74022); -#74021 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); -#74022 = VECTOR('',#74023,1.); -#74023 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74024 = PCURVE('',#73908,#74025); -#74025 = DEFINITIONAL_REPRESENTATION('',(#74026),#74030); -#74026 = LINE('',#74027,#74028); -#74027 = CARTESIAN_POINT('',(-0.7239,-0.130412707117)); -#74028 = VECTOR('',#74029,1.); -#74029 = DIRECTION('',(0.E+000,1.)); -#74030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74031 = PCURVE('',#73566,#74032); -#74032 = DEFINITIONAL_REPRESENTATION('',(#74033),#74037); -#74033 = LINE('',#74034,#74035); -#74034 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); -#74035 = VECTOR('',#74036,1.); -#74036 = DIRECTION('',(0.E+000,1.)); -#74037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74038 = ADVANCED_FACE('',(#74039),#73984,.F.); -#74039 = FACE_BOUND('',#74040,.T.); -#74040 = EDGE_LOOP('',(#74041,#74070,#74091,#74092)); -#74041 = ORIENTED_EDGE('',*,*,#74042,.F.); -#74042 = EDGE_CURVE('',#74043,#74045,#74047,.T.); -#74043 = VERTEX_POINT('',#74044); -#74044 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.1811)); -#74045 = VERTEX_POINT('',#74046); -#74046 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,0.7239)); -#74047 = SURFACE_CURVE('',#74048,(#74052,#74059),.PCURVE_S1.); -#74048 = LINE('',#74049,#74050); -#74049 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); -#74050 = VECTOR('',#74051,1.); -#74051 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74052 = PCURVE('',#73984,#74053); -#74053 = DEFINITIONAL_REPRESENTATION('',(#74054),#74058); -#74054 = LINE('',#74055,#74056); -#74055 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74056 = VECTOR('',#74057,1.); -#74057 = DIRECTION('',(0.E+000,-1.)); -#74058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74059 = PCURVE('',#74060,#74065); -#74060 = CYLINDRICAL_SURFACE('',#74061,5.253172734297E-002); -#74061 = AXIS2_PLACEMENT_3D('',#74062,#74063,#74064); -#74062 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.4478)); -#74063 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74064 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#74065 = DEFINITIONAL_REPRESENTATION('',(#74066),#74069); -#74066 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74067,#74068),.UNSPECIFIED., +#76268 = CARTESIAN_POINT('',(6.28318530718,0.7239)); +#76269 = CARTESIAN_POINT('',(4.941663714624,0.7239)); +#76270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76271 = PCURVE('',#75958,#76272); +#76272 = DEFINITIONAL_REPRESENTATION('',(#76273),#76277); +#76273 = CIRCLE('',#76274,0.127); +#76274 = AXIS2_PLACEMENT_2D('',#76275,#76276); +#76275 = CARTESIAN_POINT('',(0.4572,0.154932254901)); +#76276 = DIRECTION('',(1.,0.E+000)); +#76277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76278 = ADVANCED_FACE('',(#76279),#76224,.F.); +#76279 = FACE_BOUND('',#76280,.T.); +#76280 = EDGE_LOOP('',(#76281,#76311,#76332,#76333)); +#76281 = ORIENTED_EDGE('',*,*,#76282,.F.); +#76282 = EDGE_CURVE('',#76283,#76285,#76287,.T.); +#76283 = VERTEX_POINT('',#76284); +#76284 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); +#76285 = VERTEX_POINT('',#76286); +#76286 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); +#76287 = SURFACE_CURVE('',#76288,(#76292,#76299),.PCURVE_S1.); +#76288 = LINE('',#76289,#76290); +#76289 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.4478)); +#76290 = VECTOR('',#76291,1.); +#76291 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76292 = PCURVE('',#76224,#76293); +#76293 = DEFINITIONAL_REPRESENTATION('',(#76294),#76298); +#76294 = LINE('',#76295,#76296); +#76295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76296 = VECTOR('',#76297,1.); +#76297 = DIRECTION('',(0.E+000,-1.)); +#76298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76299 = PCURVE('',#76300,#76305); +#76300 = PLANE('',#76301); +#76301 = AXIS2_PLACEMENT_3D('',#76302,#76303,#76304); +#76302 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); +#76303 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#76304 = DIRECTION('',(0.E+000,0.E+000,1.)); +#76305 = DEFINITIONAL_REPRESENTATION('',(#76306),#76310); +#76306 = LINE('',#76307,#76308); +#76307 = CARTESIAN_POINT('',(0.E+000,-0.130412707117)); +#76308 = VECTOR('',#76309,1.); +#76309 = DIRECTION('',(-1.,0.E+000)); +#76310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76311 = ORIENTED_EDGE('',*,*,#76312,.T.); +#76312 = EDGE_CURVE('',#76283,#76208,#76313,.T.); +#76313 = SURFACE_CURVE('',#76314,(#76318,#76325),.PCURVE_S1.); +#76314 = LINE('',#76315,#76316); +#76315 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); +#76316 = VECTOR('',#76317,1.); +#76317 = DIRECTION('',(-0.973831483203,0.22727129674,-3.7556423094E-016) + ); +#76318 = PCURVE('',#76224,#76319); +#76319 = DEFINITIONAL_REPRESENTATION('',(#76320),#76324); +#76320 = LINE('',#76321,#76322); +#76321 = CARTESIAN_POINT('',(0.E+000,-0.2667)); +#76322 = VECTOR('',#76323,1.); +#76323 = DIRECTION('',(1.,-3.7556423094E-016)); +#76324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76325 = PCURVE('',#76011,#76326); +#76326 = DEFINITIONAL_REPRESENTATION('',(#76327),#76331); +#76327 = LINE('',#76328,#76329); +#76328 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); +#76329 = VECTOR('',#76330,1.); +#76330 = DIRECTION('',(0.973831483203,0.22727129674)); +#76331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76332 = ORIENTED_EDGE('',*,*,#76207,.T.); +#76333 = ORIENTED_EDGE('',*,*,#76334,.T.); +#76334 = EDGE_CURVE('',#76210,#76285,#76335,.T.); +#76335 = SURFACE_CURVE('',#76336,(#76340,#76347),.PCURVE_S1.); +#76336 = LINE('',#76337,#76338); +#76337 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); +#76338 = VECTOR('',#76339,1.); +#76339 = DIRECTION('',(0.973831483203,-0.22727129674,-1.8778211547E-016) + ); +#76340 = PCURVE('',#76224,#76341); +#76341 = DEFINITIONAL_REPRESENTATION('',(#76342),#76346); +#76342 = LINE('',#76343,#76344); +#76343 = CARTESIAN_POINT('',(2.162340269515E-016,-0.7239)); +#76344 = VECTOR('',#76345,1.); +#76345 = DIRECTION('',(-1.,-1.8778211547E-016)); +#76346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76347 = PCURVE('',#75958,#76348); +#76348 = DEFINITIONAL_REPRESENTATION('',(#76349),#76353); +#76349 = LINE('',#76350,#76351); +#76350 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); +#76351 = VECTOR('',#76352,1.); +#76352 = DIRECTION('',(0.973831483203,-0.22727129674)); +#76353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76354 = ADVANCED_FACE('',(#76355),#76300,.F.); +#76355 = FACE_BOUND('',#76356,.T.); +#76356 = EDGE_LOOP('',(#76357,#76387,#76408,#76409)); +#76357 = ORIENTED_EDGE('',*,*,#76358,.F.); +#76358 = EDGE_CURVE('',#76359,#76361,#76363,.T.); +#76359 = VERTEX_POINT('',#76360); +#76360 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.1811)); +#76361 = VERTEX_POINT('',#76362); +#76362 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,0.7239)); +#76363 = SURFACE_CURVE('',#76364,(#76368,#76375),.PCURVE_S1.); +#76364 = LINE('',#76365,#76366); +#76365 = CARTESIAN_POINT('',(1.209963454686,-0.384323401633,1.4478)); +#76366 = VECTOR('',#76367,1.); +#76367 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76368 = PCURVE('',#76300,#76369); +#76369 = DEFINITIONAL_REPRESENTATION('',(#76370),#76374); +#76370 = LINE('',#76371,#76372); +#76371 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76372 = VECTOR('',#76373,1.); +#76373 = DIRECTION('',(-1.,0.E+000)); +#76374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76375 = PCURVE('',#76376,#76381); +#76376 = PLANE('',#76377); +#76377 = AXIS2_PLACEMENT_3D('',#76378,#76379,#76380); +#76378 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); +#76379 = DIRECTION('',(-0.22727129674,-0.973831483203,0.E+000)); +#76380 = DIRECTION('',(0.973831483203,-0.22727129674,0.E+000)); +#76381 = DEFINITIONAL_REPRESENTATION('',(#76382),#76386); +#76382 = LINE('',#76383,#76384); +#76383 = CARTESIAN_POINT('',(6.62031185561E-002,0.E+000)); +#76384 = VECTOR('',#76385,1.); +#76385 = DIRECTION('',(0.E+000,-1.)); +#76386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76387 = ORIENTED_EDGE('',*,*,#76388,.F.); +#76388 = EDGE_CURVE('',#76283,#76359,#76389,.T.); +#76389 = SURFACE_CURVE('',#76390,(#76394,#76401),.PCURVE_S1.); +#76390 = LINE('',#76391,#76392); +#76391 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,1.1811)); +#76392 = VECTOR('',#76393,1.); +#76393 = DIRECTION('',(0.E+000,1.,0.E+000)); +#76394 = PCURVE('',#76300,#76395); +#76395 = DEFINITIONAL_REPRESENTATION('',(#76396),#76400); +#76396 = LINE('',#76397,#76398); +#76397 = CARTESIAN_POINT('',(-0.2667,-0.130412707117)); +#76398 = VECTOR('',#76399,1.); +#76399 = DIRECTION('',(0.E+000,1.)); +#76400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76401 = PCURVE('',#76011,#76402); +#76402 = DEFINITIONAL_REPRESENTATION('',(#76403),#76407); +#76403 = LINE('',#76404,#76405); +#76404 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); +#76405 = VECTOR('',#76406,1.); +#76406 = DIRECTION('',(0.E+000,1.)); +#76407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76408 = ORIENTED_EDGE('',*,*,#76282,.T.); +#76409 = ORIENTED_EDGE('',*,*,#76410,.T.); +#76410 = EDGE_CURVE('',#76285,#76361,#76411,.T.); +#76411 = SURFACE_CURVE('',#76412,(#76416,#76423),.PCURVE_S1.); +#76412 = LINE('',#76413,#76414); +#76413 = CARTESIAN_POINT('',(1.209963454686,-0.51473610875,0.7239)); +#76414 = VECTOR('',#76415,1.); +#76415 = DIRECTION('',(0.E+000,1.,0.E+000)); +#76416 = PCURVE('',#76300,#76417); +#76417 = DEFINITIONAL_REPRESENTATION('',(#76418),#76422); +#76418 = LINE('',#76419,#76420); +#76419 = CARTESIAN_POINT('',(-0.7239,-0.130412707117)); +#76420 = VECTOR('',#76421,1.); +#76421 = DIRECTION('',(0.E+000,1.)); +#76422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76423 = PCURVE('',#75958,#76424); +#76424 = DEFINITIONAL_REPRESENTATION('',(#76425),#76429); +#76425 = LINE('',#76426,#76427); +#76426 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); +#76427 = VECTOR('',#76428,1.); +#76428 = DIRECTION('',(0.E+000,1.)); +#76429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76430 = ADVANCED_FACE('',(#76431),#76376,.F.); +#76431 = FACE_BOUND('',#76432,.T.); +#76432 = EDGE_LOOP('',(#76433,#76462,#76483,#76484)); +#76433 = ORIENTED_EDGE('',*,*,#76434,.F.); +#76434 = EDGE_CURVE('',#76435,#76437,#76439,.T.); +#76435 = VERTEX_POINT('',#76436); +#76436 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.1811)); +#76437 = VERTEX_POINT('',#76438); +#76438 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,0.7239)); +#76439 = SURFACE_CURVE('',#76440,(#76444,#76451),.PCURVE_S1.); +#76440 = LINE('',#76441,#76442); +#76441 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.4478)); +#76442 = VECTOR('',#76443,1.); +#76443 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76444 = PCURVE('',#76376,#76445); +#76445 = DEFINITIONAL_REPRESENTATION('',(#76446),#76450); +#76446 = LINE('',#76447,#76448); +#76447 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76448 = VECTOR('',#76449,1.); +#76449 = DIRECTION('',(0.E+000,-1.)); +#76450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76451 = PCURVE('',#76452,#76457); +#76452 = CYLINDRICAL_SURFACE('',#76453,5.253172734297E-002); +#76453 = AXIS2_PLACEMENT_3D('',#76454,#76455,#76456); +#76454 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.4478)); +#76455 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76456 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#76457 = DEFINITIONAL_REPRESENTATION('',(#76458),#76461); +#76458 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76459,#76460),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#74067 = CARTESIAN_POINT('',(4.941663714624,0.2667)); -#74068 = CARTESIAN_POINT('',(4.941663714624,0.7239)); -#74069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74070 = ORIENTED_EDGE('',*,*,#74071,.T.); -#74071 = EDGE_CURVE('',#74043,#73967,#74072,.T.); -#74072 = SURFACE_CURVE('',#74073,(#74077,#74084),.PCURVE_S1.); -#74073 = LINE('',#74074,#74075); -#74074 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.1811)); -#74075 = VECTOR('',#74076,1.); -#74076 = DIRECTION('',(0.973831483203,-0.22727129674,3.7556423094E-016) - ); -#74077 = PCURVE('',#73984,#74078); -#74078 = DEFINITIONAL_REPRESENTATION('',(#74079),#74083); -#74079 = LINE('',#74080,#74081); -#74080 = CARTESIAN_POINT('',(0.E+000,-0.2667)); -#74081 = VECTOR('',#74082,1.); -#74082 = DIRECTION('',(1.,3.7556423094E-016)); -#74083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74084 = PCURVE('',#73619,#74085); -#74085 = DEFINITIONAL_REPRESENTATION('',(#74086),#74090); -#74086 = LINE('',#74087,#74088); -#74087 = CARTESIAN_POINT('',(-0.49779277355,0.145458775719)); -#74088 = VECTOR('',#74089,1.); -#74089 = DIRECTION('',(-0.973831483203,-0.22727129674)); -#74090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74091 = ORIENTED_EDGE('',*,*,#73966,.T.); -#74092 = ORIENTED_EDGE('',*,*,#74093,.T.); -#74093 = EDGE_CURVE('',#73969,#74045,#74094,.T.); -#74094 = SURFACE_CURVE('',#74095,(#74099,#74106),.PCURVE_S1.); -#74095 = LINE('',#74096,#74097); -#74096 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,0.7239)); -#74097 = VECTOR('',#74098,1.); -#74098 = DIRECTION('',(-0.973831483203,0.22727129674,1.8778211547E-016) - ); -#74099 = PCURVE('',#73984,#74100); -#74100 = DEFINITIONAL_REPRESENTATION('',(#74101),#74105); -#74101 = LINE('',#74102,#74103); -#74102 = CARTESIAN_POINT('',(-2.288501182753E-016,-0.7239)); -#74103 = VECTOR('',#74104,1.); -#74104 = DIRECTION('',(-1.,1.8778211547E-016)); -#74105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74106 = PCURVE('',#73566,#74107); -#74107 = DEFINITIONAL_REPRESENTATION('',(#74108),#74112); -#74108 = LINE('',#74109,#74110); -#74109 = CARTESIAN_POINT('',(0.49779277355,0.145458775719)); -#74110 = VECTOR('',#74111,1.); -#74111 = DIRECTION('',(-0.973831483203,0.22727129674)); -#74112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74113 = ADVANCED_FACE('',(#74114),#74060,.F.); -#74114 = FACE_BOUND('',#74115,.F.); -#74115 = EDGE_LOOP('',(#74116,#74145,#74170,#74171)); -#74116 = ORIENTED_EDGE('',*,*,#74117,.T.); -#74117 = EDGE_CURVE('',#74118,#74120,#74122,.T.); -#74118 = VERTEX_POINT('',#74119); -#74119 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.1811)); -#74120 = VERTEX_POINT('',#74121); -#74121 = CARTESIAN_POINT('',(1.1049,-0.318120283077,0.7239)); -#74122 = SURFACE_CURVE('',#74123,(#74127,#74133),.PCURVE_S1.); -#74123 = LINE('',#74124,#74125); -#74124 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); -#74125 = VECTOR('',#74126,1.); -#74126 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74127 = PCURVE('',#74060,#74128); -#74128 = DEFINITIONAL_REPRESENTATION('',(#74129),#74132); -#74129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74130,#74131),.UNSPECIFIED., +#76459 = CARTESIAN_POINT('',(4.941663714624,0.2667)); +#76460 = CARTESIAN_POINT('',(4.941663714624,0.7239)); +#76461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76462 = ORIENTED_EDGE('',*,*,#76463,.T.); +#76463 = EDGE_CURVE('',#76435,#76359,#76464,.T.); +#76464 = SURFACE_CURVE('',#76465,(#76469,#76476),.PCURVE_S1.); +#76465 = LINE('',#76466,#76467); +#76466 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,1.1811)); +#76467 = VECTOR('',#76468,1.); +#76468 = DIRECTION('',(0.973831483203,-0.22727129674,3.7556423094E-016) + ); +#76469 = PCURVE('',#76376,#76470); +#76470 = DEFINITIONAL_REPRESENTATION('',(#76471),#76475); +#76471 = LINE('',#76472,#76473); +#76472 = CARTESIAN_POINT('',(0.E+000,-0.2667)); +#76473 = VECTOR('',#76474,1.); +#76474 = DIRECTION('',(1.,3.7556423094E-016)); +#76475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76476 = PCURVE('',#76011,#76477); +#76477 = DEFINITIONAL_REPRESENTATION('',(#76478),#76482); +#76478 = LINE('',#76479,#76480); +#76479 = CARTESIAN_POINT('',(-0.49779277355,0.145458775719)); +#76480 = VECTOR('',#76481,1.); +#76481 = DIRECTION('',(-0.973831483203,-0.22727129674)); +#76482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76483 = ORIENTED_EDGE('',*,*,#76358,.T.); +#76484 = ORIENTED_EDGE('',*,*,#76485,.T.); +#76485 = EDGE_CURVE('',#76361,#76437,#76486,.T.); +#76486 = SURFACE_CURVE('',#76487,(#76491,#76498),.PCURVE_S1.); +#76487 = LINE('',#76488,#76489); +#76488 = CARTESIAN_POINT('',(1.14549277355,-0.369277333031,0.7239)); +#76489 = VECTOR('',#76490,1.); +#76490 = DIRECTION('',(-0.973831483203,0.22727129674,1.8778211547E-016) + ); +#76491 = PCURVE('',#76376,#76492); +#76492 = DEFINITIONAL_REPRESENTATION('',(#76493),#76497); +#76493 = LINE('',#76494,#76495); +#76494 = CARTESIAN_POINT('',(-2.288501182753E-016,-0.7239)); +#76495 = VECTOR('',#76496,1.); +#76496 = DIRECTION('',(-1.,1.8778211547E-016)); +#76497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76498 = PCURVE('',#75958,#76499); +#76499 = DEFINITIONAL_REPRESENTATION('',(#76500),#76504); +#76500 = LINE('',#76501,#76502); +#76501 = CARTESIAN_POINT('',(0.49779277355,0.145458775719)); +#76502 = VECTOR('',#76503,1.); +#76503 = DIRECTION('',(-0.973831483203,0.22727129674)); +#76504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76505 = ADVANCED_FACE('',(#76506),#76452,.F.); +#76506 = FACE_BOUND('',#76507,.F.); +#76507 = EDGE_LOOP('',(#76508,#76537,#76562,#76563)); +#76508 = ORIENTED_EDGE('',*,*,#76509,.T.); +#76509 = EDGE_CURVE('',#76510,#76512,#76514,.T.); +#76510 = VERTEX_POINT('',#76511); +#76511 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.1811)); +#76512 = VERTEX_POINT('',#76513); +#76513 = CARTESIAN_POINT('',(1.1049,-0.318120283077,0.7239)); +#76514 = SURFACE_CURVE('',#76515,(#76519,#76525),.PCURVE_S1.); +#76515 = LINE('',#76516,#76517); +#76516 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); +#76517 = VECTOR('',#76518,1.); +#76518 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76519 = PCURVE('',#76452,#76520); +#76520 = DEFINITIONAL_REPRESENTATION('',(#76521),#76524); +#76521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76522,#76523),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#74130 = CARTESIAN_POINT('',(6.28318530718,0.2667)); -#74131 = CARTESIAN_POINT('',(6.28318530718,0.7239)); -#74132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74133 = PCURVE('',#74134,#74139); -#74134 = PLANE('',#74135); -#74135 = AXIS2_PLACEMENT_3D('',#74136,#74137,#74138); -#74136 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); -#74137 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#74138 = DIRECTION('',(0.E+000,0.E+000,1.)); -#74139 = DEFINITIONAL_REPRESENTATION('',(#74140),#74144); -#74140 = LINE('',#74141,#74142); -#74141 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74142 = VECTOR('',#74143,1.); -#74143 = DIRECTION('',(-1.,0.E+000)); -#74144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74145 = ORIENTED_EDGE('',*,*,#74146,.F.); -#74146 = EDGE_CURVE('',#74045,#74120,#74147,.T.); -#74147 = SURFACE_CURVE('',#74148,(#74153,#74159),.PCURVE_S1.); -#74148 = CIRCLE('',#74149,5.253172734297E-002); -#74149 = AXIS2_PLACEMENT_3D('',#74150,#74151,#74152); -#74150 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,0.7239)); -#74151 = DIRECTION('',(-1.928281419412E-016,1.558756378926E-047,-1.)); -#74152 = DIRECTION('',(1.,-1.031949858994E-015,-1.928281419412E-016)); -#74153 = PCURVE('',#74060,#74154); -#74154 = DEFINITIONAL_REPRESENTATION('',(#74155),#74158); -#74155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74156,#74157),.UNSPECIFIED., +#76522 = CARTESIAN_POINT('',(6.28318530718,0.2667)); +#76523 = CARTESIAN_POINT('',(6.28318530718,0.7239)); +#76524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76525 = PCURVE('',#76526,#76531); +#76526 = PLANE('',#76527); +#76527 = AXIS2_PLACEMENT_3D('',#76528,#76529,#76530); +#76528 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.4478)); +#76529 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#76530 = DIRECTION('',(0.E+000,0.E+000,1.)); +#76531 = DEFINITIONAL_REPRESENTATION('',(#76532),#76536); +#76532 = LINE('',#76533,#76534); +#76533 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76534 = VECTOR('',#76535,1.); +#76535 = DIRECTION('',(-1.,0.E+000)); +#76536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76537 = ORIENTED_EDGE('',*,*,#76538,.F.); +#76538 = EDGE_CURVE('',#76437,#76512,#76539,.T.); +#76539 = SURFACE_CURVE('',#76540,(#76545,#76551),.PCURVE_S1.); +#76540 = CIRCLE('',#76541,5.253172734297E-002); +#76541 = AXIS2_PLACEMENT_3D('',#76542,#76543,#76544); +#76542 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,0.7239)); +#76543 = DIRECTION('',(-1.928281419412E-016,1.558756378926E-047,-1.)); +#76544 = DIRECTION('',(1.,-1.031949858994E-015,-1.928281419412E-016)); +#76545 = PCURVE('',#76452,#76546); +#76546 = DEFINITIONAL_REPRESENTATION('',(#76547),#76550); +#76547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76548,#76549),.UNSPECIFIED., .F.,.F.,(2,2),(1.800071061035,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#74156 = CARTESIAN_POINT('',(4.941663714624,0.7239)); -#74157 = CARTESIAN_POINT('',(6.28318530718,0.7239)); -#74158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#76548 = CARTESIAN_POINT('',(4.941663714624,0.7239)); +#76549 = CARTESIAN_POINT('',(6.28318530718,0.7239)); +#76550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#74159 = PCURVE('',#73566,#74160); -#74160 = DEFINITIONAL_REPRESENTATION('',(#74161),#74169); -#74161 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74162,#74163,#74164,#74165 - ,#74166,#74167,#74168),.UNSPECIFIED.,.T.,.F.) +#76551 = PCURVE('',#75958,#76552); +#76552 = DEFINITIONAL_REPRESENTATION('',(#76553),#76561); +#76553 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#76554,#76555,#76556,#76557 + ,#76558,#76559,#76560),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#74162 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); -#74163 = CARTESIAN_POINT('',(0.562263454686,0.105628204905)); -#74164 = CARTESIAN_POINT('',(0.483465863671,0.151122015289)); -#74165 = CARTESIAN_POINT('',(0.404668272657,0.196615825673)); -#74166 = CARTESIAN_POINT('',(0.483465863671,0.242109636056)); -#74167 = CARTESIAN_POINT('',(0.562263454686,0.28760344644)); -#74168 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); -#74169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74170 = ORIENTED_EDGE('',*,*,#74042,.F.); -#74171 = ORIENTED_EDGE('',*,*,#74172,.F.); -#74172 = EDGE_CURVE('',#74118,#74043,#74173,.T.); -#74173 = SURFACE_CURVE('',#74174,(#74179,#74185),.PCURVE_S1.); -#74174 = CIRCLE('',#74175,5.253172734297E-002); -#74175 = AXIS2_PLACEMENT_3D('',#74176,#74177,#74178); -#74176 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.1811)); -#74177 = DIRECTION('',(-3.856562838825E-016,0.E+000,1.)); -#74178 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); -#74179 = PCURVE('',#74060,#74180); -#74180 = DEFINITIONAL_REPRESENTATION('',(#74181),#74184); -#74181 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74182,#74183),.UNSPECIFIED., +#76554 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); +#76555 = CARTESIAN_POINT('',(0.562263454686,0.105628204905)); +#76556 = CARTESIAN_POINT('',(0.483465863671,0.151122015289)); +#76557 = CARTESIAN_POINT('',(0.404668272657,0.196615825673)); +#76558 = CARTESIAN_POINT('',(0.483465863671,0.242109636056)); +#76559 = CARTESIAN_POINT('',(0.562263454686,0.28760344644)); +#76560 = CARTESIAN_POINT('',(0.562263454686,0.196615825673)); +#76561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76562 = ORIENTED_EDGE('',*,*,#76434,.F.); +#76563 = ORIENTED_EDGE('',*,*,#76564,.F.); +#76564 = EDGE_CURVE('',#76510,#76435,#76565,.T.); +#76565 = SURFACE_CURVE('',#76566,(#76571,#76577),.PCURVE_S1.); +#76566 = CIRCLE('',#76567,5.253172734297E-002); +#76567 = AXIS2_PLACEMENT_3D('',#76568,#76569,#76570); +#76568 = CARTESIAN_POINT('',(1.157431727343,-0.318120283077,1.1811)); +#76569 = DIRECTION('',(-3.856562838825E-016,0.E+000,1.)); +#76570 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); +#76571 = PCURVE('',#76452,#76572); +#76572 = DEFINITIONAL_REPRESENTATION('',(#76573),#76576); +#76573 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76574,#76575),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.341521592555),.PIECEWISE_BEZIER_KNOTS.); -#74182 = CARTESIAN_POINT('',(6.28318530718,0.2667)); -#74183 = CARTESIAN_POINT('',(4.941663714624,0.2667)); -#74184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#76574 = CARTESIAN_POINT('',(6.28318530718,0.2667)); +#76575 = CARTESIAN_POINT('',(4.941663714624,0.2667)); +#76576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#74185 = PCURVE('',#73619,#74186); -#74186 = DEFINITIONAL_REPRESENTATION('',(#74187),#74195); -#74187 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#74188,#74189,#74190,#74191 - ,#74192,#74193,#74194),.UNSPECIFIED.,.F.,.F.) +#76577 = PCURVE('',#76011,#76578); +#76578 = DEFINITIONAL_REPRESENTATION('',(#76579),#76587); +#76579 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#76580,#76581,#76582,#76583 + ,#76584,#76585,#76586),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#74188 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#74189 = CARTESIAN_POINT('',(-0.4572,0.105628204905)); -#74190 = CARTESIAN_POINT('',(-0.535997591014,0.151122015289)); -#74191 = CARTESIAN_POINT('',(-0.614795182029,0.196615825673)); -#74192 = CARTESIAN_POINT('',(-0.535997591014,0.242109636056)); -#74193 = CARTESIAN_POINT('',(-0.4572,0.28760344644)); -#74194 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#74195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74196 = ADVANCED_FACE('',(#74197),#74134,.F.); -#74197 = FACE_BOUND('',#74198,.T.); -#74198 = EDGE_LOOP('',(#74199,#74228,#74249,#74250)); -#74199 = ORIENTED_EDGE('',*,*,#74200,.F.); -#74200 = EDGE_CURVE('',#74201,#74203,#74205,.T.); -#74201 = VERTEX_POINT('',#74202); -#74202 = CARTESIAN_POINT('',(1.1049,-0.254,1.1811)); -#74203 = VERTEX_POINT('',#74204); -#74204 = CARTESIAN_POINT('',(1.1049,-0.254,0.7239)); -#74205 = SURFACE_CURVE('',#74206,(#74210,#74217),.PCURVE_S1.); -#74206 = LINE('',#74207,#74208); -#74207 = CARTESIAN_POINT('',(1.1049,-0.254,1.4478)); -#74208 = VECTOR('',#74209,1.); -#74209 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74210 = PCURVE('',#74134,#74211); -#74211 = DEFINITIONAL_REPRESENTATION('',(#74212),#74216); -#74212 = LINE('',#74213,#74214); -#74213 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); -#74214 = VECTOR('',#74215,1.); -#74215 = DIRECTION('',(-1.,0.E+000)); -#74216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74217 = PCURVE('',#74218,#74223); -#74218 = CYLINDRICAL_SURFACE('',#74219,0.254); -#74219 = AXIS2_PLACEMENT_3D('',#74220,#74221,#74222); -#74220 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); -#74221 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74222 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#74223 = DEFINITIONAL_REPRESENTATION('',(#74224),#74227); -#74224 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74225,#74226),.UNSPECIFIED., +#76580 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#76581 = CARTESIAN_POINT('',(-0.4572,0.105628204905)); +#76582 = CARTESIAN_POINT('',(-0.535997591014,0.151122015289)); +#76583 = CARTESIAN_POINT('',(-0.614795182029,0.196615825673)); +#76584 = CARTESIAN_POINT('',(-0.535997591014,0.242109636056)); +#76585 = CARTESIAN_POINT('',(-0.4572,0.28760344644)); +#76586 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#76587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76588 = ADVANCED_FACE('',(#76589),#76526,.F.); +#76589 = FACE_BOUND('',#76590,.T.); +#76590 = EDGE_LOOP('',(#76591,#76620,#76641,#76642)); +#76591 = ORIENTED_EDGE('',*,*,#76592,.F.); +#76592 = EDGE_CURVE('',#76593,#76595,#76597,.T.); +#76593 = VERTEX_POINT('',#76594); +#76594 = CARTESIAN_POINT('',(1.1049,-0.254,1.1811)); +#76595 = VERTEX_POINT('',#76596); +#76596 = CARTESIAN_POINT('',(1.1049,-0.254,0.7239)); +#76597 = SURFACE_CURVE('',#76598,(#76602,#76609),.PCURVE_S1.); +#76598 = LINE('',#76599,#76600); +#76599 = CARTESIAN_POINT('',(1.1049,-0.254,1.4478)); +#76600 = VECTOR('',#76601,1.); +#76601 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76602 = PCURVE('',#76526,#76603); +#76603 = DEFINITIONAL_REPRESENTATION('',(#76604),#76608); +#76604 = LINE('',#76605,#76606); +#76605 = CARTESIAN_POINT('',(0.E+000,6.412028307706E-002)); +#76606 = VECTOR('',#76607,1.); +#76607 = DIRECTION('',(-1.,0.E+000)); +#76608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76609 = PCURVE('',#76610,#76615); +#76610 = CYLINDRICAL_SURFACE('',#76611,0.254); +#76611 = AXIS2_PLACEMENT_3D('',#76612,#76613,#76614); +#76612 = CARTESIAN_POINT('',(0.8509,-0.254,1.4478)); +#76613 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76614 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#76615 = DEFINITIONAL_REPRESENTATION('',(#76616),#76619); +#76616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76617,#76618),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#74225 = CARTESIAN_POINT('',(3.14159265359,0.2667)); -#74226 = CARTESIAN_POINT('',(3.14159265359,0.7239)); -#74227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74228 = ORIENTED_EDGE('',*,*,#74229,.T.); -#74229 = EDGE_CURVE('',#74201,#74118,#74230,.T.); -#74230 = SURFACE_CURVE('',#74231,(#74235,#74242),.PCURVE_S1.); -#74231 = LINE('',#74232,#74233); -#74232 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.1811)); -#74233 = VECTOR('',#74234,1.); -#74234 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#74235 = PCURVE('',#74134,#74236); -#74236 = DEFINITIONAL_REPRESENTATION('',(#74237),#74241); -#74237 = LINE('',#74238,#74239); -#74238 = CARTESIAN_POINT('',(-0.2667,0.E+000)); -#74239 = VECTOR('',#74240,1.); -#74240 = DIRECTION('',(0.E+000,-1.)); -#74241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74242 = PCURVE('',#73619,#74243); -#74243 = DEFINITIONAL_REPRESENTATION('',(#74244),#74248); -#74244 = LINE('',#74245,#74246); -#74245 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); -#74246 = VECTOR('',#74247,1.); -#74247 = DIRECTION('',(0.E+000,-1.)); -#74248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74249 = ORIENTED_EDGE('',*,*,#74117,.T.); -#74250 = ORIENTED_EDGE('',*,*,#74251,.T.); -#74251 = EDGE_CURVE('',#74120,#74203,#74252,.T.); -#74252 = SURFACE_CURVE('',#74253,(#74257,#74264),.PCURVE_S1.); -#74253 = LINE('',#74254,#74255); -#74254 = CARTESIAN_POINT('',(1.1049,-0.318120283077,0.7239)); -#74255 = VECTOR('',#74256,1.); -#74256 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74257 = PCURVE('',#74134,#74258); -#74258 = DEFINITIONAL_REPRESENTATION('',(#74259),#74263); -#74259 = LINE('',#74260,#74261); -#74260 = CARTESIAN_POINT('',(-0.7239,0.E+000)); -#74261 = VECTOR('',#74262,1.); -#74262 = DIRECTION('',(0.E+000,1.)); -#74263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74264 = PCURVE('',#73566,#74265); -#74265 = DEFINITIONAL_REPRESENTATION('',(#74266),#74270); -#74266 = LINE('',#74267,#74268); -#74267 = CARTESIAN_POINT('',(0.4572,0.196615825673)); -#74268 = VECTOR('',#74269,1.); -#74269 = DIRECTION('',(0.E+000,1.)); -#74270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74271 = ADVANCED_FACE('',(#74272),#74218,.T.); -#74272 = FACE_BOUND('',#74273,.T.); -#74273 = EDGE_LOOP('',(#74274,#74303,#74324,#74325)); -#74274 = ORIENTED_EDGE('',*,*,#74275,.F.); -#74275 = EDGE_CURVE('',#74276,#74278,#74280,.T.); -#74276 = VERTEX_POINT('',#74277); -#74277 = CARTESIAN_POINT('',(0.8509,0.E+000,1.1811)); -#74278 = VERTEX_POINT('',#74279); -#74279 = CARTESIAN_POINT('',(0.8509,0.E+000,0.7239)); -#74280 = SURFACE_CURVE('',#74281,(#74285,#74291),.PCURVE_S1.); -#74281 = LINE('',#74282,#74283); -#74282 = CARTESIAN_POINT('',(0.8509,0.E+000,1.4478)); -#74283 = VECTOR('',#74284,1.); -#74284 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74285 = PCURVE('',#74218,#74286); -#74286 = DEFINITIONAL_REPRESENTATION('',(#74287),#74290); -#74287 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74288,#74289),.UNSPECIFIED., +#76617 = CARTESIAN_POINT('',(3.14159265359,0.2667)); +#76618 = CARTESIAN_POINT('',(3.14159265359,0.7239)); +#76619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76620 = ORIENTED_EDGE('',*,*,#76621,.T.); +#76621 = EDGE_CURVE('',#76593,#76510,#76622,.T.); +#76622 = SURFACE_CURVE('',#76623,(#76627,#76634),.PCURVE_S1.); +#76623 = LINE('',#76624,#76625); +#76624 = CARTESIAN_POINT('',(1.1049,-0.318120283077,1.1811)); +#76625 = VECTOR('',#76626,1.); +#76626 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#76627 = PCURVE('',#76526,#76628); +#76628 = DEFINITIONAL_REPRESENTATION('',(#76629),#76633); +#76629 = LINE('',#76630,#76631); +#76630 = CARTESIAN_POINT('',(-0.2667,0.E+000)); +#76631 = VECTOR('',#76632,1.); +#76632 = DIRECTION('',(0.E+000,-1.)); +#76633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76634 = PCURVE('',#76011,#76635); +#76635 = DEFINITIONAL_REPRESENTATION('',(#76636),#76640); +#76636 = LINE('',#76637,#76638); +#76637 = CARTESIAN_POINT('',(-0.4572,0.196615825673)); +#76638 = VECTOR('',#76639,1.); +#76639 = DIRECTION('',(0.E+000,-1.)); +#76640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76641 = ORIENTED_EDGE('',*,*,#76509,.T.); +#76642 = ORIENTED_EDGE('',*,*,#76643,.T.); +#76643 = EDGE_CURVE('',#76512,#76595,#76644,.T.); +#76644 = SURFACE_CURVE('',#76645,(#76649,#76656),.PCURVE_S1.); +#76645 = LINE('',#76646,#76647); +#76646 = CARTESIAN_POINT('',(1.1049,-0.318120283077,0.7239)); +#76647 = VECTOR('',#76648,1.); +#76648 = DIRECTION('',(0.E+000,1.,0.E+000)); +#76649 = PCURVE('',#76526,#76650); +#76650 = DEFINITIONAL_REPRESENTATION('',(#76651),#76655); +#76651 = LINE('',#76652,#76653); +#76652 = CARTESIAN_POINT('',(-0.7239,0.E+000)); +#76653 = VECTOR('',#76654,1.); +#76654 = DIRECTION('',(0.E+000,1.)); +#76655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76656 = PCURVE('',#75958,#76657); +#76657 = DEFINITIONAL_REPRESENTATION('',(#76658),#76662); +#76658 = LINE('',#76659,#76660); +#76659 = CARTESIAN_POINT('',(0.4572,0.196615825673)); +#76660 = VECTOR('',#76661,1.); +#76661 = DIRECTION('',(0.E+000,1.)); +#76662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76663 = ADVANCED_FACE('',(#76664),#76610,.T.); +#76664 = FACE_BOUND('',#76665,.T.); +#76665 = EDGE_LOOP('',(#76666,#76695,#76716,#76717)); +#76666 = ORIENTED_EDGE('',*,*,#76667,.F.); +#76667 = EDGE_CURVE('',#76668,#76670,#76672,.T.); +#76668 = VERTEX_POINT('',#76669); +#76669 = CARTESIAN_POINT('',(0.8509,0.E+000,1.1811)); +#76670 = VERTEX_POINT('',#76671); +#76671 = CARTESIAN_POINT('',(0.8509,0.E+000,0.7239)); +#76672 = SURFACE_CURVE('',#76673,(#76677,#76683),.PCURVE_S1.); +#76673 = LINE('',#76674,#76675); +#76674 = CARTESIAN_POINT('',(0.8509,0.E+000,1.4478)); +#76675 = VECTOR('',#76676,1.); +#76676 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76677 = PCURVE('',#76610,#76678); +#76678 = DEFINITIONAL_REPRESENTATION('',(#76679),#76682); +#76679 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76680,#76681),.UNSPECIFIED., .F.,.F.,(2,2),(0.2667,0.7239),.PIECEWISE_BEZIER_KNOTS.); -#74288 = CARTESIAN_POINT('',(1.570796326795,0.2667)); -#74289 = CARTESIAN_POINT('',(1.570796326795,0.7239)); -#74290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74291 = PCURVE('',#74292,#74297); -#74292 = PLANE('',#74293); -#74293 = AXIS2_PLACEMENT_3D('',#74294,#74295,#74296); -#74294 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74295 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#74296 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74297 = DEFINITIONAL_REPRESENTATION('',(#74298),#74302); -#74298 = LINE('',#74299,#74300); -#74299 = CARTESIAN_POINT('',(0.E+000,0.2032)); -#74300 = VECTOR('',#74301,1.); -#74301 = DIRECTION('',(1.,0.E+000)); -#74302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74303 = ORIENTED_EDGE('',*,*,#74304,.T.); -#74304 = EDGE_CURVE('',#74276,#74201,#74305,.T.); -#74305 = SURFACE_CURVE('',#74306,(#74311,#74317),.PCURVE_S1.); -#74306 = CIRCLE('',#74307,0.254); -#74307 = AXIS2_PLACEMENT_3D('',#74308,#74309,#74310); -#74308 = CARTESIAN_POINT('',(0.8509,-0.254,1.1811)); -#74309 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); -#74310 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); -#74311 = PCURVE('',#74218,#74312); -#74312 = DEFINITIONAL_REPRESENTATION('',(#74313),#74316); -#74313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74314,#74315),.UNSPECIFIED., +#76680 = CARTESIAN_POINT('',(1.570796326795,0.2667)); +#76681 = CARTESIAN_POINT('',(1.570796326795,0.7239)); +#76682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76683 = PCURVE('',#76684,#76689); +#76684 = PLANE('',#76685); +#76685 = AXIS2_PLACEMENT_3D('',#76686,#76687,#76688); +#76686 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76687 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#76688 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76689 = DEFINITIONAL_REPRESENTATION('',(#76690),#76694); +#76690 = LINE('',#76691,#76692); +#76691 = CARTESIAN_POINT('',(0.E+000,0.2032)); +#76692 = VECTOR('',#76693,1.); +#76693 = DIRECTION('',(1.,0.E+000)); +#76694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76695 = ORIENTED_EDGE('',*,*,#76696,.T.); +#76696 = EDGE_CURVE('',#76668,#76593,#76697,.T.); +#76697 = SURFACE_CURVE('',#76698,(#76703,#76709),.PCURVE_S1.); +#76698 = CIRCLE('',#76699,0.254); +#76699 = AXIS2_PLACEMENT_3D('',#76700,#76701,#76702); +#76700 = CARTESIAN_POINT('',(0.8509,-0.254,1.1811)); +#76701 = DIRECTION('',(3.856562838825E-016,0.E+000,-1.)); +#76702 = DIRECTION('',(-1.,0.E+000,-3.856562838825E-016)); +#76703 = PCURVE('',#76610,#76704); +#76704 = DEFINITIONAL_REPRESENTATION('',(#76705),#76708); +#76705 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76706,#76707),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#74314 = CARTESIAN_POINT('',(1.570796326795,0.2667)); -#74315 = CARTESIAN_POINT('',(3.14159265359,0.2667)); -#74316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74317 = PCURVE('',#73619,#74318); -#74318 = DEFINITIONAL_REPRESENTATION('',(#74319),#74323); -#74319 = CIRCLE('',#74320,0.254); -#74320 = AXIS2_PLACEMENT_2D('',#74321,#74322); -#74321 = CARTESIAN_POINT('',(-0.2032,0.26073610875)); -#74322 = DIRECTION('',(1.,0.E+000)); -#74323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74324 = ORIENTED_EDGE('',*,*,#74200,.T.); -#74325 = ORIENTED_EDGE('',*,*,#74326,.T.); -#74326 = EDGE_CURVE('',#74203,#74278,#74327,.T.); -#74327 = SURFACE_CURVE('',#74328,(#74333,#74339),.PCURVE_S1.); -#74328 = CIRCLE('',#74329,0.254); -#74329 = AXIS2_PLACEMENT_3D('',#74330,#74331,#74332); -#74330 = CARTESIAN_POINT('',(0.8509,-0.254,0.7239)); -#74331 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); -#74332 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); -#74333 = PCURVE('',#74218,#74334); -#74334 = DEFINITIONAL_REPRESENTATION('',(#74335),#74338); -#74335 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#74336,#74337),.UNSPECIFIED., +#76706 = CARTESIAN_POINT('',(1.570796326795,0.2667)); +#76707 = CARTESIAN_POINT('',(3.14159265359,0.2667)); +#76708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76709 = PCURVE('',#76011,#76710); +#76710 = DEFINITIONAL_REPRESENTATION('',(#76711),#76715); +#76711 = CIRCLE('',#76712,0.254); +#76712 = AXIS2_PLACEMENT_2D('',#76713,#76714); +#76713 = CARTESIAN_POINT('',(-0.2032,0.26073610875)); +#76714 = DIRECTION('',(1.,0.E+000)); +#76715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76716 = ORIENTED_EDGE('',*,*,#76592,.T.); +#76717 = ORIENTED_EDGE('',*,*,#76718,.T.); +#76718 = EDGE_CURVE('',#76595,#76670,#76719,.T.); +#76719 = SURFACE_CURVE('',#76720,(#76725,#76731),.PCURVE_S1.); +#76720 = CIRCLE('',#76721,0.254); +#76721 = AXIS2_PLACEMENT_3D('',#76722,#76723,#76724); +#76722 = CARTESIAN_POINT('',(0.8509,-0.254,0.7239)); +#76723 = DIRECTION('',(1.928281419412E-016,0.E+000,1.)); +#76724 = DIRECTION('',(1.,0.E+000,-1.928281419412E-016)); +#76725 = PCURVE('',#76610,#76726); +#76726 = DEFINITIONAL_REPRESENTATION('',(#76727),#76730); +#76727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76728,#76729),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.570796326795),.PIECEWISE_BEZIER_KNOTS.); -#74336 = CARTESIAN_POINT('',(3.14159265359,0.7239)); -#74337 = CARTESIAN_POINT('',(1.570796326795,0.7239)); -#74338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74339 = PCURVE('',#73566,#74340); -#74340 = DEFINITIONAL_REPRESENTATION('',(#74341),#74345); -#74341 = CIRCLE('',#74342,0.254); -#74342 = AXIS2_PLACEMENT_2D('',#74343,#74344); -#74343 = CARTESIAN_POINT('',(0.2032,0.26073610875)); -#74344 = DIRECTION('',(1.,0.E+000)); -#74345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74346 = ADVANCED_FACE('',(#74347),#74292,.F.); -#74347 = FACE_BOUND('',#74348,.T.); -#74348 = EDGE_LOOP('',(#74349,#74374,#74395,#74396)); -#74349 = ORIENTED_EDGE('',*,*,#74350,.F.); -#74350 = EDGE_CURVE('',#74351,#74353,#74355,.T.); -#74351 = VERTEX_POINT('',#74352); -#74352 = CARTESIAN_POINT('',(0.6477,1.647987302178E-014,1.1811)); -#74353 = VERTEX_POINT('',#74354); -#74354 = CARTESIAN_POINT('',(0.6477,-1.084202172486E-015,0.7239)); -#74355 = SURFACE_CURVE('',#74356,(#74360,#74367),.PCURVE_S1.); -#74356 = LINE('',#74357,#74358); -#74357 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74358 = VECTOR('',#74359,1.); -#74359 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74360 = PCURVE('',#74292,#74361); -#74361 = DEFINITIONAL_REPRESENTATION('',(#74362),#74366); -#74362 = LINE('',#74363,#74364); -#74363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74364 = VECTOR('',#74365,1.); -#74365 = DIRECTION('',(1.,0.E+000)); -#74366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74367 = PCURVE('',#71960,#74368); -#74368 = DEFINITIONAL_REPRESENTATION('',(#74369),#74373); -#74369 = LINE('',#74370,#74371); -#74370 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#74371 = VECTOR('',#74372,1.); -#74372 = DIRECTION('',(0.E+000,-1.)); -#74373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74374 = ORIENTED_EDGE('',*,*,#74375,.T.); -#74375 = EDGE_CURVE('',#74351,#74276,#74376,.T.); -#74376 = SURFACE_CURVE('',#74377,(#74381,#74388),.PCURVE_S1.); -#74377 = LINE('',#74378,#74379); -#74378 = CARTESIAN_POINT('',(0.6477,0.E+000,1.1811)); -#74379 = VECTOR('',#74380,1.); -#74380 = DIRECTION('',(1.,0.E+000,3.856562838825E-016)); -#74381 = PCURVE('',#74292,#74382); -#74382 = DEFINITIONAL_REPRESENTATION('',(#74383),#74387); -#74383 = LINE('',#74384,#74385); -#74384 = CARTESIAN_POINT('',(0.2667,1.110223024625E-016)); -#74385 = VECTOR('',#74386,1.); -#74386 = DIRECTION('',(-3.856562838825E-016,1.)); -#74387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74388 = PCURVE('',#73619,#74389); -#74389 = DEFINITIONAL_REPRESENTATION('',(#74390),#74394); -#74390 = LINE('',#74391,#74392); -#74391 = CARTESIAN_POINT('',(-1.887379141863E-015,0.51473610875)); -#74392 = VECTOR('',#74393,1.); -#74393 = DIRECTION('',(-1.,0.E+000)); -#74394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74395 = ORIENTED_EDGE('',*,*,#74275,.T.); -#74396 = ORIENTED_EDGE('',*,*,#74397,.T.); -#74397 = EDGE_CURVE('',#74278,#74353,#74398,.T.); -#74398 = SURFACE_CURVE('',#74399,(#74403,#74410),.PCURVE_S1.); -#74399 = LINE('',#74400,#74401); -#74400 = CARTESIAN_POINT('',(0.6477,0.E+000,0.7239)); -#74401 = VECTOR('',#74402,1.); -#74402 = DIRECTION('',(-1.,0.E+000,1.928281419412E-016)); -#74403 = PCURVE('',#74292,#74404); -#74404 = DEFINITIONAL_REPRESENTATION('',(#74405),#74409); -#74405 = LINE('',#74406,#74407); -#74406 = CARTESIAN_POINT('',(0.7239,-1.110223024625E-016)); -#74407 = VECTOR('',#74408,1.); -#74408 = DIRECTION('',(-1.928281419412E-016,-1.)); -#74409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74410 = PCURVE('',#73566,#74411); -#74411 = DEFINITIONAL_REPRESENTATION('',(#74412),#74416); -#74412 = LINE('',#74413,#74414); -#74413 = CARTESIAN_POINT('',(-2.22044604925E-016,0.51473610875)); -#74414 = VECTOR('',#74415,1.); -#74415 = DIRECTION('',(-1.,0.E+000)); -#74416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74417 = ADVANCED_FACE('',(#74418),#71960,.F.); -#74418 = FACE_BOUND('',#74419,.T.); -#74419 = EDGE_LOOP('',(#74420,#74443,#74466,#74489,#74512,#74533,#74534, - #74555)); -#74420 = ORIENTED_EDGE('',*,*,#74421,.T.); -#74421 = EDGE_CURVE('',#71922,#74422,#74424,.T.); -#74422 = VERTEX_POINT('',#74423); -#74423 = CARTESIAN_POINT('',(0.6477,4.336808689942E-015,-1.4478)); -#74424 = SURFACE_CURVE('',#74425,(#74429,#74436),.PCURVE_S1.); -#74425 = LINE('',#74426,#74427); -#74426 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74427 = VECTOR('',#74428,1.); -#74428 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74429 = PCURVE('',#71960,#74430); -#74430 = DEFINITIONAL_REPRESENTATION('',(#74431),#74435); -#74431 = LINE('',#74432,#74433); -#74432 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#74433 = VECTOR('',#74434,1.); -#74434 = DIRECTION('',(0.E+000,-1.)); -#74435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74436 = PCURVE('',#73465,#74437); -#74437 = DEFINITIONAL_REPRESENTATION('',(#74438),#74442); -#74438 = LINE('',#74439,#74440); -#74439 = CARTESIAN_POINT('',(2.8956,0.51473610875)); -#74440 = VECTOR('',#74441,1.); -#74441 = DIRECTION('',(-1.,0.E+000)); -#74442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74443 = ORIENTED_EDGE('',*,*,#74444,.T.); -#74444 = EDGE_CURVE('',#74422,#74445,#74447,.T.); -#74445 = VERTEX_POINT('',#74446); -#74446 = CARTESIAN_POINT('',(0.596976696061,0.4826,-1.414053320556)); -#74447 = SURFACE_CURVE('',#74448,(#74452,#74459),.PCURVE_S1.); -#74448 = LINE('',#74449,#74450); -#74449 = CARTESIAN_POINT('',(0.5762731525,0.679581058932,-1.400279063092 +#76728 = CARTESIAN_POINT('',(3.14159265359,0.7239)); +#76729 = CARTESIAN_POINT('',(1.570796326795,0.7239)); +#76730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76731 = PCURVE('',#75958,#76732); +#76732 = DEFINITIONAL_REPRESENTATION('',(#76733),#76737); +#76733 = CIRCLE('',#76734,0.254); +#76734 = AXIS2_PLACEMENT_2D('',#76735,#76736); +#76735 = CARTESIAN_POINT('',(0.2032,0.26073610875)); +#76736 = DIRECTION('',(1.,0.E+000)); +#76737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76738 = ADVANCED_FACE('',(#76739),#76684,.F.); +#76739 = FACE_BOUND('',#76740,.T.); +#76740 = EDGE_LOOP('',(#76741,#76766,#76787,#76788)); +#76741 = ORIENTED_EDGE('',*,*,#76742,.F.); +#76742 = EDGE_CURVE('',#76743,#76745,#76747,.T.); +#76743 = VERTEX_POINT('',#76744); +#76744 = CARTESIAN_POINT('',(0.6477,1.647987302178E-014,1.1811)); +#76745 = VERTEX_POINT('',#76746); +#76746 = CARTESIAN_POINT('',(0.6477,-1.084202172486E-015,0.7239)); +#76747 = SURFACE_CURVE('',#76748,(#76752,#76759),.PCURVE_S1.); +#76748 = LINE('',#76749,#76750); +#76749 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76750 = VECTOR('',#76751,1.); +#76751 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76752 = PCURVE('',#76684,#76753); +#76753 = DEFINITIONAL_REPRESENTATION('',(#76754),#76758); +#76754 = LINE('',#76755,#76756); +#76755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76756 = VECTOR('',#76757,1.); +#76757 = DIRECTION('',(1.,0.E+000)); +#76758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76759 = PCURVE('',#74352,#76760); +#76760 = DEFINITIONAL_REPRESENTATION('',(#76761),#76765); +#76761 = LINE('',#76762,#76763); +#76762 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#76763 = VECTOR('',#76764,1.); +#76764 = DIRECTION('',(0.E+000,-1.)); +#76765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76766 = ORIENTED_EDGE('',*,*,#76767,.T.); +#76767 = EDGE_CURVE('',#76743,#76668,#76768,.T.); +#76768 = SURFACE_CURVE('',#76769,(#76773,#76780),.PCURVE_S1.); +#76769 = LINE('',#76770,#76771); +#76770 = CARTESIAN_POINT('',(0.6477,0.E+000,1.1811)); +#76771 = VECTOR('',#76772,1.); +#76772 = DIRECTION('',(1.,0.E+000,3.856562838825E-016)); +#76773 = PCURVE('',#76684,#76774); +#76774 = DEFINITIONAL_REPRESENTATION('',(#76775),#76779); +#76775 = LINE('',#76776,#76777); +#76776 = CARTESIAN_POINT('',(0.2667,1.110223024625E-016)); +#76777 = VECTOR('',#76778,1.); +#76778 = DIRECTION('',(-3.856562838825E-016,1.)); +#76779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76780 = PCURVE('',#76011,#76781); +#76781 = DEFINITIONAL_REPRESENTATION('',(#76782),#76786); +#76782 = LINE('',#76783,#76784); +#76783 = CARTESIAN_POINT('',(-1.887379141863E-015,0.51473610875)); +#76784 = VECTOR('',#76785,1.); +#76785 = DIRECTION('',(-1.,0.E+000)); +#76786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76787 = ORIENTED_EDGE('',*,*,#76667,.T.); +#76788 = ORIENTED_EDGE('',*,*,#76789,.T.); +#76789 = EDGE_CURVE('',#76670,#76745,#76790,.T.); +#76790 = SURFACE_CURVE('',#76791,(#76795,#76802),.PCURVE_S1.); +#76791 = LINE('',#76792,#76793); +#76792 = CARTESIAN_POINT('',(0.6477,0.E+000,0.7239)); +#76793 = VECTOR('',#76794,1.); +#76794 = DIRECTION('',(-1.,0.E+000,1.928281419412E-016)); +#76795 = PCURVE('',#76684,#76796); +#76796 = DEFINITIONAL_REPRESENTATION('',(#76797),#76801); +#76797 = LINE('',#76798,#76799); +#76798 = CARTESIAN_POINT('',(0.7239,-1.110223024625E-016)); +#76799 = VECTOR('',#76800,1.); +#76800 = DIRECTION('',(-1.928281419412E-016,-1.)); +#76801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76802 = PCURVE('',#75958,#76803); +#76803 = DEFINITIONAL_REPRESENTATION('',(#76804),#76808); +#76804 = LINE('',#76805,#76806); +#76805 = CARTESIAN_POINT('',(-2.22044604925E-016,0.51473610875)); +#76806 = VECTOR('',#76807,1.); +#76807 = DIRECTION('',(-1.,0.E+000)); +#76808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76809 = ADVANCED_FACE('',(#76810),#74352,.F.); +#76810 = FACE_BOUND('',#76811,.T.); +#76811 = EDGE_LOOP('',(#76812,#76835,#76858,#76881,#76904,#76925,#76926, + #76947)); +#76812 = ORIENTED_EDGE('',*,*,#76813,.T.); +#76813 = EDGE_CURVE('',#74314,#76814,#76816,.T.); +#76814 = VERTEX_POINT('',#76815); +#76815 = CARTESIAN_POINT('',(0.6477,4.336808689942E-015,-1.4478)); +#76816 = SURFACE_CURVE('',#76817,(#76821,#76828),.PCURVE_S1.); +#76817 = LINE('',#76818,#76819); +#76818 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76819 = VECTOR('',#76820,1.); +#76820 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76821 = PCURVE('',#74352,#76822); +#76822 = DEFINITIONAL_REPRESENTATION('',(#76823),#76827); +#76823 = LINE('',#76824,#76825); +#76824 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#76825 = VECTOR('',#76826,1.); +#76826 = DIRECTION('',(0.E+000,-1.)); +#76827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76828 = PCURVE('',#75857,#76829); +#76829 = DEFINITIONAL_REPRESENTATION('',(#76830),#76834); +#76830 = LINE('',#76831,#76832); +#76831 = CARTESIAN_POINT('',(2.8956,0.51473610875)); +#76832 = VECTOR('',#76833,1.); +#76833 = DIRECTION('',(-1.,0.E+000)); +#76834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76835 = ORIENTED_EDGE('',*,*,#76836,.T.); +#76836 = EDGE_CURVE('',#76814,#76837,#76839,.T.); +#76837 = VERTEX_POINT('',#76838); +#76838 = CARTESIAN_POINT('',(0.596976696061,0.4826,-1.414053320556)); +#76839 = SURFACE_CURVE('',#76840,(#76844,#76851),.PCURVE_S1.); +#76840 = LINE('',#76841,#76842); +#76841 = CARTESIAN_POINT('',(0.5762731525,0.679581058932,-1.400279063092 )); -#74450 = VECTOR('',#74451,1.); -#74451 = DIRECTION('',(-0.104276609233,0.992125664297,6.93761847516E-002 +#76842 = VECTOR('',#76843,1.); +#76843 = DIRECTION('',(-0.104276609233,0.992125664297,6.93761847516E-002 )); -#74452 = PCURVE('',#71960,#74453); -#74453 = DEFINITIONAL_REPRESENTATION('',(#74454),#74458); -#74454 = LINE('',#74455,#74456); -#74455 = CARTESIAN_POINT('',(-0.198066085673,-2.848079063092)); -#74456 = VECTOR('',#74457,1.); -#74457 = DIRECTION('',(-0.997590569818,6.93761847516E-002)); -#74458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74459 = PCURVE('',#72047,#74460); -#74460 = DEFINITIONAL_REPRESENTATION('',(#74461),#74465); -#74461 = LINE('',#74462,#74463); -#74462 = CARTESIAN_POINT('',(-0.197462066602,1.3382731525)); -#74463 = VECTOR('',#74464,1.); -#74464 = DIRECTION('',(-0.994548334053,-0.104276609233)); -#74465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74466 = ORIENTED_EDGE('',*,*,#74467,.F.); -#74467 = EDGE_CURVE('',#74468,#74445,#74470,.T.); -#74468 = VERTEX_POINT('',#74469); -#74469 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.414053320556)); -#74470 = SURFACE_CURVE('',#74471,(#74475,#74482),.PCURVE_S1.); -#74471 = LINE('',#74472,#74473); -#74472 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.4478)); -#74473 = VECTOR('',#74474,1.); -#74474 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74475 = PCURVE('',#71960,#74476); -#74476 = DEFINITIONAL_REPRESENTATION('',(#74477),#74481); -#74477 = LINE('',#74478,#74479); -#74478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74479 = VECTOR('',#74480,1.); -#74480 = DIRECTION('',(0.E+000,-1.)); -#74481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74482 = PCURVE('',#72019,#74483); -#74483 = DEFINITIONAL_REPRESENTATION('',(#74484),#74488); -#74484 = LINE('',#74485,#74486); -#74485 = CARTESIAN_POINT('',(0.E+000,1.193953392122)); -#74486 = VECTOR('',#74487,1.); -#74487 = DIRECTION('',(1.,0.E+000)); -#74488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74489 = ORIENTED_EDGE('',*,*,#74490,.T.); -#74490 = EDGE_CURVE('',#74468,#74491,#74493,.T.); -#74491 = VERTEX_POINT('',#74492); -#74492 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74493 = SURFACE_CURVE('',#74494,(#74498,#74505),.PCURVE_S1.); -#74494 = LINE('',#74495,#74496); -#74495 = CARTESIAN_POINT('',(0.597220830113,0.480277219652, +#76844 = PCURVE('',#74352,#76845); +#76845 = DEFINITIONAL_REPRESENTATION('',(#76846),#76850); +#76846 = LINE('',#76847,#76848); +#76847 = CARTESIAN_POINT('',(-0.198066085673,-2.848079063092)); +#76848 = VECTOR('',#76849,1.); +#76849 = DIRECTION('',(-0.997590569818,6.93761847516E-002)); +#76850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76851 = PCURVE('',#74439,#76852); +#76852 = DEFINITIONAL_REPRESENTATION('',(#76853),#76857); +#76853 = LINE('',#76854,#76855); +#76854 = CARTESIAN_POINT('',(-0.197462066602,1.3382731525)); +#76855 = VECTOR('',#76856,1.); +#76856 = DIRECTION('',(-0.994548334053,-0.104276609233)); +#76857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76858 = ORIENTED_EDGE('',*,*,#76859,.F.); +#76859 = EDGE_CURVE('',#76860,#76837,#76862,.T.); +#76860 = VERTEX_POINT('',#76861); +#76861 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.414053320556)); +#76862 = SURFACE_CURVE('',#76863,(#76867,#76874),.PCURVE_S1.); +#76863 = LINE('',#76864,#76865); +#76864 = CARTESIAN_POINT('',(0.596976696061,0.4826,1.4478)); +#76865 = VECTOR('',#76866,1.); +#76866 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76867 = PCURVE('',#74352,#76868); +#76868 = DEFINITIONAL_REPRESENTATION('',(#76869),#76873); +#76869 = LINE('',#76870,#76871); +#76870 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76871 = VECTOR('',#76872,1.); +#76872 = DIRECTION('',(0.E+000,-1.)); +#76873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76874 = PCURVE('',#74411,#76875); +#76875 = DEFINITIONAL_REPRESENTATION('',(#76876),#76880); +#76876 = LINE('',#76877,#76878); +#76877 = CARTESIAN_POINT('',(0.E+000,1.193953392122)); +#76878 = VECTOR('',#76879,1.); +#76879 = DIRECTION('',(1.,0.E+000)); +#76880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76881 = ORIENTED_EDGE('',*,*,#76882,.T.); +#76882 = EDGE_CURVE('',#76860,#76883,#76885,.T.); +#76883 = VERTEX_POINT('',#76884); +#76884 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76885 = SURFACE_CURVE('',#76886,(#76890,#76897),.PCURVE_S1.); +#76886 = LINE('',#76887,#76888); +#76887 = CARTESIAN_POINT('',(0.597220830113,0.480277219652, 1.414215745181)); -#74496 = VECTOR('',#74497,1.); -#74497 = DIRECTION('',(0.104276609233,-0.992125664297,6.93761847516E-002 +#76888 = VECTOR('',#76889,1.); +#76889 = DIRECTION('',(0.104276609233,-0.992125664297,6.93761847516E-002 )); -#74498 = PCURVE('',#71960,#74499); -#74499 = DEFINITIONAL_REPRESENTATION('',(#74500),#74504); -#74500 = LINE('',#74501,#74502); -#74501 = CARTESIAN_POINT('',(2.33557487168E-003,-3.358425481934E-002)); -#74502 = VECTOR('',#74503,1.); -#74503 = DIRECTION('',(0.997590569818,6.93761847516E-002)); -#74504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74505 = PCURVE('',#72157,#74506); -#74506 = DEFINITIONAL_REPRESENTATION('',(#74507),#74511); -#74507 = LINE('',#74508,#74509); -#74508 = CARTESIAN_POINT('',(-2.328452341033E-003,1.359220830113)); -#74509 = VECTOR('',#74510,1.); -#74510 = DIRECTION('',(-0.994548334053,0.104276609233)); -#74511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74512 = ORIENTED_EDGE('',*,*,#74513,.T.); -#74513 = EDGE_CURVE('',#74491,#74351,#74514,.T.); -#74514 = SURFACE_CURVE('',#74515,(#74519,#74526),.PCURVE_S1.); -#74515 = LINE('',#74516,#74517); -#74516 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74517 = VECTOR('',#74518,1.); -#74518 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74519 = PCURVE('',#71960,#74520); -#74520 = DEFINITIONAL_REPRESENTATION('',(#74521),#74525); -#74521 = LINE('',#74522,#74523); -#74522 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#74523 = VECTOR('',#74524,1.); -#74524 = DIRECTION('',(0.E+000,-1.)); -#74525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74526 = PCURVE('',#73392,#74527); -#74527 = DEFINITIONAL_REPRESENTATION('',(#74528),#74532); -#74528 = LINE('',#74529,#74530); -#74529 = CARTESIAN_POINT('',(0.E+000,0.51473610875)); -#74530 = VECTOR('',#74531,1.); -#74531 = DIRECTION('',(-1.,0.E+000)); -#74532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74533 = ORIENTED_EDGE('',*,*,#74350,.T.); -#74534 = ORIENTED_EDGE('',*,*,#74535,.T.); -#74535 = EDGE_CURVE('',#74353,#71945,#74536,.T.); -#74536 = SURFACE_CURVE('',#74537,(#74541,#74548),.PCURVE_S1.); -#74537 = LINE('',#74538,#74539); -#74538 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); -#74539 = VECTOR('',#74540,1.); -#74540 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#74541 = PCURVE('',#71960,#74542); -#74542 = DEFINITIONAL_REPRESENTATION('',(#74543),#74547); -#74543 = LINE('',#74544,#74545); -#74544 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); -#74545 = VECTOR('',#74546,1.); -#74546 = DIRECTION('',(0.E+000,-1.)); -#74547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74548 = PCURVE('',#73538,#74549); -#74549 = DEFINITIONAL_REPRESENTATION('',(#74550),#74554); -#74550 = LINE('',#74551,#74552); -#74551 = CARTESIAN_POINT('',(2.1717,0.51473610875)); -#74552 = VECTOR('',#74553,1.); -#74553 = DIRECTION('',(-1.,0.E+000)); -#74554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74555 = ORIENTED_EDGE('',*,*,#71944,.T.); -#74556 = ADVANCED_FACE('',(#74557),#72019,.F.); -#74557 = FACE_BOUND('',#74558,.T.); -#74558 = EDGE_LOOP('',(#74559,#74560,#74581,#74582)); -#74559 = ORIENTED_EDGE('',*,*,#74467,.T.); -#74560 = ORIENTED_EDGE('',*,*,#74561,.F.); -#74561 = EDGE_CURVE('',#71999,#74445,#74562,.T.); -#74562 = SURFACE_CURVE('',#74563,(#74567,#74574),.PCURVE_S1.); -#74563 = LINE('',#74564,#74565); -#74564 = CARTESIAN_POINT('',(-0.762,0.4826,-1.414053320556)); -#74565 = VECTOR('',#74566,1.); -#74566 = DIRECTION('',(1.,0.E+000,0.E+000)); -#74567 = PCURVE('',#72019,#74568); -#74568 = DEFINITIONAL_REPRESENTATION('',(#74569),#74573); -#74569 = LINE('',#74570,#74571); -#74570 = CARTESIAN_POINT('',(2.861853320556,-0.165023303939)); -#74571 = VECTOR('',#74572,1.); -#74572 = DIRECTION('',(0.E+000,1.)); -#74573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74574 = PCURVE('',#72047,#74575); -#74575 = DEFINITIONAL_REPRESENTATION('',(#74576),#74580); -#74576 = LINE('',#74577,#74578); -#74577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74578 = VECTOR('',#74579,1.); -#74579 = DIRECTION('',(0.E+000,1.)); -#74580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74581 = ORIENTED_EDGE('',*,*,#71996,.F.); -#74582 = ORIENTED_EDGE('',*,*,#74583,.T.); -#74583 = EDGE_CURVE('',#71997,#74468,#74584,.T.); -#74584 = SURFACE_CURVE('',#74585,(#74589,#74596),.PCURVE_S1.); -#74585 = LINE('',#74586,#74587); -#74586 = CARTESIAN_POINT('',(-0.762,0.4826,1.414053320556)); -#74587 = VECTOR('',#74588,1.); -#74588 = DIRECTION('',(1.,0.E+000,0.E+000)); -#74589 = PCURVE('',#72019,#74590); -#74590 = DEFINITIONAL_REPRESENTATION('',(#74591),#74595); -#74591 = LINE('',#74592,#74593); -#74592 = CARTESIAN_POINT('',(3.374667944393E-002,-0.165023303939)); -#74593 = VECTOR('',#74594,1.); -#74594 = DIRECTION('',(0.E+000,1.)); -#74595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74596 = PCURVE('',#72157,#74597); -#74597 = DEFINITIONAL_REPRESENTATION('',(#74598),#74602); -#74598 = LINE('',#74599,#74600); -#74599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74600 = VECTOR('',#74601,1.); -#74601 = DIRECTION('',(0.E+000,1.)); -#74602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74603 = ADVANCED_FACE('',(#74604),#72242,.F.); -#74604 = FACE_BOUND('',#74605,.T.); -#74605 = EDGE_LOOP('',(#74606,#74627,#74628,#74629,#74630,#74631,#74632, - #74633,#74634,#74635,#74636,#74637)); -#74606 = ORIENTED_EDGE('',*,*,#74607,.F.); -#74607 = EDGE_CURVE('',#73077,#72060,#74608,.T.); -#74608 = SURFACE_CURVE('',#74609,(#74613,#74620),.PCURVE_S1.); -#74609 = LINE('',#74610,#74611); -#74610 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,-0.2286)); -#74611 = VECTOR('',#74612,1.); -#74612 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74613 = PCURVE('',#72242,#74614); -#74614 = DEFINITIONAL_REPRESENTATION('',(#74615),#74619); -#74615 = LINE('',#74616,#74617); -#74616 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); -#74617 = VECTOR('',#74618,1.); -#74618 = DIRECTION('',(0.E+000,1.)); -#74619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74620 = PCURVE('',#72075,#74621); -#74621 = DEFINITIONAL_REPRESENTATION('',(#74622),#74626); -#74622 = LINE('',#74623,#74624); -#74623 = CARTESIAN_POINT('',(-1.2192,0.E+000)); -#74624 = VECTOR('',#74625,1.); -#74625 = DIRECTION('',(0.E+000,1.)); -#74626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74627 = ORIENTED_EDGE('',*,*,#73076,.F.); -#74628 = ORIENTED_EDGE('',*,*,#72919,.F.); -#74629 = ORIENTED_EDGE('',*,*,#72866,.F.); -#74630 = ORIENTED_EDGE('',*,*,#72768,.F.); -#74631 = ORIENTED_EDGE('',*,*,#72693,.F.); -#74632 = ORIENTED_EDGE('',*,*,#72618,.T.); -#74633 = ORIENTED_EDGE('',*,*,#72542,.F.); -#74634 = ORIENTED_EDGE('',*,*,#72436,.F.); -#74635 = ORIENTED_EDGE('',*,*,#72383,.F.); -#74636 = ORIENTED_EDGE('',*,*,#72308,.F.); -#74637 = ORIENTED_EDGE('',*,*,#72228,.F.); -#74638 = ADVANCED_FACE('',(#74639),#72075,.F.); -#74639 = FACE_BOUND('',#74640,.T.); -#74640 = EDGE_LOOP('',(#74641,#74642,#74663,#74664)); -#74641 = ORIENTED_EDGE('',*,*,#72059,.F.); -#74642 = ORIENTED_EDGE('',*,*,#74643,.T.); -#74643 = EDGE_CURVE('',#72032,#73100,#74644,.T.); -#74644 = SURFACE_CURVE('',#74645,(#74649,#74656),.PCURVE_S1.); -#74645 = LINE('',#74646,#74647); -#74646 = CARTESIAN_POINT('',(-0.6477,-0.512231420537,-1.411981289785)); -#74647 = VECTOR('',#74648,1.); -#74648 = DIRECTION('',(0.E+000,-0.99756405026,6.975647374412E-002)); -#74649 = PCURVE('',#72075,#74650); -#74650 = DEFINITIONAL_REPRESENTATION('',(#74651),#74655); -#74651 = LINE('',#74652,#74653); -#74652 = CARTESIAN_POINT('',(-3.581871021541E-002,2.504688213292E-003)); -#74653 = VECTOR('',#74654,1.); -#74654 = DIRECTION('',(-6.975647374412E-002,-0.99756405026)); -#74655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74656 = PCURVE('',#73136,#74657); -#74657 = DEFINITIONAL_REPRESENTATION('',(#74658),#74662); -#74658 = LINE('',#74659,#74660); -#74659 = CARTESIAN_POINT('',(0.513482237459,0.1143)); -#74660 = VECTOR('',#74661,1.); -#74661 = DIRECTION('',(1.,0.E+000)); -#74662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74663 = ORIENTED_EDGE('',*,*,#73099,.F.); -#74664 = ORIENTED_EDGE('',*,*,#74607,.T.); -#74665 = ADVANCED_FACE('',(#74666),#72215,.F.); -#74666 = FACE_BOUND('',#74667,.T.); -#74667 = EDGE_LOOP('',(#74668,#74669,#74670,#74671,#74672,#74673,#74674, - #74675,#74676,#74677,#74678,#74699)); -#74668 = ORIENTED_EDGE('',*,*,#72286,.F.); -#74669 = ORIENTED_EDGE('',*,*,#72361,.F.); -#74670 = ORIENTED_EDGE('',*,*,#72462,.F.); -#74671 = ORIENTED_EDGE('',*,*,#72520,.F.); -#74672 = ORIENTED_EDGE('',*,*,#72596,.F.); -#74673 = ORIENTED_EDGE('',*,*,#72671,.F.); -#74674 = ORIENTED_EDGE('',*,*,#72746,.F.); -#74675 = ORIENTED_EDGE('',*,*,#72844,.F.); -#74676 = ORIENTED_EDGE('',*,*,#72945,.F.); -#74677 = ORIENTED_EDGE('',*,*,#73054,.F.); -#74678 = ORIENTED_EDGE('',*,*,#74679,.T.); -#74679 = EDGE_CURVE('',#73032,#72088,#74680,.T.); -#74680 = SURFACE_CURVE('',#74681,(#74685,#74692),.PCURVE_S1.); -#74681 = LINE('',#74682,#74683); -#74682 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,0.2286)); -#74683 = VECTOR('',#74684,1.); -#74684 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74685 = PCURVE('',#72215,#74686); -#74686 = DEFINITIONAL_REPRESENTATION('',(#74687),#74691); -#74687 = LINE('',#74688,#74689); -#74688 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); -#74689 = VECTOR('',#74690,1.); -#74690 = DIRECTION('',(0.E+000,1.)); -#74691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74692 = PCURVE('',#72131,#74693); -#74693 = DEFINITIONAL_REPRESENTATION('',(#74694),#74698); -#74694 = LINE('',#74695,#74696); -#74695 = CARTESIAN_POINT('',(1.2192,0.E+000)); -#74696 = VECTOR('',#74697,1.); -#74697 = DIRECTION('',(0.E+000,1.)); -#74698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74699 = ORIENTED_EDGE('',*,*,#72201,.F.); -#74700 = ADVANCED_FACE('',(#74701),#72131,.F.); -#74701 = FACE_BOUND('',#74702,.T.); -#74702 = EDGE_LOOP('',(#74703,#74704,#74725,#74726)); -#74703 = ORIENTED_EDGE('',*,*,#73031,.F.); -#74704 = ORIENTED_EDGE('',*,*,#74705,.T.); -#74705 = EDGE_CURVE('',#73004,#72116,#74706,.T.); -#74706 = SURFACE_CURVE('',#74707,(#74711,#74718),.PCURVE_S1.); -#74707 = LINE('',#74708,#74709); -#74708 = CARTESIAN_POINT('',(-0.6477,-0.512231420537,1.411981289785)); -#74709 = VECTOR('',#74710,1.); -#74710 = DIRECTION('',(0.E+000,0.99756405026,6.975647374412E-002)); -#74711 = PCURVE('',#72131,#74712); -#74712 = DEFINITIONAL_REPRESENTATION('',(#74713),#74717); -#74713 = LINE('',#74714,#74715); -#74714 = CARTESIAN_POINT('',(3.581871021541E-002,2.504688213292E-003)); -#74715 = VECTOR('',#74716,1.); -#74716 = DIRECTION('',(-6.975647374412E-002,0.99756405026)); -#74717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74718 = PCURVE('',#73019,#74719); -#74719 = DEFINITIONAL_REPRESENTATION('',(#74720),#74724); -#74720 = LINE('',#74721,#74722); -#74721 = CARTESIAN_POINT('',(-0.513482237459,0.1143)); -#74722 = VECTOR('',#74723,1.); -#74723 = DIRECTION('',(1.,0.E+000)); -#74724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74725 = ORIENTED_EDGE('',*,*,#72115,.T.); -#74726 = ORIENTED_EDGE('',*,*,#74679,.F.); -#74727 = ADVANCED_FACE('',(#74728),#71211,.F.); -#74728 = FACE_BOUND('',#74729,.T.); -#74729 = EDGE_LOOP('',(#74730,#74731,#74732,#74733,#74734,#74735,#74736, - #74737,#74738,#74739,#74740,#74761)); -#74730 = ORIENTED_EDGE('',*,*,#71195,.F.); -#74731 = ORIENTED_EDGE('',*,*,#71361,.F.); -#74732 = ORIENTED_EDGE('',*,*,#71436,.F.); -#74733 = ORIENTED_EDGE('',*,*,#71512,.F.); -#74734 = ORIENTED_EDGE('',*,*,#71588,.T.); -#74735 = ORIENTED_EDGE('',*,*,#71663,.F.); -#74736 = ORIENTED_EDGE('',*,*,#71688,.F.); -#74737 = ORIENTED_EDGE('',*,*,#71821,.F.); -#74738 = ORIENTED_EDGE('',*,*,#71896,.F.); -#74739 = ORIENTED_EDGE('',*,*,#71972,.F.); -#74740 = ORIENTED_EDGE('',*,*,#74741,.F.); -#74741 = EDGE_CURVE('',#73500,#71945,#74742,.T.); -#74742 = SURFACE_CURVE('',#74743,(#74747,#74754),.PCURVE_S1.); -#74743 = LINE('',#74744,#74745); -#74744 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); -#74745 = VECTOR('',#74746,1.); -#74746 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74747 = PCURVE('',#71211,#74748); -#74748 = DEFINITIONAL_REPRESENTATION('',(#74749),#74753); -#74749 = LINE('',#74750,#74751); -#74750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74751 = VECTOR('',#74752,1.); -#74752 = DIRECTION('',(0.E+000,1.)); -#74753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74754 = PCURVE('',#73538,#74755); -#74755 = DEFINITIONAL_REPRESENTATION('',(#74756),#74760); -#74756 = LINE('',#74757,#74758); -#74757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74758 = VECTOR('',#74759,1.); -#74759 = DIRECTION('',(0.E+000,1.)); -#74760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74761 = ORIENTED_EDGE('',*,*,#73499,.F.); -#74762 = ADVANCED_FACE('',(#74763),#73566,.F.); -#74763 = FACE_BOUND('',#74764,.T.); -#74764 = EDGE_LOOP('',(#74765,#74786,#74787,#74788,#74789,#74790,#74791, - #74792,#74793,#74794,#74795,#74796)); -#74765 = ORIENTED_EDGE('',*,*,#74766,.T.); -#74766 = EDGE_CURVE('',#73523,#74353,#74767,.T.); -#74767 = SURFACE_CURVE('',#74768,(#74772,#74779),.PCURVE_S1.); -#74768 = LINE('',#74769,#74770); -#74769 = CARTESIAN_POINT('',(0.6477,-0.51473610875,0.7239)); -#74770 = VECTOR('',#74771,1.); -#74771 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74772 = PCURVE('',#73566,#74773); -#74773 = DEFINITIONAL_REPRESENTATION('',(#74774),#74778); -#74774 = LINE('',#74775,#74776); -#74775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74776 = VECTOR('',#74777,1.); -#74777 = DIRECTION('',(0.E+000,1.)); -#74778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74779 = PCURVE('',#73538,#74780); -#74780 = DEFINITIONAL_REPRESENTATION('',(#74781),#74785); -#74781 = LINE('',#74782,#74783); -#74782 = CARTESIAN_POINT('',(1.4478,0.E+000)); -#74783 = VECTOR('',#74784,1.); -#74784 = DIRECTION('',(0.E+000,1.)); -#74785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74786 = ORIENTED_EDGE('',*,*,#74397,.F.); -#74787 = ORIENTED_EDGE('',*,*,#74326,.F.); -#74788 = ORIENTED_EDGE('',*,*,#74251,.F.); -#74789 = ORIENTED_EDGE('',*,*,#74146,.F.); -#74790 = ORIENTED_EDGE('',*,*,#74093,.F.); -#74791 = ORIENTED_EDGE('',*,*,#74018,.F.); -#74792 = ORIENTED_EDGE('',*,*,#73942,.F.); -#74793 = ORIENTED_EDGE('',*,*,#73866,.F.); -#74794 = ORIENTED_EDGE('',*,*,#73791,.F.); -#74795 = ORIENTED_EDGE('',*,*,#73663,.F.); -#74796 = ORIENTED_EDGE('',*,*,#73550,.F.); -#74797 = ADVANCED_FACE('',(#74798),#73538,.F.); -#74798 = FACE_BOUND('',#74799,.T.); -#74799 = EDGE_LOOP('',(#74800,#74801,#74802,#74803)); -#74800 = ORIENTED_EDGE('',*,*,#74741,.T.); -#74801 = ORIENTED_EDGE('',*,*,#74535,.F.); -#74802 = ORIENTED_EDGE('',*,*,#74766,.F.); -#74803 = ORIENTED_EDGE('',*,*,#73522,.F.); -#74804 = ADVANCED_FACE('',(#74805),#71268,.F.); -#74805 = FACE_BOUND('',#74806,.T.); -#74806 = EDGE_LOOP('',(#74807,#74808,#74809,#74810,#74811,#74812,#74813, - #74834,#74835,#74836,#74837,#74838)); -#74807 = ORIENTED_EDGE('',*,*,#71537,.F.); -#74808 = ORIENTED_EDGE('',*,*,#71461,.F.); -#74809 = ORIENTED_EDGE('',*,*,#71386,.F.); -#74810 = ORIENTED_EDGE('',*,*,#71288,.F.); -#74811 = ORIENTED_EDGE('',*,*,#71254,.F.); -#74812 = ORIENTED_EDGE('',*,*,#73477,.F.); -#74813 = ORIENTED_EDGE('',*,*,#74814,.T.); -#74814 = EDGE_CURVE('',#73450,#71922,#74815,.T.); -#74815 = SURFACE_CURVE('',#74816,(#74820,#74827),.PCURVE_S1.); -#74816 = LINE('',#74817,#74818); -#74817 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.1811)); -#74818 = VECTOR('',#74819,1.); -#74819 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74820 = PCURVE('',#71268,#74821); -#74821 = DEFINITIONAL_REPRESENTATION('',(#74822),#74826); -#74822 = LINE('',#74823,#74824); -#74823 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74824 = VECTOR('',#74825,1.); -#74825 = DIRECTION('',(0.E+000,1.)); -#74826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74827 = PCURVE('',#73465,#74828); -#74828 = DEFINITIONAL_REPRESENTATION('',(#74829),#74833); -#74829 = LINE('',#74830,#74831); -#74830 = CARTESIAN_POINT('',(0.2667,0.E+000)); -#74831 = VECTOR('',#74832,1.); -#74832 = DIRECTION('',(0.E+000,1.)); -#74833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74834 = ORIENTED_EDGE('',*,*,#71921,.F.); -#74835 = ORIENTED_EDGE('',*,*,#71846,.F.); -#74836 = ORIENTED_EDGE('',*,*,#71771,.F.); -#74837 = ORIENTED_EDGE('',*,*,#71742,.F.); -#74838 = ORIENTED_EDGE('',*,*,#71613,.F.); -#74839 = ADVANCED_FACE('',(#74840),#73465,.F.); -#74840 = FACE_BOUND('',#74841,.T.); -#74841 = EDGE_LOOP('',(#74842,#74843,#74864,#74865)); -#74842 = ORIENTED_EDGE('',*,*,#73449,.F.); -#74843 = ORIENTED_EDGE('',*,*,#74844,.T.); -#74844 = EDGE_CURVE('',#73427,#74422,#74845,.T.); -#74845 = SURFACE_CURVE('',#74846,(#74850,#74857),.PCURVE_S1.); -#74846 = LINE('',#74847,#74848); -#74847 = CARTESIAN_POINT('',(0.6477,-0.512231420537,-1.411981289785)); -#74848 = VECTOR('',#74849,1.); -#74849 = DIRECTION('',(0.E+000,0.99756405026,-6.975647374412E-002)); -#74850 = PCURVE('',#73465,#74851); -#74851 = DEFINITIONAL_REPRESENTATION('',(#74852),#74856); -#74852 = LINE('',#74853,#74854); -#74853 = CARTESIAN_POINT('',(3.581871021541E-002,2.504688213292E-003)); -#74854 = VECTOR('',#74855,1.); -#74855 = DIRECTION('',(-6.975647374412E-002,0.99756405026)); -#74856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74857 = PCURVE('',#73136,#74858); -#74858 = DEFINITIONAL_REPRESENTATION('',(#74859),#74863); -#74859 = LINE('',#74860,#74861); -#74860 = CARTESIAN_POINT('',(0.513482237459,1.4097)); -#74861 = VECTOR('',#74862,1.); -#74862 = DIRECTION('',(-1.,0.E+000)); -#74863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74864 = ORIENTED_EDGE('',*,*,#74421,.F.); -#74865 = ORIENTED_EDGE('',*,*,#74814,.F.); -#74866 = ADVANCED_FACE('',(#74867),#73619,.F.); -#74867 = FACE_BOUND('',#74868,.T.); -#74868 = EDGE_LOOP('',(#74869,#74870,#74871,#74872,#74873,#74874,#74875, - #74876,#74877,#74878,#74879,#74900)); -#74869 = ORIENTED_EDGE('',*,*,#73689,.F.); -#74870 = ORIENTED_EDGE('',*,*,#73769,.F.); -#74871 = ORIENTED_EDGE('',*,*,#73844,.F.); -#74872 = ORIENTED_EDGE('',*,*,#73920,.F.); -#74873 = ORIENTED_EDGE('',*,*,#73996,.T.); -#74874 = ORIENTED_EDGE('',*,*,#74071,.F.); -#74875 = ORIENTED_EDGE('',*,*,#74172,.F.); -#74876 = ORIENTED_EDGE('',*,*,#74229,.F.); -#74877 = ORIENTED_EDGE('',*,*,#74304,.F.); -#74878 = ORIENTED_EDGE('',*,*,#74375,.F.); -#74879 = ORIENTED_EDGE('',*,*,#74880,.F.); -#74880 = EDGE_CURVE('',#73375,#74351,#74881,.T.); -#74881 = SURFACE_CURVE('',#74882,(#74886,#74893),.PCURVE_S1.); -#74882 = LINE('',#74883,#74884); -#74883 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.1811)); -#74884 = VECTOR('',#74885,1.); -#74885 = DIRECTION('',(0.E+000,1.,0.E+000)); -#74886 = PCURVE('',#73619,#74887); -#74887 = DEFINITIONAL_REPRESENTATION('',(#74888),#74892); -#74888 = LINE('',#74889,#74890); -#74889 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#74890 = VECTOR('',#74891,1.); -#74891 = DIRECTION('',(0.E+000,1.)); -#74892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74893 = PCURVE('',#73392,#74894); -#74894 = DEFINITIONAL_REPRESENTATION('',(#74895),#74899); -#74895 = LINE('',#74896,#74897); -#74896 = CARTESIAN_POINT('',(-0.2667,0.E+000)); -#74897 = VECTOR('',#74898,1.); -#74898 = DIRECTION('',(0.E+000,1.)); -#74899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74900 = ORIENTED_EDGE('',*,*,#73605,.F.); -#74901 = ADVANCED_FACE('',(#74902),#73392,.F.); -#74902 = FACE_BOUND('',#74903,.T.); -#74903 = EDGE_LOOP('',(#74904,#74905,#74926,#74927)); -#74904 = ORIENTED_EDGE('',*,*,#74513,.F.); -#74905 = ORIENTED_EDGE('',*,*,#74906,.T.); -#74906 = EDGE_CURVE('',#74491,#73377,#74907,.T.); -#74907 = SURFACE_CURVE('',#74908,(#74912,#74919),.PCURVE_S1.); -#74908 = LINE('',#74909,#74910); -#74909 = CARTESIAN_POINT('',(0.6477,-0.512231420537,1.411981289785)); -#74910 = VECTOR('',#74911,1.); -#74911 = DIRECTION('',(0.E+000,-0.99756405026,-6.975647374412E-002)); -#74912 = PCURVE('',#73392,#74913); -#74913 = DEFINITIONAL_REPRESENTATION('',(#74914),#74918); -#74914 = LINE('',#74915,#74916); -#74915 = CARTESIAN_POINT('',(-3.581871021541E-002,2.504688213292E-003)); -#74916 = VECTOR('',#74917,1.); -#74917 = DIRECTION('',(-6.975647374412E-002,-0.99756405026)); -#74918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74919 = PCURVE('',#73019,#74920); -#74920 = DEFINITIONAL_REPRESENTATION('',(#74921),#74925); -#74921 = LINE('',#74922,#74923); -#74922 = CARTESIAN_POINT('',(-0.513482237459,1.4097)); -#74923 = VECTOR('',#74924,1.); -#74924 = DIRECTION('',(-1.,0.E+000)); -#74925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74926 = ORIENTED_EDGE('',*,*,#73374,.F.); -#74927 = ORIENTED_EDGE('',*,*,#74880,.T.); -#74928 = ADVANCED_FACE('',(#74929),#72157,.F.); -#74929 = FACE_BOUND('',#74930,.T.); -#74930 = EDGE_LOOP('',(#74931,#74952,#74953,#74954)); -#74931 = ORIENTED_EDGE('',*,*,#74932,.F.); -#74932 = EDGE_CURVE('',#74491,#72116,#74933,.T.); -#74933 = SURFACE_CURVE('',#74934,(#74938,#74945),.PCURVE_S1.); -#74934 = LINE('',#74935,#74936); -#74935 = CARTESIAN_POINT('',(0.8509,-5.421010862428E-017,1.4478)); -#74936 = VECTOR('',#74937,1.); -#74937 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#74938 = PCURVE('',#72157,#74939); -#74939 = DEFINITIONAL_REPRESENTATION('',(#74940),#74944); -#74940 = LINE('',#74941,#74942); -#74941 = CARTESIAN_POINT('',(-0.483778460014,1.6129)); -#74942 = VECTOR('',#74943,1.); -#74943 = DIRECTION('',(0.E+000,-1.)); -#74944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74945 = PCURVE('',#73019,#74946); -#74946 = DEFINITIONAL_REPRESENTATION('',(#74947),#74951); -#74947 = LINE('',#74948,#74949); -#74948 = CARTESIAN_POINT('',(-3.943977738883E-015,1.6129)); -#74949 = VECTOR('',#74950,1.); -#74950 = DIRECTION('',(0.E+000,-1.)); -#74951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74952 = ORIENTED_EDGE('',*,*,#74490,.F.); -#74953 = ORIENTED_EDGE('',*,*,#74583,.F.); -#74954 = ORIENTED_EDGE('',*,*,#72143,.F.); -#74955 = ADVANCED_FACE('',(#74956),#72047,.F.); -#74956 = FACE_BOUND('',#74957,.T.); -#74957 = EDGE_LOOP('',(#74958,#74959,#74960,#74981)); -#74958 = ORIENTED_EDGE('',*,*,#74561,.T.); -#74959 = ORIENTED_EDGE('',*,*,#74444,.F.); -#74960 = ORIENTED_EDGE('',*,*,#74961,.T.); -#74961 = EDGE_CURVE('',#74422,#72032,#74962,.T.); -#74962 = SURFACE_CURVE('',#74963,(#74967,#74974),.PCURVE_S1.); -#74963 = LINE('',#74964,#74965); -#74964 = CARTESIAN_POINT('',(0.8509,-4.065758146821E-015,-1.4478)); -#74965 = VECTOR('',#74966,1.); -#74966 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#74967 = PCURVE('',#72047,#74968); -#74968 = DEFINITIONAL_REPRESENTATION('',(#74969),#74973); -#74969 = LINE('',#74970,#74971); -#74970 = CARTESIAN_POINT('',(0.483778460014,1.6129)); -#74971 = VECTOR('',#74972,1.); -#74972 = DIRECTION('',(0.E+000,-1.)); -#74973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74974 = PCURVE('',#73136,#74975); -#74975 = DEFINITIONAL_REPRESENTATION('',(#74976),#74980); -#74976 = LINE('',#74977,#74978); -#74977 = CARTESIAN_POINT('',(8.387778748502E-015,1.6129)); -#74978 = VECTOR('',#74979,1.); -#74979 = DIRECTION('',(0.E+000,-1.)); -#74980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#74981 = ORIENTED_EDGE('',*,*,#72031,.F.); -#74982 = ADVANCED_FACE('',(#74983),#73136,.F.); -#74983 = FACE_BOUND('',#74984,.T.); -#74984 = EDGE_LOOP('',(#74985,#74986,#74987,#74988,#74989,#74990,#74991, - #74992)); -#74985 = ORIENTED_EDGE('',*,*,#73122,.F.); -#74986 = ORIENTED_EDGE('',*,*,#74643,.F.); -#74987 = ORIENTED_EDGE('',*,*,#74961,.F.); -#74988 = ORIENTED_EDGE('',*,*,#74844,.F.); -#74989 = ORIENTED_EDGE('',*,*,#73426,.F.); -#74990 = ORIENTED_EDGE('',*,*,#73350,.F.); -#74991 = ORIENTED_EDGE('',*,*,#73279,.F.); -#74992 = ORIENTED_EDGE('',*,*,#73203,.F.); -#74993 = ADVANCED_FACE('',(#74994),#73019,.F.); -#74994 = FACE_BOUND('',#74995,.T.); -#74995 = EDGE_LOOP('',(#74996,#74997,#74998,#74999,#75000,#75001,#75002, - #75003)); -#74996 = ORIENTED_EDGE('',*,*,#73257,.T.); -#74997 = ORIENTED_EDGE('',*,*,#73328,.F.); -#74998 = ORIENTED_EDGE('',*,*,#73404,.F.); -#74999 = ORIENTED_EDGE('',*,*,#74906,.F.); -#75000 = ORIENTED_EDGE('',*,*,#74932,.T.); -#75001 = ORIENTED_EDGE('',*,*,#74705,.F.); -#75002 = ORIENTED_EDGE('',*,*,#73003,.F.); -#75003 = ORIENTED_EDGE('',*,*,#73181,.F.); -#75004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75008)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75005,#75006,#75007)) +#76890 = PCURVE('',#74352,#76891); +#76891 = DEFINITIONAL_REPRESENTATION('',(#76892),#76896); +#76892 = LINE('',#76893,#76894); +#76893 = CARTESIAN_POINT('',(2.33557487168E-003,-3.358425481934E-002)); +#76894 = VECTOR('',#76895,1.); +#76895 = DIRECTION('',(0.997590569818,6.93761847516E-002)); +#76896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76897 = PCURVE('',#74549,#76898); +#76898 = DEFINITIONAL_REPRESENTATION('',(#76899),#76903); +#76899 = LINE('',#76900,#76901); +#76900 = CARTESIAN_POINT('',(-2.328452341033E-003,1.359220830113)); +#76901 = VECTOR('',#76902,1.); +#76902 = DIRECTION('',(-0.994548334053,0.104276609233)); +#76903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76904 = ORIENTED_EDGE('',*,*,#76905,.T.); +#76905 = EDGE_CURVE('',#76883,#76743,#76906,.T.); +#76906 = SURFACE_CURVE('',#76907,(#76911,#76918),.PCURVE_S1.); +#76907 = LINE('',#76908,#76909); +#76908 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76909 = VECTOR('',#76910,1.); +#76910 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76911 = PCURVE('',#74352,#76912); +#76912 = DEFINITIONAL_REPRESENTATION('',(#76913),#76917); +#76913 = LINE('',#76914,#76915); +#76914 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#76915 = VECTOR('',#76916,1.); +#76916 = DIRECTION('',(0.E+000,-1.)); +#76917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76918 = PCURVE('',#75784,#76919); +#76919 = DEFINITIONAL_REPRESENTATION('',(#76920),#76924); +#76920 = LINE('',#76921,#76922); +#76921 = CARTESIAN_POINT('',(0.E+000,0.51473610875)); +#76922 = VECTOR('',#76923,1.); +#76923 = DIRECTION('',(-1.,0.E+000)); +#76924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76925 = ORIENTED_EDGE('',*,*,#76742,.T.); +#76926 = ORIENTED_EDGE('',*,*,#76927,.T.); +#76927 = EDGE_CURVE('',#76745,#74337,#76928,.T.); +#76928 = SURFACE_CURVE('',#76929,(#76933,#76940),.PCURVE_S1.); +#76929 = LINE('',#76930,#76931); +#76930 = CARTESIAN_POINT('',(0.6477,0.E+000,1.4478)); +#76931 = VECTOR('',#76932,1.); +#76932 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#76933 = PCURVE('',#74352,#76934); +#76934 = DEFINITIONAL_REPRESENTATION('',(#76935),#76939); +#76935 = LINE('',#76936,#76937); +#76936 = CARTESIAN_POINT('',(0.485258295717,0.E+000)); +#76937 = VECTOR('',#76938,1.); +#76938 = DIRECTION('',(0.E+000,-1.)); +#76939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76940 = PCURVE('',#75930,#76941); +#76941 = DEFINITIONAL_REPRESENTATION('',(#76942),#76946); +#76942 = LINE('',#76943,#76944); +#76943 = CARTESIAN_POINT('',(2.1717,0.51473610875)); +#76944 = VECTOR('',#76945,1.); +#76945 = DIRECTION('',(-1.,0.E+000)); +#76946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76947 = ORIENTED_EDGE('',*,*,#74336,.T.); +#76948 = ADVANCED_FACE('',(#76949),#74411,.F.); +#76949 = FACE_BOUND('',#76950,.T.); +#76950 = EDGE_LOOP('',(#76951,#76952,#76973,#76974)); +#76951 = ORIENTED_EDGE('',*,*,#76859,.T.); +#76952 = ORIENTED_EDGE('',*,*,#76953,.F.); +#76953 = EDGE_CURVE('',#74391,#76837,#76954,.T.); +#76954 = SURFACE_CURVE('',#76955,(#76959,#76966),.PCURVE_S1.); +#76955 = LINE('',#76956,#76957); +#76956 = CARTESIAN_POINT('',(-0.762,0.4826,-1.414053320556)); +#76957 = VECTOR('',#76958,1.); +#76958 = DIRECTION('',(1.,0.E+000,0.E+000)); +#76959 = PCURVE('',#74411,#76960); +#76960 = DEFINITIONAL_REPRESENTATION('',(#76961),#76965); +#76961 = LINE('',#76962,#76963); +#76962 = CARTESIAN_POINT('',(2.861853320556,-0.165023303939)); +#76963 = VECTOR('',#76964,1.); +#76964 = DIRECTION('',(0.E+000,1.)); +#76965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76966 = PCURVE('',#74439,#76967); +#76967 = DEFINITIONAL_REPRESENTATION('',(#76968),#76972); +#76968 = LINE('',#76969,#76970); +#76969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76970 = VECTOR('',#76971,1.); +#76971 = DIRECTION('',(0.E+000,1.)); +#76972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76973 = ORIENTED_EDGE('',*,*,#74388,.F.); +#76974 = ORIENTED_EDGE('',*,*,#76975,.T.); +#76975 = EDGE_CURVE('',#74389,#76860,#76976,.T.); +#76976 = SURFACE_CURVE('',#76977,(#76981,#76988),.PCURVE_S1.); +#76977 = LINE('',#76978,#76979); +#76978 = CARTESIAN_POINT('',(-0.762,0.4826,1.414053320556)); +#76979 = VECTOR('',#76980,1.); +#76980 = DIRECTION('',(1.,0.E+000,0.E+000)); +#76981 = PCURVE('',#74411,#76982); +#76982 = DEFINITIONAL_REPRESENTATION('',(#76983),#76987); +#76983 = LINE('',#76984,#76985); +#76984 = CARTESIAN_POINT('',(3.374667944393E-002,-0.165023303939)); +#76985 = VECTOR('',#76986,1.); +#76986 = DIRECTION('',(0.E+000,1.)); +#76987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76988 = PCURVE('',#74549,#76989); +#76989 = DEFINITIONAL_REPRESENTATION('',(#76990),#76994); +#76990 = LINE('',#76991,#76992); +#76991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#76992 = VECTOR('',#76993,1.); +#76993 = DIRECTION('',(0.E+000,1.)); +#76994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#76995 = ADVANCED_FACE('',(#76996),#74634,.F.); +#76996 = FACE_BOUND('',#76997,.T.); +#76997 = EDGE_LOOP('',(#76998,#77019,#77020,#77021,#77022,#77023,#77024, + #77025,#77026,#77027,#77028,#77029)); +#76998 = ORIENTED_EDGE('',*,*,#76999,.F.); +#76999 = EDGE_CURVE('',#75469,#74452,#77000,.T.); +#77000 = SURFACE_CURVE('',#77001,(#77005,#77012),.PCURVE_S1.); +#77001 = LINE('',#77002,#77003); +#77002 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,-0.2286)); +#77003 = VECTOR('',#77004,1.); +#77004 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77005 = PCURVE('',#74634,#77006); +#77006 = DEFINITIONAL_REPRESENTATION('',(#77007),#77011); +#77007 = LINE('',#77008,#77009); +#77008 = CARTESIAN_POINT('',(0.562263454686,0.E+000)); +#77009 = VECTOR('',#77010,1.); +#77010 = DIRECTION('',(0.E+000,1.)); +#77011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77012 = PCURVE('',#74467,#77013); +#77013 = DEFINITIONAL_REPRESENTATION('',(#77014),#77018); +#77014 = LINE('',#77015,#77016); +#77015 = CARTESIAN_POINT('',(-1.2192,0.E+000)); +#77016 = VECTOR('',#77017,1.); +#77017 = DIRECTION('',(0.E+000,1.)); +#77018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77019 = ORIENTED_EDGE('',*,*,#75468,.F.); +#77020 = ORIENTED_EDGE('',*,*,#75311,.F.); +#77021 = ORIENTED_EDGE('',*,*,#75258,.F.); +#77022 = ORIENTED_EDGE('',*,*,#75160,.F.); +#77023 = ORIENTED_EDGE('',*,*,#75085,.F.); +#77024 = ORIENTED_EDGE('',*,*,#75010,.T.); +#77025 = ORIENTED_EDGE('',*,*,#74934,.F.); +#77026 = ORIENTED_EDGE('',*,*,#74828,.F.); +#77027 = ORIENTED_EDGE('',*,*,#74775,.F.); +#77028 = ORIENTED_EDGE('',*,*,#74700,.F.); +#77029 = ORIENTED_EDGE('',*,*,#74620,.F.); +#77030 = ADVANCED_FACE('',(#77031),#74467,.F.); +#77031 = FACE_BOUND('',#77032,.T.); +#77032 = EDGE_LOOP('',(#77033,#77034,#77055,#77056)); +#77033 = ORIENTED_EDGE('',*,*,#74451,.F.); +#77034 = ORIENTED_EDGE('',*,*,#77035,.T.); +#77035 = EDGE_CURVE('',#74424,#75492,#77036,.T.); +#77036 = SURFACE_CURVE('',#77037,(#77041,#77048),.PCURVE_S1.); +#77037 = LINE('',#77038,#77039); +#77038 = CARTESIAN_POINT('',(-0.6477,-0.512231420537,-1.411981289785)); +#77039 = VECTOR('',#77040,1.); +#77040 = DIRECTION('',(0.E+000,-0.99756405026,6.975647374412E-002)); +#77041 = PCURVE('',#74467,#77042); +#77042 = DEFINITIONAL_REPRESENTATION('',(#77043),#77047); +#77043 = LINE('',#77044,#77045); +#77044 = CARTESIAN_POINT('',(-3.581871021541E-002,2.504688213292E-003)); +#77045 = VECTOR('',#77046,1.); +#77046 = DIRECTION('',(-6.975647374412E-002,-0.99756405026)); +#77047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77048 = PCURVE('',#75528,#77049); +#77049 = DEFINITIONAL_REPRESENTATION('',(#77050),#77054); +#77050 = LINE('',#77051,#77052); +#77051 = CARTESIAN_POINT('',(0.513482237459,0.1143)); +#77052 = VECTOR('',#77053,1.); +#77053 = DIRECTION('',(1.,0.E+000)); +#77054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77055 = ORIENTED_EDGE('',*,*,#75491,.F.); +#77056 = ORIENTED_EDGE('',*,*,#76999,.T.); +#77057 = ADVANCED_FACE('',(#77058),#74607,.F.); +#77058 = FACE_BOUND('',#77059,.T.); +#77059 = EDGE_LOOP('',(#77060,#77061,#77062,#77063,#77064,#77065,#77066, + #77067,#77068,#77069,#77070,#77091)); +#77060 = ORIENTED_EDGE('',*,*,#74678,.F.); +#77061 = ORIENTED_EDGE('',*,*,#74753,.F.); +#77062 = ORIENTED_EDGE('',*,*,#74854,.F.); +#77063 = ORIENTED_EDGE('',*,*,#74912,.F.); +#77064 = ORIENTED_EDGE('',*,*,#74988,.F.); +#77065 = ORIENTED_EDGE('',*,*,#75063,.F.); +#77066 = ORIENTED_EDGE('',*,*,#75138,.F.); +#77067 = ORIENTED_EDGE('',*,*,#75236,.F.); +#77068 = ORIENTED_EDGE('',*,*,#75337,.F.); +#77069 = ORIENTED_EDGE('',*,*,#75446,.F.); +#77070 = ORIENTED_EDGE('',*,*,#77071,.T.); +#77071 = EDGE_CURVE('',#75424,#74480,#77072,.T.); +#77072 = SURFACE_CURVE('',#77073,(#77077,#77084),.PCURVE_S1.); +#77073 = LINE('',#77074,#77075); +#77074 = CARTESIAN_POINT('',(-0.6477,-0.51473610875,0.2286)); +#77075 = VECTOR('',#77076,1.); +#77076 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77077 = PCURVE('',#74607,#77078); +#77078 = DEFINITIONAL_REPRESENTATION('',(#77079),#77083); +#77079 = LINE('',#77080,#77081); +#77080 = CARTESIAN_POINT('',(-0.562263454686,0.E+000)); +#77081 = VECTOR('',#77082,1.); +#77082 = DIRECTION('',(0.E+000,1.)); +#77083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77084 = PCURVE('',#74523,#77085); +#77085 = DEFINITIONAL_REPRESENTATION('',(#77086),#77090); +#77086 = LINE('',#77087,#77088); +#77087 = CARTESIAN_POINT('',(1.2192,0.E+000)); +#77088 = VECTOR('',#77089,1.); +#77089 = DIRECTION('',(0.E+000,1.)); +#77090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77091 = ORIENTED_EDGE('',*,*,#74593,.F.); +#77092 = ADVANCED_FACE('',(#77093),#74523,.F.); +#77093 = FACE_BOUND('',#77094,.T.); +#77094 = EDGE_LOOP('',(#77095,#77096,#77117,#77118)); +#77095 = ORIENTED_EDGE('',*,*,#75423,.F.); +#77096 = ORIENTED_EDGE('',*,*,#77097,.T.); +#77097 = EDGE_CURVE('',#75396,#74508,#77098,.T.); +#77098 = SURFACE_CURVE('',#77099,(#77103,#77110),.PCURVE_S1.); +#77099 = LINE('',#77100,#77101); +#77100 = CARTESIAN_POINT('',(-0.6477,-0.512231420537,1.411981289785)); +#77101 = VECTOR('',#77102,1.); +#77102 = DIRECTION('',(0.E+000,0.99756405026,6.975647374412E-002)); +#77103 = PCURVE('',#74523,#77104); +#77104 = DEFINITIONAL_REPRESENTATION('',(#77105),#77109); +#77105 = LINE('',#77106,#77107); +#77106 = CARTESIAN_POINT('',(3.581871021541E-002,2.504688213292E-003)); +#77107 = VECTOR('',#77108,1.); +#77108 = DIRECTION('',(-6.975647374412E-002,0.99756405026)); +#77109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77110 = PCURVE('',#75411,#77111); +#77111 = DEFINITIONAL_REPRESENTATION('',(#77112),#77116); +#77112 = LINE('',#77113,#77114); +#77113 = CARTESIAN_POINT('',(-0.513482237459,0.1143)); +#77114 = VECTOR('',#77115,1.); +#77115 = DIRECTION('',(1.,0.E+000)); +#77116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77117 = ORIENTED_EDGE('',*,*,#74507,.T.); +#77118 = ORIENTED_EDGE('',*,*,#77071,.F.); +#77119 = ADVANCED_FACE('',(#77120),#73603,.F.); +#77120 = FACE_BOUND('',#77121,.T.); +#77121 = EDGE_LOOP('',(#77122,#77123,#77124,#77125,#77126,#77127,#77128, + #77129,#77130,#77131,#77132,#77153)); +#77122 = ORIENTED_EDGE('',*,*,#73587,.F.); +#77123 = ORIENTED_EDGE('',*,*,#73753,.F.); +#77124 = ORIENTED_EDGE('',*,*,#73828,.F.); +#77125 = ORIENTED_EDGE('',*,*,#73904,.F.); +#77126 = ORIENTED_EDGE('',*,*,#73980,.T.); +#77127 = ORIENTED_EDGE('',*,*,#74055,.F.); +#77128 = ORIENTED_EDGE('',*,*,#74080,.F.); +#77129 = ORIENTED_EDGE('',*,*,#74213,.F.); +#77130 = ORIENTED_EDGE('',*,*,#74288,.F.); +#77131 = ORIENTED_EDGE('',*,*,#74364,.F.); +#77132 = ORIENTED_EDGE('',*,*,#77133,.F.); +#77133 = EDGE_CURVE('',#75892,#74337,#77134,.T.); +#77134 = SURFACE_CURVE('',#77135,(#77139,#77146),.PCURVE_S1.); +#77135 = LINE('',#77136,#77137); +#77136 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-0.7239)); +#77137 = VECTOR('',#77138,1.); +#77138 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77139 = PCURVE('',#73603,#77140); +#77140 = DEFINITIONAL_REPRESENTATION('',(#77141),#77145); +#77141 = LINE('',#77142,#77143); +#77142 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#77143 = VECTOR('',#77144,1.); +#77144 = DIRECTION('',(0.E+000,1.)); +#77145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77146 = PCURVE('',#75930,#77147); +#77147 = DEFINITIONAL_REPRESENTATION('',(#77148),#77152); +#77148 = LINE('',#77149,#77150); +#77149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#77150 = VECTOR('',#77151,1.); +#77151 = DIRECTION('',(0.E+000,1.)); +#77152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77153 = ORIENTED_EDGE('',*,*,#75891,.F.); +#77154 = ADVANCED_FACE('',(#77155),#75958,.F.); +#77155 = FACE_BOUND('',#77156,.T.); +#77156 = EDGE_LOOP('',(#77157,#77178,#77179,#77180,#77181,#77182,#77183, + #77184,#77185,#77186,#77187,#77188)); +#77157 = ORIENTED_EDGE('',*,*,#77158,.T.); +#77158 = EDGE_CURVE('',#75915,#76745,#77159,.T.); +#77159 = SURFACE_CURVE('',#77160,(#77164,#77171),.PCURVE_S1.); +#77160 = LINE('',#77161,#77162); +#77161 = CARTESIAN_POINT('',(0.6477,-0.51473610875,0.7239)); +#77162 = VECTOR('',#77163,1.); +#77163 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77164 = PCURVE('',#75958,#77165); +#77165 = DEFINITIONAL_REPRESENTATION('',(#77166),#77170); +#77166 = LINE('',#77167,#77168); +#77167 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#77168 = VECTOR('',#77169,1.); +#77169 = DIRECTION('',(0.E+000,1.)); +#77170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77171 = PCURVE('',#75930,#77172); +#77172 = DEFINITIONAL_REPRESENTATION('',(#77173),#77177); +#77173 = LINE('',#77174,#77175); +#77174 = CARTESIAN_POINT('',(1.4478,0.E+000)); +#77175 = VECTOR('',#77176,1.); +#77176 = DIRECTION('',(0.E+000,1.)); +#77177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77178 = ORIENTED_EDGE('',*,*,#76789,.F.); +#77179 = ORIENTED_EDGE('',*,*,#76718,.F.); +#77180 = ORIENTED_EDGE('',*,*,#76643,.F.); +#77181 = ORIENTED_EDGE('',*,*,#76538,.F.); +#77182 = ORIENTED_EDGE('',*,*,#76485,.F.); +#77183 = ORIENTED_EDGE('',*,*,#76410,.F.); +#77184 = ORIENTED_EDGE('',*,*,#76334,.F.); +#77185 = ORIENTED_EDGE('',*,*,#76258,.F.); +#77186 = ORIENTED_EDGE('',*,*,#76183,.F.); +#77187 = ORIENTED_EDGE('',*,*,#76055,.F.); +#77188 = ORIENTED_EDGE('',*,*,#75942,.F.); +#77189 = ADVANCED_FACE('',(#77190),#75930,.F.); +#77190 = FACE_BOUND('',#77191,.T.); +#77191 = EDGE_LOOP('',(#77192,#77193,#77194,#77195)); +#77192 = ORIENTED_EDGE('',*,*,#77133,.T.); +#77193 = ORIENTED_EDGE('',*,*,#76927,.F.); +#77194 = ORIENTED_EDGE('',*,*,#77158,.F.); +#77195 = ORIENTED_EDGE('',*,*,#75914,.F.); +#77196 = ADVANCED_FACE('',(#77197),#73660,.F.); +#77197 = FACE_BOUND('',#77198,.T.); +#77198 = EDGE_LOOP('',(#77199,#77200,#77201,#77202,#77203,#77204,#77205, + #77226,#77227,#77228,#77229,#77230)); +#77199 = ORIENTED_EDGE('',*,*,#73929,.F.); +#77200 = ORIENTED_EDGE('',*,*,#73853,.F.); +#77201 = ORIENTED_EDGE('',*,*,#73778,.F.); +#77202 = ORIENTED_EDGE('',*,*,#73680,.F.); +#77203 = ORIENTED_EDGE('',*,*,#73646,.F.); +#77204 = ORIENTED_EDGE('',*,*,#75869,.F.); +#77205 = ORIENTED_EDGE('',*,*,#77206,.T.); +#77206 = EDGE_CURVE('',#75842,#74314,#77207,.T.); +#77207 = SURFACE_CURVE('',#77208,(#77212,#77219),.PCURVE_S1.); +#77208 = LINE('',#77209,#77210); +#77209 = CARTESIAN_POINT('',(0.6477,-0.51473610875,-1.1811)); +#77210 = VECTOR('',#77211,1.); +#77211 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77212 = PCURVE('',#73660,#77213); +#77213 = DEFINITIONAL_REPRESENTATION('',(#77214),#77218); +#77214 = LINE('',#77215,#77216); +#77215 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#77216 = VECTOR('',#77217,1.); +#77217 = DIRECTION('',(0.E+000,1.)); +#77218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77219 = PCURVE('',#75857,#77220); +#77220 = DEFINITIONAL_REPRESENTATION('',(#77221),#77225); +#77221 = LINE('',#77222,#77223); +#77222 = CARTESIAN_POINT('',(0.2667,0.E+000)); +#77223 = VECTOR('',#77224,1.); +#77224 = DIRECTION('',(0.E+000,1.)); +#77225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77226 = ORIENTED_EDGE('',*,*,#74313,.F.); +#77227 = ORIENTED_EDGE('',*,*,#74238,.F.); +#77228 = ORIENTED_EDGE('',*,*,#74163,.F.); +#77229 = ORIENTED_EDGE('',*,*,#74134,.F.); +#77230 = ORIENTED_EDGE('',*,*,#74005,.F.); +#77231 = ADVANCED_FACE('',(#77232),#75857,.F.); +#77232 = FACE_BOUND('',#77233,.T.); +#77233 = EDGE_LOOP('',(#77234,#77235,#77256,#77257)); +#77234 = ORIENTED_EDGE('',*,*,#75841,.F.); +#77235 = ORIENTED_EDGE('',*,*,#77236,.T.); +#77236 = EDGE_CURVE('',#75819,#76814,#77237,.T.); +#77237 = SURFACE_CURVE('',#77238,(#77242,#77249),.PCURVE_S1.); +#77238 = LINE('',#77239,#77240); +#77239 = CARTESIAN_POINT('',(0.6477,-0.512231420537,-1.411981289785)); +#77240 = VECTOR('',#77241,1.); +#77241 = DIRECTION('',(0.E+000,0.99756405026,-6.975647374412E-002)); +#77242 = PCURVE('',#75857,#77243); +#77243 = DEFINITIONAL_REPRESENTATION('',(#77244),#77248); +#77244 = LINE('',#77245,#77246); +#77245 = CARTESIAN_POINT('',(3.581871021541E-002,2.504688213292E-003)); +#77246 = VECTOR('',#77247,1.); +#77247 = DIRECTION('',(-6.975647374412E-002,0.99756405026)); +#77248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77249 = PCURVE('',#75528,#77250); +#77250 = DEFINITIONAL_REPRESENTATION('',(#77251),#77255); +#77251 = LINE('',#77252,#77253); +#77252 = CARTESIAN_POINT('',(0.513482237459,1.4097)); +#77253 = VECTOR('',#77254,1.); +#77254 = DIRECTION('',(-1.,0.E+000)); +#77255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77256 = ORIENTED_EDGE('',*,*,#76813,.F.); +#77257 = ORIENTED_EDGE('',*,*,#77206,.F.); +#77258 = ADVANCED_FACE('',(#77259),#76011,.F.); +#77259 = FACE_BOUND('',#77260,.T.); +#77260 = EDGE_LOOP('',(#77261,#77262,#77263,#77264,#77265,#77266,#77267, + #77268,#77269,#77270,#77271,#77292)); +#77261 = ORIENTED_EDGE('',*,*,#76081,.F.); +#77262 = ORIENTED_EDGE('',*,*,#76161,.F.); +#77263 = ORIENTED_EDGE('',*,*,#76236,.F.); +#77264 = ORIENTED_EDGE('',*,*,#76312,.F.); +#77265 = ORIENTED_EDGE('',*,*,#76388,.T.); +#77266 = ORIENTED_EDGE('',*,*,#76463,.F.); +#77267 = ORIENTED_EDGE('',*,*,#76564,.F.); +#77268 = ORIENTED_EDGE('',*,*,#76621,.F.); +#77269 = ORIENTED_EDGE('',*,*,#76696,.F.); +#77270 = ORIENTED_EDGE('',*,*,#76767,.F.); +#77271 = ORIENTED_EDGE('',*,*,#77272,.F.); +#77272 = EDGE_CURVE('',#75767,#76743,#77273,.T.); +#77273 = SURFACE_CURVE('',#77274,(#77278,#77285),.PCURVE_S1.); +#77274 = LINE('',#77275,#77276); +#77275 = CARTESIAN_POINT('',(0.6477,-0.51473610875,1.1811)); +#77276 = VECTOR('',#77277,1.); +#77277 = DIRECTION('',(0.E+000,1.,0.E+000)); +#77278 = PCURVE('',#76011,#77279); +#77279 = DEFINITIONAL_REPRESENTATION('',(#77280),#77284); +#77280 = LINE('',#77281,#77282); +#77281 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#77282 = VECTOR('',#77283,1.); +#77283 = DIRECTION('',(0.E+000,1.)); +#77284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77285 = PCURVE('',#75784,#77286); +#77286 = DEFINITIONAL_REPRESENTATION('',(#77287),#77291); +#77287 = LINE('',#77288,#77289); +#77288 = CARTESIAN_POINT('',(-0.2667,0.E+000)); +#77289 = VECTOR('',#77290,1.); +#77290 = DIRECTION('',(0.E+000,1.)); +#77291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77292 = ORIENTED_EDGE('',*,*,#75997,.F.); +#77293 = ADVANCED_FACE('',(#77294),#75784,.F.); +#77294 = FACE_BOUND('',#77295,.T.); +#77295 = EDGE_LOOP('',(#77296,#77297,#77318,#77319)); +#77296 = ORIENTED_EDGE('',*,*,#76905,.F.); +#77297 = ORIENTED_EDGE('',*,*,#77298,.T.); +#77298 = EDGE_CURVE('',#76883,#75769,#77299,.T.); +#77299 = SURFACE_CURVE('',#77300,(#77304,#77311),.PCURVE_S1.); +#77300 = LINE('',#77301,#77302); +#77301 = CARTESIAN_POINT('',(0.6477,-0.512231420537,1.411981289785)); +#77302 = VECTOR('',#77303,1.); +#77303 = DIRECTION('',(0.E+000,-0.99756405026,-6.975647374412E-002)); +#77304 = PCURVE('',#75784,#77305); +#77305 = DEFINITIONAL_REPRESENTATION('',(#77306),#77310); +#77306 = LINE('',#77307,#77308); +#77307 = CARTESIAN_POINT('',(-3.581871021541E-002,2.504688213292E-003)); +#77308 = VECTOR('',#77309,1.); +#77309 = DIRECTION('',(-6.975647374412E-002,-0.99756405026)); +#77310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77311 = PCURVE('',#75411,#77312); +#77312 = DEFINITIONAL_REPRESENTATION('',(#77313),#77317); +#77313 = LINE('',#77314,#77315); +#77314 = CARTESIAN_POINT('',(-0.513482237459,1.4097)); +#77315 = VECTOR('',#77316,1.); +#77316 = DIRECTION('',(-1.,0.E+000)); +#77317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77318 = ORIENTED_EDGE('',*,*,#75766,.F.); +#77319 = ORIENTED_EDGE('',*,*,#77272,.T.); +#77320 = ADVANCED_FACE('',(#77321),#74549,.F.); +#77321 = FACE_BOUND('',#77322,.T.); +#77322 = EDGE_LOOP('',(#77323,#77344,#77345,#77346)); +#77323 = ORIENTED_EDGE('',*,*,#77324,.F.); +#77324 = EDGE_CURVE('',#76883,#74508,#77325,.T.); +#77325 = SURFACE_CURVE('',#77326,(#77330,#77337),.PCURVE_S1.); +#77326 = LINE('',#77327,#77328); +#77327 = CARTESIAN_POINT('',(0.8509,-5.421010862428E-017,1.4478)); +#77328 = VECTOR('',#77329,1.); +#77329 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#77330 = PCURVE('',#74549,#77331); +#77331 = DEFINITIONAL_REPRESENTATION('',(#77332),#77336); +#77332 = LINE('',#77333,#77334); +#77333 = CARTESIAN_POINT('',(-0.483778460014,1.6129)); +#77334 = VECTOR('',#77335,1.); +#77335 = DIRECTION('',(0.E+000,-1.)); +#77336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77337 = PCURVE('',#75411,#77338); +#77338 = DEFINITIONAL_REPRESENTATION('',(#77339),#77343); +#77339 = LINE('',#77340,#77341); +#77340 = CARTESIAN_POINT('',(-3.943977738883E-015,1.6129)); +#77341 = VECTOR('',#77342,1.); +#77342 = DIRECTION('',(0.E+000,-1.)); +#77343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77344 = ORIENTED_EDGE('',*,*,#76882,.F.); +#77345 = ORIENTED_EDGE('',*,*,#76975,.F.); +#77346 = ORIENTED_EDGE('',*,*,#74535,.F.); +#77347 = ADVANCED_FACE('',(#77348),#74439,.F.); +#77348 = FACE_BOUND('',#77349,.T.); +#77349 = EDGE_LOOP('',(#77350,#77351,#77352,#77373)); +#77350 = ORIENTED_EDGE('',*,*,#76953,.T.); +#77351 = ORIENTED_EDGE('',*,*,#76836,.F.); +#77352 = ORIENTED_EDGE('',*,*,#77353,.T.); +#77353 = EDGE_CURVE('',#76814,#74424,#77354,.T.); +#77354 = SURFACE_CURVE('',#77355,(#77359,#77366),.PCURVE_S1.); +#77355 = LINE('',#77356,#77357); +#77356 = CARTESIAN_POINT('',(0.8509,-4.065758146821E-015,-1.4478)); +#77357 = VECTOR('',#77358,1.); +#77358 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#77359 = PCURVE('',#74439,#77360); +#77360 = DEFINITIONAL_REPRESENTATION('',(#77361),#77365); +#77361 = LINE('',#77362,#77363); +#77362 = CARTESIAN_POINT('',(0.483778460014,1.6129)); +#77363 = VECTOR('',#77364,1.); +#77364 = DIRECTION('',(0.E+000,-1.)); +#77365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77366 = PCURVE('',#75528,#77367); +#77367 = DEFINITIONAL_REPRESENTATION('',(#77368),#77372); +#77368 = LINE('',#77369,#77370); +#77369 = CARTESIAN_POINT('',(8.387778748502E-015,1.6129)); +#77370 = VECTOR('',#77371,1.); +#77371 = DIRECTION('',(0.E+000,-1.)); +#77372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77373 = ORIENTED_EDGE('',*,*,#74423,.F.); +#77374 = ADVANCED_FACE('',(#77375),#75528,.F.); +#77375 = FACE_BOUND('',#77376,.T.); +#77376 = EDGE_LOOP('',(#77377,#77378,#77379,#77380,#77381,#77382,#77383, + #77384)); +#77377 = ORIENTED_EDGE('',*,*,#75514,.F.); +#77378 = ORIENTED_EDGE('',*,*,#77035,.F.); +#77379 = ORIENTED_EDGE('',*,*,#77353,.F.); +#77380 = ORIENTED_EDGE('',*,*,#77236,.F.); +#77381 = ORIENTED_EDGE('',*,*,#75818,.F.); +#77382 = ORIENTED_EDGE('',*,*,#75742,.F.); +#77383 = ORIENTED_EDGE('',*,*,#75671,.F.); +#77384 = ORIENTED_EDGE('',*,*,#75595,.F.); +#77385 = ADVANCED_FACE('',(#77386),#75411,.F.); +#77386 = FACE_BOUND('',#77387,.T.); +#77387 = EDGE_LOOP('',(#77388,#77389,#77390,#77391,#77392,#77393,#77394, + #77395)); +#77388 = ORIENTED_EDGE('',*,*,#75649,.T.); +#77389 = ORIENTED_EDGE('',*,*,#75720,.F.); +#77390 = ORIENTED_EDGE('',*,*,#75796,.F.); +#77391 = ORIENTED_EDGE('',*,*,#77298,.F.); +#77392 = ORIENTED_EDGE('',*,*,#77324,.T.); +#77393 = ORIENTED_EDGE('',*,*,#77097,.F.); +#77394 = ORIENTED_EDGE('',*,*,#75395,.F.); +#77395 = ORIENTED_EDGE('',*,*,#75573,.F.); +#77396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77400)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77397,#77398,#77399)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75005 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75006 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75007 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75008 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75005, +#77397 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77398 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77399 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77400 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77397, 'distance_accuracy_value','confusion accuracy'); -#75009 = SHAPE_DEFINITION_REPRESENTATION(#75010,#71154); -#75010 = PRODUCT_DEFINITION_SHAPE('','',#75011); -#75011 = PRODUCT_DEFINITION('design','',#75012,#75015); -#75012 = PRODUCT_DEFINITION_FORMATION('','',#75013); -#75013 = PRODUCT('SOT-23','SOT-23','',(#75014)); -#75014 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75015 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75016 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75017,#75019); -#75017 = ( REPRESENTATION_RELATIONSHIP('','',#71154,#71144) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75018) +#77401 = SHAPE_DEFINITION_REPRESENTATION(#77402,#73546); +#77402 = PRODUCT_DEFINITION_SHAPE('','',#77403); +#77403 = PRODUCT_DEFINITION('design','',#77404,#77407); +#77404 = PRODUCT_DEFINITION_FORMATION('','',#77405); +#77405 = PRODUCT('SOT-23','SOT-23','',(#77406)); +#77406 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77407 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77408 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77409,#77411); +#77409 = ( REPRESENTATION_RELATIONSHIP('','',#73546,#73536) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77410) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75018 = ITEM_DEFINED_TRANSFORMATION('','',#11,#71145); -#75019 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75020); -#75020 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('218','=>[0:1:1:59]','',#71139, - #75011,$); -#75021 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75013)); -#75022 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75023,#75025); -#75023 = ( REPRESENTATION_RELATIONSHIP('','',#71144,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75024) +#77410 = ITEM_DEFINED_TRANSFORMATION('','',#11,#73537); +#77411 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77412); +#77412 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('319','=>[0:1:1:59]','',#73531, + #77403,$); +#77413 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77405)); +#77414 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77415,#77417); +#77415 = ( REPRESENTATION_RELATIONSHIP('','',#73536,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77416) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75024 = ITEM_DEFINED_TRANSFORMATION('','',#11,#163); -#75025 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75026); -#75026 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('219','=>[0:1:1:58]','',#5, - #71139,$); -#75027 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#71141)); -#75028 = SHAPE_DEFINITION_REPRESENTATION(#75029,#75035); -#75029 = PRODUCT_DEFINITION_SHAPE('','',#75030); -#75030 = PRODUCT_DEFINITION('design','',#75031,#75034); -#75031 = PRODUCT_DEFINITION_FORMATION('','',#75032); -#75032 = PRODUCT('D2','D2','',(#75033)); -#75033 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75034 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75035 = SHAPE_REPRESENTATION('',(#11,#75036),#75040); -#75036 = AXIS2_PLACEMENT_3D('',#75037,#75038,#75039); -#75037 = CARTESIAN_POINT('',(15.9888428,4.04644098,1.27E-002)); -#75038 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75039 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#75040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75044)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75041,#75042,#75043)) +#77416 = ITEM_DEFINED_TRANSFORMATION('','',#11,#163); +#77417 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77418); +#77418 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('320','=>[0:1:1:58]','',#5, + #73531,$); +#77419 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#73533)); +#77420 = SHAPE_DEFINITION_REPRESENTATION(#77421,#77427); +#77421 = PRODUCT_DEFINITION_SHAPE('','',#77422); +#77422 = PRODUCT_DEFINITION('design','',#77423,#77426); +#77423 = PRODUCT_DEFINITION_FORMATION('','',#77424); +#77424 = PRODUCT('D2','D2','',(#77425)); +#77425 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77426 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77427 = SHAPE_REPRESENTATION('',(#11,#77428),#77432); +#77428 = AXIS2_PLACEMENT_3D('',#77429,#77430,#77431); +#77429 = CARTESIAN_POINT('',(15.9888428,4.04644098,1.27E-002)); +#77430 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77431 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#77432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77436)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77433,#77434,#77435)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75041 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75042 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75043 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75044 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75041, +#77433 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77434 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77435 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77436 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77433, 'distance_accuracy_value','confusion accuracy'); -#75045 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75046,#75048); -#75046 = ( REPRESENTATION_RELATIONSHIP('','',#7524,#75035) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75047) +#77437 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77438,#77440); +#77438 = ( REPRESENTATION_RELATIONSHIP('','',#9916,#77427) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77439) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75047 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75036); -#75048 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75049); -#75049 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('220','=>[0:1:1:10]','',#75030, - #11023,$); -#75050 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75051,#75053); -#75051 = ( REPRESENTATION_RELATIONSHIP('','',#75035,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75052) +#77439 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77428); +#77440 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77441); +#77441 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('321','=>[0:1:1:10]','',#77422, + #13415,$); +#77442 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77443,#77445); +#77443 = ( REPRESENTATION_RELATIONSHIP('','',#77427,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77444) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75052 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167); -#75053 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75054); -#75054 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('221','=>[0:1:1:60]','',#5, - #75030,$); -#75055 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75032)); -#75056 = SHAPE_DEFINITION_REPRESENTATION(#75057,#75063); -#75057 = PRODUCT_DEFINITION_SHAPE('','',#75058); -#75058 = PRODUCT_DEFINITION('design','',#75059,#75062); -#75059 = PRODUCT_DEFINITION_FORMATION('','',#75060); -#75060 = PRODUCT('JP1','JP1','',(#75061)); -#75061 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75062 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75063 = SHAPE_REPRESENTATION('',(#11,#75064,#75068,#75072,#75076), - #75080); -#75064 = AXIS2_PLACEMENT_3D('',#75065,#75066,#75067); -#75065 = CARTESIAN_POINT('',(31.55002072,27.6538182,-2.48730008)); -#75066 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75067 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75068 = AXIS2_PLACEMENT_3D('',#75069,#75070,#75071); -#75069 = CARTESIAN_POINT('',(31.55002072,27.6538182,1.27E-002)); -#75070 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75071 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75072 = AXIS2_PLACEMENT_3D('',#75073,#75074,#75075); -#75073 = CARTESIAN_POINT('',(29.00002074,27.6538182,-2.48730008)); -#75074 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75075 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75076 = AXIS2_PLACEMENT_3D('',#75077,#75078,#75079); -#75077 = CARTESIAN_POINT('',(34.1000207,27.6538182,-2.48730008)); -#75078 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75079 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75084)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75081,#75082,#75083)) +#77444 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167); +#77445 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77446); +#77446 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('322','=>[0:1:1:60]','',#5, + #77422,$); +#77447 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77424)); +#77448 = SHAPE_DEFINITION_REPRESENTATION(#77449,#77455); +#77449 = PRODUCT_DEFINITION_SHAPE('','',#77450); +#77450 = PRODUCT_DEFINITION('design','',#77451,#77454); +#77451 = PRODUCT_DEFINITION_FORMATION('','',#77452); +#77452 = PRODUCT('JP1','JP1','',(#77453)); +#77453 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77454 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77455 = SHAPE_REPRESENTATION('',(#11,#77456,#77460,#77464,#77468), + #77472); +#77456 = AXIS2_PLACEMENT_3D('',#77457,#77458,#77459); +#77457 = CARTESIAN_POINT('',(31.55002072,27.6538182,-2.48730008)); +#77458 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77459 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77460 = AXIS2_PLACEMENT_3D('',#77461,#77462,#77463); +#77461 = CARTESIAN_POINT('',(31.55002072,27.6538182,1.27E-002)); +#77462 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77463 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77464 = AXIS2_PLACEMENT_3D('',#77465,#77466,#77467); +#77465 = CARTESIAN_POINT('',(29.00002074,27.6538182,-2.48730008)); +#77466 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77467 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77468 = AXIS2_PLACEMENT_3D('',#77469,#77470,#77471); +#77469 = CARTESIAN_POINT('',(34.1000207,27.6538182,-2.48730008)); +#77470 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77471 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77476)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77473,#77474,#77475)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75081 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75082 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75083 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75084 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75081, +#77473 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77474 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77475 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77476 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77473, 'distance_accuracy_value','confusion accuracy'); -#75085 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75086,#75088); -#75086 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75063) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75087) +#77477 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77478,#77480); +#77478 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77455) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77479) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75087 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75064); -#75088 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75089); -#75089 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('222','=>[0:1:1:13]','',#75058, - #11099,$); -#75090 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75091,#75093); -#75091 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75063) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75092) +#77479 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77456); +#77480 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77481); +#77481 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('323','=>[0:1:1:13]','',#77450, + #13491,$); +#77482 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77483,#77485); +#77483 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77455) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77484) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75092 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75068); -#75093 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75094); -#75094 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('223','=>[0:1:1:15]','',#75058, - #11476,$); -#75095 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75096,#75098); -#75096 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75063) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75097) +#77484 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77460); +#77485 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77486); +#77486 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('324','=>[0:1:1:15]','',#77450, + #13868,$); +#77487 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77488,#77490); +#77488 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77455) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77489) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75097 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75072); -#75098 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75099); -#75099 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('224','=>[0:1:1:13]','',#75058, - #11099,$); -#75100 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75101,#75103); -#75101 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75063) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75102) +#77489 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77464); +#77490 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77491); +#77491 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('325','=>[0:1:1:13]','',#77450, + #13491,$); +#77492 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77493,#77495); +#77493 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77455) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77494) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75102 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75076); -#75103 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75104); -#75104 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('225','=>[0:1:1:13]','',#75058, - #11099,$); -#75105 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75106,#75108); -#75106 = ( REPRESENTATION_RELATIONSHIP('','',#75063,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75107) +#77494 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77468); +#77495 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77496); +#77496 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('326','=>[0:1:1:13]','',#77450, + #13491,$); +#77497 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77498,#77500); +#77498 = ( REPRESENTATION_RELATIONSHIP('','',#77455,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77499) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75107 = ITEM_DEFINED_TRANSFORMATION('','',#11,#171); -#75108 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75109); -#75109 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('226','=>[0:1:1:61]','',#5, - #75058,$); -#75110 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75060)); -#75111 = SHAPE_DEFINITION_REPRESENTATION(#75112,#75118); -#75112 = PRODUCT_DEFINITION_SHAPE('','',#75113); -#75113 = PRODUCT_DEFINITION('design','',#75114,#75117); -#75114 = PRODUCT_DEFINITION_FORMATION('','',#75115); -#75115 = PRODUCT('JP2','JP2','',(#75116)); -#75116 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75117 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75118 = SHAPE_REPRESENTATION('',(#11,#75119,#75123,#75127,#75131), - #75135); -#75119 = AXIS2_PLACEMENT_3D('',#75120,#75121,#75122); -#75120 = CARTESIAN_POINT('',(31.55002072,25.1138182,-2.48730008)); -#75121 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75122 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75123 = AXIS2_PLACEMENT_3D('',#75124,#75125,#75126); -#75124 = CARTESIAN_POINT('',(31.55002072,25.1138182,1.27E-002)); -#75125 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75126 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75127 = AXIS2_PLACEMENT_3D('',#75128,#75129,#75130); -#75128 = CARTESIAN_POINT('',(29.00002074,25.1138182,-2.48730008)); -#75129 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75130 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75131 = AXIS2_PLACEMENT_3D('',#75132,#75133,#75134); -#75132 = CARTESIAN_POINT('',(34.1000207,25.1138182,-2.48730008)); -#75133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75134 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75139)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75136,#75137,#75138)) +#77499 = ITEM_DEFINED_TRANSFORMATION('','',#11,#171); +#77500 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77501); +#77501 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('327','=>[0:1:1:61]','',#5, + #77450,$); +#77502 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77452)); +#77503 = SHAPE_DEFINITION_REPRESENTATION(#77504,#77510); +#77504 = PRODUCT_DEFINITION_SHAPE('','',#77505); +#77505 = PRODUCT_DEFINITION('design','',#77506,#77509); +#77506 = PRODUCT_DEFINITION_FORMATION('','',#77507); +#77507 = PRODUCT('JP2','JP2','',(#77508)); +#77508 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77509 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77510 = SHAPE_REPRESENTATION('',(#11,#77511,#77515,#77519,#77523), + #77527); +#77511 = AXIS2_PLACEMENT_3D('',#77512,#77513,#77514); +#77512 = CARTESIAN_POINT('',(31.55002072,25.1138182,-2.48730008)); +#77513 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77514 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77515 = AXIS2_PLACEMENT_3D('',#77516,#77517,#77518); +#77516 = CARTESIAN_POINT('',(31.55002072,25.1138182,1.27E-002)); +#77517 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77518 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77519 = AXIS2_PLACEMENT_3D('',#77520,#77521,#77522); +#77520 = CARTESIAN_POINT('',(29.00002074,25.1138182,-2.48730008)); +#77521 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77522 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77523 = AXIS2_PLACEMENT_3D('',#77524,#77525,#77526); +#77524 = CARTESIAN_POINT('',(34.1000207,25.1138182,-2.48730008)); +#77525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77526 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77531)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77528,#77529,#77530)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75136 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75137 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75138 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75139 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75136, +#77528 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77529 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77530 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77531 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77528, 'distance_accuracy_value','confusion accuracy'); -#75140 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75141,#75143); -#75141 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75118) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75142) +#77532 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77533,#77535); +#77533 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77510) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77534) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75142 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75119); -#75143 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75144); -#75144 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('227','=>[0:1:1:13]','',#75113, - #11099,$); -#75145 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75146,#75148); -#75146 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75118) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75147) +#77534 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77511); +#77535 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77536); +#77536 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('328','=>[0:1:1:13]','',#77505, + #13491,$); +#77537 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77538,#77540); +#77538 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77510) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77539) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75147 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75123); -#75148 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75149); -#75149 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('228','=>[0:1:1:15]','',#75113, - #11476,$); -#75150 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75151,#75153); -#75151 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75118) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75152) +#77539 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77515); +#77540 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77541); +#77541 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('329','=>[0:1:1:15]','',#77505, + #13868,$); +#77542 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77543,#77545); +#77543 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77510) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77544) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75152 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75127); -#75153 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75154); -#75154 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('229','=>[0:1:1:13]','',#75113, - #11099,$); -#75155 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75156,#75158); -#75156 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75118) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75157) +#77544 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77519); +#77545 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77546); +#77546 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('330','=>[0:1:1:13]','',#77505, + #13491,$); +#77547 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77548,#77550); +#77548 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77510) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77549) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75157 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75131); -#75158 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75159); -#75159 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('230','=>[0:1:1:13]','',#75113, - #11099,$); -#75160 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75161,#75163); -#75161 = ( REPRESENTATION_RELATIONSHIP('','',#75118,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75162) +#77549 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77523); +#77550 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77551); +#77551 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('331','=>[0:1:1:13]','',#77505, + #13491,$); +#77552 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77553,#77555); +#77553 = ( REPRESENTATION_RELATIONSHIP('','',#77510,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77554) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75162 = ITEM_DEFINED_TRANSFORMATION('','',#11,#175); -#75163 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75164); -#75164 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('231','=>[0:1:1:62]','',#5, - #75113,$); -#75165 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75115)); -#75166 = SHAPE_DEFINITION_REPRESENTATION(#75167,#75173); -#75167 = PRODUCT_DEFINITION_SHAPE('','',#75168); -#75168 = PRODUCT_DEFINITION('design','',#75169,#75172); -#75169 = PRODUCT_DEFINITION_FORMATION('','',#75170); -#75170 = PRODUCT('JP3','JP3','',(#75171)); -#75171 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75172 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75173 = SHAPE_REPRESENTATION('',(#11,#75174,#75178,#75182,#75186), - #75190); -#75174 = AXIS2_PLACEMENT_3D('',#75175,#75176,#75177); -#75175 = CARTESIAN_POINT('',(31.55002072,22.5738182,-2.48730008)); -#75176 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75177 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75178 = AXIS2_PLACEMENT_3D('',#75179,#75180,#75181); -#75179 = CARTESIAN_POINT('',(31.55002072,22.5738182,1.27E-002)); -#75180 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75181 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75182 = AXIS2_PLACEMENT_3D('',#75183,#75184,#75185); -#75183 = CARTESIAN_POINT('',(29.00002074,22.5738182,-2.48730008)); -#75184 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75185 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75186 = AXIS2_PLACEMENT_3D('',#75187,#75188,#75189); -#75187 = CARTESIAN_POINT('',(34.1000207,22.5738182,-2.48730008)); -#75188 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75189 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75194)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75191,#75192,#75193)) +#77554 = ITEM_DEFINED_TRANSFORMATION('','',#11,#175); +#77555 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77556); +#77556 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('332','=>[0:1:1:62]','',#5, + #77505,$); +#77557 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77507)); +#77558 = SHAPE_DEFINITION_REPRESENTATION(#77559,#77565); +#77559 = PRODUCT_DEFINITION_SHAPE('','',#77560); +#77560 = PRODUCT_DEFINITION('design','',#77561,#77564); +#77561 = PRODUCT_DEFINITION_FORMATION('','',#77562); +#77562 = PRODUCT('JP3','JP3','',(#77563)); +#77563 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77564 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77565 = SHAPE_REPRESENTATION('',(#11,#77566,#77570,#77574,#77578), + #77582); +#77566 = AXIS2_PLACEMENT_3D('',#77567,#77568,#77569); +#77567 = CARTESIAN_POINT('',(31.55002072,22.5738182,-2.48730008)); +#77568 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77569 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77570 = AXIS2_PLACEMENT_3D('',#77571,#77572,#77573); +#77571 = CARTESIAN_POINT('',(31.55002072,22.5738182,1.27E-002)); +#77572 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77573 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77574 = AXIS2_PLACEMENT_3D('',#77575,#77576,#77577); +#77575 = CARTESIAN_POINT('',(29.00002074,22.5738182,-2.48730008)); +#77576 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77577 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77578 = AXIS2_PLACEMENT_3D('',#77579,#77580,#77581); +#77579 = CARTESIAN_POINT('',(34.1000207,22.5738182,-2.48730008)); +#77580 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77581 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77586)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77583,#77584,#77585)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75191 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75192 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75193 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75194 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75191, +#77583 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77584 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77585 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77586 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77583, 'distance_accuracy_value','confusion accuracy'); -#75195 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75196,#75198); -#75196 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75173) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75197) +#77587 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77588,#77590); +#77588 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77565) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77589) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75197 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75174); -#75198 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75199); -#75199 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('232','=>[0:1:1:13]','',#75168, - #11099,$); -#75200 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75201,#75203); -#75201 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75173) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75202) +#77589 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77566); +#77590 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77591); +#77591 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('333','=>[0:1:1:13]','',#77560, + #13491,$); +#77592 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77593,#77595); +#77593 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77565) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77594) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75202 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75178); -#75203 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75204); -#75204 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('233','=>[0:1:1:15]','',#75168, - #11476,$); -#75205 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75206,#75208); -#75206 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75173) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75207) +#77594 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77570); +#77595 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77596); +#77596 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('334','=>[0:1:1:15]','',#77560, + #13868,$); +#77597 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77598,#77600); +#77598 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77565) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77599) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75207 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75182); -#75208 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75209); -#75209 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('234','=>[0:1:1:13]','',#75168, - #11099,$); -#75210 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75211,#75213); -#75211 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75173) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75212) +#77599 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77574); +#77600 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77601); +#77601 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('335','=>[0:1:1:13]','',#77560, + #13491,$); +#77602 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77603,#77605); +#77603 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77565) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77604) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75212 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75186); -#75213 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75214); -#75214 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('235','=>[0:1:1:13]','',#75168, - #11099,$); -#75215 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75216,#75218); -#75216 = ( REPRESENTATION_RELATIONSHIP('','',#75173,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75217) +#77604 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77578); +#77605 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77606); +#77606 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('336','=>[0:1:1:13]','',#77560, + #13491,$); +#77607 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77608,#77610); +#77608 = ( REPRESENTATION_RELATIONSHIP('','',#77565,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77609) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75217 = ITEM_DEFINED_TRANSFORMATION('','',#11,#179); -#75218 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75219); -#75219 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('236','=>[0:1:1:63]','',#5, - #75168,$); -#75220 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75170)); -#75221 = SHAPE_DEFINITION_REPRESENTATION(#75222,#75228); -#75222 = PRODUCT_DEFINITION_SHAPE('','',#75223); -#75223 = PRODUCT_DEFINITION('design','',#75224,#75227); -#75224 = PRODUCT_DEFINITION_FORMATION('','',#75225); -#75225 = PRODUCT('JP4','JP4','',(#75226)); -#75226 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75227 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75228 = SHAPE_REPRESENTATION('',(#11,#75229,#75233,#75237,#75241), - #75245); -#75229 = AXIS2_PLACEMENT_3D('',#75230,#75231,#75232); -#75230 = CARTESIAN_POINT('',(31.55002072,20.0338182,-2.48730008)); -#75231 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75232 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75233 = AXIS2_PLACEMENT_3D('',#75234,#75235,#75236); -#75234 = CARTESIAN_POINT('',(31.55002072,20.0338182,1.27E-002)); -#75235 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75236 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75237 = AXIS2_PLACEMENT_3D('',#75238,#75239,#75240); -#75238 = CARTESIAN_POINT('',(29.00002074,20.0338182,-2.48730008)); -#75239 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75240 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75241 = AXIS2_PLACEMENT_3D('',#75242,#75243,#75244); -#75242 = CARTESIAN_POINT('',(34.1000207,20.0338182,-2.48730008)); -#75243 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75244 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75249)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75246,#75247,#75248)) +#77609 = ITEM_DEFINED_TRANSFORMATION('','',#11,#179); +#77610 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77611); +#77611 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('337','=>[0:1:1:63]','',#5, + #77560,$); +#77612 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77562)); +#77613 = SHAPE_DEFINITION_REPRESENTATION(#77614,#77620); +#77614 = PRODUCT_DEFINITION_SHAPE('','',#77615); +#77615 = PRODUCT_DEFINITION('design','',#77616,#77619); +#77616 = PRODUCT_DEFINITION_FORMATION('','',#77617); +#77617 = PRODUCT('JP4','JP4','',(#77618)); +#77618 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77619 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77620 = SHAPE_REPRESENTATION('',(#11,#77621,#77625,#77629,#77633), + #77637); +#77621 = AXIS2_PLACEMENT_3D('',#77622,#77623,#77624); +#77622 = CARTESIAN_POINT('',(31.55002072,20.0338182,-2.48730008)); +#77623 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77624 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77625 = AXIS2_PLACEMENT_3D('',#77626,#77627,#77628); +#77626 = CARTESIAN_POINT('',(31.55002072,20.0338182,1.27E-002)); +#77627 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77628 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77629 = AXIS2_PLACEMENT_3D('',#77630,#77631,#77632); +#77630 = CARTESIAN_POINT('',(29.00002074,20.0338182,-2.48730008)); +#77631 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77632 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77633 = AXIS2_PLACEMENT_3D('',#77634,#77635,#77636); +#77634 = CARTESIAN_POINT('',(34.1000207,20.0338182,-2.48730008)); +#77635 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77636 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77641)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77638,#77639,#77640)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75246 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75247 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75248 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75249 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75246, +#77638 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77639 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77640 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77641 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77638, 'distance_accuracy_value','confusion accuracy'); -#75250 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75251,#75253); -#75251 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75228) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75252) +#77642 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77643,#77645); +#77643 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77620) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77644) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75252 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75229); -#75253 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75254); -#75254 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('237','=>[0:1:1:13]','',#75223, - #11099,$); -#75255 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75256,#75258); -#75256 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75228) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75257) +#77644 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77621); +#77645 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77646); +#77646 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('338','=>[0:1:1:13]','',#77615, + #13491,$); +#77647 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77648,#77650); +#77648 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77620) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77649) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75257 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75233); -#75258 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75259); -#75259 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('238','=>[0:1:1:15]','',#75223, - #11476,$); -#75260 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75261,#75263); -#75261 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75228) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75262) +#77649 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77625); +#77650 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77651); +#77651 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('339','=>[0:1:1:15]','',#77615, + #13868,$); +#77652 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77653,#77655); +#77653 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77620) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77654) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75262 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75237); -#75263 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75264); -#75264 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('239','=>[0:1:1:13]','',#75223, - #11099,$); -#75265 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75266,#75268); -#75266 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75228) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75267) +#77654 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77629); +#77655 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77656); +#77656 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('340','=>[0:1:1:13]','',#77615, + #13491,$); +#77657 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77658,#77660); +#77658 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77620) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77659) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75267 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75241); -#75268 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75269); -#75269 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('240','=>[0:1:1:13]','',#75223, - #11099,$); -#75270 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75271,#75273); -#75271 = ( REPRESENTATION_RELATIONSHIP('','',#75228,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75272) +#77659 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77633); +#77660 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77661); +#77661 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('341','=>[0:1:1:13]','',#77615, + #13491,$); +#77662 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77663,#77665); +#77663 = ( REPRESENTATION_RELATIONSHIP('','',#77620,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77664) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75272 = ITEM_DEFINED_TRANSFORMATION('','',#11,#183); -#75273 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75274); -#75274 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('241','=>[0:1:1:64]','',#5, - #75223,$); -#75275 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75225)); -#75276 = SHAPE_DEFINITION_REPRESENTATION(#75277,#75283); -#75277 = PRODUCT_DEFINITION_SHAPE('','',#75278); -#75278 = PRODUCT_DEFINITION('design','',#75279,#75282); -#75279 = PRODUCT_DEFINITION_FORMATION('','',#75280); -#75280 = PRODUCT('JP5','JP5','',(#75281)); -#75281 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75282 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75283 = SHAPE_REPRESENTATION('',(#11,#75284,#75288,#75292,#75296), - #75300); -#75284 = AXIS2_PLACEMENT_3D('',#75285,#75286,#75287); -#75285 = CARTESIAN_POINT('',(31.55002072,17.4938182,-2.48730008)); -#75286 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75287 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75288 = AXIS2_PLACEMENT_3D('',#75289,#75290,#75291); -#75289 = CARTESIAN_POINT('',(31.55002072,17.4938182,1.27E-002)); -#75290 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75291 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75292 = AXIS2_PLACEMENT_3D('',#75293,#75294,#75295); -#75293 = CARTESIAN_POINT('',(29.00002074,17.4938182,-2.48730008)); -#75294 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75295 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75296 = AXIS2_PLACEMENT_3D('',#75297,#75298,#75299); -#75297 = CARTESIAN_POINT('',(34.1000207,17.4938182,-2.48730008)); -#75298 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75299 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75304)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75301,#75302,#75303)) +#77664 = ITEM_DEFINED_TRANSFORMATION('','',#11,#183); +#77665 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77666); +#77666 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('342','=>[0:1:1:64]','',#5, + #77615,$); +#77667 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77617)); +#77668 = SHAPE_DEFINITION_REPRESENTATION(#77669,#77675); +#77669 = PRODUCT_DEFINITION_SHAPE('','',#77670); +#77670 = PRODUCT_DEFINITION('design','',#77671,#77674); +#77671 = PRODUCT_DEFINITION_FORMATION('','',#77672); +#77672 = PRODUCT('JP5','JP5','',(#77673)); +#77673 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77674 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77675 = SHAPE_REPRESENTATION('',(#11,#77676,#77680,#77684,#77688), + #77692); +#77676 = AXIS2_PLACEMENT_3D('',#77677,#77678,#77679); +#77677 = CARTESIAN_POINT('',(31.55002072,17.4938182,-2.48730008)); +#77678 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77679 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77680 = AXIS2_PLACEMENT_3D('',#77681,#77682,#77683); +#77681 = CARTESIAN_POINT('',(31.55002072,17.4938182,1.27E-002)); +#77682 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77683 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77684 = AXIS2_PLACEMENT_3D('',#77685,#77686,#77687); +#77685 = CARTESIAN_POINT('',(29.00002074,17.4938182,-2.48730008)); +#77686 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77687 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77688 = AXIS2_PLACEMENT_3D('',#77689,#77690,#77691); +#77689 = CARTESIAN_POINT('',(34.1000207,17.4938182,-2.48730008)); +#77690 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77691 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77696)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77693,#77694,#77695)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75301 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75302 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75303 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75304 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75301, +#77693 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77694 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77695 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77696 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77693, 'distance_accuracy_value','confusion accuracy'); -#75305 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75306,#75308); -#75306 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75283) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75307) +#77697 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77698,#77700); +#77698 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77675) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77699) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75307 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75284); -#75308 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75309); -#75309 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('242','=>[0:1:1:13]','',#75278, - #11099,$); -#75310 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75311,#75313); -#75311 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75283) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75312) +#77699 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77676); +#77700 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77701); +#77701 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('343','=>[0:1:1:13]','',#77670, + #13491,$); +#77702 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77703,#77705); +#77703 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77675) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77704) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75312 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75288); -#75313 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75314); -#75314 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('243','=>[0:1:1:15]','',#75278, - #11476,$); -#75315 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75316,#75318); -#75316 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75283) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75317) +#77704 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77680); +#77705 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77706); +#77706 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('344','=>[0:1:1:15]','',#77670, + #13868,$); +#77707 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77708,#77710); +#77708 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77675) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77709) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75317 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75292); -#75318 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75319); -#75319 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('244','=>[0:1:1:13]','',#75278, - #11099,$); -#75320 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75321,#75323); -#75321 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75283) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75322) +#77709 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77684); +#77710 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77711); +#77711 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('345','=>[0:1:1:13]','',#77670, + #13491,$); +#77712 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77713,#77715); +#77713 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77675) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77714) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75322 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75296); -#75323 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75324); -#75324 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('245','=>[0:1:1:13]','',#75278, - #11099,$); -#75325 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75326,#75328); -#75326 = ( REPRESENTATION_RELATIONSHIP('','',#75283,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75327) +#77714 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77688); +#77715 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77716); +#77716 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('346','=>[0:1:1:13]','',#77670, + #13491,$); +#77717 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77718,#77720); +#77718 = ( REPRESENTATION_RELATIONSHIP('','',#77675,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77719) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75327 = ITEM_DEFINED_TRANSFORMATION('','',#11,#187); -#75328 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75329); -#75329 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('246','=>[0:1:1:65]','',#5, - #75278,$); -#75330 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75280)); -#75331 = SHAPE_DEFINITION_REPRESENTATION(#75332,#75338); -#75332 = PRODUCT_DEFINITION_SHAPE('','',#75333); -#75333 = PRODUCT_DEFINITION('design','',#75334,#75337); -#75334 = PRODUCT_DEFINITION_FORMATION('','',#75335); -#75335 = PRODUCT('JP6','JP6','',(#75336)); -#75336 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75337 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75338 = SHAPE_REPRESENTATION('',(#11,#75339,#75343,#75347,#75351), - #75355); -#75339 = AXIS2_PLACEMENT_3D('',#75340,#75341,#75342); -#75340 = CARTESIAN_POINT('',(31.55002072,14.9538182,-2.48730008)); -#75341 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75342 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75343 = AXIS2_PLACEMENT_3D('',#75344,#75345,#75346); -#75344 = CARTESIAN_POINT('',(31.55002072,14.9538182,1.27E-002)); -#75345 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75346 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75347 = AXIS2_PLACEMENT_3D('',#75348,#75349,#75350); -#75348 = CARTESIAN_POINT('',(29.00002074,14.9538182,-2.48730008)); -#75349 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75351 = AXIS2_PLACEMENT_3D('',#75352,#75353,#75354); -#75352 = CARTESIAN_POINT('',(34.1000207,14.9538182,-2.48730008)); -#75353 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75354 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75359)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75356,#75357,#75358)) +#77719 = ITEM_DEFINED_TRANSFORMATION('','',#11,#187); +#77720 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77721); +#77721 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('347','=>[0:1:1:65]','',#5, + #77670,$); +#77722 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77672)); +#77723 = SHAPE_DEFINITION_REPRESENTATION(#77724,#77730); +#77724 = PRODUCT_DEFINITION_SHAPE('','',#77725); +#77725 = PRODUCT_DEFINITION('design','',#77726,#77729); +#77726 = PRODUCT_DEFINITION_FORMATION('','',#77727); +#77727 = PRODUCT('JP6','JP6','',(#77728)); +#77728 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77729 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77730 = SHAPE_REPRESENTATION('',(#11,#77731,#77735,#77739,#77743), + #77747); +#77731 = AXIS2_PLACEMENT_3D('',#77732,#77733,#77734); +#77732 = CARTESIAN_POINT('',(31.55002072,14.9538182,-2.48730008)); +#77733 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77734 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77735 = AXIS2_PLACEMENT_3D('',#77736,#77737,#77738); +#77736 = CARTESIAN_POINT('',(31.55002072,14.9538182,1.27E-002)); +#77737 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77738 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77739 = AXIS2_PLACEMENT_3D('',#77740,#77741,#77742); +#77740 = CARTESIAN_POINT('',(29.00002074,14.9538182,-2.48730008)); +#77741 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77743 = AXIS2_PLACEMENT_3D('',#77744,#77745,#77746); +#77744 = CARTESIAN_POINT('',(34.1000207,14.9538182,-2.48730008)); +#77745 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77746 = DIRECTION('',(1.,0.E+000,0.E+000)); +#77747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77751)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77748,#77749,#77750)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75356 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75357 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75358 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75359 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75356, +#77748 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77749 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77750 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77751 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77748, 'distance_accuracy_value','confusion accuracy'); -#75360 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75361,#75363); -#75361 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75338) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75362) +#77752 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77753,#77755); +#77753 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77730) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77754) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75362 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75339); -#75363 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75364); -#75364 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('247','=>[0:1:1:13]','',#75333, - #11099,$); -#75365 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75366,#75368); -#75366 = ( REPRESENTATION_RELATIONSHIP('','',#11481,#75338) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75367) +#77754 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77731); +#77755 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77756); +#77756 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('348','=>[0:1:1:13]','',#77725, + #13491,$); +#77757 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77758,#77760); +#77758 = ( REPRESENTATION_RELATIONSHIP('','',#13873,#77730) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77759) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75367 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75343); -#75368 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75369); -#75369 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('248','=>[0:1:1:15]','',#75333, - #11476,$); -#75370 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75371,#75373); -#75371 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75338) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75372) +#77759 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77735); +#77760 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77761); +#77761 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('349','=>[0:1:1:15]','',#77725, + #13868,$); +#77762 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77763,#77765); +#77763 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77730) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77764) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75372 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75347); -#75373 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75374); -#75374 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('249','=>[0:1:1:13]','',#75333, - #11099,$); -#75375 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75376,#75378); -#75376 = ( REPRESENTATION_RELATIONSHIP('','',#11104,#75338) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75377) +#77764 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77739); +#77765 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77766); +#77766 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('350','=>[0:1:1:13]','',#77725, + #13491,$); +#77767 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77768,#77770); +#77768 = ( REPRESENTATION_RELATIONSHIP('','',#13496,#77730) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77769) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75377 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75351); -#75378 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75379); -#75379 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('250','=>[0:1:1:13]','',#75333, - #11099,$); -#75380 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75381,#75383); -#75381 = ( REPRESENTATION_RELATIONSHIP('','',#75338,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75382) +#77769 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77743); +#77770 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77771); +#77771 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('351','=>[0:1:1:13]','',#77725, + #13491,$); +#77772 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77773,#77775); +#77773 = ( REPRESENTATION_RELATIONSHIP('','',#77730,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77774) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75382 = ITEM_DEFINED_TRANSFORMATION('','',#11,#191); -#75383 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75384); -#75384 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('251','=>[0:1:1:66]','',#5, - #75333,$); -#75385 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75335)); -#75386 = SHAPE_DEFINITION_REPRESENTATION(#75387,#75393); -#75387 = PRODUCT_DEFINITION_SHAPE('','',#75388); -#75388 = PRODUCT_DEFINITION('design','',#75389,#75392); -#75389 = PRODUCT_DEFINITION_FORMATION('','',#75390); -#75390 = PRODUCT('R2','R2','',(#75391)); -#75391 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75392 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75393 = SHAPE_REPRESENTATION('',(#11,#75394),#75398); -#75394 = AXIS2_PLACEMENT_3D('',#75395,#75396,#75397); -#75395 = CARTESIAN_POINT('',(28.067,11.1719995,-1.27E-002)); -#75396 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75397 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#75398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75402)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75399,#75400,#75401)) +#77774 = ITEM_DEFINED_TRANSFORMATION('','',#11,#191); +#77775 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77776); +#77776 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('352','=>[0:1:1:66]','',#5, + #77725,$); +#77777 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77727)); +#77778 = SHAPE_DEFINITION_REPRESENTATION(#77779,#77785); +#77779 = PRODUCT_DEFINITION_SHAPE('','',#77780); +#77780 = PRODUCT_DEFINITION('design','',#77781,#77784); +#77781 = PRODUCT_DEFINITION_FORMATION('','',#77782); +#77782 = PRODUCT('R2','R2','',(#77783)); +#77783 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77784 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77785 = SHAPE_REPRESENTATION('',(#11,#77786),#77790); +#77786 = AXIS2_PLACEMENT_3D('',#77787,#77788,#77789); +#77787 = CARTESIAN_POINT('',(28.067,11.1719995,-1.27E-002)); +#77788 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77789 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#77790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77794)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77791,#77792,#77793)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75399 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75400 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75401 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75402 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75399, +#77791 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77792 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77793 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77794 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77791, 'distance_accuracy_value','confusion accuracy'); -#75403 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75404,#75406); -#75404 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#75393) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75405) +#77795 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77796,#77798); +#77796 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#77785) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77797) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75405 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75394); -#75406 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75407); -#75407 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('252','=>[0:1:1:7]','',#75388, - #7462,$); -#75408 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75409,#75411); -#75409 = ( REPRESENTATION_RELATIONSHIP('','',#75393,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75410) +#77797 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77786); +#77798 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77799); +#77799 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('353','=>[0:1:1:7]','',#77780, + #9854,$); +#77800 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77801,#77803); +#77801 = ( REPRESENTATION_RELATIONSHIP('','',#77785,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77802) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75410 = ITEM_DEFINED_TRANSFORMATION('','',#11,#195); -#75411 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75412); -#75412 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('253','=>[0:1:1:67]','',#5, - #75388,$); -#75413 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75390)); -#75414 = SHAPE_DEFINITION_REPRESENTATION(#75415,#75421); -#75415 = PRODUCT_DEFINITION_SHAPE('','',#75416); -#75416 = PRODUCT_DEFINITION('design','',#75417,#75420); -#75417 = PRODUCT_DEFINITION_FORMATION('','',#75418); -#75418 = PRODUCT('R10','R10','',(#75419)); -#75419 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75420 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75421 = SHAPE_REPRESENTATION('',(#11,#75422),#75426); -#75422 = AXIS2_PLACEMENT_3D('',#75423,#75424,#75425); -#75423 = CARTESIAN_POINT('',(7.1160005,18.796,-1.27E-002)); -#75424 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75425 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#75426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75430)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75427,#75428,#75429)) +#77802 = ITEM_DEFINED_TRANSFORMATION('','',#11,#195); +#77803 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77804); +#77804 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('354','=>[0:1:1:67]','',#5, + #77780,$); +#77805 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77782)); +#77806 = SHAPE_DEFINITION_REPRESENTATION(#77807,#77813); +#77807 = PRODUCT_DEFINITION_SHAPE('','',#77808); +#77808 = PRODUCT_DEFINITION('design','',#77809,#77812); +#77809 = PRODUCT_DEFINITION_FORMATION('','',#77810); +#77810 = PRODUCT('R10','R10','',(#77811)); +#77811 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77812 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77813 = SHAPE_REPRESENTATION('',(#11,#77814),#77818); +#77814 = AXIS2_PLACEMENT_3D('',#77815,#77816,#77817); +#77815 = CARTESIAN_POINT('',(7.1160005,18.796,-1.27E-002)); +#77816 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77817 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#77818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77822)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77819,#77820,#77821)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75427 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75428 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75429 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75430 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75427, +#77819 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77820 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77821 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77822 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77819, 'distance_accuracy_value','confusion accuracy'); -#75431 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75432,#75434); -#75432 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#75421) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75433) +#77823 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77824,#77826); +#77824 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#77813) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77825) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75433 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75422); -#75434 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75435); -#75435 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('254','=>[0:1:1:7]','',#75416, - #7462,$); -#75436 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75437,#75439); -#75437 = ( REPRESENTATION_RELATIONSHIP('','',#75421,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75438) +#77825 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77814); +#77826 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77827); +#77827 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('355','=>[0:1:1:7]','',#77808, + #9854,$); +#77828 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77829,#77831); +#77829 = ( REPRESENTATION_RELATIONSHIP('','',#77813,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77830) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75438 = ITEM_DEFINED_TRANSFORMATION('','',#11,#199); -#75439 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75440); -#75440 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('255','=>[0:1:1:68]','',#5, - #75416,$); -#75441 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75418)); -#75442 = SHAPE_DEFINITION_REPRESENTATION(#75443,#75449); -#75443 = PRODUCT_DEFINITION_SHAPE('','',#75444); -#75444 = PRODUCT_DEFINITION('design','',#75445,#75448); -#75445 = PRODUCT_DEFINITION_FORMATION('','',#75446); -#75446 = PRODUCT('R11','R11','',(#75447)); -#75447 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75448 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75449 = SHAPE_REPRESENTATION('',(#11,#75450),#75454); -#75450 = AXIS2_PLACEMENT_3D('',#75451,#75452,#75453); -#75451 = CARTESIAN_POINT('',(6.604,14.7360005,-1.27E-002)); -#75452 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75453 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#75454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75458)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75455,#75456,#75457)) +#77830 = ITEM_DEFINED_TRANSFORMATION('','',#11,#199); +#77831 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77832); +#77832 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('356','=>[0:1:1:68]','',#5, + #77808,$); +#77833 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77810)); +#77834 = SHAPE_DEFINITION_REPRESENTATION(#77835,#77841); +#77835 = PRODUCT_DEFINITION_SHAPE('','',#77836); +#77836 = PRODUCT_DEFINITION('design','',#77837,#77840); +#77837 = PRODUCT_DEFINITION_FORMATION('','',#77838); +#77838 = PRODUCT('R11','R11','',(#77839)); +#77839 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77840 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77841 = SHAPE_REPRESENTATION('',(#11,#77842),#77846); +#77842 = AXIS2_PLACEMENT_3D('',#77843,#77844,#77845); +#77843 = CARTESIAN_POINT('',(6.604,14.7360005,-1.27E-002)); +#77844 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77845 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#77846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77850)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77847,#77848,#77849)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75455 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75456 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75457 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75458 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75455, +#77847 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77848 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77849 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77850 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77847, 'distance_accuracy_value','confusion accuracy'); -#75459 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75460,#75462); -#75460 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#75449) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75461) +#77851 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77852,#77854); +#77852 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#77841) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77853) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75461 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75450); -#75462 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75463); -#75463 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('256','=>[0:1:1:7]','',#75444, - #7462,$); -#75464 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75465,#75467); -#75465 = ( REPRESENTATION_RELATIONSHIP('','',#75449,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75466) +#77853 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77842); +#77854 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77855); +#77855 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('357','=>[0:1:1:7]','',#77836, + #9854,$); +#77856 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77857,#77859); +#77857 = ( REPRESENTATION_RELATIONSHIP('','',#77841,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77858) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75466 = ITEM_DEFINED_TRANSFORMATION('','',#11,#203); -#75467 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75468); -#75468 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('257','=>[0:1:1:69]','',#5, - #75444,$); -#75469 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75446)); -#75470 = SHAPE_DEFINITION_REPRESENTATION(#75471,#75477); -#75471 = PRODUCT_DEFINITION_SHAPE('','',#75472); -#75472 = PRODUCT_DEFINITION('design','',#75473,#75476); -#75473 = PRODUCT_DEFINITION_FORMATION('','',#75474); -#75474 = PRODUCT('R13','R13','',(#75475)); -#75475 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75476 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75477 = SHAPE_REPRESENTATION('',(#11,#75478),#75482); -#75478 = AXIS2_PLACEMENT_3D('',#75479,#75480,#75481); -#75479 = CARTESIAN_POINT('',(6.604,13.7200005,-1.27E-002)); -#75480 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75481 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#75482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75486)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75483,#75484,#75485)) +#77858 = ITEM_DEFINED_TRANSFORMATION('','',#11,#203); +#77859 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77860); +#77860 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('358','=>[0:1:1:69]','',#5, + #77836,$); +#77861 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77838)); +#77862 = SHAPE_DEFINITION_REPRESENTATION(#77863,#77869); +#77863 = PRODUCT_DEFINITION_SHAPE('','',#77864); +#77864 = PRODUCT_DEFINITION('design','',#77865,#77868); +#77865 = PRODUCT_DEFINITION_FORMATION('','',#77866); +#77866 = PRODUCT('R13','R13','',(#77867)); +#77867 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77868 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77869 = SHAPE_REPRESENTATION('',(#11,#77870),#77874); +#77870 = AXIS2_PLACEMENT_3D('',#77871,#77872,#77873); +#77871 = CARTESIAN_POINT('',(6.604,13.7200005,-1.27E-002)); +#77872 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77873 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#77874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77878)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77875,#77876,#77877)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75483 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75484 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75485 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75486 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75483, +#77875 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77876 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77877 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77878 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77875, 'distance_accuracy_value','confusion accuracy'); -#75487 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75488,#75490); -#75488 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#75477) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75489) +#77879 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77880,#77882); +#77880 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#77869) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77881) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75489 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75478); -#75490 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75491); -#75491 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('258','=>[0:1:1:7]','',#75472, - #7462,$); -#75492 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75493,#75495); -#75493 = ( REPRESENTATION_RELATIONSHIP('','',#75477,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75494) +#77881 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77870); +#77882 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77883); +#77883 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('359','=>[0:1:1:7]','',#77864, + #9854,$); +#77884 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77885,#77887); +#77885 = ( REPRESENTATION_RELATIONSHIP('','',#77869,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77886) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75494 = ITEM_DEFINED_TRANSFORMATION('','',#11,#207); -#75495 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75496); -#75496 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('259','=>[0:1:1:70]','',#5, - #75472,$); -#75497 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75474)); -#75498 = SHAPE_DEFINITION_REPRESENTATION(#75499,#75505); -#75499 = PRODUCT_DEFINITION_SHAPE('','',#75500); -#75500 = PRODUCT_DEFINITION('design','',#75501,#75504); -#75501 = PRODUCT_DEFINITION_FORMATION('','',#75502); -#75502 = PRODUCT('R16','R16','',(#75503)); -#75503 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75504 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75505 = SHAPE_REPRESENTATION('',(#11,#75506),#75510); -#75506 = AXIS2_PLACEMENT_3D('',#75507,#75508,#75509); -#75507 = CARTESIAN_POINT('',(19.558,8.3779995,-1.27E-002)); -#75508 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75509 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#75510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75514)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75511,#75512,#75513)) +#77886 = ITEM_DEFINED_TRANSFORMATION('','',#11,#207); +#77887 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77888); +#77888 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('360','=>[0:1:1:70]','',#5, + #77864,$); +#77889 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77866)); +#77890 = SHAPE_DEFINITION_REPRESENTATION(#77891,#77897); +#77891 = PRODUCT_DEFINITION_SHAPE('','',#77892); +#77892 = PRODUCT_DEFINITION('design','',#77893,#77896); +#77893 = PRODUCT_DEFINITION_FORMATION('','',#77894); +#77894 = PRODUCT('R16','R16','',(#77895)); +#77895 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77896 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77897 = SHAPE_REPRESENTATION('',(#11,#77898),#77902); +#77898 = AXIS2_PLACEMENT_3D('',#77899,#77900,#77901); +#77899 = CARTESIAN_POINT('',(19.558,8.3779995,-1.27E-002)); +#77900 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77901 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#77902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77906)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77903,#77904,#77905)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75511 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75512 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75513 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75514 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#75511, +#77903 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77904 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77905 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77906 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#77903, 'distance_accuracy_value','confusion accuracy'); -#75515 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75516,#75518); -#75516 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#75505) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75517) +#77907 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77908,#77910); +#77908 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#77897) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77909) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75517 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75506); -#75518 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75519); -#75519 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('260','=>[0:1:1:7]','',#75500, - #7462,$); -#75520 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#75521,#75523); -#75521 = ( REPRESENTATION_RELATIONSHIP('','',#75505,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#75522) +#77909 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77898); +#77910 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77911); +#77911 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('361','=>[0:1:1:7]','',#77892, + #9854,$); +#77912 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#77913,#77915); +#77913 = ( REPRESENTATION_RELATIONSHIP('','',#77897,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#77914) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#75522 = ITEM_DEFINED_TRANSFORMATION('','',#11,#211); -#75523 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #75524); -#75524 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('261','=>[0:1:1:71]','',#5, - #75500,$); -#75525 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75502)); -#75526 = SHAPE_DEFINITION_REPRESENTATION(#75527,#75533); -#75527 = PRODUCT_DEFINITION_SHAPE('','',#75528); -#75528 = PRODUCT_DEFINITION('design','',#75529,#75532); -#75529 = PRODUCT_DEFINITION_FORMATION('','',#75530); -#75530 = PRODUCT('U2','U2','',(#75531)); -#75531 = PRODUCT_CONTEXT('',#2,'mechanical'); -#75532 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#75533 = SHAPE_REPRESENTATION('',(#11,#75534),#75538); -#75534 = AXIS2_PLACEMENT_3D('',#75535,#75536,#75537); -#75535 = CARTESIAN_POINT('',(24.51091872,26.2888857,-1.27E-002)); -#75536 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75537 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#75538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#75542)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#75539,#75540,#75541)) +#77914 = ITEM_DEFINED_TRANSFORMATION('','',#11,#211); +#77915 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #77916); +#77916 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('362','=>[0:1:1:71]','',#5, + #77892,$); +#77917 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77894)); +#77918 = SHAPE_DEFINITION_REPRESENTATION(#77919,#77925); +#77919 = PRODUCT_DEFINITION_SHAPE('','',#77920); +#77920 = PRODUCT_DEFINITION('design','',#77921,#77924); +#77921 = PRODUCT_DEFINITION_FORMATION('','',#77922); +#77922 = PRODUCT('U2','U2','',(#77923)); +#77923 = PRODUCT_CONTEXT('',#2,'mechanical'); +#77924 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#77925 = SHAPE_REPRESENTATION('',(#11,#77926),#77930); +#77926 = AXIS2_PLACEMENT_3D('',#77927,#77928,#77929); +#77927 = CARTESIAN_POINT('',(24.51091872,26.2888857,-1.27E-002)); +#77928 = DIRECTION('',(0.E+000,0.E+000,1.)); +#77929 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#77930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#77934)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#77931,#77932,#77933)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#75539 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#75540 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#75541 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#75542 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-004),#75539, +#77931 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#77932 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#77933 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#77934 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-004),#77931, 'distance_accuracy_value','confusion accuracy'); -#75543 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#75544),#85891); -#75544 = MANIFOLD_SOLID_BREP('',#75545); -#75545 = CLOSED_SHELL('',(#75546,#75826,#76101,#76376,#76651,#76954, - #77229,#77504,#77779,#78116,#78583,#78752,#78918,#79064,#79234, - #79555,#79667,#79802,#80123,#80198,#80273,#80527,#80746,#80772, - #80798,#80847,#80874,#80901,#80950,#80976,#81002,#81009,#81084, - #81159,#81413,#81632,#81658,#81684,#81733,#81760,#81787,#81836, - #81862,#81888,#81895,#81970,#82251,#82299,#82518,#82544,#82570, - #82619,#82646,#82673,#82722,#82748,#82774,#82781,#82856,#83137, - #83185,#83404,#83430,#83456,#83505,#83532,#83559,#83608,#83634, - #83660,#83667,#83742,#84023,#84264,#84311,#84360,#84386,#84412, - #84438,#84445,#84471,#84497,#84546,#84553,#84691,#84764,#84902, - #84975,#85113,#85186,#85324,#85397,#85446,#85453,#85502,#85551, - #85558,#85565,#85614,#85621,#85670,#85742,#85749,#85756,#85805, - #85877,#85884)); -#75546 = ADVANCED_FACE('',(#75547),#75562,.T.); -#75547 = FACE_BOUND('',#75548,.T.); -#75548 = EDGE_LOOP('',(#75549,#75620,#75705,#75778)); -#75549 = ORIENTED_EDGE('',*,*,#75550,.F.); -#75550 = EDGE_CURVE('',#75551,#75553,#75555,.T.); -#75551 = VERTEX_POINT('',#75552); -#75552 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#75553 = VERTEX_POINT('',#75554); -#75554 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#75555 = SURFACE_CURVE('',#75556,(#75561,#75607),.PCURVE_S1.); -#75556 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75557,#75558,#75559,#75560 +#77935 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#77936),#88283); +#77936 = MANIFOLD_SOLID_BREP('',#77937); +#77937 = CLOSED_SHELL('',(#77938,#78218,#78493,#78768,#79043,#79346, + #79621,#79896,#80171,#80508,#80975,#81144,#81310,#81456,#81626, + #81947,#82059,#82194,#82515,#82590,#82665,#82919,#83138,#83164, + #83190,#83239,#83266,#83293,#83342,#83368,#83394,#83401,#83476, + #83551,#83805,#84024,#84050,#84076,#84125,#84152,#84179,#84228, + #84254,#84280,#84287,#84362,#84643,#84691,#84910,#84936,#84962, + #85011,#85038,#85065,#85114,#85140,#85166,#85173,#85248,#85529, + #85577,#85796,#85822,#85848,#85897,#85924,#85951,#86000,#86026, + #86052,#86059,#86134,#86415,#86656,#86703,#86752,#86778,#86804, + #86830,#86837,#86863,#86889,#86938,#86945,#87083,#87156,#87294, + #87367,#87505,#87578,#87716,#87789,#87838,#87845,#87894,#87943, + #87950,#87957,#88006,#88013,#88062,#88134,#88141,#88148,#88197, + #88269,#88276)); +#77938 = ADVANCED_FACE('',(#77939),#77954,.T.); +#77939 = FACE_BOUND('',#77940,.T.); +#77940 = EDGE_LOOP('',(#77941,#78012,#78097,#78170)); +#77941 = ORIENTED_EDGE('',*,*,#77942,.F.); +#77942 = EDGE_CURVE('',#77943,#77945,#77947,.T.); +#77943 = VERTEX_POINT('',#77944); +#77944 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#77945 = VERTEX_POINT('',#77946); +#77946 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#77947 = SURFACE_CURVE('',#77948,(#77953,#77999),.PCURVE_S1.); +#77948 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77949,#77950,#77951,#77952 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75557 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#75558 = CARTESIAN_POINT('',(1.241596067115,-0.46790129499,1.E-001)); -#75559 = CARTESIAN_POINT('',(1.217584046027,-0.477659054385,1.E-001)); -#75560 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#75561 = PCURVE('',#75562,#75579); -#75562 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#75563,#75564,#75565,#75566) - ,(#75567,#75568,#75569,#75570) - ,(#75571,#75572,#75573,#75574) - ,(#75575,#75576,#75577,#75578 +#77949 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#77950 = CARTESIAN_POINT('',(1.241596067115,-0.46790129499,1.E-001)); +#77951 = CARTESIAN_POINT('',(1.217584046027,-0.477659054385,1.E-001)); +#77952 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#77953 = PCURVE('',#77954,#77971); +#77954 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#77955,#77956,#77957,#77958) + ,(#77959,#77960,#77961,#77962) + ,(#77963,#77964,#77965,#77966) + ,(#77967,#77968,#77969,#77970 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#75563 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#75564 = CARTESIAN_POINT('',(1.191066471757,-0.499475670035,1.E-001)); -#75565 = CARTESIAN_POINT('',(1.191066471757,-0.52030879007, +#77955 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#77956 = CARTESIAN_POINT('',(1.191066471757,-0.499475670035,1.E-001)); +#77957 = CARTESIAN_POINT('',(1.191066471757,-0.52030879007, 0.115985815246)); -#75566 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 +#77958 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 )); -#75567 = CARTESIAN_POINT('',(1.21695495248,-0.477659054385,1.E-001)); -#75568 = CARTESIAN_POINT('',(1.222435083194,-0.498429042165,1.E-001)); -#75569 = CARTESIAN_POINT('',(1.227668168966,-0.518443665671, +#77959 = CARTESIAN_POINT('',(1.21695495248,-0.477659054385,1.E-001)); +#77960 = CARTESIAN_POINT('',(1.222435083194,-0.498429042165,1.E-001)); +#77961 = CARTESIAN_POINT('',(1.227668168966,-0.518443665671, 0.114318476015)); -#75570 = CARTESIAN_POINT('',(1.229086531164,-0.525142684022, +#77962 = CARTESIAN_POINT('',(1.229086531164,-0.525142684022, 0.134026153074)); -#75571 = CARTESIAN_POINT('',(1.242026713303,-0.467470648802,1.E-001)); -#75572 = CARTESIAN_POINT('',(1.252452511959,-0.485531311073,1.E-001)); -#75573 = CARTESIAN_POINT('',(1.262532596412,-0.50299309093, +#77963 = CARTESIAN_POINT('',(1.242026713303,-0.467470648802,1.E-001)); +#77964 = CARTESIAN_POINT('',(1.252452511959,-0.485531311073,1.E-001)); +#77965 = CARTESIAN_POINT('',(1.262532596412,-0.50299309093, 0.113446578632)); -#75574 = CARTESIAN_POINT('',(1.266226971076,-0.509392874324,0.132282534) +#77966 = CARTESIAN_POINT('',(1.266226971076,-0.509392874324,0.132282534) ); -#75575 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#75576 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); -#75577 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, +#77967 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#77968 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); +#77969 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, 0.113446578632)); -#75578 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#75579 = DEFINITIONAL_REPRESENTATION('',(#75580),#75606); -#75580 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75581,#75582,#75583,#75584, - #75585,#75586,#75587,#75588,#75589,#75590,#75591,#75592,#75593, - #75594,#75595,#75596,#75597,#75598,#75599,#75600,#75601,#75602, - #75603,#75604,#75605),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#77970 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#77971 = DEFINITIONAL_REPRESENTATION('',(#77972),#77998); +#77972 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77973,#77974,#77975,#77976, + #77977,#77978,#77979,#77980,#77981,#77982,#77983,#77984,#77985, + #77986,#77987,#77988,#77989,#77990,#77991,#77992,#77993,#77994, + #77995,#77996,#77997),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(8.809142651445E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -93187,69 +96176,69 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#75581 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#75582 = CARTESIAN_POINT('',(6.272059569215,1.375318786182E-008)); -#75583 = CARTESIAN_POINT('',(6.24973263213,2.924134010748E-005)); -#75584 = CARTESIAN_POINT('',(6.21603939964,1.4137075777E-004)); -#75585 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); -#75586 = CARTESIAN_POINT('',(6.148138870073,4.93149846864E-004)); -#75587 = CARTESIAN_POINT('',(6.113975913115,6.962198987687E-004)); -#75588 = CARTESIAN_POINT('',(6.079699188623,8.953387637315E-004)); -#75589 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); -#75590 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); -#75591 = CARTESIAN_POINT('',(5.976382533559,1.33926347788E-003)); -#75592 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); -#75593 = CARTESIAN_POINT('',(5.907285653264,1.422641316496E-003)); -#75594 = CARTESIAN_POINT('',(5.87272580864,1.390009812367E-003)); -#75595 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); -#75596 = CARTESIAN_POINT('',(5.803674042174,1.187353930381E-003)); -#75597 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); -#75598 = CARTESIAN_POINT('',(5.734837892756,8.475624467434E-004)); -#75599 = CARTESIAN_POINT('',(5.700549707253,6.520952931825E-004)); -#75600 = CARTESIAN_POINT('',(5.666375694827,4.570658043145E-004)); -#75601 = CARTESIAN_POINT('',(5.632337541793,2.772530388755E-004)); -#75602 = CARTESIAN_POINT('',(5.598457782919,1.282673134885E-004)); -#75603 = CARTESIAN_POINT('',(5.564759695218,2.616756246979E-005)); -#75604 = CARTESIAN_POINT('',(5.542431609433,-2.901324312813E-008)); -#75605 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#75606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75607 = PCURVE('',#75608,#75613); -#75608 = PLANE('',#75609); -#75609 = AXIS2_PLACEMENT_3D('',#75610,#75611,#75612); -#75610 = CARTESIAN_POINT('',(1.46,-0.65,1.E-001)); -#75611 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75612 = DIRECTION('',(1.,0.E+000,0.E+000)); -#75613 = DEFINITIONAL_REPRESENTATION('',(#75614),#75619); -#75614 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75615,#75616,#75617,#75618 +#77973 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#77974 = CARTESIAN_POINT('',(6.272059569215,1.375318786182E-008)); +#77975 = CARTESIAN_POINT('',(6.24973263213,2.924134010748E-005)); +#77976 = CARTESIAN_POINT('',(6.21603939964,1.4137075777E-004)); +#77977 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); +#77978 = CARTESIAN_POINT('',(6.148138870073,4.93149846864E-004)); +#77979 = CARTESIAN_POINT('',(6.113975913115,6.962198987687E-004)); +#77980 = CARTESIAN_POINT('',(6.079699188623,8.953387637315E-004)); +#77981 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); +#77982 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); +#77983 = CARTESIAN_POINT('',(5.976382533559,1.33926347788E-003)); +#77984 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); +#77985 = CARTESIAN_POINT('',(5.907285653264,1.422641316496E-003)); +#77986 = CARTESIAN_POINT('',(5.87272580864,1.390009812367E-003)); +#77987 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); +#77988 = CARTESIAN_POINT('',(5.803674042174,1.187353930381E-003)); +#77989 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); +#77990 = CARTESIAN_POINT('',(5.734837892756,8.475624467434E-004)); +#77991 = CARTESIAN_POINT('',(5.700549707253,6.520952931825E-004)); +#77992 = CARTESIAN_POINT('',(5.666375694827,4.570658043145E-004)); +#77993 = CARTESIAN_POINT('',(5.632337541793,2.772530388755E-004)); +#77994 = CARTESIAN_POINT('',(5.598457782919,1.282673134885E-004)); +#77995 = CARTESIAN_POINT('',(5.564759695218,2.616756246979E-005)); +#77996 = CARTESIAN_POINT('',(5.542431609433,-2.901324312813E-008)); +#77997 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#77998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#77999 = PCURVE('',#78000,#78005); +#78000 = PLANE('',#78001); +#78001 = AXIS2_PLACEMENT_3D('',#78002,#78003,#78004); +#78002 = CARTESIAN_POINT('',(1.46,-0.65,1.E-001)); +#78003 = DIRECTION('',(0.E+000,0.E+000,1.)); +#78004 = DIRECTION('',(1.,0.E+000,0.E+000)); +#78005 = DEFINITIONAL_REPRESENTATION('',(#78006),#78011); +#78006 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78007,#78008,#78009,#78010 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75615 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#75616 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); -#75617 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); -#75618 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); -#75619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75620 = ORIENTED_EDGE('',*,*,#75621,.T.); -#75621 = EDGE_CURVE('',#75551,#75622,#75624,.T.); -#75622 = VERTEX_POINT('',#75623); -#75623 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#75624 = SURFACE_CURVE('',#75625,(#75630,#75659),.PCURVE_S1.); -#75625 = CIRCLE('',#75626,5.E-002); -#75626 = AXIS2_PLACEMENT_3D('',#75627,#75628,#75629); -#75627 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,0.15)); -#75628 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#75629 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#75630 = PCURVE('',#75562,#75631); -#75631 = DEFINITIONAL_REPRESENTATION('',(#75632),#75658); -#75632 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75633,#75634,#75635,#75636, - #75637,#75638,#75639,#75640,#75641,#75642,#75643,#75644,#75645, - #75646,#75647,#75648,#75649,#75650,#75651,#75652,#75653,#75654, - #75655,#75656,#75657),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78007 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#78008 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); +#78009 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); +#78010 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); +#78011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78012 = ORIENTED_EDGE('',*,*,#78013,.T.); +#78013 = EDGE_CURVE('',#77943,#78014,#78016,.T.); +#78014 = VERTEX_POINT('',#78015); +#78015 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#78016 = SURFACE_CURVE('',#78017,(#78022,#78051),.PCURVE_S1.); +#78017 = CIRCLE('',#78018,5.E-002); +#78018 = AXIS2_PLACEMENT_3D('',#78019,#78020,#78021); +#78019 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,0.15)); +#78020 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#78021 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#78022 = PCURVE('',#77954,#78023); +#78023 = DEFINITIONAL_REPRESENTATION('',(#78024),#78050); +#78024 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78025,#78026,#78027,#78028, + #78029,#78030,#78031,#78032,#78033,#78034,#78035,#78036,#78037, + #78038,#78039,#78040,#78041,#78042,#78043,#78044,#78045,#78046, + #78047,#78048,#78049),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -93257,70 +96246,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#75633 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#75634 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#75635 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#75636 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#75637 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#75638 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#75639 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#75640 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#75641 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#75642 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#75643 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#75644 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#75645 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#75646 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#75647 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#75648 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#75649 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#75650 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#75651 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#75652 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#75653 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#75654 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#75655 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#75656 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#75657 = CARTESIAN_POINT('',(6.28318530718,1.)); -#75658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75659 = PCURVE('',#75660,#75677); -#75660 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#75661,#75662,#75663,#75664) - ,(#75665,#75666,#75667,#75668) - ,(#75669,#75670,#75671,#75672) - ,(#75673,#75674,#75675,#75676 +#78025 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78026 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#78027 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#78028 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#78029 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#78030 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#78031 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#78032 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#78033 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#78034 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#78035 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#78036 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#78037 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#78038 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#78039 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#78040 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#78041 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#78042 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#78043 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#78044 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#78045 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#78046 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#78047 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#78048 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#78049 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78051 = PCURVE('',#78052,#78069); +#78052 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78053,#78054,#78055,#78056) + ,(#78057,#78058,#78059,#78060) + ,(#78061,#78062,#78063,#78064) + ,(#78065,#78066,#78067,#78068 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#75661 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#75662 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); -#75663 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, +#78053 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#78054 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); +#78055 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, 0.113446578632)); -#75664 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#75665 = CARTESIAN_POINT('',(1.277470648802,-0.432026713303,1.E-001)); -#75666 = CARTESIAN_POINT('',(1.295531311073,-0.442452511959,1.E-001)); -#75667 = CARTESIAN_POINT('',(1.31299309093,-0.452532596412, +#78056 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#78057 = CARTESIAN_POINT('',(1.277470648802,-0.432026713303,1.E-001)); +#78058 = CARTESIAN_POINT('',(1.295531311073,-0.442452511959,1.E-001)); +#78059 = CARTESIAN_POINT('',(1.31299309093,-0.452532596412, 0.113446578632)); -#75668 = CARTESIAN_POINT('',(1.319392874324,-0.456226971076,0.132282534) +#78060 = CARTESIAN_POINT('',(1.319392874324,-0.456226971076,0.132282534) ); -#75669 = CARTESIAN_POINT('',(1.287659054385,-0.40695495248,1.E-001)); -#75670 = CARTESIAN_POINT('',(1.308429042165,-0.412435083194,1.E-001)); -#75671 = CARTESIAN_POINT('',(1.328443665671,-0.417668168966, +#78061 = CARTESIAN_POINT('',(1.287659054385,-0.40695495248,1.E-001)); +#78062 = CARTESIAN_POINT('',(1.308429042165,-0.412435083194,1.E-001)); +#78063 = CARTESIAN_POINT('',(1.328443665671,-0.417668168966, 0.114318476015)); -#75672 = CARTESIAN_POINT('',(1.335142684022,-0.419086531164, +#78064 = CARTESIAN_POINT('',(1.335142684022,-0.419086531164, 0.134026153074)); -#75673 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#75674 = CARTESIAN_POINT('',(1.309475670035,-0.381066471757,1.E-001)); -#75675 = CARTESIAN_POINT('',(1.33030879007,-0.381066471757, +#78065 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#78066 = CARTESIAN_POINT('',(1.309475670035,-0.381066471757,1.E-001)); +#78067 = CARTESIAN_POINT('',(1.33030879007,-0.381066471757, 0.115985815246)); -#75676 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 +#78068 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 )); -#75677 = DEFINITIONAL_REPRESENTATION('',(#75678),#75704); -#75678 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75679,#75680,#75681,#75682, - #75683,#75684,#75685,#75686,#75687,#75688,#75689,#75690,#75691, - #75692,#75693,#75694,#75695,#75696,#75697,#75698,#75699,#75700, - #75701,#75702,#75703),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78069 = DEFINITIONAL_REPRESENTATION('',(#78070),#78096); +#78070 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78071,#78072,#78073,#78074, + #78075,#78076,#78077,#78078,#78079,#78080,#78081,#78082,#78083, + #78084,#78085,#78086,#78087,#78088,#78089,#78090,#78091,#78092, + #78093,#78094,#78095),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -93328,58 +96317,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#75679 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#75680 = CARTESIAN_POINT('',(-1.144439603192E-015,1.515278164504E-002)); -#75681 = CARTESIAN_POINT('',(-9.175368395657E-016,4.549920749135E-002)); -#75682 = CARTESIAN_POINT('',(1.372925320255E-016,9.109101074357E-002)); -#75683 = CARTESIAN_POINT('',(5.6159890698E-016,0.136698748187)); -#75684 = CARTESIAN_POINT('',(-1.545422737611E-015,0.1822865144)); -#75685 = CARTESIAN_POINT('',(-1.348585819112E-015,0.2278300409)); -#75686 = CARTESIAN_POINT('',(3.786426572017E-016,0.27331674602)); -#75687 = CARTESIAN_POINT('',(-3.253009613166E-016,0.318743220066)); -#75688 = CARTESIAN_POINT('',(-7.297245182018E-016,0.364113426255)); -#75689 = CARTESIAN_POINT('',(1.988956429665E-015,0.409436881051)); -#75690 = CARTESIAN_POINT('',(-6.120609827186E-016,0.454727066523)); -#75691 = CARTESIAN_POINT('',(-1.685236759928E-015,0.5)); -#75692 = CARTESIAN_POINT('',(1.855627463945E-015,0.545272933477)); -#75693 = CARTESIAN_POINT('',(-2.167943843688E-015,0.590563118949)); -#75694 = CARTESIAN_POINT('',(2.303008870842E-016,0.635886573745)); -#75695 = CARTESIAN_POINT('',(-3.217601376884E-017,0.681256779934)); -#75696 = CARTESIAN_POINT('',(5.276053820311E-016,0.72668325398)); -#75697 = CARTESIAN_POINT('',(-1.216399179866E-015,0.7721699591)); -#75698 = CARTESIAN_POINT('',(4.872508256886E-016,0.8177134856)); -#75699 = CARTESIAN_POINT('',(-1.155567275167E-015,0.863301251813)); -#75700 = CARTESIAN_POINT('',(6.923566871284E-016,0.908908989256)); -#75701 = CARTESIAN_POINT('',(-1.695305503108E-015,0.954500792509)); -#75702 = CARTESIAN_POINT('',(-1.701205294602E-015,0.984847218355)); -#75703 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#75704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75705 = ORIENTED_EDGE('',*,*,#75706,.F.); -#75706 = EDGE_CURVE('',#75707,#75622,#75709,.T.); -#75707 = VERTEX_POINT('',#75708); -#75708 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 +#78071 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#78072 = CARTESIAN_POINT('',(-1.144439603192E-015,1.515278164504E-002)); +#78073 = CARTESIAN_POINT('',(-9.175368395657E-016,4.549920749135E-002)); +#78074 = CARTESIAN_POINT('',(1.372925320255E-016,9.109101074357E-002)); +#78075 = CARTESIAN_POINT('',(5.6159890698E-016,0.136698748187)); +#78076 = CARTESIAN_POINT('',(-1.545422737611E-015,0.1822865144)); +#78077 = CARTESIAN_POINT('',(-1.348585819112E-015,0.2278300409)); +#78078 = CARTESIAN_POINT('',(3.786426572017E-016,0.27331674602)); +#78079 = CARTESIAN_POINT('',(-3.253009613166E-016,0.318743220066)); +#78080 = CARTESIAN_POINT('',(-7.297245182018E-016,0.364113426255)); +#78081 = CARTESIAN_POINT('',(1.988956429665E-015,0.409436881051)); +#78082 = CARTESIAN_POINT('',(-6.120609827186E-016,0.454727066523)); +#78083 = CARTESIAN_POINT('',(-1.685236759928E-015,0.5)); +#78084 = CARTESIAN_POINT('',(1.855627463945E-015,0.545272933477)); +#78085 = CARTESIAN_POINT('',(-2.167943843688E-015,0.590563118949)); +#78086 = CARTESIAN_POINT('',(2.303008870842E-016,0.635886573745)); +#78087 = CARTESIAN_POINT('',(-3.217601376884E-017,0.681256779934)); +#78088 = CARTESIAN_POINT('',(5.276053820311E-016,0.72668325398)); +#78089 = CARTESIAN_POINT('',(-1.216399179866E-015,0.7721699591)); +#78090 = CARTESIAN_POINT('',(4.872508256886E-016,0.8177134856)); +#78091 = CARTESIAN_POINT('',(-1.155567275167E-015,0.863301251813)); +#78092 = CARTESIAN_POINT('',(6.923566871284E-016,0.908908989256)); +#78093 = CARTESIAN_POINT('',(-1.695305503108E-015,0.954500792509)); +#78094 = CARTESIAN_POINT('',(-1.701205294602E-015,0.984847218355)); +#78095 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#78096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78097 = ORIENTED_EDGE('',*,*,#78098,.F.); +#78098 = EDGE_CURVE('',#78099,#78014,#78101,.T.); +#78099 = VERTEX_POINT('',#78100); +#78100 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 )); -#75709 = SURFACE_CURVE('',#75710,(#75715,#75744),.PCURVE_S1.); -#75710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75711,#75712,#75713,#75714 +#78101 = SURFACE_CURVE('',#78102,(#78107,#78136),.PCURVE_S1.); +#78102 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78103,#78104,#78105,#78106 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75711 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 +#78103 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457,0.137059047745 )); -#75712 = CARTESIAN_POINT('',(1.230010423697,-0.525122936235, +#78104 = CARTESIAN_POINT('',(1.230010423697,-0.525122936235, 0.133952453327)); -#75713 = CARTESIAN_POINT('',(1.265581001793,-0.510038843607,0.132282534) - ); -#75714 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#75715 = PCURVE('',#75562,#75716); -#75716 = DEFINITIONAL_REPRESENTATION('',(#75717),#75743); -#75717 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75718,#75719,#75720,#75721, - #75722,#75723,#75724,#75725,#75726,#75727,#75728,#75729,#75730, - #75731,#75732,#75733,#75734,#75735,#75736,#75737,#75738,#75739, - #75740,#75741,#75742),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78105 = CARTESIAN_POINT('',(1.265581001793,-0.510038843607,0.132282534) + ); +#78106 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#78107 = PCURVE('',#77954,#78108); +#78108 = DEFINITIONAL_REPRESENTATION('',(#78109),#78135); +#78109 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78110,#78111,#78112,#78113, + #78114,#78115,#78116,#78117,#78118,#78119,#78120,#78121,#78122, + #78123,#78124,#78125,#78126,#78127,#78128,#78129,#78130,#78131, + #78132,#78133,#78134),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -93387,47 +96376,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#75718 = CARTESIAN_POINT('',(5.531305892885,1.)); -#75719 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); -#75720 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); -#75721 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); -#75722 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); -#75723 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); -#75724 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); -#75725 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); -#75726 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#75727 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#75728 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#75729 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#75730 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#75731 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#75732 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#75733 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#75734 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#75735 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#75736 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#75737 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#75738 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#75739 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#75740 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#75741 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#75742 = CARTESIAN_POINT('',(6.28318530718,1.)); -#75743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75744 = PCURVE('',#75745,#75750); -#75745 = CYLINDRICAL_SURFACE('',#75746,0.15); -#75746 = AXIS2_PLACEMENT_3D('',#75747,#75748,#75749); -#75747 = CARTESIAN_POINT('',(1.140884875554,-0.330884875554, +#78110 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78111 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); +#78112 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); +#78113 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); +#78114 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); +#78115 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); +#78116 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); +#78117 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); +#78118 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#78119 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#78120 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#78121 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#78122 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#78123 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#78124 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#78125 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#78126 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#78127 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#78128 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#78129 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#78130 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#78131 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#78132 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#78133 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#78134 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78136 = PCURVE('',#78137,#78142); +#78137 = CYLINDRICAL_SURFACE('',#78138,0.15); +#78138 = AXIS2_PLACEMENT_3D('',#78139,#78140,#78141); +#78139 = CARTESIAN_POINT('',(1.140884875554,-0.330884875554, -1.13983621231E-002)); -#75748 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#75749 = DIRECTION('',(0.965925826289,5.263462734238E-017, +#78140 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#78141 = DIRECTION('',(0.965925826289,5.263462734238E-017, -0.258819045103)); -#75750 = DEFINITIONAL_REPRESENTATION('',(#75751),#75777); -#75751 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75752,#75753,#75754,#75755, - #75756,#75757,#75758,#75759,#75760,#75761,#75762,#75763,#75764, - #75765,#75766,#75767,#75768,#75769,#75770,#75771,#75772,#75773, - #75774,#75775,#75776),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78142 = DEFINITIONAL_REPRESENTATION('',(#78143),#78169); +#78143 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78144,#78145,#78146,#78147, + #78148,#78149,#78150,#78151,#78152,#78153,#78154,#78155,#78156, + #78157,#78158,#78159,#78160,#78161,#78162,#78163,#78164,#78165, + #78166,#78167,#78168),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -93435,48 +96424,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#75752 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); -#75753 = CARTESIAN_POINT('',(4.790552085824,0.200563476544)); -#75754 = CARTESIAN_POINT('',(4.812874135705,0.201130925764)); -#75755 = CARTESIAN_POINT('',(4.846552114392,0.201954800758)); -#75756 = CARTESIAN_POINT('',(4.880407630888,0.202749452758)); -#75757 = CARTESIAN_POINT('',(4.914422492066,0.203513040252)); -#75758 = CARTESIAN_POINT('',(4.948578027862,0.204243791819)); -#75759 = CARTESIAN_POINT('',(4.98285506838,0.204940025039)); -#75760 = CARTESIAN_POINT('',(5.017234026195,0.205600156427)); -#75761 = CARTESIAN_POINT('',(5.051694955172,0.206222712991)); -#75762 = CARTESIAN_POINT('',(5.086217619636,0.206806342405)); -#75763 = CARTESIAN_POINT('',(5.120781564146,0.207349822399)); -#75764 = CARTESIAN_POINT('',(5.155366185737,0.207852069041)); -#75765 = CARTESIAN_POINT('',(5.189950807328,0.208312143851)); -#75766 = CARTESIAN_POINT('',(5.224514751839,0.208729259627)); -#75767 = CARTESIAN_POINT('',(5.259037416303,0.209102784922)); -#75768 = CARTESIAN_POINT('',(5.293498345279,0.209432247104)); -#75769 = CARTESIAN_POINT('',(5.327877303094,0.209717334008)); -#75770 = CARTESIAN_POINT('',(5.362154343612,0.209957894032)); -#75771 = CARTESIAN_POINT('',(5.396309879408,0.210153935227)); -#75772 = CARTESIAN_POINT('',(5.430324740587,0.210305621442)); -#75773 = CARTESIAN_POINT('',(5.464180257082,0.21041327299)); -#75774 = CARTESIAN_POINT('',(5.49785823577,0.210477344272)); -#75775 = CARTESIAN_POINT('',(5.52018028565,0.210491435842)); -#75776 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); -#75777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75778 = ORIENTED_EDGE('',*,*,#75779,.T.); -#75779 = EDGE_CURVE('',#75707,#75553,#75780,.T.); -#75780 = SURFACE_CURVE('',#75781,(#75786,#75815),.PCURVE_S1.); -#75781 = CIRCLE('',#75782,5.E-002); -#75782 = AXIS2_PLACEMENT_3D('',#75783,#75784,#75785); -#75783 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,0.15)); -#75784 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); -#75785 = DIRECTION('',(-4.336808689942E-015,3.735199373413E-045,-1.)); -#75786 = PCURVE('',#75562,#75787); -#75787 = DEFINITIONAL_REPRESENTATION('',(#75788),#75814); -#75788 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75789,#75790,#75791,#75792, - #75793,#75794,#75795,#75796,#75797,#75798,#75799,#75800,#75801, - #75802,#75803,#75804,#75805,#75806,#75807,#75808,#75809,#75810, - #75811,#75812,#75813),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78144 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); +#78145 = CARTESIAN_POINT('',(4.790552085824,0.200563476544)); +#78146 = CARTESIAN_POINT('',(4.812874135705,0.201130925764)); +#78147 = CARTESIAN_POINT('',(4.846552114392,0.201954800758)); +#78148 = CARTESIAN_POINT('',(4.880407630888,0.202749452758)); +#78149 = CARTESIAN_POINT('',(4.914422492066,0.203513040252)); +#78150 = CARTESIAN_POINT('',(4.948578027862,0.204243791819)); +#78151 = CARTESIAN_POINT('',(4.98285506838,0.204940025039)); +#78152 = CARTESIAN_POINT('',(5.017234026195,0.205600156427)); +#78153 = CARTESIAN_POINT('',(5.051694955172,0.206222712991)); +#78154 = CARTESIAN_POINT('',(5.086217619636,0.206806342405)); +#78155 = CARTESIAN_POINT('',(5.120781564146,0.207349822399)); +#78156 = CARTESIAN_POINT('',(5.155366185737,0.207852069041)); +#78157 = CARTESIAN_POINT('',(5.189950807328,0.208312143851)); +#78158 = CARTESIAN_POINT('',(5.224514751839,0.208729259627)); +#78159 = CARTESIAN_POINT('',(5.259037416303,0.209102784922)); +#78160 = CARTESIAN_POINT('',(5.293498345279,0.209432247104)); +#78161 = CARTESIAN_POINT('',(5.327877303094,0.209717334008)); +#78162 = CARTESIAN_POINT('',(5.362154343612,0.209957894032)); +#78163 = CARTESIAN_POINT('',(5.396309879408,0.210153935227)); +#78164 = CARTESIAN_POINT('',(5.430324740587,0.210305621442)); +#78165 = CARTESIAN_POINT('',(5.464180257082,0.21041327299)); +#78166 = CARTESIAN_POINT('',(5.49785823577,0.210477344272)); +#78167 = CARTESIAN_POINT('',(5.52018028565,0.210491435842)); +#78168 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); +#78169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78170 = ORIENTED_EDGE('',*,*,#78171,.T.); +#78171 = EDGE_CURVE('',#78099,#77945,#78172,.T.); +#78172 = SURFACE_CURVE('',#78173,(#78178,#78207),.PCURVE_S1.); +#78173 = CIRCLE('',#78174,5.E-002); +#78174 = AXIS2_PLACEMENT_3D('',#78175,#78176,#78177); +#78175 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,0.15)); +#78176 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); +#78177 = DIRECTION('',(-4.336808689942E-015,3.735199373413E-045,-1.)); +#78178 = PCURVE('',#77954,#78179); +#78179 = DEFINITIONAL_REPRESENTATION('',(#78180),#78206); +#78180 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78181,#78182,#78183,#78184, + #78185,#78186,#78187,#78188,#78189,#78190,#78191,#78192,#78193, + #78194,#78195,#78196,#78197,#78198,#78199,#78200,#78201,#78202, + #78203,#78204,#78205),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -93484,104 +96473,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#75789 = CARTESIAN_POINT('',(5.531305892885,1.)); -#75790 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#75791 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#75792 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#75793 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#75794 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#75795 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#75796 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#75797 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#75798 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#75799 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#75800 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#75801 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#75802 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#75803 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#75804 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#75805 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#75806 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#75807 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#75808 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#75809 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#75810 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#75811 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#75812 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#75813 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#75814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75815 = PCURVE('',#75816,#75821); -#75816 = CYLINDRICAL_SURFACE('',#75817,5.E-002); -#75817 = AXIS2_PLACEMENT_3D('',#75818,#75819,#75820); -#75818 = CARTESIAN_POINT('',(-1.46,-0.477659054385,0.15)); -#75819 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#75820 = DIRECTION('',(0.E+000,0.E+000,1.)); -#75821 = DEFINITIONAL_REPRESENTATION('',(#75822),#75825); -#75822 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#75823,#75824),.UNSPECIFIED., +#78181 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78182 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#78183 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#78184 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#78185 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#78186 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#78187 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#78188 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#78189 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#78190 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#78191 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#78192 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#78193 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#78194 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#78195 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#78196 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#78197 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#78198 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#78199 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#78200 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#78201 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#78202 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#78203 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#78204 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#78205 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78207 = PCURVE('',#78208,#78213); +#78208 = CYLINDRICAL_SURFACE('',#78209,5.E-002); +#78209 = AXIS2_PLACEMENT_3D('',#78210,#78211,#78212); +#78210 = CARTESIAN_POINT('',(-1.46,-0.477659054385,0.15)); +#78211 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#78212 = DIRECTION('',(0.E+000,0.E+000,1.)); +#78213 = DEFINITIONAL_REPRESENTATION('',(#78214),#78217); +#78214 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78215,#78216),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#75823 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); -#75824 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); -#75825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75826 = ADVANCED_FACE('',(#75827),#75842,.T.); -#75827 = FACE_BOUND('',#75828,.T.); -#75828 = EDGE_LOOP('',(#75829,#75895,#75980,#76053)); -#75829 = ORIENTED_EDGE('',*,*,#75830,.F.); -#75830 = EDGE_CURVE('',#75831,#75833,#75835,.T.); -#75831 = VERTEX_POINT('',#75832); -#75832 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#75833 = VERTEX_POINT('',#75834); -#75834 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#75835 = SURFACE_CURVE('',#75836,(#75841,#75887),.PCURVE_S1.); -#75836 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75837,#75838,#75839,#75840 +#78215 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); +#78216 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); +#78217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78218 = ADVANCED_FACE('',(#78219),#78234,.T.); +#78219 = FACE_BOUND('',#78220,.T.); +#78220 = EDGE_LOOP('',(#78221,#78287,#78372,#78445)); +#78221 = ORIENTED_EDGE('',*,*,#78222,.F.); +#78222 = EDGE_CURVE('',#78223,#78225,#78227,.T.); +#78223 = VERTEX_POINT('',#78224); +#78224 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#78225 = VERTEX_POINT('',#78226); +#78226 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#78227 = SURFACE_CURVE('',#78228,(#78233,#78279),.PCURVE_S1.); +#78228 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78229,#78230,#78231,#78232 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75837 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#75838 = CARTESIAN_POINT('',(-1.27790129499,-0.431596067115,1.E-001)); -#75839 = CARTESIAN_POINT('',(-1.287659054385,-0.407584046027,1.E-001)); -#75840 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#75841 = PCURVE('',#75842,#75859); -#75842 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#75843,#75844,#75845,#75846) - ,(#75847,#75848,#75849,#75850) - ,(#75851,#75852,#75853,#75854) - ,(#75855,#75856,#75857,#75858 +#78229 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#78230 = CARTESIAN_POINT('',(-1.27790129499,-0.431596067115,1.E-001)); +#78231 = CARTESIAN_POINT('',(-1.287659054385,-0.407584046027,1.E-001)); +#78232 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#78233 = PCURVE('',#78234,#78251); +#78234 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78235,#78236,#78237,#78238) + ,(#78239,#78240,#78241,#78242) + ,(#78243,#78244,#78245,#78246) + ,(#78247,#78248,#78249,#78250 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#75843 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#75844 = CARTESIAN_POINT('',(-1.309475670035,-0.381066471757,1.E-001)); -#75845 = CARTESIAN_POINT('',(-1.33030879007,-0.381066471757, +#78235 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#78236 = CARTESIAN_POINT('',(-1.309475670035,-0.381066471757,1.E-001)); +#78237 = CARTESIAN_POINT('',(-1.33030879007,-0.381066471757, 0.115985815246)); -#75846 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#78238 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#75847 = CARTESIAN_POINT('',(-1.287659054385,-0.40695495248,1.E-001)); -#75848 = CARTESIAN_POINT('',(-1.308429042165,-0.412435083194,1.E-001)); -#75849 = CARTESIAN_POINT('',(-1.328443665671,-0.417668168966, +#78239 = CARTESIAN_POINT('',(-1.287659054385,-0.40695495248,1.E-001)); +#78240 = CARTESIAN_POINT('',(-1.308429042165,-0.412435083194,1.E-001)); +#78241 = CARTESIAN_POINT('',(-1.328443665671,-0.417668168966, 0.114318476015)); -#75850 = CARTESIAN_POINT('',(-1.335142684022,-0.419086531164, +#78242 = CARTESIAN_POINT('',(-1.335142684022,-0.419086531164, 0.134026153074)); -#75851 = CARTESIAN_POINT('',(-1.277470648802,-0.432026713303,1.E-001)); -#75852 = CARTESIAN_POINT('',(-1.295531311073,-0.442452511959,1.E-001)); -#75853 = CARTESIAN_POINT('',(-1.31299309093,-0.452532596412, +#78243 = CARTESIAN_POINT('',(-1.277470648802,-0.432026713303,1.E-001)); +#78244 = CARTESIAN_POINT('',(-1.295531311073,-0.442452511959,1.E-001)); +#78245 = CARTESIAN_POINT('',(-1.31299309093,-0.452532596412, 0.113446578632)); -#75854 = CARTESIAN_POINT('',(-1.319392874324,-0.456226971076,0.132282534 +#78246 = CARTESIAN_POINT('',(-1.319392874324,-0.456226971076,0.132282534 )); -#75855 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#75856 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); -#75857 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, +#78247 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#78248 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); +#78249 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, 0.113446578632)); -#75858 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#75859 = DEFINITIONAL_REPRESENTATION('',(#75860),#75886); -#75860 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75861,#75862,#75863,#75864, - #75865,#75866,#75867,#75868,#75869,#75870,#75871,#75872,#75873, - #75874,#75875,#75876,#75877,#75878,#75879,#75880,#75881,#75882, - #75883,#75884,#75885),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78250 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#78251 = DEFINITIONAL_REPRESENTATION('',(#78252),#78278); +#78252 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78253,#78254,#78255,#78256, + #78257,#78258,#78259,#78260,#78261,#78262,#78263,#78264,#78265, + #78266,#78267,#78268,#78269,#78270,#78271,#78272,#78273,#78274, + #78275,#78276,#78277),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -93589,64 +96578,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#75861 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#75862 = CARTESIAN_POINT('',(6.272059569215,1.375318524705E-008)); -#75863 = CARTESIAN_POINT('',(6.24973263213,2.924134010322E-005)); -#75864 = CARTESIAN_POINT('',(6.21603939964,1.413707577683E-004)); -#75865 = CARTESIAN_POINT('',(6.182167276026,3.02285926994E-004)); -#75866 = CARTESIAN_POINT('',(6.148138870073,4.931498468587E-004)); -#75867 = CARTESIAN_POINT('',(6.113975913115,6.962198987668E-004)); -#75868 = CARTESIAN_POINT('',(6.079699188623,8.953387637366E-004)); -#75869 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); -#75870 = CARTESIAN_POINT('',(6.010883543172,1.227390254484E-003)); -#75871 = CARTESIAN_POINT('',(5.976382533559,1.339263477876E-003)); -#75872 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); -#75873 = CARTESIAN_POINT('',(5.907285653264,1.422641316502E-003)); -#75874 = CARTESIAN_POINT('',(5.87272580864,1.390009812359E-003)); -#75875 = CARTESIAN_POINT('',(5.838182469936,1.309904867194E-003)); -#75876 = CARTESIAN_POINT('',(5.803674042174,1.187353930373E-003)); -#75877 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); -#75878 = CARTESIAN_POINT('',(5.734837892756,8.475624467463E-004)); -#75879 = CARTESIAN_POINT('',(5.700549707253,6.520952931822E-004)); -#75880 = CARTESIAN_POINT('',(5.666375694827,4.570658043163E-004)); -#75881 = CARTESIAN_POINT('',(5.632337541793,2.772530388765E-004)); -#75882 = CARTESIAN_POINT('',(5.598457782919,1.282673134888E-004)); -#75883 = CARTESIAN_POINT('',(5.564759695218,2.616756247326E-005)); -#75884 = CARTESIAN_POINT('',(5.542431609433,-2.901324085024E-008)); -#75885 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#75886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75887 = PCURVE('',#75608,#75888); -#75888 = DEFINITIONAL_REPRESENTATION('',(#75889),#75894); -#75889 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75890,#75891,#75892,#75893 +#78253 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78254 = CARTESIAN_POINT('',(6.272059569215,1.375318524705E-008)); +#78255 = CARTESIAN_POINT('',(6.24973263213,2.924134010322E-005)); +#78256 = CARTESIAN_POINT('',(6.21603939964,1.413707577683E-004)); +#78257 = CARTESIAN_POINT('',(6.182167276026,3.02285926994E-004)); +#78258 = CARTESIAN_POINT('',(6.148138870073,4.931498468587E-004)); +#78259 = CARTESIAN_POINT('',(6.113975913115,6.962198987668E-004)); +#78260 = CARTESIAN_POINT('',(6.079699188623,8.953387637366E-004)); +#78261 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); +#78262 = CARTESIAN_POINT('',(6.010883543172,1.227390254484E-003)); +#78263 = CARTESIAN_POINT('',(5.976382533559,1.339263477876E-003)); +#78264 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); +#78265 = CARTESIAN_POINT('',(5.907285653264,1.422641316502E-003)); +#78266 = CARTESIAN_POINT('',(5.87272580864,1.390009812359E-003)); +#78267 = CARTESIAN_POINT('',(5.838182469936,1.309904867194E-003)); +#78268 = CARTESIAN_POINT('',(5.803674042174,1.187353930373E-003)); +#78269 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); +#78270 = CARTESIAN_POINT('',(5.734837892756,8.475624467463E-004)); +#78271 = CARTESIAN_POINT('',(5.700549707253,6.520952931822E-004)); +#78272 = CARTESIAN_POINT('',(5.666375694827,4.570658043163E-004)); +#78273 = CARTESIAN_POINT('',(5.632337541793,2.772530388765E-004)); +#78274 = CARTESIAN_POINT('',(5.598457782919,1.282673134888E-004)); +#78275 = CARTESIAN_POINT('',(5.564759695218,2.616756247326E-005)); +#78276 = CARTESIAN_POINT('',(5.542431609433,-2.901324085024E-008)); +#78277 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78279 = PCURVE('',#78000,#78280); +#78280 = DEFINITIONAL_REPRESENTATION('',(#78281),#78286); +#78281 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78282,#78283,#78284,#78285 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75890 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); -#75891 = CARTESIAN_POINT('',(-2.73790129499,0.218403932885)); -#75892 = CARTESIAN_POINT('',(-2.747659054385,0.242415953973)); -#75893 = CARTESIAN_POINT('',(-2.747659054385,0.268933528243)); -#75894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75895 = ORIENTED_EDGE('',*,*,#75896,.T.); -#75896 = EDGE_CURVE('',#75831,#75897,#75899,.T.); -#75897 = VERTEX_POINT('',#75898); -#75898 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#75899 = SURFACE_CURVE('',#75900,(#75905,#75934),.PCURVE_S1.); -#75900 = CIRCLE('',#75901,5.E-002); -#75901 = AXIS2_PLACEMENT_3D('',#75902,#75903,#75904); -#75902 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,0.15)); -#75903 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#75904 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#75905 = PCURVE('',#75842,#75906); -#75906 = DEFINITIONAL_REPRESENTATION('',(#75907),#75933); -#75907 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75908,#75909,#75910,#75911, - #75912,#75913,#75914,#75915,#75916,#75917,#75918,#75919,#75920, - #75921,#75922,#75923,#75924,#75925,#75926,#75927,#75928,#75929, - #75930,#75931,#75932),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78282 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); +#78283 = CARTESIAN_POINT('',(-2.73790129499,0.218403932885)); +#78284 = CARTESIAN_POINT('',(-2.747659054385,0.242415953973)); +#78285 = CARTESIAN_POINT('',(-2.747659054385,0.268933528243)); +#78286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78287 = ORIENTED_EDGE('',*,*,#78288,.T.); +#78288 = EDGE_CURVE('',#78223,#78289,#78291,.T.); +#78289 = VERTEX_POINT('',#78290); +#78290 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#78291 = SURFACE_CURVE('',#78292,(#78297,#78326),.PCURVE_S1.); +#78292 = CIRCLE('',#78293,5.E-002); +#78293 = AXIS2_PLACEMENT_3D('',#78294,#78295,#78296); +#78294 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,0.15)); +#78295 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#78296 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#78297 = PCURVE('',#78234,#78298); +#78298 = DEFINITIONAL_REPRESENTATION('',(#78299),#78325); +#78299 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78300,#78301,#78302,#78303, + #78304,#78305,#78306,#78307,#78308,#78309,#78310,#78311,#78312, + #78313,#78314,#78315,#78316,#78317,#78318,#78319,#78320,#78321, + #78322,#78323,#78324),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -93654,70 +96643,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#75908 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#75909 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#75910 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#75911 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#75912 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#75913 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#75914 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#75915 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#75916 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#75917 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#75918 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#75919 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#75920 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#75921 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#75922 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#75923 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#75924 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#75925 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#75926 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#75927 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#75928 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#75929 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#75930 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#75931 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#75932 = CARTESIAN_POINT('',(6.28318530718,1.)); -#75933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75934 = PCURVE('',#75935,#75952); -#75935 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#75936,#75937,#75938,#75939) - ,(#75940,#75941,#75942,#75943) - ,(#75944,#75945,#75946,#75947) - ,(#75948,#75949,#75950,#75951 +#78300 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78301 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#78302 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#78303 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#78304 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#78305 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#78306 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#78307 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#78308 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#78309 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#78310 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#78311 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#78312 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#78313 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#78314 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#78315 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#78316 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#78317 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#78318 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#78319 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#78320 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#78321 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#78322 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#78323 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#78324 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78326 = PCURVE('',#78327,#78344); +#78327 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78328,#78329,#78330,#78331) + ,(#78332,#78333,#78334,#78335) + ,(#78336,#78337,#78338,#78339) + ,(#78340,#78341,#78342,#78343 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#75936 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#75937 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); -#75938 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, +#78328 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#78329 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); +#78330 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, 0.113446578632)); -#75939 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#75940 = CARTESIAN_POINT('',(-1.242026713303,-0.467470648802,1.E-001)); -#75941 = CARTESIAN_POINT('',(-1.252452511959,-0.485531311073,1.E-001)); -#75942 = CARTESIAN_POINT('',(-1.262532596412,-0.50299309093, +#78331 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#78332 = CARTESIAN_POINT('',(-1.242026713303,-0.467470648802,1.E-001)); +#78333 = CARTESIAN_POINT('',(-1.252452511959,-0.485531311073,1.E-001)); +#78334 = CARTESIAN_POINT('',(-1.262532596412,-0.50299309093, 0.113446578632)); -#75943 = CARTESIAN_POINT('',(-1.266226971076,-0.509392874324,0.132282534 +#78335 = CARTESIAN_POINT('',(-1.266226971076,-0.509392874324,0.132282534 )); -#75944 = CARTESIAN_POINT('',(-1.21695495248,-0.477659054385,1.E-001)); -#75945 = CARTESIAN_POINT('',(-1.222435083194,-0.498429042165,1.E-001)); -#75946 = CARTESIAN_POINT('',(-1.227668168966,-0.518443665671, +#78336 = CARTESIAN_POINT('',(-1.21695495248,-0.477659054385,1.E-001)); +#78337 = CARTESIAN_POINT('',(-1.222435083194,-0.498429042165,1.E-001)); +#78338 = CARTESIAN_POINT('',(-1.227668168966,-0.518443665671, 0.114318476015)); -#75947 = CARTESIAN_POINT('',(-1.229086531164,-0.525142684022, +#78339 = CARTESIAN_POINT('',(-1.229086531164,-0.525142684022, 0.134026153074)); -#75948 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#75949 = CARTESIAN_POINT('',(-1.191066471757,-0.499475670035,1.E-001)); -#75950 = CARTESIAN_POINT('',(-1.191066471757,-0.52030879007, +#78340 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#78341 = CARTESIAN_POINT('',(-1.191066471757,-0.499475670035,1.E-001)); +#78342 = CARTESIAN_POINT('',(-1.191066471757,-0.52030879007, 0.115985815246)); -#75951 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#78343 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#75952 = DEFINITIONAL_REPRESENTATION('',(#75953),#75979); -#75953 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75954,#75955,#75956,#75957, - #75958,#75959,#75960,#75961,#75962,#75963,#75964,#75965,#75966, - #75967,#75968,#75969,#75970,#75971,#75972,#75973,#75974,#75975, - #75976,#75977,#75978),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78344 = DEFINITIONAL_REPRESENTATION('',(#78345),#78371); +#78345 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78346,#78347,#78348,#78349, + #78350,#78351,#78352,#78353,#78354,#78355,#78356,#78357,#78358, + #78359,#78360,#78361,#78362,#78363,#78364,#78365,#78366,#78367, + #78368,#78369,#78370),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -93725,58 +96714,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#75954 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#75955 = CARTESIAN_POINT('',(1.249334129403E-015,1.515278164503E-002)); -#75956 = CARTESIAN_POINT('',(1.92028783152E-015,4.549920749134E-002)); -#75957 = CARTESIAN_POINT('',(1.277950380648E-015,9.109101074356E-002)); -#75958 = CARTESIAN_POINT('',(-4.452410912024E-016,0.136698748187)); -#75959 = CARTESIAN_POINT('',(1.63616653244E-015,0.1822865144)); -#75960 = CARTESIAN_POINT('',(1.217038436523E-016,0.2278300409)); -#75961 = CARTESIAN_POINT('',(9.520556691239E-016,0.27331674602)); -#75962 = CARTESIAN_POINT('',(-1.993255720205E-015,0.318743220066)); -#75963 = CARTESIAN_POINT('',(1.941660140614E-015,0.364113426255)); -#75964 = CARTESIAN_POINT('',(-2.507252454051E-015,0.409436881051)); -#75965 = CARTESIAN_POINT('',(9.244817616574E-016,0.454727066523)); -#75966 = CARTESIAN_POINT('',(-2.178843416601E-015,0.5)); -#75967 = CARTESIAN_POINT('',(-1.460413071254E-015,0.545272933477)); -#75968 = CARTESIAN_POINT('',(-2.368640258981E-015,0.590563118949)); -#75969 = CARTESIAN_POINT('',(1.200342950948E-015,0.635886573745)); -#75970 = CARTESIAN_POINT('',(-2.891058446001E-015,0.681256779934)); -#75971 = CARTESIAN_POINT('',(-1.089100273504E-015,0.72668325398)); -#75972 = CARTESIAN_POINT('',(-1.35470191066E-016,0.7721699591)); -#75973 = CARTESIAN_POINT('',(-1.653663396122E-015,0.8177134856)); -#75974 = CARTESIAN_POINT('',(-2.183887769705E-015,0.863301251813)); -#75975 = CARTESIAN_POINT('',(-9.551908994562E-016,0.908908989256)); -#75976 = CARTESIAN_POINT('',(-1.359363333985E-015,0.954500792509)); -#75977 = CARTESIAN_POINT('',(-5.557512487972E-016,0.984847218355)); -#75978 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#75979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#75980 = ORIENTED_EDGE('',*,*,#75981,.F.); -#75981 = EDGE_CURVE('',#75982,#75897,#75984,.T.); -#75982 = VERTEX_POINT('',#75983); -#75983 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#78346 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#78347 = CARTESIAN_POINT('',(1.249334129403E-015,1.515278164503E-002)); +#78348 = CARTESIAN_POINT('',(1.92028783152E-015,4.549920749134E-002)); +#78349 = CARTESIAN_POINT('',(1.277950380648E-015,9.109101074356E-002)); +#78350 = CARTESIAN_POINT('',(-4.452410912024E-016,0.136698748187)); +#78351 = CARTESIAN_POINT('',(1.63616653244E-015,0.1822865144)); +#78352 = CARTESIAN_POINT('',(1.217038436523E-016,0.2278300409)); +#78353 = CARTESIAN_POINT('',(9.520556691239E-016,0.27331674602)); +#78354 = CARTESIAN_POINT('',(-1.993255720205E-015,0.318743220066)); +#78355 = CARTESIAN_POINT('',(1.941660140614E-015,0.364113426255)); +#78356 = CARTESIAN_POINT('',(-2.507252454051E-015,0.409436881051)); +#78357 = CARTESIAN_POINT('',(9.244817616574E-016,0.454727066523)); +#78358 = CARTESIAN_POINT('',(-2.178843416601E-015,0.5)); +#78359 = CARTESIAN_POINT('',(-1.460413071254E-015,0.545272933477)); +#78360 = CARTESIAN_POINT('',(-2.368640258981E-015,0.590563118949)); +#78361 = CARTESIAN_POINT('',(1.200342950948E-015,0.635886573745)); +#78362 = CARTESIAN_POINT('',(-2.891058446001E-015,0.681256779934)); +#78363 = CARTESIAN_POINT('',(-1.089100273504E-015,0.72668325398)); +#78364 = CARTESIAN_POINT('',(-1.35470191066E-016,0.7721699591)); +#78365 = CARTESIAN_POINT('',(-1.653663396122E-015,0.8177134856)); +#78366 = CARTESIAN_POINT('',(-2.183887769705E-015,0.863301251813)); +#78367 = CARTESIAN_POINT('',(-9.551908994562E-016,0.908908989256)); +#78368 = CARTESIAN_POINT('',(-1.359363333985E-015,0.954500792509)); +#78369 = CARTESIAN_POINT('',(-5.557512487972E-016,0.984847218355)); +#78370 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#78371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78372 = ORIENTED_EDGE('',*,*,#78373,.F.); +#78373 = EDGE_CURVE('',#78374,#78289,#78376,.T.); +#78374 = VERTEX_POINT('',#78375); +#78375 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#75984 = SURFACE_CURVE('',#75985,(#75990,#76019),.PCURVE_S1.); -#75985 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#75986,#75987,#75988,#75989 +#78376 = SURFACE_CURVE('',#78377,(#78382,#78411),.PCURVE_S1.); +#78377 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78378,#78379,#78380,#78381 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#75986 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#78378 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#75987 = CARTESIAN_POINT('',(-1.335122936235,-0.420010423697, +#78379 = CARTESIAN_POINT('',(-1.335122936235,-0.420010423697, 0.133952453327)); -#75988 = CARTESIAN_POINT('',(-1.320038843607,-0.455581001793,0.132282534 +#78380 = CARTESIAN_POINT('',(-1.320038843607,-0.455581001793,0.132282534 )); -#75989 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#75990 = PCURVE('',#75842,#75991); -#75991 = DEFINITIONAL_REPRESENTATION('',(#75992),#76018); -#75992 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#75993,#75994,#75995,#75996, - #75997,#75998,#75999,#76000,#76001,#76002,#76003,#76004,#76005, - #76006,#76007,#76008,#76009,#76010,#76011,#76012,#76013,#76014, - #76015,#76016,#76017),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78381 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#78382 = PCURVE('',#78234,#78383); +#78383 = DEFINITIONAL_REPRESENTATION('',(#78384),#78410); +#78384 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78385,#78386,#78387,#78388, + #78389,#78390,#78391,#78392,#78393,#78394,#78395,#78396,#78397, + #78398,#78399,#78400,#78401,#78402,#78403,#78404,#78405,#78406, + #78407,#78408,#78409),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -93784,47 +96773,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#75993 = CARTESIAN_POINT('',(5.531305892885,1.)); -#75994 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#75995 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#75996 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#75997 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#75998 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#75999 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#76000 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#76001 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#76002 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#76003 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#76004 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#76005 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#76006 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#76007 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#76008 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#76009 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#76010 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#76011 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#76012 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#76013 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#76014 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#76015 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#76016 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#76017 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76019 = PCURVE('',#76020,#76025); -#76020 = CYLINDRICAL_SURFACE('',#76021,0.15); -#76021 = AXIS2_PLACEMENT_3D('',#76022,#76023,#76024); -#76022 = CARTESIAN_POINT('',(-1.242591262431,-0.432591262431, +#78385 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78386 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#78387 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#78388 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#78389 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#78390 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#78391 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#78392 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#78393 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#78394 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#78395 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#78396 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#78397 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#78398 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#78399 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#78400 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#78401 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#78402 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#78403 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#78404 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#78405 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#78406 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#78407 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#78408 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#78409 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78411 = PCURVE('',#78412,#78417); +#78412 = CYLINDRICAL_SURFACE('',#78413,0.15); +#78413 = AXIS2_PLACEMENT_3D('',#78414,#78415,#78416); +#78414 = CARTESIAN_POINT('',(-1.242591262431,-0.432591262431, 0.368175041158)); -#76023 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); -#76024 = DIRECTION('',(0.965925826289,4.24499031846E-017,0.258819045103) - ); -#76025 = DEFINITIONAL_REPRESENTATION('',(#76026),#76052); -#76026 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76027,#76028,#76029,#76030, - #76031,#76032,#76033,#76034,#76035,#76036,#76037,#76038,#76039, - #76040,#76041,#76042,#76043,#76044,#76045,#76046,#76047,#76048, - #76049,#76050,#76051),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78415 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); +#78416 = DIRECTION('',(0.965925826289,4.24499031846E-017,0.258819045103) + ); +#78417 = DEFINITIONAL_REPRESENTATION('',(#78418),#78444); +#78418 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78419,#78420,#78421,#78422, + #78423,#78424,#78425,#78426,#78427,#78428,#78429,#78430,#78431, + #78432,#78433,#78434,#78435,#78436,#78437,#78438,#78439,#78440, + #78441,#78442,#78443),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -93832,48 +96821,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76027 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); -#76028 = CARTESIAN_POINT('',(3.152718260825,-0.205348270935)); -#76029 = CARTESIAN_POINT('',(3.175040310705,-0.204780821715)); -#76030 = CARTESIAN_POINT('',(3.208718289392,-0.203956946721)); -#76031 = CARTESIAN_POINT('',(3.242573805888,-0.203162294721)); -#76032 = CARTESIAN_POINT('',(3.276588667066,-0.202398707226)); -#76033 = CARTESIAN_POINT('',(3.310744202863,-0.20166795566)); -#76034 = CARTESIAN_POINT('',(3.34502124338,-0.20097172244)); -#76035 = CARTESIAN_POINT('',(3.379400201195,-0.200311591052)); -#76036 = CARTESIAN_POINT('',(3.413861130172,-0.199689034488)); -#76037 = CARTESIAN_POINT('',(3.448383794636,-0.199105405074)); -#76038 = CARTESIAN_POINT('',(3.482947739147,-0.19856192508)); -#76039 = CARTESIAN_POINT('',(3.517532360737,-0.198059678438)); -#76040 = CARTESIAN_POINT('',(3.552116982328,-0.197599603628)); -#76041 = CARTESIAN_POINT('',(3.586680926839,-0.197182487852)); -#76042 = CARTESIAN_POINT('',(3.621203591303,-0.196808962557)); -#76043 = CARTESIAN_POINT('',(3.65566452028,-0.196479500374)); -#76044 = CARTESIAN_POINT('',(3.690043478095,-0.196194413471)); -#76045 = CARTESIAN_POINT('',(3.724320518612,-0.195953853447)); -#76046 = CARTESIAN_POINT('',(3.758476054408,-0.195757812252)); -#76047 = CARTESIAN_POINT('',(3.792490915587,-0.195606126036)); -#76048 = CARTESIAN_POINT('',(3.826346432082,-0.195498474489)); -#76049 = CARTESIAN_POINT('',(3.86002441077,-0.195434403207)); -#76050 = CARTESIAN_POINT('',(3.88234646065,-0.195420311637)); -#76051 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); -#76052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76053 = ORIENTED_EDGE('',*,*,#76054,.T.); -#76054 = EDGE_CURVE('',#75982,#75833,#76055,.T.); -#76055 = SURFACE_CURVE('',#76056,(#76061,#76090),.PCURVE_S1.); -#76056 = CIRCLE('',#76057,5.E-002); -#76057 = AXIS2_PLACEMENT_3D('',#76058,#76059,#76060); -#76058 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,0.15)); -#76059 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#76060 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#76061 = PCURVE('',#75842,#76062); -#76062 = DEFINITIONAL_REPRESENTATION('',(#76063),#76089); -#76063 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76064,#76065,#76066,#76067, - #76068,#76069,#76070,#76071,#76072,#76073,#76074,#76075,#76076, - #76077,#76078,#76079,#76080,#76081,#76082,#76083,#76084,#76085, - #76086,#76087,#76088),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78419 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); +#78420 = CARTESIAN_POINT('',(3.152718260825,-0.205348270935)); +#78421 = CARTESIAN_POINT('',(3.175040310705,-0.204780821715)); +#78422 = CARTESIAN_POINT('',(3.208718289392,-0.203956946721)); +#78423 = CARTESIAN_POINT('',(3.242573805888,-0.203162294721)); +#78424 = CARTESIAN_POINT('',(3.276588667066,-0.202398707226)); +#78425 = CARTESIAN_POINT('',(3.310744202863,-0.20166795566)); +#78426 = CARTESIAN_POINT('',(3.34502124338,-0.20097172244)); +#78427 = CARTESIAN_POINT('',(3.379400201195,-0.200311591052)); +#78428 = CARTESIAN_POINT('',(3.413861130172,-0.199689034488)); +#78429 = CARTESIAN_POINT('',(3.448383794636,-0.199105405074)); +#78430 = CARTESIAN_POINT('',(3.482947739147,-0.19856192508)); +#78431 = CARTESIAN_POINT('',(3.517532360737,-0.198059678438)); +#78432 = CARTESIAN_POINT('',(3.552116982328,-0.197599603628)); +#78433 = CARTESIAN_POINT('',(3.586680926839,-0.197182487852)); +#78434 = CARTESIAN_POINT('',(3.621203591303,-0.196808962557)); +#78435 = CARTESIAN_POINT('',(3.65566452028,-0.196479500374)); +#78436 = CARTESIAN_POINT('',(3.690043478095,-0.196194413471)); +#78437 = CARTESIAN_POINT('',(3.724320518612,-0.195953853447)); +#78438 = CARTESIAN_POINT('',(3.758476054408,-0.195757812252)); +#78439 = CARTESIAN_POINT('',(3.792490915587,-0.195606126036)); +#78440 = CARTESIAN_POINT('',(3.826346432082,-0.195498474489)); +#78441 = CARTESIAN_POINT('',(3.86002441077,-0.195434403207)); +#78442 = CARTESIAN_POINT('',(3.88234646065,-0.195420311637)); +#78443 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); +#78444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78445 = ORIENTED_EDGE('',*,*,#78446,.T.); +#78446 = EDGE_CURVE('',#78374,#78225,#78447,.T.); +#78447 = SURFACE_CURVE('',#78448,(#78453,#78482),.PCURVE_S1.); +#78448 = CIRCLE('',#78449,5.E-002); +#78449 = AXIS2_PLACEMENT_3D('',#78450,#78451,#78452); +#78450 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,0.15)); +#78451 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#78452 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#78453 = PCURVE('',#78234,#78454); +#78454 = DEFINITIONAL_REPRESENTATION('',(#78455),#78481); +#78455 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78456,#78457,#78458,#78459, + #78460,#78461,#78462,#78463,#78464,#78465,#78466,#78467,#78468, + #78469,#78470,#78471,#78472,#78473,#78474,#78475,#78476,#78477, + #78478,#78479,#78480),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -93881,104 +96870,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76064 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76065 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#76066 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#76067 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#76068 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#76069 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#76070 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#76071 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#76072 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#76073 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#76074 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#76075 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#76076 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#76077 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#76078 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#76079 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#76080 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#76081 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#76082 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#76083 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#76084 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#76085 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#76086 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#76087 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#76088 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76090 = PCURVE('',#76091,#76096); -#76091 = CYLINDRICAL_SURFACE('',#76092,5.E-002); -#76092 = AXIS2_PLACEMENT_3D('',#76093,#76094,#76095); -#76093 = CARTESIAN_POINT('',(-1.287659054385,0.65,0.15)); -#76094 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#76095 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); -#76096 = DEFINITIONAL_REPRESENTATION('',(#76097),#76100); -#76097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76098,#76099),.UNSPECIFIED., +#78456 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78457 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#78458 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#78459 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#78460 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#78461 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#78462 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#78463 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#78464 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#78465 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#78466 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#78467 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#78468 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#78469 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#78470 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#78471 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#78472 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#78473 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#78474 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#78475 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#78476 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#78477 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#78478 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#78479 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#78480 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78482 = PCURVE('',#78483,#78488); +#78483 = CYLINDRICAL_SURFACE('',#78484,5.E-002); +#78484 = AXIS2_PLACEMENT_3D('',#78485,#78486,#78487); +#78485 = CARTESIAN_POINT('',(-1.287659054385,0.65,0.15)); +#78486 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#78487 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); +#78488 = DEFINITIONAL_REPRESENTATION('',(#78489),#78492); +#78489 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78490,#78491),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#76098 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); -#76099 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); -#76100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76101 = ADVANCED_FACE('',(#76102),#76117,.T.); -#76102 = FACE_BOUND('',#76103,.T.); -#76103 = EDGE_LOOP('',(#76104,#76170,#76255,#76328)); -#76104 = ORIENTED_EDGE('',*,*,#76105,.F.); -#76105 = EDGE_CURVE('',#76106,#76108,#76110,.T.); -#76106 = VERTEX_POINT('',#76107); -#76107 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#76108 = VERTEX_POINT('',#76109); -#76109 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#76110 = SURFACE_CURVE('',#76111,(#76116,#76162),.PCURVE_S1.); -#76111 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76112,#76113,#76114,#76115 +#78490 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); +#78491 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); +#78492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78493 = ADVANCED_FACE('',(#78494),#78509,.T.); +#78494 = FACE_BOUND('',#78495,.T.); +#78495 = EDGE_LOOP('',(#78496,#78562,#78647,#78720)); +#78496 = ORIENTED_EDGE('',*,*,#78497,.F.); +#78497 = EDGE_CURVE('',#78498,#78500,#78502,.T.); +#78498 = VERTEX_POINT('',#78499); +#78499 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#78500 = VERTEX_POINT('',#78501); +#78501 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#78502 = SURFACE_CURVE('',#78503,(#78508,#78554),.PCURVE_S1.); +#78503 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78504,#78505,#78506,#78507 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76112 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#76113 = CARTESIAN_POINT('',(1.27790129499,0.431596067115,1.E-001)); -#76114 = CARTESIAN_POINT('',(1.287659054385,0.407584046027,1.E-001)); -#76115 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#76116 = PCURVE('',#76117,#76134); -#76117 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76118,#76119,#76120,#76121) - ,(#76122,#76123,#76124,#76125) - ,(#76126,#76127,#76128,#76129) - ,(#76130,#76131,#76132,#76133 +#78504 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#78505 = CARTESIAN_POINT('',(1.27790129499,0.431596067115,1.E-001)); +#78506 = CARTESIAN_POINT('',(1.287659054385,0.407584046027,1.E-001)); +#78507 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#78508 = PCURVE('',#78509,#78526); +#78509 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78510,#78511,#78512,#78513) + ,(#78514,#78515,#78516,#78517) + ,(#78518,#78519,#78520,#78521) + ,(#78522,#78523,#78524,#78525 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76118 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#76119 = CARTESIAN_POINT('',(1.309475670035,0.381066471757,1.E-001)); -#76120 = CARTESIAN_POINT('',(1.33030879007,0.381066471757,0.115985815246 +#78510 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#78511 = CARTESIAN_POINT('',(1.309475670035,0.381066471757,1.E-001)); +#78512 = CARTESIAN_POINT('',(1.33030879007,0.381066471757,0.115985815246 )); -#76121 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) +#78513 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) ); -#76122 = CARTESIAN_POINT('',(1.287659054385,0.40695495248,1.E-001)); -#76123 = CARTESIAN_POINT('',(1.308429042165,0.412435083194,1.E-001)); -#76124 = CARTESIAN_POINT('',(1.328443665671,0.417668168966, +#78514 = CARTESIAN_POINT('',(1.287659054385,0.40695495248,1.E-001)); +#78515 = CARTESIAN_POINT('',(1.308429042165,0.412435083194,1.E-001)); +#78516 = CARTESIAN_POINT('',(1.328443665671,0.417668168966, 0.114318476015)); -#76125 = CARTESIAN_POINT('',(1.335142684022,0.419086531164, +#78517 = CARTESIAN_POINT('',(1.335142684022,0.419086531164, 0.134026153074)); -#76126 = CARTESIAN_POINT('',(1.277470648802,0.432026713303,1.E-001)); -#76127 = CARTESIAN_POINT('',(1.295531311073,0.442452511959,1.E-001)); -#76128 = CARTESIAN_POINT('',(1.31299309093,0.452532596412,0.113446578632 +#78518 = CARTESIAN_POINT('',(1.277470648802,0.432026713303,1.E-001)); +#78519 = CARTESIAN_POINT('',(1.295531311073,0.442452511959,1.E-001)); +#78520 = CARTESIAN_POINT('',(1.31299309093,0.452532596412,0.113446578632 )); -#76129 = CARTESIAN_POINT('',(1.319392874324,0.456226971076,0.132282534) +#78521 = CARTESIAN_POINT('',(1.319392874324,0.456226971076,0.132282534) ); -#76130 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#76131 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); -#76132 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, +#78522 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#78523 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); +#78524 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, 0.113446578632)); -#76133 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#76134 = DEFINITIONAL_REPRESENTATION('',(#76135),#76161); -#76135 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76136,#76137,#76138,#76139, - #76140,#76141,#76142,#76143,#76144,#76145,#76146,#76147,#76148, - #76149,#76150,#76151,#76152,#76153,#76154,#76155,#76156,#76157, - #76158,#76159,#76160),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78525 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#78526 = DEFINITIONAL_REPRESENTATION('',(#78527),#78553); +#78527 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78528,#78529,#78530,#78531, + #78532,#78533,#78534,#78535,#78536,#78537,#78538,#78539,#78540, + #78541,#78542,#78543,#78544,#78545,#78546,#78547,#78548,#78549, + #78550,#78551,#78552),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -93986,64 +96975,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#76136 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76137 = CARTESIAN_POINT('',(6.272059569215,1.375318315925E-008)); -#76138 = CARTESIAN_POINT('',(6.24973263213,2.92413401008E-005)); -#76139 = CARTESIAN_POINT('',(6.21603939964,1.413707577698E-004)); -#76140 = CARTESIAN_POINT('',(6.182167276026,3.022859269977E-004)); -#76141 = CARTESIAN_POINT('',(6.148138870073,4.931498468535E-004)); -#76142 = CARTESIAN_POINT('',(6.113975913115,6.962198987843E-004)); -#76143 = CARTESIAN_POINT('',(6.079699188623,8.953387637273E-004)); -#76144 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); -#76145 = CARTESIAN_POINT('',(6.010883543172,1.22739025449E-003)); -#76146 = CARTESIAN_POINT('',(5.976382533559,1.339263477879E-003)); -#76147 = CARTESIAN_POINT('',(5.941843890817,1.405524714334E-003)); -#76148 = CARTESIAN_POINT('',(5.907285653264,1.422641316504E-003)); -#76149 = CARTESIAN_POINT('',(5.87272580864,1.390009812369E-003)); -#76150 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); -#76151 = CARTESIAN_POINT('',(5.803674042174,1.187353930383E-003)); -#76152 = CARTESIAN_POINT('',(5.769219374506,1.029943289557E-003)); -#76153 = CARTESIAN_POINT('',(5.734837892756,8.475624467446E-004)); -#76154 = CARTESIAN_POINT('',(5.700549707253,6.520952931874E-004)); -#76155 = CARTESIAN_POINT('',(5.666375694827,4.57065804322E-004)); -#76156 = CARTESIAN_POINT('',(5.632337541793,2.772530388735E-004)); -#76157 = CARTESIAN_POINT('',(5.598457782919,1.282673135018E-004)); -#76158 = CARTESIAN_POINT('',(5.564759695218,2.616756247318E-005)); -#76159 = CARTESIAN_POINT('',(5.542431609433,-2.901324327884E-008)); -#76160 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76162 = PCURVE('',#75608,#76163); -#76163 = DEFINITIONAL_REPRESENTATION('',(#76164),#76169); -#76164 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76165,#76166,#76167,#76168 +#78528 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78529 = CARTESIAN_POINT('',(6.272059569215,1.375318315925E-008)); +#78530 = CARTESIAN_POINT('',(6.24973263213,2.92413401008E-005)); +#78531 = CARTESIAN_POINT('',(6.21603939964,1.413707577698E-004)); +#78532 = CARTESIAN_POINT('',(6.182167276026,3.022859269977E-004)); +#78533 = CARTESIAN_POINT('',(6.148138870073,4.931498468535E-004)); +#78534 = CARTESIAN_POINT('',(6.113975913115,6.962198987843E-004)); +#78535 = CARTESIAN_POINT('',(6.079699188623,8.953387637273E-004)); +#78536 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); +#78537 = CARTESIAN_POINT('',(6.010883543172,1.22739025449E-003)); +#78538 = CARTESIAN_POINT('',(5.976382533559,1.339263477879E-003)); +#78539 = CARTESIAN_POINT('',(5.941843890817,1.405524714334E-003)); +#78540 = CARTESIAN_POINT('',(5.907285653264,1.422641316504E-003)); +#78541 = CARTESIAN_POINT('',(5.87272580864,1.390009812369E-003)); +#78542 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); +#78543 = CARTESIAN_POINT('',(5.803674042174,1.187353930383E-003)); +#78544 = CARTESIAN_POINT('',(5.769219374506,1.029943289557E-003)); +#78545 = CARTESIAN_POINT('',(5.734837892756,8.475624467446E-004)); +#78546 = CARTESIAN_POINT('',(5.700549707253,6.520952931874E-004)); +#78547 = CARTESIAN_POINT('',(5.666375694827,4.57065804322E-004)); +#78548 = CARTESIAN_POINT('',(5.632337541793,2.772530388735E-004)); +#78549 = CARTESIAN_POINT('',(5.598457782919,1.282673135018E-004)); +#78550 = CARTESIAN_POINT('',(5.564759695218,2.616756247318E-005)); +#78551 = CARTESIAN_POINT('',(5.542431609433,-2.901324327884E-008)); +#78552 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78554 = PCURVE('',#78000,#78555); +#78555 = DEFINITIONAL_REPRESENTATION('',(#78556),#78561); +#78556 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78557,#78558,#78559,#78560 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76165 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); -#76166 = CARTESIAN_POINT('',(-0.18209870501,1.081596067115)); -#76167 = CARTESIAN_POINT('',(-0.172340945615,1.057584046027)); -#76168 = CARTESIAN_POINT('',(-0.172340945615,1.031066471757)); -#76169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76170 = ORIENTED_EDGE('',*,*,#76171,.T.); -#76171 = EDGE_CURVE('',#76106,#76172,#76174,.T.); -#76172 = VERTEX_POINT('',#76173); -#76173 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#76174 = SURFACE_CURVE('',#76175,(#76180,#76209),.PCURVE_S1.); -#76175 = CIRCLE('',#76176,5.E-002); -#76176 = AXIS2_PLACEMENT_3D('',#76177,#76178,#76179); -#76177 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,0.15)); -#76178 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#76179 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#76180 = PCURVE('',#76117,#76181); -#76181 = DEFINITIONAL_REPRESENTATION('',(#76182),#76208); -#76182 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76183,#76184,#76185,#76186, - #76187,#76188,#76189,#76190,#76191,#76192,#76193,#76194,#76195, - #76196,#76197,#76198,#76199,#76200,#76201,#76202,#76203,#76204, - #76205,#76206,#76207),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78557 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); +#78558 = CARTESIAN_POINT('',(-0.18209870501,1.081596067115)); +#78559 = CARTESIAN_POINT('',(-0.172340945615,1.057584046027)); +#78560 = CARTESIAN_POINT('',(-0.172340945615,1.031066471757)); +#78561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78562 = ORIENTED_EDGE('',*,*,#78563,.T.); +#78563 = EDGE_CURVE('',#78498,#78564,#78566,.T.); +#78564 = VERTEX_POINT('',#78565); +#78565 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#78566 = SURFACE_CURVE('',#78567,(#78572,#78601),.PCURVE_S1.); +#78567 = CIRCLE('',#78568,5.E-002); +#78568 = AXIS2_PLACEMENT_3D('',#78569,#78570,#78571); +#78569 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,0.15)); +#78570 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#78571 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#78572 = PCURVE('',#78509,#78573); +#78573 = DEFINITIONAL_REPRESENTATION('',(#78574),#78600); +#78574 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78575,#78576,#78577,#78578, + #78579,#78580,#78581,#78582,#78583,#78584,#78585,#78586,#78587, + #78588,#78589,#78590,#78591,#78592,#78593,#78594,#78595,#78596, + #78597,#78598,#78599),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -94051,70 +97040,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#76183 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76184 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#76185 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#76186 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#76187 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#76188 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#76189 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#76190 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#76191 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#76192 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#76193 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#76194 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#76195 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#76196 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#76197 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#76198 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#76199 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#76200 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#76201 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#76202 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#76203 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#76204 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#76205 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#76206 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#76207 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76209 = PCURVE('',#76210,#76227); -#76210 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76211,#76212,#76213,#76214) - ,(#76215,#76216,#76217,#76218) - ,(#76219,#76220,#76221,#76222) - ,(#76223,#76224,#76225,#76226 +#78575 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78576 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#78577 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#78578 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#78579 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#78580 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#78581 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#78582 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#78583 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#78584 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#78585 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#78586 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#78587 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#78588 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#78589 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#78590 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#78591 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#78592 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#78593 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#78594 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#78595 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#78596 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#78597 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#78598 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#78599 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78601 = PCURVE('',#78602,#78619); +#78602 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78603,#78604,#78605,#78606) + ,(#78607,#78608,#78609,#78610) + ,(#78611,#78612,#78613,#78614) + ,(#78615,#78616,#78617,#78618 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76211 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#76212 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); -#76213 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, +#78603 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#78604 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); +#78605 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, 0.113446578632)); -#76214 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#76215 = CARTESIAN_POINT('',(1.242026713303,0.467470648802,1.E-001)); -#76216 = CARTESIAN_POINT('',(1.252452511959,0.485531311073,1.E-001)); -#76217 = CARTESIAN_POINT('',(1.262532596412,0.50299309093,0.113446578632 +#78606 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#78607 = CARTESIAN_POINT('',(1.242026713303,0.467470648802,1.E-001)); +#78608 = CARTESIAN_POINT('',(1.252452511959,0.485531311073,1.E-001)); +#78609 = CARTESIAN_POINT('',(1.262532596412,0.50299309093,0.113446578632 )); -#76218 = CARTESIAN_POINT('',(1.266226971076,0.509392874324,0.132282534) +#78610 = CARTESIAN_POINT('',(1.266226971076,0.509392874324,0.132282534) ); -#76219 = CARTESIAN_POINT('',(1.21695495248,0.477659054385,1.E-001)); -#76220 = CARTESIAN_POINT('',(1.222435083194,0.498429042165,1.E-001)); -#76221 = CARTESIAN_POINT('',(1.227668168966,0.518443665671, +#78611 = CARTESIAN_POINT('',(1.21695495248,0.477659054385,1.E-001)); +#78612 = CARTESIAN_POINT('',(1.222435083194,0.498429042165,1.E-001)); +#78613 = CARTESIAN_POINT('',(1.227668168966,0.518443665671, 0.114318476015)); -#76222 = CARTESIAN_POINT('',(1.229086531164,0.525142684022, +#78614 = CARTESIAN_POINT('',(1.229086531164,0.525142684022, 0.134026153074)); -#76223 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#76224 = CARTESIAN_POINT('',(1.191066471757,0.499475670035,1.E-001)); -#76225 = CARTESIAN_POINT('',(1.191066471757,0.52030879007,0.115985815246 +#78615 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#78616 = CARTESIAN_POINT('',(1.191066471757,0.499475670035,1.E-001)); +#78617 = CARTESIAN_POINT('',(1.191066471757,0.52030879007,0.115985815246 )); -#76226 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) +#78618 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) ); -#76227 = DEFINITIONAL_REPRESENTATION('',(#76228),#76254); -#76228 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76229,#76230,#76231,#76232, - #76233,#76234,#76235,#76236,#76237,#76238,#76239,#76240,#76241, - #76242,#76243,#76244,#76245,#76246,#76247,#76248,#76249,#76250, - #76251,#76252,#76253),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78619 = DEFINITIONAL_REPRESENTATION('',(#78620),#78646); +#78620 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78621,#78622,#78623,#78624, + #78625,#78626,#78627,#78628,#78629,#78630,#78631,#78632,#78633, + #78634,#78635,#78636,#78637,#78638,#78639,#78640,#78641,#78642, + #78643,#78644,#78645),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -94122,58 +97111,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#76229 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#76230 = CARTESIAN_POINT('',(2.91033471756E-015,1.515278164503E-002)); -#76231 = CARTESIAN_POINT('',(4.632036949666E-015,4.549920749134E-002)); -#76232 = CARTESIAN_POINT('',(2.193829578482E-015,9.109101074356E-002)); -#76233 = CARTESIAN_POINT('',(1.17318239543E-015,0.136698748187)); -#76234 = CARTESIAN_POINT('',(3.825709488835E-015,0.1822865144)); -#76235 = CARTESIAN_POINT('',(3.007585829836E-015,0.2278300409)); -#76236 = CARTESIAN_POINT('',(2.081705218533E-015,0.27331674602)); -#76237 = CARTESIAN_POINT('',(-9.978985593511E-016,0.318743220066)); -#76238 = CARTESIAN_POINT('',(6.847313983409E-016,0.364113426255)); -#76239 = CARTESIAN_POINT('',(-1.12737588722E-015,0.409436881051)); -#76240 = CARTESIAN_POINT('',(6.035053617114E-016,0.454727066523)); -#76241 = CARTESIAN_POINT('',(8.32511851254E-016,0.5)); -#76242 = CARTESIAN_POINT('',(-1.205030190221E-016,0.545272933477)); -#76243 = CARTESIAN_POINT('',(-1.833983566176E-016,0.590563118949)); -#76244 = CARTESIAN_POINT('',(8.47972121338E-016,0.635886573745)); -#76245 = CARTESIAN_POINT('',(-1.687035406625E-015,0.681256779934)); -#76246 = CARTESIAN_POINT('',(4.840019940136E-016,0.72668325398)); -#76247 = CARTESIAN_POINT('',(-9.263151972584E-016,0.7721699591)); -#76248 = CARTESIAN_POINT('',(6.893490225787E-016,0.8177134856)); -#76249 = CARTESIAN_POINT('',(2.97210397481E-016,0.863301251813)); -#76250 = CARTESIAN_POINT('',(8.03868702767E-017,0.908908989256)); -#76251 = CARTESIAN_POINT('',(-4.245535665613E-016,0.954500792509)); -#76252 = CARTESIAN_POINT('',(-1.098819920641E-016,0.984847218355)); -#76253 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#76254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76255 = ORIENTED_EDGE('',*,*,#76256,.F.); -#76256 = EDGE_CURVE('',#76257,#76172,#76259,.T.); -#76257 = VERTEX_POINT('',#76258); -#76258 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) - ); -#76259 = SURFACE_CURVE('',#76260,(#76265,#76294),.PCURVE_S1.); -#76260 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76261,#76262,#76263,#76264 +#78621 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#78622 = CARTESIAN_POINT('',(2.91033471756E-015,1.515278164503E-002)); +#78623 = CARTESIAN_POINT('',(4.632036949666E-015,4.549920749134E-002)); +#78624 = CARTESIAN_POINT('',(2.193829578482E-015,9.109101074356E-002)); +#78625 = CARTESIAN_POINT('',(1.17318239543E-015,0.136698748187)); +#78626 = CARTESIAN_POINT('',(3.825709488835E-015,0.1822865144)); +#78627 = CARTESIAN_POINT('',(3.007585829836E-015,0.2278300409)); +#78628 = CARTESIAN_POINT('',(2.081705218533E-015,0.27331674602)); +#78629 = CARTESIAN_POINT('',(-9.978985593511E-016,0.318743220066)); +#78630 = CARTESIAN_POINT('',(6.847313983409E-016,0.364113426255)); +#78631 = CARTESIAN_POINT('',(-1.12737588722E-015,0.409436881051)); +#78632 = CARTESIAN_POINT('',(6.035053617114E-016,0.454727066523)); +#78633 = CARTESIAN_POINT('',(8.32511851254E-016,0.5)); +#78634 = CARTESIAN_POINT('',(-1.205030190221E-016,0.545272933477)); +#78635 = CARTESIAN_POINT('',(-1.833983566176E-016,0.590563118949)); +#78636 = CARTESIAN_POINT('',(8.47972121338E-016,0.635886573745)); +#78637 = CARTESIAN_POINT('',(-1.687035406625E-015,0.681256779934)); +#78638 = CARTESIAN_POINT('',(4.840019940136E-016,0.72668325398)); +#78639 = CARTESIAN_POINT('',(-9.263151972584E-016,0.7721699591)); +#78640 = CARTESIAN_POINT('',(6.893490225787E-016,0.8177134856)); +#78641 = CARTESIAN_POINT('',(2.97210397481E-016,0.863301251813)); +#78642 = CARTESIAN_POINT('',(8.03868702767E-017,0.908908989256)); +#78643 = CARTESIAN_POINT('',(-4.245535665613E-016,0.954500792509)); +#78644 = CARTESIAN_POINT('',(-1.098819920641E-016,0.984847218355)); +#78645 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#78646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78647 = ORIENTED_EDGE('',*,*,#78648,.F.); +#78648 = EDGE_CURVE('',#78649,#78564,#78651,.T.); +#78649 = VERTEX_POINT('',#78650); +#78650 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) + ); +#78651 = SURFACE_CURVE('',#78652,(#78657,#78686),.PCURVE_S1.); +#78652 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78653,#78654,#78655,#78656 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76261 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) +#78653 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745) ); -#76262 = CARTESIAN_POINT('',(1.335122936235,0.420010423697, +#78654 = CARTESIAN_POINT('',(1.335122936235,0.420010423697, 0.133952453327)); -#76263 = CARTESIAN_POINT('',(1.320038843607,0.455581001793,0.132282534) - ); -#76264 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#76265 = PCURVE('',#76117,#76266); -#76266 = DEFINITIONAL_REPRESENTATION('',(#76267),#76293); -#76267 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76268,#76269,#76270,#76271, - #76272,#76273,#76274,#76275,#76276,#76277,#76278,#76279,#76280, - #76281,#76282,#76283,#76284,#76285,#76286,#76287,#76288,#76289, - #76290,#76291,#76292),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78655 = CARTESIAN_POINT('',(1.320038843607,0.455581001793,0.132282534) + ); +#78656 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#78657 = PCURVE('',#78509,#78658); +#78658 = DEFINITIONAL_REPRESENTATION('',(#78659),#78685); +#78659 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78660,#78661,#78662,#78663, + #78664,#78665,#78666,#78667,#78668,#78669,#78670,#78671,#78672, + #78673,#78674,#78675,#78676,#78677,#78678,#78679,#78680,#78681, + #78682,#78683,#78684),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -94181,47 +97170,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76268 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76269 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#76270 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#76271 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#76272 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#76273 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#76274 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#76275 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#76276 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#76277 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#76278 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#76279 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#76280 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#76281 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#76282 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#76283 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#76284 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#76285 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#76286 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#76287 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#76288 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#76289 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#76290 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#76291 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#76292 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76294 = PCURVE('',#76295,#76300); -#76295 = CYLINDRICAL_SURFACE('',#76296,0.15); -#76296 = AXIS2_PLACEMENT_3D('',#76297,#76298,#76299); -#76297 = CARTESIAN_POINT('',(1.324207498814,0.514207498814, +#78660 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78661 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#78662 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#78663 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#78664 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#78665 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#78666 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#78667 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#78668 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#78669 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#78670 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#78671 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#78672 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#78673 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#78674 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#78675 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#78676 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#78677 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#78678 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#78679 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#78680 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#78681 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#78682 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#78683 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#78684 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78686 = PCURVE('',#78687,#78692); +#78687 = CYLINDRICAL_SURFACE('',#78688,0.15); +#78688 = AXIS2_PLACEMENT_3D('',#78689,#78690,#78691); +#78689 = CARTESIAN_POINT('',(1.324207498814,0.514207498814, 0.672770982062)); -#76298 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#76299 = DIRECTION('',(0.965925826289,-1.331129217269E-016, +#78690 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#78691 = DIRECTION('',(0.965925826289,-1.331129217269E-016, -0.258819045103)); -#76300 = DEFINITIONAL_REPRESENTATION('',(#76301),#76327); -#76301 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76302,#76303,#76304,#76305, - #76306,#76307,#76308,#76309,#76310,#76311,#76312,#76313,#76314, - #76315,#76316,#76317,#76318,#76319,#76320,#76321,#76322,#76323, - #76324,#76325,#76326),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78692 = DEFINITIONAL_REPRESENTATION('',(#78693),#78719); +#78693 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78694,#78695,#78696,#78697, + #78698,#78699,#78700,#78701,#78702,#78703,#78704,#78705,#78706, + #78707,#78708,#78709,#78710,#78711,#78712,#78713,#78714,#78715, + #78716,#78717,#78718),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -94229,48 +97218,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76302 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#76303 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); -#76304 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); -#76305 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); -#76306 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); -#76307 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); -#76308 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); -#76309 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); -#76310 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); -#76311 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); -#76312 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); -#76313 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); -#76314 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); -#76315 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); -#76316 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); -#76317 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); -#76318 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); -#76319 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); -#76320 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); -#76321 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); -#76322 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); -#76323 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); -#76324 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); -#76325 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); -#76326 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#76327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76328 = ORIENTED_EDGE('',*,*,#76329,.F.); -#76329 = EDGE_CURVE('',#76108,#76257,#76330,.T.); -#76330 = SURFACE_CURVE('',#76331,(#76336,#76365),.PCURVE_S1.); -#76331 = CIRCLE('',#76332,5.E-002); -#76332 = AXIS2_PLACEMENT_3D('',#76333,#76334,#76335); -#76333 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,0.15)); -#76334 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#76335 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#76336 = PCURVE('',#76117,#76337); -#76337 = DEFINITIONAL_REPRESENTATION('',(#76338),#76364); -#76338 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76339,#76340,#76341,#76342, - #76343,#76344,#76345,#76346,#76347,#76348,#76349,#76350,#76351, - #76352,#76353,#76354,#76355,#76356,#76357,#76358,#76359,#76360, - #76361,#76362,#76363),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78694 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#78695 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); +#78696 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); +#78697 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); +#78698 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); +#78699 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); +#78700 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); +#78701 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); +#78702 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); +#78703 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); +#78704 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); +#78705 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); +#78706 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); +#78707 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); +#78708 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); +#78709 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); +#78710 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); +#78711 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); +#78712 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); +#78713 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); +#78714 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); +#78715 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); +#78716 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); +#78717 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); +#78718 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#78719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78720 = ORIENTED_EDGE('',*,*,#78721,.F.); +#78721 = EDGE_CURVE('',#78500,#78649,#78722,.T.); +#78722 = SURFACE_CURVE('',#78723,(#78728,#78757),.PCURVE_S1.); +#78723 = CIRCLE('',#78724,5.E-002); +#78724 = AXIS2_PLACEMENT_3D('',#78725,#78726,#78727); +#78725 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,0.15)); +#78726 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#78727 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#78728 = PCURVE('',#78509,#78729); +#78729 = DEFINITIONAL_REPRESENTATION('',(#78730),#78756); +#78730 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78731,#78732,#78733,#78734, + #78735,#78736,#78737,#78738,#78739,#78740,#78741,#78742,#78743, + #78744,#78745,#78746,#78747,#78748,#78749,#78750,#78751,#78752, + #78753,#78754,#78755),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,5.949986086344E-002,0.118999721727, 0.17849958259,0.237999443454,0.297499304317,0.356999165181, 0.416499026044,0.475998886908,0.535498747771,0.594998608634, @@ -94278,103 +97267,103 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.892497912952,0.951997773815,1.011497634679,1.070997495542, 1.130497356405,1.189997217269,1.249497078132,1.308996938996), .QUASI_UNIFORM_KNOTS.); -#76339 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76340 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#76341 = CARTESIAN_POINT('',(5.531305889761,4.551530703749E-002)); -#76342 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#76343 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#76344 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#76345 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#76346 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#76347 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#76348 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#76349 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); -#76350 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#76351 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#76352 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#76353 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#76354 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#76355 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#76356 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#76357 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#76358 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#76359 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#76360 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#76361 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#76362 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#76363 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76365 = PCURVE('',#76366,#76371); -#76366 = CYLINDRICAL_SURFACE('',#76367,5.E-002); -#76367 = AXIS2_PLACEMENT_3D('',#76368,#76369,#76370); -#76368 = CARTESIAN_POINT('',(1.287659054385,0.65,0.15)); -#76369 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#76370 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); -#76371 = DEFINITIONAL_REPRESENTATION('',(#76372),#76375); -#76372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76373,#76374),.UNSPECIFIED., +#78731 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78732 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#78733 = CARTESIAN_POINT('',(5.531305889761,4.551530703749E-002)); +#78734 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#78735 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#78736 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#78737 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#78738 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#78739 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#78740 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#78741 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); +#78742 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#78743 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#78744 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#78745 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#78746 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#78747 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#78748 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#78749 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#78750 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#78751 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#78752 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#78753 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#78754 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#78755 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78757 = PCURVE('',#78758,#78763); +#78758 = CYLINDRICAL_SURFACE('',#78759,5.E-002); +#78759 = AXIS2_PLACEMENT_3D('',#78760,#78761,#78762); +#78760 = CARTESIAN_POINT('',(1.287659054385,0.65,0.15)); +#78761 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#78762 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); +#78763 = DEFINITIONAL_REPRESENTATION('',(#78764),#78767); +#78764 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78765,#78766),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#76373 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#76374 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#76375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76376 = ADVANCED_FACE('',(#76377),#76392,.T.); -#76377 = FACE_BOUND('',#76378,.T.); -#76378 = EDGE_LOOP('',(#76379,#76445,#76530,#76603)); -#76379 = ORIENTED_EDGE('',*,*,#76380,.F.); -#76380 = EDGE_CURVE('',#76381,#76383,#76385,.T.); -#76381 = VERTEX_POINT('',#76382); -#76382 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#76383 = VERTEX_POINT('',#76384); -#76384 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#76385 = SURFACE_CURVE('',#76386,(#76391,#76437),.PCURVE_S1.); -#76386 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76387,#76388,#76389,#76390 +#78765 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#78766 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#78767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78768 = ADVANCED_FACE('',(#78769),#78784,.T.); +#78769 = FACE_BOUND('',#78770,.T.); +#78770 = EDGE_LOOP('',(#78771,#78837,#78922,#78995)); +#78771 = ORIENTED_EDGE('',*,*,#78772,.F.); +#78772 = EDGE_CURVE('',#78773,#78775,#78777,.T.); +#78773 = VERTEX_POINT('',#78774); +#78774 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#78775 = VERTEX_POINT('',#78776); +#78776 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#78777 = SURFACE_CURVE('',#78778,(#78783,#78829),.PCURVE_S1.); +#78778 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78779,#78780,#78781,#78782 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76387 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#76388 = CARTESIAN_POINT('',(-1.241596067115,0.46790129499,1.E-001)); -#76389 = CARTESIAN_POINT('',(-1.217584046027,0.477659054385,1.E-001)); -#76390 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#76391 = PCURVE('',#76392,#76409); -#76392 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76393,#76394,#76395,#76396) - ,(#76397,#76398,#76399,#76400) - ,(#76401,#76402,#76403,#76404) - ,(#76405,#76406,#76407,#76408 +#78779 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#78780 = CARTESIAN_POINT('',(-1.241596067115,0.46790129499,1.E-001)); +#78781 = CARTESIAN_POINT('',(-1.217584046027,0.477659054385,1.E-001)); +#78782 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#78783 = PCURVE('',#78784,#78801); +#78784 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78785,#78786,#78787,#78788) + ,(#78789,#78790,#78791,#78792) + ,(#78793,#78794,#78795,#78796) + ,(#78797,#78798,#78799,#78800 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76393 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#76394 = CARTESIAN_POINT('',(-1.191066471757,0.499475670035,1.E-001)); -#76395 = CARTESIAN_POINT('',(-1.191066471757,0.52030879007, +#78785 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#78786 = CARTESIAN_POINT('',(-1.191066471757,0.499475670035,1.E-001)); +#78787 = CARTESIAN_POINT('',(-1.191066471757,0.52030879007, 0.115985815246)); -#76396 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 +#78788 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 )); -#76397 = CARTESIAN_POINT('',(-1.21695495248,0.477659054385,1.E-001)); -#76398 = CARTESIAN_POINT('',(-1.222435083194,0.498429042165,1.E-001)); -#76399 = CARTESIAN_POINT('',(-1.227668168966,0.518443665671, +#78789 = CARTESIAN_POINT('',(-1.21695495248,0.477659054385,1.E-001)); +#78790 = CARTESIAN_POINT('',(-1.222435083194,0.498429042165,1.E-001)); +#78791 = CARTESIAN_POINT('',(-1.227668168966,0.518443665671, 0.114318476015)); -#76400 = CARTESIAN_POINT('',(-1.229086531164,0.525142684022, +#78792 = CARTESIAN_POINT('',(-1.229086531164,0.525142684022, 0.134026153074)); -#76401 = CARTESIAN_POINT('',(-1.242026713303,0.467470648802,1.E-001)); -#76402 = CARTESIAN_POINT('',(-1.252452511959,0.485531311073,1.E-001)); -#76403 = CARTESIAN_POINT('',(-1.262532596412,0.50299309093, +#78793 = CARTESIAN_POINT('',(-1.242026713303,0.467470648802,1.E-001)); +#78794 = CARTESIAN_POINT('',(-1.252452511959,0.485531311073,1.E-001)); +#78795 = CARTESIAN_POINT('',(-1.262532596412,0.50299309093, 0.113446578632)); -#76404 = CARTESIAN_POINT('',(-1.266226971076,0.509392874324,0.132282534) +#78796 = CARTESIAN_POINT('',(-1.266226971076,0.509392874324,0.132282534) ); -#76405 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#76406 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); -#76407 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, +#78797 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#78798 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); +#78799 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, 0.113446578632)); -#76408 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#76409 = DEFINITIONAL_REPRESENTATION('',(#76410),#76436); -#76410 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76411,#76412,#76413,#76414, - #76415,#76416,#76417,#76418,#76419,#76420,#76421,#76422,#76423, - #76424,#76425,#76426,#76427,#76428,#76429,#76430,#76431,#76432, - #76433,#76434,#76435),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78800 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#78801 = DEFINITIONAL_REPRESENTATION('',(#78802),#78828); +#78802 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78803,#78804,#78805,#78806, + #78807,#78808,#78809,#78810,#78811,#78812,#78813,#78814,#78815, + #78816,#78817,#78818,#78819,#78820,#78821,#78822,#78823,#78824, + #78825,#78826,#78827),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(8.809142651445E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -94382,64 +97371,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#76411 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76412 = CARTESIAN_POINT('',(6.272059569215,1.375318493936E-008)); -#76413 = CARTESIAN_POINT('',(6.24973263213,2.924134010172E-005)); -#76414 = CARTESIAN_POINT('',(6.21603939964,1.413707577648E-004)); -#76415 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); -#76416 = CARTESIAN_POINT('',(6.148138870073,4.931498468595E-004)); -#76417 = CARTESIAN_POINT('',(6.113975913115,6.962198987677E-004)); -#76418 = CARTESIAN_POINT('',(6.079699188623,8.953387637279E-004)); -#76419 = CARTESIAN_POINT('',(6.045328652128,1.076339414005E-003)); -#76420 = CARTESIAN_POINT('',(6.010883543172,1.227390254476E-003)); -#76421 = CARTESIAN_POINT('',(5.976382533559,1.339263477883E-003)); -#76422 = CARTESIAN_POINT('',(5.941843890817,1.405524714321E-003)); -#76423 = CARTESIAN_POINT('',(5.907285653264,1.422641316499E-003)); -#76424 = CARTESIAN_POINT('',(5.87272580864,1.39000981236E-003)); -#76425 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); -#76426 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); -#76427 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); -#76428 = CARTESIAN_POINT('',(5.734837892756,8.475624467432E-004)); -#76429 = CARTESIAN_POINT('',(5.700549707253,6.520952931824E-004)); -#76430 = CARTESIAN_POINT('',(5.666375694827,4.570658043143E-004)); -#76431 = CARTESIAN_POINT('',(5.632337541793,2.772530388753E-004)); -#76432 = CARTESIAN_POINT('',(5.598457782919,1.282673134886E-004)); -#76433 = CARTESIAN_POINT('',(5.564759695218,2.61675624706E-005)); -#76434 = CARTESIAN_POINT('',(5.542431609433,-2.901324262083E-008)); -#76435 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76437 = PCURVE('',#75608,#76438); -#76438 = DEFINITIONAL_REPRESENTATION('',(#76439),#76444); -#76439 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76440,#76441,#76442,#76443 +#78803 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78804 = CARTESIAN_POINT('',(6.272059569215,1.375318493936E-008)); +#78805 = CARTESIAN_POINT('',(6.24973263213,2.924134010172E-005)); +#78806 = CARTESIAN_POINT('',(6.21603939964,1.413707577648E-004)); +#78807 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); +#78808 = CARTESIAN_POINT('',(6.148138870073,4.931498468595E-004)); +#78809 = CARTESIAN_POINT('',(6.113975913115,6.962198987677E-004)); +#78810 = CARTESIAN_POINT('',(6.079699188623,8.953387637279E-004)); +#78811 = CARTESIAN_POINT('',(6.045328652128,1.076339414005E-003)); +#78812 = CARTESIAN_POINT('',(6.010883543172,1.227390254476E-003)); +#78813 = CARTESIAN_POINT('',(5.976382533559,1.339263477883E-003)); +#78814 = CARTESIAN_POINT('',(5.941843890817,1.405524714321E-003)); +#78815 = CARTESIAN_POINT('',(5.907285653264,1.422641316499E-003)); +#78816 = CARTESIAN_POINT('',(5.87272580864,1.39000981236E-003)); +#78817 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); +#78818 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); +#78819 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); +#78820 = CARTESIAN_POINT('',(5.734837892756,8.475624467432E-004)); +#78821 = CARTESIAN_POINT('',(5.700549707253,6.520952931824E-004)); +#78822 = CARTESIAN_POINT('',(5.666375694827,4.570658043143E-004)); +#78823 = CARTESIAN_POINT('',(5.632337541793,2.772530388753E-004)); +#78824 = CARTESIAN_POINT('',(5.598457782919,1.282673134886E-004)); +#78825 = CARTESIAN_POINT('',(5.564759695218,2.61675624706E-005)); +#78826 = CARTESIAN_POINT('',(5.542431609433,-2.901324262083E-008)); +#78827 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#78828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78829 = PCURVE('',#78000,#78830); +#78830 = DEFINITIONAL_REPRESENTATION('',(#78831),#78836); +#78831 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78832,#78833,#78834,#78835 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76440 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); -#76441 = CARTESIAN_POINT('',(-2.701596067115,1.11790129499)); -#76442 = CARTESIAN_POINT('',(-2.677584046027,1.127659054385)); -#76443 = CARTESIAN_POINT('',(-2.651066471757,1.127659054385)); -#76444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76445 = ORIENTED_EDGE('',*,*,#76446,.T.); -#76446 = EDGE_CURVE('',#76381,#76447,#76449,.T.); -#76447 = VERTEX_POINT('',#76448); -#76448 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#76449 = SURFACE_CURVE('',#76450,(#76455,#76484),.PCURVE_S1.); -#76450 = CIRCLE('',#76451,5.E-002); -#76451 = AXIS2_PLACEMENT_3D('',#76452,#76453,#76454); -#76452 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,0.15)); -#76453 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#76454 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#76455 = PCURVE('',#76392,#76456); -#76456 = DEFINITIONAL_REPRESENTATION('',(#76457),#76483); -#76457 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76458,#76459,#76460,#76461, - #76462,#76463,#76464,#76465,#76466,#76467,#76468,#76469,#76470, - #76471,#76472,#76473,#76474,#76475,#76476,#76477,#76478,#76479, - #76480,#76481,#76482),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78832 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); +#78833 = CARTESIAN_POINT('',(-2.701596067115,1.11790129499)); +#78834 = CARTESIAN_POINT('',(-2.677584046027,1.127659054385)); +#78835 = CARTESIAN_POINT('',(-2.651066471757,1.127659054385)); +#78836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78837 = ORIENTED_EDGE('',*,*,#78838,.T.); +#78838 = EDGE_CURVE('',#78773,#78839,#78841,.T.); +#78839 = VERTEX_POINT('',#78840); +#78840 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#78841 = SURFACE_CURVE('',#78842,(#78847,#78876),.PCURVE_S1.); +#78842 = CIRCLE('',#78843,5.E-002); +#78843 = AXIS2_PLACEMENT_3D('',#78844,#78845,#78846); +#78844 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,0.15)); +#78845 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#78846 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#78847 = PCURVE('',#78784,#78848); +#78848 = DEFINITIONAL_REPRESENTATION('',(#78849),#78875); +#78849 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78850,#78851,#78852,#78853, + #78854,#78855,#78856,#78857,#78858,#78859,#78860,#78861,#78862, + #78863,#78864,#78865,#78866,#78867,#78868,#78869,#78870,#78871, + #78872,#78873,#78874),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -94447,70 +97436,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#76458 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76459 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#76460 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#76461 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#76462 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#76463 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#76464 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#76465 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#76466 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#76467 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#76468 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#76469 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#76470 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#76471 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#76472 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#76473 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#76474 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#76475 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#76476 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#76477 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#76478 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#76479 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#76480 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#76481 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#76482 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76484 = PCURVE('',#76485,#76502); -#76485 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76486,#76487,#76488,#76489) - ,(#76490,#76491,#76492,#76493) - ,(#76494,#76495,#76496,#76497) - ,(#76498,#76499,#76500,#76501 +#78850 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#78851 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#78852 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#78853 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#78854 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#78855 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#78856 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#78857 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#78858 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#78859 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#78860 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#78861 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#78862 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#78863 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#78864 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#78865 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#78866 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#78867 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#78868 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#78869 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#78870 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#78871 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#78872 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#78873 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#78874 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78876 = PCURVE('',#78877,#78894); +#78877 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#78878,#78879,#78880,#78881) + ,(#78882,#78883,#78884,#78885) + ,(#78886,#78887,#78888,#78889) + ,(#78890,#78891,#78892,#78893 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76486 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#76487 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); -#76488 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, +#78878 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#78879 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); +#78880 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, 0.113446578632)); -#76489 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#76490 = CARTESIAN_POINT('',(-1.277470648802,0.432026713303,1.E-001)); -#76491 = CARTESIAN_POINT('',(-1.295531311073,0.442452511959,1.E-001)); -#76492 = CARTESIAN_POINT('',(-1.31299309093,0.452532596412, +#78881 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#78882 = CARTESIAN_POINT('',(-1.277470648802,0.432026713303,1.E-001)); +#78883 = CARTESIAN_POINT('',(-1.295531311073,0.442452511959,1.E-001)); +#78884 = CARTESIAN_POINT('',(-1.31299309093,0.452532596412, 0.113446578632)); -#76493 = CARTESIAN_POINT('',(-1.319392874324,0.456226971076,0.132282534) +#78885 = CARTESIAN_POINT('',(-1.319392874324,0.456226971076,0.132282534) ); -#76494 = CARTESIAN_POINT('',(-1.287659054385,0.40695495248,1.E-001)); -#76495 = CARTESIAN_POINT('',(-1.308429042165,0.412435083194,1.E-001)); -#76496 = CARTESIAN_POINT('',(-1.328443665671,0.417668168966, +#78886 = CARTESIAN_POINT('',(-1.287659054385,0.40695495248,1.E-001)); +#78887 = CARTESIAN_POINT('',(-1.308429042165,0.412435083194,1.E-001)); +#78888 = CARTESIAN_POINT('',(-1.328443665671,0.417668168966, 0.114318476015)); -#76497 = CARTESIAN_POINT('',(-1.335142684022,0.419086531164, +#78889 = CARTESIAN_POINT('',(-1.335142684022,0.419086531164, 0.134026153074)); -#76498 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#76499 = CARTESIAN_POINT('',(-1.309475670035,0.381066471757,1.E-001)); -#76500 = CARTESIAN_POINT('',(-1.33030879007,0.381066471757, +#78890 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#78891 = CARTESIAN_POINT('',(-1.309475670035,0.381066471757,1.E-001)); +#78892 = CARTESIAN_POINT('',(-1.33030879007,0.381066471757, 0.115985815246)); -#76501 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 +#78893 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 )); -#76502 = DEFINITIONAL_REPRESENTATION('',(#76503),#76529); -#76503 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76504,#76505,#76506,#76507, - #76508,#76509,#76510,#76511,#76512,#76513,#76514,#76515,#76516, - #76517,#76518,#76519,#76520,#76521,#76522,#76523,#76524,#76525, - #76526,#76527,#76528),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78894 = DEFINITIONAL_REPRESENTATION('',(#78895),#78921); +#78895 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78896,#78897,#78898,#78899, + #78900,#78901,#78902,#78903,#78904,#78905,#78906,#78907,#78908, + #78909,#78910,#78911,#78912,#78913,#78914,#78915,#78916,#78917, + #78918,#78919,#78920),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.767324352275, 4.822259724165,4.877195096055,4.932130467945,4.987065839835, 5.042001211726,5.096936583616,5.151871955506,5.206807327396, @@ -94518,58 +97507,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.481484186847,5.536419558737,5.591354930627,5.646290302517, 5.701225674407,5.756161046297,5.811096418188,5.866031790078, 5.920967161968),.QUASI_UNIFORM_KNOTS.); -#76504 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#76505 = CARTESIAN_POINT('',(-1.46330102167E-015,1.515278164503E-002)); -#76506 = CARTESIAN_POINT('',(-1.464455124249E-015,4.549920749134E-002)); -#76507 = CARTESIAN_POINT('',(-2.215304484765E-016,9.109101074357E-002)); -#76508 = CARTESIAN_POINT('',(1.493819329251E-015,0.136698748187)); -#76509 = CARTESIAN_POINT('',(-2.096990132421E-015,0.1822865144)); -#76510 = CARTESIAN_POINT('',(-1.821258059536E-015,0.2278300409)); -#76511 = CARTESIAN_POINT('',(-1.426172734298E-015,0.27331674602)); -#76512 = CARTESIAN_POINT('',(2.639844373571E-015,0.318743220066)); -#76513 = CARTESIAN_POINT('',(-2.242246185818E-015,0.364113426255)); -#76514 = CARTESIAN_POINT('',(1.933048259393E-015,0.409436881051)); -#76515 = CARTESIAN_POINT('',(-5.27771497447E-016,0.454727066523)); -#76516 = CARTESIAN_POINT('',(1.562527491438E-015,0.5)); -#76517 = CARTESIAN_POINT('',(1.106310870334E-015,0.545272933477)); -#76518 = CARTESIAN_POINT('',(9.420665051041E-016,0.590563118949)); -#76519 = CARTESIAN_POINT('',(-1.359829843782E-015,0.635886573745)); -#76520 = CARTESIAN_POINT('',(2.853349287298E-015,0.681256779934)); -#76521 = CARTESIAN_POINT('',(3.785671830011E-017,0.72668325398)); -#76522 = CARTESIAN_POINT('',(2.100632383276E-015,0.7721699591)); -#76523 = CARTESIAN_POINT('',(-1.017498792288E-016,0.8177134856)); -#76524 = CARTESIAN_POINT('',(1.712000903909E-015,0.863301251813)); -#76525 = CARTESIAN_POINT('',(2.988232549161E-015,0.908908989256)); -#76526 = CARTESIAN_POINT('',(7.917676621896E-016,0.954500792509)); -#76527 = CARTESIAN_POINT('',(-5.466081644211E-016,0.984847218355)); -#76528 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#76529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76530 = ORIENTED_EDGE('',*,*,#76531,.F.); -#76531 = EDGE_CURVE('',#76532,#76447,#76534,.T.); -#76532 = VERTEX_POINT('',#76533); -#76533 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 +#78896 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#78897 = CARTESIAN_POINT('',(-1.46330102167E-015,1.515278164503E-002)); +#78898 = CARTESIAN_POINT('',(-1.464455124249E-015,4.549920749134E-002)); +#78899 = CARTESIAN_POINT('',(-2.215304484765E-016,9.109101074357E-002)); +#78900 = CARTESIAN_POINT('',(1.493819329251E-015,0.136698748187)); +#78901 = CARTESIAN_POINT('',(-2.096990132421E-015,0.1822865144)); +#78902 = CARTESIAN_POINT('',(-1.821258059536E-015,0.2278300409)); +#78903 = CARTESIAN_POINT('',(-1.426172734298E-015,0.27331674602)); +#78904 = CARTESIAN_POINT('',(2.639844373571E-015,0.318743220066)); +#78905 = CARTESIAN_POINT('',(-2.242246185818E-015,0.364113426255)); +#78906 = CARTESIAN_POINT('',(1.933048259393E-015,0.409436881051)); +#78907 = CARTESIAN_POINT('',(-5.27771497447E-016,0.454727066523)); +#78908 = CARTESIAN_POINT('',(1.562527491438E-015,0.5)); +#78909 = CARTESIAN_POINT('',(1.106310870334E-015,0.545272933477)); +#78910 = CARTESIAN_POINT('',(9.420665051041E-016,0.590563118949)); +#78911 = CARTESIAN_POINT('',(-1.359829843782E-015,0.635886573745)); +#78912 = CARTESIAN_POINT('',(2.853349287298E-015,0.681256779934)); +#78913 = CARTESIAN_POINT('',(3.785671830011E-017,0.72668325398)); +#78914 = CARTESIAN_POINT('',(2.100632383276E-015,0.7721699591)); +#78915 = CARTESIAN_POINT('',(-1.017498792288E-016,0.8177134856)); +#78916 = CARTESIAN_POINT('',(1.712000903909E-015,0.863301251813)); +#78917 = CARTESIAN_POINT('',(2.988232549161E-015,0.908908989256)); +#78918 = CARTESIAN_POINT('',(7.917676621896E-016,0.954500792509)); +#78919 = CARTESIAN_POINT('',(-5.466081644211E-016,0.984847218355)); +#78920 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#78921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78922 = ORIENTED_EDGE('',*,*,#78923,.F.); +#78923 = EDGE_CURVE('',#78924,#78839,#78926,.T.); +#78924 = VERTEX_POINT('',#78925); +#78925 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 )); -#76534 = SURFACE_CURVE('',#76535,(#76540,#76569),.PCURVE_S1.); -#76535 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76536,#76537,#76538,#76539 +#78926 = SURFACE_CURVE('',#78927,(#78932,#78961),.PCURVE_S1.); +#78927 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#78928,#78929,#78930,#78931 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76536 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 +#78928 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457,0.137059047745 )); -#76537 = CARTESIAN_POINT('',(-1.230010423697,0.525122936235, +#78929 = CARTESIAN_POINT('',(-1.230010423697,0.525122936235, 0.133952453327)); -#76538 = CARTESIAN_POINT('',(-1.265581001793,0.510038843607,0.132282534) - ); -#76539 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#76540 = PCURVE('',#76392,#76541); -#76541 = DEFINITIONAL_REPRESENTATION('',(#76542),#76568); -#76542 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76543,#76544,#76545,#76546, - #76547,#76548,#76549,#76550,#76551,#76552,#76553,#76554,#76555, - #76556,#76557,#76558,#76559,#76560,#76561,#76562,#76563,#76564, - #76565,#76566,#76567),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78930 = CARTESIAN_POINT('',(-1.265581001793,0.510038843607,0.132282534) + ); +#78931 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#78932 = PCURVE('',#78784,#78933); +#78933 = DEFINITIONAL_REPRESENTATION('',(#78934),#78960); +#78934 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78935,#78936,#78937,#78938, + #78939,#78940,#78941,#78942,#78943,#78944,#78945,#78946,#78947, + #78948,#78949,#78950,#78951,#78952,#78953,#78954,#78955,#78956, + #78957,#78958,#78959),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -94577,47 +97566,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76543 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76544 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); -#76545 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); -#76546 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); -#76547 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); -#76548 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); -#76549 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); -#76550 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); -#76551 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#76552 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#76553 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#76554 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#76555 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#76556 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#76557 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#76558 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#76559 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#76560 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#76561 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#76562 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#76563 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#76564 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#76565 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#76566 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#76567 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76569 = PCURVE('',#76570,#76575); -#76570 = CYLINDRICAL_SURFACE('',#76571,0.15); -#76571 = AXIS2_PLACEMENT_3D('',#76572,#76573,#76574); -#76572 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, +#78935 = CARTESIAN_POINT('',(5.531305892885,1.)); +#78936 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); +#78937 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); +#78938 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); +#78939 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); +#78940 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); +#78941 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); +#78942 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); +#78943 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#78944 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#78945 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#78946 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#78947 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#78948 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#78949 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#78950 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#78951 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#78952 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#78953 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#78954 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#78955 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#78956 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#78957 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#78958 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#78959 = CARTESIAN_POINT('',(6.28318530718,1.)); +#78960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78961 = PCURVE('',#78962,#78967); +#78962 = CYLINDRICAL_SURFACE('',#78963,0.15); +#78963 = AXIS2_PLACEMENT_3D('',#78964,#78965,#78966); +#78964 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, 0.672770982062)); -#76573 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#76574 = DIRECTION('',(0.965925826289,-3.026618127129E-017, +#78965 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#78966 = DIRECTION('',(0.965925826289,-3.026618127129E-017, 0.258819045103)); -#76575 = DEFINITIONAL_REPRESENTATION('',(#76576),#76602); -#76576 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76577,#76578,#76579,#76580, - #76581,#76582,#76583,#76584,#76585,#76586,#76587,#76588,#76589, - #76590,#76591,#76592,#76593,#76594,#76595,#76596,#76597,#76598, - #76599,#76600,#76601),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78967 = DEFINITIONAL_REPRESENTATION('',(#78968),#78994); +#78968 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78969,#78970,#78971,#78972, + #78973,#78974,#78975,#78976,#78977,#78978,#78979,#78980,#78981, + #78982,#78983,#78984,#78985,#78986,#78987,#78988,#78989,#78990, + #78991,#78992,#78993),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -94625,48 +97614,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76577 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#76578 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); -#76579 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); -#76580 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); -#76581 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); -#76582 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); -#76583 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); -#76584 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); -#76585 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); -#76586 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); -#76587 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); -#76588 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); -#76589 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); -#76590 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); -#76591 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); -#76592 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); -#76593 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); -#76594 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); -#76595 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); -#76596 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); -#76597 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); -#76598 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); -#76599 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); -#76600 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); -#76601 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#76602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76603 = ORIENTED_EDGE('',*,*,#76604,.F.); -#76604 = EDGE_CURVE('',#76383,#76532,#76605,.T.); -#76605 = SURFACE_CURVE('',#76606,(#76611,#76640),.PCURVE_S1.); -#76606 = CIRCLE('',#76607,5.E-002); -#76607 = AXIS2_PLACEMENT_3D('',#76608,#76609,#76610); -#76608 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,0.15)); -#76609 = DIRECTION('',(1.,0.E+000,0.E+000)); -#76610 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#76611 = PCURVE('',#76392,#76612); -#76612 = DEFINITIONAL_REPRESENTATION('',(#76613),#76639); -#76613 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76614,#76615,#76616,#76617, - #76618,#76619,#76620,#76621,#76622,#76623,#76624,#76625,#76626, - #76627,#76628,#76629,#76630,#76631,#76632,#76633,#76634,#76635, - #76636,#76637,#76638),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#78969 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#78970 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); +#78971 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); +#78972 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); +#78973 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); +#78974 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); +#78975 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); +#78976 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); +#78977 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); +#78978 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); +#78979 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); +#78980 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); +#78981 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); +#78982 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); +#78983 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); +#78984 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); +#78985 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); +#78986 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); +#78987 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); +#78988 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); +#78989 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); +#78990 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); +#78991 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); +#78992 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); +#78993 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#78994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#78995 = ORIENTED_EDGE('',*,*,#78996,.F.); +#78996 = EDGE_CURVE('',#78775,#78924,#78997,.T.); +#78997 = SURFACE_CURVE('',#78998,(#79003,#79032),.PCURVE_S1.); +#78998 = CIRCLE('',#78999,5.E-002); +#78999 = AXIS2_PLACEMENT_3D('',#79000,#79001,#79002); +#79000 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,0.15)); +#79001 = DIRECTION('',(1.,0.E+000,0.E+000)); +#79002 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#79003 = PCURVE('',#78784,#79004); +#79004 = DEFINITIONAL_REPRESENTATION('',(#79005),#79031); +#79005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79006,#79007,#79008,#79009, + #79010,#79011,#79012,#79013,#79014,#79015,#79016,#79017,#79018, + #79019,#79020,#79021,#79022,#79023,#79024,#79025,#79026,#79027, + #79028,#79029,#79030),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,5.949986086344E-002,0.118999721727, 0.17849958259,0.237999443454,0.297499304317,0.356999165181, 0.416499026044,0.475998886908,0.535498747771,0.594998608634, @@ -94674,110 +97663,110 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.892497912952,0.951997773815,1.011497634679,1.070997495542, 1.130497356405,1.189997217269,1.249497078132,1.308996938996), .QUASI_UNIFORM_KNOTS.); -#76614 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76615 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#76616 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#76617 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#76618 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#76619 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#76620 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#76621 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#76622 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#76623 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#76624 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#76625 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#76626 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#76627 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#76628 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#76629 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#76630 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#76631 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#76632 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#76633 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#76634 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#76635 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#76636 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#76637 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#76638 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76640 = PCURVE('',#76641,#76646); -#76641 = CYLINDRICAL_SURFACE('',#76642,5.E-002); -#76642 = AXIS2_PLACEMENT_3D('',#76643,#76644,#76645); -#76643 = CARTESIAN_POINT('',(-1.46,0.477659054385,0.15)); -#76644 = DIRECTION('',(1.,0.E+000,0.E+000)); -#76645 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#76646 = DEFINITIONAL_REPRESENTATION('',(#76647),#76650); -#76647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#76648,#76649),.UNSPECIFIED., +#79006 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79007 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#79008 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#79009 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#79010 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#79011 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#79012 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#79013 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#79014 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#79015 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#79016 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#79017 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#79018 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#79019 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#79020 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#79021 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#79022 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#79023 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#79024 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#79025 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#79026 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#79027 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#79028 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#79029 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#79030 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79032 = PCURVE('',#79033,#79038); +#79033 = CYLINDRICAL_SURFACE('',#79034,5.E-002); +#79034 = AXIS2_PLACEMENT_3D('',#79035,#79036,#79037); +#79035 = CARTESIAN_POINT('',(-1.46,0.477659054385,0.15)); +#79036 = DIRECTION('',(1.,0.E+000,0.E+000)); +#79037 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#79038 = DEFINITIONAL_REPRESENTATION('',(#79039),#79042); +#79039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79040,#79041),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#76648 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#76649 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#76650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76651 = ADVANCED_FACE('',(#76652),#76667,.T.); -#76652 = FACE_BOUND('',#76653,.T.); -#76653 = EDGE_LOOP('',(#76654,#76746,#76831,#76883)); -#76654 = ORIENTED_EDGE('',*,*,#76655,.F.); -#76655 = EDGE_CURVE('',#76656,#76658,#76660,.T.); -#76656 = VERTEX_POINT('',#76657); -#76657 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 +#79040 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#79041 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#79042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79043 = ADVANCED_FACE('',(#79044),#79059,.T.); +#79044 = FACE_BOUND('',#79045,.T.); +#79045 = EDGE_LOOP('',(#79046,#79138,#79223,#79275)); +#79046 = ORIENTED_EDGE('',*,*,#79047,.F.); +#79047 = EDGE_CURVE('',#79048,#79050,#79052,.T.); +#79048 = VERTEX_POINT('',#79049); +#79049 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 )); -#76658 = VERTEX_POINT('',#76659); -#76659 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 +#79050 = VERTEX_POINT('',#79051); +#79051 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 )); -#76660 = SURFACE_CURVE('',#76661,(#76666,#76712),.PCURVE_S1.); -#76661 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76662,#76663,#76664,#76665 +#79052 = SURFACE_CURVE('',#79053,(#79058,#79104),.PCURVE_S1.); +#79053 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79054,#79055,#79056,#79057 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.614007241618E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76662 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 +#79054 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 )); -#76663 = CARTESIAN_POINT('',(-1.34683376285,-0.482375921036,0.967717466) +#79055 = CARTESIAN_POINT('',(-1.34683376285,-0.482375921036,0.967717466) ); -#76664 = CARTESIAN_POINT('',(-1.361917855478,-0.44680534294, +#79056 = CARTESIAN_POINT('',(-1.361917855478,-0.44680534294, 0.966047546673)); -#76665 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 +#79057 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 )); -#76666 = PCURVE('',#76667,#76684); -#76667 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76668,#76669,#76670,#76671) - ,(#76672,#76673,#76674,#76675) - ,(#76676,#76677,#76678,#76679) - ,(#76680,#76681,#76682,#76683 +#79058 = PCURVE('',#79059,#79076); +#79059 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79060,#79061,#79062,#79063) + ,(#79064,#79065,#79066,#79067) + ,(#79068,#79069,#79070,#79071) + ,(#79072,#79073,#79074,#79075 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76668 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 +#79060 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391,0.962940952255 )); -#76669 = CARTESIAN_POINT('',(-1.357103709313,-0.407861391,0.984014184754 +#79061 = CARTESIAN_POINT('',(-1.357103709313,-0.407861391,0.984014184754 )); -#76670 = CARTESIAN_POINT('',(-1.336270589279,-0.407861391,1.)); -#76671 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#76672 = CARTESIAN_POINT('',(-1.361937603265,-0.445881450408, +#79062 = CARTESIAN_POINT('',(-1.336270589279,-0.407861391,1.)); +#79063 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#79064 = CARTESIAN_POINT('',(-1.361937603265,-0.445881450408, 0.965973846926)); -#76673 = CARTESIAN_POINT('',(-1.355238584914,-0.444463088209, +#79065 = CARTESIAN_POINT('',(-1.355238584914,-0.444463088209, 0.985681523985)); -#76674 = CARTESIAN_POINT('',(-1.335223961408,-0.439230002437,1.)); -#76675 = CARTESIAN_POINT('',(-1.314453973629,-0.433749871723,1.)); -#76676 = CARTESIAN_POINT('',(-1.346187793567,-0.483021890319,0.967717466 +#79066 = CARTESIAN_POINT('',(-1.335223961408,-0.439230002437,1.)); +#79067 = CARTESIAN_POINT('',(-1.314453973629,-0.433749871723,1.)); +#79068 = CARTESIAN_POINT('',(-1.346187793567,-0.483021890319,0.967717466 )); -#76677 = CARTESIAN_POINT('',(-1.339788010173,-0.479327515655, +#79069 = CARTESIAN_POINT('',(-1.339788010173,-0.479327515655, 0.986553421368)); -#76678 = CARTESIAN_POINT('',(-1.322326230316,-0.469247431202,1.)); -#76679 = CARTESIAN_POINT('',(-1.304265568045,-0.458821632546,1.)); -#76680 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 +#79070 = CARTESIAN_POINT('',(-1.322326230316,-0.469247431202,1.)); +#79071 = CARTESIAN_POINT('',(-1.304265568045,-0.458821632546,1.)); +#79072 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 )); -#76681 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, +#79073 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, 0.986553421368)); -#76682 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); -#76683 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#76684 = DEFINITIONAL_REPRESENTATION('',(#76685),#76711); -#76685 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76686,#76687,#76688,#76689, - #76690,#76691,#76692,#76693,#76694,#76695,#76696,#76697,#76698, - #76699,#76700,#76701,#76702,#76703,#76704,#76705,#76706,#76707, - #76708,#76709,#76710),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79074 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); +#79075 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#79076 = DEFINITIONAL_REPRESENTATION('',(#79077),#79103); +#79077 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79078,#79079,#79080,#79081, + #79082,#79083,#79084,#79085,#79086,#79087,#79088,#79089,#79090, + #79091,#79092,#79093,#79094,#79095,#79096,#79097,#79098,#79099, + #79100,#79101,#79102),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.614007241618E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -94785,48 +97774,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#76686 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76687 = CARTESIAN_POINT('',(6.272059551128,2.972804133766E-006)); -#76688 = CARTESIAN_POINT('',(6.249732638972,-1.037052467445E-005)); -#76689 = CARTESIAN_POINT('',(6.216039360813,-5.446484095571E-005)); -#76690 = CARTESIAN_POINT('',(6.182166930891,-8.868396576175E-005)); -#76691 = CARTESIAN_POINT('',(6.148137469616,-7.965797689889E-005)); -#76692 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); -#76693 = CARTESIAN_POINT('',(6.079693755153,-8.179989506536E-005)); -#76694 = CARTESIAN_POINT('',(6.045320300361,-8.220472162591E-005)); -#76695 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); -#76696 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); -#76697 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); -#76698 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); -#76699 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); -#76700 = CARTESIAN_POINT('',(5.838159829417,-8.435280808233E-005)); -#76701 = CARTESIAN_POINT('',(5.803652201529,-8.485308627406E-005)); -#76702 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); -#76703 = CARTESIAN_POINT('',(5.734821280548,-8.593545386256E-005)); -#76704 = CARTESIAN_POINT('',(5.700537102675,-8.687395637433E-005)); -#76705 = CARTESIAN_POINT('',(5.666367464043,-8.643221197456E-005)); -#76706 = CARTESIAN_POINT('',(5.632333796953,-9.135814826506E-005)); -#76707 = CARTESIAN_POINT('',(5.59845580442,-3.211561474224E-005)); -#76708 = CARTESIAN_POINT('',(5.564759360754,-7.920681094116E-006)); -#76709 = CARTESIAN_POINT('',(5.542431620275,5.712075443838E-008)); -#76710 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76712 = PCURVE('',#76713,#76718); -#76713 = CYLINDRICAL_SURFACE('',#76714,0.15); -#76714 = AXIS2_PLACEMENT_3D('',#76715,#76716,#76717); -#76715 = CARTESIAN_POINT('',(-1.324207498814,-0.514207498814, +#79078 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79079 = CARTESIAN_POINT('',(6.272059551128,2.972804133766E-006)); +#79080 = CARTESIAN_POINT('',(6.249732638972,-1.037052467445E-005)); +#79081 = CARTESIAN_POINT('',(6.216039360813,-5.446484095571E-005)); +#79082 = CARTESIAN_POINT('',(6.182166930891,-8.868396576175E-005)); +#79083 = CARTESIAN_POINT('',(6.148137469616,-7.965797689889E-005)); +#79084 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); +#79085 = CARTESIAN_POINT('',(6.079693755153,-8.179989506536E-005)); +#79086 = CARTESIAN_POINT('',(6.045320300361,-8.220472162591E-005)); +#79087 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); +#79088 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); +#79089 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); +#79090 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); +#79091 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); +#79092 = CARTESIAN_POINT('',(5.838159829417,-8.435280808233E-005)); +#79093 = CARTESIAN_POINT('',(5.803652201529,-8.485308627406E-005)); +#79094 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); +#79095 = CARTESIAN_POINT('',(5.734821280548,-8.593545386256E-005)); +#79096 = CARTESIAN_POINT('',(5.700537102675,-8.687395637433E-005)); +#79097 = CARTESIAN_POINT('',(5.666367464043,-8.643221197456E-005)); +#79098 = CARTESIAN_POINT('',(5.632333796953,-9.135814826506E-005)); +#79099 = CARTESIAN_POINT('',(5.59845580442,-3.211561474224E-005)); +#79100 = CARTESIAN_POINT('',(5.564759360754,-7.920681094116E-006)); +#79101 = CARTESIAN_POINT('',(5.542431620275,5.712075443838E-008)); +#79102 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79104 = PCURVE('',#79105,#79110); +#79105 = CYLINDRICAL_SURFACE('',#79106,0.15); +#79106 = AXIS2_PLACEMENT_3D('',#79107,#79108,#79109); +#79107 = CARTESIAN_POINT('',(-1.324207498814,-0.514207498814, 0.527229017938)); -#76716 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) +#79108 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) ); -#76717 = DIRECTION('',(-0.965925826289,4.046106982444E-017, +#79109 = DIRECTION('',(-0.965925826289,4.046106982444E-017, 0.258819045103)); -#76718 = DEFINITIONAL_REPRESENTATION('',(#76719),#76745); -#76719 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76720,#76721,#76722,#76723, - #76724,#76725,#76726,#76727,#76728,#76729,#76730,#76731,#76732, - #76733,#76734,#76735,#76736,#76737,#76738,#76739,#76740,#76741, - #76742,#76743,#76744),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79110 = DEFINITIONAL_REPRESENTATION('',(#79111),#79137); +#79111 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79112,#79113,#79114,#79115, + #79116,#79117,#79118,#79119,#79120,#79121,#79122,#79123,#79124, + #79125,#79126,#79127,#79128,#79129,#79130,#79131,#79132,#79133, + #79134,#79135,#79136),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.614007241618E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -94834,50 +97823,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#76720 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); -#76721 = CARTESIAN_POINT('',(5.542431500119,-0.414213027833)); -#76722 = CARTESIAN_POINT('',(5.56475355,-0.414227119403)); -#76723 = CARTESIAN_POINT('',(5.598431528687,-0.414291190685)); -#76724 = CARTESIAN_POINT('',(5.632287045183,-0.414398842232)); -#76725 = CARTESIAN_POINT('',(5.666301906361,-0.414550528448)); -#76726 = CARTESIAN_POINT('',(5.700457442157,-0.414746569643)); -#76727 = CARTESIAN_POINT('',(5.734734482675,-0.414987129667)); -#76728 = CARTESIAN_POINT('',(5.76911344049,-0.41527221657)); -#76729 = CARTESIAN_POINT('',(5.803574369467,-0.415601678753)); -#76730 = CARTESIAN_POINT('',(5.838097033931,-0.415975204048)); -#76731 = CARTESIAN_POINT('',(5.872660978441,-0.416392319824)); -#76732 = CARTESIAN_POINT('',(5.907245600032,-0.416852394634)); -#76733 = CARTESIAN_POINT('',(5.941830221623,-0.417354641276)); -#76734 = CARTESIAN_POINT('',(5.976394166134,-0.41789812127)); -#76735 = CARTESIAN_POINT('',(6.010916830598,-0.418481750684)); -#76736 = CARTESIAN_POINT('',(6.045377759574,-0.419104307248)); -#76737 = CARTESIAN_POINT('',(6.079756717389,-0.419764438636)); -#76738 = CARTESIAN_POINT('',(6.114033757907,-0.420460671856)); -#76739 = CARTESIAN_POINT('',(6.148189293703,-0.421191423422)); -#76740 = CARTESIAN_POINT('',(6.182204154882,-0.421955010917)); -#76741 = CARTESIAN_POINT('',(6.216059671377,-0.422749662917)); -#76742 = CARTESIAN_POINT('',(6.249737650065,-0.423573537911)); -#76743 = CARTESIAN_POINT('',(6.272059699945,-0.424140987131)); -#76744 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); -#76745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76746 = ORIENTED_EDGE('',*,*,#76747,.T.); -#76747 = EDGE_CURVE('',#76656,#76748,#76750,.T.); -#76748 = VERTEX_POINT('',#76749); -#76749 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#76750 = SURFACE_CURVE('',#76751,(#76756,#76785),.PCURVE_S1.); -#76751 = CIRCLE('',#76752,5.E-002); -#76752 = AXIS2_PLACEMENT_3D('',#76753,#76754,#76755); -#76753 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,0.95)); -#76754 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#76755 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#76756 = PCURVE('',#76667,#76757); -#76757 = DEFINITIONAL_REPRESENTATION('',(#76758),#76784); -#76758 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76759,#76760,#76761,#76762, - #76763,#76764,#76765,#76766,#76767,#76768,#76769,#76770,#76771, - #76772,#76773,#76774,#76775,#76776,#76777,#76778,#76779,#76780, - #76781,#76782,#76783),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79112 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); +#79113 = CARTESIAN_POINT('',(5.542431500119,-0.414213027833)); +#79114 = CARTESIAN_POINT('',(5.56475355,-0.414227119403)); +#79115 = CARTESIAN_POINT('',(5.598431528687,-0.414291190685)); +#79116 = CARTESIAN_POINT('',(5.632287045183,-0.414398842232)); +#79117 = CARTESIAN_POINT('',(5.666301906361,-0.414550528448)); +#79118 = CARTESIAN_POINT('',(5.700457442157,-0.414746569643)); +#79119 = CARTESIAN_POINT('',(5.734734482675,-0.414987129667)); +#79120 = CARTESIAN_POINT('',(5.76911344049,-0.41527221657)); +#79121 = CARTESIAN_POINT('',(5.803574369467,-0.415601678753)); +#79122 = CARTESIAN_POINT('',(5.838097033931,-0.415975204048)); +#79123 = CARTESIAN_POINT('',(5.872660978441,-0.416392319824)); +#79124 = CARTESIAN_POINT('',(5.907245600032,-0.416852394634)); +#79125 = CARTESIAN_POINT('',(5.941830221623,-0.417354641276)); +#79126 = CARTESIAN_POINT('',(5.976394166134,-0.41789812127)); +#79127 = CARTESIAN_POINT('',(6.010916830598,-0.418481750684)); +#79128 = CARTESIAN_POINT('',(6.045377759574,-0.419104307248)); +#79129 = CARTESIAN_POINT('',(6.079756717389,-0.419764438636)); +#79130 = CARTESIAN_POINT('',(6.114033757907,-0.420460671856)); +#79131 = CARTESIAN_POINT('',(6.148189293703,-0.421191423422)); +#79132 = CARTESIAN_POINT('',(6.182204154882,-0.421955010917)); +#79133 = CARTESIAN_POINT('',(6.216059671377,-0.422749662917)); +#79134 = CARTESIAN_POINT('',(6.249737650065,-0.423573537911)); +#79135 = CARTESIAN_POINT('',(6.272059699945,-0.424140987131)); +#79136 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); +#79137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79138 = ORIENTED_EDGE('',*,*,#79139,.T.); +#79139 = EDGE_CURVE('',#79048,#79140,#79142,.T.); +#79140 = VERTEX_POINT('',#79141); +#79141 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#79142 = SURFACE_CURVE('',#79143,(#79148,#79177),.PCURVE_S1.); +#79143 = CIRCLE('',#79144,5.E-002); +#79144 = AXIS2_PLACEMENT_3D('',#79145,#79146,#79147); +#79145 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,0.95)); +#79146 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#79147 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#79148 = PCURVE('',#79059,#79149); +#79149 = DEFINITIONAL_REPRESENTATION('',(#79150),#79176); +#79150 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79151,#79152,#79153,#79154, + #79155,#79156,#79157,#79158,#79159,#79160,#79161,#79162,#79163, + #79164,#79165,#79166,#79167,#79168,#79169,#79170,#79171,#79172, + #79173,#79174,#79175),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -94885,71 +97874,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#76759 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76760 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#76761 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#76762 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#76763 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#76764 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#76765 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#76766 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#76767 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#76768 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#76769 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#76770 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#76771 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#76772 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#76773 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#76774 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#76775 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#76776 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#76777 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#76778 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#76779 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#76780 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#76781 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#76782 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#76783 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76785 = PCURVE('',#76786,#76803); -#76786 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76787,#76788,#76789,#76790) - ,(#76791,#76792,#76793,#76794) - ,(#76795,#76796,#76797,#76798) - ,(#76799,#76800,#76801,#76802 +#79151 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79152 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#79153 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#79154 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#79155 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#79156 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#79157 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#79158 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#79159 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#79160 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#79161 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#79162 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#79163 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#79164 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#79165 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#79166 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#79167 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#79168 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#79169 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#79170 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#79171 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#79172 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#79173 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#79174 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#79175 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79177 = PCURVE('',#79178,#79195); +#79178 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79179,#79180,#79181,#79182) + ,(#79183,#79184,#79185,#79186) + ,(#79187,#79188,#79189,#79190) + ,(#79191,#79192,#79193,#79194 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76787 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 +#79179 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 )); -#76788 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, +#79180 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, 0.986553421368)); -#76789 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); -#76790 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#76791 = CARTESIAN_POINT('',(-1.293021890319,-0.536187793567,0.967717466 +#79181 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); +#79182 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#79183 = CARTESIAN_POINT('',(-1.293021890319,-0.536187793567,0.967717466 )); -#76792 = CARTESIAN_POINT('',(-1.289327515655,-0.529788010173, +#79184 = CARTESIAN_POINT('',(-1.289327515655,-0.529788010173, 0.986553421368)); -#76793 = CARTESIAN_POINT('',(-1.279247431202,-0.512326230316,1.)); -#76794 = CARTESIAN_POINT('',(-1.268821632546,-0.494265568045,1.)); -#76795 = CARTESIAN_POINT('',(-1.255881450408,-0.551937603265, +#79185 = CARTESIAN_POINT('',(-1.279247431202,-0.512326230316,1.)); +#79186 = CARTESIAN_POINT('',(-1.268821632546,-0.494265568045,1.)); +#79187 = CARTESIAN_POINT('',(-1.255881450408,-0.551937603265, 0.965973846926)); -#76796 = CARTESIAN_POINT('',(-1.254463088209,-0.545238584914, +#79188 = CARTESIAN_POINT('',(-1.254463088209,-0.545238584914, 0.985681523985)); -#76797 = CARTESIAN_POINT('',(-1.249230002437,-0.525223961408,1.)); -#76798 = CARTESIAN_POINT('',(-1.243749871723,-0.504453973629,1.)); -#76799 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 +#79189 = CARTESIAN_POINT('',(-1.249230002437,-0.525223961408,1.)); +#79190 = CARTESIAN_POINT('',(-1.243749871723,-0.504453973629,1.)); +#79191 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 )); -#76800 = CARTESIAN_POINT('',(-1.217861391,-0.547103709313,0.984014184754 +#79192 = CARTESIAN_POINT('',(-1.217861391,-0.547103709313,0.984014184754 )); -#76801 = CARTESIAN_POINT('',(-1.217861391,-0.526270589279,1.)); -#76802 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#76803 = DEFINITIONAL_REPRESENTATION('',(#76804),#76830); -#76804 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76805,#76806,#76807,#76808, - #76809,#76810,#76811,#76812,#76813,#76814,#76815,#76816,#76817, - #76818,#76819,#76820,#76821,#76822,#76823,#76824,#76825,#76826, - #76827,#76828,#76829),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79193 = CARTESIAN_POINT('',(-1.217861391,-0.526270589279,1.)); +#79194 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#79195 = DEFINITIONAL_REPRESENTATION('',(#79196),#79222); +#79196 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79197,#79198,#79199,#79200, + #79201,#79202,#79203,#79204,#79205,#79206,#79207,#79208,#79209, + #79210,#79211,#79212,#79213,#79214,#79215,#79216,#79217,#79218, + #79219,#79220,#79221),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -94957,54 +97946,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#76805 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#76806 = CARTESIAN_POINT('',(-7.405118739674E-017,1.515278164503E-002)); -#76807 = CARTESIAN_POINT('',(-3.985677504963E-016,4.549920749134E-002)); -#76808 = CARTESIAN_POINT('',(-1.580210697048E-016,9.109101074356E-002)); -#76809 = CARTESIAN_POINT('',(-1.134047533416E-015,0.136698748187)); -#76810 = CARTESIAN_POINT('',(-1.18401290745E-015,0.1822865144)); -#76811 = CARTESIAN_POINT('',(-4.407567392352E-016,0.2278300409)); -#76812 = CARTESIAN_POINT('',(-4.839912429467E-016,0.27331674602)); -#76813 = CARTESIAN_POINT('',(-1.491400225705E-015,0.318743220066)); -#76814 = CARTESIAN_POINT('',(-1.224284056902E-015,0.364113426255)); -#76815 = CARTESIAN_POINT('',(1.807913054958E-015,0.409436881051)); -#76816 = CARTESIAN_POINT('',(-2.245594212443E-015,0.454727066523)); -#76817 = CARTESIAN_POINT('',(-2.261564653344E-016,0.5)); -#76818 = CARTESIAN_POINT('',(8.823179217072E-016,0.545272933477)); -#76819 = CARTESIAN_POINT('',(-4.43084088851E-016,0.590563118949)); -#76820 = CARTESIAN_POINT('',(1.354931126903E-015,0.635886573745)); -#76821 = CARTESIAN_POINT('',(-1.161199682066E-015,0.681256779934)); -#76822 = CARTESIAN_POINT('',(6.31123117599E-016,0.72668325398)); -#76823 = CARTESIAN_POINT('',(1.538180390986E-015,0.7721699591)); -#76824 = CARTESIAN_POINT('',(1.66425983616E-015,0.8177134856)); -#76825 = CARTESIAN_POINT('',(1.570550897846E-015,0.863301251813)); -#76826 = CARTESIAN_POINT('',(9.673829897528E-016,0.908908989256)); -#76827 = CARTESIAN_POINT('',(3.957986323149E-016,0.954500792509)); -#76828 = CARTESIAN_POINT('',(2.701619826828E-016,0.984847218355)); -#76829 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#76830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76831 = ORIENTED_EDGE('',*,*,#76832,.F.); -#76832 = EDGE_CURVE('',#76833,#76748,#76835,.T.); -#76833 = VERTEX_POINT('',#76834); -#76834 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#76835 = SURFACE_CURVE('',#76836,(#76841,#76870),.PCURVE_S1.); -#76836 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76837,#76838,#76839,#76840 +#79197 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#79198 = CARTESIAN_POINT('',(-7.405118739674E-017,1.515278164503E-002)); +#79199 = CARTESIAN_POINT('',(-3.985677504963E-016,4.549920749134E-002)); +#79200 = CARTESIAN_POINT('',(-1.580210697048E-016,9.109101074356E-002)); +#79201 = CARTESIAN_POINT('',(-1.134047533416E-015,0.136698748187)); +#79202 = CARTESIAN_POINT('',(-1.18401290745E-015,0.1822865144)); +#79203 = CARTESIAN_POINT('',(-4.407567392352E-016,0.2278300409)); +#79204 = CARTESIAN_POINT('',(-4.839912429467E-016,0.27331674602)); +#79205 = CARTESIAN_POINT('',(-1.491400225705E-015,0.318743220066)); +#79206 = CARTESIAN_POINT('',(-1.224284056902E-015,0.364113426255)); +#79207 = CARTESIAN_POINT('',(1.807913054958E-015,0.409436881051)); +#79208 = CARTESIAN_POINT('',(-2.245594212443E-015,0.454727066523)); +#79209 = CARTESIAN_POINT('',(-2.261564653344E-016,0.5)); +#79210 = CARTESIAN_POINT('',(8.823179217072E-016,0.545272933477)); +#79211 = CARTESIAN_POINT('',(-4.43084088851E-016,0.590563118949)); +#79212 = CARTESIAN_POINT('',(1.354931126903E-015,0.635886573745)); +#79213 = CARTESIAN_POINT('',(-1.161199682066E-015,0.681256779934)); +#79214 = CARTESIAN_POINT('',(6.31123117599E-016,0.72668325398)); +#79215 = CARTESIAN_POINT('',(1.538180390986E-015,0.7721699591)); +#79216 = CARTESIAN_POINT('',(1.66425983616E-015,0.8177134856)); +#79217 = CARTESIAN_POINT('',(1.570550897846E-015,0.863301251813)); +#79218 = CARTESIAN_POINT('',(9.673829897528E-016,0.908908989256)); +#79219 = CARTESIAN_POINT('',(3.957986323149E-016,0.954500792509)); +#79220 = CARTESIAN_POINT('',(2.701619826828E-016,0.984847218355)); +#79221 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#79222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79223 = ORIENTED_EDGE('',*,*,#79224,.F.); +#79224 = EDGE_CURVE('',#79225,#79140,#79227,.T.); +#79225 = VERTEX_POINT('',#79226); +#79226 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#79227 = SURFACE_CURVE('',#79228,(#79233,#79262),.PCURVE_S1.); +#79228 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79229,#79230,#79231,#79232 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76837 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#76838 = CARTESIAN_POINT('',(-1.314453973629,-0.43437896527,1.)); -#76839 = CARTESIAN_POINT('',(-1.304696214234,-0.458390986358,1.)); -#76840 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#76841 = PCURVE('',#76667,#76842); -#76842 = DEFINITIONAL_REPRESENTATION('',(#76843),#76869); -#76843 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76844,#76845,#76846,#76847, - #76848,#76849,#76850,#76851,#76852,#76853,#76854,#76855,#76856, - #76857,#76858,#76859,#76860,#76861,#76862,#76863,#76864,#76865, - #76866,#76867,#76868),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79229 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#79230 = CARTESIAN_POINT('',(-1.314453973629,-0.43437896527,1.)); +#79231 = CARTESIAN_POINT('',(-1.304696214234,-0.458390986358,1.)); +#79232 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#79233 = PCURVE('',#79059,#79234); +#79234 = DEFINITIONAL_REPRESENTATION('',(#79235),#79261); +#79235 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79236,#79237,#79238,#79239, + #79240,#79241,#79242,#79243,#79244,#79245,#79246,#79247,#79248, + #79249,#79250,#79251,#79252,#79253,#79254,#79255,#79256,#79257, + #79258,#79259,#79260),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -95012,67 +98001,67 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#76844 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76845 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#76846 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#76847 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#76848 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#76849 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#76850 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#76851 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#76852 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#76853 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#76854 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#76855 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#76856 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#76857 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#76858 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#76859 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#76860 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#76861 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#76862 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#76863 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#76864 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#76865 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#76866 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#76867 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#76868 = CARTESIAN_POINT('',(6.28318530718,1.)); -#76869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76870 = PCURVE('',#76871,#76876); -#76871 = PLANE('',#76872); -#76872 = AXIS2_PLACEMENT_3D('',#76873,#76874,#76875); -#76873 = CARTESIAN_POINT('',(1.46,-0.65,1.)); -#76874 = DIRECTION('',(0.E+000,0.E+000,1.)); -#76875 = DIRECTION('',(1.,0.E+000,0.E+000)); -#76876 = DEFINITIONAL_REPRESENTATION('',(#76877),#76882); -#76877 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76878,#76879,#76880,#76881 +#79236 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79237 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#79238 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#79239 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#79240 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#79241 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#79242 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#79243 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#79244 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#79245 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#79246 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#79247 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#79248 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#79249 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#79250 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#79251 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#79252 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#79253 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#79254 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#79255 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#79256 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#79257 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#79258 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#79259 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#79260 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79262 = PCURVE('',#79263,#79268); +#79263 = PLANE('',#79264); +#79264 = AXIS2_PLACEMENT_3D('',#79265,#79266,#79267); +#79265 = CARTESIAN_POINT('',(1.46,-0.65,1.)); +#79266 = DIRECTION('',(0.E+000,0.E+000,1.)); +#79267 = DIRECTION('',(1.,0.E+000,0.E+000)); +#79268 = DEFINITIONAL_REPRESENTATION('',(#79269),#79274); +#79269 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79270,#79271,#79272,#79273 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76878 = CARTESIAN_POINT('',(-2.774453973629,0.242138609)); -#76879 = CARTESIAN_POINT('',(-2.774453973629,0.21562103473)); -#76880 = CARTESIAN_POINT('',(-2.764696214234,0.191609013642)); -#76881 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); -#76882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76883 = ORIENTED_EDGE('',*,*,#76884,.T.); -#76884 = EDGE_CURVE('',#76833,#76658,#76885,.T.); -#76885 = SURFACE_CURVE('',#76886,(#76891,#76920),.PCURVE_S1.); -#76886 = CIRCLE('',#76887,5.E-002); -#76887 = AXIS2_PLACEMENT_3D('',#76888,#76889,#76890); -#76888 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,0.95)); -#76889 = DIRECTION('',(2.244897367846E-015,-1.,0.E+000)); -#76890 = DIRECTION('',(1.,2.244897367846E-015,0.E+000)); -#76891 = PCURVE('',#76667,#76892); -#76892 = DEFINITIONAL_REPRESENTATION('',(#76893),#76919); -#76893 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76894,#76895,#76896,#76897, - #76898,#76899,#76900,#76901,#76902,#76903,#76904,#76905,#76906, - #76907,#76908,#76909,#76910,#76911,#76912,#76913,#76914,#76915, - #76916,#76917,#76918),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79270 = CARTESIAN_POINT('',(-2.774453973629,0.242138609)); +#79271 = CARTESIAN_POINT('',(-2.774453973629,0.21562103473)); +#79272 = CARTESIAN_POINT('',(-2.764696214234,0.191609013642)); +#79273 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); +#79274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79275 = ORIENTED_EDGE('',*,*,#79276,.T.); +#79276 = EDGE_CURVE('',#79225,#79050,#79277,.T.); +#79277 = SURFACE_CURVE('',#79278,(#79283,#79312),.PCURVE_S1.); +#79278 = CIRCLE('',#79279,5.E-002); +#79279 = AXIS2_PLACEMENT_3D('',#79280,#79281,#79282); +#79280 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,0.95)); +#79281 = DIRECTION('',(2.244897367846E-015,-1.,0.E+000)); +#79282 = DIRECTION('',(1.,2.244897367846E-015,0.E+000)); +#79283 = PCURVE('',#79059,#79284); +#79284 = DEFINITIONAL_REPRESENTATION('',(#79285),#79311); +#79285 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79286,#79287,#79288,#79289, + #79290,#79291,#79292,#79293,#79294,#79295,#79296,#79297,#79298, + #79299,#79300,#79301,#79302,#79303,#79304,#79305,#79306,#79307, + #79308,#79309,#79310),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.630296187658, 1.689796048522,1.749295909385,1.808795770249,1.868295631112, 1.927795491976,1.987295352839,2.046795213702,2.106295074566, @@ -95080,45 +98069,45 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.403794378883,2.463294239747,2.52279410061,2.582293961473, 2.641793822337,2.7012936832,2.760793544064,2.820293404927, 2.879793265791),.QUASI_UNIFORM_KNOTS.); -#76894 = CARTESIAN_POINT('',(5.531305892885,1.)); -#76895 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#76896 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#76897 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#76898 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#76899 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#76900 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#76901 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#76902 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#76903 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#76904 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#76905 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#76906 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#76907 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#76908 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#76909 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#76910 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#76911 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#76912 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#76913 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#76914 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#76915 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#76916 = CARTESIAN_POINT('',(5.531305899752,4.551530551222E-002)); -#76917 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#76918 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#76919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76920 = PCURVE('',#76921,#76926); -#76921 = CYLINDRICAL_SURFACE('',#76922,5.E-002); -#76922 = AXIS2_PLACEMENT_3D('',#76923,#76924,#76925); -#76923 = CARTESIAN_POINT('',(-1.314453973629,-0.65,0.95)); -#76924 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#76925 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); -#76926 = DEFINITIONAL_REPRESENTATION('',(#76927),#76953); -#76927 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76928,#76929,#76930,#76931, - #76932,#76933,#76934,#76935,#76936,#76937,#76938,#76939,#76940, - #76941,#76942,#76943,#76944,#76945,#76946,#76947,#76948,#76949, - #76950,#76951,#76952),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79286 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79287 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#79288 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#79289 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#79290 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#79291 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#79292 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#79293 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#79294 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#79295 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#79296 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#79297 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#79298 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#79299 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#79300 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#79301 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#79302 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#79303 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#79304 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#79305 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#79306 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#79307 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#79308 = CARTESIAN_POINT('',(5.531305899752,4.551530551222E-002)); +#79309 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#79310 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79312 = PCURVE('',#79313,#79318); +#79313 = CYLINDRICAL_SURFACE('',#79314,5.E-002); +#79314 = AXIS2_PLACEMENT_3D('',#79315,#79316,#79317); +#79315 = CARTESIAN_POINT('',(-1.314453973629,-0.65,0.95)); +#79316 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#79317 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); +#79318 = DEFINITIONAL_REPRESENTATION('',(#79319),#79345); +#79319 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79320,#79321,#79322,#79323, + #79324,#79325,#79326,#79327,#79328,#79329,#79330,#79331,#79332, + #79333,#79334,#79335,#79336,#79337,#79338,#79339,#79340,#79341, + #79342,#79343,#79344),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795,1.630296187658, 1.689796048522,1.749295909385,1.808795770249,1.868295631112, 1.927795491976,1.987295352839,2.046795213702,2.106295074566, @@ -95126,96 +98115,96 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.403794378883,2.463294239747,2.52279410061,2.582293961473, 2.641793822337,2.7012936832,2.760793544064,2.820293404927, 2.879793265791),.QUASI_UNIFORM_KNOTS.); -#76928 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); -#76929 = CARTESIAN_POINT('',(1.590629613749,-0.242138609)); -#76930 = CARTESIAN_POINT('',(1.630296187658,-0.242138609)); -#76931 = CARTESIAN_POINT('',(1.689796048522,-0.242138609)); -#76932 = CARTESIAN_POINT('',(1.749295909385,-0.242138609)); -#76933 = CARTESIAN_POINT('',(1.808795770249,-0.242138609)); -#76934 = CARTESIAN_POINT('',(1.868295631112,-0.242138609)); -#76935 = CARTESIAN_POINT('',(1.927795491976,-0.242138609)); -#76936 = CARTESIAN_POINT('',(1.987295352839,-0.242138609)); -#76937 = CARTESIAN_POINT('',(2.046795213702,-0.242138609)); -#76938 = CARTESIAN_POINT('',(2.106295074566,-0.242138609)); -#76939 = CARTESIAN_POINT('',(2.165794935429,-0.242138609)); -#76940 = CARTESIAN_POINT('',(2.225294796293,-0.242138609)); -#76941 = CARTESIAN_POINT('',(2.284794657156,-0.242138609)); -#76942 = CARTESIAN_POINT('',(2.34429451802,-0.242138609)); -#76943 = CARTESIAN_POINT('',(2.403794378883,-0.242138609)); -#76944 = CARTESIAN_POINT('',(2.463294239747,-0.242138609)); -#76945 = CARTESIAN_POINT('',(2.52279410061,-0.242138609)); -#76946 = CARTESIAN_POINT('',(2.582293961473,-0.242138609)); -#76947 = CARTESIAN_POINT('',(2.641793822337,-0.242138609)); -#76948 = CARTESIAN_POINT('',(2.7012936832,-0.242138609)); -#76949 = CARTESIAN_POINT('',(2.760793544064,-0.242138609)); -#76950 = CARTESIAN_POINT('',(2.820293404927,-0.242138609)); -#76951 = CARTESIAN_POINT('',(2.859959978836,-0.242138609)); -#76952 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); -#76953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#76954 = ADVANCED_FACE('',(#76955),#76970,.T.); -#76955 = FACE_BOUND('',#76956,.T.); -#76956 = EDGE_LOOP('',(#76957,#77049,#77134,#77181)); -#76957 = ORIENTED_EDGE('',*,*,#76958,.F.); -#76958 = EDGE_CURVE('',#76959,#76961,#76963,.T.); -#76959 = VERTEX_POINT('',#76960); -#76960 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) - ); -#76961 = VERTEX_POINT('',#76962); -#76962 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) - ); -#76963 = SURFACE_CURVE('',#76964,(#76969,#77015),.PCURVE_S1.); -#76964 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#76965,#76966,#76967,#76968 +#79320 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); +#79321 = CARTESIAN_POINT('',(1.590629613749,-0.242138609)); +#79322 = CARTESIAN_POINT('',(1.630296187658,-0.242138609)); +#79323 = CARTESIAN_POINT('',(1.689796048522,-0.242138609)); +#79324 = CARTESIAN_POINT('',(1.749295909385,-0.242138609)); +#79325 = CARTESIAN_POINT('',(1.808795770249,-0.242138609)); +#79326 = CARTESIAN_POINT('',(1.868295631112,-0.242138609)); +#79327 = CARTESIAN_POINT('',(1.927795491976,-0.242138609)); +#79328 = CARTESIAN_POINT('',(1.987295352839,-0.242138609)); +#79329 = CARTESIAN_POINT('',(2.046795213702,-0.242138609)); +#79330 = CARTESIAN_POINT('',(2.106295074566,-0.242138609)); +#79331 = CARTESIAN_POINT('',(2.165794935429,-0.242138609)); +#79332 = CARTESIAN_POINT('',(2.225294796293,-0.242138609)); +#79333 = CARTESIAN_POINT('',(2.284794657156,-0.242138609)); +#79334 = CARTESIAN_POINT('',(2.34429451802,-0.242138609)); +#79335 = CARTESIAN_POINT('',(2.403794378883,-0.242138609)); +#79336 = CARTESIAN_POINT('',(2.463294239747,-0.242138609)); +#79337 = CARTESIAN_POINT('',(2.52279410061,-0.242138609)); +#79338 = CARTESIAN_POINT('',(2.582293961473,-0.242138609)); +#79339 = CARTESIAN_POINT('',(2.641793822337,-0.242138609)); +#79340 = CARTESIAN_POINT('',(2.7012936832,-0.242138609)); +#79341 = CARTESIAN_POINT('',(2.760793544064,-0.242138609)); +#79342 = CARTESIAN_POINT('',(2.820293404927,-0.242138609)); +#79343 = CARTESIAN_POINT('',(2.859959978836,-0.242138609)); +#79344 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); +#79345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79346 = ADVANCED_FACE('',(#79347),#79362,.T.); +#79347 = FACE_BOUND('',#79348,.T.); +#79348 = EDGE_LOOP('',(#79349,#79441,#79526,#79573)); +#79349 = ORIENTED_EDGE('',*,*,#79350,.F.); +#79350 = EDGE_CURVE('',#79351,#79353,#79355,.T.); +#79351 = VERTEX_POINT('',#79352); +#79352 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) + ); +#79353 = VERTEX_POINT('',#79354); +#79354 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) + ); +#79355 = SURFACE_CURVE('',#79356,(#79361,#79407),.PCURVE_S1.); +#79356 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79357,#79358,#79359,#79360 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#76965 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) +#79357 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) ); -#76966 = CARTESIAN_POINT('',(1.292375921036,-0.53683376285,0.967717466) +#79358 = CARTESIAN_POINT('',(1.292375921036,-0.53683376285,0.967717466) ); -#76967 = CARTESIAN_POINT('',(1.25680534294,-0.551917855478, +#79359 = CARTESIAN_POINT('',(1.25680534294,-0.551917855478, 0.966047546673)); -#76968 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) - ); -#76969 = PCURVE('',#76970,#76987); -#76970 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#76971,#76972,#76973,#76974) - ,(#76975,#76976,#76977,#76978) - ,(#76979,#76980,#76981,#76982) - ,(#76983,#76984,#76985,#76986 +#79360 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) + ); +#79361 = PCURVE('',#79362,#79379); +#79362 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79363,#79364,#79365,#79366) + ,(#79367,#79368,#79369,#79370) + ,(#79371,#79372,#79373,#79374) + ,(#79375,#79376,#79377,#79378 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#76971 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) +#79363 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255) ); -#76972 = CARTESIAN_POINT('',(1.217861391,-0.547103709313,0.984014184754) +#79364 = CARTESIAN_POINT('',(1.217861391,-0.547103709313,0.984014184754) ); -#76973 = CARTESIAN_POINT('',(1.217861391,-0.526270589279,1.)); -#76974 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#76975 = CARTESIAN_POINT('',(1.255881450408,-0.551937603265, +#79365 = CARTESIAN_POINT('',(1.217861391,-0.526270589279,1.)); +#79366 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#79367 = CARTESIAN_POINT('',(1.255881450408,-0.551937603265, 0.965973846926)); -#76976 = CARTESIAN_POINT('',(1.254463088209,-0.545238584914, +#79368 = CARTESIAN_POINT('',(1.254463088209,-0.545238584914, 0.985681523985)); -#76977 = CARTESIAN_POINT('',(1.249230002437,-0.525223961408,1.)); -#76978 = CARTESIAN_POINT('',(1.243749871723,-0.504453973629,1.)); -#76979 = CARTESIAN_POINT('',(1.293021890319,-0.536187793567,0.967717466) +#79369 = CARTESIAN_POINT('',(1.249230002437,-0.525223961408,1.)); +#79370 = CARTESIAN_POINT('',(1.243749871723,-0.504453973629,1.)); +#79371 = CARTESIAN_POINT('',(1.293021890319,-0.536187793567,0.967717466) ); -#76980 = CARTESIAN_POINT('',(1.289327515655,-0.529788010173, +#79372 = CARTESIAN_POINT('',(1.289327515655,-0.529788010173, 0.986553421368)); -#76981 = CARTESIAN_POINT('',(1.279247431202,-0.512326230316,1.)); -#76982 = CARTESIAN_POINT('',(1.268821632546,-0.494265568045,1.)); -#76983 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) +#79373 = CARTESIAN_POINT('',(1.279247431202,-0.512326230316,1.)); +#79374 = CARTESIAN_POINT('',(1.268821632546,-0.494265568045,1.)); +#79375 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) ); -#76984 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, +#79376 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, 0.986553421368)); -#76985 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); -#76986 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#76987 = DEFINITIONAL_REPRESENTATION('',(#76988),#77014); -#76988 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#76989,#76990,#76991,#76992, - #76993,#76994,#76995,#76996,#76997,#76998,#76999,#77000,#77001, - #77002,#77003,#77004,#77005,#77006,#77007,#77008,#77009,#77010, - #77011,#77012,#77013),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79377 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); +#79378 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#79379 = DEFINITIONAL_REPRESENTATION('',(#79380),#79406); +#79380 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79381,#79382,#79383,#79384, + #79385,#79386,#79387,#79388,#79389,#79390,#79391,#79392,#79393, + #79394,#79395,#79396,#79397,#79398,#79399,#79400,#79401,#79402, + #79403,#79404,#79405),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -95223,47 +98212,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#76989 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#76990 = CARTESIAN_POINT('',(6.272059551128,2.972804133168E-006)); -#76991 = CARTESIAN_POINT('',(6.249732638972,-1.037052467567E-005)); -#76992 = CARTESIAN_POINT('',(6.216039360813,-5.446484095684E-005)); -#76993 = CARTESIAN_POINT('',(6.182166930891,-8.868396576145E-005)); -#76994 = CARTESIAN_POINT('',(6.148137469616,-7.965797689896E-005)); -#76995 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); -#76996 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); -#76997 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#76998 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); -#76999 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#77000 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#77001 = CARTESIAN_POINT('',(5.907265074214,-8.346461194622E-005)); -#77002 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); -#77003 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#77004 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); -#77005 = CARTESIAN_POINT('',(5.769199593774,-8.542361824739E-005)); -#77006 = CARTESIAN_POINT('',(5.734821280547,-8.593542635488E-005)); -#77007 = CARTESIAN_POINT('',(5.700537102678,-8.687405903438E-005)); -#77008 = CARTESIAN_POINT('',(5.666367464031,-8.643182884201E-005)); -#77009 = CARTESIAN_POINT('',(5.632333796998,-9.13595781352E-005)); -#77010 = CARTESIAN_POINT('',(5.598455804408,-3.211524037865E-005)); -#77011 = CARTESIAN_POINT('',(5.564759360757,-7.920748676221E-006)); -#77012 = CARTESIAN_POINT('',(5.542431620278,5.702886411975E-008)); -#77013 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77015 = PCURVE('',#77016,#77021); -#77016 = CYLINDRICAL_SURFACE('',#77017,0.15); -#77017 = AXIS2_PLACEMENT_3D('',#77018,#77019,#77020); -#77018 = CARTESIAN_POINT('',(1.242591262431,-0.432591262431, +#79381 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79382 = CARTESIAN_POINT('',(6.272059551128,2.972804133168E-006)); +#79383 = CARTESIAN_POINT('',(6.249732638972,-1.037052467567E-005)); +#79384 = CARTESIAN_POINT('',(6.216039360813,-5.446484095684E-005)); +#79385 = CARTESIAN_POINT('',(6.182166930891,-8.868396576145E-005)); +#79386 = CARTESIAN_POINT('',(6.148137469616,-7.965797689896E-005)); +#79387 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); +#79388 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); +#79389 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#79390 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); +#79391 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#79392 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#79393 = CARTESIAN_POINT('',(5.907265074214,-8.346461194622E-005)); +#79394 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); +#79395 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#79396 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); +#79397 = CARTESIAN_POINT('',(5.769199593774,-8.542361824739E-005)); +#79398 = CARTESIAN_POINT('',(5.734821280547,-8.593542635488E-005)); +#79399 = CARTESIAN_POINT('',(5.700537102678,-8.687405903438E-005)); +#79400 = CARTESIAN_POINT('',(5.666367464031,-8.643182884201E-005)); +#79401 = CARTESIAN_POINT('',(5.632333796998,-9.13595781352E-005)); +#79402 = CARTESIAN_POINT('',(5.598455804408,-3.211524037865E-005)); +#79403 = CARTESIAN_POINT('',(5.564759360757,-7.920748676221E-006)); +#79404 = CARTESIAN_POINT('',(5.542431620278,5.702886411975E-008)); +#79405 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79407 = PCURVE('',#79408,#79413); +#79408 = CYLINDRICAL_SURFACE('',#79409,0.15); +#79409 = AXIS2_PLACEMENT_3D('',#79410,#79411,#79412); +#79410 = CARTESIAN_POINT('',(1.242591262431,-0.432591262431, 0.831824958842)); -#77019 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); -#77020 = DIRECTION('',(-0.965925826289,1.229180331738E-016, +#79411 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); +#79412 = DIRECTION('',(-0.965925826289,1.229180331738E-016, -0.258819045103)); -#77021 = DEFINITIONAL_REPRESENTATION('',(#77022),#77048); -#77022 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77023,#77024,#77025,#77026, - #77027,#77028,#77029,#77030,#77031,#77032,#77033,#77034,#77035, - #77036,#77037,#77038,#77039,#77040,#77041,#77042,#77043,#77044, - #77045,#77046,#77047),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79413 = DEFINITIONAL_REPRESENTATION('',(#79414),#79440); +#79414 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79415,#79416,#79417,#79418, + #79419,#79420,#79421,#79422,#79423,#79424,#79425,#79426,#79427, + #79428,#79429,#79430,#79431,#79432,#79433,#79434,#79435,#79436, + #79437,#79438,#79439),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -95271,50 +98260,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#77023 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); -#77024 = CARTESIAN_POINT('',(3.90459767512,-8.848137862171E-002)); -#77025 = CARTESIAN_POINT('',(3.926919725,-8.849547019148E-002)); -#77026 = CARTESIAN_POINT('',(3.960597703687,-8.855954147362E-002)); -#77027 = CARTESIAN_POINT('',(3.994453220183,-8.866719302101E-002)); -#77028 = CARTESIAN_POINT('',(4.028468081361,-8.881887923673E-002)); -#77029 = CARTESIAN_POINT('',(4.062623617158,-8.901492043166E-002)); -#77030 = CARTESIAN_POINT('',(4.096900657675,-8.92554804551E-002)); -#77031 = CARTESIAN_POINT('',(4.13127961549,-8.954056735899E-002)); -#77032 = CARTESIAN_POINT('',(4.165740544467,-8.987002954109E-002)); -#77033 = CARTESIAN_POINT('',(4.200263208931,-9.024355483614E-002)); -#77034 = CARTESIAN_POINT('',(4.234827153442,-9.066067061216E-002)); -#77035 = CARTESIAN_POINT('',(4.269411775032,-9.112074542238E-002)); -#77036 = CARTESIAN_POINT('',(4.303996396623,-9.162299206488E-002)); -#77037 = CARTESIAN_POINT('',(4.338560341134,-9.216647205879E-002)); -#77038 = CARTESIAN_POINT('',(4.373083005598,-9.275010147284E-002)); -#77039 = CARTESIAN_POINT('',(4.407543934574,-9.337265803686E-002)); -#77040 = CARTESIAN_POINT('',(4.44192289239,-9.403278942409E-002)); -#77041 = CARTESIAN_POINT('',(4.476199932907,-9.472902264469E-002)); -#77042 = CARTESIAN_POINT('',(4.510355468703,-9.545977421098E-002)); -#77043 = CARTESIAN_POINT('',(4.544370329882,-9.622336170581E-002)); -#77044 = CARTESIAN_POINT('',(4.578225846377,-9.701801370533E-002)); -#77045 = CARTESIAN_POINT('',(4.611903825065,-9.78418886995E-002)); -#77046 = CARTESIAN_POINT('',(4.634225874945,-9.840933791906E-002)); -#77047 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); -#77048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77049 = ORIENTED_EDGE('',*,*,#77050,.T.); -#77050 = EDGE_CURVE('',#76959,#77051,#77053,.T.); -#77051 = VERTEX_POINT('',#77052); -#77052 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#77053 = SURFACE_CURVE('',#77054,(#77059,#77088),.PCURVE_S1.); -#77054 = CIRCLE('',#77055,5.E-002); -#77055 = AXIS2_PLACEMENT_3D('',#77056,#77057,#77058); -#77056 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,0.95)); -#77057 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#77058 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#77059 = PCURVE('',#76970,#77060); -#77060 = DEFINITIONAL_REPRESENTATION('',(#77061),#77087); -#77061 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77062,#77063,#77064,#77065, - #77066,#77067,#77068,#77069,#77070,#77071,#77072,#77073,#77074, - #77075,#77076,#77077,#77078,#77079,#77080,#77081,#77082,#77083, - #77084,#77085,#77086),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79415 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); +#79416 = CARTESIAN_POINT('',(3.90459767512,-8.848137862171E-002)); +#79417 = CARTESIAN_POINT('',(3.926919725,-8.849547019148E-002)); +#79418 = CARTESIAN_POINT('',(3.960597703687,-8.855954147362E-002)); +#79419 = CARTESIAN_POINT('',(3.994453220183,-8.866719302101E-002)); +#79420 = CARTESIAN_POINT('',(4.028468081361,-8.881887923673E-002)); +#79421 = CARTESIAN_POINT('',(4.062623617158,-8.901492043166E-002)); +#79422 = CARTESIAN_POINT('',(4.096900657675,-8.92554804551E-002)); +#79423 = CARTESIAN_POINT('',(4.13127961549,-8.954056735899E-002)); +#79424 = CARTESIAN_POINT('',(4.165740544467,-8.987002954109E-002)); +#79425 = CARTESIAN_POINT('',(4.200263208931,-9.024355483614E-002)); +#79426 = CARTESIAN_POINT('',(4.234827153442,-9.066067061216E-002)); +#79427 = CARTESIAN_POINT('',(4.269411775032,-9.112074542238E-002)); +#79428 = CARTESIAN_POINT('',(4.303996396623,-9.162299206488E-002)); +#79429 = CARTESIAN_POINT('',(4.338560341134,-9.216647205879E-002)); +#79430 = CARTESIAN_POINT('',(4.373083005598,-9.275010147284E-002)); +#79431 = CARTESIAN_POINT('',(4.407543934574,-9.337265803686E-002)); +#79432 = CARTESIAN_POINT('',(4.44192289239,-9.403278942409E-002)); +#79433 = CARTESIAN_POINT('',(4.476199932907,-9.472902264469E-002)); +#79434 = CARTESIAN_POINT('',(4.510355468703,-9.545977421098E-002)); +#79435 = CARTESIAN_POINT('',(4.544370329882,-9.622336170581E-002)); +#79436 = CARTESIAN_POINT('',(4.578225846377,-9.701801370533E-002)); +#79437 = CARTESIAN_POINT('',(4.611903825065,-9.78418886995E-002)); +#79438 = CARTESIAN_POINT('',(4.634225874945,-9.840933791906E-002)); +#79439 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); +#79440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79441 = ORIENTED_EDGE('',*,*,#79442,.T.); +#79442 = EDGE_CURVE('',#79351,#79443,#79445,.T.); +#79443 = VERTEX_POINT('',#79444); +#79444 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#79445 = SURFACE_CURVE('',#79446,(#79451,#79480),.PCURVE_S1.); +#79446 = CIRCLE('',#79447,5.E-002); +#79447 = AXIS2_PLACEMENT_3D('',#79448,#79449,#79450); +#79448 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,0.95)); +#79449 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#79450 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#79451 = PCURVE('',#79362,#79452); +#79452 = DEFINITIONAL_REPRESENTATION('',(#79453),#79479); +#79453 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79454,#79455,#79456,#79457, + #79458,#79459,#79460,#79461,#79462,#79463,#79464,#79465,#79466, + #79467,#79468,#79469,#79470,#79471,#79472,#79473,#79474,#79475, + #79476,#79477,#79478),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -95322,71 +98311,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77062 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#77063 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#77064 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#77065 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#77066 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#77067 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#77068 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#77069 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#77070 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#77071 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#77072 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#77073 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#77074 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#77075 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#77076 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#77077 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#77078 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#77079 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#77080 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#77081 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#77082 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#77083 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#77084 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#77085 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#77086 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77088 = PCURVE('',#77089,#77106); -#77089 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#77090,#77091,#77092,#77093) - ,(#77094,#77095,#77096,#77097) - ,(#77098,#77099,#77100,#77101) - ,(#77102,#77103,#77104,#77105 +#79454 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79455 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#79456 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#79457 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#79458 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#79459 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#79460 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#79461 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#79462 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#79463 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#79464 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#79465 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#79466 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#79467 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#79468 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#79469 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#79470 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#79471 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#79472 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#79473 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#79474 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#79475 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#79476 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#79477 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#79478 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79480 = PCURVE('',#79481,#79498); +#79481 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79482,#79483,#79484,#79485) + ,(#79486,#79487,#79488,#79489) + ,(#79490,#79491,#79492,#79493) + ,(#79494,#79495,#79496,#79497 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#77090 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) +#79482 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) ); -#77091 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, +#79483 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, 0.986553421368)); -#77092 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); -#77093 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#77094 = CARTESIAN_POINT('',(1.346187793567,-0.483021890319,0.967717466) +#79484 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); +#79485 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#79486 = CARTESIAN_POINT('',(1.346187793567,-0.483021890319,0.967717466) ); -#77095 = CARTESIAN_POINT('',(1.339788010173,-0.479327515655, +#79487 = CARTESIAN_POINT('',(1.339788010173,-0.479327515655, 0.986553421368)); -#77096 = CARTESIAN_POINT('',(1.322326230316,-0.469247431202,1.)); -#77097 = CARTESIAN_POINT('',(1.304265568045,-0.458821632546,1.)); -#77098 = CARTESIAN_POINT('',(1.361937603265,-0.445881450408, +#79488 = CARTESIAN_POINT('',(1.322326230316,-0.469247431202,1.)); +#79489 = CARTESIAN_POINT('',(1.304265568045,-0.458821632546,1.)); +#79490 = CARTESIAN_POINT('',(1.361937603265,-0.445881450408, 0.965973846926)); -#77099 = CARTESIAN_POINT('',(1.355238584914,-0.444463088209, +#79491 = CARTESIAN_POINT('',(1.355238584914,-0.444463088209, 0.985681523985)); -#77100 = CARTESIAN_POINT('',(1.335223961408,-0.439230002437,1.)); -#77101 = CARTESIAN_POINT('',(1.314453973629,-0.433749871723,1.)); -#77102 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) - ); -#77103 = CARTESIAN_POINT('',(1.357103709313,-0.407861391,0.984014184754) - ); -#77104 = CARTESIAN_POINT('',(1.336270589279,-0.407861391,1.)); -#77105 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#77106 = DEFINITIONAL_REPRESENTATION('',(#77107),#77133); -#77107 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77108,#77109,#77110,#77111, - #77112,#77113,#77114,#77115,#77116,#77117,#77118,#77119,#77120, - #77121,#77122,#77123,#77124,#77125,#77126,#77127,#77128,#77129, - #77130,#77131,#77132),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79492 = CARTESIAN_POINT('',(1.335223961408,-0.439230002437,1.)); +#79493 = CARTESIAN_POINT('',(1.314453973629,-0.433749871723,1.)); +#79494 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) + ); +#79495 = CARTESIAN_POINT('',(1.357103709313,-0.407861391,0.984014184754) + ); +#79496 = CARTESIAN_POINT('',(1.336270589279,-0.407861391,1.)); +#79497 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#79498 = DEFINITIONAL_REPRESENTATION('',(#79499),#79525); +#79499 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79500,#79501,#79502,#79503, + #79504,#79505,#79506,#79507,#79508,#79509,#79510,#79511,#79512, + #79513,#79514,#79515,#79516,#79517,#79518,#79519,#79520,#79521, + #79522,#79523,#79524),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -95394,54 +98383,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77108 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#77109 = CARTESIAN_POINT('',(-1.392688852623E-015,1.515278164503E-002)); -#77110 = CARTESIAN_POINT('',(-9.628449452701E-016,4.549920749135E-002)); -#77111 = CARTESIAN_POINT('',(1.739110110531E-015,9.109101074357E-002)); -#77112 = CARTESIAN_POINT('',(-1.724871081711E-015,0.136698748187)); -#77113 = CARTESIAN_POINT('',(1.295107148168E-015,0.1822865144)); -#77114 = CARTESIAN_POINT('',(8.060381873871E-016,0.2278300409)); -#77115 = CARTESIAN_POINT('',(-2.06538645198E-015,0.27331674602)); -#77116 = CARTESIAN_POINT('',(1.379945602909E-015,0.318743220066)); -#77117 = CARTESIAN_POINT('',(-1.19027085225E-015,0.364113426255)); -#77118 = CARTESIAN_POINT('',(1.647771114557E-016,0.409436881051)); -#77119 = CARTESIAN_POINT('',(4.913799127153E-016,0.454727066523)); -#77120 = CARTESIAN_POINT('',(8.971598177169E-016,0.5)); -#77121 = CARTESIAN_POINT('',(1.340550616274E-016,0.545272933477)); -#77122 = CARTESIAN_POINT('',(2.524318819079E-016,0.590563118949)); -#77123 = CARTESIAN_POINT('',(1.690560413567E-015,0.635886573745)); -#77124 = CARTESIAN_POINT('',(7.375212679738E-016,0.681256779934)); -#77125 = CARTESIAN_POINT('',(-1.835607109901E-015,0.72668325398)); -#77126 = CARTESIAN_POINT('',(2.426164767721E-015,0.7721699591)); -#77127 = CARTESIAN_POINT('',(1.519062126208E-015,0.8177134856)); -#77128 = CARTESIAN_POINT('',(1.783037821893E-015,0.863301251813)); -#77129 = CARTESIAN_POINT('',(3.621548057198E-016,0.908908989256)); -#77130 = CARTESIAN_POINT('',(5.998332923287E-017,0.954500792509)); -#77131 = CARTESIAN_POINT('',(-4.765899297509E-016,0.984847218355)); -#77132 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#77133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77134 = ORIENTED_EDGE('',*,*,#77135,.F.); -#77135 = EDGE_CURVE('',#77136,#77051,#77138,.T.); -#77136 = VERTEX_POINT('',#77137); -#77137 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#77138 = SURFACE_CURVE('',#77139,(#77144,#77173),.PCURVE_S1.); -#77139 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77140,#77141,#77142,#77143 +#79500 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#79501 = CARTESIAN_POINT('',(-1.392688852623E-015,1.515278164503E-002)); +#79502 = CARTESIAN_POINT('',(-9.628449452701E-016,4.549920749135E-002)); +#79503 = CARTESIAN_POINT('',(1.739110110531E-015,9.109101074357E-002)); +#79504 = CARTESIAN_POINT('',(-1.724871081711E-015,0.136698748187)); +#79505 = CARTESIAN_POINT('',(1.295107148168E-015,0.1822865144)); +#79506 = CARTESIAN_POINT('',(8.060381873871E-016,0.2278300409)); +#79507 = CARTESIAN_POINT('',(-2.06538645198E-015,0.27331674602)); +#79508 = CARTESIAN_POINT('',(1.379945602909E-015,0.318743220066)); +#79509 = CARTESIAN_POINT('',(-1.19027085225E-015,0.364113426255)); +#79510 = CARTESIAN_POINT('',(1.647771114557E-016,0.409436881051)); +#79511 = CARTESIAN_POINT('',(4.913799127153E-016,0.454727066523)); +#79512 = CARTESIAN_POINT('',(8.971598177169E-016,0.5)); +#79513 = CARTESIAN_POINT('',(1.340550616274E-016,0.545272933477)); +#79514 = CARTESIAN_POINT('',(2.524318819079E-016,0.590563118949)); +#79515 = CARTESIAN_POINT('',(1.690560413567E-015,0.635886573745)); +#79516 = CARTESIAN_POINT('',(7.375212679738E-016,0.681256779934)); +#79517 = CARTESIAN_POINT('',(-1.835607109901E-015,0.72668325398)); +#79518 = CARTESIAN_POINT('',(2.426164767721E-015,0.7721699591)); +#79519 = CARTESIAN_POINT('',(1.519062126208E-015,0.8177134856)); +#79520 = CARTESIAN_POINT('',(1.783037821893E-015,0.863301251813)); +#79521 = CARTESIAN_POINT('',(3.621548057198E-016,0.908908989256)); +#79522 = CARTESIAN_POINT('',(5.998332923287E-017,0.954500792509)); +#79523 = CARTESIAN_POINT('',(-4.765899297509E-016,0.984847218355)); +#79524 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#79525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79526 = ORIENTED_EDGE('',*,*,#79527,.F.); +#79527 = EDGE_CURVE('',#79528,#79443,#79530,.T.); +#79528 = VERTEX_POINT('',#79529); +#79529 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#79530 = SURFACE_CURVE('',#79531,(#79536,#79565),.PCURVE_S1.); +#79531 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79532,#79533,#79534,#79535 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77140 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#77141 = CARTESIAN_POINT('',(1.24437896527,-0.504453973629,1.)); -#77142 = CARTESIAN_POINT('',(1.268390986358,-0.494696214234,1.)); -#77143 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#77144 = PCURVE('',#76970,#77145); -#77145 = DEFINITIONAL_REPRESENTATION('',(#77146),#77172); -#77146 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77147,#77148,#77149,#77150, - #77151,#77152,#77153,#77154,#77155,#77156,#77157,#77158,#77159, - #77160,#77161,#77162,#77163,#77164,#77165,#77166,#77167,#77168, - #77169,#77170,#77171),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79532 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#79533 = CARTESIAN_POINT('',(1.24437896527,-0.504453973629,1.)); +#79534 = CARTESIAN_POINT('',(1.268390986358,-0.494696214234,1.)); +#79535 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#79536 = PCURVE('',#79362,#79537); +#79537 = DEFINITIONAL_REPRESENTATION('',(#79538),#79564); +#79538 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79539,#79540,#79541,#79542, + #79543,#79544,#79545,#79546,#79547,#79548,#79549,#79550,#79551, + #79552,#79553,#79554,#79555,#79556,#79557,#79558,#79559,#79560, + #79561,#79562,#79563),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -95449,62 +98438,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#77147 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77148 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#77149 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#77150 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#77151 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#77152 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#77153 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#77154 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#77155 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#77156 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#77157 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#77158 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#77159 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#77160 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#77161 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#77162 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#77163 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#77164 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#77165 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#77166 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#77167 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#77168 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#77169 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#77170 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#77171 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77173 = PCURVE('',#76871,#77174); -#77174 = DEFINITIONAL_REPRESENTATION('',(#77175),#77180); -#77175 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77176,#77177,#77178,#77179 +#79539 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79540 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#79541 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#79542 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#79543 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#79544 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#79545 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#79546 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#79547 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#79548 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#79549 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#79550 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#79551 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#79552 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#79553 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#79554 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#79555 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#79556 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#79557 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#79558 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#79559 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#79560 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#79561 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#79562 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#79563 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79565 = PCURVE('',#79263,#79566); +#79566 = DEFINITIONAL_REPRESENTATION('',(#79567),#79572); +#79567 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79568,#79569,#79570,#79571 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77176 = CARTESIAN_POINT('',(-0.242138609,0.145546026371)); -#77177 = CARTESIAN_POINT('',(-0.21562103473,0.145546026371)); -#77178 = CARTESIAN_POINT('',(-0.191609013642,0.155303785766)); -#77179 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); -#77180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77181 = ORIENTED_EDGE('',*,*,#77182,.F.); -#77182 = EDGE_CURVE('',#76961,#77136,#77183,.T.); -#77183 = SURFACE_CURVE('',#77184,(#77189,#77218),.PCURVE_S1.); -#77184 = CIRCLE('',#77185,5.E-002); -#77185 = AXIS2_PLACEMENT_3D('',#77186,#77187,#77188); -#77186 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,0.95)); -#77187 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#77188 = DIRECTION('',(0.E+000,0.E+000,1.)); -#77189 = PCURVE('',#76970,#77190); -#77190 = DEFINITIONAL_REPRESENTATION('',(#77191),#77217); -#77191 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77192,#77193,#77194,#77195, - #77196,#77197,#77198,#77199,#77200,#77201,#77202,#77203,#77204, - #77205,#77206,#77207,#77208,#77209,#77210,#77211,#77212,#77213, - #77214,#77215,#77216),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79568 = CARTESIAN_POINT('',(-0.242138609,0.145546026371)); +#79569 = CARTESIAN_POINT('',(-0.21562103473,0.145546026371)); +#79570 = CARTESIAN_POINT('',(-0.191609013642,0.155303785766)); +#79571 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); +#79572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79573 = ORIENTED_EDGE('',*,*,#79574,.F.); +#79574 = EDGE_CURVE('',#79353,#79528,#79575,.T.); +#79575 = SURFACE_CURVE('',#79576,(#79581,#79610),.PCURVE_S1.); +#79576 = CIRCLE('',#79577,5.E-002); +#79577 = AXIS2_PLACEMENT_3D('',#79578,#79579,#79580); +#79578 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,0.95)); +#79579 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#79580 = DIRECTION('',(0.E+000,0.E+000,1.)); +#79581 = PCURVE('',#79362,#79582); +#79582 = DEFINITIONAL_REPRESENTATION('',(#79583),#79609); +#79583 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79584,#79585,#79586,#79587, + #79588,#79589,#79590,#79591,#79592,#79593,#79594,#79595,#79596, + #79597,#79598,#79599,#79600,#79601,#79602,#79603,#79604,#79605, + #79606,#79607,#79608),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -95512,111 +98501,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#77192 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77193 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#77194 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#77195 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#77196 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#77197 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#77198 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#77199 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#77200 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#77201 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#77202 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#77203 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#77204 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#77205 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#77206 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#77207 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#77208 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#77209 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#77210 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#77211 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#77212 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#77213 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#77214 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#77215 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#77216 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77218 = PCURVE('',#77219,#77224); -#77219 = CYLINDRICAL_SURFACE('',#77220,5.E-002); -#77220 = AXIS2_PLACEMENT_3D('',#77221,#77222,#77223); -#77221 = CARTESIAN_POINT('',(1.46,-0.504453973629,0.95)); -#77222 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77223 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#77224 = DEFINITIONAL_REPRESENTATION('',(#77225),#77228); -#77225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#77226,#77227),.UNSPECIFIED., +#79584 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79585 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#79586 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#79587 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#79588 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#79589 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#79590 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#79591 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#79592 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#79593 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#79594 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#79595 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#79596 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#79597 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#79598 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#79599 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#79600 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#79601 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#79602 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#79603 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#79604 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#79605 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#79606 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#79607 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#79608 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79610 = PCURVE('',#79611,#79616); +#79611 = CYLINDRICAL_SURFACE('',#79612,5.E-002); +#79612 = AXIS2_PLACEMENT_3D('',#79613,#79614,#79615); +#79613 = CARTESIAN_POINT('',(1.46,-0.504453973629,0.95)); +#79614 = DIRECTION('',(1.,0.E+000,0.E+000)); +#79615 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#79616 = DEFINITIONAL_REPRESENTATION('',(#79617),#79620); +#79617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79618,#79619),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#77226 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); -#77227 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); -#77228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#79618 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); +#79619 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); +#79620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#77229 = ADVANCED_FACE('',(#77230),#77245,.T.); -#77230 = FACE_BOUND('',#77231,.T.); -#77231 = EDGE_LOOP('',(#77232,#77324,#77409,#77456)); -#77232 = ORIENTED_EDGE('',*,*,#77233,.F.); -#77233 = EDGE_CURVE('',#77234,#77236,#77238,.T.); -#77234 = VERTEX_POINT('',#77235); -#77235 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) +#79621 = ADVANCED_FACE('',(#79622),#79637,.T.); +#79622 = FACE_BOUND('',#79623,.T.); +#79623 = EDGE_LOOP('',(#79624,#79716,#79801,#79848)); +#79624 = ORIENTED_EDGE('',*,*,#79625,.F.); +#79625 = EDGE_CURVE('',#79626,#79628,#79630,.T.); +#79626 = VERTEX_POINT('',#79627); +#79627 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) ); -#77236 = VERTEX_POINT('',#77237); -#77237 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) +#79628 = VERTEX_POINT('',#79629); +#79629 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) ); -#77238 = SURFACE_CURVE('',#77239,(#77244,#77290),.PCURVE_S1.); -#77239 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77240,#77241,#77242,#77243 +#79630 = SURFACE_CURVE('',#79631,(#79636,#79682),.PCURVE_S1.); +#79631 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79632,#79633,#79634,#79635 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77240 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) +#79632 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) ); -#77241 = CARTESIAN_POINT('',(-1.292375921036,0.53683376285,0.967717466) +#79633 = CARTESIAN_POINT('',(-1.292375921036,0.53683376285,0.967717466) ); -#77242 = CARTESIAN_POINT('',(-1.25680534294,0.551917855478, +#79634 = CARTESIAN_POINT('',(-1.25680534294,0.551917855478, 0.966047546673)); -#77243 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) - ); -#77244 = PCURVE('',#77245,#77262); -#77245 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#77246,#77247,#77248,#77249) - ,(#77250,#77251,#77252,#77253) - ,(#77254,#77255,#77256,#77257) - ,(#77258,#77259,#77260,#77261 +#79635 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) + ); +#79636 = PCURVE('',#79637,#79654); +#79637 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79638,#79639,#79640,#79641) + ,(#79642,#79643,#79644,#79645) + ,(#79646,#79647,#79648,#79649) + ,(#79650,#79651,#79652,#79653 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#77246 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) +#79638 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255) ); -#77247 = CARTESIAN_POINT('',(-1.217861391,0.547103709313,0.984014184754) +#79639 = CARTESIAN_POINT('',(-1.217861391,0.547103709313,0.984014184754) ); -#77248 = CARTESIAN_POINT('',(-1.217861391,0.526270589279,1.)); -#77249 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#77250 = CARTESIAN_POINT('',(-1.255881450408,0.551937603265, +#79640 = CARTESIAN_POINT('',(-1.217861391,0.526270589279,1.)); +#79641 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#79642 = CARTESIAN_POINT('',(-1.255881450408,0.551937603265, 0.965973846926)); -#77251 = CARTESIAN_POINT('',(-1.254463088209,0.545238584914, +#79643 = CARTESIAN_POINT('',(-1.254463088209,0.545238584914, 0.985681523985)); -#77252 = CARTESIAN_POINT('',(-1.249230002437,0.525223961408,1.)); -#77253 = CARTESIAN_POINT('',(-1.243749871723,0.504453973629,1.)); -#77254 = CARTESIAN_POINT('',(-1.293021890319,0.536187793567,0.967717466) +#79644 = CARTESIAN_POINT('',(-1.249230002437,0.525223961408,1.)); +#79645 = CARTESIAN_POINT('',(-1.243749871723,0.504453973629,1.)); +#79646 = CARTESIAN_POINT('',(-1.293021890319,0.536187793567,0.967717466) ); -#77255 = CARTESIAN_POINT('',(-1.289327515655,0.529788010173, +#79647 = CARTESIAN_POINT('',(-1.289327515655,0.529788010173, 0.986553421368)); -#77256 = CARTESIAN_POINT('',(-1.279247431202,0.512326230316,1.)); -#77257 = CARTESIAN_POINT('',(-1.268821632546,0.494265568045,1.)); -#77258 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) +#79648 = CARTESIAN_POINT('',(-1.279247431202,0.512326230316,1.)); +#79649 = CARTESIAN_POINT('',(-1.268821632546,0.494265568045,1.)); +#79650 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) ); -#77259 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, +#79651 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, 0.986553421368)); -#77260 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); -#77261 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#77262 = DEFINITIONAL_REPRESENTATION('',(#77263),#77289); -#77263 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77264,#77265,#77266,#77267, - #77268,#77269,#77270,#77271,#77272,#77273,#77274,#77275,#77276, - #77277,#77278,#77279,#77280,#77281,#77282,#77283,#77284,#77285, - #77286,#77287,#77288),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79652 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); +#79653 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#79654 = DEFINITIONAL_REPRESENTATION('',(#79655),#79681); +#79655 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79656,#79657,#79658,#79659, + #79660,#79661,#79662,#79663,#79664,#79665,#79666,#79667,#79668, + #79669,#79670,#79671,#79672,#79673,#79674,#79675,#79676,#79677, + #79678,#79679,#79680),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -95624,47 +98613,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#77264 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#77265 = CARTESIAN_POINT('',(6.272059551128,2.972804134475E-006)); -#77266 = CARTESIAN_POINT('',(6.249732638972,-1.037052467297E-005)); -#77267 = CARTESIAN_POINT('',(6.216039360813,-5.446484095426E-005)); -#77268 = CARTESIAN_POINT('',(6.182166930891,-8.868396576214E-005)); -#77269 = CARTESIAN_POINT('',(6.148137469616,-7.965797689878E-005)); -#77270 = CARTESIAN_POINT('',(6.113972837442,-8.226451401253E-005)); -#77271 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); -#77272 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#77273 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); -#77274 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#77275 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#77276 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); -#77277 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); -#77278 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#77279 = CARTESIAN_POINT('',(5.803652201529,-8.48530842991E-005)); -#77280 = CARTESIAN_POINT('',(5.769199593774,-8.542361824737E-005)); -#77281 = CARTESIAN_POINT('',(5.734821280547,-8.593542635494E-005)); -#77282 = CARTESIAN_POINT('',(5.700537102678,-8.687405903416E-005)); -#77283 = CARTESIAN_POINT('',(5.666367464031,-8.643182884285E-005)); -#77284 = CARTESIAN_POINT('',(5.632333796998,-9.135957813208E-005)); -#77285 = CARTESIAN_POINT('',(5.598455804408,-3.211524038017E-005)); -#77286 = CARTESIAN_POINT('',(5.564759360757,-7.920748672451E-006)); -#77287 = CARTESIAN_POINT('',(5.542431620278,5.702886687369E-008)); -#77288 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77290 = PCURVE('',#77291,#77296); -#77291 = CYLINDRICAL_SURFACE('',#77292,0.15); -#77292 = AXIS2_PLACEMENT_3D('',#77293,#77294,#77295); -#77293 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, +#79656 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79657 = CARTESIAN_POINT('',(6.272059551128,2.972804134475E-006)); +#79658 = CARTESIAN_POINT('',(6.249732638972,-1.037052467297E-005)); +#79659 = CARTESIAN_POINT('',(6.216039360813,-5.446484095426E-005)); +#79660 = CARTESIAN_POINT('',(6.182166930891,-8.868396576214E-005)); +#79661 = CARTESIAN_POINT('',(6.148137469616,-7.965797689878E-005)); +#79662 = CARTESIAN_POINT('',(6.113972837442,-8.226451401253E-005)); +#79663 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); +#79664 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#79665 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); +#79666 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#79667 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#79668 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); +#79669 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); +#79670 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#79671 = CARTESIAN_POINT('',(5.803652201529,-8.48530842991E-005)); +#79672 = CARTESIAN_POINT('',(5.769199593774,-8.542361824737E-005)); +#79673 = CARTESIAN_POINT('',(5.734821280547,-8.593542635494E-005)); +#79674 = CARTESIAN_POINT('',(5.700537102678,-8.687405903416E-005)); +#79675 = CARTESIAN_POINT('',(5.666367464031,-8.643182884285E-005)); +#79676 = CARTESIAN_POINT('',(5.632333796998,-9.135957813208E-005)); +#79677 = CARTESIAN_POINT('',(5.598455804408,-3.211524038017E-005)); +#79678 = CARTESIAN_POINT('',(5.564759360757,-7.920748672451E-006)); +#79679 = CARTESIAN_POINT('',(5.542431620278,5.702886687369E-008)); +#79680 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79682 = PCURVE('',#79683,#79688); +#79683 = CYLINDRICAL_SURFACE('',#79684,0.15); +#79684 = AXIS2_PLACEMENT_3D('',#79685,#79686,#79687); +#79685 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, 0.527229017938)); -#77294 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); -#77295 = DIRECTION('',(-0.965925826289,3.026618127129E-017, +#79686 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); +#79687 = DIRECTION('',(-0.965925826289,3.026618127129E-017, 0.258819045103)); -#77296 = DEFINITIONAL_REPRESENTATION('',(#77297),#77323); -#77297 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77298,#77299,#77300,#77301, - #77302,#77303,#77304,#77305,#77306,#77307,#77308,#77309,#77310, - #77311,#77312,#77313,#77314,#77315,#77316,#77317,#77318,#77319, - #77320,#77321,#77322),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79688 = DEFINITIONAL_REPRESENTATION('',(#79689),#79715); +#79689 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79690,#79691,#79692,#79693, + #79694,#79695,#79696,#79697,#79698,#79699,#79700,#79701,#79702, + #79703,#79704,#79705,#79706,#79707,#79708,#79709,#79710,#79711, + #79712,#79713,#79714),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -95672,50 +98661,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#77298 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); -#77299 = CARTESIAN_POINT('',(0.76300502153,-0.414213027833)); -#77300 = CARTESIAN_POINT('',(0.78532707141,-0.414227119403)); -#77301 = CARTESIAN_POINT('',(0.819005050097,-0.414291190685)); -#77302 = CARTESIAN_POINT('',(0.852860566593,-0.414398842232)); -#77303 = CARTESIAN_POINT('',(0.886875427771,-0.414550528448)); -#77304 = CARTESIAN_POINT('',(0.921030963568,-0.414746569643)); -#77305 = CARTESIAN_POINT('',(0.955308004085,-0.414987129667)); -#77306 = CARTESIAN_POINT('',(0.9896869619,-0.41527221657)); -#77307 = CARTESIAN_POINT('',(1.024147890877,-0.415601678753)); -#77308 = CARTESIAN_POINT('',(1.058670555341,-0.415975204048)); -#77309 = CARTESIAN_POINT('',(1.093234499852,-0.416392319824)); -#77310 = CARTESIAN_POINT('',(1.127819121442,-0.416852394634)); -#77311 = CARTESIAN_POINT('',(1.162403743033,-0.417354641276)); -#77312 = CARTESIAN_POINT('',(1.196967687544,-0.41789812127)); -#77313 = CARTESIAN_POINT('',(1.231490352008,-0.418481750684)); -#77314 = CARTESIAN_POINT('',(1.265951280985,-0.419104307248)); -#77315 = CARTESIAN_POINT('',(1.3003302388,-0.419764438636)); -#77316 = CARTESIAN_POINT('',(1.334607279317,-0.420460671856)); -#77317 = CARTESIAN_POINT('',(1.368762815114,-0.421191423422)); -#77318 = CARTESIAN_POINT('',(1.402777676292,-0.421955010917)); -#77319 = CARTESIAN_POINT('',(1.436633192788,-0.422749662917)); -#77320 = CARTESIAN_POINT('',(1.470311171475,-0.423573537911)); -#77321 = CARTESIAN_POINT('',(1.492633221355,-0.424140987131)); -#77322 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); -#77323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77324 = ORIENTED_EDGE('',*,*,#77325,.T.); -#77325 = EDGE_CURVE('',#77234,#77326,#77328,.T.); -#77326 = VERTEX_POINT('',#77327); -#77327 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#77328 = SURFACE_CURVE('',#77329,(#77334,#77363),.PCURVE_S1.); -#77329 = CIRCLE('',#77330,5.E-002); -#77330 = AXIS2_PLACEMENT_3D('',#77331,#77332,#77333); -#77331 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,0.95)); -#77332 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#77333 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#77334 = PCURVE('',#77245,#77335); -#77335 = DEFINITIONAL_REPRESENTATION('',(#77336),#77362); -#77336 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77337,#77338,#77339,#77340, - #77341,#77342,#77343,#77344,#77345,#77346,#77347,#77348,#77349, - #77350,#77351,#77352,#77353,#77354,#77355,#77356,#77357,#77358, - #77359,#77360,#77361),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79690 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); +#79691 = CARTESIAN_POINT('',(0.76300502153,-0.414213027833)); +#79692 = CARTESIAN_POINT('',(0.78532707141,-0.414227119403)); +#79693 = CARTESIAN_POINT('',(0.819005050097,-0.414291190685)); +#79694 = CARTESIAN_POINT('',(0.852860566593,-0.414398842232)); +#79695 = CARTESIAN_POINT('',(0.886875427771,-0.414550528448)); +#79696 = CARTESIAN_POINT('',(0.921030963568,-0.414746569643)); +#79697 = CARTESIAN_POINT('',(0.955308004085,-0.414987129667)); +#79698 = CARTESIAN_POINT('',(0.9896869619,-0.41527221657)); +#79699 = CARTESIAN_POINT('',(1.024147890877,-0.415601678753)); +#79700 = CARTESIAN_POINT('',(1.058670555341,-0.415975204048)); +#79701 = CARTESIAN_POINT('',(1.093234499852,-0.416392319824)); +#79702 = CARTESIAN_POINT('',(1.127819121442,-0.416852394634)); +#79703 = CARTESIAN_POINT('',(1.162403743033,-0.417354641276)); +#79704 = CARTESIAN_POINT('',(1.196967687544,-0.41789812127)); +#79705 = CARTESIAN_POINT('',(1.231490352008,-0.418481750684)); +#79706 = CARTESIAN_POINT('',(1.265951280985,-0.419104307248)); +#79707 = CARTESIAN_POINT('',(1.3003302388,-0.419764438636)); +#79708 = CARTESIAN_POINT('',(1.334607279317,-0.420460671856)); +#79709 = CARTESIAN_POINT('',(1.368762815114,-0.421191423422)); +#79710 = CARTESIAN_POINT('',(1.402777676292,-0.421955010917)); +#79711 = CARTESIAN_POINT('',(1.436633192788,-0.422749662917)); +#79712 = CARTESIAN_POINT('',(1.470311171475,-0.423573537911)); +#79713 = CARTESIAN_POINT('',(1.492633221355,-0.424140987131)); +#79714 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); +#79715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79716 = ORIENTED_EDGE('',*,*,#79717,.T.); +#79717 = EDGE_CURVE('',#79626,#79718,#79720,.T.); +#79718 = VERTEX_POINT('',#79719); +#79719 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#79720 = SURFACE_CURVE('',#79721,(#79726,#79755),.PCURVE_S1.); +#79721 = CIRCLE('',#79722,5.E-002); +#79722 = AXIS2_PLACEMENT_3D('',#79723,#79724,#79725); +#79723 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,0.95)); +#79724 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#79725 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#79726 = PCURVE('',#79637,#79727); +#79727 = DEFINITIONAL_REPRESENTATION('',(#79728),#79754); +#79728 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79729,#79730,#79731,#79732, + #79733,#79734,#79735,#79736,#79737,#79738,#79739,#79740,#79741, + #79742,#79743,#79744,#79745,#79746,#79747,#79748,#79749,#79750, + #79751,#79752,#79753),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -95723,71 +98712,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77337 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#77338 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#77339 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#77340 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#77341 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#77342 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#77343 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#77344 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#77345 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#77346 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#77347 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#77348 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#77349 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#77350 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#77351 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#77352 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#77353 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#77354 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#77355 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#77356 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#77357 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#77358 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#77359 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#77360 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#77361 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77363 = PCURVE('',#77364,#77381); -#77364 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#77365,#77366,#77367,#77368) - ,(#77369,#77370,#77371,#77372) - ,(#77373,#77374,#77375,#77376) - ,(#77377,#77378,#77379,#77380 +#79729 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79730 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#79731 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#79732 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#79733 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#79734 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#79735 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#79736 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#79737 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#79738 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#79739 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#79740 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#79741 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#79742 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#79743 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#79744 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#79745 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#79746 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#79747 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#79748 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#79749 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#79750 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#79751 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#79752 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#79753 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79755 = PCURVE('',#79756,#79773); +#79756 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79757,#79758,#79759,#79760) + ,(#79761,#79762,#79763,#79764) + ,(#79765,#79766,#79767,#79768) + ,(#79769,#79770,#79771,#79772 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#77365 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) +#79757 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) ); -#77366 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, +#79758 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, 0.986553421368)); -#77367 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); -#77368 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#77369 = CARTESIAN_POINT('',(-1.346187793567,0.483021890319,0.967717466) +#79759 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); +#79760 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#79761 = CARTESIAN_POINT('',(-1.346187793567,0.483021890319,0.967717466) ); -#77370 = CARTESIAN_POINT('',(-1.339788010173,0.479327515655, +#79762 = CARTESIAN_POINT('',(-1.339788010173,0.479327515655, 0.986553421368)); -#77371 = CARTESIAN_POINT('',(-1.322326230316,0.469247431202,1.)); -#77372 = CARTESIAN_POINT('',(-1.304265568045,0.458821632546,1.)); -#77373 = CARTESIAN_POINT('',(-1.361937603265,0.445881450408, +#79763 = CARTESIAN_POINT('',(-1.322326230316,0.469247431202,1.)); +#79764 = CARTESIAN_POINT('',(-1.304265568045,0.458821632546,1.)); +#79765 = CARTESIAN_POINT('',(-1.361937603265,0.445881450408, 0.965973846926)); -#77374 = CARTESIAN_POINT('',(-1.355238584914,0.444463088209, +#79766 = CARTESIAN_POINT('',(-1.355238584914,0.444463088209, 0.985681523985)); -#77375 = CARTESIAN_POINT('',(-1.335223961408,0.439230002437,1.)); -#77376 = CARTESIAN_POINT('',(-1.314453973629,0.433749871723,1.)); -#77377 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) - ); -#77378 = CARTESIAN_POINT('',(-1.357103709313,0.407861391,0.984014184754) - ); -#77379 = CARTESIAN_POINT('',(-1.336270589279,0.407861391,1.)); -#77380 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#77381 = DEFINITIONAL_REPRESENTATION('',(#77382),#77408); -#77382 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77383,#77384,#77385,#77386, - #77387,#77388,#77389,#77390,#77391,#77392,#77393,#77394,#77395, - #77396,#77397,#77398,#77399,#77400,#77401,#77402,#77403,#77404, - #77405,#77406,#77407),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79767 = CARTESIAN_POINT('',(-1.335223961408,0.439230002437,1.)); +#79768 = CARTESIAN_POINT('',(-1.314453973629,0.433749871723,1.)); +#79769 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) + ); +#79770 = CARTESIAN_POINT('',(-1.357103709313,0.407861391,0.984014184754) + ); +#79771 = CARTESIAN_POINT('',(-1.336270589279,0.407861391,1.)); +#79772 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#79773 = DEFINITIONAL_REPRESENTATION('',(#79774),#79800); +#79774 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79775,#79776,#79777,#79778, + #79779,#79780,#79781,#79782,#79783,#79784,#79785,#79786,#79787, + #79788,#79789,#79790,#79791,#79792,#79793,#79794,#79795,#79796, + #79797,#79798,#79799),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -95795,54 +98784,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77383 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#77384 = CARTESIAN_POINT('',(-5.97196979057E-016,1.515278164504E-002)); -#77385 = CARTESIAN_POINT('',(-2.300290560433E-016,4.549920749135E-002)); -#77386 = CARTESIAN_POINT('',(2.351976805257E-017,9.109101074357E-002)); -#77387 = CARTESIAN_POINT('',(-1.077052714274E-015,0.136698748187)); -#77388 = CARTESIAN_POINT('',(3.256854623462E-016,0.1822865144)); -#77389 = CARTESIAN_POINT('',(-4.097288967669E-016,0.2278300409)); -#77390 = CARTESIAN_POINT('',(-1.672479737944E-015,0.27331674602)); -#77391 = CARTESIAN_POINT('',(1.332393111868E-015,0.318743220066)); -#77392 = CARTESIAN_POINT('',(-2.039656136759E-015,0.364113426255)); -#77393 = CARTESIAN_POINT('',(-1.328144975024E-015,0.409436881051)); -#77394 = CARTESIAN_POINT('',(1.686259519686E-015,0.454727066523)); -#77395 = CARTESIAN_POINT('',(-1.485085254245E-015,0.5)); -#77396 = CARTESIAN_POINT('',(-2.107721094731E-015,0.545272933477)); -#77397 = CARTESIAN_POINT('',(6.424773659417E-016,0.590563118949)); -#77398 = CARTESIAN_POINT('',(-3.238482269288E-015,0.635886573745)); -#77399 = CARTESIAN_POINT('',(6.910290152852E-016,0.681256779934)); -#77400 = CARTESIAN_POINT('',(-2.327227246002E-015,0.72668325398)); -#77401 = CARTESIAN_POINT('',(5.7970355512E-016,0.7721699591)); -#77402 = CARTESIAN_POINT('',(1.129336876171E-015,0.8177134856)); -#77403 = CARTESIAN_POINT('',(-1.149947593023E-015,0.863301251813)); -#77404 = CARTESIAN_POINT('',(-2.747238813904E-015,0.908908989256)); -#77405 = CARTESIAN_POINT('',(2.063513688634E-016,0.954500792509)); -#77406 = CARTESIAN_POINT('',(2.617768229511E-016,0.984847218355)); -#77407 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#77408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77409 = ORIENTED_EDGE('',*,*,#77410,.F.); -#77410 = EDGE_CURVE('',#77411,#77326,#77413,.T.); -#77411 = VERTEX_POINT('',#77412); -#77412 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#77413 = SURFACE_CURVE('',#77414,(#77419,#77448),.PCURVE_S1.); -#77414 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77415,#77416,#77417,#77418 +#79775 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#79776 = CARTESIAN_POINT('',(-5.97196979057E-016,1.515278164504E-002)); +#79777 = CARTESIAN_POINT('',(-2.300290560433E-016,4.549920749135E-002)); +#79778 = CARTESIAN_POINT('',(2.351976805257E-017,9.109101074357E-002)); +#79779 = CARTESIAN_POINT('',(-1.077052714274E-015,0.136698748187)); +#79780 = CARTESIAN_POINT('',(3.256854623462E-016,0.1822865144)); +#79781 = CARTESIAN_POINT('',(-4.097288967669E-016,0.2278300409)); +#79782 = CARTESIAN_POINT('',(-1.672479737944E-015,0.27331674602)); +#79783 = CARTESIAN_POINT('',(1.332393111868E-015,0.318743220066)); +#79784 = CARTESIAN_POINT('',(-2.039656136759E-015,0.364113426255)); +#79785 = CARTESIAN_POINT('',(-1.328144975024E-015,0.409436881051)); +#79786 = CARTESIAN_POINT('',(1.686259519686E-015,0.454727066523)); +#79787 = CARTESIAN_POINT('',(-1.485085254245E-015,0.5)); +#79788 = CARTESIAN_POINT('',(-2.107721094731E-015,0.545272933477)); +#79789 = CARTESIAN_POINT('',(6.424773659417E-016,0.590563118949)); +#79790 = CARTESIAN_POINT('',(-3.238482269288E-015,0.635886573745)); +#79791 = CARTESIAN_POINT('',(6.910290152852E-016,0.681256779934)); +#79792 = CARTESIAN_POINT('',(-2.327227246002E-015,0.72668325398)); +#79793 = CARTESIAN_POINT('',(5.7970355512E-016,0.7721699591)); +#79794 = CARTESIAN_POINT('',(1.129336876171E-015,0.8177134856)); +#79795 = CARTESIAN_POINT('',(-1.149947593023E-015,0.863301251813)); +#79796 = CARTESIAN_POINT('',(-2.747238813904E-015,0.908908989256)); +#79797 = CARTESIAN_POINT('',(2.063513688634E-016,0.954500792509)); +#79798 = CARTESIAN_POINT('',(2.617768229511E-016,0.984847218355)); +#79799 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#79800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79801 = ORIENTED_EDGE('',*,*,#79802,.F.); +#79802 = EDGE_CURVE('',#79803,#79718,#79805,.T.); +#79803 = VERTEX_POINT('',#79804); +#79804 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#79805 = SURFACE_CURVE('',#79806,(#79811,#79840),.PCURVE_S1.); +#79806 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79807,#79808,#79809,#79810 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77415 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#77416 = CARTESIAN_POINT('',(-1.24437896527,0.504453973629,1.)); -#77417 = CARTESIAN_POINT('',(-1.268390986358,0.494696214234,1.)); -#77418 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#77419 = PCURVE('',#77245,#77420); -#77420 = DEFINITIONAL_REPRESENTATION('',(#77421),#77447); -#77421 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77422,#77423,#77424,#77425, - #77426,#77427,#77428,#77429,#77430,#77431,#77432,#77433,#77434, - #77435,#77436,#77437,#77438,#77439,#77440,#77441,#77442,#77443, - #77444,#77445,#77446),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79807 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#79808 = CARTESIAN_POINT('',(-1.24437896527,0.504453973629,1.)); +#79809 = CARTESIAN_POINT('',(-1.268390986358,0.494696214234,1.)); +#79810 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#79811 = PCURVE('',#79637,#79812); +#79812 = DEFINITIONAL_REPRESENTATION('',(#79813),#79839); +#79813 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79814,#79815,#79816,#79817, + #79818,#79819,#79820,#79821,#79822,#79823,#79824,#79825,#79826, + #79827,#79828,#79829,#79830,#79831,#79832,#79833,#79834,#79835, + #79836,#79837,#79838),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -95850,62 +98839,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#77422 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77423 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#77424 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#77425 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#77426 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#77427 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#77428 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#77429 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#77430 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#77431 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#77432 = CARTESIAN_POINT('',(5.838182469935,0.998690095133)); -#77433 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#77434 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#77435 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#77436 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#77437 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#77438 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#77439 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#77440 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#77441 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#77442 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#77443 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#77444 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#77445 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#77446 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77448 = PCURVE('',#76871,#77449); -#77449 = DEFINITIONAL_REPRESENTATION('',(#77450),#77455); -#77450 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77451,#77452,#77453,#77454 +#79814 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79815 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#79816 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#79817 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#79818 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#79819 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#79820 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#79821 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#79822 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#79823 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#79824 = CARTESIAN_POINT('',(5.838182469935,0.998690095133)); +#79825 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#79826 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#79827 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#79828 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#79829 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#79830 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#79831 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#79832 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#79833 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#79834 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#79835 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#79836 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#79837 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#79838 = CARTESIAN_POINT('',(6.28318530718,1.)); +#79839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79840 = PCURVE('',#79263,#79841); +#79841 = DEFINITIONAL_REPRESENTATION('',(#79842),#79847); +#79842 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79843,#79844,#79845,#79846 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77451 = CARTESIAN_POINT('',(-2.677861391,1.154453973629)); -#77452 = CARTESIAN_POINT('',(-2.70437896527,1.154453973629)); -#77453 = CARTESIAN_POINT('',(-2.728390986358,1.144696214234)); -#77454 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); -#77455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77456 = ORIENTED_EDGE('',*,*,#77457,.T.); -#77457 = EDGE_CURVE('',#77411,#77236,#77458,.T.); -#77458 = SURFACE_CURVE('',#77459,(#77464,#77493),.PCURVE_S1.); -#77459 = CIRCLE('',#77460,5.E-002); -#77460 = AXIS2_PLACEMENT_3D('',#77461,#77462,#77463); -#77461 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,0.95)); -#77462 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#77463 = DIRECTION('',(0.E+000,0.E+000,1.)); -#77464 = PCURVE('',#77245,#77465); -#77465 = DEFINITIONAL_REPRESENTATION('',(#77466),#77492); -#77466 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77467,#77468,#77469,#77470, - #77471,#77472,#77473,#77474,#77475,#77476,#77477,#77478,#77479, - #77480,#77481,#77482,#77483,#77484,#77485,#77486,#77487,#77488, - #77489,#77490,#77491),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79843 = CARTESIAN_POINT('',(-2.677861391,1.154453973629)); +#79844 = CARTESIAN_POINT('',(-2.70437896527,1.154453973629)); +#79845 = CARTESIAN_POINT('',(-2.728390986358,1.144696214234)); +#79846 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); +#79847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79848 = ORIENTED_EDGE('',*,*,#79849,.T.); +#79849 = EDGE_CURVE('',#79803,#79628,#79850,.T.); +#79850 = SURFACE_CURVE('',#79851,(#79856,#79885),.PCURVE_S1.); +#79851 = CIRCLE('',#79852,5.E-002); +#79852 = AXIS2_PLACEMENT_3D('',#79853,#79854,#79855); +#79853 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,0.95)); +#79854 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#79855 = DIRECTION('',(0.E+000,0.E+000,1.)); +#79856 = PCURVE('',#79637,#79857); +#79857 = DEFINITIONAL_REPRESENTATION('',(#79858),#79884); +#79858 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79859,#79860,#79861,#79862, + #79863,#79864,#79865,#79866,#79867,#79868,#79869,#79870,#79871, + #79872,#79873,#79874,#79875,#79876,#79877,#79878,#79879,#79880, + #79881,#79882,#79883),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,5.949986086344E-002,0.118999721727, 0.17849958259,0.237999443454,0.297499304317,0.356999165181, 0.416499026044,0.475998886908,0.535498747771,0.594998608634, @@ -95913,109 +98902,109 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.892497912952,0.951997773815,1.011497634679,1.070997495542, 1.130497356405,1.189997217269,1.249497078132,1.308996938996), .QUASI_UNIFORM_KNOTS.); -#77467 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77468 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#77469 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#77470 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#77471 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#77472 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#77473 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#77474 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#77475 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#77476 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#77477 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); -#77478 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#77479 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#77480 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#77481 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#77482 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#77483 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#77484 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#77485 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#77486 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#77487 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#77488 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#77489 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#77490 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#77491 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77493 = PCURVE('',#77494,#77499); -#77494 = CYLINDRICAL_SURFACE('',#77495,5.E-002); -#77495 = AXIS2_PLACEMENT_3D('',#77496,#77497,#77498); -#77496 = CARTESIAN_POINT('',(1.46,0.504453973629,0.95)); -#77497 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#77498 = DIRECTION('',(0.E+000,0.E+000,1.)); -#77499 = DEFINITIONAL_REPRESENTATION('',(#77500),#77503); -#77500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#77501,#77502),.UNSPECIFIED., +#79859 = CARTESIAN_POINT('',(5.531305892885,1.)); +#79860 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#79861 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#79862 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#79863 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#79864 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#79865 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#79866 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#79867 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#79868 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#79869 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); +#79870 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#79871 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#79872 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#79873 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#79874 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#79875 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#79876 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#79877 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#79878 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#79879 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#79880 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#79881 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#79882 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#79883 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79885 = PCURVE('',#79886,#79891); +#79886 = CYLINDRICAL_SURFACE('',#79887,5.E-002); +#79887 = AXIS2_PLACEMENT_3D('',#79888,#79889,#79890); +#79888 = CARTESIAN_POINT('',(1.46,0.504453973629,0.95)); +#79889 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#79890 = DIRECTION('',(0.E+000,0.E+000,1.)); +#79891 = DEFINITIONAL_REPRESENTATION('',(#79892),#79895); +#79892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79893,#79894),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#77501 = CARTESIAN_POINT('',(0.E+000,2.677861391)); -#77502 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); -#77503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#79893 = CARTESIAN_POINT('',(0.E+000,2.677861391)); +#79894 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); +#79895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#77504 = ADVANCED_FACE('',(#77505),#77520,.T.); -#77505 = FACE_BOUND('',#77506,.T.); -#77506 = EDGE_LOOP('',(#77507,#77599,#77684,#77731)); -#77507 = ORIENTED_EDGE('',*,*,#77508,.F.); -#77508 = EDGE_CURVE('',#77509,#77511,#77513,.T.); -#77509 = VERTEX_POINT('',#77510); -#77510 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#79896 = ADVANCED_FACE('',(#79897),#79912,.T.); +#79897 = FACE_BOUND('',#79898,.T.); +#79898 = EDGE_LOOP('',(#79899,#79991,#80076,#80123)); +#79899 = ORIENTED_EDGE('',*,*,#79900,.F.); +#79900 = EDGE_CURVE('',#79901,#79903,#79905,.T.); +#79901 = VERTEX_POINT('',#79902); +#79902 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#77511 = VERTEX_POINT('',#77512); -#77512 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) +#79903 = VERTEX_POINT('',#79904); +#79904 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) ); -#77513 = SURFACE_CURVE('',#77514,(#77519,#77565),.PCURVE_S1.); -#77514 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77515,#77516,#77517,#77518 +#79905 = SURFACE_CURVE('',#79906,(#79911,#79957),.PCURVE_S1.); +#79906 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79907,#79908,#79909,#79910 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 9.93851991445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77515 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#79907 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#77516 = CARTESIAN_POINT('',(1.34683376285,0.482375921036,0.967717466)); -#77517 = CARTESIAN_POINT('',(1.361917855478,0.44680534294,0.966047546673 +#79908 = CARTESIAN_POINT('',(1.34683376285,0.482375921036,0.967717466)); +#79909 = CARTESIAN_POINT('',(1.361917855478,0.44680534294,0.966047546673 )); -#77518 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) - ); -#77519 = PCURVE('',#77520,#77537); -#77520 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#77521,#77522,#77523,#77524) - ,(#77525,#77526,#77527,#77528) - ,(#77529,#77530,#77531,#77532) - ,(#77533,#77534,#77535,#77536 +#79910 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) + ); +#79911 = PCURVE('',#79912,#79929); +#79912 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#79913,#79914,#79915,#79916) + ,(#79917,#79918,#79919,#79920) + ,(#79921,#79922,#79923,#79924) + ,(#79925,#79926,#79927,#79928 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885, 6.28318530718),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#77521 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) +#79913 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) ); -#77522 = CARTESIAN_POINT('',(1.357103709313,0.407861391,0.984014184754) +#79914 = CARTESIAN_POINT('',(1.357103709313,0.407861391,0.984014184754) ); -#77523 = CARTESIAN_POINT('',(1.336270589279,0.407861391,1.)); -#77524 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#77525 = CARTESIAN_POINT('',(1.361937603265,0.445881450408, +#79915 = CARTESIAN_POINT('',(1.336270589279,0.407861391,1.)); +#79916 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#79917 = CARTESIAN_POINT('',(1.361937603265,0.445881450408, 0.965973846926)); -#77526 = CARTESIAN_POINT('',(1.355238584914,0.444463088209, +#79918 = CARTESIAN_POINT('',(1.355238584914,0.444463088209, 0.985681523985)); -#77527 = CARTESIAN_POINT('',(1.335223961408,0.439230002437,1.)); -#77528 = CARTESIAN_POINT('',(1.314453973629,0.433749871723,1.)); -#77529 = CARTESIAN_POINT('',(1.346187793567,0.483021890319,0.967717466) +#79919 = CARTESIAN_POINT('',(1.335223961408,0.439230002437,1.)); +#79920 = CARTESIAN_POINT('',(1.314453973629,0.433749871723,1.)); +#79921 = CARTESIAN_POINT('',(1.346187793567,0.483021890319,0.967717466) ); -#77530 = CARTESIAN_POINT('',(1.339788010173,0.479327515655, +#79922 = CARTESIAN_POINT('',(1.339788010173,0.479327515655, 0.986553421368)); -#77531 = CARTESIAN_POINT('',(1.322326230316,0.469247431202,1.)); -#77532 = CARTESIAN_POINT('',(1.304265568045,0.458821632546,1.)); -#77533 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#79923 = CARTESIAN_POINT('',(1.322326230316,0.469247431202,1.)); +#79924 = CARTESIAN_POINT('',(1.304265568045,0.458821632546,1.)); +#79925 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#77534 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, +#79926 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, 0.986553421368)); -#77535 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); -#77536 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#77537 = DEFINITIONAL_REPRESENTATION('',(#77538),#77564); -#77538 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77539,#77540,#77541,#77542, - #77543,#77544,#77545,#77546,#77547,#77548,#77549,#77550,#77551, - #77552,#77553,#77554,#77555,#77556,#77557,#77558,#77559,#77560, - #77561,#77562,#77563),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79927 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); +#79928 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#79929 = DEFINITIONAL_REPRESENTATION('',(#79930),#79956); +#79930 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79931,#79932,#79933,#79934, + #79935,#79936,#79937,#79938,#79939,#79940,#79941,#79942,#79943, + #79944,#79945,#79946,#79947,#79948,#79949,#79950,#79951,#79952, + #79953,#79954,#79955),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(9.93851991445E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -96023,47 +99012,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#77539 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#77540 = CARTESIAN_POINT('',(6.272059551128,2.972804133332E-006)); -#77541 = CARTESIAN_POINT('',(6.249732638972,-1.037052467407E-005)); -#77542 = CARTESIAN_POINT('',(6.216039360813,-5.446484095213E-005)); -#77543 = CARTESIAN_POINT('',(6.182166930891,-8.868396576271E-005)); -#77544 = CARTESIAN_POINT('',(6.148137469616,-7.965797689863E-005)); -#77545 = CARTESIAN_POINT('',(6.113972837442,-8.226451401256E-005)); -#77546 = CARTESIAN_POINT('',(6.079693755153,-8.179989506534E-005)); -#77547 = CARTESIAN_POINT('',(6.045320300361,-8.220472162592E-005)); -#77548 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); -#77549 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); -#77550 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); -#77551 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); -#77552 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); -#77553 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); -#77554 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); -#77555 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); -#77556 = CARTESIAN_POINT('',(5.734821280548,-8.593545386255E-005)); -#77557 = CARTESIAN_POINT('',(5.700537102675,-8.687395637438E-005)); -#77558 = CARTESIAN_POINT('',(5.666367464043,-8.643221197436E-005)); -#77559 = CARTESIAN_POINT('',(5.632333796953,-9.13581482658E-005)); -#77560 = CARTESIAN_POINT('',(5.59845580442,-3.211561474274E-005)); -#77561 = CARTESIAN_POINT('',(5.564759360754,-7.920681089086E-006)); -#77562 = CARTESIAN_POINT('',(5.542431620275,5.712075790494E-008)); -#77563 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77565 = PCURVE('',#77566,#77571); -#77566 = CYLINDRICAL_SURFACE('',#77567,0.15); -#77567 = AXIS2_PLACEMENT_3D('',#77568,#77569,#77570); -#77568 = CARTESIAN_POINT('',(1.140884875554,0.330884875554, +#79931 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#79932 = CARTESIAN_POINT('',(6.272059551128,2.972804133332E-006)); +#79933 = CARTESIAN_POINT('',(6.249732638972,-1.037052467407E-005)); +#79934 = CARTESIAN_POINT('',(6.216039360813,-5.446484095213E-005)); +#79935 = CARTESIAN_POINT('',(6.182166930891,-8.868396576271E-005)); +#79936 = CARTESIAN_POINT('',(6.148137469616,-7.965797689863E-005)); +#79937 = CARTESIAN_POINT('',(6.113972837442,-8.226451401256E-005)); +#79938 = CARTESIAN_POINT('',(6.079693755153,-8.179989506534E-005)); +#79939 = CARTESIAN_POINT('',(6.045320300361,-8.220472162592E-005)); +#79940 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); +#79941 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); +#79942 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); +#79943 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); +#79944 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); +#79945 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); +#79946 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); +#79947 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); +#79948 = CARTESIAN_POINT('',(5.734821280548,-8.593545386255E-005)); +#79949 = CARTESIAN_POINT('',(5.700537102675,-8.687395637438E-005)); +#79950 = CARTESIAN_POINT('',(5.666367464043,-8.643221197436E-005)); +#79951 = CARTESIAN_POINT('',(5.632333796953,-9.13581482658E-005)); +#79952 = CARTESIAN_POINT('',(5.59845580442,-3.211561474274E-005)); +#79953 = CARTESIAN_POINT('',(5.564759360754,-7.920681089086E-006)); +#79954 = CARTESIAN_POINT('',(5.542431620275,5.712075790494E-008)); +#79955 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#79956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79957 = PCURVE('',#79958,#79963); +#79958 = CYLINDRICAL_SURFACE('',#79959,0.15); +#79959 = AXIS2_PLACEMENT_3D('',#79960,#79961,#79962); +#79960 = CARTESIAN_POINT('',(1.140884875554,0.330884875554, 1.211398362123)); -#77569 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#77570 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, +#79961 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#79962 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, -0.258819045103)); -#77571 = DEFINITIONAL_REPRESENTATION('',(#77572),#77598); -#77572 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77573,#77574,#77575,#77576, - #77577,#77578,#77579,#77580,#77581,#77582,#77583,#77584,#77585, - #77586,#77587,#77588,#77589,#77590,#77591,#77592,#77593,#77594, - #77595,#77596,#77597),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79963 = DEFINITIONAL_REPRESENTATION('',(#79964),#79990); +#79964 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79965,#79966,#79967,#79968, + #79969,#79970,#79971,#79972,#79973,#79974,#79975,#79976,#79977, + #79978,#79979,#79980,#79981,#79982,#79983,#79984,#79985,#79986, + #79987,#79988,#79989),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(9.93851991445E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -96071,50 +99060,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#77573 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); -#77574 = CARTESIAN_POINT('',(2.40083884653,0.317430368857)); -#77575 = CARTESIAN_POINT('',(2.42316089641,0.317416277287)); -#77576 = CARTESIAN_POINT('',(2.456838875097,0.317352206005)); -#77577 = CARTESIAN_POINT('',(2.490694391593,0.317244554458)); -#77578 = CARTESIAN_POINT('',(2.524709252771,0.317092868242)); -#77579 = CARTESIAN_POINT('',(2.558864788568,0.316896827047)); -#77580 = CARTESIAN_POINT('',(2.593141829085,0.316656267024)); -#77581 = CARTESIAN_POINT('',(2.6275207869,0.31637118012)); -#77582 = CARTESIAN_POINT('',(2.661981715877,0.316041717938)); -#77583 = CARTESIAN_POINT('',(2.696504380341,0.315668192643)); -#77584 = CARTESIAN_POINT('',(2.731068324852,0.315251076867)); -#77585 = CARTESIAN_POINT('',(2.765652946442,0.314791002057)); -#77586 = CARTESIAN_POINT('',(2.800237568033,0.314288755414)); -#77587 = CARTESIAN_POINT('',(2.834801512544,0.31374527542)); -#77588 = CARTESIAN_POINT('',(2.869324177008,0.313161646006)); -#77589 = CARTESIAN_POINT('',(2.903785105985,0.312539089442)); -#77590 = CARTESIAN_POINT('',(2.9381640638,0.311878958055)); -#77591 = CARTESIAN_POINT('',(2.972441104317,0.311182724834)); -#77592 = CARTESIAN_POINT('',(3.006596640113,0.310451973268)); -#77593 = CARTESIAN_POINT('',(3.040611501292,0.309688385773)); -#77594 = CARTESIAN_POINT('',(3.074467017787,0.308893733774)); -#77595 = CARTESIAN_POINT('',(3.108144996475,0.308069858779)); -#77596 = CARTESIAN_POINT('',(3.130467046355,0.30750240956)); -#77597 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); -#77598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77599 = ORIENTED_EDGE('',*,*,#77600,.T.); -#77600 = EDGE_CURVE('',#77509,#77601,#77603,.T.); -#77601 = VERTEX_POINT('',#77602); -#77602 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#77603 = SURFACE_CURVE('',#77604,(#77609,#77638),.PCURVE_S1.); -#77604 = CIRCLE('',#77605,5.E-002); -#77605 = AXIS2_PLACEMENT_3D('',#77606,#77607,#77608); -#77606 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,0.95)); -#77607 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#77608 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#77609 = PCURVE('',#77520,#77610); -#77610 = DEFINITIONAL_REPRESENTATION('',(#77611),#77637); -#77611 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77612,#77613,#77614,#77615, - #77616,#77617,#77618,#77619,#77620,#77621,#77622,#77623,#77624, - #77625,#77626,#77627,#77628,#77629,#77630,#77631,#77632,#77633, - #77634,#77635,#77636),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#79965 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); +#79966 = CARTESIAN_POINT('',(2.40083884653,0.317430368857)); +#79967 = CARTESIAN_POINT('',(2.42316089641,0.317416277287)); +#79968 = CARTESIAN_POINT('',(2.456838875097,0.317352206005)); +#79969 = CARTESIAN_POINT('',(2.490694391593,0.317244554458)); +#79970 = CARTESIAN_POINT('',(2.524709252771,0.317092868242)); +#79971 = CARTESIAN_POINT('',(2.558864788568,0.316896827047)); +#79972 = CARTESIAN_POINT('',(2.593141829085,0.316656267024)); +#79973 = CARTESIAN_POINT('',(2.6275207869,0.31637118012)); +#79974 = CARTESIAN_POINT('',(2.661981715877,0.316041717938)); +#79975 = CARTESIAN_POINT('',(2.696504380341,0.315668192643)); +#79976 = CARTESIAN_POINT('',(2.731068324852,0.315251076867)); +#79977 = CARTESIAN_POINT('',(2.765652946442,0.314791002057)); +#79978 = CARTESIAN_POINT('',(2.800237568033,0.314288755414)); +#79979 = CARTESIAN_POINT('',(2.834801512544,0.31374527542)); +#79980 = CARTESIAN_POINT('',(2.869324177008,0.313161646006)); +#79981 = CARTESIAN_POINT('',(2.903785105985,0.312539089442)); +#79982 = CARTESIAN_POINT('',(2.9381640638,0.311878958055)); +#79983 = CARTESIAN_POINT('',(2.972441104317,0.311182724834)); +#79984 = CARTESIAN_POINT('',(3.006596640113,0.310451973268)); +#79985 = CARTESIAN_POINT('',(3.040611501292,0.309688385773)); +#79986 = CARTESIAN_POINT('',(3.074467017787,0.308893733774)); +#79987 = CARTESIAN_POINT('',(3.108144996475,0.308069858779)); +#79988 = CARTESIAN_POINT('',(3.130467046355,0.30750240956)); +#79989 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); +#79990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#79991 = ORIENTED_EDGE('',*,*,#79992,.T.); +#79992 = EDGE_CURVE('',#79901,#79993,#79995,.T.); +#79993 = VERTEX_POINT('',#79994); +#79994 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#79995 = SURFACE_CURVE('',#79996,(#80001,#80030),.PCURVE_S1.); +#79996 = CIRCLE('',#79997,5.E-002); +#79997 = AXIS2_PLACEMENT_3D('',#79998,#79999,#80000); +#79998 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,0.95)); +#79999 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#80000 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#80001 = PCURVE('',#79912,#80002); +#80002 = DEFINITIONAL_REPRESENTATION('',(#80003),#80029); +#80003 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80004,#80005,#80006,#80007, + #80008,#80009,#80010,#80011,#80012,#80013,#80014,#80015,#80016, + #80017,#80018,#80019,#80020,#80021,#80022,#80023,#80024,#80025, + #80026,#80027,#80028),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -96122,71 +99111,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77612 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#77613 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#77614 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#77615 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#77616 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#77617 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#77618 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#77619 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#77620 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#77621 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#77622 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#77623 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#77624 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#77625 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#77626 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#77627 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#77628 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#77629 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#77630 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#77631 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#77632 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#77633 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#77634 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#77635 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#77636 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77638 = PCURVE('',#77639,#77656); -#77639 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#77640,#77641,#77642,#77643) - ,(#77644,#77645,#77646,#77647) - ,(#77648,#77649,#77650,#77651) - ,(#77652,#77653,#77654,#77655 +#80004 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#80005 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#80006 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#80007 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#80008 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#80009 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#80010 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#80011 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#80012 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#80013 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#80014 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#80015 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#80016 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#80017 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#80018 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#80019 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#80020 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#80021 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#80022 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#80023 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#80024 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#80025 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#80026 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#80027 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#80028 = CARTESIAN_POINT('',(6.28318530718,1.)); +#80029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80030 = PCURVE('',#80031,#80048); +#80031 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#80032,#80033,#80034,#80035) + ,(#80036,#80037,#80038,#80039) + ,(#80040,#80041,#80042,#80043) + ,(#80044,#80045,#80046,#80047 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#77640 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#80032 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#77641 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, +#80033 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, 0.986553421368)); -#77642 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); -#77643 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#77644 = CARTESIAN_POINT('',(1.293021890319,0.536187793567,0.967717466) +#80034 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); +#80035 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#80036 = CARTESIAN_POINT('',(1.293021890319,0.536187793567,0.967717466) ); -#77645 = CARTESIAN_POINT('',(1.289327515655,0.529788010173, +#80037 = CARTESIAN_POINT('',(1.289327515655,0.529788010173, 0.986553421368)); -#77646 = CARTESIAN_POINT('',(1.279247431202,0.512326230316,1.)); -#77647 = CARTESIAN_POINT('',(1.268821632546,0.494265568045,1.)); -#77648 = CARTESIAN_POINT('',(1.255881450408,0.551937603265, +#80038 = CARTESIAN_POINT('',(1.279247431202,0.512326230316,1.)); +#80039 = CARTESIAN_POINT('',(1.268821632546,0.494265568045,1.)); +#80040 = CARTESIAN_POINT('',(1.255881450408,0.551937603265, 0.965973846926)); -#77649 = CARTESIAN_POINT('',(1.254463088209,0.545238584914, +#80041 = CARTESIAN_POINT('',(1.254463088209,0.545238584914, 0.985681523985)); -#77650 = CARTESIAN_POINT('',(1.249230002437,0.525223961408,1.)); -#77651 = CARTESIAN_POINT('',(1.243749871723,0.504453973629,1.)); -#77652 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) - ); -#77653 = CARTESIAN_POINT('',(1.217861391,0.547103709313,0.984014184754) - ); -#77654 = CARTESIAN_POINT('',(1.217861391,0.526270589279,1.)); -#77655 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#77656 = DEFINITIONAL_REPRESENTATION('',(#77657),#77683); -#77657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77658,#77659,#77660,#77661, - #77662,#77663,#77664,#77665,#77666,#77667,#77668,#77669,#77670, - #77671,#77672,#77673,#77674,#77675,#77676,#77677,#77678,#77679, - #77680,#77681,#77682),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80042 = CARTESIAN_POINT('',(1.249230002437,0.525223961408,1.)); +#80043 = CARTESIAN_POINT('',(1.243749871723,0.504453973629,1.)); +#80044 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) + ); +#80045 = CARTESIAN_POINT('',(1.217861391,0.547103709313,0.984014184754) + ); +#80046 = CARTESIAN_POINT('',(1.217861391,0.526270589279,1.)); +#80047 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#80048 = DEFINITIONAL_REPRESENTATION('',(#80049),#80075); +#80049 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80050,#80051,#80052,#80053, + #80054,#80055,#80056,#80057,#80058,#80059,#80060,#80061,#80062, + #80063,#80064,#80065,#80066,#80067,#80068,#80069,#80070,#80071, + #80072,#80073,#80074),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212,0.417153517102, 0.472088888992,0.527024260882,0.581959632772,0.636895004662, 0.691830376553,0.746765748443,0.801701120333,0.856636492223, @@ -96194,54 +99183,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.131313351674,1.186248723564,1.241184095454,1.296119467344, 1.351054839234,1.405990211124,1.460925583015,1.515860954905, 1.570796326795),.QUASI_UNIFORM_KNOTS.); -#77658 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#77659 = CARTESIAN_POINT('',(1.061661611134E-015,1.515278164503E-002)); -#77660 = CARTESIAN_POINT('',(6.739209458866E-016,4.549920749134E-002)); -#77661 = CARTESIAN_POINT('',(-2.253788534801E-015,9.109101074357E-002)); -#77662 = CARTESIAN_POINT('',(1.35298307003E-016,0.136698748187)); -#77663 = CARTESIAN_POINT('',(-2.763061698481E-016,0.1822865144)); -#77664 = CARTESIAN_POINT('',(-1.298830252807E-015,0.2278300409)); -#77665 = CARTESIAN_POINT('',(-3.515607692919E-016,0.27331674602)); -#77666 = CARTESIAN_POINT('',(2.497661180885E-017,0.318743220066)); -#77667 = CARTESIAN_POINT('',(7.334648223176E-016,0.364113426255)); -#77668 = CARTESIAN_POINT('',(7.016373077783E-016,0.409436881051)); -#77669 = CARTESIAN_POINT('',(-1.916593767267E-015,0.454727066523)); -#77670 = CARTESIAN_POINT('',(1.267507683608E-015,0.5)); -#77671 = CARTESIAN_POINT('',(1.162539513313E-016,0.545272933477)); -#77672 = CARTESIAN_POINT('',(-5.556713119141E-016,0.590563118949)); -#77673 = CARTESIAN_POINT('',(1.19988048939E-015,0.635886573745)); -#77674 = CARTESIAN_POINT('',(-1.47765137311E-015,0.681256779934)); -#77675 = CARTESIAN_POINT('',(-6.210166973602E-016,0.72668325398)); -#77676 = CARTESIAN_POINT('',(2.579818538055E-015,0.7721699591)); -#77677 = CARTESIAN_POINT('',(-3.024846433617E-015,0.8177134856)); -#77678 = CARTESIAN_POINT('',(1.042025613774E-015,0.863301251813)); -#77679 = CARTESIAN_POINT('',(1.210297274954E-015,0.908908989256)); -#77680 = CARTESIAN_POINT('',(6.259121812265E-016,0.954500792509)); -#77681 = CARTESIAN_POINT('',(2.663325483931E-016,0.984847218355)); -#77682 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#77683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77684 = ORIENTED_EDGE('',*,*,#77685,.F.); -#77685 = EDGE_CURVE('',#77686,#77601,#77688,.T.); -#77686 = VERTEX_POINT('',#77687); -#77687 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#77688 = SURFACE_CURVE('',#77689,(#77694,#77723),.PCURVE_S1.); -#77689 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77690,#77691,#77692,#77693 +#80050 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#80051 = CARTESIAN_POINT('',(1.061661611134E-015,1.515278164503E-002)); +#80052 = CARTESIAN_POINT('',(6.739209458866E-016,4.549920749134E-002)); +#80053 = CARTESIAN_POINT('',(-2.253788534801E-015,9.109101074357E-002)); +#80054 = CARTESIAN_POINT('',(1.35298307003E-016,0.136698748187)); +#80055 = CARTESIAN_POINT('',(-2.763061698481E-016,0.1822865144)); +#80056 = CARTESIAN_POINT('',(-1.298830252807E-015,0.2278300409)); +#80057 = CARTESIAN_POINT('',(-3.515607692919E-016,0.27331674602)); +#80058 = CARTESIAN_POINT('',(2.497661180885E-017,0.318743220066)); +#80059 = CARTESIAN_POINT('',(7.334648223176E-016,0.364113426255)); +#80060 = CARTESIAN_POINT('',(7.016373077783E-016,0.409436881051)); +#80061 = CARTESIAN_POINT('',(-1.916593767267E-015,0.454727066523)); +#80062 = CARTESIAN_POINT('',(1.267507683608E-015,0.5)); +#80063 = CARTESIAN_POINT('',(1.162539513313E-016,0.545272933477)); +#80064 = CARTESIAN_POINT('',(-5.556713119141E-016,0.590563118949)); +#80065 = CARTESIAN_POINT('',(1.19988048939E-015,0.635886573745)); +#80066 = CARTESIAN_POINT('',(-1.47765137311E-015,0.681256779934)); +#80067 = CARTESIAN_POINT('',(-6.210166973602E-016,0.72668325398)); +#80068 = CARTESIAN_POINT('',(2.579818538055E-015,0.7721699591)); +#80069 = CARTESIAN_POINT('',(-3.024846433617E-015,0.8177134856)); +#80070 = CARTESIAN_POINT('',(1.042025613774E-015,0.863301251813)); +#80071 = CARTESIAN_POINT('',(1.210297274954E-015,0.908908989256)); +#80072 = CARTESIAN_POINT('',(6.259121812265E-016,0.954500792509)); +#80073 = CARTESIAN_POINT('',(2.663325483931E-016,0.984847218355)); +#80074 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#80075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80076 = ORIENTED_EDGE('',*,*,#80077,.F.); +#80077 = EDGE_CURVE('',#80078,#79993,#80080,.T.); +#80078 = VERTEX_POINT('',#80079); +#80079 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#80080 = SURFACE_CURVE('',#80081,(#80086,#80115),.PCURVE_S1.); +#80081 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80082,#80083,#80084,#80085 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77690 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#77691 = CARTESIAN_POINT('',(1.314453973629,0.43437896527,1.)); -#77692 = CARTESIAN_POINT('',(1.304696214234,0.458390986358,1.)); -#77693 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#77694 = PCURVE('',#77520,#77695); -#77695 = DEFINITIONAL_REPRESENTATION('',(#77696),#77722); -#77696 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77697,#77698,#77699,#77700, - #77701,#77702,#77703,#77704,#77705,#77706,#77707,#77708,#77709, - #77710,#77711,#77712,#77713,#77714,#77715,#77716,#77717,#77718, - #77719,#77720,#77721),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80082 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#80083 = CARTESIAN_POINT('',(1.314453973629,0.43437896527,1.)); +#80084 = CARTESIAN_POINT('',(1.304696214234,0.458390986358,1.)); +#80085 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#80086 = PCURVE('',#79912,#80087); +#80087 = DEFINITIONAL_REPRESENTATION('',(#80088),#80114); +#80088 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80089,#80090,#80091,#80092, + #80093,#80094,#80095,#80096,#80097,#80098,#80099,#80100,#80101, + #80102,#80103,#80104,#80105,#80106,#80107,#80108,#80109,#80110, + #80111,#80112,#80113),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -96249,62 +99238,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#77697 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77698 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#77699 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#77700 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#77701 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#77702 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#77703 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#77704 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#77705 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#77706 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#77707 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#77708 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#77709 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#77710 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#77711 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#77712 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#77713 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#77714 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#77715 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#77716 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#77717 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#77718 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#77719 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#77720 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#77721 = CARTESIAN_POINT('',(6.28318530718,1.)); -#77722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77723 = PCURVE('',#76871,#77724); -#77724 = DEFINITIONAL_REPRESENTATION('',(#77725),#77730); -#77725 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#77726,#77727,#77728,#77729 +#80089 = CARTESIAN_POINT('',(5.531305892885,1.)); +#80090 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#80091 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#80092 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#80093 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#80094 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#80095 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#80096 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#80097 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#80098 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#80099 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#80100 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#80101 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#80102 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#80103 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#80104 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#80105 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#80106 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#80107 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#80108 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#80109 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#80110 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#80111 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#80112 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#80113 = CARTESIAN_POINT('',(6.28318530718,1.)); +#80114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80115 = PCURVE('',#79263,#80116); +#80116 = DEFINITIONAL_REPRESENTATION('',(#80117),#80122); +#80117 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80118,#80119,#80120,#80121 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#77726 = CARTESIAN_POINT('',(-0.145546026371,1.057861391)); -#77727 = CARTESIAN_POINT('',(-0.145546026371,1.08437896527)); -#77728 = CARTESIAN_POINT('',(-0.155303785766,1.108390986358)); -#77729 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); -#77730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80118 = CARTESIAN_POINT('',(-0.145546026371,1.057861391)); +#80119 = CARTESIAN_POINT('',(-0.145546026371,1.08437896527)); +#80120 = CARTESIAN_POINT('',(-0.155303785766,1.108390986358)); +#80121 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); +#80122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#77731 = ORIENTED_EDGE('',*,*,#77732,.F.); -#77732 = EDGE_CURVE('',#77511,#77686,#77733,.T.); -#77733 = SURFACE_CURVE('',#77734,(#77739,#77768),.PCURVE_S1.); -#77734 = CIRCLE('',#77735,5.E-002); -#77735 = AXIS2_PLACEMENT_3D('',#77736,#77737,#77738); -#77736 = CARTESIAN_POINT('',(1.314453973629,0.407861391,0.95)); -#77737 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#77738 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#77739 = PCURVE('',#77520,#77740); -#77740 = DEFINITIONAL_REPRESENTATION('',(#77741),#77767); -#77741 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77742,#77743,#77744,#77745, - #77746,#77747,#77748,#77749,#77750,#77751,#77752,#77753,#77754, - #77755,#77756,#77757,#77758,#77759,#77760,#77761,#77762,#77763, - #77764,#77765,#77766),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80123 = ORIENTED_EDGE('',*,*,#80124,.F.); +#80124 = EDGE_CURVE('',#79903,#80078,#80125,.T.); +#80125 = SURFACE_CURVE('',#80126,(#80131,#80160),.PCURVE_S1.); +#80126 = CIRCLE('',#80127,5.E-002); +#80127 = AXIS2_PLACEMENT_3D('',#80128,#80129,#80130); +#80128 = CARTESIAN_POINT('',(1.314453973629,0.407861391,0.95)); +#80129 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#80130 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80131 = PCURVE('',#79912,#80132); +#80132 = DEFINITIONAL_REPRESENTATION('',(#80133),#80159); +#80133 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80134,#80135,#80136,#80137, + #80138,#80139,#80140,#80141,#80142,#80143,#80144,#80145,#80146, + #80147,#80148,#80149,#80150,#80151,#80152,#80153,#80154,#80155, + #80156,#80157,#80158),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594,1.892095575457, 1.951595436321,2.011095297184,2.070595158048,2.130095018911, 2.189594879775,2.249094740638,2.308594601502,2.368094462365, @@ -96312,143 +99301,143 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.665593766682,2.725093627546,2.784593488409,2.844093349273, 2.903593210136,2.963093070999,3.022592931863,3.082092792726, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#77742 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#77743 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#77744 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#77745 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#77746 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#77747 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#77748 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#77749 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#77750 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#77751 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#77752 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#77753 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#77754 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#77755 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#77756 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); -#77757 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#77758 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#77759 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#77760 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#77761 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#77762 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#77763 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#77764 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#77765 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#77766 = CARTESIAN_POINT('',(5.531305892885,1.)); -#77767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77768 = PCURVE('',#77769,#77774); -#77769 = CYLINDRICAL_SURFACE('',#77770,5.E-002); -#77770 = AXIS2_PLACEMENT_3D('',#77771,#77772,#77773); -#77771 = CARTESIAN_POINT('',(1.314453973629,-0.65,0.95)); -#77772 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#77773 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); -#77774 = DEFINITIONAL_REPRESENTATION('',(#77775),#77778); -#77775 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#77776,#77777),.UNSPECIFIED., +#80134 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#80135 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#80136 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#80137 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#80138 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#80139 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#80140 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#80141 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#80142 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#80143 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#80144 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#80145 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#80146 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#80147 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#80148 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); +#80149 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#80150 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#80151 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#80152 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#80153 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#80154 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#80155 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#80156 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#80157 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#80158 = CARTESIAN_POINT('',(5.531305892885,1.)); +#80159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80160 = PCURVE('',#80161,#80166); +#80161 = CYLINDRICAL_SURFACE('',#80162,5.E-002); +#80162 = AXIS2_PLACEMENT_3D('',#80163,#80164,#80165); +#80163 = CARTESIAN_POINT('',(1.314453973629,-0.65,0.95)); +#80164 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#80165 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); +#80166 = DEFINITIONAL_REPRESENTATION('',(#80167),#80170); +#80167 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80168,#80169),.UNSPECIFIED., .F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#77776 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); -#77777 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); -#77778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77779 = ADVANCED_FACE('',(#77780),#77792,.T.); -#77780 = FACE_BOUND('',#77781,.T.); -#77781 = EDGE_LOOP('',(#77782,#77809,#77831,#77876,#77904,#77932,#77960, - #77988,#78011,#78039,#78067,#78095)); -#77782 = ORIENTED_EDGE('',*,*,#77783,.T.); -#77783 = EDGE_CURVE('',#77784,#76961,#77786,.T.); -#77784 = VERTEX_POINT('',#77785); -#77785 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); -#77786 = SURFACE_CURVE('',#77787,(#77791,#77803),.PCURVE_S1.); -#77787 = LINE('',#77788,#77789); -#77788 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, +#80168 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); +#80169 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); +#80170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80171 = ADVANCED_FACE('',(#80172),#80184,.T.); +#80172 = FACE_BOUND('',#80173,.T.); +#80173 = EDGE_LOOP('',(#80174,#80201,#80223,#80268,#80296,#80324,#80352, + #80380,#80403,#80431,#80459,#80487)); +#80174 = ORIENTED_EDGE('',*,*,#80175,.T.); +#80175 = EDGE_CURVE('',#80176,#79353,#80178,.T.); +#80176 = VERTEX_POINT('',#80177); +#80177 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); +#80178 = SURFACE_CURVE('',#80179,(#80183,#80195),.PCURVE_S1.); +#80179 = LINE('',#80180,#80181); +#80180 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, 1.250221218888)); -#77789 = VECTOR('',#77790,1.); -#77790 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#77791 = PCURVE('',#77792,#77797); -#77792 = PLANE('',#77793); -#77793 = AXIS2_PLACEMENT_3D('',#77794,#77795,#77796); -#77794 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#77795 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); -#77796 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#77797 = DEFINITIONAL_REPRESENTATION('',(#77798),#77802); -#77798 = LINE('',#77799,#77800); -#77799 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); -#77800 = VECTOR('',#77801,1.); -#77801 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#77802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77803 = PCURVE('',#77016,#77804); -#77804 = DEFINITIONAL_REPRESENTATION('',(#77805),#77808); -#77805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#77806,#77807),.UNSPECIFIED., +#80181 = VECTOR('',#80182,1.); +#80182 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#80183 = PCURVE('',#80184,#80189); +#80184 = PLANE('',#80185); +#80185 = AXIS2_PLACEMENT_3D('',#80186,#80187,#80188); +#80186 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#80187 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); +#80188 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#80189 = DEFINITIONAL_REPRESENTATION('',(#80190),#80194); +#80190 = LINE('',#80191,#80192); +#80191 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); +#80192 = VECTOR('',#80193,1.); +#80193 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#80194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80195 = PCURVE('',#79408,#80196); +#80196 = DEFINITIONAL_REPRESENTATION('',(#80197),#80200); +#80197 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80198,#80199),.UNSPECIFIED., .F.,.F.,(2,2),(-0.69533963372,-0.307214451902), .PIECEWISE_BEZIER_KNOTS.); -#77806 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#77807 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); -#77808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80198 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#80199 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); +#80200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#77809 = ORIENTED_EDGE('',*,*,#77810,.T.); -#77810 = EDGE_CURVE('',#76961,#77811,#77813,.T.); -#77811 = VERTEX_POINT('',#77812); -#77812 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 +#80201 = ORIENTED_EDGE('',*,*,#80202,.T.); +#80202 = EDGE_CURVE('',#79353,#80203,#80205,.T.); +#80203 = VERTEX_POINT('',#80204); +#80204 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 )); -#77813 = SURFACE_CURVE('',#77814,(#77818,#77825),.PCURVE_S1.); -#77814 = LINE('',#77815,#77816); -#77815 = CARTESIAN_POINT('',(-1.207931449084,-0.552750264943, +#80205 = SURFACE_CURVE('',#80206,(#80210,#80217),.PCURVE_S1.); +#80206 = LINE('',#80207,#80208); +#80207 = CARTESIAN_POINT('',(-1.207931449084,-0.552750264943, 0.962940952255)); -#77816 = VECTOR('',#77817,1.); -#77817 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#77818 = PCURVE('',#77792,#77819); -#77819 = DEFINITIONAL_REPRESENTATION('',(#77820),#77824); -#77820 = LINE('',#77821,#77822); -#77821 = CARTESIAN_POINT('',(-0.375744122765,0.252068550916)); -#77822 = VECTOR('',#77823,1.); -#77823 = DIRECTION('',(0.E+000,-1.)); -#77824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77825 = PCURVE('',#77219,#77826); -#77826 = DEFINITIONAL_REPRESENTATION('',(#77827),#77830); -#77827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#77828,#77829),.UNSPECIFIED., +#80208 = VECTOR('',#80209,1.); +#80209 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80210 = PCURVE('',#80184,#80211); +#80211 = DEFINITIONAL_REPRESENTATION('',(#80212),#80216); +#80212 = LINE('',#80213,#80214); +#80213 = CARTESIAN_POINT('',(-0.375744122765,0.252068550916)); +#80214 = VECTOR('',#80215,1.); +#80215 = DIRECTION('',(0.E+000,-1.)); +#80216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80217 = PCURVE('',#79611,#80218); +#80218 = DEFINITIONAL_REPRESENTATION('',(#80219),#80222); +#80219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80220,#80221),.UNSPECIFIED., .F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#77828 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); -#77829 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); -#77830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80220 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); +#80221 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); +#80222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#77831 = ORIENTED_EDGE('',*,*,#77832,.T.); -#77832 = EDGE_CURVE('',#77811,#77833,#77835,.T.); -#77833 = VERTEX_POINT('',#77834); -#77834 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); -#77835 = SURFACE_CURVE('',#77836,(#77840,#77847),.PCURVE_S1.); -#77836 = LINE('',#77837,#77838); -#77837 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, +#80223 = ORIENTED_EDGE('',*,*,#80224,.T.); +#80224 = EDGE_CURVE('',#80203,#80225,#80227,.T.); +#80225 = VERTEX_POINT('',#80226); +#80226 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); +#80227 = SURFACE_CURVE('',#80228,(#80232,#80239),.PCURVE_S1.); +#80228 = LINE('',#80229,#80230); +#80229 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, 0.566051874704)); -#77838 = VECTOR('',#77839,1.); -#77839 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#77840 = PCURVE('',#77792,#77841); -#77841 = DEFINITIONAL_REPRESENTATION('',(#77842),#77846); -#77842 = LINE('',#77843,#77844); -#77843 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#77844 = VECTOR('',#77845,1.); -#77845 = DIRECTION('',(0.968100345886,-0.250562807086)); -#77846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77847 = PCURVE('',#76713,#77848); -#77848 = DEFINITIONAL_REPRESENTATION('',(#77849),#77875); -#77849 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#77850,#77851,#77852,#77853, - #77854,#77855,#77856,#77857,#77858,#77859,#77860,#77861,#77862, - #77863,#77864,#77865,#77866,#77867,#77868,#77869,#77870,#77871, - #77872,#77873,#77874),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80230 = VECTOR('',#80231,1.); +#80231 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#80232 = PCURVE('',#80184,#80233); +#80233 = DEFINITIONAL_REPRESENTATION('',(#80234),#80238); +#80234 = LINE('',#80235,#80236); +#80235 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#80236 = VECTOR('',#80237,1.); +#80237 = DIRECTION('',(0.968100345886,-0.250562807086)); +#80238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80239 = PCURVE('',#79105,#80240); +#80240 = DEFINITIONAL_REPRESENTATION('',(#80241),#80267); +#80241 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80242,#80243,#80244,#80245, + #80246,#80247,#80248,#80249,#80250,#80251,#80252,#80253,#80254, + #80255,#80256,#80257,#80258,#80259,#80260,#80261,#80262,#80263, + #80264,#80265,#80266),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.424428944789,-0.40678689107, -0.389144837351,-0.371502783632,-0.353860729913,-0.336218676194, -0.318576622475,-0.300934568756,-0.283292515037,-0.265650461318, @@ -96456,344 +99445,344 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.177440192723,-0.159798139004,-0.142156085285,-0.124514031566, -0.106871977847,-8.922992412772E-002,-7.158787040873E-002, -5.394581668973E-002,-3.630376297074E-002),.QUASI_UNIFORM_KNOTS.); -#77850 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); -#77851 = CARTESIAN_POINT('',(4.77942647859,-0.418548260216)); -#77852 = CARTESIAN_POINT('',(4.77942647859,-0.40678689107)); -#77853 = CARTESIAN_POINT('',(4.77942647859,-0.389144837351)); -#77854 = CARTESIAN_POINT('',(4.77942647859,-0.371502783632)); -#77855 = CARTESIAN_POINT('',(4.77942647859,-0.353860729913)); -#77856 = CARTESIAN_POINT('',(4.77942647859,-0.336218676194)); -#77857 = CARTESIAN_POINT('',(4.77942647859,-0.318576622475)); -#77858 = CARTESIAN_POINT('',(4.77942647859,-0.300934568756)); -#77859 = CARTESIAN_POINT('',(4.77942647859,-0.283292515037)); -#77860 = CARTESIAN_POINT('',(4.77942647859,-0.265650461318)); -#77861 = CARTESIAN_POINT('',(4.77942647859,-0.248008407599)); -#77862 = CARTESIAN_POINT('',(4.77942647859,-0.23036635388)); -#77863 = CARTESIAN_POINT('',(4.77942647859,-0.212724300161)); -#77864 = CARTESIAN_POINT('',(4.77942647859,-0.195082246442)); -#77865 = CARTESIAN_POINT('',(4.77942647859,-0.177440192723)); -#77866 = CARTESIAN_POINT('',(4.77942647859,-0.159798139004)); -#77867 = CARTESIAN_POINT('',(4.77942647859,-0.142156085285)); -#77868 = CARTESIAN_POINT('',(4.77942647859,-0.124514031566)); -#77869 = CARTESIAN_POINT('',(4.77942647859,-0.106871977847)); -#77870 = CARTESIAN_POINT('',(4.77942647859,-8.922992412772E-002)); -#77871 = CARTESIAN_POINT('',(4.77942647859,-7.158787040873E-002)); -#77872 = CARTESIAN_POINT('',(4.77942647859,-5.394581668973E-002)); -#77873 = CARTESIAN_POINT('',(4.77942647859,-4.218444754374E-002)); -#77874 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#77875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77876 = ORIENTED_EDGE('',*,*,#77877,.T.); -#77877 = EDGE_CURVE('',#77833,#77878,#77880,.T.); -#77878 = VERTEX_POINT('',#77879); -#77879 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); -#77880 = SURFACE_CURVE('',#77881,(#77885,#77892),.PCURVE_S1.); -#77881 = LINE('',#77882,#77883); -#77882 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#77883 = VECTOR('',#77884,1.); -#77884 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77885 = PCURVE('',#77792,#77886); -#77886 = DEFINITIONAL_REPRESENTATION('',(#77887),#77891); -#77887 = LINE('',#77888,#77889); -#77888 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#77889 = VECTOR('',#77890,1.); -#77890 = DIRECTION('',(0.E+000,1.)); -#77891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77892 = PCURVE('',#77893,#77898); -#77893 = PLANE('',#77894); -#77894 = AXIS2_PLACEMENT_3D('',#77895,#77896,#77897); -#77895 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#77896 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); -#77897 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); -#77898 = DEFINITIONAL_REPRESENTATION('',(#77899),#77903); -#77899 = LINE('',#77900,#77901); -#77900 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#77901 = VECTOR('',#77902,1.); -#77902 = DIRECTION('',(0.E+000,1.)); -#77903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77904 = ORIENTED_EDGE('',*,*,#77905,.F.); -#77905 = EDGE_CURVE('',#77906,#77878,#77908,.T.); -#77906 = VERTEX_POINT('',#77907); -#77907 = CARTESIAN_POINT('',(-1.145,-0.609807621135,0.75)); -#77908 = SURFACE_CURVE('',#77909,(#77913,#77920),.PCURVE_S1.); -#77909 = LINE('',#77910,#77911); -#77910 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); -#77911 = VECTOR('',#77912,1.); -#77912 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#77913 = PCURVE('',#77792,#77914); -#77914 = DEFINITIONAL_REPRESENTATION('',(#77915),#77919); -#77915 = LINE('',#77916,#77917); -#77916 = CARTESIAN_POINT('',(0.E+000,0.315)); -#77917 = VECTOR('',#77918,1.); -#77918 = DIRECTION('',(1.,0.E+000)); -#77919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77920 = PCURVE('',#77921,#77926); -#77921 = PLANE('',#77922); -#77922 = AXIS2_PLACEMENT_3D('',#77923,#77924,#77925); -#77923 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#77924 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77925 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#77926 = DEFINITIONAL_REPRESENTATION('',(#77927),#77931); -#77927 = LINE('',#77928,#77929); -#77928 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#77929 = VECTOR('',#77930,1.); -#77930 = DIRECTION('',(0.965925826289,-0.258819045103)); -#77931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77932 = ORIENTED_EDGE('',*,*,#77933,.T.); -#77933 = EDGE_CURVE('',#77906,#77934,#77936,.T.); -#77934 = VERTEX_POINT('',#77935); -#77935 = CARTESIAN_POINT('',(-0.745,-0.609807621135,0.75)); -#77936 = SURFACE_CURVE('',#77937,(#77941,#77948),.PCURVE_S1.); -#77937 = LINE('',#77938,#77939); -#77938 = CARTESIAN_POINT('',(-3.36,-0.609807621135,0.75)); -#77939 = VECTOR('',#77940,1.); -#77940 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77941 = PCURVE('',#77792,#77942); -#77942 = DEFINITIONAL_REPRESENTATION('',(#77943),#77947); -#77943 = LINE('',#77944,#77945); -#77944 = CARTESIAN_POINT('',(-0.155291427062,-1.9)); -#77945 = VECTOR('',#77946,1.); -#77946 = DIRECTION('',(0.E+000,1.)); -#77947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77948 = PCURVE('',#77949,#77954); -#77949 = PLANE('',#77950); -#77950 = AXIS2_PLACEMENT_3D('',#77951,#77952,#77953); -#77951 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#77952 = DIRECTION('',(0.E+000,0.E+000,1.)); -#77953 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77954 = DEFINITIONAL_REPRESENTATION('',(#77955),#77959); -#77955 = LINE('',#77956,#77957); -#77956 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); -#77957 = VECTOR('',#77958,1.); -#77958 = DIRECTION('',(1.,0.E+000)); -#77959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77960 = ORIENTED_EDGE('',*,*,#77961,.T.); -#77961 = EDGE_CURVE('',#77934,#77962,#77964,.T.); -#77962 = VERTEX_POINT('',#77963); -#77963 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); -#77964 = SURFACE_CURVE('',#77965,(#77969,#77976),.PCURVE_S1.); -#77965 = LINE('',#77966,#77967); -#77966 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); -#77967 = VECTOR('',#77968,1.); -#77968 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#77969 = PCURVE('',#77792,#77970); -#77970 = DEFINITIONAL_REPRESENTATION('',(#77971),#77975); -#77971 = LINE('',#77972,#77973); -#77972 = CARTESIAN_POINT('',(0.E+000,0.715)); -#77973 = VECTOR('',#77974,1.); -#77974 = DIRECTION('',(1.,0.E+000)); -#77975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77976 = PCURVE('',#77977,#77982); -#77977 = PLANE('',#77978); -#77978 = AXIS2_PLACEMENT_3D('',#77979,#77980,#77981); -#77979 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#77980 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77981 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#77982 = DEFINITIONAL_REPRESENTATION('',(#77983),#77987); -#77983 = LINE('',#77984,#77985); -#77984 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#77985 = VECTOR('',#77986,1.); -#77986 = DIRECTION('',(0.965925826289,-0.258819045103)); -#77987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#77988 = ORIENTED_EDGE('',*,*,#77989,.T.); -#77989 = EDGE_CURVE('',#77962,#77990,#77992,.T.); -#77990 = VERTEX_POINT('',#77991); -#77991 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); -#77992 = SURFACE_CURVE('',#77993,(#77997,#78004),.PCURVE_S1.); -#77993 = LINE('',#77994,#77995); -#77994 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#77995 = VECTOR('',#77996,1.); -#77996 = DIRECTION('',(1.,0.E+000,0.E+000)); -#77997 = PCURVE('',#77792,#77998); -#77998 = DEFINITIONAL_REPRESENTATION('',(#77999),#78003); -#77999 = LINE('',#78000,#78001); -#78000 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78001 = VECTOR('',#78002,1.); -#78002 = DIRECTION('',(0.E+000,1.)); -#78003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78004 = PCURVE('',#77893,#78005); -#78005 = DEFINITIONAL_REPRESENTATION('',(#78006),#78010); -#78006 = LINE('',#78007,#78008); -#78007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78008 = VECTOR('',#78009,1.); -#78009 = DIRECTION('',(0.E+000,1.)); -#78010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78011 = ORIENTED_EDGE('',*,*,#78012,.F.); -#78012 = EDGE_CURVE('',#78013,#77990,#78015,.T.); -#78013 = VERTEX_POINT('',#78014); -#78014 = CARTESIAN_POINT('',(0.755,-0.609807621135,0.75)); -#78015 = SURFACE_CURVE('',#78016,(#78020,#78027),.PCURVE_S1.); -#78016 = LINE('',#78017,#78018); -#78017 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); -#78018 = VECTOR('',#78019,1.); -#78019 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#78020 = PCURVE('',#77792,#78021); -#78021 = DEFINITIONAL_REPRESENTATION('',(#78022),#78026); -#78022 = LINE('',#78023,#78024); -#78023 = CARTESIAN_POINT('',(0.E+000,2.215)); -#78024 = VECTOR('',#78025,1.); -#78025 = DIRECTION('',(1.,0.E+000)); -#78026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78027 = PCURVE('',#78028,#78033); -#78028 = PLANE('',#78029); -#78029 = AXIS2_PLACEMENT_3D('',#78030,#78031,#78032); -#78030 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#78031 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78032 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78033 = DEFINITIONAL_REPRESENTATION('',(#78034),#78038); -#78034 = LINE('',#78035,#78036); -#78035 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#78036 = VECTOR('',#78037,1.); -#78037 = DIRECTION('',(0.965925826289,-0.258819045103)); -#78038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78039 = ORIENTED_EDGE('',*,*,#78040,.T.); -#78040 = EDGE_CURVE('',#78013,#78041,#78043,.T.); -#78041 = VERTEX_POINT('',#78042); -#78042 = CARTESIAN_POINT('',(1.155,-0.609807621135,0.75)); -#78043 = SURFACE_CURVE('',#78044,(#78048,#78055),.PCURVE_S1.); -#78044 = LINE('',#78045,#78046); -#78045 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); -#78046 = VECTOR('',#78047,1.); -#78047 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78048 = PCURVE('',#77792,#78049); -#78049 = DEFINITIONAL_REPRESENTATION('',(#78050),#78054); -#78050 = LINE('',#78051,#78052); -#78051 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); -#78052 = VECTOR('',#78053,1.); -#78053 = DIRECTION('',(0.E+000,1.)); -#78054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78055 = PCURVE('',#78056,#78061); -#78056 = PLANE('',#78057); -#78057 = AXIS2_PLACEMENT_3D('',#78058,#78059,#78060); -#78058 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#78059 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78060 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78061 = DEFINITIONAL_REPRESENTATION('',(#78062),#78066); -#78062 = LINE('',#78063,#78064); -#78063 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); -#78064 = VECTOR('',#78065,1.); -#78065 = DIRECTION('',(1.,0.E+000)); -#78066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78067 = ORIENTED_EDGE('',*,*,#78068,.T.); -#78068 = EDGE_CURVE('',#78041,#78069,#78071,.T.); -#78069 = VERTEX_POINT('',#78070); -#78070 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); -#78071 = SURFACE_CURVE('',#78072,(#78076,#78083),.PCURVE_S1.); -#78072 = LINE('',#78073,#78074); -#78073 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); -#78074 = VECTOR('',#78075,1.); -#78075 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#78076 = PCURVE('',#77792,#78077); -#78077 = DEFINITIONAL_REPRESENTATION('',(#78078),#78082); -#78078 = LINE('',#78079,#78080); -#78079 = CARTESIAN_POINT('',(0.E+000,2.615)); -#78080 = VECTOR('',#78081,1.); -#78081 = DIRECTION('',(1.,0.E+000)); -#78082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78083 = PCURVE('',#78084,#78089); -#78084 = PLANE('',#78085); -#78085 = AXIS2_PLACEMENT_3D('',#78086,#78087,#78088); -#78086 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#78087 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78088 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78089 = DEFINITIONAL_REPRESENTATION('',(#78090),#78094); -#78090 = LINE('',#78091,#78092); -#78091 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#78092 = VECTOR('',#78093,1.); -#78093 = DIRECTION('',(0.965925826289,-0.258819045103)); -#78094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78095 = ORIENTED_EDGE('',*,*,#78096,.T.); -#78096 = EDGE_CURVE('',#78069,#77784,#78097,.T.); -#78097 = SURFACE_CURVE('',#78098,(#78102,#78109),.PCURVE_S1.); -#78098 = LINE('',#78099,#78100); -#78099 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#78100 = VECTOR('',#78101,1.); -#78101 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78102 = PCURVE('',#77792,#78103); -#78103 = DEFINITIONAL_REPRESENTATION('',(#78104),#78108); -#78104 = LINE('',#78105,#78106); -#78105 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78106 = VECTOR('',#78107,1.); -#78107 = DIRECTION('',(0.E+000,1.)); -#78108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78109 = PCURVE('',#77893,#78110); -#78110 = DEFINITIONAL_REPRESENTATION('',(#78111),#78115); -#78111 = LINE('',#78112,#78113); -#78112 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78113 = VECTOR('',#78114,1.); -#78114 = DIRECTION('',(0.E+000,1.)); -#78115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78116 = ADVANCED_FACE('',(#78117),#78129,.T.); -#78117 = FACE_BOUND('',#78118,.T.); -#78118 = EDGE_LOOP('',(#78119,#78169,#78191,#78236,#78264,#78292,#78320, - #78348,#78371,#78399,#78427,#78455,#78478,#78506,#78534,#78562)); -#78119 = ORIENTED_EDGE('',*,*,#78120,.T.); -#78120 = EDGE_CURVE('',#78121,#77236,#78123,.T.); -#78121 = VERTEX_POINT('',#78122); -#78122 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); -#78123 = SURFACE_CURVE('',#78124,(#78128,#78140),.PCURVE_S1.); -#78124 = LINE('',#78125,#78126); -#78125 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, +#80242 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); +#80243 = CARTESIAN_POINT('',(4.77942647859,-0.418548260216)); +#80244 = CARTESIAN_POINT('',(4.77942647859,-0.40678689107)); +#80245 = CARTESIAN_POINT('',(4.77942647859,-0.389144837351)); +#80246 = CARTESIAN_POINT('',(4.77942647859,-0.371502783632)); +#80247 = CARTESIAN_POINT('',(4.77942647859,-0.353860729913)); +#80248 = CARTESIAN_POINT('',(4.77942647859,-0.336218676194)); +#80249 = CARTESIAN_POINT('',(4.77942647859,-0.318576622475)); +#80250 = CARTESIAN_POINT('',(4.77942647859,-0.300934568756)); +#80251 = CARTESIAN_POINT('',(4.77942647859,-0.283292515037)); +#80252 = CARTESIAN_POINT('',(4.77942647859,-0.265650461318)); +#80253 = CARTESIAN_POINT('',(4.77942647859,-0.248008407599)); +#80254 = CARTESIAN_POINT('',(4.77942647859,-0.23036635388)); +#80255 = CARTESIAN_POINT('',(4.77942647859,-0.212724300161)); +#80256 = CARTESIAN_POINT('',(4.77942647859,-0.195082246442)); +#80257 = CARTESIAN_POINT('',(4.77942647859,-0.177440192723)); +#80258 = CARTESIAN_POINT('',(4.77942647859,-0.159798139004)); +#80259 = CARTESIAN_POINT('',(4.77942647859,-0.142156085285)); +#80260 = CARTESIAN_POINT('',(4.77942647859,-0.124514031566)); +#80261 = CARTESIAN_POINT('',(4.77942647859,-0.106871977847)); +#80262 = CARTESIAN_POINT('',(4.77942647859,-8.922992412772E-002)); +#80263 = CARTESIAN_POINT('',(4.77942647859,-7.158787040873E-002)); +#80264 = CARTESIAN_POINT('',(4.77942647859,-5.394581668973E-002)); +#80265 = CARTESIAN_POINT('',(4.77942647859,-4.218444754374E-002)); +#80266 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#80267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80268 = ORIENTED_EDGE('',*,*,#80269,.T.); +#80269 = EDGE_CURVE('',#80225,#80270,#80272,.T.); +#80270 = VERTEX_POINT('',#80271); +#80271 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); +#80272 = SURFACE_CURVE('',#80273,(#80277,#80284),.PCURVE_S1.); +#80273 = LINE('',#80274,#80275); +#80274 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#80275 = VECTOR('',#80276,1.); +#80276 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80277 = PCURVE('',#80184,#80278); +#80278 = DEFINITIONAL_REPRESENTATION('',(#80279),#80283); +#80279 = LINE('',#80280,#80281); +#80280 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80281 = VECTOR('',#80282,1.); +#80282 = DIRECTION('',(0.E+000,1.)); +#80283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80284 = PCURVE('',#80285,#80290); +#80285 = PLANE('',#80286); +#80286 = AXIS2_PLACEMENT_3D('',#80287,#80288,#80289); +#80287 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#80288 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); +#80289 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); +#80290 = DEFINITIONAL_REPRESENTATION('',(#80291),#80295); +#80291 = LINE('',#80292,#80293); +#80292 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80293 = VECTOR('',#80294,1.); +#80294 = DIRECTION('',(0.E+000,1.)); +#80295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80296 = ORIENTED_EDGE('',*,*,#80297,.F.); +#80297 = EDGE_CURVE('',#80298,#80270,#80300,.T.); +#80298 = VERTEX_POINT('',#80299); +#80299 = CARTESIAN_POINT('',(-1.145,-0.609807621135,0.75)); +#80300 = SURFACE_CURVE('',#80301,(#80305,#80312),.PCURVE_S1.); +#80301 = LINE('',#80302,#80303); +#80302 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); +#80303 = VECTOR('',#80304,1.); +#80304 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#80305 = PCURVE('',#80184,#80306); +#80306 = DEFINITIONAL_REPRESENTATION('',(#80307),#80311); +#80307 = LINE('',#80308,#80309); +#80308 = CARTESIAN_POINT('',(0.E+000,0.315)); +#80309 = VECTOR('',#80310,1.); +#80310 = DIRECTION('',(1.,0.E+000)); +#80311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80312 = PCURVE('',#80313,#80318); +#80313 = PLANE('',#80314); +#80314 = AXIS2_PLACEMENT_3D('',#80315,#80316,#80317); +#80315 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#80316 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80317 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80318 = DEFINITIONAL_REPRESENTATION('',(#80319),#80323); +#80319 = LINE('',#80320,#80321); +#80320 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#80321 = VECTOR('',#80322,1.); +#80322 = DIRECTION('',(0.965925826289,-0.258819045103)); +#80323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80324 = ORIENTED_EDGE('',*,*,#80325,.T.); +#80325 = EDGE_CURVE('',#80298,#80326,#80328,.T.); +#80326 = VERTEX_POINT('',#80327); +#80327 = CARTESIAN_POINT('',(-0.745,-0.609807621135,0.75)); +#80328 = SURFACE_CURVE('',#80329,(#80333,#80340),.PCURVE_S1.); +#80329 = LINE('',#80330,#80331); +#80330 = CARTESIAN_POINT('',(-3.36,-0.609807621135,0.75)); +#80331 = VECTOR('',#80332,1.); +#80332 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80333 = PCURVE('',#80184,#80334); +#80334 = DEFINITIONAL_REPRESENTATION('',(#80335),#80339); +#80335 = LINE('',#80336,#80337); +#80336 = CARTESIAN_POINT('',(-0.155291427062,-1.9)); +#80337 = VECTOR('',#80338,1.); +#80338 = DIRECTION('',(0.E+000,1.)); +#80339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80340 = PCURVE('',#80341,#80346); +#80341 = PLANE('',#80342); +#80342 = AXIS2_PLACEMENT_3D('',#80343,#80344,#80345); +#80343 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#80344 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80345 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80346 = DEFINITIONAL_REPRESENTATION('',(#80347),#80351); +#80347 = LINE('',#80348,#80349); +#80348 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); +#80349 = VECTOR('',#80350,1.); +#80350 = DIRECTION('',(1.,0.E+000)); +#80351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80352 = ORIENTED_EDGE('',*,*,#80353,.T.); +#80353 = EDGE_CURVE('',#80326,#80354,#80356,.T.); +#80354 = VERTEX_POINT('',#80355); +#80355 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); +#80356 = SURFACE_CURVE('',#80357,(#80361,#80368),.PCURVE_S1.); +#80357 = LINE('',#80358,#80359); +#80358 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); +#80359 = VECTOR('',#80360,1.); +#80360 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#80361 = PCURVE('',#80184,#80362); +#80362 = DEFINITIONAL_REPRESENTATION('',(#80363),#80367); +#80363 = LINE('',#80364,#80365); +#80364 = CARTESIAN_POINT('',(0.E+000,0.715)); +#80365 = VECTOR('',#80366,1.); +#80366 = DIRECTION('',(1.,0.E+000)); +#80367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80368 = PCURVE('',#80369,#80374); +#80369 = PLANE('',#80370); +#80370 = AXIS2_PLACEMENT_3D('',#80371,#80372,#80373); +#80371 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#80372 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80373 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80374 = DEFINITIONAL_REPRESENTATION('',(#80375),#80379); +#80375 = LINE('',#80376,#80377); +#80376 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#80377 = VECTOR('',#80378,1.); +#80378 = DIRECTION('',(0.965925826289,-0.258819045103)); +#80379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80380 = ORIENTED_EDGE('',*,*,#80381,.T.); +#80381 = EDGE_CURVE('',#80354,#80382,#80384,.T.); +#80382 = VERTEX_POINT('',#80383); +#80383 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); +#80384 = SURFACE_CURVE('',#80385,(#80389,#80396),.PCURVE_S1.); +#80385 = LINE('',#80386,#80387); +#80386 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#80387 = VECTOR('',#80388,1.); +#80388 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80389 = PCURVE('',#80184,#80390); +#80390 = DEFINITIONAL_REPRESENTATION('',(#80391),#80395); +#80391 = LINE('',#80392,#80393); +#80392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80393 = VECTOR('',#80394,1.); +#80394 = DIRECTION('',(0.E+000,1.)); +#80395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80396 = PCURVE('',#80285,#80397); +#80397 = DEFINITIONAL_REPRESENTATION('',(#80398),#80402); +#80398 = LINE('',#80399,#80400); +#80399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80400 = VECTOR('',#80401,1.); +#80401 = DIRECTION('',(0.E+000,1.)); +#80402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80403 = ORIENTED_EDGE('',*,*,#80404,.F.); +#80404 = EDGE_CURVE('',#80405,#80382,#80407,.T.); +#80405 = VERTEX_POINT('',#80406); +#80406 = CARTESIAN_POINT('',(0.755,-0.609807621135,0.75)); +#80407 = SURFACE_CURVE('',#80408,(#80412,#80419),.PCURVE_S1.); +#80408 = LINE('',#80409,#80410); +#80409 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); +#80410 = VECTOR('',#80411,1.); +#80411 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#80412 = PCURVE('',#80184,#80413); +#80413 = DEFINITIONAL_REPRESENTATION('',(#80414),#80418); +#80414 = LINE('',#80415,#80416); +#80415 = CARTESIAN_POINT('',(0.E+000,2.215)); +#80416 = VECTOR('',#80417,1.); +#80417 = DIRECTION('',(1.,0.E+000)); +#80418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80419 = PCURVE('',#80420,#80425); +#80420 = PLANE('',#80421); +#80421 = AXIS2_PLACEMENT_3D('',#80422,#80423,#80424); +#80422 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#80423 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80424 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80425 = DEFINITIONAL_REPRESENTATION('',(#80426),#80430); +#80426 = LINE('',#80427,#80428); +#80427 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#80428 = VECTOR('',#80429,1.); +#80429 = DIRECTION('',(0.965925826289,-0.258819045103)); +#80430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80431 = ORIENTED_EDGE('',*,*,#80432,.T.); +#80432 = EDGE_CURVE('',#80405,#80433,#80435,.T.); +#80433 = VERTEX_POINT('',#80434); +#80434 = CARTESIAN_POINT('',(1.155,-0.609807621135,0.75)); +#80435 = SURFACE_CURVE('',#80436,(#80440,#80447),.PCURVE_S1.); +#80436 = LINE('',#80437,#80438); +#80437 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); +#80438 = VECTOR('',#80439,1.); +#80439 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80440 = PCURVE('',#80184,#80441); +#80441 = DEFINITIONAL_REPRESENTATION('',(#80442),#80446); +#80442 = LINE('',#80443,#80444); +#80443 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); +#80444 = VECTOR('',#80445,1.); +#80445 = DIRECTION('',(0.E+000,1.)); +#80446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80447 = PCURVE('',#80448,#80453); +#80448 = PLANE('',#80449); +#80449 = AXIS2_PLACEMENT_3D('',#80450,#80451,#80452); +#80450 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#80451 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80452 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80453 = DEFINITIONAL_REPRESENTATION('',(#80454),#80458); +#80454 = LINE('',#80455,#80456); +#80455 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); +#80456 = VECTOR('',#80457,1.); +#80457 = DIRECTION('',(1.,0.E+000)); +#80458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80459 = ORIENTED_EDGE('',*,*,#80460,.T.); +#80460 = EDGE_CURVE('',#80433,#80461,#80463,.T.); +#80461 = VERTEX_POINT('',#80462); +#80462 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); +#80463 = SURFACE_CURVE('',#80464,(#80468,#80475),.PCURVE_S1.); +#80464 = LINE('',#80465,#80466); +#80465 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); +#80466 = VECTOR('',#80467,1.); +#80467 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#80468 = PCURVE('',#80184,#80469); +#80469 = DEFINITIONAL_REPRESENTATION('',(#80470),#80474); +#80470 = LINE('',#80471,#80472); +#80471 = CARTESIAN_POINT('',(0.E+000,2.615)); +#80472 = VECTOR('',#80473,1.); +#80473 = DIRECTION('',(1.,0.E+000)); +#80474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80475 = PCURVE('',#80476,#80481); +#80476 = PLANE('',#80477); +#80477 = AXIS2_PLACEMENT_3D('',#80478,#80479,#80480); +#80478 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#80479 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80480 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80481 = DEFINITIONAL_REPRESENTATION('',(#80482),#80486); +#80482 = LINE('',#80483,#80484); +#80483 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#80484 = VECTOR('',#80485,1.); +#80485 = DIRECTION('',(0.965925826289,-0.258819045103)); +#80486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80487 = ORIENTED_EDGE('',*,*,#80488,.T.); +#80488 = EDGE_CURVE('',#80461,#80176,#80489,.T.); +#80489 = SURFACE_CURVE('',#80490,(#80494,#80501),.PCURVE_S1.); +#80490 = LINE('',#80491,#80492); +#80491 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#80492 = VECTOR('',#80493,1.); +#80493 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80494 = PCURVE('',#80184,#80495); +#80495 = DEFINITIONAL_REPRESENTATION('',(#80496),#80500); +#80496 = LINE('',#80497,#80498); +#80497 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80498 = VECTOR('',#80499,1.); +#80499 = DIRECTION('',(0.E+000,1.)); +#80500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80501 = PCURVE('',#80285,#80502); +#80502 = DEFINITIONAL_REPRESENTATION('',(#80503),#80507); +#80503 = LINE('',#80504,#80505); +#80504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80505 = VECTOR('',#80506,1.); +#80506 = DIRECTION('',(0.E+000,1.)); +#80507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80508 = ADVANCED_FACE('',(#80509),#80521,.T.); +#80509 = FACE_BOUND('',#80510,.T.); +#80510 = EDGE_LOOP('',(#80511,#80561,#80583,#80628,#80656,#80684,#80712, + #80740,#80763,#80791,#80819,#80847,#80870,#80898,#80926,#80954)); +#80511 = ORIENTED_EDGE('',*,*,#80512,.T.); +#80512 = EDGE_CURVE('',#80513,#79628,#80515,.T.); +#80513 = VERTEX_POINT('',#80514); +#80514 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); +#80515 = SURFACE_CURVE('',#80516,(#80520,#80532),.PCURVE_S1.); +#80516 = LINE('',#80517,#80518); +#80517 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, 0.566051874704)); -#78126 = VECTOR('',#78127,1.); -#78127 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#78128 = PCURVE('',#78129,#78134); -#78129 = PLANE('',#78130); -#78130 = AXIS2_PLACEMENT_3D('',#78131,#78132,#78133); -#78131 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78132 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); -#78133 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#78134 = DEFINITIONAL_REPRESENTATION('',(#78135),#78139); -#78135 = LINE('',#78136,#78137); -#78136 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#78137 = VECTOR('',#78138,1.); -#78138 = DIRECTION('',(0.968100345886,0.250562807086)); -#78139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78140 = PCURVE('',#77291,#78141); -#78141 = DEFINITIONAL_REPRESENTATION('',(#78142),#78168); -#78142 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78143,#78144,#78145,#78146, - #78147,#78148,#78149,#78150,#78151,#78152,#78153,#78154,#78155, - #78156,#78157,#78158,#78159,#78160,#78161,#78162,#78163,#78164, - #78165,#78166,#78167),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80518 = VECTOR('',#80519,1.); +#80519 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#80520 = PCURVE('',#80521,#80526); +#80521 = PLANE('',#80522); +#80522 = AXIS2_PLACEMENT_3D('',#80523,#80524,#80525); +#80523 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80524 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); +#80525 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#80526 = DEFINITIONAL_REPRESENTATION('',(#80527),#80531); +#80527 = LINE('',#80528,#80529); +#80528 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#80529 = VECTOR('',#80530,1.); +#80530 = DIRECTION('',(0.968100345886,0.250562807086)); +#80531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80532 = PCURVE('',#79683,#80533); +#80533 = DEFINITIONAL_REPRESENTATION('',(#80534),#80560); +#80534 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80535,#80536,#80537,#80538, + #80539,#80540,#80541,#80542,#80543,#80544,#80545,#80546,#80547, + #80548,#80549,#80550,#80551,#80552,#80553,#80554,#80555,#80556, + #80557,#80558,#80559),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.630376297074E-002,5.394581668973E-002, 7.158787040873E-002,8.922992412772E-002,0.106871977847, 0.124514031566,0.142156085285,0.159798139004,0.177440192723, @@ -96801,89 +99790,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.265650461318,0.283292515037,0.300934568756,0.318576622475, 0.336218676194,0.353860729913,0.371502783632,0.389144837351, 0.40678689107,0.424428944789),.QUASI_UNIFORM_KNOTS.); -#78143 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#78144 = CARTESIAN_POINT('',(1.50375882859,-4.218444754374E-002)); -#78145 = CARTESIAN_POINT('',(1.50375882859,-5.394581668973E-002)); -#78146 = CARTESIAN_POINT('',(1.50375882859,-7.158787040873E-002)); -#78147 = CARTESIAN_POINT('',(1.50375882859,-8.922992412772E-002)); -#78148 = CARTESIAN_POINT('',(1.50375882859,-0.106871977847)); -#78149 = CARTESIAN_POINT('',(1.50375882859,-0.124514031566)); -#78150 = CARTESIAN_POINT('',(1.50375882859,-0.142156085285)); -#78151 = CARTESIAN_POINT('',(1.50375882859,-0.159798139004)); -#78152 = CARTESIAN_POINT('',(1.50375882859,-0.177440192723)); -#78153 = CARTESIAN_POINT('',(1.50375882859,-0.195082246442)); -#78154 = CARTESIAN_POINT('',(1.50375882859,-0.212724300161)); -#78155 = CARTESIAN_POINT('',(1.50375882859,-0.23036635388)); -#78156 = CARTESIAN_POINT('',(1.50375882859,-0.248008407599)); -#78157 = CARTESIAN_POINT('',(1.50375882859,-0.265650461318)); -#78158 = CARTESIAN_POINT('',(1.50375882859,-0.283292515037)); -#78159 = CARTESIAN_POINT('',(1.50375882859,-0.300934568756)); -#78160 = CARTESIAN_POINT('',(1.50375882859,-0.318576622475)); -#78161 = CARTESIAN_POINT('',(1.50375882859,-0.336218676194)); -#78162 = CARTESIAN_POINT('',(1.50375882859,-0.353860729913)); -#78163 = CARTESIAN_POINT('',(1.50375882859,-0.371502783632)); -#78164 = CARTESIAN_POINT('',(1.50375882859,-0.389144837351)); -#78165 = CARTESIAN_POINT('',(1.50375882859,-0.40678689107)); -#78166 = CARTESIAN_POINT('',(1.50375882859,-0.418548260216)); -#78167 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); -#78168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78169 = ORIENTED_EDGE('',*,*,#78170,.T.); -#78170 = EDGE_CURVE('',#77236,#78171,#78173,.T.); -#78171 = VERTEX_POINT('',#78172); -#78172 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) - ); -#78173 = SURFACE_CURVE('',#78174,(#78178,#78185),.PCURVE_S1.); -#78174 = LINE('',#78175,#78176); -#78175 = CARTESIAN_POINT('',(1.207931449084,0.552750264943, +#80535 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#80536 = CARTESIAN_POINT('',(1.50375882859,-4.218444754374E-002)); +#80537 = CARTESIAN_POINT('',(1.50375882859,-5.394581668973E-002)); +#80538 = CARTESIAN_POINT('',(1.50375882859,-7.158787040873E-002)); +#80539 = CARTESIAN_POINT('',(1.50375882859,-8.922992412772E-002)); +#80540 = CARTESIAN_POINT('',(1.50375882859,-0.106871977847)); +#80541 = CARTESIAN_POINT('',(1.50375882859,-0.124514031566)); +#80542 = CARTESIAN_POINT('',(1.50375882859,-0.142156085285)); +#80543 = CARTESIAN_POINT('',(1.50375882859,-0.159798139004)); +#80544 = CARTESIAN_POINT('',(1.50375882859,-0.177440192723)); +#80545 = CARTESIAN_POINT('',(1.50375882859,-0.195082246442)); +#80546 = CARTESIAN_POINT('',(1.50375882859,-0.212724300161)); +#80547 = CARTESIAN_POINT('',(1.50375882859,-0.23036635388)); +#80548 = CARTESIAN_POINT('',(1.50375882859,-0.248008407599)); +#80549 = CARTESIAN_POINT('',(1.50375882859,-0.265650461318)); +#80550 = CARTESIAN_POINT('',(1.50375882859,-0.283292515037)); +#80551 = CARTESIAN_POINT('',(1.50375882859,-0.300934568756)); +#80552 = CARTESIAN_POINT('',(1.50375882859,-0.318576622475)); +#80553 = CARTESIAN_POINT('',(1.50375882859,-0.336218676194)); +#80554 = CARTESIAN_POINT('',(1.50375882859,-0.353860729913)); +#80555 = CARTESIAN_POINT('',(1.50375882859,-0.371502783632)); +#80556 = CARTESIAN_POINT('',(1.50375882859,-0.389144837351)); +#80557 = CARTESIAN_POINT('',(1.50375882859,-0.40678689107)); +#80558 = CARTESIAN_POINT('',(1.50375882859,-0.418548260216)); +#80559 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); +#80560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80561 = ORIENTED_EDGE('',*,*,#80562,.T.); +#80562 = EDGE_CURVE('',#79628,#80563,#80565,.T.); +#80563 = VERTEX_POINT('',#80564); +#80564 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) + ); +#80565 = SURFACE_CURVE('',#80566,(#80570,#80577),.PCURVE_S1.); +#80566 = LINE('',#80567,#80568); +#80567 = CARTESIAN_POINT('',(1.207931449084,0.552750264943, 0.962940952255)); -#78176 = VECTOR('',#78177,1.); -#78177 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78178 = PCURVE('',#78129,#78179); -#78179 = DEFINITIONAL_REPRESENTATION('',(#78180),#78184); -#78180 = LINE('',#78181,#78182); -#78181 = CARTESIAN_POINT('',(0.375744122765,2.667931449084)); -#78182 = VECTOR('',#78183,1.); -#78183 = DIRECTION('',(0.E+000,1.)); -#78184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78185 = PCURVE('',#77494,#78186); -#78186 = DEFINITIONAL_REPRESENTATION('',(#78187),#78190); -#78187 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78188,#78189),.UNSPECIFIED., +#80568 = VECTOR('',#80569,1.); +#80569 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80570 = PCURVE('',#80521,#80571); +#80571 = DEFINITIONAL_REPRESENTATION('',(#80572),#80576); +#80572 = LINE('',#80573,#80574); +#80573 = CARTESIAN_POINT('',(0.375744122765,2.667931449084)); +#80574 = VECTOR('',#80575,1.); +#80575 = DIRECTION('',(0.E+000,1.)); +#80576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80577 = PCURVE('',#79886,#80578); +#80578 = DEFINITIONAL_REPRESENTATION('',(#80579),#80582); +#80579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80580,#80581),.UNSPECIFIED., .F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#78188 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); -#78189 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); -#78190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80580 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); +#80581 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); +#80582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78191 = ORIENTED_EDGE('',*,*,#78192,.T.); -#78192 = EDGE_CURVE('',#78171,#78193,#78195,.T.); -#78193 = VERTEX_POINT('',#78194); -#78194 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); -#78195 = SURFACE_CURVE('',#78196,(#78200,#78207),.PCURVE_S1.); -#78196 = LINE('',#78197,#78198); -#78197 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, +#80583 = ORIENTED_EDGE('',*,*,#80584,.T.); +#80584 = EDGE_CURVE('',#80563,#80585,#80587,.T.); +#80585 = VERTEX_POINT('',#80586); +#80586 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); +#80587 = SURFACE_CURVE('',#80588,(#80592,#80599),.PCURVE_S1.); +#80588 = LINE('',#80589,#80590); +#80589 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, 1.250221218888)); -#78198 = VECTOR('',#78199,1.); -#78199 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#78200 = PCURVE('',#78129,#78201); -#78201 = DEFINITIONAL_REPRESENTATION('',(#78202),#78206); -#78202 = LINE('',#78203,#78204); -#78203 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); -#78204 = VECTOR('',#78205,1.); -#78205 = DIRECTION('',(-0.968100345886,0.250562807086)); -#78206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80590 = VECTOR('',#80591,1.); +#80591 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#80592 = PCURVE('',#80521,#80593); +#80593 = DEFINITIONAL_REPRESENTATION('',(#80594),#80598); +#80594 = LINE('',#80595,#80596); +#80595 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); +#80596 = VECTOR('',#80597,1.); +#80597 = DIRECTION('',(-0.968100345886,0.250562807086)); +#80598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78207 = PCURVE('',#77566,#78208); -#78208 = DEFINITIONAL_REPRESENTATION('',(#78209),#78235); -#78209 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78210,#78211,#78212,#78213, - #78214,#78215,#78216,#78217,#78218,#78219,#78220,#78221,#78222, - #78223,#78224,#78225,#78226,#78227,#78228,#78229,#78230,#78231, - #78232,#78233,#78234),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80599 = PCURVE('',#79958,#80600); +#80600 = DEFINITIONAL_REPRESENTATION('',(#80601),#80627); +#80601 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80602,#80603,#80604,#80605, + #80606,#80607,#80608,#80609,#80610,#80611,#80612,#80613,#80614, + #80615,#80616,#80617,#80618,#80619,#80620,#80621,#80622,#80623, + #80624,#80625,#80626),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.307214451902,0.324856505621,0.34249855934 ,0.360140613059,0.377782666778,0.395424720497,0.413066774216, 0.430708827935,0.448350881654,0.465992935373,0.483634989092, @@ -96891,471 +99880,471 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.571845257687,0.589487311406,0.607129365125,0.624771418844, 0.642413472563,0.660055526282,0.677697580001,0.69533963372), .QUASI_UNIFORM_KNOTS.); -#78210 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); -#78211 = CARTESIAN_POINT('',(1.637833825,0.313095136475)); -#78212 = CARTESIAN_POINT('',(1.637833825,0.324856505621)); -#78213 = CARTESIAN_POINT('',(1.637833825,0.34249855934)); -#78214 = CARTESIAN_POINT('',(1.637833825,0.360140613059)); -#78215 = CARTESIAN_POINT('',(1.637833825,0.377782666778)); -#78216 = CARTESIAN_POINT('',(1.637833825,0.395424720497)); -#78217 = CARTESIAN_POINT('',(1.637833825,0.413066774216)); -#78218 = CARTESIAN_POINT('',(1.637833825,0.430708827935)); -#78219 = CARTESIAN_POINT('',(1.637833825,0.448350881654)); -#78220 = CARTESIAN_POINT('',(1.637833825,0.465992935373)); -#78221 = CARTESIAN_POINT('',(1.637833825,0.483634989092)); -#78222 = CARTESIAN_POINT('',(1.637833825,0.501277042811)); -#78223 = CARTESIAN_POINT('',(1.637833825,0.51891909653)); -#78224 = CARTESIAN_POINT('',(1.637833825,0.536561150249)); -#78225 = CARTESIAN_POINT('',(1.637833825,0.554203203968)); -#78226 = CARTESIAN_POINT('',(1.637833825,0.571845257687)); -#78227 = CARTESIAN_POINT('',(1.637833825,0.589487311406)); -#78228 = CARTESIAN_POINT('',(1.637833825,0.607129365125)); -#78229 = CARTESIAN_POINT('',(1.637833825,0.624771418844)); -#78230 = CARTESIAN_POINT('',(1.637833825,0.642413472563)); -#78231 = CARTESIAN_POINT('',(1.637833825,0.660055526282)); -#78232 = CARTESIAN_POINT('',(1.637833825,0.677697580001)); -#78233 = CARTESIAN_POINT('',(1.637833825,0.689458949147)); -#78234 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); -#78235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78236 = ORIENTED_EDGE('',*,*,#78237,.T.); -#78237 = EDGE_CURVE('',#78193,#78238,#78240,.T.); -#78238 = VERTEX_POINT('',#78239); -#78239 = CARTESIAN_POINT('',(1.155,0.65,0.6)); -#78240 = SURFACE_CURVE('',#78241,(#78245,#78252),.PCURVE_S1.); -#78241 = LINE('',#78242,#78243); -#78242 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78243 = VECTOR('',#78244,1.); -#78244 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78245 = PCURVE('',#78129,#78246); -#78246 = DEFINITIONAL_REPRESENTATION('',(#78247),#78251); -#78247 = LINE('',#78248,#78249); -#78248 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78249 = VECTOR('',#78250,1.); -#78250 = DIRECTION('',(0.E+000,-1.)); -#78251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78252 = PCURVE('',#78253,#78258); -#78253 = PLANE('',#78254); -#78254 = AXIS2_PLACEMENT_3D('',#78255,#78256,#78257); -#78255 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78256 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); -#78257 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#78258 = DEFINITIONAL_REPRESENTATION('',(#78259),#78263); -#78259 = LINE('',#78260,#78261); -#78260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78261 = VECTOR('',#78262,1.); -#78262 = DIRECTION('',(0.E+000,-1.)); -#78263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78264 = ORIENTED_EDGE('',*,*,#78265,.T.); -#78265 = EDGE_CURVE('',#78238,#78266,#78268,.T.); -#78266 = VERTEX_POINT('',#78267); -#78267 = CARTESIAN_POINT('',(1.155,0.609807621135,0.75)); -#78268 = SURFACE_CURVE('',#78269,(#78273,#78280),.PCURVE_S1.); -#78269 = LINE('',#78270,#78271); -#78270 = CARTESIAN_POINT('',(1.155,0.65,0.6)); -#78271 = VECTOR('',#78272,1.); -#78272 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#78273 = PCURVE('',#78129,#78274); -#78274 = DEFINITIONAL_REPRESENTATION('',(#78275),#78279); -#78275 = LINE('',#78276,#78277); -#78276 = CARTESIAN_POINT('',(0.E+000,2.615)); -#78277 = VECTOR('',#78278,1.); -#78278 = DIRECTION('',(1.,0.E+000)); -#78279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78280 = PCURVE('',#78281,#78286); -#78281 = PLANE('',#78282); -#78282 = AXIS2_PLACEMENT_3D('',#78283,#78284,#78285); -#78283 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#78284 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78285 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78286 = DEFINITIONAL_REPRESENTATION('',(#78287),#78291); -#78287 = LINE('',#78288,#78289); -#78288 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#78289 = VECTOR('',#78290,1.); -#78290 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#78291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78292 = ORIENTED_EDGE('',*,*,#78293,.T.); -#78293 = EDGE_CURVE('',#78266,#78294,#78296,.T.); -#78294 = VERTEX_POINT('',#78295); -#78295 = CARTESIAN_POINT('',(0.755,0.609807621135,0.75)); -#78296 = SURFACE_CURVE('',#78297,(#78301,#78308),.PCURVE_S1.); -#78297 = LINE('',#78298,#78299); -#78298 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); -#78299 = VECTOR('',#78300,1.); -#78300 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78301 = PCURVE('',#78129,#78302); -#78302 = DEFINITIONAL_REPRESENTATION('',(#78303),#78307); -#78303 = LINE('',#78304,#78305); -#78304 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); -#78305 = VECTOR('',#78306,1.); -#78306 = DIRECTION('',(0.E+000,-1.)); -#78307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78308 = PCURVE('',#78309,#78314); -#78309 = PLANE('',#78310); -#78310 = AXIS2_PLACEMENT_3D('',#78311,#78312,#78313); -#78311 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#78312 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78313 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78314 = DEFINITIONAL_REPRESENTATION('',(#78315),#78319); -#78315 = LINE('',#78316,#78317); -#78316 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); -#78317 = VECTOR('',#78318,1.); -#78318 = DIRECTION('',(-1.,0.E+000)); -#78319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78320 = ORIENTED_EDGE('',*,*,#78321,.F.); -#78321 = EDGE_CURVE('',#78322,#78294,#78324,.T.); -#78322 = VERTEX_POINT('',#78323); -#78323 = CARTESIAN_POINT('',(0.755,0.65,0.6)); -#78324 = SURFACE_CURVE('',#78325,(#78329,#78336),.PCURVE_S1.); -#78325 = LINE('',#78326,#78327); -#78326 = CARTESIAN_POINT('',(0.755,0.65,0.6)); -#78327 = VECTOR('',#78328,1.); -#78328 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#78329 = PCURVE('',#78129,#78330); -#78330 = DEFINITIONAL_REPRESENTATION('',(#78331),#78335); -#78331 = LINE('',#78332,#78333); -#78332 = CARTESIAN_POINT('',(0.E+000,2.215)); -#78333 = VECTOR('',#78334,1.); -#78334 = DIRECTION('',(1.,0.E+000)); -#78335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78336 = PCURVE('',#78337,#78342); -#78337 = PLANE('',#78338); -#78338 = AXIS2_PLACEMENT_3D('',#78339,#78340,#78341); -#78339 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#78340 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78341 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78342 = DEFINITIONAL_REPRESENTATION('',(#78343),#78347); -#78343 = LINE('',#78344,#78345); -#78344 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#78345 = VECTOR('',#78346,1.); -#78346 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#78347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78348 = ORIENTED_EDGE('',*,*,#78349,.T.); -#78349 = EDGE_CURVE('',#78322,#78350,#78352,.T.); -#78350 = VERTEX_POINT('',#78351); -#78351 = CARTESIAN_POINT('',(0.2,0.65,0.6)); -#78352 = SURFACE_CURVE('',#78353,(#78357,#78364),.PCURVE_S1.); -#78353 = LINE('',#78354,#78355); -#78354 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78355 = VECTOR('',#78356,1.); -#78356 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78357 = PCURVE('',#78129,#78358); -#78358 = DEFINITIONAL_REPRESENTATION('',(#78359),#78363); -#78359 = LINE('',#78360,#78361); -#78360 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78361 = VECTOR('',#78362,1.); -#78362 = DIRECTION('',(0.E+000,-1.)); -#78363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78364 = PCURVE('',#78253,#78365); -#78365 = DEFINITIONAL_REPRESENTATION('',(#78366),#78370); -#78366 = LINE('',#78367,#78368); -#78367 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78368 = VECTOR('',#78369,1.); -#78369 = DIRECTION('',(0.E+000,-1.)); -#78370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78371 = ORIENTED_EDGE('',*,*,#78372,.F.); -#78372 = EDGE_CURVE('',#78373,#78350,#78375,.T.); -#78373 = VERTEX_POINT('',#78374); -#78374 = CARTESIAN_POINT('',(0.2,0.609807621135,0.75)); -#78375 = SURFACE_CURVE('',#78376,(#78380,#78387),.PCURVE_S1.); -#78376 = LINE('',#78377,#78378); -#78377 = CARTESIAN_POINT('',(0.2,0.65,0.6)); -#78378 = VECTOR('',#78379,1.); -#78379 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); -#78380 = PCURVE('',#78129,#78381); -#78381 = DEFINITIONAL_REPRESENTATION('',(#78382),#78386); -#78382 = LINE('',#78383,#78384); -#78383 = CARTESIAN_POINT('',(0.E+000,1.66)); -#78384 = VECTOR('',#78385,1.); -#78385 = DIRECTION('',(-1.,0.E+000)); -#78386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78387 = PCURVE('',#78388,#78393); -#78388 = PLANE('',#78389); -#78389 = AXIS2_PLACEMENT_3D('',#78390,#78391,#78392); -#78390 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); -#78391 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78392 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78393 = DEFINITIONAL_REPRESENTATION('',(#78394),#78398); -#78394 = LINE('',#78395,#78396); -#78395 = CARTESIAN_POINT('',(0.4,-0.295297240108)); -#78396 = VECTOR('',#78397,1.); -#78397 = DIRECTION('',(-0.965925826289,0.258819045103)); -#78398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78399 = ORIENTED_EDGE('',*,*,#78400,.T.); -#78400 = EDGE_CURVE('',#78373,#78401,#78403,.T.); -#78401 = VERTEX_POINT('',#78402); -#78402 = CARTESIAN_POINT('',(-0.2,0.609807621135,0.75)); -#78403 = SURFACE_CURVE('',#78404,(#78408,#78415),.PCURVE_S1.); -#78404 = LINE('',#78405,#78406); -#78405 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); -#78406 = VECTOR('',#78407,1.); -#78407 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78408 = PCURVE('',#78129,#78409); -#78409 = DEFINITIONAL_REPRESENTATION('',(#78410),#78414); -#78410 = LINE('',#78411,#78412); -#78411 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); -#78412 = VECTOR('',#78413,1.); -#78413 = DIRECTION('',(0.E+000,-1.)); -#78414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78415 = PCURVE('',#78416,#78421); -#78416 = PLANE('',#78417); -#78417 = AXIS2_PLACEMENT_3D('',#78418,#78419,#78420); -#78418 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#78419 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78420 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78421 = DEFINITIONAL_REPRESENTATION('',(#78422),#78426); -#78422 = LINE('',#78423,#78424); -#78423 = CARTESIAN_POINT('',(-1.26,-4.54003800589E-002)); -#78424 = VECTOR('',#78425,1.); -#78425 = DIRECTION('',(-1.,0.E+000)); -#78426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78427 = ORIENTED_EDGE('',*,*,#78428,.T.); -#78428 = EDGE_CURVE('',#78401,#78429,#78431,.T.); -#78429 = VERTEX_POINT('',#78430); -#78430 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); -#78431 = SURFACE_CURVE('',#78432,(#78436,#78443),.PCURVE_S1.); -#78432 = LINE('',#78433,#78434); -#78433 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); -#78434 = VECTOR('',#78435,1.); -#78435 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); -#78436 = PCURVE('',#78129,#78437); -#78437 = DEFINITIONAL_REPRESENTATION('',(#78438),#78442); -#78438 = LINE('',#78439,#78440); -#78439 = CARTESIAN_POINT('',(0.E+000,1.26)); -#78440 = VECTOR('',#78441,1.); -#78441 = DIRECTION('',(-1.,0.E+000)); -#78442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78443 = PCURVE('',#78444,#78449); -#78444 = PLANE('',#78445); -#78445 = AXIS2_PLACEMENT_3D('',#78446,#78447,#78448); -#78446 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#78447 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78448 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78449 = DEFINITIONAL_REPRESENTATION('',(#78450),#78454); -#78450 = LINE('',#78451,#78452); -#78451 = CARTESIAN_POINT('',(0.4,-0.295297240108)); -#78452 = VECTOR('',#78453,1.); -#78453 = DIRECTION('',(-0.965925826289,0.258819045103)); -#78454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78455 = ORIENTED_EDGE('',*,*,#78456,.T.); -#78456 = EDGE_CURVE('',#78429,#78457,#78459,.T.); -#78457 = VERTEX_POINT('',#78458); -#78458 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); -#78459 = SURFACE_CURVE('',#78460,(#78464,#78471),.PCURVE_S1.); -#78460 = LINE('',#78461,#78462); -#78461 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78462 = VECTOR('',#78463,1.); -#78463 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78464 = PCURVE('',#78129,#78465); -#78465 = DEFINITIONAL_REPRESENTATION('',(#78466),#78470); -#78466 = LINE('',#78467,#78468); -#78467 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78468 = VECTOR('',#78469,1.); -#78469 = DIRECTION('',(0.E+000,-1.)); -#78470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78471 = PCURVE('',#78253,#78472); -#78472 = DEFINITIONAL_REPRESENTATION('',(#78473),#78477); -#78473 = LINE('',#78474,#78475); -#78474 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78475 = VECTOR('',#78476,1.); -#78476 = DIRECTION('',(0.E+000,-1.)); -#78477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78478 = ORIENTED_EDGE('',*,*,#78479,.T.); -#78479 = EDGE_CURVE('',#78457,#78480,#78482,.T.); -#78480 = VERTEX_POINT('',#78481); -#78481 = CARTESIAN_POINT('',(-0.745,0.609807621135,0.75)); -#78482 = SURFACE_CURVE('',#78483,(#78487,#78494),.PCURVE_S1.); -#78483 = LINE('',#78484,#78485); -#78484 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); -#78485 = VECTOR('',#78486,1.); -#78486 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#78487 = PCURVE('',#78129,#78488); -#78488 = DEFINITIONAL_REPRESENTATION('',(#78489),#78493); -#78489 = LINE('',#78490,#78491); -#78490 = CARTESIAN_POINT('',(0.E+000,0.715)); -#78491 = VECTOR('',#78492,1.); -#78492 = DIRECTION('',(1.,0.E+000)); -#78493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78494 = PCURVE('',#78495,#78500); -#78495 = PLANE('',#78496); -#78496 = AXIS2_PLACEMENT_3D('',#78497,#78498,#78499); -#78497 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#78498 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78499 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78500 = DEFINITIONAL_REPRESENTATION('',(#78501),#78505); -#78501 = LINE('',#78502,#78503); -#78502 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#78503 = VECTOR('',#78504,1.); -#78504 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#78505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78506 = ORIENTED_EDGE('',*,*,#78507,.T.); -#78507 = EDGE_CURVE('',#78480,#78508,#78510,.T.); -#78508 = VERTEX_POINT('',#78509); -#78509 = CARTESIAN_POINT('',(-1.145,0.609807621135,0.75)); -#78510 = SURFACE_CURVE('',#78511,(#78515,#78522),.PCURVE_S1.); -#78511 = LINE('',#78512,#78513); -#78512 = CARTESIAN_POINT('',(-3.36,0.609807621135,0.75)); -#78513 = VECTOR('',#78514,1.); -#78514 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78515 = PCURVE('',#78129,#78516); -#78516 = DEFINITIONAL_REPRESENTATION('',(#78517),#78521); -#78517 = LINE('',#78518,#78519); -#78518 = CARTESIAN_POINT('',(0.155291427062,-1.9)); -#78519 = VECTOR('',#78520,1.); -#78520 = DIRECTION('',(0.E+000,-1.)); -#78521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78522 = PCURVE('',#78523,#78528); -#78523 = PLANE('',#78524); -#78524 = AXIS2_PLACEMENT_3D('',#78525,#78526,#78527); -#78525 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#78526 = DIRECTION('',(0.E+000,0.E+000,1.)); -#78527 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78528 = DEFINITIONAL_REPRESENTATION('',(#78529),#78533); -#78529 = LINE('',#78530,#78531); -#78530 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); -#78531 = VECTOR('',#78532,1.); -#78532 = DIRECTION('',(-1.,0.E+000)); -#78533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78534 = ORIENTED_EDGE('',*,*,#78535,.F.); -#78535 = EDGE_CURVE('',#78536,#78508,#78538,.T.); -#78536 = VERTEX_POINT('',#78537); -#78537 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); -#78538 = SURFACE_CURVE('',#78539,(#78543,#78550),.PCURVE_S1.); -#78539 = LINE('',#78540,#78541); -#78540 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); -#78541 = VECTOR('',#78542,1.); -#78542 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#78543 = PCURVE('',#78129,#78544); -#78544 = DEFINITIONAL_REPRESENTATION('',(#78545),#78549); -#78545 = LINE('',#78546,#78547); -#78546 = CARTESIAN_POINT('',(0.E+000,0.315)); -#78547 = VECTOR('',#78548,1.); -#78548 = DIRECTION('',(1.,0.E+000)); -#78549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78550 = PCURVE('',#78551,#78556); -#78551 = PLANE('',#78552); -#78552 = AXIS2_PLACEMENT_3D('',#78553,#78554,#78555); -#78553 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#78554 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78555 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78556 = DEFINITIONAL_REPRESENTATION('',(#78557),#78561); -#78557 = LINE('',#78558,#78559); -#78558 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#78559 = VECTOR('',#78560,1.); -#78560 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#78561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#80602 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); +#80603 = CARTESIAN_POINT('',(1.637833825,0.313095136475)); +#80604 = CARTESIAN_POINT('',(1.637833825,0.324856505621)); +#80605 = CARTESIAN_POINT('',(1.637833825,0.34249855934)); +#80606 = CARTESIAN_POINT('',(1.637833825,0.360140613059)); +#80607 = CARTESIAN_POINT('',(1.637833825,0.377782666778)); +#80608 = CARTESIAN_POINT('',(1.637833825,0.395424720497)); +#80609 = CARTESIAN_POINT('',(1.637833825,0.413066774216)); +#80610 = CARTESIAN_POINT('',(1.637833825,0.430708827935)); +#80611 = CARTESIAN_POINT('',(1.637833825,0.448350881654)); +#80612 = CARTESIAN_POINT('',(1.637833825,0.465992935373)); +#80613 = CARTESIAN_POINT('',(1.637833825,0.483634989092)); +#80614 = CARTESIAN_POINT('',(1.637833825,0.501277042811)); +#80615 = CARTESIAN_POINT('',(1.637833825,0.51891909653)); +#80616 = CARTESIAN_POINT('',(1.637833825,0.536561150249)); +#80617 = CARTESIAN_POINT('',(1.637833825,0.554203203968)); +#80618 = CARTESIAN_POINT('',(1.637833825,0.571845257687)); +#80619 = CARTESIAN_POINT('',(1.637833825,0.589487311406)); +#80620 = CARTESIAN_POINT('',(1.637833825,0.607129365125)); +#80621 = CARTESIAN_POINT('',(1.637833825,0.624771418844)); +#80622 = CARTESIAN_POINT('',(1.637833825,0.642413472563)); +#80623 = CARTESIAN_POINT('',(1.637833825,0.660055526282)); +#80624 = CARTESIAN_POINT('',(1.637833825,0.677697580001)); +#80625 = CARTESIAN_POINT('',(1.637833825,0.689458949147)); +#80626 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); +#80627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78562 = ORIENTED_EDGE('',*,*,#78563,.T.); -#78563 = EDGE_CURVE('',#78536,#78121,#78564,.T.); -#78564 = SURFACE_CURVE('',#78565,(#78569,#78576),.PCURVE_S1.); -#78565 = LINE('',#78566,#78567); -#78566 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78567 = VECTOR('',#78568,1.); -#78568 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78569 = PCURVE('',#78129,#78570); -#78570 = DEFINITIONAL_REPRESENTATION('',(#78571),#78575); -#78571 = LINE('',#78572,#78573); -#78572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78573 = VECTOR('',#78574,1.); -#78574 = DIRECTION('',(0.E+000,-1.)); -#78575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78576 = PCURVE('',#78253,#78577); -#78577 = DEFINITIONAL_REPRESENTATION('',(#78578),#78582); -#78578 = LINE('',#78579,#78580); -#78579 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78580 = VECTOR('',#78581,1.); -#78581 = DIRECTION('',(0.E+000,-1.)); -#78582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78583 = ADVANCED_FACE('',(#78584),#78598,.T.); -#78584 = FACE_BOUND('',#78585,.T.); -#78585 = EDGE_LOOP('',(#78586,#78638,#78681,#78726)); -#78586 = ORIENTED_EDGE('',*,*,#78587,.T.); -#78587 = EDGE_CURVE('',#78588,#78590,#78592,.T.); -#78588 = VERTEX_POINT('',#78589); -#78589 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); -#78590 = VERTEX_POINT('',#78591); -#78591 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 +#80628 = ORIENTED_EDGE('',*,*,#80629,.T.); +#80629 = EDGE_CURVE('',#80585,#80630,#80632,.T.); +#80630 = VERTEX_POINT('',#80631); +#80631 = CARTESIAN_POINT('',(1.155,0.65,0.6)); +#80632 = SURFACE_CURVE('',#80633,(#80637,#80644),.PCURVE_S1.); +#80633 = LINE('',#80634,#80635); +#80634 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80635 = VECTOR('',#80636,1.); +#80636 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80637 = PCURVE('',#80521,#80638); +#80638 = DEFINITIONAL_REPRESENTATION('',(#80639),#80643); +#80639 = LINE('',#80640,#80641); +#80640 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80641 = VECTOR('',#80642,1.); +#80642 = DIRECTION('',(0.E+000,-1.)); +#80643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80644 = PCURVE('',#80645,#80650); +#80645 = PLANE('',#80646); +#80646 = AXIS2_PLACEMENT_3D('',#80647,#80648,#80649); +#80647 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80648 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); +#80649 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#80650 = DEFINITIONAL_REPRESENTATION('',(#80651),#80655); +#80651 = LINE('',#80652,#80653); +#80652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80653 = VECTOR('',#80654,1.); +#80654 = DIRECTION('',(0.E+000,-1.)); +#80655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80656 = ORIENTED_EDGE('',*,*,#80657,.T.); +#80657 = EDGE_CURVE('',#80630,#80658,#80660,.T.); +#80658 = VERTEX_POINT('',#80659); +#80659 = CARTESIAN_POINT('',(1.155,0.609807621135,0.75)); +#80660 = SURFACE_CURVE('',#80661,(#80665,#80672),.PCURVE_S1.); +#80661 = LINE('',#80662,#80663); +#80662 = CARTESIAN_POINT('',(1.155,0.65,0.6)); +#80663 = VECTOR('',#80664,1.); +#80664 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#80665 = PCURVE('',#80521,#80666); +#80666 = DEFINITIONAL_REPRESENTATION('',(#80667),#80671); +#80667 = LINE('',#80668,#80669); +#80668 = CARTESIAN_POINT('',(0.E+000,2.615)); +#80669 = VECTOR('',#80670,1.); +#80670 = DIRECTION('',(1.,0.E+000)); +#80671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80672 = PCURVE('',#80673,#80678); +#80673 = PLANE('',#80674); +#80674 = AXIS2_PLACEMENT_3D('',#80675,#80676,#80677); +#80675 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#80676 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80677 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80678 = DEFINITIONAL_REPRESENTATION('',(#80679),#80683); +#80679 = LINE('',#80680,#80681); +#80680 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#80681 = VECTOR('',#80682,1.); +#80682 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#80683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80684 = ORIENTED_EDGE('',*,*,#80685,.T.); +#80685 = EDGE_CURVE('',#80658,#80686,#80688,.T.); +#80686 = VERTEX_POINT('',#80687); +#80687 = CARTESIAN_POINT('',(0.755,0.609807621135,0.75)); +#80688 = SURFACE_CURVE('',#80689,(#80693,#80700),.PCURVE_S1.); +#80689 = LINE('',#80690,#80691); +#80690 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); +#80691 = VECTOR('',#80692,1.); +#80692 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80693 = PCURVE('',#80521,#80694); +#80694 = DEFINITIONAL_REPRESENTATION('',(#80695),#80699); +#80695 = LINE('',#80696,#80697); +#80696 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); +#80697 = VECTOR('',#80698,1.); +#80698 = DIRECTION('',(0.E+000,-1.)); +#80699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80700 = PCURVE('',#80701,#80706); +#80701 = PLANE('',#80702); +#80702 = AXIS2_PLACEMENT_3D('',#80703,#80704,#80705); +#80703 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#80704 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80705 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80706 = DEFINITIONAL_REPRESENTATION('',(#80707),#80711); +#80707 = LINE('',#80708,#80709); +#80708 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); +#80709 = VECTOR('',#80710,1.); +#80710 = DIRECTION('',(-1.,0.E+000)); +#80711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80712 = ORIENTED_EDGE('',*,*,#80713,.F.); +#80713 = EDGE_CURVE('',#80714,#80686,#80716,.T.); +#80714 = VERTEX_POINT('',#80715); +#80715 = CARTESIAN_POINT('',(0.755,0.65,0.6)); +#80716 = SURFACE_CURVE('',#80717,(#80721,#80728),.PCURVE_S1.); +#80717 = LINE('',#80718,#80719); +#80718 = CARTESIAN_POINT('',(0.755,0.65,0.6)); +#80719 = VECTOR('',#80720,1.); +#80720 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#80721 = PCURVE('',#80521,#80722); +#80722 = DEFINITIONAL_REPRESENTATION('',(#80723),#80727); +#80723 = LINE('',#80724,#80725); +#80724 = CARTESIAN_POINT('',(0.E+000,2.215)); +#80725 = VECTOR('',#80726,1.); +#80726 = DIRECTION('',(1.,0.E+000)); +#80727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80728 = PCURVE('',#80729,#80734); +#80729 = PLANE('',#80730); +#80730 = AXIS2_PLACEMENT_3D('',#80731,#80732,#80733); +#80731 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#80732 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80733 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80734 = DEFINITIONAL_REPRESENTATION('',(#80735),#80739); +#80735 = LINE('',#80736,#80737); +#80736 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#80737 = VECTOR('',#80738,1.); +#80738 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#80739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80740 = ORIENTED_EDGE('',*,*,#80741,.T.); +#80741 = EDGE_CURVE('',#80714,#80742,#80744,.T.); +#80742 = VERTEX_POINT('',#80743); +#80743 = CARTESIAN_POINT('',(0.2,0.65,0.6)); +#80744 = SURFACE_CURVE('',#80745,(#80749,#80756),.PCURVE_S1.); +#80745 = LINE('',#80746,#80747); +#80746 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80747 = VECTOR('',#80748,1.); +#80748 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80749 = PCURVE('',#80521,#80750); +#80750 = DEFINITIONAL_REPRESENTATION('',(#80751),#80755); +#80751 = LINE('',#80752,#80753); +#80752 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80753 = VECTOR('',#80754,1.); +#80754 = DIRECTION('',(0.E+000,-1.)); +#80755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80756 = PCURVE('',#80645,#80757); +#80757 = DEFINITIONAL_REPRESENTATION('',(#80758),#80762); +#80758 = LINE('',#80759,#80760); +#80759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80760 = VECTOR('',#80761,1.); +#80761 = DIRECTION('',(0.E+000,-1.)); +#80762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80763 = ORIENTED_EDGE('',*,*,#80764,.F.); +#80764 = EDGE_CURVE('',#80765,#80742,#80767,.T.); +#80765 = VERTEX_POINT('',#80766); +#80766 = CARTESIAN_POINT('',(0.2,0.609807621135,0.75)); +#80767 = SURFACE_CURVE('',#80768,(#80772,#80779),.PCURVE_S1.); +#80768 = LINE('',#80769,#80770); +#80769 = CARTESIAN_POINT('',(0.2,0.65,0.6)); +#80770 = VECTOR('',#80771,1.); +#80771 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); +#80772 = PCURVE('',#80521,#80773); +#80773 = DEFINITIONAL_REPRESENTATION('',(#80774),#80778); +#80774 = LINE('',#80775,#80776); +#80775 = CARTESIAN_POINT('',(0.E+000,1.66)); +#80776 = VECTOR('',#80777,1.); +#80777 = DIRECTION('',(-1.,0.E+000)); +#80778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80779 = PCURVE('',#80780,#80785); +#80780 = PLANE('',#80781); +#80781 = AXIS2_PLACEMENT_3D('',#80782,#80783,#80784); +#80782 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); +#80783 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80784 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80785 = DEFINITIONAL_REPRESENTATION('',(#80786),#80790); +#80786 = LINE('',#80787,#80788); +#80787 = CARTESIAN_POINT('',(0.4,-0.295297240108)); +#80788 = VECTOR('',#80789,1.); +#80789 = DIRECTION('',(-0.965925826289,0.258819045103)); +#80790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80791 = ORIENTED_EDGE('',*,*,#80792,.T.); +#80792 = EDGE_CURVE('',#80765,#80793,#80795,.T.); +#80793 = VERTEX_POINT('',#80794); +#80794 = CARTESIAN_POINT('',(-0.2,0.609807621135,0.75)); +#80795 = SURFACE_CURVE('',#80796,(#80800,#80807),.PCURVE_S1.); +#80796 = LINE('',#80797,#80798); +#80797 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); +#80798 = VECTOR('',#80799,1.); +#80799 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80800 = PCURVE('',#80521,#80801); +#80801 = DEFINITIONAL_REPRESENTATION('',(#80802),#80806); +#80802 = LINE('',#80803,#80804); +#80803 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); +#80804 = VECTOR('',#80805,1.); +#80805 = DIRECTION('',(0.E+000,-1.)); +#80806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80807 = PCURVE('',#80808,#80813); +#80808 = PLANE('',#80809); +#80809 = AXIS2_PLACEMENT_3D('',#80810,#80811,#80812); +#80810 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#80811 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80812 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80813 = DEFINITIONAL_REPRESENTATION('',(#80814),#80818); +#80814 = LINE('',#80815,#80816); +#80815 = CARTESIAN_POINT('',(-1.26,-4.54003800589E-002)); +#80816 = VECTOR('',#80817,1.); +#80817 = DIRECTION('',(-1.,0.E+000)); +#80818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80819 = ORIENTED_EDGE('',*,*,#80820,.T.); +#80820 = EDGE_CURVE('',#80793,#80821,#80823,.T.); +#80821 = VERTEX_POINT('',#80822); +#80822 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); +#80823 = SURFACE_CURVE('',#80824,(#80828,#80835),.PCURVE_S1.); +#80824 = LINE('',#80825,#80826); +#80825 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); +#80826 = VECTOR('',#80827,1.); +#80827 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); +#80828 = PCURVE('',#80521,#80829); +#80829 = DEFINITIONAL_REPRESENTATION('',(#80830),#80834); +#80830 = LINE('',#80831,#80832); +#80831 = CARTESIAN_POINT('',(0.E+000,1.26)); +#80832 = VECTOR('',#80833,1.); +#80833 = DIRECTION('',(-1.,0.E+000)); +#80834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80835 = PCURVE('',#80836,#80841); +#80836 = PLANE('',#80837); +#80837 = AXIS2_PLACEMENT_3D('',#80838,#80839,#80840); +#80838 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#80839 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80840 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80841 = DEFINITIONAL_REPRESENTATION('',(#80842),#80846); +#80842 = LINE('',#80843,#80844); +#80843 = CARTESIAN_POINT('',(0.4,-0.295297240108)); +#80844 = VECTOR('',#80845,1.); +#80845 = DIRECTION('',(-0.965925826289,0.258819045103)); +#80846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80847 = ORIENTED_EDGE('',*,*,#80848,.T.); +#80848 = EDGE_CURVE('',#80821,#80849,#80851,.T.); +#80849 = VERTEX_POINT('',#80850); +#80850 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); +#80851 = SURFACE_CURVE('',#80852,(#80856,#80863),.PCURVE_S1.); +#80852 = LINE('',#80853,#80854); +#80853 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80854 = VECTOR('',#80855,1.); +#80855 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80856 = PCURVE('',#80521,#80857); +#80857 = DEFINITIONAL_REPRESENTATION('',(#80858),#80862); +#80858 = LINE('',#80859,#80860); +#80859 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80860 = VECTOR('',#80861,1.); +#80861 = DIRECTION('',(0.E+000,-1.)); +#80862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80863 = PCURVE('',#80645,#80864); +#80864 = DEFINITIONAL_REPRESENTATION('',(#80865),#80869); +#80865 = LINE('',#80866,#80867); +#80866 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80867 = VECTOR('',#80868,1.); +#80868 = DIRECTION('',(0.E+000,-1.)); +#80869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80870 = ORIENTED_EDGE('',*,*,#80871,.T.); +#80871 = EDGE_CURVE('',#80849,#80872,#80874,.T.); +#80872 = VERTEX_POINT('',#80873); +#80873 = CARTESIAN_POINT('',(-0.745,0.609807621135,0.75)); +#80874 = SURFACE_CURVE('',#80875,(#80879,#80886),.PCURVE_S1.); +#80875 = LINE('',#80876,#80877); +#80876 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); +#80877 = VECTOR('',#80878,1.); +#80878 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#80879 = PCURVE('',#80521,#80880); +#80880 = DEFINITIONAL_REPRESENTATION('',(#80881),#80885); +#80881 = LINE('',#80882,#80883); +#80882 = CARTESIAN_POINT('',(0.E+000,0.715)); +#80883 = VECTOR('',#80884,1.); +#80884 = DIRECTION('',(1.,0.E+000)); +#80885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80886 = PCURVE('',#80887,#80892); +#80887 = PLANE('',#80888); +#80888 = AXIS2_PLACEMENT_3D('',#80889,#80890,#80891); +#80889 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#80890 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80891 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80892 = DEFINITIONAL_REPRESENTATION('',(#80893),#80897); +#80893 = LINE('',#80894,#80895); +#80894 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#80895 = VECTOR('',#80896,1.); +#80896 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#80897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80898 = ORIENTED_EDGE('',*,*,#80899,.T.); +#80899 = EDGE_CURVE('',#80872,#80900,#80902,.T.); +#80900 = VERTEX_POINT('',#80901); +#80901 = CARTESIAN_POINT('',(-1.145,0.609807621135,0.75)); +#80902 = SURFACE_CURVE('',#80903,(#80907,#80914),.PCURVE_S1.); +#80903 = LINE('',#80904,#80905); +#80904 = CARTESIAN_POINT('',(-3.36,0.609807621135,0.75)); +#80905 = VECTOR('',#80906,1.); +#80906 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80907 = PCURVE('',#80521,#80908); +#80908 = DEFINITIONAL_REPRESENTATION('',(#80909),#80913); +#80909 = LINE('',#80910,#80911); +#80910 = CARTESIAN_POINT('',(0.155291427062,-1.9)); +#80911 = VECTOR('',#80912,1.); +#80912 = DIRECTION('',(0.E+000,-1.)); +#80913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80914 = PCURVE('',#80915,#80920); +#80915 = PLANE('',#80916); +#80916 = AXIS2_PLACEMENT_3D('',#80917,#80918,#80919); +#80917 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#80918 = DIRECTION('',(0.E+000,0.E+000,1.)); +#80919 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80920 = DEFINITIONAL_REPRESENTATION('',(#80921),#80925); +#80921 = LINE('',#80922,#80923); +#80922 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); +#80923 = VECTOR('',#80924,1.); +#80924 = DIRECTION('',(-1.,0.E+000)); +#80925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80926 = ORIENTED_EDGE('',*,*,#80927,.F.); +#80927 = EDGE_CURVE('',#80928,#80900,#80930,.T.); +#80928 = VERTEX_POINT('',#80929); +#80929 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); +#80930 = SURFACE_CURVE('',#80931,(#80935,#80942),.PCURVE_S1.); +#80931 = LINE('',#80932,#80933); +#80932 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); +#80933 = VECTOR('',#80934,1.); +#80934 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#80935 = PCURVE('',#80521,#80936); +#80936 = DEFINITIONAL_REPRESENTATION('',(#80937),#80941); +#80937 = LINE('',#80938,#80939); +#80938 = CARTESIAN_POINT('',(0.E+000,0.315)); +#80939 = VECTOR('',#80940,1.); +#80940 = DIRECTION('',(1.,0.E+000)); +#80941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80942 = PCURVE('',#80943,#80948); +#80943 = PLANE('',#80944); +#80944 = AXIS2_PLACEMENT_3D('',#80945,#80946,#80947); +#80945 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#80946 = DIRECTION('',(1.,0.E+000,0.E+000)); +#80947 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#80948 = DEFINITIONAL_REPRESENTATION('',(#80949),#80953); +#80949 = LINE('',#80950,#80951); +#80950 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#80951 = VECTOR('',#80952,1.); +#80952 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#80953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80954 = ORIENTED_EDGE('',*,*,#80955,.T.); +#80955 = EDGE_CURVE('',#80928,#80513,#80956,.T.); +#80956 = SURFACE_CURVE('',#80957,(#80961,#80968),.PCURVE_S1.); +#80957 = LINE('',#80958,#80959); +#80958 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#80959 = VECTOR('',#80960,1.); +#80960 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#80961 = PCURVE('',#80521,#80962); +#80962 = DEFINITIONAL_REPRESENTATION('',(#80963),#80967); +#80963 = LINE('',#80964,#80965); +#80964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80965 = VECTOR('',#80966,1.); +#80966 = DIRECTION('',(0.E+000,-1.)); +#80967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80968 = PCURVE('',#80645,#80969); +#80969 = DEFINITIONAL_REPRESENTATION('',(#80970),#80974); +#80970 = LINE('',#80971,#80972); +#80971 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#80972 = VECTOR('',#80973,1.); +#80973 = DIRECTION('',(0.E+000,-1.)); +#80974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#80975 = ADVANCED_FACE('',(#80976),#80990,.T.); +#80976 = FACE_BOUND('',#80977,.T.); +#80977 = EDGE_LOOP('',(#80978,#81030,#81073,#81118)); +#80978 = ORIENTED_EDGE('',*,*,#80979,.T.); +#80979 = EDGE_CURVE('',#80980,#80982,#80984,.T.); +#80980 = VERTEX_POINT('',#80981); +#80981 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); +#80982 = VERTEX_POINT('',#80983); +#80983 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 )); -#78592 = SURFACE_CURVE('',#78593,(#78597,#78609),.PCURVE_S1.); -#78593 = LINE('',#78594,#78595); -#78594 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, +#80984 = SURFACE_CURVE('',#80985,(#80989,#81001),.PCURVE_S1.); +#80985 = LINE('',#80986,#80987); +#80986 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, 0.329352184392)); -#78595 = VECTOR('',#78596,1.); -#78596 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); -#78597 = PCURVE('',#78598,#78603); -#78598 = PLANE('',#78599); -#78599 = AXIS2_PLACEMENT_3D('',#78600,#78601,#78602); -#78600 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#78601 = DIRECTION('',(0.965925826289,1.61116750665E-016,-0.258819045103 +#80987 = VECTOR('',#80988,1.); +#80988 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); +#80989 = PCURVE('',#80990,#80995); +#80990 = PLANE('',#80991); +#80991 = AXIS2_PLACEMENT_3D('',#80992,#80993,#80994); +#80992 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#80993 = DIRECTION('',(0.965925826289,1.61116750665E-016,-0.258819045103 )); -#78602 = DIRECTION('',(-0.258819045103,9.069926331849E-033, +#80994 = DIRECTION('',(-0.258819045103,9.069926331849E-033, -0.965925826289)); -#78603 = DEFINITIONAL_REPRESENTATION('',(#78604),#78608); -#78604 = LINE('',#78605,#78606); -#78605 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); -#78606 = VECTOR('',#78607,1.); -#78607 = DIRECTION('',(0.968100345886,0.250562807086)); -#78608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78609 = PCURVE('',#75745,#78610); -#78610 = DEFINITIONAL_REPRESENTATION('',(#78611),#78637); -#78611 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78612,#78613,#78614,#78615, - #78616,#78617,#78618,#78619,#78620,#78621,#78622,#78623,#78624, - #78625,#78626,#78627,#78628,#78629,#78630,#78631,#78632,#78633, - #78634,#78635,#78636),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#80995 = DEFINITIONAL_REPRESENTATION('',(#80996),#81000); +#80996 = LINE('',#80997,#80998); +#80997 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); +#80998 = VECTOR('',#80999,1.); +#80999 = DIRECTION('',(0.968100345886,0.250562807086)); +#81000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81001 = PCURVE('',#78137,#81002); +#81002 = DEFINITIONAL_REPRESENTATION('',(#81003),#81029); +#81003 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81004,#81005,#81006,#81007, + #81008,#81009,#81010,#81011,#81012,#81013,#81014,#81015,#81016, + #81017,#81018,#81019,#81020,#81021,#81022,#81023,#81024,#81025, + #81026,#81027,#81028),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.289427886241,-0.26692497193, -0.244422057619,-0.221919143309,-0.199416228998,-0.176913314688, -0.154410400377,-0.131907486066,-0.109404571756,-8.690165744525E-002 @@ -97363,57 +100352,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 3.109999797173E-003,2.561291410778E-002,4.811582841839E-002, 7.061874272899E-002,9.31216570396E-002,0.11562457135,0.138127485661, 0.160630399971,0.183133314282,0.205636228593),.UNSPECIFIED.); -#78612 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); -#78613 = CARTESIAN_POINT('',(6.28318530718,0.687838662283)); -#78614 = CARTESIAN_POINT('',(6.28318530718,0.672836719409)); -#78615 = CARTESIAN_POINT('',(6.28318530718,0.650333805098)); -#78616 = CARTESIAN_POINT('',(6.28318530718,0.627830890788)); -#78617 = CARTESIAN_POINT('',(6.28318530718,0.605327976477)); -#78618 = CARTESIAN_POINT('',(6.28318530718,0.582825062167)); -#78619 = CARTESIAN_POINT('',(6.28318530718,0.560322147856)); -#78620 = CARTESIAN_POINT('',(6.28318530718,0.537819233545)); -#78621 = CARTESIAN_POINT('',(6.28318530718,0.515316319235)); -#78622 = CARTESIAN_POINT('',(6.28318530718,0.492813404924)); -#78623 = CARTESIAN_POINT('',(6.28318530718,0.470310490614)); -#78624 = CARTESIAN_POINT('',(6.28318530718,0.447807576303)); -#78625 = CARTESIAN_POINT('',(6.28318530718,0.425304661992)); -#78626 = CARTESIAN_POINT('',(6.28318530718,0.402801747682)); -#78627 = CARTESIAN_POINT('',(6.28318530718,0.380298833371)); -#78628 = CARTESIAN_POINT('',(6.28318530718,0.35779591906)); -#78629 = CARTESIAN_POINT('',(6.28318530718,0.33529300475)); -#78630 = CARTESIAN_POINT('',(6.28318530718,0.312790090439)); -#78631 = CARTESIAN_POINT('',(6.28318530718,0.290287176129)); -#78632 = CARTESIAN_POINT('',(6.28318530718,0.267784261818)); -#78633 = CARTESIAN_POINT('',(6.28318530718,0.245281347507)); -#78634 = CARTESIAN_POINT('',(6.28318530718,0.222778433197)); -#78635 = CARTESIAN_POINT('',(6.28318530718,0.207776490323)); -#78636 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); -#78637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78638 = ORIENTED_EDGE('',*,*,#78639,.T.); -#78639 = EDGE_CURVE('',#78590,#76257,#78640,.T.); -#78640 = SURFACE_CURVE('',#78641,(#78645,#78652),.PCURVE_S1.); -#78641 = LINE('',#78642,#78643); -#78642 = CARTESIAN_POINT('',(1.3359553457,0.371136529841,0.137059047745) - ); -#78643 = VECTOR('',#78644,1.); -#78644 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); -#78645 = PCURVE('',#78598,#78646); -#78646 = DEFINITIONAL_REPRESENTATION('',(#78647),#78651); -#78647 = LINE('',#78648,#78649); -#78648 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); -#78649 = VECTOR('',#78650,1.); -#78650 = DIRECTION('',(4.317110322781E-017,1.)); -#78651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78652 = PCURVE('',#76366,#78653); -#78653 = DEFINITIONAL_REPRESENTATION('',(#78654),#78680); -#78654 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78655,#78656,#78657,#78658, - #78659,#78660,#78661,#78662,#78663,#78664,#78665,#78666,#78667, - #78668,#78669,#78670,#78671,#78672,#78673,#78674,#78675,#78676, - #78677,#78678,#78679),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81004 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); +#81005 = CARTESIAN_POINT('',(6.28318530718,0.687838662283)); +#81006 = CARTESIAN_POINT('',(6.28318530718,0.672836719409)); +#81007 = CARTESIAN_POINT('',(6.28318530718,0.650333805098)); +#81008 = CARTESIAN_POINT('',(6.28318530718,0.627830890788)); +#81009 = CARTESIAN_POINT('',(6.28318530718,0.605327976477)); +#81010 = CARTESIAN_POINT('',(6.28318530718,0.582825062167)); +#81011 = CARTESIAN_POINT('',(6.28318530718,0.560322147856)); +#81012 = CARTESIAN_POINT('',(6.28318530718,0.537819233545)); +#81013 = CARTESIAN_POINT('',(6.28318530718,0.515316319235)); +#81014 = CARTESIAN_POINT('',(6.28318530718,0.492813404924)); +#81015 = CARTESIAN_POINT('',(6.28318530718,0.470310490614)); +#81016 = CARTESIAN_POINT('',(6.28318530718,0.447807576303)); +#81017 = CARTESIAN_POINT('',(6.28318530718,0.425304661992)); +#81018 = CARTESIAN_POINT('',(6.28318530718,0.402801747682)); +#81019 = CARTESIAN_POINT('',(6.28318530718,0.380298833371)); +#81020 = CARTESIAN_POINT('',(6.28318530718,0.35779591906)); +#81021 = CARTESIAN_POINT('',(6.28318530718,0.33529300475)); +#81022 = CARTESIAN_POINT('',(6.28318530718,0.312790090439)); +#81023 = CARTESIAN_POINT('',(6.28318530718,0.290287176129)); +#81024 = CARTESIAN_POINT('',(6.28318530718,0.267784261818)); +#81025 = CARTESIAN_POINT('',(6.28318530718,0.245281347507)); +#81026 = CARTESIAN_POINT('',(6.28318530718,0.222778433197)); +#81027 = CARTESIAN_POINT('',(6.28318530718,0.207776490323)); +#81028 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); +#81029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81030 = ORIENTED_EDGE('',*,*,#81031,.T.); +#81031 = EDGE_CURVE('',#80982,#78649,#81032,.T.); +#81032 = SURFACE_CURVE('',#81033,(#81037,#81044),.PCURVE_S1.); +#81033 = LINE('',#81034,#81035); +#81034 = CARTESIAN_POINT('',(1.3359553457,0.371136529841,0.137059047745) + ); +#81035 = VECTOR('',#81036,1.); +#81036 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); +#81037 = PCURVE('',#80990,#81038); +#81038 = DEFINITIONAL_REPRESENTATION('',(#81039),#81043); +#81039 = LINE('',#81040,#81041); +#81040 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); +#81041 = VECTOR('',#81042,1.); +#81042 = DIRECTION('',(4.317110322781E-017,1.)); +#81043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81044 = PCURVE('',#78758,#81045); +#81045 = DEFINITIONAL_REPRESENTATION('',(#81046),#81072); +#81046 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81047,#81048,#81049,#81050, + #81051,#81052,#81053,#81054,#81055,#81056,#81057,#81058,#81059, + #81060,#81061,#81062,#81063,#81064,#81065,#81066,#81067,#81068, + #81069,#81070,#81071),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598,-0.717560595074, -0.682918188551,-0.648275782028,-0.613633375504,-0.578990968981, -0.544348562458,-0.509706155934,-0.475063749411,-0.440421342888, @@ -97421,59 +100410,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.267209310271,-0.232566903748,-0.197924497224,-0.163282090701, -0.128639684178,-9.399727765447E-002,-5.935487113115E-002, -2.471246460782E-002,9.929941915506E-003),.UNSPECIFIED.); -#78655 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); -#78656 = CARTESIAN_POINT('',(6.02138591938,1.019519002915)); -#78657 = CARTESIAN_POINT('',(6.02138591938,0.996424065233)); -#78658 = CARTESIAN_POINT('',(6.02138591938,0.96178165871)); -#78659 = CARTESIAN_POINT('',(6.02138591938,0.927139252187)); -#78660 = CARTESIAN_POINT('',(6.02138591938,0.892496845663)); -#78661 = CARTESIAN_POINT('',(6.02138591938,0.85785443914)); -#78662 = CARTESIAN_POINT('',(6.02138591938,0.823212032617)); -#78663 = CARTESIAN_POINT('',(6.02138591938,0.788569626093)); -#78664 = CARTESIAN_POINT('',(6.02138591938,0.75392721957)); -#78665 = CARTESIAN_POINT('',(6.02138591938,0.719284813047)); -#78666 = CARTESIAN_POINT('',(6.02138591938,0.684642406523)); -#78667 = CARTESIAN_POINT('',(6.02138591938,0.65)); -#78668 = CARTESIAN_POINT('',(6.02138591938,0.615357593477)); -#78669 = CARTESIAN_POINT('',(6.02138591938,0.580715186953)); -#78670 = CARTESIAN_POINT('',(6.02138591938,0.54607278043)); -#78671 = CARTESIAN_POINT('',(6.02138591938,0.511430373907)); -#78672 = CARTESIAN_POINT('',(6.02138591938,0.476787967383)); -#78673 = CARTESIAN_POINT('',(6.02138591938,0.44214556086)); -#78674 = CARTESIAN_POINT('',(6.02138591938,0.407503154337)); -#78675 = CARTESIAN_POINT('',(6.02138591938,0.372860747813)); -#78676 = CARTESIAN_POINT('',(6.02138591938,0.33821834129)); -#78677 = CARTESIAN_POINT('',(6.02138591938,0.303575934767)); -#78678 = CARTESIAN_POINT('',(6.02138591938,0.280480997085)); -#78679 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#78680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78681 = ORIENTED_EDGE('',*,*,#78682,.T.); -#78682 = EDGE_CURVE('',#76257,#78683,#78685,.T.); -#78683 = VERTEX_POINT('',#78684); -#78684 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); -#78685 = SURFACE_CURVE('',#78686,(#78690,#78697),.PCURVE_S1.); -#78686 = LINE('',#78687,#78688); -#78687 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, +#81047 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); +#81048 = CARTESIAN_POINT('',(6.02138591938,1.019519002915)); +#81049 = CARTESIAN_POINT('',(6.02138591938,0.996424065233)); +#81050 = CARTESIAN_POINT('',(6.02138591938,0.96178165871)); +#81051 = CARTESIAN_POINT('',(6.02138591938,0.927139252187)); +#81052 = CARTESIAN_POINT('',(6.02138591938,0.892496845663)); +#81053 = CARTESIAN_POINT('',(6.02138591938,0.85785443914)); +#81054 = CARTESIAN_POINT('',(6.02138591938,0.823212032617)); +#81055 = CARTESIAN_POINT('',(6.02138591938,0.788569626093)); +#81056 = CARTESIAN_POINT('',(6.02138591938,0.75392721957)); +#81057 = CARTESIAN_POINT('',(6.02138591938,0.719284813047)); +#81058 = CARTESIAN_POINT('',(6.02138591938,0.684642406523)); +#81059 = CARTESIAN_POINT('',(6.02138591938,0.65)); +#81060 = CARTESIAN_POINT('',(6.02138591938,0.615357593477)); +#81061 = CARTESIAN_POINT('',(6.02138591938,0.580715186953)); +#81062 = CARTESIAN_POINT('',(6.02138591938,0.54607278043)); +#81063 = CARTESIAN_POINT('',(6.02138591938,0.511430373907)); +#81064 = CARTESIAN_POINT('',(6.02138591938,0.476787967383)); +#81065 = CARTESIAN_POINT('',(6.02138591938,0.44214556086)); +#81066 = CARTESIAN_POINT('',(6.02138591938,0.407503154337)); +#81067 = CARTESIAN_POINT('',(6.02138591938,0.372860747813)); +#81068 = CARTESIAN_POINT('',(6.02138591938,0.33821834129)); +#81069 = CARTESIAN_POINT('',(6.02138591938,0.303575934767)); +#81070 = CARTESIAN_POINT('',(6.02138591938,0.280480997085)); +#81071 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#81072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81073 = ORIENTED_EDGE('',*,*,#81074,.T.); +#81074 = EDGE_CURVE('',#78649,#81075,#81077,.T.); +#81075 = VERTEX_POINT('',#81076); +#81076 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); +#81077 = SURFACE_CURVE('',#81078,(#81082,#81089),.PCURVE_S1.); +#81078 = LINE('',#81079,#81080); +#81079 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, 0.633948125296)); -#78688 = VECTOR('',#78689,1.); -#78689 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#78690 = PCURVE('',#78598,#78691); -#78691 = DEFINITIONAL_REPRESENTATION('',(#78692),#78696); -#78692 = LINE('',#78693,#78694); -#78693 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#78694 = VECTOR('',#78695,1.); -#78695 = DIRECTION('',(-0.968100345886,0.250562807086)); -#78696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78697 = PCURVE('',#76295,#78698); -#78698 = DEFINITIONAL_REPRESENTATION('',(#78699),#78725); -#78699 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78700,#78701,#78702,#78703, - #78704,#78705,#78706,#78707,#78708,#78709,#78710,#78711,#78712, - #78713,#78714,#78715,#78716,#78717,#78718,#78719,#78720,#78721, - #78722,#78723,#78724),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81080 = VECTOR('',#81081,1.); +#81081 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#81082 = PCURVE('',#80990,#81083); +#81083 = DEFINITIONAL_REPRESENTATION('',(#81084),#81088); +#81084 = LINE('',#81085,#81086); +#81085 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#81086 = VECTOR('',#81087,1.); +#81087 = DIRECTION('',(-0.968100345886,0.250562807086)); +#81088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81089 = PCURVE('',#78687,#81090); +#81090 = DEFINITIONAL_REPRESENTATION('',(#81091),#81117); +#81091 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81092,#81093,#81094,#81095, + #81096,#81097,#81098,#81099,#81100,#81101,#81102,#81103,#81104, + #81105,#81106,#81107,#81108,#81109,#81110,#81111,#81112,#81113, + #81114,#81115,#81116),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.531367877804,-0.508864963493, -0.486362049183,-0.463859134872,-0.441356220562,-0.418853306251, -0.39635039194,-0.37384747763,-0.351344563319,-0.328841649009, @@ -97481,98 +100470,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.216327077456,-0.193824163145,-0.171321248834,-0.148818334524, -0.126315420213,-0.103812505903,-8.130959159195E-002, -5.880667728135E-002,-3.630376297074E-002),.UNSPECIFIED.); -#78700 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#78701 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.523866906367)); -#78702 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.508864963493)); -#78703 = CARTESIAN_POINT('',(0.E+000,-0.486362049183)); -#78704 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.463859134872)); -#78705 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.441356220562)); -#78706 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.418853306251)); -#78707 = CARTESIAN_POINT('',(0.E+000,-0.39635039194)); -#78708 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.37384747763)); -#78709 = CARTESIAN_POINT('',(8.881784197001E-016,-0.351344563319)); -#78710 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.328841649009)); -#78711 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.306338734698)); -#78712 = CARTESIAN_POINT('',(0.E+000,-0.283835820387)); -#78713 = CARTESIAN_POINT('',(0.E+000,-0.261332906077)); -#78714 = CARTESIAN_POINT('',(8.881784197001E-016,-0.238829991766)); -#78715 = CARTESIAN_POINT('',(0.E+000,-0.216327077456)); -#78716 = CARTESIAN_POINT('',(8.881784197001E-016,-0.193824163145)); -#78717 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.171321248834)); -#78718 = CARTESIAN_POINT('',(8.881784197001E-016,-0.148818334524)); -#78719 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.126315420213)); -#78720 = CARTESIAN_POINT('',(8.881784197001E-016,-0.103812505903)); -#78721 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.130959159195E-002) - ); -#78722 = CARTESIAN_POINT('',(-8.881784197001E-016,-5.880667728135E-002) - ); -#78723 = CARTESIAN_POINT('',(0.E+000,-4.380473440761E-002)); -#78724 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#78725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78726 = ORIENTED_EDGE('',*,*,#78727,.F.); -#78727 = EDGE_CURVE('',#78588,#78683,#78728,.T.); -#78728 = SURFACE_CURVE('',#78729,(#78733,#78740),.PCURVE_S1.); -#78729 = LINE('',#78730,#78731); -#78730 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#78731 = VECTOR('',#78732,1.); -#78732 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#78733 = PCURVE('',#78598,#78734); -#78734 = DEFINITIONAL_REPRESENTATION('',(#78735),#78739); -#78735 = LINE('',#78736,#78737); -#78736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78737 = VECTOR('',#78738,1.); -#78738 = DIRECTION('',(4.317110322781E-017,1.)); -#78739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78740 = PCURVE('',#78741,#78746); -#78741 = PLANE('',#78742); -#78742 = AXIS2_PLACEMENT_3D('',#78743,#78744,#78745); -#78743 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#78744 = DIRECTION('',(0.965925826289,1.61116750665E-016,0.258819045103) - ); -#78745 = DIRECTION('',(0.258819045103,-9.069926331849E-033, +#81092 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#81093 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.523866906367)); +#81094 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.508864963493)); +#81095 = CARTESIAN_POINT('',(0.E+000,-0.486362049183)); +#81096 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.463859134872)); +#81097 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.441356220562)); +#81098 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.418853306251)); +#81099 = CARTESIAN_POINT('',(0.E+000,-0.39635039194)); +#81100 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.37384747763)); +#81101 = CARTESIAN_POINT('',(8.881784197001E-016,-0.351344563319)); +#81102 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.328841649009)); +#81103 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.306338734698)); +#81104 = CARTESIAN_POINT('',(0.E+000,-0.283835820387)); +#81105 = CARTESIAN_POINT('',(0.E+000,-0.261332906077)); +#81106 = CARTESIAN_POINT('',(8.881784197001E-016,-0.238829991766)); +#81107 = CARTESIAN_POINT('',(0.E+000,-0.216327077456)); +#81108 = CARTESIAN_POINT('',(8.881784197001E-016,-0.193824163145)); +#81109 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.171321248834)); +#81110 = CARTESIAN_POINT('',(8.881784197001E-016,-0.148818334524)); +#81111 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.126315420213)); +#81112 = CARTESIAN_POINT('',(8.881784197001E-016,-0.103812505903)); +#81113 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.130959159195E-002) + ); +#81114 = CARTESIAN_POINT('',(-8.881784197001E-016,-5.880667728135E-002) + ); +#81115 = CARTESIAN_POINT('',(0.E+000,-4.380473440761E-002)); +#81116 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#81117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81118 = ORIENTED_EDGE('',*,*,#81119,.F.); +#81119 = EDGE_CURVE('',#80980,#81075,#81120,.T.); +#81120 = SURFACE_CURVE('',#81121,(#81125,#81132),.PCURVE_S1.); +#81121 = LINE('',#81122,#81123); +#81122 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#81123 = VECTOR('',#81124,1.); +#81124 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#81125 = PCURVE('',#80990,#81126); +#81126 = DEFINITIONAL_REPRESENTATION('',(#81127),#81131); +#81127 = LINE('',#81128,#81129); +#81128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81129 = VECTOR('',#81130,1.); +#81130 = DIRECTION('',(4.317110322781E-017,1.)); +#81131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81132 = PCURVE('',#81133,#81138); +#81133 = PLANE('',#81134); +#81134 = AXIS2_PLACEMENT_3D('',#81135,#81136,#81137); +#81135 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#81136 = DIRECTION('',(0.965925826289,1.61116750665E-016,0.258819045103) + ); +#81137 = DIRECTION('',(0.258819045103,-9.069926331849E-033, -0.965925826289)); -#78746 = DEFINITIONAL_REPRESENTATION('',(#78747),#78751); -#78747 = LINE('',#78748,#78749); -#78748 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78749 = VECTOR('',#78750,1.); -#78750 = DIRECTION('',(-4.317110322781E-017,1.)); -#78751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78752 = ADVANCED_FACE('',(#78753),#77893,.T.); -#78753 = FACE_BOUND('',#78754,.T.); -#78754 = EDGE_LOOP('',(#78755,#78800,#78820,#78863,#78864,#78890,#78891, - #78917)); -#78755 = ORIENTED_EDGE('',*,*,#78756,.T.); -#78756 = EDGE_CURVE('',#77833,#78757,#78759,.T.); -#78757 = VERTEX_POINT('',#78758); -#78758 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#81138 = DEFINITIONAL_REPRESENTATION('',(#81139),#81143); +#81139 = LINE('',#81140,#81141); +#81140 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81141 = VECTOR('',#81142,1.); +#81142 = DIRECTION('',(-4.317110322781E-017,1.)); +#81143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81144 = ADVANCED_FACE('',(#81145),#80285,.T.); +#81145 = FACE_BOUND('',#81146,.T.); +#81146 = EDGE_LOOP('',(#81147,#81192,#81212,#81255,#81256,#81282,#81283, + #81309)); +#81147 = ORIENTED_EDGE('',*,*,#81148,.T.); +#81148 = EDGE_CURVE('',#80225,#81149,#81151,.T.); +#81149 = VERTEX_POINT('',#81150); +#81150 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#78759 = SURFACE_CURVE('',#78760,(#78764,#78771),.PCURVE_S1.); -#78760 = LINE('',#78761,#78762); -#78761 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, +#81151 = SURFACE_CURVE('',#81152,(#81156,#81163),.PCURVE_S1.); +#81152 = LINE('',#81153,#81154); +#81153 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, 0.633948125296)); -#78762 = VECTOR('',#78763,1.); -#78763 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#78764 = PCURVE('',#77893,#78765); -#78765 = DEFINITIONAL_REPRESENTATION('',(#78766),#78770); -#78766 = LINE('',#78767,#78768); -#78767 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#78768 = VECTOR('',#78769,1.); -#78769 = DIRECTION('',(0.968100345886,0.250562807086)); -#78770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78771 = PCURVE('',#76020,#78772); -#78772 = DEFINITIONAL_REPRESENTATION('',(#78773),#78799); -#78773 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78774,#78775,#78776,#78777, - #78778,#78779,#78780,#78781,#78782,#78783,#78784,#78785,#78786, - #78787,#78788,#78789,#78790,#78791,#78792,#78793,#78794,#78795, - #78796,#78797,#78798),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81154 = VECTOR('',#81155,1.); +#81155 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#81156 = PCURVE('',#80285,#81157); +#81157 = DEFINITIONAL_REPRESENTATION('',(#81158),#81162); +#81158 = LINE('',#81159,#81160); +#81159 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#81160 = VECTOR('',#81161,1.); +#81161 = DIRECTION('',(0.968100345886,0.250562807086)); +#81162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81163 = PCURVE('',#78412,#81164); +#81164 = DEFINITIONAL_REPRESENTATION('',(#81165),#81191); +#81165 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81166,#81167,#81168,#81169, + #81170,#81171,#81172,#81173,#81174,#81175,#81176,#81177,#81178, + #81179,#81180,#81181,#81182,#81183,#81184,#81185,#81186,#81187, + #81188,#81189,#81190),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.630376297074E-002,5.880667728135E-002, 8.130959159195E-002,0.103812505903,0.126315420213,0.148818334524, 0.171321248834,0.193824163145,0.216327077456,0.238829991766, @@ -97580,84 +100569,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.351344563319,0.37384747763,0.39635039194,0.418853306251, 0.441356220562,0.463859134872,0.486362049183,0.508864963493, 0.531367877804),.QUASI_UNIFORM_KNOTS.); -#78774 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#78775 = CARTESIAN_POINT('',(4.64535148218,0.281926914804)); -#78776 = CARTESIAN_POINT('',(4.64535148218,0.26692497193)); -#78777 = CARTESIAN_POINT('',(4.64535148218,0.244422057619)); -#78778 = CARTESIAN_POINT('',(4.64535148218,0.221919143309)); -#78779 = CARTESIAN_POINT('',(4.64535148218,0.199416228998)); -#78780 = CARTESIAN_POINT('',(4.64535148218,0.176913314688)); -#78781 = CARTESIAN_POINT('',(4.64535148218,0.154410400377)); -#78782 = CARTESIAN_POINT('',(4.64535148218,0.131907486066)); -#78783 = CARTESIAN_POINT('',(4.64535148218,0.109404571756)); -#78784 = CARTESIAN_POINT('',(4.64535148218,8.690165744525E-002)); -#78785 = CARTESIAN_POINT('',(4.64535148218,6.439874313465E-002)); -#78786 = CARTESIAN_POINT('',(4.64535148218,4.189582882404E-002)); -#78787 = CARTESIAN_POINT('',(4.64535148218,1.939291451343E-002)); -#78788 = CARTESIAN_POINT('',(4.64535148218,-3.109999797174E-003)); -#78789 = CARTESIAN_POINT('',(4.64535148218,-2.561291410778E-002)); -#78790 = CARTESIAN_POINT('',(4.64535148218,-4.811582841839E-002)); -#78791 = CARTESIAN_POINT('',(4.64535148218,-7.061874272899E-002)); -#78792 = CARTESIAN_POINT('',(4.64535148218,-9.31216570396E-002)); -#78793 = CARTESIAN_POINT('',(4.64535148218,-0.11562457135)); -#78794 = CARTESIAN_POINT('',(4.64535148218,-0.138127485661)); -#78795 = CARTESIAN_POINT('',(4.64535148218,-0.160630399971)); -#78796 = CARTESIAN_POINT('',(4.64535148218,-0.183133314282)); -#78797 = CARTESIAN_POINT('',(4.64535148218,-0.198135257156)); -#78798 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); -#78799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78800 = ORIENTED_EDGE('',*,*,#78801,.T.); -#78801 = EDGE_CURVE('',#78757,#75707,#78802,.T.); -#78802 = SURFACE_CURVE('',#78803,(#78807,#78814),.PCURVE_S1.); -#78803 = LINE('',#78804,#78805); -#78804 = CARTESIAN_POINT('',(1.181136529841,-0.5259553457,0.137059047745 +#81166 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#81167 = CARTESIAN_POINT('',(4.64535148218,0.281926914804)); +#81168 = CARTESIAN_POINT('',(4.64535148218,0.26692497193)); +#81169 = CARTESIAN_POINT('',(4.64535148218,0.244422057619)); +#81170 = CARTESIAN_POINT('',(4.64535148218,0.221919143309)); +#81171 = CARTESIAN_POINT('',(4.64535148218,0.199416228998)); +#81172 = CARTESIAN_POINT('',(4.64535148218,0.176913314688)); +#81173 = CARTESIAN_POINT('',(4.64535148218,0.154410400377)); +#81174 = CARTESIAN_POINT('',(4.64535148218,0.131907486066)); +#81175 = CARTESIAN_POINT('',(4.64535148218,0.109404571756)); +#81176 = CARTESIAN_POINT('',(4.64535148218,8.690165744525E-002)); +#81177 = CARTESIAN_POINT('',(4.64535148218,6.439874313465E-002)); +#81178 = CARTESIAN_POINT('',(4.64535148218,4.189582882404E-002)); +#81179 = CARTESIAN_POINT('',(4.64535148218,1.939291451343E-002)); +#81180 = CARTESIAN_POINT('',(4.64535148218,-3.109999797174E-003)); +#81181 = CARTESIAN_POINT('',(4.64535148218,-2.561291410778E-002)); +#81182 = CARTESIAN_POINT('',(4.64535148218,-4.811582841839E-002)); +#81183 = CARTESIAN_POINT('',(4.64535148218,-7.061874272899E-002)); +#81184 = CARTESIAN_POINT('',(4.64535148218,-9.31216570396E-002)); +#81185 = CARTESIAN_POINT('',(4.64535148218,-0.11562457135)); +#81186 = CARTESIAN_POINT('',(4.64535148218,-0.138127485661)); +#81187 = CARTESIAN_POINT('',(4.64535148218,-0.160630399971)); +#81188 = CARTESIAN_POINT('',(4.64535148218,-0.183133314282)); +#81189 = CARTESIAN_POINT('',(4.64535148218,-0.198135257156)); +#81190 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); +#81191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81192 = ORIENTED_EDGE('',*,*,#81193,.T.); +#81193 = EDGE_CURVE('',#81149,#78099,#81194,.T.); +#81194 = SURFACE_CURVE('',#81195,(#81199,#81206),.PCURVE_S1.); +#81195 = LINE('',#81196,#81197); +#81196 = CARTESIAN_POINT('',(1.181136529841,-0.5259553457,0.137059047745 )); -#78805 = VECTOR('',#78806,1.); -#78806 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78807 = PCURVE('',#77893,#78808); -#78808 = DEFINITIONAL_REPRESENTATION('',(#78809),#78813); -#78809 = LINE('',#78810,#78811); -#78810 = CARTESIAN_POINT('',(0.479271740806,2.641136529841)); -#78811 = VECTOR('',#78812,1.); -#78812 = DIRECTION('',(0.E+000,1.)); -#78813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78814 = PCURVE('',#75816,#78815); -#78815 = DEFINITIONAL_REPRESENTATION('',(#78816),#78819); -#78816 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78817,#78818),.UNSPECIFIED., +#81197 = VECTOR('',#81198,1.); +#81198 = DIRECTION('',(1.,0.E+000,0.E+000)); +#81199 = PCURVE('',#80285,#81200); +#81200 = DEFINITIONAL_REPRESENTATION('',(#81201),#81205); +#81201 = LINE('',#81202,#81203); +#81202 = CARTESIAN_POINT('',(0.479271740806,2.641136529841)); +#81203 = VECTOR('',#81204,1.); +#81204 = DIRECTION('',(0.E+000,1.)); +#81205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81206 = PCURVE('',#78208,#81207); +#81207 = DEFINITIONAL_REPRESENTATION('',(#81208),#81211); +#81208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81209,#81210),.UNSPECIFIED., .F.,.F.,(2,2),(-2.372203001598,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#78817 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#78818 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); -#78819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81209 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#81210 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); +#81211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78820 = ORIENTED_EDGE('',*,*,#78821,.T.); -#78821 = EDGE_CURVE('',#75707,#77784,#78822,.T.); -#78822 = SURFACE_CURVE('',#78823,(#78827,#78834),.PCURVE_S1.); -#78823 = LINE('',#78824,#78825); -#78824 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, +#81212 = ORIENTED_EDGE('',*,*,#81213,.T.); +#81213 = EDGE_CURVE('',#78099,#80176,#81214,.T.); +#81214 = SURFACE_CURVE('',#81215,(#81219,#81226),.PCURVE_S1.); +#81215 = LINE('',#81216,#81217); +#81216 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, -5.022121888847E-002)); -#78825 = VECTOR('',#78826,1.); -#78826 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#78827 = PCURVE('',#77893,#78828); -#78828 = DEFINITIONAL_REPRESENTATION('',(#78829),#78833); -#78829 = LINE('',#78830,#78831); -#78830 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); -#78831 = VECTOR('',#78832,1.); -#78832 = DIRECTION('',(-0.968100345886,0.250562807086)); -#78833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78834 = PCURVE('',#75745,#78835); -#78835 = DEFINITIONAL_REPRESENTATION('',(#78836),#78862); -#78836 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78837,#78838,#78839,#78840, - #78841,#78842,#78843,#78844,#78845,#78846,#78847,#78848,#78849, - #78850,#78851,#78852,#78853,#78854,#78855,#78856,#78857,#78858, - #78859,#78860,#78861),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81217 = VECTOR('',#81218,1.); +#81218 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#81219 = PCURVE('',#80285,#81220); +#81220 = DEFINITIONAL_REPRESENTATION('',(#81221),#81225); +#81221 = LINE('',#81222,#81223); +#81222 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); +#81223 = VECTOR('',#81224,1.); +#81224 = DIRECTION('',(-0.968100345886,0.250562807086)); +#81225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81226 = PCURVE('',#78137,#81227); +#81227 = DEFINITIONAL_REPRESENTATION('',(#81228),#81254); +#81228 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81229,#81230,#81231,#81232, + #81233,#81234,#81235,#81236,#81237,#81238,#81239,#81240,#81241, + #81242,#81243,#81244,#81245,#81246,#81247,#81248,#81249,#81250, + #81251,#81252,#81253),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.200275518886,0.222778433197, 0.245281347507,0.267784261818,0.290287176129,0.312790090439, 0.33529300475,0.35779591906,0.380298833371,0.402801747682, @@ -97665,162 +100654,162 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.515316319235,0.537819233545,0.560322147856,0.582825062167, 0.605327976477,0.627830890788,0.650333805098,0.672836719409, 0.69533963372),.QUASI_UNIFORM_KNOTS.); -#78837 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); -#78838 = CARTESIAN_POINT('',(4.77942647859,0.207776490323)); -#78839 = CARTESIAN_POINT('',(4.77942647859,0.222778433197)); -#78840 = CARTESIAN_POINT('',(4.77942647859,0.245281347507)); -#78841 = CARTESIAN_POINT('',(4.77942647859,0.267784261818)); -#78842 = CARTESIAN_POINT('',(4.77942647859,0.290287176129)); -#78843 = CARTESIAN_POINT('',(4.77942647859,0.312790090439)); -#78844 = CARTESIAN_POINT('',(4.77942647859,0.33529300475)); -#78845 = CARTESIAN_POINT('',(4.77942647859,0.35779591906)); -#78846 = CARTESIAN_POINT('',(4.77942647859,0.380298833371)); -#78847 = CARTESIAN_POINT('',(4.77942647859,0.402801747682)); -#78848 = CARTESIAN_POINT('',(4.77942647859,0.425304661992)); -#78849 = CARTESIAN_POINT('',(4.77942647859,0.447807576303)); -#78850 = CARTESIAN_POINT('',(4.77942647859,0.470310490614)); -#78851 = CARTESIAN_POINT('',(4.77942647859,0.492813404924)); -#78852 = CARTESIAN_POINT('',(4.77942647859,0.515316319235)); -#78853 = CARTESIAN_POINT('',(4.77942647859,0.537819233545)); -#78854 = CARTESIAN_POINT('',(4.77942647859,0.560322147856)); -#78855 = CARTESIAN_POINT('',(4.77942647859,0.582825062167)); -#78856 = CARTESIAN_POINT('',(4.77942647859,0.605327976477)); -#78857 = CARTESIAN_POINT('',(4.77942647859,0.627830890788)); -#78858 = CARTESIAN_POINT('',(4.77942647859,0.650333805098)); -#78859 = CARTESIAN_POINT('',(4.77942647859,0.672836719409)); -#78860 = CARTESIAN_POINT('',(4.77942647859,0.687838662283)); -#78861 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); -#78862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78863 = ORIENTED_EDGE('',*,*,#78096,.F.); -#78864 = ORIENTED_EDGE('',*,*,#78865,.F.); -#78865 = EDGE_CURVE('',#77990,#78069,#78866,.T.); -#78866 = SURFACE_CURVE('',#78867,(#78871,#78878),.PCURVE_S1.); -#78867 = LINE('',#78868,#78869); -#78868 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#78869 = VECTOR('',#78870,1.); -#78870 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78871 = PCURVE('',#77893,#78872); -#78872 = DEFINITIONAL_REPRESENTATION('',(#78873),#78877); -#78873 = LINE('',#78874,#78875); -#78874 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#78875 = VECTOR('',#78876,1.); -#78876 = DIRECTION('',(0.E+000,1.)); -#78877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78878 = PCURVE('',#78879,#78884); -#78879 = PLANE('',#78880); -#78880 = AXIS2_PLACEMENT_3D('',#78881,#78882,#78883); -#78881 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#78882 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78883 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78884 = DEFINITIONAL_REPRESENTATION('',(#78885),#78889); -#78885 = LINE('',#78886,#78887); -#78886 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); -#78887 = VECTOR('',#78888,1.); -#78888 = DIRECTION('',(-1.,0.E+000)); -#78889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78890 = ORIENTED_EDGE('',*,*,#77989,.F.); -#78891 = ORIENTED_EDGE('',*,*,#78892,.F.); -#78892 = EDGE_CURVE('',#77878,#77962,#78893,.T.); -#78893 = SURFACE_CURVE('',#78894,(#78898,#78905),.PCURVE_S1.); -#78894 = LINE('',#78895,#78896); -#78895 = CARTESIAN_POINT('',(-3.36,-0.65,0.6)); -#78896 = VECTOR('',#78897,1.); -#78897 = DIRECTION('',(1.,0.E+000,0.E+000)); -#78898 = PCURVE('',#77893,#78899); -#78899 = DEFINITIONAL_REPRESENTATION('',(#78900),#78904); -#78900 = LINE('',#78901,#78902); -#78901 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#78902 = VECTOR('',#78903,1.); -#78903 = DIRECTION('',(0.E+000,1.)); -#78904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78905 = PCURVE('',#78906,#78911); -#78906 = PLANE('',#78907); -#78907 = AXIS2_PLACEMENT_3D('',#78908,#78909,#78910); -#78908 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#78909 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#78910 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#78911 = DEFINITIONAL_REPRESENTATION('',(#78912),#78916); -#78912 = LINE('',#78913,#78914); -#78913 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); -#78914 = VECTOR('',#78915,1.); -#78915 = DIRECTION('',(-1.,0.E+000)); -#78916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78917 = ORIENTED_EDGE('',*,*,#77877,.F.); -#78918 = ADVANCED_FACE('',(#78919),#78933,.T.); -#78919 = FACE_BOUND('',#78920,.T.); -#78920 = EDGE_LOOP('',(#78921,#78950,#78993,#79038)); -#78921 = ORIENTED_EDGE('',*,*,#78922,.T.); -#78922 = EDGE_CURVE('',#78923,#78925,#78927,.T.); -#78923 = VERTEX_POINT('',#78924); -#78924 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); -#78925 = VERTEX_POINT('',#78926); -#78926 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 +#81229 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); +#81230 = CARTESIAN_POINT('',(4.77942647859,0.207776490323)); +#81231 = CARTESIAN_POINT('',(4.77942647859,0.222778433197)); +#81232 = CARTESIAN_POINT('',(4.77942647859,0.245281347507)); +#81233 = CARTESIAN_POINT('',(4.77942647859,0.267784261818)); +#81234 = CARTESIAN_POINT('',(4.77942647859,0.290287176129)); +#81235 = CARTESIAN_POINT('',(4.77942647859,0.312790090439)); +#81236 = CARTESIAN_POINT('',(4.77942647859,0.33529300475)); +#81237 = CARTESIAN_POINT('',(4.77942647859,0.35779591906)); +#81238 = CARTESIAN_POINT('',(4.77942647859,0.380298833371)); +#81239 = CARTESIAN_POINT('',(4.77942647859,0.402801747682)); +#81240 = CARTESIAN_POINT('',(4.77942647859,0.425304661992)); +#81241 = CARTESIAN_POINT('',(4.77942647859,0.447807576303)); +#81242 = CARTESIAN_POINT('',(4.77942647859,0.470310490614)); +#81243 = CARTESIAN_POINT('',(4.77942647859,0.492813404924)); +#81244 = CARTESIAN_POINT('',(4.77942647859,0.515316319235)); +#81245 = CARTESIAN_POINT('',(4.77942647859,0.537819233545)); +#81246 = CARTESIAN_POINT('',(4.77942647859,0.560322147856)); +#81247 = CARTESIAN_POINT('',(4.77942647859,0.582825062167)); +#81248 = CARTESIAN_POINT('',(4.77942647859,0.605327976477)); +#81249 = CARTESIAN_POINT('',(4.77942647859,0.627830890788)); +#81250 = CARTESIAN_POINT('',(4.77942647859,0.650333805098)); +#81251 = CARTESIAN_POINT('',(4.77942647859,0.672836719409)); +#81252 = CARTESIAN_POINT('',(4.77942647859,0.687838662283)); +#81253 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); +#81254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81255 = ORIENTED_EDGE('',*,*,#80488,.F.); +#81256 = ORIENTED_EDGE('',*,*,#81257,.F.); +#81257 = EDGE_CURVE('',#80382,#80461,#81258,.T.); +#81258 = SURFACE_CURVE('',#81259,(#81263,#81270),.PCURVE_S1.); +#81259 = LINE('',#81260,#81261); +#81260 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#81261 = VECTOR('',#81262,1.); +#81262 = DIRECTION('',(1.,0.E+000,0.E+000)); +#81263 = PCURVE('',#80285,#81264); +#81264 = DEFINITIONAL_REPRESENTATION('',(#81265),#81269); +#81265 = LINE('',#81266,#81267); +#81266 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81267 = VECTOR('',#81268,1.); +#81268 = DIRECTION('',(0.E+000,1.)); +#81269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81270 = PCURVE('',#81271,#81276); +#81271 = PLANE('',#81272); +#81272 = AXIS2_PLACEMENT_3D('',#81273,#81274,#81275); +#81273 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#81274 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#81275 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81276 = DEFINITIONAL_REPRESENTATION('',(#81277),#81281); +#81277 = LINE('',#81278,#81279); +#81278 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); +#81279 = VECTOR('',#81280,1.); +#81280 = DIRECTION('',(-1.,0.E+000)); +#81281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81282 = ORIENTED_EDGE('',*,*,#80381,.F.); +#81283 = ORIENTED_EDGE('',*,*,#81284,.F.); +#81284 = EDGE_CURVE('',#80270,#80354,#81285,.T.); +#81285 = SURFACE_CURVE('',#81286,(#81290,#81297),.PCURVE_S1.); +#81286 = LINE('',#81287,#81288); +#81287 = CARTESIAN_POINT('',(-3.36,-0.65,0.6)); +#81288 = VECTOR('',#81289,1.); +#81289 = DIRECTION('',(1.,0.E+000,0.E+000)); +#81290 = PCURVE('',#80285,#81291); +#81291 = DEFINITIONAL_REPRESENTATION('',(#81292),#81296); +#81292 = LINE('',#81293,#81294); +#81293 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#81294 = VECTOR('',#81295,1.); +#81295 = DIRECTION('',(0.E+000,1.)); +#81296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81297 = PCURVE('',#81298,#81303); +#81298 = PLANE('',#81299); +#81299 = AXIS2_PLACEMENT_3D('',#81300,#81301,#81302); +#81300 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#81301 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#81302 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81303 = DEFINITIONAL_REPRESENTATION('',(#81304),#81308); +#81304 = LINE('',#81305,#81306); +#81305 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); +#81306 = VECTOR('',#81307,1.); +#81307 = DIRECTION('',(-1.,0.E+000)); +#81308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81309 = ORIENTED_EDGE('',*,*,#80269,.F.); +#81310 = ADVANCED_FACE('',(#81311),#81325,.T.); +#81311 = FACE_BOUND('',#81312,.T.); +#81312 = EDGE_LOOP('',(#81313,#81342,#81385,#81430)); +#81313 = ORIENTED_EDGE('',*,*,#81314,.T.); +#81314 = EDGE_CURVE('',#81315,#81317,#81319,.T.); +#81315 = VERTEX_POINT('',#81316); +#81316 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); +#81317 = VERTEX_POINT('',#81318); +#81318 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 )); -#78927 = SURFACE_CURVE('',#78928,(#78932,#78944),.PCURVE_S1.); -#78928 = LINE('',#78929,#78930); -#78929 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, +#81319 = SURFACE_CURVE('',#81320,(#81324,#81336),.PCURVE_S1.); +#81320 = LINE('',#81321,#81322); +#81321 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, 0.633948125296)); -#78930 = VECTOR('',#78931,1.); -#78931 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); -#78932 = PCURVE('',#78933,#78938); -#78933 = PLANE('',#78934); -#78934 = AXIS2_PLACEMENT_3D('',#78935,#78936,#78937); -#78935 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#78936 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, +#81322 = VECTOR('',#81323,1.); +#81323 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); +#81324 = PCURVE('',#81325,#81330); +#81325 = PLANE('',#81326); +#81326 = AXIS2_PLACEMENT_3D('',#81327,#81328,#81329); +#81327 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#81328 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, -0.258819045103)); -#78937 = DIRECTION('',(-0.258819045103,9.069926331849E-033, +#81329 = DIRECTION('',(-0.258819045103,9.069926331849E-033, 0.965925826289)); -#78938 = DEFINITIONAL_REPRESENTATION('',(#78939),#78943); -#78939 = LINE('',#78940,#78941); -#78940 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#78941 = VECTOR('',#78942,1.); -#78942 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#78943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81330 = DEFINITIONAL_REPRESENTATION('',(#81331),#81335); +#81331 = LINE('',#81332,#81333); +#81332 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#81333 = VECTOR('',#81334,1.); +#81334 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#81335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78944 = PCURVE('',#76570,#78945); -#78945 = DEFINITIONAL_REPRESENTATION('',(#78946),#78949); -#78946 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#78947,#78948),.UNSPECIFIED., +#81336 = PCURVE('',#78962,#81337); +#81337 = DEFINITIONAL_REPRESENTATION('',(#81338),#81341); +#81338 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81339,#81340),.UNSPECIFIED., .F.,.F.,(2,2),(3.630376297074E-002,0.531367877804), .PIECEWISE_BEZIER_KNOTS.); -#78947 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#78948 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#78949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81339 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#81340 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#81341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#78950 = ORIENTED_EDGE('',*,*,#78951,.T.); -#78951 = EDGE_CURVE('',#78925,#75982,#78952,.T.); -#78952 = SURFACE_CURVE('',#78953,(#78957,#78964),.PCURVE_S1.); -#78953 = LINE('',#78954,#78955); -#78954 = CARTESIAN_POINT('',(-1.3359553457,-0.371136529841, +#81342 = ORIENTED_EDGE('',*,*,#81343,.T.); +#81343 = EDGE_CURVE('',#81317,#78374,#81344,.T.); +#81344 = SURFACE_CURVE('',#81345,(#81349,#81356),.PCURVE_S1.); +#81345 = LINE('',#81346,#81347); +#81346 = CARTESIAN_POINT('',(-1.3359553457,-0.371136529841, 0.137059047745)); -#78955 = VECTOR('',#78956,1.); -#78956 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); -#78957 = PCURVE('',#78933,#78958); -#78958 = DEFINITIONAL_REPRESENTATION('',(#78959),#78963); -#78959 = LINE('',#78960,#78961); -#78960 = CARTESIAN_POINT('',(-0.479271740806,-1.021136529841)); -#78961 = VECTOR('',#78962,1.); -#78962 = DIRECTION('',(-4.317110322781E-017,-1.)); -#78963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78964 = PCURVE('',#76091,#78965); -#78965 = DEFINITIONAL_REPRESENTATION('',(#78966),#78992); -#78966 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#78967,#78968,#78969,#78970, - #78971,#78972,#78973,#78974,#78975,#78976,#78977,#78978,#78979, - #78980,#78981,#78982,#78983,#78984,#78985,#78986,#78987,#78988, - #78989,#78990,#78991),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81347 = VECTOR('',#81348,1.); +#81348 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); +#81349 = PCURVE('',#81325,#81350); +#81350 = DEFINITIONAL_REPRESENTATION('',(#81351),#81355); +#81351 = LINE('',#81352,#81353); +#81352 = CARTESIAN_POINT('',(-0.479271740806,-1.021136529841)); +#81353 = VECTOR('',#81354,1.); +#81354 = DIRECTION('',(-4.317110322781E-017,-1.)); +#81355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81356 = PCURVE('',#78483,#81357); +#81357 = DEFINITIONAL_REPRESENTATION('',(#81358),#81384); +#81358 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81359,#81360,#81361,#81362, + #81363,#81364,#81365,#81366,#81367,#81368,#81369,#81370,#81371, + #81372,#81373,#81374,#81375,#81376,#81377,#81378,#81379,#81380, + #81381,#81382,#81383),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598,-0.717560595074, -0.682918188551,-0.648275782028,-0.613633375504,-0.578990968981, -0.544348562458,-0.509706155934,-0.475063749411,-0.440421342888, @@ -97828,59 +100817,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.267209310271,-0.232566903748,-0.197924497224,-0.163282090701, -0.128639684178,-9.399727765447E-002,-5.935487113115E-002, -2.471246460782E-002,9.929941915506E-003),.UNSPECIFIED.); -#78967 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#78968 = CARTESIAN_POINT('',(6.02138591938,-0.280480997085)); -#78969 = CARTESIAN_POINT('',(6.02138591938,-0.303575934767)); -#78970 = CARTESIAN_POINT('',(6.02138591938,-0.33821834129)); -#78971 = CARTESIAN_POINT('',(6.02138591938,-0.372860747813)); -#78972 = CARTESIAN_POINT('',(6.02138591938,-0.407503154337)); -#78973 = CARTESIAN_POINT('',(6.02138591938,-0.44214556086)); -#78974 = CARTESIAN_POINT('',(6.02138591938,-0.476787967383)); -#78975 = CARTESIAN_POINT('',(6.02138591938,-0.511430373907)); -#78976 = CARTESIAN_POINT('',(6.02138591938,-0.54607278043)); -#78977 = CARTESIAN_POINT('',(6.02138591938,-0.580715186953)); -#78978 = CARTESIAN_POINT('',(6.02138591938,-0.615357593477)); -#78979 = CARTESIAN_POINT('',(6.02138591938,-0.65)); -#78980 = CARTESIAN_POINT('',(6.02138591938,-0.684642406523)); -#78981 = CARTESIAN_POINT('',(6.02138591938,-0.719284813047)); -#78982 = CARTESIAN_POINT('',(6.02138591938,-0.75392721957)); -#78983 = CARTESIAN_POINT('',(6.02138591938,-0.788569626093)); -#78984 = CARTESIAN_POINT('',(6.02138591938,-0.823212032617)); -#78985 = CARTESIAN_POINT('',(6.02138591938,-0.85785443914)); -#78986 = CARTESIAN_POINT('',(6.02138591938,-0.892496845663)); -#78987 = CARTESIAN_POINT('',(6.02138591938,-0.927139252187)); -#78988 = CARTESIAN_POINT('',(6.02138591938,-0.96178165871)); -#78989 = CARTESIAN_POINT('',(6.02138591938,-0.996424065233)); -#78990 = CARTESIAN_POINT('',(6.02138591938,-1.019519002915)); -#78991 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); -#78992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#78993 = ORIENTED_EDGE('',*,*,#78994,.T.); -#78994 = EDGE_CURVE('',#75982,#78995,#78997,.T.); -#78995 = VERTEX_POINT('',#78996); -#78996 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); -#78997 = SURFACE_CURVE('',#78998,(#79002,#79009),.PCURVE_S1.); -#78998 = LINE('',#78999,#79000); -#78999 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, +#81359 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#81360 = CARTESIAN_POINT('',(6.02138591938,-0.280480997085)); +#81361 = CARTESIAN_POINT('',(6.02138591938,-0.303575934767)); +#81362 = CARTESIAN_POINT('',(6.02138591938,-0.33821834129)); +#81363 = CARTESIAN_POINT('',(6.02138591938,-0.372860747813)); +#81364 = CARTESIAN_POINT('',(6.02138591938,-0.407503154337)); +#81365 = CARTESIAN_POINT('',(6.02138591938,-0.44214556086)); +#81366 = CARTESIAN_POINT('',(6.02138591938,-0.476787967383)); +#81367 = CARTESIAN_POINT('',(6.02138591938,-0.511430373907)); +#81368 = CARTESIAN_POINT('',(6.02138591938,-0.54607278043)); +#81369 = CARTESIAN_POINT('',(6.02138591938,-0.580715186953)); +#81370 = CARTESIAN_POINT('',(6.02138591938,-0.615357593477)); +#81371 = CARTESIAN_POINT('',(6.02138591938,-0.65)); +#81372 = CARTESIAN_POINT('',(6.02138591938,-0.684642406523)); +#81373 = CARTESIAN_POINT('',(6.02138591938,-0.719284813047)); +#81374 = CARTESIAN_POINT('',(6.02138591938,-0.75392721957)); +#81375 = CARTESIAN_POINT('',(6.02138591938,-0.788569626093)); +#81376 = CARTESIAN_POINT('',(6.02138591938,-0.823212032617)); +#81377 = CARTESIAN_POINT('',(6.02138591938,-0.85785443914)); +#81378 = CARTESIAN_POINT('',(6.02138591938,-0.892496845663)); +#81379 = CARTESIAN_POINT('',(6.02138591938,-0.927139252187)); +#81380 = CARTESIAN_POINT('',(6.02138591938,-0.96178165871)); +#81381 = CARTESIAN_POINT('',(6.02138591938,-0.996424065233)); +#81382 = CARTESIAN_POINT('',(6.02138591938,-1.019519002915)); +#81383 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); +#81384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81385 = ORIENTED_EDGE('',*,*,#81386,.T.); +#81386 = EDGE_CURVE('',#78374,#81387,#81389,.T.); +#81387 = VERTEX_POINT('',#81388); +#81388 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); +#81389 = SURFACE_CURVE('',#81390,(#81394,#81401),.PCURVE_S1.); +#81390 = LINE('',#81391,#81392); +#81391 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, 0.329352184392)); -#79000 = VECTOR('',#79001,1.); -#79001 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); -#79002 = PCURVE('',#78933,#79003); -#79003 = DEFINITIONAL_REPRESENTATION('',(#79004),#79008); -#79004 = LINE('',#79005,#79006); -#79005 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); -#79006 = VECTOR('',#79007,1.); -#79007 = DIRECTION('',(0.968100345886,-0.250562807086)); -#79008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79009 = PCURVE('',#76020,#79010); -#79010 = DEFINITIONAL_REPRESENTATION('',(#79011),#79037); -#79011 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79012,#79013,#79014,#79015, - #79016,#79017,#79018,#79019,#79020,#79021,#79022,#79023,#79024, - #79025,#79026,#79027,#79028,#79029,#79030,#79031,#79032,#79033, - #79034,#79035,#79036),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81392 = VECTOR('',#81393,1.); +#81393 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); +#81394 = PCURVE('',#81325,#81395); +#81395 = DEFINITIONAL_REPRESENTATION('',(#81396),#81400); +#81396 = LINE('',#81397,#81398); +#81397 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); +#81398 = VECTOR('',#81399,1.); +#81399 = DIRECTION('',(0.968100345886,-0.250562807086)); +#81400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81401 = PCURVE('',#78412,#81402); +#81402 = DEFINITIONAL_REPRESENTATION('',(#81403),#81429); +#81403 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81404,#81405,#81406,#81407, + #81408,#81409,#81410,#81411,#81412,#81413,#81414,#81415,#81416, + #81417,#81418,#81419,#81420,#81421,#81422,#81423,#81424,#81425, + #81426,#81427,#81428),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.205636228593,-0.183133314282, -0.160630399971,-0.138127485661,-0.11562457135,-9.31216570396E-002, -7.061874272899E-002,-4.811582841839E-002,-2.561291410778E-002, @@ -97889,97 +100878,97 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.131907486066,0.154410400377,0.176913314688,0.199416228998, 0.221919143309,0.244422057619,0.26692497193,0.289427886241), .UNSPECIFIED.); -#79012 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); -#79013 = CARTESIAN_POINT('',(3.14159265359,-0.198135257156)); -#79014 = CARTESIAN_POINT('',(3.14159265359,-0.183133314282)); -#79015 = CARTESIAN_POINT('',(3.14159265359,-0.160630399971)); -#79016 = CARTESIAN_POINT('',(3.14159265359,-0.138127485661)); -#79017 = CARTESIAN_POINT('',(3.14159265359,-0.11562457135)); -#79018 = CARTESIAN_POINT('',(3.14159265359,-9.31216570396E-002)); -#79019 = CARTESIAN_POINT('',(3.14159265359,-7.061874272899E-002)); -#79020 = CARTESIAN_POINT('',(3.14159265359,-4.811582841839E-002)); -#79021 = CARTESIAN_POINT('',(3.14159265359,-2.561291410778E-002)); -#79022 = CARTESIAN_POINT('',(3.14159265359,-3.109999797174E-003)); -#79023 = CARTESIAN_POINT('',(3.14159265359,1.939291451343E-002)); -#79024 = CARTESIAN_POINT('',(3.14159265359,4.189582882404E-002)); -#79025 = CARTESIAN_POINT('',(3.14159265359,6.439874313465E-002)); -#79026 = CARTESIAN_POINT('',(3.14159265359,8.690165744525E-002)); -#79027 = CARTESIAN_POINT('',(3.14159265359,0.109404571756)); -#79028 = CARTESIAN_POINT('',(3.14159265359,0.131907486066)); -#79029 = CARTESIAN_POINT('',(3.14159265359,0.154410400377)); -#79030 = CARTESIAN_POINT('',(3.14159265359,0.176913314688)); -#79031 = CARTESIAN_POINT('',(3.14159265359,0.199416228998)); -#79032 = CARTESIAN_POINT('',(3.14159265359,0.221919143309)); -#79033 = CARTESIAN_POINT('',(3.14159265359,0.244422057619)); -#79034 = CARTESIAN_POINT('',(3.14159265359,0.26692497193)); -#79035 = CARTESIAN_POINT('',(3.14159265359,0.281926914804)); -#79036 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#79037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79038 = ORIENTED_EDGE('',*,*,#79039,.F.); -#79039 = EDGE_CURVE('',#78923,#78995,#79040,.T.); -#79040 = SURFACE_CURVE('',#79041,(#79045,#79052),.PCURVE_S1.); -#79041 = LINE('',#79042,#79043); -#79042 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#79043 = VECTOR('',#79044,1.); -#79044 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#79045 = PCURVE('',#78933,#79046); -#79046 = DEFINITIONAL_REPRESENTATION('',(#79047),#79051); -#79047 = LINE('',#79048,#79049); -#79048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#79049 = VECTOR('',#79050,1.); -#79050 = DIRECTION('',(-4.317110322781E-017,-1.)); -#79051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79052 = PCURVE('',#79053,#79058); -#79053 = PLANE('',#79054); -#79054 = AXIS2_PLACEMENT_3D('',#79055,#79056,#79057); -#79055 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#79056 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, +#81404 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); +#81405 = CARTESIAN_POINT('',(3.14159265359,-0.198135257156)); +#81406 = CARTESIAN_POINT('',(3.14159265359,-0.183133314282)); +#81407 = CARTESIAN_POINT('',(3.14159265359,-0.160630399971)); +#81408 = CARTESIAN_POINT('',(3.14159265359,-0.138127485661)); +#81409 = CARTESIAN_POINT('',(3.14159265359,-0.11562457135)); +#81410 = CARTESIAN_POINT('',(3.14159265359,-9.31216570396E-002)); +#81411 = CARTESIAN_POINT('',(3.14159265359,-7.061874272899E-002)); +#81412 = CARTESIAN_POINT('',(3.14159265359,-4.811582841839E-002)); +#81413 = CARTESIAN_POINT('',(3.14159265359,-2.561291410778E-002)); +#81414 = CARTESIAN_POINT('',(3.14159265359,-3.109999797174E-003)); +#81415 = CARTESIAN_POINT('',(3.14159265359,1.939291451343E-002)); +#81416 = CARTESIAN_POINT('',(3.14159265359,4.189582882404E-002)); +#81417 = CARTESIAN_POINT('',(3.14159265359,6.439874313465E-002)); +#81418 = CARTESIAN_POINT('',(3.14159265359,8.690165744525E-002)); +#81419 = CARTESIAN_POINT('',(3.14159265359,0.109404571756)); +#81420 = CARTESIAN_POINT('',(3.14159265359,0.131907486066)); +#81421 = CARTESIAN_POINT('',(3.14159265359,0.154410400377)); +#81422 = CARTESIAN_POINT('',(3.14159265359,0.176913314688)); +#81423 = CARTESIAN_POINT('',(3.14159265359,0.199416228998)); +#81424 = CARTESIAN_POINT('',(3.14159265359,0.221919143309)); +#81425 = CARTESIAN_POINT('',(3.14159265359,0.244422057619)); +#81426 = CARTESIAN_POINT('',(3.14159265359,0.26692497193)); +#81427 = CARTESIAN_POINT('',(3.14159265359,0.281926914804)); +#81428 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#81429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81430 = ORIENTED_EDGE('',*,*,#81431,.F.); +#81431 = EDGE_CURVE('',#81315,#81387,#81432,.T.); +#81432 = SURFACE_CURVE('',#81433,(#81437,#81444),.PCURVE_S1.); +#81433 = LINE('',#81434,#81435); +#81434 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#81435 = VECTOR('',#81436,1.); +#81436 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#81437 = PCURVE('',#81325,#81438); +#81438 = DEFINITIONAL_REPRESENTATION('',(#81439),#81443); +#81439 = LINE('',#81440,#81441); +#81440 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81441 = VECTOR('',#81442,1.); +#81442 = DIRECTION('',(-4.317110322781E-017,-1.)); +#81443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81444 = PCURVE('',#81445,#81450); +#81445 = PLANE('',#81446); +#81446 = AXIS2_PLACEMENT_3D('',#81447,#81448,#81449); +#81447 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#81448 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, 0.258819045103)); -#79057 = DIRECTION('',(0.258819045103,-9.069926331849E-033, +#81449 = DIRECTION('',(0.258819045103,-9.069926331849E-033, 0.965925826289)); -#79058 = DEFINITIONAL_REPRESENTATION('',(#79059),#79063); -#79059 = LINE('',#79060,#79061); -#79060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#79061 = VECTOR('',#79062,1.); -#79062 = DIRECTION('',(4.317110322781E-017,-1.)); -#79063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79064 = ADVANCED_FACE('',(#79065),#78253,.T.); -#79065 = FACE_BOUND('',#79066,.T.); -#79066 = EDGE_LOOP('',(#79067,#79112,#79132,#79152,#79153,#79179,#79180, - #79206,#79207,#79233)); -#79067 = ORIENTED_EDGE('',*,*,#79068,.T.); -#79068 = EDGE_CURVE('',#78193,#79069,#79071,.T.); -#79069 = VERTEX_POINT('',#79070); -#79070 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) - ); -#79071 = SURFACE_CURVE('',#79072,(#79076,#79083),.PCURVE_S1.); -#79072 = LINE('',#79073,#79074); -#79073 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, +#81450 = DEFINITIONAL_REPRESENTATION('',(#81451),#81455); +#81451 = LINE('',#81452,#81453); +#81452 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81453 = VECTOR('',#81454,1.); +#81454 = DIRECTION('',(4.317110322781E-017,-1.)); +#81455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81456 = ADVANCED_FACE('',(#81457),#80645,.T.); +#81457 = FACE_BOUND('',#81458,.T.); +#81458 = EDGE_LOOP('',(#81459,#81504,#81524,#81544,#81545,#81571,#81572, + #81598,#81599,#81625)); +#81459 = ORIENTED_EDGE('',*,*,#81460,.T.); +#81460 = EDGE_CURVE('',#80585,#81461,#81463,.T.); +#81461 = VERTEX_POINT('',#81462); +#81462 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) + ); +#81463 = SURFACE_CURVE('',#81464,(#81468,#81475),.PCURVE_S1.); +#81464 = LINE('',#81465,#81466); +#81465 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, -5.022121888847E-002)); -#79074 = VECTOR('',#79075,1.); -#79075 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#79076 = PCURVE('',#78253,#79077); -#79077 = DEFINITIONAL_REPRESENTATION('',(#79078),#79082); -#79078 = LINE('',#79079,#79080); -#79079 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); -#79080 = VECTOR('',#79081,1.); -#79081 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#79082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79083 = PCURVE('',#76295,#79084); -#79084 = DEFINITIONAL_REPRESENTATION('',(#79085),#79111); -#79085 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79086,#79087,#79088,#79089, - #79090,#79091,#79092,#79093,#79094,#79095,#79096,#79097,#79098, - #79099,#79100,#79101,#79102,#79103,#79104,#79105,#79106,#79107, - #79108,#79109,#79110),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81466 = VECTOR('',#81467,1.); +#81467 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#81468 = PCURVE('',#80645,#81469); +#81469 = DEFINITIONAL_REPRESENTATION('',(#81470),#81474); +#81470 = LINE('',#81471,#81472); +#81471 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); +#81472 = VECTOR('',#81473,1.); +#81473 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#81474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81475 = PCURVE('',#78687,#81476); +#81476 = DEFINITIONAL_REPRESENTATION('',(#81477),#81503); +#81477 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81478,#81479,#81480,#81481, + #81482,#81483,#81484,#81485,#81486,#81487,#81488,#81489,#81490, + #81491,#81492,#81493,#81494,#81495,#81496,#81497,#81498,#81499, + #81500,#81501,#81502),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.69533963372,-0.672836719409, -0.650333805098,-0.627830890788,-0.605327976477,-0.582825062167, -0.560322147856,-0.537819233545,-0.515316319235,-0.492813404924, @@ -97987,210 +100976,210 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.380298833371,-0.35779591906,-0.33529300475,-0.312790090439, -0.290287176129,-0.267784261818,-0.245281347507,-0.222778433197, -0.200275518886),.QUASI_UNIFORM_KNOTS.); -#79086 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#79087 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); -#79088 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); -#79089 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); -#79090 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); -#79091 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); -#79092 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); -#79093 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); -#79094 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); -#79095 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); -#79096 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); -#79097 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); -#79098 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); -#79099 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); -#79100 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); -#79101 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); -#79102 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); -#79103 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); -#79104 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); -#79105 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); -#79106 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); -#79107 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); -#79108 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); -#79109 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); -#79110 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#79111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79112 = ORIENTED_EDGE('',*,*,#79113,.T.); -#79113 = EDGE_CURVE('',#79069,#76532,#79114,.T.); -#79114 = SURFACE_CURVE('',#79115,(#79119,#79126),.PCURVE_S1.); -#79115 = LINE('',#79116,#79117); -#79116 = CARTESIAN_POINT('',(-1.181136529841,0.5259553457,0.137059047745 +#81478 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#81479 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); +#81480 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); +#81481 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); +#81482 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); +#81483 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); +#81484 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); +#81485 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); +#81486 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); +#81487 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); +#81488 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); +#81489 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); +#81490 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); +#81491 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); +#81492 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); +#81493 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); +#81494 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); +#81495 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); +#81496 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); +#81497 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); +#81498 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); +#81499 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); +#81500 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); +#81501 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); +#81502 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#81503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81504 = ORIENTED_EDGE('',*,*,#81505,.T.); +#81505 = EDGE_CURVE('',#81461,#78924,#81506,.T.); +#81506 = SURFACE_CURVE('',#81507,(#81511,#81518),.PCURVE_S1.); +#81507 = LINE('',#81508,#81509); +#81508 = CARTESIAN_POINT('',(-1.181136529841,0.5259553457,0.137059047745 )); -#79117 = VECTOR('',#79118,1.); -#79118 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79119 = PCURVE('',#78253,#79120); -#79120 = DEFINITIONAL_REPRESENTATION('',(#79121),#79125); -#79121 = LINE('',#79122,#79123); -#79122 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); -#79123 = VECTOR('',#79124,1.); -#79124 = DIRECTION('',(0.E+000,-1.)); -#79125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79126 = PCURVE('',#76641,#79127); -#79127 = DEFINITIONAL_REPRESENTATION('',(#79128),#79131); -#79128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79129,#79130),.UNSPECIFIED., +#81509 = VECTOR('',#81510,1.); +#81510 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81511 = PCURVE('',#80645,#81512); +#81512 = DEFINITIONAL_REPRESENTATION('',(#81513),#81517); +#81513 = LINE('',#81514,#81515); +#81514 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); +#81515 = VECTOR('',#81516,1.); +#81516 = DIRECTION('',(0.E+000,-1.)); +#81517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81518 = PCURVE('',#79033,#81519); +#81519 = DEFINITIONAL_REPRESENTATION('',(#81520),#81523); +#81520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81521,#81522),.UNSPECIFIED., .F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#79129 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); -#79130 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#79131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81521 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); +#81522 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#81523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#79132 = ORIENTED_EDGE('',*,*,#79133,.T.); -#79133 = EDGE_CURVE('',#76532,#78121,#79134,.T.); -#79134 = SURFACE_CURVE('',#79135,(#79139,#79146),.PCURVE_S1.); -#79135 = LINE('',#79136,#79137); -#79136 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, +#81524 = ORIENTED_EDGE('',*,*,#81525,.T.); +#81525 = EDGE_CURVE('',#78924,#80513,#81526,.T.); +#81526 = SURFACE_CURVE('',#81527,(#81531,#81538),.PCURVE_S1.); +#81527 = LINE('',#81528,#81529); +#81528 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, 0.633948125296)); -#79137 = VECTOR('',#79138,1.); -#79138 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#79139 = PCURVE('',#78253,#79140); -#79140 = DEFINITIONAL_REPRESENTATION('',(#79141),#79145); -#79141 = LINE('',#79142,#79143); -#79142 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#79143 = VECTOR('',#79144,1.); -#79144 = DIRECTION('',(0.968100345886,-0.250562807086)); -#79145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79146 = PCURVE('',#76570,#79147); -#79147 = DEFINITIONAL_REPRESENTATION('',(#79148),#79151); -#79148 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79149,#79150),.UNSPECIFIED., +#81529 = VECTOR('',#81530,1.); +#81530 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#81531 = PCURVE('',#80645,#81532); +#81532 = DEFINITIONAL_REPRESENTATION('',(#81533),#81537); +#81533 = LINE('',#81534,#81535); +#81534 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#81535 = VECTOR('',#81536,1.); +#81536 = DIRECTION('',(0.968100345886,-0.250562807086)); +#81537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81538 = PCURVE('',#78962,#81539); +#81539 = DEFINITIONAL_REPRESENTATION('',(#81540),#81543); +#81540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81541,#81542),.UNSPECIFIED., .F.,.F.,(2,2),(-0.531367877804,-3.630376297074E-002), .PIECEWISE_BEZIER_KNOTS.); -#79149 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#79150 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#79151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79152 = ORIENTED_EDGE('',*,*,#78563,.F.); -#79153 = ORIENTED_EDGE('',*,*,#79154,.F.); -#79154 = EDGE_CURVE('',#78457,#78536,#79155,.T.); -#79155 = SURFACE_CURVE('',#79156,(#79160,#79167),.PCURVE_S1.); -#79156 = LINE('',#79157,#79158); -#79157 = CARTESIAN_POINT('',(-3.36,0.65,0.6)); -#79158 = VECTOR('',#79159,1.); -#79159 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79160 = PCURVE('',#78253,#79161); -#79161 = DEFINITIONAL_REPRESENTATION('',(#79162),#79166); -#79162 = LINE('',#79163,#79164); -#79163 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#79164 = VECTOR('',#79165,1.); -#79165 = DIRECTION('',(0.E+000,-1.)); -#79166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79167 = PCURVE('',#79168,#79173); -#79168 = PLANE('',#79169); -#79169 = AXIS2_PLACEMENT_3D('',#79170,#79171,#79172); -#79170 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#79171 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#79172 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79173 = DEFINITIONAL_REPRESENTATION('',(#79174),#79178); -#79174 = LINE('',#79175,#79176); -#79175 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); -#79176 = VECTOR('',#79177,1.); -#79177 = DIRECTION('',(1.,0.E+000)); -#79178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79179 = ORIENTED_EDGE('',*,*,#78456,.F.); -#79180 = ORIENTED_EDGE('',*,*,#79181,.F.); -#79181 = EDGE_CURVE('',#78350,#78429,#79182,.T.); -#79182 = SURFACE_CURVE('',#79183,(#79187,#79194),.PCURVE_S1.); -#79183 = LINE('',#79184,#79185); -#79184 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#79185 = VECTOR('',#79186,1.); -#79186 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79187 = PCURVE('',#78253,#79188); -#79188 = DEFINITIONAL_REPRESENTATION('',(#79189),#79193); -#79189 = LINE('',#79190,#79191); -#79190 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#79191 = VECTOR('',#79192,1.); -#79192 = DIRECTION('',(0.E+000,-1.)); -#79193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79194 = PCURVE('',#79195,#79200); -#79195 = PLANE('',#79196); -#79196 = AXIS2_PLACEMENT_3D('',#79197,#79198,#79199); -#79197 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#79198 = DIRECTION('',(0.E+000,0.E+000,1.)); -#79199 = DIRECTION('',(1.,0.E+000,0.E+000)); -#79200 = DEFINITIONAL_REPRESENTATION('',(#79201),#79205); -#79201 = LINE('',#79202,#79203); -#79202 = CARTESIAN_POINT('',(-1.26,-5.208001194231E-003)); -#79203 = VECTOR('',#79204,1.); -#79204 = DIRECTION('',(-1.,0.E+000)); -#79205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79206 = ORIENTED_EDGE('',*,*,#78349,.F.); -#79207 = ORIENTED_EDGE('',*,*,#79208,.F.); -#79208 = EDGE_CURVE('',#78238,#78322,#79209,.T.); -#79209 = SURFACE_CURVE('',#79210,(#79214,#79221),.PCURVE_S1.); -#79210 = LINE('',#79211,#79212); -#79211 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#79212 = VECTOR('',#79213,1.); -#79213 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79214 = PCURVE('',#78253,#79215); -#79215 = DEFINITIONAL_REPRESENTATION('',(#79216),#79220); -#79216 = LINE('',#79217,#79218); -#79217 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#79218 = VECTOR('',#79219,1.); -#79219 = DIRECTION('',(0.E+000,-1.)); -#79220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79221 = PCURVE('',#79222,#79227); -#79222 = PLANE('',#79223); -#79223 = AXIS2_PLACEMENT_3D('',#79224,#79225,#79226); -#79224 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#79225 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#79226 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79227 = DEFINITIONAL_REPRESENTATION('',(#79228),#79232); -#79228 = LINE('',#79229,#79230); -#79229 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); -#79230 = VECTOR('',#79231,1.); -#79231 = DIRECTION('',(1.,0.E+000)); -#79232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79233 = ORIENTED_EDGE('',*,*,#78237,.F.); -#79234 = ADVANCED_FACE('',(#79235),#75608,.F.); -#79235 = FACE_BOUND('',#79236,.T.); -#79236 = EDGE_LOOP('',(#79237,#79282,#79327,#79328,#79350,#79395,#79396, - #79441,#79486,#79487,#79509,#79554)); -#79237 = ORIENTED_EDGE('',*,*,#79238,.T.); -#79238 = EDGE_CURVE('',#76108,#79239,#79241,.T.); -#79239 = VERTEX_POINT('',#79240); -#79240 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#79241 = SURFACE_CURVE('',#79242,(#79246,#79253),.PCURVE_S1.); -#79242 = LINE('',#79243,#79244); -#79243 = CARTESIAN_POINT('',(1.287659054385,-0.371136529841,1.E-001)); -#79244 = VECTOR('',#79245,1.); -#79245 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#79246 = PCURVE('',#75608,#79247); -#79247 = DEFINITIONAL_REPRESENTATION('',(#79248),#79252); -#79248 = LINE('',#79249,#79250); -#79249 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); -#79250 = VECTOR('',#79251,1.); -#79251 = DIRECTION('',(1.668003342285E-016,-1.)); -#79252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79253 = PCURVE('',#76366,#79254); -#79254 = DEFINITIONAL_REPRESENTATION('',(#79255),#79281); -#79255 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79256,#79257,#79258,#79259, - #79260,#79261,#79262,#79263,#79264,#79265,#79266,#79267,#79268, - #79269,#79270,#79271,#79272,#79273,#79274,#79275,#79276,#79277, - #79278,#79279,#79280),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81541 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#81542 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#81543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81544 = ORIENTED_EDGE('',*,*,#80955,.F.); +#81545 = ORIENTED_EDGE('',*,*,#81546,.F.); +#81546 = EDGE_CURVE('',#80849,#80928,#81547,.T.); +#81547 = SURFACE_CURVE('',#81548,(#81552,#81559),.PCURVE_S1.); +#81548 = LINE('',#81549,#81550); +#81549 = CARTESIAN_POINT('',(-3.36,0.65,0.6)); +#81550 = VECTOR('',#81551,1.); +#81551 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81552 = PCURVE('',#80645,#81553); +#81553 = DEFINITIONAL_REPRESENTATION('',(#81554),#81558); +#81554 = LINE('',#81555,#81556); +#81555 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#81556 = VECTOR('',#81557,1.); +#81557 = DIRECTION('',(0.E+000,-1.)); +#81558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81559 = PCURVE('',#81560,#81565); +#81560 = PLANE('',#81561); +#81561 = AXIS2_PLACEMENT_3D('',#81562,#81563,#81564); +#81562 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#81563 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#81564 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81565 = DEFINITIONAL_REPRESENTATION('',(#81566),#81570); +#81566 = LINE('',#81567,#81568); +#81567 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); +#81568 = VECTOR('',#81569,1.); +#81569 = DIRECTION('',(1.,0.E+000)); +#81570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81571 = ORIENTED_EDGE('',*,*,#80848,.F.); +#81572 = ORIENTED_EDGE('',*,*,#81573,.F.); +#81573 = EDGE_CURVE('',#80742,#80821,#81574,.T.); +#81574 = SURFACE_CURVE('',#81575,(#81579,#81586),.PCURVE_S1.); +#81575 = LINE('',#81576,#81577); +#81576 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#81577 = VECTOR('',#81578,1.); +#81578 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81579 = PCURVE('',#80645,#81580); +#81580 = DEFINITIONAL_REPRESENTATION('',(#81581),#81585); +#81581 = LINE('',#81582,#81583); +#81582 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81583 = VECTOR('',#81584,1.); +#81584 = DIRECTION('',(0.E+000,-1.)); +#81585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81586 = PCURVE('',#81587,#81592); +#81587 = PLANE('',#81588); +#81588 = AXIS2_PLACEMENT_3D('',#81589,#81590,#81591); +#81589 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#81590 = DIRECTION('',(0.E+000,0.E+000,1.)); +#81591 = DIRECTION('',(1.,0.E+000,0.E+000)); +#81592 = DEFINITIONAL_REPRESENTATION('',(#81593),#81597); +#81593 = LINE('',#81594,#81595); +#81594 = CARTESIAN_POINT('',(-1.26,-5.208001194231E-003)); +#81595 = VECTOR('',#81596,1.); +#81596 = DIRECTION('',(-1.,0.E+000)); +#81597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81598 = ORIENTED_EDGE('',*,*,#80741,.F.); +#81599 = ORIENTED_EDGE('',*,*,#81600,.F.); +#81600 = EDGE_CURVE('',#80630,#80714,#81601,.T.); +#81601 = SURFACE_CURVE('',#81602,(#81606,#81613),.PCURVE_S1.); +#81602 = LINE('',#81603,#81604); +#81603 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#81604 = VECTOR('',#81605,1.); +#81605 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81606 = PCURVE('',#80645,#81607); +#81607 = DEFINITIONAL_REPRESENTATION('',(#81608),#81612); +#81608 = LINE('',#81609,#81610); +#81609 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#81610 = VECTOR('',#81611,1.); +#81611 = DIRECTION('',(0.E+000,-1.)); +#81612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81613 = PCURVE('',#81614,#81619); +#81614 = PLANE('',#81615); +#81615 = AXIS2_PLACEMENT_3D('',#81616,#81617,#81618); +#81616 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#81617 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#81618 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81619 = DEFINITIONAL_REPRESENTATION('',(#81620),#81624); +#81620 = LINE('',#81621,#81622); +#81621 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); +#81622 = VECTOR('',#81623,1.); +#81623 = DIRECTION('',(1.,0.E+000)); +#81624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81625 = ORIENTED_EDGE('',*,*,#80629,.F.); +#81626 = ADVANCED_FACE('',(#81627),#78000,.F.); +#81627 = FACE_BOUND('',#81628,.T.); +#81628 = EDGE_LOOP('',(#81629,#81674,#81719,#81720,#81742,#81787,#81788, + #81833,#81878,#81879,#81901,#81946)); +#81629 = ORIENTED_EDGE('',*,*,#81630,.T.); +#81630 = EDGE_CURVE('',#78500,#81631,#81633,.T.); +#81631 = VERTEX_POINT('',#81632); +#81632 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#81633 = SURFACE_CURVE('',#81634,(#81638,#81645),.PCURVE_S1.); +#81634 = LINE('',#81635,#81636); +#81635 = CARTESIAN_POINT('',(1.287659054385,-0.371136529841,1.E-001)); +#81636 = VECTOR('',#81637,1.); +#81637 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#81638 = PCURVE('',#78000,#81639); +#81639 = DEFINITIONAL_REPRESENTATION('',(#81640),#81644); +#81640 = LINE('',#81641,#81642); +#81641 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); +#81642 = VECTOR('',#81643,1.); +#81643 = DIRECTION('',(1.668003342285E-016,-1.)); +#81644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81645 = PCURVE('',#78758,#81646); +#81646 = DEFINITIONAL_REPRESENTATION('',(#81647),#81673); +#81647 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81648,#81649,#81650,#81651, + #81652,#81653,#81654,#81655,#81656,#81657,#81658,#81659,#81660, + #81661,#81662,#81663,#81664,#81665,#81666,#81667,#81668,#81669, + #81670,#81671,#81672),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598,-0.717560595074, -0.682918188551,-0.648275782028,-0.613633375504,-0.578990968981, -0.544348562458,-0.509706155934,-0.475063749411,-0.440421342888, @@ -98198,66 +101187,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.267209310271,-0.232566903748,-0.197924497224,-0.163282090701, -0.128639684178,-9.399727765447E-002,-5.935487113115E-002, -2.471246460782E-002,9.929941915506E-003),.UNSPECIFIED.); -#79256 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#79257 = CARTESIAN_POINT('',(4.712388980385,0.280480997085)); -#79258 = CARTESIAN_POINT('',(4.712388980385,0.303575934767)); -#79259 = CARTESIAN_POINT('',(4.712388980385,0.33821834129)); -#79260 = CARTESIAN_POINT('',(4.712388980385,0.372860747813)); -#79261 = CARTESIAN_POINT('',(4.712388980385,0.407503154337)); -#79262 = CARTESIAN_POINT('',(4.712388980385,0.44214556086)); -#79263 = CARTESIAN_POINT('',(4.712388980385,0.476787967383)); -#79264 = CARTESIAN_POINT('',(4.712388980385,0.511430373907)); -#79265 = CARTESIAN_POINT('',(4.712388980385,0.54607278043)); -#79266 = CARTESIAN_POINT('',(4.712388980385,0.580715186953)); -#79267 = CARTESIAN_POINT('',(4.712388980385,0.615357593477)); -#79268 = CARTESIAN_POINT('',(4.712388980385,0.65)); -#79269 = CARTESIAN_POINT('',(4.712388980385,0.684642406523)); -#79270 = CARTESIAN_POINT('',(4.712388980385,0.719284813047)); -#79271 = CARTESIAN_POINT('',(4.712388980385,0.75392721957)); -#79272 = CARTESIAN_POINT('',(4.712388980385,0.788569626093)); -#79273 = CARTESIAN_POINT('',(4.712388980385,0.823212032617)); -#79274 = CARTESIAN_POINT('',(4.712388980385,0.85785443914)); -#79275 = CARTESIAN_POINT('',(4.712388980385,0.892496845663)); -#79276 = CARTESIAN_POINT('',(4.712388980385,0.927139252187)); -#79277 = CARTESIAN_POINT('',(4.712388980385,0.96178165871)); -#79278 = CARTESIAN_POINT('',(4.712388980385,0.996424065233)); -#79279 = CARTESIAN_POINT('',(4.712388980385,1.019519002915)); -#79280 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); -#79281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79282 = ORIENTED_EDGE('',*,*,#79283,.T.); -#79283 = EDGE_CURVE('',#79239,#75551,#79284,.T.); -#79284 = SURFACE_CURVE('',#79285,(#79290,#79298),.PCURVE_S1.); -#79285 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79286,#79287,#79288,#79289 +#81648 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#81649 = CARTESIAN_POINT('',(4.712388980385,0.280480997085)); +#81650 = CARTESIAN_POINT('',(4.712388980385,0.303575934767)); +#81651 = CARTESIAN_POINT('',(4.712388980385,0.33821834129)); +#81652 = CARTESIAN_POINT('',(4.712388980385,0.372860747813)); +#81653 = CARTESIAN_POINT('',(4.712388980385,0.407503154337)); +#81654 = CARTESIAN_POINT('',(4.712388980385,0.44214556086)); +#81655 = CARTESIAN_POINT('',(4.712388980385,0.476787967383)); +#81656 = CARTESIAN_POINT('',(4.712388980385,0.511430373907)); +#81657 = CARTESIAN_POINT('',(4.712388980385,0.54607278043)); +#81658 = CARTESIAN_POINT('',(4.712388980385,0.580715186953)); +#81659 = CARTESIAN_POINT('',(4.712388980385,0.615357593477)); +#81660 = CARTESIAN_POINT('',(4.712388980385,0.65)); +#81661 = CARTESIAN_POINT('',(4.712388980385,0.684642406523)); +#81662 = CARTESIAN_POINT('',(4.712388980385,0.719284813047)); +#81663 = CARTESIAN_POINT('',(4.712388980385,0.75392721957)); +#81664 = CARTESIAN_POINT('',(4.712388980385,0.788569626093)); +#81665 = CARTESIAN_POINT('',(4.712388980385,0.823212032617)); +#81666 = CARTESIAN_POINT('',(4.712388980385,0.85785443914)); +#81667 = CARTESIAN_POINT('',(4.712388980385,0.892496845663)); +#81668 = CARTESIAN_POINT('',(4.712388980385,0.927139252187)); +#81669 = CARTESIAN_POINT('',(4.712388980385,0.96178165871)); +#81670 = CARTESIAN_POINT('',(4.712388980385,0.996424065233)); +#81671 = CARTESIAN_POINT('',(4.712388980385,1.019519002915)); +#81672 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); +#81673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81674 = ORIENTED_EDGE('',*,*,#81675,.T.); +#81675 = EDGE_CURVE('',#81631,#77943,#81676,.T.); +#81676 = SURFACE_CURVE('',#81677,(#81682,#81690),.PCURVE_S1.); +#81677 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81678,#81679,#81680,#81681 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79286 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#79287 = CARTESIAN_POINT('',(1.287659054385,-0.407584046027,1.E-001)); -#79288 = CARTESIAN_POINT('',(1.27790129499,-0.431596067115,1.E-001)); -#79289 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#79290 = PCURVE('',#75608,#79291); -#79291 = DEFINITIONAL_REPRESENTATION('',(#79292),#79297); -#79292 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79293,#79294,#79295,#79296 +#81678 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#81679 = CARTESIAN_POINT('',(1.287659054385,-0.407584046027,1.E-001)); +#81680 = CARTESIAN_POINT('',(1.27790129499,-0.431596067115,1.E-001)); +#81681 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#81682 = PCURVE('',#78000,#81683); +#81683 = DEFINITIONAL_REPRESENTATION('',(#81684),#81689); +#81684 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81685,#81686,#81687,#81688 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79293 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); -#79294 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); -#79295 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); -#79296 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#79297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79298 = PCURVE('',#75660,#79299); -#79299 = DEFINITIONAL_REPRESENTATION('',(#79300),#79326); -#79300 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79301,#79302,#79303,#79304, - #79305,#79306,#79307,#79308,#79309,#79310,#79311,#79312,#79313, - #79314,#79315,#79316,#79317,#79318,#79319,#79320,#79321,#79322, - #79323,#79324,#79325),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81685 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); +#81686 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); +#81687 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); +#81688 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#81689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81690 = PCURVE('',#78052,#81691); +#81691 = DEFINITIONAL_REPRESENTATION('',(#81692),#81718); +#81692 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81693,#81694,#81695,#81696, + #81697,#81698,#81699,#81700,#81701,#81702,#81703,#81704,#81705, + #81706,#81707,#81708,#81709,#81710,#81711,#81712,#81713,#81714, + #81715,#81716,#81717),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -98265,95 +101254,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#79301 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#79302 = CARTESIAN_POINT('',(0.740753697746,-2.901323913156E-008)); -#79303 = CARTESIAN_POINT('',(0.718425611961,2.616756247982E-005)); -#79304 = CARTESIAN_POINT('',(0.684727524261,1.282673135031E-004)); -#79305 = CARTESIAN_POINT('',(0.650847765387,2.772530388756E-004)); -#79306 = CARTESIAN_POINT('',(0.616809612353,4.570658043226E-004)); -#79307 = CARTESIAN_POINT('',(0.582635599926,6.520952931882E-004)); -#79308 = CARTESIAN_POINT('',(0.548347414424,8.475624467471E-004)); -#79309 = CARTESIAN_POINT('',(0.513965932674,1.029943289554E-003)); -#79310 = CARTESIAN_POINT('',(0.479511265006,1.18735393038E-003)); -#79311 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); -#79312 = CARTESIAN_POINT('',(0.41045949854,1.390009812362E-003)); -#79313 = CARTESIAN_POINT('',(0.375899653916,1.422641316503E-003)); -#79314 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); -#79315 = CARTESIAN_POINT('',(0.306802773621,1.339263477882E-003)); -#79316 = CARTESIAN_POINT('',(0.272301764008,1.227390254485E-003)); -#79317 = CARTESIAN_POINT('',(0.237856655052,1.076339414003E-003)); -#79318 = CARTESIAN_POINT('',(0.203486118557,8.953387637339E-004)); -#79319 = CARTESIAN_POINT('',(0.169209394064,6.962198987728E-004)); -#79320 = CARTESIAN_POINT('',(0.135046437107,4.93149846856E-004)); -#79321 = CARTESIAN_POINT('',(0.101018031154,3.022859269965E-004)); -#79322 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577683E-004)); -#79323 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401059E-005)); -#79324 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318693053E-008)); -#79325 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#79326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79327 = ORIENTED_EDGE('',*,*,#75550,.T.); -#79328 = ORIENTED_EDGE('',*,*,#79329,.T.); -#79329 = EDGE_CURVE('',#75553,#79330,#79332,.T.); -#79330 = VERTEX_POINT('',#79331); -#79331 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#79332 = SURFACE_CURVE('',#79333,(#79337,#79344),.PCURVE_S1.); -#79333 = LINE('',#79334,#79335); -#79334 = CARTESIAN_POINT('',(-1.181136529841,-0.477659054385,1.E-001)); -#79335 = VECTOR('',#79336,1.); -#79336 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#79337 = PCURVE('',#75608,#79338); -#79338 = DEFINITIONAL_REPRESENTATION('',(#79339),#79343); -#79339 = LINE('',#79340,#79341); -#79340 = CARTESIAN_POINT('',(-2.641136529841,0.172340945615)); -#79341 = VECTOR('',#79342,1.); -#79342 = DIRECTION('',(-1.,0.E+000)); -#79343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79344 = PCURVE('',#75816,#79345); -#79345 = DEFINITIONAL_REPRESENTATION('',(#79346),#79349); -#79346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79347,#79348),.UNSPECIFIED., +#81693 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#81694 = CARTESIAN_POINT('',(0.740753697746,-2.901323913156E-008)); +#81695 = CARTESIAN_POINT('',(0.718425611961,2.616756247982E-005)); +#81696 = CARTESIAN_POINT('',(0.684727524261,1.282673135031E-004)); +#81697 = CARTESIAN_POINT('',(0.650847765387,2.772530388756E-004)); +#81698 = CARTESIAN_POINT('',(0.616809612353,4.570658043226E-004)); +#81699 = CARTESIAN_POINT('',(0.582635599926,6.520952931882E-004)); +#81700 = CARTESIAN_POINT('',(0.548347414424,8.475624467471E-004)); +#81701 = CARTESIAN_POINT('',(0.513965932674,1.029943289554E-003)); +#81702 = CARTESIAN_POINT('',(0.479511265006,1.18735393038E-003)); +#81703 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); +#81704 = CARTESIAN_POINT('',(0.41045949854,1.390009812362E-003)); +#81705 = CARTESIAN_POINT('',(0.375899653916,1.422641316503E-003)); +#81706 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); +#81707 = CARTESIAN_POINT('',(0.306802773621,1.339263477882E-003)); +#81708 = CARTESIAN_POINT('',(0.272301764008,1.227390254485E-003)); +#81709 = CARTESIAN_POINT('',(0.237856655052,1.076339414003E-003)); +#81710 = CARTESIAN_POINT('',(0.203486118557,8.953387637339E-004)); +#81711 = CARTESIAN_POINT('',(0.169209394064,6.962198987728E-004)); +#81712 = CARTESIAN_POINT('',(0.135046437107,4.93149846856E-004)); +#81713 = CARTESIAN_POINT('',(0.101018031154,3.022859269965E-004)); +#81714 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577683E-004)); +#81715 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401059E-005)); +#81716 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318693053E-008)); +#81717 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#81718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81719 = ORIENTED_EDGE('',*,*,#77942,.T.); +#81720 = ORIENTED_EDGE('',*,*,#81721,.T.); +#81721 = EDGE_CURVE('',#77945,#81722,#81724,.T.); +#81722 = VERTEX_POINT('',#81723); +#81723 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#81724 = SURFACE_CURVE('',#81725,(#81729,#81736),.PCURVE_S1.); +#81725 = LINE('',#81726,#81727); +#81726 = CARTESIAN_POINT('',(-1.181136529841,-0.477659054385,1.E-001)); +#81727 = VECTOR('',#81728,1.); +#81728 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#81729 = PCURVE('',#78000,#81730); +#81730 = DEFINITIONAL_REPRESENTATION('',(#81731),#81735); +#81731 = LINE('',#81732,#81733); +#81732 = CARTESIAN_POINT('',(-2.641136529841,0.172340945615)); +#81733 = VECTOR('',#81734,1.); +#81734 = DIRECTION('',(-1.,0.E+000)); +#81735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81736 = PCURVE('',#78208,#81737); +#81737 = DEFINITIONAL_REPRESENTATION('',(#81738),#81741); +#81738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81739,#81740),.UNSPECIFIED., .F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#79347 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); -#79348 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#79349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81739 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); +#81740 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#81741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#79350 = ORIENTED_EDGE('',*,*,#79351,.T.); -#79351 = EDGE_CURVE('',#79330,#75831,#79352,.T.); -#79352 = SURFACE_CURVE('',#79353,(#79358,#79366),.PCURVE_S1.); -#79353 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79354,#79355,#79356,#79357 +#81742 = ORIENTED_EDGE('',*,*,#81743,.T.); +#81743 = EDGE_CURVE('',#81722,#78223,#81744,.T.); +#81744 = SURFACE_CURVE('',#81745,(#81750,#81758),.PCURVE_S1.); +#81745 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81746,#81747,#81748,#81749 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79354 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#79355 = CARTESIAN_POINT('',(-1.217584046027,-0.477659054385,1.E-001)); -#79356 = CARTESIAN_POINT('',(-1.241596067115,-0.46790129499,1.E-001)); -#79357 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#79358 = PCURVE('',#75608,#79359); -#79359 = DEFINITIONAL_REPRESENTATION('',(#79360),#79365); -#79360 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79361,#79362,#79363,#79364 +#81746 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#81747 = CARTESIAN_POINT('',(-1.217584046027,-0.477659054385,1.E-001)); +#81748 = CARTESIAN_POINT('',(-1.241596067115,-0.46790129499,1.E-001)); +#81749 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#81750 = PCURVE('',#78000,#81751); +#81751 = DEFINITIONAL_REPRESENTATION('',(#81752),#81757); +#81752 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81753,#81754,#81755,#81756 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79361 = CARTESIAN_POINT('',(-2.651066471757,0.172340945615)); -#79362 = CARTESIAN_POINT('',(-2.677584046027,0.172340945615)); -#79363 = CARTESIAN_POINT('',(-2.701596067115,0.18209870501)); -#79364 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); -#79365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79366 = PCURVE('',#75935,#79367); -#79367 = DEFINITIONAL_REPRESENTATION('',(#79368),#79394); -#79368 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79369,#79370,#79371,#79372, - #79373,#79374,#79375,#79376,#79377,#79378,#79379,#79380,#79381, - #79382,#79383,#79384,#79385,#79386,#79387,#79388,#79389,#79390, - #79391,#79392,#79393),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81753 = CARTESIAN_POINT('',(-2.651066471757,0.172340945615)); +#81754 = CARTESIAN_POINT('',(-2.677584046027,0.172340945615)); +#81755 = CARTESIAN_POINT('',(-2.701596067115,0.18209870501)); +#81756 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); +#81757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81758 = PCURVE('',#78327,#81759); +#81759 = DEFINITIONAL_REPRESENTATION('',(#81760),#81786); +#81760 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81761,#81762,#81763,#81764, + #81765,#81766,#81767,#81768,#81769,#81770,#81771,#81772,#81773, + #81774,#81775,#81776,#81777,#81778,#81779,#81780,#81781,#81782, + #81783,#81784,#81785),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -98361,59 +101350,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#79369 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#79370 = CARTESIAN_POINT('',(0.740753697746,-2.901324287027E-008)); -#79371 = CARTESIAN_POINT('',(0.718425611961,2.616756246917E-005)); -#79372 = CARTESIAN_POINT('',(0.684727524261,1.282673134852E-004)); -#79373 = CARTESIAN_POINT('',(0.650847765387,2.772530388731E-004)); -#79374 = CARTESIAN_POINT('',(0.616809612353,4.570658043139E-004)); -#79375 = CARTESIAN_POINT('',(0.582635599926,6.5209529318E-004)); -#79376 = CARTESIAN_POINT('',(0.548347414424,8.475624467432E-004)); -#79377 = CARTESIAN_POINT('',(0.513965932674,1.029943289548E-003)); -#79378 = CARTESIAN_POINT('',(0.479511265006,1.187353930379E-003)); -#79379 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); -#79380 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); -#79381 = CARTESIAN_POINT('',(0.375899653916,1.422641316492E-003)); -#79382 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); -#79383 = CARTESIAN_POINT('',(0.306802773621,1.339263477879E-003)); -#79384 = CARTESIAN_POINT('',(0.272301764008,1.227390254476E-003)); -#79385 = CARTESIAN_POINT('',(0.237856655052,1.076339413998E-003)); -#79386 = CARTESIAN_POINT('',(0.203486118557,8.953387637282E-004)); -#79387 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); -#79388 = CARTESIAN_POINT('',(0.135046437107,4.931498468552E-004)); -#79389 = CARTESIAN_POINT('',(0.101018031154,3.022859269932E-004)); -#79390 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577614E-004)); -#79391 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009786E-005)); -#79392 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318295513E-008)); -#79393 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#79394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79395 = ORIENTED_EDGE('',*,*,#75830,.T.); -#79396 = ORIENTED_EDGE('',*,*,#79397,.T.); -#79397 = EDGE_CURVE('',#75833,#79398,#79400,.T.); -#79398 = VERTEX_POINT('',#79399); -#79399 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#79400 = SURFACE_CURVE('',#79401,(#79405,#79412),.PCURVE_S1.); -#79401 = LINE('',#79402,#79403); -#79402 = CARTESIAN_POINT('',(-1.287659054385,0.371136529841,1.E-001)); -#79403 = VECTOR('',#79404,1.); -#79404 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#79405 = PCURVE('',#75608,#79406); -#79406 = DEFINITIONAL_REPRESENTATION('',(#79407),#79411); -#79407 = LINE('',#79408,#79409); -#79408 = CARTESIAN_POINT('',(-2.747659054385,1.021136529841)); -#79409 = VECTOR('',#79410,1.); -#79410 = DIRECTION('',(-1.668003342285E-016,1.)); -#79411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79412 = PCURVE('',#76091,#79413); -#79413 = DEFINITIONAL_REPRESENTATION('',(#79414),#79440); -#79414 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79415,#79416,#79417,#79418, - #79419,#79420,#79421,#79422,#79423,#79424,#79425,#79426,#79427, - #79428,#79429,#79430,#79431,#79432,#79433,#79434,#79435,#79436, - #79437,#79438,#79439),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81761 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#81762 = CARTESIAN_POINT('',(0.740753697746,-2.901324287027E-008)); +#81763 = CARTESIAN_POINT('',(0.718425611961,2.616756246917E-005)); +#81764 = CARTESIAN_POINT('',(0.684727524261,1.282673134852E-004)); +#81765 = CARTESIAN_POINT('',(0.650847765387,2.772530388731E-004)); +#81766 = CARTESIAN_POINT('',(0.616809612353,4.570658043139E-004)); +#81767 = CARTESIAN_POINT('',(0.582635599926,6.5209529318E-004)); +#81768 = CARTESIAN_POINT('',(0.548347414424,8.475624467432E-004)); +#81769 = CARTESIAN_POINT('',(0.513965932674,1.029943289548E-003)); +#81770 = CARTESIAN_POINT('',(0.479511265006,1.187353930379E-003)); +#81771 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); +#81772 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); +#81773 = CARTESIAN_POINT('',(0.375899653916,1.422641316492E-003)); +#81774 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); +#81775 = CARTESIAN_POINT('',(0.306802773621,1.339263477879E-003)); +#81776 = CARTESIAN_POINT('',(0.272301764008,1.227390254476E-003)); +#81777 = CARTESIAN_POINT('',(0.237856655052,1.076339413998E-003)); +#81778 = CARTESIAN_POINT('',(0.203486118557,8.953387637282E-004)); +#81779 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); +#81780 = CARTESIAN_POINT('',(0.135046437107,4.931498468552E-004)); +#81781 = CARTESIAN_POINT('',(0.101018031154,3.022859269932E-004)); +#81782 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577614E-004)); +#81783 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009786E-005)); +#81784 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318295513E-008)); +#81785 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#81786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81787 = ORIENTED_EDGE('',*,*,#78222,.T.); +#81788 = ORIENTED_EDGE('',*,*,#81789,.T.); +#81789 = EDGE_CURVE('',#78225,#81790,#81792,.T.); +#81790 = VERTEX_POINT('',#81791); +#81791 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#81792 = SURFACE_CURVE('',#81793,(#81797,#81804),.PCURVE_S1.); +#81793 = LINE('',#81794,#81795); +#81794 = CARTESIAN_POINT('',(-1.287659054385,0.371136529841,1.E-001)); +#81795 = VECTOR('',#81796,1.); +#81796 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#81797 = PCURVE('',#78000,#81798); +#81798 = DEFINITIONAL_REPRESENTATION('',(#81799),#81803); +#81799 = LINE('',#81800,#81801); +#81800 = CARTESIAN_POINT('',(-2.747659054385,1.021136529841)); +#81801 = VECTOR('',#81802,1.); +#81802 = DIRECTION('',(-1.668003342285E-016,1.)); +#81803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81804 = PCURVE('',#78483,#81805); +#81805 = DEFINITIONAL_REPRESENTATION('',(#81806),#81832); +#81806 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81807,#81808,#81809,#81810, + #81811,#81812,#81813,#81814,#81815,#81816,#81817,#81818,#81819, + #81820,#81821,#81822,#81823,#81824,#81825,#81826,#81827,#81828, + #81829,#81830,#81831),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598,-0.717560595074, -0.682918188551,-0.648275782028,-0.613633375504,-0.578990968981, -0.544348562458,-0.509706155934,-0.475063749411,-0.440421342888, @@ -98421,66 +101410,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.267209310271,-0.232566903748,-0.197924497224,-0.163282090701, -0.128639684178,-9.399727765447E-002,-5.935487113115E-002, -2.471246460782E-002,9.929941915506E-003),.UNSPECIFIED.); -#79415 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); -#79416 = CARTESIAN_POINT('',(4.712388980385,-1.019519002915)); -#79417 = CARTESIAN_POINT('',(4.712388980385,-0.996424065233)); -#79418 = CARTESIAN_POINT('',(4.712388980385,-0.96178165871)); -#79419 = CARTESIAN_POINT('',(4.712388980385,-0.927139252187)); -#79420 = CARTESIAN_POINT('',(4.712388980385,-0.892496845663)); -#79421 = CARTESIAN_POINT('',(4.712388980385,-0.85785443914)); -#79422 = CARTESIAN_POINT('',(4.712388980385,-0.823212032617)); -#79423 = CARTESIAN_POINT('',(4.712388980385,-0.788569626093)); -#79424 = CARTESIAN_POINT('',(4.712388980385,-0.75392721957)); -#79425 = CARTESIAN_POINT('',(4.712388980385,-0.719284813047)); -#79426 = CARTESIAN_POINT('',(4.712388980385,-0.684642406523)); -#79427 = CARTESIAN_POINT('',(4.712388980385,-0.65)); -#79428 = CARTESIAN_POINT('',(4.712388980385,-0.615357593477)); -#79429 = CARTESIAN_POINT('',(4.712388980385,-0.580715186953)); -#79430 = CARTESIAN_POINT('',(4.712388980385,-0.54607278043)); -#79431 = CARTESIAN_POINT('',(4.712388980385,-0.511430373907)); -#79432 = CARTESIAN_POINT('',(4.712388980385,-0.476787967383)); -#79433 = CARTESIAN_POINT('',(4.712388980385,-0.44214556086)); -#79434 = CARTESIAN_POINT('',(4.712388980385,-0.407503154337)); -#79435 = CARTESIAN_POINT('',(4.712388980385,-0.372860747813)); -#79436 = CARTESIAN_POINT('',(4.712388980385,-0.33821834129)); -#79437 = CARTESIAN_POINT('',(4.712388980385,-0.303575934767)); -#79438 = CARTESIAN_POINT('',(4.712388980385,-0.280480997085)); -#79439 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#79440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79441 = ORIENTED_EDGE('',*,*,#79442,.T.); -#79442 = EDGE_CURVE('',#79398,#76381,#79443,.T.); -#79443 = SURFACE_CURVE('',#79444,(#79449,#79457),.PCURVE_S1.); -#79444 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79445,#79446,#79447,#79448 +#81807 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); +#81808 = CARTESIAN_POINT('',(4.712388980385,-1.019519002915)); +#81809 = CARTESIAN_POINT('',(4.712388980385,-0.996424065233)); +#81810 = CARTESIAN_POINT('',(4.712388980385,-0.96178165871)); +#81811 = CARTESIAN_POINT('',(4.712388980385,-0.927139252187)); +#81812 = CARTESIAN_POINT('',(4.712388980385,-0.892496845663)); +#81813 = CARTESIAN_POINT('',(4.712388980385,-0.85785443914)); +#81814 = CARTESIAN_POINT('',(4.712388980385,-0.823212032617)); +#81815 = CARTESIAN_POINT('',(4.712388980385,-0.788569626093)); +#81816 = CARTESIAN_POINT('',(4.712388980385,-0.75392721957)); +#81817 = CARTESIAN_POINT('',(4.712388980385,-0.719284813047)); +#81818 = CARTESIAN_POINT('',(4.712388980385,-0.684642406523)); +#81819 = CARTESIAN_POINT('',(4.712388980385,-0.65)); +#81820 = CARTESIAN_POINT('',(4.712388980385,-0.615357593477)); +#81821 = CARTESIAN_POINT('',(4.712388980385,-0.580715186953)); +#81822 = CARTESIAN_POINT('',(4.712388980385,-0.54607278043)); +#81823 = CARTESIAN_POINT('',(4.712388980385,-0.511430373907)); +#81824 = CARTESIAN_POINT('',(4.712388980385,-0.476787967383)); +#81825 = CARTESIAN_POINT('',(4.712388980385,-0.44214556086)); +#81826 = CARTESIAN_POINT('',(4.712388980385,-0.407503154337)); +#81827 = CARTESIAN_POINT('',(4.712388980385,-0.372860747813)); +#81828 = CARTESIAN_POINT('',(4.712388980385,-0.33821834129)); +#81829 = CARTESIAN_POINT('',(4.712388980385,-0.303575934767)); +#81830 = CARTESIAN_POINT('',(4.712388980385,-0.280480997085)); +#81831 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#81832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81833 = ORIENTED_EDGE('',*,*,#81834,.T.); +#81834 = EDGE_CURVE('',#81790,#78773,#81835,.T.); +#81835 = SURFACE_CURVE('',#81836,(#81841,#81849),.PCURVE_S1.); +#81836 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81837,#81838,#81839,#81840 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79445 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#79446 = CARTESIAN_POINT('',(-1.287659054385,0.407584046027,1.E-001)); -#79447 = CARTESIAN_POINT('',(-1.27790129499,0.431596067115,1.E-001)); -#79448 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#79449 = PCURVE('',#75608,#79450); -#79450 = DEFINITIONAL_REPRESENTATION('',(#79451),#79456); -#79451 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79452,#79453,#79454,#79455 +#81837 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#81838 = CARTESIAN_POINT('',(-1.287659054385,0.407584046027,1.E-001)); +#81839 = CARTESIAN_POINT('',(-1.27790129499,0.431596067115,1.E-001)); +#81840 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#81841 = PCURVE('',#78000,#81842); +#81842 = DEFINITIONAL_REPRESENTATION('',(#81843),#81848); +#81843 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81844,#81845,#81846,#81847 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79452 = CARTESIAN_POINT('',(-2.747659054385,1.031066471757)); -#79453 = CARTESIAN_POINT('',(-2.747659054385,1.057584046027)); -#79454 = CARTESIAN_POINT('',(-2.73790129499,1.081596067115)); -#79455 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); -#79456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79457 = PCURVE('',#76485,#79458); -#79458 = DEFINITIONAL_REPRESENTATION('',(#79459),#79485); -#79459 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79460,#79461,#79462,#79463, - #79464,#79465,#79466,#79467,#79468,#79469,#79470,#79471,#79472, - #79473,#79474,#79475,#79476,#79477,#79478,#79479,#79480,#79481, - #79482,#79483,#79484),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81844 = CARTESIAN_POINT('',(-2.747659054385,1.031066471757)); +#81845 = CARTESIAN_POINT('',(-2.747659054385,1.057584046027)); +#81846 = CARTESIAN_POINT('',(-2.73790129499,1.081596067115)); +#81847 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); +#81848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81849 = PCURVE('',#78877,#81850); +#81850 = DEFINITIONAL_REPRESENTATION('',(#81851),#81877); +#81851 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81852,#81853,#81854,#81855, + #81856,#81857,#81858,#81859,#81860,#81861,#81862,#81863,#81864, + #81865,#81866,#81867,#81868,#81869,#81870,#81871,#81872,#81873, + #81874,#81875,#81876),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -98488,95 +101477,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#79460 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#79461 = CARTESIAN_POINT('',(0.740753697746,-2.901324291685E-008)); -#79462 = CARTESIAN_POINT('',(0.718425611961,2.616756246933E-005)); -#79463 = CARTESIAN_POINT('',(0.684727524261,1.282673134849E-004)); -#79464 = CARTESIAN_POINT('',(0.650847765387,2.772530388796E-004)); -#79465 = CARTESIAN_POINT('',(0.616809612353,4.570658043087E-004)); -#79466 = CARTESIAN_POINT('',(0.582635599926,6.52095293185E-004)); -#79467 = CARTESIAN_POINT('',(0.548347414424,8.475624467394E-004)); -#79468 = CARTESIAN_POINT('',(0.513965932674,1.029943289555E-003)); -#79469 = CARTESIAN_POINT('',(0.479511265006,1.187353930376E-003)); -#79470 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); -#79471 = CARTESIAN_POINT('',(0.41045949854,1.390009812356E-003)); -#79472 = CARTESIAN_POINT('',(0.375899653916,1.422641316499E-003)); -#79473 = CARTESIAN_POINT('',(0.341341416362,1.405524714319E-003)); -#79474 = CARTESIAN_POINT('',(0.306802773621,1.33926347789E-003)); -#79475 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); -#79476 = CARTESIAN_POINT('',(0.237856655052,1.076339413999E-003)); -#79477 = CARTESIAN_POINT('',(0.203486118557,8.953387637356E-004)); -#79478 = CARTESIAN_POINT('',(0.169209394064,6.962198987701E-004)); -#79479 = CARTESIAN_POINT('',(0.135046437107,4.931498468579E-004)); -#79480 = CARTESIAN_POINT('',(0.101018031154,3.022859269955E-004)); -#79481 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577615E-004)); -#79482 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401014E-005)); -#79483 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318532432E-008)); -#79484 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#79485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79486 = ORIENTED_EDGE('',*,*,#76380,.T.); -#79487 = ORIENTED_EDGE('',*,*,#79488,.T.); -#79488 = EDGE_CURVE('',#76383,#79489,#79491,.T.); -#79489 = VERTEX_POINT('',#79490); -#79490 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#79491 = SURFACE_CURVE('',#79492,(#79496,#79503),.PCURVE_S1.); -#79492 = LINE('',#79493,#79494); -#79493 = CARTESIAN_POINT('',(1.181136529841,0.477659054385,1.E-001)); -#79494 = VECTOR('',#79495,1.); -#79495 = DIRECTION('',(1.,0.E+000,0.E+000)); -#79496 = PCURVE('',#75608,#79497); -#79497 = DEFINITIONAL_REPRESENTATION('',(#79498),#79502); -#79498 = LINE('',#79499,#79500); -#79499 = CARTESIAN_POINT('',(-0.278863470159,1.127659054385)); -#79500 = VECTOR('',#79501,1.); -#79501 = DIRECTION('',(1.,0.E+000)); -#79502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79503 = PCURVE('',#76641,#79504); -#79504 = DEFINITIONAL_REPRESENTATION('',(#79505),#79508); -#79505 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79506,#79507),.UNSPECIFIED., +#81852 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#81853 = CARTESIAN_POINT('',(0.740753697746,-2.901324291685E-008)); +#81854 = CARTESIAN_POINT('',(0.718425611961,2.616756246933E-005)); +#81855 = CARTESIAN_POINT('',(0.684727524261,1.282673134849E-004)); +#81856 = CARTESIAN_POINT('',(0.650847765387,2.772530388796E-004)); +#81857 = CARTESIAN_POINT('',(0.616809612353,4.570658043087E-004)); +#81858 = CARTESIAN_POINT('',(0.582635599926,6.52095293185E-004)); +#81859 = CARTESIAN_POINT('',(0.548347414424,8.475624467394E-004)); +#81860 = CARTESIAN_POINT('',(0.513965932674,1.029943289555E-003)); +#81861 = CARTESIAN_POINT('',(0.479511265006,1.187353930376E-003)); +#81862 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); +#81863 = CARTESIAN_POINT('',(0.41045949854,1.390009812356E-003)); +#81864 = CARTESIAN_POINT('',(0.375899653916,1.422641316499E-003)); +#81865 = CARTESIAN_POINT('',(0.341341416362,1.405524714319E-003)); +#81866 = CARTESIAN_POINT('',(0.306802773621,1.33926347789E-003)); +#81867 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); +#81868 = CARTESIAN_POINT('',(0.237856655052,1.076339413999E-003)); +#81869 = CARTESIAN_POINT('',(0.203486118557,8.953387637356E-004)); +#81870 = CARTESIAN_POINT('',(0.169209394064,6.962198987701E-004)); +#81871 = CARTESIAN_POINT('',(0.135046437107,4.931498468579E-004)); +#81872 = CARTESIAN_POINT('',(0.101018031154,3.022859269955E-004)); +#81873 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577615E-004)); +#81874 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401014E-005)); +#81875 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318532432E-008)); +#81876 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#81877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81878 = ORIENTED_EDGE('',*,*,#78772,.T.); +#81879 = ORIENTED_EDGE('',*,*,#81880,.T.); +#81880 = EDGE_CURVE('',#78775,#81881,#81883,.T.); +#81881 = VERTEX_POINT('',#81882); +#81882 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#81883 = SURFACE_CURVE('',#81884,(#81888,#81895),.PCURVE_S1.); +#81884 = LINE('',#81885,#81886); +#81885 = CARTESIAN_POINT('',(1.181136529841,0.477659054385,1.E-001)); +#81886 = VECTOR('',#81887,1.); +#81887 = DIRECTION('',(1.,0.E+000,0.E+000)); +#81888 = PCURVE('',#78000,#81889); +#81889 = DEFINITIONAL_REPRESENTATION('',(#81890),#81894); +#81890 = LINE('',#81891,#81892); +#81891 = CARTESIAN_POINT('',(-0.278863470159,1.127659054385)); +#81892 = VECTOR('',#81893,1.); +#81893 = DIRECTION('',(1.,0.E+000)); +#81894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81895 = PCURVE('',#79033,#81896); +#81896 = DEFINITIONAL_REPRESENTATION('',(#81897),#81900); +#81897 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81898,#81899),.UNSPECIFIED., .F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#79506 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#79507 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); -#79508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#81898 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#81899 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); +#81900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#79509 = ORIENTED_EDGE('',*,*,#79510,.T.); -#79510 = EDGE_CURVE('',#79489,#76106,#79511,.T.); -#79511 = SURFACE_CURVE('',#79512,(#79517,#79525),.PCURVE_S1.); -#79512 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79513,#79514,#79515,#79516 +#81901 = ORIENTED_EDGE('',*,*,#81902,.T.); +#81902 = EDGE_CURVE('',#81881,#78498,#81903,.T.); +#81903 = SURFACE_CURVE('',#81904,(#81909,#81917),.PCURVE_S1.); +#81904 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81905,#81906,#81907,#81908 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79513 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#79514 = CARTESIAN_POINT('',(1.217584046027,0.477659054385,1.E-001)); -#79515 = CARTESIAN_POINT('',(1.241596067115,0.46790129499,1.E-001)); -#79516 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#79517 = PCURVE('',#75608,#79518); -#79518 = DEFINITIONAL_REPRESENTATION('',(#79519),#79524); -#79519 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79520,#79521,#79522,#79523 +#81905 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#81906 = CARTESIAN_POINT('',(1.217584046027,0.477659054385,1.E-001)); +#81907 = CARTESIAN_POINT('',(1.241596067115,0.46790129499,1.E-001)); +#81908 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#81909 = PCURVE('',#78000,#81910); +#81910 = DEFINITIONAL_REPRESENTATION('',(#81911),#81916); +#81911 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#81912,#81913,#81914,#81915 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79520 = CARTESIAN_POINT('',(-0.268933528243,1.127659054385)); -#79521 = CARTESIAN_POINT('',(-0.242415953973,1.127659054385)); -#79522 = CARTESIAN_POINT('',(-0.218403932885,1.11790129499)); -#79523 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); -#79524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79525 = PCURVE('',#76210,#79526); -#79526 = DEFINITIONAL_REPRESENTATION('',(#79527),#79553); -#79527 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79528,#79529,#79530,#79531, - #79532,#79533,#79534,#79535,#79536,#79537,#79538,#79539,#79540, - #79541,#79542,#79543,#79544,#79545,#79546,#79547,#79548,#79549, - #79550,#79551,#79552),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81912 = CARTESIAN_POINT('',(-0.268933528243,1.127659054385)); +#81913 = CARTESIAN_POINT('',(-0.242415953973,1.127659054385)); +#81914 = CARTESIAN_POINT('',(-0.218403932885,1.11790129499)); +#81915 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); +#81916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81917 = PCURVE('',#78602,#81918); +#81918 = DEFINITIONAL_REPRESENTATION('',(#81919),#81945); +#81919 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81920,#81921,#81922,#81923, + #81924,#81925,#81926,#81927,#81928,#81929,#81930,#81931,#81932, + #81933,#81934,#81935,#81936,#81937,#81938,#81939,#81940,#81941, + #81942,#81943,#81944),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -98584,61 +101573,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#79528 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#79529 = CARTESIAN_POINT('',(0.740753697746,-2.901324288341E-008)); -#79530 = CARTESIAN_POINT('',(0.718425611961,2.616756246965E-005)); -#79531 = CARTESIAN_POINT('',(0.684727524261,1.282673134864E-004)); -#79532 = CARTESIAN_POINT('',(0.650847765387,2.772530388755E-004)); -#79533 = CARTESIAN_POINT('',(0.616809612353,4.570658043114E-004)); -#79534 = CARTESIAN_POINT('',(0.582635599926,6.520952931831E-004)); -#79535 = CARTESIAN_POINT('',(0.548347414424,8.475624467404E-004)); -#79536 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); -#79537 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); -#79538 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); -#79539 = CARTESIAN_POINT('',(0.41045949854,1.390009812357E-003)); -#79540 = CARTESIAN_POINT('',(0.375899653916,1.422641316493E-003)); -#79541 = CARTESIAN_POINT('',(0.341341416362,1.405524714323E-003)); -#79542 = CARTESIAN_POINT('',(0.306802773621,1.339263477877E-003)); -#79543 = CARTESIAN_POINT('',(0.272301764008,1.227390254469E-003)); -#79544 = CARTESIAN_POINT('',(0.237856655052,1.076339414E-003)); -#79545 = CARTESIAN_POINT('',(0.203486118557,8.95338763721E-004)); -#79546 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); -#79547 = CARTESIAN_POINT('',(0.135046437107,4.931498468535E-004)); -#79548 = CARTESIAN_POINT('',(0.101018031154,3.022859269914E-004)); -#79549 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577579E-004)); -#79550 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009729E-005)); -#79551 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318323614E-008)); -#79552 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#79553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79554 = ORIENTED_EDGE('',*,*,#76105,.T.); -#79555 = ADVANCED_FACE('',(#79556),#78741,.T.); -#79556 = FACE_BOUND('',#79557,.T.); -#79557 = EDGE_LOOP('',(#79558,#79601,#79646,#79666)); -#79558 = ORIENTED_EDGE('',*,*,#79559,.T.); -#79559 = EDGE_CURVE('',#78683,#77511,#79560,.T.); -#79560 = SURFACE_CURVE('',#79561,(#79565,#79572),.PCURVE_S1.); -#79561 = LINE('',#79562,#79563); -#79562 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, +#81920 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#81921 = CARTESIAN_POINT('',(0.740753697746,-2.901324288341E-008)); +#81922 = CARTESIAN_POINT('',(0.718425611961,2.616756246965E-005)); +#81923 = CARTESIAN_POINT('',(0.684727524261,1.282673134864E-004)); +#81924 = CARTESIAN_POINT('',(0.650847765387,2.772530388755E-004)); +#81925 = CARTESIAN_POINT('',(0.616809612353,4.570658043114E-004)); +#81926 = CARTESIAN_POINT('',(0.582635599926,6.520952931831E-004)); +#81927 = CARTESIAN_POINT('',(0.548347414424,8.475624467404E-004)); +#81928 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); +#81929 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); +#81930 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); +#81931 = CARTESIAN_POINT('',(0.41045949854,1.390009812357E-003)); +#81932 = CARTESIAN_POINT('',(0.375899653916,1.422641316493E-003)); +#81933 = CARTESIAN_POINT('',(0.341341416362,1.405524714323E-003)); +#81934 = CARTESIAN_POINT('',(0.306802773621,1.339263477877E-003)); +#81935 = CARTESIAN_POINT('',(0.272301764008,1.227390254469E-003)); +#81936 = CARTESIAN_POINT('',(0.237856655052,1.076339414E-003)); +#81937 = CARTESIAN_POINT('',(0.203486118557,8.95338763721E-004)); +#81938 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); +#81939 = CARTESIAN_POINT('',(0.135046437107,4.931498468535E-004)); +#81940 = CARTESIAN_POINT('',(0.101018031154,3.022859269914E-004)); +#81941 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577579E-004)); +#81942 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009729E-005)); +#81943 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318323614E-008)); +#81944 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#81945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81946 = ORIENTED_EDGE('',*,*,#78497,.T.); +#81947 = ADVANCED_FACE('',(#81948),#81133,.T.); +#81948 = FACE_BOUND('',#81949,.T.); +#81949 = EDGE_LOOP('',(#81950,#81993,#82038,#82058)); +#81950 = ORIENTED_EDGE('',*,*,#81951,.T.); +#81951 = EDGE_CURVE('',#81075,#79903,#81952,.T.); +#81952 = SURFACE_CURVE('',#81953,(#81957,#81964),.PCURVE_S1.); +#81953 = LINE('',#81954,#81955); +#81954 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, 0.566051874704)); -#79563 = VECTOR('',#79564,1.); -#79564 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); -#79565 = PCURVE('',#78741,#79566); -#79566 = DEFINITIONAL_REPRESENTATION('',(#79567),#79571); -#79567 = LINE('',#79568,#79569); -#79568 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#79569 = VECTOR('',#79570,1.); -#79570 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#79571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79572 = PCURVE('',#77566,#79573); -#79573 = DEFINITIONAL_REPRESENTATION('',(#79574),#79600); -#79574 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79575,#79576,#79577,#79578, - #79579,#79580,#79581,#79582,#79583,#79584,#79585,#79586,#79587, - #79588,#79589,#79590,#79591,#79592,#79593,#79594,#79595,#79596, - #79597,#79598,#79599),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#81955 = VECTOR('',#81956,1.); +#81956 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531)); +#81957 = PCURVE('',#81133,#81958); +#81958 = DEFINITIONAL_REPRESENTATION('',(#81959),#81963); +#81959 = LINE('',#81960,#81961); +#81960 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#81961 = VECTOR('',#81962,1.); +#81962 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#81963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81964 = PCURVE('',#79958,#81965); +#81965 = DEFINITIONAL_REPRESENTATION('',(#81966),#81992); +#81966 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81967,#81968,#81969,#81970, + #81971,#81972,#81973,#81974,#81975,#81976,#81977,#81978,#81979, + #81980,#81981,#81982,#81983,#81984,#81985,#81986,#81987,#81988, + #81989,#81990,#81991),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.630376297074E-002,5.394581668973E-002, 7.158787040873E-002,8.922992412772E-002,0.106871977847, 0.124514031566,0.142156085285,0.159798139004,0.177440192723, @@ -98646,60 +101635,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.265650461318,0.283292515037,0.300934568756,0.318576622475, 0.336218676194,0.353860729913,0.371502783632,0.389144837351, 0.40678689107,0.424428944789),.QUASI_UNIFORM_KNOTS.); -#79575 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); -#79576 = CARTESIAN_POINT('',(3.14159265359,0.689458949147)); -#79577 = CARTESIAN_POINT('',(3.14159265359,0.677697580001)); -#79578 = CARTESIAN_POINT('',(3.14159265359,0.660055526282)); -#79579 = CARTESIAN_POINT('',(3.14159265359,0.642413472563)); -#79580 = CARTESIAN_POINT('',(3.14159265359,0.624771418844)); -#79581 = CARTESIAN_POINT('',(3.14159265359,0.607129365125)); -#79582 = CARTESIAN_POINT('',(3.14159265359,0.589487311406)); -#79583 = CARTESIAN_POINT('',(3.14159265359,0.571845257687)); -#79584 = CARTESIAN_POINT('',(3.14159265359,0.554203203968)); -#79585 = CARTESIAN_POINT('',(3.14159265359,0.536561150249)); -#79586 = CARTESIAN_POINT('',(3.14159265359,0.51891909653)); -#79587 = CARTESIAN_POINT('',(3.14159265359,0.501277042811)); -#79588 = CARTESIAN_POINT('',(3.14159265359,0.483634989092)); -#79589 = CARTESIAN_POINT('',(3.14159265359,0.465992935373)); -#79590 = CARTESIAN_POINT('',(3.14159265359,0.448350881654)); -#79591 = CARTESIAN_POINT('',(3.14159265359,0.430708827935)); -#79592 = CARTESIAN_POINT('',(3.14159265359,0.413066774216)); -#79593 = CARTESIAN_POINT('',(3.14159265359,0.395424720497)); -#79594 = CARTESIAN_POINT('',(3.14159265359,0.377782666778)); -#79595 = CARTESIAN_POINT('',(3.14159265359,0.360140613059)); -#79596 = CARTESIAN_POINT('',(3.14159265359,0.34249855934)); -#79597 = CARTESIAN_POINT('',(3.14159265359,0.324856505621)); -#79598 = CARTESIAN_POINT('',(3.14159265359,0.313095136475)); -#79599 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); -#79600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79601 = ORIENTED_EDGE('',*,*,#79602,.T.); -#79602 = EDGE_CURVE('',#77511,#79603,#79605,.T.); -#79603 = VERTEX_POINT('',#79604); -#79604 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) - ); -#79605 = SURFACE_CURVE('',#79606,(#79610,#79617),.PCURVE_S1.); -#79606 = LINE('',#79607,#79608); -#79607 = CARTESIAN_POINT('',(1.362750264943,-0.397931449084, +#81967 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); +#81968 = CARTESIAN_POINT('',(3.14159265359,0.689458949147)); +#81969 = CARTESIAN_POINT('',(3.14159265359,0.677697580001)); +#81970 = CARTESIAN_POINT('',(3.14159265359,0.660055526282)); +#81971 = CARTESIAN_POINT('',(3.14159265359,0.642413472563)); +#81972 = CARTESIAN_POINT('',(3.14159265359,0.624771418844)); +#81973 = CARTESIAN_POINT('',(3.14159265359,0.607129365125)); +#81974 = CARTESIAN_POINT('',(3.14159265359,0.589487311406)); +#81975 = CARTESIAN_POINT('',(3.14159265359,0.571845257687)); +#81976 = CARTESIAN_POINT('',(3.14159265359,0.554203203968)); +#81977 = CARTESIAN_POINT('',(3.14159265359,0.536561150249)); +#81978 = CARTESIAN_POINT('',(3.14159265359,0.51891909653)); +#81979 = CARTESIAN_POINT('',(3.14159265359,0.501277042811)); +#81980 = CARTESIAN_POINT('',(3.14159265359,0.483634989092)); +#81981 = CARTESIAN_POINT('',(3.14159265359,0.465992935373)); +#81982 = CARTESIAN_POINT('',(3.14159265359,0.448350881654)); +#81983 = CARTESIAN_POINT('',(3.14159265359,0.430708827935)); +#81984 = CARTESIAN_POINT('',(3.14159265359,0.413066774216)); +#81985 = CARTESIAN_POINT('',(3.14159265359,0.395424720497)); +#81986 = CARTESIAN_POINT('',(3.14159265359,0.377782666778)); +#81987 = CARTESIAN_POINT('',(3.14159265359,0.360140613059)); +#81988 = CARTESIAN_POINT('',(3.14159265359,0.34249855934)); +#81989 = CARTESIAN_POINT('',(3.14159265359,0.324856505621)); +#81990 = CARTESIAN_POINT('',(3.14159265359,0.313095136475)); +#81991 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); +#81992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#81993 = ORIENTED_EDGE('',*,*,#81994,.T.); +#81994 = EDGE_CURVE('',#79903,#81995,#81997,.T.); +#81995 = VERTEX_POINT('',#81996); +#81996 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) + ); +#81997 = SURFACE_CURVE('',#81998,(#82002,#82009),.PCURVE_S1.); +#81998 = LINE('',#81999,#82000); +#81999 = CARTESIAN_POINT('',(1.362750264943,-0.397931449084, 0.962940952255)); -#79608 = VECTOR('',#79609,1.); -#79609 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); -#79610 = PCURVE('',#78741,#79611); -#79611 = DEFINITIONAL_REPRESENTATION('',(#79612),#79616); -#79612 = LINE('',#79613,#79614); -#79613 = CARTESIAN_POINT('',(-0.375744122765,-1.047931449084)); -#79614 = VECTOR('',#79615,1.); -#79615 = DIRECTION('',(4.317110322781E-017,-1.)); -#79616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79617 = PCURVE('',#77769,#79618); -#79618 = DEFINITIONAL_REPRESENTATION('',(#79619),#79645); -#79619 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79620,#79621,#79622,#79623, - #79624,#79625,#79626,#79627,#79628,#79629,#79630,#79631,#79632, - #79633,#79634,#79635,#79636,#79637,#79638,#79639,#79640,#79641, - #79642,#79643,#79644),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82000 = VECTOR('',#82001,1.); +#82001 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); +#82002 = PCURVE('',#81133,#82003); +#82003 = DEFINITIONAL_REPRESENTATION('',(#82004),#82008); +#82004 = LINE('',#82005,#82006); +#82005 = CARTESIAN_POINT('',(-0.375744122765,-1.047931449084)); +#82006 = VECTOR('',#82007,1.); +#82007 = DIRECTION('',(4.317110322781E-017,-1.)); +#82008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82009 = PCURVE('',#80161,#82010); +#82010 = DEFINITIONAL_REPRESENTATION('',(#82011),#82037); +#82011 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82012,#82013,#82014,#82015, + #82016,#82017,#82018,#82019,#82020,#82021,#82022,#82023,#82024, + #82025,#82026,#82027,#82028,#82029,#82030,#82031,#82032,#82033, + #82034,#82035,#82036),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084,-0.768714531811, -0.731636223538,-0.694557915266,-0.657479606993,-0.62040129872, -0.583322990448,-0.546244682175,-0.509166373902,-0.47208806563, @@ -98707,88 +101696,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.286696524266,-0.249618215993,-0.212539907721,-0.175461599448, -0.138383291175,-0.101304982903,-6.422667462989E-002, -2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#79620 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); -#79621 = CARTESIAN_POINT('',(2.879793265791,1.045501954909)); -#79622 = CARTESIAN_POINT('',(2.879793265791,1.020783082727)); -#79623 = CARTESIAN_POINT('',(2.879793265791,0.983704774454)); -#79624 = CARTESIAN_POINT('',(2.879793265791,0.946626466182)); -#79625 = CARTESIAN_POINT('',(2.879793265791,0.909548157909)); -#79626 = CARTESIAN_POINT('',(2.879793265791,0.872469849636)); -#79627 = CARTESIAN_POINT('',(2.879793265791,0.835391541363)); -#79628 = CARTESIAN_POINT('',(2.879793265791,0.798313233091)); -#79629 = CARTESIAN_POINT('',(2.879793265791,0.761234924818)); -#79630 = CARTESIAN_POINT('',(2.879793265791,0.724156616545)); -#79631 = CARTESIAN_POINT('',(2.879793265791,0.687078308273)); -#79632 = CARTESIAN_POINT('',(2.879793265791,0.65)); -#79633 = CARTESIAN_POINT('',(2.879793265791,0.612921691727)); -#79634 = CARTESIAN_POINT('',(2.879793265791,0.575843383455)); -#79635 = CARTESIAN_POINT('',(2.879793265791,0.538765075182)); -#79636 = CARTESIAN_POINT('',(2.879793265791,0.501686766909)); -#79637 = CARTESIAN_POINT('',(2.879793265791,0.464608458637)); -#79638 = CARTESIAN_POINT('',(2.879793265791,0.427530150364)); -#79639 = CARTESIAN_POINT('',(2.879793265791,0.390451842091)); -#79640 = CARTESIAN_POINT('',(2.879793265791,0.353373533818)); -#79641 = CARTESIAN_POINT('',(2.879793265791,0.316295225546)); -#79642 = CARTESIAN_POINT('',(2.879793265791,0.279216917273)); -#79643 = CARTESIAN_POINT('',(2.879793265791,0.254498045091)); -#79644 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); -#79645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79646 = ORIENTED_EDGE('',*,*,#79647,.T.); -#79647 = EDGE_CURVE('',#79603,#78588,#79648,.T.); -#79648 = SURFACE_CURVE('',#79649,(#79653,#79660),.PCURVE_S1.); -#79649 = LINE('',#79650,#79651); -#79650 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, +#82012 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); +#82013 = CARTESIAN_POINT('',(2.879793265791,1.045501954909)); +#82014 = CARTESIAN_POINT('',(2.879793265791,1.020783082727)); +#82015 = CARTESIAN_POINT('',(2.879793265791,0.983704774454)); +#82016 = CARTESIAN_POINT('',(2.879793265791,0.946626466182)); +#82017 = CARTESIAN_POINT('',(2.879793265791,0.909548157909)); +#82018 = CARTESIAN_POINT('',(2.879793265791,0.872469849636)); +#82019 = CARTESIAN_POINT('',(2.879793265791,0.835391541363)); +#82020 = CARTESIAN_POINT('',(2.879793265791,0.798313233091)); +#82021 = CARTESIAN_POINT('',(2.879793265791,0.761234924818)); +#82022 = CARTESIAN_POINT('',(2.879793265791,0.724156616545)); +#82023 = CARTESIAN_POINT('',(2.879793265791,0.687078308273)); +#82024 = CARTESIAN_POINT('',(2.879793265791,0.65)); +#82025 = CARTESIAN_POINT('',(2.879793265791,0.612921691727)); +#82026 = CARTESIAN_POINT('',(2.879793265791,0.575843383455)); +#82027 = CARTESIAN_POINT('',(2.879793265791,0.538765075182)); +#82028 = CARTESIAN_POINT('',(2.879793265791,0.501686766909)); +#82029 = CARTESIAN_POINT('',(2.879793265791,0.464608458637)); +#82030 = CARTESIAN_POINT('',(2.879793265791,0.427530150364)); +#82031 = CARTESIAN_POINT('',(2.879793265791,0.390451842091)); +#82032 = CARTESIAN_POINT('',(2.879793265791,0.353373533818)); +#82033 = CARTESIAN_POINT('',(2.879793265791,0.316295225546)); +#82034 = CARTESIAN_POINT('',(2.879793265791,0.279216917273)); +#82035 = CARTESIAN_POINT('',(2.879793265791,0.254498045091)); +#82036 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); +#82037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82038 = ORIENTED_EDGE('',*,*,#82039,.T.); +#82039 = EDGE_CURVE('',#81995,#80980,#82040,.T.); +#82040 = SURFACE_CURVE('',#82041,(#82045,#82052),.PCURVE_S1.); +#82041 = LINE('',#82042,#82043); +#82042 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, 0.870647815608)); -#79651 = VECTOR('',#79652,1.); -#79652 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); -#79653 = PCURVE('',#78741,#79654); -#79654 = DEFINITIONAL_REPRESENTATION('',(#79655),#79659); -#79655 = LINE('',#79656,#79657); -#79656 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); -#79657 = VECTOR('',#79658,1.); -#79658 = DIRECTION('',(0.968100345886,-0.250562807086)); -#79659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79660 = PCURVE('',#77016,#79661); -#79661 = DEFINITIONAL_REPRESENTATION('',(#79662),#79665); -#79662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79663,#79664),.UNSPECIFIED., +#82043 = VECTOR('',#82044,1.); +#82044 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531)); +#82045 = PCURVE('',#81133,#82046); +#82046 = DEFINITIONAL_REPRESENTATION('',(#82047),#82051); +#82047 = LINE('',#82048,#82049); +#82048 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); +#82049 = VECTOR('',#82050,1.); +#82050 = DIRECTION('',(0.968100345886,-0.250562807086)); +#82051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82052 = PCURVE('',#79408,#82053); +#82053 = DEFINITIONAL_REPRESENTATION('',(#82054),#82057); +#82054 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82055,#82056),.UNSPECIFIED., .F.,.F.,(2,2),(-9.869729557715E-002,0.289427886241), .PIECEWISE_BEZIER_KNOTS.); -#79663 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); -#79664 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#79665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#82055 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); +#82056 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#82057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#79666 = ORIENTED_EDGE('',*,*,#78727,.T.); -#79667 = ADVANCED_FACE('',(#79668),#79053,.T.); -#79668 = FACE_BOUND('',#79669,.T.); -#79669 = EDGE_LOOP('',(#79670,#79713,#79758,#79801)); -#79670 = ORIENTED_EDGE('',*,*,#79671,.T.); -#79671 = EDGE_CURVE('',#78995,#76658,#79672,.T.); -#79672 = SURFACE_CURVE('',#79673,(#79677,#79684),.PCURVE_S1.); -#79673 = LINE('',#79674,#79675); -#79674 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, +#82058 = ORIENTED_EDGE('',*,*,#81119,.T.); +#82059 = ADVANCED_FACE('',(#82060),#81445,.T.); +#82060 = FACE_BOUND('',#82061,.T.); +#82061 = EDGE_LOOP('',(#82062,#82105,#82150,#82193)); +#82062 = ORIENTED_EDGE('',*,*,#82063,.T.); +#82063 = EDGE_CURVE('',#81387,#79050,#82064,.T.); +#82064 = SURFACE_CURVE('',#82065,(#82069,#82076),.PCURVE_S1.); +#82065 = LINE('',#82066,#82067); +#82066 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, 0.870647815608)); -#79675 = VECTOR('',#79676,1.); -#79676 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#79677 = PCURVE('',#79053,#79678); -#79678 = DEFINITIONAL_REPRESENTATION('',(#79679),#79683); -#79679 = LINE('',#79680,#79681); -#79680 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); -#79681 = VECTOR('',#79682,1.); -#79682 = DIRECTION('',(0.968100345886,0.250562807086)); -#79683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79684 = PCURVE('',#76713,#79685); -#79685 = DEFINITIONAL_REPRESENTATION('',(#79686),#79712); -#79686 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79687,#79688,#79689,#79690, - #79691,#79692,#79693,#79694,#79695,#79696,#79697,#79698,#79699, - #79700,#79701,#79702,#79703,#79704,#79705,#79706,#79707,#79708, - #79709,#79710,#79711),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82067 = VECTOR('',#82068,1.); +#82068 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#82069 = PCURVE('',#81445,#82070); +#82070 = DEFINITIONAL_REPRESENTATION('',(#82071),#82075); +#82071 = LINE('',#82072,#82073); +#82072 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); +#82073 = VECTOR('',#82074,1.); +#82074 = DIRECTION('',(0.968100345886,0.250562807086)); +#82075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82076 = PCURVE('',#79105,#82077); +#82077 = DEFINITIONAL_REPRESENTATION('',(#82078),#82104); +#82078 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82079,#82080,#82081,#82082, + #82083,#82084,#82085,#82086,#82087,#82088,#82089,#82090,#82091, + #82092,#82093,#82094,#82095,#82096,#82097,#82098,#82099,#82100, + #82101,#82102,#82103),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.289427886241,-0.271785832522, -0.254143778803,-0.236501725084,-0.218859671365,-0.201217617646, -0.183575563927,-0.165933510208,-0.148291456489,-0.13064940277, @@ -98797,60 +101786,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -7.155026736812E-003,1.048702698218E-002,2.812908070118E-002, 4.577113442017E-002,6.341318813916E-002,8.105524185816E-002, 9.869729557715E-002),.UNSPECIFIED.); -#79687 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#79688 = CARTESIAN_POINT('',(6.28318530718,-4.218444754374E-002)); -#79689 = CARTESIAN_POINT('',(6.28318530718,-5.394581668973E-002)); -#79690 = CARTESIAN_POINT('',(6.28318530718,-7.158787040873E-002)); -#79691 = CARTESIAN_POINT('',(6.28318530718,-8.922992412772E-002)); -#79692 = CARTESIAN_POINT('',(6.28318530718,-0.106871977847)); -#79693 = CARTESIAN_POINT('',(6.28318530718,-0.124514031566)); -#79694 = CARTESIAN_POINT('',(6.28318530718,-0.142156085285)); -#79695 = CARTESIAN_POINT('',(6.28318530718,-0.159798139004)); -#79696 = CARTESIAN_POINT('',(6.28318530718,-0.177440192723)); -#79697 = CARTESIAN_POINT('',(6.28318530718,-0.195082246442)); -#79698 = CARTESIAN_POINT('',(6.28318530718,-0.212724300161)); -#79699 = CARTESIAN_POINT('',(6.28318530718,-0.23036635388)); -#79700 = CARTESIAN_POINT('',(6.28318530718,-0.248008407599)); -#79701 = CARTESIAN_POINT('',(6.28318530718,-0.265650461318)); -#79702 = CARTESIAN_POINT('',(6.28318530718,-0.283292515037)); -#79703 = CARTESIAN_POINT('',(6.28318530718,-0.300934568756)); -#79704 = CARTESIAN_POINT('',(6.28318530718,-0.318576622475)); -#79705 = CARTESIAN_POINT('',(6.28318530718,-0.336218676194)); -#79706 = CARTESIAN_POINT('',(6.28318530718,-0.353860729913)); -#79707 = CARTESIAN_POINT('',(6.28318530718,-0.371502783632)); -#79708 = CARTESIAN_POINT('',(6.28318530718,-0.389144837351)); -#79709 = CARTESIAN_POINT('',(6.28318530718,-0.40678689107)); -#79710 = CARTESIAN_POINT('',(6.28318530718,-0.418548260216)); -#79711 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); -#79712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79713 = ORIENTED_EDGE('',*,*,#79714,.T.); -#79714 = EDGE_CURVE('',#76658,#79715,#79717,.T.); -#79715 = VERTEX_POINT('',#79716); -#79716 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) - ); -#79717 = SURFACE_CURVE('',#79718,(#79722,#79729),.PCURVE_S1.); -#79718 = LINE('',#79719,#79720); -#79719 = CARTESIAN_POINT('',(-1.362750264943,0.397931449084, +#82079 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#82080 = CARTESIAN_POINT('',(6.28318530718,-4.218444754374E-002)); +#82081 = CARTESIAN_POINT('',(6.28318530718,-5.394581668973E-002)); +#82082 = CARTESIAN_POINT('',(6.28318530718,-7.158787040873E-002)); +#82083 = CARTESIAN_POINT('',(6.28318530718,-8.922992412772E-002)); +#82084 = CARTESIAN_POINT('',(6.28318530718,-0.106871977847)); +#82085 = CARTESIAN_POINT('',(6.28318530718,-0.124514031566)); +#82086 = CARTESIAN_POINT('',(6.28318530718,-0.142156085285)); +#82087 = CARTESIAN_POINT('',(6.28318530718,-0.159798139004)); +#82088 = CARTESIAN_POINT('',(6.28318530718,-0.177440192723)); +#82089 = CARTESIAN_POINT('',(6.28318530718,-0.195082246442)); +#82090 = CARTESIAN_POINT('',(6.28318530718,-0.212724300161)); +#82091 = CARTESIAN_POINT('',(6.28318530718,-0.23036635388)); +#82092 = CARTESIAN_POINT('',(6.28318530718,-0.248008407599)); +#82093 = CARTESIAN_POINT('',(6.28318530718,-0.265650461318)); +#82094 = CARTESIAN_POINT('',(6.28318530718,-0.283292515037)); +#82095 = CARTESIAN_POINT('',(6.28318530718,-0.300934568756)); +#82096 = CARTESIAN_POINT('',(6.28318530718,-0.318576622475)); +#82097 = CARTESIAN_POINT('',(6.28318530718,-0.336218676194)); +#82098 = CARTESIAN_POINT('',(6.28318530718,-0.353860729913)); +#82099 = CARTESIAN_POINT('',(6.28318530718,-0.371502783632)); +#82100 = CARTESIAN_POINT('',(6.28318530718,-0.389144837351)); +#82101 = CARTESIAN_POINT('',(6.28318530718,-0.40678689107)); +#82102 = CARTESIAN_POINT('',(6.28318530718,-0.418548260216)); +#82103 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); +#82104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82105 = ORIENTED_EDGE('',*,*,#82106,.T.); +#82106 = EDGE_CURVE('',#79050,#82107,#82109,.T.); +#82107 = VERTEX_POINT('',#82108); +#82108 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) + ); +#82109 = SURFACE_CURVE('',#82110,(#82114,#82121),.PCURVE_S1.); +#82110 = LINE('',#82111,#82112); +#82111 = CARTESIAN_POINT('',(-1.362750264943,0.397931449084, 0.962940952255)); -#79720 = VECTOR('',#79721,1.); -#79721 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); -#79722 = PCURVE('',#79053,#79723); -#79723 = DEFINITIONAL_REPRESENTATION('',(#79724),#79728); -#79724 = LINE('',#79725,#79726); -#79725 = CARTESIAN_POINT('',(0.375744122765,-0.252068550916)); -#79726 = VECTOR('',#79727,1.); -#79727 = DIRECTION('',(-4.317110322781E-017,1.)); -#79728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79729 = PCURVE('',#76921,#79730); -#79730 = DEFINITIONAL_REPRESENTATION('',(#79731),#79757); -#79731 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79732,#79733,#79734,#79735, - #79736,#79737,#79738,#79739,#79740,#79741,#79742,#79743,#79744, - #79745,#79746,#79747,#79748,#79749,#79750,#79751,#79752,#79753, - #79754,#79755,#79756),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82112 = VECTOR('',#82113,1.); +#82113 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); +#82114 = PCURVE('',#81445,#82115); +#82115 = DEFINITIONAL_REPRESENTATION('',(#82116),#82120); +#82116 = LINE('',#82117,#82118); +#82117 = CARTESIAN_POINT('',(0.375744122765,-0.252068550916)); +#82118 = VECTOR('',#82119,1.); +#82119 = DIRECTION('',(-4.317110322781E-017,1.)); +#82120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82121 = PCURVE('',#79313,#82122); +#82122 = DEFINITIONAL_REPRESENTATION('',(#82123),#82149); +#82123 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82124,#82125,#82126,#82127, + #82128,#82129,#82130,#82131,#82132,#82133,#82134,#82135,#82136, + #82137,#82138,#82139,#82140,#82141,#82142,#82143,#82144,#82145, + #82146,#82147,#82148),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084,-0.768714531811, -0.731636223538,-0.694557915266,-0.657479606993,-0.62040129872, -0.583322990448,-0.546244682175,-0.509166373902,-0.47208806563, @@ -98858,57 +101847,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.286696524266,-0.249618215993,-0.212539907721,-0.175461599448, -0.138383291175,-0.101304982903,-6.422667462989E-002, -2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#79732 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); -#79733 = CARTESIAN_POINT('',(2.879793265791,-0.254498045091)); -#79734 = CARTESIAN_POINT('',(2.879793265791,-0.279216917273)); -#79735 = CARTESIAN_POINT('',(2.879793265791,-0.316295225546)); -#79736 = CARTESIAN_POINT('',(2.879793265791,-0.353373533818)); -#79737 = CARTESIAN_POINT('',(2.879793265791,-0.390451842091)); -#79738 = CARTESIAN_POINT('',(2.879793265791,-0.427530150364)); -#79739 = CARTESIAN_POINT('',(2.879793265791,-0.464608458637)); -#79740 = CARTESIAN_POINT('',(2.879793265791,-0.501686766909)); -#79741 = CARTESIAN_POINT('',(2.879793265791,-0.538765075182)); -#79742 = CARTESIAN_POINT('',(2.879793265791,-0.575843383455)); -#79743 = CARTESIAN_POINT('',(2.879793265791,-0.612921691727)); -#79744 = CARTESIAN_POINT('',(2.879793265791,-0.65)); -#79745 = CARTESIAN_POINT('',(2.879793265791,-0.687078308273)); -#79746 = CARTESIAN_POINT('',(2.879793265791,-0.724156616545)); -#79747 = CARTESIAN_POINT('',(2.879793265791,-0.761234924818)); -#79748 = CARTESIAN_POINT('',(2.879793265791,-0.798313233091)); -#79749 = CARTESIAN_POINT('',(2.879793265791,-0.835391541363)); -#79750 = CARTESIAN_POINT('',(2.879793265791,-0.872469849636)); -#79751 = CARTESIAN_POINT('',(2.879793265791,-0.909548157909)); -#79752 = CARTESIAN_POINT('',(2.879793265791,-0.946626466182)); -#79753 = CARTESIAN_POINT('',(2.879793265791,-0.983704774454)); -#79754 = CARTESIAN_POINT('',(2.879793265791,-1.020783082727)); -#79755 = CARTESIAN_POINT('',(2.879793265791,-1.045501954909)); -#79756 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); -#79757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79758 = ORIENTED_EDGE('',*,*,#79759,.T.); -#79759 = EDGE_CURVE('',#79715,#78923,#79760,.T.); -#79760 = SURFACE_CURVE('',#79761,(#79765,#79772),.PCURVE_S1.); -#79761 = LINE('',#79762,#79763); -#79762 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, +#82124 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); +#82125 = CARTESIAN_POINT('',(2.879793265791,-0.254498045091)); +#82126 = CARTESIAN_POINT('',(2.879793265791,-0.279216917273)); +#82127 = CARTESIAN_POINT('',(2.879793265791,-0.316295225546)); +#82128 = CARTESIAN_POINT('',(2.879793265791,-0.353373533818)); +#82129 = CARTESIAN_POINT('',(2.879793265791,-0.390451842091)); +#82130 = CARTESIAN_POINT('',(2.879793265791,-0.427530150364)); +#82131 = CARTESIAN_POINT('',(2.879793265791,-0.464608458637)); +#82132 = CARTESIAN_POINT('',(2.879793265791,-0.501686766909)); +#82133 = CARTESIAN_POINT('',(2.879793265791,-0.538765075182)); +#82134 = CARTESIAN_POINT('',(2.879793265791,-0.575843383455)); +#82135 = CARTESIAN_POINT('',(2.879793265791,-0.612921691727)); +#82136 = CARTESIAN_POINT('',(2.879793265791,-0.65)); +#82137 = CARTESIAN_POINT('',(2.879793265791,-0.687078308273)); +#82138 = CARTESIAN_POINT('',(2.879793265791,-0.724156616545)); +#82139 = CARTESIAN_POINT('',(2.879793265791,-0.761234924818)); +#82140 = CARTESIAN_POINT('',(2.879793265791,-0.798313233091)); +#82141 = CARTESIAN_POINT('',(2.879793265791,-0.835391541363)); +#82142 = CARTESIAN_POINT('',(2.879793265791,-0.872469849636)); +#82143 = CARTESIAN_POINT('',(2.879793265791,-0.909548157909)); +#82144 = CARTESIAN_POINT('',(2.879793265791,-0.946626466182)); +#82145 = CARTESIAN_POINT('',(2.879793265791,-0.983704774454)); +#82146 = CARTESIAN_POINT('',(2.879793265791,-1.020783082727)); +#82147 = CARTESIAN_POINT('',(2.879793265791,-1.045501954909)); +#82148 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); +#82149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82150 = ORIENTED_EDGE('',*,*,#82151,.T.); +#82151 = EDGE_CURVE('',#82107,#81315,#82152,.T.); +#82152 = SURFACE_CURVE('',#82153,(#82157,#82164),.PCURVE_S1.); +#82153 = LINE('',#82154,#82155); +#82154 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, 0.566051874704)); -#79763 = VECTOR('',#79764,1.); -#79764 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); -#79765 = PCURVE('',#79053,#79766); -#79766 = DEFINITIONAL_REPRESENTATION('',(#79767),#79771); -#79767 = LINE('',#79768,#79769); -#79768 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#79769 = VECTOR('',#79770,1.); -#79770 = DIRECTION('',(-0.968100345886,0.250562807086)); -#79771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79772 = PCURVE('',#77291,#79773); -#79773 = DEFINITIONAL_REPRESENTATION('',(#79774),#79800); -#79774 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79775,#79776,#79777,#79778, - #79779,#79780,#79781,#79782,#79783,#79784,#79785,#79786,#79787, - #79788,#79789,#79790,#79791,#79792,#79793,#79794,#79795,#79796, - #79797,#79798,#79799),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82155 = VECTOR('',#82156,1.); +#82156 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531)); +#82157 = PCURVE('',#81445,#82158); +#82158 = DEFINITIONAL_REPRESENTATION('',(#82159),#82163); +#82159 = LINE('',#82160,#82161); +#82160 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#82161 = VECTOR('',#82162,1.); +#82162 = DIRECTION('',(-0.968100345886,0.250562807086)); +#82163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82164 = PCURVE('',#79683,#82165); +#82165 = DEFINITIONAL_REPRESENTATION('',(#82166),#82192); +#82166 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82167,#82168,#82169,#82170, + #82171,#82172,#82173,#82174,#82175,#82176,#82177,#82178,#82179, + #82180,#82181,#82182,#82183,#82184,#82185,#82186,#82187,#82188, + #82189,#82190,#82191),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.424428944789,-0.40678689107, -0.389144837351,-0.371502783632,-0.353860729913,-0.336218676194, -0.318576622475,-0.300934568756,-0.283292515037,-0.265650461318, @@ -98916,63 +101905,63 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.177440192723,-0.159798139004,-0.142156085285,-0.124514031566, -0.106871977847,-8.922992412772E-002,-7.158787040873E-002, -5.394581668973E-002,-3.630376297074E-002),.UNSPECIFIED.); -#79775 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); -#79776 = CARTESIAN_POINT('',(8.223874256483E-016,-0.418548260216)); -#79777 = CARTESIAN_POINT('',(1.072145602316E-015,-0.40678689107)); -#79778 = CARTESIAN_POINT('',(-5.451986480786E-016,-0.389144837351)); -#79779 = CARTESIAN_POINT('',(1.108648989998E-015,-0.371502783632)); -#79780 = CARTESIAN_POINT('',(5.514947865868E-016,-0.353860729913)); -#79781 = CARTESIAN_POINT('',(1.126263962155E-015,-0.336218676194)); -#79782 = CARTESIAN_POINT('',(-6.15658536707E-016,-0.318576622475)); -#79783 = CARTESIAN_POINT('',(1.336370184673E-015,-0.300934568756)); -#79784 = CARTESIAN_POINT('',(-2.889301034839E-016,-0.283292515037)); -#79785 = CARTESIAN_POINT('',(-1.806497707372E-016,-0.265650461318)); -#79786 = CARTESIAN_POINT('',(1.011529186433E-015,-0.248008407599)); -#79787 = CARTESIAN_POINT('',(5.754251235075E-016,-0.23036635388)); -#79788 = CARTESIAN_POINT('',(1.127662418038E-015,-0.212724300161)); -#79789 = CARTESIAN_POINT('',(-6.451826971595E-016,-0.195082246442)); -#79790 = CARTESIAN_POINT('',(1.4530683706E-015,-0.177440192723)); -#79791 = CARTESIAN_POINT('',(-7.261986867395E-016,-0.159798139004)); -#79792 = CARTESIAN_POINT('',(1.451726376358E-015,-0.142156085285)); -#79793 = CARTESIAN_POINT('',(-6.398147201925E-016,-0.124514031566)); -#79794 = CARTESIAN_POINT('',(1.107532504412E-015,-0.106871977847)); -#79795 = CARTESIAN_POINT('',(6.505768010463E-016,-8.922992412772E-002)); -#79796 = CARTESIAN_POINT('',(7.310523899038E-016,-7.158787040873E-002)); -#79797 = CARTESIAN_POINT('',(8.661057378391E-016,-5.394581668973E-002)); -#79798 = CARTESIAN_POINT('',(4.523130841065E-016,-4.218444754374E-002)); -#79799 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#79800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79801 = ORIENTED_EDGE('',*,*,#79039,.T.); -#79802 = ADVANCED_FACE('',(#79803),#76871,.T.); -#79803 = FACE_BOUND('',#79804,.T.); -#79804 = EDGE_LOOP('',(#79805,#79850,#79851,#79898,#79918,#79919,#79966, - #80009,#80010,#80057,#80077,#80078)); -#79805 = ORIENTED_EDGE('',*,*,#79806,.T.); -#79806 = EDGE_CURVE('',#79807,#76833,#79809,.T.); -#79807 = VERTEX_POINT('',#79808); -#79808 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#79809 = SURFACE_CURVE('',#79810,(#79814,#79821),.PCURVE_S1.); -#79810 = LINE('',#79811,#79812); -#79811 = CARTESIAN_POINT('',(-1.314453973629,-0.397931449084,1.)); -#79812 = VECTOR('',#79813,1.); -#79813 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#79814 = PCURVE('',#76871,#79815); -#79815 = DEFINITIONAL_REPRESENTATION('',(#79816),#79820); -#79816 = LINE('',#79817,#79818); -#79817 = CARTESIAN_POINT('',(-2.774453973629,0.252068550916)); -#79818 = VECTOR('',#79819,1.); -#79819 = DIRECTION('',(1.668003342285E-016,-1.)); -#79820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79821 = PCURVE('',#76921,#79822); -#79822 = DEFINITIONAL_REPRESENTATION('',(#79823),#79849); -#79823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79824,#79825,#79826,#79827, - #79828,#79829,#79830,#79831,#79832,#79833,#79834,#79835,#79836, - #79837,#79838,#79839,#79840,#79841,#79842,#79843,#79844,#79845, - #79846,#79847,#79848),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82167 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); +#82168 = CARTESIAN_POINT('',(8.223874256483E-016,-0.418548260216)); +#82169 = CARTESIAN_POINT('',(1.072145602316E-015,-0.40678689107)); +#82170 = CARTESIAN_POINT('',(-5.451986480786E-016,-0.389144837351)); +#82171 = CARTESIAN_POINT('',(1.108648989998E-015,-0.371502783632)); +#82172 = CARTESIAN_POINT('',(5.514947865868E-016,-0.353860729913)); +#82173 = CARTESIAN_POINT('',(1.126263962155E-015,-0.336218676194)); +#82174 = CARTESIAN_POINT('',(-6.15658536707E-016,-0.318576622475)); +#82175 = CARTESIAN_POINT('',(1.336370184673E-015,-0.300934568756)); +#82176 = CARTESIAN_POINT('',(-2.889301034839E-016,-0.283292515037)); +#82177 = CARTESIAN_POINT('',(-1.806497707372E-016,-0.265650461318)); +#82178 = CARTESIAN_POINT('',(1.011529186433E-015,-0.248008407599)); +#82179 = CARTESIAN_POINT('',(5.754251235075E-016,-0.23036635388)); +#82180 = CARTESIAN_POINT('',(1.127662418038E-015,-0.212724300161)); +#82181 = CARTESIAN_POINT('',(-6.451826971595E-016,-0.195082246442)); +#82182 = CARTESIAN_POINT('',(1.4530683706E-015,-0.177440192723)); +#82183 = CARTESIAN_POINT('',(-7.261986867395E-016,-0.159798139004)); +#82184 = CARTESIAN_POINT('',(1.451726376358E-015,-0.142156085285)); +#82185 = CARTESIAN_POINT('',(-6.398147201925E-016,-0.124514031566)); +#82186 = CARTESIAN_POINT('',(1.107532504412E-015,-0.106871977847)); +#82187 = CARTESIAN_POINT('',(6.505768010463E-016,-8.922992412772E-002)); +#82188 = CARTESIAN_POINT('',(7.310523899038E-016,-7.158787040873E-002)); +#82189 = CARTESIAN_POINT('',(8.661057378391E-016,-5.394581668973E-002)); +#82190 = CARTESIAN_POINT('',(4.523130841065E-016,-4.218444754374E-002)); +#82191 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#82192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82193 = ORIENTED_EDGE('',*,*,#81431,.T.); +#82194 = ADVANCED_FACE('',(#82195),#79263,.T.); +#82195 = FACE_BOUND('',#82196,.T.); +#82196 = EDGE_LOOP('',(#82197,#82242,#82243,#82290,#82310,#82311,#82358, + #82401,#82402,#82449,#82469,#82470)); +#82197 = ORIENTED_EDGE('',*,*,#82198,.T.); +#82198 = EDGE_CURVE('',#82199,#79225,#82201,.T.); +#82199 = VERTEX_POINT('',#82200); +#82200 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#82201 = SURFACE_CURVE('',#82202,(#82206,#82213),.PCURVE_S1.); +#82202 = LINE('',#82203,#82204); +#82203 = CARTESIAN_POINT('',(-1.314453973629,-0.397931449084,1.)); +#82204 = VECTOR('',#82205,1.); +#82205 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#82206 = PCURVE('',#79263,#82207); +#82207 = DEFINITIONAL_REPRESENTATION('',(#82208),#82212); +#82208 = LINE('',#82209,#82210); +#82209 = CARTESIAN_POINT('',(-2.774453973629,0.252068550916)); +#82210 = VECTOR('',#82211,1.); +#82211 = DIRECTION('',(1.668003342285E-016,-1.)); +#82212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82213 = PCURVE('',#79313,#82214); +#82214 = DEFINITIONAL_REPRESENTATION('',(#82215),#82241); +#82215 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82216,#82217,#82218,#82219, + #82220,#82221,#82222,#82223,#82224,#82225,#82226,#82227,#82228, + #82229,#82230,#82231,#82232,#82233,#82234,#82235,#82236,#82237, + #82238,#82239,#82240),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084,-0.768714531811, -0.731636223538,-0.694557915266,-0.657479606993,-0.62040129872, -0.583322990448,-0.546244682175,-0.509166373902,-0.47208806563, @@ -98980,69 +101969,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.286696524266,-0.249618215993,-0.212539907721,-0.175461599448, -0.138383291175,-0.101304982903,-6.422667462989E-002, -2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#79824 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); -#79825 = CARTESIAN_POINT('',(1.570796326795,-1.045501954909)); -#79826 = CARTESIAN_POINT('',(1.570796326795,-1.020783082727)); -#79827 = CARTESIAN_POINT('',(1.570796326795,-0.983704774454)); -#79828 = CARTESIAN_POINT('',(1.570796326795,-0.946626466182)); -#79829 = CARTESIAN_POINT('',(1.570796326795,-0.909548157909)); -#79830 = CARTESIAN_POINT('',(1.570796326795,-0.872469849636)); -#79831 = CARTESIAN_POINT('',(1.570796326795,-0.835391541363)); -#79832 = CARTESIAN_POINT('',(1.570796326795,-0.798313233091)); -#79833 = CARTESIAN_POINT('',(1.570796326795,-0.761234924818)); -#79834 = CARTESIAN_POINT('',(1.570796326795,-0.724156616545)); -#79835 = CARTESIAN_POINT('',(1.570796326795,-0.687078308273)); -#79836 = CARTESIAN_POINT('',(1.570796326795,-0.65)); -#79837 = CARTESIAN_POINT('',(1.570796326795,-0.612921691727)); -#79838 = CARTESIAN_POINT('',(1.570796326795,-0.575843383455)); -#79839 = CARTESIAN_POINT('',(1.570796326795,-0.538765075182)); -#79840 = CARTESIAN_POINT('',(1.570796326795,-0.501686766909)); -#79841 = CARTESIAN_POINT('',(1.570796326795,-0.464608458637)); -#79842 = CARTESIAN_POINT('',(1.570796326795,-0.427530150364)); -#79843 = CARTESIAN_POINT('',(1.570796326795,-0.390451842091)); -#79844 = CARTESIAN_POINT('',(1.570796326795,-0.353373533818)); -#79845 = CARTESIAN_POINT('',(1.570796326795,-0.316295225546)); -#79846 = CARTESIAN_POINT('',(1.570796326795,-0.279216917273)); -#79847 = CARTESIAN_POINT('',(1.570796326795,-0.254498045091)); -#79848 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); -#79849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79850 = ORIENTED_EDGE('',*,*,#76832,.T.); -#79851 = ORIENTED_EDGE('',*,*,#79852,.T.); -#79852 = EDGE_CURVE('',#76748,#79853,#79855,.T.); -#79853 = VERTEX_POINT('',#79854); -#79854 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#79855 = SURFACE_CURVE('',#79856,(#79861,#79869),.PCURVE_S1.); -#79856 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79857,#79858,#79859,#79860 +#82216 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); +#82217 = CARTESIAN_POINT('',(1.570796326795,-1.045501954909)); +#82218 = CARTESIAN_POINT('',(1.570796326795,-1.020783082727)); +#82219 = CARTESIAN_POINT('',(1.570796326795,-0.983704774454)); +#82220 = CARTESIAN_POINT('',(1.570796326795,-0.946626466182)); +#82221 = CARTESIAN_POINT('',(1.570796326795,-0.909548157909)); +#82222 = CARTESIAN_POINT('',(1.570796326795,-0.872469849636)); +#82223 = CARTESIAN_POINT('',(1.570796326795,-0.835391541363)); +#82224 = CARTESIAN_POINT('',(1.570796326795,-0.798313233091)); +#82225 = CARTESIAN_POINT('',(1.570796326795,-0.761234924818)); +#82226 = CARTESIAN_POINT('',(1.570796326795,-0.724156616545)); +#82227 = CARTESIAN_POINT('',(1.570796326795,-0.687078308273)); +#82228 = CARTESIAN_POINT('',(1.570796326795,-0.65)); +#82229 = CARTESIAN_POINT('',(1.570796326795,-0.612921691727)); +#82230 = CARTESIAN_POINT('',(1.570796326795,-0.575843383455)); +#82231 = CARTESIAN_POINT('',(1.570796326795,-0.538765075182)); +#82232 = CARTESIAN_POINT('',(1.570796326795,-0.501686766909)); +#82233 = CARTESIAN_POINT('',(1.570796326795,-0.464608458637)); +#82234 = CARTESIAN_POINT('',(1.570796326795,-0.427530150364)); +#82235 = CARTESIAN_POINT('',(1.570796326795,-0.390451842091)); +#82236 = CARTESIAN_POINT('',(1.570796326795,-0.353373533818)); +#82237 = CARTESIAN_POINT('',(1.570796326795,-0.316295225546)); +#82238 = CARTESIAN_POINT('',(1.570796326795,-0.279216917273)); +#82239 = CARTESIAN_POINT('',(1.570796326795,-0.254498045091)); +#82240 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); +#82241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82242 = ORIENTED_EDGE('',*,*,#79224,.T.); +#82243 = ORIENTED_EDGE('',*,*,#82244,.T.); +#82244 = EDGE_CURVE('',#79140,#82245,#82247,.T.); +#82245 = VERTEX_POINT('',#82246); +#82246 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#82247 = SURFACE_CURVE('',#82248,(#82253,#82261),.PCURVE_S1.); +#82248 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82249,#82250,#82251,#82252 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79857 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#79858 = CARTESIAN_POINT('',(-1.268390986358,-0.494696214234,1.)); -#79859 = CARTESIAN_POINT('',(-1.24437896527,-0.504453973629,1.)); -#79860 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#79861 = PCURVE('',#76871,#79862); -#79862 = DEFINITIONAL_REPRESENTATION('',(#79863),#79868); -#79863 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79864,#79865,#79866,#79867 +#82249 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#82250 = CARTESIAN_POINT('',(-1.268390986358,-0.494696214234,1.)); +#82251 = CARTESIAN_POINT('',(-1.24437896527,-0.504453973629,1.)); +#82252 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#82253 = PCURVE('',#79263,#82254); +#82254 = DEFINITIONAL_REPRESENTATION('',(#82255),#82260); +#82255 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82256,#82257,#82258,#82259 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79864 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); -#79865 = CARTESIAN_POINT('',(-2.728390986358,0.155303785766)); -#79866 = CARTESIAN_POINT('',(-2.70437896527,0.145546026371)); -#79867 = CARTESIAN_POINT('',(-2.677861391,0.145546026371)); -#79868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79869 = PCURVE('',#76786,#79870); -#79870 = DEFINITIONAL_REPRESENTATION('',(#79871),#79897); -#79871 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79872,#79873,#79874,#79875, - #79876,#79877,#79878,#79879,#79880,#79881,#79882,#79883,#79884, - #79885,#79886,#79887,#79888,#79889,#79890,#79891,#79892,#79893, - #79894,#79895,#79896),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82256 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); +#82257 = CARTESIAN_POINT('',(-2.728390986358,0.155303785766)); +#82258 = CARTESIAN_POINT('',(-2.70437896527,0.145546026371)); +#82259 = CARTESIAN_POINT('',(-2.677861391,0.145546026371)); +#82260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82261 = PCURVE('',#79178,#82262); +#82262 = DEFINITIONAL_REPRESENTATION('',(#82263),#82289); +#82263 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82264,#82265,#82266,#82267, + #82268,#82269,#82270,#82271,#82272,#82273,#82274,#82275,#82276, + #82277,#82278,#82279,#82280,#82281,#82282,#82283,#82284,#82285, + #82286,#82287,#82288),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.388131789017E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -99050,95 +102039,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#79872 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#79873 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#79874 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); -#79875 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#79876 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#79877 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#79878 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#79879 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#79880 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#79881 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#79882 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#79883 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#79884 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#79885 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#79886 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#79887 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#79888 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#79889 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#79890 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#79891 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#79892 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#79893 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#79894 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#79895 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#79896 = CARTESIAN_POINT('',(0.751879414295,1.)); -#79897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79898 = ORIENTED_EDGE('',*,*,#79899,.T.); -#79899 = EDGE_CURVE('',#79853,#77136,#79900,.T.); -#79900 = SURFACE_CURVE('',#79901,(#79905,#79912),.PCURVE_S1.); -#79901 = LINE('',#79902,#79903); -#79902 = CARTESIAN_POINT('',(1.207931449084,-0.504453973629,1.)); -#79903 = VECTOR('',#79904,1.); -#79904 = DIRECTION('',(1.,0.E+000,0.E+000)); -#79905 = PCURVE('',#76871,#79906); -#79906 = DEFINITIONAL_REPRESENTATION('',(#79907),#79911); -#79907 = LINE('',#79908,#79909); -#79908 = CARTESIAN_POINT('',(-0.252068550916,0.145546026371)); -#79909 = VECTOR('',#79910,1.); -#79910 = DIRECTION('',(1.,0.E+000)); -#79911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79912 = PCURVE('',#77219,#79913); -#79913 = DEFINITIONAL_REPRESENTATION('',(#79914),#79917); -#79914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#79915,#79916),.UNSPECIFIED., +#82264 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#82265 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#82266 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); +#82267 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#82268 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#82269 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#82270 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#82271 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#82272 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#82273 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#82274 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#82275 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#82276 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#82277 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#82278 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#82279 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#82280 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#82281 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#82282 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#82283 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#82284 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#82285 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#82286 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#82287 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#82288 = CARTESIAN_POINT('',(0.751879414295,1.)); +#82289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82290 = ORIENTED_EDGE('',*,*,#82291,.T.); +#82291 = EDGE_CURVE('',#82245,#79528,#82292,.T.); +#82292 = SURFACE_CURVE('',#82293,(#82297,#82304),.PCURVE_S1.); +#82293 = LINE('',#82294,#82295); +#82294 = CARTESIAN_POINT('',(1.207931449084,-0.504453973629,1.)); +#82295 = VECTOR('',#82296,1.); +#82296 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82297 = PCURVE('',#79263,#82298); +#82298 = DEFINITIONAL_REPRESENTATION('',(#82299),#82303); +#82299 = LINE('',#82300,#82301); +#82300 = CARTESIAN_POINT('',(-0.252068550916,0.145546026371)); +#82301 = VECTOR('',#82302,1.); +#82302 = DIRECTION('',(1.,0.E+000)); +#82303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82304 = PCURVE('',#79611,#82305); +#82305 = DEFINITIONAL_REPRESENTATION('',(#82306),#82309); +#82306 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82307,#82308),.UNSPECIFIED., .F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#79915 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); -#79916 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); -#79917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#82307 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); +#82308 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); +#82309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#79918 = ORIENTED_EDGE('',*,*,#77135,.T.); -#79919 = ORIENTED_EDGE('',*,*,#79920,.T.); -#79920 = EDGE_CURVE('',#77051,#79921,#79923,.T.); -#79921 = VERTEX_POINT('',#79922); -#79922 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#79923 = SURFACE_CURVE('',#79924,(#79929,#79937),.PCURVE_S1.); -#79924 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79925,#79926,#79927,#79928 +#82310 = ORIENTED_EDGE('',*,*,#79527,.T.); +#82311 = ORIENTED_EDGE('',*,*,#82312,.T.); +#82312 = EDGE_CURVE('',#79443,#82313,#82315,.T.); +#82313 = VERTEX_POINT('',#82314); +#82314 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#82315 = SURFACE_CURVE('',#82316,(#82321,#82329),.PCURVE_S1.); +#82316 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82317,#82318,#82319,#82320 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79925 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#79926 = CARTESIAN_POINT('',(1.304696214234,-0.458390986358,1.)); -#79927 = CARTESIAN_POINT('',(1.314453973629,-0.43437896527,1.)); -#79928 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#79929 = PCURVE('',#76871,#79930); -#79930 = DEFINITIONAL_REPRESENTATION('',(#79931),#79936); -#79931 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#79932,#79933,#79934,#79935 +#82317 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#82318 = CARTESIAN_POINT('',(1.304696214234,-0.458390986358,1.)); +#82319 = CARTESIAN_POINT('',(1.314453973629,-0.43437896527,1.)); +#82320 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#82321 = PCURVE('',#79263,#82322); +#82322 = DEFINITIONAL_REPRESENTATION('',(#82323),#82328); +#82323 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82324,#82325,#82326,#82327 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#79932 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); -#79933 = CARTESIAN_POINT('',(-0.155303785766,0.191609013642)); -#79934 = CARTESIAN_POINT('',(-0.145546026371,0.21562103473)); -#79935 = CARTESIAN_POINT('',(-0.145546026371,0.242138609)); -#79936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79937 = PCURVE('',#77089,#79938); -#79938 = DEFINITIONAL_REPRESENTATION('',(#79939),#79965); -#79939 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79940,#79941,#79942,#79943, - #79944,#79945,#79946,#79947,#79948,#79949,#79950,#79951,#79952, - #79953,#79954,#79955,#79956,#79957,#79958,#79959,#79960,#79961, - #79962,#79963,#79964),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82324 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); +#82325 = CARTESIAN_POINT('',(-0.155303785766,0.191609013642)); +#82326 = CARTESIAN_POINT('',(-0.145546026371,0.21562103473)); +#82327 = CARTESIAN_POINT('',(-0.145546026371,0.242138609)); +#82328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82329 = PCURVE('',#79481,#82330); +#82330 = DEFINITIONAL_REPRESENTATION('',(#82331),#82357); +#82331 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82332,#82333,#82334,#82335, + #82336,#82337,#82338,#82339,#82340,#82341,#82342,#82343,#82344, + #82345,#82346,#82347,#82348,#82349,#82350,#82351,#82352,#82353, + #82354,#82355,#82356),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -99146,56 +102135,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#79940 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#79941 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#79942 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#79943 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#79944 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#79945 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#79946 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#79947 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#79948 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#79949 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#79950 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#79951 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#79952 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#79953 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#79954 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#79955 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#79956 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#79957 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#79958 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#79959 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#79960 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#79961 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#79962 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#79963 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#79964 = CARTESIAN_POINT('',(0.751879414295,1.)); -#79965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79966 = ORIENTED_EDGE('',*,*,#79967,.T.); -#79967 = EDGE_CURVE('',#79921,#77686,#79968,.T.); -#79968 = SURFACE_CURVE('',#79969,(#79973,#79980),.PCURVE_S1.); -#79969 = LINE('',#79970,#79971); -#79970 = CARTESIAN_POINT('',(1.314453973629,0.397931449084,1.)); -#79971 = VECTOR('',#79972,1.); -#79972 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#79973 = PCURVE('',#76871,#79974); -#79974 = DEFINITIONAL_REPRESENTATION('',(#79975),#79979); -#79975 = LINE('',#79976,#79977); -#79976 = CARTESIAN_POINT('',(-0.145546026371,1.047931449084)); -#79977 = VECTOR('',#79978,1.); -#79978 = DIRECTION('',(-1.668003342285E-016,1.)); -#79979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#79980 = PCURVE('',#77769,#79981); -#79981 = DEFINITIONAL_REPRESENTATION('',(#79982),#80008); -#79982 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#79983,#79984,#79985,#79986, - #79987,#79988,#79989,#79990,#79991,#79992,#79993,#79994,#79995, - #79996,#79997,#79998,#79999,#80000,#80001,#80002,#80003,#80004, - #80005,#80006,#80007),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82332 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#82333 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#82334 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#82335 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#82336 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#82337 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#82338 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#82339 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#82340 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#82341 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#82342 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#82343 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#82344 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#82345 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#82346 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#82347 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#82348 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#82349 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#82350 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#82351 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#82352 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#82353 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#82354 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#82355 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#82356 = CARTESIAN_POINT('',(0.751879414295,1.)); +#82357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82358 = ORIENTED_EDGE('',*,*,#82359,.T.); +#82359 = EDGE_CURVE('',#82313,#80078,#82360,.T.); +#82360 = SURFACE_CURVE('',#82361,(#82365,#82372),.PCURVE_S1.); +#82361 = LINE('',#82362,#82363); +#82362 = CARTESIAN_POINT('',(1.314453973629,0.397931449084,1.)); +#82363 = VECTOR('',#82364,1.); +#82364 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#82365 = PCURVE('',#79263,#82366); +#82366 = DEFINITIONAL_REPRESENTATION('',(#82367),#82371); +#82367 = LINE('',#82368,#82369); +#82368 = CARTESIAN_POINT('',(-0.145546026371,1.047931449084)); +#82369 = VECTOR('',#82370,1.); +#82370 = DIRECTION('',(-1.668003342285E-016,1.)); +#82371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82372 = PCURVE('',#80161,#82373); +#82373 = DEFINITIONAL_REPRESENTATION('',(#82374),#82400); +#82374 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82375,#82376,#82377,#82378, + #82379,#82380,#82381,#82382,#82383,#82384,#82385,#82386,#82387, + #82388,#82389,#82390,#82391,#82392,#82393,#82394,#82395,#82396, + #82397,#82398,#82399),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084,-0.768714531811, -0.731636223538,-0.694557915266,-0.657479606993,-0.62040129872, -0.583322990448,-0.546244682175,-0.509166373902,-0.47208806563, @@ -99203,69 +102192,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.286696524266,-0.249618215993,-0.212539907721,-0.175461599448, -0.138383291175,-0.101304982903,-6.422667462989E-002, -2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#79983 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); -#79984 = CARTESIAN_POINT('',(1.570796326795,0.254498045091)); -#79985 = CARTESIAN_POINT('',(1.570796326795,0.279216917273)); -#79986 = CARTESIAN_POINT('',(1.570796326795,0.316295225546)); -#79987 = CARTESIAN_POINT('',(1.570796326795,0.353373533818)); -#79988 = CARTESIAN_POINT('',(1.570796326795,0.390451842091)); -#79989 = CARTESIAN_POINT('',(1.570796326795,0.427530150364)); -#79990 = CARTESIAN_POINT('',(1.570796326795,0.464608458637)); -#79991 = CARTESIAN_POINT('',(1.570796326795,0.501686766909)); -#79992 = CARTESIAN_POINT('',(1.570796326795,0.538765075182)); -#79993 = CARTESIAN_POINT('',(1.570796326795,0.575843383455)); -#79994 = CARTESIAN_POINT('',(1.570796326795,0.612921691727)); -#79995 = CARTESIAN_POINT('',(1.570796326795,0.65)); -#79996 = CARTESIAN_POINT('',(1.570796326795,0.687078308273)); -#79997 = CARTESIAN_POINT('',(1.570796326795,0.724156616545)); -#79998 = CARTESIAN_POINT('',(1.570796326795,0.761234924818)); -#79999 = CARTESIAN_POINT('',(1.570796326795,0.798313233091)); -#80000 = CARTESIAN_POINT('',(1.570796326795,0.835391541363)); -#80001 = CARTESIAN_POINT('',(1.570796326795,0.872469849636)); -#80002 = CARTESIAN_POINT('',(1.570796326795,0.909548157909)); -#80003 = CARTESIAN_POINT('',(1.570796326795,0.946626466182)); -#80004 = CARTESIAN_POINT('',(1.570796326795,0.983704774454)); -#80005 = CARTESIAN_POINT('',(1.570796326795,1.020783082727)); -#80006 = CARTESIAN_POINT('',(1.570796326795,1.045501954909)); -#80007 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); -#80008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80009 = ORIENTED_EDGE('',*,*,#77685,.T.); -#80010 = ORIENTED_EDGE('',*,*,#80011,.T.); -#80011 = EDGE_CURVE('',#77601,#80012,#80014,.T.); -#80012 = VERTEX_POINT('',#80013); -#80013 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#80014 = SURFACE_CURVE('',#80015,(#80020,#80028),.PCURVE_S1.); -#80015 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80016,#80017,#80018,#80019 +#82375 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); +#82376 = CARTESIAN_POINT('',(1.570796326795,0.254498045091)); +#82377 = CARTESIAN_POINT('',(1.570796326795,0.279216917273)); +#82378 = CARTESIAN_POINT('',(1.570796326795,0.316295225546)); +#82379 = CARTESIAN_POINT('',(1.570796326795,0.353373533818)); +#82380 = CARTESIAN_POINT('',(1.570796326795,0.390451842091)); +#82381 = CARTESIAN_POINT('',(1.570796326795,0.427530150364)); +#82382 = CARTESIAN_POINT('',(1.570796326795,0.464608458637)); +#82383 = CARTESIAN_POINT('',(1.570796326795,0.501686766909)); +#82384 = CARTESIAN_POINT('',(1.570796326795,0.538765075182)); +#82385 = CARTESIAN_POINT('',(1.570796326795,0.575843383455)); +#82386 = CARTESIAN_POINT('',(1.570796326795,0.612921691727)); +#82387 = CARTESIAN_POINT('',(1.570796326795,0.65)); +#82388 = CARTESIAN_POINT('',(1.570796326795,0.687078308273)); +#82389 = CARTESIAN_POINT('',(1.570796326795,0.724156616545)); +#82390 = CARTESIAN_POINT('',(1.570796326795,0.761234924818)); +#82391 = CARTESIAN_POINT('',(1.570796326795,0.798313233091)); +#82392 = CARTESIAN_POINT('',(1.570796326795,0.835391541363)); +#82393 = CARTESIAN_POINT('',(1.570796326795,0.872469849636)); +#82394 = CARTESIAN_POINT('',(1.570796326795,0.909548157909)); +#82395 = CARTESIAN_POINT('',(1.570796326795,0.946626466182)); +#82396 = CARTESIAN_POINT('',(1.570796326795,0.983704774454)); +#82397 = CARTESIAN_POINT('',(1.570796326795,1.020783082727)); +#82398 = CARTESIAN_POINT('',(1.570796326795,1.045501954909)); +#82399 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); +#82400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82401 = ORIENTED_EDGE('',*,*,#80077,.T.); +#82402 = ORIENTED_EDGE('',*,*,#82403,.T.); +#82403 = EDGE_CURVE('',#79993,#82404,#82406,.T.); +#82404 = VERTEX_POINT('',#82405); +#82405 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#82406 = SURFACE_CURVE('',#82407,(#82412,#82420),.PCURVE_S1.); +#82407 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82408,#82409,#82410,#82411 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#80016 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#80017 = CARTESIAN_POINT('',(1.268390986358,0.494696214234,1.)); -#80018 = CARTESIAN_POINT('',(1.24437896527,0.504453973629,1.)); -#80019 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#80020 = PCURVE('',#76871,#80021); -#80021 = DEFINITIONAL_REPRESENTATION('',(#80022),#80027); -#80022 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80023,#80024,#80025,#80026 +#82408 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#82409 = CARTESIAN_POINT('',(1.268390986358,0.494696214234,1.)); +#82410 = CARTESIAN_POINT('',(1.24437896527,0.504453973629,1.)); +#82411 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#82412 = PCURVE('',#79263,#82413); +#82413 = DEFINITIONAL_REPRESENTATION('',(#82414),#82419); +#82414 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82415,#82416,#82417,#82418 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#80023 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); -#80024 = CARTESIAN_POINT('',(-0.191609013642,1.144696214234)); -#80025 = CARTESIAN_POINT('',(-0.21562103473,1.154453973629)); -#80026 = CARTESIAN_POINT('',(-0.242138609,1.154453973629)); -#80027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80028 = PCURVE('',#77639,#80029); -#80029 = DEFINITIONAL_REPRESENTATION('',(#80030),#80056); -#80030 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80031,#80032,#80033,#80034, - #80035,#80036,#80037,#80038,#80039,#80040,#80041,#80042,#80043, - #80044,#80045,#80046,#80047,#80048,#80049,#80050,#80051,#80052, - #80053,#80054,#80055),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82415 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); +#82416 = CARTESIAN_POINT('',(-0.191609013642,1.144696214234)); +#82417 = CARTESIAN_POINT('',(-0.21562103473,1.154453973629)); +#82418 = CARTESIAN_POINT('',(-0.242138609,1.154453973629)); +#82419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82420 = PCURVE('',#80031,#82421); +#82421 = DEFINITIONAL_REPRESENTATION('',(#82422),#82448); +#82422 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82423,#82424,#82425,#82426, + #82427,#82428,#82429,#82430,#82431,#82432,#82433,#82434,#82435, + #82436,#82437,#82438,#82439,#82440,#82441,#82442,#82443,#82444, + #82445,#82446,#82447),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.388131789017E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -99273,93 +102262,93 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#80031 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#80032 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#80033 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#80034 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#80035 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#80036 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#80037 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#80038 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#80039 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#80040 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#80041 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#80042 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#80043 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#80044 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#80045 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#80046 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#80047 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#80048 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#80049 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#80050 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#80051 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#80052 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#80053 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#80054 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#80055 = CARTESIAN_POINT('',(0.751879414295,1.)); -#80056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80057 = ORIENTED_EDGE('',*,*,#80058,.T.); -#80058 = EDGE_CURVE('',#80012,#77411,#80059,.T.); -#80059 = SURFACE_CURVE('',#80060,(#80064,#80071),.PCURVE_S1.); -#80060 = LINE('',#80061,#80062); -#80061 = CARTESIAN_POINT('',(-1.207931449084,0.504453973629,1.)); -#80062 = VECTOR('',#80063,1.); -#80063 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80064 = PCURVE('',#76871,#80065); -#80065 = DEFINITIONAL_REPRESENTATION('',(#80066),#80070); -#80066 = LINE('',#80067,#80068); -#80067 = CARTESIAN_POINT('',(-2.667931449084,1.154453973629)); -#80068 = VECTOR('',#80069,1.); -#80069 = DIRECTION('',(-1.,0.E+000)); -#80070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80071 = PCURVE('',#77494,#80072); -#80072 = DEFINITIONAL_REPRESENTATION('',(#80073),#80076); -#80073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80074,#80075),.UNSPECIFIED., +#82423 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#82424 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#82425 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#82426 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#82427 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#82428 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#82429 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#82430 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#82431 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#82432 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#82433 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#82434 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#82435 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#82436 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#82437 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#82438 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#82439 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#82440 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#82441 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#82442 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#82443 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#82444 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#82445 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#82446 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#82447 = CARTESIAN_POINT('',(0.751879414295,1.)); +#82448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82449 = ORIENTED_EDGE('',*,*,#82450,.T.); +#82450 = EDGE_CURVE('',#82404,#79803,#82451,.T.); +#82451 = SURFACE_CURVE('',#82452,(#82456,#82463),.PCURVE_S1.); +#82452 = LINE('',#82453,#82454); +#82453 = CARTESIAN_POINT('',(-1.207931449084,0.504453973629,1.)); +#82454 = VECTOR('',#82455,1.); +#82455 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#82456 = PCURVE('',#79263,#82457); +#82457 = DEFINITIONAL_REPRESENTATION('',(#82458),#82462); +#82458 = LINE('',#82459,#82460); +#82459 = CARTESIAN_POINT('',(-2.667931449084,1.154453973629)); +#82460 = VECTOR('',#82461,1.); +#82461 = DIRECTION('',(-1.,0.E+000)); +#82462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82463 = PCURVE('',#79886,#82464); +#82464 = DEFINITIONAL_REPRESENTATION('',(#82465),#82468); +#82465 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82466,#82467),.UNSPECIFIED., .F.,.F.,(2,2),(-2.425792840084,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#80074 = CARTESIAN_POINT('',(0.E+000,0.242138609)); -#80075 = CARTESIAN_POINT('',(0.E+000,2.677861391)); -#80076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#82466 = CARTESIAN_POINT('',(0.E+000,0.242138609)); +#82467 = CARTESIAN_POINT('',(0.E+000,2.677861391)); +#82468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#80077 = ORIENTED_EDGE('',*,*,#77410,.T.); -#80078 = ORIENTED_EDGE('',*,*,#80079,.T.); -#80079 = EDGE_CURVE('',#77326,#79807,#80080,.T.); -#80080 = SURFACE_CURVE('',#80081,(#80086,#80094),.PCURVE_S1.); -#80081 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80082,#80083,#80084,#80085 +#82469 = ORIENTED_EDGE('',*,*,#79802,.T.); +#82470 = ORIENTED_EDGE('',*,*,#82471,.T.); +#82471 = EDGE_CURVE('',#79718,#82199,#82472,.T.); +#82472 = SURFACE_CURVE('',#82473,(#82478,#82486),.PCURVE_S1.); +#82473 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82474,#82475,#82476,#82477 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#80082 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#80083 = CARTESIAN_POINT('',(-1.304696214234,0.458390986358,1.)); -#80084 = CARTESIAN_POINT('',(-1.314453973629,0.43437896527,1.)); -#80085 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#80086 = PCURVE('',#76871,#80087); -#80087 = DEFINITIONAL_REPRESENTATION('',(#80088),#80093); -#80088 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#80089,#80090,#80091,#80092 +#82474 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#82475 = CARTESIAN_POINT('',(-1.304696214234,0.458390986358,1.)); +#82476 = CARTESIAN_POINT('',(-1.314453973629,0.43437896527,1.)); +#82477 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#82478 = PCURVE('',#79263,#82479); +#82479 = DEFINITIONAL_REPRESENTATION('',(#82480),#82485); +#82480 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#82481,#82482,#82483,#82484 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#80089 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); -#80090 = CARTESIAN_POINT('',(-2.764696214234,1.108390986358)); -#80091 = CARTESIAN_POINT('',(-2.774453973629,1.08437896527)); -#80092 = CARTESIAN_POINT('',(-2.774453973629,1.057861391)); -#80093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80094 = PCURVE('',#77364,#80095); -#80095 = DEFINITIONAL_REPRESENTATION('',(#80096),#80122); -#80096 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80097,#80098,#80099,#80100, - #80101,#80102,#80103,#80104,#80105,#80106,#80107,#80108,#80109, - #80110,#80111,#80112,#80113,#80114,#80115,#80116,#80117,#80118, - #80119,#80120,#80121),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#82481 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); +#82482 = CARTESIAN_POINT('',(-2.764696214234,1.108390986358)); +#82483 = CARTESIAN_POINT('',(-2.774453973629,1.08437896527)); +#82484 = CARTESIAN_POINT('',(-2.774453973629,1.057861391)); +#82485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82486 = PCURVE('',#79756,#82487); +#82487 = DEFINITIONAL_REPRESENTATION('',(#82488),#82514); +#82488 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82489,#82490,#82491,#82492, + #82493,#82494,#82495,#82496,#82497,#82498,#82499,#82500,#82501, + #82502,#82503,#82504,#82505,#82506,#82507,#82508,#82509,#82510, + #82511,#82512,#82513),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -99367,877 +102356,877 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#80097 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#80098 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#80099 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#80100 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#80101 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#80102 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#80103 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#80104 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#80105 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#80106 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#80107 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#80108 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#80109 = CARTESIAN_POINT('',(0.375899653916,0.998577358683)); -#80110 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#80111 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#80112 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#80113 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#80114 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#80115 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#80116 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#80117 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#80118 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#80119 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#80120 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#80121 = CARTESIAN_POINT('',(0.751879414295,1.)); -#80122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#82489 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#82490 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#82491 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#82492 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#82493 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#82494 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#82495 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#82496 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#82497 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#82498 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#82499 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#82500 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#82501 = CARTESIAN_POINT('',(0.375899653916,0.998577358683)); +#82502 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#82503 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#82504 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#82505 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#82506 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#82507 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#82508 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#82509 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#82510 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#82511 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#82512 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#82513 = CARTESIAN_POINT('',(0.751879414295,1.)); +#82514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82515 = ADVANCED_FACE('',(#82516),#80448,.T.); +#82516 = FACE_BOUND('',#82517,.T.); +#82517 = EDGE_LOOP('',(#82518,#82519,#82542,#82569)); +#82518 = ORIENTED_EDGE('',*,*,#80432,.F.); +#82519 = ORIENTED_EDGE('',*,*,#82520,.T.); +#82520 = EDGE_CURVE('',#80405,#82521,#82523,.T.); +#82521 = VERTEX_POINT('',#82522); +#82522 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#82523 = SURFACE_CURVE('',#82524,(#82528,#82535),.PCURVE_S1.); +#82524 = LINE('',#82525,#82526); +#82525 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#82526 = VECTOR('',#82527,1.); +#82527 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#82528 = PCURVE('',#80448,#82529); +#82529 = DEFINITIONAL_REPRESENTATION('',(#82530),#82534); +#82530 = LINE('',#82531,#82532); +#82531 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82532 = VECTOR('',#82533,1.); +#82533 = DIRECTION('',(0.E+000,-1.)); +#82534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82535 = PCURVE('',#80420,#82536); +#82536 = DEFINITIONAL_REPRESENTATION('',(#82537),#82541); +#82537 = LINE('',#82538,#82539); +#82538 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#82539 = VECTOR('',#82540,1.); +#82540 = DIRECTION('',(0.E+000,-1.)); +#82541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82542 = ORIENTED_EDGE('',*,*,#82543,.T.); +#82543 = EDGE_CURVE('',#82521,#82544,#82546,.T.); +#82544 = VERTEX_POINT('',#82545); +#82545 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); +#82546 = SURFACE_CURVE('',#82547,(#82551,#82558),.PCURVE_S1.); +#82547 = LINE('',#82548,#82549); +#82548 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#82549 = VECTOR('',#82550,1.); +#82550 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82551 = PCURVE('',#80448,#82552); +#82552 = DEFINITIONAL_REPRESENTATION('',(#82553),#82557); +#82553 = LINE('',#82554,#82555); +#82554 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82555 = VECTOR('',#82556,1.); +#82556 = DIRECTION('',(1.,0.E+000)); +#82557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82558 = PCURVE('',#82559,#82564); +#82559 = CYLINDRICAL_SURFACE('',#82560,0.2); +#82560 = AXIS2_PLACEMENT_3D('',#82561,#82562,#82563); +#82561 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#82562 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82563 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82564 = DEFINITIONAL_REPRESENTATION('',(#82565),#82568); +#82565 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82566,#82567),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#82566 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#82567 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#82568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#80123 = ADVANCED_FACE('',(#80124),#78056,.T.); -#80124 = FACE_BOUND('',#80125,.T.); -#80125 = EDGE_LOOP('',(#80126,#80127,#80150,#80177)); -#80126 = ORIENTED_EDGE('',*,*,#78040,.F.); -#80127 = ORIENTED_EDGE('',*,*,#80128,.T.); -#80128 = EDGE_CURVE('',#78013,#80129,#80131,.T.); -#80129 = VERTEX_POINT('',#80130); -#80130 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#80131 = SURFACE_CURVE('',#80132,(#80136,#80143),.PCURVE_S1.); -#80132 = LINE('',#80133,#80134); -#80133 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#80134 = VECTOR('',#80135,1.); -#80135 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#80136 = PCURVE('',#78056,#80137); -#80137 = DEFINITIONAL_REPRESENTATION('',(#80138),#80142); -#80138 = LINE('',#80139,#80140); -#80139 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80140 = VECTOR('',#80141,1.); -#80141 = DIRECTION('',(0.E+000,-1.)); -#80142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80143 = PCURVE('',#78028,#80144); -#80144 = DEFINITIONAL_REPRESENTATION('',(#80145),#80149); -#80145 = LINE('',#80146,#80147); -#80146 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#80147 = VECTOR('',#80148,1.); -#80148 = DIRECTION('',(0.E+000,-1.)); -#80149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80150 = ORIENTED_EDGE('',*,*,#80151,.T.); -#80151 = EDGE_CURVE('',#80129,#80152,#80154,.T.); -#80152 = VERTEX_POINT('',#80153); -#80153 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); -#80154 = SURFACE_CURVE('',#80155,(#80159,#80166),.PCURVE_S1.); -#80155 = LINE('',#80156,#80157); -#80156 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#80157 = VECTOR('',#80158,1.); -#80158 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80159 = PCURVE('',#78056,#80160); -#80160 = DEFINITIONAL_REPRESENTATION('',(#80161),#80165); -#80161 = LINE('',#80162,#80163); -#80162 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80163 = VECTOR('',#80164,1.); -#80164 = DIRECTION('',(1.,0.E+000)); -#80165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80166 = PCURVE('',#80167,#80172); -#80167 = CYLINDRICAL_SURFACE('',#80168,0.2); -#80168 = AXIS2_PLACEMENT_3D('',#80169,#80170,#80171); -#80169 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#80170 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80171 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80172 = DEFINITIONAL_REPRESENTATION('',(#80173),#80176); -#80173 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80174,#80175),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80174 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#80175 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#80176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80177 = ORIENTED_EDGE('',*,*,#80178,.F.); -#80178 = EDGE_CURVE('',#78041,#80152,#80179,.T.); -#80179 = SURFACE_CURVE('',#80180,(#80184,#80191),.PCURVE_S1.); -#80180 = LINE('',#80181,#80182); -#80181 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); -#80182 = VECTOR('',#80183,1.); -#80183 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#80184 = PCURVE('',#78056,#80185); -#80185 = DEFINITIONAL_REPRESENTATION('',(#80186),#80190); -#80186 = LINE('',#80187,#80188); -#80187 = CARTESIAN_POINT('',(0.4,0.E+000)); -#80188 = VECTOR('',#80189,1.); -#80189 = DIRECTION('',(0.E+000,-1.)); -#80190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80191 = PCURVE('',#78084,#80192); -#80192 = DEFINITIONAL_REPRESENTATION('',(#80193),#80197); -#80193 = LINE('',#80194,#80195); -#80194 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#80195 = VECTOR('',#80196,1.); -#80196 = DIRECTION('',(0.E+000,-1.)); -#80197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80198 = ADVANCED_FACE('',(#80199),#78879,.T.); -#80199 = FACE_BOUND('',#80200,.T.); -#80200 = EDGE_LOOP('',(#80201,#80202,#80225,#80252)); -#80201 = ORIENTED_EDGE('',*,*,#78865,.T.); -#80202 = ORIENTED_EDGE('',*,*,#80203,.F.); -#80203 = EDGE_CURVE('',#80204,#78069,#80206,.T.); -#80204 = VERTEX_POINT('',#80205); -#80205 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); -#80206 = SURFACE_CURVE('',#80207,(#80211,#80218),.PCURVE_S1.); -#80207 = LINE('',#80208,#80209); -#80208 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); -#80209 = VECTOR('',#80210,1.); -#80210 = DIRECTION('',(0.E+000,1.,0.E+000)); -#80211 = PCURVE('',#78879,#80212); -#80212 = DEFINITIONAL_REPRESENTATION('',(#80213),#80217); -#80213 = LINE('',#80214,#80215); -#80214 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#80215 = VECTOR('',#80216,1.); -#80216 = DIRECTION('',(0.E+000,1.)); -#80217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80218 = PCURVE('',#78084,#80219); -#80219 = DEFINITIONAL_REPRESENTATION('',(#80220),#80224); -#80220 = LINE('',#80221,#80222); -#80221 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#80222 = VECTOR('',#80223,1.); -#80223 = DIRECTION('',(0.E+000,1.)); -#80224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80225 = ORIENTED_EDGE('',*,*,#80226,.F.); -#80226 = EDGE_CURVE('',#80227,#80204,#80229,.T.); -#80227 = VERTEX_POINT('',#80228); -#80228 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#80229 = SURFACE_CURVE('',#80230,(#80234,#80241),.PCURVE_S1.); -#80230 = LINE('',#80231,#80232); -#80231 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#80232 = VECTOR('',#80233,1.); -#80233 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80234 = PCURVE('',#78879,#80235); -#80235 = DEFINITIONAL_REPRESENTATION('',(#80236),#80240); -#80236 = LINE('',#80237,#80238); -#80237 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80238 = VECTOR('',#80239,1.); -#80239 = DIRECTION('',(-1.,0.E+000)); -#80240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80241 = PCURVE('',#80242,#80247); -#80242 = CYLINDRICAL_SURFACE('',#80243,5.E-002); -#80243 = AXIS2_PLACEMENT_3D('',#80244,#80245,#80246); -#80244 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#80245 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80246 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80247 = DEFINITIONAL_REPRESENTATION('',(#80248),#80251); -#80248 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80249,#80250),.UNSPECIFIED., +#82569 = ORIENTED_EDGE('',*,*,#82570,.F.); +#82570 = EDGE_CURVE('',#80433,#82544,#82571,.T.); +#82571 = SURFACE_CURVE('',#82572,(#82576,#82583),.PCURVE_S1.); +#82572 = LINE('',#82573,#82574); +#82573 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); +#82574 = VECTOR('',#82575,1.); +#82575 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#82576 = PCURVE('',#80448,#82577); +#82577 = DEFINITIONAL_REPRESENTATION('',(#82578),#82582); +#82578 = LINE('',#82579,#82580); +#82579 = CARTESIAN_POINT('',(0.4,0.E+000)); +#82580 = VECTOR('',#82581,1.); +#82581 = DIRECTION('',(0.E+000,-1.)); +#82582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82583 = PCURVE('',#80476,#82584); +#82584 = DEFINITIONAL_REPRESENTATION('',(#82585),#82589); +#82585 = LINE('',#82586,#82587); +#82586 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#82587 = VECTOR('',#82588,1.); +#82588 = DIRECTION('',(0.E+000,-1.)); +#82589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82590 = ADVANCED_FACE('',(#82591),#81271,.T.); +#82591 = FACE_BOUND('',#82592,.T.); +#82592 = EDGE_LOOP('',(#82593,#82594,#82617,#82644)); +#82593 = ORIENTED_EDGE('',*,*,#81257,.T.); +#82594 = ORIENTED_EDGE('',*,*,#82595,.F.); +#82595 = EDGE_CURVE('',#82596,#80461,#82598,.T.); +#82596 = VERTEX_POINT('',#82597); +#82597 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); +#82598 = SURFACE_CURVE('',#82599,(#82603,#82610),.PCURVE_S1.); +#82599 = LINE('',#82600,#82601); +#82600 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); +#82601 = VECTOR('',#82602,1.); +#82602 = DIRECTION('',(0.E+000,1.,0.E+000)); +#82603 = PCURVE('',#81271,#82604); +#82604 = DEFINITIONAL_REPRESENTATION('',(#82605),#82609); +#82605 = LINE('',#82606,#82607); +#82606 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#82607 = VECTOR('',#82608,1.); +#82608 = DIRECTION('',(0.E+000,1.)); +#82609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82610 = PCURVE('',#80476,#82611); +#82611 = DEFINITIONAL_REPRESENTATION('',(#82612),#82616); +#82612 = LINE('',#82613,#82614); +#82613 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#82614 = VECTOR('',#82615,1.); +#82615 = DIRECTION('',(0.E+000,1.)); +#82616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82617 = ORIENTED_EDGE('',*,*,#82618,.F.); +#82618 = EDGE_CURVE('',#82619,#82596,#82621,.T.); +#82619 = VERTEX_POINT('',#82620); +#82620 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#82621 = SURFACE_CURVE('',#82622,(#82626,#82633),.PCURVE_S1.); +#82622 = LINE('',#82623,#82624); +#82623 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#82624 = VECTOR('',#82625,1.); +#82625 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82626 = PCURVE('',#81271,#82627); +#82627 = DEFINITIONAL_REPRESENTATION('',(#82628),#82632); +#82628 = LINE('',#82629,#82630); +#82629 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82630 = VECTOR('',#82631,1.); +#82631 = DIRECTION('',(-1.,0.E+000)); +#82632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82633 = PCURVE('',#82634,#82639); +#82634 = CYLINDRICAL_SURFACE('',#82635,5.E-002); +#82635 = AXIS2_PLACEMENT_3D('',#82636,#82637,#82638); +#82636 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#82637 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82638 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82639 = DEFINITIONAL_REPRESENTATION('',(#82640),#82643); +#82640 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82641,#82642),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80249 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#80250 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#80251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80252 = ORIENTED_EDGE('',*,*,#80253,.T.); -#80253 = EDGE_CURVE('',#80227,#77990,#80254,.T.); -#80254 = SURFACE_CURVE('',#80255,(#80259,#80266),.PCURVE_S1.); -#80255 = LINE('',#80256,#80257); -#80256 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#80257 = VECTOR('',#80258,1.); -#80258 = DIRECTION('',(0.E+000,1.,0.E+000)); -#80259 = PCURVE('',#78879,#80260); -#80260 = DEFINITIONAL_REPRESENTATION('',(#80261),#80265); -#80261 = LINE('',#80262,#80263); -#80262 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80263 = VECTOR('',#80264,1.); -#80264 = DIRECTION('',(0.E+000,1.)); -#80265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80266 = PCURVE('',#78028,#80267); -#80267 = DEFINITIONAL_REPRESENTATION('',(#80268),#80272); -#80268 = LINE('',#80269,#80270); -#80269 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#80270 = VECTOR('',#80271,1.); -#80271 = DIRECTION('',(0.E+000,1.)); -#80272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80273 = ADVANCED_FACE('',(#80274),#78028,.F.); -#80274 = FACE_BOUND('',#80275,.T.); -#80275 = EDGE_LOOP('',(#80276,#80277,#80278,#80279,#80306,#80334,#80362, - #80390,#80418,#80446,#80478,#80506)); -#80276 = ORIENTED_EDGE('',*,*,#80128,.F.); -#80277 = ORIENTED_EDGE('',*,*,#78012,.T.); -#80278 = ORIENTED_EDGE('',*,*,#80253,.F.); -#80279 = ORIENTED_EDGE('',*,*,#80280,.F.); -#80280 = EDGE_CURVE('',#80281,#80227,#80283,.T.); -#80281 = VERTEX_POINT('',#80282); -#80282 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#80283 = SURFACE_CURVE('',#80284,(#80289,#80300),.PCURVE_S1.); -#80284 = CIRCLE('',#80285,5.E-002); -#80285 = AXIS2_PLACEMENT_3D('',#80286,#80287,#80288); -#80286 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#80287 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80288 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80289 = PCURVE('',#78028,#80290); -#80290 = DEFINITIONAL_REPRESENTATION('',(#80291),#80299); -#80291 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#80292,#80293,#80294,#80295 - ,#80296,#80297,#80298),.UNSPECIFIED.,.F.,.F.) +#82641 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#82642 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#82643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82644 = ORIENTED_EDGE('',*,*,#82645,.T.); +#82645 = EDGE_CURVE('',#82619,#80382,#82646,.T.); +#82646 = SURFACE_CURVE('',#82647,(#82651,#82658),.PCURVE_S1.); +#82647 = LINE('',#82648,#82649); +#82648 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#82649 = VECTOR('',#82650,1.); +#82650 = DIRECTION('',(0.E+000,1.,0.E+000)); +#82651 = PCURVE('',#81271,#82652); +#82652 = DEFINITIONAL_REPRESENTATION('',(#82653),#82657); +#82653 = LINE('',#82654,#82655); +#82654 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82655 = VECTOR('',#82656,1.); +#82656 = DIRECTION('',(0.E+000,1.)); +#82657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82658 = PCURVE('',#80420,#82659); +#82659 = DEFINITIONAL_REPRESENTATION('',(#82660),#82664); +#82660 = LINE('',#82661,#82662); +#82661 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#82662 = VECTOR('',#82663,1.); +#82663 = DIRECTION('',(0.E+000,1.)); +#82664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82665 = ADVANCED_FACE('',(#82666),#80420,.F.); +#82666 = FACE_BOUND('',#82667,.T.); +#82667 = EDGE_LOOP('',(#82668,#82669,#82670,#82671,#82698,#82726,#82754, + #82782,#82810,#82838,#82870,#82898)); +#82668 = ORIENTED_EDGE('',*,*,#82520,.F.); +#82669 = ORIENTED_EDGE('',*,*,#80404,.T.); +#82670 = ORIENTED_EDGE('',*,*,#82645,.F.); +#82671 = ORIENTED_EDGE('',*,*,#82672,.F.); +#82672 = EDGE_CURVE('',#82673,#82619,#82675,.T.); +#82673 = VERTEX_POINT('',#82674); +#82674 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#82675 = SURFACE_CURVE('',#82676,(#82681,#82692),.PCURVE_S1.); +#82676 = CIRCLE('',#82677,5.E-002); +#82677 = AXIS2_PLACEMENT_3D('',#82678,#82679,#82680); +#82678 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#82679 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#82680 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82681 = PCURVE('',#80420,#82682); +#82682 = DEFINITIONAL_REPRESENTATION('',(#82683),#82691); +#82683 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82684,#82685,#82686,#82687 + ,#82688,#82689,#82690),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#80292 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#80293 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#80294 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#80295 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#80296 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#80297 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#80298 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#80299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80300 = PCURVE('',#80242,#80301); -#80301 = DEFINITIONAL_REPRESENTATION('',(#80302),#80305); -#80302 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80303,#80304),.UNSPECIFIED., +#82684 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#82685 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#82686 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#82687 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#82688 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#82689 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#82690 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#82691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82692 = PCURVE('',#82634,#82693); +#82693 = DEFINITIONAL_REPRESENTATION('',(#82694),#82697); +#82694 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82695,#82696),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#80303 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#80304 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#80305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80306 = ORIENTED_EDGE('',*,*,#80307,.F.); -#80307 = EDGE_CURVE('',#80308,#80281,#80310,.T.); -#80308 = VERTEX_POINT('',#80309); -#80309 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); -#80310 = SURFACE_CURVE('',#80311,(#80315,#80322),.PCURVE_S1.); -#80311 = LINE('',#80312,#80313); -#80312 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#80313 = VECTOR('',#80314,1.); -#80314 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#80315 = PCURVE('',#78028,#80316); -#80316 = DEFINITIONAL_REPRESENTATION('',(#80317),#80321); -#80317 = LINE('',#80318,#80319); -#80318 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#80319 = VECTOR('',#80320,1.); -#80320 = DIRECTION('',(-0.993981062721,0.109552028512)); -#80321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80322 = PCURVE('',#80323,#80328); -#80323 = PLANE('',#80324); -#80324 = AXIS2_PLACEMENT_3D('',#80325,#80326,#80327); -#80325 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#80326 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); -#80327 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#80328 = DEFINITIONAL_REPRESENTATION('',(#80329),#80333); -#80329 = LINE('',#80330,#80331); -#80330 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80331 = VECTOR('',#80332,1.); -#80332 = DIRECTION('',(1.,0.E+000)); -#80333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80334 = ORIENTED_EDGE('',*,*,#80335,.F.); -#80335 = EDGE_CURVE('',#80336,#80308,#80338,.T.); -#80336 = VERTEX_POINT('',#80337); -#80337 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); -#80338 = SURFACE_CURVE('',#80339,(#80344,#80351),.PCURVE_S1.); -#80339 = CIRCLE('',#80340,0.2); -#80340 = AXIS2_PLACEMENT_3D('',#80341,#80342,#80343); -#80341 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#80342 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80343 = DIRECTION('',(0.E+000,0.E+000,1.)); -#80344 = PCURVE('',#78028,#80345); -#80345 = DEFINITIONAL_REPRESENTATION('',(#80346),#80350); -#80346 = CIRCLE('',#80347,0.2); -#80347 = AXIS2_PLACEMENT_2D('',#80348,#80349); -#80348 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#80349 = DIRECTION('',(-1.,0.E+000)); -#80350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80351 = PCURVE('',#80352,#80357); -#80352 = CYLINDRICAL_SURFACE('',#80353,0.2); -#80353 = AXIS2_PLACEMENT_3D('',#80354,#80355,#80356); -#80354 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#80355 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80356 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80357 = DEFINITIONAL_REPRESENTATION('',(#80358),#80361); -#80358 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80359,#80360),.UNSPECIFIED., +#82695 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#82696 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#82697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82698 = ORIENTED_EDGE('',*,*,#82699,.F.); +#82699 = EDGE_CURVE('',#82700,#82673,#82702,.T.); +#82700 = VERTEX_POINT('',#82701); +#82701 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); +#82702 = SURFACE_CURVE('',#82703,(#82707,#82714),.PCURVE_S1.); +#82703 = LINE('',#82704,#82705); +#82704 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#82705 = VECTOR('',#82706,1.); +#82706 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#82707 = PCURVE('',#80420,#82708); +#82708 = DEFINITIONAL_REPRESENTATION('',(#82709),#82713); +#82709 = LINE('',#82710,#82711); +#82710 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#82711 = VECTOR('',#82712,1.); +#82712 = DIRECTION('',(-0.993981062721,0.109552028512)); +#82713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82714 = PCURVE('',#82715,#82720); +#82715 = PLANE('',#82716); +#82716 = AXIS2_PLACEMENT_3D('',#82717,#82718,#82719); +#82717 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#82718 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); +#82719 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#82720 = DEFINITIONAL_REPRESENTATION('',(#82721),#82725); +#82721 = LINE('',#82722,#82723); +#82722 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82723 = VECTOR('',#82724,1.); +#82724 = DIRECTION('',(1.,0.E+000)); +#82725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82726 = ORIENTED_EDGE('',*,*,#82727,.F.); +#82727 = EDGE_CURVE('',#82728,#82700,#82730,.T.); +#82728 = VERTEX_POINT('',#82729); +#82729 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); +#82730 = SURFACE_CURVE('',#82731,(#82736,#82743),.PCURVE_S1.); +#82731 = CIRCLE('',#82732,0.2); +#82732 = AXIS2_PLACEMENT_3D('',#82733,#82734,#82735); +#82733 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#82734 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82735 = DIRECTION('',(0.E+000,0.E+000,1.)); +#82736 = PCURVE('',#80420,#82737); +#82737 = DEFINITIONAL_REPRESENTATION('',(#82738),#82742); +#82738 = CIRCLE('',#82739,0.2); +#82739 = AXIS2_PLACEMENT_2D('',#82740,#82741); +#82740 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#82741 = DIRECTION('',(-1.,0.E+000)); +#82742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82743 = PCURVE('',#82744,#82749); +#82744 = CYLINDRICAL_SURFACE('',#82745,0.2); +#82745 = AXIS2_PLACEMENT_3D('',#82746,#82747,#82748); +#82746 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#82747 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82749 = DEFINITIONAL_REPRESENTATION('',(#82750),#82753); +#82750 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82751,#82752),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#80359 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80360 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#80361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80362 = ORIENTED_EDGE('',*,*,#80363,.F.); -#80363 = EDGE_CURVE('',#80364,#80336,#80366,.T.); -#80364 = VERTEX_POINT('',#80365); -#80365 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80366 = SURFACE_CURVE('',#80367,(#80371,#80378),.PCURVE_S1.); -#80367 = LINE('',#80368,#80369); -#80368 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80369 = VECTOR('',#80370,1.); -#80370 = DIRECTION('',(0.E+000,1.,0.E+000)); -#80371 = PCURVE('',#78028,#80372); -#80372 = DEFINITIONAL_REPRESENTATION('',(#80373),#80377); -#80373 = LINE('',#80374,#80375); -#80374 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#80375 = VECTOR('',#80376,1.); -#80376 = DIRECTION('',(0.E+000,1.)); -#80377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80378 = PCURVE('',#80379,#80384); -#80379 = PLANE('',#80380); -#80380 = AXIS2_PLACEMENT_3D('',#80381,#80382,#80383); -#80381 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80382 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80383 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80384 = DEFINITIONAL_REPRESENTATION('',(#80385),#80389); -#80385 = LINE('',#80386,#80387); -#80386 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80387 = VECTOR('',#80388,1.); -#80388 = DIRECTION('',(0.E+000,1.)); -#80389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80390 = ORIENTED_EDGE('',*,*,#80391,.F.); -#80391 = EDGE_CURVE('',#80392,#80364,#80394,.T.); -#80392 = VERTEX_POINT('',#80393); -#80393 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#80394 = SURFACE_CURVE('',#80395,(#80399,#80406),.PCURVE_S1.); -#80395 = LINE('',#80396,#80397); -#80396 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80397 = VECTOR('',#80398,1.); -#80398 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80399 = PCURVE('',#78028,#80400); -#80400 = DEFINITIONAL_REPRESENTATION('',(#80401),#80405); -#80401 = LINE('',#80402,#80403); -#80402 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#80403 = VECTOR('',#80404,1.); -#80404 = DIRECTION('',(1.,0.E+000)); -#80405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80406 = PCURVE('',#80407,#80412); -#80407 = PLANE('',#80408); -#80408 = AXIS2_PLACEMENT_3D('',#80409,#80410,#80411); -#80409 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80410 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#80411 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80412 = DEFINITIONAL_REPRESENTATION('',(#80413),#80417); -#80413 = LINE('',#80414,#80415); -#80414 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80415 = VECTOR('',#80416,1.); -#80416 = DIRECTION('',(1.,0.E+000)); -#80417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80418 = ORIENTED_EDGE('',*,*,#80419,.F.); -#80419 = EDGE_CURVE('',#80420,#80392,#80422,.T.); -#80420 = VERTEX_POINT('',#80421); -#80421 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); -#80422 = SURFACE_CURVE('',#80423,(#80427,#80434),.PCURVE_S1.); -#80423 = LINE('',#80424,#80425); -#80424 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#80425 = VECTOR('',#80426,1.); -#80426 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#80427 = PCURVE('',#78028,#80428); -#80428 = DEFINITIONAL_REPRESENTATION('',(#80429),#80433); -#80429 = LINE('',#80430,#80431); -#80430 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#80431 = VECTOR('',#80432,1.); -#80432 = DIRECTION('',(0.E+000,-1.)); -#80433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80434 = PCURVE('',#80435,#80440); -#80435 = PLANE('',#80436); -#80436 = AXIS2_PLACEMENT_3D('',#80437,#80438,#80439); -#80437 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#80438 = DIRECTION('',(0.E+000,0.E+000,1.)); -#80439 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80440 = DEFINITIONAL_REPRESENTATION('',(#80441),#80445); -#80441 = LINE('',#80442,#80443); -#80442 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80443 = VECTOR('',#80444,1.); -#80444 = DIRECTION('',(0.E+000,-1.)); -#80445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80446 = ORIENTED_EDGE('',*,*,#80447,.F.); -#80447 = EDGE_CURVE('',#80448,#80420,#80450,.T.); -#80448 = VERTEX_POINT('',#80449); -#80449 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#80450 = SURFACE_CURVE('',#80451,(#80456,#80467),.PCURVE_S1.); -#80451 = CIRCLE('',#80452,5.E-002); -#80452 = AXIS2_PLACEMENT_3D('',#80453,#80454,#80455); -#80453 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#80454 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80455 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80456 = PCURVE('',#78028,#80457); -#80457 = DEFINITIONAL_REPRESENTATION('',(#80458),#80466); -#80458 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#80459,#80460,#80461,#80462 - ,#80463,#80464,#80465),.UNSPECIFIED.,.F.,.F.) +#82751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82752 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#82753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82754 = ORIENTED_EDGE('',*,*,#82755,.F.); +#82755 = EDGE_CURVE('',#82756,#82728,#82758,.T.); +#82756 = VERTEX_POINT('',#82757); +#82757 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#82758 = SURFACE_CURVE('',#82759,(#82763,#82770),.PCURVE_S1.); +#82759 = LINE('',#82760,#82761); +#82760 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#82761 = VECTOR('',#82762,1.); +#82762 = DIRECTION('',(0.E+000,1.,0.E+000)); +#82763 = PCURVE('',#80420,#82764); +#82764 = DEFINITIONAL_REPRESENTATION('',(#82765),#82769); +#82765 = LINE('',#82766,#82767); +#82766 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#82767 = VECTOR('',#82768,1.); +#82768 = DIRECTION('',(0.E+000,1.)); +#82769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82770 = PCURVE('',#82771,#82776); +#82771 = PLANE('',#82772); +#82772 = AXIS2_PLACEMENT_3D('',#82773,#82774,#82775); +#82773 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#82774 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82775 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#82776 = DEFINITIONAL_REPRESENTATION('',(#82777),#82781); +#82777 = LINE('',#82778,#82779); +#82778 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82779 = VECTOR('',#82780,1.); +#82780 = DIRECTION('',(0.E+000,1.)); +#82781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82782 = ORIENTED_EDGE('',*,*,#82783,.F.); +#82783 = EDGE_CURVE('',#82784,#82756,#82786,.T.); +#82784 = VERTEX_POINT('',#82785); +#82785 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#82786 = SURFACE_CURVE('',#82787,(#82791,#82798),.PCURVE_S1.); +#82787 = LINE('',#82788,#82789); +#82788 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#82789 = VECTOR('',#82790,1.); +#82790 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82791 = PCURVE('',#80420,#82792); +#82792 = DEFINITIONAL_REPRESENTATION('',(#82793),#82797); +#82793 = LINE('',#82794,#82795); +#82794 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#82795 = VECTOR('',#82796,1.); +#82796 = DIRECTION('',(1.,0.E+000)); +#82797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82798 = PCURVE('',#82799,#82804); +#82799 = PLANE('',#82800); +#82800 = AXIS2_PLACEMENT_3D('',#82801,#82802,#82803); +#82801 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#82802 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#82803 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82804 = DEFINITIONAL_REPRESENTATION('',(#82805),#82809); +#82805 = LINE('',#82806,#82807); +#82806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82807 = VECTOR('',#82808,1.); +#82808 = DIRECTION('',(1.,0.E+000)); +#82809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82810 = ORIENTED_EDGE('',*,*,#82811,.F.); +#82811 = EDGE_CURVE('',#82812,#82784,#82814,.T.); +#82812 = VERTEX_POINT('',#82813); +#82813 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); +#82814 = SURFACE_CURVE('',#82815,(#82819,#82826),.PCURVE_S1.); +#82815 = LINE('',#82816,#82817); +#82816 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#82817 = VECTOR('',#82818,1.); +#82818 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#82819 = PCURVE('',#80420,#82820); +#82820 = DEFINITIONAL_REPRESENTATION('',(#82821),#82825); +#82821 = LINE('',#82822,#82823); +#82822 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#82823 = VECTOR('',#82824,1.); +#82824 = DIRECTION('',(0.E+000,-1.)); +#82825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82826 = PCURVE('',#82827,#82832); +#82827 = PLANE('',#82828); +#82828 = AXIS2_PLACEMENT_3D('',#82829,#82830,#82831); +#82829 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#82830 = DIRECTION('',(0.E+000,0.E+000,1.)); +#82831 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82832 = DEFINITIONAL_REPRESENTATION('',(#82833),#82837); +#82833 = LINE('',#82834,#82835); +#82834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82835 = VECTOR('',#82836,1.); +#82836 = DIRECTION('',(0.E+000,-1.)); +#82837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82838 = ORIENTED_EDGE('',*,*,#82839,.F.); +#82839 = EDGE_CURVE('',#82840,#82812,#82842,.T.); +#82840 = VERTEX_POINT('',#82841); +#82841 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#82842 = SURFACE_CURVE('',#82843,(#82848,#82859),.PCURVE_S1.); +#82843 = CIRCLE('',#82844,5.E-002); +#82844 = AXIS2_PLACEMENT_3D('',#82845,#82846,#82847); +#82845 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#82846 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#82847 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82848 = PCURVE('',#80420,#82849); +#82849 = DEFINITIONAL_REPRESENTATION('',(#82850),#82858); +#82850 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82851,#82852,#82853,#82854 + ,#82855,#82856,#82857),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#80459 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#80460 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#80461 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#80462 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#80463 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#80464 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#80465 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#80466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80467 = PCURVE('',#80468,#80473); -#80468 = CYLINDRICAL_SURFACE('',#80469,5.E-002); -#80469 = AXIS2_PLACEMENT_3D('',#80470,#80471,#80472); -#80470 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#80471 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80472 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80473 = DEFINITIONAL_REPRESENTATION('',(#80474),#80477); -#80474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80475,#80476),.UNSPECIFIED., +#82851 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#82852 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#82853 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#82854 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#82855 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#82856 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#82857 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#82858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82859 = PCURVE('',#82860,#82865); +#82860 = CYLINDRICAL_SURFACE('',#82861,5.E-002); +#82861 = AXIS2_PLACEMENT_3D('',#82862,#82863,#82864); +#82862 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#82863 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82864 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82865 = DEFINITIONAL_REPRESENTATION('',(#82866),#82869); +#82866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82867,#82868),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#80475 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#80476 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80478 = ORIENTED_EDGE('',*,*,#80479,.F.); -#80479 = EDGE_CURVE('',#80480,#80448,#80482,.T.); -#80480 = VERTEX_POINT('',#80481); -#80481 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); -#80482 = SURFACE_CURVE('',#80483,(#80487,#80494),.PCURVE_S1.); -#80483 = LINE('',#80484,#80485); -#80484 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#80485 = VECTOR('',#80486,1.); -#80486 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#80487 = PCURVE('',#78028,#80488); -#80488 = DEFINITIONAL_REPRESENTATION('',(#80489),#80493); -#80489 = LINE('',#80490,#80491); -#80490 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#80491 = VECTOR('',#80492,1.); -#80492 = DIRECTION('',(0.993981062721,-0.109552028512)); -#80493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80494 = PCURVE('',#80495,#80500); -#80495 = PLANE('',#80496); -#80496 = AXIS2_PLACEMENT_3D('',#80497,#80498,#80499); -#80497 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#80498 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); -#80499 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#80500 = DEFINITIONAL_REPRESENTATION('',(#80501),#80505); -#80501 = LINE('',#80502,#80503); -#80502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80503 = VECTOR('',#80504,1.); -#80504 = DIRECTION('',(1.,0.E+000)); -#80505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80506 = ORIENTED_EDGE('',*,*,#80507,.F.); -#80507 = EDGE_CURVE('',#80129,#80480,#80508,.T.); -#80508 = SURFACE_CURVE('',#80509,(#80514,#80521),.PCURVE_S1.); -#80509 = CIRCLE('',#80510,0.2); -#80510 = AXIS2_PLACEMENT_3D('',#80511,#80512,#80513); -#80511 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#80512 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80513 = DIRECTION('',(0.E+000,0.E+000,1.)); -#80514 = PCURVE('',#78028,#80515); -#80515 = DEFINITIONAL_REPRESENTATION('',(#80516),#80520); -#80516 = CIRCLE('',#80517,0.2); -#80517 = AXIS2_PLACEMENT_2D('',#80518,#80519); -#80518 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#80519 = DIRECTION('',(-1.,0.E+000)); -#80520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80521 = PCURVE('',#80167,#80522); -#80522 = DEFINITIONAL_REPRESENTATION('',(#80523),#80526); -#80523 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80524,#80525),.UNSPECIFIED., +#82867 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#82868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82870 = ORIENTED_EDGE('',*,*,#82871,.F.); +#82871 = EDGE_CURVE('',#82872,#82840,#82874,.T.); +#82872 = VERTEX_POINT('',#82873); +#82873 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); +#82874 = SURFACE_CURVE('',#82875,(#82879,#82886),.PCURVE_S1.); +#82875 = LINE('',#82876,#82877); +#82876 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#82877 = VECTOR('',#82878,1.); +#82878 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#82879 = PCURVE('',#80420,#82880); +#82880 = DEFINITIONAL_REPRESENTATION('',(#82881),#82885); +#82881 = LINE('',#82882,#82883); +#82882 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#82883 = VECTOR('',#82884,1.); +#82884 = DIRECTION('',(0.993981062721,-0.109552028512)); +#82885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82886 = PCURVE('',#82887,#82892); +#82887 = PLANE('',#82888); +#82888 = AXIS2_PLACEMENT_3D('',#82889,#82890,#82891); +#82889 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#82890 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); +#82891 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#82892 = DEFINITIONAL_REPRESENTATION('',(#82893),#82897); +#82893 = LINE('',#82894,#82895); +#82894 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#82895 = VECTOR('',#82896,1.); +#82896 = DIRECTION('',(1.,0.E+000)); +#82897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82898 = ORIENTED_EDGE('',*,*,#82899,.F.); +#82899 = EDGE_CURVE('',#82521,#82872,#82900,.T.); +#82900 = SURFACE_CURVE('',#82901,(#82906,#82913),.PCURVE_S1.); +#82901 = CIRCLE('',#82902,0.2); +#82902 = AXIS2_PLACEMENT_3D('',#82903,#82904,#82905); +#82903 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#82904 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82905 = DIRECTION('',(0.E+000,0.E+000,1.)); +#82906 = PCURVE('',#80420,#82907); +#82907 = DEFINITIONAL_REPRESENTATION('',(#82908),#82912); +#82908 = CIRCLE('',#82909,0.2); +#82909 = AXIS2_PLACEMENT_2D('',#82910,#82911); +#82910 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#82911 = DIRECTION('',(-1.,0.E+000)); +#82912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82913 = PCURVE('',#82559,#82914); +#82914 = DEFINITIONAL_REPRESENTATION('',(#82915),#82918); +#82915 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82916,#82917),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#80524 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#80525 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#80526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80527 = ADVANCED_FACE('',(#80528),#78084,.T.); -#80528 = FACE_BOUND('',#80529,.T.); -#80529 = EDGE_LOOP('',(#80530,#80531,#80532,#80555,#80578,#80605,#80628, - #80651,#80674,#80697,#80720,#80745)); -#80530 = ORIENTED_EDGE('',*,*,#78068,.F.); -#80531 = ORIENTED_EDGE('',*,*,#80178,.T.); -#80532 = ORIENTED_EDGE('',*,*,#80533,.T.); -#80533 = EDGE_CURVE('',#80152,#80534,#80536,.T.); -#80534 = VERTEX_POINT('',#80535); -#80535 = CARTESIAN_POINT('',(1.155,-0.854004213739,0.571910405702)); -#80536 = SURFACE_CURVE('',#80537,(#80542,#80549),.PCURVE_S1.); -#80537 = CIRCLE('',#80538,0.2); -#80538 = AXIS2_PLACEMENT_3D('',#80539,#80540,#80541); -#80539 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#80540 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80541 = DIRECTION('',(0.E+000,0.E+000,1.)); -#80542 = PCURVE('',#78084,#80543); -#80543 = DEFINITIONAL_REPRESENTATION('',(#80544),#80548); -#80544 = CIRCLE('',#80545,0.2); -#80545 = AXIS2_PLACEMENT_2D('',#80546,#80547); -#80546 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#80547 = DIRECTION('',(-1.,0.E+000)); -#80548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80549 = PCURVE('',#80167,#80550); -#80550 = DEFINITIONAL_REPRESENTATION('',(#80551),#80554); -#80551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80552,#80553),.UNSPECIFIED., +#82916 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#82917 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#82918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82919 = ADVANCED_FACE('',(#82920),#80476,.T.); +#82920 = FACE_BOUND('',#82921,.T.); +#82921 = EDGE_LOOP('',(#82922,#82923,#82924,#82947,#82970,#82997,#83020, + #83043,#83066,#83089,#83112,#83137)); +#82922 = ORIENTED_EDGE('',*,*,#80460,.F.); +#82923 = ORIENTED_EDGE('',*,*,#82570,.T.); +#82924 = ORIENTED_EDGE('',*,*,#82925,.T.); +#82925 = EDGE_CURVE('',#82544,#82926,#82928,.T.); +#82926 = VERTEX_POINT('',#82927); +#82927 = CARTESIAN_POINT('',(1.155,-0.854004213739,0.571910405702)); +#82928 = SURFACE_CURVE('',#82929,(#82934,#82941),.PCURVE_S1.); +#82929 = CIRCLE('',#82930,0.2); +#82930 = AXIS2_PLACEMENT_3D('',#82931,#82932,#82933); +#82931 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#82932 = DIRECTION('',(1.,0.E+000,0.E+000)); +#82933 = DIRECTION('',(0.E+000,0.E+000,1.)); +#82934 = PCURVE('',#80476,#82935); +#82935 = DEFINITIONAL_REPRESENTATION('',(#82936),#82940); +#82936 = CIRCLE('',#82937,0.2); +#82937 = AXIS2_PLACEMENT_2D('',#82938,#82939); +#82938 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#82939 = DIRECTION('',(-1.,0.E+000)); +#82940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82941 = PCURVE('',#82559,#82942); +#82942 = DEFINITIONAL_REPRESENTATION('',(#82943),#82946); +#82943 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82944,#82945),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#80552 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#80553 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#80554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80555 = ORIENTED_EDGE('',*,*,#80556,.T.); -#80556 = EDGE_CURVE('',#80534,#80557,#80559,.T.); -#80557 = VERTEX_POINT('',#80558); -#80558 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); -#80559 = SURFACE_CURVE('',#80560,(#80564,#80571),.PCURVE_S1.); -#80560 = LINE('',#80561,#80562); -#80561 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); -#80562 = VECTOR('',#80563,1.); -#80563 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#80564 = PCURVE('',#78084,#80565); -#80565 = DEFINITIONAL_REPRESENTATION('',(#80566),#80570); -#80566 = LINE('',#80567,#80568); -#80567 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#80568 = VECTOR('',#80569,1.); -#80569 = DIRECTION('',(0.993981062721,-0.109552028512)); -#80570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80571 = PCURVE('',#80495,#80572); -#80572 = DEFINITIONAL_REPRESENTATION('',(#80573),#80577); -#80573 = LINE('',#80574,#80575); -#80574 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80575 = VECTOR('',#80576,1.); -#80576 = DIRECTION('',(1.,0.E+000)); -#80577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80578 = ORIENTED_EDGE('',*,*,#80579,.T.); -#80579 = EDGE_CURVE('',#80557,#80580,#80582,.T.); -#80580 = VERTEX_POINT('',#80581); -#80581 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.15)); -#80582 = SURFACE_CURVE('',#80583,(#80588,#80599),.PCURVE_S1.); -#80583 = CIRCLE('',#80584,5.E-002); -#80584 = AXIS2_PLACEMENT_3D('',#80585,#80586,#80587); -#80585 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); -#80586 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80587 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80588 = PCURVE('',#78084,#80589); -#80589 = DEFINITIONAL_REPRESENTATION('',(#80590),#80598); -#80590 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#80591,#80592,#80593,#80594 - ,#80595,#80596,#80597),.UNSPECIFIED.,.F.,.F.) +#82944 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#82945 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#82946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82947 = ORIENTED_EDGE('',*,*,#82948,.T.); +#82948 = EDGE_CURVE('',#82926,#82949,#82951,.T.); +#82949 = VERTEX_POINT('',#82950); +#82950 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); +#82951 = SURFACE_CURVE('',#82952,(#82956,#82963),.PCURVE_S1.); +#82952 = LINE('',#82953,#82954); +#82953 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); +#82954 = VECTOR('',#82955,1.); +#82955 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#82956 = PCURVE('',#80476,#82957); +#82957 = DEFINITIONAL_REPRESENTATION('',(#82958),#82962); +#82958 = LINE('',#82959,#82960); +#82959 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#82960 = VECTOR('',#82961,1.); +#82961 = DIRECTION('',(0.993981062721,-0.109552028512)); +#82962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82963 = PCURVE('',#82887,#82964); +#82964 = DEFINITIONAL_REPRESENTATION('',(#82965),#82969); +#82965 = LINE('',#82966,#82967); +#82966 = CARTESIAN_POINT('',(0.E+000,0.4)); +#82967 = VECTOR('',#82968,1.); +#82968 = DIRECTION('',(1.,0.E+000)); +#82969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82970 = ORIENTED_EDGE('',*,*,#82971,.T.); +#82971 = EDGE_CURVE('',#82949,#82972,#82974,.T.); +#82972 = VERTEX_POINT('',#82973); +#82973 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.15)); +#82974 = SURFACE_CURVE('',#82975,(#82980,#82991),.PCURVE_S1.); +#82975 = CIRCLE('',#82976,5.E-002); +#82976 = AXIS2_PLACEMENT_3D('',#82977,#82978,#82979); +#82977 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); +#82978 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#82979 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#82980 = PCURVE('',#80476,#82981); +#82981 = DEFINITIONAL_REPRESENTATION('',(#82982),#82990); +#82982 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82983,#82984,#82985,#82986 + ,#82987,#82988,#82989),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#80591 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#80592 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#80593 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#80594 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#80595 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#80596 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#80597 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#80598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80599 = PCURVE('',#80468,#80600); -#80600 = DEFINITIONAL_REPRESENTATION('',(#80601),#80604); -#80601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80602,#80603),.UNSPECIFIED., +#82983 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#82984 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#82985 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#82986 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#82987 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#82988 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#82989 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#82990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82991 = PCURVE('',#82860,#82992); +#82992 = DEFINITIONAL_REPRESENTATION('',(#82993),#82996); +#82993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82994,#82995),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#80602 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#80603 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80605 = ORIENTED_EDGE('',*,*,#80606,.T.); -#80606 = EDGE_CURVE('',#80580,#80607,#80609,.T.); -#80607 = VERTEX_POINT('',#80608); -#80608 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); -#80609 = SURFACE_CURVE('',#80610,(#80614,#80621),.PCURVE_S1.); -#80610 = LINE('',#80611,#80612); -#80611 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); -#80612 = VECTOR('',#80613,1.); -#80613 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#80614 = PCURVE('',#78084,#80615); -#80615 = DEFINITIONAL_REPRESENTATION('',(#80616),#80620); -#80616 = LINE('',#80617,#80618); -#80617 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#80618 = VECTOR('',#80619,1.); -#80619 = DIRECTION('',(0.E+000,-1.)); -#80620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80621 = PCURVE('',#80435,#80622); -#80622 = DEFINITIONAL_REPRESENTATION('',(#80623),#80627); -#80623 = LINE('',#80624,#80625); -#80624 = CARTESIAN_POINT('',(0.4,0.E+000)); -#80625 = VECTOR('',#80626,1.); -#80626 = DIRECTION('',(0.E+000,-1.)); -#80627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80628 = ORIENTED_EDGE('',*,*,#80629,.T.); -#80629 = EDGE_CURVE('',#80607,#80630,#80632,.T.); -#80630 = VERTEX_POINT('',#80631); -#80631 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#80632 = SURFACE_CURVE('',#80633,(#80637,#80644),.PCURVE_S1.); -#80633 = LINE('',#80634,#80635); -#80634 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#80635 = VECTOR('',#80636,1.); -#80636 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80637 = PCURVE('',#78084,#80638); -#80638 = DEFINITIONAL_REPRESENTATION('',(#80639),#80643); -#80639 = LINE('',#80640,#80641); -#80640 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#80641 = VECTOR('',#80642,1.); -#80642 = DIRECTION('',(1.,0.E+000)); -#80643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80644 = PCURVE('',#80407,#80645); -#80645 = DEFINITIONAL_REPRESENTATION('',(#80646),#80650); -#80646 = LINE('',#80647,#80648); -#80647 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80648 = VECTOR('',#80649,1.); -#80649 = DIRECTION('',(1.,0.E+000)); -#80650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80651 = ORIENTED_EDGE('',*,*,#80652,.T.); -#80652 = EDGE_CURVE('',#80630,#80653,#80655,.T.); -#80653 = VERTEX_POINT('',#80654); -#80654 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.E+000)); -#80655 = SURFACE_CURVE('',#80656,(#80660,#80667),.PCURVE_S1.); -#80656 = LINE('',#80657,#80658); -#80657 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#80658 = VECTOR('',#80659,1.); -#80659 = DIRECTION('',(0.E+000,1.,0.E+000)); -#80660 = PCURVE('',#78084,#80661); -#80661 = DEFINITIONAL_REPRESENTATION('',(#80662),#80666); -#80662 = LINE('',#80663,#80664); -#80663 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#80664 = VECTOR('',#80665,1.); -#80665 = DIRECTION('',(0.E+000,1.)); -#80666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80667 = PCURVE('',#80379,#80668); -#80668 = DEFINITIONAL_REPRESENTATION('',(#80669),#80673); -#80669 = LINE('',#80670,#80671); -#80670 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#80671 = VECTOR('',#80672,1.); -#80672 = DIRECTION('',(0.E+000,1.)); -#80673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80674 = ORIENTED_EDGE('',*,*,#80675,.T.); -#80675 = EDGE_CURVE('',#80653,#80676,#80678,.T.); -#80676 = VERTEX_POINT('',#80677); -#80677 = CARTESIAN_POINT('',(1.155,-0.746501027564,0.178089594298)); -#80678 = SURFACE_CURVE('',#80679,(#80684,#80691),.PCURVE_S1.); -#80679 = CIRCLE('',#80680,0.2); -#80680 = AXIS2_PLACEMENT_3D('',#80681,#80682,#80683); -#80681 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); -#80682 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80683 = DIRECTION('',(0.E+000,0.E+000,1.)); -#80684 = PCURVE('',#78084,#80685); -#80685 = DEFINITIONAL_REPRESENTATION('',(#80686),#80690); -#80686 = CIRCLE('',#80687,0.2); -#80687 = AXIS2_PLACEMENT_2D('',#80688,#80689); -#80688 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#80689 = DIRECTION('',(-1.,0.E+000)); -#80690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80691 = PCURVE('',#80352,#80692); -#80692 = DEFINITIONAL_REPRESENTATION('',(#80693),#80696); -#80693 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80694,#80695),.UNSPECIFIED., +#82994 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#82995 = CARTESIAN_POINT('',(0.E+000,0.4)); +#82996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#82997 = ORIENTED_EDGE('',*,*,#82998,.T.); +#82998 = EDGE_CURVE('',#82972,#82999,#83001,.T.); +#82999 = VERTEX_POINT('',#83000); +#83000 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); +#83001 = SURFACE_CURVE('',#83002,(#83006,#83013),.PCURVE_S1.); +#83002 = LINE('',#83003,#83004); +#83003 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); +#83004 = VECTOR('',#83005,1.); +#83005 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#83006 = PCURVE('',#80476,#83007); +#83007 = DEFINITIONAL_REPRESENTATION('',(#83008),#83012); +#83008 = LINE('',#83009,#83010); +#83009 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#83010 = VECTOR('',#83011,1.); +#83011 = DIRECTION('',(0.E+000,-1.)); +#83012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83013 = PCURVE('',#82827,#83014); +#83014 = DEFINITIONAL_REPRESENTATION('',(#83015),#83019); +#83015 = LINE('',#83016,#83017); +#83016 = CARTESIAN_POINT('',(0.4,0.E+000)); +#83017 = VECTOR('',#83018,1.); +#83018 = DIRECTION('',(0.E+000,-1.)); +#83019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83020 = ORIENTED_EDGE('',*,*,#83021,.T.); +#83021 = EDGE_CURVE('',#82999,#83022,#83024,.T.); +#83022 = VERTEX_POINT('',#83023); +#83023 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#83024 = SURFACE_CURVE('',#83025,(#83029,#83036),.PCURVE_S1.); +#83025 = LINE('',#83026,#83027); +#83026 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#83027 = VECTOR('',#83028,1.); +#83028 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83029 = PCURVE('',#80476,#83030); +#83030 = DEFINITIONAL_REPRESENTATION('',(#83031),#83035); +#83031 = LINE('',#83032,#83033); +#83032 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#83033 = VECTOR('',#83034,1.); +#83034 = DIRECTION('',(1.,0.E+000)); +#83035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83036 = PCURVE('',#82799,#83037); +#83037 = DEFINITIONAL_REPRESENTATION('',(#83038),#83042); +#83038 = LINE('',#83039,#83040); +#83039 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83040 = VECTOR('',#83041,1.); +#83041 = DIRECTION('',(1.,0.E+000)); +#83042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83043 = ORIENTED_EDGE('',*,*,#83044,.T.); +#83044 = EDGE_CURVE('',#83022,#83045,#83047,.T.); +#83045 = VERTEX_POINT('',#83046); +#83046 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.E+000)); +#83047 = SURFACE_CURVE('',#83048,(#83052,#83059),.PCURVE_S1.); +#83048 = LINE('',#83049,#83050); +#83049 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#83050 = VECTOR('',#83051,1.); +#83051 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83052 = PCURVE('',#80476,#83053); +#83053 = DEFINITIONAL_REPRESENTATION('',(#83054),#83058); +#83054 = LINE('',#83055,#83056); +#83055 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#83056 = VECTOR('',#83057,1.); +#83057 = DIRECTION('',(0.E+000,1.)); +#83058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83059 = PCURVE('',#82771,#83060); +#83060 = DEFINITIONAL_REPRESENTATION('',(#83061),#83065); +#83061 = LINE('',#83062,#83063); +#83062 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#83063 = VECTOR('',#83064,1.); +#83064 = DIRECTION('',(0.E+000,1.)); +#83065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83066 = ORIENTED_EDGE('',*,*,#83067,.T.); +#83067 = EDGE_CURVE('',#83045,#83068,#83070,.T.); +#83068 = VERTEX_POINT('',#83069); +#83069 = CARTESIAN_POINT('',(1.155,-0.746501027564,0.178089594298)); +#83070 = SURFACE_CURVE('',#83071,(#83076,#83083),.PCURVE_S1.); +#83071 = CIRCLE('',#83072,0.2); +#83072 = AXIS2_PLACEMENT_3D('',#83073,#83074,#83075); +#83073 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); +#83074 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83075 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83076 = PCURVE('',#80476,#83077); +#83077 = DEFINITIONAL_REPRESENTATION('',(#83078),#83082); +#83078 = CIRCLE('',#83079,0.2); +#83079 = AXIS2_PLACEMENT_2D('',#83080,#83081); +#83080 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#83081 = DIRECTION('',(-1.,0.E+000)); +#83082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83083 = PCURVE('',#82744,#83084); +#83084 = DEFINITIONAL_REPRESENTATION('',(#83085),#83088); +#83085 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83086,#83087),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#80694 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80695 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#80696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80697 = ORIENTED_EDGE('',*,*,#80698,.T.); -#80698 = EDGE_CURVE('',#80676,#80699,#80701,.T.); -#80699 = VERTEX_POINT('',#80700); -#80700 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); -#80701 = SURFACE_CURVE('',#80702,(#80706,#80713),.PCURVE_S1.); -#80702 = LINE('',#80703,#80704); -#80703 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); -#80704 = VECTOR('',#80705,1.); -#80705 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#80706 = PCURVE('',#78084,#80707); -#80707 = DEFINITIONAL_REPRESENTATION('',(#80708),#80712); -#80708 = LINE('',#80709,#80710); -#80709 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#80710 = VECTOR('',#80711,1.); -#80711 = DIRECTION('',(-0.993981062721,0.109552028512)); -#80712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80713 = PCURVE('',#80323,#80714); -#80714 = DEFINITIONAL_REPRESENTATION('',(#80715),#80719); -#80715 = LINE('',#80716,#80717); -#80716 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80717 = VECTOR('',#80718,1.); -#80718 = DIRECTION('',(1.,0.E+000)); -#80719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80720 = ORIENTED_EDGE('',*,*,#80721,.T.); -#80721 = EDGE_CURVE('',#80699,#80204,#80722,.T.); -#80722 = SURFACE_CURVE('',#80723,(#80728,#80739),.PCURVE_S1.); -#80723 = CIRCLE('',#80724,5.E-002); -#80724 = AXIS2_PLACEMENT_3D('',#80725,#80726,#80727); -#80725 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#80726 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#80727 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#80728 = PCURVE('',#78084,#80729); -#80729 = DEFINITIONAL_REPRESENTATION('',(#80730),#80738); -#80730 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#80731,#80732,#80733,#80734 - ,#80735,#80736,#80737),.UNSPECIFIED.,.F.,.F.) +#83086 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83087 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#83088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83089 = ORIENTED_EDGE('',*,*,#83090,.T.); +#83090 = EDGE_CURVE('',#83068,#83091,#83093,.T.); +#83091 = VERTEX_POINT('',#83092); +#83092 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); +#83093 = SURFACE_CURVE('',#83094,(#83098,#83105),.PCURVE_S1.); +#83094 = LINE('',#83095,#83096); +#83095 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); +#83096 = VECTOR('',#83097,1.); +#83097 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#83098 = PCURVE('',#80476,#83099); +#83099 = DEFINITIONAL_REPRESENTATION('',(#83100),#83104); +#83100 = LINE('',#83101,#83102); +#83101 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#83102 = VECTOR('',#83103,1.); +#83103 = DIRECTION('',(-0.993981062721,0.109552028512)); +#83104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83105 = PCURVE('',#82715,#83106); +#83106 = DEFINITIONAL_REPRESENTATION('',(#83107),#83111); +#83107 = LINE('',#83108,#83109); +#83108 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83109 = VECTOR('',#83110,1.); +#83110 = DIRECTION('',(1.,0.E+000)); +#83111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83112 = ORIENTED_EDGE('',*,*,#83113,.T.); +#83113 = EDGE_CURVE('',#83091,#82596,#83114,.T.); +#83114 = SURFACE_CURVE('',#83115,(#83120,#83131),.PCURVE_S1.); +#83115 = CIRCLE('',#83116,5.E-002); +#83116 = AXIS2_PLACEMENT_3D('',#83117,#83118,#83119); +#83117 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#83118 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83119 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83120 = PCURVE('',#80476,#83121); +#83121 = DEFINITIONAL_REPRESENTATION('',(#83122),#83130); +#83122 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83123,#83124,#83125,#83126 + ,#83127,#83128,#83129),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#80731 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#80732 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#80733 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#80734 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#80735 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#80736 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#80737 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#80738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80739 = PCURVE('',#80242,#80740); -#80740 = DEFINITIONAL_REPRESENTATION('',(#80741),#80744); -#80741 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80742,#80743),.UNSPECIFIED., +#83123 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#83124 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#83125 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#83126 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#83127 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#83128 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#83129 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#83130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83131 = PCURVE('',#82634,#83132); +#83132 = DEFINITIONAL_REPRESENTATION('',(#83133),#83136); +#83133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83134,#83135),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#80742 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#80743 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#80744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80745 = ORIENTED_EDGE('',*,*,#80203,.T.); -#80746 = ADVANCED_FACE('',(#80747),#80242,.F.); -#80747 = FACE_BOUND('',#80748,.F.); -#80748 = EDGE_LOOP('',(#80749,#80750,#80751,#80771)); -#80749 = ORIENTED_EDGE('',*,*,#80226,.F.); -#80750 = ORIENTED_EDGE('',*,*,#80280,.F.); -#80751 = ORIENTED_EDGE('',*,*,#80752,.T.); -#80752 = EDGE_CURVE('',#80281,#80699,#80753,.T.); -#80753 = SURFACE_CURVE('',#80754,(#80758,#80764),.PCURVE_S1.); -#80754 = LINE('',#80755,#80756); -#80755 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#80756 = VECTOR('',#80757,1.); -#80757 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80758 = PCURVE('',#80242,#80759); -#80759 = DEFINITIONAL_REPRESENTATION('',(#80760),#80763); -#80760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80761,#80762),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80761 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#80762 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#80763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80764 = PCURVE('',#80323,#80765); -#80765 = DEFINITIONAL_REPRESENTATION('',(#80766),#80770); -#80766 = LINE('',#80767,#80768); -#80767 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80768 = VECTOR('',#80769,1.); -#80769 = DIRECTION('',(0.E+000,1.)); -#80770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80771 = ORIENTED_EDGE('',*,*,#80721,.T.); -#80772 = ADVANCED_FACE('',(#80773),#80323,.T.); -#80773 = FACE_BOUND('',#80774,.T.); -#80774 = EDGE_LOOP('',(#80775,#80776,#80777,#80797)); -#80775 = ORIENTED_EDGE('',*,*,#80752,.T.); -#80776 = ORIENTED_EDGE('',*,*,#80698,.F.); -#80777 = ORIENTED_EDGE('',*,*,#80778,.F.); -#80778 = EDGE_CURVE('',#80308,#80676,#80779,.T.); -#80779 = SURFACE_CURVE('',#80780,(#80784,#80791),.PCURVE_S1.); -#80780 = LINE('',#80781,#80782); -#80781 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); -#80782 = VECTOR('',#80783,1.); -#80783 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80784 = PCURVE('',#80323,#80785); -#80785 = DEFINITIONAL_REPRESENTATION('',(#80786),#80790); -#80786 = LINE('',#80787,#80788); -#80787 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#80788 = VECTOR('',#80789,1.); -#80789 = DIRECTION('',(0.E+000,1.)); -#80790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#83134 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#83135 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#83136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#80791 = PCURVE('',#80352,#80792); -#80792 = DEFINITIONAL_REPRESENTATION('',(#80793),#80796); -#80793 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80794,#80795),.UNSPECIFIED., +#83137 = ORIENTED_EDGE('',*,*,#82595,.T.); +#83138 = ADVANCED_FACE('',(#83139),#82634,.F.); +#83139 = FACE_BOUND('',#83140,.F.); +#83140 = EDGE_LOOP('',(#83141,#83142,#83143,#83163)); +#83141 = ORIENTED_EDGE('',*,*,#82618,.F.); +#83142 = ORIENTED_EDGE('',*,*,#82672,.F.); +#83143 = ORIENTED_EDGE('',*,*,#83144,.T.); +#83144 = EDGE_CURVE('',#82673,#83091,#83145,.T.); +#83145 = SURFACE_CURVE('',#83146,(#83150,#83156),.PCURVE_S1.); +#83146 = LINE('',#83147,#83148); +#83147 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#83148 = VECTOR('',#83149,1.); +#83149 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83150 = PCURVE('',#82634,#83151); +#83151 = DEFINITIONAL_REPRESENTATION('',(#83152),#83155); +#83152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83153,#83154),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#83153 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#83154 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#83155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83156 = PCURVE('',#82715,#83157); +#83157 = DEFINITIONAL_REPRESENTATION('',(#83158),#83162); +#83158 = LINE('',#83159,#83160); +#83159 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83160 = VECTOR('',#83161,1.); +#83161 = DIRECTION('',(0.E+000,1.)); +#83162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83163 = ORIENTED_EDGE('',*,*,#83113,.T.); +#83164 = ADVANCED_FACE('',(#83165),#82715,.T.); +#83165 = FACE_BOUND('',#83166,.T.); +#83166 = EDGE_LOOP('',(#83167,#83168,#83169,#83189)); +#83167 = ORIENTED_EDGE('',*,*,#83144,.T.); +#83168 = ORIENTED_EDGE('',*,*,#83090,.F.); +#83169 = ORIENTED_EDGE('',*,*,#83170,.F.); +#83170 = EDGE_CURVE('',#82700,#83068,#83171,.T.); +#83171 = SURFACE_CURVE('',#83172,(#83176,#83183),.PCURVE_S1.); +#83172 = LINE('',#83173,#83174); +#83173 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); +#83174 = VECTOR('',#83175,1.); +#83175 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83176 = PCURVE('',#82715,#83177); +#83177 = DEFINITIONAL_REPRESENTATION('',(#83178),#83182); +#83178 = LINE('',#83179,#83180); +#83179 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#83180 = VECTOR('',#83181,1.); +#83181 = DIRECTION('',(0.E+000,1.)); +#83182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83183 = PCURVE('',#82744,#83184); +#83184 = DEFINITIONAL_REPRESENTATION('',(#83185),#83188); +#83185 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83186,#83187),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80794 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#80795 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#80796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80797 = ORIENTED_EDGE('',*,*,#80307,.T.); -#80798 = ADVANCED_FACE('',(#80799),#80352,.T.); -#80799 = FACE_BOUND('',#80800,.T.); -#80800 = EDGE_LOOP('',(#80801,#80802,#80803,#80846)); -#80801 = ORIENTED_EDGE('',*,*,#80778,.T.); -#80802 = ORIENTED_EDGE('',*,*,#80675,.F.); -#80803 = ORIENTED_EDGE('',*,*,#80804,.F.); -#80804 = EDGE_CURVE('',#80336,#80653,#80805,.T.); -#80805 = SURFACE_CURVE('',#80806,(#80810,#80839),.PCURVE_S1.); -#80806 = LINE('',#80807,#80808); -#80807 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); -#80808 = VECTOR('',#80809,1.); -#80809 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80810 = PCURVE('',#80352,#80811); -#80811 = DEFINITIONAL_REPRESENTATION('',(#80812),#80838); -#80812 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80813,#80814,#80815,#80816, - #80817,#80818,#80819,#80820,#80821,#80822,#80823,#80824,#80825, - #80826,#80827,#80828,#80829,#80830,#80831,#80832,#80833,#80834, - #80835,#80836,#80837),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#83186 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#83187 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#83188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83189 = ORIENTED_EDGE('',*,*,#82699,.T.); +#83190 = ADVANCED_FACE('',(#83191),#82744,.T.); +#83191 = FACE_BOUND('',#83192,.T.); +#83192 = EDGE_LOOP('',(#83193,#83194,#83195,#83238)); +#83193 = ORIENTED_EDGE('',*,*,#83170,.T.); +#83194 = ORIENTED_EDGE('',*,*,#83067,.F.); +#83195 = ORIENTED_EDGE('',*,*,#83196,.F.); +#83196 = EDGE_CURVE('',#82728,#83045,#83197,.T.); +#83197 = SURFACE_CURVE('',#83198,(#83202,#83231),.PCURVE_S1.); +#83198 = LINE('',#83199,#83200); +#83199 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); +#83200 = VECTOR('',#83201,1.); +#83201 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83202 = PCURVE('',#82744,#83203); +#83203 = DEFINITIONAL_REPRESENTATION('',(#83204),#83230); +#83204 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#83205,#83206,#83207,#83208, + #83209,#83210,#83211,#83212,#83213,#83214,#83215,#83216,#83217, + #83218,#83219,#83220,#83221,#83222,#83223,#83224,#83225,#83226, + #83227,#83228,#83229),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -100245,133 +103234,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#80813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80814 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003)); -#80815 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002)); -#80816 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); -#80817 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002)); -#80818 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002)); -#80819 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002)); -#80820 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); -#80821 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); -#80822 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); -#80823 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); -#80824 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); -#80825 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); -#80826 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); -#80827 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); -#80828 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); -#80829 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); -#80830 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); -#80831 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); -#80832 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); -#80833 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); -#80834 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); -#80835 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); -#80836 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); -#80837 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80839 = PCURVE('',#80379,#80840); -#80840 = DEFINITIONAL_REPRESENTATION('',(#80841),#80845); -#80841 = LINE('',#80842,#80843); -#80842 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#80843 = VECTOR('',#80844,1.); -#80844 = DIRECTION('',(-1.,0.E+000)); -#80845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80846 = ORIENTED_EDGE('',*,*,#80335,.T.); -#80847 = ADVANCED_FACE('',(#80848),#80379,.T.); -#80848 = FACE_BOUND('',#80849,.T.); -#80849 = EDGE_LOOP('',(#80850,#80851,#80852,#80873)); -#80850 = ORIENTED_EDGE('',*,*,#80804,.T.); -#80851 = ORIENTED_EDGE('',*,*,#80652,.F.); -#80852 = ORIENTED_EDGE('',*,*,#80853,.F.); -#80853 = EDGE_CURVE('',#80364,#80630,#80854,.T.); -#80854 = SURFACE_CURVE('',#80855,(#80859,#80866),.PCURVE_S1.); -#80855 = LINE('',#80856,#80857); -#80856 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#80857 = VECTOR('',#80858,1.); -#80858 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80859 = PCURVE('',#80379,#80860); -#80860 = DEFINITIONAL_REPRESENTATION('',(#80861),#80865); -#80861 = LINE('',#80862,#80863); -#80862 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80863 = VECTOR('',#80864,1.); -#80864 = DIRECTION('',(-1.,0.E+000)); -#80865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80866 = PCURVE('',#80407,#80867); -#80867 = DEFINITIONAL_REPRESENTATION('',(#80868),#80872); -#80868 = LINE('',#80869,#80870); -#80869 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80870 = VECTOR('',#80871,1.); -#80871 = DIRECTION('',(0.E+000,1.)); -#80872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80873 = ORIENTED_EDGE('',*,*,#80363,.T.); -#80874 = ADVANCED_FACE('',(#80875),#80407,.T.); -#80875 = FACE_BOUND('',#80876,.T.); -#80876 = EDGE_LOOP('',(#80877,#80878,#80879,#80900)); -#80877 = ORIENTED_EDGE('',*,*,#80853,.T.); -#80878 = ORIENTED_EDGE('',*,*,#80629,.F.); -#80879 = ORIENTED_EDGE('',*,*,#80880,.F.); -#80880 = EDGE_CURVE('',#80392,#80607,#80881,.T.); -#80881 = SURFACE_CURVE('',#80882,(#80886,#80893),.PCURVE_S1.); -#80882 = LINE('',#80883,#80884); -#80883 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#80884 = VECTOR('',#80885,1.); -#80885 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80886 = PCURVE('',#80407,#80887); -#80887 = DEFINITIONAL_REPRESENTATION('',(#80888),#80892); -#80888 = LINE('',#80889,#80890); -#80889 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#80890 = VECTOR('',#80891,1.); -#80891 = DIRECTION('',(0.E+000,1.)); -#80892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80893 = PCURVE('',#80435,#80894); -#80894 = DEFINITIONAL_REPRESENTATION('',(#80895),#80899); -#80895 = LINE('',#80896,#80897); -#80896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80897 = VECTOR('',#80898,1.); -#80898 = DIRECTION('',(1.,0.E+000)); -#80899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80900 = ORIENTED_EDGE('',*,*,#80391,.T.); -#80901 = ADVANCED_FACE('',(#80902),#80435,.T.); -#80902 = FACE_BOUND('',#80903,.T.); -#80903 = EDGE_LOOP('',(#80904,#80905,#80906,#80949)); -#80904 = ORIENTED_EDGE('',*,*,#80880,.T.); -#80905 = ORIENTED_EDGE('',*,*,#80606,.F.); -#80906 = ORIENTED_EDGE('',*,*,#80907,.F.); -#80907 = EDGE_CURVE('',#80420,#80580,#80908,.T.); -#80908 = SURFACE_CURVE('',#80909,(#80913,#80920),.PCURVE_S1.); -#80909 = LINE('',#80910,#80911); -#80910 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); -#80911 = VECTOR('',#80912,1.); -#80912 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80913 = PCURVE('',#80435,#80914); -#80914 = DEFINITIONAL_REPRESENTATION('',(#80915),#80919); -#80915 = LINE('',#80916,#80917); -#80916 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#80917 = VECTOR('',#80918,1.); -#80918 = DIRECTION('',(1.,0.E+000)); -#80919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80920 = PCURVE('',#80468,#80921); -#80921 = DEFINITIONAL_REPRESENTATION('',(#80922),#80948); -#80922 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#80923,#80924,#80925,#80926, - #80927,#80928,#80929,#80930,#80931,#80932,#80933,#80934,#80935, - #80936,#80937,#80938,#80939,#80940,#80941,#80942,#80943,#80944, - #80945,#80946,#80947),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#83205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83206 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003)); +#83207 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002)); +#83208 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); +#83209 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002)); +#83210 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002)); +#83211 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002)); +#83212 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); +#83213 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); +#83214 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); +#83215 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); +#83216 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); +#83217 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); +#83218 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); +#83219 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); +#83220 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); +#83221 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); +#83222 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); +#83223 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); +#83224 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); +#83225 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); +#83226 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); +#83227 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); +#83228 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); +#83229 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83231 = PCURVE('',#82771,#83232); +#83232 = DEFINITIONAL_REPRESENTATION('',(#83233),#83237); +#83233 = LINE('',#83234,#83235); +#83234 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#83235 = VECTOR('',#83236,1.); +#83236 = DIRECTION('',(-1.,0.E+000)); +#83237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83238 = ORIENTED_EDGE('',*,*,#82727,.T.); +#83239 = ADVANCED_FACE('',(#83240),#82771,.T.); +#83240 = FACE_BOUND('',#83241,.T.); +#83241 = EDGE_LOOP('',(#83242,#83243,#83244,#83265)); +#83242 = ORIENTED_EDGE('',*,*,#83196,.T.); +#83243 = ORIENTED_EDGE('',*,*,#83044,.F.); +#83244 = ORIENTED_EDGE('',*,*,#83245,.F.); +#83245 = EDGE_CURVE('',#82756,#83022,#83246,.T.); +#83246 = SURFACE_CURVE('',#83247,(#83251,#83258),.PCURVE_S1.); +#83247 = LINE('',#83248,#83249); +#83248 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#83249 = VECTOR('',#83250,1.); +#83250 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83251 = PCURVE('',#82771,#83252); +#83252 = DEFINITIONAL_REPRESENTATION('',(#83253),#83257); +#83253 = LINE('',#83254,#83255); +#83254 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83255 = VECTOR('',#83256,1.); +#83256 = DIRECTION('',(-1.,0.E+000)); +#83257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83258 = PCURVE('',#82799,#83259); +#83259 = DEFINITIONAL_REPRESENTATION('',(#83260),#83264); +#83260 = LINE('',#83261,#83262); +#83261 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83262 = VECTOR('',#83263,1.); +#83263 = DIRECTION('',(0.E+000,1.)); +#83264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83265 = ORIENTED_EDGE('',*,*,#82755,.T.); +#83266 = ADVANCED_FACE('',(#83267),#82799,.T.); +#83267 = FACE_BOUND('',#83268,.T.); +#83268 = EDGE_LOOP('',(#83269,#83270,#83271,#83292)); +#83269 = ORIENTED_EDGE('',*,*,#83245,.T.); +#83270 = ORIENTED_EDGE('',*,*,#83021,.F.); +#83271 = ORIENTED_EDGE('',*,*,#83272,.F.); +#83272 = EDGE_CURVE('',#82784,#82999,#83273,.T.); +#83273 = SURFACE_CURVE('',#83274,(#83278,#83285),.PCURVE_S1.); +#83274 = LINE('',#83275,#83276); +#83275 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#83276 = VECTOR('',#83277,1.); +#83277 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83278 = PCURVE('',#82799,#83279); +#83279 = DEFINITIONAL_REPRESENTATION('',(#83280),#83284); +#83280 = LINE('',#83281,#83282); +#83281 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#83282 = VECTOR('',#83283,1.); +#83283 = DIRECTION('',(0.E+000,1.)); +#83284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83285 = PCURVE('',#82827,#83286); +#83286 = DEFINITIONAL_REPRESENTATION('',(#83287),#83291); +#83287 = LINE('',#83288,#83289); +#83288 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83289 = VECTOR('',#83290,1.); +#83290 = DIRECTION('',(1.,0.E+000)); +#83291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83292 = ORIENTED_EDGE('',*,*,#82783,.T.); +#83293 = ADVANCED_FACE('',(#83294),#82827,.T.); +#83294 = FACE_BOUND('',#83295,.T.); +#83295 = EDGE_LOOP('',(#83296,#83297,#83298,#83341)); +#83296 = ORIENTED_EDGE('',*,*,#83272,.T.); +#83297 = ORIENTED_EDGE('',*,*,#82998,.F.); +#83298 = ORIENTED_EDGE('',*,*,#83299,.F.); +#83299 = EDGE_CURVE('',#82812,#82972,#83300,.T.); +#83300 = SURFACE_CURVE('',#83301,(#83305,#83312),.PCURVE_S1.); +#83301 = LINE('',#83302,#83303); +#83302 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); +#83303 = VECTOR('',#83304,1.); +#83304 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83305 = PCURVE('',#82827,#83306); +#83306 = DEFINITIONAL_REPRESENTATION('',(#83307),#83311); +#83307 = LINE('',#83308,#83309); +#83308 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#83309 = VECTOR('',#83310,1.); +#83310 = DIRECTION('',(1.,0.E+000)); +#83311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83312 = PCURVE('',#82860,#83313); +#83313 = DEFINITIONAL_REPRESENTATION('',(#83314),#83340); +#83314 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#83315,#83316,#83317,#83318, + #83319,#83320,#83321,#83322,#83323,#83324,#83325,#83326,#83327, + #83328,#83329,#83330,#83331,#83332,#83333,#83334,#83335,#83336, + #83337,#83338,#83339),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -100379,945 +103368,945 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#80923 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80924 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003)); -#80925 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); -#80926 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); -#80927 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002)); -#80928 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002)); -#80929 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002)); -#80930 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); -#80931 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); -#80932 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); -#80933 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); -#80934 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); -#80935 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); -#80936 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); -#80937 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); -#80938 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); -#80939 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); -#80940 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); -#80941 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#80942 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); -#80943 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); -#80944 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); -#80945 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); -#80946 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); -#80947 = CARTESIAN_POINT('',(0.E+000,0.4)); -#80948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80949 = ORIENTED_EDGE('',*,*,#80419,.T.); -#80950 = ADVANCED_FACE('',(#80951),#80468,.F.); -#80951 = FACE_BOUND('',#80952,.F.); -#80952 = EDGE_LOOP('',(#80953,#80954,#80955,#80975)); -#80953 = ORIENTED_EDGE('',*,*,#80907,.F.); -#80954 = ORIENTED_EDGE('',*,*,#80447,.F.); -#80955 = ORIENTED_EDGE('',*,*,#80956,.T.); -#80956 = EDGE_CURVE('',#80448,#80557,#80957,.T.); -#80957 = SURFACE_CURVE('',#80958,(#80962,#80968),.PCURVE_S1.); -#80958 = LINE('',#80959,#80960); -#80959 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#80960 = VECTOR('',#80961,1.); -#80961 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80962 = PCURVE('',#80468,#80963); -#80963 = DEFINITIONAL_REPRESENTATION('',(#80964),#80967); -#80964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80965,#80966),.UNSPECIFIED., +#83315 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83316 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003)); +#83317 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); +#83318 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); +#83319 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002)); +#83320 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002)); +#83321 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002)); +#83322 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); +#83323 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); +#83324 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); +#83325 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); +#83326 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); +#83327 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); +#83328 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); +#83329 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); +#83330 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); +#83331 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); +#83332 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); +#83333 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#83334 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); +#83335 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); +#83336 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); +#83337 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); +#83338 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); +#83339 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83341 = ORIENTED_EDGE('',*,*,#82811,.T.); +#83342 = ADVANCED_FACE('',(#83343),#82860,.F.); +#83343 = FACE_BOUND('',#83344,.F.); +#83344 = EDGE_LOOP('',(#83345,#83346,#83347,#83367)); +#83345 = ORIENTED_EDGE('',*,*,#83299,.F.); +#83346 = ORIENTED_EDGE('',*,*,#82839,.F.); +#83347 = ORIENTED_EDGE('',*,*,#83348,.T.); +#83348 = EDGE_CURVE('',#82840,#82949,#83349,.T.); +#83349 = SURFACE_CURVE('',#83350,(#83354,#83360),.PCURVE_S1.); +#83350 = LINE('',#83351,#83352); +#83351 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#83352 = VECTOR('',#83353,1.); +#83353 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83354 = PCURVE('',#82860,#83355); +#83355 = DEFINITIONAL_REPRESENTATION('',(#83356),#83359); +#83356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83357,#83358),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80965 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#80966 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#80967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80968 = PCURVE('',#80495,#80969); -#80969 = DEFINITIONAL_REPRESENTATION('',(#80970),#80974); -#80970 = LINE('',#80971,#80972); -#80971 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#80972 = VECTOR('',#80973,1.); -#80973 = DIRECTION('',(0.E+000,1.)); -#80974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#83357 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#83358 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#83359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83360 = PCURVE('',#82887,#83361); +#83361 = DEFINITIONAL_REPRESENTATION('',(#83362),#83366); +#83362 = LINE('',#83363,#83364); +#83363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83364 = VECTOR('',#83365,1.); +#83365 = DIRECTION('',(0.E+000,1.)); +#83366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83367 = ORIENTED_EDGE('',*,*,#82971,.T.); +#83368 = ADVANCED_FACE('',(#83369),#82887,.T.); +#83369 = FACE_BOUND('',#83370,.T.); +#83370 = EDGE_LOOP('',(#83371,#83372,#83373,#83393)); +#83371 = ORIENTED_EDGE('',*,*,#83348,.T.); +#83372 = ORIENTED_EDGE('',*,*,#82948,.F.); +#83373 = ORIENTED_EDGE('',*,*,#83374,.F.); +#83374 = EDGE_CURVE('',#82872,#82926,#83375,.T.); +#83375 = SURFACE_CURVE('',#83376,(#83380,#83387),.PCURVE_S1.); +#83376 = LINE('',#83377,#83378); +#83377 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); +#83378 = VECTOR('',#83379,1.); +#83379 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83380 = PCURVE('',#82887,#83381); +#83381 = DEFINITIONAL_REPRESENTATION('',(#83382),#83386); +#83382 = LINE('',#83383,#83384); +#83383 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#83384 = VECTOR('',#83385,1.); +#83385 = DIRECTION('',(0.E+000,1.)); +#83386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83387 = PCURVE('',#82559,#83388); +#83388 = DEFINITIONAL_REPRESENTATION('',(#83389),#83392); +#83389 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83390,#83391),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#83390 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#83391 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#83392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83393 = ORIENTED_EDGE('',*,*,#82871,.T.); +#83394 = ADVANCED_FACE('',(#83395),#82559,.T.); +#83395 = FACE_BOUND('',#83396,.T.); +#83396 = EDGE_LOOP('',(#83397,#83398,#83399,#83400)); +#83397 = ORIENTED_EDGE('',*,*,#83374,.T.); +#83398 = ORIENTED_EDGE('',*,*,#82925,.F.); +#83399 = ORIENTED_EDGE('',*,*,#82543,.F.); +#83400 = ORIENTED_EDGE('',*,*,#82899,.T.); +#83401 = ADVANCED_FACE('',(#83402),#81614,.T.); +#83402 = FACE_BOUND('',#83403,.T.); +#83403 = EDGE_LOOP('',(#83404,#83405,#83428,#83455)); +#83404 = ORIENTED_EDGE('',*,*,#81600,.T.); +#83405 = ORIENTED_EDGE('',*,*,#83406,.T.); +#83406 = EDGE_CURVE('',#80714,#83407,#83409,.T.); +#83407 = VERTEX_POINT('',#83408); +#83408 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#83409 = SURFACE_CURVE('',#83410,(#83414,#83421),.PCURVE_S1.); +#83410 = LINE('',#83411,#83412); +#83411 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#83412 = VECTOR('',#83413,1.); +#83413 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83414 = PCURVE('',#81614,#83415); +#83415 = DEFINITIONAL_REPRESENTATION('',(#83416),#83420); +#83416 = LINE('',#83417,#83418); +#83417 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83418 = VECTOR('',#83419,1.); +#83419 = DIRECTION('',(0.E+000,1.)); +#83420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83421 = PCURVE('',#80729,#83422); +#83422 = DEFINITIONAL_REPRESENTATION('',(#83423),#83427); +#83423 = LINE('',#83424,#83425); +#83424 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#83425 = VECTOR('',#83426,1.); +#83426 = DIRECTION('',(0.E+000,1.)); +#83427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83428 = ORIENTED_EDGE('',*,*,#83429,.T.); +#83429 = EDGE_CURVE('',#83407,#83430,#83432,.T.); +#83430 = VERTEX_POINT('',#83431); +#83431 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); +#83432 = SURFACE_CURVE('',#83433,(#83437,#83444),.PCURVE_S1.); +#83433 = LINE('',#83434,#83435); +#83434 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#83435 = VECTOR('',#83436,1.); +#83436 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83437 = PCURVE('',#81614,#83438); +#83438 = DEFINITIONAL_REPRESENTATION('',(#83439),#83443); +#83439 = LINE('',#83440,#83441); +#83440 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83441 = VECTOR('',#83442,1.); +#83442 = DIRECTION('',(-1.,0.E+000)); +#83443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83444 = PCURVE('',#83445,#83450); +#83445 = CYLINDRICAL_SURFACE('',#83446,5.E-002); +#83446 = AXIS2_PLACEMENT_3D('',#83447,#83448,#83449); +#83447 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#83448 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83449 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83450 = DEFINITIONAL_REPRESENTATION('',(#83451),#83454); +#83451 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83452,#83453),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#83452 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#83453 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#83454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#80975 = ORIENTED_EDGE('',*,*,#80579,.T.); -#80976 = ADVANCED_FACE('',(#80977),#80495,.T.); -#80977 = FACE_BOUND('',#80978,.T.); -#80978 = EDGE_LOOP('',(#80979,#80980,#80981,#81001)); -#80979 = ORIENTED_EDGE('',*,*,#80956,.T.); -#80980 = ORIENTED_EDGE('',*,*,#80556,.F.); -#80981 = ORIENTED_EDGE('',*,*,#80982,.F.); -#80982 = EDGE_CURVE('',#80480,#80534,#80983,.T.); -#80983 = SURFACE_CURVE('',#80984,(#80988,#80995),.PCURVE_S1.); -#80984 = LINE('',#80985,#80986); -#80985 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); -#80986 = VECTOR('',#80987,1.); -#80987 = DIRECTION('',(1.,0.E+000,0.E+000)); -#80988 = PCURVE('',#80495,#80989); -#80989 = DEFINITIONAL_REPRESENTATION('',(#80990),#80994); -#80990 = LINE('',#80991,#80992); -#80991 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#80992 = VECTOR('',#80993,1.); -#80993 = DIRECTION('',(0.E+000,1.)); -#80994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#80995 = PCURVE('',#80167,#80996); -#80996 = DEFINITIONAL_REPRESENTATION('',(#80997),#81000); -#80997 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#80998,#80999),.UNSPECIFIED., +#83455 = ORIENTED_EDGE('',*,*,#83456,.F.); +#83456 = EDGE_CURVE('',#80630,#83430,#83457,.T.); +#83457 = SURFACE_CURVE('',#83458,(#83462,#83469),.PCURVE_S1.); +#83458 = LINE('',#83459,#83460); +#83459 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); +#83460 = VECTOR('',#83461,1.); +#83461 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83462 = PCURVE('',#81614,#83463); +#83463 = DEFINITIONAL_REPRESENTATION('',(#83464),#83468); +#83464 = LINE('',#83465,#83466); +#83465 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#83466 = VECTOR('',#83467,1.); +#83467 = DIRECTION('',(0.E+000,1.)); +#83468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83469 = PCURVE('',#80673,#83470); +#83470 = DEFINITIONAL_REPRESENTATION('',(#83471),#83475); +#83471 = LINE('',#83472,#83473); +#83472 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#83473 = VECTOR('',#83474,1.); +#83474 = DIRECTION('',(0.E+000,1.)); +#83475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83476 = ADVANCED_FACE('',(#83477),#80701,.T.); +#83477 = FACE_BOUND('',#83478,.T.); +#83478 = EDGE_LOOP('',(#83479,#83480,#83503,#83530)); +#83479 = ORIENTED_EDGE('',*,*,#80685,.F.); +#83480 = ORIENTED_EDGE('',*,*,#83481,.F.); +#83481 = EDGE_CURVE('',#83482,#80658,#83484,.T.); +#83482 = VERTEX_POINT('',#83483); +#83483 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); +#83484 = SURFACE_CURVE('',#83485,(#83489,#83496),.PCURVE_S1.); +#83485 = LINE('',#83486,#83487); +#83486 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); +#83487 = VECTOR('',#83488,1.); +#83488 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#83489 = PCURVE('',#80701,#83490); +#83490 = DEFINITIONAL_REPRESENTATION('',(#83491),#83495); +#83491 = LINE('',#83492,#83493); +#83492 = CARTESIAN_POINT('',(0.4,0.E+000)); +#83493 = VECTOR('',#83494,1.); +#83494 = DIRECTION('',(0.E+000,-1.)); +#83495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83496 = PCURVE('',#80673,#83497); +#83497 = DEFINITIONAL_REPRESENTATION('',(#83498),#83502); +#83498 = LINE('',#83499,#83500); +#83499 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#83500 = VECTOR('',#83501,1.); +#83501 = DIRECTION('',(0.E+000,-1.)); +#83502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83503 = ORIENTED_EDGE('',*,*,#83504,.F.); +#83504 = EDGE_CURVE('',#83505,#83482,#83507,.T.); +#83505 = VERTEX_POINT('',#83506); +#83506 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#83507 = SURFACE_CURVE('',#83508,(#83512,#83519),.PCURVE_S1.); +#83508 = LINE('',#83509,#83510); +#83509 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#83510 = VECTOR('',#83511,1.); +#83511 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83512 = PCURVE('',#80701,#83513); +#83513 = DEFINITIONAL_REPRESENTATION('',(#83514),#83518); +#83514 = LINE('',#83515,#83516); +#83515 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83516 = VECTOR('',#83517,1.); +#83517 = DIRECTION('',(1.,0.E+000)); +#83518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83519 = PCURVE('',#83520,#83525); +#83520 = CYLINDRICAL_SURFACE('',#83521,0.2); +#83521 = AXIS2_PLACEMENT_3D('',#83522,#83523,#83524); +#83522 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#83523 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83524 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83525 = DEFINITIONAL_REPRESENTATION('',(#83526),#83529); +#83526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83527,#83528),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#80998 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#80999 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#81000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#83527 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#83528 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#83529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83530 = ORIENTED_EDGE('',*,*,#83531,.T.); +#83531 = EDGE_CURVE('',#83505,#80686,#83532,.T.); +#83532 = SURFACE_CURVE('',#83533,(#83537,#83544),.PCURVE_S1.); +#83533 = LINE('',#83534,#83535); +#83534 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#83535 = VECTOR('',#83536,1.); +#83536 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#83537 = PCURVE('',#80701,#83538); +#83538 = DEFINITIONAL_REPRESENTATION('',(#83539),#83543); +#83539 = LINE('',#83540,#83541); +#83540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83541 = VECTOR('',#83542,1.); +#83542 = DIRECTION('',(0.E+000,-1.)); +#83543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83544 = PCURVE('',#80729,#83545); +#83545 = DEFINITIONAL_REPRESENTATION('',(#83546),#83550); +#83546 = LINE('',#83547,#83548); +#83547 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#83548 = VECTOR('',#83549,1.); +#83549 = DIRECTION('',(0.E+000,-1.)); +#83550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#81001 = ORIENTED_EDGE('',*,*,#80479,.T.); -#81002 = ADVANCED_FACE('',(#81003),#80167,.T.); -#81003 = FACE_BOUND('',#81004,.T.); -#81004 = EDGE_LOOP('',(#81005,#81006,#81007,#81008)); -#81005 = ORIENTED_EDGE('',*,*,#80982,.T.); -#81006 = ORIENTED_EDGE('',*,*,#80533,.F.); -#81007 = ORIENTED_EDGE('',*,*,#80151,.F.); -#81008 = ORIENTED_EDGE('',*,*,#80507,.T.); -#81009 = ADVANCED_FACE('',(#81010),#79222,.T.); -#81010 = FACE_BOUND('',#81011,.T.); -#81011 = EDGE_LOOP('',(#81012,#81013,#81036,#81063)); -#81012 = ORIENTED_EDGE('',*,*,#79208,.T.); -#81013 = ORIENTED_EDGE('',*,*,#81014,.T.); -#81014 = EDGE_CURVE('',#78322,#81015,#81017,.T.); -#81015 = VERTEX_POINT('',#81016); -#81016 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#81017 = SURFACE_CURVE('',#81018,(#81022,#81029),.PCURVE_S1.); -#81018 = LINE('',#81019,#81020); -#81019 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#81020 = VECTOR('',#81021,1.); -#81021 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81022 = PCURVE('',#79222,#81023); -#81023 = DEFINITIONAL_REPRESENTATION('',(#81024),#81028); -#81024 = LINE('',#81025,#81026); -#81025 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81026 = VECTOR('',#81027,1.); -#81027 = DIRECTION('',(0.E+000,1.)); -#81028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81029 = PCURVE('',#78337,#81030); -#81030 = DEFINITIONAL_REPRESENTATION('',(#81031),#81035); -#81031 = LINE('',#81032,#81033); -#81032 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#81033 = VECTOR('',#81034,1.); -#81034 = DIRECTION('',(0.E+000,1.)); -#81035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81036 = ORIENTED_EDGE('',*,*,#81037,.T.); -#81037 = EDGE_CURVE('',#81015,#81038,#81040,.T.); -#81038 = VERTEX_POINT('',#81039); -#81039 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); -#81040 = SURFACE_CURVE('',#81041,(#81045,#81052),.PCURVE_S1.); -#81041 = LINE('',#81042,#81043); -#81042 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#81043 = VECTOR('',#81044,1.); -#81044 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81045 = PCURVE('',#79222,#81046); -#81046 = DEFINITIONAL_REPRESENTATION('',(#81047),#81051); -#81047 = LINE('',#81048,#81049); -#81048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81049 = VECTOR('',#81050,1.); -#81050 = DIRECTION('',(-1.,0.E+000)); -#81051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81052 = PCURVE('',#81053,#81058); -#81053 = CYLINDRICAL_SURFACE('',#81054,5.E-002); -#81054 = AXIS2_PLACEMENT_3D('',#81055,#81056,#81057); -#81055 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#81056 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81057 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81058 = DEFINITIONAL_REPRESENTATION('',(#81059),#81062); -#81059 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81060,#81061),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81060 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#81061 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#81062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81063 = ORIENTED_EDGE('',*,*,#81064,.F.); -#81064 = EDGE_CURVE('',#78238,#81038,#81065,.T.); -#81065 = SURFACE_CURVE('',#81066,(#81070,#81077),.PCURVE_S1.); -#81066 = LINE('',#81067,#81068); -#81067 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); -#81068 = VECTOR('',#81069,1.); -#81069 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81070 = PCURVE('',#79222,#81071); -#81071 = DEFINITIONAL_REPRESENTATION('',(#81072),#81076); -#81072 = LINE('',#81073,#81074); -#81073 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#81074 = VECTOR('',#81075,1.); -#81075 = DIRECTION('',(0.E+000,1.)); -#81076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81077 = PCURVE('',#78281,#81078); -#81078 = DEFINITIONAL_REPRESENTATION('',(#81079),#81083); -#81079 = LINE('',#81080,#81081); -#81080 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#81081 = VECTOR('',#81082,1.); -#81082 = DIRECTION('',(0.E+000,1.)); -#81083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81084 = ADVANCED_FACE('',(#81085),#78309,.T.); -#81085 = FACE_BOUND('',#81086,.T.); -#81086 = EDGE_LOOP('',(#81087,#81088,#81111,#81138)); -#81087 = ORIENTED_EDGE('',*,*,#78293,.F.); -#81088 = ORIENTED_EDGE('',*,*,#81089,.F.); -#81089 = EDGE_CURVE('',#81090,#78266,#81092,.T.); -#81090 = VERTEX_POINT('',#81091); -#81091 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); -#81092 = SURFACE_CURVE('',#81093,(#81097,#81104),.PCURVE_S1.); -#81093 = LINE('',#81094,#81095); -#81094 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); -#81095 = VECTOR('',#81096,1.); -#81096 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#81097 = PCURVE('',#78309,#81098); -#81098 = DEFINITIONAL_REPRESENTATION('',(#81099),#81103); -#81099 = LINE('',#81100,#81101); -#81100 = CARTESIAN_POINT('',(0.4,0.E+000)); -#81101 = VECTOR('',#81102,1.); -#81102 = DIRECTION('',(0.E+000,-1.)); -#81103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81104 = PCURVE('',#78281,#81105); -#81105 = DEFINITIONAL_REPRESENTATION('',(#81106),#81110); -#81106 = LINE('',#81107,#81108); -#81107 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#81108 = VECTOR('',#81109,1.); -#81109 = DIRECTION('',(0.E+000,-1.)); -#81110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81111 = ORIENTED_EDGE('',*,*,#81112,.F.); -#81112 = EDGE_CURVE('',#81113,#81090,#81115,.T.); -#81113 = VERTEX_POINT('',#81114); -#81114 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#81115 = SURFACE_CURVE('',#81116,(#81120,#81127),.PCURVE_S1.); -#81116 = LINE('',#81117,#81118); -#81117 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#81118 = VECTOR('',#81119,1.); -#81119 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81120 = PCURVE('',#78309,#81121); -#81121 = DEFINITIONAL_REPRESENTATION('',(#81122),#81126); -#81122 = LINE('',#81123,#81124); -#81123 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81124 = VECTOR('',#81125,1.); -#81125 = DIRECTION('',(1.,0.E+000)); -#81126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81127 = PCURVE('',#81128,#81133); -#81128 = CYLINDRICAL_SURFACE('',#81129,0.2); -#81129 = AXIS2_PLACEMENT_3D('',#81130,#81131,#81132); -#81130 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#81131 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81132 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81133 = DEFINITIONAL_REPRESENTATION('',(#81134),#81137); -#81134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81135,#81136),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81135 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#81136 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#81137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81138 = ORIENTED_EDGE('',*,*,#81139,.T.); -#81139 = EDGE_CURVE('',#81113,#78294,#81140,.T.); -#81140 = SURFACE_CURVE('',#81141,(#81145,#81152),.PCURVE_S1.); -#81141 = LINE('',#81142,#81143); -#81142 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#81143 = VECTOR('',#81144,1.); -#81144 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#81145 = PCURVE('',#78309,#81146); -#81146 = DEFINITIONAL_REPRESENTATION('',(#81147),#81151); -#81147 = LINE('',#81148,#81149); -#81148 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81149 = VECTOR('',#81150,1.); -#81150 = DIRECTION('',(0.E+000,-1.)); -#81151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81152 = PCURVE('',#78337,#81153); -#81153 = DEFINITIONAL_REPRESENTATION('',(#81154),#81158); -#81154 = LINE('',#81155,#81156); -#81155 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#81156 = VECTOR('',#81157,1.); -#81157 = DIRECTION('',(0.E+000,-1.)); -#81158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81159 = ADVANCED_FACE('',(#81160),#78337,.F.); -#81160 = FACE_BOUND('',#81161,.T.); -#81161 = EDGE_LOOP('',(#81162,#81163,#81164,#81165,#81188,#81216,#81248, - #81276,#81304,#81332,#81360,#81388)); -#81162 = ORIENTED_EDGE('',*,*,#81014,.F.); -#81163 = ORIENTED_EDGE('',*,*,#78321,.T.); -#81164 = ORIENTED_EDGE('',*,*,#81139,.F.); -#81165 = ORIENTED_EDGE('',*,*,#81166,.F.); -#81166 = EDGE_CURVE('',#81167,#81113,#81169,.T.); -#81167 = VERTEX_POINT('',#81168); -#81168 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); -#81169 = SURFACE_CURVE('',#81170,(#81175,#81182),.PCURVE_S1.); -#81170 = CIRCLE('',#81171,0.2); -#81171 = AXIS2_PLACEMENT_3D('',#81172,#81173,#81174); -#81172 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#81173 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81174 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81175 = PCURVE('',#78337,#81176); -#81176 = DEFINITIONAL_REPRESENTATION('',(#81177),#81181); -#81177 = CIRCLE('',#81178,0.2); -#81178 = AXIS2_PLACEMENT_2D('',#81179,#81180); -#81179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81180 = DIRECTION('',(1.,0.E+000)); -#81181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81182 = PCURVE('',#81128,#81183); -#81183 = DEFINITIONAL_REPRESENTATION('',(#81184),#81187); -#81184 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81185,#81186),.UNSPECIFIED., +#83551 = ADVANCED_FACE('',(#83552),#80729,.F.); +#83552 = FACE_BOUND('',#83553,.T.); +#83553 = EDGE_LOOP('',(#83554,#83555,#83556,#83557,#83580,#83608,#83640, + #83668,#83696,#83724,#83752,#83780)); +#83554 = ORIENTED_EDGE('',*,*,#83406,.F.); +#83555 = ORIENTED_EDGE('',*,*,#80713,.T.); +#83556 = ORIENTED_EDGE('',*,*,#83531,.F.); +#83557 = ORIENTED_EDGE('',*,*,#83558,.F.); +#83558 = EDGE_CURVE('',#83559,#83505,#83561,.T.); +#83559 = VERTEX_POINT('',#83560); +#83560 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); +#83561 = SURFACE_CURVE('',#83562,(#83567,#83574),.PCURVE_S1.); +#83562 = CIRCLE('',#83563,0.2); +#83563 = AXIS2_PLACEMENT_3D('',#83564,#83565,#83566); +#83564 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#83565 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83566 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83567 = PCURVE('',#80729,#83568); +#83568 = DEFINITIONAL_REPRESENTATION('',(#83569),#83573); +#83569 = CIRCLE('',#83570,0.2); +#83570 = AXIS2_PLACEMENT_2D('',#83571,#83572); +#83571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83572 = DIRECTION('',(1.,0.E+000)); +#83573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83574 = PCURVE('',#83520,#83575); +#83575 = DEFINITIONAL_REPRESENTATION('',(#83576),#83579); +#83576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83577,#83578),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#81185 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#81186 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#81187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81188 = ORIENTED_EDGE('',*,*,#81189,.F.); -#81189 = EDGE_CURVE('',#81190,#81167,#81192,.T.); -#81190 = VERTEX_POINT('',#81191); -#81191 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#81192 = SURFACE_CURVE('',#81193,(#81197,#81204),.PCURVE_S1.); -#81193 = LINE('',#81194,#81195); -#81194 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#81195 = VECTOR('',#81196,1.); -#81196 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#81197 = PCURVE('',#78337,#81198); -#81198 = DEFINITIONAL_REPRESENTATION('',(#81199),#81203); -#81199 = LINE('',#81200,#81201); -#81200 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#81201 = VECTOR('',#81202,1.); -#81202 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#81203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81204 = PCURVE('',#81205,#81210); -#81205 = PLANE('',#81206); -#81206 = AXIS2_PLACEMENT_3D('',#81207,#81208,#81209); -#81207 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#81208 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#81209 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#81210 = DEFINITIONAL_REPRESENTATION('',(#81211),#81215); -#81211 = LINE('',#81212,#81213); -#81212 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81213 = VECTOR('',#81214,1.); -#81214 = DIRECTION('',(1.,0.E+000)); -#81215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81216 = ORIENTED_EDGE('',*,*,#81217,.F.); -#81217 = EDGE_CURVE('',#81218,#81190,#81220,.T.); -#81218 = VERTEX_POINT('',#81219); -#81219 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); -#81220 = SURFACE_CURVE('',#81221,(#81226,#81237),.PCURVE_S1.); -#81221 = CIRCLE('',#81222,5.E-002); -#81222 = AXIS2_PLACEMENT_3D('',#81223,#81224,#81225); -#81223 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#81224 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#81225 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81226 = PCURVE('',#78337,#81227); -#81227 = DEFINITIONAL_REPRESENTATION('',(#81228),#81236); -#81228 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#81229,#81230,#81231,#81232 - ,#81233,#81234,#81235),.UNSPECIFIED.,.F.,.F.) +#83577 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#83578 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#83579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83580 = ORIENTED_EDGE('',*,*,#83581,.F.); +#83581 = EDGE_CURVE('',#83582,#83559,#83584,.T.); +#83582 = VERTEX_POINT('',#83583); +#83583 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#83584 = SURFACE_CURVE('',#83585,(#83589,#83596),.PCURVE_S1.); +#83585 = LINE('',#83586,#83587); +#83586 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#83587 = VECTOR('',#83588,1.); +#83588 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#83589 = PCURVE('',#80729,#83590); +#83590 = DEFINITIONAL_REPRESENTATION('',(#83591),#83595); +#83591 = LINE('',#83592,#83593); +#83592 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#83593 = VECTOR('',#83594,1.); +#83594 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#83595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83596 = PCURVE('',#83597,#83602); +#83597 = PLANE('',#83598); +#83598 = AXIS2_PLACEMENT_3D('',#83599,#83600,#83601); +#83599 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#83600 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#83601 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#83602 = DEFINITIONAL_REPRESENTATION('',(#83603),#83607); +#83603 = LINE('',#83604,#83605); +#83604 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83605 = VECTOR('',#83606,1.); +#83606 = DIRECTION('',(1.,0.E+000)); +#83607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83608 = ORIENTED_EDGE('',*,*,#83609,.F.); +#83609 = EDGE_CURVE('',#83610,#83582,#83612,.T.); +#83610 = VERTEX_POINT('',#83611); +#83611 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); +#83612 = SURFACE_CURVE('',#83613,(#83618,#83629),.PCURVE_S1.); +#83613 = CIRCLE('',#83614,5.E-002); +#83614 = AXIS2_PLACEMENT_3D('',#83615,#83616,#83617); +#83615 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#83616 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83617 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83618 = PCURVE('',#80729,#83619); +#83619 = DEFINITIONAL_REPRESENTATION('',(#83620),#83628); +#83620 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83621,#83622,#83623,#83624 + ,#83625,#83626,#83627),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#81229 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#81230 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#81231 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#81232 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#81233 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#81234 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#81235 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#81236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81237 = PCURVE('',#81238,#81243); -#81238 = CYLINDRICAL_SURFACE('',#81239,5.E-002); -#81239 = AXIS2_PLACEMENT_3D('',#81240,#81241,#81242); -#81240 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#81241 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81242 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81243 = DEFINITIONAL_REPRESENTATION('',(#81244),#81247); -#81244 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81245,#81246),.UNSPECIFIED., +#83621 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#83622 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#83623 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#83624 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#83625 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#83626 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#83627 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#83628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83629 = PCURVE('',#83630,#83635); +#83630 = CYLINDRICAL_SURFACE('',#83631,5.E-002); +#83631 = AXIS2_PLACEMENT_3D('',#83632,#83633,#83634); +#83632 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#83633 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83634 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83635 = DEFINITIONAL_REPRESENTATION('',(#83636),#83639); +#83636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83637,#83638),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#81245 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#81246 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#81247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81248 = ORIENTED_EDGE('',*,*,#81249,.F.); -#81249 = EDGE_CURVE('',#81250,#81218,#81252,.T.); -#81250 = VERTEX_POINT('',#81251); -#81251 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#81252 = SURFACE_CURVE('',#81253,(#81257,#81264),.PCURVE_S1.); -#81253 = LINE('',#81254,#81255); -#81254 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#81255 = VECTOR('',#81256,1.); -#81256 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#81257 = PCURVE('',#78337,#81258); -#81258 = DEFINITIONAL_REPRESENTATION('',(#81259),#81263); -#81259 = LINE('',#81260,#81261); -#81260 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#81261 = VECTOR('',#81262,1.); -#81262 = DIRECTION('',(0.E+000,-1.)); -#81263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81264 = PCURVE('',#81265,#81270); -#81265 = PLANE('',#81266); -#81266 = AXIS2_PLACEMENT_3D('',#81267,#81268,#81269); -#81267 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#81268 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81269 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81270 = DEFINITIONAL_REPRESENTATION('',(#81271),#81275); -#81271 = LINE('',#81272,#81273); -#81272 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81273 = VECTOR('',#81274,1.); -#81274 = DIRECTION('',(0.E+000,-1.)); -#81275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81276 = ORIENTED_EDGE('',*,*,#81277,.F.); -#81277 = EDGE_CURVE('',#81278,#81250,#81280,.T.); -#81278 = VERTEX_POINT('',#81279); -#81279 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81280 = SURFACE_CURVE('',#81281,(#81285,#81292),.PCURVE_S1.); -#81281 = LINE('',#81282,#81283); -#81282 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81283 = VECTOR('',#81284,1.); -#81284 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81285 = PCURVE('',#78337,#81286); -#81286 = DEFINITIONAL_REPRESENTATION('',(#81287),#81291); -#81287 = LINE('',#81288,#81289); -#81288 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#81289 = VECTOR('',#81290,1.); -#81290 = DIRECTION('',(-1.,0.E+000)); -#81291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81292 = PCURVE('',#81293,#81298); -#81293 = PLANE('',#81294); -#81294 = AXIS2_PLACEMENT_3D('',#81295,#81296,#81297); -#81295 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81296 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81297 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81298 = DEFINITIONAL_REPRESENTATION('',(#81299),#81303); -#81299 = LINE('',#81300,#81301); -#81300 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81301 = VECTOR('',#81302,1.); -#81302 = DIRECTION('',(1.,0.E+000)); -#81303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81304 = ORIENTED_EDGE('',*,*,#81305,.F.); -#81305 = EDGE_CURVE('',#81306,#81278,#81308,.T.); -#81306 = VERTEX_POINT('',#81307); -#81307 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); -#81308 = SURFACE_CURVE('',#81309,(#81313,#81320),.PCURVE_S1.); -#81309 = LINE('',#81310,#81311); -#81310 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81311 = VECTOR('',#81312,1.); -#81312 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81313 = PCURVE('',#78337,#81314); -#81314 = DEFINITIONAL_REPRESENTATION('',(#81315),#81319); -#81315 = LINE('',#81316,#81317); -#81316 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#81317 = VECTOR('',#81318,1.); -#81318 = DIRECTION('',(0.E+000,1.)); -#81319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81320 = PCURVE('',#81321,#81326); -#81321 = PLANE('',#81322); -#81322 = AXIS2_PLACEMENT_3D('',#81323,#81324,#81325); -#81323 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81324 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81325 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#81326 = DEFINITIONAL_REPRESENTATION('',(#81327),#81331); -#81327 = LINE('',#81328,#81329); -#81328 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81329 = VECTOR('',#81330,1.); -#81330 = DIRECTION('',(0.E+000,1.)); -#81331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81332 = ORIENTED_EDGE('',*,*,#81333,.F.); -#81333 = EDGE_CURVE('',#81334,#81306,#81336,.T.); -#81334 = VERTEX_POINT('',#81335); -#81335 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); -#81336 = SURFACE_CURVE('',#81337,(#81342,#81349),.PCURVE_S1.); -#81337 = CIRCLE('',#81338,0.2); -#81338 = AXIS2_PLACEMENT_3D('',#81339,#81340,#81341); -#81339 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#81340 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81341 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81342 = PCURVE('',#78337,#81343); -#81343 = DEFINITIONAL_REPRESENTATION('',(#81344),#81348); -#81344 = CIRCLE('',#81345,0.2); -#81345 = AXIS2_PLACEMENT_2D('',#81346,#81347); -#81346 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#81347 = DIRECTION('',(1.,0.E+000)); -#81348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81349 = PCURVE('',#81350,#81355); -#81350 = CYLINDRICAL_SURFACE('',#81351,0.2); -#81351 = AXIS2_PLACEMENT_3D('',#81352,#81353,#81354); -#81352 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#81353 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81354 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81355 = DEFINITIONAL_REPRESENTATION('',(#81356),#81359); -#81356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81357,#81358),.UNSPECIFIED., +#83637 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#83638 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#83639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83640 = ORIENTED_EDGE('',*,*,#83641,.F.); +#83641 = EDGE_CURVE('',#83642,#83610,#83644,.T.); +#83642 = VERTEX_POINT('',#83643); +#83643 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#83644 = SURFACE_CURVE('',#83645,(#83649,#83656),.PCURVE_S1.); +#83645 = LINE('',#83646,#83647); +#83646 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#83647 = VECTOR('',#83648,1.); +#83648 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#83649 = PCURVE('',#80729,#83650); +#83650 = DEFINITIONAL_REPRESENTATION('',(#83651),#83655); +#83651 = LINE('',#83652,#83653); +#83652 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#83653 = VECTOR('',#83654,1.); +#83654 = DIRECTION('',(0.E+000,-1.)); +#83655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83656 = PCURVE('',#83657,#83662); +#83657 = PLANE('',#83658); +#83658 = AXIS2_PLACEMENT_3D('',#83659,#83660,#83661); +#83659 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#83660 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83661 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83662 = DEFINITIONAL_REPRESENTATION('',(#83663),#83667); +#83663 = LINE('',#83664,#83665); +#83664 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83665 = VECTOR('',#83666,1.); +#83666 = DIRECTION('',(0.E+000,-1.)); +#83667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83668 = ORIENTED_EDGE('',*,*,#83669,.F.); +#83669 = EDGE_CURVE('',#83670,#83642,#83672,.T.); +#83670 = VERTEX_POINT('',#83671); +#83671 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#83672 = SURFACE_CURVE('',#83673,(#83677,#83684),.PCURVE_S1.); +#83673 = LINE('',#83674,#83675); +#83674 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#83675 = VECTOR('',#83676,1.); +#83676 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83677 = PCURVE('',#80729,#83678); +#83678 = DEFINITIONAL_REPRESENTATION('',(#83679),#83683); +#83679 = LINE('',#83680,#83681); +#83680 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#83681 = VECTOR('',#83682,1.); +#83682 = DIRECTION('',(-1.,0.E+000)); +#83683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83684 = PCURVE('',#83685,#83690); +#83685 = PLANE('',#83686); +#83686 = AXIS2_PLACEMENT_3D('',#83687,#83688,#83689); +#83687 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#83688 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83689 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83690 = DEFINITIONAL_REPRESENTATION('',(#83691),#83695); +#83691 = LINE('',#83692,#83693); +#83692 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83693 = VECTOR('',#83694,1.); +#83694 = DIRECTION('',(1.,0.E+000)); +#83695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83696 = ORIENTED_EDGE('',*,*,#83697,.F.); +#83697 = EDGE_CURVE('',#83698,#83670,#83700,.T.); +#83698 = VERTEX_POINT('',#83699); +#83699 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); +#83700 = SURFACE_CURVE('',#83701,(#83705,#83712),.PCURVE_S1.); +#83701 = LINE('',#83702,#83703); +#83702 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#83703 = VECTOR('',#83704,1.); +#83704 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83705 = PCURVE('',#80729,#83706); +#83706 = DEFINITIONAL_REPRESENTATION('',(#83707),#83711); +#83707 = LINE('',#83708,#83709); +#83708 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#83709 = VECTOR('',#83710,1.); +#83710 = DIRECTION('',(0.E+000,1.)); +#83711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83712 = PCURVE('',#83713,#83718); +#83713 = PLANE('',#83714); +#83714 = AXIS2_PLACEMENT_3D('',#83715,#83716,#83717); +#83715 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#83716 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83717 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83718 = DEFINITIONAL_REPRESENTATION('',(#83719),#83723); +#83719 = LINE('',#83720,#83721); +#83720 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83721 = VECTOR('',#83722,1.); +#83722 = DIRECTION('',(0.E+000,1.)); +#83723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83724 = ORIENTED_EDGE('',*,*,#83725,.F.); +#83725 = EDGE_CURVE('',#83726,#83698,#83728,.T.); +#83726 = VERTEX_POINT('',#83727); +#83727 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); +#83728 = SURFACE_CURVE('',#83729,(#83734,#83741),.PCURVE_S1.); +#83729 = CIRCLE('',#83730,0.2); +#83730 = AXIS2_PLACEMENT_3D('',#83731,#83732,#83733); +#83731 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#83732 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83733 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83734 = PCURVE('',#80729,#83735); +#83735 = DEFINITIONAL_REPRESENTATION('',(#83736),#83740); +#83736 = CIRCLE('',#83737,0.2); +#83737 = AXIS2_PLACEMENT_2D('',#83738,#83739); +#83738 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#83739 = DIRECTION('',(1.,0.E+000)); +#83740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83741 = PCURVE('',#83742,#83747); +#83742 = CYLINDRICAL_SURFACE('',#83743,0.2); +#83743 = AXIS2_PLACEMENT_3D('',#83744,#83745,#83746); +#83744 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#83745 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83746 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83747 = DEFINITIONAL_REPRESENTATION('',(#83748),#83751); +#83748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83749,#83750),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#81357 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#81358 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#81359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81360 = ORIENTED_EDGE('',*,*,#81361,.F.); -#81361 = EDGE_CURVE('',#81362,#81334,#81364,.T.); -#81362 = VERTEX_POINT('',#81363); -#81363 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#81364 = SURFACE_CURVE('',#81365,(#81369,#81376),.PCURVE_S1.); -#81365 = LINE('',#81366,#81367); -#81366 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#81367 = VECTOR('',#81368,1.); -#81368 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#81369 = PCURVE('',#78337,#81370); -#81370 = DEFINITIONAL_REPRESENTATION('',(#81371),#81375); -#81371 = LINE('',#81372,#81373); -#81372 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); -#81373 = VECTOR('',#81374,1.); -#81374 = DIRECTION('',(0.993981062721,0.109552028512)); -#81375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81376 = PCURVE('',#81377,#81382); -#81377 = PLANE('',#81378); -#81378 = AXIS2_PLACEMENT_3D('',#81379,#81380,#81381); -#81379 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#81380 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#81381 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#81382 = DEFINITIONAL_REPRESENTATION('',(#81383),#81387); -#81383 = LINE('',#81384,#81385); -#81384 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81385 = VECTOR('',#81386,1.); -#81386 = DIRECTION('',(1.,0.E+000)); -#81387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81388 = ORIENTED_EDGE('',*,*,#81389,.F.); -#81389 = EDGE_CURVE('',#81015,#81362,#81390,.T.); -#81390 = SURFACE_CURVE('',#81391,(#81396,#81407),.PCURVE_S1.); -#81391 = CIRCLE('',#81392,5.E-002); -#81392 = AXIS2_PLACEMENT_3D('',#81393,#81394,#81395); -#81393 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#81394 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#81395 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81396 = PCURVE('',#78337,#81397); -#81397 = DEFINITIONAL_REPRESENTATION('',(#81398),#81406); -#81398 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#81399,#81400,#81401,#81402 - ,#81403,#81404,#81405),.UNSPECIFIED.,.F.,.F.) +#83749 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#83750 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#83751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83752 = ORIENTED_EDGE('',*,*,#83753,.F.); +#83753 = EDGE_CURVE('',#83754,#83726,#83756,.T.); +#83754 = VERTEX_POINT('',#83755); +#83755 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#83756 = SURFACE_CURVE('',#83757,(#83761,#83768),.PCURVE_S1.); +#83757 = LINE('',#83758,#83759); +#83758 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#83759 = VECTOR('',#83760,1.); +#83760 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#83761 = PCURVE('',#80729,#83762); +#83762 = DEFINITIONAL_REPRESENTATION('',(#83763),#83767); +#83763 = LINE('',#83764,#83765); +#83764 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); +#83765 = VECTOR('',#83766,1.); +#83766 = DIRECTION('',(0.993981062721,0.109552028512)); +#83767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83768 = PCURVE('',#83769,#83774); +#83769 = PLANE('',#83770); +#83770 = AXIS2_PLACEMENT_3D('',#83771,#83772,#83773); +#83771 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#83772 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#83773 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#83774 = DEFINITIONAL_REPRESENTATION('',(#83775),#83779); +#83775 = LINE('',#83776,#83777); +#83776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#83777 = VECTOR('',#83778,1.); +#83778 = DIRECTION('',(1.,0.E+000)); +#83779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83780 = ORIENTED_EDGE('',*,*,#83781,.F.); +#83781 = EDGE_CURVE('',#83407,#83754,#83782,.T.); +#83782 = SURFACE_CURVE('',#83783,(#83788,#83799),.PCURVE_S1.); +#83783 = CIRCLE('',#83784,5.E-002); +#83784 = AXIS2_PLACEMENT_3D('',#83785,#83786,#83787); +#83785 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#83786 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83787 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83788 = PCURVE('',#80729,#83789); +#83789 = DEFINITIONAL_REPRESENTATION('',(#83790),#83798); +#83790 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83791,#83792,#83793,#83794 + ,#83795,#83796,#83797),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#81399 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#81400 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#81401 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#81402 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#81403 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#81404 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#81405 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#81406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81407 = PCURVE('',#81053,#81408); -#81408 = DEFINITIONAL_REPRESENTATION('',(#81409),#81412); -#81409 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81410,#81411),.UNSPECIFIED., +#83791 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#83792 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#83793 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#83794 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#83795 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#83796 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#83797 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#83798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83799 = PCURVE('',#83445,#83800); +#83800 = DEFINITIONAL_REPRESENTATION('',(#83801),#83804); +#83801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83802,#83803),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#81410 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#81411 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#81412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81413 = ADVANCED_FACE('',(#81414),#78281,.T.); -#81414 = FACE_BOUND('',#81415,.T.); -#81415 = EDGE_LOOP('',(#81416,#81417,#81418,#81445,#81468,#81491,#81514, - #81537,#81560,#81587,#81610,#81631)); -#81416 = ORIENTED_EDGE('',*,*,#78265,.F.); -#81417 = ORIENTED_EDGE('',*,*,#81064,.T.); -#81418 = ORIENTED_EDGE('',*,*,#81419,.T.); -#81419 = EDGE_CURVE('',#81038,#81420,#81422,.T.); -#81420 = VERTEX_POINT('',#81421); -#81421 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); -#81422 = SURFACE_CURVE('',#81423,(#81428,#81439),.PCURVE_S1.); -#81423 = CIRCLE('',#81424,5.E-002); -#81424 = AXIS2_PLACEMENT_3D('',#81425,#81426,#81427); -#81425 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#81426 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#81427 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81428 = PCURVE('',#78281,#81429); -#81429 = DEFINITIONAL_REPRESENTATION('',(#81430),#81438); -#81430 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#81431,#81432,#81433,#81434 - ,#81435,#81436,#81437),.UNSPECIFIED.,.F.,.F.) +#83802 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#83803 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#83804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83805 = ADVANCED_FACE('',(#83806),#80673,.T.); +#83806 = FACE_BOUND('',#83807,.T.); +#83807 = EDGE_LOOP('',(#83808,#83809,#83810,#83837,#83860,#83883,#83906, + #83929,#83952,#83979,#84002,#84023)); +#83808 = ORIENTED_EDGE('',*,*,#80657,.F.); +#83809 = ORIENTED_EDGE('',*,*,#83456,.T.); +#83810 = ORIENTED_EDGE('',*,*,#83811,.T.); +#83811 = EDGE_CURVE('',#83430,#83812,#83814,.T.); +#83812 = VERTEX_POINT('',#83813); +#83813 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); +#83814 = SURFACE_CURVE('',#83815,(#83820,#83831),.PCURVE_S1.); +#83815 = CIRCLE('',#83816,5.E-002); +#83816 = AXIS2_PLACEMENT_3D('',#83817,#83818,#83819); +#83817 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#83818 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83819 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83820 = PCURVE('',#80673,#83821); +#83821 = DEFINITIONAL_REPRESENTATION('',(#83822),#83830); +#83822 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83823,#83824,#83825,#83826 + ,#83827,#83828,#83829),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#81431 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#81432 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#81433 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#81434 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#81435 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#81436 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#81437 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#81438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81439 = PCURVE('',#81053,#81440); -#81440 = DEFINITIONAL_REPRESENTATION('',(#81441),#81444); -#81441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81442,#81443),.UNSPECIFIED., +#83823 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#83824 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#83825 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#83826 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#83827 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#83828 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#83829 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#83830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83831 = PCURVE('',#83445,#83832); +#83832 = DEFINITIONAL_REPRESENTATION('',(#83833),#83836); +#83833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83834,#83835),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#81442 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#81443 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#81444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81445 = ORIENTED_EDGE('',*,*,#81446,.T.); -#81446 = EDGE_CURVE('',#81420,#81447,#81449,.T.); -#81447 = VERTEX_POINT('',#81448); -#81448 = CARTESIAN_POINT('',(1.155,0.746501027564,0.178089594298)); -#81449 = SURFACE_CURVE('',#81450,(#81454,#81461),.PCURVE_S1.); -#81450 = LINE('',#81451,#81452); -#81451 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); -#81452 = VECTOR('',#81453,1.); -#81453 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#81454 = PCURVE('',#78281,#81455); -#81455 = DEFINITIONAL_REPRESENTATION('',(#81456),#81460); -#81456 = LINE('',#81457,#81458); -#81457 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); -#81458 = VECTOR('',#81459,1.); -#81459 = DIRECTION('',(0.993981062721,0.109552028512)); -#81460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81461 = PCURVE('',#81377,#81462); -#81462 = DEFINITIONAL_REPRESENTATION('',(#81463),#81467); -#81463 = LINE('',#81464,#81465); -#81464 = CARTESIAN_POINT('',(0.E+000,0.4)); -#81465 = VECTOR('',#81466,1.); -#81466 = DIRECTION('',(1.,0.E+000)); -#81467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81468 = ORIENTED_EDGE('',*,*,#81469,.T.); -#81469 = EDGE_CURVE('',#81447,#81470,#81472,.T.); -#81470 = VERTEX_POINT('',#81471); -#81471 = CARTESIAN_POINT('',(1.155,0.945297240108,0.E+000)); -#81472 = SURFACE_CURVE('',#81473,(#81478,#81485),.PCURVE_S1.); -#81473 = CIRCLE('',#81474,0.2); -#81474 = AXIS2_PLACEMENT_3D('',#81475,#81476,#81477); -#81475 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); -#81476 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81477 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81478 = PCURVE('',#78281,#81479); -#81479 = DEFINITIONAL_REPRESENTATION('',(#81480),#81484); -#81480 = CIRCLE('',#81481,0.2); -#81481 = AXIS2_PLACEMENT_2D('',#81482,#81483); -#81482 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#81483 = DIRECTION('',(1.,0.E+000)); -#81484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81485 = PCURVE('',#81350,#81486); -#81486 = DEFINITIONAL_REPRESENTATION('',(#81487),#81490); -#81487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81488,#81489),.UNSPECIFIED., +#83834 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#83835 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#83836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83837 = ORIENTED_EDGE('',*,*,#83838,.T.); +#83838 = EDGE_CURVE('',#83812,#83839,#83841,.T.); +#83839 = VERTEX_POINT('',#83840); +#83840 = CARTESIAN_POINT('',(1.155,0.746501027564,0.178089594298)); +#83841 = SURFACE_CURVE('',#83842,(#83846,#83853),.PCURVE_S1.); +#83842 = LINE('',#83843,#83844); +#83843 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); +#83844 = VECTOR('',#83845,1.); +#83845 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#83846 = PCURVE('',#80673,#83847); +#83847 = DEFINITIONAL_REPRESENTATION('',(#83848),#83852); +#83848 = LINE('',#83849,#83850); +#83849 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); +#83850 = VECTOR('',#83851,1.); +#83851 = DIRECTION('',(0.993981062721,0.109552028512)); +#83852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83853 = PCURVE('',#83769,#83854); +#83854 = DEFINITIONAL_REPRESENTATION('',(#83855),#83859); +#83855 = LINE('',#83856,#83857); +#83856 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83857 = VECTOR('',#83858,1.); +#83858 = DIRECTION('',(1.,0.E+000)); +#83859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83860 = ORIENTED_EDGE('',*,*,#83861,.T.); +#83861 = EDGE_CURVE('',#83839,#83862,#83864,.T.); +#83862 = VERTEX_POINT('',#83863); +#83863 = CARTESIAN_POINT('',(1.155,0.945297240108,0.E+000)); +#83864 = SURFACE_CURVE('',#83865,(#83870,#83877),.PCURVE_S1.); +#83865 = CIRCLE('',#83866,0.2); +#83866 = AXIS2_PLACEMENT_3D('',#83867,#83868,#83869); +#83867 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); +#83868 = DIRECTION('',(1.,0.E+000,0.E+000)); +#83869 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#83870 = PCURVE('',#80673,#83871); +#83871 = DEFINITIONAL_REPRESENTATION('',(#83872),#83876); +#83872 = CIRCLE('',#83873,0.2); +#83873 = AXIS2_PLACEMENT_2D('',#83874,#83875); +#83874 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#83875 = DIRECTION('',(1.,0.E+000)); +#83876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83877 = PCURVE('',#83742,#83878); +#83878 = DEFINITIONAL_REPRESENTATION('',(#83879),#83882); +#83879 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83880,#83881),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#81488 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#81489 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#81490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81491 = ORIENTED_EDGE('',*,*,#81492,.T.); -#81492 = EDGE_CURVE('',#81470,#81493,#81495,.T.); -#81493 = VERTEX_POINT('',#81494); -#81494 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#81495 = SURFACE_CURVE('',#81496,(#81500,#81507),.PCURVE_S1.); -#81496 = LINE('',#81497,#81498); -#81497 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#81498 = VECTOR('',#81499,1.); -#81499 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81500 = PCURVE('',#78281,#81501); -#81501 = DEFINITIONAL_REPRESENTATION('',(#81502),#81506); -#81502 = LINE('',#81503,#81504); -#81503 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#81504 = VECTOR('',#81505,1.); -#81505 = DIRECTION('',(0.E+000,1.)); -#81506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81507 = PCURVE('',#81321,#81508); -#81508 = DEFINITIONAL_REPRESENTATION('',(#81509),#81513); -#81509 = LINE('',#81510,#81511); -#81510 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#81511 = VECTOR('',#81512,1.); -#81512 = DIRECTION('',(0.E+000,1.)); -#81513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81514 = ORIENTED_EDGE('',*,*,#81515,.T.); -#81515 = EDGE_CURVE('',#81493,#81516,#81518,.T.); -#81516 = VERTEX_POINT('',#81517); -#81517 = CARTESIAN_POINT('',(1.155,1.17,0.15)); -#81518 = SURFACE_CURVE('',#81519,(#81523,#81530),.PCURVE_S1.); -#81519 = LINE('',#81520,#81521); -#81520 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#81521 = VECTOR('',#81522,1.); -#81522 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81523 = PCURVE('',#78281,#81524); -#81524 = DEFINITIONAL_REPRESENTATION('',(#81525),#81529); -#81525 = LINE('',#81526,#81527); -#81526 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#81527 = VECTOR('',#81528,1.); -#81528 = DIRECTION('',(-1.,0.E+000)); -#81529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81530 = PCURVE('',#81293,#81531); -#81531 = DEFINITIONAL_REPRESENTATION('',(#81532),#81536); -#81532 = LINE('',#81533,#81534); -#81533 = CARTESIAN_POINT('',(0.E+000,0.4)); -#81534 = VECTOR('',#81535,1.); -#81535 = DIRECTION('',(1.,0.E+000)); -#81536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81537 = ORIENTED_EDGE('',*,*,#81538,.T.); -#81538 = EDGE_CURVE('',#81516,#81539,#81541,.T.); -#81539 = VERTEX_POINT('',#81540); -#81540 = CARTESIAN_POINT('',(1.155,0.945297240108,0.15)); -#81541 = SURFACE_CURVE('',#81542,(#81546,#81553),.PCURVE_S1.); -#81542 = LINE('',#81543,#81544); -#81543 = CARTESIAN_POINT('',(1.155,1.17,0.15)); -#81544 = VECTOR('',#81545,1.); -#81545 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#81546 = PCURVE('',#78281,#81547); -#81547 = DEFINITIONAL_REPRESENTATION('',(#81548),#81552); -#81548 = LINE('',#81549,#81550); -#81549 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#81550 = VECTOR('',#81551,1.); -#81551 = DIRECTION('',(0.E+000,-1.)); -#81552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81553 = PCURVE('',#81265,#81554); -#81554 = DEFINITIONAL_REPRESENTATION('',(#81555),#81559); -#81555 = LINE('',#81556,#81557); -#81556 = CARTESIAN_POINT('',(0.4,0.E+000)); -#81557 = VECTOR('',#81558,1.); -#81558 = DIRECTION('',(0.E+000,-1.)); -#81559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81560 = ORIENTED_EDGE('',*,*,#81561,.T.); -#81561 = EDGE_CURVE('',#81539,#81562,#81564,.T.); -#81562 = VERTEX_POINT('',#81563); -#81563 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); -#81564 = SURFACE_CURVE('',#81565,(#81570,#81581),.PCURVE_S1.); -#81565 = CIRCLE('',#81566,5.E-002); -#81566 = AXIS2_PLACEMENT_3D('',#81567,#81568,#81569); -#81567 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); -#81568 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#81569 = DIRECTION('',(0.E+000,0.E+000,1.)); -#81570 = PCURVE('',#78281,#81571); -#81571 = DEFINITIONAL_REPRESENTATION('',(#81572),#81580); -#81572 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#81573,#81574,#81575,#81576 - ,#81577,#81578,#81579),.UNSPECIFIED.,.F.,.F.) +#83880 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#83881 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#83882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83883 = ORIENTED_EDGE('',*,*,#83884,.T.); +#83884 = EDGE_CURVE('',#83862,#83885,#83887,.T.); +#83885 = VERTEX_POINT('',#83886); +#83886 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#83887 = SURFACE_CURVE('',#83888,(#83892,#83899),.PCURVE_S1.); +#83888 = LINE('',#83889,#83890); +#83889 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#83890 = VECTOR('',#83891,1.); +#83891 = DIRECTION('',(0.E+000,1.,0.E+000)); +#83892 = PCURVE('',#80673,#83893); +#83893 = DEFINITIONAL_REPRESENTATION('',(#83894),#83898); +#83894 = LINE('',#83895,#83896); +#83895 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#83896 = VECTOR('',#83897,1.); +#83897 = DIRECTION('',(0.E+000,1.)); +#83898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83899 = PCURVE('',#83713,#83900); +#83900 = DEFINITIONAL_REPRESENTATION('',(#83901),#83905); +#83901 = LINE('',#83902,#83903); +#83902 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#83903 = VECTOR('',#83904,1.); +#83904 = DIRECTION('',(0.E+000,1.)); +#83905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83906 = ORIENTED_EDGE('',*,*,#83907,.T.); +#83907 = EDGE_CURVE('',#83885,#83908,#83910,.T.); +#83908 = VERTEX_POINT('',#83909); +#83909 = CARTESIAN_POINT('',(1.155,1.17,0.15)); +#83910 = SURFACE_CURVE('',#83911,(#83915,#83922),.PCURVE_S1.); +#83911 = LINE('',#83912,#83913); +#83912 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#83913 = VECTOR('',#83914,1.); +#83914 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83915 = PCURVE('',#80673,#83916); +#83916 = DEFINITIONAL_REPRESENTATION('',(#83917),#83921); +#83917 = LINE('',#83918,#83919); +#83918 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#83919 = VECTOR('',#83920,1.); +#83920 = DIRECTION('',(-1.,0.E+000)); +#83921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83922 = PCURVE('',#83685,#83923); +#83923 = DEFINITIONAL_REPRESENTATION('',(#83924),#83928); +#83924 = LINE('',#83925,#83926); +#83925 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83926 = VECTOR('',#83927,1.); +#83927 = DIRECTION('',(1.,0.E+000)); +#83928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83929 = ORIENTED_EDGE('',*,*,#83930,.T.); +#83930 = EDGE_CURVE('',#83908,#83931,#83933,.T.); +#83931 = VERTEX_POINT('',#83932); +#83932 = CARTESIAN_POINT('',(1.155,0.945297240108,0.15)); +#83933 = SURFACE_CURVE('',#83934,(#83938,#83945),.PCURVE_S1.); +#83934 = LINE('',#83935,#83936); +#83935 = CARTESIAN_POINT('',(1.155,1.17,0.15)); +#83936 = VECTOR('',#83937,1.); +#83937 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#83938 = PCURVE('',#80673,#83939); +#83939 = DEFINITIONAL_REPRESENTATION('',(#83940),#83944); +#83940 = LINE('',#83941,#83942); +#83941 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#83942 = VECTOR('',#83943,1.); +#83943 = DIRECTION('',(0.E+000,-1.)); +#83944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83945 = PCURVE('',#83657,#83946); +#83946 = DEFINITIONAL_REPRESENTATION('',(#83947),#83951); +#83947 = LINE('',#83948,#83949); +#83948 = CARTESIAN_POINT('',(0.4,0.E+000)); +#83949 = VECTOR('',#83950,1.); +#83950 = DIRECTION('',(0.E+000,-1.)); +#83951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83952 = ORIENTED_EDGE('',*,*,#83953,.T.); +#83953 = EDGE_CURVE('',#83931,#83954,#83956,.T.); +#83954 = VERTEX_POINT('',#83955); +#83955 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); +#83956 = SURFACE_CURVE('',#83957,(#83962,#83973),.PCURVE_S1.); +#83957 = CIRCLE('',#83958,5.E-002); +#83958 = AXIS2_PLACEMENT_3D('',#83959,#83960,#83961); +#83959 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); +#83960 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#83961 = DIRECTION('',(0.E+000,0.E+000,1.)); +#83962 = PCURVE('',#80673,#83963); +#83963 = DEFINITIONAL_REPRESENTATION('',(#83964),#83972); +#83964 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83965,#83966,#83967,#83968 + ,#83969,#83970,#83971),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#81573 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#81574 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#81575 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#81576 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#81577 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#81578 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#81579 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#81580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81581 = PCURVE('',#81238,#81582); -#81582 = DEFINITIONAL_REPRESENTATION('',(#81583),#81586); -#81583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81584,#81585),.UNSPECIFIED., +#83965 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#83966 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#83967 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#83968 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#83969 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#83970 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#83971 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#83972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83973 = PCURVE('',#83630,#83974); +#83974 = DEFINITIONAL_REPRESENTATION('',(#83975),#83978); +#83975 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83976,#83977),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#81584 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#81585 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#81586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81587 = ORIENTED_EDGE('',*,*,#81588,.T.); -#81588 = EDGE_CURVE('',#81562,#81589,#81591,.T.); -#81589 = VERTEX_POINT('',#81590); -#81590 = CARTESIAN_POINT('',(1.155,0.854004213739,0.571910405702)); -#81591 = SURFACE_CURVE('',#81592,(#81596,#81603),.PCURVE_S1.); -#81592 = LINE('',#81593,#81594); -#81593 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); -#81594 = VECTOR('',#81595,1.); -#81595 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#81596 = PCURVE('',#78281,#81597); -#81597 = DEFINITIONAL_REPRESENTATION('',(#81598),#81602); -#81598 = LINE('',#81599,#81600); -#81599 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#81600 = VECTOR('',#81601,1.); -#81601 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#81602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81603 = PCURVE('',#81205,#81604); -#81604 = DEFINITIONAL_REPRESENTATION('',(#81605),#81609); -#81605 = LINE('',#81606,#81607); -#81606 = CARTESIAN_POINT('',(0.E+000,0.4)); -#81607 = VECTOR('',#81608,1.); -#81608 = DIRECTION('',(1.,0.E+000)); -#81609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81610 = ORIENTED_EDGE('',*,*,#81611,.T.); -#81611 = EDGE_CURVE('',#81589,#81090,#81612,.T.); -#81612 = SURFACE_CURVE('',#81613,(#81618,#81625),.PCURVE_S1.); -#81613 = CIRCLE('',#81614,0.2); -#81614 = AXIS2_PLACEMENT_3D('',#81615,#81616,#81617); -#81615 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#81616 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81617 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81618 = PCURVE('',#78281,#81619); -#81619 = DEFINITIONAL_REPRESENTATION('',(#81620),#81624); -#81620 = CIRCLE('',#81621,0.2); -#81621 = AXIS2_PLACEMENT_2D('',#81622,#81623); -#81622 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81623 = DIRECTION('',(1.,0.E+000)); -#81624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#83976 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#83977 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#83978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83979 = ORIENTED_EDGE('',*,*,#83980,.T.); +#83980 = EDGE_CURVE('',#83954,#83981,#83983,.T.); +#83981 = VERTEX_POINT('',#83982); +#83982 = CARTESIAN_POINT('',(1.155,0.854004213739,0.571910405702)); +#83983 = SURFACE_CURVE('',#83984,(#83988,#83995),.PCURVE_S1.); +#83984 = LINE('',#83985,#83986); +#83985 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); +#83986 = VECTOR('',#83987,1.); +#83987 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#83988 = PCURVE('',#80673,#83989); +#83989 = DEFINITIONAL_REPRESENTATION('',(#83990),#83994); +#83990 = LINE('',#83991,#83992); +#83991 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#83992 = VECTOR('',#83993,1.); +#83993 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#83994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#83995 = PCURVE('',#83597,#83996); +#83996 = DEFINITIONAL_REPRESENTATION('',(#83997),#84001); +#83997 = LINE('',#83998,#83999); +#83998 = CARTESIAN_POINT('',(0.E+000,0.4)); +#83999 = VECTOR('',#84000,1.); +#84000 = DIRECTION('',(1.,0.E+000)); +#84001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#81625 = PCURVE('',#81128,#81626); -#81626 = DEFINITIONAL_REPRESENTATION('',(#81627),#81630); -#81627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81628,#81629),.UNSPECIFIED., +#84002 = ORIENTED_EDGE('',*,*,#84003,.T.); +#84003 = EDGE_CURVE('',#83981,#83482,#84004,.T.); +#84004 = SURFACE_CURVE('',#84005,(#84010,#84017),.PCURVE_S1.); +#84005 = CIRCLE('',#84006,0.2); +#84006 = AXIS2_PLACEMENT_3D('',#84007,#84008,#84009); +#84007 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#84008 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84009 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84010 = PCURVE('',#80673,#84011); +#84011 = DEFINITIONAL_REPRESENTATION('',(#84012),#84016); +#84012 = CIRCLE('',#84013,0.2); +#84013 = AXIS2_PLACEMENT_2D('',#84014,#84015); +#84014 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84015 = DIRECTION('',(1.,0.E+000)); +#84016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84017 = PCURVE('',#83520,#84018); +#84018 = DEFINITIONAL_REPRESENTATION('',(#84019),#84022); +#84019 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84020,#84021),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#81628 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#81629 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#81630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#84020 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84021 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#84022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#81631 = ORIENTED_EDGE('',*,*,#81089,.T.); -#81632 = ADVANCED_FACE('',(#81633),#81128,.T.); -#81633 = FACE_BOUND('',#81634,.T.); -#81634 = EDGE_LOOP('',(#81635,#81636,#81637,#81657)); -#81635 = ORIENTED_EDGE('',*,*,#81112,.T.); -#81636 = ORIENTED_EDGE('',*,*,#81611,.F.); -#81637 = ORIENTED_EDGE('',*,*,#81638,.F.); -#81638 = EDGE_CURVE('',#81167,#81589,#81639,.T.); -#81639 = SURFACE_CURVE('',#81640,(#81644,#81650),.PCURVE_S1.); -#81640 = LINE('',#81641,#81642); -#81641 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); -#81642 = VECTOR('',#81643,1.); -#81643 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81644 = PCURVE('',#81128,#81645); -#81645 = DEFINITIONAL_REPRESENTATION('',(#81646),#81649); -#81646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81647,#81648),.UNSPECIFIED., +#84023 = ORIENTED_EDGE('',*,*,#83481,.T.); +#84024 = ADVANCED_FACE('',(#84025),#83520,.T.); +#84025 = FACE_BOUND('',#84026,.T.); +#84026 = EDGE_LOOP('',(#84027,#84028,#84029,#84049)); +#84027 = ORIENTED_EDGE('',*,*,#83504,.T.); +#84028 = ORIENTED_EDGE('',*,*,#84003,.F.); +#84029 = ORIENTED_EDGE('',*,*,#84030,.F.); +#84030 = EDGE_CURVE('',#83559,#83981,#84031,.T.); +#84031 = SURFACE_CURVE('',#84032,(#84036,#84042),.PCURVE_S1.); +#84032 = LINE('',#84033,#84034); +#84033 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); +#84034 = VECTOR('',#84035,1.); +#84035 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84036 = PCURVE('',#83520,#84037); +#84037 = DEFINITIONAL_REPRESENTATION('',(#84038),#84041); +#84038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84039,#84040),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81647 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#81648 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#81649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81650 = PCURVE('',#81205,#81651); -#81651 = DEFINITIONAL_REPRESENTATION('',(#81652),#81656); -#81652 = LINE('',#81653,#81654); -#81653 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#81654 = VECTOR('',#81655,1.); -#81655 = DIRECTION('',(0.E+000,1.)); -#81656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81657 = ORIENTED_EDGE('',*,*,#81166,.T.); -#81658 = ADVANCED_FACE('',(#81659),#81205,.T.); -#81659 = FACE_BOUND('',#81660,.T.); -#81660 = EDGE_LOOP('',(#81661,#81662,#81663,#81683)); -#81661 = ORIENTED_EDGE('',*,*,#81638,.T.); -#81662 = ORIENTED_EDGE('',*,*,#81588,.F.); -#81663 = ORIENTED_EDGE('',*,*,#81664,.F.); -#81664 = EDGE_CURVE('',#81190,#81562,#81665,.T.); -#81665 = SURFACE_CURVE('',#81666,(#81670,#81677),.PCURVE_S1.); -#81666 = LINE('',#81667,#81668); -#81667 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#81668 = VECTOR('',#81669,1.); -#81669 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81670 = PCURVE('',#81205,#81671); -#81671 = DEFINITIONAL_REPRESENTATION('',(#81672),#81676); -#81672 = LINE('',#81673,#81674); -#81673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81674 = VECTOR('',#81675,1.); -#81675 = DIRECTION('',(0.E+000,1.)); -#81676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81677 = PCURVE('',#81238,#81678); -#81678 = DEFINITIONAL_REPRESENTATION('',(#81679),#81682); -#81679 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81680,#81681),.UNSPECIFIED., +#84039 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#84040 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84042 = PCURVE('',#83597,#84043); +#84043 = DEFINITIONAL_REPRESENTATION('',(#84044),#84048); +#84044 = LINE('',#84045,#84046); +#84045 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#84046 = VECTOR('',#84047,1.); +#84047 = DIRECTION('',(0.E+000,1.)); +#84048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84049 = ORIENTED_EDGE('',*,*,#83558,.T.); +#84050 = ADVANCED_FACE('',(#84051),#83597,.T.); +#84051 = FACE_BOUND('',#84052,.T.); +#84052 = EDGE_LOOP('',(#84053,#84054,#84055,#84075)); +#84053 = ORIENTED_EDGE('',*,*,#84030,.T.); +#84054 = ORIENTED_EDGE('',*,*,#83980,.F.); +#84055 = ORIENTED_EDGE('',*,*,#84056,.F.); +#84056 = EDGE_CURVE('',#83582,#83954,#84057,.T.); +#84057 = SURFACE_CURVE('',#84058,(#84062,#84069),.PCURVE_S1.); +#84058 = LINE('',#84059,#84060); +#84059 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#84060 = VECTOR('',#84061,1.); +#84061 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84062 = PCURVE('',#83597,#84063); +#84063 = DEFINITIONAL_REPRESENTATION('',(#84064),#84068); +#84064 = LINE('',#84065,#84066); +#84065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84066 = VECTOR('',#84067,1.); +#84067 = DIRECTION('',(0.E+000,1.)); +#84068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84069 = PCURVE('',#83630,#84070); +#84070 = DEFINITIONAL_REPRESENTATION('',(#84071),#84074); +#84071 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84072,#84073),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81680 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#81681 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#81682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81683 = ORIENTED_EDGE('',*,*,#81189,.T.); -#81684 = ADVANCED_FACE('',(#81685),#81238,.F.); -#81685 = FACE_BOUND('',#81686,.F.); -#81686 = EDGE_LOOP('',(#81687,#81688,#81689,#81732)); -#81687 = ORIENTED_EDGE('',*,*,#81664,.F.); -#81688 = ORIENTED_EDGE('',*,*,#81217,.F.); -#81689 = ORIENTED_EDGE('',*,*,#81690,.T.); -#81690 = EDGE_CURVE('',#81218,#81539,#81691,.T.); -#81691 = SURFACE_CURVE('',#81692,(#81696,#81725),.PCURVE_S1.); -#81692 = LINE('',#81693,#81694); -#81693 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); -#81694 = VECTOR('',#81695,1.); -#81695 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81696 = PCURVE('',#81238,#81697); -#81697 = DEFINITIONAL_REPRESENTATION('',(#81698),#81724); -#81698 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81699,#81700,#81701,#81702, - #81703,#81704,#81705,#81706,#81707,#81708,#81709,#81710,#81711, - #81712,#81713,#81714,#81715,#81716,#81717,#81718,#81719,#81720, - #81721,#81722,#81723),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#84072 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#84073 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#84074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84075 = ORIENTED_EDGE('',*,*,#83581,.T.); +#84076 = ADVANCED_FACE('',(#84077),#83630,.F.); +#84077 = FACE_BOUND('',#84078,.F.); +#84078 = EDGE_LOOP('',(#84079,#84080,#84081,#84124)); +#84079 = ORIENTED_EDGE('',*,*,#84056,.F.); +#84080 = ORIENTED_EDGE('',*,*,#83609,.F.); +#84081 = ORIENTED_EDGE('',*,*,#84082,.T.); +#84082 = EDGE_CURVE('',#83610,#83931,#84083,.T.); +#84083 = SURFACE_CURVE('',#84084,(#84088,#84117),.PCURVE_S1.); +#84084 = LINE('',#84085,#84086); +#84085 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); +#84086 = VECTOR('',#84087,1.); +#84087 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84088 = PCURVE('',#83630,#84089); +#84089 = DEFINITIONAL_REPRESENTATION('',(#84090),#84116); +#84090 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84091,#84092,#84093,#84094, + #84095,#84096,#84097,#84098,#84099,#84100,#84101,#84102,#84103, + #84104,#84105,#84106,#84107,#84108,#84109,#84110,#84111,#84112, + #84113,#84114,#84115),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -101325,133 +104314,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#81699 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#81700 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#81701 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#81702 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#81703 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#81704 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#81705 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#81706 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#81707 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#81708 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#81709 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#81710 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#81711 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#81712 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#81713 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#81714 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#81715 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#81716 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#81717 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#81718 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#81719 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#81720 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#81721 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#81722 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#81723 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#81724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81725 = PCURVE('',#81265,#81726); -#81726 = DEFINITIONAL_REPRESENTATION('',(#81727),#81731); -#81727 = LINE('',#81728,#81729); -#81728 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#81729 = VECTOR('',#81730,1.); -#81730 = DIRECTION('',(1.,0.E+000)); -#81731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81732 = ORIENTED_EDGE('',*,*,#81561,.T.); -#81733 = ADVANCED_FACE('',(#81734),#81265,.T.); -#81734 = FACE_BOUND('',#81735,.T.); -#81735 = EDGE_LOOP('',(#81736,#81737,#81738,#81759)); -#81736 = ORIENTED_EDGE('',*,*,#81690,.T.); -#81737 = ORIENTED_EDGE('',*,*,#81538,.F.); -#81738 = ORIENTED_EDGE('',*,*,#81739,.F.); -#81739 = EDGE_CURVE('',#81250,#81516,#81740,.T.); -#81740 = SURFACE_CURVE('',#81741,(#81745,#81752),.PCURVE_S1.); -#81741 = LINE('',#81742,#81743); -#81742 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#81743 = VECTOR('',#81744,1.); -#81744 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81745 = PCURVE('',#81265,#81746); -#81746 = DEFINITIONAL_REPRESENTATION('',(#81747),#81751); -#81747 = LINE('',#81748,#81749); -#81748 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81749 = VECTOR('',#81750,1.); -#81750 = DIRECTION('',(1.,0.E+000)); -#81751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81752 = PCURVE('',#81293,#81753); -#81753 = DEFINITIONAL_REPRESENTATION('',(#81754),#81758); -#81754 = LINE('',#81755,#81756); -#81755 = CARTESIAN_POINT('',(0.15,0.E+000)); -#81756 = VECTOR('',#81757,1.); -#81757 = DIRECTION('',(0.E+000,1.)); -#81758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81759 = ORIENTED_EDGE('',*,*,#81249,.T.); -#81760 = ADVANCED_FACE('',(#81761),#81293,.T.); -#81761 = FACE_BOUND('',#81762,.T.); -#81762 = EDGE_LOOP('',(#81763,#81764,#81765,#81786)); -#81763 = ORIENTED_EDGE('',*,*,#81739,.T.); -#81764 = ORIENTED_EDGE('',*,*,#81515,.F.); -#81765 = ORIENTED_EDGE('',*,*,#81766,.F.); -#81766 = EDGE_CURVE('',#81278,#81493,#81767,.T.); -#81767 = SURFACE_CURVE('',#81768,(#81772,#81779),.PCURVE_S1.); -#81768 = LINE('',#81769,#81770); -#81769 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#81770 = VECTOR('',#81771,1.); -#81771 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81772 = PCURVE('',#81293,#81773); -#81773 = DEFINITIONAL_REPRESENTATION('',(#81774),#81778); -#81774 = LINE('',#81775,#81776); -#81775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81776 = VECTOR('',#81777,1.); -#81777 = DIRECTION('',(0.E+000,1.)); -#81778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81779 = PCURVE('',#81321,#81780); -#81780 = DEFINITIONAL_REPRESENTATION('',(#81781),#81785); -#81781 = LINE('',#81782,#81783); -#81782 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81783 = VECTOR('',#81784,1.); -#81784 = DIRECTION('',(-1.,0.E+000)); -#81785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81786 = ORIENTED_EDGE('',*,*,#81277,.T.); -#81787 = ADVANCED_FACE('',(#81788),#81321,.T.); -#81788 = FACE_BOUND('',#81789,.T.); -#81789 = EDGE_LOOP('',(#81790,#81791,#81792,#81835)); -#81790 = ORIENTED_EDGE('',*,*,#81766,.T.); -#81791 = ORIENTED_EDGE('',*,*,#81492,.F.); -#81792 = ORIENTED_EDGE('',*,*,#81793,.F.); -#81793 = EDGE_CURVE('',#81306,#81470,#81794,.T.); -#81794 = SURFACE_CURVE('',#81795,(#81799,#81806),.PCURVE_S1.); -#81795 = LINE('',#81796,#81797); -#81796 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); -#81797 = VECTOR('',#81798,1.); -#81798 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81799 = PCURVE('',#81321,#81800); -#81800 = DEFINITIONAL_REPRESENTATION('',(#81801),#81805); -#81801 = LINE('',#81802,#81803); -#81802 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#81803 = VECTOR('',#81804,1.); -#81804 = DIRECTION('',(-1.,0.E+000)); -#81805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81806 = PCURVE('',#81350,#81807); -#81807 = DEFINITIONAL_REPRESENTATION('',(#81808),#81834); -#81808 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#81809,#81810,#81811,#81812, - #81813,#81814,#81815,#81816,#81817,#81818,#81819,#81820,#81821, - #81822,#81823,#81824,#81825,#81826,#81827,#81828,#81829,#81830, - #81831,#81832,#81833),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#84091 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#84092 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#84093 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#84094 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#84095 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#84096 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#84097 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#84098 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#84099 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#84100 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#84101 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#84102 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#84103 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#84104 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#84105 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#84106 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#84107 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#84108 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#84109 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#84110 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#84111 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#84112 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#84113 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#84114 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#84115 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#84116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84117 = PCURVE('',#83657,#84118); +#84118 = DEFINITIONAL_REPRESENTATION('',(#84119),#84123); +#84119 = LINE('',#84120,#84121); +#84120 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#84121 = VECTOR('',#84122,1.); +#84122 = DIRECTION('',(1.,0.E+000)); +#84123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84124 = ORIENTED_EDGE('',*,*,#83953,.T.); +#84125 = ADVANCED_FACE('',(#84126),#83657,.T.); +#84126 = FACE_BOUND('',#84127,.T.); +#84127 = EDGE_LOOP('',(#84128,#84129,#84130,#84151)); +#84128 = ORIENTED_EDGE('',*,*,#84082,.T.); +#84129 = ORIENTED_EDGE('',*,*,#83930,.F.); +#84130 = ORIENTED_EDGE('',*,*,#84131,.F.); +#84131 = EDGE_CURVE('',#83642,#83908,#84132,.T.); +#84132 = SURFACE_CURVE('',#84133,(#84137,#84144),.PCURVE_S1.); +#84133 = LINE('',#84134,#84135); +#84134 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#84135 = VECTOR('',#84136,1.); +#84136 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84137 = PCURVE('',#83657,#84138); +#84138 = DEFINITIONAL_REPRESENTATION('',(#84139),#84143); +#84139 = LINE('',#84140,#84141); +#84140 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84141 = VECTOR('',#84142,1.); +#84142 = DIRECTION('',(1.,0.E+000)); +#84143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84144 = PCURVE('',#83685,#84145); +#84145 = DEFINITIONAL_REPRESENTATION('',(#84146),#84150); +#84146 = LINE('',#84147,#84148); +#84147 = CARTESIAN_POINT('',(0.15,0.E+000)); +#84148 = VECTOR('',#84149,1.); +#84149 = DIRECTION('',(0.E+000,1.)); +#84150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84151 = ORIENTED_EDGE('',*,*,#83641,.T.); +#84152 = ADVANCED_FACE('',(#84153),#83685,.T.); +#84153 = FACE_BOUND('',#84154,.T.); +#84154 = EDGE_LOOP('',(#84155,#84156,#84157,#84178)); +#84155 = ORIENTED_EDGE('',*,*,#84131,.T.); +#84156 = ORIENTED_EDGE('',*,*,#83907,.F.); +#84157 = ORIENTED_EDGE('',*,*,#84158,.F.); +#84158 = EDGE_CURVE('',#83670,#83885,#84159,.T.); +#84159 = SURFACE_CURVE('',#84160,(#84164,#84171),.PCURVE_S1.); +#84160 = LINE('',#84161,#84162); +#84161 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#84162 = VECTOR('',#84163,1.); +#84163 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84164 = PCURVE('',#83685,#84165); +#84165 = DEFINITIONAL_REPRESENTATION('',(#84166),#84170); +#84166 = LINE('',#84167,#84168); +#84167 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84168 = VECTOR('',#84169,1.); +#84169 = DIRECTION('',(0.E+000,1.)); +#84170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84171 = PCURVE('',#83713,#84172); +#84172 = DEFINITIONAL_REPRESENTATION('',(#84173),#84177); +#84173 = LINE('',#84174,#84175); +#84174 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84175 = VECTOR('',#84176,1.); +#84176 = DIRECTION('',(-1.,0.E+000)); +#84177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84178 = ORIENTED_EDGE('',*,*,#83669,.T.); +#84179 = ADVANCED_FACE('',(#84180),#83713,.T.); +#84180 = FACE_BOUND('',#84181,.T.); +#84181 = EDGE_LOOP('',(#84182,#84183,#84184,#84227)); +#84182 = ORIENTED_EDGE('',*,*,#84158,.T.); +#84183 = ORIENTED_EDGE('',*,*,#83884,.F.); +#84184 = ORIENTED_EDGE('',*,*,#84185,.F.); +#84185 = EDGE_CURVE('',#83698,#83862,#84186,.T.); +#84186 = SURFACE_CURVE('',#84187,(#84191,#84198),.PCURVE_S1.); +#84187 = LINE('',#84188,#84189); +#84188 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); +#84189 = VECTOR('',#84190,1.); +#84190 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84191 = PCURVE('',#83713,#84192); +#84192 = DEFINITIONAL_REPRESENTATION('',(#84193),#84197); +#84193 = LINE('',#84194,#84195); +#84194 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#84195 = VECTOR('',#84196,1.); +#84196 = DIRECTION('',(-1.,0.E+000)); +#84197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84198 = PCURVE('',#83742,#84199); +#84199 = DEFINITIONAL_REPRESENTATION('',(#84200),#84226); +#84200 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84201,#84202,#84203,#84204, + #84205,#84206,#84207,#84208,#84209,#84210,#84211,#84212,#84213, + #84214,#84215,#84216,#84217,#84218,#84219,#84220,#84221,#84222, + #84223,#84224,#84225),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -101459,945 +104448,945 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#81809 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#81810 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#81811 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#81812 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#81813 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#81814 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#81815 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#81816 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#81817 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#81818 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#81819 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#81820 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#81821 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#81822 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#81823 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#81824 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#81825 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#81826 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#81827 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#81828 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#81829 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#81830 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#81831 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#81832 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#81833 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#81834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81835 = ORIENTED_EDGE('',*,*,#81305,.T.); -#81836 = ADVANCED_FACE('',(#81837),#81350,.T.); -#81837 = FACE_BOUND('',#81838,.T.); -#81838 = EDGE_LOOP('',(#81839,#81840,#81841,#81861)); -#81839 = ORIENTED_EDGE('',*,*,#81793,.T.); -#81840 = ORIENTED_EDGE('',*,*,#81469,.F.); -#81841 = ORIENTED_EDGE('',*,*,#81842,.F.); -#81842 = EDGE_CURVE('',#81334,#81447,#81843,.T.); -#81843 = SURFACE_CURVE('',#81844,(#81848,#81854),.PCURVE_S1.); -#81844 = LINE('',#81845,#81846); -#81845 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); -#81846 = VECTOR('',#81847,1.); -#81847 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81848 = PCURVE('',#81350,#81849); -#81849 = DEFINITIONAL_REPRESENTATION('',(#81850),#81853); -#81850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81851,#81852),.UNSPECIFIED., +#84201 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#84202 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#84203 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#84204 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#84205 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#84206 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#84207 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#84208 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#84209 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#84210 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#84211 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#84212 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#84213 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#84214 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#84215 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#84216 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#84217 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#84218 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#84219 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#84220 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#84221 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#84222 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#84223 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#84224 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#84225 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#84226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84227 = ORIENTED_EDGE('',*,*,#83697,.T.); +#84228 = ADVANCED_FACE('',(#84229),#83742,.T.); +#84229 = FACE_BOUND('',#84230,.T.); +#84230 = EDGE_LOOP('',(#84231,#84232,#84233,#84253)); +#84231 = ORIENTED_EDGE('',*,*,#84185,.T.); +#84232 = ORIENTED_EDGE('',*,*,#83861,.F.); +#84233 = ORIENTED_EDGE('',*,*,#84234,.F.); +#84234 = EDGE_CURVE('',#83726,#83839,#84235,.T.); +#84235 = SURFACE_CURVE('',#84236,(#84240,#84246),.PCURVE_S1.); +#84236 = LINE('',#84237,#84238); +#84237 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); +#84238 = VECTOR('',#84239,1.); +#84239 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84240 = PCURVE('',#83742,#84241); +#84241 = DEFINITIONAL_REPRESENTATION('',(#84242),#84245); +#84242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84243,#84244),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81851 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#81852 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#81853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81854 = PCURVE('',#81377,#81855); -#81855 = DEFINITIONAL_REPRESENTATION('',(#81856),#81860); -#81856 = LINE('',#81857,#81858); -#81857 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#81858 = VECTOR('',#81859,1.); -#81859 = DIRECTION('',(0.E+000,1.)); -#81860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81861 = ORIENTED_EDGE('',*,*,#81333,.T.); -#81862 = ADVANCED_FACE('',(#81863),#81377,.T.); -#81863 = FACE_BOUND('',#81864,.T.); -#81864 = EDGE_LOOP('',(#81865,#81866,#81867,#81887)); -#81865 = ORIENTED_EDGE('',*,*,#81842,.T.); -#81866 = ORIENTED_EDGE('',*,*,#81446,.F.); -#81867 = ORIENTED_EDGE('',*,*,#81868,.F.); -#81868 = EDGE_CURVE('',#81362,#81420,#81869,.T.); -#81869 = SURFACE_CURVE('',#81870,(#81874,#81881),.PCURVE_S1.); -#81870 = LINE('',#81871,#81872); -#81871 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#81872 = VECTOR('',#81873,1.); -#81873 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81874 = PCURVE('',#81377,#81875); -#81875 = DEFINITIONAL_REPRESENTATION('',(#81876),#81880); -#81876 = LINE('',#81877,#81878); -#81877 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81878 = VECTOR('',#81879,1.); -#81879 = DIRECTION('',(0.E+000,1.)); -#81880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81881 = PCURVE('',#81053,#81882); -#81882 = DEFINITIONAL_REPRESENTATION('',(#81883),#81886); -#81883 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81884,#81885),.UNSPECIFIED., +#84243 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#84244 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#84245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84246 = PCURVE('',#83769,#84247); +#84247 = DEFINITIONAL_REPRESENTATION('',(#84248),#84252); +#84248 = LINE('',#84249,#84250); +#84249 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#84250 = VECTOR('',#84251,1.); +#84251 = DIRECTION('',(0.E+000,1.)); +#84252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84253 = ORIENTED_EDGE('',*,*,#83725,.T.); +#84254 = ADVANCED_FACE('',(#84255),#83769,.T.); +#84255 = FACE_BOUND('',#84256,.T.); +#84256 = EDGE_LOOP('',(#84257,#84258,#84259,#84279)); +#84257 = ORIENTED_EDGE('',*,*,#84234,.T.); +#84258 = ORIENTED_EDGE('',*,*,#83838,.F.); +#84259 = ORIENTED_EDGE('',*,*,#84260,.F.); +#84260 = EDGE_CURVE('',#83754,#83812,#84261,.T.); +#84261 = SURFACE_CURVE('',#84262,(#84266,#84273),.PCURVE_S1.); +#84262 = LINE('',#84263,#84264); +#84263 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#84264 = VECTOR('',#84265,1.); +#84265 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84266 = PCURVE('',#83769,#84267); +#84267 = DEFINITIONAL_REPRESENTATION('',(#84268),#84272); +#84268 = LINE('',#84269,#84270); +#84269 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84270 = VECTOR('',#84271,1.); +#84271 = DIRECTION('',(0.E+000,1.)); +#84272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84273 = PCURVE('',#83445,#84274); +#84274 = DEFINITIONAL_REPRESENTATION('',(#84275),#84278); +#84275 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84276,#84277),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81884 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#81885 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#81886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81887 = ORIENTED_EDGE('',*,*,#81361,.T.); -#81888 = ADVANCED_FACE('',(#81889),#81053,.F.); -#81889 = FACE_BOUND('',#81890,.F.); -#81890 = EDGE_LOOP('',(#81891,#81892,#81893,#81894)); -#81891 = ORIENTED_EDGE('',*,*,#81868,.F.); -#81892 = ORIENTED_EDGE('',*,*,#81389,.F.); -#81893 = ORIENTED_EDGE('',*,*,#81037,.T.); -#81894 = ORIENTED_EDGE('',*,*,#81419,.T.); -#81895 = ADVANCED_FACE('',(#81896),#79168,.T.); -#81896 = FACE_BOUND('',#81897,.T.); -#81897 = EDGE_LOOP('',(#81898,#81899,#81922,#81949)); -#81898 = ORIENTED_EDGE('',*,*,#79154,.T.); -#81899 = ORIENTED_EDGE('',*,*,#81900,.T.); -#81900 = EDGE_CURVE('',#78536,#81901,#81903,.T.); -#81901 = VERTEX_POINT('',#81902); -#81902 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#81903 = SURFACE_CURVE('',#81904,(#81908,#81915),.PCURVE_S1.); -#81904 = LINE('',#81905,#81906); -#81905 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#81906 = VECTOR('',#81907,1.); -#81907 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81908 = PCURVE('',#79168,#81909); -#81909 = DEFINITIONAL_REPRESENTATION('',(#81910),#81914); -#81910 = LINE('',#81911,#81912); -#81911 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81912 = VECTOR('',#81913,1.); -#81913 = DIRECTION('',(0.E+000,1.)); -#81914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81915 = PCURVE('',#78551,#81916); -#81916 = DEFINITIONAL_REPRESENTATION('',(#81917),#81921); -#81917 = LINE('',#81918,#81919); -#81918 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#81919 = VECTOR('',#81920,1.); -#81920 = DIRECTION('',(0.E+000,1.)); -#81921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81922 = ORIENTED_EDGE('',*,*,#81923,.T.); -#81923 = EDGE_CURVE('',#81901,#81924,#81926,.T.); -#81924 = VERTEX_POINT('',#81925); -#81925 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); -#81926 = SURFACE_CURVE('',#81927,(#81931,#81938),.PCURVE_S1.); -#81927 = LINE('',#81928,#81929); -#81928 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#81929 = VECTOR('',#81930,1.); -#81930 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81931 = PCURVE('',#79168,#81932); -#81932 = DEFINITIONAL_REPRESENTATION('',(#81933),#81937); -#81933 = LINE('',#81934,#81935); -#81934 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81935 = VECTOR('',#81936,1.); -#81936 = DIRECTION('',(-1.,0.E+000)); -#81937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81938 = PCURVE('',#81939,#81944); -#81939 = CYLINDRICAL_SURFACE('',#81940,5.E-002); -#81940 = AXIS2_PLACEMENT_3D('',#81941,#81942,#81943); -#81941 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#81942 = DIRECTION('',(1.,0.E+000,0.E+000)); -#81943 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#81944 = DEFINITIONAL_REPRESENTATION('',(#81945),#81948); -#81945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#81946,#81947),.UNSPECIFIED., +#84276 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#84277 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84279 = ORIENTED_EDGE('',*,*,#83753,.T.); +#84280 = ADVANCED_FACE('',(#84281),#83445,.F.); +#84281 = FACE_BOUND('',#84282,.F.); +#84282 = EDGE_LOOP('',(#84283,#84284,#84285,#84286)); +#84283 = ORIENTED_EDGE('',*,*,#84260,.F.); +#84284 = ORIENTED_EDGE('',*,*,#83781,.F.); +#84285 = ORIENTED_EDGE('',*,*,#83429,.T.); +#84286 = ORIENTED_EDGE('',*,*,#83811,.T.); +#84287 = ADVANCED_FACE('',(#84288),#81560,.T.); +#84288 = FACE_BOUND('',#84289,.T.); +#84289 = EDGE_LOOP('',(#84290,#84291,#84314,#84341)); +#84290 = ORIENTED_EDGE('',*,*,#81546,.T.); +#84291 = ORIENTED_EDGE('',*,*,#84292,.T.); +#84292 = EDGE_CURVE('',#80928,#84293,#84295,.T.); +#84293 = VERTEX_POINT('',#84294); +#84294 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#84295 = SURFACE_CURVE('',#84296,(#84300,#84307),.PCURVE_S1.); +#84296 = LINE('',#84297,#84298); +#84297 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#84298 = VECTOR('',#84299,1.); +#84299 = DIRECTION('',(0.E+000,1.,0.E+000)); +#84300 = PCURVE('',#81560,#84301); +#84301 = DEFINITIONAL_REPRESENTATION('',(#84302),#84306); +#84302 = LINE('',#84303,#84304); +#84303 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84304 = VECTOR('',#84305,1.); +#84305 = DIRECTION('',(0.E+000,1.)); +#84306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84307 = PCURVE('',#80943,#84308); +#84308 = DEFINITIONAL_REPRESENTATION('',(#84309),#84313); +#84309 = LINE('',#84310,#84311); +#84310 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#84311 = VECTOR('',#84312,1.); +#84312 = DIRECTION('',(0.E+000,1.)); +#84313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84314 = ORIENTED_EDGE('',*,*,#84315,.T.); +#84315 = EDGE_CURVE('',#84293,#84316,#84318,.T.); +#84316 = VERTEX_POINT('',#84317); +#84317 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); +#84318 = SURFACE_CURVE('',#84319,(#84323,#84330),.PCURVE_S1.); +#84319 = LINE('',#84320,#84321); +#84320 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#84321 = VECTOR('',#84322,1.); +#84322 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84323 = PCURVE('',#81560,#84324); +#84324 = DEFINITIONAL_REPRESENTATION('',(#84325),#84329); +#84325 = LINE('',#84326,#84327); +#84326 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84327 = VECTOR('',#84328,1.); +#84328 = DIRECTION('',(-1.,0.E+000)); +#84329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84330 = PCURVE('',#84331,#84336); +#84331 = CYLINDRICAL_SURFACE('',#84332,5.E-002); +#84332 = AXIS2_PLACEMENT_3D('',#84333,#84334,#84335); +#84333 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#84334 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84335 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84336 = DEFINITIONAL_REPRESENTATION('',(#84337),#84340); +#84337 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84338,#84339),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#81946 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#81947 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#81948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81949 = ORIENTED_EDGE('',*,*,#81950,.F.); -#81950 = EDGE_CURVE('',#78457,#81924,#81951,.T.); -#81951 = SURFACE_CURVE('',#81952,(#81956,#81963),.PCURVE_S1.); -#81952 = LINE('',#81953,#81954); -#81953 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); -#81954 = VECTOR('',#81955,1.); -#81955 = DIRECTION('',(0.E+000,1.,0.E+000)); -#81956 = PCURVE('',#79168,#81957); -#81957 = DEFINITIONAL_REPRESENTATION('',(#81958),#81962); -#81958 = LINE('',#81959,#81960); -#81959 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#81960 = VECTOR('',#81961,1.); -#81961 = DIRECTION('',(0.E+000,1.)); -#81962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81963 = PCURVE('',#78495,#81964); -#81964 = DEFINITIONAL_REPRESENTATION('',(#81965),#81969); -#81965 = LINE('',#81966,#81967); -#81966 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#81967 = VECTOR('',#81968,1.); -#81968 = DIRECTION('',(0.E+000,1.)); -#81969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81970 = ADVANCED_FACE('',(#81971),#78551,.F.); -#81971 = FACE_BOUND('',#81972,.T.); -#81972 = EDGE_LOOP('',(#81973,#81974,#81975,#81998,#82026,#82054,#82086, - #82114,#82142,#82170,#82198,#82226)); -#81973 = ORIENTED_EDGE('',*,*,#81900,.F.); -#81974 = ORIENTED_EDGE('',*,*,#78535,.T.); -#81975 = ORIENTED_EDGE('',*,*,#81976,.F.); -#81976 = EDGE_CURVE('',#81977,#78508,#81979,.T.); -#81977 = VERTEX_POINT('',#81978); -#81978 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#81979 = SURFACE_CURVE('',#81980,(#81984,#81991),.PCURVE_S1.); -#81980 = LINE('',#81981,#81982); -#81981 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#81982 = VECTOR('',#81983,1.); -#81983 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#81984 = PCURVE('',#78551,#81985); -#81985 = DEFINITIONAL_REPRESENTATION('',(#81986),#81990); -#81986 = LINE('',#81987,#81988); -#81987 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#81988 = VECTOR('',#81989,1.); -#81989 = DIRECTION('',(0.E+000,-1.)); -#81990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81991 = PCURVE('',#78523,#81992); -#81992 = DEFINITIONAL_REPRESENTATION('',(#81993),#81997); -#81993 = LINE('',#81994,#81995); -#81994 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#81995 = VECTOR('',#81996,1.); -#81996 = DIRECTION('',(0.E+000,-1.)); -#81997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#81998 = ORIENTED_EDGE('',*,*,#81999,.F.); -#81999 = EDGE_CURVE('',#82000,#81977,#82002,.T.); -#82000 = VERTEX_POINT('',#82001); -#82001 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); -#82002 = SURFACE_CURVE('',#82003,(#82008,#82015),.PCURVE_S1.); -#82003 = CIRCLE('',#82004,0.2); -#82004 = AXIS2_PLACEMENT_3D('',#82005,#82006,#82007); -#82005 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#82006 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82007 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82008 = PCURVE('',#78551,#82009); -#82009 = DEFINITIONAL_REPRESENTATION('',(#82010),#82014); -#82010 = CIRCLE('',#82011,0.2); -#82011 = AXIS2_PLACEMENT_2D('',#82012,#82013); -#82012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82013 = DIRECTION('',(1.,0.E+000)); -#82014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82015 = PCURVE('',#82016,#82021); -#82016 = CYLINDRICAL_SURFACE('',#82017,0.2); -#82017 = AXIS2_PLACEMENT_3D('',#82018,#82019,#82020); -#82018 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#82019 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82020 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82021 = DEFINITIONAL_REPRESENTATION('',(#82022),#82025); -#82022 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82023,#82024),.UNSPECIFIED., +#84338 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#84339 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#84340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84341 = ORIENTED_EDGE('',*,*,#84342,.F.); +#84342 = EDGE_CURVE('',#80849,#84316,#84343,.T.); +#84343 = SURFACE_CURVE('',#84344,(#84348,#84355),.PCURVE_S1.); +#84344 = LINE('',#84345,#84346); +#84345 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); +#84346 = VECTOR('',#84347,1.); +#84347 = DIRECTION('',(0.E+000,1.,0.E+000)); +#84348 = PCURVE('',#81560,#84349); +#84349 = DEFINITIONAL_REPRESENTATION('',(#84350),#84354); +#84350 = LINE('',#84351,#84352); +#84351 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#84352 = VECTOR('',#84353,1.); +#84353 = DIRECTION('',(0.E+000,1.)); +#84354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84355 = PCURVE('',#80887,#84356); +#84356 = DEFINITIONAL_REPRESENTATION('',(#84357),#84361); +#84357 = LINE('',#84358,#84359); +#84358 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#84359 = VECTOR('',#84360,1.); +#84360 = DIRECTION('',(0.E+000,1.)); +#84361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84362 = ADVANCED_FACE('',(#84363),#80943,.F.); +#84363 = FACE_BOUND('',#84364,.T.); +#84364 = EDGE_LOOP('',(#84365,#84366,#84367,#84390,#84418,#84446,#84478, + #84506,#84534,#84562,#84590,#84618)); +#84365 = ORIENTED_EDGE('',*,*,#84292,.F.); +#84366 = ORIENTED_EDGE('',*,*,#80927,.T.); +#84367 = ORIENTED_EDGE('',*,*,#84368,.F.); +#84368 = EDGE_CURVE('',#84369,#80900,#84371,.T.); +#84369 = VERTEX_POINT('',#84370); +#84370 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#84371 = SURFACE_CURVE('',#84372,(#84376,#84383),.PCURVE_S1.); +#84372 = LINE('',#84373,#84374); +#84373 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#84374 = VECTOR('',#84375,1.); +#84375 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#84376 = PCURVE('',#80943,#84377); +#84377 = DEFINITIONAL_REPRESENTATION('',(#84378),#84382); +#84378 = LINE('',#84379,#84380); +#84379 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#84380 = VECTOR('',#84381,1.); +#84381 = DIRECTION('',(0.E+000,-1.)); +#84382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84383 = PCURVE('',#80915,#84384); +#84384 = DEFINITIONAL_REPRESENTATION('',(#84385),#84389); +#84385 = LINE('',#84386,#84387); +#84386 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84387 = VECTOR('',#84388,1.); +#84388 = DIRECTION('',(0.E+000,-1.)); +#84389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84390 = ORIENTED_EDGE('',*,*,#84391,.F.); +#84391 = EDGE_CURVE('',#84392,#84369,#84394,.T.); +#84392 = VERTEX_POINT('',#84393); +#84393 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); +#84394 = SURFACE_CURVE('',#84395,(#84400,#84407),.PCURVE_S1.); +#84395 = CIRCLE('',#84396,0.2); +#84396 = AXIS2_PLACEMENT_3D('',#84397,#84398,#84399); +#84397 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#84398 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84399 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84400 = PCURVE('',#80943,#84401); +#84401 = DEFINITIONAL_REPRESENTATION('',(#84402),#84406); +#84402 = CIRCLE('',#84403,0.2); +#84403 = AXIS2_PLACEMENT_2D('',#84404,#84405); +#84404 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84405 = DIRECTION('',(1.,0.E+000)); +#84406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84407 = PCURVE('',#84408,#84413); +#84408 = CYLINDRICAL_SURFACE('',#84409,0.2); +#84409 = AXIS2_PLACEMENT_3D('',#84410,#84411,#84412); +#84410 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#84411 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84412 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84413 = DEFINITIONAL_REPRESENTATION('',(#84414),#84417); +#84414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84415,#84416),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#82023 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#82024 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#82025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82026 = ORIENTED_EDGE('',*,*,#82027,.F.); -#82027 = EDGE_CURVE('',#82028,#82000,#82030,.T.); -#82028 = VERTEX_POINT('',#82029); -#82029 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#82030 = SURFACE_CURVE('',#82031,(#82035,#82042),.PCURVE_S1.); -#82031 = LINE('',#82032,#82033); -#82032 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#82033 = VECTOR('',#82034,1.); -#82034 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#82035 = PCURVE('',#78551,#82036); -#82036 = DEFINITIONAL_REPRESENTATION('',(#82037),#82041); -#82037 = LINE('',#82038,#82039); -#82038 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#82039 = VECTOR('',#82040,1.); -#82040 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#82041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82042 = PCURVE('',#82043,#82048); -#82043 = PLANE('',#82044); -#82044 = AXIS2_PLACEMENT_3D('',#82045,#82046,#82047); -#82045 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#82046 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#82047 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#82048 = DEFINITIONAL_REPRESENTATION('',(#82049),#82053); -#82049 = LINE('',#82050,#82051); -#82050 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82051 = VECTOR('',#82052,1.); -#82052 = DIRECTION('',(1.,0.E+000)); -#82053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82054 = ORIENTED_EDGE('',*,*,#82055,.F.); -#82055 = EDGE_CURVE('',#82056,#82028,#82058,.T.); -#82056 = VERTEX_POINT('',#82057); -#82057 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); -#82058 = SURFACE_CURVE('',#82059,(#82064,#82075),.PCURVE_S1.); -#82059 = CIRCLE('',#82060,5.E-002); -#82060 = AXIS2_PLACEMENT_3D('',#82061,#82062,#82063); -#82061 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#82062 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82063 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82064 = PCURVE('',#78551,#82065); -#82065 = DEFINITIONAL_REPRESENTATION('',(#82066),#82074); -#82066 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82067,#82068,#82069,#82070 - ,#82071,#82072,#82073),.UNSPECIFIED.,.F.,.F.) +#84415 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#84416 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#84417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84418 = ORIENTED_EDGE('',*,*,#84419,.F.); +#84419 = EDGE_CURVE('',#84420,#84392,#84422,.T.); +#84420 = VERTEX_POINT('',#84421); +#84421 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#84422 = SURFACE_CURVE('',#84423,(#84427,#84434),.PCURVE_S1.); +#84423 = LINE('',#84424,#84425); +#84424 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#84425 = VECTOR('',#84426,1.); +#84426 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#84427 = PCURVE('',#80943,#84428); +#84428 = DEFINITIONAL_REPRESENTATION('',(#84429),#84433); +#84429 = LINE('',#84430,#84431); +#84430 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#84431 = VECTOR('',#84432,1.); +#84432 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#84433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84434 = PCURVE('',#84435,#84440); +#84435 = PLANE('',#84436); +#84436 = AXIS2_PLACEMENT_3D('',#84437,#84438,#84439); +#84437 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#84438 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#84439 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#84440 = DEFINITIONAL_REPRESENTATION('',(#84441),#84445); +#84441 = LINE('',#84442,#84443); +#84442 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84443 = VECTOR('',#84444,1.); +#84444 = DIRECTION('',(1.,0.E+000)); +#84445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84446 = ORIENTED_EDGE('',*,*,#84447,.F.); +#84447 = EDGE_CURVE('',#84448,#84420,#84450,.T.); +#84448 = VERTEX_POINT('',#84449); +#84449 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); +#84450 = SURFACE_CURVE('',#84451,(#84456,#84467),.PCURVE_S1.); +#84451 = CIRCLE('',#84452,5.E-002); +#84452 = AXIS2_PLACEMENT_3D('',#84453,#84454,#84455); +#84453 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#84454 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#84455 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84456 = PCURVE('',#80943,#84457); +#84457 = DEFINITIONAL_REPRESENTATION('',(#84458),#84466); +#84458 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84459,#84460,#84461,#84462 + ,#84463,#84464,#84465),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#82067 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#82068 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#82069 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#82070 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#82071 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#82072 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#82073 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#82074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82075 = PCURVE('',#82076,#82081); -#82076 = CYLINDRICAL_SURFACE('',#82077,5.E-002); -#82077 = AXIS2_PLACEMENT_3D('',#82078,#82079,#82080); -#82078 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#82079 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82080 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82081 = DEFINITIONAL_REPRESENTATION('',(#82082),#82085); -#82082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82083,#82084),.UNSPECIFIED., +#84459 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#84460 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#84461 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#84462 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#84463 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#84464 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#84465 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#84466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84467 = PCURVE('',#84468,#84473); +#84468 = CYLINDRICAL_SURFACE('',#84469,5.E-002); +#84469 = AXIS2_PLACEMENT_3D('',#84470,#84471,#84472); +#84470 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#84471 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84472 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84473 = DEFINITIONAL_REPRESENTATION('',(#84474),#84477); +#84474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84475,#84476),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#82083 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#82084 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#82085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82086 = ORIENTED_EDGE('',*,*,#82087,.F.); -#82087 = EDGE_CURVE('',#82088,#82056,#82090,.T.); -#82088 = VERTEX_POINT('',#82089); -#82089 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#82090 = SURFACE_CURVE('',#82091,(#82095,#82102),.PCURVE_S1.); -#82091 = LINE('',#82092,#82093); -#82092 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#82093 = VECTOR('',#82094,1.); -#82094 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#82095 = PCURVE('',#78551,#82096); -#82096 = DEFINITIONAL_REPRESENTATION('',(#82097),#82101); -#82097 = LINE('',#82098,#82099); -#82098 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#82099 = VECTOR('',#82100,1.); -#82100 = DIRECTION('',(0.E+000,-1.)); -#82101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82102 = PCURVE('',#82103,#82108); -#82103 = PLANE('',#82104); -#82104 = AXIS2_PLACEMENT_3D('',#82105,#82106,#82107); -#82105 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#82106 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82107 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82108 = DEFINITIONAL_REPRESENTATION('',(#82109),#82113); -#82109 = LINE('',#82110,#82111); -#82110 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82111 = VECTOR('',#82112,1.); -#82112 = DIRECTION('',(0.E+000,-1.)); -#82113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82114 = ORIENTED_EDGE('',*,*,#82115,.F.); -#82115 = EDGE_CURVE('',#82116,#82088,#82118,.T.); -#82116 = VERTEX_POINT('',#82117); -#82117 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82118 = SURFACE_CURVE('',#82119,(#82123,#82130),.PCURVE_S1.); -#82119 = LINE('',#82120,#82121); -#82120 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82121 = VECTOR('',#82122,1.); -#82122 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82123 = PCURVE('',#78551,#82124); -#82124 = DEFINITIONAL_REPRESENTATION('',(#82125),#82129); -#82125 = LINE('',#82126,#82127); -#82126 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#82127 = VECTOR('',#82128,1.); -#82128 = DIRECTION('',(-1.,0.E+000)); -#82129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82130 = PCURVE('',#82131,#82136); -#82131 = PLANE('',#82132); -#82132 = AXIS2_PLACEMENT_3D('',#82133,#82134,#82135); -#82133 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82134 = DIRECTION('',(0.E+000,1.,0.E+000)); -#82135 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82136 = DEFINITIONAL_REPRESENTATION('',(#82137),#82141); -#82137 = LINE('',#82138,#82139); -#82138 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82139 = VECTOR('',#82140,1.); -#82140 = DIRECTION('',(1.,0.E+000)); -#82141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82142 = ORIENTED_EDGE('',*,*,#82143,.F.); -#82143 = EDGE_CURVE('',#82144,#82116,#82146,.T.); -#82144 = VERTEX_POINT('',#82145); -#82145 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); -#82146 = SURFACE_CURVE('',#82147,(#82151,#82158),.PCURVE_S1.); -#82147 = LINE('',#82148,#82149); -#82148 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82149 = VECTOR('',#82150,1.); -#82150 = DIRECTION('',(0.E+000,1.,0.E+000)); -#82151 = PCURVE('',#78551,#82152); -#82152 = DEFINITIONAL_REPRESENTATION('',(#82153),#82157); -#82153 = LINE('',#82154,#82155); -#82154 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#82155 = VECTOR('',#82156,1.); -#82156 = DIRECTION('',(0.E+000,1.)); -#82157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82158 = PCURVE('',#82159,#82164); -#82159 = PLANE('',#82160); -#82160 = AXIS2_PLACEMENT_3D('',#82161,#82162,#82163); -#82161 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82162 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82163 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82164 = DEFINITIONAL_REPRESENTATION('',(#82165),#82169); -#82165 = LINE('',#82166,#82167); -#82166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82167 = VECTOR('',#82168,1.); -#82168 = DIRECTION('',(0.E+000,1.)); -#82169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82170 = ORIENTED_EDGE('',*,*,#82171,.F.); -#82171 = EDGE_CURVE('',#82172,#82144,#82174,.T.); -#82172 = VERTEX_POINT('',#82173); -#82173 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); -#82174 = SURFACE_CURVE('',#82175,(#82180,#82187),.PCURVE_S1.); -#82175 = CIRCLE('',#82176,0.2); -#82176 = AXIS2_PLACEMENT_3D('',#82177,#82178,#82179); -#82177 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#82178 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82179 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82180 = PCURVE('',#78551,#82181); -#82181 = DEFINITIONAL_REPRESENTATION('',(#82182),#82186); -#82182 = CIRCLE('',#82183,0.2); -#82183 = AXIS2_PLACEMENT_2D('',#82184,#82185); -#82184 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#82185 = DIRECTION('',(1.,0.E+000)); -#82186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82187 = PCURVE('',#82188,#82193); -#82188 = CYLINDRICAL_SURFACE('',#82189,0.2); -#82189 = AXIS2_PLACEMENT_3D('',#82190,#82191,#82192); -#82190 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#82191 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82192 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82193 = DEFINITIONAL_REPRESENTATION('',(#82194),#82197); -#82194 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82195,#82196),.UNSPECIFIED., +#84475 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#84476 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#84477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84478 = ORIENTED_EDGE('',*,*,#84479,.F.); +#84479 = EDGE_CURVE('',#84480,#84448,#84482,.T.); +#84480 = VERTEX_POINT('',#84481); +#84481 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#84482 = SURFACE_CURVE('',#84483,(#84487,#84494),.PCURVE_S1.); +#84483 = LINE('',#84484,#84485); +#84484 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#84485 = VECTOR('',#84486,1.); +#84486 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#84487 = PCURVE('',#80943,#84488); +#84488 = DEFINITIONAL_REPRESENTATION('',(#84489),#84493); +#84489 = LINE('',#84490,#84491); +#84490 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#84491 = VECTOR('',#84492,1.); +#84492 = DIRECTION('',(0.E+000,-1.)); +#84493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84494 = PCURVE('',#84495,#84500); +#84495 = PLANE('',#84496); +#84496 = AXIS2_PLACEMENT_3D('',#84497,#84498,#84499); +#84497 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#84498 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84499 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84500 = DEFINITIONAL_REPRESENTATION('',(#84501),#84505); +#84501 = LINE('',#84502,#84503); +#84502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84503 = VECTOR('',#84504,1.); +#84504 = DIRECTION('',(0.E+000,-1.)); +#84505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84506 = ORIENTED_EDGE('',*,*,#84507,.F.); +#84507 = EDGE_CURVE('',#84508,#84480,#84510,.T.); +#84508 = VERTEX_POINT('',#84509); +#84509 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#84510 = SURFACE_CURVE('',#84511,(#84515,#84522),.PCURVE_S1.); +#84511 = LINE('',#84512,#84513); +#84512 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#84513 = VECTOR('',#84514,1.); +#84514 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84515 = PCURVE('',#80943,#84516); +#84516 = DEFINITIONAL_REPRESENTATION('',(#84517),#84521); +#84517 = LINE('',#84518,#84519); +#84518 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#84519 = VECTOR('',#84520,1.); +#84520 = DIRECTION('',(-1.,0.E+000)); +#84521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84522 = PCURVE('',#84523,#84528); +#84523 = PLANE('',#84524); +#84524 = AXIS2_PLACEMENT_3D('',#84525,#84526,#84527); +#84525 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#84526 = DIRECTION('',(0.E+000,1.,0.E+000)); +#84527 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84528 = DEFINITIONAL_REPRESENTATION('',(#84529),#84533); +#84529 = LINE('',#84530,#84531); +#84530 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84531 = VECTOR('',#84532,1.); +#84532 = DIRECTION('',(1.,0.E+000)); +#84533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84534 = ORIENTED_EDGE('',*,*,#84535,.F.); +#84535 = EDGE_CURVE('',#84536,#84508,#84538,.T.); +#84536 = VERTEX_POINT('',#84537); +#84537 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); +#84538 = SURFACE_CURVE('',#84539,(#84543,#84550),.PCURVE_S1.); +#84539 = LINE('',#84540,#84541); +#84540 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#84541 = VECTOR('',#84542,1.); +#84542 = DIRECTION('',(0.E+000,1.,0.E+000)); +#84543 = PCURVE('',#80943,#84544); +#84544 = DEFINITIONAL_REPRESENTATION('',(#84545),#84549); +#84545 = LINE('',#84546,#84547); +#84546 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#84547 = VECTOR('',#84548,1.); +#84548 = DIRECTION('',(0.E+000,1.)); +#84549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84550 = PCURVE('',#84551,#84556); +#84551 = PLANE('',#84552); +#84552 = AXIS2_PLACEMENT_3D('',#84553,#84554,#84555); +#84553 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#84554 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84555 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#84556 = DEFINITIONAL_REPRESENTATION('',(#84557),#84561); +#84557 = LINE('',#84558,#84559); +#84558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84559 = VECTOR('',#84560,1.); +#84560 = DIRECTION('',(0.E+000,1.)); +#84561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84562 = ORIENTED_EDGE('',*,*,#84563,.F.); +#84563 = EDGE_CURVE('',#84564,#84536,#84566,.T.); +#84564 = VERTEX_POINT('',#84565); +#84565 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); +#84566 = SURFACE_CURVE('',#84567,(#84572,#84579),.PCURVE_S1.); +#84567 = CIRCLE('',#84568,0.2); +#84568 = AXIS2_PLACEMENT_3D('',#84569,#84570,#84571); +#84569 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#84570 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84571 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84572 = PCURVE('',#80943,#84573); +#84573 = DEFINITIONAL_REPRESENTATION('',(#84574),#84578); +#84574 = CIRCLE('',#84575,0.2); +#84575 = AXIS2_PLACEMENT_2D('',#84576,#84577); +#84576 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#84577 = DIRECTION('',(1.,0.E+000)); +#84578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84579 = PCURVE('',#84580,#84585); +#84580 = CYLINDRICAL_SURFACE('',#84581,0.2); +#84581 = AXIS2_PLACEMENT_3D('',#84582,#84583,#84584); +#84582 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#84583 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84584 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84585 = DEFINITIONAL_REPRESENTATION('',(#84586),#84589); +#84586 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84587,#84588),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#82195 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#82196 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#82197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82198 = ORIENTED_EDGE('',*,*,#82199,.F.); -#82199 = EDGE_CURVE('',#82200,#82172,#82202,.T.); -#82200 = VERTEX_POINT('',#82201); -#82201 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#82202 = SURFACE_CURVE('',#82203,(#82207,#82214),.PCURVE_S1.); -#82203 = LINE('',#82204,#82205); -#82204 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#82205 = VECTOR('',#82206,1.); -#82206 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#82207 = PCURVE('',#78551,#82208); -#82208 = DEFINITIONAL_REPRESENTATION('',(#82209),#82213); -#82209 = LINE('',#82210,#82211); -#82210 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); -#82211 = VECTOR('',#82212,1.); -#82212 = DIRECTION('',(0.993981062721,0.109552028512)); -#82213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82214 = PCURVE('',#82215,#82220); -#82215 = PLANE('',#82216); -#82216 = AXIS2_PLACEMENT_3D('',#82217,#82218,#82219); -#82217 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#82218 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#82219 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#82220 = DEFINITIONAL_REPRESENTATION('',(#82221),#82225); -#82221 = LINE('',#82222,#82223); -#82222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82223 = VECTOR('',#82224,1.); -#82224 = DIRECTION('',(1.,0.E+000)); -#82225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82226 = ORIENTED_EDGE('',*,*,#82227,.F.); -#82227 = EDGE_CURVE('',#81901,#82200,#82228,.T.); -#82228 = SURFACE_CURVE('',#82229,(#82234,#82245),.PCURVE_S1.); -#82229 = CIRCLE('',#82230,5.E-002); -#82230 = AXIS2_PLACEMENT_3D('',#82231,#82232,#82233); -#82231 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#82232 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82233 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82234 = PCURVE('',#78551,#82235); -#82235 = DEFINITIONAL_REPRESENTATION('',(#82236),#82244); -#82236 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82237,#82238,#82239,#82240 - ,#82241,#82242,#82243),.UNSPECIFIED.,.F.,.F.) +#84587 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#84588 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#84589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84590 = ORIENTED_EDGE('',*,*,#84591,.F.); +#84591 = EDGE_CURVE('',#84592,#84564,#84594,.T.); +#84592 = VERTEX_POINT('',#84593); +#84593 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#84594 = SURFACE_CURVE('',#84595,(#84599,#84606),.PCURVE_S1.); +#84595 = LINE('',#84596,#84597); +#84596 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#84597 = VECTOR('',#84598,1.); +#84598 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#84599 = PCURVE('',#80943,#84600); +#84600 = DEFINITIONAL_REPRESENTATION('',(#84601),#84605); +#84601 = LINE('',#84602,#84603); +#84602 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); +#84603 = VECTOR('',#84604,1.); +#84604 = DIRECTION('',(0.993981062721,0.109552028512)); +#84605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84606 = PCURVE('',#84607,#84612); +#84607 = PLANE('',#84608); +#84608 = AXIS2_PLACEMENT_3D('',#84609,#84610,#84611); +#84609 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#84610 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#84611 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#84612 = DEFINITIONAL_REPRESENTATION('',(#84613),#84617); +#84613 = LINE('',#84614,#84615); +#84614 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84615 = VECTOR('',#84616,1.); +#84616 = DIRECTION('',(1.,0.E+000)); +#84617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84618 = ORIENTED_EDGE('',*,*,#84619,.F.); +#84619 = EDGE_CURVE('',#84293,#84592,#84620,.T.); +#84620 = SURFACE_CURVE('',#84621,(#84626,#84637),.PCURVE_S1.); +#84621 = CIRCLE('',#84622,5.E-002); +#84622 = AXIS2_PLACEMENT_3D('',#84623,#84624,#84625); +#84623 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#84624 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#84625 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84626 = PCURVE('',#80943,#84627); +#84627 = DEFINITIONAL_REPRESENTATION('',(#84628),#84636); +#84628 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84629,#84630,#84631,#84632 + ,#84633,#84634,#84635),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#82237 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#82238 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#82239 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#82240 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#82241 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#82242 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#82243 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#82244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82245 = PCURVE('',#81939,#82246); -#82246 = DEFINITIONAL_REPRESENTATION('',(#82247),#82250); -#82247 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82248,#82249),.UNSPECIFIED., +#84629 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#84630 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#84631 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#84632 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#84633 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#84634 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#84635 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#84636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84637 = PCURVE('',#84331,#84638); +#84638 = DEFINITIONAL_REPRESENTATION('',(#84639),#84642); +#84639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84640,#84641),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#82248 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#82249 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#82250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82251 = ADVANCED_FACE('',(#82252),#78523,.T.); -#82252 = FACE_BOUND('',#82253,.T.); -#82253 = EDGE_LOOP('',(#82254,#82255,#82278,#82298)); -#82254 = ORIENTED_EDGE('',*,*,#78507,.F.); -#82255 = ORIENTED_EDGE('',*,*,#82256,.F.); -#82256 = EDGE_CURVE('',#82257,#78480,#82259,.T.); -#82257 = VERTEX_POINT('',#82258); -#82258 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); -#82259 = SURFACE_CURVE('',#82260,(#82264,#82271),.PCURVE_S1.); -#82260 = LINE('',#82261,#82262); -#82261 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); -#82262 = VECTOR('',#82263,1.); -#82263 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#82264 = PCURVE('',#78523,#82265); -#82265 = DEFINITIONAL_REPRESENTATION('',(#82266),#82270); -#82266 = LINE('',#82267,#82268); -#82267 = CARTESIAN_POINT('',(0.4,0.E+000)); -#82268 = VECTOR('',#82269,1.); -#82269 = DIRECTION('',(0.E+000,-1.)); -#82270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82271 = PCURVE('',#78495,#82272); -#82272 = DEFINITIONAL_REPRESENTATION('',(#82273),#82277); -#82273 = LINE('',#82274,#82275); -#82274 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#82275 = VECTOR('',#82276,1.); -#82276 = DIRECTION('',(0.E+000,-1.)); -#82277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82278 = ORIENTED_EDGE('',*,*,#82279,.F.); -#82279 = EDGE_CURVE('',#81977,#82257,#82280,.T.); -#82280 = SURFACE_CURVE('',#82281,(#82285,#82292),.PCURVE_S1.); -#82281 = LINE('',#82282,#82283); -#82282 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#82283 = VECTOR('',#82284,1.); -#82284 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82285 = PCURVE('',#78523,#82286); -#82286 = DEFINITIONAL_REPRESENTATION('',(#82287),#82291); -#82287 = LINE('',#82288,#82289); -#82288 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82289 = VECTOR('',#82290,1.); -#82290 = DIRECTION('',(1.,0.E+000)); -#82291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82292 = PCURVE('',#82016,#82293); -#82293 = DEFINITIONAL_REPRESENTATION('',(#82294),#82297); -#82294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82295,#82296),.UNSPECIFIED., +#84640 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#84641 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#84642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84643 = ADVANCED_FACE('',(#84644),#80915,.T.); +#84644 = FACE_BOUND('',#84645,.T.); +#84645 = EDGE_LOOP('',(#84646,#84647,#84670,#84690)); +#84646 = ORIENTED_EDGE('',*,*,#80899,.F.); +#84647 = ORIENTED_EDGE('',*,*,#84648,.F.); +#84648 = EDGE_CURVE('',#84649,#80872,#84651,.T.); +#84649 = VERTEX_POINT('',#84650); +#84650 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); +#84651 = SURFACE_CURVE('',#84652,(#84656,#84663),.PCURVE_S1.); +#84652 = LINE('',#84653,#84654); +#84653 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); +#84654 = VECTOR('',#84655,1.); +#84655 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#84656 = PCURVE('',#80915,#84657); +#84657 = DEFINITIONAL_REPRESENTATION('',(#84658),#84662); +#84658 = LINE('',#84659,#84660); +#84659 = CARTESIAN_POINT('',(0.4,0.E+000)); +#84660 = VECTOR('',#84661,1.); +#84661 = DIRECTION('',(0.E+000,-1.)); +#84662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84663 = PCURVE('',#80887,#84664); +#84664 = DEFINITIONAL_REPRESENTATION('',(#84665),#84669); +#84665 = LINE('',#84666,#84667); +#84666 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#84667 = VECTOR('',#84668,1.); +#84668 = DIRECTION('',(0.E+000,-1.)); +#84669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84670 = ORIENTED_EDGE('',*,*,#84671,.F.); +#84671 = EDGE_CURVE('',#84369,#84649,#84672,.T.); +#84672 = SURFACE_CURVE('',#84673,(#84677,#84684),.PCURVE_S1.); +#84673 = LINE('',#84674,#84675); +#84674 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#84675 = VECTOR('',#84676,1.); +#84676 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84677 = PCURVE('',#80915,#84678); +#84678 = DEFINITIONAL_REPRESENTATION('',(#84679),#84683); +#84679 = LINE('',#84680,#84681); +#84680 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84681 = VECTOR('',#84682,1.); +#84682 = DIRECTION('',(1.,0.E+000)); +#84683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84684 = PCURVE('',#84408,#84685); +#84685 = DEFINITIONAL_REPRESENTATION('',(#84686),#84689); +#84686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84687,#84688),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82295 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#82296 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#82297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82298 = ORIENTED_EDGE('',*,*,#81976,.T.); -#82299 = ADVANCED_FACE('',(#82300),#78495,.T.); -#82300 = FACE_BOUND('',#82301,.T.); -#82301 = EDGE_LOOP('',(#82302,#82303,#82304,#82331,#82354,#82377,#82400, - #82423,#82446,#82473,#82496,#82517)); -#82302 = ORIENTED_EDGE('',*,*,#78479,.F.); -#82303 = ORIENTED_EDGE('',*,*,#81950,.T.); -#82304 = ORIENTED_EDGE('',*,*,#82305,.T.); -#82305 = EDGE_CURVE('',#81924,#82306,#82308,.T.); -#82306 = VERTEX_POINT('',#82307); -#82307 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); -#82308 = SURFACE_CURVE('',#82309,(#82314,#82325),.PCURVE_S1.); -#82309 = CIRCLE('',#82310,5.E-002); -#82310 = AXIS2_PLACEMENT_3D('',#82311,#82312,#82313); -#82311 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#82312 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82313 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82314 = PCURVE('',#78495,#82315); -#82315 = DEFINITIONAL_REPRESENTATION('',(#82316),#82324); -#82316 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82317,#82318,#82319,#82320 - ,#82321,#82322,#82323),.UNSPECIFIED.,.F.,.F.) +#84687 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#84688 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#84689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84690 = ORIENTED_EDGE('',*,*,#84368,.T.); +#84691 = ADVANCED_FACE('',(#84692),#80887,.T.); +#84692 = FACE_BOUND('',#84693,.T.); +#84693 = EDGE_LOOP('',(#84694,#84695,#84696,#84723,#84746,#84769,#84792, + #84815,#84838,#84865,#84888,#84909)); +#84694 = ORIENTED_EDGE('',*,*,#80871,.F.); +#84695 = ORIENTED_EDGE('',*,*,#84342,.T.); +#84696 = ORIENTED_EDGE('',*,*,#84697,.T.); +#84697 = EDGE_CURVE('',#84316,#84698,#84700,.T.); +#84698 = VERTEX_POINT('',#84699); +#84699 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); +#84700 = SURFACE_CURVE('',#84701,(#84706,#84717),.PCURVE_S1.); +#84701 = CIRCLE('',#84702,5.E-002); +#84702 = AXIS2_PLACEMENT_3D('',#84703,#84704,#84705); +#84703 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#84704 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#84705 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84706 = PCURVE('',#80887,#84707); +#84707 = DEFINITIONAL_REPRESENTATION('',(#84708),#84716); +#84708 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84709,#84710,#84711,#84712 + ,#84713,#84714,#84715),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#82317 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#82318 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#82319 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#82320 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#82321 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#82322 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#82323 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#82324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82325 = PCURVE('',#81939,#82326); -#82326 = DEFINITIONAL_REPRESENTATION('',(#82327),#82330); -#82327 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82328,#82329),.UNSPECIFIED., +#84709 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#84710 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#84711 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#84712 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#84713 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#84714 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#84715 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#84716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84717 = PCURVE('',#84331,#84718); +#84718 = DEFINITIONAL_REPRESENTATION('',(#84719),#84722); +#84719 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84720,#84721),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#82328 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#82329 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#82330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82331 = ORIENTED_EDGE('',*,*,#82332,.T.); -#82332 = EDGE_CURVE('',#82306,#82333,#82335,.T.); -#82333 = VERTEX_POINT('',#82334); -#82334 = CARTESIAN_POINT('',(-0.745,0.746501027564,0.178089594298)); -#82335 = SURFACE_CURVE('',#82336,(#82340,#82347),.PCURVE_S1.); -#82336 = LINE('',#82337,#82338); -#82337 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); -#82338 = VECTOR('',#82339,1.); -#82339 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#82340 = PCURVE('',#78495,#82341); -#82341 = DEFINITIONAL_REPRESENTATION('',(#82342),#82346); -#82342 = LINE('',#82343,#82344); -#82343 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); -#82344 = VECTOR('',#82345,1.); -#82345 = DIRECTION('',(0.993981062721,0.109552028512)); -#82346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82347 = PCURVE('',#82215,#82348); -#82348 = DEFINITIONAL_REPRESENTATION('',(#82349),#82353); -#82349 = LINE('',#82350,#82351); -#82350 = CARTESIAN_POINT('',(0.E+000,0.4)); -#82351 = VECTOR('',#82352,1.); -#82352 = DIRECTION('',(1.,0.E+000)); -#82353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82354 = ORIENTED_EDGE('',*,*,#82355,.T.); -#82355 = EDGE_CURVE('',#82333,#82356,#82358,.T.); -#82356 = VERTEX_POINT('',#82357); -#82357 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.E+000)); -#82358 = SURFACE_CURVE('',#82359,(#82364,#82371),.PCURVE_S1.); -#82359 = CIRCLE('',#82360,0.2); -#82360 = AXIS2_PLACEMENT_3D('',#82361,#82362,#82363); -#82361 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); -#82362 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82363 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82364 = PCURVE('',#78495,#82365); -#82365 = DEFINITIONAL_REPRESENTATION('',(#82366),#82370); -#82366 = CIRCLE('',#82367,0.2); -#82367 = AXIS2_PLACEMENT_2D('',#82368,#82369); -#82368 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#82369 = DIRECTION('',(1.,0.E+000)); -#82370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82371 = PCURVE('',#82188,#82372); -#82372 = DEFINITIONAL_REPRESENTATION('',(#82373),#82376); -#82373 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82374,#82375),.UNSPECIFIED., +#84720 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#84721 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84723 = ORIENTED_EDGE('',*,*,#84724,.T.); +#84724 = EDGE_CURVE('',#84698,#84725,#84727,.T.); +#84725 = VERTEX_POINT('',#84726); +#84726 = CARTESIAN_POINT('',(-0.745,0.746501027564,0.178089594298)); +#84727 = SURFACE_CURVE('',#84728,(#84732,#84739),.PCURVE_S1.); +#84728 = LINE('',#84729,#84730); +#84729 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); +#84730 = VECTOR('',#84731,1.); +#84731 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#84732 = PCURVE('',#80887,#84733); +#84733 = DEFINITIONAL_REPRESENTATION('',(#84734),#84738); +#84734 = LINE('',#84735,#84736); +#84735 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002)); +#84736 = VECTOR('',#84737,1.); +#84737 = DIRECTION('',(0.993981062721,0.109552028512)); +#84738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84739 = PCURVE('',#84607,#84740); +#84740 = DEFINITIONAL_REPRESENTATION('',(#84741),#84745); +#84741 = LINE('',#84742,#84743); +#84742 = CARTESIAN_POINT('',(0.E+000,0.4)); +#84743 = VECTOR('',#84744,1.); +#84744 = DIRECTION('',(1.,0.E+000)); +#84745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84746 = ORIENTED_EDGE('',*,*,#84747,.T.); +#84747 = EDGE_CURVE('',#84725,#84748,#84750,.T.); +#84748 = VERTEX_POINT('',#84749); +#84749 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.E+000)); +#84750 = SURFACE_CURVE('',#84751,(#84756,#84763),.PCURVE_S1.); +#84751 = CIRCLE('',#84752,0.2); +#84752 = AXIS2_PLACEMENT_3D('',#84753,#84754,#84755); +#84753 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); +#84754 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84755 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84756 = PCURVE('',#80887,#84757); +#84757 = DEFINITIONAL_REPRESENTATION('',(#84758),#84762); +#84758 = CIRCLE('',#84759,0.2); +#84759 = AXIS2_PLACEMENT_2D('',#84760,#84761); +#84760 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#84761 = DIRECTION('',(1.,0.E+000)); +#84762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84763 = PCURVE('',#84580,#84764); +#84764 = DEFINITIONAL_REPRESENTATION('',(#84765),#84768); +#84765 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84766,#84767),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#82374 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#82375 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#82376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82377 = ORIENTED_EDGE('',*,*,#82378,.T.); -#82378 = EDGE_CURVE('',#82356,#82379,#82381,.T.); -#82379 = VERTEX_POINT('',#82380); -#82380 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#82381 = SURFACE_CURVE('',#82382,(#82386,#82393),.PCURVE_S1.); -#82382 = LINE('',#82383,#82384); -#82383 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#82384 = VECTOR('',#82385,1.); -#82385 = DIRECTION('',(0.E+000,1.,0.E+000)); -#82386 = PCURVE('',#78495,#82387); -#82387 = DEFINITIONAL_REPRESENTATION('',(#82388),#82392); -#82388 = LINE('',#82389,#82390); -#82389 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#82390 = VECTOR('',#82391,1.); -#82391 = DIRECTION('',(0.E+000,1.)); -#82392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82393 = PCURVE('',#82159,#82394); -#82394 = DEFINITIONAL_REPRESENTATION('',(#82395),#82399); -#82395 = LINE('',#82396,#82397); -#82396 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#82397 = VECTOR('',#82398,1.); -#82398 = DIRECTION('',(0.E+000,1.)); -#82399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82400 = ORIENTED_EDGE('',*,*,#82401,.T.); -#82401 = EDGE_CURVE('',#82379,#82402,#82404,.T.); -#82402 = VERTEX_POINT('',#82403); -#82403 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); -#82404 = SURFACE_CURVE('',#82405,(#82409,#82416),.PCURVE_S1.); -#82405 = LINE('',#82406,#82407); -#82406 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#82407 = VECTOR('',#82408,1.); -#82408 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82409 = PCURVE('',#78495,#82410); -#82410 = DEFINITIONAL_REPRESENTATION('',(#82411),#82415); -#82411 = LINE('',#82412,#82413); -#82412 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#82413 = VECTOR('',#82414,1.); -#82414 = DIRECTION('',(-1.,0.E+000)); -#82415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82416 = PCURVE('',#82131,#82417); -#82417 = DEFINITIONAL_REPRESENTATION('',(#82418),#82422); -#82418 = LINE('',#82419,#82420); -#82419 = CARTESIAN_POINT('',(0.E+000,0.4)); -#82420 = VECTOR('',#82421,1.); -#82421 = DIRECTION('',(1.,0.E+000)); -#82422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82423 = ORIENTED_EDGE('',*,*,#82424,.T.); -#82424 = EDGE_CURVE('',#82402,#82425,#82427,.T.); -#82425 = VERTEX_POINT('',#82426); -#82426 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.15)); -#82427 = SURFACE_CURVE('',#82428,(#82432,#82439),.PCURVE_S1.); -#82428 = LINE('',#82429,#82430); -#82429 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); -#82430 = VECTOR('',#82431,1.); -#82431 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#82432 = PCURVE('',#78495,#82433); -#82433 = DEFINITIONAL_REPRESENTATION('',(#82434),#82438); -#82434 = LINE('',#82435,#82436); -#82435 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#82436 = VECTOR('',#82437,1.); -#82437 = DIRECTION('',(0.E+000,-1.)); -#82438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82439 = PCURVE('',#82103,#82440); -#82440 = DEFINITIONAL_REPRESENTATION('',(#82441),#82445); -#82441 = LINE('',#82442,#82443); -#82442 = CARTESIAN_POINT('',(0.4,0.E+000)); -#82443 = VECTOR('',#82444,1.); -#82444 = DIRECTION('',(0.E+000,-1.)); -#82445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82446 = ORIENTED_EDGE('',*,*,#82447,.T.); -#82447 = EDGE_CURVE('',#82425,#82448,#82450,.T.); -#82448 = VERTEX_POINT('',#82449); -#82449 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); -#82450 = SURFACE_CURVE('',#82451,(#82456,#82467),.PCURVE_S1.); -#82451 = CIRCLE('',#82452,5.E-002); -#82452 = AXIS2_PLACEMENT_3D('',#82453,#82454,#82455); -#82453 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); -#82454 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82455 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82456 = PCURVE('',#78495,#82457); -#82457 = DEFINITIONAL_REPRESENTATION('',(#82458),#82466); -#82458 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82459,#82460,#82461,#82462 - ,#82463,#82464,#82465),.UNSPECIFIED.,.F.,.F.) +#84766 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#84767 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#84768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84769 = ORIENTED_EDGE('',*,*,#84770,.T.); +#84770 = EDGE_CURVE('',#84748,#84771,#84773,.T.); +#84771 = VERTEX_POINT('',#84772); +#84772 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#84773 = SURFACE_CURVE('',#84774,(#84778,#84785),.PCURVE_S1.); +#84774 = LINE('',#84775,#84776); +#84775 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#84776 = VECTOR('',#84777,1.); +#84777 = DIRECTION('',(0.E+000,1.,0.E+000)); +#84778 = PCURVE('',#80887,#84779); +#84779 = DEFINITIONAL_REPRESENTATION('',(#84780),#84784); +#84780 = LINE('',#84781,#84782); +#84781 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#84782 = VECTOR('',#84783,1.); +#84783 = DIRECTION('',(0.E+000,1.)); +#84784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84785 = PCURVE('',#84551,#84786); +#84786 = DEFINITIONAL_REPRESENTATION('',(#84787),#84791); +#84787 = LINE('',#84788,#84789); +#84788 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#84789 = VECTOR('',#84790,1.); +#84790 = DIRECTION('',(0.E+000,1.)); +#84791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84792 = ORIENTED_EDGE('',*,*,#84793,.T.); +#84793 = EDGE_CURVE('',#84771,#84794,#84796,.T.); +#84794 = VERTEX_POINT('',#84795); +#84795 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); +#84796 = SURFACE_CURVE('',#84797,(#84801,#84808),.PCURVE_S1.); +#84797 = LINE('',#84798,#84799); +#84798 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#84799 = VECTOR('',#84800,1.); +#84800 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84801 = PCURVE('',#80887,#84802); +#84802 = DEFINITIONAL_REPRESENTATION('',(#84803),#84807); +#84803 = LINE('',#84804,#84805); +#84804 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#84805 = VECTOR('',#84806,1.); +#84806 = DIRECTION('',(-1.,0.E+000)); +#84807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84808 = PCURVE('',#84523,#84809); +#84809 = DEFINITIONAL_REPRESENTATION('',(#84810),#84814); +#84810 = LINE('',#84811,#84812); +#84811 = CARTESIAN_POINT('',(0.E+000,0.4)); +#84812 = VECTOR('',#84813,1.); +#84813 = DIRECTION('',(1.,0.E+000)); +#84814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84815 = ORIENTED_EDGE('',*,*,#84816,.T.); +#84816 = EDGE_CURVE('',#84794,#84817,#84819,.T.); +#84817 = VERTEX_POINT('',#84818); +#84818 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.15)); +#84819 = SURFACE_CURVE('',#84820,(#84824,#84831),.PCURVE_S1.); +#84820 = LINE('',#84821,#84822); +#84821 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); +#84822 = VECTOR('',#84823,1.); +#84823 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#84824 = PCURVE('',#80887,#84825); +#84825 = DEFINITIONAL_REPRESENTATION('',(#84826),#84830); +#84826 = LINE('',#84827,#84828); +#84827 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#84828 = VECTOR('',#84829,1.); +#84829 = DIRECTION('',(0.E+000,-1.)); +#84830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84831 = PCURVE('',#84495,#84832); +#84832 = DEFINITIONAL_REPRESENTATION('',(#84833),#84837); +#84833 = LINE('',#84834,#84835); +#84834 = CARTESIAN_POINT('',(0.4,0.E+000)); +#84835 = VECTOR('',#84836,1.); +#84836 = DIRECTION('',(0.E+000,-1.)); +#84837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84838 = ORIENTED_EDGE('',*,*,#84839,.T.); +#84839 = EDGE_CURVE('',#84817,#84840,#84842,.T.); +#84840 = VERTEX_POINT('',#84841); +#84841 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); +#84842 = SURFACE_CURVE('',#84843,(#84848,#84859),.PCURVE_S1.); +#84843 = CIRCLE('',#84844,5.E-002); +#84844 = AXIS2_PLACEMENT_3D('',#84845,#84846,#84847); +#84845 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); +#84846 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#84847 = DIRECTION('',(0.E+000,0.E+000,1.)); +#84848 = PCURVE('',#80887,#84849); +#84849 = DEFINITIONAL_REPRESENTATION('',(#84850),#84858); +#84850 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84851,#84852,#84853,#84854 + ,#84855,#84856,#84857),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#82459 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#82460 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#82461 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#82462 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#82463 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#82464 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#82465 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#82466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82467 = PCURVE('',#82076,#82468); -#82468 = DEFINITIONAL_REPRESENTATION('',(#82469),#82472); -#82469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82470,#82471),.UNSPECIFIED., +#84851 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#84852 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#84853 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#84854 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#84855 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#84856 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#84857 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#84858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84859 = PCURVE('',#84468,#84860); +#84860 = DEFINITIONAL_REPRESENTATION('',(#84861),#84864); +#84861 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84862,#84863),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#82470 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#82471 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#82472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82473 = ORIENTED_EDGE('',*,*,#82474,.T.); -#82474 = EDGE_CURVE('',#82448,#82475,#82477,.T.); -#82475 = VERTEX_POINT('',#82476); -#82476 = CARTESIAN_POINT('',(-0.745,0.854004213739,0.571910405702)); -#82477 = SURFACE_CURVE('',#82478,(#82482,#82489),.PCURVE_S1.); -#82478 = LINE('',#82479,#82480); -#82479 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); -#82480 = VECTOR('',#82481,1.); -#82481 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#82482 = PCURVE('',#78495,#82483); -#82483 = DEFINITIONAL_REPRESENTATION('',(#82484),#82488); -#82484 = LINE('',#82485,#82486); -#82485 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#82486 = VECTOR('',#82487,1.); -#82487 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#82488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82489 = PCURVE('',#82043,#82490); -#82490 = DEFINITIONAL_REPRESENTATION('',(#82491),#82495); -#82491 = LINE('',#82492,#82493); -#82492 = CARTESIAN_POINT('',(0.E+000,0.4)); -#82493 = VECTOR('',#82494,1.); -#82494 = DIRECTION('',(1.,0.E+000)); -#82495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82496 = ORIENTED_EDGE('',*,*,#82497,.T.); -#82497 = EDGE_CURVE('',#82475,#82257,#82498,.T.); -#82498 = SURFACE_CURVE('',#82499,(#82504,#82511),.PCURVE_S1.); -#82499 = CIRCLE('',#82500,0.2); -#82500 = AXIS2_PLACEMENT_3D('',#82501,#82502,#82503); -#82501 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#82502 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82503 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82504 = PCURVE('',#78495,#82505); -#82505 = DEFINITIONAL_REPRESENTATION('',(#82506),#82510); -#82506 = CIRCLE('',#82507,0.2); -#82507 = AXIS2_PLACEMENT_2D('',#82508,#82509); -#82508 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82509 = DIRECTION('',(1.,0.E+000)); -#82510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82511 = PCURVE('',#82016,#82512); -#82512 = DEFINITIONAL_REPRESENTATION('',(#82513),#82516); -#82513 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82514,#82515),.UNSPECIFIED., +#84862 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#84863 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#84864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84865 = ORIENTED_EDGE('',*,*,#84866,.T.); +#84866 = EDGE_CURVE('',#84840,#84867,#84869,.T.); +#84867 = VERTEX_POINT('',#84868); +#84868 = CARTESIAN_POINT('',(-0.745,0.854004213739,0.571910405702)); +#84869 = SURFACE_CURVE('',#84870,(#84874,#84881),.PCURVE_S1.); +#84870 = LINE('',#84871,#84872); +#84871 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); +#84872 = VECTOR('',#84873,1.); +#84873 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#84874 = PCURVE('',#80887,#84875); +#84875 = DEFINITIONAL_REPRESENTATION('',(#84876),#84880); +#84876 = LINE('',#84877,#84878); +#84877 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#84878 = VECTOR('',#84879,1.); +#84879 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#84880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84881 = PCURVE('',#84435,#84882); +#84882 = DEFINITIONAL_REPRESENTATION('',(#84883),#84887); +#84883 = LINE('',#84884,#84885); +#84884 = CARTESIAN_POINT('',(0.E+000,0.4)); +#84885 = VECTOR('',#84886,1.); +#84886 = DIRECTION('',(1.,0.E+000)); +#84887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84888 = ORIENTED_EDGE('',*,*,#84889,.T.); +#84889 = EDGE_CURVE('',#84867,#84649,#84890,.T.); +#84890 = SURFACE_CURVE('',#84891,(#84896,#84903),.PCURVE_S1.); +#84891 = CIRCLE('',#84892,0.2); +#84892 = AXIS2_PLACEMENT_3D('',#84893,#84894,#84895); +#84893 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#84894 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84895 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#84896 = PCURVE('',#80887,#84897); +#84897 = DEFINITIONAL_REPRESENTATION('',(#84898),#84902); +#84898 = CIRCLE('',#84899,0.2); +#84899 = AXIS2_PLACEMENT_2D('',#84900,#84901); +#84900 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84901 = DIRECTION('',(1.,0.E+000)); +#84902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84903 = PCURVE('',#84408,#84904); +#84904 = DEFINITIONAL_REPRESENTATION('',(#84905),#84908); +#84905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84906,#84907),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#82514 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#82515 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#82516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82517 = ORIENTED_EDGE('',*,*,#82256,.T.); -#82518 = ADVANCED_FACE('',(#82519),#82016,.T.); -#82519 = FACE_BOUND('',#82520,.T.); -#82520 = EDGE_LOOP('',(#82521,#82522,#82523,#82543)); -#82521 = ORIENTED_EDGE('',*,*,#82279,.T.); -#82522 = ORIENTED_EDGE('',*,*,#82497,.F.); -#82523 = ORIENTED_EDGE('',*,*,#82524,.F.); -#82524 = EDGE_CURVE('',#82000,#82475,#82525,.T.); -#82525 = SURFACE_CURVE('',#82526,(#82530,#82536),.PCURVE_S1.); -#82526 = LINE('',#82527,#82528); -#82527 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); -#82528 = VECTOR('',#82529,1.); -#82529 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82530 = PCURVE('',#82016,#82531); -#82531 = DEFINITIONAL_REPRESENTATION('',(#82532),#82535); -#82532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82533,#82534),.UNSPECIFIED., +#84906 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84907 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#84908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84909 = ORIENTED_EDGE('',*,*,#84648,.T.); +#84910 = ADVANCED_FACE('',(#84911),#84408,.T.); +#84911 = FACE_BOUND('',#84912,.T.); +#84912 = EDGE_LOOP('',(#84913,#84914,#84915,#84935)); +#84913 = ORIENTED_EDGE('',*,*,#84671,.T.); +#84914 = ORIENTED_EDGE('',*,*,#84889,.F.); +#84915 = ORIENTED_EDGE('',*,*,#84916,.F.); +#84916 = EDGE_CURVE('',#84392,#84867,#84917,.T.); +#84917 = SURFACE_CURVE('',#84918,(#84922,#84928),.PCURVE_S1.); +#84918 = LINE('',#84919,#84920); +#84919 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); +#84920 = VECTOR('',#84921,1.); +#84921 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84922 = PCURVE('',#84408,#84923); +#84923 = DEFINITIONAL_REPRESENTATION('',(#84924),#84927); +#84924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84925,#84926),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82533 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#82534 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#82535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82536 = PCURVE('',#82043,#82537); -#82537 = DEFINITIONAL_REPRESENTATION('',(#82538),#82542); -#82538 = LINE('',#82539,#82540); -#82539 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#82540 = VECTOR('',#82541,1.); -#82541 = DIRECTION('',(0.E+000,1.)); -#82542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82543 = ORIENTED_EDGE('',*,*,#81999,.T.); -#82544 = ADVANCED_FACE('',(#82545),#82043,.T.); -#82545 = FACE_BOUND('',#82546,.T.); -#82546 = EDGE_LOOP('',(#82547,#82548,#82549,#82569)); -#82547 = ORIENTED_EDGE('',*,*,#82524,.T.); -#82548 = ORIENTED_EDGE('',*,*,#82474,.F.); -#82549 = ORIENTED_EDGE('',*,*,#82550,.F.); -#82550 = EDGE_CURVE('',#82028,#82448,#82551,.T.); -#82551 = SURFACE_CURVE('',#82552,(#82556,#82563),.PCURVE_S1.); -#82552 = LINE('',#82553,#82554); -#82553 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#82554 = VECTOR('',#82555,1.); -#82555 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82556 = PCURVE('',#82043,#82557); -#82557 = DEFINITIONAL_REPRESENTATION('',(#82558),#82562); -#82558 = LINE('',#82559,#82560); -#82559 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82560 = VECTOR('',#82561,1.); -#82561 = DIRECTION('',(0.E+000,1.)); -#82562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82563 = PCURVE('',#82076,#82564); -#82564 = DEFINITIONAL_REPRESENTATION('',(#82565),#82568); -#82565 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82566,#82567),.UNSPECIFIED., +#84925 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#84926 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#84927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84928 = PCURVE('',#84435,#84929); +#84929 = DEFINITIONAL_REPRESENTATION('',(#84930),#84934); +#84930 = LINE('',#84931,#84932); +#84931 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#84932 = VECTOR('',#84933,1.); +#84933 = DIRECTION('',(0.E+000,1.)); +#84934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84935 = ORIENTED_EDGE('',*,*,#84391,.T.); +#84936 = ADVANCED_FACE('',(#84937),#84435,.T.); +#84937 = FACE_BOUND('',#84938,.T.); +#84938 = EDGE_LOOP('',(#84939,#84940,#84941,#84961)); +#84939 = ORIENTED_EDGE('',*,*,#84916,.T.); +#84940 = ORIENTED_EDGE('',*,*,#84866,.F.); +#84941 = ORIENTED_EDGE('',*,*,#84942,.F.); +#84942 = EDGE_CURVE('',#84420,#84840,#84943,.T.); +#84943 = SURFACE_CURVE('',#84944,(#84948,#84955),.PCURVE_S1.); +#84944 = LINE('',#84945,#84946); +#84945 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#84946 = VECTOR('',#84947,1.); +#84947 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84948 = PCURVE('',#84435,#84949); +#84949 = DEFINITIONAL_REPRESENTATION('',(#84950),#84954); +#84950 = LINE('',#84951,#84952); +#84951 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#84952 = VECTOR('',#84953,1.); +#84953 = DIRECTION('',(0.E+000,1.)); +#84954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84955 = PCURVE('',#84468,#84956); +#84956 = DEFINITIONAL_REPRESENTATION('',(#84957),#84960); +#84957 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84958,#84959),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82566 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#82567 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#82568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82569 = ORIENTED_EDGE('',*,*,#82027,.T.); -#82570 = ADVANCED_FACE('',(#82571),#82076,.F.); -#82571 = FACE_BOUND('',#82572,.F.); -#82572 = EDGE_LOOP('',(#82573,#82574,#82575,#82618)); -#82573 = ORIENTED_EDGE('',*,*,#82550,.F.); -#82574 = ORIENTED_EDGE('',*,*,#82055,.F.); -#82575 = ORIENTED_EDGE('',*,*,#82576,.T.); -#82576 = EDGE_CURVE('',#82056,#82425,#82577,.T.); -#82577 = SURFACE_CURVE('',#82578,(#82582,#82611),.PCURVE_S1.); -#82578 = LINE('',#82579,#82580); -#82579 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); -#82580 = VECTOR('',#82581,1.); -#82581 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82582 = PCURVE('',#82076,#82583); -#82583 = DEFINITIONAL_REPRESENTATION('',(#82584),#82610); -#82584 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82585,#82586,#82587,#82588, - #82589,#82590,#82591,#82592,#82593,#82594,#82595,#82596,#82597, - #82598,#82599,#82600,#82601,#82602,#82603,#82604,#82605,#82606, - #82607,#82608,#82609),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#84958 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#84959 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#84960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#84961 = ORIENTED_EDGE('',*,*,#84419,.T.); +#84962 = ADVANCED_FACE('',(#84963),#84468,.F.); +#84963 = FACE_BOUND('',#84964,.F.); +#84964 = EDGE_LOOP('',(#84965,#84966,#84967,#85010)); +#84965 = ORIENTED_EDGE('',*,*,#84942,.F.); +#84966 = ORIENTED_EDGE('',*,*,#84447,.F.); +#84967 = ORIENTED_EDGE('',*,*,#84968,.T.); +#84968 = EDGE_CURVE('',#84448,#84817,#84969,.T.); +#84969 = SURFACE_CURVE('',#84970,(#84974,#85003),.PCURVE_S1.); +#84970 = LINE('',#84971,#84972); +#84971 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); +#84972 = VECTOR('',#84973,1.); +#84973 = DIRECTION('',(1.,0.E+000,0.E+000)); +#84974 = PCURVE('',#84468,#84975); +#84975 = DEFINITIONAL_REPRESENTATION('',(#84976),#85002); +#84976 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84977,#84978,#84979,#84980, + #84981,#84982,#84983,#84984,#84985,#84986,#84987,#84988,#84989, + #84990,#84991,#84992,#84993,#84994,#84995,#84996,#84997,#84998, + #84999,#85000,#85001),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -102405,133 +105394,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#82585 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#82586 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#82587 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#82588 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#82589 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#82590 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#82591 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#82592 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#82593 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#82594 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#82595 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#82596 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#82597 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#82598 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#82599 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#82600 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#82601 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#82602 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#82603 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#82604 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#82605 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#82606 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#82607 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#82608 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#82609 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#82610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82611 = PCURVE('',#82103,#82612); -#82612 = DEFINITIONAL_REPRESENTATION('',(#82613),#82617); -#82613 = LINE('',#82614,#82615); -#82614 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#82615 = VECTOR('',#82616,1.); -#82616 = DIRECTION('',(1.,0.E+000)); -#82617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82618 = ORIENTED_EDGE('',*,*,#82447,.T.); -#82619 = ADVANCED_FACE('',(#82620),#82103,.T.); -#82620 = FACE_BOUND('',#82621,.T.); -#82621 = EDGE_LOOP('',(#82622,#82623,#82624,#82645)); -#82622 = ORIENTED_EDGE('',*,*,#82576,.T.); -#82623 = ORIENTED_EDGE('',*,*,#82424,.F.); -#82624 = ORIENTED_EDGE('',*,*,#82625,.F.); -#82625 = EDGE_CURVE('',#82088,#82402,#82626,.T.); -#82626 = SURFACE_CURVE('',#82627,(#82631,#82638),.PCURVE_S1.); -#82627 = LINE('',#82628,#82629); -#82628 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#82629 = VECTOR('',#82630,1.); -#82630 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82631 = PCURVE('',#82103,#82632); -#82632 = DEFINITIONAL_REPRESENTATION('',(#82633),#82637); -#82633 = LINE('',#82634,#82635); -#82634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82635 = VECTOR('',#82636,1.); -#82636 = DIRECTION('',(1.,0.E+000)); -#82637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82638 = PCURVE('',#82131,#82639); -#82639 = DEFINITIONAL_REPRESENTATION('',(#82640),#82644); -#82640 = LINE('',#82641,#82642); -#82641 = CARTESIAN_POINT('',(0.15,0.E+000)); -#82642 = VECTOR('',#82643,1.); -#82643 = DIRECTION('',(0.E+000,1.)); -#82644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82645 = ORIENTED_EDGE('',*,*,#82087,.T.); -#82646 = ADVANCED_FACE('',(#82647),#82131,.T.); -#82647 = FACE_BOUND('',#82648,.T.); -#82648 = EDGE_LOOP('',(#82649,#82650,#82651,#82672)); -#82649 = ORIENTED_EDGE('',*,*,#82625,.T.); -#82650 = ORIENTED_EDGE('',*,*,#82401,.F.); -#82651 = ORIENTED_EDGE('',*,*,#82652,.F.); -#82652 = EDGE_CURVE('',#82116,#82379,#82653,.T.); -#82653 = SURFACE_CURVE('',#82654,(#82658,#82665),.PCURVE_S1.); -#82654 = LINE('',#82655,#82656); -#82655 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#82656 = VECTOR('',#82657,1.); -#82657 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82658 = PCURVE('',#82131,#82659); -#82659 = DEFINITIONAL_REPRESENTATION('',(#82660),#82664); -#82660 = LINE('',#82661,#82662); -#82661 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82662 = VECTOR('',#82663,1.); -#82663 = DIRECTION('',(0.E+000,1.)); -#82664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82665 = PCURVE('',#82159,#82666); -#82666 = DEFINITIONAL_REPRESENTATION('',(#82667),#82671); -#82667 = LINE('',#82668,#82669); -#82668 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82669 = VECTOR('',#82670,1.); -#82670 = DIRECTION('',(-1.,0.E+000)); -#82671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82672 = ORIENTED_EDGE('',*,*,#82115,.T.); -#82673 = ADVANCED_FACE('',(#82674),#82159,.T.); -#82674 = FACE_BOUND('',#82675,.T.); -#82675 = EDGE_LOOP('',(#82676,#82677,#82678,#82721)); -#82676 = ORIENTED_EDGE('',*,*,#82652,.T.); -#82677 = ORIENTED_EDGE('',*,*,#82378,.F.); -#82678 = ORIENTED_EDGE('',*,*,#82679,.F.); -#82679 = EDGE_CURVE('',#82144,#82356,#82680,.T.); -#82680 = SURFACE_CURVE('',#82681,(#82685,#82692),.PCURVE_S1.); -#82681 = LINE('',#82682,#82683); -#82682 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); -#82683 = VECTOR('',#82684,1.); -#82684 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82685 = PCURVE('',#82159,#82686); -#82686 = DEFINITIONAL_REPRESENTATION('',(#82687),#82691); -#82687 = LINE('',#82688,#82689); -#82688 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#82689 = VECTOR('',#82690,1.); -#82690 = DIRECTION('',(-1.,0.E+000)); -#82691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#84977 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#84978 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#84979 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#84980 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#84981 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#84982 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#84983 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#84984 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#84985 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#84986 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#84987 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#84988 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#84989 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#84990 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#84991 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#84992 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#84993 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#84994 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#84995 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#84996 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#84997 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#84998 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#84999 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#85000 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#85001 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#85002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85003 = PCURVE('',#84495,#85004); +#85004 = DEFINITIONAL_REPRESENTATION('',(#85005),#85009); +#85005 = LINE('',#85006,#85007); +#85006 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#85007 = VECTOR('',#85008,1.); +#85008 = DIRECTION('',(1.,0.E+000)); +#85009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85010 = ORIENTED_EDGE('',*,*,#84839,.T.); +#85011 = ADVANCED_FACE('',(#85012),#84495,.T.); +#85012 = FACE_BOUND('',#85013,.T.); +#85013 = EDGE_LOOP('',(#85014,#85015,#85016,#85037)); +#85014 = ORIENTED_EDGE('',*,*,#84968,.T.); +#85015 = ORIENTED_EDGE('',*,*,#84816,.F.); +#85016 = ORIENTED_EDGE('',*,*,#85017,.F.); +#85017 = EDGE_CURVE('',#84480,#84794,#85018,.T.); +#85018 = SURFACE_CURVE('',#85019,(#85023,#85030),.PCURVE_S1.); +#85019 = LINE('',#85020,#85021); +#85020 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#85021 = VECTOR('',#85022,1.); +#85022 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85023 = PCURVE('',#84495,#85024); +#85024 = DEFINITIONAL_REPRESENTATION('',(#85025),#85029); +#85025 = LINE('',#85026,#85027); +#85026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85027 = VECTOR('',#85028,1.); +#85028 = DIRECTION('',(1.,0.E+000)); +#85029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85030 = PCURVE('',#84523,#85031); +#85031 = DEFINITIONAL_REPRESENTATION('',(#85032),#85036); +#85032 = LINE('',#85033,#85034); +#85033 = CARTESIAN_POINT('',(0.15,0.E+000)); +#85034 = VECTOR('',#85035,1.); +#85035 = DIRECTION('',(0.E+000,1.)); +#85036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85037 = ORIENTED_EDGE('',*,*,#84479,.T.); +#85038 = ADVANCED_FACE('',(#85039),#84523,.T.); +#85039 = FACE_BOUND('',#85040,.T.); +#85040 = EDGE_LOOP('',(#85041,#85042,#85043,#85064)); +#85041 = ORIENTED_EDGE('',*,*,#85017,.T.); +#85042 = ORIENTED_EDGE('',*,*,#84793,.F.); +#85043 = ORIENTED_EDGE('',*,*,#85044,.F.); +#85044 = EDGE_CURVE('',#84508,#84771,#85045,.T.); +#85045 = SURFACE_CURVE('',#85046,(#85050,#85057),.PCURVE_S1.); +#85046 = LINE('',#85047,#85048); +#85047 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#85048 = VECTOR('',#85049,1.); +#85049 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85050 = PCURVE('',#84523,#85051); +#85051 = DEFINITIONAL_REPRESENTATION('',(#85052),#85056); +#85052 = LINE('',#85053,#85054); +#85053 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85054 = VECTOR('',#85055,1.); +#85055 = DIRECTION('',(0.E+000,1.)); +#85056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85057 = PCURVE('',#84551,#85058); +#85058 = DEFINITIONAL_REPRESENTATION('',(#85059),#85063); +#85059 = LINE('',#85060,#85061); +#85060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85061 = VECTOR('',#85062,1.); +#85062 = DIRECTION('',(-1.,0.E+000)); +#85063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85064 = ORIENTED_EDGE('',*,*,#84507,.T.); +#85065 = ADVANCED_FACE('',(#85066),#84551,.T.); +#85066 = FACE_BOUND('',#85067,.T.); +#85067 = EDGE_LOOP('',(#85068,#85069,#85070,#85113)); +#85068 = ORIENTED_EDGE('',*,*,#85044,.T.); +#85069 = ORIENTED_EDGE('',*,*,#84770,.F.); +#85070 = ORIENTED_EDGE('',*,*,#85071,.F.); +#85071 = EDGE_CURVE('',#84536,#84748,#85072,.T.); +#85072 = SURFACE_CURVE('',#85073,(#85077,#85084),.PCURVE_S1.); +#85073 = LINE('',#85074,#85075); +#85074 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); +#85075 = VECTOR('',#85076,1.); +#85076 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85077 = PCURVE('',#84551,#85078); +#85078 = DEFINITIONAL_REPRESENTATION('',(#85079),#85083); +#85079 = LINE('',#85080,#85081); +#85080 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#85081 = VECTOR('',#85082,1.); +#85082 = DIRECTION('',(-1.,0.E+000)); +#85083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#82692 = PCURVE('',#82188,#82693); -#82693 = DEFINITIONAL_REPRESENTATION('',(#82694),#82720); -#82694 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#82695,#82696,#82697,#82698, - #82699,#82700,#82701,#82702,#82703,#82704,#82705,#82706,#82707, - #82708,#82709,#82710,#82711,#82712,#82713,#82714,#82715,#82716, - #82717,#82718,#82719),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#85084 = PCURVE('',#84580,#85085); +#85085 = DEFINITIONAL_REPRESENTATION('',(#85086),#85112); +#85086 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85087,#85088,#85089,#85090, + #85091,#85092,#85093,#85094,#85095,#85096,#85097,#85098,#85099, + #85100,#85101,#85102,#85103,#85104,#85105,#85106,#85107,#85108, + #85109,#85110,#85111),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -102539,947 +105528,947 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#82695 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#82696 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#82697 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#82698 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#82699 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#82700 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#82701 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#82702 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#82703 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#82704 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#82705 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#82706 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#82707 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#82708 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#82709 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#82710 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#82711 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#82712 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#82713 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#82714 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#82715 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#82716 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#82717 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#82718 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#82719 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#82720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82721 = ORIENTED_EDGE('',*,*,#82143,.T.); -#82722 = ADVANCED_FACE('',(#82723),#82188,.T.); -#82723 = FACE_BOUND('',#82724,.T.); -#82724 = EDGE_LOOP('',(#82725,#82726,#82727,#82747)); -#82725 = ORIENTED_EDGE('',*,*,#82679,.T.); -#82726 = ORIENTED_EDGE('',*,*,#82355,.F.); -#82727 = ORIENTED_EDGE('',*,*,#82728,.F.); -#82728 = EDGE_CURVE('',#82172,#82333,#82729,.T.); -#82729 = SURFACE_CURVE('',#82730,(#82734,#82740),.PCURVE_S1.); -#82730 = LINE('',#82731,#82732); -#82731 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); -#82732 = VECTOR('',#82733,1.); -#82733 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82734 = PCURVE('',#82188,#82735); -#82735 = DEFINITIONAL_REPRESENTATION('',(#82736),#82739); -#82736 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82737,#82738),.UNSPECIFIED., +#85087 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#85088 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#85089 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#85090 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#85091 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#85092 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#85093 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#85094 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#85095 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#85096 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#85097 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#85098 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#85099 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#85100 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#85101 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#85102 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#85103 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#85104 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#85105 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#85106 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#85107 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#85108 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#85109 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#85110 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#85111 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#85112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85113 = ORIENTED_EDGE('',*,*,#84535,.T.); +#85114 = ADVANCED_FACE('',(#85115),#84580,.T.); +#85115 = FACE_BOUND('',#85116,.T.); +#85116 = EDGE_LOOP('',(#85117,#85118,#85119,#85139)); +#85117 = ORIENTED_EDGE('',*,*,#85071,.T.); +#85118 = ORIENTED_EDGE('',*,*,#84747,.F.); +#85119 = ORIENTED_EDGE('',*,*,#85120,.F.); +#85120 = EDGE_CURVE('',#84564,#84725,#85121,.T.); +#85121 = SURFACE_CURVE('',#85122,(#85126,#85132),.PCURVE_S1.); +#85122 = LINE('',#85123,#85124); +#85123 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); +#85124 = VECTOR('',#85125,1.); +#85125 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85126 = PCURVE('',#84580,#85127); +#85127 = DEFINITIONAL_REPRESENTATION('',(#85128),#85131); +#85128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85129,#85130),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82737 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#82738 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#82739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82740 = PCURVE('',#82215,#82741); -#82741 = DEFINITIONAL_REPRESENTATION('',(#82742),#82746); -#82742 = LINE('',#82743,#82744); -#82743 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#82744 = VECTOR('',#82745,1.); -#82745 = DIRECTION('',(0.E+000,1.)); -#82746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82747 = ORIENTED_EDGE('',*,*,#82171,.T.); -#82748 = ADVANCED_FACE('',(#82749),#82215,.T.); -#82749 = FACE_BOUND('',#82750,.T.); -#82750 = EDGE_LOOP('',(#82751,#82752,#82753,#82773)); -#82751 = ORIENTED_EDGE('',*,*,#82728,.T.); -#82752 = ORIENTED_EDGE('',*,*,#82332,.F.); -#82753 = ORIENTED_EDGE('',*,*,#82754,.F.); -#82754 = EDGE_CURVE('',#82200,#82306,#82755,.T.); -#82755 = SURFACE_CURVE('',#82756,(#82760,#82767),.PCURVE_S1.); -#82756 = LINE('',#82757,#82758); -#82757 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#82758 = VECTOR('',#82759,1.); -#82759 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82760 = PCURVE('',#82215,#82761); -#82761 = DEFINITIONAL_REPRESENTATION('',(#82762),#82766); -#82762 = LINE('',#82763,#82764); -#82763 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82764 = VECTOR('',#82765,1.); -#82765 = DIRECTION('',(0.E+000,1.)); -#82766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82767 = PCURVE('',#81939,#82768); -#82768 = DEFINITIONAL_REPRESENTATION('',(#82769),#82772); -#82769 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82770,#82771),.UNSPECIFIED., +#85129 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#85130 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#85131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85132 = PCURVE('',#84607,#85133); +#85133 = DEFINITIONAL_REPRESENTATION('',(#85134),#85138); +#85134 = LINE('',#85135,#85136); +#85135 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#85136 = VECTOR('',#85137,1.); +#85137 = DIRECTION('',(0.E+000,1.)); +#85138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85139 = ORIENTED_EDGE('',*,*,#84563,.T.); +#85140 = ADVANCED_FACE('',(#85141),#84607,.T.); +#85141 = FACE_BOUND('',#85142,.T.); +#85142 = EDGE_LOOP('',(#85143,#85144,#85145,#85165)); +#85143 = ORIENTED_EDGE('',*,*,#85120,.T.); +#85144 = ORIENTED_EDGE('',*,*,#84724,.F.); +#85145 = ORIENTED_EDGE('',*,*,#85146,.F.); +#85146 = EDGE_CURVE('',#84592,#84698,#85147,.T.); +#85147 = SURFACE_CURVE('',#85148,(#85152,#85159),.PCURVE_S1.); +#85148 = LINE('',#85149,#85150); +#85149 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#85150 = VECTOR('',#85151,1.); +#85151 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85152 = PCURVE('',#84607,#85153); +#85153 = DEFINITIONAL_REPRESENTATION('',(#85154),#85158); +#85154 = LINE('',#85155,#85156); +#85155 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85156 = VECTOR('',#85157,1.); +#85157 = DIRECTION('',(0.E+000,1.)); +#85158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85159 = PCURVE('',#84331,#85160); +#85160 = DEFINITIONAL_REPRESENTATION('',(#85161),#85164); +#85161 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85162,#85163),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82770 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#82771 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#82772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82773 = ORIENTED_EDGE('',*,*,#82199,.T.); -#82774 = ADVANCED_FACE('',(#82775),#81939,.F.); -#82775 = FACE_BOUND('',#82776,.F.); -#82776 = EDGE_LOOP('',(#82777,#82778,#82779,#82780)); -#82777 = ORIENTED_EDGE('',*,*,#82754,.F.); -#82778 = ORIENTED_EDGE('',*,*,#82227,.F.); -#82779 = ORIENTED_EDGE('',*,*,#81923,.T.); -#82780 = ORIENTED_EDGE('',*,*,#82305,.T.); -#82781 = ADVANCED_FACE('',(#82782),#77949,.T.); -#82782 = FACE_BOUND('',#82783,.T.); -#82783 = EDGE_LOOP('',(#82784,#82785,#82808,#82835)); -#82784 = ORIENTED_EDGE('',*,*,#77933,.F.); -#82785 = ORIENTED_EDGE('',*,*,#82786,.T.); -#82786 = EDGE_CURVE('',#77906,#82787,#82789,.T.); -#82787 = VERTEX_POINT('',#82788); -#82788 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#82789 = SURFACE_CURVE('',#82790,(#82794,#82801),.PCURVE_S1.); -#82790 = LINE('',#82791,#82792); -#82791 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#82792 = VECTOR('',#82793,1.); -#82793 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#82794 = PCURVE('',#77949,#82795); -#82795 = DEFINITIONAL_REPRESENTATION('',(#82796),#82800); -#82796 = LINE('',#82797,#82798); -#82797 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82798 = VECTOR('',#82799,1.); -#82799 = DIRECTION('',(0.E+000,-1.)); -#82800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82801 = PCURVE('',#77921,#82802); -#82802 = DEFINITIONAL_REPRESENTATION('',(#82803),#82807); -#82803 = LINE('',#82804,#82805); -#82804 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#82805 = VECTOR('',#82806,1.); -#82806 = DIRECTION('',(0.E+000,-1.)); -#82807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82808 = ORIENTED_EDGE('',*,*,#82809,.T.); -#82809 = EDGE_CURVE('',#82787,#82810,#82812,.T.); -#82810 = VERTEX_POINT('',#82811); -#82811 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); -#82812 = SURFACE_CURVE('',#82813,(#82817,#82824),.PCURVE_S1.); -#82813 = LINE('',#82814,#82815); -#82814 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#82815 = VECTOR('',#82816,1.); -#82816 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82817 = PCURVE('',#77949,#82818); -#82818 = DEFINITIONAL_REPRESENTATION('',(#82819),#82823); -#82819 = LINE('',#82820,#82821); -#82820 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82821 = VECTOR('',#82822,1.); -#82822 = DIRECTION('',(1.,0.E+000)); -#82823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82824 = PCURVE('',#82825,#82830); -#82825 = CYLINDRICAL_SURFACE('',#82826,0.2); -#82826 = AXIS2_PLACEMENT_3D('',#82827,#82828,#82829); -#82827 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#82828 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82829 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82830 = DEFINITIONAL_REPRESENTATION('',(#82831),#82834); -#82831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82832,#82833),.UNSPECIFIED., +#85162 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#85163 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#85164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85165 = ORIENTED_EDGE('',*,*,#84591,.T.); +#85166 = ADVANCED_FACE('',(#85167),#84331,.F.); +#85167 = FACE_BOUND('',#85168,.F.); +#85168 = EDGE_LOOP('',(#85169,#85170,#85171,#85172)); +#85169 = ORIENTED_EDGE('',*,*,#85146,.F.); +#85170 = ORIENTED_EDGE('',*,*,#84619,.F.); +#85171 = ORIENTED_EDGE('',*,*,#84315,.T.); +#85172 = ORIENTED_EDGE('',*,*,#84697,.T.); +#85173 = ADVANCED_FACE('',(#85174),#80341,.T.); +#85174 = FACE_BOUND('',#85175,.T.); +#85175 = EDGE_LOOP('',(#85176,#85177,#85200,#85227)); +#85176 = ORIENTED_EDGE('',*,*,#80325,.F.); +#85177 = ORIENTED_EDGE('',*,*,#85178,.T.); +#85178 = EDGE_CURVE('',#80298,#85179,#85181,.T.); +#85179 = VERTEX_POINT('',#85180); +#85180 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#85181 = SURFACE_CURVE('',#85182,(#85186,#85193),.PCURVE_S1.); +#85182 = LINE('',#85183,#85184); +#85183 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#85184 = VECTOR('',#85185,1.); +#85185 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#85186 = PCURVE('',#80341,#85187); +#85187 = DEFINITIONAL_REPRESENTATION('',(#85188),#85192); +#85188 = LINE('',#85189,#85190); +#85189 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85190 = VECTOR('',#85191,1.); +#85191 = DIRECTION('',(0.E+000,-1.)); +#85192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85193 = PCURVE('',#80313,#85194); +#85194 = DEFINITIONAL_REPRESENTATION('',(#85195),#85199); +#85195 = LINE('',#85196,#85197); +#85196 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#85197 = VECTOR('',#85198,1.); +#85198 = DIRECTION('',(0.E+000,-1.)); +#85199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85200 = ORIENTED_EDGE('',*,*,#85201,.T.); +#85201 = EDGE_CURVE('',#85179,#85202,#85204,.T.); +#85202 = VERTEX_POINT('',#85203); +#85203 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); +#85204 = SURFACE_CURVE('',#85205,(#85209,#85216),.PCURVE_S1.); +#85205 = LINE('',#85206,#85207); +#85206 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#85207 = VECTOR('',#85208,1.); +#85208 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85209 = PCURVE('',#80341,#85210); +#85210 = DEFINITIONAL_REPRESENTATION('',(#85211),#85215); +#85211 = LINE('',#85212,#85213); +#85212 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85213 = VECTOR('',#85214,1.); +#85214 = DIRECTION('',(1.,0.E+000)); +#85215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85216 = PCURVE('',#85217,#85222); +#85217 = CYLINDRICAL_SURFACE('',#85218,0.2); +#85218 = AXIS2_PLACEMENT_3D('',#85219,#85220,#85221); +#85219 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#85220 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85221 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85222 = DEFINITIONAL_REPRESENTATION('',(#85223),#85226); +#85223 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85224,#85225),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#82832 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#82833 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#82834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82835 = ORIENTED_EDGE('',*,*,#82836,.F.); -#82836 = EDGE_CURVE('',#77934,#82810,#82837,.T.); -#82837 = SURFACE_CURVE('',#82838,(#82842,#82849),.PCURVE_S1.); -#82838 = LINE('',#82839,#82840); -#82839 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); -#82840 = VECTOR('',#82841,1.); -#82841 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#82842 = PCURVE('',#77949,#82843); -#82843 = DEFINITIONAL_REPRESENTATION('',(#82844),#82848); -#82844 = LINE('',#82845,#82846); -#82845 = CARTESIAN_POINT('',(0.4,0.E+000)); -#82846 = VECTOR('',#82847,1.); -#82847 = DIRECTION('',(0.E+000,-1.)); -#82848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82849 = PCURVE('',#77977,#82850); -#82850 = DEFINITIONAL_REPRESENTATION('',(#82851),#82855); -#82851 = LINE('',#82852,#82853); -#82852 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#82853 = VECTOR('',#82854,1.); -#82854 = DIRECTION('',(0.E+000,-1.)); -#82855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82856 = ADVANCED_FACE('',(#82857),#77921,.F.); -#82857 = FACE_BOUND('',#82858,.T.); -#82858 = EDGE_LOOP('',(#82859,#82860,#82861,#82884,#82916,#82944,#82972, - #83000,#83028,#83056,#83088,#83116)); -#82859 = ORIENTED_EDGE('',*,*,#82786,.F.); -#82860 = ORIENTED_EDGE('',*,*,#77905,.T.); -#82861 = ORIENTED_EDGE('',*,*,#82862,.F.); -#82862 = EDGE_CURVE('',#82863,#77878,#82865,.T.); -#82863 = VERTEX_POINT('',#82864); -#82864 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#82865 = SURFACE_CURVE('',#82866,(#82870,#82877),.PCURVE_S1.); -#82866 = LINE('',#82867,#82868); -#82867 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#82868 = VECTOR('',#82869,1.); -#82869 = DIRECTION('',(0.E+000,1.,0.E+000)); -#82870 = PCURVE('',#77921,#82871); -#82871 = DEFINITIONAL_REPRESENTATION('',(#82872),#82876); -#82872 = LINE('',#82873,#82874); -#82873 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#82874 = VECTOR('',#82875,1.); -#82875 = DIRECTION('',(0.E+000,1.)); -#82876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82877 = PCURVE('',#78906,#82878); -#82878 = DEFINITIONAL_REPRESENTATION('',(#82879),#82883); -#82879 = LINE('',#82880,#82881); -#82880 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82881 = VECTOR('',#82882,1.); -#82882 = DIRECTION('',(0.E+000,1.)); -#82883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82884 = ORIENTED_EDGE('',*,*,#82885,.F.); -#82885 = EDGE_CURVE('',#82886,#82863,#82888,.T.); -#82886 = VERTEX_POINT('',#82887); -#82887 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#82888 = SURFACE_CURVE('',#82889,(#82894,#82905),.PCURVE_S1.); -#82889 = CIRCLE('',#82890,5.E-002); -#82890 = AXIS2_PLACEMENT_3D('',#82891,#82892,#82893); -#82891 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#82892 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82893 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82894 = PCURVE('',#77921,#82895); -#82895 = DEFINITIONAL_REPRESENTATION('',(#82896),#82904); -#82896 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#82897,#82898,#82899,#82900 - ,#82901,#82902,#82903),.UNSPECIFIED.,.F.,.F.) +#85224 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#85225 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#85226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85227 = ORIENTED_EDGE('',*,*,#85228,.F.); +#85228 = EDGE_CURVE('',#80326,#85202,#85229,.T.); +#85229 = SURFACE_CURVE('',#85230,(#85234,#85241),.PCURVE_S1.); +#85230 = LINE('',#85231,#85232); +#85231 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); +#85232 = VECTOR('',#85233,1.); +#85233 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#85234 = PCURVE('',#80341,#85235); +#85235 = DEFINITIONAL_REPRESENTATION('',(#85236),#85240); +#85236 = LINE('',#85237,#85238); +#85237 = CARTESIAN_POINT('',(0.4,0.E+000)); +#85238 = VECTOR('',#85239,1.); +#85239 = DIRECTION('',(0.E+000,-1.)); +#85240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85241 = PCURVE('',#80369,#85242); +#85242 = DEFINITIONAL_REPRESENTATION('',(#85243),#85247); +#85243 = LINE('',#85244,#85245); +#85244 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#85245 = VECTOR('',#85246,1.); +#85246 = DIRECTION('',(0.E+000,-1.)); +#85247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85248 = ADVANCED_FACE('',(#85249),#80313,.F.); +#85249 = FACE_BOUND('',#85250,.T.); +#85250 = EDGE_LOOP('',(#85251,#85252,#85253,#85276,#85308,#85336,#85364, + #85392,#85420,#85448,#85480,#85508)); +#85251 = ORIENTED_EDGE('',*,*,#85178,.F.); +#85252 = ORIENTED_EDGE('',*,*,#80297,.T.); +#85253 = ORIENTED_EDGE('',*,*,#85254,.F.); +#85254 = EDGE_CURVE('',#85255,#80270,#85257,.T.); +#85255 = VERTEX_POINT('',#85256); +#85256 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#85257 = SURFACE_CURVE('',#85258,(#85262,#85269),.PCURVE_S1.); +#85258 = LINE('',#85259,#85260); +#85259 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#85260 = VECTOR('',#85261,1.); +#85261 = DIRECTION('',(0.E+000,1.,0.E+000)); +#85262 = PCURVE('',#80313,#85263); +#85263 = DEFINITIONAL_REPRESENTATION('',(#85264),#85268); +#85264 = LINE('',#85265,#85266); +#85265 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#85266 = VECTOR('',#85267,1.); +#85267 = DIRECTION('',(0.E+000,1.)); +#85268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85269 = PCURVE('',#81298,#85270); +#85270 = DEFINITIONAL_REPRESENTATION('',(#85271),#85275); +#85271 = LINE('',#85272,#85273); +#85272 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85273 = VECTOR('',#85274,1.); +#85274 = DIRECTION('',(0.E+000,1.)); +#85275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85276 = ORIENTED_EDGE('',*,*,#85277,.F.); +#85277 = EDGE_CURVE('',#85278,#85255,#85280,.T.); +#85278 = VERTEX_POINT('',#85279); +#85279 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#85280 = SURFACE_CURVE('',#85281,(#85286,#85297),.PCURVE_S1.); +#85281 = CIRCLE('',#85282,5.E-002); +#85282 = AXIS2_PLACEMENT_3D('',#85283,#85284,#85285); +#85283 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#85284 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#85285 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85286 = PCURVE('',#80313,#85287); +#85287 = DEFINITIONAL_REPRESENTATION('',(#85288),#85296); +#85288 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#85289,#85290,#85291,#85292 + ,#85293,#85294,#85295),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#82897 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#82898 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#82899 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#82900 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#82901 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#82902 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#82903 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#82904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82905 = PCURVE('',#82906,#82911); -#82906 = CYLINDRICAL_SURFACE('',#82907,5.E-002); -#82907 = AXIS2_PLACEMENT_3D('',#82908,#82909,#82910); -#82908 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#82909 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82910 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82911 = DEFINITIONAL_REPRESENTATION('',(#82912),#82915); -#82912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82913,#82914),.UNSPECIFIED., +#85289 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#85290 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#85291 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#85292 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#85293 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#85294 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#85295 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#85296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85297 = PCURVE('',#85298,#85303); +#85298 = CYLINDRICAL_SURFACE('',#85299,5.E-002); +#85299 = AXIS2_PLACEMENT_3D('',#85300,#85301,#85302); +#85300 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#85301 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85302 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85303 = DEFINITIONAL_REPRESENTATION('',(#85304),#85307); +#85304 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85305,#85306),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#82913 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#82914 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#82915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82916 = ORIENTED_EDGE('',*,*,#82917,.F.); -#82917 = EDGE_CURVE('',#82918,#82886,#82920,.T.); -#82918 = VERTEX_POINT('',#82919); -#82919 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); -#82920 = SURFACE_CURVE('',#82921,(#82925,#82932),.PCURVE_S1.); -#82921 = LINE('',#82922,#82923); -#82922 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#82923 = VECTOR('',#82924,1.); -#82924 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#82925 = PCURVE('',#77921,#82926); -#82926 = DEFINITIONAL_REPRESENTATION('',(#82927),#82931); -#82927 = LINE('',#82928,#82929); -#82928 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#82929 = VECTOR('',#82930,1.); -#82930 = DIRECTION('',(-0.993981062721,0.109552028512)); -#82931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82932 = PCURVE('',#82933,#82938); -#82933 = PLANE('',#82934); -#82934 = AXIS2_PLACEMENT_3D('',#82935,#82936,#82937); -#82935 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#82936 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); -#82937 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#82938 = DEFINITIONAL_REPRESENTATION('',(#82939),#82943); -#82939 = LINE('',#82940,#82941); -#82940 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82941 = VECTOR('',#82942,1.); -#82942 = DIRECTION('',(1.,0.E+000)); -#82943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82944 = ORIENTED_EDGE('',*,*,#82945,.F.); -#82945 = EDGE_CURVE('',#82946,#82918,#82948,.T.); -#82946 = VERTEX_POINT('',#82947); -#82947 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); -#82948 = SURFACE_CURVE('',#82949,(#82954,#82961),.PCURVE_S1.); -#82949 = CIRCLE('',#82950,0.2); -#82950 = AXIS2_PLACEMENT_3D('',#82951,#82952,#82953); -#82951 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#82952 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82953 = DIRECTION('',(0.E+000,0.E+000,1.)); -#82954 = PCURVE('',#77921,#82955); -#82955 = DEFINITIONAL_REPRESENTATION('',(#82956),#82960); -#82956 = CIRCLE('',#82957,0.2); -#82957 = AXIS2_PLACEMENT_2D('',#82958,#82959); -#82958 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#82959 = DIRECTION('',(-1.,0.E+000)); -#82960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82961 = PCURVE('',#82962,#82967); -#82962 = CYLINDRICAL_SURFACE('',#82963,0.2); -#82963 = AXIS2_PLACEMENT_3D('',#82964,#82965,#82966); -#82964 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#82965 = DIRECTION('',(1.,0.E+000,0.E+000)); -#82966 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82967 = DEFINITIONAL_REPRESENTATION('',(#82968),#82971); -#82968 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#82969,#82970),.UNSPECIFIED., +#85305 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#85306 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#85307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85308 = ORIENTED_EDGE('',*,*,#85309,.F.); +#85309 = EDGE_CURVE('',#85310,#85278,#85312,.T.); +#85310 = VERTEX_POINT('',#85311); +#85311 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); +#85312 = SURFACE_CURVE('',#85313,(#85317,#85324),.PCURVE_S1.); +#85313 = LINE('',#85314,#85315); +#85314 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#85315 = VECTOR('',#85316,1.); +#85316 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#85317 = PCURVE('',#80313,#85318); +#85318 = DEFINITIONAL_REPRESENTATION('',(#85319),#85323); +#85319 = LINE('',#85320,#85321); +#85320 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#85321 = VECTOR('',#85322,1.); +#85322 = DIRECTION('',(-0.993981062721,0.109552028512)); +#85323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85324 = PCURVE('',#85325,#85330); +#85325 = PLANE('',#85326); +#85326 = AXIS2_PLACEMENT_3D('',#85327,#85328,#85329); +#85327 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#85328 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); +#85329 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#85330 = DEFINITIONAL_REPRESENTATION('',(#85331),#85335); +#85331 = LINE('',#85332,#85333); +#85332 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85333 = VECTOR('',#85334,1.); +#85334 = DIRECTION('',(1.,0.E+000)); +#85335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85336 = ORIENTED_EDGE('',*,*,#85337,.F.); +#85337 = EDGE_CURVE('',#85338,#85310,#85340,.T.); +#85338 = VERTEX_POINT('',#85339); +#85339 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); +#85340 = SURFACE_CURVE('',#85341,(#85346,#85353),.PCURVE_S1.); +#85341 = CIRCLE('',#85342,0.2); +#85342 = AXIS2_PLACEMENT_3D('',#85343,#85344,#85345); +#85343 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#85344 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#85346 = PCURVE('',#80313,#85347); +#85347 = DEFINITIONAL_REPRESENTATION('',(#85348),#85352); +#85348 = CIRCLE('',#85349,0.2); +#85349 = AXIS2_PLACEMENT_2D('',#85350,#85351); +#85350 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#85351 = DIRECTION('',(-1.,0.E+000)); +#85352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85353 = PCURVE('',#85354,#85359); +#85354 = CYLINDRICAL_SURFACE('',#85355,0.2); +#85355 = AXIS2_PLACEMENT_3D('',#85356,#85357,#85358); +#85356 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#85357 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85358 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85359 = DEFINITIONAL_REPRESENTATION('',(#85360),#85363); +#85360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85361,#85362),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#82969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82970 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#82971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82972 = ORIENTED_EDGE('',*,*,#82973,.F.); -#82973 = EDGE_CURVE('',#82974,#82946,#82976,.T.); -#82974 = VERTEX_POINT('',#82975); -#82975 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#82976 = SURFACE_CURVE('',#82977,(#82981,#82988),.PCURVE_S1.); -#82977 = LINE('',#82978,#82979); -#82978 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#82979 = VECTOR('',#82980,1.); -#82980 = DIRECTION('',(0.E+000,1.,0.E+000)); -#82981 = PCURVE('',#77921,#82982); -#82982 = DEFINITIONAL_REPRESENTATION('',(#82983),#82987); -#82983 = LINE('',#82984,#82985); -#82984 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#82985 = VECTOR('',#82986,1.); -#82986 = DIRECTION('',(0.E+000,1.)); -#82987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#82988 = PCURVE('',#82989,#82994); -#82989 = PLANE('',#82990); -#82990 = AXIS2_PLACEMENT_3D('',#82991,#82992,#82993); -#82991 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#82992 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#82993 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#82994 = DEFINITIONAL_REPRESENTATION('',(#82995),#82999); -#82995 = LINE('',#82996,#82997); -#82996 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#82997 = VECTOR('',#82998,1.); -#82998 = DIRECTION('',(0.E+000,1.)); -#82999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83000 = ORIENTED_EDGE('',*,*,#83001,.F.); -#83001 = EDGE_CURVE('',#83002,#82974,#83004,.T.); -#83002 = VERTEX_POINT('',#83003); -#83003 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#83004 = SURFACE_CURVE('',#83005,(#83009,#83016),.PCURVE_S1.); -#83005 = LINE('',#83006,#83007); -#83006 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#83007 = VECTOR('',#83008,1.); -#83008 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83009 = PCURVE('',#77921,#83010); -#83010 = DEFINITIONAL_REPRESENTATION('',(#83011),#83015); -#83011 = LINE('',#83012,#83013); -#83012 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#83013 = VECTOR('',#83014,1.); -#83014 = DIRECTION('',(1.,0.E+000)); -#83015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83016 = PCURVE('',#83017,#83022); -#83017 = PLANE('',#83018); -#83018 = AXIS2_PLACEMENT_3D('',#83019,#83020,#83021); -#83019 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#83020 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83021 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83022 = DEFINITIONAL_REPRESENTATION('',(#83023),#83027); -#83023 = LINE('',#83024,#83025); -#83024 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83025 = VECTOR('',#83026,1.); -#83026 = DIRECTION('',(1.,0.E+000)); -#83027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83028 = ORIENTED_EDGE('',*,*,#83029,.F.); -#83029 = EDGE_CURVE('',#83030,#83002,#83032,.T.); -#83030 = VERTEX_POINT('',#83031); -#83031 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); -#83032 = SURFACE_CURVE('',#83033,(#83037,#83044),.PCURVE_S1.); -#83033 = LINE('',#83034,#83035); -#83034 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#83035 = VECTOR('',#83036,1.); -#83036 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83037 = PCURVE('',#77921,#83038); -#83038 = DEFINITIONAL_REPRESENTATION('',(#83039),#83043); -#83039 = LINE('',#83040,#83041); -#83040 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#83041 = VECTOR('',#83042,1.); -#83042 = DIRECTION('',(0.E+000,-1.)); -#83043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83044 = PCURVE('',#83045,#83050); -#83045 = PLANE('',#83046); -#83046 = AXIS2_PLACEMENT_3D('',#83047,#83048,#83049); -#83047 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#83048 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83049 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83050 = DEFINITIONAL_REPRESENTATION('',(#83051),#83055); -#83051 = LINE('',#83052,#83053); -#83052 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83053 = VECTOR('',#83054,1.); -#83054 = DIRECTION('',(0.E+000,-1.)); -#83055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83056 = ORIENTED_EDGE('',*,*,#83057,.F.); -#83057 = EDGE_CURVE('',#83058,#83030,#83060,.T.); -#83058 = VERTEX_POINT('',#83059); -#83059 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#83060 = SURFACE_CURVE('',#83061,(#83066,#83077),.PCURVE_S1.); -#83061 = CIRCLE('',#83062,5.E-002); -#83062 = AXIS2_PLACEMENT_3D('',#83063,#83064,#83065); -#83063 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#83064 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#83065 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83066 = PCURVE('',#77921,#83067); -#83067 = DEFINITIONAL_REPRESENTATION('',(#83068),#83076); -#83068 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83069,#83070,#83071,#83072 - ,#83073,#83074,#83075),.UNSPECIFIED.,.F.,.F.) +#85361 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85362 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#85363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85364 = ORIENTED_EDGE('',*,*,#85365,.F.); +#85365 = EDGE_CURVE('',#85366,#85338,#85368,.T.); +#85366 = VERTEX_POINT('',#85367); +#85367 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85368 = SURFACE_CURVE('',#85369,(#85373,#85380),.PCURVE_S1.); +#85369 = LINE('',#85370,#85371); +#85370 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85371 = VECTOR('',#85372,1.); +#85372 = DIRECTION('',(0.E+000,1.,0.E+000)); +#85373 = PCURVE('',#80313,#85374); +#85374 = DEFINITIONAL_REPRESENTATION('',(#85375),#85379); +#85375 = LINE('',#85376,#85377); +#85376 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#85377 = VECTOR('',#85378,1.); +#85378 = DIRECTION('',(0.E+000,1.)); +#85379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85380 = PCURVE('',#85381,#85386); +#85381 = PLANE('',#85382); +#85382 = AXIS2_PLACEMENT_3D('',#85383,#85384,#85385); +#85383 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85384 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85385 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#85386 = DEFINITIONAL_REPRESENTATION('',(#85387),#85391); +#85387 = LINE('',#85388,#85389); +#85388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85389 = VECTOR('',#85390,1.); +#85390 = DIRECTION('',(0.E+000,1.)); +#85391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85392 = ORIENTED_EDGE('',*,*,#85393,.F.); +#85393 = EDGE_CURVE('',#85394,#85366,#85396,.T.); +#85394 = VERTEX_POINT('',#85395); +#85395 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#85396 = SURFACE_CURVE('',#85397,(#85401,#85408),.PCURVE_S1.); +#85397 = LINE('',#85398,#85399); +#85398 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85399 = VECTOR('',#85400,1.); +#85400 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85401 = PCURVE('',#80313,#85402); +#85402 = DEFINITIONAL_REPRESENTATION('',(#85403),#85407); +#85403 = LINE('',#85404,#85405); +#85404 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#85405 = VECTOR('',#85406,1.); +#85406 = DIRECTION('',(1.,0.E+000)); +#85407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85408 = PCURVE('',#85409,#85414); +#85409 = PLANE('',#85410); +#85410 = AXIS2_PLACEMENT_3D('',#85411,#85412,#85413); +#85411 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85412 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#85413 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85414 = DEFINITIONAL_REPRESENTATION('',(#85415),#85419); +#85415 = LINE('',#85416,#85417); +#85416 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85417 = VECTOR('',#85418,1.); +#85418 = DIRECTION('',(1.,0.E+000)); +#85419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85420 = ORIENTED_EDGE('',*,*,#85421,.F.); +#85421 = EDGE_CURVE('',#85422,#85394,#85424,.T.); +#85422 = VERTEX_POINT('',#85423); +#85423 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); +#85424 = SURFACE_CURVE('',#85425,(#85429,#85436),.PCURVE_S1.); +#85425 = LINE('',#85426,#85427); +#85426 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#85427 = VECTOR('',#85428,1.); +#85428 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#85429 = PCURVE('',#80313,#85430); +#85430 = DEFINITIONAL_REPRESENTATION('',(#85431),#85435); +#85431 = LINE('',#85432,#85433); +#85432 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#85433 = VECTOR('',#85434,1.); +#85434 = DIRECTION('',(0.E+000,-1.)); +#85435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85436 = PCURVE('',#85437,#85442); +#85437 = PLANE('',#85438); +#85438 = AXIS2_PLACEMENT_3D('',#85439,#85440,#85441); +#85439 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#85440 = DIRECTION('',(0.E+000,0.E+000,1.)); +#85441 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85442 = DEFINITIONAL_REPRESENTATION('',(#85443),#85447); +#85443 = LINE('',#85444,#85445); +#85444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85445 = VECTOR('',#85446,1.); +#85446 = DIRECTION('',(0.E+000,-1.)); +#85447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85448 = ORIENTED_EDGE('',*,*,#85449,.F.); +#85449 = EDGE_CURVE('',#85450,#85422,#85452,.T.); +#85450 = VERTEX_POINT('',#85451); +#85451 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#85452 = SURFACE_CURVE('',#85453,(#85458,#85469),.PCURVE_S1.); +#85453 = CIRCLE('',#85454,5.E-002); +#85454 = AXIS2_PLACEMENT_3D('',#85455,#85456,#85457); +#85455 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#85456 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#85457 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85458 = PCURVE('',#80313,#85459); +#85459 = DEFINITIONAL_REPRESENTATION('',(#85460),#85468); +#85460 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#85461,#85462,#85463,#85464 + ,#85465,#85466,#85467),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#83069 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#83070 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#83071 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#83072 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#83073 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#83074 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#83075 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#83076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83077 = PCURVE('',#83078,#83083); -#83078 = CYLINDRICAL_SURFACE('',#83079,5.E-002); -#83079 = AXIS2_PLACEMENT_3D('',#83080,#83081,#83082); -#83080 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#83081 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83082 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83083 = DEFINITIONAL_REPRESENTATION('',(#83084),#83087); -#83084 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83085,#83086),.UNSPECIFIED., +#85461 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#85462 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#85463 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#85464 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#85465 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#85466 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#85467 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#85468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85469 = PCURVE('',#85470,#85475); +#85470 = CYLINDRICAL_SURFACE('',#85471,5.E-002); +#85471 = AXIS2_PLACEMENT_3D('',#85472,#85473,#85474); +#85472 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#85473 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85474 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85475 = DEFINITIONAL_REPRESENTATION('',(#85476),#85479); +#85476 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85477,#85478),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#83085 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#83086 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83088 = ORIENTED_EDGE('',*,*,#83089,.F.); -#83089 = EDGE_CURVE('',#83090,#83058,#83092,.T.); -#83090 = VERTEX_POINT('',#83091); -#83091 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); -#83092 = SURFACE_CURVE('',#83093,(#83097,#83104),.PCURVE_S1.); -#83093 = LINE('',#83094,#83095); -#83094 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#83095 = VECTOR('',#83096,1.); -#83096 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#83097 = PCURVE('',#77921,#83098); -#83098 = DEFINITIONAL_REPRESENTATION('',(#83099),#83103); -#83099 = LINE('',#83100,#83101); -#83100 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#83101 = VECTOR('',#83102,1.); -#83102 = DIRECTION('',(0.993981062721,-0.109552028512)); -#83103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83104 = PCURVE('',#83105,#83110); -#83105 = PLANE('',#83106); -#83106 = AXIS2_PLACEMENT_3D('',#83107,#83108,#83109); -#83107 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#83108 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); -#83109 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#83110 = DEFINITIONAL_REPRESENTATION('',(#83111),#83115); -#83111 = LINE('',#83112,#83113); -#83112 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83113 = VECTOR('',#83114,1.); -#83114 = DIRECTION('',(1.,0.E+000)); -#83115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83116 = ORIENTED_EDGE('',*,*,#83117,.F.); -#83117 = EDGE_CURVE('',#82787,#83090,#83118,.T.); -#83118 = SURFACE_CURVE('',#83119,(#83124,#83131),.PCURVE_S1.); -#83119 = CIRCLE('',#83120,0.2); -#83120 = AXIS2_PLACEMENT_3D('',#83121,#83122,#83123); -#83121 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#83122 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83123 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83124 = PCURVE('',#77921,#83125); -#83125 = DEFINITIONAL_REPRESENTATION('',(#83126),#83130); -#83126 = CIRCLE('',#83127,0.2); -#83127 = AXIS2_PLACEMENT_2D('',#83128,#83129); -#83128 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#83129 = DIRECTION('',(-1.,0.E+000)); -#83130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83131 = PCURVE('',#82825,#83132); -#83132 = DEFINITIONAL_REPRESENTATION('',(#83133),#83136); -#83133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83134,#83135),.UNSPECIFIED., +#85477 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#85478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85480 = ORIENTED_EDGE('',*,*,#85481,.F.); +#85481 = EDGE_CURVE('',#85482,#85450,#85484,.T.); +#85482 = VERTEX_POINT('',#85483); +#85483 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); +#85484 = SURFACE_CURVE('',#85485,(#85489,#85496),.PCURVE_S1.); +#85485 = LINE('',#85486,#85487); +#85486 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#85487 = VECTOR('',#85488,1.); +#85488 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#85489 = PCURVE('',#80313,#85490); +#85490 = DEFINITIONAL_REPRESENTATION('',(#85491),#85495); +#85491 = LINE('',#85492,#85493); +#85492 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#85493 = VECTOR('',#85494,1.); +#85494 = DIRECTION('',(0.993981062721,-0.109552028512)); +#85495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85496 = PCURVE('',#85497,#85502); +#85497 = PLANE('',#85498); +#85498 = AXIS2_PLACEMENT_3D('',#85499,#85500,#85501); +#85499 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#85500 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); +#85501 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#85502 = DEFINITIONAL_REPRESENTATION('',(#85503),#85507); +#85503 = LINE('',#85504,#85505); +#85504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85505 = VECTOR('',#85506,1.); +#85506 = DIRECTION('',(1.,0.E+000)); +#85507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85508 = ORIENTED_EDGE('',*,*,#85509,.F.); +#85509 = EDGE_CURVE('',#85179,#85482,#85510,.T.); +#85510 = SURFACE_CURVE('',#85511,(#85516,#85523),.PCURVE_S1.); +#85511 = CIRCLE('',#85512,0.2); +#85512 = AXIS2_PLACEMENT_3D('',#85513,#85514,#85515); +#85513 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#85514 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85515 = DIRECTION('',(0.E+000,0.E+000,1.)); +#85516 = PCURVE('',#80313,#85517); +#85517 = DEFINITIONAL_REPRESENTATION('',(#85518),#85522); +#85518 = CIRCLE('',#85519,0.2); +#85519 = AXIS2_PLACEMENT_2D('',#85520,#85521); +#85520 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#85521 = DIRECTION('',(-1.,0.E+000)); +#85522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85523 = PCURVE('',#85217,#85524); +#85524 = DEFINITIONAL_REPRESENTATION('',(#85525),#85528); +#85525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85526,#85527),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#83134 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#83135 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#83136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83137 = ADVANCED_FACE('',(#83138),#78906,.T.); -#83138 = FACE_BOUND('',#83139,.T.); -#83139 = EDGE_LOOP('',(#83140,#83141,#83164,#83184)); -#83140 = ORIENTED_EDGE('',*,*,#78892,.T.); -#83141 = ORIENTED_EDGE('',*,*,#83142,.F.); -#83142 = EDGE_CURVE('',#83143,#77962,#83145,.T.); -#83143 = VERTEX_POINT('',#83144); -#83144 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); -#83145 = SURFACE_CURVE('',#83146,(#83150,#83157),.PCURVE_S1.); -#83146 = LINE('',#83147,#83148); -#83147 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); -#83148 = VECTOR('',#83149,1.); -#83149 = DIRECTION('',(0.E+000,1.,0.E+000)); -#83150 = PCURVE('',#78906,#83151); -#83151 = DEFINITIONAL_REPRESENTATION('',(#83152),#83156); -#83152 = LINE('',#83153,#83154); -#83153 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#83154 = VECTOR('',#83155,1.); -#83155 = DIRECTION('',(0.E+000,1.)); -#83156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83157 = PCURVE('',#77977,#83158); -#83158 = DEFINITIONAL_REPRESENTATION('',(#83159),#83163); -#83159 = LINE('',#83160,#83161); -#83160 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#83161 = VECTOR('',#83162,1.); -#83162 = DIRECTION('',(0.E+000,1.)); -#83163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83164 = ORIENTED_EDGE('',*,*,#83165,.F.); -#83165 = EDGE_CURVE('',#82863,#83143,#83166,.T.); -#83166 = SURFACE_CURVE('',#83167,(#83171,#83178),.PCURVE_S1.); -#83167 = LINE('',#83168,#83169); -#83168 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#83169 = VECTOR('',#83170,1.); -#83170 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83171 = PCURVE('',#78906,#83172); -#83172 = DEFINITIONAL_REPRESENTATION('',(#83173),#83177); -#83173 = LINE('',#83174,#83175); -#83174 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83175 = VECTOR('',#83176,1.); -#83176 = DIRECTION('',(-1.,0.E+000)); -#83177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83178 = PCURVE('',#82906,#83179); -#83179 = DEFINITIONAL_REPRESENTATION('',(#83180),#83183); -#83180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83181,#83182),.UNSPECIFIED., +#85526 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#85527 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#85528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85529 = ADVANCED_FACE('',(#85530),#81298,.T.); +#85530 = FACE_BOUND('',#85531,.T.); +#85531 = EDGE_LOOP('',(#85532,#85533,#85556,#85576)); +#85532 = ORIENTED_EDGE('',*,*,#81284,.T.); +#85533 = ORIENTED_EDGE('',*,*,#85534,.F.); +#85534 = EDGE_CURVE('',#85535,#80354,#85537,.T.); +#85535 = VERTEX_POINT('',#85536); +#85536 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); +#85537 = SURFACE_CURVE('',#85538,(#85542,#85549),.PCURVE_S1.); +#85538 = LINE('',#85539,#85540); +#85539 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); +#85540 = VECTOR('',#85541,1.); +#85541 = DIRECTION('',(0.E+000,1.,0.E+000)); +#85542 = PCURVE('',#81298,#85543); +#85543 = DEFINITIONAL_REPRESENTATION('',(#85544),#85548); +#85544 = LINE('',#85545,#85546); +#85545 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#85546 = VECTOR('',#85547,1.); +#85547 = DIRECTION('',(0.E+000,1.)); +#85548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85549 = PCURVE('',#80369,#85550); +#85550 = DEFINITIONAL_REPRESENTATION('',(#85551),#85555); +#85551 = LINE('',#85552,#85553); +#85552 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#85553 = VECTOR('',#85554,1.); +#85554 = DIRECTION('',(0.E+000,1.)); +#85555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85556 = ORIENTED_EDGE('',*,*,#85557,.F.); +#85557 = EDGE_CURVE('',#85255,#85535,#85558,.T.); +#85558 = SURFACE_CURVE('',#85559,(#85563,#85570),.PCURVE_S1.); +#85559 = LINE('',#85560,#85561); +#85560 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#85561 = VECTOR('',#85562,1.); +#85562 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85563 = PCURVE('',#81298,#85564); +#85564 = DEFINITIONAL_REPRESENTATION('',(#85565),#85569); +#85565 = LINE('',#85566,#85567); +#85566 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85567 = VECTOR('',#85568,1.); +#85568 = DIRECTION('',(-1.,0.E+000)); +#85569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85570 = PCURVE('',#85298,#85571); +#85571 = DEFINITIONAL_REPRESENTATION('',(#85572),#85575); +#85572 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85573,#85574),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83181 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#83182 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#83183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83184 = ORIENTED_EDGE('',*,*,#82862,.T.); -#83185 = ADVANCED_FACE('',(#83186),#77977,.T.); -#83186 = FACE_BOUND('',#83187,.T.); -#83187 = EDGE_LOOP('',(#83188,#83189,#83190,#83213,#83236,#83263,#83286, - #83309,#83332,#83355,#83378,#83403)); -#83188 = ORIENTED_EDGE('',*,*,#77961,.F.); -#83189 = ORIENTED_EDGE('',*,*,#82836,.T.); -#83190 = ORIENTED_EDGE('',*,*,#83191,.T.); -#83191 = EDGE_CURVE('',#82810,#83192,#83194,.T.); -#83192 = VERTEX_POINT('',#83193); -#83193 = CARTESIAN_POINT('',(-0.745,-0.854004213739,0.571910405702)); -#83194 = SURFACE_CURVE('',#83195,(#83200,#83207),.PCURVE_S1.); -#83195 = CIRCLE('',#83196,0.2); -#83196 = AXIS2_PLACEMENT_3D('',#83197,#83198,#83199); -#83197 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#83198 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83199 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83200 = PCURVE('',#77977,#83201); -#83201 = DEFINITIONAL_REPRESENTATION('',(#83202),#83206); -#83202 = CIRCLE('',#83203,0.2); -#83203 = AXIS2_PLACEMENT_2D('',#83204,#83205); -#83204 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#83205 = DIRECTION('',(-1.,0.E+000)); -#83206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83207 = PCURVE('',#82825,#83208); -#83208 = DEFINITIONAL_REPRESENTATION('',(#83209),#83212); -#83209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83210,#83211),.UNSPECIFIED., +#85573 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#85574 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#85575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85576 = ORIENTED_EDGE('',*,*,#85254,.T.); +#85577 = ADVANCED_FACE('',(#85578),#80369,.T.); +#85578 = FACE_BOUND('',#85579,.T.); +#85579 = EDGE_LOOP('',(#85580,#85581,#85582,#85605,#85628,#85655,#85678, + #85701,#85724,#85747,#85770,#85795)); +#85580 = ORIENTED_EDGE('',*,*,#80353,.F.); +#85581 = ORIENTED_EDGE('',*,*,#85228,.T.); +#85582 = ORIENTED_EDGE('',*,*,#85583,.T.); +#85583 = EDGE_CURVE('',#85202,#85584,#85586,.T.); +#85584 = VERTEX_POINT('',#85585); +#85585 = CARTESIAN_POINT('',(-0.745,-0.854004213739,0.571910405702)); +#85586 = SURFACE_CURVE('',#85587,(#85592,#85599),.PCURVE_S1.); +#85587 = CIRCLE('',#85588,0.2); +#85588 = AXIS2_PLACEMENT_3D('',#85589,#85590,#85591); +#85589 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#85590 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85591 = DIRECTION('',(0.E+000,0.E+000,1.)); +#85592 = PCURVE('',#80369,#85593); +#85593 = DEFINITIONAL_REPRESENTATION('',(#85594),#85598); +#85594 = CIRCLE('',#85595,0.2); +#85595 = AXIS2_PLACEMENT_2D('',#85596,#85597); +#85596 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#85597 = DIRECTION('',(-1.,0.E+000)); +#85598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85599 = PCURVE('',#85217,#85600); +#85600 = DEFINITIONAL_REPRESENTATION('',(#85601),#85604); +#85601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85602,#85603),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#83210 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#83211 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#83212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83213 = ORIENTED_EDGE('',*,*,#83214,.T.); -#83214 = EDGE_CURVE('',#83192,#83215,#83217,.T.); -#83215 = VERTEX_POINT('',#83216); -#83216 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); -#83217 = SURFACE_CURVE('',#83218,(#83222,#83229),.PCURVE_S1.); -#83218 = LINE('',#83219,#83220); -#83219 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); -#83220 = VECTOR('',#83221,1.); -#83221 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#83222 = PCURVE('',#77977,#83223); -#83223 = DEFINITIONAL_REPRESENTATION('',(#83224),#83228); -#83224 = LINE('',#83225,#83226); -#83225 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#83226 = VECTOR('',#83227,1.); -#83227 = DIRECTION('',(0.993981062721,-0.109552028512)); -#83228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83229 = PCURVE('',#83105,#83230); -#83230 = DEFINITIONAL_REPRESENTATION('',(#83231),#83235); -#83231 = LINE('',#83232,#83233); -#83232 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83233 = VECTOR('',#83234,1.); -#83234 = DIRECTION('',(1.,0.E+000)); -#83235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83236 = ORIENTED_EDGE('',*,*,#83237,.T.); -#83237 = EDGE_CURVE('',#83215,#83238,#83240,.T.); -#83238 = VERTEX_POINT('',#83239); -#83239 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.15)); -#83240 = SURFACE_CURVE('',#83241,(#83246,#83257),.PCURVE_S1.); -#83241 = CIRCLE('',#83242,5.E-002); -#83242 = AXIS2_PLACEMENT_3D('',#83243,#83244,#83245); -#83243 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); -#83244 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#83245 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83246 = PCURVE('',#77977,#83247); -#83247 = DEFINITIONAL_REPRESENTATION('',(#83248),#83256); -#83248 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83249,#83250,#83251,#83252 - ,#83253,#83254,#83255),.UNSPECIFIED.,.F.,.F.) +#85602 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#85603 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#85604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85605 = ORIENTED_EDGE('',*,*,#85606,.T.); +#85606 = EDGE_CURVE('',#85584,#85607,#85609,.T.); +#85607 = VERTEX_POINT('',#85608); +#85608 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); +#85609 = SURFACE_CURVE('',#85610,(#85614,#85621),.PCURVE_S1.); +#85610 = LINE('',#85611,#85612); +#85611 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); +#85612 = VECTOR('',#85613,1.); +#85613 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#85614 = PCURVE('',#80369,#85615); +#85615 = DEFINITIONAL_REPRESENTATION('',(#85616),#85620); +#85616 = LINE('',#85617,#85618); +#85617 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#85618 = VECTOR('',#85619,1.); +#85619 = DIRECTION('',(0.993981062721,-0.109552028512)); +#85620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85621 = PCURVE('',#85497,#85622); +#85622 = DEFINITIONAL_REPRESENTATION('',(#85623),#85627); +#85623 = LINE('',#85624,#85625); +#85624 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85625 = VECTOR('',#85626,1.); +#85626 = DIRECTION('',(1.,0.E+000)); +#85627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85628 = ORIENTED_EDGE('',*,*,#85629,.T.); +#85629 = EDGE_CURVE('',#85607,#85630,#85632,.T.); +#85630 = VERTEX_POINT('',#85631); +#85631 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.15)); +#85632 = SURFACE_CURVE('',#85633,(#85638,#85649),.PCURVE_S1.); +#85633 = CIRCLE('',#85634,5.E-002); +#85634 = AXIS2_PLACEMENT_3D('',#85635,#85636,#85637); +#85635 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); +#85636 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#85637 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85638 = PCURVE('',#80369,#85639); +#85639 = DEFINITIONAL_REPRESENTATION('',(#85640),#85648); +#85640 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#85641,#85642,#85643,#85644 + ,#85645,#85646,#85647),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#83249 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#83250 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#83251 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#83252 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#83253 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#83254 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#83255 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#83256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83257 = PCURVE('',#83078,#83258); -#83258 = DEFINITIONAL_REPRESENTATION('',(#83259),#83262); -#83259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83260,#83261),.UNSPECIFIED., +#85641 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#85642 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#85643 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#85644 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#85645 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#85646 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#85647 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#85648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85649 = PCURVE('',#85470,#85650); +#85650 = DEFINITIONAL_REPRESENTATION('',(#85651),#85654); +#85651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85652,#85653),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#83260 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#83261 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83263 = ORIENTED_EDGE('',*,*,#83264,.T.); -#83264 = EDGE_CURVE('',#83238,#83265,#83267,.T.); -#83265 = VERTEX_POINT('',#83266); -#83266 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); -#83267 = SURFACE_CURVE('',#83268,(#83272,#83279),.PCURVE_S1.); -#83268 = LINE('',#83269,#83270); -#83269 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); -#83270 = VECTOR('',#83271,1.); -#83271 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83272 = PCURVE('',#77977,#83273); -#83273 = DEFINITIONAL_REPRESENTATION('',(#83274),#83278); -#83274 = LINE('',#83275,#83276); -#83275 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#83276 = VECTOR('',#83277,1.); -#83277 = DIRECTION('',(0.E+000,-1.)); -#83278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83279 = PCURVE('',#83045,#83280); -#83280 = DEFINITIONAL_REPRESENTATION('',(#83281),#83285); -#83281 = LINE('',#83282,#83283); -#83282 = CARTESIAN_POINT('',(0.4,0.E+000)); -#83283 = VECTOR('',#83284,1.); -#83284 = DIRECTION('',(0.E+000,-1.)); -#83285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83286 = ORIENTED_EDGE('',*,*,#83287,.T.); -#83287 = EDGE_CURVE('',#83265,#83288,#83290,.T.); -#83288 = VERTEX_POINT('',#83289); -#83289 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#83290 = SURFACE_CURVE('',#83291,(#83295,#83302),.PCURVE_S1.); -#83291 = LINE('',#83292,#83293); -#83292 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#83293 = VECTOR('',#83294,1.); -#83294 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83295 = PCURVE('',#77977,#83296); -#83296 = DEFINITIONAL_REPRESENTATION('',(#83297),#83301); -#83297 = LINE('',#83298,#83299); -#83298 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#83299 = VECTOR('',#83300,1.); -#83300 = DIRECTION('',(1.,0.E+000)); -#83301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83302 = PCURVE('',#83017,#83303); -#83303 = DEFINITIONAL_REPRESENTATION('',(#83304),#83308); -#83304 = LINE('',#83305,#83306); -#83305 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83306 = VECTOR('',#83307,1.); -#83307 = DIRECTION('',(1.,0.E+000)); -#83308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83309 = ORIENTED_EDGE('',*,*,#83310,.T.); -#83310 = EDGE_CURVE('',#83288,#83311,#83313,.T.); -#83311 = VERTEX_POINT('',#83312); -#83312 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.E+000)); -#83313 = SURFACE_CURVE('',#83314,(#83318,#83325),.PCURVE_S1.); -#83314 = LINE('',#83315,#83316); -#83315 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#83316 = VECTOR('',#83317,1.); -#83317 = DIRECTION('',(0.E+000,1.,0.E+000)); -#83318 = PCURVE('',#77977,#83319); -#83319 = DEFINITIONAL_REPRESENTATION('',(#83320),#83324); -#83320 = LINE('',#83321,#83322); -#83321 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#83322 = VECTOR('',#83323,1.); -#83323 = DIRECTION('',(0.E+000,1.)); -#83324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83325 = PCURVE('',#82989,#83326); -#83326 = DEFINITIONAL_REPRESENTATION('',(#83327),#83331); -#83327 = LINE('',#83328,#83329); -#83328 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#83329 = VECTOR('',#83330,1.); -#83330 = DIRECTION('',(0.E+000,1.)); -#83331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83332 = ORIENTED_EDGE('',*,*,#83333,.T.); -#83333 = EDGE_CURVE('',#83311,#83334,#83336,.T.); -#83334 = VERTEX_POINT('',#83335); -#83335 = CARTESIAN_POINT('',(-0.745,-0.746501027564,0.178089594298)); -#83336 = SURFACE_CURVE('',#83337,(#83342,#83349),.PCURVE_S1.); -#83337 = CIRCLE('',#83338,0.2); -#83338 = AXIS2_PLACEMENT_3D('',#83339,#83340,#83341); -#83339 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); -#83340 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83341 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83342 = PCURVE('',#77977,#83343); -#83343 = DEFINITIONAL_REPRESENTATION('',(#83344),#83348); -#83344 = CIRCLE('',#83345,0.2); -#83345 = AXIS2_PLACEMENT_2D('',#83346,#83347); -#83346 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#83347 = DIRECTION('',(-1.,0.E+000)); -#83348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83349 = PCURVE('',#82962,#83350); -#83350 = DEFINITIONAL_REPRESENTATION('',(#83351),#83354); -#83351 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83352,#83353),.UNSPECIFIED., +#85652 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#85653 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85655 = ORIENTED_EDGE('',*,*,#85656,.T.); +#85656 = EDGE_CURVE('',#85630,#85657,#85659,.T.); +#85657 = VERTEX_POINT('',#85658); +#85658 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); +#85659 = SURFACE_CURVE('',#85660,(#85664,#85671),.PCURVE_S1.); +#85660 = LINE('',#85661,#85662); +#85661 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); +#85662 = VECTOR('',#85663,1.); +#85663 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#85664 = PCURVE('',#80369,#85665); +#85665 = DEFINITIONAL_REPRESENTATION('',(#85666),#85670); +#85666 = LINE('',#85667,#85668); +#85667 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#85668 = VECTOR('',#85669,1.); +#85669 = DIRECTION('',(0.E+000,-1.)); +#85670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85671 = PCURVE('',#85437,#85672); +#85672 = DEFINITIONAL_REPRESENTATION('',(#85673),#85677); +#85673 = LINE('',#85674,#85675); +#85674 = CARTESIAN_POINT('',(0.4,0.E+000)); +#85675 = VECTOR('',#85676,1.); +#85676 = DIRECTION('',(0.E+000,-1.)); +#85677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85678 = ORIENTED_EDGE('',*,*,#85679,.T.); +#85679 = EDGE_CURVE('',#85657,#85680,#85682,.T.); +#85680 = VERTEX_POINT('',#85681); +#85681 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#85682 = SURFACE_CURVE('',#85683,(#85687,#85694),.PCURVE_S1.); +#85683 = LINE('',#85684,#85685); +#85684 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#85685 = VECTOR('',#85686,1.); +#85686 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85687 = PCURVE('',#80369,#85688); +#85688 = DEFINITIONAL_REPRESENTATION('',(#85689),#85693); +#85689 = LINE('',#85690,#85691); +#85690 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#85691 = VECTOR('',#85692,1.); +#85692 = DIRECTION('',(1.,0.E+000)); +#85693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85694 = PCURVE('',#85409,#85695); +#85695 = DEFINITIONAL_REPRESENTATION('',(#85696),#85700); +#85696 = LINE('',#85697,#85698); +#85697 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85698 = VECTOR('',#85699,1.); +#85699 = DIRECTION('',(1.,0.E+000)); +#85700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85701 = ORIENTED_EDGE('',*,*,#85702,.T.); +#85702 = EDGE_CURVE('',#85680,#85703,#85705,.T.); +#85703 = VERTEX_POINT('',#85704); +#85704 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.E+000)); +#85705 = SURFACE_CURVE('',#85706,(#85710,#85717),.PCURVE_S1.); +#85706 = LINE('',#85707,#85708); +#85707 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#85708 = VECTOR('',#85709,1.); +#85709 = DIRECTION('',(0.E+000,1.,0.E+000)); +#85710 = PCURVE('',#80369,#85711); +#85711 = DEFINITIONAL_REPRESENTATION('',(#85712),#85716); +#85712 = LINE('',#85713,#85714); +#85713 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#85714 = VECTOR('',#85715,1.); +#85715 = DIRECTION('',(0.E+000,1.)); +#85716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85717 = PCURVE('',#85381,#85718); +#85718 = DEFINITIONAL_REPRESENTATION('',(#85719),#85723); +#85719 = LINE('',#85720,#85721); +#85720 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#85721 = VECTOR('',#85722,1.); +#85722 = DIRECTION('',(0.E+000,1.)); +#85723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85724 = ORIENTED_EDGE('',*,*,#85725,.T.); +#85725 = EDGE_CURVE('',#85703,#85726,#85728,.T.); +#85726 = VERTEX_POINT('',#85727); +#85727 = CARTESIAN_POINT('',(-0.745,-0.746501027564,0.178089594298)); +#85728 = SURFACE_CURVE('',#85729,(#85734,#85741),.PCURVE_S1.); +#85729 = CIRCLE('',#85730,0.2); +#85730 = AXIS2_PLACEMENT_3D('',#85731,#85732,#85733); +#85731 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); +#85732 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85733 = DIRECTION('',(0.E+000,0.E+000,1.)); +#85734 = PCURVE('',#80369,#85735); +#85735 = DEFINITIONAL_REPRESENTATION('',(#85736),#85740); +#85736 = CIRCLE('',#85737,0.2); +#85737 = AXIS2_PLACEMENT_2D('',#85738,#85739); +#85738 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#85739 = DIRECTION('',(-1.,0.E+000)); +#85740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85741 = PCURVE('',#85354,#85742); +#85742 = DEFINITIONAL_REPRESENTATION('',(#85743),#85746); +#85743 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85744,#85745),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#83352 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83353 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#83354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83355 = ORIENTED_EDGE('',*,*,#83356,.T.); -#83356 = EDGE_CURVE('',#83334,#83357,#83359,.T.); -#83357 = VERTEX_POINT('',#83358); -#83358 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); -#83359 = SURFACE_CURVE('',#83360,(#83364,#83371),.PCURVE_S1.); -#83360 = LINE('',#83361,#83362); -#83361 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); -#83362 = VECTOR('',#83363,1.); -#83363 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#83364 = PCURVE('',#77977,#83365); -#83365 = DEFINITIONAL_REPRESENTATION('',(#83366),#83370); -#83366 = LINE('',#83367,#83368); -#83367 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#83368 = VECTOR('',#83369,1.); -#83369 = DIRECTION('',(-0.993981062721,0.109552028512)); -#83370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83371 = PCURVE('',#82933,#83372); -#83372 = DEFINITIONAL_REPRESENTATION('',(#83373),#83377); -#83373 = LINE('',#83374,#83375); -#83374 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83375 = VECTOR('',#83376,1.); -#83376 = DIRECTION('',(1.,0.E+000)); -#83377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83378 = ORIENTED_EDGE('',*,*,#83379,.T.); -#83379 = EDGE_CURVE('',#83357,#83143,#83380,.T.); -#83380 = SURFACE_CURVE('',#83381,(#83386,#83397),.PCURVE_S1.); -#83381 = CIRCLE('',#83382,5.E-002); -#83382 = AXIS2_PLACEMENT_3D('',#83383,#83384,#83385); -#83383 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#83384 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#83385 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83386 = PCURVE('',#77977,#83387); -#83387 = DEFINITIONAL_REPRESENTATION('',(#83388),#83396); -#83388 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83389,#83390,#83391,#83392 - ,#83393,#83394,#83395),.UNSPECIFIED.,.F.,.F.) +#85744 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85745 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#85746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85747 = ORIENTED_EDGE('',*,*,#85748,.T.); +#85748 = EDGE_CURVE('',#85726,#85749,#85751,.T.); +#85749 = VERTEX_POINT('',#85750); +#85750 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); +#85751 = SURFACE_CURVE('',#85752,(#85756,#85763),.PCURVE_S1.); +#85752 = LINE('',#85753,#85754); +#85753 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); +#85754 = VECTOR('',#85755,1.); +#85755 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#85756 = PCURVE('',#80369,#85757); +#85757 = DEFINITIONAL_REPRESENTATION('',(#85758),#85762); +#85758 = LINE('',#85759,#85760); +#85759 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#85760 = VECTOR('',#85761,1.); +#85761 = DIRECTION('',(-0.993981062721,0.109552028512)); +#85762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85763 = PCURVE('',#85325,#85764); +#85764 = DEFINITIONAL_REPRESENTATION('',(#85765),#85769); +#85765 = LINE('',#85766,#85767); +#85766 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85767 = VECTOR('',#85768,1.); +#85768 = DIRECTION('',(1.,0.E+000)); +#85769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85770 = ORIENTED_EDGE('',*,*,#85771,.T.); +#85771 = EDGE_CURVE('',#85749,#85535,#85772,.T.); +#85772 = SURFACE_CURVE('',#85773,(#85778,#85789),.PCURVE_S1.); +#85773 = CIRCLE('',#85774,5.E-002); +#85774 = AXIS2_PLACEMENT_3D('',#85775,#85776,#85777); +#85775 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#85776 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#85777 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#85778 = PCURVE('',#80369,#85779); +#85779 = DEFINITIONAL_REPRESENTATION('',(#85780),#85788); +#85780 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#85781,#85782,#85783,#85784 + ,#85785,#85786,#85787),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#83389 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#83390 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#83391 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#83392 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#83393 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#83394 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#83395 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#83396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83397 = PCURVE('',#82906,#83398); -#83398 = DEFINITIONAL_REPRESENTATION('',(#83399),#83402); -#83399 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83400,#83401),.UNSPECIFIED., +#85781 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#85782 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#85783 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#85784 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#85785 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#85786 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#85787 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#85788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85789 = PCURVE('',#85298,#85790); +#85790 = DEFINITIONAL_REPRESENTATION('',(#85791),#85794); +#85791 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85792,#85793),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#83400 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#83401 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#83402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83403 = ORIENTED_EDGE('',*,*,#83142,.T.); -#83404 = ADVANCED_FACE('',(#83405),#82906,.F.); -#83405 = FACE_BOUND('',#83406,.F.); -#83406 = EDGE_LOOP('',(#83407,#83408,#83409,#83429)); -#83407 = ORIENTED_EDGE('',*,*,#83165,.F.); -#83408 = ORIENTED_EDGE('',*,*,#82885,.F.); -#83409 = ORIENTED_EDGE('',*,*,#83410,.T.); -#83410 = EDGE_CURVE('',#82886,#83357,#83411,.T.); -#83411 = SURFACE_CURVE('',#83412,(#83416,#83422),.PCURVE_S1.); -#83412 = LINE('',#83413,#83414); -#83413 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#83414 = VECTOR('',#83415,1.); -#83415 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83416 = PCURVE('',#82906,#83417); -#83417 = DEFINITIONAL_REPRESENTATION('',(#83418),#83421); -#83418 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83419,#83420),.UNSPECIFIED., +#85792 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#85793 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#85794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85795 = ORIENTED_EDGE('',*,*,#85534,.T.); +#85796 = ADVANCED_FACE('',(#85797),#85298,.F.); +#85797 = FACE_BOUND('',#85798,.F.); +#85798 = EDGE_LOOP('',(#85799,#85800,#85801,#85821)); +#85799 = ORIENTED_EDGE('',*,*,#85557,.F.); +#85800 = ORIENTED_EDGE('',*,*,#85277,.F.); +#85801 = ORIENTED_EDGE('',*,*,#85802,.T.); +#85802 = EDGE_CURVE('',#85278,#85749,#85803,.T.); +#85803 = SURFACE_CURVE('',#85804,(#85808,#85814),.PCURVE_S1.); +#85804 = LINE('',#85805,#85806); +#85805 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#85806 = VECTOR('',#85807,1.); +#85807 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85808 = PCURVE('',#85298,#85809); +#85809 = DEFINITIONAL_REPRESENTATION('',(#85810),#85813); +#85810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85811,#85812),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83419 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#83420 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#83421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83422 = PCURVE('',#82933,#83423); -#83423 = DEFINITIONAL_REPRESENTATION('',(#83424),#83428); -#83424 = LINE('',#83425,#83426); -#83425 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83426 = VECTOR('',#83427,1.); -#83427 = DIRECTION('',(0.E+000,1.)); -#83428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83429 = ORIENTED_EDGE('',*,*,#83379,.T.); -#83430 = ADVANCED_FACE('',(#83431),#82933,.T.); -#83431 = FACE_BOUND('',#83432,.T.); -#83432 = EDGE_LOOP('',(#83433,#83434,#83435,#83455)); -#83433 = ORIENTED_EDGE('',*,*,#83410,.T.); -#83434 = ORIENTED_EDGE('',*,*,#83356,.F.); -#83435 = ORIENTED_EDGE('',*,*,#83436,.F.); -#83436 = EDGE_CURVE('',#82918,#83334,#83437,.T.); -#83437 = SURFACE_CURVE('',#83438,(#83442,#83449),.PCURVE_S1.); -#83438 = LINE('',#83439,#83440); -#83439 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); -#83440 = VECTOR('',#83441,1.); -#83441 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83442 = PCURVE('',#82933,#83443); -#83443 = DEFINITIONAL_REPRESENTATION('',(#83444),#83448); -#83444 = LINE('',#83445,#83446); -#83445 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#83446 = VECTOR('',#83447,1.); -#83447 = DIRECTION('',(0.E+000,1.)); -#83448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83449 = PCURVE('',#82962,#83450); -#83450 = DEFINITIONAL_REPRESENTATION('',(#83451),#83454); -#83451 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83452,#83453),.UNSPECIFIED., +#85811 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#85812 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#85813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85814 = PCURVE('',#85325,#85815); +#85815 = DEFINITIONAL_REPRESENTATION('',(#85816),#85820); +#85816 = LINE('',#85817,#85818); +#85817 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85818 = VECTOR('',#85819,1.); +#85819 = DIRECTION('',(0.E+000,1.)); +#85820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85821 = ORIENTED_EDGE('',*,*,#85771,.T.); +#85822 = ADVANCED_FACE('',(#85823),#85325,.T.); +#85823 = FACE_BOUND('',#85824,.T.); +#85824 = EDGE_LOOP('',(#85825,#85826,#85827,#85847)); +#85825 = ORIENTED_EDGE('',*,*,#85802,.T.); +#85826 = ORIENTED_EDGE('',*,*,#85748,.F.); +#85827 = ORIENTED_EDGE('',*,*,#85828,.F.); +#85828 = EDGE_CURVE('',#85310,#85726,#85829,.T.); +#85829 = SURFACE_CURVE('',#85830,(#85834,#85841),.PCURVE_S1.); +#85830 = LINE('',#85831,#85832); +#85831 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); +#85832 = VECTOR('',#85833,1.); +#85833 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85834 = PCURVE('',#85325,#85835); +#85835 = DEFINITIONAL_REPRESENTATION('',(#85836),#85840); +#85836 = LINE('',#85837,#85838); +#85837 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#85838 = VECTOR('',#85839,1.); +#85839 = DIRECTION('',(0.E+000,1.)); +#85840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85841 = PCURVE('',#85354,#85842); +#85842 = DEFINITIONAL_REPRESENTATION('',(#85843),#85846); +#85843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85844,#85845),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83452 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#83453 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#83454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#85844 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#85845 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#85846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#83455 = ORIENTED_EDGE('',*,*,#82917,.T.); -#83456 = ADVANCED_FACE('',(#83457),#82962,.T.); -#83457 = FACE_BOUND('',#83458,.T.); -#83458 = EDGE_LOOP('',(#83459,#83460,#83461,#83504)); -#83459 = ORIENTED_EDGE('',*,*,#83436,.T.); -#83460 = ORIENTED_EDGE('',*,*,#83333,.F.); -#83461 = ORIENTED_EDGE('',*,*,#83462,.F.); -#83462 = EDGE_CURVE('',#82946,#83311,#83463,.T.); -#83463 = SURFACE_CURVE('',#83464,(#83468,#83497),.PCURVE_S1.); -#83464 = LINE('',#83465,#83466); -#83465 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); -#83466 = VECTOR('',#83467,1.); -#83467 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83468 = PCURVE('',#82962,#83469); -#83469 = DEFINITIONAL_REPRESENTATION('',(#83470),#83496); -#83470 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#83471,#83472,#83473,#83474, - #83475,#83476,#83477,#83478,#83479,#83480,#83481,#83482,#83483, - #83484,#83485,#83486,#83487,#83488,#83489,#83490,#83491,#83492, - #83493,#83494,#83495),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#85847 = ORIENTED_EDGE('',*,*,#85309,.T.); +#85848 = ADVANCED_FACE('',(#85849),#85354,.T.); +#85849 = FACE_BOUND('',#85850,.T.); +#85850 = EDGE_LOOP('',(#85851,#85852,#85853,#85896)); +#85851 = ORIENTED_EDGE('',*,*,#85828,.T.); +#85852 = ORIENTED_EDGE('',*,*,#85725,.F.); +#85853 = ORIENTED_EDGE('',*,*,#85854,.F.); +#85854 = EDGE_CURVE('',#85338,#85703,#85855,.T.); +#85855 = SURFACE_CURVE('',#85856,(#85860,#85889),.PCURVE_S1.); +#85856 = LINE('',#85857,#85858); +#85857 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); +#85858 = VECTOR('',#85859,1.); +#85859 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85860 = PCURVE('',#85354,#85861); +#85861 = DEFINITIONAL_REPRESENTATION('',(#85862),#85888); +#85862 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85863,#85864,#85865,#85866, + #85867,#85868,#85869,#85870,#85871,#85872,#85873,#85874,#85875, + #85876,#85877,#85878,#85879,#85880,#85881,#85882,#85883,#85884, + #85885,#85886,#85887),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -103487,133 +106476,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#83471 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83472 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003)); -#83473 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002)); -#83474 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); -#83475 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002)); -#83476 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002)); -#83477 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002)); -#83478 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); -#83479 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); -#83480 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); -#83481 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); -#83482 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); -#83483 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); -#83484 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); -#83485 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); -#83486 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); -#83487 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); -#83488 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); -#83489 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); -#83490 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); -#83491 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); -#83492 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); -#83493 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); -#83494 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); -#83495 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83497 = PCURVE('',#82989,#83498); -#83498 = DEFINITIONAL_REPRESENTATION('',(#83499),#83503); -#83499 = LINE('',#83500,#83501); -#83500 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#83501 = VECTOR('',#83502,1.); -#83502 = DIRECTION('',(-1.,0.E+000)); -#83503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83504 = ORIENTED_EDGE('',*,*,#82945,.T.); -#83505 = ADVANCED_FACE('',(#83506),#82989,.T.); -#83506 = FACE_BOUND('',#83507,.T.); -#83507 = EDGE_LOOP('',(#83508,#83509,#83510,#83531)); -#83508 = ORIENTED_EDGE('',*,*,#83462,.T.); -#83509 = ORIENTED_EDGE('',*,*,#83310,.F.); -#83510 = ORIENTED_EDGE('',*,*,#83511,.F.); -#83511 = EDGE_CURVE('',#82974,#83288,#83512,.T.); -#83512 = SURFACE_CURVE('',#83513,(#83517,#83524),.PCURVE_S1.); -#83513 = LINE('',#83514,#83515); -#83514 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#83515 = VECTOR('',#83516,1.); -#83516 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83517 = PCURVE('',#82989,#83518); -#83518 = DEFINITIONAL_REPRESENTATION('',(#83519),#83523); -#83519 = LINE('',#83520,#83521); -#83520 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83521 = VECTOR('',#83522,1.); -#83522 = DIRECTION('',(-1.,0.E+000)); -#83523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83524 = PCURVE('',#83017,#83525); -#83525 = DEFINITIONAL_REPRESENTATION('',(#83526),#83530); -#83526 = LINE('',#83527,#83528); -#83527 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83528 = VECTOR('',#83529,1.); -#83529 = DIRECTION('',(0.E+000,1.)); -#83530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83531 = ORIENTED_EDGE('',*,*,#82973,.T.); -#83532 = ADVANCED_FACE('',(#83533),#83017,.T.); -#83533 = FACE_BOUND('',#83534,.T.); -#83534 = EDGE_LOOP('',(#83535,#83536,#83537,#83558)); -#83535 = ORIENTED_EDGE('',*,*,#83511,.T.); -#83536 = ORIENTED_EDGE('',*,*,#83287,.F.); -#83537 = ORIENTED_EDGE('',*,*,#83538,.F.); -#83538 = EDGE_CURVE('',#83002,#83265,#83539,.T.); -#83539 = SURFACE_CURVE('',#83540,(#83544,#83551),.PCURVE_S1.); -#83540 = LINE('',#83541,#83542); -#83541 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#83542 = VECTOR('',#83543,1.); -#83543 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83544 = PCURVE('',#83017,#83545); -#83545 = DEFINITIONAL_REPRESENTATION('',(#83546),#83550); -#83546 = LINE('',#83547,#83548); -#83547 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#83548 = VECTOR('',#83549,1.); -#83549 = DIRECTION('',(0.E+000,1.)); -#83550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83551 = PCURVE('',#83045,#83552); -#83552 = DEFINITIONAL_REPRESENTATION('',(#83553),#83557); -#83553 = LINE('',#83554,#83555); -#83554 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83555 = VECTOR('',#83556,1.); -#83556 = DIRECTION('',(1.,0.E+000)); -#83557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83558 = ORIENTED_EDGE('',*,*,#83001,.T.); -#83559 = ADVANCED_FACE('',(#83560),#83045,.T.); -#83560 = FACE_BOUND('',#83561,.T.); -#83561 = EDGE_LOOP('',(#83562,#83563,#83564,#83607)); -#83562 = ORIENTED_EDGE('',*,*,#83538,.T.); -#83563 = ORIENTED_EDGE('',*,*,#83264,.F.); -#83564 = ORIENTED_EDGE('',*,*,#83565,.F.); -#83565 = EDGE_CURVE('',#83030,#83238,#83566,.T.); -#83566 = SURFACE_CURVE('',#83567,(#83571,#83578),.PCURVE_S1.); -#83567 = LINE('',#83568,#83569); -#83568 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); -#83569 = VECTOR('',#83570,1.); -#83570 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83571 = PCURVE('',#83045,#83572); -#83572 = DEFINITIONAL_REPRESENTATION('',(#83573),#83577); -#83573 = LINE('',#83574,#83575); -#83574 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#83575 = VECTOR('',#83576,1.); -#83576 = DIRECTION('',(1.,0.E+000)); -#83577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83578 = PCURVE('',#83078,#83579); -#83579 = DEFINITIONAL_REPRESENTATION('',(#83580),#83606); -#83580 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#83581,#83582,#83583,#83584, - #83585,#83586,#83587,#83588,#83589,#83590,#83591,#83592,#83593, - #83594,#83595,#83596,#83597,#83598,#83599,#83600,#83601,#83602, - #83603,#83604,#83605),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#85863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85864 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003)); +#85865 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002)); +#85866 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); +#85867 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002)); +#85868 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002)); +#85869 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002)); +#85870 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); +#85871 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); +#85872 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); +#85873 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); +#85874 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); +#85875 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); +#85876 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); +#85877 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); +#85878 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); +#85879 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); +#85880 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); +#85881 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); +#85882 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); +#85883 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); +#85884 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); +#85885 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); +#85886 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); +#85887 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85889 = PCURVE('',#85381,#85890); +#85890 = DEFINITIONAL_REPRESENTATION('',(#85891),#85895); +#85891 = LINE('',#85892,#85893); +#85892 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#85893 = VECTOR('',#85894,1.); +#85894 = DIRECTION('',(-1.,0.E+000)); +#85895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85896 = ORIENTED_EDGE('',*,*,#85337,.T.); +#85897 = ADVANCED_FACE('',(#85898),#85381,.T.); +#85898 = FACE_BOUND('',#85899,.T.); +#85899 = EDGE_LOOP('',(#85900,#85901,#85902,#85923)); +#85900 = ORIENTED_EDGE('',*,*,#85854,.T.); +#85901 = ORIENTED_EDGE('',*,*,#85702,.F.); +#85902 = ORIENTED_EDGE('',*,*,#85903,.F.); +#85903 = EDGE_CURVE('',#85366,#85680,#85904,.T.); +#85904 = SURFACE_CURVE('',#85905,(#85909,#85916),.PCURVE_S1.); +#85905 = LINE('',#85906,#85907); +#85906 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#85907 = VECTOR('',#85908,1.); +#85908 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85909 = PCURVE('',#85381,#85910); +#85910 = DEFINITIONAL_REPRESENTATION('',(#85911),#85915); +#85911 = LINE('',#85912,#85913); +#85912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85913 = VECTOR('',#85914,1.); +#85914 = DIRECTION('',(-1.,0.E+000)); +#85915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85916 = PCURVE('',#85409,#85917); +#85917 = DEFINITIONAL_REPRESENTATION('',(#85918),#85922); +#85918 = LINE('',#85919,#85920); +#85919 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85920 = VECTOR('',#85921,1.); +#85921 = DIRECTION('',(0.E+000,1.)); +#85922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85923 = ORIENTED_EDGE('',*,*,#85365,.T.); +#85924 = ADVANCED_FACE('',(#85925),#85409,.T.); +#85925 = FACE_BOUND('',#85926,.T.); +#85926 = EDGE_LOOP('',(#85927,#85928,#85929,#85950)); +#85927 = ORIENTED_EDGE('',*,*,#85903,.T.); +#85928 = ORIENTED_EDGE('',*,*,#85679,.F.); +#85929 = ORIENTED_EDGE('',*,*,#85930,.F.); +#85930 = EDGE_CURVE('',#85394,#85657,#85931,.T.); +#85931 = SURFACE_CURVE('',#85932,(#85936,#85943),.PCURVE_S1.); +#85932 = LINE('',#85933,#85934); +#85933 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#85934 = VECTOR('',#85935,1.); +#85935 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85936 = PCURVE('',#85409,#85937); +#85937 = DEFINITIONAL_REPRESENTATION('',(#85938),#85942); +#85938 = LINE('',#85939,#85940); +#85939 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#85940 = VECTOR('',#85941,1.); +#85941 = DIRECTION('',(0.E+000,1.)); +#85942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85943 = PCURVE('',#85437,#85944); +#85944 = DEFINITIONAL_REPRESENTATION('',(#85945),#85949); +#85945 = LINE('',#85946,#85947); +#85946 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85947 = VECTOR('',#85948,1.); +#85948 = DIRECTION('',(1.,0.E+000)); +#85949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85950 = ORIENTED_EDGE('',*,*,#85393,.T.); +#85951 = ADVANCED_FACE('',(#85952),#85437,.T.); +#85952 = FACE_BOUND('',#85953,.T.); +#85953 = EDGE_LOOP('',(#85954,#85955,#85956,#85999)); +#85954 = ORIENTED_EDGE('',*,*,#85930,.T.); +#85955 = ORIENTED_EDGE('',*,*,#85656,.F.); +#85956 = ORIENTED_EDGE('',*,*,#85957,.F.); +#85957 = EDGE_CURVE('',#85422,#85630,#85958,.T.); +#85958 = SURFACE_CURVE('',#85959,(#85963,#85970),.PCURVE_S1.); +#85959 = LINE('',#85960,#85961); +#85960 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); +#85961 = VECTOR('',#85962,1.); +#85962 = DIRECTION('',(1.,0.E+000,0.E+000)); +#85963 = PCURVE('',#85437,#85964); +#85964 = DEFINITIONAL_REPRESENTATION('',(#85965),#85969); +#85965 = LINE('',#85966,#85967); +#85966 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#85967 = VECTOR('',#85968,1.); +#85968 = DIRECTION('',(1.,0.E+000)); +#85969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85970 = PCURVE('',#85470,#85971); +#85971 = DEFINITIONAL_REPRESENTATION('',(#85972),#85998); +#85972 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85973,#85974,#85975,#85976, + #85977,#85978,#85979,#85980,#85981,#85982,#85983,#85984,#85985, + #85986,#85987,#85988,#85989,#85990,#85991,#85992,#85993,#85994, + #85995,#85996,#85997),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -103621,918 +106610,918 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#83581 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83582 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003)); -#83583 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); -#83584 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); -#83585 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002)); -#83586 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002)); -#83587 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002)); -#83588 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); -#83589 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); -#83590 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); -#83591 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); -#83592 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); -#83593 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); -#83594 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); -#83595 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); -#83596 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); -#83597 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); -#83598 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); -#83599 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#83600 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); -#83601 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); -#83602 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); -#83603 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); -#83604 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); -#83605 = CARTESIAN_POINT('',(0.E+000,0.4)); -#83606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83607 = ORIENTED_EDGE('',*,*,#83029,.T.); -#83608 = ADVANCED_FACE('',(#83609),#83078,.F.); -#83609 = FACE_BOUND('',#83610,.F.); -#83610 = EDGE_LOOP('',(#83611,#83612,#83613,#83633)); -#83611 = ORIENTED_EDGE('',*,*,#83565,.F.); -#83612 = ORIENTED_EDGE('',*,*,#83057,.F.); -#83613 = ORIENTED_EDGE('',*,*,#83614,.T.); -#83614 = EDGE_CURVE('',#83058,#83215,#83615,.T.); -#83615 = SURFACE_CURVE('',#83616,(#83620,#83626),.PCURVE_S1.); -#83616 = LINE('',#83617,#83618); -#83617 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#83618 = VECTOR('',#83619,1.); -#83619 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83620 = PCURVE('',#83078,#83621); -#83621 = DEFINITIONAL_REPRESENTATION('',(#83622),#83625); -#83622 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83623,#83624),.UNSPECIFIED., +#85973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#85974 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003)); +#85975 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); +#85976 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002)); +#85977 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002)); +#85978 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002)); +#85979 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002)); +#85980 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); +#85981 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); +#85982 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); +#85983 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); +#85984 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); +#85985 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); +#85986 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); +#85987 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); +#85988 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); +#85989 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); +#85990 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); +#85991 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#85992 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); +#85993 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); +#85994 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); +#85995 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); +#85996 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); +#85997 = CARTESIAN_POINT('',(0.E+000,0.4)); +#85998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#85999 = ORIENTED_EDGE('',*,*,#85421,.T.); +#86000 = ADVANCED_FACE('',(#86001),#85470,.F.); +#86001 = FACE_BOUND('',#86002,.F.); +#86002 = EDGE_LOOP('',(#86003,#86004,#86005,#86025)); +#86003 = ORIENTED_EDGE('',*,*,#85957,.F.); +#86004 = ORIENTED_EDGE('',*,*,#85449,.F.); +#86005 = ORIENTED_EDGE('',*,*,#86006,.T.); +#86006 = EDGE_CURVE('',#85450,#85607,#86007,.T.); +#86007 = SURFACE_CURVE('',#86008,(#86012,#86018),.PCURVE_S1.); +#86008 = LINE('',#86009,#86010); +#86009 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#86010 = VECTOR('',#86011,1.); +#86011 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86012 = PCURVE('',#85470,#86013); +#86013 = DEFINITIONAL_REPRESENTATION('',(#86014),#86017); +#86014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86015,#86016),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83623 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#83624 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#83625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83626 = PCURVE('',#83105,#83627); -#83627 = DEFINITIONAL_REPRESENTATION('',(#83628),#83632); -#83628 = LINE('',#83629,#83630); -#83629 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83630 = VECTOR('',#83631,1.); -#83631 = DIRECTION('',(0.E+000,1.)); -#83632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83633 = ORIENTED_EDGE('',*,*,#83237,.T.); -#83634 = ADVANCED_FACE('',(#83635),#83105,.T.); -#83635 = FACE_BOUND('',#83636,.T.); -#83636 = EDGE_LOOP('',(#83637,#83638,#83639,#83659)); -#83637 = ORIENTED_EDGE('',*,*,#83614,.T.); -#83638 = ORIENTED_EDGE('',*,*,#83214,.F.); -#83639 = ORIENTED_EDGE('',*,*,#83640,.F.); -#83640 = EDGE_CURVE('',#83090,#83192,#83641,.T.); -#83641 = SURFACE_CURVE('',#83642,(#83646,#83653),.PCURVE_S1.); -#83642 = LINE('',#83643,#83644); -#83643 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); -#83644 = VECTOR('',#83645,1.); -#83645 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83646 = PCURVE('',#83105,#83647); -#83647 = DEFINITIONAL_REPRESENTATION('',(#83648),#83652); -#83648 = LINE('',#83649,#83650); -#83649 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#83650 = VECTOR('',#83651,1.); -#83651 = DIRECTION('',(0.E+000,1.)); -#83652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83653 = PCURVE('',#82825,#83654); -#83654 = DEFINITIONAL_REPRESENTATION('',(#83655),#83658); -#83655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83656,#83657),.UNSPECIFIED., +#86015 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#86016 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#86017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86018 = PCURVE('',#85497,#86019); +#86019 = DEFINITIONAL_REPRESENTATION('',(#86020),#86024); +#86020 = LINE('',#86021,#86022); +#86021 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86022 = VECTOR('',#86023,1.); +#86023 = DIRECTION('',(0.E+000,1.)); +#86024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86025 = ORIENTED_EDGE('',*,*,#85629,.T.); +#86026 = ADVANCED_FACE('',(#86027),#85497,.T.); +#86027 = FACE_BOUND('',#86028,.T.); +#86028 = EDGE_LOOP('',(#86029,#86030,#86031,#86051)); +#86029 = ORIENTED_EDGE('',*,*,#86006,.T.); +#86030 = ORIENTED_EDGE('',*,*,#85606,.F.); +#86031 = ORIENTED_EDGE('',*,*,#86032,.F.); +#86032 = EDGE_CURVE('',#85482,#85584,#86033,.T.); +#86033 = SURFACE_CURVE('',#86034,(#86038,#86045),.PCURVE_S1.); +#86034 = LINE('',#86035,#86036); +#86035 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); +#86036 = VECTOR('',#86037,1.); +#86037 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86038 = PCURVE('',#85497,#86039); +#86039 = DEFINITIONAL_REPRESENTATION('',(#86040),#86044); +#86040 = LINE('',#86041,#86042); +#86041 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#86042 = VECTOR('',#86043,1.); +#86043 = DIRECTION('',(0.E+000,1.)); +#86044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86045 = PCURVE('',#85217,#86046); +#86046 = DEFINITIONAL_REPRESENTATION('',(#86047),#86050); +#86047 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86048,#86049),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83656 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#83657 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#83658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83659 = ORIENTED_EDGE('',*,*,#83089,.T.); -#83660 = ADVANCED_FACE('',(#83661),#82825,.T.); -#83661 = FACE_BOUND('',#83662,.T.); -#83662 = EDGE_LOOP('',(#83663,#83664,#83665,#83666)); -#83663 = ORIENTED_EDGE('',*,*,#83640,.T.); -#83664 = ORIENTED_EDGE('',*,*,#83191,.F.); -#83665 = ORIENTED_EDGE('',*,*,#82809,.F.); -#83666 = ORIENTED_EDGE('',*,*,#83117,.T.); -#83667 = ADVANCED_FACE('',(#83668),#78416,.T.); -#83668 = FACE_BOUND('',#83669,.T.); -#83669 = EDGE_LOOP('',(#83670,#83671,#83694,#83721)); -#83670 = ORIENTED_EDGE('',*,*,#78400,.F.); -#83671 = ORIENTED_EDGE('',*,*,#83672,.F.); -#83672 = EDGE_CURVE('',#83673,#78373,#83675,.T.); -#83673 = VERTEX_POINT('',#83674); -#83674 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); -#83675 = SURFACE_CURVE('',#83676,(#83680,#83687),.PCURVE_S1.); -#83676 = LINE('',#83677,#83678); -#83677 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); -#83678 = VECTOR('',#83679,1.); -#83679 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83680 = PCURVE('',#78416,#83681); -#83681 = DEFINITIONAL_REPRESENTATION('',(#83682),#83686); -#83682 = LINE('',#83683,#83684); -#83683 = CARTESIAN_POINT('',(0.4,0.E+000)); -#83684 = VECTOR('',#83685,1.); -#83685 = DIRECTION('',(0.E+000,-1.)); -#83686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83687 = PCURVE('',#78388,#83688); -#83688 = DEFINITIONAL_REPRESENTATION('',(#83689),#83693); -#83689 = LINE('',#83690,#83691); -#83690 = CARTESIAN_POINT('',(0.55,-0.290089238914)); -#83691 = VECTOR('',#83692,1.); -#83692 = DIRECTION('',(0.E+000,-1.)); -#83693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83694 = ORIENTED_EDGE('',*,*,#83695,.F.); -#83695 = EDGE_CURVE('',#83696,#83673,#83698,.T.); -#83696 = VERTEX_POINT('',#83697); -#83697 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#83698 = SURFACE_CURVE('',#83699,(#83703,#83710),.PCURVE_S1.); -#83699 = LINE('',#83700,#83701); -#83700 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#83701 = VECTOR('',#83702,1.); -#83702 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83703 = PCURVE('',#78416,#83704); -#83704 = DEFINITIONAL_REPRESENTATION('',(#83705),#83709); -#83705 = LINE('',#83706,#83707); -#83706 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83707 = VECTOR('',#83708,1.); -#83708 = DIRECTION('',(1.,0.E+000)); -#83709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83710 = PCURVE('',#83711,#83716); -#83711 = CYLINDRICAL_SURFACE('',#83712,0.2); -#83712 = AXIS2_PLACEMENT_3D('',#83713,#83714,#83715); -#83713 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#83714 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83715 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83716 = DEFINITIONAL_REPRESENTATION('',(#83717),#83720); -#83717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83718,#83719),.UNSPECIFIED., +#86048 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#86049 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#86050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86051 = ORIENTED_EDGE('',*,*,#85481,.T.); +#86052 = ADVANCED_FACE('',(#86053),#85217,.T.); +#86053 = FACE_BOUND('',#86054,.T.); +#86054 = EDGE_LOOP('',(#86055,#86056,#86057,#86058)); +#86055 = ORIENTED_EDGE('',*,*,#86032,.T.); +#86056 = ORIENTED_EDGE('',*,*,#85583,.F.); +#86057 = ORIENTED_EDGE('',*,*,#85201,.F.); +#86058 = ORIENTED_EDGE('',*,*,#85509,.T.); +#86059 = ADVANCED_FACE('',(#86060),#80808,.T.); +#86060 = FACE_BOUND('',#86061,.T.); +#86061 = EDGE_LOOP('',(#86062,#86063,#86086,#86113)); +#86062 = ORIENTED_EDGE('',*,*,#80792,.F.); +#86063 = ORIENTED_EDGE('',*,*,#86064,.F.); +#86064 = EDGE_CURVE('',#86065,#80765,#86067,.T.); +#86065 = VERTEX_POINT('',#86066); +#86066 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); +#86067 = SURFACE_CURVE('',#86068,(#86072,#86079),.PCURVE_S1.); +#86068 = LINE('',#86069,#86070); +#86069 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); +#86070 = VECTOR('',#86071,1.); +#86071 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86072 = PCURVE('',#80808,#86073); +#86073 = DEFINITIONAL_REPRESENTATION('',(#86074),#86078); +#86074 = LINE('',#86075,#86076); +#86075 = CARTESIAN_POINT('',(0.4,0.E+000)); +#86076 = VECTOR('',#86077,1.); +#86077 = DIRECTION('',(0.E+000,-1.)); +#86078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86079 = PCURVE('',#80780,#86080); +#86080 = DEFINITIONAL_REPRESENTATION('',(#86081),#86085); +#86081 = LINE('',#86082,#86083); +#86082 = CARTESIAN_POINT('',(0.55,-0.290089238914)); +#86083 = VECTOR('',#86084,1.); +#86084 = DIRECTION('',(0.E+000,-1.)); +#86085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86086 = ORIENTED_EDGE('',*,*,#86087,.F.); +#86087 = EDGE_CURVE('',#86088,#86065,#86090,.T.); +#86088 = VERTEX_POINT('',#86089); +#86089 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#86090 = SURFACE_CURVE('',#86091,(#86095,#86102),.PCURVE_S1.); +#86091 = LINE('',#86092,#86093); +#86092 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#86093 = VECTOR('',#86094,1.); +#86094 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86095 = PCURVE('',#80808,#86096); +#86096 = DEFINITIONAL_REPRESENTATION('',(#86097),#86101); +#86097 = LINE('',#86098,#86099); +#86098 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86099 = VECTOR('',#86100,1.); +#86100 = DIRECTION('',(1.,0.E+000)); +#86101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86102 = PCURVE('',#86103,#86108); +#86103 = CYLINDRICAL_SURFACE('',#86104,0.2); +#86104 = AXIS2_PLACEMENT_3D('',#86105,#86106,#86107); +#86105 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#86106 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86107 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86108 = DEFINITIONAL_REPRESENTATION('',(#86109),#86112); +#86109 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86110,#86111),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#83718 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#83719 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#83720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83721 = ORIENTED_EDGE('',*,*,#83722,.T.); -#83722 = EDGE_CURVE('',#83696,#78401,#83723,.T.); -#83723 = SURFACE_CURVE('',#83724,(#83728,#83735),.PCURVE_S1.); -#83724 = LINE('',#83725,#83726); -#83725 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#83726 = VECTOR('',#83727,1.); -#83727 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83728 = PCURVE('',#78416,#83729); -#83729 = DEFINITIONAL_REPRESENTATION('',(#83730),#83734); -#83730 = LINE('',#83731,#83732); -#83731 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83732 = VECTOR('',#83733,1.); -#83733 = DIRECTION('',(0.E+000,-1.)); -#83734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83735 = PCURVE('',#78444,#83736); -#83736 = DEFINITIONAL_REPRESENTATION('',(#83737),#83741); -#83737 = LINE('',#83738,#83739); -#83738 = CARTESIAN_POINT('',(0.55,-0.290089238914)); -#83739 = VECTOR('',#83740,1.); -#83740 = DIRECTION('',(0.E+000,-1.)); -#83741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83742 = ADVANCED_FACE('',(#83743),#78444,.T.); -#83743 = FACE_BOUND('',#83744,.T.); -#83744 = EDGE_LOOP('',(#83745,#83746,#83747,#83774,#83802,#83830,#83858, - #83886,#83914,#83946,#83974,#84002)); -#83745 = ORIENTED_EDGE('',*,*,#78428,.F.); -#83746 = ORIENTED_EDGE('',*,*,#83722,.F.); -#83747 = ORIENTED_EDGE('',*,*,#83748,.F.); -#83748 = EDGE_CURVE('',#83749,#83696,#83751,.T.); -#83749 = VERTEX_POINT('',#83750); -#83750 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); -#83751 = SURFACE_CURVE('',#83752,(#83757,#83768),.PCURVE_S1.); -#83752 = CIRCLE('',#83753,0.2); -#83753 = AXIS2_PLACEMENT_3D('',#83754,#83755,#83756); -#83754 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#83755 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83756 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83757 = PCURVE('',#78444,#83758); -#83758 = DEFINITIONAL_REPRESENTATION('',(#83759),#83767); -#83759 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83760,#83761,#83762,#83763 - ,#83764,#83765,#83766),.UNSPECIFIED.,.T.,.F.) +#86110 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#86111 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#86112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86113 = ORIENTED_EDGE('',*,*,#86114,.T.); +#86114 = EDGE_CURVE('',#86088,#80793,#86115,.T.); +#86115 = SURFACE_CURVE('',#86116,(#86120,#86127),.PCURVE_S1.); +#86116 = LINE('',#86117,#86118); +#86117 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#86118 = VECTOR('',#86119,1.); +#86119 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86120 = PCURVE('',#80808,#86121); +#86121 = DEFINITIONAL_REPRESENTATION('',(#86122),#86126); +#86122 = LINE('',#86123,#86124); +#86123 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86124 = VECTOR('',#86125,1.); +#86125 = DIRECTION('',(0.E+000,-1.)); +#86126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86127 = PCURVE('',#80836,#86128); +#86128 = DEFINITIONAL_REPRESENTATION('',(#86129),#86133); +#86129 = LINE('',#86130,#86131); +#86130 = CARTESIAN_POINT('',(0.55,-0.290089238914)); +#86131 = VECTOR('',#86132,1.); +#86132 = DIRECTION('',(0.E+000,-1.)); +#86133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86134 = ADVANCED_FACE('',(#86135),#80836,.T.); +#86135 = FACE_BOUND('',#86136,.T.); +#86136 = EDGE_LOOP('',(#86137,#86138,#86139,#86166,#86194,#86222,#86250, + #86278,#86306,#86338,#86366,#86394)); +#86137 = ORIENTED_EDGE('',*,*,#80820,.F.); +#86138 = ORIENTED_EDGE('',*,*,#86114,.F.); +#86139 = ORIENTED_EDGE('',*,*,#86140,.F.); +#86140 = EDGE_CURVE('',#86141,#86088,#86143,.T.); +#86141 = VERTEX_POINT('',#86142); +#86142 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); +#86143 = SURFACE_CURVE('',#86144,(#86149,#86160),.PCURVE_S1.); +#86144 = CIRCLE('',#86145,0.2); +#86145 = AXIS2_PLACEMENT_3D('',#86146,#86147,#86148); +#86146 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#86147 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86148 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86149 = PCURVE('',#80836,#86150); +#86150 = DEFINITIONAL_REPRESENTATION('',(#86151),#86159); +#86151 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#86152,#86153,#86154,#86155 + ,#86156,#86157,#86158),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#83760 = CARTESIAN_POINT('',(0.15,-0.290089238914)); -#83761 = CARTESIAN_POINT('',(0.15,5.63209226002E-002)); -#83762 = CARTESIAN_POINT('',(0.45,-0.116884158157)); -#83763 = CARTESIAN_POINT('',(0.75,-0.290089238914)); -#83764 = CARTESIAN_POINT('',(0.45,-0.46329431967)); -#83765 = CARTESIAN_POINT('',(0.15,-0.636499400427)); -#83766 = CARTESIAN_POINT('',(0.15,-0.290089238914)); -#83767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83768 = PCURVE('',#83711,#83769); -#83769 = DEFINITIONAL_REPRESENTATION('',(#83770),#83773); -#83770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83771,#83772),.UNSPECIFIED., +#86152 = CARTESIAN_POINT('',(0.15,-0.290089238914)); +#86153 = CARTESIAN_POINT('',(0.15,5.63209226002E-002)); +#86154 = CARTESIAN_POINT('',(0.45,-0.116884158157)); +#86155 = CARTESIAN_POINT('',(0.75,-0.290089238914)); +#86156 = CARTESIAN_POINT('',(0.45,-0.46329431967)); +#86157 = CARTESIAN_POINT('',(0.15,-0.636499400427)); +#86158 = CARTESIAN_POINT('',(0.15,-0.290089238914)); +#86159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86160 = PCURVE('',#86103,#86161); +#86161 = DEFINITIONAL_REPRESENTATION('',(#86162),#86165); +#86162 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86163,#86164),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#83771 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#83772 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#83773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83774 = ORIENTED_EDGE('',*,*,#83775,.F.); -#83775 = EDGE_CURVE('',#83776,#83749,#83778,.T.); -#83776 = VERTEX_POINT('',#83777); -#83777 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#83778 = SURFACE_CURVE('',#83779,(#83783,#83790),.PCURVE_S1.); -#83779 = LINE('',#83780,#83781); -#83780 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#83781 = VECTOR('',#83782,1.); -#83782 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#83783 = PCURVE('',#78444,#83784); -#83784 = DEFINITIONAL_REPRESENTATION('',(#83785),#83789); -#83785 = LINE('',#83786,#83787); -#83786 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#83787 = VECTOR('',#83788,1.); -#83788 = DIRECTION('',(0.993981062721,-0.109552028512)); -#83789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83790 = PCURVE('',#83791,#83796); -#83791 = PLANE('',#83792); -#83792 = AXIS2_PLACEMENT_3D('',#83793,#83794,#83795); -#83793 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#83794 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#83795 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#83796 = DEFINITIONAL_REPRESENTATION('',(#83797),#83801); -#83797 = LINE('',#83798,#83799); -#83798 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83799 = VECTOR('',#83800,1.); -#83800 = DIRECTION('',(1.,0.E+000)); -#83801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83802 = ORIENTED_EDGE('',*,*,#83803,.F.); -#83803 = EDGE_CURVE('',#83804,#83776,#83806,.T.); -#83804 = VERTEX_POINT('',#83805); -#83805 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); -#83806 = SURFACE_CURVE('',#83807,(#83812,#83819),.PCURVE_S1.); -#83807 = CIRCLE('',#83808,5.E-002); -#83808 = AXIS2_PLACEMENT_3D('',#83809,#83810,#83811); -#83809 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#83810 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#83811 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83812 = PCURVE('',#78444,#83813); -#83813 = DEFINITIONAL_REPRESENTATION('',(#83814),#83818); -#83814 = CIRCLE('',#83815,5.E-002); -#83815 = AXIS2_PLACEMENT_2D('',#83816,#83817); -#83816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83817 = DIRECTION('',(1.,0.E+000)); -#83818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83819 = PCURVE('',#83820,#83825); -#83820 = CYLINDRICAL_SURFACE('',#83821,5.E-002); -#83821 = AXIS2_PLACEMENT_3D('',#83822,#83823,#83824); -#83822 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#83823 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83824 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83825 = DEFINITIONAL_REPRESENTATION('',(#83826),#83829); -#83826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83827,#83828),.UNSPECIFIED., +#86163 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#86164 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#86165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86166 = ORIENTED_EDGE('',*,*,#86167,.F.); +#86167 = EDGE_CURVE('',#86168,#86141,#86170,.T.); +#86168 = VERTEX_POINT('',#86169); +#86169 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#86170 = SURFACE_CURVE('',#86171,(#86175,#86182),.PCURVE_S1.); +#86171 = LINE('',#86172,#86173); +#86172 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#86173 = VECTOR('',#86174,1.); +#86174 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#86175 = PCURVE('',#80836,#86176); +#86176 = DEFINITIONAL_REPRESENTATION('',(#86177),#86181); +#86177 = LINE('',#86178,#86179); +#86178 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#86179 = VECTOR('',#86180,1.); +#86180 = DIRECTION('',(0.993981062721,-0.109552028512)); +#86181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86182 = PCURVE('',#86183,#86188); +#86183 = PLANE('',#86184); +#86184 = AXIS2_PLACEMENT_3D('',#86185,#86186,#86187); +#86185 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#86186 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#86187 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#86188 = DEFINITIONAL_REPRESENTATION('',(#86189),#86193); +#86189 = LINE('',#86190,#86191); +#86190 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86191 = VECTOR('',#86192,1.); +#86192 = DIRECTION('',(1.,0.E+000)); +#86193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86194 = ORIENTED_EDGE('',*,*,#86195,.F.); +#86195 = EDGE_CURVE('',#86196,#86168,#86198,.T.); +#86196 = VERTEX_POINT('',#86197); +#86197 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); +#86198 = SURFACE_CURVE('',#86199,(#86204,#86211),.PCURVE_S1.); +#86199 = CIRCLE('',#86200,5.E-002); +#86200 = AXIS2_PLACEMENT_3D('',#86201,#86202,#86203); +#86201 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#86202 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#86203 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86204 = PCURVE('',#80836,#86205); +#86205 = DEFINITIONAL_REPRESENTATION('',(#86206),#86210); +#86206 = CIRCLE('',#86207,5.E-002); +#86207 = AXIS2_PLACEMENT_2D('',#86208,#86209); +#86208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86209 = DIRECTION('',(1.,0.E+000)); +#86210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86211 = PCURVE('',#86212,#86217); +#86212 = CYLINDRICAL_SURFACE('',#86213,5.E-002); +#86213 = AXIS2_PLACEMENT_3D('',#86214,#86215,#86216); +#86214 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#86215 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86216 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86217 = DEFINITIONAL_REPRESENTATION('',(#86218),#86221); +#86218 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86219,#86220),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#83827 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#83828 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#83829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83830 = ORIENTED_EDGE('',*,*,#83831,.F.); -#83831 = EDGE_CURVE('',#83832,#83804,#83834,.T.); -#83832 = VERTEX_POINT('',#83833); -#83833 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#83834 = SURFACE_CURVE('',#83835,(#83839,#83846),.PCURVE_S1.); -#83835 = LINE('',#83836,#83837); -#83836 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#83837 = VECTOR('',#83838,1.); -#83838 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83839 = PCURVE('',#78444,#83840); -#83840 = DEFINITIONAL_REPRESENTATION('',(#83841),#83845); -#83841 = LINE('',#83842,#83843); -#83842 = CARTESIAN_POINT('',(-5.E-002,0.224702759892)); -#83843 = VECTOR('',#83844,1.); -#83844 = DIRECTION('',(0.E+000,-1.)); -#83845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83846 = PCURVE('',#83847,#83852); -#83847 = PLANE('',#83848); -#83848 = AXIS2_PLACEMENT_3D('',#83849,#83850,#83851); -#83849 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#83850 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83851 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83852 = DEFINITIONAL_REPRESENTATION('',(#83853),#83857); -#83853 = LINE('',#83854,#83855); -#83854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83855 = VECTOR('',#83856,1.); -#83856 = DIRECTION('',(0.E+000,-1.)); -#83857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83858 = ORIENTED_EDGE('',*,*,#83859,.F.); -#83859 = EDGE_CURVE('',#83860,#83832,#83862,.T.); -#83860 = VERTEX_POINT('',#83861); -#83861 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#83862 = SURFACE_CURVE('',#83863,(#83867,#83874),.PCURVE_S1.); -#83863 = LINE('',#83864,#83865); -#83864 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#83865 = VECTOR('',#83866,1.); -#83866 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83867 = PCURVE('',#78444,#83868); -#83868 = DEFINITIONAL_REPRESENTATION('',(#83869),#83873); -#83869 = LINE('',#83870,#83871); -#83870 = CARTESIAN_POINT('',(-0.2,0.224702759892)); -#83871 = VECTOR('',#83872,1.); -#83872 = DIRECTION('',(1.,0.E+000)); -#83873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83874 = PCURVE('',#83875,#83880); -#83875 = PLANE('',#83876); -#83876 = AXIS2_PLACEMENT_3D('',#83877,#83878,#83879); -#83877 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#83878 = DIRECTION('',(0.E+000,1.,0.E+000)); -#83879 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83880 = DEFINITIONAL_REPRESENTATION('',(#83881),#83885); -#83881 = LINE('',#83882,#83883); -#83882 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83883 = VECTOR('',#83884,1.); -#83884 = DIRECTION('',(1.,0.E+000)); -#83885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83886 = ORIENTED_EDGE('',*,*,#83887,.T.); -#83887 = EDGE_CURVE('',#83860,#83888,#83890,.T.); -#83888 = VERTEX_POINT('',#83889); -#83889 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); -#83890 = SURFACE_CURVE('',#83891,(#83895,#83902),.PCURVE_S1.); -#83891 = LINE('',#83892,#83893); -#83892 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#83893 = VECTOR('',#83894,1.); -#83894 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#83895 = PCURVE('',#78444,#83896); -#83896 = DEFINITIONAL_REPRESENTATION('',(#83897),#83901); -#83897 = LINE('',#83898,#83899); -#83898 = CARTESIAN_POINT('',(-0.2,0.224702759892)); -#83899 = VECTOR('',#83900,1.); -#83900 = DIRECTION('',(0.E+000,-1.)); -#83901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83902 = PCURVE('',#83903,#83908); -#83903 = PLANE('',#83904); -#83904 = AXIS2_PLACEMENT_3D('',#83905,#83906,#83907); -#83905 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#83906 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83907 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83908 = DEFINITIONAL_REPRESENTATION('',(#83909),#83913); -#83909 = LINE('',#83910,#83911); -#83910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83911 = VECTOR('',#83912,1.); -#83912 = DIRECTION('',(0.E+000,-1.)); -#83913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83914 = ORIENTED_EDGE('',*,*,#83915,.F.); -#83915 = EDGE_CURVE('',#83916,#83888,#83918,.T.); -#83916 = VERTEX_POINT('',#83917); -#83917 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); -#83918 = SURFACE_CURVE('',#83919,(#83924,#83935),.PCURVE_S1.); -#83919 = CIRCLE('',#83920,0.2); -#83920 = AXIS2_PLACEMENT_3D('',#83921,#83922,#83923); -#83921 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#83922 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83923 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83924 = PCURVE('',#78444,#83925); -#83925 = DEFINITIONAL_REPRESENTATION('',(#83926),#83934); -#83926 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#83927,#83928,#83929,#83930 - ,#83931,#83932,#83933),.UNSPECIFIED.,.F.,.F.) +#86219 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#86220 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#86221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86222 = ORIENTED_EDGE('',*,*,#86223,.F.); +#86223 = EDGE_CURVE('',#86224,#86196,#86226,.T.); +#86224 = VERTEX_POINT('',#86225); +#86225 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#86226 = SURFACE_CURVE('',#86227,(#86231,#86238),.PCURVE_S1.); +#86227 = LINE('',#86228,#86229); +#86228 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#86229 = VECTOR('',#86230,1.); +#86230 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86231 = PCURVE('',#80836,#86232); +#86232 = DEFINITIONAL_REPRESENTATION('',(#86233),#86237); +#86233 = LINE('',#86234,#86235); +#86234 = CARTESIAN_POINT('',(-5.E-002,0.224702759892)); +#86235 = VECTOR('',#86236,1.); +#86236 = DIRECTION('',(0.E+000,-1.)); +#86237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86238 = PCURVE('',#86239,#86244); +#86239 = PLANE('',#86240); +#86240 = AXIS2_PLACEMENT_3D('',#86241,#86242,#86243); +#86241 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#86242 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86243 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86244 = DEFINITIONAL_REPRESENTATION('',(#86245),#86249); +#86245 = LINE('',#86246,#86247); +#86246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86247 = VECTOR('',#86248,1.); +#86248 = DIRECTION('',(0.E+000,-1.)); +#86249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86250 = ORIENTED_EDGE('',*,*,#86251,.F.); +#86251 = EDGE_CURVE('',#86252,#86224,#86254,.T.); +#86252 = VERTEX_POINT('',#86253); +#86253 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86254 = SURFACE_CURVE('',#86255,(#86259,#86266),.PCURVE_S1.); +#86255 = LINE('',#86256,#86257); +#86256 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86257 = VECTOR('',#86258,1.); +#86258 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86259 = PCURVE('',#80836,#86260); +#86260 = DEFINITIONAL_REPRESENTATION('',(#86261),#86265); +#86261 = LINE('',#86262,#86263); +#86262 = CARTESIAN_POINT('',(-0.2,0.224702759892)); +#86263 = VECTOR('',#86264,1.); +#86264 = DIRECTION('',(1.,0.E+000)); +#86265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86266 = PCURVE('',#86267,#86272); +#86267 = PLANE('',#86268); +#86268 = AXIS2_PLACEMENT_3D('',#86269,#86270,#86271); +#86269 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86270 = DIRECTION('',(0.E+000,1.,0.E+000)); +#86271 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86272 = DEFINITIONAL_REPRESENTATION('',(#86273),#86277); +#86273 = LINE('',#86274,#86275); +#86274 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86275 = VECTOR('',#86276,1.); +#86276 = DIRECTION('',(1.,0.E+000)); +#86277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86278 = ORIENTED_EDGE('',*,*,#86279,.T.); +#86279 = EDGE_CURVE('',#86252,#86280,#86282,.T.); +#86280 = VERTEX_POINT('',#86281); +#86281 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); +#86282 = SURFACE_CURVE('',#86283,(#86287,#86294),.PCURVE_S1.); +#86283 = LINE('',#86284,#86285); +#86284 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86285 = VECTOR('',#86286,1.); +#86286 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86287 = PCURVE('',#80836,#86288); +#86288 = DEFINITIONAL_REPRESENTATION('',(#86289),#86293); +#86289 = LINE('',#86290,#86291); +#86290 = CARTESIAN_POINT('',(-0.2,0.224702759892)); +#86291 = VECTOR('',#86292,1.); +#86292 = DIRECTION('',(0.E+000,-1.)); +#86293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86294 = PCURVE('',#86295,#86300); +#86295 = PLANE('',#86296); +#86296 = AXIS2_PLACEMENT_3D('',#86297,#86298,#86299); +#86297 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86298 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86299 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86300 = DEFINITIONAL_REPRESENTATION('',(#86301),#86305); +#86301 = LINE('',#86302,#86303); +#86302 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86303 = VECTOR('',#86304,1.); +#86304 = DIRECTION('',(0.E+000,-1.)); +#86305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86306 = ORIENTED_EDGE('',*,*,#86307,.F.); +#86307 = EDGE_CURVE('',#86308,#86280,#86310,.T.); +#86308 = VERTEX_POINT('',#86309); +#86309 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); +#86310 = SURFACE_CURVE('',#86311,(#86316,#86327),.PCURVE_S1.); +#86311 = CIRCLE('',#86312,0.2); +#86312 = AXIS2_PLACEMENT_3D('',#86313,#86314,#86315); +#86313 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#86314 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86315 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86316 = PCURVE('',#80836,#86317); +#86317 = DEFINITIONAL_REPRESENTATION('',(#86318),#86326); +#86318 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#86319,#86320,#86321,#86322 + ,#86323,#86324,#86325),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#83927 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#83928 = CARTESIAN_POINT('',(-0.2,0.346410161514)); -#83929 = CARTESIAN_POINT('',(1.E-001,0.173205080757)); -#83930 = CARTESIAN_POINT('',(0.4,1.378020961229E-016)); -#83931 = CARTESIAN_POINT('',(0.1,-0.173205080757)); -#83932 = CARTESIAN_POINT('',(-0.2,-0.346410161514)); -#83933 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#83934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83935 = PCURVE('',#83936,#83941); -#83936 = CYLINDRICAL_SURFACE('',#83937,0.2); -#83937 = AXIS2_PLACEMENT_3D('',#83938,#83939,#83940); -#83938 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#83939 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83940 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83941 = DEFINITIONAL_REPRESENTATION('',(#83942),#83945); -#83942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83943,#83944),.UNSPECIFIED., +#86319 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#86320 = CARTESIAN_POINT('',(-0.2,0.346410161514)); +#86321 = CARTESIAN_POINT('',(1.E-001,0.173205080757)); +#86322 = CARTESIAN_POINT('',(0.4,1.378020961229E-016)); +#86323 = CARTESIAN_POINT('',(0.1,-0.173205080757)); +#86324 = CARTESIAN_POINT('',(-0.2,-0.346410161514)); +#86325 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#86326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86327 = PCURVE('',#86328,#86333); +#86328 = CYLINDRICAL_SURFACE('',#86329,0.2); +#86329 = AXIS2_PLACEMENT_3D('',#86330,#86331,#86332); +#86330 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#86331 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86332 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86333 = DEFINITIONAL_REPRESENTATION('',(#86334),#86337); +#86334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86335,#86336),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#83943 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#83944 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#83945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83946 = ORIENTED_EDGE('',*,*,#83947,.F.); -#83947 = EDGE_CURVE('',#83948,#83916,#83950,.T.); -#83948 = VERTEX_POINT('',#83949); -#83949 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#83950 = SURFACE_CURVE('',#83951,(#83955,#83962),.PCURVE_S1.); -#83951 = LINE('',#83952,#83953); -#83952 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#83953 = VECTOR('',#83954,1.); -#83954 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#83955 = PCURVE('',#78444,#83956); -#83956 = DEFINITIONAL_REPRESENTATION('',(#83957),#83961); -#83957 = LINE('',#83958,#83959); -#83958 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#83959 = VECTOR('',#83960,1.); -#83960 = DIRECTION('',(-0.993981062721,0.109552028512)); -#83961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83962 = PCURVE('',#83963,#83968); -#83963 = PLANE('',#83964); -#83964 = AXIS2_PLACEMENT_3D('',#83965,#83966,#83967); -#83965 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#83966 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#83967 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#83968 = DEFINITIONAL_REPRESENTATION('',(#83969),#83973); -#83969 = LINE('',#83970,#83971); -#83970 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#83971 = VECTOR('',#83972,1.); -#83972 = DIRECTION('',(1.,0.E+000)); -#83973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83974 = ORIENTED_EDGE('',*,*,#83975,.F.); -#83975 = EDGE_CURVE('',#83976,#83948,#83978,.T.); -#83976 = VERTEX_POINT('',#83977); -#83977 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#83978 = SURFACE_CURVE('',#83979,(#83984,#83991),.PCURVE_S1.); -#83979 = CIRCLE('',#83980,5.E-002); -#83980 = AXIS2_PLACEMENT_3D('',#83981,#83982,#83983); -#83981 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#83982 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#83983 = DIRECTION('',(0.E+000,0.E+000,1.)); -#83984 = PCURVE('',#78444,#83985); -#83985 = DEFINITIONAL_REPRESENTATION('',(#83986),#83990); -#83986 = CIRCLE('',#83987,5.E-002); -#83987 = AXIS2_PLACEMENT_2D('',#83988,#83989); -#83988 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#83989 = DIRECTION('',(1.,0.E+000)); -#83990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#83991 = PCURVE('',#83992,#83997); -#83992 = CYLINDRICAL_SURFACE('',#83993,5.E-002); -#83993 = AXIS2_PLACEMENT_3D('',#83994,#83995,#83996); -#83994 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#83995 = DIRECTION('',(1.,0.E+000,0.E+000)); -#83996 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#83997 = DEFINITIONAL_REPRESENTATION('',(#83998),#84001); -#83998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#83999,#84000),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#83999 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#84000 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#84001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#86335 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#86336 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#86337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86338 = ORIENTED_EDGE('',*,*,#86339,.F.); +#86339 = EDGE_CURVE('',#86340,#86308,#86342,.T.); +#86340 = VERTEX_POINT('',#86341); +#86341 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#86342 = SURFACE_CURVE('',#86343,(#86347,#86354),.PCURVE_S1.); +#86343 = LINE('',#86344,#86345); +#86344 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#86345 = VECTOR('',#86346,1.); +#86346 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#86347 = PCURVE('',#80836,#86348); +#86348 = DEFINITIONAL_REPRESENTATION('',(#86349),#86353); +#86349 = LINE('',#86350,#86351); +#86350 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#86351 = VECTOR('',#86352,1.); +#86352 = DIRECTION('',(-0.993981062721,0.109552028512)); +#86353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86354 = PCURVE('',#86355,#86360); +#86355 = PLANE('',#86356); +#86356 = AXIS2_PLACEMENT_3D('',#86357,#86358,#86359); +#86357 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#86358 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#86359 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#86360 = DEFINITIONAL_REPRESENTATION('',(#86361),#86365); +#86361 = LINE('',#86362,#86363); +#86362 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86363 = VECTOR('',#86364,1.); +#86364 = DIRECTION('',(1.,0.E+000)); +#86365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86366 = ORIENTED_EDGE('',*,*,#86367,.F.); +#86367 = EDGE_CURVE('',#86368,#86340,#86370,.T.); +#86368 = VERTEX_POINT('',#86369); +#86369 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#86370 = SURFACE_CURVE('',#86371,(#86376,#86383),.PCURVE_S1.); +#86371 = CIRCLE('',#86372,5.E-002); +#86372 = AXIS2_PLACEMENT_3D('',#86373,#86374,#86375); +#86373 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#86374 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#86375 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86376 = PCURVE('',#80836,#86377); +#86377 = DEFINITIONAL_REPRESENTATION('',(#86378),#86382); +#86378 = CIRCLE('',#86379,5.E-002); +#86379 = AXIS2_PLACEMENT_2D('',#86380,#86381); +#86380 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#86381 = DIRECTION('',(1.,0.E+000)); +#86382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#84002 = ORIENTED_EDGE('',*,*,#84003,.T.); -#84003 = EDGE_CURVE('',#83976,#78429,#84004,.T.); -#84004 = SURFACE_CURVE('',#84005,(#84009,#84016),.PCURVE_S1.); -#84005 = LINE('',#84006,#84007); -#84006 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#84007 = VECTOR('',#84008,1.); -#84008 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#84009 = PCURVE('',#78444,#84010); -#84010 = DEFINITIONAL_REPRESENTATION('',(#84011),#84015); -#84011 = LINE('',#84012,#84013); -#84012 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#84013 = VECTOR('',#84014,1.); -#84014 = DIRECTION('',(0.E+000,-1.)); -#84015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84016 = PCURVE('',#79195,#84017); -#84017 = DEFINITIONAL_REPRESENTATION('',(#84018),#84022); -#84018 = LINE('',#84019,#84020); -#84019 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84020 = VECTOR('',#84021,1.); -#84021 = DIRECTION('',(0.E+000,-1.)); -#84022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#86383 = PCURVE('',#86384,#86389); +#86384 = CYLINDRICAL_SURFACE('',#86385,5.E-002); +#86385 = AXIS2_PLACEMENT_3D('',#86386,#86387,#86388); +#86386 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#86387 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86388 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86389 = DEFINITIONAL_REPRESENTATION('',(#86390),#86393); +#86390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86391,#86392),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); +#86391 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#86392 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#86393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#84023 = ADVANCED_FACE('',(#84024),#78388,.F.); -#84024 = FACE_BOUND('',#84025,.T.); -#84025 = EDGE_LOOP('',(#84026,#84027,#84028,#84051,#84074,#84097,#84124, - #84147,#84170,#84193,#84216,#84239)); -#84026 = ORIENTED_EDGE('',*,*,#83672,.T.); -#84027 = ORIENTED_EDGE('',*,*,#78372,.T.); -#84028 = ORIENTED_EDGE('',*,*,#84029,.F.); -#84029 = EDGE_CURVE('',#84030,#78350,#84032,.T.); -#84030 = VERTEX_POINT('',#84031); -#84031 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); -#84032 = SURFACE_CURVE('',#84033,(#84037,#84044),.PCURVE_S1.); -#84033 = LINE('',#84034,#84035); -#84034 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); -#84035 = VECTOR('',#84036,1.); -#84036 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#84037 = PCURVE('',#78388,#84038); -#84038 = DEFINITIONAL_REPRESENTATION('',(#84039),#84043); -#84039 = LINE('',#84040,#84041); -#84040 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#84041 = VECTOR('',#84042,1.); -#84042 = DIRECTION('',(0.E+000,-1.)); -#84043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84044 = PCURVE('',#79195,#84045); -#84045 = DEFINITIONAL_REPRESENTATION('',(#84046),#84050); -#84046 = LINE('',#84047,#84048); -#84047 = CARTESIAN_POINT('',(0.4,0.E+000)); -#84048 = VECTOR('',#84049,1.); -#84049 = DIRECTION('',(0.E+000,-1.)); -#84050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84051 = ORIENTED_EDGE('',*,*,#84052,.T.); -#84052 = EDGE_CURVE('',#84030,#84053,#84055,.T.); -#84053 = VERTEX_POINT('',#84054); -#84054 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); -#84055 = SURFACE_CURVE('',#84056,(#84061,#84068),.PCURVE_S1.); -#84056 = CIRCLE('',#84057,5.E-002); -#84057 = AXIS2_PLACEMENT_3D('',#84058,#84059,#84060); -#84058 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); -#84059 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#84060 = DIRECTION('',(0.E+000,0.E+000,1.)); -#84061 = PCURVE('',#78388,#84062); -#84062 = DEFINITIONAL_REPRESENTATION('',(#84063),#84067); -#84063 = CIRCLE('',#84064,5.E-002); -#84064 = AXIS2_PLACEMENT_2D('',#84065,#84066); -#84065 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#84066 = DIRECTION('',(1.,0.E+000)); -#84067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84068 = PCURVE('',#83992,#84069); -#84069 = DEFINITIONAL_REPRESENTATION('',(#84070),#84073); -#84070 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84071,#84072),.UNSPECIFIED., +#86394 = ORIENTED_EDGE('',*,*,#86395,.T.); +#86395 = EDGE_CURVE('',#86368,#80821,#86396,.T.); +#86396 = SURFACE_CURVE('',#86397,(#86401,#86408),.PCURVE_S1.); +#86397 = LINE('',#86398,#86399); +#86398 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#86399 = VECTOR('',#86400,1.); +#86400 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86401 = PCURVE('',#80836,#86402); +#86402 = DEFINITIONAL_REPRESENTATION('',(#86403),#86407); +#86403 = LINE('',#86404,#86405); +#86404 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#86405 = VECTOR('',#86406,1.); +#86406 = DIRECTION('',(0.E+000,-1.)); +#86407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86408 = PCURVE('',#81587,#86409); +#86409 = DEFINITIONAL_REPRESENTATION('',(#86410),#86414); +#86410 = LINE('',#86411,#86412); +#86411 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86412 = VECTOR('',#86413,1.); +#86413 = DIRECTION('',(0.E+000,-1.)); +#86414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86415 = ADVANCED_FACE('',(#86416),#80780,.F.); +#86416 = FACE_BOUND('',#86417,.T.); +#86417 = EDGE_LOOP('',(#86418,#86419,#86420,#86443,#86466,#86489,#86516, + #86539,#86562,#86585,#86608,#86631)); +#86418 = ORIENTED_EDGE('',*,*,#86064,.T.); +#86419 = ORIENTED_EDGE('',*,*,#80764,.T.); +#86420 = ORIENTED_EDGE('',*,*,#86421,.F.); +#86421 = EDGE_CURVE('',#86422,#80742,#86424,.T.); +#86422 = VERTEX_POINT('',#86423); +#86423 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); +#86424 = SURFACE_CURVE('',#86425,(#86429,#86436),.PCURVE_S1.); +#86425 = LINE('',#86426,#86427); +#86426 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); +#86427 = VECTOR('',#86428,1.); +#86428 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86429 = PCURVE('',#80780,#86430); +#86430 = DEFINITIONAL_REPRESENTATION('',(#86431),#86435); +#86431 = LINE('',#86432,#86433); +#86432 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#86433 = VECTOR('',#86434,1.); +#86434 = DIRECTION('',(0.E+000,-1.)); +#86435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86436 = PCURVE('',#81587,#86437); +#86437 = DEFINITIONAL_REPRESENTATION('',(#86438),#86442); +#86438 = LINE('',#86439,#86440); +#86439 = CARTESIAN_POINT('',(0.4,0.E+000)); +#86440 = VECTOR('',#86441,1.); +#86441 = DIRECTION('',(0.E+000,-1.)); +#86442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86443 = ORIENTED_EDGE('',*,*,#86444,.T.); +#86444 = EDGE_CURVE('',#86422,#86445,#86447,.T.); +#86445 = VERTEX_POINT('',#86446); +#86446 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); +#86447 = SURFACE_CURVE('',#86448,(#86453,#86460),.PCURVE_S1.); +#86448 = CIRCLE('',#86449,5.E-002); +#86449 = AXIS2_PLACEMENT_3D('',#86450,#86451,#86452); +#86450 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); +#86451 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#86452 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86453 = PCURVE('',#80780,#86454); +#86454 = DEFINITIONAL_REPRESENTATION('',(#86455),#86459); +#86455 = CIRCLE('',#86456,5.E-002); +#86456 = AXIS2_PLACEMENT_2D('',#86457,#86458); +#86457 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#86458 = DIRECTION('',(1.,0.E+000)); +#86459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86460 = PCURVE('',#86384,#86461); +#86461 = DEFINITIONAL_REPRESENTATION('',(#86462),#86465); +#86462 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86463,#86464),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.461023972143),.PIECEWISE_BEZIER_KNOTS.); -#84071 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#84072 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#84073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84074 = ORIENTED_EDGE('',*,*,#84075,.T.); -#84075 = EDGE_CURVE('',#84053,#84076,#84078,.T.); -#84076 = VERTEX_POINT('',#84077); -#84077 = CARTESIAN_POINT('',(0.2,0.746501027564,0.178089594298)); -#84078 = SURFACE_CURVE('',#84079,(#84083,#84090),.PCURVE_S1.); -#84079 = LINE('',#84080,#84081); -#84080 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); -#84081 = VECTOR('',#84082,1.); -#84082 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#84083 = PCURVE('',#78388,#84084); -#84084 = DEFINITIONAL_REPRESENTATION('',(#84085),#84089); -#84085 = LINE('',#84086,#84087); -#84086 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#84087 = VECTOR('',#84088,1.); -#84088 = DIRECTION('',(-0.993981062721,0.109552028512)); -#84089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84090 = PCURVE('',#83963,#84091); -#84091 = DEFINITIONAL_REPRESENTATION('',(#84092),#84096); -#84092 = LINE('',#84093,#84094); -#84093 = CARTESIAN_POINT('',(0.E+000,0.4)); -#84094 = VECTOR('',#84095,1.); -#84095 = DIRECTION('',(1.,0.E+000)); -#84096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84097 = ORIENTED_EDGE('',*,*,#84098,.T.); -#84098 = EDGE_CURVE('',#84076,#84099,#84101,.T.); -#84099 = VERTEX_POINT('',#84100); -#84100 = CARTESIAN_POINT('',(0.2,0.945297240108,0.E+000)); -#84101 = SURFACE_CURVE('',#84102,(#84107,#84118),.PCURVE_S1.); -#84102 = CIRCLE('',#84103,0.2); -#84103 = AXIS2_PLACEMENT_3D('',#84104,#84105,#84106); -#84104 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); -#84105 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84106 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#84107 = PCURVE('',#78388,#84108); -#84108 = DEFINITIONAL_REPRESENTATION('',(#84109),#84117); -#84109 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84110,#84111,#84112,#84113 - ,#84114,#84115,#84116),.UNSPECIFIED.,.F.,.F.) +#86463 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#86464 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#86465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86466 = ORIENTED_EDGE('',*,*,#86467,.T.); +#86467 = EDGE_CURVE('',#86445,#86468,#86470,.T.); +#86468 = VERTEX_POINT('',#86469); +#86469 = CARTESIAN_POINT('',(0.2,0.746501027564,0.178089594298)); +#86470 = SURFACE_CURVE('',#86471,(#86475,#86482),.PCURVE_S1.); +#86471 = LINE('',#86472,#86473); +#86472 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); +#86473 = VECTOR('',#86474,1.); +#86474 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#86475 = PCURVE('',#80780,#86476); +#86476 = DEFINITIONAL_REPRESENTATION('',(#86477),#86481); +#86477 = LINE('',#86478,#86479); +#86478 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#86479 = VECTOR('',#86480,1.); +#86480 = DIRECTION('',(-0.993981062721,0.109552028512)); +#86481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86482 = PCURVE('',#86355,#86483); +#86483 = DEFINITIONAL_REPRESENTATION('',(#86484),#86488); +#86484 = LINE('',#86485,#86486); +#86485 = CARTESIAN_POINT('',(0.E+000,0.4)); +#86486 = VECTOR('',#86487,1.); +#86487 = DIRECTION('',(1.,0.E+000)); +#86488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86489 = ORIENTED_EDGE('',*,*,#86490,.T.); +#86490 = EDGE_CURVE('',#86468,#86491,#86493,.T.); +#86491 = VERTEX_POINT('',#86492); +#86492 = CARTESIAN_POINT('',(0.2,0.945297240108,0.E+000)); +#86493 = SURFACE_CURVE('',#86494,(#86499,#86510),.PCURVE_S1.); +#86494 = CIRCLE('',#86495,0.2); +#86495 = AXIS2_PLACEMENT_3D('',#86496,#86497,#86498); +#86496 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); +#86497 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86498 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86499 = PCURVE('',#80780,#86500); +#86500 = DEFINITIONAL_REPRESENTATION('',(#86501),#86509); +#86501 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#86502,#86503,#86504,#86505 + ,#86506,#86507,#86508),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#84110 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#84111 = CARTESIAN_POINT('',(-0.2,0.346410161514)); -#84112 = CARTESIAN_POINT('',(1.E-001,0.173205080757)); -#84113 = CARTESIAN_POINT('',(0.4,1.378020961229E-016)); -#84114 = CARTESIAN_POINT('',(0.1,-0.173205080757)); -#84115 = CARTESIAN_POINT('',(-0.2,-0.346410161514)); -#84116 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#84117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84118 = PCURVE('',#83936,#84119); -#84119 = DEFINITIONAL_REPRESENTATION('',(#84120),#84123); -#84120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84121,#84122),.UNSPECIFIED., +#86502 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#86503 = CARTESIAN_POINT('',(-0.2,0.346410161514)); +#86504 = CARTESIAN_POINT('',(1.E-001,0.173205080757)); +#86505 = CARTESIAN_POINT('',(0.4,1.378020961229E-016)); +#86506 = CARTESIAN_POINT('',(0.1,-0.173205080757)); +#86507 = CARTESIAN_POINT('',(-0.2,-0.346410161514)); +#86508 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#86509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86510 = PCURVE('',#86328,#86511); +#86511 = DEFINITIONAL_REPRESENTATION('',(#86512),#86515); +#86512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86513,#86514),.UNSPECIFIED., .F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#84121 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#84122 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#84123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#86513 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#86514 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#86515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86516 = ORIENTED_EDGE('',*,*,#86517,.F.); +#86517 = EDGE_CURVE('',#86518,#86491,#86520,.T.); +#86518 = VERTEX_POINT('',#86519); +#86519 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#86520 = SURFACE_CURVE('',#86521,(#86525,#86532),.PCURVE_S1.); +#86521 = LINE('',#86522,#86523); +#86522 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#86523 = VECTOR('',#86524,1.); +#86524 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86525 = PCURVE('',#80780,#86526); +#86526 = DEFINITIONAL_REPRESENTATION('',(#86527),#86531); +#86527 = LINE('',#86528,#86529); +#86528 = CARTESIAN_POINT('',(-0.2,0.224702759892)); +#86529 = VECTOR('',#86530,1.); +#86530 = DIRECTION('',(0.E+000,-1.)); +#86531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86532 = PCURVE('',#86295,#86533); +#86533 = DEFINITIONAL_REPRESENTATION('',(#86534),#86538); +#86534 = LINE('',#86535,#86536); +#86535 = CARTESIAN_POINT('',(0.4,0.E+000)); +#86536 = VECTOR('',#86537,1.); +#86537 = DIRECTION('',(0.E+000,-1.)); +#86538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#84124 = ORIENTED_EDGE('',*,*,#84125,.F.); -#84125 = EDGE_CURVE('',#84126,#84099,#84128,.T.); -#84126 = VERTEX_POINT('',#84127); -#84127 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#84128 = SURFACE_CURVE('',#84129,(#84133,#84140),.PCURVE_S1.); -#84129 = LINE('',#84130,#84131); -#84130 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#84131 = VECTOR('',#84132,1.); -#84132 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#84133 = PCURVE('',#78388,#84134); -#84134 = DEFINITIONAL_REPRESENTATION('',(#84135),#84139); -#84135 = LINE('',#84136,#84137); -#84136 = CARTESIAN_POINT('',(-0.2,0.224702759892)); -#84137 = VECTOR('',#84138,1.); -#84138 = DIRECTION('',(0.E+000,-1.)); -#84139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84140 = PCURVE('',#83903,#84141); -#84141 = DEFINITIONAL_REPRESENTATION('',(#84142),#84146); -#84142 = LINE('',#84143,#84144); -#84143 = CARTESIAN_POINT('',(0.4,0.E+000)); -#84144 = VECTOR('',#84145,1.); -#84145 = DIRECTION('',(0.E+000,-1.)); -#84146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84147 = ORIENTED_EDGE('',*,*,#84148,.T.); -#84148 = EDGE_CURVE('',#84126,#84149,#84151,.T.); -#84149 = VERTEX_POINT('',#84150); -#84150 = CARTESIAN_POINT('',(0.2,1.17,0.15)); -#84151 = SURFACE_CURVE('',#84152,(#84156,#84163),.PCURVE_S1.); -#84152 = LINE('',#84153,#84154); -#84153 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#84154 = VECTOR('',#84155,1.); -#84155 = DIRECTION('',(0.E+000,0.E+000,1.)); -#84156 = PCURVE('',#78388,#84157); -#84157 = DEFINITIONAL_REPRESENTATION('',(#84158),#84162); -#84158 = LINE('',#84159,#84160); -#84159 = CARTESIAN_POINT('',(-0.2,0.224702759892)); -#84160 = VECTOR('',#84161,1.); -#84161 = DIRECTION('',(1.,0.E+000)); -#84162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84163 = PCURVE('',#83875,#84164); -#84164 = DEFINITIONAL_REPRESENTATION('',(#84165),#84169); -#84165 = LINE('',#84166,#84167); -#84166 = CARTESIAN_POINT('',(0.E+000,0.4)); -#84167 = VECTOR('',#84168,1.); -#84168 = DIRECTION('',(1.,0.E+000)); -#84169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84170 = ORIENTED_EDGE('',*,*,#84171,.T.); -#84171 = EDGE_CURVE('',#84149,#84172,#84174,.T.); -#84172 = VERTEX_POINT('',#84173); -#84173 = CARTESIAN_POINT('',(0.2,0.945297240108,0.15)); -#84174 = SURFACE_CURVE('',#84175,(#84179,#84186),.PCURVE_S1.); -#84175 = LINE('',#84176,#84177); -#84176 = CARTESIAN_POINT('',(0.2,1.17,0.15)); -#84177 = VECTOR('',#84178,1.); -#84178 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#84179 = PCURVE('',#78388,#84180); -#84180 = DEFINITIONAL_REPRESENTATION('',(#84181),#84185); -#84181 = LINE('',#84182,#84183); -#84182 = CARTESIAN_POINT('',(-5.E-002,0.224702759892)); -#84183 = VECTOR('',#84184,1.); -#84184 = DIRECTION('',(0.E+000,-1.)); -#84185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84186 = PCURVE('',#83847,#84187); -#84187 = DEFINITIONAL_REPRESENTATION('',(#84188),#84192); -#84188 = LINE('',#84189,#84190); -#84189 = CARTESIAN_POINT('',(0.4,0.E+000)); -#84190 = VECTOR('',#84191,1.); -#84191 = DIRECTION('',(0.E+000,-1.)); -#84192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84193 = ORIENTED_EDGE('',*,*,#84194,.T.); -#84194 = EDGE_CURVE('',#84172,#84195,#84197,.T.); -#84195 = VERTEX_POINT('',#84196); -#84196 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); -#84197 = SURFACE_CURVE('',#84198,(#84203,#84210),.PCURVE_S1.); -#84198 = CIRCLE('',#84199,5.E-002); -#84199 = AXIS2_PLACEMENT_3D('',#84200,#84201,#84202); -#84200 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); -#84201 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#84202 = DIRECTION('',(0.E+000,0.E+000,1.)); -#84203 = PCURVE('',#78388,#84204); -#84204 = DEFINITIONAL_REPRESENTATION('',(#84205),#84209); -#84205 = CIRCLE('',#84206,5.E-002); -#84206 = AXIS2_PLACEMENT_2D('',#84207,#84208); -#84207 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84208 = DIRECTION('',(1.,0.E+000)); -#84209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84210 = PCURVE('',#83820,#84211); -#84211 = DEFINITIONAL_REPRESENTATION('',(#84212),#84215); -#84212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84213,#84214),.UNSPECIFIED., +#86539 = ORIENTED_EDGE('',*,*,#86540,.T.); +#86540 = EDGE_CURVE('',#86518,#86541,#86543,.T.); +#86541 = VERTEX_POINT('',#86542); +#86542 = CARTESIAN_POINT('',(0.2,1.17,0.15)); +#86543 = SURFACE_CURVE('',#86544,(#86548,#86555),.PCURVE_S1.); +#86544 = LINE('',#86545,#86546); +#86545 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#86546 = VECTOR('',#86547,1.); +#86547 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86548 = PCURVE('',#80780,#86549); +#86549 = DEFINITIONAL_REPRESENTATION('',(#86550),#86554); +#86550 = LINE('',#86551,#86552); +#86551 = CARTESIAN_POINT('',(-0.2,0.224702759892)); +#86552 = VECTOR('',#86553,1.); +#86553 = DIRECTION('',(1.,0.E+000)); +#86554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86555 = PCURVE('',#86267,#86556); +#86556 = DEFINITIONAL_REPRESENTATION('',(#86557),#86561); +#86557 = LINE('',#86558,#86559); +#86558 = CARTESIAN_POINT('',(0.E+000,0.4)); +#86559 = VECTOR('',#86560,1.); +#86560 = DIRECTION('',(1.,0.E+000)); +#86561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86562 = ORIENTED_EDGE('',*,*,#86563,.T.); +#86563 = EDGE_CURVE('',#86541,#86564,#86566,.T.); +#86564 = VERTEX_POINT('',#86565); +#86565 = CARTESIAN_POINT('',(0.2,0.945297240108,0.15)); +#86566 = SURFACE_CURVE('',#86567,(#86571,#86578),.PCURVE_S1.); +#86567 = LINE('',#86568,#86569); +#86568 = CARTESIAN_POINT('',(0.2,1.17,0.15)); +#86569 = VECTOR('',#86570,1.); +#86570 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#86571 = PCURVE('',#80780,#86572); +#86572 = DEFINITIONAL_REPRESENTATION('',(#86573),#86577); +#86573 = LINE('',#86574,#86575); +#86574 = CARTESIAN_POINT('',(-5.E-002,0.224702759892)); +#86575 = VECTOR('',#86576,1.); +#86576 = DIRECTION('',(0.E+000,-1.)); +#86577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86578 = PCURVE('',#86239,#86579); +#86579 = DEFINITIONAL_REPRESENTATION('',(#86580),#86584); +#86580 = LINE('',#86581,#86582); +#86581 = CARTESIAN_POINT('',(0.4,0.E+000)); +#86582 = VECTOR('',#86583,1.); +#86583 = DIRECTION('',(0.E+000,-1.)); +#86584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86585 = ORIENTED_EDGE('',*,*,#86586,.T.); +#86586 = EDGE_CURVE('',#86564,#86587,#86589,.T.); +#86587 = VERTEX_POINT('',#86588); +#86588 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); +#86589 = SURFACE_CURVE('',#86590,(#86595,#86602),.PCURVE_S1.); +#86590 = CIRCLE('',#86591,5.E-002); +#86591 = AXIS2_PLACEMENT_3D('',#86592,#86593,#86594); +#86592 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); +#86593 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#86594 = DIRECTION('',(0.E+000,0.E+000,1.)); +#86595 = PCURVE('',#80780,#86596); +#86596 = DEFINITIONAL_REPRESENTATION('',(#86597),#86601); +#86597 = CIRCLE('',#86598,5.E-002); +#86598 = AXIS2_PLACEMENT_2D('',#86599,#86600); +#86599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86600 = DIRECTION('',(1.,0.E+000)); +#86601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86602 = PCURVE('',#86212,#86603); +#86603 = DEFINITIONAL_REPRESENTATION('',(#86604),#86607); +#86604 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86605,#86606),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#84213 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#84214 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#84215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84216 = ORIENTED_EDGE('',*,*,#84217,.T.); -#84217 = EDGE_CURVE('',#84195,#84218,#84220,.T.); -#84218 = VERTEX_POINT('',#84219); -#84219 = CARTESIAN_POINT('',(0.2,0.854004213739,0.571910405702)); -#84220 = SURFACE_CURVE('',#84221,(#84225,#84232),.PCURVE_S1.); -#84221 = LINE('',#84222,#84223); -#84222 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); -#84223 = VECTOR('',#84224,1.); -#84224 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#84225 = PCURVE('',#78388,#84226); -#84226 = DEFINITIONAL_REPRESENTATION('',(#84227),#84231); -#84227 = LINE('',#84228,#84229); -#84228 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#84229 = VECTOR('',#84230,1.); -#84230 = DIRECTION('',(0.993981062721,-0.109552028512)); -#84231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84232 = PCURVE('',#83791,#84233); -#84233 = DEFINITIONAL_REPRESENTATION('',(#84234),#84238); -#84234 = LINE('',#84235,#84236); -#84235 = CARTESIAN_POINT('',(0.E+000,0.4)); -#84236 = VECTOR('',#84237,1.); -#84237 = DIRECTION('',(1.,0.E+000)); -#84238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84239 = ORIENTED_EDGE('',*,*,#84240,.T.); -#84240 = EDGE_CURVE('',#84218,#83673,#84241,.T.); -#84241 = SURFACE_CURVE('',#84242,(#84247,#84258),.PCURVE_S1.); -#84242 = CIRCLE('',#84243,0.2); -#84243 = AXIS2_PLACEMENT_3D('',#84244,#84245,#84246); -#84244 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); -#84245 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84246 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#84247 = PCURVE('',#78388,#84248); -#84248 = DEFINITIONAL_REPRESENTATION('',(#84249),#84257); -#84249 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#84250,#84251,#84252,#84253 - ,#84254,#84255,#84256),.UNSPECIFIED.,.T.,.F.) +#86605 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#86606 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#86607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86608 = ORIENTED_EDGE('',*,*,#86609,.T.); +#86609 = EDGE_CURVE('',#86587,#86610,#86612,.T.); +#86610 = VERTEX_POINT('',#86611); +#86611 = CARTESIAN_POINT('',(0.2,0.854004213739,0.571910405702)); +#86612 = SURFACE_CURVE('',#86613,(#86617,#86624),.PCURVE_S1.); +#86613 = LINE('',#86614,#86615); +#86614 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); +#86615 = VECTOR('',#86616,1.); +#86616 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#86617 = PCURVE('',#80780,#86618); +#86618 = DEFINITIONAL_REPRESENTATION('',(#86619),#86623); +#86619 = LINE('',#86620,#86621); +#86620 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#86621 = VECTOR('',#86622,1.); +#86622 = DIRECTION('',(0.993981062721,-0.109552028512)); +#86623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86624 = PCURVE('',#86183,#86625); +#86625 = DEFINITIONAL_REPRESENTATION('',(#86626),#86630); +#86626 = LINE('',#86627,#86628); +#86627 = CARTESIAN_POINT('',(0.E+000,0.4)); +#86628 = VECTOR('',#86629,1.); +#86629 = DIRECTION('',(1.,0.E+000)); +#86630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86631 = ORIENTED_EDGE('',*,*,#86632,.T.); +#86632 = EDGE_CURVE('',#86610,#86065,#86633,.T.); +#86633 = SURFACE_CURVE('',#86634,(#86639,#86650),.PCURVE_S1.); +#86634 = CIRCLE('',#86635,0.2); +#86635 = AXIS2_PLACEMENT_3D('',#86636,#86637,#86638); +#86636 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); +#86637 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86638 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#86639 = PCURVE('',#80780,#86640); +#86640 = DEFINITIONAL_REPRESENTATION('',(#86641),#86649); +#86641 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#86642,#86643,#86644,#86645 + ,#86646,#86647,#86648),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#84250 = CARTESIAN_POINT('',(0.15,-0.290089238914)); -#84251 = CARTESIAN_POINT('',(0.15,5.63209226002E-002)); -#84252 = CARTESIAN_POINT('',(0.45,-0.116884158157)); -#84253 = CARTESIAN_POINT('',(0.75,-0.290089238914)); -#84254 = CARTESIAN_POINT('',(0.45,-0.46329431967)); -#84255 = CARTESIAN_POINT('',(0.15,-0.636499400427)); -#84256 = CARTESIAN_POINT('',(0.15,-0.290089238914)); -#84257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84258 = PCURVE('',#83711,#84259); -#84259 = DEFINITIONAL_REPRESENTATION('',(#84260),#84263); -#84260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84261,#84262),.UNSPECIFIED., +#86642 = CARTESIAN_POINT('',(0.15,-0.290089238914)); +#86643 = CARTESIAN_POINT('',(0.15,5.63209226002E-002)); +#86644 = CARTESIAN_POINT('',(0.45,-0.116884158157)); +#86645 = CARTESIAN_POINT('',(0.75,-0.290089238914)); +#86646 = CARTESIAN_POINT('',(0.45,-0.46329431967)); +#86647 = CARTESIAN_POINT('',(0.15,-0.636499400427)); +#86648 = CARTESIAN_POINT('',(0.15,-0.290089238914)); +#86649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86650 = PCURVE('',#86103,#86651); +#86651 = DEFINITIONAL_REPRESENTATION('',(#86652),#86655); +#86652 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86653,#86654),.UNSPECIFIED., .F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#84261 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#84262 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#84263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84264 = ADVANCED_FACE('',(#84265),#83875,.T.); -#84265 = FACE_BOUND('',#84266,.T.); -#84266 = EDGE_LOOP('',(#84267,#84288,#84289,#84310)); -#84267 = ORIENTED_EDGE('',*,*,#84268,.T.); -#84268 = EDGE_CURVE('',#83832,#84149,#84269,.T.); -#84269 = SURFACE_CURVE('',#84270,(#84274,#84281),.PCURVE_S1.); -#84270 = LINE('',#84271,#84272); -#84271 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#84272 = VECTOR('',#84273,1.); -#84273 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84274 = PCURVE('',#83875,#84275); -#84275 = DEFINITIONAL_REPRESENTATION('',(#84276),#84280); -#84276 = LINE('',#84277,#84278); -#84277 = CARTESIAN_POINT('',(0.15,0.E+000)); -#84278 = VECTOR('',#84279,1.); -#84279 = DIRECTION('',(0.E+000,1.)); -#84280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84281 = PCURVE('',#83847,#84282); -#84282 = DEFINITIONAL_REPRESENTATION('',(#84283),#84287); -#84283 = LINE('',#84284,#84285); -#84284 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84285 = VECTOR('',#84286,1.); -#84286 = DIRECTION('',(1.,0.E+000)); -#84287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84288 = ORIENTED_EDGE('',*,*,#84148,.F.); -#84289 = ORIENTED_EDGE('',*,*,#84290,.F.); -#84290 = EDGE_CURVE('',#83860,#84126,#84291,.T.); -#84291 = SURFACE_CURVE('',#84292,(#84296,#84303),.PCURVE_S1.); -#84292 = LINE('',#84293,#84294); -#84293 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#84294 = VECTOR('',#84295,1.); -#84295 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84296 = PCURVE('',#83875,#84297); -#84297 = DEFINITIONAL_REPRESENTATION('',(#84298),#84302); -#84298 = LINE('',#84299,#84300); -#84299 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84300 = VECTOR('',#84301,1.); -#84301 = DIRECTION('',(0.E+000,1.)); -#84302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84303 = PCURVE('',#83903,#84304); -#84304 = DEFINITIONAL_REPRESENTATION('',(#84305),#84309); -#84305 = LINE('',#84306,#84307); -#84306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84307 = VECTOR('',#84308,1.); -#84308 = DIRECTION('',(1.,0.E+000)); -#84309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84310 = ORIENTED_EDGE('',*,*,#83859,.T.); -#84311 = ADVANCED_FACE('',(#84312),#83903,.F.); -#84312 = FACE_BOUND('',#84313,.T.); -#84313 = EDGE_LOOP('',(#84314,#84315,#84316,#84359)); -#84314 = ORIENTED_EDGE('',*,*,#84290,.T.); -#84315 = ORIENTED_EDGE('',*,*,#84125,.T.); -#84316 = ORIENTED_EDGE('',*,*,#84317,.F.); -#84317 = EDGE_CURVE('',#83888,#84099,#84318,.T.); -#84318 = SURFACE_CURVE('',#84319,(#84323,#84330),.PCURVE_S1.); -#84319 = LINE('',#84320,#84321); -#84320 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); -#84321 = VECTOR('',#84322,1.); -#84322 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84323 = PCURVE('',#83903,#84324); -#84324 = DEFINITIONAL_REPRESENTATION('',(#84325),#84329); -#84325 = LINE('',#84326,#84327); -#84326 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#84327 = VECTOR('',#84328,1.); -#84328 = DIRECTION('',(1.,0.E+000)); -#84329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#86653 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#86654 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#86655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#84330 = PCURVE('',#83936,#84331); -#84331 = DEFINITIONAL_REPRESENTATION('',(#84332),#84358); -#84332 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84333,#84334,#84335,#84336, - #84337,#84338,#84339,#84340,#84341,#84342,#84343,#84344,#84345, - #84346,#84347,#84348,#84349,#84350,#84351,#84352,#84353,#84354, - #84355,#84356,#84357),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#86656 = ADVANCED_FACE('',(#86657),#86267,.T.); +#86657 = FACE_BOUND('',#86658,.T.); +#86658 = EDGE_LOOP('',(#86659,#86680,#86681,#86702)); +#86659 = ORIENTED_EDGE('',*,*,#86660,.T.); +#86660 = EDGE_CURVE('',#86224,#86541,#86661,.T.); +#86661 = SURFACE_CURVE('',#86662,(#86666,#86673),.PCURVE_S1.); +#86662 = LINE('',#86663,#86664); +#86663 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#86664 = VECTOR('',#86665,1.); +#86665 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86666 = PCURVE('',#86267,#86667); +#86667 = DEFINITIONAL_REPRESENTATION('',(#86668),#86672); +#86668 = LINE('',#86669,#86670); +#86669 = CARTESIAN_POINT('',(0.15,0.E+000)); +#86670 = VECTOR('',#86671,1.); +#86671 = DIRECTION('',(0.E+000,1.)); +#86672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86673 = PCURVE('',#86239,#86674); +#86674 = DEFINITIONAL_REPRESENTATION('',(#86675),#86679); +#86675 = LINE('',#86676,#86677); +#86676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86677 = VECTOR('',#86678,1.); +#86678 = DIRECTION('',(1.,0.E+000)); +#86679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86680 = ORIENTED_EDGE('',*,*,#86540,.F.); +#86681 = ORIENTED_EDGE('',*,*,#86682,.F.); +#86682 = EDGE_CURVE('',#86252,#86518,#86683,.T.); +#86683 = SURFACE_CURVE('',#86684,(#86688,#86695),.PCURVE_S1.); +#86684 = LINE('',#86685,#86686); +#86685 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#86686 = VECTOR('',#86687,1.); +#86687 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86688 = PCURVE('',#86267,#86689); +#86689 = DEFINITIONAL_REPRESENTATION('',(#86690),#86694); +#86690 = LINE('',#86691,#86692); +#86691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86692 = VECTOR('',#86693,1.); +#86693 = DIRECTION('',(0.E+000,1.)); +#86694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86695 = PCURVE('',#86295,#86696); +#86696 = DEFINITIONAL_REPRESENTATION('',(#86697),#86701); +#86697 = LINE('',#86698,#86699); +#86698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86699 = VECTOR('',#86700,1.); +#86700 = DIRECTION('',(1.,0.E+000)); +#86701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86702 = ORIENTED_EDGE('',*,*,#86251,.T.); +#86703 = ADVANCED_FACE('',(#86704),#86295,.F.); +#86704 = FACE_BOUND('',#86705,.T.); +#86705 = EDGE_LOOP('',(#86706,#86707,#86708,#86751)); +#86706 = ORIENTED_EDGE('',*,*,#86682,.T.); +#86707 = ORIENTED_EDGE('',*,*,#86517,.T.); +#86708 = ORIENTED_EDGE('',*,*,#86709,.F.); +#86709 = EDGE_CURVE('',#86280,#86491,#86710,.T.); +#86710 = SURFACE_CURVE('',#86711,(#86715,#86722),.PCURVE_S1.); +#86711 = LINE('',#86712,#86713); +#86712 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); +#86713 = VECTOR('',#86714,1.); +#86714 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86715 = PCURVE('',#86295,#86716); +#86716 = DEFINITIONAL_REPRESENTATION('',(#86717),#86721); +#86717 = LINE('',#86718,#86719); +#86718 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#86719 = VECTOR('',#86720,1.); +#86720 = DIRECTION('',(1.,0.E+000)); +#86721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86722 = PCURVE('',#86328,#86723); +#86723 = DEFINITIONAL_REPRESENTATION('',(#86724),#86750); +#86724 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#86725,#86726,#86727,#86728, + #86729,#86730,#86731,#86732,#86733,#86734,#86735,#86736,#86737, + #86738,#86739,#86740,#86741,#86742,#86743,#86744,#86745,#86746, + #86747,#86748,#86749),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -104540,215 +107529,215 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#84333 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#84334 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#84335 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#84336 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#84337 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#84338 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#84339 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#84340 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#84341 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#84342 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#84343 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#84344 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#84345 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#84346 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#84347 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#84348 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#84349 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#84350 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#84351 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#84352 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#84353 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#84354 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#84355 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#84356 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#84357 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#84358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84359 = ORIENTED_EDGE('',*,*,#83887,.F.); -#84360 = ADVANCED_FACE('',(#84361),#83936,.T.); -#84361 = FACE_BOUND('',#84362,.T.); -#84362 = EDGE_LOOP('',(#84363,#84364,#84365,#84385)); -#84363 = ORIENTED_EDGE('',*,*,#84317,.T.); -#84364 = ORIENTED_EDGE('',*,*,#84098,.F.); -#84365 = ORIENTED_EDGE('',*,*,#84366,.F.); -#84366 = EDGE_CURVE('',#83916,#84076,#84367,.T.); -#84367 = SURFACE_CURVE('',#84368,(#84372,#84378),.PCURVE_S1.); -#84368 = LINE('',#84369,#84370); -#84369 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); -#84370 = VECTOR('',#84371,1.); -#84371 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84372 = PCURVE('',#83936,#84373); -#84373 = DEFINITIONAL_REPRESENTATION('',(#84374),#84377); -#84374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84375,#84376),.UNSPECIFIED., +#86725 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#86726 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#86727 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#86728 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#86729 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#86730 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#86731 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#86732 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#86733 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#86734 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#86735 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#86736 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#86737 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#86738 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#86739 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#86740 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#86741 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#86742 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#86743 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#86744 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#86745 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#86746 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#86747 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#86748 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#86749 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#86750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86751 = ORIENTED_EDGE('',*,*,#86279,.F.); +#86752 = ADVANCED_FACE('',(#86753),#86328,.T.); +#86753 = FACE_BOUND('',#86754,.T.); +#86754 = EDGE_LOOP('',(#86755,#86756,#86757,#86777)); +#86755 = ORIENTED_EDGE('',*,*,#86709,.T.); +#86756 = ORIENTED_EDGE('',*,*,#86490,.F.); +#86757 = ORIENTED_EDGE('',*,*,#86758,.F.); +#86758 = EDGE_CURVE('',#86308,#86468,#86759,.T.); +#86759 = SURFACE_CURVE('',#86760,(#86764,#86770),.PCURVE_S1.); +#86760 = LINE('',#86761,#86762); +#86761 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); +#86762 = VECTOR('',#86763,1.); +#86763 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86764 = PCURVE('',#86328,#86765); +#86765 = DEFINITIONAL_REPRESENTATION('',(#86766),#86769); +#86766 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86767,#86768),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#84375 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#84376 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#84377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84378 = PCURVE('',#83963,#84379); -#84379 = DEFINITIONAL_REPRESENTATION('',(#84380),#84384); -#84380 = LINE('',#84381,#84382); -#84381 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#84382 = VECTOR('',#84383,1.); -#84383 = DIRECTION('',(0.E+000,1.)); -#84384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84385 = ORIENTED_EDGE('',*,*,#83915,.T.); -#84386 = ADVANCED_FACE('',(#84387),#83963,.T.); -#84387 = FACE_BOUND('',#84388,.T.); -#84388 = EDGE_LOOP('',(#84389,#84390,#84391,#84411)); -#84389 = ORIENTED_EDGE('',*,*,#84366,.T.); -#84390 = ORIENTED_EDGE('',*,*,#84075,.F.); -#84391 = ORIENTED_EDGE('',*,*,#84392,.F.); -#84392 = EDGE_CURVE('',#83948,#84053,#84393,.T.); -#84393 = SURFACE_CURVE('',#84394,(#84398,#84405),.PCURVE_S1.); -#84394 = LINE('',#84395,#84396); -#84395 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#84396 = VECTOR('',#84397,1.); -#84397 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84398 = PCURVE('',#83963,#84399); -#84399 = DEFINITIONAL_REPRESENTATION('',(#84400),#84404); -#84400 = LINE('',#84401,#84402); -#84401 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84402 = VECTOR('',#84403,1.); -#84403 = DIRECTION('',(0.E+000,1.)); -#84404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84405 = PCURVE('',#83992,#84406); -#84406 = DEFINITIONAL_REPRESENTATION('',(#84407),#84410); -#84407 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84408,#84409),.UNSPECIFIED., +#86767 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#86768 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#86769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86770 = PCURVE('',#86355,#86771); +#86771 = DEFINITIONAL_REPRESENTATION('',(#86772),#86776); +#86772 = LINE('',#86773,#86774); +#86773 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#86774 = VECTOR('',#86775,1.); +#86775 = DIRECTION('',(0.E+000,1.)); +#86776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86777 = ORIENTED_EDGE('',*,*,#86307,.T.); +#86778 = ADVANCED_FACE('',(#86779),#86355,.T.); +#86779 = FACE_BOUND('',#86780,.T.); +#86780 = EDGE_LOOP('',(#86781,#86782,#86783,#86803)); +#86781 = ORIENTED_EDGE('',*,*,#86758,.T.); +#86782 = ORIENTED_EDGE('',*,*,#86467,.F.); +#86783 = ORIENTED_EDGE('',*,*,#86784,.F.); +#86784 = EDGE_CURVE('',#86340,#86445,#86785,.T.); +#86785 = SURFACE_CURVE('',#86786,(#86790,#86797),.PCURVE_S1.); +#86786 = LINE('',#86787,#86788); +#86787 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#86788 = VECTOR('',#86789,1.); +#86789 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86790 = PCURVE('',#86355,#86791); +#86791 = DEFINITIONAL_REPRESENTATION('',(#86792),#86796); +#86792 = LINE('',#86793,#86794); +#86793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86794 = VECTOR('',#86795,1.); +#86795 = DIRECTION('',(0.E+000,1.)); +#86796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86797 = PCURVE('',#86384,#86798); +#86798 = DEFINITIONAL_REPRESENTATION('',(#86799),#86802); +#86799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86800,#86801),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#84408 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#84409 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#84410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84411 = ORIENTED_EDGE('',*,*,#83947,.T.); -#84412 = ADVANCED_FACE('',(#84413),#83992,.F.); -#84413 = FACE_BOUND('',#84414,.F.); -#84414 = EDGE_LOOP('',(#84415,#84416,#84417,#84437)); -#84415 = ORIENTED_EDGE('',*,*,#84392,.F.); -#84416 = ORIENTED_EDGE('',*,*,#83975,.F.); -#84417 = ORIENTED_EDGE('',*,*,#84418,.T.); -#84418 = EDGE_CURVE('',#83976,#84030,#84419,.T.); -#84419 = SURFACE_CURVE('',#84420,(#84424,#84430),.PCURVE_S1.); -#84420 = LINE('',#84421,#84422); -#84421 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#84422 = VECTOR('',#84423,1.); -#84423 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84424 = PCURVE('',#83992,#84425); -#84425 = DEFINITIONAL_REPRESENTATION('',(#84426),#84429); -#84426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84427,#84428),.UNSPECIFIED., +#86800 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#86801 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#86802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86803 = ORIENTED_EDGE('',*,*,#86339,.T.); +#86804 = ADVANCED_FACE('',(#86805),#86384,.F.); +#86805 = FACE_BOUND('',#86806,.F.); +#86806 = EDGE_LOOP('',(#86807,#86808,#86809,#86829)); +#86807 = ORIENTED_EDGE('',*,*,#86784,.F.); +#86808 = ORIENTED_EDGE('',*,*,#86367,.F.); +#86809 = ORIENTED_EDGE('',*,*,#86810,.T.); +#86810 = EDGE_CURVE('',#86368,#86422,#86811,.T.); +#86811 = SURFACE_CURVE('',#86812,(#86816,#86822),.PCURVE_S1.); +#86812 = LINE('',#86813,#86814); +#86813 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#86814 = VECTOR('',#86815,1.); +#86815 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86816 = PCURVE('',#86384,#86817); +#86817 = DEFINITIONAL_REPRESENTATION('',(#86818),#86821); +#86818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86819,#86820),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#84427 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#84428 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#84429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84430 = PCURVE('',#79195,#84431); -#84431 = DEFINITIONAL_REPRESENTATION('',(#84432),#84436); -#84432 = LINE('',#84433,#84434); -#84433 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84434 = VECTOR('',#84435,1.); -#84435 = DIRECTION('',(1.,0.E+000)); -#84436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84437 = ORIENTED_EDGE('',*,*,#84052,.T.); -#84438 = ADVANCED_FACE('',(#84439),#79195,.F.); -#84439 = FACE_BOUND('',#84440,.T.); -#84440 = EDGE_LOOP('',(#84441,#84442,#84443,#84444)); -#84441 = ORIENTED_EDGE('',*,*,#79181,.T.); -#84442 = ORIENTED_EDGE('',*,*,#84003,.F.); -#84443 = ORIENTED_EDGE('',*,*,#84418,.T.); -#84444 = ORIENTED_EDGE('',*,*,#84029,.T.); -#84445 = ADVANCED_FACE('',(#84446),#83711,.T.); -#84446 = FACE_BOUND('',#84447,.T.); -#84447 = EDGE_LOOP('',(#84448,#84449,#84450,#84470)); -#84448 = ORIENTED_EDGE('',*,*,#83695,.T.); -#84449 = ORIENTED_EDGE('',*,*,#84240,.F.); -#84450 = ORIENTED_EDGE('',*,*,#84451,.F.); -#84451 = EDGE_CURVE('',#83749,#84218,#84452,.T.); -#84452 = SURFACE_CURVE('',#84453,(#84457,#84463),.PCURVE_S1.); -#84453 = LINE('',#84454,#84455); -#84454 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); -#84455 = VECTOR('',#84456,1.); -#84456 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84457 = PCURVE('',#83711,#84458); -#84458 = DEFINITIONAL_REPRESENTATION('',(#84459),#84462); -#84459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84460,#84461),.UNSPECIFIED., +#86819 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#86820 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#86821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86822 = PCURVE('',#81587,#86823); +#86823 = DEFINITIONAL_REPRESENTATION('',(#86824),#86828); +#86824 = LINE('',#86825,#86826); +#86825 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86826 = VECTOR('',#86827,1.); +#86827 = DIRECTION('',(1.,0.E+000)); +#86828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86829 = ORIENTED_EDGE('',*,*,#86444,.T.); +#86830 = ADVANCED_FACE('',(#86831),#81587,.F.); +#86831 = FACE_BOUND('',#86832,.T.); +#86832 = EDGE_LOOP('',(#86833,#86834,#86835,#86836)); +#86833 = ORIENTED_EDGE('',*,*,#81573,.T.); +#86834 = ORIENTED_EDGE('',*,*,#86395,.F.); +#86835 = ORIENTED_EDGE('',*,*,#86810,.T.); +#86836 = ORIENTED_EDGE('',*,*,#86421,.T.); +#86837 = ADVANCED_FACE('',(#86838),#86103,.T.); +#86838 = FACE_BOUND('',#86839,.T.); +#86839 = EDGE_LOOP('',(#86840,#86841,#86842,#86862)); +#86840 = ORIENTED_EDGE('',*,*,#86087,.T.); +#86841 = ORIENTED_EDGE('',*,*,#86632,.F.); +#86842 = ORIENTED_EDGE('',*,*,#86843,.F.); +#86843 = EDGE_CURVE('',#86141,#86610,#86844,.T.); +#86844 = SURFACE_CURVE('',#86845,(#86849,#86855),.PCURVE_S1.); +#86845 = LINE('',#86846,#86847); +#86846 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); +#86847 = VECTOR('',#86848,1.); +#86848 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86849 = PCURVE('',#86103,#86850); +#86850 = DEFINITIONAL_REPRESENTATION('',(#86851),#86854); +#86851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86852,#86853),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#84460 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#84461 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#84462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84463 = PCURVE('',#83791,#84464); -#84464 = DEFINITIONAL_REPRESENTATION('',(#84465),#84469); -#84465 = LINE('',#84466,#84467); -#84466 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#84467 = VECTOR('',#84468,1.); -#84468 = DIRECTION('',(0.E+000,1.)); -#84469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84470 = ORIENTED_EDGE('',*,*,#83748,.T.); -#84471 = ADVANCED_FACE('',(#84472),#83791,.T.); -#84472 = FACE_BOUND('',#84473,.T.); -#84473 = EDGE_LOOP('',(#84474,#84475,#84476,#84496)); -#84474 = ORIENTED_EDGE('',*,*,#84451,.T.); -#84475 = ORIENTED_EDGE('',*,*,#84217,.F.); -#84476 = ORIENTED_EDGE('',*,*,#84477,.F.); -#84477 = EDGE_CURVE('',#83776,#84195,#84478,.T.); -#84478 = SURFACE_CURVE('',#84479,(#84483,#84490),.PCURVE_S1.); -#84479 = LINE('',#84480,#84481); -#84480 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#84481 = VECTOR('',#84482,1.); -#84482 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84483 = PCURVE('',#83791,#84484); -#84484 = DEFINITIONAL_REPRESENTATION('',(#84485),#84489); -#84485 = LINE('',#84486,#84487); -#84486 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#84487 = VECTOR('',#84488,1.); -#84488 = DIRECTION('',(0.E+000,1.)); -#84489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84490 = PCURVE('',#83820,#84491); -#84491 = DEFINITIONAL_REPRESENTATION('',(#84492),#84495); -#84492 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#84493,#84494),.UNSPECIFIED., +#86852 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#86853 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#86854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86855 = PCURVE('',#86183,#86856); +#86856 = DEFINITIONAL_REPRESENTATION('',(#86857),#86861); +#86857 = LINE('',#86858,#86859); +#86858 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#86859 = VECTOR('',#86860,1.); +#86860 = DIRECTION('',(0.E+000,1.)); +#86861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86862 = ORIENTED_EDGE('',*,*,#86140,.T.); +#86863 = ADVANCED_FACE('',(#86864),#86183,.T.); +#86864 = FACE_BOUND('',#86865,.T.); +#86865 = EDGE_LOOP('',(#86866,#86867,#86868,#86888)); +#86866 = ORIENTED_EDGE('',*,*,#86843,.T.); +#86867 = ORIENTED_EDGE('',*,*,#86609,.F.); +#86868 = ORIENTED_EDGE('',*,*,#86869,.F.); +#86869 = EDGE_CURVE('',#86168,#86587,#86870,.T.); +#86870 = SURFACE_CURVE('',#86871,(#86875,#86882),.PCURVE_S1.); +#86871 = LINE('',#86872,#86873); +#86872 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#86873 = VECTOR('',#86874,1.); +#86874 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86875 = PCURVE('',#86183,#86876); +#86876 = DEFINITIONAL_REPRESENTATION('',(#86877),#86881); +#86877 = LINE('',#86878,#86879); +#86878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#86879 = VECTOR('',#86880,1.); +#86880 = DIRECTION('',(0.E+000,1.)); +#86881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86882 = PCURVE('',#86212,#86883); +#86883 = DEFINITIONAL_REPRESENTATION('',(#86884),#86887); +#86884 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86885,#86886),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#84493 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#84494 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#84495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84496 = ORIENTED_EDGE('',*,*,#83775,.T.); -#84497 = ADVANCED_FACE('',(#84498),#83820,.F.); -#84498 = FACE_BOUND('',#84499,.F.); -#84499 = EDGE_LOOP('',(#84500,#84501,#84502,#84545)); -#84500 = ORIENTED_EDGE('',*,*,#84477,.F.); -#84501 = ORIENTED_EDGE('',*,*,#83803,.F.); -#84502 = ORIENTED_EDGE('',*,*,#84503,.T.); -#84503 = EDGE_CURVE('',#83804,#84172,#84504,.T.); -#84504 = SURFACE_CURVE('',#84505,(#84509,#84538),.PCURVE_S1.); -#84505 = LINE('',#84506,#84507); -#84506 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); -#84507 = VECTOR('',#84508,1.); -#84508 = DIRECTION('',(1.,0.E+000,0.E+000)); -#84509 = PCURVE('',#83820,#84510); -#84510 = DEFINITIONAL_REPRESENTATION('',(#84511),#84537); -#84511 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84512,#84513,#84514,#84515, - #84516,#84517,#84518,#84519,#84520,#84521,#84522,#84523,#84524, - #84525,#84526,#84527,#84528,#84529,#84530,#84531,#84532,#84533, - #84534,#84535,#84536),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#86885 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#86886 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#86887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86888 = ORIENTED_EDGE('',*,*,#86167,.T.); +#86889 = ADVANCED_FACE('',(#86890),#86212,.F.); +#86890 = FACE_BOUND('',#86891,.F.); +#86891 = EDGE_LOOP('',(#86892,#86893,#86894,#86937)); +#86892 = ORIENTED_EDGE('',*,*,#86869,.F.); +#86893 = ORIENTED_EDGE('',*,*,#86195,.F.); +#86894 = ORIENTED_EDGE('',*,*,#86895,.T.); +#86895 = EDGE_CURVE('',#86196,#86564,#86896,.T.); +#86896 = SURFACE_CURVE('',#86897,(#86901,#86930),.PCURVE_S1.); +#86897 = LINE('',#86898,#86899); +#86898 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); +#86899 = VECTOR('',#86900,1.); +#86900 = DIRECTION('',(1.,0.E+000,0.E+000)); +#86901 = PCURVE('',#86212,#86902); +#86902 = DEFINITIONAL_REPRESENTATION('',(#86903),#86929); +#86903 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#86904,#86905,#86906,#86907, + #86908,#86909,#86910,#86911,#86912,#86913,#86914,#86915,#86916, + #86917,#86918,#86919,#86920,#86921,#86922,#86923,#86924,#86925, + #86926,#86927,#86928),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,1.818181818182E-002, 3.636363636364E-002,5.454545454545E-002,7.272727272727E-002, 9.090909090909E-002,0.109090909091,0.127272727273,0.145454545455, @@ -104756,77 +107745,77 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.254545454545,0.272727272727,0.290909090909,0.309090909091, 0.327272727273,0.345454545455,0.363636363636,0.381818181818,0.4), .QUASI_UNIFORM_KNOTS.); -#84512 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#84513 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#84514 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#84515 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#84516 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#84517 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#84518 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#84519 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#84520 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#84521 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#84522 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#84523 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#84524 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#84525 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#84526 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#84527 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#84528 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#84529 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#84530 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#84531 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#84532 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#84533 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#84534 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#84535 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#84536 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#84537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84538 = PCURVE('',#83847,#84539); -#84539 = DEFINITIONAL_REPRESENTATION('',(#84540),#84544); -#84540 = LINE('',#84541,#84542); -#84541 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#84542 = VECTOR('',#84543,1.); -#84543 = DIRECTION('',(1.,0.E+000)); -#84544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84545 = ORIENTED_EDGE('',*,*,#84194,.T.); -#84546 = ADVANCED_FACE('',(#84547),#83847,.T.); -#84547 = FACE_BOUND('',#84548,.T.); -#84548 = EDGE_LOOP('',(#84549,#84550,#84551,#84552)); -#84549 = ORIENTED_EDGE('',*,*,#84503,.T.); -#84550 = ORIENTED_EDGE('',*,*,#84171,.F.); -#84551 = ORIENTED_EDGE('',*,*,#84268,.F.); -#84552 = ORIENTED_EDGE('',*,*,#83831,.T.); -#84553 = ADVANCED_FACE('',(#84554),#76713,.T.); -#84554 = FACE_BOUND('',#84555,.T.); -#84555 = EDGE_LOOP('',(#84556,#84557,#84623,#84624,#84625)); -#84556 = ORIENTED_EDGE('',*,*,#77832,.F.); -#84557 = ORIENTED_EDGE('',*,*,#84558,.T.); -#84558 = EDGE_CURVE('',#77811,#76656,#84559,.T.); -#84559 = SURFACE_CURVE('',#84560,(#84565,#84594),.PCURVE_S1.); -#84560 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84561,#84562,#84563,#84564 +#86904 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#86905 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#86906 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#86907 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#86908 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#86909 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#86910 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#86911 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#86912 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#86913 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#86914 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#86915 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#86916 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#86917 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#86918 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#86919 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#86920 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#86921 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#86922 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#86923 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#86924 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#86925 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#86926 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#86927 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#86928 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#86929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86930 = PCURVE('',#86239,#86931); +#86931 = DEFINITIONAL_REPRESENTATION('',(#86932),#86936); +#86932 = LINE('',#86933,#86934); +#86933 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#86934 = VECTOR('',#86935,1.); +#86935 = DIRECTION('',(1.,0.E+000)); +#86936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86937 = ORIENTED_EDGE('',*,*,#86586,.T.); +#86938 = ADVANCED_FACE('',(#86939),#86239,.T.); +#86939 = FACE_BOUND('',#86940,.T.); +#86940 = EDGE_LOOP('',(#86941,#86942,#86943,#86944)); +#86941 = ORIENTED_EDGE('',*,*,#86895,.T.); +#86942 = ORIENTED_EDGE('',*,*,#86563,.F.); +#86943 = ORIENTED_EDGE('',*,*,#86660,.F.); +#86944 = ORIENTED_EDGE('',*,*,#86223,.T.); +#86945 = ADVANCED_FACE('',(#86946),#79105,.T.); +#86946 = FACE_BOUND('',#86947,.T.); +#86947 = EDGE_LOOP('',(#86948,#86949,#87015,#87016,#87017)); +#86948 = ORIENTED_EDGE('',*,*,#80224,.F.); +#86949 = ORIENTED_EDGE('',*,*,#86950,.T.); +#86950 = EDGE_CURVE('',#80203,#79048,#86951,.T.); +#86951 = SURFACE_CURVE('',#86952,(#86957,#86986),.PCURVE_S1.); +#86952 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#86953,#86954,#86955,#86956 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#84561 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 +#86953 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943,0.962940952255 )); -#84562 = CARTESIAN_POINT('',(-1.25680534294,-0.551917855478, +#86954 = CARTESIAN_POINT('',(-1.25680534294,-0.551917855478, 0.966047546673)); -#84563 = CARTESIAN_POINT('',(-1.292375921036,-0.53683376285,0.967717466) +#86955 = CARTESIAN_POINT('',(-1.292375921036,-0.53683376285,0.967717466) ); -#84564 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 +#86956 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943,0.967717466 )); -#84565 = PCURVE('',#76713,#84566); -#84566 = DEFINITIONAL_REPRESENTATION('',(#84567),#84593); -#84567 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84568,#84569,#84570,#84571, - #84572,#84573,#84574,#84575,#84576,#84577,#84578,#84579,#84580, - #84581,#84582,#84583,#84584,#84585,#84586,#84587,#84588,#84589, - #84590,#84591,#84592),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#86957 = PCURVE('',#79105,#86958); +#86958 = DEFINITIONAL_REPRESENTATION('',(#86959),#86985); +#86959 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#86960,#86961,#86962,#86963, + #86964,#86965,#86966,#86967,#86968,#86969,#86970,#86971,#86972, + #86973,#86974,#86975,#86976,#86977,#86978,#86979,#86980,#86981, + #86982,#86983,#86984),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -104834,40 +107823,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#84568 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); -#84569 = CARTESIAN_POINT('',(4.790552085824,-0.424140987131)); -#84570 = CARTESIAN_POINT('',(4.812874135705,-0.423573537911)); -#84571 = CARTESIAN_POINT('',(4.846552114392,-0.422749662917)); -#84572 = CARTESIAN_POINT('',(4.880407630888,-0.421955010917)); -#84573 = CARTESIAN_POINT('',(4.914422492066,-0.421191423422)); -#84574 = CARTESIAN_POINT('',(4.948578027862,-0.420460671856)); -#84575 = CARTESIAN_POINT('',(4.98285506838,-0.419764438636)); -#84576 = CARTESIAN_POINT('',(5.017234026195,-0.419104307248)); -#84577 = CARTESIAN_POINT('',(5.051694955172,-0.418481750684)); -#84578 = CARTESIAN_POINT('',(5.086217619636,-0.41789812127)); -#84579 = CARTESIAN_POINT('',(5.120781564146,-0.417354641276)); -#84580 = CARTESIAN_POINT('',(5.155366185737,-0.416852394634)); -#84581 = CARTESIAN_POINT('',(5.189950807328,-0.416392319824)); -#84582 = CARTESIAN_POINT('',(5.224514751839,-0.415975204048)); -#84583 = CARTESIAN_POINT('',(5.259037416303,-0.415601678753)); -#84584 = CARTESIAN_POINT('',(5.293498345279,-0.41527221657)); -#84585 = CARTESIAN_POINT('',(5.327877303094,-0.414987129667)); -#84586 = CARTESIAN_POINT('',(5.362154343612,-0.414746569643)); -#84587 = CARTESIAN_POINT('',(5.396309879408,-0.414550528448)); -#84588 = CARTESIAN_POINT('',(5.430324740587,-0.414398842232)); -#84589 = CARTESIAN_POINT('',(5.464180257082,-0.414291190685)); -#84590 = CARTESIAN_POINT('',(5.49785823577,-0.414227119403)); -#84591 = CARTESIAN_POINT('',(5.52018028565,-0.414213027833)); -#84592 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); -#84593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84594 = PCURVE('',#76786,#84595); -#84595 = DEFINITIONAL_REPRESENTATION('',(#84596),#84622); -#84596 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84597,#84598,#84599,#84600, - #84601,#84602,#84603,#84604,#84605,#84606,#84607,#84608,#84609, - #84610,#84611,#84612,#84613,#84614,#84615,#84616,#84617,#84618, - #84619,#84620,#84621),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#86960 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); +#86961 = CARTESIAN_POINT('',(4.790552085824,-0.424140987131)); +#86962 = CARTESIAN_POINT('',(4.812874135705,-0.423573537911)); +#86963 = CARTESIAN_POINT('',(4.846552114392,-0.422749662917)); +#86964 = CARTESIAN_POINT('',(4.880407630888,-0.421955010917)); +#86965 = CARTESIAN_POINT('',(4.914422492066,-0.421191423422)); +#86966 = CARTESIAN_POINT('',(4.948578027862,-0.420460671856)); +#86967 = CARTESIAN_POINT('',(4.98285506838,-0.419764438636)); +#86968 = CARTESIAN_POINT('',(5.017234026195,-0.419104307248)); +#86969 = CARTESIAN_POINT('',(5.051694955172,-0.418481750684)); +#86970 = CARTESIAN_POINT('',(5.086217619636,-0.41789812127)); +#86971 = CARTESIAN_POINT('',(5.120781564146,-0.417354641276)); +#86972 = CARTESIAN_POINT('',(5.155366185737,-0.416852394634)); +#86973 = CARTESIAN_POINT('',(5.189950807328,-0.416392319824)); +#86974 = CARTESIAN_POINT('',(5.224514751839,-0.415975204048)); +#86975 = CARTESIAN_POINT('',(5.259037416303,-0.415601678753)); +#86976 = CARTESIAN_POINT('',(5.293498345279,-0.41527221657)); +#86977 = CARTESIAN_POINT('',(5.327877303094,-0.414987129667)); +#86978 = CARTESIAN_POINT('',(5.362154343612,-0.414746569643)); +#86979 = CARTESIAN_POINT('',(5.396309879408,-0.414550528448)); +#86980 = CARTESIAN_POINT('',(5.430324740587,-0.414398842232)); +#86981 = CARTESIAN_POINT('',(5.464180257082,-0.414291190685)); +#86982 = CARTESIAN_POINT('',(5.49785823577,-0.414227119403)); +#86983 = CARTESIAN_POINT('',(5.52018028565,-0.414213027833)); +#86984 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); +#86985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#86986 = PCURVE('',#79178,#86987); +#86987 = DEFINITIONAL_REPRESENTATION('',(#86988),#87014); +#86988 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#86989,#86990,#86991,#86992, + #86993,#86994,#86995,#86996,#86997,#86998,#86999,#87000,#87001, + #87002,#87003,#87004,#87005,#87006,#87007,#87008,#87009,#87010, + #87011,#87012,#87013),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -104875,54 +107864,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#84597 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#84598 = CARTESIAN_POINT('',(0.740753686901,5.702886578311E-008)); -#84599 = CARTESIAN_POINT('',(0.718425946423,-7.920748674994E-006)); -#84600 = CARTESIAN_POINT('',(0.684729502771,-3.211524038325E-005)); -#84601 = CARTESIAN_POINT('',(0.650851510181,-9.135957813192E-005)); -#84602 = CARTESIAN_POINT('',(0.616817843149,-8.643182884289E-005)); -#84603 = CARTESIAN_POINT('',(0.582648204501,-8.687405903415E-005)); -#84604 = CARTESIAN_POINT('',(0.548364026633,-8.593542635494E-005)); -#84605 = CARTESIAN_POINT('',(0.513985713405,-8.542361824737E-005)); -#84606 = CARTESIAN_POINT('',(0.479533105651,-8.48530842991E-005)); -#84607 = CARTESIAN_POINT('',(0.445025477762,-8.435280861152E-005)); -#84608 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); -#84609 = CARTESIAN_POINT('',(0.375920232966,-8.346461194622E-005)); -#84610 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); -#84611 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); -#84612 = CARTESIAN_POINT('',(0.272313393703,-8.242390084137E-005)); -#84613 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#84614 = CARTESIAN_POINT('',(0.203491552027,-8.179989506531E-005)); -#84615 = CARTESIAN_POINT('',(0.169212469737,-8.226451401246E-005)); -#84616 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); -#84617 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); -#84618 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095812E-005)); -#84619 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467631E-005)); -#84620 = CARTESIAN_POINT('',(1.112575605159E-002,2.97280413299E-006)); -#84621 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#84622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84623 = ORIENTED_EDGE('',*,*,#76655,.T.); -#84624 = ORIENTED_EDGE('',*,*,#79671,.F.); -#84625 = ORIENTED_EDGE('',*,*,#84626,.F.); -#84626 = EDGE_CURVE('',#77833,#78995,#84627,.T.); -#84627 = SURFACE_CURVE('',#84628,(#84633,#84662),.PCURVE_S1.); -#84628 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84629,#84630,#84631,#84632 +#86989 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#86990 = CARTESIAN_POINT('',(0.740753686901,5.702886578311E-008)); +#86991 = CARTESIAN_POINT('',(0.718425946423,-7.920748674994E-006)); +#86992 = CARTESIAN_POINT('',(0.684729502771,-3.211524038325E-005)); +#86993 = CARTESIAN_POINT('',(0.650851510181,-9.135957813192E-005)); +#86994 = CARTESIAN_POINT('',(0.616817843149,-8.643182884289E-005)); +#86995 = CARTESIAN_POINT('',(0.582648204501,-8.687405903415E-005)); +#86996 = CARTESIAN_POINT('',(0.548364026633,-8.593542635494E-005)); +#86997 = CARTESIAN_POINT('',(0.513985713405,-8.542361824737E-005)); +#86998 = CARTESIAN_POINT('',(0.479533105651,-8.48530842991E-005)); +#86999 = CARTESIAN_POINT('',(0.445025477762,-8.435280861152E-005)); +#87000 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); +#87001 = CARTESIAN_POINT('',(0.375920232966,-8.346461194622E-005)); +#87002 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); +#87003 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); +#87004 = CARTESIAN_POINT('',(0.272313393703,-8.242390084137E-005)); +#87005 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#87006 = CARTESIAN_POINT('',(0.203491552027,-8.179989506531E-005)); +#87007 = CARTESIAN_POINT('',(0.169212469737,-8.226451401246E-005)); +#87008 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); +#87009 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); +#87010 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095812E-005)); +#87011 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467631E-005)); +#87012 = CARTESIAN_POINT('',(1.112575605159E-002,2.97280413299E-006)); +#87013 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#87014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87015 = ORIENTED_EDGE('',*,*,#79047,.T.); +#87016 = ORIENTED_EDGE('',*,*,#82063,.F.); +#87017 = ORIENTED_EDGE('',*,*,#87018,.F.); +#87018 = EDGE_CURVE('',#80225,#81387,#87019,.T.); +#87019 = SURFACE_CURVE('',#87020,(#87025,#87054),.PCURVE_S1.); +#87020 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87021,#87022,#87023,#87024 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#84629 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); -#84630 = CARTESIAN_POINT('',(-1.401121542172,-0.65,0.6)); -#84631 = CARTESIAN_POINT('',(-1.46,-0.591121542172,0.6)); -#84632 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); -#84633 = PCURVE('',#76713,#84634); -#84634 = DEFINITIONAL_REPRESENTATION('',(#84635),#84661); -#84635 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84636,#84637,#84638,#84639, - #84640,#84641,#84642,#84643,#84644,#84645,#84646,#84647,#84648, - #84649,#84650,#84651,#84652,#84653,#84654,#84655,#84656,#84657, - #84658,#84659,#84660),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87021 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); +#87022 = CARTESIAN_POINT('',(-1.401121542172,-0.65,0.6)); +#87023 = CARTESIAN_POINT('',(-1.46,-0.591121542172,0.6)); +#87024 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); +#87025 = PCURVE('',#79105,#87026); +#87026 = DEFINITIONAL_REPRESENTATION('',(#87027),#87053); +#87027 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87028,#87029,#87030,#87031, + #87032,#87033,#87034,#87035,#87036,#87037,#87038,#87039,#87040, + #87041,#87042,#87043,#87044,#87045,#87046,#87047,#87048,#87049, + #87050,#87051,#87052),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -104930,40 +107919,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#84636 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#84637 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); -#84638 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); -#84639 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); -#84640 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); -#84641 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); -#84642 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); -#84643 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); -#84644 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); -#84645 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); -#84646 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); -#84647 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); -#84648 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); -#84649 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); -#84650 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); -#84651 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); -#84652 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); -#84653 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); -#84654 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); -#84655 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); -#84656 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); -#84657 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); -#84658 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); -#84659 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); -#84660 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#84661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84662 = PCURVE('',#76020,#84663); -#84663 = DEFINITIONAL_REPRESENTATION('',(#84664),#84690); -#84664 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84665,#84666,#84667,#84668, - #84669,#84670,#84671,#84672,#84673,#84674,#84675,#84676,#84677, - #84678,#84679,#84680,#84681,#84682,#84683,#84684,#84685,#84686, - #84687,#84688,#84689),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87028 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#87029 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); +#87030 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); +#87031 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); +#87032 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); +#87033 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); +#87034 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); +#87035 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); +#87036 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); +#87037 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); +#87038 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); +#87039 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); +#87040 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); +#87041 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); +#87042 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); +#87043 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); +#87044 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); +#87045 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); +#87046 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); +#87047 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); +#87048 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); +#87049 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); +#87050 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); +#87051 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); +#87052 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#87053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87054 = PCURVE('',#78412,#87055); +#87055 = DEFINITIONAL_REPRESENTATION('',(#87056),#87082); +#87056 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87057,#87058,#87059,#87060, + #87061,#87062,#87063,#87064,#87065,#87066,#87067,#87068,#87069, + #87070,#87071,#87072,#87073,#87074,#87075,#87076,#87077,#87078, + #87079,#87080,#87081),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -104971,60 +107960,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#84665 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#84666 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); -#84667 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); -#84668 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); -#84669 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); -#84670 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); -#84671 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); -#84672 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); -#84673 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); -#84674 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); -#84675 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); -#84676 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); -#84677 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); -#84678 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); -#84679 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); -#84680 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); -#84681 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); -#84682 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); -#84683 = CARTESIAN_POINT('',(3.469181876598,0.299752403237)); -#84684 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); -#84685 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); -#84686 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); -#84687 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); -#84688 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); -#84689 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#84690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84691 = ADVANCED_FACE('',(#84692),#76020,.T.); -#84692 = FACE_BOUND('',#84693,.T.); -#84693 = EDGE_LOOP('',(#84694,#84695,#84696,#84762,#84763)); -#84694 = ORIENTED_EDGE('',*,*,#78994,.F.); -#84695 = ORIENTED_EDGE('',*,*,#75981,.T.); -#84696 = ORIENTED_EDGE('',*,*,#84697,.T.); -#84697 = EDGE_CURVE('',#75897,#78757,#84698,.T.); -#84698 = SURFACE_CURVE('',#84699,(#84704,#84733),.PCURVE_S1.); -#84699 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84700,#84701,#84702,#84703 +#87057 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#87058 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); +#87059 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); +#87060 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); +#87061 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); +#87062 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); +#87063 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); +#87064 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); +#87065 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); +#87066 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); +#87067 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); +#87068 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); +#87069 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); +#87070 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); +#87071 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); +#87072 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); +#87073 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); +#87074 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); +#87075 = CARTESIAN_POINT('',(3.469181876598,0.299752403237)); +#87076 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); +#87077 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); +#87078 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); +#87079 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); +#87080 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); +#87081 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#87082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87083 = ADVANCED_FACE('',(#87084),#78412,.T.); +#87084 = FACE_BOUND('',#87085,.T.); +#87085 = EDGE_LOOP('',(#87086,#87087,#87088,#87154,#87155)); +#87086 = ORIENTED_EDGE('',*,*,#81386,.F.); +#87087 = ORIENTED_EDGE('',*,*,#78373,.T.); +#87088 = ORIENTED_EDGE('',*,*,#87089,.T.); +#87089 = EDGE_CURVE('',#78289,#81149,#87090,.T.); +#87090 = SURFACE_CURVE('',#87091,(#87096,#87125),.PCURVE_S1.); +#87091 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87092,#87093,#87094,#87095 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#84700 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#84701 = CARTESIAN_POINT('',(-1.265581001793,-0.510038843607,0.132282534 +#87092 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#87093 = CARTESIAN_POINT('',(-1.265581001793,-0.510038843607,0.132282534 )); -#84702 = CARTESIAN_POINT('',(-1.230010423697,-0.525122936235, +#87094 = CARTESIAN_POINT('',(-1.230010423697,-0.525122936235, 0.133952453327)); -#84703 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#87095 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#84704 = PCURVE('',#76020,#84705); -#84705 = DEFINITIONAL_REPRESENTATION('',(#84706),#84732); -#84706 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84707,#84708,#84709,#84710, - #84711,#84712,#84713,#84714,#84715,#84716,#84717,#84718,#84719, - #84720,#84721,#84722,#84723,#84724,#84725,#84726,#84727,#84728, - #84729,#84730,#84731),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87096 = PCURVE('',#78412,#87097); +#87097 = DEFINITIONAL_REPRESENTATION('',(#87098),#87124); +#87098 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87099,#87100,#87101,#87102, + #87103,#87104,#87105,#87106,#87107,#87108,#87109,#87110,#87111, + #87112,#87113,#87114,#87115,#87116,#87117,#87118,#87119,#87120, + #87121,#87122,#87123),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-8.881784197001E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105032,40 +108021,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.UNSPECIFIED.); -#84707 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); -#84708 = CARTESIAN_POINT('',(3.90459767512,-0.195420311637)); -#84709 = CARTESIAN_POINT('',(3.926919725,-0.195434403207)); -#84710 = CARTESIAN_POINT('',(3.960597703687,-0.195498474489)); -#84711 = CARTESIAN_POINT('',(3.994453220183,-0.195606126036)); -#84712 = CARTESIAN_POINT('',(4.028468081361,-0.195757812252)); -#84713 = CARTESIAN_POINT('',(4.062623617158,-0.195953853447)); -#84714 = CARTESIAN_POINT('',(4.096900657675,-0.196194413471)); -#84715 = CARTESIAN_POINT('',(4.13127961549,-0.196479500374)); -#84716 = CARTESIAN_POINT('',(4.165740544467,-0.196808962557)); -#84717 = CARTESIAN_POINT('',(4.200263208931,-0.197182487852)); -#84718 = CARTESIAN_POINT('',(4.234827153442,-0.197599603628)); -#84719 = CARTESIAN_POINT('',(4.269411775032,-0.198059678438)); -#84720 = CARTESIAN_POINT('',(4.303996396623,-0.19856192508)); -#84721 = CARTESIAN_POINT('',(4.338560341134,-0.199105405074)); -#84722 = CARTESIAN_POINT('',(4.373083005598,-0.199689034488)); -#84723 = CARTESIAN_POINT('',(4.407543934574,-0.200311591052)); -#84724 = CARTESIAN_POINT('',(4.44192289239,-0.20097172244)); -#84725 = CARTESIAN_POINT('',(4.476199932907,-0.20166795566)); -#84726 = CARTESIAN_POINT('',(4.510355468703,-0.202398707226)); -#84727 = CARTESIAN_POINT('',(4.544370329882,-0.203162294721)); -#84728 = CARTESIAN_POINT('',(4.578225846377,-0.203956946721)); -#84729 = CARTESIAN_POINT('',(4.611903825065,-0.204780821715)); -#84730 = CARTESIAN_POINT('',(4.634225874945,-0.205348270935)); -#84731 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); -#84732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84733 = PCURVE('',#75935,#84734); -#84734 = DEFINITIONAL_REPRESENTATION('',(#84735),#84761); -#84735 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84736,#84737,#84738,#84739, - #84740,#84741,#84742,#84743,#84744,#84745,#84746,#84747,#84748, - #84749,#84750,#84751,#84752,#84753,#84754,#84755,#84756,#84757, - #84758,#84759,#84760),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87099 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); +#87100 = CARTESIAN_POINT('',(3.90459767512,-0.195420311637)); +#87101 = CARTESIAN_POINT('',(3.926919725,-0.195434403207)); +#87102 = CARTESIAN_POINT('',(3.960597703687,-0.195498474489)); +#87103 = CARTESIAN_POINT('',(3.994453220183,-0.195606126036)); +#87104 = CARTESIAN_POINT('',(4.028468081361,-0.195757812252)); +#87105 = CARTESIAN_POINT('',(4.062623617158,-0.195953853447)); +#87106 = CARTESIAN_POINT('',(4.096900657675,-0.196194413471)); +#87107 = CARTESIAN_POINT('',(4.13127961549,-0.196479500374)); +#87108 = CARTESIAN_POINT('',(4.165740544467,-0.196808962557)); +#87109 = CARTESIAN_POINT('',(4.200263208931,-0.197182487852)); +#87110 = CARTESIAN_POINT('',(4.234827153442,-0.197599603628)); +#87111 = CARTESIAN_POINT('',(4.269411775032,-0.198059678438)); +#87112 = CARTESIAN_POINT('',(4.303996396623,-0.19856192508)); +#87113 = CARTESIAN_POINT('',(4.338560341134,-0.199105405074)); +#87114 = CARTESIAN_POINT('',(4.373083005598,-0.199689034488)); +#87115 = CARTESIAN_POINT('',(4.407543934574,-0.200311591052)); +#87116 = CARTESIAN_POINT('',(4.44192289239,-0.20097172244)); +#87117 = CARTESIAN_POINT('',(4.476199932907,-0.20166795566)); +#87118 = CARTESIAN_POINT('',(4.510355468703,-0.202398707226)); +#87119 = CARTESIAN_POINT('',(4.544370329882,-0.203162294721)); +#87120 = CARTESIAN_POINT('',(4.578225846377,-0.203956946721)); +#87121 = CARTESIAN_POINT('',(4.611903825065,-0.204780821715)); +#87122 = CARTESIAN_POINT('',(4.634225874945,-0.205348270935)); +#87123 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); +#87124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87125 = PCURVE('',#78327,#87126); +#87126 = DEFINITIONAL_REPRESENTATION('',(#87127),#87153); +#87127 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87128,#87129,#87130,#87131, + #87132,#87133,#87134,#87135,#87136,#87137,#87138,#87139,#87140, + #87141,#87142,#87143,#87144,#87145,#87146,#87147,#87148,#87149, + #87150,#87151,#87152),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(-8.881784197001E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105073,62 +108062,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.UNSPECIFIED.); -#84736 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#84737 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#84738 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#84739 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#84740 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#84741 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#84742 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#84743 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#84744 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#84745 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#84746 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#84747 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#84748 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#84749 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#84750 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#84751 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#84752 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); -#84753 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); -#84754 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); -#84755 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); -#84756 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); -#84757 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); -#84758 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); -#84759 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); -#84760 = CARTESIAN_POINT('',(0.751879414295,1.)); -#84761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84762 = ORIENTED_EDGE('',*,*,#78756,.F.); -#84763 = ORIENTED_EDGE('',*,*,#84626,.T.); -#84764 = ADVANCED_FACE('',(#84765),#77291,.T.); -#84765 = FACE_BOUND('',#84766,.T.); -#84766 = EDGE_LOOP('',(#84767,#84768,#84834,#84835,#84836)); -#84767 = ORIENTED_EDGE('',*,*,#79759,.F.); -#84768 = ORIENTED_EDGE('',*,*,#84769,.T.); -#84769 = EDGE_CURVE('',#79715,#77234,#84770,.T.); -#84770 = SURFACE_CURVE('',#84771,(#84776,#84805),.PCURVE_S1.); -#84771 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84772,#84773,#84774,#84775 +#87128 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#87129 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#87130 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#87131 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#87132 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#87133 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#87134 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#87135 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#87136 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#87137 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#87138 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#87139 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#87140 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#87141 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#87142 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#87143 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#87144 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); +#87145 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); +#87146 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); +#87147 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); +#87148 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); +#87149 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); +#87150 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); +#87151 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); +#87152 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87154 = ORIENTED_EDGE('',*,*,#81148,.F.); +#87155 = ORIENTED_EDGE('',*,*,#87018,.T.); +#87156 = ADVANCED_FACE('',(#87157),#79683,.T.); +#87157 = FACE_BOUND('',#87158,.T.); +#87158 = EDGE_LOOP('',(#87159,#87160,#87226,#87227,#87228)); +#87159 = ORIENTED_EDGE('',*,*,#82151,.F.); +#87160 = ORIENTED_EDGE('',*,*,#87161,.T.); +#87161 = EDGE_CURVE('',#82107,#79626,#87162,.T.); +#87162 = SURFACE_CURVE('',#87163,(#87168,#87197),.PCURVE_S1.); +#87163 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87164,#87165,#87166,#87167 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#84772 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) +#87164 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255) ); -#84773 = CARTESIAN_POINT('',(-1.361917855478,0.44680534294, +#87165 = CARTESIAN_POINT('',(-1.361917855478,0.44680534294, 0.966047546673)); -#84774 = CARTESIAN_POINT('',(-1.34683376285,0.482375921036,0.967717466) +#87166 = CARTESIAN_POINT('',(-1.34683376285,0.482375921036,0.967717466) ); -#84775 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) +#87167 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466) ); -#84776 = PCURVE('',#77291,#84777); -#84777 = DEFINITIONAL_REPRESENTATION('',(#84778),#84804); -#84778 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84779,#84780,#84781,#84782, - #84783,#84784,#84785,#84786,#84787,#84788,#84789,#84790,#84791, - #84792,#84793,#84794,#84795,#84796,#84797,#84798,#84799,#84800, - #84801,#84802,#84803),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87168 = PCURVE('',#79683,#87169); +#87169 = DEFINITIONAL_REPRESENTATION('',(#87170),#87196); +#87170 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87171,#87172,#87173,#87174, + #87175,#87176,#87177,#87178,#87179,#87180,#87181,#87182,#87183, + #87184,#87185,#87186,#87187,#87188,#87189,#87190,#87191,#87192, + #87193,#87194,#87195),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105136,40 +108125,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#84779 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); -#84780 = CARTESIAN_POINT('',(1.112560723485E-002,-0.424140987131)); -#84781 = CARTESIAN_POINT('',(3.344765711494E-002,-0.423573537911)); -#84782 = CARTESIAN_POINT('',(6.712563580239E-002,-0.422749662917)); -#84783 = CARTESIAN_POINT('',(0.100981152298,-0.421955010917)); -#84784 = CARTESIAN_POINT('',(0.134996013476,-0.421191423422)); -#84785 = CARTESIAN_POINT('',(0.169151549273,-0.420460671856)); -#84786 = CARTESIAN_POINT('',(0.20342858979,-0.419764438636)); -#84787 = CARTESIAN_POINT('',(0.237807547605,-0.419104307248)); -#84788 = CARTESIAN_POINT('',(0.272268476582,-0.418481750684)); -#84789 = CARTESIAN_POINT('',(0.306791141046,-0.41789812127)); -#84790 = CARTESIAN_POINT('',(0.341355085557,-0.417354641276)); -#84791 = CARTESIAN_POINT('',(0.375939707147,-0.416852394634)); -#84792 = CARTESIAN_POINT('',(0.410524328738,-0.416392319824)); -#84793 = CARTESIAN_POINT('',(0.445088273249,-0.415975204048)); -#84794 = CARTESIAN_POINT('',(0.479610937713,-0.415601678753)); -#84795 = CARTESIAN_POINT('',(0.51407186669,-0.41527221657)); -#84796 = CARTESIAN_POINT('',(0.548450824505,-0.414987129667)); -#84797 = CARTESIAN_POINT('',(0.582727865022,-0.414746569643)); -#84798 = CARTESIAN_POINT('',(0.616883400819,-0.414550528448)); -#84799 = CARTESIAN_POINT('',(0.650898261997,-0.414398842232)); -#84800 = CARTESIAN_POINT('',(0.684753778493,-0.414291190685)); -#84801 = CARTESIAN_POINT('',(0.71843175718,-0.414227119403)); -#84802 = CARTESIAN_POINT('',(0.74075380706,-0.414213027833)); -#84803 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); -#84804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84805 = PCURVE('',#77364,#84806); -#84806 = DEFINITIONAL_REPRESENTATION('',(#84807),#84833); -#84807 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84808,#84809,#84810,#84811, - #84812,#84813,#84814,#84815,#84816,#84817,#84818,#84819,#84820, - #84821,#84822,#84823,#84824,#84825,#84826,#84827,#84828,#84829, - #84830,#84831,#84832),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87171 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); +#87172 = CARTESIAN_POINT('',(1.112560723485E-002,-0.424140987131)); +#87173 = CARTESIAN_POINT('',(3.344765711494E-002,-0.423573537911)); +#87174 = CARTESIAN_POINT('',(6.712563580239E-002,-0.422749662917)); +#87175 = CARTESIAN_POINT('',(0.100981152298,-0.421955010917)); +#87176 = CARTESIAN_POINT('',(0.134996013476,-0.421191423422)); +#87177 = CARTESIAN_POINT('',(0.169151549273,-0.420460671856)); +#87178 = CARTESIAN_POINT('',(0.20342858979,-0.419764438636)); +#87179 = CARTESIAN_POINT('',(0.237807547605,-0.419104307248)); +#87180 = CARTESIAN_POINT('',(0.272268476582,-0.418481750684)); +#87181 = CARTESIAN_POINT('',(0.306791141046,-0.41789812127)); +#87182 = CARTESIAN_POINT('',(0.341355085557,-0.417354641276)); +#87183 = CARTESIAN_POINT('',(0.375939707147,-0.416852394634)); +#87184 = CARTESIAN_POINT('',(0.410524328738,-0.416392319824)); +#87185 = CARTESIAN_POINT('',(0.445088273249,-0.415975204048)); +#87186 = CARTESIAN_POINT('',(0.479610937713,-0.415601678753)); +#87187 = CARTESIAN_POINT('',(0.51407186669,-0.41527221657)); +#87188 = CARTESIAN_POINT('',(0.548450824505,-0.414987129667)); +#87189 = CARTESIAN_POINT('',(0.582727865022,-0.414746569643)); +#87190 = CARTESIAN_POINT('',(0.616883400819,-0.414550528448)); +#87191 = CARTESIAN_POINT('',(0.650898261997,-0.414398842232)); +#87192 = CARTESIAN_POINT('',(0.684753778493,-0.414291190685)); +#87193 = CARTESIAN_POINT('',(0.71843175718,-0.414227119403)); +#87194 = CARTESIAN_POINT('',(0.74075380706,-0.414213027833)); +#87195 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); +#87196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87197 = PCURVE('',#79756,#87198); +#87198 = DEFINITIONAL_REPRESENTATION('',(#87199),#87225); +#87199 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87200,#87201,#87202,#87203, + #87204,#87205,#87206,#87207,#87208,#87209,#87210,#87211,#87212, + #87213,#87214,#87215,#87216,#87217,#87218,#87219,#87220,#87221, + #87222,#87223,#87224),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105177,54 +108166,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#84808 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#84809 = CARTESIAN_POINT('',(0.740753686904,5.712075643651E-008)); -#84810 = CARTESIAN_POINT('',(0.718425946425,-7.920681090372E-006)); -#84811 = CARTESIAN_POINT('',(0.684729502759,-3.211561473994E-005)); -#84812 = CARTESIAN_POINT('',(0.650851510226,-9.135814826272E-005)); -#84813 = CARTESIAN_POINT('',(0.616817843137,-8.643221197519E-005)); -#84814 = CARTESIAN_POINT('',(0.582648204505,-8.687395637416E-005)); -#84815 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); -#84816 = CARTESIAN_POINT('',(0.513985713406,-8.542361087673E-005)); -#84817 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); -#84818 = CARTESIAN_POINT('',(0.445025477762,-8.435280808235E-005)); -#84819 = CARTESIAN_POINT('',(0.410481676253,-8.388702482308E-005)); -#84820 = CARTESIAN_POINT('',(0.375920232966,-8.346461190823E-005)); -#84821 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); -#84822 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); -#84823 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); -#84824 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); -#84825 = CARTESIAN_POINT('',(0.203491552027,-8.179989506535E-005)); -#84826 = CARTESIAN_POINT('',(0.169212469737,-8.226451401251E-005)); -#84827 = CARTESIAN_POINT('',(0.135047837564,-7.965797689881E-005)); -#84828 = CARTESIAN_POINT('',(0.101018376289,-8.868396576202E-005)); -#84829 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095473E-005)); -#84830 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467085E-005)); -#84831 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135975E-006)); -#84832 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#84833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84834 = ORIENTED_EDGE('',*,*,#77233,.T.); -#84835 = ORIENTED_EDGE('',*,*,#78120,.F.); -#84836 = ORIENTED_EDGE('',*,*,#84837,.F.); -#84837 = EDGE_CURVE('',#78923,#78121,#84838,.T.); -#84838 = SURFACE_CURVE('',#84839,(#84844,#84873),.PCURVE_S1.); -#84839 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84840,#84841,#84842,#84843 +#87200 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87201 = CARTESIAN_POINT('',(0.740753686904,5.712075643651E-008)); +#87202 = CARTESIAN_POINT('',(0.718425946425,-7.920681090372E-006)); +#87203 = CARTESIAN_POINT('',(0.684729502759,-3.211561473994E-005)); +#87204 = CARTESIAN_POINT('',(0.650851510226,-9.135814826272E-005)); +#87205 = CARTESIAN_POINT('',(0.616817843137,-8.643221197519E-005)); +#87206 = CARTESIAN_POINT('',(0.582648204505,-8.687395637416E-005)); +#87207 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); +#87208 = CARTESIAN_POINT('',(0.513985713406,-8.542361087673E-005)); +#87209 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); +#87210 = CARTESIAN_POINT('',(0.445025477762,-8.435280808235E-005)); +#87211 = CARTESIAN_POINT('',(0.410481676253,-8.388702482308E-005)); +#87212 = CARTESIAN_POINT('',(0.375920232966,-8.346461190823E-005)); +#87213 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); +#87214 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); +#87215 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); +#87216 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); +#87217 = CARTESIAN_POINT('',(0.203491552027,-8.179989506535E-005)); +#87218 = CARTESIAN_POINT('',(0.169212469737,-8.226451401251E-005)); +#87219 = CARTESIAN_POINT('',(0.135047837564,-7.965797689881E-005)); +#87220 = CARTESIAN_POINT('',(0.101018376289,-8.868396576202E-005)); +#87221 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095473E-005)); +#87222 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467085E-005)); +#87223 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135975E-006)); +#87224 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#87225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87226 = ORIENTED_EDGE('',*,*,#79625,.T.); +#87227 = ORIENTED_EDGE('',*,*,#80512,.F.); +#87228 = ORIENTED_EDGE('',*,*,#87229,.F.); +#87229 = EDGE_CURVE('',#81315,#80513,#87230,.T.); +#87230 = SURFACE_CURVE('',#87231,(#87236,#87265),.PCURVE_S1.); +#87231 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87232,#87233,#87234,#87235 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#84840 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); -#84841 = CARTESIAN_POINT('',(-1.46,0.591121542172,0.6)); -#84842 = CARTESIAN_POINT('',(-1.401121542172,0.65,0.6)); -#84843 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); -#84844 = PCURVE('',#77291,#84845); -#84845 = DEFINITIONAL_REPRESENTATION('',(#84846),#84872); -#84846 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84847,#84848,#84849,#84850, - #84851,#84852,#84853,#84854,#84855,#84856,#84857,#84858,#84859, - #84860,#84861,#84862,#84863,#84864,#84865,#84866,#84867,#84868, - #84869,#84870,#84871),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87232 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); +#87233 = CARTESIAN_POINT('',(-1.46,0.591121542172,0.6)); +#87234 = CARTESIAN_POINT('',(-1.401121542172,0.65,0.6)); +#87235 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); +#87236 = PCURVE('',#79683,#87237); +#87237 = DEFINITIONAL_REPRESENTATION('',(#87238),#87264); +#87238 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87239,#87240,#87241,#87242, + #87243,#87244,#87245,#87246,#87247,#87248,#87249,#87250,#87251, + #87252,#87253,#87254,#87255,#87256,#87257,#87258,#87259,#87260, + #87261,#87262,#87263),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -105232,40 +108221,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#84847 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#84848 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#84849 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002)); -#84850 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#84851 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#84852 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#84853 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#84854 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#84855 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#84856 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#84857 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#84858 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#84859 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#84860 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#84861 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#84862 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#84863 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#84864 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#84865 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#84866 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#84867 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#84868 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#84869 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#84870 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#84871 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#84872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84873 = PCURVE('',#76570,#84874); -#84874 = DEFINITIONAL_REPRESENTATION('',(#84875),#84901); -#84875 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84876,#84877,#84878,#84879, - #84880,#84881,#84882,#84883,#84884,#84885,#84886,#84887,#84888, - #84889,#84890,#84891,#84892,#84893,#84894,#84895,#84896,#84897, - #84898,#84899,#84900),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87239 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#87240 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#87241 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002)); +#87242 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#87243 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#87244 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#87245 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#87246 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#87247 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#87248 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#87249 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#87250 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#87251 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#87252 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#87253 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#87254 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#87255 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#87256 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#87257 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#87258 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#87259 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#87260 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#87261 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#87262 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#87263 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#87264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87265 = PCURVE('',#78962,#87266); +#87266 = DEFINITIONAL_REPRESENTATION('',(#87267),#87293); +#87267 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87268,#87269,#87270,#87271, + #87272,#87273,#87274,#87275,#87276,#87277,#87278,#87279,#87280, + #87281,#87282,#87283,#87284,#87285,#87286,#87287,#87288,#87289, + #87290,#87291,#87292),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -105273,60 +108262,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#84876 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#84877 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); -#84878 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); -#84879 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); -#84880 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); -#84881 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); -#84882 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); -#84883 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); -#84884 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); -#84885 = CARTESIAN_POINT('',(2.604275354486,-2.223663371573E-002)); -#84886 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); -#84887 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); -#84888 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); -#84889 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); -#84890 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); -#84891 = CARTESIAN_POINT('',(2.175151124104,-2.223663371573E-002)); -#84892 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); -#84893 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); -#84894 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); -#84895 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); -#84896 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); -#84897 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); -#84898 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); -#84899 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); -#84900 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#84901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84902 = ADVANCED_FACE('',(#84903),#76570,.T.); -#84903 = FACE_BOUND('',#84904,.T.); -#84904 = EDGE_LOOP('',(#84905,#84906,#84907,#84973,#84974)); -#84905 = ORIENTED_EDGE('',*,*,#79133,.F.); -#84906 = ORIENTED_EDGE('',*,*,#76531,.T.); -#84907 = ORIENTED_EDGE('',*,*,#84908,.T.); -#84908 = EDGE_CURVE('',#76447,#78925,#84909,.T.); -#84909 = SURFACE_CURVE('',#84910,(#84915,#84944),.PCURVE_S1.); -#84910 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84911,#84912,#84913,#84914 +#87268 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#87269 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); +#87270 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); +#87271 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); +#87272 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); +#87273 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); +#87274 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); +#87275 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); +#87276 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); +#87277 = CARTESIAN_POINT('',(2.604275354486,-2.223663371573E-002)); +#87278 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); +#87279 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); +#87280 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); +#87281 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); +#87282 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); +#87283 = CARTESIAN_POINT('',(2.175151124104,-2.223663371573E-002)); +#87284 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); +#87285 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); +#87286 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); +#87287 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); +#87288 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); +#87289 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); +#87290 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); +#87291 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); +#87292 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#87293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87294 = ADVANCED_FACE('',(#87295),#78962,.T.); +#87295 = FACE_BOUND('',#87296,.T.); +#87296 = EDGE_LOOP('',(#87297,#87298,#87299,#87365,#87366)); +#87297 = ORIENTED_EDGE('',*,*,#81525,.F.); +#87298 = ORIENTED_EDGE('',*,*,#78923,.T.); +#87299 = ORIENTED_EDGE('',*,*,#87300,.T.); +#87300 = EDGE_CURVE('',#78839,#81317,#87301,.T.); +#87301 = SURFACE_CURVE('',#87302,(#87307,#87336),.PCURVE_S1.); +#87302 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87303,#87304,#87305,#87306 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.807003620809E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#84911 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#84912 = CARTESIAN_POINT('',(-1.320038843607,0.455581001793,0.132282534) +#87303 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#87304 = CARTESIAN_POINT('',(-1.320038843607,0.455581001793,0.132282534) ); -#84913 = CARTESIAN_POINT('',(-1.335122936235,0.420010423697, +#87305 = CARTESIAN_POINT('',(-1.335122936235,0.420010423697, 0.133952453327)); -#84914 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 +#87306 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757,0.137059047745 )); -#84915 = PCURVE('',#76570,#84916); -#84916 = DEFINITIONAL_REPRESENTATION('',(#84917),#84943); -#84917 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84918,#84919,#84920,#84921, - #84922,#84923,#84924,#84925,#84926,#84927,#84928,#84929,#84930, - #84931,#84932,#84933,#84934,#84935,#84936,#84937,#84938,#84939, - #84940,#84941,#84942),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87307 = PCURVE('',#78962,#87308); +#87308 = DEFINITIONAL_REPRESENTATION('',(#87309),#87335); +#87309 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87310,#87311,#87312,#87313, + #87314,#87315,#87316,#87317,#87318,#87319,#87320,#87321,#87322, + #87323,#87324,#87325,#87326,#87327,#87328,#87329,#87330,#87331, + #87332,#87333,#87334),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.807003620809E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105334,40 +108323,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#84918 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#84919 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); -#84920 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); -#84921 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); -#84922 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); -#84923 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); -#84924 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); -#84925 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); -#84926 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); -#84927 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); -#84928 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); -#84929 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); -#84930 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); -#84931 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); -#84932 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); -#84933 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); -#84934 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); -#84935 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); -#84936 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); -#84937 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); -#84938 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); -#84939 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); -#84940 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); -#84941 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); -#84942 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#84943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84944 = PCURVE('',#76485,#84945); -#84945 = DEFINITIONAL_REPRESENTATION('',(#84946),#84972); -#84946 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84947,#84948,#84949,#84950, - #84951,#84952,#84953,#84954,#84955,#84956,#84957,#84958,#84959, - #84960,#84961,#84962,#84963,#84964,#84965,#84966,#84967,#84968, - #84969,#84970,#84971),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87310 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#87311 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); +#87312 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); +#87313 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); +#87314 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); +#87315 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); +#87316 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); +#87317 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); +#87318 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); +#87319 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); +#87320 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); +#87321 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); +#87322 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); +#87323 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); +#87324 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); +#87325 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); +#87326 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); +#87327 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); +#87328 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); +#87329 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); +#87330 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); +#87331 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); +#87332 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); +#87333 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); +#87334 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#87335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87336 = PCURVE('',#78877,#87337); +#87337 = DEFINITIONAL_REPRESENTATION('',(#87338),#87364); +#87338 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87339,#87340,#87341,#87342, + #87343,#87344,#87345,#87346,#87347,#87348,#87349,#87350,#87351, + #87352,#87353,#87354,#87355,#87356,#87357,#87358,#87359,#87360, + #87361,#87362,#87363),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.807003620809E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105375,62 +108364,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#84947 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#84948 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#84949 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#84950 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#84951 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#84952 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#84953 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#84954 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#84955 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#84956 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#84957 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#84958 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#84959 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#84960 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#84961 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); -#84962 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); -#84963 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); -#84964 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); -#84965 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); -#84966 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); -#84967 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); -#84968 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); -#84969 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); -#84970 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); -#84971 = CARTESIAN_POINT('',(0.751879414295,1.)); -#84972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#84973 = ORIENTED_EDGE('',*,*,#78922,.F.); -#84974 = ORIENTED_EDGE('',*,*,#84837,.T.); -#84975 = ADVANCED_FACE('',(#84976),#77016,.T.); -#84976 = FACE_BOUND('',#84977,.T.); -#84977 = EDGE_LOOP('',(#84978,#84979,#85045,#85046,#85047)); -#84978 = ORIENTED_EDGE('',*,*,#79647,.F.); -#84979 = ORIENTED_EDGE('',*,*,#84980,.T.); -#84980 = EDGE_CURVE('',#79603,#76959,#84981,.T.); -#84981 = SURFACE_CURVE('',#84982,(#84987,#85016),.PCURVE_S1.); -#84982 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#84983,#84984,#84985,#84986 +#87339 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#87340 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#87341 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#87342 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#87343 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#87344 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#87345 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#87346 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#87347 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#87348 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#87349 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#87350 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#87351 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#87352 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#87353 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); +#87354 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); +#87355 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); +#87356 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); +#87357 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); +#87358 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); +#87359 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); +#87360 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); +#87361 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); +#87362 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); +#87363 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87365 = ORIENTED_EDGE('',*,*,#81314,.F.); +#87366 = ORIENTED_EDGE('',*,*,#87229,.T.); +#87367 = ADVANCED_FACE('',(#87368),#79408,.T.); +#87368 = FACE_BOUND('',#87369,.T.); +#87369 = EDGE_LOOP('',(#87370,#87371,#87437,#87438,#87439)); +#87370 = ORIENTED_EDGE('',*,*,#82039,.F.); +#87371 = ORIENTED_EDGE('',*,*,#87372,.T.); +#87372 = EDGE_CURVE('',#81995,#79351,#87373,.T.); +#87373 = SURFACE_CURVE('',#87374,(#87379,#87408),.PCURVE_S1.); +#87374 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87375,#87376,#87377,#87378 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#84983 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) +#87375 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255) ); -#84984 = CARTESIAN_POINT('',(1.361917855478,-0.44680534294, +#87376 = CARTESIAN_POINT('',(1.361917855478,-0.44680534294, 0.966047546673)); -#84985 = CARTESIAN_POINT('',(1.34683376285,-0.482375921036,0.967717466) +#87377 = CARTESIAN_POINT('',(1.34683376285,-0.482375921036,0.967717466) ); -#84986 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) +#87378 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466) ); -#84987 = PCURVE('',#77016,#84988); -#84988 = DEFINITIONAL_REPRESENTATION('',(#84989),#85015); -#84989 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#84990,#84991,#84992,#84993, - #84994,#84995,#84996,#84997,#84998,#84999,#85000,#85001,#85002, - #85003,#85004,#85005,#85006,#85007,#85008,#85009,#85010,#85011, - #85012,#85013,#85014),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87379 = PCURVE('',#79408,#87380); +#87380 = DEFINITIONAL_REPRESENTATION('',(#87381),#87407); +#87381 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87382,#87383,#87384,#87385, + #87386,#87387,#87388,#87389,#87390,#87391,#87392,#87393,#87394, + #87395,#87396,#87397,#87398,#87399,#87400,#87401,#87402,#87403, + #87404,#87405,#87406),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105438,40 +108427,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#84990 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); -#84991 = CARTESIAN_POINT('',(3.152718260825,-9.840933791906E-002)); -#84992 = CARTESIAN_POINT('',(3.175040310705,-9.78418886995E-002)); -#84993 = CARTESIAN_POINT('',(3.208718289392,-9.701801370533E-002)); -#84994 = CARTESIAN_POINT('',(3.242573805888,-9.622336170581E-002)); -#84995 = CARTESIAN_POINT('',(3.276588667066,-9.545977421098E-002)); -#84996 = CARTESIAN_POINT('',(3.310744202863,-9.472902264469E-002)); -#84997 = CARTESIAN_POINT('',(3.34502124338,-9.403278942409E-002)); -#84998 = CARTESIAN_POINT('',(3.379400201195,-9.337265803686E-002)); -#84999 = CARTESIAN_POINT('',(3.413861130172,-9.275010147284E-002)); -#85000 = CARTESIAN_POINT('',(3.448383794636,-9.216647205879E-002)); -#85001 = CARTESIAN_POINT('',(3.482947739147,-9.162299206488E-002)); -#85002 = CARTESIAN_POINT('',(3.517532360737,-9.112074542238E-002)); -#85003 = CARTESIAN_POINT('',(3.552116982328,-9.066067061216E-002)); -#85004 = CARTESIAN_POINT('',(3.586680926839,-9.024355483614E-002)); -#85005 = CARTESIAN_POINT('',(3.621203591303,-8.987002954109E-002)); -#85006 = CARTESIAN_POINT('',(3.65566452028,-8.954056735899E-002)); -#85007 = CARTESIAN_POINT('',(3.690043478095,-8.92554804551E-002)); -#85008 = CARTESIAN_POINT('',(3.724320518612,-8.901492043166E-002)); -#85009 = CARTESIAN_POINT('',(3.758476054408,-8.881887923673E-002)); -#85010 = CARTESIAN_POINT('',(3.792490915587,-8.866719302101E-002)); -#85011 = CARTESIAN_POINT('',(3.826346432082,-8.855954147362E-002)); -#85012 = CARTESIAN_POINT('',(3.86002441077,-8.849547019148E-002)); -#85013 = CARTESIAN_POINT('',(3.88234646065,-8.848137862171E-002)); -#85014 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); -#85015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85016 = PCURVE('',#77089,#85017); -#85017 = DEFINITIONAL_REPRESENTATION('',(#85018),#85044); -#85018 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85019,#85020,#85021,#85022, - #85023,#85024,#85025,#85026,#85027,#85028,#85029,#85030,#85031, - #85032,#85033,#85034,#85035,#85036,#85037,#85038,#85039,#85040, - #85041,#85042,#85043),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87382 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); +#87383 = CARTESIAN_POINT('',(3.152718260825,-9.840933791906E-002)); +#87384 = CARTESIAN_POINT('',(3.175040310705,-9.78418886995E-002)); +#87385 = CARTESIAN_POINT('',(3.208718289392,-9.701801370533E-002)); +#87386 = CARTESIAN_POINT('',(3.242573805888,-9.622336170581E-002)); +#87387 = CARTESIAN_POINT('',(3.276588667066,-9.545977421098E-002)); +#87388 = CARTESIAN_POINT('',(3.310744202863,-9.472902264469E-002)); +#87389 = CARTESIAN_POINT('',(3.34502124338,-9.403278942409E-002)); +#87390 = CARTESIAN_POINT('',(3.379400201195,-9.337265803686E-002)); +#87391 = CARTESIAN_POINT('',(3.413861130172,-9.275010147284E-002)); +#87392 = CARTESIAN_POINT('',(3.448383794636,-9.216647205879E-002)); +#87393 = CARTESIAN_POINT('',(3.482947739147,-9.162299206488E-002)); +#87394 = CARTESIAN_POINT('',(3.517532360737,-9.112074542238E-002)); +#87395 = CARTESIAN_POINT('',(3.552116982328,-9.066067061216E-002)); +#87396 = CARTESIAN_POINT('',(3.586680926839,-9.024355483614E-002)); +#87397 = CARTESIAN_POINT('',(3.621203591303,-8.987002954109E-002)); +#87398 = CARTESIAN_POINT('',(3.65566452028,-8.954056735899E-002)); +#87399 = CARTESIAN_POINT('',(3.690043478095,-8.92554804551E-002)); +#87400 = CARTESIAN_POINT('',(3.724320518612,-8.901492043166E-002)); +#87401 = CARTESIAN_POINT('',(3.758476054408,-8.881887923673E-002)); +#87402 = CARTESIAN_POINT('',(3.792490915587,-8.866719302101E-002)); +#87403 = CARTESIAN_POINT('',(3.826346432082,-8.855954147362E-002)); +#87404 = CARTESIAN_POINT('',(3.86002441077,-8.849547019148E-002)); +#87405 = CARTESIAN_POINT('',(3.88234646065,-8.848137862171E-002)); +#87406 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); +#87407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87408 = PCURVE('',#79481,#87409); +#87409 = DEFINITIONAL_REPRESENTATION('',(#87410),#87436); +#87410 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87411,#87412,#87413,#87414, + #87415,#87416,#87417,#87418,#87419,#87420,#87421,#87422,#87423, + #87424,#87425,#87426,#87427,#87428,#87429,#87430,#87431,#87432, + #87433,#87434,#87435),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105479,54 +108468,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85019 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85020 = CARTESIAN_POINT('',(0.740753686904,5.712075427117E-008)); -#85021 = CARTESIAN_POINT('',(0.718425946425,-7.920681094289E-006)); -#85022 = CARTESIAN_POINT('',(0.684729502759,-3.211561474216E-005)); -#85023 = CARTESIAN_POINT('',(0.650851510226,-9.135814826314E-005)); -#85024 = CARTESIAN_POINT('',(0.616817843137,-8.643221197507E-005)); -#85025 = CARTESIAN_POINT('',(0.582648204505,-8.687395637419E-005)); -#85026 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); -#85027 = CARTESIAN_POINT('',(0.513985713406,-8.542361087672E-005)); -#85028 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); -#85029 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); -#85030 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); -#85031 = CARTESIAN_POINT('',(0.375920232966,-8.346461190825E-005)); -#85032 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); -#85033 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); -#85034 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); -#85035 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); -#85036 = CARTESIAN_POINT('',(0.203491552027,-8.179989506537E-005)); -#85037 = CARTESIAN_POINT('',(0.169212469737,-8.226451401244E-005)); -#85038 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); -#85039 = CARTESIAN_POINT('',(0.101018376289,-8.868396576113E-005)); -#85040 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095804E-005)); -#85041 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467402E-005)); -#85042 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134499E-006)); -#85043 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#85044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85045 = ORIENTED_EDGE('',*,*,#76958,.T.); -#85046 = ORIENTED_EDGE('',*,*,#77783,.F.); -#85047 = ORIENTED_EDGE('',*,*,#85048,.F.); -#85048 = EDGE_CURVE('',#78588,#77784,#85049,.T.); -#85049 = SURFACE_CURVE('',#85050,(#85055,#85084),.PCURVE_S1.); -#85050 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#85051,#85052,#85053,#85054 +#87411 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87412 = CARTESIAN_POINT('',(0.740753686904,5.712075427117E-008)); +#87413 = CARTESIAN_POINT('',(0.718425946425,-7.920681094289E-006)); +#87414 = CARTESIAN_POINT('',(0.684729502759,-3.211561474216E-005)); +#87415 = CARTESIAN_POINT('',(0.650851510226,-9.135814826314E-005)); +#87416 = CARTESIAN_POINT('',(0.616817843137,-8.643221197507E-005)); +#87417 = CARTESIAN_POINT('',(0.582648204505,-8.687395637419E-005)); +#87418 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); +#87419 = CARTESIAN_POINT('',(0.513985713406,-8.542361087672E-005)); +#87420 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); +#87421 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); +#87422 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); +#87423 = CARTESIAN_POINT('',(0.375920232966,-8.346461190825E-005)); +#87424 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); +#87425 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); +#87426 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); +#87427 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); +#87428 = CARTESIAN_POINT('',(0.203491552027,-8.179989506537E-005)); +#87429 = CARTESIAN_POINT('',(0.169212469737,-8.226451401244E-005)); +#87430 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); +#87431 = CARTESIAN_POINT('',(0.101018376289,-8.868396576113E-005)); +#87432 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095804E-005)); +#87433 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467402E-005)); +#87434 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134499E-006)); +#87435 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#87436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87437 = ORIENTED_EDGE('',*,*,#79350,.T.); +#87438 = ORIENTED_EDGE('',*,*,#80175,.F.); +#87439 = ORIENTED_EDGE('',*,*,#87440,.F.); +#87440 = EDGE_CURVE('',#80980,#80176,#87441,.T.); +#87441 = SURFACE_CURVE('',#87442,(#87447,#87476),.PCURVE_S1.); +#87442 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87443,#87444,#87445,#87446 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#85051 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); -#85052 = CARTESIAN_POINT('',(1.46,-0.591121542172,0.6)); -#85053 = CARTESIAN_POINT('',(1.401121542172,-0.65,0.6)); -#85054 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); -#85055 = PCURVE('',#77016,#85056); -#85056 = DEFINITIONAL_REPRESENTATION('',(#85057),#85083); -#85057 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85058,#85059,#85060,#85061, - #85062,#85063,#85064,#85065,#85066,#85067,#85068,#85069,#85070, - #85071,#85072,#85073,#85074,#85075,#85076,#85077,#85078,#85079, - #85080,#85081,#85082),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87443 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); +#87444 = CARTESIAN_POINT('',(1.46,-0.591121542172,0.6)); +#87445 = CARTESIAN_POINT('',(1.401121542172,-0.65,0.6)); +#87446 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); +#87447 = PCURVE('',#79408,#87448); +#87448 = DEFINITIONAL_REPRESENTATION('',(#87449),#87475); +#87449 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87450,#87451,#87452,#87453, + #87454,#87455,#87456,#87457,#87458,#87459,#87460,#87461,#87462, + #87463,#87464,#87465,#87466,#87467,#87468,#87469,#87470,#87471, + #87472,#87473,#87474),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -105534,40 +108523,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#85058 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#85059 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); -#85060 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); -#85061 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); -#85062 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); -#85063 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); -#85064 = CARTESIAN_POINT('',(3.469181876599,0.299752403237)); -#85065 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); -#85066 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); -#85067 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); -#85068 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); -#85069 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); -#85070 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); -#85071 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); -#85072 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); -#85073 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); -#85074 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); -#85075 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); -#85076 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); -#85077 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); -#85078 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); -#85079 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); -#85080 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); -#85081 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); -#85082 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#85083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85084 = PCURVE('',#75745,#85085); -#85085 = DEFINITIONAL_REPRESENTATION('',(#85086),#85112); -#85086 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85087,#85088,#85089,#85090, - #85091,#85092,#85093,#85094,#85095,#85096,#85097,#85098,#85099, - #85100,#85101,#85102,#85103,#85104,#85105,#85106,#85107,#85108, - #85109,#85110,#85111),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87450 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#87451 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); +#87452 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); +#87453 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); +#87454 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); +#87455 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); +#87456 = CARTESIAN_POINT('',(3.469181876599,0.299752403237)); +#87457 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); +#87458 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); +#87459 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); +#87460 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); +#87461 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); +#87462 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); +#87463 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); +#87464 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); +#87465 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); +#87466 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); +#87467 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); +#87468 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); +#87469 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); +#87470 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); +#87471 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); +#87472 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); +#87473 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); +#87474 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#87475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87476 = PCURVE('',#78137,#87477); +#87477 = DEFINITIONAL_REPRESENTATION('',(#87478),#87504); +#87478 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87479,#87480,#87481,#87482, + #87483,#87484,#87485,#87486,#87487,#87488,#87489,#87490,#87491, + #87492,#87493,#87494,#87495,#87496,#87497,#87498,#87499,#87500, + #87501,#87502,#87503),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937046,6.009774611072,6.078127285099,6.146479959126, @@ -105575,60 +108564,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#85087 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); -#85088 = CARTESIAN_POINT('',(6.262489231417,0.696143131232)); -#85089 = CARTESIAN_POINT('',(6.220584971823,0.697716602796)); -#85090 = CARTESIAN_POINT('',(6.156280355087,0.699951833424)); -#85091 = CARTESIAN_POINT('',(6.090609548043,0.702037713133)); -#85092 = CARTESIAN_POINT('',(6.02367579713,0.703949755251)); -#85093 = CARTESIAN_POINT('',(5.955596084171,0.705664150716)); -#85094 = CARTESIAN_POINT('',(5.886502464374,0.707158375919)); -#85095 = CARTESIAN_POINT('',(5.816540513026,0.708411883433)); -#85096 = CARTESIAN_POINT('',(5.745868008076,0.709406762975)); -#85097 = CARTESIAN_POINT('',(5.674653029936,0.710128356401)); -#85098 = CARTESIAN_POINT('',(5.603071746948,0.710565783597)); -#85099 = CARTESIAN_POINT('',(5.531305892885,0.710712346536)); -#85100 = CARTESIAN_POINT('',(5.459540038821,0.710565783597)); -#85101 = CARTESIAN_POINT('',(5.387958755834,0.710128356401)); -#85102 = CARTESIAN_POINT('',(5.316743777694,0.709406762975)); -#85103 = CARTESIAN_POINT('',(5.246071272743,0.708411883433)); -#85104 = CARTESIAN_POINT('',(5.176109321395,0.707158375919)); -#85105 = CARTESIAN_POINT('',(5.107015701598,0.705664150716)); -#85106 = CARTESIAN_POINT('',(5.038935988639,0.703949755251)); -#85107 = CARTESIAN_POINT('',(4.972002237726,0.702037713133)); -#85108 = CARTESIAN_POINT('',(4.906331430682,0.699951833424)); -#85109 = CARTESIAN_POINT('',(4.842026813946,0.697716602796)); -#85110 = CARTESIAN_POINT('',(4.800122554352,0.696143131232)); -#85111 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); -#85112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85113 = ADVANCED_FACE('',(#85114),#75745,.T.); -#85114 = FACE_BOUND('',#85115,.T.); -#85115 = EDGE_LOOP('',(#85116,#85117,#85118,#85184,#85185)); -#85116 = ORIENTED_EDGE('',*,*,#78821,.F.); -#85117 = ORIENTED_EDGE('',*,*,#75706,.T.); -#85118 = ORIENTED_EDGE('',*,*,#85119,.T.); -#85119 = EDGE_CURVE('',#75622,#78590,#85120,.T.); -#85120 = SURFACE_CURVE('',#85121,(#85126,#85155),.PCURVE_S1.); -#85121 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#85122,#85123,#85124,#85125 +#87479 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); +#87480 = CARTESIAN_POINT('',(6.262489231417,0.696143131232)); +#87481 = CARTESIAN_POINT('',(6.220584971823,0.697716602796)); +#87482 = CARTESIAN_POINT('',(6.156280355087,0.699951833424)); +#87483 = CARTESIAN_POINT('',(6.090609548043,0.702037713133)); +#87484 = CARTESIAN_POINT('',(6.02367579713,0.703949755251)); +#87485 = CARTESIAN_POINT('',(5.955596084171,0.705664150716)); +#87486 = CARTESIAN_POINT('',(5.886502464374,0.707158375919)); +#87487 = CARTESIAN_POINT('',(5.816540513026,0.708411883433)); +#87488 = CARTESIAN_POINT('',(5.745868008076,0.709406762975)); +#87489 = CARTESIAN_POINT('',(5.674653029936,0.710128356401)); +#87490 = CARTESIAN_POINT('',(5.603071746948,0.710565783597)); +#87491 = CARTESIAN_POINT('',(5.531305892885,0.710712346536)); +#87492 = CARTESIAN_POINT('',(5.459540038821,0.710565783597)); +#87493 = CARTESIAN_POINT('',(5.387958755834,0.710128356401)); +#87494 = CARTESIAN_POINT('',(5.316743777694,0.709406762975)); +#87495 = CARTESIAN_POINT('',(5.246071272743,0.708411883433)); +#87496 = CARTESIAN_POINT('',(5.176109321395,0.707158375919)); +#87497 = CARTESIAN_POINT('',(5.107015701598,0.705664150716)); +#87498 = CARTESIAN_POINT('',(5.038935988639,0.703949755251)); +#87499 = CARTESIAN_POINT('',(4.972002237726,0.702037713133)); +#87500 = CARTESIAN_POINT('',(4.906331430682,0.699951833424)); +#87501 = CARTESIAN_POINT('',(4.842026813946,0.697716602796)); +#87502 = CARTESIAN_POINT('',(4.800122554352,0.696143131232)); +#87503 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); +#87504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87505 = ADVANCED_FACE('',(#87506),#78137,.T.); +#87506 = FACE_BOUND('',#87507,.T.); +#87507 = EDGE_LOOP('',(#87508,#87509,#87510,#87576,#87577)); +#87508 = ORIENTED_EDGE('',*,*,#81213,.F.); +#87509 = ORIENTED_EDGE('',*,*,#78098,.T.); +#87510 = ORIENTED_EDGE('',*,*,#87511,.T.); +#87511 = EDGE_CURVE('',#78014,#80982,#87512,.T.); +#87512 = SURFACE_CURVE('',#87513,(#87518,#87547),.PCURVE_S1.); +#87513 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87514,#87515,#87516,#87517 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.421010862428E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#85122 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#85123 = CARTESIAN_POINT('',(1.320038843607,-0.455581001793,0.132282534) +#87514 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#87515 = CARTESIAN_POINT('',(1.320038843607,-0.455581001793,0.132282534) ); -#85124 = CARTESIAN_POINT('',(1.335122936235,-0.420010423697, +#87516 = CARTESIAN_POINT('',(1.335122936235,-0.420010423697, 0.133952453327)); -#85125 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 +#87517 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757,0.137059047745 )); -#85126 = PCURVE('',#75745,#85127); -#85127 = DEFINITIONAL_REPRESENTATION('',(#85128),#85154); -#85128 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85129,#85130,#85131,#85132, - #85133,#85134,#85135,#85136,#85137,#85138,#85139,#85140,#85141, - #85142,#85143,#85144,#85145,#85146,#85147,#85148,#85149,#85150, - #85151,#85152,#85153),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87518 = PCURVE('',#78137,#87519); +#87519 = DEFINITIONAL_REPRESENTATION('',(#87520),#87546); +#87520 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87521,#87522,#87523,#87524, + #87525,#87526,#87527,#87528,#87529,#87530,#87531,#87532,#87533, + #87534,#87535,#87536,#87537,#87538,#87539,#87540,#87541,#87542, + #87543,#87544,#87545),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.421010862428E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105636,40 +108625,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#85129 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); -#85130 = CARTESIAN_POINT('',(5.542431500119,0.210491435842)); -#85131 = CARTESIAN_POINT('',(5.56475355,0.210477344272)); -#85132 = CARTESIAN_POINT('',(5.598431528687,0.21041327299)); -#85133 = CARTESIAN_POINT('',(5.632287045183,0.210305621442)); -#85134 = CARTESIAN_POINT('',(5.666301906361,0.210153935227)); -#85135 = CARTESIAN_POINT('',(5.700457442157,0.209957894032)); -#85136 = CARTESIAN_POINT('',(5.734734482675,0.209717334008)); -#85137 = CARTESIAN_POINT('',(5.76911344049,0.209432247104)); -#85138 = CARTESIAN_POINT('',(5.803574369467,0.209102784922)); -#85139 = CARTESIAN_POINT('',(5.838097033931,0.208729259627)); -#85140 = CARTESIAN_POINT('',(5.872660978441,0.208312143851)); -#85141 = CARTESIAN_POINT('',(5.907245600032,0.207852069041)); -#85142 = CARTESIAN_POINT('',(5.941830221623,0.207349822399)); -#85143 = CARTESIAN_POINT('',(5.976394166134,0.206806342405)); -#85144 = CARTESIAN_POINT('',(6.010916830598,0.206222712991)); -#85145 = CARTESIAN_POINT('',(6.045377759574,0.205600156427)); -#85146 = CARTESIAN_POINT('',(6.079756717389,0.204940025039)); -#85147 = CARTESIAN_POINT('',(6.114033757907,0.204243791819)); -#85148 = CARTESIAN_POINT('',(6.148189293703,0.203513040252)); -#85149 = CARTESIAN_POINT('',(6.182204154882,0.202749452758)); -#85150 = CARTESIAN_POINT('',(6.216059671377,0.201954800758)); -#85151 = CARTESIAN_POINT('',(6.249737650065,0.201130925764)); -#85152 = CARTESIAN_POINT('',(6.272059699945,0.200563476544)); -#85153 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); -#85154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85155 = PCURVE('',#75660,#85156); -#85156 = DEFINITIONAL_REPRESENTATION('',(#85157),#85183); -#85157 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85158,#85159,#85160,#85161, - #85162,#85163,#85164,#85165,#85166,#85167,#85168,#85169,#85170, - #85171,#85172,#85173,#85174,#85175,#85176,#85177,#85178,#85179, - #85180,#85181,#85182),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87521 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); +#87522 = CARTESIAN_POINT('',(5.542431500119,0.210491435842)); +#87523 = CARTESIAN_POINT('',(5.56475355,0.210477344272)); +#87524 = CARTESIAN_POINT('',(5.598431528687,0.21041327299)); +#87525 = CARTESIAN_POINT('',(5.632287045183,0.210305621442)); +#87526 = CARTESIAN_POINT('',(5.666301906361,0.210153935227)); +#87527 = CARTESIAN_POINT('',(5.700457442157,0.209957894032)); +#87528 = CARTESIAN_POINT('',(5.734734482675,0.209717334008)); +#87529 = CARTESIAN_POINT('',(5.76911344049,0.209432247104)); +#87530 = CARTESIAN_POINT('',(5.803574369467,0.209102784922)); +#87531 = CARTESIAN_POINT('',(5.838097033931,0.208729259627)); +#87532 = CARTESIAN_POINT('',(5.872660978441,0.208312143851)); +#87533 = CARTESIAN_POINT('',(5.907245600032,0.207852069041)); +#87534 = CARTESIAN_POINT('',(5.941830221623,0.207349822399)); +#87535 = CARTESIAN_POINT('',(5.976394166134,0.206806342405)); +#87536 = CARTESIAN_POINT('',(6.010916830598,0.206222712991)); +#87537 = CARTESIAN_POINT('',(6.045377759574,0.205600156427)); +#87538 = CARTESIAN_POINT('',(6.079756717389,0.204940025039)); +#87539 = CARTESIAN_POINT('',(6.114033757907,0.204243791819)); +#87540 = CARTESIAN_POINT('',(6.148189293703,0.203513040252)); +#87541 = CARTESIAN_POINT('',(6.182204154882,0.202749452758)); +#87542 = CARTESIAN_POINT('',(6.216059671377,0.201954800758)); +#87543 = CARTESIAN_POINT('',(6.249737650065,0.201130925764)); +#87544 = CARTESIAN_POINT('',(6.272059699945,0.200563476544)); +#87545 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); +#87546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87547 = PCURVE('',#78052,#87548); +#87548 = DEFINITIONAL_REPRESENTATION('',(#87549),#87575); +#87549 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87550,#87551,#87552,#87553, + #87554,#87555,#87556,#87557,#87558,#87559,#87560,#87561,#87562, + #87563,#87564,#87565,#87566,#87567,#87568,#87569,#87570,#87571, + #87572,#87573,#87574),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.421010862428E-016,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105677,61 +108666,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#85158 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#85159 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#85160 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#85161 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#85162 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#85163 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#85164 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#85165 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#85166 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#85167 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#85168 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#85169 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#85170 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#85171 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#85172 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); -#85173 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); -#85174 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); -#85175 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); -#85176 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); -#85177 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); -#85178 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); -#85179 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); -#85180 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); -#85181 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); -#85182 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85184 = ORIENTED_EDGE('',*,*,#78587,.F.); -#85185 = ORIENTED_EDGE('',*,*,#85048,.T.); -#85186 = ADVANCED_FACE('',(#85187),#77566,.T.); -#85187 = FACE_BOUND('',#85188,.T.); -#85188 = EDGE_LOOP('',(#85189,#85190,#85256,#85257,#85258)); -#85189 = ORIENTED_EDGE('',*,*,#78192,.F.); -#85190 = ORIENTED_EDGE('',*,*,#85191,.T.); -#85191 = EDGE_CURVE('',#78171,#77509,#85192,.T.); -#85192 = SURFACE_CURVE('',#85193,(#85198,#85227),.PCURVE_S1.); -#85193 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#85194,#85195,#85196,#85197 +#87550 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#87551 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#87552 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#87553 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#87554 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#87555 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#87556 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#87557 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#87558 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#87559 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#87560 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#87561 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#87562 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#87563 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#87564 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); +#87565 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); +#87566 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); +#87567 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); +#87568 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); +#87569 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); +#87570 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); +#87571 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); +#87572 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); +#87573 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); +#87574 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87576 = ORIENTED_EDGE('',*,*,#80979,.F.); +#87577 = ORIENTED_EDGE('',*,*,#87440,.T.); +#87578 = ADVANCED_FACE('',(#87579),#79958,.T.); +#87579 = FACE_BOUND('',#87580,.T.); +#87580 = EDGE_LOOP('',(#87581,#87582,#87648,#87649,#87650)); +#87581 = ORIENTED_EDGE('',*,*,#80584,.F.); +#87582 = ORIENTED_EDGE('',*,*,#87583,.T.); +#87583 = EDGE_CURVE('',#80563,#79901,#87584,.T.); +#87584 = SURFACE_CURVE('',#87585,(#87590,#87619),.PCURVE_S1.); +#87585 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87586,#87587,#87588,#87589 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#85194 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) +#87586 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) ); -#85195 = CARTESIAN_POINT('',(1.25680534294,0.551917855478,0.966047546673 +#87587 = CARTESIAN_POINT('',(1.25680534294,0.551917855478,0.966047546673 )); -#85196 = CARTESIAN_POINT('',(1.292375921036,0.53683376285,0.967717466)); -#85197 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) - ); -#85198 = PCURVE('',#77566,#85199); -#85199 = DEFINITIONAL_REPRESENTATION('',(#85200),#85226); -#85200 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85201,#85202,#85203,#85204, - #85205,#85206,#85207,#85208,#85209,#85210,#85211,#85212,#85213, - #85214,#85215,#85216,#85217,#85218,#85219,#85220,#85221,#85222, - #85223,#85224,#85225),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87588 = CARTESIAN_POINT('',(1.292375921036,0.53683376285,0.967717466)); +#87589 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) + ); +#87590 = PCURVE('',#79958,#87591); +#87591 = DEFINITIONAL_REPRESENTATION('',(#87592),#87618); +#87592 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87593,#87594,#87595,#87596, + #87597,#87598,#87599,#87600,#87601,#87602,#87603,#87604,#87605, + #87606,#87607,#87608,#87609,#87610,#87611,#87612,#87613,#87614, + #87615,#87616,#87617),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105739,40 +108728,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85201 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); -#85202 = CARTESIAN_POINT('',(1.648959432235,0.30750240956)); -#85203 = CARTESIAN_POINT('',(1.671281482115,0.308069858779)); -#85204 = CARTESIAN_POINT('',(1.704959460802,0.308893733774)); -#85205 = CARTESIAN_POINT('',(1.738814977298,0.309688385773)); -#85206 = CARTESIAN_POINT('',(1.772829838476,0.310451973268)); -#85207 = CARTESIAN_POINT('',(1.806985374273,0.311182724834)); -#85208 = CARTESIAN_POINT('',(1.84126241479,0.311878958055)); -#85209 = CARTESIAN_POINT('',(1.875641372605,0.312539089442)); -#85210 = CARTESIAN_POINT('',(1.910102301582,0.313161646006)); -#85211 = CARTESIAN_POINT('',(1.944624966046,0.31374527542)); -#85212 = CARTESIAN_POINT('',(1.979188910557,0.314288755414)); -#85213 = CARTESIAN_POINT('',(2.013773532147,0.314791002057)); -#85214 = CARTESIAN_POINT('',(2.048358153738,0.315251076867)); -#85215 = CARTESIAN_POINT('',(2.082922098249,0.315668192643)); -#85216 = CARTESIAN_POINT('',(2.117444762713,0.316041717938)); -#85217 = CARTESIAN_POINT('',(2.15190569169,0.31637118012)); -#85218 = CARTESIAN_POINT('',(2.186284649505,0.316656267024)); -#85219 = CARTESIAN_POINT('',(2.220561690022,0.316896827047)); -#85220 = CARTESIAN_POINT('',(2.254717225818,0.317092868242)); -#85221 = CARTESIAN_POINT('',(2.288732086997,0.317244554458)); -#85222 = CARTESIAN_POINT('',(2.322587603492,0.317352206005)); -#85223 = CARTESIAN_POINT('',(2.35626558218,0.317416277287)); -#85224 = CARTESIAN_POINT('',(2.37858763206,0.317430368857)); -#85225 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); -#85226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85227 = PCURVE('',#77639,#85228); -#85228 = DEFINITIONAL_REPRESENTATION('',(#85229),#85255); -#85229 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85230,#85231,#85232,#85233, - #85234,#85235,#85236,#85237,#85238,#85239,#85240,#85241,#85242, - #85243,#85244,#85245,#85246,#85247,#85248,#85249,#85250,#85251, - #85252,#85253,#85254),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87593 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); +#87594 = CARTESIAN_POINT('',(1.648959432235,0.30750240956)); +#87595 = CARTESIAN_POINT('',(1.671281482115,0.308069858779)); +#87596 = CARTESIAN_POINT('',(1.704959460802,0.308893733774)); +#87597 = CARTESIAN_POINT('',(1.738814977298,0.309688385773)); +#87598 = CARTESIAN_POINT('',(1.772829838476,0.310451973268)); +#87599 = CARTESIAN_POINT('',(1.806985374273,0.311182724834)); +#87600 = CARTESIAN_POINT('',(1.84126241479,0.311878958055)); +#87601 = CARTESIAN_POINT('',(1.875641372605,0.312539089442)); +#87602 = CARTESIAN_POINT('',(1.910102301582,0.313161646006)); +#87603 = CARTESIAN_POINT('',(1.944624966046,0.31374527542)); +#87604 = CARTESIAN_POINT('',(1.979188910557,0.314288755414)); +#87605 = CARTESIAN_POINT('',(2.013773532147,0.314791002057)); +#87606 = CARTESIAN_POINT('',(2.048358153738,0.315251076867)); +#87607 = CARTESIAN_POINT('',(2.082922098249,0.315668192643)); +#87608 = CARTESIAN_POINT('',(2.117444762713,0.316041717938)); +#87609 = CARTESIAN_POINT('',(2.15190569169,0.31637118012)); +#87610 = CARTESIAN_POINT('',(2.186284649505,0.316656267024)); +#87611 = CARTESIAN_POINT('',(2.220561690022,0.316896827047)); +#87612 = CARTESIAN_POINT('',(2.254717225818,0.317092868242)); +#87613 = CARTESIAN_POINT('',(2.288732086997,0.317244554458)); +#87614 = CARTESIAN_POINT('',(2.322587603492,0.317352206005)); +#87615 = CARTESIAN_POINT('',(2.35626558218,0.317416277287)); +#87616 = CARTESIAN_POINT('',(2.37858763206,0.317430368857)); +#87617 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); +#87618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87619 = PCURVE('',#80031,#87620); +#87620 = DEFINITIONAL_REPRESENTATION('',(#87621),#87647); +#87621 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87622,#87623,#87624,#87625, + #87626,#87627,#87628,#87629,#87630,#87631,#87632,#87633,#87634, + #87635,#87636,#87637,#87638,#87639,#87640,#87641,#87642,#87643, + #87644,#87645,#87646),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.565482229898, 5.599658566911,5.633834903925,5.668011240938,5.702187577952, 5.736363914965,5.770540251978,5.804716588992,5.838892926005, @@ -105780,54 +108769,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.009774611072,6.043950948086,6.078127285099,6.112303622113, 6.146479959126,6.180656296139,6.214832633153,6.249008970166, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85230 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85231 = CARTESIAN_POINT('',(0.740753686901,5.702835799539E-008)); -#85232 = CARTESIAN_POINT('',(0.718425946423,-7.920749048097E-006)); -#85233 = CARTESIAN_POINT('',(0.684729502771,-3.211523831336E-005)); -#85234 = CARTESIAN_POINT('',(0.650851510181,-9.135958603284E-005)); -#85235 = CARTESIAN_POINT('',(0.616817843149,-8.643182672584E-005)); -#85236 = CARTESIAN_POINT('',(0.582648204501,-8.687405960141E-005)); -#85237 = CARTESIAN_POINT('',(0.548364026633,-8.593542620295E-005)); -#85238 = CARTESIAN_POINT('',(0.513985713405,-8.54236182881E-005)); -#85239 = CARTESIAN_POINT('',(0.479533105651,-8.485308428819E-005)); -#85240 = CARTESIAN_POINT('',(0.445025477762,-8.435280861445E-005)); -#85241 = CARTESIAN_POINT('',(0.410481676253,-8.388702468049E-005)); -#85242 = CARTESIAN_POINT('',(0.375920232966,-8.346461194645E-005)); -#85243 = CARTESIAN_POINT('',(0.341359494752,-8.308081521476E-005)); -#85244 = CARTESIAN_POINT('',(0.306817755739,-8.274098333401E-005)); -#85245 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); -#85246 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#85247 = CARTESIAN_POINT('',(0.203491552027,-8.17998950653E-005)); -#85248 = CARTESIAN_POINT('',(0.169212469737,-8.226451401252E-005)); -#85249 = CARTESIAN_POINT('',(0.135047837564,-7.965797689883E-005)); -#85250 = CARTESIAN_POINT('',(0.101018376289,-8.868396576193E-005)); -#85251 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095504E-005)); -#85252 = CARTESIAN_POINT('',(3.345266820762E-002,-1.03705246737E-005)); -#85253 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134137E-006)); -#85254 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#85255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85256 = ORIENTED_EDGE('',*,*,#77508,.T.); -#85257 = ORIENTED_EDGE('',*,*,#79559,.F.); -#85258 = ORIENTED_EDGE('',*,*,#85259,.F.); -#85259 = EDGE_CURVE('',#78193,#78683,#85260,.T.); -#85260 = SURFACE_CURVE('',#85261,(#85266,#85295),.PCURVE_S1.); -#85261 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#85262,#85263,#85264,#85265 +#87622 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87623 = CARTESIAN_POINT('',(0.740753686901,5.702835799539E-008)); +#87624 = CARTESIAN_POINT('',(0.718425946423,-7.920749048097E-006)); +#87625 = CARTESIAN_POINT('',(0.684729502771,-3.211523831336E-005)); +#87626 = CARTESIAN_POINT('',(0.650851510181,-9.135958603284E-005)); +#87627 = CARTESIAN_POINT('',(0.616817843149,-8.643182672584E-005)); +#87628 = CARTESIAN_POINT('',(0.582648204501,-8.687405960141E-005)); +#87629 = CARTESIAN_POINT('',(0.548364026633,-8.593542620295E-005)); +#87630 = CARTESIAN_POINT('',(0.513985713405,-8.54236182881E-005)); +#87631 = CARTESIAN_POINT('',(0.479533105651,-8.485308428819E-005)); +#87632 = CARTESIAN_POINT('',(0.445025477762,-8.435280861445E-005)); +#87633 = CARTESIAN_POINT('',(0.410481676253,-8.388702468049E-005)); +#87634 = CARTESIAN_POINT('',(0.375920232966,-8.346461194645E-005)); +#87635 = CARTESIAN_POINT('',(0.341359494752,-8.308081521476E-005)); +#87636 = CARTESIAN_POINT('',(0.306817755739,-8.274098333401E-005)); +#87637 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); +#87638 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#87639 = CARTESIAN_POINT('',(0.203491552027,-8.17998950653E-005)); +#87640 = CARTESIAN_POINT('',(0.169212469737,-8.226451401252E-005)); +#87641 = CARTESIAN_POINT('',(0.135047837564,-7.965797689883E-005)); +#87642 = CARTESIAN_POINT('',(0.101018376289,-8.868396576193E-005)); +#87643 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095504E-005)); +#87644 = CARTESIAN_POINT('',(3.345266820762E-002,-1.03705246737E-005)); +#87645 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134137E-006)); +#87646 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#87647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87648 = ORIENTED_EDGE('',*,*,#79900,.T.); +#87649 = ORIENTED_EDGE('',*,*,#81951,.F.); +#87650 = ORIENTED_EDGE('',*,*,#87651,.F.); +#87651 = EDGE_CURVE('',#80585,#81075,#87652,.T.); +#87652 = SURFACE_CURVE('',#87653,(#87658,#87687),.PCURVE_S1.); +#87653 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87654,#87655,#87656,#87657 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(5.531305892885 ,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#85262 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); -#85263 = CARTESIAN_POINT('',(1.401121542172,0.65,0.6)); -#85264 = CARTESIAN_POINT('',(1.46,0.591121542172,0.6)); -#85265 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); -#85266 = PCURVE('',#77566,#85267); -#85267 = DEFINITIONAL_REPRESENTATION('',(#85268),#85294); -#85268 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85269,#85270,#85271,#85272, - #85273,#85274,#85275,#85276,#85277,#85278,#85279,#85280,#85281, - #85282,#85283,#85284,#85285,#85286,#85287,#85288,#85289,#85290, - #85291,#85292,#85293),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87654 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); +#87655 = CARTESIAN_POINT('',(1.401121542172,0.65,0.6)); +#87656 = CARTESIAN_POINT('',(1.46,0.591121542172,0.6)); +#87657 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); +#87658 = PCURVE('',#79958,#87659); +#87659 = DEFINITIONAL_REPRESENTATION('',(#87660),#87686); +#87660 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87661,#87662,#87663,#87664, + #87665,#87666,#87667,#87668,#87669,#87670,#87671,#87672,#87673, + #87674,#87675,#87676,#87677,#87678,#87679,#87680,#87681,#87682, + #87683,#87684,#87685),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937045,6.009774611072,6.078127285099,6.146479959126, @@ -105835,40 +108824,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#85269 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); -#85270 = CARTESIAN_POINT('',(1.658529900762,0.696143131232)); -#85271 = CARTESIAN_POINT('',(1.700434160356,0.697716602796)); -#85272 = CARTESIAN_POINT('',(1.764738777092,0.699951833424)); -#85273 = CARTESIAN_POINT('',(1.830409584136,0.702037713133)); -#85274 = CARTESIAN_POINT('',(1.89734333505,0.703949755251)); -#85275 = CARTESIAN_POINT('',(1.965423048009,0.705664150716)); -#85276 = CARTESIAN_POINT('',(2.034516667805,0.707158375919)); -#85277 = CARTESIAN_POINT('',(2.104478619153,0.708411883433)); -#85278 = CARTESIAN_POINT('',(2.175151124104,0.709406762975)); -#85279 = CARTESIAN_POINT('',(2.246366102244,0.710128356401)); -#85280 = CARTESIAN_POINT('',(2.317947385231,0.710565783597)); -#85281 = CARTESIAN_POINT('',(2.389713239295,0.710712346536)); -#85282 = CARTESIAN_POINT('',(2.461479093359,0.710565783597)); -#85283 = CARTESIAN_POINT('',(2.533060376346,0.710128356401)); -#85284 = CARTESIAN_POINT('',(2.604275354486,0.709406762975)); -#85285 = CARTESIAN_POINT('',(2.674947859436,0.708411883433)); -#85286 = CARTESIAN_POINT('',(2.744909810785,0.707158375919)); -#85287 = CARTESIAN_POINT('',(2.814003430581,0.705664150716)); -#85288 = CARTESIAN_POINT('',(2.88208314354,0.703949755251)); -#85289 = CARTESIAN_POINT('',(2.949016894454,0.702037713133)); -#85290 = CARTESIAN_POINT('',(3.014687701497,0.699951833424)); -#85291 = CARTESIAN_POINT('',(3.078992318233,0.697716602796)); -#85292 = CARTESIAN_POINT('',(3.120896577828,0.696143131232)); -#85293 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); -#85294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85295 = PCURVE('',#76295,#85296); -#85296 = DEFINITIONAL_REPRESENTATION('',(#85297),#85323); -#85297 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85298,#85299,#85300,#85301, - #85302,#85303,#85304,#85305,#85306,#85307,#85308,#85309,#85310, - #85311,#85312,#85313,#85314,#85315,#85316,#85317,#85318,#85319, - #85320,#85321,#85322),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87661 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); +#87662 = CARTESIAN_POINT('',(1.658529900762,0.696143131232)); +#87663 = CARTESIAN_POINT('',(1.700434160356,0.697716602796)); +#87664 = CARTESIAN_POINT('',(1.764738777092,0.699951833424)); +#87665 = CARTESIAN_POINT('',(1.830409584136,0.702037713133)); +#87666 = CARTESIAN_POINT('',(1.89734333505,0.703949755251)); +#87667 = CARTESIAN_POINT('',(1.965423048009,0.705664150716)); +#87668 = CARTESIAN_POINT('',(2.034516667805,0.707158375919)); +#87669 = CARTESIAN_POINT('',(2.104478619153,0.708411883433)); +#87670 = CARTESIAN_POINT('',(2.175151124104,0.709406762975)); +#87671 = CARTESIAN_POINT('',(2.246366102244,0.710128356401)); +#87672 = CARTESIAN_POINT('',(2.317947385231,0.710565783597)); +#87673 = CARTESIAN_POINT('',(2.389713239295,0.710712346536)); +#87674 = CARTESIAN_POINT('',(2.461479093359,0.710565783597)); +#87675 = CARTESIAN_POINT('',(2.533060376346,0.710128356401)); +#87676 = CARTESIAN_POINT('',(2.604275354486,0.709406762975)); +#87677 = CARTESIAN_POINT('',(2.674947859436,0.708411883433)); +#87678 = CARTESIAN_POINT('',(2.744909810785,0.707158375919)); +#87679 = CARTESIAN_POINT('',(2.814003430581,0.705664150716)); +#87680 = CARTESIAN_POINT('',(2.88208314354,0.703949755251)); +#87681 = CARTESIAN_POINT('',(2.949016894454,0.702037713133)); +#87682 = CARTESIAN_POINT('',(3.014687701497,0.699951833424)); +#87683 = CARTESIAN_POINT('',(3.078992318233,0.697716602796)); +#87684 = CARTESIAN_POINT('',(3.120896577828,0.696143131232)); +#87685 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); +#87686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87687 = PCURVE('',#78687,#87688); +#87688 = DEFINITIONAL_REPRESENTATION('',(#87689),#87715); +#87689 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87690,#87691,#87692,#87693, + #87694,#87695,#87696,#87697,#87698,#87699,#87700,#87701,#87702, + #87703,#87704,#87705,#87706,#87707,#87708,#87709,#87710,#87711, + #87712,#87713,#87714),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885,5.599658566911, 5.668011240938,5.736363914965,5.804716588992,5.873069263019, 5.941421937045,6.009774611072,6.078127285099,6.146479959126, @@ -105876,60 +108865,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.48824332926,6.556596003287,6.624948677314,6.69330135134, 6.761654025367,6.830006699394,6.898359373421,6.966712047448, 7.035064721475),.QUASI_UNIFORM_KNOTS.); -#85298 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#85299 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#85300 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#85301 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#85302 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#85303 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#85304 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#85305 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#85306 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#85307 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#85308 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#85309 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#85310 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#85311 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#85312 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#85313 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#85314 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#85315 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#85316 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#85317 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#85318 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#85319 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#85320 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002)); -#85321 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#85322 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#85323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85324 = ADVANCED_FACE('',(#85325),#76295,.T.); -#85325 = FACE_BOUND('',#85326,.T.); -#85326 = EDGE_LOOP('',(#85327,#85328,#85329,#85395,#85396)); -#85327 = ORIENTED_EDGE('',*,*,#78682,.F.); -#85328 = ORIENTED_EDGE('',*,*,#76256,.T.); -#85329 = ORIENTED_EDGE('',*,*,#85330,.T.); -#85330 = EDGE_CURVE('',#76172,#79069,#85331,.T.); -#85331 = SURFACE_CURVE('',#85332,(#85337,#85366),.PCURVE_S1.); -#85332 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#85333,#85334,#85335,#85336 +#87690 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#87691 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#87692 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#87693 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#87694 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#87695 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#87696 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#87697 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#87698 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#87699 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#87700 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#87701 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#87702 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#87703 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#87704 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#87705 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#87706 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#87707 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#87708 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#87709 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#87710 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#87711 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#87712 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002)); +#87713 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#87714 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#87715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87716 = ADVANCED_FACE('',(#87717),#78687,.T.); +#87717 = FACE_BOUND('',#87718,.T.); +#87718 = EDGE_LOOP('',(#87719,#87720,#87721,#87787,#87788)); +#87719 = ORIENTED_EDGE('',*,*,#81074,.F.); +#87720 = ORIENTED_EDGE('',*,*,#78648,.T.); +#87721 = ORIENTED_EDGE('',*,*,#87722,.T.); +#87722 = EDGE_CURVE('',#78564,#81461,#87723,.T.); +#87723 = SURFACE_CURVE('',#87724,(#87729,#87758),.PCURVE_S1.); +#87724 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#87725,#87726,#87727,#87728 ),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000, 0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#85333 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#85334 = CARTESIAN_POINT('',(1.265581001793,0.510038843607,0.132282534) +#87725 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#87726 = CARTESIAN_POINT('',(1.265581001793,0.510038843607,0.132282534) ); -#85335 = CARTESIAN_POINT('',(1.230010423697,0.525122936235, +#87727 = CARTESIAN_POINT('',(1.230010423697,0.525122936235, 0.133952453327)); -#85336 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) - ); -#85337 = PCURVE('',#76295,#85338); -#85338 = DEFINITIONAL_REPRESENTATION('',(#85339),#85365); -#85339 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85340,#85341,#85342,#85343, - #85344,#85345,#85346,#85347,#85348,#85349,#85350,#85351,#85352, - #85353,#85354,#85355,#85356,#85357,#85358,#85359,#85360,#85361, - #85362,#85363,#85364),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87728 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745) + ); +#87729 = PCURVE('',#78687,#87730); +#87730 = DEFINITIONAL_REPRESENTATION('',(#87731),#87757); +#87731 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87732,#87733,#87734,#87735, + #87736,#87737,#87738,#87739,#87740,#87741,#87742,#87743,#87744, + #87745,#87746,#87747,#87748,#87749,#87750,#87751,#87752,#87753, + #87754,#87755,#87756),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105937,40 +108926,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#85340 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#85341 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); -#85342 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); -#85343 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); -#85344 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); -#85345 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); -#85346 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); -#85347 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); -#85348 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); -#85349 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); -#85350 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); -#85351 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); -#85352 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); -#85353 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); -#85354 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); -#85355 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); -#85356 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); -#85357 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); -#85358 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); -#85359 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); -#85360 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); -#85361 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); -#85362 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); -#85363 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); -#85364 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#85365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85366 = PCURVE('',#76210,#85367); -#85367 = DEFINITIONAL_REPRESENTATION('',(#85368),#85394); -#85368 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85369,#85370,#85371,#85372, - #85373,#85374,#85375,#85376,#85377,#85378,#85379,#85380,#85381, - #85382,#85383,#85384,#85385,#85386,#85387,#85388,#85389,#85390, - #85391,#85392,#85393),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87732 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#87733 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); +#87734 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); +#87735 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); +#87736 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); +#87737 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); +#87738 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); +#87739 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); +#87740 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); +#87741 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); +#87742 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); +#87743 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); +#87744 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); +#87745 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); +#87746 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); +#87747 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); +#87748 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); +#87749 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); +#87750 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); +#87751 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); +#87752 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); +#87753 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); +#87754 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); +#87755 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); +#87756 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#87757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87758 = PCURVE('',#78602,#87759); +#87759 = DEFINITIONAL_REPRESENTATION('',(#87760),#87786); +#87760 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87761,#87762,#87763,#87764, + #87765,#87766,#87767,#87768,#87769,#87770,#87771,#87772,#87773, + #87774,#87775,#87776,#87777,#87778,#87779,#87780,#87781,#87782, + #87783,#87784,#87785),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,3.417633701341E-002, 6.835267402682E-002,0.10252901104,0.136705348054,0.170881685067, 0.20505802208,0.239234359094,0.273410696107,0.307587033121, @@ -105978,55 +108967,55 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.478468718188,0.512645055201,0.546821392215,0.580997729228, 0.615174066241,0.649350403255,0.683526740268,0.717703077282, 0.751879414295),.QUASI_UNIFORM_KNOTS.); -#85369 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#85370 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#85371 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#85372 = CARTESIAN_POINT('',(6.714594636695E-002,1.000054464841)); -#85373 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#85374 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#85375 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#85376 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#85377 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#85378 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#85379 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#85380 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#85381 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#85382 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#85383 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#85384 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#85385 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); -#85386 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); -#85387 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); -#85388 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); -#85389 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); -#85390 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); -#85391 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); -#85392 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); -#85393 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85395 = ORIENTED_EDGE('',*,*,#79068,.F.); -#85396 = ORIENTED_EDGE('',*,*,#85259,.T.); -#85397 = ADVANCED_FACE('',(#85398),#77639,.T.); -#85398 = FACE_BOUND('',#85399,.T.); -#85399 = EDGE_LOOP('',(#85400,#85401,#85402,#85445)); -#85400 = ORIENTED_EDGE('',*,*,#77600,.F.); -#85401 = ORIENTED_EDGE('',*,*,#85191,.F.); -#85402 = ORIENTED_EDGE('',*,*,#85403,.F.); -#85403 = EDGE_CURVE('',#80012,#78171,#85404,.T.); -#85404 = SURFACE_CURVE('',#85405,(#85410,#85439),.PCURVE_S1.); -#85405 = CIRCLE('',#85406,5.E-002); -#85406 = AXIS2_PLACEMENT_3D('',#85407,#85408,#85409); -#85407 = CARTESIAN_POINT('',(1.217861391,0.504453973629,0.95)); -#85408 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#85409 = DIRECTION('',(0.E+000,0.E+000,1.)); -#85410 = PCURVE('',#77639,#85411); -#85411 = DEFINITIONAL_REPRESENTATION('',(#85412),#85438); -#85412 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85413,#85414,#85415,#85416, - #85417,#85418,#85419,#85420,#85421,#85422,#85423,#85424,#85425, - #85426,#85427,#85428,#85429,#85430,#85431,#85432,#85433,#85434, - #85435,#85436,#85437),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87761 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#87762 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#87763 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#87764 = CARTESIAN_POINT('',(6.714594636695E-002,1.000054464841)); +#87765 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#87766 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#87767 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#87768 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#87769 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#87770 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#87771 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#87772 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#87773 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#87774 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#87775 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#87776 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#87777 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); +#87778 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); +#87779 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); +#87780 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); +#87781 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); +#87782 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); +#87783 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); +#87784 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); +#87785 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87787 = ORIENTED_EDGE('',*,*,#81460,.F.); +#87788 = ORIENTED_EDGE('',*,*,#87651,.T.); +#87789 = ADVANCED_FACE('',(#87790),#80031,.T.); +#87790 = FACE_BOUND('',#87791,.T.); +#87791 = EDGE_LOOP('',(#87792,#87793,#87794,#87837)); +#87792 = ORIENTED_EDGE('',*,*,#79992,.F.); +#87793 = ORIENTED_EDGE('',*,*,#87583,.F.); +#87794 = ORIENTED_EDGE('',*,*,#87795,.F.); +#87795 = EDGE_CURVE('',#82404,#80563,#87796,.T.); +#87796 = SURFACE_CURVE('',#87797,(#87802,#87831),.PCURVE_S1.); +#87797 = CIRCLE('',#87798,5.E-002); +#87798 = AXIS2_PLACEMENT_3D('',#87799,#87800,#87801); +#87799 = CARTESIAN_POINT('',(1.217861391,0.504453973629,0.95)); +#87800 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#87801 = DIRECTION('',(0.E+000,0.E+000,1.)); +#87802 = PCURVE('',#80031,#87803); +#87803 = DEFINITIONAL_REPRESENTATION('',(#87804),#87830); +#87804 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87805,#87806,#87807,#87808, + #87809,#87810,#87811,#87812,#87813,#87814,#87815,#87816,#87817, + #87818,#87819,#87820,#87821,#87822,#87823,#87824,#87825,#87826, + #87827,#87828,#87829),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(0.E+000,5.949986086344E-002,0.118999721727, 0.17849958259,0.237999443454,0.297499304317,0.356999165181, 0.416499026044,0.475998886908,0.535498747771,0.594998608634, @@ -106034,80 +109023,80 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.892497912952,0.951997773815,1.011497634679,1.070997495542, 1.130497356405,1.189997217269,1.249497078132,1.308996938996), .QUASI_UNIFORM_KNOTS.); -#85413 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85414 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#85415 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#85416 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#85417 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#85418 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#85419 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#85420 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#85421 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#85422 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#85423 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#85424 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#85425 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#85426 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#85427 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#85428 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#85429 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#85430 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#85431 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#85432 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#85433 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#85434 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#85435 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#85436 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#85437 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85439 = PCURVE('',#77494,#85440); -#85440 = DEFINITIONAL_REPRESENTATION('',(#85441),#85444); -#85441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85442,#85443),.UNSPECIFIED., +#87805 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87806 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#87807 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#87808 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#87809 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#87810 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#87811 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#87812 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#87813 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#87814 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#87815 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#87816 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#87817 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#87818 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#87819 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#87820 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#87821 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#87822 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#87823 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#87824 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#87825 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#87826 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#87827 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#87828 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#87829 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87831 = PCURVE('',#79886,#87832); +#87832 = DEFINITIONAL_REPRESENTATION('',(#87833),#87836); +#87833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#87834,#87835),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,1.308996938996),.PIECEWISE_BEZIER_KNOTS.); -#85442 = CARTESIAN_POINT('',(0.E+000,0.242138609)); -#85443 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); -#85444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85445 = ORIENTED_EDGE('',*,*,#80011,.F.); -#85446 = ADVANCED_FACE('',(#85447),#77494,.T.); -#85447 = FACE_BOUND('',#85448,.T.); -#85448 = EDGE_LOOP('',(#85449,#85450,#85451,#85452)); -#85449 = ORIENTED_EDGE('',*,*,#85403,.T.); -#85450 = ORIENTED_EDGE('',*,*,#78170,.F.); -#85451 = ORIENTED_EDGE('',*,*,#77457,.F.); -#85452 = ORIENTED_EDGE('',*,*,#80058,.F.); -#85453 = ADVANCED_FACE('',(#85454),#77769,.T.); -#85454 = FACE_BOUND('',#85455,.T.); -#85455 = EDGE_LOOP('',(#85456,#85457,#85458,#85501)); -#85456 = ORIENTED_EDGE('',*,*,#77732,.T.); -#85457 = ORIENTED_EDGE('',*,*,#79967,.F.); -#85458 = ORIENTED_EDGE('',*,*,#85459,.F.); -#85459 = EDGE_CURVE('',#79603,#79921,#85460,.T.); -#85460 = SURFACE_CURVE('',#85461,(#85466,#85472),.PCURVE_S1.); -#85461 = CIRCLE('',#85462,5.E-002); -#85462 = AXIS2_PLACEMENT_3D('',#85463,#85464,#85465); -#85463 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,0.95)); -#85464 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#85465 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#85466 = PCURVE('',#77769,#85467); -#85467 = DEFINITIONAL_REPRESENTATION('',(#85468),#85471); -#85468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85469,#85470),.UNSPECIFIED., +#87834 = CARTESIAN_POINT('',(0.E+000,0.242138609)); +#87835 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); +#87836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87837 = ORIENTED_EDGE('',*,*,#82403,.F.); +#87838 = ADVANCED_FACE('',(#87839),#79886,.T.); +#87839 = FACE_BOUND('',#87840,.T.); +#87840 = EDGE_LOOP('',(#87841,#87842,#87843,#87844)); +#87841 = ORIENTED_EDGE('',*,*,#87795,.T.); +#87842 = ORIENTED_EDGE('',*,*,#80562,.F.); +#87843 = ORIENTED_EDGE('',*,*,#79849,.F.); +#87844 = ORIENTED_EDGE('',*,*,#82450,.F.); +#87845 = ADVANCED_FACE('',(#87846),#80161,.T.); +#87846 = FACE_BOUND('',#87847,.T.); +#87847 = EDGE_LOOP('',(#87848,#87849,#87850,#87893)); +#87848 = ORIENTED_EDGE('',*,*,#80124,.T.); +#87849 = ORIENTED_EDGE('',*,*,#82359,.F.); +#87850 = ORIENTED_EDGE('',*,*,#87851,.F.); +#87851 = EDGE_CURVE('',#81995,#82313,#87852,.T.); +#87852 = SURFACE_CURVE('',#87853,(#87858,#87864),.PCURVE_S1.); +#87853 = CIRCLE('',#87854,5.E-002); +#87854 = AXIS2_PLACEMENT_3D('',#87855,#87856,#87857); +#87855 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,0.95)); +#87856 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#87857 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#87858 = PCURVE('',#80161,#87859); +#87859 = DEFINITIONAL_REPRESENTATION('',(#87860),#87863); +#87860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#87861,#87862),.UNSPECIFIED., .F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#85469 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); -#85470 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); -#85471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#87861 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); +#87862 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); +#87863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#85472 = PCURVE('',#77089,#85473); -#85473 = DEFINITIONAL_REPRESENTATION('',(#85474),#85500); -#85474 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85475,#85476,#85477,#85478, - #85479,#85480,#85481,#85482,#85483,#85484,#85485,#85486,#85487, - #85488,#85489,#85490,#85491,#85492,#85493,#85494,#85495,#85496, - #85497,#85498,#85499),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87864 = PCURVE('',#79481,#87865); +#87865 = DEFINITIONAL_REPRESENTATION('',(#87866),#87892); +#87866 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87867,#87868,#87869,#87870, + #87871,#87872,#87873,#87874,#87875,#87876,#87877,#87878,#87879, + #87880,#87881,#87882,#87883,#87884,#87885,#87886,#87887,#87888, + #87889,#87890,#87891),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594,1.892095575457, 1.951595436321,2.011095297184,2.070595158048,2.130095018911, 2.189594879775,2.249094740638,2.308594601502,2.368094462365, @@ -106115,54 +109104,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.665593766682,2.725093627546,2.784593488409,2.844093349273, 2.903593210136,2.963093070999,3.022592931863,3.082092792726, 3.14159265359),.QUASI_UNIFORM_KNOTS.); -#85475 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85476 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#85477 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#85478 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#85479 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#85480 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#85481 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#85482 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#85483 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#85484 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#85485 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#85486 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#85487 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#85488 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#85489 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#85490 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#85491 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#85492 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#85493 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#85494 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#85495 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#85496 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#85497 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#85498 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#85499 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85501 = ORIENTED_EDGE('',*,*,#79602,.F.); -#85502 = ADVANCED_FACE('',(#85503),#77364,.T.); -#85503 = FACE_BOUND('',#85504,.T.); -#85504 = EDGE_LOOP('',(#85505,#85506,#85507,#85550)); -#85505 = ORIENTED_EDGE('',*,*,#77325,.F.); -#85506 = ORIENTED_EDGE('',*,*,#84769,.F.); -#85507 = ORIENTED_EDGE('',*,*,#85508,.F.); -#85508 = EDGE_CURVE('',#79807,#79715,#85509,.T.); -#85509 = SURFACE_CURVE('',#85510,(#85515,#85544),.PCURVE_S1.); -#85510 = CIRCLE('',#85511,5.E-002); -#85511 = AXIS2_PLACEMENT_3D('',#85512,#85513,#85514); -#85512 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,0.95)); -#85513 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#85514 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#85515 = PCURVE('',#77364,#85516); -#85516 = DEFINITIONAL_REPRESENTATION('',(#85517),#85543); -#85517 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85518,#85519,#85520,#85521, - #85522,#85523,#85524,#85525,#85526,#85527,#85528,#85529,#85530, - #85531,#85532,#85533,#85534,#85535,#85536,#85537,#85538,#85539, - #85540,#85541,#85542),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87867 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87868 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#87869 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#87870 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#87871 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#87872 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#87873 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#87874 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#87875 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#87876 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#87877 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#87878 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#87879 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#87880 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#87881 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#87882 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#87883 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#87884 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#87885 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#87886 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#87887 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#87888 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#87889 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#87890 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#87891 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87893 = ORIENTED_EDGE('',*,*,#81994,.F.); +#87894 = ADVANCED_FACE('',(#87895),#79756,.T.); +#87895 = FACE_BOUND('',#87896,.T.); +#87896 = EDGE_LOOP('',(#87897,#87898,#87899,#87942)); +#87897 = ORIENTED_EDGE('',*,*,#79717,.F.); +#87898 = ORIENTED_EDGE('',*,*,#87161,.F.); +#87899 = ORIENTED_EDGE('',*,*,#87900,.F.); +#87900 = EDGE_CURVE('',#82199,#82107,#87901,.T.); +#87901 = SURFACE_CURVE('',#87902,(#87907,#87936),.PCURVE_S1.); +#87902 = CIRCLE('',#87903,5.E-002); +#87903 = AXIS2_PLACEMENT_3D('',#87904,#87905,#87906); +#87904 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,0.95)); +#87905 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#87906 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#87907 = PCURVE('',#79756,#87908); +#87908 = DEFINITIONAL_REPRESENTATION('',(#87909),#87935); +#87909 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87910,#87911,#87912,#87913, + #87914,#87915,#87916,#87917,#87918,#87919,#87920,#87921,#87922, + #87923,#87924,#87925,#87926,#87927,#87928,#87929,#87930,#87931, + #87932,#87933,#87934),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359,3.201092514453,3.260592375317 ,3.32009223618,3.379592097044,3.439091957907,3.49859181877, 3.558091679634,3.617591540497,3.677091401361,3.736591262224, @@ -106170,88 +109159,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.034090566541,4.093590427405,4.153090288268,4.212590149132, 4.272090009995,4.331589870859,4.391089731722,4.450589592586), .QUASI_UNIFORM_KNOTS.); -#85518 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85519 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#85520 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#85521 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#85522 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#85523 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#85524 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#85525 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#85526 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#85527 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#85528 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#85529 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#85530 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#85531 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#85532 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#85533 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#85534 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#85535 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#85536 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#85537 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#85538 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#85539 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#85540 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#85541 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#85542 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85544 = PCURVE('',#76921,#85545); -#85545 = DEFINITIONAL_REPRESENTATION('',(#85546),#85549); -#85546 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85547,#85548),.UNSPECIFIED., +#87910 = CARTESIAN_POINT('',(0.751879414295,1.)); +#87911 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#87912 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#87913 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#87914 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#87915 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#87916 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#87917 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#87918 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#87919 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#87920 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#87921 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#87922 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#87923 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#87924 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#87925 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#87926 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#87927 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#87928 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#87929 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#87930 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#87931 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#87932 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#87933 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#87934 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87936 = PCURVE('',#79313,#87937); +#87937 = DEFINITIONAL_REPRESENTATION('',(#87938),#87941); +#87938 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#87939,#87940),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,4.450589592586), .PIECEWISE_BEZIER_KNOTS.); -#85547 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); -#85548 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); -#85549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85550 = ORIENTED_EDGE('',*,*,#80079,.F.); -#85551 = ADVANCED_FACE('',(#85552),#77089,.T.); -#85552 = FACE_BOUND('',#85553,.T.); -#85553 = EDGE_LOOP('',(#85554,#85555,#85556,#85557)); -#85554 = ORIENTED_EDGE('',*,*,#77050,.F.); -#85555 = ORIENTED_EDGE('',*,*,#84980,.F.); -#85556 = ORIENTED_EDGE('',*,*,#85459,.T.); -#85557 = ORIENTED_EDGE('',*,*,#79920,.F.); -#85558 = ADVANCED_FACE('',(#85559),#76921,.T.); -#85559 = FACE_BOUND('',#85560,.T.); -#85560 = EDGE_LOOP('',(#85561,#85562,#85563,#85564)); -#85561 = ORIENTED_EDGE('',*,*,#85508,.T.); -#85562 = ORIENTED_EDGE('',*,*,#79714,.F.); -#85563 = ORIENTED_EDGE('',*,*,#76884,.F.); -#85564 = ORIENTED_EDGE('',*,*,#79806,.F.); -#85565 = ADVANCED_FACE('',(#85566),#77219,.T.); -#85566 = FACE_BOUND('',#85567,.T.); -#85567 = EDGE_LOOP('',(#85568,#85569,#85570,#85613)); -#85568 = ORIENTED_EDGE('',*,*,#77182,.T.); -#85569 = ORIENTED_EDGE('',*,*,#79899,.F.); -#85570 = ORIENTED_EDGE('',*,*,#85571,.F.); -#85571 = EDGE_CURVE('',#77811,#79853,#85572,.T.); -#85572 = SURFACE_CURVE('',#85573,(#85578,#85584),.PCURVE_S1.); -#85573 = CIRCLE('',#85574,5.E-002); -#85574 = AXIS2_PLACEMENT_3D('',#85575,#85576,#85577); -#85575 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,0.95)); -#85576 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#85577 = DIRECTION('',(0.E+000,0.E+000,1.)); -#85578 = PCURVE('',#77219,#85579); -#85579 = DEFINITIONAL_REPRESENTATION('',(#85580),#85583); -#85580 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85581,#85582),.UNSPECIFIED., +#87939 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); +#87940 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); +#87941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#87942 = ORIENTED_EDGE('',*,*,#82471,.F.); +#87943 = ADVANCED_FACE('',(#87944),#79481,.T.); +#87944 = FACE_BOUND('',#87945,.T.); +#87945 = EDGE_LOOP('',(#87946,#87947,#87948,#87949)); +#87946 = ORIENTED_EDGE('',*,*,#79442,.F.); +#87947 = ORIENTED_EDGE('',*,*,#87372,.F.); +#87948 = ORIENTED_EDGE('',*,*,#87851,.T.); +#87949 = ORIENTED_EDGE('',*,*,#82312,.F.); +#87950 = ADVANCED_FACE('',(#87951),#79313,.T.); +#87951 = FACE_BOUND('',#87952,.T.); +#87952 = EDGE_LOOP('',(#87953,#87954,#87955,#87956)); +#87953 = ORIENTED_EDGE('',*,*,#87900,.T.); +#87954 = ORIENTED_EDGE('',*,*,#82106,.F.); +#87955 = ORIENTED_EDGE('',*,*,#79276,.F.); +#87956 = ORIENTED_EDGE('',*,*,#82198,.F.); +#87957 = ADVANCED_FACE('',(#87958),#79611,.T.); +#87958 = FACE_BOUND('',#87959,.T.); +#87959 = EDGE_LOOP('',(#87960,#87961,#87962,#88005)); +#87960 = ORIENTED_EDGE('',*,*,#79574,.T.); +#87961 = ORIENTED_EDGE('',*,*,#82291,.F.); +#87962 = ORIENTED_EDGE('',*,*,#87963,.F.); +#87963 = EDGE_CURVE('',#80203,#82245,#87964,.T.); +#87964 = SURFACE_CURVE('',#87965,(#87970,#87976),.PCURVE_S1.); +#87965 = CIRCLE('',#87966,5.E-002); +#87966 = AXIS2_PLACEMENT_3D('',#87967,#87968,#87969); +#87967 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,0.95)); +#87968 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#87969 = DIRECTION('',(0.E+000,0.E+000,1.)); +#87970 = PCURVE('',#79611,#87971); +#87971 = DEFINITIONAL_REPRESENTATION('',(#87972),#87975); +#87972 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#87973,#87974),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#85581 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); -#85582 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); -#85583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#87973 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); +#87974 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); +#87975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#85584 = PCURVE('',#76786,#85585); -#85585 = DEFINITIONAL_REPRESENTATION('',(#85586),#85612); -#85586 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85587,#85588,#85589,#85590, - #85591,#85592,#85593,#85594,#85595,#85596,#85597,#85598,#85599, - #85600,#85601,#85602,#85603,#85604,#85605,#85606,#85607,#85608, - #85609,#85610,#85611),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87976 = PCURVE('',#79178,#87977); +#87977 = DEFINITIONAL_REPRESENTATION('',(#87978),#88004); +#87978 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#87979,#87980,#87981,#87982, + #87983,#87984,#87985,#87986,#87987,#87988,#87989,#87990,#87991, + #87992,#87993,#87994,#87995,#87996,#87997,#87998,#87999,#88000, + #88001,#88002,#88003),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -106259,61 +109248,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85587 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85588 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#85589 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#85590 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#85591 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#85592 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#85593 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#85594 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#85595 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#85596 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#85597 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#85598 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#85599 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#85600 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#85601 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#85602 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#85603 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#85604 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#85605 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#85606 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#85607 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#85608 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#85609 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#85610 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#85611 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85613 = ORIENTED_EDGE('',*,*,#77810,.F.); -#85614 = ADVANCED_FACE('',(#85615),#76786,.T.); -#85615 = FACE_BOUND('',#85616,.T.); -#85616 = EDGE_LOOP('',(#85617,#85618,#85619,#85620)); -#85617 = ORIENTED_EDGE('',*,*,#76747,.F.); -#85618 = ORIENTED_EDGE('',*,*,#84558,.F.); -#85619 = ORIENTED_EDGE('',*,*,#85571,.T.); -#85620 = ORIENTED_EDGE('',*,*,#79852,.F.); -#85621 = ADVANCED_FACE('',(#85622),#76485,.T.); -#85622 = FACE_BOUND('',#85623,.T.); -#85623 = EDGE_LOOP('',(#85624,#85625,#85626,#85669)); -#85624 = ORIENTED_EDGE('',*,*,#76446,.F.); -#85625 = ORIENTED_EDGE('',*,*,#79442,.F.); -#85626 = ORIENTED_EDGE('',*,*,#85627,.F.); -#85627 = EDGE_CURVE('',#78925,#79398,#85628,.T.); -#85628 = SURFACE_CURVE('',#85629,(#85634,#85663),.PCURVE_S1.); -#85629 = CIRCLE('',#85630,5.E-002); -#85630 = AXIS2_PLACEMENT_3D('',#85631,#85632,#85633); -#85631 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,0.15)); -#85632 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#85633 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#85634 = PCURVE('',#76485,#85635); -#85635 = DEFINITIONAL_REPRESENTATION('',(#85636),#85662); -#85636 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85637,#85638,#85639,#85640, - #85641,#85642,#85643,#85644,#85645,#85646,#85647,#85648,#85649, - #85650,#85651,#85652,#85653,#85654,#85655,#85656,#85657,#85658, - #85659,#85660,#85661),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#87979 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#87980 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#87981 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#87982 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#87983 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#87984 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#87985 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#87986 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#87987 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#87988 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#87989 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#87990 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#87991 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#87992 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#87993 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#87994 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#87995 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#87996 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#87997 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#87998 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#87999 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#88000 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#88001 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#88002 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#88003 = CARTESIAN_POINT('',(0.751879414295,1.)); +#88004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88005 = ORIENTED_EDGE('',*,*,#80202,.F.); +#88006 = ADVANCED_FACE('',(#88007),#79178,.T.); +#88007 = FACE_BOUND('',#88008,.T.); +#88008 = EDGE_LOOP('',(#88009,#88010,#88011,#88012)); +#88009 = ORIENTED_EDGE('',*,*,#79139,.F.); +#88010 = ORIENTED_EDGE('',*,*,#86950,.F.); +#88011 = ORIENTED_EDGE('',*,*,#87963,.T.); +#88012 = ORIENTED_EDGE('',*,*,#82244,.F.); +#88013 = ADVANCED_FACE('',(#88014),#78877,.T.); +#88014 = FACE_BOUND('',#88015,.T.); +#88015 = EDGE_LOOP('',(#88016,#88017,#88018,#88061)); +#88016 = ORIENTED_EDGE('',*,*,#78838,.F.); +#88017 = ORIENTED_EDGE('',*,*,#81834,.F.); +#88018 = ORIENTED_EDGE('',*,*,#88019,.F.); +#88019 = EDGE_CURVE('',#81317,#81790,#88020,.T.); +#88020 = SURFACE_CURVE('',#88021,(#88026,#88055),.PCURVE_S1.); +#88021 = CIRCLE('',#88022,5.E-002); +#88022 = AXIS2_PLACEMENT_3D('',#88023,#88024,#88025); +#88023 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,0.15)); +#88024 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88025 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88026 = PCURVE('',#78877,#88027); +#88027 = DEFINITIONAL_REPRESENTATION('',(#88028),#88054); +#88028 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88029,#88030,#88031,#88032, + #88033,#88034,#88035,#88036,#88037,#88038,#88039,#88040,#88041, + #88042,#88043,#88044,#88045,#88046,#88047,#88048,#88049,#88050, + #88051,#88052,#88053),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -106321,64 +109310,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85637 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85638 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#85639 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#85640 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#85641 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#85642 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#85643 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#85644 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#85645 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#85646 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#85647 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#85648 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#85649 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#85650 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#85651 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#85652 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#85653 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#85654 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#85655 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#85656 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#85657 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#85658 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); -#85659 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#85660 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#85661 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85663 = PCURVE('',#76091,#85664); -#85664 = DEFINITIONAL_REPRESENTATION('',(#85665),#85668); -#85665 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85666,#85667),.UNSPECIFIED., +#88029 = CARTESIAN_POINT('',(0.751879414295,1.)); +#88030 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#88031 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#88032 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#88033 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#88034 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#88035 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#88036 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#88037 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#88038 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#88039 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#88040 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#88041 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#88042 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#88043 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#88044 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#88045 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#88046 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#88047 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#88048 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#88049 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#88050 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); +#88051 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#88052 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#88053 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#88054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88055 = PCURVE('',#78483,#88056); +#88056 = DEFINITIONAL_REPRESENTATION('',(#88057),#88060); +#88057 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88058,#88059),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#85666 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#85667 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#85668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85669 = ORIENTED_EDGE('',*,*,#84908,.F.); -#85670 = ADVANCED_FACE('',(#85671),#76641,.T.); -#85671 = FACE_BOUND('',#85672,.T.); -#85672 = EDGE_LOOP('',(#85673,#85674,#85675,#85741)); -#85673 = ORIENTED_EDGE('',*,*,#76604,.T.); -#85674 = ORIENTED_EDGE('',*,*,#79113,.F.); -#85675 = ORIENTED_EDGE('',*,*,#85676,.F.); -#85676 = EDGE_CURVE('',#79489,#79069,#85677,.T.); -#85677 = SURFACE_CURVE('',#85678,(#85683,#85712),.PCURVE_S1.); -#85678 = CIRCLE('',#85679,5.E-002); -#85679 = AXIS2_PLACEMENT_3D('',#85680,#85681,#85682); -#85680 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,0.15)); -#85681 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); -#85682 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); -#85683 = PCURVE('',#76641,#85684); -#85684 = DEFINITIONAL_REPRESENTATION('',(#85685),#85711); -#85685 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85686,#85687,#85688,#85689, - #85690,#85691,#85692,#85693,#85694,#85695,#85696,#85697,#85698, - #85699,#85700,#85701,#85702,#85703,#85704,#85705,#85706,#85707, - #85708,#85709,#85710),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#88058 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#88059 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#88060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88061 = ORIENTED_EDGE('',*,*,#87300,.F.); +#88062 = ADVANCED_FACE('',(#88063),#79033,.T.); +#88063 = FACE_BOUND('',#88064,.T.); +#88064 = EDGE_LOOP('',(#88065,#88066,#88067,#88133)); +#88065 = ORIENTED_EDGE('',*,*,#78996,.T.); +#88066 = ORIENTED_EDGE('',*,*,#81505,.F.); +#88067 = ORIENTED_EDGE('',*,*,#88068,.F.); +#88068 = EDGE_CURVE('',#81881,#81461,#88069,.T.); +#88069 = SURFACE_CURVE('',#88070,(#88075,#88104),.PCURVE_S1.); +#88070 = CIRCLE('',#88071,5.E-002); +#88071 = AXIS2_PLACEMENT_3D('',#88072,#88073,#88074); +#88072 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,0.15)); +#88073 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); +#88074 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); +#88075 = PCURVE('',#79033,#88076); +#88076 = DEFINITIONAL_REPRESENTATION('',(#88077),#88103); +#88077 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88078,#88079,#88080,#88081, + #88082,#88083,#88084,#88085,#88086,#88087,#88088,#88089,#88090, + #88091,#88092,#88093,#88094,#88095,#88096,#88097,#88098,#88099, + #88100,#88101,#88102),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.771888841248, 4.831388702112,4.890888562975,4.950388423838,5.009888284702, 5.069388145565,5.128888006429,5.188387867292,5.247887728156, @@ -106386,40 +109375,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.545387032473,5.604886893336,5.6643867542,5.723886615063, 5.783386475927,5.84288633679,5.902386197654,5.961886058517, 6.02138591938),.QUASI_UNIFORM_KNOTS.); -#85686 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); -#85687 = CARTESIAN_POINT('',(1.983328695448E-002,2.651066471757)); -#85688 = CARTESIAN_POINT('',(5.949986086344E-002,2.651066471757)); -#85689 = CARTESIAN_POINT('',(0.118999721727,2.651066471757)); -#85690 = CARTESIAN_POINT('',(0.17849958259,2.651066471757)); -#85691 = CARTESIAN_POINT('',(0.237999443454,2.651066471757)); -#85692 = CARTESIAN_POINT('',(0.297499304317,2.651066471757)); -#85693 = CARTESIAN_POINT('',(0.356999165181,2.651066471757)); -#85694 = CARTESIAN_POINT('',(0.416499026044,2.651066471757)); -#85695 = CARTESIAN_POINT('',(0.475998886908,2.651066471757)); -#85696 = CARTESIAN_POINT('',(0.535498747771,2.651066471757)); -#85697 = CARTESIAN_POINT('',(0.594998608634,2.651066471757)); -#85698 = CARTESIAN_POINT('',(0.654498469498,2.651066471757)); -#85699 = CARTESIAN_POINT('',(0.713998330361,2.651066471757)); -#85700 = CARTESIAN_POINT('',(0.773498191225,2.651066471757)); -#85701 = CARTESIAN_POINT('',(0.832998052088,2.651066471757)); -#85702 = CARTESIAN_POINT('',(0.892497912952,2.651066471757)); -#85703 = CARTESIAN_POINT('',(0.951997773815,2.651066471757)); -#85704 = CARTESIAN_POINT('',(1.011497634679,2.651066471757)); -#85705 = CARTESIAN_POINT('',(1.070997495542,2.651066471757)); -#85706 = CARTESIAN_POINT('',(1.130497356405,2.651066471757)); -#85707 = CARTESIAN_POINT('',(1.189997217269,2.651066471757)); -#85708 = CARTESIAN_POINT('',(1.249497078132,2.651066471757)); -#85709 = CARTESIAN_POINT('',(1.289163652041,2.651066471757)); -#85710 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); -#85711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85712 = PCURVE('',#76210,#85713); -#85713 = DEFINITIONAL_REPRESENTATION('',(#85714),#85740); -#85714 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85715,#85716,#85717,#85718, - #85719,#85720,#85721,#85722,#85723,#85724,#85725,#85726,#85727, - #85728,#85729,#85730,#85731,#85732,#85733,#85734,#85735,#85736, - #85737,#85738,#85739),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#88078 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); +#88079 = CARTESIAN_POINT('',(1.983328695448E-002,2.651066471757)); +#88080 = CARTESIAN_POINT('',(5.949986086344E-002,2.651066471757)); +#88081 = CARTESIAN_POINT('',(0.118999721727,2.651066471757)); +#88082 = CARTESIAN_POINT('',(0.17849958259,2.651066471757)); +#88083 = CARTESIAN_POINT('',(0.237999443454,2.651066471757)); +#88084 = CARTESIAN_POINT('',(0.297499304317,2.651066471757)); +#88085 = CARTESIAN_POINT('',(0.356999165181,2.651066471757)); +#88086 = CARTESIAN_POINT('',(0.416499026044,2.651066471757)); +#88087 = CARTESIAN_POINT('',(0.475998886908,2.651066471757)); +#88088 = CARTESIAN_POINT('',(0.535498747771,2.651066471757)); +#88089 = CARTESIAN_POINT('',(0.594998608634,2.651066471757)); +#88090 = CARTESIAN_POINT('',(0.654498469498,2.651066471757)); +#88091 = CARTESIAN_POINT('',(0.713998330361,2.651066471757)); +#88092 = CARTESIAN_POINT('',(0.773498191225,2.651066471757)); +#88093 = CARTESIAN_POINT('',(0.832998052088,2.651066471757)); +#88094 = CARTESIAN_POINT('',(0.892497912952,2.651066471757)); +#88095 = CARTESIAN_POINT('',(0.951997773815,2.651066471757)); +#88096 = CARTESIAN_POINT('',(1.011497634679,2.651066471757)); +#88097 = CARTESIAN_POINT('',(1.070997495542,2.651066471757)); +#88098 = CARTESIAN_POINT('',(1.130497356405,2.651066471757)); +#88099 = CARTESIAN_POINT('',(1.189997217269,2.651066471757)); +#88100 = CARTESIAN_POINT('',(1.249497078132,2.651066471757)); +#88101 = CARTESIAN_POINT('',(1.289163652041,2.651066471757)); +#88102 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); +#88103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88104 = PCURVE('',#78602,#88105); +#88105 = DEFINITIONAL_REPRESENTATION('',(#88106),#88132); +#88106 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88107,#88108,#88109,#88110, + #88111,#88112,#88113,#88114,#88115,#88116,#88117,#88118,#88119, + #88120,#88121,#88122,#88123,#88124,#88125,#88126,#88127,#88128, + #88129,#88130,#88131),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.771888841248, 4.831388702112,4.890888562975,4.950388423838,5.009888284702, 5.069388145565,5.128888006429,5.188387867292,5.247887728156, @@ -106427,68 +109416,68 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.545387032473,5.604886893336,5.6643867542,5.723886615063, 5.783386475927,5.84288633679,5.902386197654,5.961886058517, 6.02138591938),.QUASI_UNIFORM_KNOTS.); -#85715 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85716 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#85717 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#85718 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#85719 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#85720 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#85721 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#85722 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#85723 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#85724 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#85725 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#85726 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#85727 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#85728 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#85729 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#85730 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#85731 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#85732 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#85733 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#85734 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#85735 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#85736 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#85737 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#85738 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#85739 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85741 = ORIENTED_EDGE('',*,*,#79488,.F.); -#85742 = ADVANCED_FACE('',(#85743),#76091,.T.); -#85743 = FACE_BOUND('',#85744,.T.); -#85744 = EDGE_LOOP('',(#85745,#85746,#85747,#85748)); -#85745 = ORIENTED_EDGE('',*,*,#85627,.T.); -#85746 = ORIENTED_EDGE('',*,*,#79397,.F.); -#85747 = ORIENTED_EDGE('',*,*,#76054,.F.); -#85748 = ORIENTED_EDGE('',*,*,#78951,.F.); -#85749 = ADVANCED_FACE('',(#85750),#76210,.T.); -#85750 = FACE_BOUND('',#85751,.T.); -#85751 = EDGE_LOOP('',(#85752,#85753,#85754,#85755)); -#85752 = ORIENTED_EDGE('',*,*,#76171,.F.); -#85753 = ORIENTED_EDGE('',*,*,#79510,.F.); -#85754 = ORIENTED_EDGE('',*,*,#85676,.T.); -#85755 = ORIENTED_EDGE('',*,*,#85330,.F.); -#85756 = ADVANCED_FACE('',(#85757),#75935,.T.); -#85757 = FACE_BOUND('',#85758,.T.); -#85758 = EDGE_LOOP('',(#85759,#85760,#85761,#85804)); -#85759 = ORIENTED_EDGE('',*,*,#75896,.F.); -#85760 = ORIENTED_EDGE('',*,*,#79351,.F.); -#85761 = ORIENTED_EDGE('',*,*,#85762,.F.); -#85762 = EDGE_CURVE('',#78757,#79330,#85763,.T.); -#85763 = SURFACE_CURVE('',#85764,(#85769,#85798),.PCURVE_S1.); -#85764 = CIRCLE('',#85765,5.E-002); -#85765 = AXIS2_PLACEMENT_3D('',#85766,#85767,#85768); -#85766 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,0.15)); -#85767 = DIRECTION('',(1.,0.E+000,0.E+000)); -#85768 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#85769 = PCURVE('',#75935,#85770); -#85770 = DEFINITIONAL_REPRESENTATION('',(#85771),#85797); -#85771 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85772,#85773,#85774,#85775, - #85776,#85777,#85778,#85779,#85780,#85781,#85782,#85783,#85784, - #85785,#85786,#85787,#85788,#85789,#85790,#85791,#85792,#85793, - #85794,#85795,#85796),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#88107 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#88108 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#88109 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#88110 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#88111 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#88112 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#88113 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#88114 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#88115 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#88116 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#88117 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#88118 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#88119 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#88120 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#88121 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#88122 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#88123 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#88124 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#88125 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#88126 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#88127 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#88128 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#88129 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#88130 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#88131 = CARTESIAN_POINT('',(0.751879414295,1.)); +#88132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88133 = ORIENTED_EDGE('',*,*,#81880,.F.); +#88134 = ADVANCED_FACE('',(#88135),#78483,.T.); +#88135 = FACE_BOUND('',#88136,.T.); +#88136 = EDGE_LOOP('',(#88137,#88138,#88139,#88140)); +#88137 = ORIENTED_EDGE('',*,*,#88019,.T.); +#88138 = ORIENTED_EDGE('',*,*,#81789,.F.); +#88139 = ORIENTED_EDGE('',*,*,#78446,.F.); +#88140 = ORIENTED_EDGE('',*,*,#81343,.F.); +#88141 = ADVANCED_FACE('',(#88142),#78602,.T.); +#88142 = FACE_BOUND('',#88143,.T.); +#88143 = EDGE_LOOP('',(#88144,#88145,#88146,#88147)); +#88144 = ORIENTED_EDGE('',*,*,#78563,.F.); +#88145 = ORIENTED_EDGE('',*,*,#81902,.F.); +#88146 = ORIENTED_EDGE('',*,*,#88068,.T.); +#88147 = ORIENTED_EDGE('',*,*,#87722,.F.); +#88148 = ADVANCED_FACE('',(#88149),#78327,.T.); +#88149 = FACE_BOUND('',#88150,.T.); +#88150 = EDGE_LOOP('',(#88151,#88152,#88153,#88196)); +#88151 = ORIENTED_EDGE('',*,*,#78288,.F.); +#88152 = ORIENTED_EDGE('',*,*,#81743,.F.); +#88153 = ORIENTED_EDGE('',*,*,#88154,.F.); +#88154 = EDGE_CURVE('',#81149,#81722,#88155,.T.); +#88155 = SURFACE_CURVE('',#88156,(#88161,#88190),.PCURVE_S1.); +#88156 = CIRCLE('',#88157,5.E-002); +#88157 = AXIS2_PLACEMENT_3D('',#88158,#88159,#88160); +#88158 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,0.15)); +#88159 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88160 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88161 = PCURVE('',#78327,#88162); +#88162 = DEFINITIONAL_REPRESENTATION('',(#88163),#88189); +#88163 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88164,#88165,#88166,#88167, + #88168,#88169,#88170,#88171,#88172,#88173,#88174,#88175,#88176, + #88177,#88178,#88179,#88180,#88181,#88182,#88183,#88184,#88185, + #88186,#88187,#88188),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184,5.033688229047, 5.093188089911,5.152687950774,5.212187811638,5.271687672501, 5.331187533364,5.390687394228,5.450187255091,5.509687115955, @@ -106496,64 +109485,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.807186420272,5.866686281135,5.926186141999,5.985686002862, 6.045185863726,6.104685724589,6.164185585453,6.223685446316, 6.28318530718),.QUASI_UNIFORM_KNOTS.); -#85772 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85773 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#85774 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#85775 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#85776 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#85777 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#85778 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#85779 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#85780 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#85781 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#85782 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#85783 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#85784 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#85785 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#85786 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#85787 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#85788 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#85789 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#85790 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#85791 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#85792 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#85793 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#85794 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#85795 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#85796 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85798 = PCURVE('',#75816,#85799); -#85799 = DEFINITIONAL_REPRESENTATION('',(#85800),#85803); -#85800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#85801,#85802),.UNSPECIFIED., +#88164 = CARTESIAN_POINT('',(0.751879414295,1.)); +#88165 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#88166 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#88167 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#88168 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#88169 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#88170 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#88171 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#88172 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#88173 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#88174 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#88175 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#88176 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#88177 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#88178 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#88179 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#88180 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#88181 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#88182 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#88183 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#88184 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#88185 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#88186 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#88187 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#88188 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#88189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88190 = PCURVE('',#78208,#88191); +#88191 = DEFINITIONAL_REPRESENTATION('',(#88192),#88195); +#88192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88193,#88194),.UNSPECIFIED., .F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#85801 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#85802 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#85803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85804 = ORIENTED_EDGE('',*,*,#84697,.F.); -#85805 = ADVANCED_FACE('',(#85806),#76366,.T.); -#85806 = FACE_BOUND('',#85807,.T.); -#85807 = EDGE_LOOP('',(#85808,#85809,#85810,#85876)); -#85808 = ORIENTED_EDGE('',*,*,#76329,.T.); -#85809 = ORIENTED_EDGE('',*,*,#78639,.F.); -#85810 = ORIENTED_EDGE('',*,*,#85811,.F.); -#85811 = EDGE_CURVE('',#79239,#78590,#85812,.T.); -#85812 = SURFACE_CURVE('',#85813,(#85818,#85847),.PCURVE_S1.); -#85813 = CIRCLE('',#85814,5.E-002); -#85814 = AXIS2_PLACEMENT_3D('',#85815,#85816,#85817); -#85815 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,0.15)); -#85816 = DIRECTION('',(-1.122448683923E-015,-1.,0.E+000)); -#85817 = DIRECTION('',(1.,-1.122448683923E-015,0.E+000)); -#85818 = PCURVE('',#76366,#85819); -#85819 = DEFINITIONAL_REPRESENTATION('',(#85820),#85846); -#85820 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85821,#85822,#85823,#85824, - #85825,#85826,#85827,#85828,#85829,#85830,#85831,#85832,#85833, - #85834,#85835,#85836,#85837,#85838,#85839,#85840,#85841,#85842, - #85843,#85844,#85845),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#88193 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#88194 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#88195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88196 = ORIENTED_EDGE('',*,*,#87089,.F.); +#88197 = ADVANCED_FACE('',(#88198),#78758,.T.); +#88198 = FACE_BOUND('',#88199,.T.); +#88199 = EDGE_LOOP('',(#88200,#88201,#88202,#88268)); +#88200 = ORIENTED_EDGE('',*,*,#78721,.T.); +#88201 = ORIENTED_EDGE('',*,*,#81031,.F.); +#88202 = ORIENTED_EDGE('',*,*,#88203,.F.); +#88203 = EDGE_CURVE('',#81631,#80982,#88204,.T.); +#88204 = SURFACE_CURVE('',#88205,(#88210,#88239),.PCURVE_S1.); +#88205 = CIRCLE('',#88206,5.E-002); +#88206 = AXIS2_PLACEMENT_3D('',#88207,#88208,#88209); +#88207 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,0.15)); +#88208 = DIRECTION('',(-1.122448683923E-015,-1.,0.E+000)); +#88209 = DIRECTION('',(1.,-1.122448683923E-015,0.E+000)); +#88210 = PCURVE('',#78758,#88211); +#88211 = DEFINITIONAL_REPRESENTATION('',(#88212),#88238); +#88212 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88213,#88214,#88215,#88216, + #88217,#88218,#88219,#88220,#88221,#88222,#88223,#88224,#88225, + #88226,#88227,#88228,#88229,#88230,#88231,#88232,#88233,#88234, + #88235,#88236,#88237),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.771888841248, 4.831388702112,4.890888562975,4.950388423838,5.009888284702, 5.069388145565,5.128888006429,5.188387867292,5.247887728156, @@ -106561,40 +109550,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.545387032473,5.604886893336,5.6643867542,5.723886615063, 5.783386475927,5.84288633679,5.902386197654,5.961886058517, 6.02138591938),.QUASI_UNIFORM_KNOTS.); -#85821 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); -#85822 = CARTESIAN_POINT('',(4.732222267339,1.031066471757)); -#85823 = CARTESIAN_POINT('',(4.771888841248,1.031066471757)); -#85824 = CARTESIAN_POINT('',(4.831388702112,1.031066471757)); -#85825 = CARTESIAN_POINT('',(4.890888562975,1.031066471757)); -#85826 = CARTESIAN_POINT('',(4.950388423838,1.031066471757)); -#85827 = CARTESIAN_POINT('',(5.009888284702,1.031066471757)); -#85828 = CARTESIAN_POINT('',(5.069388145565,1.031066471757)); -#85829 = CARTESIAN_POINT('',(5.128888006429,1.031066471757)); -#85830 = CARTESIAN_POINT('',(5.188387867292,1.031066471757)); -#85831 = CARTESIAN_POINT('',(5.247887728156,1.031066471757)); -#85832 = CARTESIAN_POINT('',(5.307387589019,1.031066471757)); -#85833 = CARTESIAN_POINT('',(5.366887449883,1.031066471757)); -#85834 = CARTESIAN_POINT('',(5.426387310746,1.031066471757)); -#85835 = CARTESIAN_POINT('',(5.485887171609,1.031066471757)); -#85836 = CARTESIAN_POINT('',(5.545387032473,1.031066471757)); -#85837 = CARTESIAN_POINT('',(5.604886893336,1.031066471757)); -#85838 = CARTESIAN_POINT('',(5.6643867542,1.031066471757)); -#85839 = CARTESIAN_POINT('',(5.723886615063,1.031066471757)); -#85840 = CARTESIAN_POINT('',(5.783386475927,1.031066471757)); -#85841 = CARTESIAN_POINT('',(5.84288633679,1.031066471757)); -#85842 = CARTESIAN_POINT('',(5.902386197654,1.031066471757)); -#85843 = CARTESIAN_POINT('',(5.961886058517,1.031066471757)); -#85844 = CARTESIAN_POINT('',(6.001552632426,1.031066471757)); -#85845 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); -#85846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85847 = PCURVE('',#75660,#85848); -#85848 = DEFINITIONAL_REPRESENTATION('',(#85849),#85875); -#85849 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#85850,#85851,#85852,#85853, - #85854,#85855,#85856,#85857,#85858,#85859,#85860,#85861,#85862, - #85863,#85864,#85865,#85866,#85867,#85868,#85869,#85870,#85871, - #85872,#85873,#85874),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 +#88213 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); +#88214 = CARTESIAN_POINT('',(4.732222267339,1.031066471757)); +#88215 = CARTESIAN_POINT('',(4.771888841248,1.031066471757)); +#88216 = CARTESIAN_POINT('',(4.831388702112,1.031066471757)); +#88217 = CARTESIAN_POINT('',(4.890888562975,1.031066471757)); +#88218 = CARTESIAN_POINT('',(4.950388423838,1.031066471757)); +#88219 = CARTESIAN_POINT('',(5.009888284702,1.031066471757)); +#88220 = CARTESIAN_POINT('',(5.069388145565,1.031066471757)); +#88221 = CARTESIAN_POINT('',(5.128888006429,1.031066471757)); +#88222 = CARTESIAN_POINT('',(5.188387867292,1.031066471757)); +#88223 = CARTESIAN_POINT('',(5.247887728156,1.031066471757)); +#88224 = CARTESIAN_POINT('',(5.307387589019,1.031066471757)); +#88225 = CARTESIAN_POINT('',(5.366887449883,1.031066471757)); +#88226 = CARTESIAN_POINT('',(5.426387310746,1.031066471757)); +#88227 = CARTESIAN_POINT('',(5.485887171609,1.031066471757)); +#88228 = CARTESIAN_POINT('',(5.545387032473,1.031066471757)); +#88229 = CARTESIAN_POINT('',(5.604886893336,1.031066471757)); +#88230 = CARTESIAN_POINT('',(5.6643867542,1.031066471757)); +#88231 = CARTESIAN_POINT('',(5.723886615063,1.031066471757)); +#88232 = CARTESIAN_POINT('',(5.783386475927,1.031066471757)); +#88233 = CARTESIAN_POINT('',(5.84288633679,1.031066471757)); +#88234 = CARTESIAN_POINT('',(5.902386197654,1.031066471757)); +#88235 = CARTESIAN_POINT('',(5.961886058517,1.031066471757)); +#88236 = CARTESIAN_POINT('',(6.001552632426,1.031066471757)); +#88237 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); +#88238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88239 = PCURVE('',#78052,#88240); +#88240 = DEFINITIONAL_REPRESENTATION('',(#88241),#88267); +#88241 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#88242,#88243,#88244,#88245, + #88246,#88247,#88248,#88249,#88250,#88251,#88252,#88253,#88254, + #88255,#88256,#88257,#88258,#88259,#88260,#88261,#88262,#88263, + #88264,#88265,#88266),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1,1,1,1,1,1,1 ,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385,4.771888841248, 4.831388702112,4.890888562975,4.950388423838,5.009888284702, 5.069388145565,5.128888006429,5.188387867292,5.247887728156, @@ -106602,26927 +109591,26940 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.545387032473,5.604886893336,5.6643867542,5.723886615063, 5.783386475927,5.84288633679,5.902386197654,5.961886058517, 6.02138591938),.QUASI_UNIFORM_KNOTS.); -#85850 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#85851 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); -#85852 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); -#85853 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); -#85854 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#85855 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#85856 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#85857 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#85858 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#85859 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#85860 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#85861 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#85862 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#85863 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#85864 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#85865 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#85866 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#85867 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#85868 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#85869 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#85870 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#85871 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#85872 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#85873 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#85874 = CARTESIAN_POINT('',(0.751879414295,1.)); -#85875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85876 = ORIENTED_EDGE('',*,*,#79238,.F.); -#85877 = ADVANCED_FACE('',(#85878),#75816,.T.); -#85878 = FACE_BOUND('',#85879,.T.); -#85879 = EDGE_LOOP('',(#85880,#85881,#85882,#85883)); -#85880 = ORIENTED_EDGE('',*,*,#85762,.T.); -#85881 = ORIENTED_EDGE('',*,*,#79329,.F.); -#85882 = ORIENTED_EDGE('',*,*,#75779,.F.); -#85883 = ORIENTED_EDGE('',*,*,#78801,.F.); -#85884 = ADVANCED_FACE('',(#85885),#75660,.T.); -#85885 = FACE_BOUND('',#85886,.T.); -#85886 = EDGE_LOOP('',(#85887,#85888,#85889,#85890)); -#85887 = ORIENTED_EDGE('',*,*,#75621,.F.); -#85888 = ORIENTED_EDGE('',*,*,#79283,.F.); -#85889 = ORIENTED_EDGE('',*,*,#85811,.T.); -#85890 = ORIENTED_EDGE('',*,*,#85119,.F.); -#85891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#85895)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#85892,#85893,#85894)) +#88242 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#88243 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); +#88244 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); +#88245 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); +#88246 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#88247 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#88248 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#88249 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#88250 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#88251 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#88252 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#88253 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#88254 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#88255 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#88256 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#88257 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#88258 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#88259 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#88260 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#88261 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#88262 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#88263 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#88264 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#88265 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#88266 = CARTESIAN_POINT('',(0.751879414295,1.)); +#88267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88268 = ORIENTED_EDGE('',*,*,#81630,.F.); +#88269 = ADVANCED_FACE('',(#88270),#78208,.T.); +#88270 = FACE_BOUND('',#88271,.T.); +#88271 = EDGE_LOOP('',(#88272,#88273,#88274,#88275)); +#88272 = ORIENTED_EDGE('',*,*,#88154,.T.); +#88273 = ORIENTED_EDGE('',*,*,#81721,.F.); +#88274 = ORIENTED_EDGE('',*,*,#78171,.F.); +#88275 = ORIENTED_EDGE('',*,*,#81193,.F.); +#88276 = ADVANCED_FACE('',(#88277),#78052,.T.); +#88277 = FACE_BOUND('',#88278,.T.); +#88278 = EDGE_LOOP('',(#88279,#88280,#88281,#88282)); +#88279 = ORIENTED_EDGE('',*,*,#78013,.F.); +#88280 = ORIENTED_EDGE('',*,*,#81675,.F.); +#88281 = ORIENTED_EDGE('',*,*,#88203,.T.); +#88282 = ORIENTED_EDGE('',*,*,#87511,.F.); +#88283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#88287)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#88284,#88285,#88286)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#85892 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#85893 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#85894 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#85895 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-004),#85892, +#88284 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#88285 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#88286 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#88287 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-004),#88284, 'distance_accuracy_value','confusion accuracy'); -#85896 = SHAPE_DEFINITION_REPRESENTATION(#85897,#75543); -#85897 = PRODUCT_DEFINITION_SHAPE('','',#85898); -#85898 = PRODUCT_DEFINITION('design','',#85899,#85902); -#85899 = PRODUCT_DEFINITION_FORMATION('','',#85900); -#85900 = PRODUCT('SOT23-5','SOT23-5','',(#85901)); -#85901 = PRODUCT_CONTEXT('',#2,'mechanical'); -#85902 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#85903 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#85904,#85906); -#85904 = ( REPRESENTATION_RELATIONSHIP('','',#75543,#75533) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#85905) +#88288 = SHAPE_DEFINITION_REPRESENTATION(#88289,#77935); +#88289 = PRODUCT_DEFINITION_SHAPE('','',#88290); +#88290 = PRODUCT_DEFINITION('design','',#88291,#88294); +#88291 = PRODUCT_DEFINITION_FORMATION('','',#88292); +#88292 = PRODUCT('SOT23-5','SOT23-5','',(#88293)); +#88293 = PRODUCT_CONTEXT('',#2,'mechanical'); +#88294 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#88295 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#88296,#88298); +#88296 = ( REPRESENTATION_RELATIONSHIP('','',#77935,#77925) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#88297) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#85905 = ITEM_DEFINED_TRANSFORMATION('','',#11,#75534); -#85906 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #85907); -#85907 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('262','=>[0:1:1:73]','',#75528, - #85898,$); -#85908 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#85900)); -#85909 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#85910,#85912); -#85910 = ( REPRESENTATION_RELATIONSHIP('','',#75533,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#85911) +#88297 = ITEM_DEFINED_TRANSFORMATION('','',#11,#77926); +#88298 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #88299); +#88299 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('363','=>[0:1:1:73]','',#77920, + #88290,$); +#88300 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#88292)); +#88301 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#88302,#88304); +#88302 = ( REPRESENTATION_RELATIONSHIP('','',#77925,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#88303) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#85911 = ITEM_DEFINED_TRANSFORMATION('','',#11,#215); -#85912 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #85913); -#85913 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('263','=>[0:1:1:72]','',#5, - #75528,$); -#85914 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#75530)); -#85915 = SHAPE_DEFINITION_REPRESENTATION(#85916,#85922); -#85916 = PRODUCT_DEFINITION_SHAPE('','',#85917); -#85917 = PRODUCT_DEFINITION('design','',#85918,#85921); -#85918 = PRODUCT_DEFINITION_FORMATION('','',#85919); -#85919 = PRODUCT('U4','U4','',(#85920)); -#85920 = PRODUCT_CONTEXT('',#2,'mechanical'); -#85921 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#85922 = SHAPE_REPRESENTATION('',(#11,#85923),#85927); -#85923 = AXIS2_PLACEMENT_3D('',#85924,#85925,#85926); -#85924 = CARTESIAN_POINT('',(17.399,28.575,6.26999E-002)); -#85925 = DIRECTION('',(0.E+000,0.E+000,1.)); -#85926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#85927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#85931)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#85928,#85929,#85930)) +#88303 = ITEM_DEFINED_TRANSFORMATION('','',#11,#215); +#88304 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #88305); +#88305 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('364','=>[0:1:1:72]','',#5, + #77920,$); +#88306 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#77922)); +#88307 = SHAPE_DEFINITION_REPRESENTATION(#88308,#88314); +#88308 = PRODUCT_DEFINITION_SHAPE('','',#88309); +#88309 = PRODUCT_DEFINITION('design','',#88310,#88313); +#88310 = PRODUCT_DEFINITION_FORMATION('','',#88311); +#88311 = PRODUCT('U4','U4','',(#88312)); +#88312 = PRODUCT_CONTEXT('',#2,'mechanical'); +#88313 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#88314 = SHAPE_REPRESENTATION('',(#11,#88315),#88319); +#88315 = AXIS2_PLACEMENT_3D('',#88316,#88317,#88318); +#88316 = CARTESIAN_POINT('',(17.399,28.575,6.26999E-002)); +#88317 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#88323)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#88320,#88321,#88322)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#85928 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#85929 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#85930 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#85931 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#85928, +#88320 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#88321 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#88322 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#88323 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#88320, 'distance_accuracy_value','confusion accuracy'); -#85932 = SHAPE_DEFINITION_REPRESENTATION(#85933,#85939); -#85933 = PRODUCT_DEFINITION_SHAPE('','',#85934); -#85934 = PRODUCT_DEFINITION('design','',#85935,#85938); -#85935 = PRODUCT_DEFINITION_FORMATION('','',#85936); -#85936 = PRODUCT('622885664','622885664','',(#85937)); -#85937 = PRODUCT_CONTEXT('',#2,'mechanical'); -#85938 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#85939 = SHAPE_REPRESENTATION('',(#11,#85940),#85944); -#85940 = AXIS2_PLACEMENT_3D('',#85941,#85942,#85943); -#85941 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#85942 = DIRECTION('',(0.E+000,0.E+000,1.)); -#85943 = DIRECTION('',(1.,0.E+000,0.E+000)); -#85944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#85948)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#85945,#85946,#85947)) +#88324 = SHAPE_DEFINITION_REPRESENTATION(#88325,#88331); +#88325 = PRODUCT_DEFINITION_SHAPE('','',#88326); +#88326 = PRODUCT_DEFINITION('design','',#88327,#88330); +#88327 = PRODUCT_DEFINITION_FORMATION('','',#88328); +#88328 = PRODUCT('549180192','549180192','',(#88329)); +#88329 = PRODUCT_CONTEXT('',#2,'mechanical'); +#88330 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#88331 = SHAPE_REPRESENTATION('',(#11,#88332),#88336); +#88332 = AXIS2_PLACEMENT_3D('',#88333,#88334,#88335); +#88333 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#88334 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88335 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#88340)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#88337,#88338,#88339)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#85945 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#85946 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#85947 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#85948 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#85945, +#88337 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#88338 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#88339 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#88340 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#88337, 'distance_accuracy_value','confusion accuracy'); -#85949 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#85950),#86280); -#85950 = MANIFOLD_SOLID_BREP('',#85951); -#85951 = CLOSED_SHELL('',(#85952,#86072,#86148,#86219,#86266,#86273)); -#85952 = ADVANCED_FACE('',(#85953),#85967,.T.); -#85953 = FACE_BOUND('',#85954,.T.); -#85954 = EDGE_LOOP('',(#85955,#85990,#86018,#86046)); -#85955 = ORIENTED_EDGE('',*,*,#85956,.T.); -#85956 = EDGE_CURVE('',#85957,#85959,#85961,.T.); -#85957 = VERTEX_POINT('',#85958); -#85958 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); -#85959 = VERTEX_POINT('',#85960); -#85960 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.95)); -#85961 = SURFACE_CURVE('',#85962,(#85966,#85978),.PCURVE_S1.); -#85962 = LINE('',#85963,#85964); -#85963 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); -#85964 = VECTOR('',#85965,1.); -#85965 = DIRECTION('',(0.E+000,0.E+000,1.)); -#85966 = PCURVE('',#85967,#85972); -#85967 = PLANE('',#85968); -#85968 = AXIS2_PLACEMENT_3D('',#85969,#85970,#85971); -#85969 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); -#85970 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#85971 = DIRECTION('',(0.E+000,1.,0.E+000)); -#85972 = DEFINITIONAL_REPRESENTATION('',(#85973),#85977); -#85973 = LINE('',#85974,#85975); -#85974 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#85975 = VECTOR('',#85976,1.); -#85976 = DIRECTION('',(0.E+000,-1.)); -#85977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85978 = PCURVE('',#85979,#85984); -#85979 = PLANE('',#85980); -#85980 = AXIS2_PLACEMENT_3D('',#85981,#85982,#85983); -#85981 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); -#85982 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#85983 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#85984 = DEFINITIONAL_REPRESENTATION('',(#85985),#85989); -#85985 = LINE('',#85986,#85987); -#85986 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#85987 = VECTOR('',#85988,1.); -#85988 = DIRECTION('',(0.E+000,-1.)); -#85989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#85990 = ORIENTED_EDGE('',*,*,#85991,.T.); -#85991 = EDGE_CURVE('',#85959,#85992,#85994,.T.); -#85992 = VERTEX_POINT('',#85993); -#85993 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.95)); -#85994 = SURFACE_CURVE('',#85995,(#85999,#86006),.PCURVE_S1.); -#85995 = LINE('',#85996,#85997); -#85996 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.95)); -#85997 = VECTOR('',#85998,1.); -#85998 = DIRECTION('',(0.E+000,1.,0.E+000)); -#85999 = PCURVE('',#85967,#86000); -#86000 = DEFINITIONAL_REPRESENTATION('',(#86001),#86005); -#86001 = LINE('',#86002,#86003); -#86002 = CARTESIAN_POINT('',(0.E+000,-0.95)); -#86003 = VECTOR('',#86004,1.); -#86004 = DIRECTION('',(1.,0.E+000)); -#86005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86006 = PCURVE('',#86007,#86012); -#86007 = PLANE('',#86008); -#86008 = AXIS2_PLACEMENT_3D('',#86009,#86010,#86011); -#86009 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.95)); -#86010 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86011 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86012 = DEFINITIONAL_REPRESENTATION('',(#86013),#86017); -#86013 = LINE('',#86014,#86015); -#86014 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86015 = VECTOR('',#86016,1.); -#86016 = DIRECTION('',(0.E+000,1.)); -#86017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86018 = ORIENTED_EDGE('',*,*,#86019,.F.); -#86019 = EDGE_CURVE('',#86020,#85992,#86022,.T.); -#86020 = VERTEX_POINT('',#86021); -#86021 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); -#86022 = SURFACE_CURVE('',#86023,(#86027,#86034),.PCURVE_S1.); -#86023 = LINE('',#86024,#86025); -#86024 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); -#86025 = VECTOR('',#86026,1.); -#86026 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86027 = PCURVE('',#85967,#86028); -#86028 = DEFINITIONAL_REPRESENTATION('',(#86029),#86033); -#86029 = LINE('',#86030,#86031); -#86030 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#86031 = VECTOR('',#86032,1.); -#86032 = DIRECTION('',(0.E+000,-1.)); -#86033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86034 = PCURVE('',#86035,#86040); -#86035 = PLANE('',#86036); -#86036 = AXIS2_PLACEMENT_3D('',#86037,#86038,#86039); -#86037 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); -#86038 = DIRECTION('',(0.E+000,1.,0.E+000)); -#86039 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86040 = DEFINITIONAL_REPRESENTATION('',(#86041),#86045); -#86041 = LINE('',#86042,#86043); -#86042 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86043 = VECTOR('',#86044,1.); -#86044 = DIRECTION('',(0.E+000,-1.)); -#86045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86046 = ORIENTED_EDGE('',*,*,#86047,.F.); -#86047 = EDGE_CURVE('',#85957,#86020,#86048,.T.); -#86048 = SURFACE_CURVE('',#86049,(#86053,#86060),.PCURVE_S1.); -#86049 = LINE('',#86050,#86051); -#86050 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); -#86051 = VECTOR('',#86052,1.); -#86052 = DIRECTION('',(0.E+000,1.,0.E+000)); -#86053 = PCURVE('',#85967,#86054); -#86054 = DEFINITIONAL_REPRESENTATION('',(#86055),#86059); -#86055 = LINE('',#86056,#86057); -#86056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86057 = VECTOR('',#86058,1.); -#86058 = DIRECTION('',(1.,0.E+000)); -#86059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86060 = PCURVE('',#86061,#86066); -#86061 = PLANE('',#86062); -#86062 = AXIS2_PLACEMENT_3D('',#86063,#86064,#86065); -#86063 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); -#86064 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86065 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86066 = DEFINITIONAL_REPRESENTATION('',(#86067),#86071); -#86067 = LINE('',#86068,#86069); -#86068 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86069 = VECTOR('',#86070,1.); -#86070 = DIRECTION('',(0.E+000,1.)); -#86071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86072 = ADVANCED_FACE('',(#86073),#86035,.T.); -#86073 = FACE_BOUND('',#86074,.T.); -#86074 = EDGE_LOOP('',(#86075,#86076,#86099,#86127)); -#86075 = ORIENTED_EDGE('',*,*,#86019,.T.); -#86076 = ORIENTED_EDGE('',*,*,#86077,.T.); -#86077 = EDGE_CURVE('',#85992,#86078,#86080,.T.); -#86078 = VERTEX_POINT('',#86079); -#86079 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.95)); -#86080 = SURFACE_CURVE('',#86081,(#86085,#86092),.PCURVE_S1.); -#86081 = LINE('',#86082,#86083); -#86082 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.95)); -#86083 = VECTOR('',#86084,1.); -#86084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86085 = PCURVE('',#86035,#86086); -#86086 = DEFINITIONAL_REPRESENTATION('',(#86087),#86091); -#86087 = LINE('',#86088,#86089); -#86088 = CARTESIAN_POINT('',(0.E+000,-0.95)); -#86089 = VECTOR('',#86090,1.); -#86090 = DIRECTION('',(1.,0.E+000)); -#86091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86092 = PCURVE('',#86007,#86093); -#86093 = DEFINITIONAL_REPRESENTATION('',(#86094),#86098); -#86094 = LINE('',#86095,#86096); -#86095 = CARTESIAN_POINT('',(0.E+000,3.09999888)); -#86096 = VECTOR('',#86097,1.); -#86097 = DIRECTION('',(1.,0.E+000)); -#86098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86099 = ORIENTED_EDGE('',*,*,#86100,.F.); -#86100 = EDGE_CURVE('',#86101,#86078,#86103,.T.); -#86101 = VERTEX_POINT('',#86102); -#86102 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); -#86103 = SURFACE_CURVE('',#86104,(#86108,#86115),.PCURVE_S1.); -#86104 = LINE('',#86105,#86106); -#86105 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); -#86106 = VECTOR('',#86107,1.); -#86107 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86108 = PCURVE('',#86035,#86109); -#86109 = DEFINITIONAL_REPRESENTATION('',(#86110),#86114); -#86110 = LINE('',#86111,#86112); -#86111 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#86112 = VECTOR('',#86113,1.); -#86113 = DIRECTION('',(0.E+000,-1.)); -#86114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86115 = PCURVE('',#86116,#86121); -#86116 = PLANE('',#86117); -#86117 = AXIS2_PLACEMENT_3D('',#86118,#86119,#86120); -#86118 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); -#86119 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86120 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#86121 = DEFINITIONAL_REPRESENTATION('',(#86122),#86126); -#86122 = LINE('',#86123,#86124); -#86123 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86124 = VECTOR('',#86125,1.); -#86125 = DIRECTION('',(0.E+000,-1.)); -#86126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86127 = ORIENTED_EDGE('',*,*,#86128,.F.); -#86128 = EDGE_CURVE('',#86020,#86101,#86129,.T.); -#86129 = SURFACE_CURVE('',#86130,(#86134,#86141),.PCURVE_S1.); -#86130 = LINE('',#86131,#86132); -#86131 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); -#86132 = VECTOR('',#86133,1.); -#86133 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86134 = PCURVE('',#86035,#86135); -#86135 = DEFINITIONAL_REPRESENTATION('',(#86136),#86140); -#86136 = LINE('',#86137,#86138); -#86137 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86138 = VECTOR('',#86139,1.); -#86139 = DIRECTION('',(1.,0.E+000)); -#86140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86141 = PCURVE('',#86061,#86142); -#86142 = DEFINITIONAL_REPRESENTATION('',(#86143),#86147); -#86143 = LINE('',#86144,#86145); -#86144 = CARTESIAN_POINT('',(0.E+000,3.09999888)); -#86145 = VECTOR('',#86146,1.); -#86146 = DIRECTION('',(1.,0.E+000)); -#86147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86148 = ADVANCED_FACE('',(#86149),#86116,.T.); -#86149 = FACE_BOUND('',#86150,.T.); -#86150 = EDGE_LOOP('',(#86151,#86152,#86175,#86198)); -#86151 = ORIENTED_EDGE('',*,*,#86100,.T.); -#86152 = ORIENTED_EDGE('',*,*,#86153,.T.); -#86153 = EDGE_CURVE('',#86078,#86154,#86156,.T.); -#86154 = VERTEX_POINT('',#86155); -#86155 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.95)); -#86156 = SURFACE_CURVE('',#86157,(#86161,#86168),.PCURVE_S1.); -#86157 = LINE('',#86158,#86159); -#86158 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.95)); -#86159 = VECTOR('',#86160,1.); -#86160 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#86161 = PCURVE('',#86116,#86162); -#86162 = DEFINITIONAL_REPRESENTATION('',(#86163),#86167); -#86163 = LINE('',#86164,#86165); -#86164 = CARTESIAN_POINT('',(0.E+000,-0.95)); -#86165 = VECTOR('',#86166,1.); -#86166 = DIRECTION('',(1.,0.E+000)); -#86167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86168 = PCURVE('',#86007,#86169); -#86169 = DEFINITIONAL_REPRESENTATION('',(#86170),#86174); -#86170 = LINE('',#86171,#86172); -#86171 = CARTESIAN_POINT('',(3.09999888,3.09999888)); -#86172 = VECTOR('',#86173,1.); -#86173 = DIRECTION('',(0.E+000,-1.)); -#86174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86175 = ORIENTED_EDGE('',*,*,#86176,.F.); -#86176 = EDGE_CURVE('',#86177,#86154,#86179,.T.); -#86177 = VERTEX_POINT('',#86178); -#86178 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); -#86179 = SURFACE_CURVE('',#86180,(#86184,#86191),.PCURVE_S1.); -#86180 = LINE('',#86181,#86182); -#86181 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); -#86182 = VECTOR('',#86183,1.); -#86183 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86184 = PCURVE('',#86116,#86185); -#86185 = DEFINITIONAL_REPRESENTATION('',(#86186),#86190); -#86186 = LINE('',#86187,#86188); -#86187 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#86188 = VECTOR('',#86189,1.); -#86189 = DIRECTION('',(0.E+000,-1.)); -#86190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86191 = PCURVE('',#85979,#86192); -#86192 = DEFINITIONAL_REPRESENTATION('',(#86193),#86197); -#86193 = LINE('',#86194,#86195); -#86194 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86195 = VECTOR('',#86196,1.); -#86196 = DIRECTION('',(0.E+000,-1.)); -#86197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86198 = ORIENTED_EDGE('',*,*,#86199,.F.); -#86199 = EDGE_CURVE('',#86101,#86177,#86200,.T.); -#86200 = SURFACE_CURVE('',#86201,(#86205,#86212),.PCURVE_S1.); -#86201 = LINE('',#86202,#86203); -#86202 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); -#86203 = VECTOR('',#86204,1.); -#86204 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#86205 = PCURVE('',#86116,#86206); -#86206 = DEFINITIONAL_REPRESENTATION('',(#86207),#86211); -#86207 = LINE('',#86208,#86209); -#86208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86209 = VECTOR('',#86210,1.); -#86210 = DIRECTION('',(1.,0.E+000)); -#86211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86212 = PCURVE('',#86061,#86213); -#86213 = DEFINITIONAL_REPRESENTATION('',(#86214),#86218); -#86214 = LINE('',#86215,#86216); -#86215 = CARTESIAN_POINT('',(3.09999888,3.09999888)); -#86216 = VECTOR('',#86217,1.); -#86217 = DIRECTION('',(0.E+000,-1.)); -#86218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86219 = ADVANCED_FACE('',(#86220),#85979,.T.); -#86220 = FACE_BOUND('',#86221,.T.); -#86221 = EDGE_LOOP('',(#86222,#86223,#86244,#86245)); -#86222 = ORIENTED_EDGE('',*,*,#86176,.T.); -#86223 = ORIENTED_EDGE('',*,*,#86224,.T.); -#86224 = EDGE_CURVE('',#86154,#85959,#86225,.T.); -#86225 = SURFACE_CURVE('',#86226,(#86230,#86237),.PCURVE_S1.); -#86226 = LINE('',#86227,#86228); -#86227 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.95)); -#86228 = VECTOR('',#86229,1.); -#86229 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86230 = PCURVE('',#85979,#86231); -#86231 = DEFINITIONAL_REPRESENTATION('',(#86232),#86236); -#86232 = LINE('',#86233,#86234); -#86233 = CARTESIAN_POINT('',(0.E+000,-0.95)); -#86234 = VECTOR('',#86235,1.); -#86235 = DIRECTION('',(1.,0.E+000)); -#86236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86237 = PCURVE('',#86007,#86238); -#86238 = DEFINITIONAL_REPRESENTATION('',(#86239),#86243); -#86239 = LINE('',#86240,#86241); -#86240 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#86241 = VECTOR('',#86242,1.); -#86242 = DIRECTION('',(-1.,0.E+000)); -#86243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86244 = ORIENTED_EDGE('',*,*,#85956,.F.); -#86245 = ORIENTED_EDGE('',*,*,#86246,.F.); -#86246 = EDGE_CURVE('',#86177,#85957,#86247,.T.); -#86247 = SURFACE_CURVE('',#86248,(#86252,#86259),.PCURVE_S1.); -#86248 = LINE('',#86249,#86250); -#86249 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); -#86250 = VECTOR('',#86251,1.); -#86251 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86252 = PCURVE('',#85979,#86253); -#86253 = DEFINITIONAL_REPRESENTATION('',(#86254),#86258); -#86254 = LINE('',#86255,#86256); -#86255 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86256 = VECTOR('',#86257,1.); -#86257 = DIRECTION('',(1.,0.E+000)); -#86258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86259 = PCURVE('',#86061,#86260); -#86260 = DEFINITIONAL_REPRESENTATION('',(#86261),#86265); -#86261 = LINE('',#86262,#86263); -#86262 = CARTESIAN_POINT('',(3.09999888,0.E+000)); -#86263 = VECTOR('',#86264,1.); -#86264 = DIRECTION('',(-1.,0.E+000)); -#86265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#88341 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#88342),#88672); +#88342 = MANIFOLD_SOLID_BREP('',#88343); +#88343 = CLOSED_SHELL('',(#88344,#88464,#88540,#88611,#88658,#88665)); +#88344 = ADVANCED_FACE('',(#88345),#88359,.T.); +#88345 = FACE_BOUND('',#88346,.T.); +#88346 = EDGE_LOOP('',(#88347,#88382,#88410,#88438)); +#88347 = ORIENTED_EDGE('',*,*,#88348,.T.); +#88348 = EDGE_CURVE('',#88349,#88351,#88353,.T.); +#88349 = VERTEX_POINT('',#88350); +#88350 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); +#88351 = VERTEX_POINT('',#88352); +#88352 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.95)); +#88353 = SURFACE_CURVE('',#88354,(#88358,#88370),.PCURVE_S1.); +#88354 = LINE('',#88355,#88356); +#88355 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); +#88356 = VECTOR('',#88357,1.); +#88357 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88358 = PCURVE('',#88359,#88364); +#88359 = PLANE('',#88360); +#88360 = AXIS2_PLACEMENT_3D('',#88361,#88362,#88363); +#88361 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); +#88362 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88363 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88364 = DEFINITIONAL_REPRESENTATION('',(#88365),#88369); +#88365 = LINE('',#88366,#88367); +#88366 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88367 = VECTOR('',#88368,1.); +#88368 = DIRECTION('',(0.E+000,-1.)); +#88369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88370 = PCURVE('',#88371,#88376); +#88371 = PLANE('',#88372); +#88372 = AXIS2_PLACEMENT_3D('',#88373,#88374,#88375); +#88373 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); +#88374 = DIRECTION('',(0.E+000,1.,0.E+000)); +#88375 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88376 = DEFINITIONAL_REPRESENTATION('',(#88377),#88381); +#88377 = LINE('',#88378,#88379); +#88378 = CARTESIAN_POINT('',(3.09999888,0.E+000)); +#88379 = VECTOR('',#88380,1.); +#88380 = DIRECTION('',(0.E+000,-1.)); +#88381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88382 = ORIENTED_EDGE('',*,*,#88383,.T.); +#88383 = EDGE_CURVE('',#88351,#88384,#88386,.T.); +#88384 = VERTEX_POINT('',#88385); +#88385 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.95)); +#88386 = SURFACE_CURVE('',#88387,(#88391,#88398),.PCURVE_S1.); +#88387 = LINE('',#88388,#88389); +#88388 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.95)); +#88389 = VECTOR('',#88390,1.); +#88390 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88391 = PCURVE('',#88359,#88392); +#88392 = DEFINITIONAL_REPRESENTATION('',(#88393),#88397); +#88393 = LINE('',#88394,#88395); +#88394 = CARTESIAN_POINT('',(0.E+000,-0.95)); +#88395 = VECTOR('',#88396,1.); +#88396 = DIRECTION('',(1.,0.E+000)); +#88397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88398 = PCURVE('',#88399,#88404); +#88399 = PLANE('',#88400); +#88400 = AXIS2_PLACEMENT_3D('',#88401,#88402,#88403); +#88401 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.95)); +#88402 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88403 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88404 = DEFINITIONAL_REPRESENTATION('',(#88405),#88409); +#88405 = LINE('',#88406,#88407); +#88406 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88407 = VECTOR('',#88408,1.); +#88408 = DIRECTION('',(0.E+000,-1.)); +#88409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88410 = ORIENTED_EDGE('',*,*,#88411,.F.); +#88411 = EDGE_CURVE('',#88412,#88384,#88414,.T.); +#88412 = VERTEX_POINT('',#88413); +#88413 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); +#88414 = SURFACE_CURVE('',#88415,(#88419,#88426),.PCURVE_S1.); +#88415 = LINE('',#88416,#88417); +#88416 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); +#88417 = VECTOR('',#88418,1.); +#88418 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88419 = PCURVE('',#88359,#88420); +#88420 = DEFINITIONAL_REPRESENTATION('',(#88421),#88425); +#88421 = LINE('',#88422,#88423); +#88422 = CARTESIAN_POINT('',(3.09999888,0.E+000)); +#88423 = VECTOR('',#88424,1.); +#88424 = DIRECTION('',(0.E+000,-1.)); +#88425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88426 = PCURVE('',#88427,#88432); +#88427 = PLANE('',#88428); +#88428 = AXIS2_PLACEMENT_3D('',#88429,#88430,#88431); +#88429 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); +#88430 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88431 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88432 = DEFINITIONAL_REPRESENTATION('',(#88433),#88437); +#88433 = LINE('',#88434,#88435); +#88434 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88435 = VECTOR('',#88436,1.); +#88436 = DIRECTION('',(0.E+000,-1.)); +#88437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88438 = ORIENTED_EDGE('',*,*,#88439,.F.); +#88439 = EDGE_CURVE('',#88349,#88412,#88440,.T.); +#88440 = SURFACE_CURVE('',#88441,(#88445,#88452),.PCURVE_S1.); +#88441 = LINE('',#88442,#88443); +#88442 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); +#88443 = VECTOR('',#88444,1.); +#88444 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88445 = PCURVE('',#88359,#88446); +#88446 = DEFINITIONAL_REPRESENTATION('',(#88447),#88451); +#88447 = LINE('',#88448,#88449); +#88448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88449 = VECTOR('',#88450,1.); +#88450 = DIRECTION('',(1.,0.E+000)); +#88451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88452 = PCURVE('',#88453,#88458); +#88453 = PLANE('',#88454); +#88454 = AXIS2_PLACEMENT_3D('',#88455,#88456,#88457); +#88455 = CARTESIAN_POINT('',(1.54999944,1.54999944,0.E+000)); +#88456 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88457 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88458 = DEFINITIONAL_REPRESENTATION('',(#88459),#88463); +#88459 = LINE('',#88460,#88461); +#88460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88461 = VECTOR('',#88462,1.); +#88462 = DIRECTION('',(0.E+000,-1.)); +#88463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88464 = ADVANCED_FACE('',(#88465),#88427,.T.); +#88465 = FACE_BOUND('',#88466,.T.); +#88466 = EDGE_LOOP('',(#88467,#88468,#88491,#88519)); +#88467 = ORIENTED_EDGE('',*,*,#88411,.T.); +#88468 = ORIENTED_EDGE('',*,*,#88469,.T.); +#88469 = EDGE_CURVE('',#88384,#88470,#88472,.T.); +#88470 = VERTEX_POINT('',#88471); +#88471 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.95)); +#88472 = SURFACE_CURVE('',#88473,(#88477,#88484),.PCURVE_S1.); +#88473 = LINE('',#88474,#88475); +#88474 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.95)); +#88475 = VECTOR('',#88476,1.); +#88476 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88477 = PCURVE('',#88427,#88478); +#88478 = DEFINITIONAL_REPRESENTATION('',(#88479),#88483); +#88479 = LINE('',#88480,#88481); +#88480 = CARTESIAN_POINT('',(0.E+000,-0.95)); +#88481 = VECTOR('',#88482,1.); +#88482 = DIRECTION('',(1.,0.E+000)); +#88483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88484 = PCURVE('',#88399,#88485); +#88485 = DEFINITIONAL_REPRESENTATION('',(#88486),#88490); +#88486 = LINE('',#88487,#88488); +#88487 = CARTESIAN_POINT('',(0.E+000,-3.09999888)); +#88488 = VECTOR('',#88489,1.); +#88489 = DIRECTION('',(-1.,0.E+000)); +#88490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88491 = ORIENTED_EDGE('',*,*,#88492,.F.); +#88492 = EDGE_CURVE('',#88493,#88470,#88495,.T.); +#88493 = VERTEX_POINT('',#88494); +#88494 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); +#88495 = SURFACE_CURVE('',#88496,(#88500,#88507),.PCURVE_S1.); +#88496 = LINE('',#88497,#88498); +#88497 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); +#88498 = VECTOR('',#88499,1.); +#88499 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88500 = PCURVE('',#88427,#88501); +#88501 = DEFINITIONAL_REPRESENTATION('',(#88502),#88506); +#88502 = LINE('',#88503,#88504); +#88503 = CARTESIAN_POINT('',(3.09999888,0.E+000)); +#88504 = VECTOR('',#88505,1.); +#88505 = DIRECTION('',(0.E+000,-1.)); +#88506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88507 = PCURVE('',#88508,#88513); +#88508 = PLANE('',#88509); +#88509 = AXIS2_PLACEMENT_3D('',#88510,#88511,#88512); +#88510 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); +#88511 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88512 = DIRECTION('',(0.E+000,1.,0.E+000)); +#88513 = DEFINITIONAL_REPRESENTATION('',(#88514),#88518); +#88514 = LINE('',#88515,#88516); +#88515 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88516 = VECTOR('',#88517,1.); +#88517 = DIRECTION('',(0.E+000,-1.)); +#88518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88519 = ORIENTED_EDGE('',*,*,#88520,.F.); +#88520 = EDGE_CURVE('',#88412,#88493,#88521,.T.); +#88521 = SURFACE_CURVE('',#88522,(#88526,#88533),.PCURVE_S1.); +#88522 = LINE('',#88523,#88524); +#88523 = CARTESIAN_POINT('',(1.54999944,-1.54999944,0.E+000)); +#88524 = VECTOR('',#88525,1.); +#88525 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88526 = PCURVE('',#88427,#88527); +#88527 = DEFINITIONAL_REPRESENTATION('',(#88528),#88532); +#88528 = LINE('',#88529,#88530); +#88529 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88530 = VECTOR('',#88531,1.); +#88531 = DIRECTION('',(1.,0.E+000)); +#88532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88533 = PCURVE('',#88453,#88534); +#88534 = DEFINITIONAL_REPRESENTATION('',(#88535),#88539); +#88535 = LINE('',#88536,#88537); +#88536 = CARTESIAN_POINT('',(0.E+000,-3.09999888)); +#88537 = VECTOR('',#88538,1.); +#88538 = DIRECTION('',(-1.,0.E+000)); +#88539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88540 = ADVANCED_FACE('',(#88541),#88508,.T.); +#88541 = FACE_BOUND('',#88542,.T.); +#88542 = EDGE_LOOP('',(#88543,#88544,#88567,#88590)); +#88543 = ORIENTED_EDGE('',*,*,#88492,.T.); +#88544 = ORIENTED_EDGE('',*,*,#88545,.T.); +#88545 = EDGE_CURVE('',#88470,#88546,#88548,.T.); +#88546 = VERTEX_POINT('',#88547); +#88547 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.95)); +#88548 = SURFACE_CURVE('',#88549,(#88553,#88560),.PCURVE_S1.); +#88549 = LINE('',#88550,#88551); +#88550 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.95)); +#88551 = VECTOR('',#88552,1.); +#88552 = DIRECTION('',(0.E+000,1.,0.E+000)); +#88553 = PCURVE('',#88508,#88554); +#88554 = DEFINITIONAL_REPRESENTATION('',(#88555),#88559); +#88555 = LINE('',#88556,#88557); +#88556 = CARTESIAN_POINT('',(0.E+000,-0.95)); +#88557 = VECTOR('',#88558,1.); +#88558 = DIRECTION('',(1.,0.E+000)); +#88559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88560 = PCURVE('',#88399,#88561); +#88561 = DEFINITIONAL_REPRESENTATION('',(#88562),#88566); +#88562 = LINE('',#88563,#88564); +#88563 = CARTESIAN_POINT('',(-3.09999888,-3.09999888)); +#88564 = VECTOR('',#88565,1.); +#88565 = DIRECTION('',(0.E+000,1.)); +#88566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88567 = ORIENTED_EDGE('',*,*,#88568,.F.); +#88568 = EDGE_CURVE('',#88569,#88546,#88571,.T.); +#88569 = VERTEX_POINT('',#88570); +#88570 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); +#88571 = SURFACE_CURVE('',#88572,(#88576,#88583),.PCURVE_S1.); +#88572 = LINE('',#88573,#88574); +#88573 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); +#88574 = VECTOR('',#88575,1.); +#88575 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88576 = PCURVE('',#88508,#88577); +#88577 = DEFINITIONAL_REPRESENTATION('',(#88578),#88582); +#88578 = LINE('',#88579,#88580); +#88579 = CARTESIAN_POINT('',(3.09999888,0.E+000)); +#88580 = VECTOR('',#88581,1.); +#88581 = DIRECTION('',(0.E+000,-1.)); +#88582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88583 = PCURVE('',#88371,#88584); +#88584 = DEFINITIONAL_REPRESENTATION('',(#88585),#88589); +#88585 = LINE('',#88586,#88587); +#88586 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88587 = VECTOR('',#88588,1.); +#88588 = DIRECTION('',(0.E+000,-1.)); +#88589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88590 = ORIENTED_EDGE('',*,*,#88591,.F.); +#88591 = EDGE_CURVE('',#88493,#88569,#88592,.T.); +#88592 = SURFACE_CURVE('',#88593,(#88597,#88604),.PCURVE_S1.); +#88593 = LINE('',#88594,#88595); +#88594 = CARTESIAN_POINT('',(-1.54999944,-1.54999944,0.E+000)); +#88595 = VECTOR('',#88596,1.); +#88596 = DIRECTION('',(0.E+000,1.,0.E+000)); +#88597 = PCURVE('',#88508,#88598); +#88598 = DEFINITIONAL_REPRESENTATION('',(#88599),#88603); +#88599 = LINE('',#88600,#88601); +#88600 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88601 = VECTOR('',#88602,1.); +#88602 = DIRECTION('',(1.,0.E+000)); +#88603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88604 = PCURVE('',#88453,#88605); +#88605 = DEFINITIONAL_REPRESENTATION('',(#88606),#88610); +#88606 = LINE('',#88607,#88608); +#88607 = CARTESIAN_POINT('',(-3.09999888,-3.09999888)); +#88608 = VECTOR('',#88609,1.); +#88609 = DIRECTION('',(0.E+000,1.)); +#88610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#86266 = ADVANCED_FACE('',(#86267),#86061,.F.); -#86267 = FACE_BOUND('',#86268,.T.); -#86268 = EDGE_LOOP('',(#86269,#86270,#86271,#86272)); -#86269 = ORIENTED_EDGE('',*,*,#86047,.T.); -#86270 = ORIENTED_EDGE('',*,*,#86128,.T.); -#86271 = ORIENTED_EDGE('',*,*,#86199,.T.); -#86272 = ORIENTED_EDGE('',*,*,#86246,.T.); -#86273 = ADVANCED_FACE('',(#86274),#86007,.T.); -#86274 = FACE_BOUND('',#86275,.F.); -#86275 = EDGE_LOOP('',(#86276,#86277,#86278,#86279)); -#86276 = ORIENTED_EDGE('',*,*,#85991,.T.); -#86277 = ORIENTED_EDGE('',*,*,#86077,.T.); -#86278 = ORIENTED_EDGE('',*,*,#86153,.T.); -#86279 = ORIENTED_EDGE('',*,*,#86224,.T.); -#86280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#86284)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#86281,#86282,#86283)) +#88611 = ADVANCED_FACE('',(#88612),#88371,.T.); +#88612 = FACE_BOUND('',#88613,.T.); +#88613 = EDGE_LOOP('',(#88614,#88615,#88636,#88637)); +#88614 = ORIENTED_EDGE('',*,*,#88568,.T.); +#88615 = ORIENTED_EDGE('',*,*,#88616,.T.); +#88616 = EDGE_CURVE('',#88546,#88351,#88617,.T.); +#88617 = SURFACE_CURVE('',#88618,(#88622,#88629),.PCURVE_S1.); +#88618 = LINE('',#88619,#88620); +#88619 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.95)); +#88620 = VECTOR('',#88621,1.); +#88621 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88622 = PCURVE('',#88371,#88623); +#88623 = DEFINITIONAL_REPRESENTATION('',(#88624),#88628); +#88624 = LINE('',#88625,#88626); +#88625 = CARTESIAN_POINT('',(0.E+000,-0.95)); +#88626 = VECTOR('',#88627,1.); +#88627 = DIRECTION('',(1.,0.E+000)); +#88628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88629 = PCURVE('',#88399,#88630); +#88630 = DEFINITIONAL_REPRESENTATION('',(#88631),#88635); +#88631 = LINE('',#88632,#88633); +#88632 = CARTESIAN_POINT('',(-3.09999888,0.E+000)); +#88633 = VECTOR('',#88634,1.); +#88634 = DIRECTION('',(1.,0.E+000)); +#88635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88636 = ORIENTED_EDGE('',*,*,#88348,.F.); +#88637 = ORIENTED_EDGE('',*,*,#88638,.F.); +#88638 = EDGE_CURVE('',#88569,#88349,#88639,.T.); +#88639 = SURFACE_CURVE('',#88640,(#88644,#88651),.PCURVE_S1.); +#88640 = LINE('',#88641,#88642); +#88641 = CARTESIAN_POINT('',(-1.54999944,1.54999944,0.E+000)); +#88642 = VECTOR('',#88643,1.); +#88643 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88644 = PCURVE('',#88371,#88645); +#88645 = DEFINITIONAL_REPRESENTATION('',(#88646),#88650); +#88646 = LINE('',#88647,#88648); +#88647 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88648 = VECTOR('',#88649,1.); +#88649 = DIRECTION('',(1.,0.E+000)); +#88650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88651 = PCURVE('',#88453,#88652); +#88652 = DEFINITIONAL_REPRESENTATION('',(#88653),#88657); +#88653 = LINE('',#88654,#88655); +#88654 = CARTESIAN_POINT('',(-3.09999888,0.E+000)); +#88655 = VECTOR('',#88656,1.); +#88656 = DIRECTION('',(1.,0.E+000)); +#88657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88658 = ADVANCED_FACE('',(#88659),#88453,.F.); +#88659 = FACE_BOUND('',#88660,.T.); +#88660 = EDGE_LOOP('',(#88661,#88662,#88663,#88664)); +#88661 = ORIENTED_EDGE('',*,*,#88439,.T.); +#88662 = ORIENTED_EDGE('',*,*,#88520,.T.); +#88663 = ORIENTED_EDGE('',*,*,#88591,.T.); +#88664 = ORIENTED_EDGE('',*,*,#88638,.T.); +#88665 = ADVANCED_FACE('',(#88666),#88399,.T.); +#88666 = FACE_BOUND('',#88667,.F.); +#88667 = EDGE_LOOP('',(#88668,#88669,#88670,#88671)); +#88668 = ORIENTED_EDGE('',*,*,#88383,.T.); +#88669 = ORIENTED_EDGE('',*,*,#88469,.T.); +#88670 = ORIENTED_EDGE('',*,*,#88545,.T.); +#88671 = ORIENTED_EDGE('',*,*,#88616,.T.); +#88672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#88676)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#88673,#88674,#88675)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#86281 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#86282 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#86283 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#86284 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#86281, +#88673 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#88674 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#88675 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#88676 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#88673, 'distance_accuracy_value','confusion accuracy'); -#86285 = SHAPE_DEFINITION_REPRESENTATION(#86286,#85949); -#86286 = PRODUCT_DEFINITION_SHAPE('','',#86287); -#86287 = PRODUCT_DEFINITION('design','',#86288,#86291); -#86288 = PRODUCT_DEFINITION_FORMATION('','',#86289); -#86289 = PRODUCT('Extruded','Extruded','',(#86290)); -#86290 = PRODUCT_CONTEXT('',#2,'mechanical'); -#86291 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#86292 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#86293,#86295); -#86293 = ( REPRESENTATION_RELATIONSHIP('','',#85949,#85939) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#86294) +#88677 = SHAPE_DEFINITION_REPRESENTATION(#88678,#88341); +#88678 = PRODUCT_DEFINITION_SHAPE('','',#88679); +#88679 = PRODUCT_DEFINITION('design','',#88680,#88683); +#88680 = PRODUCT_DEFINITION_FORMATION('','',#88681); +#88681 = PRODUCT('Extruded','Extruded','',(#88682)); +#88682 = PRODUCT_CONTEXT('',#2,'mechanical'); +#88683 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#88684 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#88685,#88687); +#88685 = ( REPRESENTATION_RELATIONSHIP('','',#88341,#88331) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#88686) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#86294 = ITEM_DEFINED_TRANSFORMATION('','',#11,#85940); -#86295 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #86296); -#86296 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('264','=>[0:1:1:2]','',#85934, - #86287,$); -#86297 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#86289)); -#86298 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#86299,#86301); -#86299 = ( REPRESENTATION_RELATIONSHIP('','',#85939,#85922) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#86300) +#88686 = ITEM_DEFINED_TRANSFORMATION('','',#11,#88332); +#88687 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #88688); +#88688 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('365','=>[0:1:1:2]','',#88326, + #88679,$); +#88689 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#88681)); +#88690 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#88691,#88693); +#88691 = ( REPRESENTATION_RELATIONSHIP('','',#88331,#88314) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#88692) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#86300 = ITEM_DEFINED_TRANSFORMATION('','',#11,#85923); -#86301 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #86302); -#86302 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('265','=>[0:1:1:75]','',#85917, - #85934,$); -#86303 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#85936)); -#86304 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#86305,#86307); -#86305 = ( REPRESENTATION_RELATIONSHIP('','',#85922,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#86306) +#88692 = ITEM_DEFINED_TRANSFORMATION('','',#11,#88315); +#88693 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #88694); +#88694 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('366','=>[0:1:1:75]','',#88309, + #88326,$); +#88695 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#88328)); +#88696 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#88697,#88699); +#88697 = ( REPRESENTATION_RELATIONSHIP('','',#88314,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#88698) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#86306 = ITEM_DEFINED_TRANSFORMATION('','',#11,#219); -#86307 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #86308); -#86308 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('266','=>[0:1:1:74]','',#5, - #85917,$); -#86309 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#85919)); -#86310 = SHAPE_DEFINITION_REPRESENTATION(#86311,#86317); -#86311 = PRODUCT_DEFINITION_SHAPE('','',#86312); -#86312 = PRODUCT_DEFINITION('design','',#86313,#86316); -#86313 = PRODUCT_DEFINITION_FORMATION('','',#86314); -#86314 = PRODUCT('U1','U1','',(#86315)); -#86315 = PRODUCT_CONTEXT('',#2,'mechanical'); -#86316 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#86317 = SHAPE_REPRESENTATION('',(#11,#86318),#86322); -#86318 = AXIS2_PLACEMENT_3D('',#86319,#86320,#86321); -#86319 = CARTESIAN_POINT('',(22.15059832,12.13939914,0.3175)); -#86320 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86321 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#86322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#86326)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#86323,#86324,#86325)) +#88698 = ITEM_DEFINED_TRANSFORMATION('','',#11,#219); +#88699 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #88700); +#88700 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('367','=>[0:1:1:74]','',#5, + #88309,$); +#88701 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#88311)); +#88702 = SHAPE_DEFINITION_REPRESENTATION(#88703,#88709); +#88703 = PRODUCT_DEFINITION_SHAPE('','',#88704); +#88704 = PRODUCT_DEFINITION('design','',#88705,#88708); +#88705 = PRODUCT_DEFINITION_FORMATION('','',#88706); +#88706 = PRODUCT('U1','U1','',(#88707)); +#88707 = PRODUCT_CONTEXT('',#2,'mechanical'); +#88708 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#88709 = SHAPE_REPRESENTATION('',(#11,#88710),#88714); +#88710 = AXIS2_PLACEMENT_3D('',#88711,#88712,#88713); +#88711 = CARTESIAN_POINT('',(22.15059832,12.13939914,0.3175)); +#88712 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88713 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#88714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#88718)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#88715,#88716,#88717)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#86323 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#86324 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#86325 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#86326 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#86323, +#88715 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#88716 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#88717 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#88718 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#88715, 'distance_accuracy_value','confusion accuracy'); -#86327 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#86328),#151200); -#86328 = MANIFOLD_SOLID_BREP('',#86329); -#86329 = CLOSED_SHELL('',(#86330,#86445,#88389,#90328,#92257,#94186, - #94309,#94400,#94509,#94613,#94692,#94771,#94846,#94921,#94995, - #95069,#95144,#95171,#95226,#95233,#95240,#95349,#95453,#95532, - #95611,#95686,#95761,#95835,#95909,#95956,#96011,#96038,#96073, - #96080,#96189,#96293,#96372,#96451,#96526,#96601,#96675,#96749, - #96824,#96851,#96906,#96913,#96920,#97029,#97133,#97212,#97291, - #97366,#97441,#97515,#97589,#97664,#97691,#97746,#97753,#97760, - #97869,#97973,#98052,#98131,#98206,#98281,#98355,#98429,#98504, - #98531,#98586,#98593,#98600,#98709,#98813,#98892,#98971,#99046, - #99121,#99195,#99269,#99344,#99371,#99426,#99433,#99440,#99549, - #99653,#99732,#99811,#99886,#99961,#100035,#100109,#100184,#100211, - #100266,#100273,#100280,#100389,#100493,#100572,#100651,#100726, - #100801,#100875,#100949,#101024,#101051,#101106,#101113,#101120, - #101229,#101333,#101412,#101491,#101566,#101641,#101715,#101789, - #101864,#101891,#101946,#101953,#101960,#102069,#102173,#102252, - #102331,#102406,#102481,#102555,#102629,#102704,#102731,#102786, - #102793,#102800,#102909,#103013,#103092,#103171,#103246,#103321, - #103395,#103469,#103544,#103571,#103626,#103633,#103640,#103749, - #103853,#103932,#104011,#104086,#104161,#104235,#104309,#104384, - #104411,#104466,#104473,#104480,#104589,#104693,#104772,#104851, - #104926,#105001,#105075,#105149,#105224,#105251,#105306,#105313, - #105320,#105429,#105533,#105612,#105691,#105766,#105841,#105915, - #105989,#106064,#106091,#106146,#106153,#106160,#106269,#106373, - #106452,#106531,#106606,#106681,#106755,#106829,#106904,#106931, - #106986,#106993,#107000,#107109,#107213,#107292,#107371,#107446, - #107521,#107595,#107669,#107744,#107771,#107826,#107833,#107840, - #107949,#108053,#108132,#108211,#108286,#108361,#108458,#108555, - #108602,#108657,#108684,#108719,#108726,#108835,#108939,#109018, - #109097,#109172,#109247,#109344,#109441,#109516,#109543,#109598, - #109605,#109612,#109721,#109825,#109904,#109983,#110058,#110133, - #110230,#110327,#110374,#110429,#110456,#110491,#110498,#110607, - #110711,#110836,#110915,#110990,#111065,#111162,#111305,#111352, - #111407,#111434,#111469,#111476,#111585,#111689,#111791,#111870, - #111945,#112020,#112117,#112237,#112284,#112339,#112366,#112401, - #112408,#112517,#112621,#112700,#112779,#112854,#112929,#113026, - #113123,#113170,#113225,#113252,#113287,#113294,#113403,#113507, - #113609,#113688,#113763,#113838,#113935,#114055,#114102,#114157, - #114184,#114219,#114226,#114335,#114439,#114518,#114597,#114672, - #114747,#114844,#114941,#114988,#115043,#115070,#115105,#115112, - #115221,#115325,#115404,#115483,#115558,#115633,#115730,#115827, - #115874,#115929,#115956,#115991,#115998,#116107,#116211,#116290, - #116369,#116444,#116519,#116616,#116713,#116760,#116815,#116842, - #116877,#116884,#116993,#117097,#117176,#117255,#117330,#117405, - #117502,#117599,#117646,#117701,#117728,#117763,#117770,#117879, - #117983,#118062,#118141,#118216,#118291,#118388,#118485,#118532, - #118587,#118614,#118649,#118656,#118765,#118869,#118948,#119027, - #119102,#119177,#119274,#119371,#119418,#119473,#119500,#119535, - #119542,#119651,#119755,#119834,#119913,#119988,#120063,#120160, - #120257,#120304,#120359,#120386,#120421,#120428,#120537,#120641, - #120720,#120799,#120874,#120949,#121046,#121143,#121190,#121245, - #121272,#121307,#121314,#121423,#121527,#121606,#121685,#121760, - #121835,#121932,#122029,#122076,#122131,#122158,#122193,#122200, - #122309,#122413,#122492,#122571,#122646,#122721,#122795,#122869, - #122916,#122971,#122998,#123033,#123040,#123149,#123253,#123332, - #123411,#123486,#123561,#123635,#123709,#123784,#123811,#123866, - #123873,#123880,#123989,#124093,#124172,#124251,#124326,#124401, - #124475,#124549,#124596,#124651,#124678,#124713,#124720,#124829, - #124933,#125012,#125091,#125166,#125241,#125315,#125389,#125436, - #125491,#125518,#125553,#125560,#125669,#125773,#125852,#125931, - #126006,#126081,#126155,#126229,#126276,#126331,#126358,#126393, - #126400,#126509,#126613,#126692,#126771,#126846,#126921,#126995, - #127069,#127116,#127171,#127198,#127233,#127240,#127349,#127453, - #127532,#127611,#127686,#127761,#127835,#127909,#127956,#128011, - #128038,#128073,#128080,#128189,#128293,#128372,#128451,#128526, - #128601,#128675,#128749,#128796,#128851,#128878,#128913,#128920, - #129029,#129133,#129212,#129291,#129366,#129441,#129515,#129589, - #129636,#129691,#129718,#129753,#129760,#129869,#129973,#130052, - #130131,#130206,#130281,#130355,#130429,#130476,#130531,#130558, - #130593,#130600,#130709,#130813,#130892,#131017,#131092,#131167, - #131287,#131361,#131408,#131463,#131490,#131525,#131532,#131641, - #131745,#131824,#131949,#132024,#132099,#132219,#132293,#132340, - #132395,#132422,#132457,#132464,#132573,#132677,#132756,#132881, - #132956,#133031,#133151,#133225,#133272,#133327,#133354,#133389, - #133396,#133505,#133609,#133688,#133813,#133888,#133963,#134083, - #134157,#134204,#134259,#134286,#134321,#134328,#134437,#134541, - #134620,#134745,#134820,#134895,#134969,#135043,#135090,#135145, - #135172,#135207,#135214,#135323,#135427,#135506,#135631,#135706, - #135781,#135855,#135929,#135976,#136031,#136058,#136093,#136100, - #136209,#136313,#136392,#136471,#136546,#136621,#136695,#136769, - #136844,#136871,#136926,#136933,#136940,#137049,#137153,#137278, - #137357,#137432,#137507,#137581,#137701,#137748,#137803,#137830, - #137865,#137872,#137981,#138085,#138164,#138243,#138318,#138393, - #138467,#138541,#138616,#138643,#138698,#138705,#138712,#138821, - #138925,#139004,#139129,#139204,#139279,#139353,#139473,#139548, - #139575,#139630,#139637,#139644,#139753,#139857,#139936,#140061, - #140136,#140211,#140285,#140405,#140480,#140507,#140562,#140569, - #140576,#140685,#140789,#140868,#140993,#141068,#141143,#141217, - #141337,#141412,#141439,#141494,#141501,#141508,#141617,#141721, - #141800,#141925,#142000,#142075,#142149,#142269,#142344,#142371, - #142426,#142433,#142440,#142549,#142653,#142732,#142857,#142932, - #143007,#143081,#143201,#143276,#143303,#143358,#143365,#143372, - #143481,#143585,#143664,#143789,#143864,#143939,#144013,#144133, - #144208,#144235,#144290,#144297,#144304,#144413,#144517,#144642, - #144721,#144796,#144871,#144991,#145065,#145140,#145167,#145222, - #145229,#145236,#145345,#145449,#145574,#145653,#145728,#145803, - #145877,#145951,#146026,#146053,#146108,#146115,#146122,#146231, - #146335,#146460,#146539,#146614,#146689,#146763,#146837,#146912, - #146939,#146994,#147001,#147008,#147117,#147221,#147346,#147425, - #147500,#147575,#147649,#147723,#147798,#147825,#147880,#147887, - #147894,#148003,#148107,#148232,#148311,#148386,#148461,#148535, - #148609,#148684,#148711,#148766,#148773,#148780,#148889,#148993, - #149118,#149243,#149318,#149393,#149513,#149633,#149708,#149735, - #149790,#149797,#149804,#149913,#150017,#150142,#150267,#150342, - #150417,#150537,#150657,#150732,#150759,#150814,#150821,#150828, - #150860,#150906,#150938,#150965,#150997,#151024,#151050,#151076, - #151108,#151135,#151161,#151168,#151195)); -#86330 = ADVANCED_FACE('',(#86331),#86346,.F.); -#86331 = FACE_BOUND('',#86332,.F.); -#86332 = EDGE_LOOP('',(#86333,#86368,#86394,#86426)); -#86333 = ORIENTED_EDGE('',*,*,#86334,.T.); -#86334 = EDGE_CURVE('',#86335,#86337,#86339,.T.); -#86335 = VERTEX_POINT('',#86336); -#86336 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.1)); -#86337 = VERTEX_POINT('',#86338); -#86338 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.1)); -#86339 = SURFACE_CURVE('',#86340,(#86345,#86356),.PCURVE_S1.); -#86340 = CIRCLE('',#86341,0.345974717232); -#86341 = AXIS2_PLACEMENT_3D('',#86342,#86343,#86344); -#86342 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); -#86343 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86344 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86345 = PCURVE('',#86346,#86351); -#86346 = CYLINDRICAL_SURFACE('',#86347,0.345974717232); -#86347 = AXIS2_PLACEMENT_3D('',#86348,#86349,#86350); -#86348 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); -#86349 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86351 = DEFINITIONAL_REPRESENTATION('',(#86352),#86355); -#86352 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86353,#86354),.UNSPECIFIED., +#88719 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#88720),#153592); +#88720 = MANIFOLD_SOLID_BREP('',#88721); +#88721 = CLOSED_SHELL('',(#88722,#88837,#90781,#92720,#94649,#96578, + #96701,#96792,#96901,#97005,#97084,#97163,#97238,#97313,#97387, + #97461,#97536,#97563,#97618,#97625,#97632,#97741,#97845,#97924, + #98003,#98078,#98153,#98227,#98301,#98348,#98403,#98430,#98465, + #98472,#98581,#98685,#98764,#98843,#98918,#98993,#99067,#99141, + #99216,#99243,#99298,#99305,#99312,#99421,#99525,#99604,#99683, + #99758,#99833,#99907,#99981,#100056,#100083,#100138,#100145,#100152, + #100261,#100365,#100444,#100523,#100598,#100673,#100747,#100821, + #100896,#100923,#100978,#100985,#100992,#101101,#101205,#101284, + #101363,#101438,#101513,#101587,#101661,#101736,#101763,#101818, + #101825,#101832,#101941,#102045,#102124,#102203,#102278,#102353, + #102427,#102501,#102576,#102603,#102658,#102665,#102672,#102781, + #102885,#102964,#103043,#103118,#103193,#103267,#103341,#103416, + #103443,#103498,#103505,#103512,#103621,#103725,#103804,#103883, + #103958,#104033,#104107,#104181,#104256,#104283,#104338,#104345, + #104352,#104461,#104565,#104644,#104723,#104798,#104873,#104947, + #105021,#105096,#105123,#105178,#105185,#105192,#105301,#105405, + #105484,#105563,#105638,#105713,#105787,#105861,#105936,#105963, + #106018,#106025,#106032,#106141,#106245,#106324,#106403,#106478, + #106553,#106627,#106701,#106776,#106803,#106858,#106865,#106872, + #106981,#107085,#107164,#107243,#107318,#107393,#107467,#107541, + #107616,#107643,#107698,#107705,#107712,#107821,#107925,#108004, + #108083,#108158,#108233,#108307,#108381,#108456,#108483,#108538, + #108545,#108552,#108661,#108765,#108844,#108923,#108998,#109073, + #109147,#109221,#109296,#109323,#109378,#109385,#109392,#109501, + #109605,#109684,#109763,#109838,#109913,#109987,#110061,#110136, + #110163,#110218,#110225,#110232,#110341,#110445,#110524,#110603, + #110678,#110753,#110850,#110947,#110994,#111049,#111076,#111111, + #111118,#111227,#111331,#111410,#111489,#111564,#111639,#111736, + #111833,#111908,#111935,#111990,#111997,#112004,#112113,#112217, + #112296,#112375,#112450,#112525,#112622,#112719,#112766,#112821, + #112848,#112883,#112890,#112999,#113103,#113228,#113307,#113382, + #113457,#113554,#113697,#113744,#113799,#113826,#113861,#113868, + #113977,#114081,#114183,#114262,#114337,#114412,#114509,#114629, + #114676,#114731,#114758,#114793,#114800,#114909,#115013,#115092, + #115171,#115246,#115321,#115418,#115515,#115562,#115617,#115644, + #115679,#115686,#115795,#115899,#116001,#116080,#116155,#116230, + #116327,#116447,#116494,#116549,#116576,#116611,#116618,#116727, + #116831,#116910,#116989,#117064,#117139,#117236,#117333,#117380, + #117435,#117462,#117497,#117504,#117613,#117717,#117796,#117875, + #117950,#118025,#118122,#118219,#118266,#118321,#118348,#118383, + #118390,#118499,#118603,#118682,#118761,#118836,#118911,#119008, + #119105,#119152,#119207,#119234,#119269,#119276,#119385,#119489, + #119568,#119647,#119722,#119797,#119894,#119991,#120038,#120093, + #120120,#120155,#120162,#120271,#120375,#120454,#120533,#120608, + #120683,#120780,#120877,#120924,#120979,#121006,#121041,#121048, + #121157,#121261,#121340,#121419,#121494,#121569,#121666,#121763, + #121810,#121865,#121892,#121927,#121934,#122043,#122147,#122226, + #122305,#122380,#122455,#122552,#122649,#122696,#122751,#122778, + #122813,#122820,#122929,#123033,#123112,#123191,#123266,#123341, + #123438,#123535,#123582,#123637,#123664,#123699,#123706,#123815, + #123919,#123998,#124077,#124152,#124227,#124324,#124421,#124468, + #124523,#124550,#124585,#124592,#124701,#124805,#124884,#124963, + #125038,#125113,#125187,#125261,#125308,#125363,#125390,#125425, + #125432,#125541,#125645,#125724,#125803,#125878,#125953,#126027, + #126101,#126176,#126203,#126258,#126265,#126272,#126381,#126485, + #126564,#126643,#126718,#126793,#126867,#126941,#126988,#127043, + #127070,#127105,#127112,#127221,#127325,#127404,#127483,#127558, + #127633,#127707,#127781,#127828,#127883,#127910,#127945,#127952, + #128061,#128165,#128244,#128323,#128398,#128473,#128547,#128621, + #128668,#128723,#128750,#128785,#128792,#128901,#129005,#129084, + #129163,#129238,#129313,#129387,#129461,#129508,#129563,#129590, + #129625,#129632,#129741,#129845,#129924,#130003,#130078,#130153, + #130227,#130301,#130348,#130403,#130430,#130465,#130472,#130581, + #130685,#130764,#130843,#130918,#130993,#131067,#131141,#131188, + #131243,#131270,#131305,#131312,#131421,#131525,#131604,#131683, + #131758,#131833,#131907,#131981,#132028,#132083,#132110,#132145, + #132152,#132261,#132365,#132444,#132523,#132598,#132673,#132747, + #132821,#132868,#132923,#132950,#132985,#132992,#133101,#133205, + #133284,#133409,#133484,#133559,#133679,#133753,#133800,#133855, + #133882,#133917,#133924,#134033,#134137,#134216,#134341,#134416, + #134491,#134611,#134685,#134732,#134787,#134814,#134849,#134856, + #134965,#135069,#135148,#135273,#135348,#135423,#135543,#135617, + #135664,#135719,#135746,#135781,#135788,#135897,#136001,#136080, + #136205,#136280,#136355,#136475,#136549,#136596,#136651,#136678, + #136713,#136720,#136829,#136933,#137012,#137137,#137212,#137287, + #137361,#137435,#137482,#137537,#137564,#137599,#137606,#137715, + #137819,#137898,#138023,#138098,#138173,#138247,#138321,#138368, + #138423,#138450,#138485,#138492,#138601,#138705,#138784,#138863, + #138938,#139013,#139087,#139161,#139236,#139263,#139318,#139325, + #139332,#139441,#139545,#139670,#139749,#139824,#139899,#139973, + #140093,#140140,#140195,#140222,#140257,#140264,#140373,#140477, + #140556,#140635,#140710,#140785,#140859,#140933,#141008,#141035, + #141090,#141097,#141104,#141213,#141317,#141396,#141521,#141596, + #141671,#141745,#141865,#141940,#141967,#142022,#142029,#142036, + #142145,#142249,#142328,#142453,#142528,#142603,#142677,#142797, + #142872,#142899,#142954,#142961,#142968,#143077,#143181,#143260, + #143385,#143460,#143535,#143609,#143729,#143804,#143831,#143886, + #143893,#143900,#144009,#144113,#144192,#144317,#144392,#144467, + #144541,#144661,#144736,#144763,#144818,#144825,#144832,#144941, + #145045,#145124,#145249,#145324,#145399,#145473,#145593,#145668, + #145695,#145750,#145757,#145764,#145873,#145977,#146056,#146181, + #146256,#146331,#146405,#146525,#146600,#146627,#146682,#146689, + #146696,#146805,#146909,#147034,#147113,#147188,#147263,#147383, + #147457,#147532,#147559,#147614,#147621,#147628,#147737,#147841, + #147966,#148045,#148120,#148195,#148269,#148343,#148418,#148445, + #148500,#148507,#148514,#148623,#148727,#148852,#148931,#149006, + #149081,#149155,#149229,#149304,#149331,#149386,#149393,#149400, + #149509,#149613,#149738,#149817,#149892,#149967,#150041,#150115, + #150190,#150217,#150272,#150279,#150286,#150395,#150499,#150624, + #150703,#150778,#150853,#150927,#151001,#151076,#151103,#151158, + #151165,#151172,#151281,#151385,#151510,#151635,#151710,#151785, + #151905,#152025,#152100,#152127,#152182,#152189,#152196,#152305, + #152409,#152534,#152659,#152734,#152809,#152929,#153049,#153124, + #153151,#153206,#153213,#153220,#153252,#153298,#153330,#153357, + #153389,#153416,#153442,#153468,#153500,#153527,#153553,#153560, + #153587)); +#88722 = ADVANCED_FACE('',(#88723),#88738,.F.); +#88723 = FACE_BOUND('',#88724,.F.); +#88724 = EDGE_LOOP('',(#88725,#88760,#88786,#88818)); +#88725 = ORIENTED_EDGE('',*,*,#88726,.T.); +#88726 = EDGE_CURVE('',#88727,#88729,#88731,.T.); +#88727 = VERTEX_POINT('',#88728); +#88728 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.1)); +#88729 = VERTEX_POINT('',#88730); +#88730 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.1)); +#88731 = SURFACE_CURVE('',#88732,(#88737,#88748),.PCURVE_S1.); +#88732 = CIRCLE('',#88733,0.345974717232); +#88733 = AXIS2_PLACEMENT_3D('',#88734,#88735,#88736); +#88734 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); +#88735 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88736 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88737 = PCURVE('',#88738,#88743); +#88738 = CYLINDRICAL_SURFACE('',#88739,0.345974717232); +#88739 = AXIS2_PLACEMENT_3D('',#88740,#88741,#88742); +#88740 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); +#88741 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88743 = DEFINITIONAL_REPRESENTATION('',(#88744),#88747); +#88744 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88745,#88746),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#86353 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#86354 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#86355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86356 = PCURVE('',#86357,#86362); -#86357 = PLANE('',#86358); -#86358 = AXIS2_PLACEMENT_3D('',#86359,#86360,#86361); -#86359 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); -#86360 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86361 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86362 = DEFINITIONAL_REPRESENTATION('',(#86363),#86367); -#86363 = CIRCLE('',#86364,0.345974717232); -#86364 = AXIS2_PLACEMENT_2D('',#86365,#86366); -#86365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86366 = DIRECTION('',(1.,0.E+000)); -#86367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86368 = ORIENTED_EDGE('',*,*,#86369,.T.); -#86369 = EDGE_CURVE('',#86337,#86370,#86372,.T.); -#86370 = VERTEX_POINT('',#86371); -#86371 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.4)); -#86372 = SURFACE_CURVE('',#86373,(#86377,#86383),.PCURVE_S1.); -#86373 = LINE('',#86374,#86375); -#86374 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.1)); -#86375 = VECTOR('',#86376,1.); -#86376 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86377 = PCURVE('',#86346,#86378); -#86378 = DEFINITIONAL_REPRESENTATION('',(#86379),#86382); -#86379 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86380,#86381),.UNSPECIFIED., +#88745 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#88746 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#88747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88748 = PCURVE('',#88749,#88754); +#88749 = PLANE('',#88750); +#88750 = AXIS2_PLACEMENT_3D('',#88751,#88752,#88753); +#88751 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); +#88752 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88753 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88754 = DEFINITIONAL_REPRESENTATION('',(#88755),#88759); +#88755 = CIRCLE('',#88756,0.345974717232); +#88756 = AXIS2_PLACEMENT_2D('',#88757,#88758); +#88757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88758 = DIRECTION('',(1.,0.E+000)); +#88759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88760 = ORIENTED_EDGE('',*,*,#88761,.T.); +#88761 = EDGE_CURVE('',#88729,#88762,#88764,.T.); +#88762 = VERTEX_POINT('',#88763); +#88763 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.4)); +#88764 = SURFACE_CURVE('',#88765,(#88769,#88775),.PCURVE_S1.); +#88765 = LINE('',#88766,#88767); +#88766 = CARTESIAN_POINT('',(1.224883566201,0.95874916833,1.1)); +#88767 = VECTOR('',#88768,1.); +#88768 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88769 = PCURVE('',#88738,#88770); +#88770 = DEFINITIONAL_REPRESENTATION('',(#88771),#88774); +#88771 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88772,#88773),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#86380 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#86381 = CARTESIAN_POINT('',(6.28318530718,0.3)); -#86382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86383 = PCURVE('',#86384,#86389); -#86384 = CYLINDRICAL_SURFACE('',#86385,0.345974717232); -#86385 = AXIS2_PLACEMENT_3D('',#86386,#86387,#86388); -#86386 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); -#86387 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86388 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86389 = DEFINITIONAL_REPRESENTATION('',(#86390),#86393); -#86390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86391,#86392),.UNSPECIFIED., +#88772 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#88773 = CARTESIAN_POINT('',(6.28318530718,0.3)); +#88774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88775 = PCURVE('',#88776,#88781); +#88776 = CYLINDRICAL_SURFACE('',#88777,0.345974717232); +#88777 = AXIS2_PLACEMENT_3D('',#88778,#88779,#88780); +#88778 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); +#88779 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88780 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88781 = DEFINITIONAL_REPRESENTATION('',(#88782),#88785); +#88782 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88783,#88784),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#86391 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86392 = CARTESIAN_POINT('',(0.E+000,0.3)); -#86393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86394 = ORIENTED_EDGE('',*,*,#86395,.F.); -#86395 = EDGE_CURVE('',#86396,#86370,#86398,.T.); -#86396 = VERTEX_POINT('',#86397); -#86397 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.4)); -#86398 = SURFACE_CURVE('',#86399,(#86404,#86410),.PCURVE_S1.); -#86399 = CIRCLE('',#86400,0.345974717232); -#86400 = AXIS2_PLACEMENT_3D('',#86401,#86402,#86403); -#86401 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.4)); -#86402 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86403 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86404 = PCURVE('',#86346,#86405); -#86405 = DEFINITIONAL_REPRESENTATION('',(#86406),#86409); -#86406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86407,#86408),.UNSPECIFIED., +#88783 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88784 = CARTESIAN_POINT('',(0.E+000,0.3)); +#88785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88786 = ORIENTED_EDGE('',*,*,#88787,.F.); +#88787 = EDGE_CURVE('',#88788,#88762,#88790,.T.); +#88788 = VERTEX_POINT('',#88789); +#88789 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.4)); +#88790 = SURFACE_CURVE('',#88791,(#88796,#88802),.PCURVE_S1.); +#88791 = CIRCLE('',#88792,0.345974717232); +#88792 = AXIS2_PLACEMENT_3D('',#88793,#88794,#88795); +#88793 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.4)); +#88794 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88795 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88796 = PCURVE('',#88738,#88797); +#88797 = DEFINITIONAL_REPRESENTATION('',(#88798),#88801); +#88798 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88799,#88800),.UNSPECIFIED., .F.,.F.,(2,2),(3.14159265359,6.28318530718),.PIECEWISE_BEZIER_KNOTS.); -#86407 = CARTESIAN_POINT('',(3.14159265359,0.3)); -#86408 = CARTESIAN_POINT('',(6.28318530718,0.3)); -#86409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86410 = PCURVE('',#86411,#86416); -#86411 = PLANE('',#86412); -#86412 = AXIS2_PLACEMENT_3D('',#86413,#86414,#86415); -#86413 = CARTESIAN_POINT('',(0.E+000,10.,1.4)); -#86414 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86415 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86416 = DEFINITIONAL_REPRESENTATION('',(#86417),#86425); -#86417 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#86418,#86419,#86420,#86421 - ,#86422,#86423,#86424),.UNSPECIFIED.,.T.,.F.) +#88799 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#88800 = CARTESIAN_POINT('',(6.28318530718,0.3)); +#88801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88802 = PCURVE('',#88803,#88808); +#88803 = PLANE('',#88804); +#88804 = AXIS2_PLACEMENT_3D('',#88805,#88806,#88807); +#88805 = CARTESIAN_POINT('',(0.E+000,10.,1.4)); +#88806 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88807 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88808 = DEFINITIONAL_REPRESENTATION('',(#88809),#88817); +#88809 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#88810,#88811,#88812,#88813 + ,#88814,#88815,#88816),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#86418 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); -#86419 = CARTESIAN_POINT('',(-1.224883566201,-8.44200504329)); -#86420 = CARTESIAN_POINT('',(-0.705921490353,-8.74162793748)); -#86421 = CARTESIAN_POINT('',(-0.186959414504,-9.04125083167)); -#86422 = CARTESIAN_POINT('',(-0.705921490353,-9.34087372586)); -#86423 = CARTESIAN_POINT('',(-1.224883566201,-9.64049662005)); -#86424 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); -#86425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86426 = ORIENTED_EDGE('',*,*,#86427,.F.); -#86427 = EDGE_CURVE('',#86335,#86396,#86428,.T.); -#86428 = SURFACE_CURVE('',#86429,(#86433,#86439),.PCURVE_S1.); -#86429 = LINE('',#86430,#86431); -#86430 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.1)); -#86431 = VECTOR('',#86432,1.); -#86432 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86433 = PCURVE('',#86346,#86434); -#86434 = DEFINITIONAL_REPRESENTATION('',(#86435),#86438); -#86435 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86436,#86437),.UNSPECIFIED., +#88810 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); +#88811 = CARTESIAN_POINT('',(-1.224883566201,-8.44200504329)); +#88812 = CARTESIAN_POINT('',(-0.705921490353,-8.74162793748)); +#88813 = CARTESIAN_POINT('',(-0.186959414504,-9.04125083167)); +#88814 = CARTESIAN_POINT('',(-0.705921490353,-9.34087372586)); +#88815 = CARTESIAN_POINT('',(-1.224883566201,-9.64049662005)); +#88816 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); +#88817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88818 = ORIENTED_EDGE('',*,*,#88819,.F.); +#88819 = EDGE_CURVE('',#88727,#88788,#88820,.T.); +#88820 = SURFACE_CURVE('',#88821,(#88825,#88831),.PCURVE_S1.); +#88821 = LINE('',#88822,#88823); +#88822 = CARTESIAN_POINT('',(0.532934131737,0.95874916833,1.1)); +#88823 = VECTOR('',#88824,1.); +#88824 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88825 = PCURVE('',#88738,#88826); +#88826 = DEFINITIONAL_REPRESENTATION('',(#88827),#88830); +#88827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88828,#88829),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#86436 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#86437 = CARTESIAN_POINT('',(3.14159265359,0.3)); -#86438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#88828 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#88829 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#88830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#86439 = PCURVE('',#86384,#86440); -#86440 = DEFINITIONAL_REPRESENTATION('',(#86441),#86444); -#86441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#86442,#86443),.UNSPECIFIED., +#88831 = PCURVE('',#88776,#88832); +#88832 = DEFINITIONAL_REPRESENTATION('',(#88833),#88836); +#88833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#88834,#88835),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.3),.PIECEWISE_BEZIER_KNOTS.); -#86442 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#86443 = CARTESIAN_POINT('',(3.14159265359,0.3)); -#86444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86445 = ADVANCED_FACE('',(#86446,#86565,#86679,#86793,#86907,#87021, - #87135,#87249,#87363,#87477,#87591,#87705,#87819,#87933,#88047, - #88161,#88275),#86460,.F.); -#86446 = FACE_BOUND('',#86447,.T.); -#86447 = EDGE_LOOP('',(#86448,#86483,#86511,#86539)); -#86448 = ORIENTED_EDGE('',*,*,#86449,.T.); -#86449 = EDGE_CURVE('',#86450,#86452,#86454,.T.); -#86450 = VERTEX_POINT('',#86451); -#86451 = CARTESIAN_POINT('',(9.8,10.,0.E+000)); -#86452 = VERTEX_POINT('',#86453); -#86453 = CARTESIAN_POINT('',(0.2,10.,0.E+000)); -#86454 = SURFACE_CURVE('',#86455,(#86459,#86471),.PCURVE_S1.); -#86455 = LINE('',#86456,#86457); -#86456 = CARTESIAN_POINT('',(0.E+000,10.,0.E+000)); -#86457 = VECTOR('',#86458,1.); -#86458 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86459 = PCURVE('',#86460,#86465); -#86460 = PLANE('',#86461); -#86461 = AXIS2_PLACEMENT_3D('',#86462,#86463,#86464); -#86462 = CARTESIAN_POINT('',(0.E+000,10.,1.4)); -#86463 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#86464 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86465 = DEFINITIONAL_REPRESENTATION('',(#86466),#86470); -#86466 = LINE('',#86467,#86468); -#86467 = CARTESIAN_POINT('',(1.4,0.E+000)); -#86468 = VECTOR('',#86469,1.); -#86469 = DIRECTION('',(0.E+000,-1.)); -#86470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86471 = PCURVE('',#86472,#86477); -#86472 = PLANE('',#86473); -#86473 = AXIS2_PLACEMENT_3D('',#86474,#86475,#86476); -#86474 = CARTESIAN_POINT('',(0.E+000,10.,0.E+000)); -#86475 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86476 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86477 = DEFINITIONAL_REPRESENTATION('',(#86478),#86482); -#86478 = LINE('',#86479,#86480); -#86479 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86480 = VECTOR('',#86481,1.); -#86481 = DIRECTION('',(1.,0.E+000)); -#86482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86483 = ORIENTED_EDGE('',*,*,#86484,.T.); -#86484 = EDGE_CURVE('',#86452,#86485,#86487,.T.); -#86485 = VERTEX_POINT('',#86486); -#86486 = CARTESIAN_POINT('',(0.2,10.,1.2)); -#86487 = SURFACE_CURVE('',#86488,(#86492,#86499),.PCURVE_S1.); -#86488 = LINE('',#86489,#86490); -#86489 = CARTESIAN_POINT('',(0.2,10.,1.4)); -#86490 = VECTOR('',#86491,1.); -#86491 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86492 = PCURVE('',#86460,#86493); -#86493 = DEFINITIONAL_REPRESENTATION('',(#86494),#86498); -#86494 = LINE('',#86495,#86496); -#86495 = CARTESIAN_POINT('',(0.E+000,0.2)); -#86496 = VECTOR('',#86497,1.); -#86497 = DIRECTION('',(-1.,0.E+000)); -#86498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86499 = PCURVE('',#86500,#86505); -#86500 = PLANE('',#86501); -#86501 = AXIS2_PLACEMENT_3D('',#86502,#86503,#86504); -#86502 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); -#86503 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#86504 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#86505 = DEFINITIONAL_REPRESENTATION('',(#86506),#86510); -#86506 = LINE('',#86507,#86508); -#86507 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); -#86508 = VECTOR('',#86509,1.); -#86509 = DIRECTION('',(0.E+000,1.)); -#86510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86511 = ORIENTED_EDGE('',*,*,#86512,.T.); -#86512 = EDGE_CURVE('',#86485,#86513,#86515,.T.); -#86513 = VERTEX_POINT('',#86514); -#86514 = CARTESIAN_POINT('',(9.8,10.,1.2)); -#86515 = SURFACE_CURVE('',#86516,(#86520,#86527),.PCURVE_S1.); -#86516 = LINE('',#86517,#86518); -#86517 = CARTESIAN_POINT('',(0.E+000,10.,1.2)); -#86518 = VECTOR('',#86519,1.); -#86519 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86520 = PCURVE('',#86460,#86521); -#86521 = DEFINITIONAL_REPRESENTATION('',(#86522),#86526); -#86522 = LINE('',#86523,#86524); -#86523 = CARTESIAN_POINT('',(0.2,0.E+000)); -#86524 = VECTOR('',#86525,1.); -#86525 = DIRECTION('',(0.E+000,1.)); -#86526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86527 = PCURVE('',#86528,#86533); -#86528 = PLANE('',#86529); -#86529 = AXIS2_PLACEMENT_3D('',#86530,#86531,#86532); -#86530 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); -#86531 = DIRECTION('',(0.E+000,-0.707106781187,-0.707106781187)); -#86532 = DIRECTION('',(0.E+000,0.707106781187,-0.707106781187)); -#86533 = DEFINITIONAL_REPRESENTATION('',(#86534),#86538); -#86534 = LINE('',#86535,#86536); -#86535 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); -#86536 = VECTOR('',#86537,1.); -#86537 = DIRECTION('',(0.E+000,1.)); -#86538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86539 = ORIENTED_EDGE('',*,*,#86540,.T.); -#86540 = EDGE_CURVE('',#86513,#86450,#86541,.T.); -#86541 = SURFACE_CURVE('',#86542,(#86546,#86553),.PCURVE_S1.); -#86542 = LINE('',#86543,#86544); -#86543 = CARTESIAN_POINT('',(9.8,10.,1.4)); -#86544 = VECTOR('',#86545,1.); -#86545 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86546 = PCURVE('',#86460,#86547); -#86547 = DEFINITIONAL_REPRESENTATION('',(#86548),#86552); -#86548 = LINE('',#86549,#86550); -#86549 = CARTESIAN_POINT('',(0.E+000,9.8)); -#86550 = VECTOR('',#86551,1.); -#86551 = DIRECTION('',(1.,0.E+000)); -#86552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86553 = PCURVE('',#86554,#86559); -#86554 = PLANE('',#86555); -#86555 = AXIS2_PLACEMENT_3D('',#86556,#86557,#86558); -#86556 = CARTESIAN_POINT('',(9.8,10.,1.4)); -#86557 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#86558 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#86559 = DEFINITIONAL_REPRESENTATION('',(#86560),#86564); -#86560 = LINE('',#86561,#86562); -#86561 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#86562 = VECTOR('',#86563,1.); -#86563 = DIRECTION('',(0.E+000,-1.)); -#86564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86565 = FACE_BOUND('',#86566,.T.); -#86566 = EDGE_LOOP('',(#86567,#86597,#86625,#86653)); -#86567 = ORIENTED_EDGE('',*,*,#86568,.F.); -#86568 = EDGE_CURVE('',#86569,#86571,#86573,.T.); -#86569 = VERTEX_POINT('',#86570); -#86570 = CARTESIAN_POINT('',(1.85,10.,0.75)); -#86571 = VERTEX_POINT('',#86572); -#86572 = CARTESIAN_POINT('',(1.85,10.,0.65)); -#86573 = SURFACE_CURVE('',#86574,(#86578,#86585),.PCURVE_S1.); -#86574 = LINE('',#86575,#86576); -#86575 = CARTESIAN_POINT('',(1.85,10.,0.65)); -#86576 = VECTOR('',#86577,1.); -#86577 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86578 = PCURVE('',#86460,#86579); -#86579 = DEFINITIONAL_REPRESENTATION('',(#86580),#86584); -#86580 = LINE('',#86581,#86582); -#86581 = CARTESIAN_POINT('',(0.75,1.85)); -#86582 = VECTOR('',#86583,1.); -#86583 = DIRECTION('',(1.,0.E+000)); -#86584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86585 = PCURVE('',#86586,#86591); -#86586 = PLANE('',#86587); -#86587 = AXIS2_PLACEMENT_3D('',#86588,#86589,#86590); -#86588 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); -#86589 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86590 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86591 = DEFINITIONAL_REPRESENTATION('',(#86592),#86596); -#86592 = LINE('',#86593,#86594); -#86593 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#86594 = VECTOR('',#86595,1.); -#86595 = DIRECTION('',(-1.,0.E+000)); -#86596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86597 = ORIENTED_EDGE('',*,*,#86598,.F.); -#86598 = EDGE_CURVE('',#86599,#86569,#86601,.T.); -#86599 = VERTEX_POINT('',#86600); -#86600 = CARTESIAN_POINT('',(1.65,10.,0.75)); -#86601 = SURFACE_CURVE('',#86602,(#86606,#86613),.PCURVE_S1.); -#86602 = LINE('',#86603,#86604); -#86603 = CARTESIAN_POINT('',(1.85,10.,0.75)); -#86604 = VECTOR('',#86605,1.); -#86605 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#86606 = PCURVE('',#86460,#86607); -#86607 = DEFINITIONAL_REPRESENTATION('',(#86608),#86612); -#86608 = LINE('',#86609,#86610); -#86609 = CARTESIAN_POINT('',(0.65,1.85)); -#86610 = VECTOR('',#86611,1.); -#86611 = DIRECTION('',(0.E+000,1.)); -#86612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86613 = PCURVE('',#86614,#86619); -#86614 = PLANE('',#86615); -#86615 = AXIS2_PLACEMENT_3D('',#86616,#86617,#86618); -#86616 = CARTESIAN_POINT('',(1.85,10.527847992439,0.75)); -#86617 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#86618 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#86619 = DEFINITIONAL_REPRESENTATION('',(#86620),#86624); -#86620 = LINE('',#86621,#86622); -#86621 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#86622 = VECTOR('',#86623,1.); -#86623 = DIRECTION('',(-8.881784197001E-016,1.)); -#86624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86625 = ORIENTED_EDGE('',*,*,#86626,.F.); -#86626 = EDGE_CURVE('',#86627,#86599,#86629,.T.); -#86627 = VERTEX_POINT('',#86628); -#86628 = CARTESIAN_POINT('',(1.65,10.,0.65)); -#86629 = SURFACE_CURVE('',#86630,(#86634,#86641),.PCURVE_S1.); -#86630 = LINE('',#86631,#86632); -#86631 = CARTESIAN_POINT('',(1.65,10.,0.65)); -#86632 = VECTOR('',#86633,1.); -#86633 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86634 = PCURVE('',#86460,#86635); -#86635 = DEFINITIONAL_REPRESENTATION('',(#86636),#86640); -#86636 = LINE('',#86637,#86638); -#86637 = CARTESIAN_POINT('',(0.75,1.65)); -#86638 = VECTOR('',#86639,1.); -#86639 = DIRECTION('',(-1.,0.E+000)); -#86640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86641 = PCURVE('',#86642,#86647); -#86642 = PLANE('',#86643); -#86643 = AXIS2_PLACEMENT_3D('',#86644,#86645,#86646); -#86644 = CARTESIAN_POINT('',(1.65,10.527847992439,0.65)); -#86645 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86646 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86647 = DEFINITIONAL_REPRESENTATION('',(#86648),#86652); -#86648 = LINE('',#86649,#86650); -#86649 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#86650 = VECTOR('',#86651,1.); -#86651 = DIRECTION('',(-1.,0.E+000)); -#86652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86653 = ORIENTED_EDGE('',*,*,#86654,.F.); -#86654 = EDGE_CURVE('',#86571,#86627,#86655,.T.); -#86655 = SURFACE_CURVE('',#86656,(#86660,#86667),.PCURVE_S1.); -#86656 = LINE('',#86657,#86658); -#86657 = CARTESIAN_POINT('',(1.85,10.,0.65)); -#86658 = VECTOR('',#86659,1.); -#86659 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#86660 = PCURVE('',#86460,#86661); -#86661 = DEFINITIONAL_REPRESENTATION('',(#86662),#86666); -#86662 = LINE('',#86663,#86664); -#86663 = CARTESIAN_POINT('',(0.75,1.85)); -#86664 = VECTOR('',#86665,1.); -#86665 = DIRECTION('',(0.E+000,-1.)); -#86666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86667 = PCURVE('',#86668,#86673); -#86668 = PLANE('',#86669); -#86669 = AXIS2_PLACEMENT_3D('',#86670,#86671,#86672); -#86670 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); -#86671 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#86672 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#86673 = DEFINITIONAL_REPRESENTATION('',(#86674),#86678); -#86674 = LINE('',#86675,#86676); -#86675 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#86676 = VECTOR('',#86677,1.); -#86677 = DIRECTION('',(-8.881784197001E-016,-1.)); -#86678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86679 = FACE_BOUND('',#86680,.T.); -#86680 = EDGE_LOOP('',(#86681,#86711,#86739,#86767)); -#86681 = ORIENTED_EDGE('',*,*,#86682,.F.); -#86682 = EDGE_CURVE('',#86683,#86685,#86687,.T.); -#86683 = VERTEX_POINT('',#86684); -#86684 = CARTESIAN_POINT('',(2.85,10.,0.75)); -#86685 = VERTEX_POINT('',#86686); -#86686 = CARTESIAN_POINT('',(2.85,10.,0.65)); -#86687 = SURFACE_CURVE('',#86688,(#86692,#86699),.PCURVE_S1.); -#86688 = LINE('',#86689,#86690); -#86689 = CARTESIAN_POINT('',(2.85,10.,0.65)); -#86690 = VECTOR('',#86691,1.); -#86691 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86692 = PCURVE('',#86460,#86693); -#86693 = DEFINITIONAL_REPRESENTATION('',(#86694),#86698); -#86694 = LINE('',#86695,#86696); -#86695 = CARTESIAN_POINT('',(0.75,2.85)); -#86696 = VECTOR('',#86697,1.); -#86697 = DIRECTION('',(1.,0.E+000)); -#86698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86699 = PCURVE('',#86700,#86705); -#86700 = PLANE('',#86701); -#86701 = AXIS2_PLACEMENT_3D('',#86702,#86703,#86704); -#86702 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); -#86703 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86704 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86705 = DEFINITIONAL_REPRESENTATION('',(#86706),#86710); -#86706 = LINE('',#86707,#86708); -#86707 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#86708 = VECTOR('',#86709,1.); -#86709 = DIRECTION('',(-1.,0.E+000)); -#86710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86711 = ORIENTED_EDGE('',*,*,#86712,.F.); -#86712 = EDGE_CURVE('',#86713,#86683,#86715,.T.); -#86713 = VERTEX_POINT('',#86714); -#86714 = CARTESIAN_POINT('',(2.65,10.,0.75)); -#86715 = SURFACE_CURVE('',#86716,(#86720,#86727),.PCURVE_S1.); -#86716 = LINE('',#86717,#86718); -#86717 = CARTESIAN_POINT('',(2.85,10.,0.75)); -#86718 = VECTOR('',#86719,1.); -#86719 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#86720 = PCURVE('',#86460,#86721); -#86721 = DEFINITIONAL_REPRESENTATION('',(#86722),#86726); -#86722 = LINE('',#86723,#86724); -#86723 = CARTESIAN_POINT('',(0.65,2.85)); -#86724 = VECTOR('',#86725,1.); -#86725 = DIRECTION('',(0.E+000,1.)); -#86726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86727 = PCURVE('',#86728,#86733); -#86728 = PLANE('',#86729); -#86729 = AXIS2_PLACEMENT_3D('',#86730,#86731,#86732); -#86730 = CARTESIAN_POINT('',(2.85,10.527847992439,0.75)); -#86731 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#86732 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#86733 = DEFINITIONAL_REPRESENTATION('',(#86734),#86738); -#86734 = LINE('',#86735,#86736); -#86735 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#86736 = VECTOR('',#86737,1.); -#86737 = DIRECTION('',(-8.881784197001E-016,1.)); -#86738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86739 = ORIENTED_EDGE('',*,*,#86740,.F.); -#86740 = EDGE_CURVE('',#86741,#86713,#86743,.T.); -#86741 = VERTEX_POINT('',#86742); -#86742 = CARTESIAN_POINT('',(2.65,10.,0.65)); -#86743 = SURFACE_CURVE('',#86744,(#86748,#86755),.PCURVE_S1.); -#86744 = LINE('',#86745,#86746); -#86745 = CARTESIAN_POINT('',(2.65,10.,0.65)); -#86746 = VECTOR('',#86747,1.); -#86747 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86748 = PCURVE('',#86460,#86749); -#86749 = DEFINITIONAL_REPRESENTATION('',(#86750),#86754); -#86750 = LINE('',#86751,#86752); -#86751 = CARTESIAN_POINT('',(0.75,2.65)); -#86752 = VECTOR('',#86753,1.); -#86753 = DIRECTION('',(-1.,0.E+000)); -#86754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86755 = PCURVE('',#86756,#86761); -#86756 = PLANE('',#86757); -#86757 = AXIS2_PLACEMENT_3D('',#86758,#86759,#86760); -#86758 = CARTESIAN_POINT('',(2.65,10.527847992439,0.65)); -#86759 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86760 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86761 = DEFINITIONAL_REPRESENTATION('',(#86762),#86766); -#86762 = LINE('',#86763,#86764); -#86763 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#86764 = VECTOR('',#86765,1.); -#86765 = DIRECTION('',(-1.,0.E+000)); -#86766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86767 = ORIENTED_EDGE('',*,*,#86768,.F.); -#86768 = EDGE_CURVE('',#86685,#86741,#86769,.T.); -#86769 = SURFACE_CURVE('',#86770,(#86774,#86781),.PCURVE_S1.); -#86770 = LINE('',#86771,#86772); -#86771 = CARTESIAN_POINT('',(2.85,10.,0.65)); -#86772 = VECTOR('',#86773,1.); -#86773 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#86774 = PCURVE('',#86460,#86775); -#86775 = DEFINITIONAL_REPRESENTATION('',(#86776),#86780); -#86776 = LINE('',#86777,#86778); -#86777 = CARTESIAN_POINT('',(0.75,2.85)); -#86778 = VECTOR('',#86779,1.); -#86779 = DIRECTION('',(0.E+000,-1.)); -#86780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86781 = PCURVE('',#86782,#86787); -#86782 = PLANE('',#86783); -#86783 = AXIS2_PLACEMENT_3D('',#86784,#86785,#86786); -#86784 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); -#86785 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#86786 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#86787 = DEFINITIONAL_REPRESENTATION('',(#86788),#86792); -#86788 = LINE('',#86789,#86790); -#86789 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#86790 = VECTOR('',#86791,1.); -#86791 = DIRECTION('',(-8.881784197001E-016,-1.)); -#86792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86793 = FACE_BOUND('',#86794,.T.); -#86794 = EDGE_LOOP('',(#86795,#86825,#86853,#86881)); -#86795 = ORIENTED_EDGE('',*,*,#86796,.F.); -#86796 = EDGE_CURVE('',#86797,#86799,#86801,.T.); -#86797 = VERTEX_POINT('',#86798); -#86798 = CARTESIAN_POINT('',(3.85,10.,0.75)); -#86799 = VERTEX_POINT('',#86800); -#86800 = CARTESIAN_POINT('',(3.85,10.,0.65)); -#86801 = SURFACE_CURVE('',#86802,(#86806,#86813),.PCURVE_S1.); -#86802 = LINE('',#86803,#86804); -#86803 = CARTESIAN_POINT('',(3.85,10.,0.65)); -#86804 = VECTOR('',#86805,1.); -#86805 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86806 = PCURVE('',#86460,#86807); -#86807 = DEFINITIONAL_REPRESENTATION('',(#86808),#86812); -#86808 = LINE('',#86809,#86810); -#86809 = CARTESIAN_POINT('',(0.75,3.85)); -#86810 = VECTOR('',#86811,1.); -#86811 = DIRECTION('',(1.,0.E+000)); -#86812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86813 = PCURVE('',#86814,#86819); -#86814 = PLANE('',#86815); -#86815 = AXIS2_PLACEMENT_3D('',#86816,#86817,#86818); -#86816 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); -#86817 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86818 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86819 = DEFINITIONAL_REPRESENTATION('',(#86820),#86824); -#86820 = LINE('',#86821,#86822); -#86821 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#86822 = VECTOR('',#86823,1.); -#86823 = DIRECTION('',(-1.,0.E+000)); -#86824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86825 = ORIENTED_EDGE('',*,*,#86826,.F.); -#86826 = EDGE_CURVE('',#86827,#86797,#86829,.T.); -#86827 = VERTEX_POINT('',#86828); -#86828 = CARTESIAN_POINT('',(3.65,10.,0.75)); -#86829 = SURFACE_CURVE('',#86830,(#86834,#86841),.PCURVE_S1.); -#86830 = LINE('',#86831,#86832); -#86831 = CARTESIAN_POINT('',(3.85,10.,0.75)); -#86832 = VECTOR('',#86833,1.); -#86833 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#86834 = PCURVE('',#86460,#86835); -#86835 = DEFINITIONAL_REPRESENTATION('',(#86836),#86840); -#86836 = LINE('',#86837,#86838); -#86837 = CARTESIAN_POINT('',(0.65,3.85)); -#86838 = VECTOR('',#86839,1.); -#86839 = DIRECTION('',(0.E+000,1.)); -#86840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86841 = PCURVE('',#86842,#86847); -#86842 = PLANE('',#86843); -#86843 = AXIS2_PLACEMENT_3D('',#86844,#86845,#86846); -#86844 = CARTESIAN_POINT('',(3.85,10.527847992439,0.75)); -#86845 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#86846 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#86847 = DEFINITIONAL_REPRESENTATION('',(#86848),#86852); -#86848 = LINE('',#86849,#86850); -#86849 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#86850 = VECTOR('',#86851,1.); -#86851 = DIRECTION('',(-8.881784197001E-016,1.)); -#86852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86853 = ORIENTED_EDGE('',*,*,#86854,.F.); -#86854 = EDGE_CURVE('',#86855,#86827,#86857,.T.); -#86855 = VERTEX_POINT('',#86856); -#86856 = CARTESIAN_POINT('',(3.65,10.,0.65)); -#86857 = SURFACE_CURVE('',#86858,(#86862,#86869),.PCURVE_S1.); -#86858 = LINE('',#86859,#86860); -#86859 = CARTESIAN_POINT('',(3.65,10.,0.65)); -#86860 = VECTOR('',#86861,1.); -#86861 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86862 = PCURVE('',#86460,#86863); -#86863 = DEFINITIONAL_REPRESENTATION('',(#86864),#86868); -#86864 = LINE('',#86865,#86866); -#86865 = CARTESIAN_POINT('',(0.75,3.65)); -#86866 = VECTOR('',#86867,1.); -#86867 = DIRECTION('',(-1.,0.E+000)); -#86868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86869 = PCURVE('',#86870,#86875); -#86870 = PLANE('',#86871); -#86871 = AXIS2_PLACEMENT_3D('',#86872,#86873,#86874); -#86872 = CARTESIAN_POINT('',(3.65,10.527847992439,0.65)); -#86873 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86874 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86875 = DEFINITIONAL_REPRESENTATION('',(#86876),#86880); -#86876 = LINE('',#86877,#86878); -#86877 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#86878 = VECTOR('',#86879,1.); -#86879 = DIRECTION('',(-1.,0.E+000)); -#86880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86881 = ORIENTED_EDGE('',*,*,#86882,.F.); -#86882 = EDGE_CURVE('',#86799,#86855,#86883,.T.); -#86883 = SURFACE_CURVE('',#86884,(#86888,#86895),.PCURVE_S1.); -#86884 = LINE('',#86885,#86886); -#86885 = CARTESIAN_POINT('',(3.85,10.,0.65)); -#86886 = VECTOR('',#86887,1.); -#86887 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#86888 = PCURVE('',#86460,#86889); -#86889 = DEFINITIONAL_REPRESENTATION('',(#86890),#86894); -#86890 = LINE('',#86891,#86892); -#86891 = CARTESIAN_POINT('',(0.75,3.85)); -#86892 = VECTOR('',#86893,1.); -#86893 = DIRECTION('',(0.E+000,-1.)); -#86894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86895 = PCURVE('',#86896,#86901); -#86896 = PLANE('',#86897); -#86897 = AXIS2_PLACEMENT_3D('',#86898,#86899,#86900); -#86898 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); -#86899 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#86900 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#86901 = DEFINITIONAL_REPRESENTATION('',(#86902),#86906); -#86902 = LINE('',#86903,#86904); -#86903 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#86904 = VECTOR('',#86905,1.); -#86905 = DIRECTION('',(-8.881784197001E-016,-1.)); -#86906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86907 = FACE_BOUND('',#86908,.T.); -#86908 = EDGE_LOOP('',(#86909,#86939,#86967,#86995)); -#86909 = ORIENTED_EDGE('',*,*,#86910,.F.); -#86910 = EDGE_CURVE('',#86911,#86913,#86915,.T.); -#86911 = VERTEX_POINT('',#86912); -#86912 = CARTESIAN_POINT('',(5.15,10.,0.65)); -#86913 = VERTEX_POINT('',#86914); -#86914 = CARTESIAN_POINT('',(5.15,10.,0.75)); -#86915 = SURFACE_CURVE('',#86916,(#86920,#86927),.PCURVE_S1.); -#86916 = LINE('',#86917,#86918); -#86917 = CARTESIAN_POINT('',(5.15,10.,0.65)); -#86918 = VECTOR('',#86919,1.); -#86919 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86920 = PCURVE('',#86460,#86921); -#86921 = DEFINITIONAL_REPRESENTATION('',(#86922),#86926); -#86922 = LINE('',#86923,#86924); -#86923 = CARTESIAN_POINT('',(0.75,5.15)); -#86924 = VECTOR('',#86925,1.); -#86925 = DIRECTION('',(-1.,0.E+000)); -#86926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86927 = PCURVE('',#86928,#86933); -#86928 = PLANE('',#86929); -#86929 = AXIS2_PLACEMENT_3D('',#86930,#86931,#86932); -#86930 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); -#86931 = DIRECTION('',(1.,0.E+000,0.E+000)); -#86932 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86933 = DEFINITIONAL_REPRESENTATION('',(#86934),#86938); -#86934 = LINE('',#86935,#86936); -#86935 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#86936 = VECTOR('',#86937,1.); -#86937 = DIRECTION('',(-1.,0.E+000)); -#86938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86939 = ORIENTED_EDGE('',*,*,#86940,.F.); -#86940 = EDGE_CURVE('',#86941,#86911,#86943,.T.); -#86941 = VERTEX_POINT('',#86942); -#86942 = CARTESIAN_POINT('',(5.35,10.,0.65)); -#86943 = SURFACE_CURVE('',#86944,(#86948,#86955),.PCURVE_S1.); -#86944 = LINE('',#86945,#86946); -#86945 = CARTESIAN_POINT('',(5.15,10.,0.65)); -#86946 = VECTOR('',#86947,1.); -#86947 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#86948 = PCURVE('',#86460,#86949); -#86949 = DEFINITIONAL_REPRESENTATION('',(#86950),#86954); -#86950 = LINE('',#86951,#86952); -#86951 = CARTESIAN_POINT('',(0.75,5.15)); -#86952 = VECTOR('',#86953,1.); -#86953 = DIRECTION('',(0.E+000,-1.)); -#86954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86955 = PCURVE('',#86956,#86961); -#86956 = PLANE('',#86957); -#86957 = AXIS2_PLACEMENT_3D('',#86958,#86959,#86960); -#86958 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); -#86959 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#86960 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#86961 = DEFINITIONAL_REPRESENTATION('',(#86962),#86966); -#86962 = LINE('',#86963,#86964); -#86963 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#86964 = VECTOR('',#86965,1.); -#86965 = DIRECTION('',(-8.881784197001E-016,-1.)); -#86966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86967 = ORIENTED_EDGE('',*,*,#86968,.F.); -#86968 = EDGE_CURVE('',#86969,#86941,#86971,.T.); -#86969 = VERTEX_POINT('',#86970); -#86970 = CARTESIAN_POINT('',(5.35,10.,0.75)); -#86971 = SURFACE_CURVE('',#86972,(#86976,#86983),.PCURVE_S1.); -#86972 = LINE('',#86973,#86974); -#86973 = CARTESIAN_POINT('',(5.35,10.,0.65)); -#86974 = VECTOR('',#86975,1.); -#86975 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#86976 = PCURVE('',#86460,#86977); -#86977 = DEFINITIONAL_REPRESENTATION('',(#86978),#86982); -#86978 = LINE('',#86979,#86980); -#86979 = CARTESIAN_POINT('',(0.75,5.35)); -#86980 = VECTOR('',#86981,1.); -#86981 = DIRECTION('',(1.,0.E+000)); -#86982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86983 = PCURVE('',#86984,#86989); -#86984 = PLANE('',#86985); -#86985 = AXIS2_PLACEMENT_3D('',#86986,#86987,#86988); -#86986 = CARTESIAN_POINT('',(5.35,10.527847992439,0.65)); -#86987 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#86988 = DIRECTION('',(0.E+000,0.E+000,1.)); -#86989 = DEFINITIONAL_REPRESENTATION('',(#86990),#86994); -#86990 = LINE('',#86991,#86992); -#86991 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#86992 = VECTOR('',#86993,1.); -#86993 = DIRECTION('',(-1.,0.E+000)); -#86994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#86995 = ORIENTED_EDGE('',*,*,#86996,.F.); -#86996 = EDGE_CURVE('',#86913,#86969,#86997,.T.); -#86997 = SURFACE_CURVE('',#86998,(#87002,#87009),.PCURVE_S1.); -#86998 = LINE('',#86999,#87000); -#86999 = CARTESIAN_POINT('',(5.15,10.,0.75)); -#87000 = VECTOR('',#87001,1.); -#87001 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87002 = PCURVE('',#86460,#87003); -#87003 = DEFINITIONAL_REPRESENTATION('',(#87004),#87008); -#87004 = LINE('',#87005,#87006); -#87005 = CARTESIAN_POINT('',(0.65,5.15)); -#87006 = VECTOR('',#87007,1.); -#87007 = DIRECTION('',(0.E+000,1.)); -#87008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87009 = PCURVE('',#87010,#87015); -#87010 = PLANE('',#87011); -#87011 = AXIS2_PLACEMENT_3D('',#87012,#87013,#87014); -#87012 = CARTESIAN_POINT('',(5.15,10.527847992439,0.75)); -#87013 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87014 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87015 = DEFINITIONAL_REPRESENTATION('',(#87016),#87020); -#87016 = LINE('',#87017,#87018); -#87017 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87018 = VECTOR('',#87019,1.); -#87019 = DIRECTION('',(-8.881784197001E-016,1.)); -#87020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87021 = FACE_BOUND('',#87022,.T.); -#87022 = EDGE_LOOP('',(#87023,#87053,#87081,#87109)); -#87023 = ORIENTED_EDGE('',*,*,#87024,.F.); -#87024 = EDGE_CURVE('',#87025,#87027,#87029,.T.); -#87025 = VERTEX_POINT('',#87026); -#87026 = CARTESIAN_POINT('',(6.15,10.,0.65)); -#87027 = VERTEX_POINT('',#87028); -#87028 = CARTESIAN_POINT('',(6.15,10.,0.75)); -#87029 = SURFACE_CURVE('',#87030,(#87034,#87041),.PCURVE_S1.); -#87030 = LINE('',#87031,#87032); -#87031 = CARTESIAN_POINT('',(6.15,10.,0.65)); -#87032 = VECTOR('',#87033,1.); -#87033 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87034 = PCURVE('',#86460,#87035); -#87035 = DEFINITIONAL_REPRESENTATION('',(#87036),#87040); -#87036 = LINE('',#87037,#87038); -#87037 = CARTESIAN_POINT('',(0.75,6.15)); -#87038 = VECTOR('',#87039,1.); -#87039 = DIRECTION('',(-1.,0.E+000)); -#87040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87041 = PCURVE('',#87042,#87047); -#87042 = PLANE('',#87043); -#87043 = AXIS2_PLACEMENT_3D('',#87044,#87045,#87046); -#87044 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); -#87045 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87046 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87047 = DEFINITIONAL_REPRESENTATION('',(#87048),#87052); -#87048 = LINE('',#87049,#87050); -#87049 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87050 = VECTOR('',#87051,1.); -#87051 = DIRECTION('',(-1.,0.E+000)); -#87052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87053 = ORIENTED_EDGE('',*,*,#87054,.F.); -#87054 = EDGE_CURVE('',#87055,#87025,#87057,.T.); -#87055 = VERTEX_POINT('',#87056); -#87056 = CARTESIAN_POINT('',(6.35,10.,0.65)); -#87057 = SURFACE_CURVE('',#87058,(#87062,#87069),.PCURVE_S1.); -#87058 = LINE('',#87059,#87060); -#87059 = CARTESIAN_POINT('',(6.15,10.,0.65)); -#87060 = VECTOR('',#87061,1.); -#87061 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87062 = PCURVE('',#86460,#87063); -#87063 = DEFINITIONAL_REPRESENTATION('',(#87064),#87068); -#87064 = LINE('',#87065,#87066); -#87065 = CARTESIAN_POINT('',(0.75,6.15)); -#87066 = VECTOR('',#87067,1.); -#87067 = DIRECTION('',(0.E+000,-1.)); -#87068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87069 = PCURVE('',#87070,#87075); -#87070 = PLANE('',#87071); -#87071 = AXIS2_PLACEMENT_3D('',#87072,#87073,#87074); -#87072 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); -#87073 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87074 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87075 = DEFINITIONAL_REPRESENTATION('',(#87076),#87080); -#87076 = LINE('',#87077,#87078); -#87077 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87078 = VECTOR('',#87079,1.); -#87079 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87081 = ORIENTED_EDGE('',*,*,#87082,.F.); -#87082 = EDGE_CURVE('',#87083,#87055,#87085,.T.); -#87083 = VERTEX_POINT('',#87084); -#87084 = CARTESIAN_POINT('',(6.35,10.,0.75)); -#87085 = SURFACE_CURVE('',#87086,(#87090,#87097),.PCURVE_S1.); -#87086 = LINE('',#87087,#87088); -#87087 = CARTESIAN_POINT('',(6.35,10.,0.65)); -#87088 = VECTOR('',#87089,1.); -#87089 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87090 = PCURVE('',#86460,#87091); -#87091 = DEFINITIONAL_REPRESENTATION('',(#87092),#87096); -#87092 = LINE('',#87093,#87094); -#87093 = CARTESIAN_POINT('',(0.75,6.35)); -#87094 = VECTOR('',#87095,1.); -#87095 = DIRECTION('',(1.,0.E+000)); -#87096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87097 = PCURVE('',#87098,#87103); -#87098 = PLANE('',#87099); -#87099 = AXIS2_PLACEMENT_3D('',#87100,#87101,#87102); -#87100 = CARTESIAN_POINT('',(6.35,10.527847992439,0.65)); -#87101 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87102 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87103 = DEFINITIONAL_REPRESENTATION('',(#87104),#87108); -#87104 = LINE('',#87105,#87106); -#87105 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87106 = VECTOR('',#87107,1.); -#87107 = DIRECTION('',(-1.,0.E+000)); -#87108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87109 = ORIENTED_EDGE('',*,*,#87110,.F.); -#87110 = EDGE_CURVE('',#87027,#87083,#87111,.T.); -#87111 = SURFACE_CURVE('',#87112,(#87116,#87123),.PCURVE_S1.); -#87112 = LINE('',#87113,#87114); -#87113 = CARTESIAN_POINT('',(6.15,10.,0.75)); -#87114 = VECTOR('',#87115,1.); -#87115 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87116 = PCURVE('',#86460,#87117); -#87117 = DEFINITIONAL_REPRESENTATION('',(#87118),#87122); -#87118 = LINE('',#87119,#87120); -#87119 = CARTESIAN_POINT('',(0.65,6.15)); -#87120 = VECTOR('',#87121,1.); -#87121 = DIRECTION('',(0.E+000,1.)); -#87122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87123 = PCURVE('',#87124,#87129); -#87124 = PLANE('',#87125); -#87125 = AXIS2_PLACEMENT_3D('',#87126,#87127,#87128); -#87126 = CARTESIAN_POINT('',(6.15,10.527847992439,0.75)); -#87127 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87128 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87129 = DEFINITIONAL_REPRESENTATION('',(#87130),#87134); -#87130 = LINE('',#87131,#87132); -#87131 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87132 = VECTOR('',#87133,1.); -#87133 = DIRECTION('',(-8.881784197001E-016,1.)); -#87134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87135 = FACE_BOUND('',#87136,.T.); -#87136 = EDGE_LOOP('',(#87137,#87167,#87195,#87223)); -#87137 = ORIENTED_EDGE('',*,*,#87138,.F.); -#87138 = EDGE_CURVE('',#87139,#87141,#87143,.T.); -#87139 = VERTEX_POINT('',#87140); -#87140 = CARTESIAN_POINT('',(7.15,10.,0.65)); -#87141 = VERTEX_POINT('',#87142); -#87142 = CARTESIAN_POINT('',(7.15,10.,0.75)); -#87143 = SURFACE_CURVE('',#87144,(#87148,#87155),.PCURVE_S1.); -#87144 = LINE('',#87145,#87146); -#87145 = CARTESIAN_POINT('',(7.15,10.,0.65)); -#87146 = VECTOR('',#87147,1.); -#87147 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87148 = PCURVE('',#86460,#87149); -#87149 = DEFINITIONAL_REPRESENTATION('',(#87150),#87154); -#87150 = LINE('',#87151,#87152); -#87151 = CARTESIAN_POINT('',(0.75,7.15)); -#87152 = VECTOR('',#87153,1.); -#87153 = DIRECTION('',(-1.,0.E+000)); -#87154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87155 = PCURVE('',#87156,#87161); -#87156 = PLANE('',#87157); -#87157 = AXIS2_PLACEMENT_3D('',#87158,#87159,#87160); -#87158 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); -#87159 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87160 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87161 = DEFINITIONAL_REPRESENTATION('',(#87162),#87166); -#87162 = LINE('',#87163,#87164); -#87163 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87164 = VECTOR('',#87165,1.); -#87165 = DIRECTION('',(-1.,0.E+000)); -#87166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87167 = ORIENTED_EDGE('',*,*,#87168,.F.); -#87168 = EDGE_CURVE('',#87169,#87139,#87171,.T.); -#87169 = VERTEX_POINT('',#87170); -#87170 = CARTESIAN_POINT('',(7.35,10.,0.65)); -#87171 = SURFACE_CURVE('',#87172,(#87176,#87183),.PCURVE_S1.); -#87172 = LINE('',#87173,#87174); -#87173 = CARTESIAN_POINT('',(7.15,10.,0.65)); -#87174 = VECTOR('',#87175,1.); -#87175 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87176 = PCURVE('',#86460,#87177); -#87177 = DEFINITIONAL_REPRESENTATION('',(#87178),#87182); -#87178 = LINE('',#87179,#87180); -#87179 = CARTESIAN_POINT('',(0.75,7.15)); -#87180 = VECTOR('',#87181,1.); -#87181 = DIRECTION('',(0.E+000,-1.)); -#87182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87183 = PCURVE('',#87184,#87189); -#87184 = PLANE('',#87185); -#87185 = AXIS2_PLACEMENT_3D('',#87186,#87187,#87188); -#87186 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); -#87187 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87188 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87189 = DEFINITIONAL_REPRESENTATION('',(#87190),#87194); -#87190 = LINE('',#87191,#87192); -#87191 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87192 = VECTOR('',#87193,1.); -#87193 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87195 = ORIENTED_EDGE('',*,*,#87196,.F.); -#87196 = EDGE_CURVE('',#87197,#87169,#87199,.T.); -#87197 = VERTEX_POINT('',#87198); -#87198 = CARTESIAN_POINT('',(7.35,10.,0.75)); -#87199 = SURFACE_CURVE('',#87200,(#87204,#87211),.PCURVE_S1.); -#87200 = LINE('',#87201,#87202); -#87201 = CARTESIAN_POINT('',(7.35,10.,0.65)); -#87202 = VECTOR('',#87203,1.); -#87203 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87204 = PCURVE('',#86460,#87205); -#87205 = DEFINITIONAL_REPRESENTATION('',(#87206),#87210); -#87206 = LINE('',#87207,#87208); -#87207 = CARTESIAN_POINT('',(0.75,7.35)); -#87208 = VECTOR('',#87209,1.); -#87209 = DIRECTION('',(1.,0.E+000)); -#87210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87211 = PCURVE('',#87212,#87217); -#87212 = PLANE('',#87213); -#87213 = AXIS2_PLACEMENT_3D('',#87214,#87215,#87216); -#87214 = CARTESIAN_POINT('',(7.35,10.527847992439,0.65)); -#87215 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87216 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87217 = DEFINITIONAL_REPRESENTATION('',(#87218),#87222); -#87218 = LINE('',#87219,#87220); -#87219 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87220 = VECTOR('',#87221,1.); -#87221 = DIRECTION('',(-1.,0.E+000)); -#87222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87223 = ORIENTED_EDGE('',*,*,#87224,.F.); -#87224 = EDGE_CURVE('',#87141,#87197,#87225,.T.); -#87225 = SURFACE_CURVE('',#87226,(#87230,#87237),.PCURVE_S1.); -#87226 = LINE('',#87227,#87228); -#87227 = CARTESIAN_POINT('',(7.15,10.,0.75)); -#87228 = VECTOR('',#87229,1.); -#87229 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87230 = PCURVE('',#86460,#87231); -#87231 = DEFINITIONAL_REPRESENTATION('',(#87232),#87236); -#87232 = LINE('',#87233,#87234); -#87233 = CARTESIAN_POINT('',(0.65,7.15)); -#87234 = VECTOR('',#87235,1.); -#87235 = DIRECTION('',(0.E+000,1.)); -#87236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87237 = PCURVE('',#87238,#87243); -#87238 = PLANE('',#87239); -#87239 = AXIS2_PLACEMENT_3D('',#87240,#87241,#87242); -#87240 = CARTESIAN_POINT('',(7.15,10.527847992439,0.75)); -#87241 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87242 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87243 = DEFINITIONAL_REPRESENTATION('',(#87244),#87248); -#87244 = LINE('',#87245,#87246); -#87245 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87246 = VECTOR('',#87247,1.); -#87247 = DIRECTION('',(-8.881784197001E-016,1.)); -#87248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87249 = FACE_BOUND('',#87250,.T.); -#87250 = EDGE_LOOP('',(#87251,#87281,#87309,#87337)); -#87251 = ORIENTED_EDGE('',*,*,#87252,.F.); -#87252 = EDGE_CURVE('',#87253,#87255,#87257,.T.); -#87253 = VERTEX_POINT('',#87254); -#87254 = CARTESIAN_POINT('',(8.15,10.,0.65)); -#87255 = VERTEX_POINT('',#87256); -#87256 = CARTESIAN_POINT('',(8.15,10.,0.75)); -#87257 = SURFACE_CURVE('',#87258,(#87262,#87269),.PCURVE_S1.); -#87258 = LINE('',#87259,#87260); -#87259 = CARTESIAN_POINT('',(8.15,10.,0.65)); -#87260 = VECTOR('',#87261,1.); -#87261 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87262 = PCURVE('',#86460,#87263); -#87263 = DEFINITIONAL_REPRESENTATION('',(#87264),#87268); -#87264 = LINE('',#87265,#87266); -#87265 = CARTESIAN_POINT('',(0.75,8.15)); -#87266 = VECTOR('',#87267,1.); -#87267 = DIRECTION('',(-1.,0.E+000)); -#87268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87269 = PCURVE('',#87270,#87275); -#87270 = PLANE('',#87271); -#87271 = AXIS2_PLACEMENT_3D('',#87272,#87273,#87274); -#87272 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); -#87273 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87274 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87275 = DEFINITIONAL_REPRESENTATION('',(#87276),#87280); -#87276 = LINE('',#87277,#87278); -#87277 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87278 = VECTOR('',#87279,1.); -#87279 = DIRECTION('',(-1.,0.E+000)); -#87280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87281 = ORIENTED_EDGE('',*,*,#87282,.F.); -#87282 = EDGE_CURVE('',#87283,#87253,#87285,.T.); -#87283 = VERTEX_POINT('',#87284); -#87284 = CARTESIAN_POINT('',(8.35,10.,0.65)); -#87285 = SURFACE_CURVE('',#87286,(#87290,#87297),.PCURVE_S1.); -#87286 = LINE('',#87287,#87288); -#87287 = CARTESIAN_POINT('',(8.15,10.,0.65)); -#87288 = VECTOR('',#87289,1.); -#87289 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87290 = PCURVE('',#86460,#87291); -#87291 = DEFINITIONAL_REPRESENTATION('',(#87292),#87296); -#87292 = LINE('',#87293,#87294); -#87293 = CARTESIAN_POINT('',(0.75,8.15)); -#87294 = VECTOR('',#87295,1.); -#87295 = DIRECTION('',(0.E+000,-1.)); -#87296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87297 = PCURVE('',#87298,#87303); -#87298 = PLANE('',#87299); -#87299 = AXIS2_PLACEMENT_3D('',#87300,#87301,#87302); -#87300 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); -#87301 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87302 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87303 = DEFINITIONAL_REPRESENTATION('',(#87304),#87308); -#87304 = LINE('',#87305,#87306); -#87305 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87306 = VECTOR('',#87307,1.); -#87307 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87309 = ORIENTED_EDGE('',*,*,#87310,.F.); -#87310 = EDGE_CURVE('',#87311,#87283,#87313,.T.); -#87311 = VERTEX_POINT('',#87312); -#87312 = CARTESIAN_POINT('',(8.35,10.,0.75)); -#87313 = SURFACE_CURVE('',#87314,(#87318,#87325),.PCURVE_S1.); -#87314 = LINE('',#87315,#87316); -#87315 = CARTESIAN_POINT('',(8.35,10.,0.65)); -#87316 = VECTOR('',#87317,1.); -#87317 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87318 = PCURVE('',#86460,#87319); -#87319 = DEFINITIONAL_REPRESENTATION('',(#87320),#87324); -#87320 = LINE('',#87321,#87322); -#87321 = CARTESIAN_POINT('',(0.75,8.35)); -#87322 = VECTOR('',#87323,1.); -#87323 = DIRECTION('',(1.,0.E+000)); -#87324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87325 = PCURVE('',#87326,#87331); -#87326 = PLANE('',#87327); -#87327 = AXIS2_PLACEMENT_3D('',#87328,#87329,#87330); -#87328 = CARTESIAN_POINT('',(8.35,10.527847992439,0.65)); -#87329 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87330 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87331 = DEFINITIONAL_REPRESENTATION('',(#87332),#87336); -#87332 = LINE('',#87333,#87334); -#87333 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87334 = VECTOR('',#87335,1.); -#87335 = DIRECTION('',(-1.,0.E+000)); -#87336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87337 = ORIENTED_EDGE('',*,*,#87338,.F.); -#87338 = EDGE_CURVE('',#87255,#87311,#87339,.T.); -#87339 = SURFACE_CURVE('',#87340,(#87344,#87351),.PCURVE_S1.); -#87340 = LINE('',#87341,#87342); -#87341 = CARTESIAN_POINT('',(8.15,10.,0.75)); -#87342 = VECTOR('',#87343,1.); -#87343 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87344 = PCURVE('',#86460,#87345); -#87345 = DEFINITIONAL_REPRESENTATION('',(#87346),#87350); -#87346 = LINE('',#87347,#87348); -#87347 = CARTESIAN_POINT('',(0.65,8.15)); -#87348 = VECTOR('',#87349,1.); -#87349 = DIRECTION('',(0.E+000,1.)); -#87350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87351 = PCURVE('',#87352,#87357); -#87352 = PLANE('',#87353); -#87353 = AXIS2_PLACEMENT_3D('',#87354,#87355,#87356); -#87354 = CARTESIAN_POINT('',(8.15,10.527847992439,0.75)); -#87355 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87356 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87357 = DEFINITIONAL_REPRESENTATION('',(#87358),#87362); -#87358 = LINE('',#87359,#87360); -#87359 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87360 = VECTOR('',#87361,1.); -#87361 = DIRECTION('',(-8.881784197001E-016,1.)); -#87362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87363 = FACE_BOUND('',#87364,.T.); -#87364 = EDGE_LOOP('',(#87365,#87395,#87423,#87451)); -#87365 = ORIENTED_EDGE('',*,*,#87366,.F.); -#87366 = EDGE_CURVE('',#87367,#87369,#87371,.T.); -#87367 = VERTEX_POINT('',#87368); -#87368 = CARTESIAN_POINT('',(8.65,10.,0.65)); -#87369 = VERTEX_POINT('',#87370); -#87370 = CARTESIAN_POINT('',(8.65,10.,0.75)); -#87371 = SURFACE_CURVE('',#87372,(#87376,#87383),.PCURVE_S1.); -#87372 = LINE('',#87373,#87374); -#87373 = CARTESIAN_POINT('',(8.65,10.,0.65)); -#87374 = VECTOR('',#87375,1.); -#87375 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87376 = PCURVE('',#86460,#87377); -#87377 = DEFINITIONAL_REPRESENTATION('',(#87378),#87382); -#87378 = LINE('',#87379,#87380); -#87379 = CARTESIAN_POINT('',(0.75,8.65)); -#87380 = VECTOR('',#87381,1.); -#87381 = DIRECTION('',(-1.,0.E+000)); -#87382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87383 = PCURVE('',#87384,#87389); -#87384 = PLANE('',#87385); -#87385 = AXIS2_PLACEMENT_3D('',#87386,#87387,#87388); -#87386 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); -#87387 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87388 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87389 = DEFINITIONAL_REPRESENTATION('',(#87390),#87394); -#87390 = LINE('',#87391,#87392); -#87391 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87392 = VECTOR('',#87393,1.); -#87393 = DIRECTION('',(-1.,0.E+000)); -#87394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87395 = ORIENTED_EDGE('',*,*,#87396,.F.); -#87396 = EDGE_CURVE('',#87397,#87367,#87399,.T.); -#87397 = VERTEX_POINT('',#87398); -#87398 = CARTESIAN_POINT('',(8.85,10.,0.65)); -#87399 = SURFACE_CURVE('',#87400,(#87404,#87411),.PCURVE_S1.); -#87400 = LINE('',#87401,#87402); -#87401 = CARTESIAN_POINT('',(8.65,10.,0.65)); -#87402 = VECTOR('',#87403,1.); -#87403 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87404 = PCURVE('',#86460,#87405); -#87405 = DEFINITIONAL_REPRESENTATION('',(#87406),#87410); -#87406 = LINE('',#87407,#87408); -#87407 = CARTESIAN_POINT('',(0.75,8.65)); -#87408 = VECTOR('',#87409,1.); -#87409 = DIRECTION('',(0.E+000,-1.)); -#87410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87411 = PCURVE('',#87412,#87417); -#87412 = PLANE('',#87413); -#87413 = AXIS2_PLACEMENT_3D('',#87414,#87415,#87416); -#87414 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); -#87415 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87416 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87417 = DEFINITIONAL_REPRESENTATION('',(#87418),#87422); -#87418 = LINE('',#87419,#87420); -#87419 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87420 = VECTOR('',#87421,1.); -#87421 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87423 = ORIENTED_EDGE('',*,*,#87424,.F.); -#87424 = EDGE_CURVE('',#87425,#87397,#87427,.T.); -#87425 = VERTEX_POINT('',#87426); -#87426 = CARTESIAN_POINT('',(8.85,10.,0.75)); -#87427 = SURFACE_CURVE('',#87428,(#87432,#87439),.PCURVE_S1.); -#87428 = LINE('',#87429,#87430); -#87429 = CARTESIAN_POINT('',(8.85,10.,0.65)); -#87430 = VECTOR('',#87431,1.); -#87431 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87432 = PCURVE('',#86460,#87433); -#87433 = DEFINITIONAL_REPRESENTATION('',(#87434),#87438); -#87434 = LINE('',#87435,#87436); -#87435 = CARTESIAN_POINT('',(0.75,8.85)); -#87436 = VECTOR('',#87437,1.); -#87437 = DIRECTION('',(1.,0.E+000)); -#87438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87439 = PCURVE('',#87440,#87445); -#87440 = PLANE('',#87441); -#87441 = AXIS2_PLACEMENT_3D('',#87442,#87443,#87444); -#87442 = CARTESIAN_POINT('',(8.85,10.527847992439,0.65)); -#87443 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87444 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87445 = DEFINITIONAL_REPRESENTATION('',(#87446),#87450); -#87446 = LINE('',#87447,#87448); -#87447 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87448 = VECTOR('',#87449,1.); -#87449 = DIRECTION('',(-1.,0.E+000)); -#87450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87451 = ORIENTED_EDGE('',*,*,#87452,.F.); -#87452 = EDGE_CURVE('',#87369,#87425,#87453,.T.); -#87453 = SURFACE_CURVE('',#87454,(#87458,#87465),.PCURVE_S1.); -#87454 = LINE('',#87455,#87456); -#87455 = CARTESIAN_POINT('',(8.65,10.,0.75)); -#87456 = VECTOR('',#87457,1.); -#87457 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87458 = PCURVE('',#86460,#87459); -#87459 = DEFINITIONAL_REPRESENTATION('',(#87460),#87464); -#87460 = LINE('',#87461,#87462); -#87461 = CARTESIAN_POINT('',(0.65,8.65)); -#87462 = VECTOR('',#87463,1.); -#87463 = DIRECTION('',(0.E+000,1.)); -#87464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87465 = PCURVE('',#87466,#87471); -#87466 = PLANE('',#87467); -#87467 = AXIS2_PLACEMENT_3D('',#87468,#87469,#87470); -#87468 = CARTESIAN_POINT('',(8.65,10.527847992439,0.75)); -#87469 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87470 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87471 = DEFINITIONAL_REPRESENTATION('',(#87472),#87476); -#87472 = LINE('',#87473,#87474); -#87473 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87474 = VECTOR('',#87475,1.); -#87475 = DIRECTION('',(-8.881784197001E-016,1.)); -#87476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87477 = FACE_BOUND('',#87478,.T.); -#87478 = EDGE_LOOP('',(#87479,#87509,#87537,#87565)); -#87479 = ORIENTED_EDGE('',*,*,#87480,.F.); -#87480 = EDGE_CURVE('',#87481,#87483,#87485,.T.); -#87481 = VERTEX_POINT('',#87482); -#87482 = CARTESIAN_POINT('',(4.85,10.,0.65)); -#87483 = VERTEX_POINT('',#87484); -#87484 = CARTESIAN_POINT('',(4.65,10.,0.65)); -#87485 = SURFACE_CURVE('',#87486,(#87490,#87497),.PCURVE_S1.); -#87486 = LINE('',#87487,#87488); -#87487 = CARTESIAN_POINT('',(4.85,10.,0.65)); -#87488 = VECTOR('',#87489,1.); -#87489 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87490 = PCURVE('',#86460,#87491); -#87491 = DEFINITIONAL_REPRESENTATION('',(#87492),#87496); -#87492 = LINE('',#87493,#87494); -#87493 = CARTESIAN_POINT('',(0.75,4.85)); -#87494 = VECTOR('',#87495,1.); -#87495 = DIRECTION('',(0.E+000,-1.)); -#87496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87497 = PCURVE('',#87498,#87503); -#87498 = PLANE('',#87499); -#87499 = AXIS2_PLACEMENT_3D('',#87500,#87501,#87502); -#87500 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); -#87501 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87502 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87503 = DEFINITIONAL_REPRESENTATION('',(#87504),#87508); -#87504 = LINE('',#87505,#87506); -#87505 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87506 = VECTOR('',#87507,1.); -#87507 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87509 = ORIENTED_EDGE('',*,*,#87510,.F.); -#87510 = EDGE_CURVE('',#87511,#87481,#87513,.T.); -#87511 = VERTEX_POINT('',#87512); -#87512 = CARTESIAN_POINT('',(4.85,10.,0.75)); -#87513 = SURFACE_CURVE('',#87514,(#87518,#87525),.PCURVE_S1.); -#87514 = LINE('',#87515,#87516); -#87515 = CARTESIAN_POINT('',(4.85,10.,0.65)); -#87516 = VECTOR('',#87517,1.); -#87517 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87518 = PCURVE('',#86460,#87519); -#87519 = DEFINITIONAL_REPRESENTATION('',(#87520),#87524); -#87520 = LINE('',#87521,#87522); -#87521 = CARTESIAN_POINT('',(0.75,4.85)); -#87522 = VECTOR('',#87523,1.); -#87523 = DIRECTION('',(1.,0.E+000)); -#87524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87525 = PCURVE('',#87526,#87531); -#87526 = PLANE('',#87527); -#87527 = AXIS2_PLACEMENT_3D('',#87528,#87529,#87530); -#87528 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); -#87529 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87530 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87531 = DEFINITIONAL_REPRESENTATION('',(#87532),#87536); -#87532 = LINE('',#87533,#87534); -#87533 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87534 = VECTOR('',#87535,1.); -#87535 = DIRECTION('',(-1.,0.E+000)); -#87536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87537 = ORIENTED_EDGE('',*,*,#87538,.F.); -#87538 = EDGE_CURVE('',#87539,#87511,#87541,.T.); -#87539 = VERTEX_POINT('',#87540); -#87540 = CARTESIAN_POINT('',(4.65,10.,0.75)); -#87541 = SURFACE_CURVE('',#87542,(#87546,#87553),.PCURVE_S1.); -#87542 = LINE('',#87543,#87544); -#87543 = CARTESIAN_POINT('',(4.85,10.,0.75)); -#87544 = VECTOR('',#87545,1.); -#87545 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87546 = PCURVE('',#86460,#87547); -#87547 = DEFINITIONAL_REPRESENTATION('',(#87548),#87552); -#87548 = LINE('',#87549,#87550); -#87549 = CARTESIAN_POINT('',(0.65,4.85)); -#87550 = VECTOR('',#87551,1.); -#87551 = DIRECTION('',(0.E+000,1.)); -#87552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87553 = PCURVE('',#87554,#87559); -#87554 = PLANE('',#87555); -#87555 = AXIS2_PLACEMENT_3D('',#87556,#87557,#87558); -#87556 = CARTESIAN_POINT('',(4.85,10.527847992439,0.75)); -#87557 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87558 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87559 = DEFINITIONAL_REPRESENTATION('',(#87560),#87564); -#87560 = LINE('',#87561,#87562); -#87561 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87562 = VECTOR('',#87563,1.); -#87563 = DIRECTION('',(-8.881784197001E-016,1.)); -#87564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87565 = ORIENTED_EDGE('',*,*,#87566,.F.); -#87566 = EDGE_CURVE('',#87483,#87539,#87567,.T.); -#87567 = SURFACE_CURVE('',#87568,(#87572,#87579),.PCURVE_S1.); -#87568 = LINE('',#87569,#87570); -#87569 = CARTESIAN_POINT('',(4.65,10.,0.65)); -#87570 = VECTOR('',#87571,1.); -#87571 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87572 = PCURVE('',#86460,#87573); -#87573 = DEFINITIONAL_REPRESENTATION('',(#87574),#87578); -#87574 = LINE('',#87575,#87576); -#87575 = CARTESIAN_POINT('',(0.75,4.65)); -#87576 = VECTOR('',#87577,1.); -#87577 = DIRECTION('',(-1.,0.E+000)); -#87578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87579 = PCURVE('',#87580,#87585); -#87580 = PLANE('',#87581); -#87581 = AXIS2_PLACEMENT_3D('',#87582,#87583,#87584); -#87582 = CARTESIAN_POINT('',(4.65,10.527847992439,0.65)); -#87583 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87584 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87585 = DEFINITIONAL_REPRESENTATION('',(#87586),#87590); -#87586 = LINE('',#87587,#87588); -#87587 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87588 = VECTOR('',#87589,1.); -#87589 = DIRECTION('',(-1.,0.E+000)); -#87590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87591 = FACE_BOUND('',#87592,.T.); -#87592 = EDGE_LOOP('',(#87593,#87623,#87651,#87679)); -#87593 = ORIENTED_EDGE('',*,*,#87594,.F.); -#87594 = EDGE_CURVE('',#87595,#87597,#87599,.T.); -#87595 = VERTEX_POINT('',#87596); -#87596 = CARTESIAN_POINT('',(7.65,10.,0.65)); -#87597 = VERTEX_POINT('',#87598); -#87598 = CARTESIAN_POINT('',(7.65,10.,0.75)); -#87599 = SURFACE_CURVE('',#87600,(#87604,#87611),.PCURVE_S1.); -#87600 = LINE('',#87601,#87602); -#87601 = CARTESIAN_POINT('',(7.65,10.,0.65)); -#87602 = VECTOR('',#87603,1.); -#87603 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87604 = PCURVE('',#86460,#87605); -#87605 = DEFINITIONAL_REPRESENTATION('',(#87606),#87610); -#87606 = LINE('',#87607,#87608); -#87607 = CARTESIAN_POINT('',(0.75,7.65)); -#87608 = VECTOR('',#87609,1.); -#87609 = DIRECTION('',(-1.,0.E+000)); -#87610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87611 = PCURVE('',#87612,#87617); -#87612 = PLANE('',#87613); -#87613 = AXIS2_PLACEMENT_3D('',#87614,#87615,#87616); -#87614 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); -#87615 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87616 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87617 = DEFINITIONAL_REPRESENTATION('',(#87618),#87622); -#87618 = LINE('',#87619,#87620); -#87619 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87620 = VECTOR('',#87621,1.); -#87621 = DIRECTION('',(-1.,0.E+000)); -#87622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87623 = ORIENTED_EDGE('',*,*,#87624,.F.); -#87624 = EDGE_CURVE('',#87625,#87595,#87627,.T.); -#87625 = VERTEX_POINT('',#87626); -#87626 = CARTESIAN_POINT('',(7.85,10.,0.65)); -#87627 = SURFACE_CURVE('',#87628,(#87632,#87639),.PCURVE_S1.); -#87628 = LINE('',#87629,#87630); -#87629 = CARTESIAN_POINT('',(7.65,10.,0.65)); -#87630 = VECTOR('',#87631,1.); -#87631 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87632 = PCURVE('',#86460,#87633); -#87633 = DEFINITIONAL_REPRESENTATION('',(#87634),#87638); -#87634 = LINE('',#87635,#87636); -#87635 = CARTESIAN_POINT('',(0.75,7.65)); -#87636 = VECTOR('',#87637,1.); -#87637 = DIRECTION('',(0.E+000,-1.)); -#87638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87639 = PCURVE('',#87640,#87645); -#87640 = PLANE('',#87641); -#87641 = AXIS2_PLACEMENT_3D('',#87642,#87643,#87644); -#87642 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); -#87643 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87644 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87645 = DEFINITIONAL_REPRESENTATION('',(#87646),#87650); -#87646 = LINE('',#87647,#87648); -#87647 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87648 = VECTOR('',#87649,1.); -#87649 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87651 = ORIENTED_EDGE('',*,*,#87652,.F.); -#87652 = EDGE_CURVE('',#87653,#87625,#87655,.T.); -#87653 = VERTEX_POINT('',#87654); -#87654 = CARTESIAN_POINT('',(7.85,10.,0.75)); -#87655 = SURFACE_CURVE('',#87656,(#87660,#87667),.PCURVE_S1.); -#87656 = LINE('',#87657,#87658); -#87657 = CARTESIAN_POINT('',(7.85,10.,0.65)); -#87658 = VECTOR('',#87659,1.); -#87659 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87660 = PCURVE('',#86460,#87661); -#87661 = DEFINITIONAL_REPRESENTATION('',(#87662),#87666); -#87662 = LINE('',#87663,#87664); -#87663 = CARTESIAN_POINT('',(0.75,7.85)); -#87664 = VECTOR('',#87665,1.); -#87665 = DIRECTION('',(1.,0.E+000)); -#87666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87667 = PCURVE('',#87668,#87673); -#87668 = PLANE('',#87669); -#87669 = AXIS2_PLACEMENT_3D('',#87670,#87671,#87672); -#87670 = CARTESIAN_POINT('',(7.85,10.527847992439,0.65)); -#87671 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87672 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87673 = DEFINITIONAL_REPRESENTATION('',(#87674),#87678); -#87674 = LINE('',#87675,#87676); -#87675 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87676 = VECTOR('',#87677,1.); -#87677 = DIRECTION('',(-1.,0.E+000)); -#87678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87679 = ORIENTED_EDGE('',*,*,#87680,.F.); -#87680 = EDGE_CURVE('',#87597,#87653,#87681,.T.); -#87681 = SURFACE_CURVE('',#87682,(#87686,#87693),.PCURVE_S1.); -#87682 = LINE('',#87683,#87684); -#87683 = CARTESIAN_POINT('',(7.65,10.,0.75)); -#87684 = VECTOR('',#87685,1.); -#87685 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87686 = PCURVE('',#86460,#87687); -#87687 = DEFINITIONAL_REPRESENTATION('',(#87688),#87692); -#87688 = LINE('',#87689,#87690); -#87689 = CARTESIAN_POINT('',(0.65,7.65)); -#87690 = VECTOR('',#87691,1.); -#87691 = DIRECTION('',(0.E+000,1.)); -#87692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87693 = PCURVE('',#87694,#87699); -#87694 = PLANE('',#87695); -#87695 = AXIS2_PLACEMENT_3D('',#87696,#87697,#87698); -#87696 = CARTESIAN_POINT('',(7.65,10.527847992439,0.75)); -#87697 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87698 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87699 = DEFINITIONAL_REPRESENTATION('',(#87700),#87704); -#87700 = LINE('',#87701,#87702); -#87701 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87702 = VECTOR('',#87703,1.); -#87703 = DIRECTION('',(-8.881784197001E-016,1.)); -#87704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87705 = FACE_BOUND('',#87706,.T.); -#87706 = EDGE_LOOP('',(#87707,#87737,#87765,#87793)); -#87707 = ORIENTED_EDGE('',*,*,#87708,.F.); -#87708 = EDGE_CURVE('',#87709,#87711,#87713,.T.); -#87709 = VERTEX_POINT('',#87710); -#87710 = CARTESIAN_POINT('',(6.65,10.,0.65)); -#87711 = VERTEX_POINT('',#87712); -#87712 = CARTESIAN_POINT('',(6.65,10.,0.75)); -#87713 = SURFACE_CURVE('',#87714,(#87718,#87725),.PCURVE_S1.); -#87714 = LINE('',#87715,#87716); -#87715 = CARTESIAN_POINT('',(6.65,10.,0.65)); -#87716 = VECTOR('',#87717,1.); -#87717 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87718 = PCURVE('',#86460,#87719); -#87719 = DEFINITIONAL_REPRESENTATION('',(#87720),#87724); -#87720 = LINE('',#87721,#87722); -#87721 = CARTESIAN_POINT('',(0.75,6.65)); -#87722 = VECTOR('',#87723,1.); -#87723 = DIRECTION('',(-1.,0.E+000)); -#87724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87725 = PCURVE('',#87726,#87731); -#87726 = PLANE('',#87727); -#87727 = AXIS2_PLACEMENT_3D('',#87728,#87729,#87730); -#87728 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); -#87729 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87730 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87731 = DEFINITIONAL_REPRESENTATION('',(#87732),#87736); -#87732 = LINE('',#87733,#87734); -#87733 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87734 = VECTOR('',#87735,1.); -#87735 = DIRECTION('',(-1.,0.E+000)); -#87736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87737 = ORIENTED_EDGE('',*,*,#87738,.F.); -#87738 = EDGE_CURVE('',#87739,#87709,#87741,.T.); -#87739 = VERTEX_POINT('',#87740); -#87740 = CARTESIAN_POINT('',(6.85,10.,0.65)); -#87741 = SURFACE_CURVE('',#87742,(#87746,#87753),.PCURVE_S1.); -#87742 = LINE('',#87743,#87744); -#87743 = CARTESIAN_POINT('',(6.65,10.,0.65)); -#87744 = VECTOR('',#87745,1.); -#87745 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87746 = PCURVE('',#86460,#87747); -#87747 = DEFINITIONAL_REPRESENTATION('',(#87748),#87752); -#87748 = LINE('',#87749,#87750); -#87749 = CARTESIAN_POINT('',(0.75,6.65)); -#87750 = VECTOR('',#87751,1.); -#87751 = DIRECTION('',(0.E+000,-1.)); -#87752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87753 = PCURVE('',#87754,#87759); -#87754 = PLANE('',#87755); -#87755 = AXIS2_PLACEMENT_3D('',#87756,#87757,#87758); -#87756 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); -#87757 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87758 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87759 = DEFINITIONAL_REPRESENTATION('',(#87760),#87764); -#87760 = LINE('',#87761,#87762); -#87761 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87762 = VECTOR('',#87763,1.); -#87763 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87765 = ORIENTED_EDGE('',*,*,#87766,.F.); -#87766 = EDGE_CURVE('',#87767,#87739,#87769,.T.); -#87767 = VERTEX_POINT('',#87768); -#87768 = CARTESIAN_POINT('',(6.85,10.,0.75)); -#87769 = SURFACE_CURVE('',#87770,(#87774,#87781),.PCURVE_S1.); -#87770 = LINE('',#87771,#87772); -#87771 = CARTESIAN_POINT('',(6.85,10.,0.65)); -#87772 = VECTOR('',#87773,1.); -#87773 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87774 = PCURVE('',#86460,#87775); -#87775 = DEFINITIONAL_REPRESENTATION('',(#87776),#87780); -#87776 = LINE('',#87777,#87778); -#87777 = CARTESIAN_POINT('',(0.75,6.85)); -#87778 = VECTOR('',#87779,1.); -#87779 = DIRECTION('',(1.,0.E+000)); -#87780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87781 = PCURVE('',#87782,#87787); -#87782 = PLANE('',#87783); -#87783 = AXIS2_PLACEMENT_3D('',#87784,#87785,#87786); -#87784 = CARTESIAN_POINT('',(6.85,10.527847992439,0.65)); -#87785 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87786 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87787 = DEFINITIONAL_REPRESENTATION('',(#87788),#87792); -#87788 = LINE('',#87789,#87790); -#87789 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87790 = VECTOR('',#87791,1.); -#87791 = DIRECTION('',(-1.,0.E+000)); -#87792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87793 = ORIENTED_EDGE('',*,*,#87794,.F.); -#87794 = EDGE_CURVE('',#87711,#87767,#87795,.T.); -#87795 = SURFACE_CURVE('',#87796,(#87800,#87807),.PCURVE_S1.); -#87796 = LINE('',#87797,#87798); -#87797 = CARTESIAN_POINT('',(6.65,10.,0.75)); -#87798 = VECTOR('',#87799,1.); -#87799 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87800 = PCURVE('',#86460,#87801); -#87801 = DEFINITIONAL_REPRESENTATION('',(#87802),#87806); -#87802 = LINE('',#87803,#87804); -#87803 = CARTESIAN_POINT('',(0.65,6.65)); -#87804 = VECTOR('',#87805,1.); -#87805 = DIRECTION('',(0.E+000,1.)); -#87806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87807 = PCURVE('',#87808,#87813); -#87808 = PLANE('',#87809); -#87809 = AXIS2_PLACEMENT_3D('',#87810,#87811,#87812); -#87810 = CARTESIAN_POINT('',(6.65,10.527847992439,0.75)); -#87811 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87812 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87813 = DEFINITIONAL_REPRESENTATION('',(#87814),#87818); -#87814 = LINE('',#87815,#87816); -#87815 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87816 = VECTOR('',#87817,1.); -#87817 = DIRECTION('',(-8.881784197001E-016,1.)); -#87818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87819 = FACE_BOUND('',#87820,.T.); -#87820 = EDGE_LOOP('',(#87821,#87851,#87879,#87907)); -#87821 = ORIENTED_EDGE('',*,*,#87822,.F.); -#87822 = EDGE_CURVE('',#87823,#87825,#87827,.T.); -#87823 = VERTEX_POINT('',#87824); -#87824 = CARTESIAN_POINT('',(5.65,10.,0.65)); -#87825 = VERTEX_POINT('',#87826); -#87826 = CARTESIAN_POINT('',(5.65,10.,0.75)); -#87827 = SURFACE_CURVE('',#87828,(#87832,#87839),.PCURVE_S1.); -#87828 = LINE('',#87829,#87830); -#87829 = CARTESIAN_POINT('',(5.65,10.,0.65)); -#87830 = VECTOR('',#87831,1.); -#87831 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87832 = PCURVE('',#86460,#87833); -#87833 = DEFINITIONAL_REPRESENTATION('',(#87834),#87838); -#87834 = LINE('',#87835,#87836); -#87835 = CARTESIAN_POINT('',(0.75,5.65)); -#87836 = VECTOR('',#87837,1.); -#87837 = DIRECTION('',(-1.,0.E+000)); -#87838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87839 = PCURVE('',#87840,#87845); -#87840 = PLANE('',#87841); -#87841 = AXIS2_PLACEMENT_3D('',#87842,#87843,#87844); -#87842 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); -#87843 = DIRECTION('',(1.,0.E+000,0.E+000)); -#87844 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87845 = DEFINITIONAL_REPRESENTATION('',(#87846),#87850); -#87846 = LINE('',#87847,#87848); -#87847 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#87848 = VECTOR('',#87849,1.); -#87849 = DIRECTION('',(-1.,0.E+000)); -#87850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87851 = ORIENTED_EDGE('',*,*,#87852,.F.); -#87852 = EDGE_CURVE('',#87853,#87823,#87855,.T.); -#87853 = VERTEX_POINT('',#87854); -#87854 = CARTESIAN_POINT('',(5.85,10.,0.65)); -#87855 = SURFACE_CURVE('',#87856,(#87860,#87867),.PCURVE_S1.); -#87856 = LINE('',#87857,#87858); -#87857 = CARTESIAN_POINT('',(5.65,10.,0.65)); -#87858 = VECTOR('',#87859,1.); -#87859 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#87860 = PCURVE('',#86460,#87861); -#87861 = DEFINITIONAL_REPRESENTATION('',(#87862),#87866); -#87862 = LINE('',#87863,#87864); -#87863 = CARTESIAN_POINT('',(0.75,5.65)); -#87864 = VECTOR('',#87865,1.); -#87865 = DIRECTION('',(0.E+000,-1.)); -#87866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87867 = PCURVE('',#87868,#87873); -#87868 = PLANE('',#87869); -#87869 = AXIS2_PLACEMENT_3D('',#87870,#87871,#87872); -#87870 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); -#87871 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#87872 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#87873 = DEFINITIONAL_REPRESENTATION('',(#87874),#87878); -#87874 = LINE('',#87875,#87876); -#87875 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#87876 = VECTOR('',#87877,1.); -#87877 = DIRECTION('',(-8.881784197001E-016,-1.)); -#87878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87879 = ORIENTED_EDGE('',*,*,#87880,.F.); -#87880 = EDGE_CURVE('',#87881,#87853,#87883,.T.); -#87881 = VERTEX_POINT('',#87882); -#87882 = CARTESIAN_POINT('',(5.85,10.,0.75)); -#87883 = SURFACE_CURVE('',#87884,(#87888,#87895),.PCURVE_S1.); -#87884 = LINE('',#87885,#87886); -#87885 = CARTESIAN_POINT('',(5.85,10.,0.65)); -#87886 = VECTOR('',#87887,1.); -#87887 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87888 = PCURVE('',#86460,#87889); -#87889 = DEFINITIONAL_REPRESENTATION('',(#87890),#87894); -#87890 = LINE('',#87891,#87892); -#87891 = CARTESIAN_POINT('',(0.75,5.85)); -#87892 = VECTOR('',#87893,1.); -#87893 = DIRECTION('',(1.,0.E+000)); -#87894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87895 = PCURVE('',#87896,#87901); -#87896 = PLANE('',#87897); -#87897 = AXIS2_PLACEMENT_3D('',#87898,#87899,#87900); -#87898 = CARTESIAN_POINT('',(5.85,10.527847992439,0.65)); -#87899 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87900 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87901 = DEFINITIONAL_REPRESENTATION('',(#87902),#87906); -#87902 = LINE('',#87903,#87904); -#87903 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87904 = VECTOR('',#87905,1.); -#87905 = DIRECTION('',(-1.,0.E+000)); -#87906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87907 = ORIENTED_EDGE('',*,*,#87908,.F.); -#87908 = EDGE_CURVE('',#87825,#87881,#87909,.T.); -#87909 = SURFACE_CURVE('',#87910,(#87914,#87921),.PCURVE_S1.); -#87910 = LINE('',#87911,#87912); -#87911 = CARTESIAN_POINT('',(5.65,10.,0.75)); -#87912 = VECTOR('',#87913,1.); -#87913 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87914 = PCURVE('',#86460,#87915); -#87915 = DEFINITIONAL_REPRESENTATION('',(#87916),#87920); -#87916 = LINE('',#87917,#87918); -#87917 = CARTESIAN_POINT('',(0.65,5.65)); -#87918 = VECTOR('',#87919,1.); -#87919 = DIRECTION('',(0.E+000,1.)); -#87920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87921 = PCURVE('',#87922,#87927); -#87922 = PLANE('',#87923); -#87923 = AXIS2_PLACEMENT_3D('',#87924,#87925,#87926); -#87924 = CARTESIAN_POINT('',(5.65,10.527847992439,0.75)); -#87925 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87926 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87927 = DEFINITIONAL_REPRESENTATION('',(#87928),#87932); -#87928 = LINE('',#87929,#87930); -#87929 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87930 = VECTOR('',#87931,1.); -#87931 = DIRECTION('',(-8.881784197001E-016,1.)); -#87932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87933 = FACE_BOUND('',#87934,.T.); -#87934 = EDGE_LOOP('',(#87935,#87965,#87993,#88021)); -#87935 = ORIENTED_EDGE('',*,*,#87936,.F.); -#87936 = EDGE_CURVE('',#87937,#87939,#87941,.T.); -#87937 = VERTEX_POINT('',#87938); -#87938 = CARTESIAN_POINT('',(4.35,10.,0.75)); -#87939 = VERTEX_POINT('',#87940); -#87940 = CARTESIAN_POINT('',(4.35,10.,0.65)); -#87941 = SURFACE_CURVE('',#87942,(#87946,#87953),.PCURVE_S1.); -#87942 = LINE('',#87943,#87944); -#87943 = CARTESIAN_POINT('',(4.35,10.,0.65)); -#87944 = VECTOR('',#87945,1.); -#87945 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#87946 = PCURVE('',#86460,#87947); -#87947 = DEFINITIONAL_REPRESENTATION('',(#87948),#87952); -#87948 = LINE('',#87949,#87950); -#87949 = CARTESIAN_POINT('',(0.75,4.35)); -#87950 = VECTOR('',#87951,1.); -#87951 = DIRECTION('',(1.,0.E+000)); -#87952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87953 = PCURVE('',#87954,#87959); -#87954 = PLANE('',#87955); -#87955 = AXIS2_PLACEMENT_3D('',#87956,#87957,#87958); -#87956 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); -#87957 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#87958 = DIRECTION('',(0.E+000,0.E+000,1.)); -#87959 = DEFINITIONAL_REPRESENTATION('',(#87960),#87964); -#87960 = LINE('',#87961,#87962); -#87961 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#87962 = VECTOR('',#87963,1.); -#87963 = DIRECTION('',(-1.,0.E+000)); -#87964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87965 = ORIENTED_EDGE('',*,*,#87966,.F.); -#87966 = EDGE_CURVE('',#87967,#87937,#87969,.T.); -#87967 = VERTEX_POINT('',#87968); -#87968 = CARTESIAN_POINT('',(4.15,10.,0.75)); -#87969 = SURFACE_CURVE('',#87970,(#87974,#87981),.PCURVE_S1.); -#87970 = LINE('',#87971,#87972); -#87971 = CARTESIAN_POINT('',(4.35,10.,0.75)); -#87972 = VECTOR('',#87973,1.); -#87973 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#87974 = PCURVE('',#86460,#87975); -#87975 = DEFINITIONAL_REPRESENTATION('',(#87976),#87980); -#87976 = LINE('',#87977,#87978); -#87977 = CARTESIAN_POINT('',(0.65,4.35)); -#87978 = VECTOR('',#87979,1.); -#87979 = DIRECTION('',(0.E+000,1.)); -#87980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87981 = PCURVE('',#87982,#87987); -#87982 = PLANE('',#87983); -#87983 = AXIS2_PLACEMENT_3D('',#87984,#87985,#87986); -#87984 = CARTESIAN_POINT('',(4.35,10.527847992439,0.75)); -#87985 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#87986 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#87987 = DEFINITIONAL_REPRESENTATION('',(#87988),#87992); -#87988 = LINE('',#87989,#87990); -#87989 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#87990 = VECTOR('',#87991,1.); -#87991 = DIRECTION('',(-8.881784197001E-016,1.)); -#87992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#87993 = ORIENTED_EDGE('',*,*,#87994,.F.); -#87994 = EDGE_CURVE('',#87995,#87967,#87997,.T.); -#87995 = VERTEX_POINT('',#87996); -#87996 = CARTESIAN_POINT('',(4.15,10.,0.65)); -#87997 = SURFACE_CURVE('',#87998,(#88002,#88009),.PCURVE_S1.); -#87998 = LINE('',#87999,#88000); -#87999 = CARTESIAN_POINT('',(4.15,10.,0.65)); -#88000 = VECTOR('',#88001,1.); -#88001 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88002 = PCURVE('',#86460,#88003); -#88003 = DEFINITIONAL_REPRESENTATION('',(#88004),#88008); -#88004 = LINE('',#88005,#88006); -#88005 = CARTESIAN_POINT('',(0.75,4.15)); -#88006 = VECTOR('',#88007,1.); -#88007 = DIRECTION('',(-1.,0.E+000)); -#88008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88009 = PCURVE('',#88010,#88015); -#88010 = PLANE('',#88011); -#88011 = AXIS2_PLACEMENT_3D('',#88012,#88013,#88014); -#88012 = CARTESIAN_POINT('',(4.15,10.527847992439,0.65)); -#88013 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88014 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88015 = DEFINITIONAL_REPRESENTATION('',(#88016),#88020); -#88016 = LINE('',#88017,#88018); -#88017 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#88018 = VECTOR('',#88019,1.); -#88019 = DIRECTION('',(-1.,0.E+000)); -#88020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88021 = ORIENTED_EDGE('',*,*,#88022,.F.); -#88022 = EDGE_CURVE('',#87939,#87995,#88023,.T.); -#88023 = SURFACE_CURVE('',#88024,(#88028,#88035),.PCURVE_S1.); -#88024 = LINE('',#88025,#88026); -#88025 = CARTESIAN_POINT('',(4.35,10.,0.65)); -#88026 = VECTOR('',#88027,1.); -#88027 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#88028 = PCURVE('',#86460,#88029); -#88029 = DEFINITIONAL_REPRESENTATION('',(#88030),#88034); -#88030 = LINE('',#88031,#88032); -#88031 = CARTESIAN_POINT('',(0.75,4.35)); -#88032 = VECTOR('',#88033,1.); -#88033 = DIRECTION('',(0.E+000,-1.)); -#88034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88035 = PCURVE('',#88036,#88041); -#88036 = PLANE('',#88037); -#88037 = AXIS2_PLACEMENT_3D('',#88038,#88039,#88040); -#88038 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); -#88039 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#88040 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#88041 = DEFINITIONAL_REPRESENTATION('',(#88042),#88046); -#88042 = LINE('',#88043,#88044); -#88043 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#88044 = VECTOR('',#88045,1.); -#88045 = DIRECTION('',(-8.881784197001E-016,-1.)); -#88046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88047 = FACE_BOUND('',#88048,.T.); -#88048 = EDGE_LOOP('',(#88049,#88079,#88107,#88135)); -#88049 = ORIENTED_EDGE('',*,*,#88050,.F.); -#88050 = EDGE_CURVE('',#88051,#88053,#88055,.T.); -#88051 = VERTEX_POINT('',#88052); -#88052 = CARTESIAN_POINT('',(3.35,10.,0.75)); -#88053 = VERTEX_POINT('',#88054); -#88054 = CARTESIAN_POINT('',(3.35,10.,0.65)); -#88055 = SURFACE_CURVE('',#88056,(#88060,#88067),.PCURVE_S1.); -#88056 = LINE('',#88057,#88058); -#88057 = CARTESIAN_POINT('',(3.35,10.,0.65)); -#88058 = VECTOR('',#88059,1.); -#88059 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88060 = PCURVE('',#86460,#88061); -#88061 = DEFINITIONAL_REPRESENTATION('',(#88062),#88066); -#88062 = LINE('',#88063,#88064); -#88063 = CARTESIAN_POINT('',(0.75,3.35)); -#88064 = VECTOR('',#88065,1.); -#88065 = DIRECTION('',(1.,0.E+000)); -#88066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88067 = PCURVE('',#88068,#88073); -#88068 = PLANE('',#88069); -#88069 = AXIS2_PLACEMENT_3D('',#88070,#88071,#88072); -#88070 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); -#88071 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88072 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88073 = DEFINITIONAL_REPRESENTATION('',(#88074),#88078); -#88074 = LINE('',#88075,#88076); -#88075 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#88076 = VECTOR('',#88077,1.); -#88077 = DIRECTION('',(-1.,0.E+000)); -#88078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88079 = ORIENTED_EDGE('',*,*,#88080,.F.); -#88080 = EDGE_CURVE('',#88081,#88051,#88083,.T.); -#88081 = VERTEX_POINT('',#88082); -#88082 = CARTESIAN_POINT('',(3.15,10.,0.75)); -#88083 = SURFACE_CURVE('',#88084,(#88088,#88095),.PCURVE_S1.); -#88084 = LINE('',#88085,#88086); -#88085 = CARTESIAN_POINT('',(3.35,10.,0.75)); -#88086 = VECTOR('',#88087,1.); -#88087 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#88088 = PCURVE('',#86460,#88089); -#88089 = DEFINITIONAL_REPRESENTATION('',(#88090),#88094); -#88090 = LINE('',#88091,#88092); -#88091 = CARTESIAN_POINT('',(0.65,3.35)); -#88092 = VECTOR('',#88093,1.); -#88093 = DIRECTION('',(0.E+000,1.)); -#88094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88095 = PCURVE('',#88096,#88101); -#88096 = PLANE('',#88097); -#88097 = AXIS2_PLACEMENT_3D('',#88098,#88099,#88100); -#88098 = CARTESIAN_POINT('',(3.35,10.527847992439,0.75)); -#88099 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#88100 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#88101 = DEFINITIONAL_REPRESENTATION('',(#88102),#88106); -#88102 = LINE('',#88103,#88104); -#88103 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#88104 = VECTOR('',#88105,1.); -#88105 = DIRECTION('',(-8.881784197001E-016,1.)); -#88106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88107 = ORIENTED_EDGE('',*,*,#88108,.F.); -#88108 = EDGE_CURVE('',#88109,#88081,#88111,.T.); -#88109 = VERTEX_POINT('',#88110); -#88110 = CARTESIAN_POINT('',(3.15,10.,0.65)); -#88111 = SURFACE_CURVE('',#88112,(#88116,#88123),.PCURVE_S1.); -#88112 = LINE('',#88113,#88114); -#88113 = CARTESIAN_POINT('',(3.15,10.,0.65)); -#88114 = VECTOR('',#88115,1.); -#88115 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88116 = PCURVE('',#86460,#88117); -#88117 = DEFINITIONAL_REPRESENTATION('',(#88118),#88122); -#88118 = LINE('',#88119,#88120); -#88119 = CARTESIAN_POINT('',(0.75,3.15)); -#88120 = VECTOR('',#88121,1.); -#88121 = DIRECTION('',(-1.,0.E+000)); -#88122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88123 = PCURVE('',#88124,#88129); -#88124 = PLANE('',#88125); -#88125 = AXIS2_PLACEMENT_3D('',#88126,#88127,#88128); -#88126 = CARTESIAN_POINT('',(3.15,10.527847992439,0.65)); -#88127 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88128 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88129 = DEFINITIONAL_REPRESENTATION('',(#88130),#88134); -#88130 = LINE('',#88131,#88132); -#88131 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#88132 = VECTOR('',#88133,1.); -#88133 = DIRECTION('',(-1.,0.E+000)); -#88134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88135 = ORIENTED_EDGE('',*,*,#88136,.F.); -#88136 = EDGE_CURVE('',#88053,#88109,#88137,.T.); -#88137 = SURFACE_CURVE('',#88138,(#88142,#88149),.PCURVE_S1.); -#88138 = LINE('',#88139,#88140); -#88139 = CARTESIAN_POINT('',(3.35,10.,0.65)); -#88140 = VECTOR('',#88141,1.); -#88141 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#88142 = PCURVE('',#86460,#88143); -#88143 = DEFINITIONAL_REPRESENTATION('',(#88144),#88148); -#88144 = LINE('',#88145,#88146); -#88145 = CARTESIAN_POINT('',(0.75,3.35)); -#88146 = VECTOR('',#88147,1.); -#88147 = DIRECTION('',(0.E+000,-1.)); -#88148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88149 = PCURVE('',#88150,#88155); -#88150 = PLANE('',#88151); -#88151 = AXIS2_PLACEMENT_3D('',#88152,#88153,#88154); -#88152 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); -#88153 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#88154 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#88155 = DEFINITIONAL_REPRESENTATION('',(#88156),#88160); -#88156 = LINE('',#88157,#88158); -#88157 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#88158 = VECTOR('',#88159,1.); -#88159 = DIRECTION('',(-8.881784197001E-016,-1.)); -#88160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88161 = FACE_BOUND('',#88162,.T.); -#88162 = EDGE_LOOP('',(#88163,#88193,#88221,#88249)); -#88163 = ORIENTED_EDGE('',*,*,#88164,.F.); -#88164 = EDGE_CURVE('',#88165,#88167,#88169,.T.); -#88165 = VERTEX_POINT('',#88166); -#88166 = CARTESIAN_POINT('',(2.35,10.,0.75)); -#88167 = VERTEX_POINT('',#88168); -#88168 = CARTESIAN_POINT('',(2.35,10.,0.65)); -#88169 = SURFACE_CURVE('',#88170,(#88174,#88181),.PCURVE_S1.); -#88170 = LINE('',#88171,#88172); -#88171 = CARTESIAN_POINT('',(2.35,10.,0.65)); -#88172 = VECTOR('',#88173,1.); -#88173 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88174 = PCURVE('',#86460,#88175); -#88175 = DEFINITIONAL_REPRESENTATION('',(#88176),#88180); -#88176 = LINE('',#88177,#88178); -#88177 = CARTESIAN_POINT('',(0.75,2.35)); -#88178 = VECTOR('',#88179,1.); -#88179 = DIRECTION('',(1.,0.E+000)); -#88180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88181 = PCURVE('',#88182,#88187); -#88182 = PLANE('',#88183); -#88183 = AXIS2_PLACEMENT_3D('',#88184,#88185,#88186); -#88184 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); -#88185 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88186 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88187 = DEFINITIONAL_REPRESENTATION('',(#88188),#88192); -#88188 = LINE('',#88189,#88190); -#88189 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#88190 = VECTOR('',#88191,1.); -#88191 = DIRECTION('',(-1.,0.E+000)); -#88192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88193 = ORIENTED_EDGE('',*,*,#88194,.F.); -#88194 = EDGE_CURVE('',#88195,#88165,#88197,.T.); -#88195 = VERTEX_POINT('',#88196); -#88196 = CARTESIAN_POINT('',(2.15,10.,0.75)); -#88197 = SURFACE_CURVE('',#88198,(#88202,#88209),.PCURVE_S1.); -#88198 = LINE('',#88199,#88200); -#88199 = CARTESIAN_POINT('',(2.35,10.,0.75)); -#88200 = VECTOR('',#88201,1.); -#88201 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#88202 = PCURVE('',#86460,#88203); -#88203 = DEFINITIONAL_REPRESENTATION('',(#88204),#88208); -#88204 = LINE('',#88205,#88206); -#88205 = CARTESIAN_POINT('',(0.65,2.35)); -#88206 = VECTOR('',#88207,1.); -#88207 = DIRECTION('',(0.E+000,1.)); -#88208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88209 = PCURVE('',#88210,#88215); -#88210 = PLANE('',#88211); -#88211 = AXIS2_PLACEMENT_3D('',#88212,#88213,#88214); -#88212 = CARTESIAN_POINT('',(2.35,10.527847992439,0.75)); -#88213 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#88214 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#88215 = DEFINITIONAL_REPRESENTATION('',(#88216),#88220); -#88216 = LINE('',#88217,#88218); -#88217 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#88218 = VECTOR('',#88219,1.); -#88219 = DIRECTION('',(-8.881784197001E-016,1.)); -#88220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88221 = ORIENTED_EDGE('',*,*,#88222,.F.); -#88222 = EDGE_CURVE('',#88223,#88195,#88225,.T.); -#88223 = VERTEX_POINT('',#88224); -#88224 = CARTESIAN_POINT('',(2.15,10.,0.65)); -#88225 = SURFACE_CURVE('',#88226,(#88230,#88237),.PCURVE_S1.); -#88226 = LINE('',#88227,#88228); -#88227 = CARTESIAN_POINT('',(2.15,10.,0.65)); -#88228 = VECTOR('',#88229,1.); -#88229 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88230 = PCURVE('',#86460,#88231); -#88231 = DEFINITIONAL_REPRESENTATION('',(#88232),#88236); -#88232 = LINE('',#88233,#88234); -#88233 = CARTESIAN_POINT('',(0.75,2.15)); -#88234 = VECTOR('',#88235,1.); -#88235 = DIRECTION('',(-1.,0.E+000)); -#88236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88237 = PCURVE('',#88238,#88243); -#88238 = PLANE('',#88239); -#88239 = AXIS2_PLACEMENT_3D('',#88240,#88241,#88242); -#88240 = CARTESIAN_POINT('',(2.15,10.527847992439,0.65)); -#88241 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88242 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88243 = DEFINITIONAL_REPRESENTATION('',(#88244),#88248); -#88244 = LINE('',#88245,#88246); -#88245 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#88246 = VECTOR('',#88247,1.); -#88247 = DIRECTION('',(-1.,0.E+000)); -#88248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88249 = ORIENTED_EDGE('',*,*,#88250,.F.); -#88250 = EDGE_CURVE('',#88167,#88223,#88251,.T.); -#88251 = SURFACE_CURVE('',#88252,(#88256,#88263),.PCURVE_S1.); -#88252 = LINE('',#88253,#88254); -#88253 = CARTESIAN_POINT('',(2.35,10.,0.65)); -#88254 = VECTOR('',#88255,1.); -#88255 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#88256 = PCURVE('',#86460,#88257); -#88257 = DEFINITIONAL_REPRESENTATION('',(#88258),#88262); -#88258 = LINE('',#88259,#88260); -#88259 = CARTESIAN_POINT('',(0.75,2.35)); -#88260 = VECTOR('',#88261,1.); -#88261 = DIRECTION('',(0.E+000,-1.)); -#88262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88263 = PCURVE('',#88264,#88269); -#88264 = PLANE('',#88265); -#88265 = AXIS2_PLACEMENT_3D('',#88266,#88267,#88268); -#88266 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); -#88267 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#88268 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#88269 = DEFINITIONAL_REPRESENTATION('',(#88270),#88274); -#88270 = LINE('',#88271,#88272); -#88271 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#88272 = VECTOR('',#88273,1.); -#88273 = DIRECTION('',(-8.881784197001E-016,-1.)); -#88274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88275 = FACE_BOUND('',#88276,.T.); -#88276 = EDGE_LOOP('',(#88277,#88307,#88335,#88363)); -#88277 = ORIENTED_EDGE('',*,*,#88278,.F.); -#88278 = EDGE_CURVE('',#88279,#88281,#88283,.T.); -#88279 = VERTEX_POINT('',#88280); -#88280 = CARTESIAN_POINT('',(1.35,10.,0.75)); -#88281 = VERTEX_POINT('',#88282); -#88282 = CARTESIAN_POINT('',(1.35,10.,0.65)); -#88283 = SURFACE_CURVE('',#88284,(#88288,#88295),.PCURVE_S1.); -#88284 = LINE('',#88285,#88286); -#88285 = CARTESIAN_POINT('',(1.35,10.,0.65)); -#88286 = VECTOR('',#88287,1.); -#88287 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88288 = PCURVE('',#86460,#88289); -#88289 = DEFINITIONAL_REPRESENTATION('',(#88290),#88294); -#88290 = LINE('',#88291,#88292); -#88291 = CARTESIAN_POINT('',(0.75,1.35)); -#88292 = VECTOR('',#88293,1.); -#88293 = DIRECTION('',(1.,0.E+000)); -#88294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88295 = PCURVE('',#88296,#88301); -#88296 = PLANE('',#88297); -#88297 = AXIS2_PLACEMENT_3D('',#88298,#88299,#88300); -#88298 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); -#88299 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88300 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88301 = DEFINITIONAL_REPRESENTATION('',(#88302),#88306); -#88302 = LINE('',#88303,#88304); -#88303 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#88304 = VECTOR('',#88305,1.); -#88305 = DIRECTION('',(-1.,0.E+000)); -#88306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88307 = ORIENTED_EDGE('',*,*,#88308,.F.); -#88308 = EDGE_CURVE('',#88309,#88279,#88311,.T.); -#88309 = VERTEX_POINT('',#88310); -#88310 = CARTESIAN_POINT('',(1.15,10.,0.75)); -#88311 = SURFACE_CURVE('',#88312,(#88316,#88323),.PCURVE_S1.); -#88312 = LINE('',#88313,#88314); -#88313 = CARTESIAN_POINT('',(1.35,10.,0.75)); -#88314 = VECTOR('',#88315,1.); -#88315 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#88316 = PCURVE('',#86460,#88317); -#88317 = DEFINITIONAL_REPRESENTATION('',(#88318),#88322); -#88318 = LINE('',#88319,#88320); -#88319 = CARTESIAN_POINT('',(0.65,1.35)); -#88320 = VECTOR('',#88321,1.); -#88321 = DIRECTION('',(0.E+000,1.)); -#88322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88323 = PCURVE('',#88324,#88329); -#88324 = PLANE('',#88325); -#88325 = AXIS2_PLACEMENT_3D('',#88326,#88327,#88328); -#88326 = CARTESIAN_POINT('',(1.35,10.527847992439,0.75)); -#88327 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); -#88328 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); -#88329 = DEFINITIONAL_REPRESENTATION('',(#88330),#88334); -#88330 = LINE('',#88331,#88332); -#88331 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); -#88332 = VECTOR('',#88333,1.); -#88333 = DIRECTION('',(-8.881784197001E-016,1.)); -#88334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88335 = ORIENTED_EDGE('',*,*,#88336,.F.); -#88336 = EDGE_CURVE('',#88337,#88309,#88339,.T.); -#88337 = VERTEX_POINT('',#88338); -#88338 = CARTESIAN_POINT('',(1.15,10.,0.65)); -#88339 = SURFACE_CURVE('',#88340,(#88344,#88351),.PCURVE_S1.); -#88340 = LINE('',#88341,#88342); -#88341 = CARTESIAN_POINT('',(1.15,10.,0.65)); -#88342 = VECTOR('',#88343,1.); -#88343 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88344 = PCURVE('',#86460,#88345); -#88345 = DEFINITIONAL_REPRESENTATION('',(#88346),#88350); -#88346 = LINE('',#88347,#88348); -#88347 = CARTESIAN_POINT('',(0.75,1.15)); -#88348 = VECTOR('',#88349,1.); -#88349 = DIRECTION('',(-1.,0.E+000)); -#88350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88351 = PCURVE('',#88352,#88357); -#88352 = PLANE('',#88353); -#88353 = AXIS2_PLACEMENT_3D('',#88354,#88355,#88356); -#88354 = CARTESIAN_POINT('',(1.15,10.527847992439,0.65)); -#88355 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88356 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88357 = DEFINITIONAL_REPRESENTATION('',(#88358),#88362); -#88358 = LINE('',#88359,#88360); -#88359 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#88360 = VECTOR('',#88361,1.); -#88361 = DIRECTION('',(-1.,0.E+000)); -#88362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88363 = ORIENTED_EDGE('',*,*,#88364,.F.); -#88364 = EDGE_CURVE('',#88281,#88337,#88365,.T.); -#88365 = SURFACE_CURVE('',#88366,(#88370,#88377),.PCURVE_S1.); -#88366 = LINE('',#88367,#88368); -#88367 = CARTESIAN_POINT('',(1.35,10.,0.65)); -#88368 = VECTOR('',#88369,1.); -#88369 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#88370 = PCURVE('',#86460,#88371); -#88371 = DEFINITIONAL_REPRESENTATION('',(#88372),#88376); -#88372 = LINE('',#88373,#88374); -#88373 = CARTESIAN_POINT('',(0.75,1.35)); -#88374 = VECTOR('',#88375,1.); -#88375 = DIRECTION('',(0.E+000,-1.)); -#88376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88377 = PCURVE('',#88378,#88383); -#88378 = PLANE('',#88379); -#88379 = AXIS2_PLACEMENT_3D('',#88380,#88381,#88382); -#88380 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); -#88381 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); -#88382 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#88383 = DEFINITIONAL_REPRESENTATION('',(#88384),#88388); -#88384 = LINE('',#88385,#88386); -#88385 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); -#88386 = VECTOR('',#88387,1.); -#88387 = DIRECTION('',(-8.881784197001E-016,-1.)); -#88388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88389 = ADVANCED_FACE('',(#88390,#88509,#88623,#88737,#88851,#88965, - #89079,#89193,#89307,#89416,#89530,#89644,#89758,#89872,#89986, - #90100,#90214),#88404,.F.); -#88390 = FACE_BOUND('',#88391,.T.); -#88391 = EDGE_LOOP('',(#88392,#88427,#88455,#88483)); -#88392 = ORIENTED_EDGE('',*,*,#88393,.F.); -#88393 = EDGE_CURVE('',#88394,#88396,#88398,.T.); -#88394 = VERTEX_POINT('',#88395); -#88395 = CARTESIAN_POINT('',(8.15,0.E+000,0.75)); -#88396 = VERTEX_POINT('',#88397); -#88397 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); -#88398 = SURFACE_CURVE('',#88399,(#88403,#88415),.PCURVE_S1.); -#88399 = LINE('',#88400,#88401); -#88400 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); -#88401 = VECTOR('',#88402,1.); -#88402 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88403 = PCURVE('',#88404,#88409); -#88404 = PLANE('',#88405); -#88405 = AXIS2_PLACEMENT_3D('',#88406,#88407,#88408); -#88406 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.4)); -#88407 = DIRECTION('',(0.E+000,1.,0.E+000)); -#88408 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88409 = DEFINITIONAL_REPRESENTATION('',(#88410),#88414); -#88410 = LINE('',#88411,#88412); -#88411 = CARTESIAN_POINT('',(-0.75,8.15)); -#88412 = VECTOR('',#88413,1.); -#88413 = DIRECTION('',(-1.,0.E+000)); -#88414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88415 = PCURVE('',#88416,#88421); -#88416 = PLANE('',#88417); -#88417 = AXIS2_PLACEMENT_3D('',#88418,#88419,#88420); -#88418 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); -#88419 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88420 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88421 = DEFINITIONAL_REPRESENTATION('',(#88422),#88426); -#88422 = LINE('',#88423,#88424); -#88423 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#88424 = VECTOR('',#88425,1.); -#88425 = DIRECTION('',(1.,0.E+000)); -#88426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88427 = ORIENTED_EDGE('',*,*,#88428,.F.); -#88428 = EDGE_CURVE('',#88429,#88394,#88431,.T.); -#88429 = VERTEX_POINT('',#88430); -#88430 = CARTESIAN_POINT('',(8.35,0.E+000,0.75)); -#88431 = SURFACE_CURVE('',#88432,(#88436,#88443),.PCURVE_S1.); -#88432 = LINE('',#88433,#88434); -#88433 = CARTESIAN_POINT('',(8.15,0.E+000,0.75)); -#88434 = VECTOR('',#88435,1.); -#88435 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88436 = PCURVE('',#88404,#88437); -#88437 = DEFINITIONAL_REPRESENTATION('',(#88438),#88442); -#88438 = LINE('',#88439,#88440); -#88439 = CARTESIAN_POINT('',(-0.65,8.15)); -#88440 = VECTOR('',#88441,1.); -#88441 = DIRECTION('',(0.E+000,-1.)); -#88442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88443 = PCURVE('',#88444,#88449); -#88444 = PLANE('',#88445); -#88445 = AXIS2_PLACEMENT_3D('',#88446,#88447,#88448); -#88446 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.75)); -#88447 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#88448 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#88449 = DEFINITIONAL_REPRESENTATION('',(#88450),#88454); -#88450 = LINE('',#88451,#88452); -#88451 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#88452 = VECTOR('',#88453,1.); -#88453 = DIRECTION('',(0.E+000,-1.)); -#88454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88455 = ORIENTED_EDGE('',*,*,#88456,.F.); -#88456 = EDGE_CURVE('',#88457,#88429,#88459,.T.); -#88457 = VERTEX_POINT('',#88458); -#88458 = CARTESIAN_POINT('',(8.35,0.E+000,0.65)); -#88459 = SURFACE_CURVE('',#88460,(#88464,#88471),.PCURVE_S1.); -#88460 = LINE('',#88461,#88462); -#88461 = CARTESIAN_POINT('',(8.35,0.E+000,0.65)); -#88462 = VECTOR('',#88463,1.); -#88463 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88464 = PCURVE('',#88404,#88465); -#88465 = DEFINITIONAL_REPRESENTATION('',(#88466),#88470); -#88466 = LINE('',#88467,#88468); -#88467 = CARTESIAN_POINT('',(-0.75,8.35)); -#88468 = VECTOR('',#88469,1.); -#88469 = DIRECTION('',(1.,0.E+000)); -#88470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88471 = PCURVE('',#88472,#88477); -#88472 = PLANE('',#88473); -#88473 = AXIS2_PLACEMENT_3D('',#88474,#88475,#88476); -#88474 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.65)); -#88475 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88476 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88477 = DEFINITIONAL_REPRESENTATION('',(#88478),#88482); -#88478 = LINE('',#88479,#88480); -#88479 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88480 = VECTOR('',#88481,1.); -#88481 = DIRECTION('',(1.,0.E+000)); -#88482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88483 = ORIENTED_EDGE('',*,*,#88484,.F.); -#88484 = EDGE_CURVE('',#88396,#88457,#88485,.T.); -#88485 = SURFACE_CURVE('',#88486,(#88490,#88497),.PCURVE_S1.); -#88486 = LINE('',#88487,#88488); -#88487 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); -#88488 = VECTOR('',#88489,1.); -#88489 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88490 = PCURVE('',#88404,#88491); -#88491 = DEFINITIONAL_REPRESENTATION('',(#88492),#88496); -#88492 = LINE('',#88493,#88494); -#88493 = CARTESIAN_POINT('',(-0.75,8.15)); -#88494 = VECTOR('',#88495,1.); -#88495 = DIRECTION('',(0.E+000,1.)); -#88496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88497 = PCURVE('',#88498,#88503); -#88498 = PLANE('',#88499); -#88499 = AXIS2_PLACEMENT_3D('',#88500,#88501,#88502); -#88500 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); -#88501 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#88502 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#88503 = DEFINITIONAL_REPRESENTATION('',(#88504),#88508); -#88504 = LINE('',#88505,#88506); -#88505 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#88506 = VECTOR('',#88507,1.); -#88507 = DIRECTION('',(0.E+000,1.)); -#88508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88509 = FACE_BOUND('',#88510,.T.); -#88510 = EDGE_LOOP('',(#88511,#88541,#88569,#88597)); -#88511 = ORIENTED_EDGE('',*,*,#88512,.F.); -#88512 = EDGE_CURVE('',#88513,#88515,#88517,.T.); -#88513 = VERTEX_POINT('',#88514); -#88514 = CARTESIAN_POINT('',(7.15,0.E+000,0.75)); -#88515 = VERTEX_POINT('',#88516); -#88516 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); -#88517 = SURFACE_CURVE('',#88518,(#88522,#88529),.PCURVE_S1.); -#88518 = LINE('',#88519,#88520); -#88519 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); -#88520 = VECTOR('',#88521,1.); -#88521 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88522 = PCURVE('',#88404,#88523); -#88523 = DEFINITIONAL_REPRESENTATION('',(#88524),#88528); -#88524 = LINE('',#88525,#88526); -#88525 = CARTESIAN_POINT('',(-0.75,7.15)); -#88526 = VECTOR('',#88527,1.); -#88527 = DIRECTION('',(-1.,0.E+000)); -#88528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88529 = PCURVE('',#88530,#88535); -#88530 = PLANE('',#88531); -#88531 = AXIS2_PLACEMENT_3D('',#88532,#88533,#88534); -#88532 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); -#88533 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88534 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88535 = DEFINITIONAL_REPRESENTATION('',(#88536),#88540); -#88536 = LINE('',#88537,#88538); -#88537 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#88538 = VECTOR('',#88539,1.); -#88539 = DIRECTION('',(1.,0.E+000)); -#88540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88541 = ORIENTED_EDGE('',*,*,#88542,.F.); -#88542 = EDGE_CURVE('',#88543,#88513,#88545,.T.); -#88543 = VERTEX_POINT('',#88544); -#88544 = CARTESIAN_POINT('',(7.35,0.E+000,0.75)); -#88545 = SURFACE_CURVE('',#88546,(#88550,#88557),.PCURVE_S1.); -#88546 = LINE('',#88547,#88548); -#88547 = CARTESIAN_POINT('',(7.15,0.E+000,0.75)); -#88548 = VECTOR('',#88549,1.); -#88549 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88550 = PCURVE('',#88404,#88551); -#88551 = DEFINITIONAL_REPRESENTATION('',(#88552),#88556); -#88552 = LINE('',#88553,#88554); -#88553 = CARTESIAN_POINT('',(-0.65,7.15)); -#88554 = VECTOR('',#88555,1.); -#88555 = DIRECTION('',(0.E+000,-1.)); -#88556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88557 = PCURVE('',#88558,#88563); -#88558 = PLANE('',#88559); -#88559 = AXIS2_PLACEMENT_3D('',#88560,#88561,#88562); -#88560 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.75)); -#88561 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#88562 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#88563 = DEFINITIONAL_REPRESENTATION('',(#88564),#88568); -#88564 = LINE('',#88565,#88566); -#88565 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#88566 = VECTOR('',#88567,1.); -#88567 = DIRECTION('',(0.E+000,-1.)); -#88568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88569 = ORIENTED_EDGE('',*,*,#88570,.F.); -#88570 = EDGE_CURVE('',#88571,#88543,#88573,.T.); -#88571 = VERTEX_POINT('',#88572); -#88572 = CARTESIAN_POINT('',(7.35,0.E+000,0.65)); -#88573 = SURFACE_CURVE('',#88574,(#88578,#88585),.PCURVE_S1.); -#88574 = LINE('',#88575,#88576); -#88575 = CARTESIAN_POINT('',(7.35,0.E+000,0.65)); -#88576 = VECTOR('',#88577,1.); -#88577 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88578 = PCURVE('',#88404,#88579); -#88579 = DEFINITIONAL_REPRESENTATION('',(#88580),#88584); -#88580 = LINE('',#88581,#88582); -#88581 = CARTESIAN_POINT('',(-0.75,7.35)); -#88582 = VECTOR('',#88583,1.); -#88583 = DIRECTION('',(1.,0.E+000)); -#88584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88585 = PCURVE('',#88586,#88591); -#88586 = PLANE('',#88587); -#88587 = AXIS2_PLACEMENT_3D('',#88588,#88589,#88590); -#88588 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.65)); -#88589 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88590 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88591 = DEFINITIONAL_REPRESENTATION('',(#88592),#88596); -#88592 = LINE('',#88593,#88594); -#88593 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88594 = VECTOR('',#88595,1.); -#88595 = DIRECTION('',(1.,0.E+000)); -#88596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88597 = ORIENTED_EDGE('',*,*,#88598,.F.); -#88598 = EDGE_CURVE('',#88515,#88571,#88599,.T.); -#88599 = SURFACE_CURVE('',#88600,(#88604,#88611),.PCURVE_S1.); -#88600 = LINE('',#88601,#88602); -#88601 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); -#88602 = VECTOR('',#88603,1.); -#88603 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88604 = PCURVE('',#88404,#88605); -#88605 = DEFINITIONAL_REPRESENTATION('',(#88606),#88610); -#88606 = LINE('',#88607,#88608); -#88607 = CARTESIAN_POINT('',(-0.75,7.15)); -#88608 = VECTOR('',#88609,1.); -#88609 = DIRECTION('',(0.E+000,1.)); -#88610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88611 = PCURVE('',#88612,#88617); -#88612 = PLANE('',#88613); -#88613 = AXIS2_PLACEMENT_3D('',#88614,#88615,#88616); -#88614 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); -#88615 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#88616 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#88617 = DEFINITIONAL_REPRESENTATION('',(#88618),#88622); -#88618 = LINE('',#88619,#88620); -#88619 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#88620 = VECTOR('',#88621,1.); -#88621 = DIRECTION('',(0.E+000,1.)); -#88622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88623 = FACE_BOUND('',#88624,.T.); -#88624 = EDGE_LOOP('',(#88625,#88655,#88683,#88711)); -#88625 = ORIENTED_EDGE('',*,*,#88626,.F.); -#88626 = EDGE_CURVE('',#88627,#88629,#88631,.T.); -#88627 = VERTEX_POINT('',#88628); -#88628 = CARTESIAN_POINT('',(6.15,0.E+000,0.75)); -#88629 = VERTEX_POINT('',#88630); -#88630 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); -#88631 = SURFACE_CURVE('',#88632,(#88636,#88643),.PCURVE_S1.); -#88632 = LINE('',#88633,#88634); -#88633 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); -#88634 = VECTOR('',#88635,1.); -#88635 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88636 = PCURVE('',#88404,#88637); -#88637 = DEFINITIONAL_REPRESENTATION('',(#88638),#88642); -#88638 = LINE('',#88639,#88640); -#88639 = CARTESIAN_POINT('',(-0.75,6.15)); -#88640 = VECTOR('',#88641,1.); -#88641 = DIRECTION('',(-1.,0.E+000)); -#88642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88643 = PCURVE('',#88644,#88649); -#88644 = PLANE('',#88645); -#88645 = AXIS2_PLACEMENT_3D('',#88646,#88647,#88648); -#88646 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); -#88647 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88648 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88649 = DEFINITIONAL_REPRESENTATION('',(#88650),#88654); -#88650 = LINE('',#88651,#88652); -#88651 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#88652 = VECTOR('',#88653,1.); -#88653 = DIRECTION('',(1.,0.E+000)); -#88654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88655 = ORIENTED_EDGE('',*,*,#88656,.F.); -#88656 = EDGE_CURVE('',#88657,#88627,#88659,.T.); -#88657 = VERTEX_POINT('',#88658); -#88658 = CARTESIAN_POINT('',(6.35,0.E+000,0.75)); -#88659 = SURFACE_CURVE('',#88660,(#88664,#88671),.PCURVE_S1.); -#88660 = LINE('',#88661,#88662); -#88661 = CARTESIAN_POINT('',(6.15,0.E+000,0.75)); -#88662 = VECTOR('',#88663,1.); -#88663 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88664 = PCURVE('',#88404,#88665); -#88665 = DEFINITIONAL_REPRESENTATION('',(#88666),#88670); -#88666 = LINE('',#88667,#88668); -#88667 = CARTESIAN_POINT('',(-0.65,6.15)); -#88668 = VECTOR('',#88669,1.); -#88669 = DIRECTION('',(0.E+000,-1.)); -#88670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88671 = PCURVE('',#88672,#88677); -#88672 = PLANE('',#88673); -#88673 = AXIS2_PLACEMENT_3D('',#88674,#88675,#88676); -#88674 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.75)); -#88675 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#88676 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#88677 = DEFINITIONAL_REPRESENTATION('',(#88678),#88682); -#88678 = LINE('',#88679,#88680); -#88679 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#88680 = VECTOR('',#88681,1.); -#88681 = DIRECTION('',(0.E+000,-1.)); -#88682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88683 = ORIENTED_EDGE('',*,*,#88684,.F.); -#88684 = EDGE_CURVE('',#88685,#88657,#88687,.T.); -#88685 = VERTEX_POINT('',#88686); -#88686 = CARTESIAN_POINT('',(6.35,0.E+000,0.65)); -#88687 = SURFACE_CURVE('',#88688,(#88692,#88699),.PCURVE_S1.); -#88688 = LINE('',#88689,#88690); -#88689 = CARTESIAN_POINT('',(6.35,0.E+000,0.65)); -#88690 = VECTOR('',#88691,1.); -#88691 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88692 = PCURVE('',#88404,#88693); -#88693 = DEFINITIONAL_REPRESENTATION('',(#88694),#88698); -#88694 = LINE('',#88695,#88696); -#88695 = CARTESIAN_POINT('',(-0.75,6.35)); -#88696 = VECTOR('',#88697,1.); -#88697 = DIRECTION('',(1.,0.E+000)); -#88698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88699 = PCURVE('',#88700,#88705); -#88700 = PLANE('',#88701); -#88701 = AXIS2_PLACEMENT_3D('',#88702,#88703,#88704); -#88702 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.65)); -#88703 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88704 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88705 = DEFINITIONAL_REPRESENTATION('',(#88706),#88710); -#88706 = LINE('',#88707,#88708); -#88707 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88708 = VECTOR('',#88709,1.); -#88709 = DIRECTION('',(1.,0.E+000)); -#88710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88711 = ORIENTED_EDGE('',*,*,#88712,.F.); -#88712 = EDGE_CURVE('',#88629,#88685,#88713,.T.); -#88713 = SURFACE_CURVE('',#88714,(#88718,#88725),.PCURVE_S1.); -#88714 = LINE('',#88715,#88716); -#88715 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); -#88716 = VECTOR('',#88717,1.); -#88717 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88718 = PCURVE('',#88404,#88719); -#88719 = DEFINITIONAL_REPRESENTATION('',(#88720),#88724); -#88720 = LINE('',#88721,#88722); -#88721 = CARTESIAN_POINT('',(-0.75,6.15)); -#88722 = VECTOR('',#88723,1.); -#88723 = DIRECTION('',(0.E+000,1.)); -#88724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88725 = PCURVE('',#88726,#88731); -#88726 = PLANE('',#88727); -#88727 = AXIS2_PLACEMENT_3D('',#88728,#88729,#88730); -#88728 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); -#88729 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#88730 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#88731 = DEFINITIONAL_REPRESENTATION('',(#88732),#88736); -#88732 = LINE('',#88733,#88734); -#88733 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#88734 = VECTOR('',#88735,1.); -#88735 = DIRECTION('',(0.E+000,1.)); -#88736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88737 = FACE_BOUND('',#88738,.T.); -#88738 = EDGE_LOOP('',(#88739,#88769,#88797,#88825)); -#88739 = ORIENTED_EDGE('',*,*,#88740,.F.); -#88740 = EDGE_CURVE('',#88741,#88743,#88745,.T.); -#88741 = VERTEX_POINT('',#88742); -#88742 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); -#88743 = VERTEX_POINT('',#88744); -#88744 = CARTESIAN_POINT('',(4.85,0.E+000,0.75)); -#88745 = SURFACE_CURVE('',#88746,(#88750,#88757),.PCURVE_S1.); -#88746 = LINE('',#88747,#88748); -#88747 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); -#88748 = VECTOR('',#88749,1.); -#88749 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88750 = PCURVE('',#88404,#88751); -#88751 = DEFINITIONAL_REPRESENTATION('',(#88752),#88756); -#88752 = LINE('',#88753,#88754); -#88753 = CARTESIAN_POINT('',(-0.75,4.85)); -#88754 = VECTOR('',#88755,1.); -#88755 = DIRECTION('',(1.,0.E+000)); -#88756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88757 = PCURVE('',#88758,#88763); -#88758 = PLANE('',#88759); -#88759 = AXIS2_PLACEMENT_3D('',#88760,#88761,#88762); -#88760 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); -#88761 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88762 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88763 = DEFINITIONAL_REPRESENTATION('',(#88764),#88768); -#88764 = LINE('',#88765,#88766); -#88765 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88766 = VECTOR('',#88767,1.); -#88767 = DIRECTION('',(1.,0.E+000)); -#88768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88769 = ORIENTED_EDGE('',*,*,#88770,.F.); -#88770 = EDGE_CURVE('',#88771,#88741,#88773,.T.); -#88771 = VERTEX_POINT('',#88772); -#88772 = CARTESIAN_POINT('',(4.65,0.E+000,0.65)); -#88773 = SURFACE_CURVE('',#88774,(#88778,#88785),.PCURVE_S1.); -#88774 = LINE('',#88775,#88776); -#88775 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); -#88776 = VECTOR('',#88777,1.); -#88777 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88778 = PCURVE('',#88404,#88779); -#88779 = DEFINITIONAL_REPRESENTATION('',(#88780),#88784); -#88780 = LINE('',#88781,#88782); -#88781 = CARTESIAN_POINT('',(-0.75,4.85)); -#88782 = VECTOR('',#88783,1.); -#88783 = DIRECTION('',(0.E+000,1.)); -#88784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88785 = PCURVE('',#88786,#88791); -#88786 = PLANE('',#88787); -#88787 = AXIS2_PLACEMENT_3D('',#88788,#88789,#88790); -#88788 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); -#88789 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#88790 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#88791 = DEFINITIONAL_REPRESENTATION('',(#88792),#88796); -#88792 = LINE('',#88793,#88794); -#88793 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#88794 = VECTOR('',#88795,1.); -#88795 = DIRECTION('',(0.E+000,1.)); -#88796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88797 = ORIENTED_EDGE('',*,*,#88798,.F.); -#88798 = EDGE_CURVE('',#88799,#88771,#88801,.T.); -#88799 = VERTEX_POINT('',#88800); -#88800 = CARTESIAN_POINT('',(4.65,0.E+000,0.75)); -#88801 = SURFACE_CURVE('',#88802,(#88806,#88813),.PCURVE_S1.); -#88802 = LINE('',#88803,#88804); -#88803 = CARTESIAN_POINT('',(4.65,0.E+000,0.65)); -#88804 = VECTOR('',#88805,1.); -#88805 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88806 = PCURVE('',#88404,#88807); -#88807 = DEFINITIONAL_REPRESENTATION('',(#88808),#88812); -#88808 = LINE('',#88809,#88810); -#88809 = CARTESIAN_POINT('',(-0.75,4.65)); -#88810 = VECTOR('',#88811,1.); -#88811 = DIRECTION('',(-1.,0.E+000)); -#88812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88813 = PCURVE('',#88814,#88819); -#88814 = PLANE('',#88815); -#88815 = AXIS2_PLACEMENT_3D('',#88816,#88817,#88818); -#88816 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.65)); -#88817 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88818 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88819 = DEFINITIONAL_REPRESENTATION('',(#88820),#88824); -#88820 = LINE('',#88821,#88822); -#88821 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#88822 = VECTOR('',#88823,1.); -#88823 = DIRECTION('',(1.,0.E+000)); -#88824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88825 = ORIENTED_EDGE('',*,*,#88826,.F.); -#88826 = EDGE_CURVE('',#88743,#88799,#88827,.T.); -#88827 = SURFACE_CURVE('',#88828,(#88832,#88839),.PCURVE_S1.); -#88828 = LINE('',#88829,#88830); -#88829 = CARTESIAN_POINT('',(4.85,0.E+000,0.75)); -#88830 = VECTOR('',#88831,1.); -#88831 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88832 = PCURVE('',#88404,#88833); -#88833 = DEFINITIONAL_REPRESENTATION('',(#88834),#88838); -#88834 = LINE('',#88835,#88836); -#88835 = CARTESIAN_POINT('',(-0.65,4.85)); -#88836 = VECTOR('',#88837,1.); -#88837 = DIRECTION('',(0.E+000,-1.)); -#88838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88839 = PCURVE('',#88840,#88845); -#88840 = PLANE('',#88841); -#88841 = AXIS2_PLACEMENT_3D('',#88842,#88843,#88844); -#88842 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.75)); -#88843 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#88844 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#88845 = DEFINITIONAL_REPRESENTATION('',(#88846),#88850); -#88846 = LINE('',#88847,#88848); -#88847 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#88848 = VECTOR('',#88849,1.); -#88849 = DIRECTION('',(0.E+000,-1.)); -#88850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88851 = FACE_BOUND('',#88852,.T.); -#88852 = EDGE_LOOP('',(#88853,#88883,#88911,#88939)); -#88853 = ORIENTED_EDGE('',*,*,#88854,.F.); -#88854 = EDGE_CURVE('',#88855,#88857,#88859,.T.); -#88855 = VERTEX_POINT('',#88856); -#88856 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); -#88857 = VERTEX_POINT('',#88858); -#88858 = CARTESIAN_POINT('',(3.85,0.E+000,0.75)); -#88859 = SURFACE_CURVE('',#88860,(#88864,#88871),.PCURVE_S1.); -#88860 = LINE('',#88861,#88862); -#88861 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); -#88862 = VECTOR('',#88863,1.); -#88863 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88864 = PCURVE('',#88404,#88865); -#88865 = DEFINITIONAL_REPRESENTATION('',(#88866),#88870); -#88866 = LINE('',#88867,#88868); -#88867 = CARTESIAN_POINT('',(-0.75,3.85)); -#88868 = VECTOR('',#88869,1.); -#88869 = DIRECTION('',(1.,0.E+000)); -#88870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88871 = PCURVE('',#88872,#88877); -#88872 = PLANE('',#88873); -#88873 = AXIS2_PLACEMENT_3D('',#88874,#88875,#88876); -#88874 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); -#88875 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88876 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88877 = DEFINITIONAL_REPRESENTATION('',(#88878),#88882); -#88878 = LINE('',#88879,#88880); -#88879 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88880 = VECTOR('',#88881,1.); -#88881 = DIRECTION('',(1.,0.E+000)); -#88882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88883 = ORIENTED_EDGE('',*,*,#88884,.F.); -#88884 = EDGE_CURVE('',#88885,#88855,#88887,.T.); -#88885 = VERTEX_POINT('',#88886); -#88886 = CARTESIAN_POINT('',(3.65,0.E+000,0.65)); -#88887 = SURFACE_CURVE('',#88888,(#88892,#88899),.PCURVE_S1.); -#88888 = LINE('',#88889,#88890); -#88889 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); -#88890 = VECTOR('',#88891,1.); -#88891 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88892 = PCURVE('',#88404,#88893); -#88893 = DEFINITIONAL_REPRESENTATION('',(#88894),#88898); -#88894 = LINE('',#88895,#88896); -#88895 = CARTESIAN_POINT('',(-0.75,3.85)); -#88896 = VECTOR('',#88897,1.); -#88897 = DIRECTION('',(0.E+000,1.)); -#88898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88899 = PCURVE('',#88900,#88905); -#88900 = PLANE('',#88901); -#88901 = AXIS2_PLACEMENT_3D('',#88902,#88903,#88904); -#88902 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); -#88903 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#88904 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#88905 = DEFINITIONAL_REPRESENTATION('',(#88906),#88910); -#88906 = LINE('',#88907,#88908); -#88907 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#88908 = VECTOR('',#88909,1.); -#88909 = DIRECTION('',(0.E+000,1.)); -#88910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88911 = ORIENTED_EDGE('',*,*,#88912,.F.); -#88912 = EDGE_CURVE('',#88913,#88885,#88915,.T.); -#88913 = VERTEX_POINT('',#88914); -#88914 = CARTESIAN_POINT('',(3.65,0.E+000,0.75)); -#88915 = SURFACE_CURVE('',#88916,(#88920,#88927),.PCURVE_S1.); -#88916 = LINE('',#88917,#88918); -#88917 = CARTESIAN_POINT('',(3.65,0.E+000,0.65)); -#88918 = VECTOR('',#88919,1.); -#88919 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88920 = PCURVE('',#88404,#88921); -#88921 = DEFINITIONAL_REPRESENTATION('',(#88922),#88926); -#88922 = LINE('',#88923,#88924); -#88923 = CARTESIAN_POINT('',(-0.75,3.65)); -#88924 = VECTOR('',#88925,1.); -#88925 = DIRECTION('',(-1.,0.E+000)); -#88926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88927 = PCURVE('',#88928,#88933); -#88928 = PLANE('',#88929); -#88929 = AXIS2_PLACEMENT_3D('',#88930,#88931,#88932); -#88930 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.65)); -#88931 = DIRECTION('',(1.,0.E+000,0.E+000)); -#88932 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#88933 = DEFINITIONAL_REPRESENTATION('',(#88934),#88938); +#88834 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#88835 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#88836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88837 = ADVANCED_FACE('',(#88838,#88957,#89071,#89185,#89299,#89413, + #89527,#89641,#89755,#89869,#89983,#90097,#90211,#90325,#90439, + #90553,#90667),#88852,.F.); +#88838 = FACE_BOUND('',#88839,.T.); +#88839 = EDGE_LOOP('',(#88840,#88875,#88903,#88931)); +#88840 = ORIENTED_EDGE('',*,*,#88841,.T.); +#88841 = EDGE_CURVE('',#88842,#88844,#88846,.T.); +#88842 = VERTEX_POINT('',#88843); +#88843 = CARTESIAN_POINT('',(9.8,10.,0.E+000)); +#88844 = VERTEX_POINT('',#88845); +#88845 = CARTESIAN_POINT('',(0.2,10.,0.E+000)); +#88846 = SURFACE_CURVE('',#88847,(#88851,#88863),.PCURVE_S1.); +#88847 = LINE('',#88848,#88849); +#88848 = CARTESIAN_POINT('',(0.E+000,10.,0.E+000)); +#88849 = VECTOR('',#88850,1.); +#88850 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88851 = PCURVE('',#88852,#88857); +#88852 = PLANE('',#88853); +#88853 = AXIS2_PLACEMENT_3D('',#88854,#88855,#88856); +#88854 = CARTESIAN_POINT('',(0.E+000,10.,1.4)); +#88855 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#88856 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88857 = DEFINITIONAL_REPRESENTATION('',(#88858),#88862); +#88858 = LINE('',#88859,#88860); +#88859 = CARTESIAN_POINT('',(1.4,0.E+000)); +#88860 = VECTOR('',#88861,1.); +#88861 = DIRECTION('',(0.E+000,-1.)); +#88862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88863 = PCURVE('',#88864,#88869); +#88864 = PLANE('',#88865); +#88865 = AXIS2_PLACEMENT_3D('',#88866,#88867,#88868); +#88866 = CARTESIAN_POINT('',(0.E+000,10.,0.E+000)); +#88867 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88868 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88869 = DEFINITIONAL_REPRESENTATION('',(#88870),#88874); +#88870 = LINE('',#88871,#88872); +#88871 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88872 = VECTOR('',#88873,1.); +#88873 = DIRECTION('',(1.,0.E+000)); +#88874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88875 = ORIENTED_EDGE('',*,*,#88876,.T.); +#88876 = EDGE_CURVE('',#88844,#88877,#88879,.T.); +#88877 = VERTEX_POINT('',#88878); +#88878 = CARTESIAN_POINT('',(0.2,10.,1.2)); +#88879 = SURFACE_CURVE('',#88880,(#88884,#88891),.PCURVE_S1.); +#88880 = LINE('',#88881,#88882); +#88881 = CARTESIAN_POINT('',(0.2,10.,1.4)); +#88882 = VECTOR('',#88883,1.); +#88883 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88884 = PCURVE('',#88852,#88885); +#88885 = DEFINITIONAL_REPRESENTATION('',(#88886),#88890); +#88886 = LINE('',#88887,#88888); +#88887 = CARTESIAN_POINT('',(0.E+000,0.2)); +#88888 = VECTOR('',#88889,1.); +#88889 = DIRECTION('',(-1.,0.E+000)); +#88890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88891 = PCURVE('',#88892,#88897); +#88892 = PLANE('',#88893); +#88893 = AXIS2_PLACEMENT_3D('',#88894,#88895,#88896); +#88894 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); +#88895 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#88896 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#88897 = DEFINITIONAL_REPRESENTATION('',(#88898),#88902); +#88898 = LINE('',#88899,#88900); +#88899 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); +#88900 = VECTOR('',#88901,1.); +#88901 = DIRECTION('',(0.E+000,1.)); +#88902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88903 = ORIENTED_EDGE('',*,*,#88904,.T.); +#88904 = EDGE_CURVE('',#88877,#88905,#88907,.T.); +#88905 = VERTEX_POINT('',#88906); +#88906 = CARTESIAN_POINT('',(9.8,10.,1.2)); +#88907 = SURFACE_CURVE('',#88908,(#88912,#88919),.PCURVE_S1.); +#88908 = LINE('',#88909,#88910); +#88909 = CARTESIAN_POINT('',(0.E+000,10.,1.2)); +#88910 = VECTOR('',#88911,1.); +#88911 = DIRECTION('',(1.,0.E+000,0.E+000)); +#88912 = PCURVE('',#88852,#88913); +#88913 = DEFINITIONAL_REPRESENTATION('',(#88914),#88918); +#88914 = LINE('',#88915,#88916); +#88915 = CARTESIAN_POINT('',(0.2,0.E+000)); +#88916 = VECTOR('',#88917,1.); +#88917 = DIRECTION('',(0.E+000,1.)); +#88918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88919 = PCURVE('',#88920,#88925); +#88920 = PLANE('',#88921); +#88921 = AXIS2_PLACEMENT_3D('',#88922,#88923,#88924); +#88922 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); +#88923 = DIRECTION('',(0.E+000,-0.707106781187,-0.707106781187)); +#88924 = DIRECTION('',(0.E+000,0.707106781187,-0.707106781187)); +#88925 = DEFINITIONAL_REPRESENTATION('',(#88926),#88930); +#88926 = LINE('',#88927,#88928); +#88927 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); +#88928 = VECTOR('',#88929,1.); +#88929 = DIRECTION('',(0.E+000,1.)); +#88930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88931 = ORIENTED_EDGE('',*,*,#88932,.T.); +#88932 = EDGE_CURVE('',#88905,#88842,#88933,.T.); +#88933 = SURFACE_CURVE('',#88934,(#88938,#88945),.PCURVE_S1.); #88934 = LINE('',#88935,#88936); -#88935 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#88935 = CARTESIAN_POINT('',(9.8,10.,1.4)); #88936 = VECTOR('',#88937,1.); -#88937 = DIRECTION('',(1.,0.E+000)); -#88938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88939 = ORIENTED_EDGE('',*,*,#88940,.F.); -#88940 = EDGE_CURVE('',#88857,#88913,#88941,.T.); -#88941 = SURFACE_CURVE('',#88942,(#88946,#88953),.PCURVE_S1.); -#88942 = LINE('',#88943,#88944); -#88943 = CARTESIAN_POINT('',(3.85,0.E+000,0.75)); -#88944 = VECTOR('',#88945,1.); -#88945 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88946 = PCURVE('',#88404,#88947); -#88947 = DEFINITIONAL_REPRESENTATION('',(#88948),#88952); -#88948 = LINE('',#88949,#88950); -#88949 = CARTESIAN_POINT('',(-0.65,3.85)); -#88950 = VECTOR('',#88951,1.); -#88951 = DIRECTION('',(0.E+000,-1.)); -#88952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88953 = PCURVE('',#88954,#88959); -#88954 = PLANE('',#88955); -#88955 = AXIS2_PLACEMENT_3D('',#88956,#88957,#88958); -#88956 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.75)); -#88957 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#88958 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#88959 = DEFINITIONAL_REPRESENTATION('',(#88960),#88964); -#88960 = LINE('',#88961,#88962); -#88961 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#88962 = VECTOR('',#88963,1.); -#88963 = DIRECTION('',(0.E+000,-1.)); -#88964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88965 = FACE_BOUND('',#88966,.T.); -#88966 = EDGE_LOOP('',(#88967,#88997,#89025,#89053)); -#88967 = ORIENTED_EDGE('',*,*,#88968,.F.); -#88968 = EDGE_CURVE('',#88969,#88971,#88973,.T.); -#88969 = VERTEX_POINT('',#88970); -#88970 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); -#88971 = VERTEX_POINT('',#88972); -#88972 = CARTESIAN_POINT('',(2.85,0.E+000,0.75)); -#88973 = SURFACE_CURVE('',#88974,(#88978,#88985),.PCURVE_S1.); -#88974 = LINE('',#88975,#88976); -#88975 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); -#88976 = VECTOR('',#88977,1.); -#88977 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88978 = PCURVE('',#88404,#88979); -#88979 = DEFINITIONAL_REPRESENTATION('',(#88980),#88984); -#88980 = LINE('',#88981,#88982); -#88981 = CARTESIAN_POINT('',(-0.75,2.85)); -#88982 = VECTOR('',#88983,1.); -#88983 = DIRECTION('',(1.,0.E+000)); -#88984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88985 = PCURVE('',#88986,#88991); -#88986 = PLANE('',#88987); -#88987 = AXIS2_PLACEMENT_3D('',#88988,#88989,#88990); -#88988 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); -#88989 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#88990 = DIRECTION('',(0.E+000,0.E+000,1.)); -#88991 = DEFINITIONAL_REPRESENTATION('',(#88992),#88996); -#88992 = LINE('',#88993,#88994); -#88993 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#88994 = VECTOR('',#88995,1.); -#88995 = DIRECTION('',(1.,0.E+000)); -#88996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#88997 = ORIENTED_EDGE('',*,*,#88998,.F.); -#88998 = EDGE_CURVE('',#88999,#88969,#89001,.T.); -#88999 = VERTEX_POINT('',#89000); -#89000 = CARTESIAN_POINT('',(2.65,0.E+000,0.65)); -#89001 = SURFACE_CURVE('',#89002,(#89006,#89013),.PCURVE_S1.); -#89002 = LINE('',#89003,#89004); -#89003 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); -#89004 = VECTOR('',#89005,1.); -#89005 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89006 = PCURVE('',#88404,#89007); -#89007 = DEFINITIONAL_REPRESENTATION('',(#89008),#89012); -#89008 = LINE('',#89009,#89010); -#89009 = CARTESIAN_POINT('',(-0.75,2.85)); -#89010 = VECTOR('',#89011,1.); -#89011 = DIRECTION('',(0.E+000,1.)); -#89012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89013 = PCURVE('',#89014,#89019); -#89014 = PLANE('',#89015); -#89015 = AXIS2_PLACEMENT_3D('',#89016,#89017,#89018); -#89016 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); -#89017 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89018 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89019 = DEFINITIONAL_REPRESENTATION('',(#89020),#89024); -#89020 = LINE('',#89021,#89022); -#89021 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89022 = VECTOR('',#89023,1.); -#89023 = DIRECTION('',(0.E+000,1.)); -#89024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89025 = ORIENTED_EDGE('',*,*,#89026,.F.); -#89026 = EDGE_CURVE('',#89027,#88999,#89029,.T.); -#89027 = VERTEX_POINT('',#89028); -#89028 = CARTESIAN_POINT('',(2.65,0.E+000,0.75)); -#89029 = SURFACE_CURVE('',#89030,(#89034,#89041),.PCURVE_S1.); -#89030 = LINE('',#89031,#89032); -#89031 = CARTESIAN_POINT('',(2.65,0.E+000,0.65)); -#89032 = VECTOR('',#89033,1.); -#89033 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89034 = PCURVE('',#88404,#89035); -#89035 = DEFINITIONAL_REPRESENTATION('',(#89036),#89040); -#89036 = LINE('',#89037,#89038); -#89037 = CARTESIAN_POINT('',(-0.75,2.65)); -#89038 = VECTOR('',#89039,1.); -#89039 = DIRECTION('',(-1.,0.E+000)); -#89040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89041 = PCURVE('',#89042,#89047); -#89042 = PLANE('',#89043); -#89043 = AXIS2_PLACEMENT_3D('',#89044,#89045,#89046); -#89044 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.65)); -#89045 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89046 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89047 = DEFINITIONAL_REPRESENTATION('',(#89048),#89052); +#88937 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88938 = PCURVE('',#88852,#88939); +#88939 = DEFINITIONAL_REPRESENTATION('',(#88940),#88944); +#88940 = LINE('',#88941,#88942); +#88941 = CARTESIAN_POINT('',(0.E+000,9.8)); +#88942 = VECTOR('',#88943,1.); +#88943 = DIRECTION('',(1.,0.E+000)); +#88944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88945 = PCURVE('',#88946,#88951); +#88946 = PLANE('',#88947); +#88947 = AXIS2_PLACEMENT_3D('',#88948,#88949,#88950); +#88948 = CARTESIAN_POINT('',(9.8,10.,1.4)); +#88949 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#88950 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#88951 = DEFINITIONAL_REPRESENTATION('',(#88952),#88956); +#88952 = LINE('',#88953,#88954); +#88953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#88954 = VECTOR('',#88955,1.); +#88955 = DIRECTION('',(0.E+000,-1.)); +#88956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88957 = FACE_BOUND('',#88958,.T.); +#88958 = EDGE_LOOP('',(#88959,#88989,#89017,#89045)); +#88959 = ORIENTED_EDGE('',*,*,#88960,.F.); +#88960 = EDGE_CURVE('',#88961,#88963,#88965,.T.); +#88961 = VERTEX_POINT('',#88962); +#88962 = CARTESIAN_POINT('',(1.85,10.,0.75)); +#88963 = VERTEX_POINT('',#88964); +#88964 = CARTESIAN_POINT('',(1.85,10.,0.65)); +#88965 = SURFACE_CURVE('',#88966,(#88970,#88977),.PCURVE_S1.); +#88966 = LINE('',#88967,#88968); +#88967 = CARTESIAN_POINT('',(1.85,10.,0.65)); +#88968 = VECTOR('',#88969,1.); +#88969 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#88970 = PCURVE('',#88852,#88971); +#88971 = DEFINITIONAL_REPRESENTATION('',(#88972),#88976); +#88972 = LINE('',#88973,#88974); +#88973 = CARTESIAN_POINT('',(0.75,1.85)); +#88974 = VECTOR('',#88975,1.); +#88975 = DIRECTION('',(1.,0.E+000)); +#88976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88977 = PCURVE('',#88978,#88983); +#88978 = PLANE('',#88979); +#88979 = AXIS2_PLACEMENT_3D('',#88980,#88981,#88982); +#88980 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); +#88981 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#88982 = DIRECTION('',(0.E+000,0.E+000,1.)); +#88983 = DEFINITIONAL_REPRESENTATION('',(#88984),#88988); +#88984 = LINE('',#88985,#88986); +#88985 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#88986 = VECTOR('',#88987,1.); +#88987 = DIRECTION('',(-1.,0.E+000)); +#88988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#88989 = ORIENTED_EDGE('',*,*,#88990,.F.); +#88990 = EDGE_CURVE('',#88991,#88961,#88993,.T.); +#88991 = VERTEX_POINT('',#88992); +#88992 = CARTESIAN_POINT('',(1.65,10.,0.75)); +#88993 = SURFACE_CURVE('',#88994,(#88998,#89005),.PCURVE_S1.); +#88994 = LINE('',#88995,#88996); +#88995 = CARTESIAN_POINT('',(1.85,10.,0.75)); +#88996 = VECTOR('',#88997,1.); +#88997 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#88998 = PCURVE('',#88852,#88999); +#88999 = DEFINITIONAL_REPRESENTATION('',(#89000),#89004); +#89000 = LINE('',#89001,#89002); +#89001 = CARTESIAN_POINT('',(0.65,1.85)); +#89002 = VECTOR('',#89003,1.); +#89003 = DIRECTION('',(0.E+000,1.)); +#89004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89005 = PCURVE('',#89006,#89011); +#89006 = PLANE('',#89007); +#89007 = AXIS2_PLACEMENT_3D('',#89008,#89009,#89010); +#89008 = CARTESIAN_POINT('',(1.85,10.527847992439,0.75)); +#89009 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89010 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89011 = DEFINITIONAL_REPRESENTATION('',(#89012),#89016); +#89012 = LINE('',#89013,#89014); +#89013 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89014 = VECTOR('',#89015,1.); +#89015 = DIRECTION('',(-8.881784197001E-016,1.)); +#89016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89017 = ORIENTED_EDGE('',*,*,#89018,.F.); +#89018 = EDGE_CURVE('',#89019,#88991,#89021,.T.); +#89019 = VERTEX_POINT('',#89020); +#89020 = CARTESIAN_POINT('',(1.65,10.,0.65)); +#89021 = SURFACE_CURVE('',#89022,(#89026,#89033),.PCURVE_S1.); +#89022 = LINE('',#89023,#89024); +#89023 = CARTESIAN_POINT('',(1.65,10.,0.65)); +#89024 = VECTOR('',#89025,1.); +#89025 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89026 = PCURVE('',#88852,#89027); +#89027 = DEFINITIONAL_REPRESENTATION('',(#89028),#89032); +#89028 = LINE('',#89029,#89030); +#89029 = CARTESIAN_POINT('',(0.75,1.65)); +#89030 = VECTOR('',#89031,1.); +#89031 = DIRECTION('',(-1.,0.E+000)); +#89032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89033 = PCURVE('',#89034,#89039); +#89034 = PLANE('',#89035); +#89035 = AXIS2_PLACEMENT_3D('',#89036,#89037,#89038); +#89036 = CARTESIAN_POINT('',(1.65,10.527847992439,0.65)); +#89037 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89038 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89039 = DEFINITIONAL_REPRESENTATION('',(#89040),#89044); +#89040 = LINE('',#89041,#89042); +#89041 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89042 = VECTOR('',#89043,1.); +#89043 = DIRECTION('',(-1.,0.E+000)); +#89044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89045 = ORIENTED_EDGE('',*,*,#89046,.F.); +#89046 = EDGE_CURVE('',#88963,#89019,#89047,.T.); +#89047 = SURFACE_CURVE('',#89048,(#89052,#89059),.PCURVE_S1.); #89048 = LINE('',#89049,#89050); -#89049 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#89049 = CARTESIAN_POINT('',(1.85,10.,0.65)); #89050 = VECTOR('',#89051,1.); -#89051 = DIRECTION('',(1.,0.E+000)); -#89052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89053 = ORIENTED_EDGE('',*,*,#89054,.F.); -#89054 = EDGE_CURVE('',#88971,#89027,#89055,.T.); -#89055 = SURFACE_CURVE('',#89056,(#89060,#89067),.PCURVE_S1.); -#89056 = LINE('',#89057,#89058); -#89057 = CARTESIAN_POINT('',(2.85,0.E+000,0.75)); -#89058 = VECTOR('',#89059,1.); -#89059 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89060 = PCURVE('',#88404,#89061); -#89061 = DEFINITIONAL_REPRESENTATION('',(#89062),#89066); -#89062 = LINE('',#89063,#89064); -#89063 = CARTESIAN_POINT('',(-0.65,2.85)); -#89064 = VECTOR('',#89065,1.); -#89065 = DIRECTION('',(0.E+000,-1.)); -#89066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89067 = PCURVE('',#89068,#89073); -#89068 = PLANE('',#89069); -#89069 = AXIS2_PLACEMENT_3D('',#89070,#89071,#89072); -#89070 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.75)); -#89071 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89072 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89073 = DEFINITIONAL_REPRESENTATION('',(#89074),#89078); -#89074 = LINE('',#89075,#89076); -#89075 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89076 = VECTOR('',#89077,1.); -#89077 = DIRECTION('',(0.E+000,-1.)); -#89078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89079 = FACE_BOUND('',#89080,.T.); -#89080 = EDGE_LOOP('',(#89081,#89111,#89139,#89167)); -#89081 = ORIENTED_EDGE('',*,*,#89082,.F.); -#89082 = EDGE_CURVE('',#89083,#89085,#89087,.T.); -#89083 = VERTEX_POINT('',#89084); -#89084 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); -#89085 = VERTEX_POINT('',#89086); -#89086 = CARTESIAN_POINT('',(1.85,0.E+000,0.75)); -#89087 = SURFACE_CURVE('',#89088,(#89092,#89099),.PCURVE_S1.); -#89088 = LINE('',#89089,#89090); -#89089 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); -#89090 = VECTOR('',#89091,1.); -#89091 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89092 = PCURVE('',#88404,#89093); -#89093 = DEFINITIONAL_REPRESENTATION('',(#89094),#89098); -#89094 = LINE('',#89095,#89096); -#89095 = CARTESIAN_POINT('',(-0.75,1.85)); -#89096 = VECTOR('',#89097,1.); -#89097 = DIRECTION('',(1.,0.E+000)); -#89098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89099 = PCURVE('',#89100,#89105); -#89100 = PLANE('',#89101); -#89101 = AXIS2_PLACEMENT_3D('',#89102,#89103,#89104); -#89102 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); -#89103 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89104 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89105 = DEFINITIONAL_REPRESENTATION('',(#89106),#89110); -#89106 = LINE('',#89107,#89108); -#89107 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89108 = VECTOR('',#89109,1.); -#89109 = DIRECTION('',(1.,0.E+000)); -#89110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89111 = ORIENTED_EDGE('',*,*,#89112,.F.); -#89112 = EDGE_CURVE('',#89113,#89083,#89115,.T.); -#89113 = VERTEX_POINT('',#89114); -#89114 = CARTESIAN_POINT('',(1.65,0.E+000,0.65)); -#89115 = SURFACE_CURVE('',#89116,(#89120,#89127),.PCURVE_S1.); -#89116 = LINE('',#89117,#89118); -#89117 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); -#89118 = VECTOR('',#89119,1.); -#89119 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89120 = PCURVE('',#88404,#89121); -#89121 = DEFINITIONAL_REPRESENTATION('',(#89122),#89126); -#89122 = LINE('',#89123,#89124); -#89123 = CARTESIAN_POINT('',(-0.75,1.85)); -#89124 = VECTOR('',#89125,1.); -#89125 = DIRECTION('',(0.E+000,1.)); -#89126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89127 = PCURVE('',#89128,#89133); -#89128 = PLANE('',#89129); -#89129 = AXIS2_PLACEMENT_3D('',#89130,#89131,#89132); -#89130 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); -#89131 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89132 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89133 = DEFINITIONAL_REPRESENTATION('',(#89134),#89138); -#89134 = LINE('',#89135,#89136); -#89135 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89136 = VECTOR('',#89137,1.); -#89137 = DIRECTION('',(0.E+000,1.)); -#89138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89139 = ORIENTED_EDGE('',*,*,#89140,.F.); -#89140 = EDGE_CURVE('',#89141,#89113,#89143,.T.); -#89141 = VERTEX_POINT('',#89142); -#89142 = CARTESIAN_POINT('',(1.65,0.E+000,0.75)); -#89143 = SURFACE_CURVE('',#89144,(#89148,#89155),.PCURVE_S1.); -#89144 = LINE('',#89145,#89146); -#89145 = CARTESIAN_POINT('',(1.65,0.E+000,0.65)); -#89146 = VECTOR('',#89147,1.); -#89147 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89148 = PCURVE('',#88404,#89149); -#89149 = DEFINITIONAL_REPRESENTATION('',(#89150),#89154); -#89150 = LINE('',#89151,#89152); -#89151 = CARTESIAN_POINT('',(-0.75,1.65)); -#89152 = VECTOR('',#89153,1.); -#89153 = DIRECTION('',(-1.,0.E+000)); -#89154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89155 = PCURVE('',#89156,#89161); -#89156 = PLANE('',#89157); -#89157 = AXIS2_PLACEMENT_3D('',#89158,#89159,#89160); -#89158 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.65)); -#89159 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89160 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89161 = DEFINITIONAL_REPRESENTATION('',(#89162),#89166); +#89051 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89052 = PCURVE('',#88852,#89053); +#89053 = DEFINITIONAL_REPRESENTATION('',(#89054),#89058); +#89054 = LINE('',#89055,#89056); +#89055 = CARTESIAN_POINT('',(0.75,1.85)); +#89056 = VECTOR('',#89057,1.); +#89057 = DIRECTION('',(0.E+000,-1.)); +#89058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89059 = PCURVE('',#89060,#89065); +#89060 = PLANE('',#89061); +#89061 = AXIS2_PLACEMENT_3D('',#89062,#89063,#89064); +#89062 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); +#89063 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89064 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89065 = DEFINITIONAL_REPRESENTATION('',(#89066),#89070); +#89066 = LINE('',#89067,#89068); +#89067 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89068 = VECTOR('',#89069,1.); +#89069 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89071 = FACE_BOUND('',#89072,.T.); +#89072 = EDGE_LOOP('',(#89073,#89103,#89131,#89159)); +#89073 = ORIENTED_EDGE('',*,*,#89074,.F.); +#89074 = EDGE_CURVE('',#89075,#89077,#89079,.T.); +#89075 = VERTEX_POINT('',#89076); +#89076 = CARTESIAN_POINT('',(2.85,10.,0.75)); +#89077 = VERTEX_POINT('',#89078); +#89078 = CARTESIAN_POINT('',(2.85,10.,0.65)); +#89079 = SURFACE_CURVE('',#89080,(#89084,#89091),.PCURVE_S1.); +#89080 = LINE('',#89081,#89082); +#89081 = CARTESIAN_POINT('',(2.85,10.,0.65)); +#89082 = VECTOR('',#89083,1.); +#89083 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89084 = PCURVE('',#88852,#89085); +#89085 = DEFINITIONAL_REPRESENTATION('',(#89086),#89090); +#89086 = LINE('',#89087,#89088); +#89087 = CARTESIAN_POINT('',(0.75,2.85)); +#89088 = VECTOR('',#89089,1.); +#89089 = DIRECTION('',(1.,0.E+000)); +#89090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89091 = PCURVE('',#89092,#89097); +#89092 = PLANE('',#89093); +#89093 = AXIS2_PLACEMENT_3D('',#89094,#89095,#89096); +#89094 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); +#89095 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89096 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89097 = DEFINITIONAL_REPRESENTATION('',(#89098),#89102); +#89098 = LINE('',#89099,#89100); +#89099 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89100 = VECTOR('',#89101,1.); +#89101 = DIRECTION('',(-1.,0.E+000)); +#89102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89103 = ORIENTED_EDGE('',*,*,#89104,.F.); +#89104 = EDGE_CURVE('',#89105,#89075,#89107,.T.); +#89105 = VERTEX_POINT('',#89106); +#89106 = CARTESIAN_POINT('',(2.65,10.,0.75)); +#89107 = SURFACE_CURVE('',#89108,(#89112,#89119),.PCURVE_S1.); +#89108 = LINE('',#89109,#89110); +#89109 = CARTESIAN_POINT('',(2.85,10.,0.75)); +#89110 = VECTOR('',#89111,1.); +#89111 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89112 = PCURVE('',#88852,#89113); +#89113 = DEFINITIONAL_REPRESENTATION('',(#89114),#89118); +#89114 = LINE('',#89115,#89116); +#89115 = CARTESIAN_POINT('',(0.65,2.85)); +#89116 = VECTOR('',#89117,1.); +#89117 = DIRECTION('',(0.E+000,1.)); +#89118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89119 = PCURVE('',#89120,#89125); +#89120 = PLANE('',#89121); +#89121 = AXIS2_PLACEMENT_3D('',#89122,#89123,#89124); +#89122 = CARTESIAN_POINT('',(2.85,10.527847992439,0.75)); +#89123 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89124 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89125 = DEFINITIONAL_REPRESENTATION('',(#89126),#89130); +#89126 = LINE('',#89127,#89128); +#89127 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89128 = VECTOR('',#89129,1.); +#89129 = DIRECTION('',(-8.881784197001E-016,1.)); +#89130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89131 = ORIENTED_EDGE('',*,*,#89132,.F.); +#89132 = EDGE_CURVE('',#89133,#89105,#89135,.T.); +#89133 = VERTEX_POINT('',#89134); +#89134 = CARTESIAN_POINT('',(2.65,10.,0.65)); +#89135 = SURFACE_CURVE('',#89136,(#89140,#89147),.PCURVE_S1.); +#89136 = LINE('',#89137,#89138); +#89137 = CARTESIAN_POINT('',(2.65,10.,0.65)); +#89138 = VECTOR('',#89139,1.); +#89139 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89140 = PCURVE('',#88852,#89141); +#89141 = DEFINITIONAL_REPRESENTATION('',(#89142),#89146); +#89142 = LINE('',#89143,#89144); +#89143 = CARTESIAN_POINT('',(0.75,2.65)); +#89144 = VECTOR('',#89145,1.); +#89145 = DIRECTION('',(-1.,0.E+000)); +#89146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89147 = PCURVE('',#89148,#89153); +#89148 = PLANE('',#89149); +#89149 = AXIS2_PLACEMENT_3D('',#89150,#89151,#89152); +#89150 = CARTESIAN_POINT('',(2.65,10.527847992439,0.65)); +#89151 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89152 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89153 = DEFINITIONAL_REPRESENTATION('',(#89154),#89158); +#89154 = LINE('',#89155,#89156); +#89155 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89156 = VECTOR('',#89157,1.); +#89157 = DIRECTION('',(-1.,0.E+000)); +#89158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89159 = ORIENTED_EDGE('',*,*,#89160,.F.); +#89160 = EDGE_CURVE('',#89077,#89133,#89161,.T.); +#89161 = SURFACE_CURVE('',#89162,(#89166,#89173),.PCURVE_S1.); #89162 = LINE('',#89163,#89164); -#89163 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#89163 = CARTESIAN_POINT('',(2.85,10.,0.65)); #89164 = VECTOR('',#89165,1.); -#89165 = DIRECTION('',(1.,0.E+000)); -#89166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89167 = ORIENTED_EDGE('',*,*,#89168,.F.); -#89168 = EDGE_CURVE('',#89085,#89141,#89169,.T.); -#89169 = SURFACE_CURVE('',#89170,(#89174,#89181),.PCURVE_S1.); -#89170 = LINE('',#89171,#89172); -#89171 = CARTESIAN_POINT('',(1.85,0.E+000,0.75)); -#89172 = VECTOR('',#89173,1.); -#89173 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89174 = PCURVE('',#88404,#89175); -#89175 = DEFINITIONAL_REPRESENTATION('',(#89176),#89180); -#89176 = LINE('',#89177,#89178); -#89177 = CARTESIAN_POINT('',(-0.65,1.85)); -#89178 = VECTOR('',#89179,1.); -#89179 = DIRECTION('',(0.E+000,-1.)); -#89180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89181 = PCURVE('',#89182,#89187); -#89182 = PLANE('',#89183); -#89183 = AXIS2_PLACEMENT_3D('',#89184,#89185,#89186); -#89184 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.75)); -#89185 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89186 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89187 = DEFINITIONAL_REPRESENTATION('',(#89188),#89192); -#89188 = LINE('',#89189,#89190); -#89189 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89190 = VECTOR('',#89191,1.); -#89191 = DIRECTION('',(0.E+000,-1.)); -#89192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89193 = FACE_BOUND('',#89194,.T.); -#89194 = EDGE_LOOP('',(#89195,#89225,#89253,#89281)); -#89195 = ORIENTED_EDGE('',*,*,#89196,.F.); -#89196 = EDGE_CURVE('',#89197,#89199,#89201,.T.); -#89197 = VERTEX_POINT('',#89198); -#89198 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); -#89199 = VERTEX_POINT('',#89200); -#89200 = CARTESIAN_POINT('',(1.35,0.E+000,0.75)); -#89201 = SURFACE_CURVE('',#89202,(#89206,#89213),.PCURVE_S1.); -#89202 = LINE('',#89203,#89204); -#89203 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); -#89204 = VECTOR('',#89205,1.); -#89205 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89206 = PCURVE('',#88404,#89207); -#89207 = DEFINITIONAL_REPRESENTATION('',(#89208),#89212); -#89208 = LINE('',#89209,#89210); -#89209 = CARTESIAN_POINT('',(-0.75,1.35)); -#89210 = VECTOR('',#89211,1.); -#89211 = DIRECTION('',(1.,0.E+000)); -#89212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89213 = PCURVE('',#89214,#89219); -#89214 = PLANE('',#89215); -#89215 = AXIS2_PLACEMENT_3D('',#89216,#89217,#89218); -#89216 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); -#89217 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89219 = DEFINITIONAL_REPRESENTATION('',(#89220),#89224); -#89220 = LINE('',#89221,#89222); -#89221 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89222 = VECTOR('',#89223,1.); -#89223 = DIRECTION('',(1.,0.E+000)); -#89224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89225 = ORIENTED_EDGE('',*,*,#89226,.F.); -#89226 = EDGE_CURVE('',#89227,#89197,#89229,.T.); -#89227 = VERTEX_POINT('',#89228); -#89228 = CARTESIAN_POINT('',(1.15,0.E+000,0.65)); -#89229 = SURFACE_CURVE('',#89230,(#89234,#89241),.PCURVE_S1.); -#89230 = LINE('',#89231,#89232); -#89231 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); -#89232 = VECTOR('',#89233,1.); -#89233 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89234 = PCURVE('',#88404,#89235); -#89235 = DEFINITIONAL_REPRESENTATION('',(#89236),#89240); -#89236 = LINE('',#89237,#89238); -#89237 = CARTESIAN_POINT('',(-0.75,1.35)); -#89238 = VECTOR('',#89239,1.); -#89239 = DIRECTION('',(0.E+000,1.)); -#89240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89241 = PCURVE('',#89242,#89247); -#89242 = PLANE('',#89243); -#89243 = AXIS2_PLACEMENT_3D('',#89244,#89245,#89246); -#89244 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); -#89245 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89246 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89247 = DEFINITIONAL_REPRESENTATION('',(#89248),#89252); -#89248 = LINE('',#89249,#89250); -#89249 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89250 = VECTOR('',#89251,1.); -#89251 = DIRECTION('',(0.E+000,1.)); -#89252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89253 = ORIENTED_EDGE('',*,*,#89254,.F.); -#89254 = EDGE_CURVE('',#89255,#89227,#89257,.T.); -#89255 = VERTEX_POINT('',#89256); -#89256 = CARTESIAN_POINT('',(1.15,0.E+000,0.75)); -#89257 = SURFACE_CURVE('',#89258,(#89262,#89269),.PCURVE_S1.); -#89258 = LINE('',#89259,#89260); -#89259 = CARTESIAN_POINT('',(1.15,0.E+000,0.65)); -#89260 = VECTOR('',#89261,1.); -#89261 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89262 = PCURVE('',#88404,#89263); -#89263 = DEFINITIONAL_REPRESENTATION('',(#89264),#89268); -#89264 = LINE('',#89265,#89266); -#89265 = CARTESIAN_POINT('',(-0.75,1.15)); -#89266 = VECTOR('',#89267,1.); -#89267 = DIRECTION('',(-1.,0.E+000)); -#89268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89269 = PCURVE('',#89270,#89275); -#89270 = PLANE('',#89271); -#89271 = AXIS2_PLACEMENT_3D('',#89272,#89273,#89274); -#89272 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.65)); -#89273 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89274 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89275 = DEFINITIONAL_REPRESENTATION('',(#89276),#89280); +#89165 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89166 = PCURVE('',#88852,#89167); +#89167 = DEFINITIONAL_REPRESENTATION('',(#89168),#89172); +#89168 = LINE('',#89169,#89170); +#89169 = CARTESIAN_POINT('',(0.75,2.85)); +#89170 = VECTOR('',#89171,1.); +#89171 = DIRECTION('',(0.E+000,-1.)); +#89172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89173 = PCURVE('',#89174,#89179); +#89174 = PLANE('',#89175); +#89175 = AXIS2_PLACEMENT_3D('',#89176,#89177,#89178); +#89176 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); +#89177 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89178 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89179 = DEFINITIONAL_REPRESENTATION('',(#89180),#89184); +#89180 = LINE('',#89181,#89182); +#89181 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89182 = VECTOR('',#89183,1.); +#89183 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89185 = FACE_BOUND('',#89186,.T.); +#89186 = EDGE_LOOP('',(#89187,#89217,#89245,#89273)); +#89187 = ORIENTED_EDGE('',*,*,#89188,.F.); +#89188 = EDGE_CURVE('',#89189,#89191,#89193,.T.); +#89189 = VERTEX_POINT('',#89190); +#89190 = CARTESIAN_POINT('',(3.85,10.,0.75)); +#89191 = VERTEX_POINT('',#89192); +#89192 = CARTESIAN_POINT('',(3.85,10.,0.65)); +#89193 = SURFACE_CURVE('',#89194,(#89198,#89205),.PCURVE_S1.); +#89194 = LINE('',#89195,#89196); +#89195 = CARTESIAN_POINT('',(3.85,10.,0.65)); +#89196 = VECTOR('',#89197,1.); +#89197 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89198 = PCURVE('',#88852,#89199); +#89199 = DEFINITIONAL_REPRESENTATION('',(#89200),#89204); +#89200 = LINE('',#89201,#89202); +#89201 = CARTESIAN_POINT('',(0.75,3.85)); +#89202 = VECTOR('',#89203,1.); +#89203 = DIRECTION('',(1.,0.E+000)); +#89204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89205 = PCURVE('',#89206,#89211); +#89206 = PLANE('',#89207); +#89207 = AXIS2_PLACEMENT_3D('',#89208,#89209,#89210); +#89208 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); +#89209 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89210 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89211 = DEFINITIONAL_REPRESENTATION('',(#89212),#89216); +#89212 = LINE('',#89213,#89214); +#89213 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89214 = VECTOR('',#89215,1.); +#89215 = DIRECTION('',(-1.,0.E+000)); +#89216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89217 = ORIENTED_EDGE('',*,*,#89218,.F.); +#89218 = EDGE_CURVE('',#89219,#89189,#89221,.T.); +#89219 = VERTEX_POINT('',#89220); +#89220 = CARTESIAN_POINT('',(3.65,10.,0.75)); +#89221 = SURFACE_CURVE('',#89222,(#89226,#89233),.PCURVE_S1.); +#89222 = LINE('',#89223,#89224); +#89223 = CARTESIAN_POINT('',(3.85,10.,0.75)); +#89224 = VECTOR('',#89225,1.); +#89225 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89226 = PCURVE('',#88852,#89227); +#89227 = DEFINITIONAL_REPRESENTATION('',(#89228),#89232); +#89228 = LINE('',#89229,#89230); +#89229 = CARTESIAN_POINT('',(0.65,3.85)); +#89230 = VECTOR('',#89231,1.); +#89231 = DIRECTION('',(0.E+000,1.)); +#89232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89233 = PCURVE('',#89234,#89239); +#89234 = PLANE('',#89235); +#89235 = AXIS2_PLACEMENT_3D('',#89236,#89237,#89238); +#89236 = CARTESIAN_POINT('',(3.85,10.527847992439,0.75)); +#89237 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89238 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89239 = DEFINITIONAL_REPRESENTATION('',(#89240),#89244); +#89240 = LINE('',#89241,#89242); +#89241 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89242 = VECTOR('',#89243,1.); +#89243 = DIRECTION('',(-8.881784197001E-016,1.)); +#89244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89245 = ORIENTED_EDGE('',*,*,#89246,.F.); +#89246 = EDGE_CURVE('',#89247,#89219,#89249,.T.); +#89247 = VERTEX_POINT('',#89248); +#89248 = CARTESIAN_POINT('',(3.65,10.,0.65)); +#89249 = SURFACE_CURVE('',#89250,(#89254,#89261),.PCURVE_S1.); +#89250 = LINE('',#89251,#89252); +#89251 = CARTESIAN_POINT('',(3.65,10.,0.65)); +#89252 = VECTOR('',#89253,1.); +#89253 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89254 = PCURVE('',#88852,#89255); +#89255 = DEFINITIONAL_REPRESENTATION('',(#89256),#89260); +#89256 = LINE('',#89257,#89258); +#89257 = CARTESIAN_POINT('',(0.75,3.65)); +#89258 = VECTOR('',#89259,1.); +#89259 = DIRECTION('',(-1.,0.E+000)); +#89260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89261 = PCURVE('',#89262,#89267); +#89262 = PLANE('',#89263); +#89263 = AXIS2_PLACEMENT_3D('',#89264,#89265,#89266); +#89264 = CARTESIAN_POINT('',(3.65,10.527847992439,0.65)); +#89265 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89266 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89267 = DEFINITIONAL_REPRESENTATION('',(#89268),#89272); +#89268 = LINE('',#89269,#89270); +#89269 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89270 = VECTOR('',#89271,1.); +#89271 = DIRECTION('',(-1.,0.E+000)); +#89272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89273 = ORIENTED_EDGE('',*,*,#89274,.F.); +#89274 = EDGE_CURVE('',#89191,#89247,#89275,.T.); +#89275 = SURFACE_CURVE('',#89276,(#89280,#89287),.PCURVE_S1.); #89276 = LINE('',#89277,#89278); -#89277 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#89277 = CARTESIAN_POINT('',(3.85,10.,0.65)); #89278 = VECTOR('',#89279,1.); -#89279 = DIRECTION('',(1.,0.E+000)); -#89280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89281 = ORIENTED_EDGE('',*,*,#89282,.F.); -#89282 = EDGE_CURVE('',#89199,#89255,#89283,.T.); -#89283 = SURFACE_CURVE('',#89284,(#89288,#89295),.PCURVE_S1.); -#89284 = LINE('',#89285,#89286); -#89285 = CARTESIAN_POINT('',(1.35,0.E+000,0.75)); -#89286 = VECTOR('',#89287,1.); -#89287 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89288 = PCURVE('',#88404,#89289); -#89289 = DEFINITIONAL_REPRESENTATION('',(#89290),#89294); -#89290 = LINE('',#89291,#89292); -#89291 = CARTESIAN_POINT('',(-0.65,1.35)); -#89292 = VECTOR('',#89293,1.); -#89293 = DIRECTION('',(0.E+000,-1.)); -#89294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89295 = PCURVE('',#89296,#89301); -#89296 = PLANE('',#89297); -#89297 = AXIS2_PLACEMENT_3D('',#89298,#89299,#89300); -#89298 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.75)); -#89299 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89300 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89301 = DEFINITIONAL_REPRESENTATION('',(#89302),#89306); -#89302 = LINE('',#89303,#89304); -#89303 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89304 = VECTOR('',#89305,1.); -#89305 = DIRECTION('',(0.E+000,-1.)); -#89306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89307 = FACE_BOUND('',#89308,.T.); -#89308 = EDGE_LOOP('',(#89309,#89339,#89367,#89390)); -#89309 = ORIENTED_EDGE('',*,*,#89310,.T.); -#89310 = EDGE_CURVE('',#89311,#89313,#89315,.T.); -#89311 = VERTEX_POINT('',#89312); -#89312 = CARTESIAN_POINT('',(9.8,0.E+000,1.2)); -#89313 = VERTEX_POINT('',#89314); -#89314 = CARTESIAN_POINT('',(0.2,0.E+000,1.2)); -#89315 = SURFACE_CURVE('',#89316,(#89320,#89327),.PCURVE_S1.); -#89316 = LINE('',#89317,#89318); -#89317 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.2)); -#89318 = VECTOR('',#89319,1.); -#89319 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89320 = PCURVE('',#88404,#89321); -#89321 = DEFINITIONAL_REPRESENTATION('',(#89322),#89326); -#89322 = LINE('',#89323,#89324); -#89323 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#89324 = VECTOR('',#89325,1.); -#89325 = DIRECTION('',(0.E+000,-1.)); -#89326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89327 = PCURVE('',#89328,#89333); -#89328 = PLANE('',#89329); -#89329 = AXIS2_PLACEMENT_3D('',#89330,#89331,#89332); -#89330 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); -#89331 = DIRECTION('',(0.E+000,0.707106781187,-0.707106781187)); -#89332 = DIRECTION('',(0.E+000,0.707106781187,0.707106781187)); -#89333 = DEFINITIONAL_REPRESENTATION('',(#89334),#89338); -#89334 = LINE('',#89335,#89336); -#89335 = CARTESIAN_POINT('',(-0.282842712475,0.E+000)); -#89336 = VECTOR('',#89337,1.); -#89337 = DIRECTION('',(0.E+000,-1.)); -#89338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89339 = ORIENTED_EDGE('',*,*,#89340,.T.); -#89340 = EDGE_CURVE('',#89313,#89341,#89343,.T.); -#89341 = VERTEX_POINT('',#89342); -#89342 = CARTESIAN_POINT('',(0.2,-8.673617379884E-016,0.E+000)); -#89343 = SURFACE_CURVE('',#89344,(#89348,#89355),.PCURVE_S1.); -#89344 = LINE('',#89345,#89346); -#89345 = CARTESIAN_POINT('',(0.2,0.E+000,1.4)); -#89346 = VECTOR('',#89347,1.); -#89347 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89348 = PCURVE('',#88404,#89349); -#89349 = DEFINITIONAL_REPRESENTATION('',(#89350),#89354); -#89350 = LINE('',#89351,#89352); -#89351 = CARTESIAN_POINT('',(0.E+000,0.2)); -#89352 = VECTOR('',#89353,1.); -#89353 = DIRECTION('',(-1.,0.E+000)); -#89354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89355 = PCURVE('',#89356,#89361); -#89356 = PLANE('',#89357); -#89357 = AXIS2_PLACEMENT_3D('',#89358,#89359,#89360); -#89358 = CARTESIAN_POINT('',(0.2,0.E+000,1.4)); -#89359 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#89360 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#89361 = DEFINITIONAL_REPRESENTATION('',(#89362),#89366); -#89362 = LINE('',#89363,#89364); -#89363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#89364 = VECTOR('',#89365,1.); -#89365 = DIRECTION('',(0.E+000,-1.)); -#89366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89367 = ORIENTED_EDGE('',*,*,#89368,.T.); -#89368 = EDGE_CURVE('',#89341,#89369,#89371,.T.); -#89369 = VERTEX_POINT('',#89370); -#89370 = CARTESIAN_POINT('',(9.8,0.E+000,0.E+000)); -#89371 = SURFACE_CURVE('',#89372,(#89376,#89383),.PCURVE_S1.); -#89372 = LINE('',#89373,#89374); -#89373 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#89374 = VECTOR('',#89375,1.); -#89375 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89376 = PCURVE('',#88404,#89377); -#89377 = DEFINITIONAL_REPRESENTATION('',(#89378),#89382); -#89378 = LINE('',#89379,#89380); -#89379 = CARTESIAN_POINT('',(-1.4,0.E+000)); -#89380 = VECTOR('',#89381,1.); -#89381 = DIRECTION('',(0.E+000,1.)); -#89382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89383 = PCURVE('',#86472,#89384); -#89384 = DEFINITIONAL_REPRESENTATION('',(#89385),#89389); -#89385 = LINE('',#89386,#89387); -#89386 = CARTESIAN_POINT('',(0.E+000,-10.)); -#89387 = VECTOR('',#89388,1.); -#89388 = DIRECTION('',(-1.,0.E+000)); -#89389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89390 = ORIENTED_EDGE('',*,*,#89391,.T.); -#89391 = EDGE_CURVE('',#89369,#89311,#89392,.T.); -#89392 = SURFACE_CURVE('',#89393,(#89397,#89404),.PCURVE_S1.); -#89393 = LINE('',#89394,#89395); -#89394 = CARTESIAN_POINT('',(9.8,0.E+000,1.4)); -#89395 = VECTOR('',#89396,1.); -#89396 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89397 = PCURVE('',#88404,#89398); -#89398 = DEFINITIONAL_REPRESENTATION('',(#89399),#89403); -#89399 = LINE('',#89400,#89401); -#89400 = CARTESIAN_POINT('',(0.E+000,9.8)); -#89401 = VECTOR('',#89402,1.); -#89402 = DIRECTION('',(1.,0.E+000)); -#89403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89404 = PCURVE('',#89405,#89410); -#89405 = PLANE('',#89406); -#89406 = AXIS2_PLACEMENT_3D('',#89407,#89408,#89409); -#89407 = CARTESIAN_POINT('',(10.,0.2,1.4)); -#89408 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#89409 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#89410 = DEFINITIONAL_REPRESENTATION('',(#89411),#89415); -#89411 = LINE('',#89412,#89413); -#89412 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); -#89413 = VECTOR('',#89414,1.); -#89414 = DIRECTION('',(0.E+000,1.)); -#89415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89416 = FACE_BOUND('',#89417,.T.); -#89417 = EDGE_LOOP('',(#89418,#89448,#89476,#89504)); -#89418 = ORIENTED_EDGE('',*,*,#89419,.F.); -#89419 = EDGE_CURVE('',#89420,#89422,#89424,.T.); -#89420 = VERTEX_POINT('',#89421); -#89421 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); -#89422 = VERTEX_POINT('',#89423); -#89423 = CARTESIAN_POINT('',(5.35,0.E+000,0.65)); -#89424 = SURFACE_CURVE('',#89425,(#89429,#89436),.PCURVE_S1.); -#89425 = LINE('',#89426,#89427); -#89426 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); -#89427 = VECTOR('',#89428,1.); -#89428 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89429 = PCURVE('',#88404,#89430); -#89430 = DEFINITIONAL_REPRESENTATION('',(#89431),#89435); -#89431 = LINE('',#89432,#89433); -#89432 = CARTESIAN_POINT('',(-0.75,5.15)); -#89433 = VECTOR('',#89434,1.); -#89434 = DIRECTION('',(0.E+000,1.)); -#89435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89436 = PCURVE('',#89437,#89442); -#89437 = PLANE('',#89438); -#89438 = AXIS2_PLACEMENT_3D('',#89439,#89440,#89441); -#89439 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); -#89440 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89441 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89442 = DEFINITIONAL_REPRESENTATION('',(#89443),#89447); -#89443 = LINE('',#89444,#89445); -#89444 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89445 = VECTOR('',#89446,1.); -#89446 = DIRECTION('',(0.E+000,1.)); -#89447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89448 = ORIENTED_EDGE('',*,*,#89449,.F.); -#89449 = EDGE_CURVE('',#89450,#89420,#89452,.T.); -#89450 = VERTEX_POINT('',#89451); -#89451 = CARTESIAN_POINT('',(5.15,0.E+000,0.75)); -#89452 = SURFACE_CURVE('',#89453,(#89457,#89464),.PCURVE_S1.); -#89453 = LINE('',#89454,#89455); -#89454 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); -#89455 = VECTOR('',#89456,1.); -#89456 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89457 = PCURVE('',#88404,#89458); -#89458 = DEFINITIONAL_REPRESENTATION('',(#89459),#89463); -#89459 = LINE('',#89460,#89461); -#89460 = CARTESIAN_POINT('',(-0.75,5.15)); -#89461 = VECTOR('',#89462,1.); -#89462 = DIRECTION('',(-1.,0.E+000)); -#89463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89464 = PCURVE('',#89465,#89470); -#89465 = PLANE('',#89466); -#89466 = AXIS2_PLACEMENT_3D('',#89467,#89468,#89469); -#89467 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); -#89468 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89469 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89470 = DEFINITIONAL_REPRESENTATION('',(#89471),#89475); -#89471 = LINE('',#89472,#89473); -#89472 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#89473 = VECTOR('',#89474,1.); -#89474 = DIRECTION('',(1.,0.E+000)); -#89475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89476 = ORIENTED_EDGE('',*,*,#89477,.F.); -#89477 = EDGE_CURVE('',#89478,#89450,#89480,.T.); -#89478 = VERTEX_POINT('',#89479); -#89479 = CARTESIAN_POINT('',(5.35,0.E+000,0.75)); -#89480 = SURFACE_CURVE('',#89481,(#89485,#89492),.PCURVE_S1.); -#89481 = LINE('',#89482,#89483); -#89482 = CARTESIAN_POINT('',(5.15,0.E+000,0.75)); -#89483 = VECTOR('',#89484,1.); -#89484 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89485 = PCURVE('',#88404,#89486); -#89486 = DEFINITIONAL_REPRESENTATION('',(#89487),#89491); -#89487 = LINE('',#89488,#89489); -#89488 = CARTESIAN_POINT('',(-0.65,5.15)); -#89489 = VECTOR('',#89490,1.); -#89490 = DIRECTION('',(0.E+000,-1.)); -#89491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89492 = PCURVE('',#89493,#89498); -#89493 = PLANE('',#89494); -#89494 = AXIS2_PLACEMENT_3D('',#89495,#89496,#89497); -#89495 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.75)); -#89496 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89497 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89498 = DEFINITIONAL_REPRESENTATION('',(#89499),#89503); -#89499 = LINE('',#89500,#89501); -#89500 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89501 = VECTOR('',#89502,1.); -#89502 = DIRECTION('',(0.E+000,-1.)); -#89503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89504 = ORIENTED_EDGE('',*,*,#89505,.F.); -#89505 = EDGE_CURVE('',#89422,#89478,#89506,.T.); -#89506 = SURFACE_CURVE('',#89507,(#89511,#89518),.PCURVE_S1.); -#89507 = LINE('',#89508,#89509); -#89508 = CARTESIAN_POINT('',(5.35,0.E+000,0.65)); -#89509 = VECTOR('',#89510,1.); -#89510 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89511 = PCURVE('',#88404,#89512); -#89512 = DEFINITIONAL_REPRESENTATION('',(#89513),#89517); -#89513 = LINE('',#89514,#89515); -#89514 = CARTESIAN_POINT('',(-0.75,5.35)); -#89515 = VECTOR('',#89516,1.); -#89516 = DIRECTION('',(1.,0.E+000)); -#89517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89518 = PCURVE('',#89519,#89524); -#89519 = PLANE('',#89520); -#89520 = AXIS2_PLACEMENT_3D('',#89521,#89522,#89523); -#89521 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.65)); -#89522 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89523 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89524 = DEFINITIONAL_REPRESENTATION('',(#89525),#89529); -#89525 = LINE('',#89526,#89527); -#89526 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89527 = VECTOR('',#89528,1.); -#89528 = DIRECTION('',(1.,0.E+000)); -#89529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89530 = FACE_BOUND('',#89531,.T.); -#89531 = EDGE_LOOP('',(#89532,#89562,#89590,#89618)); -#89532 = ORIENTED_EDGE('',*,*,#89533,.F.); -#89533 = EDGE_CURVE('',#89534,#89536,#89538,.T.); -#89534 = VERTEX_POINT('',#89535); -#89535 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); -#89536 = VERTEX_POINT('',#89537); -#89537 = CARTESIAN_POINT('',(2.35,0.E+000,0.75)); -#89538 = SURFACE_CURVE('',#89539,(#89543,#89550),.PCURVE_S1.); -#89539 = LINE('',#89540,#89541); -#89540 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); -#89541 = VECTOR('',#89542,1.); -#89542 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89543 = PCURVE('',#88404,#89544); -#89544 = DEFINITIONAL_REPRESENTATION('',(#89545),#89549); -#89545 = LINE('',#89546,#89547); -#89546 = CARTESIAN_POINT('',(-0.75,2.35)); -#89547 = VECTOR('',#89548,1.); -#89548 = DIRECTION('',(1.,0.E+000)); -#89549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89550 = PCURVE('',#89551,#89556); -#89551 = PLANE('',#89552); -#89552 = AXIS2_PLACEMENT_3D('',#89553,#89554,#89555); -#89553 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); -#89554 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89555 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89556 = DEFINITIONAL_REPRESENTATION('',(#89557),#89561); -#89557 = LINE('',#89558,#89559); -#89558 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89559 = VECTOR('',#89560,1.); -#89560 = DIRECTION('',(1.,0.E+000)); -#89561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89562 = ORIENTED_EDGE('',*,*,#89563,.F.); -#89563 = EDGE_CURVE('',#89564,#89534,#89566,.T.); -#89564 = VERTEX_POINT('',#89565); -#89565 = CARTESIAN_POINT('',(2.15,0.E+000,0.65)); -#89566 = SURFACE_CURVE('',#89567,(#89571,#89578),.PCURVE_S1.); -#89567 = LINE('',#89568,#89569); -#89568 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); -#89569 = VECTOR('',#89570,1.); -#89570 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89571 = PCURVE('',#88404,#89572); -#89572 = DEFINITIONAL_REPRESENTATION('',(#89573),#89577); -#89573 = LINE('',#89574,#89575); -#89574 = CARTESIAN_POINT('',(-0.75,2.35)); -#89575 = VECTOR('',#89576,1.); -#89576 = DIRECTION('',(0.E+000,1.)); -#89577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89578 = PCURVE('',#89579,#89584); -#89579 = PLANE('',#89580); -#89580 = AXIS2_PLACEMENT_3D('',#89581,#89582,#89583); -#89581 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); -#89582 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89583 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89584 = DEFINITIONAL_REPRESENTATION('',(#89585),#89589); -#89585 = LINE('',#89586,#89587); -#89586 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89587 = VECTOR('',#89588,1.); -#89588 = DIRECTION('',(0.E+000,1.)); -#89589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89590 = ORIENTED_EDGE('',*,*,#89591,.F.); -#89591 = EDGE_CURVE('',#89592,#89564,#89594,.T.); -#89592 = VERTEX_POINT('',#89593); -#89593 = CARTESIAN_POINT('',(2.15,0.E+000,0.75)); -#89594 = SURFACE_CURVE('',#89595,(#89599,#89606),.PCURVE_S1.); -#89595 = LINE('',#89596,#89597); -#89596 = CARTESIAN_POINT('',(2.15,0.E+000,0.65)); -#89597 = VECTOR('',#89598,1.); -#89598 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89599 = PCURVE('',#88404,#89600); -#89600 = DEFINITIONAL_REPRESENTATION('',(#89601),#89605); -#89601 = LINE('',#89602,#89603); -#89602 = CARTESIAN_POINT('',(-0.75,2.15)); -#89603 = VECTOR('',#89604,1.); -#89604 = DIRECTION('',(-1.,0.E+000)); -#89605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89606 = PCURVE('',#89607,#89612); -#89607 = PLANE('',#89608); -#89608 = AXIS2_PLACEMENT_3D('',#89609,#89610,#89611); -#89609 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.65)); -#89610 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89611 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89612 = DEFINITIONAL_REPRESENTATION('',(#89613),#89617); -#89613 = LINE('',#89614,#89615); -#89614 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#89615 = VECTOR('',#89616,1.); -#89616 = DIRECTION('',(1.,0.E+000)); -#89617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89618 = ORIENTED_EDGE('',*,*,#89619,.F.); -#89619 = EDGE_CURVE('',#89536,#89592,#89620,.T.); -#89620 = SURFACE_CURVE('',#89621,(#89625,#89632),.PCURVE_S1.); -#89621 = LINE('',#89622,#89623); -#89622 = CARTESIAN_POINT('',(2.35,0.E+000,0.75)); -#89623 = VECTOR('',#89624,1.); -#89624 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89625 = PCURVE('',#88404,#89626); -#89626 = DEFINITIONAL_REPRESENTATION('',(#89627),#89631); -#89627 = LINE('',#89628,#89629); -#89628 = CARTESIAN_POINT('',(-0.65,2.35)); -#89629 = VECTOR('',#89630,1.); -#89630 = DIRECTION('',(0.E+000,-1.)); -#89631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89632 = PCURVE('',#89633,#89638); -#89633 = PLANE('',#89634); -#89634 = AXIS2_PLACEMENT_3D('',#89635,#89636,#89637); -#89635 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.75)); -#89636 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89637 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89638 = DEFINITIONAL_REPRESENTATION('',(#89639),#89643); -#89639 = LINE('',#89640,#89641); -#89640 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89641 = VECTOR('',#89642,1.); -#89642 = DIRECTION('',(0.E+000,-1.)); -#89643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89644 = FACE_BOUND('',#89645,.T.); -#89645 = EDGE_LOOP('',(#89646,#89676,#89704,#89732)); -#89646 = ORIENTED_EDGE('',*,*,#89647,.F.); -#89647 = EDGE_CURVE('',#89648,#89650,#89652,.T.); -#89648 = VERTEX_POINT('',#89649); -#89649 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); -#89650 = VERTEX_POINT('',#89651); -#89651 = CARTESIAN_POINT('',(3.35,0.E+000,0.75)); -#89652 = SURFACE_CURVE('',#89653,(#89657,#89664),.PCURVE_S1.); -#89653 = LINE('',#89654,#89655); -#89654 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); -#89655 = VECTOR('',#89656,1.); -#89656 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89657 = PCURVE('',#88404,#89658); -#89658 = DEFINITIONAL_REPRESENTATION('',(#89659),#89663); -#89659 = LINE('',#89660,#89661); -#89660 = CARTESIAN_POINT('',(-0.75,3.35)); -#89661 = VECTOR('',#89662,1.); -#89662 = DIRECTION('',(1.,0.E+000)); -#89663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89664 = PCURVE('',#89665,#89670); -#89665 = PLANE('',#89666); -#89666 = AXIS2_PLACEMENT_3D('',#89667,#89668,#89669); -#89667 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); -#89668 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89669 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89670 = DEFINITIONAL_REPRESENTATION('',(#89671),#89675); -#89671 = LINE('',#89672,#89673); -#89672 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89673 = VECTOR('',#89674,1.); -#89674 = DIRECTION('',(1.,0.E+000)); -#89675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89676 = ORIENTED_EDGE('',*,*,#89677,.F.); -#89677 = EDGE_CURVE('',#89678,#89648,#89680,.T.); -#89678 = VERTEX_POINT('',#89679); -#89679 = CARTESIAN_POINT('',(3.15,0.E+000,0.65)); -#89680 = SURFACE_CURVE('',#89681,(#89685,#89692),.PCURVE_S1.); -#89681 = LINE('',#89682,#89683); -#89682 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); -#89683 = VECTOR('',#89684,1.); -#89684 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89685 = PCURVE('',#88404,#89686); -#89686 = DEFINITIONAL_REPRESENTATION('',(#89687),#89691); -#89687 = LINE('',#89688,#89689); -#89688 = CARTESIAN_POINT('',(-0.75,3.35)); -#89689 = VECTOR('',#89690,1.); -#89690 = DIRECTION('',(0.E+000,1.)); -#89691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89692 = PCURVE('',#89693,#89698); -#89693 = PLANE('',#89694); -#89694 = AXIS2_PLACEMENT_3D('',#89695,#89696,#89697); -#89695 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); -#89696 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89697 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89698 = DEFINITIONAL_REPRESENTATION('',(#89699),#89703); -#89699 = LINE('',#89700,#89701); -#89700 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89701 = VECTOR('',#89702,1.); -#89702 = DIRECTION('',(0.E+000,1.)); -#89703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89704 = ORIENTED_EDGE('',*,*,#89705,.F.); -#89705 = EDGE_CURVE('',#89706,#89678,#89708,.T.); -#89706 = VERTEX_POINT('',#89707); -#89707 = CARTESIAN_POINT('',(3.15,0.E+000,0.75)); -#89708 = SURFACE_CURVE('',#89709,(#89713,#89720),.PCURVE_S1.); -#89709 = LINE('',#89710,#89711); -#89710 = CARTESIAN_POINT('',(3.15,0.E+000,0.65)); -#89711 = VECTOR('',#89712,1.); -#89712 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89713 = PCURVE('',#88404,#89714); -#89714 = DEFINITIONAL_REPRESENTATION('',(#89715),#89719); -#89715 = LINE('',#89716,#89717); -#89716 = CARTESIAN_POINT('',(-0.75,3.15)); -#89717 = VECTOR('',#89718,1.); -#89718 = DIRECTION('',(-1.,0.E+000)); -#89719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89720 = PCURVE('',#89721,#89726); -#89721 = PLANE('',#89722); -#89722 = AXIS2_PLACEMENT_3D('',#89723,#89724,#89725); -#89723 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.65)); -#89724 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89725 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89726 = DEFINITIONAL_REPRESENTATION('',(#89727),#89731); -#89727 = LINE('',#89728,#89729); -#89728 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#89729 = VECTOR('',#89730,1.); -#89730 = DIRECTION('',(1.,0.E+000)); -#89731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89732 = ORIENTED_EDGE('',*,*,#89733,.F.); -#89733 = EDGE_CURVE('',#89650,#89706,#89734,.T.); -#89734 = SURFACE_CURVE('',#89735,(#89739,#89746),.PCURVE_S1.); -#89735 = LINE('',#89736,#89737); -#89736 = CARTESIAN_POINT('',(3.35,0.E+000,0.75)); -#89737 = VECTOR('',#89738,1.); -#89738 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89739 = PCURVE('',#88404,#89740); -#89740 = DEFINITIONAL_REPRESENTATION('',(#89741),#89745); -#89741 = LINE('',#89742,#89743); -#89742 = CARTESIAN_POINT('',(-0.65,3.35)); -#89743 = VECTOR('',#89744,1.); -#89744 = DIRECTION('',(0.E+000,-1.)); -#89745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89746 = PCURVE('',#89747,#89752); -#89747 = PLANE('',#89748); -#89748 = AXIS2_PLACEMENT_3D('',#89749,#89750,#89751); -#89749 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.75)); -#89750 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89751 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89752 = DEFINITIONAL_REPRESENTATION('',(#89753),#89757); -#89753 = LINE('',#89754,#89755); -#89754 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89755 = VECTOR('',#89756,1.); -#89756 = DIRECTION('',(0.E+000,-1.)); -#89757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89758 = FACE_BOUND('',#89759,.T.); -#89759 = EDGE_LOOP('',(#89760,#89790,#89818,#89846)); -#89760 = ORIENTED_EDGE('',*,*,#89761,.F.); -#89761 = EDGE_CURVE('',#89762,#89764,#89766,.T.); -#89762 = VERTEX_POINT('',#89763); -#89763 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); -#89764 = VERTEX_POINT('',#89765); -#89765 = CARTESIAN_POINT('',(4.35,0.E+000,0.75)); -#89766 = SURFACE_CURVE('',#89767,(#89771,#89778),.PCURVE_S1.); -#89767 = LINE('',#89768,#89769); -#89768 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); -#89769 = VECTOR('',#89770,1.); -#89770 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89771 = PCURVE('',#88404,#89772); -#89772 = DEFINITIONAL_REPRESENTATION('',(#89773),#89777); -#89773 = LINE('',#89774,#89775); -#89774 = CARTESIAN_POINT('',(-0.75,4.35)); -#89775 = VECTOR('',#89776,1.); -#89776 = DIRECTION('',(1.,0.E+000)); -#89777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89778 = PCURVE('',#89779,#89784); -#89779 = PLANE('',#89780); -#89780 = AXIS2_PLACEMENT_3D('',#89781,#89782,#89783); -#89781 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); -#89782 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89783 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89784 = DEFINITIONAL_REPRESENTATION('',(#89785),#89789); -#89785 = LINE('',#89786,#89787); -#89786 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89787 = VECTOR('',#89788,1.); -#89788 = DIRECTION('',(1.,0.E+000)); -#89789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89790 = ORIENTED_EDGE('',*,*,#89791,.F.); -#89791 = EDGE_CURVE('',#89792,#89762,#89794,.T.); -#89792 = VERTEX_POINT('',#89793); -#89793 = CARTESIAN_POINT('',(4.15,0.E+000,0.65)); -#89794 = SURFACE_CURVE('',#89795,(#89799,#89806),.PCURVE_S1.); -#89795 = LINE('',#89796,#89797); -#89796 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); -#89797 = VECTOR('',#89798,1.); -#89798 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89799 = PCURVE('',#88404,#89800); -#89800 = DEFINITIONAL_REPRESENTATION('',(#89801),#89805); -#89801 = LINE('',#89802,#89803); -#89802 = CARTESIAN_POINT('',(-0.75,4.35)); -#89803 = VECTOR('',#89804,1.); -#89804 = DIRECTION('',(0.E+000,1.)); -#89805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89806 = PCURVE('',#89807,#89812); -#89807 = PLANE('',#89808); -#89808 = AXIS2_PLACEMENT_3D('',#89809,#89810,#89811); -#89809 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); -#89810 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89811 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89812 = DEFINITIONAL_REPRESENTATION('',(#89813),#89817); -#89813 = LINE('',#89814,#89815); -#89814 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89815 = VECTOR('',#89816,1.); -#89816 = DIRECTION('',(0.E+000,1.)); -#89817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89818 = ORIENTED_EDGE('',*,*,#89819,.F.); -#89819 = EDGE_CURVE('',#89820,#89792,#89822,.T.); -#89820 = VERTEX_POINT('',#89821); -#89821 = CARTESIAN_POINT('',(4.15,0.E+000,0.75)); -#89822 = SURFACE_CURVE('',#89823,(#89827,#89834),.PCURVE_S1.); -#89823 = LINE('',#89824,#89825); -#89824 = CARTESIAN_POINT('',(4.15,0.E+000,0.65)); -#89825 = VECTOR('',#89826,1.); -#89826 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89827 = PCURVE('',#88404,#89828); -#89828 = DEFINITIONAL_REPRESENTATION('',(#89829),#89833); -#89829 = LINE('',#89830,#89831); -#89830 = CARTESIAN_POINT('',(-0.75,4.15)); -#89831 = VECTOR('',#89832,1.); -#89832 = DIRECTION('',(-1.,0.E+000)); -#89833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89834 = PCURVE('',#89835,#89840); -#89835 = PLANE('',#89836); -#89836 = AXIS2_PLACEMENT_3D('',#89837,#89838,#89839); -#89837 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.65)); -#89838 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89839 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89840 = DEFINITIONAL_REPRESENTATION('',(#89841),#89845); -#89841 = LINE('',#89842,#89843); -#89842 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#89843 = VECTOR('',#89844,1.); -#89844 = DIRECTION('',(1.,0.E+000)); -#89845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89846 = ORIENTED_EDGE('',*,*,#89847,.F.); -#89847 = EDGE_CURVE('',#89764,#89820,#89848,.T.); -#89848 = SURFACE_CURVE('',#89849,(#89853,#89860),.PCURVE_S1.); -#89849 = LINE('',#89850,#89851); -#89850 = CARTESIAN_POINT('',(4.35,0.E+000,0.75)); -#89851 = VECTOR('',#89852,1.); -#89852 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89853 = PCURVE('',#88404,#89854); -#89854 = DEFINITIONAL_REPRESENTATION('',(#89855),#89859); -#89855 = LINE('',#89856,#89857); -#89856 = CARTESIAN_POINT('',(-0.65,4.35)); -#89857 = VECTOR('',#89858,1.); -#89858 = DIRECTION('',(0.E+000,-1.)); -#89859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89860 = PCURVE('',#89861,#89866); -#89861 = PLANE('',#89862); -#89862 = AXIS2_PLACEMENT_3D('',#89863,#89864,#89865); -#89863 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.75)); -#89864 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89865 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89866 = DEFINITIONAL_REPRESENTATION('',(#89867),#89871); -#89867 = LINE('',#89868,#89869); -#89868 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89869 = VECTOR('',#89870,1.); -#89870 = DIRECTION('',(0.E+000,-1.)); -#89871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89872 = FACE_BOUND('',#89873,.T.); -#89873 = EDGE_LOOP('',(#89874,#89904,#89932,#89960)); -#89874 = ORIENTED_EDGE('',*,*,#89875,.F.); -#89875 = EDGE_CURVE('',#89876,#89878,#89880,.T.); -#89876 = VERTEX_POINT('',#89877); -#89877 = CARTESIAN_POINT('',(5.65,0.E+000,0.75)); -#89878 = VERTEX_POINT('',#89879); -#89879 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); -#89880 = SURFACE_CURVE('',#89881,(#89885,#89892),.PCURVE_S1.); -#89881 = LINE('',#89882,#89883); -#89882 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); -#89883 = VECTOR('',#89884,1.); -#89884 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89885 = PCURVE('',#88404,#89886); -#89886 = DEFINITIONAL_REPRESENTATION('',(#89887),#89891); -#89887 = LINE('',#89888,#89889); -#89888 = CARTESIAN_POINT('',(-0.75,5.65)); -#89889 = VECTOR('',#89890,1.); -#89890 = DIRECTION('',(-1.,0.E+000)); -#89891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89892 = PCURVE('',#89893,#89898); -#89893 = PLANE('',#89894); -#89894 = AXIS2_PLACEMENT_3D('',#89895,#89896,#89897); -#89895 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); -#89896 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89897 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89898 = DEFINITIONAL_REPRESENTATION('',(#89899),#89903); -#89899 = LINE('',#89900,#89901); -#89900 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#89901 = VECTOR('',#89902,1.); -#89902 = DIRECTION('',(1.,0.E+000)); -#89903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89904 = ORIENTED_EDGE('',*,*,#89905,.F.); -#89905 = EDGE_CURVE('',#89906,#89876,#89908,.T.); -#89906 = VERTEX_POINT('',#89907); -#89907 = CARTESIAN_POINT('',(5.85,0.E+000,0.75)); -#89908 = SURFACE_CURVE('',#89909,(#89913,#89920),.PCURVE_S1.); -#89909 = LINE('',#89910,#89911); -#89910 = CARTESIAN_POINT('',(5.65,0.E+000,0.75)); -#89911 = VECTOR('',#89912,1.); -#89912 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89913 = PCURVE('',#88404,#89914); -#89914 = DEFINITIONAL_REPRESENTATION('',(#89915),#89919); -#89915 = LINE('',#89916,#89917); -#89916 = CARTESIAN_POINT('',(-0.65,5.65)); -#89917 = VECTOR('',#89918,1.); -#89918 = DIRECTION('',(0.E+000,-1.)); -#89919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89920 = PCURVE('',#89921,#89926); -#89921 = PLANE('',#89922); -#89922 = AXIS2_PLACEMENT_3D('',#89923,#89924,#89925); -#89923 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.75)); -#89924 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#89925 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#89926 = DEFINITIONAL_REPRESENTATION('',(#89927),#89931); -#89927 = LINE('',#89928,#89929); -#89928 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#89929 = VECTOR('',#89930,1.); -#89930 = DIRECTION('',(0.E+000,-1.)); -#89931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89932 = ORIENTED_EDGE('',*,*,#89933,.F.); -#89933 = EDGE_CURVE('',#89934,#89906,#89936,.T.); -#89934 = VERTEX_POINT('',#89935); -#89935 = CARTESIAN_POINT('',(5.85,0.E+000,0.65)); -#89936 = SURFACE_CURVE('',#89937,(#89941,#89948),.PCURVE_S1.); -#89937 = LINE('',#89938,#89939); -#89938 = CARTESIAN_POINT('',(5.85,0.E+000,0.65)); -#89939 = VECTOR('',#89940,1.); -#89940 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89941 = PCURVE('',#88404,#89942); -#89942 = DEFINITIONAL_REPRESENTATION('',(#89943),#89947); -#89943 = LINE('',#89944,#89945); -#89944 = CARTESIAN_POINT('',(-0.75,5.85)); -#89945 = VECTOR('',#89946,1.); -#89946 = DIRECTION('',(1.,0.E+000)); -#89947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89948 = PCURVE('',#89949,#89954); -#89949 = PLANE('',#89950); -#89950 = AXIS2_PLACEMENT_3D('',#89951,#89952,#89953); -#89951 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.65)); -#89952 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#89953 = DIRECTION('',(0.E+000,0.E+000,1.)); -#89954 = DEFINITIONAL_REPRESENTATION('',(#89955),#89959); -#89955 = LINE('',#89956,#89957); -#89956 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#89957 = VECTOR('',#89958,1.); -#89958 = DIRECTION('',(1.,0.E+000)); -#89959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89960 = ORIENTED_EDGE('',*,*,#89961,.F.); -#89961 = EDGE_CURVE('',#89878,#89934,#89962,.T.); -#89962 = SURFACE_CURVE('',#89963,(#89967,#89974),.PCURVE_S1.); -#89963 = LINE('',#89964,#89965); -#89964 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); -#89965 = VECTOR('',#89966,1.); -#89966 = DIRECTION('',(1.,0.E+000,0.E+000)); -#89967 = PCURVE('',#88404,#89968); -#89968 = DEFINITIONAL_REPRESENTATION('',(#89969),#89973); -#89969 = LINE('',#89970,#89971); -#89970 = CARTESIAN_POINT('',(-0.75,5.65)); -#89971 = VECTOR('',#89972,1.); -#89972 = DIRECTION('',(0.E+000,1.)); -#89973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89974 = PCURVE('',#89975,#89980); -#89975 = PLANE('',#89976); -#89976 = AXIS2_PLACEMENT_3D('',#89977,#89978,#89979); -#89977 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); -#89978 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#89979 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#89980 = DEFINITIONAL_REPRESENTATION('',(#89981),#89985); -#89981 = LINE('',#89982,#89983); -#89982 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#89983 = VECTOR('',#89984,1.); -#89984 = DIRECTION('',(0.E+000,1.)); -#89985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#89986 = FACE_BOUND('',#89987,.T.); -#89987 = EDGE_LOOP('',(#89988,#90018,#90046,#90074)); -#89988 = ORIENTED_EDGE('',*,*,#89989,.F.); -#89989 = EDGE_CURVE('',#89990,#89992,#89994,.T.); -#89990 = VERTEX_POINT('',#89991); -#89991 = CARTESIAN_POINT('',(6.65,0.E+000,0.75)); -#89992 = VERTEX_POINT('',#89993); -#89993 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); -#89994 = SURFACE_CURVE('',#89995,(#89999,#90006),.PCURVE_S1.); -#89995 = LINE('',#89996,#89997); -#89996 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); -#89997 = VECTOR('',#89998,1.); -#89998 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#89999 = PCURVE('',#88404,#90000); -#90000 = DEFINITIONAL_REPRESENTATION('',(#90001),#90005); -#90001 = LINE('',#90002,#90003); -#90002 = CARTESIAN_POINT('',(-0.75,6.65)); -#90003 = VECTOR('',#90004,1.); -#90004 = DIRECTION('',(-1.,0.E+000)); -#90005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90006 = PCURVE('',#90007,#90012); -#90007 = PLANE('',#90008); -#90008 = AXIS2_PLACEMENT_3D('',#90009,#90010,#90011); -#90009 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); -#90010 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90011 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90012 = DEFINITIONAL_REPRESENTATION('',(#90013),#90017); -#90013 = LINE('',#90014,#90015); -#90014 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90015 = VECTOR('',#90016,1.); -#90016 = DIRECTION('',(1.,0.E+000)); -#90017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90018 = ORIENTED_EDGE('',*,*,#90019,.F.); -#90019 = EDGE_CURVE('',#90020,#89990,#90022,.T.); -#90020 = VERTEX_POINT('',#90021); -#90021 = CARTESIAN_POINT('',(6.85,0.E+000,0.75)); -#90022 = SURFACE_CURVE('',#90023,(#90027,#90034),.PCURVE_S1.); -#90023 = LINE('',#90024,#90025); -#90024 = CARTESIAN_POINT('',(6.65,0.E+000,0.75)); -#90025 = VECTOR('',#90026,1.); -#90026 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90027 = PCURVE('',#88404,#90028); -#90028 = DEFINITIONAL_REPRESENTATION('',(#90029),#90033); -#90029 = LINE('',#90030,#90031); -#90030 = CARTESIAN_POINT('',(-0.65,6.65)); -#90031 = VECTOR('',#90032,1.); -#90032 = DIRECTION('',(0.E+000,-1.)); -#90033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90034 = PCURVE('',#90035,#90040); -#90035 = PLANE('',#90036); -#90036 = AXIS2_PLACEMENT_3D('',#90037,#90038,#90039); -#90037 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.75)); -#90038 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#90039 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#90040 = DEFINITIONAL_REPRESENTATION('',(#90041),#90045); -#90041 = LINE('',#90042,#90043); -#90042 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#90043 = VECTOR('',#90044,1.); -#90044 = DIRECTION('',(0.E+000,-1.)); -#90045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90046 = ORIENTED_EDGE('',*,*,#90047,.F.); -#90047 = EDGE_CURVE('',#90048,#90020,#90050,.T.); -#90048 = VERTEX_POINT('',#90049); -#90049 = CARTESIAN_POINT('',(6.85,0.E+000,0.65)); -#90050 = SURFACE_CURVE('',#90051,(#90055,#90062),.PCURVE_S1.); -#90051 = LINE('',#90052,#90053); -#90052 = CARTESIAN_POINT('',(6.85,0.E+000,0.65)); -#90053 = VECTOR('',#90054,1.); -#90054 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90055 = PCURVE('',#88404,#90056); -#90056 = DEFINITIONAL_REPRESENTATION('',(#90057),#90061); -#90057 = LINE('',#90058,#90059); -#90058 = CARTESIAN_POINT('',(-0.75,6.85)); -#90059 = VECTOR('',#90060,1.); -#90060 = DIRECTION('',(1.,0.E+000)); -#90061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90062 = PCURVE('',#90063,#90068); -#90063 = PLANE('',#90064); -#90064 = AXIS2_PLACEMENT_3D('',#90065,#90066,#90067); -#90065 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.65)); -#90066 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90067 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90068 = DEFINITIONAL_REPRESENTATION('',(#90069),#90073); -#90069 = LINE('',#90070,#90071); -#90070 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90071 = VECTOR('',#90072,1.); -#90072 = DIRECTION('',(1.,0.E+000)); -#90073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90074 = ORIENTED_EDGE('',*,*,#90075,.F.); -#90075 = EDGE_CURVE('',#89992,#90048,#90076,.T.); -#90076 = SURFACE_CURVE('',#90077,(#90081,#90088),.PCURVE_S1.); -#90077 = LINE('',#90078,#90079); -#90078 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); -#90079 = VECTOR('',#90080,1.); -#90080 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90081 = PCURVE('',#88404,#90082); -#90082 = DEFINITIONAL_REPRESENTATION('',(#90083),#90087); -#90083 = LINE('',#90084,#90085); -#90084 = CARTESIAN_POINT('',(-0.75,6.65)); -#90085 = VECTOR('',#90086,1.); -#90086 = DIRECTION('',(0.E+000,1.)); -#90087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90088 = PCURVE('',#90089,#90094); -#90089 = PLANE('',#90090); -#90090 = AXIS2_PLACEMENT_3D('',#90091,#90092,#90093); -#90091 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); -#90092 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#90093 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#90094 = DEFINITIONAL_REPRESENTATION('',(#90095),#90099); -#90095 = LINE('',#90096,#90097); -#90096 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#90097 = VECTOR('',#90098,1.); -#90098 = DIRECTION('',(0.E+000,1.)); -#90099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90100 = FACE_BOUND('',#90101,.T.); -#90101 = EDGE_LOOP('',(#90102,#90132,#90160,#90188)); -#90102 = ORIENTED_EDGE('',*,*,#90103,.F.); -#90103 = EDGE_CURVE('',#90104,#90106,#90108,.T.); -#90104 = VERTEX_POINT('',#90105); -#90105 = CARTESIAN_POINT('',(7.65,0.E+000,0.75)); -#90106 = VERTEX_POINT('',#90107); -#90107 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); -#90108 = SURFACE_CURVE('',#90109,(#90113,#90120),.PCURVE_S1.); -#90109 = LINE('',#90110,#90111); -#90110 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); -#90111 = VECTOR('',#90112,1.); -#90112 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90113 = PCURVE('',#88404,#90114); -#90114 = DEFINITIONAL_REPRESENTATION('',(#90115),#90119); -#90115 = LINE('',#90116,#90117); -#90116 = CARTESIAN_POINT('',(-0.75,7.65)); -#90117 = VECTOR('',#90118,1.); -#90118 = DIRECTION('',(-1.,0.E+000)); -#90119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90120 = PCURVE('',#90121,#90126); -#90121 = PLANE('',#90122); -#90122 = AXIS2_PLACEMENT_3D('',#90123,#90124,#90125); -#90123 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); -#90124 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90125 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90126 = DEFINITIONAL_REPRESENTATION('',(#90127),#90131); -#90127 = LINE('',#90128,#90129); -#90128 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90129 = VECTOR('',#90130,1.); -#90130 = DIRECTION('',(1.,0.E+000)); -#90131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90132 = ORIENTED_EDGE('',*,*,#90133,.F.); -#90133 = EDGE_CURVE('',#90134,#90104,#90136,.T.); -#90134 = VERTEX_POINT('',#90135); -#90135 = CARTESIAN_POINT('',(7.85,0.E+000,0.75)); -#90136 = SURFACE_CURVE('',#90137,(#90141,#90148),.PCURVE_S1.); -#90137 = LINE('',#90138,#90139); -#90138 = CARTESIAN_POINT('',(7.65,0.E+000,0.75)); -#90139 = VECTOR('',#90140,1.); -#90140 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90141 = PCURVE('',#88404,#90142); -#90142 = DEFINITIONAL_REPRESENTATION('',(#90143),#90147); -#90143 = LINE('',#90144,#90145); -#90144 = CARTESIAN_POINT('',(-0.65,7.65)); -#90145 = VECTOR('',#90146,1.); -#90146 = DIRECTION('',(0.E+000,-1.)); -#90147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90148 = PCURVE('',#90149,#90154); -#90149 = PLANE('',#90150); -#90150 = AXIS2_PLACEMENT_3D('',#90151,#90152,#90153); -#90151 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.75)); -#90152 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#90153 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#90154 = DEFINITIONAL_REPRESENTATION('',(#90155),#90159); -#90155 = LINE('',#90156,#90157); -#90156 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#90157 = VECTOR('',#90158,1.); -#90158 = DIRECTION('',(0.E+000,-1.)); -#90159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90160 = ORIENTED_EDGE('',*,*,#90161,.F.); -#90161 = EDGE_CURVE('',#90162,#90134,#90164,.T.); -#90162 = VERTEX_POINT('',#90163); -#90163 = CARTESIAN_POINT('',(7.85,0.E+000,0.65)); -#90164 = SURFACE_CURVE('',#90165,(#90169,#90176),.PCURVE_S1.); -#90165 = LINE('',#90166,#90167); -#90166 = CARTESIAN_POINT('',(7.85,0.E+000,0.65)); -#90167 = VECTOR('',#90168,1.); -#90168 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90169 = PCURVE('',#88404,#90170); -#90170 = DEFINITIONAL_REPRESENTATION('',(#90171),#90175); -#90171 = LINE('',#90172,#90173); -#90172 = CARTESIAN_POINT('',(-0.75,7.85)); -#90173 = VECTOR('',#90174,1.); -#90174 = DIRECTION('',(1.,0.E+000)); -#90175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90176 = PCURVE('',#90177,#90182); -#90177 = PLANE('',#90178); -#90178 = AXIS2_PLACEMENT_3D('',#90179,#90180,#90181); -#90179 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.65)); -#90180 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90181 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90182 = DEFINITIONAL_REPRESENTATION('',(#90183),#90187); -#90183 = LINE('',#90184,#90185); -#90184 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90185 = VECTOR('',#90186,1.); -#90186 = DIRECTION('',(1.,0.E+000)); -#90187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90188 = ORIENTED_EDGE('',*,*,#90189,.F.); -#90189 = EDGE_CURVE('',#90106,#90162,#90190,.T.); -#90190 = SURFACE_CURVE('',#90191,(#90195,#90202),.PCURVE_S1.); -#90191 = LINE('',#90192,#90193); -#90192 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); -#90193 = VECTOR('',#90194,1.); -#90194 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90195 = PCURVE('',#88404,#90196); -#90196 = DEFINITIONAL_REPRESENTATION('',(#90197),#90201); -#90197 = LINE('',#90198,#90199); -#90198 = CARTESIAN_POINT('',(-0.75,7.65)); -#90199 = VECTOR('',#90200,1.); -#90200 = DIRECTION('',(0.E+000,1.)); -#90201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90202 = PCURVE('',#90203,#90208); -#90203 = PLANE('',#90204); -#90204 = AXIS2_PLACEMENT_3D('',#90205,#90206,#90207); -#90205 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); -#90206 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#90207 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#90208 = DEFINITIONAL_REPRESENTATION('',(#90209),#90213); -#90209 = LINE('',#90210,#90211); -#90210 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#90211 = VECTOR('',#90212,1.); -#90212 = DIRECTION('',(0.E+000,1.)); -#90213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90214 = FACE_BOUND('',#90215,.T.); -#90215 = EDGE_LOOP('',(#90216,#90246,#90274,#90302)); -#90216 = ORIENTED_EDGE('',*,*,#90217,.F.); -#90217 = EDGE_CURVE('',#90218,#90220,#90222,.T.); -#90218 = VERTEX_POINT('',#90219); -#90219 = CARTESIAN_POINT('',(8.65,0.E+000,0.75)); -#90220 = VERTEX_POINT('',#90221); -#90221 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); -#90222 = SURFACE_CURVE('',#90223,(#90227,#90234),.PCURVE_S1.); -#90223 = LINE('',#90224,#90225); -#90224 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); -#90225 = VECTOR('',#90226,1.); -#90226 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90227 = PCURVE('',#88404,#90228); -#90228 = DEFINITIONAL_REPRESENTATION('',(#90229),#90233); -#90229 = LINE('',#90230,#90231); -#90230 = CARTESIAN_POINT('',(-0.75,8.65)); -#90231 = VECTOR('',#90232,1.); -#90232 = DIRECTION('',(-1.,0.E+000)); -#90233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90234 = PCURVE('',#90235,#90240); -#90235 = PLANE('',#90236); -#90236 = AXIS2_PLACEMENT_3D('',#90237,#90238,#90239); -#90237 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); -#90238 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90239 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90240 = DEFINITIONAL_REPRESENTATION('',(#90241),#90245); -#90241 = LINE('',#90242,#90243); -#90242 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90243 = VECTOR('',#90244,1.); -#90244 = DIRECTION('',(1.,0.E+000)); -#90245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90246 = ORIENTED_EDGE('',*,*,#90247,.F.); -#90247 = EDGE_CURVE('',#90248,#90218,#90250,.T.); -#90248 = VERTEX_POINT('',#90249); -#90249 = CARTESIAN_POINT('',(8.85,0.E+000,0.75)); -#90250 = SURFACE_CURVE('',#90251,(#90255,#90262),.PCURVE_S1.); -#90251 = LINE('',#90252,#90253); -#90252 = CARTESIAN_POINT('',(8.65,0.E+000,0.75)); -#90253 = VECTOR('',#90254,1.); -#90254 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90255 = PCURVE('',#88404,#90256); -#90256 = DEFINITIONAL_REPRESENTATION('',(#90257),#90261); -#90257 = LINE('',#90258,#90259); -#90258 = CARTESIAN_POINT('',(-0.65,8.65)); -#90259 = VECTOR('',#90260,1.); -#90260 = DIRECTION('',(0.E+000,-1.)); -#90261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90262 = PCURVE('',#90263,#90268); -#90263 = PLANE('',#90264); -#90264 = AXIS2_PLACEMENT_3D('',#90265,#90266,#90267); -#90265 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.75)); -#90266 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); -#90267 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#90268 = DEFINITIONAL_REPRESENTATION('',(#90269),#90273); -#90269 = LINE('',#90270,#90271); -#90270 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); -#90271 = VECTOR('',#90272,1.); -#90272 = DIRECTION('',(0.E+000,-1.)); -#90273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90274 = ORIENTED_EDGE('',*,*,#90275,.F.); -#90275 = EDGE_CURVE('',#90276,#90248,#90278,.T.); -#90276 = VERTEX_POINT('',#90277); -#90277 = CARTESIAN_POINT('',(8.85,0.E+000,0.65)); -#90278 = SURFACE_CURVE('',#90279,(#90283,#90290),.PCURVE_S1.); -#90279 = LINE('',#90280,#90281); -#90280 = CARTESIAN_POINT('',(8.85,0.E+000,0.65)); -#90281 = VECTOR('',#90282,1.); -#90282 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90283 = PCURVE('',#88404,#90284); -#90284 = DEFINITIONAL_REPRESENTATION('',(#90285),#90289); -#90285 = LINE('',#90286,#90287); -#90286 = CARTESIAN_POINT('',(-0.75,8.85)); -#90287 = VECTOR('',#90288,1.); -#90288 = DIRECTION('',(1.,0.E+000)); -#90289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90290 = PCURVE('',#90291,#90296); -#90291 = PLANE('',#90292); -#90292 = AXIS2_PLACEMENT_3D('',#90293,#90294,#90295); -#90293 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.65)); -#90294 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#90295 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90296 = DEFINITIONAL_REPRESENTATION('',(#90297),#90301); -#90297 = LINE('',#90298,#90299); -#90298 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90299 = VECTOR('',#90300,1.); -#90300 = DIRECTION('',(1.,0.E+000)); -#90301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90302 = ORIENTED_EDGE('',*,*,#90303,.F.); -#90303 = EDGE_CURVE('',#90220,#90276,#90304,.T.); -#90304 = SURFACE_CURVE('',#90305,(#90309,#90316),.PCURVE_S1.); -#90305 = LINE('',#90306,#90307); -#90306 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); -#90307 = VECTOR('',#90308,1.); -#90308 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90309 = PCURVE('',#88404,#90310); -#90310 = DEFINITIONAL_REPRESENTATION('',(#90311),#90315); -#90311 = LINE('',#90312,#90313); -#90312 = CARTESIAN_POINT('',(-0.75,8.65)); -#90313 = VECTOR('',#90314,1.); -#90314 = DIRECTION('',(0.E+000,1.)); -#90315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90316 = PCURVE('',#90317,#90322); -#90317 = PLANE('',#90318); -#90318 = AXIS2_PLACEMENT_3D('',#90319,#90320,#90321); -#90319 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); -#90320 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); -#90321 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); -#90322 = DEFINITIONAL_REPRESENTATION('',(#90323),#90327); -#90323 = LINE('',#90324,#90325); -#90324 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); -#90325 = VECTOR('',#90326,1.); -#90326 = DIRECTION('',(0.E+000,1.)); -#90327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90328 = ADVANCED_FACE('',(#90329,#90448,#90562,#90676,#90790,#90904, - #91018,#91132,#91246,#91360,#91474,#91588,#91702,#91816,#91930, - #92044,#92158),#90343,.F.); -#90329 = FACE_BOUND('',#90330,.T.); -#90330 = EDGE_LOOP('',(#90331,#90366,#90394,#90422)); -#90331 = ORIENTED_EDGE('',*,*,#90332,.T.); -#90332 = EDGE_CURVE('',#90333,#90335,#90337,.T.); -#90333 = VERTEX_POINT('',#90334); -#90334 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.75)); -#90335 = VERTEX_POINT('',#90336); -#90336 = CARTESIAN_POINT('',(0.E+000,8.65,0.65)); -#90337 = SURFACE_CURVE('',#90338,(#90342,#90354),.PCURVE_S1.); -#90338 = LINE('',#90339,#90340); -#90339 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.65)); -#90340 = VECTOR('',#90341,1.); -#90341 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90342 = PCURVE('',#90343,#90348); -#90343 = PLANE('',#90344); -#90344 = AXIS2_PLACEMENT_3D('',#90345,#90346,#90347); -#90345 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.4)); -#90346 = DIRECTION('',(1.,0.E+000,0.E+000)); -#90347 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90348 = DEFINITIONAL_REPRESENTATION('',(#90349),#90353); -#90349 = LINE('',#90350,#90351); -#90350 = CARTESIAN_POINT('',(0.75,8.65)); -#90351 = VECTOR('',#90352,1.); -#90352 = DIRECTION('',(1.,0.E+000)); -#90353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90354 = PCURVE('',#90355,#90360); -#90355 = PLANE('',#90356); -#90356 = AXIS2_PLACEMENT_3D('',#90357,#90358,#90359); -#90357 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); -#90358 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90359 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90360 = DEFINITIONAL_REPRESENTATION('',(#90361),#90365); -#90361 = LINE('',#90362,#90363); -#90362 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90363 = VECTOR('',#90364,1.); -#90364 = DIRECTION('',(1.,0.E+000)); -#90365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90366 = ORIENTED_EDGE('',*,*,#90367,.T.); -#90367 = EDGE_CURVE('',#90335,#90368,#90370,.T.); -#90368 = VERTEX_POINT('',#90369); -#90369 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.65)); -#90370 = SURFACE_CURVE('',#90371,(#90375,#90382),.PCURVE_S1.); -#90371 = LINE('',#90372,#90373); -#90372 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.65)); -#90373 = VECTOR('',#90374,1.); -#90374 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90375 = PCURVE('',#90343,#90376); -#90376 = DEFINITIONAL_REPRESENTATION('',(#90377),#90381); -#90377 = LINE('',#90378,#90379); -#90378 = CARTESIAN_POINT('',(0.75,8.65)); -#90379 = VECTOR('',#90380,1.); -#90380 = DIRECTION('',(0.E+000,1.)); -#90381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90382 = PCURVE('',#90383,#90388); -#90383 = PLANE('',#90384); -#90384 = AXIS2_PLACEMENT_3D('',#90385,#90386,#90387); -#90385 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); -#90386 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90387 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90388 = DEFINITIONAL_REPRESENTATION('',(#90389),#90393); -#90389 = LINE('',#90390,#90391); -#90390 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90391 = VECTOR('',#90392,1.); -#90392 = DIRECTION('',(4.440892098501E-016,1.)); -#90393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90394 = ORIENTED_EDGE('',*,*,#90395,.T.); -#90395 = EDGE_CURVE('',#90368,#90396,#90398,.T.); -#90396 = VERTEX_POINT('',#90397); -#90397 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.75)); -#90398 = SURFACE_CURVE('',#90399,(#90403,#90410),.PCURVE_S1.); -#90399 = LINE('',#90400,#90401); -#90400 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.65)); -#90401 = VECTOR('',#90402,1.); -#90402 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90403 = PCURVE('',#90343,#90404); -#90404 = DEFINITIONAL_REPRESENTATION('',(#90405),#90409); -#90405 = LINE('',#90406,#90407); -#90406 = CARTESIAN_POINT('',(0.75,8.85)); -#90407 = VECTOR('',#90408,1.); -#90408 = DIRECTION('',(-1.,0.E+000)); -#90409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90410 = PCURVE('',#90411,#90416); -#90411 = PLANE('',#90412); -#90412 = AXIS2_PLACEMENT_3D('',#90413,#90414,#90415); -#90413 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.65)); -#90414 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90415 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90416 = DEFINITIONAL_REPRESENTATION('',(#90417),#90421); -#90417 = LINE('',#90418,#90419); -#90418 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90419 = VECTOR('',#90420,1.); -#90420 = DIRECTION('',(1.,0.E+000)); -#90421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90422 = ORIENTED_EDGE('',*,*,#90423,.T.); -#90423 = EDGE_CURVE('',#90396,#90333,#90424,.T.); -#90424 = SURFACE_CURVE('',#90425,(#90429,#90436),.PCURVE_S1.); -#90425 = LINE('',#90426,#90427); -#90426 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.75)); -#90427 = VECTOR('',#90428,1.); -#90428 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90429 = PCURVE('',#90343,#90430); -#90430 = DEFINITIONAL_REPRESENTATION('',(#90431),#90435); -#90431 = LINE('',#90432,#90433); -#90432 = CARTESIAN_POINT('',(0.65,8.65)); -#90433 = VECTOR('',#90434,1.); -#90434 = DIRECTION('',(0.E+000,-1.)); -#90435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90436 = PCURVE('',#90437,#90442); -#90437 = PLANE('',#90438); -#90438 = AXIS2_PLACEMENT_3D('',#90439,#90440,#90441); -#90439 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.75)); -#90440 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#90441 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#90442 = DEFINITIONAL_REPRESENTATION('',(#90443),#90447); -#90443 = LINE('',#90444,#90445); -#90444 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#90445 = VECTOR('',#90446,1.); -#90446 = DIRECTION('',(4.440892098501E-016,-1.)); -#90447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90448 = FACE_BOUND('',#90449,.T.); -#90449 = EDGE_LOOP('',(#90450,#90480,#90508,#90536)); -#90450 = ORIENTED_EDGE('',*,*,#90451,.T.); -#90451 = EDGE_CURVE('',#90452,#90454,#90456,.T.); -#90452 = VERTEX_POINT('',#90453); -#90453 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.75)); -#90454 = VERTEX_POINT('',#90455); -#90455 = CARTESIAN_POINT('',(0.E+000,8.15,0.65)); -#90456 = SURFACE_CURVE('',#90457,(#90461,#90468),.PCURVE_S1.); -#90457 = LINE('',#90458,#90459); -#90458 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.65)); -#90459 = VECTOR('',#90460,1.); -#90460 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90461 = PCURVE('',#90343,#90462); -#90462 = DEFINITIONAL_REPRESENTATION('',(#90463),#90467); -#90463 = LINE('',#90464,#90465); -#90464 = CARTESIAN_POINT('',(0.75,8.15)); -#90465 = VECTOR('',#90466,1.); -#90466 = DIRECTION('',(1.,0.E+000)); -#90467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90468 = PCURVE('',#90469,#90474); -#90469 = PLANE('',#90470); -#90470 = AXIS2_PLACEMENT_3D('',#90471,#90472,#90473); -#90471 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); -#90472 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90473 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90474 = DEFINITIONAL_REPRESENTATION('',(#90475),#90479); -#90475 = LINE('',#90476,#90477); -#90476 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90477 = VECTOR('',#90478,1.); -#90478 = DIRECTION('',(1.,0.E+000)); -#90479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90480 = ORIENTED_EDGE('',*,*,#90481,.T.); -#90481 = EDGE_CURVE('',#90454,#90482,#90484,.T.); -#90482 = VERTEX_POINT('',#90483); -#90483 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.65)); -#90484 = SURFACE_CURVE('',#90485,(#90489,#90496),.PCURVE_S1.); -#90485 = LINE('',#90486,#90487); -#90486 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.65)); -#90487 = VECTOR('',#90488,1.); -#90488 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90489 = PCURVE('',#90343,#90490); -#90490 = DEFINITIONAL_REPRESENTATION('',(#90491),#90495); -#90491 = LINE('',#90492,#90493); -#90492 = CARTESIAN_POINT('',(0.75,8.15)); -#90493 = VECTOR('',#90494,1.); -#90494 = DIRECTION('',(0.E+000,1.)); -#90495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90496 = PCURVE('',#90497,#90502); -#90497 = PLANE('',#90498); -#90498 = AXIS2_PLACEMENT_3D('',#90499,#90500,#90501); -#90499 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); -#90500 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90501 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90502 = DEFINITIONAL_REPRESENTATION('',(#90503),#90507); -#90503 = LINE('',#90504,#90505); -#90504 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90505 = VECTOR('',#90506,1.); -#90506 = DIRECTION('',(4.440892098501E-016,1.)); -#90507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90508 = ORIENTED_EDGE('',*,*,#90509,.T.); -#90509 = EDGE_CURVE('',#90482,#90510,#90512,.T.); -#90510 = VERTEX_POINT('',#90511); -#90511 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.75)); -#90512 = SURFACE_CURVE('',#90513,(#90517,#90524),.PCURVE_S1.); -#90513 = LINE('',#90514,#90515); -#90514 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.65)); -#90515 = VECTOR('',#90516,1.); -#90516 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90517 = PCURVE('',#90343,#90518); -#90518 = DEFINITIONAL_REPRESENTATION('',(#90519),#90523); -#90519 = LINE('',#90520,#90521); -#90520 = CARTESIAN_POINT('',(0.75,8.35)); -#90521 = VECTOR('',#90522,1.); -#90522 = DIRECTION('',(-1.,0.E+000)); -#90523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90524 = PCURVE('',#90525,#90530); -#90525 = PLANE('',#90526); -#90526 = AXIS2_PLACEMENT_3D('',#90527,#90528,#90529); -#90527 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.65)); -#90528 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90529 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90530 = DEFINITIONAL_REPRESENTATION('',(#90531),#90535); -#90531 = LINE('',#90532,#90533); -#90532 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90533 = VECTOR('',#90534,1.); -#90534 = DIRECTION('',(1.,0.E+000)); -#90535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90536 = ORIENTED_EDGE('',*,*,#90537,.T.); -#90537 = EDGE_CURVE('',#90510,#90452,#90538,.T.); -#90538 = SURFACE_CURVE('',#90539,(#90543,#90550),.PCURVE_S1.); -#90539 = LINE('',#90540,#90541); -#90540 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.75)); -#90541 = VECTOR('',#90542,1.); -#90542 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90543 = PCURVE('',#90343,#90544); -#90544 = DEFINITIONAL_REPRESENTATION('',(#90545),#90549); -#90545 = LINE('',#90546,#90547); -#90546 = CARTESIAN_POINT('',(0.65,8.15)); -#90547 = VECTOR('',#90548,1.); -#90548 = DIRECTION('',(0.E+000,-1.)); -#90549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90550 = PCURVE('',#90551,#90556); -#90551 = PLANE('',#90552); -#90552 = AXIS2_PLACEMENT_3D('',#90553,#90554,#90555); -#90553 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.75)); -#90554 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#90555 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#90556 = DEFINITIONAL_REPRESENTATION('',(#90557),#90561); -#90557 = LINE('',#90558,#90559); -#90558 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#90559 = VECTOR('',#90560,1.); -#90560 = DIRECTION('',(4.440892098501E-016,-1.)); -#90561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90562 = FACE_BOUND('',#90563,.T.); -#90563 = EDGE_LOOP('',(#90564,#90594,#90622,#90650)); -#90564 = ORIENTED_EDGE('',*,*,#90565,.T.); -#90565 = EDGE_CURVE('',#90566,#90568,#90570,.T.); -#90566 = VERTEX_POINT('',#90567); -#90567 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.75)); -#90568 = VERTEX_POINT('',#90569); -#90569 = CARTESIAN_POINT('',(0.E+000,7.65,0.65)); -#90570 = SURFACE_CURVE('',#90571,(#90575,#90582),.PCURVE_S1.); -#90571 = LINE('',#90572,#90573); -#90572 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.65)); -#90573 = VECTOR('',#90574,1.); -#90574 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90575 = PCURVE('',#90343,#90576); -#90576 = DEFINITIONAL_REPRESENTATION('',(#90577),#90581); -#90577 = LINE('',#90578,#90579); -#90578 = CARTESIAN_POINT('',(0.75,7.65)); -#90579 = VECTOR('',#90580,1.); -#90580 = DIRECTION('',(1.,0.E+000)); -#90581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90582 = PCURVE('',#90583,#90588); -#90583 = PLANE('',#90584); -#90584 = AXIS2_PLACEMENT_3D('',#90585,#90586,#90587); -#90585 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); -#90586 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90587 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90588 = DEFINITIONAL_REPRESENTATION('',(#90589),#90593); -#90589 = LINE('',#90590,#90591); -#90590 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90591 = VECTOR('',#90592,1.); -#90592 = DIRECTION('',(1.,0.E+000)); -#90593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90594 = ORIENTED_EDGE('',*,*,#90595,.T.); -#90595 = EDGE_CURVE('',#90568,#90596,#90598,.T.); -#90596 = VERTEX_POINT('',#90597); -#90597 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.65)); -#90598 = SURFACE_CURVE('',#90599,(#90603,#90610),.PCURVE_S1.); -#90599 = LINE('',#90600,#90601); -#90600 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.65)); -#90601 = VECTOR('',#90602,1.); -#90602 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90603 = PCURVE('',#90343,#90604); -#90604 = DEFINITIONAL_REPRESENTATION('',(#90605),#90609); -#90605 = LINE('',#90606,#90607); -#90606 = CARTESIAN_POINT('',(0.75,7.65)); -#90607 = VECTOR('',#90608,1.); -#90608 = DIRECTION('',(0.E+000,1.)); -#90609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90610 = PCURVE('',#90611,#90616); -#90611 = PLANE('',#90612); -#90612 = AXIS2_PLACEMENT_3D('',#90613,#90614,#90615); -#90613 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); -#90614 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90615 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90616 = DEFINITIONAL_REPRESENTATION('',(#90617),#90621); -#90617 = LINE('',#90618,#90619); -#90618 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90619 = VECTOR('',#90620,1.); -#90620 = DIRECTION('',(4.440892098501E-016,1.)); -#90621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90622 = ORIENTED_EDGE('',*,*,#90623,.T.); -#90623 = EDGE_CURVE('',#90596,#90624,#90626,.T.); -#90624 = VERTEX_POINT('',#90625); -#90625 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.75)); -#90626 = SURFACE_CURVE('',#90627,(#90631,#90638),.PCURVE_S1.); -#90627 = LINE('',#90628,#90629); -#90628 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.65)); -#90629 = VECTOR('',#90630,1.); -#90630 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90631 = PCURVE('',#90343,#90632); -#90632 = DEFINITIONAL_REPRESENTATION('',(#90633),#90637); -#90633 = LINE('',#90634,#90635); -#90634 = CARTESIAN_POINT('',(0.75,7.85)); -#90635 = VECTOR('',#90636,1.); -#90636 = DIRECTION('',(-1.,0.E+000)); -#90637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90638 = PCURVE('',#90639,#90644); -#90639 = PLANE('',#90640); -#90640 = AXIS2_PLACEMENT_3D('',#90641,#90642,#90643); -#90641 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.65)); -#90642 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90643 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90644 = DEFINITIONAL_REPRESENTATION('',(#90645),#90649); -#90645 = LINE('',#90646,#90647); -#90646 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90647 = VECTOR('',#90648,1.); -#90648 = DIRECTION('',(1.,0.E+000)); -#90649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90650 = ORIENTED_EDGE('',*,*,#90651,.T.); -#90651 = EDGE_CURVE('',#90624,#90566,#90652,.T.); -#90652 = SURFACE_CURVE('',#90653,(#90657,#90664),.PCURVE_S1.); -#90653 = LINE('',#90654,#90655); -#90654 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.75)); -#90655 = VECTOR('',#90656,1.); -#90656 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90657 = PCURVE('',#90343,#90658); -#90658 = DEFINITIONAL_REPRESENTATION('',(#90659),#90663); -#90659 = LINE('',#90660,#90661); -#90660 = CARTESIAN_POINT('',(0.65,7.65)); -#90661 = VECTOR('',#90662,1.); -#90662 = DIRECTION('',(0.E+000,-1.)); -#90663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90664 = PCURVE('',#90665,#90670); -#90665 = PLANE('',#90666); -#90666 = AXIS2_PLACEMENT_3D('',#90667,#90668,#90669); -#90667 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.75)); -#90668 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#90669 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#90670 = DEFINITIONAL_REPRESENTATION('',(#90671),#90675); -#90671 = LINE('',#90672,#90673); -#90672 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#90673 = VECTOR('',#90674,1.); -#90674 = DIRECTION('',(4.440892098501E-016,-1.)); -#90675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90676 = FACE_BOUND('',#90677,.T.); -#90677 = EDGE_LOOP('',(#90678,#90708,#90736,#90764)); -#90678 = ORIENTED_EDGE('',*,*,#90679,.T.); -#90679 = EDGE_CURVE('',#90680,#90682,#90684,.T.); -#90680 = VERTEX_POINT('',#90681); -#90681 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.75)); -#90682 = VERTEX_POINT('',#90683); -#90683 = CARTESIAN_POINT('',(0.E+000,7.15,0.65)); -#90684 = SURFACE_CURVE('',#90685,(#90689,#90696),.PCURVE_S1.); -#90685 = LINE('',#90686,#90687); -#90686 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.65)); -#90687 = VECTOR('',#90688,1.); -#90688 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90689 = PCURVE('',#90343,#90690); -#90690 = DEFINITIONAL_REPRESENTATION('',(#90691),#90695); -#90691 = LINE('',#90692,#90693); -#90692 = CARTESIAN_POINT('',(0.75,7.15)); -#90693 = VECTOR('',#90694,1.); -#90694 = DIRECTION('',(1.,0.E+000)); -#90695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90696 = PCURVE('',#90697,#90702); -#90697 = PLANE('',#90698); -#90698 = AXIS2_PLACEMENT_3D('',#90699,#90700,#90701); -#90699 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); -#90700 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90701 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90702 = DEFINITIONAL_REPRESENTATION('',(#90703),#90707); -#90703 = LINE('',#90704,#90705); -#90704 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90705 = VECTOR('',#90706,1.); -#90706 = DIRECTION('',(1.,0.E+000)); -#90707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90708 = ORIENTED_EDGE('',*,*,#90709,.T.); -#90709 = EDGE_CURVE('',#90682,#90710,#90712,.T.); -#90710 = VERTEX_POINT('',#90711); -#90711 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.65)); -#90712 = SURFACE_CURVE('',#90713,(#90717,#90724),.PCURVE_S1.); -#90713 = LINE('',#90714,#90715); -#90714 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.65)); -#90715 = VECTOR('',#90716,1.); -#90716 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90717 = PCURVE('',#90343,#90718); -#90718 = DEFINITIONAL_REPRESENTATION('',(#90719),#90723); -#90719 = LINE('',#90720,#90721); -#90720 = CARTESIAN_POINT('',(0.75,7.15)); -#90721 = VECTOR('',#90722,1.); -#90722 = DIRECTION('',(0.E+000,1.)); -#90723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90724 = PCURVE('',#90725,#90730); -#90725 = PLANE('',#90726); -#90726 = AXIS2_PLACEMENT_3D('',#90727,#90728,#90729); -#90727 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); -#90728 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90729 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90730 = DEFINITIONAL_REPRESENTATION('',(#90731),#90735); -#90731 = LINE('',#90732,#90733); -#90732 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90733 = VECTOR('',#90734,1.); -#90734 = DIRECTION('',(4.440892098501E-016,1.)); -#90735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90736 = ORIENTED_EDGE('',*,*,#90737,.T.); -#90737 = EDGE_CURVE('',#90710,#90738,#90740,.T.); -#90738 = VERTEX_POINT('',#90739); -#90739 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.75)); -#90740 = SURFACE_CURVE('',#90741,(#90745,#90752),.PCURVE_S1.); -#90741 = LINE('',#90742,#90743); -#90742 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.65)); -#90743 = VECTOR('',#90744,1.); -#90744 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90745 = PCURVE('',#90343,#90746); -#90746 = DEFINITIONAL_REPRESENTATION('',(#90747),#90751); -#90747 = LINE('',#90748,#90749); -#90748 = CARTESIAN_POINT('',(0.75,7.35)); -#90749 = VECTOR('',#90750,1.); -#90750 = DIRECTION('',(-1.,0.E+000)); -#90751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90752 = PCURVE('',#90753,#90758); -#90753 = PLANE('',#90754); -#90754 = AXIS2_PLACEMENT_3D('',#90755,#90756,#90757); -#90755 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.65)); -#90756 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90757 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90758 = DEFINITIONAL_REPRESENTATION('',(#90759),#90763); -#90759 = LINE('',#90760,#90761); -#90760 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90761 = VECTOR('',#90762,1.); -#90762 = DIRECTION('',(1.,0.E+000)); -#90763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90764 = ORIENTED_EDGE('',*,*,#90765,.T.); -#90765 = EDGE_CURVE('',#90738,#90680,#90766,.T.); -#90766 = SURFACE_CURVE('',#90767,(#90771,#90778),.PCURVE_S1.); -#90767 = LINE('',#90768,#90769); -#90768 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.75)); -#90769 = VECTOR('',#90770,1.); -#90770 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90771 = PCURVE('',#90343,#90772); -#90772 = DEFINITIONAL_REPRESENTATION('',(#90773),#90777); -#90773 = LINE('',#90774,#90775); -#90774 = CARTESIAN_POINT('',(0.65,7.15)); -#90775 = VECTOR('',#90776,1.); -#90776 = DIRECTION('',(0.E+000,-1.)); -#90777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90778 = PCURVE('',#90779,#90784); -#90779 = PLANE('',#90780); -#90780 = AXIS2_PLACEMENT_3D('',#90781,#90782,#90783); -#90781 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.75)); -#90782 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#90783 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#90784 = DEFINITIONAL_REPRESENTATION('',(#90785),#90789); -#90785 = LINE('',#90786,#90787); -#90786 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#90787 = VECTOR('',#90788,1.); -#90788 = DIRECTION('',(4.440892098501E-016,-1.)); -#90789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90790 = FACE_BOUND('',#90791,.T.); -#90791 = EDGE_LOOP('',(#90792,#90822,#90850,#90878)); -#90792 = ORIENTED_EDGE('',*,*,#90793,.T.); -#90793 = EDGE_CURVE('',#90794,#90796,#90798,.T.); -#90794 = VERTEX_POINT('',#90795); -#90795 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.75)); -#90796 = VERTEX_POINT('',#90797); -#90797 = CARTESIAN_POINT('',(0.E+000,6.65,0.65)); -#90798 = SURFACE_CURVE('',#90799,(#90803,#90810),.PCURVE_S1.); -#90799 = LINE('',#90800,#90801); -#90800 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.65)); -#90801 = VECTOR('',#90802,1.); -#90802 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90803 = PCURVE('',#90343,#90804); -#90804 = DEFINITIONAL_REPRESENTATION('',(#90805),#90809); -#90805 = LINE('',#90806,#90807); -#90806 = CARTESIAN_POINT('',(0.75,6.65)); -#90807 = VECTOR('',#90808,1.); -#90808 = DIRECTION('',(1.,0.E+000)); -#90809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90810 = PCURVE('',#90811,#90816); -#90811 = PLANE('',#90812); -#90812 = AXIS2_PLACEMENT_3D('',#90813,#90814,#90815); -#90813 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); -#90814 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90815 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90816 = DEFINITIONAL_REPRESENTATION('',(#90817),#90821); -#90817 = LINE('',#90818,#90819); -#90818 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90819 = VECTOR('',#90820,1.); -#90820 = DIRECTION('',(1.,0.E+000)); -#90821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90822 = ORIENTED_EDGE('',*,*,#90823,.T.); -#90823 = EDGE_CURVE('',#90796,#90824,#90826,.T.); -#90824 = VERTEX_POINT('',#90825); -#90825 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.65)); -#90826 = SURFACE_CURVE('',#90827,(#90831,#90838),.PCURVE_S1.); -#90827 = LINE('',#90828,#90829); -#90828 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.65)); -#90829 = VECTOR('',#90830,1.); -#90830 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90831 = PCURVE('',#90343,#90832); -#90832 = DEFINITIONAL_REPRESENTATION('',(#90833),#90837); -#90833 = LINE('',#90834,#90835); -#90834 = CARTESIAN_POINT('',(0.75,6.65)); -#90835 = VECTOR('',#90836,1.); -#90836 = DIRECTION('',(0.E+000,1.)); -#90837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90838 = PCURVE('',#90839,#90844); -#90839 = PLANE('',#90840); -#90840 = AXIS2_PLACEMENT_3D('',#90841,#90842,#90843); -#90841 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); -#90842 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90843 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90844 = DEFINITIONAL_REPRESENTATION('',(#90845),#90849); -#90845 = LINE('',#90846,#90847); -#90846 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90847 = VECTOR('',#90848,1.); -#90848 = DIRECTION('',(4.440892098501E-016,1.)); -#90849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90850 = ORIENTED_EDGE('',*,*,#90851,.T.); -#90851 = EDGE_CURVE('',#90824,#90852,#90854,.T.); -#90852 = VERTEX_POINT('',#90853); -#90853 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.75)); -#90854 = SURFACE_CURVE('',#90855,(#90859,#90866),.PCURVE_S1.); -#90855 = LINE('',#90856,#90857); -#90856 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.65)); -#90857 = VECTOR('',#90858,1.); -#90858 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90859 = PCURVE('',#90343,#90860); -#90860 = DEFINITIONAL_REPRESENTATION('',(#90861),#90865); -#90861 = LINE('',#90862,#90863); -#90862 = CARTESIAN_POINT('',(0.75,6.85)); -#90863 = VECTOR('',#90864,1.); -#90864 = DIRECTION('',(-1.,0.E+000)); -#90865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90866 = PCURVE('',#90867,#90872); -#90867 = PLANE('',#90868); -#90868 = AXIS2_PLACEMENT_3D('',#90869,#90870,#90871); -#90869 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.65)); -#90870 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90871 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90872 = DEFINITIONAL_REPRESENTATION('',(#90873),#90877); -#90873 = LINE('',#90874,#90875); -#90874 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90875 = VECTOR('',#90876,1.); -#90876 = DIRECTION('',(1.,0.E+000)); -#90877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90878 = ORIENTED_EDGE('',*,*,#90879,.T.); -#90879 = EDGE_CURVE('',#90852,#90794,#90880,.T.); -#90880 = SURFACE_CURVE('',#90881,(#90885,#90892),.PCURVE_S1.); -#90881 = LINE('',#90882,#90883); -#90882 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.75)); -#90883 = VECTOR('',#90884,1.); -#90884 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90885 = PCURVE('',#90343,#90886); -#90886 = DEFINITIONAL_REPRESENTATION('',(#90887),#90891); -#90887 = LINE('',#90888,#90889); -#90888 = CARTESIAN_POINT('',(0.65,6.65)); -#90889 = VECTOR('',#90890,1.); -#90890 = DIRECTION('',(0.E+000,-1.)); -#90891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90892 = PCURVE('',#90893,#90898); -#90893 = PLANE('',#90894); -#90894 = AXIS2_PLACEMENT_3D('',#90895,#90896,#90897); -#90895 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.75)); -#90896 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#90897 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#90898 = DEFINITIONAL_REPRESENTATION('',(#90899),#90903); -#90899 = LINE('',#90900,#90901); -#90900 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#90901 = VECTOR('',#90902,1.); -#90902 = DIRECTION('',(4.440892098501E-016,-1.)); -#90903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90904 = FACE_BOUND('',#90905,.T.); -#90905 = EDGE_LOOP('',(#90906,#90936,#90964,#90992)); -#90906 = ORIENTED_EDGE('',*,*,#90907,.T.); -#90907 = EDGE_CURVE('',#90908,#90910,#90912,.T.); -#90908 = VERTEX_POINT('',#90909); -#90909 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.75)); -#90910 = VERTEX_POINT('',#90911); -#90911 = CARTESIAN_POINT('',(0.E+000,6.15,0.65)); -#90912 = SURFACE_CURVE('',#90913,(#90917,#90924),.PCURVE_S1.); -#90913 = LINE('',#90914,#90915); -#90914 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.65)); -#90915 = VECTOR('',#90916,1.); -#90916 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90917 = PCURVE('',#90343,#90918); -#90918 = DEFINITIONAL_REPRESENTATION('',(#90919),#90923); -#90919 = LINE('',#90920,#90921); -#90920 = CARTESIAN_POINT('',(0.75,6.15)); -#90921 = VECTOR('',#90922,1.); -#90922 = DIRECTION('',(1.,0.E+000)); -#90923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90924 = PCURVE('',#90925,#90930); -#90925 = PLANE('',#90926); -#90926 = AXIS2_PLACEMENT_3D('',#90927,#90928,#90929); -#90927 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); -#90928 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#90929 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#90930 = DEFINITIONAL_REPRESENTATION('',(#90931),#90935); -#90931 = LINE('',#90932,#90933); -#90932 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#90933 = VECTOR('',#90934,1.); -#90934 = DIRECTION('',(1.,0.E+000)); -#90935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90936 = ORIENTED_EDGE('',*,*,#90937,.T.); -#90937 = EDGE_CURVE('',#90910,#90938,#90940,.T.); -#90938 = VERTEX_POINT('',#90939); -#90939 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.65)); -#90940 = SURFACE_CURVE('',#90941,(#90945,#90952),.PCURVE_S1.); -#90941 = LINE('',#90942,#90943); -#90942 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.65)); -#90943 = VECTOR('',#90944,1.); -#90944 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#90945 = PCURVE('',#90343,#90946); -#90946 = DEFINITIONAL_REPRESENTATION('',(#90947),#90951); -#90947 = LINE('',#90948,#90949); -#90948 = CARTESIAN_POINT('',(0.75,6.15)); -#90949 = VECTOR('',#90950,1.); -#90950 = DIRECTION('',(0.E+000,1.)); -#90951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90952 = PCURVE('',#90953,#90958); -#90953 = PLANE('',#90954); -#90954 = AXIS2_PLACEMENT_3D('',#90955,#90956,#90957); -#90955 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); -#90956 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#90957 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#90958 = DEFINITIONAL_REPRESENTATION('',(#90959),#90963); -#90959 = LINE('',#90960,#90961); -#90960 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#90961 = VECTOR('',#90962,1.); -#90962 = DIRECTION('',(4.440892098501E-016,1.)); -#90963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90964 = ORIENTED_EDGE('',*,*,#90965,.T.); -#90965 = EDGE_CURVE('',#90938,#90966,#90968,.T.); -#90966 = VERTEX_POINT('',#90967); -#90967 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.75)); -#90968 = SURFACE_CURVE('',#90969,(#90973,#90980),.PCURVE_S1.); -#90969 = LINE('',#90970,#90971); -#90970 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.65)); -#90971 = VECTOR('',#90972,1.); -#90972 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90973 = PCURVE('',#90343,#90974); -#90974 = DEFINITIONAL_REPRESENTATION('',(#90975),#90979); -#90975 = LINE('',#90976,#90977); -#90976 = CARTESIAN_POINT('',(0.75,6.35)); -#90977 = VECTOR('',#90978,1.); -#90978 = DIRECTION('',(-1.,0.E+000)); -#90979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90980 = PCURVE('',#90981,#90986); -#90981 = PLANE('',#90982); -#90982 = AXIS2_PLACEMENT_3D('',#90983,#90984,#90985); -#90983 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.65)); -#90984 = DIRECTION('',(0.E+000,1.,0.E+000)); -#90985 = DIRECTION('',(0.E+000,0.E+000,1.)); -#90986 = DEFINITIONAL_REPRESENTATION('',(#90987),#90991); -#90987 = LINE('',#90988,#90989); -#90988 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#90989 = VECTOR('',#90990,1.); -#90990 = DIRECTION('',(1.,0.E+000)); -#90991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#90992 = ORIENTED_EDGE('',*,*,#90993,.T.); -#90993 = EDGE_CURVE('',#90966,#90908,#90994,.T.); -#90994 = SURFACE_CURVE('',#90995,(#90999,#91006),.PCURVE_S1.); -#90995 = LINE('',#90996,#90997); -#90996 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.75)); -#90997 = VECTOR('',#90998,1.); -#90998 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#90999 = PCURVE('',#90343,#91000); -#91000 = DEFINITIONAL_REPRESENTATION('',(#91001),#91005); -#91001 = LINE('',#91002,#91003); -#91002 = CARTESIAN_POINT('',(0.65,6.15)); -#91003 = VECTOR('',#91004,1.); -#91004 = DIRECTION('',(0.E+000,-1.)); -#91005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91006 = PCURVE('',#91007,#91012); -#91007 = PLANE('',#91008); -#91008 = AXIS2_PLACEMENT_3D('',#91009,#91010,#91011); -#91009 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.75)); -#91010 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91011 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91012 = DEFINITIONAL_REPRESENTATION('',(#91013),#91017); -#91013 = LINE('',#91014,#91015); -#91014 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91015 = VECTOR('',#91016,1.); -#91016 = DIRECTION('',(4.440892098501E-016,-1.)); -#91017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91018 = FACE_BOUND('',#91019,.T.); -#91019 = EDGE_LOOP('',(#91020,#91050,#91078,#91106)); -#91020 = ORIENTED_EDGE('',*,*,#91021,.T.); -#91021 = EDGE_CURVE('',#91022,#91024,#91026,.T.); -#91022 = VERTEX_POINT('',#91023); -#91023 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.75)); -#91024 = VERTEX_POINT('',#91025); -#91025 = CARTESIAN_POINT('',(0.E+000,5.65,0.65)); -#91026 = SURFACE_CURVE('',#91027,(#91031,#91038),.PCURVE_S1.); -#91027 = LINE('',#91028,#91029); -#91028 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.65)); -#91029 = VECTOR('',#91030,1.); -#91030 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91031 = PCURVE('',#90343,#91032); -#91032 = DEFINITIONAL_REPRESENTATION('',(#91033),#91037); -#91033 = LINE('',#91034,#91035); -#91034 = CARTESIAN_POINT('',(0.75,5.65)); -#91035 = VECTOR('',#91036,1.); -#91036 = DIRECTION('',(1.,0.E+000)); -#91037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91038 = PCURVE('',#91039,#91044); -#91039 = PLANE('',#91040); -#91040 = AXIS2_PLACEMENT_3D('',#91041,#91042,#91043); -#91041 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); -#91042 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91043 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91044 = DEFINITIONAL_REPRESENTATION('',(#91045),#91049); -#91045 = LINE('',#91046,#91047); -#91046 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91047 = VECTOR('',#91048,1.); -#91048 = DIRECTION('',(1.,0.E+000)); -#91049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91050 = ORIENTED_EDGE('',*,*,#91051,.T.); -#91051 = EDGE_CURVE('',#91024,#91052,#91054,.T.); -#91052 = VERTEX_POINT('',#91053); -#91053 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.65)); -#91054 = SURFACE_CURVE('',#91055,(#91059,#91066),.PCURVE_S1.); -#91055 = LINE('',#91056,#91057); -#91056 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.65)); -#91057 = VECTOR('',#91058,1.); -#91058 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91059 = PCURVE('',#90343,#91060); -#91060 = DEFINITIONAL_REPRESENTATION('',(#91061),#91065); -#91061 = LINE('',#91062,#91063); -#91062 = CARTESIAN_POINT('',(0.75,5.65)); -#91063 = VECTOR('',#91064,1.); -#91064 = DIRECTION('',(0.E+000,1.)); -#91065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91066 = PCURVE('',#91067,#91072); -#91067 = PLANE('',#91068); -#91068 = AXIS2_PLACEMENT_3D('',#91069,#91070,#91071); -#91069 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); -#91070 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91071 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91072 = DEFINITIONAL_REPRESENTATION('',(#91073),#91077); -#91073 = LINE('',#91074,#91075); -#91074 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91075 = VECTOR('',#91076,1.); -#91076 = DIRECTION('',(4.440892098501E-016,1.)); -#91077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91078 = ORIENTED_EDGE('',*,*,#91079,.T.); -#91079 = EDGE_CURVE('',#91052,#91080,#91082,.T.); -#91080 = VERTEX_POINT('',#91081); -#91081 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.75)); -#91082 = SURFACE_CURVE('',#91083,(#91087,#91094),.PCURVE_S1.); -#91083 = LINE('',#91084,#91085); -#91084 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.65)); -#91085 = VECTOR('',#91086,1.); -#91086 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91087 = PCURVE('',#90343,#91088); -#91088 = DEFINITIONAL_REPRESENTATION('',(#91089),#91093); -#91089 = LINE('',#91090,#91091); -#91090 = CARTESIAN_POINT('',(0.75,5.85)); -#91091 = VECTOR('',#91092,1.); -#91092 = DIRECTION('',(-1.,0.E+000)); -#91093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91094 = PCURVE('',#91095,#91100); -#91095 = PLANE('',#91096); -#91096 = AXIS2_PLACEMENT_3D('',#91097,#91098,#91099); -#91097 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.65)); -#91098 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91099 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91100 = DEFINITIONAL_REPRESENTATION('',(#91101),#91105); -#91101 = LINE('',#91102,#91103); -#91102 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91103 = VECTOR('',#91104,1.); -#91104 = DIRECTION('',(1.,0.E+000)); -#91105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91106 = ORIENTED_EDGE('',*,*,#91107,.T.); -#91107 = EDGE_CURVE('',#91080,#91022,#91108,.T.); -#91108 = SURFACE_CURVE('',#91109,(#91113,#91120),.PCURVE_S1.); -#91109 = LINE('',#91110,#91111); -#91110 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.75)); -#91111 = VECTOR('',#91112,1.); -#91112 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91113 = PCURVE('',#90343,#91114); -#91114 = DEFINITIONAL_REPRESENTATION('',(#91115),#91119); -#91115 = LINE('',#91116,#91117); -#91116 = CARTESIAN_POINT('',(0.65,5.65)); -#91117 = VECTOR('',#91118,1.); -#91118 = DIRECTION('',(0.E+000,-1.)); -#91119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91120 = PCURVE('',#91121,#91126); -#91121 = PLANE('',#91122); -#91122 = AXIS2_PLACEMENT_3D('',#91123,#91124,#91125); -#91123 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.75)); -#91124 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91125 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91126 = DEFINITIONAL_REPRESENTATION('',(#91127),#91131); -#91127 = LINE('',#91128,#91129); -#91128 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91129 = VECTOR('',#91130,1.); -#91130 = DIRECTION('',(4.440892098501E-016,-1.)); -#91131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91132 = FACE_BOUND('',#91133,.T.); -#91133 = EDGE_LOOP('',(#91134,#91164,#91192,#91220)); -#91134 = ORIENTED_EDGE('',*,*,#91135,.T.); -#91135 = EDGE_CURVE('',#91136,#91138,#91140,.T.); -#91136 = VERTEX_POINT('',#91137); -#91137 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.75)); -#91138 = VERTEX_POINT('',#91139); -#91139 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.65)); -#91140 = SURFACE_CURVE('',#91141,(#91145,#91152),.PCURVE_S1.); -#91141 = LINE('',#91142,#91143); -#91142 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.65)); -#91143 = VECTOR('',#91144,1.); -#91144 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91145 = PCURVE('',#90343,#91146); -#91146 = DEFINITIONAL_REPRESENTATION('',(#91147),#91151); -#91147 = LINE('',#91148,#91149); -#91148 = CARTESIAN_POINT('',(0.75,4.65)); -#91149 = VECTOR('',#91150,1.); -#91150 = DIRECTION('',(1.,0.E+000)); -#91151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91152 = PCURVE('',#91153,#91158); -#91153 = PLANE('',#91154); -#91154 = AXIS2_PLACEMENT_3D('',#91155,#91156,#91157); -#91155 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.65)); -#91156 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91157 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91158 = DEFINITIONAL_REPRESENTATION('',(#91159),#91163); -#91159 = LINE('',#91160,#91161); -#91160 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91161 = VECTOR('',#91162,1.); -#91162 = DIRECTION('',(1.,0.E+000)); -#91163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91164 = ORIENTED_EDGE('',*,*,#91165,.T.); -#91165 = EDGE_CURVE('',#91138,#91166,#91168,.T.); -#91166 = VERTEX_POINT('',#91167); -#91167 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); -#91168 = SURFACE_CURVE('',#91169,(#91173,#91180),.PCURVE_S1.); -#91169 = LINE('',#91170,#91171); -#91170 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); -#91171 = VECTOR('',#91172,1.); -#91172 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91173 = PCURVE('',#90343,#91174); -#91174 = DEFINITIONAL_REPRESENTATION('',(#91175),#91179); -#91175 = LINE('',#91176,#91177); -#91176 = CARTESIAN_POINT('',(0.75,4.85)); -#91177 = VECTOR('',#91178,1.); -#91178 = DIRECTION('',(0.E+000,1.)); -#91179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91180 = PCURVE('',#91181,#91186); -#91181 = PLANE('',#91182); -#91182 = AXIS2_PLACEMENT_3D('',#91183,#91184,#91185); -#91183 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); -#91184 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91185 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91186 = DEFINITIONAL_REPRESENTATION('',(#91187),#91191); -#91187 = LINE('',#91188,#91189); -#91188 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91189 = VECTOR('',#91190,1.); -#91190 = DIRECTION('',(4.440892098501E-016,1.)); -#91191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91192 = ORIENTED_EDGE('',*,*,#91193,.T.); -#91193 = EDGE_CURVE('',#91166,#91194,#91196,.T.); -#91194 = VERTEX_POINT('',#91195); -#91195 = CARTESIAN_POINT('',(0.E+000,4.85,0.75)); -#91196 = SURFACE_CURVE('',#91197,(#91201,#91208),.PCURVE_S1.); -#91197 = LINE('',#91198,#91199); -#91198 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); -#91199 = VECTOR('',#91200,1.); -#91200 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91201 = PCURVE('',#90343,#91202); -#91202 = DEFINITIONAL_REPRESENTATION('',(#91203),#91207); -#91203 = LINE('',#91204,#91205); -#91204 = CARTESIAN_POINT('',(0.75,4.85)); -#91205 = VECTOR('',#91206,1.); -#91206 = DIRECTION('',(-1.,0.E+000)); -#91207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91208 = PCURVE('',#91209,#91214); -#91209 = PLANE('',#91210); -#91210 = AXIS2_PLACEMENT_3D('',#91211,#91212,#91213); -#91211 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); -#91212 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91213 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91214 = DEFINITIONAL_REPRESENTATION('',(#91215),#91219); -#91215 = LINE('',#91216,#91217); -#91216 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91217 = VECTOR('',#91218,1.); -#91218 = DIRECTION('',(1.,0.E+000)); -#91219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91220 = ORIENTED_EDGE('',*,*,#91221,.T.); -#91221 = EDGE_CURVE('',#91194,#91136,#91222,.T.); -#91222 = SURFACE_CURVE('',#91223,(#91227,#91234),.PCURVE_S1.); -#91223 = LINE('',#91224,#91225); -#91224 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.75)); -#91225 = VECTOR('',#91226,1.); -#91226 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91227 = PCURVE('',#90343,#91228); -#91228 = DEFINITIONAL_REPRESENTATION('',(#91229),#91233); -#91229 = LINE('',#91230,#91231); -#91230 = CARTESIAN_POINT('',(0.65,4.85)); -#91231 = VECTOR('',#91232,1.); -#91232 = DIRECTION('',(0.E+000,-1.)); -#91233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91234 = PCURVE('',#91235,#91240); -#91235 = PLANE('',#91236); -#91236 = AXIS2_PLACEMENT_3D('',#91237,#91238,#91239); -#91237 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.75)); -#91238 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91239 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91240 = DEFINITIONAL_REPRESENTATION('',(#91241),#91245); -#91241 = LINE('',#91242,#91243); -#91242 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91243 = VECTOR('',#91244,1.); -#91244 = DIRECTION('',(4.440892098501E-016,-1.)); -#91245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91246 = FACE_BOUND('',#91247,.T.); -#91247 = EDGE_LOOP('',(#91248,#91278,#91306,#91334)); -#91248 = ORIENTED_EDGE('',*,*,#91249,.T.); -#91249 = EDGE_CURVE('',#91250,#91252,#91254,.T.); -#91250 = VERTEX_POINT('',#91251); -#91251 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.75)); -#91252 = VERTEX_POINT('',#91253); -#91253 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.65)); -#91254 = SURFACE_CURVE('',#91255,(#91259,#91266),.PCURVE_S1.); -#91255 = LINE('',#91256,#91257); -#91256 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.65)); -#91257 = VECTOR('',#91258,1.); -#91258 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91259 = PCURVE('',#90343,#91260); -#91260 = DEFINITIONAL_REPRESENTATION('',(#91261),#91265); -#91261 = LINE('',#91262,#91263); -#91262 = CARTESIAN_POINT('',(0.75,4.15)); -#91263 = VECTOR('',#91264,1.); -#91264 = DIRECTION('',(1.,0.E+000)); -#91265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91266 = PCURVE('',#91267,#91272); -#91267 = PLANE('',#91268); -#91268 = AXIS2_PLACEMENT_3D('',#91269,#91270,#91271); -#91269 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.65)); -#91270 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91271 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91272 = DEFINITIONAL_REPRESENTATION('',(#91273),#91277); -#91273 = LINE('',#91274,#91275); -#91274 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91275 = VECTOR('',#91276,1.); -#91276 = DIRECTION('',(1.,0.E+000)); -#91277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91278 = ORIENTED_EDGE('',*,*,#91279,.T.); -#91279 = EDGE_CURVE('',#91252,#91280,#91282,.T.); -#91280 = VERTEX_POINT('',#91281); -#91281 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); -#91282 = SURFACE_CURVE('',#91283,(#91287,#91294),.PCURVE_S1.); -#91283 = LINE('',#91284,#91285); -#91284 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); -#91285 = VECTOR('',#91286,1.); -#91286 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91287 = PCURVE('',#90343,#91288); -#91288 = DEFINITIONAL_REPRESENTATION('',(#91289),#91293); -#91289 = LINE('',#91290,#91291); -#91290 = CARTESIAN_POINT('',(0.75,4.35)); -#91291 = VECTOR('',#91292,1.); -#91292 = DIRECTION('',(0.E+000,1.)); -#91293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91294 = PCURVE('',#91295,#91300); -#91295 = PLANE('',#91296); -#91296 = AXIS2_PLACEMENT_3D('',#91297,#91298,#91299); -#91297 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); -#91298 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91299 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91300 = DEFINITIONAL_REPRESENTATION('',(#91301),#91305); -#91301 = LINE('',#91302,#91303); -#91302 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91303 = VECTOR('',#91304,1.); -#91304 = DIRECTION('',(4.440892098501E-016,1.)); -#91305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91306 = ORIENTED_EDGE('',*,*,#91307,.T.); -#91307 = EDGE_CURVE('',#91280,#91308,#91310,.T.); -#91308 = VERTEX_POINT('',#91309); -#91309 = CARTESIAN_POINT('',(0.E+000,4.35,0.75)); -#91310 = SURFACE_CURVE('',#91311,(#91315,#91322),.PCURVE_S1.); -#91311 = LINE('',#91312,#91313); -#91312 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); -#91313 = VECTOR('',#91314,1.); -#91314 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91315 = PCURVE('',#90343,#91316); -#91316 = DEFINITIONAL_REPRESENTATION('',(#91317),#91321); -#91317 = LINE('',#91318,#91319); -#91318 = CARTESIAN_POINT('',(0.75,4.35)); -#91319 = VECTOR('',#91320,1.); -#91320 = DIRECTION('',(-1.,0.E+000)); -#91321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91322 = PCURVE('',#91323,#91328); -#91323 = PLANE('',#91324); -#91324 = AXIS2_PLACEMENT_3D('',#91325,#91326,#91327); -#91325 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); -#91326 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91327 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91328 = DEFINITIONAL_REPRESENTATION('',(#91329),#91333); -#91329 = LINE('',#91330,#91331); -#91330 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91331 = VECTOR('',#91332,1.); -#91332 = DIRECTION('',(1.,0.E+000)); -#91333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91334 = ORIENTED_EDGE('',*,*,#91335,.T.); -#91335 = EDGE_CURVE('',#91308,#91250,#91336,.T.); -#91336 = SURFACE_CURVE('',#91337,(#91341,#91348),.PCURVE_S1.); -#91337 = LINE('',#91338,#91339); -#91338 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.75)); -#91339 = VECTOR('',#91340,1.); -#91340 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91341 = PCURVE('',#90343,#91342); -#91342 = DEFINITIONAL_REPRESENTATION('',(#91343),#91347); -#91343 = LINE('',#91344,#91345); -#91344 = CARTESIAN_POINT('',(0.65,4.35)); -#91345 = VECTOR('',#91346,1.); -#91346 = DIRECTION('',(0.E+000,-1.)); -#91347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91348 = PCURVE('',#91349,#91354); -#91349 = PLANE('',#91350); -#91350 = AXIS2_PLACEMENT_3D('',#91351,#91352,#91353); -#91351 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.75)); -#91352 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91353 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91354 = DEFINITIONAL_REPRESENTATION('',(#91355),#91359); -#91355 = LINE('',#91356,#91357); -#91356 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91357 = VECTOR('',#91358,1.); -#91358 = DIRECTION('',(4.440892098501E-016,-1.)); -#91359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91360 = FACE_BOUND('',#91361,.T.); -#91361 = EDGE_LOOP('',(#91362,#91392,#91420,#91448)); -#91362 = ORIENTED_EDGE('',*,*,#91363,.T.); -#91363 = EDGE_CURVE('',#91364,#91366,#91368,.T.); -#91364 = VERTEX_POINT('',#91365); -#91365 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.75)); -#91366 = VERTEX_POINT('',#91367); -#91367 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.65)); -#91368 = SURFACE_CURVE('',#91369,(#91373,#91380),.PCURVE_S1.); -#91369 = LINE('',#91370,#91371); -#91370 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.65)); -#91371 = VECTOR('',#91372,1.); -#91372 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91373 = PCURVE('',#90343,#91374); -#91374 = DEFINITIONAL_REPRESENTATION('',(#91375),#91379); -#91375 = LINE('',#91376,#91377); -#91376 = CARTESIAN_POINT('',(0.75,3.65)); -#91377 = VECTOR('',#91378,1.); -#91378 = DIRECTION('',(1.,0.E+000)); -#91379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91380 = PCURVE('',#91381,#91386); -#91381 = PLANE('',#91382); -#91382 = AXIS2_PLACEMENT_3D('',#91383,#91384,#91385); -#91383 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.65)); -#91384 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91385 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91386 = DEFINITIONAL_REPRESENTATION('',(#91387),#91391); -#91387 = LINE('',#91388,#91389); -#91388 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91389 = VECTOR('',#91390,1.); -#91390 = DIRECTION('',(1.,0.E+000)); -#91391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91392 = ORIENTED_EDGE('',*,*,#91393,.T.); -#91393 = EDGE_CURVE('',#91366,#91394,#91396,.T.); -#91394 = VERTEX_POINT('',#91395); -#91395 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); -#91396 = SURFACE_CURVE('',#91397,(#91401,#91408),.PCURVE_S1.); -#91397 = LINE('',#91398,#91399); -#91398 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); -#91399 = VECTOR('',#91400,1.); -#91400 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91401 = PCURVE('',#90343,#91402); -#91402 = DEFINITIONAL_REPRESENTATION('',(#91403),#91407); -#91403 = LINE('',#91404,#91405); -#91404 = CARTESIAN_POINT('',(0.75,3.85)); -#91405 = VECTOR('',#91406,1.); -#91406 = DIRECTION('',(0.E+000,1.)); -#91407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91408 = PCURVE('',#91409,#91414); -#91409 = PLANE('',#91410); -#91410 = AXIS2_PLACEMENT_3D('',#91411,#91412,#91413); -#91411 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); -#91412 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91413 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91414 = DEFINITIONAL_REPRESENTATION('',(#91415),#91419); -#91415 = LINE('',#91416,#91417); -#91416 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91417 = VECTOR('',#91418,1.); -#91418 = DIRECTION('',(4.440892098501E-016,1.)); -#91419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91420 = ORIENTED_EDGE('',*,*,#91421,.T.); -#91421 = EDGE_CURVE('',#91394,#91422,#91424,.T.); -#91422 = VERTEX_POINT('',#91423); -#91423 = CARTESIAN_POINT('',(0.E+000,3.85,0.75)); -#91424 = SURFACE_CURVE('',#91425,(#91429,#91436),.PCURVE_S1.); -#91425 = LINE('',#91426,#91427); -#91426 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); -#91427 = VECTOR('',#91428,1.); -#91428 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91429 = PCURVE('',#90343,#91430); -#91430 = DEFINITIONAL_REPRESENTATION('',(#91431),#91435); -#91431 = LINE('',#91432,#91433); -#91432 = CARTESIAN_POINT('',(0.75,3.85)); -#91433 = VECTOR('',#91434,1.); -#91434 = DIRECTION('',(-1.,0.E+000)); -#91435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91436 = PCURVE('',#91437,#91442); -#91437 = PLANE('',#91438); -#91438 = AXIS2_PLACEMENT_3D('',#91439,#91440,#91441); -#91439 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); -#91440 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91441 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91442 = DEFINITIONAL_REPRESENTATION('',(#91443),#91447); -#91443 = LINE('',#91444,#91445); -#91444 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91445 = VECTOR('',#91446,1.); -#91446 = DIRECTION('',(1.,0.E+000)); -#91447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91448 = ORIENTED_EDGE('',*,*,#91449,.T.); -#91449 = EDGE_CURVE('',#91422,#91364,#91450,.T.); -#91450 = SURFACE_CURVE('',#91451,(#91455,#91462),.PCURVE_S1.); -#91451 = LINE('',#91452,#91453); -#91452 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.75)); -#91453 = VECTOR('',#91454,1.); -#91454 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91455 = PCURVE('',#90343,#91456); -#91456 = DEFINITIONAL_REPRESENTATION('',(#91457),#91461); -#91457 = LINE('',#91458,#91459); -#91458 = CARTESIAN_POINT('',(0.65,3.85)); -#91459 = VECTOR('',#91460,1.); -#91460 = DIRECTION('',(0.E+000,-1.)); -#91461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91462 = PCURVE('',#91463,#91468); -#91463 = PLANE('',#91464); -#91464 = AXIS2_PLACEMENT_3D('',#91465,#91466,#91467); -#91465 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.75)); -#91466 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91467 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91468 = DEFINITIONAL_REPRESENTATION('',(#91469),#91473); -#91469 = LINE('',#91470,#91471); -#91470 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91471 = VECTOR('',#91472,1.); -#91472 = DIRECTION('',(4.440892098501E-016,-1.)); -#91473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91474 = FACE_BOUND('',#91475,.T.); -#91475 = EDGE_LOOP('',(#91476,#91506,#91534,#91562)); -#91476 = ORIENTED_EDGE('',*,*,#91477,.T.); -#91477 = EDGE_CURVE('',#91478,#91480,#91482,.T.); -#91478 = VERTEX_POINT('',#91479); -#91479 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.75)); -#91480 = VERTEX_POINT('',#91481); -#91481 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.65)); -#91482 = SURFACE_CURVE('',#91483,(#91487,#91494),.PCURVE_S1.); -#91483 = LINE('',#91484,#91485); -#91484 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.65)); -#91485 = VECTOR('',#91486,1.); -#91486 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91487 = PCURVE('',#90343,#91488); -#91488 = DEFINITIONAL_REPRESENTATION('',(#91489),#91493); -#91489 = LINE('',#91490,#91491); -#91490 = CARTESIAN_POINT('',(0.75,3.15)); -#91491 = VECTOR('',#91492,1.); -#91492 = DIRECTION('',(1.,0.E+000)); -#91493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91494 = PCURVE('',#91495,#91500); -#91495 = PLANE('',#91496); -#91496 = AXIS2_PLACEMENT_3D('',#91497,#91498,#91499); -#91497 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.65)); -#91498 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91499 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91500 = DEFINITIONAL_REPRESENTATION('',(#91501),#91505); -#91501 = LINE('',#91502,#91503); -#91502 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91503 = VECTOR('',#91504,1.); -#91504 = DIRECTION('',(1.,0.E+000)); -#91505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91506 = ORIENTED_EDGE('',*,*,#91507,.T.); -#91507 = EDGE_CURVE('',#91480,#91508,#91510,.T.); -#91508 = VERTEX_POINT('',#91509); -#91509 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); -#91510 = SURFACE_CURVE('',#91511,(#91515,#91522),.PCURVE_S1.); -#91511 = LINE('',#91512,#91513); -#91512 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); -#91513 = VECTOR('',#91514,1.); -#91514 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91515 = PCURVE('',#90343,#91516); -#91516 = DEFINITIONAL_REPRESENTATION('',(#91517),#91521); -#91517 = LINE('',#91518,#91519); -#91518 = CARTESIAN_POINT('',(0.75,3.35)); -#91519 = VECTOR('',#91520,1.); -#91520 = DIRECTION('',(0.E+000,1.)); -#91521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91522 = PCURVE('',#91523,#91528); -#91523 = PLANE('',#91524); -#91524 = AXIS2_PLACEMENT_3D('',#91525,#91526,#91527); -#91525 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); -#91526 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91527 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91528 = DEFINITIONAL_REPRESENTATION('',(#91529),#91533); -#91529 = LINE('',#91530,#91531); -#91530 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91531 = VECTOR('',#91532,1.); -#91532 = DIRECTION('',(4.440892098501E-016,1.)); -#91533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91534 = ORIENTED_EDGE('',*,*,#91535,.T.); -#91535 = EDGE_CURVE('',#91508,#91536,#91538,.T.); -#91536 = VERTEX_POINT('',#91537); -#91537 = CARTESIAN_POINT('',(0.E+000,3.35,0.75)); -#91538 = SURFACE_CURVE('',#91539,(#91543,#91550),.PCURVE_S1.); -#91539 = LINE('',#91540,#91541); -#91540 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); -#91541 = VECTOR('',#91542,1.); -#91542 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91543 = PCURVE('',#90343,#91544); -#91544 = DEFINITIONAL_REPRESENTATION('',(#91545),#91549); -#91545 = LINE('',#91546,#91547); -#91546 = CARTESIAN_POINT('',(0.75,3.35)); -#91547 = VECTOR('',#91548,1.); -#91548 = DIRECTION('',(-1.,0.E+000)); -#91549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91550 = PCURVE('',#91551,#91556); -#91551 = PLANE('',#91552); -#91552 = AXIS2_PLACEMENT_3D('',#91553,#91554,#91555); -#91553 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); -#91554 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91555 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91556 = DEFINITIONAL_REPRESENTATION('',(#91557),#91561); -#91557 = LINE('',#91558,#91559); -#91558 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91559 = VECTOR('',#91560,1.); -#91560 = DIRECTION('',(1.,0.E+000)); -#91561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91562 = ORIENTED_EDGE('',*,*,#91563,.T.); -#91563 = EDGE_CURVE('',#91536,#91478,#91564,.T.); -#91564 = SURFACE_CURVE('',#91565,(#91569,#91576),.PCURVE_S1.); -#91565 = LINE('',#91566,#91567); -#91566 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.75)); -#91567 = VECTOR('',#91568,1.); -#91568 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91569 = PCURVE('',#90343,#91570); -#91570 = DEFINITIONAL_REPRESENTATION('',(#91571),#91575); -#91571 = LINE('',#91572,#91573); -#91572 = CARTESIAN_POINT('',(0.65,3.35)); -#91573 = VECTOR('',#91574,1.); -#91574 = DIRECTION('',(0.E+000,-1.)); -#91575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91576 = PCURVE('',#91577,#91582); -#91577 = PLANE('',#91578); -#91578 = AXIS2_PLACEMENT_3D('',#91579,#91580,#91581); -#91579 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.75)); -#91580 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91581 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91582 = DEFINITIONAL_REPRESENTATION('',(#91583),#91587); -#91583 = LINE('',#91584,#91585); -#91584 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91585 = VECTOR('',#91586,1.); -#91586 = DIRECTION('',(4.440892098501E-016,-1.)); -#91587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91588 = FACE_BOUND('',#91589,.T.); -#91589 = EDGE_LOOP('',(#91590,#91620,#91648,#91676)); -#91590 = ORIENTED_EDGE('',*,*,#91591,.T.); -#91591 = EDGE_CURVE('',#91592,#91594,#91596,.T.); -#91592 = VERTEX_POINT('',#91593); -#91593 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.75)); -#91594 = VERTEX_POINT('',#91595); -#91595 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.65)); -#91596 = SURFACE_CURVE('',#91597,(#91601,#91608),.PCURVE_S1.); -#91597 = LINE('',#91598,#91599); -#91598 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.65)); -#91599 = VECTOR('',#91600,1.); -#91600 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91601 = PCURVE('',#90343,#91602); -#91602 = DEFINITIONAL_REPRESENTATION('',(#91603),#91607); -#91603 = LINE('',#91604,#91605); -#91604 = CARTESIAN_POINT('',(0.75,2.65)); -#91605 = VECTOR('',#91606,1.); -#91606 = DIRECTION('',(1.,0.E+000)); -#91607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91608 = PCURVE('',#91609,#91614); -#91609 = PLANE('',#91610); -#91610 = AXIS2_PLACEMENT_3D('',#91611,#91612,#91613); -#91611 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.65)); -#91612 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91613 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91614 = DEFINITIONAL_REPRESENTATION('',(#91615),#91619); -#91615 = LINE('',#91616,#91617); -#91616 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91617 = VECTOR('',#91618,1.); -#91618 = DIRECTION('',(1.,0.E+000)); -#91619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91620 = ORIENTED_EDGE('',*,*,#91621,.T.); -#91621 = EDGE_CURVE('',#91594,#91622,#91624,.T.); -#91622 = VERTEX_POINT('',#91623); -#91623 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); -#91624 = SURFACE_CURVE('',#91625,(#91629,#91636),.PCURVE_S1.); -#91625 = LINE('',#91626,#91627); -#91626 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); -#91627 = VECTOR('',#91628,1.); -#91628 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91629 = PCURVE('',#90343,#91630); -#91630 = DEFINITIONAL_REPRESENTATION('',(#91631),#91635); -#91631 = LINE('',#91632,#91633); -#91632 = CARTESIAN_POINT('',(0.75,2.85)); -#91633 = VECTOR('',#91634,1.); -#91634 = DIRECTION('',(0.E+000,1.)); -#91635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91636 = PCURVE('',#91637,#91642); -#91637 = PLANE('',#91638); -#91638 = AXIS2_PLACEMENT_3D('',#91639,#91640,#91641); -#91639 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); -#91640 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91641 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91642 = DEFINITIONAL_REPRESENTATION('',(#91643),#91647); -#91643 = LINE('',#91644,#91645); -#91644 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91645 = VECTOR('',#91646,1.); -#91646 = DIRECTION('',(4.440892098501E-016,1.)); -#91647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91648 = ORIENTED_EDGE('',*,*,#91649,.T.); -#91649 = EDGE_CURVE('',#91622,#91650,#91652,.T.); -#91650 = VERTEX_POINT('',#91651); -#91651 = CARTESIAN_POINT('',(0.E+000,2.85,0.75)); -#91652 = SURFACE_CURVE('',#91653,(#91657,#91664),.PCURVE_S1.); -#91653 = LINE('',#91654,#91655); -#91654 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); -#91655 = VECTOR('',#91656,1.); -#91656 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91657 = PCURVE('',#90343,#91658); -#91658 = DEFINITIONAL_REPRESENTATION('',(#91659),#91663); -#91659 = LINE('',#91660,#91661); -#91660 = CARTESIAN_POINT('',(0.75,2.85)); -#91661 = VECTOR('',#91662,1.); -#91662 = DIRECTION('',(-1.,0.E+000)); -#91663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91664 = PCURVE('',#91665,#91670); -#91665 = PLANE('',#91666); -#91666 = AXIS2_PLACEMENT_3D('',#91667,#91668,#91669); -#91667 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); -#91668 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91669 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91670 = DEFINITIONAL_REPRESENTATION('',(#91671),#91675); -#91671 = LINE('',#91672,#91673); -#91672 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#91673 = VECTOR('',#91674,1.); -#91674 = DIRECTION('',(1.,0.E+000)); -#91675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91676 = ORIENTED_EDGE('',*,*,#91677,.T.); -#91677 = EDGE_CURVE('',#91650,#91592,#91678,.T.); -#91678 = SURFACE_CURVE('',#91679,(#91683,#91690),.PCURVE_S1.); -#91679 = LINE('',#91680,#91681); -#91680 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.75)); -#91681 = VECTOR('',#91682,1.); -#91682 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91683 = PCURVE('',#90343,#91684); -#91684 = DEFINITIONAL_REPRESENTATION('',(#91685),#91689); -#91685 = LINE('',#91686,#91687); -#91686 = CARTESIAN_POINT('',(0.65,2.85)); -#91687 = VECTOR('',#91688,1.); -#91688 = DIRECTION('',(0.E+000,-1.)); -#91689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91690 = PCURVE('',#91691,#91696); -#91691 = PLANE('',#91692); -#91692 = AXIS2_PLACEMENT_3D('',#91693,#91694,#91695); -#91693 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.75)); -#91694 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91695 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91696 = DEFINITIONAL_REPRESENTATION('',(#91697),#91701); -#91697 = LINE('',#91698,#91699); -#91698 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91699 = VECTOR('',#91700,1.); -#91700 = DIRECTION('',(4.440892098501E-016,-1.)); -#91701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91702 = FACE_BOUND('',#91703,.T.); -#91703 = EDGE_LOOP('',(#91704,#91734,#91762,#91790)); -#91704 = ORIENTED_EDGE('',*,*,#91705,.T.); -#91705 = EDGE_CURVE('',#91706,#91708,#91710,.T.); -#91706 = VERTEX_POINT('',#91707); -#91707 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.75)); -#91708 = VERTEX_POINT('',#91709); -#91709 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.65)); -#91710 = SURFACE_CURVE('',#91711,(#91715,#91722),.PCURVE_S1.); -#91711 = LINE('',#91712,#91713); -#91712 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.65)); -#91713 = VECTOR('',#91714,1.); -#91714 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91715 = PCURVE('',#90343,#91716); -#91716 = DEFINITIONAL_REPRESENTATION('',(#91717),#91721); -#91717 = LINE('',#91718,#91719); -#91718 = CARTESIAN_POINT('',(0.75,2.15)); -#91719 = VECTOR('',#91720,1.); -#91720 = DIRECTION('',(1.,0.E+000)); -#91721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91722 = PCURVE('',#91723,#91728); -#91723 = PLANE('',#91724); -#91724 = AXIS2_PLACEMENT_3D('',#91725,#91726,#91727); -#91725 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.65)); -#91726 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91727 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91728 = DEFINITIONAL_REPRESENTATION('',(#91729),#91733); -#91729 = LINE('',#91730,#91731); -#91730 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91731 = VECTOR('',#91732,1.); -#91732 = DIRECTION('',(1.,0.E+000)); -#91733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91734 = ORIENTED_EDGE('',*,*,#91735,.T.); -#91735 = EDGE_CURVE('',#91708,#91736,#91738,.T.); -#91736 = VERTEX_POINT('',#91737); -#91737 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); -#91738 = SURFACE_CURVE('',#91739,(#91743,#91750),.PCURVE_S1.); -#91739 = LINE('',#91740,#91741); -#91740 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); -#91741 = VECTOR('',#91742,1.); -#91742 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91743 = PCURVE('',#90343,#91744); -#91744 = DEFINITIONAL_REPRESENTATION('',(#91745),#91749); -#91745 = LINE('',#91746,#91747); -#91746 = CARTESIAN_POINT('',(0.75,2.35)); -#91747 = VECTOR('',#91748,1.); -#91748 = DIRECTION('',(0.E+000,1.)); -#91749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91750 = PCURVE('',#91751,#91756); -#91751 = PLANE('',#91752); -#91752 = AXIS2_PLACEMENT_3D('',#91753,#91754,#91755); -#91753 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); -#91754 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91755 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91756 = DEFINITIONAL_REPRESENTATION('',(#91757),#91761); -#91757 = LINE('',#91758,#91759); -#91758 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91759 = VECTOR('',#91760,1.); -#91760 = DIRECTION('',(4.440892098501E-016,1.)); -#91761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91762 = ORIENTED_EDGE('',*,*,#91763,.T.); -#91763 = EDGE_CURVE('',#91736,#91764,#91766,.T.); -#91764 = VERTEX_POINT('',#91765); -#91765 = CARTESIAN_POINT('',(0.E+000,2.35,0.75)); -#91766 = SURFACE_CURVE('',#91767,(#91771,#91778),.PCURVE_S1.); -#91767 = LINE('',#91768,#91769); -#91768 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); -#91769 = VECTOR('',#91770,1.); -#91770 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91771 = PCURVE('',#90343,#91772); -#91772 = DEFINITIONAL_REPRESENTATION('',(#91773),#91777); -#91773 = LINE('',#91774,#91775); -#91774 = CARTESIAN_POINT('',(0.75,2.35)); -#91775 = VECTOR('',#91776,1.); -#91776 = DIRECTION('',(-1.,0.E+000)); -#91777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91778 = PCURVE('',#91779,#91784); -#91779 = PLANE('',#91780); -#91780 = AXIS2_PLACEMENT_3D('',#91781,#91782,#91783); -#91781 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); -#91782 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91783 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91784 = DEFINITIONAL_REPRESENTATION('',(#91785),#91789); +#89279 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89280 = PCURVE('',#88852,#89281); +#89281 = DEFINITIONAL_REPRESENTATION('',(#89282),#89286); +#89282 = LINE('',#89283,#89284); +#89283 = CARTESIAN_POINT('',(0.75,3.85)); +#89284 = VECTOR('',#89285,1.); +#89285 = DIRECTION('',(0.E+000,-1.)); +#89286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89287 = PCURVE('',#89288,#89293); +#89288 = PLANE('',#89289); +#89289 = AXIS2_PLACEMENT_3D('',#89290,#89291,#89292); +#89290 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); +#89291 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89292 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89293 = DEFINITIONAL_REPRESENTATION('',(#89294),#89298); +#89294 = LINE('',#89295,#89296); +#89295 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89296 = VECTOR('',#89297,1.); +#89297 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89299 = FACE_BOUND('',#89300,.T.); +#89300 = EDGE_LOOP('',(#89301,#89331,#89359,#89387)); +#89301 = ORIENTED_EDGE('',*,*,#89302,.F.); +#89302 = EDGE_CURVE('',#89303,#89305,#89307,.T.); +#89303 = VERTEX_POINT('',#89304); +#89304 = CARTESIAN_POINT('',(5.15,10.,0.65)); +#89305 = VERTEX_POINT('',#89306); +#89306 = CARTESIAN_POINT('',(5.15,10.,0.75)); +#89307 = SURFACE_CURVE('',#89308,(#89312,#89319),.PCURVE_S1.); +#89308 = LINE('',#89309,#89310); +#89309 = CARTESIAN_POINT('',(5.15,10.,0.65)); +#89310 = VECTOR('',#89311,1.); +#89311 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89312 = PCURVE('',#88852,#89313); +#89313 = DEFINITIONAL_REPRESENTATION('',(#89314),#89318); +#89314 = LINE('',#89315,#89316); +#89315 = CARTESIAN_POINT('',(0.75,5.15)); +#89316 = VECTOR('',#89317,1.); +#89317 = DIRECTION('',(-1.,0.E+000)); +#89318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89319 = PCURVE('',#89320,#89325); +#89320 = PLANE('',#89321); +#89321 = AXIS2_PLACEMENT_3D('',#89322,#89323,#89324); +#89322 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); +#89323 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89324 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89325 = DEFINITIONAL_REPRESENTATION('',(#89326),#89330); +#89326 = LINE('',#89327,#89328); +#89327 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89328 = VECTOR('',#89329,1.); +#89329 = DIRECTION('',(-1.,0.E+000)); +#89330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89331 = ORIENTED_EDGE('',*,*,#89332,.F.); +#89332 = EDGE_CURVE('',#89333,#89303,#89335,.T.); +#89333 = VERTEX_POINT('',#89334); +#89334 = CARTESIAN_POINT('',(5.35,10.,0.65)); +#89335 = SURFACE_CURVE('',#89336,(#89340,#89347),.PCURVE_S1.); +#89336 = LINE('',#89337,#89338); +#89337 = CARTESIAN_POINT('',(5.15,10.,0.65)); +#89338 = VECTOR('',#89339,1.); +#89339 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89340 = PCURVE('',#88852,#89341); +#89341 = DEFINITIONAL_REPRESENTATION('',(#89342),#89346); +#89342 = LINE('',#89343,#89344); +#89343 = CARTESIAN_POINT('',(0.75,5.15)); +#89344 = VECTOR('',#89345,1.); +#89345 = DIRECTION('',(0.E+000,-1.)); +#89346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89347 = PCURVE('',#89348,#89353); +#89348 = PLANE('',#89349); +#89349 = AXIS2_PLACEMENT_3D('',#89350,#89351,#89352); +#89350 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); +#89351 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89352 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89353 = DEFINITIONAL_REPRESENTATION('',(#89354),#89358); +#89354 = LINE('',#89355,#89356); +#89355 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89356 = VECTOR('',#89357,1.); +#89357 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89359 = ORIENTED_EDGE('',*,*,#89360,.F.); +#89360 = EDGE_CURVE('',#89361,#89333,#89363,.T.); +#89361 = VERTEX_POINT('',#89362); +#89362 = CARTESIAN_POINT('',(5.35,10.,0.75)); +#89363 = SURFACE_CURVE('',#89364,(#89368,#89375),.PCURVE_S1.); +#89364 = LINE('',#89365,#89366); +#89365 = CARTESIAN_POINT('',(5.35,10.,0.65)); +#89366 = VECTOR('',#89367,1.); +#89367 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89368 = PCURVE('',#88852,#89369); +#89369 = DEFINITIONAL_REPRESENTATION('',(#89370),#89374); +#89370 = LINE('',#89371,#89372); +#89371 = CARTESIAN_POINT('',(0.75,5.35)); +#89372 = VECTOR('',#89373,1.); +#89373 = DIRECTION('',(1.,0.E+000)); +#89374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89375 = PCURVE('',#89376,#89381); +#89376 = PLANE('',#89377); +#89377 = AXIS2_PLACEMENT_3D('',#89378,#89379,#89380); +#89378 = CARTESIAN_POINT('',(5.35,10.527847992439,0.65)); +#89379 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89380 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89381 = DEFINITIONAL_REPRESENTATION('',(#89382),#89386); +#89382 = LINE('',#89383,#89384); +#89383 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89384 = VECTOR('',#89385,1.); +#89385 = DIRECTION('',(-1.,0.E+000)); +#89386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89387 = ORIENTED_EDGE('',*,*,#89388,.F.); +#89388 = EDGE_CURVE('',#89305,#89361,#89389,.T.); +#89389 = SURFACE_CURVE('',#89390,(#89394,#89401),.PCURVE_S1.); +#89390 = LINE('',#89391,#89392); +#89391 = CARTESIAN_POINT('',(5.15,10.,0.75)); +#89392 = VECTOR('',#89393,1.); +#89393 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89394 = PCURVE('',#88852,#89395); +#89395 = DEFINITIONAL_REPRESENTATION('',(#89396),#89400); +#89396 = LINE('',#89397,#89398); +#89397 = CARTESIAN_POINT('',(0.65,5.15)); +#89398 = VECTOR('',#89399,1.); +#89399 = DIRECTION('',(0.E+000,1.)); +#89400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89401 = PCURVE('',#89402,#89407); +#89402 = PLANE('',#89403); +#89403 = AXIS2_PLACEMENT_3D('',#89404,#89405,#89406); +#89404 = CARTESIAN_POINT('',(5.15,10.527847992439,0.75)); +#89405 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89406 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89407 = DEFINITIONAL_REPRESENTATION('',(#89408),#89412); +#89408 = LINE('',#89409,#89410); +#89409 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89410 = VECTOR('',#89411,1.); +#89411 = DIRECTION('',(-8.881784197001E-016,1.)); +#89412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89413 = FACE_BOUND('',#89414,.T.); +#89414 = EDGE_LOOP('',(#89415,#89445,#89473,#89501)); +#89415 = ORIENTED_EDGE('',*,*,#89416,.F.); +#89416 = EDGE_CURVE('',#89417,#89419,#89421,.T.); +#89417 = VERTEX_POINT('',#89418); +#89418 = CARTESIAN_POINT('',(6.15,10.,0.65)); +#89419 = VERTEX_POINT('',#89420); +#89420 = CARTESIAN_POINT('',(6.15,10.,0.75)); +#89421 = SURFACE_CURVE('',#89422,(#89426,#89433),.PCURVE_S1.); +#89422 = LINE('',#89423,#89424); +#89423 = CARTESIAN_POINT('',(6.15,10.,0.65)); +#89424 = VECTOR('',#89425,1.); +#89425 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89426 = PCURVE('',#88852,#89427); +#89427 = DEFINITIONAL_REPRESENTATION('',(#89428),#89432); +#89428 = LINE('',#89429,#89430); +#89429 = CARTESIAN_POINT('',(0.75,6.15)); +#89430 = VECTOR('',#89431,1.); +#89431 = DIRECTION('',(-1.,0.E+000)); +#89432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89433 = PCURVE('',#89434,#89439); +#89434 = PLANE('',#89435); +#89435 = AXIS2_PLACEMENT_3D('',#89436,#89437,#89438); +#89436 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); +#89437 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89438 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89439 = DEFINITIONAL_REPRESENTATION('',(#89440),#89444); +#89440 = LINE('',#89441,#89442); +#89441 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89442 = VECTOR('',#89443,1.); +#89443 = DIRECTION('',(-1.,0.E+000)); +#89444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89445 = ORIENTED_EDGE('',*,*,#89446,.F.); +#89446 = EDGE_CURVE('',#89447,#89417,#89449,.T.); +#89447 = VERTEX_POINT('',#89448); +#89448 = CARTESIAN_POINT('',(6.35,10.,0.65)); +#89449 = SURFACE_CURVE('',#89450,(#89454,#89461),.PCURVE_S1.); +#89450 = LINE('',#89451,#89452); +#89451 = CARTESIAN_POINT('',(6.15,10.,0.65)); +#89452 = VECTOR('',#89453,1.); +#89453 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89454 = PCURVE('',#88852,#89455); +#89455 = DEFINITIONAL_REPRESENTATION('',(#89456),#89460); +#89456 = LINE('',#89457,#89458); +#89457 = CARTESIAN_POINT('',(0.75,6.15)); +#89458 = VECTOR('',#89459,1.); +#89459 = DIRECTION('',(0.E+000,-1.)); +#89460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89461 = PCURVE('',#89462,#89467); +#89462 = PLANE('',#89463); +#89463 = AXIS2_PLACEMENT_3D('',#89464,#89465,#89466); +#89464 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); +#89465 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89466 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89467 = DEFINITIONAL_REPRESENTATION('',(#89468),#89472); +#89468 = LINE('',#89469,#89470); +#89469 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89470 = VECTOR('',#89471,1.); +#89471 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89473 = ORIENTED_EDGE('',*,*,#89474,.F.); +#89474 = EDGE_CURVE('',#89475,#89447,#89477,.T.); +#89475 = VERTEX_POINT('',#89476); +#89476 = CARTESIAN_POINT('',(6.35,10.,0.75)); +#89477 = SURFACE_CURVE('',#89478,(#89482,#89489),.PCURVE_S1.); +#89478 = LINE('',#89479,#89480); +#89479 = CARTESIAN_POINT('',(6.35,10.,0.65)); +#89480 = VECTOR('',#89481,1.); +#89481 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89482 = PCURVE('',#88852,#89483); +#89483 = DEFINITIONAL_REPRESENTATION('',(#89484),#89488); +#89484 = LINE('',#89485,#89486); +#89485 = CARTESIAN_POINT('',(0.75,6.35)); +#89486 = VECTOR('',#89487,1.); +#89487 = DIRECTION('',(1.,0.E+000)); +#89488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89489 = PCURVE('',#89490,#89495); +#89490 = PLANE('',#89491); +#89491 = AXIS2_PLACEMENT_3D('',#89492,#89493,#89494); +#89492 = CARTESIAN_POINT('',(6.35,10.527847992439,0.65)); +#89493 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89494 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89495 = DEFINITIONAL_REPRESENTATION('',(#89496),#89500); +#89496 = LINE('',#89497,#89498); +#89497 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89498 = VECTOR('',#89499,1.); +#89499 = DIRECTION('',(-1.,0.E+000)); +#89500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89501 = ORIENTED_EDGE('',*,*,#89502,.F.); +#89502 = EDGE_CURVE('',#89419,#89475,#89503,.T.); +#89503 = SURFACE_CURVE('',#89504,(#89508,#89515),.PCURVE_S1.); +#89504 = LINE('',#89505,#89506); +#89505 = CARTESIAN_POINT('',(6.15,10.,0.75)); +#89506 = VECTOR('',#89507,1.); +#89507 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89508 = PCURVE('',#88852,#89509); +#89509 = DEFINITIONAL_REPRESENTATION('',(#89510),#89514); +#89510 = LINE('',#89511,#89512); +#89511 = CARTESIAN_POINT('',(0.65,6.15)); +#89512 = VECTOR('',#89513,1.); +#89513 = DIRECTION('',(0.E+000,1.)); +#89514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89515 = PCURVE('',#89516,#89521); +#89516 = PLANE('',#89517); +#89517 = AXIS2_PLACEMENT_3D('',#89518,#89519,#89520); +#89518 = CARTESIAN_POINT('',(6.15,10.527847992439,0.75)); +#89519 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89520 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89521 = DEFINITIONAL_REPRESENTATION('',(#89522),#89526); +#89522 = LINE('',#89523,#89524); +#89523 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89524 = VECTOR('',#89525,1.); +#89525 = DIRECTION('',(-8.881784197001E-016,1.)); +#89526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89527 = FACE_BOUND('',#89528,.T.); +#89528 = EDGE_LOOP('',(#89529,#89559,#89587,#89615)); +#89529 = ORIENTED_EDGE('',*,*,#89530,.F.); +#89530 = EDGE_CURVE('',#89531,#89533,#89535,.T.); +#89531 = VERTEX_POINT('',#89532); +#89532 = CARTESIAN_POINT('',(7.15,10.,0.65)); +#89533 = VERTEX_POINT('',#89534); +#89534 = CARTESIAN_POINT('',(7.15,10.,0.75)); +#89535 = SURFACE_CURVE('',#89536,(#89540,#89547),.PCURVE_S1.); +#89536 = LINE('',#89537,#89538); +#89537 = CARTESIAN_POINT('',(7.15,10.,0.65)); +#89538 = VECTOR('',#89539,1.); +#89539 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89540 = PCURVE('',#88852,#89541); +#89541 = DEFINITIONAL_REPRESENTATION('',(#89542),#89546); +#89542 = LINE('',#89543,#89544); +#89543 = CARTESIAN_POINT('',(0.75,7.15)); +#89544 = VECTOR('',#89545,1.); +#89545 = DIRECTION('',(-1.,0.E+000)); +#89546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89547 = PCURVE('',#89548,#89553); +#89548 = PLANE('',#89549); +#89549 = AXIS2_PLACEMENT_3D('',#89550,#89551,#89552); +#89550 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); +#89551 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89552 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89553 = DEFINITIONAL_REPRESENTATION('',(#89554),#89558); +#89554 = LINE('',#89555,#89556); +#89555 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89556 = VECTOR('',#89557,1.); +#89557 = DIRECTION('',(-1.,0.E+000)); +#89558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89559 = ORIENTED_EDGE('',*,*,#89560,.F.); +#89560 = EDGE_CURVE('',#89561,#89531,#89563,.T.); +#89561 = VERTEX_POINT('',#89562); +#89562 = CARTESIAN_POINT('',(7.35,10.,0.65)); +#89563 = SURFACE_CURVE('',#89564,(#89568,#89575),.PCURVE_S1.); +#89564 = LINE('',#89565,#89566); +#89565 = CARTESIAN_POINT('',(7.15,10.,0.65)); +#89566 = VECTOR('',#89567,1.); +#89567 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89568 = PCURVE('',#88852,#89569); +#89569 = DEFINITIONAL_REPRESENTATION('',(#89570),#89574); +#89570 = LINE('',#89571,#89572); +#89571 = CARTESIAN_POINT('',(0.75,7.15)); +#89572 = VECTOR('',#89573,1.); +#89573 = DIRECTION('',(0.E+000,-1.)); +#89574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89575 = PCURVE('',#89576,#89581); +#89576 = PLANE('',#89577); +#89577 = AXIS2_PLACEMENT_3D('',#89578,#89579,#89580); +#89578 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); +#89579 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89580 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89581 = DEFINITIONAL_REPRESENTATION('',(#89582),#89586); +#89582 = LINE('',#89583,#89584); +#89583 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89584 = VECTOR('',#89585,1.); +#89585 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89587 = ORIENTED_EDGE('',*,*,#89588,.F.); +#89588 = EDGE_CURVE('',#89589,#89561,#89591,.T.); +#89589 = VERTEX_POINT('',#89590); +#89590 = CARTESIAN_POINT('',(7.35,10.,0.75)); +#89591 = SURFACE_CURVE('',#89592,(#89596,#89603),.PCURVE_S1.); +#89592 = LINE('',#89593,#89594); +#89593 = CARTESIAN_POINT('',(7.35,10.,0.65)); +#89594 = VECTOR('',#89595,1.); +#89595 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89596 = PCURVE('',#88852,#89597); +#89597 = DEFINITIONAL_REPRESENTATION('',(#89598),#89602); +#89598 = LINE('',#89599,#89600); +#89599 = CARTESIAN_POINT('',(0.75,7.35)); +#89600 = VECTOR('',#89601,1.); +#89601 = DIRECTION('',(1.,0.E+000)); +#89602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89603 = PCURVE('',#89604,#89609); +#89604 = PLANE('',#89605); +#89605 = AXIS2_PLACEMENT_3D('',#89606,#89607,#89608); +#89606 = CARTESIAN_POINT('',(7.35,10.527847992439,0.65)); +#89607 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89608 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89609 = DEFINITIONAL_REPRESENTATION('',(#89610),#89614); +#89610 = LINE('',#89611,#89612); +#89611 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89612 = VECTOR('',#89613,1.); +#89613 = DIRECTION('',(-1.,0.E+000)); +#89614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89615 = ORIENTED_EDGE('',*,*,#89616,.F.); +#89616 = EDGE_CURVE('',#89533,#89589,#89617,.T.); +#89617 = SURFACE_CURVE('',#89618,(#89622,#89629),.PCURVE_S1.); +#89618 = LINE('',#89619,#89620); +#89619 = CARTESIAN_POINT('',(7.15,10.,0.75)); +#89620 = VECTOR('',#89621,1.); +#89621 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89622 = PCURVE('',#88852,#89623); +#89623 = DEFINITIONAL_REPRESENTATION('',(#89624),#89628); +#89624 = LINE('',#89625,#89626); +#89625 = CARTESIAN_POINT('',(0.65,7.15)); +#89626 = VECTOR('',#89627,1.); +#89627 = DIRECTION('',(0.E+000,1.)); +#89628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89629 = PCURVE('',#89630,#89635); +#89630 = PLANE('',#89631); +#89631 = AXIS2_PLACEMENT_3D('',#89632,#89633,#89634); +#89632 = CARTESIAN_POINT('',(7.15,10.527847992439,0.75)); +#89633 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89634 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89635 = DEFINITIONAL_REPRESENTATION('',(#89636),#89640); +#89636 = LINE('',#89637,#89638); +#89637 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89638 = VECTOR('',#89639,1.); +#89639 = DIRECTION('',(-8.881784197001E-016,1.)); +#89640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89641 = FACE_BOUND('',#89642,.T.); +#89642 = EDGE_LOOP('',(#89643,#89673,#89701,#89729)); +#89643 = ORIENTED_EDGE('',*,*,#89644,.F.); +#89644 = EDGE_CURVE('',#89645,#89647,#89649,.T.); +#89645 = VERTEX_POINT('',#89646); +#89646 = CARTESIAN_POINT('',(8.15,10.,0.65)); +#89647 = VERTEX_POINT('',#89648); +#89648 = CARTESIAN_POINT('',(8.15,10.,0.75)); +#89649 = SURFACE_CURVE('',#89650,(#89654,#89661),.PCURVE_S1.); +#89650 = LINE('',#89651,#89652); +#89651 = CARTESIAN_POINT('',(8.15,10.,0.65)); +#89652 = VECTOR('',#89653,1.); +#89653 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89654 = PCURVE('',#88852,#89655); +#89655 = DEFINITIONAL_REPRESENTATION('',(#89656),#89660); +#89656 = LINE('',#89657,#89658); +#89657 = CARTESIAN_POINT('',(0.75,8.15)); +#89658 = VECTOR('',#89659,1.); +#89659 = DIRECTION('',(-1.,0.E+000)); +#89660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89661 = PCURVE('',#89662,#89667); +#89662 = PLANE('',#89663); +#89663 = AXIS2_PLACEMENT_3D('',#89664,#89665,#89666); +#89664 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); +#89665 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89666 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89667 = DEFINITIONAL_REPRESENTATION('',(#89668),#89672); +#89668 = LINE('',#89669,#89670); +#89669 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89670 = VECTOR('',#89671,1.); +#89671 = DIRECTION('',(-1.,0.E+000)); +#89672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89673 = ORIENTED_EDGE('',*,*,#89674,.F.); +#89674 = EDGE_CURVE('',#89675,#89645,#89677,.T.); +#89675 = VERTEX_POINT('',#89676); +#89676 = CARTESIAN_POINT('',(8.35,10.,0.65)); +#89677 = SURFACE_CURVE('',#89678,(#89682,#89689),.PCURVE_S1.); +#89678 = LINE('',#89679,#89680); +#89679 = CARTESIAN_POINT('',(8.15,10.,0.65)); +#89680 = VECTOR('',#89681,1.); +#89681 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89682 = PCURVE('',#88852,#89683); +#89683 = DEFINITIONAL_REPRESENTATION('',(#89684),#89688); +#89684 = LINE('',#89685,#89686); +#89685 = CARTESIAN_POINT('',(0.75,8.15)); +#89686 = VECTOR('',#89687,1.); +#89687 = DIRECTION('',(0.E+000,-1.)); +#89688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89689 = PCURVE('',#89690,#89695); +#89690 = PLANE('',#89691); +#89691 = AXIS2_PLACEMENT_3D('',#89692,#89693,#89694); +#89692 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); +#89693 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89694 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89695 = DEFINITIONAL_REPRESENTATION('',(#89696),#89700); +#89696 = LINE('',#89697,#89698); +#89697 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89698 = VECTOR('',#89699,1.); +#89699 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89701 = ORIENTED_EDGE('',*,*,#89702,.F.); +#89702 = EDGE_CURVE('',#89703,#89675,#89705,.T.); +#89703 = VERTEX_POINT('',#89704); +#89704 = CARTESIAN_POINT('',(8.35,10.,0.75)); +#89705 = SURFACE_CURVE('',#89706,(#89710,#89717),.PCURVE_S1.); +#89706 = LINE('',#89707,#89708); +#89707 = CARTESIAN_POINT('',(8.35,10.,0.65)); +#89708 = VECTOR('',#89709,1.); +#89709 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89710 = PCURVE('',#88852,#89711); +#89711 = DEFINITIONAL_REPRESENTATION('',(#89712),#89716); +#89712 = LINE('',#89713,#89714); +#89713 = CARTESIAN_POINT('',(0.75,8.35)); +#89714 = VECTOR('',#89715,1.); +#89715 = DIRECTION('',(1.,0.E+000)); +#89716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89717 = PCURVE('',#89718,#89723); +#89718 = PLANE('',#89719); +#89719 = AXIS2_PLACEMENT_3D('',#89720,#89721,#89722); +#89720 = CARTESIAN_POINT('',(8.35,10.527847992439,0.65)); +#89721 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89722 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89723 = DEFINITIONAL_REPRESENTATION('',(#89724),#89728); +#89724 = LINE('',#89725,#89726); +#89725 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89726 = VECTOR('',#89727,1.); +#89727 = DIRECTION('',(-1.,0.E+000)); +#89728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89729 = ORIENTED_EDGE('',*,*,#89730,.F.); +#89730 = EDGE_CURVE('',#89647,#89703,#89731,.T.); +#89731 = SURFACE_CURVE('',#89732,(#89736,#89743),.PCURVE_S1.); +#89732 = LINE('',#89733,#89734); +#89733 = CARTESIAN_POINT('',(8.15,10.,0.75)); +#89734 = VECTOR('',#89735,1.); +#89735 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89736 = PCURVE('',#88852,#89737); +#89737 = DEFINITIONAL_REPRESENTATION('',(#89738),#89742); +#89738 = LINE('',#89739,#89740); +#89739 = CARTESIAN_POINT('',(0.65,8.15)); +#89740 = VECTOR('',#89741,1.); +#89741 = DIRECTION('',(0.E+000,1.)); +#89742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89743 = PCURVE('',#89744,#89749); +#89744 = PLANE('',#89745); +#89745 = AXIS2_PLACEMENT_3D('',#89746,#89747,#89748); +#89746 = CARTESIAN_POINT('',(8.15,10.527847992439,0.75)); +#89747 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89748 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89749 = DEFINITIONAL_REPRESENTATION('',(#89750),#89754); +#89750 = LINE('',#89751,#89752); +#89751 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89752 = VECTOR('',#89753,1.); +#89753 = DIRECTION('',(-8.881784197001E-016,1.)); +#89754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89755 = FACE_BOUND('',#89756,.T.); +#89756 = EDGE_LOOP('',(#89757,#89787,#89815,#89843)); +#89757 = ORIENTED_EDGE('',*,*,#89758,.F.); +#89758 = EDGE_CURVE('',#89759,#89761,#89763,.T.); +#89759 = VERTEX_POINT('',#89760); +#89760 = CARTESIAN_POINT('',(8.65,10.,0.65)); +#89761 = VERTEX_POINT('',#89762); +#89762 = CARTESIAN_POINT('',(8.65,10.,0.75)); +#89763 = SURFACE_CURVE('',#89764,(#89768,#89775),.PCURVE_S1.); +#89764 = LINE('',#89765,#89766); +#89765 = CARTESIAN_POINT('',(8.65,10.,0.65)); +#89766 = VECTOR('',#89767,1.); +#89767 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89768 = PCURVE('',#88852,#89769); +#89769 = DEFINITIONAL_REPRESENTATION('',(#89770),#89774); +#89770 = LINE('',#89771,#89772); +#89771 = CARTESIAN_POINT('',(0.75,8.65)); +#89772 = VECTOR('',#89773,1.); +#89773 = DIRECTION('',(-1.,0.E+000)); +#89774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89775 = PCURVE('',#89776,#89781); +#89776 = PLANE('',#89777); +#89777 = AXIS2_PLACEMENT_3D('',#89778,#89779,#89780); +#89778 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); +#89779 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89780 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89781 = DEFINITIONAL_REPRESENTATION('',(#89782),#89786); +#89782 = LINE('',#89783,#89784); +#89783 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89784 = VECTOR('',#89785,1.); +#89785 = DIRECTION('',(-1.,0.E+000)); +#89786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89787 = ORIENTED_EDGE('',*,*,#89788,.F.); +#89788 = EDGE_CURVE('',#89789,#89759,#89791,.T.); +#89789 = VERTEX_POINT('',#89790); +#89790 = CARTESIAN_POINT('',(8.85,10.,0.65)); +#89791 = SURFACE_CURVE('',#89792,(#89796,#89803),.PCURVE_S1.); +#89792 = LINE('',#89793,#89794); +#89793 = CARTESIAN_POINT('',(8.65,10.,0.65)); +#89794 = VECTOR('',#89795,1.); +#89795 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89796 = PCURVE('',#88852,#89797); +#89797 = DEFINITIONAL_REPRESENTATION('',(#89798),#89802); +#89798 = LINE('',#89799,#89800); +#89799 = CARTESIAN_POINT('',(0.75,8.65)); +#89800 = VECTOR('',#89801,1.); +#89801 = DIRECTION('',(0.E+000,-1.)); +#89802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89803 = PCURVE('',#89804,#89809); +#89804 = PLANE('',#89805); +#89805 = AXIS2_PLACEMENT_3D('',#89806,#89807,#89808); +#89806 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); +#89807 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89808 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89809 = DEFINITIONAL_REPRESENTATION('',(#89810),#89814); +#89810 = LINE('',#89811,#89812); +#89811 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89812 = VECTOR('',#89813,1.); +#89813 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89815 = ORIENTED_EDGE('',*,*,#89816,.F.); +#89816 = EDGE_CURVE('',#89817,#89789,#89819,.T.); +#89817 = VERTEX_POINT('',#89818); +#89818 = CARTESIAN_POINT('',(8.85,10.,0.75)); +#89819 = SURFACE_CURVE('',#89820,(#89824,#89831),.PCURVE_S1.); +#89820 = LINE('',#89821,#89822); +#89821 = CARTESIAN_POINT('',(8.85,10.,0.65)); +#89822 = VECTOR('',#89823,1.); +#89823 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89824 = PCURVE('',#88852,#89825); +#89825 = DEFINITIONAL_REPRESENTATION('',(#89826),#89830); +#89826 = LINE('',#89827,#89828); +#89827 = CARTESIAN_POINT('',(0.75,8.85)); +#89828 = VECTOR('',#89829,1.); +#89829 = DIRECTION('',(1.,0.E+000)); +#89830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89831 = PCURVE('',#89832,#89837); +#89832 = PLANE('',#89833); +#89833 = AXIS2_PLACEMENT_3D('',#89834,#89835,#89836); +#89834 = CARTESIAN_POINT('',(8.85,10.527847992439,0.65)); +#89835 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89836 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89837 = DEFINITIONAL_REPRESENTATION('',(#89838),#89842); +#89838 = LINE('',#89839,#89840); +#89839 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89840 = VECTOR('',#89841,1.); +#89841 = DIRECTION('',(-1.,0.E+000)); +#89842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89843 = ORIENTED_EDGE('',*,*,#89844,.F.); +#89844 = EDGE_CURVE('',#89761,#89817,#89845,.T.); +#89845 = SURFACE_CURVE('',#89846,(#89850,#89857),.PCURVE_S1.); +#89846 = LINE('',#89847,#89848); +#89847 = CARTESIAN_POINT('',(8.65,10.,0.75)); +#89848 = VECTOR('',#89849,1.); +#89849 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89850 = PCURVE('',#88852,#89851); +#89851 = DEFINITIONAL_REPRESENTATION('',(#89852),#89856); +#89852 = LINE('',#89853,#89854); +#89853 = CARTESIAN_POINT('',(0.65,8.65)); +#89854 = VECTOR('',#89855,1.); +#89855 = DIRECTION('',(0.E+000,1.)); +#89856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89857 = PCURVE('',#89858,#89863); +#89858 = PLANE('',#89859); +#89859 = AXIS2_PLACEMENT_3D('',#89860,#89861,#89862); +#89860 = CARTESIAN_POINT('',(8.65,10.527847992439,0.75)); +#89861 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89862 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89863 = DEFINITIONAL_REPRESENTATION('',(#89864),#89868); +#89864 = LINE('',#89865,#89866); +#89865 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89866 = VECTOR('',#89867,1.); +#89867 = DIRECTION('',(-8.881784197001E-016,1.)); +#89868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89869 = FACE_BOUND('',#89870,.T.); +#89870 = EDGE_LOOP('',(#89871,#89901,#89929,#89957)); +#89871 = ORIENTED_EDGE('',*,*,#89872,.F.); +#89872 = EDGE_CURVE('',#89873,#89875,#89877,.T.); +#89873 = VERTEX_POINT('',#89874); +#89874 = CARTESIAN_POINT('',(4.85,10.,0.65)); +#89875 = VERTEX_POINT('',#89876); +#89876 = CARTESIAN_POINT('',(4.65,10.,0.65)); +#89877 = SURFACE_CURVE('',#89878,(#89882,#89889),.PCURVE_S1.); +#89878 = LINE('',#89879,#89880); +#89879 = CARTESIAN_POINT('',(4.85,10.,0.65)); +#89880 = VECTOR('',#89881,1.); +#89881 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#89882 = PCURVE('',#88852,#89883); +#89883 = DEFINITIONAL_REPRESENTATION('',(#89884),#89888); +#89884 = LINE('',#89885,#89886); +#89885 = CARTESIAN_POINT('',(0.75,4.85)); +#89886 = VECTOR('',#89887,1.); +#89887 = DIRECTION('',(0.E+000,-1.)); +#89888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89889 = PCURVE('',#89890,#89895); +#89890 = PLANE('',#89891); +#89891 = AXIS2_PLACEMENT_3D('',#89892,#89893,#89894); +#89892 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); +#89893 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#89894 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#89895 = DEFINITIONAL_REPRESENTATION('',(#89896),#89900); +#89896 = LINE('',#89897,#89898); +#89897 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#89898 = VECTOR('',#89899,1.); +#89899 = DIRECTION('',(-8.881784197001E-016,-1.)); +#89900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89901 = ORIENTED_EDGE('',*,*,#89902,.F.); +#89902 = EDGE_CURVE('',#89903,#89873,#89905,.T.); +#89903 = VERTEX_POINT('',#89904); +#89904 = CARTESIAN_POINT('',(4.85,10.,0.75)); +#89905 = SURFACE_CURVE('',#89906,(#89910,#89917),.PCURVE_S1.); +#89906 = LINE('',#89907,#89908); +#89907 = CARTESIAN_POINT('',(4.85,10.,0.65)); +#89908 = VECTOR('',#89909,1.); +#89909 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89910 = PCURVE('',#88852,#89911); +#89911 = DEFINITIONAL_REPRESENTATION('',(#89912),#89916); +#89912 = LINE('',#89913,#89914); +#89913 = CARTESIAN_POINT('',(0.75,4.85)); +#89914 = VECTOR('',#89915,1.); +#89915 = DIRECTION('',(1.,0.E+000)); +#89916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89917 = PCURVE('',#89918,#89923); +#89918 = PLANE('',#89919); +#89919 = AXIS2_PLACEMENT_3D('',#89920,#89921,#89922); +#89920 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); +#89921 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#89922 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89923 = DEFINITIONAL_REPRESENTATION('',(#89924),#89928); +#89924 = LINE('',#89925,#89926); +#89925 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#89926 = VECTOR('',#89927,1.); +#89927 = DIRECTION('',(-1.,0.E+000)); +#89928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89929 = ORIENTED_EDGE('',*,*,#89930,.F.); +#89930 = EDGE_CURVE('',#89931,#89903,#89933,.T.); +#89931 = VERTEX_POINT('',#89932); +#89932 = CARTESIAN_POINT('',(4.65,10.,0.75)); +#89933 = SURFACE_CURVE('',#89934,(#89938,#89945),.PCURVE_S1.); +#89934 = LINE('',#89935,#89936); +#89935 = CARTESIAN_POINT('',(4.85,10.,0.75)); +#89936 = VECTOR('',#89937,1.); +#89937 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#89938 = PCURVE('',#88852,#89939); +#89939 = DEFINITIONAL_REPRESENTATION('',(#89940),#89944); +#89940 = LINE('',#89941,#89942); +#89941 = CARTESIAN_POINT('',(0.65,4.85)); +#89942 = VECTOR('',#89943,1.); +#89943 = DIRECTION('',(0.E+000,1.)); +#89944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89945 = PCURVE('',#89946,#89951); +#89946 = PLANE('',#89947); +#89947 = AXIS2_PLACEMENT_3D('',#89948,#89949,#89950); +#89948 = CARTESIAN_POINT('',(4.85,10.527847992439,0.75)); +#89949 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#89950 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#89951 = DEFINITIONAL_REPRESENTATION('',(#89952),#89956); +#89952 = LINE('',#89953,#89954); +#89953 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#89954 = VECTOR('',#89955,1.); +#89955 = DIRECTION('',(-8.881784197001E-016,1.)); +#89956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89957 = ORIENTED_EDGE('',*,*,#89958,.F.); +#89958 = EDGE_CURVE('',#89875,#89931,#89959,.T.); +#89959 = SURFACE_CURVE('',#89960,(#89964,#89971),.PCURVE_S1.); +#89960 = LINE('',#89961,#89962); +#89961 = CARTESIAN_POINT('',(4.65,10.,0.65)); +#89962 = VECTOR('',#89963,1.); +#89963 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89964 = PCURVE('',#88852,#89965); +#89965 = DEFINITIONAL_REPRESENTATION('',(#89966),#89970); +#89966 = LINE('',#89967,#89968); +#89967 = CARTESIAN_POINT('',(0.75,4.65)); +#89968 = VECTOR('',#89969,1.); +#89969 = DIRECTION('',(-1.,0.E+000)); +#89970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89971 = PCURVE('',#89972,#89977); +#89972 = PLANE('',#89973); +#89973 = AXIS2_PLACEMENT_3D('',#89974,#89975,#89976); +#89974 = CARTESIAN_POINT('',(4.65,10.527847992439,0.65)); +#89975 = DIRECTION('',(1.,0.E+000,0.E+000)); +#89976 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#89977 = DEFINITIONAL_REPRESENTATION('',(#89978),#89982); +#89978 = LINE('',#89979,#89980); +#89979 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#89980 = VECTOR('',#89981,1.); +#89981 = DIRECTION('',(-1.,0.E+000)); +#89982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#89983 = FACE_BOUND('',#89984,.T.); +#89984 = EDGE_LOOP('',(#89985,#90015,#90043,#90071)); +#89985 = ORIENTED_EDGE('',*,*,#89986,.F.); +#89986 = EDGE_CURVE('',#89987,#89989,#89991,.T.); +#89987 = VERTEX_POINT('',#89988); +#89988 = CARTESIAN_POINT('',(7.65,10.,0.65)); +#89989 = VERTEX_POINT('',#89990); +#89990 = CARTESIAN_POINT('',(7.65,10.,0.75)); +#89991 = SURFACE_CURVE('',#89992,(#89996,#90003),.PCURVE_S1.); +#89992 = LINE('',#89993,#89994); +#89993 = CARTESIAN_POINT('',(7.65,10.,0.65)); +#89994 = VECTOR('',#89995,1.); +#89995 = DIRECTION('',(0.E+000,0.E+000,1.)); +#89996 = PCURVE('',#88852,#89997); +#89997 = DEFINITIONAL_REPRESENTATION('',(#89998),#90002); +#89998 = LINE('',#89999,#90000); +#89999 = CARTESIAN_POINT('',(0.75,7.65)); +#90000 = VECTOR('',#90001,1.); +#90001 = DIRECTION('',(-1.,0.E+000)); +#90002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90003 = PCURVE('',#90004,#90009); +#90004 = PLANE('',#90005); +#90005 = AXIS2_PLACEMENT_3D('',#90006,#90007,#90008); +#90006 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); +#90007 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90008 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90009 = DEFINITIONAL_REPRESENTATION('',(#90010),#90014); +#90010 = LINE('',#90011,#90012); +#90011 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90012 = VECTOR('',#90013,1.); +#90013 = DIRECTION('',(-1.,0.E+000)); +#90014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90015 = ORIENTED_EDGE('',*,*,#90016,.F.); +#90016 = EDGE_CURVE('',#90017,#89987,#90019,.T.); +#90017 = VERTEX_POINT('',#90018); +#90018 = CARTESIAN_POINT('',(7.85,10.,0.65)); +#90019 = SURFACE_CURVE('',#90020,(#90024,#90031),.PCURVE_S1.); +#90020 = LINE('',#90021,#90022); +#90021 = CARTESIAN_POINT('',(7.65,10.,0.65)); +#90022 = VECTOR('',#90023,1.); +#90023 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90024 = PCURVE('',#88852,#90025); +#90025 = DEFINITIONAL_REPRESENTATION('',(#90026),#90030); +#90026 = LINE('',#90027,#90028); +#90027 = CARTESIAN_POINT('',(0.75,7.65)); +#90028 = VECTOR('',#90029,1.); +#90029 = DIRECTION('',(0.E+000,-1.)); +#90030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90031 = PCURVE('',#90032,#90037); +#90032 = PLANE('',#90033); +#90033 = AXIS2_PLACEMENT_3D('',#90034,#90035,#90036); +#90034 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); +#90035 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90036 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90037 = DEFINITIONAL_REPRESENTATION('',(#90038),#90042); +#90038 = LINE('',#90039,#90040); +#90039 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90040 = VECTOR('',#90041,1.); +#90041 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90043 = ORIENTED_EDGE('',*,*,#90044,.F.); +#90044 = EDGE_CURVE('',#90045,#90017,#90047,.T.); +#90045 = VERTEX_POINT('',#90046); +#90046 = CARTESIAN_POINT('',(7.85,10.,0.75)); +#90047 = SURFACE_CURVE('',#90048,(#90052,#90059),.PCURVE_S1.); +#90048 = LINE('',#90049,#90050); +#90049 = CARTESIAN_POINT('',(7.85,10.,0.65)); +#90050 = VECTOR('',#90051,1.); +#90051 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90052 = PCURVE('',#88852,#90053); +#90053 = DEFINITIONAL_REPRESENTATION('',(#90054),#90058); +#90054 = LINE('',#90055,#90056); +#90055 = CARTESIAN_POINT('',(0.75,7.85)); +#90056 = VECTOR('',#90057,1.); +#90057 = DIRECTION('',(1.,0.E+000)); +#90058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90059 = PCURVE('',#90060,#90065); +#90060 = PLANE('',#90061); +#90061 = AXIS2_PLACEMENT_3D('',#90062,#90063,#90064); +#90062 = CARTESIAN_POINT('',(7.85,10.527847992439,0.65)); +#90063 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90064 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90065 = DEFINITIONAL_REPRESENTATION('',(#90066),#90070); +#90066 = LINE('',#90067,#90068); +#90067 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90068 = VECTOR('',#90069,1.); +#90069 = DIRECTION('',(-1.,0.E+000)); +#90070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90071 = ORIENTED_EDGE('',*,*,#90072,.F.); +#90072 = EDGE_CURVE('',#89989,#90045,#90073,.T.); +#90073 = SURFACE_CURVE('',#90074,(#90078,#90085),.PCURVE_S1.); +#90074 = LINE('',#90075,#90076); +#90075 = CARTESIAN_POINT('',(7.65,10.,0.75)); +#90076 = VECTOR('',#90077,1.); +#90077 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90078 = PCURVE('',#88852,#90079); +#90079 = DEFINITIONAL_REPRESENTATION('',(#90080),#90084); +#90080 = LINE('',#90081,#90082); +#90081 = CARTESIAN_POINT('',(0.65,7.65)); +#90082 = VECTOR('',#90083,1.); +#90083 = DIRECTION('',(0.E+000,1.)); +#90084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90085 = PCURVE('',#90086,#90091); +#90086 = PLANE('',#90087); +#90087 = AXIS2_PLACEMENT_3D('',#90088,#90089,#90090); +#90088 = CARTESIAN_POINT('',(7.65,10.527847992439,0.75)); +#90089 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90090 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90091 = DEFINITIONAL_REPRESENTATION('',(#90092),#90096); +#90092 = LINE('',#90093,#90094); +#90093 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90094 = VECTOR('',#90095,1.); +#90095 = DIRECTION('',(-8.881784197001E-016,1.)); +#90096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90097 = FACE_BOUND('',#90098,.T.); +#90098 = EDGE_LOOP('',(#90099,#90129,#90157,#90185)); +#90099 = ORIENTED_EDGE('',*,*,#90100,.F.); +#90100 = EDGE_CURVE('',#90101,#90103,#90105,.T.); +#90101 = VERTEX_POINT('',#90102); +#90102 = CARTESIAN_POINT('',(6.65,10.,0.65)); +#90103 = VERTEX_POINT('',#90104); +#90104 = CARTESIAN_POINT('',(6.65,10.,0.75)); +#90105 = SURFACE_CURVE('',#90106,(#90110,#90117),.PCURVE_S1.); +#90106 = LINE('',#90107,#90108); +#90107 = CARTESIAN_POINT('',(6.65,10.,0.65)); +#90108 = VECTOR('',#90109,1.); +#90109 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90110 = PCURVE('',#88852,#90111); +#90111 = DEFINITIONAL_REPRESENTATION('',(#90112),#90116); +#90112 = LINE('',#90113,#90114); +#90113 = CARTESIAN_POINT('',(0.75,6.65)); +#90114 = VECTOR('',#90115,1.); +#90115 = DIRECTION('',(-1.,0.E+000)); +#90116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90117 = PCURVE('',#90118,#90123); +#90118 = PLANE('',#90119); +#90119 = AXIS2_PLACEMENT_3D('',#90120,#90121,#90122); +#90120 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); +#90121 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90122 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90123 = DEFINITIONAL_REPRESENTATION('',(#90124),#90128); +#90124 = LINE('',#90125,#90126); +#90125 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90126 = VECTOR('',#90127,1.); +#90127 = DIRECTION('',(-1.,0.E+000)); +#90128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90129 = ORIENTED_EDGE('',*,*,#90130,.F.); +#90130 = EDGE_CURVE('',#90131,#90101,#90133,.T.); +#90131 = VERTEX_POINT('',#90132); +#90132 = CARTESIAN_POINT('',(6.85,10.,0.65)); +#90133 = SURFACE_CURVE('',#90134,(#90138,#90145),.PCURVE_S1.); +#90134 = LINE('',#90135,#90136); +#90135 = CARTESIAN_POINT('',(6.65,10.,0.65)); +#90136 = VECTOR('',#90137,1.); +#90137 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90138 = PCURVE('',#88852,#90139); +#90139 = DEFINITIONAL_REPRESENTATION('',(#90140),#90144); +#90140 = LINE('',#90141,#90142); +#90141 = CARTESIAN_POINT('',(0.75,6.65)); +#90142 = VECTOR('',#90143,1.); +#90143 = DIRECTION('',(0.E+000,-1.)); +#90144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90145 = PCURVE('',#90146,#90151); +#90146 = PLANE('',#90147); +#90147 = AXIS2_PLACEMENT_3D('',#90148,#90149,#90150); +#90148 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); +#90149 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90150 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90151 = DEFINITIONAL_REPRESENTATION('',(#90152),#90156); +#90152 = LINE('',#90153,#90154); +#90153 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90154 = VECTOR('',#90155,1.); +#90155 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90157 = ORIENTED_EDGE('',*,*,#90158,.F.); +#90158 = EDGE_CURVE('',#90159,#90131,#90161,.T.); +#90159 = VERTEX_POINT('',#90160); +#90160 = CARTESIAN_POINT('',(6.85,10.,0.75)); +#90161 = SURFACE_CURVE('',#90162,(#90166,#90173),.PCURVE_S1.); +#90162 = LINE('',#90163,#90164); +#90163 = CARTESIAN_POINT('',(6.85,10.,0.65)); +#90164 = VECTOR('',#90165,1.); +#90165 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90166 = PCURVE('',#88852,#90167); +#90167 = DEFINITIONAL_REPRESENTATION('',(#90168),#90172); +#90168 = LINE('',#90169,#90170); +#90169 = CARTESIAN_POINT('',(0.75,6.85)); +#90170 = VECTOR('',#90171,1.); +#90171 = DIRECTION('',(1.,0.E+000)); +#90172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90173 = PCURVE('',#90174,#90179); +#90174 = PLANE('',#90175); +#90175 = AXIS2_PLACEMENT_3D('',#90176,#90177,#90178); +#90176 = CARTESIAN_POINT('',(6.85,10.527847992439,0.65)); +#90177 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90178 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90179 = DEFINITIONAL_REPRESENTATION('',(#90180),#90184); +#90180 = LINE('',#90181,#90182); +#90181 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90182 = VECTOR('',#90183,1.); +#90183 = DIRECTION('',(-1.,0.E+000)); +#90184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90185 = ORIENTED_EDGE('',*,*,#90186,.F.); +#90186 = EDGE_CURVE('',#90103,#90159,#90187,.T.); +#90187 = SURFACE_CURVE('',#90188,(#90192,#90199),.PCURVE_S1.); +#90188 = LINE('',#90189,#90190); +#90189 = CARTESIAN_POINT('',(6.65,10.,0.75)); +#90190 = VECTOR('',#90191,1.); +#90191 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90192 = PCURVE('',#88852,#90193); +#90193 = DEFINITIONAL_REPRESENTATION('',(#90194),#90198); +#90194 = LINE('',#90195,#90196); +#90195 = CARTESIAN_POINT('',(0.65,6.65)); +#90196 = VECTOR('',#90197,1.); +#90197 = DIRECTION('',(0.E+000,1.)); +#90198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90199 = PCURVE('',#90200,#90205); +#90200 = PLANE('',#90201); +#90201 = AXIS2_PLACEMENT_3D('',#90202,#90203,#90204); +#90202 = CARTESIAN_POINT('',(6.65,10.527847992439,0.75)); +#90203 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90204 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90205 = DEFINITIONAL_REPRESENTATION('',(#90206),#90210); +#90206 = LINE('',#90207,#90208); +#90207 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90208 = VECTOR('',#90209,1.); +#90209 = DIRECTION('',(-8.881784197001E-016,1.)); +#90210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90211 = FACE_BOUND('',#90212,.T.); +#90212 = EDGE_LOOP('',(#90213,#90243,#90271,#90299)); +#90213 = ORIENTED_EDGE('',*,*,#90214,.F.); +#90214 = EDGE_CURVE('',#90215,#90217,#90219,.T.); +#90215 = VERTEX_POINT('',#90216); +#90216 = CARTESIAN_POINT('',(5.65,10.,0.65)); +#90217 = VERTEX_POINT('',#90218); +#90218 = CARTESIAN_POINT('',(5.65,10.,0.75)); +#90219 = SURFACE_CURVE('',#90220,(#90224,#90231),.PCURVE_S1.); +#90220 = LINE('',#90221,#90222); +#90221 = CARTESIAN_POINT('',(5.65,10.,0.65)); +#90222 = VECTOR('',#90223,1.); +#90223 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90224 = PCURVE('',#88852,#90225); +#90225 = DEFINITIONAL_REPRESENTATION('',(#90226),#90230); +#90226 = LINE('',#90227,#90228); +#90227 = CARTESIAN_POINT('',(0.75,5.65)); +#90228 = VECTOR('',#90229,1.); +#90229 = DIRECTION('',(-1.,0.E+000)); +#90230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90231 = PCURVE('',#90232,#90237); +#90232 = PLANE('',#90233); +#90233 = AXIS2_PLACEMENT_3D('',#90234,#90235,#90236); +#90234 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); +#90235 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90236 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90237 = DEFINITIONAL_REPRESENTATION('',(#90238),#90242); +#90238 = LINE('',#90239,#90240); +#90239 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90240 = VECTOR('',#90241,1.); +#90241 = DIRECTION('',(-1.,0.E+000)); +#90242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90243 = ORIENTED_EDGE('',*,*,#90244,.F.); +#90244 = EDGE_CURVE('',#90245,#90215,#90247,.T.); +#90245 = VERTEX_POINT('',#90246); +#90246 = CARTESIAN_POINT('',(5.85,10.,0.65)); +#90247 = SURFACE_CURVE('',#90248,(#90252,#90259),.PCURVE_S1.); +#90248 = LINE('',#90249,#90250); +#90249 = CARTESIAN_POINT('',(5.65,10.,0.65)); +#90250 = VECTOR('',#90251,1.); +#90251 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90252 = PCURVE('',#88852,#90253); +#90253 = DEFINITIONAL_REPRESENTATION('',(#90254),#90258); +#90254 = LINE('',#90255,#90256); +#90255 = CARTESIAN_POINT('',(0.75,5.65)); +#90256 = VECTOR('',#90257,1.); +#90257 = DIRECTION('',(0.E+000,-1.)); +#90258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90259 = PCURVE('',#90260,#90265); +#90260 = PLANE('',#90261); +#90261 = AXIS2_PLACEMENT_3D('',#90262,#90263,#90264); +#90262 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); +#90263 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90264 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90265 = DEFINITIONAL_REPRESENTATION('',(#90266),#90270); +#90266 = LINE('',#90267,#90268); +#90267 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90268 = VECTOR('',#90269,1.); +#90269 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90271 = ORIENTED_EDGE('',*,*,#90272,.F.); +#90272 = EDGE_CURVE('',#90273,#90245,#90275,.T.); +#90273 = VERTEX_POINT('',#90274); +#90274 = CARTESIAN_POINT('',(5.85,10.,0.75)); +#90275 = SURFACE_CURVE('',#90276,(#90280,#90287),.PCURVE_S1.); +#90276 = LINE('',#90277,#90278); +#90277 = CARTESIAN_POINT('',(5.85,10.,0.65)); +#90278 = VECTOR('',#90279,1.); +#90279 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90280 = PCURVE('',#88852,#90281); +#90281 = DEFINITIONAL_REPRESENTATION('',(#90282),#90286); +#90282 = LINE('',#90283,#90284); +#90283 = CARTESIAN_POINT('',(0.75,5.85)); +#90284 = VECTOR('',#90285,1.); +#90285 = DIRECTION('',(1.,0.E+000)); +#90286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90287 = PCURVE('',#90288,#90293); +#90288 = PLANE('',#90289); +#90289 = AXIS2_PLACEMENT_3D('',#90290,#90291,#90292); +#90290 = CARTESIAN_POINT('',(5.85,10.527847992439,0.65)); +#90291 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90292 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90293 = DEFINITIONAL_REPRESENTATION('',(#90294),#90298); +#90294 = LINE('',#90295,#90296); +#90295 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90296 = VECTOR('',#90297,1.); +#90297 = DIRECTION('',(-1.,0.E+000)); +#90298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90299 = ORIENTED_EDGE('',*,*,#90300,.F.); +#90300 = EDGE_CURVE('',#90217,#90273,#90301,.T.); +#90301 = SURFACE_CURVE('',#90302,(#90306,#90313),.PCURVE_S1.); +#90302 = LINE('',#90303,#90304); +#90303 = CARTESIAN_POINT('',(5.65,10.,0.75)); +#90304 = VECTOR('',#90305,1.); +#90305 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90306 = PCURVE('',#88852,#90307); +#90307 = DEFINITIONAL_REPRESENTATION('',(#90308),#90312); +#90308 = LINE('',#90309,#90310); +#90309 = CARTESIAN_POINT('',(0.65,5.65)); +#90310 = VECTOR('',#90311,1.); +#90311 = DIRECTION('',(0.E+000,1.)); +#90312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90313 = PCURVE('',#90314,#90319); +#90314 = PLANE('',#90315); +#90315 = AXIS2_PLACEMENT_3D('',#90316,#90317,#90318); +#90316 = CARTESIAN_POINT('',(5.65,10.527847992439,0.75)); +#90317 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90318 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90319 = DEFINITIONAL_REPRESENTATION('',(#90320),#90324); +#90320 = LINE('',#90321,#90322); +#90321 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90322 = VECTOR('',#90323,1.); +#90323 = DIRECTION('',(-8.881784197001E-016,1.)); +#90324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90325 = FACE_BOUND('',#90326,.T.); +#90326 = EDGE_LOOP('',(#90327,#90357,#90385,#90413)); +#90327 = ORIENTED_EDGE('',*,*,#90328,.F.); +#90328 = EDGE_CURVE('',#90329,#90331,#90333,.T.); +#90329 = VERTEX_POINT('',#90330); +#90330 = CARTESIAN_POINT('',(4.35,10.,0.75)); +#90331 = VERTEX_POINT('',#90332); +#90332 = CARTESIAN_POINT('',(4.35,10.,0.65)); +#90333 = SURFACE_CURVE('',#90334,(#90338,#90345),.PCURVE_S1.); +#90334 = LINE('',#90335,#90336); +#90335 = CARTESIAN_POINT('',(4.35,10.,0.65)); +#90336 = VECTOR('',#90337,1.); +#90337 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90338 = PCURVE('',#88852,#90339); +#90339 = DEFINITIONAL_REPRESENTATION('',(#90340),#90344); +#90340 = LINE('',#90341,#90342); +#90341 = CARTESIAN_POINT('',(0.75,4.35)); +#90342 = VECTOR('',#90343,1.); +#90343 = DIRECTION('',(1.,0.E+000)); +#90344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90345 = PCURVE('',#90346,#90351); +#90346 = PLANE('',#90347); +#90347 = AXIS2_PLACEMENT_3D('',#90348,#90349,#90350); +#90348 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); +#90349 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90350 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90351 = DEFINITIONAL_REPRESENTATION('',(#90352),#90356); +#90352 = LINE('',#90353,#90354); +#90353 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90354 = VECTOR('',#90355,1.); +#90355 = DIRECTION('',(-1.,0.E+000)); +#90356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90357 = ORIENTED_EDGE('',*,*,#90358,.F.); +#90358 = EDGE_CURVE('',#90359,#90329,#90361,.T.); +#90359 = VERTEX_POINT('',#90360); +#90360 = CARTESIAN_POINT('',(4.15,10.,0.75)); +#90361 = SURFACE_CURVE('',#90362,(#90366,#90373),.PCURVE_S1.); +#90362 = LINE('',#90363,#90364); +#90363 = CARTESIAN_POINT('',(4.35,10.,0.75)); +#90364 = VECTOR('',#90365,1.); +#90365 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90366 = PCURVE('',#88852,#90367); +#90367 = DEFINITIONAL_REPRESENTATION('',(#90368),#90372); +#90368 = LINE('',#90369,#90370); +#90369 = CARTESIAN_POINT('',(0.65,4.35)); +#90370 = VECTOR('',#90371,1.); +#90371 = DIRECTION('',(0.E+000,1.)); +#90372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90373 = PCURVE('',#90374,#90379); +#90374 = PLANE('',#90375); +#90375 = AXIS2_PLACEMENT_3D('',#90376,#90377,#90378); +#90376 = CARTESIAN_POINT('',(4.35,10.527847992439,0.75)); +#90377 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90378 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90379 = DEFINITIONAL_REPRESENTATION('',(#90380),#90384); +#90380 = LINE('',#90381,#90382); +#90381 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90382 = VECTOR('',#90383,1.); +#90383 = DIRECTION('',(-8.881784197001E-016,1.)); +#90384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90385 = ORIENTED_EDGE('',*,*,#90386,.F.); +#90386 = EDGE_CURVE('',#90387,#90359,#90389,.T.); +#90387 = VERTEX_POINT('',#90388); +#90388 = CARTESIAN_POINT('',(4.15,10.,0.65)); +#90389 = SURFACE_CURVE('',#90390,(#90394,#90401),.PCURVE_S1.); +#90390 = LINE('',#90391,#90392); +#90391 = CARTESIAN_POINT('',(4.15,10.,0.65)); +#90392 = VECTOR('',#90393,1.); +#90393 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90394 = PCURVE('',#88852,#90395); +#90395 = DEFINITIONAL_REPRESENTATION('',(#90396),#90400); +#90396 = LINE('',#90397,#90398); +#90397 = CARTESIAN_POINT('',(0.75,4.15)); +#90398 = VECTOR('',#90399,1.); +#90399 = DIRECTION('',(-1.,0.E+000)); +#90400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90401 = PCURVE('',#90402,#90407); +#90402 = PLANE('',#90403); +#90403 = AXIS2_PLACEMENT_3D('',#90404,#90405,#90406); +#90404 = CARTESIAN_POINT('',(4.15,10.527847992439,0.65)); +#90405 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90406 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90407 = DEFINITIONAL_REPRESENTATION('',(#90408),#90412); +#90408 = LINE('',#90409,#90410); +#90409 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90410 = VECTOR('',#90411,1.); +#90411 = DIRECTION('',(-1.,0.E+000)); +#90412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90413 = ORIENTED_EDGE('',*,*,#90414,.F.); +#90414 = EDGE_CURVE('',#90331,#90387,#90415,.T.); +#90415 = SURFACE_CURVE('',#90416,(#90420,#90427),.PCURVE_S1.); +#90416 = LINE('',#90417,#90418); +#90417 = CARTESIAN_POINT('',(4.35,10.,0.65)); +#90418 = VECTOR('',#90419,1.); +#90419 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90420 = PCURVE('',#88852,#90421); +#90421 = DEFINITIONAL_REPRESENTATION('',(#90422),#90426); +#90422 = LINE('',#90423,#90424); +#90423 = CARTESIAN_POINT('',(0.75,4.35)); +#90424 = VECTOR('',#90425,1.); +#90425 = DIRECTION('',(0.E+000,-1.)); +#90426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90427 = PCURVE('',#90428,#90433); +#90428 = PLANE('',#90429); +#90429 = AXIS2_PLACEMENT_3D('',#90430,#90431,#90432); +#90430 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); +#90431 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90432 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90433 = DEFINITIONAL_REPRESENTATION('',(#90434),#90438); +#90434 = LINE('',#90435,#90436); +#90435 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90436 = VECTOR('',#90437,1.); +#90437 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90439 = FACE_BOUND('',#90440,.T.); +#90440 = EDGE_LOOP('',(#90441,#90471,#90499,#90527)); +#90441 = ORIENTED_EDGE('',*,*,#90442,.F.); +#90442 = EDGE_CURVE('',#90443,#90445,#90447,.T.); +#90443 = VERTEX_POINT('',#90444); +#90444 = CARTESIAN_POINT('',(3.35,10.,0.75)); +#90445 = VERTEX_POINT('',#90446); +#90446 = CARTESIAN_POINT('',(3.35,10.,0.65)); +#90447 = SURFACE_CURVE('',#90448,(#90452,#90459),.PCURVE_S1.); +#90448 = LINE('',#90449,#90450); +#90449 = CARTESIAN_POINT('',(3.35,10.,0.65)); +#90450 = VECTOR('',#90451,1.); +#90451 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90452 = PCURVE('',#88852,#90453); +#90453 = DEFINITIONAL_REPRESENTATION('',(#90454),#90458); +#90454 = LINE('',#90455,#90456); +#90455 = CARTESIAN_POINT('',(0.75,3.35)); +#90456 = VECTOR('',#90457,1.); +#90457 = DIRECTION('',(1.,0.E+000)); +#90458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90459 = PCURVE('',#90460,#90465); +#90460 = PLANE('',#90461); +#90461 = AXIS2_PLACEMENT_3D('',#90462,#90463,#90464); +#90462 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); +#90463 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90464 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90465 = DEFINITIONAL_REPRESENTATION('',(#90466),#90470); +#90466 = LINE('',#90467,#90468); +#90467 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90468 = VECTOR('',#90469,1.); +#90469 = DIRECTION('',(-1.,0.E+000)); +#90470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90471 = ORIENTED_EDGE('',*,*,#90472,.F.); +#90472 = EDGE_CURVE('',#90473,#90443,#90475,.T.); +#90473 = VERTEX_POINT('',#90474); +#90474 = CARTESIAN_POINT('',(3.15,10.,0.75)); +#90475 = SURFACE_CURVE('',#90476,(#90480,#90487),.PCURVE_S1.); +#90476 = LINE('',#90477,#90478); +#90477 = CARTESIAN_POINT('',(3.35,10.,0.75)); +#90478 = VECTOR('',#90479,1.); +#90479 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90480 = PCURVE('',#88852,#90481); +#90481 = DEFINITIONAL_REPRESENTATION('',(#90482),#90486); +#90482 = LINE('',#90483,#90484); +#90483 = CARTESIAN_POINT('',(0.65,3.35)); +#90484 = VECTOR('',#90485,1.); +#90485 = DIRECTION('',(0.E+000,1.)); +#90486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90487 = PCURVE('',#90488,#90493); +#90488 = PLANE('',#90489); +#90489 = AXIS2_PLACEMENT_3D('',#90490,#90491,#90492); +#90490 = CARTESIAN_POINT('',(3.35,10.527847992439,0.75)); +#90491 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90492 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90493 = DEFINITIONAL_REPRESENTATION('',(#90494),#90498); +#90494 = LINE('',#90495,#90496); +#90495 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90496 = VECTOR('',#90497,1.); +#90497 = DIRECTION('',(-8.881784197001E-016,1.)); +#90498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90499 = ORIENTED_EDGE('',*,*,#90500,.F.); +#90500 = EDGE_CURVE('',#90501,#90473,#90503,.T.); +#90501 = VERTEX_POINT('',#90502); +#90502 = CARTESIAN_POINT('',(3.15,10.,0.65)); +#90503 = SURFACE_CURVE('',#90504,(#90508,#90515),.PCURVE_S1.); +#90504 = LINE('',#90505,#90506); +#90505 = CARTESIAN_POINT('',(3.15,10.,0.65)); +#90506 = VECTOR('',#90507,1.); +#90507 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90508 = PCURVE('',#88852,#90509); +#90509 = DEFINITIONAL_REPRESENTATION('',(#90510),#90514); +#90510 = LINE('',#90511,#90512); +#90511 = CARTESIAN_POINT('',(0.75,3.15)); +#90512 = VECTOR('',#90513,1.); +#90513 = DIRECTION('',(-1.,0.E+000)); +#90514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90515 = PCURVE('',#90516,#90521); +#90516 = PLANE('',#90517); +#90517 = AXIS2_PLACEMENT_3D('',#90518,#90519,#90520); +#90518 = CARTESIAN_POINT('',(3.15,10.527847992439,0.65)); +#90519 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90520 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90521 = DEFINITIONAL_REPRESENTATION('',(#90522),#90526); +#90522 = LINE('',#90523,#90524); +#90523 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90524 = VECTOR('',#90525,1.); +#90525 = DIRECTION('',(-1.,0.E+000)); +#90526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90527 = ORIENTED_EDGE('',*,*,#90528,.F.); +#90528 = EDGE_CURVE('',#90445,#90501,#90529,.T.); +#90529 = SURFACE_CURVE('',#90530,(#90534,#90541),.PCURVE_S1.); +#90530 = LINE('',#90531,#90532); +#90531 = CARTESIAN_POINT('',(3.35,10.,0.65)); +#90532 = VECTOR('',#90533,1.); +#90533 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90534 = PCURVE('',#88852,#90535); +#90535 = DEFINITIONAL_REPRESENTATION('',(#90536),#90540); +#90536 = LINE('',#90537,#90538); +#90537 = CARTESIAN_POINT('',(0.75,3.35)); +#90538 = VECTOR('',#90539,1.); +#90539 = DIRECTION('',(0.E+000,-1.)); +#90540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90541 = PCURVE('',#90542,#90547); +#90542 = PLANE('',#90543); +#90543 = AXIS2_PLACEMENT_3D('',#90544,#90545,#90546); +#90544 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); +#90545 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90546 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90547 = DEFINITIONAL_REPRESENTATION('',(#90548),#90552); +#90548 = LINE('',#90549,#90550); +#90549 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90550 = VECTOR('',#90551,1.); +#90551 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90553 = FACE_BOUND('',#90554,.T.); +#90554 = EDGE_LOOP('',(#90555,#90585,#90613,#90641)); +#90555 = ORIENTED_EDGE('',*,*,#90556,.F.); +#90556 = EDGE_CURVE('',#90557,#90559,#90561,.T.); +#90557 = VERTEX_POINT('',#90558); +#90558 = CARTESIAN_POINT('',(2.35,10.,0.75)); +#90559 = VERTEX_POINT('',#90560); +#90560 = CARTESIAN_POINT('',(2.35,10.,0.65)); +#90561 = SURFACE_CURVE('',#90562,(#90566,#90573),.PCURVE_S1.); +#90562 = LINE('',#90563,#90564); +#90563 = CARTESIAN_POINT('',(2.35,10.,0.65)); +#90564 = VECTOR('',#90565,1.); +#90565 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90566 = PCURVE('',#88852,#90567); +#90567 = DEFINITIONAL_REPRESENTATION('',(#90568),#90572); +#90568 = LINE('',#90569,#90570); +#90569 = CARTESIAN_POINT('',(0.75,2.35)); +#90570 = VECTOR('',#90571,1.); +#90571 = DIRECTION('',(1.,0.E+000)); +#90572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90573 = PCURVE('',#90574,#90579); +#90574 = PLANE('',#90575); +#90575 = AXIS2_PLACEMENT_3D('',#90576,#90577,#90578); +#90576 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); +#90577 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90578 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90579 = DEFINITIONAL_REPRESENTATION('',(#90580),#90584); +#90580 = LINE('',#90581,#90582); +#90581 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90582 = VECTOR('',#90583,1.); +#90583 = DIRECTION('',(-1.,0.E+000)); +#90584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90585 = ORIENTED_EDGE('',*,*,#90586,.F.); +#90586 = EDGE_CURVE('',#90587,#90557,#90589,.T.); +#90587 = VERTEX_POINT('',#90588); +#90588 = CARTESIAN_POINT('',(2.15,10.,0.75)); +#90589 = SURFACE_CURVE('',#90590,(#90594,#90601),.PCURVE_S1.); +#90590 = LINE('',#90591,#90592); +#90591 = CARTESIAN_POINT('',(2.35,10.,0.75)); +#90592 = VECTOR('',#90593,1.); +#90593 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90594 = PCURVE('',#88852,#90595); +#90595 = DEFINITIONAL_REPRESENTATION('',(#90596),#90600); +#90596 = LINE('',#90597,#90598); +#90597 = CARTESIAN_POINT('',(0.65,2.35)); +#90598 = VECTOR('',#90599,1.); +#90599 = DIRECTION('',(0.E+000,1.)); +#90600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90601 = PCURVE('',#90602,#90607); +#90602 = PLANE('',#90603); +#90603 = AXIS2_PLACEMENT_3D('',#90604,#90605,#90606); +#90604 = CARTESIAN_POINT('',(2.35,10.527847992439,0.75)); +#90605 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90606 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90607 = DEFINITIONAL_REPRESENTATION('',(#90608),#90612); +#90608 = LINE('',#90609,#90610); +#90609 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90610 = VECTOR('',#90611,1.); +#90611 = DIRECTION('',(-8.881784197001E-016,1.)); +#90612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90613 = ORIENTED_EDGE('',*,*,#90614,.F.); +#90614 = EDGE_CURVE('',#90615,#90587,#90617,.T.); +#90615 = VERTEX_POINT('',#90616); +#90616 = CARTESIAN_POINT('',(2.15,10.,0.65)); +#90617 = SURFACE_CURVE('',#90618,(#90622,#90629),.PCURVE_S1.); +#90618 = LINE('',#90619,#90620); +#90619 = CARTESIAN_POINT('',(2.15,10.,0.65)); +#90620 = VECTOR('',#90621,1.); +#90621 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90622 = PCURVE('',#88852,#90623); +#90623 = DEFINITIONAL_REPRESENTATION('',(#90624),#90628); +#90624 = LINE('',#90625,#90626); +#90625 = CARTESIAN_POINT('',(0.75,2.15)); +#90626 = VECTOR('',#90627,1.); +#90627 = DIRECTION('',(-1.,0.E+000)); +#90628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90629 = PCURVE('',#90630,#90635); +#90630 = PLANE('',#90631); +#90631 = AXIS2_PLACEMENT_3D('',#90632,#90633,#90634); +#90632 = CARTESIAN_POINT('',(2.15,10.527847992439,0.65)); +#90633 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90634 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90635 = DEFINITIONAL_REPRESENTATION('',(#90636),#90640); +#90636 = LINE('',#90637,#90638); +#90637 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90638 = VECTOR('',#90639,1.); +#90639 = DIRECTION('',(-1.,0.E+000)); +#90640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90641 = ORIENTED_EDGE('',*,*,#90642,.F.); +#90642 = EDGE_CURVE('',#90559,#90615,#90643,.T.); +#90643 = SURFACE_CURVE('',#90644,(#90648,#90655),.PCURVE_S1.); +#90644 = LINE('',#90645,#90646); +#90645 = CARTESIAN_POINT('',(2.35,10.,0.65)); +#90646 = VECTOR('',#90647,1.); +#90647 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90648 = PCURVE('',#88852,#90649); +#90649 = DEFINITIONAL_REPRESENTATION('',(#90650),#90654); +#90650 = LINE('',#90651,#90652); +#90651 = CARTESIAN_POINT('',(0.75,2.35)); +#90652 = VECTOR('',#90653,1.); +#90653 = DIRECTION('',(0.E+000,-1.)); +#90654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90655 = PCURVE('',#90656,#90661); +#90656 = PLANE('',#90657); +#90657 = AXIS2_PLACEMENT_3D('',#90658,#90659,#90660); +#90658 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); +#90659 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90660 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90661 = DEFINITIONAL_REPRESENTATION('',(#90662),#90666); +#90662 = LINE('',#90663,#90664); +#90663 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90664 = VECTOR('',#90665,1.); +#90665 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90667 = FACE_BOUND('',#90668,.T.); +#90668 = EDGE_LOOP('',(#90669,#90699,#90727,#90755)); +#90669 = ORIENTED_EDGE('',*,*,#90670,.F.); +#90670 = EDGE_CURVE('',#90671,#90673,#90675,.T.); +#90671 = VERTEX_POINT('',#90672); +#90672 = CARTESIAN_POINT('',(1.35,10.,0.75)); +#90673 = VERTEX_POINT('',#90674); +#90674 = CARTESIAN_POINT('',(1.35,10.,0.65)); +#90675 = SURFACE_CURVE('',#90676,(#90680,#90687),.PCURVE_S1.); +#90676 = LINE('',#90677,#90678); +#90677 = CARTESIAN_POINT('',(1.35,10.,0.65)); +#90678 = VECTOR('',#90679,1.); +#90679 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90680 = PCURVE('',#88852,#90681); +#90681 = DEFINITIONAL_REPRESENTATION('',(#90682),#90686); +#90682 = LINE('',#90683,#90684); +#90683 = CARTESIAN_POINT('',(0.75,1.35)); +#90684 = VECTOR('',#90685,1.); +#90685 = DIRECTION('',(1.,0.E+000)); +#90686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90687 = PCURVE('',#90688,#90693); +#90688 = PLANE('',#90689); +#90689 = AXIS2_PLACEMENT_3D('',#90690,#90691,#90692); +#90690 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); +#90691 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90692 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90693 = DEFINITIONAL_REPRESENTATION('',(#90694),#90698); +#90694 = LINE('',#90695,#90696); +#90695 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#90696 = VECTOR('',#90697,1.); +#90697 = DIRECTION('',(-1.,0.E+000)); +#90698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90699 = ORIENTED_EDGE('',*,*,#90700,.F.); +#90700 = EDGE_CURVE('',#90701,#90671,#90703,.T.); +#90701 = VERTEX_POINT('',#90702); +#90702 = CARTESIAN_POINT('',(1.15,10.,0.75)); +#90703 = SURFACE_CURVE('',#90704,(#90708,#90715),.PCURVE_S1.); +#90704 = LINE('',#90705,#90706); +#90705 = CARTESIAN_POINT('',(1.35,10.,0.75)); +#90706 = VECTOR('',#90707,1.); +#90707 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#90708 = PCURVE('',#88852,#90709); +#90709 = DEFINITIONAL_REPRESENTATION('',(#90710),#90714); +#90710 = LINE('',#90711,#90712); +#90711 = CARTESIAN_POINT('',(0.65,1.35)); +#90712 = VECTOR('',#90713,1.); +#90713 = DIRECTION('',(0.E+000,1.)); +#90714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90715 = PCURVE('',#90716,#90721); +#90716 = PLANE('',#90717); +#90717 = AXIS2_PLACEMENT_3D('',#90718,#90719,#90720); +#90718 = CARTESIAN_POINT('',(1.35,10.527847992439,0.75)); +#90719 = DIRECTION('',(-3.165136704051E-031,-3.563627120235E-016,-1.)); +#90720 = DIRECTION('',(0.E+000,1.,-3.563627120235E-016)); +#90721 = DEFINITIONAL_REPRESENTATION('',(#90722),#90726); +#90722 = LINE('',#90723,#90724); +#90723 = CARTESIAN_POINT('',(-0.527847992439,-1.074224064075E-047)); +#90724 = VECTOR('',#90725,1.); +#90725 = DIRECTION('',(-8.881784197001E-016,1.)); +#90726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90727 = ORIENTED_EDGE('',*,*,#90728,.F.); +#90728 = EDGE_CURVE('',#90729,#90701,#90731,.T.); +#90729 = VERTEX_POINT('',#90730); +#90730 = CARTESIAN_POINT('',(1.15,10.,0.65)); +#90731 = SURFACE_CURVE('',#90732,(#90736,#90743),.PCURVE_S1.); +#90732 = LINE('',#90733,#90734); +#90733 = CARTESIAN_POINT('',(1.15,10.,0.65)); +#90734 = VECTOR('',#90735,1.); +#90735 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90736 = PCURVE('',#88852,#90737); +#90737 = DEFINITIONAL_REPRESENTATION('',(#90738),#90742); +#90738 = LINE('',#90739,#90740); +#90739 = CARTESIAN_POINT('',(0.75,1.15)); +#90740 = VECTOR('',#90741,1.); +#90741 = DIRECTION('',(-1.,0.E+000)); +#90742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90743 = PCURVE('',#90744,#90749); +#90744 = PLANE('',#90745); +#90745 = AXIS2_PLACEMENT_3D('',#90746,#90747,#90748); +#90746 = CARTESIAN_POINT('',(1.15,10.527847992439,0.65)); +#90747 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90749 = DEFINITIONAL_REPRESENTATION('',(#90750),#90754); +#90750 = LINE('',#90751,#90752); +#90751 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#90752 = VECTOR('',#90753,1.); +#90753 = DIRECTION('',(-1.,0.E+000)); +#90754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90755 = ORIENTED_EDGE('',*,*,#90756,.F.); +#90756 = EDGE_CURVE('',#90673,#90729,#90757,.T.); +#90757 = SURFACE_CURVE('',#90758,(#90762,#90769),.PCURVE_S1.); +#90758 = LINE('',#90759,#90760); +#90759 = CARTESIAN_POINT('',(1.35,10.,0.65)); +#90760 = VECTOR('',#90761,1.); +#90761 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#90762 = PCURVE('',#88852,#90763); +#90763 = DEFINITIONAL_REPRESENTATION('',(#90764),#90768); +#90764 = LINE('',#90765,#90766); +#90765 = CARTESIAN_POINT('',(0.75,1.35)); +#90766 = VECTOR('',#90767,1.); +#90767 = DIRECTION('',(0.E+000,-1.)); +#90768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90769 = PCURVE('',#90770,#90775); +#90770 = PLANE('',#90771); +#90771 = AXIS2_PLACEMENT_3D('',#90772,#90773,#90774); +#90772 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); +#90773 = DIRECTION('',(3.165136704051E-031,3.563627120235E-016,1.)); +#90774 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#90775 = DEFINITIONAL_REPRESENTATION('',(#90776),#90780); +#90776 = LINE('',#90777,#90778); +#90777 = CARTESIAN_POINT('',(0.527847992439,-1.074224064075E-047)); +#90778 = VECTOR('',#90779,1.); +#90779 = DIRECTION('',(-8.881784197001E-016,-1.)); +#90780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90781 = ADVANCED_FACE('',(#90782,#90901,#91015,#91129,#91243,#91357, + #91471,#91585,#91699,#91808,#91922,#92036,#92150,#92264,#92378, + #92492,#92606),#90796,.F.); +#90782 = FACE_BOUND('',#90783,.T.); +#90783 = EDGE_LOOP('',(#90784,#90819,#90847,#90875)); +#90784 = ORIENTED_EDGE('',*,*,#90785,.F.); +#90785 = EDGE_CURVE('',#90786,#90788,#90790,.T.); +#90786 = VERTEX_POINT('',#90787); +#90787 = CARTESIAN_POINT('',(8.15,0.E+000,0.75)); +#90788 = VERTEX_POINT('',#90789); +#90789 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); +#90790 = SURFACE_CURVE('',#90791,(#90795,#90807),.PCURVE_S1.); +#90791 = LINE('',#90792,#90793); +#90792 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); +#90793 = VECTOR('',#90794,1.); +#90794 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90795 = PCURVE('',#90796,#90801); +#90796 = PLANE('',#90797); +#90797 = AXIS2_PLACEMENT_3D('',#90798,#90799,#90800); +#90798 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.4)); +#90799 = DIRECTION('',(0.E+000,1.,0.E+000)); +#90800 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90801 = DEFINITIONAL_REPRESENTATION('',(#90802),#90806); +#90802 = LINE('',#90803,#90804); +#90803 = CARTESIAN_POINT('',(-0.75,8.15)); +#90804 = VECTOR('',#90805,1.); +#90805 = DIRECTION('',(-1.,0.E+000)); +#90806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90807 = PCURVE('',#90808,#90813); +#90808 = PLANE('',#90809); +#90809 = AXIS2_PLACEMENT_3D('',#90810,#90811,#90812); +#90810 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); +#90811 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90812 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90813 = DEFINITIONAL_REPRESENTATION('',(#90814),#90818); +#90814 = LINE('',#90815,#90816); +#90815 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#90816 = VECTOR('',#90817,1.); +#90817 = DIRECTION('',(1.,0.E+000)); +#90818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90819 = ORIENTED_EDGE('',*,*,#90820,.F.); +#90820 = EDGE_CURVE('',#90821,#90786,#90823,.T.); +#90821 = VERTEX_POINT('',#90822); +#90822 = CARTESIAN_POINT('',(8.35,0.E+000,0.75)); +#90823 = SURFACE_CURVE('',#90824,(#90828,#90835),.PCURVE_S1.); +#90824 = LINE('',#90825,#90826); +#90825 = CARTESIAN_POINT('',(8.15,0.E+000,0.75)); +#90826 = VECTOR('',#90827,1.); +#90827 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90828 = PCURVE('',#90796,#90829); +#90829 = DEFINITIONAL_REPRESENTATION('',(#90830),#90834); +#90830 = LINE('',#90831,#90832); +#90831 = CARTESIAN_POINT('',(-0.65,8.15)); +#90832 = VECTOR('',#90833,1.); +#90833 = DIRECTION('',(0.E+000,-1.)); +#90834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90835 = PCURVE('',#90836,#90841); +#90836 = PLANE('',#90837); +#90837 = AXIS2_PLACEMENT_3D('',#90838,#90839,#90840); +#90838 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.75)); +#90839 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#90840 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#90841 = DEFINITIONAL_REPRESENTATION('',(#90842),#90846); +#90842 = LINE('',#90843,#90844); +#90843 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#90844 = VECTOR('',#90845,1.); +#90845 = DIRECTION('',(0.E+000,-1.)); +#90846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90847 = ORIENTED_EDGE('',*,*,#90848,.F.); +#90848 = EDGE_CURVE('',#90849,#90821,#90851,.T.); +#90849 = VERTEX_POINT('',#90850); +#90850 = CARTESIAN_POINT('',(8.35,0.E+000,0.65)); +#90851 = SURFACE_CURVE('',#90852,(#90856,#90863),.PCURVE_S1.); +#90852 = LINE('',#90853,#90854); +#90853 = CARTESIAN_POINT('',(8.35,0.E+000,0.65)); +#90854 = VECTOR('',#90855,1.); +#90855 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90856 = PCURVE('',#90796,#90857); +#90857 = DEFINITIONAL_REPRESENTATION('',(#90858),#90862); +#90858 = LINE('',#90859,#90860); +#90859 = CARTESIAN_POINT('',(-0.75,8.35)); +#90860 = VECTOR('',#90861,1.); +#90861 = DIRECTION('',(1.,0.E+000)); +#90862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90863 = PCURVE('',#90864,#90869); +#90864 = PLANE('',#90865); +#90865 = AXIS2_PLACEMENT_3D('',#90866,#90867,#90868); +#90866 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.65)); +#90867 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90868 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90869 = DEFINITIONAL_REPRESENTATION('',(#90870),#90874); +#90870 = LINE('',#90871,#90872); +#90871 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#90872 = VECTOR('',#90873,1.); +#90873 = DIRECTION('',(1.,0.E+000)); +#90874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90875 = ORIENTED_EDGE('',*,*,#90876,.F.); +#90876 = EDGE_CURVE('',#90788,#90849,#90877,.T.); +#90877 = SURFACE_CURVE('',#90878,(#90882,#90889),.PCURVE_S1.); +#90878 = LINE('',#90879,#90880); +#90879 = CARTESIAN_POINT('',(8.15,0.E+000,0.65)); +#90880 = VECTOR('',#90881,1.); +#90881 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90882 = PCURVE('',#90796,#90883); +#90883 = DEFINITIONAL_REPRESENTATION('',(#90884),#90888); +#90884 = LINE('',#90885,#90886); +#90885 = CARTESIAN_POINT('',(-0.75,8.15)); +#90886 = VECTOR('',#90887,1.); +#90887 = DIRECTION('',(0.E+000,1.)); +#90888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90889 = PCURVE('',#90890,#90895); +#90890 = PLANE('',#90891); +#90891 = AXIS2_PLACEMENT_3D('',#90892,#90893,#90894); +#90892 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); +#90893 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#90894 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#90895 = DEFINITIONAL_REPRESENTATION('',(#90896),#90900); +#90896 = LINE('',#90897,#90898); +#90897 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#90898 = VECTOR('',#90899,1.); +#90899 = DIRECTION('',(0.E+000,1.)); +#90900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90901 = FACE_BOUND('',#90902,.T.); +#90902 = EDGE_LOOP('',(#90903,#90933,#90961,#90989)); +#90903 = ORIENTED_EDGE('',*,*,#90904,.F.); +#90904 = EDGE_CURVE('',#90905,#90907,#90909,.T.); +#90905 = VERTEX_POINT('',#90906); +#90906 = CARTESIAN_POINT('',(7.15,0.E+000,0.75)); +#90907 = VERTEX_POINT('',#90908); +#90908 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); +#90909 = SURFACE_CURVE('',#90910,(#90914,#90921),.PCURVE_S1.); +#90910 = LINE('',#90911,#90912); +#90911 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); +#90912 = VECTOR('',#90913,1.); +#90913 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90914 = PCURVE('',#90796,#90915); +#90915 = DEFINITIONAL_REPRESENTATION('',(#90916),#90920); +#90916 = LINE('',#90917,#90918); +#90917 = CARTESIAN_POINT('',(-0.75,7.15)); +#90918 = VECTOR('',#90919,1.); +#90919 = DIRECTION('',(-1.,0.E+000)); +#90920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90921 = PCURVE('',#90922,#90927); +#90922 = PLANE('',#90923); +#90923 = AXIS2_PLACEMENT_3D('',#90924,#90925,#90926); +#90924 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); +#90925 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90926 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#90927 = DEFINITIONAL_REPRESENTATION('',(#90928),#90932); +#90928 = LINE('',#90929,#90930); +#90929 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#90930 = VECTOR('',#90931,1.); +#90931 = DIRECTION('',(1.,0.E+000)); +#90932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90933 = ORIENTED_EDGE('',*,*,#90934,.F.); +#90934 = EDGE_CURVE('',#90935,#90905,#90937,.T.); +#90935 = VERTEX_POINT('',#90936); +#90936 = CARTESIAN_POINT('',(7.35,0.E+000,0.75)); +#90937 = SURFACE_CURVE('',#90938,(#90942,#90949),.PCURVE_S1.); +#90938 = LINE('',#90939,#90940); +#90939 = CARTESIAN_POINT('',(7.15,0.E+000,0.75)); +#90940 = VECTOR('',#90941,1.); +#90941 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90942 = PCURVE('',#90796,#90943); +#90943 = DEFINITIONAL_REPRESENTATION('',(#90944),#90948); +#90944 = LINE('',#90945,#90946); +#90945 = CARTESIAN_POINT('',(-0.65,7.15)); +#90946 = VECTOR('',#90947,1.); +#90947 = DIRECTION('',(0.E+000,-1.)); +#90948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90949 = PCURVE('',#90950,#90955); +#90950 = PLANE('',#90951); +#90951 = AXIS2_PLACEMENT_3D('',#90952,#90953,#90954); +#90952 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.75)); +#90953 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#90954 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#90955 = DEFINITIONAL_REPRESENTATION('',(#90956),#90960); +#90956 = LINE('',#90957,#90958); +#90957 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#90958 = VECTOR('',#90959,1.); +#90959 = DIRECTION('',(0.E+000,-1.)); +#90960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90961 = ORIENTED_EDGE('',*,*,#90962,.F.); +#90962 = EDGE_CURVE('',#90963,#90935,#90965,.T.); +#90963 = VERTEX_POINT('',#90964); +#90964 = CARTESIAN_POINT('',(7.35,0.E+000,0.65)); +#90965 = SURFACE_CURVE('',#90966,(#90970,#90977),.PCURVE_S1.); +#90966 = LINE('',#90967,#90968); +#90967 = CARTESIAN_POINT('',(7.35,0.E+000,0.65)); +#90968 = VECTOR('',#90969,1.); +#90969 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90970 = PCURVE('',#90796,#90971); +#90971 = DEFINITIONAL_REPRESENTATION('',(#90972),#90976); +#90972 = LINE('',#90973,#90974); +#90973 = CARTESIAN_POINT('',(-0.75,7.35)); +#90974 = VECTOR('',#90975,1.); +#90975 = DIRECTION('',(1.,0.E+000)); +#90976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90977 = PCURVE('',#90978,#90983); +#90978 = PLANE('',#90979); +#90979 = AXIS2_PLACEMENT_3D('',#90980,#90981,#90982); +#90980 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.65)); +#90981 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#90982 = DIRECTION('',(0.E+000,0.E+000,1.)); +#90983 = DEFINITIONAL_REPRESENTATION('',(#90984),#90988); +#90984 = LINE('',#90985,#90986); +#90985 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#90986 = VECTOR('',#90987,1.); +#90987 = DIRECTION('',(1.,0.E+000)); +#90988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#90989 = ORIENTED_EDGE('',*,*,#90990,.F.); +#90990 = EDGE_CURVE('',#90907,#90963,#90991,.T.); +#90991 = SURFACE_CURVE('',#90992,(#90996,#91003),.PCURVE_S1.); +#90992 = LINE('',#90993,#90994); +#90993 = CARTESIAN_POINT('',(7.15,0.E+000,0.65)); +#90994 = VECTOR('',#90995,1.); +#90995 = DIRECTION('',(1.,0.E+000,0.E+000)); +#90996 = PCURVE('',#90796,#90997); +#90997 = DEFINITIONAL_REPRESENTATION('',(#90998),#91002); +#90998 = LINE('',#90999,#91000); +#90999 = CARTESIAN_POINT('',(-0.75,7.15)); +#91000 = VECTOR('',#91001,1.); +#91001 = DIRECTION('',(0.E+000,1.)); +#91002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91003 = PCURVE('',#91004,#91009); +#91004 = PLANE('',#91005); +#91005 = AXIS2_PLACEMENT_3D('',#91006,#91007,#91008); +#91006 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); +#91007 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91008 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91009 = DEFINITIONAL_REPRESENTATION('',(#91010),#91014); +#91010 = LINE('',#91011,#91012); +#91011 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91012 = VECTOR('',#91013,1.); +#91013 = DIRECTION('',(0.E+000,1.)); +#91014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91015 = FACE_BOUND('',#91016,.T.); +#91016 = EDGE_LOOP('',(#91017,#91047,#91075,#91103)); +#91017 = ORIENTED_EDGE('',*,*,#91018,.F.); +#91018 = EDGE_CURVE('',#91019,#91021,#91023,.T.); +#91019 = VERTEX_POINT('',#91020); +#91020 = CARTESIAN_POINT('',(6.15,0.E+000,0.75)); +#91021 = VERTEX_POINT('',#91022); +#91022 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); +#91023 = SURFACE_CURVE('',#91024,(#91028,#91035),.PCURVE_S1.); +#91024 = LINE('',#91025,#91026); +#91025 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); +#91026 = VECTOR('',#91027,1.); +#91027 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91028 = PCURVE('',#90796,#91029); +#91029 = DEFINITIONAL_REPRESENTATION('',(#91030),#91034); +#91030 = LINE('',#91031,#91032); +#91031 = CARTESIAN_POINT('',(-0.75,6.15)); +#91032 = VECTOR('',#91033,1.); +#91033 = DIRECTION('',(-1.,0.E+000)); +#91034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91035 = PCURVE('',#91036,#91041); +#91036 = PLANE('',#91037); +#91037 = AXIS2_PLACEMENT_3D('',#91038,#91039,#91040); +#91038 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); +#91039 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91040 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91041 = DEFINITIONAL_REPRESENTATION('',(#91042),#91046); +#91042 = LINE('',#91043,#91044); +#91043 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91044 = VECTOR('',#91045,1.); +#91045 = DIRECTION('',(1.,0.E+000)); +#91046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91047 = ORIENTED_EDGE('',*,*,#91048,.F.); +#91048 = EDGE_CURVE('',#91049,#91019,#91051,.T.); +#91049 = VERTEX_POINT('',#91050); +#91050 = CARTESIAN_POINT('',(6.35,0.E+000,0.75)); +#91051 = SURFACE_CURVE('',#91052,(#91056,#91063),.PCURVE_S1.); +#91052 = LINE('',#91053,#91054); +#91053 = CARTESIAN_POINT('',(6.15,0.E+000,0.75)); +#91054 = VECTOR('',#91055,1.); +#91055 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91056 = PCURVE('',#90796,#91057); +#91057 = DEFINITIONAL_REPRESENTATION('',(#91058),#91062); +#91058 = LINE('',#91059,#91060); +#91059 = CARTESIAN_POINT('',(-0.65,6.15)); +#91060 = VECTOR('',#91061,1.); +#91061 = DIRECTION('',(0.E+000,-1.)); +#91062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91063 = PCURVE('',#91064,#91069); +#91064 = PLANE('',#91065); +#91065 = AXIS2_PLACEMENT_3D('',#91066,#91067,#91068); +#91066 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.75)); +#91067 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91068 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91069 = DEFINITIONAL_REPRESENTATION('',(#91070),#91074); +#91070 = LINE('',#91071,#91072); +#91071 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91072 = VECTOR('',#91073,1.); +#91073 = DIRECTION('',(0.E+000,-1.)); +#91074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91075 = ORIENTED_EDGE('',*,*,#91076,.F.); +#91076 = EDGE_CURVE('',#91077,#91049,#91079,.T.); +#91077 = VERTEX_POINT('',#91078); +#91078 = CARTESIAN_POINT('',(6.35,0.E+000,0.65)); +#91079 = SURFACE_CURVE('',#91080,(#91084,#91091),.PCURVE_S1.); +#91080 = LINE('',#91081,#91082); +#91081 = CARTESIAN_POINT('',(6.35,0.E+000,0.65)); +#91082 = VECTOR('',#91083,1.); +#91083 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91084 = PCURVE('',#90796,#91085); +#91085 = DEFINITIONAL_REPRESENTATION('',(#91086),#91090); +#91086 = LINE('',#91087,#91088); +#91087 = CARTESIAN_POINT('',(-0.75,6.35)); +#91088 = VECTOR('',#91089,1.); +#91089 = DIRECTION('',(1.,0.E+000)); +#91090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91091 = PCURVE('',#91092,#91097); +#91092 = PLANE('',#91093); +#91093 = AXIS2_PLACEMENT_3D('',#91094,#91095,#91096); +#91094 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.65)); +#91095 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91096 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91097 = DEFINITIONAL_REPRESENTATION('',(#91098),#91102); +#91098 = LINE('',#91099,#91100); +#91099 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91100 = VECTOR('',#91101,1.); +#91101 = DIRECTION('',(1.,0.E+000)); +#91102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91103 = ORIENTED_EDGE('',*,*,#91104,.F.); +#91104 = EDGE_CURVE('',#91021,#91077,#91105,.T.); +#91105 = SURFACE_CURVE('',#91106,(#91110,#91117),.PCURVE_S1.); +#91106 = LINE('',#91107,#91108); +#91107 = CARTESIAN_POINT('',(6.15,0.E+000,0.65)); +#91108 = VECTOR('',#91109,1.); +#91109 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91110 = PCURVE('',#90796,#91111); +#91111 = DEFINITIONAL_REPRESENTATION('',(#91112),#91116); +#91112 = LINE('',#91113,#91114); +#91113 = CARTESIAN_POINT('',(-0.75,6.15)); +#91114 = VECTOR('',#91115,1.); +#91115 = DIRECTION('',(0.E+000,1.)); +#91116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91117 = PCURVE('',#91118,#91123); +#91118 = PLANE('',#91119); +#91119 = AXIS2_PLACEMENT_3D('',#91120,#91121,#91122); +#91120 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); +#91121 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91122 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91123 = DEFINITIONAL_REPRESENTATION('',(#91124),#91128); +#91124 = LINE('',#91125,#91126); +#91125 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91126 = VECTOR('',#91127,1.); +#91127 = DIRECTION('',(0.E+000,1.)); +#91128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91129 = FACE_BOUND('',#91130,.T.); +#91130 = EDGE_LOOP('',(#91131,#91161,#91189,#91217)); +#91131 = ORIENTED_EDGE('',*,*,#91132,.F.); +#91132 = EDGE_CURVE('',#91133,#91135,#91137,.T.); +#91133 = VERTEX_POINT('',#91134); +#91134 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); +#91135 = VERTEX_POINT('',#91136); +#91136 = CARTESIAN_POINT('',(4.85,0.E+000,0.75)); +#91137 = SURFACE_CURVE('',#91138,(#91142,#91149),.PCURVE_S1.); +#91138 = LINE('',#91139,#91140); +#91139 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); +#91140 = VECTOR('',#91141,1.); +#91141 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91142 = PCURVE('',#90796,#91143); +#91143 = DEFINITIONAL_REPRESENTATION('',(#91144),#91148); +#91144 = LINE('',#91145,#91146); +#91145 = CARTESIAN_POINT('',(-0.75,4.85)); +#91146 = VECTOR('',#91147,1.); +#91147 = DIRECTION('',(1.,0.E+000)); +#91148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91149 = PCURVE('',#91150,#91155); +#91150 = PLANE('',#91151); +#91151 = AXIS2_PLACEMENT_3D('',#91152,#91153,#91154); +#91152 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); +#91153 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91154 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91155 = DEFINITIONAL_REPRESENTATION('',(#91156),#91160); +#91156 = LINE('',#91157,#91158); +#91157 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91158 = VECTOR('',#91159,1.); +#91159 = DIRECTION('',(1.,0.E+000)); +#91160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91161 = ORIENTED_EDGE('',*,*,#91162,.F.); +#91162 = EDGE_CURVE('',#91163,#91133,#91165,.T.); +#91163 = VERTEX_POINT('',#91164); +#91164 = CARTESIAN_POINT('',(4.65,0.E+000,0.65)); +#91165 = SURFACE_CURVE('',#91166,(#91170,#91177),.PCURVE_S1.); +#91166 = LINE('',#91167,#91168); +#91167 = CARTESIAN_POINT('',(4.85,0.E+000,0.65)); +#91168 = VECTOR('',#91169,1.); +#91169 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91170 = PCURVE('',#90796,#91171); +#91171 = DEFINITIONAL_REPRESENTATION('',(#91172),#91176); +#91172 = LINE('',#91173,#91174); +#91173 = CARTESIAN_POINT('',(-0.75,4.85)); +#91174 = VECTOR('',#91175,1.); +#91175 = DIRECTION('',(0.E+000,1.)); +#91176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91177 = PCURVE('',#91178,#91183); +#91178 = PLANE('',#91179); +#91179 = AXIS2_PLACEMENT_3D('',#91180,#91181,#91182); +#91180 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); +#91181 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91182 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91183 = DEFINITIONAL_REPRESENTATION('',(#91184),#91188); +#91184 = LINE('',#91185,#91186); +#91185 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91186 = VECTOR('',#91187,1.); +#91187 = DIRECTION('',(0.E+000,1.)); +#91188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91189 = ORIENTED_EDGE('',*,*,#91190,.F.); +#91190 = EDGE_CURVE('',#91191,#91163,#91193,.T.); +#91191 = VERTEX_POINT('',#91192); +#91192 = CARTESIAN_POINT('',(4.65,0.E+000,0.75)); +#91193 = SURFACE_CURVE('',#91194,(#91198,#91205),.PCURVE_S1.); +#91194 = LINE('',#91195,#91196); +#91195 = CARTESIAN_POINT('',(4.65,0.E+000,0.65)); +#91196 = VECTOR('',#91197,1.); +#91197 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91198 = PCURVE('',#90796,#91199); +#91199 = DEFINITIONAL_REPRESENTATION('',(#91200),#91204); +#91200 = LINE('',#91201,#91202); +#91201 = CARTESIAN_POINT('',(-0.75,4.65)); +#91202 = VECTOR('',#91203,1.); +#91203 = DIRECTION('',(-1.,0.E+000)); +#91204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91205 = PCURVE('',#91206,#91211); +#91206 = PLANE('',#91207); +#91207 = AXIS2_PLACEMENT_3D('',#91208,#91209,#91210); +#91208 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.65)); +#91209 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91210 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91211 = DEFINITIONAL_REPRESENTATION('',(#91212),#91216); +#91212 = LINE('',#91213,#91214); +#91213 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91214 = VECTOR('',#91215,1.); +#91215 = DIRECTION('',(1.,0.E+000)); +#91216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91217 = ORIENTED_EDGE('',*,*,#91218,.F.); +#91218 = EDGE_CURVE('',#91135,#91191,#91219,.T.); +#91219 = SURFACE_CURVE('',#91220,(#91224,#91231),.PCURVE_S1.); +#91220 = LINE('',#91221,#91222); +#91221 = CARTESIAN_POINT('',(4.85,0.E+000,0.75)); +#91222 = VECTOR('',#91223,1.); +#91223 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91224 = PCURVE('',#90796,#91225); +#91225 = DEFINITIONAL_REPRESENTATION('',(#91226),#91230); +#91226 = LINE('',#91227,#91228); +#91227 = CARTESIAN_POINT('',(-0.65,4.85)); +#91228 = VECTOR('',#91229,1.); +#91229 = DIRECTION('',(0.E+000,-1.)); +#91230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91231 = PCURVE('',#91232,#91237); +#91232 = PLANE('',#91233); +#91233 = AXIS2_PLACEMENT_3D('',#91234,#91235,#91236); +#91234 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.75)); +#91235 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91236 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91237 = DEFINITIONAL_REPRESENTATION('',(#91238),#91242); +#91238 = LINE('',#91239,#91240); +#91239 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91240 = VECTOR('',#91241,1.); +#91241 = DIRECTION('',(0.E+000,-1.)); +#91242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91243 = FACE_BOUND('',#91244,.T.); +#91244 = EDGE_LOOP('',(#91245,#91275,#91303,#91331)); +#91245 = ORIENTED_EDGE('',*,*,#91246,.F.); +#91246 = EDGE_CURVE('',#91247,#91249,#91251,.T.); +#91247 = VERTEX_POINT('',#91248); +#91248 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); +#91249 = VERTEX_POINT('',#91250); +#91250 = CARTESIAN_POINT('',(3.85,0.E+000,0.75)); +#91251 = SURFACE_CURVE('',#91252,(#91256,#91263),.PCURVE_S1.); +#91252 = LINE('',#91253,#91254); +#91253 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); +#91254 = VECTOR('',#91255,1.); +#91255 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91256 = PCURVE('',#90796,#91257); +#91257 = DEFINITIONAL_REPRESENTATION('',(#91258),#91262); +#91258 = LINE('',#91259,#91260); +#91259 = CARTESIAN_POINT('',(-0.75,3.85)); +#91260 = VECTOR('',#91261,1.); +#91261 = DIRECTION('',(1.,0.E+000)); +#91262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91263 = PCURVE('',#91264,#91269); +#91264 = PLANE('',#91265); +#91265 = AXIS2_PLACEMENT_3D('',#91266,#91267,#91268); +#91266 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); +#91267 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91268 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91269 = DEFINITIONAL_REPRESENTATION('',(#91270),#91274); +#91270 = LINE('',#91271,#91272); +#91271 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91272 = VECTOR('',#91273,1.); +#91273 = DIRECTION('',(1.,0.E+000)); +#91274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91275 = ORIENTED_EDGE('',*,*,#91276,.F.); +#91276 = EDGE_CURVE('',#91277,#91247,#91279,.T.); +#91277 = VERTEX_POINT('',#91278); +#91278 = CARTESIAN_POINT('',(3.65,0.E+000,0.65)); +#91279 = SURFACE_CURVE('',#91280,(#91284,#91291),.PCURVE_S1.); +#91280 = LINE('',#91281,#91282); +#91281 = CARTESIAN_POINT('',(3.85,0.E+000,0.65)); +#91282 = VECTOR('',#91283,1.); +#91283 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91284 = PCURVE('',#90796,#91285); +#91285 = DEFINITIONAL_REPRESENTATION('',(#91286),#91290); +#91286 = LINE('',#91287,#91288); +#91287 = CARTESIAN_POINT('',(-0.75,3.85)); +#91288 = VECTOR('',#91289,1.); +#91289 = DIRECTION('',(0.E+000,1.)); +#91290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91291 = PCURVE('',#91292,#91297); +#91292 = PLANE('',#91293); +#91293 = AXIS2_PLACEMENT_3D('',#91294,#91295,#91296); +#91294 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); +#91295 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91296 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91297 = DEFINITIONAL_REPRESENTATION('',(#91298),#91302); +#91298 = LINE('',#91299,#91300); +#91299 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91300 = VECTOR('',#91301,1.); +#91301 = DIRECTION('',(0.E+000,1.)); +#91302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91303 = ORIENTED_EDGE('',*,*,#91304,.F.); +#91304 = EDGE_CURVE('',#91305,#91277,#91307,.T.); +#91305 = VERTEX_POINT('',#91306); +#91306 = CARTESIAN_POINT('',(3.65,0.E+000,0.75)); +#91307 = SURFACE_CURVE('',#91308,(#91312,#91319),.PCURVE_S1.); +#91308 = LINE('',#91309,#91310); +#91309 = CARTESIAN_POINT('',(3.65,0.E+000,0.65)); +#91310 = VECTOR('',#91311,1.); +#91311 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91312 = PCURVE('',#90796,#91313); +#91313 = DEFINITIONAL_REPRESENTATION('',(#91314),#91318); +#91314 = LINE('',#91315,#91316); +#91315 = CARTESIAN_POINT('',(-0.75,3.65)); +#91316 = VECTOR('',#91317,1.); +#91317 = DIRECTION('',(-1.,0.E+000)); +#91318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91319 = PCURVE('',#91320,#91325); +#91320 = PLANE('',#91321); +#91321 = AXIS2_PLACEMENT_3D('',#91322,#91323,#91324); +#91322 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.65)); +#91323 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91324 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91325 = DEFINITIONAL_REPRESENTATION('',(#91326),#91330); +#91326 = LINE('',#91327,#91328); +#91327 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91328 = VECTOR('',#91329,1.); +#91329 = DIRECTION('',(1.,0.E+000)); +#91330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91331 = ORIENTED_EDGE('',*,*,#91332,.F.); +#91332 = EDGE_CURVE('',#91249,#91305,#91333,.T.); +#91333 = SURFACE_CURVE('',#91334,(#91338,#91345),.PCURVE_S1.); +#91334 = LINE('',#91335,#91336); +#91335 = CARTESIAN_POINT('',(3.85,0.E+000,0.75)); +#91336 = VECTOR('',#91337,1.); +#91337 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91338 = PCURVE('',#90796,#91339); +#91339 = DEFINITIONAL_REPRESENTATION('',(#91340),#91344); +#91340 = LINE('',#91341,#91342); +#91341 = CARTESIAN_POINT('',(-0.65,3.85)); +#91342 = VECTOR('',#91343,1.); +#91343 = DIRECTION('',(0.E+000,-1.)); +#91344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91345 = PCURVE('',#91346,#91351); +#91346 = PLANE('',#91347); +#91347 = AXIS2_PLACEMENT_3D('',#91348,#91349,#91350); +#91348 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.75)); +#91349 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91350 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91351 = DEFINITIONAL_REPRESENTATION('',(#91352),#91356); +#91352 = LINE('',#91353,#91354); +#91353 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91354 = VECTOR('',#91355,1.); +#91355 = DIRECTION('',(0.E+000,-1.)); +#91356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91357 = FACE_BOUND('',#91358,.T.); +#91358 = EDGE_LOOP('',(#91359,#91389,#91417,#91445)); +#91359 = ORIENTED_EDGE('',*,*,#91360,.F.); +#91360 = EDGE_CURVE('',#91361,#91363,#91365,.T.); +#91361 = VERTEX_POINT('',#91362); +#91362 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); +#91363 = VERTEX_POINT('',#91364); +#91364 = CARTESIAN_POINT('',(2.85,0.E+000,0.75)); +#91365 = SURFACE_CURVE('',#91366,(#91370,#91377),.PCURVE_S1.); +#91366 = LINE('',#91367,#91368); +#91367 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); +#91368 = VECTOR('',#91369,1.); +#91369 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91370 = PCURVE('',#90796,#91371); +#91371 = DEFINITIONAL_REPRESENTATION('',(#91372),#91376); +#91372 = LINE('',#91373,#91374); +#91373 = CARTESIAN_POINT('',(-0.75,2.85)); +#91374 = VECTOR('',#91375,1.); +#91375 = DIRECTION('',(1.,0.E+000)); +#91376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91377 = PCURVE('',#91378,#91383); +#91378 = PLANE('',#91379); +#91379 = AXIS2_PLACEMENT_3D('',#91380,#91381,#91382); +#91380 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); +#91381 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91382 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91383 = DEFINITIONAL_REPRESENTATION('',(#91384),#91388); +#91384 = LINE('',#91385,#91386); +#91385 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91386 = VECTOR('',#91387,1.); +#91387 = DIRECTION('',(1.,0.E+000)); +#91388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91389 = ORIENTED_EDGE('',*,*,#91390,.F.); +#91390 = EDGE_CURVE('',#91391,#91361,#91393,.T.); +#91391 = VERTEX_POINT('',#91392); +#91392 = CARTESIAN_POINT('',(2.65,0.E+000,0.65)); +#91393 = SURFACE_CURVE('',#91394,(#91398,#91405),.PCURVE_S1.); +#91394 = LINE('',#91395,#91396); +#91395 = CARTESIAN_POINT('',(2.85,0.E+000,0.65)); +#91396 = VECTOR('',#91397,1.); +#91397 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91398 = PCURVE('',#90796,#91399); +#91399 = DEFINITIONAL_REPRESENTATION('',(#91400),#91404); +#91400 = LINE('',#91401,#91402); +#91401 = CARTESIAN_POINT('',(-0.75,2.85)); +#91402 = VECTOR('',#91403,1.); +#91403 = DIRECTION('',(0.E+000,1.)); +#91404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91405 = PCURVE('',#91406,#91411); +#91406 = PLANE('',#91407); +#91407 = AXIS2_PLACEMENT_3D('',#91408,#91409,#91410); +#91408 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); +#91409 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91410 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91411 = DEFINITIONAL_REPRESENTATION('',(#91412),#91416); +#91412 = LINE('',#91413,#91414); +#91413 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91414 = VECTOR('',#91415,1.); +#91415 = DIRECTION('',(0.E+000,1.)); +#91416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91417 = ORIENTED_EDGE('',*,*,#91418,.F.); +#91418 = EDGE_CURVE('',#91419,#91391,#91421,.T.); +#91419 = VERTEX_POINT('',#91420); +#91420 = CARTESIAN_POINT('',(2.65,0.E+000,0.75)); +#91421 = SURFACE_CURVE('',#91422,(#91426,#91433),.PCURVE_S1.); +#91422 = LINE('',#91423,#91424); +#91423 = CARTESIAN_POINT('',(2.65,0.E+000,0.65)); +#91424 = VECTOR('',#91425,1.); +#91425 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91426 = PCURVE('',#90796,#91427); +#91427 = DEFINITIONAL_REPRESENTATION('',(#91428),#91432); +#91428 = LINE('',#91429,#91430); +#91429 = CARTESIAN_POINT('',(-0.75,2.65)); +#91430 = VECTOR('',#91431,1.); +#91431 = DIRECTION('',(-1.,0.E+000)); +#91432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91433 = PCURVE('',#91434,#91439); +#91434 = PLANE('',#91435); +#91435 = AXIS2_PLACEMENT_3D('',#91436,#91437,#91438); +#91436 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.65)); +#91437 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91438 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91439 = DEFINITIONAL_REPRESENTATION('',(#91440),#91444); +#91440 = LINE('',#91441,#91442); +#91441 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91442 = VECTOR('',#91443,1.); +#91443 = DIRECTION('',(1.,0.E+000)); +#91444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91445 = ORIENTED_EDGE('',*,*,#91446,.F.); +#91446 = EDGE_CURVE('',#91363,#91419,#91447,.T.); +#91447 = SURFACE_CURVE('',#91448,(#91452,#91459),.PCURVE_S1.); +#91448 = LINE('',#91449,#91450); +#91449 = CARTESIAN_POINT('',(2.85,0.E+000,0.75)); +#91450 = VECTOR('',#91451,1.); +#91451 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91452 = PCURVE('',#90796,#91453); +#91453 = DEFINITIONAL_REPRESENTATION('',(#91454),#91458); +#91454 = LINE('',#91455,#91456); +#91455 = CARTESIAN_POINT('',(-0.65,2.85)); +#91456 = VECTOR('',#91457,1.); +#91457 = DIRECTION('',(0.E+000,-1.)); +#91458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91459 = PCURVE('',#91460,#91465); +#91460 = PLANE('',#91461); +#91461 = AXIS2_PLACEMENT_3D('',#91462,#91463,#91464); +#91462 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.75)); +#91463 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91464 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91465 = DEFINITIONAL_REPRESENTATION('',(#91466),#91470); +#91466 = LINE('',#91467,#91468); +#91467 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91468 = VECTOR('',#91469,1.); +#91469 = DIRECTION('',(0.E+000,-1.)); +#91470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91471 = FACE_BOUND('',#91472,.T.); +#91472 = EDGE_LOOP('',(#91473,#91503,#91531,#91559)); +#91473 = ORIENTED_EDGE('',*,*,#91474,.F.); +#91474 = EDGE_CURVE('',#91475,#91477,#91479,.T.); +#91475 = VERTEX_POINT('',#91476); +#91476 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); +#91477 = VERTEX_POINT('',#91478); +#91478 = CARTESIAN_POINT('',(1.85,0.E+000,0.75)); +#91479 = SURFACE_CURVE('',#91480,(#91484,#91491),.PCURVE_S1.); +#91480 = LINE('',#91481,#91482); +#91481 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); +#91482 = VECTOR('',#91483,1.); +#91483 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91484 = PCURVE('',#90796,#91485); +#91485 = DEFINITIONAL_REPRESENTATION('',(#91486),#91490); +#91486 = LINE('',#91487,#91488); +#91487 = CARTESIAN_POINT('',(-0.75,1.85)); +#91488 = VECTOR('',#91489,1.); +#91489 = DIRECTION('',(1.,0.E+000)); +#91490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91491 = PCURVE('',#91492,#91497); +#91492 = PLANE('',#91493); +#91493 = AXIS2_PLACEMENT_3D('',#91494,#91495,#91496); +#91494 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); +#91495 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91496 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91497 = DEFINITIONAL_REPRESENTATION('',(#91498),#91502); +#91498 = LINE('',#91499,#91500); +#91499 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91500 = VECTOR('',#91501,1.); +#91501 = DIRECTION('',(1.,0.E+000)); +#91502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91503 = ORIENTED_EDGE('',*,*,#91504,.F.); +#91504 = EDGE_CURVE('',#91505,#91475,#91507,.T.); +#91505 = VERTEX_POINT('',#91506); +#91506 = CARTESIAN_POINT('',(1.65,0.E+000,0.65)); +#91507 = SURFACE_CURVE('',#91508,(#91512,#91519),.PCURVE_S1.); +#91508 = LINE('',#91509,#91510); +#91509 = CARTESIAN_POINT('',(1.85,0.E+000,0.65)); +#91510 = VECTOR('',#91511,1.); +#91511 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91512 = PCURVE('',#90796,#91513); +#91513 = DEFINITIONAL_REPRESENTATION('',(#91514),#91518); +#91514 = LINE('',#91515,#91516); +#91515 = CARTESIAN_POINT('',(-0.75,1.85)); +#91516 = VECTOR('',#91517,1.); +#91517 = DIRECTION('',(0.E+000,1.)); +#91518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91519 = PCURVE('',#91520,#91525); +#91520 = PLANE('',#91521); +#91521 = AXIS2_PLACEMENT_3D('',#91522,#91523,#91524); +#91522 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); +#91523 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91524 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91525 = DEFINITIONAL_REPRESENTATION('',(#91526),#91530); +#91526 = LINE('',#91527,#91528); +#91527 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91528 = VECTOR('',#91529,1.); +#91529 = DIRECTION('',(0.E+000,1.)); +#91530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91531 = ORIENTED_EDGE('',*,*,#91532,.F.); +#91532 = EDGE_CURVE('',#91533,#91505,#91535,.T.); +#91533 = VERTEX_POINT('',#91534); +#91534 = CARTESIAN_POINT('',(1.65,0.E+000,0.75)); +#91535 = SURFACE_CURVE('',#91536,(#91540,#91547),.PCURVE_S1.); +#91536 = LINE('',#91537,#91538); +#91537 = CARTESIAN_POINT('',(1.65,0.E+000,0.65)); +#91538 = VECTOR('',#91539,1.); +#91539 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91540 = PCURVE('',#90796,#91541); +#91541 = DEFINITIONAL_REPRESENTATION('',(#91542),#91546); +#91542 = LINE('',#91543,#91544); +#91543 = CARTESIAN_POINT('',(-0.75,1.65)); +#91544 = VECTOR('',#91545,1.); +#91545 = DIRECTION('',(-1.,0.E+000)); +#91546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91547 = PCURVE('',#91548,#91553); +#91548 = PLANE('',#91549); +#91549 = AXIS2_PLACEMENT_3D('',#91550,#91551,#91552); +#91550 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.65)); +#91551 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91552 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91553 = DEFINITIONAL_REPRESENTATION('',(#91554),#91558); +#91554 = LINE('',#91555,#91556); +#91555 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91556 = VECTOR('',#91557,1.); +#91557 = DIRECTION('',(1.,0.E+000)); +#91558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91559 = ORIENTED_EDGE('',*,*,#91560,.F.); +#91560 = EDGE_CURVE('',#91477,#91533,#91561,.T.); +#91561 = SURFACE_CURVE('',#91562,(#91566,#91573),.PCURVE_S1.); +#91562 = LINE('',#91563,#91564); +#91563 = CARTESIAN_POINT('',(1.85,0.E+000,0.75)); +#91564 = VECTOR('',#91565,1.); +#91565 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91566 = PCURVE('',#90796,#91567); +#91567 = DEFINITIONAL_REPRESENTATION('',(#91568),#91572); +#91568 = LINE('',#91569,#91570); +#91569 = CARTESIAN_POINT('',(-0.65,1.85)); +#91570 = VECTOR('',#91571,1.); +#91571 = DIRECTION('',(0.E+000,-1.)); +#91572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91573 = PCURVE('',#91574,#91579); +#91574 = PLANE('',#91575); +#91575 = AXIS2_PLACEMENT_3D('',#91576,#91577,#91578); +#91576 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.75)); +#91577 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91578 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91579 = DEFINITIONAL_REPRESENTATION('',(#91580),#91584); +#91580 = LINE('',#91581,#91582); +#91581 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91582 = VECTOR('',#91583,1.); +#91583 = DIRECTION('',(0.E+000,-1.)); +#91584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91585 = FACE_BOUND('',#91586,.T.); +#91586 = EDGE_LOOP('',(#91587,#91617,#91645,#91673)); +#91587 = ORIENTED_EDGE('',*,*,#91588,.F.); +#91588 = EDGE_CURVE('',#91589,#91591,#91593,.T.); +#91589 = VERTEX_POINT('',#91590); +#91590 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); +#91591 = VERTEX_POINT('',#91592); +#91592 = CARTESIAN_POINT('',(1.35,0.E+000,0.75)); +#91593 = SURFACE_CURVE('',#91594,(#91598,#91605),.PCURVE_S1.); +#91594 = LINE('',#91595,#91596); +#91595 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); +#91596 = VECTOR('',#91597,1.); +#91597 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91598 = PCURVE('',#90796,#91599); +#91599 = DEFINITIONAL_REPRESENTATION('',(#91600),#91604); +#91600 = LINE('',#91601,#91602); +#91601 = CARTESIAN_POINT('',(-0.75,1.35)); +#91602 = VECTOR('',#91603,1.); +#91603 = DIRECTION('',(1.,0.E+000)); +#91604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91605 = PCURVE('',#91606,#91611); +#91606 = PLANE('',#91607); +#91607 = AXIS2_PLACEMENT_3D('',#91608,#91609,#91610); +#91608 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); +#91609 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91611 = DEFINITIONAL_REPRESENTATION('',(#91612),#91616); +#91612 = LINE('',#91613,#91614); +#91613 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91614 = VECTOR('',#91615,1.); +#91615 = DIRECTION('',(1.,0.E+000)); +#91616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91617 = ORIENTED_EDGE('',*,*,#91618,.F.); +#91618 = EDGE_CURVE('',#91619,#91589,#91621,.T.); +#91619 = VERTEX_POINT('',#91620); +#91620 = CARTESIAN_POINT('',(1.15,0.E+000,0.65)); +#91621 = SURFACE_CURVE('',#91622,(#91626,#91633),.PCURVE_S1.); +#91622 = LINE('',#91623,#91624); +#91623 = CARTESIAN_POINT('',(1.35,0.E+000,0.65)); +#91624 = VECTOR('',#91625,1.); +#91625 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91626 = PCURVE('',#90796,#91627); +#91627 = DEFINITIONAL_REPRESENTATION('',(#91628),#91632); +#91628 = LINE('',#91629,#91630); +#91629 = CARTESIAN_POINT('',(-0.75,1.35)); +#91630 = VECTOR('',#91631,1.); +#91631 = DIRECTION('',(0.E+000,1.)); +#91632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91633 = PCURVE('',#91634,#91639); +#91634 = PLANE('',#91635); +#91635 = AXIS2_PLACEMENT_3D('',#91636,#91637,#91638); +#91636 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); +#91637 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91638 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91639 = DEFINITIONAL_REPRESENTATION('',(#91640),#91644); +#91640 = LINE('',#91641,#91642); +#91641 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91642 = VECTOR('',#91643,1.); +#91643 = DIRECTION('',(0.E+000,1.)); +#91644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91645 = ORIENTED_EDGE('',*,*,#91646,.F.); +#91646 = EDGE_CURVE('',#91647,#91619,#91649,.T.); +#91647 = VERTEX_POINT('',#91648); +#91648 = CARTESIAN_POINT('',(1.15,0.E+000,0.75)); +#91649 = SURFACE_CURVE('',#91650,(#91654,#91661),.PCURVE_S1.); +#91650 = LINE('',#91651,#91652); +#91651 = CARTESIAN_POINT('',(1.15,0.E+000,0.65)); +#91652 = VECTOR('',#91653,1.); +#91653 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91654 = PCURVE('',#90796,#91655); +#91655 = DEFINITIONAL_REPRESENTATION('',(#91656),#91660); +#91656 = LINE('',#91657,#91658); +#91657 = CARTESIAN_POINT('',(-0.75,1.15)); +#91658 = VECTOR('',#91659,1.); +#91659 = DIRECTION('',(-1.,0.E+000)); +#91660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91661 = PCURVE('',#91662,#91667); +#91662 = PLANE('',#91663); +#91663 = AXIS2_PLACEMENT_3D('',#91664,#91665,#91666); +#91664 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.65)); +#91665 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91666 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91667 = DEFINITIONAL_REPRESENTATION('',(#91668),#91672); +#91668 = LINE('',#91669,#91670); +#91669 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91670 = VECTOR('',#91671,1.); +#91671 = DIRECTION('',(1.,0.E+000)); +#91672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91673 = ORIENTED_EDGE('',*,*,#91674,.F.); +#91674 = EDGE_CURVE('',#91591,#91647,#91675,.T.); +#91675 = SURFACE_CURVE('',#91676,(#91680,#91687),.PCURVE_S1.); +#91676 = LINE('',#91677,#91678); +#91677 = CARTESIAN_POINT('',(1.35,0.E+000,0.75)); +#91678 = VECTOR('',#91679,1.); +#91679 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91680 = PCURVE('',#90796,#91681); +#91681 = DEFINITIONAL_REPRESENTATION('',(#91682),#91686); +#91682 = LINE('',#91683,#91684); +#91683 = CARTESIAN_POINT('',(-0.65,1.35)); +#91684 = VECTOR('',#91685,1.); +#91685 = DIRECTION('',(0.E+000,-1.)); +#91686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91687 = PCURVE('',#91688,#91693); +#91688 = PLANE('',#91689); +#91689 = AXIS2_PLACEMENT_3D('',#91690,#91691,#91692); +#91690 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.75)); +#91691 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91692 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91693 = DEFINITIONAL_REPRESENTATION('',(#91694),#91698); +#91694 = LINE('',#91695,#91696); +#91695 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91696 = VECTOR('',#91697,1.); +#91697 = DIRECTION('',(0.E+000,-1.)); +#91698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91699 = FACE_BOUND('',#91700,.T.); +#91700 = EDGE_LOOP('',(#91701,#91731,#91759,#91782)); +#91701 = ORIENTED_EDGE('',*,*,#91702,.T.); +#91702 = EDGE_CURVE('',#91703,#91705,#91707,.T.); +#91703 = VERTEX_POINT('',#91704); +#91704 = CARTESIAN_POINT('',(9.8,0.E+000,1.2)); +#91705 = VERTEX_POINT('',#91706); +#91706 = CARTESIAN_POINT('',(0.2,0.E+000,1.2)); +#91707 = SURFACE_CURVE('',#91708,(#91712,#91719),.PCURVE_S1.); +#91708 = LINE('',#91709,#91710); +#91709 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.2)); +#91710 = VECTOR('',#91711,1.); +#91711 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91712 = PCURVE('',#90796,#91713); +#91713 = DEFINITIONAL_REPRESENTATION('',(#91714),#91718); +#91714 = LINE('',#91715,#91716); +#91715 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#91716 = VECTOR('',#91717,1.); +#91717 = DIRECTION('',(0.E+000,-1.)); +#91718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91719 = PCURVE('',#91720,#91725); +#91720 = PLANE('',#91721); +#91721 = AXIS2_PLACEMENT_3D('',#91722,#91723,#91724); +#91722 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); +#91723 = DIRECTION('',(0.E+000,0.707106781187,-0.707106781187)); +#91724 = DIRECTION('',(0.E+000,0.707106781187,0.707106781187)); +#91725 = DEFINITIONAL_REPRESENTATION('',(#91726),#91730); +#91726 = LINE('',#91727,#91728); +#91727 = CARTESIAN_POINT('',(-0.282842712475,0.E+000)); +#91728 = VECTOR('',#91729,1.); +#91729 = DIRECTION('',(0.E+000,-1.)); +#91730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91731 = ORIENTED_EDGE('',*,*,#91732,.T.); +#91732 = EDGE_CURVE('',#91705,#91733,#91735,.T.); +#91733 = VERTEX_POINT('',#91734); +#91734 = CARTESIAN_POINT('',(0.2,-8.673617379884E-016,0.E+000)); +#91735 = SURFACE_CURVE('',#91736,(#91740,#91747),.PCURVE_S1.); +#91736 = LINE('',#91737,#91738); +#91737 = CARTESIAN_POINT('',(0.2,0.E+000,1.4)); +#91738 = VECTOR('',#91739,1.); +#91739 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91740 = PCURVE('',#90796,#91741); +#91741 = DEFINITIONAL_REPRESENTATION('',(#91742),#91746); +#91742 = LINE('',#91743,#91744); +#91743 = CARTESIAN_POINT('',(0.E+000,0.2)); +#91744 = VECTOR('',#91745,1.); +#91745 = DIRECTION('',(-1.,0.E+000)); +#91746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91747 = PCURVE('',#91748,#91753); +#91748 = PLANE('',#91749); +#91749 = AXIS2_PLACEMENT_3D('',#91750,#91751,#91752); +#91750 = CARTESIAN_POINT('',(0.2,0.E+000,1.4)); +#91751 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#91752 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#91753 = DEFINITIONAL_REPRESENTATION('',(#91754),#91758); +#91754 = LINE('',#91755,#91756); +#91755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#91756 = VECTOR('',#91757,1.); +#91757 = DIRECTION('',(0.E+000,-1.)); +#91758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91759 = ORIENTED_EDGE('',*,*,#91760,.T.); +#91760 = EDGE_CURVE('',#91733,#91761,#91763,.T.); +#91761 = VERTEX_POINT('',#91762); +#91762 = CARTESIAN_POINT('',(9.8,0.E+000,0.E+000)); +#91763 = SURFACE_CURVE('',#91764,(#91768,#91775),.PCURVE_S1.); +#91764 = LINE('',#91765,#91766); +#91765 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#91766 = VECTOR('',#91767,1.); +#91767 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91768 = PCURVE('',#90796,#91769); +#91769 = DEFINITIONAL_REPRESENTATION('',(#91770),#91774); +#91770 = LINE('',#91771,#91772); +#91771 = CARTESIAN_POINT('',(-1.4,0.E+000)); +#91772 = VECTOR('',#91773,1.); +#91773 = DIRECTION('',(0.E+000,1.)); +#91774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91775 = PCURVE('',#88864,#91776); +#91776 = DEFINITIONAL_REPRESENTATION('',(#91777),#91781); +#91777 = LINE('',#91778,#91779); +#91778 = CARTESIAN_POINT('',(0.E+000,-10.)); +#91779 = VECTOR('',#91780,1.); +#91780 = DIRECTION('',(-1.,0.E+000)); +#91781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91782 = ORIENTED_EDGE('',*,*,#91783,.T.); +#91783 = EDGE_CURVE('',#91761,#91703,#91784,.T.); +#91784 = SURFACE_CURVE('',#91785,(#91789,#91796),.PCURVE_S1.); #91785 = LINE('',#91786,#91787); -#91786 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91786 = CARTESIAN_POINT('',(9.8,0.E+000,1.4)); #91787 = VECTOR('',#91788,1.); -#91788 = DIRECTION('',(1.,0.E+000)); -#91789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91790 = ORIENTED_EDGE('',*,*,#91791,.T.); -#91791 = EDGE_CURVE('',#91764,#91706,#91792,.T.); -#91792 = SURFACE_CURVE('',#91793,(#91797,#91804),.PCURVE_S1.); -#91793 = LINE('',#91794,#91795); -#91794 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.75)); -#91795 = VECTOR('',#91796,1.); -#91796 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91797 = PCURVE('',#90343,#91798); -#91798 = DEFINITIONAL_REPRESENTATION('',(#91799),#91803); -#91799 = LINE('',#91800,#91801); -#91800 = CARTESIAN_POINT('',(0.65,2.35)); -#91801 = VECTOR('',#91802,1.); -#91802 = DIRECTION('',(0.E+000,-1.)); -#91803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91804 = PCURVE('',#91805,#91810); -#91805 = PLANE('',#91806); -#91806 = AXIS2_PLACEMENT_3D('',#91807,#91808,#91809); -#91807 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.75)); -#91808 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91809 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91810 = DEFINITIONAL_REPRESENTATION('',(#91811),#91815); -#91811 = LINE('',#91812,#91813); -#91812 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91813 = VECTOR('',#91814,1.); -#91814 = DIRECTION('',(4.440892098501E-016,-1.)); -#91815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91816 = FACE_BOUND('',#91817,.T.); -#91817 = EDGE_LOOP('',(#91818,#91848,#91876,#91904)); -#91818 = ORIENTED_EDGE('',*,*,#91819,.T.); -#91819 = EDGE_CURVE('',#91820,#91822,#91824,.T.); -#91820 = VERTEX_POINT('',#91821); -#91821 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.75)); -#91822 = VERTEX_POINT('',#91823); -#91823 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.65)); -#91824 = SURFACE_CURVE('',#91825,(#91829,#91836),.PCURVE_S1.); -#91825 = LINE('',#91826,#91827); -#91826 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.65)); -#91827 = VECTOR('',#91828,1.); -#91828 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91829 = PCURVE('',#90343,#91830); -#91830 = DEFINITIONAL_REPRESENTATION('',(#91831),#91835); -#91831 = LINE('',#91832,#91833); -#91832 = CARTESIAN_POINT('',(0.75,1.65)); -#91833 = VECTOR('',#91834,1.); -#91834 = DIRECTION('',(1.,0.E+000)); -#91835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91836 = PCURVE('',#91837,#91842); -#91837 = PLANE('',#91838); -#91838 = AXIS2_PLACEMENT_3D('',#91839,#91840,#91841); -#91839 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.65)); -#91840 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91841 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91842 = DEFINITIONAL_REPRESENTATION('',(#91843),#91847); -#91843 = LINE('',#91844,#91845); -#91844 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91845 = VECTOR('',#91846,1.); -#91846 = DIRECTION('',(1.,0.E+000)); -#91847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91848 = ORIENTED_EDGE('',*,*,#91849,.T.); -#91849 = EDGE_CURVE('',#91822,#91850,#91852,.T.); -#91850 = VERTEX_POINT('',#91851); -#91851 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); -#91852 = SURFACE_CURVE('',#91853,(#91857,#91864),.PCURVE_S1.); -#91853 = LINE('',#91854,#91855); -#91854 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); -#91855 = VECTOR('',#91856,1.); -#91856 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91857 = PCURVE('',#90343,#91858); -#91858 = DEFINITIONAL_REPRESENTATION('',(#91859),#91863); -#91859 = LINE('',#91860,#91861); -#91860 = CARTESIAN_POINT('',(0.75,1.85)); -#91861 = VECTOR('',#91862,1.); -#91862 = DIRECTION('',(0.E+000,1.)); -#91863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91864 = PCURVE('',#91865,#91870); -#91865 = PLANE('',#91866); -#91866 = AXIS2_PLACEMENT_3D('',#91867,#91868,#91869); -#91867 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); -#91868 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#91869 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#91870 = DEFINITIONAL_REPRESENTATION('',(#91871),#91875); -#91871 = LINE('',#91872,#91873); -#91872 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#91873 = VECTOR('',#91874,1.); -#91874 = DIRECTION('',(4.440892098501E-016,1.)); -#91875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91876 = ORIENTED_EDGE('',*,*,#91877,.T.); -#91877 = EDGE_CURVE('',#91850,#91878,#91880,.T.); -#91878 = VERTEX_POINT('',#91879); -#91879 = CARTESIAN_POINT('',(0.E+000,1.85,0.75)); -#91880 = SURFACE_CURVE('',#91881,(#91885,#91892),.PCURVE_S1.); -#91881 = LINE('',#91882,#91883); -#91882 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); -#91883 = VECTOR('',#91884,1.); -#91884 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91885 = PCURVE('',#90343,#91886); -#91886 = DEFINITIONAL_REPRESENTATION('',(#91887),#91891); -#91887 = LINE('',#91888,#91889); -#91888 = CARTESIAN_POINT('',(0.75,1.85)); -#91889 = VECTOR('',#91890,1.); -#91890 = DIRECTION('',(-1.,0.E+000)); -#91891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91892 = PCURVE('',#91893,#91898); -#91893 = PLANE('',#91894); -#91894 = AXIS2_PLACEMENT_3D('',#91895,#91896,#91897); -#91895 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); -#91896 = DIRECTION('',(0.E+000,1.,0.E+000)); -#91897 = DIRECTION('',(0.E+000,0.E+000,1.)); -#91898 = DEFINITIONAL_REPRESENTATION('',(#91899),#91903); +#91788 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91789 = PCURVE('',#90796,#91790); +#91790 = DEFINITIONAL_REPRESENTATION('',(#91791),#91795); +#91791 = LINE('',#91792,#91793); +#91792 = CARTESIAN_POINT('',(0.E+000,9.8)); +#91793 = VECTOR('',#91794,1.); +#91794 = DIRECTION('',(1.,0.E+000)); +#91795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91796 = PCURVE('',#91797,#91802); +#91797 = PLANE('',#91798); +#91798 = AXIS2_PLACEMENT_3D('',#91799,#91800,#91801); +#91799 = CARTESIAN_POINT('',(10.,0.2,1.4)); +#91800 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#91801 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#91802 = DEFINITIONAL_REPRESENTATION('',(#91803),#91807); +#91803 = LINE('',#91804,#91805); +#91804 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); +#91805 = VECTOR('',#91806,1.); +#91806 = DIRECTION('',(0.E+000,1.)); +#91807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91808 = FACE_BOUND('',#91809,.T.); +#91809 = EDGE_LOOP('',(#91810,#91840,#91868,#91896)); +#91810 = ORIENTED_EDGE('',*,*,#91811,.F.); +#91811 = EDGE_CURVE('',#91812,#91814,#91816,.T.); +#91812 = VERTEX_POINT('',#91813); +#91813 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); +#91814 = VERTEX_POINT('',#91815); +#91815 = CARTESIAN_POINT('',(5.35,0.E+000,0.65)); +#91816 = SURFACE_CURVE('',#91817,(#91821,#91828),.PCURVE_S1.); +#91817 = LINE('',#91818,#91819); +#91818 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); +#91819 = VECTOR('',#91820,1.); +#91820 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91821 = PCURVE('',#90796,#91822); +#91822 = DEFINITIONAL_REPRESENTATION('',(#91823),#91827); +#91823 = LINE('',#91824,#91825); +#91824 = CARTESIAN_POINT('',(-0.75,5.15)); +#91825 = VECTOR('',#91826,1.); +#91826 = DIRECTION('',(0.E+000,1.)); +#91827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91828 = PCURVE('',#91829,#91834); +#91829 = PLANE('',#91830); +#91830 = AXIS2_PLACEMENT_3D('',#91831,#91832,#91833); +#91831 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); +#91832 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91833 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91834 = DEFINITIONAL_REPRESENTATION('',(#91835),#91839); +#91835 = LINE('',#91836,#91837); +#91836 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91837 = VECTOR('',#91838,1.); +#91838 = DIRECTION('',(0.E+000,1.)); +#91839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91840 = ORIENTED_EDGE('',*,*,#91841,.F.); +#91841 = EDGE_CURVE('',#91842,#91812,#91844,.T.); +#91842 = VERTEX_POINT('',#91843); +#91843 = CARTESIAN_POINT('',(5.15,0.E+000,0.75)); +#91844 = SURFACE_CURVE('',#91845,(#91849,#91856),.PCURVE_S1.); +#91845 = LINE('',#91846,#91847); +#91846 = CARTESIAN_POINT('',(5.15,0.E+000,0.65)); +#91847 = VECTOR('',#91848,1.); +#91848 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91849 = PCURVE('',#90796,#91850); +#91850 = DEFINITIONAL_REPRESENTATION('',(#91851),#91855); +#91851 = LINE('',#91852,#91853); +#91852 = CARTESIAN_POINT('',(-0.75,5.15)); +#91853 = VECTOR('',#91854,1.); +#91854 = DIRECTION('',(-1.,0.E+000)); +#91855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91856 = PCURVE('',#91857,#91862); +#91857 = PLANE('',#91858); +#91858 = AXIS2_PLACEMENT_3D('',#91859,#91860,#91861); +#91859 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); +#91860 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91861 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91862 = DEFINITIONAL_REPRESENTATION('',(#91863),#91867); +#91863 = LINE('',#91864,#91865); +#91864 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#91865 = VECTOR('',#91866,1.); +#91866 = DIRECTION('',(1.,0.E+000)); +#91867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91868 = ORIENTED_EDGE('',*,*,#91869,.F.); +#91869 = EDGE_CURVE('',#91870,#91842,#91872,.T.); +#91870 = VERTEX_POINT('',#91871); +#91871 = CARTESIAN_POINT('',(5.35,0.E+000,0.75)); +#91872 = SURFACE_CURVE('',#91873,(#91877,#91884),.PCURVE_S1.); +#91873 = LINE('',#91874,#91875); +#91874 = CARTESIAN_POINT('',(5.15,0.E+000,0.75)); +#91875 = VECTOR('',#91876,1.); +#91876 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91877 = PCURVE('',#90796,#91878); +#91878 = DEFINITIONAL_REPRESENTATION('',(#91879),#91883); +#91879 = LINE('',#91880,#91881); +#91880 = CARTESIAN_POINT('',(-0.65,5.15)); +#91881 = VECTOR('',#91882,1.); +#91882 = DIRECTION('',(0.E+000,-1.)); +#91883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91884 = PCURVE('',#91885,#91890); +#91885 = PLANE('',#91886); +#91886 = AXIS2_PLACEMENT_3D('',#91887,#91888,#91889); +#91887 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.75)); +#91888 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#91889 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#91890 = DEFINITIONAL_REPRESENTATION('',(#91891),#91895); +#91891 = LINE('',#91892,#91893); +#91892 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#91893 = VECTOR('',#91894,1.); +#91894 = DIRECTION('',(0.E+000,-1.)); +#91895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91896 = ORIENTED_EDGE('',*,*,#91897,.F.); +#91897 = EDGE_CURVE('',#91814,#91870,#91898,.T.); +#91898 = SURFACE_CURVE('',#91899,(#91903,#91910),.PCURVE_S1.); #91899 = LINE('',#91900,#91901); -#91900 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91900 = CARTESIAN_POINT('',(5.35,0.E+000,0.65)); #91901 = VECTOR('',#91902,1.); -#91902 = DIRECTION('',(1.,0.E+000)); -#91903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91904 = ORIENTED_EDGE('',*,*,#91905,.T.); -#91905 = EDGE_CURVE('',#91878,#91820,#91906,.T.); -#91906 = SURFACE_CURVE('',#91907,(#91911,#91918),.PCURVE_S1.); -#91907 = LINE('',#91908,#91909); -#91908 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.75)); -#91909 = VECTOR('',#91910,1.); -#91910 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91911 = PCURVE('',#90343,#91912); -#91912 = DEFINITIONAL_REPRESENTATION('',(#91913),#91917); -#91913 = LINE('',#91914,#91915); -#91914 = CARTESIAN_POINT('',(0.65,1.85)); -#91915 = VECTOR('',#91916,1.); -#91916 = DIRECTION('',(0.E+000,-1.)); -#91917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91918 = PCURVE('',#91919,#91924); -#91919 = PLANE('',#91920); -#91920 = AXIS2_PLACEMENT_3D('',#91921,#91922,#91923); -#91921 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.75)); -#91922 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91923 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91924 = DEFINITIONAL_REPRESENTATION('',(#91925),#91929); -#91925 = LINE('',#91926,#91927); -#91926 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91927 = VECTOR('',#91928,1.); -#91928 = DIRECTION('',(4.440892098501E-016,-1.)); -#91929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91930 = FACE_BOUND('',#91931,.T.); -#91931 = EDGE_LOOP('',(#91932,#91962,#91990,#92018)); -#91932 = ORIENTED_EDGE('',*,*,#91933,.T.); -#91933 = EDGE_CURVE('',#91934,#91936,#91938,.T.); -#91934 = VERTEX_POINT('',#91935); -#91935 = CARTESIAN_POINT('',(-2.375877272698E-015,5.35,0.75)); -#91936 = VERTEX_POINT('',#91937); -#91937 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.75)); -#91938 = SURFACE_CURVE('',#91939,(#91943,#91950),.PCURVE_S1.); -#91939 = LINE('',#91940,#91941); -#91940 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.75)); -#91941 = VECTOR('',#91942,1.); -#91942 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#91943 = PCURVE('',#90343,#91944); -#91944 = DEFINITIONAL_REPRESENTATION('',(#91945),#91949); -#91945 = LINE('',#91946,#91947); -#91946 = CARTESIAN_POINT('',(0.65,5.15)); -#91947 = VECTOR('',#91948,1.); -#91948 = DIRECTION('',(0.E+000,-1.)); -#91949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91950 = PCURVE('',#91951,#91956); -#91951 = PLANE('',#91952); -#91952 = AXIS2_PLACEMENT_3D('',#91953,#91954,#91955); -#91953 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.75)); -#91954 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#91955 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#91956 = DEFINITIONAL_REPRESENTATION('',(#91957),#91961); -#91957 = LINE('',#91958,#91959); -#91958 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#91959 = VECTOR('',#91960,1.); -#91960 = DIRECTION('',(4.440892098501E-016,-1.)); -#91961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91962 = ORIENTED_EDGE('',*,*,#91963,.T.); -#91963 = EDGE_CURVE('',#91936,#91964,#91966,.T.); -#91964 = VERTEX_POINT('',#91965); -#91965 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); -#91966 = SURFACE_CURVE('',#91967,(#91971,#91978),.PCURVE_S1.); -#91967 = LINE('',#91968,#91969); -#91968 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); -#91969 = VECTOR('',#91970,1.); -#91970 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91971 = PCURVE('',#90343,#91972); -#91972 = DEFINITIONAL_REPRESENTATION('',(#91973),#91977); -#91973 = LINE('',#91974,#91975); -#91974 = CARTESIAN_POINT('',(0.75,5.15)); -#91975 = VECTOR('',#91976,1.); -#91976 = DIRECTION('',(1.,0.E+000)); -#91977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91978 = PCURVE('',#91979,#91984); -#91979 = PLANE('',#91980); -#91980 = AXIS2_PLACEMENT_3D('',#91981,#91982,#91983); -#91981 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); -#91982 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#91983 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#91984 = DEFINITIONAL_REPRESENTATION('',(#91985),#91989); -#91985 = LINE('',#91986,#91987); -#91986 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#91987 = VECTOR('',#91988,1.); -#91988 = DIRECTION('',(1.,0.E+000)); -#91989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#91990 = ORIENTED_EDGE('',*,*,#91991,.T.); -#91991 = EDGE_CURVE('',#91964,#91992,#91994,.T.); -#91992 = VERTEX_POINT('',#91993); -#91993 = CARTESIAN_POINT('',(0.E+000,5.35,0.65)); -#91994 = SURFACE_CURVE('',#91995,(#91999,#92006),.PCURVE_S1.); -#91995 = LINE('',#91996,#91997); -#91996 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); -#91997 = VECTOR('',#91998,1.); -#91998 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#91999 = PCURVE('',#90343,#92000); -#92000 = DEFINITIONAL_REPRESENTATION('',(#92001),#92005); -#92001 = LINE('',#92002,#92003); -#92002 = CARTESIAN_POINT('',(0.75,5.15)); -#92003 = VECTOR('',#92004,1.); -#92004 = DIRECTION('',(0.E+000,1.)); -#92005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92006 = PCURVE('',#92007,#92012); -#92007 = PLANE('',#92008); -#92008 = AXIS2_PLACEMENT_3D('',#92009,#92010,#92011); -#92009 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); -#92010 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#92011 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#92012 = DEFINITIONAL_REPRESENTATION('',(#92013),#92017); +#91902 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91903 = PCURVE('',#90796,#91904); +#91904 = DEFINITIONAL_REPRESENTATION('',(#91905),#91909); +#91905 = LINE('',#91906,#91907); +#91906 = CARTESIAN_POINT('',(-0.75,5.35)); +#91907 = VECTOR('',#91908,1.); +#91908 = DIRECTION('',(1.,0.E+000)); +#91909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91910 = PCURVE('',#91911,#91916); +#91911 = PLANE('',#91912); +#91912 = AXIS2_PLACEMENT_3D('',#91913,#91914,#91915); +#91913 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.65)); +#91914 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91915 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91916 = DEFINITIONAL_REPRESENTATION('',(#91917),#91921); +#91917 = LINE('',#91918,#91919); +#91918 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91919 = VECTOR('',#91920,1.); +#91920 = DIRECTION('',(1.,0.E+000)); +#91921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91922 = FACE_BOUND('',#91923,.T.); +#91923 = EDGE_LOOP('',(#91924,#91954,#91982,#92010)); +#91924 = ORIENTED_EDGE('',*,*,#91925,.F.); +#91925 = EDGE_CURVE('',#91926,#91928,#91930,.T.); +#91926 = VERTEX_POINT('',#91927); +#91927 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); +#91928 = VERTEX_POINT('',#91929); +#91929 = CARTESIAN_POINT('',(2.35,0.E+000,0.75)); +#91930 = SURFACE_CURVE('',#91931,(#91935,#91942),.PCURVE_S1.); +#91931 = LINE('',#91932,#91933); +#91932 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); +#91933 = VECTOR('',#91934,1.); +#91934 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91935 = PCURVE('',#90796,#91936); +#91936 = DEFINITIONAL_REPRESENTATION('',(#91937),#91941); +#91937 = LINE('',#91938,#91939); +#91938 = CARTESIAN_POINT('',(-0.75,2.35)); +#91939 = VECTOR('',#91940,1.); +#91940 = DIRECTION('',(1.,0.E+000)); +#91941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91942 = PCURVE('',#91943,#91948); +#91943 = PLANE('',#91944); +#91944 = AXIS2_PLACEMENT_3D('',#91945,#91946,#91947); +#91945 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); +#91946 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#91947 = DIRECTION('',(0.E+000,0.E+000,1.)); +#91948 = DEFINITIONAL_REPRESENTATION('',(#91949),#91953); +#91949 = LINE('',#91950,#91951); +#91950 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#91951 = VECTOR('',#91952,1.); +#91952 = DIRECTION('',(1.,0.E+000)); +#91953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91954 = ORIENTED_EDGE('',*,*,#91955,.F.); +#91955 = EDGE_CURVE('',#91956,#91926,#91958,.T.); +#91956 = VERTEX_POINT('',#91957); +#91957 = CARTESIAN_POINT('',(2.15,0.E+000,0.65)); +#91958 = SURFACE_CURVE('',#91959,(#91963,#91970),.PCURVE_S1.); +#91959 = LINE('',#91960,#91961); +#91960 = CARTESIAN_POINT('',(2.35,0.E+000,0.65)); +#91961 = VECTOR('',#91962,1.); +#91962 = DIRECTION('',(1.,0.E+000,0.E+000)); +#91963 = PCURVE('',#90796,#91964); +#91964 = DEFINITIONAL_REPRESENTATION('',(#91965),#91969); +#91965 = LINE('',#91966,#91967); +#91966 = CARTESIAN_POINT('',(-0.75,2.35)); +#91967 = VECTOR('',#91968,1.); +#91968 = DIRECTION('',(0.E+000,1.)); +#91969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91970 = PCURVE('',#91971,#91976); +#91971 = PLANE('',#91972); +#91972 = AXIS2_PLACEMENT_3D('',#91973,#91974,#91975); +#91973 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); +#91974 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#91975 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#91976 = DEFINITIONAL_REPRESENTATION('',(#91977),#91981); +#91977 = LINE('',#91978,#91979); +#91978 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#91979 = VECTOR('',#91980,1.); +#91980 = DIRECTION('',(0.E+000,1.)); +#91981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91982 = ORIENTED_EDGE('',*,*,#91983,.F.); +#91983 = EDGE_CURVE('',#91984,#91956,#91986,.T.); +#91984 = VERTEX_POINT('',#91985); +#91985 = CARTESIAN_POINT('',(2.15,0.E+000,0.75)); +#91986 = SURFACE_CURVE('',#91987,(#91991,#91998),.PCURVE_S1.); +#91987 = LINE('',#91988,#91989); +#91988 = CARTESIAN_POINT('',(2.15,0.E+000,0.65)); +#91989 = VECTOR('',#91990,1.); +#91990 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#91991 = PCURVE('',#90796,#91992); +#91992 = DEFINITIONAL_REPRESENTATION('',(#91993),#91997); +#91993 = LINE('',#91994,#91995); +#91994 = CARTESIAN_POINT('',(-0.75,2.15)); +#91995 = VECTOR('',#91996,1.); +#91996 = DIRECTION('',(-1.,0.E+000)); +#91997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#91998 = PCURVE('',#91999,#92004); +#91999 = PLANE('',#92000); +#92000 = AXIS2_PLACEMENT_3D('',#92001,#92002,#92003); +#92001 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.65)); +#92002 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92003 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92004 = DEFINITIONAL_REPRESENTATION('',(#92005),#92009); +#92005 = LINE('',#92006,#92007); +#92006 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92007 = VECTOR('',#92008,1.); +#92008 = DIRECTION('',(1.,0.E+000)); +#92009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92010 = ORIENTED_EDGE('',*,*,#92011,.F.); +#92011 = EDGE_CURVE('',#91928,#91984,#92012,.T.); +#92012 = SURFACE_CURVE('',#92013,(#92017,#92024),.PCURVE_S1.); #92013 = LINE('',#92014,#92015); -#92014 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#92014 = CARTESIAN_POINT('',(2.35,0.E+000,0.75)); #92015 = VECTOR('',#92016,1.); -#92016 = DIRECTION('',(4.440892098501E-016,1.)); -#92017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92018 = ORIENTED_EDGE('',*,*,#92019,.T.); -#92019 = EDGE_CURVE('',#91992,#91934,#92020,.T.); -#92020 = SURFACE_CURVE('',#92021,(#92025,#92032),.PCURVE_S1.); -#92021 = LINE('',#92022,#92023); -#92022 = CARTESIAN_POINT('',(-2.375877272698E-015,5.35,0.65)); -#92023 = VECTOR('',#92024,1.); -#92024 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92025 = PCURVE('',#90343,#92026); -#92026 = DEFINITIONAL_REPRESENTATION('',(#92027),#92031); -#92027 = LINE('',#92028,#92029); -#92028 = CARTESIAN_POINT('',(0.75,5.35)); -#92029 = VECTOR('',#92030,1.); -#92030 = DIRECTION('',(-1.,0.E+000)); -#92031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92032 = PCURVE('',#92033,#92038); -#92033 = PLANE('',#92034); -#92034 = AXIS2_PLACEMENT_3D('',#92035,#92036,#92037); -#92035 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.65)); -#92036 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92037 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92038 = DEFINITIONAL_REPRESENTATION('',(#92039),#92043); -#92039 = LINE('',#92040,#92041); -#92040 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); -#92041 = VECTOR('',#92042,1.); -#92042 = DIRECTION('',(1.,0.E+000)); -#92043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92044 = FACE_BOUND('',#92045,.T.); -#92045 = EDGE_LOOP('',(#92046,#92076,#92104,#92132)); -#92046 = ORIENTED_EDGE('',*,*,#92047,.T.); -#92047 = EDGE_CURVE('',#92048,#92050,#92052,.T.); -#92048 = VERTEX_POINT('',#92049); -#92049 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.75)); -#92050 = VERTEX_POINT('',#92051); -#92051 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.65)); -#92052 = SURFACE_CURVE('',#92053,(#92057,#92064),.PCURVE_S1.); -#92053 = LINE('',#92054,#92055); -#92054 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.65)); -#92055 = VECTOR('',#92056,1.); -#92056 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92057 = PCURVE('',#90343,#92058); -#92058 = DEFINITIONAL_REPRESENTATION('',(#92059),#92063); -#92059 = LINE('',#92060,#92061); -#92060 = CARTESIAN_POINT('',(0.75,1.15)); -#92061 = VECTOR('',#92062,1.); -#92062 = DIRECTION('',(1.,0.E+000)); -#92063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92064 = PCURVE('',#92065,#92070); -#92065 = PLANE('',#92066); -#92066 = AXIS2_PLACEMENT_3D('',#92067,#92068,#92069); -#92067 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.65)); -#92068 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92069 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92070 = DEFINITIONAL_REPRESENTATION('',(#92071),#92075); -#92071 = LINE('',#92072,#92073); -#92072 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); -#92073 = VECTOR('',#92074,1.); -#92074 = DIRECTION('',(1.,0.E+000)); -#92075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92076 = ORIENTED_EDGE('',*,*,#92077,.T.); -#92077 = EDGE_CURVE('',#92050,#92078,#92080,.T.); -#92078 = VERTEX_POINT('',#92079); -#92079 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); -#92080 = SURFACE_CURVE('',#92081,(#92085,#92092),.PCURVE_S1.); -#92081 = LINE('',#92082,#92083); -#92082 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); -#92083 = VECTOR('',#92084,1.); -#92084 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#92085 = PCURVE('',#90343,#92086); -#92086 = DEFINITIONAL_REPRESENTATION('',(#92087),#92091); -#92087 = LINE('',#92088,#92089); -#92088 = CARTESIAN_POINT('',(0.75,1.35)); -#92089 = VECTOR('',#92090,1.); -#92090 = DIRECTION('',(0.E+000,1.)); -#92091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92092 = PCURVE('',#92093,#92098); -#92093 = PLANE('',#92094); -#92094 = AXIS2_PLACEMENT_3D('',#92095,#92096,#92097); -#92095 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); -#92096 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); -#92097 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); -#92098 = DEFINITIONAL_REPRESENTATION('',(#92099),#92103); -#92099 = LINE('',#92100,#92101); -#92100 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92101 = VECTOR('',#92102,1.); -#92102 = DIRECTION('',(4.440892098501E-016,1.)); -#92103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92104 = ORIENTED_EDGE('',*,*,#92105,.T.); -#92105 = EDGE_CURVE('',#92078,#92106,#92108,.T.); -#92106 = VERTEX_POINT('',#92107); -#92107 = CARTESIAN_POINT('',(0.E+000,1.35,0.75)); -#92108 = SURFACE_CURVE('',#92109,(#92113,#92120),.PCURVE_S1.); -#92109 = LINE('',#92110,#92111); -#92110 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); -#92111 = VECTOR('',#92112,1.); -#92112 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92113 = PCURVE('',#90343,#92114); -#92114 = DEFINITIONAL_REPRESENTATION('',(#92115),#92119); -#92115 = LINE('',#92116,#92117); -#92116 = CARTESIAN_POINT('',(0.75,1.35)); -#92117 = VECTOR('',#92118,1.); -#92118 = DIRECTION('',(-1.,0.E+000)); -#92119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92120 = PCURVE('',#92121,#92126); -#92121 = PLANE('',#92122); -#92122 = AXIS2_PLACEMENT_3D('',#92123,#92124,#92125); -#92123 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); -#92124 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92125 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92126 = DEFINITIONAL_REPRESENTATION('',(#92127),#92131); +#92016 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92017 = PCURVE('',#90796,#92018); +#92018 = DEFINITIONAL_REPRESENTATION('',(#92019),#92023); +#92019 = LINE('',#92020,#92021); +#92020 = CARTESIAN_POINT('',(-0.65,2.35)); +#92021 = VECTOR('',#92022,1.); +#92022 = DIRECTION('',(0.E+000,-1.)); +#92023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92024 = PCURVE('',#92025,#92030); +#92025 = PLANE('',#92026); +#92026 = AXIS2_PLACEMENT_3D('',#92027,#92028,#92029); +#92027 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.75)); +#92028 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92029 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92030 = DEFINITIONAL_REPRESENTATION('',(#92031),#92035); +#92031 = LINE('',#92032,#92033); +#92032 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92033 = VECTOR('',#92034,1.); +#92034 = DIRECTION('',(0.E+000,-1.)); +#92035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92036 = FACE_BOUND('',#92037,.T.); +#92037 = EDGE_LOOP('',(#92038,#92068,#92096,#92124)); +#92038 = ORIENTED_EDGE('',*,*,#92039,.F.); +#92039 = EDGE_CURVE('',#92040,#92042,#92044,.T.); +#92040 = VERTEX_POINT('',#92041); +#92041 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); +#92042 = VERTEX_POINT('',#92043); +#92043 = CARTESIAN_POINT('',(3.35,0.E+000,0.75)); +#92044 = SURFACE_CURVE('',#92045,(#92049,#92056),.PCURVE_S1.); +#92045 = LINE('',#92046,#92047); +#92046 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); +#92047 = VECTOR('',#92048,1.); +#92048 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92049 = PCURVE('',#90796,#92050); +#92050 = DEFINITIONAL_REPRESENTATION('',(#92051),#92055); +#92051 = LINE('',#92052,#92053); +#92052 = CARTESIAN_POINT('',(-0.75,3.35)); +#92053 = VECTOR('',#92054,1.); +#92054 = DIRECTION('',(1.,0.E+000)); +#92055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92056 = PCURVE('',#92057,#92062); +#92057 = PLANE('',#92058); +#92058 = AXIS2_PLACEMENT_3D('',#92059,#92060,#92061); +#92059 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); +#92060 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92061 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92062 = DEFINITIONAL_REPRESENTATION('',(#92063),#92067); +#92063 = LINE('',#92064,#92065); +#92064 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92065 = VECTOR('',#92066,1.); +#92066 = DIRECTION('',(1.,0.E+000)); +#92067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92068 = ORIENTED_EDGE('',*,*,#92069,.F.); +#92069 = EDGE_CURVE('',#92070,#92040,#92072,.T.); +#92070 = VERTEX_POINT('',#92071); +#92071 = CARTESIAN_POINT('',(3.15,0.E+000,0.65)); +#92072 = SURFACE_CURVE('',#92073,(#92077,#92084),.PCURVE_S1.); +#92073 = LINE('',#92074,#92075); +#92074 = CARTESIAN_POINT('',(3.35,0.E+000,0.65)); +#92075 = VECTOR('',#92076,1.); +#92076 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92077 = PCURVE('',#90796,#92078); +#92078 = DEFINITIONAL_REPRESENTATION('',(#92079),#92083); +#92079 = LINE('',#92080,#92081); +#92080 = CARTESIAN_POINT('',(-0.75,3.35)); +#92081 = VECTOR('',#92082,1.); +#92082 = DIRECTION('',(0.E+000,1.)); +#92083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92084 = PCURVE('',#92085,#92090); +#92085 = PLANE('',#92086); +#92086 = AXIS2_PLACEMENT_3D('',#92087,#92088,#92089); +#92087 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); +#92088 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92089 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92090 = DEFINITIONAL_REPRESENTATION('',(#92091),#92095); +#92091 = LINE('',#92092,#92093); +#92092 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92093 = VECTOR('',#92094,1.); +#92094 = DIRECTION('',(0.E+000,1.)); +#92095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92096 = ORIENTED_EDGE('',*,*,#92097,.F.); +#92097 = EDGE_CURVE('',#92098,#92070,#92100,.T.); +#92098 = VERTEX_POINT('',#92099); +#92099 = CARTESIAN_POINT('',(3.15,0.E+000,0.75)); +#92100 = SURFACE_CURVE('',#92101,(#92105,#92112),.PCURVE_S1.); +#92101 = LINE('',#92102,#92103); +#92102 = CARTESIAN_POINT('',(3.15,0.E+000,0.65)); +#92103 = VECTOR('',#92104,1.); +#92104 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92105 = PCURVE('',#90796,#92106); +#92106 = DEFINITIONAL_REPRESENTATION('',(#92107),#92111); +#92107 = LINE('',#92108,#92109); +#92108 = CARTESIAN_POINT('',(-0.75,3.15)); +#92109 = VECTOR('',#92110,1.); +#92110 = DIRECTION('',(-1.,0.E+000)); +#92111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92112 = PCURVE('',#92113,#92118); +#92113 = PLANE('',#92114); +#92114 = AXIS2_PLACEMENT_3D('',#92115,#92116,#92117); +#92115 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.65)); +#92116 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92117 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92118 = DEFINITIONAL_REPRESENTATION('',(#92119),#92123); +#92119 = LINE('',#92120,#92121); +#92120 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92121 = VECTOR('',#92122,1.); +#92122 = DIRECTION('',(1.,0.E+000)); +#92123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92124 = ORIENTED_EDGE('',*,*,#92125,.F.); +#92125 = EDGE_CURVE('',#92042,#92098,#92126,.T.); +#92126 = SURFACE_CURVE('',#92127,(#92131,#92138),.PCURVE_S1.); #92127 = LINE('',#92128,#92129); -#92128 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92128 = CARTESIAN_POINT('',(3.35,0.E+000,0.75)); #92129 = VECTOR('',#92130,1.); -#92130 = DIRECTION('',(1.,0.E+000)); -#92131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92132 = ORIENTED_EDGE('',*,*,#92133,.T.); -#92133 = EDGE_CURVE('',#92106,#92048,#92134,.T.); -#92134 = SURFACE_CURVE('',#92135,(#92139,#92146),.PCURVE_S1.); -#92135 = LINE('',#92136,#92137); -#92136 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.75)); -#92137 = VECTOR('',#92138,1.); -#92138 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#92139 = PCURVE('',#90343,#92140); -#92140 = DEFINITIONAL_REPRESENTATION('',(#92141),#92145); -#92141 = LINE('',#92142,#92143); -#92142 = CARTESIAN_POINT('',(0.65,1.35)); -#92143 = VECTOR('',#92144,1.); -#92144 = DIRECTION('',(0.E+000,-1.)); -#92145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92146 = PCURVE('',#92147,#92152); -#92147 = PLANE('',#92148); -#92148 = AXIS2_PLACEMENT_3D('',#92149,#92150,#92151); -#92149 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.75)); -#92150 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); -#92151 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#92152 = DEFINITIONAL_REPRESENTATION('',(#92153),#92157); -#92153 = LINE('',#92154,#92155); -#92154 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92155 = VECTOR('',#92156,1.); -#92156 = DIRECTION('',(4.440892098501E-016,-1.)); -#92157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92158 = FACE_BOUND('',#92159,.T.); -#92159 = EDGE_LOOP('',(#92160,#92185,#92208,#92236)); -#92160 = ORIENTED_EDGE('',*,*,#92161,.T.); -#92161 = EDGE_CURVE('',#92162,#92164,#92166,.T.); -#92162 = VERTEX_POINT('',#92163); -#92163 = CARTESIAN_POINT('',(-6.030874584451E-016,9.8,0.E+000)); -#92164 = VERTEX_POINT('',#92165); -#92165 = CARTESIAN_POINT('',(0.E+000,0.2,0.E+000)); -#92166 = SURFACE_CURVE('',#92167,(#92171,#92178),.PCURVE_S1.); -#92167 = LINE('',#92168,#92169); -#92168 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#92169 = VECTOR('',#92170,1.); -#92170 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92171 = PCURVE('',#90343,#92172); -#92172 = DEFINITIONAL_REPRESENTATION('',(#92173),#92177); -#92173 = LINE('',#92174,#92175); -#92174 = CARTESIAN_POINT('',(1.4,0.E+000)); -#92175 = VECTOR('',#92176,1.); -#92176 = DIRECTION('',(0.E+000,-1.)); -#92177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92178 = PCURVE('',#86472,#92179); -#92179 = DEFINITIONAL_REPRESENTATION('',(#92180),#92184); -#92180 = LINE('',#92181,#92182); -#92181 = CARTESIAN_POINT('',(0.E+000,-10.)); -#92182 = VECTOR('',#92183,1.); -#92183 = DIRECTION('',(0.E+000,-1.)); -#92184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92185 = ORIENTED_EDGE('',*,*,#92186,.T.); -#92186 = EDGE_CURVE('',#92164,#92187,#92189,.T.); -#92187 = VERTEX_POINT('',#92188); -#92188 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); -#92189 = SURFACE_CURVE('',#92190,(#92194,#92201),.PCURVE_S1.); -#92190 = LINE('',#92191,#92192); -#92191 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); -#92192 = VECTOR('',#92193,1.); -#92193 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92194 = PCURVE('',#90343,#92195); -#92195 = DEFINITIONAL_REPRESENTATION('',(#92196),#92200); -#92196 = LINE('',#92197,#92198); -#92197 = CARTESIAN_POINT('',(0.E+000,0.2)); -#92198 = VECTOR('',#92199,1.); -#92199 = DIRECTION('',(-1.,0.E+000)); -#92200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92201 = PCURVE('',#89356,#92202); -#92202 = DEFINITIONAL_REPRESENTATION('',(#92203),#92207); -#92203 = LINE('',#92204,#92205); -#92204 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); -#92205 = VECTOR('',#92206,1.); -#92206 = DIRECTION('',(0.E+000,1.)); -#92207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92208 = ORIENTED_EDGE('',*,*,#92209,.T.); -#92209 = EDGE_CURVE('',#92187,#92210,#92212,.T.); -#92210 = VERTEX_POINT('',#92211); -#92211 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); -#92212 = SURFACE_CURVE('',#92213,(#92217,#92224),.PCURVE_S1.); -#92213 = LINE('',#92214,#92215); -#92214 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.2)); -#92215 = VECTOR('',#92216,1.); -#92216 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92217 = PCURVE('',#90343,#92218); -#92218 = DEFINITIONAL_REPRESENTATION('',(#92219),#92223); -#92219 = LINE('',#92220,#92221); -#92220 = CARTESIAN_POINT('',(0.2,0.E+000)); -#92221 = VECTOR('',#92222,1.); -#92222 = DIRECTION('',(0.E+000,1.)); -#92223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92224 = PCURVE('',#92225,#92230); -#92225 = PLANE('',#92226); -#92226 = AXIS2_PLACEMENT_3D('',#92227,#92228,#92229); -#92227 = CARTESIAN_POINT('',(0.2,10.,1.4)); -#92228 = DIRECTION('',(0.707106781187,0.E+000,-0.707106781187)); -#92229 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); -#92230 = DEFINITIONAL_REPRESENTATION('',(#92231),#92235); -#92231 = LINE('',#92232,#92233); -#92232 = CARTESIAN_POINT('',(0.282842712475,-10.)); -#92233 = VECTOR('',#92234,1.); -#92234 = DIRECTION('',(0.E+000,1.)); -#92235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92236 = ORIENTED_EDGE('',*,*,#92237,.T.); -#92237 = EDGE_CURVE('',#92210,#92162,#92238,.T.); -#92238 = SURFACE_CURVE('',#92239,(#92243,#92250),.PCURVE_S1.); -#92239 = LINE('',#92240,#92241); -#92240 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); -#92241 = VECTOR('',#92242,1.); -#92242 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92243 = PCURVE('',#90343,#92244); -#92244 = DEFINITIONAL_REPRESENTATION('',(#92245),#92249); -#92245 = LINE('',#92246,#92247); -#92246 = CARTESIAN_POINT('',(0.E+000,9.8)); -#92247 = VECTOR('',#92248,1.); -#92248 = DIRECTION('',(1.,0.E+000)); -#92249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92250 = PCURVE('',#86500,#92251); -#92251 = DEFINITIONAL_REPRESENTATION('',(#92252),#92256); -#92252 = LINE('',#92253,#92254); -#92253 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#92254 = VECTOR('',#92255,1.); -#92255 = DIRECTION('',(0.E+000,-1.)); -#92256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92257 = ADVANCED_FACE('',(#92258,#92377,#92491,#92605,#92719,#92833, - #92947,#93061,#93175,#93289,#93403,#93517,#93631,#93745,#93859, - #93973,#94087),#92272,.F.); -#92258 = FACE_BOUND('',#92259,.T.); -#92259 = EDGE_LOOP('',(#92260,#92295,#92323,#92351)); -#92260 = ORIENTED_EDGE('',*,*,#92261,.T.); -#92261 = EDGE_CURVE('',#92262,#92264,#92266,.T.); -#92262 = VERTEX_POINT('',#92263); -#92263 = CARTESIAN_POINT('',(10.,1.35,0.75)); -#92264 = VERTEX_POINT('',#92265); -#92265 = CARTESIAN_POINT('',(10.,1.35,0.65)); -#92266 = SURFACE_CURVE('',#92267,(#92271,#92283),.PCURVE_S1.); -#92267 = LINE('',#92268,#92269); -#92268 = CARTESIAN_POINT('',(10.,1.35,0.65)); -#92269 = VECTOR('',#92270,1.); -#92270 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92271 = PCURVE('',#92272,#92277); -#92272 = PLANE('',#92273); -#92273 = AXIS2_PLACEMENT_3D('',#92274,#92275,#92276); -#92274 = CARTESIAN_POINT('',(10.,0.E+000,1.4)); -#92275 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#92276 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92277 = DEFINITIONAL_REPRESENTATION('',(#92278),#92282); -#92278 = LINE('',#92279,#92280); -#92279 = CARTESIAN_POINT('',(-0.75,1.35)); -#92280 = VECTOR('',#92281,1.); -#92281 = DIRECTION('',(-1.,0.E+000)); -#92282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92283 = PCURVE('',#92284,#92289); -#92284 = PLANE('',#92285); -#92285 = AXIS2_PLACEMENT_3D('',#92286,#92287,#92288); -#92286 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); -#92287 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92288 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92289 = DEFINITIONAL_REPRESENTATION('',(#92290),#92294); -#92290 = LINE('',#92291,#92292); -#92291 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92292 = VECTOR('',#92293,1.); -#92293 = DIRECTION('',(-1.,0.E+000)); -#92294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92295 = ORIENTED_EDGE('',*,*,#92296,.T.); -#92296 = EDGE_CURVE('',#92264,#92297,#92299,.T.); -#92297 = VERTEX_POINT('',#92298); -#92298 = CARTESIAN_POINT('',(10.,1.15,0.65)); -#92299 = SURFACE_CURVE('',#92300,(#92304,#92311),.PCURVE_S1.); -#92300 = LINE('',#92301,#92302); -#92301 = CARTESIAN_POINT('',(10.,1.35,0.65)); -#92302 = VECTOR('',#92303,1.); -#92303 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92304 = PCURVE('',#92272,#92305); -#92305 = DEFINITIONAL_REPRESENTATION('',(#92306),#92310); -#92306 = LINE('',#92307,#92308); -#92307 = CARTESIAN_POINT('',(-0.75,1.35)); -#92308 = VECTOR('',#92309,1.); -#92309 = DIRECTION('',(0.E+000,-1.)); -#92310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92311 = PCURVE('',#92312,#92317); -#92312 = PLANE('',#92313); -#92313 = AXIS2_PLACEMENT_3D('',#92314,#92315,#92316); -#92314 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); -#92315 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92316 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92317 = DEFINITIONAL_REPRESENTATION('',(#92318),#92322); -#92318 = LINE('',#92319,#92320); -#92319 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92320 = VECTOR('',#92321,1.); -#92321 = DIRECTION('',(4.440892098501E-016,-1.)); -#92322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92323 = ORIENTED_EDGE('',*,*,#92324,.T.); -#92324 = EDGE_CURVE('',#92297,#92325,#92327,.T.); -#92325 = VERTEX_POINT('',#92326); -#92326 = CARTESIAN_POINT('',(10.,1.15,0.75)); -#92327 = SURFACE_CURVE('',#92328,(#92332,#92339),.PCURVE_S1.); -#92328 = LINE('',#92329,#92330); -#92329 = CARTESIAN_POINT('',(10.,1.15,0.65)); -#92330 = VECTOR('',#92331,1.); -#92331 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92332 = PCURVE('',#92272,#92333); -#92333 = DEFINITIONAL_REPRESENTATION('',(#92334),#92338); -#92334 = LINE('',#92335,#92336); -#92335 = CARTESIAN_POINT('',(-0.75,1.15)); -#92336 = VECTOR('',#92337,1.); -#92337 = DIRECTION('',(1.,0.E+000)); -#92338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92339 = PCURVE('',#92340,#92345); -#92340 = PLANE('',#92341); -#92341 = AXIS2_PLACEMENT_3D('',#92342,#92343,#92344); -#92342 = CARTESIAN_POINT('',(10.527847992439,1.15,0.65)); -#92343 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92344 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92345 = DEFINITIONAL_REPRESENTATION('',(#92346),#92350); -#92346 = LINE('',#92347,#92348); -#92347 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92348 = VECTOR('',#92349,1.); -#92349 = DIRECTION('',(-1.,0.E+000)); -#92350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92351 = ORIENTED_EDGE('',*,*,#92352,.T.); -#92352 = EDGE_CURVE('',#92325,#92262,#92353,.T.); -#92353 = SURFACE_CURVE('',#92354,(#92358,#92365),.PCURVE_S1.); -#92354 = LINE('',#92355,#92356); -#92355 = CARTESIAN_POINT('',(10.,1.35,0.75)); -#92356 = VECTOR('',#92357,1.); -#92357 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92358 = PCURVE('',#92272,#92359); -#92359 = DEFINITIONAL_REPRESENTATION('',(#92360),#92364); -#92360 = LINE('',#92361,#92362); -#92361 = CARTESIAN_POINT('',(-0.65,1.35)); -#92362 = VECTOR('',#92363,1.); -#92363 = DIRECTION('',(0.E+000,1.)); -#92364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92365 = PCURVE('',#92366,#92371); -#92366 = PLANE('',#92367); -#92367 = AXIS2_PLACEMENT_3D('',#92368,#92369,#92370); -#92368 = CARTESIAN_POINT('',(10.527847992439,1.35,0.75)); -#92369 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92370 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92371 = DEFINITIONAL_REPRESENTATION('',(#92372),#92376); -#92372 = LINE('',#92373,#92374); -#92373 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92374 = VECTOR('',#92375,1.); -#92375 = DIRECTION('',(4.440892098501E-016,1.)); -#92376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92377 = FACE_BOUND('',#92378,.T.); -#92378 = EDGE_LOOP('',(#92379,#92409,#92437,#92465)); -#92379 = ORIENTED_EDGE('',*,*,#92380,.T.); -#92380 = EDGE_CURVE('',#92381,#92383,#92385,.T.); -#92381 = VERTEX_POINT('',#92382); -#92382 = CARTESIAN_POINT('',(10.,1.85,0.75)); -#92383 = VERTEX_POINT('',#92384); -#92384 = CARTESIAN_POINT('',(10.,1.85,0.65)); -#92385 = SURFACE_CURVE('',#92386,(#92390,#92397),.PCURVE_S1.); -#92386 = LINE('',#92387,#92388); -#92387 = CARTESIAN_POINT('',(10.,1.85,0.65)); -#92388 = VECTOR('',#92389,1.); -#92389 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92390 = PCURVE('',#92272,#92391); -#92391 = DEFINITIONAL_REPRESENTATION('',(#92392),#92396); -#92392 = LINE('',#92393,#92394); -#92393 = CARTESIAN_POINT('',(-0.75,1.85)); -#92394 = VECTOR('',#92395,1.); -#92395 = DIRECTION('',(-1.,0.E+000)); -#92396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92397 = PCURVE('',#92398,#92403); -#92398 = PLANE('',#92399); -#92399 = AXIS2_PLACEMENT_3D('',#92400,#92401,#92402); -#92400 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); -#92401 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92402 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92403 = DEFINITIONAL_REPRESENTATION('',(#92404),#92408); -#92404 = LINE('',#92405,#92406); -#92405 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92406 = VECTOR('',#92407,1.); -#92407 = DIRECTION('',(-1.,0.E+000)); -#92408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92409 = ORIENTED_EDGE('',*,*,#92410,.T.); -#92410 = EDGE_CURVE('',#92383,#92411,#92413,.T.); -#92411 = VERTEX_POINT('',#92412); -#92412 = CARTESIAN_POINT('',(10.,1.65,0.65)); -#92413 = SURFACE_CURVE('',#92414,(#92418,#92425),.PCURVE_S1.); -#92414 = LINE('',#92415,#92416); -#92415 = CARTESIAN_POINT('',(10.,1.85,0.65)); -#92416 = VECTOR('',#92417,1.); -#92417 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92418 = PCURVE('',#92272,#92419); -#92419 = DEFINITIONAL_REPRESENTATION('',(#92420),#92424); -#92420 = LINE('',#92421,#92422); -#92421 = CARTESIAN_POINT('',(-0.75,1.85)); -#92422 = VECTOR('',#92423,1.); -#92423 = DIRECTION('',(0.E+000,-1.)); -#92424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92425 = PCURVE('',#92426,#92431); -#92426 = PLANE('',#92427); -#92427 = AXIS2_PLACEMENT_3D('',#92428,#92429,#92430); -#92428 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); -#92429 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92430 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92431 = DEFINITIONAL_REPRESENTATION('',(#92432),#92436); -#92432 = LINE('',#92433,#92434); -#92433 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92434 = VECTOR('',#92435,1.); -#92435 = DIRECTION('',(4.440892098501E-016,-1.)); -#92436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92437 = ORIENTED_EDGE('',*,*,#92438,.T.); -#92438 = EDGE_CURVE('',#92411,#92439,#92441,.T.); -#92439 = VERTEX_POINT('',#92440); -#92440 = CARTESIAN_POINT('',(10.,1.65,0.75)); -#92441 = SURFACE_CURVE('',#92442,(#92446,#92453),.PCURVE_S1.); -#92442 = LINE('',#92443,#92444); -#92443 = CARTESIAN_POINT('',(10.,1.65,0.65)); -#92444 = VECTOR('',#92445,1.); -#92445 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92446 = PCURVE('',#92272,#92447); -#92447 = DEFINITIONAL_REPRESENTATION('',(#92448),#92452); -#92448 = LINE('',#92449,#92450); -#92449 = CARTESIAN_POINT('',(-0.75,1.65)); -#92450 = VECTOR('',#92451,1.); -#92451 = DIRECTION('',(1.,0.E+000)); -#92452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92453 = PCURVE('',#92454,#92459); -#92454 = PLANE('',#92455); -#92455 = AXIS2_PLACEMENT_3D('',#92456,#92457,#92458); -#92456 = CARTESIAN_POINT('',(10.527847992439,1.65,0.65)); -#92457 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92458 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92459 = DEFINITIONAL_REPRESENTATION('',(#92460),#92464); -#92460 = LINE('',#92461,#92462); -#92461 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92462 = VECTOR('',#92463,1.); -#92463 = DIRECTION('',(-1.,0.E+000)); -#92464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92465 = ORIENTED_EDGE('',*,*,#92466,.T.); -#92466 = EDGE_CURVE('',#92439,#92381,#92467,.T.); -#92467 = SURFACE_CURVE('',#92468,(#92472,#92479),.PCURVE_S1.); -#92468 = LINE('',#92469,#92470); -#92469 = CARTESIAN_POINT('',(10.,1.85,0.75)); -#92470 = VECTOR('',#92471,1.); -#92471 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92472 = PCURVE('',#92272,#92473); -#92473 = DEFINITIONAL_REPRESENTATION('',(#92474),#92478); -#92474 = LINE('',#92475,#92476); -#92475 = CARTESIAN_POINT('',(-0.65,1.85)); -#92476 = VECTOR('',#92477,1.); -#92477 = DIRECTION('',(0.E+000,1.)); -#92478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92479 = PCURVE('',#92480,#92485); -#92480 = PLANE('',#92481); -#92481 = AXIS2_PLACEMENT_3D('',#92482,#92483,#92484); -#92482 = CARTESIAN_POINT('',(10.527847992439,1.85,0.75)); -#92483 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92484 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92485 = DEFINITIONAL_REPRESENTATION('',(#92486),#92490); -#92486 = LINE('',#92487,#92488); -#92487 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92488 = VECTOR('',#92489,1.); -#92489 = DIRECTION('',(4.440892098501E-016,1.)); -#92490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92491 = FACE_BOUND('',#92492,.T.); -#92492 = EDGE_LOOP('',(#92493,#92523,#92551,#92579)); -#92493 = ORIENTED_EDGE('',*,*,#92494,.T.); -#92494 = EDGE_CURVE('',#92495,#92497,#92499,.T.); -#92495 = VERTEX_POINT('',#92496); -#92496 = CARTESIAN_POINT('',(10.,2.35,0.75)); -#92497 = VERTEX_POINT('',#92498); -#92498 = CARTESIAN_POINT('',(10.,2.35,0.65)); -#92499 = SURFACE_CURVE('',#92500,(#92504,#92511),.PCURVE_S1.); -#92500 = LINE('',#92501,#92502); -#92501 = CARTESIAN_POINT('',(10.,2.35,0.65)); -#92502 = VECTOR('',#92503,1.); -#92503 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92504 = PCURVE('',#92272,#92505); -#92505 = DEFINITIONAL_REPRESENTATION('',(#92506),#92510); -#92506 = LINE('',#92507,#92508); -#92507 = CARTESIAN_POINT('',(-0.75,2.35)); -#92508 = VECTOR('',#92509,1.); -#92509 = DIRECTION('',(-1.,0.E+000)); -#92510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92511 = PCURVE('',#92512,#92517); -#92512 = PLANE('',#92513); -#92513 = AXIS2_PLACEMENT_3D('',#92514,#92515,#92516); -#92514 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); -#92515 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92516 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92517 = DEFINITIONAL_REPRESENTATION('',(#92518),#92522); -#92518 = LINE('',#92519,#92520); -#92519 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92520 = VECTOR('',#92521,1.); -#92521 = DIRECTION('',(-1.,0.E+000)); -#92522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92523 = ORIENTED_EDGE('',*,*,#92524,.T.); -#92524 = EDGE_CURVE('',#92497,#92525,#92527,.T.); -#92525 = VERTEX_POINT('',#92526); -#92526 = CARTESIAN_POINT('',(10.,2.15,0.65)); -#92527 = SURFACE_CURVE('',#92528,(#92532,#92539),.PCURVE_S1.); -#92528 = LINE('',#92529,#92530); -#92529 = CARTESIAN_POINT('',(10.,2.35,0.65)); -#92530 = VECTOR('',#92531,1.); -#92531 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92532 = PCURVE('',#92272,#92533); -#92533 = DEFINITIONAL_REPRESENTATION('',(#92534),#92538); -#92534 = LINE('',#92535,#92536); -#92535 = CARTESIAN_POINT('',(-0.75,2.35)); -#92536 = VECTOR('',#92537,1.); -#92537 = DIRECTION('',(0.E+000,-1.)); -#92538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92539 = PCURVE('',#92540,#92545); -#92540 = PLANE('',#92541); -#92541 = AXIS2_PLACEMENT_3D('',#92542,#92543,#92544); -#92542 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); -#92543 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92544 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92545 = DEFINITIONAL_REPRESENTATION('',(#92546),#92550); -#92546 = LINE('',#92547,#92548); -#92547 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92548 = VECTOR('',#92549,1.); -#92549 = DIRECTION('',(4.440892098501E-016,-1.)); -#92550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92551 = ORIENTED_EDGE('',*,*,#92552,.T.); -#92552 = EDGE_CURVE('',#92525,#92553,#92555,.T.); -#92553 = VERTEX_POINT('',#92554); -#92554 = CARTESIAN_POINT('',(10.,2.15,0.75)); -#92555 = SURFACE_CURVE('',#92556,(#92560,#92567),.PCURVE_S1.); -#92556 = LINE('',#92557,#92558); -#92557 = CARTESIAN_POINT('',(10.,2.15,0.65)); -#92558 = VECTOR('',#92559,1.); -#92559 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92560 = PCURVE('',#92272,#92561); -#92561 = DEFINITIONAL_REPRESENTATION('',(#92562),#92566); -#92562 = LINE('',#92563,#92564); -#92563 = CARTESIAN_POINT('',(-0.75,2.15)); -#92564 = VECTOR('',#92565,1.); -#92565 = DIRECTION('',(1.,0.E+000)); -#92566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92567 = PCURVE('',#92568,#92573); -#92568 = PLANE('',#92569); -#92569 = AXIS2_PLACEMENT_3D('',#92570,#92571,#92572); -#92570 = CARTESIAN_POINT('',(10.527847992439,2.15,0.65)); -#92571 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92572 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92573 = DEFINITIONAL_REPRESENTATION('',(#92574),#92578); -#92574 = LINE('',#92575,#92576); -#92575 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92576 = VECTOR('',#92577,1.); -#92577 = DIRECTION('',(-1.,0.E+000)); -#92578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92579 = ORIENTED_EDGE('',*,*,#92580,.T.); -#92580 = EDGE_CURVE('',#92553,#92495,#92581,.T.); -#92581 = SURFACE_CURVE('',#92582,(#92586,#92593),.PCURVE_S1.); -#92582 = LINE('',#92583,#92584); -#92583 = CARTESIAN_POINT('',(10.,2.35,0.75)); -#92584 = VECTOR('',#92585,1.); -#92585 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92586 = PCURVE('',#92272,#92587); -#92587 = DEFINITIONAL_REPRESENTATION('',(#92588),#92592); -#92588 = LINE('',#92589,#92590); -#92589 = CARTESIAN_POINT('',(-0.65,2.35)); -#92590 = VECTOR('',#92591,1.); -#92591 = DIRECTION('',(0.E+000,1.)); -#92592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92593 = PCURVE('',#92594,#92599); -#92594 = PLANE('',#92595); -#92595 = AXIS2_PLACEMENT_3D('',#92596,#92597,#92598); -#92596 = CARTESIAN_POINT('',(10.527847992439,2.35,0.75)); -#92597 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92598 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92599 = DEFINITIONAL_REPRESENTATION('',(#92600),#92604); -#92600 = LINE('',#92601,#92602); -#92601 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92602 = VECTOR('',#92603,1.); -#92603 = DIRECTION('',(4.440892098501E-016,1.)); -#92604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92605 = FACE_BOUND('',#92606,.T.); -#92606 = EDGE_LOOP('',(#92607,#92637,#92665,#92693)); -#92607 = ORIENTED_EDGE('',*,*,#92608,.T.); -#92608 = EDGE_CURVE('',#92609,#92611,#92613,.T.); -#92609 = VERTEX_POINT('',#92610); -#92610 = CARTESIAN_POINT('',(10.,2.85,0.75)); -#92611 = VERTEX_POINT('',#92612); -#92612 = CARTESIAN_POINT('',(10.,2.85,0.65)); -#92613 = SURFACE_CURVE('',#92614,(#92618,#92625),.PCURVE_S1.); -#92614 = LINE('',#92615,#92616); -#92615 = CARTESIAN_POINT('',(10.,2.85,0.65)); -#92616 = VECTOR('',#92617,1.); -#92617 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92618 = PCURVE('',#92272,#92619); -#92619 = DEFINITIONAL_REPRESENTATION('',(#92620),#92624); -#92620 = LINE('',#92621,#92622); -#92621 = CARTESIAN_POINT('',(-0.75,2.85)); -#92622 = VECTOR('',#92623,1.); -#92623 = DIRECTION('',(-1.,0.E+000)); -#92624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92625 = PCURVE('',#92626,#92631); -#92626 = PLANE('',#92627); -#92627 = AXIS2_PLACEMENT_3D('',#92628,#92629,#92630); -#92628 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); -#92629 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92630 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92631 = DEFINITIONAL_REPRESENTATION('',(#92632),#92636); -#92632 = LINE('',#92633,#92634); -#92633 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92634 = VECTOR('',#92635,1.); -#92635 = DIRECTION('',(-1.,0.E+000)); -#92636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92637 = ORIENTED_EDGE('',*,*,#92638,.T.); -#92638 = EDGE_CURVE('',#92611,#92639,#92641,.T.); -#92639 = VERTEX_POINT('',#92640); -#92640 = CARTESIAN_POINT('',(10.,2.65,0.65)); -#92641 = SURFACE_CURVE('',#92642,(#92646,#92653),.PCURVE_S1.); -#92642 = LINE('',#92643,#92644); -#92643 = CARTESIAN_POINT('',(10.,2.85,0.65)); -#92644 = VECTOR('',#92645,1.); -#92645 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92646 = PCURVE('',#92272,#92647); -#92647 = DEFINITIONAL_REPRESENTATION('',(#92648),#92652); -#92648 = LINE('',#92649,#92650); -#92649 = CARTESIAN_POINT('',(-0.75,2.85)); -#92650 = VECTOR('',#92651,1.); -#92651 = DIRECTION('',(0.E+000,-1.)); -#92652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92653 = PCURVE('',#92654,#92659); -#92654 = PLANE('',#92655); -#92655 = AXIS2_PLACEMENT_3D('',#92656,#92657,#92658); -#92656 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); -#92657 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92658 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92659 = DEFINITIONAL_REPRESENTATION('',(#92660),#92664); -#92660 = LINE('',#92661,#92662); -#92661 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92662 = VECTOR('',#92663,1.); -#92663 = DIRECTION('',(4.440892098501E-016,-1.)); -#92664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92665 = ORIENTED_EDGE('',*,*,#92666,.T.); -#92666 = EDGE_CURVE('',#92639,#92667,#92669,.T.); -#92667 = VERTEX_POINT('',#92668); -#92668 = CARTESIAN_POINT('',(10.,2.65,0.75)); -#92669 = SURFACE_CURVE('',#92670,(#92674,#92681),.PCURVE_S1.); -#92670 = LINE('',#92671,#92672); -#92671 = CARTESIAN_POINT('',(10.,2.65,0.65)); -#92672 = VECTOR('',#92673,1.); -#92673 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92674 = PCURVE('',#92272,#92675); -#92675 = DEFINITIONAL_REPRESENTATION('',(#92676),#92680); -#92676 = LINE('',#92677,#92678); -#92677 = CARTESIAN_POINT('',(-0.75,2.65)); -#92678 = VECTOR('',#92679,1.); -#92679 = DIRECTION('',(1.,0.E+000)); -#92680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92681 = PCURVE('',#92682,#92687); -#92682 = PLANE('',#92683); -#92683 = AXIS2_PLACEMENT_3D('',#92684,#92685,#92686); -#92684 = CARTESIAN_POINT('',(10.527847992439,2.65,0.65)); -#92685 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92686 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92687 = DEFINITIONAL_REPRESENTATION('',(#92688),#92692); -#92688 = LINE('',#92689,#92690); -#92689 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92690 = VECTOR('',#92691,1.); -#92691 = DIRECTION('',(-1.,0.E+000)); -#92692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92693 = ORIENTED_EDGE('',*,*,#92694,.T.); -#92694 = EDGE_CURVE('',#92667,#92609,#92695,.T.); -#92695 = SURFACE_CURVE('',#92696,(#92700,#92707),.PCURVE_S1.); -#92696 = LINE('',#92697,#92698); -#92697 = CARTESIAN_POINT('',(10.,2.85,0.75)); -#92698 = VECTOR('',#92699,1.); -#92699 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92700 = PCURVE('',#92272,#92701); -#92701 = DEFINITIONAL_REPRESENTATION('',(#92702),#92706); -#92702 = LINE('',#92703,#92704); -#92703 = CARTESIAN_POINT('',(-0.65,2.85)); -#92704 = VECTOR('',#92705,1.); -#92705 = DIRECTION('',(0.E+000,1.)); -#92706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92707 = PCURVE('',#92708,#92713); -#92708 = PLANE('',#92709); -#92709 = AXIS2_PLACEMENT_3D('',#92710,#92711,#92712); -#92710 = CARTESIAN_POINT('',(10.527847992439,2.85,0.75)); -#92711 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92712 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92713 = DEFINITIONAL_REPRESENTATION('',(#92714),#92718); -#92714 = LINE('',#92715,#92716); -#92715 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92716 = VECTOR('',#92717,1.); -#92717 = DIRECTION('',(4.440892098501E-016,1.)); -#92718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92719 = FACE_BOUND('',#92720,.T.); -#92720 = EDGE_LOOP('',(#92721,#92751,#92779,#92807)); -#92721 = ORIENTED_EDGE('',*,*,#92722,.T.); -#92722 = EDGE_CURVE('',#92723,#92725,#92727,.T.); -#92723 = VERTEX_POINT('',#92724); -#92724 = CARTESIAN_POINT('',(10.,3.35,0.75)); +#92130 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92131 = PCURVE('',#90796,#92132); +#92132 = DEFINITIONAL_REPRESENTATION('',(#92133),#92137); +#92133 = LINE('',#92134,#92135); +#92134 = CARTESIAN_POINT('',(-0.65,3.35)); +#92135 = VECTOR('',#92136,1.); +#92136 = DIRECTION('',(0.E+000,-1.)); +#92137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92138 = PCURVE('',#92139,#92144); +#92139 = PLANE('',#92140); +#92140 = AXIS2_PLACEMENT_3D('',#92141,#92142,#92143); +#92141 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.75)); +#92142 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92143 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92144 = DEFINITIONAL_REPRESENTATION('',(#92145),#92149); +#92145 = LINE('',#92146,#92147); +#92146 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92147 = VECTOR('',#92148,1.); +#92148 = DIRECTION('',(0.E+000,-1.)); +#92149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92150 = FACE_BOUND('',#92151,.T.); +#92151 = EDGE_LOOP('',(#92152,#92182,#92210,#92238)); +#92152 = ORIENTED_EDGE('',*,*,#92153,.F.); +#92153 = EDGE_CURVE('',#92154,#92156,#92158,.T.); +#92154 = VERTEX_POINT('',#92155); +#92155 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); +#92156 = VERTEX_POINT('',#92157); +#92157 = CARTESIAN_POINT('',(4.35,0.E+000,0.75)); +#92158 = SURFACE_CURVE('',#92159,(#92163,#92170),.PCURVE_S1.); +#92159 = LINE('',#92160,#92161); +#92160 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); +#92161 = VECTOR('',#92162,1.); +#92162 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92163 = PCURVE('',#90796,#92164); +#92164 = DEFINITIONAL_REPRESENTATION('',(#92165),#92169); +#92165 = LINE('',#92166,#92167); +#92166 = CARTESIAN_POINT('',(-0.75,4.35)); +#92167 = VECTOR('',#92168,1.); +#92168 = DIRECTION('',(1.,0.E+000)); +#92169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92170 = PCURVE('',#92171,#92176); +#92171 = PLANE('',#92172); +#92172 = AXIS2_PLACEMENT_3D('',#92173,#92174,#92175); +#92173 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); +#92174 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92175 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92176 = DEFINITIONAL_REPRESENTATION('',(#92177),#92181); +#92177 = LINE('',#92178,#92179); +#92178 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92179 = VECTOR('',#92180,1.); +#92180 = DIRECTION('',(1.,0.E+000)); +#92181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92182 = ORIENTED_EDGE('',*,*,#92183,.F.); +#92183 = EDGE_CURVE('',#92184,#92154,#92186,.T.); +#92184 = VERTEX_POINT('',#92185); +#92185 = CARTESIAN_POINT('',(4.15,0.E+000,0.65)); +#92186 = SURFACE_CURVE('',#92187,(#92191,#92198),.PCURVE_S1.); +#92187 = LINE('',#92188,#92189); +#92188 = CARTESIAN_POINT('',(4.35,0.E+000,0.65)); +#92189 = VECTOR('',#92190,1.); +#92190 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92191 = PCURVE('',#90796,#92192); +#92192 = DEFINITIONAL_REPRESENTATION('',(#92193),#92197); +#92193 = LINE('',#92194,#92195); +#92194 = CARTESIAN_POINT('',(-0.75,4.35)); +#92195 = VECTOR('',#92196,1.); +#92196 = DIRECTION('',(0.E+000,1.)); +#92197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92198 = PCURVE('',#92199,#92204); +#92199 = PLANE('',#92200); +#92200 = AXIS2_PLACEMENT_3D('',#92201,#92202,#92203); +#92201 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); +#92202 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92203 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92204 = DEFINITIONAL_REPRESENTATION('',(#92205),#92209); +#92205 = LINE('',#92206,#92207); +#92206 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92207 = VECTOR('',#92208,1.); +#92208 = DIRECTION('',(0.E+000,1.)); +#92209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92210 = ORIENTED_EDGE('',*,*,#92211,.F.); +#92211 = EDGE_CURVE('',#92212,#92184,#92214,.T.); +#92212 = VERTEX_POINT('',#92213); +#92213 = CARTESIAN_POINT('',(4.15,0.E+000,0.75)); +#92214 = SURFACE_CURVE('',#92215,(#92219,#92226),.PCURVE_S1.); +#92215 = LINE('',#92216,#92217); +#92216 = CARTESIAN_POINT('',(4.15,0.E+000,0.65)); +#92217 = VECTOR('',#92218,1.); +#92218 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92219 = PCURVE('',#90796,#92220); +#92220 = DEFINITIONAL_REPRESENTATION('',(#92221),#92225); +#92221 = LINE('',#92222,#92223); +#92222 = CARTESIAN_POINT('',(-0.75,4.15)); +#92223 = VECTOR('',#92224,1.); +#92224 = DIRECTION('',(-1.,0.E+000)); +#92225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92226 = PCURVE('',#92227,#92232); +#92227 = PLANE('',#92228); +#92228 = AXIS2_PLACEMENT_3D('',#92229,#92230,#92231); +#92229 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.65)); +#92230 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92231 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92232 = DEFINITIONAL_REPRESENTATION('',(#92233),#92237); +#92233 = LINE('',#92234,#92235); +#92234 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92235 = VECTOR('',#92236,1.); +#92236 = DIRECTION('',(1.,0.E+000)); +#92237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92238 = ORIENTED_EDGE('',*,*,#92239,.F.); +#92239 = EDGE_CURVE('',#92156,#92212,#92240,.T.); +#92240 = SURFACE_CURVE('',#92241,(#92245,#92252),.PCURVE_S1.); +#92241 = LINE('',#92242,#92243); +#92242 = CARTESIAN_POINT('',(4.35,0.E+000,0.75)); +#92243 = VECTOR('',#92244,1.); +#92244 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92245 = PCURVE('',#90796,#92246); +#92246 = DEFINITIONAL_REPRESENTATION('',(#92247),#92251); +#92247 = LINE('',#92248,#92249); +#92248 = CARTESIAN_POINT('',(-0.65,4.35)); +#92249 = VECTOR('',#92250,1.); +#92250 = DIRECTION('',(0.E+000,-1.)); +#92251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92252 = PCURVE('',#92253,#92258); +#92253 = PLANE('',#92254); +#92254 = AXIS2_PLACEMENT_3D('',#92255,#92256,#92257); +#92255 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.75)); +#92256 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92257 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92258 = DEFINITIONAL_REPRESENTATION('',(#92259),#92263); +#92259 = LINE('',#92260,#92261); +#92260 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92261 = VECTOR('',#92262,1.); +#92262 = DIRECTION('',(0.E+000,-1.)); +#92263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92264 = FACE_BOUND('',#92265,.T.); +#92265 = EDGE_LOOP('',(#92266,#92296,#92324,#92352)); +#92266 = ORIENTED_EDGE('',*,*,#92267,.F.); +#92267 = EDGE_CURVE('',#92268,#92270,#92272,.T.); +#92268 = VERTEX_POINT('',#92269); +#92269 = CARTESIAN_POINT('',(5.65,0.E+000,0.75)); +#92270 = VERTEX_POINT('',#92271); +#92271 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); +#92272 = SURFACE_CURVE('',#92273,(#92277,#92284),.PCURVE_S1.); +#92273 = LINE('',#92274,#92275); +#92274 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); +#92275 = VECTOR('',#92276,1.); +#92276 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92277 = PCURVE('',#90796,#92278); +#92278 = DEFINITIONAL_REPRESENTATION('',(#92279),#92283); +#92279 = LINE('',#92280,#92281); +#92280 = CARTESIAN_POINT('',(-0.75,5.65)); +#92281 = VECTOR('',#92282,1.); +#92282 = DIRECTION('',(-1.,0.E+000)); +#92283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92284 = PCURVE('',#92285,#92290); +#92285 = PLANE('',#92286); +#92286 = AXIS2_PLACEMENT_3D('',#92287,#92288,#92289); +#92287 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); +#92288 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92289 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92290 = DEFINITIONAL_REPRESENTATION('',(#92291),#92295); +#92291 = LINE('',#92292,#92293); +#92292 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92293 = VECTOR('',#92294,1.); +#92294 = DIRECTION('',(1.,0.E+000)); +#92295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92296 = ORIENTED_EDGE('',*,*,#92297,.F.); +#92297 = EDGE_CURVE('',#92298,#92268,#92300,.T.); +#92298 = VERTEX_POINT('',#92299); +#92299 = CARTESIAN_POINT('',(5.85,0.E+000,0.75)); +#92300 = SURFACE_CURVE('',#92301,(#92305,#92312),.PCURVE_S1.); +#92301 = LINE('',#92302,#92303); +#92302 = CARTESIAN_POINT('',(5.65,0.E+000,0.75)); +#92303 = VECTOR('',#92304,1.); +#92304 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92305 = PCURVE('',#90796,#92306); +#92306 = DEFINITIONAL_REPRESENTATION('',(#92307),#92311); +#92307 = LINE('',#92308,#92309); +#92308 = CARTESIAN_POINT('',(-0.65,5.65)); +#92309 = VECTOR('',#92310,1.); +#92310 = DIRECTION('',(0.E+000,-1.)); +#92311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92312 = PCURVE('',#92313,#92318); +#92313 = PLANE('',#92314); +#92314 = AXIS2_PLACEMENT_3D('',#92315,#92316,#92317); +#92315 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.75)); +#92316 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92317 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92318 = DEFINITIONAL_REPRESENTATION('',(#92319),#92323); +#92319 = LINE('',#92320,#92321); +#92320 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92321 = VECTOR('',#92322,1.); +#92322 = DIRECTION('',(0.E+000,-1.)); +#92323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92324 = ORIENTED_EDGE('',*,*,#92325,.F.); +#92325 = EDGE_CURVE('',#92326,#92298,#92328,.T.); +#92326 = VERTEX_POINT('',#92327); +#92327 = CARTESIAN_POINT('',(5.85,0.E+000,0.65)); +#92328 = SURFACE_CURVE('',#92329,(#92333,#92340),.PCURVE_S1.); +#92329 = LINE('',#92330,#92331); +#92330 = CARTESIAN_POINT('',(5.85,0.E+000,0.65)); +#92331 = VECTOR('',#92332,1.); +#92332 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92333 = PCURVE('',#90796,#92334); +#92334 = DEFINITIONAL_REPRESENTATION('',(#92335),#92339); +#92335 = LINE('',#92336,#92337); +#92336 = CARTESIAN_POINT('',(-0.75,5.85)); +#92337 = VECTOR('',#92338,1.); +#92338 = DIRECTION('',(1.,0.E+000)); +#92339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92340 = PCURVE('',#92341,#92346); +#92341 = PLANE('',#92342); +#92342 = AXIS2_PLACEMENT_3D('',#92343,#92344,#92345); +#92343 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.65)); +#92344 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92346 = DEFINITIONAL_REPRESENTATION('',(#92347),#92351); +#92347 = LINE('',#92348,#92349); +#92348 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92349 = VECTOR('',#92350,1.); +#92350 = DIRECTION('',(1.,0.E+000)); +#92351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92352 = ORIENTED_EDGE('',*,*,#92353,.F.); +#92353 = EDGE_CURVE('',#92270,#92326,#92354,.T.); +#92354 = SURFACE_CURVE('',#92355,(#92359,#92366),.PCURVE_S1.); +#92355 = LINE('',#92356,#92357); +#92356 = CARTESIAN_POINT('',(5.65,0.E+000,0.65)); +#92357 = VECTOR('',#92358,1.); +#92358 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92359 = PCURVE('',#90796,#92360); +#92360 = DEFINITIONAL_REPRESENTATION('',(#92361),#92365); +#92361 = LINE('',#92362,#92363); +#92362 = CARTESIAN_POINT('',(-0.75,5.65)); +#92363 = VECTOR('',#92364,1.); +#92364 = DIRECTION('',(0.E+000,1.)); +#92365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92366 = PCURVE('',#92367,#92372); +#92367 = PLANE('',#92368); +#92368 = AXIS2_PLACEMENT_3D('',#92369,#92370,#92371); +#92369 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); +#92370 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92371 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92372 = DEFINITIONAL_REPRESENTATION('',(#92373),#92377); +#92373 = LINE('',#92374,#92375); +#92374 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92375 = VECTOR('',#92376,1.); +#92376 = DIRECTION('',(0.E+000,1.)); +#92377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92378 = FACE_BOUND('',#92379,.T.); +#92379 = EDGE_LOOP('',(#92380,#92410,#92438,#92466)); +#92380 = ORIENTED_EDGE('',*,*,#92381,.F.); +#92381 = EDGE_CURVE('',#92382,#92384,#92386,.T.); +#92382 = VERTEX_POINT('',#92383); +#92383 = CARTESIAN_POINT('',(6.65,0.E+000,0.75)); +#92384 = VERTEX_POINT('',#92385); +#92385 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); +#92386 = SURFACE_CURVE('',#92387,(#92391,#92398),.PCURVE_S1.); +#92387 = LINE('',#92388,#92389); +#92388 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); +#92389 = VECTOR('',#92390,1.); +#92390 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92391 = PCURVE('',#90796,#92392); +#92392 = DEFINITIONAL_REPRESENTATION('',(#92393),#92397); +#92393 = LINE('',#92394,#92395); +#92394 = CARTESIAN_POINT('',(-0.75,6.65)); +#92395 = VECTOR('',#92396,1.); +#92396 = DIRECTION('',(-1.,0.E+000)); +#92397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92398 = PCURVE('',#92399,#92404); +#92399 = PLANE('',#92400); +#92400 = AXIS2_PLACEMENT_3D('',#92401,#92402,#92403); +#92401 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); +#92402 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92403 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92404 = DEFINITIONAL_REPRESENTATION('',(#92405),#92409); +#92405 = LINE('',#92406,#92407); +#92406 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92407 = VECTOR('',#92408,1.); +#92408 = DIRECTION('',(1.,0.E+000)); +#92409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92410 = ORIENTED_EDGE('',*,*,#92411,.F.); +#92411 = EDGE_CURVE('',#92412,#92382,#92414,.T.); +#92412 = VERTEX_POINT('',#92413); +#92413 = CARTESIAN_POINT('',(6.85,0.E+000,0.75)); +#92414 = SURFACE_CURVE('',#92415,(#92419,#92426),.PCURVE_S1.); +#92415 = LINE('',#92416,#92417); +#92416 = CARTESIAN_POINT('',(6.65,0.E+000,0.75)); +#92417 = VECTOR('',#92418,1.); +#92418 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92419 = PCURVE('',#90796,#92420); +#92420 = DEFINITIONAL_REPRESENTATION('',(#92421),#92425); +#92421 = LINE('',#92422,#92423); +#92422 = CARTESIAN_POINT('',(-0.65,6.65)); +#92423 = VECTOR('',#92424,1.); +#92424 = DIRECTION('',(0.E+000,-1.)); +#92425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92426 = PCURVE('',#92427,#92432); +#92427 = PLANE('',#92428); +#92428 = AXIS2_PLACEMENT_3D('',#92429,#92430,#92431); +#92429 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.75)); +#92430 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92431 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92432 = DEFINITIONAL_REPRESENTATION('',(#92433),#92437); +#92433 = LINE('',#92434,#92435); +#92434 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92435 = VECTOR('',#92436,1.); +#92436 = DIRECTION('',(0.E+000,-1.)); +#92437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92438 = ORIENTED_EDGE('',*,*,#92439,.F.); +#92439 = EDGE_CURVE('',#92440,#92412,#92442,.T.); +#92440 = VERTEX_POINT('',#92441); +#92441 = CARTESIAN_POINT('',(6.85,0.E+000,0.65)); +#92442 = SURFACE_CURVE('',#92443,(#92447,#92454),.PCURVE_S1.); +#92443 = LINE('',#92444,#92445); +#92444 = CARTESIAN_POINT('',(6.85,0.E+000,0.65)); +#92445 = VECTOR('',#92446,1.); +#92446 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92447 = PCURVE('',#90796,#92448); +#92448 = DEFINITIONAL_REPRESENTATION('',(#92449),#92453); +#92449 = LINE('',#92450,#92451); +#92450 = CARTESIAN_POINT('',(-0.75,6.85)); +#92451 = VECTOR('',#92452,1.); +#92452 = DIRECTION('',(1.,0.E+000)); +#92453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92454 = PCURVE('',#92455,#92460); +#92455 = PLANE('',#92456); +#92456 = AXIS2_PLACEMENT_3D('',#92457,#92458,#92459); +#92457 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.65)); +#92458 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92459 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92460 = DEFINITIONAL_REPRESENTATION('',(#92461),#92465); +#92461 = LINE('',#92462,#92463); +#92462 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92463 = VECTOR('',#92464,1.); +#92464 = DIRECTION('',(1.,0.E+000)); +#92465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92466 = ORIENTED_EDGE('',*,*,#92467,.F.); +#92467 = EDGE_CURVE('',#92384,#92440,#92468,.T.); +#92468 = SURFACE_CURVE('',#92469,(#92473,#92480),.PCURVE_S1.); +#92469 = LINE('',#92470,#92471); +#92470 = CARTESIAN_POINT('',(6.65,0.E+000,0.65)); +#92471 = VECTOR('',#92472,1.); +#92472 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92473 = PCURVE('',#90796,#92474); +#92474 = DEFINITIONAL_REPRESENTATION('',(#92475),#92479); +#92475 = LINE('',#92476,#92477); +#92476 = CARTESIAN_POINT('',(-0.75,6.65)); +#92477 = VECTOR('',#92478,1.); +#92478 = DIRECTION('',(0.E+000,1.)); +#92479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92480 = PCURVE('',#92481,#92486); +#92481 = PLANE('',#92482); +#92482 = AXIS2_PLACEMENT_3D('',#92483,#92484,#92485); +#92483 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); +#92484 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92485 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92486 = DEFINITIONAL_REPRESENTATION('',(#92487),#92491); +#92487 = LINE('',#92488,#92489); +#92488 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92489 = VECTOR('',#92490,1.); +#92490 = DIRECTION('',(0.E+000,1.)); +#92491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92492 = FACE_BOUND('',#92493,.T.); +#92493 = EDGE_LOOP('',(#92494,#92524,#92552,#92580)); +#92494 = ORIENTED_EDGE('',*,*,#92495,.F.); +#92495 = EDGE_CURVE('',#92496,#92498,#92500,.T.); +#92496 = VERTEX_POINT('',#92497); +#92497 = CARTESIAN_POINT('',(7.65,0.E+000,0.75)); +#92498 = VERTEX_POINT('',#92499); +#92499 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); +#92500 = SURFACE_CURVE('',#92501,(#92505,#92512),.PCURVE_S1.); +#92501 = LINE('',#92502,#92503); +#92502 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); +#92503 = VECTOR('',#92504,1.); +#92504 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92505 = PCURVE('',#90796,#92506); +#92506 = DEFINITIONAL_REPRESENTATION('',(#92507),#92511); +#92507 = LINE('',#92508,#92509); +#92508 = CARTESIAN_POINT('',(-0.75,7.65)); +#92509 = VECTOR('',#92510,1.); +#92510 = DIRECTION('',(-1.,0.E+000)); +#92511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92512 = PCURVE('',#92513,#92518); +#92513 = PLANE('',#92514); +#92514 = AXIS2_PLACEMENT_3D('',#92515,#92516,#92517); +#92515 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); +#92516 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92517 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92518 = DEFINITIONAL_REPRESENTATION('',(#92519),#92523); +#92519 = LINE('',#92520,#92521); +#92520 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92521 = VECTOR('',#92522,1.); +#92522 = DIRECTION('',(1.,0.E+000)); +#92523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92524 = ORIENTED_EDGE('',*,*,#92525,.F.); +#92525 = EDGE_CURVE('',#92526,#92496,#92528,.T.); +#92526 = VERTEX_POINT('',#92527); +#92527 = CARTESIAN_POINT('',(7.85,0.E+000,0.75)); +#92528 = SURFACE_CURVE('',#92529,(#92533,#92540),.PCURVE_S1.); +#92529 = LINE('',#92530,#92531); +#92530 = CARTESIAN_POINT('',(7.65,0.E+000,0.75)); +#92531 = VECTOR('',#92532,1.); +#92532 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92533 = PCURVE('',#90796,#92534); +#92534 = DEFINITIONAL_REPRESENTATION('',(#92535),#92539); +#92535 = LINE('',#92536,#92537); +#92536 = CARTESIAN_POINT('',(-0.65,7.65)); +#92537 = VECTOR('',#92538,1.); +#92538 = DIRECTION('',(0.E+000,-1.)); +#92539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92540 = PCURVE('',#92541,#92546); +#92541 = PLANE('',#92542); +#92542 = AXIS2_PLACEMENT_3D('',#92543,#92544,#92545); +#92543 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.75)); +#92544 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92545 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92546 = DEFINITIONAL_REPRESENTATION('',(#92547),#92551); +#92547 = LINE('',#92548,#92549); +#92548 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92549 = VECTOR('',#92550,1.); +#92550 = DIRECTION('',(0.E+000,-1.)); +#92551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92552 = ORIENTED_EDGE('',*,*,#92553,.F.); +#92553 = EDGE_CURVE('',#92554,#92526,#92556,.T.); +#92554 = VERTEX_POINT('',#92555); +#92555 = CARTESIAN_POINT('',(7.85,0.E+000,0.65)); +#92556 = SURFACE_CURVE('',#92557,(#92561,#92568),.PCURVE_S1.); +#92557 = LINE('',#92558,#92559); +#92558 = CARTESIAN_POINT('',(7.85,0.E+000,0.65)); +#92559 = VECTOR('',#92560,1.); +#92560 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92561 = PCURVE('',#90796,#92562); +#92562 = DEFINITIONAL_REPRESENTATION('',(#92563),#92567); +#92563 = LINE('',#92564,#92565); +#92564 = CARTESIAN_POINT('',(-0.75,7.85)); +#92565 = VECTOR('',#92566,1.); +#92566 = DIRECTION('',(1.,0.E+000)); +#92567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92568 = PCURVE('',#92569,#92574); +#92569 = PLANE('',#92570); +#92570 = AXIS2_PLACEMENT_3D('',#92571,#92572,#92573); +#92571 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.65)); +#92572 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92573 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92574 = DEFINITIONAL_REPRESENTATION('',(#92575),#92579); +#92575 = LINE('',#92576,#92577); +#92576 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92577 = VECTOR('',#92578,1.); +#92578 = DIRECTION('',(1.,0.E+000)); +#92579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92580 = ORIENTED_EDGE('',*,*,#92581,.F.); +#92581 = EDGE_CURVE('',#92498,#92554,#92582,.T.); +#92582 = SURFACE_CURVE('',#92583,(#92587,#92594),.PCURVE_S1.); +#92583 = LINE('',#92584,#92585); +#92584 = CARTESIAN_POINT('',(7.65,0.E+000,0.65)); +#92585 = VECTOR('',#92586,1.); +#92586 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92587 = PCURVE('',#90796,#92588); +#92588 = DEFINITIONAL_REPRESENTATION('',(#92589),#92593); +#92589 = LINE('',#92590,#92591); +#92590 = CARTESIAN_POINT('',(-0.75,7.65)); +#92591 = VECTOR('',#92592,1.); +#92592 = DIRECTION('',(0.E+000,1.)); +#92593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92594 = PCURVE('',#92595,#92600); +#92595 = PLANE('',#92596); +#92596 = AXIS2_PLACEMENT_3D('',#92597,#92598,#92599); +#92597 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); +#92598 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92599 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92600 = DEFINITIONAL_REPRESENTATION('',(#92601),#92605); +#92601 = LINE('',#92602,#92603); +#92602 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92603 = VECTOR('',#92604,1.); +#92604 = DIRECTION('',(0.E+000,1.)); +#92605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92606 = FACE_BOUND('',#92607,.T.); +#92607 = EDGE_LOOP('',(#92608,#92638,#92666,#92694)); +#92608 = ORIENTED_EDGE('',*,*,#92609,.F.); +#92609 = EDGE_CURVE('',#92610,#92612,#92614,.T.); +#92610 = VERTEX_POINT('',#92611); +#92611 = CARTESIAN_POINT('',(8.65,0.E+000,0.75)); +#92612 = VERTEX_POINT('',#92613); +#92613 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); +#92614 = SURFACE_CURVE('',#92615,(#92619,#92626),.PCURVE_S1.); +#92615 = LINE('',#92616,#92617); +#92616 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); +#92617 = VECTOR('',#92618,1.); +#92618 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92619 = PCURVE('',#90796,#92620); +#92620 = DEFINITIONAL_REPRESENTATION('',(#92621),#92625); +#92621 = LINE('',#92622,#92623); +#92622 = CARTESIAN_POINT('',(-0.75,8.65)); +#92623 = VECTOR('',#92624,1.); +#92624 = DIRECTION('',(-1.,0.E+000)); +#92625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92626 = PCURVE('',#92627,#92632); +#92627 = PLANE('',#92628); +#92628 = AXIS2_PLACEMENT_3D('',#92629,#92630,#92631); +#92629 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); +#92630 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92631 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92632 = DEFINITIONAL_REPRESENTATION('',(#92633),#92637); +#92633 = LINE('',#92634,#92635); +#92634 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92635 = VECTOR('',#92636,1.); +#92636 = DIRECTION('',(1.,0.E+000)); +#92637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92638 = ORIENTED_EDGE('',*,*,#92639,.F.); +#92639 = EDGE_CURVE('',#92640,#92610,#92642,.T.); +#92640 = VERTEX_POINT('',#92641); +#92641 = CARTESIAN_POINT('',(8.85,0.E+000,0.75)); +#92642 = SURFACE_CURVE('',#92643,(#92647,#92654),.PCURVE_S1.); +#92643 = LINE('',#92644,#92645); +#92644 = CARTESIAN_POINT('',(8.65,0.E+000,0.75)); +#92645 = VECTOR('',#92646,1.); +#92646 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92647 = PCURVE('',#90796,#92648); +#92648 = DEFINITIONAL_REPRESENTATION('',(#92649),#92653); +#92649 = LINE('',#92650,#92651); +#92650 = CARTESIAN_POINT('',(-0.65,8.65)); +#92651 = VECTOR('',#92652,1.); +#92652 = DIRECTION('',(0.E+000,-1.)); +#92653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92654 = PCURVE('',#92655,#92660); +#92655 = PLANE('',#92656); +#92656 = AXIS2_PLACEMENT_3D('',#92657,#92658,#92659); +#92657 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.75)); +#92658 = DIRECTION('',(0.E+000,3.563627120235E-016,-1.)); +#92659 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#92660 = DEFINITIONAL_REPRESENTATION('',(#92661),#92665); +#92661 = LINE('',#92662,#92663); +#92662 = CARTESIAN_POINT('',(0.527847992439,0.E+000)); +#92663 = VECTOR('',#92664,1.); +#92664 = DIRECTION('',(0.E+000,-1.)); +#92665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92666 = ORIENTED_EDGE('',*,*,#92667,.F.); +#92667 = EDGE_CURVE('',#92668,#92640,#92670,.T.); +#92668 = VERTEX_POINT('',#92669); +#92669 = CARTESIAN_POINT('',(8.85,0.E+000,0.65)); +#92670 = SURFACE_CURVE('',#92671,(#92675,#92682),.PCURVE_S1.); +#92671 = LINE('',#92672,#92673); +#92672 = CARTESIAN_POINT('',(8.85,0.E+000,0.65)); +#92673 = VECTOR('',#92674,1.); +#92674 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92675 = PCURVE('',#90796,#92676); +#92676 = DEFINITIONAL_REPRESENTATION('',(#92677),#92681); +#92677 = LINE('',#92678,#92679); +#92678 = CARTESIAN_POINT('',(-0.75,8.85)); +#92679 = VECTOR('',#92680,1.); +#92680 = DIRECTION('',(1.,0.E+000)); +#92681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92682 = PCURVE('',#92683,#92688); +#92683 = PLANE('',#92684); +#92684 = AXIS2_PLACEMENT_3D('',#92685,#92686,#92687); +#92685 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.65)); +#92686 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#92687 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92688 = DEFINITIONAL_REPRESENTATION('',(#92689),#92693); +#92689 = LINE('',#92690,#92691); +#92690 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92691 = VECTOR('',#92692,1.); +#92692 = DIRECTION('',(1.,0.E+000)); +#92693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92694 = ORIENTED_EDGE('',*,*,#92695,.F.); +#92695 = EDGE_CURVE('',#92612,#92668,#92696,.T.); +#92696 = SURFACE_CURVE('',#92697,(#92701,#92708),.PCURVE_S1.); +#92697 = LINE('',#92698,#92699); +#92698 = CARTESIAN_POINT('',(8.65,0.E+000,0.65)); +#92699 = VECTOR('',#92700,1.); +#92700 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92701 = PCURVE('',#90796,#92702); +#92702 = DEFINITIONAL_REPRESENTATION('',(#92703),#92707); +#92703 = LINE('',#92704,#92705); +#92704 = CARTESIAN_POINT('',(-0.75,8.65)); +#92705 = VECTOR('',#92706,1.); +#92706 = DIRECTION('',(0.E+000,1.)); +#92707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92708 = PCURVE('',#92709,#92714); +#92709 = PLANE('',#92710); +#92710 = AXIS2_PLACEMENT_3D('',#92711,#92712,#92713); +#92711 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); +#92712 = DIRECTION('',(0.E+000,-3.563627120235E-016,1.)); +#92713 = DIRECTION('',(0.E+000,-1.,-3.563627120235E-016)); +#92714 = DEFINITIONAL_REPRESENTATION('',(#92715),#92719); +#92715 = LINE('',#92716,#92717); +#92716 = CARTESIAN_POINT('',(-0.527847992439,0.E+000)); +#92717 = VECTOR('',#92718,1.); +#92718 = DIRECTION('',(0.E+000,1.)); +#92719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92720 = ADVANCED_FACE('',(#92721,#92840,#92954,#93068,#93182,#93296, + #93410,#93524,#93638,#93752,#93866,#93980,#94094,#94208,#94322, + #94436,#94550),#92735,.F.); +#92721 = FACE_BOUND('',#92722,.T.); +#92722 = EDGE_LOOP('',(#92723,#92758,#92786,#92814)); +#92723 = ORIENTED_EDGE('',*,*,#92724,.T.); +#92724 = EDGE_CURVE('',#92725,#92727,#92729,.T.); #92725 = VERTEX_POINT('',#92726); -#92726 = CARTESIAN_POINT('',(10.,3.35,0.65)); -#92727 = SURFACE_CURVE('',#92728,(#92732,#92739),.PCURVE_S1.); -#92728 = LINE('',#92729,#92730); -#92729 = CARTESIAN_POINT('',(10.,3.35,0.65)); -#92730 = VECTOR('',#92731,1.); -#92731 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92732 = PCURVE('',#92272,#92733); -#92733 = DEFINITIONAL_REPRESENTATION('',(#92734),#92738); -#92734 = LINE('',#92735,#92736); -#92735 = CARTESIAN_POINT('',(-0.75,3.35)); -#92736 = VECTOR('',#92737,1.); -#92737 = DIRECTION('',(-1.,0.E+000)); -#92738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92739 = PCURVE('',#92740,#92745); -#92740 = PLANE('',#92741); -#92741 = AXIS2_PLACEMENT_3D('',#92742,#92743,#92744); -#92742 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); -#92743 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92744 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92745 = DEFINITIONAL_REPRESENTATION('',(#92746),#92750); -#92746 = LINE('',#92747,#92748); -#92747 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92748 = VECTOR('',#92749,1.); -#92749 = DIRECTION('',(-1.,0.E+000)); -#92750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92751 = ORIENTED_EDGE('',*,*,#92752,.T.); -#92752 = EDGE_CURVE('',#92725,#92753,#92755,.T.); -#92753 = VERTEX_POINT('',#92754); -#92754 = CARTESIAN_POINT('',(10.,3.15,0.65)); -#92755 = SURFACE_CURVE('',#92756,(#92760,#92767),.PCURVE_S1.); -#92756 = LINE('',#92757,#92758); -#92757 = CARTESIAN_POINT('',(10.,3.35,0.65)); -#92758 = VECTOR('',#92759,1.); -#92759 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92760 = PCURVE('',#92272,#92761); -#92761 = DEFINITIONAL_REPRESENTATION('',(#92762),#92766); -#92762 = LINE('',#92763,#92764); -#92763 = CARTESIAN_POINT('',(-0.75,3.35)); -#92764 = VECTOR('',#92765,1.); -#92765 = DIRECTION('',(0.E+000,-1.)); -#92766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92767 = PCURVE('',#92768,#92773); -#92768 = PLANE('',#92769); -#92769 = AXIS2_PLACEMENT_3D('',#92770,#92771,#92772); -#92770 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); -#92771 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92772 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92773 = DEFINITIONAL_REPRESENTATION('',(#92774),#92778); -#92774 = LINE('',#92775,#92776); -#92775 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92776 = VECTOR('',#92777,1.); -#92777 = DIRECTION('',(4.440892098501E-016,-1.)); -#92778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92779 = ORIENTED_EDGE('',*,*,#92780,.T.); -#92780 = EDGE_CURVE('',#92753,#92781,#92783,.T.); -#92781 = VERTEX_POINT('',#92782); -#92782 = CARTESIAN_POINT('',(10.,3.15,0.75)); -#92783 = SURFACE_CURVE('',#92784,(#92788,#92795),.PCURVE_S1.); -#92784 = LINE('',#92785,#92786); -#92785 = CARTESIAN_POINT('',(10.,3.15,0.65)); -#92786 = VECTOR('',#92787,1.); -#92787 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92788 = PCURVE('',#92272,#92789); -#92789 = DEFINITIONAL_REPRESENTATION('',(#92790),#92794); -#92790 = LINE('',#92791,#92792); -#92791 = CARTESIAN_POINT('',(-0.75,3.15)); -#92792 = VECTOR('',#92793,1.); -#92793 = DIRECTION('',(1.,0.E+000)); -#92794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92795 = PCURVE('',#92796,#92801); -#92796 = PLANE('',#92797); -#92797 = AXIS2_PLACEMENT_3D('',#92798,#92799,#92800); -#92798 = CARTESIAN_POINT('',(10.527847992439,3.15,0.65)); -#92799 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92800 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92801 = DEFINITIONAL_REPRESENTATION('',(#92802),#92806); -#92802 = LINE('',#92803,#92804); -#92803 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92804 = VECTOR('',#92805,1.); -#92805 = DIRECTION('',(-1.,0.E+000)); -#92806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92807 = ORIENTED_EDGE('',*,*,#92808,.T.); -#92808 = EDGE_CURVE('',#92781,#92723,#92809,.T.); -#92809 = SURFACE_CURVE('',#92810,(#92814,#92821),.PCURVE_S1.); -#92810 = LINE('',#92811,#92812); -#92811 = CARTESIAN_POINT('',(10.,3.35,0.75)); -#92812 = VECTOR('',#92813,1.); -#92813 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92814 = PCURVE('',#92272,#92815); -#92815 = DEFINITIONAL_REPRESENTATION('',(#92816),#92820); -#92816 = LINE('',#92817,#92818); -#92817 = CARTESIAN_POINT('',(-0.65,3.35)); -#92818 = VECTOR('',#92819,1.); -#92819 = DIRECTION('',(0.E+000,1.)); -#92820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92821 = PCURVE('',#92822,#92827); -#92822 = PLANE('',#92823); -#92823 = AXIS2_PLACEMENT_3D('',#92824,#92825,#92826); -#92824 = CARTESIAN_POINT('',(10.527847992439,3.35,0.75)); -#92825 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92826 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92827 = DEFINITIONAL_REPRESENTATION('',(#92828),#92832); -#92828 = LINE('',#92829,#92830); -#92829 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92830 = VECTOR('',#92831,1.); -#92831 = DIRECTION('',(4.440892098501E-016,1.)); -#92832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92833 = FACE_BOUND('',#92834,.T.); -#92834 = EDGE_LOOP('',(#92835,#92865,#92893,#92921)); -#92835 = ORIENTED_EDGE('',*,*,#92836,.T.); -#92836 = EDGE_CURVE('',#92837,#92839,#92841,.T.); -#92837 = VERTEX_POINT('',#92838); -#92838 = CARTESIAN_POINT('',(10.,3.85,0.75)); -#92839 = VERTEX_POINT('',#92840); -#92840 = CARTESIAN_POINT('',(10.,3.85,0.65)); -#92841 = SURFACE_CURVE('',#92842,(#92846,#92853),.PCURVE_S1.); -#92842 = LINE('',#92843,#92844); -#92843 = CARTESIAN_POINT('',(10.,3.85,0.65)); -#92844 = VECTOR('',#92845,1.); -#92845 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92846 = PCURVE('',#92272,#92847); -#92847 = DEFINITIONAL_REPRESENTATION('',(#92848),#92852); -#92848 = LINE('',#92849,#92850); -#92849 = CARTESIAN_POINT('',(-0.75,3.85)); -#92850 = VECTOR('',#92851,1.); -#92851 = DIRECTION('',(-1.,0.E+000)); -#92852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92853 = PCURVE('',#92854,#92859); -#92854 = PLANE('',#92855); -#92855 = AXIS2_PLACEMENT_3D('',#92856,#92857,#92858); -#92856 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); -#92857 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92858 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92859 = DEFINITIONAL_REPRESENTATION('',(#92860),#92864); -#92860 = LINE('',#92861,#92862); -#92861 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92862 = VECTOR('',#92863,1.); -#92863 = DIRECTION('',(-1.,0.E+000)); -#92864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92865 = ORIENTED_EDGE('',*,*,#92866,.T.); -#92866 = EDGE_CURVE('',#92839,#92867,#92869,.T.); -#92867 = VERTEX_POINT('',#92868); -#92868 = CARTESIAN_POINT('',(10.,3.65,0.65)); -#92869 = SURFACE_CURVE('',#92870,(#92874,#92881),.PCURVE_S1.); -#92870 = LINE('',#92871,#92872); -#92871 = CARTESIAN_POINT('',(10.,3.85,0.65)); -#92872 = VECTOR('',#92873,1.); -#92873 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92874 = PCURVE('',#92272,#92875); -#92875 = DEFINITIONAL_REPRESENTATION('',(#92876),#92880); -#92876 = LINE('',#92877,#92878); -#92877 = CARTESIAN_POINT('',(-0.75,3.85)); -#92878 = VECTOR('',#92879,1.); -#92879 = DIRECTION('',(0.E+000,-1.)); -#92880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92881 = PCURVE('',#92882,#92887); -#92882 = PLANE('',#92883); -#92883 = AXIS2_PLACEMENT_3D('',#92884,#92885,#92886); -#92884 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); -#92885 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#92886 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#92887 = DEFINITIONAL_REPRESENTATION('',(#92888),#92892); -#92888 = LINE('',#92889,#92890); -#92889 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#92890 = VECTOR('',#92891,1.); -#92891 = DIRECTION('',(4.440892098501E-016,-1.)); -#92892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92893 = ORIENTED_EDGE('',*,*,#92894,.T.); -#92894 = EDGE_CURVE('',#92867,#92895,#92897,.T.); -#92895 = VERTEX_POINT('',#92896); -#92896 = CARTESIAN_POINT('',(10.,3.65,0.75)); -#92897 = SURFACE_CURVE('',#92898,(#92902,#92909),.PCURVE_S1.); -#92898 = LINE('',#92899,#92900); -#92899 = CARTESIAN_POINT('',(10.,3.65,0.65)); -#92900 = VECTOR('',#92901,1.); -#92901 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92902 = PCURVE('',#92272,#92903); -#92903 = DEFINITIONAL_REPRESENTATION('',(#92904),#92908); -#92904 = LINE('',#92905,#92906); -#92905 = CARTESIAN_POINT('',(-0.75,3.65)); -#92906 = VECTOR('',#92907,1.); -#92907 = DIRECTION('',(1.,0.E+000)); -#92908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92909 = PCURVE('',#92910,#92915); -#92910 = PLANE('',#92911); -#92911 = AXIS2_PLACEMENT_3D('',#92912,#92913,#92914); -#92912 = CARTESIAN_POINT('',(10.527847992439,3.65,0.65)); -#92913 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#92914 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92915 = DEFINITIONAL_REPRESENTATION('',(#92916),#92920); -#92916 = LINE('',#92917,#92918); -#92917 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#92918 = VECTOR('',#92919,1.); -#92919 = DIRECTION('',(-1.,0.E+000)); -#92920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92921 = ORIENTED_EDGE('',*,*,#92922,.T.); -#92922 = EDGE_CURVE('',#92895,#92837,#92923,.T.); -#92923 = SURFACE_CURVE('',#92924,(#92928,#92935),.PCURVE_S1.); -#92924 = LINE('',#92925,#92926); -#92925 = CARTESIAN_POINT('',(10.,3.85,0.75)); -#92926 = VECTOR('',#92927,1.); -#92927 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#92928 = PCURVE('',#92272,#92929); -#92929 = DEFINITIONAL_REPRESENTATION('',(#92930),#92934); -#92930 = LINE('',#92931,#92932); -#92931 = CARTESIAN_POINT('',(-0.65,3.85)); -#92932 = VECTOR('',#92933,1.); -#92933 = DIRECTION('',(0.E+000,1.)); -#92934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92935 = PCURVE('',#92936,#92941); -#92936 = PLANE('',#92937); -#92937 = AXIS2_PLACEMENT_3D('',#92938,#92939,#92940); -#92938 = CARTESIAN_POINT('',(10.527847992439,3.85,0.75)); -#92939 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#92940 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#92941 = DEFINITIONAL_REPRESENTATION('',(#92942),#92946); -#92942 = LINE('',#92943,#92944); -#92943 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#92944 = VECTOR('',#92945,1.); -#92945 = DIRECTION('',(4.440892098501E-016,1.)); -#92946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92947 = FACE_BOUND('',#92948,.T.); -#92948 = EDGE_LOOP('',(#92949,#92979,#93007,#93035)); -#92949 = ORIENTED_EDGE('',*,*,#92950,.T.); -#92950 = EDGE_CURVE('',#92951,#92953,#92955,.T.); -#92951 = VERTEX_POINT('',#92952); -#92952 = CARTESIAN_POINT('',(10.,4.35,0.75)); -#92953 = VERTEX_POINT('',#92954); -#92954 = CARTESIAN_POINT('',(10.,4.35,0.65)); -#92955 = SURFACE_CURVE('',#92956,(#92960,#92967),.PCURVE_S1.); -#92956 = LINE('',#92957,#92958); -#92957 = CARTESIAN_POINT('',(10.,4.35,0.65)); -#92958 = VECTOR('',#92959,1.); -#92959 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#92960 = PCURVE('',#92272,#92961); -#92961 = DEFINITIONAL_REPRESENTATION('',(#92962),#92966); -#92962 = LINE('',#92963,#92964); -#92963 = CARTESIAN_POINT('',(-0.75,4.35)); -#92964 = VECTOR('',#92965,1.); -#92965 = DIRECTION('',(-1.,0.E+000)); -#92966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92967 = PCURVE('',#92968,#92973); -#92968 = PLANE('',#92969); -#92969 = AXIS2_PLACEMENT_3D('',#92970,#92971,#92972); -#92970 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); -#92971 = DIRECTION('',(0.E+000,1.,0.E+000)); -#92972 = DIRECTION('',(0.E+000,0.E+000,1.)); -#92973 = DEFINITIONAL_REPRESENTATION('',(#92974),#92978); -#92974 = LINE('',#92975,#92976); -#92975 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#92976 = VECTOR('',#92977,1.); -#92977 = DIRECTION('',(-1.,0.E+000)); -#92978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92979 = ORIENTED_EDGE('',*,*,#92980,.T.); -#92980 = EDGE_CURVE('',#92953,#92981,#92983,.T.); -#92981 = VERTEX_POINT('',#92982); -#92982 = CARTESIAN_POINT('',(10.,4.15,0.65)); -#92983 = SURFACE_CURVE('',#92984,(#92988,#92995),.PCURVE_S1.); -#92984 = LINE('',#92985,#92986); -#92985 = CARTESIAN_POINT('',(10.,4.35,0.65)); -#92986 = VECTOR('',#92987,1.); -#92987 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#92988 = PCURVE('',#92272,#92989); -#92989 = DEFINITIONAL_REPRESENTATION('',(#92990),#92994); -#92990 = LINE('',#92991,#92992); -#92991 = CARTESIAN_POINT('',(-0.75,4.35)); -#92992 = VECTOR('',#92993,1.); -#92993 = DIRECTION('',(0.E+000,-1.)); -#92994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#92995 = PCURVE('',#92996,#93001); -#92996 = PLANE('',#92997); -#92997 = AXIS2_PLACEMENT_3D('',#92998,#92999,#93000); -#92998 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); -#92999 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93000 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93001 = DEFINITIONAL_REPRESENTATION('',(#93002),#93006); -#93002 = LINE('',#93003,#93004); -#93003 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93004 = VECTOR('',#93005,1.); -#93005 = DIRECTION('',(4.440892098501E-016,-1.)); -#93006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93007 = ORIENTED_EDGE('',*,*,#93008,.T.); -#93008 = EDGE_CURVE('',#92981,#93009,#93011,.T.); -#93009 = VERTEX_POINT('',#93010); -#93010 = CARTESIAN_POINT('',(10.,4.15,0.75)); -#93011 = SURFACE_CURVE('',#93012,(#93016,#93023),.PCURVE_S1.); -#93012 = LINE('',#93013,#93014); -#93013 = CARTESIAN_POINT('',(10.,4.15,0.65)); -#93014 = VECTOR('',#93015,1.); -#93015 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93016 = PCURVE('',#92272,#93017); -#93017 = DEFINITIONAL_REPRESENTATION('',(#93018),#93022); -#93018 = LINE('',#93019,#93020); -#93019 = CARTESIAN_POINT('',(-0.75,4.15)); -#93020 = VECTOR('',#93021,1.); -#93021 = DIRECTION('',(1.,0.E+000)); -#93022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93023 = PCURVE('',#93024,#93029); -#93024 = PLANE('',#93025); -#93025 = AXIS2_PLACEMENT_3D('',#93026,#93027,#93028); -#93026 = CARTESIAN_POINT('',(10.527847992439,4.15,0.65)); -#93027 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93028 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93029 = DEFINITIONAL_REPRESENTATION('',(#93030),#93034); -#93030 = LINE('',#93031,#93032); -#93031 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93032 = VECTOR('',#93033,1.); -#93033 = DIRECTION('',(-1.,0.E+000)); -#93034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93035 = ORIENTED_EDGE('',*,*,#93036,.T.); -#93036 = EDGE_CURVE('',#93009,#92951,#93037,.T.); -#93037 = SURFACE_CURVE('',#93038,(#93042,#93049),.PCURVE_S1.); -#93038 = LINE('',#93039,#93040); -#93039 = CARTESIAN_POINT('',(10.,4.35,0.75)); -#93040 = VECTOR('',#93041,1.); -#93041 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93042 = PCURVE('',#92272,#93043); -#93043 = DEFINITIONAL_REPRESENTATION('',(#93044),#93048); -#93044 = LINE('',#93045,#93046); -#93045 = CARTESIAN_POINT('',(-0.65,4.35)); -#93046 = VECTOR('',#93047,1.); -#93047 = DIRECTION('',(0.E+000,1.)); -#93048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93049 = PCURVE('',#93050,#93055); -#93050 = PLANE('',#93051); -#93051 = AXIS2_PLACEMENT_3D('',#93052,#93053,#93054); -#93052 = CARTESIAN_POINT('',(10.527847992439,4.35,0.75)); -#93053 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93054 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93055 = DEFINITIONAL_REPRESENTATION('',(#93056),#93060); -#93056 = LINE('',#93057,#93058); -#93057 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93058 = VECTOR('',#93059,1.); -#93059 = DIRECTION('',(4.440892098501E-016,1.)); -#93060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93061 = FACE_BOUND('',#93062,.T.); -#93062 = EDGE_LOOP('',(#93063,#93093,#93121,#93149)); -#93063 = ORIENTED_EDGE('',*,*,#93064,.T.); -#93064 = EDGE_CURVE('',#93065,#93067,#93069,.T.); -#93065 = VERTEX_POINT('',#93066); -#93066 = CARTESIAN_POINT('',(10.,5.35,0.75)); -#93067 = VERTEX_POINT('',#93068); -#93068 = CARTESIAN_POINT('',(10.,5.35,0.65)); -#93069 = SURFACE_CURVE('',#93070,(#93074,#93081),.PCURVE_S1.); -#93070 = LINE('',#93071,#93072); -#93071 = CARTESIAN_POINT('',(10.,5.35,0.65)); -#93072 = VECTOR('',#93073,1.); -#93073 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93074 = PCURVE('',#92272,#93075); -#93075 = DEFINITIONAL_REPRESENTATION('',(#93076),#93080); -#93076 = LINE('',#93077,#93078); -#93077 = CARTESIAN_POINT('',(-0.75,5.35)); -#93078 = VECTOR('',#93079,1.); -#93079 = DIRECTION('',(-1.,0.E+000)); -#93080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93081 = PCURVE('',#93082,#93087); -#93082 = PLANE('',#93083); -#93083 = AXIS2_PLACEMENT_3D('',#93084,#93085,#93086); -#93084 = CARTESIAN_POINT('',(10.527847992439,5.35,0.65)); -#93085 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93086 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93087 = DEFINITIONAL_REPRESENTATION('',(#93088),#93092); -#93088 = LINE('',#93089,#93090); -#93089 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93090 = VECTOR('',#93091,1.); -#93091 = DIRECTION('',(-1.,0.E+000)); -#93092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93093 = ORIENTED_EDGE('',*,*,#93094,.T.); -#93094 = EDGE_CURVE('',#93067,#93095,#93097,.T.); -#93095 = VERTEX_POINT('',#93096); -#93096 = CARTESIAN_POINT('',(10.,5.15,0.65)); -#93097 = SURFACE_CURVE('',#93098,(#93102,#93109),.PCURVE_S1.); -#93098 = LINE('',#93099,#93100); -#93099 = CARTESIAN_POINT('',(10.,5.15,0.65)); -#93100 = VECTOR('',#93101,1.); -#93101 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93102 = PCURVE('',#92272,#93103); -#93103 = DEFINITIONAL_REPRESENTATION('',(#93104),#93108); -#93104 = LINE('',#93105,#93106); -#93105 = CARTESIAN_POINT('',(-0.75,5.15)); -#93106 = VECTOR('',#93107,1.); -#93107 = DIRECTION('',(0.E+000,-1.)); -#93108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93109 = PCURVE('',#93110,#93115); -#93110 = PLANE('',#93111); -#93111 = AXIS2_PLACEMENT_3D('',#93112,#93113,#93114); -#93112 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); -#93113 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93114 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93115 = DEFINITIONAL_REPRESENTATION('',(#93116),#93120); -#93116 = LINE('',#93117,#93118); -#93117 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93118 = VECTOR('',#93119,1.); -#93119 = DIRECTION('',(4.440892098501E-016,-1.)); -#93120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93121 = ORIENTED_EDGE('',*,*,#93122,.T.); -#93122 = EDGE_CURVE('',#93095,#93123,#93125,.T.); -#93123 = VERTEX_POINT('',#93124); -#93124 = CARTESIAN_POINT('',(10.,5.15,0.75)); -#93125 = SURFACE_CURVE('',#93126,(#93130,#93137),.PCURVE_S1.); -#93126 = LINE('',#93127,#93128); -#93127 = CARTESIAN_POINT('',(10.,5.15,0.65)); -#93128 = VECTOR('',#93129,1.); -#93129 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93130 = PCURVE('',#92272,#93131); -#93131 = DEFINITIONAL_REPRESENTATION('',(#93132),#93136); -#93132 = LINE('',#93133,#93134); -#93133 = CARTESIAN_POINT('',(-0.75,5.15)); -#93134 = VECTOR('',#93135,1.); -#93135 = DIRECTION('',(1.,0.E+000)); -#93136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93137 = PCURVE('',#93138,#93143); -#93138 = PLANE('',#93139); -#93139 = AXIS2_PLACEMENT_3D('',#93140,#93141,#93142); -#93140 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); -#93141 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93142 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93143 = DEFINITIONAL_REPRESENTATION('',(#93144),#93148); -#93144 = LINE('',#93145,#93146); -#93145 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93146 = VECTOR('',#93147,1.); -#93147 = DIRECTION('',(-1.,0.E+000)); -#93148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93149 = ORIENTED_EDGE('',*,*,#93150,.T.); -#93150 = EDGE_CURVE('',#93123,#93065,#93151,.T.); -#93151 = SURFACE_CURVE('',#93152,(#93156,#93163),.PCURVE_S1.); -#93152 = LINE('',#93153,#93154); -#93153 = CARTESIAN_POINT('',(10.,5.15,0.75)); -#93154 = VECTOR('',#93155,1.); -#93155 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93156 = PCURVE('',#92272,#93157); -#93157 = DEFINITIONAL_REPRESENTATION('',(#93158),#93162); -#93158 = LINE('',#93159,#93160); -#93159 = CARTESIAN_POINT('',(-0.65,5.15)); -#93160 = VECTOR('',#93161,1.); -#93161 = DIRECTION('',(0.E+000,1.)); -#93162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93163 = PCURVE('',#93164,#93169); -#93164 = PLANE('',#93165); -#93165 = AXIS2_PLACEMENT_3D('',#93166,#93167,#93168); -#93166 = CARTESIAN_POINT('',(10.527847992439,5.15,0.75)); -#93167 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93168 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93169 = DEFINITIONAL_REPRESENTATION('',(#93170),#93174); -#93170 = LINE('',#93171,#93172); -#93171 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93172 = VECTOR('',#93173,1.); -#93173 = DIRECTION('',(4.440892098501E-016,1.)); -#93174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93175 = FACE_BOUND('',#93176,.T.); -#93176 = EDGE_LOOP('',(#93177,#93207,#93235,#93263)); -#93177 = ORIENTED_EDGE('',*,*,#93178,.T.); -#93178 = EDGE_CURVE('',#93179,#93181,#93183,.T.); -#93179 = VERTEX_POINT('',#93180); -#93180 = CARTESIAN_POINT('',(10.,5.85,0.75)); -#93181 = VERTEX_POINT('',#93182); -#93182 = CARTESIAN_POINT('',(10.,5.85,0.65)); -#93183 = SURFACE_CURVE('',#93184,(#93188,#93195),.PCURVE_S1.); -#93184 = LINE('',#93185,#93186); -#93185 = CARTESIAN_POINT('',(10.,5.85,0.65)); -#93186 = VECTOR('',#93187,1.); -#93187 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93188 = PCURVE('',#92272,#93189); -#93189 = DEFINITIONAL_REPRESENTATION('',(#93190),#93194); -#93190 = LINE('',#93191,#93192); -#93191 = CARTESIAN_POINT('',(-0.75,5.85)); -#93192 = VECTOR('',#93193,1.); -#93193 = DIRECTION('',(-1.,0.E+000)); -#93194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93195 = PCURVE('',#93196,#93201); -#93196 = PLANE('',#93197); -#93197 = AXIS2_PLACEMENT_3D('',#93198,#93199,#93200); -#93198 = CARTESIAN_POINT('',(10.527847992439,5.85,0.65)); -#93199 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93200 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93201 = DEFINITIONAL_REPRESENTATION('',(#93202),#93206); -#93202 = LINE('',#93203,#93204); -#93203 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93204 = VECTOR('',#93205,1.); -#93205 = DIRECTION('',(-1.,0.E+000)); -#93206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93207 = ORIENTED_EDGE('',*,*,#93208,.T.); -#93208 = EDGE_CURVE('',#93181,#93209,#93211,.T.); -#93209 = VERTEX_POINT('',#93210); -#93210 = CARTESIAN_POINT('',(10.,5.65,0.65)); -#93211 = SURFACE_CURVE('',#93212,(#93216,#93223),.PCURVE_S1.); -#93212 = LINE('',#93213,#93214); -#93213 = CARTESIAN_POINT('',(10.,5.65,0.65)); -#93214 = VECTOR('',#93215,1.); -#93215 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93216 = PCURVE('',#92272,#93217); -#93217 = DEFINITIONAL_REPRESENTATION('',(#93218),#93222); -#93218 = LINE('',#93219,#93220); -#93219 = CARTESIAN_POINT('',(-0.75,5.65)); -#93220 = VECTOR('',#93221,1.); -#93221 = DIRECTION('',(0.E+000,-1.)); -#93222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93223 = PCURVE('',#93224,#93229); -#93224 = PLANE('',#93225); -#93225 = AXIS2_PLACEMENT_3D('',#93226,#93227,#93228); -#93226 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); -#93227 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93228 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93229 = DEFINITIONAL_REPRESENTATION('',(#93230),#93234); -#93230 = LINE('',#93231,#93232); -#93231 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93232 = VECTOR('',#93233,1.); -#93233 = DIRECTION('',(4.440892098501E-016,-1.)); -#93234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93235 = ORIENTED_EDGE('',*,*,#93236,.T.); -#93236 = EDGE_CURVE('',#93209,#93237,#93239,.T.); -#93237 = VERTEX_POINT('',#93238); -#93238 = CARTESIAN_POINT('',(10.,5.65,0.75)); -#93239 = SURFACE_CURVE('',#93240,(#93244,#93251),.PCURVE_S1.); -#93240 = LINE('',#93241,#93242); -#93241 = CARTESIAN_POINT('',(10.,5.65,0.65)); -#93242 = VECTOR('',#93243,1.); -#93243 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93244 = PCURVE('',#92272,#93245); -#93245 = DEFINITIONAL_REPRESENTATION('',(#93246),#93250); -#93246 = LINE('',#93247,#93248); -#93247 = CARTESIAN_POINT('',(-0.75,5.65)); -#93248 = VECTOR('',#93249,1.); -#93249 = DIRECTION('',(1.,0.E+000)); -#93250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93251 = PCURVE('',#93252,#93257); -#93252 = PLANE('',#93253); -#93253 = AXIS2_PLACEMENT_3D('',#93254,#93255,#93256); -#93254 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); -#93255 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93256 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93257 = DEFINITIONAL_REPRESENTATION('',(#93258),#93262); -#93258 = LINE('',#93259,#93260); -#93259 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93260 = VECTOR('',#93261,1.); -#93261 = DIRECTION('',(-1.,0.E+000)); -#93262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93263 = ORIENTED_EDGE('',*,*,#93264,.T.); -#93264 = EDGE_CURVE('',#93237,#93179,#93265,.T.); -#93265 = SURFACE_CURVE('',#93266,(#93270,#93277),.PCURVE_S1.); -#93266 = LINE('',#93267,#93268); -#93267 = CARTESIAN_POINT('',(10.,5.65,0.75)); -#93268 = VECTOR('',#93269,1.); -#93269 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93270 = PCURVE('',#92272,#93271); -#93271 = DEFINITIONAL_REPRESENTATION('',(#93272),#93276); -#93272 = LINE('',#93273,#93274); -#93273 = CARTESIAN_POINT('',(-0.65,5.65)); -#93274 = VECTOR('',#93275,1.); -#93275 = DIRECTION('',(0.E+000,1.)); -#93276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93277 = PCURVE('',#93278,#93283); -#93278 = PLANE('',#93279); -#93279 = AXIS2_PLACEMENT_3D('',#93280,#93281,#93282); -#93280 = CARTESIAN_POINT('',(10.527847992439,5.65,0.75)); -#93281 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93282 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93283 = DEFINITIONAL_REPRESENTATION('',(#93284),#93288); -#93284 = LINE('',#93285,#93286); -#93285 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93286 = VECTOR('',#93287,1.); -#93287 = DIRECTION('',(4.440892098501E-016,1.)); -#93288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93289 = FACE_BOUND('',#93290,.T.); -#93290 = EDGE_LOOP('',(#93291,#93321,#93349,#93377)); -#93291 = ORIENTED_EDGE('',*,*,#93292,.T.); -#93292 = EDGE_CURVE('',#93293,#93295,#93297,.T.); -#93293 = VERTEX_POINT('',#93294); -#93294 = CARTESIAN_POINT('',(10.,6.35,0.75)); -#93295 = VERTEX_POINT('',#93296); -#93296 = CARTESIAN_POINT('',(10.,6.35,0.65)); -#93297 = SURFACE_CURVE('',#93298,(#93302,#93309),.PCURVE_S1.); -#93298 = LINE('',#93299,#93300); -#93299 = CARTESIAN_POINT('',(10.,6.35,0.65)); -#93300 = VECTOR('',#93301,1.); -#93301 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93302 = PCURVE('',#92272,#93303); -#93303 = DEFINITIONAL_REPRESENTATION('',(#93304),#93308); -#93304 = LINE('',#93305,#93306); -#93305 = CARTESIAN_POINT('',(-0.75,6.35)); -#93306 = VECTOR('',#93307,1.); -#93307 = DIRECTION('',(-1.,0.E+000)); -#93308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93309 = PCURVE('',#93310,#93315); -#93310 = PLANE('',#93311); -#93311 = AXIS2_PLACEMENT_3D('',#93312,#93313,#93314); -#93312 = CARTESIAN_POINT('',(10.527847992439,6.35,0.65)); -#93313 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93314 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93315 = DEFINITIONAL_REPRESENTATION('',(#93316),#93320); -#93316 = LINE('',#93317,#93318); -#93317 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93318 = VECTOR('',#93319,1.); -#93319 = DIRECTION('',(-1.,0.E+000)); -#93320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93321 = ORIENTED_EDGE('',*,*,#93322,.T.); -#93322 = EDGE_CURVE('',#93295,#93323,#93325,.T.); -#93323 = VERTEX_POINT('',#93324); -#93324 = CARTESIAN_POINT('',(10.,6.15,0.65)); -#93325 = SURFACE_CURVE('',#93326,(#93330,#93337),.PCURVE_S1.); -#93326 = LINE('',#93327,#93328); -#93327 = CARTESIAN_POINT('',(10.,6.15,0.65)); -#93328 = VECTOR('',#93329,1.); -#93329 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93330 = PCURVE('',#92272,#93331); -#93331 = DEFINITIONAL_REPRESENTATION('',(#93332),#93336); -#93332 = LINE('',#93333,#93334); -#93333 = CARTESIAN_POINT('',(-0.75,6.15)); -#93334 = VECTOR('',#93335,1.); -#93335 = DIRECTION('',(0.E+000,-1.)); -#93336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93337 = PCURVE('',#93338,#93343); -#93338 = PLANE('',#93339); -#93339 = AXIS2_PLACEMENT_3D('',#93340,#93341,#93342); -#93340 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); -#93341 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93342 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93343 = DEFINITIONAL_REPRESENTATION('',(#93344),#93348); -#93344 = LINE('',#93345,#93346); -#93345 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93346 = VECTOR('',#93347,1.); -#93347 = DIRECTION('',(4.440892098501E-016,-1.)); -#93348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93349 = ORIENTED_EDGE('',*,*,#93350,.T.); -#93350 = EDGE_CURVE('',#93323,#93351,#93353,.T.); -#93351 = VERTEX_POINT('',#93352); -#93352 = CARTESIAN_POINT('',(10.,6.15,0.75)); -#93353 = SURFACE_CURVE('',#93354,(#93358,#93365),.PCURVE_S1.); -#93354 = LINE('',#93355,#93356); -#93355 = CARTESIAN_POINT('',(10.,6.15,0.65)); -#93356 = VECTOR('',#93357,1.); -#93357 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93358 = PCURVE('',#92272,#93359); -#93359 = DEFINITIONAL_REPRESENTATION('',(#93360),#93364); -#93360 = LINE('',#93361,#93362); -#93361 = CARTESIAN_POINT('',(-0.75,6.15)); -#93362 = VECTOR('',#93363,1.); -#93363 = DIRECTION('',(1.,0.E+000)); -#93364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93365 = PCURVE('',#93366,#93371); -#93366 = PLANE('',#93367); -#93367 = AXIS2_PLACEMENT_3D('',#93368,#93369,#93370); -#93368 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); -#93369 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93370 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93371 = DEFINITIONAL_REPRESENTATION('',(#93372),#93376); -#93372 = LINE('',#93373,#93374); -#93373 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93374 = VECTOR('',#93375,1.); -#93375 = DIRECTION('',(-1.,0.E+000)); -#93376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93377 = ORIENTED_EDGE('',*,*,#93378,.T.); -#93378 = EDGE_CURVE('',#93351,#93293,#93379,.T.); -#93379 = SURFACE_CURVE('',#93380,(#93384,#93391),.PCURVE_S1.); -#93380 = LINE('',#93381,#93382); -#93381 = CARTESIAN_POINT('',(10.,6.15,0.75)); -#93382 = VECTOR('',#93383,1.); -#93383 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93384 = PCURVE('',#92272,#93385); -#93385 = DEFINITIONAL_REPRESENTATION('',(#93386),#93390); -#93386 = LINE('',#93387,#93388); -#93387 = CARTESIAN_POINT('',(-0.65,6.15)); -#93388 = VECTOR('',#93389,1.); -#93389 = DIRECTION('',(0.E+000,1.)); -#93390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93391 = PCURVE('',#93392,#93397); -#93392 = PLANE('',#93393); -#93393 = AXIS2_PLACEMENT_3D('',#93394,#93395,#93396); -#93394 = CARTESIAN_POINT('',(10.527847992439,6.15,0.75)); -#93395 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93396 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93397 = DEFINITIONAL_REPRESENTATION('',(#93398),#93402); -#93398 = LINE('',#93399,#93400); -#93399 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93400 = VECTOR('',#93401,1.); -#93401 = DIRECTION('',(4.440892098501E-016,1.)); -#93402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93403 = FACE_BOUND('',#93404,.T.); -#93404 = EDGE_LOOP('',(#93405,#93435,#93463,#93491)); -#93405 = ORIENTED_EDGE('',*,*,#93406,.T.); -#93406 = EDGE_CURVE('',#93407,#93409,#93411,.T.); -#93407 = VERTEX_POINT('',#93408); -#93408 = CARTESIAN_POINT('',(10.,6.85,0.75)); -#93409 = VERTEX_POINT('',#93410); -#93410 = CARTESIAN_POINT('',(10.,6.85,0.65)); -#93411 = SURFACE_CURVE('',#93412,(#93416,#93423),.PCURVE_S1.); -#93412 = LINE('',#93413,#93414); -#93413 = CARTESIAN_POINT('',(10.,6.85,0.65)); -#93414 = VECTOR('',#93415,1.); -#93415 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93416 = PCURVE('',#92272,#93417); -#93417 = DEFINITIONAL_REPRESENTATION('',(#93418),#93422); -#93418 = LINE('',#93419,#93420); -#93419 = CARTESIAN_POINT('',(-0.75,6.85)); -#93420 = VECTOR('',#93421,1.); -#93421 = DIRECTION('',(-1.,0.E+000)); -#93422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93423 = PCURVE('',#93424,#93429); -#93424 = PLANE('',#93425); -#93425 = AXIS2_PLACEMENT_3D('',#93426,#93427,#93428); -#93426 = CARTESIAN_POINT('',(10.527847992439,6.85,0.65)); -#93427 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93428 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93429 = DEFINITIONAL_REPRESENTATION('',(#93430),#93434); -#93430 = LINE('',#93431,#93432); -#93431 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93432 = VECTOR('',#93433,1.); -#93433 = DIRECTION('',(-1.,0.E+000)); -#93434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93435 = ORIENTED_EDGE('',*,*,#93436,.T.); -#93436 = EDGE_CURVE('',#93409,#93437,#93439,.T.); -#93437 = VERTEX_POINT('',#93438); -#93438 = CARTESIAN_POINT('',(10.,6.65,0.65)); -#93439 = SURFACE_CURVE('',#93440,(#93444,#93451),.PCURVE_S1.); -#93440 = LINE('',#93441,#93442); -#93441 = CARTESIAN_POINT('',(10.,6.65,0.65)); -#93442 = VECTOR('',#93443,1.); -#93443 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93444 = PCURVE('',#92272,#93445); -#93445 = DEFINITIONAL_REPRESENTATION('',(#93446),#93450); -#93446 = LINE('',#93447,#93448); -#93447 = CARTESIAN_POINT('',(-0.75,6.65)); -#93448 = VECTOR('',#93449,1.); -#93449 = DIRECTION('',(0.E+000,-1.)); -#93450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93451 = PCURVE('',#93452,#93457); -#93452 = PLANE('',#93453); -#93453 = AXIS2_PLACEMENT_3D('',#93454,#93455,#93456); -#93454 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); -#93455 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93456 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93457 = DEFINITIONAL_REPRESENTATION('',(#93458),#93462); -#93458 = LINE('',#93459,#93460); -#93459 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93460 = VECTOR('',#93461,1.); -#93461 = DIRECTION('',(4.440892098501E-016,-1.)); -#93462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93463 = ORIENTED_EDGE('',*,*,#93464,.T.); -#93464 = EDGE_CURVE('',#93437,#93465,#93467,.T.); -#93465 = VERTEX_POINT('',#93466); -#93466 = CARTESIAN_POINT('',(10.,6.65,0.75)); -#93467 = SURFACE_CURVE('',#93468,(#93472,#93479),.PCURVE_S1.); -#93468 = LINE('',#93469,#93470); -#93469 = CARTESIAN_POINT('',(10.,6.65,0.65)); -#93470 = VECTOR('',#93471,1.); -#93471 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93472 = PCURVE('',#92272,#93473); -#93473 = DEFINITIONAL_REPRESENTATION('',(#93474),#93478); -#93474 = LINE('',#93475,#93476); -#93475 = CARTESIAN_POINT('',(-0.75,6.65)); -#93476 = VECTOR('',#93477,1.); -#93477 = DIRECTION('',(1.,0.E+000)); -#93478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93479 = PCURVE('',#93480,#93485); -#93480 = PLANE('',#93481); -#93481 = AXIS2_PLACEMENT_3D('',#93482,#93483,#93484); -#93482 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); -#93483 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93484 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93485 = DEFINITIONAL_REPRESENTATION('',(#93486),#93490); -#93486 = LINE('',#93487,#93488); -#93487 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93488 = VECTOR('',#93489,1.); -#93489 = DIRECTION('',(-1.,0.E+000)); -#93490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93491 = ORIENTED_EDGE('',*,*,#93492,.T.); -#93492 = EDGE_CURVE('',#93465,#93407,#93493,.T.); -#93493 = SURFACE_CURVE('',#93494,(#93498,#93505),.PCURVE_S1.); -#93494 = LINE('',#93495,#93496); -#93495 = CARTESIAN_POINT('',(10.,6.65,0.75)); -#93496 = VECTOR('',#93497,1.); -#93497 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93498 = PCURVE('',#92272,#93499); -#93499 = DEFINITIONAL_REPRESENTATION('',(#93500),#93504); -#93500 = LINE('',#93501,#93502); -#93501 = CARTESIAN_POINT('',(-0.65,6.65)); -#93502 = VECTOR('',#93503,1.); -#93503 = DIRECTION('',(0.E+000,1.)); -#93504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93505 = PCURVE('',#93506,#93511); -#93506 = PLANE('',#93507); -#93507 = AXIS2_PLACEMENT_3D('',#93508,#93509,#93510); -#93508 = CARTESIAN_POINT('',(10.527847992439,6.65,0.75)); -#93509 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93510 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93511 = DEFINITIONAL_REPRESENTATION('',(#93512),#93516); -#93512 = LINE('',#93513,#93514); -#93513 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93514 = VECTOR('',#93515,1.); -#93515 = DIRECTION('',(4.440892098501E-016,1.)); -#93516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93517 = FACE_BOUND('',#93518,.T.); -#93518 = EDGE_LOOP('',(#93519,#93549,#93577,#93605)); -#93519 = ORIENTED_EDGE('',*,*,#93520,.T.); -#93520 = EDGE_CURVE('',#93521,#93523,#93525,.T.); -#93521 = VERTEX_POINT('',#93522); -#93522 = CARTESIAN_POINT('',(10.,7.35,0.75)); -#93523 = VERTEX_POINT('',#93524); -#93524 = CARTESIAN_POINT('',(10.,7.35,0.65)); -#93525 = SURFACE_CURVE('',#93526,(#93530,#93537),.PCURVE_S1.); -#93526 = LINE('',#93527,#93528); -#93527 = CARTESIAN_POINT('',(10.,7.35,0.65)); -#93528 = VECTOR('',#93529,1.); -#93529 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93530 = PCURVE('',#92272,#93531); -#93531 = DEFINITIONAL_REPRESENTATION('',(#93532),#93536); -#93532 = LINE('',#93533,#93534); -#93533 = CARTESIAN_POINT('',(-0.75,7.35)); -#93534 = VECTOR('',#93535,1.); -#93535 = DIRECTION('',(-1.,0.E+000)); -#93536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93537 = PCURVE('',#93538,#93543); -#93538 = PLANE('',#93539); -#93539 = AXIS2_PLACEMENT_3D('',#93540,#93541,#93542); -#93540 = CARTESIAN_POINT('',(10.527847992439,7.35,0.65)); -#93541 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93542 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93543 = DEFINITIONAL_REPRESENTATION('',(#93544),#93548); -#93544 = LINE('',#93545,#93546); -#93545 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93546 = VECTOR('',#93547,1.); -#93547 = DIRECTION('',(-1.,0.E+000)); -#93548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93549 = ORIENTED_EDGE('',*,*,#93550,.T.); -#93550 = EDGE_CURVE('',#93523,#93551,#93553,.T.); -#93551 = VERTEX_POINT('',#93552); -#93552 = CARTESIAN_POINT('',(10.,7.15,0.65)); -#93553 = SURFACE_CURVE('',#93554,(#93558,#93565),.PCURVE_S1.); -#93554 = LINE('',#93555,#93556); -#93555 = CARTESIAN_POINT('',(10.,7.15,0.65)); -#93556 = VECTOR('',#93557,1.); -#93557 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93558 = PCURVE('',#92272,#93559); -#93559 = DEFINITIONAL_REPRESENTATION('',(#93560),#93564); -#93560 = LINE('',#93561,#93562); -#93561 = CARTESIAN_POINT('',(-0.75,7.15)); -#93562 = VECTOR('',#93563,1.); -#93563 = DIRECTION('',(0.E+000,-1.)); -#93564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93565 = PCURVE('',#93566,#93571); -#93566 = PLANE('',#93567); -#93567 = AXIS2_PLACEMENT_3D('',#93568,#93569,#93570); -#93568 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); -#93569 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93570 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93571 = DEFINITIONAL_REPRESENTATION('',(#93572),#93576); -#93572 = LINE('',#93573,#93574); -#93573 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93574 = VECTOR('',#93575,1.); -#93575 = DIRECTION('',(4.440892098501E-016,-1.)); -#93576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93577 = ORIENTED_EDGE('',*,*,#93578,.T.); -#93578 = EDGE_CURVE('',#93551,#93579,#93581,.T.); -#93579 = VERTEX_POINT('',#93580); -#93580 = CARTESIAN_POINT('',(10.,7.15,0.75)); -#93581 = SURFACE_CURVE('',#93582,(#93586,#93593),.PCURVE_S1.); -#93582 = LINE('',#93583,#93584); -#93583 = CARTESIAN_POINT('',(10.,7.15,0.65)); -#93584 = VECTOR('',#93585,1.); -#93585 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93586 = PCURVE('',#92272,#93587); -#93587 = DEFINITIONAL_REPRESENTATION('',(#93588),#93592); -#93588 = LINE('',#93589,#93590); -#93589 = CARTESIAN_POINT('',(-0.75,7.15)); -#93590 = VECTOR('',#93591,1.); -#93591 = DIRECTION('',(1.,0.E+000)); -#93592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93593 = PCURVE('',#93594,#93599); -#93594 = PLANE('',#93595); -#93595 = AXIS2_PLACEMENT_3D('',#93596,#93597,#93598); -#93596 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); -#93597 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93598 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93599 = DEFINITIONAL_REPRESENTATION('',(#93600),#93604); -#93600 = LINE('',#93601,#93602); -#93601 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93602 = VECTOR('',#93603,1.); -#93603 = DIRECTION('',(-1.,0.E+000)); -#93604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93605 = ORIENTED_EDGE('',*,*,#93606,.T.); -#93606 = EDGE_CURVE('',#93579,#93521,#93607,.T.); -#93607 = SURFACE_CURVE('',#93608,(#93612,#93619),.PCURVE_S1.); -#93608 = LINE('',#93609,#93610); -#93609 = CARTESIAN_POINT('',(10.,7.15,0.75)); -#93610 = VECTOR('',#93611,1.); -#93611 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93612 = PCURVE('',#92272,#93613); -#93613 = DEFINITIONAL_REPRESENTATION('',(#93614),#93618); -#93614 = LINE('',#93615,#93616); -#93615 = CARTESIAN_POINT('',(-0.65,7.15)); -#93616 = VECTOR('',#93617,1.); -#93617 = DIRECTION('',(0.E+000,1.)); -#93618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93619 = PCURVE('',#93620,#93625); -#93620 = PLANE('',#93621); -#93621 = AXIS2_PLACEMENT_3D('',#93622,#93623,#93624); -#93622 = CARTESIAN_POINT('',(10.527847992439,7.15,0.75)); -#93623 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93624 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93625 = DEFINITIONAL_REPRESENTATION('',(#93626),#93630); -#93626 = LINE('',#93627,#93628); -#93627 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93628 = VECTOR('',#93629,1.); -#93629 = DIRECTION('',(4.440892098501E-016,1.)); -#93630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93631 = FACE_BOUND('',#93632,.T.); -#93632 = EDGE_LOOP('',(#93633,#93663,#93691,#93719)); -#93633 = ORIENTED_EDGE('',*,*,#93634,.T.); -#93634 = EDGE_CURVE('',#93635,#93637,#93639,.T.); -#93635 = VERTEX_POINT('',#93636); -#93636 = CARTESIAN_POINT('',(10.,7.85,0.75)); -#93637 = VERTEX_POINT('',#93638); -#93638 = CARTESIAN_POINT('',(10.,7.85,0.65)); -#93639 = SURFACE_CURVE('',#93640,(#93644,#93651),.PCURVE_S1.); -#93640 = LINE('',#93641,#93642); -#93641 = CARTESIAN_POINT('',(10.,7.85,0.65)); -#93642 = VECTOR('',#93643,1.); -#93643 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93644 = PCURVE('',#92272,#93645); -#93645 = DEFINITIONAL_REPRESENTATION('',(#93646),#93650); -#93646 = LINE('',#93647,#93648); -#93647 = CARTESIAN_POINT('',(-0.75,7.85)); -#93648 = VECTOR('',#93649,1.); -#93649 = DIRECTION('',(-1.,0.E+000)); -#93650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93651 = PCURVE('',#93652,#93657); -#93652 = PLANE('',#93653); -#93653 = AXIS2_PLACEMENT_3D('',#93654,#93655,#93656); -#93654 = CARTESIAN_POINT('',(10.527847992439,7.85,0.65)); -#93655 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93656 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93657 = DEFINITIONAL_REPRESENTATION('',(#93658),#93662); -#93658 = LINE('',#93659,#93660); -#93659 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93660 = VECTOR('',#93661,1.); -#93661 = DIRECTION('',(-1.,0.E+000)); -#93662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93663 = ORIENTED_EDGE('',*,*,#93664,.T.); -#93664 = EDGE_CURVE('',#93637,#93665,#93667,.T.); -#93665 = VERTEX_POINT('',#93666); -#93666 = CARTESIAN_POINT('',(10.,7.65,0.65)); -#93667 = SURFACE_CURVE('',#93668,(#93672,#93679),.PCURVE_S1.); -#93668 = LINE('',#93669,#93670); -#93669 = CARTESIAN_POINT('',(10.,7.65,0.65)); -#93670 = VECTOR('',#93671,1.); -#93671 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93672 = PCURVE('',#92272,#93673); -#93673 = DEFINITIONAL_REPRESENTATION('',(#93674),#93678); -#93674 = LINE('',#93675,#93676); -#93675 = CARTESIAN_POINT('',(-0.75,7.65)); -#93676 = VECTOR('',#93677,1.); -#93677 = DIRECTION('',(0.E+000,-1.)); -#93678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93679 = PCURVE('',#93680,#93685); -#93680 = PLANE('',#93681); -#93681 = AXIS2_PLACEMENT_3D('',#93682,#93683,#93684); -#93682 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); -#93683 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93684 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93685 = DEFINITIONAL_REPRESENTATION('',(#93686),#93690); -#93686 = LINE('',#93687,#93688); -#93687 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93688 = VECTOR('',#93689,1.); -#93689 = DIRECTION('',(4.440892098501E-016,-1.)); -#93690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93691 = ORIENTED_EDGE('',*,*,#93692,.T.); -#93692 = EDGE_CURVE('',#93665,#93693,#93695,.T.); -#93693 = VERTEX_POINT('',#93694); -#93694 = CARTESIAN_POINT('',(10.,7.65,0.75)); -#93695 = SURFACE_CURVE('',#93696,(#93700,#93707),.PCURVE_S1.); -#93696 = LINE('',#93697,#93698); -#93697 = CARTESIAN_POINT('',(10.,7.65,0.65)); -#93698 = VECTOR('',#93699,1.); -#93699 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93700 = PCURVE('',#92272,#93701); -#93701 = DEFINITIONAL_REPRESENTATION('',(#93702),#93706); -#93702 = LINE('',#93703,#93704); -#93703 = CARTESIAN_POINT('',(-0.75,7.65)); -#93704 = VECTOR('',#93705,1.); -#93705 = DIRECTION('',(1.,0.E+000)); -#93706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93707 = PCURVE('',#93708,#93713); -#93708 = PLANE('',#93709); -#93709 = AXIS2_PLACEMENT_3D('',#93710,#93711,#93712); -#93710 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); -#93711 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93712 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93713 = DEFINITIONAL_REPRESENTATION('',(#93714),#93718); -#93714 = LINE('',#93715,#93716); -#93715 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93716 = VECTOR('',#93717,1.); -#93717 = DIRECTION('',(-1.,0.E+000)); -#93718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93719 = ORIENTED_EDGE('',*,*,#93720,.T.); -#93720 = EDGE_CURVE('',#93693,#93635,#93721,.T.); -#93721 = SURFACE_CURVE('',#93722,(#93726,#93733),.PCURVE_S1.); -#93722 = LINE('',#93723,#93724); -#93723 = CARTESIAN_POINT('',(10.,7.65,0.75)); -#93724 = VECTOR('',#93725,1.); -#93725 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93726 = PCURVE('',#92272,#93727); -#93727 = DEFINITIONAL_REPRESENTATION('',(#93728),#93732); -#93728 = LINE('',#93729,#93730); -#93729 = CARTESIAN_POINT('',(-0.65,7.65)); -#93730 = VECTOR('',#93731,1.); -#93731 = DIRECTION('',(0.E+000,1.)); -#93732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93733 = PCURVE('',#93734,#93739); -#93734 = PLANE('',#93735); -#93735 = AXIS2_PLACEMENT_3D('',#93736,#93737,#93738); -#93736 = CARTESIAN_POINT('',(10.527847992439,7.65,0.75)); -#93737 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93738 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93739 = DEFINITIONAL_REPRESENTATION('',(#93740),#93744); -#93740 = LINE('',#93741,#93742); -#93741 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93742 = VECTOR('',#93743,1.); -#93743 = DIRECTION('',(4.440892098501E-016,1.)); -#93744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93745 = FACE_BOUND('',#93746,.T.); -#93746 = EDGE_LOOP('',(#93747,#93777,#93805,#93833)); -#93747 = ORIENTED_EDGE('',*,*,#93748,.T.); -#93748 = EDGE_CURVE('',#93749,#93751,#93753,.T.); -#93749 = VERTEX_POINT('',#93750); -#93750 = CARTESIAN_POINT('',(10.,8.35,0.75)); -#93751 = VERTEX_POINT('',#93752); -#93752 = CARTESIAN_POINT('',(10.,8.35,0.65)); -#93753 = SURFACE_CURVE('',#93754,(#93758,#93765),.PCURVE_S1.); -#93754 = LINE('',#93755,#93756); -#93755 = CARTESIAN_POINT('',(10.,8.35,0.65)); -#93756 = VECTOR('',#93757,1.); -#93757 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93758 = PCURVE('',#92272,#93759); -#93759 = DEFINITIONAL_REPRESENTATION('',(#93760),#93764); -#93760 = LINE('',#93761,#93762); -#93761 = CARTESIAN_POINT('',(-0.75,8.35)); -#93762 = VECTOR('',#93763,1.); -#93763 = DIRECTION('',(-1.,0.E+000)); -#93764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93765 = PCURVE('',#93766,#93771); -#93766 = PLANE('',#93767); -#93767 = AXIS2_PLACEMENT_3D('',#93768,#93769,#93770); -#93768 = CARTESIAN_POINT('',(10.527847992439,8.35,0.65)); -#93769 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93770 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93771 = DEFINITIONAL_REPRESENTATION('',(#93772),#93776); -#93772 = LINE('',#93773,#93774); -#93773 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93774 = VECTOR('',#93775,1.); -#93775 = DIRECTION('',(-1.,0.E+000)); -#93776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93777 = ORIENTED_EDGE('',*,*,#93778,.T.); -#93778 = EDGE_CURVE('',#93751,#93779,#93781,.T.); -#93779 = VERTEX_POINT('',#93780); -#93780 = CARTESIAN_POINT('',(10.,8.15,0.65)); -#93781 = SURFACE_CURVE('',#93782,(#93786,#93793),.PCURVE_S1.); -#93782 = LINE('',#93783,#93784); -#93783 = CARTESIAN_POINT('',(10.,8.15,0.65)); -#93784 = VECTOR('',#93785,1.); -#93785 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93786 = PCURVE('',#92272,#93787); -#93787 = DEFINITIONAL_REPRESENTATION('',(#93788),#93792); -#93788 = LINE('',#93789,#93790); -#93789 = CARTESIAN_POINT('',(-0.75,8.15)); -#93790 = VECTOR('',#93791,1.); -#93791 = DIRECTION('',(0.E+000,-1.)); -#93792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93793 = PCURVE('',#93794,#93799); -#93794 = PLANE('',#93795); -#93795 = AXIS2_PLACEMENT_3D('',#93796,#93797,#93798); -#93796 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); -#93797 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93798 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93799 = DEFINITIONAL_REPRESENTATION('',(#93800),#93804); -#93800 = LINE('',#93801,#93802); -#93801 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93802 = VECTOR('',#93803,1.); -#93803 = DIRECTION('',(4.440892098501E-016,-1.)); -#93804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93805 = ORIENTED_EDGE('',*,*,#93806,.T.); -#93806 = EDGE_CURVE('',#93779,#93807,#93809,.T.); -#93807 = VERTEX_POINT('',#93808); -#93808 = CARTESIAN_POINT('',(10.,8.15,0.75)); -#93809 = SURFACE_CURVE('',#93810,(#93814,#93821),.PCURVE_S1.); -#93810 = LINE('',#93811,#93812); -#93811 = CARTESIAN_POINT('',(10.,8.15,0.65)); -#93812 = VECTOR('',#93813,1.); -#93813 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93814 = PCURVE('',#92272,#93815); -#93815 = DEFINITIONAL_REPRESENTATION('',(#93816),#93820); -#93816 = LINE('',#93817,#93818); -#93817 = CARTESIAN_POINT('',(-0.75,8.15)); -#93818 = VECTOR('',#93819,1.); -#93819 = DIRECTION('',(1.,0.E+000)); -#93820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93821 = PCURVE('',#93822,#93827); -#93822 = PLANE('',#93823); -#93823 = AXIS2_PLACEMENT_3D('',#93824,#93825,#93826); -#93824 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); -#93825 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93826 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93827 = DEFINITIONAL_REPRESENTATION('',(#93828),#93832); -#93828 = LINE('',#93829,#93830); -#93829 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93830 = VECTOR('',#93831,1.); -#93831 = DIRECTION('',(-1.,0.E+000)); -#93832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93833 = ORIENTED_EDGE('',*,*,#93834,.T.); -#93834 = EDGE_CURVE('',#93807,#93749,#93835,.T.); -#93835 = SURFACE_CURVE('',#93836,(#93840,#93847),.PCURVE_S1.); -#93836 = LINE('',#93837,#93838); -#93837 = CARTESIAN_POINT('',(10.,8.15,0.75)); -#93838 = VECTOR('',#93839,1.); -#93839 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93840 = PCURVE('',#92272,#93841); -#93841 = DEFINITIONAL_REPRESENTATION('',(#93842),#93846); -#93842 = LINE('',#93843,#93844); -#93843 = CARTESIAN_POINT('',(-0.65,8.15)); -#93844 = VECTOR('',#93845,1.); -#93845 = DIRECTION('',(0.E+000,1.)); -#93846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93847 = PCURVE('',#93848,#93853); -#93848 = PLANE('',#93849); -#93849 = AXIS2_PLACEMENT_3D('',#93850,#93851,#93852); -#93850 = CARTESIAN_POINT('',(10.527847992439,8.15,0.75)); -#93851 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93852 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93853 = DEFINITIONAL_REPRESENTATION('',(#93854),#93858); -#93854 = LINE('',#93855,#93856); -#93855 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93856 = VECTOR('',#93857,1.); -#93857 = DIRECTION('',(4.440892098501E-016,1.)); -#93858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93859 = FACE_BOUND('',#93860,.T.); -#93860 = EDGE_LOOP('',(#93861,#93891,#93919,#93947)); -#93861 = ORIENTED_EDGE('',*,*,#93862,.T.); -#93862 = EDGE_CURVE('',#93863,#93865,#93867,.T.); -#93863 = VERTEX_POINT('',#93864); -#93864 = CARTESIAN_POINT('',(10.,4.65,0.75)); -#93865 = VERTEX_POINT('',#93866); -#93866 = CARTESIAN_POINT('',(10.,4.85,0.75)); -#93867 = SURFACE_CURVE('',#93868,(#93872,#93879),.PCURVE_S1.); -#93868 = LINE('',#93869,#93870); -#93869 = CARTESIAN_POINT('',(10.,4.85,0.75)); -#93870 = VECTOR('',#93871,1.); -#93871 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#93872 = PCURVE('',#92272,#93873); -#93873 = DEFINITIONAL_REPRESENTATION('',(#93874),#93878); -#93874 = LINE('',#93875,#93876); -#93875 = CARTESIAN_POINT('',(-0.65,4.85)); -#93876 = VECTOR('',#93877,1.); -#93877 = DIRECTION('',(0.E+000,1.)); -#93878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93879 = PCURVE('',#93880,#93885); -#93880 = PLANE('',#93881); -#93881 = AXIS2_PLACEMENT_3D('',#93882,#93883,#93884); -#93882 = CARTESIAN_POINT('',(10.527847992439,4.85,0.75)); -#93883 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#93884 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#93885 = DEFINITIONAL_REPRESENTATION('',(#93886),#93890); -#93886 = LINE('',#93887,#93888); -#93887 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#93888 = VECTOR('',#93889,1.); -#93889 = DIRECTION('',(4.440892098501E-016,1.)); -#93890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93891 = ORIENTED_EDGE('',*,*,#93892,.T.); -#93892 = EDGE_CURVE('',#93865,#93893,#93895,.T.); -#93893 = VERTEX_POINT('',#93894); -#93894 = CARTESIAN_POINT('',(10.,4.85,0.65)); -#93895 = SURFACE_CURVE('',#93896,(#93900,#93907),.PCURVE_S1.); -#93896 = LINE('',#93897,#93898); -#93897 = CARTESIAN_POINT('',(10.,4.85,0.65)); -#93898 = VECTOR('',#93899,1.); -#93899 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93900 = PCURVE('',#92272,#93901); -#93901 = DEFINITIONAL_REPRESENTATION('',(#93902),#93906); -#93902 = LINE('',#93903,#93904); -#93903 = CARTESIAN_POINT('',(-0.75,4.85)); -#93904 = VECTOR('',#93905,1.); -#93905 = DIRECTION('',(-1.,0.E+000)); -#93906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93907 = PCURVE('',#93908,#93913); -#93908 = PLANE('',#93909); -#93909 = AXIS2_PLACEMENT_3D('',#93910,#93911,#93912); -#93910 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); -#93911 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93912 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93913 = DEFINITIONAL_REPRESENTATION('',(#93914),#93918); -#93914 = LINE('',#93915,#93916); -#93915 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#93916 = VECTOR('',#93917,1.); -#93917 = DIRECTION('',(-1.,0.E+000)); -#93918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93919 = ORIENTED_EDGE('',*,*,#93920,.T.); -#93920 = EDGE_CURVE('',#93893,#93921,#93923,.T.); -#93921 = VERTEX_POINT('',#93922); -#93922 = CARTESIAN_POINT('',(10.,4.65,0.65)); -#93923 = SURFACE_CURVE('',#93924,(#93928,#93935),.PCURVE_S1.); -#93924 = LINE('',#93925,#93926); -#93925 = CARTESIAN_POINT('',(10.,4.85,0.65)); -#93926 = VECTOR('',#93927,1.); -#93927 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#93928 = PCURVE('',#92272,#93929); -#93929 = DEFINITIONAL_REPRESENTATION('',(#93930),#93934); -#93930 = LINE('',#93931,#93932); -#93931 = CARTESIAN_POINT('',(-0.75,4.85)); -#93932 = VECTOR('',#93933,1.); -#93933 = DIRECTION('',(0.E+000,-1.)); -#93934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93935 = PCURVE('',#93936,#93941); -#93936 = PLANE('',#93937); -#93937 = AXIS2_PLACEMENT_3D('',#93938,#93939,#93940); -#93938 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); -#93939 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#93940 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#93941 = DEFINITIONAL_REPRESENTATION('',(#93942),#93946); -#93942 = LINE('',#93943,#93944); -#93943 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#93944 = VECTOR('',#93945,1.); -#93945 = DIRECTION('',(4.440892098501E-016,-1.)); -#93946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93947 = ORIENTED_EDGE('',*,*,#93948,.T.); -#93948 = EDGE_CURVE('',#93921,#93863,#93949,.T.); -#93949 = SURFACE_CURVE('',#93950,(#93954,#93961),.PCURVE_S1.); -#93950 = LINE('',#93951,#93952); -#93951 = CARTESIAN_POINT('',(10.,4.65,0.65)); -#93952 = VECTOR('',#93953,1.); -#93953 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93954 = PCURVE('',#92272,#93955); -#93955 = DEFINITIONAL_REPRESENTATION('',(#93956),#93960); -#93956 = LINE('',#93957,#93958); -#93957 = CARTESIAN_POINT('',(-0.75,4.65)); -#93958 = VECTOR('',#93959,1.); -#93959 = DIRECTION('',(1.,0.E+000)); -#93960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93961 = PCURVE('',#93962,#93967); -#93962 = PLANE('',#93963); -#93963 = AXIS2_PLACEMENT_3D('',#93964,#93965,#93966); -#93964 = CARTESIAN_POINT('',(10.527847992439,4.65,0.65)); -#93965 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#93966 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93967 = DEFINITIONAL_REPRESENTATION('',(#93968),#93972); -#93968 = LINE('',#93969,#93970); -#93969 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#93970 = VECTOR('',#93971,1.); -#93971 = DIRECTION('',(-1.,0.E+000)); -#93972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93973 = FACE_BOUND('',#93974,.T.); -#93974 = EDGE_LOOP('',(#93975,#94005,#94033,#94061)); -#93975 = ORIENTED_EDGE('',*,*,#93976,.T.); -#93976 = EDGE_CURVE('',#93977,#93979,#93981,.T.); -#93977 = VERTEX_POINT('',#93978); -#93978 = CARTESIAN_POINT('',(10.,8.85,0.75)); -#93979 = VERTEX_POINT('',#93980); -#93980 = CARTESIAN_POINT('',(10.,8.85,0.65)); -#93981 = SURFACE_CURVE('',#93982,(#93986,#93993),.PCURVE_S1.); -#93982 = LINE('',#93983,#93984); -#93983 = CARTESIAN_POINT('',(10.,8.85,0.65)); -#93984 = VECTOR('',#93985,1.); -#93985 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#93986 = PCURVE('',#92272,#93987); -#93987 = DEFINITIONAL_REPRESENTATION('',(#93988),#93992); -#93988 = LINE('',#93989,#93990); -#93989 = CARTESIAN_POINT('',(-0.75,8.85)); -#93990 = VECTOR('',#93991,1.); -#93991 = DIRECTION('',(-1.,0.E+000)); -#93992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#93993 = PCURVE('',#93994,#93999); -#93994 = PLANE('',#93995); -#93995 = AXIS2_PLACEMENT_3D('',#93996,#93997,#93998); -#93996 = CARTESIAN_POINT('',(10.527847992439,8.85,0.65)); -#93997 = DIRECTION('',(0.E+000,1.,0.E+000)); -#93998 = DIRECTION('',(0.E+000,0.E+000,1.)); -#93999 = DEFINITIONAL_REPRESENTATION('',(#94000),#94004); -#94000 = LINE('',#94001,#94002); -#94001 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); -#94002 = VECTOR('',#94003,1.); -#94003 = DIRECTION('',(-1.,0.E+000)); -#94004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94005 = ORIENTED_EDGE('',*,*,#94006,.T.); -#94006 = EDGE_CURVE('',#93979,#94007,#94009,.T.); -#94007 = VERTEX_POINT('',#94008); -#94008 = CARTESIAN_POINT('',(10.,8.65,0.65)); -#94009 = SURFACE_CURVE('',#94010,(#94014,#94021),.PCURVE_S1.); -#94010 = LINE('',#94011,#94012); -#94011 = CARTESIAN_POINT('',(10.,8.65,0.65)); -#94012 = VECTOR('',#94013,1.); -#94013 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#94014 = PCURVE('',#92272,#94015); -#94015 = DEFINITIONAL_REPRESENTATION('',(#94016),#94020); -#94016 = LINE('',#94017,#94018); -#94017 = CARTESIAN_POINT('',(-0.75,8.65)); -#94018 = VECTOR('',#94019,1.); -#94019 = DIRECTION('',(0.E+000,-1.)); -#94020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94021 = PCURVE('',#94022,#94027); -#94022 = PLANE('',#94023); -#94023 = AXIS2_PLACEMENT_3D('',#94024,#94025,#94026); -#94024 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); -#94025 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); -#94026 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#94027 = DEFINITIONAL_REPRESENTATION('',(#94028),#94032); -#94028 = LINE('',#94029,#94030); -#94029 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); -#94030 = VECTOR('',#94031,1.); -#94031 = DIRECTION('',(4.440892098501E-016,-1.)); -#94032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94033 = ORIENTED_EDGE('',*,*,#94034,.T.); -#94034 = EDGE_CURVE('',#94007,#94035,#94037,.T.); -#94035 = VERTEX_POINT('',#94036); -#94036 = CARTESIAN_POINT('',(10.,8.65,0.75)); -#94037 = SURFACE_CURVE('',#94038,(#94042,#94049),.PCURVE_S1.); -#94038 = LINE('',#94039,#94040); -#94039 = CARTESIAN_POINT('',(10.,8.65,0.65)); -#94040 = VECTOR('',#94041,1.); -#94041 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94042 = PCURVE('',#92272,#94043); -#94043 = DEFINITIONAL_REPRESENTATION('',(#94044),#94048); -#94044 = LINE('',#94045,#94046); -#94045 = CARTESIAN_POINT('',(-0.75,8.65)); -#94046 = VECTOR('',#94047,1.); -#94047 = DIRECTION('',(1.,0.E+000)); -#94048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94049 = PCURVE('',#94050,#94055); -#94050 = PLANE('',#94051); -#94051 = AXIS2_PLACEMENT_3D('',#94052,#94053,#94054); -#94052 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); -#94053 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94054 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94055 = DEFINITIONAL_REPRESENTATION('',(#94056),#94060); -#94056 = LINE('',#94057,#94058); -#94057 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); -#94058 = VECTOR('',#94059,1.); -#94059 = DIRECTION('',(-1.,0.E+000)); -#94060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94061 = ORIENTED_EDGE('',*,*,#94062,.T.); -#94062 = EDGE_CURVE('',#94035,#93977,#94063,.T.); -#94063 = SURFACE_CURVE('',#94064,(#94068,#94075),.PCURVE_S1.); -#94064 = LINE('',#94065,#94066); -#94065 = CARTESIAN_POINT('',(10.,8.65,0.75)); -#94066 = VECTOR('',#94067,1.); -#94067 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#94068 = PCURVE('',#92272,#94069); -#94069 = DEFINITIONAL_REPRESENTATION('',(#94070),#94074); -#94070 = LINE('',#94071,#94072); -#94071 = CARTESIAN_POINT('',(-0.65,8.65)); -#94072 = VECTOR('',#94073,1.); -#94073 = DIRECTION('',(0.E+000,1.)); -#94074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94075 = PCURVE('',#94076,#94081); -#94076 = PLANE('',#94077); -#94077 = AXIS2_PLACEMENT_3D('',#94078,#94079,#94080); -#94078 = CARTESIAN_POINT('',(10.527847992439,8.65,0.75)); -#94079 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); -#94080 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); -#94081 = DEFINITIONAL_REPRESENTATION('',(#94082),#94086); -#94082 = LINE('',#94083,#94084); -#94083 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); -#94084 = VECTOR('',#94085,1.); -#94085 = DIRECTION('',(4.440892098501E-016,1.)); -#94086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94087 = FACE_BOUND('',#94088,.T.); -#94088 = EDGE_LOOP('',(#94089,#94119,#94142,#94165)); -#94089 = ORIENTED_EDGE('',*,*,#94090,.T.); -#94090 = EDGE_CURVE('',#94091,#94093,#94095,.T.); -#94091 = VERTEX_POINT('',#94092); -#94092 = CARTESIAN_POINT('',(10.,9.8,1.2)); -#94093 = VERTEX_POINT('',#94094); -#94094 = CARTESIAN_POINT('',(10.,0.2,1.2)); -#94095 = SURFACE_CURVE('',#94096,(#94100,#94107),.PCURVE_S1.); -#94096 = LINE('',#94097,#94098); -#94097 = CARTESIAN_POINT('',(10.,0.E+000,1.2)); -#94098 = VECTOR('',#94099,1.); -#94099 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94100 = PCURVE('',#92272,#94101); -#94101 = DEFINITIONAL_REPRESENTATION('',(#94102),#94106); -#94102 = LINE('',#94103,#94104); -#94103 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#94104 = VECTOR('',#94105,1.); -#94105 = DIRECTION('',(0.E+000,-1.)); -#94106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94107 = PCURVE('',#94108,#94113); -#94108 = PLANE('',#94109); -#94109 = AXIS2_PLACEMENT_3D('',#94110,#94111,#94112); -#94110 = CARTESIAN_POINT('',(9.8,10.,1.4)); -#94111 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); -#94112 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); -#94113 = DEFINITIONAL_REPRESENTATION('',(#94114),#94118); -#94114 = LINE('',#94115,#94116); -#94115 = CARTESIAN_POINT('',(-0.282842712475,-10.)); -#94116 = VECTOR('',#94117,1.); -#94117 = DIRECTION('',(0.E+000,-1.)); -#94118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94119 = ORIENTED_EDGE('',*,*,#94120,.T.); -#94120 = EDGE_CURVE('',#94093,#94121,#94123,.T.); -#94121 = VERTEX_POINT('',#94122); -#94122 = CARTESIAN_POINT('',(10.,0.2,0.E+000)); -#94123 = SURFACE_CURVE('',#94124,(#94128,#94135),.PCURVE_S1.); -#94124 = LINE('',#94125,#94126); -#94125 = CARTESIAN_POINT('',(10.,0.2,1.4)); -#94126 = VECTOR('',#94127,1.); -#94127 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94128 = PCURVE('',#92272,#94129); -#94129 = DEFINITIONAL_REPRESENTATION('',(#94130),#94134); -#94130 = LINE('',#94131,#94132); -#94131 = CARTESIAN_POINT('',(0.E+000,0.2)); -#94132 = VECTOR('',#94133,1.); -#94133 = DIRECTION('',(-1.,0.E+000)); -#94134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94135 = PCURVE('',#89405,#94136); +#92726 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.75)); +#92727 = VERTEX_POINT('',#92728); +#92728 = CARTESIAN_POINT('',(0.E+000,8.65,0.65)); +#92729 = SURFACE_CURVE('',#92730,(#92734,#92746),.PCURVE_S1.); +#92730 = LINE('',#92731,#92732); +#92731 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.65)); +#92732 = VECTOR('',#92733,1.); +#92733 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92734 = PCURVE('',#92735,#92740); +#92735 = PLANE('',#92736); +#92736 = AXIS2_PLACEMENT_3D('',#92737,#92738,#92739); +#92737 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.4)); +#92738 = DIRECTION('',(1.,0.E+000,0.E+000)); +#92739 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92740 = DEFINITIONAL_REPRESENTATION('',(#92741),#92745); +#92741 = LINE('',#92742,#92743); +#92742 = CARTESIAN_POINT('',(0.75,8.65)); +#92743 = VECTOR('',#92744,1.); +#92744 = DIRECTION('',(1.,0.E+000)); +#92745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92746 = PCURVE('',#92747,#92752); +#92747 = PLANE('',#92748); +#92748 = AXIS2_PLACEMENT_3D('',#92749,#92750,#92751); +#92749 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); +#92750 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#92751 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92752 = DEFINITIONAL_REPRESENTATION('',(#92753),#92757); +#92753 = LINE('',#92754,#92755); +#92754 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92755 = VECTOR('',#92756,1.); +#92756 = DIRECTION('',(1.,0.E+000)); +#92757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92758 = ORIENTED_EDGE('',*,*,#92759,.T.); +#92759 = EDGE_CURVE('',#92727,#92760,#92762,.T.); +#92760 = VERTEX_POINT('',#92761); +#92761 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.65)); +#92762 = SURFACE_CURVE('',#92763,(#92767,#92774),.PCURVE_S1.); +#92763 = LINE('',#92764,#92765); +#92764 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.65)); +#92765 = VECTOR('',#92766,1.); +#92766 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#92767 = PCURVE('',#92735,#92768); +#92768 = DEFINITIONAL_REPRESENTATION('',(#92769),#92773); +#92769 = LINE('',#92770,#92771); +#92770 = CARTESIAN_POINT('',(0.75,8.65)); +#92771 = VECTOR('',#92772,1.); +#92772 = DIRECTION('',(0.E+000,1.)); +#92773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92774 = PCURVE('',#92775,#92780); +#92775 = PLANE('',#92776); +#92776 = AXIS2_PLACEMENT_3D('',#92777,#92778,#92779); +#92777 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); +#92778 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#92779 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#92780 = DEFINITIONAL_REPRESENTATION('',(#92781),#92785); +#92781 = LINE('',#92782,#92783); +#92782 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#92783 = VECTOR('',#92784,1.); +#92784 = DIRECTION('',(4.440892098501E-016,1.)); +#92785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92786 = ORIENTED_EDGE('',*,*,#92787,.T.); +#92787 = EDGE_CURVE('',#92760,#92788,#92790,.T.); +#92788 = VERTEX_POINT('',#92789); +#92789 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.75)); +#92790 = SURFACE_CURVE('',#92791,(#92795,#92802),.PCURVE_S1.); +#92791 = LINE('',#92792,#92793); +#92792 = CARTESIAN_POINT('',(-3.930189507173E-015,8.85,0.65)); +#92793 = VECTOR('',#92794,1.); +#92794 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92795 = PCURVE('',#92735,#92796); +#92796 = DEFINITIONAL_REPRESENTATION('',(#92797),#92801); +#92797 = LINE('',#92798,#92799); +#92798 = CARTESIAN_POINT('',(0.75,8.85)); +#92799 = VECTOR('',#92800,1.); +#92800 = DIRECTION('',(-1.,0.E+000)); +#92801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92802 = PCURVE('',#92803,#92808); +#92803 = PLANE('',#92804); +#92804 = AXIS2_PLACEMENT_3D('',#92805,#92806,#92807); +#92805 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.65)); +#92806 = DIRECTION('',(0.E+000,1.,0.E+000)); +#92807 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92808 = DEFINITIONAL_REPRESENTATION('',(#92809),#92813); +#92809 = LINE('',#92810,#92811); +#92810 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92811 = VECTOR('',#92812,1.); +#92812 = DIRECTION('',(1.,0.E+000)); +#92813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92814 = ORIENTED_EDGE('',*,*,#92815,.T.); +#92815 = EDGE_CURVE('',#92788,#92725,#92816,.T.); +#92816 = SURFACE_CURVE('',#92817,(#92821,#92828),.PCURVE_S1.); +#92817 = LINE('',#92818,#92819); +#92818 = CARTESIAN_POINT('',(-3.841371665203E-015,8.65,0.75)); +#92819 = VECTOR('',#92820,1.); +#92820 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#92821 = PCURVE('',#92735,#92822); +#92822 = DEFINITIONAL_REPRESENTATION('',(#92823),#92827); +#92823 = LINE('',#92824,#92825); +#92824 = CARTESIAN_POINT('',(0.65,8.65)); +#92825 = VECTOR('',#92826,1.); +#92826 = DIRECTION('',(0.E+000,-1.)); +#92827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92828 = PCURVE('',#92829,#92834); +#92829 = PLANE('',#92830); +#92830 = AXIS2_PLACEMENT_3D('',#92831,#92832,#92833); +#92831 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.75)); +#92832 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#92833 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#92834 = DEFINITIONAL_REPRESENTATION('',(#92835),#92839); +#92835 = LINE('',#92836,#92837); +#92836 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#92837 = VECTOR('',#92838,1.); +#92838 = DIRECTION('',(4.440892098501E-016,-1.)); +#92839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92840 = FACE_BOUND('',#92841,.T.); +#92841 = EDGE_LOOP('',(#92842,#92872,#92900,#92928)); +#92842 = ORIENTED_EDGE('',*,*,#92843,.T.); +#92843 = EDGE_CURVE('',#92844,#92846,#92848,.T.); +#92844 = VERTEX_POINT('',#92845); +#92845 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.75)); +#92846 = VERTEX_POINT('',#92847); +#92847 = CARTESIAN_POINT('',(0.E+000,8.15,0.65)); +#92848 = SURFACE_CURVE('',#92849,(#92853,#92860),.PCURVE_S1.); +#92849 = LINE('',#92850,#92851); +#92850 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.65)); +#92851 = VECTOR('',#92852,1.); +#92852 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92853 = PCURVE('',#92735,#92854); +#92854 = DEFINITIONAL_REPRESENTATION('',(#92855),#92859); +#92855 = LINE('',#92856,#92857); +#92856 = CARTESIAN_POINT('',(0.75,8.15)); +#92857 = VECTOR('',#92858,1.); +#92858 = DIRECTION('',(1.,0.E+000)); +#92859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92860 = PCURVE('',#92861,#92866); +#92861 = PLANE('',#92862); +#92862 = AXIS2_PLACEMENT_3D('',#92863,#92864,#92865); +#92863 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); +#92864 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#92865 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92866 = DEFINITIONAL_REPRESENTATION('',(#92867),#92871); +#92867 = LINE('',#92868,#92869); +#92868 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92869 = VECTOR('',#92870,1.); +#92870 = DIRECTION('',(1.,0.E+000)); +#92871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92872 = ORIENTED_EDGE('',*,*,#92873,.T.); +#92873 = EDGE_CURVE('',#92846,#92874,#92876,.T.); +#92874 = VERTEX_POINT('',#92875); +#92875 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.65)); +#92876 = SURFACE_CURVE('',#92877,(#92881,#92888),.PCURVE_S1.); +#92877 = LINE('',#92878,#92879); +#92878 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.65)); +#92879 = VECTOR('',#92880,1.); +#92880 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#92881 = PCURVE('',#92735,#92882); +#92882 = DEFINITIONAL_REPRESENTATION('',(#92883),#92887); +#92883 = LINE('',#92884,#92885); +#92884 = CARTESIAN_POINT('',(0.75,8.15)); +#92885 = VECTOR('',#92886,1.); +#92886 = DIRECTION('',(0.E+000,1.)); +#92887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92888 = PCURVE('',#92889,#92894); +#92889 = PLANE('',#92890); +#92890 = AXIS2_PLACEMENT_3D('',#92891,#92892,#92893); +#92891 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); +#92892 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#92893 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#92894 = DEFINITIONAL_REPRESENTATION('',(#92895),#92899); +#92895 = LINE('',#92896,#92897); +#92896 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#92897 = VECTOR('',#92898,1.); +#92898 = DIRECTION('',(4.440892098501E-016,1.)); +#92899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92900 = ORIENTED_EDGE('',*,*,#92901,.T.); +#92901 = EDGE_CURVE('',#92874,#92902,#92904,.T.); +#92902 = VERTEX_POINT('',#92903); +#92903 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.75)); +#92904 = SURFACE_CURVE('',#92905,(#92909,#92916),.PCURVE_S1.); +#92905 = LINE('',#92906,#92907); +#92906 = CARTESIAN_POINT('',(-3.708144902248E-015,8.35,0.65)); +#92907 = VECTOR('',#92908,1.); +#92908 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92909 = PCURVE('',#92735,#92910); +#92910 = DEFINITIONAL_REPRESENTATION('',(#92911),#92915); +#92911 = LINE('',#92912,#92913); +#92912 = CARTESIAN_POINT('',(0.75,8.35)); +#92913 = VECTOR('',#92914,1.); +#92914 = DIRECTION('',(-1.,0.E+000)); +#92915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92916 = PCURVE('',#92917,#92922); +#92917 = PLANE('',#92918); +#92918 = AXIS2_PLACEMENT_3D('',#92919,#92920,#92921); +#92919 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.65)); +#92920 = DIRECTION('',(0.E+000,1.,0.E+000)); +#92921 = DIRECTION('',(0.E+000,0.E+000,1.)); +#92922 = DEFINITIONAL_REPRESENTATION('',(#92923),#92927); +#92923 = LINE('',#92924,#92925); +#92924 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#92925 = VECTOR('',#92926,1.); +#92926 = DIRECTION('',(1.,0.E+000)); +#92927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92928 = ORIENTED_EDGE('',*,*,#92929,.T.); +#92929 = EDGE_CURVE('',#92902,#92844,#92930,.T.); +#92930 = SURFACE_CURVE('',#92931,(#92935,#92942),.PCURVE_S1.); +#92931 = LINE('',#92932,#92933); +#92932 = CARTESIAN_POINT('',(-3.619327060278E-015,8.15,0.75)); +#92933 = VECTOR('',#92934,1.); +#92934 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#92935 = PCURVE('',#92735,#92936); +#92936 = DEFINITIONAL_REPRESENTATION('',(#92937),#92941); +#92937 = LINE('',#92938,#92939); +#92938 = CARTESIAN_POINT('',(0.65,8.15)); +#92939 = VECTOR('',#92940,1.); +#92940 = DIRECTION('',(0.E+000,-1.)); +#92941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92942 = PCURVE('',#92943,#92948); +#92943 = PLANE('',#92944); +#92944 = AXIS2_PLACEMENT_3D('',#92945,#92946,#92947); +#92945 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.75)); +#92946 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#92947 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#92948 = DEFINITIONAL_REPRESENTATION('',(#92949),#92953); +#92949 = LINE('',#92950,#92951); +#92950 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#92951 = VECTOR('',#92952,1.); +#92952 = DIRECTION('',(4.440892098501E-016,-1.)); +#92953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92954 = FACE_BOUND('',#92955,.T.); +#92955 = EDGE_LOOP('',(#92956,#92986,#93014,#93042)); +#92956 = ORIENTED_EDGE('',*,*,#92957,.T.); +#92957 = EDGE_CURVE('',#92958,#92960,#92962,.T.); +#92958 = VERTEX_POINT('',#92959); +#92959 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.75)); +#92960 = VERTEX_POINT('',#92961); +#92961 = CARTESIAN_POINT('',(0.E+000,7.65,0.65)); +#92962 = SURFACE_CURVE('',#92963,(#92967,#92974),.PCURVE_S1.); +#92963 = LINE('',#92964,#92965); +#92964 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.65)); +#92965 = VECTOR('',#92966,1.); +#92966 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92967 = PCURVE('',#92735,#92968); +#92968 = DEFINITIONAL_REPRESENTATION('',(#92969),#92973); +#92969 = LINE('',#92970,#92971); +#92970 = CARTESIAN_POINT('',(0.75,7.65)); +#92971 = VECTOR('',#92972,1.); +#92972 = DIRECTION('',(1.,0.E+000)); +#92973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92974 = PCURVE('',#92975,#92980); +#92975 = PLANE('',#92976); +#92976 = AXIS2_PLACEMENT_3D('',#92977,#92978,#92979); +#92977 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); +#92978 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#92979 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#92980 = DEFINITIONAL_REPRESENTATION('',(#92981),#92985); +#92981 = LINE('',#92982,#92983); +#92982 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#92983 = VECTOR('',#92984,1.); +#92984 = DIRECTION('',(1.,0.E+000)); +#92985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#92986 = ORIENTED_EDGE('',*,*,#92987,.T.); +#92987 = EDGE_CURVE('',#92960,#92988,#92990,.T.); +#92988 = VERTEX_POINT('',#92989); +#92989 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.65)); +#92990 = SURFACE_CURVE('',#92991,(#92995,#93002),.PCURVE_S1.); +#92991 = LINE('',#92992,#92993); +#92992 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.65)); +#92993 = VECTOR('',#92994,1.); +#92994 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#92995 = PCURVE('',#92735,#92996); +#92996 = DEFINITIONAL_REPRESENTATION('',(#92997),#93001); +#92997 = LINE('',#92998,#92999); +#92998 = CARTESIAN_POINT('',(0.75,7.65)); +#92999 = VECTOR('',#93000,1.); +#93000 = DIRECTION('',(0.E+000,1.)); +#93001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93002 = PCURVE('',#93003,#93008); +#93003 = PLANE('',#93004); +#93004 = AXIS2_PLACEMENT_3D('',#93005,#93006,#93007); +#93005 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); +#93006 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93007 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93008 = DEFINITIONAL_REPRESENTATION('',(#93009),#93013); +#93009 = LINE('',#93010,#93011); +#93010 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93011 = VECTOR('',#93012,1.); +#93012 = DIRECTION('',(4.440892098501E-016,1.)); +#93013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93014 = ORIENTED_EDGE('',*,*,#93015,.T.); +#93015 = EDGE_CURVE('',#92988,#93016,#93018,.T.); +#93016 = VERTEX_POINT('',#93017); +#93017 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.75)); +#93018 = SURFACE_CURVE('',#93019,(#93023,#93030),.PCURVE_S1.); +#93019 = LINE('',#93020,#93021); +#93020 = CARTESIAN_POINT('',(-3.486100297323E-015,7.85,0.65)); +#93021 = VECTOR('',#93022,1.); +#93022 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93023 = PCURVE('',#92735,#93024); +#93024 = DEFINITIONAL_REPRESENTATION('',(#93025),#93029); +#93025 = LINE('',#93026,#93027); +#93026 = CARTESIAN_POINT('',(0.75,7.85)); +#93027 = VECTOR('',#93028,1.); +#93028 = DIRECTION('',(-1.,0.E+000)); +#93029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93030 = PCURVE('',#93031,#93036); +#93031 = PLANE('',#93032); +#93032 = AXIS2_PLACEMENT_3D('',#93033,#93034,#93035); +#93033 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.65)); +#93034 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93035 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93036 = DEFINITIONAL_REPRESENTATION('',(#93037),#93041); +#93037 = LINE('',#93038,#93039); +#93038 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93039 = VECTOR('',#93040,1.); +#93040 = DIRECTION('',(1.,0.E+000)); +#93041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93042 = ORIENTED_EDGE('',*,*,#93043,.T.); +#93043 = EDGE_CURVE('',#93016,#92958,#93044,.T.); +#93044 = SURFACE_CURVE('',#93045,(#93049,#93056),.PCURVE_S1.); +#93045 = LINE('',#93046,#93047); +#93046 = CARTESIAN_POINT('',(-3.397282455353E-015,7.65,0.75)); +#93047 = VECTOR('',#93048,1.); +#93048 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93049 = PCURVE('',#92735,#93050); +#93050 = DEFINITIONAL_REPRESENTATION('',(#93051),#93055); +#93051 = LINE('',#93052,#93053); +#93052 = CARTESIAN_POINT('',(0.65,7.65)); +#93053 = VECTOR('',#93054,1.); +#93054 = DIRECTION('',(0.E+000,-1.)); +#93055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93056 = PCURVE('',#93057,#93062); +#93057 = PLANE('',#93058); +#93058 = AXIS2_PLACEMENT_3D('',#93059,#93060,#93061); +#93059 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.75)); +#93060 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93061 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93062 = DEFINITIONAL_REPRESENTATION('',(#93063),#93067); +#93063 = LINE('',#93064,#93065); +#93064 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93065 = VECTOR('',#93066,1.); +#93066 = DIRECTION('',(4.440892098501E-016,-1.)); +#93067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93068 = FACE_BOUND('',#93069,.T.); +#93069 = EDGE_LOOP('',(#93070,#93100,#93128,#93156)); +#93070 = ORIENTED_EDGE('',*,*,#93071,.T.); +#93071 = EDGE_CURVE('',#93072,#93074,#93076,.T.); +#93072 = VERTEX_POINT('',#93073); +#93073 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.75)); +#93074 = VERTEX_POINT('',#93075); +#93075 = CARTESIAN_POINT('',(0.E+000,7.15,0.65)); +#93076 = SURFACE_CURVE('',#93077,(#93081,#93088),.PCURVE_S1.); +#93077 = LINE('',#93078,#93079); +#93078 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.65)); +#93079 = VECTOR('',#93080,1.); +#93080 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93081 = PCURVE('',#92735,#93082); +#93082 = DEFINITIONAL_REPRESENTATION('',(#93083),#93087); +#93083 = LINE('',#93084,#93085); +#93084 = CARTESIAN_POINT('',(0.75,7.15)); +#93085 = VECTOR('',#93086,1.); +#93086 = DIRECTION('',(1.,0.E+000)); +#93087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93088 = PCURVE('',#93089,#93094); +#93089 = PLANE('',#93090); +#93090 = AXIS2_PLACEMENT_3D('',#93091,#93092,#93093); +#93091 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); +#93092 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93093 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93094 = DEFINITIONAL_REPRESENTATION('',(#93095),#93099); +#93095 = LINE('',#93096,#93097); +#93096 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93097 = VECTOR('',#93098,1.); +#93098 = DIRECTION('',(1.,0.E+000)); +#93099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93100 = ORIENTED_EDGE('',*,*,#93101,.T.); +#93101 = EDGE_CURVE('',#93074,#93102,#93104,.T.); +#93102 = VERTEX_POINT('',#93103); +#93103 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.65)); +#93104 = SURFACE_CURVE('',#93105,(#93109,#93116),.PCURVE_S1.); +#93105 = LINE('',#93106,#93107); +#93106 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.65)); +#93107 = VECTOR('',#93108,1.); +#93108 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93109 = PCURVE('',#92735,#93110); +#93110 = DEFINITIONAL_REPRESENTATION('',(#93111),#93115); +#93111 = LINE('',#93112,#93113); +#93112 = CARTESIAN_POINT('',(0.75,7.15)); +#93113 = VECTOR('',#93114,1.); +#93114 = DIRECTION('',(0.E+000,1.)); +#93115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93116 = PCURVE('',#93117,#93122); +#93117 = PLANE('',#93118); +#93118 = AXIS2_PLACEMENT_3D('',#93119,#93120,#93121); +#93119 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); +#93120 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93121 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93122 = DEFINITIONAL_REPRESENTATION('',(#93123),#93127); +#93123 = LINE('',#93124,#93125); +#93124 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93125 = VECTOR('',#93126,1.); +#93126 = DIRECTION('',(4.440892098501E-016,1.)); +#93127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93128 = ORIENTED_EDGE('',*,*,#93129,.T.); +#93129 = EDGE_CURVE('',#93102,#93130,#93132,.T.); +#93130 = VERTEX_POINT('',#93131); +#93131 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.75)); +#93132 = SURFACE_CURVE('',#93133,(#93137,#93144),.PCURVE_S1.); +#93133 = LINE('',#93134,#93135); +#93134 = CARTESIAN_POINT('',(-3.264055692398E-015,7.35,0.65)); +#93135 = VECTOR('',#93136,1.); +#93136 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93137 = PCURVE('',#92735,#93138); +#93138 = DEFINITIONAL_REPRESENTATION('',(#93139),#93143); +#93139 = LINE('',#93140,#93141); +#93140 = CARTESIAN_POINT('',(0.75,7.35)); +#93141 = VECTOR('',#93142,1.); +#93142 = DIRECTION('',(-1.,0.E+000)); +#93143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93144 = PCURVE('',#93145,#93150); +#93145 = PLANE('',#93146); +#93146 = AXIS2_PLACEMENT_3D('',#93147,#93148,#93149); +#93147 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.65)); +#93148 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93149 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93150 = DEFINITIONAL_REPRESENTATION('',(#93151),#93155); +#93151 = LINE('',#93152,#93153); +#93152 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93153 = VECTOR('',#93154,1.); +#93154 = DIRECTION('',(1.,0.E+000)); +#93155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93156 = ORIENTED_EDGE('',*,*,#93157,.T.); +#93157 = EDGE_CURVE('',#93130,#93072,#93158,.T.); +#93158 = SURFACE_CURVE('',#93159,(#93163,#93170),.PCURVE_S1.); +#93159 = LINE('',#93160,#93161); +#93160 = CARTESIAN_POINT('',(-3.175237850428E-015,7.15,0.75)); +#93161 = VECTOR('',#93162,1.); +#93162 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93163 = PCURVE('',#92735,#93164); +#93164 = DEFINITIONAL_REPRESENTATION('',(#93165),#93169); +#93165 = LINE('',#93166,#93167); +#93166 = CARTESIAN_POINT('',(0.65,7.15)); +#93167 = VECTOR('',#93168,1.); +#93168 = DIRECTION('',(0.E+000,-1.)); +#93169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93170 = PCURVE('',#93171,#93176); +#93171 = PLANE('',#93172); +#93172 = AXIS2_PLACEMENT_3D('',#93173,#93174,#93175); +#93173 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.75)); +#93174 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93175 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93176 = DEFINITIONAL_REPRESENTATION('',(#93177),#93181); +#93177 = LINE('',#93178,#93179); +#93178 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93179 = VECTOR('',#93180,1.); +#93180 = DIRECTION('',(4.440892098501E-016,-1.)); +#93181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93182 = FACE_BOUND('',#93183,.T.); +#93183 = EDGE_LOOP('',(#93184,#93214,#93242,#93270)); +#93184 = ORIENTED_EDGE('',*,*,#93185,.T.); +#93185 = EDGE_CURVE('',#93186,#93188,#93190,.T.); +#93186 = VERTEX_POINT('',#93187); +#93187 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.75)); +#93188 = VERTEX_POINT('',#93189); +#93189 = CARTESIAN_POINT('',(0.E+000,6.65,0.65)); +#93190 = SURFACE_CURVE('',#93191,(#93195,#93202),.PCURVE_S1.); +#93191 = LINE('',#93192,#93193); +#93192 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.65)); +#93193 = VECTOR('',#93194,1.); +#93194 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93195 = PCURVE('',#92735,#93196); +#93196 = DEFINITIONAL_REPRESENTATION('',(#93197),#93201); +#93197 = LINE('',#93198,#93199); +#93198 = CARTESIAN_POINT('',(0.75,6.65)); +#93199 = VECTOR('',#93200,1.); +#93200 = DIRECTION('',(1.,0.E+000)); +#93201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93202 = PCURVE('',#93203,#93208); +#93203 = PLANE('',#93204); +#93204 = AXIS2_PLACEMENT_3D('',#93205,#93206,#93207); +#93205 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); +#93206 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93207 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93208 = DEFINITIONAL_REPRESENTATION('',(#93209),#93213); +#93209 = LINE('',#93210,#93211); +#93210 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93211 = VECTOR('',#93212,1.); +#93212 = DIRECTION('',(1.,0.E+000)); +#93213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93214 = ORIENTED_EDGE('',*,*,#93215,.T.); +#93215 = EDGE_CURVE('',#93188,#93216,#93218,.T.); +#93216 = VERTEX_POINT('',#93217); +#93217 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.65)); +#93218 = SURFACE_CURVE('',#93219,(#93223,#93230),.PCURVE_S1.); +#93219 = LINE('',#93220,#93221); +#93220 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.65)); +#93221 = VECTOR('',#93222,1.); +#93222 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93223 = PCURVE('',#92735,#93224); +#93224 = DEFINITIONAL_REPRESENTATION('',(#93225),#93229); +#93225 = LINE('',#93226,#93227); +#93226 = CARTESIAN_POINT('',(0.75,6.65)); +#93227 = VECTOR('',#93228,1.); +#93228 = DIRECTION('',(0.E+000,1.)); +#93229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93230 = PCURVE('',#93231,#93236); +#93231 = PLANE('',#93232); +#93232 = AXIS2_PLACEMENT_3D('',#93233,#93234,#93235); +#93233 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); +#93234 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93235 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93236 = DEFINITIONAL_REPRESENTATION('',(#93237),#93241); +#93237 = LINE('',#93238,#93239); +#93238 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93239 = VECTOR('',#93240,1.); +#93240 = DIRECTION('',(4.440892098501E-016,1.)); +#93241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93242 = ORIENTED_EDGE('',*,*,#93243,.T.); +#93243 = EDGE_CURVE('',#93216,#93244,#93246,.T.); +#93244 = VERTEX_POINT('',#93245); +#93245 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.75)); +#93246 = SURFACE_CURVE('',#93247,(#93251,#93258),.PCURVE_S1.); +#93247 = LINE('',#93248,#93249); +#93248 = CARTESIAN_POINT('',(-3.042011087473E-015,6.85,0.65)); +#93249 = VECTOR('',#93250,1.); +#93250 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93251 = PCURVE('',#92735,#93252); +#93252 = DEFINITIONAL_REPRESENTATION('',(#93253),#93257); +#93253 = LINE('',#93254,#93255); +#93254 = CARTESIAN_POINT('',(0.75,6.85)); +#93255 = VECTOR('',#93256,1.); +#93256 = DIRECTION('',(-1.,0.E+000)); +#93257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93258 = PCURVE('',#93259,#93264); +#93259 = PLANE('',#93260); +#93260 = AXIS2_PLACEMENT_3D('',#93261,#93262,#93263); +#93261 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.65)); +#93262 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93263 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93264 = DEFINITIONAL_REPRESENTATION('',(#93265),#93269); +#93265 = LINE('',#93266,#93267); +#93266 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93267 = VECTOR('',#93268,1.); +#93268 = DIRECTION('',(1.,0.E+000)); +#93269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93270 = ORIENTED_EDGE('',*,*,#93271,.T.); +#93271 = EDGE_CURVE('',#93244,#93186,#93272,.T.); +#93272 = SURFACE_CURVE('',#93273,(#93277,#93284),.PCURVE_S1.); +#93273 = LINE('',#93274,#93275); +#93274 = CARTESIAN_POINT('',(-2.953193245503E-015,6.65,0.75)); +#93275 = VECTOR('',#93276,1.); +#93276 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93277 = PCURVE('',#92735,#93278); +#93278 = DEFINITIONAL_REPRESENTATION('',(#93279),#93283); +#93279 = LINE('',#93280,#93281); +#93280 = CARTESIAN_POINT('',(0.65,6.65)); +#93281 = VECTOR('',#93282,1.); +#93282 = DIRECTION('',(0.E+000,-1.)); +#93283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93284 = PCURVE('',#93285,#93290); +#93285 = PLANE('',#93286); +#93286 = AXIS2_PLACEMENT_3D('',#93287,#93288,#93289); +#93287 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.75)); +#93288 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93289 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93290 = DEFINITIONAL_REPRESENTATION('',(#93291),#93295); +#93291 = LINE('',#93292,#93293); +#93292 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93293 = VECTOR('',#93294,1.); +#93294 = DIRECTION('',(4.440892098501E-016,-1.)); +#93295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93296 = FACE_BOUND('',#93297,.T.); +#93297 = EDGE_LOOP('',(#93298,#93328,#93356,#93384)); +#93298 = ORIENTED_EDGE('',*,*,#93299,.T.); +#93299 = EDGE_CURVE('',#93300,#93302,#93304,.T.); +#93300 = VERTEX_POINT('',#93301); +#93301 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.75)); +#93302 = VERTEX_POINT('',#93303); +#93303 = CARTESIAN_POINT('',(0.E+000,6.15,0.65)); +#93304 = SURFACE_CURVE('',#93305,(#93309,#93316),.PCURVE_S1.); +#93305 = LINE('',#93306,#93307); +#93306 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.65)); +#93307 = VECTOR('',#93308,1.); +#93308 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93309 = PCURVE('',#92735,#93310); +#93310 = DEFINITIONAL_REPRESENTATION('',(#93311),#93315); +#93311 = LINE('',#93312,#93313); +#93312 = CARTESIAN_POINT('',(0.75,6.15)); +#93313 = VECTOR('',#93314,1.); +#93314 = DIRECTION('',(1.,0.E+000)); +#93315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93316 = PCURVE('',#93317,#93322); +#93317 = PLANE('',#93318); +#93318 = AXIS2_PLACEMENT_3D('',#93319,#93320,#93321); +#93319 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); +#93320 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93321 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93322 = DEFINITIONAL_REPRESENTATION('',(#93323),#93327); +#93323 = LINE('',#93324,#93325); +#93324 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93325 = VECTOR('',#93326,1.); +#93326 = DIRECTION('',(1.,0.E+000)); +#93327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93328 = ORIENTED_EDGE('',*,*,#93329,.T.); +#93329 = EDGE_CURVE('',#93302,#93330,#93332,.T.); +#93330 = VERTEX_POINT('',#93331); +#93331 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.65)); +#93332 = SURFACE_CURVE('',#93333,(#93337,#93344),.PCURVE_S1.); +#93333 = LINE('',#93334,#93335); +#93334 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.65)); +#93335 = VECTOR('',#93336,1.); +#93336 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93337 = PCURVE('',#92735,#93338); +#93338 = DEFINITIONAL_REPRESENTATION('',(#93339),#93343); +#93339 = LINE('',#93340,#93341); +#93340 = CARTESIAN_POINT('',(0.75,6.15)); +#93341 = VECTOR('',#93342,1.); +#93342 = DIRECTION('',(0.E+000,1.)); +#93343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93344 = PCURVE('',#93345,#93350); +#93345 = PLANE('',#93346); +#93346 = AXIS2_PLACEMENT_3D('',#93347,#93348,#93349); +#93347 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); +#93348 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93349 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93350 = DEFINITIONAL_REPRESENTATION('',(#93351),#93355); +#93351 = LINE('',#93352,#93353); +#93352 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93353 = VECTOR('',#93354,1.); +#93354 = DIRECTION('',(4.440892098501E-016,1.)); +#93355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93356 = ORIENTED_EDGE('',*,*,#93357,.T.); +#93357 = EDGE_CURVE('',#93330,#93358,#93360,.T.); +#93358 = VERTEX_POINT('',#93359); +#93359 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.75)); +#93360 = SURFACE_CURVE('',#93361,(#93365,#93372),.PCURVE_S1.); +#93361 = LINE('',#93362,#93363); +#93362 = CARTESIAN_POINT('',(-2.819966482548E-015,6.35,0.65)); +#93363 = VECTOR('',#93364,1.); +#93364 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93365 = PCURVE('',#92735,#93366); +#93366 = DEFINITIONAL_REPRESENTATION('',(#93367),#93371); +#93367 = LINE('',#93368,#93369); +#93368 = CARTESIAN_POINT('',(0.75,6.35)); +#93369 = VECTOR('',#93370,1.); +#93370 = DIRECTION('',(-1.,0.E+000)); +#93371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93372 = PCURVE('',#93373,#93378); +#93373 = PLANE('',#93374); +#93374 = AXIS2_PLACEMENT_3D('',#93375,#93376,#93377); +#93375 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.65)); +#93376 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93377 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93378 = DEFINITIONAL_REPRESENTATION('',(#93379),#93383); +#93379 = LINE('',#93380,#93381); +#93380 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93381 = VECTOR('',#93382,1.); +#93382 = DIRECTION('',(1.,0.E+000)); +#93383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93384 = ORIENTED_EDGE('',*,*,#93385,.T.); +#93385 = EDGE_CURVE('',#93358,#93300,#93386,.T.); +#93386 = SURFACE_CURVE('',#93387,(#93391,#93398),.PCURVE_S1.); +#93387 = LINE('',#93388,#93389); +#93388 = CARTESIAN_POINT('',(-2.731148640578E-015,6.15,0.75)); +#93389 = VECTOR('',#93390,1.); +#93390 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93391 = PCURVE('',#92735,#93392); +#93392 = DEFINITIONAL_REPRESENTATION('',(#93393),#93397); +#93393 = LINE('',#93394,#93395); +#93394 = CARTESIAN_POINT('',(0.65,6.15)); +#93395 = VECTOR('',#93396,1.); +#93396 = DIRECTION('',(0.E+000,-1.)); +#93397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93398 = PCURVE('',#93399,#93404); +#93399 = PLANE('',#93400); +#93400 = AXIS2_PLACEMENT_3D('',#93401,#93402,#93403); +#93401 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.75)); +#93402 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93403 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93404 = DEFINITIONAL_REPRESENTATION('',(#93405),#93409); +#93405 = LINE('',#93406,#93407); +#93406 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93407 = VECTOR('',#93408,1.); +#93408 = DIRECTION('',(4.440892098501E-016,-1.)); +#93409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93410 = FACE_BOUND('',#93411,.T.); +#93411 = EDGE_LOOP('',(#93412,#93442,#93470,#93498)); +#93412 = ORIENTED_EDGE('',*,*,#93413,.T.); +#93413 = EDGE_CURVE('',#93414,#93416,#93418,.T.); +#93414 = VERTEX_POINT('',#93415); +#93415 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.75)); +#93416 = VERTEX_POINT('',#93417); +#93417 = CARTESIAN_POINT('',(0.E+000,5.65,0.65)); +#93418 = SURFACE_CURVE('',#93419,(#93423,#93430),.PCURVE_S1.); +#93419 = LINE('',#93420,#93421); +#93420 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.65)); +#93421 = VECTOR('',#93422,1.); +#93422 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93423 = PCURVE('',#92735,#93424); +#93424 = DEFINITIONAL_REPRESENTATION('',(#93425),#93429); +#93425 = LINE('',#93426,#93427); +#93426 = CARTESIAN_POINT('',(0.75,5.65)); +#93427 = VECTOR('',#93428,1.); +#93428 = DIRECTION('',(1.,0.E+000)); +#93429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93430 = PCURVE('',#93431,#93436); +#93431 = PLANE('',#93432); +#93432 = AXIS2_PLACEMENT_3D('',#93433,#93434,#93435); +#93433 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); +#93434 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93435 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93436 = DEFINITIONAL_REPRESENTATION('',(#93437),#93441); +#93437 = LINE('',#93438,#93439); +#93438 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93439 = VECTOR('',#93440,1.); +#93440 = DIRECTION('',(1.,0.E+000)); +#93441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93442 = ORIENTED_EDGE('',*,*,#93443,.T.); +#93443 = EDGE_CURVE('',#93416,#93444,#93446,.T.); +#93444 = VERTEX_POINT('',#93445); +#93445 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.65)); +#93446 = SURFACE_CURVE('',#93447,(#93451,#93458),.PCURVE_S1.); +#93447 = LINE('',#93448,#93449); +#93448 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.65)); +#93449 = VECTOR('',#93450,1.); +#93450 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93451 = PCURVE('',#92735,#93452); +#93452 = DEFINITIONAL_REPRESENTATION('',(#93453),#93457); +#93453 = LINE('',#93454,#93455); +#93454 = CARTESIAN_POINT('',(0.75,5.65)); +#93455 = VECTOR('',#93456,1.); +#93456 = DIRECTION('',(0.E+000,1.)); +#93457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93458 = PCURVE('',#93459,#93464); +#93459 = PLANE('',#93460); +#93460 = AXIS2_PLACEMENT_3D('',#93461,#93462,#93463); +#93461 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); +#93462 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93463 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93464 = DEFINITIONAL_REPRESENTATION('',(#93465),#93469); +#93465 = LINE('',#93466,#93467); +#93466 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93467 = VECTOR('',#93468,1.); +#93468 = DIRECTION('',(4.440892098501E-016,1.)); +#93469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93470 = ORIENTED_EDGE('',*,*,#93471,.T.); +#93471 = EDGE_CURVE('',#93444,#93472,#93474,.T.); +#93472 = VERTEX_POINT('',#93473); +#93473 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.75)); +#93474 = SURFACE_CURVE('',#93475,(#93479,#93486),.PCURVE_S1.); +#93475 = LINE('',#93476,#93477); +#93476 = CARTESIAN_POINT('',(-2.597921877623E-015,5.85,0.65)); +#93477 = VECTOR('',#93478,1.); +#93478 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93479 = PCURVE('',#92735,#93480); +#93480 = DEFINITIONAL_REPRESENTATION('',(#93481),#93485); +#93481 = LINE('',#93482,#93483); +#93482 = CARTESIAN_POINT('',(0.75,5.85)); +#93483 = VECTOR('',#93484,1.); +#93484 = DIRECTION('',(-1.,0.E+000)); +#93485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93486 = PCURVE('',#93487,#93492); +#93487 = PLANE('',#93488); +#93488 = AXIS2_PLACEMENT_3D('',#93489,#93490,#93491); +#93489 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.65)); +#93490 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93491 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93492 = DEFINITIONAL_REPRESENTATION('',(#93493),#93497); +#93493 = LINE('',#93494,#93495); +#93494 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93495 = VECTOR('',#93496,1.); +#93496 = DIRECTION('',(1.,0.E+000)); +#93497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93498 = ORIENTED_EDGE('',*,*,#93499,.T.); +#93499 = EDGE_CURVE('',#93472,#93414,#93500,.T.); +#93500 = SURFACE_CURVE('',#93501,(#93505,#93512),.PCURVE_S1.); +#93501 = LINE('',#93502,#93503); +#93502 = CARTESIAN_POINT('',(-2.509104035653E-015,5.65,0.75)); +#93503 = VECTOR('',#93504,1.); +#93504 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93505 = PCURVE('',#92735,#93506); +#93506 = DEFINITIONAL_REPRESENTATION('',(#93507),#93511); +#93507 = LINE('',#93508,#93509); +#93508 = CARTESIAN_POINT('',(0.65,5.65)); +#93509 = VECTOR('',#93510,1.); +#93510 = DIRECTION('',(0.E+000,-1.)); +#93511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93512 = PCURVE('',#93513,#93518); +#93513 = PLANE('',#93514); +#93514 = AXIS2_PLACEMENT_3D('',#93515,#93516,#93517); +#93515 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.75)); +#93516 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93517 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93518 = DEFINITIONAL_REPRESENTATION('',(#93519),#93523); +#93519 = LINE('',#93520,#93521); +#93520 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93521 = VECTOR('',#93522,1.); +#93522 = DIRECTION('',(4.440892098501E-016,-1.)); +#93523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93524 = FACE_BOUND('',#93525,.T.); +#93525 = EDGE_LOOP('',(#93526,#93556,#93584,#93612)); +#93526 = ORIENTED_EDGE('',*,*,#93527,.T.); +#93527 = EDGE_CURVE('',#93528,#93530,#93532,.T.); +#93528 = VERTEX_POINT('',#93529); +#93529 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.75)); +#93530 = VERTEX_POINT('',#93531); +#93531 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.65)); +#93532 = SURFACE_CURVE('',#93533,(#93537,#93544),.PCURVE_S1.); +#93533 = LINE('',#93534,#93535); +#93534 = CARTESIAN_POINT('',(-2.065014825803E-015,4.65,0.65)); +#93535 = VECTOR('',#93536,1.); +#93536 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93537 = PCURVE('',#92735,#93538); +#93538 = DEFINITIONAL_REPRESENTATION('',(#93539),#93543); +#93539 = LINE('',#93540,#93541); +#93540 = CARTESIAN_POINT('',(0.75,4.65)); +#93541 = VECTOR('',#93542,1.); +#93542 = DIRECTION('',(1.,0.E+000)); +#93543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93544 = PCURVE('',#93545,#93550); +#93545 = PLANE('',#93546); +#93546 = AXIS2_PLACEMENT_3D('',#93547,#93548,#93549); +#93547 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.65)); +#93548 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93549 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93550 = DEFINITIONAL_REPRESENTATION('',(#93551),#93555); +#93551 = LINE('',#93552,#93553); +#93552 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93553 = VECTOR('',#93554,1.); +#93554 = DIRECTION('',(1.,0.E+000)); +#93555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93556 = ORIENTED_EDGE('',*,*,#93557,.T.); +#93557 = EDGE_CURVE('',#93530,#93558,#93560,.T.); +#93558 = VERTEX_POINT('',#93559); +#93559 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); +#93560 = SURFACE_CURVE('',#93561,(#93565,#93572),.PCURVE_S1.); +#93561 = LINE('',#93562,#93563); +#93562 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); +#93563 = VECTOR('',#93564,1.); +#93564 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93565 = PCURVE('',#92735,#93566); +#93566 = DEFINITIONAL_REPRESENTATION('',(#93567),#93571); +#93567 = LINE('',#93568,#93569); +#93568 = CARTESIAN_POINT('',(0.75,4.85)); +#93569 = VECTOR('',#93570,1.); +#93570 = DIRECTION('',(0.E+000,1.)); +#93571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93572 = PCURVE('',#93573,#93578); +#93573 = PLANE('',#93574); +#93574 = AXIS2_PLACEMENT_3D('',#93575,#93576,#93577); +#93575 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); +#93576 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93577 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93578 = DEFINITIONAL_REPRESENTATION('',(#93579),#93583); +#93579 = LINE('',#93580,#93581); +#93580 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93581 = VECTOR('',#93582,1.); +#93582 = DIRECTION('',(4.440892098501E-016,1.)); +#93583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93584 = ORIENTED_EDGE('',*,*,#93585,.T.); +#93585 = EDGE_CURVE('',#93558,#93586,#93588,.T.); +#93586 = VERTEX_POINT('',#93587); +#93587 = CARTESIAN_POINT('',(0.E+000,4.85,0.75)); +#93588 = SURFACE_CURVE('',#93589,(#93593,#93600),.PCURVE_S1.); +#93589 = LINE('',#93590,#93591); +#93590 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.65)); +#93591 = VECTOR('',#93592,1.); +#93592 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93593 = PCURVE('',#92735,#93594); +#93594 = DEFINITIONAL_REPRESENTATION('',(#93595),#93599); +#93595 = LINE('',#93596,#93597); +#93596 = CARTESIAN_POINT('',(0.75,4.85)); +#93597 = VECTOR('',#93598,1.); +#93598 = DIRECTION('',(-1.,0.E+000)); +#93599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93600 = PCURVE('',#93601,#93606); +#93601 = PLANE('',#93602); +#93602 = AXIS2_PLACEMENT_3D('',#93603,#93604,#93605); +#93603 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); +#93604 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93605 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93606 = DEFINITIONAL_REPRESENTATION('',(#93607),#93611); +#93607 = LINE('',#93608,#93609); +#93608 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93609 = VECTOR('',#93610,1.); +#93610 = DIRECTION('',(1.,0.E+000)); +#93611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93612 = ORIENTED_EDGE('',*,*,#93613,.T.); +#93613 = EDGE_CURVE('',#93586,#93528,#93614,.T.); +#93614 = SURFACE_CURVE('',#93615,(#93619,#93626),.PCURVE_S1.); +#93615 = LINE('',#93616,#93617); +#93616 = CARTESIAN_POINT('',(-2.153832667773E-015,4.85,0.75)); +#93617 = VECTOR('',#93618,1.); +#93618 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93619 = PCURVE('',#92735,#93620); +#93620 = DEFINITIONAL_REPRESENTATION('',(#93621),#93625); +#93621 = LINE('',#93622,#93623); +#93622 = CARTESIAN_POINT('',(0.65,4.85)); +#93623 = VECTOR('',#93624,1.); +#93624 = DIRECTION('',(0.E+000,-1.)); +#93625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93626 = PCURVE('',#93627,#93632); +#93627 = PLANE('',#93628); +#93628 = AXIS2_PLACEMENT_3D('',#93629,#93630,#93631); +#93629 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.75)); +#93630 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93631 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93632 = DEFINITIONAL_REPRESENTATION('',(#93633),#93637); +#93633 = LINE('',#93634,#93635); +#93634 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93635 = VECTOR('',#93636,1.); +#93636 = DIRECTION('',(4.440892098501E-016,-1.)); +#93637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93638 = FACE_BOUND('',#93639,.T.); +#93639 = EDGE_LOOP('',(#93640,#93670,#93698,#93726)); +#93640 = ORIENTED_EDGE('',*,*,#93641,.T.); +#93641 = EDGE_CURVE('',#93642,#93644,#93646,.T.); +#93642 = VERTEX_POINT('',#93643); +#93643 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.75)); +#93644 = VERTEX_POINT('',#93645); +#93645 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.65)); +#93646 = SURFACE_CURVE('',#93647,(#93651,#93658),.PCURVE_S1.); +#93647 = LINE('',#93648,#93649); +#93648 = CARTESIAN_POINT('',(-1.842970220878E-015,4.15,0.65)); +#93649 = VECTOR('',#93650,1.); +#93650 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93651 = PCURVE('',#92735,#93652); +#93652 = DEFINITIONAL_REPRESENTATION('',(#93653),#93657); +#93653 = LINE('',#93654,#93655); +#93654 = CARTESIAN_POINT('',(0.75,4.15)); +#93655 = VECTOR('',#93656,1.); +#93656 = DIRECTION('',(1.,0.E+000)); +#93657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93658 = PCURVE('',#93659,#93664); +#93659 = PLANE('',#93660); +#93660 = AXIS2_PLACEMENT_3D('',#93661,#93662,#93663); +#93661 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.65)); +#93662 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93663 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93664 = DEFINITIONAL_REPRESENTATION('',(#93665),#93669); +#93665 = LINE('',#93666,#93667); +#93666 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93667 = VECTOR('',#93668,1.); +#93668 = DIRECTION('',(1.,0.E+000)); +#93669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93670 = ORIENTED_EDGE('',*,*,#93671,.T.); +#93671 = EDGE_CURVE('',#93644,#93672,#93674,.T.); +#93672 = VERTEX_POINT('',#93673); +#93673 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); +#93674 = SURFACE_CURVE('',#93675,(#93679,#93686),.PCURVE_S1.); +#93675 = LINE('',#93676,#93677); +#93676 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); +#93677 = VECTOR('',#93678,1.); +#93678 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93679 = PCURVE('',#92735,#93680); +#93680 = DEFINITIONAL_REPRESENTATION('',(#93681),#93685); +#93681 = LINE('',#93682,#93683); +#93682 = CARTESIAN_POINT('',(0.75,4.35)); +#93683 = VECTOR('',#93684,1.); +#93684 = DIRECTION('',(0.E+000,1.)); +#93685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93686 = PCURVE('',#93687,#93692); +#93687 = PLANE('',#93688); +#93688 = AXIS2_PLACEMENT_3D('',#93689,#93690,#93691); +#93689 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); +#93690 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93691 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93692 = DEFINITIONAL_REPRESENTATION('',(#93693),#93697); +#93693 = LINE('',#93694,#93695); +#93694 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93695 = VECTOR('',#93696,1.); +#93696 = DIRECTION('',(4.440892098501E-016,1.)); +#93697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93698 = ORIENTED_EDGE('',*,*,#93699,.T.); +#93699 = EDGE_CURVE('',#93672,#93700,#93702,.T.); +#93700 = VERTEX_POINT('',#93701); +#93701 = CARTESIAN_POINT('',(0.E+000,4.35,0.75)); +#93702 = SURFACE_CURVE('',#93703,(#93707,#93714),.PCURVE_S1.); +#93703 = LINE('',#93704,#93705); +#93704 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.65)); +#93705 = VECTOR('',#93706,1.); +#93706 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93707 = PCURVE('',#92735,#93708); +#93708 = DEFINITIONAL_REPRESENTATION('',(#93709),#93713); +#93709 = LINE('',#93710,#93711); +#93710 = CARTESIAN_POINT('',(0.75,4.35)); +#93711 = VECTOR('',#93712,1.); +#93712 = DIRECTION('',(-1.,0.E+000)); +#93713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93714 = PCURVE('',#93715,#93720); +#93715 = PLANE('',#93716); +#93716 = AXIS2_PLACEMENT_3D('',#93717,#93718,#93719); +#93717 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); +#93718 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93719 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93720 = DEFINITIONAL_REPRESENTATION('',(#93721),#93725); +#93721 = LINE('',#93722,#93723); +#93722 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93723 = VECTOR('',#93724,1.); +#93724 = DIRECTION('',(1.,0.E+000)); +#93725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93726 = ORIENTED_EDGE('',*,*,#93727,.T.); +#93727 = EDGE_CURVE('',#93700,#93642,#93728,.T.); +#93728 = SURFACE_CURVE('',#93729,(#93733,#93740),.PCURVE_S1.); +#93729 = LINE('',#93730,#93731); +#93730 = CARTESIAN_POINT('',(-1.931788062848E-015,4.35,0.75)); +#93731 = VECTOR('',#93732,1.); +#93732 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93733 = PCURVE('',#92735,#93734); +#93734 = DEFINITIONAL_REPRESENTATION('',(#93735),#93739); +#93735 = LINE('',#93736,#93737); +#93736 = CARTESIAN_POINT('',(0.65,4.35)); +#93737 = VECTOR('',#93738,1.); +#93738 = DIRECTION('',(0.E+000,-1.)); +#93739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93740 = PCURVE('',#93741,#93746); +#93741 = PLANE('',#93742); +#93742 = AXIS2_PLACEMENT_3D('',#93743,#93744,#93745); +#93743 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.75)); +#93744 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93745 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93746 = DEFINITIONAL_REPRESENTATION('',(#93747),#93751); +#93747 = LINE('',#93748,#93749); +#93748 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93749 = VECTOR('',#93750,1.); +#93750 = DIRECTION('',(4.440892098501E-016,-1.)); +#93751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93752 = FACE_BOUND('',#93753,.T.); +#93753 = EDGE_LOOP('',(#93754,#93784,#93812,#93840)); +#93754 = ORIENTED_EDGE('',*,*,#93755,.T.); +#93755 = EDGE_CURVE('',#93756,#93758,#93760,.T.); +#93756 = VERTEX_POINT('',#93757); +#93757 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.75)); +#93758 = VERTEX_POINT('',#93759); +#93759 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.65)); +#93760 = SURFACE_CURVE('',#93761,(#93765,#93772),.PCURVE_S1.); +#93761 = LINE('',#93762,#93763); +#93762 = CARTESIAN_POINT('',(-1.620925615953E-015,3.65,0.65)); +#93763 = VECTOR('',#93764,1.); +#93764 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93765 = PCURVE('',#92735,#93766); +#93766 = DEFINITIONAL_REPRESENTATION('',(#93767),#93771); +#93767 = LINE('',#93768,#93769); +#93768 = CARTESIAN_POINT('',(0.75,3.65)); +#93769 = VECTOR('',#93770,1.); +#93770 = DIRECTION('',(1.,0.E+000)); +#93771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93772 = PCURVE('',#93773,#93778); +#93773 = PLANE('',#93774); +#93774 = AXIS2_PLACEMENT_3D('',#93775,#93776,#93777); +#93775 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.65)); +#93776 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93777 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93778 = DEFINITIONAL_REPRESENTATION('',(#93779),#93783); +#93779 = LINE('',#93780,#93781); +#93780 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93781 = VECTOR('',#93782,1.); +#93782 = DIRECTION('',(1.,0.E+000)); +#93783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93784 = ORIENTED_EDGE('',*,*,#93785,.T.); +#93785 = EDGE_CURVE('',#93758,#93786,#93788,.T.); +#93786 = VERTEX_POINT('',#93787); +#93787 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); +#93788 = SURFACE_CURVE('',#93789,(#93793,#93800),.PCURVE_S1.); +#93789 = LINE('',#93790,#93791); +#93790 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); +#93791 = VECTOR('',#93792,1.); +#93792 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93793 = PCURVE('',#92735,#93794); +#93794 = DEFINITIONAL_REPRESENTATION('',(#93795),#93799); +#93795 = LINE('',#93796,#93797); +#93796 = CARTESIAN_POINT('',(0.75,3.85)); +#93797 = VECTOR('',#93798,1.); +#93798 = DIRECTION('',(0.E+000,1.)); +#93799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93800 = PCURVE('',#93801,#93806); +#93801 = PLANE('',#93802); +#93802 = AXIS2_PLACEMENT_3D('',#93803,#93804,#93805); +#93803 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); +#93804 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93805 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93806 = DEFINITIONAL_REPRESENTATION('',(#93807),#93811); +#93807 = LINE('',#93808,#93809); +#93808 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93809 = VECTOR('',#93810,1.); +#93810 = DIRECTION('',(4.440892098501E-016,1.)); +#93811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93812 = ORIENTED_EDGE('',*,*,#93813,.T.); +#93813 = EDGE_CURVE('',#93786,#93814,#93816,.T.); +#93814 = VERTEX_POINT('',#93815); +#93815 = CARTESIAN_POINT('',(0.E+000,3.85,0.75)); +#93816 = SURFACE_CURVE('',#93817,(#93821,#93828),.PCURVE_S1.); +#93817 = LINE('',#93818,#93819); +#93818 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.65)); +#93819 = VECTOR('',#93820,1.); +#93820 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93821 = PCURVE('',#92735,#93822); +#93822 = DEFINITIONAL_REPRESENTATION('',(#93823),#93827); +#93823 = LINE('',#93824,#93825); +#93824 = CARTESIAN_POINT('',(0.75,3.85)); +#93825 = VECTOR('',#93826,1.); +#93826 = DIRECTION('',(-1.,0.E+000)); +#93827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93828 = PCURVE('',#93829,#93834); +#93829 = PLANE('',#93830); +#93830 = AXIS2_PLACEMENT_3D('',#93831,#93832,#93833); +#93831 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); +#93832 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93833 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93834 = DEFINITIONAL_REPRESENTATION('',(#93835),#93839); +#93835 = LINE('',#93836,#93837); +#93836 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93837 = VECTOR('',#93838,1.); +#93838 = DIRECTION('',(1.,0.E+000)); +#93839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93840 = ORIENTED_EDGE('',*,*,#93841,.T.); +#93841 = EDGE_CURVE('',#93814,#93756,#93842,.T.); +#93842 = SURFACE_CURVE('',#93843,(#93847,#93854),.PCURVE_S1.); +#93843 = LINE('',#93844,#93845); +#93844 = CARTESIAN_POINT('',(-1.709743457923E-015,3.85,0.75)); +#93845 = VECTOR('',#93846,1.); +#93846 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93847 = PCURVE('',#92735,#93848); +#93848 = DEFINITIONAL_REPRESENTATION('',(#93849),#93853); +#93849 = LINE('',#93850,#93851); +#93850 = CARTESIAN_POINT('',(0.65,3.85)); +#93851 = VECTOR('',#93852,1.); +#93852 = DIRECTION('',(0.E+000,-1.)); +#93853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93854 = PCURVE('',#93855,#93860); +#93855 = PLANE('',#93856); +#93856 = AXIS2_PLACEMENT_3D('',#93857,#93858,#93859); +#93857 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.75)); +#93858 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93859 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93860 = DEFINITIONAL_REPRESENTATION('',(#93861),#93865); +#93861 = LINE('',#93862,#93863); +#93862 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93863 = VECTOR('',#93864,1.); +#93864 = DIRECTION('',(4.440892098501E-016,-1.)); +#93865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93866 = FACE_BOUND('',#93867,.T.); +#93867 = EDGE_LOOP('',(#93868,#93898,#93926,#93954)); +#93868 = ORIENTED_EDGE('',*,*,#93869,.T.); +#93869 = EDGE_CURVE('',#93870,#93872,#93874,.T.); +#93870 = VERTEX_POINT('',#93871); +#93871 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.75)); +#93872 = VERTEX_POINT('',#93873); +#93873 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.65)); +#93874 = SURFACE_CURVE('',#93875,(#93879,#93886),.PCURVE_S1.); +#93875 = LINE('',#93876,#93877); +#93876 = CARTESIAN_POINT('',(-1.398881011028E-015,3.15,0.65)); +#93877 = VECTOR('',#93878,1.); +#93878 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93879 = PCURVE('',#92735,#93880); +#93880 = DEFINITIONAL_REPRESENTATION('',(#93881),#93885); +#93881 = LINE('',#93882,#93883); +#93882 = CARTESIAN_POINT('',(0.75,3.15)); +#93883 = VECTOR('',#93884,1.); +#93884 = DIRECTION('',(1.,0.E+000)); +#93885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93886 = PCURVE('',#93887,#93892); +#93887 = PLANE('',#93888); +#93888 = AXIS2_PLACEMENT_3D('',#93889,#93890,#93891); +#93889 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.65)); +#93890 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#93891 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93892 = DEFINITIONAL_REPRESENTATION('',(#93893),#93897); +#93893 = LINE('',#93894,#93895); +#93894 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#93895 = VECTOR('',#93896,1.); +#93896 = DIRECTION('',(1.,0.E+000)); +#93897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93898 = ORIENTED_EDGE('',*,*,#93899,.T.); +#93899 = EDGE_CURVE('',#93872,#93900,#93902,.T.); +#93900 = VERTEX_POINT('',#93901); +#93901 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); +#93902 = SURFACE_CURVE('',#93903,(#93907,#93914),.PCURVE_S1.); +#93903 = LINE('',#93904,#93905); +#93904 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); +#93905 = VECTOR('',#93906,1.); +#93906 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#93907 = PCURVE('',#92735,#93908); +#93908 = DEFINITIONAL_REPRESENTATION('',(#93909),#93913); +#93909 = LINE('',#93910,#93911); +#93910 = CARTESIAN_POINT('',(0.75,3.35)); +#93911 = VECTOR('',#93912,1.); +#93912 = DIRECTION('',(0.E+000,1.)); +#93913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93914 = PCURVE('',#93915,#93920); +#93915 = PLANE('',#93916); +#93916 = AXIS2_PLACEMENT_3D('',#93917,#93918,#93919); +#93917 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); +#93918 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#93919 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#93920 = DEFINITIONAL_REPRESENTATION('',(#93921),#93925); +#93921 = LINE('',#93922,#93923); +#93922 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#93923 = VECTOR('',#93924,1.); +#93924 = DIRECTION('',(4.440892098501E-016,1.)); +#93925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93926 = ORIENTED_EDGE('',*,*,#93927,.T.); +#93927 = EDGE_CURVE('',#93900,#93928,#93930,.T.); +#93928 = VERTEX_POINT('',#93929); +#93929 = CARTESIAN_POINT('',(0.E+000,3.35,0.75)); +#93930 = SURFACE_CURVE('',#93931,(#93935,#93942),.PCURVE_S1.); +#93931 = LINE('',#93932,#93933); +#93932 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.65)); +#93933 = VECTOR('',#93934,1.); +#93934 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93935 = PCURVE('',#92735,#93936); +#93936 = DEFINITIONAL_REPRESENTATION('',(#93937),#93941); +#93937 = LINE('',#93938,#93939); +#93938 = CARTESIAN_POINT('',(0.75,3.35)); +#93939 = VECTOR('',#93940,1.); +#93940 = DIRECTION('',(-1.,0.E+000)); +#93941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93942 = PCURVE('',#93943,#93948); +#93943 = PLANE('',#93944); +#93944 = AXIS2_PLACEMENT_3D('',#93945,#93946,#93947); +#93945 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); +#93946 = DIRECTION('',(0.E+000,1.,0.E+000)); +#93947 = DIRECTION('',(0.E+000,0.E+000,1.)); +#93948 = DEFINITIONAL_REPRESENTATION('',(#93949),#93953); +#93949 = LINE('',#93950,#93951); +#93950 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#93951 = VECTOR('',#93952,1.); +#93952 = DIRECTION('',(1.,0.E+000)); +#93953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93954 = ORIENTED_EDGE('',*,*,#93955,.T.); +#93955 = EDGE_CURVE('',#93928,#93870,#93956,.T.); +#93956 = SURFACE_CURVE('',#93957,(#93961,#93968),.PCURVE_S1.); +#93957 = LINE('',#93958,#93959); +#93958 = CARTESIAN_POINT('',(-1.487698852998E-015,3.35,0.75)); +#93959 = VECTOR('',#93960,1.); +#93960 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#93961 = PCURVE('',#92735,#93962); +#93962 = DEFINITIONAL_REPRESENTATION('',(#93963),#93967); +#93963 = LINE('',#93964,#93965); +#93964 = CARTESIAN_POINT('',(0.65,3.35)); +#93965 = VECTOR('',#93966,1.); +#93966 = DIRECTION('',(0.E+000,-1.)); +#93967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93968 = PCURVE('',#93969,#93974); +#93969 = PLANE('',#93970); +#93970 = AXIS2_PLACEMENT_3D('',#93971,#93972,#93973); +#93971 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.75)); +#93972 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#93973 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#93974 = DEFINITIONAL_REPRESENTATION('',(#93975),#93979); +#93975 = LINE('',#93976,#93977); +#93976 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#93977 = VECTOR('',#93978,1.); +#93978 = DIRECTION('',(4.440892098501E-016,-1.)); +#93979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#93980 = FACE_BOUND('',#93981,.T.); +#93981 = EDGE_LOOP('',(#93982,#94012,#94040,#94068)); +#93982 = ORIENTED_EDGE('',*,*,#93983,.T.); +#93983 = EDGE_CURVE('',#93984,#93986,#93988,.T.); +#93984 = VERTEX_POINT('',#93985); +#93985 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.75)); +#93986 = VERTEX_POINT('',#93987); +#93987 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.65)); +#93988 = SURFACE_CURVE('',#93989,(#93993,#94000),.PCURVE_S1.); +#93989 = LINE('',#93990,#93991); +#93990 = CARTESIAN_POINT('',(-1.176836406103E-015,2.65,0.65)); +#93991 = VECTOR('',#93992,1.); +#93992 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#93993 = PCURVE('',#92735,#93994); +#93994 = DEFINITIONAL_REPRESENTATION('',(#93995),#93999); +#93995 = LINE('',#93996,#93997); +#93996 = CARTESIAN_POINT('',(0.75,2.65)); +#93997 = VECTOR('',#93998,1.); +#93998 = DIRECTION('',(1.,0.E+000)); +#93999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94000 = PCURVE('',#94001,#94006); +#94001 = PLANE('',#94002); +#94002 = AXIS2_PLACEMENT_3D('',#94003,#94004,#94005); +#94003 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.65)); +#94004 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94005 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94006 = DEFINITIONAL_REPRESENTATION('',(#94007),#94011); +#94007 = LINE('',#94008,#94009); +#94008 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#94009 = VECTOR('',#94010,1.); +#94010 = DIRECTION('',(1.,0.E+000)); +#94011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94012 = ORIENTED_EDGE('',*,*,#94013,.T.); +#94013 = EDGE_CURVE('',#93986,#94014,#94016,.T.); +#94014 = VERTEX_POINT('',#94015); +#94015 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); +#94016 = SURFACE_CURVE('',#94017,(#94021,#94028),.PCURVE_S1.); +#94017 = LINE('',#94018,#94019); +#94018 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); +#94019 = VECTOR('',#94020,1.); +#94020 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#94021 = PCURVE('',#92735,#94022); +#94022 = DEFINITIONAL_REPRESENTATION('',(#94023),#94027); +#94023 = LINE('',#94024,#94025); +#94024 = CARTESIAN_POINT('',(0.75,2.85)); +#94025 = VECTOR('',#94026,1.); +#94026 = DIRECTION('',(0.E+000,1.)); +#94027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94028 = PCURVE('',#94029,#94034); +#94029 = PLANE('',#94030); +#94030 = AXIS2_PLACEMENT_3D('',#94031,#94032,#94033); +#94031 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); +#94032 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#94033 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#94034 = DEFINITIONAL_REPRESENTATION('',(#94035),#94039); +#94035 = LINE('',#94036,#94037); +#94036 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94037 = VECTOR('',#94038,1.); +#94038 = DIRECTION('',(4.440892098501E-016,1.)); +#94039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94040 = ORIENTED_EDGE('',*,*,#94041,.T.); +#94041 = EDGE_CURVE('',#94014,#94042,#94044,.T.); +#94042 = VERTEX_POINT('',#94043); +#94043 = CARTESIAN_POINT('',(0.E+000,2.85,0.75)); +#94044 = SURFACE_CURVE('',#94045,(#94049,#94056),.PCURVE_S1.); +#94045 = LINE('',#94046,#94047); +#94046 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.65)); +#94047 = VECTOR('',#94048,1.); +#94048 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94049 = PCURVE('',#92735,#94050); +#94050 = DEFINITIONAL_REPRESENTATION('',(#94051),#94055); +#94051 = LINE('',#94052,#94053); +#94052 = CARTESIAN_POINT('',(0.75,2.85)); +#94053 = VECTOR('',#94054,1.); +#94054 = DIRECTION('',(-1.,0.E+000)); +#94055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94056 = PCURVE('',#94057,#94062); +#94057 = PLANE('',#94058); +#94058 = AXIS2_PLACEMENT_3D('',#94059,#94060,#94061); +#94059 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); +#94060 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94061 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94062 = DEFINITIONAL_REPRESENTATION('',(#94063),#94067); +#94063 = LINE('',#94064,#94065); +#94064 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#94065 = VECTOR('',#94066,1.); +#94066 = DIRECTION('',(1.,0.E+000)); +#94067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94068 = ORIENTED_EDGE('',*,*,#94069,.T.); +#94069 = EDGE_CURVE('',#94042,#93984,#94070,.T.); +#94070 = SURFACE_CURVE('',#94071,(#94075,#94082),.PCURVE_S1.); +#94071 = LINE('',#94072,#94073); +#94072 = CARTESIAN_POINT('',(-1.265654248073E-015,2.85,0.75)); +#94073 = VECTOR('',#94074,1.); +#94074 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#94075 = PCURVE('',#92735,#94076); +#94076 = DEFINITIONAL_REPRESENTATION('',(#94077),#94081); +#94077 = LINE('',#94078,#94079); +#94078 = CARTESIAN_POINT('',(0.65,2.85)); +#94079 = VECTOR('',#94080,1.); +#94080 = DIRECTION('',(0.E+000,-1.)); +#94081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94082 = PCURVE('',#94083,#94088); +#94083 = PLANE('',#94084); +#94084 = AXIS2_PLACEMENT_3D('',#94085,#94086,#94087); +#94085 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.75)); +#94086 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#94087 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#94088 = DEFINITIONAL_REPRESENTATION('',(#94089),#94093); +#94089 = LINE('',#94090,#94091); +#94090 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94091 = VECTOR('',#94092,1.); +#94092 = DIRECTION('',(4.440892098501E-016,-1.)); +#94093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94094 = FACE_BOUND('',#94095,.T.); +#94095 = EDGE_LOOP('',(#94096,#94126,#94154,#94182)); +#94096 = ORIENTED_EDGE('',*,*,#94097,.T.); +#94097 = EDGE_CURVE('',#94098,#94100,#94102,.T.); +#94098 = VERTEX_POINT('',#94099); +#94099 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.75)); +#94100 = VERTEX_POINT('',#94101); +#94101 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.65)); +#94102 = SURFACE_CURVE('',#94103,(#94107,#94114),.PCURVE_S1.); +#94103 = LINE('',#94104,#94105); +#94104 = CARTESIAN_POINT('',(-9.547918011776E-016,2.15,0.65)); +#94105 = VECTOR('',#94106,1.); +#94106 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94107 = PCURVE('',#92735,#94108); +#94108 = DEFINITIONAL_REPRESENTATION('',(#94109),#94113); +#94109 = LINE('',#94110,#94111); +#94110 = CARTESIAN_POINT('',(0.75,2.15)); +#94111 = VECTOR('',#94112,1.); +#94112 = DIRECTION('',(1.,0.E+000)); +#94113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94114 = PCURVE('',#94115,#94120); +#94115 = PLANE('',#94116); +#94116 = AXIS2_PLACEMENT_3D('',#94117,#94118,#94119); +#94117 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.65)); +#94118 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94119 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94120 = DEFINITIONAL_REPRESENTATION('',(#94121),#94125); +#94121 = LINE('',#94122,#94123); +#94122 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#94123 = VECTOR('',#94124,1.); +#94124 = DIRECTION('',(1.,0.E+000)); +#94125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94126 = ORIENTED_EDGE('',*,*,#94127,.T.); +#94127 = EDGE_CURVE('',#94100,#94128,#94130,.T.); +#94128 = VERTEX_POINT('',#94129); +#94129 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); +#94130 = SURFACE_CURVE('',#94131,(#94135,#94142),.PCURVE_S1.); +#94131 = LINE('',#94132,#94133); +#94132 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); +#94133 = VECTOR('',#94134,1.); +#94134 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#94135 = PCURVE('',#92735,#94136); #94136 = DEFINITIONAL_REPRESENTATION('',(#94137),#94141); #94137 = LINE('',#94138,#94139); -#94138 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#94138 = CARTESIAN_POINT('',(0.75,2.35)); #94139 = VECTOR('',#94140,1.); -#94140 = DIRECTION('',(0.E+000,-1.)); +#94140 = DIRECTION('',(0.E+000,1.)); #94141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94142 = ORIENTED_EDGE('',*,*,#94143,.T.); -#94143 = EDGE_CURVE('',#94121,#94144,#94146,.T.); -#94144 = VERTEX_POINT('',#94145); -#94145 = CARTESIAN_POINT('',(10.,9.8,0.E+000)); -#94146 = SURFACE_CURVE('',#94147,(#94151,#94158),.PCURVE_S1.); -#94147 = LINE('',#94148,#94149); -#94148 = CARTESIAN_POINT('',(10.,0.E+000,0.E+000)); -#94149 = VECTOR('',#94150,1.); -#94150 = DIRECTION('',(0.E+000,1.,0.E+000)); -#94151 = PCURVE('',#92272,#94152); -#94152 = DEFINITIONAL_REPRESENTATION('',(#94153),#94157); -#94153 = LINE('',#94154,#94155); -#94154 = CARTESIAN_POINT('',(-1.4,0.E+000)); -#94155 = VECTOR('',#94156,1.); -#94156 = DIRECTION('',(0.E+000,1.)); -#94157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94158 = PCURVE('',#86472,#94159); -#94159 = DEFINITIONAL_REPRESENTATION('',(#94160),#94164); -#94160 = LINE('',#94161,#94162); -#94161 = CARTESIAN_POINT('',(-10.,-10.)); -#94162 = VECTOR('',#94163,1.); -#94163 = DIRECTION('',(0.E+000,1.)); -#94164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94165 = ORIENTED_EDGE('',*,*,#94166,.T.); -#94166 = EDGE_CURVE('',#94144,#94091,#94167,.T.); -#94167 = SURFACE_CURVE('',#94168,(#94172,#94179),.PCURVE_S1.); -#94168 = LINE('',#94169,#94170); -#94169 = CARTESIAN_POINT('',(10.,9.8,1.4)); -#94170 = VECTOR('',#94171,1.); -#94171 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94172 = PCURVE('',#92272,#94173); -#94173 = DEFINITIONAL_REPRESENTATION('',(#94174),#94178); -#94174 = LINE('',#94175,#94176); -#94175 = CARTESIAN_POINT('',(0.E+000,9.8)); -#94176 = VECTOR('',#94177,1.); -#94177 = DIRECTION('',(1.,0.E+000)); -#94178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94179 = PCURVE('',#86554,#94180); -#94180 = DEFINITIONAL_REPRESENTATION('',(#94181),#94185); -#94181 = LINE('',#94182,#94183); -#94182 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); -#94183 = VECTOR('',#94184,1.); -#94184 = DIRECTION('',(0.E+000,1.)); -#94185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94186 = ADVANCED_FACE('',(#94187,#94215),#86411,.F.); -#94187 = FACE_BOUND('',#94188,.T.); -#94188 = EDGE_LOOP('',(#94189,#94214)); -#94189 = ORIENTED_EDGE('',*,*,#94190,.F.); -#94190 = EDGE_CURVE('',#86370,#86396,#94191,.T.); -#94191 = SURFACE_CURVE('',#94192,(#94197,#94208),.PCURVE_S1.); -#94192 = CIRCLE('',#94193,0.345974717232); -#94193 = AXIS2_PLACEMENT_3D('',#94194,#94195,#94196); -#94194 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.4)); -#94195 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94196 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94197 = PCURVE('',#86411,#94198); -#94198 = DEFINITIONAL_REPRESENTATION('',(#94199),#94207); -#94199 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#94200,#94201,#94202,#94203 - ,#94204,#94205,#94206),.UNSPECIFIED.,.T.,.F.) +#94142 = PCURVE('',#94143,#94148); +#94143 = PLANE('',#94144); +#94144 = AXIS2_PLACEMENT_3D('',#94145,#94146,#94147); +#94145 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); +#94146 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#94147 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#94148 = DEFINITIONAL_REPRESENTATION('',(#94149),#94153); +#94149 = LINE('',#94150,#94151); +#94150 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94151 = VECTOR('',#94152,1.); +#94152 = DIRECTION('',(4.440892098501E-016,1.)); +#94153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94154 = ORIENTED_EDGE('',*,*,#94155,.T.); +#94155 = EDGE_CURVE('',#94128,#94156,#94158,.T.); +#94156 = VERTEX_POINT('',#94157); +#94157 = CARTESIAN_POINT('',(0.E+000,2.35,0.75)); +#94158 = SURFACE_CURVE('',#94159,(#94163,#94170),.PCURVE_S1.); +#94159 = LINE('',#94160,#94161); +#94160 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.65)); +#94161 = VECTOR('',#94162,1.); +#94162 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94163 = PCURVE('',#92735,#94164); +#94164 = DEFINITIONAL_REPRESENTATION('',(#94165),#94169); +#94165 = LINE('',#94166,#94167); +#94166 = CARTESIAN_POINT('',(0.75,2.35)); +#94167 = VECTOR('',#94168,1.); +#94168 = DIRECTION('',(-1.,0.E+000)); +#94169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94170 = PCURVE('',#94171,#94176); +#94171 = PLANE('',#94172); +#94172 = AXIS2_PLACEMENT_3D('',#94173,#94174,#94175); +#94173 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); +#94174 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94175 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94176 = DEFINITIONAL_REPRESENTATION('',(#94177),#94181); +#94177 = LINE('',#94178,#94179); +#94178 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#94179 = VECTOR('',#94180,1.); +#94180 = DIRECTION('',(1.,0.E+000)); +#94181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94182 = ORIENTED_EDGE('',*,*,#94183,.T.); +#94183 = EDGE_CURVE('',#94156,#94098,#94184,.T.); +#94184 = SURFACE_CURVE('',#94185,(#94189,#94196),.PCURVE_S1.); +#94185 = LINE('',#94186,#94187); +#94186 = CARTESIAN_POINT('',(-1.043609643148E-015,2.35,0.75)); +#94187 = VECTOR('',#94188,1.); +#94188 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#94189 = PCURVE('',#92735,#94190); +#94190 = DEFINITIONAL_REPRESENTATION('',(#94191),#94195); +#94191 = LINE('',#94192,#94193); +#94192 = CARTESIAN_POINT('',(0.65,2.35)); +#94193 = VECTOR('',#94194,1.); +#94194 = DIRECTION('',(0.E+000,-1.)); +#94195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94196 = PCURVE('',#94197,#94202); +#94197 = PLANE('',#94198); +#94198 = AXIS2_PLACEMENT_3D('',#94199,#94200,#94201); +#94199 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.75)); +#94200 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#94201 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#94202 = DEFINITIONAL_REPRESENTATION('',(#94203),#94207); +#94203 = LINE('',#94204,#94205); +#94204 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94205 = VECTOR('',#94206,1.); +#94206 = DIRECTION('',(4.440892098501E-016,-1.)); +#94207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94208 = FACE_BOUND('',#94209,.T.); +#94209 = EDGE_LOOP('',(#94210,#94240,#94268,#94296)); +#94210 = ORIENTED_EDGE('',*,*,#94211,.T.); +#94211 = EDGE_CURVE('',#94212,#94214,#94216,.T.); +#94212 = VERTEX_POINT('',#94213); +#94213 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.75)); +#94214 = VERTEX_POINT('',#94215); +#94215 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.65)); +#94216 = SURFACE_CURVE('',#94217,(#94221,#94228),.PCURVE_S1.); +#94217 = LINE('',#94218,#94219); +#94218 = CARTESIAN_POINT('',(-7.327471962526E-016,1.65,0.65)); +#94219 = VECTOR('',#94220,1.); +#94220 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94221 = PCURVE('',#92735,#94222); +#94222 = DEFINITIONAL_REPRESENTATION('',(#94223),#94227); +#94223 = LINE('',#94224,#94225); +#94224 = CARTESIAN_POINT('',(0.75,1.65)); +#94225 = VECTOR('',#94226,1.); +#94226 = DIRECTION('',(1.,0.E+000)); +#94227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94228 = PCURVE('',#94229,#94234); +#94229 = PLANE('',#94230); +#94230 = AXIS2_PLACEMENT_3D('',#94231,#94232,#94233); +#94231 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.65)); +#94232 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94233 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94234 = DEFINITIONAL_REPRESENTATION('',(#94235),#94239); +#94235 = LINE('',#94236,#94237); +#94236 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#94237 = VECTOR('',#94238,1.); +#94238 = DIRECTION('',(1.,0.E+000)); +#94239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94240 = ORIENTED_EDGE('',*,*,#94241,.T.); +#94241 = EDGE_CURVE('',#94214,#94242,#94244,.T.); +#94242 = VERTEX_POINT('',#94243); +#94243 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); +#94244 = SURFACE_CURVE('',#94245,(#94249,#94256),.PCURVE_S1.); +#94245 = LINE('',#94246,#94247); +#94246 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); +#94247 = VECTOR('',#94248,1.); +#94248 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#94249 = PCURVE('',#92735,#94250); +#94250 = DEFINITIONAL_REPRESENTATION('',(#94251),#94255); +#94251 = LINE('',#94252,#94253); +#94252 = CARTESIAN_POINT('',(0.75,1.85)); +#94253 = VECTOR('',#94254,1.); +#94254 = DIRECTION('',(0.E+000,1.)); +#94255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94256 = PCURVE('',#94257,#94262); +#94257 = PLANE('',#94258); +#94258 = AXIS2_PLACEMENT_3D('',#94259,#94260,#94261); +#94259 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); +#94260 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#94261 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#94262 = DEFINITIONAL_REPRESENTATION('',(#94263),#94267); +#94263 = LINE('',#94264,#94265); +#94264 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94265 = VECTOR('',#94266,1.); +#94266 = DIRECTION('',(4.440892098501E-016,1.)); +#94267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94268 = ORIENTED_EDGE('',*,*,#94269,.T.); +#94269 = EDGE_CURVE('',#94242,#94270,#94272,.T.); +#94270 = VERTEX_POINT('',#94271); +#94271 = CARTESIAN_POINT('',(0.E+000,1.85,0.75)); +#94272 = SURFACE_CURVE('',#94273,(#94277,#94284),.PCURVE_S1.); +#94273 = LINE('',#94274,#94275); +#94274 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.65)); +#94275 = VECTOR('',#94276,1.); +#94276 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94277 = PCURVE('',#92735,#94278); +#94278 = DEFINITIONAL_REPRESENTATION('',(#94279),#94283); +#94279 = LINE('',#94280,#94281); +#94280 = CARTESIAN_POINT('',(0.75,1.85)); +#94281 = VECTOR('',#94282,1.); +#94282 = DIRECTION('',(-1.,0.E+000)); +#94283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94284 = PCURVE('',#94285,#94290); +#94285 = PLANE('',#94286); +#94286 = AXIS2_PLACEMENT_3D('',#94287,#94288,#94289); +#94287 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); +#94288 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94289 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94290 = DEFINITIONAL_REPRESENTATION('',(#94291),#94295); +#94291 = LINE('',#94292,#94293); +#94292 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#94293 = VECTOR('',#94294,1.); +#94294 = DIRECTION('',(1.,0.E+000)); +#94295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94296 = ORIENTED_EDGE('',*,*,#94297,.T.); +#94297 = EDGE_CURVE('',#94270,#94212,#94298,.T.); +#94298 = SURFACE_CURVE('',#94299,(#94303,#94310),.PCURVE_S1.); +#94299 = LINE('',#94300,#94301); +#94300 = CARTESIAN_POINT('',(-8.215650382226E-016,1.85,0.75)); +#94301 = VECTOR('',#94302,1.); +#94302 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#94303 = PCURVE('',#92735,#94304); +#94304 = DEFINITIONAL_REPRESENTATION('',(#94305),#94309); +#94305 = LINE('',#94306,#94307); +#94306 = CARTESIAN_POINT('',(0.65,1.85)); +#94307 = VECTOR('',#94308,1.); +#94308 = DIRECTION('',(0.E+000,-1.)); +#94309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94310 = PCURVE('',#94311,#94316); +#94311 = PLANE('',#94312); +#94312 = AXIS2_PLACEMENT_3D('',#94313,#94314,#94315); +#94313 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.75)); +#94314 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#94315 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#94316 = DEFINITIONAL_REPRESENTATION('',(#94317),#94321); +#94317 = LINE('',#94318,#94319); +#94318 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94319 = VECTOR('',#94320,1.); +#94320 = DIRECTION('',(4.440892098501E-016,-1.)); +#94321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94322 = FACE_BOUND('',#94323,.T.); +#94323 = EDGE_LOOP('',(#94324,#94354,#94382,#94410)); +#94324 = ORIENTED_EDGE('',*,*,#94325,.T.); +#94325 = EDGE_CURVE('',#94326,#94328,#94330,.T.); +#94326 = VERTEX_POINT('',#94327); +#94327 = CARTESIAN_POINT('',(-2.375877272698E-015,5.35,0.75)); +#94328 = VERTEX_POINT('',#94329); +#94329 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.75)); +#94330 = SURFACE_CURVE('',#94331,(#94335,#94342),.PCURVE_S1.); +#94331 = LINE('',#94332,#94333); +#94332 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.75)); +#94333 = VECTOR('',#94334,1.); +#94334 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#94335 = PCURVE('',#92735,#94336); +#94336 = DEFINITIONAL_REPRESENTATION('',(#94337),#94341); +#94337 = LINE('',#94338,#94339); +#94338 = CARTESIAN_POINT('',(0.65,5.15)); +#94339 = VECTOR('',#94340,1.); +#94340 = DIRECTION('',(0.E+000,-1.)); +#94341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94342 = PCURVE('',#94343,#94348); +#94343 = PLANE('',#94344); +#94344 = AXIS2_PLACEMENT_3D('',#94345,#94346,#94347); +#94345 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.75)); +#94346 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#94347 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#94348 = DEFINITIONAL_REPRESENTATION('',(#94349),#94353); +#94349 = LINE('',#94350,#94351); +#94350 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94351 = VECTOR('',#94352,1.); +#94352 = DIRECTION('',(4.440892098501E-016,-1.)); +#94353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94354 = ORIENTED_EDGE('',*,*,#94355,.T.); +#94355 = EDGE_CURVE('',#94328,#94356,#94358,.T.); +#94356 = VERTEX_POINT('',#94357); +#94357 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); +#94358 = SURFACE_CURVE('',#94359,(#94363,#94370),.PCURVE_S1.); +#94359 = LINE('',#94360,#94361); +#94360 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); +#94361 = VECTOR('',#94362,1.); +#94362 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94363 = PCURVE('',#92735,#94364); +#94364 = DEFINITIONAL_REPRESENTATION('',(#94365),#94369); +#94365 = LINE('',#94366,#94367); +#94366 = CARTESIAN_POINT('',(0.75,5.15)); +#94367 = VECTOR('',#94368,1.); +#94368 = DIRECTION('',(1.,0.E+000)); +#94369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94370 = PCURVE('',#94371,#94376); +#94371 = PLANE('',#94372); +#94372 = AXIS2_PLACEMENT_3D('',#94373,#94374,#94375); +#94373 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); +#94374 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94375 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94376 = DEFINITIONAL_REPRESENTATION('',(#94377),#94381); +#94377 = LINE('',#94378,#94379); +#94378 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#94379 = VECTOR('',#94380,1.); +#94380 = DIRECTION('',(1.,0.E+000)); +#94381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94382 = ORIENTED_EDGE('',*,*,#94383,.T.); +#94383 = EDGE_CURVE('',#94356,#94384,#94386,.T.); +#94384 = VERTEX_POINT('',#94385); +#94385 = CARTESIAN_POINT('',(0.E+000,5.35,0.65)); +#94386 = SURFACE_CURVE('',#94387,(#94391,#94398),.PCURVE_S1.); +#94387 = LINE('',#94388,#94389); +#94388 = CARTESIAN_POINT('',(-2.287059430728E-015,5.15,0.65)); +#94389 = VECTOR('',#94390,1.); +#94390 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#94391 = PCURVE('',#92735,#94392); +#94392 = DEFINITIONAL_REPRESENTATION('',(#94393),#94397); +#94393 = LINE('',#94394,#94395); +#94394 = CARTESIAN_POINT('',(0.75,5.15)); +#94395 = VECTOR('',#94396,1.); +#94396 = DIRECTION('',(0.E+000,1.)); +#94397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94398 = PCURVE('',#94399,#94404); +#94399 = PLANE('',#94400); +#94400 = AXIS2_PLACEMENT_3D('',#94401,#94402,#94403); +#94401 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); +#94402 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#94403 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#94404 = DEFINITIONAL_REPRESENTATION('',(#94405),#94409); +#94405 = LINE('',#94406,#94407); +#94406 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94407 = VECTOR('',#94408,1.); +#94408 = DIRECTION('',(4.440892098501E-016,1.)); +#94409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94410 = ORIENTED_EDGE('',*,*,#94411,.T.); +#94411 = EDGE_CURVE('',#94384,#94326,#94412,.T.); +#94412 = SURFACE_CURVE('',#94413,(#94417,#94424),.PCURVE_S1.); +#94413 = LINE('',#94414,#94415); +#94414 = CARTESIAN_POINT('',(-2.375877272698E-015,5.35,0.65)); +#94415 = VECTOR('',#94416,1.); +#94416 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94417 = PCURVE('',#92735,#94418); +#94418 = DEFINITIONAL_REPRESENTATION('',(#94419),#94423); +#94419 = LINE('',#94420,#94421); +#94420 = CARTESIAN_POINT('',(0.75,5.35)); +#94421 = VECTOR('',#94422,1.); +#94422 = DIRECTION('',(-1.,0.E+000)); +#94423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94424 = PCURVE('',#94425,#94430); +#94425 = PLANE('',#94426); +#94426 = AXIS2_PLACEMENT_3D('',#94427,#94428,#94429); +#94427 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.65)); +#94428 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94429 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94430 = DEFINITIONAL_REPRESENTATION('',(#94431),#94435); +#94431 = LINE('',#94432,#94433); +#94432 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#94433 = VECTOR('',#94434,1.); +#94434 = DIRECTION('',(1.,0.E+000)); +#94435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94436 = FACE_BOUND('',#94437,.T.); +#94437 = EDGE_LOOP('',(#94438,#94468,#94496,#94524)); +#94438 = ORIENTED_EDGE('',*,*,#94439,.T.); +#94439 = EDGE_CURVE('',#94440,#94442,#94444,.T.); +#94440 = VERTEX_POINT('',#94441); +#94441 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.75)); +#94442 = VERTEX_POINT('',#94443); +#94443 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.65)); +#94444 = SURFACE_CURVE('',#94445,(#94449,#94456),.PCURVE_S1.); +#94445 = LINE('',#94446,#94447); +#94446 = CARTESIAN_POINT('',(-5.107025913276E-016,1.15,0.65)); +#94447 = VECTOR('',#94448,1.); +#94448 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94449 = PCURVE('',#92735,#94450); +#94450 = DEFINITIONAL_REPRESENTATION('',(#94451),#94455); +#94451 = LINE('',#94452,#94453); +#94452 = CARTESIAN_POINT('',(0.75,1.15)); +#94453 = VECTOR('',#94454,1.); +#94454 = DIRECTION('',(1.,0.E+000)); +#94455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94456 = PCURVE('',#94457,#94462); +#94457 = PLANE('',#94458); +#94458 = AXIS2_PLACEMENT_3D('',#94459,#94460,#94461); +#94459 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.65)); +#94460 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94461 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94462 = DEFINITIONAL_REPRESENTATION('',(#94463),#94467); +#94463 = LINE('',#94464,#94465); +#94464 = CARTESIAN_POINT('',(-2.22044604925E-016,0.527847992439)); +#94465 = VECTOR('',#94466,1.); +#94466 = DIRECTION('',(1.,0.E+000)); +#94467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94468 = ORIENTED_EDGE('',*,*,#94469,.T.); +#94469 = EDGE_CURVE('',#94442,#94470,#94472,.T.); +#94470 = VERTEX_POINT('',#94471); +#94471 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); +#94472 = SURFACE_CURVE('',#94473,(#94477,#94484),.PCURVE_S1.); +#94473 = LINE('',#94474,#94475); +#94474 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); +#94475 = VECTOR('',#94476,1.); +#94476 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#94477 = PCURVE('',#92735,#94478); +#94478 = DEFINITIONAL_REPRESENTATION('',(#94479),#94483); +#94479 = LINE('',#94480,#94481); +#94480 = CARTESIAN_POINT('',(0.75,1.35)); +#94481 = VECTOR('',#94482,1.); +#94482 = DIRECTION('',(0.E+000,1.)); +#94483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94484 = PCURVE('',#94485,#94490); +#94485 = PLANE('',#94486); +#94486 = AXIS2_PLACEMENT_3D('',#94487,#94488,#94489); +#94487 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); +#94488 = DIRECTION('',(3.563627120235E-016,1.582568352025E-031,-1.)); +#94489 = DIRECTION('',(-1.,0.E+000,-3.563627120235E-016)); +#94490 = DEFINITIONAL_REPRESENTATION('',(#94491),#94495); +#94491 = LINE('',#94492,#94493); +#94492 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94493 = VECTOR('',#94494,1.); +#94494 = DIRECTION('',(4.440892098501E-016,1.)); +#94495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94496 = ORIENTED_EDGE('',*,*,#94497,.T.); +#94497 = EDGE_CURVE('',#94470,#94498,#94500,.T.); +#94498 = VERTEX_POINT('',#94499); +#94499 = CARTESIAN_POINT('',(0.E+000,1.35,0.75)); +#94500 = SURFACE_CURVE('',#94501,(#94505,#94512),.PCURVE_S1.); +#94501 = LINE('',#94502,#94503); +#94502 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.65)); +#94503 = VECTOR('',#94504,1.); +#94504 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94505 = PCURVE('',#92735,#94506); +#94506 = DEFINITIONAL_REPRESENTATION('',(#94507),#94511); +#94507 = LINE('',#94508,#94509); +#94508 = CARTESIAN_POINT('',(0.75,1.35)); +#94509 = VECTOR('',#94510,1.); +#94510 = DIRECTION('',(-1.,0.E+000)); +#94511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94512 = PCURVE('',#94513,#94518); +#94513 = PLANE('',#94514); +#94514 = AXIS2_PLACEMENT_3D('',#94515,#94516,#94517); +#94515 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); +#94516 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94517 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94518 = DEFINITIONAL_REPRESENTATION('',(#94519),#94523); +#94519 = LINE('',#94520,#94521); +#94520 = CARTESIAN_POINT('',(2.22044604925E-016,0.527847992439)); +#94521 = VECTOR('',#94522,1.); +#94522 = DIRECTION('',(1.,0.E+000)); +#94523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94524 = ORIENTED_EDGE('',*,*,#94525,.T.); +#94525 = EDGE_CURVE('',#94498,#94440,#94526,.T.); +#94526 = SURFACE_CURVE('',#94527,(#94531,#94538),.PCURVE_S1.); +#94527 = LINE('',#94528,#94529); +#94528 = CARTESIAN_POINT('',(-5.995204332976E-016,1.35,0.75)); +#94529 = VECTOR('',#94530,1.); +#94530 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#94531 = PCURVE('',#92735,#94532); +#94532 = DEFINITIONAL_REPRESENTATION('',(#94533),#94537); +#94533 = LINE('',#94534,#94535); +#94534 = CARTESIAN_POINT('',(0.65,1.35)); +#94535 = VECTOR('',#94536,1.); +#94536 = DIRECTION('',(0.E+000,-1.)); +#94537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94538 = PCURVE('',#94539,#94544); +#94539 = PLANE('',#94540); +#94540 = AXIS2_PLACEMENT_3D('',#94541,#94542,#94543); +#94541 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.75)); +#94542 = DIRECTION('',(-3.563627120235E-016,-1.582568352025E-031,1.)); +#94543 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#94544 = DEFINITIONAL_REPRESENTATION('',(#94545),#94549); +#94545 = LINE('',#94546,#94547); +#94546 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94547 = VECTOR('',#94548,1.); +#94548 = DIRECTION('',(4.440892098501E-016,-1.)); +#94549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94550 = FACE_BOUND('',#94551,.T.); +#94551 = EDGE_LOOP('',(#94552,#94577,#94600,#94628)); +#94552 = ORIENTED_EDGE('',*,*,#94553,.T.); +#94553 = EDGE_CURVE('',#94554,#94556,#94558,.T.); +#94554 = VERTEX_POINT('',#94555); +#94555 = CARTESIAN_POINT('',(-6.030874584451E-016,9.8,0.E+000)); +#94556 = VERTEX_POINT('',#94557); +#94557 = CARTESIAN_POINT('',(0.E+000,0.2,0.E+000)); +#94558 = SURFACE_CURVE('',#94559,(#94563,#94570),.PCURVE_S1.); +#94559 = LINE('',#94560,#94561); +#94560 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#94561 = VECTOR('',#94562,1.); +#94562 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94563 = PCURVE('',#92735,#94564); +#94564 = DEFINITIONAL_REPRESENTATION('',(#94565),#94569); +#94565 = LINE('',#94566,#94567); +#94566 = CARTESIAN_POINT('',(1.4,0.E+000)); +#94567 = VECTOR('',#94568,1.); +#94568 = DIRECTION('',(0.E+000,-1.)); +#94569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94570 = PCURVE('',#88864,#94571); +#94571 = DEFINITIONAL_REPRESENTATION('',(#94572),#94576); +#94572 = LINE('',#94573,#94574); +#94573 = CARTESIAN_POINT('',(0.E+000,-10.)); +#94574 = VECTOR('',#94575,1.); +#94575 = DIRECTION('',(0.E+000,-1.)); +#94576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94577 = ORIENTED_EDGE('',*,*,#94578,.T.); +#94578 = EDGE_CURVE('',#94556,#94579,#94581,.T.); +#94579 = VERTEX_POINT('',#94580); +#94580 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); +#94581 = SURFACE_CURVE('',#94582,(#94586,#94593),.PCURVE_S1.); +#94582 = LINE('',#94583,#94584); +#94583 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); +#94584 = VECTOR('',#94585,1.); +#94585 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94586 = PCURVE('',#92735,#94587); +#94587 = DEFINITIONAL_REPRESENTATION('',(#94588),#94592); +#94588 = LINE('',#94589,#94590); +#94589 = CARTESIAN_POINT('',(0.E+000,0.2)); +#94590 = VECTOR('',#94591,1.); +#94591 = DIRECTION('',(-1.,0.E+000)); +#94592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94593 = PCURVE('',#91748,#94594); +#94594 = DEFINITIONAL_REPRESENTATION('',(#94595),#94599); +#94595 = LINE('',#94596,#94597); +#94596 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); +#94597 = VECTOR('',#94598,1.); +#94598 = DIRECTION('',(0.E+000,1.)); +#94599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94600 = ORIENTED_EDGE('',*,*,#94601,.T.); +#94601 = EDGE_CURVE('',#94579,#94602,#94604,.T.); +#94602 = VERTEX_POINT('',#94603); +#94603 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); +#94604 = SURFACE_CURVE('',#94605,(#94609,#94616),.PCURVE_S1.); +#94605 = LINE('',#94606,#94607); +#94606 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.2)); +#94607 = VECTOR('',#94608,1.); +#94608 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94609 = PCURVE('',#92735,#94610); +#94610 = DEFINITIONAL_REPRESENTATION('',(#94611),#94615); +#94611 = LINE('',#94612,#94613); +#94612 = CARTESIAN_POINT('',(0.2,0.E+000)); +#94613 = VECTOR('',#94614,1.); +#94614 = DIRECTION('',(0.E+000,1.)); +#94615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94616 = PCURVE('',#94617,#94622); +#94617 = PLANE('',#94618); +#94618 = AXIS2_PLACEMENT_3D('',#94619,#94620,#94621); +#94619 = CARTESIAN_POINT('',(0.2,10.,1.4)); +#94620 = DIRECTION('',(0.707106781187,0.E+000,-0.707106781187)); +#94621 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); +#94622 = DEFINITIONAL_REPRESENTATION('',(#94623),#94627); +#94623 = LINE('',#94624,#94625); +#94624 = CARTESIAN_POINT('',(0.282842712475,-10.)); +#94625 = VECTOR('',#94626,1.); +#94626 = DIRECTION('',(0.E+000,1.)); +#94627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94628 = ORIENTED_EDGE('',*,*,#94629,.T.); +#94629 = EDGE_CURVE('',#94602,#94554,#94630,.T.); +#94630 = SURFACE_CURVE('',#94631,(#94635,#94642),.PCURVE_S1.); +#94631 = LINE('',#94632,#94633); +#94632 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); +#94633 = VECTOR('',#94634,1.); +#94634 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94635 = PCURVE('',#92735,#94636); +#94636 = DEFINITIONAL_REPRESENTATION('',(#94637),#94641); +#94637 = LINE('',#94638,#94639); +#94638 = CARTESIAN_POINT('',(0.E+000,9.8)); +#94639 = VECTOR('',#94640,1.); +#94640 = DIRECTION('',(1.,0.E+000)); +#94641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94642 = PCURVE('',#88892,#94643); +#94643 = DEFINITIONAL_REPRESENTATION('',(#94644),#94648); +#94644 = LINE('',#94645,#94646); +#94645 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#94646 = VECTOR('',#94647,1.); +#94647 = DIRECTION('',(0.E+000,-1.)); +#94648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94649 = ADVANCED_FACE('',(#94650,#94769,#94883,#94997,#95111,#95225, + #95339,#95453,#95567,#95681,#95795,#95909,#96023,#96137,#96251, + #96365,#96479),#94664,.F.); +#94650 = FACE_BOUND('',#94651,.T.); +#94651 = EDGE_LOOP('',(#94652,#94687,#94715,#94743)); +#94652 = ORIENTED_EDGE('',*,*,#94653,.T.); +#94653 = EDGE_CURVE('',#94654,#94656,#94658,.T.); +#94654 = VERTEX_POINT('',#94655); +#94655 = CARTESIAN_POINT('',(10.,1.35,0.75)); +#94656 = VERTEX_POINT('',#94657); +#94657 = CARTESIAN_POINT('',(10.,1.35,0.65)); +#94658 = SURFACE_CURVE('',#94659,(#94663,#94675),.PCURVE_S1.); +#94659 = LINE('',#94660,#94661); +#94660 = CARTESIAN_POINT('',(10.,1.35,0.65)); +#94661 = VECTOR('',#94662,1.); +#94662 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94663 = PCURVE('',#94664,#94669); +#94664 = PLANE('',#94665); +#94665 = AXIS2_PLACEMENT_3D('',#94666,#94667,#94668); +#94666 = CARTESIAN_POINT('',(10.,0.E+000,1.4)); +#94667 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#94668 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94669 = DEFINITIONAL_REPRESENTATION('',(#94670),#94674); +#94670 = LINE('',#94671,#94672); +#94671 = CARTESIAN_POINT('',(-0.75,1.35)); +#94672 = VECTOR('',#94673,1.); +#94673 = DIRECTION('',(-1.,0.E+000)); +#94674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94675 = PCURVE('',#94676,#94681); +#94676 = PLANE('',#94677); +#94677 = AXIS2_PLACEMENT_3D('',#94678,#94679,#94680); +#94678 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); +#94679 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94680 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94681 = DEFINITIONAL_REPRESENTATION('',(#94682),#94686); +#94682 = LINE('',#94683,#94684); +#94683 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#94684 = VECTOR('',#94685,1.); +#94685 = DIRECTION('',(-1.,0.E+000)); +#94686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94687 = ORIENTED_EDGE('',*,*,#94688,.T.); +#94688 = EDGE_CURVE('',#94656,#94689,#94691,.T.); +#94689 = VERTEX_POINT('',#94690); +#94690 = CARTESIAN_POINT('',(10.,1.15,0.65)); +#94691 = SURFACE_CURVE('',#94692,(#94696,#94703),.PCURVE_S1.); +#94692 = LINE('',#94693,#94694); +#94693 = CARTESIAN_POINT('',(10.,1.35,0.65)); +#94694 = VECTOR('',#94695,1.); +#94695 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#94696 = PCURVE('',#94664,#94697); +#94697 = DEFINITIONAL_REPRESENTATION('',(#94698),#94702); +#94698 = LINE('',#94699,#94700); +#94699 = CARTESIAN_POINT('',(-0.75,1.35)); +#94700 = VECTOR('',#94701,1.); +#94701 = DIRECTION('',(0.E+000,-1.)); +#94702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94703 = PCURVE('',#94704,#94709); +#94704 = PLANE('',#94705); +#94705 = AXIS2_PLACEMENT_3D('',#94706,#94707,#94708); +#94706 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); +#94707 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#94708 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#94709 = DEFINITIONAL_REPRESENTATION('',(#94710),#94714); +#94710 = LINE('',#94711,#94712); +#94711 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94712 = VECTOR('',#94713,1.); +#94713 = DIRECTION('',(4.440892098501E-016,-1.)); +#94714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94715 = ORIENTED_EDGE('',*,*,#94716,.T.); +#94716 = EDGE_CURVE('',#94689,#94717,#94719,.T.); +#94717 = VERTEX_POINT('',#94718); +#94718 = CARTESIAN_POINT('',(10.,1.15,0.75)); +#94719 = SURFACE_CURVE('',#94720,(#94724,#94731),.PCURVE_S1.); +#94720 = LINE('',#94721,#94722); +#94721 = CARTESIAN_POINT('',(10.,1.15,0.65)); +#94722 = VECTOR('',#94723,1.); +#94723 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94724 = PCURVE('',#94664,#94725); +#94725 = DEFINITIONAL_REPRESENTATION('',(#94726),#94730); +#94726 = LINE('',#94727,#94728); +#94727 = CARTESIAN_POINT('',(-0.75,1.15)); +#94728 = VECTOR('',#94729,1.); +#94729 = DIRECTION('',(1.,0.E+000)); +#94730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94731 = PCURVE('',#94732,#94737); +#94732 = PLANE('',#94733); +#94733 = AXIS2_PLACEMENT_3D('',#94734,#94735,#94736); +#94734 = CARTESIAN_POINT('',(10.527847992439,1.15,0.65)); +#94735 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94736 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94737 = DEFINITIONAL_REPRESENTATION('',(#94738),#94742); +#94738 = LINE('',#94739,#94740); +#94739 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#94740 = VECTOR('',#94741,1.); +#94741 = DIRECTION('',(-1.,0.E+000)); +#94742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94743 = ORIENTED_EDGE('',*,*,#94744,.T.); +#94744 = EDGE_CURVE('',#94717,#94654,#94745,.T.); +#94745 = SURFACE_CURVE('',#94746,(#94750,#94757),.PCURVE_S1.); +#94746 = LINE('',#94747,#94748); +#94747 = CARTESIAN_POINT('',(10.,1.35,0.75)); +#94748 = VECTOR('',#94749,1.); +#94749 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#94750 = PCURVE('',#94664,#94751); +#94751 = DEFINITIONAL_REPRESENTATION('',(#94752),#94756); +#94752 = LINE('',#94753,#94754); +#94753 = CARTESIAN_POINT('',(-0.65,1.35)); +#94754 = VECTOR('',#94755,1.); +#94755 = DIRECTION('',(0.E+000,1.)); +#94756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94757 = PCURVE('',#94758,#94763); +#94758 = PLANE('',#94759); +#94759 = AXIS2_PLACEMENT_3D('',#94760,#94761,#94762); +#94760 = CARTESIAN_POINT('',(10.527847992439,1.35,0.75)); +#94761 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#94762 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#94763 = DEFINITIONAL_REPRESENTATION('',(#94764),#94768); +#94764 = LINE('',#94765,#94766); +#94765 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94766 = VECTOR('',#94767,1.); +#94767 = DIRECTION('',(4.440892098501E-016,1.)); +#94768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94769 = FACE_BOUND('',#94770,.T.); +#94770 = EDGE_LOOP('',(#94771,#94801,#94829,#94857)); +#94771 = ORIENTED_EDGE('',*,*,#94772,.T.); +#94772 = EDGE_CURVE('',#94773,#94775,#94777,.T.); +#94773 = VERTEX_POINT('',#94774); +#94774 = CARTESIAN_POINT('',(10.,1.85,0.75)); +#94775 = VERTEX_POINT('',#94776); +#94776 = CARTESIAN_POINT('',(10.,1.85,0.65)); +#94777 = SURFACE_CURVE('',#94778,(#94782,#94789),.PCURVE_S1.); +#94778 = LINE('',#94779,#94780); +#94779 = CARTESIAN_POINT('',(10.,1.85,0.65)); +#94780 = VECTOR('',#94781,1.); +#94781 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94782 = PCURVE('',#94664,#94783); +#94783 = DEFINITIONAL_REPRESENTATION('',(#94784),#94788); +#94784 = LINE('',#94785,#94786); +#94785 = CARTESIAN_POINT('',(-0.75,1.85)); +#94786 = VECTOR('',#94787,1.); +#94787 = DIRECTION('',(-1.,0.E+000)); +#94788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94789 = PCURVE('',#94790,#94795); +#94790 = PLANE('',#94791); +#94791 = AXIS2_PLACEMENT_3D('',#94792,#94793,#94794); +#94792 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); +#94793 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94794 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94795 = DEFINITIONAL_REPRESENTATION('',(#94796),#94800); +#94796 = LINE('',#94797,#94798); +#94797 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#94798 = VECTOR('',#94799,1.); +#94799 = DIRECTION('',(-1.,0.E+000)); +#94800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94801 = ORIENTED_EDGE('',*,*,#94802,.T.); +#94802 = EDGE_CURVE('',#94775,#94803,#94805,.T.); +#94803 = VERTEX_POINT('',#94804); +#94804 = CARTESIAN_POINT('',(10.,1.65,0.65)); +#94805 = SURFACE_CURVE('',#94806,(#94810,#94817),.PCURVE_S1.); +#94806 = LINE('',#94807,#94808); +#94807 = CARTESIAN_POINT('',(10.,1.85,0.65)); +#94808 = VECTOR('',#94809,1.); +#94809 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#94810 = PCURVE('',#94664,#94811); +#94811 = DEFINITIONAL_REPRESENTATION('',(#94812),#94816); +#94812 = LINE('',#94813,#94814); +#94813 = CARTESIAN_POINT('',(-0.75,1.85)); +#94814 = VECTOR('',#94815,1.); +#94815 = DIRECTION('',(0.E+000,-1.)); +#94816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94817 = PCURVE('',#94818,#94823); +#94818 = PLANE('',#94819); +#94819 = AXIS2_PLACEMENT_3D('',#94820,#94821,#94822); +#94820 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); +#94821 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#94822 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#94823 = DEFINITIONAL_REPRESENTATION('',(#94824),#94828); +#94824 = LINE('',#94825,#94826); +#94825 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94826 = VECTOR('',#94827,1.); +#94827 = DIRECTION('',(4.440892098501E-016,-1.)); +#94828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94829 = ORIENTED_EDGE('',*,*,#94830,.T.); +#94830 = EDGE_CURVE('',#94803,#94831,#94833,.T.); +#94831 = VERTEX_POINT('',#94832); +#94832 = CARTESIAN_POINT('',(10.,1.65,0.75)); +#94833 = SURFACE_CURVE('',#94834,(#94838,#94845),.PCURVE_S1.); +#94834 = LINE('',#94835,#94836); +#94835 = CARTESIAN_POINT('',(10.,1.65,0.65)); +#94836 = VECTOR('',#94837,1.); +#94837 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94838 = PCURVE('',#94664,#94839); +#94839 = DEFINITIONAL_REPRESENTATION('',(#94840),#94844); +#94840 = LINE('',#94841,#94842); +#94841 = CARTESIAN_POINT('',(-0.75,1.65)); +#94842 = VECTOR('',#94843,1.); +#94843 = DIRECTION('',(1.,0.E+000)); +#94844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94845 = PCURVE('',#94846,#94851); +#94846 = PLANE('',#94847); +#94847 = AXIS2_PLACEMENT_3D('',#94848,#94849,#94850); +#94848 = CARTESIAN_POINT('',(10.527847992439,1.65,0.65)); +#94849 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94850 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94851 = DEFINITIONAL_REPRESENTATION('',(#94852),#94856); +#94852 = LINE('',#94853,#94854); +#94853 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#94854 = VECTOR('',#94855,1.); +#94855 = DIRECTION('',(-1.,0.E+000)); +#94856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94857 = ORIENTED_EDGE('',*,*,#94858,.T.); +#94858 = EDGE_CURVE('',#94831,#94773,#94859,.T.); +#94859 = SURFACE_CURVE('',#94860,(#94864,#94871),.PCURVE_S1.); +#94860 = LINE('',#94861,#94862); +#94861 = CARTESIAN_POINT('',(10.,1.85,0.75)); +#94862 = VECTOR('',#94863,1.); +#94863 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#94864 = PCURVE('',#94664,#94865); +#94865 = DEFINITIONAL_REPRESENTATION('',(#94866),#94870); +#94866 = LINE('',#94867,#94868); +#94867 = CARTESIAN_POINT('',(-0.65,1.85)); +#94868 = VECTOR('',#94869,1.); +#94869 = DIRECTION('',(0.E+000,1.)); +#94870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94871 = PCURVE('',#94872,#94877); +#94872 = PLANE('',#94873); +#94873 = AXIS2_PLACEMENT_3D('',#94874,#94875,#94876); +#94874 = CARTESIAN_POINT('',(10.527847992439,1.85,0.75)); +#94875 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#94876 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#94877 = DEFINITIONAL_REPRESENTATION('',(#94878),#94882); +#94878 = LINE('',#94879,#94880); +#94879 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94880 = VECTOR('',#94881,1.); +#94881 = DIRECTION('',(4.440892098501E-016,1.)); +#94882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94883 = FACE_BOUND('',#94884,.T.); +#94884 = EDGE_LOOP('',(#94885,#94915,#94943,#94971)); +#94885 = ORIENTED_EDGE('',*,*,#94886,.T.); +#94886 = EDGE_CURVE('',#94887,#94889,#94891,.T.); +#94887 = VERTEX_POINT('',#94888); +#94888 = CARTESIAN_POINT('',(10.,2.35,0.75)); +#94889 = VERTEX_POINT('',#94890); +#94890 = CARTESIAN_POINT('',(10.,2.35,0.65)); +#94891 = SURFACE_CURVE('',#94892,(#94896,#94903),.PCURVE_S1.); +#94892 = LINE('',#94893,#94894); +#94893 = CARTESIAN_POINT('',(10.,2.35,0.65)); +#94894 = VECTOR('',#94895,1.); +#94895 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94896 = PCURVE('',#94664,#94897); +#94897 = DEFINITIONAL_REPRESENTATION('',(#94898),#94902); +#94898 = LINE('',#94899,#94900); +#94899 = CARTESIAN_POINT('',(-0.75,2.35)); +#94900 = VECTOR('',#94901,1.); +#94901 = DIRECTION('',(-1.,0.E+000)); +#94902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94903 = PCURVE('',#94904,#94909); +#94904 = PLANE('',#94905); +#94905 = AXIS2_PLACEMENT_3D('',#94906,#94907,#94908); +#94906 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); +#94907 = DIRECTION('',(0.E+000,1.,0.E+000)); +#94908 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94909 = DEFINITIONAL_REPRESENTATION('',(#94910),#94914); +#94910 = LINE('',#94911,#94912); +#94911 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#94912 = VECTOR('',#94913,1.); +#94913 = DIRECTION('',(-1.,0.E+000)); +#94914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94915 = ORIENTED_EDGE('',*,*,#94916,.T.); +#94916 = EDGE_CURVE('',#94889,#94917,#94919,.T.); +#94917 = VERTEX_POINT('',#94918); +#94918 = CARTESIAN_POINT('',(10.,2.15,0.65)); +#94919 = SURFACE_CURVE('',#94920,(#94924,#94931),.PCURVE_S1.); +#94920 = LINE('',#94921,#94922); +#94921 = CARTESIAN_POINT('',(10.,2.35,0.65)); +#94922 = VECTOR('',#94923,1.); +#94923 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#94924 = PCURVE('',#94664,#94925); +#94925 = DEFINITIONAL_REPRESENTATION('',(#94926),#94930); +#94926 = LINE('',#94927,#94928); +#94927 = CARTESIAN_POINT('',(-0.75,2.35)); +#94928 = VECTOR('',#94929,1.); +#94929 = DIRECTION('',(0.E+000,-1.)); +#94930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94931 = PCURVE('',#94932,#94937); +#94932 = PLANE('',#94933); +#94933 = AXIS2_PLACEMENT_3D('',#94934,#94935,#94936); +#94934 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); +#94935 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#94936 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#94937 = DEFINITIONAL_REPRESENTATION('',(#94938),#94942); +#94938 = LINE('',#94939,#94940); +#94939 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#94940 = VECTOR('',#94941,1.); +#94941 = DIRECTION('',(4.440892098501E-016,-1.)); +#94942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94943 = ORIENTED_EDGE('',*,*,#94944,.T.); +#94944 = EDGE_CURVE('',#94917,#94945,#94947,.T.); +#94945 = VERTEX_POINT('',#94946); +#94946 = CARTESIAN_POINT('',(10.,2.15,0.75)); +#94947 = SURFACE_CURVE('',#94948,(#94952,#94959),.PCURVE_S1.); +#94948 = LINE('',#94949,#94950); +#94949 = CARTESIAN_POINT('',(10.,2.15,0.65)); +#94950 = VECTOR('',#94951,1.); +#94951 = DIRECTION('',(0.E+000,0.E+000,1.)); +#94952 = PCURVE('',#94664,#94953); +#94953 = DEFINITIONAL_REPRESENTATION('',(#94954),#94958); +#94954 = LINE('',#94955,#94956); +#94955 = CARTESIAN_POINT('',(-0.75,2.15)); +#94956 = VECTOR('',#94957,1.); +#94957 = DIRECTION('',(1.,0.E+000)); +#94958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94959 = PCURVE('',#94960,#94965); +#94960 = PLANE('',#94961); +#94961 = AXIS2_PLACEMENT_3D('',#94962,#94963,#94964); +#94962 = CARTESIAN_POINT('',(10.527847992439,2.15,0.65)); +#94963 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#94964 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#94965 = DEFINITIONAL_REPRESENTATION('',(#94966),#94970); +#94966 = LINE('',#94967,#94968); +#94967 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#94968 = VECTOR('',#94969,1.); +#94969 = DIRECTION('',(-1.,0.E+000)); +#94970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94971 = ORIENTED_EDGE('',*,*,#94972,.T.); +#94972 = EDGE_CURVE('',#94945,#94887,#94973,.T.); +#94973 = SURFACE_CURVE('',#94974,(#94978,#94985),.PCURVE_S1.); +#94974 = LINE('',#94975,#94976); +#94975 = CARTESIAN_POINT('',(10.,2.35,0.75)); +#94976 = VECTOR('',#94977,1.); +#94977 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#94978 = PCURVE('',#94664,#94979); +#94979 = DEFINITIONAL_REPRESENTATION('',(#94980),#94984); +#94980 = LINE('',#94981,#94982); +#94981 = CARTESIAN_POINT('',(-0.65,2.35)); +#94982 = VECTOR('',#94983,1.); +#94983 = DIRECTION('',(0.E+000,1.)); +#94984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94985 = PCURVE('',#94986,#94991); +#94986 = PLANE('',#94987); +#94987 = AXIS2_PLACEMENT_3D('',#94988,#94989,#94990); +#94988 = CARTESIAN_POINT('',(10.527847992439,2.35,0.75)); +#94989 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#94990 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#94991 = DEFINITIONAL_REPRESENTATION('',(#94992),#94996); +#94992 = LINE('',#94993,#94994); +#94993 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#94994 = VECTOR('',#94995,1.); +#94995 = DIRECTION('',(4.440892098501E-016,1.)); +#94996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#94997 = FACE_BOUND('',#94998,.T.); +#94998 = EDGE_LOOP('',(#94999,#95029,#95057,#95085)); +#94999 = ORIENTED_EDGE('',*,*,#95000,.T.); +#95000 = EDGE_CURVE('',#95001,#95003,#95005,.T.); +#95001 = VERTEX_POINT('',#95002); +#95002 = CARTESIAN_POINT('',(10.,2.85,0.75)); +#95003 = VERTEX_POINT('',#95004); +#95004 = CARTESIAN_POINT('',(10.,2.85,0.65)); +#95005 = SURFACE_CURVE('',#95006,(#95010,#95017),.PCURVE_S1.); +#95006 = LINE('',#95007,#95008); +#95007 = CARTESIAN_POINT('',(10.,2.85,0.65)); +#95008 = VECTOR('',#95009,1.); +#95009 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95010 = PCURVE('',#94664,#95011); +#95011 = DEFINITIONAL_REPRESENTATION('',(#95012),#95016); +#95012 = LINE('',#95013,#95014); +#95013 = CARTESIAN_POINT('',(-0.75,2.85)); +#95014 = VECTOR('',#95015,1.); +#95015 = DIRECTION('',(-1.,0.E+000)); +#95016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95017 = PCURVE('',#95018,#95023); +#95018 = PLANE('',#95019); +#95019 = AXIS2_PLACEMENT_3D('',#95020,#95021,#95022); +#95020 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); +#95021 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95022 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95023 = DEFINITIONAL_REPRESENTATION('',(#95024),#95028); +#95024 = LINE('',#95025,#95026); +#95025 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95026 = VECTOR('',#95027,1.); +#95027 = DIRECTION('',(-1.,0.E+000)); +#95028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95029 = ORIENTED_EDGE('',*,*,#95030,.T.); +#95030 = EDGE_CURVE('',#95003,#95031,#95033,.T.); +#95031 = VERTEX_POINT('',#95032); +#95032 = CARTESIAN_POINT('',(10.,2.65,0.65)); +#95033 = SURFACE_CURVE('',#95034,(#95038,#95045),.PCURVE_S1.); +#95034 = LINE('',#95035,#95036); +#95035 = CARTESIAN_POINT('',(10.,2.85,0.65)); +#95036 = VECTOR('',#95037,1.); +#95037 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95038 = PCURVE('',#94664,#95039); +#95039 = DEFINITIONAL_REPRESENTATION('',(#95040),#95044); +#95040 = LINE('',#95041,#95042); +#95041 = CARTESIAN_POINT('',(-0.75,2.85)); +#95042 = VECTOR('',#95043,1.); +#95043 = DIRECTION('',(0.E+000,-1.)); +#95044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95045 = PCURVE('',#95046,#95051); +#95046 = PLANE('',#95047); +#95047 = AXIS2_PLACEMENT_3D('',#95048,#95049,#95050); +#95048 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); +#95049 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95050 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95051 = DEFINITIONAL_REPRESENTATION('',(#95052),#95056); +#95052 = LINE('',#95053,#95054); +#95053 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95054 = VECTOR('',#95055,1.); +#95055 = DIRECTION('',(4.440892098501E-016,-1.)); +#95056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95057 = ORIENTED_EDGE('',*,*,#95058,.T.); +#95058 = EDGE_CURVE('',#95031,#95059,#95061,.T.); +#95059 = VERTEX_POINT('',#95060); +#95060 = CARTESIAN_POINT('',(10.,2.65,0.75)); +#95061 = SURFACE_CURVE('',#95062,(#95066,#95073),.PCURVE_S1.); +#95062 = LINE('',#95063,#95064); +#95063 = CARTESIAN_POINT('',(10.,2.65,0.65)); +#95064 = VECTOR('',#95065,1.); +#95065 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95066 = PCURVE('',#94664,#95067); +#95067 = DEFINITIONAL_REPRESENTATION('',(#95068),#95072); +#95068 = LINE('',#95069,#95070); +#95069 = CARTESIAN_POINT('',(-0.75,2.65)); +#95070 = VECTOR('',#95071,1.); +#95071 = DIRECTION('',(1.,0.E+000)); +#95072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95073 = PCURVE('',#95074,#95079); +#95074 = PLANE('',#95075); +#95075 = AXIS2_PLACEMENT_3D('',#95076,#95077,#95078); +#95076 = CARTESIAN_POINT('',(10.527847992439,2.65,0.65)); +#95077 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95078 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95079 = DEFINITIONAL_REPRESENTATION('',(#95080),#95084); +#95080 = LINE('',#95081,#95082); +#95081 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95082 = VECTOR('',#95083,1.); +#95083 = DIRECTION('',(-1.,0.E+000)); +#95084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95085 = ORIENTED_EDGE('',*,*,#95086,.T.); +#95086 = EDGE_CURVE('',#95059,#95001,#95087,.T.); +#95087 = SURFACE_CURVE('',#95088,(#95092,#95099),.PCURVE_S1.); +#95088 = LINE('',#95089,#95090); +#95089 = CARTESIAN_POINT('',(10.,2.85,0.75)); +#95090 = VECTOR('',#95091,1.); +#95091 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95092 = PCURVE('',#94664,#95093); +#95093 = DEFINITIONAL_REPRESENTATION('',(#95094),#95098); +#95094 = LINE('',#95095,#95096); +#95095 = CARTESIAN_POINT('',(-0.65,2.85)); +#95096 = VECTOR('',#95097,1.); +#95097 = DIRECTION('',(0.E+000,1.)); +#95098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95099 = PCURVE('',#95100,#95105); +#95100 = PLANE('',#95101); +#95101 = AXIS2_PLACEMENT_3D('',#95102,#95103,#95104); +#95102 = CARTESIAN_POINT('',(10.527847992439,2.85,0.75)); +#95103 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95104 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95105 = DEFINITIONAL_REPRESENTATION('',(#95106),#95110); +#95106 = LINE('',#95107,#95108); +#95107 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95108 = VECTOR('',#95109,1.); +#95109 = DIRECTION('',(4.440892098501E-016,1.)); +#95110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95111 = FACE_BOUND('',#95112,.T.); +#95112 = EDGE_LOOP('',(#95113,#95143,#95171,#95199)); +#95113 = ORIENTED_EDGE('',*,*,#95114,.T.); +#95114 = EDGE_CURVE('',#95115,#95117,#95119,.T.); +#95115 = VERTEX_POINT('',#95116); +#95116 = CARTESIAN_POINT('',(10.,3.35,0.75)); +#95117 = VERTEX_POINT('',#95118); +#95118 = CARTESIAN_POINT('',(10.,3.35,0.65)); +#95119 = SURFACE_CURVE('',#95120,(#95124,#95131),.PCURVE_S1.); +#95120 = LINE('',#95121,#95122); +#95121 = CARTESIAN_POINT('',(10.,3.35,0.65)); +#95122 = VECTOR('',#95123,1.); +#95123 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95124 = PCURVE('',#94664,#95125); +#95125 = DEFINITIONAL_REPRESENTATION('',(#95126),#95130); +#95126 = LINE('',#95127,#95128); +#95127 = CARTESIAN_POINT('',(-0.75,3.35)); +#95128 = VECTOR('',#95129,1.); +#95129 = DIRECTION('',(-1.,0.E+000)); +#95130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95131 = PCURVE('',#95132,#95137); +#95132 = PLANE('',#95133); +#95133 = AXIS2_PLACEMENT_3D('',#95134,#95135,#95136); +#95134 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); +#95135 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95136 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95137 = DEFINITIONAL_REPRESENTATION('',(#95138),#95142); +#95138 = LINE('',#95139,#95140); +#95139 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95140 = VECTOR('',#95141,1.); +#95141 = DIRECTION('',(-1.,0.E+000)); +#95142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95143 = ORIENTED_EDGE('',*,*,#95144,.T.); +#95144 = EDGE_CURVE('',#95117,#95145,#95147,.T.); +#95145 = VERTEX_POINT('',#95146); +#95146 = CARTESIAN_POINT('',(10.,3.15,0.65)); +#95147 = SURFACE_CURVE('',#95148,(#95152,#95159),.PCURVE_S1.); +#95148 = LINE('',#95149,#95150); +#95149 = CARTESIAN_POINT('',(10.,3.35,0.65)); +#95150 = VECTOR('',#95151,1.); +#95151 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95152 = PCURVE('',#94664,#95153); +#95153 = DEFINITIONAL_REPRESENTATION('',(#95154),#95158); +#95154 = LINE('',#95155,#95156); +#95155 = CARTESIAN_POINT('',(-0.75,3.35)); +#95156 = VECTOR('',#95157,1.); +#95157 = DIRECTION('',(0.E+000,-1.)); +#95158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95159 = PCURVE('',#95160,#95165); +#95160 = PLANE('',#95161); +#95161 = AXIS2_PLACEMENT_3D('',#95162,#95163,#95164); +#95162 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); +#95163 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95164 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95165 = DEFINITIONAL_REPRESENTATION('',(#95166),#95170); +#95166 = LINE('',#95167,#95168); +#95167 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95168 = VECTOR('',#95169,1.); +#95169 = DIRECTION('',(4.440892098501E-016,-1.)); +#95170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95171 = ORIENTED_EDGE('',*,*,#95172,.T.); +#95172 = EDGE_CURVE('',#95145,#95173,#95175,.T.); +#95173 = VERTEX_POINT('',#95174); +#95174 = CARTESIAN_POINT('',(10.,3.15,0.75)); +#95175 = SURFACE_CURVE('',#95176,(#95180,#95187),.PCURVE_S1.); +#95176 = LINE('',#95177,#95178); +#95177 = CARTESIAN_POINT('',(10.,3.15,0.65)); +#95178 = VECTOR('',#95179,1.); +#95179 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95180 = PCURVE('',#94664,#95181); +#95181 = DEFINITIONAL_REPRESENTATION('',(#95182),#95186); +#95182 = LINE('',#95183,#95184); +#95183 = CARTESIAN_POINT('',(-0.75,3.15)); +#95184 = VECTOR('',#95185,1.); +#95185 = DIRECTION('',(1.,0.E+000)); +#95186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95187 = PCURVE('',#95188,#95193); +#95188 = PLANE('',#95189); +#95189 = AXIS2_PLACEMENT_3D('',#95190,#95191,#95192); +#95190 = CARTESIAN_POINT('',(10.527847992439,3.15,0.65)); +#95191 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95192 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95193 = DEFINITIONAL_REPRESENTATION('',(#95194),#95198); +#95194 = LINE('',#95195,#95196); +#95195 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95196 = VECTOR('',#95197,1.); +#95197 = DIRECTION('',(-1.,0.E+000)); +#95198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95199 = ORIENTED_EDGE('',*,*,#95200,.T.); +#95200 = EDGE_CURVE('',#95173,#95115,#95201,.T.); +#95201 = SURFACE_CURVE('',#95202,(#95206,#95213),.PCURVE_S1.); +#95202 = LINE('',#95203,#95204); +#95203 = CARTESIAN_POINT('',(10.,3.35,0.75)); +#95204 = VECTOR('',#95205,1.); +#95205 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95206 = PCURVE('',#94664,#95207); +#95207 = DEFINITIONAL_REPRESENTATION('',(#95208),#95212); +#95208 = LINE('',#95209,#95210); +#95209 = CARTESIAN_POINT('',(-0.65,3.35)); +#95210 = VECTOR('',#95211,1.); +#95211 = DIRECTION('',(0.E+000,1.)); +#95212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95213 = PCURVE('',#95214,#95219); +#95214 = PLANE('',#95215); +#95215 = AXIS2_PLACEMENT_3D('',#95216,#95217,#95218); +#95216 = CARTESIAN_POINT('',(10.527847992439,3.35,0.75)); +#95217 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95218 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95219 = DEFINITIONAL_REPRESENTATION('',(#95220),#95224); +#95220 = LINE('',#95221,#95222); +#95221 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95222 = VECTOR('',#95223,1.); +#95223 = DIRECTION('',(4.440892098501E-016,1.)); +#95224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95225 = FACE_BOUND('',#95226,.T.); +#95226 = EDGE_LOOP('',(#95227,#95257,#95285,#95313)); +#95227 = ORIENTED_EDGE('',*,*,#95228,.T.); +#95228 = EDGE_CURVE('',#95229,#95231,#95233,.T.); +#95229 = VERTEX_POINT('',#95230); +#95230 = CARTESIAN_POINT('',(10.,3.85,0.75)); +#95231 = VERTEX_POINT('',#95232); +#95232 = CARTESIAN_POINT('',(10.,3.85,0.65)); +#95233 = SURFACE_CURVE('',#95234,(#95238,#95245),.PCURVE_S1.); +#95234 = LINE('',#95235,#95236); +#95235 = CARTESIAN_POINT('',(10.,3.85,0.65)); +#95236 = VECTOR('',#95237,1.); +#95237 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95238 = PCURVE('',#94664,#95239); +#95239 = DEFINITIONAL_REPRESENTATION('',(#95240),#95244); +#95240 = LINE('',#95241,#95242); +#95241 = CARTESIAN_POINT('',(-0.75,3.85)); +#95242 = VECTOR('',#95243,1.); +#95243 = DIRECTION('',(-1.,0.E+000)); +#95244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95245 = PCURVE('',#95246,#95251); +#95246 = PLANE('',#95247); +#95247 = AXIS2_PLACEMENT_3D('',#95248,#95249,#95250); +#95248 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); +#95249 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95250 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95251 = DEFINITIONAL_REPRESENTATION('',(#95252),#95256); +#95252 = LINE('',#95253,#95254); +#95253 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95254 = VECTOR('',#95255,1.); +#95255 = DIRECTION('',(-1.,0.E+000)); +#95256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95257 = ORIENTED_EDGE('',*,*,#95258,.T.); +#95258 = EDGE_CURVE('',#95231,#95259,#95261,.T.); +#95259 = VERTEX_POINT('',#95260); +#95260 = CARTESIAN_POINT('',(10.,3.65,0.65)); +#95261 = SURFACE_CURVE('',#95262,(#95266,#95273),.PCURVE_S1.); +#95262 = LINE('',#95263,#95264); +#95263 = CARTESIAN_POINT('',(10.,3.85,0.65)); +#95264 = VECTOR('',#95265,1.); +#95265 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95266 = PCURVE('',#94664,#95267); +#95267 = DEFINITIONAL_REPRESENTATION('',(#95268),#95272); +#95268 = LINE('',#95269,#95270); +#95269 = CARTESIAN_POINT('',(-0.75,3.85)); +#95270 = VECTOR('',#95271,1.); +#95271 = DIRECTION('',(0.E+000,-1.)); +#95272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95273 = PCURVE('',#95274,#95279); +#95274 = PLANE('',#95275); +#95275 = AXIS2_PLACEMENT_3D('',#95276,#95277,#95278); +#95276 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); +#95277 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95278 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95279 = DEFINITIONAL_REPRESENTATION('',(#95280),#95284); +#95280 = LINE('',#95281,#95282); +#95281 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95282 = VECTOR('',#95283,1.); +#95283 = DIRECTION('',(4.440892098501E-016,-1.)); +#95284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95285 = ORIENTED_EDGE('',*,*,#95286,.T.); +#95286 = EDGE_CURVE('',#95259,#95287,#95289,.T.); +#95287 = VERTEX_POINT('',#95288); +#95288 = CARTESIAN_POINT('',(10.,3.65,0.75)); +#95289 = SURFACE_CURVE('',#95290,(#95294,#95301),.PCURVE_S1.); +#95290 = LINE('',#95291,#95292); +#95291 = CARTESIAN_POINT('',(10.,3.65,0.65)); +#95292 = VECTOR('',#95293,1.); +#95293 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95294 = PCURVE('',#94664,#95295); +#95295 = DEFINITIONAL_REPRESENTATION('',(#95296),#95300); +#95296 = LINE('',#95297,#95298); +#95297 = CARTESIAN_POINT('',(-0.75,3.65)); +#95298 = VECTOR('',#95299,1.); +#95299 = DIRECTION('',(1.,0.E+000)); +#95300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95301 = PCURVE('',#95302,#95307); +#95302 = PLANE('',#95303); +#95303 = AXIS2_PLACEMENT_3D('',#95304,#95305,#95306); +#95304 = CARTESIAN_POINT('',(10.527847992439,3.65,0.65)); +#95305 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95306 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95307 = DEFINITIONAL_REPRESENTATION('',(#95308),#95312); +#95308 = LINE('',#95309,#95310); +#95309 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95310 = VECTOR('',#95311,1.); +#95311 = DIRECTION('',(-1.,0.E+000)); +#95312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95313 = ORIENTED_EDGE('',*,*,#95314,.T.); +#95314 = EDGE_CURVE('',#95287,#95229,#95315,.T.); +#95315 = SURFACE_CURVE('',#95316,(#95320,#95327),.PCURVE_S1.); +#95316 = LINE('',#95317,#95318); +#95317 = CARTESIAN_POINT('',(10.,3.85,0.75)); +#95318 = VECTOR('',#95319,1.); +#95319 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95320 = PCURVE('',#94664,#95321); +#95321 = DEFINITIONAL_REPRESENTATION('',(#95322),#95326); +#95322 = LINE('',#95323,#95324); +#95323 = CARTESIAN_POINT('',(-0.65,3.85)); +#95324 = VECTOR('',#95325,1.); +#95325 = DIRECTION('',(0.E+000,1.)); +#95326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95327 = PCURVE('',#95328,#95333); +#95328 = PLANE('',#95329); +#95329 = AXIS2_PLACEMENT_3D('',#95330,#95331,#95332); +#95330 = CARTESIAN_POINT('',(10.527847992439,3.85,0.75)); +#95331 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95332 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95333 = DEFINITIONAL_REPRESENTATION('',(#95334),#95338); +#95334 = LINE('',#95335,#95336); +#95335 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95336 = VECTOR('',#95337,1.); +#95337 = DIRECTION('',(4.440892098501E-016,1.)); +#95338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95339 = FACE_BOUND('',#95340,.T.); +#95340 = EDGE_LOOP('',(#95341,#95371,#95399,#95427)); +#95341 = ORIENTED_EDGE('',*,*,#95342,.T.); +#95342 = EDGE_CURVE('',#95343,#95345,#95347,.T.); +#95343 = VERTEX_POINT('',#95344); +#95344 = CARTESIAN_POINT('',(10.,4.35,0.75)); +#95345 = VERTEX_POINT('',#95346); +#95346 = CARTESIAN_POINT('',(10.,4.35,0.65)); +#95347 = SURFACE_CURVE('',#95348,(#95352,#95359),.PCURVE_S1.); +#95348 = LINE('',#95349,#95350); +#95349 = CARTESIAN_POINT('',(10.,4.35,0.65)); +#95350 = VECTOR('',#95351,1.); +#95351 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95352 = PCURVE('',#94664,#95353); +#95353 = DEFINITIONAL_REPRESENTATION('',(#95354),#95358); +#95354 = LINE('',#95355,#95356); +#95355 = CARTESIAN_POINT('',(-0.75,4.35)); +#95356 = VECTOR('',#95357,1.); +#95357 = DIRECTION('',(-1.,0.E+000)); +#95358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95359 = PCURVE('',#95360,#95365); +#95360 = PLANE('',#95361); +#95361 = AXIS2_PLACEMENT_3D('',#95362,#95363,#95364); +#95362 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); +#95363 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95364 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95365 = DEFINITIONAL_REPRESENTATION('',(#95366),#95370); +#95366 = LINE('',#95367,#95368); +#95367 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95368 = VECTOR('',#95369,1.); +#95369 = DIRECTION('',(-1.,0.E+000)); +#95370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95371 = ORIENTED_EDGE('',*,*,#95372,.T.); +#95372 = EDGE_CURVE('',#95345,#95373,#95375,.T.); +#95373 = VERTEX_POINT('',#95374); +#95374 = CARTESIAN_POINT('',(10.,4.15,0.65)); +#95375 = SURFACE_CURVE('',#95376,(#95380,#95387),.PCURVE_S1.); +#95376 = LINE('',#95377,#95378); +#95377 = CARTESIAN_POINT('',(10.,4.35,0.65)); +#95378 = VECTOR('',#95379,1.); +#95379 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95380 = PCURVE('',#94664,#95381); +#95381 = DEFINITIONAL_REPRESENTATION('',(#95382),#95386); +#95382 = LINE('',#95383,#95384); +#95383 = CARTESIAN_POINT('',(-0.75,4.35)); +#95384 = VECTOR('',#95385,1.); +#95385 = DIRECTION('',(0.E+000,-1.)); +#95386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95387 = PCURVE('',#95388,#95393); +#95388 = PLANE('',#95389); +#95389 = AXIS2_PLACEMENT_3D('',#95390,#95391,#95392); +#95390 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); +#95391 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95392 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95393 = DEFINITIONAL_REPRESENTATION('',(#95394),#95398); +#95394 = LINE('',#95395,#95396); +#95395 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95396 = VECTOR('',#95397,1.); +#95397 = DIRECTION('',(4.440892098501E-016,-1.)); +#95398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95399 = ORIENTED_EDGE('',*,*,#95400,.T.); +#95400 = EDGE_CURVE('',#95373,#95401,#95403,.T.); +#95401 = VERTEX_POINT('',#95402); +#95402 = CARTESIAN_POINT('',(10.,4.15,0.75)); +#95403 = SURFACE_CURVE('',#95404,(#95408,#95415),.PCURVE_S1.); +#95404 = LINE('',#95405,#95406); +#95405 = CARTESIAN_POINT('',(10.,4.15,0.65)); +#95406 = VECTOR('',#95407,1.); +#95407 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95408 = PCURVE('',#94664,#95409); +#95409 = DEFINITIONAL_REPRESENTATION('',(#95410),#95414); +#95410 = LINE('',#95411,#95412); +#95411 = CARTESIAN_POINT('',(-0.75,4.15)); +#95412 = VECTOR('',#95413,1.); +#95413 = DIRECTION('',(1.,0.E+000)); +#95414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95415 = PCURVE('',#95416,#95421); +#95416 = PLANE('',#95417); +#95417 = AXIS2_PLACEMENT_3D('',#95418,#95419,#95420); +#95418 = CARTESIAN_POINT('',(10.527847992439,4.15,0.65)); +#95419 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95420 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95421 = DEFINITIONAL_REPRESENTATION('',(#95422),#95426); +#95422 = LINE('',#95423,#95424); +#95423 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95424 = VECTOR('',#95425,1.); +#95425 = DIRECTION('',(-1.,0.E+000)); +#95426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95427 = ORIENTED_EDGE('',*,*,#95428,.T.); +#95428 = EDGE_CURVE('',#95401,#95343,#95429,.T.); +#95429 = SURFACE_CURVE('',#95430,(#95434,#95441),.PCURVE_S1.); +#95430 = LINE('',#95431,#95432); +#95431 = CARTESIAN_POINT('',(10.,4.35,0.75)); +#95432 = VECTOR('',#95433,1.); +#95433 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95434 = PCURVE('',#94664,#95435); +#95435 = DEFINITIONAL_REPRESENTATION('',(#95436),#95440); +#95436 = LINE('',#95437,#95438); +#95437 = CARTESIAN_POINT('',(-0.65,4.35)); +#95438 = VECTOR('',#95439,1.); +#95439 = DIRECTION('',(0.E+000,1.)); +#95440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95441 = PCURVE('',#95442,#95447); +#95442 = PLANE('',#95443); +#95443 = AXIS2_PLACEMENT_3D('',#95444,#95445,#95446); +#95444 = CARTESIAN_POINT('',(10.527847992439,4.35,0.75)); +#95445 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95446 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95447 = DEFINITIONAL_REPRESENTATION('',(#95448),#95452); +#95448 = LINE('',#95449,#95450); +#95449 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95450 = VECTOR('',#95451,1.); +#95451 = DIRECTION('',(4.440892098501E-016,1.)); +#95452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95453 = FACE_BOUND('',#95454,.T.); +#95454 = EDGE_LOOP('',(#95455,#95485,#95513,#95541)); +#95455 = ORIENTED_EDGE('',*,*,#95456,.T.); +#95456 = EDGE_CURVE('',#95457,#95459,#95461,.T.); +#95457 = VERTEX_POINT('',#95458); +#95458 = CARTESIAN_POINT('',(10.,5.35,0.75)); +#95459 = VERTEX_POINT('',#95460); +#95460 = CARTESIAN_POINT('',(10.,5.35,0.65)); +#95461 = SURFACE_CURVE('',#95462,(#95466,#95473),.PCURVE_S1.); +#95462 = LINE('',#95463,#95464); +#95463 = CARTESIAN_POINT('',(10.,5.35,0.65)); +#95464 = VECTOR('',#95465,1.); +#95465 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95466 = PCURVE('',#94664,#95467); +#95467 = DEFINITIONAL_REPRESENTATION('',(#95468),#95472); +#95468 = LINE('',#95469,#95470); +#95469 = CARTESIAN_POINT('',(-0.75,5.35)); +#95470 = VECTOR('',#95471,1.); +#95471 = DIRECTION('',(-1.,0.E+000)); +#95472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95473 = PCURVE('',#95474,#95479); +#95474 = PLANE('',#95475); +#95475 = AXIS2_PLACEMENT_3D('',#95476,#95477,#95478); +#95476 = CARTESIAN_POINT('',(10.527847992439,5.35,0.65)); +#95477 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95478 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95479 = DEFINITIONAL_REPRESENTATION('',(#95480),#95484); +#95480 = LINE('',#95481,#95482); +#95481 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95482 = VECTOR('',#95483,1.); +#95483 = DIRECTION('',(-1.,0.E+000)); +#95484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95485 = ORIENTED_EDGE('',*,*,#95486,.T.); +#95486 = EDGE_CURVE('',#95459,#95487,#95489,.T.); +#95487 = VERTEX_POINT('',#95488); +#95488 = CARTESIAN_POINT('',(10.,5.15,0.65)); +#95489 = SURFACE_CURVE('',#95490,(#95494,#95501),.PCURVE_S1.); +#95490 = LINE('',#95491,#95492); +#95491 = CARTESIAN_POINT('',(10.,5.15,0.65)); +#95492 = VECTOR('',#95493,1.); +#95493 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95494 = PCURVE('',#94664,#95495); +#95495 = DEFINITIONAL_REPRESENTATION('',(#95496),#95500); +#95496 = LINE('',#95497,#95498); +#95497 = CARTESIAN_POINT('',(-0.75,5.15)); +#95498 = VECTOR('',#95499,1.); +#95499 = DIRECTION('',(0.E+000,-1.)); +#95500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95501 = PCURVE('',#95502,#95507); +#95502 = PLANE('',#95503); +#95503 = AXIS2_PLACEMENT_3D('',#95504,#95505,#95506); +#95504 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); +#95505 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95506 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95507 = DEFINITIONAL_REPRESENTATION('',(#95508),#95512); +#95508 = LINE('',#95509,#95510); +#95509 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95510 = VECTOR('',#95511,1.); +#95511 = DIRECTION('',(4.440892098501E-016,-1.)); +#95512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95513 = ORIENTED_EDGE('',*,*,#95514,.T.); +#95514 = EDGE_CURVE('',#95487,#95515,#95517,.T.); +#95515 = VERTEX_POINT('',#95516); +#95516 = CARTESIAN_POINT('',(10.,5.15,0.75)); +#95517 = SURFACE_CURVE('',#95518,(#95522,#95529),.PCURVE_S1.); +#95518 = LINE('',#95519,#95520); +#95519 = CARTESIAN_POINT('',(10.,5.15,0.65)); +#95520 = VECTOR('',#95521,1.); +#95521 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95522 = PCURVE('',#94664,#95523); +#95523 = DEFINITIONAL_REPRESENTATION('',(#95524),#95528); +#95524 = LINE('',#95525,#95526); +#95525 = CARTESIAN_POINT('',(-0.75,5.15)); +#95526 = VECTOR('',#95527,1.); +#95527 = DIRECTION('',(1.,0.E+000)); +#95528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95529 = PCURVE('',#95530,#95535); +#95530 = PLANE('',#95531); +#95531 = AXIS2_PLACEMENT_3D('',#95532,#95533,#95534); +#95532 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); +#95533 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95534 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95535 = DEFINITIONAL_REPRESENTATION('',(#95536),#95540); +#95536 = LINE('',#95537,#95538); +#95537 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95538 = VECTOR('',#95539,1.); +#95539 = DIRECTION('',(-1.,0.E+000)); +#95540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95541 = ORIENTED_EDGE('',*,*,#95542,.T.); +#95542 = EDGE_CURVE('',#95515,#95457,#95543,.T.); +#95543 = SURFACE_CURVE('',#95544,(#95548,#95555),.PCURVE_S1.); +#95544 = LINE('',#95545,#95546); +#95545 = CARTESIAN_POINT('',(10.,5.15,0.75)); +#95546 = VECTOR('',#95547,1.); +#95547 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95548 = PCURVE('',#94664,#95549); +#95549 = DEFINITIONAL_REPRESENTATION('',(#95550),#95554); +#95550 = LINE('',#95551,#95552); +#95551 = CARTESIAN_POINT('',(-0.65,5.15)); +#95552 = VECTOR('',#95553,1.); +#95553 = DIRECTION('',(0.E+000,1.)); +#95554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95555 = PCURVE('',#95556,#95561); +#95556 = PLANE('',#95557); +#95557 = AXIS2_PLACEMENT_3D('',#95558,#95559,#95560); +#95558 = CARTESIAN_POINT('',(10.527847992439,5.15,0.75)); +#95559 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95560 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95561 = DEFINITIONAL_REPRESENTATION('',(#95562),#95566); +#95562 = LINE('',#95563,#95564); +#95563 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95564 = VECTOR('',#95565,1.); +#95565 = DIRECTION('',(4.440892098501E-016,1.)); +#95566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95567 = FACE_BOUND('',#95568,.T.); +#95568 = EDGE_LOOP('',(#95569,#95599,#95627,#95655)); +#95569 = ORIENTED_EDGE('',*,*,#95570,.T.); +#95570 = EDGE_CURVE('',#95571,#95573,#95575,.T.); +#95571 = VERTEX_POINT('',#95572); +#95572 = CARTESIAN_POINT('',(10.,5.85,0.75)); +#95573 = VERTEX_POINT('',#95574); +#95574 = CARTESIAN_POINT('',(10.,5.85,0.65)); +#95575 = SURFACE_CURVE('',#95576,(#95580,#95587),.PCURVE_S1.); +#95576 = LINE('',#95577,#95578); +#95577 = CARTESIAN_POINT('',(10.,5.85,0.65)); +#95578 = VECTOR('',#95579,1.); +#95579 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95580 = PCURVE('',#94664,#95581); +#95581 = DEFINITIONAL_REPRESENTATION('',(#95582),#95586); +#95582 = LINE('',#95583,#95584); +#95583 = CARTESIAN_POINT('',(-0.75,5.85)); +#95584 = VECTOR('',#95585,1.); +#95585 = DIRECTION('',(-1.,0.E+000)); +#95586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95587 = PCURVE('',#95588,#95593); +#95588 = PLANE('',#95589); +#95589 = AXIS2_PLACEMENT_3D('',#95590,#95591,#95592); +#95590 = CARTESIAN_POINT('',(10.527847992439,5.85,0.65)); +#95591 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95592 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95593 = DEFINITIONAL_REPRESENTATION('',(#95594),#95598); +#95594 = LINE('',#95595,#95596); +#95595 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95596 = VECTOR('',#95597,1.); +#95597 = DIRECTION('',(-1.,0.E+000)); +#95598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95599 = ORIENTED_EDGE('',*,*,#95600,.T.); +#95600 = EDGE_CURVE('',#95573,#95601,#95603,.T.); +#95601 = VERTEX_POINT('',#95602); +#95602 = CARTESIAN_POINT('',(10.,5.65,0.65)); +#95603 = SURFACE_CURVE('',#95604,(#95608,#95615),.PCURVE_S1.); +#95604 = LINE('',#95605,#95606); +#95605 = CARTESIAN_POINT('',(10.,5.65,0.65)); +#95606 = VECTOR('',#95607,1.); +#95607 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95608 = PCURVE('',#94664,#95609); +#95609 = DEFINITIONAL_REPRESENTATION('',(#95610),#95614); +#95610 = LINE('',#95611,#95612); +#95611 = CARTESIAN_POINT('',(-0.75,5.65)); +#95612 = VECTOR('',#95613,1.); +#95613 = DIRECTION('',(0.E+000,-1.)); +#95614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95615 = PCURVE('',#95616,#95621); +#95616 = PLANE('',#95617); +#95617 = AXIS2_PLACEMENT_3D('',#95618,#95619,#95620); +#95618 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); +#95619 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95620 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95621 = DEFINITIONAL_REPRESENTATION('',(#95622),#95626); +#95622 = LINE('',#95623,#95624); +#95623 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95624 = VECTOR('',#95625,1.); +#95625 = DIRECTION('',(4.440892098501E-016,-1.)); +#95626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95627 = ORIENTED_EDGE('',*,*,#95628,.T.); +#95628 = EDGE_CURVE('',#95601,#95629,#95631,.T.); +#95629 = VERTEX_POINT('',#95630); +#95630 = CARTESIAN_POINT('',(10.,5.65,0.75)); +#95631 = SURFACE_CURVE('',#95632,(#95636,#95643),.PCURVE_S1.); +#95632 = LINE('',#95633,#95634); +#95633 = CARTESIAN_POINT('',(10.,5.65,0.65)); +#95634 = VECTOR('',#95635,1.); +#95635 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95636 = PCURVE('',#94664,#95637); +#95637 = DEFINITIONAL_REPRESENTATION('',(#95638),#95642); +#95638 = LINE('',#95639,#95640); +#95639 = CARTESIAN_POINT('',(-0.75,5.65)); +#95640 = VECTOR('',#95641,1.); +#95641 = DIRECTION('',(1.,0.E+000)); +#95642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95643 = PCURVE('',#95644,#95649); +#95644 = PLANE('',#95645); +#95645 = AXIS2_PLACEMENT_3D('',#95646,#95647,#95648); +#95646 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); +#95647 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95648 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95649 = DEFINITIONAL_REPRESENTATION('',(#95650),#95654); +#95650 = LINE('',#95651,#95652); +#95651 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95652 = VECTOR('',#95653,1.); +#95653 = DIRECTION('',(-1.,0.E+000)); +#95654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95655 = ORIENTED_EDGE('',*,*,#95656,.T.); +#95656 = EDGE_CURVE('',#95629,#95571,#95657,.T.); +#95657 = SURFACE_CURVE('',#95658,(#95662,#95669),.PCURVE_S1.); +#95658 = LINE('',#95659,#95660); +#95659 = CARTESIAN_POINT('',(10.,5.65,0.75)); +#95660 = VECTOR('',#95661,1.); +#95661 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95662 = PCURVE('',#94664,#95663); +#95663 = DEFINITIONAL_REPRESENTATION('',(#95664),#95668); +#95664 = LINE('',#95665,#95666); +#95665 = CARTESIAN_POINT('',(-0.65,5.65)); +#95666 = VECTOR('',#95667,1.); +#95667 = DIRECTION('',(0.E+000,1.)); +#95668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95669 = PCURVE('',#95670,#95675); +#95670 = PLANE('',#95671); +#95671 = AXIS2_PLACEMENT_3D('',#95672,#95673,#95674); +#95672 = CARTESIAN_POINT('',(10.527847992439,5.65,0.75)); +#95673 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95674 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95675 = DEFINITIONAL_REPRESENTATION('',(#95676),#95680); +#95676 = LINE('',#95677,#95678); +#95677 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95678 = VECTOR('',#95679,1.); +#95679 = DIRECTION('',(4.440892098501E-016,1.)); +#95680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95681 = FACE_BOUND('',#95682,.T.); +#95682 = EDGE_LOOP('',(#95683,#95713,#95741,#95769)); +#95683 = ORIENTED_EDGE('',*,*,#95684,.T.); +#95684 = EDGE_CURVE('',#95685,#95687,#95689,.T.); +#95685 = VERTEX_POINT('',#95686); +#95686 = CARTESIAN_POINT('',(10.,6.35,0.75)); +#95687 = VERTEX_POINT('',#95688); +#95688 = CARTESIAN_POINT('',(10.,6.35,0.65)); +#95689 = SURFACE_CURVE('',#95690,(#95694,#95701),.PCURVE_S1.); +#95690 = LINE('',#95691,#95692); +#95691 = CARTESIAN_POINT('',(10.,6.35,0.65)); +#95692 = VECTOR('',#95693,1.); +#95693 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95694 = PCURVE('',#94664,#95695); +#95695 = DEFINITIONAL_REPRESENTATION('',(#95696),#95700); +#95696 = LINE('',#95697,#95698); +#95697 = CARTESIAN_POINT('',(-0.75,6.35)); +#95698 = VECTOR('',#95699,1.); +#95699 = DIRECTION('',(-1.,0.E+000)); +#95700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95701 = PCURVE('',#95702,#95707); +#95702 = PLANE('',#95703); +#95703 = AXIS2_PLACEMENT_3D('',#95704,#95705,#95706); +#95704 = CARTESIAN_POINT('',(10.527847992439,6.35,0.65)); +#95705 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95706 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95707 = DEFINITIONAL_REPRESENTATION('',(#95708),#95712); +#95708 = LINE('',#95709,#95710); +#95709 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95710 = VECTOR('',#95711,1.); +#95711 = DIRECTION('',(-1.,0.E+000)); +#95712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95713 = ORIENTED_EDGE('',*,*,#95714,.T.); +#95714 = EDGE_CURVE('',#95687,#95715,#95717,.T.); +#95715 = VERTEX_POINT('',#95716); +#95716 = CARTESIAN_POINT('',(10.,6.15,0.65)); +#95717 = SURFACE_CURVE('',#95718,(#95722,#95729),.PCURVE_S1.); +#95718 = LINE('',#95719,#95720); +#95719 = CARTESIAN_POINT('',(10.,6.15,0.65)); +#95720 = VECTOR('',#95721,1.); +#95721 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95722 = PCURVE('',#94664,#95723); +#95723 = DEFINITIONAL_REPRESENTATION('',(#95724),#95728); +#95724 = LINE('',#95725,#95726); +#95725 = CARTESIAN_POINT('',(-0.75,6.15)); +#95726 = VECTOR('',#95727,1.); +#95727 = DIRECTION('',(0.E+000,-1.)); +#95728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95729 = PCURVE('',#95730,#95735); +#95730 = PLANE('',#95731); +#95731 = AXIS2_PLACEMENT_3D('',#95732,#95733,#95734); +#95732 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); +#95733 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95734 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95735 = DEFINITIONAL_REPRESENTATION('',(#95736),#95740); +#95736 = LINE('',#95737,#95738); +#95737 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95738 = VECTOR('',#95739,1.); +#95739 = DIRECTION('',(4.440892098501E-016,-1.)); +#95740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95741 = ORIENTED_EDGE('',*,*,#95742,.T.); +#95742 = EDGE_CURVE('',#95715,#95743,#95745,.T.); +#95743 = VERTEX_POINT('',#95744); +#95744 = CARTESIAN_POINT('',(10.,6.15,0.75)); +#95745 = SURFACE_CURVE('',#95746,(#95750,#95757),.PCURVE_S1.); +#95746 = LINE('',#95747,#95748); +#95747 = CARTESIAN_POINT('',(10.,6.15,0.65)); +#95748 = VECTOR('',#95749,1.); +#95749 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95750 = PCURVE('',#94664,#95751); +#95751 = DEFINITIONAL_REPRESENTATION('',(#95752),#95756); +#95752 = LINE('',#95753,#95754); +#95753 = CARTESIAN_POINT('',(-0.75,6.15)); +#95754 = VECTOR('',#95755,1.); +#95755 = DIRECTION('',(1.,0.E+000)); +#95756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95757 = PCURVE('',#95758,#95763); +#95758 = PLANE('',#95759); +#95759 = AXIS2_PLACEMENT_3D('',#95760,#95761,#95762); +#95760 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); +#95761 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95762 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95763 = DEFINITIONAL_REPRESENTATION('',(#95764),#95768); +#95764 = LINE('',#95765,#95766); +#95765 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95766 = VECTOR('',#95767,1.); +#95767 = DIRECTION('',(-1.,0.E+000)); +#95768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95769 = ORIENTED_EDGE('',*,*,#95770,.T.); +#95770 = EDGE_CURVE('',#95743,#95685,#95771,.T.); +#95771 = SURFACE_CURVE('',#95772,(#95776,#95783),.PCURVE_S1.); +#95772 = LINE('',#95773,#95774); +#95773 = CARTESIAN_POINT('',(10.,6.15,0.75)); +#95774 = VECTOR('',#95775,1.); +#95775 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95776 = PCURVE('',#94664,#95777); +#95777 = DEFINITIONAL_REPRESENTATION('',(#95778),#95782); +#95778 = LINE('',#95779,#95780); +#95779 = CARTESIAN_POINT('',(-0.65,6.15)); +#95780 = VECTOR('',#95781,1.); +#95781 = DIRECTION('',(0.E+000,1.)); +#95782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95783 = PCURVE('',#95784,#95789); +#95784 = PLANE('',#95785); +#95785 = AXIS2_PLACEMENT_3D('',#95786,#95787,#95788); +#95786 = CARTESIAN_POINT('',(10.527847992439,6.15,0.75)); +#95787 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95788 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95789 = DEFINITIONAL_REPRESENTATION('',(#95790),#95794); +#95790 = LINE('',#95791,#95792); +#95791 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95792 = VECTOR('',#95793,1.); +#95793 = DIRECTION('',(4.440892098501E-016,1.)); +#95794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95795 = FACE_BOUND('',#95796,.T.); +#95796 = EDGE_LOOP('',(#95797,#95827,#95855,#95883)); +#95797 = ORIENTED_EDGE('',*,*,#95798,.T.); +#95798 = EDGE_CURVE('',#95799,#95801,#95803,.T.); +#95799 = VERTEX_POINT('',#95800); +#95800 = CARTESIAN_POINT('',(10.,6.85,0.75)); +#95801 = VERTEX_POINT('',#95802); +#95802 = CARTESIAN_POINT('',(10.,6.85,0.65)); +#95803 = SURFACE_CURVE('',#95804,(#95808,#95815),.PCURVE_S1.); +#95804 = LINE('',#95805,#95806); +#95805 = CARTESIAN_POINT('',(10.,6.85,0.65)); +#95806 = VECTOR('',#95807,1.); +#95807 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95808 = PCURVE('',#94664,#95809); +#95809 = DEFINITIONAL_REPRESENTATION('',(#95810),#95814); +#95810 = LINE('',#95811,#95812); +#95811 = CARTESIAN_POINT('',(-0.75,6.85)); +#95812 = VECTOR('',#95813,1.); +#95813 = DIRECTION('',(-1.,0.E+000)); +#95814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95815 = PCURVE('',#95816,#95821); +#95816 = PLANE('',#95817); +#95817 = AXIS2_PLACEMENT_3D('',#95818,#95819,#95820); +#95818 = CARTESIAN_POINT('',(10.527847992439,6.85,0.65)); +#95819 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95820 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95821 = DEFINITIONAL_REPRESENTATION('',(#95822),#95826); +#95822 = LINE('',#95823,#95824); +#95823 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95824 = VECTOR('',#95825,1.); +#95825 = DIRECTION('',(-1.,0.E+000)); +#95826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95827 = ORIENTED_EDGE('',*,*,#95828,.T.); +#95828 = EDGE_CURVE('',#95801,#95829,#95831,.T.); +#95829 = VERTEX_POINT('',#95830); +#95830 = CARTESIAN_POINT('',(10.,6.65,0.65)); +#95831 = SURFACE_CURVE('',#95832,(#95836,#95843),.PCURVE_S1.); +#95832 = LINE('',#95833,#95834); +#95833 = CARTESIAN_POINT('',(10.,6.65,0.65)); +#95834 = VECTOR('',#95835,1.); +#95835 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95836 = PCURVE('',#94664,#95837); +#95837 = DEFINITIONAL_REPRESENTATION('',(#95838),#95842); +#95838 = LINE('',#95839,#95840); +#95839 = CARTESIAN_POINT('',(-0.75,6.65)); +#95840 = VECTOR('',#95841,1.); +#95841 = DIRECTION('',(0.E+000,-1.)); +#95842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95843 = PCURVE('',#95844,#95849); +#95844 = PLANE('',#95845); +#95845 = AXIS2_PLACEMENT_3D('',#95846,#95847,#95848); +#95846 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); +#95847 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95848 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95849 = DEFINITIONAL_REPRESENTATION('',(#95850),#95854); +#95850 = LINE('',#95851,#95852); +#95851 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95852 = VECTOR('',#95853,1.); +#95853 = DIRECTION('',(4.440892098501E-016,-1.)); +#95854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95855 = ORIENTED_EDGE('',*,*,#95856,.T.); +#95856 = EDGE_CURVE('',#95829,#95857,#95859,.T.); +#95857 = VERTEX_POINT('',#95858); +#95858 = CARTESIAN_POINT('',(10.,6.65,0.75)); +#95859 = SURFACE_CURVE('',#95860,(#95864,#95871),.PCURVE_S1.); +#95860 = LINE('',#95861,#95862); +#95861 = CARTESIAN_POINT('',(10.,6.65,0.65)); +#95862 = VECTOR('',#95863,1.); +#95863 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95864 = PCURVE('',#94664,#95865); +#95865 = DEFINITIONAL_REPRESENTATION('',(#95866),#95870); +#95866 = LINE('',#95867,#95868); +#95867 = CARTESIAN_POINT('',(-0.75,6.65)); +#95868 = VECTOR('',#95869,1.); +#95869 = DIRECTION('',(1.,0.E+000)); +#95870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95871 = PCURVE('',#95872,#95877); +#95872 = PLANE('',#95873); +#95873 = AXIS2_PLACEMENT_3D('',#95874,#95875,#95876); +#95874 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); +#95875 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95876 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95877 = DEFINITIONAL_REPRESENTATION('',(#95878),#95882); +#95878 = LINE('',#95879,#95880); +#95879 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95880 = VECTOR('',#95881,1.); +#95881 = DIRECTION('',(-1.,0.E+000)); +#95882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95883 = ORIENTED_EDGE('',*,*,#95884,.T.); +#95884 = EDGE_CURVE('',#95857,#95799,#95885,.T.); +#95885 = SURFACE_CURVE('',#95886,(#95890,#95897),.PCURVE_S1.); +#95886 = LINE('',#95887,#95888); +#95887 = CARTESIAN_POINT('',(10.,6.65,0.75)); +#95888 = VECTOR('',#95889,1.); +#95889 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#95890 = PCURVE('',#94664,#95891); +#95891 = DEFINITIONAL_REPRESENTATION('',(#95892),#95896); +#95892 = LINE('',#95893,#95894); +#95893 = CARTESIAN_POINT('',(-0.65,6.65)); +#95894 = VECTOR('',#95895,1.); +#95895 = DIRECTION('',(0.E+000,1.)); +#95896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95897 = PCURVE('',#95898,#95903); +#95898 = PLANE('',#95899); +#95899 = AXIS2_PLACEMENT_3D('',#95900,#95901,#95902); +#95900 = CARTESIAN_POINT('',(10.527847992439,6.65,0.75)); +#95901 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#95902 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#95903 = DEFINITIONAL_REPRESENTATION('',(#95904),#95908); +#95904 = LINE('',#95905,#95906); +#95905 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#95906 = VECTOR('',#95907,1.); +#95907 = DIRECTION('',(4.440892098501E-016,1.)); +#95908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95909 = FACE_BOUND('',#95910,.T.); +#95910 = EDGE_LOOP('',(#95911,#95941,#95969,#95997)); +#95911 = ORIENTED_EDGE('',*,*,#95912,.T.); +#95912 = EDGE_CURVE('',#95913,#95915,#95917,.T.); +#95913 = VERTEX_POINT('',#95914); +#95914 = CARTESIAN_POINT('',(10.,7.35,0.75)); +#95915 = VERTEX_POINT('',#95916); +#95916 = CARTESIAN_POINT('',(10.,7.35,0.65)); +#95917 = SURFACE_CURVE('',#95918,(#95922,#95929),.PCURVE_S1.); +#95918 = LINE('',#95919,#95920); +#95919 = CARTESIAN_POINT('',(10.,7.35,0.65)); +#95920 = VECTOR('',#95921,1.); +#95921 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95922 = PCURVE('',#94664,#95923); +#95923 = DEFINITIONAL_REPRESENTATION('',(#95924),#95928); +#95924 = LINE('',#95925,#95926); +#95925 = CARTESIAN_POINT('',(-0.75,7.35)); +#95926 = VECTOR('',#95927,1.); +#95927 = DIRECTION('',(-1.,0.E+000)); +#95928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95929 = PCURVE('',#95930,#95935); +#95930 = PLANE('',#95931); +#95931 = AXIS2_PLACEMENT_3D('',#95932,#95933,#95934); +#95932 = CARTESIAN_POINT('',(10.527847992439,7.35,0.65)); +#95933 = DIRECTION('',(0.E+000,1.,0.E+000)); +#95934 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95935 = DEFINITIONAL_REPRESENTATION('',(#95936),#95940); +#95936 = LINE('',#95937,#95938); +#95937 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#95938 = VECTOR('',#95939,1.); +#95939 = DIRECTION('',(-1.,0.E+000)); +#95940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95941 = ORIENTED_EDGE('',*,*,#95942,.T.); +#95942 = EDGE_CURVE('',#95915,#95943,#95945,.T.); +#95943 = VERTEX_POINT('',#95944); +#95944 = CARTESIAN_POINT('',(10.,7.15,0.65)); +#95945 = SURFACE_CURVE('',#95946,(#95950,#95957),.PCURVE_S1.); +#95946 = LINE('',#95947,#95948); +#95947 = CARTESIAN_POINT('',(10.,7.15,0.65)); +#95948 = VECTOR('',#95949,1.); +#95949 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#95950 = PCURVE('',#94664,#95951); +#95951 = DEFINITIONAL_REPRESENTATION('',(#95952),#95956); +#95952 = LINE('',#95953,#95954); +#95953 = CARTESIAN_POINT('',(-0.75,7.15)); +#95954 = VECTOR('',#95955,1.); +#95955 = DIRECTION('',(0.E+000,-1.)); +#95956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95957 = PCURVE('',#95958,#95963); +#95958 = PLANE('',#95959); +#95959 = AXIS2_PLACEMENT_3D('',#95960,#95961,#95962); +#95960 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); +#95961 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#95962 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#95963 = DEFINITIONAL_REPRESENTATION('',(#95964),#95968); +#95964 = LINE('',#95965,#95966); +#95965 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#95966 = VECTOR('',#95967,1.); +#95967 = DIRECTION('',(4.440892098501E-016,-1.)); +#95968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95969 = ORIENTED_EDGE('',*,*,#95970,.T.); +#95970 = EDGE_CURVE('',#95943,#95971,#95973,.T.); +#95971 = VERTEX_POINT('',#95972); +#95972 = CARTESIAN_POINT('',(10.,7.15,0.75)); +#95973 = SURFACE_CURVE('',#95974,(#95978,#95985),.PCURVE_S1.); +#95974 = LINE('',#95975,#95976); +#95975 = CARTESIAN_POINT('',(10.,7.15,0.65)); +#95976 = VECTOR('',#95977,1.); +#95977 = DIRECTION('',(0.E+000,0.E+000,1.)); +#95978 = PCURVE('',#94664,#95979); +#95979 = DEFINITIONAL_REPRESENTATION('',(#95980),#95984); +#95980 = LINE('',#95981,#95982); +#95981 = CARTESIAN_POINT('',(-0.75,7.15)); +#95982 = VECTOR('',#95983,1.); +#95983 = DIRECTION('',(1.,0.E+000)); +#95984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95985 = PCURVE('',#95986,#95991); +#95986 = PLANE('',#95987); +#95987 = AXIS2_PLACEMENT_3D('',#95988,#95989,#95990); +#95988 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); +#95989 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#95990 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#95991 = DEFINITIONAL_REPRESENTATION('',(#95992),#95996); +#95992 = LINE('',#95993,#95994); +#95993 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#95994 = VECTOR('',#95995,1.); +#95995 = DIRECTION('',(-1.,0.E+000)); +#95996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#95997 = ORIENTED_EDGE('',*,*,#95998,.T.); +#95998 = EDGE_CURVE('',#95971,#95913,#95999,.T.); +#95999 = SURFACE_CURVE('',#96000,(#96004,#96011),.PCURVE_S1.); +#96000 = LINE('',#96001,#96002); +#96001 = CARTESIAN_POINT('',(10.,7.15,0.75)); +#96002 = VECTOR('',#96003,1.); +#96003 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#96004 = PCURVE('',#94664,#96005); +#96005 = DEFINITIONAL_REPRESENTATION('',(#96006),#96010); +#96006 = LINE('',#96007,#96008); +#96007 = CARTESIAN_POINT('',(-0.65,7.15)); +#96008 = VECTOR('',#96009,1.); +#96009 = DIRECTION('',(0.E+000,1.)); +#96010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96011 = PCURVE('',#96012,#96017); +#96012 = PLANE('',#96013); +#96013 = AXIS2_PLACEMENT_3D('',#96014,#96015,#96016); +#96014 = CARTESIAN_POINT('',(10.527847992439,7.15,0.75)); +#96015 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#96016 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#96017 = DEFINITIONAL_REPRESENTATION('',(#96018),#96022); +#96018 = LINE('',#96019,#96020); +#96019 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#96020 = VECTOR('',#96021,1.); +#96021 = DIRECTION('',(4.440892098501E-016,1.)); +#96022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96023 = FACE_BOUND('',#96024,.T.); +#96024 = EDGE_LOOP('',(#96025,#96055,#96083,#96111)); +#96025 = ORIENTED_EDGE('',*,*,#96026,.T.); +#96026 = EDGE_CURVE('',#96027,#96029,#96031,.T.); +#96027 = VERTEX_POINT('',#96028); +#96028 = CARTESIAN_POINT('',(10.,7.85,0.75)); +#96029 = VERTEX_POINT('',#96030); +#96030 = CARTESIAN_POINT('',(10.,7.85,0.65)); +#96031 = SURFACE_CURVE('',#96032,(#96036,#96043),.PCURVE_S1.); +#96032 = LINE('',#96033,#96034); +#96033 = CARTESIAN_POINT('',(10.,7.85,0.65)); +#96034 = VECTOR('',#96035,1.); +#96035 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96036 = PCURVE('',#94664,#96037); +#96037 = DEFINITIONAL_REPRESENTATION('',(#96038),#96042); +#96038 = LINE('',#96039,#96040); +#96039 = CARTESIAN_POINT('',(-0.75,7.85)); +#96040 = VECTOR('',#96041,1.); +#96041 = DIRECTION('',(-1.,0.E+000)); +#96042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96043 = PCURVE('',#96044,#96049); +#96044 = PLANE('',#96045); +#96045 = AXIS2_PLACEMENT_3D('',#96046,#96047,#96048); +#96046 = CARTESIAN_POINT('',(10.527847992439,7.85,0.65)); +#96047 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96048 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96049 = DEFINITIONAL_REPRESENTATION('',(#96050),#96054); +#96050 = LINE('',#96051,#96052); +#96051 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#96052 = VECTOR('',#96053,1.); +#96053 = DIRECTION('',(-1.,0.E+000)); +#96054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96055 = ORIENTED_EDGE('',*,*,#96056,.T.); +#96056 = EDGE_CURVE('',#96029,#96057,#96059,.T.); +#96057 = VERTEX_POINT('',#96058); +#96058 = CARTESIAN_POINT('',(10.,7.65,0.65)); +#96059 = SURFACE_CURVE('',#96060,(#96064,#96071),.PCURVE_S1.); +#96060 = LINE('',#96061,#96062); +#96061 = CARTESIAN_POINT('',(10.,7.65,0.65)); +#96062 = VECTOR('',#96063,1.); +#96063 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#96064 = PCURVE('',#94664,#96065); +#96065 = DEFINITIONAL_REPRESENTATION('',(#96066),#96070); +#96066 = LINE('',#96067,#96068); +#96067 = CARTESIAN_POINT('',(-0.75,7.65)); +#96068 = VECTOR('',#96069,1.); +#96069 = DIRECTION('',(0.E+000,-1.)); +#96070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96071 = PCURVE('',#96072,#96077); +#96072 = PLANE('',#96073); +#96073 = AXIS2_PLACEMENT_3D('',#96074,#96075,#96076); +#96074 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); +#96075 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#96076 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#96077 = DEFINITIONAL_REPRESENTATION('',(#96078),#96082); +#96078 = LINE('',#96079,#96080); +#96079 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#96080 = VECTOR('',#96081,1.); +#96081 = DIRECTION('',(4.440892098501E-016,-1.)); +#96082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96083 = ORIENTED_EDGE('',*,*,#96084,.T.); +#96084 = EDGE_CURVE('',#96057,#96085,#96087,.T.); +#96085 = VERTEX_POINT('',#96086); +#96086 = CARTESIAN_POINT('',(10.,7.65,0.75)); +#96087 = SURFACE_CURVE('',#96088,(#96092,#96099),.PCURVE_S1.); +#96088 = LINE('',#96089,#96090); +#96089 = CARTESIAN_POINT('',(10.,7.65,0.65)); +#96090 = VECTOR('',#96091,1.); +#96091 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96092 = PCURVE('',#94664,#96093); +#96093 = DEFINITIONAL_REPRESENTATION('',(#96094),#96098); +#96094 = LINE('',#96095,#96096); +#96095 = CARTESIAN_POINT('',(-0.75,7.65)); +#96096 = VECTOR('',#96097,1.); +#96097 = DIRECTION('',(1.,0.E+000)); +#96098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96099 = PCURVE('',#96100,#96105); +#96100 = PLANE('',#96101); +#96101 = AXIS2_PLACEMENT_3D('',#96102,#96103,#96104); +#96102 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); +#96103 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96104 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96105 = DEFINITIONAL_REPRESENTATION('',(#96106),#96110); +#96106 = LINE('',#96107,#96108); +#96107 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#96108 = VECTOR('',#96109,1.); +#96109 = DIRECTION('',(-1.,0.E+000)); +#96110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96111 = ORIENTED_EDGE('',*,*,#96112,.T.); +#96112 = EDGE_CURVE('',#96085,#96027,#96113,.T.); +#96113 = SURFACE_CURVE('',#96114,(#96118,#96125),.PCURVE_S1.); +#96114 = LINE('',#96115,#96116); +#96115 = CARTESIAN_POINT('',(10.,7.65,0.75)); +#96116 = VECTOR('',#96117,1.); +#96117 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#96118 = PCURVE('',#94664,#96119); +#96119 = DEFINITIONAL_REPRESENTATION('',(#96120),#96124); +#96120 = LINE('',#96121,#96122); +#96121 = CARTESIAN_POINT('',(-0.65,7.65)); +#96122 = VECTOR('',#96123,1.); +#96123 = DIRECTION('',(0.E+000,1.)); +#96124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96125 = PCURVE('',#96126,#96131); +#96126 = PLANE('',#96127); +#96127 = AXIS2_PLACEMENT_3D('',#96128,#96129,#96130); +#96128 = CARTESIAN_POINT('',(10.527847992439,7.65,0.75)); +#96129 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#96130 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#96131 = DEFINITIONAL_REPRESENTATION('',(#96132),#96136); +#96132 = LINE('',#96133,#96134); +#96133 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#96134 = VECTOR('',#96135,1.); +#96135 = DIRECTION('',(4.440892098501E-016,1.)); +#96136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96137 = FACE_BOUND('',#96138,.T.); +#96138 = EDGE_LOOP('',(#96139,#96169,#96197,#96225)); +#96139 = ORIENTED_EDGE('',*,*,#96140,.T.); +#96140 = EDGE_CURVE('',#96141,#96143,#96145,.T.); +#96141 = VERTEX_POINT('',#96142); +#96142 = CARTESIAN_POINT('',(10.,8.35,0.75)); +#96143 = VERTEX_POINT('',#96144); +#96144 = CARTESIAN_POINT('',(10.,8.35,0.65)); +#96145 = SURFACE_CURVE('',#96146,(#96150,#96157),.PCURVE_S1.); +#96146 = LINE('',#96147,#96148); +#96147 = CARTESIAN_POINT('',(10.,8.35,0.65)); +#96148 = VECTOR('',#96149,1.); +#96149 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96150 = PCURVE('',#94664,#96151); +#96151 = DEFINITIONAL_REPRESENTATION('',(#96152),#96156); +#96152 = LINE('',#96153,#96154); +#96153 = CARTESIAN_POINT('',(-0.75,8.35)); +#96154 = VECTOR('',#96155,1.); +#96155 = DIRECTION('',(-1.,0.E+000)); +#96156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96157 = PCURVE('',#96158,#96163); +#96158 = PLANE('',#96159); +#96159 = AXIS2_PLACEMENT_3D('',#96160,#96161,#96162); +#96160 = CARTESIAN_POINT('',(10.527847992439,8.35,0.65)); +#96161 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96162 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96163 = DEFINITIONAL_REPRESENTATION('',(#96164),#96168); +#96164 = LINE('',#96165,#96166); +#96165 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#96166 = VECTOR('',#96167,1.); +#96167 = DIRECTION('',(-1.,0.E+000)); +#96168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96169 = ORIENTED_EDGE('',*,*,#96170,.T.); +#96170 = EDGE_CURVE('',#96143,#96171,#96173,.T.); +#96171 = VERTEX_POINT('',#96172); +#96172 = CARTESIAN_POINT('',(10.,8.15,0.65)); +#96173 = SURFACE_CURVE('',#96174,(#96178,#96185),.PCURVE_S1.); +#96174 = LINE('',#96175,#96176); +#96175 = CARTESIAN_POINT('',(10.,8.15,0.65)); +#96176 = VECTOR('',#96177,1.); +#96177 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#96178 = PCURVE('',#94664,#96179); +#96179 = DEFINITIONAL_REPRESENTATION('',(#96180),#96184); +#96180 = LINE('',#96181,#96182); +#96181 = CARTESIAN_POINT('',(-0.75,8.15)); +#96182 = VECTOR('',#96183,1.); +#96183 = DIRECTION('',(0.E+000,-1.)); +#96184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96185 = PCURVE('',#96186,#96191); +#96186 = PLANE('',#96187); +#96187 = AXIS2_PLACEMENT_3D('',#96188,#96189,#96190); +#96188 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); +#96189 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#96190 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#96191 = DEFINITIONAL_REPRESENTATION('',(#96192),#96196); +#96192 = LINE('',#96193,#96194); +#96193 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#96194 = VECTOR('',#96195,1.); +#96195 = DIRECTION('',(4.440892098501E-016,-1.)); +#96196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96197 = ORIENTED_EDGE('',*,*,#96198,.T.); +#96198 = EDGE_CURVE('',#96171,#96199,#96201,.T.); +#96199 = VERTEX_POINT('',#96200); +#96200 = CARTESIAN_POINT('',(10.,8.15,0.75)); +#96201 = SURFACE_CURVE('',#96202,(#96206,#96213),.PCURVE_S1.); +#96202 = LINE('',#96203,#96204); +#96203 = CARTESIAN_POINT('',(10.,8.15,0.65)); +#96204 = VECTOR('',#96205,1.); +#96205 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96206 = PCURVE('',#94664,#96207); +#96207 = DEFINITIONAL_REPRESENTATION('',(#96208),#96212); +#96208 = LINE('',#96209,#96210); +#96209 = CARTESIAN_POINT('',(-0.75,8.15)); +#96210 = VECTOR('',#96211,1.); +#96211 = DIRECTION('',(1.,0.E+000)); +#96212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96213 = PCURVE('',#96214,#96219); +#96214 = PLANE('',#96215); +#96215 = AXIS2_PLACEMENT_3D('',#96216,#96217,#96218); +#96216 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); +#96217 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96218 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96219 = DEFINITIONAL_REPRESENTATION('',(#96220),#96224); +#96220 = LINE('',#96221,#96222); +#96221 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#96222 = VECTOR('',#96223,1.); +#96223 = DIRECTION('',(-1.,0.E+000)); +#96224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96225 = ORIENTED_EDGE('',*,*,#96226,.T.); +#96226 = EDGE_CURVE('',#96199,#96141,#96227,.T.); +#96227 = SURFACE_CURVE('',#96228,(#96232,#96239),.PCURVE_S1.); +#96228 = LINE('',#96229,#96230); +#96229 = CARTESIAN_POINT('',(10.,8.15,0.75)); +#96230 = VECTOR('',#96231,1.); +#96231 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#96232 = PCURVE('',#94664,#96233); +#96233 = DEFINITIONAL_REPRESENTATION('',(#96234),#96238); +#96234 = LINE('',#96235,#96236); +#96235 = CARTESIAN_POINT('',(-0.65,8.15)); +#96236 = VECTOR('',#96237,1.); +#96237 = DIRECTION('',(0.E+000,1.)); +#96238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96239 = PCURVE('',#96240,#96245); +#96240 = PLANE('',#96241); +#96241 = AXIS2_PLACEMENT_3D('',#96242,#96243,#96244); +#96242 = CARTESIAN_POINT('',(10.527847992439,8.15,0.75)); +#96243 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#96244 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#96245 = DEFINITIONAL_REPRESENTATION('',(#96246),#96250); +#96246 = LINE('',#96247,#96248); +#96247 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#96248 = VECTOR('',#96249,1.); +#96249 = DIRECTION('',(4.440892098501E-016,1.)); +#96250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96251 = FACE_BOUND('',#96252,.T.); +#96252 = EDGE_LOOP('',(#96253,#96283,#96311,#96339)); +#96253 = ORIENTED_EDGE('',*,*,#96254,.T.); +#96254 = EDGE_CURVE('',#96255,#96257,#96259,.T.); +#96255 = VERTEX_POINT('',#96256); +#96256 = CARTESIAN_POINT('',(10.,4.65,0.75)); +#96257 = VERTEX_POINT('',#96258); +#96258 = CARTESIAN_POINT('',(10.,4.85,0.75)); +#96259 = SURFACE_CURVE('',#96260,(#96264,#96271),.PCURVE_S1.); +#96260 = LINE('',#96261,#96262); +#96261 = CARTESIAN_POINT('',(10.,4.85,0.75)); +#96262 = VECTOR('',#96263,1.); +#96263 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#96264 = PCURVE('',#94664,#96265); +#96265 = DEFINITIONAL_REPRESENTATION('',(#96266),#96270); +#96266 = LINE('',#96267,#96268); +#96267 = CARTESIAN_POINT('',(-0.65,4.85)); +#96268 = VECTOR('',#96269,1.); +#96269 = DIRECTION('',(0.E+000,1.)); +#96270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96271 = PCURVE('',#96272,#96277); +#96272 = PLANE('',#96273); +#96273 = AXIS2_PLACEMENT_3D('',#96274,#96275,#96276); +#96274 = CARTESIAN_POINT('',(10.527847992439,4.85,0.75)); +#96275 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#96276 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#96277 = DEFINITIONAL_REPRESENTATION('',(#96278),#96282); +#96278 = LINE('',#96279,#96280); +#96279 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#96280 = VECTOR('',#96281,1.); +#96281 = DIRECTION('',(4.440892098501E-016,1.)); +#96282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96283 = ORIENTED_EDGE('',*,*,#96284,.T.); +#96284 = EDGE_CURVE('',#96257,#96285,#96287,.T.); +#96285 = VERTEX_POINT('',#96286); +#96286 = CARTESIAN_POINT('',(10.,4.85,0.65)); +#96287 = SURFACE_CURVE('',#96288,(#96292,#96299),.PCURVE_S1.); +#96288 = LINE('',#96289,#96290); +#96289 = CARTESIAN_POINT('',(10.,4.85,0.65)); +#96290 = VECTOR('',#96291,1.); +#96291 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96292 = PCURVE('',#94664,#96293); +#96293 = DEFINITIONAL_REPRESENTATION('',(#96294),#96298); +#96294 = LINE('',#96295,#96296); +#96295 = CARTESIAN_POINT('',(-0.75,4.85)); +#96296 = VECTOR('',#96297,1.); +#96297 = DIRECTION('',(-1.,0.E+000)); +#96298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96299 = PCURVE('',#96300,#96305); +#96300 = PLANE('',#96301); +#96301 = AXIS2_PLACEMENT_3D('',#96302,#96303,#96304); +#96302 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); +#96303 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96304 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96305 = DEFINITIONAL_REPRESENTATION('',(#96306),#96310); +#96306 = LINE('',#96307,#96308); +#96307 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#96308 = VECTOR('',#96309,1.); +#96309 = DIRECTION('',(-1.,0.E+000)); +#96310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96311 = ORIENTED_EDGE('',*,*,#96312,.T.); +#96312 = EDGE_CURVE('',#96285,#96313,#96315,.T.); +#96313 = VERTEX_POINT('',#96314); +#96314 = CARTESIAN_POINT('',(10.,4.65,0.65)); +#96315 = SURFACE_CURVE('',#96316,(#96320,#96327),.PCURVE_S1.); +#96316 = LINE('',#96317,#96318); +#96317 = CARTESIAN_POINT('',(10.,4.85,0.65)); +#96318 = VECTOR('',#96319,1.); +#96319 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#96320 = PCURVE('',#94664,#96321); +#96321 = DEFINITIONAL_REPRESENTATION('',(#96322),#96326); +#96322 = LINE('',#96323,#96324); +#96323 = CARTESIAN_POINT('',(-0.75,4.85)); +#96324 = VECTOR('',#96325,1.); +#96325 = DIRECTION('',(0.E+000,-1.)); +#96326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96327 = PCURVE('',#96328,#96333); +#96328 = PLANE('',#96329); +#96329 = AXIS2_PLACEMENT_3D('',#96330,#96331,#96332); +#96330 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); +#96331 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#96332 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#96333 = DEFINITIONAL_REPRESENTATION('',(#96334),#96338); +#96334 = LINE('',#96335,#96336); +#96335 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#96336 = VECTOR('',#96337,1.); +#96337 = DIRECTION('',(4.440892098501E-016,-1.)); +#96338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96339 = ORIENTED_EDGE('',*,*,#96340,.T.); +#96340 = EDGE_CURVE('',#96313,#96255,#96341,.T.); +#96341 = SURFACE_CURVE('',#96342,(#96346,#96353),.PCURVE_S1.); +#96342 = LINE('',#96343,#96344); +#96343 = CARTESIAN_POINT('',(10.,4.65,0.65)); +#96344 = VECTOR('',#96345,1.); +#96345 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96346 = PCURVE('',#94664,#96347); +#96347 = DEFINITIONAL_REPRESENTATION('',(#96348),#96352); +#96348 = LINE('',#96349,#96350); +#96349 = CARTESIAN_POINT('',(-0.75,4.65)); +#96350 = VECTOR('',#96351,1.); +#96351 = DIRECTION('',(1.,0.E+000)); +#96352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96353 = PCURVE('',#96354,#96359); +#96354 = PLANE('',#96355); +#96355 = AXIS2_PLACEMENT_3D('',#96356,#96357,#96358); +#96356 = CARTESIAN_POINT('',(10.527847992439,4.65,0.65)); +#96357 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96358 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96359 = DEFINITIONAL_REPRESENTATION('',(#96360),#96364); +#96360 = LINE('',#96361,#96362); +#96361 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#96362 = VECTOR('',#96363,1.); +#96363 = DIRECTION('',(-1.,0.E+000)); +#96364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96365 = FACE_BOUND('',#96366,.T.); +#96366 = EDGE_LOOP('',(#96367,#96397,#96425,#96453)); +#96367 = ORIENTED_EDGE('',*,*,#96368,.T.); +#96368 = EDGE_CURVE('',#96369,#96371,#96373,.T.); +#96369 = VERTEX_POINT('',#96370); +#96370 = CARTESIAN_POINT('',(10.,8.85,0.75)); +#96371 = VERTEX_POINT('',#96372); +#96372 = CARTESIAN_POINT('',(10.,8.85,0.65)); +#96373 = SURFACE_CURVE('',#96374,(#96378,#96385),.PCURVE_S1.); +#96374 = LINE('',#96375,#96376); +#96375 = CARTESIAN_POINT('',(10.,8.85,0.65)); +#96376 = VECTOR('',#96377,1.); +#96377 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96378 = PCURVE('',#94664,#96379); +#96379 = DEFINITIONAL_REPRESENTATION('',(#96380),#96384); +#96380 = LINE('',#96381,#96382); +#96381 = CARTESIAN_POINT('',(-0.75,8.85)); +#96382 = VECTOR('',#96383,1.); +#96383 = DIRECTION('',(-1.,0.E+000)); +#96384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96385 = PCURVE('',#96386,#96391); +#96386 = PLANE('',#96387); +#96387 = AXIS2_PLACEMENT_3D('',#96388,#96389,#96390); +#96388 = CARTESIAN_POINT('',(10.527847992439,8.85,0.65)); +#96389 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96390 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96391 = DEFINITIONAL_REPRESENTATION('',(#96392),#96396); +#96392 = LINE('',#96393,#96394); +#96393 = CARTESIAN_POINT('',(2.22044604925E-016,-0.527847992439)); +#96394 = VECTOR('',#96395,1.); +#96395 = DIRECTION('',(-1.,0.E+000)); +#96396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96397 = ORIENTED_EDGE('',*,*,#96398,.T.); +#96398 = EDGE_CURVE('',#96371,#96399,#96401,.T.); +#96399 = VERTEX_POINT('',#96400); +#96400 = CARTESIAN_POINT('',(10.,8.65,0.65)); +#96401 = SURFACE_CURVE('',#96402,(#96406,#96413),.PCURVE_S1.); +#96402 = LINE('',#96403,#96404); +#96403 = CARTESIAN_POINT('',(10.,8.65,0.65)); +#96404 = VECTOR('',#96405,1.); +#96405 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#96406 = PCURVE('',#94664,#96407); +#96407 = DEFINITIONAL_REPRESENTATION('',(#96408),#96412); +#96408 = LINE('',#96409,#96410); +#96409 = CARTESIAN_POINT('',(-0.75,8.65)); +#96410 = VECTOR('',#96411,1.); +#96411 = DIRECTION('',(0.E+000,-1.)); +#96412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96413 = PCURVE('',#96414,#96419); +#96414 = PLANE('',#96415); +#96415 = AXIS2_PLACEMENT_3D('',#96416,#96417,#96418); +#96416 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); +#96417 = DIRECTION('',(-3.563627120235E-016,1.582568352025E-031,-1.)); +#96418 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#96419 = DEFINITIONAL_REPRESENTATION('',(#96420),#96424); +#96420 = LINE('',#96421,#96422); +#96421 = CARTESIAN_POINT('',(0.527847992439,5.371120320375E-048)); +#96422 = VECTOR('',#96423,1.); +#96423 = DIRECTION('',(4.440892098501E-016,-1.)); +#96424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96425 = ORIENTED_EDGE('',*,*,#96426,.T.); +#96426 = EDGE_CURVE('',#96399,#96427,#96429,.T.); +#96427 = VERTEX_POINT('',#96428); +#96428 = CARTESIAN_POINT('',(10.,8.65,0.75)); +#96429 = SURFACE_CURVE('',#96430,(#96434,#96441),.PCURVE_S1.); +#96430 = LINE('',#96431,#96432); +#96431 = CARTESIAN_POINT('',(10.,8.65,0.65)); +#96432 = VECTOR('',#96433,1.); +#96433 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96434 = PCURVE('',#94664,#96435); +#96435 = DEFINITIONAL_REPRESENTATION('',(#96436),#96440); +#96436 = LINE('',#96437,#96438); +#96437 = CARTESIAN_POINT('',(-0.75,8.65)); +#96438 = VECTOR('',#96439,1.); +#96439 = DIRECTION('',(1.,0.E+000)); +#96440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96441 = PCURVE('',#96442,#96447); +#96442 = PLANE('',#96443); +#96443 = AXIS2_PLACEMENT_3D('',#96444,#96445,#96446); +#96444 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); +#96445 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96446 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96447 = DEFINITIONAL_REPRESENTATION('',(#96448),#96452); +#96448 = LINE('',#96449,#96450); +#96449 = CARTESIAN_POINT('',(-2.22044604925E-016,-0.527847992439)); +#96450 = VECTOR('',#96451,1.); +#96451 = DIRECTION('',(-1.,0.E+000)); +#96452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96453 = ORIENTED_EDGE('',*,*,#96454,.T.); +#96454 = EDGE_CURVE('',#96427,#96369,#96455,.T.); +#96455 = SURFACE_CURVE('',#96456,(#96460,#96467),.PCURVE_S1.); +#96456 = LINE('',#96457,#96458); +#96457 = CARTESIAN_POINT('',(10.,8.65,0.75)); +#96458 = VECTOR('',#96459,1.); +#96459 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#96460 = PCURVE('',#94664,#96461); +#96461 = DEFINITIONAL_REPRESENTATION('',(#96462),#96466); +#96462 = LINE('',#96463,#96464); +#96463 = CARTESIAN_POINT('',(-0.65,8.65)); +#96464 = VECTOR('',#96465,1.); +#96465 = DIRECTION('',(0.E+000,1.)); +#96466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96467 = PCURVE('',#96468,#96473); +#96468 = PLANE('',#96469); +#96469 = AXIS2_PLACEMENT_3D('',#96470,#96471,#96472); +#96470 = CARTESIAN_POINT('',(10.527847992439,8.65,0.75)); +#96471 = DIRECTION('',(3.563627120235E-016,-1.582568352025E-031,1.)); +#96472 = DIRECTION('',(1.,0.E+000,-3.563627120235E-016)); +#96473 = DEFINITIONAL_REPRESENTATION('',(#96474),#96478); +#96474 = LINE('',#96475,#96476); +#96475 = CARTESIAN_POINT('',(-0.527847992439,5.371120320375E-048)); +#96476 = VECTOR('',#96477,1.); +#96477 = DIRECTION('',(4.440892098501E-016,1.)); +#96478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96479 = FACE_BOUND('',#96480,.T.); +#96480 = EDGE_LOOP('',(#96481,#96511,#96534,#96557)); +#96481 = ORIENTED_EDGE('',*,*,#96482,.T.); +#96482 = EDGE_CURVE('',#96483,#96485,#96487,.T.); +#96483 = VERTEX_POINT('',#96484); +#96484 = CARTESIAN_POINT('',(10.,9.8,1.2)); +#96485 = VERTEX_POINT('',#96486); +#96486 = CARTESIAN_POINT('',(10.,0.2,1.2)); +#96487 = SURFACE_CURVE('',#96488,(#96492,#96499),.PCURVE_S1.); +#96488 = LINE('',#96489,#96490); +#96489 = CARTESIAN_POINT('',(10.,0.E+000,1.2)); +#96490 = VECTOR('',#96491,1.); +#96491 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96492 = PCURVE('',#94664,#96493); +#96493 = DEFINITIONAL_REPRESENTATION('',(#96494),#96498); +#96494 = LINE('',#96495,#96496); +#96495 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#96496 = VECTOR('',#96497,1.); +#96497 = DIRECTION('',(0.E+000,-1.)); +#96498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96499 = PCURVE('',#96500,#96505); +#96500 = PLANE('',#96501); +#96501 = AXIS2_PLACEMENT_3D('',#96502,#96503,#96504); +#96502 = CARTESIAN_POINT('',(9.8,10.,1.4)); +#96503 = DIRECTION('',(-0.707106781187,0.E+000,-0.707106781187)); +#96504 = DIRECTION('',(-0.707106781187,0.E+000,0.707106781187)); +#96505 = DEFINITIONAL_REPRESENTATION('',(#96506),#96510); +#96506 = LINE('',#96507,#96508); +#96507 = CARTESIAN_POINT('',(-0.282842712475,-10.)); +#96508 = VECTOR('',#96509,1.); +#96509 = DIRECTION('',(0.E+000,-1.)); +#96510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96511 = ORIENTED_EDGE('',*,*,#96512,.T.); +#96512 = EDGE_CURVE('',#96485,#96513,#96515,.T.); +#96513 = VERTEX_POINT('',#96514); +#96514 = CARTESIAN_POINT('',(10.,0.2,0.E+000)); +#96515 = SURFACE_CURVE('',#96516,(#96520,#96527),.PCURVE_S1.); +#96516 = LINE('',#96517,#96518); +#96517 = CARTESIAN_POINT('',(10.,0.2,1.4)); +#96518 = VECTOR('',#96519,1.); +#96519 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96520 = PCURVE('',#94664,#96521); +#96521 = DEFINITIONAL_REPRESENTATION('',(#96522),#96526); +#96522 = LINE('',#96523,#96524); +#96523 = CARTESIAN_POINT('',(0.E+000,0.2)); +#96524 = VECTOR('',#96525,1.); +#96525 = DIRECTION('',(-1.,0.E+000)); +#96526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96527 = PCURVE('',#91797,#96528); +#96528 = DEFINITIONAL_REPRESENTATION('',(#96529),#96533); +#96529 = LINE('',#96530,#96531); +#96530 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96531 = VECTOR('',#96532,1.); +#96532 = DIRECTION('',(0.E+000,-1.)); +#96533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96534 = ORIENTED_EDGE('',*,*,#96535,.T.); +#96535 = EDGE_CURVE('',#96513,#96536,#96538,.T.); +#96536 = VERTEX_POINT('',#96537); +#96537 = CARTESIAN_POINT('',(10.,9.8,0.E+000)); +#96538 = SURFACE_CURVE('',#96539,(#96543,#96550),.PCURVE_S1.); +#96539 = LINE('',#96540,#96541); +#96540 = CARTESIAN_POINT('',(10.,0.E+000,0.E+000)); +#96541 = VECTOR('',#96542,1.); +#96542 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96543 = PCURVE('',#94664,#96544); +#96544 = DEFINITIONAL_REPRESENTATION('',(#96545),#96549); +#96545 = LINE('',#96546,#96547); +#96546 = CARTESIAN_POINT('',(-1.4,0.E+000)); +#96547 = VECTOR('',#96548,1.); +#96548 = DIRECTION('',(0.E+000,1.)); +#96549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96550 = PCURVE('',#88864,#96551); +#96551 = DEFINITIONAL_REPRESENTATION('',(#96552),#96556); +#96552 = LINE('',#96553,#96554); +#96553 = CARTESIAN_POINT('',(-10.,-10.)); +#96554 = VECTOR('',#96555,1.); +#96555 = DIRECTION('',(0.E+000,1.)); +#96556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96557 = ORIENTED_EDGE('',*,*,#96558,.T.); +#96558 = EDGE_CURVE('',#96536,#96483,#96559,.T.); +#96559 = SURFACE_CURVE('',#96560,(#96564,#96571),.PCURVE_S1.); +#96560 = LINE('',#96561,#96562); +#96561 = CARTESIAN_POINT('',(10.,9.8,1.4)); +#96562 = VECTOR('',#96563,1.); +#96563 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96564 = PCURVE('',#94664,#96565); +#96565 = DEFINITIONAL_REPRESENTATION('',(#96566),#96570); +#96566 = LINE('',#96567,#96568); +#96567 = CARTESIAN_POINT('',(0.E+000,9.8)); +#96568 = VECTOR('',#96569,1.); +#96569 = DIRECTION('',(1.,0.E+000)); +#96570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96571 = PCURVE('',#88946,#96572); +#96572 = DEFINITIONAL_REPRESENTATION('',(#96573),#96577); +#96573 = LINE('',#96574,#96575); +#96574 = CARTESIAN_POINT('',(0.282842712475,0.E+000)); +#96575 = VECTOR('',#96576,1.); +#96576 = DIRECTION('',(0.E+000,1.)); +#96577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96578 = ADVANCED_FACE('',(#96579,#96607),#88803,.F.); +#96579 = FACE_BOUND('',#96580,.T.); +#96580 = EDGE_LOOP('',(#96581,#96606)); +#96581 = ORIENTED_EDGE('',*,*,#96582,.F.); +#96582 = EDGE_CURVE('',#88762,#88788,#96583,.T.); +#96583 = SURFACE_CURVE('',#96584,(#96589,#96600),.PCURVE_S1.); +#96584 = CIRCLE('',#96585,0.345974717232); +#96585 = AXIS2_PLACEMENT_3D('',#96586,#96587,#96588); +#96586 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.4)); +#96587 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96588 = DIRECTION('',(1.,0.E+000,0.E+000)); +#96589 = PCURVE('',#88803,#96590); +#96590 = DEFINITIONAL_REPRESENTATION('',(#96591),#96599); +#96591 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#96592,#96593,#96594,#96595 + ,#96596,#96597,#96598),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#94200 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); -#94201 = CARTESIAN_POINT('',(-1.224883566201,-8.44200504329)); -#94202 = CARTESIAN_POINT('',(-0.705921490353,-8.74162793748)); -#94203 = CARTESIAN_POINT('',(-0.186959414504,-9.04125083167)); -#94204 = CARTESIAN_POINT('',(-0.705921490353,-9.34087372586)); -#94205 = CARTESIAN_POINT('',(-1.224883566201,-9.64049662005)); -#94206 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); -#94207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#96592 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); +#96593 = CARTESIAN_POINT('',(-1.224883566201,-8.44200504329)); +#96594 = CARTESIAN_POINT('',(-0.705921490353,-8.74162793748)); +#96595 = CARTESIAN_POINT('',(-0.186959414504,-9.04125083167)); +#96596 = CARTESIAN_POINT('',(-0.705921490353,-9.34087372586)); +#96597 = CARTESIAN_POINT('',(-1.224883566201,-9.64049662005)); +#96598 = CARTESIAN_POINT('',(-1.224883566201,-9.04125083167)); +#96599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96600 = PCURVE('',#88776,#96601); +#96601 = DEFINITIONAL_REPRESENTATION('',(#96602),#96605); +#96602 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96603,#96604),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); +#96603 = CARTESIAN_POINT('',(0.E+000,0.3)); +#96604 = CARTESIAN_POINT('',(3.14159265359,0.3)); +#96605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96606 = ORIENTED_EDGE('',*,*,#88787,.F.); +#96607 = FACE_BOUND('',#96608,.T.); +#96608 = EDGE_LOOP('',(#96609,#96634,#96657,#96680)); +#96609 = ORIENTED_EDGE('',*,*,#96610,.T.); +#96610 = EDGE_CURVE('',#96611,#96613,#96615,.T.); +#96611 = VERTEX_POINT('',#96612); +#96612 = CARTESIAN_POINT('',(0.2,9.8,1.4)); +#96613 = VERTEX_POINT('',#96614); +#96614 = CARTESIAN_POINT('',(0.2,0.2,1.4)); +#96615 = SURFACE_CURVE('',#96616,(#96620,#96627),.PCURVE_S1.); +#96616 = LINE('',#96617,#96618); +#96617 = CARTESIAN_POINT('',(0.2,10.,1.4)); +#96618 = VECTOR('',#96619,1.); +#96619 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96620 = PCURVE('',#88803,#96621); +#96621 = DEFINITIONAL_REPRESENTATION('',(#96622),#96626); +#96622 = LINE('',#96623,#96624); +#96623 = CARTESIAN_POINT('',(-0.2,0.E+000)); +#96624 = VECTOR('',#96625,1.); +#96625 = DIRECTION('',(0.E+000,-1.)); +#96626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96627 = PCURVE('',#94617,#96628); +#96628 = DEFINITIONAL_REPRESENTATION('',(#96629),#96633); +#96629 = LINE('',#96630,#96631); +#96630 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96631 = VECTOR('',#96632,1.); +#96632 = DIRECTION('',(0.E+000,-1.)); +#96633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96634 = ORIENTED_EDGE('',*,*,#96635,.T.); +#96635 = EDGE_CURVE('',#96613,#96636,#96638,.T.); +#96636 = VERTEX_POINT('',#96637); +#96637 = CARTESIAN_POINT('',(9.8,0.2,1.4)); +#96638 = SURFACE_CURVE('',#96639,(#96643,#96650),.PCURVE_S1.); +#96639 = LINE('',#96640,#96641); +#96640 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); +#96641 = VECTOR('',#96642,1.); +#96642 = DIRECTION('',(1.,0.E+000,0.E+000)); +#96643 = PCURVE('',#88803,#96644); +#96644 = DEFINITIONAL_REPRESENTATION('',(#96645),#96649); +#96645 = LINE('',#96646,#96647); +#96646 = CARTESIAN_POINT('',(0.E+000,-9.8)); +#96647 = VECTOR('',#96648,1.); +#96648 = DIRECTION('',(-1.,0.E+000)); +#96649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96650 = PCURVE('',#91720,#96651); +#96651 = DEFINITIONAL_REPRESENTATION('',(#96652),#96656); +#96652 = LINE('',#96653,#96654); +#96653 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96654 = VECTOR('',#96655,1.); +#96655 = DIRECTION('',(0.E+000,1.)); +#96656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96657 = ORIENTED_EDGE('',*,*,#96658,.T.); +#96658 = EDGE_CURVE('',#96636,#96659,#96661,.T.); +#96659 = VERTEX_POINT('',#96660); +#96660 = CARTESIAN_POINT('',(9.8,9.8,1.4)); +#96661 = SURFACE_CURVE('',#96662,(#96666,#96673),.PCURVE_S1.); +#96662 = LINE('',#96663,#96664); +#96663 = CARTESIAN_POINT('',(9.8,10.,1.4)); +#96664 = VECTOR('',#96665,1.); +#96665 = DIRECTION('',(0.E+000,1.,0.E+000)); +#96666 = PCURVE('',#88803,#96667); +#96667 = DEFINITIONAL_REPRESENTATION('',(#96668),#96672); +#96668 = LINE('',#96669,#96670); +#96669 = CARTESIAN_POINT('',(-9.8,0.E+000)); +#96670 = VECTOR('',#96671,1.); +#96671 = DIRECTION('',(0.E+000,1.)); +#96672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96673 = PCURVE('',#96500,#96674); +#96674 = DEFINITIONAL_REPRESENTATION('',(#96675),#96679); +#96675 = LINE('',#96676,#96677); +#96676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96677 = VECTOR('',#96678,1.); +#96678 = DIRECTION('',(0.E+000,1.)); +#96679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96680 = ORIENTED_EDGE('',*,*,#96681,.T.); +#96681 = EDGE_CURVE('',#96659,#96611,#96682,.T.); +#96682 = SURFACE_CURVE('',#96683,(#96687,#96694),.PCURVE_S1.); +#96683 = LINE('',#96684,#96685); +#96684 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); +#96685 = VECTOR('',#96686,1.); +#96686 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96687 = PCURVE('',#88803,#96688); +#96688 = DEFINITIONAL_REPRESENTATION('',(#96689),#96693); +#96689 = LINE('',#96690,#96691); +#96690 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#96691 = VECTOR('',#96692,1.); +#96692 = DIRECTION('',(1.,0.E+000)); +#96693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94208 = PCURVE('',#86384,#94209); -#94209 = DEFINITIONAL_REPRESENTATION('',(#94210),#94213); -#94210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94211,#94212),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,3.14159265359),.PIECEWISE_BEZIER_KNOTS.); -#94211 = CARTESIAN_POINT('',(0.E+000,0.3)); -#94212 = CARTESIAN_POINT('',(3.14159265359,0.3)); -#94213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94214 = ORIENTED_EDGE('',*,*,#86395,.F.); -#94215 = FACE_BOUND('',#94216,.T.); -#94216 = EDGE_LOOP('',(#94217,#94242,#94265,#94288)); -#94217 = ORIENTED_EDGE('',*,*,#94218,.T.); -#94218 = EDGE_CURVE('',#94219,#94221,#94223,.T.); -#94219 = VERTEX_POINT('',#94220); -#94220 = CARTESIAN_POINT('',(0.2,9.8,1.4)); -#94221 = VERTEX_POINT('',#94222); -#94222 = CARTESIAN_POINT('',(0.2,0.2,1.4)); -#94223 = SURFACE_CURVE('',#94224,(#94228,#94235),.PCURVE_S1.); -#94224 = LINE('',#94225,#94226); -#94225 = CARTESIAN_POINT('',(0.2,10.,1.4)); -#94226 = VECTOR('',#94227,1.); -#94227 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94228 = PCURVE('',#86411,#94229); -#94229 = DEFINITIONAL_REPRESENTATION('',(#94230),#94234); -#94230 = LINE('',#94231,#94232); -#94231 = CARTESIAN_POINT('',(-0.2,0.E+000)); -#94232 = VECTOR('',#94233,1.); -#94233 = DIRECTION('',(0.E+000,-1.)); -#94234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94235 = PCURVE('',#92225,#94236); -#94236 = DEFINITIONAL_REPRESENTATION('',(#94237),#94241); -#94237 = LINE('',#94238,#94239); -#94238 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94239 = VECTOR('',#94240,1.); -#94240 = DIRECTION('',(0.E+000,-1.)); -#94241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94242 = ORIENTED_EDGE('',*,*,#94243,.T.); -#94243 = EDGE_CURVE('',#94221,#94244,#94246,.T.); -#94244 = VERTEX_POINT('',#94245); -#94245 = CARTESIAN_POINT('',(9.8,0.2,1.4)); -#94246 = SURFACE_CURVE('',#94247,(#94251,#94258),.PCURVE_S1.); -#94247 = LINE('',#94248,#94249); -#94248 = CARTESIAN_POINT('',(0.E+000,0.2,1.4)); -#94249 = VECTOR('',#94250,1.); -#94250 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94251 = PCURVE('',#86411,#94252); -#94252 = DEFINITIONAL_REPRESENTATION('',(#94253),#94257); -#94253 = LINE('',#94254,#94255); -#94254 = CARTESIAN_POINT('',(0.E+000,-9.8)); -#94255 = VECTOR('',#94256,1.); -#94256 = DIRECTION('',(-1.,0.E+000)); -#94257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94258 = PCURVE('',#89328,#94259); -#94259 = DEFINITIONAL_REPRESENTATION('',(#94260),#94264); -#94260 = LINE('',#94261,#94262); -#94261 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94262 = VECTOR('',#94263,1.); -#94263 = DIRECTION('',(0.E+000,1.)); -#94264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94265 = ORIENTED_EDGE('',*,*,#94266,.T.); -#94266 = EDGE_CURVE('',#94244,#94267,#94269,.T.); -#94267 = VERTEX_POINT('',#94268); -#94268 = CARTESIAN_POINT('',(9.8,9.8,1.4)); -#94269 = SURFACE_CURVE('',#94270,(#94274,#94281),.PCURVE_S1.); -#94270 = LINE('',#94271,#94272); -#94271 = CARTESIAN_POINT('',(9.8,10.,1.4)); -#94272 = VECTOR('',#94273,1.); -#94273 = DIRECTION('',(0.E+000,1.,0.E+000)); -#94274 = PCURVE('',#86411,#94275); -#94275 = DEFINITIONAL_REPRESENTATION('',(#94276),#94280); -#94276 = LINE('',#94277,#94278); -#94277 = CARTESIAN_POINT('',(-9.8,0.E+000)); -#94278 = VECTOR('',#94279,1.); -#94279 = DIRECTION('',(0.E+000,1.)); -#94280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94281 = PCURVE('',#94108,#94282); -#94282 = DEFINITIONAL_REPRESENTATION('',(#94283),#94287); -#94283 = LINE('',#94284,#94285); -#94284 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94285 = VECTOR('',#94286,1.); -#94286 = DIRECTION('',(0.E+000,1.)); -#94287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94288 = ORIENTED_EDGE('',*,*,#94289,.T.); -#94289 = EDGE_CURVE('',#94267,#94219,#94290,.T.); -#94290 = SURFACE_CURVE('',#94291,(#94295,#94302),.PCURVE_S1.); -#94291 = LINE('',#94292,#94293); -#94292 = CARTESIAN_POINT('',(0.E+000,9.8,1.4)); -#94293 = VECTOR('',#94294,1.); -#94294 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94295 = PCURVE('',#86411,#94296); -#94296 = DEFINITIONAL_REPRESENTATION('',(#94297),#94301); -#94297 = LINE('',#94298,#94299); -#94298 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#94299 = VECTOR('',#94300,1.); -#94300 = DIRECTION('',(1.,0.E+000)); -#94301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94302 = PCURVE('',#86528,#94303); -#94303 = DEFINITIONAL_REPRESENTATION('',(#94304),#94308); -#94304 = LINE('',#94305,#94306); -#94305 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94306 = VECTOR('',#94307,1.); -#94307 = DIRECTION('',(0.E+000,-1.)); -#94308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94309 = ADVANCED_FACE('',(#94310),#86472,.T.); -#94310 = FACE_BOUND('',#94311,.T.); -#94311 = EDGE_LOOP('',(#94312,#94313,#94334,#94335,#94356,#94357,#94378, - #94379)); -#94312 = ORIENTED_EDGE('',*,*,#89368,.F.); -#94313 = ORIENTED_EDGE('',*,*,#94314,.T.); -#94314 = EDGE_CURVE('',#89341,#92164,#94315,.T.); -#94315 = SURFACE_CURVE('',#94316,(#94320,#94327),.PCURVE_S1.); -#94316 = LINE('',#94317,#94318); -#94317 = CARTESIAN_POINT('',(-4.9,5.1,0.E+000)); -#94318 = VECTOR('',#94319,1.); -#94319 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#94320 = PCURVE('',#86472,#94321); -#94321 = DEFINITIONAL_REPRESENTATION('',(#94322),#94326); -#94322 = LINE('',#94323,#94324); -#94323 = CARTESIAN_POINT('',(4.9,-4.9)); -#94324 = VECTOR('',#94325,1.); -#94325 = DIRECTION('',(0.707106781187,0.707106781187)); -#94326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94327 = PCURVE('',#89356,#94328); -#94328 = DEFINITIONAL_REPRESENTATION('',(#94329),#94333); -#94329 = LINE('',#94330,#94331); -#94330 = CARTESIAN_POINT('',(7.212489168103,-1.4)); -#94331 = VECTOR('',#94332,1.); -#94332 = DIRECTION('',(1.,0.E+000)); -#94333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94334 = ORIENTED_EDGE('',*,*,#92161,.F.); -#94335 = ORIENTED_EDGE('',*,*,#94336,.T.); -#94336 = EDGE_CURVE('',#92162,#86452,#94337,.T.); -#94337 = SURFACE_CURVE('',#94338,(#94342,#94349),.PCURVE_S1.); -#94338 = LINE('',#94339,#94340); -#94339 = CARTESIAN_POINT('',(0.1,9.9,0.E+000)); -#94340 = VECTOR('',#94341,1.); -#94341 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#94342 = PCURVE('',#86472,#94343); -#94343 = DEFINITIONAL_REPRESENTATION('',(#94344),#94348); -#94344 = LINE('',#94345,#94346); -#94345 = CARTESIAN_POINT('',(-0.1,-1.E-001)); -#94346 = VECTOR('',#94347,1.); -#94347 = DIRECTION('',(-0.707106781187,0.707106781187)); -#94348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94349 = PCURVE('',#86500,#94350); -#94350 = DEFINITIONAL_REPRESENTATION('',(#94351),#94355); -#94351 = LINE('',#94352,#94353); -#94352 = CARTESIAN_POINT('',(0.141421356237,-1.4)); -#94353 = VECTOR('',#94354,1.); -#94354 = DIRECTION('',(1.,0.E+000)); -#94355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94356 = ORIENTED_EDGE('',*,*,#86449,.F.); -#94357 = ORIENTED_EDGE('',*,*,#94358,.T.); -#94358 = EDGE_CURVE('',#86450,#94144,#94359,.T.); -#94359 = SURFACE_CURVE('',#94360,(#94364,#94371),.PCURVE_S1.); -#94360 = LINE('',#94361,#94362); -#94361 = CARTESIAN_POINT('',(4.9,14.9,0.E+000)); -#94362 = VECTOR('',#94363,1.); -#94363 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#94364 = PCURVE('',#86472,#94365); -#94365 = DEFINITIONAL_REPRESENTATION('',(#94366),#94370); -#94366 = LINE('',#94367,#94368); -#94367 = CARTESIAN_POINT('',(-4.9,4.9)); -#94368 = VECTOR('',#94369,1.); -#94369 = DIRECTION('',(-0.707106781187,-0.707106781187)); -#94370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94371 = PCURVE('',#86554,#94372); -#94372 = DEFINITIONAL_REPRESENTATION('',(#94373),#94377); -#94373 = LINE('',#94374,#94375); -#94374 = CARTESIAN_POINT('',(-6.929646455628,-1.4)); -#94375 = VECTOR('',#94376,1.); -#94376 = DIRECTION('',(1.,0.E+000)); -#94377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94378 = ORIENTED_EDGE('',*,*,#94143,.F.); -#94379 = ORIENTED_EDGE('',*,*,#94380,.T.); -#94380 = EDGE_CURVE('',#94121,#89369,#94381,.T.); -#94381 = SURFACE_CURVE('',#94382,(#94386,#94393),.PCURVE_S1.); -#94382 = LINE('',#94383,#94384); -#94383 = CARTESIAN_POINT('',(9.9,9.999999999999E-002,0.E+000)); -#94384 = VECTOR('',#94385,1.); -#94385 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#94386 = PCURVE('',#86472,#94387); -#94387 = DEFINITIONAL_REPRESENTATION('',(#94388),#94392); -#94388 = LINE('',#94389,#94390); -#94389 = CARTESIAN_POINT('',(-9.9,-9.9)); -#94390 = VECTOR('',#94391,1.); -#94391 = DIRECTION('',(0.707106781187,-0.707106781187)); -#94392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94393 = PCURVE('',#89405,#94394); -#94394 = DEFINITIONAL_REPRESENTATION('',(#94395),#94399); -#94395 = LINE('',#94396,#94397); -#94396 = CARTESIAN_POINT('',(0.141421356237,-1.4)); -#94397 = VECTOR('',#94398,1.); -#94398 = DIRECTION('',(1.,0.E+000)); -#94399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94400 = ADVANCED_FACE('',(#94401),#94415,.T.); -#94401 = FACE_BOUND('',#94402,.T.); -#94402 = EDGE_LOOP('',(#94403,#94433,#94461,#94484)); -#94403 = ORIENTED_EDGE('',*,*,#94404,.T.); -#94404 = EDGE_CURVE('',#94405,#94407,#94409,.T.); -#94405 = VERTEX_POINT('',#94406); -#94406 = CARTESIAN_POINT('',(1.15,-0.740726081328,-0.208196358798)); -#94407 = VERTEX_POINT('',#94408); -#94408 = CARTESIAN_POINT('',(1.15,-1.,-0.208196358798)); -#94409 = SURFACE_CURVE('',#94410,(#94414,#94426),.PCURVE_S1.); -#94410 = LINE('',#94411,#94412); -#94411 = CARTESIAN_POINT('',(1.15,-0.740726081328,-0.208196358798)); -#94412 = VECTOR('',#94413,1.); -#94413 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94414 = PCURVE('',#94415,#94420); -#94415 = PLANE('',#94416); -#94416 = AXIS2_PLACEMENT_3D('',#94417,#94418,#94419); -#94417 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#94418 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94419 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94420 = DEFINITIONAL_REPRESENTATION('',(#94421),#94425); -#94421 = LINE('',#94422,#94423); -#94422 = CARTESIAN_POINT('',(-8.85,0.E+000)); -#94423 = VECTOR('',#94424,1.); -#94424 = DIRECTION('',(0.E+000,-1.)); -#94425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94426 = PCURVE('',#89270,#94427); -#94427 = DEFINITIONAL_REPRESENTATION('',(#94428),#94432); -#94428 = LINE('',#94429,#94430); -#94429 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#94430 = VECTOR('',#94431,1.); -#94431 = DIRECTION('',(0.E+000,-1.)); -#94432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94433 = ORIENTED_EDGE('',*,*,#94434,.T.); -#94434 = EDGE_CURVE('',#94407,#94435,#94437,.T.); -#94435 = VERTEX_POINT('',#94436); -#94436 = CARTESIAN_POINT('',(1.35,-1.,-0.208196358798)); -#94437 = SURFACE_CURVE('',#94438,(#94442,#94449),.PCURVE_S1.); -#94438 = LINE('',#94439,#94440); -#94439 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#94440 = VECTOR('',#94441,1.); -#94441 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94442 = PCURVE('',#94415,#94443); -#94443 = DEFINITIONAL_REPRESENTATION('',(#94444),#94448); -#94444 = LINE('',#94445,#94446); -#94445 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#94446 = VECTOR('',#94447,1.); -#94447 = DIRECTION('',(1.,0.E+000)); -#94448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94449 = PCURVE('',#94450,#94455); -#94450 = PLANE('',#94451); -#94451 = AXIS2_PLACEMENT_3D('',#94452,#94453,#94454); -#94452 = CARTESIAN_POINT('',(1.25,-1.,-0.258196742327)); -#94453 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#94454 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#94455 = DEFINITIONAL_REPRESENTATION('',(#94456),#94460); -#94456 = LINE('',#94457,#94458); -#94457 = CARTESIAN_POINT('',(-5.000038352949E-002,8.75)); -#94458 = VECTOR('',#94459,1.); -#94459 = DIRECTION('',(0.E+000,1.)); -#94460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94461 = ORIENTED_EDGE('',*,*,#94462,.F.); -#94462 = EDGE_CURVE('',#94463,#94435,#94465,.T.); -#94463 = VERTEX_POINT('',#94464); -#94464 = CARTESIAN_POINT('',(1.35,-0.740726081328,-0.208196358798)); -#94465 = SURFACE_CURVE('',#94466,(#94470,#94477),.PCURVE_S1.); -#94466 = LINE('',#94467,#94468); -#94467 = CARTESIAN_POINT('',(1.35,-0.740726081328,-0.208196358798)); -#94468 = VECTOR('',#94469,1.); -#94469 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94470 = PCURVE('',#94415,#94471); -#94471 = DEFINITIONAL_REPRESENTATION('',(#94472),#94476); -#94472 = LINE('',#94473,#94474); -#94473 = CARTESIAN_POINT('',(-8.65,0.E+000)); -#94474 = VECTOR('',#94475,1.); -#94475 = DIRECTION('',(0.E+000,-1.)); -#94476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94477 = PCURVE('',#89214,#94478); -#94478 = DEFINITIONAL_REPRESENTATION('',(#94479),#94483); -#94479 = LINE('',#94480,#94481); -#94480 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#94481 = VECTOR('',#94482,1.); -#94482 = DIRECTION('',(0.E+000,-1.)); -#94483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#96694 = PCURVE('',#88920,#96695); +#96695 = DEFINITIONAL_REPRESENTATION('',(#96696),#96700); +#96696 = LINE('',#96697,#96698); +#96697 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96698 = VECTOR('',#96699,1.); +#96699 = DIRECTION('',(0.E+000,-1.)); +#96700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94484 = ORIENTED_EDGE('',*,*,#94485,.T.); -#94485 = EDGE_CURVE('',#94463,#94405,#94486,.T.); -#94486 = SURFACE_CURVE('',#94487,(#94491,#94498),.PCURVE_S1.); -#94487 = LINE('',#94488,#94489); -#94488 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#94489 = VECTOR('',#94490,1.); -#94490 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94491 = PCURVE('',#94415,#94492); -#94492 = DEFINITIONAL_REPRESENTATION('',(#94493),#94497); -#94493 = LINE('',#94494,#94495); -#94494 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94495 = VECTOR('',#94496,1.); -#94496 = DIRECTION('',(-1.,0.E+000)); -#94497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94498 = PCURVE('',#94499,#94504); -#94499 = CYLINDRICAL_SURFACE('',#94500,0.208574704164); -#94500 = AXIS2_PLACEMENT_3D('',#94501,#94502,#94503); -#94501 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#94502 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94503 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94504 = DEFINITIONAL_REPRESENTATION('',(#94505),#94508); -#94505 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94506,#94507),.UNSPECIFIED., +#96701 = ADVANCED_FACE('',(#96702),#88864,.T.); +#96702 = FACE_BOUND('',#96703,.T.); +#96703 = EDGE_LOOP('',(#96704,#96705,#96726,#96727,#96748,#96749,#96770, + #96771)); +#96704 = ORIENTED_EDGE('',*,*,#91760,.F.); +#96705 = ORIENTED_EDGE('',*,*,#96706,.T.); +#96706 = EDGE_CURVE('',#91733,#94556,#96707,.T.); +#96707 = SURFACE_CURVE('',#96708,(#96712,#96719),.PCURVE_S1.); +#96708 = LINE('',#96709,#96710); +#96709 = CARTESIAN_POINT('',(-4.9,5.1,0.E+000)); +#96710 = VECTOR('',#96711,1.); +#96711 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#96712 = PCURVE('',#88864,#96713); +#96713 = DEFINITIONAL_REPRESENTATION('',(#96714),#96718); +#96714 = LINE('',#96715,#96716); +#96715 = CARTESIAN_POINT('',(4.9,-4.9)); +#96716 = VECTOR('',#96717,1.); +#96717 = DIRECTION('',(0.707106781187,0.707106781187)); +#96718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96719 = PCURVE('',#91748,#96720); +#96720 = DEFINITIONAL_REPRESENTATION('',(#96721),#96725); +#96721 = LINE('',#96722,#96723); +#96722 = CARTESIAN_POINT('',(7.212489168103,-1.4)); +#96723 = VECTOR('',#96724,1.); +#96724 = DIRECTION('',(1.,0.E+000)); +#96725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96726 = ORIENTED_EDGE('',*,*,#94553,.F.); +#96727 = ORIENTED_EDGE('',*,*,#96728,.T.); +#96728 = EDGE_CURVE('',#94554,#88844,#96729,.T.); +#96729 = SURFACE_CURVE('',#96730,(#96734,#96741),.PCURVE_S1.); +#96730 = LINE('',#96731,#96732); +#96731 = CARTESIAN_POINT('',(0.1,9.9,0.E+000)); +#96732 = VECTOR('',#96733,1.); +#96733 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#96734 = PCURVE('',#88864,#96735); +#96735 = DEFINITIONAL_REPRESENTATION('',(#96736),#96740); +#96736 = LINE('',#96737,#96738); +#96737 = CARTESIAN_POINT('',(-0.1,-1.E-001)); +#96738 = VECTOR('',#96739,1.); +#96739 = DIRECTION('',(-0.707106781187,0.707106781187)); +#96740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96741 = PCURVE('',#88892,#96742); +#96742 = DEFINITIONAL_REPRESENTATION('',(#96743),#96747); +#96743 = LINE('',#96744,#96745); +#96744 = CARTESIAN_POINT('',(0.141421356237,-1.4)); +#96745 = VECTOR('',#96746,1.); +#96746 = DIRECTION('',(1.,0.E+000)); +#96747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96748 = ORIENTED_EDGE('',*,*,#88841,.F.); +#96749 = ORIENTED_EDGE('',*,*,#96750,.T.); +#96750 = EDGE_CURVE('',#88842,#96536,#96751,.T.); +#96751 = SURFACE_CURVE('',#96752,(#96756,#96763),.PCURVE_S1.); +#96752 = LINE('',#96753,#96754); +#96753 = CARTESIAN_POINT('',(4.9,14.9,0.E+000)); +#96754 = VECTOR('',#96755,1.); +#96755 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#96756 = PCURVE('',#88864,#96757); +#96757 = DEFINITIONAL_REPRESENTATION('',(#96758),#96762); +#96758 = LINE('',#96759,#96760); +#96759 = CARTESIAN_POINT('',(-4.9,4.9)); +#96760 = VECTOR('',#96761,1.); +#96761 = DIRECTION('',(-0.707106781187,-0.707106781187)); +#96762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96763 = PCURVE('',#88946,#96764); +#96764 = DEFINITIONAL_REPRESENTATION('',(#96765),#96769); +#96765 = LINE('',#96766,#96767); +#96766 = CARTESIAN_POINT('',(-6.929646455628,-1.4)); +#96767 = VECTOR('',#96768,1.); +#96768 = DIRECTION('',(1.,0.E+000)); +#96769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96770 = ORIENTED_EDGE('',*,*,#96535,.F.); +#96771 = ORIENTED_EDGE('',*,*,#96772,.T.); +#96772 = EDGE_CURVE('',#96513,#91761,#96773,.T.); +#96773 = SURFACE_CURVE('',#96774,(#96778,#96785),.PCURVE_S1.); +#96774 = LINE('',#96775,#96776); +#96775 = CARTESIAN_POINT('',(9.9,9.999999999999E-002,0.E+000)); +#96776 = VECTOR('',#96777,1.); +#96777 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#96778 = PCURVE('',#88864,#96779); +#96779 = DEFINITIONAL_REPRESENTATION('',(#96780),#96784); +#96780 = LINE('',#96781,#96782); +#96781 = CARTESIAN_POINT('',(-9.9,-9.9)); +#96782 = VECTOR('',#96783,1.); +#96783 = DIRECTION('',(0.707106781187,-0.707106781187)); +#96784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96785 = PCURVE('',#91797,#96786); +#96786 = DEFINITIONAL_REPRESENTATION('',(#96787),#96791); +#96787 = LINE('',#96788,#96789); +#96788 = CARTESIAN_POINT('',(0.141421356237,-1.4)); +#96789 = VECTOR('',#96790,1.); +#96790 = DIRECTION('',(1.,0.E+000)); +#96791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96792 = ADVANCED_FACE('',(#96793),#96807,.T.); +#96793 = FACE_BOUND('',#96794,.T.); +#96794 = EDGE_LOOP('',(#96795,#96825,#96853,#96876)); +#96795 = ORIENTED_EDGE('',*,*,#96796,.T.); +#96796 = EDGE_CURVE('',#96797,#96799,#96801,.T.); +#96797 = VERTEX_POINT('',#96798); +#96798 = CARTESIAN_POINT('',(1.15,-0.740726081328,-0.208196358798)); +#96799 = VERTEX_POINT('',#96800); +#96800 = CARTESIAN_POINT('',(1.15,-1.,-0.208196358798)); +#96801 = SURFACE_CURVE('',#96802,(#96806,#96818),.PCURVE_S1.); +#96802 = LINE('',#96803,#96804); +#96803 = CARTESIAN_POINT('',(1.15,-0.740726081328,-0.208196358798)); +#96804 = VECTOR('',#96805,1.); +#96805 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96806 = PCURVE('',#96807,#96812); +#96807 = PLANE('',#96808); +#96808 = AXIS2_PLACEMENT_3D('',#96809,#96810,#96811); +#96809 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#96810 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96811 = DIRECTION('',(1.,0.E+000,0.E+000)); +#96812 = DEFINITIONAL_REPRESENTATION('',(#96813),#96817); +#96813 = LINE('',#96814,#96815); +#96814 = CARTESIAN_POINT('',(-8.85,0.E+000)); +#96815 = VECTOR('',#96816,1.); +#96816 = DIRECTION('',(0.E+000,-1.)); +#96817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96818 = PCURVE('',#91662,#96819); +#96819 = DEFINITIONAL_REPRESENTATION('',(#96820),#96824); +#96820 = LINE('',#96821,#96822); +#96821 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#96822 = VECTOR('',#96823,1.); +#96823 = DIRECTION('',(0.E+000,-1.)); +#96824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96825 = ORIENTED_EDGE('',*,*,#96826,.T.); +#96826 = EDGE_CURVE('',#96799,#96827,#96829,.T.); +#96827 = VERTEX_POINT('',#96828); +#96828 = CARTESIAN_POINT('',(1.35,-1.,-0.208196358798)); +#96829 = SURFACE_CURVE('',#96830,(#96834,#96841),.PCURVE_S1.); +#96830 = LINE('',#96831,#96832); +#96831 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#96832 = VECTOR('',#96833,1.); +#96833 = DIRECTION('',(1.,0.E+000,0.E+000)); +#96834 = PCURVE('',#96807,#96835); +#96835 = DEFINITIONAL_REPRESENTATION('',(#96836),#96840); +#96836 = LINE('',#96837,#96838); +#96837 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#96838 = VECTOR('',#96839,1.); +#96839 = DIRECTION('',(1.,0.E+000)); +#96840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96841 = PCURVE('',#96842,#96847); +#96842 = PLANE('',#96843); +#96843 = AXIS2_PLACEMENT_3D('',#96844,#96845,#96846); +#96844 = CARTESIAN_POINT('',(1.25,-1.,-0.258196742327)); +#96845 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#96846 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#96847 = DEFINITIONAL_REPRESENTATION('',(#96848),#96852); +#96848 = LINE('',#96849,#96850); +#96849 = CARTESIAN_POINT('',(-5.000038352949E-002,8.75)); +#96850 = VECTOR('',#96851,1.); +#96851 = DIRECTION('',(0.E+000,1.)); +#96852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96853 = ORIENTED_EDGE('',*,*,#96854,.F.); +#96854 = EDGE_CURVE('',#96855,#96827,#96857,.T.); +#96855 = VERTEX_POINT('',#96856); +#96856 = CARTESIAN_POINT('',(1.35,-0.740726081328,-0.208196358798)); +#96857 = SURFACE_CURVE('',#96858,(#96862,#96869),.PCURVE_S1.); +#96858 = LINE('',#96859,#96860); +#96859 = CARTESIAN_POINT('',(1.35,-0.740726081328,-0.208196358798)); +#96860 = VECTOR('',#96861,1.); +#96861 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96862 = PCURVE('',#96807,#96863); +#96863 = DEFINITIONAL_REPRESENTATION('',(#96864),#96868); +#96864 = LINE('',#96865,#96866); +#96865 = CARTESIAN_POINT('',(-8.65,0.E+000)); +#96866 = VECTOR('',#96867,1.); +#96867 = DIRECTION('',(0.E+000,-1.)); +#96868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96869 = PCURVE('',#91606,#96870); +#96870 = DEFINITIONAL_REPRESENTATION('',(#96871),#96875); +#96871 = LINE('',#96872,#96873); +#96872 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#96873 = VECTOR('',#96874,1.); +#96874 = DIRECTION('',(0.E+000,-1.)); +#96875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96876 = ORIENTED_EDGE('',*,*,#96877,.T.); +#96877 = EDGE_CURVE('',#96855,#96797,#96878,.T.); +#96878 = SURFACE_CURVE('',#96879,(#96883,#96890),.PCURVE_S1.); +#96879 = LINE('',#96880,#96881); +#96880 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#96881 = VECTOR('',#96882,1.); +#96882 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96883 = PCURVE('',#96807,#96884); +#96884 = DEFINITIONAL_REPRESENTATION('',(#96885),#96889); +#96885 = LINE('',#96886,#96887); +#96886 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96887 = VECTOR('',#96888,1.); +#96888 = DIRECTION('',(-1.,0.E+000)); +#96889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96890 = PCURVE('',#96891,#96896); +#96891 = CYLINDRICAL_SURFACE('',#96892,0.208574704164); +#96892 = AXIS2_PLACEMENT_3D('',#96893,#96894,#96895); +#96893 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#96894 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96895 = DIRECTION('',(0.E+000,0.E+000,1.)); +#96896 = DEFINITIONAL_REPRESENTATION('',(#96897),#96900); +#96897 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96898,#96899),.UNSPECIFIED., .F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#94506 = CARTESIAN_POINT('',(3.201833915432,8.65)); -#94507 = CARTESIAN_POINT('',(3.201833915432,8.85)); -#94508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94509 = ADVANCED_FACE('',(#94510),#94524,.T.); -#94510 = FACE_BOUND('',#94511,.T.); -#94511 = EDGE_LOOP('',(#94512,#94542,#94565,#94588)); -#94512 = ORIENTED_EDGE('',*,*,#94513,.T.); -#94513 = EDGE_CURVE('',#94514,#94516,#94518,.T.); -#94514 = VERTEX_POINT('',#94515); -#94515 = CARTESIAN_POINT('',(1.35,-0.74341632541,-0.308197125857)); -#94516 = VERTEX_POINT('',#94517); -#94517 = CARTESIAN_POINT('',(1.35,-1.,-0.308197125857)); -#94518 = SURFACE_CURVE('',#94519,(#94523,#94535),.PCURVE_S1.); -#94519 = LINE('',#94520,#94521); -#94520 = CARTESIAN_POINT('',(1.35,-0.74341632541,-0.308197125857)); -#94521 = VECTOR('',#94522,1.); -#94522 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94523 = PCURVE('',#94524,#94529); -#94524 = PLANE('',#94525); -#94525 = AXIS2_PLACEMENT_3D('',#94526,#94527,#94528); -#94526 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#94527 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94528 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94529 = DEFINITIONAL_REPRESENTATION('',(#94530),#94534); -#94530 = LINE('',#94531,#94532); -#94531 = CARTESIAN_POINT('',(8.65,0.E+000)); -#94532 = VECTOR('',#94533,1.); -#94533 = DIRECTION('',(0.E+000,-1.)); -#94534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94535 = PCURVE('',#89214,#94536); -#94536 = DEFINITIONAL_REPRESENTATION('',(#94537),#94541); -#94537 = LINE('',#94538,#94539); -#94538 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#94539 = VECTOR('',#94540,1.); -#94540 = DIRECTION('',(0.E+000,-1.)); -#94541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94542 = ORIENTED_EDGE('',*,*,#94543,.T.); -#94543 = EDGE_CURVE('',#94516,#94544,#94546,.T.); -#94544 = VERTEX_POINT('',#94545); -#94545 = CARTESIAN_POINT('',(1.15,-1.,-0.308197125857)); -#94546 = SURFACE_CURVE('',#94547,(#94551,#94558),.PCURVE_S1.); -#94547 = LINE('',#94548,#94549); -#94548 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#94549 = VECTOR('',#94550,1.); -#94550 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94551 = PCURVE('',#94524,#94552); -#94552 = DEFINITIONAL_REPRESENTATION('',(#94553),#94557); -#94553 = LINE('',#94554,#94555); -#94554 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#94555 = VECTOR('',#94556,1.); -#94556 = DIRECTION('',(1.,0.E+000)); -#94557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94558 = PCURVE('',#94450,#94559); -#94559 = DEFINITIONAL_REPRESENTATION('',(#94560),#94564); -#94560 = LINE('',#94561,#94562); -#94561 = CARTESIAN_POINT('',(5.000038352949E-002,8.75)); -#94562 = VECTOR('',#94563,1.); -#94563 = DIRECTION('',(0.E+000,-1.)); -#94564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94565 = ORIENTED_EDGE('',*,*,#94566,.F.); -#94566 = EDGE_CURVE('',#94567,#94544,#94569,.T.); -#94567 = VERTEX_POINT('',#94568); -#94568 = CARTESIAN_POINT('',(1.15,-0.74341632541,-0.308197125857)); -#94569 = SURFACE_CURVE('',#94570,(#94574,#94581),.PCURVE_S1.); -#94570 = LINE('',#94571,#94572); -#94571 = CARTESIAN_POINT('',(1.15,-0.74341632541,-0.308197125857)); -#94572 = VECTOR('',#94573,1.); -#94573 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#94574 = PCURVE('',#94524,#94575); -#94575 = DEFINITIONAL_REPRESENTATION('',(#94576),#94580); -#94576 = LINE('',#94577,#94578); -#94577 = CARTESIAN_POINT('',(8.85,0.E+000)); -#94578 = VECTOR('',#94579,1.); -#94579 = DIRECTION('',(0.E+000,-1.)); -#94580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94581 = PCURVE('',#89270,#94582); -#94582 = DEFINITIONAL_REPRESENTATION('',(#94583),#94587); -#94583 = LINE('',#94584,#94585); -#94584 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#94585 = VECTOR('',#94586,1.); -#94586 = DIRECTION('',(0.E+000,-1.)); -#94587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94588 = ORIENTED_EDGE('',*,*,#94589,.T.); -#94589 = EDGE_CURVE('',#94567,#94514,#94590,.T.); -#94590 = SURFACE_CURVE('',#94591,(#94595,#94602),.PCURVE_S1.); -#94591 = LINE('',#94592,#94593); -#94592 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#94593 = VECTOR('',#94594,1.); -#94594 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94595 = PCURVE('',#94524,#94596); -#94596 = DEFINITIONAL_REPRESENTATION('',(#94597),#94601); -#94597 = LINE('',#94598,#94599); -#94598 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94599 = VECTOR('',#94600,1.); -#94600 = DIRECTION('',(-1.,0.E+000)); -#94601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94602 = PCURVE('',#94603,#94608); -#94603 = CYLINDRICAL_SURFACE('',#94604,0.308574064194); -#94604 = AXIS2_PLACEMENT_3D('',#94605,#94606,#94607); -#94605 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#94606 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94607 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94608 = DEFINITIONAL_REPRESENTATION('',(#94609),#94612); -#94609 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94610,#94611),.UNSPECIFIED., +#96898 = CARTESIAN_POINT('',(3.201833915432,8.65)); +#96899 = CARTESIAN_POINT('',(3.201833915432,8.85)); +#96900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96901 = ADVANCED_FACE('',(#96902),#96916,.T.); +#96902 = FACE_BOUND('',#96903,.T.); +#96903 = EDGE_LOOP('',(#96904,#96934,#96957,#96980)); +#96904 = ORIENTED_EDGE('',*,*,#96905,.T.); +#96905 = EDGE_CURVE('',#96906,#96908,#96910,.T.); +#96906 = VERTEX_POINT('',#96907); +#96907 = CARTESIAN_POINT('',(1.35,-0.74341632541,-0.308197125857)); +#96908 = VERTEX_POINT('',#96909); +#96909 = CARTESIAN_POINT('',(1.35,-1.,-0.308197125857)); +#96910 = SURFACE_CURVE('',#96911,(#96915,#96927),.PCURVE_S1.); +#96911 = LINE('',#96912,#96913); +#96912 = CARTESIAN_POINT('',(1.35,-0.74341632541,-0.308197125857)); +#96913 = VECTOR('',#96914,1.); +#96914 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96915 = PCURVE('',#96916,#96921); +#96916 = PLANE('',#96917); +#96917 = AXIS2_PLACEMENT_3D('',#96918,#96919,#96920); +#96918 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#96919 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#96920 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96921 = DEFINITIONAL_REPRESENTATION('',(#96922),#96926); +#96922 = LINE('',#96923,#96924); +#96923 = CARTESIAN_POINT('',(8.65,0.E+000)); +#96924 = VECTOR('',#96925,1.); +#96925 = DIRECTION('',(0.E+000,-1.)); +#96926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96927 = PCURVE('',#91606,#96928); +#96928 = DEFINITIONAL_REPRESENTATION('',(#96929),#96933); +#96929 = LINE('',#96930,#96931); +#96930 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#96931 = VECTOR('',#96932,1.); +#96932 = DIRECTION('',(0.E+000,-1.)); +#96933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96934 = ORIENTED_EDGE('',*,*,#96935,.T.); +#96935 = EDGE_CURVE('',#96908,#96936,#96938,.T.); +#96936 = VERTEX_POINT('',#96937); +#96937 = CARTESIAN_POINT('',(1.15,-1.,-0.308197125857)); +#96938 = SURFACE_CURVE('',#96939,(#96943,#96950),.PCURVE_S1.); +#96939 = LINE('',#96940,#96941); +#96940 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#96941 = VECTOR('',#96942,1.); +#96942 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96943 = PCURVE('',#96916,#96944); +#96944 = DEFINITIONAL_REPRESENTATION('',(#96945),#96949); +#96945 = LINE('',#96946,#96947); +#96946 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#96947 = VECTOR('',#96948,1.); +#96948 = DIRECTION('',(1.,0.E+000)); +#96949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96950 = PCURVE('',#96842,#96951); +#96951 = DEFINITIONAL_REPRESENTATION('',(#96952),#96956); +#96952 = LINE('',#96953,#96954); +#96953 = CARTESIAN_POINT('',(5.000038352949E-002,8.75)); +#96954 = VECTOR('',#96955,1.); +#96955 = DIRECTION('',(0.E+000,-1.)); +#96956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96957 = ORIENTED_EDGE('',*,*,#96958,.F.); +#96958 = EDGE_CURVE('',#96959,#96936,#96961,.T.); +#96959 = VERTEX_POINT('',#96960); +#96960 = CARTESIAN_POINT('',(1.15,-0.74341632541,-0.308197125857)); +#96961 = SURFACE_CURVE('',#96962,(#96966,#96973),.PCURVE_S1.); +#96962 = LINE('',#96963,#96964); +#96963 = CARTESIAN_POINT('',(1.15,-0.74341632541,-0.308197125857)); +#96964 = VECTOR('',#96965,1.); +#96965 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#96966 = PCURVE('',#96916,#96967); +#96967 = DEFINITIONAL_REPRESENTATION('',(#96968),#96972); +#96968 = LINE('',#96969,#96970); +#96969 = CARTESIAN_POINT('',(8.85,0.E+000)); +#96970 = VECTOR('',#96971,1.); +#96971 = DIRECTION('',(0.E+000,-1.)); +#96972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96973 = PCURVE('',#91662,#96974); +#96974 = DEFINITIONAL_REPRESENTATION('',(#96975),#96979); +#96975 = LINE('',#96976,#96977); +#96976 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#96977 = VECTOR('',#96978,1.); +#96978 = DIRECTION('',(0.E+000,-1.)); +#96979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96980 = ORIENTED_EDGE('',*,*,#96981,.T.); +#96981 = EDGE_CURVE('',#96959,#96906,#96982,.T.); +#96982 = SURFACE_CURVE('',#96983,(#96987,#96994),.PCURVE_S1.); +#96983 = LINE('',#96984,#96985); +#96984 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#96985 = VECTOR('',#96986,1.); +#96986 = DIRECTION('',(1.,0.E+000,0.E+000)); +#96987 = PCURVE('',#96916,#96988); +#96988 = DEFINITIONAL_REPRESENTATION('',(#96989),#96993); +#96989 = LINE('',#96990,#96991); +#96990 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#96991 = VECTOR('',#96992,1.); +#96992 = DIRECTION('',(-1.,0.E+000)); +#96993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#96994 = PCURVE('',#96995,#97000); +#96995 = CYLINDRICAL_SURFACE('',#96996,0.308574064194); +#96996 = AXIS2_PLACEMENT_3D('',#96997,#96998,#96999); +#96997 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#96998 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#96999 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97000 = DEFINITIONAL_REPRESENTATION('',(#97001),#97004); +#97001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97002,#97003),.UNSPECIFIED., .F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#94610 = CARTESIAN_POINT('',(3.191025391152,8.85)); -#94611 = CARTESIAN_POINT('',(3.191025391152,8.65)); -#94612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94613 = ADVANCED_FACE('',(#94614),#94499,.F.); -#94614 = FACE_BOUND('',#94615,.F.); -#94615 = EDGE_LOOP('',(#94616,#94617,#94644,#94671)); -#94616 = ORIENTED_EDGE('',*,*,#94485,.T.); -#94617 = ORIENTED_EDGE('',*,*,#94618,.F.); -#94618 = EDGE_CURVE('',#94619,#94405,#94621,.T.); -#94619 = VERTEX_POINT('',#94620); -#94620 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.E+000)); -#94621 = SURFACE_CURVE('',#94622,(#94627,#94633),.PCURVE_S1.); -#94622 = CIRCLE('',#94623,0.208574704164); -#94623 = AXIS2_PLACEMENT_3D('',#94624,#94625,#94626); -#94624 = CARTESIAN_POINT('',(1.15,-0.728168876214,2.640924866458E-017)); -#94625 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94626 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94627 = PCURVE('',#94499,#94628); -#94628 = DEFINITIONAL_REPRESENTATION('',(#94629),#94632); -#94629 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94630,#94631),.UNSPECIFIED., +#97002 = CARTESIAN_POINT('',(3.191025391152,8.85)); +#97003 = CARTESIAN_POINT('',(3.191025391152,8.65)); +#97004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97005 = ADVANCED_FACE('',(#97006),#96891,.F.); +#97006 = FACE_BOUND('',#97007,.F.); +#97007 = EDGE_LOOP('',(#97008,#97009,#97036,#97063)); +#97008 = ORIENTED_EDGE('',*,*,#96877,.T.); +#97009 = ORIENTED_EDGE('',*,*,#97010,.F.); +#97010 = EDGE_CURVE('',#97011,#96797,#97013,.T.); +#97011 = VERTEX_POINT('',#97012); +#97012 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.E+000)); +#97013 = SURFACE_CURVE('',#97014,(#97019,#97025),.PCURVE_S1.); +#97014 = CIRCLE('',#97015,0.208574704164); +#97015 = AXIS2_PLACEMENT_3D('',#97016,#97017,#97018); +#97016 = CARTESIAN_POINT('',(1.15,-0.728168876214,2.640924866458E-017)); +#97017 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97018 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97019 = PCURVE('',#96891,#97020); +#97020 = DEFINITIONAL_REPRESENTATION('',(#97021),#97024); +#97021 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97022,#97023),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#94630 = CARTESIAN_POINT('',(1.570796326795,8.85)); -#94631 = CARTESIAN_POINT('',(3.201833915432,8.85)); -#94632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97022 = CARTESIAN_POINT('',(1.570796326795,8.85)); +#97023 = CARTESIAN_POINT('',(3.201833915432,8.85)); +#97024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94633 = PCURVE('',#89270,#94634); -#94634 = DEFINITIONAL_REPRESENTATION('',(#94635),#94643); -#94635 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#94636,#94637,#94638,#94639 - ,#94640,#94641,#94642),.UNSPECIFIED.,.F.,.F.) +#97025 = PCURVE('',#91662,#97026); +#97026 = DEFINITIONAL_REPRESENTATION('',(#97027),#97035); +#97027 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97028,#97029,#97030,#97031 + ,#97032,#97033,#97034),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#94636 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#94637 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#94638 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#94639 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#94640 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#94641 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#94642 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#94643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94644 = ORIENTED_EDGE('',*,*,#94645,.T.); -#94645 = EDGE_CURVE('',#94619,#94646,#94648,.T.); -#94646 = VERTEX_POINT('',#94647); -#94647 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.E+000)); -#94648 = SURFACE_CURVE('',#94649,(#94653,#94659),.PCURVE_S1.); -#94649 = LINE('',#94650,#94651); -#94650 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#94651 = VECTOR('',#94652,1.); -#94652 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94653 = PCURVE('',#94499,#94654); -#94654 = DEFINITIONAL_REPRESENTATION('',(#94655),#94658); -#94655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94656,#94657),.UNSPECIFIED., +#97028 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#97029 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#97030 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#97031 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#97032 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#97033 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#97034 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#97035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97036 = ORIENTED_EDGE('',*,*,#97037,.T.); +#97037 = EDGE_CURVE('',#97011,#97038,#97040,.T.); +#97038 = VERTEX_POINT('',#97039); +#97039 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.E+000)); +#97040 = SURFACE_CURVE('',#97041,(#97045,#97051),.PCURVE_S1.); +#97041 = LINE('',#97042,#97043); +#97042 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#97043 = VECTOR('',#97044,1.); +#97044 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97045 = PCURVE('',#96891,#97046); +#97046 = DEFINITIONAL_REPRESENTATION('',(#97047),#97050); +#97047 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97048,#97049),.UNSPECIFIED., .F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#94656 = CARTESIAN_POINT('',(1.570796326795,8.85)); -#94657 = CARTESIAN_POINT('',(1.570796326795,8.65)); -#94658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94659 = PCURVE('',#94660,#94665); -#94660 = PLANE('',#94661); -#94661 = AXIS2_PLACEMENT_3D('',#94662,#94663,#94664); -#94662 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#94663 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#94664 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#94665 = DEFINITIONAL_REPRESENTATION('',(#94666),#94670); -#94666 = LINE('',#94667,#94668); -#94667 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#94668 = VECTOR('',#94669,1.); -#94669 = DIRECTION('',(0.E+000,1.)); -#94670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94671 = ORIENTED_EDGE('',*,*,#94672,.T.); -#94672 = EDGE_CURVE('',#94646,#94463,#94673,.T.); -#94673 = SURFACE_CURVE('',#94674,(#94679,#94685),.PCURVE_S1.); -#94674 = CIRCLE('',#94675,0.208574704164); -#94675 = AXIS2_PLACEMENT_3D('',#94676,#94677,#94678); -#94676 = CARTESIAN_POINT('',(1.35,-0.728168876214,2.640924866458E-017)); -#94677 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94678 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94679 = PCURVE('',#94499,#94680); -#94680 = DEFINITIONAL_REPRESENTATION('',(#94681),#94684); -#94681 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94682,#94683),.UNSPECIFIED., +#97048 = CARTESIAN_POINT('',(1.570796326795,8.85)); +#97049 = CARTESIAN_POINT('',(1.570796326795,8.65)); +#97050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97051 = PCURVE('',#97052,#97057); +#97052 = PLANE('',#97053); +#97053 = AXIS2_PLACEMENT_3D('',#97054,#97055,#97056); +#97054 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#97055 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#97056 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#97057 = DEFINITIONAL_REPRESENTATION('',(#97058),#97062); +#97058 = LINE('',#97059,#97060); +#97059 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#97060 = VECTOR('',#97061,1.); +#97061 = DIRECTION('',(0.E+000,1.)); +#97062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97063 = ORIENTED_EDGE('',*,*,#97064,.T.); +#97064 = EDGE_CURVE('',#97038,#96855,#97065,.T.); +#97065 = SURFACE_CURVE('',#97066,(#97071,#97077),.PCURVE_S1.); +#97066 = CIRCLE('',#97067,0.208574704164); +#97067 = AXIS2_PLACEMENT_3D('',#97068,#97069,#97070); +#97068 = CARTESIAN_POINT('',(1.35,-0.728168876214,2.640924866458E-017)); +#97069 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97070 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97071 = PCURVE('',#96891,#97072); +#97072 = DEFINITIONAL_REPRESENTATION('',(#97073),#97076); +#97073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97074,#97075),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#94682 = CARTESIAN_POINT('',(1.570796326795,8.65)); -#94683 = CARTESIAN_POINT('',(3.201833915432,8.65)); -#94684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94685 = PCURVE('',#89214,#94686); -#94686 = DEFINITIONAL_REPRESENTATION('',(#94687),#94691); -#94687 = CIRCLE('',#94688,0.208574704164); -#94688 = AXIS2_PLACEMENT_2D('',#94689,#94690); -#94689 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#94690 = DIRECTION('',(1.,0.E+000)); -#94691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94692 = ADVANCED_FACE('',(#94693),#94603,.T.); -#94693 = FACE_BOUND('',#94694,.T.); -#94694 = EDGE_LOOP('',(#94695,#94696,#94723,#94750)); -#94695 = ORIENTED_EDGE('',*,*,#94589,.F.); -#94696 = ORIENTED_EDGE('',*,*,#94697,.F.); -#94697 = EDGE_CURVE('',#94698,#94567,#94700,.T.); -#94698 = VERTEX_POINT('',#94699); -#94699 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.E+000)); -#94700 = SURFACE_CURVE('',#94701,(#94706,#94712),.PCURVE_S1.); -#94701 = CIRCLE('',#94702,0.308574064194); -#94702 = AXIS2_PLACEMENT_3D('',#94703,#94704,#94705); -#94703 = CARTESIAN_POINT('',(1.15,-0.728168876214,2.640924866458E-017)); -#94704 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94705 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94706 = PCURVE('',#94603,#94707); -#94707 = DEFINITIONAL_REPRESENTATION('',(#94708),#94711); -#94708 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94709,#94710),.UNSPECIFIED., +#97074 = CARTESIAN_POINT('',(1.570796326795,8.65)); +#97075 = CARTESIAN_POINT('',(3.201833915432,8.65)); +#97076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97077 = PCURVE('',#91606,#97078); +#97078 = DEFINITIONAL_REPRESENTATION('',(#97079),#97083); +#97079 = CIRCLE('',#97080,0.208574704164); +#97080 = AXIS2_PLACEMENT_2D('',#97081,#97082); +#97081 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#97082 = DIRECTION('',(1.,0.E+000)); +#97083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97084 = ADVANCED_FACE('',(#97085),#96995,.T.); +#97085 = FACE_BOUND('',#97086,.T.); +#97086 = EDGE_LOOP('',(#97087,#97088,#97115,#97142)); +#97087 = ORIENTED_EDGE('',*,*,#96981,.F.); +#97088 = ORIENTED_EDGE('',*,*,#97089,.F.); +#97089 = EDGE_CURVE('',#97090,#96959,#97092,.T.); +#97090 = VERTEX_POINT('',#97091); +#97091 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.E+000)); +#97092 = SURFACE_CURVE('',#97093,(#97098,#97104),.PCURVE_S1.); +#97093 = CIRCLE('',#97094,0.308574064194); +#97094 = AXIS2_PLACEMENT_3D('',#97095,#97096,#97097); +#97095 = CARTESIAN_POINT('',(1.15,-0.728168876214,2.640924866458E-017)); +#97096 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97097 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97098 = PCURVE('',#96995,#97099); +#97099 = DEFINITIONAL_REPRESENTATION('',(#97100),#97103); +#97100 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97101,#97102),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#94709 = CARTESIAN_POINT('',(1.570796326795,8.85)); -#94710 = CARTESIAN_POINT('',(3.191025391152,8.85)); -#94711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97101 = CARTESIAN_POINT('',(1.570796326795,8.85)); +#97102 = CARTESIAN_POINT('',(3.191025391152,8.85)); +#97103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94712 = PCURVE('',#89270,#94713); -#94713 = DEFINITIONAL_REPRESENTATION('',(#94714),#94722); -#94714 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#94715,#94716,#94717,#94718 - ,#94719,#94720,#94721),.UNSPECIFIED.,.T.,.F.) +#97104 = PCURVE('',#91662,#97105); +#97105 = DEFINITIONAL_REPRESENTATION('',(#97106),#97114); +#97106 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97107,#97108,#97109,#97110 + ,#97111,#97112,#97113),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#94715 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#94716 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#94717 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#94718 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#94719 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#94720 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#94721 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#94722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94723 = ORIENTED_EDGE('',*,*,#94724,.F.); -#94724 = EDGE_CURVE('',#94725,#94698,#94727,.T.); -#94725 = VERTEX_POINT('',#94726); -#94726 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.E+000)); -#94727 = SURFACE_CURVE('',#94728,(#94732,#94738),.PCURVE_S1.); -#94728 = LINE('',#94729,#94730); -#94729 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#94730 = VECTOR('',#94731,1.); -#94731 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94732 = PCURVE('',#94603,#94733); -#94733 = DEFINITIONAL_REPRESENTATION('',(#94734),#94737); -#94734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94735,#94736),.UNSPECIFIED., +#97107 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#97108 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#97109 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#97110 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#97111 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#97112 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#97113 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#97114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97115 = ORIENTED_EDGE('',*,*,#97116,.F.); +#97116 = EDGE_CURVE('',#97117,#97090,#97119,.T.); +#97117 = VERTEX_POINT('',#97118); +#97118 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.E+000)); +#97119 = SURFACE_CURVE('',#97120,(#97124,#97130),.PCURVE_S1.); +#97120 = LINE('',#97121,#97122); +#97121 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#97122 = VECTOR('',#97123,1.); +#97123 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97124 = PCURVE('',#96995,#97125); +#97125 = DEFINITIONAL_REPRESENTATION('',(#97126),#97129); +#97126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97127,#97128),.UNSPECIFIED., .F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#94735 = CARTESIAN_POINT('',(1.570796326795,8.65)); -#94736 = CARTESIAN_POINT('',(1.570796326795,8.85)); -#94737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94738 = PCURVE('',#94739,#94744); -#94739 = PLANE('',#94740); -#94740 = AXIS2_PLACEMENT_3D('',#94741,#94742,#94743); -#94741 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#94742 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#94743 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#94744 = DEFINITIONAL_REPRESENTATION('',(#94745),#94749); -#94745 = LINE('',#94746,#94747); -#94746 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#94747 = VECTOR('',#94748,1.); -#94748 = DIRECTION('',(0.E+000,-1.)); -#94749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94750 = ORIENTED_EDGE('',*,*,#94751,.T.); -#94751 = EDGE_CURVE('',#94725,#94514,#94752,.T.); -#94752 = SURFACE_CURVE('',#94753,(#94758,#94764),.PCURVE_S1.); -#94753 = CIRCLE('',#94754,0.308574064194); -#94754 = AXIS2_PLACEMENT_3D('',#94755,#94756,#94757); -#94755 = CARTESIAN_POINT('',(1.35,-0.728168876214,2.640924866458E-017)); -#94756 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94757 = DIRECTION('',(0.E+000,0.E+000,1.)); -#94758 = PCURVE('',#94603,#94759); -#94759 = DEFINITIONAL_REPRESENTATION('',(#94760),#94763); -#94760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94761,#94762),.UNSPECIFIED., +#97127 = CARTESIAN_POINT('',(1.570796326795,8.65)); +#97128 = CARTESIAN_POINT('',(1.570796326795,8.85)); +#97129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97130 = PCURVE('',#97131,#97136); +#97131 = PLANE('',#97132); +#97132 = AXIS2_PLACEMENT_3D('',#97133,#97134,#97135); +#97133 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#97134 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#97135 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97136 = DEFINITIONAL_REPRESENTATION('',(#97137),#97141); +#97137 = LINE('',#97138,#97139); +#97138 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#97139 = VECTOR('',#97140,1.); +#97140 = DIRECTION('',(0.E+000,-1.)); +#97141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97142 = ORIENTED_EDGE('',*,*,#97143,.T.); +#97143 = EDGE_CURVE('',#97117,#96906,#97144,.T.); +#97144 = SURFACE_CURVE('',#97145,(#97150,#97156),.PCURVE_S1.); +#97145 = CIRCLE('',#97146,0.308574064194); +#97146 = AXIS2_PLACEMENT_3D('',#97147,#97148,#97149); +#97147 = CARTESIAN_POINT('',(1.35,-0.728168876214,2.640924866458E-017)); +#97148 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97149 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97150 = PCURVE('',#96995,#97151); +#97151 = DEFINITIONAL_REPRESENTATION('',(#97152),#97155); +#97152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97153,#97154),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#94761 = CARTESIAN_POINT('',(1.570796326795,8.65)); -#94762 = CARTESIAN_POINT('',(3.191025391152,8.65)); -#94763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94764 = PCURVE('',#89214,#94765); -#94765 = DEFINITIONAL_REPRESENTATION('',(#94766),#94770); -#94766 = CIRCLE('',#94767,0.308574064194); -#94767 = AXIS2_PLACEMENT_2D('',#94768,#94769); -#94768 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#94769 = DIRECTION('',(1.,0.E+000)); -#94770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94771 = ADVANCED_FACE('',(#94772),#94739,.F.); -#94772 = FACE_BOUND('',#94773,.T.); -#94773 = EDGE_LOOP('',(#94774,#94803,#94824,#94825)); -#94774 = ORIENTED_EDGE('',*,*,#94775,.F.); -#94775 = EDGE_CURVE('',#94776,#94778,#94780,.T.); -#94776 = VERTEX_POINT('',#94777); -#94777 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.530776333563)); -#94778 = VERTEX_POINT('',#94779); -#94779 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.530776333563)); -#94780 = SURFACE_CURVE('',#94781,(#94785,#94792),.PCURVE_S1.); -#94781 = LINE('',#94782,#94783); -#94782 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#94783 = VECTOR('',#94784,1.); -#94784 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#94785 = PCURVE('',#94739,#94786); -#94786 = DEFINITIONAL_REPRESENTATION('',(#94787),#94791); -#94787 = LINE('',#94788,#94789); -#94788 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94789 = VECTOR('',#94790,1.); -#94790 = DIRECTION('',(0.E+000,-1.)); -#94791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94792 = PCURVE('',#94793,#94798); -#94793 = CYLINDRICAL_SURFACE('',#94794,0.119270391569); -#94794 = AXIS2_PLACEMENT_3D('',#94795,#94796,#94797); -#94795 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#94796 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94797 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94798 = DEFINITIONAL_REPRESENTATION('',(#94799),#94802); -#94799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94800,#94801),.UNSPECIFIED., +#97153 = CARTESIAN_POINT('',(1.570796326795,8.65)); +#97154 = CARTESIAN_POINT('',(3.191025391152,8.65)); +#97155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97156 = PCURVE('',#91606,#97157); +#97157 = DEFINITIONAL_REPRESENTATION('',(#97158),#97162); +#97158 = CIRCLE('',#97159,0.308574064194); +#97159 = AXIS2_PLACEMENT_2D('',#97160,#97161); +#97160 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#97161 = DIRECTION('',(1.,0.E+000)); +#97162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97163 = ADVANCED_FACE('',(#97164),#97131,.F.); +#97164 = FACE_BOUND('',#97165,.T.); +#97165 = EDGE_LOOP('',(#97166,#97195,#97216,#97217)); +#97166 = ORIENTED_EDGE('',*,*,#97167,.F.); +#97167 = EDGE_CURVE('',#97168,#97170,#97172,.T.); +#97168 = VERTEX_POINT('',#97169); +#97169 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.530776333563)); +#97170 = VERTEX_POINT('',#97171); +#97171 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.530776333563)); +#97172 = SURFACE_CURVE('',#97173,(#97177,#97184),.PCURVE_S1.); +#97173 = LINE('',#97174,#97175); +#97174 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#97175 = VECTOR('',#97176,1.); +#97176 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97177 = PCURVE('',#97131,#97178); +#97178 = DEFINITIONAL_REPRESENTATION('',(#97179),#97183); +#97179 = LINE('',#97180,#97181); +#97180 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97181 = VECTOR('',#97182,1.); +#97182 = DIRECTION('',(0.E+000,-1.)); +#97183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97184 = PCURVE('',#97185,#97190); +#97185 = CYLINDRICAL_SURFACE('',#97186,0.119270391569); +#97186 = AXIS2_PLACEMENT_3D('',#97187,#97188,#97189); +#97187 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#97188 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97189 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97190 = DEFINITIONAL_REPRESENTATION('',(#97191),#97194); +#97191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97192,#97193),.UNSPECIFIED., .F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#94800 = CARTESIAN_POINT('',(4.712388980385,-8.65)); -#94801 = CARTESIAN_POINT('',(4.712388980385,-8.85)); -#94802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97192 = CARTESIAN_POINT('',(4.712388980385,-8.65)); +#97193 = CARTESIAN_POINT('',(4.712388980385,-8.85)); +#97194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97195 = ORIENTED_EDGE('',*,*,#97196,.T.); +#97196 = EDGE_CURVE('',#97168,#97117,#97197,.T.); +#97197 = SURFACE_CURVE('',#97198,(#97202,#97209),.PCURVE_S1.); +#97198 = LINE('',#97199,#97200); +#97199 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.530776333563)); +#97200 = VECTOR('',#97201,1.); +#97201 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97202 = PCURVE('',#97131,#97203); +#97203 = DEFINITIONAL_REPRESENTATION('',(#97204),#97208); +#97204 = LINE('',#97205,#97206); +#97205 = CARTESIAN_POINT('',(0.E+000,-8.65)); +#97206 = VECTOR('',#97207,1.); +#97207 = DIRECTION('',(1.,0.E+000)); +#97208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97209 = PCURVE('',#91606,#97210); +#97210 = DEFINITIONAL_REPRESENTATION('',(#97211),#97215); +#97211 = LINE('',#97212,#97213); +#97212 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#97213 = VECTOR('',#97214,1.); +#97214 = DIRECTION('',(-1.,-1.021336205033E-016)); +#97215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97216 = ORIENTED_EDGE('',*,*,#97116,.T.); +#97217 = ORIENTED_EDGE('',*,*,#97218,.F.); +#97218 = EDGE_CURVE('',#97170,#97090,#97219,.T.); +#97219 = SURFACE_CURVE('',#97220,(#97224,#97231),.PCURVE_S1.); +#97220 = LINE('',#97221,#97222); +#97221 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.530776333563)); +#97222 = VECTOR('',#97223,1.); +#97223 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97224 = PCURVE('',#97131,#97225); +#97225 = DEFINITIONAL_REPRESENTATION('',(#97226),#97230); +#97226 = LINE('',#97227,#97228); +#97227 = CARTESIAN_POINT('',(0.E+000,-8.85)); +#97228 = VECTOR('',#97229,1.); +#97229 = DIRECTION('',(1.,0.E+000)); +#97230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97231 = PCURVE('',#91662,#97232); +#97232 = DEFINITIONAL_REPRESENTATION('',(#97233),#97237); +#97233 = LINE('',#97234,#97235); +#97234 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#97235 = VECTOR('',#97236,1.); +#97236 = DIRECTION('',(1.,-1.021336205033E-016)); +#97237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97238 = ADVANCED_FACE('',(#97239),#97052,.F.); +#97239 = FACE_BOUND('',#97240,.T.); +#97240 = EDGE_LOOP('',(#97241,#97270,#97291,#97292)); +#97241 = ORIENTED_EDGE('',*,*,#97242,.F.); +#97242 = EDGE_CURVE('',#97243,#97245,#97247,.T.); +#97243 = VERTEX_POINT('',#97244); +#97244 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.530776333563)); +#97245 = VERTEX_POINT('',#97246); +#97246 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.530776333563)); +#97247 = SURFACE_CURVE('',#97248,(#97252,#97259),.PCURVE_S1.); +#97248 = LINE('',#97249,#97250); +#97249 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#97250 = VECTOR('',#97251,1.); +#97251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97252 = PCURVE('',#97052,#97253); +#97253 = DEFINITIONAL_REPRESENTATION('',(#97254),#97258); +#97254 = LINE('',#97255,#97256); +#97255 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97256 = VECTOR('',#97257,1.); +#97257 = DIRECTION('',(0.E+000,1.)); +#97258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97259 = PCURVE('',#97260,#97265); +#97260 = CYLINDRICAL_SURFACE('',#97261,0.2192697516); +#97261 = AXIS2_PLACEMENT_3D('',#97262,#97263,#97264); +#97262 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#97263 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97264 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97265 = DEFINITIONAL_REPRESENTATION('',(#97266),#97269); +#97266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97267,#97268),.UNSPECIFIED., + .F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); +#97267 = CARTESIAN_POINT('',(4.712388980385,-8.85)); +#97268 = CARTESIAN_POINT('',(4.712388980385,-8.65)); +#97269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94803 = ORIENTED_EDGE('',*,*,#94804,.T.); -#94804 = EDGE_CURVE('',#94776,#94725,#94805,.T.); -#94805 = SURFACE_CURVE('',#94806,(#94810,#94817),.PCURVE_S1.); -#94806 = LINE('',#94807,#94808); -#94807 = CARTESIAN_POINT('',(1.35,-0.419594812019,0.530776333563)); -#94808 = VECTOR('',#94809,1.); -#94809 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#94810 = PCURVE('',#94739,#94811); -#94811 = DEFINITIONAL_REPRESENTATION('',(#94812),#94816); -#94812 = LINE('',#94813,#94814); -#94813 = CARTESIAN_POINT('',(0.E+000,-8.65)); -#94814 = VECTOR('',#94815,1.); -#94815 = DIRECTION('',(1.,0.E+000)); -#94816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97270 = ORIENTED_EDGE('',*,*,#97271,.T.); +#97271 = EDGE_CURVE('',#97243,#97011,#97272,.T.); +#97272 = SURFACE_CURVE('',#97273,(#97277,#97284),.PCURVE_S1.); +#97273 = LINE('',#97274,#97275); +#97274 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.530776333563)); +#97275 = VECTOR('',#97276,1.); +#97276 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97277 = PCURVE('',#97052,#97278); +#97278 = DEFINITIONAL_REPRESENTATION('',(#97279),#97283); +#97279 = LINE('',#97280,#97281); +#97280 = CARTESIAN_POINT('',(0.E+000,-8.85)); +#97281 = VECTOR('',#97282,1.); +#97282 = DIRECTION('',(-1.,0.E+000)); +#97283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94817 = PCURVE('',#89214,#94818); -#94818 = DEFINITIONAL_REPRESENTATION('',(#94819),#94823); -#94819 = LINE('',#94820,#94821); -#94820 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#94821 = VECTOR('',#94822,1.); -#94822 = DIRECTION('',(-1.,-1.021336205033E-016)); -#94823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94824 = ORIENTED_EDGE('',*,*,#94724,.T.); -#94825 = ORIENTED_EDGE('',*,*,#94826,.F.); -#94826 = EDGE_CURVE('',#94778,#94698,#94827,.T.); -#94827 = SURFACE_CURVE('',#94828,(#94832,#94839),.PCURVE_S1.); -#94828 = LINE('',#94829,#94830); -#94829 = CARTESIAN_POINT('',(1.15,-0.419594812019,0.530776333563)); -#94830 = VECTOR('',#94831,1.); -#94831 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#94832 = PCURVE('',#94739,#94833); -#94833 = DEFINITIONAL_REPRESENTATION('',(#94834),#94838); -#94834 = LINE('',#94835,#94836); -#94835 = CARTESIAN_POINT('',(0.E+000,-8.85)); -#94836 = VECTOR('',#94837,1.); -#94837 = DIRECTION('',(1.,0.E+000)); -#94838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94839 = PCURVE('',#89270,#94840); -#94840 = DEFINITIONAL_REPRESENTATION('',(#94841),#94845); -#94841 = LINE('',#94842,#94843); -#94842 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#94843 = VECTOR('',#94844,1.); -#94844 = DIRECTION('',(1.,-1.021336205033E-016)); -#94845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94846 = ADVANCED_FACE('',(#94847),#94660,.F.); -#94847 = FACE_BOUND('',#94848,.T.); -#94848 = EDGE_LOOP('',(#94849,#94878,#94899,#94900)); -#94849 = ORIENTED_EDGE('',*,*,#94850,.F.); -#94850 = EDGE_CURVE('',#94851,#94853,#94855,.T.); -#94851 = VERTEX_POINT('',#94852); -#94852 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.530776333563)); -#94853 = VERTEX_POINT('',#94854); -#94854 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.530776333563)); -#94855 = SURFACE_CURVE('',#94856,(#94860,#94867),.PCURVE_S1.); -#94856 = LINE('',#94857,#94858); -#94857 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#94858 = VECTOR('',#94859,1.); -#94859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94860 = PCURVE('',#94660,#94861); -#94861 = DEFINITIONAL_REPRESENTATION('',(#94862),#94866); -#94862 = LINE('',#94863,#94864); -#94863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#94864 = VECTOR('',#94865,1.); -#94865 = DIRECTION('',(0.E+000,1.)); -#94866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94867 = PCURVE('',#94868,#94873); -#94868 = CYLINDRICAL_SURFACE('',#94869,0.2192697516); -#94869 = AXIS2_PLACEMENT_3D('',#94870,#94871,#94872); -#94870 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#94871 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94872 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94873 = DEFINITIONAL_REPRESENTATION('',(#94874),#94877); -#94874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94875,#94876),.UNSPECIFIED., - .F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#94875 = CARTESIAN_POINT('',(4.712388980385,-8.85)); -#94876 = CARTESIAN_POINT('',(4.712388980385,-8.65)); -#94877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94878 = ORIENTED_EDGE('',*,*,#94879,.T.); -#94879 = EDGE_CURVE('',#94851,#94619,#94880,.T.); -#94880 = SURFACE_CURVE('',#94881,(#94885,#94892),.PCURVE_S1.); -#94881 = LINE('',#94882,#94883); -#94882 = CARTESIAN_POINT('',(1.15,-0.51959417205,0.530776333563)); -#94883 = VECTOR('',#94884,1.); -#94884 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#94885 = PCURVE('',#94660,#94886); -#94886 = DEFINITIONAL_REPRESENTATION('',(#94887),#94891); -#94887 = LINE('',#94888,#94889); -#94888 = CARTESIAN_POINT('',(0.E+000,-8.85)); -#94889 = VECTOR('',#94890,1.); -#94890 = DIRECTION('',(-1.,0.E+000)); -#94891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94892 = PCURVE('',#89270,#94893); -#94893 = DEFINITIONAL_REPRESENTATION('',(#94894),#94898); -#94894 = LINE('',#94895,#94896); -#94895 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#94896 = VECTOR('',#94897,1.); -#94897 = DIRECTION('',(1.,-1.021336205033E-016)); -#94898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94899 = ORIENTED_EDGE('',*,*,#94645,.T.); -#94900 = ORIENTED_EDGE('',*,*,#94901,.F.); -#94901 = EDGE_CURVE('',#94853,#94646,#94902,.T.); -#94902 = SURFACE_CURVE('',#94903,(#94907,#94914),.PCURVE_S1.); -#94903 = LINE('',#94904,#94905); -#94904 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.530776333563)); -#94905 = VECTOR('',#94906,1.); -#94906 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#94907 = PCURVE('',#94660,#94908); -#94908 = DEFINITIONAL_REPRESENTATION('',(#94909),#94913); -#94909 = LINE('',#94910,#94911); -#94910 = CARTESIAN_POINT('',(0.E+000,-8.65)); -#94911 = VECTOR('',#94912,1.); -#94912 = DIRECTION('',(-1.,0.E+000)); -#94913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94914 = PCURVE('',#89214,#94915); -#94915 = DEFINITIONAL_REPRESENTATION('',(#94916),#94920); -#94916 = LINE('',#94917,#94918); -#94917 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#94918 = VECTOR('',#94919,1.); -#94919 = DIRECTION('',(-1.,-1.021336205033E-016)); -#94920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94921 = ADVANCED_FACE('',(#94922),#94793,.F.); -#94922 = FACE_BOUND('',#94923,.F.); -#94923 = EDGE_LOOP('',(#94924,#94951,#94973,#94994)); -#94924 = ORIENTED_EDGE('',*,*,#94925,.F.); -#94925 = EDGE_CURVE('',#94926,#94776,#94928,.T.); -#94926 = VERTEX_POINT('',#94927); -#94927 = CARTESIAN_POINT('',(1.35,-0.303662633502,0.65)); -#94928 = SURFACE_CURVE('',#94929,(#94934,#94940),.PCURVE_S1.); -#94929 = CIRCLE('',#94930,0.119270391569); -#94930 = AXIS2_PLACEMENT_3D('',#94931,#94932,#94933); -#94931 = CARTESIAN_POINT('',(1.35,-0.30032442045,0.530776333563)); -#94932 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94933 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94934 = PCURVE('',#94793,#94935); -#94935 = DEFINITIONAL_REPRESENTATION('',(#94936),#94939); -#94936 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94937,#94938),.UNSPECIFIED., +#97284 = PCURVE('',#91662,#97285); +#97285 = DEFINITIONAL_REPRESENTATION('',(#97286),#97290); +#97286 = LINE('',#97287,#97288); +#97287 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#97288 = VECTOR('',#97289,1.); +#97289 = DIRECTION('',(1.,-1.021336205033E-016)); +#97290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97291 = ORIENTED_EDGE('',*,*,#97037,.T.); +#97292 = ORIENTED_EDGE('',*,*,#97293,.F.); +#97293 = EDGE_CURVE('',#97245,#97038,#97294,.T.); +#97294 = SURFACE_CURVE('',#97295,(#97299,#97306),.PCURVE_S1.); +#97295 = LINE('',#97296,#97297); +#97296 = CARTESIAN_POINT('',(1.35,-0.51959417205,0.530776333563)); +#97297 = VECTOR('',#97298,1.); +#97298 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97299 = PCURVE('',#97052,#97300); +#97300 = DEFINITIONAL_REPRESENTATION('',(#97301),#97305); +#97301 = LINE('',#97302,#97303); +#97302 = CARTESIAN_POINT('',(0.E+000,-8.65)); +#97303 = VECTOR('',#97304,1.); +#97304 = DIRECTION('',(-1.,0.E+000)); +#97305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97306 = PCURVE('',#91606,#97307); +#97307 = DEFINITIONAL_REPRESENTATION('',(#97308),#97312); +#97308 = LINE('',#97309,#97310); +#97309 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#97310 = VECTOR('',#97311,1.); +#97311 = DIRECTION('',(-1.,-1.021336205033E-016)); +#97312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97313 = ADVANCED_FACE('',(#97314),#97185,.F.); +#97314 = FACE_BOUND('',#97315,.F.); +#97315 = EDGE_LOOP('',(#97316,#97343,#97365,#97386)); +#97316 = ORIENTED_EDGE('',*,*,#97317,.F.); +#97317 = EDGE_CURVE('',#97318,#97168,#97320,.T.); +#97318 = VERTEX_POINT('',#97319); +#97319 = CARTESIAN_POINT('',(1.35,-0.303662633502,0.65)); +#97320 = SURFACE_CURVE('',#97321,(#97326,#97332),.PCURVE_S1.); +#97321 = CIRCLE('',#97322,0.119270391569); +#97322 = AXIS2_PLACEMENT_3D('',#97323,#97324,#97325); +#97323 = CARTESIAN_POINT('',(1.35,-0.30032442045,0.530776333563)); +#97324 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97325 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97326 = PCURVE('',#97185,#97327); +#97327 = DEFINITIONAL_REPRESENTATION('',(#97328),#97331); +#97328 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97329,#97330),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#94937 = CARTESIAN_POINT('',(3.169584923929,-8.65)); -#94938 = CARTESIAN_POINT('',(4.712388980385,-8.65)); -#94939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97329 = CARTESIAN_POINT('',(3.169584923929,-8.65)); +#97330 = CARTESIAN_POINT('',(4.712388980385,-8.65)); +#97331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#94940 = PCURVE('',#89214,#94941); -#94941 = DEFINITIONAL_REPRESENTATION('',(#94942),#94950); -#94942 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#94943,#94944,#94945,#94946 - ,#94947,#94948,#94949),.UNSPECIFIED.,.F.,.F.) +#97332 = PCURVE('',#91606,#97333); +#97333 = DEFINITIONAL_REPRESENTATION('',(#97334),#97342); +#97334 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97335,#97336,#97337,#97338 + ,#97339,#97340,#97341),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#94943 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#94944 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#94945 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#94946 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#94947 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#94948 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#94949 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#94950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94951 = ORIENTED_EDGE('',*,*,#94952,.F.); -#94952 = EDGE_CURVE('',#94953,#94926,#94955,.T.); -#94953 = VERTEX_POINT('',#94954); -#94954 = CARTESIAN_POINT('',(1.15,-0.303662633502,0.65)); -#94955 = SURFACE_CURVE('',#94956,(#94960,#94966),.PCURVE_S1.); -#94956 = LINE('',#94957,#94958); -#94957 = CARTESIAN_POINT('',(1.35,-0.303662633502,0.65)); -#94958 = VECTOR('',#94959,1.); -#94959 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94960 = PCURVE('',#94793,#94961); -#94961 = DEFINITIONAL_REPRESENTATION('',(#94962),#94965); -#94962 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94963,#94964),.UNSPECIFIED., +#97335 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#97336 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#97337 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#97338 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#97339 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#97340 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#97341 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#97342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97343 = ORIENTED_EDGE('',*,*,#97344,.F.); +#97344 = EDGE_CURVE('',#97345,#97318,#97347,.T.); +#97345 = VERTEX_POINT('',#97346); +#97346 = CARTESIAN_POINT('',(1.15,-0.303662633502,0.65)); +#97347 = SURFACE_CURVE('',#97348,(#97352,#97358),.PCURVE_S1.); +#97348 = LINE('',#97349,#97350); +#97349 = CARTESIAN_POINT('',(1.35,-0.303662633502,0.65)); +#97350 = VECTOR('',#97351,1.); +#97351 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97352 = PCURVE('',#97185,#97353); +#97353 = DEFINITIONAL_REPRESENTATION('',(#97354),#97357); +#97354 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97355,#97356),.UNSPECIFIED., .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#94963 = CARTESIAN_POINT('',(3.169584923929,-8.85)); -#94964 = CARTESIAN_POINT('',(3.169584923929,-8.65)); -#94965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94966 = PCURVE('',#89242,#94967); -#94967 = DEFINITIONAL_REPRESENTATION('',(#94968),#94972); -#94968 = LINE('',#94969,#94970); -#94969 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#94970 = VECTOR('',#94971,1.); -#94971 = DIRECTION('',(0.E+000,1.)); -#94972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94973 = ORIENTED_EDGE('',*,*,#94974,.T.); -#94974 = EDGE_CURVE('',#94953,#94778,#94975,.T.); -#94975 = SURFACE_CURVE('',#94976,(#94981,#94987),.PCURVE_S1.); -#94976 = CIRCLE('',#94977,0.119270391569); -#94977 = AXIS2_PLACEMENT_3D('',#94978,#94979,#94980); -#94978 = CARTESIAN_POINT('',(1.15,-0.30032442045,0.530776333563)); -#94979 = DIRECTION('',(1.,0.E+000,0.E+000)); -#94980 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#94981 = PCURVE('',#94793,#94982); -#94982 = DEFINITIONAL_REPRESENTATION('',(#94983),#94986); -#94983 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#94984,#94985),.UNSPECIFIED., +#97355 = CARTESIAN_POINT('',(3.169584923929,-8.85)); +#97356 = CARTESIAN_POINT('',(3.169584923929,-8.65)); +#97357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97358 = PCURVE('',#91634,#97359); +#97359 = DEFINITIONAL_REPRESENTATION('',(#97360),#97364); +#97360 = LINE('',#97361,#97362); +#97361 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#97362 = VECTOR('',#97363,1.); +#97363 = DIRECTION('',(0.E+000,1.)); +#97364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97365 = ORIENTED_EDGE('',*,*,#97366,.T.); +#97366 = EDGE_CURVE('',#97345,#97170,#97367,.T.); +#97367 = SURFACE_CURVE('',#97368,(#97373,#97379),.PCURVE_S1.); +#97368 = CIRCLE('',#97369,0.119270391569); +#97369 = AXIS2_PLACEMENT_3D('',#97370,#97371,#97372); +#97370 = CARTESIAN_POINT('',(1.15,-0.30032442045,0.530776333563)); +#97371 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97372 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97373 = PCURVE('',#97185,#97374); +#97374 = DEFINITIONAL_REPRESENTATION('',(#97375),#97378); +#97375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97376,#97377),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#94984 = CARTESIAN_POINT('',(3.169584923929,-8.85)); -#94985 = CARTESIAN_POINT('',(4.712388980385,-8.85)); -#94986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94987 = PCURVE('',#89270,#94988); -#94988 = DEFINITIONAL_REPRESENTATION('',(#94989),#94993); -#94989 = CIRCLE('',#94990,0.119270391569); -#94990 = AXIS2_PLACEMENT_2D('',#94991,#94992); -#94991 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#94992 = DIRECTION('',(1.,0.E+000)); -#94993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#94994 = ORIENTED_EDGE('',*,*,#94775,.F.); -#94995 = ADVANCED_FACE('',(#94996),#94868,.T.); -#94996 = FACE_BOUND('',#94997,.T.); -#94997 = EDGE_LOOP('',(#94998,#95021,#95022,#95049)); -#94998 = ORIENTED_EDGE('',*,*,#94999,.T.); -#94999 = EDGE_CURVE('',#95000,#94851,#95002,.T.); -#95000 = VERTEX_POINT('',#95001); -#95001 = CARTESIAN_POINT('',(1.15,-0.304819755875,0.75)); -#95002 = SURFACE_CURVE('',#95003,(#95008,#95014),.PCURVE_S1.); -#95003 = CIRCLE('',#95004,0.2192697516); -#95004 = AXIS2_PLACEMENT_3D('',#95005,#95006,#95007); -#95005 = CARTESIAN_POINT('',(1.15,-0.30032442045,0.530776333563)); -#95006 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95007 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95008 = PCURVE('',#94868,#95009); -#95009 = DEFINITIONAL_REPRESENTATION('',(#95010),#95013); -#95010 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95011,#95012),.UNSPECIFIED., +#97376 = CARTESIAN_POINT('',(3.169584923929,-8.85)); +#97377 = CARTESIAN_POINT('',(4.712388980385,-8.85)); +#97378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97379 = PCURVE('',#91662,#97380); +#97380 = DEFINITIONAL_REPRESENTATION('',(#97381),#97385); +#97381 = CIRCLE('',#97382,0.119270391569); +#97382 = AXIS2_PLACEMENT_2D('',#97383,#97384); +#97383 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#97384 = DIRECTION('',(1.,0.E+000)); +#97385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97386 = ORIENTED_EDGE('',*,*,#97167,.F.); +#97387 = ADVANCED_FACE('',(#97388),#97260,.T.); +#97388 = FACE_BOUND('',#97389,.T.); +#97389 = EDGE_LOOP('',(#97390,#97413,#97414,#97441)); +#97390 = ORIENTED_EDGE('',*,*,#97391,.T.); +#97391 = EDGE_CURVE('',#97392,#97243,#97394,.T.); +#97392 = VERTEX_POINT('',#97393); +#97393 = CARTESIAN_POINT('',(1.15,-0.304819755875,0.75)); +#97394 = SURFACE_CURVE('',#97395,(#97400,#97406),.PCURVE_S1.); +#97395 = CIRCLE('',#97396,0.2192697516); +#97396 = AXIS2_PLACEMENT_3D('',#97397,#97398,#97399); +#97397 = CARTESIAN_POINT('',(1.15,-0.30032442045,0.530776333563)); +#97398 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97399 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97400 = PCURVE('',#97260,#97401); +#97401 = DEFINITIONAL_REPRESENTATION('',(#97402),#97405); +#97402 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97403,#97404),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95011 = CARTESIAN_POINT('',(3.162095483347,-8.85)); -#95012 = CARTESIAN_POINT('',(4.712388980385,-8.85)); -#95013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95014 = PCURVE('',#89270,#95015); -#95015 = DEFINITIONAL_REPRESENTATION('',(#95016),#95020); -#95016 = CIRCLE('',#95017,0.2192697516); -#95017 = AXIS2_PLACEMENT_2D('',#95018,#95019); -#95018 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#95019 = DIRECTION('',(1.,0.E+000)); -#95020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95021 = ORIENTED_EDGE('',*,*,#94850,.T.); -#95022 = ORIENTED_EDGE('',*,*,#95023,.F.); -#95023 = EDGE_CURVE('',#95024,#94853,#95026,.T.); -#95024 = VERTEX_POINT('',#95025); -#95025 = CARTESIAN_POINT('',(1.35,-0.304819755875,0.75)); -#95026 = SURFACE_CURVE('',#95027,(#95032,#95038),.PCURVE_S1.); -#95027 = CIRCLE('',#95028,0.2192697516); -#95028 = AXIS2_PLACEMENT_3D('',#95029,#95030,#95031); -#95029 = CARTESIAN_POINT('',(1.35,-0.30032442045,0.530776333563)); -#95030 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95031 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95032 = PCURVE('',#94868,#95033); -#95033 = DEFINITIONAL_REPRESENTATION('',(#95034),#95037); -#95034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95035,#95036),.UNSPECIFIED., +#97403 = CARTESIAN_POINT('',(3.162095483347,-8.85)); +#97404 = CARTESIAN_POINT('',(4.712388980385,-8.85)); +#97405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97406 = PCURVE('',#91662,#97407); +#97407 = DEFINITIONAL_REPRESENTATION('',(#97408),#97412); +#97408 = CIRCLE('',#97409,0.2192697516); +#97409 = AXIS2_PLACEMENT_2D('',#97410,#97411); +#97410 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#97411 = DIRECTION('',(1.,0.E+000)); +#97412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97413 = ORIENTED_EDGE('',*,*,#97242,.T.); +#97414 = ORIENTED_EDGE('',*,*,#97415,.F.); +#97415 = EDGE_CURVE('',#97416,#97245,#97418,.T.); +#97416 = VERTEX_POINT('',#97417); +#97417 = CARTESIAN_POINT('',(1.35,-0.304819755875,0.75)); +#97418 = SURFACE_CURVE('',#97419,(#97424,#97430),.PCURVE_S1.); +#97419 = CIRCLE('',#97420,0.2192697516); +#97420 = AXIS2_PLACEMENT_3D('',#97421,#97422,#97423); +#97421 = CARTESIAN_POINT('',(1.35,-0.30032442045,0.530776333563)); +#97422 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97423 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97424 = PCURVE('',#97260,#97425); +#97425 = DEFINITIONAL_REPRESENTATION('',(#97426),#97429); +#97426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97427,#97428),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95035 = CARTESIAN_POINT('',(3.162095483347,-8.65)); -#95036 = CARTESIAN_POINT('',(4.712388980385,-8.65)); -#95037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97427 = CARTESIAN_POINT('',(3.162095483347,-8.65)); +#97428 = CARTESIAN_POINT('',(4.712388980385,-8.65)); +#97429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95038 = PCURVE('',#89214,#95039); -#95039 = DEFINITIONAL_REPRESENTATION('',(#95040),#95048); -#95040 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#95041,#95042,#95043,#95044 - ,#95045,#95046,#95047),.UNSPECIFIED.,.F.,.F.) +#97430 = PCURVE('',#91606,#97431); +#97431 = DEFINITIONAL_REPRESENTATION('',(#97432),#97440); +#97432 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97433,#97434,#97435,#97436 + ,#97437,#97438,#97439),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#95041 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#95042 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#95043 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#95044 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#95045 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#95046 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#95047 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#95048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95049 = ORIENTED_EDGE('',*,*,#95050,.T.); -#95050 = EDGE_CURVE('',#95024,#95000,#95051,.T.); -#95051 = SURFACE_CURVE('',#95052,(#95056,#95062),.PCURVE_S1.); -#95052 = LINE('',#95053,#95054); -#95053 = CARTESIAN_POINT('',(1.35,-0.304819755875,0.75)); -#95054 = VECTOR('',#95055,1.); -#95055 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95056 = PCURVE('',#94868,#95057); -#95057 = DEFINITIONAL_REPRESENTATION('',(#95058),#95061); -#95058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95059,#95060),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#95059 = CARTESIAN_POINT('',(3.162095483347,-8.65)); -#95060 = CARTESIAN_POINT('',(3.162095483347,-8.85)); -#95061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95062 = PCURVE('',#89296,#95063); -#95063 = DEFINITIONAL_REPRESENTATION('',(#95064),#95068); -#95064 = LINE('',#95065,#95066); -#95065 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#95066 = VECTOR('',#95067,1.); -#95067 = DIRECTION('',(0.E+000,-1.)); -#95068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95069 = ADVANCED_FACE('',(#95070),#89214,.F.); -#95070 = FACE_BOUND('',#95071,.T.); -#95071 = EDGE_LOOP('',(#95072,#95093,#95094,#95095,#95096,#95097,#95118, - #95119,#95120,#95121,#95122,#95143)); -#95072 = ORIENTED_EDGE('',*,*,#95073,.F.); -#95073 = EDGE_CURVE('',#95024,#89199,#95074,.T.); -#95074 = SURFACE_CURVE('',#95075,(#95079,#95086),.PCURVE_S1.); -#95075 = LINE('',#95076,#95077); -#95076 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.75)); -#95077 = VECTOR('',#95078,1.); -#95078 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95079 = PCURVE('',#89214,#95080); -#95080 = DEFINITIONAL_REPRESENTATION('',(#95081),#95085); -#95081 = LINE('',#95082,#95083); -#95082 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#95083 = VECTOR('',#95084,1.); -#95084 = DIRECTION('',(3.563627120235E-016,1.)); -#95085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95086 = PCURVE('',#89296,#95087); -#95087 = DEFINITIONAL_REPRESENTATION('',(#95088),#95092); -#95088 = LINE('',#95089,#95090); -#95089 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95090 = VECTOR('',#95091,1.); -#95091 = DIRECTION('',(1.,0.E+000)); -#95092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95093 = ORIENTED_EDGE('',*,*,#95023,.T.); -#95094 = ORIENTED_EDGE('',*,*,#94901,.T.); -#95095 = ORIENTED_EDGE('',*,*,#94672,.T.); -#95096 = ORIENTED_EDGE('',*,*,#94462,.T.); -#95097 = ORIENTED_EDGE('',*,*,#95098,.T.); -#95098 = EDGE_CURVE('',#94435,#94516,#95099,.T.); -#95099 = SURFACE_CURVE('',#95100,(#95104,#95111),.PCURVE_S1.); -#95100 = LINE('',#95101,#95102); -#95101 = CARTESIAN_POINT('',(1.35,-1.,1.159810404338E-002)); -#95102 = VECTOR('',#95103,1.); -#95103 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#95104 = PCURVE('',#89214,#95105); -#95105 = DEFINITIONAL_REPRESENTATION('',(#95106),#95110); -#95106 = LINE('',#95107,#95108); -#95107 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#95108 = VECTOR('',#95109,1.); -#95109 = DIRECTION('',(-1.,2.101748079665E-016)); -#95110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95111 = PCURVE('',#94450,#95112); -#95112 = DEFINITIONAL_REPRESENTATION('',(#95113),#95117); -#95113 = LINE('',#95114,#95115); -#95114 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); -#95115 = VECTOR('',#95116,1.); -#95116 = DIRECTION('',(1.,0.E+000)); -#95117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95118 = ORIENTED_EDGE('',*,*,#94513,.F.); -#95119 = ORIENTED_EDGE('',*,*,#94751,.F.); -#95120 = ORIENTED_EDGE('',*,*,#94804,.F.); -#95121 = ORIENTED_EDGE('',*,*,#94925,.F.); -#95122 = ORIENTED_EDGE('',*,*,#95123,.T.); -#95123 = EDGE_CURVE('',#94926,#89197,#95124,.T.); -#95124 = SURFACE_CURVE('',#95125,(#95129,#95136),.PCURVE_S1.); -#95125 = LINE('',#95126,#95127); -#95126 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); -#95127 = VECTOR('',#95128,1.); -#95128 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95129 = PCURVE('',#89214,#95130); -#95130 = DEFINITIONAL_REPRESENTATION('',(#95131),#95135); -#95131 = LINE('',#95132,#95133); -#95132 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95133 = VECTOR('',#95134,1.); -#95134 = DIRECTION('',(3.563627120235E-016,1.)); -#95135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95136 = PCURVE('',#89242,#95137); -#95137 = DEFINITIONAL_REPRESENTATION('',(#95138),#95142); -#95138 = LINE('',#95139,#95140); -#95139 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95140 = VECTOR('',#95141,1.); -#95141 = DIRECTION('',(-1.,0.E+000)); -#95142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95143 = ORIENTED_EDGE('',*,*,#89196,.T.); -#95144 = ADVANCED_FACE('',(#95145),#89296,.F.); -#95145 = FACE_BOUND('',#95146,.T.); -#95146 = EDGE_LOOP('',(#95147,#95148,#95149,#95150)); -#95147 = ORIENTED_EDGE('',*,*,#95050,.F.); -#95148 = ORIENTED_EDGE('',*,*,#95073,.T.); -#95149 = ORIENTED_EDGE('',*,*,#89282,.T.); -#95150 = ORIENTED_EDGE('',*,*,#95151,.F.); -#95151 = EDGE_CURVE('',#95000,#89255,#95152,.T.); -#95152 = SURFACE_CURVE('',#95153,(#95157,#95164),.PCURVE_S1.); -#95153 = LINE('',#95154,#95155); -#95154 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.75)); -#95155 = VECTOR('',#95156,1.); -#95156 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95157 = PCURVE('',#89296,#95158); -#95158 = DEFINITIONAL_REPRESENTATION('',(#95159),#95163); -#95159 = LINE('',#95160,#95161); -#95160 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#95161 = VECTOR('',#95162,1.); -#95162 = DIRECTION('',(1.,0.E+000)); -#95163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95164 = PCURVE('',#89270,#95165); -#95165 = DEFINITIONAL_REPRESENTATION('',(#95166),#95170); -#95166 = LINE('',#95167,#95168); -#95167 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#95168 = VECTOR('',#95169,1.); -#95169 = DIRECTION('',(-3.563627120235E-016,1.)); -#95170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95171 = ADVANCED_FACE('',(#95172),#89270,.F.); -#95172 = FACE_BOUND('',#95173,.T.); -#95173 = EDGE_LOOP('',(#95174,#95195,#95196,#95197,#95198,#95199,#95220, - #95221,#95222,#95223,#95224,#95225)); -#95174 = ORIENTED_EDGE('',*,*,#95175,.F.); -#95175 = EDGE_CURVE('',#94953,#89227,#95176,.T.); -#95176 = SURFACE_CURVE('',#95177,(#95181,#95188),.PCURVE_S1.); -#95177 = LINE('',#95178,#95179); -#95178 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.65)); -#95179 = VECTOR('',#95180,1.); -#95180 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95181 = PCURVE('',#89270,#95182); -#95182 = DEFINITIONAL_REPRESENTATION('',(#95183),#95187); -#95183 = LINE('',#95184,#95185); -#95184 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95185 = VECTOR('',#95186,1.); -#95186 = DIRECTION('',(-3.563627120235E-016,1.)); -#95187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95188 = PCURVE('',#89242,#95189); -#95189 = DEFINITIONAL_REPRESENTATION('',(#95190),#95194); -#95190 = LINE('',#95191,#95192); -#95191 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#95192 = VECTOR('',#95193,1.); -#95193 = DIRECTION('',(-1.,0.E+000)); -#95194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95195 = ORIENTED_EDGE('',*,*,#94974,.T.); -#95196 = ORIENTED_EDGE('',*,*,#94826,.T.); -#95197 = ORIENTED_EDGE('',*,*,#94697,.T.); -#95198 = ORIENTED_EDGE('',*,*,#94566,.T.); -#95199 = ORIENTED_EDGE('',*,*,#95200,.T.); -#95200 = EDGE_CURVE('',#94544,#94407,#95201,.T.); -#95201 = SURFACE_CURVE('',#95202,(#95206,#95213),.PCURVE_S1.); -#95202 = LINE('',#95203,#95204); -#95203 = CARTESIAN_POINT('',(1.15,-1.,1.159810404338E-002)); -#95204 = VECTOR('',#95205,1.); -#95205 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#95206 = PCURVE('',#89270,#95207); -#95207 = DEFINITIONAL_REPRESENTATION('',(#95208),#95212); -#95208 = LINE('',#95209,#95210); -#95209 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#95210 = VECTOR('',#95211,1.); -#95211 = DIRECTION('',(-1.,-2.101748079665E-016)); -#95212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95213 = PCURVE('',#94450,#95214); -#95214 = DEFINITIONAL_REPRESENTATION('',(#95215),#95219); -#95215 = LINE('',#95216,#95217); -#95216 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#95217 = VECTOR('',#95218,1.); -#95218 = DIRECTION('',(-1.,0.E+000)); -#95219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95220 = ORIENTED_EDGE('',*,*,#94404,.F.); -#95221 = ORIENTED_EDGE('',*,*,#94618,.F.); -#95222 = ORIENTED_EDGE('',*,*,#94879,.F.); -#95223 = ORIENTED_EDGE('',*,*,#94999,.F.); -#95224 = ORIENTED_EDGE('',*,*,#95151,.T.); -#95225 = ORIENTED_EDGE('',*,*,#89254,.T.); -#95226 = ADVANCED_FACE('',(#95227),#89242,.F.); -#95227 = FACE_BOUND('',#95228,.T.); -#95228 = EDGE_LOOP('',(#95229,#95230,#95231,#95232)); -#95229 = ORIENTED_EDGE('',*,*,#94952,.F.); -#95230 = ORIENTED_EDGE('',*,*,#95175,.T.); -#95231 = ORIENTED_EDGE('',*,*,#89226,.T.); -#95232 = ORIENTED_EDGE('',*,*,#95123,.F.); -#95233 = ADVANCED_FACE('',(#95234),#94450,.T.); -#95234 = FACE_BOUND('',#95235,.T.); -#95235 = EDGE_LOOP('',(#95236,#95237,#95238,#95239)); -#95236 = ORIENTED_EDGE('',*,*,#95200,.F.); -#95237 = ORIENTED_EDGE('',*,*,#94543,.F.); -#95238 = ORIENTED_EDGE('',*,*,#95098,.F.); -#95239 = ORIENTED_EDGE('',*,*,#94434,.F.); -#95240 = ADVANCED_FACE('',(#95241),#95255,.T.); -#95241 = FACE_BOUND('',#95242,.T.); -#95242 = EDGE_LOOP('',(#95243,#95273,#95301,#95324)); -#95243 = ORIENTED_EDGE('',*,*,#95244,.T.); -#95244 = EDGE_CURVE('',#95245,#95247,#95249,.T.); -#95245 = VERTEX_POINT('',#95246); -#95246 = CARTESIAN_POINT('',(5.35,-0.74341632541,-0.308197125857)); -#95247 = VERTEX_POINT('',#95248); -#95248 = CARTESIAN_POINT('',(5.35,-1.,-0.308197125857)); -#95249 = SURFACE_CURVE('',#95250,(#95254,#95266),.PCURVE_S1.); -#95250 = LINE('',#95251,#95252); -#95251 = CARTESIAN_POINT('',(5.35,-0.74341632541,-0.308197125857)); -#95252 = VECTOR('',#95253,1.); -#95253 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#95254 = PCURVE('',#95255,#95260); -#95255 = PLANE('',#95256); -#95256 = AXIS2_PLACEMENT_3D('',#95257,#95258,#95259); -#95257 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#95258 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95259 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95260 = DEFINITIONAL_REPRESENTATION('',(#95261),#95265); -#95261 = LINE('',#95262,#95263); -#95262 = CARTESIAN_POINT('',(4.65,0.E+000)); -#95263 = VECTOR('',#95264,1.); -#95264 = DIRECTION('',(0.E+000,-1.)); -#95265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95266 = PCURVE('',#89519,#95267); -#95267 = DEFINITIONAL_REPRESENTATION('',(#95268),#95272); -#95268 = LINE('',#95269,#95270); -#95269 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#95270 = VECTOR('',#95271,1.); -#95271 = DIRECTION('',(0.E+000,-1.)); -#95272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95273 = ORIENTED_EDGE('',*,*,#95274,.T.); -#95274 = EDGE_CURVE('',#95247,#95275,#95277,.T.); -#95275 = VERTEX_POINT('',#95276); -#95276 = CARTESIAN_POINT('',(5.15,-1.,-0.308197125857)); -#95277 = SURFACE_CURVE('',#95278,(#95282,#95289),.PCURVE_S1.); -#95278 = LINE('',#95279,#95280); -#95279 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#95280 = VECTOR('',#95281,1.); -#95281 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95282 = PCURVE('',#95255,#95283); -#95283 = DEFINITIONAL_REPRESENTATION('',(#95284),#95288); -#95284 = LINE('',#95285,#95286); -#95285 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#95286 = VECTOR('',#95287,1.); -#95287 = DIRECTION('',(1.,0.E+000)); -#95288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95289 = PCURVE('',#95290,#95295); -#95290 = PLANE('',#95291); -#95291 = AXIS2_PLACEMENT_3D('',#95292,#95293,#95294); -#95292 = CARTESIAN_POINT('',(5.25,-1.,-0.258196742327)); -#95293 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#95294 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#95295 = DEFINITIONAL_REPRESENTATION('',(#95296),#95300); -#95296 = LINE('',#95297,#95298); -#95297 = CARTESIAN_POINT('',(5.000038352949E-002,4.75)); -#95298 = VECTOR('',#95299,1.); -#95299 = DIRECTION('',(0.E+000,-1.)); -#95300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97433 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#97434 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#97435 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#97436 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#97437 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#97438 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#97439 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#97440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95301 = ORIENTED_EDGE('',*,*,#95302,.F.); -#95302 = EDGE_CURVE('',#95303,#95275,#95305,.T.); -#95303 = VERTEX_POINT('',#95304); -#95304 = CARTESIAN_POINT('',(5.15,-0.74341632541,-0.308197125857)); -#95305 = SURFACE_CURVE('',#95306,(#95310,#95317),.PCURVE_S1.); -#95306 = LINE('',#95307,#95308); -#95307 = CARTESIAN_POINT('',(5.15,-0.74341632541,-0.308197125857)); -#95308 = VECTOR('',#95309,1.); -#95309 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#95310 = PCURVE('',#95255,#95311); -#95311 = DEFINITIONAL_REPRESENTATION('',(#95312),#95316); -#95312 = LINE('',#95313,#95314); -#95313 = CARTESIAN_POINT('',(4.85,-1.110223024625E-016)); -#95314 = VECTOR('',#95315,1.); -#95315 = DIRECTION('',(0.E+000,-1.)); -#95316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95317 = PCURVE('',#89465,#95318); -#95318 = DEFINITIONAL_REPRESENTATION('',(#95319),#95323); -#95319 = LINE('',#95320,#95321); -#95320 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#95321 = VECTOR('',#95322,1.); -#95322 = DIRECTION('',(0.E+000,-1.)); -#95323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95324 = ORIENTED_EDGE('',*,*,#95325,.T.); -#95325 = EDGE_CURVE('',#95303,#95245,#95326,.T.); -#95326 = SURFACE_CURVE('',#95327,(#95331,#95338),.PCURVE_S1.); -#95327 = LINE('',#95328,#95329); -#95328 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#95329 = VECTOR('',#95330,1.); -#95330 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95331 = PCURVE('',#95255,#95332); -#95332 = DEFINITIONAL_REPRESENTATION('',(#95333),#95337); -#95333 = LINE('',#95334,#95335); -#95334 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95335 = VECTOR('',#95336,1.); -#95336 = DIRECTION('',(-1.,0.E+000)); -#95337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95338 = PCURVE('',#95339,#95344); -#95339 = CYLINDRICAL_SURFACE('',#95340,0.308574064194); -#95340 = AXIS2_PLACEMENT_3D('',#95341,#95342,#95343); -#95341 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#95342 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95343 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95344 = DEFINITIONAL_REPRESENTATION('',(#95345),#95348); -#95345 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95346,#95347),.UNSPECIFIED., +#97441 = ORIENTED_EDGE('',*,*,#97442,.T.); +#97442 = EDGE_CURVE('',#97416,#97392,#97443,.T.); +#97443 = SURFACE_CURVE('',#97444,(#97448,#97454),.PCURVE_S1.); +#97444 = LINE('',#97445,#97446); +#97445 = CARTESIAN_POINT('',(1.35,-0.304819755875,0.75)); +#97446 = VECTOR('',#97447,1.); +#97447 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97448 = PCURVE('',#97260,#97449); +#97449 = DEFINITIONAL_REPRESENTATION('',(#97450),#97453); +#97450 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97451,#97452),.UNSPECIFIED., + .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#97451 = CARTESIAN_POINT('',(3.162095483347,-8.65)); +#97452 = CARTESIAN_POINT('',(3.162095483347,-8.85)); +#97453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97454 = PCURVE('',#91688,#97455); +#97455 = DEFINITIONAL_REPRESENTATION('',(#97456),#97460); +#97456 = LINE('',#97457,#97458); +#97457 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#97458 = VECTOR('',#97459,1.); +#97459 = DIRECTION('',(0.E+000,-1.)); +#97460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97461 = ADVANCED_FACE('',(#97462),#91606,.F.); +#97462 = FACE_BOUND('',#97463,.T.); +#97463 = EDGE_LOOP('',(#97464,#97485,#97486,#97487,#97488,#97489,#97510, + #97511,#97512,#97513,#97514,#97535)); +#97464 = ORIENTED_EDGE('',*,*,#97465,.F.); +#97465 = EDGE_CURVE('',#97416,#91591,#97466,.T.); +#97466 = SURFACE_CURVE('',#97467,(#97471,#97478),.PCURVE_S1.); +#97467 = LINE('',#97468,#97469); +#97468 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.75)); +#97469 = VECTOR('',#97470,1.); +#97470 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#97471 = PCURVE('',#91606,#97472); +#97472 = DEFINITIONAL_REPRESENTATION('',(#97473),#97477); +#97473 = LINE('',#97474,#97475); +#97474 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#97475 = VECTOR('',#97476,1.); +#97476 = DIRECTION('',(3.563627120235E-016,1.)); +#97477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97478 = PCURVE('',#91688,#97479); +#97479 = DEFINITIONAL_REPRESENTATION('',(#97480),#97484); +#97480 = LINE('',#97481,#97482); +#97481 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97482 = VECTOR('',#97483,1.); +#97483 = DIRECTION('',(1.,0.E+000)); +#97484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97485 = ORIENTED_EDGE('',*,*,#97415,.T.); +#97486 = ORIENTED_EDGE('',*,*,#97293,.T.); +#97487 = ORIENTED_EDGE('',*,*,#97064,.T.); +#97488 = ORIENTED_EDGE('',*,*,#96854,.T.); +#97489 = ORIENTED_EDGE('',*,*,#97490,.T.); +#97490 = EDGE_CURVE('',#96827,#96908,#97491,.T.); +#97491 = SURFACE_CURVE('',#97492,(#97496,#97503),.PCURVE_S1.); +#97492 = LINE('',#97493,#97494); +#97493 = CARTESIAN_POINT('',(1.35,-1.,1.159810404338E-002)); +#97494 = VECTOR('',#97495,1.); +#97495 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#97496 = PCURVE('',#91606,#97497); +#97497 = DEFINITIONAL_REPRESENTATION('',(#97498),#97502); +#97498 = LINE('',#97499,#97500); +#97499 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#97500 = VECTOR('',#97501,1.); +#97501 = DIRECTION('',(-1.,2.101748079665E-016)); +#97502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97503 = PCURVE('',#96842,#97504); +#97504 = DEFINITIONAL_REPRESENTATION('',(#97505),#97509); +#97505 = LINE('',#97506,#97507); +#97506 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); +#97507 = VECTOR('',#97508,1.); +#97508 = DIRECTION('',(1.,0.E+000)); +#97509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97510 = ORIENTED_EDGE('',*,*,#96905,.F.); +#97511 = ORIENTED_EDGE('',*,*,#97143,.F.); +#97512 = ORIENTED_EDGE('',*,*,#97196,.F.); +#97513 = ORIENTED_EDGE('',*,*,#97317,.F.); +#97514 = ORIENTED_EDGE('',*,*,#97515,.T.); +#97515 = EDGE_CURVE('',#97318,#91589,#97516,.T.); +#97516 = SURFACE_CURVE('',#97517,(#97521,#97528),.PCURVE_S1.); +#97517 = LINE('',#97518,#97519); +#97518 = CARTESIAN_POINT('',(1.35,-0.527847992439,0.65)); +#97519 = VECTOR('',#97520,1.); +#97520 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#97521 = PCURVE('',#91606,#97522); +#97522 = DEFINITIONAL_REPRESENTATION('',(#97523),#97527); +#97523 = LINE('',#97524,#97525); +#97524 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97525 = VECTOR('',#97526,1.); +#97526 = DIRECTION('',(3.563627120235E-016,1.)); +#97527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97528 = PCURVE('',#91634,#97529); +#97529 = DEFINITIONAL_REPRESENTATION('',(#97530),#97534); +#97530 = LINE('',#97531,#97532); +#97531 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97532 = VECTOR('',#97533,1.); +#97533 = DIRECTION('',(-1.,0.E+000)); +#97534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97535 = ORIENTED_EDGE('',*,*,#91588,.T.); +#97536 = ADVANCED_FACE('',(#97537),#91688,.F.); +#97537 = FACE_BOUND('',#97538,.T.); +#97538 = EDGE_LOOP('',(#97539,#97540,#97541,#97542)); +#97539 = ORIENTED_EDGE('',*,*,#97442,.F.); +#97540 = ORIENTED_EDGE('',*,*,#97465,.T.); +#97541 = ORIENTED_EDGE('',*,*,#91674,.T.); +#97542 = ORIENTED_EDGE('',*,*,#97543,.F.); +#97543 = EDGE_CURVE('',#97392,#91647,#97544,.T.); +#97544 = SURFACE_CURVE('',#97545,(#97549,#97556),.PCURVE_S1.); +#97545 = LINE('',#97546,#97547); +#97546 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.75)); +#97547 = VECTOR('',#97548,1.); +#97548 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#97549 = PCURVE('',#91688,#97550); +#97550 = DEFINITIONAL_REPRESENTATION('',(#97551),#97555); +#97551 = LINE('',#97552,#97553); +#97552 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#97553 = VECTOR('',#97554,1.); +#97554 = DIRECTION('',(1.,0.E+000)); +#97555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97556 = PCURVE('',#91662,#97557); +#97557 = DEFINITIONAL_REPRESENTATION('',(#97558),#97562); +#97558 = LINE('',#97559,#97560); +#97559 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#97560 = VECTOR('',#97561,1.); +#97561 = DIRECTION('',(-3.563627120235E-016,1.)); +#97562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97563 = ADVANCED_FACE('',(#97564),#91662,.F.); +#97564 = FACE_BOUND('',#97565,.T.); +#97565 = EDGE_LOOP('',(#97566,#97587,#97588,#97589,#97590,#97591,#97612, + #97613,#97614,#97615,#97616,#97617)); +#97566 = ORIENTED_EDGE('',*,*,#97567,.F.); +#97567 = EDGE_CURVE('',#97345,#91619,#97568,.T.); +#97568 = SURFACE_CURVE('',#97569,(#97573,#97580),.PCURVE_S1.); +#97569 = LINE('',#97570,#97571); +#97570 = CARTESIAN_POINT('',(1.15,-0.527847992439,0.65)); +#97571 = VECTOR('',#97572,1.); +#97572 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#97573 = PCURVE('',#91662,#97574); +#97574 = DEFINITIONAL_REPRESENTATION('',(#97575),#97579); +#97575 = LINE('',#97576,#97577); +#97576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97577 = VECTOR('',#97578,1.); +#97578 = DIRECTION('',(-3.563627120235E-016,1.)); +#97579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97580 = PCURVE('',#91634,#97581); +#97581 = DEFINITIONAL_REPRESENTATION('',(#97582),#97586); +#97582 = LINE('',#97583,#97584); +#97583 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#97584 = VECTOR('',#97585,1.); +#97585 = DIRECTION('',(-1.,0.E+000)); +#97586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97587 = ORIENTED_EDGE('',*,*,#97366,.T.); +#97588 = ORIENTED_EDGE('',*,*,#97218,.T.); +#97589 = ORIENTED_EDGE('',*,*,#97089,.T.); +#97590 = ORIENTED_EDGE('',*,*,#96958,.T.); +#97591 = ORIENTED_EDGE('',*,*,#97592,.T.); +#97592 = EDGE_CURVE('',#96936,#96799,#97593,.T.); +#97593 = SURFACE_CURVE('',#97594,(#97598,#97605),.PCURVE_S1.); +#97594 = LINE('',#97595,#97596); +#97595 = CARTESIAN_POINT('',(1.15,-1.,1.159810404338E-002)); +#97596 = VECTOR('',#97597,1.); +#97597 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#97598 = PCURVE('',#91662,#97599); +#97599 = DEFINITIONAL_REPRESENTATION('',(#97600),#97604); +#97600 = LINE('',#97601,#97602); +#97601 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#97602 = VECTOR('',#97603,1.); +#97603 = DIRECTION('',(-1.,-2.101748079665E-016)); +#97604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97605 = PCURVE('',#96842,#97606); +#97606 = DEFINITIONAL_REPRESENTATION('',(#97607),#97611); +#97607 = LINE('',#97608,#97609); +#97608 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#97609 = VECTOR('',#97610,1.); +#97610 = DIRECTION('',(-1.,0.E+000)); +#97611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97612 = ORIENTED_EDGE('',*,*,#96796,.F.); +#97613 = ORIENTED_EDGE('',*,*,#97010,.F.); +#97614 = ORIENTED_EDGE('',*,*,#97271,.F.); +#97615 = ORIENTED_EDGE('',*,*,#97391,.F.); +#97616 = ORIENTED_EDGE('',*,*,#97543,.T.); +#97617 = ORIENTED_EDGE('',*,*,#91646,.T.); +#97618 = ADVANCED_FACE('',(#97619),#91634,.F.); +#97619 = FACE_BOUND('',#97620,.T.); +#97620 = EDGE_LOOP('',(#97621,#97622,#97623,#97624)); +#97621 = ORIENTED_EDGE('',*,*,#97344,.F.); +#97622 = ORIENTED_EDGE('',*,*,#97567,.T.); +#97623 = ORIENTED_EDGE('',*,*,#91618,.T.); +#97624 = ORIENTED_EDGE('',*,*,#97515,.F.); +#97625 = ADVANCED_FACE('',(#97626),#96842,.T.); +#97626 = FACE_BOUND('',#97627,.T.); +#97627 = EDGE_LOOP('',(#97628,#97629,#97630,#97631)); +#97628 = ORIENTED_EDGE('',*,*,#97592,.F.); +#97629 = ORIENTED_EDGE('',*,*,#96935,.F.); +#97630 = ORIENTED_EDGE('',*,*,#97490,.F.); +#97631 = ORIENTED_EDGE('',*,*,#96826,.F.); +#97632 = ADVANCED_FACE('',(#97633),#97647,.T.); +#97633 = FACE_BOUND('',#97634,.T.); +#97634 = EDGE_LOOP('',(#97635,#97665,#97693,#97716)); +#97635 = ORIENTED_EDGE('',*,*,#97636,.T.); +#97636 = EDGE_CURVE('',#97637,#97639,#97641,.T.); +#97637 = VERTEX_POINT('',#97638); +#97638 = CARTESIAN_POINT('',(5.35,-0.74341632541,-0.308197125857)); +#97639 = VERTEX_POINT('',#97640); +#97640 = CARTESIAN_POINT('',(5.35,-1.,-0.308197125857)); +#97641 = SURFACE_CURVE('',#97642,(#97646,#97658),.PCURVE_S1.); +#97642 = LINE('',#97643,#97644); +#97643 = CARTESIAN_POINT('',(5.35,-0.74341632541,-0.308197125857)); +#97644 = VECTOR('',#97645,1.); +#97645 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#97646 = PCURVE('',#97647,#97652); +#97647 = PLANE('',#97648); +#97648 = AXIS2_PLACEMENT_3D('',#97649,#97650,#97651); +#97649 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#97650 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#97651 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97652 = DEFINITIONAL_REPRESENTATION('',(#97653),#97657); +#97653 = LINE('',#97654,#97655); +#97654 = CARTESIAN_POINT('',(4.65,0.E+000)); +#97655 = VECTOR('',#97656,1.); +#97656 = DIRECTION('',(0.E+000,-1.)); +#97657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97658 = PCURVE('',#91911,#97659); +#97659 = DEFINITIONAL_REPRESENTATION('',(#97660),#97664); +#97660 = LINE('',#97661,#97662); +#97661 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#97662 = VECTOR('',#97663,1.); +#97663 = DIRECTION('',(0.E+000,-1.)); +#97664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97665 = ORIENTED_EDGE('',*,*,#97666,.T.); +#97666 = EDGE_CURVE('',#97639,#97667,#97669,.T.); +#97667 = VERTEX_POINT('',#97668); +#97668 = CARTESIAN_POINT('',(5.15,-1.,-0.308197125857)); +#97669 = SURFACE_CURVE('',#97670,(#97674,#97681),.PCURVE_S1.); +#97670 = LINE('',#97671,#97672); +#97671 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#97672 = VECTOR('',#97673,1.); +#97673 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97674 = PCURVE('',#97647,#97675); +#97675 = DEFINITIONAL_REPRESENTATION('',(#97676),#97680); +#97676 = LINE('',#97677,#97678); +#97677 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#97678 = VECTOR('',#97679,1.); +#97679 = DIRECTION('',(1.,0.E+000)); +#97680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97681 = PCURVE('',#97682,#97687); +#97682 = PLANE('',#97683); +#97683 = AXIS2_PLACEMENT_3D('',#97684,#97685,#97686); +#97684 = CARTESIAN_POINT('',(5.25,-1.,-0.258196742327)); +#97685 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#97686 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#97687 = DEFINITIONAL_REPRESENTATION('',(#97688),#97692); +#97688 = LINE('',#97689,#97690); +#97689 = CARTESIAN_POINT('',(5.000038352949E-002,4.75)); +#97690 = VECTOR('',#97691,1.); +#97691 = DIRECTION('',(0.E+000,-1.)); +#97692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97693 = ORIENTED_EDGE('',*,*,#97694,.F.); +#97694 = EDGE_CURVE('',#97695,#97667,#97697,.T.); +#97695 = VERTEX_POINT('',#97696); +#97696 = CARTESIAN_POINT('',(5.15,-0.74341632541,-0.308197125857)); +#97697 = SURFACE_CURVE('',#97698,(#97702,#97709),.PCURVE_S1.); +#97698 = LINE('',#97699,#97700); +#97699 = CARTESIAN_POINT('',(5.15,-0.74341632541,-0.308197125857)); +#97700 = VECTOR('',#97701,1.); +#97701 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#97702 = PCURVE('',#97647,#97703); +#97703 = DEFINITIONAL_REPRESENTATION('',(#97704),#97708); +#97704 = LINE('',#97705,#97706); +#97705 = CARTESIAN_POINT('',(4.85,-1.110223024625E-016)); +#97706 = VECTOR('',#97707,1.); +#97707 = DIRECTION('',(0.E+000,-1.)); +#97708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97709 = PCURVE('',#91857,#97710); +#97710 = DEFINITIONAL_REPRESENTATION('',(#97711),#97715); +#97711 = LINE('',#97712,#97713); +#97712 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#97713 = VECTOR('',#97714,1.); +#97714 = DIRECTION('',(0.E+000,-1.)); +#97715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97716 = ORIENTED_EDGE('',*,*,#97717,.T.); +#97717 = EDGE_CURVE('',#97695,#97637,#97718,.T.); +#97718 = SURFACE_CURVE('',#97719,(#97723,#97730),.PCURVE_S1.); +#97719 = LINE('',#97720,#97721); +#97720 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#97721 = VECTOR('',#97722,1.); +#97722 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97723 = PCURVE('',#97647,#97724); +#97724 = DEFINITIONAL_REPRESENTATION('',(#97725),#97729); +#97725 = LINE('',#97726,#97727); +#97726 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97727 = VECTOR('',#97728,1.); +#97728 = DIRECTION('',(-1.,0.E+000)); +#97729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97730 = PCURVE('',#97731,#97736); +#97731 = CYLINDRICAL_SURFACE('',#97732,0.308574064194); +#97732 = AXIS2_PLACEMENT_3D('',#97733,#97734,#97735); +#97733 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#97734 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97735 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97736 = DEFINITIONAL_REPRESENTATION('',(#97737),#97740); +#97737 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97738,#97739),.UNSPECIFIED., .F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#95346 = CARTESIAN_POINT('',(3.191025391152,4.85)); -#95347 = CARTESIAN_POINT('',(3.191025391152,4.65)); -#95348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95349 = ADVANCED_FACE('',(#95350),#95364,.T.); -#95350 = FACE_BOUND('',#95351,.T.); -#95351 = EDGE_LOOP('',(#95352,#95382,#95405,#95428)); -#95352 = ORIENTED_EDGE('',*,*,#95353,.T.); -#95353 = EDGE_CURVE('',#95354,#95356,#95358,.T.); -#95354 = VERTEX_POINT('',#95355); -#95355 = CARTESIAN_POINT('',(5.15,-0.740726081328,-0.208196358798)); -#95356 = VERTEX_POINT('',#95357); -#95357 = CARTESIAN_POINT('',(5.15,-1.,-0.208196358798)); -#95358 = SURFACE_CURVE('',#95359,(#95363,#95375),.PCURVE_S1.); -#95359 = LINE('',#95360,#95361); -#95360 = CARTESIAN_POINT('',(5.15,-0.740726081328,-0.208196358798)); -#95361 = VECTOR('',#95362,1.); -#95362 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#95363 = PCURVE('',#95364,#95369); -#95364 = PLANE('',#95365); -#95365 = AXIS2_PLACEMENT_3D('',#95366,#95367,#95368); -#95366 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#95367 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95368 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95369 = DEFINITIONAL_REPRESENTATION('',(#95370),#95374); -#95370 = LINE('',#95371,#95372); -#95371 = CARTESIAN_POINT('',(-4.85,0.E+000)); -#95372 = VECTOR('',#95373,1.); -#95373 = DIRECTION('',(0.E+000,-1.)); -#95374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95375 = PCURVE('',#89465,#95376); -#95376 = DEFINITIONAL_REPRESENTATION('',(#95377),#95381); -#95377 = LINE('',#95378,#95379); -#95378 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#95379 = VECTOR('',#95380,1.); -#95380 = DIRECTION('',(0.E+000,-1.)); -#95381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95382 = ORIENTED_EDGE('',*,*,#95383,.T.); -#95383 = EDGE_CURVE('',#95356,#95384,#95386,.T.); -#95384 = VERTEX_POINT('',#95385); -#95385 = CARTESIAN_POINT('',(5.35,-1.,-0.208196358798)); -#95386 = SURFACE_CURVE('',#95387,(#95391,#95398),.PCURVE_S1.); -#95387 = LINE('',#95388,#95389); -#95388 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#95389 = VECTOR('',#95390,1.); -#95390 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95391 = PCURVE('',#95364,#95392); -#95392 = DEFINITIONAL_REPRESENTATION('',(#95393),#95397); -#95393 = LINE('',#95394,#95395); -#95394 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#95395 = VECTOR('',#95396,1.); -#95396 = DIRECTION('',(1.,0.E+000)); -#95397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95398 = PCURVE('',#95290,#95399); -#95399 = DEFINITIONAL_REPRESENTATION('',(#95400),#95404); -#95400 = LINE('',#95401,#95402); -#95401 = CARTESIAN_POINT('',(-5.000038352949E-002,4.75)); -#95402 = VECTOR('',#95403,1.); -#95403 = DIRECTION('',(0.E+000,1.)); -#95404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95405 = ORIENTED_EDGE('',*,*,#95406,.F.); -#95406 = EDGE_CURVE('',#95407,#95384,#95409,.T.); -#95407 = VERTEX_POINT('',#95408); -#95408 = CARTESIAN_POINT('',(5.35,-0.740726081328,-0.208196358798)); -#95409 = SURFACE_CURVE('',#95410,(#95414,#95421),.PCURVE_S1.); -#95410 = LINE('',#95411,#95412); -#95411 = CARTESIAN_POINT('',(5.35,-0.740726081328,-0.208196358798)); -#95412 = VECTOR('',#95413,1.); -#95413 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#95414 = PCURVE('',#95364,#95415); -#95415 = DEFINITIONAL_REPRESENTATION('',(#95416),#95420); -#95416 = LINE('',#95417,#95418); -#95417 = CARTESIAN_POINT('',(-4.65,0.E+000)); -#95418 = VECTOR('',#95419,1.); -#95419 = DIRECTION('',(0.E+000,-1.)); -#95420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95421 = PCURVE('',#89519,#95422); -#95422 = DEFINITIONAL_REPRESENTATION('',(#95423),#95427); -#95423 = LINE('',#95424,#95425); -#95424 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#95425 = VECTOR('',#95426,1.); -#95426 = DIRECTION('',(0.E+000,-1.)); -#95427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95428 = ORIENTED_EDGE('',*,*,#95429,.T.); -#95429 = EDGE_CURVE('',#95407,#95354,#95430,.T.); -#95430 = SURFACE_CURVE('',#95431,(#95435,#95442),.PCURVE_S1.); -#95431 = LINE('',#95432,#95433); -#95432 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#95433 = VECTOR('',#95434,1.); -#95434 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95435 = PCURVE('',#95364,#95436); -#95436 = DEFINITIONAL_REPRESENTATION('',(#95437),#95441); -#95437 = LINE('',#95438,#95439); -#95438 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95439 = VECTOR('',#95440,1.); -#95440 = DIRECTION('',(-1.,0.E+000)); -#95441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95442 = PCURVE('',#95443,#95448); -#95443 = CYLINDRICAL_SURFACE('',#95444,0.208574704164); -#95444 = AXIS2_PLACEMENT_3D('',#95445,#95446,#95447); -#95445 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#95446 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95447 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95448 = DEFINITIONAL_REPRESENTATION('',(#95449),#95452); -#95449 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95450,#95451),.UNSPECIFIED., +#97738 = CARTESIAN_POINT('',(3.191025391152,4.85)); +#97739 = CARTESIAN_POINT('',(3.191025391152,4.65)); +#97740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97741 = ADVANCED_FACE('',(#97742),#97756,.T.); +#97742 = FACE_BOUND('',#97743,.T.); +#97743 = EDGE_LOOP('',(#97744,#97774,#97797,#97820)); +#97744 = ORIENTED_EDGE('',*,*,#97745,.T.); +#97745 = EDGE_CURVE('',#97746,#97748,#97750,.T.); +#97746 = VERTEX_POINT('',#97747); +#97747 = CARTESIAN_POINT('',(5.15,-0.740726081328,-0.208196358798)); +#97748 = VERTEX_POINT('',#97749); +#97749 = CARTESIAN_POINT('',(5.15,-1.,-0.208196358798)); +#97750 = SURFACE_CURVE('',#97751,(#97755,#97767),.PCURVE_S1.); +#97751 = LINE('',#97752,#97753); +#97752 = CARTESIAN_POINT('',(5.15,-0.740726081328,-0.208196358798)); +#97753 = VECTOR('',#97754,1.); +#97754 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#97755 = PCURVE('',#97756,#97761); +#97756 = PLANE('',#97757); +#97757 = AXIS2_PLACEMENT_3D('',#97758,#97759,#97760); +#97758 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#97759 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97760 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97761 = DEFINITIONAL_REPRESENTATION('',(#97762),#97766); +#97762 = LINE('',#97763,#97764); +#97763 = CARTESIAN_POINT('',(-4.85,0.E+000)); +#97764 = VECTOR('',#97765,1.); +#97765 = DIRECTION('',(0.E+000,-1.)); +#97766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97767 = PCURVE('',#91857,#97768); +#97768 = DEFINITIONAL_REPRESENTATION('',(#97769),#97773); +#97769 = LINE('',#97770,#97771); +#97770 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#97771 = VECTOR('',#97772,1.); +#97772 = DIRECTION('',(0.E+000,-1.)); +#97773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97774 = ORIENTED_EDGE('',*,*,#97775,.T.); +#97775 = EDGE_CURVE('',#97748,#97776,#97778,.T.); +#97776 = VERTEX_POINT('',#97777); +#97777 = CARTESIAN_POINT('',(5.35,-1.,-0.208196358798)); +#97778 = SURFACE_CURVE('',#97779,(#97783,#97790),.PCURVE_S1.); +#97779 = LINE('',#97780,#97781); +#97780 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#97781 = VECTOR('',#97782,1.); +#97782 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97783 = PCURVE('',#97756,#97784); +#97784 = DEFINITIONAL_REPRESENTATION('',(#97785),#97789); +#97785 = LINE('',#97786,#97787); +#97786 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#97787 = VECTOR('',#97788,1.); +#97788 = DIRECTION('',(1.,0.E+000)); +#97789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97790 = PCURVE('',#97682,#97791); +#97791 = DEFINITIONAL_REPRESENTATION('',(#97792),#97796); +#97792 = LINE('',#97793,#97794); +#97793 = CARTESIAN_POINT('',(-5.000038352949E-002,4.75)); +#97794 = VECTOR('',#97795,1.); +#97795 = DIRECTION('',(0.E+000,1.)); +#97796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97797 = ORIENTED_EDGE('',*,*,#97798,.F.); +#97798 = EDGE_CURVE('',#97799,#97776,#97801,.T.); +#97799 = VERTEX_POINT('',#97800); +#97800 = CARTESIAN_POINT('',(5.35,-0.740726081328,-0.208196358798)); +#97801 = SURFACE_CURVE('',#97802,(#97806,#97813),.PCURVE_S1.); +#97802 = LINE('',#97803,#97804); +#97803 = CARTESIAN_POINT('',(5.35,-0.740726081328,-0.208196358798)); +#97804 = VECTOR('',#97805,1.); +#97805 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#97806 = PCURVE('',#97756,#97807); +#97807 = DEFINITIONAL_REPRESENTATION('',(#97808),#97812); +#97808 = LINE('',#97809,#97810); +#97809 = CARTESIAN_POINT('',(-4.65,0.E+000)); +#97810 = VECTOR('',#97811,1.); +#97811 = DIRECTION('',(0.E+000,-1.)); +#97812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97813 = PCURVE('',#91911,#97814); +#97814 = DEFINITIONAL_REPRESENTATION('',(#97815),#97819); +#97815 = LINE('',#97816,#97817); +#97816 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#97817 = VECTOR('',#97818,1.); +#97818 = DIRECTION('',(0.E+000,-1.)); +#97819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97820 = ORIENTED_EDGE('',*,*,#97821,.T.); +#97821 = EDGE_CURVE('',#97799,#97746,#97822,.T.); +#97822 = SURFACE_CURVE('',#97823,(#97827,#97834),.PCURVE_S1.); +#97823 = LINE('',#97824,#97825); +#97824 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#97825 = VECTOR('',#97826,1.); +#97826 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97827 = PCURVE('',#97756,#97828); +#97828 = DEFINITIONAL_REPRESENTATION('',(#97829),#97833); +#97829 = LINE('',#97830,#97831); +#97830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#97831 = VECTOR('',#97832,1.); +#97832 = DIRECTION('',(-1.,0.E+000)); +#97833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97834 = PCURVE('',#97835,#97840); +#97835 = CYLINDRICAL_SURFACE('',#97836,0.208574704164); +#97836 = AXIS2_PLACEMENT_3D('',#97837,#97838,#97839); +#97837 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#97838 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97839 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97840 = DEFINITIONAL_REPRESENTATION('',(#97841),#97844); +#97841 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97842,#97843),.UNSPECIFIED., .F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#95450 = CARTESIAN_POINT('',(3.201833915432,4.65)); -#95451 = CARTESIAN_POINT('',(3.201833915432,4.85)); -#95452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95453 = ADVANCED_FACE('',(#95454),#95339,.T.); -#95454 = FACE_BOUND('',#95455,.T.); -#95455 = EDGE_LOOP('',(#95456,#95457,#95484,#95511)); -#95456 = ORIENTED_EDGE('',*,*,#95325,.F.); -#95457 = ORIENTED_EDGE('',*,*,#95458,.F.); -#95458 = EDGE_CURVE('',#95459,#95303,#95461,.T.); -#95459 = VERTEX_POINT('',#95460); -#95460 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.E+000)); -#95461 = SURFACE_CURVE('',#95462,(#95467,#95473),.PCURVE_S1.); -#95462 = CIRCLE('',#95463,0.308574064194); -#95463 = AXIS2_PLACEMENT_3D('',#95464,#95465,#95466); -#95464 = CARTESIAN_POINT('',(5.15,-0.728168876214,2.640924866458E-017)); -#95465 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95466 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95467 = PCURVE('',#95339,#95468); -#95468 = DEFINITIONAL_REPRESENTATION('',(#95469),#95472); -#95469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95470,#95471),.UNSPECIFIED., +#97842 = CARTESIAN_POINT('',(3.201833915432,4.65)); +#97843 = CARTESIAN_POINT('',(3.201833915432,4.85)); +#97844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97845 = ADVANCED_FACE('',(#97846),#97731,.T.); +#97846 = FACE_BOUND('',#97847,.T.); +#97847 = EDGE_LOOP('',(#97848,#97849,#97876,#97903)); +#97848 = ORIENTED_EDGE('',*,*,#97717,.F.); +#97849 = ORIENTED_EDGE('',*,*,#97850,.F.); +#97850 = EDGE_CURVE('',#97851,#97695,#97853,.T.); +#97851 = VERTEX_POINT('',#97852); +#97852 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.E+000)); +#97853 = SURFACE_CURVE('',#97854,(#97859,#97865),.PCURVE_S1.); +#97854 = CIRCLE('',#97855,0.308574064194); +#97855 = AXIS2_PLACEMENT_3D('',#97856,#97857,#97858); +#97856 = CARTESIAN_POINT('',(5.15,-0.728168876214,2.640924866458E-017)); +#97857 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97858 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97859 = PCURVE('',#97731,#97860); +#97860 = DEFINITIONAL_REPRESENTATION('',(#97861),#97864); +#97861 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97862,#97863),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#95470 = CARTESIAN_POINT('',(1.570796326795,4.85)); -#95471 = CARTESIAN_POINT('',(3.191025391152,4.85)); -#95472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97862 = CARTESIAN_POINT('',(1.570796326795,4.85)); +#97863 = CARTESIAN_POINT('',(3.191025391152,4.85)); +#97864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95473 = PCURVE('',#89465,#95474); -#95474 = DEFINITIONAL_REPRESENTATION('',(#95475),#95483); -#95475 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#95476,#95477,#95478,#95479 - ,#95480,#95481,#95482),.UNSPECIFIED.,.T.,.F.) +#97865 = PCURVE('',#91857,#97866); +#97866 = DEFINITIONAL_REPRESENTATION('',(#97867),#97875); +#97867 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97868,#97869,#97870,#97871 + ,#97872,#97873,#97874),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#95476 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#95477 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#95478 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#95479 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#95480 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#95481 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#95482 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#95483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95484 = ORIENTED_EDGE('',*,*,#95485,.F.); -#95485 = EDGE_CURVE('',#95486,#95459,#95488,.T.); -#95486 = VERTEX_POINT('',#95487); -#95487 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.E+000)); -#95488 = SURFACE_CURVE('',#95489,(#95493,#95499),.PCURVE_S1.); -#95489 = LINE('',#95490,#95491); -#95490 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#95491 = VECTOR('',#95492,1.); -#95492 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95493 = PCURVE('',#95339,#95494); -#95494 = DEFINITIONAL_REPRESENTATION('',(#95495),#95498); -#95495 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95496,#95497),.UNSPECIFIED., +#97868 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#97869 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#97870 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#97871 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#97872 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#97873 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#97874 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#97875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97876 = ORIENTED_EDGE('',*,*,#97877,.F.); +#97877 = EDGE_CURVE('',#97878,#97851,#97880,.T.); +#97878 = VERTEX_POINT('',#97879); +#97879 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.E+000)); +#97880 = SURFACE_CURVE('',#97881,(#97885,#97891),.PCURVE_S1.); +#97881 = LINE('',#97882,#97883); +#97882 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#97883 = VECTOR('',#97884,1.); +#97884 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97885 = PCURVE('',#97731,#97886); +#97886 = DEFINITIONAL_REPRESENTATION('',(#97887),#97890); +#97887 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97888,#97889),.UNSPECIFIED., .F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#95496 = CARTESIAN_POINT('',(1.570796326795,4.65)); -#95497 = CARTESIAN_POINT('',(1.570796326795,4.85)); -#95498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95499 = PCURVE('',#95500,#95505); -#95500 = PLANE('',#95501); -#95501 = AXIS2_PLACEMENT_3D('',#95502,#95503,#95504); -#95502 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#95503 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#95504 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#95505 = DEFINITIONAL_REPRESENTATION('',(#95506),#95510); -#95506 = LINE('',#95507,#95508); -#95507 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#95508 = VECTOR('',#95509,1.); -#95509 = DIRECTION('',(0.E+000,-1.)); -#95510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95511 = ORIENTED_EDGE('',*,*,#95512,.T.); -#95512 = EDGE_CURVE('',#95486,#95245,#95513,.T.); -#95513 = SURFACE_CURVE('',#95514,(#95519,#95525),.PCURVE_S1.); -#95514 = CIRCLE('',#95515,0.308574064194); -#95515 = AXIS2_PLACEMENT_3D('',#95516,#95517,#95518); -#95516 = CARTESIAN_POINT('',(5.35,-0.728168876214,2.640924866458E-017)); -#95517 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95518 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95519 = PCURVE('',#95339,#95520); -#95520 = DEFINITIONAL_REPRESENTATION('',(#95521),#95524); -#95521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95522,#95523),.UNSPECIFIED., +#97888 = CARTESIAN_POINT('',(1.570796326795,4.65)); +#97889 = CARTESIAN_POINT('',(1.570796326795,4.85)); +#97890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97891 = PCURVE('',#97892,#97897); +#97892 = PLANE('',#97893); +#97893 = AXIS2_PLACEMENT_3D('',#97894,#97895,#97896); +#97894 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#97895 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#97896 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#97897 = DEFINITIONAL_REPRESENTATION('',(#97898),#97902); +#97898 = LINE('',#97899,#97900); +#97899 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#97900 = VECTOR('',#97901,1.); +#97901 = DIRECTION('',(0.E+000,-1.)); +#97902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97903 = ORIENTED_EDGE('',*,*,#97904,.T.); +#97904 = EDGE_CURVE('',#97878,#97637,#97905,.T.); +#97905 = SURFACE_CURVE('',#97906,(#97911,#97917),.PCURVE_S1.); +#97906 = CIRCLE('',#97907,0.308574064194); +#97907 = AXIS2_PLACEMENT_3D('',#97908,#97909,#97910); +#97908 = CARTESIAN_POINT('',(5.35,-0.728168876214,2.640924866458E-017)); +#97909 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97910 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97911 = PCURVE('',#97731,#97912); +#97912 = DEFINITIONAL_REPRESENTATION('',(#97913),#97916); +#97913 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97914,#97915),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#95522 = CARTESIAN_POINT('',(1.570796326795,4.65)); -#95523 = CARTESIAN_POINT('',(3.191025391152,4.65)); -#95524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95525 = PCURVE('',#89519,#95526); -#95526 = DEFINITIONAL_REPRESENTATION('',(#95527),#95531); -#95527 = CIRCLE('',#95528,0.308574064194); -#95528 = AXIS2_PLACEMENT_2D('',#95529,#95530); -#95529 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#95530 = DIRECTION('',(1.,0.E+000)); -#95531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95532 = ADVANCED_FACE('',(#95533),#95443,.F.); -#95533 = FACE_BOUND('',#95534,.F.); -#95534 = EDGE_LOOP('',(#95535,#95536,#95563,#95590)); -#95535 = ORIENTED_EDGE('',*,*,#95429,.T.); -#95536 = ORIENTED_EDGE('',*,*,#95537,.F.); -#95537 = EDGE_CURVE('',#95538,#95354,#95540,.T.); -#95538 = VERTEX_POINT('',#95539); -#95539 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.E+000)); -#95540 = SURFACE_CURVE('',#95541,(#95546,#95552),.PCURVE_S1.); -#95541 = CIRCLE('',#95542,0.208574704164); -#95542 = AXIS2_PLACEMENT_3D('',#95543,#95544,#95545); -#95543 = CARTESIAN_POINT('',(5.15,-0.728168876214,2.640924866458E-017)); -#95544 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95545 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95546 = PCURVE('',#95443,#95547); -#95547 = DEFINITIONAL_REPRESENTATION('',(#95548),#95551); -#95548 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95549,#95550),.UNSPECIFIED., +#97914 = CARTESIAN_POINT('',(1.570796326795,4.65)); +#97915 = CARTESIAN_POINT('',(3.191025391152,4.65)); +#97916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97917 = PCURVE('',#91911,#97918); +#97918 = DEFINITIONAL_REPRESENTATION('',(#97919),#97923); +#97919 = CIRCLE('',#97920,0.308574064194); +#97920 = AXIS2_PLACEMENT_2D('',#97921,#97922); +#97921 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#97922 = DIRECTION('',(1.,0.E+000)); +#97923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97924 = ADVANCED_FACE('',(#97925),#97835,.F.); +#97925 = FACE_BOUND('',#97926,.F.); +#97926 = EDGE_LOOP('',(#97927,#97928,#97955,#97982)); +#97927 = ORIENTED_EDGE('',*,*,#97821,.T.); +#97928 = ORIENTED_EDGE('',*,*,#97929,.F.); +#97929 = EDGE_CURVE('',#97930,#97746,#97932,.T.); +#97930 = VERTEX_POINT('',#97931); +#97931 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.E+000)); +#97932 = SURFACE_CURVE('',#97933,(#97938,#97944),.PCURVE_S1.); +#97933 = CIRCLE('',#97934,0.208574704164); +#97934 = AXIS2_PLACEMENT_3D('',#97935,#97936,#97937); +#97935 = CARTESIAN_POINT('',(5.15,-0.728168876214,2.640924866458E-017)); +#97936 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97937 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97938 = PCURVE('',#97835,#97939); +#97939 = DEFINITIONAL_REPRESENTATION('',(#97940),#97943); +#97940 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97941,#97942),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#95549 = CARTESIAN_POINT('',(1.570796326795,4.85)); -#95550 = CARTESIAN_POINT('',(3.201833915432,4.85)); -#95551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#97941 = CARTESIAN_POINT('',(1.570796326795,4.85)); +#97942 = CARTESIAN_POINT('',(3.201833915432,4.85)); +#97943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95552 = PCURVE('',#89465,#95553); -#95553 = DEFINITIONAL_REPRESENTATION('',(#95554),#95562); -#95554 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#95555,#95556,#95557,#95558 - ,#95559,#95560,#95561),.UNSPECIFIED.,.F.,.F.) +#97944 = PCURVE('',#91857,#97945); +#97945 = DEFINITIONAL_REPRESENTATION('',(#97946),#97954); +#97946 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97947,#97948,#97949,#97950 + ,#97951,#97952,#97953),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#95555 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#95556 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#95557 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#95558 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#95559 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#95560 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#95561 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#95562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95563 = ORIENTED_EDGE('',*,*,#95564,.T.); -#95564 = EDGE_CURVE('',#95538,#95565,#95567,.T.); -#95565 = VERTEX_POINT('',#95566); -#95566 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.E+000)); -#95567 = SURFACE_CURVE('',#95568,(#95572,#95578),.PCURVE_S1.); -#95568 = LINE('',#95569,#95570); -#95569 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#95570 = VECTOR('',#95571,1.); -#95571 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95572 = PCURVE('',#95443,#95573); -#95573 = DEFINITIONAL_REPRESENTATION('',(#95574),#95577); -#95574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95575,#95576),.UNSPECIFIED., +#97947 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#97948 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#97949 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#97950 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#97951 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#97952 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#97953 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#97954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97955 = ORIENTED_EDGE('',*,*,#97956,.T.); +#97956 = EDGE_CURVE('',#97930,#97957,#97959,.T.); +#97957 = VERTEX_POINT('',#97958); +#97958 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.E+000)); +#97959 = SURFACE_CURVE('',#97960,(#97964,#97970),.PCURVE_S1.); +#97960 = LINE('',#97961,#97962); +#97961 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#97962 = VECTOR('',#97963,1.); +#97963 = DIRECTION('',(1.,0.E+000,0.E+000)); +#97964 = PCURVE('',#97835,#97965); +#97965 = DEFINITIONAL_REPRESENTATION('',(#97966),#97969); +#97966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97967,#97968),.UNSPECIFIED., .F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#95575 = CARTESIAN_POINT('',(1.570796326795,4.85)); -#95576 = CARTESIAN_POINT('',(1.570796326795,4.65)); -#95577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95578 = PCURVE('',#95579,#95584); -#95579 = PLANE('',#95580); -#95580 = AXIS2_PLACEMENT_3D('',#95581,#95582,#95583); -#95581 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#95582 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#95583 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#95584 = DEFINITIONAL_REPRESENTATION('',(#95585),#95589); -#95585 = LINE('',#95586,#95587); -#95586 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#95587 = VECTOR('',#95588,1.); -#95588 = DIRECTION('',(0.E+000,1.)); -#95589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95590 = ORIENTED_EDGE('',*,*,#95591,.T.); -#95591 = EDGE_CURVE('',#95565,#95407,#95592,.T.); -#95592 = SURFACE_CURVE('',#95593,(#95598,#95604),.PCURVE_S1.); -#95593 = CIRCLE('',#95594,0.208574704164); -#95594 = AXIS2_PLACEMENT_3D('',#95595,#95596,#95597); -#95595 = CARTESIAN_POINT('',(5.35,-0.728168876214,2.640924866458E-017)); -#95596 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95597 = DIRECTION('',(0.E+000,0.E+000,1.)); -#95598 = PCURVE('',#95443,#95599); -#95599 = DEFINITIONAL_REPRESENTATION('',(#95600),#95603); -#95600 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95601,#95602),.UNSPECIFIED., +#97967 = CARTESIAN_POINT('',(1.570796326795,4.85)); +#97968 = CARTESIAN_POINT('',(1.570796326795,4.65)); +#97969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97970 = PCURVE('',#97971,#97976); +#97971 = PLANE('',#97972); +#97972 = AXIS2_PLACEMENT_3D('',#97973,#97974,#97975); +#97973 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#97974 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#97975 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#97976 = DEFINITIONAL_REPRESENTATION('',(#97977),#97981); +#97977 = LINE('',#97978,#97979); +#97978 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#97979 = VECTOR('',#97980,1.); +#97980 = DIRECTION('',(0.E+000,1.)); +#97981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97982 = ORIENTED_EDGE('',*,*,#97983,.T.); +#97983 = EDGE_CURVE('',#97957,#97799,#97984,.T.); +#97984 = SURFACE_CURVE('',#97985,(#97990,#97996),.PCURVE_S1.); +#97985 = CIRCLE('',#97986,0.208574704164); +#97986 = AXIS2_PLACEMENT_3D('',#97987,#97988,#97989); +#97987 = CARTESIAN_POINT('',(5.35,-0.728168876214,2.640924866458E-017)); +#97988 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#97989 = DIRECTION('',(0.E+000,0.E+000,1.)); +#97990 = PCURVE('',#97835,#97991); +#97991 = DEFINITIONAL_REPRESENTATION('',(#97992),#97995); +#97992 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97993,#97994),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#95601 = CARTESIAN_POINT('',(1.570796326795,4.65)); -#95602 = CARTESIAN_POINT('',(3.201833915432,4.65)); -#95603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95604 = PCURVE('',#89519,#95605); -#95605 = DEFINITIONAL_REPRESENTATION('',(#95606),#95610); -#95606 = CIRCLE('',#95607,0.208574704164); -#95607 = AXIS2_PLACEMENT_2D('',#95608,#95609); -#95608 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#95609 = DIRECTION('',(1.,0.E+000)); -#95610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95611 = ADVANCED_FACE('',(#95612),#95579,.F.); -#95612 = FACE_BOUND('',#95613,.T.); -#95613 = EDGE_LOOP('',(#95614,#95643,#95664,#95665)); -#95614 = ORIENTED_EDGE('',*,*,#95615,.F.); -#95615 = EDGE_CURVE('',#95616,#95618,#95620,.T.); -#95616 = VERTEX_POINT('',#95617); -#95617 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.530776333563)); -#95618 = VERTEX_POINT('',#95619); -#95619 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.530776333563)); -#95620 = SURFACE_CURVE('',#95621,(#95625,#95632),.PCURVE_S1.); -#95621 = LINE('',#95622,#95623); -#95622 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#95623 = VECTOR('',#95624,1.); -#95624 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95625 = PCURVE('',#95579,#95626); -#95626 = DEFINITIONAL_REPRESENTATION('',(#95627),#95631); -#95627 = LINE('',#95628,#95629); -#95628 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95629 = VECTOR('',#95630,1.); -#95630 = DIRECTION('',(0.E+000,1.)); -#95631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95632 = PCURVE('',#95633,#95638); -#95633 = CYLINDRICAL_SURFACE('',#95634,0.2192697516); -#95634 = AXIS2_PLACEMENT_3D('',#95635,#95636,#95637); -#95635 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#95636 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95637 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95638 = DEFINITIONAL_REPRESENTATION('',(#95639),#95642); -#95639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95640,#95641),.UNSPECIFIED., +#97993 = CARTESIAN_POINT('',(1.570796326795,4.65)); +#97994 = CARTESIAN_POINT('',(3.201833915432,4.65)); +#97995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#97996 = PCURVE('',#91911,#97997); +#97997 = DEFINITIONAL_REPRESENTATION('',(#97998),#98002); +#97998 = CIRCLE('',#97999,0.208574704164); +#97999 = AXIS2_PLACEMENT_2D('',#98000,#98001); +#98000 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#98001 = DIRECTION('',(1.,0.E+000)); +#98002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98003 = ADVANCED_FACE('',(#98004),#97971,.F.); +#98004 = FACE_BOUND('',#98005,.T.); +#98005 = EDGE_LOOP('',(#98006,#98035,#98056,#98057)); +#98006 = ORIENTED_EDGE('',*,*,#98007,.F.); +#98007 = EDGE_CURVE('',#98008,#98010,#98012,.T.); +#98008 = VERTEX_POINT('',#98009); +#98009 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.530776333563)); +#98010 = VERTEX_POINT('',#98011); +#98011 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.530776333563)); +#98012 = SURFACE_CURVE('',#98013,(#98017,#98024),.PCURVE_S1.); +#98013 = LINE('',#98014,#98015); +#98014 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#98015 = VECTOR('',#98016,1.); +#98016 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98017 = PCURVE('',#97971,#98018); +#98018 = DEFINITIONAL_REPRESENTATION('',(#98019),#98023); +#98019 = LINE('',#98020,#98021); +#98020 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98021 = VECTOR('',#98022,1.); +#98022 = DIRECTION('',(0.E+000,1.)); +#98023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98024 = PCURVE('',#98025,#98030); +#98025 = CYLINDRICAL_SURFACE('',#98026,0.2192697516); +#98026 = AXIS2_PLACEMENT_3D('',#98027,#98028,#98029); +#98027 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#98028 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98029 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98030 = DEFINITIONAL_REPRESENTATION('',(#98031),#98034); +#98031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98032,#98033),.UNSPECIFIED., .F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#95640 = CARTESIAN_POINT('',(4.712388980385,-4.85)); -#95641 = CARTESIAN_POINT('',(4.712388980385,-4.65)); -#95642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98032 = CARTESIAN_POINT('',(4.712388980385,-4.85)); +#98033 = CARTESIAN_POINT('',(4.712388980385,-4.65)); +#98034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98035 = ORIENTED_EDGE('',*,*,#98036,.T.); +#98036 = EDGE_CURVE('',#98008,#97930,#98037,.T.); +#98037 = SURFACE_CURVE('',#98038,(#98042,#98049),.PCURVE_S1.); +#98038 = LINE('',#98039,#98040); +#98039 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.530776333563)); +#98040 = VECTOR('',#98041,1.); +#98041 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98042 = PCURVE('',#97971,#98043); +#98043 = DEFINITIONAL_REPRESENTATION('',(#98044),#98048); +#98044 = LINE('',#98045,#98046); +#98045 = CARTESIAN_POINT('',(0.E+000,-4.85)); +#98046 = VECTOR('',#98047,1.); +#98047 = DIRECTION('',(-1.,0.E+000)); +#98048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98049 = PCURVE('',#91857,#98050); +#98050 = DEFINITIONAL_REPRESENTATION('',(#98051),#98055); +#98051 = LINE('',#98052,#98053); +#98052 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#98053 = VECTOR('',#98054,1.); +#98054 = DIRECTION('',(1.,-1.021336205033E-016)); +#98055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98056 = ORIENTED_EDGE('',*,*,#97956,.T.); +#98057 = ORIENTED_EDGE('',*,*,#98058,.F.); +#98058 = EDGE_CURVE('',#98010,#97957,#98059,.T.); +#98059 = SURFACE_CURVE('',#98060,(#98064,#98071),.PCURVE_S1.); +#98060 = LINE('',#98061,#98062); +#98061 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.530776333563)); +#98062 = VECTOR('',#98063,1.); +#98063 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98064 = PCURVE('',#97971,#98065); +#98065 = DEFINITIONAL_REPRESENTATION('',(#98066),#98070); +#98066 = LINE('',#98067,#98068); +#98067 = CARTESIAN_POINT('',(0.E+000,-4.65)); +#98068 = VECTOR('',#98069,1.); +#98069 = DIRECTION('',(-1.,0.E+000)); +#98070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98071 = PCURVE('',#91911,#98072); +#98072 = DEFINITIONAL_REPRESENTATION('',(#98073),#98077); +#98073 = LINE('',#98074,#98075); +#98074 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#98075 = VECTOR('',#98076,1.); +#98076 = DIRECTION('',(-1.,-1.021336205033E-016)); +#98077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98078 = ADVANCED_FACE('',(#98079),#97892,.F.); +#98079 = FACE_BOUND('',#98080,.T.); +#98080 = EDGE_LOOP('',(#98081,#98110,#98131,#98132)); +#98081 = ORIENTED_EDGE('',*,*,#98082,.F.); +#98082 = EDGE_CURVE('',#98083,#98085,#98087,.T.); +#98083 = VERTEX_POINT('',#98084); +#98084 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.530776333563)); +#98085 = VERTEX_POINT('',#98086); +#98086 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.530776333563)); +#98087 = SURFACE_CURVE('',#98088,(#98092,#98099),.PCURVE_S1.); +#98088 = LINE('',#98089,#98090); +#98089 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#98090 = VECTOR('',#98091,1.); +#98091 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98092 = PCURVE('',#97892,#98093); +#98093 = DEFINITIONAL_REPRESENTATION('',(#98094),#98098); +#98094 = LINE('',#98095,#98096); +#98095 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98096 = VECTOR('',#98097,1.); +#98097 = DIRECTION('',(0.E+000,-1.)); +#98098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98099 = PCURVE('',#98100,#98105); +#98100 = CYLINDRICAL_SURFACE('',#98101,0.119270391569); +#98101 = AXIS2_PLACEMENT_3D('',#98102,#98103,#98104); +#98102 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#98103 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98104 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98105 = DEFINITIONAL_REPRESENTATION('',(#98106),#98109); +#98106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98107,#98108),.UNSPECIFIED., + .F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); +#98107 = CARTESIAN_POINT('',(4.712388980385,-4.65)); +#98108 = CARTESIAN_POINT('',(4.712388980385,-4.85)); +#98109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95643 = ORIENTED_EDGE('',*,*,#95644,.T.); -#95644 = EDGE_CURVE('',#95616,#95538,#95645,.T.); -#95645 = SURFACE_CURVE('',#95646,(#95650,#95657),.PCURVE_S1.); -#95646 = LINE('',#95647,#95648); -#95647 = CARTESIAN_POINT('',(5.15,-0.51959417205,0.530776333563)); -#95648 = VECTOR('',#95649,1.); -#95649 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#95650 = PCURVE('',#95579,#95651); -#95651 = DEFINITIONAL_REPRESENTATION('',(#95652),#95656); -#95652 = LINE('',#95653,#95654); -#95653 = CARTESIAN_POINT('',(0.E+000,-4.85)); -#95654 = VECTOR('',#95655,1.); -#95655 = DIRECTION('',(-1.,0.E+000)); -#95656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95657 = PCURVE('',#89465,#95658); -#95658 = DEFINITIONAL_REPRESENTATION('',(#95659),#95663); -#95659 = LINE('',#95660,#95661); -#95660 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#95661 = VECTOR('',#95662,1.); -#95662 = DIRECTION('',(1.,-1.021336205033E-016)); -#95663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95664 = ORIENTED_EDGE('',*,*,#95564,.T.); -#95665 = ORIENTED_EDGE('',*,*,#95666,.F.); -#95666 = EDGE_CURVE('',#95618,#95565,#95667,.T.); -#95667 = SURFACE_CURVE('',#95668,(#95672,#95679),.PCURVE_S1.); -#95668 = LINE('',#95669,#95670); -#95669 = CARTESIAN_POINT('',(5.35,-0.51959417205,0.530776333563)); -#95670 = VECTOR('',#95671,1.); -#95671 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#95672 = PCURVE('',#95579,#95673); -#95673 = DEFINITIONAL_REPRESENTATION('',(#95674),#95678); -#95674 = LINE('',#95675,#95676); -#95675 = CARTESIAN_POINT('',(0.E+000,-4.65)); -#95676 = VECTOR('',#95677,1.); -#95677 = DIRECTION('',(-1.,0.E+000)); -#95678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95679 = PCURVE('',#89519,#95680); -#95680 = DEFINITIONAL_REPRESENTATION('',(#95681),#95685); -#95681 = LINE('',#95682,#95683); -#95682 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#95683 = VECTOR('',#95684,1.); -#95684 = DIRECTION('',(-1.,-1.021336205033E-016)); -#95685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95686 = ADVANCED_FACE('',(#95687),#95500,.F.); -#95687 = FACE_BOUND('',#95688,.T.); -#95688 = EDGE_LOOP('',(#95689,#95718,#95739,#95740)); -#95689 = ORIENTED_EDGE('',*,*,#95690,.F.); -#95690 = EDGE_CURVE('',#95691,#95693,#95695,.T.); -#95691 = VERTEX_POINT('',#95692); -#95692 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.530776333563)); -#95693 = VERTEX_POINT('',#95694); -#95694 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.530776333563)); -#95695 = SURFACE_CURVE('',#95696,(#95700,#95707),.PCURVE_S1.); -#95696 = LINE('',#95697,#95698); -#95697 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#95698 = VECTOR('',#95699,1.); -#95699 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95700 = PCURVE('',#95500,#95701); -#95701 = DEFINITIONAL_REPRESENTATION('',(#95702),#95706); -#95702 = LINE('',#95703,#95704); -#95703 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95704 = VECTOR('',#95705,1.); -#95705 = DIRECTION('',(0.E+000,-1.)); -#95706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95707 = PCURVE('',#95708,#95713); -#95708 = CYLINDRICAL_SURFACE('',#95709,0.119270391569); -#95709 = AXIS2_PLACEMENT_3D('',#95710,#95711,#95712); -#95710 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#95711 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95712 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95713 = DEFINITIONAL_REPRESENTATION('',(#95714),#95717); -#95714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95715,#95716),.UNSPECIFIED., - .F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#95715 = CARTESIAN_POINT('',(4.712388980385,-4.65)); -#95716 = CARTESIAN_POINT('',(4.712388980385,-4.85)); -#95717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95718 = ORIENTED_EDGE('',*,*,#95719,.T.); -#95719 = EDGE_CURVE('',#95691,#95486,#95720,.T.); -#95720 = SURFACE_CURVE('',#95721,(#95725,#95732),.PCURVE_S1.); -#95721 = LINE('',#95722,#95723); -#95722 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.530776333563)); -#95723 = VECTOR('',#95724,1.); -#95724 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#95725 = PCURVE('',#95500,#95726); -#95726 = DEFINITIONAL_REPRESENTATION('',(#95727),#95731); -#95727 = LINE('',#95728,#95729); -#95728 = CARTESIAN_POINT('',(0.E+000,-4.65)); -#95729 = VECTOR('',#95730,1.); -#95730 = DIRECTION('',(1.,0.E+000)); -#95731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95732 = PCURVE('',#89519,#95733); -#95733 = DEFINITIONAL_REPRESENTATION('',(#95734),#95738); -#95734 = LINE('',#95735,#95736); -#95735 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#95736 = VECTOR('',#95737,1.); -#95737 = DIRECTION('',(-1.,-1.021336205033E-016)); -#95738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95739 = ORIENTED_EDGE('',*,*,#95485,.T.); -#95740 = ORIENTED_EDGE('',*,*,#95741,.F.); -#95741 = EDGE_CURVE('',#95693,#95459,#95742,.T.); -#95742 = SURFACE_CURVE('',#95743,(#95747,#95754),.PCURVE_S1.); -#95743 = LINE('',#95744,#95745); -#95744 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.530776333563)); -#95745 = VECTOR('',#95746,1.); -#95746 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#95747 = PCURVE('',#95500,#95748); -#95748 = DEFINITIONAL_REPRESENTATION('',(#95749),#95753); -#95749 = LINE('',#95750,#95751); -#95750 = CARTESIAN_POINT('',(0.E+000,-4.85)); -#95751 = VECTOR('',#95752,1.); -#95752 = DIRECTION('',(1.,0.E+000)); -#95753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95754 = PCURVE('',#89465,#95755); -#95755 = DEFINITIONAL_REPRESENTATION('',(#95756),#95760); -#95756 = LINE('',#95757,#95758); -#95757 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#95758 = VECTOR('',#95759,1.); -#95759 = DIRECTION('',(1.,-1.021336205033E-016)); -#95760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95761 = ADVANCED_FACE('',(#95762),#95708,.F.); -#95762 = FACE_BOUND('',#95763,.F.); -#95763 = EDGE_LOOP('',(#95764,#95791,#95813,#95834)); -#95764 = ORIENTED_EDGE('',*,*,#95765,.F.); -#95765 = EDGE_CURVE('',#95766,#95691,#95768,.T.); -#95766 = VERTEX_POINT('',#95767); -#95767 = CARTESIAN_POINT('',(5.35,-0.303662633502,0.65)); -#95768 = SURFACE_CURVE('',#95769,(#95774,#95780),.PCURVE_S1.); -#95769 = CIRCLE('',#95770,0.119270391569); -#95770 = AXIS2_PLACEMENT_3D('',#95771,#95772,#95773); -#95771 = CARTESIAN_POINT('',(5.35,-0.30032442045,0.530776333563)); -#95772 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95773 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95774 = PCURVE('',#95708,#95775); -#95775 = DEFINITIONAL_REPRESENTATION('',(#95776),#95779); -#95776 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95777,#95778),.UNSPECIFIED., +#98110 = ORIENTED_EDGE('',*,*,#98111,.T.); +#98111 = EDGE_CURVE('',#98083,#97878,#98112,.T.); +#98112 = SURFACE_CURVE('',#98113,(#98117,#98124),.PCURVE_S1.); +#98113 = LINE('',#98114,#98115); +#98114 = CARTESIAN_POINT('',(5.35,-0.419594812019,0.530776333563)); +#98115 = VECTOR('',#98116,1.); +#98116 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98117 = PCURVE('',#97892,#98118); +#98118 = DEFINITIONAL_REPRESENTATION('',(#98119),#98123); +#98119 = LINE('',#98120,#98121); +#98120 = CARTESIAN_POINT('',(0.E+000,-4.65)); +#98121 = VECTOR('',#98122,1.); +#98122 = DIRECTION('',(1.,0.E+000)); +#98123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98124 = PCURVE('',#91911,#98125); +#98125 = DEFINITIONAL_REPRESENTATION('',(#98126),#98130); +#98126 = LINE('',#98127,#98128); +#98127 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#98128 = VECTOR('',#98129,1.); +#98129 = DIRECTION('',(-1.,-1.021336205033E-016)); +#98130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98131 = ORIENTED_EDGE('',*,*,#97877,.T.); +#98132 = ORIENTED_EDGE('',*,*,#98133,.F.); +#98133 = EDGE_CURVE('',#98085,#97851,#98134,.T.); +#98134 = SURFACE_CURVE('',#98135,(#98139,#98146),.PCURVE_S1.); +#98135 = LINE('',#98136,#98137); +#98136 = CARTESIAN_POINT('',(5.15,-0.419594812019,0.530776333563)); +#98137 = VECTOR('',#98138,1.); +#98138 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98139 = PCURVE('',#97892,#98140); +#98140 = DEFINITIONAL_REPRESENTATION('',(#98141),#98145); +#98141 = LINE('',#98142,#98143); +#98142 = CARTESIAN_POINT('',(0.E+000,-4.85)); +#98143 = VECTOR('',#98144,1.); +#98144 = DIRECTION('',(1.,0.E+000)); +#98145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98146 = PCURVE('',#91857,#98147); +#98147 = DEFINITIONAL_REPRESENTATION('',(#98148),#98152); +#98148 = LINE('',#98149,#98150); +#98149 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#98150 = VECTOR('',#98151,1.); +#98151 = DIRECTION('',(1.,-1.021336205033E-016)); +#98152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98153 = ADVANCED_FACE('',(#98154),#98100,.F.); +#98154 = FACE_BOUND('',#98155,.F.); +#98155 = EDGE_LOOP('',(#98156,#98183,#98205,#98226)); +#98156 = ORIENTED_EDGE('',*,*,#98157,.F.); +#98157 = EDGE_CURVE('',#98158,#98083,#98160,.T.); +#98158 = VERTEX_POINT('',#98159); +#98159 = CARTESIAN_POINT('',(5.35,-0.303662633502,0.65)); +#98160 = SURFACE_CURVE('',#98161,(#98166,#98172),.PCURVE_S1.); +#98161 = CIRCLE('',#98162,0.119270391569); +#98162 = AXIS2_PLACEMENT_3D('',#98163,#98164,#98165); +#98163 = CARTESIAN_POINT('',(5.35,-0.30032442045,0.530776333563)); +#98164 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98165 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98166 = PCURVE('',#98100,#98167); +#98167 = DEFINITIONAL_REPRESENTATION('',(#98168),#98171); +#98168 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98169,#98170),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95777 = CARTESIAN_POINT('',(3.169584923929,-4.65)); -#95778 = CARTESIAN_POINT('',(4.712388980385,-4.65)); -#95779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98169 = CARTESIAN_POINT('',(3.169584923929,-4.65)); +#98170 = CARTESIAN_POINT('',(4.712388980385,-4.65)); +#98171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95780 = PCURVE('',#89519,#95781); -#95781 = DEFINITIONAL_REPRESENTATION('',(#95782),#95790); -#95782 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#95783,#95784,#95785,#95786 - ,#95787,#95788,#95789),.UNSPECIFIED.,.T.,.F.) +#98172 = PCURVE('',#91911,#98173); +#98173 = DEFINITIONAL_REPRESENTATION('',(#98174),#98182); +#98174 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98175,#98176,#98177,#98178 + ,#98179,#98180,#98181),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#95783 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#95784 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#95785 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#95786 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#95787 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#95788 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#95789 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#95790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95791 = ORIENTED_EDGE('',*,*,#95792,.F.); -#95792 = EDGE_CURVE('',#95793,#95766,#95795,.T.); -#95793 = VERTEX_POINT('',#95794); -#95794 = CARTESIAN_POINT('',(5.15,-0.303662633502,0.65)); -#95795 = SURFACE_CURVE('',#95796,(#95800,#95806),.PCURVE_S1.); -#95796 = LINE('',#95797,#95798); -#95797 = CARTESIAN_POINT('',(5.15,-0.303662633502,0.65)); -#95798 = VECTOR('',#95799,1.); -#95799 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95800 = PCURVE('',#95708,#95801); -#95801 = DEFINITIONAL_REPRESENTATION('',(#95802),#95805); -#95802 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95803,#95804),.UNSPECIFIED., +#98175 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#98176 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#98177 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#98178 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#98179 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#98180 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#98181 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#98182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98183 = ORIENTED_EDGE('',*,*,#98184,.F.); +#98184 = EDGE_CURVE('',#98185,#98158,#98187,.T.); +#98185 = VERTEX_POINT('',#98186); +#98186 = CARTESIAN_POINT('',(5.15,-0.303662633502,0.65)); +#98187 = SURFACE_CURVE('',#98188,(#98192,#98198),.PCURVE_S1.); +#98188 = LINE('',#98189,#98190); +#98189 = CARTESIAN_POINT('',(5.15,-0.303662633502,0.65)); +#98190 = VECTOR('',#98191,1.); +#98191 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98192 = PCURVE('',#98100,#98193); +#98193 = DEFINITIONAL_REPRESENTATION('',(#98194),#98197); +#98194 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98195,#98196),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#95803 = CARTESIAN_POINT('',(3.169584923929,-4.85)); -#95804 = CARTESIAN_POINT('',(3.169584923929,-4.65)); -#95805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95806 = PCURVE('',#89437,#95807); -#95807 = DEFINITIONAL_REPRESENTATION('',(#95808),#95812); -#95808 = LINE('',#95809,#95810); -#95809 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#95810 = VECTOR('',#95811,1.); -#95811 = DIRECTION('',(0.E+000,1.)); -#95812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95813 = ORIENTED_EDGE('',*,*,#95814,.T.); -#95814 = EDGE_CURVE('',#95793,#95693,#95815,.T.); -#95815 = SURFACE_CURVE('',#95816,(#95821,#95827),.PCURVE_S1.); -#95816 = CIRCLE('',#95817,0.119270391569); -#95817 = AXIS2_PLACEMENT_3D('',#95818,#95819,#95820); -#95818 = CARTESIAN_POINT('',(5.15,-0.30032442045,0.530776333563)); -#95819 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95820 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95821 = PCURVE('',#95708,#95822); -#95822 = DEFINITIONAL_REPRESENTATION('',(#95823),#95826); -#95823 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95824,#95825),.UNSPECIFIED., +#98195 = CARTESIAN_POINT('',(3.169584923929,-4.85)); +#98196 = CARTESIAN_POINT('',(3.169584923929,-4.65)); +#98197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98198 = PCURVE('',#91829,#98199); +#98199 = DEFINITIONAL_REPRESENTATION('',(#98200),#98204); +#98200 = LINE('',#98201,#98202); +#98201 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#98202 = VECTOR('',#98203,1.); +#98203 = DIRECTION('',(0.E+000,1.)); +#98204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98205 = ORIENTED_EDGE('',*,*,#98206,.T.); +#98206 = EDGE_CURVE('',#98185,#98085,#98207,.T.); +#98207 = SURFACE_CURVE('',#98208,(#98213,#98219),.PCURVE_S1.); +#98208 = CIRCLE('',#98209,0.119270391569); +#98209 = AXIS2_PLACEMENT_3D('',#98210,#98211,#98212); +#98210 = CARTESIAN_POINT('',(5.15,-0.30032442045,0.530776333563)); +#98211 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98212 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98213 = PCURVE('',#98100,#98214); +#98214 = DEFINITIONAL_REPRESENTATION('',(#98215),#98218); +#98215 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98216,#98217),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95824 = CARTESIAN_POINT('',(3.169584923929,-4.85)); -#95825 = CARTESIAN_POINT('',(4.712388980385,-4.85)); -#95826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95827 = PCURVE('',#89465,#95828); -#95828 = DEFINITIONAL_REPRESENTATION('',(#95829),#95833); -#95829 = CIRCLE('',#95830,0.119270391569); -#95830 = AXIS2_PLACEMENT_2D('',#95831,#95832); -#95831 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#95832 = DIRECTION('',(1.,0.E+000)); -#95833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95834 = ORIENTED_EDGE('',*,*,#95690,.F.); -#95835 = ADVANCED_FACE('',(#95836),#95633,.T.); -#95836 = FACE_BOUND('',#95837,.T.); -#95837 = EDGE_LOOP('',(#95838,#95861,#95862,#95889)); -#95838 = ORIENTED_EDGE('',*,*,#95839,.T.); -#95839 = EDGE_CURVE('',#95840,#95616,#95842,.T.); -#95840 = VERTEX_POINT('',#95841); -#95841 = CARTESIAN_POINT('',(5.15,-0.304819755875,0.75)); -#95842 = SURFACE_CURVE('',#95843,(#95848,#95854),.PCURVE_S1.); -#95843 = CIRCLE('',#95844,0.2192697516); -#95844 = AXIS2_PLACEMENT_3D('',#95845,#95846,#95847); -#95845 = CARTESIAN_POINT('',(5.15,-0.30032442045,0.530776333563)); -#95846 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95847 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95848 = PCURVE('',#95633,#95849); -#95849 = DEFINITIONAL_REPRESENTATION('',(#95850),#95853); -#95850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95851,#95852),.UNSPECIFIED., +#98216 = CARTESIAN_POINT('',(3.169584923929,-4.85)); +#98217 = CARTESIAN_POINT('',(4.712388980385,-4.85)); +#98218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98219 = PCURVE('',#91857,#98220); +#98220 = DEFINITIONAL_REPRESENTATION('',(#98221),#98225); +#98221 = CIRCLE('',#98222,0.119270391569); +#98222 = AXIS2_PLACEMENT_2D('',#98223,#98224); +#98223 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#98224 = DIRECTION('',(1.,0.E+000)); +#98225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98226 = ORIENTED_EDGE('',*,*,#98082,.F.); +#98227 = ADVANCED_FACE('',(#98228),#98025,.T.); +#98228 = FACE_BOUND('',#98229,.T.); +#98229 = EDGE_LOOP('',(#98230,#98253,#98254,#98281)); +#98230 = ORIENTED_EDGE('',*,*,#98231,.T.); +#98231 = EDGE_CURVE('',#98232,#98008,#98234,.T.); +#98232 = VERTEX_POINT('',#98233); +#98233 = CARTESIAN_POINT('',(5.15,-0.304819755875,0.75)); +#98234 = SURFACE_CURVE('',#98235,(#98240,#98246),.PCURVE_S1.); +#98235 = CIRCLE('',#98236,0.2192697516); +#98236 = AXIS2_PLACEMENT_3D('',#98237,#98238,#98239); +#98237 = CARTESIAN_POINT('',(5.15,-0.30032442045,0.530776333563)); +#98238 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98239 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98240 = PCURVE('',#98025,#98241); +#98241 = DEFINITIONAL_REPRESENTATION('',(#98242),#98245); +#98242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98243,#98244),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95851 = CARTESIAN_POINT('',(3.162095483347,-4.85)); -#95852 = CARTESIAN_POINT('',(4.712388980385,-4.85)); -#95853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95854 = PCURVE('',#89465,#95855); -#95855 = DEFINITIONAL_REPRESENTATION('',(#95856),#95860); -#95856 = CIRCLE('',#95857,0.2192697516); -#95857 = AXIS2_PLACEMENT_2D('',#95858,#95859); -#95858 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#95859 = DIRECTION('',(1.,0.E+000)); -#95860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95861 = ORIENTED_EDGE('',*,*,#95615,.T.); -#95862 = ORIENTED_EDGE('',*,*,#95863,.F.); -#95863 = EDGE_CURVE('',#95864,#95618,#95866,.T.); -#95864 = VERTEX_POINT('',#95865); -#95865 = CARTESIAN_POINT('',(5.35,-0.304819755875,0.75)); -#95866 = SURFACE_CURVE('',#95867,(#95872,#95878),.PCURVE_S1.); -#95867 = CIRCLE('',#95868,0.2192697516); -#95868 = AXIS2_PLACEMENT_3D('',#95869,#95870,#95871); -#95869 = CARTESIAN_POINT('',(5.35,-0.30032442045,0.530776333563)); -#95870 = DIRECTION('',(1.,0.E+000,0.E+000)); -#95871 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#95872 = PCURVE('',#95633,#95873); -#95873 = DEFINITIONAL_REPRESENTATION('',(#95874),#95877); -#95874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95875,#95876),.UNSPECIFIED., +#98243 = CARTESIAN_POINT('',(3.162095483347,-4.85)); +#98244 = CARTESIAN_POINT('',(4.712388980385,-4.85)); +#98245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98246 = PCURVE('',#91857,#98247); +#98247 = DEFINITIONAL_REPRESENTATION('',(#98248),#98252); +#98248 = CIRCLE('',#98249,0.2192697516); +#98249 = AXIS2_PLACEMENT_2D('',#98250,#98251); +#98250 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#98251 = DIRECTION('',(1.,0.E+000)); +#98252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98253 = ORIENTED_EDGE('',*,*,#98007,.T.); +#98254 = ORIENTED_EDGE('',*,*,#98255,.F.); +#98255 = EDGE_CURVE('',#98256,#98010,#98258,.T.); +#98256 = VERTEX_POINT('',#98257); +#98257 = CARTESIAN_POINT('',(5.35,-0.304819755875,0.75)); +#98258 = SURFACE_CURVE('',#98259,(#98264,#98270),.PCURVE_S1.); +#98259 = CIRCLE('',#98260,0.2192697516); +#98260 = AXIS2_PLACEMENT_3D('',#98261,#98262,#98263); +#98261 = CARTESIAN_POINT('',(5.35,-0.30032442045,0.530776333563)); +#98262 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98263 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98264 = PCURVE('',#98025,#98265); +#98265 = DEFINITIONAL_REPRESENTATION('',(#98266),#98269); +#98266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98267,#98268),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#95875 = CARTESIAN_POINT('',(3.162095483347,-4.65)); -#95876 = CARTESIAN_POINT('',(4.712388980385,-4.65)); -#95877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98267 = CARTESIAN_POINT('',(3.162095483347,-4.65)); +#98268 = CARTESIAN_POINT('',(4.712388980385,-4.65)); +#98269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95878 = PCURVE('',#89519,#95879); -#95879 = DEFINITIONAL_REPRESENTATION('',(#95880),#95888); -#95880 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#95881,#95882,#95883,#95884 - ,#95885,#95886,#95887),.UNSPECIFIED.,.T.,.F.) +#98270 = PCURVE('',#91911,#98271); +#98271 = DEFINITIONAL_REPRESENTATION('',(#98272),#98280); +#98272 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98273,#98274,#98275,#98276 + ,#98277,#98278,#98279),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#95881 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#95882 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#95883 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#95884 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#95885 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#95886 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#95887 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#95888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95889 = ORIENTED_EDGE('',*,*,#95890,.T.); -#95890 = EDGE_CURVE('',#95864,#95840,#95891,.T.); -#95891 = SURFACE_CURVE('',#95892,(#95896,#95902),.PCURVE_S1.); -#95892 = LINE('',#95893,#95894); -#95893 = CARTESIAN_POINT('',(5.15,-0.304819755875,0.75)); -#95894 = VECTOR('',#95895,1.); -#95895 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#95896 = PCURVE('',#95633,#95897); -#95897 = DEFINITIONAL_REPRESENTATION('',(#95898),#95901); -#95898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#95899,#95900),.UNSPECIFIED., - .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#95899 = CARTESIAN_POINT('',(3.162095483347,-4.65)); -#95900 = CARTESIAN_POINT('',(3.162095483347,-4.85)); -#95901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95902 = PCURVE('',#89493,#95903); -#95903 = DEFINITIONAL_REPRESENTATION('',(#95904),#95908); -#95904 = LINE('',#95905,#95906); -#95905 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#95906 = VECTOR('',#95907,1.); -#95907 = DIRECTION('',(0.E+000,-1.)); -#95908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98273 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#98274 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#98275 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#98276 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#98277 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#98278 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#98279 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#98280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#95909 = ADVANCED_FACE('',(#95910),#89437,.F.); -#95910 = FACE_BOUND('',#95911,.T.); -#95911 = EDGE_LOOP('',(#95912,#95913,#95934,#95935)); -#95912 = ORIENTED_EDGE('',*,*,#95792,.F.); -#95913 = ORIENTED_EDGE('',*,*,#95914,.T.); -#95914 = EDGE_CURVE('',#95793,#89420,#95915,.T.); -#95915 = SURFACE_CURVE('',#95916,(#95920,#95927),.PCURVE_S1.); -#95916 = LINE('',#95917,#95918); -#95917 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); -#95918 = VECTOR('',#95919,1.); -#95919 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95920 = PCURVE('',#89437,#95921); -#95921 = DEFINITIONAL_REPRESENTATION('',(#95922),#95926); -#95922 = LINE('',#95923,#95924); -#95923 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95924 = VECTOR('',#95925,1.); -#95925 = DIRECTION('',(-1.,0.E+000)); -#95926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95927 = PCURVE('',#89465,#95928); -#95928 = DEFINITIONAL_REPRESENTATION('',(#95929),#95933); -#95929 = LINE('',#95930,#95931); -#95930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95931 = VECTOR('',#95932,1.); -#95932 = DIRECTION('',(-3.563627120235E-016,1.)); -#95933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95934 = ORIENTED_EDGE('',*,*,#89419,.T.); -#95935 = ORIENTED_EDGE('',*,*,#95936,.F.); -#95936 = EDGE_CURVE('',#95766,#89422,#95937,.T.); -#95937 = SURFACE_CURVE('',#95938,(#95942,#95949),.PCURVE_S1.); -#95938 = LINE('',#95939,#95940); -#95939 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.65)); -#95940 = VECTOR('',#95941,1.); -#95941 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95942 = PCURVE('',#89437,#95943); -#95943 = DEFINITIONAL_REPRESENTATION('',(#95944),#95948); -#95944 = LINE('',#95945,#95946); -#95945 = CARTESIAN_POINT('',(0.E+000,0.2)); -#95946 = VECTOR('',#95947,1.); -#95947 = DIRECTION('',(-1.,0.E+000)); -#95948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95949 = PCURVE('',#89519,#95950); -#95950 = DEFINITIONAL_REPRESENTATION('',(#95951),#95955); -#95951 = LINE('',#95952,#95953); -#95952 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#95953 = VECTOR('',#95954,1.); -#95954 = DIRECTION('',(3.563627120235E-016,1.)); -#95955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95956 = ADVANCED_FACE('',(#95957),#89519,.F.); -#95957 = FACE_BOUND('',#95958,.T.); -#95958 = EDGE_LOOP('',(#95959,#95980,#95981,#95982,#95983,#95984,#96005, - #96006,#96007,#96008,#96009,#96010)); -#95959 = ORIENTED_EDGE('',*,*,#95960,.F.); -#95960 = EDGE_CURVE('',#95864,#89478,#95961,.T.); -#95961 = SURFACE_CURVE('',#95962,(#95966,#95973),.PCURVE_S1.); -#95962 = LINE('',#95963,#95964); -#95963 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.75)); -#95964 = VECTOR('',#95965,1.); -#95965 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#95966 = PCURVE('',#89519,#95967); -#95967 = DEFINITIONAL_REPRESENTATION('',(#95968),#95972); -#95968 = LINE('',#95969,#95970); -#95969 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#95970 = VECTOR('',#95971,1.); -#95971 = DIRECTION('',(3.563627120235E-016,1.)); -#95972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95973 = PCURVE('',#89493,#95974); -#95974 = DEFINITIONAL_REPRESENTATION('',(#95975),#95979); -#95975 = LINE('',#95976,#95977); -#95976 = CARTESIAN_POINT('',(0.E+000,0.2)); -#95977 = VECTOR('',#95978,1.); -#95978 = DIRECTION('',(1.,0.E+000)); -#95979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95980 = ORIENTED_EDGE('',*,*,#95863,.T.); -#95981 = ORIENTED_EDGE('',*,*,#95666,.T.); -#95982 = ORIENTED_EDGE('',*,*,#95591,.T.); -#95983 = ORIENTED_EDGE('',*,*,#95406,.T.); -#95984 = ORIENTED_EDGE('',*,*,#95985,.T.); -#95985 = EDGE_CURVE('',#95384,#95247,#95986,.T.); -#95986 = SURFACE_CURVE('',#95987,(#95991,#95998),.PCURVE_S1.); -#95987 = LINE('',#95988,#95989); -#95988 = CARTESIAN_POINT('',(5.35,-1.,1.159810404338E-002)); -#95989 = VECTOR('',#95990,1.); -#95990 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#95991 = PCURVE('',#89519,#95992); -#95992 = DEFINITIONAL_REPRESENTATION('',(#95993),#95997); -#95993 = LINE('',#95994,#95995); -#95994 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#95995 = VECTOR('',#95996,1.); -#95996 = DIRECTION('',(-1.,2.101748079665E-016)); -#95997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#95998 = PCURVE('',#95290,#95999); -#95999 = DEFINITIONAL_REPRESENTATION('',(#96000),#96004); -#96000 = LINE('',#96001,#96002); -#96001 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#96002 = VECTOR('',#96003,1.); -#96003 = DIRECTION('',(1.,0.E+000)); -#96004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96005 = ORIENTED_EDGE('',*,*,#95244,.F.); -#96006 = ORIENTED_EDGE('',*,*,#95512,.F.); -#96007 = ORIENTED_EDGE('',*,*,#95719,.F.); -#96008 = ORIENTED_EDGE('',*,*,#95765,.F.); -#96009 = ORIENTED_EDGE('',*,*,#95936,.T.); -#96010 = ORIENTED_EDGE('',*,*,#89505,.T.); -#96011 = ADVANCED_FACE('',(#96012),#89493,.F.); -#96012 = FACE_BOUND('',#96013,.T.); -#96013 = EDGE_LOOP('',(#96014,#96015,#96016,#96017)); -#96014 = ORIENTED_EDGE('',*,*,#95890,.F.); -#96015 = ORIENTED_EDGE('',*,*,#95960,.T.); -#96016 = ORIENTED_EDGE('',*,*,#89477,.T.); -#96017 = ORIENTED_EDGE('',*,*,#96018,.F.); -#96018 = EDGE_CURVE('',#95840,#89450,#96019,.T.); -#96019 = SURFACE_CURVE('',#96020,(#96024,#96031),.PCURVE_S1.); -#96020 = LINE('',#96021,#96022); -#96021 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.75)); -#96022 = VECTOR('',#96023,1.); -#96023 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#96024 = PCURVE('',#89493,#96025); -#96025 = DEFINITIONAL_REPRESENTATION('',(#96026),#96030); -#96026 = LINE('',#96027,#96028); -#96027 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96028 = VECTOR('',#96029,1.); -#96029 = DIRECTION('',(1.,0.E+000)); -#96030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96031 = PCURVE('',#89465,#96032); -#96032 = DEFINITIONAL_REPRESENTATION('',(#96033),#96037); -#96033 = LINE('',#96034,#96035); -#96034 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#96035 = VECTOR('',#96036,1.); -#96036 = DIRECTION('',(-3.563627120235E-016,1.)); -#96037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96038 = ADVANCED_FACE('',(#96039),#89465,.F.); -#96039 = FACE_BOUND('',#96040,.T.); -#96040 = EDGE_LOOP('',(#96041,#96042,#96043,#96044,#96045,#96046,#96067, - #96068,#96069,#96070,#96071,#96072)); -#96041 = ORIENTED_EDGE('',*,*,#95914,.F.); -#96042 = ORIENTED_EDGE('',*,*,#95814,.T.); -#96043 = ORIENTED_EDGE('',*,*,#95741,.T.); -#96044 = ORIENTED_EDGE('',*,*,#95458,.T.); -#96045 = ORIENTED_EDGE('',*,*,#95302,.T.); -#96046 = ORIENTED_EDGE('',*,*,#96047,.T.); -#96047 = EDGE_CURVE('',#95275,#95356,#96048,.T.); -#96048 = SURFACE_CURVE('',#96049,(#96053,#96060),.PCURVE_S1.); -#96049 = LINE('',#96050,#96051); -#96050 = CARTESIAN_POINT('',(5.15,-1.,1.159810404338E-002)); -#96051 = VECTOR('',#96052,1.); -#96052 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#96053 = PCURVE('',#89465,#96054); -#96054 = DEFINITIONAL_REPRESENTATION('',(#96055),#96059); -#96055 = LINE('',#96056,#96057); -#96056 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#96057 = VECTOR('',#96058,1.); -#96058 = DIRECTION('',(-1.,-2.101748079665E-016)); -#96059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96060 = PCURVE('',#95290,#96061); -#96061 = DEFINITIONAL_REPRESENTATION('',(#96062),#96066); -#96062 = LINE('',#96063,#96064); -#96063 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#96064 = VECTOR('',#96065,1.); -#96065 = DIRECTION('',(-1.,0.E+000)); -#96066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96067 = ORIENTED_EDGE('',*,*,#95353,.F.); -#96068 = ORIENTED_EDGE('',*,*,#95537,.F.); -#96069 = ORIENTED_EDGE('',*,*,#95644,.F.); -#96070 = ORIENTED_EDGE('',*,*,#95839,.F.); -#96071 = ORIENTED_EDGE('',*,*,#96018,.T.); -#96072 = ORIENTED_EDGE('',*,*,#89449,.T.); -#96073 = ADVANCED_FACE('',(#96074),#95290,.T.); -#96074 = FACE_BOUND('',#96075,.T.); -#96075 = EDGE_LOOP('',(#96076,#96077,#96078,#96079)); -#96076 = ORIENTED_EDGE('',*,*,#95383,.F.); -#96077 = ORIENTED_EDGE('',*,*,#96047,.F.); -#96078 = ORIENTED_EDGE('',*,*,#95274,.F.); -#96079 = ORIENTED_EDGE('',*,*,#95985,.F.); -#96080 = ADVANCED_FACE('',(#96081),#96095,.T.); -#96081 = FACE_BOUND('',#96082,.T.); -#96082 = EDGE_LOOP('',(#96083,#96113,#96141,#96164)); -#96083 = ORIENTED_EDGE('',*,*,#96084,.T.); -#96084 = EDGE_CURVE('',#96085,#96087,#96089,.T.); -#96085 = VERTEX_POINT('',#96086); -#96086 = CARTESIAN_POINT('',(1.65,-0.740726081328,-0.208196358798)); -#96087 = VERTEX_POINT('',#96088); -#96088 = CARTESIAN_POINT('',(1.65,-1.,-0.208196358798)); -#96089 = SURFACE_CURVE('',#96090,(#96094,#96106),.PCURVE_S1.); -#96090 = LINE('',#96091,#96092); -#96091 = CARTESIAN_POINT('',(1.65,-0.740726081328,-0.208196358798)); -#96092 = VECTOR('',#96093,1.); -#96093 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96094 = PCURVE('',#96095,#96100); -#96095 = PLANE('',#96096); -#96096 = AXIS2_PLACEMENT_3D('',#96097,#96098,#96099); -#96097 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#96098 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96099 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96100 = DEFINITIONAL_REPRESENTATION('',(#96101),#96105); -#96101 = LINE('',#96102,#96103); -#96102 = CARTESIAN_POINT('',(-8.35,0.E+000)); -#96103 = VECTOR('',#96104,1.); -#96104 = DIRECTION('',(0.E+000,-1.)); -#96105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96106 = PCURVE('',#89156,#96107); -#96107 = DEFINITIONAL_REPRESENTATION('',(#96108),#96112); -#96108 = LINE('',#96109,#96110); -#96109 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#96110 = VECTOR('',#96111,1.); -#96111 = DIRECTION('',(0.E+000,-1.)); -#96112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96113 = ORIENTED_EDGE('',*,*,#96114,.T.); -#96114 = EDGE_CURVE('',#96087,#96115,#96117,.T.); -#96115 = VERTEX_POINT('',#96116); -#96116 = CARTESIAN_POINT('',(1.85,-1.,-0.208196358798)); -#96117 = SURFACE_CURVE('',#96118,(#96122,#96129),.PCURVE_S1.); -#96118 = LINE('',#96119,#96120); -#96119 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#96120 = VECTOR('',#96121,1.); -#96121 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96122 = PCURVE('',#96095,#96123); -#96123 = DEFINITIONAL_REPRESENTATION('',(#96124),#96128); -#96124 = LINE('',#96125,#96126); -#96125 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#96126 = VECTOR('',#96127,1.); -#96127 = DIRECTION('',(1.,0.E+000)); -#96128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96129 = PCURVE('',#96130,#96135); -#96130 = PLANE('',#96131); -#96131 = AXIS2_PLACEMENT_3D('',#96132,#96133,#96134); -#96132 = CARTESIAN_POINT('',(1.75,-1.,-0.258196742327)); -#96133 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#96134 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#96135 = DEFINITIONAL_REPRESENTATION('',(#96136),#96140); -#96136 = LINE('',#96137,#96138); -#96137 = CARTESIAN_POINT('',(-5.000038352949E-002,8.25)); -#96138 = VECTOR('',#96139,1.); -#96139 = DIRECTION('',(0.E+000,1.)); -#96140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96141 = ORIENTED_EDGE('',*,*,#96142,.F.); -#96142 = EDGE_CURVE('',#96143,#96115,#96145,.T.); -#96143 = VERTEX_POINT('',#96144); -#96144 = CARTESIAN_POINT('',(1.85,-0.740726081328,-0.208196358798)); -#96145 = SURFACE_CURVE('',#96146,(#96150,#96157),.PCURVE_S1.); -#96146 = LINE('',#96147,#96148); -#96147 = CARTESIAN_POINT('',(1.85,-0.740726081328,-0.208196358798)); -#96148 = VECTOR('',#96149,1.); -#96149 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96150 = PCURVE('',#96095,#96151); -#96151 = DEFINITIONAL_REPRESENTATION('',(#96152),#96156); -#96152 = LINE('',#96153,#96154); -#96153 = CARTESIAN_POINT('',(-8.15,0.E+000)); -#96154 = VECTOR('',#96155,1.); -#96155 = DIRECTION('',(0.E+000,-1.)); -#96156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98281 = ORIENTED_EDGE('',*,*,#98282,.T.); +#98282 = EDGE_CURVE('',#98256,#98232,#98283,.T.); +#98283 = SURFACE_CURVE('',#98284,(#98288,#98294),.PCURVE_S1.); +#98284 = LINE('',#98285,#98286); +#98285 = CARTESIAN_POINT('',(5.15,-0.304819755875,0.75)); +#98286 = VECTOR('',#98287,1.); +#98287 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98288 = PCURVE('',#98025,#98289); +#98289 = DEFINITIONAL_REPRESENTATION('',(#98290),#98293); +#98290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98291,#98292),.UNSPECIFIED., + .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); +#98291 = CARTESIAN_POINT('',(3.162095483347,-4.65)); +#98292 = CARTESIAN_POINT('',(3.162095483347,-4.85)); +#98293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98294 = PCURVE('',#91885,#98295); +#98295 = DEFINITIONAL_REPRESENTATION('',(#98296),#98300); +#98296 = LINE('',#98297,#98298); +#98297 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#98298 = VECTOR('',#98299,1.); +#98299 = DIRECTION('',(0.E+000,-1.)); +#98300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98301 = ADVANCED_FACE('',(#98302),#91829,.F.); +#98302 = FACE_BOUND('',#98303,.T.); +#98303 = EDGE_LOOP('',(#98304,#98305,#98326,#98327)); +#98304 = ORIENTED_EDGE('',*,*,#98184,.F.); +#98305 = ORIENTED_EDGE('',*,*,#98306,.T.); +#98306 = EDGE_CURVE('',#98185,#91812,#98307,.T.); +#98307 = SURFACE_CURVE('',#98308,(#98312,#98319),.PCURVE_S1.); +#98308 = LINE('',#98309,#98310); +#98309 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.65)); +#98310 = VECTOR('',#98311,1.); +#98311 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#98312 = PCURVE('',#91829,#98313); +#98313 = DEFINITIONAL_REPRESENTATION('',(#98314),#98318); +#98314 = LINE('',#98315,#98316); +#98315 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98316 = VECTOR('',#98317,1.); +#98317 = DIRECTION('',(-1.,0.E+000)); +#98318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98319 = PCURVE('',#91857,#98320); +#98320 = DEFINITIONAL_REPRESENTATION('',(#98321),#98325); +#98321 = LINE('',#98322,#98323); +#98322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98323 = VECTOR('',#98324,1.); +#98324 = DIRECTION('',(-3.563627120235E-016,1.)); +#98325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#96157 = PCURVE('',#89100,#96158); -#96158 = DEFINITIONAL_REPRESENTATION('',(#96159),#96163); -#96159 = LINE('',#96160,#96161); -#96160 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#96161 = VECTOR('',#96162,1.); -#96162 = DIRECTION('',(0.E+000,-1.)); -#96163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96164 = ORIENTED_EDGE('',*,*,#96165,.T.); -#96165 = EDGE_CURVE('',#96143,#96085,#96166,.T.); -#96166 = SURFACE_CURVE('',#96167,(#96171,#96178),.PCURVE_S1.); -#96167 = LINE('',#96168,#96169); -#96168 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#96169 = VECTOR('',#96170,1.); -#96170 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96171 = PCURVE('',#96095,#96172); -#96172 = DEFINITIONAL_REPRESENTATION('',(#96173),#96177); -#96173 = LINE('',#96174,#96175); -#96174 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96175 = VECTOR('',#96176,1.); -#96176 = DIRECTION('',(-1.,0.E+000)); -#96177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96178 = PCURVE('',#96179,#96184); -#96179 = CYLINDRICAL_SURFACE('',#96180,0.208574704164); -#96180 = AXIS2_PLACEMENT_3D('',#96181,#96182,#96183); -#96181 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#96182 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96183 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96184 = DEFINITIONAL_REPRESENTATION('',(#96185),#96188); -#96185 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96186,#96187),.UNSPECIFIED., +#98326 = ORIENTED_EDGE('',*,*,#91811,.T.); +#98327 = ORIENTED_EDGE('',*,*,#98328,.F.); +#98328 = EDGE_CURVE('',#98158,#91814,#98329,.T.); +#98329 = SURFACE_CURVE('',#98330,(#98334,#98341),.PCURVE_S1.); +#98330 = LINE('',#98331,#98332); +#98331 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.65)); +#98332 = VECTOR('',#98333,1.); +#98333 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#98334 = PCURVE('',#91829,#98335); +#98335 = DEFINITIONAL_REPRESENTATION('',(#98336),#98340); +#98336 = LINE('',#98337,#98338); +#98337 = CARTESIAN_POINT('',(0.E+000,0.2)); +#98338 = VECTOR('',#98339,1.); +#98339 = DIRECTION('',(-1.,0.E+000)); +#98340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98341 = PCURVE('',#91911,#98342); +#98342 = DEFINITIONAL_REPRESENTATION('',(#98343),#98347); +#98343 = LINE('',#98344,#98345); +#98344 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98345 = VECTOR('',#98346,1.); +#98346 = DIRECTION('',(3.563627120235E-016,1.)); +#98347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98348 = ADVANCED_FACE('',(#98349),#91911,.F.); +#98349 = FACE_BOUND('',#98350,.T.); +#98350 = EDGE_LOOP('',(#98351,#98372,#98373,#98374,#98375,#98376,#98397, + #98398,#98399,#98400,#98401,#98402)); +#98351 = ORIENTED_EDGE('',*,*,#98352,.F.); +#98352 = EDGE_CURVE('',#98256,#91870,#98353,.T.); +#98353 = SURFACE_CURVE('',#98354,(#98358,#98365),.PCURVE_S1.); +#98354 = LINE('',#98355,#98356); +#98355 = CARTESIAN_POINT('',(5.35,-0.527847992439,0.75)); +#98356 = VECTOR('',#98357,1.); +#98357 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#98358 = PCURVE('',#91911,#98359); +#98359 = DEFINITIONAL_REPRESENTATION('',(#98360),#98364); +#98360 = LINE('',#98361,#98362); +#98361 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#98362 = VECTOR('',#98363,1.); +#98363 = DIRECTION('',(3.563627120235E-016,1.)); +#98364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98365 = PCURVE('',#91885,#98366); +#98366 = DEFINITIONAL_REPRESENTATION('',(#98367),#98371); +#98367 = LINE('',#98368,#98369); +#98368 = CARTESIAN_POINT('',(0.E+000,0.2)); +#98369 = VECTOR('',#98370,1.); +#98370 = DIRECTION('',(1.,0.E+000)); +#98371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98372 = ORIENTED_EDGE('',*,*,#98255,.T.); +#98373 = ORIENTED_EDGE('',*,*,#98058,.T.); +#98374 = ORIENTED_EDGE('',*,*,#97983,.T.); +#98375 = ORIENTED_EDGE('',*,*,#97798,.T.); +#98376 = ORIENTED_EDGE('',*,*,#98377,.T.); +#98377 = EDGE_CURVE('',#97776,#97639,#98378,.T.); +#98378 = SURFACE_CURVE('',#98379,(#98383,#98390),.PCURVE_S1.); +#98379 = LINE('',#98380,#98381); +#98380 = CARTESIAN_POINT('',(5.35,-1.,1.159810404338E-002)); +#98381 = VECTOR('',#98382,1.); +#98382 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#98383 = PCURVE('',#91911,#98384); +#98384 = DEFINITIONAL_REPRESENTATION('',(#98385),#98389); +#98385 = LINE('',#98386,#98387); +#98386 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#98387 = VECTOR('',#98388,1.); +#98388 = DIRECTION('',(-1.,2.101748079665E-016)); +#98389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98390 = PCURVE('',#97682,#98391); +#98391 = DEFINITIONAL_REPRESENTATION('',(#98392),#98396); +#98392 = LINE('',#98393,#98394); +#98393 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#98394 = VECTOR('',#98395,1.); +#98395 = DIRECTION('',(1.,0.E+000)); +#98396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98397 = ORIENTED_EDGE('',*,*,#97636,.F.); +#98398 = ORIENTED_EDGE('',*,*,#97904,.F.); +#98399 = ORIENTED_EDGE('',*,*,#98111,.F.); +#98400 = ORIENTED_EDGE('',*,*,#98157,.F.); +#98401 = ORIENTED_EDGE('',*,*,#98328,.T.); +#98402 = ORIENTED_EDGE('',*,*,#91897,.T.); +#98403 = ADVANCED_FACE('',(#98404),#91885,.F.); +#98404 = FACE_BOUND('',#98405,.T.); +#98405 = EDGE_LOOP('',(#98406,#98407,#98408,#98409)); +#98406 = ORIENTED_EDGE('',*,*,#98282,.F.); +#98407 = ORIENTED_EDGE('',*,*,#98352,.T.); +#98408 = ORIENTED_EDGE('',*,*,#91869,.T.); +#98409 = ORIENTED_EDGE('',*,*,#98410,.F.); +#98410 = EDGE_CURVE('',#98232,#91842,#98411,.T.); +#98411 = SURFACE_CURVE('',#98412,(#98416,#98423),.PCURVE_S1.); +#98412 = LINE('',#98413,#98414); +#98413 = CARTESIAN_POINT('',(5.15,-0.527847992439,0.75)); +#98414 = VECTOR('',#98415,1.); +#98415 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#98416 = PCURVE('',#91885,#98417); +#98417 = DEFINITIONAL_REPRESENTATION('',(#98418),#98422); +#98418 = LINE('',#98419,#98420); +#98419 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98420 = VECTOR('',#98421,1.); +#98421 = DIRECTION('',(1.,0.E+000)); +#98422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98423 = PCURVE('',#91857,#98424); +#98424 = DEFINITIONAL_REPRESENTATION('',(#98425),#98429); +#98425 = LINE('',#98426,#98427); +#98426 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#98427 = VECTOR('',#98428,1.); +#98428 = DIRECTION('',(-3.563627120235E-016,1.)); +#98429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98430 = ADVANCED_FACE('',(#98431),#91857,.F.); +#98431 = FACE_BOUND('',#98432,.T.); +#98432 = EDGE_LOOP('',(#98433,#98434,#98435,#98436,#98437,#98438,#98459, + #98460,#98461,#98462,#98463,#98464)); +#98433 = ORIENTED_EDGE('',*,*,#98306,.F.); +#98434 = ORIENTED_EDGE('',*,*,#98206,.T.); +#98435 = ORIENTED_EDGE('',*,*,#98133,.T.); +#98436 = ORIENTED_EDGE('',*,*,#97850,.T.); +#98437 = ORIENTED_EDGE('',*,*,#97694,.T.); +#98438 = ORIENTED_EDGE('',*,*,#98439,.T.); +#98439 = EDGE_CURVE('',#97667,#97748,#98440,.T.); +#98440 = SURFACE_CURVE('',#98441,(#98445,#98452),.PCURVE_S1.); +#98441 = LINE('',#98442,#98443); +#98442 = CARTESIAN_POINT('',(5.15,-1.,1.159810404338E-002)); +#98443 = VECTOR('',#98444,1.); +#98444 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#98445 = PCURVE('',#91857,#98446); +#98446 = DEFINITIONAL_REPRESENTATION('',(#98447),#98451); +#98447 = LINE('',#98448,#98449); +#98448 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#98449 = VECTOR('',#98450,1.); +#98450 = DIRECTION('',(-1.,-2.101748079665E-016)); +#98451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98452 = PCURVE('',#97682,#98453); +#98453 = DEFINITIONAL_REPRESENTATION('',(#98454),#98458); +#98454 = LINE('',#98455,#98456); +#98455 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#98456 = VECTOR('',#98457,1.); +#98457 = DIRECTION('',(-1.,0.E+000)); +#98458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98459 = ORIENTED_EDGE('',*,*,#97745,.F.); +#98460 = ORIENTED_EDGE('',*,*,#97929,.F.); +#98461 = ORIENTED_EDGE('',*,*,#98036,.F.); +#98462 = ORIENTED_EDGE('',*,*,#98231,.F.); +#98463 = ORIENTED_EDGE('',*,*,#98410,.T.); +#98464 = ORIENTED_EDGE('',*,*,#91841,.T.); +#98465 = ADVANCED_FACE('',(#98466),#97682,.T.); +#98466 = FACE_BOUND('',#98467,.T.); +#98467 = EDGE_LOOP('',(#98468,#98469,#98470,#98471)); +#98468 = ORIENTED_EDGE('',*,*,#97775,.F.); +#98469 = ORIENTED_EDGE('',*,*,#98439,.F.); +#98470 = ORIENTED_EDGE('',*,*,#97666,.F.); +#98471 = ORIENTED_EDGE('',*,*,#98377,.F.); +#98472 = ADVANCED_FACE('',(#98473),#98487,.T.); +#98473 = FACE_BOUND('',#98474,.T.); +#98474 = EDGE_LOOP('',(#98475,#98505,#98533,#98556)); +#98475 = ORIENTED_EDGE('',*,*,#98476,.T.); +#98476 = EDGE_CURVE('',#98477,#98479,#98481,.T.); +#98477 = VERTEX_POINT('',#98478); +#98478 = CARTESIAN_POINT('',(1.65,-0.740726081328,-0.208196358798)); +#98479 = VERTEX_POINT('',#98480); +#98480 = CARTESIAN_POINT('',(1.65,-1.,-0.208196358798)); +#98481 = SURFACE_CURVE('',#98482,(#98486,#98498),.PCURVE_S1.); +#98482 = LINE('',#98483,#98484); +#98483 = CARTESIAN_POINT('',(1.65,-0.740726081328,-0.208196358798)); +#98484 = VECTOR('',#98485,1.); +#98485 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#98486 = PCURVE('',#98487,#98492); +#98487 = PLANE('',#98488); +#98488 = AXIS2_PLACEMENT_3D('',#98489,#98490,#98491); +#98489 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#98490 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98491 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98492 = DEFINITIONAL_REPRESENTATION('',(#98493),#98497); +#98493 = LINE('',#98494,#98495); +#98494 = CARTESIAN_POINT('',(-8.35,0.E+000)); +#98495 = VECTOR('',#98496,1.); +#98496 = DIRECTION('',(0.E+000,-1.)); +#98497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98498 = PCURVE('',#91548,#98499); +#98499 = DEFINITIONAL_REPRESENTATION('',(#98500),#98504); +#98500 = LINE('',#98501,#98502); +#98501 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#98502 = VECTOR('',#98503,1.); +#98503 = DIRECTION('',(0.E+000,-1.)); +#98504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98505 = ORIENTED_EDGE('',*,*,#98506,.T.); +#98506 = EDGE_CURVE('',#98479,#98507,#98509,.T.); +#98507 = VERTEX_POINT('',#98508); +#98508 = CARTESIAN_POINT('',(1.85,-1.,-0.208196358798)); +#98509 = SURFACE_CURVE('',#98510,(#98514,#98521),.PCURVE_S1.); +#98510 = LINE('',#98511,#98512); +#98511 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#98512 = VECTOR('',#98513,1.); +#98513 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98514 = PCURVE('',#98487,#98515); +#98515 = DEFINITIONAL_REPRESENTATION('',(#98516),#98520); +#98516 = LINE('',#98517,#98518); +#98517 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#98518 = VECTOR('',#98519,1.); +#98519 = DIRECTION('',(1.,0.E+000)); +#98520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98521 = PCURVE('',#98522,#98527); +#98522 = PLANE('',#98523); +#98523 = AXIS2_PLACEMENT_3D('',#98524,#98525,#98526); +#98524 = CARTESIAN_POINT('',(1.75,-1.,-0.258196742327)); +#98525 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#98526 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#98527 = DEFINITIONAL_REPRESENTATION('',(#98528),#98532); +#98528 = LINE('',#98529,#98530); +#98529 = CARTESIAN_POINT('',(-5.000038352949E-002,8.25)); +#98530 = VECTOR('',#98531,1.); +#98531 = DIRECTION('',(0.E+000,1.)); +#98532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98533 = ORIENTED_EDGE('',*,*,#98534,.F.); +#98534 = EDGE_CURVE('',#98535,#98507,#98537,.T.); +#98535 = VERTEX_POINT('',#98536); +#98536 = CARTESIAN_POINT('',(1.85,-0.740726081328,-0.208196358798)); +#98537 = SURFACE_CURVE('',#98538,(#98542,#98549),.PCURVE_S1.); +#98538 = LINE('',#98539,#98540); +#98539 = CARTESIAN_POINT('',(1.85,-0.740726081328,-0.208196358798)); +#98540 = VECTOR('',#98541,1.); +#98541 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#98542 = PCURVE('',#98487,#98543); +#98543 = DEFINITIONAL_REPRESENTATION('',(#98544),#98548); +#98544 = LINE('',#98545,#98546); +#98545 = CARTESIAN_POINT('',(-8.15,0.E+000)); +#98546 = VECTOR('',#98547,1.); +#98547 = DIRECTION('',(0.E+000,-1.)); +#98548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98549 = PCURVE('',#91492,#98550); +#98550 = DEFINITIONAL_REPRESENTATION('',(#98551),#98555); +#98551 = LINE('',#98552,#98553); +#98552 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#98553 = VECTOR('',#98554,1.); +#98554 = DIRECTION('',(0.E+000,-1.)); +#98555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98556 = ORIENTED_EDGE('',*,*,#98557,.T.); +#98557 = EDGE_CURVE('',#98535,#98477,#98558,.T.); +#98558 = SURFACE_CURVE('',#98559,(#98563,#98570),.PCURVE_S1.); +#98559 = LINE('',#98560,#98561); +#98560 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#98561 = VECTOR('',#98562,1.); +#98562 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98563 = PCURVE('',#98487,#98564); +#98564 = DEFINITIONAL_REPRESENTATION('',(#98565),#98569); +#98565 = LINE('',#98566,#98567); +#98566 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98567 = VECTOR('',#98568,1.); +#98568 = DIRECTION('',(-1.,0.E+000)); +#98569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98570 = PCURVE('',#98571,#98576); +#98571 = CYLINDRICAL_SURFACE('',#98572,0.208574704164); +#98572 = AXIS2_PLACEMENT_3D('',#98573,#98574,#98575); +#98573 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#98574 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98575 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98576 = DEFINITIONAL_REPRESENTATION('',(#98577),#98580); +#98577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98578,#98579),.UNSPECIFIED., .F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#96186 = CARTESIAN_POINT('',(3.201833915432,8.15)); -#96187 = CARTESIAN_POINT('',(3.201833915432,8.35)); -#96188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96189 = ADVANCED_FACE('',(#96190),#96204,.T.); -#96190 = FACE_BOUND('',#96191,.T.); -#96191 = EDGE_LOOP('',(#96192,#96222,#96245,#96268)); -#96192 = ORIENTED_EDGE('',*,*,#96193,.T.); -#96193 = EDGE_CURVE('',#96194,#96196,#96198,.T.); -#96194 = VERTEX_POINT('',#96195); -#96195 = CARTESIAN_POINT('',(1.85,-0.74341632541,-0.308197125857)); -#96196 = VERTEX_POINT('',#96197); -#96197 = CARTESIAN_POINT('',(1.85,-1.,-0.308197125857)); -#96198 = SURFACE_CURVE('',#96199,(#96203,#96215),.PCURVE_S1.); -#96199 = LINE('',#96200,#96201); -#96200 = CARTESIAN_POINT('',(1.85,-0.74341632541,-0.308197125857)); -#96201 = VECTOR('',#96202,1.); -#96202 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96203 = PCURVE('',#96204,#96209); -#96204 = PLANE('',#96205); -#96205 = AXIS2_PLACEMENT_3D('',#96206,#96207,#96208); -#96206 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#96207 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96208 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96209 = DEFINITIONAL_REPRESENTATION('',(#96210),#96214); -#96210 = LINE('',#96211,#96212); -#96211 = CARTESIAN_POINT('',(8.15,0.E+000)); -#96212 = VECTOR('',#96213,1.); -#96213 = DIRECTION('',(0.E+000,-1.)); -#96214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96215 = PCURVE('',#89100,#96216); -#96216 = DEFINITIONAL_REPRESENTATION('',(#96217),#96221); -#96217 = LINE('',#96218,#96219); -#96218 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#96219 = VECTOR('',#96220,1.); -#96220 = DIRECTION('',(0.E+000,-1.)); -#96221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96222 = ORIENTED_EDGE('',*,*,#96223,.T.); -#96223 = EDGE_CURVE('',#96196,#96224,#96226,.T.); -#96224 = VERTEX_POINT('',#96225); -#96225 = CARTESIAN_POINT('',(1.65,-1.,-0.308197125857)); -#96226 = SURFACE_CURVE('',#96227,(#96231,#96238),.PCURVE_S1.); -#96227 = LINE('',#96228,#96229); -#96228 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#96229 = VECTOR('',#96230,1.); -#96230 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96231 = PCURVE('',#96204,#96232); -#96232 = DEFINITIONAL_REPRESENTATION('',(#96233),#96237); -#96233 = LINE('',#96234,#96235); -#96234 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#96235 = VECTOR('',#96236,1.); -#96236 = DIRECTION('',(1.,0.E+000)); -#96237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96238 = PCURVE('',#96130,#96239); -#96239 = DEFINITIONAL_REPRESENTATION('',(#96240),#96244); -#96240 = LINE('',#96241,#96242); -#96241 = CARTESIAN_POINT('',(5.000038352949E-002,8.25)); -#96242 = VECTOR('',#96243,1.); -#96243 = DIRECTION('',(0.E+000,-1.)); -#96244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96245 = ORIENTED_EDGE('',*,*,#96246,.F.); -#96246 = EDGE_CURVE('',#96247,#96224,#96249,.T.); -#96247 = VERTEX_POINT('',#96248); -#96248 = CARTESIAN_POINT('',(1.65,-0.74341632541,-0.308197125857)); -#96249 = SURFACE_CURVE('',#96250,(#96254,#96261),.PCURVE_S1.); -#96250 = LINE('',#96251,#96252); -#96251 = CARTESIAN_POINT('',(1.65,-0.74341632541,-0.308197125857)); -#96252 = VECTOR('',#96253,1.); -#96253 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96254 = PCURVE('',#96204,#96255); -#96255 = DEFINITIONAL_REPRESENTATION('',(#96256),#96260); -#96256 = LINE('',#96257,#96258); -#96257 = CARTESIAN_POINT('',(8.35,0.E+000)); -#96258 = VECTOR('',#96259,1.); -#96259 = DIRECTION('',(0.E+000,-1.)); -#96260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96261 = PCURVE('',#89156,#96262); -#96262 = DEFINITIONAL_REPRESENTATION('',(#96263),#96267); -#96263 = LINE('',#96264,#96265); -#96264 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#96265 = VECTOR('',#96266,1.); -#96266 = DIRECTION('',(0.E+000,-1.)); -#96267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96268 = ORIENTED_EDGE('',*,*,#96269,.T.); -#96269 = EDGE_CURVE('',#96247,#96194,#96270,.T.); -#96270 = SURFACE_CURVE('',#96271,(#96275,#96282),.PCURVE_S1.); -#96271 = LINE('',#96272,#96273); -#96272 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#96273 = VECTOR('',#96274,1.); -#96274 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96275 = PCURVE('',#96204,#96276); -#96276 = DEFINITIONAL_REPRESENTATION('',(#96277),#96281); -#96277 = LINE('',#96278,#96279); -#96278 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96279 = VECTOR('',#96280,1.); -#96280 = DIRECTION('',(-1.,0.E+000)); -#96281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96282 = PCURVE('',#96283,#96288); -#96283 = CYLINDRICAL_SURFACE('',#96284,0.308574064194); -#96284 = AXIS2_PLACEMENT_3D('',#96285,#96286,#96287); -#96285 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#96286 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96287 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96288 = DEFINITIONAL_REPRESENTATION('',(#96289),#96292); -#96289 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96290,#96291),.UNSPECIFIED., +#98578 = CARTESIAN_POINT('',(3.201833915432,8.15)); +#98579 = CARTESIAN_POINT('',(3.201833915432,8.35)); +#98580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98581 = ADVANCED_FACE('',(#98582),#98596,.T.); +#98582 = FACE_BOUND('',#98583,.T.); +#98583 = EDGE_LOOP('',(#98584,#98614,#98637,#98660)); +#98584 = ORIENTED_EDGE('',*,*,#98585,.T.); +#98585 = EDGE_CURVE('',#98586,#98588,#98590,.T.); +#98586 = VERTEX_POINT('',#98587); +#98587 = CARTESIAN_POINT('',(1.85,-0.74341632541,-0.308197125857)); +#98588 = VERTEX_POINT('',#98589); +#98589 = CARTESIAN_POINT('',(1.85,-1.,-0.308197125857)); +#98590 = SURFACE_CURVE('',#98591,(#98595,#98607),.PCURVE_S1.); +#98591 = LINE('',#98592,#98593); +#98592 = CARTESIAN_POINT('',(1.85,-0.74341632541,-0.308197125857)); +#98593 = VECTOR('',#98594,1.); +#98594 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#98595 = PCURVE('',#98596,#98601); +#98596 = PLANE('',#98597); +#98597 = AXIS2_PLACEMENT_3D('',#98598,#98599,#98600); +#98598 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#98599 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98600 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98601 = DEFINITIONAL_REPRESENTATION('',(#98602),#98606); +#98602 = LINE('',#98603,#98604); +#98603 = CARTESIAN_POINT('',(8.15,0.E+000)); +#98604 = VECTOR('',#98605,1.); +#98605 = DIRECTION('',(0.E+000,-1.)); +#98606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98607 = PCURVE('',#91492,#98608); +#98608 = DEFINITIONAL_REPRESENTATION('',(#98609),#98613); +#98609 = LINE('',#98610,#98611); +#98610 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#98611 = VECTOR('',#98612,1.); +#98612 = DIRECTION('',(0.E+000,-1.)); +#98613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98614 = ORIENTED_EDGE('',*,*,#98615,.T.); +#98615 = EDGE_CURVE('',#98588,#98616,#98618,.T.); +#98616 = VERTEX_POINT('',#98617); +#98617 = CARTESIAN_POINT('',(1.65,-1.,-0.308197125857)); +#98618 = SURFACE_CURVE('',#98619,(#98623,#98630),.PCURVE_S1.); +#98619 = LINE('',#98620,#98621); +#98620 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#98621 = VECTOR('',#98622,1.); +#98622 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98623 = PCURVE('',#98596,#98624); +#98624 = DEFINITIONAL_REPRESENTATION('',(#98625),#98629); +#98625 = LINE('',#98626,#98627); +#98626 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#98627 = VECTOR('',#98628,1.); +#98628 = DIRECTION('',(1.,0.E+000)); +#98629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98630 = PCURVE('',#98522,#98631); +#98631 = DEFINITIONAL_REPRESENTATION('',(#98632),#98636); +#98632 = LINE('',#98633,#98634); +#98633 = CARTESIAN_POINT('',(5.000038352949E-002,8.25)); +#98634 = VECTOR('',#98635,1.); +#98635 = DIRECTION('',(0.E+000,-1.)); +#98636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98637 = ORIENTED_EDGE('',*,*,#98638,.F.); +#98638 = EDGE_CURVE('',#98639,#98616,#98641,.T.); +#98639 = VERTEX_POINT('',#98640); +#98640 = CARTESIAN_POINT('',(1.65,-0.74341632541,-0.308197125857)); +#98641 = SURFACE_CURVE('',#98642,(#98646,#98653),.PCURVE_S1.); +#98642 = LINE('',#98643,#98644); +#98643 = CARTESIAN_POINT('',(1.65,-0.74341632541,-0.308197125857)); +#98644 = VECTOR('',#98645,1.); +#98645 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#98646 = PCURVE('',#98596,#98647); +#98647 = DEFINITIONAL_REPRESENTATION('',(#98648),#98652); +#98648 = LINE('',#98649,#98650); +#98649 = CARTESIAN_POINT('',(8.35,0.E+000)); +#98650 = VECTOR('',#98651,1.); +#98651 = DIRECTION('',(0.E+000,-1.)); +#98652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98653 = PCURVE('',#91548,#98654); +#98654 = DEFINITIONAL_REPRESENTATION('',(#98655),#98659); +#98655 = LINE('',#98656,#98657); +#98656 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#98657 = VECTOR('',#98658,1.); +#98658 = DIRECTION('',(0.E+000,-1.)); +#98659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98660 = ORIENTED_EDGE('',*,*,#98661,.T.); +#98661 = EDGE_CURVE('',#98639,#98586,#98662,.T.); +#98662 = SURFACE_CURVE('',#98663,(#98667,#98674),.PCURVE_S1.); +#98663 = LINE('',#98664,#98665); +#98664 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#98665 = VECTOR('',#98666,1.); +#98666 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98667 = PCURVE('',#98596,#98668); +#98668 = DEFINITIONAL_REPRESENTATION('',(#98669),#98673); +#98669 = LINE('',#98670,#98671); +#98670 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98671 = VECTOR('',#98672,1.); +#98672 = DIRECTION('',(-1.,0.E+000)); +#98673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98674 = PCURVE('',#98675,#98680); +#98675 = CYLINDRICAL_SURFACE('',#98676,0.308574064194); +#98676 = AXIS2_PLACEMENT_3D('',#98677,#98678,#98679); +#98677 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#98678 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98679 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98680 = DEFINITIONAL_REPRESENTATION('',(#98681),#98684); +#98681 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98682,#98683),.UNSPECIFIED., .F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#96290 = CARTESIAN_POINT('',(3.191025391152,8.35)); -#96291 = CARTESIAN_POINT('',(3.191025391152,8.15)); -#96292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96293 = ADVANCED_FACE('',(#96294),#96179,.F.); -#96294 = FACE_BOUND('',#96295,.F.); -#96295 = EDGE_LOOP('',(#96296,#96297,#96324,#96351)); -#96296 = ORIENTED_EDGE('',*,*,#96165,.T.); -#96297 = ORIENTED_EDGE('',*,*,#96298,.F.); -#96298 = EDGE_CURVE('',#96299,#96085,#96301,.T.); -#96299 = VERTEX_POINT('',#96300); -#96300 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.E+000)); -#96301 = SURFACE_CURVE('',#96302,(#96307,#96313),.PCURVE_S1.); -#96302 = CIRCLE('',#96303,0.208574704164); -#96303 = AXIS2_PLACEMENT_3D('',#96304,#96305,#96306); -#96304 = CARTESIAN_POINT('',(1.65,-0.728168876214,2.640924866458E-017)); -#96305 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96306 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96307 = PCURVE('',#96179,#96308); -#96308 = DEFINITIONAL_REPRESENTATION('',(#96309),#96312); -#96309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96310,#96311),.UNSPECIFIED., +#98682 = CARTESIAN_POINT('',(3.191025391152,8.35)); +#98683 = CARTESIAN_POINT('',(3.191025391152,8.15)); +#98684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98685 = ADVANCED_FACE('',(#98686),#98571,.F.); +#98686 = FACE_BOUND('',#98687,.F.); +#98687 = EDGE_LOOP('',(#98688,#98689,#98716,#98743)); +#98688 = ORIENTED_EDGE('',*,*,#98557,.T.); +#98689 = ORIENTED_EDGE('',*,*,#98690,.F.); +#98690 = EDGE_CURVE('',#98691,#98477,#98693,.T.); +#98691 = VERTEX_POINT('',#98692); +#98692 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.E+000)); +#98693 = SURFACE_CURVE('',#98694,(#98699,#98705),.PCURVE_S1.); +#98694 = CIRCLE('',#98695,0.208574704164); +#98695 = AXIS2_PLACEMENT_3D('',#98696,#98697,#98698); +#98696 = CARTESIAN_POINT('',(1.65,-0.728168876214,2.640924866458E-017)); +#98697 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98698 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98699 = PCURVE('',#98571,#98700); +#98700 = DEFINITIONAL_REPRESENTATION('',(#98701),#98704); +#98701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98702,#98703),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#96310 = CARTESIAN_POINT('',(1.570796326795,8.35)); -#96311 = CARTESIAN_POINT('',(3.201833915432,8.35)); -#96312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98702 = CARTESIAN_POINT('',(1.570796326795,8.35)); +#98703 = CARTESIAN_POINT('',(3.201833915432,8.35)); +#98704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#96313 = PCURVE('',#89156,#96314); -#96314 = DEFINITIONAL_REPRESENTATION('',(#96315),#96323); -#96315 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#96316,#96317,#96318,#96319 - ,#96320,#96321,#96322),.UNSPECIFIED.,.F.,.F.) +#98705 = PCURVE('',#91548,#98706); +#98706 = DEFINITIONAL_REPRESENTATION('',(#98707),#98715); +#98707 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98708,#98709,#98710,#98711 + ,#98712,#98713,#98714),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#96316 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#96317 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#96318 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#96319 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#96320 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#96321 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#96322 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#96323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96324 = ORIENTED_EDGE('',*,*,#96325,.T.); -#96325 = EDGE_CURVE('',#96299,#96326,#96328,.T.); -#96326 = VERTEX_POINT('',#96327); -#96327 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.E+000)); -#96328 = SURFACE_CURVE('',#96329,(#96333,#96339),.PCURVE_S1.); -#96329 = LINE('',#96330,#96331); -#96330 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#96331 = VECTOR('',#96332,1.); -#96332 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96333 = PCURVE('',#96179,#96334); -#96334 = DEFINITIONAL_REPRESENTATION('',(#96335),#96338); -#96335 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96336,#96337),.UNSPECIFIED., +#98708 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#98709 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#98710 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#98711 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#98712 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#98713 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#98714 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#98715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98716 = ORIENTED_EDGE('',*,*,#98717,.T.); +#98717 = EDGE_CURVE('',#98691,#98718,#98720,.T.); +#98718 = VERTEX_POINT('',#98719); +#98719 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.E+000)); +#98720 = SURFACE_CURVE('',#98721,(#98725,#98731),.PCURVE_S1.); +#98721 = LINE('',#98722,#98723); +#98722 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#98723 = VECTOR('',#98724,1.); +#98724 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98725 = PCURVE('',#98571,#98726); +#98726 = DEFINITIONAL_REPRESENTATION('',(#98727),#98730); +#98727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98728,#98729),.UNSPECIFIED., .F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#96336 = CARTESIAN_POINT('',(1.570796326795,8.35)); -#96337 = CARTESIAN_POINT('',(1.570796326795,8.15)); -#96338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96339 = PCURVE('',#96340,#96345); -#96340 = PLANE('',#96341); -#96341 = AXIS2_PLACEMENT_3D('',#96342,#96343,#96344); -#96342 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#96343 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#96344 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#96345 = DEFINITIONAL_REPRESENTATION('',(#96346),#96350); -#96346 = LINE('',#96347,#96348); -#96347 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#96348 = VECTOR('',#96349,1.); -#96349 = DIRECTION('',(0.E+000,1.)); -#96350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96351 = ORIENTED_EDGE('',*,*,#96352,.T.); -#96352 = EDGE_CURVE('',#96326,#96143,#96353,.T.); -#96353 = SURFACE_CURVE('',#96354,(#96359,#96365),.PCURVE_S1.); -#96354 = CIRCLE('',#96355,0.208574704164); -#96355 = AXIS2_PLACEMENT_3D('',#96356,#96357,#96358); -#96356 = CARTESIAN_POINT('',(1.85,-0.728168876214,2.640924866458E-017)); -#96357 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96358 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96359 = PCURVE('',#96179,#96360); -#96360 = DEFINITIONAL_REPRESENTATION('',(#96361),#96364); -#96361 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96362,#96363),.UNSPECIFIED., +#98728 = CARTESIAN_POINT('',(1.570796326795,8.35)); +#98729 = CARTESIAN_POINT('',(1.570796326795,8.15)); +#98730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98731 = PCURVE('',#98732,#98737); +#98732 = PLANE('',#98733); +#98733 = AXIS2_PLACEMENT_3D('',#98734,#98735,#98736); +#98734 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#98735 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#98736 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#98737 = DEFINITIONAL_REPRESENTATION('',(#98738),#98742); +#98738 = LINE('',#98739,#98740); +#98739 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#98740 = VECTOR('',#98741,1.); +#98741 = DIRECTION('',(0.E+000,1.)); +#98742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98743 = ORIENTED_EDGE('',*,*,#98744,.T.); +#98744 = EDGE_CURVE('',#98718,#98535,#98745,.T.); +#98745 = SURFACE_CURVE('',#98746,(#98751,#98757),.PCURVE_S1.); +#98746 = CIRCLE('',#98747,0.208574704164); +#98747 = AXIS2_PLACEMENT_3D('',#98748,#98749,#98750); +#98748 = CARTESIAN_POINT('',(1.85,-0.728168876214,2.640924866458E-017)); +#98749 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98750 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98751 = PCURVE('',#98571,#98752); +#98752 = DEFINITIONAL_REPRESENTATION('',(#98753),#98756); +#98753 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98754,#98755),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#96362 = CARTESIAN_POINT('',(1.570796326795,8.15)); -#96363 = CARTESIAN_POINT('',(3.201833915432,8.15)); -#96364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96365 = PCURVE('',#89100,#96366); -#96366 = DEFINITIONAL_REPRESENTATION('',(#96367),#96371); -#96367 = CIRCLE('',#96368,0.208574704164); -#96368 = AXIS2_PLACEMENT_2D('',#96369,#96370); -#96369 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#96370 = DIRECTION('',(1.,0.E+000)); -#96371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96372 = ADVANCED_FACE('',(#96373),#96283,.T.); -#96373 = FACE_BOUND('',#96374,.T.); -#96374 = EDGE_LOOP('',(#96375,#96376,#96403,#96430)); -#96375 = ORIENTED_EDGE('',*,*,#96269,.F.); -#96376 = ORIENTED_EDGE('',*,*,#96377,.F.); -#96377 = EDGE_CURVE('',#96378,#96247,#96380,.T.); -#96378 = VERTEX_POINT('',#96379); -#96379 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.E+000)); -#96380 = SURFACE_CURVE('',#96381,(#96386,#96392),.PCURVE_S1.); -#96381 = CIRCLE('',#96382,0.308574064194); -#96382 = AXIS2_PLACEMENT_3D('',#96383,#96384,#96385); -#96383 = CARTESIAN_POINT('',(1.65,-0.728168876214,2.640924866458E-017)); -#96384 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96385 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96386 = PCURVE('',#96283,#96387); -#96387 = DEFINITIONAL_REPRESENTATION('',(#96388),#96391); -#96388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96389,#96390),.UNSPECIFIED., +#98754 = CARTESIAN_POINT('',(1.570796326795,8.15)); +#98755 = CARTESIAN_POINT('',(3.201833915432,8.15)); +#98756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98757 = PCURVE('',#91492,#98758); +#98758 = DEFINITIONAL_REPRESENTATION('',(#98759),#98763); +#98759 = CIRCLE('',#98760,0.208574704164); +#98760 = AXIS2_PLACEMENT_2D('',#98761,#98762); +#98761 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#98762 = DIRECTION('',(1.,0.E+000)); +#98763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98764 = ADVANCED_FACE('',(#98765),#98675,.T.); +#98765 = FACE_BOUND('',#98766,.T.); +#98766 = EDGE_LOOP('',(#98767,#98768,#98795,#98822)); +#98767 = ORIENTED_EDGE('',*,*,#98661,.F.); +#98768 = ORIENTED_EDGE('',*,*,#98769,.F.); +#98769 = EDGE_CURVE('',#98770,#98639,#98772,.T.); +#98770 = VERTEX_POINT('',#98771); +#98771 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.E+000)); +#98772 = SURFACE_CURVE('',#98773,(#98778,#98784),.PCURVE_S1.); +#98773 = CIRCLE('',#98774,0.308574064194); +#98774 = AXIS2_PLACEMENT_3D('',#98775,#98776,#98777); +#98775 = CARTESIAN_POINT('',(1.65,-0.728168876214,2.640924866458E-017)); +#98776 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98777 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98778 = PCURVE('',#98675,#98779); +#98779 = DEFINITIONAL_REPRESENTATION('',(#98780),#98783); +#98780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98781,#98782),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#96389 = CARTESIAN_POINT('',(1.570796326795,8.35)); -#96390 = CARTESIAN_POINT('',(3.191025391152,8.35)); -#96391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#98781 = CARTESIAN_POINT('',(1.570796326795,8.35)); +#98782 = CARTESIAN_POINT('',(3.191025391152,8.35)); +#98783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#96392 = PCURVE('',#89156,#96393); -#96393 = DEFINITIONAL_REPRESENTATION('',(#96394),#96402); -#96394 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#96395,#96396,#96397,#96398 - ,#96399,#96400,#96401),.UNSPECIFIED.,.T.,.F.) +#98784 = PCURVE('',#91548,#98785); +#98785 = DEFINITIONAL_REPRESENTATION('',(#98786),#98794); +#98786 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98787,#98788,#98789,#98790 + ,#98791,#98792,#98793),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#96395 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#96396 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#96397 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#96398 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#96399 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#96400 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#96401 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#96402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96403 = ORIENTED_EDGE('',*,*,#96404,.F.); -#96404 = EDGE_CURVE('',#96405,#96378,#96407,.T.); -#96405 = VERTEX_POINT('',#96406); -#96406 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.E+000)); -#96407 = SURFACE_CURVE('',#96408,(#96412,#96418),.PCURVE_S1.); -#96408 = LINE('',#96409,#96410); -#96409 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#96410 = VECTOR('',#96411,1.); -#96411 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96412 = PCURVE('',#96283,#96413); -#96413 = DEFINITIONAL_REPRESENTATION('',(#96414),#96417); -#96414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96415,#96416),.UNSPECIFIED., +#98787 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#98788 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#98789 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#98790 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#98791 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#98792 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#98793 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#98794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98795 = ORIENTED_EDGE('',*,*,#98796,.F.); +#98796 = EDGE_CURVE('',#98797,#98770,#98799,.T.); +#98797 = VERTEX_POINT('',#98798); +#98798 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.E+000)); +#98799 = SURFACE_CURVE('',#98800,(#98804,#98810),.PCURVE_S1.); +#98800 = LINE('',#98801,#98802); +#98801 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#98802 = VECTOR('',#98803,1.); +#98803 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98804 = PCURVE('',#98675,#98805); +#98805 = DEFINITIONAL_REPRESENTATION('',(#98806),#98809); +#98806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98807,#98808),.UNSPECIFIED., .F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#96415 = CARTESIAN_POINT('',(1.570796326795,8.15)); -#96416 = CARTESIAN_POINT('',(1.570796326795,8.35)); -#96417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96418 = PCURVE('',#96419,#96424); -#96419 = PLANE('',#96420); -#96420 = AXIS2_PLACEMENT_3D('',#96421,#96422,#96423); -#96421 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#96422 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#96423 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#96424 = DEFINITIONAL_REPRESENTATION('',(#96425),#96429); -#96425 = LINE('',#96426,#96427); -#96426 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#96427 = VECTOR('',#96428,1.); -#96428 = DIRECTION('',(0.E+000,-1.)); -#96429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96430 = ORIENTED_EDGE('',*,*,#96431,.T.); -#96431 = EDGE_CURVE('',#96405,#96194,#96432,.T.); -#96432 = SURFACE_CURVE('',#96433,(#96438,#96444),.PCURVE_S1.); -#96433 = CIRCLE('',#96434,0.308574064194); -#96434 = AXIS2_PLACEMENT_3D('',#96435,#96436,#96437); -#96435 = CARTESIAN_POINT('',(1.85,-0.728168876214,2.640924866458E-017)); -#96436 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96437 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96438 = PCURVE('',#96283,#96439); -#96439 = DEFINITIONAL_REPRESENTATION('',(#96440),#96443); -#96440 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96441,#96442),.UNSPECIFIED., +#98807 = CARTESIAN_POINT('',(1.570796326795,8.15)); +#98808 = CARTESIAN_POINT('',(1.570796326795,8.35)); +#98809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98810 = PCURVE('',#98811,#98816); +#98811 = PLANE('',#98812); +#98812 = AXIS2_PLACEMENT_3D('',#98813,#98814,#98815); +#98813 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#98814 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#98815 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98816 = DEFINITIONAL_REPRESENTATION('',(#98817),#98821); +#98817 = LINE('',#98818,#98819); +#98818 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#98819 = VECTOR('',#98820,1.); +#98820 = DIRECTION('',(0.E+000,-1.)); +#98821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98822 = ORIENTED_EDGE('',*,*,#98823,.T.); +#98823 = EDGE_CURVE('',#98797,#98586,#98824,.T.); +#98824 = SURFACE_CURVE('',#98825,(#98830,#98836),.PCURVE_S1.); +#98825 = CIRCLE('',#98826,0.308574064194); +#98826 = AXIS2_PLACEMENT_3D('',#98827,#98828,#98829); +#98827 = CARTESIAN_POINT('',(1.85,-0.728168876214,2.640924866458E-017)); +#98828 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98829 = DIRECTION('',(0.E+000,0.E+000,1.)); +#98830 = PCURVE('',#98675,#98831); +#98831 = DEFINITIONAL_REPRESENTATION('',(#98832),#98835); +#98832 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98833,#98834),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#96441 = CARTESIAN_POINT('',(1.570796326795,8.15)); -#96442 = CARTESIAN_POINT('',(3.191025391152,8.15)); -#96443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96444 = PCURVE('',#89100,#96445); -#96445 = DEFINITIONAL_REPRESENTATION('',(#96446),#96450); -#96446 = CIRCLE('',#96447,0.308574064194); -#96447 = AXIS2_PLACEMENT_2D('',#96448,#96449); -#96448 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#96449 = DIRECTION('',(1.,0.E+000)); -#96450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96451 = ADVANCED_FACE('',(#96452),#96419,.F.); -#96452 = FACE_BOUND('',#96453,.T.); -#96453 = EDGE_LOOP('',(#96454,#96483,#96504,#96505)); -#96454 = ORIENTED_EDGE('',*,*,#96455,.F.); -#96455 = EDGE_CURVE('',#96456,#96458,#96460,.T.); -#96456 = VERTEX_POINT('',#96457); -#96457 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.530776333563)); -#96458 = VERTEX_POINT('',#96459); -#96459 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.530776333563)); -#96460 = SURFACE_CURVE('',#96461,(#96465,#96472),.PCURVE_S1.); -#96461 = LINE('',#96462,#96463); -#96462 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#96463 = VECTOR('',#96464,1.); -#96464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96465 = PCURVE('',#96419,#96466); -#96466 = DEFINITIONAL_REPRESENTATION('',(#96467),#96471); -#96467 = LINE('',#96468,#96469); -#96468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96469 = VECTOR('',#96470,1.); -#96470 = DIRECTION('',(0.E+000,-1.)); -#96471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96472 = PCURVE('',#96473,#96478); -#96473 = CYLINDRICAL_SURFACE('',#96474,0.119270391569); -#96474 = AXIS2_PLACEMENT_3D('',#96475,#96476,#96477); -#96475 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#96476 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96477 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96478 = DEFINITIONAL_REPRESENTATION('',(#96479),#96482); -#96479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96480,#96481),.UNSPECIFIED., +#98833 = CARTESIAN_POINT('',(1.570796326795,8.15)); +#98834 = CARTESIAN_POINT('',(3.191025391152,8.15)); +#98835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98836 = PCURVE('',#91492,#98837); +#98837 = DEFINITIONAL_REPRESENTATION('',(#98838),#98842); +#98838 = CIRCLE('',#98839,0.308574064194); +#98839 = AXIS2_PLACEMENT_2D('',#98840,#98841); +#98840 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#98841 = DIRECTION('',(1.,0.E+000)); +#98842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98843 = ADVANCED_FACE('',(#98844),#98811,.F.); +#98844 = FACE_BOUND('',#98845,.T.); +#98845 = EDGE_LOOP('',(#98846,#98875,#98896,#98897)); +#98846 = ORIENTED_EDGE('',*,*,#98847,.F.); +#98847 = EDGE_CURVE('',#98848,#98850,#98852,.T.); +#98848 = VERTEX_POINT('',#98849); +#98849 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.530776333563)); +#98850 = VERTEX_POINT('',#98851); +#98851 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.530776333563)); +#98852 = SURFACE_CURVE('',#98853,(#98857,#98864),.PCURVE_S1.); +#98853 = LINE('',#98854,#98855); +#98854 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#98855 = VECTOR('',#98856,1.); +#98856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#98857 = PCURVE('',#98811,#98858); +#98858 = DEFINITIONAL_REPRESENTATION('',(#98859),#98863); +#98859 = LINE('',#98860,#98861); +#98860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98861 = VECTOR('',#98862,1.); +#98862 = DIRECTION('',(0.E+000,-1.)); +#98863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98864 = PCURVE('',#98865,#98870); +#98865 = CYLINDRICAL_SURFACE('',#98866,0.119270391569); +#98866 = AXIS2_PLACEMENT_3D('',#98867,#98868,#98869); +#98867 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#98868 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98869 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98870 = DEFINITIONAL_REPRESENTATION('',(#98871),#98874); +#98871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98872,#98873),.UNSPECIFIED., .F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#96480 = CARTESIAN_POINT('',(4.712388980385,-8.15)); -#96481 = CARTESIAN_POINT('',(4.712388980385,-8.35)); -#96482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96483 = ORIENTED_EDGE('',*,*,#96484,.T.); -#96484 = EDGE_CURVE('',#96456,#96405,#96485,.T.); -#96485 = SURFACE_CURVE('',#96486,(#96490,#96497),.PCURVE_S1.); -#96486 = LINE('',#96487,#96488); -#96487 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.530776333563)); -#96488 = VECTOR('',#96489,1.); -#96489 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#96490 = PCURVE('',#96419,#96491); -#96491 = DEFINITIONAL_REPRESENTATION('',(#96492),#96496); -#96492 = LINE('',#96493,#96494); -#96493 = CARTESIAN_POINT('',(0.E+000,-8.15)); -#96494 = VECTOR('',#96495,1.); -#96495 = DIRECTION('',(1.,0.E+000)); -#96496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96497 = PCURVE('',#89100,#96498); -#96498 = DEFINITIONAL_REPRESENTATION('',(#96499),#96503); -#96499 = LINE('',#96500,#96501); -#96500 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#96501 = VECTOR('',#96502,1.); -#96502 = DIRECTION('',(-1.,-1.021336205033E-016)); -#96503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96504 = ORIENTED_EDGE('',*,*,#96404,.T.); -#96505 = ORIENTED_EDGE('',*,*,#96506,.F.); -#96506 = EDGE_CURVE('',#96458,#96378,#96507,.T.); -#96507 = SURFACE_CURVE('',#96508,(#96512,#96519),.PCURVE_S1.); -#96508 = LINE('',#96509,#96510); -#96509 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.530776333563)); -#96510 = VECTOR('',#96511,1.); -#96511 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#96512 = PCURVE('',#96419,#96513); -#96513 = DEFINITIONAL_REPRESENTATION('',(#96514),#96518); -#96514 = LINE('',#96515,#96516); -#96515 = CARTESIAN_POINT('',(0.E+000,-8.35)); -#96516 = VECTOR('',#96517,1.); -#96517 = DIRECTION('',(1.,0.E+000)); -#96518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96519 = PCURVE('',#89156,#96520); -#96520 = DEFINITIONAL_REPRESENTATION('',(#96521),#96525); -#96521 = LINE('',#96522,#96523); -#96522 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#96523 = VECTOR('',#96524,1.); -#96524 = DIRECTION('',(1.,-1.021336205033E-016)); -#96525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96526 = ADVANCED_FACE('',(#96527),#96340,.F.); -#96527 = FACE_BOUND('',#96528,.T.); -#96528 = EDGE_LOOP('',(#96529,#96558,#96579,#96580)); -#96529 = ORIENTED_EDGE('',*,*,#96530,.F.); -#96530 = EDGE_CURVE('',#96531,#96533,#96535,.T.); -#96531 = VERTEX_POINT('',#96532); -#96532 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.530776333563)); -#96533 = VERTEX_POINT('',#96534); -#96534 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.530776333563)); -#96535 = SURFACE_CURVE('',#96536,(#96540,#96547),.PCURVE_S1.); -#96536 = LINE('',#96537,#96538); -#96537 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#96538 = VECTOR('',#96539,1.); -#96539 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96540 = PCURVE('',#96340,#96541); -#96541 = DEFINITIONAL_REPRESENTATION('',(#96542),#96546); -#96542 = LINE('',#96543,#96544); -#96543 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96544 = VECTOR('',#96545,1.); -#96545 = DIRECTION('',(0.E+000,1.)); -#96546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96547 = PCURVE('',#96548,#96553); -#96548 = CYLINDRICAL_SURFACE('',#96549,0.2192697516); -#96549 = AXIS2_PLACEMENT_3D('',#96550,#96551,#96552); -#96550 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#96551 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96552 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96553 = DEFINITIONAL_REPRESENTATION('',(#96554),#96557); -#96554 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96555,#96556),.UNSPECIFIED., +#98872 = CARTESIAN_POINT('',(4.712388980385,-8.15)); +#98873 = CARTESIAN_POINT('',(4.712388980385,-8.35)); +#98874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98875 = ORIENTED_EDGE('',*,*,#98876,.T.); +#98876 = EDGE_CURVE('',#98848,#98797,#98877,.T.); +#98877 = SURFACE_CURVE('',#98878,(#98882,#98889),.PCURVE_S1.); +#98878 = LINE('',#98879,#98880); +#98879 = CARTESIAN_POINT('',(1.85,-0.419594812019,0.530776333563)); +#98880 = VECTOR('',#98881,1.); +#98881 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98882 = PCURVE('',#98811,#98883); +#98883 = DEFINITIONAL_REPRESENTATION('',(#98884),#98888); +#98884 = LINE('',#98885,#98886); +#98885 = CARTESIAN_POINT('',(0.E+000,-8.15)); +#98886 = VECTOR('',#98887,1.); +#98887 = DIRECTION('',(1.,0.E+000)); +#98888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98889 = PCURVE('',#91492,#98890); +#98890 = DEFINITIONAL_REPRESENTATION('',(#98891),#98895); +#98891 = LINE('',#98892,#98893); +#98892 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#98893 = VECTOR('',#98894,1.); +#98894 = DIRECTION('',(-1.,-1.021336205033E-016)); +#98895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98896 = ORIENTED_EDGE('',*,*,#98796,.T.); +#98897 = ORIENTED_EDGE('',*,*,#98898,.F.); +#98898 = EDGE_CURVE('',#98850,#98770,#98899,.T.); +#98899 = SURFACE_CURVE('',#98900,(#98904,#98911),.PCURVE_S1.); +#98900 = LINE('',#98901,#98902); +#98901 = CARTESIAN_POINT('',(1.65,-0.419594812019,0.530776333563)); +#98902 = VECTOR('',#98903,1.); +#98903 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98904 = PCURVE('',#98811,#98905); +#98905 = DEFINITIONAL_REPRESENTATION('',(#98906),#98910); +#98906 = LINE('',#98907,#98908); +#98907 = CARTESIAN_POINT('',(0.E+000,-8.35)); +#98908 = VECTOR('',#98909,1.); +#98909 = DIRECTION('',(1.,0.E+000)); +#98910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98911 = PCURVE('',#91548,#98912); +#98912 = DEFINITIONAL_REPRESENTATION('',(#98913),#98917); +#98913 = LINE('',#98914,#98915); +#98914 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#98915 = VECTOR('',#98916,1.); +#98916 = DIRECTION('',(1.,-1.021336205033E-016)); +#98917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98918 = ADVANCED_FACE('',(#98919),#98732,.F.); +#98919 = FACE_BOUND('',#98920,.T.); +#98920 = EDGE_LOOP('',(#98921,#98950,#98971,#98972)); +#98921 = ORIENTED_EDGE('',*,*,#98922,.F.); +#98922 = EDGE_CURVE('',#98923,#98925,#98927,.T.); +#98923 = VERTEX_POINT('',#98924); +#98924 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.530776333563)); +#98925 = VERTEX_POINT('',#98926); +#98926 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.530776333563)); +#98927 = SURFACE_CURVE('',#98928,(#98932,#98939),.PCURVE_S1.); +#98928 = LINE('',#98929,#98930); +#98929 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#98930 = VECTOR('',#98931,1.); +#98931 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98932 = PCURVE('',#98732,#98933); +#98933 = DEFINITIONAL_REPRESENTATION('',(#98934),#98938); +#98934 = LINE('',#98935,#98936); +#98935 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#98936 = VECTOR('',#98937,1.); +#98937 = DIRECTION('',(0.E+000,1.)); +#98938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98939 = PCURVE('',#98940,#98945); +#98940 = CYLINDRICAL_SURFACE('',#98941,0.2192697516); +#98941 = AXIS2_PLACEMENT_3D('',#98942,#98943,#98944); +#98942 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#98943 = DIRECTION('',(1.,0.E+000,0.E+000)); +#98944 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#98945 = DEFINITIONAL_REPRESENTATION('',(#98946),#98949); +#98946 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98947,#98948),.UNSPECIFIED., .F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#96555 = CARTESIAN_POINT('',(4.712388980385,-8.35)); -#96556 = CARTESIAN_POINT('',(4.712388980385,-8.15)); -#96557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96558 = ORIENTED_EDGE('',*,*,#96559,.T.); -#96559 = EDGE_CURVE('',#96531,#96299,#96560,.T.); -#96560 = SURFACE_CURVE('',#96561,(#96565,#96572),.PCURVE_S1.); -#96561 = LINE('',#96562,#96563); -#96562 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.530776333563)); -#96563 = VECTOR('',#96564,1.); -#96564 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#96565 = PCURVE('',#96340,#96566); -#96566 = DEFINITIONAL_REPRESENTATION('',(#96567),#96571); -#96567 = LINE('',#96568,#96569); -#96568 = CARTESIAN_POINT('',(0.E+000,-8.35)); -#96569 = VECTOR('',#96570,1.); -#96570 = DIRECTION('',(-1.,0.E+000)); -#96571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96572 = PCURVE('',#89156,#96573); -#96573 = DEFINITIONAL_REPRESENTATION('',(#96574),#96578); -#96574 = LINE('',#96575,#96576); -#96575 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#96576 = VECTOR('',#96577,1.); -#96577 = DIRECTION('',(1.,-1.021336205033E-016)); -#96578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96579 = ORIENTED_EDGE('',*,*,#96325,.T.); -#96580 = ORIENTED_EDGE('',*,*,#96581,.F.); -#96581 = EDGE_CURVE('',#96533,#96326,#96582,.T.); -#96582 = SURFACE_CURVE('',#96583,(#96587,#96594),.PCURVE_S1.); -#96583 = LINE('',#96584,#96585); -#96584 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.530776333563)); -#96585 = VECTOR('',#96586,1.); -#96586 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#96587 = PCURVE('',#96340,#96588); -#96588 = DEFINITIONAL_REPRESENTATION('',(#96589),#96593); -#96589 = LINE('',#96590,#96591); -#96590 = CARTESIAN_POINT('',(0.E+000,-8.15)); -#96591 = VECTOR('',#96592,1.); -#96592 = DIRECTION('',(-1.,0.E+000)); -#96593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96594 = PCURVE('',#89100,#96595); -#96595 = DEFINITIONAL_REPRESENTATION('',(#96596),#96600); -#96596 = LINE('',#96597,#96598); -#96597 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#96598 = VECTOR('',#96599,1.); -#96599 = DIRECTION('',(-1.,-1.021336205033E-016)); -#96600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96601 = ADVANCED_FACE('',(#96602),#96473,.F.); -#96602 = FACE_BOUND('',#96603,.F.); -#96603 = EDGE_LOOP('',(#96604,#96631,#96653,#96674)); -#96604 = ORIENTED_EDGE('',*,*,#96605,.F.); -#96605 = EDGE_CURVE('',#96606,#96456,#96608,.T.); -#96606 = VERTEX_POINT('',#96607); -#96607 = CARTESIAN_POINT('',(1.85,-0.303662633502,0.65)); -#96608 = SURFACE_CURVE('',#96609,(#96614,#96620),.PCURVE_S1.); -#96609 = CIRCLE('',#96610,0.119270391569); -#96610 = AXIS2_PLACEMENT_3D('',#96611,#96612,#96613); -#96611 = CARTESIAN_POINT('',(1.85,-0.30032442045,0.530776333563)); -#96612 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96613 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96614 = PCURVE('',#96473,#96615); -#96615 = DEFINITIONAL_REPRESENTATION('',(#96616),#96619); -#96616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96617,#96618),.UNSPECIFIED., +#98947 = CARTESIAN_POINT('',(4.712388980385,-8.35)); +#98948 = CARTESIAN_POINT('',(4.712388980385,-8.15)); +#98949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98950 = ORIENTED_EDGE('',*,*,#98951,.T.); +#98951 = EDGE_CURVE('',#98923,#98691,#98952,.T.); +#98952 = SURFACE_CURVE('',#98953,(#98957,#98964),.PCURVE_S1.); +#98953 = LINE('',#98954,#98955); +#98954 = CARTESIAN_POINT('',(1.65,-0.51959417205,0.530776333563)); +#98955 = VECTOR('',#98956,1.); +#98956 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98957 = PCURVE('',#98732,#98958); +#98958 = DEFINITIONAL_REPRESENTATION('',(#98959),#98963); +#98959 = LINE('',#98960,#98961); +#98960 = CARTESIAN_POINT('',(0.E+000,-8.35)); +#98961 = VECTOR('',#98962,1.); +#98962 = DIRECTION('',(-1.,0.E+000)); +#98963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98964 = PCURVE('',#91548,#98965); +#98965 = DEFINITIONAL_REPRESENTATION('',(#98966),#98970); +#98966 = LINE('',#98967,#98968); +#98967 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#98968 = VECTOR('',#98969,1.); +#98969 = DIRECTION('',(1.,-1.021336205033E-016)); +#98970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98971 = ORIENTED_EDGE('',*,*,#98717,.T.); +#98972 = ORIENTED_EDGE('',*,*,#98973,.F.); +#98973 = EDGE_CURVE('',#98925,#98718,#98974,.T.); +#98974 = SURFACE_CURVE('',#98975,(#98979,#98986),.PCURVE_S1.); +#98975 = LINE('',#98976,#98977); +#98976 = CARTESIAN_POINT('',(1.85,-0.51959417205,0.530776333563)); +#98977 = VECTOR('',#98978,1.); +#98978 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#98979 = PCURVE('',#98732,#98980); +#98980 = DEFINITIONAL_REPRESENTATION('',(#98981),#98985); +#98981 = LINE('',#98982,#98983); +#98982 = CARTESIAN_POINT('',(0.E+000,-8.15)); +#98983 = VECTOR('',#98984,1.); +#98984 = DIRECTION('',(-1.,0.E+000)); +#98985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98986 = PCURVE('',#91492,#98987); +#98987 = DEFINITIONAL_REPRESENTATION('',(#98988),#98992); +#98988 = LINE('',#98989,#98990); +#98989 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#98990 = VECTOR('',#98991,1.); +#98991 = DIRECTION('',(-1.,-1.021336205033E-016)); +#98992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#98993 = ADVANCED_FACE('',(#98994),#98865,.F.); +#98994 = FACE_BOUND('',#98995,.F.); +#98995 = EDGE_LOOP('',(#98996,#99023,#99045,#99066)); +#98996 = ORIENTED_EDGE('',*,*,#98997,.F.); +#98997 = EDGE_CURVE('',#98998,#98848,#99000,.T.); +#98998 = VERTEX_POINT('',#98999); +#98999 = CARTESIAN_POINT('',(1.85,-0.303662633502,0.65)); +#99000 = SURFACE_CURVE('',#99001,(#99006,#99012),.PCURVE_S1.); +#99001 = CIRCLE('',#99002,0.119270391569); +#99002 = AXIS2_PLACEMENT_3D('',#99003,#99004,#99005); +#99003 = CARTESIAN_POINT('',(1.85,-0.30032442045,0.530776333563)); +#99004 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99005 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99006 = PCURVE('',#98865,#99007); +#99007 = DEFINITIONAL_REPRESENTATION('',(#99008),#99011); +#99008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99009,#99010),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#96617 = CARTESIAN_POINT('',(3.169584923929,-8.15)); -#96618 = CARTESIAN_POINT('',(4.712388980385,-8.15)); -#96619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99009 = CARTESIAN_POINT('',(3.169584923929,-8.15)); +#99010 = CARTESIAN_POINT('',(4.712388980385,-8.15)); +#99011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#96620 = PCURVE('',#89100,#96621); -#96621 = DEFINITIONAL_REPRESENTATION('',(#96622),#96630); -#96622 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#96623,#96624,#96625,#96626 - ,#96627,#96628,#96629),.UNSPECIFIED.,.F.,.F.) +#99012 = PCURVE('',#91492,#99013); +#99013 = DEFINITIONAL_REPRESENTATION('',(#99014),#99022); +#99014 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99015,#99016,#99017,#99018 + ,#99019,#99020,#99021),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#96623 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#96624 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#96625 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#96626 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#96627 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#96628 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#96629 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#96630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96631 = ORIENTED_EDGE('',*,*,#96632,.F.); -#96632 = EDGE_CURVE('',#96633,#96606,#96635,.T.); -#96633 = VERTEX_POINT('',#96634); -#96634 = CARTESIAN_POINT('',(1.65,-0.303662633502,0.65)); -#96635 = SURFACE_CURVE('',#96636,(#96640,#96646),.PCURVE_S1.); -#96636 = LINE('',#96637,#96638); -#96637 = CARTESIAN_POINT('',(1.85,-0.303662633502,0.65)); -#96638 = VECTOR('',#96639,1.); -#96639 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96640 = PCURVE('',#96473,#96641); -#96641 = DEFINITIONAL_REPRESENTATION('',(#96642),#96645); -#96642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96643,#96644),.UNSPECIFIED., +#99015 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#99016 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#99017 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#99018 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#99019 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#99020 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#99021 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#99022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99023 = ORIENTED_EDGE('',*,*,#99024,.F.); +#99024 = EDGE_CURVE('',#99025,#98998,#99027,.T.); +#99025 = VERTEX_POINT('',#99026); +#99026 = CARTESIAN_POINT('',(1.65,-0.303662633502,0.65)); +#99027 = SURFACE_CURVE('',#99028,(#99032,#99038),.PCURVE_S1.); +#99028 = LINE('',#99029,#99030); +#99029 = CARTESIAN_POINT('',(1.85,-0.303662633502,0.65)); +#99030 = VECTOR('',#99031,1.); +#99031 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99032 = PCURVE('',#98865,#99033); +#99033 = DEFINITIONAL_REPRESENTATION('',(#99034),#99037); +#99034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99035,#99036),.UNSPECIFIED., .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#96643 = CARTESIAN_POINT('',(3.169584923929,-8.35)); -#96644 = CARTESIAN_POINT('',(3.169584923929,-8.15)); -#96645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96646 = PCURVE('',#89128,#96647); -#96647 = DEFINITIONAL_REPRESENTATION('',(#96648),#96652); -#96648 = LINE('',#96649,#96650); -#96649 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#96650 = VECTOR('',#96651,1.); -#96651 = DIRECTION('',(0.E+000,1.)); -#96652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96653 = ORIENTED_EDGE('',*,*,#96654,.T.); -#96654 = EDGE_CURVE('',#96633,#96458,#96655,.T.); -#96655 = SURFACE_CURVE('',#96656,(#96661,#96667),.PCURVE_S1.); -#96656 = CIRCLE('',#96657,0.119270391569); -#96657 = AXIS2_PLACEMENT_3D('',#96658,#96659,#96660); -#96658 = CARTESIAN_POINT('',(1.65,-0.30032442045,0.530776333563)); -#96659 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96660 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96661 = PCURVE('',#96473,#96662); -#96662 = DEFINITIONAL_REPRESENTATION('',(#96663),#96666); -#96663 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96664,#96665),.UNSPECIFIED., +#99035 = CARTESIAN_POINT('',(3.169584923929,-8.35)); +#99036 = CARTESIAN_POINT('',(3.169584923929,-8.15)); +#99037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99038 = PCURVE('',#91520,#99039); +#99039 = DEFINITIONAL_REPRESENTATION('',(#99040),#99044); +#99040 = LINE('',#99041,#99042); +#99041 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#99042 = VECTOR('',#99043,1.); +#99043 = DIRECTION('',(0.E+000,1.)); +#99044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99045 = ORIENTED_EDGE('',*,*,#99046,.T.); +#99046 = EDGE_CURVE('',#99025,#98850,#99047,.T.); +#99047 = SURFACE_CURVE('',#99048,(#99053,#99059),.PCURVE_S1.); +#99048 = CIRCLE('',#99049,0.119270391569); +#99049 = AXIS2_PLACEMENT_3D('',#99050,#99051,#99052); +#99050 = CARTESIAN_POINT('',(1.65,-0.30032442045,0.530776333563)); +#99051 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99052 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99053 = PCURVE('',#98865,#99054); +#99054 = DEFINITIONAL_REPRESENTATION('',(#99055),#99058); +#99055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99056,#99057),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#96664 = CARTESIAN_POINT('',(3.169584923929,-8.35)); -#96665 = CARTESIAN_POINT('',(4.712388980385,-8.35)); -#96666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96667 = PCURVE('',#89156,#96668); -#96668 = DEFINITIONAL_REPRESENTATION('',(#96669),#96673); -#96669 = CIRCLE('',#96670,0.119270391569); -#96670 = AXIS2_PLACEMENT_2D('',#96671,#96672); -#96671 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#96672 = DIRECTION('',(1.,0.E+000)); -#96673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96674 = ORIENTED_EDGE('',*,*,#96455,.F.); -#96675 = ADVANCED_FACE('',(#96676),#96548,.T.); -#96676 = FACE_BOUND('',#96677,.T.); -#96677 = EDGE_LOOP('',(#96678,#96701,#96702,#96729)); -#96678 = ORIENTED_EDGE('',*,*,#96679,.T.); -#96679 = EDGE_CURVE('',#96680,#96531,#96682,.T.); -#96680 = VERTEX_POINT('',#96681); -#96681 = CARTESIAN_POINT('',(1.65,-0.304819755875,0.75)); -#96682 = SURFACE_CURVE('',#96683,(#96688,#96694),.PCURVE_S1.); -#96683 = CIRCLE('',#96684,0.2192697516); -#96684 = AXIS2_PLACEMENT_3D('',#96685,#96686,#96687); -#96685 = CARTESIAN_POINT('',(1.65,-0.30032442045,0.530776333563)); -#96686 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96687 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96688 = PCURVE('',#96548,#96689); -#96689 = DEFINITIONAL_REPRESENTATION('',(#96690),#96693); -#96690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96691,#96692),.UNSPECIFIED., +#99056 = CARTESIAN_POINT('',(3.169584923929,-8.35)); +#99057 = CARTESIAN_POINT('',(4.712388980385,-8.35)); +#99058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99059 = PCURVE('',#91548,#99060); +#99060 = DEFINITIONAL_REPRESENTATION('',(#99061),#99065); +#99061 = CIRCLE('',#99062,0.119270391569); +#99062 = AXIS2_PLACEMENT_2D('',#99063,#99064); +#99063 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#99064 = DIRECTION('',(1.,0.E+000)); +#99065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99066 = ORIENTED_EDGE('',*,*,#98847,.F.); +#99067 = ADVANCED_FACE('',(#99068),#98940,.T.); +#99068 = FACE_BOUND('',#99069,.T.); +#99069 = EDGE_LOOP('',(#99070,#99093,#99094,#99121)); +#99070 = ORIENTED_EDGE('',*,*,#99071,.T.); +#99071 = EDGE_CURVE('',#99072,#98923,#99074,.T.); +#99072 = VERTEX_POINT('',#99073); +#99073 = CARTESIAN_POINT('',(1.65,-0.304819755875,0.75)); +#99074 = SURFACE_CURVE('',#99075,(#99080,#99086),.PCURVE_S1.); +#99075 = CIRCLE('',#99076,0.2192697516); +#99076 = AXIS2_PLACEMENT_3D('',#99077,#99078,#99079); +#99077 = CARTESIAN_POINT('',(1.65,-0.30032442045,0.530776333563)); +#99078 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99079 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99080 = PCURVE('',#98940,#99081); +#99081 = DEFINITIONAL_REPRESENTATION('',(#99082),#99085); +#99082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99083,#99084),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#96691 = CARTESIAN_POINT('',(3.162095483347,-8.35)); -#96692 = CARTESIAN_POINT('',(4.712388980385,-8.35)); -#96693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96694 = PCURVE('',#89156,#96695); -#96695 = DEFINITIONAL_REPRESENTATION('',(#96696),#96700); -#96696 = CIRCLE('',#96697,0.2192697516); -#96697 = AXIS2_PLACEMENT_2D('',#96698,#96699); -#96698 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#96699 = DIRECTION('',(1.,0.E+000)); -#96700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96701 = ORIENTED_EDGE('',*,*,#96530,.T.); -#96702 = ORIENTED_EDGE('',*,*,#96703,.F.); -#96703 = EDGE_CURVE('',#96704,#96533,#96706,.T.); -#96704 = VERTEX_POINT('',#96705); -#96705 = CARTESIAN_POINT('',(1.85,-0.304819755875,0.75)); -#96706 = SURFACE_CURVE('',#96707,(#96712,#96718),.PCURVE_S1.); -#96707 = CIRCLE('',#96708,0.2192697516); -#96708 = AXIS2_PLACEMENT_3D('',#96709,#96710,#96711); -#96709 = CARTESIAN_POINT('',(1.85,-0.30032442045,0.530776333563)); -#96710 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96711 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#96712 = PCURVE('',#96548,#96713); -#96713 = DEFINITIONAL_REPRESENTATION('',(#96714),#96717); -#96714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96715,#96716),.UNSPECIFIED., +#99083 = CARTESIAN_POINT('',(3.162095483347,-8.35)); +#99084 = CARTESIAN_POINT('',(4.712388980385,-8.35)); +#99085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99086 = PCURVE('',#91548,#99087); +#99087 = DEFINITIONAL_REPRESENTATION('',(#99088),#99092); +#99088 = CIRCLE('',#99089,0.2192697516); +#99089 = AXIS2_PLACEMENT_2D('',#99090,#99091); +#99090 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#99091 = DIRECTION('',(1.,0.E+000)); +#99092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99093 = ORIENTED_EDGE('',*,*,#98922,.T.); +#99094 = ORIENTED_EDGE('',*,*,#99095,.F.); +#99095 = EDGE_CURVE('',#99096,#98925,#99098,.T.); +#99096 = VERTEX_POINT('',#99097); +#99097 = CARTESIAN_POINT('',(1.85,-0.304819755875,0.75)); +#99098 = SURFACE_CURVE('',#99099,(#99104,#99110),.PCURVE_S1.); +#99099 = CIRCLE('',#99100,0.2192697516); +#99100 = AXIS2_PLACEMENT_3D('',#99101,#99102,#99103); +#99101 = CARTESIAN_POINT('',(1.85,-0.30032442045,0.530776333563)); +#99102 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99103 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99104 = PCURVE('',#98940,#99105); +#99105 = DEFINITIONAL_REPRESENTATION('',(#99106),#99109); +#99106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99107,#99108),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#96715 = CARTESIAN_POINT('',(3.162095483347,-8.15)); -#96716 = CARTESIAN_POINT('',(4.712388980385,-8.15)); -#96717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99107 = CARTESIAN_POINT('',(3.162095483347,-8.15)); +#99108 = CARTESIAN_POINT('',(4.712388980385,-8.15)); +#99109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#96718 = PCURVE('',#89100,#96719); -#96719 = DEFINITIONAL_REPRESENTATION('',(#96720),#96728); -#96720 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#96721,#96722,#96723,#96724 - ,#96725,#96726,#96727),.UNSPECIFIED.,.F.,.F.) +#99110 = PCURVE('',#91492,#99111); +#99111 = DEFINITIONAL_REPRESENTATION('',(#99112),#99120); +#99112 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99113,#99114,#99115,#99116 + ,#99117,#99118,#99119),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#96721 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#96722 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#96723 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#96724 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#96725 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#96726 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#96727 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#96728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96729 = ORIENTED_EDGE('',*,*,#96730,.T.); -#96730 = EDGE_CURVE('',#96704,#96680,#96731,.T.); -#96731 = SURFACE_CURVE('',#96732,(#96736,#96742),.PCURVE_S1.); -#96732 = LINE('',#96733,#96734); -#96733 = CARTESIAN_POINT('',(1.85,-0.304819755875,0.75)); -#96734 = VECTOR('',#96735,1.); -#96735 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#96736 = PCURVE('',#96548,#96737); -#96737 = DEFINITIONAL_REPRESENTATION('',(#96738),#96741); -#96738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#96739,#96740),.UNSPECIFIED., +#99113 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#99114 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#99115 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#99116 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#99117 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#99118 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#99119 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#99120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99121 = ORIENTED_EDGE('',*,*,#99122,.T.); +#99122 = EDGE_CURVE('',#99096,#99072,#99123,.T.); +#99123 = SURFACE_CURVE('',#99124,(#99128,#99134),.PCURVE_S1.); +#99124 = LINE('',#99125,#99126); +#99125 = CARTESIAN_POINT('',(1.85,-0.304819755875,0.75)); +#99126 = VECTOR('',#99127,1.); +#99127 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99128 = PCURVE('',#98940,#99129); +#99129 = DEFINITIONAL_REPRESENTATION('',(#99130),#99133); +#99130 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99131,#99132),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#96739 = CARTESIAN_POINT('',(3.162095483347,-8.15)); -#96740 = CARTESIAN_POINT('',(3.162095483347,-8.35)); -#96741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96742 = PCURVE('',#89182,#96743); -#96743 = DEFINITIONAL_REPRESENTATION('',(#96744),#96748); -#96744 = LINE('',#96745,#96746); -#96745 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#96746 = VECTOR('',#96747,1.); -#96747 = DIRECTION('',(0.E+000,-1.)); -#96748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96749 = ADVANCED_FACE('',(#96750),#89100,.F.); -#96750 = FACE_BOUND('',#96751,.T.); -#96751 = EDGE_LOOP('',(#96752,#96773,#96774,#96775,#96776,#96777,#96798, - #96799,#96800,#96801,#96802,#96823)); -#96752 = ORIENTED_EDGE('',*,*,#96753,.F.); -#96753 = EDGE_CURVE('',#96704,#89085,#96754,.T.); -#96754 = SURFACE_CURVE('',#96755,(#96759,#96766),.PCURVE_S1.); -#96755 = LINE('',#96756,#96757); -#96756 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.75)); -#96757 = VECTOR('',#96758,1.); -#96758 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#96759 = PCURVE('',#89100,#96760); -#96760 = DEFINITIONAL_REPRESENTATION('',(#96761),#96765); -#96761 = LINE('',#96762,#96763); -#96762 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#96763 = VECTOR('',#96764,1.); -#96764 = DIRECTION('',(3.563627120235E-016,1.)); -#96765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96766 = PCURVE('',#89182,#96767); -#96767 = DEFINITIONAL_REPRESENTATION('',(#96768),#96772); -#96768 = LINE('',#96769,#96770); -#96769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96770 = VECTOR('',#96771,1.); -#96771 = DIRECTION('',(1.,0.E+000)); -#96772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96773 = ORIENTED_EDGE('',*,*,#96703,.T.); -#96774 = ORIENTED_EDGE('',*,*,#96581,.T.); -#96775 = ORIENTED_EDGE('',*,*,#96352,.T.); -#96776 = ORIENTED_EDGE('',*,*,#96142,.T.); -#96777 = ORIENTED_EDGE('',*,*,#96778,.T.); -#96778 = EDGE_CURVE('',#96115,#96196,#96779,.T.); -#96779 = SURFACE_CURVE('',#96780,(#96784,#96791),.PCURVE_S1.); -#96780 = LINE('',#96781,#96782); -#96781 = CARTESIAN_POINT('',(1.85,-1.,1.159810404338E-002)); -#96782 = VECTOR('',#96783,1.); -#96783 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#96784 = PCURVE('',#89100,#96785); -#96785 = DEFINITIONAL_REPRESENTATION('',(#96786),#96790); -#96786 = LINE('',#96787,#96788); -#96787 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#96788 = VECTOR('',#96789,1.); -#96789 = DIRECTION('',(-1.,2.101748079665E-016)); -#96790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96791 = PCURVE('',#96130,#96792); -#96792 = DEFINITIONAL_REPRESENTATION('',(#96793),#96797); -#96793 = LINE('',#96794,#96795); -#96794 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); -#96795 = VECTOR('',#96796,1.); -#96796 = DIRECTION('',(1.,0.E+000)); -#96797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96798 = ORIENTED_EDGE('',*,*,#96193,.F.); -#96799 = ORIENTED_EDGE('',*,*,#96431,.F.); -#96800 = ORIENTED_EDGE('',*,*,#96484,.F.); -#96801 = ORIENTED_EDGE('',*,*,#96605,.F.); -#96802 = ORIENTED_EDGE('',*,*,#96803,.T.); -#96803 = EDGE_CURVE('',#96606,#89083,#96804,.T.); -#96804 = SURFACE_CURVE('',#96805,(#96809,#96816),.PCURVE_S1.); -#96805 = LINE('',#96806,#96807); -#96806 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); -#96807 = VECTOR('',#96808,1.); -#96808 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#96809 = PCURVE('',#89100,#96810); -#96810 = DEFINITIONAL_REPRESENTATION('',(#96811),#96815); -#96811 = LINE('',#96812,#96813); -#96812 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96813 = VECTOR('',#96814,1.); -#96814 = DIRECTION('',(3.563627120235E-016,1.)); -#96815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96816 = PCURVE('',#89128,#96817); -#96817 = DEFINITIONAL_REPRESENTATION('',(#96818),#96822); -#96818 = LINE('',#96819,#96820); -#96819 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96820 = VECTOR('',#96821,1.); -#96821 = DIRECTION('',(-1.,0.E+000)); -#96822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96823 = ORIENTED_EDGE('',*,*,#89082,.T.); -#96824 = ADVANCED_FACE('',(#96825),#89182,.F.); -#96825 = FACE_BOUND('',#96826,.T.); -#96826 = EDGE_LOOP('',(#96827,#96828,#96829,#96830)); -#96827 = ORIENTED_EDGE('',*,*,#96730,.F.); -#96828 = ORIENTED_EDGE('',*,*,#96753,.T.); -#96829 = ORIENTED_EDGE('',*,*,#89168,.T.); -#96830 = ORIENTED_EDGE('',*,*,#96831,.F.); -#96831 = EDGE_CURVE('',#96680,#89141,#96832,.T.); -#96832 = SURFACE_CURVE('',#96833,(#96837,#96844),.PCURVE_S1.); -#96833 = LINE('',#96834,#96835); -#96834 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.75)); -#96835 = VECTOR('',#96836,1.); -#96836 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#96837 = PCURVE('',#89182,#96838); -#96838 = DEFINITIONAL_REPRESENTATION('',(#96839),#96843); -#96839 = LINE('',#96840,#96841); -#96840 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#96841 = VECTOR('',#96842,1.); -#96842 = DIRECTION('',(1.,0.E+000)); -#96843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96844 = PCURVE('',#89156,#96845); -#96845 = DEFINITIONAL_REPRESENTATION('',(#96846),#96850); -#96846 = LINE('',#96847,#96848); -#96847 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#96848 = VECTOR('',#96849,1.); -#96849 = DIRECTION('',(-3.563627120235E-016,1.)); -#96850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96851 = ADVANCED_FACE('',(#96852),#89156,.F.); -#96852 = FACE_BOUND('',#96853,.T.); -#96853 = EDGE_LOOP('',(#96854,#96875,#96876,#96877,#96878,#96879,#96900, - #96901,#96902,#96903,#96904,#96905)); -#96854 = ORIENTED_EDGE('',*,*,#96855,.F.); -#96855 = EDGE_CURVE('',#96633,#89113,#96856,.T.); -#96856 = SURFACE_CURVE('',#96857,(#96861,#96868),.PCURVE_S1.); -#96857 = LINE('',#96858,#96859); -#96858 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.65)); -#96859 = VECTOR('',#96860,1.); -#96860 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#96861 = PCURVE('',#89156,#96862); -#96862 = DEFINITIONAL_REPRESENTATION('',(#96863),#96867); -#96863 = LINE('',#96864,#96865); -#96864 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#96865 = VECTOR('',#96866,1.); -#96866 = DIRECTION('',(-3.563627120235E-016,1.)); -#96867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96868 = PCURVE('',#89128,#96869); -#96869 = DEFINITIONAL_REPRESENTATION('',(#96870),#96874); -#96870 = LINE('',#96871,#96872); -#96871 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#96872 = VECTOR('',#96873,1.); -#96873 = DIRECTION('',(-1.,0.E+000)); -#96874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96875 = ORIENTED_EDGE('',*,*,#96654,.T.); -#96876 = ORIENTED_EDGE('',*,*,#96506,.T.); -#96877 = ORIENTED_EDGE('',*,*,#96377,.T.); -#96878 = ORIENTED_EDGE('',*,*,#96246,.T.); -#96879 = ORIENTED_EDGE('',*,*,#96880,.T.); -#96880 = EDGE_CURVE('',#96224,#96087,#96881,.T.); -#96881 = SURFACE_CURVE('',#96882,(#96886,#96893),.PCURVE_S1.); -#96882 = LINE('',#96883,#96884); -#96883 = CARTESIAN_POINT('',(1.65,-1.,1.159810404338E-002)); -#96884 = VECTOR('',#96885,1.); -#96885 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#96886 = PCURVE('',#89156,#96887); -#96887 = DEFINITIONAL_REPRESENTATION('',(#96888),#96892); -#96888 = LINE('',#96889,#96890); -#96889 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#96890 = VECTOR('',#96891,1.); -#96891 = DIRECTION('',(-1.,-2.101748079665E-016)); -#96892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96893 = PCURVE('',#96130,#96894); -#96894 = DEFINITIONAL_REPRESENTATION('',(#96895),#96899); -#96895 = LINE('',#96896,#96897); -#96896 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#96897 = VECTOR('',#96898,1.); -#96898 = DIRECTION('',(-1.,0.E+000)); -#96899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96900 = ORIENTED_EDGE('',*,*,#96084,.F.); -#96901 = ORIENTED_EDGE('',*,*,#96298,.F.); -#96902 = ORIENTED_EDGE('',*,*,#96559,.F.); -#96903 = ORIENTED_EDGE('',*,*,#96679,.F.); -#96904 = ORIENTED_EDGE('',*,*,#96831,.T.); -#96905 = ORIENTED_EDGE('',*,*,#89140,.T.); -#96906 = ADVANCED_FACE('',(#96907),#89128,.F.); -#96907 = FACE_BOUND('',#96908,.T.); -#96908 = EDGE_LOOP('',(#96909,#96910,#96911,#96912)); -#96909 = ORIENTED_EDGE('',*,*,#96632,.F.); -#96910 = ORIENTED_EDGE('',*,*,#96855,.T.); -#96911 = ORIENTED_EDGE('',*,*,#89112,.T.); -#96912 = ORIENTED_EDGE('',*,*,#96803,.F.); -#96913 = ADVANCED_FACE('',(#96914),#96130,.T.); -#96914 = FACE_BOUND('',#96915,.T.); -#96915 = EDGE_LOOP('',(#96916,#96917,#96918,#96919)); -#96916 = ORIENTED_EDGE('',*,*,#96880,.F.); -#96917 = ORIENTED_EDGE('',*,*,#96223,.F.); -#96918 = ORIENTED_EDGE('',*,*,#96778,.F.); -#96919 = ORIENTED_EDGE('',*,*,#96114,.F.); -#96920 = ADVANCED_FACE('',(#96921),#96935,.T.); -#96921 = FACE_BOUND('',#96922,.T.); -#96922 = EDGE_LOOP('',(#96923,#96953,#96981,#97004)); -#96923 = ORIENTED_EDGE('',*,*,#96924,.T.); -#96924 = EDGE_CURVE('',#96925,#96927,#96929,.T.); -#96925 = VERTEX_POINT('',#96926); -#96926 = CARTESIAN_POINT('',(2.15,-0.740726081328,-0.208196358798)); -#96927 = VERTEX_POINT('',#96928); -#96928 = CARTESIAN_POINT('',(2.15,-1.,-0.208196358798)); -#96929 = SURFACE_CURVE('',#96930,(#96934,#96946),.PCURVE_S1.); -#96930 = LINE('',#96931,#96932); -#96931 = CARTESIAN_POINT('',(2.15,-0.740726081328,-0.208196358798)); -#96932 = VECTOR('',#96933,1.); -#96933 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96934 = PCURVE('',#96935,#96940); -#96935 = PLANE('',#96936); -#96936 = AXIS2_PLACEMENT_3D('',#96937,#96938,#96939); -#96937 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#96938 = DIRECTION('',(0.E+000,0.E+000,1.)); -#96939 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96940 = DEFINITIONAL_REPRESENTATION('',(#96941),#96945); -#96941 = LINE('',#96942,#96943); -#96942 = CARTESIAN_POINT('',(-7.85,0.E+000)); -#96943 = VECTOR('',#96944,1.); -#96944 = DIRECTION('',(0.E+000,-1.)); -#96945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96946 = PCURVE('',#89607,#96947); -#96947 = DEFINITIONAL_REPRESENTATION('',(#96948),#96952); -#96948 = LINE('',#96949,#96950); -#96949 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#96950 = VECTOR('',#96951,1.); -#96951 = DIRECTION('',(0.E+000,-1.)); -#96952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96953 = ORIENTED_EDGE('',*,*,#96954,.T.); -#96954 = EDGE_CURVE('',#96927,#96955,#96957,.T.); -#96955 = VERTEX_POINT('',#96956); -#96956 = CARTESIAN_POINT('',(2.35,-1.,-0.208196358798)); -#96957 = SURFACE_CURVE('',#96958,(#96962,#96969),.PCURVE_S1.); -#96958 = LINE('',#96959,#96960); -#96959 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#96960 = VECTOR('',#96961,1.); -#96961 = DIRECTION('',(1.,0.E+000,0.E+000)); -#96962 = PCURVE('',#96935,#96963); -#96963 = DEFINITIONAL_REPRESENTATION('',(#96964),#96968); -#96964 = LINE('',#96965,#96966); -#96965 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#96966 = VECTOR('',#96967,1.); -#96967 = DIRECTION('',(1.,0.E+000)); -#96968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96969 = PCURVE('',#96970,#96975); -#96970 = PLANE('',#96971); -#96971 = AXIS2_PLACEMENT_3D('',#96972,#96973,#96974); -#96972 = CARTESIAN_POINT('',(2.25,-1.,-0.258196742327)); -#96973 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#96974 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#96975 = DEFINITIONAL_REPRESENTATION('',(#96976),#96980); -#96976 = LINE('',#96977,#96978); -#96977 = CARTESIAN_POINT('',(-5.000038352949E-002,7.75)); -#96978 = VECTOR('',#96979,1.); -#96979 = DIRECTION('',(0.E+000,1.)); -#96980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96981 = ORIENTED_EDGE('',*,*,#96982,.F.); -#96982 = EDGE_CURVE('',#96983,#96955,#96985,.T.); -#96983 = VERTEX_POINT('',#96984); -#96984 = CARTESIAN_POINT('',(2.35,-0.740726081328,-0.208196358798)); -#96985 = SURFACE_CURVE('',#96986,(#96990,#96997),.PCURVE_S1.); -#96986 = LINE('',#96987,#96988); -#96987 = CARTESIAN_POINT('',(2.35,-0.740726081328,-0.208196358798)); -#96988 = VECTOR('',#96989,1.); -#96989 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#96990 = PCURVE('',#96935,#96991); -#96991 = DEFINITIONAL_REPRESENTATION('',(#96992),#96996); -#96992 = LINE('',#96993,#96994); -#96993 = CARTESIAN_POINT('',(-7.65,0.E+000)); -#96994 = VECTOR('',#96995,1.); -#96995 = DIRECTION('',(0.E+000,-1.)); -#96996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#96997 = PCURVE('',#89551,#96998); -#96998 = DEFINITIONAL_REPRESENTATION('',(#96999),#97003); -#96999 = LINE('',#97000,#97001); -#97000 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#97001 = VECTOR('',#97002,1.); -#97002 = DIRECTION('',(0.E+000,-1.)); -#97003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97004 = ORIENTED_EDGE('',*,*,#97005,.T.); -#97005 = EDGE_CURVE('',#96983,#96925,#97006,.T.); -#97006 = SURFACE_CURVE('',#97007,(#97011,#97018),.PCURVE_S1.); -#97007 = LINE('',#97008,#97009); -#97008 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#97009 = VECTOR('',#97010,1.); -#97010 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97011 = PCURVE('',#96935,#97012); -#97012 = DEFINITIONAL_REPRESENTATION('',(#97013),#97017); -#97013 = LINE('',#97014,#97015); -#97014 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97015 = VECTOR('',#97016,1.); -#97016 = DIRECTION('',(-1.,0.E+000)); -#97017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97018 = PCURVE('',#97019,#97024); -#97019 = CYLINDRICAL_SURFACE('',#97020,0.208574704164); -#97020 = AXIS2_PLACEMENT_3D('',#97021,#97022,#97023); -#97021 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#97022 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97023 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97024 = DEFINITIONAL_REPRESENTATION('',(#97025),#97028); -#97025 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97026,#97027),.UNSPECIFIED., +#99131 = CARTESIAN_POINT('',(3.162095483347,-8.15)); +#99132 = CARTESIAN_POINT('',(3.162095483347,-8.35)); +#99133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99134 = PCURVE('',#91574,#99135); +#99135 = DEFINITIONAL_REPRESENTATION('',(#99136),#99140); +#99136 = LINE('',#99137,#99138); +#99137 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#99138 = VECTOR('',#99139,1.); +#99139 = DIRECTION('',(0.E+000,-1.)); +#99140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99141 = ADVANCED_FACE('',(#99142),#91492,.F.); +#99142 = FACE_BOUND('',#99143,.T.); +#99143 = EDGE_LOOP('',(#99144,#99165,#99166,#99167,#99168,#99169,#99190, + #99191,#99192,#99193,#99194,#99215)); +#99144 = ORIENTED_EDGE('',*,*,#99145,.F.); +#99145 = EDGE_CURVE('',#99096,#91477,#99146,.T.); +#99146 = SURFACE_CURVE('',#99147,(#99151,#99158),.PCURVE_S1.); +#99147 = LINE('',#99148,#99149); +#99148 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.75)); +#99149 = VECTOR('',#99150,1.); +#99150 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#99151 = PCURVE('',#91492,#99152); +#99152 = DEFINITIONAL_REPRESENTATION('',(#99153),#99157); +#99153 = LINE('',#99154,#99155); +#99154 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#99155 = VECTOR('',#99156,1.); +#99156 = DIRECTION('',(3.563627120235E-016,1.)); +#99157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99158 = PCURVE('',#91574,#99159); +#99159 = DEFINITIONAL_REPRESENTATION('',(#99160),#99164); +#99160 = LINE('',#99161,#99162); +#99161 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99162 = VECTOR('',#99163,1.); +#99163 = DIRECTION('',(1.,0.E+000)); +#99164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99165 = ORIENTED_EDGE('',*,*,#99095,.T.); +#99166 = ORIENTED_EDGE('',*,*,#98973,.T.); +#99167 = ORIENTED_EDGE('',*,*,#98744,.T.); +#99168 = ORIENTED_EDGE('',*,*,#98534,.T.); +#99169 = ORIENTED_EDGE('',*,*,#99170,.T.); +#99170 = EDGE_CURVE('',#98507,#98588,#99171,.T.); +#99171 = SURFACE_CURVE('',#99172,(#99176,#99183),.PCURVE_S1.); +#99172 = LINE('',#99173,#99174); +#99173 = CARTESIAN_POINT('',(1.85,-1.,1.159810404338E-002)); +#99174 = VECTOR('',#99175,1.); +#99175 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#99176 = PCURVE('',#91492,#99177); +#99177 = DEFINITIONAL_REPRESENTATION('',(#99178),#99182); +#99178 = LINE('',#99179,#99180); +#99179 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#99180 = VECTOR('',#99181,1.); +#99181 = DIRECTION('',(-1.,2.101748079665E-016)); +#99182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99183 = PCURVE('',#98522,#99184); +#99184 = DEFINITIONAL_REPRESENTATION('',(#99185),#99189); +#99185 = LINE('',#99186,#99187); +#99186 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); +#99187 = VECTOR('',#99188,1.); +#99188 = DIRECTION('',(1.,0.E+000)); +#99189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99190 = ORIENTED_EDGE('',*,*,#98585,.F.); +#99191 = ORIENTED_EDGE('',*,*,#98823,.F.); +#99192 = ORIENTED_EDGE('',*,*,#98876,.F.); +#99193 = ORIENTED_EDGE('',*,*,#98997,.F.); +#99194 = ORIENTED_EDGE('',*,*,#99195,.T.); +#99195 = EDGE_CURVE('',#98998,#91475,#99196,.T.); +#99196 = SURFACE_CURVE('',#99197,(#99201,#99208),.PCURVE_S1.); +#99197 = LINE('',#99198,#99199); +#99198 = CARTESIAN_POINT('',(1.85,-0.527847992439,0.65)); +#99199 = VECTOR('',#99200,1.); +#99200 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#99201 = PCURVE('',#91492,#99202); +#99202 = DEFINITIONAL_REPRESENTATION('',(#99203),#99207); +#99203 = LINE('',#99204,#99205); +#99204 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99205 = VECTOR('',#99206,1.); +#99206 = DIRECTION('',(3.563627120235E-016,1.)); +#99207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99208 = PCURVE('',#91520,#99209); +#99209 = DEFINITIONAL_REPRESENTATION('',(#99210),#99214); +#99210 = LINE('',#99211,#99212); +#99211 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99212 = VECTOR('',#99213,1.); +#99213 = DIRECTION('',(-1.,0.E+000)); +#99214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99215 = ORIENTED_EDGE('',*,*,#91474,.T.); +#99216 = ADVANCED_FACE('',(#99217),#91574,.F.); +#99217 = FACE_BOUND('',#99218,.T.); +#99218 = EDGE_LOOP('',(#99219,#99220,#99221,#99222)); +#99219 = ORIENTED_EDGE('',*,*,#99122,.F.); +#99220 = ORIENTED_EDGE('',*,*,#99145,.T.); +#99221 = ORIENTED_EDGE('',*,*,#91560,.T.); +#99222 = ORIENTED_EDGE('',*,*,#99223,.F.); +#99223 = EDGE_CURVE('',#99072,#91533,#99224,.T.); +#99224 = SURFACE_CURVE('',#99225,(#99229,#99236),.PCURVE_S1.); +#99225 = LINE('',#99226,#99227); +#99226 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.75)); +#99227 = VECTOR('',#99228,1.); +#99228 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#99229 = PCURVE('',#91574,#99230); +#99230 = DEFINITIONAL_REPRESENTATION('',(#99231),#99235); +#99231 = LINE('',#99232,#99233); +#99232 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#99233 = VECTOR('',#99234,1.); +#99234 = DIRECTION('',(1.,0.E+000)); +#99235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99236 = PCURVE('',#91548,#99237); +#99237 = DEFINITIONAL_REPRESENTATION('',(#99238),#99242); +#99238 = LINE('',#99239,#99240); +#99239 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#99240 = VECTOR('',#99241,1.); +#99241 = DIRECTION('',(-3.563627120235E-016,1.)); +#99242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99243 = ADVANCED_FACE('',(#99244),#91548,.F.); +#99244 = FACE_BOUND('',#99245,.T.); +#99245 = EDGE_LOOP('',(#99246,#99267,#99268,#99269,#99270,#99271,#99292, + #99293,#99294,#99295,#99296,#99297)); +#99246 = ORIENTED_EDGE('',*,*,#99247,.F.); +#99247 = EDGE_CURVE('',#99025,#91505,#99248,.T.); +#99248 = SURFACE_CURVE('',#99249,(#99253,#99260),.PCURVE_S1.); +#99249 = LINE('',#99250,#99251); +#99250 = CARTESIAN_POINT('',(1.65,-0.527847992439,0.65)); +#99251 = VECTOR('',#99252,1.); +#99252 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#99253 = PCURVE('',#91548,#99254); +#99254 = DEFINITIONAL_REPRESENTATION('',(#99255),#99259); +#99255 = LINE('',#99256,#99257); +#99256 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99257 = VECTOR('',#99258,1.); +#99258 = DIRECTION('',(-3.563627120235E-016,1.)); +#99259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99260 = PCURVE('',#91520,#99261); +#99261 = DEFINITIONAL_REPRESENTATION('',(#99262),#99266); +#99262 = LINE('',#99263,#99264); +#99263 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#99264 = VECTOR('',#99265,1.); +#99265 = DIRECTION('',(-1.,0.E+000)); +#99266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99267 = ORIENTED_EDGE('',*,*,#99046,.T.); +#99268 = ORIENTED_EDGE('',*,*,#98898,.T.); +#99269 = ORIENTED_EDGE('',*,*,#98769,.T.); +#99270 = ORIENTED_EDGE('',*,*,#98638,.T.); +#99271 = ORIENTED_EDGE('',*,*,#99272,.T.); +#99272 = EDGE_CURVE('',#98616,#98479,#99273,.T.); +#99273 = SURFACE_CURVE('',#99274,(#99278,#99285),.PCURVE_S1.); +#99274 = LINE('',#99275,#99276); +#99275 = CARTESIAN_POINT('',(1.65,-1.,1.159810404338E-002)); +#99276 = VECTOR('',#99277,1.); +#99277 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#99278 = PCURVE('',#91548,#99279); +#99279 = DEFINITIONAL_REPRESENTATION('',(#99280),#99284); +#99280 = LINE('',#99281,#99282); +#99281 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#99282 = VECTOR('',#99283,1.); +#99283 = DIRECTION('',(-1.,-2.101748079665E-016)); +#99284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99285 = PCURVE('',#98522,#99286); +#99286 = DEFINITIONAL_REPRESENTATION('',(#99287),#99291); +#99287 = LINE('',#99288,#99289); +#99288 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#99289 = VECTOR('',#99290,1.); +#99290 = DIRECTION('',(-1.,0.E+000)); +#99291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99292 = ORIENTED_EDGE('',*,*,#98476,.F.); +#99293 = ORIENTED_EDGE('',*,*,#98690,.F.); +#99294 = ORIENTED_EDGE('',*,*,#98951,.F.); +#99295 = ORIENTED_EDGE('',*,*,#99071,.F.); +#99296 = ORIENTED_EDGE('',*,*,#99223,.T.); +#99297 = ORIENTED_EDGE('',*,*,#91532,.T.); +#99298 = ADVANCED_FACE('',(#99299),#91520,.F.); +#99299 = FACE_BOUND('',#99300,.T.); +#99300 = EDGE_LOOP('',(#99301,#99302,#99303,#99304)); +#99301 = ORIENTED_EDGE('',*,*,#99024,.F.); +#99302 = ORIENTED_EDGE('',*,*,#99247,.T.); +#99303 = ORIENTED_EDGE('',*,*,#91504,.T.); +#99304 = ORIENTED_EDGE('',*,*,#99195,.F.); +#99305 = ADVANCED_FACE('',(#99306),#98522,.T.); +#99306 = FACE_BOUND('',#99307,.T.); +#99307 = EDGE_LOOP('',(#99308,#99309,#99310,#99311)); +#99308 = ORIENTED_EDGE('',*,*,#99272,.F.); +#99309 = ORIENTED_EDGE('',*,*,#98615,.F.); +#99310 = ORIENTED_EDGE('',*,*,#99170,.F.); +#99311 = ORIENTED_EDGE('',*,*,#98506,.F.); +#99312 = ADVANCED_FACE('',(#99313),#99327,.T.); +#99313 = FACE_BOUND('',#99314,.T.); +#99314 = EDGE_LOOP('',(#99315,#99345,#99373,#99396)); +#99315 = ORIENTED_EDGE('',*,*,#99316,.T.); +#99316 = EDGE_CURVE('',#99317,#99319,#99321,.T.); +#99317 = VERTEX_POINT('',#99318); +#99318 = CARTESIAN_POINT('',(2.15,-0.740726081328,-0.208196358798)); +#99319 = VERTEX_POINT('',#99320); +#99320 = CARTESIAN_POINT('',(2.15,-1.,-0.208196358798)); +#99321 = SURFACE_CURVE('',#99322,(#99326,#99338),.PCURVE_S1.); +#99322 = LINE('',#99323,#99324); +#99323 = CARTESIAN_POINT('',(2.15,-0.740726081328,-0.208196358798)); +#99324 = VECTOR('',#99325,1.); +#99325 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#99326 = PCURVE('',#99327,#99332); +#99327 = PLANE('',#99328); +#99328 = AXIS2_PLACEMENT_3D('',#99329,#99330,#99331); +#99329 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#99330 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99331 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99332 = DEFINITIONAL_REPRESENTATION('',(#99333),#99337); +#99333 = LINE('',#99334,#99335); +#99334 = CARTESIAN_POINT('',(-7.85,0.E+000)); +#99335 = VECTOR('',#99336,1.); +#99336 = DIRECTION('',(0.E+000,-1.)); +#99337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99338 = PCURVE('',#91999,#99339); +#99339 = DEFINITIONAL_REPRESENTATION('',(#99340),#99344); +#99340 = LINE('',#99341,#99342); +#99341 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#99342 = VECTOR('',#99343,1.); +#99343 = DIRECTION('',(0.E+000,-1.)); +#99344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99345 = ORIENTED_EDGE('',*,*,#99346,.T.); +#99346 = EDGE_CURVE('',#99319,#99347,#99349,.T.); +#99347 = VERTEX_POINT('',#99348); +#99348 = CARTESIAN_POINT('',(2.35,-1.,-0.208196358798)); +#99349 = SURFACE_CURVE('',#99350,(#99354,#99361),.PCURVE_S1.); +#99350 = LINE('',#99351,#99352); +#99351 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#99352 = VECTOR('',#99353,1.); +#99353 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99354 = PCURVE('',#99327,#99355); +#99355 = DEFINITIONAL_REPRESENTATION('',(#99356),#99360); +#99356 = LINE('',#99357,#99358); +#99357 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#99358 = VECTOR('',#99359,1.); +#99359 = DIRECTION('',(1.,0.E+000)); +#99360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99361 = PCURVE('',#99362,#99367); +#99362 = PLANE('',#99363); +#99363 = AXIS2_PLACEMENT_3D('',#99364,#99365,#99366); +#99364 = CARTESIAN_POINT('',(2.25,-1.,-0.258196742327)); +#99365 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#99366 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#99367 = DEFINITIONAL_REPRESENTATION('',(#99368),#99372); +#99368 = LINE('',#99369,#99370); +#99369 = CARTESIAN_POINT('',(-5.000038352949E-002,7.75)); +#99370 = VECTOR('',#99371,1.); +#99371 = DIRECTION('',(0.E+000,1.)); +#99372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99373 = ORIENTED_EDGE('',*,*,#99374,.F.); +#99374 = EDGE_CURVE('',#99375,#99347,#99377,.T.); +#99375 = VERTEX_POINT('',#99376); +#99376 = CARTESIAN_POINT('',(2.35,-0.740726081328,-0.208196358798)); +#99377 = SURFACE_CURVE('',#99378,(#99382,#99389),.PCURVE_S1.); +#99378 = LINE('',#99379,#99380); +#99379 = CARTESIAN_POINT('',(2.35,-0.740726081328,-0.208196358798)); +#99380 = VECTOR('',#99381,1.); +#99381 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#99382 = PCURVE('',#99327,#99383); +#99383 = DEFINITIONAL_REPRESENTATION('',(#99384),#99388); +#99384 = LINE('',#99385,#99386); +#99385 = CARTESIAN_POINT('',(-7.65,0.E+000)); +#99386 = VECTOR('',#99387,1.); +#99387 = DIRECTION('',(0.E+000,-1.)); +#99388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99389 = PCURVE('',#91943,#99390); +#99390 = DEFINITIONAL_REPRESENTATION('',(#99391),#99395); +#99391 = LINE('',#99392,#99393); +#99392 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#99393 = VECTOR('',#99394,1.); +#99394 = DIRECTION('',(0.E+000,-1.)); +#99395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99396 = ORIENTED_EDGE('',*,*,#99397,.T.); +#99397 = EDGE_CURVE('',#99375,#99317,#99398,.T.); +#99398 = SURFACE_CURVE('',#99399,(#99403,#99410),.PCURVE_S1.); +#99399 = LINE('',#99400,#99401); +#99400 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#99401 = VECTOR('',#99402,1.); +#99402 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99403 = PCURVE('',#99327,#99404); +#99404 = DEFINITIONAL_REPRESENTATION('',(#99405),#99409); +#99405 = LINE('',#99406,#99407); +#99406 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99407 = VECTOR('',#99408,1.); +#99408 = DIRECTION('',(-1.,0.E+000)); +#99409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99410 = PCURVE('',#99411,#99416); +#99411 = CYLINDRICAL_SURFACE('',#99412,0.208574704164); +#99412 = AXIS2_PLACEMENT_3D('',#99413,#99414,#99415); +#99413 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#99414 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99415 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99416 = DEFINITIONAL_REPRESENTATION('',(#99417),#99420); +#99417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99418,#99419),.UNSPECIFIED., .F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#97026 = CARTESIAN_POINT('',(3.201833915432,7.65)); -#97027 = CARTESIAN_POINT('',(3.201833915432,7.85)); -#97028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97029 = ADVANCED_FACE('',(#97030),#97044,.T.); -#97030 = FACE_BOUND('',#97031,.T.); -#97031 = EDGE_LOOP('',(#97032,#97062,#97085,#97108)); -#97032 = ORIENTED_EDGE('',*,*,#97033,.T.); -#97033 = EDGE_CURVE('',#97034,#97036,#97038,.T.); -#97034 = VERTEX_POINT('',#97035); -#97035 = CARTESIAN_POINT('',(2.35,-0.74341632541,-0.308197125857)); -#97036 = VERTEX_POINT('',#97037); -#97037 = CARTESIAN_POINT('',(2.35,-1.,-0.308197125857)); -#97038 = SURFACE_CURVE('',#97039,(#97043,#97055),.PCURVE_S1.); -#97039 = LINE('',#97040,#97041); -#97040 = CARTESIAN_POINT('',(2.35,-0.74341632541,-0.308197125857)); -#97041 = VECTOR('',#97042,1.); -#97042 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97043 = PCURVE('',#97044,#97049); -#97044 = PLANE('',#97045); -#97045 = AXIS2_PLACEMENT_3D('',#97046,#97047,#97048); -#97046 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#97047 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97048 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97049 = DEFINITIONAL_REPRESENTATION('',(#97050),#97054); -#97050 = LINE('',#97051,#97052); -#97051 = CARTESIAN_POINT('',(7.65,0.E+000)); -#97052 = VECTOR('',#97053,1.); -#97053 = DIRECTION('',(0.E+000,-1.)); -#97054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97055 = PCURVE('',#89551,#97056); -#97056 = DEFINITIONAL_REPRESENTATION('',(#97057),#97061); -#97057 = LINE('',#97058,#97059); -#97058 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#97059 = VECTOR('',#97060,1.); -#97060 = DIRECTION('',(0.E+000,-1.)); -#97061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97062 = ORIENTED_EDGE('',*,*,#97063,.T.); -#97063 = EDGE_CURVE('',#97036,#97064,#97066,.T.); -#97064 = VERTEX_POINT('',#97065); -#97065 = CARTESIAN_POINT('',(2.15,-1.,-0.308197125857)); -#97066 = SURFACE_CURVE('',#97067,(#97071,#97078),.PCURVE_S1.); -#97067 = LINE('',#97068,#97069); -#97068 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#97069 = VECTOR('',#97070,1.); -#97070 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97071 = PCURVE('',#97044,#97072); -#97072 = DEFINITIONAL_REPRESENTATION('',(#97073),#97077); -#97073 = LINE('',#97074,#97075); -#97074 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#97075 = VECTOR('',#97076,1.); -#97076 = DIRECTION('',(1.,0.E+000)); -#97077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97078 = PCURVE('',#96970,#97079); -#97079 = DEFINITIONAL_REPRESENTATION('',(#97080),#97084); -#97080 = LINE('',#97081,#97082); -#97081 = CARTESIAN_POINT('',(5.000038352949E-002,7.75)); -#97082 = VECTOR('',#97083,1.); -#97083 = DIRECTION('',(0.E+000,-1.)); -#97084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97085 = ORIENTED_EDGE('',*,*,#97086,.F.); -#97086 = EDGE_CURVE('',#97087,#97064,#97089,.T.); -#97087 = VERTEX_POINT('',#97088); -#97088 = CARTESIAN_POINT('',(2.15,-0.74341632541,-0.308197125857)); -#97089 = SURFACE_CURVE('',#97090,(#97094,#97101),.PCURVE_S1.); -#97090 = LINE('',#97091,#97092); -#97091 = CARTESIAN_POINT('',(2.15,-0.74341632541,-0.308197125857)); -#97092 = VECTOR('',#97093,1.); -#97093 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97094 = PCURVE('',#97044,#97095); -#97095 = DEFINITIONAL_REPRESENTATION('',(#97096),#97100); -#97096 = LINE('',#97097,#97098); -#97097 = CARTESIAN_POINT('',(7.85,0.E+000)); -#97098 = VECTOR('',#97099,1.); -#97099 = DIRECTION('',(0.E+000,-1.)); -#97100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97101 = PCURVE('',#89607,#97102); -#97102 = DEFINITIONAL_REPRESENTATION('',(#97103),#97107); -#97103 = LINE('',#97104,#97105); -#97104 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#97105 = VECTOR('',#97106,1.); -#97106 = DIRECTION('',(0.E+000,-1.)); -#97107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97108 = ORIENTED_EDGE('',*,*,#97109,.T.); -#97109 = EDGE_CURVE('',#97087,#97034,#97110,.T.); -#97110 = SURFACE_CURVE('',#97111,(#97115,#97122),.PCURVE_S1.); -#97111 = LINE('',#97112,#97113); -#97112 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#97113 = VECTOR('',#97114,1.); -#97114 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97115 = PCURVE('',#97044,#97116); -#97116 = DEFINITIONAL_REPRESENTATION('',(#97117),#97121); -#97117 = LINE('',#97118,#97119); -#97118 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97119 = VECTOR('',#97120,1.); -#97120 = DIRECTION('',(-1.,0.E+000)); -#97121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97122 = PCURVE('',#97123,#97128); -#97123 = CYLINDRICAL_SURFACE('',#97124,0.308574064194); -#97124 = AXIS2_PLACEMENT_3D('',#97125,#97126,#97127); -#97125 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#97126 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97127 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97128 = DEFINITIONAL_REPRESENTATION('',(#97129),#97132); -#97129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97130,#97131),.UNSPECIFIED., +#99418 = CARTESIAN_POINT('',(3.201833915432,7.65)); +#99419 = CARTESIAN_POINT('',(3.201833915432,7.85)); +#99420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99421 = ADVANCED_FACE('',(#99422),#99436,.T.); +#99422 = FACE_BOUND('',#99423,.T.); +#99423 = EDGE_LOOP('',(#99424,#99454,#99477,#99500)); +#99424 = ORIENTED_EDGE('',*,*,#99425,.T.); +#99425 = EDGE_CURVE('',#99426,#99428,#99430,.T.); +#99426 = VERTEX_POINT('',#99427); +#99427 = CARTESIAN_POINT('',(2.35,-0.74341632541,-0.308197125857)); +#99428 = VERTEX_POINT('',#99429); +#99429 = CARTESIAN_POINT('',(2.35,-1.,-0.308197125857)); +#99430 = SURFACE_CURVE('',#99431,(#99435,#99447),.PCURVE_S1.); +#99431 = LINE('',#99432,#99433); +#99432 = CARTESIAN_POINT('',(2.35,-0.74341632541,-0.308197125857)); +#99433 = VECTOR('',#99434,1.); +#99434 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#99435 = PCURVE('',#99436,#99441); +#99436 = PLANE('',#99437); +#99437 = AXIS2_PLACEMENT_3D('',#99438,#99439,#99440); +#99438 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#99439 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99440 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99441 = DEFINITIONAL_REPRESENTATION('',(#99442),#99446); +#99442 = LINE('',#99443,#99444); +#99443 = CARTESIAN_POINT('',(7.65,0.E+000)); +#99444 = VECTOR('',#99445,1.); +#99445 = DIRECTION('',(0.E+000,-1.)); +#99446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99447 = PCURVE('',#91943,#99448); +#99448 = DEFINITIONAL_REPRESENTATION('',(#99449),#99453); +#99449 = LINE('',#99450,#99451); +#99450 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#99451 = VECTOR('',#99452,1.); +#99452 = DIRECTION('',(0.E+000,-1.)); +#99453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99454 = ORIENTED_EDGE('',*,*,#99455,.T.); +#99455 = EDGE_CURVE('',#99428,#99456,#99458,.T.); +#99456 = VERTEX_POINT('',#99457); +#99457 = CARTESIAN_POINT('',(2.15,-1.,-0.308197125857)); +#99458 = SURFACE_CURVE('',#99459,(#99463,#99470),.PCURVE_S1.); +#99459 = LINE('',#99460,#99461); +#99460 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#99461 = VECTOR('',#99462,1.); +#99462 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99463 = PCURVE('',#99436,#99464); +#99464 = DEFINITIONAL_REPRESENTATION('',(#99465),#99469); +#99465 = LINE('',#99466,#99467); +#99466 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#99467 = VECTOR('',#99468,1.); +#99468 = DIRECTION('',(1.,0.E+000)); +#99469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99470 = PCURVE('',#99362,#99471); +#99471 = DEFINITIONAL_REPRESENTATION('',(#99472),#99476); +#99472 = LINE('',#99473,#99474); +#99473 = CARTESIAN_POINT('',(5.000038352949E-002,7.75)); +#99474 = VECTOR('',#99475,1.); +#99475 = DIRECTION('',(0.E+000,-1.)); +#99476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99477 = ORIENTED_EDGE('',*,*,#99478,.F.); +#99478 = EDGE_CURVE('',#99479,#99456,#99481,.T.); +#99479 = VERTEX_POINT('',#99480); +#99480 = CARTESIAN_POINT('',(2.15,-0.74341632541,-0.308197125857)); +#99481 = SURFACE_CURVE('',#99482,(#99486,#99493),.PCURVE_S1.); +#99482 = LINE('',#99483,#99484); +#99483 = CARTESIAN_POINT('',(2.15,-0.74341632541,-0.308197125857)); +#99484 = VECTOR('',#99485,1.); +#99485 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#99486 = PCURVE('',#99436,#99487); +#99487 = DEFINITIONAL_REPRESENTATION('',(#99488),#99492); +#99488 = LINE('',#99489,#99490); +#99489 = CARTESIAN_POINT('',(7.85,0.E+000)); +#99490 = VECTOR('',#99491,1.); +#99491 = DIRECTION('',(0.E+000,-1.)); +#99492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99493 = PCURVE('',#91999,#99494); +#99494 = DEFINITIONAL_REPRESENTATION('',(#99495),#99499); +#99495 = LINE('',#99496,#99497); +#99496 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#99497 = VECTOR('',#99498,1.); +#99498 = DIRECTION('',(0.E+000,-1.)); +#99499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99500 = ORIENTED_EDGE('',*,*,#99501,.T.); +#99501 = EDGE_CURVE('',#99479,#99426,#99502,.T.); +#99502 = SURFACE_CURVE('',#99503,(#99507,#99514),.PCURVE_S1.); +#99503 = LINE('',#99504,#99505); +#99504 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#99505 = VECTOR('',#99506,1.); +#99506 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99507 = PCURVE('',#99436,#99508); +#99508 = DEFINITIONAL_REPRESENTATION('',(#99509),#99513); +#99509 = LINE('',#99510,#99511); +#99510 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99511 = VECTOR('',#99512,1.); +#99512 = DIRECTION('',(-1.,0.E+000)); +#99513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99514 = PCURVE('',#99515,#99520); +#99515 = CYLINDRICAL_SURFACE('',#99516,0.308574064194); +#99516 = AXIS2_PLACEMENT_3D('',#99517,#99518,#99519); +#99517 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#99518 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99519 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99520 = DEFINITIONAL_REPRESENTATION('',(#99521),#99524); +#99521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99522,#99523),.UNSPECIFIED., .F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#97130 = CARTESIAN_POINT('',(3.191025391152,7.85)); -#97131 = CARTESIAN_POINT('',(3.191025391152,7.65)); -#97132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97133 = ADVANCED_FACE('',(#97134),#97019,.F.); -#97134 = FACE_BOUND('',#97135,.F.); -#97135 = EDGE_LOOP('',(#97136,#97137,#97164,#97191)); -#97136 = ORIENTED_EDGE('',*,*,#97005,.T.); -#97137 = ORIENTED_EDGE('',*,*,#97138,.F.); -#97138 = EDGE_CURVE('',#97139,#96925,#97141,.T.); -#97139 = VERTEX_POINT('',#97140); -#97140 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.E+000)); -#97141 = SURFACE_CURVE('',#97142,(#97147,#97153),.PCURVE_S1.); -#97142 = CIRCLE('',#97143,0.208574704164); -#97143 = AXIS2_PLACEMENT_3D('',#97144,#97145,#97146); -#97144 = CARTESIAN_POINT('',(2.15,-0.728168876214,2.640924866458E-017)); -#97145 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97146 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97147 = PCURVE('',#97019,#97148); -#97148 = DEFINITIONAL_REPRESENTATION('',(#97149),#97152); -#97149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97150,#97151),.UNSPECIFIED., +#99522 = CARTESIAN_POINT('',(3.191025391152,7.85)); +#99523 = CARTESIAN_POINT('',(3.191025391152,7.65)); +#99524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99525 = ADVANCED_FACE('',(#99526),#99411,.F.); +#99526 = FACE_BOUND('',#99527,.F.); +#99527 = EDGE_LOOP('',(#99528,#99529,#99556,#99583)); +#99528 = ORIENTED_EDGE('',*,*,#99397,.T.); +#99529 = ORIENTED_EDGE('',*,*,#99530,.F.); +#99530 = EDGE_CURVE('',#99531,#99317,#99533,.T.); +#99531 = VERTEX_POINT('',#99532); +#99532 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.E+000)); +#99533 = SURFACE_CURVE('',#99534,(#99539,#99545),.PCURVE_S1.); +#99534 = CIRCLE('',#99535,0.208574704164); +#99535 = AXIS2_PLACEMENT_3D('',#99536,#99537,#99538); +#99536 = CARTESIAN_POINT('',(2.15,-0.728168876214,2.640924866458E-017)); +#99537 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99538 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99539 = PCURVE('',#99411,#99540); +#99540 = DEFINITIONAL_REPRESENTATION('',(#99541),#99544); +#99541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99542,#99543),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#97150 = CARTESIAN_POINT('',(1.570796326795,7.85)); -#97151 = CARTESIAN_POINT('',(3.201833915432,7.85)); -#97152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99542 = CARTESIAN_POINT('',(1.570796326795,7.85)); +#99543 = CARTESIAN_POINT('',(3.201833915432,7.85)); +#99544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97153 = PCURVE('',#89607,#97154); -#97154 = DEFINITIONAL_REPRESENTATION('',(#97155),#97163); -#97155 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97156,#97157,#97158,#97159 - ,#97160,#97161,#97162),.UNSPECIFIED.,.F.,.F.) +#99545 = PCURVE('',#91999,#99546); +#99546 = DEFINITIONAL_REPRESENTATION('',(#99547),#99555); +#99547 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99548,#99549,#99550,#99551 + ,#99552,#99553,#99554),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#97156 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#97157 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#97158 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#97159 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#97160 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#97161 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#97162 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#97163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97164 = ORIENTED_EDGE('',*,*,#97165,.T.); -#97165 = EDGE_CURVE('',#97139,#97166,#97168,.T.); -#97166 = VERTEX_POINT('',#97167); -#97167 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.E+000)); -#97168 = SURFACE_CURVE('',#97169,(#97173,#97179),.PCURVE_S1.); -#97169 = LINE('',#97170,#97171); -#97170 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#97171 = VECTOR('',#97172,1.); -#97172 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97173 = PCURVE('',#97019,#97174); -#97174 = DEFINITIONAL_REPRESENTATION('',(#97175),#97178); -#97175 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97176,#97177),.UNSPECIFIED., +#99548 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#99549 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#99550 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#99551 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#99552 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#99553 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#99554 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#99555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99556 = ORIENTED_EDGE('',*,*,#99557,.T.); +#99557 = EDGE_CURVE('',#99531,#99558,#99560,.T.); +#99558 = VERTEX_POINT('',#99559); +#99559 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.E+000)); +#99560 = SURFACE_CURVE('',#99561,(#99565,#99571),.PCURVE_S1.); +#99561 = LINE('',#99562,#99563); +#99562 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#99563 = VECTOR('',#99564,1.); +#99564 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99565 = PCURVE('',#99411,#99566); +#99566 = DEFINITIONAL_REPRESENTATION('',(#99567),#99570); +#99567 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99568,#99569),.UNSPECIFIED., .F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#97176 = CARTESIAN_POINT('',(1.570796326795,7.85)); -#97177 = CARTESIAN_POINT('',(1.570796326795,7.65)); -#97178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97179 = PCURVE('',#97180,#97185); -#97180 = PLANE('',#97181); -#97181 = AXIS2_PLACEMENT_3D('',#97182,#97183,#97184); -#97182 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#97183 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#97184 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#97185 = DEFINITIONAL_REPRESENTATION('',(#97186),#97190); -#97186 = LINE('',#97187,#97188); -#97187 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#97188 = VECTOR('',#97189,1.); -#97189 = DIRECTION('',(0.E+000,1.)); -#97190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97191 = ORIENTED_EDGE('',*,*,#97192,.T.); -#97192 = EDGE_CURVE('',#97166,#96983,#97193,.T.); -#97193 = SURFACE_CURVE('',#97194,(#97199,#97205),.PCURVE_S1.); -#97194 = CIRCLE('',#97195,0.208574704164); -#97195 = AXIS2_PLACEMENT_3D('',#97196,#97197,#97198); -#97196 = CARTESIAN_POINT('',(2.35,-0.728168876214,2.640924866458E-017)); -#97197 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97198 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97199 = PCURVE('',#97019,#97200); -#97200 = DEFINITIONAL_REPRESENTATION('',(#97201),#97204); -#97201 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97202,#97203),.UNSPECIFIED., +#99568 = CARTESIAN_POINT('',(1.570796326795,7.85)); +#99569 = CARTESIAN_POINT('',(1.570796326795,7.65)); +#99570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99571 = PCURVE('',#99572,#99577); +#99572 = PLANE('',#99573); +#99573 = AXIS2_PLACEMENT_3D('',#99574,#99575,#99576); +#99574 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#99575 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#99576 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#99577 = DEFINITIONAL_REPRESENTATION('',(#99578),#99582); +#99578 = LINE('',#99579,#99580); +#99579 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#99580 = VECTOR('',#99581,1.); +#99581 = DIRECTION('',(0.E+000,1.)); +#99582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99583 = ORIENTED_EDGE('',*,*,#99584,.T.); +#99584 = EDGE_CURVE('',#99558,#99375,#99585,.T.); +#99585 = SURFACE_CURVE('',#99586,(#99591,#99597),.PCURVE_S1.); +#99586 = CIRCLE('',#99587,0.208574704164); +#99587 = AXIS2_PLACEMENT_3D('',#99588,#99589,#99590); +#99588 = CARTESIAN_POINT('',(2.35,-0.728168876214,2.640924866458E-017)); +#99589 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99590 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99591 = PCURVE('',#99411,#99592); +#99592 = DEFINITIONAL_REPRESENTATION('',(#99593),#99596); +#99593 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99594,#99595),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#97202 = CARTESIAN_POINT('',(1.570796326795,7.65)); -#97203 = CARTESIAN_POINT('',(3.201833915432,7.65)); -#97204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97205 = PCURVE('',#89551,#97206); -#97206 = DEFINITIONAL_REPRESENTATION('',(#97207),#97211); -#97207 = CIRCLE('',#97208,0.208574704164); -#97208 = AXIS2_PLACEMENT_2D('',#97209,#97210); -#97209 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#97210 = DIRECTION('',(1.,0.E+000)); -#97211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97212 = ADVANCED_FACE('',(#97213),#97123,.T.); -#97213 = FACE_BOUND('',#97214,.T.); -#97214 = EDGE_LOOP('',(#97215,#97216,#97243,#97270)); -#97215 = ORIENTED_EDGE('',*,*,#97109,.F.); -#97216 = ORIENTED_EDGE('',*,*,#97217,.F.); -#97217 = EDGE_CURVE('',#97218,#97087,#97220,.T.); -#97218 = VERTEX_POINT('',#97219); -#97219 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.E+000)); -#97220 = SURFACE_CURVE('',#97221,(#97226,#97232),.PCURVE_S1.); -#97221 = CIRCLE('',#97222,0.308574064194); -#97222 = AXIS2_PLACEMENT_3D('',#97223,#97224,#97225); -#97223 = CARTESIAN_POINT('',(2.15,-0.728168876214,2.640924866458E-017)); -#97224 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97225 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97226 = PCURVE('',#97123,#97227); -#97227 = DEFINITIONAL_REPRESENTATION('',(#97228),#97231); -#97228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97229,#97230),.UNSPECIFIED., +#99594 = CARTESIAN_POINT('',(1.570796326795,7.65)); +#99595 = CARTESIAN_POINT('',(3.201833915432,7.65)); +#99596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99597 = PCURVE('',#91943,#99598); +#99598 = DEFINITIONAL_REPRESENTATION('',(#99599),#99603); +#99599 = CIRCLE('',#99600,0.208574704164); +#99600 = AXIS2_PLACEMENT_2D('',#99601,#99602); +#99601 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#99602 = DIRECTION('',(1.,0.E+000)); +#99603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99604 = ADVANCED_FACE('',(#99605),#99515,.T.); +#99605 = FACE_BOUND('',#99606,.T.); +#99606 = EDGE_LOOP('',(#99607,#99608,#99635,#99662)); +#99607 = ORIENTED_EDGE('',*,*,#99501,.F.); +#99608 = ORIENTED_EDGE('',*,*,#99609,.F.); +#99609 = EDGE_CURVE('',#99610,#99479,#99612,.T.); +#99610 = VERTEX_POINT('',#99611); +#99611 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.E+000)); +#99612 = SURFACE_CURVE('',#99613,(#99618,#99624),.PCURVE_S1.); +#99613 = CIRCLE('',#99614,0.308574064194); +#99614 = AXIS2_PLACEMENT_3D('',#99615,#99616,#99617); +#99615 = CARTESIAN_POINT('',(2.15,-0.728168876214,2.640924866458E-017)); +#99616 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99617 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99618 = PCURVE('',#99515,#99619); +#99619 = DEFINITIONAL_REPRESENTATION('',(#99620),#99623); +#99620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99621,#99622),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#97229 = CARTESIAN_POINT('',(1.570796326795,7.85)); -#97230 = CARTESIAN_POINT('',(3.191025391152,7.85)); -#97231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99621 = CARTESIAN_POINT('',(1.570796326795,7.85)); +#99622 = CARTESIAN_POINT('',(3.191025391152,7.85)); +#99623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97232 = PCURVE('',#89607,#97233); -#97233 = DEFINITIONAL_REPRESENTATION('',(#97234),#97242); -#97234 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97235,#97236,#97237,#97238 - ,#97239,#97240,#97241),.UNSPECIFIED.,.T.,.F.) +#99624 = PCURVE('',#91999,#99625); +#99625 = DEFINITIONAL_REPRESENTATION('',(#99626),#99634); +#99626 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99627,#99628,#99629,#99630 + ,#99631,#99632,#99633),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#97235 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#97236 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#97237 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#97238 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#97239 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#97240 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#97241 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#97242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97243 = ORIENTED_EDGE('',*,*,#97244,.F.); -#97244 = EDGE_CURVE('',#97245,#97218,#97247,.T.); -#97245 = VERTEX_POINT('',#97246); -#97246 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.E+000)); -#97247 = SURFACE_CURVE('',#97248,(#97252,#97258),.PCURVE_S1.); -#97248 = LINE('',#97249,#97250); -#97249 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#97250 = VECTOR('',#97251,1.); -#97251 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97252 = PCURVE('',#97123,#97253); -#97253 = DEFINITIONAL_REPRESENTATION('',(#97254),#97257); -#97254 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97255,#97256),.UNSPECIFIED., +#99627 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#99628 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#99629 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#99630 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#99631 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#99632 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#99633 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#99634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99635 = ORIENTED_EDGE('',*,*,#99636,.F.); +#99636 = EDGE_CURVE('',#99637,#99610,#99639,.T.); +#99637 = VERTEX_POINT('',#99638); +#99638 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.E+000)); +#99639 = SURFACE_CURVE('',#99640,(#99644,#99650),.PCURVE_S1.); +#99640 = LINE('',#99641,#99642); +#99641 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#99642 = VECTOR('',#99643,1.); +#99643 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99644 = PCURVE('',#99515,#99645); +#99645 = DEFINITIONAL_REPRESENTATION('',(#99646),#99649); +#99646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99647,#99648),.UNSPECIFIED., .F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#97255 = CARTESIAN_POINT('',(1.570796326795,7.65)); -#97256 = CARTESIAN_POINT('',(1.570796326795,7.85)); -#97257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97258 = PCURVE('',#97259,#97264); -#97259 = PLANE('',#97260); -#97260 = AXIS2_PLACEMENT_3D('',#97261,#97262,#97263); -#97261 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#97262 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#97263 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#97264 = DEFINITIONAL_REPRESENTATION('',(#97265),#97269); -#97265 = LINE('',#97266,#97267); -#97266 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#97267 = VECTOR('',#97268,1.); -#97268 = DIRECTION('',(0.E+000,-1.)); -#97269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97270 = ORIENTED_EDGE('',*,*,#97271,.T.); -#97271 = EDGE_CURVE('',#97245,#97034,#97272,.T.); -#97272 = SURFACE_CURVE('',#97273,(#97278,#97284),.PCURVE_S1.); -#97273 = CIRCLE('',#97274,0.308574064194); -#97274 = AXIS2_PLACEMENT_3D('',#97275,#97276,#97277); -#97275 = CARTESIAN_POINT('',(2.35,-0.728168876214,2.640924866458E-017)); -#97276 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97277 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97278 = PCURVE('',#97123,#97279); -#97279 = DEFINITIONAL_REPRESENTATION('',(#97280),#97283); -#97280 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97281,#97282),.UNSPECIFIED., +#99647 = CARTESIAN_POINT('',(1.570796326795,7.65)); +#99648 = CARTESIAN_POINT('',(1.570796326795,7.85)); +#99649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99650 = PCURVE('',#99651,#99656); +#99651 = PLANE('',#99652); +#99652 = AXIS2_PLACEMENT_3D('',#99653,#99654,#99655); +#99653 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#99654 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#99655 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#99656 = DEFINITIONAL_REPRESENTATION('',(#99657),#99661); +#99657 = LINE('',#99658,#99659); +#99658 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#99659 = VECTOR('',#99660,1.); +#99660 = DIRECTION('',(0.E+000,-1.)); +#99661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99662 = ORIENTED_EDGE('',*,*,#99663,.T.); +#99663 = EDGE_CURVE('',#99637,#99426,#99664,.T.); +#99664 = SURFACE_CURVE('',#99665,(#99670,#99676),.PCURVE_S1.); +#99665 = CIRCLE('',#99666,0.308574064194); +#99666 = AXIS2_PLACEMENT_3D('',#99667,#99668,#99669); +#99667 = CARTESIAN_POINT('',(2.35,-0.728168876214,2.640924866458E-017)); +#99668 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99669 = DIRECTION('',(0.E+000,0.E+000,1.)); +#99670 = PCURVE('',#99515,#99671); +#99671 = DEFINITIONAL_REPRESENTATION('',(#99672),#99675); +#99672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99673,#99674),.UNSPECIFIED., .F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#97281 = CARTESIAN_POINT('',(1.570796326795,7.65)); -#97282 = CARTESIAN_POINT('',(3.191025391152,7.65)); -#97283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99673 = CARTESIAN_POINT('',(1.570796326795,7.65)); +#99674 = CARTESIAN_POINT('',(3.191025391152,7.65)); +#99675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99676 = PCURVE('',#91943,#99677); +#99677 = DEFINITIONAL_REPRESENTATION('',(#99678),#99682); +#99678 = CIRCLE('',#99679,0.308574064194); +#99679 = AXIS2_PLACEMENT_2D('',#99680,#99681); +#99680 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#99681 = DIRECTION('',(1.,0.E+000)); +#99682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99683 = ADVANCED_FACE('',(#99684),#99651,.F.); +#99684 = FACE_BOUND('',#99685,.T.); +#99685 = EDGE_LOOP('',(#99686,#99715,#99736,#99737)); +#99686 = ORIENTED_EDGE('',*,*,#99687,.F.); +#99687 = EDGE_CURVE('',#99688,#99690,#99692,.T.); +#99688 = VERTEX_POINT('',#99689); +#99689 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.530776333563)); +#99690 = VERTEX_POINT('',#99691); +#99691 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.530776333563)); +#99692 = SURFACE_CURVE('',#99693,(#99697,#99704),.PCURVE_S1.); +#99693 = LINE('',#99694,#99695); +#99694 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#99695 = VECTOR('',#99696,1.); +#99696 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99697 = PCURVE('',#99651,#99698); +#99698 = DEFINITIONAL_REPRESENTATION('',(#99699),#99703); +#99699 = LINE('',#99700,#99701); +#99700 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99701 = VECTOR('',#99702,1.); +#99702 = DIRECTION('',(0.E+000,-1.)); +#99703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99704 = PCURVE('',#99705,#99710); +#99705 = CYLINDRICAL_SURFACE('',#99706,0.119270391569); +#99706 = AXIS2_PLACEMENT_3D('',#99707,#99708,#99709); +#99707 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#99708 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99709 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99710 = DEFINITIONAL_REPRESENTATION('',(#99711),#99714); +#99711 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99712,#99713),.UNSPECIFIED., + .F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); +#99712 = CARTESIAN_POINT('',(4.712388980385,-7.65)); +#99713 = CARTESIAN_POINT('',(4.712388980385,-7.85)); +#99714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99715 = ORIENTED_EDGE('',*,*,#99716,.T.); +#99716 = EDGE_CURVE('',#99688,#99637,#99717,.T.); +#99717 = SURFACE_CURVE('',#99718,(#99722,#99729),.PCURVE_S1.); +#99718 = LINE('',#99719,#99720); +#99719 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.530776333563)); +#99720 = VECTOR('',#99721,1.); +#99721 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#99722 = PCURVE('',#99651,#99723); +#99723 = DEFINITIONAL_REPRESENTATION('',(#99724),#99728); +#99724 = LINE('',#99725,#99726); +#99725 = CARTESIAN_POINT('',(0.E+000,-7.65)); +#99726 = VECTOR('',#99727,1.); +#99727 = DIRECTION('',(1.,0.E+000)); +#99728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99729 = PCURVE('',#91943,#99730); +#99730 = DEFINITIONAL_REPRESENTATION('',(#99731),#99735); +#99731 = LINE('',#99732,#99733); +#99732 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#99733 = VECTOR('',#99734,1.); +#99734 = DIRECTION('',(-1.,-1.021336205033E-016)); +#99735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99736 = ORIENTED_EDGE('',*,*,#99636,.T.); +#99737 = ORIENTED_EDGE('',*,*,#99738,.F.); +#99738 = EDGE_CURVE('',#99690,#99610,#99739,.T.); +#99739 = SURFACE_CURVE('',#99740,(#99744,#99751),.PCURVE_S1.); +#99740 = LINE('',#99741,#99742); +#99741 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.530776333563)); +#99742 = VECTOR('',#99743,1.); +#99743 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#99744 = PCURVE('',#99651,#99745); +#99745 = DEFINITIONAL_REPRESENTATION('',(#99746),#99750); +#99746 = LINE('',#99747,#99748); +#99747 = CARTESIAN_POINT('',(0.E+000,-7.85)); +#99748 = VECTOR('',#99749,1.); +#99749 = DIRECTION('',(1.,0.E+000)); +#99750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99751 = PCURVE('',#91999,#99752); +#99752 = DEFINITIONAL_REPRESENTATION('',(#99753),#99757); +#99753 = LINE('',#99754,#99755); +#99754 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#99755 = VECTOR('',#99756,1.); +#99756 = DIRECTION('',(1.,-1.021336205033E-016)); +#99757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99758 = ADVANCED_FACE('',(#99759),#99572,.F.); +#99759 = FACE_BOUND('',#99760,.T.); +#99760 = EDGE_LOOP('',(#99761,#99790,#99811,#99812)); +#99761 = ORIENTED_EDGE('',*,*,#99762,.F.); +#99762 = EDGE_CURVE('',#99763,#99765,#99767,.T.); +#99763 = VERTEX_POINT('',#99764); +#99764 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.530776333563)); +#99765 = VERTEX_POINT('',#99766); +#99766 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.530776333563)); +#99767 = SURFACE_CURVE('',#99768,(#99772,#99779),.PCURVE_S1.); +#99768 = LINE('',#99769,#99770); +#99769 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#99770 = VECTOR('',#99771,1.); +#99771 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99772 = PCURVE('',#99572,#99773); +#99773 = DEFINITIONAL_REPRESENTATION('',(#99774),#99778); +#99774 = LINE('',#99775,#99776); +#99775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#99776 = VECTOR('',#99777,1.); +#99777 = DIRECTION('',(0.E+000,1.)); +#99778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99779 = PCURVE('',#99780,#99785); +#99780 = CYLINDRICAL_SURFACE('',#99781,0.2192697516); +#99781 = AXIS2_PLACEMENT_3D('',#99782,#99783,#99784); +#99782 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#99783 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99784 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99785 = DEFINITIONAL_REPRESENTATION('',(#99786),#99789); +#99786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99787,#99788),.UNSPECIFIED., + .F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); +#99787 = CARTESIAN_POINT('',(4.712388980385,-7.85)); +#99788 = CARTESIAN_POINT('',(4.712388980385,-7.65)); +#99789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97284 = PCURVE('',#89551,#97285); -#97285 = DEFINITIONAL_REPRESENTATION('',(#97286),#97290); -#97286 = CIRCLE('',#97287,0.308574064194); -#97287 = AXIS2_PLACEMENT_2D('',#97288,#97289); -#97288 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#97289 = DIRECTION('',(1.,0.E+000)); -#97290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99790 = ORIENTED_EDGE('',*,*,#99791,.T.); +#99791 = EDGE_CURVE('',#99763,#99531,#99792,.T.); +#99792 = SURFACE_CURVE('',#99793,(#99797,#99804),.PCURVE_S1.); +#99793 = LINE('',#99794,#99795); +#99794 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.530776333563)); +#99795 = VECTOR('',#99796,1.); +#99796 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#99797 = PCURVE('',#99572,#99798); +#99798 = DEFINITIONAL_REPRESENTATION('',(#99799),#99803); +#99799 = LINE('',#99800,#99801); +#99800 = CARTESIAN_POINT('',(0.E+000,-7.85)); +#99801 = VECTOR('',#99802,1.); +#99802 = DIRECTION('',(-1.,0.E+000)); +#99803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97291 = ADVANCED_FACE('',(#97292),#97259,.F.); -#97292 = FACE_BOUND('',#97293,.T.); -#97293 = EDGE_LOOP('',(#97294,#97323,#97344,#97345)); -#97294 = ORIENTED_EDGE('',*,*,#97295,.F.); -#97295 = EDGE_CURVE('',#97296,#97298,#97300,.T.); -#97296 = VERTEX_POINT('',#97297); -#97297 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.530776333563)); -#97298 = VERTEX_POINT('',#97299); -#97299 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.530776333563)); -#97300 = SURFACE_CURVE('',#97301,(#97305,#97312),.PCURVE_S1.); -#97301 = LINE('',#97302,#97303); -#97302 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#97303 = VECTOR('',#97304,1.); -#97304 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97305 = PCURVE('',#97259,#97306); -#97306 = DEFINITIONAL_REPRESENTATION('',(#97307),#97311); -#97307 = LINE('',#97308,#97309); -#97308 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97309 = VECTOR('',#97310,1.); -#97310 = DIRECTION('',(0.E+000,-1.)); -#97311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97312 = PCURVE('',#97313,#97318); -#97313 = CYLINDRICAL_SURFACE('',#97314,0.119270391569); -#97314 = AXIS2_PLACEMENT_3D('',#97315,#97316,#97317); -#97315 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#97316 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97317 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97318 = DEFINITIONAL_REPRESENTATION('',(#97319),#97322); -#97319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97320,#97321),.UNSPECIFIED., - .F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#97320 = CARTESIAN_POINT('',(4.712388980385,-7.65)); -#97321 = CARTESIAN_POINT('',(4.712388980385,-7.85)); -#97322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97323 = ORIENTED_EDGE('',*,*,#97324,.T.); -#97324 = EDGE_CURVE('',#97296,#97245,#97325,.T.); -#97325 = SURFACE_CURVE('',#97326,(#97330,#97337),.PCURVE_S1.); -#97326 = LINE('',#97327,#97328); -#97327 = CARTESIAN_POINT('',(2.35,-0.419594812019,0.530776333563)); -#97328 = VECTOR('',#97329,1.); -#97329 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#97330 = PCURVE('',#97259,#97331); -#97331 = DEFINITIONAL_REPRESENTATION('',(#97332),#97336); -#97332 = LINE('',#97333,#97334); -#97333 = CARTESIAN_POINT('',(0.E+000,-7.65)); -#97334 = VECTOR('',#97335,1.); -#97335 = DIRECTION('',(1.,0.E+000)); -#97336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97337 = PCURVE('',#89551,#97338); -#97338 = DEFINITIONAL_REPRESENTATION('',(#97339),#97343); -#97339 = LINE('',#97340,#97341); -#97340 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#97341 = VECTOR('',#97342,1.); -#97342 = DIRECTION('',(-1.,-1.021336205033E-016)); -#97343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97344 = ORIENTED_EDGE('',*,*,#97244,.T.); -#97345 = ORIENTED_EDGE('',*,*,#97346,.F.); -#97346 = EDGE_CURVE('',#97298,#97218,#97347,.T.); -#97347 = SURFACE_CURVE('',#97348,(#97352,#97359),.PCURVE_S1.); -#97348 = LINE('',#97349,#97350); -#97349 = CARTESIAN_POINT('',(2.15,-0.419594812019,0.530776333563)); -#97350 = VECTOR('',#97351,1.); -#97351 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#97352 = PCURVE('',#97259,#97353); -#97353 = DEFINITIONAL_REPRESENTATION('',(#97354),#97358); -#97354 = LINE('',#97355,#97356); -#97355 = CARTESIAN_POINT('',(0.E+000,-7.85)); -#97356 = VECTOR('',#97357,1.); -#97357 = DIRECTION('',(1.,0.E+000)); -#97358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97359 = PCURVE('',#89607,#97360); -#97360 = DEFINITIONAL_REPRESENTATION('',(#97361),#97365); -#97361 = LINE('',#97362,#97363); -#97362 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#97363 = VECTOR('',#97364,1.); -#97364 = DIRECTION('',(1.,-1.021336205033E-016)); -#97365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97366 = ADVANCED_FACE('',(#97367),#97180,.F.); -#97367 = FACE_BOUND('',#97368,.T.); -#97368 = EDGE_LOOP('',(#97369,#97398,#97419,#97420)); -#97369 = ORIENTED_EDGE('',*,*,#97370,.F.); -#97370 = EDGE_CURVE('',#97371,#97373,#97375,.T.); -#97371 = VERTEX_POINT('',#97372); -#97372 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.530776333563)); -#97373 = VERTEX_POINT('',#97374); -#97374 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.530776333563)); -#97375 = SURFACE_CURVE('',#97376,(#97380,#97387),.PCURVE_S1.); -#97376 = LINE('',#97377,#97378); -#97377 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#97378 = VECTOR('',#97379,1.); -#97379 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97380 = PCURVE('',#97180,#97381); -#97381 = DEFINITIONAL_REPRESENTATION('',(#97382),#97386); -#97382 = LINE('',#97383,#97384); -#97383 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97384 = VECTOR('',#97385,1.); -#97385 = DIRECTION('',(0.E+000,1.)); -#97386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97387 = PCURVE('',#97388,#97393); -#97388 = CYLINDRICAL_SURFACE('',#97389,0.2192697516); -#97389 = AXIS2_PLACEMENT_3D('',#97390,#97391,#97392); -#97390 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#97391 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97392 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97393 = DEFINITIONAL_REPRESENTATION('',(#97394),#97397); -#97394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97395,#97396),.UNSPECIFIED., - .F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#97395 = CARTESIAN_POINT('',(4.712388980385,-7.85)); -#97396 = CARTESIAN_POINT('',(4.712388980385,-7.65)); -#97397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97398 = ORIENTED_EDGE('',*,*,#97399,.T.); -#97399 = EDGE_CURVE('',#97371,#97139,#97400,.T.); -#97400 = SURFACE_CURVE('',#97401,(#97405,#97412),.PCURVE_S1.); -#97401 = LINE('',#97402,#97403); -#97402 = CARTESIAN_POINT('',(2.15,-0.51959417205,0.530776333563)); -#97403 = VECTOR('',#97404,1.); -#97404 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#97405 = PCURVE('',#97180,#97406); -#97406 = DEFINITIONAL_REPRESENTATION('',(#97407),#97411); -#97407 = LINE('',#97408,#97409); -#97408 = CARTESIAN_POINT('',(0.E+000,-7.85)); -#97409 = VECTOR('',#97410,1.); -#97410 = DIRECTION('',(-1.,0.E+000)); -#97411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97412 = PCURVE('',#89607,#97413); -#97413 = DEFINITIONAL_REPRESENTATION('',(#97414),#97418); -#97414 = LINE('',#97415,#97416); -#97415 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#97416 = VECTOR('',#97417,1.); -#97417 = DIRECTION('',(1.,-1.021336205033E-016)); -#97418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97419 = ORIENTED_EDGE('',*,*,#97165,.T.); -#97420 = ORIENTED_EDGE('',*,*,#97421,.F.); -#97421 = EDGE_CURVE('',#97373,#97166,#97422,.T.); -#97422 = SURFACE_CURVE('',#97423,(#97427,#97434),.PCURVE_S1.); -#97423 = LINE('',#97424,#97425); -#97424 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.530776333563)); -#97425 = VECTOR('',#97426,1.); -#97426 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#97427 = PCURVE('',#97180,#97428); -#97428 = DEFINITIONAL_REPRESENTATION('',(#97429),#97433); -#97429 = LINE('',#97430,#97431); -#97430 = CARTESIAN_POINT('',(0.E+000,-7.65)); -#97431 = VECTOR('',#97432,1.); -#97432 = DIRECTION('',(-1.,0.E+000)); -#97433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97434 = PCURVE('',#89551,#97435); -#97435 = DEFINITIONAL_REPRESENTATION('',(#97436),#97440); -#97436 = LINE('',#97437,#97438); -#97437 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#97438 = VECTOR('',#97439,1.); -#97439 = DIRECTION('',(-1.,-1.021336205033E-016)); -#97440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99804 = PCURVE('',#91999,#99805); +#99805 = DEFINITIONAL_REPRESENTATION('',(#99806),#99810); +#99806 = LINE('',#99807,#99808); +#99807 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#99808 = VECTOR('',#99809,1.); +#99809 = DIRECTION('',(1.,-1.021336205033E-016)); +#99810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97441 = ADVANCED_FACE('',(#97442),#97313,.F.); -#97442 = FACE_BOUND('',#97443,.F.); -#97443 = EDGE_LOOP('',(#97444,#97471,#97493,#97514)); -#97444 = ORIENTED_EDGE('',*,*,#97445,.F.); -#97445 = EDGE_CURVE('',#97446,#97296,#97448,.T.); -#97446 = VERTEX_POINT('',#97447); -#97447 = CARTESIAN_POINT('',(2.35,-0.303662633502,0.65)); -#97448 = SURFACE_CURVE('',#97449,(#97454,#97460),.PCURVE_S1.); -#97449 = CIRCLE('',#97450,0.119270391569); -#97450 = AXIS2_PLACEMENT_3D('',#97451,#97452,#97453); -#97451 = CARTESIAN_POINT('',(2.35,-0.30032442045,0.530776333563)); -#97452 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97453 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97454 = PCURVE('',#97313,#97455); -#97455 = DEFINITIONAL_REPRESENTATION('',(#97456),#97459); -#97456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97457,#97458),.UNSPECIFIED., +#99811 = ORIENTED_EDGE('',*,*,#99557,.T.); +#99812 = ORIENTED_EDGE('',*,*,#99813,.F.); +#99813 = EDGE_CURVE('',#99765,#99558,#99814,.T.); +#99814 = SURFACE_CURVE('',#99815,(#99819,#99826),.PCURVE_S1.); +#99815 = LINE('',#99816,#99817); +#99816 = CARTESIAN_POINT('',(2.35,-0.51959417205,0.530776333563)); +#99817 = VECTOR('',#99818,1.); +#99818 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#99819 = PCURVE('',#99572,#99820); +#99820 = DEFINITIONAL_REPRESENTATION('',(#99821),#99825); +#99821 = LINE('',#99822,#99823); +#99822 = CARTESIAN_POINT('',(0.E+000,-7.65)); +#99823 = VECTOR('',#99824,1.); +#99824 = DIRECTION('',(-1.,0.E+000)); +#99825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99826 = PCURVE('',#91943,#99827); +#99827 = DEFINITIONAL_REPRESENTATION('',(#99828),#99832); +#99828 = LINE('',#99829,#99830); +#99829 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#99830 = VECTOR('',#99831,1.); +#99831 = DIRECTION('',(-1.,-1.021336205033E-016)); +#99832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99833 = ADVANCED_FACE('',(#99834),#99705,.F.); +#99834 = FACE_BOUND('',#99835,.F.); +#99835 = EDGE_LOOP('',(#99836,#99863,#99885,#99906)); +#99836 = ORIENTED_EDGE('',*,*,#99837,.F.); +#99837 = EDGE_CURVE('',#99838,#99688,#99840,.T.); +#99838 = VERTEX_POINT('',#99839); +#99839 = CARTESIAN_POINT('',(2.35,-0.303662633502,0.65)); +#99840 = SURFACE_CURVE('',#99841,(#99846,#99852),.PCURVE_S1.); +#99841 = CIRCLE('',#99842,0.119270391569); +#99842 = AXIS2_PLACEMENT_3D('',#99843,#99844,#99845); +#99843 = CARTESIAN_POINT('',(2.35,-0.30032442045,0.530776333563)); +#99844 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99845 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99846 = PCURVE('',#99705,#99847); +#99847 = DEFINITIONAL_REPRESENTATION('',(#99848),#99851); +#99848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99849,#99850),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#97457 = CARTESIAN_POINT('',(3.169584923929,-7.65)); -#97458 = CARTESIAN_POINT('',(4.712388980385,-7.65)); -#97459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99849 = CARTESIAN_POINT('',(3.169584923929,-7.65)); +#99850 = CARTESIAN_POINT('',(4.712388980385,-7.65)); +#99851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97460 = PCURVE('',#89551,#97461); -#97461 = DEFINITIONAL_REPRESENTATION('',(#97462),#97470); -#97462 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97463,#97464,#97465,#97466 - ,#97467,#97468,#97469),.UNSPECIFIED.,.F.,.F.) +#99852 = PCURVE('',#91943,#99853); +#99853 = DEFINITIONAL_REPRESENTATION('',(#99854),#99862); +#99854 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99855,#99856,#99857,#99858 + ,#99859,#99860,#99861),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#97463 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#97464 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#97465 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#97466 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#97467 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#97468 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#97469 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#97470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97471 = ORIENTED_EDGE('',*,*,#97472,.F.); -#97472 = EDGE_CURVE('',#97473,#97446,#97475,.T.); -#97473 = VERTEX_POINT('',#97474); -#97474 = CARTESIAN_POINT('',(2.15,-0.303662633502,0.65)); -#97475 = SURFACE_CURVE('',#97476,(#97480,#97486),.PCURVE_S1.); -#97476 = LINE('',#97477,#97478); -#97477 = CARTESIAN_POINT('',(2.35,-0.303662633502,0.65)); -#97478 = VECTOR('',#97479,1.); -#97479 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97480 = PCURVE('',#97313,#97481); -#97481 = DEFINITIONAL_REPRESENTATION('',(#97482),#97485); -#97482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97483,#97484),.UNSPECIFIED., +#99855 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#99856 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#99857 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#99858 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#99859 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#99860 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#99861 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#99862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99863 = ORIENTED_EDGE('',*,*,#99864,.F.); +#99864 = EDGE_CURVE('',#99865,#99838,#99867,.T.); +#99865 = VERTEX_POINT('',#99866); +#99866 = CARTESIAN_POINT('',(2.15,-0.303662633502,0.65)); +#99867 = SURFACE_CURVE('',#99868,(#99872,#99878),.PCURVE_S1.); +#99868 = LINE('',#99869,#99870); +#99869 = CARTESIAN_POINT('',(2.35,-0.303662633502,0.65)); +#99870 = VECTOR('',#99871,1.); +#99871 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99872 = PCURVE('',#99705,#99873); +#99873 = DEFINITIONAL_REPRESENTATION('',(#99874),#99877); +#99874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99875,#99876),.UNSPECIFIED., .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#97483 = CARTESIAN_POINT('',(3.169584923929,-7.85)); -#97484 = CARTESIAN_POINT('',(3.169584923929,-7.65)); -#97485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97486 = PCURVE('',#89579,#97487); -#97487 = DEFINITIONAL_REPRESENTATION('',(#97488),#97492); -#97488 = LINE('',#97489,#97490); -#97489 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#97490 = VECTOR('',#97491,1.); -#97491 = DIRECTION('',(0.E+000,1.)); -#97492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97493 = ORIENTED_EDGE('',*,*,#97494,.T.); -#97494 = EDGE_CURVE('',#97473,#97298,#97495,.T.); -#97495 = SURFACE_CURVE('',#97496,(#97501,#97507),.PCURVE_S1.); -#97496 = CIRCLE('',#97497,0.119270391569); -#97497 = AXIS2_PLACEMENT_3D('',#97498,#97499,#97500); -#97498 = CARTESIAN_POINT('',(2.15,-0.30032442045,0.530776333563)); -#97499 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97500 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97501 = PCURVE('',#97313,#97502); -#97502 = DEFINITIONAL_REPRESENTATION('',(#97503),#97506); -#97503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97504,#97505),.UNSPECIFIED., +#99875 = CARTESIAN_POINT('',(3.169584923929,-7.85)); +#99876 = CARTESIAN_POINT('',(3.169584923929,-7.65)); +#99877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99878 = PCURVE('',#91971,#99879); +#99879 = DEFINITIONAL_REPRESENTATION('',(#99880),#99884); +#99880 = LINE('',#99881,#99882); +#99881 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#99882 = VECTOR('',#99883,1.); +#99883 = DIRECTION('',(0.E+000,1.)); +#99884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99885 = ORIENTED_EDGE('',*,*,#99886,.T.); +#99886 = EDGE_CURVE('',#99865,#99690,#99887,.T.); +#99887 = SURFACE_CURVE('',#99888,(#99893,#99899),.PCURVE_S1.); +#99888 = CIRCLE('',#99889,0.119270391569); +#99889 = AXIS2_PLACEMENT_3D('',#99890,#99891,#99892); +#99890 = CARTESIAN_POINT('',(2.15,-0.30032442045,0.530776333563)); +#99891 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99892 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99893 = PCURVE('',#99705,#99894); +#99894 = DEFINITIONAL_REPRESENTATION('',(#99895),#99898); +#99895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99896,#99897),.UNSPECIFIED., .F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#97504 = CARTESIAN_POINT('',(3.169584923929,-7.85)); -#97505 = CARTESIAN_POINT('',(4.712388980385,-7.85)); -#97506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97507 = PCURVE('',#89607,#97508); -#97508 = DEFINITIONAL_REPRESENTATION('',(#97509),#97513); -#97509 = CIRCLE('',#97510,0.119270391569); -#97510 = AXIS2_PLACEMENT_2D('',#97511,#97512); -#97511 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#97512 = DIRECTION('',(1.,0.E+000)); -#97513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97514 = ORIENTED_EDGE('',*,*,#97295,.F.); -#97515 = ADVANCED_FACE('',(#97516),#97388,.T.); -#97516 = FACE_BOUND('',#97517,.T.); -#97517 = EDGE_LOOP('',(#97518,#97541,#97542,#97569)); -#97518 = ORIENTED_EDGE('',*,*,#97519,.T.); -#97519 = EDGE_CURVE('',#97520,#97371,#97522,.T.); -#97520 = VERTEX_POINT('',#97521); -#97521 = CARTESIAN_POINT('',(2.15,-0.304819755875,0.75)); -#97522 = SURFACE_CURVE('',#97523,(#97528,#97534),.PCURVE_S1.); -#97523 = CIRCLE('',#97524,0.2192697516); -#97524 = AXIS2_PLACEMENT_3D('',#97525,#97526,#97527); -#97525 = CARTESIAN_POINT('',(2.15,-0.30032442045,0.530776333563)); -#97526 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97527 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97528 = PCURVE('',#97388,#97529); -#97529 = DEFINITIONAL_REPRESENTATION('',(#97530),#97533); -#97530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97531,#97532),.UNSPECIFIED., +#99896 = CARTESIAN_POINT('',(3.169584923929,-7.85)); +#99897 = CARTESIAN_POINT('',(4.712388980385,-7.85)); +#99898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99899 = PCURVE('',#91999,#99900); +#99900 = DEFINITIONAL_REPRESENTATION('',(#99901),#99905); +#99901 = CIRCLE('',#99902,0.119270391569); +#99902 = AXIS2_PLACEMENT_2D('',#99903,#99904); +#99903 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#99904 = DIRECTION('',(1.,0.E+000)); +#99905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99906 = ORIENTED_EDGE('',*,*,#99687,.F.); +#99907 = ADVANCED_FACE('',(#99908),#99780,.T.); +#99908 = FACE_BOUND('',#99909,.T.); +#99909 = EDGE_LOOP('',(#99910,#99933,#99934,#99961)); +#99910 = ORIENTED_EDGE('',*,*,#99911,.T.); +#99911 = EDGE_CURVE('',#99912,#99763,#99914,.T.); +#99912 = VERTEX_POINT('',#99913); +#99913 = CARTESIAN_POINT('',(2.15,-0.304819755875,0.75)); +#99914 = SURFACE_CURVE('',#99915,(#99920,#99926),.PCURVE_S1.); +#99915 = CIRCLE('',#99916,0.2192697516); +#99916 = AXIS2_PLACEMENT_3D('',#99917,#99918,#99919); +#99917 = CARTESIAN_POINT('',(2.15,-0.30032442045,0.530776333563)); +#99918 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99919 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99920 = PCURVE('',#99780,#99921); +#99921 = DEFINITIONAL_REPRESENTATION('',(#99922),#99925); +#99922 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99923,#99924),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#97531 = CARTESIAN_POINT('',(3.162095483347,-7.85)); -#97532 = CARTESIAN_POINT('',(4.712388980385,-7.85)); -#97533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97534 = PCURVE('',#89607,#97535); -#97535 = DEFINITIONAL_REPRESENTATION('',(#97536),#97540); -#97536 = CIRCLE('',#97537,0.2192697516); -#97537 = AXIS2_PLACEMENT_2D('',#97538,#97539); -#97538 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#97539 = DIRECTION('',(1.,0.E+000)); -#97540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97541 = ORIENTED_EDGE('',*,*,#97370,.T.); -#97542 = ORIENTED_EDGE('',*,*,#97543,.F.); -#97543 = EDGE_CURVE('',#97544,#97373,#97546,.T.); -#97544 = VERTEX_POINT('',#97545); -#97545 = CARTESIAN_POINT('',(2.35,-0.304819755875,0.75)); -#97546 = SURFACE_CURVE('',#97547,(#97552,#97558),.PCURVE_S1.); -#97547 = CIRCLE('',#97548,0.2192697516); -#97548 = AXIS2_PLACEMENT_3D('',#97549,#97550,#97551); -#97549 = CARTESIAN_POINT('',(2.35,-0.30032442045,0.530776333563)); -#97550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97551 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97552 = PCURVE('',#97388,#97553); -#97553 = DEFINITIONAL_REPRESENTATION('',(#97554),#97557); -#97554 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97555,#97556),.UNSPECIFIED., +#99923 = CARTESIAN_POINT('',(3.162095483347,-7.85)); +#99924 = CARTESIAN_POINT('',(4.712388980385,-7.85)); +#99925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99926 = PCURVE('',#91999,#99927); +#99927 = DEFINITIONAL_REPRESENTATION('',(#99928),#99932); +#99928 = CIRCLE('',#99929,0.2192697516); +#99929 = AXIS2_PLACEMENT_2D('',#99930,#99931); +#99930 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#99931 = DIRECTION('',(1.,0.E+000)); +#99932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99933 = ORIENTED_EDGE('',*,*,#99762,.T.); +#99934 = ORIENTED_EDGE('',*,*,#99935,.F.); +#99935 = EDGE_CURVE('',#99936,#99765,#99938,.T.); +#99936 = VERTEX_POINT('',#99937); +#99937 = CARTESIAN_POINT('',(2.35,-0.304819755875,0.75)); +#99938 = SURFACE_CURVE('',#99939,(#99944,#99950),.PCURVE_S1.); +#99939 = CIRCLE('',#99940,0.2192697516); +#99940 = AXIS2_PLACEMENT_3D('',#99941,#99942,#99943); +#99941 = CARTESIAN_POINT('',(2.35,-0.30032442045,0.530776333563)); +#99942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#99943 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#99944 = PCURVE('',#99780,#99945); +#99945 = DEFINITIONAL_REPRESENTATION('',(#99946),#99949); +#99946 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99947,#99948),.UNSPECIFIED., .F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#97555 = CARTESIAN_POINT('',(3.162095483347,-7.65)); -#97556 = CARTESIAN_POINT('',(4.712388980385,-7.65)); -#97557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#99947 = CARTESIAN_POINT('',(3.162095483347,-7.65)); +#99948 = CARTESIAN_POINT('',(4.712388980385,-7.65)); +#99949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97558 = PCURVE('',#89551,#97559); -#97559 = DEFINITIONAL_REPRESENTATION('',(#97560),#97568); -#97560 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97561,#97562,#97563,#97564 - ,#97565,#97566,#97567),.UNSPECIFIED.,.T.,.F.) +#99950 = PCURVE('',#91943,#99951); +#99951 = DEFINITIONAL_REPRESENTATION('',(#99952),#99960); +#99952 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99953,#99954,#99955,#99956 + ,#99957,#99958,#99959),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#97561 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#97562 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#97563 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#97564 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#97565 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#97566 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#97567 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#97568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97569 = ORIENTED_EDGE('',*,*,#97570,.T.); -#97570 = EDGE_CURVE('',#97544,#97520,#97571,.T.); -#97571 = SURFACE_CURVE('',#97572,(#97576,#97582),.PCURVE_S1.); -#97572 = LINE('',#97573,#97574); -#97573 = CARTESIAN_POINT('',(2.35,-0.304819755875,0.75)); -#97574 = VECTOR('',#97575,1.); -#97575 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97576 = PCURVE('',#97388,#97577); -#97577 = DEFINITIONAL_REPRESENTATION('',(#97578),#97581); -#97578 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97579,#97580),.UNSPECIFIED., +#99953 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#99954 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#99955 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#99956 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#99957 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#99958 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#99959 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#99960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99961 = ORIENTED_EDGE('',*,*,#99962,.T.); +#99962 = EDGE_CURVE('',#99936,#99912,#99963,.T.); +#99963 = SURFACE_CURVE('',#99964,(#99968,#99974),.PCURVE_S1.); +#99964 = LINE('',#99965,#99966); +#99965 = CARTESIAN_POINT('',(2.35,-0.304819755875,0.75)); +#99966 = VECTOR('',#99967,1.); +#99967 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#99968 = PCURVE('',#99780,#99969); +#99969 = DEFINITIONAL_REPRESENTATION('',(#99970),#99973); +#99970 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99971,#99972),.UNSPECIFIED., .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#97579 = CARTESIAN_POINT('',(3.162095483347,-7.65)); -#97580 = CARTESIAN_POINT('',(3.162095483347,-7.85)); -#97581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97582 = PCURVE('',#89633,#97583); -#97583 = DEFINITIONAL_REPRESENTATION('',(#97584),#97588); -#97584 = LINE('',#97585,#97586); -#97585 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#97586 = VECTOR('',#97587,1.); -#97587 = DIRECTION('',(0.E+000,-1.)); -#97588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97589 = ADVANCED_FACE('',(#97590),#89551,.F.); -#97590 = FACE_BOUND('',#97591,.T.); -#97591 = EDGE_LOOP('',(#97592,#97613,#97614,#97615,#97616,#97617,#97638, - #97639,#97640,#97641,#97642,#97663)); -#97592 = ORIENTED_EDGE('',*,*,#97593,.F.); -#97593 = EDGE_CURVE('',#97544,#89536,#97594,.T.); -#97594 = SURFACE_CURVE('',#97595,(#97599,#97606),.PCURVE_S1.); -#97595 = LINE('',#97596,#97597); -#97596 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.75)); -#97597 = VECTOR('',#97598,1.); -#97598 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#97599 = PCURVE('',#89551,#97600); -#97600 = DEFINITIONAL_REPRESENTATION('',(#97601),#97605); -#97601 = LINE('',#97602,#97603); -#97602 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#97603 = VECTOR('',#97604,1.); -#97604 = DIRECTION('',(3.563627120235E-016,1.)); -#97605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97606 = PCURVE('',#89633,#97607); -#97607 = DEFINITIONAL_REPRESENTATION('',(#97608),#97612); -#97608 = LINE('',#97609,#97610); -#97609 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97610 = VECTOR('',#97611,1.); -#97611 = DIRECTION('',(1.,0.E+000)); -#97612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97613 = ORIENTED_EDGE('',*,*,#97543,.T.); -#97614 = ORIENTED_EDGE('',*,*,#97421,.T.); -#97615 = ORIENTED_EDGE('',*,*,#97192,.T.); -#97616 = ORIENTED_EDGE('',*,*,#96982,.T.); -#97617 = ORIENTED_EDGE('',*,*,#97618,.T.); -#97618 = EDGE_CURVE('',#96955,#97036,#97619,.T.); -#97619 = SURFACE_CURVE('',#97620,(#97624,#97631),.PCURVE_S1.); -#97620 = LINE('',#97621,#97622); -#97621 = CARTESIAN_POINT('',(2.35,-1.,1.159810404338E-002)); -#97622 = VECTOR('',#97623,1.); -#97623 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#97624 = PCURVE('',#89551,#97625); -#97625 = DEFINITIONAL_REPRESENTATION('',(#97626),#97630); -#97626 = LINE('',#97627,#97628); -#97627 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#97628 = VECTOR('',#97629,1.); -#97629 = DIRECTION('',(-1.,2.101748079665E-016)); -#97630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97631 = PCURVE('',#96970,#97632); -#97632 = DEFINITIONAL_REPRESENTATION('',(#97633),#97637); -#97633 = LINE('',#97634,#97635); -#97634 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#97635 = VECTOR('',#97636,1.); -#97636 = DIRECTION('',(1.,0.E+000)); -#97637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97638 = ORIENTED_EDGE('',*,*,#97033,.F.); -#97639 = ORIENTED_EDGE('',*,*,#97271,.F.); -#97640 = ORIENTED_EDGE('',*,*,#97324,.F.); -#97641 = ORIENTED_EDGE('',*,*,#97445,.F.); -#97642 = ORIENTED_EDGE('',*,*,#97643,.T.); -#97643 = EDGE_CURVE('',#97446,#89534,#97644,.T.); -#97644 = SURFACE_CURVE('',#97645,(#97649,#97656),.PCURVE_S1.); -#97645 = LINE('',#97646,#97647); -#97646 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); -#97647 = VECTOR('',#97648,1.); -#97648 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#97649 = PCURVE('',#89551,#97650); -#97650 = DEFINITIONAL_REPRESENTATION('',(#97651),#97655); -#97651 = LINE('',#97652,#97653); -#97652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97653 = VECTOR('',#97654,1.); -#97654 = DIRECTION('',(3.563627120235E-016,1.)); -#97655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97656 = PCURVE('',#89579,#97657); -#97657 = DEFINITIONAL_REPRESENTATION('',(#97658),#97662); -#97658 = LINE('',#97659,#97660); -#97659 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97660 = VECTOR('',#97661,1.); -#97661 = DIRECTION('',(-1.,0.E+000)); -#97662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97663 = ORIENTED_EDGE('',*,*,#89533,.T.); -#97664 = ADVANCED_FACE('',(#97665),#89633,.F.); -#97665 = FACE_BOUND('',#97666,.T.); -#97666 = EDGE_LOOP('',(#97667,#97668,#97669,#97670)); -#97667 = ORIENTED_EDGE('',*,*,#97570,.F.); -#97668 = ORIENTED_EDGE('',*,*,#97593,.T.); -#97669 = ORIENTED_EDGE('',*,*,#89619,.T.); -#97670 = ORIENTED_EDGE('',*,*,#97671,.F.); -#97671 = EDGE_CURVE('',#97520,#89592,#97672,.T.); -#97672 = SURFACE_CURVE('',#97673,(#97677,#97684),.PCURVE_S1.); -#97673 = LINE('',#97674,#97675); -#97674 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.75)); -#97675 = VECTOR('',#97676,1.); -#97676 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#97677 = PCURVE('',#89633,#97678); -#97678 = DEFINITIONAL_REPRESENTATION('',(#97679),#97683); -#97679 = LINE('',#97680,#97681); -#97680 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#97681 = VECTOR('',#97682,1.); -#97682 = DIRECTION('',(1.,0.E+000)); -#97683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97684 = PCURVE('',#89607,#97685); -#97685 = DEFINITIONAL_REPRESENTATION('',(#97686),#97690); -#97686 = LINE('',#97687,#97688); -#97687 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#97688 = VECTOR('',#97689,1.); -#97689 = DIRECTION('',(-3.563627120235E-016,1.)); -#97690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97691 = ADVANCED_FACE('',(#97692),#89607,.F.); -#97692 = FACE_BOUND('',#97693,.T.); -#97693 = EDGE_LOOP('',(#97694,#97715,#97716,#97717,#97718,#97719,#97740, - #97741,#97742,#97743,#97744,#97745)); -#97694 = ORIENTED_EDGE('',*,*,#97695,.F.); -#97695 = EDGE_CURVE('',#97473,#89564,#97696,.T.); -#97696 = SURFACE_CURVE('',#97697,(#97701,#97708),.PCURVE_S1.); -#97697 = LINE('',#97698,#97699); -#97698 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.65)); -#97699 = VECTOR('',#97700,1.); -#97700 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#97701 = PCURVE('',#89607,#97702); -#97702 = DEFINITIONAL_REPRESENTATION('',(#97703),#97707); -#97703 = LINE('',#97704,#97705); -#97704 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97705 = VECTOR('',#97706,1.); -#97706 = DIRECTION('',(-3.563627120235E-016,1.)); -#97707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97708 = PCURVE('',#89579,#97709); -#97709 = DEFINITIONAL_REPRESENTATION('',(#97710),#97714); -#97710 = LINE('',#97711,#97712); -#97711 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#97712 = VECTOR('',#97713,1.); -#97713 = DIRECTION('',(-1.,0.E+000)); -#97714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97715 = ORIENTED_EDGE('',*,*,#97494,.T.); -#97716 = ORIENTED_EDGE('',*,*,#97346,.T.); -#97717 = ORIENTED_EDGE('',*,*,#97217,.T.); -#97718 = ORIENTED_EDGE('',*,*,#97086,.T.); -#97719 = ORIENTED_EDGE('',*,*,#97720,.T.); -#97720 = EDGE_CURVE('',#97064,#96927,#97721,.T.); -#97721 = SURFACE_CURVE('',#97722,(#97726,#97733),.PCURVE_S1.); -#97722 = LINE('',#97723,#97724); -#97723 = CARTESIAN_POINT('',(2.15,-1.,1.159810404338E-002)); -#97724 = VECTOR('',#97725,1.); -#97725 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#97726 = PCURVE('',#89607,#97727); -#97727 = DEFINITIONAL_REPRESENTATION('',(#97728),#97732); -#97728 = LINE('',#97729,#97730); -#97729 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#97730 = VECTOR('',#97731,1.); -#97731 = DIRECTION('',(-1.,-2.101748079665E-016)); -#97732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97733 = PCURVE('',#96970,#97734); -#97734 = DEFINITIONAL_REPRESENTATION('',(#97735),#97739); -#97735 = LINE('',#97736,#97737); -#97736 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#97737 = VECTOR('',#97738,1.); -#97738 = DIRECTION('',(-1.,0.E+000)); -#97739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97740 = ORIENTED_EDGE('',*,*,#96924,.F.); -#97741 = ORIENTED_EDGE('',*,*,#97138,.F.); -#97742 = ORIENTED_EDGE('',*,*,#97399,.F.); -#97743 = ORIENTED_EDGE('',*,*,#97519,.F.); -#97744 = ORIENTED_EDGE('',*,*,#97671,.T.); -#97745 = ORIENTED_EDGE('',*,*,#89591,.T.); -#97746 = ADVANCED_FACE('',(#97747),#89579,.F.); -#97747 = FACE_BOUND('',#97748,.T.); -#97748 = EDGE_LOOP('',(#97749,#97750,#97751,#97752)); -#97749 = ORIENTED_EDGE('',*,*,#97472,.F.); -#97750 = ORIENTED_EDGE('',*,*,#97695,.T.); -#97751 = ORIENTED_EDGE('',*,*,#89563,.T.); -#97752 = ORIENTED_EDGE('',*,*,#97643,.F.); -#97753 = ADVANCED_FACE('',(#97754),#96970,.T.); -#97754 = FACE_BOUND('',#97755,.T.); -#97755 = EDGE_LOOP('',(#97756,#97757,#97758,#97759)); -#97756 = ORIENTED_EDGE('',*,*,#97720,.F.); -#97757 = ORIENTED_EDGE('',*,*,#97063,.F.); -#97758 = ORIENTED_EDGE('',*,*,#97618,.F.); -#97759 = ORIENTED_EDGE('',*,*,#96954,.F.); -#97760 = ADVANCED_FACE('',(#97761),#97775,.T.); -#97761 = FACE_BOUND('',#97762,.T.); -#97762 = EDGE_LOOP('',(#97763,#97793,#97821,#97844)); -#97763 = ORIENTED_EDGE('',*,*,#97764,.T.); -#97764 = EDGE_CURVE('',#97765,#97767,#97769,.T.); -#97765 = VERTEX_POINT('',#97766); -#97766 = CARTESIAN_POINT('',(2.65,-0.740726081328,-0.208196358798)); -#97767 = VERTEX_POINT('',#97768); -#97768 = CARTESIAN_POINT('',(2.65,-1.,-0.208196358798)); -#97769 = SURFACE_CURVE('',#97770,(#97774,#97786),.PCURVE_S1.); -#97770 = LINE('',#97771,#97772); -#97771 = CARTESIAN_POINT('',(2.65,-0.740726081328,-0.208196358798)); -#97772 = VECTOR('',#97773,1.); -#97773 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97774 = PCURVE('',#97775,#97780); -#97775 = PLANE('',#97776); -#97776 = AXIS2_PLACEMENT_3D('',#97777,#97778,#97779); -#97777 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#97778 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97779 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97780 = DEFINITIONAL_REPRESENTATION('',(#97781),#97785); -#97781 = LINE('',#97782,#97783); -#97782 = CARTESIAN_POINT('',(-7.35,0.E+000)); -#97783 = VECTOR('',#97784,1.); -#97784 = DIRECTION('',(0.E+000,-1.)); -#97785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97786 = PCURVE('',#89042,#97787); -#97787 = DEFINITIONAL_REPRESENTATION('',(#97788),#97792); -#97788 = LINE('',#97789,#97790); -#97789 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#97790 = VECTOR('',#97791,1.); -#97791 = DIRECTION('',(0.E+000,-1.)); -#97792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97793 = ORIENTED_EDGE('',*,*,#97794,.T.); -#97794 = EDGE_CURVE('',#97767,#97795,#97797,.T.); -#97795 = VERTEX_POINT('',#97796); -#97796 = CARTESIAN_POINT('',(2.85,-1.,-0.208196358798)); -#97797 = SURFACE_CURVE('',#97798,(#97802,#97809),.PCURVE_S1.); -#97798 = LINE('',#97799,#97800); -#97799 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#97800 = VECTOR('',#97801,1.); -#97801 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97802 = PCURVE('',#97775,#97803); -#97803 = DEFINITIONAL_REPRESENTATION('',(#97804),#97808); -#97804 = LINE('',#97805,#97806); -#97805 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#97806 = VECTOR('',#97807,1.); -#97807 = DIRECTION('',(1.,0.E+000)); -#97808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97809 = PCURVE('',#97810,#97815); -#97810 = PLANE('',#97811); -#97811 = AXIS2_PLACEMENT_3D('',#97812,#97813,#97814); -#97812 = CARTESIAN_POINT('',(2.75,-1.,-0.258196742327)); -#97813 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#97814 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#97815 = DEFINITIONAL_REPRESENTATION('',(#97816),#97820); -#97816 = LINE('',#97817,#97818); -#97817 = CARTESIAN_POINT('',(-5.000038352949E-002,7.25)); -#97818 = VECTOR('',#97819,1.); -#97819 = DIRECTION('',(0.E+000,1.)); -#97820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97821 = ORIENTED_EDGE('',*,*,#97822,.F.); -#97822 = EDGE_CURVE('',#97823,#97795,#97825,.T.); -#97823 = VERTEX_POINT('',#97824); -#97824 = CARTESIAN_POINT('',(2.85,-0.740726081328,-0.208196358798)); -#97825 = SURFACE_CURVE('',#97826,(#97830,#97837),.PCURVE_S1.); -#97826 = LINE('',#97827,#97828); -#97827 = CARTESIAN_POINT('',(2.85,-0.740726081328,-0.208196358798)); -#97828 = VECTOR('',#97829,1.); -#97829 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97830 = PCURVE('',#97775,#97831); -#97831 = DEFINITIONAL_REPRESENTATION('',(#97832),#97836); -#97832 = LINE('',#97833,#97834); -#97833 = CARTESIAN_POINT('',(-7.15,0.E+000)); -#97834 = VECTOR('',#97835,1.); -#97835 = DIRECTION('',(0.E+000,-1.)); -#97836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97837 = PCURVE('',#88986,#97838); -#97838 = DEFINITIONAL_REPRESENTATION('',(#97839),#97843); -#97839 = LINE('',#97840,#97841); -#97840 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#97841 = VECTOR('',#97842,1.); -#97842 = DIRECTION('',(0.E+000,-1.)); -#97843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97844 = ORIENTED_EDGE('',*,*,#97845,.T.); -#97845 = EDGE_CURVE('',#97823,#97765,#97846,.T.); -#97846 = SURFACE_CURVE('',#97847,(#97851,#97858),.PCURVE_S1.); -#97847 = LINE('',#97848,#97849); -#97848 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#97849 = VECTOR('',#97850,1.); -#97850 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97851 = PCURVE('',#97775,#97852); -#97852 = DEFINITIONAL_REPRESENTATION('',(#97853),#97857); -#97853 = LINE('',#97854,#97855); -#97854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97855 = VECTOR('',#97856,1.); -#97856 = DIRECTION('',(-1.,0.E+000)); -#97857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97858 = PCURVE('',#97859,#97864); -#97859 = CYLINDRICAL_SURFACE('',#97860,0.208574704164); -#97860 = AXIS2_PLACEMENT_3D('',#97861,#97862,#97863); -#97861 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#97862 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97863 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97864 = DEFINITIONAL_REPRESENTATION('',(#97865),#97868); -#97865 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97866,#97867),.UNSPECIFIED., - .F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#97866 = CARTESIAN_POINT('',(3.201833915432,7.15)); -#97867 = CARTESIAN_POINT('',(3.201833915432,7.35)); -#97868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97869 = ADVANCED_FACE('',(#97870),#97884,.T.); -#97870 = FACE_BOUND('',#97871,.T.); -#97871 = EDGE_LOOP('',(#97872,#97902,#97925,#97948)); -#97872 = ORIENTED_EDGE('',*,*,#97873,.T.); -#97873 = EDGE_CURVE('',#97874,#97876,#97878,.T.); -#97874 = VERTEX_POINT('',#97875); -#97875 = CARTESIAN_POINT('',(2.85,-0.74341632541,-0.308197125857)); -#97876 = VERTEX_POINT('',#97877); -#97877 = CARTESIAN_POINT('',(2.85,-1.,-0.308197125857)); -#97878 = SURFACE_CURVE('',#97879,(#97883,#97895),.PCURVE_S1.); -#97879 = LINE('',#97880,#97881); -#97880 = CARTESIAN_POINT('',(2.85,-0.74341632541,-0.308197125857)); -#97881 = VECTOR('',#97882,1.); -#97882 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97883 = PCURVE('',#97884,#97889); -#97884 = PLANE('',#97885); -#97885 = AXIS2_PLACEMENT_3D('',#97886,#97887,#97888); -#97886 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#97887 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#97888 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97889 = DEFINITIONAL_REPRESENTATION('',(#97890),#97894); -#97890 = LINE('',#97891,#97892); -#97891 = CARTESIAN_POINT('',(7.15,0.E+000)); -#97892 = VECTOR('',#97893,1.); -#97893 = DIRECTION('',(0.E+000,-1.)); -#97894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97895 = PCURVE('',#88986,#97896); -#97896 = DEFINITIONAL_REPRESENTATION('',(#97897),#97901); -#97897 = LINE('',#97898,#97899); -#97898 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#97899 = VECTOR('',#97900,1.); -#97900 = DIRECTION('',(0.E+000,-1.)); -#97901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97902 = ORIENTED_EDGE('',*,*,#97903,.T.); -#97903 = EDGE_CURVE('',#97876,#97904,#97906,.T.); -#97904 = VERTEX_POINT('',#97905); -#97905 = CARTESIAN_POINT('',(2.65,-1.,-0.308197125857)); -#97906 = SURFACE_CURVE('',#97907,(#97911,#97918),.PCURVE_S1.); -#97907 = LINE('',#97908,#97909); -#97908 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#97909 = VECTOR('',#97910,1.); -#97910 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97911 = PCURVE('',#97884,#97912); -#97912 = DEFINITIONAL_REPRESENTATION('',(#97913),#97917); -#97913 = LINE('',#97914,#97915); -#97914 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#97915 = VECTOR('',#97916,1.); -#97916 = DIRECTION('',(1.,0.E+000)); -#97917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97918 = PCURVE('',#97810,#97919); -#97919 = DEFINITIONAL_REPRESENTATION('',(#97920),#97924); -#97920 = LINE('',#97921,#97922); -#97921 = CARTESIAN_POINT('',(5.000038352949E-002,7.25)); -#97922 = VECTOR('',#97923,1.); -#97923 = DIRECTION('',(0.E+000,-1.)); -#97924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97925 = ORIENTED_EDGE('',*,*,#97926,.F.); -#97926 = EDGE_CURVE('',#97927,#97904,#97929,.T.); -#97927 = VERTEX_POINT('',#97928); -#97928 = CARTESIAN_POINT('',(2.65,-0.74341632541,-0.308197125857)); -#97929 = SURFACE_CURVE('',#97930,(#97934,#97941),.PCURVE_S1.); -#97930 = LINE('',#97931,#97932); -#97931 = CARTESIAN_POINT('',(2.65,-0.74341632541,-0.308197125857)); -#97932 = VECTOR('',#97933,1.); -#97933 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#97934 = PCURVE('',#97884,#97935); -#97935 = DEFINITIONAL_REPRESENTATION('',(#97936),#97940); -#97936 = LINE('',#97937,#97938); -#97937 = CARTESIAN_POINT('',(7.35,0.E+000)); -#97938 = VECTOR('',#97939,1.); -#97939 = DIRECTION('',(0.E+000,-1.)); -#97940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97941 = PCURVE('',#89042,#97942); -#97942 = DEFINITIONAL_REPRESENTATION('',(#97943),#97947); -#97943 = LINE('',#97944,#97945); -#97944 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#97945 = VECTOR('',#97946,1.); -#97946 = DIRECTION('',(0.E+000,-1.)); -#97947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97948 = ORIENTED_EDGE('',*,*,#97949,.T.); -#97949 = EDGE_CURVE('',#97927,#97874,#97950,.T.); -#97950 = SURFACE_CURVE('',#97951,(#97955,#97962),.PCURVE_S1.); -#97951 = LINE('',#97952,#97953); -#97952 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#97953 = VECTOR('',#97954,1.); -#97954 = DIRECTION('',(1.,0.E+000,0.E+000)); -#97955 = PCURVE('',#97884,#97956); -#97956 = DEFINITIONAL_REPRESENTATION('',(#97957),#97961); -#97957 = LINE('',#97958,#97959); -#97958 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#97959 = VECTOR('',#97960,1.); -#97960 = DIRECTION('',(-1.,0.E+000)); -#97961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97962 = PCURVE('',#97963,#97968); -#97963 = CYLINDRICAL_SURFACE('',#97964,0.308574064194); -#97964 = AXIS2_PLACEMENT_3D('',#97965,#97966,#97967); -#97965 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#97966 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97967 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97968 = DEFINITIONAL_REPRESENTATION('',(#97969),#97972); -#97969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97970,#97971),.UNSPECIFIED., - .F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#97970 = CARTESIAN_POINT('',(3.191025391152,7.35)); -#97971 = CARTESIAN_POINT('',(3.191025391152,7.15)); -#97972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#97973 = ADVANCED_FACE('',(#97974),#97859,.F.); -#97974 = FACE_BOUND('',#97975,.F.); -#97975 = EDGE_LOOP('',(#97976,#97977,#98004,#98031)); -#97976 = ORIENTED_EDGE('',*,*,#97845,.T.); -#97977 = ORIENTED_EDGE('',*,*,#97978,.F.); -#97978 = EDGE_CURVE('',#97979,#97765,#97981,.T.); -#97979 = VERTEX_POINT('',#97980); -#97980 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.E+000)); -#97981 = SURFACE_CURVE('',#97982,(#97987,#97993),.PCURVE_S1.); -#97982 = CIRCLE('',#97983,0.208574704164); -#97983 = AXIS2_PLACEMENT_3D('',#97984,#97985,#97986); -#97984 = CARTESIAN_POINT('',(2.65,-0.728168876214,2.640924866458E-017)); -#97985 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#97986 = DIRECTION('',(0.E+000,0.E+000,1.)); -#97987 = PCURVE('',#97859,#97988); -#97988 = DEFINITIONAL_REPRESENTATION('',(#97989),#97992); -#97989 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#97990,#97991),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#99971 = CARTESIAN_POINT('',(3.162095483347,-7.65)); +#99972 = CARTESIAN_POINT('',(3.162095483347,-7.85)); +#99973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99974 = PCURVE('',#92025,#99975); +#99975 = DEFINITIONAL_REPRESENTATION('',(#99976),#99980); +#99976 = LINE('',#99977,#99978); +#99977 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#99978 = VECTOR('',#99979,1.); +#99979 = DIRECTION('',(0.E+000,-1.)); +#99980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99981 = ADVANCED_FACE('',(#99982),#91943,.F.); +#99982 = FACE_BOUND('',#99983,.T.); +#99983 = EDGE_LOOP('',(#99984,#100005,#100006,#100007,#100008,#100009, + #100030,#100031,#100032,#100033,#100034,#100055)); +#99984 = ORIENTED_EDGE('',*,*,#99985,.F.); +#99985 = EDGE_CURVE('',#99936,#91928,#99986,.T.); +#99986 = SURFACE_CURVE('',#99987,(#99991,#99998),.PCURVE_S1.); +#99987 = LINE('',#99988,#99989); +#99988 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.75)); +#99989 = VECTOR('',#99990,1.); +#99990 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#99991 = PCURVE('',#91943,#99992); +#99992 = DEFINITIONAL_REPRESENTATION('',(#99993),#99997); +#99993 = LINE('',#99994,#99995); +#99994 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#99995 = VECTOR('',#99996,1.); +#99996 = DIRECTION('',(3.563627120235E-016,1.)); +#99997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#99998 = PCURVE('',#92025,#99999); +#99999 = DEFINITIONAL_REPRESENTATION('',(#100000),#100004); +#100000 = LINE('',#100001,#100002); +#100001 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100002 = VECTOR('',#100003,1.); +#100003 = DIRECTION('',(1.,0.E+000)); +#100004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100005 = ORIENTED_EDGE('',*,*,#99935,.T.); +#100006 = ORIENTED_EDGE('',*,*,#99813,.T.); +#100007 = ORIENTED_EDGE('',*,*,#99584,.T.); +#100008 = ORIENTED_EDGE('',*,*,#99374,.T.); +#100009 = ORIENTED_EDGE('',*,*,#100010,.T.); +#100010 = EDGE_CURVE('',#99347,#99428,#100011,.T.); +#100011 = SURFACE_CURVE('',#100012,(#100016,#100023),.PCURVE_S1.); +#100012 = LINE('',#100013,#100014); +#100013 = CARTESIAN_POINT('',(2.35,-1.,1.159810404338E-002)); +#100014 = VECTOR('',#100015,1.); +#100015 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#100016 = PCURVE('',#91943,#100017); +#100017 = DEFINITIONAL_REPRESENTATION('',(#100018),#100022); +#100018 = LINE('',#100019,#100020); +#100019 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#100020 = VECTOR('',#100021,1.); +#100021 = DIRECTION('',(-1.,2.101748079665E-016)); +#100022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100023 = PCURVE('',#99362,#100024); +#100024 = DEFINITIONAL_REPRESENTATION('',(#100025),#100029); +#100025 = LINE('',#100026,#100027); +#100026 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#100027 = VECTOR('',#100028,1.); +#100028 = DIRECTION('',(1.,0.E+000)); +#100029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100030 = ORIENTED_EDGE('',*,*,#99425,.F.); +#100031 = ORIENTED_EDGE('',*,*,#99663,.F.); +#100032 = ORIENTED_EDGE('',*,*,#99716,.F.); +#100033 = ORIENTED_EDGE('',*,*,#99837,.F.); +#100034 = ORIENTED_EDGE('',*,*,#100035,.T.); +#100035 = EDGE_CURVE('',#99838,#91926,#100036,.T.); +#100036 = SURFACE_CURVE('',#100037,(#100041,#100048),.PCURVE_S1.); +#100037 = LINE('',#100038,#100039); +#100038 = CARTESIAN_POINT('',(2.35,-0.527847992439,0.65)); +#100039 = VECTOR('',#100040,1.); +#100040 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100041 = PCURVE('',#91943,#100042); +#100042 = DEFINITIONAL_REPRESENTATION('',(#100043),#100047); +#100043 = LINE('',#100044,#100045); +#100044 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100045 = VECTOR('',#100046,1.); +#100046 = DIRECTION('',(3.563627120235E-016,1.)); +#100047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100048 = PCURVE('',#91971,#100049); +#100049 = DEFINITIONAL_REPRESENTATION('',(#100050),#100054); +#100050 = LINE('',#100051,#100052); +#100051 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100052 = VECTOR('',#100053,1.); +#100053 = DIRECTION('',(-1.,0.E+000)); +#100054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100055 = ORIENTED_EDGE('',*,*,#91925,.T.); +#100056 = ADVANCED_FACE('',(#100057),#92025,.F.); +#100057 = FACE_BOUND('',#100058,.T.); +#100058 = EDGE_LOOP('',(#100059,#100060,#100061,#100062)); +#100059 = ORIENTED_EDGE('',*,*,#99962,.F.); +#100060 = ORIENTED_EDGE('',*,*,#99985,.T.); +#100061 = ORIENTED_EDGE('',*,*,#92011,.T.); +#100062 = ORIENTED_EDGE('',*,*,#100063,.F.); +#100063 = EDGE_CURVE('',#99912,#91984,#100064,.T.); +#100064 = SURFACE_CURVE('',#100065,(#100069,#100076),.PCURVE_S1.); +#100065 = LINE('',#100066,#100067); +#100066 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.75)); +#100067 = VECTOR('',#100068,1.); +#100068 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100069 = PCURVE('',#92025,#100070); +#100070 = DEFINITIONAL_REPRESENTATION('',(#100071),#100075); +#100071 = LINE('',#100072,#100073); +#100072 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#100073 = VECTOR('',#100074,1.); +#100074 = DIRECTION('',(1.,0.E+000)); +#100075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100076 = PCURVE('',#91999,#100077); +#100077 = DEFINITIONAL_REPRESENTATION('',(#100078),#100082); +#100078 = LINE('',#100079,#100080); +#100079 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#100080 = VECTOR('',#100081,1.); +#100081 = DIRECTION('',(-3.563627120235E-016,1.)); +#100082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100083 = ADVANCED_FACE('',(#100084),#91999,.F.); +#100084 = FACE_BOUND('',#100085,.T.); +#100085 = EDGE_LOOP('',(#100086,#100107,#100108,#100109,#100110,#100111, + #100132,#100133,#100134,#100135,#100136,#100137)); +#100086 = ORIENTED_EDGE('',*,*,#100087,.F.); +#100087 = EDGE_CURVE('',#99865,#91956,#100088,.T.); +#100088 = SURFACE_CURVE('',#100089,(#100093,#100100),.PCURVE_S1.); +#100089 = LINE('',#100090,#100091); +#100090 = CARTESIAN_POINT('',(2.15,-0.527847992439,0.65)); +#100091 = VECTOR('',#100092,1.); +#100092 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100093 = PCURVE('',#91999,#100094); +#100094 = DEFINITIONAL_REPRESENTATION('',(#100095),#100099); +#100095 = LINE('',#100096,#100097); +#100096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100097 = VECTOR('',#100098,1.); +#100098 = DIRECTION('',(-3.563627120235E-016,1.)); +#100099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100100 = PCURVE('',#91971,#100101); +#100101 = DEFINITIONAL_REPRESENTATION('',(#100102),#100106); +#100102 = LINE('',#100103,#100104); +#100103 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#100104 = VECTOR('',#100105,1.); +#100105 = DIRECTION('',(-1.,0.E+000)); +#100106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100107 = ORIENTED_EDGE('',*,*,#99886,.T.); +#100108 = ORIENTED_EDGE('',*,*,#99738,.T.); +#100109 = ORIENTED_EDGE('',*,*,#99609,.T.); +#100110 = ORIENTED_EDGE('',*,*,#99478,.T.); +#100111 = ORIENTED_EDGE('',*,*,#100112,.T.); +#100112 = EDGE_CURVE('',#99456,#99319,#100113,.T.); +#100113 = SURFACE_CURVE('',#100114,(#100118,#100125),.PCURVE_S1.); +#100114 = LINE('',#100115,#100116); +#100115 = CARTESIAN_POINT('',(2.15,-1.,1.159810404338E-002)); +#100116 = VECTOR('',#100117,1.); +#100117 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#100118 = PCURVE('',#91999,#100119); +#100119 = DEFINITIONAL_REPRESENTATION('',(#100120),#100124); +#100120 = LINE('',#100121,#100122); +#100121 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#100122 = VECTOR('',#100123,1.); +#100123 = DIRECTION('',(-1.,-2.101748079665E-016)); +#100124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100125 = PCURVE('',#99362,#100126); +#100126 = DEFINITIONAL_REPRESENTATION('',(#100127),#100131); +#100127 = LINE('',#100128,#100129); +#100128 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#100129 = VECTOR('',#100130,1.); +#100130 = DIRECTION('',(-1.,0.E+000)); +#100131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100132 = ORIENTED_EDGE('',*,*,#99316,.F.); +#100133 = ORIENTED_EDGE('',*,*,#99530,.F.); +#100134 = ORIENTED_EDGE('',*,*,#99791,.F.); +#100135 = ORIENTED_EDGE('',*,*,#99911,.F.); +#100136 = ORIENTED_EDGE('',*,*,#100063,.T.); +#100137 = ORIENTED_EDGE('',*,*,#91983,.T.); +#100138 = ADVANCED_FACE('',(#100139),#91971,.F.); +#100139 = FACE_BOUND('',#100140,.T.); +#100140 = EDGE_LOOP('',(#100141,#100142,#100143,#100144)); +#100141 = ORIENTED_EDGE('',*,*,#99864,.F.); +#100142 = ORIENTED_EDGE('',*,*,#100087,.T.); +#100143 = ORIENTED_EDGE('',*,*,#91955,.T.); +#100144 = ORIENTED_EDGE('',*,*,#100035,.F.); +#100145 = ADVANCED_FACE('',(#100146),#99362,.T.); +#100146 = FACE_BOUND('',#100147,.T.); +#100147 = EDGE_LOOP('',(#100148,#100149,#100150,#100151)); +#100148 = ORIENTED_EDGE('',*,*,#100112,.F.); +#100149 = ORIENTED_EDGE('',*,*,#99455,.F.); +#100150 = ORIENTED_EDGE('',*,*,#100010,.F.); +#100151 = ORIENTED_EDGE('',*,*,#99346,.F.); +#100152 = ADVANCED_FACE('',(#100153),#100167,.T.); +#100153 = FACE_BOUND('',#100154,.T.); +#100154 = EDGE_LOOP('',(#100155,#100185,#100213,#100236)); +#100155 = ORIENTED_EDGE('',*,*,#100156,.T.); +#100156 = EDGE_CURVE('',#100157,#100159,#100161,.T.); +#100157 = VERTEX_POINT('',#100158); +#100158 = CARTESIAN_POINT('',(2.65,-0.740726081328,-0.208196358798)); +#100159 = VERTEX_POINT('',#100160); +#100160 = CARTESIAN_POINT('',(2.65,-1.,-0.208196358798)); +#100161 = SURFACE_CURVE('',#100162,(#100166,#100178),.PCURVE_S1.); +#100162 = LINE('',#100163,#100164); +#100163 = CARTESIAN_POINT('',(2.65,-0.740726081328,-0.208196358798)); +#100164 = VECTOR('',#100165,1.); +#100165 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#100166 = PCURVE('',#100167,#100172); +#100167 = PLANE('',#100168); +#100168 = AXIS2_PLACEMENT_3D('',#100169,#100170,#100171); +#100169 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#100170 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100171 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100172 = DEFINITIONAL_REPRESENTATION('',(#100173),#100177); +#100173 = LINE('',#100174,#100175); +#100174 = CARTESIAN_POINT('',(-7.35,0.E+000)); +#100175 = VECTOR('',#100176,1.); +#100176 = DIRECTION('',(0.E+000,-1.)); +#100177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100178 = PCURVE('',#91434,#100179); +#100179 = DEFINITIONAL_REPRESENTATION('',(#100180),#100184); +#100180 = LINE('',#100181,#100182); +#100181 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#100182 = VECTOR('',#100183,1.); +#100183 = DIRECTION('',(0.E+000,-1.)); +#100184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100185 = ORIENTED_EDGE('',*,*,#100186,.T.); +#100186 = EDGE_CURVE('',#100159,#100187,#100189,.T.); +#100187 = VERTEX_POINT('',#100188); +#100188 = CARTESIAN_POINT('',(2.85,-1.,-0.208196358798)); +#100189 = SURFACE_CURVE('',#100190,(#100194,#100201),.PCURVE_S1.); +#100190 = LINE('',#100191,#100192); +#100191 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#100192 = VECTOR('',#100193,1.); +#100193 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100194 = PCURVE('',#100167,#100195); +#100195 = DEFINITIONAL_REPRESENTATION('',(#100196),#100200); +#100196 = LINE('',#100197,#100198); +#100197 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#100198 = VECTOR('',#100199,1.); +#100199 = DIRECTION('',(1.,0.E+000)); +#100200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100201 = PCURVE('',#100202,#100207); +#100202 = PLANE('',#100203); +#100203 = AXIS2_PLACEMENT_3D('',#100204,#100205,#100206); +#100204 = CARTESIAN_POINT('',(2.75,-1.,-0.258196742327)); +#100205 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#100206 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#100207 = DEFINITIONAL_REPRESENTATION('',(#100208),#100212); +#100208 = LINE('',#100209,#100210); +#100209 = CARTESIAN_POINT('',(-5.000038352949E-002,7.25)); +#100210 = VECTOR('',#100211,1.); +#100211 = DIRECTION('',(0.E+000,1.)); +#100212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100213 = ORIENTED_EDGE('',*,*,#100214,.F.); +#100214 = EDGE_CURVE('',#100215,#100187,#100217,.T.); +#100215 = VERTEX_POINT('',#100216); +#100216 = CARTESIAN_POINT('',(2.85,-0.740726081328,-0.208196358798)); +#100217 = SURFACE_CURVE('',#100218,(#100222,#100229),.PCURVE_S1.); +#100218 = LINE('',#100219,#100220); +#100219 = CARTESIAN_POINT('',(2.85,-0.740726081328,-0.208196358798)); +#100220 = VECTOR('',#100221,1.); +#100221 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#100222 = PCURVE('',#100167,#100223); +#100223 = DEFINITIONAL_REPRESENTATION('',(#100224),#100228); +#100224 = LINE('',#100225,#100226); +#100225 = CARTESIAN_POINT('',(-7.15,0.E+000)); +#100226 = VECTOR('',#100227,1.); +#100227 = DIRECTION('',(0.E+000,-1.)); +#100228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100229 = PCURVE('',#91378,#100230); +#100230 = DEFINITIONAL_REPRESENTATION('',(#100231),#100235); +#100231 = LINE('',#100232,#100233); +#100232 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#100233 = VECTOR('',#100234,1.); +#100234 = DIRECTION('',(0.E+000,-1.)); +#100235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100236 = ORIENTED_EDGE('',*,*,#100237,.T.); +#100237 = EDGE_CURVE('',#100215,#100157,#100238,.T.); +#100238 = SURFACE_CURVE('',#100239,(#100243,#100250),.PCURVE_S1.); +#100239 = LINE('',#100240,#100241); +#100240 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#100241 = VECTOR('',#100242,1.); +#100242 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100243 = PCURVE('',#100167,#100244); +#100244 = DEFINITIONAL_REPRESENTATION('',(#100245),#100249); +#100245 = LINE('',#100246,#100247); +#100246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100247 = VECTOR('',#100248,1.); +#100248 = DIRECTION('',(-1.,0.E+000)); +#100249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100250 = PCURVE('',#100251,#100256); +#100251 = CYLINDRICAL_SURFACE('',#100252,0.208574704164); +#100252 = AXIS2_PLACEMENT_3D('',#100253,#100254,#100255); +#100253 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#100254 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100255 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100256 = DEFINITIONAL_REPRESENTATION('',(#100257),#100260); +#100257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100258,#100259), + .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); +#100258 = CARTESIAN_POINT('',(3.201833915432,7.15)); +#100259 = CARTESIAN_POINT('',(3.201833915432,7.35)); +#100260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100261 = ADVANCED_FACE('',(#100262),#100276,.T.); +#100262 = FACE_BOUND('',#100263,.T.); +#100263 = EDGE_LOOP('',(#100264,#100294,#100317,#100340)); +#100264 = ORIENTED_EDGE('',*,*,#100265,.T.); +#100265 = EDGE_CURVE('',#100266,#100268,#100270,.T.); +#100266 = VERTEX_POINT('',#100267); +#100267 = CARTESIAN_POINT('',(2.85,-0.74341632541,-0.308197125857)); +#100268 = VERTEX_POINT('',#100269); +#100269 = CARTESIAN_POINT('',(2.85,-1.,-0.308197125857)); +#100270 = SURFACE_CURVE('',#100271,(#100275,#100287),.PCURVE_S1.); +#100271 = LINE('',#100272,#100273); +#100272 = CARTESIAN_POINT('',(2.85,-0.74341632541,-0.308197125857)); +#100273 = VECTOR('',#100274,1.); +#100274 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#100275 = PCURVE('',#100276,#100281); +#100276 = PLANE('',#100277); +#100277 = AXIS2_PLACEMENT_3D('',#100278,#100279,#100280); +#100278 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#100279 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100280 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100281 = DEFINITIONAL_REPRESENTATION('',(#100282),#100286); +#100282 = LINE('',#100283,#100284); +#100283 = CARTESIAN_POINT('',(7.15,0.E+000)); +#100284 = VECTOR('',#100285,1.); +#100285 = DIRECTION('',(0.E+000,-1.)); +#100286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100287 = PCURVE('',#91378,#100288); +#100288 = DEFINITIONAL_REPRESENTATION('',(#100289),#100293); +#100289 = LINE('',#100290,#100291); +#100290 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#100291 = VECTOR('',#100292,1.); +#100292 = DIRECTION('',(0.E+000,-1.)); +#100293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100294 = ORIENTED_EDGE('',*,*,#100295,.T.); +#100295 = EDGE_CURVE('',#100268,#100296,#100298,.T.); +#100296 = VERTEX_POINT('',#100297); +#100297 = CARTESIAN_POINT('',(2.65,-1.,-0.308197125857)); +#100298 = SURFACE_CURVE('',#100299,(#100303,#100310),.PCURVE_S1.); +#100299 = LINE('',#100300,#100301); +#100300 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#100301 = VECTOR('',#100302,1.); +#100302 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100303 = PCURVE('',#100276,#100304); +#100304 = DEFINITIONAL_REPRESENTATION('',(#100305),#100309); +#100305 = LINE('',#100306,#100307); +#100306 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#100307 = VECTOR('',#100308,1.); +#100308 = DIRECTION('',(1.,0.E+000)); +#100309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100310 = PCURVE('',#100202,#100311); +#100311 = DEFINITIONAL_REPRESENTATION('',(#100312),#100316); +#100312 = LINE('',#100313,#100314); +#100313 = CARTESIAN_POINT('',(5.000038352949E-002,7.25)); +#100314 = VECTOR('',#100315,1.); +#100315 = DIRECTION('',(0.E+000,-1.)); +#100316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100317 = ORIENTED_EDGE('',*,*,#100318,.F.); +#100318 = EDGE_CURVE('',#100319,#100296,#100321,.T.); +#100319 = VERTEX_POINT('',#100320); +#100320 = CARTESIAN_POINT('',(2.65,-0.74341632541,-0.308197125857)); +#100321 = SURFACE_CURVE('',#100322,(#100326,#100333),.PCURVE_S1.); +#100322 = LINE('',#100323,#100324); +#100323 = CARTESIAN_POINT('',(2.65,-0.74341632541,-0.308197125857)); +#100324 = VECTOR('',#100325,1.); +#100325 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#100326 = PCURVE('',#100276,#100327); +#100327 = DEFINITIONAL_REPRESENTATION('',(#100328),#100332); +#100328 = LINE('',#100329,#100330); +#100329 = CARTESIAN_POINT('',(7.35,0.E+000)); +#100330 = VECTOR('',#100331,1.); +#100331 = DIRECTION('',(0.E+000,-1.)); +#100332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100333 = PCURVE('',#91434,#100334); +#100334 = DEFINITIONAL_REPRESENTATION('',(#100335),#100339); +#100335 = LINE('',#100336,#100337); +#100336 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#100337 = VECTOR('',#100338,1.); +#100338 = DIRECTION('',(0.E+000,-1.)); +#100339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100340 = ORIENTED_EDGE('',*,*,#100341,.T.); +#100341 = EDGE_CURVE('',#100319,#100266,#100342,.T.); +#100342 = SURFACE_CURVE('',#100343,(#100347,#100354),.PCURVE_S1.); +#100343 = LINE('',#100344,#100345); +#100344 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#100345 = VECTOR('',#100346,1.); +#100346 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100347 = PCURVE('',#100276,#100348); +#100348 = DEFINITIONAL_REPRESENTATION('',(#100349),#100353); +#100349 = LINE('',#100350,#100351); +#100350 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100351 = VECTOR('',#100352,1.); +#100352 = DIRECTION('',(-1.,0.E+000)); +#100353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100354 = PCURVE('',#100355,#100360); +#100355 = CYLINDRICAL_SURFACE('',#100356,0.308574064194); +#100356 = AXIS2_PLACEMENT_3D('',#100357,#100358,#100359); +#100357 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#100358 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100359 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100360 = DEFINITIONAL_REPRESENTATION('',(#100361),#100364); +#100361 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100362,#100363), + .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); +#100362 = CARTESIAN_POINT('',(3.191025391152,7.35)); +#100363 = CARTESIAN_POINT('',(3.191025391152,7.15)); +#100364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100365 = ADVANCED_FACE('',(#100366),#100251,.F.); +#100366 = FACE_BOUND('',#100367,.F.); +#100367 = EDGE_LOOP('',(#100368,#100369,#100396,#100423)); +#100368 = ORIENTED_EDGE('',*,*,#100237,.T.); +#100369 = ORIENTED_EDGE('',*,*,#100370,.F.); +#100370 = EDGE_CURVE('',#100371,#100157,#100373,.T.); +#100371 = VERTEX_POINT('',#100372); +#100372 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.E+000)); +#100373 = SURFACE_CURVE('',#100374,(#100379,#100385),.PCURVE_S1.); +#100374 = CIRCLE('',#100375,0.208574704164); +#100375 = AXIS2_PLACEMENT_3D('',#100376,#100377,#100378); +#100376 = CARTESIAN_POINT('',(2.65,-0.728168876214,2.640924866458E-017) + ); +#100377 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100378 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100379 = PCURVE('',#100251,#100380); +#100380 = DEFINITIONAL_REPRESENTATION('',(#100381),#100384); +#100381 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100382,#100383), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#97990 = CARTESIAN_POINT('',(1.570796326795,7.35)); -#97991 = CARTESIAN_POINT('',(3.201833915432,7.35)); -#97992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100382 = CARTESIAN_POINT('',(1.570796326795,7.35)); +#100383 = CARTESIAN_POINT('',(3.201833915432,7.35)); +#100384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#97993 = PCURVE('',#89042,#97994); -#97994 = DEFINITIONAL_REPRESENTATION('',(#97995),#98003); -#97995 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#97996,#97997,#97998,#97999 - ,#98000,#98001,#98002),.UNSPECIFIED.,.F.,.F.) +#100385 = PCURVE('',#91434,#100386); +#100386 = DEFINITIONAL_REPRESENTATION('',(#100387),#100395); +#100387 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100388,#100389,#100390, + #100391,#100392,#100393,#100394),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#97996 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#97997 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#97998 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#97999 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#98000 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#98001 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#98002 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#98003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98004 = ORIENTED_EDGE('',*,*,#98005,.T.); -#98005 = EDGE_CURVE('',#97979,#98006,#98008,.T.); -#98006 = VERTEX_POINT('',#98007); -#98007 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.E+000)); -#98008 = SURFACE_CURVE('',#98009,(#98013,#98019),.PCURVE_S1.); -#98009 = LINE('',#98010,#98011); -#98010 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#98011 = VECTOR('',#98012,1.); -#98012 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98013 = PCURVE('',#97859,#98014); -#98014 = DEFINITIONAL_REPRESENTATION('',(#98015),#98018); -#98015 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98016,#98017),.UNSPECIFIED., - .F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#98016 = CARTESIAN_POINT('',(1.570796326795,7.35)); -#98017 = CARTESIAN_POINT('',(1.570796326795,7.15)); -#98018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98019 = PCURVE('',#98020,#98025); -#98020 = PLANE('',#98021); -#98021 = AXIS2_PLACEMENT_3D('',#98022,#98023,#98024); -#98022 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#98023 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#98024 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#98025 = DEFINITIONAL_REPRESENTATION('',(#98026),#98030); -#98026 = LINE('',#98027,#98028); -#98027 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#98028 = VECTOR('',#98029,1.); -#98029 = DIRECTION('',(0.E+000,1.)); -#98030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98031 = ORIENTED_EDGE('',*,*,#98032,.T.); -#98032 = EDGE_CURVE('',#98006,#97823,#98033,.T.); -#98033 = SURFACE_CURVE('',#98034,(#98039,#98045),.PCURVE_S1.); -#98034 = CIRCLE('',#98035,0.208574704164); -#98035 = AXIS2_PLACEMENT_3D('',#98036,#98037,#98038); -#98036 = CARTESIAN_POINT('',(2.85,-0.728168876214,2.640924866458E-017)); -#98037 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98038 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98039 = PCURVE('',#97859,#98040); -#98040 = DEFINITIONAL_REPRESENTATION('',(#98041),#98044); -#98041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98042,#98043),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#100388 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#100389 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#100390 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#100391 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#100392 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#100393 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#100394 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#100395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100396 = ORIENTED_EDGE('',*,*,#100397,.T.); +#100397 = EDGE_CURVE('',#100371,#100398,#100400,.T.); +#100398 = VERTEX_POINT('',#100399); +#100399 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.E+000)); +#100400 = SURFACE_CURVE('',#100401,(#100405,#100411),.PCURVE_S1.); +#100401 = LINE('',#100402,#100403); +#100402 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#100403 = VECTOR('',#100404,1.); +#100404 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100405 = PCURVE('',#100251,#100406); +#100406 = DEFINITIONAL_REPRESENTATION('',(#100407),#100410); +#100407 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100408,#100409), + .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); +#100408 = CARTESIAN_POINT('',(1.570796326795,7.35)); +#100409 = CARTESIAN_POINT('',(1.570796326795,7.15)); +#100410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100411 = PCURVE('',#100412,#100417); +#100412 = PLANE('',#100413); +#100413 = AXIS2_PLACEMENT_3D('',#100414,#100415,#100416); +#100414 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#100415 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#100416 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#100417 = DEFINITIONAL_REPRESENTATION('',(#100418),#100422); +#100418 = LINE('',#100419,#100420); +#100419 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#100420 = VECTOR('',#100421,1.); +#100421 = DIRECTION('',(0.E+000,1.)); +#100422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100423 = ORIENTED_EDGE('',*,*,#100424,.T.); +#100424 = EDGE_CURVE('',#100398,#100215,#100425,.T.); +#100425 = SURFACE_CURVE('',#100426,(#100431,#100437),.PCURVE_S1.); +#100426 = CIRCLE('',#100427,0.208574704164); +#100427 = AXIS2_PLACEMENT_3D('',#100428,#100429,#100430); +#100428 = CARTESIAN_POINT('',(2.85,-0.728168876214,2.640924866458E-017) + ); +#100429 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100430 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100431 = PCURVE('',#100251,#100432); +#100432 = DEFINITIONAL_REPRESENTATION('',(#100433),#100436); +#100433 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100434,#100435), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#98042 = CARTESIAN_POINT('',(1.570796326795,7.15)); -#98043 = CARTESIAN_POINT('',(3.201833915432,7.15)); -#98044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98045 = PCURVE('',#88986,#98046); -#98046 = DEFINITIONAL_REPRESENTATION('',(#98047),#98051); -#98047 = CIRCLE('',#98048,0.208574704164); -#98048 = AXIS2_PLACEMENT_2D('',#98049,#98050); -#98049 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#98050 = DIRECTION('',(1.,0.E+000)); -#98051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98052 = ADVANCED_FACE('',(#98053),#97963,.T.); -#98053 = FACE_BOUND('',#98054,.T.); -#98054 = EDGE_LOOP('',(#98055,#98056,#98083,#98110)); -#98055 = ORIENTED_EDGE('',*,*,#97949,.F.); -#98056 = ORIENTED_EDGE('',*,*,#98057,.F.); -#98057 = EDGE_CURVE('',#98058,#97927,#98060,.T.); -#98058 = VERTEX_POINT('',#98059); -#98059 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.E+000)); -#98060 = SURFACE_CURVE('',#98061,(#98066,#98072),.PCURVE_S1.); -#98061 = CIRCLE('',#98062,0.308574064194); -#98062 = AXIS2_PLACEMENT_3D('',#98063,#98064,#98065); -#98063 = CARTESIAN_POINT('',(2.65,-0.728168876214,2.640924866458E-017)); -#98064 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98065 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98066 = PCURVE('',#97963,#98067); -#98067 = DEFINITIONAL_REPRESENTATION('',(#98068),#98071); -#98068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98069,#98070),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#100434 = CARTESIAN_POINT('',(1.570796326795,7.15)); +#100435 = CARTESIAN_POINT('',(3.201833915432,7.15)); +#100436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100437 = PCURVE('',#91378,#100438); +#100438 = DEFINITIONAL_REPRESENTATION('',(#100439),#100443); +#100439 = CIRCLE('',#100440,0.208574704164); +#100440 = AXIS2_PLACEMENT_2D('',#100441,#100442); +#100441 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#100442 = DIRECTION('',(1.,0.E+000)); +#100443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100444 = ADVANCED_FACE('',(#100445),#100355,.T.); +#100445 = FACE_BOUND('',#100446,.T.); +#100446 = EDGE_LOOP('',(#100447,#100448,#100475,#100502)); +#100447 = ORIENTED_EDGE('',*,*,#100341,.F.); +#100448 = ORIENTED_EDGE('',*,*,#100449,.F.); +#100449 = EDGE_CURVE('',#100450,#100319,#100452,.T.); +#100450 = VERTEX_POINT('',#100451); +#100451 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.E+000)); +#100452 = SURFACE_CURVE('',#100453,(#100458,#100464),.PCURVE_S1.); +#100453 = CIRCLE('',#100454,0.308574064194); +#100454 = AXIS2_PLACEMENT_3D('',#100455,#100456,#100457); +#100455 = CARTESIAN_POINT('',(2.65,-0.728168876214,2.640924866458E-017) + ); +#100456 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100457 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100458 = PCURVE('',#100355,#100459); +#100459 = DEFINITIONAL_REPRESENTATION('',(#100460),#100463); +#100460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100461,#100462), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#98069 = CARTESIAN_POINT('',(1.570796326795,7.35)); -#98070 = CARTESIAN_POINT('',(3.191025391152,7.35)); -#98071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100461 = CARTESIAN_POINT('',(1.570796326795,7.35)); +#100462 = CARTESIAN_POINT('',(3.191025391152,7.35)); +#100463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98072 = PCURVE('',#89042,#98073); -#98073 = DEFINITIONAL_REPRESENTATION('',(#98074),#98082); -#98074 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98075,#98076,#98077,#98078 - ,#98079,#98080,#98081),.UNSPECIFIED.,.T.,.F.) +#100464 = PCURVE('',#91434,#100465); +#100465 = DEFINITIONAL_REPRESENTATION('',(#100466),#100474); +#100466 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100467,#100468,#100469, + #100470,#100471,#100472,#100473),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#98075 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#98076 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#98077 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#98078 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#98079 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#98080 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#98081 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#98082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98083 = ORIENTED_EDGE('',*,*,#98084,.F.); -#98084 = EDGE_CURVE('',#98085,#98058,#98087,.T.); -#98085 = VERTEX_POINT('',#98086); -#98086 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.E+000)); -#98087 = SURFACE_CURVE('',#98088,(#98092,#98098),.PCURVE_S1.); -#98088 = LINE('',#98089,#98090); -#98089 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#98090 = VECTOR('',#98091,1.); -#98091 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98092 = PCURVE('',#97963,#98093); -#98093 = DEFINITIONAL_REPRESENTATION('',(#98094),#98097); -#98094 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98095,#98096),.UNSPECIFIED., - .F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#98095 = CARTESIAN_POINT('',(1.570796326795,7.15)); -#98096 = CARTESIAN_POINT('',(1.570796326795,7.35)); -#98097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98098 = PCURVE('',#98099,#98104); -#98099 = PLANE('',#98100); -#98100 = AXIS2_PLACEMENT_3D('',#98101,#98102,#98103); -#98101 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#98102 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#98103 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98104 = DEFINITIONAL_REPRESENTATION('',(#98105),#98109); -#98105 = LINE('',#98106,#98107); -#98106 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#98107 = VECTOR('',#98108,1.); -#98108 = DIRECTION('',(0.E+000,-1.)); -#98109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98110 = ORIENTED_EDGE('',*,*,#98111,.T.); -#98111 = EDGE_CURVE('',#98085,#97874,#98112,.T.); -#98112 = SURFACE_CURVE('',#98113,(#98118,#98124),.PCURVE_S1.); -#98113 = CIRCLE('',#98114,0.308574064194); -#98114 = AXIS2_PLACEMENT_3D('',#98115,#98116,#98117); -#98115 = CARTESIAN_POINT('',(2.85,-0.728168876214,2.640924866458E-017)); -#98116 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98117 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98118 = PCURVE('',#97963,#98119); -#98119 = DEFINITIONAL_REPRESENTATION('',(#98120),#98123); -#98120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98121,#98122),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#100467 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#100468 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#100469 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#100470 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#100471 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#100472 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#100473 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#100474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100475 = ORIENTED_EDGE('',*,*,#100476,.F.); +#100476 = EDGE_CURVE('',#100477,#100450,#100479,.T.); +#100477 = VERTEX_POINT('',#100478); +#100478 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.E+000)); +#100479 = SURFACE_CURVE('',#100480,(#100484,#100490),.PCURVE_S1.); +#100480 = LINE('',#100481,#100482); +#100481 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#100482 = VECTOR('',#100483,1.); +#100483 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100484 = PCURVE('',#100355,#100485); +#100485 = DEFINITIONAL_REPRESENTATION('',(#100486),#100489); +#100486 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100487,#100488), + .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); +#100487 = CARTESIAN_POINT('',(1.570796326795,7.15)); +#100488 = CARTESIAN_POINT('',(1.570796326795,7.35)); +#100489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100490 = PCURVE('',#100491,#100496); +#100491 = PLANE('',#100492); +#100492 = AXIS2_PLACEMENT_3D('',#100493,#100494,#100495); +#100493 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#100494 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#100495 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#100496 = DEFINITIONAL_REPRESENTATION('',(#100497),#100501); +#100497 = LINE('',#100498,#100499); +#100498 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#100499 = VECTOR('',#100500,1.); +#100500 = DIRECTION('',(0.E+000,-1.)); +#100501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100502 = ORIENTED_EDGE('',*,*,#100503,.T.); +#100503 = EDGE_CURVE('',#100477,#100266,#100504,.T.); +#100504 = SURFACE_CURVE('',#100505,(#100510,#100516),.PCURVE_S1.); +#100505 = CIRCLE('',#100506,0.308574064194); +#100506 = AXIS2_PLACEMENT_3D('',#100507,#100508,#100509); +#100507 = CARTESIAN_POINT('',(2.85,-0.728168876214,2.640924866458E-017) + ); +#100508 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100509 = DIRECTION('',(0.E+000,0.E+000,1.)); +#100510 = PCURVE('',#100355,#100511); +#100511 = DEFINITIONAL_REPRESENTATION('',(#100512),#100515); +#100512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100513,#100514), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#98121 = CARTESIAN_POINT('',(1.570796326795,7.15)); -#98122 = CARTESIAN_POINT('',(3.191025391152,7.15)); -#98123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100513 = CARTESIAN_POINT('',(1.570796326795,7.15)); +#100514 = CARTESIAN_POINT('',(3.191025391152,7.15)); +#100515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100516 = PCURVE('',#91378,#100517); +#100517 = DEFINITIONAL_REPRESENTATION('',(#100518),#100522); +#100518 = CIRCLE('',#100519,0.308574064194); +#100519 = AXIS2_PLACEMENT_2D('',#100520,#100521); +#100520 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#100521 = DIRECTION('',(1.,0.E+000)); +#100522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100523 = ADVANCED_FACE('',(#100524),#100491,.F.); +#100524 = FACE_BOUND('',#100525,.T.); +#100525 = EDGE_LOOP('',(#100526,#100555,#100576,#100577)); +#100526 = ORIENTED_EDGE('',*,*,#100527,.F.); +#100527 = EDGE_CURVE('',#100528,#100530,#100532,.T.); +#100528 = VERTEX_POINT('',#100529); +#100529 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.530776333563)); +#100530 = VERTEX_POINT('',#100531); +#100531 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.530776333563)); +#100532 = SURFACE_CURVE('',#100533,(#100537,#100544),.PCURVE_S1.); +#100533 = LINE('',#100534,#100535); +#100534 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#100535 = VECTOR('',#100536,1.); +#100536 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100537 = PCURVE('',#100491,#100538); +#100538 = DEFINITIONAL_REPRESENTATION('',(#100539),#100543); +#100539 = LINE('',#100540,#100541); +#100540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100541 = VECTOR('',#100542,1.); +#100542 = DIRECTION('',(0.E+000,-1.)); +#100543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100544 = PCURVE('',#100545,#100550); +#100545 = CYLINDRICAL_SURFACE('',#100546,0.119270391569); +#100546 = AXIS2_PLACEMENT_3D('',#100547,#100548,#100549); +#100547 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#100548 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100549 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100550 = DEFINITIONAL_REPRESENTATION('',(#100551),#100554); +#100551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100552,#100553), + .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); +#100552 = CARTESIAN_POINT('',(4.712388980385,-7.15)); +#100553 = CARTESIAN_POINT('',(4.712388980385,-7.35)); +#100554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100555 = ORIENTED_EDGE('',*,*,#100556,.T.); +#100556 = EDGE_CURVE('',#100528,#100477,#100557,.T.); +#100557 = SURFACE_CURVE('',#100558,(#100562,#100569),.PCURVE_S1.); +#100558 = LINE('',#100559,#100560); +#100559 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.530776333563)); +#100560 = VECTOR('',#100561,1.); +#100561 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#100562 = PCURVE('',#100491,#100563); +#100563 = DEFINITIONAL_REPRESENTATION('',(#100564),#100568); +#100564 = LINE('',#100565,#100566); +#100565 = CARTESIAN_POINT('',(0.E+000,-7.15)); +#100566 = VECTOR('',#100567,1.); +#100567 = DIRECTION('',(1.,0.E+000)); +#100568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100569 = PCURVE('',#91378,#100570); +#100570 = DEFINITIONAL_REPRESENTATION('',(#100571),#100575); +#100571 = LINE('',#100572,#100573); +#100572 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#100573 = VECTOR('',#100574,1.); +#100574 = DIRECTION('',(-1.,-1.021336205033E-016)); +#100575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100576 = ORIENTED_EDGE('',*,*,#100476,.T.); +#100577 = ORIENTED_EDGE('',*,*,#100578,.F.); +#100578 = EDGE_CURVE('',#100530,#100450,#100579,.T.); +#100579 = SURFACE_CURVE('',#100580,(#100584,#100591),.PCURVE_S1.); +#100580 = LINE('',#100581,#100582); +#100581 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.530776333563)); +#100582 = VECTOR('',#100583,1.); +#100583 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#100584 = PCURVE('',#100491,#100585); +#100585 = DEFINITIONAL_REPRESENTATION('',(#100586),#100590); +#100586 = LINE('',#100587,#100588); +#100587 = CARTESIAN_POINT('',(0.E+000,-7.35)); +#100588 = VECTOR('',#100589,1.); +#100589 = DIRECTION('',(1.,0.E+000)); +#100590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100591 = PCURVE('',#91434,#100592); +#100592 = DEFINITIONAL_REPRESENTATION('',(#100593),#100597); +#100593 = LINE('',#100594,#100595); +#100594 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#100595 = VECTOR('',#100596,1.); +#100596 = DIRECTION('',(1.,-1.021336205033E-016)); +#100597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100598 = ADVANCED_FACE('',(#100599),#100412,.F.); +#100599 = FACE_BOUND('',#100600,.T.); +#100600 = EDGE_LOOP('',(#100601,#100630,#100651,#100652)); +#100601 = ORIENTED_EDGE('',*,*,#100602,.F.); +#100602 = EDGE_CURVE('',#100603,#100605,#100607,.T.); +#100603 = VERTEX_POINT('',#100604); +#100604 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.530776333563)); +#100605 = VERTEX_POINT('',#100606); +#100606 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.530776333563)); +#100607 = SURFACE_CURVE('',#100608,(#100612,#100619),.PCURVE_S1.); +#100608 = LINE('',#100609,#100610); +#100609 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#100610 = VECTOR('',#100611,1.); +#100611 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100612 = PCURVE('',#100412,#100613); +#100613 = DEFINITIONAL_REPRESENTATION('',(#100614),#100618); +#100614 = LINE('',#100615,#100616); +#100615 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100616 = VECTOR('',#100617,1.); +#100617 = DIRECTION('',(0.E+000,1.)); +#100618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100619 = PCURVE('',#100620,#100625); +#100620 = CYLINDRICAL_SURFACE('',#100621,0.2192697516); +#100621 = AXIS2_PLACEMENT_3D('',#100622,#100623,#100624); +#100622 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#100623 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100624 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100625 = DEFINITIONAL_REPRESENTATION('',(#100626),#100629); +#100626 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100627,#100628), + .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); +#100627 = CARTESIAN_POINT('',(4.712388980385,-7.35)); +#100628 = CARTESIAN_POINT('',(4.712388980385,-7.15)); +#100629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98124 = PCURVE('',#88986,#98125); -#98125 = DEFINITIONAL_REPRESENTATION('',(#98126),#98130); -#98126 = CIRCLE('',#98127,0.308574064194); -#98127 = AXIS2_PLACEMENT_2D('',#98128,#98129); -#98128 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#98129 = DIRECTION('',(1.,0.E+000)); -#98130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100630 = ORIENTED_EDGE('',*,*,#100631,.T.); +#100631 = EDGE_CURVE('',#100603,#100371,#100632,.T.); +#100632 = SURFACE_CURVE('',#100633,(#100637,#100644),.PCURVE_S1.); +#100633 = LINE('',#100634,#100635); +#100634 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.530776333563)); +#100635 = VECTOR('',#100636,1.); +#100636 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#100637 = PCURVE('',#100412,#100638); +#100638 = DEFINITIONAL_REPRESENTATION('',(#100639),#100643); +#100639 = LINE('',#100640,#100641); +#100640 = CARTESIAN_POINT('',(0.E+000,-7.35)); +#100641 = VECTOR('',#100642,1.); +#100642 = DIRECTION('',(-1.,0.E+000)); +#100643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98131 = ADVANCED_FACE('',(#98132),#98099,.F.); -#98132 = FACE_BOUND('',#98133,.T.); -#98133 = EDGE_LOOP('',(#98134,#98163,#98184,#98185)); -#98134 = ORIENTED_EDGE('',*,*,#98135,.F.); -#98135 = EDGE_CURVE('',#98136,#98138,#98140,.T.); -#98136 = VERTEX_POINT('',#98137); -#98137 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.530776333563)); -#98138 = VERTEX_POINT('',#98139); -#98139 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.530776333563)); -#98140 = SURFACE_CURVE('',#98141,(#98145,#98152),.PCURVE_S1.); -#98141 = LINE('',#98142,#98143); -#98142 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#98143 = VECTOR('',#98144,1.); -#98144 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98145 = PCURVE('',#98099,#98146); -#98146 = DEFINITIONAL_REPRESENTATION('',(#98147),#98151); -#98147 = LINE('',#98148,#98149); -#98148 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98149 = VECTOR('',#98150,1.); -#98150 = DIRECTION('',(0.E+000,-1.)); -#98151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98152 = PCURVE('',#98153,#98158); -#98153 = CYLINDRICAL_SURFACE('',#98154,0.119270391569); -#98154 = AXIS2_PLACEMENT_3D('',#98155,#98156,#98157); -#98155 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#98156 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98157 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98158 = DEFINITIONAL_REPRESENTATION('',(#98159),#98162); -#98159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98160,#98161),.UNSPECIFIED., - .F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#98160 = CARTESIAN_POINT('',(4.712388980385,-7.15)); -#98161 = CARTESIAN_POINT('',(4.712388980385,-7.35)); -#98162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98163 = ORIENTED_EDGE('',*,*,#98164,.T.); -#98164 = EDGE_CURVE('',#98136,#98085,#98165,.T.); -#98165 = SURFACE_CURVE('',#98166,(#98170,#98177),.PCURVE_S1.); -#98166 = LINE('',#98167,#98168); -#98167 = CARTESIAN_POINT('',(2.85,-0.419594812019,0.530776333563)); -#98168 = VECTOR('',#98169,1.); -#98169 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98170 = PCURVE('',#98099,#98171); -#98171 = DEFINITIONAL_REPRESENTATION('',(#98172),#98176); -#98172 = LINE('',#98173,#98174); -#98173 = CARTESIAN_POINT('',(0.E+000,-7.15)); -#98174 = VECTOR('',#98175,1.); -#98175 = DIRECTION('',(1.,0.E+000)); -#98176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98177 = PCURVE('',#88986,#98178); -#98178 = DEFINITIONAL_REPRESENTATION('',(#98179),#98183); -#98179 = LINE('',#98180,#98181); -#98180 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#98181 = VECTOR('',#98182,1.); -#98182 = DIRECTION('',(-1.,-1.021336205033E-016)); -#98183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98184 = ORIENTED_EDGE('',*,*,#98084,.T.); -#98185 = ORIENTED_EDGE('',*,*,#98186,.F.); -#98186 = EDGE_CURVE('',#98138,#98058,#98187,.T.); -#98187 = SURFACE_CURVE('',#98188,(#98192,#98199),.PCURVE_S1.); -#98188 = LINE('',#98189,#98190); -#98189 = CARTESIAN_POINT('',(2.65,-0.419594812019,0.530776333563)); -#98190 = VECTOR('',#98191,1.); -#98191 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98192 = PCURVE('',#98099,#98193); -#98193 = DEFINITIONAL_REPRESENTATION('',(#98194),#98198); -#98194 = LINE('',#98195,#98196); -#98195 = CARTESIAN_POINT('',(0.E+000,-7.35)); -#98196 = VECTOR('',#98197,1.); -#98197 = DIRECTION('',(1.,0.E+000)); -#98198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98199 = PCURVE('',#89042,#98200); -#98200 = DEFINITIONAL_REPRESENTATION('',(#98201),#98205); -#98201 = LINE('',#98202,#98203); -#98202 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#98203 = VECTOR('',#98204,1.); -#98204 = DIRECTION('',(1.,-1.021336205033E-016)); -#98205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98206 = ADVANCED_FACE('',(#98207),#98020,.F.); -#98207 = FACE_BOUND('',#98208,.T.); -#98208 = EDGE_LOOP('',(#98209,#98238,#98259,#98260)); -#98209 = ORIENTED_EDGE('',*,*,#98210,.F.); -#98210 = EDGE_CURVE('',#98211,#98213,#98215,.T.); -#98211 = VERTEX_POINT('',#98212); -#98212 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.530776333563)); -#98213 = VERTEX_POINT('',#98214); -#98214 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.530776333563)); -#98215 = SURFACE_CURVE('',#98216,(#98220,#98227),.PCURVE_S1.); -#98216 = LINE('',#98217,#98218); -#98217 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#98218 = VECTOR('',#98219,1.); -#98219 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98220 = PCURVE('',#98020,#98221); -#98221 = DEFINITIONAL_REPRESENTATION('',(#98222),#98226); -#98222 = LINE('',#98223,#98224); -#98223 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98224 = VECTOR('',#98225,1.); -#98225 = DIRECTION('',(0.E+000,1.)); -#98226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98227 = PCURVE('',#98228,#98233); -#98228 = CYLINDRICAL_SURFACE('',#98229,0.2192697516); -#98229 = AXIS2_PLACEMENT_3D('',#98230,#98231,#98232); -#98230 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#98231 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98232 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98233 = DEFINITIONAL_REPRESENTATION('',(#98234),#98237); -#98234 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98235,#98236),.UNSPECIFIED., - .F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#98235 = CARTESIAN_POINT('',(4.712388980385,-7.35)); -#98236 = CARTESIAN_POINT('',(4.712388980385,-7.15)); -#98237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98238 = ORIENTED_EDGE('',*,*,#98239,.T.); -#98239 = EDGE_CURVE('',#98211,#97979,#98240,.T.); -#98240 = SURFACE_CURVE('',#98241,(#98245,#98252),.PCURVE_S1.); -#98241 = LINE('',#98242,#98243); -#98242 = CARTESIAN_POINT('',(2.65,-0.51959417205,0.530776333563)); -#98243 = VECTOR('',#98244,1.); -#98244 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98245 = PCURVE('',#98020,#98246); -#98246 = DEFINITIONAL_REPRESENTATION('',(#98247),#98251); -#98247 = LINE('',#98248,#98249); -#98248 = CARTESIAN_POINT('',(0.E+000,-7.35)); -#98249 = VECTOR('',#98250,1.); -#98250 = DIRECTION('',(-1.,0.E+000)); -#98251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98252 = PCURVE('',#89042,#98253); -#98253 = DEFINITIONAL_REPRESENTATION('',(#98254),#98258); -#98254 = LINE('',#98255,#98256); -#98255 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#98256 = VECTOR('',#98257,1.); -#98257 = DIRECTION('',(1.,-1.021336205033E-016)); -#98258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98259 = ORIENTED_EDGE('',*,*,#98005,.T.); -#98260 = ORIENTED_EDGE('',*,*,#98261,.F.); -#98261 = EDGE_CURVE('',#98213,#98006,#98262,.T.); -#98262 = SURFACE_CURVE('',#98263,(#98267,#98274),.PCURVE_S1.); -#98263 = LINE('',#98264,#98265); -#98264 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.530776333563)); -#98265 = VECTOR('',#98266,1.); -#98266 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98267 = PCURVE('',#98020,#98268); -#98268 = DEFINITIONAL_REPRESENTATION('',(#98269),#98273); -#98269 = LINE('',#98270,#98271); -#98270 = CARTESIAN_POINT('',(0.E+000,-7.15)); -#98271 = VECTOR('',#98272,1.); -#98272 = DIRECTION('',(-1.,0.E+000)); -#98273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98274 = PCURVE('',#88986,#98275); -#98275 = DEFINITIONAL_REPRESENTATION('',(#98276),#98280); -#98276 = LINE('',#98277,#98278); -#98277 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#98278 = VECTOR('',#98279,1.); -#98279 = DIRECTION('',(-1.,-1.021336205033E-016)); -#98280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100644 = PCURVE('',#91434,#100645); +#100645 = DEFINITIONAL_REPRESENTATION('',(#100646),#100650); +#100646 = LINE('',#100647,#100648); +#100647 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#100648 = VECTOR('',#100649,1.); +#100649 = DIRECTION('',(1.,-1.021336205033E-016)); +#100650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98281 = ADVANCED_FACE('',(#98282),#98153,.F.); -#98282 = FACE_BOUND('',#98283,.F.); -#98283 = EDGE_LOOP('',(#98284,#98311,#98333,#98354)); -#98284 = ORIENTED_EDGE('',*,*,#98285,.F.); -#98285 = EDGE_CURVE('',#98286,#98136,#98288,.T.); -#98286 = VERTEX_POINT('',#98287); -#98287 = CARTESIAN_POINT('',(2.85,-0.303662633502,0.65)); -#98288 = SURFACE_CURVE('',#98289,(#98294,#98300),.PCURVE_S1.); -#98289 = CIRCLE('',#98290,0.119270391569); -#98290 = AXIS2_PLACEMENT_3D('',#98291,#98292,#98293); -#98291 = CARTESIAN_POINT('',(2.85,-0.30032442045,0.530776333563)); -#98292 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98293 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98294 = PCURVE('',#98153,#98295); -#98295 = DEFINITIONAL_REPRESENTATION('',(#98296),#98299); -#98296 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98297,#98298),.UNSPECIFIED., - .F.,.F.,(2,2),(3.169584923929,4.712388980385), +#100651 = ORIENTED_EDGE('',*,*,#100397,.T.); +#100652 = ORIENTED_EDGE('',*,*,#100653,.F.); +#100653 = EDGE_CURVE('',#100605,#100398,#100654,.T.); +#100654 = SURFACE_CURVE('',#100655,(#100659,#100666),.PCURVE_S1.); +#100655 = LINE('',#100656,#100657); +#100656 = CARTESIAN_POINT('',(2.85,-0.51959417205,0.530776333563)); +#100657 = VECTOR('',#100658,1.); +#100658 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#100659 = PCURVE('',#100412,#100660); +#100660 = DEFINITIONAL_REPRESENTATION('',(#100661),#100665); +#100661 = LINE('',#100662,#100663); +#100662 = CARTESIAN_POINT('',(0.E+000,-7.15)); +#100663 = VECTOR('',#100664,1.); +#100664 = DIRECTION('',(-1.,0.E+000)); +#100665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100666 = PCURVE('',#91378,#100667); +#100667 = DEFINITIONAL_REPRESENTATION('',(#100668),#100672); +#100668 = LINE('',#100669,#100670); +#100669 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#100670 = VECTOR('',#100671,1.); +#100671 = DIRECTION('',(-1.,-1.021336205033E-016)); +#100672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100673 = ADVANCED_FACE('',(#100674),#100545,.F.); +#100674 = FACE_BOUND('',#100675,.F.); +#100675 = EDGE_LOOP('',(#100676,#100703,#100725,#100746)); +#100676 = ORIENTED_EDGE('',*,*,#100677,.F.); +#100677 = EDGE_CURVE('',#100678,#100528,#100680,.T.); +#100678 = VERTEX_POINT('',#100679); +#100679 = CARTESIAN_POINT('',(2.85,-0.303662633502,0.65)); +#100680 = SURFACE_CURVE('',#100681,(#100686,#100692),.PCURVE_S1.); +#100681 = CIRCLE('',#100682,0.119270391569); +#100682 = AXIS2_PLACEMENT_3D('',#100683,#100684,#100685); +#100683 = CARTESIAN_POINT('',(2.85,-0.30032442045,0.530776333563)); +#100684 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100685 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100686 = PCURVE('',#100545,#100687); +#100687 = DEFINITIONAL_REPRESENTATION('',(#100688),#100691); +#100688 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100689,#100690), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#98297 = CARTESIAN_POINT('',(3.169584923929,-7.15)); -#98298 = CARTESIAN_POINT('',(4.712388980385,-7.15)); -#98299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100689 = CARTESIAN_POINT('',(3.169584923929,-7.15)); +#100690 = CARTESIAN_POINT('',(4.712388980385,-7.15)); +#100691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98300 = PCURVE('',#88986,#98301); -#98301 = DEFINITIONAL_REPRESENTATION('',(#98302),#98310); -#98302 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98303,#98304,#98305,#98306 - ,#98307,#98308,#98309),.UNSPECIFIED.,.F.,.F.) +#100692 = PCURVE('',#91378,#100693); +#100693 = DEFINITIONAL_REPRESENTATION('',(#100694),#100702); +#100694 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100695,#100696,#100697, + #100698,#100699,#100700,#100701),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#98303 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#98304 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#98305 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#98306 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#98307 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#98308 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#98309 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#98310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98311 = ORIENTED_EDGE('',*,*,#98312,.F.); -#98312 = EDGE_CURVE('',#98313,#98286,#98315,.T.); -#98313 = VERTEX_POINT('',#98314); -#98314 = CARTESIAN_POINT('',(2.65,-0.303662633502,0.65)); -#98315 = SURFACE_CURVE('',#98316,(#98320,#98326),.PCURVE_S1.); -#98316 = LINE('',#98317,#98318); -#98317 = CARTESIAN_POINT('',(2.85,-0.303662633502,0.65)); -#98318 = VECTOR('',#98319,1.); -#98319 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98320 = PCURVE('',#98153,#98321); -#98321 = DEFINITIONAL_REPRESENTATION('',(#98322),#98325); -#98322 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98323,#98324),.UNSPECIFIED., - .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#98323 = CARTESIAN_POINT('',(3.169584923929,-7.35)); -#98324 = CARTESIAN_POINT('',(3.169584923929,-7.15)); -#98325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98326 = PCURVE('',#89014,#98327); -#98327 = DEFINITIONAL_REPRESENTATION('',(#98328),#98332); -#98328 = LINE('',#98329,#98330); -#98329 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#98330 = VECTOR('',#98331,1.); -#98331 = DIRECTION('',(0.E+000,1.)); -#98332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98333 = ORIENTED_EDGE('',*,*,#98334,.T.); -#98334 = EDGE_CURVE('',#98313,#98138,#98335,.T.); -#98335 = SURFACE_CURVE('',#98336,(#98341,#98347),.PCURVE_S1.); -#98336 = CIRCLE('',#98337,0.119270391569); -#98337 = AXIS2_PLACEMENT_3D('',#98338,#98339,#98340); -#98338 = CARTESIAN_POINT('',(2.65,-0.30032442045,0.530776333563)); -#98339 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98340 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98341 = PCURVE('',#98153,#98342); -#98342 = DEFINITIONAL_REPRESENTATION('',(#98343),#98346); -#98343 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98344,#98345),.UNSPECIFIED., - .F.,.F.,(2,2),(3.169584923929,4.712388980385), +#100695 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#100696 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#100697 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#100698 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#100699 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#100700 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#100701 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#100702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100703 = ORIENTED_EDGE('',*,*,#100704,.F.); +#100704 = EDGE_CURVE('',#100705,#100678,#100707,.T.); +#100705 = VERTEX_POINT('',#100706); +#100706 = CARTESIAN_POINT('',(2.65,-0.303662633502,0.65)); +#100707 = SURFACE_CURVE('',#100708,(#100712,#100718),.PCURVE_S1.); +#100708 = LINE('',#100709,#100710); +#100709 = CARTESIAN_POINT('',(2.85,-0.303662633502,0.65)); +#100710 = VECTOR('',#100711,1.); +#100711 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100712 = PCURVE('',#100545,#100713); +#100713 = DEFINITIONAL_REPRESENTATION('',(#100714),#100717); +#100714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100715,#100716), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); +#100715 = CARTESIAN_POINT('',(3.169584923929,-7.35)); +#100716 = CARTESIAN_POINT('',(3.169584923929,-7.15)); +#100717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100718 = PCURVE('',#91406,#100719); +#100719 = DEFINITIONAL_REPRESENTATION('',(#100720),#100724); +#100720 = LINE('',#100721,#100722); +#100721 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#100722 = VECTOR('',#100723,1.); +#100723 = DIRECTION('',(0.E+000,1.)); +#100724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100725 = ORIENTED_EDGE('',*,*,#100726,.T.); +#100726 = EDGE_CURVE('',#100705,#100530,#100727,.T.); +#100727 = SURFACE_CURVE('',#100728,(#100733,#100739),.PCURVE_S1.); +#100728 = CIRCLE('',#100729,0.119270391569); +#100729 = AXIS2_PLACEMENT_3D('',#100730,#100731,#100732); +#100730 = CARTESIAN_POINT('',(2.65,-0.30032442045,0.530776333563)); +#100731 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100732 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100733 = PCURVE('',#100545,#100734); +#100734 = DEFINITIONAL_REPRESENTATION('',(#100735),#100738); +#100735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100736,#100737), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#98344 = CARTESIAN_POINT('',(3.169584923929,-7.35)); -#98345 = CARTESIAN_POINT('',(4.712388980385,-7.35)); -#98346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98347 = PCURVE('',#89042,#98348); -#98348 = DEFINITIONAL_REPRESENTATION('',(#98349),#98353); -#98349 = CIRCLE('',#98350,0.119270391569); -#98350 = AXIS2_PLACEMENT_2D('',#98351,#98352); -#98351 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#98352 = DIRECTION('',(1.,0.E+000)); -#98353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98354 = ORIENTED_EDGE('',*,*,#98135,.F.); -#98355 = ADVANCED_FACE('',(#98356),#98228,.T.); -#98356 = FACE_BOUND('',#98357,.T.); -#98357 = EDGE_LOOP('',(#98358,#98381,#98382,#98409)); -#98358 = ORIENTED_EDGE('',*,*,#98359,.T.); -#98359 = EDGE_CURVE('',#98360,#98211,#98362,.T.); -#98360 = VERTEX_POINT('',#98361); -#98361 = CARTESIAN_POINT('',(2.65,-0.304819755875,0.75)); -#98362 = SURFACE_CURVE('',#98363,(#98368,#98374),.PCURVE_S1.); -#98363 = CIRCLE('',#98364,0.2192697516); -#98364 = AXIS2_PLACEMENT_3D('',#98365,#98366,#98367); -#98365 = CARTESIAN_POINT('',(2.65,-0.30032442045,0.530776333563)); -#98366 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98367 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98368 = PCURVE('',#98228,#98369); -#98369 = DEFINITIONAL_REPRESENTATION('',(#98370),#98373); -#98370 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98371,#98372),.UNSPECIFIED., - .F.,.F.,(2,2),(3.162095483347,4.712388980385), +#100736 = CARTESIAN_POINT('',(3.169584923929,-7.35)); +#100737 = CARTESIAN_POINT('',(4.712388980385,-7.35)); +#100738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100739 = PCURVE('',#91434,#100740); +#100740 = DEFINITIONAL_REPRESENTATION('',(#100741),#100745); +#100741 = CIRCLE('',#100742,0.119270391569); +#100742 = AXIS2_PLACEMENT_2D('',#100743,#100744); +#100743 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#100744 = DIRECTION('',(1.,0.E+000)); +#100745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100746 = ORIENTED_EDGE('',*,*,#100527,.F.); +#100747 = ADVANCED_FACE('',(#100748),#100620,.T.); +#100748 = FACE_BOUND('',#100749,.T.); +#100749 = EDGE_LOOP('',(#100750,#100773,#100774,#100801)); +#100750 = ORIENTED_EDGE('',*,*,#100751,.T.); +#100751 = EDGE_CURVE('',#100752,#100603,#100754,.T.); +#100752 = VERTEX_POINT('',#100753); +#100753 = CARTESIAN_POINT('',(2.65,-0.304819755875,0.75)); +#100754 = SURFACE_CURVE('',#100755,(#100760,#100766),.PCURVE_S1.); +#100755 = CIRCLE('',#100756,0.2192697516); +#100756 = AXIS2_PLACEMENT_3D('',#100757,#100758,#100759); +#100757 = CARTESIAN_POINT('',(2.65,-0.30032442045,0.530776333563)); +#100758 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100759 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100760 = PCURVE('',#100620,#100761); +#100761 = DEFINITIONAL_REPRESENTATION('',(#100762),#100765); +#100762 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100763,#100764), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#98371 = CARTESIAN_POINT('',(3.162095483347,-7.35)); -#98372 = CARTESIAN_POINT('',(4.712388980385,-7.35)); -#98373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98374 = PCURVE('',#89042,#98375); -#98375 = DEFINITIONAL_REPRESENTATION('',(#98376),#98380); -#98376 = CIRCLE('',#98377,0.2192697516); -#98377 = AXIS2_PLACEMENT_2D('',#98378,#98379); -#98378 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#98379 = DIRECTION('',(1.,0.E+000)); -#98380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98381 = ORIENTED_EDGE('',*,*,#98210,.T.); -#98382 = ORIENTED_EDGE('',*,*,#98383,.F.); -#98383 = EDGE_CURVE('',#98384,#98213,#98386,.T.); -#98384 = VERTEX_POINT('',#98385); -#98385 = CARTESIAN_POINT('',(2.85,-0.304819755875,0.75)); -#98386 = SURFACE_CURVE('',#98387,(#98392,#98398),.PCURVE_S1.); -#98387 = CIRCLE('',#98388,0.2192697516); -#98388 = AXIS2_PLACEMENT_3D('',#98389,#98390,#98391); -#98389 = CARTESIAN_POINT('',(2.85,-0.30032442045,0.530776333563)); -#98390 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98391 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98392 = PCURVE('',#98228,#98393); -#98393 = DEFINITIONAL_REPRESENTATION('',(#98394),#98397); -#98394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98395,#98396),.UNSPECIFIED., - .F.,.F.,(2,2),(3.162095483347,4.712388980385), +#100763 = CARTESIAN_POINT('',(3.162095483347,-7.35)); +#100764 = CARTESIAN_POINT('',(4.712388980385,-7.35)); +#100765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100766 = PCURVE('',#91434,#100767); +#100767 = DEFINITIONAL_REPRESENTATION('',(#100768),#100772); +#100768 = CIRCLE('',#100769,0.2192697516); +#100769 = AXIS2_PLACEMENT_2D('',#100770,#100771); +#100770 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#100771 = DIRECTION('',(1.,0.E+000)); +#100772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100773 = ORIENTED_EDGE('',*,*,#100602,.T.); +#100774 = ORIENTED_EDGE('',*,*,#100775,.F.); +#100775 = EDGE_CURVE('',#100776,#100605,#100778,.T.); +#100776 = VERTEX_POINT('',#100777); +#100777 = CARTESIAN_POINT('',(2.85,-0.304819755875,0.75)); +#100778 = SURFACE_CURVE('',#100779,(#100784,#100790),.PCURVE_S1.); +#100779 = CIRCLE('',#100780,0.2192697516); +#100780 = AXIS2_PLACEMENT_3D('',#100781,#100782,#100783); +#100781 = CARTESIAN_POINT('',(2.85,-0.30032442045,0.530776333563)); +#100782 = DIRECTION('',(1.,0.E+000,0.E+000)); +#100783 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#100784 = PCURVE('',#100620,#100785); +#100785 = DEFINITIONAL_REPRESENTATION('',(#100786),#100789); +#100786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100787,#100788), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#98395 = CARTESIAN_POINT('',(3.162095483347,-7.15)); -#98396 = CARTESIAN_POINT('',(4.712388980385,-7.15)); -#98397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#100787 = CARTESIAN_POINT('',(3.162095483347,-7.15)); +#100788 = CARTESIAN_POINT('',(4.712388980385,-7.15)); +#100789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98398 = PCURVE('',#88986,#98399); -#98399 = DEFINITIONAL_REPRESENTATION('',(#98400),#98408); -#98400 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98401,#98402,#98403,#98404 - ,#98405,#98406,#98407),.UNSPECIFIED.,.T.,.F.) +#100790 = PCURVE('',#91378,#100791); +#100791 = DEFINITIONAL_REPRESENTATION('',(#100792),#100800); +#100792 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100793,#100794,#100795, + #100796,#100797,#100798,#100799),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#98401 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#98402 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#98403 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#98404 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#98405 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#98406 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#98407 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#98408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98409 = ORIENTED_EDGE('',*,*,#98410,.T.); -#98410 = EDGE_CURVE('',#98384,#98360,#98411,.T.); -#98411 = SURFACE_CURVE('',#98412,(#98416,#98422),.PCURVE_S1.); -#98412 = LINE('',#98413,#98414); -#98413 = CARTESIAN_POINT('',(2.85,-0.304819755875,0.75)); -#98414 = VECTOR('',#98415,1.); -#98415 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98416 = PCURVE('',#98228,#98417); -#98417 = DEFINITIONAL_REPRESENTATION('',(#98418),#98421); -#98418 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98419,#98420),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#98419 = CARTESIAN_POINT('',(3.162095483347,-7.15)); -#98420 = CARTESIAN_POINT('',(3.162095483347,-7.35)); -#98421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98422 = PCURVE('',#89068,#98423); -#98423 = DEFINITIONAL_REPRESENTATION('',(#98424),#98428); -#98424 = LINE('',#98425,#98426); -#98425 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#98426 = VECTOR('',#98427,1.); -#98427 = DIRECTION('',(0.E+000,-1.)); -#98428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98429 = ADVANCED_FACE('',(#98430),#88986,.F.); -#98430 = FACE_BOUND('',#98431,.T.); -#98431 = EDGE_LOOP('',(#98432,#98453,#98454,#98455,#98456,#98457,#98478, - #98479,#98480,#98481,#98482,#98503)); -#98432 = ORIENTED_EDGE('',*,*,#98433,.F.); -#98433 = EDGE_CURVE('',#98384,#88971,#98434,.T.); -#98434 = SURFACE_CURVE('',#98435,(#98439,#98446),.PCURVE_S1.); -#98435 = LINE('',#98436,#98437); -#98436 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.75)); -#98437 = VECTOR('',#98438,1.); -#98438 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#98439 = PCURVE('',#88986,#98440); -#98440 = DEFINITIONAL_REPRESENTATION('',(#98441),#98445); -#98441 = LINE('',#98442,#98443); -#98442 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#98443 = VECTOR('',#98444,1.); -#98444 = DIRECTION('',(3.563627120235E-016,1.)); -#98445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98446 = PCURVE('',#89068,#98447); -#98447 = DEFINITIONAL_REPRESENTATION('',(#98448),#98452); -#98448 = LINE('',#98449,#98450); -#98449 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98450 = VECTOR('',#98451,1.); -#98451 = DIRECTION('',(1.,0.E+000)); -#98452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98453 = ORIENTED_EDGE('',*,*,#98383,.T.); -#98454 = ORIENTED_EDGE('',*,*,#98261,.T.); -#98455 = ORIENTED_EDGE('',*,*,#98032,.T.); -#98456 = ORIENTED_EDGE('',*,*,#97822,.T.); -#98457 = ORIENTED_EDGE('',*,*,#98458,.T.); -#98458 = EDGE_CURVE('',#97795,#97876,#98459,.T.); -#98459 = SURFACE_CURVE('',#98460,(#98464,#98471),.PCURVE_S1.); -#98460 = LINE('',#98461,#98462); -#98461 = CARTESIAN_POINT('',(2.85,-1.,1.159810404338E-002)); -#98462 = VECTOR('',#98463,1.); -#98463 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#98464 = PCURVE('',#88986,#98465); -#98465 = DEFINITIONAL_REPRESENTATION('',(#98466),#98470); -#98466 = LINE('',#98467,#98468); -#98467 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#98468 = VECTOR('',#98469,1.); -#98469 = DIRECTION('',(-1.,2.101748079665E-016)); -#98470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98471 = PCURVE('',#97810,#98472); -#98472 = DEFINITIONAL_REPRESENTATION('',(#98473),#98477); -#98473 = LINE('',#98474,#98475); -#98474 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#98475 = VECTOR('',#98476,1.); -#98476 = DIRECTION('',(1.,0.E+000)); -#98477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98478 = ORIENTED_EDGE('',*,*,#97873,.F.); -#98479 = ORIENTED_EDGE('',*,*,#98111,.F.); -#98480 = ORIENTED_EDGE('',*,*,#98164,.F.); -#98481 = ORIENTED_EDGE('',*,*,#98285,.F.); -#98482 = ORIENTED_EDGE('',*,*,#98483,.T.); -#98483 = EDGE_CURVE('',#98286,#88969,#98484,.T.); -#98484 = SURFACE_CURVE('',#98485,(#98489,#98496),.PCURVE_S1.); -#98485 = LINE('',#98486,#98487); -#98486 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); -#98487 = VECTOR('',#98488,1.); -#98488 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#98489 = PCURVE('',#88986,#98490); -#98490 = DEFINITIONAL_REPRESENTATION('',(#98491),#98495); -#98491 = LINE('',#98492,#98493); -#98492 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98493 = VECTOR('',#98494,1.); -#98494 = DIRECTION('',(3.563627120235E-016,1.)); -#98495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98496 = PCURVE('',#89014,#98497); -#98497 = DEFINITIONAL_REPRESENTATION('',(#98498),#98502); -#98498 = LINE('',#98499,#98500); -#98499 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98500 = VECTOR('',#98501,1.); -#98501 = DIRECTION('',(-1.,0.E+000)); -#98502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98503 = ORIENTED_EDGE('',*,*,#88968,.T.); -#98504 = ADVANCED_FACE('',(#98505),#89068,.F.); -#98505 = FACE_BOUND('',#98506,.T.); -#98506 = EDGE_LOOP('',(#98507,#98508,#98509,#98510)); -#98507 = ORIENTED_EDGE('',*,*,#98410,.F.); -#98508 = ORIENTED_EDGE('',*,*,#98433,.T.); -#98509 = ORIENTED_EDGE('',*,*,#89054,.T.); -#98510 = ORIENTED_EDGE('',*,*,#98511,.F.); -#98511 = EDGE_CURVE('',#98360,#89027,#98512,.T.); -#98512 = SURFACE_CURVE('',#98513,(#98517,#98524),.PCURVE_S1.); -#98513 = LINE('',#98514,#98515); -#98514 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.75)); -#98515 = VECTOR('',#98516,1.); -#98516 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#98517 = PCURVE('',#89068,#98518); -#98518 = DEFINITIONAL_REPRESENTATION('',(#98519),#98523); -#98519 = LINE('',#98520,#98521); -#98520 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#98521 = VECTOR('',#98522,1.); -#98522 = DIRECTION('',(1.,0.E+000)); -#98523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98524 = PCURVE('',#89042,#98525); -#98525 = DEFINITIONAL_REPRESENTATION('',(#98526),#98530); -#98526 = LINE('',#98527,#98528); -#98527 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#98528 = VECTOR('',#98529,1.); -#98529 = DIRECTION('',(-3.563627120235E-016,1.)); -#98530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98531 = ADVANCED_FACE('',(#98532),#89042,.F.); -#98532 = FACE_BOUND('',#98533,.T.); -#98533 = EDGE_LOOP('',(#98534,#98555,#98556,#98557,#98558,#98559,#98580, - #98581,#98582,#98583,#98584,#98585)); -#98534 = ORIENTED_EDGE('',*,*,#98535,.F.); -#98535 = EDGE_CURVE('',#98313,#88999,#98536,.T.); -#98536 = SURFACE_CURVE('',#98537,(#98541,#98548),.PCURVE_S1.); -#98537 = LINE('',#98538,#98539); -#98538 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.65)); -#98539 = VECTOR('',#98540,1.); -#98540 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#98541 = PCURVE('',#89042,#98542); -#98542 = DEFINITIONAL_REPRESENTATION('',(#98543),#98547); -#98543 = LINE('',#98544,#98545); -#98544 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98545 = VECTOR('',#98546,1.); -#98546 = DIRECTION('',(-3.563627120235E-016,1.)); -#98547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98548 = PCURVE('',#89014,#98549); -#98549 = DEFINITIONAL_REPRESENTATION('',(#98550),#98554); -#98550 = LINE('',#98551,#98552); -#98551 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#98552 = VECTOR('',#98553,1.); -#98553 = DIRECTION('',(-1.,0.E+000)); -#98554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98555 = ORIENTED_EDGE('',*,*,#98334,.T.); -#98556 = ORIENTED_EDGE('',*,*,#98186,.T.); -#98557 = ORIENTED_EDGE('',*,*,#98057,.T.); -#98558 = ORIENTED_EDGE('',*,*,#97926,.T.); -#98559 = ORIENTED_EDGE('',*,*,#98560,.T.); -#98560 = EDGE_CURVE('',#97904,#97767,#98561,.T.); -#98561 = SURFACE_CURVE('',#98562,(#98566,#98573),.PCURVE_S1.); -#98562 = LINE('',#98563,#98564); -#98563 = CARTESIAN_POINT('',(2.65,-1.,1.159810404338E-002)); -#98564 = VECTOR('',#98565,1.); -#98565 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#98566 = PCURVE('',#89042,#98567); -#98567 = DEFINITIONAL_REPRESENTATION('',(#98568),#98572); -#98568 = LINE('',#98569,#98570); -#98569 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#98570 = VECTOR('',#98571,1.); -#98571 = DIRECTION('',(-1.,-2.101748079665E-016)); -#98572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98573 = PCURVE('',#97810,#98574); -#98574 = DEFINITIONAL_REPRESENTATION('',(#98575),#98579); -#98575 = LINE('',#98576,#98577); -#98576 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#98577 = VECTOR('',#98578,1.); -#98578 = DIRECTION('',(-1.,0.E+000)); -#98579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98580 = ORIENTED_EDGE('',*,*,#97764,.F.); -#98581 = ORIENTED_EDGE('',*,*,#97978,.F.); -#98582 = ORIENTED_EDGE('',*,*,#98239,.F.); -#98583 = ORIENTED_EDGE('',*,*,#98359,.F.); -#98584 = ORIENTED_EDGE('',*,*,#98511,.T.); -#98585 = ORIENTED_EDGE('',*,*,#89026,.T.); -#98586 = ADVANCED_FACE('',(#98587),#89014,.F.); -#98587 = FACE_BOUND('',#98588,.T.); -#98588 = EDGE_LOOP('',(#98589,#98590,#98591,#98592)); -#98589 = ORIENTED_EDGE('',*,*,#98312,.F.); -#98590 = ORIENTED_EDGE('',*,*,#98535,.T.); -#98591 = ORIENTED_EDGE('',*,*,#88998,.T.); -#98592 = ORIENTED_EDGE('',*,*,#98483,.F.); -#98593 = ADVANCED_FACE('',(#98594),#97810,.T.); -#98594 = FACE_BOUND('',#98595,.T.); -#98595 = EDGE_LOOP('',(#98596,#98597,#98598,#98599)); -#98596 = ORIENTED_EDGE('',*,*,#98560,.F.); -#98597 = ORIENTED_EDGE('',*,*,#97903,.F.); -#98598 = ORIENTED_EDGE('',*,*,#98458,.F.); -#98599 = ORIENTED_EDGE('',*,*,#97794,.F.); -#98600 = ADVANCED_FACE('',(#98601),#98615,.T.); -#98601 = FACE_BOUND('',#98602,.T.); -#98602 = EDGE_LOOP('',(#98603,#98633,#98661,#98684)); -#98603 = ORIENTED_EDGE('',*,*,#98604,.T.); -#98604 = EDGE_CURVE('',#98605,#98607,#98609,.T.); -#98605 = VERTEX_POINT('',#98606); -#98606 = CARTESIAN_POINT('',(3.15,-0.740726081328,-0.208196358798)); -#98607 = VERTEX_POINT('',#98608); -#98608 = CARTESIAN_POINT('',(3.15,-1.,-0.208196358798)); -#98609 = SURFACE_CURVE('',#98610,(#98614,#98626),.PCURVE_S1.); -#98610 = LINE('',#98611,#98612); -#98611 = CARTESIAN_POINT('',(3.15,-0.740726081328,-0.208196358798)); -#98612 = VECTOR('',#98613,1.); -#98613 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#98614 = PCURVE('',#98615,#98620); -#98615 = PLANE('',#98616); -#98616 = AXIS2_PLACEMENT_3D('',#98617,#98618,#98619); -#98617 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#98618 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98619 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98620 = DEFINITIONAL_REPRESENTATION('',(#98621),#98625); -#98621 = LINE('',#98622,#98623); -#98622 = CARTESIAN_POINT('',(-6.85,0.E+000)); -#98623 = VECTOR('',#98624,1.); -#98624 = DIRECTION('',(0.E+000,-1.)); -#98625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98626 = PCURVE('',#89721,#98627); -#98627 = DEFINITIONAL_REPRESENTATION('',(#98628),#98632); -#98628 = LINE('',#98629,#98630); -#98629 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#98630 = VECTOR('',#98631,1.); -#98631 = DIRECTION('',(0.E+000,-1.)); -#98632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98633 = ORIENTED_EDGE('',*,*,#98634,.T.); -#98634 = EDGE_CURVE('',#98607,#98635,#98637,.T.); -#98635 = VERTEX_POINT('',#98636); -#98636 = CARTESIAN_POINT('',(3.35,-1.,-0.208196358798)); -#98637 = SURFACE_CURVE('',#98638,(#98642,#98649),.PCURVE_S1.); -#98638 = LINE('',#98639,#98640); -#98639 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#98640 = VECTOR('',#98641,1.); -#98641 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98642 = PCURVE('',#98615,#98643); -#98643 = DEFINITIONAL_REPRESENTATION('',(#98644),#98648); -#98644 = LINE('',#98645,#98646); -#98645 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#98646 = VECTOR('',#98647,1.); -#98647 = DIRECTION('',(1.,0.E+000)); -#98648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98649 = PCURVE('',#98650,#98655); -#98650 = PLANE('',#98651); -#98651 = AXIS2_PLACEMENT_3D('',#98652,#98653,#98654); -#98652 = CARTESIAN_POINT('',(3.25,-1.,-0.258196742327)); -#98653 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#98654 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#98655 = DEFINITIONAL_REPRESENTATION('',(#98656),#98660); -#98656 = LINE('',#98657,#98658); -#98657 = CARTESIAN_POINT('',(-5.000038352949E-002,6.75)); -#98658 = VECTOR('',#98659,1.); -#98659 = DIRECTION('',(0.E+000,1.)); -#98660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98661 = ORIENTED_EDGE('',*,*,#98662,.F.); -#98662 = EDGE_CURVE('',#98663,#98635,#98665,.T.); -#98663 = VERTEX_POINT('',#98664); -#98664 = CARTESIAN_POINT('',(3.35,-0.740726081328,-0.208196358798)); -#98665 = SURFACE_CURVE('',#98666,(#98670,#98677),.PCURVE_S1.); -#98666 = LINE('',#98667,#98668); -#98667 = CARTESIAN_POINT('',(3.35,-0.740726081328,-0.208196358798)); -#98668 = VECTOR('',#98669,1.); -#98669 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#98670 = PCURVE('',#98615,#98671); -#98671 = DEFINITIONAL_REPRESENTATION('',(#98672),#98676); -#98672 = LINE('',#98673,#98674); -#98673 = CARTESIAN_POINT('',(-6.65,0.E+000)); -#98674 = VECTOR('',#98675,1.); -#98675 = DIRECTION('',(0.E+000,-1.)); -#98676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98677 = PCURVE('',#89665,#98678); -#98678 = DEFINITIONAL_REPRESENTATION('',(#98679),#98683); -#98679 = LINE('',#98680,#98681); -#98680 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#98681 = VECTOR('',#98682,1.); -#98682 = DIRECTION('',(0.E+000,-1.)); -#98683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98684 = ORIENTED_EDGE('',*,*,#98685,.T.); -#98685 = EDGE_CURVE('',#98663,#98605,#98686,.T.); -#98686 = SURFACE_CURVE('',#98687,(#98691,#98698),.PCURVE_S1.); -#98687 = LINE('',#98688,#98689); -#98688 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#98689 = VECTOR('',#98690,1.); -#98690 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98691 = PCURVE('',#98615,#98692); -#98692 = DEFINITIONAL_REPRESENTATION('',(#98693),#98697); -#98693 = LINE('',#98694,#98695); -#98694 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98695 = VECTOR('',#98696,1.); -#98696 = DIRECTION('',(-1.,0.E+000)); -#98697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98698 = PCURVE('',#98699,#98704); -#98699 = CYLINDRICAL_SURFACE('',#98700,0.208574704164); -#98700 = AXIS2_PLACEMENT_3D('',#98701,#98702,#98703); -#98701 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#98702 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98703 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98704 = DEFINITIONAL_REPRESENTATION('',(#98705),#98708); -#98705 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98706,#98707),.UNSPECIFIED., - .F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#98706 = CARTESIAN_POINT('',(3.201833915432,6.65)); -#98707 = CARTESIAN_POINT('',(3.201833915432,6.85)); -#98708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98709 = ADVANCED_FACE('',(#98710),#98724,.T.); -#98710 = FACE_BOUND('',#98711,.T.); -#98711 = EDGE_LOOP('',(#98712,#98742,#98765,#98788)); -#98712 = ORIENTED_EDGE('',*,*,#98713,.T.); -#98713 = EDGE_CURVE('',#98714,#98716,#98718,.T.); -#98714 = VERTEX_POINT('',#98715); -#98715 = CARTESIAN_POINT('',(3.35,-0.74341632541,-0.308197125857)); -#98716 = VERTEX_POINT('',#98717); -#98717 = CARTESIAN_POINT('',(3.35,-1.,-0.308197125857)); -#98718 = SURFACE_CURVE('',#98719,(#98723,#98735),.PCURVE_S1.); -#98719 = LINE('',#98720,#98721); -#98720 = CARTESIAN_POINT('',(3.35,-0.74341632541,-0.308197125857)); -#98721 = VECTOR('',#98722,1.); -#98722 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#98723 = PCURVE('',#98724,#98729); -#98724 = PLANE('',#98725); -#98725 = AXIS2_PLACEMENT_3D('',#98726,#98727,#98728); -#98726 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#98727 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98728 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98729 = DEFINITIONAL_REPRESENTATION('',(#98730),#98734); -#98730 = LINE('',#98731,#98732); -#98731 = CARTESIAN_POINT('',(6.65,0.E+000)); -#98732 = VECTOR('',#98733,1.); -#98733 = DIRECTION('',(0.E+000,-1.)); -#98734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98735 = PCURVE('',#89665,#98736); -#98736 = DEFINITIONAL_REPRESENTATION('',(#98737),#98741); -#98737 = LINE('',#98738,#98739); -#98738 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#98739 = VECTOR('',#98740,1.); -#98740 = DIRECTION('',(0.E+000,-1.)); -#98741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98742 = ORIENTED_EDGE('',*,*,#98743,.T.); -#98743 = EDGE_CURVE('',#98716,#98744,#98746,.T.); -#98744 = VERTEX_POINT('',#98745); -#98745 = CARTESIAN_POINT('',(3.15,-1.,-0.308197125857)); -#98746 = SURFACE_CURVE('',#98747,(#98751,#98758),.PCURVE_S1.); -#98747 = LINE('',#98748,#98749); -#98748 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#98749 = VECTOR('',#98750,1.); -#98750 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98751 = PCURVE('',#98724,#98752); -#98752 = DEFINITIONAL_REPRESENTATION('',(#98753),#98757); -#98753 = LINE('',#98754,#98755); -#98754 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#98755 = VECTOR('',#98756,1.); -#98756 = DIRECTION('',(1.,0.E+000)); -#98757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98758 = PCURVE('',#98650,#98759); -#98759 = DEFINITIONAL_REPRESENTATION('',(#98760),#98764); -#98760 = LINE('',#98761,#98762); -#98761 = CARTESIAN_POINT('',(5.000038352949E-002,6.75)); -#98762 = VECTOR('',#98763,1.); -#98763 = DIRECTION('',(0.E+000,-1.)); -#98764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98765 = ORIENTED_EDGE('',*,*,#98766,.F.); -#98766 = EDGE_CURVE('',#98767,#98744,#98769,.T.); -#98767 = VERTEX_POINT('',#98768); -#98768 = CARTESIAN_POINT('',(3.15,-0.74341632541,-0.308197125857)); -#98769 = SURFACE_CURVE('',#98770,(#98774,#98781),.PCURVE_S1.); -#98770 = LINE('',#98771,#98772); -#98771 = CARTESIAN_POINT('',(3.15,-0.74341632541,-0.308197125857)); -#98772 = VECTOR('',#98773,1.); -#98773 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#98774 = PCURVE('',#98724,#98775); -#98775 = DEFINITIONAL_REPRESENTATION('',(#98776),#98780); -#98776 = LINE('',#98777,#98778); -#98777 = CARTESIAN_POINT('',(6.85,0.E+000)); -#98778 = VECTOR('',#98779,1.); -#98779 = DIRECTION('',(0.E+000,-1.)); -#98780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98781 = PCURVE('',#89721,#98782); -#98782 = DEFINITIONAL_REPRESENTATION('',(#98783),#98787); -#98783 = LINE('',#98784,#98785); -#98784 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#98785 = VECTOR('',#98786,1.); -#98786 = DIRECTION('',(0.E+000,-1.)); -#98787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98788 = ORIENTED_EDGE('',*,*,#98789,.T.); -#98789 = EDGE_CURVE('',#98767,#98714,#98790,.T.); -#98790 = SURFACE_CURVE('',#98791,(#98795,#98802),.PCURVE_S1.); -#98791 = LINE('',#98792,#98793); -#98792 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#98793 = VECTOR('',#98794,1.); -#98794 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98795 = PCURVE('',#98724,#98796); -#98796 = DEFINITIONAL_REPRESENTATION('',(#98797),#98801); -#98797 = LINE('',#98798,#98799); -#98798 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98799 = VECTOR('',#98800,1.); -#98800 = DIRECTION('',(-1.,0.E+000)); -#98801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98802 = PCURVE('',#98803,#98808); -#98803 = CYLINDRICAL_SURFACE('',#98804,0.308574064194); -#98804 = AXIS2_PLACEMENT_3D('',#98805,#98806,#98807); -#98805 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#98806 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98807 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98808 = DEFINITIONAL_REPRESENTATION('',(#98809),#98812); -#98809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98810,#98811),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#98810 = CARTESIAN_POINT('',(3.191025391152,6.85)); -#98811 = CARTESIAN_POINT('',(3.191025391152,6.65)); -#98812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98813 = ADVANCED_FACE('',(#98814),#98699,.F.); -#98814 = FACE_BOUND('',#98815,.F.); -#98815 = EDGE_LOOP('',(#98816,#98817,#98844,#98871)); -#98816 = ORIENTED_EDGE('',*,*,#98685,.T.); -#98817 = ORIENTED_EDGE('',*,*,#98818,.F.); -#98818 = EDGE_CURVE('',#98819,#98605,#98821,.T.); -#98819 = VERTEX_POINT('',#98820); -#98820 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.E+000)); -#98821 = SURFACE_CURVE('',#98822,(#98827,#98833),.PCURVE_S1.); -#98822 = CIRCLE('',#98823,0.208574704164); -#98823 = AXIS2_PLACEMENT_3D('',#98824,#98825,#98826); -#98824 = CARTESIAN_POINT('',(3.15,-0.728168876214,2.640924866458E-017)); -#98825 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98826 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98827 = PCURVE('',#98699,#98828); -#98828 = DEFINITIONAL_REPRESENTATION('',(#98829),#98832); -#98829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98830,#98831),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#100793 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#100794 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#100795 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#100796 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#100797 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#100798 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#100799 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#100800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100801 = ORIENTED_EDGE('',*,*,#100802,.T.); +#100802 = EDGE_CURVE('',#100776,#100752,#100803,.T.); +#100803 = SURFACE_CURVE('',#100804,(#100808,#100814),.PCURVE_S1.); +#100804 = LINE('',#100805,#100806); +#100805 = CARTESIAN_POINT('',(2.85,-0.304819755875,0.75)); +#100806 = VECTOR('',#100807,1.); +#100807 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#100808 = PCURVE('',#100620,#100809); +#100809 = DEFINITIONAL_REPRESENTATION('',(#100810),#100813); +#100810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100811,#100812), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#100811 = CARTESIAN_POINT('',(3.162095483347,-7.15)); +#100812 = CARTESIAN_POINT('',(3.162095483347,-7.35)); +#100813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100814 = PCURVE('',#91460,#100815); +#100815 = DEFINITIONAL_REPRESENTATION('',(#100816),#100820); +#100816 = LINE('',#100817,#100818); +#100817 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#100818 = VECTOR('',#100819,1.); +#100819 = DIRECTION('',(0.E+000,-1.)); +#100820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100821 = ADVANCED_FACE('',(#100822),#91378,.F.); +#100822 = FACE_BOUND('',#100823,.T.); +#100823 = EDGE_LOOP('',(#100824,#100845,#100846,#100847,#100848,#100849, + #100870,#100871,#100872,#100873,#100874,#100895)); +#100824 = ORIENTED_EDGE('',*,*,#100825,.F.); +#100825 = EDGE_CURVE('',#100776,#91363,#100826,.T.); +#100826 = SURFACE_CURVE('',#100827,(#100831,#100838),.PCURVE_S1.); +#100827 = LINE('',#100828,#100829); +#100828 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.75)); +#100829 = VECTOR('',#100830,1.); +#100830 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100831 = PCURVE('',#91378,#100832); +#100832 = DEFINITIONAL_REPRESENTATION('',(#100833),#100837); +#100833 = LINE('',#100834,#100835); +#100834 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#100835 = VECTOR('',#100836,1.); +#100836 = DIRECTION('',(3.563627120235E-016,1.)); +#100837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100838 = PCURVE('',#91460,#100839); +#100839 = DEFINITIONAL_REPRESENTATION('',(#100840),#100844); +#100840 = LINE('',#100841,#100842); +#100841 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100842 = VECTOR('',#100843,1.); +#100843 = DIRECTION('',(1.,0.E+000)); +#100844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100845 = ORIENTED_EDGE('',*,*,#100775,.T.); +#100846 = ORIENTED_EDGE('',*,*,#100653,.T.); +#100847 = ORIENTED_EDGE('',*,*,#100424,.T.); +#100848 = ORIENTED_EDGE('',*,*,#100214,.T.); +#100849 = ORIENTED_EDGE('',*,*,#100850,.T.); +#100850 = EDGE_CURVE('',#100187,#100268,#100851,.T.); +#100851 = SURFACE_CURVE('',#100852,(#100856,#100863),.PCURVE_S1.); +#100852 = LINE('',#100853,#100854); +#100853 = CARTESIAN_POINT('',(2.85,-1.,1.159810404338E-002)); +#100854 = VECTOR('',#100855,1.); +#100855 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#100856 = PCURVE('',#91378,#100857); +#100857 = DEFINITIONAL_REPRESENTATION('',(#100858),#100862); +#100858 = LINE('',#100859,#100860); +#100859 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#100860 = VECTOR('',#100861,1.); +#100861 = DIRECTION('',(-1.,2.101748079665E-016)); +#100862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100863 = PCURVE('',#100202,#100864); +#100864 = DEFINITIONAL_REPRESENTATION('',(#100865),#100869); +#100865 = LINE('',#100866,#100867); +#100866 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#100867 = VECTOR('',#100868,1.); +#100868 = DIRECTION('',(1.,0.E+000)); +#100869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100870 = ORIENTED_EDGE('',*,*,#100265,.F.); +#100871 = ORIENTED_EDGE('',*,*,#100503,.F.); +#100872 = ORIENTED_EDGE('',*,*,#100556,.F.); +#100873 = ORIENTED_EDGE('',*,*,#100677,.F.); +#100874 = ORIENTED_EDGE('',*,*,#100875,.T.); +#100875 = EDGE_CURVE('',#100678,#91361,#100876,.T.); +#100876 = SURFACE_CURVE('',#100877,(#100881,#100888),.PCURVE_S1.); +#100877 = LINE('',#100878,#100879); +#100878 = CARTESIAN_POINT('',(2.85,-0.527847992439,0.65)); +#100879 = VECTOR('',#100880,1.); +#100880 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100881 = PCURVE('',#91378,#100882); +#100882 = DEFINITIONAL_REPRESENTATION('',(#100883),#100887); +#100883 = LINE('',#100884,#100885); +#100884 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100885 = VECTOR('',#100886,1.); +#100886 = DIRECTION('',(3.563627120235E-016,1.)); +#100887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100888 = PCURVE('',#91406,#100889); +#100889 = DEFINITIONAL_REPRESENTATION('',(#100890),#100894); +#100890 = LINE('',#100891,#100892); +#100891 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100892 = VECTOR('',#100893,1.); +#100893 = DIRECTION('',(-1.,0.E+000)); +#100894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100895 = ORIENTED_EDGE('',*,*,#91360,.T.); +#100896 = ADVANCED_FACE('',(#100897),#91460,.F.); +#100897 = FACE_BOUND('',#100898,.T.); +#100898 = EDGE_LOOP('',(#100899,#100900,#100901,#100902)); +#100899 = ORIENTED_EDGE('',*,*,#100802,.F.); +#100900 = ORIENTED_EDGE('',*,*,#100825,.T.); +#100901 = ORIENTED_EDGE('',*,*,#91446,.T.); +#100902 = ORIENTED_EDGE('',*,*,#100903,.F.); +#100903 = EDGE_CURVE('',#100752,#91419,#100904,.T.); +#100904 = SURFACE_CURVE('',#100905,(#100909,#100916),.PCURVE_S1.); +#100905 = LINE('',#100906,#100907); +#100906 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.75)); +#100907 = VECTOR('',#100908,1.); +#100908 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100909 = PCURVE('',#91460,#100910); +#100910 = DEFINITIONAL_REPRESENTATION('',(#100911),#100915); +#100911 = LINE('',#100912,#100913); +#100912 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#100913 = VECTOR('',#100914,1.); +#100914 = DIRECTION('',(1.,0.E+000)); +#100915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100916 = PCURVE('',#91434,#100917); +#100917 = DEFINITIONAL_REPRESENTATION('',(#100918),#100922); +#100918 = LINE('',#100919,#100920); +#100919 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#100920 = VECTOR('',#100921,1.); +#100921 = DIRECTION('',(-3.563627120235E-016,1.)); +#100922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100923 = ADVANCED_FACE('',(#100924),#91434,.F.); +#100924 = FACE_BOUND('',#100925,.T.); +#100925 = EDGE_LOOP('',(#100926,#100947,#100948,#100949,#100950,#100951, + #100972,#100973,#100974,#100975,#100976,#100977)); +#100926 = ORIENTED_EDGE('',*,*,#100927,.F.); +#100927 = EDGE_CURVE('',#100705,#91391,#100928,.T.); +#100928 = SURFACE_CURVE('',#100929,(#100933,#100940),.PCURVE_S1.); +#100929 = LINE('',#100930,#100931); +#100930 = CARTESIAN_POINT('',(2.65,-0.527847992439,0.65)); +#100931 = VECTOR('',#100932,1.); +#100932 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#100933 = PCURVE('',#91434,#100934); +#100934 = DEFINITIONAL_REPRESENTATION('',(#100935),#100939); +#100935 = LINE('',#100936,#100937); +#100936 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#100937 = VECTOR('',#100938,1.); +#100938 = DIRECTION('',(-3.563627120235E-016,1.)); +#100939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100940 = PCURVE('',#91406,#100941); +#100941 = DEFINITIONAL_REPRESENTATION('',(#100942),#100946); +#100942 = LINE('',#100943,#100944); +#100943 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#100944 = VECTOR('',#100945,1.); +#100945 = DIRECTION('',(-1.,0.E+000)); +#100946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100947 = ORIENTED_EDGE('',*,*,#100726,.T.); +#100948 = ORIENTED_EDGE('',*,*,#100578,.T.); +#100949 = ORIENTED_EDGE('',*,*,#100449,.T.); +#100950 = ORIENTED_EDGE('',*,*,#100318,.T.); +#100951 = ORIENTED_EDGE('',*,*,#100952,.T.); +#100952 = EDGE_CURVE('',#100296,#100159,#100953,.T.); +#100953 = SURFACE_CURVE('',#100954,(#100958,#100965),.PCURVE_S1.); +#100954 = LINE('',#100955,#100956); +#100955 = CARTESIAN_POINT('',(2.65,-1.,1.159810404338E-002)); +#100956 = VECTOR('',#100957,1.); +#100957 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#100958 = PCURVE('',#91434,#100959); +#100959 = DEFINITIONAL_REPRESENTATION('',(#100960),#100964); +#100960 = LINE('',#100961,#100962); +#100961 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#100962 = VECTOR('',#100963,1.); +#100963 = DIRECTION('',(-1.,-2.101748079665E-016)); +#100964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100965 = PCURVE('',#100202,#100966); +#100966 = DEFINITIONAL_REPRESENTATION('',(#100967),#100971); +#100967 = LINE('',#100968,#100969); +#100968 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#100969 = VECTOR('',#100970,1.); +#100970 = DIRECTION('',(-1.,0.E+000)); +#100971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#100972 = ORIENTED_EDGE('',*,*,#100156,.F.); +#100973 = ORIENTED_EDGE('',*,*,#100370,.F.); +#100974 = ORIENTED_EDGE('',*,*,#100631,.F.); +#100975 = ORIENTED_EDGE('',*,*,#100751,.F.); +#100976 = ORIENTED_EDGE('',*,*,#100903,.T.); +#100977 = ORIENTED_EDGE('',*,*,#91418,.T.); +#100978 = ADVANCED_FACE('',(#100979),#91406,.F.); +#100979 = FACE_BOUND('',#100980,.T.); +#100980 = EDGE_LOOP('',(#100981,#100982,#100983,#100984)); +#100981 = ORIENTED_EDGE('',*,*,#100704,.F.); +#100982 = ORIENTED_EDGE('',*,*,#100927,.T.); +#100983 = ORIENTED_EDGE('',*,*,#91390,.T.); +#100984 = ORIENTED_EDGE('',*,*,#100875,.F.); +#100985 = ADVANCED_FACE('',(#100986),#100202,.T.); +#100986 = FACE_BOUND('',#100987,.T.); +#100987 = EDGE_LOOP('',(#100988,#100989,#100990,#100991)); +#100988 = ORIENTED_EDGE('',*,*,#100952,.F.); +#100989 = ORIENTED_EDGE('',*,*,#100295,.F.); +#100990 = ORIENTED_EDGE('',*,*,#100850,.F.); +#100991 = ORIENTED_EDGE('',*,*,#100186,.F.); +#100992 = ADVANCED_FACE('',(#100993),#101007,.T.); +#100993 = FACE_BOUND('',#100994,.T.); +#100994 = EDGE_LOOP('',(#100995,#101025,#101053,#101076)); +#100995 = ORIENTED_EDGE('',*,*,#100996,.T.); +#100996 = EDGE_CURVE('',#100997,#100999,#101001,.T.); +#100997 = VERTEX_POINT('',#100998); +#100998 = CARTESIAN_POINT('',(3.15,-0.740726081328,-0.208196358798)); +#100999 = VERTEX_POINT('',#101000); +#101000 = CARTESIAN_POINT('',(3.15,-1.,-0.208196358798)); +#101001 = SURFACE_CURVE('',#101002,(#101006,#101018),.PCURVE_S1.); +#101002 = LINE('',#101003,#101004); +#101003 = CARTESIAN_POINT('',(3.15,-0.740726081328,-0.208196358798)); +#101004 = VECTOR('',#101005,1.); +#101005 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101006 = PCURVE('',#101007,#101012); +#101007 = PLANE('',#101008); +#101008 = AXIS2_PLACEMENT_3D('',#101009,#101010,#101011); +#101009 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#101010 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101011 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101012 = DEFINITIONAL_REPRESENTATION('',(#101013),#101017); +#101013 = LINE('',#101014,#101015); +#101014 = CARTESIAN_POINT('',(-6.85,0.E+000)); +#101015 = VECTOR('',#101016,1.); +#101016 = DIRECTION('',(0.E+000,-1.)); +#101017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101018 = PCURVE('',#92113,#101019); +#101019 = DEFINITIONAL_REPRESENTATION('',(#101020),#101024); +#101020 = LINE('',#101021,#101022); +#101021 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#101022 = VECTOR('',#101023,1.); +#101023 = DIRECTION('',(0.E+000,-1.)); +#101024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101025 = ORIENTED_EDGE('',*,*,#101026,.T.); +#101026 = EDGE_CURVE('',#100999,#101027,#101029,.T.); +#101027 = VERTEX_POINT('',#101028); +#101028 = CARTESIAN_POINT('',(3.35,-1.,-0.208196358798)); +#101029 = SURFACE_CURVE('',#101030,(#101034,#101041),.PCURVE_S1.); +#101030 = LINE('',#101031,#101032); +#101031 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#101032 = VECTOR('',#101033,1.); +#101033 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101034 = PCURVE('',#101007,#101035); +#101035 = DEFINITIONAL_REPRESENTATION('',(#101036),#101040); +#101036 = LINE('',#101037,#101038); +#101037 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#101038 = VECTOR('',#101039,1.); +#101039 = DIRECTION('',(1.,0.E+000)); +#101040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101041 = PCURVE('',#101042,#101047); +#101042 = PLANE('',#101043); +#101043 = AXIS2_PLACEMENT_3D('',#101044,#101045,#101046); +#101044 = CARTESIAN_POINT('',(3.25,-1.,-0.258196742327)); +#101045 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#101046 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#101047 = DEFINITIONAL_REPRESENTATION('',(#101048),#101052); +#101048 = LINE('',#101049,#101050); +#101049 = CARTESIAN_POINT('',(-5.000038352949E-002,6.75)); +#101050 = VECTOR('',#101051,1.); +#101051 = DIRECTION('',(0.E+000,1.)); +#101052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101053 = ORIENTED_EDGE('',*,*,#101054,.F.); +#101054 = EDGE_CURVE('',#101055,#101027,#101057,.T.); +#101055 = VERTEX_POINT('',#101056); +#101056 = CARTESIAN_POINT('',(3.35,-0.740726081328,-0.208196358798)); +#101057 = SURFACE_CURVE('',#101058,(#101062,#101069),.PCURVE_S1.); +#101058 = LINE('',#101059,#101060); +#101059 = CARTESIAN_POINT('',(3.35,-0.740726081328,-0.208196358798)); +#101060 = VECTOR('',#101061,1.); +#101061 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101062 = PCURVE('',#101007,#101063); +#101063 = DEFINITIONAL_REPRESENTATION('',(#101064),#101068); +#101064 = LINE('',#101065,#101066); +#101065 = CARTESIAN_POINT('',(-6.65,0.E+000)); +#101066 = VECTOR('',#101067,1.); +#101067 = DIRECTION('',(0.E+000,-1.)); +#101068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101069 = PCURVE('',#92057,#101070); +#101070 = DEFINITIONAL_REPRESENTATION('',(#101071),#101075); +#101071 = LINE('',#101072,#101073); +#101072 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#101073 = VECTOR('',#101074,1.); +#101074 = DIRECTION('',(0.E+000,-1.)); +#101075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101076 = ORIENTED_EDGE('',*,*,#101077,.T.); +#101077 = EDGE_CURVE('',#101055,#100997,#101078,.T.); +#101078 = SURFACE_CURVE('',#101079,(#101083,#101090),.PCURVE_S1.); +#101079 = LINE('',#101080,#101081); +#101080 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#101081 = VECTOR('',#101082,1.); +#101082 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101083 = PCURVE('',#101007,#101084); +#101084 = DEFINITIONAL_REPRESENTATION('',(#101085),#101089); +#101085 = LINE('',#101086,#101087); +#101086 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101087 = VECTOR('',#101088,1.); +#101088 = DIRECTION('',(-1.,0.E+000)); +#101089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101090 = PCURVE('',#101091,#101096); +#101091 = CYLINDRICAL_SURFACE('',#101092,0.208574704164); +#101092 = AXIS2_PLACEMENT_3D('',#101093,#101094,#101095); +#101093 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#101094 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101095 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101096 = DEFINITIONAL_REPRESENTATION('',(#101097),#101100); +#101097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101098,#101099), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); +#101098 = CARTESIAN_POINT('',(3.201833915432,6.65)); +#101099 = CARTESIAN_POINT('',(3.201833915432,6.85)); +#101100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101101 = ADVANCED_FACE('',(#101102),#101116,.T.); +#101102 = FACE_BOUND('',#101103,.T.); +#101103 = EDGE_LOOP('',(#101104,#101134,#101157,#101180)); +#101104 = ORIENTED_EDGE('',*,*,#101105,.T.); +#101105 = EDGE_CURVE('',#101106,#101108,#101110,.T.); +#101106 = VERTEX_POINT('',#101107); +#101107 = CARTESIAN_POINT('',(3.35,-0.74341632541,-0.308197125857)); +#101108 = VERTEX_POINT('',#101109); +#101109 = CARTESIAN_POINT('',(3.35,-1.,-0.308197125857)); +#101110 = SURFACE_CURVE('',#101111,(#101115,#101127),.PCURVE_S1.); +#101111 = LINE('',#101112,#101113); +#101112 = CARTESIAN_POINT('',(3.35,-0.74341632541,-0.308197125857)); +#101113 = VECTOR('',#101114,1.); +#101114 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101115 = PCURVE('',#101116,#101121); +#101116 = PLANE('',#101117); +#101117 = AXIS2_PLACEMENT_3D('',#101118,#101119,#101120); +#101118 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#101119 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101120 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101121 = DEFINITIONAL_REPRESENTATION('',(#101122),#101126); +#101122 = LINE('',#101123,#101124); +#101123 = CARTESIAN_POINT('',(6.65,0.E+000)); +#101124 = VECTOR('',#101125,1.); +#101125 = DIRECTION('',(0.E+000,-1.)); +#101126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101127 = PCURVE('',#92057,#101128); +#101128 = DEFINITIONAL_REPRESENTATION('',(#101129),#101133); +#101129 = LINE('',#101130,#101131); +#101130 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#101131 = VECTOR('',#101132,1.); +#101132 = DIRECTION('',(0.E+000,-1.)); +#101133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101134 = ORIENTED_EDGE('',*,*,#101135,.T.); +#101135 = EDGE_CURVE('',#101108,#101136,#101138,.T.); +#101136 = VERTEX_POINT('',#101137); +#101137 = CARTESIAN_POINT('',(3.15,-1.,-0.308197125857)); +#101138 = SURFACE_CURVE('',#101139,(#101143,#101150),.PCURVE_S1.); +#101139 = LINE('',#101140,#101141); +#101140 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#101141 = VECTOR('',#101142,1.); +#101142 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101143 = PCURVE('',#101116,#101144); +#101144 = DEFINITIONAL_REPRESENTATION('',(#101145),#101149); +#101145 = LINE('',#101146,#101147); +#101146 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#101147 = VECTOR('',#101148,1.); +#101148 = DIRECTION('',(1.,0.E+000)); +#101149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101150 = PCURVE('',#101042,#101151); +#101151 = DEFINITIONAL_REPRESENTATION('',(#101152),#101156); +#101152 = LINE('',#101153,#101154); +#101153 = CARTESIAN_POINT('',(5.000038352949E-002,6.75)); +#101154 = VECTOR('',#101155,1.); +#101155 = DIRECTION('',(0.E+000,-1.)); +#101156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101157 = ORIENTED_EDGE('',*,*,#101158,.F.); +#101158 = EDGE_CURVE('',#101159,#101136,#101161,.T.); +#101159 = VERTEX_POINT('',#101160); +#101160 = CARTESIAN_POINT('',(3.15,-0.74341632541,-0.308197125857)); +#101161 = SURFACE_CURVE('',#101162,(#101166,#101173),.PCURVE_S1.); +#101162 = LINE('',#101163,#101164); +#101163 = CARTESIAN_POINT('',(3.15,-0.74341632541,-0.308197125857)); +#101164 = VECTOR('',#101165,1.); +#101165 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101166 = PCURVE('',#101116,#101167); +#101167 = DEFINITIONAL_REPRESENTATION('',(#101168),#101172); +#101168 = LINE('',#101169,#101170); +#101169 = CARTESIAN_POINT('',(6.85,0.E+000)); +#101170 = VECTOR('',#101171,1.); +#101171 = DIRECTION('',(0.E+000,-1.)); +#101172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101173 = PCURVE('',#92113,#101174); +#101174 = DEFINITIONAL_REPRESENTATION('',(#101175),#101179); +#101175 = LINE('',#101176,#101177); +#101176 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#101177 = VECTOR('',#101178,1.); +#101178 = DIRECTION('',(0.E+000,-1.)); +#101179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101180 = ORIENTED_EDGE('',*,*,#101181,.T.); +#101181 = EDGE_CURVE('',#101159,#101106,#101182,.T.); +#101182 = SURFACE_CURVE('',#101183,(#101187,#101194),.PCURVE_S1.); +#101183 = LINE('',#101184,#101185); +#101184 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#101185 = VECTOR('',#101186,1.); +#101186 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101187 = PCURVE('',#101116,#101188); +#101188 = DEFINITIONAL_REPRESENTATION('',(#101189),#101193); +#101189 = LINE('',#101190,#101191); +#101190 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101191 = VECTOR('',#101192,1.); +#101192 = DIRECTION('',(-1.,0.E+000)); +#101193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101194 = PCURVE('',#101195,#101200); +#101195 = CYLINDRICAL_SURFACE('',#101196,0.308574064194); +#101196 = AXIS2_PLACEMENT_3D('',#101197,#101198,#101199); +#101197 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#101198 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101199 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101200 = DEFINITIONAL_REPRESENTATION('',(#101201),#101204); +#101201 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101202,#101203), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); +#101202 = CARTESIAN_POINT('',(3.191025391152,6.85)); +#101203 = CARTESIAN_POINT('',(3.191025391152,6.65)); +#101204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101205 = ADVANCED_FACE('',(#101206),#101091,.F.); +#101206 = FACE_BOUND('',#101207,.F.); +#101207 = EDGE_LOOP('',(#101208,#101209,#101236,#101263)); +#101208 = ORIENTED_EDGE('',*,*,#101077,.T.); +#101209 = ORIENTED_EDGE('',*,*,#101210,.F.); +#101210 = EDGE_CURVE('',#101211,#100997,#101213,.T.); +#101211 = VERTEX_POINT('',#101212); +#101212 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.E+000)); +#101213 = SURFACE_CURVE('',#101214,(#101219,#101225),.PCURVE_S1.); +#101214 = CIRCLE('',#101215,0.208574704164); +#101215 = AXIS2_PLACEMENT_3D('',#101216,#101217,#101218); +#101216 = CARTESIAN_POINT('',(3.15,-0.728168876214,2.640924866458E-017) + ); +#101217 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101218 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101219 = PCURVE('',#101091,#101220); +#101220 = DEFINITIONAL_REPRESENTATION('',(#101221),#101224); +#101221 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101222,#101223), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#98830 = CARTESIAN_POINT('',(1.570796326795,6.85)); -#98831 = CARTESIAN_POINT('',(3.201833915432,6.85)); -#98832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101222 = CARTESIAN_POINT('',(1.570796326795,6.85)); +#101223 = CARTESIAN_POINT('',(3.201833915432,6.85)); +#101224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98833 = PCURVE('',#89721,#98834); -#98834 = DEFINITIONAL_REPRESENTATION('',(#98835),#98843); -#98835 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98836,#98837,#98838,#98839 - ,#98840,#98841,#98842),.UNSPECIFIED.,.F.,.F.) +#101225 = PCURVE('',#92113,#101226); +#101226 = DEFINITIONAL_REPRESENTATION('',(#101227),#101235); +#101227 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101228,#101229,#101230, + #101231,#101232,#101233,#101234),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#98836 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#98837 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#98838 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#98839 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#98840 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#98841 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#98842 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#98843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98844 = ORIENTED_EDGE('',*,*,#98845,.T.); -#98845 = EDGE_CURVE('',#98819,#98846,#98848,.T.); -#98846 = VERTEX_POINT('',#98847); -#98847 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.E+000)); -#98848 = SURFACE_CURVE('',#98849,(#98853,#98859),.PCURVE_S1.); -#98849 = LINE('',#98850,#98851); -#98850 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#98851 = VECTOR('',#98852,1.); -#98852 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98853 = PCURVE('',#98699,#98854); -#98854 = DEFINITIONAL_REPRESENTATION('',(#98855),#98858); -#98855 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98856,#98857),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#98856 = CARTESIAN_POINT('',(1.570796326795,6.85)); -#98857 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#98858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98859 = PCURVE('',#98860,#98865); -#98860 = PLANE('',#98861); -#98861 = AXIS2_PLACEMENT_3D('',#98862,#98863,#98864); -#98862 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#98863 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#98864 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#98865 = DEFINITIONAL_REPRESENTATION('',(#98866),#98870); -#98866 = LINE('',#98867,#98868); -#98867 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#98868 = VECTOR('',#98869,1.); -#98869 = DIRECTION('',(0.E+000,1.)); -#98870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98871 = ORIENTED_EDGE('',*,*,#98872,.T.); -#98872 = EDGE_CURVE('',#98846,#98663,#98873,.T.); -#98873 = SURFACE_CURVE('',#98874,(#98879,#98885),.PCURVE_S1.); -#98874 = CIRCLE('',#98875,0.208574704164); -#98875 = AXIS2_PLACEMENT_3D('',#98876,#98877,#98878); -#98876 = CARTESIAN_POINT('',(3.35,-0.728168876214,2.640924866458E-017)); -#98877 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98878 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98879 = PCURVE('',#98699,#98880); -#98880 = DEFINITIONAL_REPRESENTATION('',(#98881),#98884); -#98881 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98882,#98883),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#101228 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#101229 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#101230 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#101231 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#101232 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#101233 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#101234 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#101235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101236 = ORIENTED_EDGE('',*,*,#101237,.T.); +#101237 = EDGE_CURVE('',#101211,#101238,#101240,.T.); +#101238 = VERTEX_POINT('',#101239); +#101239 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.E+000)); +#101240 = SURFACE_CURVE('',#101241,(#101245,#101251),.PCURVE_S1.); +#101241 = LINE('',#101242,#101243); +#101242 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#101243 = VECTOR('',#101244,1.); +#101244 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101245 = PCURVE('',#101091,#101246); +#101246 = DEFINITIONAL_REPRESENTATION('',(#101247),#101250); +#101247 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101248,#101249), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); +#101248 = CARTESIAN_POINT('',(1.570796326795,6.85)); +#101249 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#101250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101251 = PCURVE('',#101252,#101257); +#101252 = PLANE('',#101253); +#101253 = AXIS2_PLACEMENT_3D('',#101254,#101255,#101256); +#101254 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#101255 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#101256 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#101257 = DEFINITIONAL_REPRESENTATION('',(#101258),#101262); +#101258 = LINE('',#101259,#101260); +#101259 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#101260 = VECTOR('',#101261,1.); +#101261 = DIRECTION('',(0.E+000,1.)); +#101262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101263 = ORIENTED_EDGE('',*,*,#101264,.T.); +#101264 = EDGE_CURVE('',#101238,#101055,#101265,.T.); +#101265 = SURFACE_CURVE('',#101266,(#101271,#101277),.PCURVE_S1.); +#101266 = CIRCLE('',#101267,0.208574704164); +#101267 = AXIS2_PLACEMENT_3D('',#101268,#101269,#101270); +#101268 = CARTESIAN_POINT('',(3.35,-0.728168876214,2.640924866458E-017) + ); +#101269 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101270 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101271 = PCURVE('',#101091,#101272); +#101272 = DEFINITIONAL_REPRESENTATION('',(#101273),#101276); +#101273 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101274,#101275), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#98882 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#98883 = CARTESIAN_POINT('',(3.201833915432,6.65)); -#98884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98885 = PCURVE('',#89665,#98886); -#98886 = DEFINITIONAL_REPRESENTATION('',(#98887),#98891); -#98887 = CIRCLE('',#98888,0.208574704164); -#98888 = AXIS2_PLACEMENT_2D('',#98889,#98890); -#98889 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#98890 = DIRECTION('',(1.,0.E+000)); -#98891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98892 = ADVANCED_FACE('',(#98893),#98803,.T.); -#98893 = FACE_BOUND('',#98894,.T.); -#98894 = EDGE_LOOP('',(#98895,#98896,#98923,#98950)); -#98895 = ORIENTED_EDGE('',*,*,#98789,.F.); -#98896 = ORIENTED_EDGE('',*,*,#98897,.F.); -#98897 = EDGE_CURVE('',#98898,#98767,#98900,.T.); -#98898 = VERTEX_POINT('',#98899); -#98899 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.E+000)); -#98900 = SURFACE_CURVE('',#98901,(#98906,#98912),.PCURVE_S1.); -#98901 = CIRCLE('',#98902,0.308574064194); -#98902 = AXIS2_PLACEMENT_3D('',#98903,#98904,#98905); -#98903 = CARTESIAN_POINT('',(3.15,-0.728168876214,2.640924866458E-017)); -#98904 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98905 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98906 = PCURVE('',#98803,#98907); -#98907 = DEFINITIONAL_REPRESENTATION('',(#98908),#98911); -#98908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98909,#98910),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#101274 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#101275 = CARTESIAN_POINT('',(3.201833915432,6.65)); +#101276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101277 = PCURVE('',#92057,#101278); +#101278 = DEFINITIONAL_REPRESENTATION('',(#101279),#101283); +#101279 = CIRCLE('',#101280,0.208574704164); +#101280 = AXIS2_PLACEMENT_2D('',#101281,#101282); +#101281 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#101282 = DIRECTION('',(1.,0.E+000)); +#101283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101284 = ADVANCED_FACE('',(#101285),#101195,.T.); +#101285 = FACE_BOUND('',#101286,.T.); +#101286 = EDGE_LOOP('',(#101287,#101288,#101315,#101342)); +#101287 = ORIENTED_EDGE('',*,*,#101181,.F.); +#101288 = ORIENTED_EDGE('',*,*,#101289,.F.); +#101289 = EDGE_CURVE('',#101290,#101159,#101292,.T.); +#101290 = VERTEX_POINT('',#101291); +#101291 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.E+000)); +#101292 = SURFACE_CURVE('',#101293,(#101298,#101304),.PCURVE_S1.); +#101293 = CIRCLE('',#101294,0.308574064194); +#101294 = AXIS2_PLACEMENT_3D('',#101295,#101296,#101297); +#101295 = CARTESIAN_POINT('',(3.15,-0.728168876214,2.640924866458E-017) + ); +#101296 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101297 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101298 = PCURVE('',#101195,#101299); +#101299 = DEFINITIONAL_REPRESENTATION('',(#101300),#101303); +#101300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101301,#101302), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#98909 = CARTESIAN_POINT('',(1.570796326795,6.85)); -#98910 = CARTESIAN_POINT('',(3.191025391152,6.85)); -#98911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101301 = CARTESIAN_POINT('',(1.570796326795,6.85)); +#101302 = CARTESIAN_POINT('',(3.191025391152,6.85)); +#101303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98912 = PCURVE('',#89721,#98913); -#98913 = DEFINITIONAL_REPRESENTATION('',(#98914),#98922); -#98914 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#98915,#98916,#98917,#98918 - ,#98919,#98920,#98921),.UNSPECIFIED.,.T.,.F.) +#101304 = PCURVE('',#92113,#101305); +#101305 = DEFINITIONAL_REPRESENTATION('',(#101306),#101314); +#101306 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101307,#101308,#101309, + #101310,#101311,#101312,#101313),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#98915 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#98916 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#98917 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#98918 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#98919 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#98920 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#98921 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#98922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98923 = ORIENTED_EDGE('',*,*,#98924,.F.); -#98924 = EDGE_CURVE('',#98925,#98898,#98927,.T.); -#98925 = VERTEX_POINT('',#98926); -#98926 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.E+000)); -#98927 = SURFACE_CURVE('',#98928,(#98932,#98938),.PCURVE_S1.); -#98928 = LINE('',#98929,#98930); -#98929 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#98930 = VECTOR('',#98931,1.); -#98931 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98932 = PCURVE('',#98803,#98933); -#98933 = DEFINITIONAL_REPRESENTATION('',(#98934),#98937); -#98934 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98935,#98936),.UNSPECIFIED., - .F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#98935 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#98936 = CARTESIAN_POINT('',(1.570796326795,6.85)); -#98937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98938 = PCURVE('',#98939,#98944); -#98939 = PLANE('',#98940); -#98940 = AXIS2_PLACEMENT_3D('',#98941,#98942,#98943); -#98941 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#98942 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#98943 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#98944 = DEFINITIONAL_REPRESENTATION('',(#98945),#98949); -#98945 = LINE('',#98946,#98947); -#98946 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#98947 = VECTOR('',#98948,1.); -#98948 = DIRECTION('',(0.E+000,-1.)); -#98949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98950 = ORIENTED_EDGE('',*,*,#98951,.T.); -#98951 = EDGE_CURVE('',#98925,#98714,#98952,.T.); -#98952 = SURFACE_CURVE('',#98953,(#98958,#98964),.PCURVE_S1.); -#98953 = CIRCLE('',#98954,0.308574064194); -#98954 = AXIS2_PLACEMENT_3D('',#98955,#98956,#98957); -#98955 = CARTESIAN_POINT('',(3.35,-0.728168876214,2.640924866458E-017)); -#98956 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98957 = DIRECTION('',(0.E+000,0.E+000,1.)); -#98958 = PCURVE('',#98803,#98959); -#98959 = DEFINITIONAL_REPRESENTATION('',(#98960),#98963); -#98960 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#98961,#98962),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#101307 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#101308 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#101309 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#101310 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#101311 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#101312 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#101313 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#101314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101315 = ORIENTED_EDGE('',*,*,#101316,.F.); +#101316 = EDGE_CURVE('',#101317,#101290,#101319,.T.); +#101317 = VERTEX_POINT('',#101318); +#101318 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.E+000)); +#101319 = SURFACE_CURVE('',#101320,(#101324,#101330),.PCURVE_S1.); +#101320 = LINE('',#101321,#101322); +#101321 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#101322 = VECTOR('',#101323,1.); +#101323 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101324 = PCURVE('',#101195,#101325); +#101325 = DEFINITIONAL_REPRESENTATION('',(#101326),#101329); +#101326 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101327,#101328), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); +#101327 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#101328 = CARTESIAN_POINT('',(1.570796326795,6.85)); +#101329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101330 = PCURVE('',#101331,#101336); +#101331 = PLANE('',#101332); +#101332 = AXIS2_PLACEMENT_3D('',#101333,#101334,#101335); +#101333 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#101334 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#101335 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#101336 = DEFINITIONAL_REPRESENTATION('',(#101337),#101341); +#101337 = LINE('',#101338,#101339); +#101338 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#101339 = VECTOR('',#101340,1.); +#101340 = DIRECTION('',(0.E+000,-1.)); +#101341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101342 = ORIENTED_EDGE('',*,*,#101343,.T.); +#101343 = EDGE_CURVE('',#101317,#101106,#101344,.T.); +#101344 = SURFACE_CURVE('',#101345,(#101350,#101356),.PCURVE_S1.); +#101345 = CIRCLE('',#101346,0.308574064194); +#101346 = AXIS2_PLACEMENT_3D('',#101347,#101348,#101349); +#101347 = CARTESIAN_POINT('',(3.35,-0.728168876214,2.640924866458E-017) + ); +#101348 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101349 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101350 = PCURVE('',#101195,#101351); +#101351 = DEFINITIONAL_REPRESENTATION('',(#101352),#101355); +#101352 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101353,#101354), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#98961 = CARTESIAN_POINT('',(1.570796326795,6.65)); -#98962 = CARTESIAN_POINT('',(3.191025391152,6.65)); -#98963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101353 = CARTESIAN_POINT('',(1.570796326795,6.65)); +#101354 = CARTESIAN_POINT('',(3.191025391152,6.65)); +#101355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101356 = PCURVE('',#92057,#101357); +#101357 = DEFINITIONAL_REPRESENTATION('',(#101358),#101362); +#101358 = CIRCLE('',#101359,0.308574064194); +#101359 = AXIS2_PLACEMENT_2D('',#101360,#101361); +#101360 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#101361 = DIRECTION('',(1.,0.E+000)); +#101362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101363 = ADVANCED_FACE('',(#101364),#101331,.F.); +#101364 = FACE_BOUND('',#101365,.T.); +#101365 = EDGE_LOOP('',(#101366,#101395,#101416,#101417)); +#101366 = ORIENTED_EDGE('',*,*,#101367,.F.); +#101367 = EDGE_CURVE('',#101368,#101370,#101372,.T.); +#101368 = VERTEX_POINT('',#101369); +#101369 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.530776333563)); +#101370 = VERTEX_POINT('',#101371); +#101371 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.530776333563)); +#101372 = SURFACE_CURVE('',#101373,(#101377,#101384),.PCURVE_S1.); +#101373 = LINE('',#101374,#101375); +#101374 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#101375 = VECTOR('',#101376,1.); +#101376 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101377 = PCURVE('',#101331,#101378); +#101378 = DEFINITIONAL_REPRESENTATION('',(#101379),#101383); +#101379 = LINE('',#101380,#101381); +#101380 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101381 = VECTOR('',#101382,1.); +#101382 = DIRECTION('',(0.E+000,-1.)); +#101383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101384 = PCURVE('',#101385,#101390); +#101385 = CYLINDRICAL_SURFACE('',#101386,0.119270391569); +#101386 = AXIS2_PLACEMENT_3D('',#101387,#101388,#101389); +#101387 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#101388 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101389 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101390 = DEFINITIONAL_REPRESENTATION('',(#101391),#101394); +#101391 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101392,#101393), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); +#101392 = CARTESIAN_POINT('',(4.712388980385,-6.65)); +#101393 = CARTESIAN_POINT('',(4.712388980385,-6.85)); +#101394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101395 = ORIENTED_EDGE('',*,*,#101396,.T.); +#101396 = EDGE_CURVE('',#101368,#101317,#101397,.T.); +#101397 = SURFACE_CURVE('',#101398,(#101402,#101409),.PCURVE_S1.); +#101398 = LINE('',#101399,#101400); +#101399 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.530776333563)); +#101400 = VECTOR('',#101401,1.); +#101401 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#101402 = PCURVE('',#101331,#101403); +#101403 = DEFINITIONAL_REPRESENTATION('',(#101404),#101408); +#101404 = LINE('',#101405,#101406); +#101405 = CARTESIAN_POINT('',(0.E+000,-6.65)); +#101406 = VECTOR('',#101407,1.); +#101407 = DIRECTION('',(1.,0.E+000)); +#101408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101409 = PCURVE('',#92057,#101410); +#101410 = DEFINITIONAL_REPRESENTATION('',(#101411),#101415); +#101411 = LINE('',#101412,#101413); +#101412 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#101413 = VECTOR('',#101414,1.); +#101414 = DIRECTION('',(-1.,-1.021336205033E-016)); +#101415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101416 = ORIENTED_EDGE('',*,*,#101316,.T.); +#101417 = ORIENTED_EDGE('',*,*,#101418,.F.); +#101418 = EDGE_CURVE('',#101370,#101290,#101419,.T.); +#101419 = SURFACE_CURVE('',#101420,(#101424,#101431),.PCURVE_S1.); +#101420 = LINE('',#101421,#101422); +#101421 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.530776333563)); +#101422 = VECTOR('',#101423,1.); +#101423 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#101424 = PCURVE('',#101331,#101425); +#101425 = DEFINITIONAL_REPRESENTATION('',(#101426),#101430); +#101426 = LINE('',#101427,#101428); +#101427 = CARTESIAN_POINT('',(0.E+000,-6.85)); +#101428 = VECTOR('',#101429,1.); +#101429 = DIRECTION('',(1.,0.E+000)); +#101430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101431 = PCURVE('',#92113,#101432); +#101432 = DEFINITIONAL_REPRESENTATION('',(#101433),#101437); +#101433 = LINE('',#101434,#101435); +#101434 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#101435 = VECTOR('',#101436,1.); +#101436 = DIRECTION('',(1.,-1.021336205033E-016)); +#101437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101438 = ADVANCED_FACE('',(#101439),#101252,.F.); +#101439 = FACE_BOUND('',#101440,.T.); +#101440 = EDGE_LOOP('',(#101441,#101470,#101491,#101492)); +#101441 = ORIENTED_EDGE('',*,*,#101442,.F.); +#101442 = EDGE_CURVE('',#101443,#101445,#101447,.T.); +#101443 = VERTEX_POINT('',#101444); +#101444 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.530776333563)); +#101445 = VERTEX_POINT('',#101446); +#101446 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.530776333563)); +#101447 = SURFACE_CURVE('',#101448,(#101452,#101459),.PCURVE_S1.); +#101448 = LINE('',#101449,#101450); +#101449 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#101450 = VECTOR('',#101451,1.); +#101451 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101452 = PCURVE('',#101252,#101453); +#101453 = DEFINITIONAL_REPRESENTATION('',(#101454),#101458); +#101454 = LINE('',#101455,#101456); +#101455 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101456 = VECTOR('',#101457,1.); +#101457 = DIRECTION('',(0.E+000,1.)); +#101458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101459 = PCURVE('',#101460,#101465); +#101460 = CYLINDRICAL_SURFACE('',#101461,0.2192697516); +#101461 = AXIS2_PLACEMENT_3D('',#101462,#101463,#101464); +#101462 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#101463 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101464 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101465 = DEFINITIONAL_REPRESENTATION('',(#101466),#101469); +#101466 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101467,#101468), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); +#101467 = CARTESIAN_POINT('',(4.712388980385,-6.85)); +#101468 = CARTESIAN_POINT('',(4.712388980385,-6.65)); +#101469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98964 = PCURVE('',#89665,#98965); -#98965 = DEFINITIONAL_REPRESENTATION('',(#98966),#98970); -#98966 = CIRCLE('',#98967,0.308574064194); -#98967 = AXIS2_PLACEMENT_2D('',#98968,#98969); -#98968 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#98969 = DIRECTION('',(1.,0.E+000)); -#98970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101470 = ORIENTED_EDGE('',*,*,#101471,.T.); +#101471 = EDGE_CURVE('',#101443,#101211,#101472,.T.); +#101472 = SURFACE_CURVE('',#101473,(#101477,#101484),.PCURVE_S1.); +#101473 = LINE('',#101474,#101475); +#101474 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.530776333563)); +#101475 = VECTOR('',#101476,1.); +#101476 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#101477 = PCURVE('',#101252,#101478); +#101478 = DEFINITIONAL_REPRESENTATION('',(#101479),#101483); +#101479 = LINE('',#101480,#101481); +#101480 = CARTESIAN_POINT('',(0.E+000,-6.85)); +#101481 = VECTOR('',#101482,1.); +#101482 = DIRECTION('',(-1.,0.E+000)); +#101483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#98971 = ADVANCED_FACE('',(#98972),#98939,.F.); -#98972 = FACE_BOUND('',#98973,.T.); -#98973 = EDGE_LOOP('',(#98974,#99003,#99024,#99025)); -#98974 = ORIENTED_EDGE('',*,*,#98975,.F.); -#98975 = EDGE_CURVE('',#98976,#98978,#98980,.T.); -#98976 = VERTEX_POINT('',#98977); -#98977 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.530776333563)); -#98978 = VERTEX_POINT('',#98979); -#98979 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.530776333563)); -#98980 = SURFACE_CURVE('',#98981,(#98985,#98992),.PCURVE_S1.); -#98981 = LINE('',#98982,#98983); -#98982 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#98983 = VECTOR('',#98984,1.); -#98984 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#98985 = PCURVE('',#98939,#98986); -#98986 = DEFINITIONAL_REPRESENTATION('',(#98987),#98991); -#98987 = LINE('',#98988,#98989); -#98988 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#98989 = VECTOR('',#98990,1.); -#98990 = DIRECTION('',(0.E+000,-1.)); -#98991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#98992 = PCURVE('',#98993,#98998); -#98993 = CYLINDRICAL_SURFACE('',#98994,0.119270391569); -#98994 = AXIS2_PLACEMENT_3D('',#98995,#98996,#98997); -#98995 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#98996 = DIRECTION('',(1.,0.E+000,0.E+000)); -#98997 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#98998 = DEFINITIONAL_REPRESENTATION('',(#98999),#99002); -#98999 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99000,#99001),.UNSPECIFIED., - .F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#99000 = CARTESIAN_POINT('',(4.712388980385,-6.65)); -#99001 = CARTESIAN_POINT('',(4.712388980385,-6.85)); -#99002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99003 = ORIENTED_EDGE('',*,*,#99004,.T.); -#99004 = EDGE_CURVE('',#98976,#98925,#99005,.T.); -#99005 = SURFACE_CURVE('',#99006,(#99010,#99017),.PCURVE_S1.); -#99006 = LINE('',#99007,#99008); -#99007 = CARTESIAN_POINT('',(3.35,-0.419594812019,0.530776333563)); -#99008 = VECTOR('',#99009,1.); -#99009 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99010 = PCURVE('',#98939,#99011); -#99011 = DEFINITIONAL_REPRESENTATION('',(#99012),#99016); -#99012 = LINE('',#99013,#99014); -#99013 = CARTESIAN_POINT('',(0.E+000,-6.65)); -#99014 = VECTOR('',#99015,1.); -#99015 = DIRECTION('',(1.,0.E+000)); -#99016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99017 = PCURVE('',#89665,#99018); -#99018 = DEFINITIONAL_REPRESENTATION('',(#99019),#99023); -#99019 = LINE('',#99020,#99021); -#99020 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#99021 = VECTOR('',#99022,1.); -#99022 = DIRECTION('',(-1.,-1.021336205033E-016)); -#99023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99024 = ORIENTED_EDGE('',*,*,#98924,.T.); -#99025 = ORIENTED_EDGE('',*,*,#99026,.F.); -#99026 = EDGE_CURVE('',#98978,#98898,#99027,.T.); -#99027 = SURFACE_CURVE('',#99028,(#99032,#99039),.PCURVE_S1.); -#99028 = LINE('',#99029,#99030); -#99029 = CARTESIAN_POINT('',(3.15,-0.419594812019,0.530776333563)); -#99030 = VECTOR('',#99031,1.); -#99031 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99032 = PCURVE('',#98939,#99033); -#99033 = DEFINITIONAL_REPRESENTATION('',(#99034),#99038); -#99034 = LINE('',#99035,#99036); -#99035 = CARTESIAN_POINT('',(0.E+000,-6.85)); -#99036 = VECTOR('',#99037,1.); -#99037 = DIRECTION('',(1.,0.E+000)); -#99038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99039 = PCURVE('',#89721,#99040); -#99040 = DEFINITIONAL_REPRESENTATION('',(#99041),#99045); -#99041 = LINE('',#99042,#99043); -#99042 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#99043 = VECTOR('',#99044,1.); -#99044 = DIRECTION('',(1.,-1.021336205033E-016)); -#99045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99046 = ADVANCED_FACE('',(#99047),#98860,.F.); -#99047 = FACE_BOUND('',#99048,.T.); -#99048 = EDGE_LOOP('',(#99049,#99078,#99099,#99100)); -#99049 = ORIENTED_EDGE('',*,*,#99050,.F.); -#99050 = EDGE_CURVE('',#99051,#99053,#99055,.T.); -#99051 = VERTEX_POINT('',#99052); -#99052 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.530776333563)); -#99053 = VERTEX_POINT('',#99054); -#99054 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.530776333563)); -#99055 = SURFACE_CURVE('',#99056,(#99060,#99067),.PCURVE_S1.); -#99056 = LINE('',#99057,#99058); -#99057 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#99058 = VECTOR('',#99059,1.); -#99059 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99060 = PCURVE('',#98860,#99061); -#99061 = DEFINITIONAL_REPRESENTATION('',(#99062),#99066); -#99062 = LINE('',#99063,#99064); -#99063 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99064 = VECTOR('',#99065,1.); -#99065 = DIRECTION('',(0.E+000,1.)); -#99066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99067 = PCURVE('',#99068,#99073); -#99068 = CYLINDRICAL_SURFACE('',#99069,0.2192697516); -#99069 = AXIS2_PLACEMENT_3D('',#99070,#99071,#99072); -#99070 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#99071 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99072 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99073 = DEFINITIONAL_REPRESENTATION('',(#99074),#99077); -#99074 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99075,#99076),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#99075 = CARTESIAN_POINT('',(4.712388980385,-6.85)); -#99076 = CARTESIAN_POINT('',(4.712388980385,-6.65)); -#99077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99078 = ORIENTED_EDGE('',*,*,#99079,.T.); -#99079 = EDGE_CURVE('',#99051,#98819,#99080,.T.); -#99080 = SURFACE_CURVE('',#99081,(#99085,#99092),.PCURVE_S1.); -#99081 = LINE('',#99082,#99083); -#99082 = CARTESIAN_POINT('',(3.15,-0.51959417205,0.530776333563)); -#99083 = VECTOR('',#99084,1.); -#99084 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99085 = PCURVE('',#98860,#99086); -#99086 = DEFINITIONAL_REPRESENTATION('',(#99087),#99091); -#99087 = LINE('',#99088,#99089); -#99088 = CARTESIAN_POINT('',(0.E+000,-6.85)); -#99089 = VECTOR('',#99090,1.); -#99090 = DIRECTION('',(-1.,0.E+000)); -#99091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99092 = PCURVE('',#89721,#99093); -#99093 = DEFINITIONAL_REPRESENTATION('',(#99094),#99098); -#99094 = LINE('',#99095,#99096); -#99095 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#99096 = VECTOR('',#99097,1.); -#99097 = DIRECTION('',(1.,-1.021336205033E-016)); -#99098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99099 = ORIENTED_EDGE('',*,*,#98845,.T.); -#99100 = ORIENTED_EDGE('',*,*,#99101,.F.); -#99101 = EDGE_CURVE('',#99053,#98846,#99102,.T.); -#99102 = SURFACE_CURVE('',#99103,(#99107,#99114),.PCURVE_S1.); -#99103 = LINE('',#99104,#99105); -#99104 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.530776333563)); -#99105 = VECTOR('',#99106,1.); -#99106 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99107 = PCURVE('',#98860,#99108); -#99108 = DEFINITIONAL_REPRESENTATION('',(#99109),#99113); -#99109 = LINE('',#99110,#99111); -#99110 = CARTESIAN_POINT('',(0.E+000,-6.65)); -#99111 = VECTOR('',#99112,1.); -#99112 = DIRECTION('',(-1.,0.E+000)); -#99113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99114 = PCURVE('',#89665,#99115); -#99115 = DEFINITIONAL_REPRESENTATION('',(#99116),#99120); -#99116 = LINE('',#99117,#99118); -#99117 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#99118 = VECTOR('',#99119,1.); -#99119 = DIRECTION('',(-1.,-1.021336205033E-016)); -#99120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101484 = PCURVE('',#92113,#101485); +#101485 = DEFINITIONAL_REPRESENTATION('',(#101486),#101490); +#101486 = LINE('',#101487,#101488); +#101487 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#101488 = VECTOR('',#101489,1.); +#101489 = DIRECTION('',(1.,-1.021336205033E-016)); +#101490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99121 = ADVANCED_FACE('',(#99122),#98993,.F.); -#99122 = FACE_BOUND('',#99123,.F.); -#99123 = EDGE_LOOP('',(#99124,#99151,#99173,#99194)); -#99124 = ORIENTED_EDGE('',*,*,#99125,.F.); -#99125 = EDGE_CURVE('',#99126,#98976,#99128,.T.); -#99126 = VERTEX_POINT('',#99127); -#99127 = CARTESIAN_POINT('',(3.35,-0.303662633502,0.65)); -#99128 = SURFACE_CURVE('',#99129,(#99134,#99140),.PCURVE_S1.); -#99129 = CIRCLE('',#99130,0.119270391569); -#99130 = AXIS2_PLACEMENT_3D('',#99131,#99132,#99133); -#99131 = CARTESIAN_POINT('',(3.35,-0.30032442045,0.530776333563)); -#99132 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99133 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99134 = PCURVE('',#98993,#99135); -#99135 = DEFINITIONAL_REPRESENTATION('',(#99136),#99139); -#99136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99137,#99138),.UNSPECIFIED., - .F.,.F.,(2,2),(3.169584923929,4.712388980385), +#101491 = ORIENTED_EDGE('',*,*,#101237,.T.); +#101492 = ORIENTED_EDGE('',*,*,#101493,.F.); +#101493 = EDGE_CURVE('',#101445,#101238,#101494,.T.); +#101494 = SURFACE_CURVE('',#101495,(#101499,#101506),.PCURVE_S1.); +#101495 = LINE('',#101496,#101497); +#101496 = CARTESIAN_POINT('',(3.35,-0.51959417205,0.530776333563)); +#101497 = VECTOR('',#101498,1.); +#101498 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#101499 = PCURVE('',#101252,#101500); +#101500 = DEFINITIONAL_REPRESENTATION('',(#101501),#101505); +#101501 = LINE('',#101502,#101503); +#101502 = CARTESIAN_POINT('',(0.E+000,-6.65)); +#101503 = VECTOR('',#101504,1.); +#101504 = DIRECTION('',(-1.,0.E+000)); +#101505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101506 = PCURVE('',#92057,#101507); +#101507 = DEFINITIONAL_REPRESENTATION('',(#101508),#101512); +#101508 = LINE('',#101509,#101510); +#101509 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#101510 = VECTOR('',#101511,1.); +#101511 = DIRECTION('',(-1.,-1.021336205033E-016)); +#101512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101513 = ADVANCED_FACE('',(#101514),#101385,.F.); +#101514 = FACE_BOUND('',#101515,.F.); +#101515 = EDGE_LOOP('',(#101516,#101543,#101565,#101586)); +#101516 = ORIENTED_EDGE('',*,*,#101517,.F.); +#101517 = EDGE_CURVE('',#101518,#101368,#101520,.T.); +#101518 = VERTEX_POINT('',#101519); +#101519 = CARTESIAN_POINT('',(3.35,-0.303662633502,0.65)); +#101520 = SURFACE_CURVE('',#101521,(#101526,#101532),.PCURVE_S1.); +#101521 = CIRCLE('',#101522,0.119270391569); +#101522 = AXIS2_PLACEMENT_3D('',#101523,#101524,#101525); +#101523 = CARTESIAN_POINT('',(3.35,-0.30032442045,0.530776333563)); +#101524 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101525 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101526 = PCURVE('',#101385,#101527); +#101527 = DEFINITIONAL_REPRESENTATION('',(#101528),#101531); +#101528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101529,#101530), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#99137 = CARTESIAN_POINT('',(3.169584923929,-6.65)); -#99138 = CARTESIAN_POINT('',(4.712388980385,-6.65)); -#99139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101529 = CARTESIAN_POINT('',(3.169584923929,-6.65)); +#101530 = CARTESIAN_POINT('',(4.712388980385,-6.65)); +#101531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99140 = PCURVE('',#89665,#99141); -#99141 = DEFINITIONAL_REPRESENTATION('',(#99142),#99150); -#99142 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99143,#99144,#99145,#99146 - ,#99147,#99148,#99149),.UNSPECIFIED.,.F.,.F.) +#101532 = PCURVE('',#92057,#101533); +#101533 = DEFINITIONAL_REPRESENTATION('',(#101534),#101542); +#101534 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101535,#101536,#101537, + #101538,#101539,#101540,#101541),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#99143 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#99144 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#99145 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#99146 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#99147 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#99148 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#99149 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#99150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99151 = ORIENTED_EDGE('',*,*,#99152,.F.); -#99152 = EDGE_CURVE('',#99153,#99126,#99155,.T.); -#99153 = VERTEX_POINT('',#99154); -#99154 = CARTESIAN_POINT('',(3.15,-0.303662633502,0.65)); -#99155 = SURFACE_CURVE('',#99156,(#99160,#99166),.PCURVE_S1.); -#99156 = LINE('',#99157,#99158); -#99157 = CARTESIAN_POINT('',(3.35,-0.303662633502,0.65)); -#99158 = VECTOR('',#99159,1.); -#99159 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99160 = PCURVE('',#98993,#99161); -#99161 = DEFINITIONAL_REPRESENTATION('',(#99162),#99165); -#99162 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99163,#99164),.UNSPECIFIED., - .F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#99163 = CARTESIAN_POINT('',(3.169584923929,-6.85)); -#99164 = CARTESIAN_POINT('',(3.169584923929,-6.65)); -#99165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99166 = PCURVE('',#89693,#99167); -#99167 = DEFINITIONAL_REPRESENTATION('',(#99168),#99172); -#99168 = LINE('',#99169,#99170); -#99169 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#99170 = VECTOR('',#99171,1.); -#99171 = DIRECTION('',(0.E+000,1.)); -#99172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99173 = ORIENTED_EDGE('',*,*,#99174,.T.); -#99174 = EDGE_CURVE('',#99153,#98978,#99175,.T.); -#99175 = SURFACE_CURVE('',#99176,(#99181,#99187),.PCURVE_S1.); -#99176 = CIRCLE('',#99177,0.119270391569); -#99177 = AXIS2_PLACEMENT_3D('',#99178,#99179,#99180); -#99178 = CARTESIAN_POINT('',(3.15,-0.30032442045,0.530776333563)); -#99179 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99180 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99181 = PCURVE('',#98993,#99182); -#99182 = DEFINITIONAL_REPRESENTATION('',(#99183),#99186); -#99183 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99184,#99185),.UNSPECIFIED., - .F.,.F.,(2,2),(3.169584923929,4.712388980385), +#101535 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#101536 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#101537 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#101538 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#101539 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#101540 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#101541 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#101542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101543 = ORIENTED_EDGE('',*,*,#101544,.F.); +#101544 = EDGE_CURVE('',#101545,#101518,#101547,.T.); +#101545 = VERTEX_POINT('',#101546); +#101546 = CARTESIAN_POINT('',(3.15,-0.303662633502,0.65)); +#101547 = SURFACE_CURVE('',#101548,(#101552,#101558),.PCURVE_S1.); +#101548 = LINE('',#101549,#101550); +#101549 = CARTESIAN_POINT('',(3.35,-0.303662633502,0.65)); +#101550 = VECTOR('',#101551,1.); +#101551 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101552 = PCURVE('',#101385,#101553); +#101553 = DEFINITIONAL_REPRESENTATION('',(#101554),#101557); +#101554 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101555,#101556), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); +#101555 = CARTESIAN_POINT('',(3.169584923929,-6.85)); +#101556 = CARTESIAN_POINT('',(3.169584923929,-6.65)); +#101557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101558 = PCURVE('',#92085,#101559); +#101559 = DEFINITIONAL_REPRESENTATION('',(#101560),#101564); +#101560 = LINE('',#101561,#101562); +#101561 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#101562 = VECTOR('',#101563,1.); +#101563 = DIRECTION('',(0.E+000,1.)); +#101564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101565 = ORIENTED_EDGE('',*,*,#101566,.T.); +#101566 = EDGE_CURVE('',#101545,#101370,#101567,.T.); +#101567 = SURFACE_CURVE('',#101568,(#101573,#101579),.PCURVE_S1.); +#101568 = CIRCLE('',#101569,0.119270391569); +#101569 = AXIS2_PLACEMENT_3D('',#101570,#101571,#101572); +#101570 = CARTESIAN_POINT('',(3.15,-0.30032442045,0.530776333563)); +#101571 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101572 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101573 = PCURVE('',#101385,#101574); +#101574 = DEFINITIONAL_REPRESENTATION('',(#101575),#101578); +#101575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101576,#101577), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#99184 = CARTESIAN_POINT('',(3.169584923929,-6.85)); -#99185 = CARTESIAN_POINT('',(4.712388980385,-6.85)); -#99186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99187 = PCURVE('',#89721,#99188); -#99188 = DEFINITIONAL_REPRESENTATION('',(#99189),#99193); -#99189 = CIRCLE('',#99190,0.119270391569); -#99190 = AXIS2_PLACEMENT_2D('',#99191,#99192); -#99191 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#99192 = DIRECTION('',(1.,0.E+000)); -#99193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99194 = ORIENTED_EDGE('',*,*,#98975,.F.); -#99195 = ADVANCED_FACE('',(#99196),#99068,.T.); -#99196 = FACE_BOUND('',#99197,.T.); -#99197 = EDGE_LOOP('',(#99198,#99221,#99222,#99249)); -#99198 = ORIENTED_EDGE('',*,*,#99199,.T.); -#99199 = EDGE_CURVE('',#99200,#99051,#99202,.T.); -#99200 = VERTEX_POINT('',#99201); -#99201 = CARTESIAN_POINT('',(3.15,-0.304819755875,0.75)); -#99202 = SURFACE_CURVE('',#99203,(#99208,#99214),.PCURVE_S1.); -#99203 = CIRCLE('',#99204,0.2192697516); -#99204 = AXIS2_PLACEMENT_3D('',#99205,#99206,#99207); -#99205 = CARTESIAN_POINT('',(3.15,-0.30032442045,0.530776333563)); -#99206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99207 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99208 = PCURVE('',#99068,#99209); -#99209 = DEFINITIONAL_REPRESENTATION('',(#99210),#99213); -#99210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99211,#99212),.UNSPECIFIED., - .F.,.F.,(2,2),(3.162095483347,4.712388980385), +#101576 = CARTESIAN_POINT('',(3.169584923929,-6.85)); +#101577 = CARTESIAN_POINT('',(4.712388980385,-6.85)); +#101578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101579 = PCURVE('',#92113,#101580); +#101580 = DEFINITIONAL_REPRESENTATION('',(#101581),#101585); +#101581 = CIRCLE('',#101582,0.119270391569); +#101582 = AXIS2_PLACEMENT_2D('',#101583,#101584); +#101583 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#101584 = DIRECTION('',(1.,0.E+000)); +#101585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101586 = ORIENTED_EDGE('',*,*,#101367,.F.); +#101587 = ADVANCED_FACE('',(#101588),#101460,.T.); +#101588 = FACE_BOUND('',#101589,.T.); +#101589 = EDGE_LOOP('',(#101590,#101613,#101614,#101641)); +#101590 = ORIENTED_EDGE('',*,*,#101591,.T.); +#101591 = EDGE_CURVE('',#101592,#101443,#101594,.T.); +#101592 = VERTEX_POINT('',#101593); +#101593 = CARTESIAN_POINT('',(3.15,-0.304819755875,0.75)); +#101594 = SURFACE_CURVE('',#101595,(#101600,#101606),.PCURVE_S1.); +#101595 = CIRCLE('',#101596,0.2192697516); +#101596 = AXIS2_PLACEMENT_3D('',#101597,#101598,#101599); +#101597 = CARTESIAN_POINT('',(3.15,-0.30032442045,0.530776333563)); +#101598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101599 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101600 = PCURVE('',#101460,#101601); +#101601 = DEFINITIONAL_REPRESENTATION('',(#101602),#101605); +#101602 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101603,#101604), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#99211 = CARTESIAN_POINT('',(3.162095483347,-6.85)); -#99212 = CARTESIAN_POINT('',(4.712388980385,-6.85)); -#99213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99214 = PCURVE('',#89721,#99215); -#99215 = DEFINITIONAL_REPRESENTATION('',(#99216),#99220); -#99216 = CIRCLE('',#99217,0.2192697516); -#99217 = AXIS2_PLACEMENT_2D('',#99218,#99219); -#99218 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#99219 = DIRECTION('',(1.,0.E+000)); -#99220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99221 = ORIENTED_EDGE('',*,*,#99050,.T.); -#99222 = ORIENTED_EDGE('',*,*,#99223,.F.); -#99223 = EDGE_CURVE('',#99224,#99053,#99226,.T.); -#99224 = VERTEX_POINT('',#99225); -#99225 = CARTESIAN_POINT('',(3.35,-0.304819755875,0.75)); -#99226 = SURFACE_CURVE('',#99227,(#99232,#99238),.PCURVE_S1.); -#99227 = CIRCLE('',#99228,0.2192697516); -#99228 = AXIS2_PLACEMENT_3D('',#99229,#99230,#99231); -#99229 = CARTESIAN_POINT('',(3.35,-0.30032442045,0.530776333563)); -#99230 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99231 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99232 = PCURVE('',#99068,#99233); -#99233 = DEFINITIONAL_REPRESENTATION('',(#99234),#99237); -#99234 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99235,#99236),.UNSPECIFIED., - .F.,.F.,(2,2),(3.162095483347,4.712388980385), +#101603 = CARTESIAN_POINT('',(3.162095483347,-6.85)); +#101604 = CARTESIAN_POINT('',(4.712388980385,-6.85)); +#101605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101606 = PCURVE('',#92113,#101607); +#101607 = DEFINITIONAL_REPRESENTATION('',(#101608),#101612); +#101608 = CIRCLE('',#101609,0.2192697516); +#101609 = AXIS2_PLACEMENT_2D('',#101610,#101611); +#101610 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#101611 = DIRECTION('',(1.,0.E+000)); +#101612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101613 = ORIENTED_EDGE('',*,*,#101442,.T.); +#101614 = ORIENTED_EDGE('',*,*,#101615,.F.); +#101615 = EDGE_CURVE('',#101616,#101445,#101618,.T.); +#101616 = VERTEX_POINT('',#101617); +#101617 = CARTESIAN_POINT('',(3.35,-0.304819755875,0.75)); +#101618 = SURFACE_CURVE('',#101619,(#101624,#101630),.PCURVE_S1.); +#101619 = CIRCLE('',#101620,0.2192697516); +#101620 = AXIS2_PLACEMENT_3D('',#101621,#101622,#101623); +#101621 = CARTESIAN_POINT('',(3.35,-0.30032442045,0.530776333563)); +#101622 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101623 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101624 = PCURVE('',#101460,#101625); +#101625 = DEFINITIONAL_REPRESENTATION('',(#101626),#101629); +#101626 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101627,#101628), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#99235 = CARTESIAN_POINT('',(3.162095483347,-6.65)); -#99236 = CARTESIAN_POINT('',(4.712388980385,-6.65)); -#99237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#101627 = CARTESIAN_POINT('',(3.162095483347,-6.65)); +#101628 = CARTESIAN_POINT('',(4.712388980385,-6.65)); +#101629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99238 = PCURVE('',#89665,#99239); -#99239 = DEFINITIONAL_REPRESENTATION('',(#99240),#99248); -#99240 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99241,#99242,#99243,#99244 - ,#99245,#99246,#99247),.UNSPECIFIED.,.T.,.F.) +#101630 = PCURVE('',#92057,#101631); +#101631 = DEFINITIONAL_REPRESENTATION('',(#101632),#101640); +#101632 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101633,#101634,#101635, + #101636,#101637,#101638,#101639),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#99241 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#99242 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#99243 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#99244 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#99245 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#99246 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#99247 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#99248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99249 = ORIENTED_EDGE('',*,*,#99250,.T.); -#99250 = EDGE_CURVE('',#99224,#99200,#99251,.T.); -#99251 = SURFACE_CURVE('',#99252,(#99256,#99262),.PCURVE_S1.); -#99252 = LINE('',#99253,#99254); -#99253 = CARTESIAN_POINT('',(3.35,-0.304819755875,0.75)); -#99254 = VECTOR('',#99255,1.); -#99255 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99256 = PCURVE('',#99068,#99257); -#99257 = DEFINITIONAL_REPRESENTATION('',(#99258),#99261); -#99258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99259,#99260),.UNSPECIFIED., - .F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#99259 = CARTESIAN_POINT('',(3.162095483347,-6.65)); -#99260 = CARTESIAN_POINT('',(3.162095483347,-6.85)); -#99261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99262 = PCURVE('',#89747,#99263); -#99263 = DEFINITIONAL_REPRESENTATION('',(#99264),#99268); -#99264 = LINE('',#99265,#99266); -#99265 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#99266 = VECTOR('',#99267,1.); -#99267 = DIRECTION('',(0.E+000,-1.)); -#99268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99269 = ADVANCED_FACE('',(#99270),#89665,.F.); -#99270 = FACE_BOUND('',#99271,.T.); -#99271 = EDGE_LOOP('',(#99272,#99293,#99294,#99295,#99296,#99297,#99318, - #99319,#99320,#99321,#99322,#99343)); -#99272 = ORIENTED_EDGE('',*,*,#99273,.F.); -#99273 = EDGE_CURVE('',#99224,#89650,#99274,.T.); -#99274 = SURFACE_CURVE('',#99275,(#99279,#99286),.PCURVE_S1.); -#99275 = LINE('',#99276,#99277); -#99276 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.75)); -#99277 = VECTOR('',#99278,1.); -#99278 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#99279 = PCURVE('',#89665,#99280); -#99280 = DEFINITIONAL_REPRESENTATION('',(#99281),#99285); -#99281 = LINE('',#99282,#99283); -#99282 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#99283 = VECTOR('',#99284,1.); -#99284 = DIRECTION('',(3.563627120235E-016,1.)); -#99285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99286 = PCURVE('',#89747,#99287); -#99287 = DEFINITIONAL_REPRESENTATION('',(#99288),#99292); -#99288 = LINE('',#99289,#99290); -#99289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99290 = VECTOR('',#99291,1.); -#99291 = DIRECTION('',(1.,0.E+000)); -#99292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99293 = ORIENTED_EDGE('',*,*,#99223,.T.); -#99294 = ORIENTED_EDGE('',*,*,#99101,.T.); -#99295 = ORIENTED_EDGE('',*,*,#98872,.T.); -#99296 = ORIENTED_EDGE('',*,*,#98662,.T.); -#99297 = ORIENTED_EDGE('',*,*,#99298,.T.); -#99298 = EDGE_CURVE('',#98635,#98716,#99299,.T.); -#99299 = SURFACE_CURVE('',#99300,(#99304,#99311),.PCURVE_S1.); -#99300 = LINE('',#99301,#99302); -#99301 = CARTESIAN_POINT('',(3.35,-1.,1.159810404338E-002)); -#99302 = VECTOR('',#99303,1.); -#99303 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#99304 = PCURVE('',#89665,#99305); -#99305 = DEFINITIONAL_REPRESENTATION('',(#99306),#99310); -#99306 = LINE('',#99307,#99308); -#99307 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#99308 = VECTOR('',#99309,1.); -#99309 = DIRECTION('',(-1.,2.101748079665E-016)); -#99310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99311 = PCURVE('',#98650,#99312); -#99312 = DEFINITIONAL_REPRESENTATION('',(#99313),#99317); -#99313 = LINE('',#99314,#99315); -#99314 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#99315 = VECTOR('',#99316,1.); -#99316 = DIRECTION('',(1.,0.E+000)); -#99317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99318 = ORIENTED_EDGE('',*,*,#98713,.F.); -#99319 = ORIENTED_EDGE('',*,*,#98951,.F.); -#99320 = ORIENTED_EDGE('',*,*,#99004,.F.); -#99321 = ORIENTED_EDGE('',*,*,#99125,.F.); -#99322 = ORIENTED_EDGE('',*,*,#99323,.T.); -#99323 = EDGE_CURVE('',#99126,#89648,#99324,.T.); -#99324 = SURFACE_CURVE('',#99325,(#99329,#99336),.PCURVE_S1.); -#99325 = LINE('',#99326,#99327); -#99326 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); -#99327 = VECTOR('',#99328,1.); -#99328 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#99329 = PCURVE('',#89665,#99330); -#99330 = DEFINITIONAL_REPRESENTATION('',(#99331),#99335); -#99331 = LINE('',#99332,#99333); -#99332 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99333 = VECTOR('',#99334,1.); -#99334 = DIRECTION('',(3.563627120235E-016,1.)); -#99335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99336 = PCURVE('',#89693,#99337); -#99337 = DEFINITIONAL_REPRESENTATION('',(#99338),#99342); -#99338 = LINE('',#99339,#99340); -#99339 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99340 = VECTOR('',#99341,1.); -#99341 = DIRECTION('',(-1.,0.E+000)); -#99342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99343 = ORIENTED_EDGE('',*,*,#89647,.T.); -#99344 = ADVANCED_FACE('',(#99345),#89747,.F.); -#99345 = FACE_BOUND('',#99346,.T.); -#99346 = EDGE_LOOP('',(#99347,#99348,#99349,#99350)); -#99347 = ORIENTED_EDGE('',*,*,#99250,.F.); -#99348 = ORIENTED_EDGE('',*,*,#99273,.T.); -#99349 = ORIENTED_EDGE('',*,*,#89733,.T.); -#99350 = ORIENTED_EDGE('',*,*,#99351,.F.); -#99351 = EDGE_CURVE('',#99200,#89706,#99352,.T.); -#99352 = SURFACE_CURVE('',#99353,(#99357,#99364),.PCURVE_S1.); -#99353 = LINE('',#99354,#99355); -#99354 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.75)); -#99355 = VECTOR('',#99356,1.); -#99356 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#99357 = PCURVE('',#89747,#99358); -#99358 = DEFINITIONAL_REPRESENTATION('',(#99359),#99363); -#99359 = LINE('',#99360,#99361); -#99360 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#99361 = VECTOR('',#99362,1.); -#99362 = DIRECTION('',(1.,0.E+000)); -#99363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99364 = PCURVE('',#89721,#99365); -#99365 = DEFINITIONAL_REPRESENTATION('',(#99366),#99370); -#99366 = LINE('',#99367,#99368); -#99367 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#99368 = VECTOR('',#99369,1.); -#99369 = DIRECTION('',(-3.563627120235E-016,1.)); -#99370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99371 = ADVANCED_FACE('',(#99372),#89721,.F.); -#99372 = FACE_BOUND('',#99373,.T.); -#99373 = EDGE_LOOP('',(#99374,#99395,#99396,#99397,#99398,#99399,#99420, - #99421,#99422,#99423,#99424,#99425)); -#99374 = ORIENTED_EDGE('',*,*,#99375,.F.); -#99375 = EDGE_CURVE('',#99153,#89678,#99376,.T.); -#99376 = SURFACE_CURVE('',#99377,(#99381,#99388),.PCURVE_S1.); -#99377 = LINE('',#99378,#99379); -#99378 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.65)); -#99379 = VECTOR('',#99380,1.); -#99380 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#99381 = PCURVE('',#89721,#99382); -#99382 = DEFINITIONAL_REPRESENTATION('',(#99383),#99387); -#99383 = LINE('',#99384,#99385); -#99384 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99385 = VECTOR('',#99386,1.); -#99386 = DIRECTION('',(-3.563627120235E-016,1.)); -#99387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99388 = PCURVE('',#89693,#99389); -#99389 = DEFINITIONAL_REPRESENTATION('',(#99390),#99394); -#99390 = LINE('',#99391,#99392); -#99391 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#99392 = VECTOR('',#99393,1.); -#99393 = DIRECTION('',(-1.,0.E+000)); -#99394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99395 = ORIENTED_EDGE('',*,*,#99174,.T.); -#99396 = ORIENTED_EDGE('',*,*,#99026,.T.); -#99397 = ORIENTED_EDGE('',*,*,#98897,.T.); -#99398 = ORIENTED_EDGE('',*,*,#98766,.T.); -#99399 = ORIENTED_EDGE('',*,*,#99400,.T.); -#99400 = EDGE_CURVE('',#98744,#98607,#99401,.T.); -#99401 = SURFACE_CURVE('',#99402,(#99406,#99413),.PCURVE_S1.); -#99402 = LINE('',#99403,#99404); -#99403 = CARTESIAN_POINT('',(3.15,-1.,1.159810404338E-002)); -#99404 = VECTOR('',#99405,1.); -#99405 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#99406 = PCURVE('',#89721,#99407); -#99407 = DEFINITIONAL_REPRESENTATION('',(#99408),#99412); -#99408 = LINE('',#99409,#99410); -#99409 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#99410 = VECTOR('',#99411,1.); -#99411 = DIRECTION('',(-1.,-2.101748079665E-016)); -#99412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99413 = PCURVE('',#98650,#99414); -#99414 = DEFINITIONAL_REPRESENTATION('',(#99415),#99419); -#99415 = LINE('',#99416,#99417); -#99416 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#99417 = VECTOR('',#99418,1.); -#99418 = DIRECTION('',(-1.,0.E+000)); -#99419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99420 = ORIENTED_EDGE('',*,*,#98604,.F.); -#99421 = ORIENTED_EDGE('',*,*,#98818,.F.); -#99422 = ORIENTED_EDGE('',*,*,#99079,.F.); -#99423 = ORIENTED_EDGE('',*,*,#99199,.F.); -#99424 = ORIENTED_EDGE('',*,*,#99351,.T.); -#99425 = ORIENTED_EDGE('',*,*,#89705,.T.); -#99426 = ADVANCED_FACE('',(#99427),#89693,.F.); -#99427 = FACE_BOUND('',#99428,.T.); -#99428 = EDGE_LOOP('',(#99429,#99430,#99431,#99432)); -#99429 = ORIENTED_EDGE('',*,*,#99152,.F.); -#99430 = ORIENTED_EDGE('',*,*,#99375,.T.); -#99431 = ORIENTED_EDGE('',*,*,#89677,.T.); -#99432 = ORIENTED_EDGE('',*,*,#99323,.F.); -#99433 = ADVANCED_FACE('',(#99434),#98650,.T.); -#99434 = FACE_BOUND('',#99435,.T.); -#99435 = EDGE_LOOP('',(#99436,#99437,#99438,#99439)); -#99436 = ORIENTED_EDGE('',*,*,#99400,.F.); -#99437 = ORIENTED_EDGE('',*,*,#98743,.F.); -#99438 = ORIENTED_EDGE('',*,*,#99298,.F.); -#99439 = ORIENTED_EDGE('',*,*,#98634,.F.); -#99440 = ADVANCED_FACE('',(#99441),#99455,.T.); -#99441 = FACE_BOUND('',#99442,.T.); -#99442 = EDGE_LOOP('',(#99443,#99473,#99501,#99524)); -#99443 = ORIENTED_EDGE('',*,*,#99444,.T.); -#99444 = EDGE_CURVE('',#99445,#99447,#99449,.T.); -#99445 = VERTEX_POINT('',#99446); -#99446 = CARTESIAN_POINT('',(3.65,-0.740726081328,-0.208196358798)); -#99447 = VERTEX_POINT('',#99448); -#99448 = CARTESIAN_POINT('',(3.65,-1.,-0.208196358798)); -#99449 = SURFACE_CURVE('',#99450,(#99454,#99466),.PCURVE_S1.); -#99450 = LINE('',#99451,#99452); -#99451 = CARTESIAN_POINT('',(3.65,-0.740726081328,-0.208196358798)); -#99452 = VECTOR('',#99453,1.); -#99453 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#99454 = PCURVE('',#99455,#99460); -#99455 = PLANE('',#99456); -#99456 = AXIS2_PLACEMENT_3D('',#99457,#99458,#99459); -#99457 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#99458 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99459 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99460 = DEFINITIONAL_REPRESENTATION('',(#99461),#99465); -#99461 = LINE('',#99462,#99463); -#99462 = CARTESIAN_POINT('',(-6.35,0.E+000)); -#99463 = VECTOR('',#99464,1.); -#99464 = DIRECTION('',(0.E+000,-1.)); -#99465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99466 = PCURVE('',#88928,#99467); -#99467 = DEFINITIONAL_REPRESENTATION('',(#99468),#99472); -#99468 = LINE('',#99469,#99470); -#99469 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#99470 = VECTOR('',#99471,1.); -#99471 = DIRECTION('',(0.E+000,-1.)); -#99472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99473 = ORIENTED_EDGE('',*,*,#99474,.T.); -#99474 = EDGE_CURVE('',#99447,#99475,#99477,.T.); -#99475 = VERTEX_POINT('',#99476); -#99476 = CARTESIAN_POINT('',(3.85,-1.,-0.208196358798)); -#99477 = SURFACE_CURVE('',#99478,(#99482,#99489),.PCURVE_S1.); -#99478 = LINE('',#99479,#99480); -#99479 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#99480 = VECTOR('',#99481,1.); -#99481 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99482 = PCURVE('',#99455,#99483); -#99483 = DEFINITIONAL_REPRESENTATION('',(#99484),#99488); -#99484 = LINE('',#99485,#99486); -#99485 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#99486 = VECTOR('',#99487,1.); -#99487 = DIRECTION('',(1.,0.E+000)); -#99488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99489 = PCURVE('',#99490,#99495); -#99490 = PLANE('',#99491); -#99491 = AXIS2_PLACEMENT_3D('',#99492,#99493,#99494); -#99492 = CARTESIAN_POINT('',(3.75,-1.,-0.258196742327)); -#99493 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#99494 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#99495 = DEFINITIONAL_REPRESENTATION('',(#99496),#99500); -#99496 = LINE('',#99497,#99498); -#99497 = CARTESIAN_POINT('',(-5.000038352949E-002,6.25)); -#99498 = VECTOR('',#99499,1.); -#99499 = DIRECTION('',(0.E+000,1.)); -#99500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99501 = ORIENTED_EDGE('',*,*,#99502,.F.); -#99502 = EDGE_CURVE('',#99503,#99475,#99505,.T.); -#99503 = VERTEX_POINT('',#99504); -#99504 = CARTESIAN_POINT('',(3.85,-0.740726081328,-0.208196358798)); -#99505 = SURFACE_CURVE('',#99506,(#99510,#99517),.PCURVE_S1.); -#99506 = LINE('',#99507,#99508); -#99507 = CARTESIAN_POINT('',(3.85,-0.740726081328,-0.208196358798)); -#99508 = VECTOR('',#99509,1.); -#99509 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#99510 = PCURVE('',#99455,#99511); -#99511 = DEFINITIONAL_REPRESENTATION('',(#99512),#99516); -#99512 = LINE('',#99513,#99514); -#99513 = CARTESIAN_POINT('',(-6.15,0.E+000)); -#99514 = VECTOR('',#99515,1.); -#99515 = DIRECTION('',(0.E+000,-1.)); -#99516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99517 = PCURVE('',#88872,#99518); -#99518 = DEFINITIONAL_REPRESENTATION('',(#99519),#99523); -#99519 = LINE('',#99520,#99521); -#99520 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#99521 = VECTOR('',#99522,1.); -#99522 = DIRECTION('',(0.E+000,-1.)); -#99523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99524 = ORIENTED_EDGE('',*,*,#99525,.T.); -#99525 = EDGE_CURVE('',#99503,#99445,#99526,.T.); -#99526 = SURFACE_CURVE('',#99527,(#99531,#99538),.PCURVE_S1.); -#99527 = LINE('',#99528,#99529); -#99528 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#99529 = VECTOR('',#99530,1.); -#99530 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99531 = PCURVE('',#99455,#99532); -#99532 = DEFINITIONAL_REPRESENTATION('',(#99533),#99537); -#99533 = LINE('',#99534,#99535); -#99534 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99535 = VECTOR('',#99536,1.); -#99536 = DIRECTION('',(-1.,0.E+000)); -#99537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99538 = PCURVE('',#99539,#99544); -#99539 = CYLINDRICAL_SURFACE('',#99540,0.208574704164); -#99540 = AXIS2_PLACEMENT_3D('',#99541,#99542,#99543); -#99541 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#99542 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99543 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99544 = DEFINITIONAL_REPRESENTATION('',(#99545),#99548); -#99545 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99546,#99547),.UNSPECIFIED., - .F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#99546 = CARTESIAN_POINT('',(3.201833915432,6.15)); -#99547 = CARTESIAN_POINT('',(3.201833915432,6.35)); -#99548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99549 = ADVANCED_FACE('',(#99550),#99564,.T.); -#99550 = FACE_BOUND('',#99551,.T.); -#99551 = EDGE_LOOP('',(#99552,#99582,#99605,#99628)); -#99552 = ORIENTED_EDGE('',*,*,#99553,.T.); -#99553 = EDGE_CURVE('',#99554,#99556,#99558,.T.); -#99554 = VERTEX_POINT('',#99555); -#99555 = CARTESIAN_POINT('',(3.85,-0.74341632541,-0.308197125857)); -#99556 = VERTEX_POINT('',#99557); -#99557 = CARTESIAN_POINT('',(3.85,-1.,-0.308197125857)); -#99558 = SURFACE_CURVE('',#99559,(#99563,#99575),.PCURVE_S1.); -#99559 = LINE('',#99560,#99561); -#99560 = CARTESIAN_POINT('',(3.85,-0.74341632541,-0.308197125857)); -#99561 = VECTOR('',#99562,1.); -#99562 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#99563 = PCURVE('',#99564,#99569); -#99564 = PLANE('',#99565); -#99565 = AXIS2_PLACEMENT_3D('',#99566,#99567,#99568); -#99566 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#99567 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99568 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99569 = DEFINITIONAL_REPRESENTATION('',(#99570),#99574); -#99570 = LINE('',#99571,#99572); -#99571 = CARTESIAN_POINT('',(6.15,0.E+000)); -#99572 = VECTOR('',#99573,1.); -#99573 = DIRECTION('',(0.E+000,-1.)); -#99574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99575 = PCURVE('',#88872,#99576); -#99576 = DEFINITIONAL_REPRESENTATION('',(#99577),#99581); -#99577 = LINE('',#99578,#99579); -#99578 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#99579 = VECTOR('',#99580,1.); -#99580 = DIRECTION('',(0.E+000,-1.)); -#99581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99582 = ORIENTED_EDGE('',*,*,#99583,.T.); -#99583 = EDGE_CURVE('',#99556,#99584,#99586,.T.); -#99584 = VERTEX_POINT('',#99585); -#99585 = CARTESIAN_POINT('',(3.65,-1.,-0.308197125857)); -#99586 = SURFACE_CURVE('',#99587,(#99591,#99598),.PCURVE_S1.); -#99587 = LINE('',#99588,#99589); -#99588 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#99589 = VECTOR('',#99590,1.); -#99590 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99591 = PCURVE('',#99564,#99592); -#99592 = DEFINITIONAL_REPRESENTATION('',(#99593),#99597); -#99593 = LINE('',#99594,#99595); -#99594 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#99595 = VECTOR('',#99596,1.); -#99596 = DIRECTION('',(1.,0.E+000)); -#99597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99598 = PCURVE('',#99490,#99599); -#99599 = DEFINITIONAL_REPRESENTATION('',(#99600),#99604); -#99600 = LINE('',#99601,#99602); -#99601 = CARTESIAN_POINT('',(5.000038352949E-002,6.25)); -#99602 = VECTOR('',#99603,1.); -#99603 = DIRECTION('',(0.E+000,-1.)); -#99604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99605 = ORIENTED_EDGE('',*,*,#99606,.F.); -#99606 = EDGE_CURVE('',#99607,#99584,#99609,.T.); -#99607 = VERTEX_POINT('',#99608); -#99608 = CARTESIAN_POINT('',(3.65,-0.74341632541,-0.308197125857)); -#99609 = SURFACE_CURVE('',#99610,(#99614,#99621),.PCURVE_S1.); -#99610 = LINE('',#99611,#99612); -#99611 = CARTESIAN_POINT('',(3.65,-0.74341632541,-0.308197125857)); -#99612 = VECTOR('',#99613,1.); -#99613 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#99614 = PCURVE('',#99564,#99615); -#99615 = DEFINITIONAL_REPRESENTATION('',(#99616),#99620); -#99616 = LINE('',#99617,#99618); -#99617 = CARTESIAN_POINT('',(6.35,0.E+000)); -#99618 = VECTOR('',#99619,1.); -#99619 = DIRECTION('',(0.E+000,-1.)); -#99620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99621 = PCURVE('',#88928,#99622); -#99622 = DEFINITIONAL_REPRESENTATION('',(#99623),#99627); -#99623 = LINE('',#99624,#99625); -#99624 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#99625 = VECTOR('',#99626,1.); -#99626 = DIRECTION('',(0.E+000,-1.)); -#99627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99628 = ORIENTED_EDGE('',*,*,#99629,.T.); -#99629 = EDGE_CURVE('',#99607,#99554,#99630,.T.); -#99630 = SURFACE_CURVE('',#99631,(#99635,#99642),.PCURVE_S1.); -#99631 = LINE('',#99632,#99633); -#99632 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#99633 = VECTOR('',#99634,1.); -#99634 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99635 = PCURVE('',#99564,#99636); -#99636 = DEFINITIONAL_REPRESENTATION('',(#99637),#99641); -#99637 = LINE('',#99638,#99639); -#99638 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99639 = VECTOR('',#99640,1.); -#99640 = DIRECTION('',(-1.,0.E+000)); -#99641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99642 = PCURVE('',#99643,#99648); -#99643 = CYLINDRICAL_SURFACE('',#99644,0.308574064194); -#99644 = AXIS2_PLACEMENT_3D('',#99645,#99646,#99647); -#99645 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#99646 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99647 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99648 = DEFINITIONAL_REPRESENTATION('',(#99649),#99652); -#99649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99650,#99651),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#99650 = CARTESIAN_POINT('',(3.191025391152,6.35)); -#99651 = CARTESIAN_POINT('',(3.191025391152,6.15)); -#99652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99653 = ADVANCED_FACE('',(#99654),#99539,.F.); -#99654 = FACE_BOUND('',#99655,.F.); -#99655 = EDGE_LOOP('',(#99656,#99657,#99684,#99711)); -#99656 = ORIENTED_EDGE('',*,*,#99525,.T.); -#99657 = ORIENTED_EDGE('',*,*,#99658,.F.); -#99658 = EDGE_CURVE('',#99659,#99445,#99661,.T.); -#99659 = VERTEX_POINT('',#99660); -#99660 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.E+000)); -#99661 = SURFACE_CURVE('',#99662,(#99667,#99673),.PCURVE_S1.); -#99662 = CIRCLE('',#99663,0.208574704164); -#99663 = AXIS2_PLACEMENT_3D('',#99664,#99665,#99666); -#99664 = CARTESIAN_POINT('',(3.65,-0.728168876214,2.640924866458E-017)); -#99665 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99666 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99667 = PCURVE('',#99539,#99668); -#99668 = DEFINITIONAL_REPRESENTATION('',(#99669),#99672); -#99669 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99670,#99671),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#101633 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#101634 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#101635 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#101636 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#101637 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#101638 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#101639 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#101640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101641 = ORIENTED_EDGE('',*,*,#101642,.T.); +#101642 = EDGE_CURVE('',#101616,#101592,#101643,.T.); +#101643 = SURFACE_CURVE('',#101644,(#101648,#101654),.PCURVE_S1.); +#101644 = LINE('',#101645,#101646); +#101645 = CARTESIAN_POINT('',(3.35,-0.304819755875,0.75)); +#101646 = VECTOR('',#101647,1.); +#101647 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101648 = PCURVE('',#101460,#101649); +#101649 = DEFINITIONAL_REPRESENTATION('',(#101650),#101653); +#101650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101651,#101652), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#101651 = CARTESIAN_POINT('',(3.162095483347,-6.65)); +#101652 = CARTESIAN_POINT('',(3.162095483347,-6.85)); +#101653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101654 = PCURVE('',#92139,#101655); +#101655 = DEFINITIONAL_REPRESENTATION('',(#101656),#101660); +#101656 = LINE('',#101657,#101658); +#101657 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#101658 = VECTOR('',#101659,1.); +#101659 = DIRECTION('',(0.E+000,-1.)); +#101660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101661 = ADVANCED_FACE('',(#101662),#92057,.F.); +#101662 = FACE_BOUND('',#101663,.T.); +#101663 = EDGE_LOOP('',(#101664,#101685,#101686,#101687,#101688,#101689, + #101710,#101711,#101712,#101713,#101714,#101735)); +#101664 = ORIENTED_EDGE('',*,*,#101665,.F.); +#101665 = EDGE_CURVE('',#101616,#92042,#101666,.T.); +#101666 = SURFACE_CURVE('',#101667,(#101671,#101678),.PCURVE_S1.); +#101667 = LINE('',#101668,#101669); +#101668 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.75)); +#101669 = VECTOR('',#101670,1.); +#101670 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#101671 = PCURVE('',#92057,#101672); +#101672 = DEFINITIONAL_REPRESENTATION('',(#101673),#101677); +#101673 = LINE('',#101674,#101675); +#101674 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#101675 = VECTOR('',#101676,1.); +#101676 = DIRECTION('',(3.563627120235E-016,1.)); +#101677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101678 = PCURVE('',#92139,#101679); +#101679 = DEFINITIONAL_REPRESENTATION('',(#101680),#101684); +#101680 = LINE('',#101681,#101682); +#101681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101682 = VECTOR('',#101683,1.); +#101683 = DIRECTION('',(1.,0.E+000)); +#101684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101685 = ORIENTED_EDGE('',*,*,#101615,.T.); +#101686 = ORIENTED_EDGE('',*,*,#101493,.T.); +#101687 = ORIENTED_EDGE('',*,*,#101264,.T.); +#101688 = ORIENTED_EDGE('',*,*,#101054,.T.); +#101689 = ORIENTED_EDGE('',*,*,#101690,.T.); +#101690 = EDGE_CURVE('',#101027,#101108,#101691,.T.); +#101691 = SURFACE_CURVE('',#101692,(#101696,#101703),.PCURVE_S1.); +#101692 = LINE('',#101693,#101694); +#101693 = CARTESIAN_POINT('',(3.35,-1.,1.159810404338E-002)); +#101694 = VECTOR('',#101695,1.); +#101695 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#101696 = PCURVE('',#92057,#101697); +#101697 = DEFINITIONAL_REPRESENTATION('',(#101698),#101702); +#101698 = LINE('',#101699,#101700); +#101699 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#101700 = VECTOR('',#101701,1.); +#101701 = DIRECTION('',(-1.,2.101748079665E-016)); +#101702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101703 = PCURVE('',#101042,#101704); +#101704 = DEFINITIONAL_REPRESENTATION('',(#101705),#101709); +#101705 = LINE('',#101706,#101707); +#101706 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#101707 = VECTOR('',#101708,1.); +#101708 = DIRECTION('',(1.,0.E+000)); +#101709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101710 = ORIENTED_EDGE('',*,*,#101105,.F.); +#101711 = ORIENTED_EDGE('',*,*,#101343,.F.); +#101712 = ORIENTED_EDGE('',*,*,#101396,.F.); +#101713 = ORIENTED_EDGE('',*,*,#101517,.F.); +#101714 = ORIENTED_EDGE('',*,*,#101715,.T.); +#101715 = EDGE_CURVE('',#101518,#92040,#101716,.T.); +#101716 = SURFACE_CURVE('',#101717,(#101721,#101728),.PCURVE_S1.); +#101717 = LINE('',#101718,#101719); +#101718 = CARTESIAN_POINT('',(3.35,-0.527847992439,0.65)); +#101719 = VECTOR('',#101720,1.); +#101720 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#101721 = PCURVE('',#92057,#101722); +#101722 = DEFINITIONAL_REPRESENTATION('',(#101723),#101727); +#101723 = LINE('',#101724,#101725); +#101724 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101725 = VECTOR('',#101726,1.); +#101726 = DIRECTION('',(3.563627120235E-016,1.)); +#101727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101728 = PCURVE('',#92085,#101729); +#101729 = DEFINITIONAL_REPRESENTATION('',(#101730),#101734); +#101730 = LINE('',#101731,#101732); +#101731 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101732 = VECTOR('',#101733,1.); +#101733 = DIRECTION('',(-1.,0.E+000)); +#101734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101735 = ORIENTED_EDGE('',*,*,#92039,.T.); +#101736 = ADVANCED_FACE('',(#101737),#92139,.F.); +#101737 = FACE_BOUND('',#101738,.T.); +#101738 = EDGE_LOOP('',(#101739,#101740,#101741,#101742)); +#101739 = ORIENTED_EDGE('',*,*,#101642,.F.); +#101740 = ORIENTED_EDGE('',*,*,#101665,.T.); +#101741 = ORIENTED_EDGE('',*,*,#92125,.T.); +#101742 = ORIENTED_EDGE('',*,*,#101743,.F.); +#101743 = EDGE_CURVE('',#101592,#92098,#101744,.T.); +#101744 = SURFACE_CURVE('',#101745,(#101749,#101756),.PCURVE_S1.); +#101745 = LINE('',#101746,#101747); +#101746 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.75)); +#101747 = VECTOR('',#101748,1.); +#101748 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#101749 = PCURVE('',#92139,#101750); +#101750 = DEFINITIONAL_REPRESENTATION('',(#101751),#101755); +#101751 = LINE('',#101752,#101753); +#101752 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#101753 = VECTOR('',#101754,1.); +#101754 = DIRECTION('',(1.,0.E+000)); +#101755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101756 = PCURVE('',#92113,#101757); +#101757 = DEFINITIONAL_REPRESENTATION('',(#101758),#101762); +#101758 = LINE('',#101759,#101760); +#101759 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#101760 = VECTOR('',#101761,1.); +#101761 = DIRECTION('',(-3.563627120235E-016,1.)); +#101762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101763 = ADVANCED_FACE('',(#101764),#92113,.F.); +#101764 = FACE_BOUND('',#101765,.T.); +#101765 = EDGE_LOOP('',(#101766,#101787,#101788,#101789,#101790,#101791, + #101812,#101813,#101814,#101815,#101816,#101817)); +#101766 = ORIENTED_EDGE('',*,*,#101767,.F.); +#101767 = EDGE_CURVE('',#101545,#92070,#101768,.T.); +#101768 = SURFACE_CURVE('',#101769,(#101773,#101780),.PCURVE_S1.); +#101769 = LINE('',#101770,#101771); +#101770 = CARTESIAN_POINT('',(3.15,-0.527847992439,0.65)); +#101771 = VECTOR('',#101772,1.); +#101772 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#101773 = PCURVE('',#92113,#101774); +#101774 = DEFINITIONAL_REPRESENTATION('',(#101775),#101779); +#101775 = LINE('',#101776,#101777); +#101776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101777 = VECTOR('',#101778,1.); +#101778 = DIRECTION('',(-3.563627120235E-016,1.)); +#101779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101780 = PCURVE('',#92085,#101781); +#101781 = DEFINITIONAL_REPRESENTATION('',(#101782),#101786); +#101782 = LINE('',#101783,#101784); +#101783 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#101784 = VECTOR('',#101785,1.); +#101785 = DIRECTION('',(-1.,0.E+000)); +#101786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101787 = ORIENTED_EDGE('',*,*,#101566,.T.); +#101788 = ORIENTED_EDGE('',*,*,#101418,.T.); +#101789 = ORIENTED_EDGE('',*,*,#101289,.T.); +#101790 = ORIENTED_EDGE('',*,*,#101158,.T.); +#101791 = ORIENTED_EDGE('',*,*,#101792,.T.); +#101792 = EDGE_CURVE('',#101136,#100999,#101793,.T.); +#101793 = SURFACE_CURVE('',#101794,(#101798,#101805),.PCURVE_S1.); +#101794 = LINE('',#101795,#101796); +#101795 = CARTESIAN_POINT('',(3.15,-1.,1.159810404338E-002)); +#101796 = VECTOR('',#101797,1.); +#101797 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#101798 = PCURVE('',#92113,#101799); +#101799 = DEFINITIONAL_REPRESENTATION('',(#101800),#101804); +#101800 = LINE('',#101801,#101802); +#101801 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#101802 = VECTOR('',#101803,1.); +#101803 = DIRECTION('',(-1.,-2.101748079665E-016)); +#101804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101805 = PCURVE('',#101042,#101806); +#101806 = DEFINITIONAL_REPRESENTATION('',(#101807),#101811); +#101807 = LINE('',#101808,#101809); +#101808 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#101809 = VECTOR('',#101810,1.); +#101810 = DIRECTION('',(-1.,0.E+000)); +#101811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101812 = ORIENTED_EDGE('',*,*,#100996,.F.); +#101813 = ORIENTED_EDGE('',*,*,#101210,.F.); +#101814 = ORIENTED_EDGE('',*,*,#101471,.F.); +#101815 = ORIENTED_EDGE('',*,*,#101591,.F.); +#101816 = ORIENTED_EDGE('',*,*,#101743,.T.); +#101817 = ORIENTED_EDGE('',*,*,#92097,.T.); +#101818 = ADVANCED_FACE('',(#101819),#92085,.F.); +#101819 = FACE_BOUND('',#101820,.T.); +#101820 = EDGE_LOOP('',(#101821,#101822,#101823,#101824)); +#101821 = ORIENTED_EDGE('',*,*,#101544,.F.); +#101822 = ORIENTED_EDGE('',*,*,#101767,.T.); +#101823 = ORIENTED_EDGE('',*,*,#92069,.T.); +#101824 = ORIENTED_EDGE('',*,*,#101715,.F.); +#101825 = ADVANCED_FACE('',(#101826),#101042,.T.); +#101826 = FACE_BOUND('',#101827,.T.); +#101827 = EDGE_LOOP('',(#101828,#101829,#101830,#101831)); +#101828 = ORIENTED_EDGE('',*,*,#101792,.F.); +#101829 = ORIENTED_EDGE('',*,*,#101135,.F.); +#101830 = ORIENTED_EDGE('',*,*,#101690,.F.); +#101831 = ORIENTED_EDGE('',*,*,#101026,.F.); +#101832 = ADVANCED_FACE('',(#101833),#101847,.T.); +#101833 = FACE_BOUND('',#101834,.T.); +#101834 = EDGE_LOOP('',(#101835,#101865,#101893,#101916)); +#101835 = ORIENTED_EDGE('',*,*,#101836,.T.); +#101836 = EDGE_CURVE('',#101837,#101839,#101841,.T.); +#101837 = VERTEX_POINT('',#101838); +#101838 = CARTESIAN_POINT('',(3.65,-0.740726081328,-0.208196358798)); +#101839 = VERTEX_POINT('',#101840); +#101840 = CARTESIAN_POINT('',(3.65,-1.,-0.208196358798)); +#101841 = SURFACE_CURVE('',#101842,(#101846,#101858),.PCURVE_S1.); +#101842 = LINE('',#101843,#101844); +#101843 = CARTESIAN_POINT('',(3.65,-0.740726081328,-0.208196358798)); +#101844 = VECTOR('',#101845,1.); +#101845 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101846 = PCURVE('',#101847,#101852); +#101847 = PLANE('',#101848); +#101848 = AXIS2_PLACEMENT_3D('',#101849,#101850,#101851); +#101849 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#101850 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101851 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101852 = DEFINITIONAL_REPRESENTATION('',(#101853),#101857); +#101853 = LINE('',#101854,#101855); +#101854 = CARTESIAN_POINT('',(-6.35,0.E+000)); +#101855 = VECTOR('',#101856,1.); +#101856 = DIRECTION('',(0.E+000,-1.)); +#101857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101858 = PCURVE('',#91320,#101859); +#101859 = DEFINITIONAL_REPRESENTATION('',(#101860),#101864); +#101860 = LINE('',#101861,#101862); +#101861 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#101862 = VECTOR('',#101863,1.); +#101863 = DIRECTION('',(0.E+000,-1.)); +#101864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101865 = ORIENTED_EDGE('',*,*,#101866,.T.); +#101866 = EDGE_CURVE('',#101839,#101867,#101869,.T.); +#101867 = VERTEX_POINT('',#101868); +#101868 = CARTESIAN_POINT('',(3.85,-1.,-0.208196358798)); +#101869 = SURFACE_CURVE('',#101870,(#101874,#101881),.PCURVE_S1.); +#101870 = LINE('',#101871,#101872); +#101871 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#101872 = VECTOR('',#101873,1.); +#101873 = DIRECTION('',(1.,0.E+000,0.E+000)); +#101874 = PCURVE('',#101847,#101875); +#101875 = DEFINITIONAL_REPRESENTATION('',(#101876),#101880); +#101876 = LINE('',#101877,#101878); +#101877 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#101878 = VECTOR('',#101879,1.); +#101879 = DIRECTION('',(1.,0.E+000)); +#101880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101881 = PCURVE('',#101882,#101887); +#101882 = PLANE('',#101883); +#101883 = AXIS2_PLACEMENT_3D('',#101884,#101885,#101886); +#101884 = CARTESIAN_POINT('',(3.75,-1.,-0.258196742327)); +#101885 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#101886 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#101887 = DEFINITIONAL_REPRESENTATION('',(#101888),#101892); +#101888 = LINE('',#101889,#101890); +#101889 = CARTESIAN_POINT('',(-5.000038352949E-002,6.25)); +#101890 = VECTOR('',#101891,1.); +#101891 = DIRECTION('',(0.E+000,1.)); +#101892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101893 = ORIENTED_EDGE('',*,*,#101894,.F.); +#101894 = EDGE_CURVE('',#101895,#101867,#101897,.T.); +#101895 = VERTEX_POINT('',#101896); +#101896 = CARTESIAN_POINT('',(3.85,-0.740726081328,-0.208196358798)); +#101897 = SURFACE_CURVE('',#101898,(#101902,#101909),.PCURVE_S1.); +#101898 = LINE('',#101899,#101900); +#101899 = CARTESIAN_POINT('',(3.85,-0.740726081328,-0.208196358798)); +#101900 = VECTOR('',#101901,1.); +#101901 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101902 = PCURVE('',#101847,#101903); +#101903 = DEFINITIONAL_REPRESENTATION('',(#101904),#101908); +#101904 = LINE('',#101905,#101906); +#101905 = CARTESIAN_POINT('',(-6.15,0.E+000)); +#101906 = VECTOR('',#101907,1.); +#101907 = DIRECTION('',(0.E+000,-1.)); +#101908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101909 = PCURVE('',#91264,#101910); +#101910 = DEFINITIONAL_REPRESENTATION('',(#101911),#101915); +#101911 = LINE('',#101912,#101913); +#101912 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#101913 = VECTOR('',#101914,1.); +#101914 = DIRECTION('',(0.E+000,-1.)); +#101915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101916 = ORIENTED_EDGE('',*,*,#101917,.T.); +#101917 = EDGE_CURVE('',#101895,#101837,#101918,.T.); +#101918 = SURFACE_CURVE('',#101919,(#101923,#101930),.PCURVE_S1.); +#101919 = LINE('',#101920,#101921); +#101920 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#101921 = VECTOR('',#101922,1.); +#101922 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101923 = PCURVE('',#101847,#101924); +#101924 = DEFINITIONAL_REPRESENTATION('',(#101925),#101929); +#101925 = LINE('',#101926,#101927); +#101926 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#101927 = VECTOR('',#101928,1.); +#101928 = DIRECTION('',(-1.,0.E+000)); +#101929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101930 = PCURVE('',#101931,#101936); +#101931 = CYLINDRICAL_SURFACE('',#101932,0.208574704164); +#101932 = AXIS2_PLACEMENT_3D('',#101933,#101934,#101935); +#101933 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#101934 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101935 = DIRECTION('',(0.E+000,0.E+000,1.)); +#101936 = DEFINITIONAL_REPRESENTATION('',(#101937),#101940); +#101937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101938,#101939), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); +#101938 = CARTESIAN_POINT('',(3.201833915432,6.15)); +#101939 = CARTESIAN_POINT('',(3.201833915432,6.35)); +#101940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101941 = ADVANCED_FACE('',(#101942),#101956,.T.); +#101942 = FACE_BOUND('',#101943,.T.); +#101943 = EDGE_LOOP('',(#101944,#101974,#101997,#102020)); +#101944 = ORIENTED_EDGE('',*,*,#101945,.T.); +#101945 = EDGE_CURVE('',#101946,#101948,#101950,.T.); +#101946 = VERTEX_POINT('',#101947); +#101947 = CARTESIAN_POINT('',(3.85,-0.74341632541,-0.308197125857)); +#101948 = VERTEX_POINT('',#101949); +#101949 = CARTESIAN_POINT('',(3.85,-1.,-0.308197125857)); +#101950 = SURFACE_CURVE('',#101951,(#101955,#101967),.PCURVE_S1.); +#101951 = LINE('',#101952,#101953); +#101952 = CARTESIAN_POINT('',(3.85,-0.74341632541,-0.308197125857)); +#101953 = VECTOR('',#101954,1.); +#101954 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#101955 = PCURVE('',#101956,#101961); +#101956 = PLANE('',#101957); +#101957 = AXIS2_PLACEMENT_3D('',#101958,#101959,#101960); +#101958 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#101959 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#101960 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101961 = DEFINITIONAL_REPRESENTATION('',(#101962),#101966); +#101962 = LINE('',#101963,#101964); +#101963 = CARTESIAN_POINT('',(6.15,0.E+000)); +#101964 = VECTOR('',#101965,1.); +#101965 = DIRECTION('',(0.E+000,-1.)); +#101966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101967 = PCURVE('',#91264,#101968); +#101968 = DEFINITIONAL_REPRESENTATION('',(#101969),#101973); +#101969 = LINE('',#101970,#101971); +#101970 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#101971 = VECTOR('',#101972,1.); +#101972 = DIRECTION('',(0.E+000,-1.)); +#101973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101974 = ORIENTED_EDGE('',*,*,#101975,.T.); +#101975 = EDGE_CURVE('',#101948,#101976,#101978,.T.); +#101976 = VERTEX_POINT('',#101977); +#101977 = CARTESIAN_POINT('',(3.65,-1.,-0.308197125857)); +#101978 = SURFACE_CURVE('',#101979,(#101983,#101990),.PCURVE_S1.); +#101979 = LINE('',#101980,#101981); +#101980 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#101981 = VECTOR('',#101982,1.); +#101982 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#101983 = PCURVE('',#101956,#101984); +#101984 = DEFINITIONAL_REPRESENTATION('',(#101985),#101989); +#101985 = LINE('',#101986,#101987); +#101986 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#101987 = VECTOR('',#101988,1.); +#101988 = DIRECTION('',(1.,0.E+000)); +#101989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101990 = PCURVE('',#101882,#101991); +#101991 = DEFINITIONAL_REPRESENTATION('',(#101992),#101996); +#101992 = LINE('',#101993,#101994); +#101993 = CARTESIAN_POINT('',(5.000038352949E-002,6.25)); +#101994 = VECTOR('',#101995,1.); +#101995 = DIRECTION('',(0.E+000,-1.)); +#101996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#101997 = ORIENTED_EDGE('',*,*,#101998,.F.); +#101998 = EDGE_CURVE('',#101999,#101976,#102001,.T.); +#101999 = VERTEX_POINT('',#102000); +#102000 = CARTESIAN_POINT('',(3.65,-0.74341632541,-0.308197125857)); +#102001 = SURFACE_CURVE('',#102002,(#102006,#102013),.PCURVE_S1.); +#102002 = LINE('',#102003,#102004); +#102003 = CARTESIAN_POINT('',(3.65,-0.74341632541,-0.308197125857)); +#102004 = VECTOR('',#102005,1.); +#102005 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#102006 = PCURVE('',#101956,#102007); +#102007 = DEFINITIONAL_REPRESENTATION('',(#102008),#102012); +#102008 = LINE('',#102009,#102010); +#102009 = CARTESIAN_POINT('',(6.35,0.E+000)); +#102010 = VECTOR('',#102011,1.); +#102011 = DIRECTION('',(0.E+000,-1.)); +#102012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102013 = PCURVE('',#91320,#102014); +#102014 = DEFINITIONAL_REPRESENTATION('',(#102015),#102019); +#102015 = LINE('',#102016,#102017); +#102016 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#102017 = VECTOR('',#102018,1.); +#102018 = DIRECTION('',(0.E+000,-1.)); +#102019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102020 = ORIENTED_EDGE('',*,*,#102021,.T.); +#102021 = EDGE_CURVE('',#101999,#101946,#102022,.T.); +#102022 = SURFACE_CURVE('',#102023,(#102027,#102034),.PCURVE_S1.); +#102023 = LINE('',#102024,#102025); +#102024 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#102025 = VECTOR('',#102026,1.); +#102026 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102027 = PCURVE('',#101956,#102028); +#102028 = DEFINITIONAL_REPRESENTATION('',(#102029),#102033); +#102029 = LINE('',#102030,#102031); +#102030 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102031 = VECTOR('',#102032,1.); +#102032 = DIRECTION('',(-1.,0.E+000)); +#102033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102034 = PCURVE('',#102035,#102040); +#102035 = CYLINDRICAL_SURFACE('',#102036,0.308574064194); +#102036 = AXIS2_PLACEMENT_3D('',#102037,#102038,#102039); +#102037 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#102038 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102039 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102040 = DEFINITIONAL_REPRESENTATION('',(#102041),#102044); +#102041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102042,#102043), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); +#102042 = CARTESIAN_POINT('',(3.191025391152,6.35)); +#102043 = CARTESIAN_POINT('',(3.191025391152,6.15)); +#102044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102045 = ADVANCED_FACE('',(#102046),#101931,.F.); +#102046 = FACE_BOUND('',#102047,.F.); +#102047 = EDGE_LOOP('',(#102048,#102049,#102076,#102103)); +#102048 = ORIENTED_EDGE('',*,*,#101917,.T.); +#102049 = ORIENTED_EDGE('',*,*,#102050,.F.); +#102050 = EDGE_CURVE('',#102051,#101837,#102053,.T.); +#102051 = VERTEX_POINT('',#102052); +#102052 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.E+000)); +#102053 = SURFACE_CURVE('',#102054,(#102059,#102065),.PCURVE_S1.); +#102054 = CIRCLE('',#102055,0.208574704164); +#102055 = AXIS2_PLACEMENT_3D('',#102056,#102057,#102058); +#102056 = CARTESIAN_POINT('',(3.65,-0.728168876214,2.640924866458E-017) + ); +#102057 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102058 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102059 = PCURVE('',#101931,#102060); +#102060 = DEFINITIONAL_REPRESENTATION('',(#102061),#102064); +#102061 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102062,#102063), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#99670 = CARTESIAN_POINT('',(1.570796326795,6.35)); -#99671 = CARTESIAN_POINT('',(3.201833915432,6.35)); -#99672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102062 = CARTESIAN_POINT('',(1.570796326795,6.35)); +#102063 = CARTESIAN_POINT('',(3.201833915432,6.35)); +#102064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99673 = PCURVE('',#88928,#99674); -#99674 = DEFINITIONAL_REPRESENTATION('',(#99675),#99683); -#99675 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99676,#99677,#99678,#99679 - ,#99680,#99681,#99682),.UNSPECIFIED.,.F.,.F.) +#102065 = PCURVE('',#91320,#102066); +#102066 = DEFINITIONAL_REPRESENTATION('',(#102067),#102075); +#102067 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102068,#102069,#102070, + #102071,#102072,#102073,#102074),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#99676 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#99677 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#99678 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#99679 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#99680 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#99681 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#99682 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#99683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99684 = ORIENTED_EDGE('',*,*,#99685,.T.); -#99685 = EDGE_CURVE('',#99659,#99686,#99688,.T.); -#99686 = VERTEX_POINT('',#99687); -#99687 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.E+000)); -#99688 = SURFACE_CURVE('',#99689,(#99693,#99699),.PCURVE_S1.); -#99689 = LINE('',#99690,#99691); -#99690 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#99691 = VECTOR('',#99692,1.); -#99692 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99693 = PCURVE('',#99539,#99694); -#99694 = DEFINITIONAL_REPRESENTATION('',(#99695),#99698); -#99695 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99696,#99697),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#99696 = CARTESIAN_POINT('',(1.570796326795,6.35)); -#99697 = CARTESIAN_POINT('',(1.570796326795,6.15)); -#99698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99699 = PCURVE('',#99700,#99705); -#99700 = PLANE('',#99701); -#99701 = AXIS2_PLACEMENT_3D('',#99702,#99703,#99704); -#99702 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#99703 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#99704 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#99705 = DEFINITIONAL_REPRESENTATION('',(#99706),#99710); -#99706 = LINE('',#99707,#99708); -#99707 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#99708 = VECTOR('',#99709,1.); -#99709 = DIRECTION('',(0.E+000,1.)); -#99710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99711 = ORIENTED_EDGE('',*,*,#99712,.T.); -#99712 = EDGE_CURVE('',#99686,#99503,#99713,.T.); -#99713 = SURFACE_CURVE('',#99714,(#99719,#99725),.PCURVE_S1.); -#99714 = CIRCLE('',#99715,0.208574704164); -#99715 = AXIS2_PLACEMENT_3D('',#99716,#99717,#99718); -#99716 = CARTESIAN_POINT('',(3.85,-0.728168876214,2.640924866458E-017)); -#99717 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99718 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99719 = PCURVE('',#99539,#99720); -#99720 = DEFINITIONAL_REPRESENTATION('',(#99721),#99724); -#99721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99722,#99723),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.201833915432), +#102068 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#102069 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#102070 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#102071 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#102072 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#102073 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#102074 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#102075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102076 = ORIENTED_EDGE('',*,*,#102077,.T.); +#102077 = EDGE_CURVE('',#102051,#102078,#102080,.T.); +#102078 = VERTEX_POINT('',#102079); +#102079 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.E+000)); +#102080 = SURFACE_CURVE('',#102081,(#102085,#102091),.PCURVE_S1.); +#102081 = LINE('',#102082,#102083); +#102082 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#102083 = VECTOR('',#102084,1.); +#102084 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102085 = PCURVE('',#101931,#102086); +#102086 = DEFINITIONAL_REPRESENTATION('',(#102087),#102090); +#102087 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102088,#102089), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); +#102088 = CARTESIAN_POINT('',(1.570796326795,6.35)); +#102089 = CARTESIAN_POINT('',(1.570796326795,6.15)); +#102090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102091 = PCURVE('',#102092,#102097); +#102092 = PLANE('',#102093); +#102093 = AXIS2_PLACEMENT_3D('',#102094,#102095,#102096); +#102094 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#102095 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#102096 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#102097 = DEFINITIONAL_REPRESENTATION('',(#102098),#102102); +#102098 = LINE('',#102099,#102100); +#102099 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#102100 = VECTOR('',#102101,1.); +#102101 = DIRECTION('',(0.E+000,1.)); +#102102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102103 = ORIENTED_EDGE('',*,*,#102104,.T.); +#102104 = EDGE_CURVE('',#102078,#101895,#102105,.T.); +#102105 = SURFACE_CURVE('',#102106,(#102111,#102117),.PCURVE_S1.); +#102106 = CIRCLE('',#102107,0.208574704164); +#102107 = AXIS2_PLACEMENT_3D('',#102108,#102109,#102110); +#102108 = CARTESIAN_POINT('',(3.85,-0.728168876214,2.640924866458E-017) + ); +#102109 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102110 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102111 = PCURVE('',#101931,#102112); +#102112 = DEFINITIONAL_REPRESENTATION('',(#102113),#102116); +#102113 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102114,#102115), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#99722 = CARTESIAN_POINT('',(1.570796326795,6.15)); -#99723 = CARTESIAN_POINT('',(3.201833915432,6.15)); -#99724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99725 = PCURVE('',#88872,#99726); -#99726 = DEFINITIONAL_REPRESENTATION('',(#99727),#99731); -#99727 = CIRCLE('',#99728,0.208574704164); -#99728 = AXIS2_PLACEMENT_2D('',#99729,#99730); -#99729 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#99730 = DIRECTION('',(1.,0.E+000)); -#99731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99732 = ADVANCED_FACE('',(#99733),#99643,.T.); -#99733 = FACE_BOUND('',#99734,.T.); -#99734 = EDGE_LOOP('',(#99735,#99736,#99763,#99790)); -#99735 = ORIENTED_EDGE('',*,*,#99629,.F.); -#99736 = ORIENTED_EDGE('',*,*,#99737,.F.); -#99737 = EDGE_CURVE('',#99738,#99607,#99740,.T.); -#99738 = VERTEX_POINT('',#99739); -#99739 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.E+000)); -#99740 = SURFACE_CURVE('',#99741,(#99746,#99752),.PCURVE_S1.); -#99741 = CIRCLE('',#99742,0.308574064194); -#99742 = AXIS2_PLACEMENT_3D('',#99743,#99744,#99745); -#99743 = CARTESIAN_POINT('',(3.65,-0.728168876214,2.640924866458E-017)); -#99744 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99745 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99746 = PCURVE('',#99643,#99747); -#99747 = DEFINITIONAL_REPRESENTATION('',(#99748),#99751); -#99748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99749,#99750),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#102114 = CARTESIAN_POINT('',(1.570796326795,6.15)); +#102115 = CARTESIAN_POINT('',(3.201833915432,6.15)); +#102116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102117 = PCURVE('',#91264,#102118); +#102118 = DEFINITIONAL_REPRESENTATION('',(#102119),#102123); +#102119 = CIRCLE('',#102120,0.208574704164); +#102120 = AXIS2_PLACEMENT_2D('',#102121,#102122); +#102121 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#102122 = DIRECTION('',(1.,0.E+000)); +#102123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102124 = ADVANCED_FACE('',(#102125),#102035,.T.); +#102125 = FACE_BOUND('',#102126,.T.); +#102126 = EDGE_LOOP('',(#102127,#102128,#102155,#102182)); +#102127 = ORIENTED_EDGE('',*,*,#102021,.F.); +#102128 = ORIENTED_EDGE('',*,*,#102129,.F.); +#102129 = EDGE_CURVE('',#102130,#101999,#102132,.T.); +#102130 = VERTEX_POINT('',#102131); +#102131 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.E+000)); +#102132 = SURFACE_CURVE('',#102133,(#102138,#102144),.PCURVE_S1.); +#102133 = CIRCLE('',#102134,0.308574064194); +#102134 = AXIS2_PLACEMENT_3D('',#102135,#102136,#102137); +#102135 = CARTESIAN_POINT('',(3.65,-0.728168876214,2.640924866458E-017) + ); +#102136 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102137 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102138 = PCURVE('',#102035,#102139); +#102139 = DEFINITIONAL_REPRESENTATION('',(#102140),#102143); +#102140 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102141,#102142), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#99749 = CARTESIAN_POINT('',(1.570796326795,6.35)); -#99750 = CARTESIAN_POINT('',(3.191025391152,6.35)); -#99751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102141 = CARTESIAN_POINT('',(1.570796326795,6.35)); +#102142 = CARTESIAN_POINT('',(3.191025391152,6.35)); +#102143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99752 = PCURVE('',#88928,#99753); -#99753 = DEFINITIONAL_REPRESENTATION('',(#99754),#99762); -#99754 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99755,#99756,#99757,#99758 - ,#99759,#99760,#99761),.UNSPECIFIED.,.T.,.F.) +#102144 = PCURVE('',#91320,#102145); +#102145 = DEFINITIONAL_REPRESENTATION('',(#102146),#102154); +#102146 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102147,#102148,#102149, + #102150,#102151,#102152,#102153),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#99755 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#99756 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#99757 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#99758 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#99759 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#99760 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#99761 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#99762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99763 = ORIENTED_EDGE('',*,*,#99764,.F.); -#99764 = EDGE_CURVE('',#99765,#99738,#99767,.T.); -#99765 = VERTEX_POINT('',#99766); -#99766 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.E+000)); -#99767 = SURFACE_CURVE('',#99768,(#99772,#99778),.PCURVE_S1.); -#99768 = LINE('',#99769,#99770); -#99769 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#99770 = VECTOR('',#99771,1.); -#99771 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99772 = PCURVE('',#99643,#99773); -#99773 = DEFINITIONAL_REPRESENTATION('',(#99774),#99777); -#99774 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99775,#99776),.UNSPECIFIED., - .F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#99775 = CARTESIAN_POINT('',(1.570796326795,6.15)); -#99776 = CARTESIAN_POINT('',(1.570796326795,6.35)); -#99777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99778 = PCURVE('',#99779,#99784); -#99779 = PLANE('',#99780); -#99780 = AXIS2_PLACEMENT_3D('',#99781,#99782,#99783); -#99781 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#99782 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#99783 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99784 = DEFINITIONAL_REPRESENTATION('',(#99785),#99789); -#99785 = LINE('',#99786,#99787); -#99786 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#99787 = VECTOR('',#99788,1.); -#99788 = DIRECTION('',(0.E+000,-1.)); -#99789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99790 = ORIENTED_EDGE('',*,*,#99791,.T.); -#99791 = EDGE_CURVE('',#99765,#99554,#99792,.T.); -#99792 = SURFACE_CURVE('',#99793,(#99798,#99804),.PCURVE_S1.); -#99793 = CIRCLE('',#99794,0.308574064194); -#99794 = AXIS2_PLACEMENT_3D('',#99795,#99796,#99797); -#99795 = CARTESIAN_POINT('',(3.85,-0.728168876214,2.640924866458E-017)); -#99796 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99797 = DIRECTION('',(0.E+000,0.E+000,1.)); -#99798 = PCURVE('',#99643,#99799); -#99799 = DEFINITIONAL_REPRESENTATION('',(#99800),#99803); -#99800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99801,#99802),.UNSPECIFIED., - .F.,.F.,(2,2),(1.570796326795,3.191025391152), +#102147 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#102148 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#102149 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#102150 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#102151 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#102152 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#102153 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#102154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102155 = ORIENTED_EDGE('',*,*,#102156,.F.); +#102156 = EDGE_CURVE('',#102157,#102130,#102159,.T.); +#102157 = VERTEX_POINT('',#102158); +#102158 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.E+000)); +#102159 = SURFACE_CURVE('',#102160,(#102164,#102170),.PCURVE_S1.); +#102160 = LINE('',#102161,#102162); +#102161 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#102162 = VECTOR('',#102163,1.); +#102163 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102164 = PCURVE('',#102035,#102165); +#102165 = DEFINITIONAL_REPRESENTATION('',(#102166),#102169); +#102166 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102167,#102168), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); +#102167 = CARTESIAN_POINT('',(1.570796326795,6.15)); +#102168 = CARTESIAN_POINT('',(1.570796326795,6.35)); +#102169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102170 = PCURVE('',#102171,#102176); +#102171 = PLANE('',#102172); +#102172 = AXIS2_PLACEMENT_3D('',#102173,#102174,#102175); +#102173 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#102174 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#102175 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#102176 = DEFINITIONAL_REPRESENTATION('',(#102177),#102181); +#102177 = LINE('',#102178,#102179); +#102178 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#102179 = VECTOR('',#102180,1.); +#102180 = DIRECTION('',(0.E+000,-1.)); +#102181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102182 = ORIENTED_EDGE('',*,*,#102183,.T.); +#102183 = EDGE_CURVE('',#102157,#101946,#102184,.T.); +#102184 = SURFACE_CURVE('',#102185,(#102190,#102196),.PCURVE_S1.); +#102185 = CIRCLE('',#102186,0.308574064194); +#102186 = AXIS2_PLACEMENT_3D('',#102187,#102188,#102189); +#102187 = CARTESIAN_POINT('',(3.85,-0.728168876214,2.640924866458E-017) + ); +#102188 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102189 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102190 = PCURVE('',#102035,#102191); +#102191 = DEFINITIONAL_REPRESENTATION('',(#102192),#102195); +#102192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102193,#102194), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#99801 = CARTESIAN_POINT('',(1.570796326795,6.15)); -#99802 = CARTESIAN_POINT('',(3.191025391152,6.15)); -#99803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102193 = CARTESIAN_POINT('',(1.570796326795,6.15)); +#102194 = CARTESIAN_POINT('',(3.191025391152,6.15)); +#102195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102196 = PCURVE('',#91264,#102197); +#102197 = DEFINITIONAL_REPRESENTATION('',(#102198),#102202); +#102198 = CIRCLE('',#102199,0.308574064194); +#102199 = AXIS2_PLACEMENT_2D('',#102200,#102201); +#102200 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#102201 = DIRECTION('',(1.,0.E+000)); +#102202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102203 = ADVANCED_FACE('',(#102204),#102171,.F.); +#102204 = FACE_BOUND('',#102205,.T.); +#102205 = EDGE_LOOP('',(#102206,#102235,#102256,#102257)); +#102206 = ORIENTED_EDGE('',*,*,#102207,.F.); +#102207 = EDGE_CURVE('',#102208,#102210,#102212,.T.); +#102208 = VERTEX_POINT('',#102209); +#102209 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.530776333563)); +#102210 = VERTEX_POINT('',#102211); +#102211 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.530776333563)); +#102212 = SURFACE_CURVE('',#102213,(#102217,#102224),.PCURVE_S1.); +#102213 = LINE('',#102214,#102215); +#102214 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#102215 = VECTOR('',#102216,1.); +#102216 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102217 = PCURVE('',#102171,#102218); +#102218 = DEFINITIONAL_REPRESENTATION('',(#102219),#102223); +#102219 = LINE('',#102220,#102221); +#102220 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102221 = VECTOR('',#102222,1.); +#102222 = DIRECTION('',(0.E+000,-1.)); +#102223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102224 = PCURVE('',#102225,#102230); +#102225 = CYLINDRICAL_SURFACE('',#102226,0.119270391569); +#102226 = AXIS2_PLACEMENT_3D('',#102227,#102228,#102229); +#102227 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#102228 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102229 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102230 = DEFINITIONAL_REPRESENTATION('',(#102231),#102234); +#102231 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102232,#102233), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); +#102232 = CARTESIAN_POINT('',(4.712388980385,-6.15)); +#102233 = CARTESIAN_POINT('',(4.712388980385,-6.35)); +#102234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102235 = ORIENTED_EDGE('',*,*,#102236,.T.); +#102236 = EDGE_CURVE('',#102208,#102157,#102237,.T.); +#102237 = SURFACE_CURVE('',#102238,(#102242,#102249),.PCURVE_S1.); +#102238 = LINE('',#102239,#102240); +#102239 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.530776333563)); +#102240 = VECTOR('',#102241,1.); +#102241 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#102242 = PCURVE('',#102171,#102243); +#102243 = DEFINITIONAL_REPRESENTATION('',(#102244),#102248); +#102244 = LINE('',#102245,#102246); +#102245 = CARTESIAN_POINT('',(0.E+000,-6.15)); +#102246 = VECTOR('',#102247,1.); +#102247 = DIRECTION('',(1.,0.E+000)); +#102248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102249 = PCURVE('',#91264,#102250); +#102250 = DEFINITIONAL_REPRESENTATION('',(#102251),#102255); +#102251 = LINE('',#102252,#102253); +#102252 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#102253 = VECTOR('',#102254,1.); +#102254 = DIRECTION('',(-1.,-1.021336205033E-016)); +#102255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102256 = ORIENTED_EDGE('',*,*,#102156,.T.); +#102257 = ORIENTED_EDGE('',*,*,#102258,.F.); +#102258 = EDGE_CURVE('',#102210,#102130,#102259,.T.); +#102259 = SURFACE_CURVE('',#102260,(#102264,#102271),.PCURVE_S1.); +#102260 = LINE('',#102261,#102262); +#102261 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.530776333563)); +#102262 = VECTOR('',#102263,1.); +#102263 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#102264 = PCURVE('',#102171,#102265); +#102265 = DEFINITIONAL_REPRESENTATION('',(#102266),#102270); +#102266 = LINE('',#102267,#102268); +#102267 = CARTESIAN_POINT('',(0.E+000,-6.35)); +#102268 = VECTOR('',#102269,1.); +#102269 = DIRECTION('',(1.,0.E+000)); +#102270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102271 = PCURVE('',#91320,#102272); +#102272 = DEFINITIONAL_REPRESENTATION('',(#102273),#102277); +#102273 = LINE('',#102274,#102275); +#102274 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#102275 = VECTOR('',#102276,1.); +#102276 = DIRECTION('',(1.,-1.021336205033E-016)); +#102277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102278 = ADVANCED_FACE('',(#102279),#102092,.F.); +#102279 = FACE_BOUND('',#102280,.T.); +#102280 = EDGE_LOOP('',(#102281,#102310,#102331,#102332)); +#102281 = ORIENTED_EDGE('',*,*,#102282,.F.); +#102282 = EDGE_CURVE('',#102283,#102285,#102287,.T.); +#102283 = VERTEX_POINT('',#102284); +#102284 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.530776333563)); +#102285 = VERTEX_POINT('',#102286); +#102286 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.530776333563)); +#102287 = SURFACE_CURVE('',#102288,(#102292,#102299),.PCURVE_S1.); +#102288 = LINE('',#102289,#102290); +#102289 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#102290 = VECTOR('',#102291,1.); +#102291 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102292 = PCURVE('',#102092,#102293); +#102293 = DEFINITIONAL_REPRESENTATION('',(#102294),#102298); +#102294 = LINE('',#102295,#102296); +#102295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102296 = VECTOR('',#102297,1.); +#102297 = DIRECTION('',(0.E+000,1.)); +#102298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102299 = PCURVE('',#102300,#102305); +#102300 = CYLINDRICAL_SURFACE('',#102301,0.2192697516); +#102301 = AXIS2_PLACEMENT_3D('',#102302,#102303,#102304); +#102302 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#102303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102305 = DEFINITIONAL_REPRESENTATION('',(#102306),#102309); +#102306 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102307,#102308), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); +#102307 = CARTESIAN_POINT('',(4.712388980385,-6.35)); +#102308 = CARTESIAN_POINT('',(4.712388980385,-6.15)); +#102309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99804 = PCURVE('',#88872,#99805); -#99805 = DEFINITIONAL_REPRESENTATION('',(#99806),#99810); -#99806 = CIRCLE('',#99807,0.308574064194); -#99807 = AXIS2_PLACEMENT_2D('',#99808,#99809); -#99808 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#99809 = DIRECTION('',(1.,0.E+000)); -#99810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102310 = ORIENTED_EDGE('',*,*,#102311,.T.); +#102311 = EDGE_CURVE('',#102283,#102051,#102312,.T.); +#102312 = SURFACE_CURVE('',#102313,(#102317,#102324),.PCURVE_S1.); +#102313 = LINE('',#102314,#102315); +#102314 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.530776333563)); +#102315 = VECTOR('',#102316,1.); +#102316 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#102317 = PCURVE('',#102092,#102318); +#102318 = DEFINITIONAL_REPRESENTATION('',(#102319),#102323); +#102319 = LINE('',#102320,#102321); +#102320 = CARTESIAN_POINT('',(0.E+000,-6.35)); +#102321 = VECTOR('',#102322,1.); +#102322 = DIRECTION('',(-1.,0.E+000)); +#102323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99811 = ADVANCED_FACE('',(#99812),#99779,.F.); -#99812 = FACE_BOUND('',#99813,.T.); -#99813 = EDGE_LOOP('',(#99814,#99843,#99864,#99865)); -#99814 = ORIENTED_EDGE('',*,*,#99815,.F.); -#99815 = EDGE_CURVE('',#99816,#99818,#99820,.T.); -#99816 = VERTEX_POINT('',#99817); -#99817 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.530776333563)); -#99818 = VERTEX_POINT('',#99819); -#99819 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.530776333563)); -#99820 = SURFACE_CURVE('',#99821,(#99825,#99832),.PCURVE_S1.); -#99821 = LINE('',#99822,#99823); -#99822 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#99823 = VECTOR('',#99824,1.); -#99824 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#99825 = PCURVE('',#99779,#99826); -#99826 = DEFINITIONAL_REPRESENTATION('',(#99827),#99831); -#99827 = LINE('',#99828,#99829); -#99828 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99829 = VECTOR('',#99830,1.); -#99830 = DIRECTION('',(0.E+000,-1.)); -#99831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99832 = PCURVE('',#99833,#99838); -#99833 = CYLINDRICAL_SURFACE('',#99834,0.119270391569); -#99834 = AXIS2_PLACEMENT_3D('',#99835,#99836,#99837); -#99835 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#99836 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99837 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99838 = DEFINITIONAL_REPRESENTATION('',(#99839),#99842); -#99839 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99840,#99841),.UNSPECIFIED., - .F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#99840 = CARTESIAN_POINT('',(4.712388980385,-6.15)); -#99841 = CARTESIAN_POINT('',(4.712388980385,-6.35)); -#99842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99843 = ORIENTED_EDGE('',*,*,#99844,.T.); -#99844 = EDGE_CURVE('',#99816,#99765,#99845,.T.); -#99845 = SURFACE_CURVE('',#99846,(#99850,#99857),.PCURVE_S1.); -#99846 = LINE('',#99847,#99848); -#99847 = CARTESIAN_POINT('',(3.85,-0.419594812019,0.530776333563)); -#99848 = VECTOR('',#99849,1.); -#99849 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99850 = PCURVE('',#99779,#99851); -#99851 = DEFINITIONAL_REPRESENTATION('',(#99852),#99856); -#99852 = LINE('',#99853,#99854); -#99853 = CARTESIAN_POINT('',(0.E+000,-6.15)); -#99854 = VECTOR('',#99855,1.); -#99855 = DIRECTION('',(1.,0.E+000)); -#99856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99857 = PCURVE('',#88872,#99858); -#99858 = DEFINITIONAL_REPRESENTATION('',(#99859),#99863); -#99859 = LINE('',#99860,#99861); -#99860 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#99861 = VECTOR('',#99862,1.); -#99862 = DIRECTION('',(-1.,-1.021336205033E-016)); -#99863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99864 = ORIENTED_EDGE('',*,*,#99764,.T.); -#99865 = ORIENTED_EDGE('',*,*,#99866,.F.); -#99866 = EDGE_CURVE('',#99818,#99738,#99867,.T.); -#99867 = SURFACE_CURVE('',#99868,(#99872,#99879),.PCURVE_S1.); -#99868 = LINE('',#99869,#99870); -#99869 = CARTESIAN_POINT('',(3.65,-0.419594812019,0.530776333563)); -#99870 = VECTOR('',#99871,1.); -#99871 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99872 = PCURVE('',#99779,#99873); -#99873 = DEFINITIONAL_REPRESENTATION('',(#99874),#99878); -#99874 = LINE('',#99875,#99876); -#99875 = CARTESIAN_POINT('',(0.E+000,-6.35)); -#99876 = VECTOR('',#99877,1.); -#99877 = DIRECTION('',(1.,0.E+000)); -#99878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99879 = PCURVE('',#88928,#99880); -#99880 = DEFINITIONAL_REPRESENTATION('',(#99881),#99885); -#99881 = LINE('',#99882,#99883); -#99882 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#99883 = VECTOR('',#99884,1.); -#99884 = DIRECTION('',(1.,-1.021336205033E-016)); -#99885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99886 = ADVANCED_FACE('',(#99887),#99700,.F.); -#99887 = FACE_BOUND('',#99888,.T.); -#99888 = EDGE_LOOP('',(#99889,#99918,#99939,#99940)); -#99889 = ORIENTED_EDGE('',*,*,#99890,.F.); -#99890 = EDGE_CURVE('',#99891,#99893,#99895,.T.); -#99891 = VERTEX_POINT('',#99892); -#99892 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.530776333563)); -#99893 = VERTEX_POINT('',#99894); -#99894 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.530776333563)); -#99895 = SURFACE_CURVE('',#99896,(#99900,#99907),.PCURVE_S1.); -#99896 = LINE('',#99897,#99898); -#99897 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#99898 = VECTOR('',#99899,1.); -#99899 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99900 = PCURVE('',#99700,#99901); -#99901 = DEFINITIONAL_REPRESENTATION('',(#99902),#99906); -#99902 = LINE('',#99903,#99904); -#99903 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#99904 = VECTOR('',#99905,1.); -#99905 = DIRECTION('',(0.E+000,1.)); -#99906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99907 = PCURVE('',#99908,#99913); -#99908 = CYLINDRICAL_SURFACE('',#99909,0.2192697516); -#99909 = AXIS2_PLACEMENT_3D('',#99910,#99911,#99912); -#99910 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#99911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99913 = DEFINITIONAL_REPRESENTATION('',(#99914),#99917); -#99914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99915,#99916),.UNSPECIFIED., - .F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#99915 = CARTESIAN_POINT('',(4.712388980385,-6.35)); -#99916 = CARTESIAN_POINT('',(4.712388980385,-6.15)); -#99917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99918 = ORIENTED_EDGE('',*,*,#99919,.T.); -#99919 = EDGE_CURVE('',#99891,#99659,#99920,.T.); -#99920 = SURFACE_CURVE('',#99921,(#99925,#99932),.PCURVE_S1.); -#99921 = LINE('',#99922,#99923); -#99922 = CARTESIAN_POINT('',(3.65,-0.51959417205,0.530776333563)); -#99923 = VECTOR('',#99924,1.); -#99924 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99925 = PCURVE('',#99700,#99926); -#99926 = DEFINITIONAL_REPRESENTATION('',(#99927),#99931); -#99927 = LINE('',#99928,#99929); -#99928 = CARTESIAN_POINT('',(0.E+000,-6.35)); -#99929 = VECTOR('',#99930,1.); -#99930 = DIRECTION('',(-1.,0.E+000)); -#99931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99932 = PCURVE('',#88928,#99933); -#99933 = DEFINITIONAL_REPRESENTATION('',(#99934),#99938); -#99934 = LINE('',#99935,#99936); -#99935 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#99936 = VECTOR('',#99937,1.); -#99937 = DIRECTION('',(1.,-1.021336205033E-016)); -#99938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99939 = ORIENTED_EDGE('',*,*,#99685,.T.); -#99940 = ORIENTED_EDGE('',*,*,#99941,.F.); -#99941 = EDGE_CURVE('',#99893,#99686,#99942,.T.); -#99942 = SURFACE_CURVE('',#99943,(#99947,#99954),.PCURVE_S1.); -#99943 = LINE('',#99944,#99945); -#99944 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.530776333563)); -#99945 = VECTOR('',#99946,1.); -#99946 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#99947 = PCURVE('',#99700,#99948); -#99948 = DEFINITIONAL_REPRESENTATION('',(#99949),#99953); -#99949 = LINE('',#99950,#99951); -#99950 = CARTESIAN_POINT('',(0.E+000,-6.15)); -#99951 = VECTOR('',#99952,1.); -#99952 = DIRECTION('',(-1.,0.E+000)); -#99953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99954 = PCURVE('',#88872,#99955); -#99955 = DEFINITIONAL_REPRESENTATION('',(#99956),#99960); -#99956 = LINE('',#99957,#99958); -#99957 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#99958 = VECTOR('',#99959,1.); -#99959 = DIRECTION('',(-1.,-1.021336205033E-016)); -#99960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102324 = PCURVE('',#91320,#102325); +#102325 = DEFINITIONAL_REPRESENTATION('',(#102326),#102330); +#102326 = LINE('',#102327,#102328); +#102327 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#102328 = VECTOR('',#102329,1.); +#102329 = DIRECTION('',(1.,-1.021336205033E-016)); +#102330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99961 = ADVANCED_FACE('',(#99962),#99833,.F.); -#99962 = FACE_BOUND('',#99963,.F.); -#99963 = EDGE_LOOP('',(#99964,#99991,#100013,#100034)); -#99964 = ORIENTED_EDGE('',*,*,#99965,.F.); -#99965 = EDGE_CURVE('',#99966,#99816,#99968,.T.); -#99966 = VERTEX_POINT('',#99967); -#99967 = CARTESIAN_POINT('',(3.85,-0.303662633502,0.65)); -#99968 = SURFACE_CURVE('',#99969,(#99974,#99980),.PCURVE_S1.); -#99969 = CIRCLE('',#99970,0.119270391569); -#99970 = AXIS2_PLACEMENT_3D('',#99971,#99972,#99973); -#99971 = CARTESIAN_POINT('',(3.85,-0.30032442045,0.530776333563)); -#99972 = DIRECTION('',(1.,0.E+000,0.E+000)); -#99973 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#99974 = PCURVE('',#99833,#99975); -#99975 = DEFINITIONAL_REPRESENTATION('',(#99976),#99979); -#99976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#99977,#99978),.UNSPECIFIED., - .F.,.F.,(2,2),(3.169584923929,4.712388980385), +#102331 = ORIENTED_EDGE('',*,*,#102077,.T.); +#102332 = ORIENTED_EDGE('',*,*,#102333,.F.); +#102333 = EDGE_CURVE('',#102285,#102078,#102334,.T.); +#102334 = SURFACE_CURVE('',#102335,(#102339,#102346),.PCURVE_S1.); +#102335 = LINE('',#102336,#102337); +#102336 = CARTESIAN_POINT('',(3.85,-0.51959417205,0.530776333563)); +#102337 = VECTOR('',#102338,1.); +#102338 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#102339 = PCURVE('',#102092,#102340); +#102340 = DEFINITIONAL_REPRESENTATION('',(#102341),#102345); +#102341 = LINE('',#102342,#102343); +#102342 = CARTESIAN_POINT('',(0.E+000,-6.15)); +#102343 = VECTOR('',#102344,1.); +#102344 = DIRECTION('',(-1.,0.E+000)); +#102345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102346 = PCURVE('',#91264,#102347); +#102347 = DEFINITIONAL_REPRESENTATION('',(#102348),#102352); +#102348 = LINE('',#102349,#102350); +#102349 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#102350 = VECTOR('',#102351,1.); +#102351 = DIRECTION('',(-1.,-1.021336205033E-016)); +#102352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102353 = ADVANCED_FACE('',(#102354),#102225,.F.); +#102354 = FACE_BOUND('',#102355,.F.); +#102355 = EDGE_LOOP('',(#102356,#102383,#102405,#102426)); +#102356 = ORIENTED_EDGE('',*,*,#102357,.F.); +#102357 = EDGE_CURVE('',#102358,#102208,#102360,.T.); +#102358 = VERTEX_POINT('',#102359); +#102359 = CARTESIAN_POINT('',(3.85,-0.303662633502,0.65)); +#102360 = SURFACE_CURVE('',#102361,(#102366,#102372),.PCURVE_S1.); +#102361 = CIRCLE('',#102362,0.119270391569); +#102362 = AXIS2_PLACEMENT_3D('',#102363,#102364,#102365); +#102363 = CARTESIAN_POINT('',(3.85,-0.30032442045,0.530776333563)); +#102364 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102365 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102366 = PCURVE('',#102225,#102367); +#102367 = DEFINITIONAL_REPRESENTATION('',(#102368),#102371); +#102368 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102369,#102370), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#99977 = CARTESIAN_POINT('',(3.169584923929,-6.15)); -#99978 = CARTESIAN_POINT('',(4.712388980385,-6.15)); -#99979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102369 = CARTESIAN_POINT('',(3.169584923929,-6.15)); +#102370 = CARTESIAN_POINT('',(4.712388980385,-6.15)); +#102371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#99980 = PCURVE('',#88872,#99981); -#99981 = DEFINITIONAL_REPRESENTATION('',(#99982),#99990); -#99982 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#99983,#99984,#99985,#99986 - ,#99987,#99988,#99989),.UNSPECIFIED.,.F.,.F.) +#102372 = PCURVE('',#91264,#102373); +#102373 = DEFINITIONAL_REPRESENTATION('',(#102374),#102382); +#102374 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102375,#102376,#102377, + #102378,#102379,#102380,#102381),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#99983 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#99984 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#99985 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#99986 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#99987 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#99988 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#99989 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#99990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#99991 = ORIENTED_EDGE('',*,*,#99992,.F.); -#99992 = EDGE_CURVE('',#99993,#99966,#99995,.T.); -#99993 = VERTEX_POINT('',#99994); -#99994 = CARTESIAN_POINT('',(3.65,-0.303662633502,0.65)); -#99995 = SURFACE_CURVE('',#99996,(#100000,#100006),.PCURVE_S1.); -#99996 = LINE('',#99997,#99998); -#99997 = CARTESIAN_POINT('',(3.85,-0.303662633502,0.65)); -#99998 = VECTOR('',#99999,1.); -#99999 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100000 = PCURVE('',#99833,#100001); -#100001 = DEFINITIONAL_REPRESENTATION('',(#100002),#100005); -#100002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100003,#100004), +#102375 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#102376 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#102377 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#102378 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#102379 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#102380 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#102381 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#102382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102383 = ORIENTED_EDGE('',*,*,#102384,.F.); +#102384 = EDGE_CURVE('',#102385,#102358,#102387,.T.); +#102385 = VERTEX_POINT('',#102386); +#102386 = CARTESIAN_POINT('',(3.65,-0.303662633502,0.65)); +#102387 = SURFACE_CURVE('',#102388,(#102392,#102398),.PCURVE_S1.); +#102388 = LINE('',#102389,#102390); +#102389 = CARTESIAN_POINT('',(3.85,-0.303662633502,0.65)); +#102390 = VECTOR('',#102391,1.); +#102391 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102392 = PCURVE('',#102225,#102393); +#102393 = DEFINITIONAL_REPRESENTATION('',(#102394),#102397); +#102394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102395,#102396), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#100003 = CARTESIAN_POINT('',(3.169584923929,-6.35)); -#100004 = CARTESIAN_POINT('',(3.169584923929,-6.15)); -#100005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100006 = PCURVE('',#88900,#100007); -#100007 = DEFINITIONAL_REPRESENTATION('',(#100008),#100012); -#100008 = LINE('',#100009,#100010); -#100009 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#100010 = VECTOR('',#100011,1.); -#100011 = DIRECTION('',(0.E+000,1.)); -#100012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100013 = ORIENTED_EDGE('',*,*,#100014,.T.); -#100014 = EDGE_CURVE('',#99993,#99818,#100015,.T.); -#100015 = SURFACE_CURVE('',#100016,(#100021,#100027),.PCURVE_S1.); -#100016 = CIRCLE('',#100017,0.119270391569); -#100017 = AXIS2_PLACEMENT_3D('',#100018,#100019,#100020); -#100018 = CARTESIAN_POINT('',(3.65,-0.30032442045,0.530776333563)); -#100019 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100020 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100021 = PCURVE('',#99833,#100022); -#100022 = DEFINITIONAL_REPRESENTATION('',(#100023),#100026); -#100023 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100024,#100025), +#102395 = CARTESIAN_POINT('',(3.169584923929,-6.35)); +#102396 = CARTESIAN_POINT('',(3.169584923929,-6.15)); +#102397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102398 = PCURVE('',#91292,#102399); +#102399 = DEFINITIONAL_REPRESENTATION('',(#102400),#102404); +#102400 = LINE('',#102401,#102402); +#102401 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#102402 = VECTOR('',#102403,1.); +#102403 = DIRECTION('',(0.E+000,1.)); +#102404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102405 = ORIENTED_EDGE('',*,*,#102406,.T.); +#102406 = EDGE_CURVE('',#102385,#102210,#102407,.T.); +#102407 = SURFACE_CURVE('',#102408,(#102413,#102419),.PCURVE_S1.); +#102408 = CIRCLE('',#102409,0.119270391569); +#102409 = AXIS2_PLACEMENT_3D('',#102410,#102411,#102412); +#102410 = CARTESIAN_POINT('',(3.65,-0.30032442045,0.530776333563)); +#102411 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102412 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102413 = PCURVE('',#102225,#102414); +#102414 = DEFINITIONAL_REPRESENTATION('',(#102415),#102418); +#102415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102416,#102417), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100024 = CARTESIAN_POINT('',(3.169584923929,-6.35)); -#100025 = CARTESIAN_POINT('',(4.712388980385,-6.35)); -#100026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100027 = PCURVE('',#88928,#100028); -#100028 = DEFINITIONAL_REPRESENTATION('',(#100029),#100033); -#100029 = CIRCLE('',#100030,0.119270391569); -#100030 = AXIS2_PLACEMENT_2D('',#100031,#100032); -#100031 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#100032 = DIRECTION('',(1.,0.E+000)); -#100033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100034 = ORIENTED_EDGE('',*,*,#99815,.F.); -#100035 = ADVANCED_FACE('',(#100036),#99908,.T.); -#100036 = FACE_BOUND('',#100037,.T.); -#100037 = EDGE_LOOP('',(#100038,#100061,#100062,#100089)); -#100038 = ORIENTED_EDGE('',*,*,#100039,.T.); -#100039 = EDGE_CURVE('',#100040,#99891,#100042,.T.); -#100040 = VERTEX_POINT('',#100041); -#100041 = CARTESIAN_POINT('',(3.65,-0.304819755875,0.75)); -#100042 = SURFACE_CURVE('',#100043,(#100048,#100054),.PCURVE_S1.); -#100043 = CIRCLE('',#100044,0.2192697516); -#100044 = AXIS2_PLACEMENT_3D('',#100045,#100046,#100047); -#100045 = CARTESIAN_POINT('',(3.65,-0.30032442045,0.530776333563)); -#100046 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100047 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100048 = PCURVE('',#99908,#100049); -#100049 = DEFINITIONAL_REPRESENTATION('',(#100050),#100053); -#100050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100051,#100052), +#102416 = CARTESIAN_POINT('',(3.169584923929,-6.35)); +#102417 = CARTESIAN_POINT('',(4.712388980385,-6.35)); +#102418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102419 = PCURVE('',#91320,#102420); +#102420 = DEFINITIONAL_REPRESENTATION('',(#102421),#102425); +#102421 = CIRCLE('',#102422,0.119270391569); +#102422 = AXIS2_PLACEMENT_2D('',#102423,#102424); +#102423 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#102424 = DIRECTION('',(1.,0.E+000)); +#102425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102426 = ORIENTED_EDGE('',*,*,#102207,.F.); +#102427 = ADVANCED_FACE('',(#102428),#102300,.T.); +#102428 = FACE_BOUND('',#102429,.T.); +#102429 = EDGE_LOOP('',(#102430,#102453,#102454,#102481)); +#102430 = ORIENTED_EDGE('',*,*,#102431,.T.); +#102431 = EDGE_CURVE('',#102432,#102283,#102434,.T.); +#102432 = VERTEX_POINT('',#102433); +#102433 = CARTESIAN_POINT('',(3.65,-0.304819755875,0.75)); +#102434 = SURFACE_CURVE('',#102435,(#102440,#102446),.PCURVE_S1.); +#102435 = CIRCLE('',#102436,0.2192697516); +#102436 = AXIS2_PLACEMENT_3D('',#102437,#102438,#102439); +#102437 = CARTESIAN_POINT('',(3.65,-0.30032442045,0.530776333563)); +#102438 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102439 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102440 = PCURVE('',#102300,#102441); +#102441 = DEFINITIONAL_REPRESENTATION('',(#102442),#102445); +#102442 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102443,#102444), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100051 = CARTESIAN_POINT('',(3.162095483347,-6.35)); -#100052 = CARTESIAN_POINT('',(4.712388980385,-6.35)); -#100053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100054 = PCURVE('',#88928,#100055); -#100055 = DEFINITIONAL_REPRESENTATION('',(#100056),#100060); -#100056 = CIRCLE('',#100057,0.2192697516); -#100057 = AXIS2_PLACEMENT_2D('',#100058,#100059); -#100058 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#100059 = DIRECTION('',(1.,0.E+000)); -#100060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100061 = ORIENTED_EDGE('',*,*,#99890,.T.); -#100062 = ORIENTED_EDGE('',*,*,#100063,.F.); -#100063 = EDGE_CURVE('',#100064,#99893,#100066,.T.); -#100064 = VERTEX_POINT('',#100065); -#100065 = CARTESIAN_POINT('',(3.85,-0.304819755875,0.75)); -#100066 = SURFACE_CURVE('',#100067,(#100072,#100078),.PCURVE_S1.); -#100067 = CIRCLE('',#100068,0.2192697516); -#100068 = AXIS2_PLACEMENT_3D('',#100069,#100070,#100071); -#100069 = CARTESIAN_POINT('',(3.85,-0.30032442045,0.530776333563)); -#100070 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100071 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100072 = PCURVE('',#99908,#100073); -#100073 = DEFINITIONAL_REPRESENTATION('',(#100074),#100077); -#100074 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100075,#100076), +#102443 = CARTESIAN_POINT('',(3.162095483347,-6.35)); +#102444 = CARTESIAN_POINT('',(4.712388980385,-6.35)); +#102445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102446 = PCURVE('',#91320,#102447); +#102447 = DEFINITIONAL_REPRESENTATION('',(#102448),#102452); +#102448 = CIRCLE('',#102449,0.2192697516); +#102449 = AXIS2_PLACEMENT_2D('',#102450,#102451); +#102450 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#102451 = DIRECTION('',(1.,0.E+000)); +#102452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102453 = ORIENTED_EDGE('',*,*,#102282,.T.); +#102454 = ORIENTED_EDGE('',*,*,#102455,.F.); +#102455 = EDGE_CURVE('',#102456,#102285,#102458,.T.); +#102456 = VERTEX_POINT('',#102457); +#102457 = CARTESIAN_POINT('',(3.85,-0.304819755875,0.75)); +#102458 = SURFACE_CURVE('',#102459,(#102464,#102470),.PCURVE_S1.); +#102459 = CIRCLE('',#102460,0.2192697516); +#102460 = AXIS2_PLACEMENT_3D('',#102461,#102462,#102463); +#102461 = CARTESIAN_POINT('',(3.85,-0.30032442045,0.530776333563)); +#102462 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102463 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102464 = PCURVE('',#102300,#102465); +#102465 = DEFINITIONAL_REPRESENTATION('',(#102466),#102469); +#102466 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102467,#102468), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100075 = CARTESIAN_POINT('',(3.162095483347,-6.15)); -#100076 = CARTESIAN_POINT('',(4.712388980385,-6.15)); -#100077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102467 = CARTESIAN_POINT('',(3.162095483347,-6.15)); +#102468 = CARTESIAN_POINT('',(4.712388980385,-6.15)); +#102469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100078 = PCURVE('',#88872,#100079); -#100079 = DEFINITIONAL_REPRESENTATION('',(#100080),#100088); -#100080 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100081,#100082,#100083, - #100084,#100085,#100086,#100087),.UNSPECIFIED.,.T.,.F.) +#102470 = PCURVE('',#91264,#102471); +#102471 = DEFINITIONAL_REPRESENTATION('',(#102472),#102480); +#102472 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102473,#102474,#102475, + #102476,#102477,#102478,#102479),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#100081 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#100082 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#100083 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#100084 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#100085 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#100086 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#100087 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#100088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100089 = ORIENTED_EDGE('',*,*,#100090,.T.); -#100090 = EDGE_CURVE('',#100064,#100040,#100091,.T.); -#100091 = SURFACE_CURVE('',#100092,(#100096,#100102),.PCURVE_S1.); -#100092 = LINE('',#100093,#100094); -#100093 = CARTESIAN_POINT('',(3.85,-0.304819755875,0.75)); -#100094 = VECTOR('',#100095,1.); -#100095 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100096 = PCURVE('',#99908,#100097); -#100097 = DEFINITIONAL_REPRESENTATION('',(#100098),#100101); -#100098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100099,#100100), +#102473 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#102474 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#102475 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#102476 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#102477 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#102478 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#102479 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#102480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102481 = ORIENTED_EDGE('',*,*,#102482,.T.); +#102482 = EDGE_CURVE('',#102456,#102432,#102483,.T.); +#102483 = SURFACE_CURVE('',#102484,(#102488,#102494),.PCURVE_S1.); +#102484 = LINE('',#102485,#102486); +#102485 = CARTESIAN_POINT('',(3.85,-0.304819755875,0.75)); +#102486 = VECTOR('',#102487,1.); +#102487 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102488 = PCURVE('',#102300,#102489); +#102489 = DEFINITIONAL_REPRESENTATION('',(#102490),#102493); +#102490 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102491,#102492), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#100099 = CARTESIAN_POINT('',(3.162095483347,-6.15)); -#100100 = CARTESIAN_POINT('',(3.162095483347,-6.35)); -#100101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100102 = PCURVE('',#88954,#100103); -#100103 = DEFINITIONAL_REPRESENTATION('',(#100104),#100108); -#100104 = LINE('',#100105,#100106); -#100105 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#100106 = VECTOR('',#100107,1.); -#100107 = DIRECTION('',(0.E+000,-1.)); -#100108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100109 = ADVANCED_FACE('',(#100110),#88872,.F.); -#100110 = FACE_BOUND('',#100111,.T.); -#100111 = EDGE_LOOP('',(#100112,#100133,#100134,#100135,#100136,#100137, - #100158,#100159,#100160,#100161,#100162,#100183)); -#100112 = ORIENTED_EDGE('',*,*,#100113,.F.); -#100113 = EDGE_CURVE('',#100064,#88857,#100114,.T.); -#100114 = SURFACE_CURVE('',#100115,(#100119,#100126),.PCURVE_S1.); -#100115 = LINE('',#100116,#100117); -#100116 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.75)); -#100117 = VECTOR('',#100118,1.); -#100118 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#100119 = PCURVE('',#88872,#100120); -#100120 = DEFINITIONAL_REPRESENTATION('',(#100121),#100125); -#100121 = LINE('',#100122,#100123); -#100122 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#100123 = VECTOR('',#100124,1.); -#100124 = DIRECTION('',(3.563627120235E-016,1.)); -#100125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100126 = PCURVE('',#88954,#100127); -#100127 = DEFINITIONAL_REPRESENTATION('',(#100128),#100132); -#100128 = LINE('',#100129,#100130); -#100129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100130 = VECTOR('',#100131,1.); -#100131 = DIRECTION('',(1.,0.E+000)); -#100132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100133 = ORIENTED_EDGE('',*,*,#100063,.T.); -#100134 = ORIENTED_EDGE('',*,*,#99941,.T.); -#100135 = ORIENTED_EDGE('',*,*,#99712,.T.); -#100136 = ORIENTED_EDGE('',*,*,#99502,.T.); -#100137 = ORIENTED_EDGE('',*,*,#100138,.T.); -#100138 = EDGE_CURVE('',#99475,#99556,#100139,.T.); -#100139 = SURFACE_CURVE('',#100140,(#100144,#100151),.PCURVE_S1.); -#100140 = LINE('',#100141,#100142); -#100141 = CARTESIAN_POINT('',(3.85,-1.,1.159810404338E-002)); -#100142 = VECTOR('',#100143,1.); -#100143 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#100144 = PCURVE('',#88872,#100145); -#100145 = DEFINITIONAL_REPRESENTATION('',(#100146),#100150); -#100146 = LINE('',#100147,#100148); -#100147 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#100148 = VECTOR('',#100149,1.); -#100149 = DIRECTION('',(-1.,2.101748079665E-016)); -#100150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100151 = PCURVE('',#99490,#100152); -#100152 = DEFINITIONAL_REPRESENTATION('',(#100153),#100157); -#100153 = LINE('',#100154,#100155); -#100154 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#100155 = VECTOR('',#100156,1.); -#100156 = DIRECTION('',(1.,0.E+000)); -#100157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100158 = ORIENTED_EDGE('',*,*,#99553,.F.); -#100159 = ORIENTED_EDGE('',*,*,#99791,.F.); -#100160 = ORIENTED_EDGE('',*,*,#99844,.F.); -#100161 = ORIENTED_EDGE('',*,*,#99965,.F.); -#100162 = ORIENTED_EDGE('',*,*,#100163,.T.); -#100163 = EDGE_CURVE('',#99966,#88855,#100164,.T.); -#100164 = SURFACE_CURVE('',#100165,(#100169,#100176),.PCURVE_S1.); -#100165 = LINE('',#100166,#100167); -#100166 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); -#100167 = VECTOR('',#100168,1.); -#100168 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#100169 = PCURVE('',#88872,#100170); -#100170 = DEFINITIONAL_REPRESENTATION('',(#100171),#100175); -#100171 = LINE('',#100172,#100173); -#100172 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100173 = VECTOR('',#100174,1.); -#100174 = DIRECTION('',(3.563627120235E-016,1.)); -#100175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100176 = PCURVE('',#88900,#100177); -#100177 = DEFINITIONAL_REPRESENTATION('',(#100178),#100182); -#100178 = LINE('',#100179,#100180); -#100179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100180 = VECTOR('',#100181,1.); -#100181 = DIRECTION('',(-1.,0.E+000)); -#100182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100183 = ORIENTED_EDGE('',*,*,#88854,.T.); -#100184 = ADVANCED_FACE('',(#100185),#88954,.F.); -#100185 = FACE_BOUND('',#100186,.T.); -#100186 = EDGE_LOOP('',(#100187,#100188,#100189,#100190)); -#100187 = ORIENTED_EDGE('',*,*,#100090,.F.); -#100188 = ORIENTED_EDGE('',*,*,#100113,.T.); -#100189 = ORIENTED_EDGE('',*,*,#88940,.T.); -#100190 = ORIENTED_EDGE('',*,*,#100191,.F.); -#100191 = EDGE_CURVE('',#100040,#88913,#100192,.T.); -#100192 = SURFACE_CURVE('',#100193,(#100197,#100204),.PCURVE_S1.); -#100193 = LINE('',#100194,#100195); -#100194 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.75)); -#100195 = VECTOR('',#100196,1.); -#100196 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#100197 = PCURVE('',#88954,#100198); -#100198 = DEFINITIONAL_REPRESENTATION('',(#100199),#100203); -#100199 = LINE('',#100200,#100201); -#100200 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#100201 = VECTOR('',#100202,1.); -#100202 = DIRECTION('',(1.,0.E+000)); -#100203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100204 = PCURVE('',#88928,#100205); -#100205 = DEFINITIONAL_REPRESENTATION('',(#100206),#100210); -#100206 = LINE('',#100207,#100208); -#100207 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#100208 = VECTOR('',#100209,1.); -#100209 = DIRECTION('',(-3.563627120235E-016,1.)); -#100210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100211 = ADVANCED_FACE('',(#100212),#88928,.F.); -#100212 = FACE_BOUND('',#100213,.T.); -#100213 = EDGE_LOOP('',(#100214,#100235,#100236,#100237,#100238,#100239, - #100260,#100261,#100262,#100263,#100264,#100265)); -#100214 = ORIENTED_EDGE('',*,*,#100215,.F.); -#100215 = EDGE_CURVE('',#99993,#88885,#100216,.T.); -#100216 = SURFACE_CURVE('',#100217,(#100221,#100228),.PCURVE_S1.); -#100217 = LINE('',#100218,#100219); -#100218 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.65)); -#100219 = VECTOR('',#100220,1.); -#100220 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#100221 = PCURVE('',#88928,#100222); -#100222 = DEFINITIONAL_REPRESENTATION('',(#100223),#100227); -#100223 = LINE('',#100224,#100225); -#100224 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100225 = VECTOR('',#100226,1.); -#100226 = DIRECTION('',(-3.563627120235E-016,1.)); -#100227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100228 = PCURVE('',#88900,#100229); -#100229 = DEFINITIONAL_REPRESENTATION('',(#100230),#100234); -#100230 = LINE('',#100231,#100232); -#100231 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#100232 = VECTOR('',#100233,1.); -#100233 = DIRECTION('',(-1.,0.E+000)); -#100234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100235 = ORIENTED_EDGE('',*,*,#100014,.T.); -#100236 = ORIENTED_EDGE('',*,*,#99866,.T.); -#100237 = ORIENTED_EDGE('',*,*,#99737,.T.); -#100238 = ORIENTED_EDGE('',*,*,#99606,.T.); -#100239 = ORIENTED_EDGE('',*,*,#100240,.T.); -#100240 = EDGE_CURVE('',#99584,#99447,#100241,.T.); -#100241 = SURFACE_CURVE('',#100242,(#100246,#100253),.PCURVE_S1.); -#100242 = LINE('',#100243,#100244); -#100243 = CARTESIAN_POINT('',(3.65,-1.,1.159810404338E-002)); -#100244 = VECTOR('',#100245,1.); -#100245 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#100246 = PCURVE('',#88928,#100247); -#100247 = DEFINITIONAL_REPRESENTATION('',(#100248),#100252); -#100248 = LINE('',#100249,#100250); -#100249 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#100250 = VECTOR('',#100251,1.); -#100251 = DIRECTION('',(-1.,-2.101748079665E-016)); -#100252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100253 = PCURVE('',#99490,#100254); -#100254 = DEFINITIONAL_REPRESENTATION('',(#100255),#100259); -#100255 = LINE('',#100256,#100257); -#100256 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#100257 = VECTOR('',#100258,1.); -#100258 = DIRECTION('',(-1.,0.E+000)); -#100259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100260 = ORIENTED_EDGE('',*,*,#99444,.F.); -#100261 = ORIENTED_EDGE('',*,*,#99658,.F.); -#100262 = ORIENTED_EDGE('',*,*,#99919,.F.); -#100263 = ORIENTED_EDGE('',*,*,#100039,.F.); -#100264 = ORIENTED_EDGE('',*,*,#100191,.T.); -#100265 = ORIENTED_EDGE('',*,*,#88912,.T.); -#100266 = ADVANCED_FACE('',(#100267),#88900,.F.); -#100267 = FACE_BOUND('',#100268,.T.); -#100268 = EDGE_LOOP('',(#100269,#100270,#100271,#100272)); -#100269 = ORIENTED_EDGE('',*,*,#99992,.F.); -#100270 = ORIENTED_EDGE('',*,*,#100215,.T.); -#100271 = ORIENTED_EDGE('',*,*,#88884,.T.); -#100272 = ORIENTED_EDGE('',*,*,#100163,.F.); -#100273 = ADVANCED_FACE('',(#100274),#99490,.T.); -#100274 = FACE_BOUND('',#100275,.T.); -#100275 = EDGE_LOOP('',(#100276,#100277,#100278,#100279)); -#100276 = ORIENTED_EDGE('',*,*,#100240,.F.); -#100277 = ORIENTED_EDGE('',*,*,#99583,.F.); -#100278 = ORIENTED_EDGE('',*,*,#100138,.F.); -#100279 = ORIENTED_EDGE('',*,*,#99474,.F.); -#100280 = ADVANCED_FACE('',(#100281),#100295,.T.); -#100281 = FACE_BOUND('',#100282,.T.); -#100282 = EDGE_LOOP('',(#100283,#100313,#100341,#100364)); -#100283 = ORIENTED_EDGE('',*,*,#100284,.T.); -#100284 = EDGE_CURVE('',#100285,#100287,#100289,.T.); -#100285 = VERTEX_POINT('',#100286); -#100286 = CARTESIAN_POINT('',(4.15,-0.740726081328,-0.208196358798)); -#100287 = VERTEX_POINT('',#100288); -#100288 = CARTESIAN_POINT('',(4.15,-1.,-0.208196358798)); -#100289 = SURFACE_CURVE('',#100290,(#100294,#100306),.PCURVE_S1.); -#100290 = LINE('',#100291,#100292); -#100291 = CARTESIAN_POINT('',(4.15,-0.740726081328,-0.208196358798)); -#100292 = VECTOR('',#100293,1.); -#100293 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#100294 = PCURVE('',#100295,#100300); -#100295 = PLANE('',#100296); -#100296 = AXIS2_PLACEMENT_3D('',#100297,#100298,#100299); -#100297 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#100298 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100299 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100300 = DEFINITIONAL_REPRESENTATION('',(#100301),#100305); -#100301 = LINE('',#100302,#100303); -#100302 = CARTESIAN_POINT('',(-5.85,0.E+000)); -#100303 = VECTOR('',#100304,1.); -#100304 = DIRECTION('',(0.E+000,-1.)); -#100305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100306 = PCURVE('',#89835,#100307); -#100307 = DEFINITIONAL_REPRESENTATION('',(#100308),#100312); -#100308 = LINE('',#100309,#100310); -#100309 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#100310 = VECTOR('',#100311,1.); -#100311 = DIRECTION('',(0.E+000,-1.)); -#100312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100313 = ORIENTED_EDGE('',*,*,#100314,.T.); -#100314 = EDGE_CURVE('',#100287,#100315,#100317,.T.); -#100315 = VERTEX_POINT('',#100316); -#100316 = CARTESIAN_POINT('',(4.35,-1.,-0.208196358798)); -#100317 = SURFACE_CURVE('',#100318,(#100322,#100329),.PCURVE_S1.); -#100318 = LINE('',#100319,#100320); -#100319 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#100320 = VECTOR('',#100321,1.); -#100321 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100322 = PCURVE('',#100295,#100323); -#100323 = DEFINITIONAL_REPRESENTATION('',(#100324),#100328); -#100324 = LINE('',#100325,#100326); -#100325 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#100326 = VECTOR('',#100327,1.); -#100327 = DIRECTION('',(1.,0.E+000)); -#100328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100329 = PCURVE('',#100330,#100335); -#100330 = PLANE('',#100331); -#100331 = AXIS2_PLACEMENT_3D('',#100332,#100333,#100334); -#100332 = CARTESIAN_POINT('',(4.25,-1.,-0.258196742327)); -#100333 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#100334 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#100335 = DEFINITIONAL_REPRESENTATION('',(#100336),#100340); -#100336 = LINE('',#100337,#100338); -#100337 = CARTESIAN_POINT('',(-5.000038352949E-002,5.75)); -#100338 = VECTOR('',#100339,1.); -#100339 = DIRECTION('',(0.E+000,1.)); -#100340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100341 = ORIENTED_EDGE('',*,*,#100342,.F.); -#100342 = EDGE_CURVE('',#100343,#100315,#100345,.T.); -#100343 = VERTEX_POINT('',#100344); -#100344 = CARTESIAN_POINT('',(4.35,-0.740726081328,-0.208196358798)); -#100345 = SURFACE_CURVE('',#100346,(#100350,#100357),.PCURVE_S1.); -#100346 = LINE('',#100347,#100348); -#100347 = CARTESIAN_POINT('',(4.35,-0.740726081328,-0.208196358798)); -#100348 = VECTOR('',#100349,1.); -#100349 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#100350 = PCURVE('',#100295,#100351); -#100351 = DEFINITIONAL_REPRESENTATION('',(#100352),#100356); -#100352 = LINE('',#100353,#100354); -#100353 = CARTESIAN_POINT('',(-5.65,0.E+000)); -#100354 = VECTOR('',#100355,1.); -#100355 = DIRECTION('',(0.E+000,-1.)); -#100356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100357 = PCURVE('',#89779,#100358); -#100358 = DEFINITIONAL_REPRESENTATION('',(#100359),#100363); -#100359 = LINE('',#100360,#100361); -#100360 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#100361 = VECTOR('',#100362,1.); -#100362 = DIRECTION('',(0.E+000,-1.)); -#100363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100364 = ORIENTED_EDGE('',*,*,#100365,.T.); -#100365 = EDGE_CURVE('',#100343,#100285,#100366,.T.); -#100366 = SURFACE_CURVE('',#100367,(#100371,#100378),.PCURVE_S1.); -#100367 = LINE('',#100368,#100369); -#100368 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#100369 = VECTOR('',#100370,1.); -#100370 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100371 = PCURVE('',#100295,#100372); -#100372 = DEFINITIONAL_REPRESENTATION('',(#100373),#100377); -#100373 = LINE('',#100374,#100375); -#100374 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100375 = VECTOR('',#100376,1.); -#100376 = DIRECTION('',(-1.,0.E+000)); -#100377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100378 = PCURVE('',#100379,#100384); -#100379 = CYLINDRICAL_SURFACE('',#100380,0.208574704164); -#100380 = AXIS2_PLACEMENT_3D('',#100381,#100382,#100383); -#100381 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#100382 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100383 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100384 = DEFINITIONAL_REPRESENTATION('',(#100385),#100388); -#100385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100386,#100387), +#102491 = CARTESIAN_POINT('',(3.162095483347,-6.15)); +#102492 = CARTESIAN_POINT('',(3.162095483347,-6.35)); +#102493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102494 = PCURVE('',#91346,#102495); +#102495 = DEFINITIONAL_REPRESENTATION('',(#102496),#102500); +#102496 = LINE('',#102497,#102498); +#102497 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#102498 = VECTOR('',#102499,1.); +#102499 = DIRECTION('',(0.E+000,-1.)); +#102500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102501 = ADVANCED_FACE('',(#102502),#91264,.F.); +#102502 = FACE_BOUND('',#102503,.T.); +#102503 = EDGE_LOOP('',(#102504,#102525,#102526,#102527,#102528,#102529, + #102550,#102551,#102552,#102553,#102554,#102575)); +#102504 = ORIENTED_EDGE('',*,*,#102505,.F.); +#102505 = EDGE_CURVE('',#102456,#91249,#102506,.T.); +#102506 = SURFACE_CURVE('',#102507,(#102511,#102518),.PCURVE_S1.); +#102507 = LINE('',#102508,#102509); +#102508 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.75)); +#102509 = VECTOR('',#102510,1.); +#102510 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#102511 = PCURVE('',#91264,#102512); +#102512 = DEFINITIONAL_REPRESENTATION('',(#102513),#102517); +#102513 = LINE('',#102514,#102515); +#102514 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#102515 = VECTOR('',#102516,1.); +#102516 = DIRECTION('',(3.563627120235E-016,1.)); +#102517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102518 = PCURVE('',#91346,#102519); +#102519 = DEFINITIONAL_REPRESENTATION('',(#102520),#102524); +#102520 = LINE('',#102521,#102522); +#102521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102522 = VECTOR('',#102523,1.); +#102523 = DIRECTION('',(1.,0.E+000)); +#102524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102525 = ORIENTED_EDGE('',*,*,#102455,.T.); +#102526 = ORIENTED_EDGE('',*,*,#102333,.T.); +#102527 = ORIENTED_EDGE('',*,*,#102104,.T.); +#102528 = ORIENTED_EDGE('',*,*,#101894,.T.); +#102529 = ORIENTED_EDGE('',*,*,#102530,.T.); +#102530 = EDGE_CURVE('',#101867,#101948,#102531,.T.); +#102531 = SURFACE_CURVE('',#102532,(#102536,#102543),.PCURVE_S1.); +#102532 = LINE('',#102533,#102534); +#102533 = CARTESIAN_POINT('',(3.85,-1.,1.159810404338E-002)); +#102534 = VECTOR('',#102535,1.); +#102535 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#102536 = PCURVE('',#91264,#102537); +#102537 = DEFINITIONAL_REPRESENTATION('',(#102538),#102542); +#102538 = LINE('',#102539,#102540); +#102539 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#102540 = VECTOR('',#102541,1.); +#102541 = DIRECTION('',(-1.,2.101748079665E-016)); +#102542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102543 = PCURVE('',#101882,#102544); +#102544 = DEFINITIONAL_REPRESENTATION('',(#102545),#102549); +#102545 = LINE('',#102546,#102547); +#102546 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#102547 = VECTOR('',#102548,1.); +#102548 = DIRECTION('',(1.,0.E+000)); +#102549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102550 = ORIENTED_EDGE('',*,*,#101945,.F.); +#102551 = ORIENTED_EDGE('',*,*,#102183,.F.); +#102552 = ORIENTED_EDGE('',*,*,#102236,.F.); +#102553 = ORIENTED_EDGE('',*,*,#102357,.F.); +#102554 = ORIENTED_EDGE('',*,*,#102555,.T.); +#102555 = EDGE_CURVE('',#102358,#91247,#102556,.T.); +#102556 = SURFACE_CURVE('',#102557,(#102561,#102568),.PCURVE_S1.); +#102557 = LINE('',#102558,#102559); +#102558 = CARTESIAN_POINT('',(3.85,-0.527847992439,0.65)); +#102559 = VECTOR('',#102560,1.); +#102560 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#102561 = PCURVE('',#91264,#102562); +#102562 = DEFINITIONAL_REPRESENTATION('',(#102563),#102567); +#102563 = LINE('',#102564,#102565); +#102564 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102565 = VECTOR('',#102566,1.); +#102566 = DIRECTION('',(3.563627120235E-016,1.)); +#102567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102568 = PCURVE('',#91292,#102569); +#102569 = DEFINITIONAL_REPRESENTATION('',(#102570),#102574); +#102570 = LINE('',#102571,#102572); +#102571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102572 = VECTOR('',#102573,1.); +#102573 = DIRECTION('',(-1.,0.E+000)); +#102574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102575 = ORIENTED_EDGE('',*,*,#91246,.T.); +#102576 = ADVANCED_FACE('',(#102577),#91346,.F.); +#102577 = FACE_BOUND('',#102578,.T.); +#102578 = EDGE_LOOP('',(#102579,#102580,#102581,#102582)); +#102579 = ORIENTED_EDGE('',*,*,#102482,.F.); +#102580 = ORIENTED_EDGE('',*,*,#102505,.T.); +#102581 = ORIENTED_EDGE('',*,*,#91332,.T.); +#102582 = ORIENTED_EDGE('',*,*,#102583,.F.); +#102583 = EDGE_CURVE('',#102432,#91305,#102584,.T.); +#102584 = SURFACE_CURVE('',#102585,(#102589,#102596),.PCURVE_S1.); +#102585 = LINE('',#102586,#102587); +#102586 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.75)); +#102587 = VECTOR('',#102588,1.); +#102588 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#102589 = PCURVE('',#91346,#102590); +#102590 = DEFINITIONAL_REPRESENTATION('',(#102591),#102595); +#102591 = LINE('',#102592,#102593); +#102592 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#102593 = VECTOR('',#102594,1.); +#102594 = DIRECTION('',(1.,0.E+000)); +#102595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102596 = PCURVE('',#91320,#102597); +#102597 = DEFINITIONAL_REPRESENTATION('',(#102598),#102602); +#102598 = LINE('',#102599,#102600); +#102599 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#102600 = VECTOR('',#102601,1.); +#102601 = DIRECTION('',(-3.563627120235E-016,1.)); +#102602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102603 = ADVANCED_FACE('',(#102604),#91320,.F.); +#102604 = FACE_BOUND('',#102605,.T.); +#102605 = EDGE_LOOP('',(#102606,#102627,#102628,#102629,#102630,#102631, + #102652,#102653,#102654,#102655,#102656,#102657)); +#102606 = ORIENTED_EDGE('',*,*,#102607,.F.); +#102607 = EDGE_CURVE('',#102385,#91277,#102608,.T.); +#102608 = SURFACE_CURVE('',#102609,(#102613,#102620),.PCURVE_S1.); +#102609 = LINE('',#102610,#102611); +#102610 = CARTESIAN_POINT('',(3.65,-0.527847992439,0.65)); +#102611 = VECTOR('',#102612,1.); +#102612 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#102613 = PCURVE('',#91320,#102614); +#102614 = DEFINITIONAL_REPRESENTATION('',(#102615),#102619); +#102615 = LINE('',#102616,#102617); +#102616 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102617 = VECTOR('',#102618,1.); +#102618 = DIRECTION('',(-3.563627120235E-016,1.)); +#102619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102620 = PCURVE('',#91292,#102621); +#102621 = DEFINITIONAL_REPRESENTATION('',(#102622),#102626); +#102622 = LINE('',#102623,#102624); +#102623 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#102624 = VECTOR('',#102625,1.); +#102625 = DIRECTION('',(-1.,0.E+000)); +#102626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102627 = ORIENTED_EDGE('',*,*,#102406,.T.); +#102628 = ORIENTED_EDGE('',*,*,#102258,.T.); +#102629 = ORIENTED_EDGE('',*,*,#102129,.T.); +#102630 = ORIENTED_EDGE('',*,*,#101998,.T.); +#102631 = ORIENTED_EDGE('',*,*,#102632,.T.); +#102632 = EDGE_CURVE('',#101976,#101839,#102633,.T.); +#102633 = SURFACE_CURVE('',#102634,(#102638,#102645),.PCURVE_S1.); +#102634 = LINE('',#102635,#102636); +#102635 = CARTESIAN_POINT('',(3.65,-1.,1.159810404338E-002)); +#102636 = VECTOR('',#102637,1.); +#102637 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#102638 = PCURVE('',#91320,#102639); +#102639 = DEFINITIONAL_REPRESENTATION('',(#102640),#102644); +#102640 = LINE('',#102641,#102642); +#102641 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#102642 = VECTOR('',#102643,1.); +#102643 = DIRECTION('',(-1.,-2.101748079665E-016)); +#102644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102645 = PCURVE('',#101882,#102646); +#102646 = DEFINITIONAL_REPRESENTATION('',(#102647),#102651); +#102647 = LINE('',#102648,#102649); +#102648 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#102649 = VECTOR('',#102650,1.); +#102650 = DIRECTION('',(-1.,0.E+000)); +#102651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102652 = ORIENTED_EDGE('',*,*,#101836,.F.); +#102653 = ORIENTED_EDGE('',*,*,#102050,.F.); +#102654 = ORIENTED_EDGE('',*,*,#102311,.F.); +#102655 = ORIENTED_EDGE('',*,*,#102431,.F.); +#102656 = ORIENTED_EDGE('',*,*,#102583,.T.); +#102657 = ORIENTED_EDGE('',*,*,#91304,.T.); +#102658 = ADVANCED_FACE('',(#102659),#91292,.F.); +#102659 = FACE_BOUND('',#102660,.T.); +#102660 = EDGE_LOOP('',(#102661,#102662,#102663,#102664)); +#102661 = ORIENTED_EDGE('',*,*,#102384,.F.); +#102662 = ORIENTED_EDGE('',*,*,#102607,.T.); +#102663 = ORIENTED_EDGE('',*,*,#91276,.T.); +#102664 = ORIENTED_EDGE('',*,*,#102555,.F.); +#102665 = ADVANCED_FACE('',(#102666),#101882,.T.); +#102666 = FACE_BOUND('',#102667,.T.); +#102667 = EDGE_LOOP('',(#102668,#102669,#102670,#102671)); +#102668 = ORIENTED_EDGE('',*,*,#102632,.F.); +#102669 = ORIENTED_EDGE('',*,*,#101975,.F.); +#102670 = ORIENTED_EDGE('',*,*,#102530,.F.); +#102671 = ORIENTED_EDGE('',*,*,#101866,.F.); +#102672 = ADVANCED_FACE('',(#102673),#102687,.T.); +#102673 = FACE_BOUND('',#102674,.T.); +#102674 = EDGE_LOOP('',(#102675,#102705,#102733,#102756)); +#102675 = ORIENTED_EDGE('',*,*,#102676,.T.); +#102676 = EDGE_CURVE('',#102677,#102679,#102681,.T.); +#102677 = VERTEX_POINT('',#102678); +#102678 = CARTESIAN_POINT('',(4.15,-0.740726081328,-0.208196358798)); +#102679 = VERTEX_POINT('',#102680); +#102680 = CARTESIAN_POINT('',(4.15,-1.,-0.208196358798)); +#102681 = SURFACE_CURVE('',#102682,(#102686,#102698),.PCURVE_S1.); +#102682 = LINE('',#102683,#102684); +#102683 = CARTESIAN_POINT('',(4.15,-0.740726081328,-0.208196358798)); +#102684 = VECTOR('',#102685,1.); +#102685 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#102686 = PCURVE('',#102687,#102692); +#102687 = PLANE('',#102688); +#102688 = AXIS2_PLACEMENT_3D('',#102689,#102690,#102691); +#102689 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#102690 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102691 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102692 = DEFINITIONAL_REPRESENTATION('',(#102693),#102697); +#102693 = LINE('',#102694,#102695); +#102694 = CARTESIAN_POINT('',(-5.85,0.E+000)); +#102695 = VECTOR('',#102696,1.); +#102696 = DIRECTION('',(0.E+000,-1.)); +#102697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102698 = PCURVE('',#92227,#102699); +#102699 = DEFINITIONAL_REPRESENTATION('',(#102700),#102704); +#102700 = LINE('',#102701,#102702); +#102701 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#102702 = VECTOR('',#102703,1.); +#102703 = DIRECTION('',(0.E+000,-1.)); +#102704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102705 = ORIENTED_EDGE('',*,*,#102706,.T.); +#102706 = EDGE_CURVE('',#102679,#102707,#102709,.T.); +#102707 = VERTEX_POINT('',#102708); +#102708 = CARTESIAN_POINT('',(4.35,-1.,-0.208196358798)); +#102709 = SURFACE_CURVE('',#102710,(#102714,#102721),.PCURVE_S1.); +#102710 = LINE('',#102711,#102712); +#102711 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#102712 = VECTOR('',#102713,1.); +#102713 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102714 = PCURVE('',#102687,#102715); +#102715 = DEFINITIONAL_REPRESENTATION('',(#102716),#102720); +#102716 = LINE('',#102717,#102718); +#102717 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#102718 = VECTOR('',#102719,1.); +#102719 = DIRECTION('',(1.,0.E+000)); +#102720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102721 = PCURVE('',#102722,#102727); +#102722 = PLANE('',#102723); +#102723 = AXIS2_PLACEMENT_3D('',#102724,#102725,#102726); +#102724 = CARTESIAN_POINT('',(4.25,-1.,-0.258196742327)); +#102725 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#102726 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#102727 = DEFINITIONAL_REPRESENTATION('',(#102728),#102732); +#102728 = LINE('',#102729,#102730); +#102729 = CARTESIAN_POINT('',(-5.000038352949E-002,5.75)); +#102730 = VECTOR('',#102731,1.); +#102731 = DIRECTION('',(0.E+000,1.)); +#102732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102733 = ORIENTED_EDGE('',*,*,#102734,.F.); +#102734 = EDGE_CURVE('',#102735,#102707,#102737,.T.); +#102735 = VERTEX_POINT('',#102736); +#102736 = CARTESIAN_POINT('',(4.35,-0.740726081328,-0.208196358798)); +#102737 = SURFACE_CURVE('',#102738,(#102742,#102749),.PCURVE_S1.); +#102738 = LINE('',#102739,#102740); +#102739 = CARTESIAN_POINT('',(4.35,-0.740726081328,-0.208196358798)); +#102740 = VECTOR('',#102741,1.); +#102741 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#102742 = PCURVE('',#102687,#102743); +#102743 = DEFINITIONAL_REPRESENTATION('',(#102744),#102748); +#102744 = LINE('',#102745,#102746); +#102745 = CARTESIAN_POINT('',(-5.65,0.E+000)); +#102746 = VECTOR('',#102747,1.); +#102747 = DIRECTION('',(0.E+000,-1.)); +#102748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102749 = PCURVE('',#92171,#102750); +#102750 = DEFINITIONAL_REPRESENTATION('',(#102751),#102755); +#102751 = LINE('',#102752,#102753); +#102752 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#102753 = VECTOR('',#102754,1.); +#102754 = DIRECTION('',(0.E+000,-1.)); +#102755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102756 = ORIENTED_EDGE('',*,*,#102757,.T.); +#102757 = EDGE_CURVE('',#102735,#102677,#102758,.T.); +#102758 = SURFACE_CURVE('',#102759,(#102763,#102770),.PCURVE_S1.); +#102759 = LINE('',#102760,#102761); +#102760 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#102761 = VECTOR('',#102762,1.); +#102762 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102763 = PCURVE('',#102687,#102764); +#102764 = DEFINITIONAL_REPRESENTATION('',(#102765),#102769); +#102765 = LINE('',#102766,#102767); +#102766 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102767 = VECTOR('',#102768,1.); +#102768 = DIRECTION('',(-1.,0.E+000)); +#102769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102770 = PCURVE('',#102771,#102776); +#102771 = CYLINDRICAL_SURFACE('',#102772,0.208574704164); +#102772 = AXIS2_PLACEMENT_3D('',#102773,#102774,#102775); +#102773 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#102774 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102775 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102776 = DEFINITIONAL_REPRESENTATION('',(#102777),#102780); +#102777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102778,#102779), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#100386 = CARTESIAN_POINT('',(3.201833915432,5.65)); -#100387 = CARTESIAN_POINT('',(3.201833915432,5.85)); -#100388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100389 = ADVANCED_FACE('',(#100390),#100404,.T.); -#100390 = FACE_BOUND('',#100391,.T.); -#100391 = EDGE_LOOP('',(#100392,#100422,#100445,#100468)); -#100392 = ORIENTED_EDGE('',*,*,#100393,.T.); -#100393 = EDGE_CURVE('',#100394,#100396,#100398,.T.); -#100394 = VERTEX_POINT('',#100395); -#100395 = CARTESIAN_POINT('',(4.35,-0.74341632541,-0.308197125857)); -#100396 = VERTEX_POINT('',#100397); -#100397 = CARTESIAN_POINT('',(4.35,-1.,-0.308197125857)); -#100398 = SURFACE_CURVE('',#100399,(#100403,#100415),.PCURVE_S1.); -#100399 = LINE('',#100400,#100401); -#100400 = CARTESIAN_POINT('',(4.35,-0.74341632541,-0.308197125857)); -#100401 = VECTOR('',#100402,1.); -#100402 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#100403 = PCURVE('',#100404,#100409); -#100404 = PLANE('',#100405); -#100405 = AXIS2_PLACEMENT_3D('',#100406,#100407,#100408); -#100406 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#100407 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100408 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100409 = DEFINITIONAL_REPRESENTATION('',(#100410),#100414); -#100410 = LINE('',#100411,#100412); -#100411 = CARTESIAN_POINT('',(5.65,0.E+000)); -#100412 = VECTOR('',#100413,1.); -#100413 = DIRECTION('',(0.E+000,-1.)); -#100414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100415 = PCURVE('',#89779,#100416); -#100416 = DEFINITIONAL_REPRESENTATION('',(#100417),#100421); -#100417 = LINE('',#100418,#100419); -#100418 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#100419 = VECTOR('',#100420,1.); -#100420 = DIRECTION('',(0.E+000,-1.)); -#100421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100422 = ORIENTED_EDGE('',*,*,#100423,.T.); -#100423 = EDGE_CURVE('',#100396,#100424,#100426,.T.); -#100424 = VERTEX_POINT('',#100425); -#100425 = CARTESIAN_POINT('',(4.15,-1.,-0.308197125857)); -#100426 = SURFACE_CURVE('',#100427,(#100431,#100438),.PCURVE_S1.); -#100427 = LINE('',#100428,#100429); -#100428 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#100429 = VECTOR('',#100430,1.); -#100430 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100431 = PCURVE('',#100404,#100432); -#100432 = DEFINITIONAL_REPRESENTATION('',(#100433),#100437); -#100433 = LINE('',#100434,#100435); -#100434 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#100435 = VECTOR('',#100436,1.); -#100436 = DIRECTION('',(1.,0.E+000)); -#100437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100438 = PCURVE('',#100330,#100439); -#100439 = DEFINITIONAL_REPRESENTATION('',(#100440),#100444); -#100440 = LINE('',#100441,#100442); -#100441 = CARTESIAN_POINT('',(5.000038352949E-002,5.75)); -#100442 = VECTOR('',#100443,1.); -#100443 = DIRECTION('',(0.E+000,-1.)); -#100444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100445 = ORIENTED_EDGE('',*,*,#100446,.F.); -#100446 = EDGE_CURVE('',#100447,#100424,#100449,.T.); -#100447 = VERTEX_POINT('',#100448); -#100448 = CARTESIAN_POINT('',(4.15,-0.74341632541,-0.308197125857)); -#100449 = SURFACE_CURVE('',#100450,(#100454,#100461),.PCURVE_S1.); -#100450 = LINE('',#100451,#100452); -#100451 = CARTESIAN_POINT('',(4.15,-0.74341632541,-0.308197125857)); -#100452 = VECTOR('',#100453,1.); -#100453 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#100454 = PCURVE('',#100404,#100455); -#100455 = DEFINITIONAL_REPRESENTATION('',(#100456),#100460); -#100456 = LINE('',#100457,#100458); -#100457 = CARTESIAN_POINT('',(5.85,0.E+000)); -#100458 = VECTOR('',#100459,1.); -#100459 = DIRECTION('',(0.E+000,-1.)); -#100460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100461 = PCURVE('',#89835,#100462); -#100462 = DEFINITIONAL_REPRESENTATION('',(#100463),#100467); -#100463 = LINE('',#100464,#100465); -#100464 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#100465 = VECTOR('',#100466,1.); -#100466 = DIRECTION('',(0.E+000,-1.)); -#100467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100468 = ORIENTED_EDGE('',*,*,#100469,.T.); -#100469 = EDGE_CURVE('',#100447,#100394,#100470,.T.); -#100470 = SURFACE_CURVE('',#100471,(#100475,#100482),.PCURVE_S1.); -#100471 = LINE('',#100472,#100473); -#100472 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#100473 = VECTOR('',#100474,1.); -#100474 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100475 = PCURVE('',#100404,#100476); -#100476 = DEFINITIONAL_REPRESENTATION('',(#100477),#100481); -#100477 = LINE('',#100478,#100479); -#100478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100479 = VECTOR('',#100480,1.); -#100480 = DIRECTION('',(-1.,0.E+000)); -#100481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100482 = PCURVE('',#100483,#100488); -#100483 = CYLINDRICAL_SURFACE('',#100484,0.308574064194); -#100484 = AXIS2_PLACEMENT_3D('',#100485,#100486,#100487); -#100485 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#100486 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100487 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100488 = DEFINITIONAL_REPRESENTATION('',(#100489),#100492); -#100489 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100490,#100491), +#102778 = CARTESIAN_POINT('',(3.201833915432,5.65)); +#102779 = CARTESIAN_POINT('',(3.201833915432,5.85)); +#102780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102781 = ADVANCED_FACE('',(#102782),#102796,.T.); +#102782 = FACE_BOUND('',#102783,.T.); +#102783 = EDGE_LOOP('',(#102784,#102814,#102837,#102860)); +#102784 = ORIENTED_EDGE('',*,*,#102785,.T.); +#102785 = EDGE_CURVE('',#102786,#102788,#102790,.T.); +#102786 = VERTEX_POINT('',#102787); +#102787 = CARTESIAN_POINT('',(4.35,-0.74341632541,-0.308197125857)); +#102788 = VERTEX_POINT('',#102789); +#102789 = CARTESIAN_POINT('',(4.35,-1.,-0.308197125857)); +#102790 = SURFACE_CURVE('',#102791,(#102795,#102807),.PCURVE_S1.); +#102791 = LINE('',#102792,#102793); +#102792 = CARTESIAN_POINT('',(4.35,-0.74341632541,-0.308197125857)); +#102793 = VECTOR('',#102794,1.); +#102794 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#102795 = PCURVE('',#102796,#102801); +#102796 = PLANE('',#102797); +#102797 = AXIS2_PLACEMENT_3D('',#102798,#102799,#102800); +#102798 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#102799 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#102800 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102801 = DEFINITIONAL_REPRESENTATION('',(#102802),#102806); +#102802 = LINE('',#102803,#102804); +#102803 = CARTESIAN_POINT('',(5.65,0.E+000)); +#102804 = VECTOR('',#102805,1.); +#102805 = DIRECTION('',(0.E+000,-1.)); +#102806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102807 = PCURVE('',#92171,#102808); +#102808 = DEFINITIONAL_REPRESENTATION('',(#102809),#102813); +#102809 = LINE('',#102810,#102811); +#102810 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#102811 = VECTOR('',#102812,1.); +#102812 = DIRECTION('',(0.E+000,-1.)); +#102813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102814 = ORIENTED_EDGE('',*,*,#102815,.T.); +#102815 = EDGE_CURVE('',#102788,#102816,#102818,.T.); +#102816 = VERTEX_POINT('',#102817); +#102817 = CARTESIAN_POINT('',(4.15,-1.,-0.308197125857)); +#102818 = SURFACE_CURVE('',#102819,(#102823,#102830),.PCURVE_S1.); +#102819 = LINE('',#102820,#102821); +#102820 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#102821 = VECTOR('',#102822,1.); +#102822 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102823 = PCURVE('',#102796,#102824); +#102824 = DEFINITIONAL_REPRESENTATION('',(#102825),#102829); +#102825 = LINE('',#102826,#102827); +#102826 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#102827 = VECTOR('',#102828,1.); +#102828 = DIRECTION('',(1.,0.E+000)); +#102829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102830 = PCURVE('',#102722,#102831); +#102831 = DEFINITIONAL_REPRESENTATION('',(#102832),#102836); +#102832 = LINE('',#102833,#102834); +#102833 = CARTESIAN_POINT('',(5.000038352949E-002,5.75)); +#102834 = VECTOR('',#102835,1.); +#102835 = DIRECTION('',(0.E+000,-1.)); +#102836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102837 = ORIENTED_EDGE('',*,*,#102838,.F.); +#102838 = EDGE_CURVE('',#102839,#102816,#102841,.T.); +#102839 = VERTEX_POINT('',#102840); +#102840 = CARTESIAN_POINT('',(4.15,-0.74341632541,-0.308197125857)); +#102841 = SURFACE_CURVE('',#102842,(#102846,#102853),.PCURVE_S1.); +#102842 = LINE('',#102843,#102844); +#102843 = CARTESIAN_POINT('',(4.15,-0.74341632541,-0.308197125857)); +#102844 = VECTOR('',#102845,1.); +#102845 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#102846 = PCURVE('',#102796,#102847); +#102847 = DEFINITIONAL_REPRESENTATION('',(#102848),#102852); +#102848 = LINE('',#102849,#102850); +#102849 = CARTESIAN_POINT('',(5.85,0.E+000)); +#102850 = VECTOR('',#102851,1.); +#102851 = DIRECTION('',(0.E+000,-1.)); +#102852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102853 = PCURVE('',#92227,#102854); +#102854 = DEFINITIONAL_REPRESENTATION('',(#102855),#102859); +#102855 = LINE('',#102856,#102857); +#102856 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#102857 = VECTOR('',#102858,1.); +#102858 = DIRECTION('',(0.E+000,-1.)); +#102859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102860 = ORIENTED_EDGE('',*,*,#102861,.T.); +#102861 = EDGE_CURVE('',#102839,#102786,#102862,.T.); +#102862 = SURFACE_CURVE('',#102863,(#102867,#102874),.PCURVE_S1.); +#102863 = LINE('',#102864,#102865); +#102864 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#102865 = VECTOR('',#102866,1.); +#102866 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102867 = PCURVE('',#102796,#102868); +#102868 = DEFINITIONAL_REPRESENTATION('',(#102869),#102873); +#102869 = LINE('',#102870,#102871); +#102870 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#102871 = VECTOR('',#102872,1.); +#102872 = DIRECTION('',(-1.,0.E+000)); +#102873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102874 = PCURVE('',#102875,#102880); +#102875 = CYLINDRICAL_SURFACE('',#102876,0.308574064194); +#102876 = AXIS2_PLACEMENT_3D('',#102877,#102878,#102879); +#102877 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#102878 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102879 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102880 = DEFINITIONAL_REPRESENTATION('',(#102881),#102884); +#102881 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102882,#102883), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#100490 = CARTESIAN_POINT('',(3.191025391152,5.85)); -#100491 = CARTESIAN_POINT('',(3.191025391152,5.65)); -#100492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100493 = ADVANCED_FACE('',(#100494),#100379,.F.); -#100494 = FACE_BOUND('',#100495,.F.); -#100495 = EDGE_LOOP('',(#100496,#100497,#100524,#100551)); -#100496 = ORIENTED_EDGE('',*,*,#100365,.T.); -#100497 = ORIENTED_EDGE('',*,*,#100498,.F.); -#100498 = EDGE_CURVE('',#100499,#100285,#100501,.T.); -#100499 = VERTEX_POINT('',#100500); -#100500 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.E+000)); -#100501 = SURFACE_CURVE('',#100502,(#100507,#100513),.PCURVE_S1.); -#100502 = CIRCLE('',#100503,0.208574704164); -#100503 = AXIS2_PLACEMENT_3D('',#100504,#100505,#100506); -#100504 = CARTESIAN_POINT('',(4.15,-0.728168876214,2.640924866458E-017) - ); -#100505 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100506 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100507 = PCURVE('',#100379,#100508); -#100508 = DEFINITIONAL_REPRESENTATION('',(#100509),#100512); -#100509 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100510,#100511), +#102882 = CARTESIAN_POINT('',(3.191025391152,5.85)); +#102883 = CARTESIAN_POINT('',(3.191025391152,5.65)); +#102884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102885 = ADVANCED_FACE('',(#102886),#102771,.F.); +#102886 = FACE_BOUND('',#102887,.F.); +#102887 = EDGE_LOOP('',(#102888,#102889,#102916,#102943)); +#102888 = ORIENTED_EDGE('',*,*,#102757,.T.); +#102889 = ORIENTED_EDGE('',*,*,#102890,.F.); +#102890 = EDGE_CURVE('',#102891,#102677,#102893,.T.); +#102891 = VERTEX_POINT('',#102892); +#102892 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.E+000)); +#102893 = SURFACE_CURVE('',#102894,(#102899,#102905),.PCURVE_S1.); +#102894 = CIRCLE('',#102895,0.208574704164); +#102895 = AXIS2_PLACEMENT_3D('',#102896,#102897,#102898); +#102896 = CARTESIAN_POINT('',(4.15,-0.728168876214,2.640924866458E-017) + ); +#102897 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102898 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102899 = PCURVE('',#102771,#102900); +#102900 = DEFINITIONAL_REPRESENTATION('',(#102901),#102904); +#102901 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102902,#102903), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#100510 = CARTESIAN_POINT('',(1.570796326795,5.85)); -#100511 = CARTESIAN_POINT('',(3.201833915432,5.85)); -#100512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102902 = CARTESIAN_POINT('',(1.570796326795,5.85)); +#102903 = CARTESIAN_POINT('',(3.201833915432,5.85)); +#102904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100513 = PCURVE('',#89835,#100514); -#100514 = DEFINITIONAL_REPRESENTATION('',(#100515),#100523); -#100515 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100516,#100517,#100518, - #100519,#100520,#100521,#100522),.UNSPECIFIED.,.F.,.F.) +#102905 = PCURVE('',#92227,#102906); +#102906 = DEFINITIONAL_REPRESENTATION('',(#102907),#102915); +#102907 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102908,#102909,#102910, + #102911,#102912,#102913,#102914),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#100516 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#100517 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#100518 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#100519 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#100520 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#100521 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#100522 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#100523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100524 = ORIENTED_EDGE('',*,*,#100525,.T.); -#100525 = EDGE_CURVE('',#100499,#100526,#100528,.T.); -#100526 = VERTEX_POINT('',#100527); -#100527 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.E+000)); -#100528 = SURFACE_CURVE('',#100529,(#100533,#100539),.PCURVE_S1.); -#100529 = LINE('',#100530,#100531); -#100530 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#100531 = VECTOR('',#100532,1.); -#100532 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100533 = PCURVE('',#100379,#100534); -#100534 = DEFINITIONAL_REPRESENTATION('',(#100535),#100538); -#100535 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100536,#100537), +#102908 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#102909 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#102910 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#102911 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#102912 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#102913 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#102914 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#102915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102916 = ORIENTED_EDGE('',*,*,#102917,.T.); +#102917 = EDGE_CURVE('',#102891,#102918,#102920,.T.); +#102918 = VERTEX_POINT('',#102919); +#102919 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.E+000)); +#102920 = SURFACE_CURVE('',#102921,(#102925,#102931),.PCURVE_S1.); +#102921 = LINE('',#102922,#102923); +#102922 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#102923 = VECTOR('',#102924,1.); +#102924 = DIRECTION('',(1.,0.E+000,0.E+000)); +#102925 = PCURVE('',#102771,#102926); +#102926 = DEFINITIONAL_REPRESENTATION('',(#102927),#102930); +#102927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102928,#102929), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#100536 = CARTESIAN_POINT('',(1.570796326795,5.85)); -#100537 = CARTESIAN_POINT('',(1.570796326795,5.65)); -#100538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100539 = PCURVE('',#100540,#100545); -#100540 = PLANE('',#100541); -#100541 = AXIS2_PLACEMENT_3D('',#100542,#100543,#100544); -#100542 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#100543 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#100544 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#100545 = DEFINITIONAL_REPRESENTATION('',(#100546),#100550); -#100546 = LINE('',#100547,#100548); -#100547 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#100548 = VECTOR('',#100549,1.); -#100549 = DIRECTION('',(0.E+000,1.)); -#100550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100551 = ORIENTED_EDGE('',*,*,#100552,.T.); -#100552 = EDGE_CURVE('',#100526,#100343,#100553,.T.); -#100553 = SURFACE_CURVE('',#100554,(#100559,#100565),.PCURVE_S1.); -#100554 = CIRCLE('',#100555,0.208574704164); -#100555 = AXIS2_PLACEMENT_3D('',#100556,#100557,#100558); -#100556 = CARTESIAN_POINT('',(4.35,-0.728168876214,2.640924866458E-017) - ); -#100557 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100558 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100559 = PCURVE('',#100379,#100560); -#100560 = DEFINITIONAL_REPRESENTATION('',(#100561),#100564); -#100561 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100562,#100563), +#102928 = CARTESIAN_POINT('',(1.570796326795,5.85)); +#102929 = CARTESIAN_POINT('',(1.570796326795,5.65)); +#102930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102931 = PCURVE('',#102932,#102937); +#102932 = PLANE('',#102933); +#102933 = AXIS2_PLACEMENT_3D('',#102934,#102935,#102936); +#102934 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#102935 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#102936 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#102937 = DEFINITIONAL_REPRESENTATION('',(#102938),#102942); +#102938 = LINE('',#102939,#102940); +#102939 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#102940 = VECTOR('',#102941,1.); +#102941 = DIRECTION('',(0.E+000,1.)); +#102942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102943 = ORIENTED_EDGE('',*,*,#102944,.T.); +#102944 = EDGE_CURVE('',#102918,#102735,#102945,.T.); +#102945 = SURFACE_CURVE('',#102946,(#102951,#102957),.PCURVE_S1.); +#102946 = CIRCLE('',#102947,0.208574704164); +#102947 = AXIS2_PLACEMENT_3D('',#102948,#102949,#102950); +#102948 = CARTESIAN_POINT('',(4.35,-0.728168876214,2.640924866458E-017) + ); +#102949 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102950 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102951 = PCURVE('',#102771,#102952); +#102952 = DEFINITIONAL_REPRESENTATION('',(#102953),#102956); +#102953 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102954,#102955), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#100562 = CARTESIAN_POINT('',(1.570796326795,5.65)); -#100563 = CARTESIAN_POINT('',(3.201833915432,5.65)); -#100564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100565 = PCURVE('',#89779,#100566); -#100566 = DEFINITIONAL_REPRESENTATION('',(#100567),#100571); -#100567 = CIRCLE('',#100568,0.208574704164); -#100568 = AXIS2_PLACEMENT_2D('',#100569,#100570); -#100569 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#100570 = DIRECTION('',(1.,0.E+000)); -#100571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100572 = ADVANCED_FACE('',(#100573),#100483,.T.); -#100573 = FACE_BOUND('',#100574,.T.); -#100574 = EDGE_LOOP('',(#100575,#100576,#100603,#100630)); -#100575 = ORIENTED_EDGE('',*,*,#100469,.F.); -#100576 = ORIENTED_EDGE('',*,*,#100577,.F.); -#100577 = EDGE_CURVE('',#100578,#100447,#100580,.T.); -#100578 = VERTEX_POINT('',#100579); -#100579 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.E+000)); -#100580 = SURFACE_CURVE('',#100581,(#100586,#100592),.PCURVE_S1.); -#100581 = CIRCLE('',#100582,0.308574064194); -#100582 = AXIS2_PLACEMENT_3D('',#100583,#100584,#100585); -#100583 = CARTESIAN_POINT('',(4.15,-0.728168876214,2.640924866458E-017) - ); -#100584 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100585 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100586 = PCURVE('',#100483,#100587); -#100587 = DEFINITIONAL_REPRESENTATION('',(#100588),#100591); -#100588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100589,#100590), +#102954 = CARTESIAN_POINT('',(1.570796326795,5.65)); +#102955 = CARTESIAN_POINT('',(3.201833915432,5.65)); +#102956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102957 = PCURVE('',#92171,#102958); +#102958 = DEFINITIONAL_REPRESENTATION('',(#102959),#102963); +#102959 = CIRCLE('',#102960,0.208574704164); +#102960 = AXIS2_PLACEMENT_2D('',#102961,#102962); +#102961 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#102962 = DIRECTION('',(1.,0.E+000)); +#102963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102964 = ADVANCED_FACE('',(#102965),#102875,.T.); +#102965 = FACE_BOUND('',#102966,.T.); +#102966 = EDGE_LOOP('',(#102967,#102968,#102995,#103022)); +#102967 = ORIENTED_EDGE('',*,*,#102861,.F.); +#102968 = ORIENTED_EDGE('',*,*,#102969,.F.); +#102969 = EDGE_CURVE('',#102970,#102839,#102972,.T.); +#102970 = VERTEX_POINT('',#102971); +#102971 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.E+000)); +#102972 = SURFACE_CURVE('',#102973,(#102978,#102984),.PCURVE_S1.); +#102973 = CIRCLE('',#102974,0.308574064194); +#102974 = AXIS2_PLACEMENT_3D('',#102975,#102976,#102977); +#102975 = CARTESIAN_POINT('',(4.15,-0.728168876214,2.640924866458E-017) + ); +#102976 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#102977 = DIRECTION('',(0.E+000,0.E+000,1.)); +#102978 = PCURVE('',#102875,#102979); +#102979 = DEFINITIONAL_REPRESENTATION('',(#102980),#102983); +#102980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102981,#102982), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#100589 = CARTESIAN_POINT('',(1.570796326795,5.85)); -#100590 = CARTESIAN_POINT('',(3.191025391152,5.85)); -#100591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#102981 = CARTESIAN_POINT('',(1.570796326795,5.85)); +#102982 = CARTESIAN_POINT('',(3.191025391152,5.85)); +#102983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100592 = PCURVE('',#89835,#100593); -#100593 = DEFINITIONAL_REPRESENTATION('',(#100594),#100602); -#100594 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100595,#100596,#100597, - #100598,#100599,#100600,#100601),.UNSPECIFIED.,.T.,.F.) +#102984 = PCURVE('',#92227,#102985); +#102985 = DEFINITIONAL_REPRESENTATION('',(#102986),#102994); +#102986 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102987,#102988,#102989, + #102990,#102991,#102992,#102993),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#100595 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#100596 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#100597 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#100598 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#100599 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#100600 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#100601 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#100602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100603 = ORIENTED_EDGE('',*,*,#100604,.F.); -#100604 = EDGE_CURVE('',#100605,#100578,#100607,.T.); -#100605 = VERTEX_POINT('',#100606); -#100606 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.E+000)); -#100607 = SURFACE_CURVE('',#100608,(#100612,#100618),.PCURVE_S1.); -#100608 = LINE('',#100609,#100610); -#100609 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#100610 = VECTOR('',#100611,1.); -#100611 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100612 = PCURVE('',#100483,#100613); -#100613 = DEFINITIONAL_REPRESENTATION('',(#100614),#100617); -#100614 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100615,#100616), +#102987 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#102988 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#102989 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#102990 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#102991 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#102992 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#102993 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#102994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#102995 = ORIENTED_EDGE('',*,*,#102996,.F.); +#102996 = EDGE_CURVE('',#102997,#102970,#102999,.T.); +#102997 = VERTEX_POINT('',#102998); +#102998 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.E+000)); +#102999 = SURFACE_CURVE('',#103000,(#103004,#103010),.PCURVE_S1.); +#103000 = LINE('',#103001,#103002); +#103001 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#103002 = VECTOR('',#103003,1.); +#103003 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103004 = PCURVE('',#102875,#103005); +#103005 = DEFINITIONAL_REPRESENTATION('',(#103006),#103009); +#103006 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103007,#103008), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#100615 = CARTESIAN_POINT('',(1.570796326795,5.65)); -#100616 = CARTESIAN_POINT('',(1.570796326795,5.85)); -#100617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100618 = PCURVE('',#100619,#100624); -#100619 = PLANE('',#100620); -#100620 = AXIS2_PLACEMENT_3D('',#100621,#100622,#100623); -#100621 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#100622 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#100623 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#100624 = DEFINITIONAL_REPRESENTATION('',(#100625),#100629); -#100625 = LINE('',#100626,#100627); -#100626 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#100627 = VECTOR('',#100628,1.); -#100628 = DIRECTION('',(0.E+000,-1.)); -#100629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100630 = ORIENTED_EDGE('',*,*,#100631,.T.); -#100631 = EDGE_CURVE('',#100605,#100394,#100632,.T.); -#100632 = SURFACE_CURVE('',#100633,(#100638,#100644),.PCURVE_S1.); -#100633 = CIRCLE('',#100634,0.308574064194); -#100634 = AXIS2_PLACEMENT_3D('',#100635,#100636,#100637); -#100635 = CARTESIAN_POINT('',(4.35,-0.728168876214,2.640924866458E-017) - ); -#100636 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100637 = DIRECTION('',(0.E+000,0.E+000,1.)); -#100638 = PCURVE('',#100483,#100639); -#100639 = DEFINITIONAL_REPRESENTATION('',(#100640),#100643); -#100640 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100641,#100642), +#103007 = CARTESIAN_POINT('',(1.570796326795,5.65)); +#103008 = CARTESIAN_POINT('',(1.570796326795,5.85)); +#103009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103010 = PCURVE('',#103011,#103016); +#103011 = PLANE('',#103012); +#103012 = AXIS2_PLACEMENT_3D('',#103013,#103014,#103015); +#103013 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#103014 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#103015 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103016 = DEFINITIONAL_REPRESENTATION('',(#103017),#103021); +#103017 = LINE('',#103018,#103019); +#103018 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#103019 = VECTOR('',#103020,1.); +#103020 = DIRECTION('',(0.E+000,-1.)); +#103021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103022 = ORIENTED_EDGE('',*,*,#103023,.T.); +#103023 = EDGE_CURVE('',#102997,#102786,#103024,.T.); +#103024 = SURFACE_CURVE('',#103025,(#103030,#103036),.PCURVE_S1.); +#103025 = CIRCLE('',#103026,0.308574064194); +#103026 = AXIS2_PLACEMENT_3D('',#103027,#103028,#103029); +#103027 = CARTESIAN_POINT('',(4.35,-0.728168876214,2.640924866458E-017) + ); +#103028 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103029 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103030 = PCURVE('',#102875,#103031); +#103031 = DEFINITIONAL_REPRESENTATION('',(#103032),#103035); +#103032 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103033,#103034), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#100641 = CARTESIAN_POINT('',(1.570796326795,5.65)); -#100642 = CARTESIAN_POINT('',(3.191025391152,5.65)); -#100643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103033 = CARTESIAN_POINT('',(1.570796326795,5.65)); +#103034 = CARTESIAN_POINT('',(3.191025391152,5.65)); +#103035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103036 = PCURVE('',#92171,#103037); +#103037 = DEFINITIONAL_REPRESENTATION('',(#103038),#103042); +#103038 = CIRCLE('',#103039,0.308574064194); +#103039 = AXIS2_PLACEMENT_2D('',#103040,#103041); +#103040 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#103041 = DIRECTION('',(1.,0.E+000)); +#103042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103043 = ADVANCED_FACE('',(#103044),#103011,.F.); +#103044 = FACE_BOUND('',#103045,.T.); +#103045 = EDGE_LOOP('',(#103046,#103075,#103096,#103097)); +#103046 = ORIENTED_EDGE('',*,*,#103047,.F.); +#103047 = EDGE_CURVE('',#103048,#103050,#103052,.T.); +#103048 = VERTEX_POINT('',#103049); +#103049 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.530776333563)); +#103050 = VERTEX_POINT('',#103051); +#103051 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.530776333563)); +#103052 = SURFACE_CURVE('',#103053,(#103057,#103064),.PCURVE_S1.); +#103053 = LINE('',#103054,#103055); +#103054 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#103055 = VECTOR('',#103056,1.); +#103056 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103057 = PCURVE('',#103011,#103058); +#103058 = DEFINITIONAL_REPRESENTATION('',(#103059),#103063); +#103059 = LINE('',#103060,#103061); +#103060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103061 = VECTOR('',#103062,1.); +#103062 = DIRECTION('',(0.E+000,-1.)); +#103063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103064 = PCURVE('',#103065,#103070); +#103065 = CYLINDRICAL_SURFACE('',#103066,0.119270391569); +#103066 = AXIS2_PLACEMENT_3D('',#103067,#103068,#103069); +#103067 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#103068 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103069 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103070 = DEFINITIONAL_REPRESENTATION('',(#103071),#103074); +#103071 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103072,#103073), + .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); +#103072 = CARTESIAN_POINT('',(4.712388980385,-5.65)); +#103073 = CARTESIAN_POINT('',(4.712388980385,-5.85)); +#103074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103075 = ORIENTED_EDGE('',*,*,#103076,.T.); +#103076 = EDGE_CURVE('',#103048,#102997,#103077,.T.); +#103077 = SURFACE_CURVE('',#103078,(#103082,#103089),.PCURVE_S1.); +#103078 = LINE('',#103079,#103080); +#103079 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.530776333563)); +#103080 = VECTOR('',#103081,1.); +#103081 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103082 = PCURVE('',#103011,#103083); +#103083 = DEFINITIONAL_REPRESENTATION('',(#103084),#103088); +#103084 = LINE('',#103085,#103086); +#103085 = CARTESIAN_POINT('',(0.E+000,-5.65)); +#103086 = VECTOR('',#103087,1.); +#103087 = DIRECTION('',(1.,0.E+000)); +#103088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103089 = PCURVE('',#92171,#103090); +#103090 = DEFINITIONAL_REPRESENTATION('',(#103091),#103095); +#103091 = LINE('',#103092,#103093); +#103092 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#103093 = VECTOR('',#103094,1.); +#103094 = DIRECTION('',(-1.,-1.021336205033E-016)); +#103095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103096 = ORIENTED_EDGE('',*,*,#102996,.T.); +#103097 = ORIENTED_EDGE('',*,*,#103098,.F.); +#103098 = EDGE_CURVE('',#103050,#102970,#103099,.T.); +#103099 = SURFACE_CURVE('',#103100,(#103104,#103111),.PCURVE_S1.); +#103100 = LINE('',#103101,#103102); +#103101 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.530776333563)); +#103102 = VECTOR('',#103103,1.); +#103103 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103104 = PCURVE('',#103011,#103105); +#103105 = DEFINITIONAL_REPRESENTATION('',(#103106),#103110); +#103106 = LINE('',#103107,#103108); +#103107 = CARTESIAN_POINT('',(0.E+000,-5.85)); +#103108 = VECTOR('',#103109,1.); +#103109 = DIRECTION('',(1.,0.E+000)); +#103110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103111 = PCURVE('',#92227,#103112); +#103112 = DEFINITIONAL_REPRESENTATION('',(#103113),#103117); +#103113 = LINE('',#103114,#103115); +#103114 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#103115 = VECTOR('',#103116,1.); +#103116 = DIRECTION('',(1.,-1.021336205033E-016)); +#103117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103118 = ADVANCED_FACE('',(#103119),#102932,.F.); +#103119 = FACE_BOUND('',#103120,.T.); +#103120 = EDGE_LOOP('',(#103121,#103150,#103171,#103172)); +#103121 = ORIENTED_EDGE('',*,*,#103122,.F.); +#103122 = EDGE_CURVE('',#103123,#103125,#103127,.T.); +#103123 = VERTEX_POINT('',#103124); +#103124 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.530776333563)); +#103125 = VERTEX_POINT('',#103126); +#103126 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.530776333563)); +#103127 = SURFACE_CURVE('',#103128,(#103132,#103139),.PCURVE_S1.); +#103128 = LINE('',#103129,#103130); +#103129 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#103130 = VECTOR('',#103131,1.); +#103131 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103132 = PCURVE('',#102932,#103133); +#103133 = DEFINITIONAL_REPRESENTATION('',(#103134),#103138); +#103134 = LINE('',#103135,#103136); +#103135 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103136 = VECTOR('',#103137,1.); +#103137 = DIRECTION('',(0.E+000,1.)); +#103138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103139 = PCURVE('',#103140,#103145); +#103140 = CYLINDRICAL_SURFACE('',#103141,0.2192697516); +#103141 = AXIS2_PLACEMENT_3D('',#103142,#103143,#103144); +#103142 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#103143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103144 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103145 = DEFINITIONAL_REPRESENTATION('',(#103146),#103149); +#103146 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103147,#103148), + .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); +#103147 = CARTESIAN_POINT('',(4.712388980385,-5.85)); +#103148 = CARTESIAN_POINT('',(4.712388980385,-5.65)); +#103149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100644 = PCURVE('',#89779,#100645); -#100645 = DEFINITIONAL_REPRESENTATION('',(#100646),#100650); -#100646 = CIRCLE('',#100647,0.308574064194); -#100647 = AXIS2_PLACEMENT_2D('',#100648,#100649); -#100648 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#100649 = DIRECTION('',(1.,0.E+000)); -#100650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103150 = ORIENTED_EDGE('',*,*,#103151,.T.); +#103151 = EDGE_CURVE('',#103123,#102891,#103152,.T.); +#103152 = SURFACE_CURVE('',#103153,(#103157,#103164),.PCURVE_S1.); +#103153 = LINE('',#103154,#103155); +#103154 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.530776333563)); +#103155 = VECTOR('',#103156,1.); +#103156 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103157 = PCURVE('',#102932,#103158); +#103158 = DEFINITIONAL_REPRESENTATION('',(#103159),#103163); +#103159 = LINE('',#103160,#103161); +#103160 = CARTESIAN_POINT('',(0.E+000,-5.85)); +#103161 = VECTOR('',#103162,1.); +#103162 = DIRECTION('',(-1.,0.E+000)); +#103163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100651 = ADVANCED_FACE('',(#100652),#100619,.F.); -#100652 = FACE_BOUND('',#100653,.T.); -#100653 = EDGE_LOOP('',(#100654,#100683,#100704,#100705)); -#100654 = ORIENTED_EDGE('',*,*,#100655,.F.); -#100655 = EDGE_CURVE('',#100656,#100658,#100660,.T.); -#100656 = VERTEX_POINT('',#100657); -#100657 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.530776333563)); -#100658 = VERTEX_POINT('',#100659); -#100659 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.530776333563)); -#100660 = SURFACE_CURVE('',#100661,(#100665,#100672),.PCURVE_S1.); -#100661 = LINE('',#100662,#100663); -#100662 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#100663 = VECTOR('',#100664,1.); -#100664 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100665 = PCURVE('',#100619,#100666); -#100666 = DEFINITIONAL_REPRESENTATION('',(#100667),#100671); -#100667 = LINE('',#100668,#100669); -#100668 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100669 = VECTOR('',#100670,1.); -#100670 = DIRECTION('',(0.E+000,-1.)); -#100671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100672 = PCURVE('',#100673,#100678); -#100673 = CYLINDRICAL_SURFACE('',#100674,0.119270391569); -#100674 = AXIS2_PLACEMENT_3D('',#100675,#100676,#100677); -#100675 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#100676 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100677 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100678 = DEFINITIONAL_REPRESENTATION('',(#100679),#100682); -#100679 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100680,#100681), - .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#100680 = CARTESIAN_POINT('',(4.712388980385,-5.65)); -#100681 = CARTESIAN_POINT('',(4.712388980385,-5.85)); -#100682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100683 = ORIENTED_EDGE('',*,*,#100684,.T.); -#100684 = EDGE_CURVE('',#100656,#100605,#100685,.T.); -#100685 = SURFACE_CURVE('',#100686,(#100690,#100697),.PCURVE_S1.); -#100686 = LINE('',#100687,#100688); -#100687 = CARTESIAN_POINT('',(4.35,-0.419594812019,0.530776333563)); -#100688 = VECTOR('',#100689,1.); -#100689 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#100690 = PCURVE('',#100619,#100691); -#100691 = DEFINITIONAL_REPRESENTATION('',(#100692),#100696); -#100692 = LINE('',#100693,#100694); -#100693 = CARTESIAN_POINT('',(0.E+000,-5.65)); -#100694 = VECTOR('',#100695,1.); -#100695 = DIRECTION('',(1.,0.E+000)); -#100696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100697 = PCURVE('',#89779,#100698); -#100698 = DEFINITIONAL_REPRESENTATION('',(#100699),#100703); -#100699 = LINE('',#100700,#100701); -#100700 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#100701 = VECTOR('',#100702,1.); -#100702 = DIRECTION('',(-1.,-1.021336205033E-016)); -#100703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100704 = ORIENTED_EDGE('',*,*,#100604,.T.); -#100705 = ORIENTED_EDGE('',*,*,#100706,.F.); -#100706 = EDGE_CURVE('',#100658,#100578,#100707,.T.); -#100707 = SURFACE_CURVE('',#100708,(#100712,#100719),.PCURVE_S1.); -#100708 = LINE('',#100709,#100710); -#100709 = CARTESIAN_POINT('',(4.15,-0.419594812019,0.530776333563)); -#100710 = VECTOR('',#100711,1.); -#100711 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#100712 = PCURVE('',#100619,#100713); -#100713 = DEFINITIONAL_REPRESENTATION('',(#100714),#100718); -#100714 = LINE('',#100715,#100716); -#100715 = CARTESIAN_POINT('',(0.E+000,-5.85)); -#100716 = VECTOR('',#100717,1.); -#100717 = DIRECTION('',(1.,0.E+000)); -#100718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100719 = PCURVE('',#89835,#100720); -#100720 = DEFINITIONAL_REPRESENTATION('',(#100721),#100725); -#100721 = LINE('',#100722,#100723); -#100722 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#100723 = VECTOR('',#100724,1.); -#100724 = DIRECTION('',(1.,-1.021336205033E-016)); -#100725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100726 = ADVANCED_FACE('',(#100727),#100540,.F.); -#100727 = FACE_BOUND('',#100728,.T.); -#100728 = EDGE_LOOP('',(#100729,#100758,#100779,#100780)); -#100729 = ORIENTED_EDGE('',*,*,#100730,.F.); -#100730 = EDGE_CURVE('',#100731,#100733,#100735,.T.); -#100731 = VERTEX_POINT('',#100732); -#100732 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.530776333563)); -#100733 = VERTEX_POINT('',#100734); -#100734 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.530776333563)); -#100735 = SURFACE_CURVE('',#100736,(#100740,#100747),.PCURVE_S1.); -#100736 = LINE('',#100737,#100738); -#100737 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#100738 = VECTOR('',#100739,1.); -#100739 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100740 = PCURVE('',#100540,#100741); -#100741 = DEFINITIONAL_REPRESENTATION('',(#100742),#100746); -#100742 = LINE('',#100743,#100744); -#100743 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100744 = VECTOR('',#100745,1.); -#100745 = DIRECTION('',(0.E+000,1.)); -#100746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100747 = PCURVE('',#100748,#100753); -#100748 = CYLINDRICAL_SURFACE('',#100749,0.2192697516); -#100749 = AXIS2_PLACEMENT_3D('',#100750,#100751,#100752); -#100750 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#100751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100752 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100753 = DEFINITIONAL_REPRESENTATION('',(#100754),#100757); -#100754 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100755,#100756), - .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#100755 = CARTESIAN_POINT('',(4.712388980385,-5.85)); -#100756 = CARTESIAN_POINT('',(4.712388980385,-5.65)); -#100757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100758 = ORIENTED_EDGE('',*,*,#100759,.T.); -#100759 = EDGE_CURVE('',#100731,#100499,#100760,.T.); -#100760 = SURFACE_CURVE('',#100761,(#100765,#100772),.PCURVE_S1.); -#100761 = LINE('',#100762,#100763); -#100762 = CARTESIAN_POINT('',(4.15,-0.51959417205,0.530776333563)); -#100763 = VECTOR('',#100764,1.); -#100764 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#100765 = PCURVE('',#100540,#100766); -#100766 = DEFINITIONAL_REPRESENTATION('',(#100767),#100771); -#100767 = LINE('',#100768,#100769); -#100768 = CARTESIAN_POINT('',(0.E+000,-5.85)); -#100769 = VECTOR('',#100770,1.); -#100770 = DIRECTION('',(-1.,0.E+000)); -#100771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100772 = PCURVE('',#89835,#100773); -#100773 = DEFINITIONAL_REPRESENTATION('',(#100774),#100778); -#100774 = LINE('',#100775,#100776); -#100775 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#100776 = VECTOR('',#100777,1.); -#100777 = DIRECTION('',(1.,-1.021336205033E-016)); -#100778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100779 = ORIENTED_EDGE('',*,*,#100525,.T.); -#100780 = ORIENTED_EDGE('',*,*,#100781,.F.); -#100781 = EDGE_CURVE('',#100733,#100526,#100782,.T.); -#100782 = SURFACE_CURVE('',#100783,(#100787,#100794),.PCURVE_S1.); -#100783 = LINE('',#100784,#100785); -#100784 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.530776333563)); -#100785 = VECTOR('',#100786,1.); -#100786 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#100787 = PCURVE('',#100540,#100788); -#100788 = DEFINITIONAL_REPRESENTATION('',(#100789),#100793); -#100789 = LINE('',#100790,#100791); -#100790 = CARTESIAN_POINT('',(0.E+000,-5.65)); -#100791 = VECTOR('',#100792,1.); -#100792 = DIRECTION('',(-1.,0.E+000)); -#100793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100794 = PCURVE('',#89779,#100795); -#100795 = DEFINITIONAL_REPRESENTATION('',(#100796),#100800); -#100796 = LINE('',#100797,#100798); -#100797 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#100798 = VECTOR('',#100799,1.); -#100799 = DIRECTION('',(-1.,-1.021336205033E-016)); -#100800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103164 = PCURVE('',#92227,#103165); +#103165 = DEFINITIONAL_REPRESENTATION('',(#103166),#103170); +#103166 = LINE('',#103167,#103168); +#103167 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#103168 = VECTOR('',#103169,1.); +#103169 = DIRECTION('',(1.,-1.021336205033E-016)); +#103170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100801 = ADVANCED_FACE('',(#100802),#100673,.F.); -#100802 = FACE_BOUND('',#100803,.F.); -#100803 = EDGE_LOOP('',(#100804,#100831,#100853,#100874)); -#100804 = ORIENTED_EDGE('',*,*,#100805,.F.); -#100805 = EDGE_CURVE('',#100806,#100656,#100808,.T.); -#100806 = VERTEX_POINT('',#100807); -#100807 = CARTESIAN_POINT('',(4.35,-0.303662633502,0.65)); -#100808 = SURFACE_CURVE('',#100809,(#100814,#100820),.PCURVE_S1.); -#100809 = CIRCLE('',#100810,0.119270391569); -#100810 = AXIS2_PLACEMENT_3D('',#100811,#100812,#100813); -#100811 = CARTESIAN_POINT('',(4.35,-0.30032442045,0.530776333563)); -#100812 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100814 = PCURVE('',#100673,#100815); -#100815 = DEFINITIONAL_REPRESENTATION('',(#100816),#100819); -#100816 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100817,#100818), +#103171 = ORIENTED_EDGE('',*,*,#102917,.T.); +#103172 = ORIENTED_EDGE('',*,*,#103173,.F.); +#103173 = EDGE_CURVE('',#103125,#102918,#103174,.T.); +#103174 = SURFACE_CURVE('',#103175,(#103179,#103186),.PCURVE_S1.); +#103175 = LINE('',#103176,#103177); +#103176 = CARTESIAN_POINT('',(4.35,-0.51959417205,0.530776333563)); +#103177 = VECTOR('',#103178,1.); +#103178 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103179 = PCURVE('',#102932,#103180); +#103180 = DEFINITIONAL_REPRESENTATION('',(#103181),#103185); +#103181 = LINE('',#103182,#103183); +#103182 = CARTESIAN_POINT('',(0.E+000,-5.65)); +#103183 = VECTOR('',#103184,1.); +#103184 = DIRECTION('',(-1.,0.E+000)); +#103185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103186 = PCURVE('',#92171,#103187); +#103187 = DEFINITIONAL_REPRESENTATION('',(#103188),#103192); +#103188 = LINE('',#103189,#103190); +#103189 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#103190 = VECTOR('',#103191,1.); +#103191 = DIRECTION('',(-1.,-1.021336205033E-016)); +#103192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103193 = ADVANCED_FACE('',(#103194),#103065,.F.); +#103194 = FACE_BOUND('',#103195,.F.); +#103195 = EDGE_LOOP('',(#103196,#103223,#103245,#103266)); +#103196 = ORIENTED_EDGE('',*,*,#103197,.F.); +#103197 = EDGE_CURVE('',#103198,#103048,#103200,.T.); +#103198 = VERTEX_POINT('',#103199); +#103199 = CARTESIAN_POINT('',(4.35,-0.303662633502,0.65)); +#103200 = SURFACE_CURVE('',#103201,(#103206,#103212),.PCURVE_S1.); +#103201 = CIRCLE('',#103202,0.119270391569); +#103202 = AXIS2_PLACEMENT_3D('',#103203,#103204,#103205); +#103203 = CARTESIAN_POINT('',(4.35,-0.30032442045,0.530776333563)); +#103204 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103206 = PCURVE('',#103065,#103207); +#103207 = DEFINITIONAL_REPRESENTATION('',(#103208),#103211); +#103208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103209,#103210), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100817 = CARTESIAN_POINT('',(3.169584923929,-5.65)); -#100818 = CARTESIAN_POINT('',(4.712388980385,-5.65)); -#100819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103209 = CARTESIAN_POINT('',(3.169584923929,-5.65)); +#103210 = CARTESIAN_POINT('',(4.712388980385,-5.65)); +#103211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100820 = PCURVE('',#89779,#100821); -#100821 = DEFINITIONAL_REPRESENTATION('',(#100822),#100830); -#100822 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100823,#100824,#100825, - #100826,#100827,#100828,#100829),.UNSPECIFIED.,.F.,.F.) +#103212 = PCURVE('',#92171,#103213); +#103213 = DEFINITIONAL_REPRESENTATION('',(#103214),#103222); +#103214 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103215,#103216,#103217, + #103218,#103219,#103220,#103221),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#100823 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#100824 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#100825 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#100826 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#100827 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#100828 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#100829 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#100830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100831 = ORIENTED_EDGE('',*,*,#100832,.F.); -#100832 = EDGE_CURVE('',#100833,#100806,#100835,.T.); -#100833 = VERTEX_POINT('',#100834); -#100834 = CARTESIAN_POINT('',(4.15,-0.303662633502,0.65)); -#100835 = SURFACE_CURVE('',#100836,(#100840,#100846),.PCURVE_S1.); -#100836 = LINE('',#100837,#100838); -#100837 = CARTESIAN_POINT('',(4.35,-0.303662633502,0.65)); -#100838 = VECTOR('',#100839,1.); -#100839 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100840 = PCURVE('',#100673,#100841); -#100841 = DEFINITIONAL_REPRESENTATION('',(#100842),#100845); -#100842 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100843,#100844), +#103215 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#103216 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#103217 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#103218 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#103219 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#103220 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#103221 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#103222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103223 = ORIENTED_EDGE('',*,*,#103224,.F.); +#103224 = EDGE_CURVE('',#103225,#103198,#103227,.T.); +#103225 = VERTEX_POINT('',#103226); +#103226 = CARTESIAN_POINT('',(4.15,-0.303662633502,0.65)); +#103227 = SURFACE_CURVE('',#103228,(#103232,#103238),.PCURVE_S1.); +#103228 = LINE('',#103229,#103230); +#103229 = CARTESIAN_POINT('',(4.35,-0.303662633502,0.65)); +#103230 = VECTOR('',#103231,1.); +#103231 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103232 = PCURVE('',#103065,#103233); +#103233 = DEFINITIONAL_REPRESENTATION('',(#103234),#103237); +#103234 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103235,#103236), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#100843 = CARTESIAN_POINT('',(3.169584923929,-5.85)); -#100844 = CARTESIAN_POINT('',(3.169584923929,-5.65)); -#100845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100846 = PCURVE('',#89807,#100847); -#100847 = DEFINITIONAL_REPRESENTATION('',(#100848),#100852); -#100848 = LINE('',#100849,#100850); -#100849 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#100850 = VECTOR('',#100851,1.); -#100851 = DIRECTION('',(0.E+000,1.)); -#100852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100853 = ORIENTED_EDGE('',*,*,#100854,.T.); -#100854 = EDGE_CURVE('',#100833,#100658,#100855,.T.); -#100855 = SURFACE_CURVE('',#100856,(#100861,#100867),.PCURVE_S1.); -#100856 = CIRCLE('',#100857,0.119270391569); -#100857 = AXIS2_PLACEMENT_3D('',#100858,#100859,#100860); -#100858 = CARTESIAN_POINT('',(4.15,-0.30032442045,0.530776333563)); -#100859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100860 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100861 = PCURVE('',#100673,#100862); -#100862 = DEFINITIONAL_REPRESENTATION('',(#100863),#100866); -#100863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100864,#100865), +#103235 = CARTESIAN_POINT('',(3.169584923929,-5.85)); +#103236 = CARTESIAN_POINT('',(3.169584923929,-5.65)); +#103237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103238 = PCURVE('',#92199,#103239); +#103239 = DEFINITIONAL_REPRESENTATION('',(#103240),#103244); +#103240 = LINE('',#103241,#103242); +#103241 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#103242 = VECTOR('',#103243,1.); +#103243 = DIRECTION('',(0.E+000,1.)); +#103244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103245 = ORIENTED_EDGE('',*,*,#103246,.T.); +#103246 = EDGE_CURVE('',#103225,#103050,#103247,.T.); +#103247 = SURFACE_CURVE('',#103248,(#103253,#103259),.PCURVE_S1.); +#103248 = CIRCLE('',#103249,0.119270391569); +#103249 = AXIS2_PLACEMENT_3D('',#103250,#103251,#103252); +#103250 = CARTESIAN_POINT('',(4.15,-0.30032442045,0.530776333563)); +#103251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103252 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103253 = PCURVE('',#103065,#103254); +#103254 = DEFINITIONAL_REPRESENTATION('',(#103255),#103258); +#103255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103256,#103257), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100864 = CARTESIAN_POINT('',(3.169584923929,-5.85)); -#100865 = CARTESIAN_POINT('',(4.712388980385,-5.85)); -#100866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100867 = PCURVE('',#89835,#100868); -#100868 = DEFINITIONAL_REPRESENTATION('',(#100869),#100873); -#100869 = CIRCLE('',#100870,0.119270391569); -#100870 = AXIS2_PLACEMENT_2D('',#100871,#100872); -#100871 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#100872 = DIRECTION('',(1.,0.E+000)); -#100873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100874 = ORIENTED_EDGE('',*,*,#100655,.F.); -#100875 = ADVANCED_FACE('',(#100876),#100748,.T.); -#100876 = FACE_BOUND('',#100877,.T.); -#100877 = EDGE_LOOP('',(#100878,#100901,#100902,#100929)); -#100878 = ORIENTED_EDGE('',*,*,#100879,.T.); -#100879 = EDGE_CURVE('',#100880,#100731,#100882,.T.); -#100880 = VERTEX_POINT('',#100881); -#100881 = CARTESIAN_POINT('',(4.15,-0.304819755875,0.75)); -#100882 = SURFACE_CURVE('',#100883,(#100888,#100894),.PCURVE_S1.); -#100883 = CIRCLE('',#100884,0.2192697516); -#100884 = AXIS2_PLACEMENT_3D('',#100885,#100886,#100887); -#100885 = CARTESIAN_POINT('',(4.15,-0.30032442045,0.530776333563)); -#100886 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100887 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100888 = PCURVE('',#100748,#100889); -#100889 = DEFINITIONAL_REPRESENTATION('',(#100890),#100893); -#100890 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100891,#100892), +#103256 = CARTESIAN_POINT('',(3.169584923929,-5.85)); +#103257 = CARTESIAN_POINT('',(4.712388980385,-5.85)); +#103258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103259 = PCURVE('',#92227,#103260); +#103260 = DEFINITIONAL_REPRESENTATION('',(#103261),#103265); +#103261 = CIRCLE('',#103262,0.119270391569); +#103262 = AXIS2_PLACEMENT_2D('',#103263,#103264); +#103263 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#103264 = DIRECTION('',(1.,0.E+000)); +#103265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103266 = ORIENTED_EDGE('',*,*,#103047,.F.); +#103267 = ADVANCED_FACE('',(#103268),#103140,.T.); +#103268 = FACE_BOUND('',#103269,.T.); +#103269 = EDGE_LOOP('',(#103270,#103293,#103294,#103321)); +#103270 = ORIENTED_EDGE('',*,*,#103271,.T.); +#103271 = EDGE_CURVE('',#103272,#103123,#103274,.T.); +#103272 = VERTEX_POINT('',#103273); +#103273 = CARTESIAN_POINT('',(4.15,-0.304819755875,0.75)); +#103274 = SURFACE_CURVE('',#103275,(#103280,#103286),.PCURVE_S1.); +#103275 = CIRCLE('',#103276,0.2192697516); +#103276 = AXIS2_PLACEMENT_3D('',#103277,#103278,#103279); +#103277 = CARTESIAN_POINT('',(4.15,-0.30032442045,0.530776333563)); +#103278 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103279 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103280 = PCURVE('',#103140,#103281); +#103281 = DEFINITIONAL_REPRESENTATION('',(#103282),#103285); +#103282 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103283,#103284), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100891 = CARTESIAN_POINT('',(3.162095483347,-5.85)); -#100892 = CARTESIAN_POINT('',(4.712388980385,-5.85)); -#100893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100894 = PCURVE('',#89835,#100895); -#100895 = DEFINITIONAL_REPRESENTATION('',(#100896),#100900); -#100896 = CIRCLE('',#100897,0.2192697516); -#100897 = AXIS2_PLACEMENT_2D('',#100898,#100899); -#100898 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#100899 = DIRECTION('',(1.,0.E+000)); -#100900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100901 = ORIENTED_EDGE('',*,*,#100730,.T.); -#100902 = ORIENTED_EDGE('',*,*,#100903,.F.); -#100903 = EDGE_CURVE('',#100904,#100733,#100906,.T.); -#100904 = VERTEX_POINT('',#100905); -#100905 = CARTESIAN_POINT('',(4.35,-0.304819755875,0.75)); -#100906 = SURFACE_CURVE('',#100907,(#100912,#100918),.PCURVE_S1.); -#100907 = CIRCLE('',#100908,0.2192697516); -#100908 = AXIS2_PLACEMENT_3D('',#100909,#100910,#100911); -#100909 = CARTESIAN_POINT('',(4.35,-0.30032442045,0.530776333563)); -#100910 = DIRECTION('',(1.,0.E+000,0.E+000)); -#100911 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#100912 = PCURVE('',#100748,#100913); -#100913 = DEFINITIONAL_REPRESENTATION('',(#100914),#100917); -#100914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100915,#100916), +#103283 = CARTESIAN_POINT('',(3.162095483347,-5.85)); +#103284 = CARTESIAN_POINT('',(4.712388980385,-5.85)); +#103285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103286 = PCURVE('',#92227,#103287); +#103287 = DEFINITIONAL_REPRESENTATION('',(#103288),#103292); +#103288 = CIRCLE('',#103289,0.2192697516); +#103289 = AXIS2_PLACEMENT_2D('',#103290,#103291); +#103290 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#103291 = DIRECTION('',(1.,0.E+000)); +#103292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103293 = ORIENTED_EDGE('',*,*,#103122,.T.); +#103294 = ORIENTED_EDGE('',*,*,#103295,.F.); +#103295 = EDGE_CURVE('',#103296,#103125,#103298,.T.); +#103296 = VERTEX_POINT('',#103297); +#103297 = CARTESIAN_POINT('',(4.35,-0.304819755875,0.75)); +#103298 = SURFACE_CURVE('',#103299,(#103304,#103310),.PCURVE_S1.); +#103299 = CIRCLE('',#103300,0.2192697516); +#103300 = AXIS2_PLACEMENT_3D('',#103301,#103302,#103303); +#103301 = CARTESIAN_POINT('',(4.35,-0.30032442045,0.530776333563)); +#103302 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103303 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103304 = PCURVE('',#103140,#103305); +#103305 = DEFINITIONAL_REPRESENTATION('',(#103306),#103309); +#103306 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103307,#103308), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#100915 = CARTESIAN_POINT('',(3.162095483347,-5.65)); -#100916 = CARTESIAN_POINT('',(4.712388980385,-5.65)); -#100917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103307 = CARTESIAN_POINT('',(3.162095483347,-5.65)); +#103308 = CARTESIAN_POINT('',(4.712388980385,-5.65)); +#103309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#100918 = PCURVE('',#89779,#100919); -#100919 = DEFINITIONAL_REPRESENTATION('',(#100920),#100928); -#100920 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#100921,#100922,#100923, - #100924,#100925,#100926,#100927),.UNSPECIFIED.,.T.,.F.) +#103310 = PCURVE('',#92171,#103311); +#103311 = DEFINITIONAL_REPRESENTATION('',(#103312),#103320); +#103312 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103313,#103314,#103315, + #103316,#103317,#103318,#103319),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#100921 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#100922 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#100923 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#100924 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#100925 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#100926 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#100927 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#100928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100929 = ORIENTED_EDGE('',*,*,#100930,.T.); -#100930 = EDGE_CURVE('',#100904,#100880,#100931,.T.); -#100931 = SURFACE_CURVE('',#100932,(#100936,#100942),.PCURVE_S1.); -#100932 = LINE('',#100933,#100934); -#100933 = CARTESIAN_POINT('',(4.35,-0.304819755875,0.75)); -#100934 = VECTOR('',#100935,1.); -#100935 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#100936 = PCURVE('',#100748,#100937); -#100937 = DEFINITIONAL_REPRESENTATION('',(#100938),#100941); -#100938 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#100939,#100940), +#103313 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#103314 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#103315 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#103316 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#103317 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#103318 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#103319 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#103320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103321 = ORIENTED_EDGE('',*,*,#103322,.T.); +#103322 = EDGE_CURVE('',#103296,#103272,#103323,.T.); +#103323 = SURFACE_CURVE('',#103324,(#103328,#103334),.PCURVE_S1.); +#103324 = LINE('',#103325,#103326); +#103325 = CARTESIAN_POINT('',(4.35,-0.304819755875,0.75)); +#103326 = VECTOR('',#103327,1.); +#103327 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103328 = PCURVE('',#103140,#103329); +#103329 = DEFINITIONAL_REPRESENTATION('',(#103330),#103333); +#103330 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103331,#103332), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#100939 = CARTESIAN_POINT('',(3.162095483347,-5.65)); -#100940 = CARTESIAN_POINT('',(3.162095483347,-5.85)); -#100941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100942 = PCURVE('',#89861,#100943); -#100943 = DEFINITIONAL_REPRESENTATION('',(#100944),#100948); -#100944 = LINE('',#100945,#100946); -#100945 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#100946 = VECTOR('',#100947,1.); -#100947 = DIRECTION('',(0.E+000,-1.)); -#100948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100949 = ADVANCED_FACE('',(#100950),#89779,.F.); -#100950 = FACE_BOUND('',#100951,.T.); -#100951 = EDGE_LOOP('',(#100952,#100973,#100974,#100975,#100976,#100977, - #100998,#100999,#101000,#101001,#101002,#101023)); -#100952 = ORIENTED_EDGE('',*,*,#100953,.F.); -#100953 = EDGE_CURVE('',#100904,#89764,#100954,.T.); -#100954 = SURFACE_CURVE('',#100955,(#100959,#100966),.PCURVE_S1.); -#100955 = LINE('',#100956,#100957); -#100956 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.75)); -#100957 = VECTOR('',#100958,1.); -#100958 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#100959 = PCURVE('',#89779,#100960); -#100960 = DEFINITIONAL_REPRESENTATION('',(#100961),#100965); -#100961 = LINE('',#100962,#100963); -#100962 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#100963 = VECTOR('',#100964,1.); -#100964 = DIRECTION('',(3.563627120235E-016,1.)); -#100965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100966 = PCURVE('',#89861,#100967); -#100967 = DEFINITIONAL_REPRESENTATION('',(#100968),#100972); -#100968 = LINE('',#100969,#100970); -#100969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#100970 = VECTOR('',#100971,1.); -#100971 = DIRECTION('',(1.,0.E+000)); -#100972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100973 = ORIENTED_EDGE('',*,*,#100903,.T.); -#100974 = ORIENTED_EDGE('',*,*,#100781,.T.); -#100975 = ORIENTED_EDGE('',*,*,#100552,.T.); -#100976 = ORIENTED_EDGE('',*,*,#100342,.T.); -#100977 = ORIENTED_EDGE('',*,*,#100978,.T.); -#100978 = EDGE_CURVE('',#100315,#100396,#100979,.T.); -#100979 = SURFACE_CURVE('',#100980,(#100984,#100991),.PCURVE_S1.); -#100980 = LINE('',#100981,#100982); -#100981 = CARTESIAN_POINT('',(4.35,-1.,1.159810404338E-002)); -#100982 = VECTOR('',#100983,1.); -#100983 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#100984 = PCURVE('',#89779,#100985); -#100985 = DEFINITIONAL_REPRESENTATION('',(#100986),#100990); -#100986 = LINE('',#100987,#100988); -#100987 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#100988 = VECTOR('',#100989,1.); -#100989 = DIRECTION('',(-1.,2.101748079665E-016)); -#100990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100991 = PCURVE('',#100330,#100992); -#100992 = DEFINITIONAL_REPRESENTATION('',(#100993),#100997); -#100993 = LINE('',#100994,#100995); -#100994 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#100995 = VECTOR('',#100996,1.); -#100996 = DIRECTION('',(1.,0.E+000)); -#100997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#100998 = ORIENTED_EDGE('',*,*,#100393,.F.); -#100999 = ORIENTED_EDGE('',*,*,#100631,.F.); -#101000 = ORIENTED_EDGE('',*,*,#100684,.F.); -#101001 = ORIENTED_EDGE('',*,*,#100805,.F.); -#101002 = ORIENTED_EDGE('',*,*,#101003,.T.); -#101003 = EDGE_CURVE('',#100806,#89762,#101004,.T.); -#101004 = SURFACE_CURVE('',#101005,(#101009,#101016),.PCURVE_S1.); -#101005 = LINE('',#101006,#101007); -#101006 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); -#101007 = VECTOR('',#101008,1.); -#101008 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101009 = PCURVE('',#89779,#101010); -#101010 = DEFINITIONAL_REPRESENTATION('',(#101011),#101015); -#101011 = LINE('',#101012,#101013); -#101012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101013 = VECTOR('',#101014,1.); -#101014 = DIRECTION('',(3.563627120235E-016,1.)); -#101015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101016 = PCURVE('',#89807,#101017); -#101017 = DEFINITIONAL_REPRESENTATION('',(#101018),#101022); -#101018 = LINE('',#101019,#101020); -#101019 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101020 = VECTOR('',#101021,1.); -#101021 = DIRECTION('',(-1.,0.E+000)); -#101022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101023 = ORIENTED_EDGE('',*,*,#89761,.T.); -#101024 = ADVANCED_FACE('',(#101025),#89861,.F.); -#101025 = FACE_BOUND('',#101026,.T.); -#101026 = EDGE_LOOP('',(#101027,#101028,#101029,#101030)); -#101027 = ORIENTED_EDGE('',*,*,#100930,.F.); -#101028 = ORIENTED_EDGE('',*,*,#100953,.T.); -#101029 = ORIENTED_EDGE('',*,*,#89847,.T.); -#101030 = ORIENTED_EDGE('',*,*,#101031,.F.); -#101031 = EDGE_CURVE('',#100880,#89820,#101032,.T.); -#101032 = SURFACE_CURVE('',#101033,(#101037,#101044),.PCURVE_S1.); -#101033 = LINE('',#101034,#101035); -#101034 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.75)); -#101035 = VECTOR('',#101036,1.); -#101036 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101037 = PCURVE('',#89861,#101038); -#101038 = DEFINITIONAL_REPRESENTATION('',(#101039),#101043); -#101039 = LINE('',#101040,#101041); -#101040 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#101041 = VECTOR('',#101042,1.); -#101042 = DIRECTION('',(1.,0.E+000)); -#101043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101044 = PCURVE('',#89835,#101045); -#101045 = DEFINITIONAL_REPRESENTATION('',(#101046),#101050); -#101046 = LINE('',#101047,#101048); -#101047 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#101048 = VECTOR('',#101049,1.); -#101049 = DIRECTION('',(-3.563627120235E-016,1.)); -#101050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101051 = ADVANCED_FACE('',(#101052),#89835,.F.); -#101052 = FACE_BOUND('',#101053,.T.); -#101053 = EDGE_LOOP('',(#101054,#101075,#101076,#101077,#101078,#101079, - #101100,#101101,#101102,#101103,#101104,#101105)); -#101054 = ORIENTED_EDGE('',*,*,#101055,.F.); -#101055 = EDGE_CURVE('',#100833,#89792,#101056,.T.); -#101056 = SURFACE_CURVE('',#101057,(#101061,#101068),.PCURVE_S1.); -#101057 = LINE('',#101058,#101059); -#101058 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.65)); -#101059 = VECTOR('',#101060,1.); -#101060 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101061 = PCURVE('',#89835,#101062); -#101062 = DEFINITIONAL_REPRESENTATION('',(#101063),#101067); -#101063 = LINE('',#101064,#101065); -#101064 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101065 = VECTOR('',#101066,1.); -#101066 = DIRECTION('',(-3.563627120235E-016,1.)); -#101067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101068 = PCURVE('',#89807,#101069); -#101069 = DEFINITIONAL_REPRESENTATION('',(#101070),#101074); -#101070 = LINE('',#101071,#101072); -#101071 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#101072 = VECTOR('',#101073,1.); -#101073 = DIRECTION('',(-1.,0.E+000)); -#101074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101075 = ORIENTED_EDGE('',*,*,#100854,.T.); -#101076 = ORIENTED_EDGE('',*,*,#100706,.T.); -#101077 = ORIENTED_EDGE('',*,*,#100577,.T.); -#101078 = ORIENTED_EDGE('',*,*,#100446,.T.); -#101079 = ORIENTED_EDGE('',*,*,#101080,.T.); -#101080 = EDGE_CURVE('',#100424,#100287,#101081,.T.); -#101081 = SURFACE_CURVE('',#101082,(#101086,#101093),.PCURVE_S1.); -#101082 = LINE('',#101083,#101084); -#101083 = CARTESIAN_POINT('',(4.15,-1.,1.159810404338E-002)); -#101084 = VECTOR('',#101085,1.); -#101085 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#101086 = PCURVE('',#89835,#101087); -#101087 = DEFINITIONAL_REPRESENTATION('',(#101088),#101092); -#101088 = LINE('',#101089,#101090); -#101089 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#101090 = VECTOR('',#101091,1.); -#101091 = DIRECTION('',(-1.,-2.101748079665E-016)); -#101092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101093 = PCURVE('',#100330,#101094); -#101094 = DEFINITIONAL_REPRESENTATION('',(#101095),#101099); -#101095 = LINE('',#101096,#101097); -#101096 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#101097 = VECTOR('',#101098,1.); -#101098 = DIRECTION('',(-1.,0.E+000)); -#101099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101100 = ORIENTED_EDGE('',*,*,#100284,.F.); -#101101 = ORIENTED_EDGE('',*,*,#100498,.F.); -#101102 = ORIENTED_EDGE('',*,*,#100759,.F.); -#101103 = ORIENTED_EDGE('',*,*,#100879,.F.); -#101104 = ORIENTED_EDGE('',*,*,#101031,.T.); -#101105 = ORIENTED_EDGE('',*,*,#89819,.T.); -#101106 = ADVANCED_FACE('',(#101107),#89807,.F.); -#101107 = FACE_BOUND('',#101108,.T.); -#101108 = EDGE_LOOP('',(#101109,#101110,#101111,#101112)); -#101109 = ORIENTED_EDGE('',*,*,#100832,.F.); -#101110 = ORIENTED_EDGE('',*,*,#101055,.T.); -#101111 = ORIENTED_EDGE('',*,*,#89791,.T.); -#101112 = ORIENTED_EDGE('',*,*,#101003,.F.); -#101113 = ADVANCED_FACE('',(#101114),#100330,.T.); -#101114 = FACE_BOUND('',#101115,.T.); -#101115 = EDGE_LOOP('',(#101116,#101117,#101118,#101119)); -#101116 = ORIENTED_EDGE('',*,*,#101080,.F.); -#101117 = ORIENTED_EDGE('',*,*,#100423,.F.); -#101118 = ORIENTED_EDGE('',*,*,#100978,.F.); -#101119 = ORIENTED_EDGE('',*,*,#100314,.F.); -#101120 = ADVANCED_FACE('',(#101121),#101135,.T.); -#101121 = FACE_BOUND('',#101122,.T.); -#101122 = EDGE_LOOP('',(#101123,#101153,#101181,#101204)); -#101123 = ORIENTED_EDGE('',*,*,#101124,.T.); -#101124 = EDGE_CURVE('',#101125,#101127,#101129,.T.); -#101125 = VERTEX_POINT('',#101126); -#101126 = CARTESIAN_POINT('',(4.65,-0.740726081328,-0.208196358798)); -#101127 = VERTEX_POINT('',#101128); -#101128 = CARTESIAN_POINT('',(4.65,-1.,-0.208196358798)); -#101129 = SURFACE_CURVE('',#101130,(#101134,#101146),.PCURVE_S1.); -#101130 = LINE('',#101131,#101132); -#101131 = CARTESIAN_POINT('',(4.65,-0.740726081328,-0.208196358798)); -#101132 = VECTOR('',#101133,1.); -#101133 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#101134 = PCURVE('',#101135,#101140); -#101135 = PLANE('',#101136); -#101136 = AXIS2_PLACEMENT_3D('',#101137,#101138,#101139); -#101137 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#101138 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101139 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101140 = DEFINITIONAL_REPRESENTATION('',(#101141),#101145); -#101141 = LINE('',#101142,#101143); -#101142 = CARTESIAN_POINT('',(-5.35,0.E+000)); -#101143 = VECTOR('',#101144,1.); -#101144 = DIRECTION('',(0.E+000,-1.)); -#101145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101146 = PCURVE('',#88814,#101147); -#101147 = DEFINITIONAL_REPRESENTATION('',(#101148),#101152); -#101148 = LINE('',#101149,#101150); -#101149 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#101150 = VECTOR('',#101151,1.); -#101151 = DIRECTION('',(0.E+000,-1.)); -#101152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101153 = ORIENTED_EDGE('',*,*,#101154,.T.); -#101154 = EDGE_CURVE('',#101127,#101155,#101157,.T.); -#101155 = VERTEX_POINT('',#101156); -#101156 = CARTESIAN_POINT('',(4.85,-1.,-0.208196358798)); -#101157 = SURFACE_CURVE('',#101158,(#101162,#101169),.PCURVE_S1.); -#101158 = LINE('',#101159,#101160); -#101159 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#101160 = VECTOR('',#101161,1.); -#101161 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101162 = PCURVE('',#101135,#101163); -#101163 = DEFINITIONAL_REPRESENTATION('',(#101164),#101168); -#101164 = LINE('',#101165,#101166); -#101165 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#101166 = VECTOR('',#101167,1.); -#101167 = DIRECTION('',(1.,0.E+000)); -#101168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101169 = PCURVE('',#101170,#101175); -#101170 = PLANE('',#101171); -#101171 = AXIS2_PLACEMENT_3D('',#101172,#101173,#101174); -#101172 = CARTESIAN_POINT('',(4.75,-1.,-0.258196742327)); -#101173 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#101174 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#101175 = DEFINITIONAL_REPRESENTATION('',(#101176),#101180); -#101176 = LINE('',#101177,#101178); -#101177 = CARTESIAN_POINT('',(-5.000038352949E-002,5.25)); -#101178 = VECTOR('',#101179,1.); -#101179 = DIRECTION('',(0.E+000,1.)); -#101180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101181 = ORIENTED_EDGE('',*,*,#101182,.F.); -#101182 = EDGE_CURVE('',#101183,#101155,#101185,.T.); -#101183 = VERTEX_POINT('',#101184); -#101184 = CARTESIAN_POINT('',(4.85,-0.740726081328,-0.208196358798)); -#101185 = SURFACE_CURVE('',#101186,(#101190,#101197),.PCURVE_S1.); -#101186 = LINE('',#101187,#101188); -#101187 = CARTESIAN_POINT('',(4.85,-0.740726081328,-0.208196358798)); -#101188 = VECTOR('',#101189,1.); -#101189 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#101190 = PCURVE('',#101135,#101191); -#101191 = DEFINITIONAL_REPRESENTATION('',(#101192),#101196); -#101192 = LINE('',#101193,#101194); -#101193 = CARTESIAN_POINT('',(-5.15,0.E+000)); -#101194 = VECTOR('',#101195,1.); -#101195 = DIRECTION('',(0.E+000,-1.)); -#101196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101197 = PCURVE('',#88758,#101198); -#101198 = DEFINITIONAL_REPRESENTATION('',(#101199),#101203); -#101199 = LINE('',#101200,#101201); -#101200 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#101201 = VECTOR('',#101202,1.); -#101202 = DIRECTION('',(0.E+000,-1.)); -#101203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101204 = ORIENTED_EDGE('',*,*,#101205,.T.); -#101205 = EDGE_CURVE('',#101183,#101125,#101206,.T.); -#101206 = SURFACE_CURVE('',#101207,(#101211,#101218),.PCURVE_S1.); -#101207 = LINE('',#101208,#101209); -#101208 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#101209 = VECTOR('',#101210,1.); -#101210 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101211 = PCURVE('',#101135,#101212); -#101212 = DEFINITIONAL_REPRESENTATION('',(#101213),#101217); -#101213 = LINE('',#101214,#101215); -#101214 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101215 = VECTOR('',#101216,1.); -#101216 = DIRECTION('',(-1.,0.E+000)); -#101217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101218 = PCURVE('',#101219,#101224); -#101219 = CYLINDRICAL_SURFACE('',#101220,0.208574704164); -#101220 = AXIS2_PLACEMENT_3D('',#101221,#101222,#101223); -#101221 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#101222 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101223 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101224 = DEFINITIONAL_REPRESENTATION('',(#101225),#101228); -#101225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101226,#101227), +#103331 = CARTESIAN_POINT('',(3.162095483347,-5.65)); +#103332 = CARTESIAN_POINT('',(3.162095483347,-5.85)); +#103333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103334 = PCURVE('',#92253,#103335); +#103335 = DEFINITIONAL_REPRESENTATION('',(#103336),#103340); +#103336 = LINE('',#103337,#103338); +#103337 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#103338 = VECTOR('',#103339,1.); +#103339 = DIRECTION('',(0.E+000,-1.)); +#103340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103341 = ADVANCED_FACE('',(#103342),#92171,.F.); +#103342 = FACE_BOUND('',#103343,.T.); +#103343 = EDGE_LOOP('',(#103344,#103365,#103366,#103367,#103368,#103369, + #103390,#103391,#103392,#103393,#103394,#103415)); +#103344 = ORIENTED_EDGE('',*,*,#103345,.F.); +#103345 = EDGE_CURVE('',#103296,#92156,#103346,.T.); +#103346 = SURFACE_CURVE('',#103347,(#103351,#103358),.PCURVE_S1.); +#103347 = LINE('',#103348,#103349); +#103348 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.75)); +#103349 = VECTOR('',#103350,1.); +#103350 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#103351 = PCURVE('',#92171,#103352); +#103352 = DEFINITIONAL_REPRESENTATION('',(#103353),#103357); +#103353 = LINE('',#103354,#103355); +#103354 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#103355 = VECTOR('',#103356,1.); +#103356 = DIRECTION('',(3.563627120235E-016,1.)); +#103357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103358 = PCURVE('',#92253,#103359); +#103359 = DEFINITIONAL_REPRESENTATION('',(#103360),#103364); +#103360 = LINE('',#103361,#103362); +#103361 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103362 = VECTOR('',#103363,1.); +#103363 = DIRECTION('',(1.,0.E+000)); +#103364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103365 = ORIENTED_EDGE('',*,*,#103295,.T.); +#103366 = ORIENTED_EDGE('',*,*,#103173,.T.); +#103367 = ORIENTED_EDGE('',*,*,#102944,.T.); +#103368 = ORIENTED_EDGE('',*,*,#102734,.T.); +#103369 = ORIENTED_EDGE('',*,*,#103370,.T.); +#103370 = EDGE_CURVE('',#102707,#102788,#103371,.T.); +#103371 = SURFACE_CURVE('',#103372,(#103376,#103383),.PCURVE_S1.); +#103372 = LINE('',#103373,#103374); +#103373 = CARTESIAN_POINT('',(4.35,-1.,1.159810404338E-002)); +#103374 = VECTOR('',#103375,1.); +#103375 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#103376 = PCURVE('',#92171,#103377); +#103377 = DEFINITIONAL_REPRESENTATION('',(#103378),#103382); +#103378 = LINE('',#103379,#103380); +#103379 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#103380 = VECTOR('',#103381,1.); +#103381 = DIRECTION('',(-1.,2.101748079665E-016)); +#103382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103383 = PCURVE('',#102722,#103384); +#103384 = DEFINITIONAL_REPRESENTATION('',(#103385),#103389); +#103385 = LINE('',#103386,#103387); +#103386 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#103387 = VECTOR('',#103388,1.); +#103388 = DIRECTION('',(1.,0.E+000)); +#103389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103390 = ORIENTED_EDGE('',*,*,#102785,.F.); +#103391 = ORIENTED_EDGE('',*,*,#103023,.F.); +#103392 = ORIENTED_EDGE('',*,*,#103076,.F.); +#103393 = ORIENTED_EDGE('',*,*,#103197,.F.); +#103394 = ORIENTED_EDGE('',*,*,#103395,.T.); +#103395 = EDGE_CURVE('',#103198,#92154,#103396,.T.); +#103396 = SURFACE_CURVE('',#103397,(#103401,#103408),.PCURVE_S1.); +#103397 = LINE('',#103398,#103399); +#103398 = CARTESIAN_POINT('',(4.35,-0.527847992439,0.65)); +#103399 = VECTOR('',#103400,1.); +#103400 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#103401 = PCURVE('',#92171,#103402); +#103402 = DEFINITIONAL_REPRESENTATION('',(#103403),#103407); +#103403 = LINE('',#103404,#103405); +#103404 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103405 = VECTOR('',#103406,1.); +#103406 = DIRECTION('',(3.563627120235E-016,1.)); +#103407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103408 = PCURVE('',#92199,#103409); +#103409 = DEFINITIONAL_REPRESENTATION('',(#103410),#103414); +#103410 = LINE('',#103411,#103412); +#103411 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103412 = VECTOR('',#103413,1.); +#103413 = DIRECTION('',(-1.,0.E+000)); +#103414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103415 = ORIENTED_EDGE('',*,*,#92153,.T.); +#103416 = ADVANCED_FACE('',(#103417),#92253,.F.); +#103417 = FACE_BOUND('',#103418,.T.); +#103418 = EDGE_LOOP('',(#103419,#103420,#103421,#103422)); +#103419 = ORIENTED_EDGE('',*,*,#103322,.F.); +#103420 = ORIENTED_EDGE('',*,*,#103345,.T.); +#103421 = ORIENTED_EDGE('',*,*,#92239,.T.); +#103422 = ORIENTED_EDGE('',*,*,#103423,.F.); +#103423 = EDGE_CURVE('',#103272,#92212,#103424,.T.); +#103424 = SURFACE_CURVE('',#103425,(#103429,#103436),.PCURVE_S1.); +#103425 = LINE('',#103426,#103427); +#103426 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.75)); +#103427 = VECTOR('',#103428,1.); +#103428 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#103429 = PCURVE('',#92253,#103430); +#103430 = DEFINITIONAL_REPRESENTATION('',(#103431),#103435); +#103431 = LINE('',#103432,#103433); +#103432 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#103433 = VECTOR('',#103434,1.); +#103434 = DIRECTION('',(1.,0.E+000)); +#103435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103436 = PCURVE('',#92227,#103437); +#103437 = DEFINITIONAL_REPRESENTATION('',(#103438),#103442); +#103438 = LINE('',#103439,#103440); +#103439 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#103440 = VECTOR('',#103441,1.); +#103441 = DIRECTION('',(-3.563627120235E-016,1.)); +#103442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103443 = ADVANCED_FACE('',(#103444),#92227,.F.); +#103444 = FACE_BOUND('',#103445,.T.); +#103445 = EDGE_LOOP('',(#103446,#103467,#103468,#103469,#103470,#103471, + #103492,#103493,#103494,#103495,#103496,#103497)); +#103446 = ORIENTED_EDGE('',*,*,#103447,.F.); +#103447 = EDGE_CURVE('',#103225,#92184,#103448,.T.); +#103448 = SURFACE_CURVE('',#103449,(#103453,#103460),.PCURVE_S1.); +#103449 = LINE('',#103450,#103451); +#103450 = CARTESIAN_POINT('',(4.15,-0.527847992439,0.65)); +#103451 = VECTOR('',#103452,1.); +#103452 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#103453 = PCURVE('',#92227,#103454); +#103454 = DEFINITIONAL_REPRESENTATION('',(#103455),#103459); +#103455 = LINE('',#103456,#103457); +#103456 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103457 = VECTOR('',#103458,1.); +#103458 = DIRECTION('',(-3.563627120235E-016,1.)); +#103459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103460 = PCURVE('',#92199,#103461); +#103461 = DEFINITIONAL_REPRESENTATION('',(#103462),#103466); +#103462 = LINE('',#103463,#103464); +#103463 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#103464 = VECTOR('',#103465,1.); +#103465 = DIRECTION('',(-1.,0.E+000)); +#103466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103467 = ORIENTED_EDGE('',*,*,#103246,.T.); +#103468 = ORIENTED_EDGE('',*,*,#103098,.T.); +#103469 = ORIENTED_EDGE('',*,*,#102969,.T.); +#103470 = ORIENTED_EDGE('',*,*,#102838,.T.); +#103471 = ORIENTED_EDGE('',*,*,#103472,.T.); +#103472 = EDGE_CURVE('',#102816,#102679,#103473,.T.); +#103473 = SURFACE_CURVE('',#103474,(#103478,#103485),.PCURVE_S1.); +#103474 = LINE('',#103475,#103476); +#103475 = CARTESIAN_POINT('',(4.15,-1.,1.159810404338E-002)); +#103476 = VECTOR('',#103477,1.); +#103477 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#103478 = PCURVE('',#92227,#103479); +#103479 = DEFINITIONAL_REPRESENTATION('',(#103480),#103484); +#103480 = LINE('',#103481,#103482); +#103481 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#103482 = VECTOR('',#103483,1.); +#103483 = DIRECTION('',(-1.,-2.101748079665E-016)); +#103484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103485 = PCURVE('',#102722,#103486); +#103486 = DEFINITIONAL_REPRESENTATION('',(#103487),#103491); +#103487 = LINE('',#103488,#103489); +#103488 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#103489 = VECTOR('',#103490,1.); +#103490 = DIRECTION('',(-1.,0.E+000)); +#103491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103492 = ORIENTED_EDGE('',*,*,#102676,.F.); +#103493 = ORIENTED_EDGE('',*,*,#102890,.F.); +#103494 = ORIENTED_EDGE('',*,*,#103151,.F.); +#103495 = ORIENTED_EDGE('',*,*,#103271,.F.); +#103496 = ORIENTED_EDGE('',*,*,#103423,.T.); +#103497 = ORIENTED_EDGE('',*,*,#92211,.T.); +#103498 = ADVANCED_FACE('',(#103499),#92199,.F.); +#103499 = FACE_BOUND('',#103500,.T.); +#103500 = EDGE_LOOP('',(#103501,#103502,#103503,#103504)); +#103501 = ORIENTED_EDGE('',*,*,#103224,.F.); +#103502 = ORIENTED_EDGE('',*,*,#103447,.T.); +#103503 = ORIENTED_EDGE('',*,*,#92183,.T.); +#103504 = ORIENTED_EDGE('',*,*,#103395,.F.); +#103505 = ADVANCED_FACE('',(#103506),#102722,.T.); +#103506 = FACE_BOUND('',#103507,.T.); +#103507 = EDGE_LOOP('',(#103508,#103509,#103510,#103511)); +#103508 = ORIENTED_EDGE('',*,*,#103472,.F.); +#103509 = ORIENTED_EDGE('',*,*,#102815,.F.); +#103510 = ORIENTED_EDGE('',*,*,#103370,.F.); +#103511 = ORIENTED_EDGE('',*,*,#102706,.F.); +#103512 = ADVANCED_FACE('',(#103513),#103527,.T.); +#103513 = FACE_BOUND('',#103514,.T.); +#103514 = EDGE_LOOP('',(#103515,#103545,#103573,#103596)); +#103515 = ORIENTED_EDGE('',*,*,#103516,.T.); +#103516 = EDGE_CURVE('',#103517,#103519,#103521,.T.); +#103517 = VERTEX_POINT('',#103518); +#103518 = CARTESIAN_POINT('',(4.65,-0.740726081328,-0.208196358798)); +#103519 = VERTEX_POINT('',#103520); +#103520 = CARTESIAN_POINT('',(4.65,-1.,-0.208196358798)); +#103521 = SURFACE_CURVE('',#103522,(#103526,#103538),.PCURVE_S1.); +#103522 = LINE('',#103523,#103524); +#103523 = CARTESIAN_POINT('',(4.65,-0.740726081328,-0.208196358798)); +#103524 = VECTOR('',#103525,1.); +#103525 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#103526 = PCURVE('',#103527,#103532); +#103527 = PLANE('',#103528); +#103528 = AXIS2_PLACEMENT_3D('',#103529,#103530,#103531); +#103529 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#103530 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103531 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103532 = DEFINITIONAL_REPRESENTATION('',(#103533),#103537); +#103533 = LINE('',#103534,#103535); +#103534 = CARTESIAN_POINT('',(-5.35,0.E+000)); +#103535 = VECTOR('',#103536,1.); +#103536 = DIRECTION('',(0.E+000,-1.)); +#103537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103538 = PCURVE('',#91206,#103539); +#103539 = DEFINITIONAL_REPRESENTATION('',(#103540),#103544); +#103540 = LINE('',#103541,#103542); +#103541 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#103542 = VECTOR('',#103543,1.); +#103543 = DIRECTION('',(0.E+000,-1.)); +#103544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103545 = ORIENTED_EDGE('',*,*,#103546,.T.); +#103546 = EDGE_CURVE('',#103519,#103547,#103549,.T.); +#103547 = VERTEX_POINT('',#103548); +#103548 = CARTESIAN_POINT('',(4.85,-1.,-0.208196358798)); +#103549 = SURFACE_CURVE('',#103550,(#103554,#103561),.PCURVE_S1.); +#103550 = LINE('',#103551,#103552); +#103551 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#103552 = VECTOR('',#103553,1.); +#103553 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103554 = PCURVE('',#103527,#103555); +#103555 = DEFINITIONAL_REPRESENTATION('',(#103556),#103560); +#103556 = LINE('',#103557,#103558); +#103557 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#103558 = VECTOR('',#103559,1.); +#103559 = DIRECTION('',(1.,0.E+000)); +#103560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103561 = PCURVE('',#103562,#103567); +#103562 = PLANE('',#103563); +#103563 = AXIS2_PLACEMENT_3D('',#103564,#103565,#103566); +#103564 = CARTESIAN_POINT('',(4.75,-1.,-0.258196742327)); +#103565 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#103566 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#103567 = DEFINITIONAL_REPRESENTATION('',(#103568),#103572); +#103568 = LINE('',#103569,#103570); +#103569 = CARTESIAN_POINT('',(-5.000038352949E-002,5.25)); +#103570 = VECTOR('',#103571,1.); +#103571 = DIRECTION('',(0.E+000,1.)); +#103572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103573 = ORIENTED_EDGE('',*,*,#103574,.F.); +#103574 = EDGE_CURVE('',#103575,#103547,#103577,.T.); +#103575 = VERTEX_POINT('',#103576); +#103576 = CARTESIAN_POINT('',(4.85,-0.740726081328,-0.208196358798)); +#103577 = SURFACE_CURVE('',#103578,(#103582,#103589),.PCURVE_S1.); +#103578 = LINE('',#103579,#103580); +#103579 = CARTESIAN_POINT('',(4.85,-0.740726081328,-0.208196358798)); +#103580 = VECTOR('',#103581,1.); +#103581 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#103582 = PCURVE('',#103527,#103583); +#103583 = DEFINITIONAL_REPRESENTATION('',(#103584),#103588); +#103584 = LINE('',#103585,#103586); +#103585 = CARTESIAN_POINT('',(-5.15,0.E+000)); +#103586 = VECTOR('',#103587,1.); +#103587 = DIRECTION('',(0.E+000,-1.)); +#103588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103589 = PCURVE('',#91150,#103590); +#103590 = DEFINITIONAL_REPRESENTATION('',(#103591),#103595); +#103591 = LINE('',#103592,#103593); +#103592 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#103593 = VECTOR('',#103594,1.); +#103594 = DIRECTION('',(0.E+000,-1.)); +#103595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103596 = ORIENTED_EDGE('',*,*,#103597,.T.); +#103597 = EDGE_CURVE('',#103575,#103517,#103598,.T.); +#103598 = SURFACE_CURVE('',#103599,(#103603,#103610),.PCURVE_S1.); +#103599 = LINE('',#103600,#103601); +#103600 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#103601 = VECTOR('',#103602,1.); +#103602 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103603 = PCURVE('',#103527,#103604); +#103604 = DEFINITIONAL_REPRESENTATION('',(#103605),#103609); +#103605 = LINE('',#103606,#103607); +#103606 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103607 = VECTOR('',#103608,1.); +#103608 = DIRECTION('',(-1.,0.E+000)); +#103609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103610 = PCURVE('',#103611,#103616); +#103611 = CYLINDRICAL_SURFACE('',#103612,0.208574704164); +#103612 = AXIS2_PLACEMENT_3D('',#103613,#103614,#103615); +#103613 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#103614 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103615 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103616 = DEFINITIONAL_REPRESENTATION('',(#103617),#103620); +#103617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103618,#103619), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#101226 = CARTESIAN_POINT('',(3.201833915432,5.15)); -#101227 = CARTESIAN_POINT('',(3.201833915432,5.35)); -#101228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101229 = ADVANCED_FACE('',(#101230),#101244,.T.); -#101230 = FACE_BOUND('',#101231,.T.); -#101231 = EDGE_LOOP('',(#101232,#101262,#101285,#101308)); -#101232 = ORIENTED_EDGE('',*,*,#101233,.T.); -#101233 = EDGE_CURVE('',#101234,#101236,#101238,.T.); -#101234 = VERTEX_POINT('',#101235); -#101235 = CARTESIAN_POINT('',(4.85,-0.74341632541,-0.308197125857)); -#101236 = VERTEX_POINT('',#101237); -#101237 = CARTESIAN_POINT('',(4.85,-1.,-0.308197125857)); -#101238 = SURFACE_CURVE('',#101239,(#101243,#101255),.PCURVE_S1.); -#101239 = LINE('',#101240,#101241); -#101240 = CARTESIAN_POINT('',(4.85,-0.74341632541,-0.308197125857)); -#101241 = VECTOR('',#101242,1.); -#101242 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#101243 = PCURVE('',#101244,#101249); -#101244 = PLANE('',#101245); -#101245 = AXIS2_PLACEMENT_3D('',#101246,#101247,#101248); -#101246 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#101247 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101248 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101249 = DEFINITIONAL_REPRESENTATION('',(#101250),#101254); -#101250 = LINE('',#101251,#101252); -#101251 = CARTESIAN_POINT('',(5.15,0.E+000)); -#101252 = VECTOR('',#101253,1.); -#101253 = DIRECTION('',(0.E+000,-1.)); -#101254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101255 = PCURVE('',#88758,#101256); -#101256 = DEFINITIONAL_REPRESENTATION('',(#101257),#101261); -#101257 = LINE('',#101258,#101259); -#101258 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#101259 = VECTOR('',#101260,1.); -#101260 = DIRECTION('',(0.E+000,-1.)); -#101261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101262 = ORIENTED_EDGE('',*,*,#101263,.T.); -#101263 = EDGE_CURVE('',#101236,#101264,#101266,.T.); -#101264 = VERTEX_POINT('',#101265); -#101265 = CARTESIAN_POINT('',(4.65,-1.,-0.308197125857)); -#101266 = SURFACE_CURVE('',#101267,(#101271,#101278),.PCURVE_S1.); -#101267 = LINE('',#101268,#101269); -#101268 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#101269 = VECTOR('',#101270,1.); -#101270 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101271 = PCURVE('',#101244,#101272); -#101272 = DEFINITIONAL_REPRESENTATION('',(#101273),#101277); -#101273 = LINE('',#101274,#101275); -#101274 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#101275 = VECTOR('',#101276,1.); -#101276 = DIRECTION('',(1.,0.E+000)); -#101277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101278 = PCURVE('',#101170,#101279); -#101279 = DEFINITIONAL_REPRESENTATION('',(#101280),#101284); -#101280 = LINE('',#101281,#101282); -#101281 = CARTESIAN_POINT('',(5.000038352949E-002,5.25)); -#101282 = VECTOR('',#101283,1.); -#101283 = DIRECTION('',(0.E+000,-1.)); -#101284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101285 = ORIENTED_EDGE('',*,*,#101286,.F.); -#101286 = EDGE_CURVE('',#101287,#101264,#101289,.T.); -#101287 = VERTEX_POINT('',#101288); -#101288 = CARTESIAN_POINT('',(4.65,-0.74341632541,-0.308197125857)); -#101289 = SURFACE_CURVE('',#101290,(#101294,#101301),.PCURVE_S1.); -#101290 = LINE('',#101291,#101292); -#101291 = CARTESIAN_POINT('',(4.65,-0.74341632541,-0.308197125857)); -#101292 = VECTOR('',#101293,1.); -#101293 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#101294 = PCURVE('',#101244,#101295); -#101295 = DEFINITIONAL_REPRESENTATION('',(#101296),#101300); -#101296 = LINE('',#101297,#101298); -#101297 = CARTESIAN_POINT('',(5.35,0.E+000)); -#101298 = VECTOR('',#101299,1.); -#101299 = DIRECTION('',(0.E+000,-1.)); -#101300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101301 = PCURVE('',#88814,#101302); -#101302 = DEFINITIONAL_REPRESENTATION('',(#101303),#101307); -#101303 = LINE('',#101304,#101305); -#101304 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#101305 = VECTOR('',#101306,1.); -#101306 = DIRECTION('',(0.E+000,-1.)); -#101307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101308 = ORIENTED_EDGE('',*,*,#101309,.T.); -#101309 = EDGE_CURVE('',#101287,#101234,#101310,.T.); -#101310 = SURFACE_CURVE('',#101311,(#101315,#101322),.PCURVE_S1.); -#101311 = LINE('',#101312,#101313); -#101312 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#101313 = VECTOR('',#101314,1.); -#101314 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101315 = PCURVE('',#101244,#101316); -#101316 = DEFINITIONAL_REPRESENTATION('',(#101317),#101321); -#101317 = LINE('',#101318,#101319); -#101318 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101319 = VECTOR('',#101320,1.); -#101320 = DIRECTION('',(-1.,0.E+000)); -#101321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101322 = PCURVE('',#101323,#101328); -#101323 = CYLINDRICAL_SURFACE('',#101324,0.308574064194); -#101324 = AXIS2_PLACEMENT_3D('',#101325,#101326,#101327); -#101325 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#101326 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101327 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101328 = DEFINITIONAL_REPRESENTATION('',(#101329),#101332); -#101329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101330,#101331), +#103618 = CARTESIAN_POINT('',(3.201833915432,5.15)); +#103619 = CARTESIAN_POINT('',(3.201833915432,5.35)); +#103620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103621 = ADVANCED_FACE('',(#103622),#103636,.T.); +#103622 = FACE_BOUND('',#103623,.T.); +#103623 = EDGE_LOOP('',(#103624,#103654,#103677,#103700)); +#103624 = ORIENTED_EDGE('',*,*,#103625,.T.); +#103625 = EDGE_CURVE('',#103626,#103628,#103630,.T.); +#103626 = VERTEX_POINT('',#103627); +#103627 = CARTESIAN_POINT('',(4.85,-0.74341632541,-0.308197125857)); +#103628 = VERTEX_POINT('',#103629); +#103629 = CARTESIAN_POINT('',(4.85,-1.,-0.308197125857)); +#103630 = SURFACE_CURVE('',#103631,(#103635,#103647),.PCURVE_S1.); +#103631 = LINE('',#103632,#103633); +#103632 = CARTESIAN_POINT('',(4.85,-0.74341632541,-0.308197125857)); +#103633 = VECTOR('',#103634,1.); +#103634 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#103635 = PCURVE('',#103636,#103641); +#103636 = PLANE('',#103637); +#103637 = AXIS2_PLACEMENT_3D('',#103638,#103639,#103640); +#103638 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#103639 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103640 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103641 = DEFINITIONAL_REPRESENTATION('',(#103642),#103646); +#103642 = LINE('',#103643,#103644); +#103643 = CARTESIAN_POINT('',(5.15,0.E+000)); +#103644 = VECTOR('',#103645,1.); +#103645 = DIRECTION('',(0.E+000,-1.)); +#103646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103647 = PCURVE('',#91150,#103648); +#103648 = DEFINITIONAL_REPRESENTATION('',(#103649),#103653); +#103649 = LINE('',#103650,#103651); +#103650 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#103651 = VECTOR('',#103652,1.); +#103652 = DIRECTION('',(0.E+000,-1.)); +#103653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103654 = ORIENTED_EDGE('',*,*,#103655,.T.); +#103655 = EDGE_CURVE('',#103628,#103656,#103658,.T.); +#103656 = VERTEX_POINT('',#103657); +#103657 = CARTESIAN_POINT('',(4.65,-1.,-0.308197125857)); +#103658 = SURFACE_CURVE('',#103659,(#103663,#103670),.PCURVE_S1.); +#103659 = LINE('',#103660,#103661); +#103660 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#103661 = VECTOR('',#103662,1.); +#103662 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103663 = PCURVE('',#103636,#103664); +#103664 = DEFINITIONAL_REPRESENTATION('',(#103665),#103669); +#103665 = LINE('',#103666,#103667); +#103666 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#103667 = VECTOR('',#103668,1.); +#103668 = DIRECTION('',(1.,0.E+000)); +#103669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103670 = PCURVE('',#103562,#103671); +#103671 = DEFINITIONAL_REPRESENTATION('',(#103672),#103676); +#103672 = LINE('',#103673,#103674); +#103673 = CARTESIAN_POINT('',(5.000038352949E-002,5.25)); +#103674 = VECTOR('',#103675,1.); +#103675 = DIRECTION('',(0.E+000,-1.)); +#103676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103677 = ORIENTED_EDGE('',*,*,#103678,.F.); +#103678 = EDGE_CURVE('',#103679,#103656,#103681,.T.); +#103679 = VERTEX_POINT('',#103680); +#103680 = CARTESIAN_POINT('',(4.65,-0.74341632541,-0.308197125857)); +#103681 = SURFACE_CURVE('',#103682,(#103686,#103693),.PCURVE_S1.); +#103682 = LINE('',#103683,#103684); +#103683 = CARTESIAN_POINT('',(4.65,-0.74341632541,-0.308197125857)); +#103684 = VECTOR('',#103685,1.); +#103685 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#103686 = PCURVE('',#103636,#103687); +#103687 = DEFINITIONAL_REPRESENTATION('',(#103688),#103692); +#103688 = LINE('',#103689,#103690); +#103689 = CARTESIAN_POINT('',(5.35,0.E+000)); +#103690 = VECTOR('',#103691,1.); +#103691 = DIRECTION('',(0.E+000,-1.)); +#103692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103693 = PCURVE('',#91206,#103694); +#103694 = DEFINITIONAL_REPRESENTATION('',(#103695),#103699); +#103695 = LINE('',#103696,#103697); +#103696 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#103697 = VECTOR('',#103698,1.); +#103698 = DIRECTION('',(0.E+000,-1.)); +#103699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103700 = ORIENTED_EDGE('',*,*,#103701,.T.); +#103701 = EDGE_CURVE('',#103679,#103626,#103702,.T.); +#103702 = SURFACE_CURVE('',#103703,(#103707,#103714),.PCURVE_S1.); +#103703 = LINE('',#103704,#103705); +#103704 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#103705 = VECTOR('',#103706,1.); +#103706 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103707 = PCURVE('',#103636,#103708); +#103708 = DEFINITIONAL_REPRESENTATION('',(#103709),#103713); +#103709 = LINE('',#103710,#103711); +#103710 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103711 = VECTOR('',#103712,1.); +#103712 = DIRECTION('',(-1.,0.E+000)); +#103713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103714 = PCURVE('',#103715,#103720); +#103715 = CYLINDRICAL_SURFACE('',#103716,0.308574064194); +#103716 = AXIS2_PLACEMENT_3D('',#103717,#103718,#103719); +#103717 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#103718 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103719 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103720 = DEFINITIONAL_REPRESENTATION('',(#103721),#103724); +#103721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103722,#103723), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#101330 = CARTESIAN_POINT('',(3.191025391152,5.35)); -#101331 = CARTESIAN_POINT('',(3.191025391152,5.15)); -#101332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101333 = ADVANCED_FACE('',(#101334),#101219,.F.); -#101334 = FACE_BOUND('',#101335,.F.); -#101335 = EDGE_LOOP('',(#101336,#101337,#101364,#101391)); -#101336 = ORIENTED_EDGE('',*,*,#101205,.T.); -#101337 = ORIENTED_EDGE('',*,*,#101338,.F.); -#101338 = EDGE_CURVE('',#101339,#101125,#101341,.T.); -#101339 = VERTEX_POINT('',#101340); -#101340 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.E+000)); -#101341 = SURFACE_CURVE('',#101342,(#101347,#101353),.PCURVE_S1.); -#101342 = CIRCLE('',#101343,0.208574704164); -#101343 = AXIS2_PLACEMENT_3D('',#101344,#101345,#101346); -#101344 = CARTESIAN_POINT('',(4.65,-0.728168876214,2.640924866458E-017) - ); -#101345 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101346 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101347 = PCURVE('',#101219,#101348); -#101348 = DEFINITIONAL_REPRESENTATION('',(#101349),#101352); -#101349 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101350,#101351), +#103722 = CARTESIAN_POINT('',(3.191025391152,5.35)); +#103723 = CARTESIAN_POINT('',(3.191025391152,5.15)); +#103724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103725 = ADVANCED_FACE('',(#103726),#103611,.F.); +#103726 = FACE_BOUND('',#103727,.F.); +#103727 = EDGE_LOOP('',(#103728,#103729,#103756,#103783)); +#103728 = ORIENTED_EDGE('',*,*,#103597,.T.); +#103729 = ORIENTED_EDGE('',*,*,#103730,.F.); +#103730 = EDGE_CURVE('',#103731,#103517,#103733,.T.); +#103731 = VERTEX_POINT('',#103732); +#103732 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.E+000)); +#103733 = SURFACE_CURVE('',#103734,(#103739,#103745),.PCURVE_S1.); +#103734 = CIRCLE('',#103735,0.208574704164); +#103735 = AXIS2_PLACEMENT_3D('',#103736,#103737,#103738); +#103736 = CARTESIAN_POINT('',(4.65,-0.728168876214,2.640924866458E-017) + ); +#103737 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103738 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103739 = PCURVE('',#103611,#103740); +#103740 = DEFINITIONAL_REPRESENTATION('',(#103741),#103744); +#103741 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103742,#103743), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#101350 = CARTESIAN_POINT('',(1.570796326795,5.35)); -#101351 = CARTESIAN_POINT('',(3.201833915432,5.35)); -#101352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103742 = CARTESIAN_POINT('',(1.570796326795,5.35)); +#103743 = CARTESIAN_POINT('',(3.201833915432,5.35)); +#103744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101353 = PCURVE('',#88814,#101354); -#101354 = DEFINITIONAL_REPRESENTATION('',(#101355),#101363); -#101355 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101356,#101357,#101358, - #101359,#101360,#101361,#101362),.UNSPECIFIED.,.F.,.F.) +#103745 = PCURVE('',#91206,#103746); +#103746 = DEFINITIONAL_REPRESENTATION('',(#103747),#103755); +#103747 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103748,#103749,#103750, + #103751,#103752,#103753,#103754),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#101356 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#101357 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#101358 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#101359 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#101360 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#101361 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#101362 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#101363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101364 = ORIENTED_EDGE('',*,*,#101365,.T.); -#101365 = EDGE_CURVE('',#101339,#101366,#101368,.T.); -#101366 = VERTEX_POINT('',#101367); -#101367 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.E+000)); -#101368 = SURFACE_CURVE('',#101369,(#101373,#101379),.PCURVE_S1.); -#101369 = LINE('',#101370,#101371); -#101370 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#101371 = VECTOR('',#101372,1.); -#101372 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101373 = PCURVE('',#101219,#101374); -#101374 = DEFINITIONAL_REPRESENTATION('',(#101375),#101378); -#101375 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101376,#101377), +#103748 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#103749 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#103750 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#103751 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#103752 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#103753 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#103754 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#103755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103756 = ORIENTED_EDGE('',*,*,#103757,.T.); +#103757 = EDGE_CURVE('',#103731,#103758,#103760,.T.); +#103758 = VERTEX_POINT('',#103759); +#103759 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.E+000)); +#103760 = SURFACE_CURVE('',#103761,(#103765,#103771),.PCURVE_S1.); +#103761 = LINE('',#103762,#103763); +#103762 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#103763 = VECTOR('',#103764,1.); +#103764 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103765 = PCURVE('',#103611,#103766); +#103766 = DEFINITIONAL_REPRESENTATION('',(#103767),#103770); +#103767 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103768,#103769), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#101376 = CARTESIAN_POINT('',(1.570796326795,5.35)); -#101377 = CARTESIAN_POINT('',(1.570796326795,5.15)); -#101378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101379 = PCURVE('',#101380,#101385); -#101380 = PLANE('',#101381); -#101381 = AXIS2_PLACEMENT_3D('',#101382,#101383,#101384); -#101382 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#101383 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#101384 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#101385 = DEFINITIONAL_REPRESENTATION('',(#101386),#101390); -#101386 = LINE('',#101387,#101388); -#101387 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#101388 = VECTOR('',#101389,1.); -#101389 = DIRECTION('',(0.E+000,1.)); -#101390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101391 = ORIENTED_EDGE('',*,*,#101392,.T.); -#101392 = EDGE_CURVE('',#101366,#101183,#101393,.T.); -#101393 = SURFACE_CURVE('',#101394,(#101399,#101405),.PCURVE_S1.); -#101394 = CIRCLE('',#101395,0.208574704164); -#101395 = AXIS2_PLACEMENT_3D('',#101396,#101397,#101398); -#101396 = CARTESIAN_POINT('',(4.85,-0.728168876214,2.640924866458E-017) - ); -#101397 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101398 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101399 = PCURVE('',#101219,#101400); -#101400 = DEFINITIONAL_REPRESENTATION('',(#101401),#101404); -#101401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101402,#101403), +#103768 = CARTESIAN_POINT('',(1.570796326795,5.35)); +#103769 = CARTESIAN_POINT('',(1.570796326795,5.15)); +#103770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103771 = PCURVE('',#103772,#103777); +#103772 = PLANE('',#103773); +#103773 = AXIS2_PLACEMENT_3D('',#103774,#103775,#103776); +#103774 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#103775 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#103776 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#103777 = DEFINITIONAL_REPRESENTATION('',(#103778),#103782); +#103778 = LINE('',#103779,#103780); +#103779 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#103780 = VECTOR('',#103781,1.); +#103781 = DIRECTION('',(0.E+000,1.)); +#103782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103783 = ORIENTED_EDGE('',*,*,#103784,.T.); +#103784 = EDGE_CURVE('',#103758,#103575,#103785,.T.); +#103785 = SURFACE_CURVE('',#103786,(#103791,#103797),.PCURVE_S1.); +#103786 = CIRCLE('',#103787,0.208574704164); +#103787 = AXIS2_PLACEMENT_3D('',#103788,#103789,#103790); +#103788 = CARTESIAN_POINT('',(4.85,-0.728168876214,2.640924866458E-017) + ); +#103789 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103790 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103791 = PCURVE('',#103611,#103792); +#103792 = DEFINITIONAL_REPRESENTATION('',(#103793),#103796); +#103793 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103794,#103795), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#101402 = CARTESIAN_POINT('',(1.570796326795,5.15)); -#101403 = CARTESIAN_POINT('',(3.201833915432,5.15)); -#101404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101405 = PCURVE('',#88758,#101406); -#101406 = DEFINITIONAL_REPRESENTATION('',(#101407),#101411); -#101407 = CIRCLE('',#101408,0.208574704164); -#101408 = AXIS2_PLACEMENT_2D('',#101409,#101410); -#101409 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#101410 = DIRECTION('',(1.,0.E+000)); -#101411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101412 = ADVANCED_FACE('',(#101413),#101323,.T.); -#101413 = FACE_BOUND('',#101414,.T.); -#101414 = EDGE_LOOP('',(#101415,#101416,#101443,#101470)); -#101415 = ORIENTED_EDGE('',*,*,#101309,.F.); -#101416 = ORIENTED_EDGE('',*,*,#101417,.F.); -#101417 = EDGE_CURVE('',#101418,#101287,#101420,.T.); -#101418 = VERTEX_POINT('',#101419); -#101419 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.E+000)); -#101420 = SURFACE_CURVE('',#101421,(#101426,#101432),.PCURVE_S1.); -#101421 = CIRCLE('',#101422,0.308574064194); -#101422 = AXIS2_PLACEMENT_3D('',#101423,#101424,#101425); -#101423 = CARTESIAN_POINT('',(4.65,-0.728168876214,2.640924866458E-017) - ); -#101424 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101425 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101426 = PCURVE('',#101323,#101427); -#101427 = DEFINITIONAL_REPRESENTATION('',(#101428),#101431); -#101428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101429,#101430), +#103794 = CARTESIAN_POINT('',(1.570796326795,5.15)); +#103795 = CARTESIAN_POINT('',(3.201833915432,5.15)); +#103796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103797 = PCURVE('',#91150,#103798); +#103798 = DEFINITIONAL_REPRESENTATION('',(#103799),#103803); +#103799 = CIRCLE('',#103800,0.208574704164); +#103800 = AXIS2_PLACEMENT_2D('',#103801,#103802); +#103801 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#103802 = DIRECTION('',(1.,0.E+000)); +#103803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103804 = ADVANCED_FACE('',(#103805),#103715,.T.); +#103805 = FACE_BOUND('',#103806,.T.); +#103806 = EDGE_LOOP('',(#103807,#103808,#103835,#103862)); +#103807 = ORIENTED_EDGE('',*,*,#103701,.F.); +#103808 = ORIENTED_EDGE('',*,*,#103809,.F.); +#103809 = EDGE_CURVE('',#103810,#103679,#103812,.T.); +#103810 = VERTEX_POINT('',#103811); +#103811 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.E+000)); +#103812 = SURFACE_CURVE('',#103813,(#103818,#103824),.PCURVE_S1.); +#103813 = CIRCLE('',#103814,0.308574064194); +#103814 = AXIS2_PLACEMENT_3D('',#103815,#103816,#103817); +#103815 = CARTESIAN_POINT('',(4.65,-0.728168876214,2.640924866458E-017) + ); +#103816 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103817 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103818 = PCURVE('',#103715,#103819); +#103819 = DEFINITIONAL_REPRESENTATION('',(#103820),#103823); +#103820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103821,#103822), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#101429 = CARTESIAN_POINT('',(1.570796326795,5.35)); -#101430 = CARTESIAN_POINT('',(3.191025391152,5.35)); -#101431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103821 = CARTESIAN_POINT('',(1.570796326795,5.35)); +#103822 = CARTESIAN_POINT('',(3.191025391152,5.35)); +#103823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101432 = PCURVE('',#88814,#101433); -#101433 = DEFINITIONAL_REPRESENTATION('',(#101434),#101442); -#101434 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101435,#101436,#101437, - #101438,#101439,#101440,#101441),.UNSPECIFIED.,.T.,.F.) +#103824 = PCURVE('',#91206,#103825); +#103825 = DEFINITIONAL_REPRESENTATION('',(#103826),#103834); +#103826 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103827,#103828,#103829, + #103830,#103831,#103832,#103833),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#101435 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#101436 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#101437 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#101438 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#101439 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#101440 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#101441 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#101442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101443 = ORIENTED_EDGE('',*,*,#101444,.F.); -#101444 = EDGE_CURVE('',#101445,#101418,#101447,.T.); -#101445 = VERTEX_POINT('',#101446); -#101446 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.E+000)); -#101447 = SURFACE_CURVE('',#101448,(#101452,#101458),.PCURVE_S1.); -#101448 = LINE('',#101449,#101450); -#101449 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#101450 = VECTOR('',#101451,1.); -#101451 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101452 = PCURVE('',#101323,#101453); -#101453 = DEFINITIONAL_REPRESENTATION('',(#101454),#101457); -#101454 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101455,#101456), +#103827 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#103828 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#103829 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#103830 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#103831 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#103832 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#103833 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#103834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103835 = ORIENTED_EDGE('',*,*,#103836,.F.); +#103836 = EDGE_CURVE('',#103837,#103810,#103839,.T.); +#103837 = VERTEX_POINT('',#103838); +#103838 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.E+000)); +#103839 = SURFACE_CURVE('',#103840,(#103844,#103850),.PCURVE_S1.); +#103840 = LINE('',#103841,#103842); +#103841 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#103842 = VECTOR('',#103843,1.); +#103843 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103844 = PCURVE('',#103715,#103845); +#103845 = DEFINITIONAL_REPRESENTATION('',(#103846),#103849); +#103846 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103847,#103848), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#101455 = CARTESIAN_POINT('',(1.570796326795,5.15)); -#101456 = CARTESIAN_POINT('',(1.570796326795,5.35)); -#101457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101458 = PCURVE('',#101459,#101464); -#101459 = PLANE('',#101460); -#101460 = AXIS2_PLACEMENT_3D('',#101461,#101462,#101463); -#101461 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#101462 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#101463 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#101464 = DEFINITIONAL_REPRESENTATION('',(#101465),#101469); -#101465 = LINE('',#101466,#101467); -#101466 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#101467 = VECTOR('',#101468,1.); -#101468 = DIRECTION('',(0.E+000,-1.)); -#101469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101470 = ORIENTED_EDGE('',*,*,#101471,.T.); -#101471 = EDGE_CURVE('',#101445,#101234,#101472,.T.); -#101472 = SURFACE_CURVE('',#101473,(#101478,#101484),.PCURVE_S1.); -#101473 = CIRCLE('',#101474,0.308574064194); -#101474 = AXIS2_PLACEMENT_3D('',#101475,#101476,#101477); -#101475 = CARTESIAN_POINT('',(4.85,-0.728168876214,2.640924866458E-017) - ); -#101476 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101477 = DIRECTION('',(0.E+000,0.E+000,1.)); -#101478 = PCURVE('',#101323,#101479); -#101479 = DEFINITIONAL_REPRESENTATION('',(#101480),#101483); -#101480 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101481,#101482), +#103847 = CARTESIAN_POINT('',(1.570796326795,5.15)); +#103848 = CARTESIAN_POINT('',(1.570796326795,5.35)); +#103849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103850 = PCURVE('',#103851,#103856); +#103851 = PLANE('',#103852); +#103852 = AXIS2_PLACEMENT_3D('',#103853,#103854,#103855); +#103853 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#103854 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#103855 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103856 = DEFINITIONAL_REPRESENTATION('',(#103857),#103861); +#103857 = LINE('',#103858,#103859); +#103858 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#103859 = VECTOR('',#103860,1.); +#103860 = DIRECTION('',(0.E+000,-1.)); +#103861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103862 = ORIENTED_EDGE('',*,*,#103863,.T.); +#103863 = EDGE_CURVE('',#103837,#103626,#103864,.T.); +#103864 = SURFACE_CURVE('',#103865,(#103870,#103876),.PCURVE_S1.); +#103865 = CIRCLE('',#103866,0.308574064194); +#103866 = AXIS2_PLACEMENT_3D('',#103867,#103868,#103869); +#103867 = CARTESIAN_POINT('',(4.85,-0.728168876214,2.640924866458E-017) + ); +#103868 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103869 = DIRECTION('',(0.E+000,0.E+000,1.)); +#103870 = PCURVE('',#103715,#103871); +#103871 = DEFINITIONAL_REPRESENTATION('',(#103872),#103875); +#103872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103873,#103874), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#101481 = CARTESIAN_POINT('',(1.570796326795,5.15)); -#101482 = CARTESIAN_POINT('',(3.191025391152,5.15)); -#101483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103873 = CARTESIAN_POINT('',(1.570796326795,5.15)); +#103874 = CARTESIAN_POINT('',(3.191025391152,5.15)); +#103875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103876 = PCURVE('',#91150,#103877); +#103877 = DEFINITIONAL_REPRESENTATION('',(#103878),#103882); +#103878 = CIRCLE('',#103879,0.308574064194); +#103879 = AXIS2_PLACEMENT_2D('',#103880,#103881); +#103880 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#103881 = DIRECTION('',(1.,0.E+000)); +#103882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103883 = ADVANCED_FACE('',(#103884),#103851,.F.); +#103884 = FACE_BOUND('',#103885,.T.); +#103885 = EDGE_LOOP('',(#103886,#103915,#103936,#103937)); +#103886 = ORIENTED_EDGE('',*,*,#103887,.F.); +#103887 = EDGE_CURVE('',#103888,#103890,#103892,.T.); +#103888 = VERTEX_POINT('',#103889); +#103889 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.530776333563)); +#103890 = VERTEX_POINT('',#103891); +#103891 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.530776333563)); +#103892 = SURFACE_CURVE('',#103893,(#103897,#103904),.PCURVE_S1.); +#103893 = LINE('',#103894,#103895); +#103894 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#103895 = VECTOR('',#103896,1.); +#103896 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#103897 = PCURVE('',#103851,#103898); +#103898 = DEFINITIONAL_REPRESENTATION('',(#103899),#103903); +#103899 = LINE('',#103900,#103901); +#103900 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103901 = VECTOR('',#103902,1.); +#103902 = DIRECTION('',(0.E+000,-1.)); +#103903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103904 = PCURVE('',#103905,#103910); +#103905 = CYLINDRICAL_SURFACE('',#103906,0.119270391569); +#103906 = AXIS2_PLACEMENT_3D('',#103907,#103908,#103909); +#103907 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#103908 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103909 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103910 = DEFINITIONAL_REPRESENTATION('',(#103911),#103914); +#103911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103912,#103913), + .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); +#103912 = CARTESIAN_POINT('',(4.712388980385,-5.15)); +#103913 = CARTESIAN_POINT('',(4.712388980385,-5.35)); +#103914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103915 = ORIENTED_EDGE('',*,*,#103916,.T.); +#103916 = EDGE_CURVE('',#103888,#103837,#103917,.T.); +#103917 = SURFACE_CURVE('',#103918,(#103922,#103929),.PCURVE_S1.); +#103918 = LINE('',#103919,#103920); +#103919 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.530776333563)); +#103920 = VECTOR('',#103921,1.); +#103921 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103922 = PCURVE('',#103851,#103923); +#103923 = DEFINITIONAL_REPRESENTATION('',(#103924),#103928); +#103924 = LINE('',#103925,#103926); +#103925 = CARTESIAN_POINT('',(0.E+000,-5.15)); +#103926 = VECTOR('',#103927,1.); +#103927 = DIRECTION('',(1.,0.E+000)); +#103928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103929 = PCURVE('',#91150,#103930); +#103930 = DEFINITIONAL_REPRESENTATION('',(#103931),#103935); +#103931 = LINE('',#103932,#103933); +#103932 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#103933 = VECTOR('',#103934,1.); +#103934 = DIRECTION('',(-1.,-1.021336205033E-016)); +#103935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103936 = ORIENTED_EDGE('',*,*,#103836,.T.); +#103937 = ORIENTED_EDGE('',*,*,#103938,.F.); +#103938 = EDGE_CURVE('',#103890,#103810,#103939,.T.); +#103939 = SURFACE_CURVE('',#103940,(#103944,#103951),.PCURVE_S1.); +#103940 = LINE('',#103941,#103942); +#103941 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.530776333563)); +#103942 = VECTOR('',#103943,1.); +#103943 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103944 = PCURVE('',#103851,#103945); +#103945 = DEFINITIONAL_REPRESENTATION('',(#103946),#103950); +#103946 = LINE('',#103947,#103948); +#103947 = CARTESIAN_POINT('',(0.E+000,-5.35)); +#103948 = VECTOR('',#103949,1.); +#103949 = DIRECTION('',(1.,0.E+000)); +#103950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103951 = PCURVE('',#91206,#103952); +#103952 = DEFINITIONAL_REPRESENTATION('',(#103953),#103957); +#103953 = LINE('',#103954,#103955); +#103954 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#103955 = VECTOR('',#103956,1.); +#103956 = DIRECTION('',(1.,-1.021336205033E-016)); +#103957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103958 = ADVANCED_FACE('',(#103959),#103772,.F.); +#103959 = FACE_BOUND('',#103960,.T.); +#103960 = EDGE_LOOP('',(#103961,#103990,#104011,#104012)); +#103961 = ORIENTED_EDGE('',*,*,#103962,.F.); +#103962 = EDGE_CURVE('',#103963,#103965,#103967,.T.); +#103963 = VERTEX_POINT('',#103964); +#103964 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.530776333563)); +#103965 = VERTEX_POINT('',#103966); +#103966 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.530776333563)); +#103967 = SURFACE_CURVE('',#103968,(#103972,#103979),.PCURVE_S1.); +#103968 = LINE('',#103969,#103970); +#103969 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#103970 = VECTOR('',#103971,1.); +#103971 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103972 = PCURVE('',#103772,#103973); +#103973 = DEFINITIONAL_REPRESENTATION('',(#103974),#103978); +#103974 = LINE('',#103975,#103976); +#103975 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#103976 = VECTOR('',#103977,1.); +#103977 = DIRECTION('',(0.E+000,1.)); +#103978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#103979 = PCURVE('',#103980,#103985); +#103980 = CYLINDRICAL_SURFACE('',#103981,0.2192697516); +#103981 = AXIS2_PLACEMENT_3D('',#103982,#103983,#103984); +#103982 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#103983 = DIRECTION('',(1.,0.E+000,0.E+000)); +#103984 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#103985 = DEFINITIONAL_REPRESENTATION('',(#103986),#103989); +#103986 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103987,#103988), + .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); +#103987 = CARTESIAN_POINT('',(4.712388980385,-5.35)); +#103988 = CARTESIAN_POINT('',(4.712388980385,-5.15)); +#103989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101484 = PCURVE('',#88758,#101485); -#101485 = DEFINITIONAL_REPRESENTATION('',(#101486),#101490); -#101486 = CIRCLE('',#101487,0.308574064194); -#101487 = AXIS2_PLACEMENT_2D('',#101488,#101489); -#101488 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#101489 = DIRECTION('',(1.,0.E+000)); -#101490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#103990 = ORIENTED_EDGE('',*,*,#103991,.T.); +#103991 = EDGE_CURVE('',#103963,#103731,#103992,.T.); +#103992 = SURFACE_CURVE('',#103993,(#103997,#104004),.PCURVE_S1.); +#103993 = LINE('',#103994,#103995); +#103994 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.530776333563)); +#103995 = VECTOR('',#103996,1.); +#103996 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#103997 = PCURVE('',#103772,#103998); +#103998 = DEFINITIONAL_REPRESENTATION('',(#103999),#104003); +#103999 = LINE('',#104000,#104001); +#104000 = CARTESIAN_POINT('',(0.E+000,-5.35)); +#104001 = VECTOR('',#104002,1.); +#104002 = DIRECTION('',(-1.,0.E+000)); +#104003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101491 = ADVANCED_FACE('',(#101492),#101459,.F.); -#101492 = FACE_BOUND('',#101493,.T.); -#101493 = EDGE_LOOP('',(#101494,#101523,#101544,#101545)); -#101494 = ORIENTED_EDGE('',*,*,#101495,.F.); -#101495 = EDGE_CURVE('',#101496,#101498,#101500,.T.); -#101496 = VERTEX_POINT('',#101497); -#101497 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.530776333563)); -#101498 = VERTEX_POINT('',#101499); -#101499 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.530776333563)); -#101500 = SURFACE_CURVE('',#101501,(#101505,#101512),.PCURVE_S1.); -#101501 = LINE('',#101502,#101503); -#101502 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#101503 = VECTOR('',#101504,1.); -#101504 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101505 = PCURVE('',#101459,#101506); -#101506 = DEFINITIONAL_REPRESENTATION('',(#101507),#101511); -#101507 = LINE('',#101508,#101509); -#101508 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101509 = VECTOR('',#101510,1.); -#101510 = DIRECTION('',(0.E+000,-1.)); -#101511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101512 = PCURVE('',#101513,#101518); -#101513 = CYLINDRICAL_SURFACE('',#101514,0.119270391569); -#101514 = AXIS2_PLACEMENT_3D('',#101515,#101516,#101517); -#101515 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#101516 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101517 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101518 = DEFINITIONAL_REPRESENTATION('',(#101519),#101522); -#101519 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101520,#101521), - .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#101520 = CARTESIAN_POINT('',(4.712388980385,-5.15)); -#101521 = CARTESIAN_POINT('',(4.712388980385,-5.35)); -#101522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101523 = ORIENTED_EDGE('',*,*,#101524,.T.); -#101524 = EDGE_CURVE('',#101496,#101445,#101525,.T.); -#101525 = SURFACE_CURVE('',#101526,(#101530,#101537),.PCURVE_S1.); -#101526 = LINE('',#101527,#101528); -#101527 = CARTESIAN_POINT('',(4.85,-0.419594812019,0.530776333563)); -#101528 = VECTOR('',#101529,1.); -#101529 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#101530 = PCURVE('',#101459,#101531); -#101531 = DEFINITIONAL_REPRESENTATION('',(#101532),#101536); -#101532 = LINE('',#101533,#101534); -#101533 = CARTESIAN_POINT('',(0.E+000,-5.15)); -#101534 = VECTOR('',#101535,1.); -#101535 = DIRECTION('',(1.,0.E+000)); -#101536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101537 = PCURVE('',#88758,#101538); -#101538 = DEFINITIONAL_REPRESENTATION('',(#101539),#101543); -#101539 = LINE('',#101540,#101541); -#101540 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#101541 = VECTOR('',#101542,1.); -#101542 = DIRECTION('',(-1.,-1.021336205033E-016)); -#101543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101544 = ORIENTED_EDGE('',*,*,#101444,.T.); -#101545 = ORIENTED_EDGE('',*,*,#101546,.F.); -#101546 = EDGE_CURVE('',#101498,#101418,#101547,.T.); -#101547 = SURFACE_CURVE('',#101548,(#101552,#101559),.PCURVE_S1.); -#101548 = LINE('',#101549,#101550); -#101549 = CARTESIAN_POINT('',(4.65,-0.419594812019,0.530776333563)); -#101550 = VECTOR('',#101551,1.); -#101551 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#101552 = PCURVE('',#101459,#101553); -#101553 = DEFINITIONAL_REPRESENTATION('',(#101554),#101558); -#101554 = LINE('',#101555,#101556); -#101555 = CARTESIAN_POINT('',(0.E+000,-5.35)); -#101556 = VECTOR('',#101557,1.); -#101557 = DIRECTION('',(1.,0.E+000)); -#101558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101559 = PCURVE('',#88814,#101560); -#101560 = DEFINITIONAL_REPRESENTATION('',(#101561),#101565); -#101561 = LINE('',#101562,#101563); -#101562 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#101563 = VECTOR('',#101564,1.); -#101564 = DIRECTION('',(1.,-1.021336205033E-016)); -#101565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101566 = ADVANCED_FACE('',(#101567),#101380,.F.); -#101567 = FACE_BOUND('',#101568,.T.); -#101568 = EDGE_LOOP('',(#101569,#101598,#101619,#101620)); -#101569 = ORIENTED_EDGE('',*,*,#101570,.F.); -#101570 = EDGE_CURVE('',#101571,#101573,#101575,.T.); -#101571 = VERTEX_POINT('',#101572); -#101572 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.530776333563)); -#101573 = VERTEX_POINT('',#101574); -#101574 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.530776333563)); -#101575 = SURFACE_CURVE('',#101576,(#101580,#101587),.PCURVE_S1.); -#101576 = LINE('',#101577,#101578); -#101577 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#101578 = VECTOR('',#101579,1.); -#101579 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101580 = PCURVE('',#101380,#101581); -#101581 = DEFINITIONAL_REPRESENTATION('',(#101582),#101586); -#101582 = LINE('',#101583,#101584); -#101583 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101584 = VECTOR('',#101585,1.); -#101585 = DIRECTION('',(0.E+000,1.)); -#101586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101587 = PCURVE('',#101588,#101593); -#101588 = CYLINDRICAL_SURFACE('',#101589,0.2192697516); -#101589 = AXIS2_PLACEMENT_3D('',#101590,#101591,#101592); -#101590 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#101591 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101592 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101593 = DEFINITIONAL_REPRESENTATION('',(#101594),#101597); -#101594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101595,#101596), - .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#101595 = CARTESIAN_POINT('',(4.712388980385,-5.35)); -#101596 = CARTESIAN_POINT('',(4.712388980385,-5.15)); -#101597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101598 = ORIENTED_EDGE('',*,*,#101599,.T.); -#101599 = EDGE_CURVE('',#101571,#101339,#101600,.T.); -#101600 = SURFACE_CURVE('',#101601,(#101605,#101612),.PCURVE_S1.); -#101601 = LINE('',#101602,#101603); -#101602 = CARTESIAN_POINT('',(4.65,-0.51959417205,0.530776333563)); -#101603 = VECTOR('',#101604,1.); -#101604 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#101605 = PCURVE('',#101380,#101606); -#101606 = DEFINITIONAL_REPRESENTATION('',(#101607),#101611); -#101607 = LINE('',#101608,#101609); -#101608 = CARTESIAN_POINT('',(0.E+000,-5.35)); -#101609 = VECTOR('',#101610,1.); -#101610 = DIRECTION('',(-1.,0.E+000)); -#101611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101612 = PCURVE('',#88814,#101613); -#101613 = DEFINITIONAL_REPRESENTATION('',(#101614),#101618); -#101614 = LINE('',#101615,#101616); -#101615 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#101616 = VECTOR('',#101617,1.); -#101617 = DIRECTION('',(1.,-1.021336205033E-016)); -#101618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101619 = ORIENTED_EDGE('',*,*,#101365,.T.); -#101620 = ORIENTED_EDGE('',*,*,#101621,.F.); -#101621 = EDGE_CURVE('',#101573,#101366,#101622,.T.); -#101622 = SURFACE_CURVE('',#101623,(#101627,#101634),.PCURVE_S1.); -#101623 = LINE('',#101624,#101625); -#101624 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.530776333563)); -#101625 = VECTOR('',#101626,1.); -#101626 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#101627 = PCURVE('',#101380,#101628); -#101628 = DEFINITIONAL_REPRESENTATION('',(#101629),#101633); -#101629 = LINE('',#101630,#101631); -#101630 = CARTESIAN_POINT('',(0.E+000,-5.15)); -#101631 = VECTOR('',#101632,1.); -#101632 = DIRECTION('',(-1.,0.E+000)); -#101633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101634 = PCURVE('',#88758,#101635); -#101635 = DEFINITIONAL_REPRESENTATION('',(#101636),#101640); -#101636 = LINE('',#101637,#101638); -#101637 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#101638 = VECTOR('',#101639,1.); -#101639 = DIRECTION('',(-1.,-1.021336205033E-016)); -#101640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104004 = PCURVE('',#91206,#104005); +#104005 = DEFINITIONAL_REPRESENTATION('',(#104006),#104010); +#104006 = LINE('',#104007,#104008); +#104007 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#104008 = VECTOR('',#104009,1.); +#104009 = DIRECTION('',(1.,-1.021336205033E-016)); +#104010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101641 = ADVANCED_FACE('',(#101642),#101513,.F.); -#101642 = FACE_BOUND('',#101643,.F.); -#101643 = EDGE_LOOP('',(#101644,#101671,#101693,#101714)); -#101644 = ORIENTED_EDGE('',*,*,#101645,.F.); -#101645 = EDGE_CURVE('',#101646,#101496,#101648,.T.); -#101646 = VERTEX_POINT('',#101647); -#101647 = CARTESIAN_POINT('',(4.85,-0.303662633502,0.65)); -#101648 = SURFACE_CURVE('',#101649,(#101654,#101660),.PCURVE_S1.); -#101649 = CIRCLE('',#101650,0.119270391569); -#101650 = AXIS2_PLACEMENT_3D('',#101651,#101652,#101653); -#101651 = CARTESIAN_POINT('',(4.85,-0.30032442045,0.530776333563)); -#101652 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101653 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101654 = PCURVE('',#101513,#101655); -#101655 = DEFINITIONAL_REPRESENTATION('',(#101656),#101659); -#101656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101657,#101658), +#104011 = ORIENTED_EDGE('',*,*,#103757,.T.); +#104012 = ORIENTED_EDGE('',*,*,#104013,.F.); +#104013 = EDGE_CURVE('',#103965,#103758,#104014,.T.); +#104014 = SURFACE_CURVE('',#104015,(#104019,#104026),.PCURVE_S1.); +#104015 = LINE('',#104016,#104017); +#104016 = CARTESIAN_POINT('',(4.85,-0.51959417205,0.530776333563)); +#104017 = VECTOR('',#104018,1.); +#104018 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104019 = PCURVE('',#103772,#104020); +#104020 = DEFINITIONAL_REPRESENTATION('',(#104021),#104025); +#104021 = LINE('',#104022,#104023); +#104022 = CARTESIAN_POINT('',(0.E+000,-5.15)); +#104023 = VECTOR('',#104024,1.); +#104024 = DIRECTION('',(-1.,0.E+000)); +#104025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104026 = PCURVE('',#91150,#104027); +#104027 = DEFINITIONAL_REPRESENTATION('',(#104028),#104032); +#104028 = LINE('',#104029,#104030); +#104029 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#104030 = VECTOR('',#104031,1.); +#104031 = DIRECTION('',(-1.,-1.021336205033E-016)); +#104032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104033 = ADVANCED_FACE('',(#104034),#103905,.F.); +#104034 = FACE_BOUND('',#104035,.F.); +#104035 = EDGE_LOOP('',(#104036,#104063,#104085,#104106)); +#104036 = ORIENTED_EDGE('',*,*,#104037,.F.); +#104037 = EDGE_CURVE('',#104038,#103888,#104040,.T.); +#104038 = VERTEX_POINT('',#104039); +#104039 = CARTESIAN_POINT('',(4.85,-0.303662633502,0.65)); +#104040 = SURFACE_CURVE('',#104041,(#104046,#104052),.PCURVE_S1.); +#104041 = CIRCLE('',#104042,0.119270391569); +#104042 = AXIS2_PLACEMENT_3D('',#104043,#104044,#104045); +#104043 = CARTESIAN_POINT('',(4.85,-0.30032442045,0.530776333563)); +#104044 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104045 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104046 = PCURVE('',#103905,#104047); +#104047 = DEFINITIONAL_REPRESENTATION('',(#104048),#104051); +#104048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104049,#104050), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#101657 = CARTESIAN_POINT('',(3.169584923929,-5.15)); -#101658 = CARTESIAN_POINT('',(4.712388980385,-5.15)); -#101659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104049 = CARTESIAN_POINT('',(3.169584923929,-5.15)); +#104050 = CARTESIAN_POINT('',(4.712388980385,-5.15)); +#104051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101660 = PCURVE('',#88758,#101661); -#101661 = DEFINITIONAL_REPRESENTATION('',(#101662),#101670); -#101662 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101663,#101664,#101665, - #101666,#101667,#101668,#101669),.UNSPECIFIED.,.F.,.F.) +#104052 = PCURVE('',#91150,#104053); +#104053 = DEFINITIONAL_REPRESENTATION('',(#104054),#104062); +#104054 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104055,#104056,#104057, + #104058,#104059,#104060,#104061),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#101663 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#101664 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#101665 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#101666 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#101667 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#101668 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#101669 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#101670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101671 = ORIENTED_EDGE('',*,*,#101672,.F.); -#101672 = EDGE_CURVE('',#101673,#101646,#101675,.T.); -#101673 = VERTEX_POINT('',#101674); -#101674 = CARTESIAN_POINT('',(4.65,-0.303662633502,0.65)); -#101675 = SURFACE_CURVE('',#101676,(#101680,#101686),.PCURVE_S1.); -#101676 = LINE('',#101677,#101678); -#101677 = CARTESIAN_POINT('',(4.85,-0.303662633502,0.65)); -#101678 = VECTOR('',#101679,1.); -#101679 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101680 = PCURVE('',#101513,#101681); -#101681 = DEFINITIONAL_REPRESENTATION('',(#101682),#101685); -#101682 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101683,#101684), +#104055 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#104056 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#104057 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#104058 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#104059 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#104060 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#104061 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#104062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104063 = ORIENTED_EDGE('',*,*,#104064,.F.); +#104064 = EDGE_CURVE('',#104065,#104038,#104067,.T.); +#104065 = VERTEX_POINT('',#104066); +#104066 = CARTESIAN_POINT('',(4.65,-0.303662633502,0.65)); +#104067 = SURFACE_CURVE('',#104068,(#104072,#104078),.PCURVE_S1.); +#104068 = LINE('',#104069,#104070); +#104069 = CARTESIAN_POINT('',(4.85,-0.303662633502,0.65)); +#104070 = VECTOR('',#104071,1.); +#104071 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104072 = PCURVE('',#103905,#104073); +#104073 = DEFINITIONAL_REPRESENTATION('',(#104074),#104077); +#104074 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104075,#104076), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#101683 = CARTESIAN_POINT('',(3.169584923929,-5.35)); -#101684 = CARTESIAN_POINT('',(3.169584923929,-5.15)); -#101685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101686 = PCURVE('',#88786,#101687); -#101687 = DEFINITIONAL_REPRESENTATION('',(#101688),#101692); -#101688 = LINE('',#101689,#101690); -#101689 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#101690 = VECTOR('',#101691,1.); -#101691 = DIRECTION('',(0.E+000,1.)); -#101692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101693 = ORIENTED_EDGE('',*,*,#101694,.T.); -#101694 = EDGE_CURVE('',#101673,#101498,#101695,.T.); -#101695 = SURFACE_CURVE('',#101696,(#101701,#101707),.PCURVE_S1.); -#101696 = CIRCLE('',#101697,0.119270391569); -#101697 = AXIS2_PLACEMENT_3D('',#101698,#101699,#101700); -#101698 = CARTESIAN_POINT('',(4.65,-0.30032442045,0.530776333563)); -#101699 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101700 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101701 = PCURVE('',#101513,#101702); -#101702 = DEFINITIONAL_REPRESENTATION('',(#101703),#101706); -#101703 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101704,#101705), +#104075 = CARTESIAN_POINT('',(3.169584923929,-5.35)); +#104076 = CARTESIAN_POINT('',(3.169584923929,-5.15)); +#104077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104078 = PCURVE('',#91178,#104079); +#104079 = DEFINITIONAL_REPRESENTATION('',(#104080),#104084); +#104080 = LINE('',#104081,#104082); +#104081 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#104082 = VECTOR('',#104083,1.); +#104083 = DIRECTION('',(0.E+000,1.)); +#104084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104085 = ORIENTED_EDGE('',*,*,#104086,.T.); +#104086 = EDGE_CURVE('',#104065,#103890,#104087,.T.); +#104087 = SURFACE_CURVE('',#104088,(#104093,#104099),.PCURVE_S1.); +#104088 = CIRCLE('',#104089,0.119270391569); +#104089 = AXIS2_PLACEMENT_3D('',#104090,#104091,#104092); +#104090 = CARTESIAN_POINT('',(4.65,-0.30032442045,0.530776333563)); +#104091 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104092 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104093 = PCURVE('',#103905,#104094); +#104094 = DEFINITIONAL_REPRESENTATION('',(#104095),#104098); +#104095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104096,#104097), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#101704 = CARTESIAN_POINT('',(3.169584923929,-5.35)); -#101705 = CARTESIAN_POINT('',(4.712388980385,-5.35)); -#101706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101707 = PCURVE('',#88814,#101708); -#101708 = DEFINITIONAL_REPRESENTATION('',(#101709),#101713); -#101709 = CIRCLE('',#101710,0.119270391569); -#101710 = AXIS2_PLACEMENT_2D('',#101711,#101712); -#101711 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#101712 = DIRECTION('',(1.,0.E+000)); -#101713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101714 = ORIENTED_EDGE('',*,*,#101495,.F.); -#101715 = ADVANCED_FACE('',(#101716),#101588,.T.); -#101716 = FACE_BOUND('',#101717,.T.); -#101717 = EDGE_LOOP('',(#101718,#101741,#101742,#101769)); -#101718 = ORIENTED_EDGE('',*,*,#101719,.T.); -#101719 = EDGE_CURVE('',#101720,#101571,#101722,.T.); -#101720 = VERTEX_POINT('',#101721); -#101721 = CARTESIAN_POINT('',(4.65,-0.304819755875,0.75)); -#101722 = SURFACE_CURVE('',#101723,(#101728,#101734),.PCURVE_S1.); -#101723 = CIRCLE('',#101724,0.2192697516); -#101724 = AXIS2_PLACEMENT_3D('',#101725,#101726,#101727); -#101725 = CARTESIAN_POINT('',(4.65,-0.30032442045,0.530776333563)); -#101726 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101727 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101728 = PCURVE('',#101588,#101729); -#101729 = DEFINITIONAL_REPRESENTATION('',(#101730),#101733); -#101730 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101731,#101732), +#104096 = CARTESIAN_POINT('',(3.169584923929,-5.35)); +#104097 = CARTESIAN_POINT('',(4.712388980385,-5.35)); +#104098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104099 = PCURVE('',#91206,#104100); +#104100 = DEFINITIONAL_REPRESENTATION('',(#104101),#104105); +#104101 = CIRCLE('',#104102,0.119270391569); +#104102 = AXIS2_PLACEMENT_2D('',#104103,#104104); +#104103 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#104104 = DIRECTION('',(1.,0.E+000)); +#104105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104106 = ORIENTED_EDGE('',*,*,#103887,.F.); +#104107 = ADVANCED_FACE('',(#104108),#103980,.T.); +#104108 = FACE_BOUND('',#104109,.T.); +#104109 = EDGE_LOOP('',(#104110,#104133,#104134,#104161)); +#104110 = ORIENTED_EDGE('',*,*,#104111,.T.); +#104111 = EDGE_CURVE('',#104112,#103963,#104114,.T.); +#104112 = VERTEX_POINT('',#104113); +#104113 = CARTESIAN_POINT('',(4.65,-0.304819755875,0.75)); +#104114 = SURFACE_CURVE('',#104115,(#104120,#104126),.PCURVE_S1.); +#104115 = CIRCLE('',#104116,0.2192697516); +#104116 = AXIS2_PLACEMENT_3D('',#104117,#104118,#104119); +#104117 = CARTESIAN_POINT('',(4.65,-0.30032442045,0.530776333563)); +#104118 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104119 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104120 = PCURVE('',#103980,#104121); +#104121 = DEFINITIONAL_REPRESENTATION('',(#104122),#104125); +#104122 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104123,#104124), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#101731 = CARTESIAN_POINT('',(3.162095483347,-5.35)); -#101732 = CARTESIAN_POINT('',(4.712388980385,-5.35)); -#101733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101734 = PCURVE('',#88814,#101735); -#101735 = DEFINITIONAL_REPRESENTATION('',(#101736),#101740); -#101736 = CIRCLE('',#101737,0.2192697516); -#101737 = AXIS2_PLACEMENT_2D('',#101738,#101739); -#101738 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#101739 = DIRECTION('',(1.,0.E+000)); -#101740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101741 = ORIENTED_EDGE('',*,*,#101570,.T.); -#101742 = ORIENTED_EDGE('',*,*,#101743,.F.); -#101743 = EDGE_CURVE('',#101744,#101573,#101746,.T.); -#101744 = VERTEX_POINT('',#101745); -#101745 = CARTESIAN_POINT('',(4.85,-0.304819755875,0.75)); -#101746 = SURFACE_CURVE('',#101747,(#101752,#101758),.PCURVE_S1.); -#101747 = CIRCLE('',#101748,0.2192697516); -#101748 = AXIS2_PLACEMENT_3D('',#101749,#101750,#101751); -#101749 = CARTESIAN_POINT('',(4.85,-0.30032442045,0.530776333563)); -#101750 = DIRECTION('',(1.,0.E+000,0.E+000)); -#101751 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101752 = PCURVE('',#101588,#101753); -#101753 = DEFINITIONAL_REPRESENTATION('',(#101754),#101757); -#101754 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101755,#101756), +#104123 = CARTESIAN_POINT('',(3.162095483347,-5.35)); +#104124 = CARTESIAN_POINT('',(4.712388980385,-5.35)); +#104125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104126 = PCURVE('',#91206,#104127); +#104127 = DEFINITIONAL_REPRESENTATION('',(#104128),#104132); +#104128 = CIRCLE('',#104129,0.2192697516); +#104129 = AXIS2_PLACEMENT_2D('',#104130,#104131); +#104130 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#104131 = DIRECTION('',(1.,0.E+000)); +#104132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104133 = ORIENTED_EDGE('',*,*,#103962,.T.); +#104134 = ORIENTED_EDGE('',*,*,#104135,.F.); +#104135 = EDGE_CURVE('',#104136,#103965,#104138,.T.); +#104136 = VERTEX_POINT('',#104137); +#104137 = CARTESIAN_POINT('',(4.85,-0.304819755875,0.75)); +#104138 = SURFACE_CURVE('',#104139,(#104144,#104150),.PCURVE_S1.); +#104139 = CIRCLE('',#104140,0.2192697516); +#104140 = AXIS2_PLACEMENT_3D('',#104141,#104142,#104143); +#104141 = CARTESIAN_POINT('',(4.85,-0.30032442045,0.530776333563)); +#104142 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104143 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104144 = PCURVE('',#103980,#104145); +#104145 = DEFINITIONAL_REPRESENTATION('',(#104146),#104149); +#104146 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104147,#104148), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#101755 = CARTESIAN_POINT('',(3.162095483347,-5.15)); -#101756 = CARTESIAN_POINT('',(4.712388980385,-5.15)); -#101757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104147 = CARTESIAN_POINT('',(3.162095483347,-5.15)); +#104148 = CARTESIAN_POINT('',(4.712388980385,-5.15)); +#104149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#101758 = PCURVE('',#88758,#101759); -#101759 = DEFINITIONAL_REPRESENTATION('',(#101760),#101768); -#101760 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#101761,#101762,#101763, - #101764,#101765,#101766,#101767),.UNSPECIFIED.,.T.,.F.) +#104150 = PCURVE('',#91150,#104151); +#104151 = DEFINITIONAL_REPRESENTATION('',(#104152),#104160); +#104152 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104153,#104154,#104155, + #104156,#104157,#104158,#104159),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#101761 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#101762 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#101763 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#101764 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#101765 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#101766 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#101767 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#101768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101769 = ORIENTED_EDGE('',*,*,#101770,.T.); -#101770 = EDGE_CURVE('',#101744,#101720,#101771,.T.); -#101771 = SURFACE_CURVE('',#101772,(#101776,#101782),.PCURVE_S1.); -#101772 = LINE('',#101773,#101774); -#101773 = CARTESIAN_POINT('',(4.85,-0.304819755875,0.75)); -#101774 = VECTOR('',#101775,1.); -#101775 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101776 = PCURVE('',#101588,#101777); -#101777 = DEFINITIONAL_REPRESENTATION('',(#101778),#101781); -#101778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#101779,#101780), +#104153 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#104154 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#104155 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#104156 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#104157 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#104158 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#104159 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#104160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104161 = ORIENTED_EDGE('',*,*,#104162,.T.); +#104162 = EDGE_CURVE('',#104136,#104112,#104163,.T.); +#104163 = SURFACE_CURVE('',#104164,(#104168,#104174),.PCURVE_S1.); +#104164 = LINE('',#104165,#104166); +#104165 = CARTESIAN_POINT('',(4.85,-0.304819755875,0.75)); +#104166 = VECTOR('',#104167,1.); +#104167 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104168 = PCURVE('',#103980,#104169); +#104169 = DEFINITIONAL_REPRESENTATION('',(#104170),#104173); +#104170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104171,#104172), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#101779 = CARTESIAN_POINT('',(3.162095483347,-5.15)); -#101780 = CARTESIAN_POINT('',(3.162095483347,-5.35)); -#101781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101782 = PCURVE('',#88840,#101783); -#101783 = DEFINITIONAL_REPRESENTATION('',(#101784),#101788); -#101784 = LINE('',#101785,#101786); -#101785 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#101786 = VECTOR('',#101787,1.); -#101787 = DIRECTION('',(0.E+000,-1.)); -#101788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101789 = ADVANCED_FACE('',(#101790),#88758,.F.); -#101790 = FACE_BOUND('',#101791,.T.); -#101791 = EDGE_LOOP('',(#101792,#101813,#101814,#101815,#101816,#101817, - #101838,#101839,#101840,#101841,#101842,#101863)); -#101792 = ORIENTED_EDGE('',*,*,#101793,.F.); -#101793 = EDGE_CURVE('',#101744,#88743,#101794,.T.); -#101794 = SURFACE_CURVE('',#101795,(#101799,#101806),.PCURVE_S1.); -#101795 = LINE('',#101796,#101797); -#101796 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.75)); -#101797 = VECTOR('',#101798,1.); -#101798 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101799 = PCURVE('',#88758,#101800); -#101800 = DEFINITIONAL_REPRESENTATION('',(#101801),#101805); -#101801 = LINE('',#101802,#101803); -#101802 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#101803 = VECTOR('',#101804,1.); -#101804 = DIRECTION('',(3.563627120235E-016,1.)); -#101805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101806 = PCURVE('',#88840,#101807); -#101807 = DEFINITIONAL_REPRESENTATION('',(#101808),#101812); -#101808 = LINE('',#101809,#101810); -#101809 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101810 = VECTOR('',#101811,1.); -#101811 = DIRECTION('',(1.,0.E+000)); -#101812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101813 = ORIENTED_EDGE('',*,*,#101743,.T.); -#101814 = ORIENTED_EDGE('',*,*,#101621,.T.); -#101815 = ORIENTED_EDGE('',*,*,#101392,.T.); -#101816 = ORIENTED_EDGE('',*,*,#101182,.T.); -#101817 = ORIENTED_EDGE('',*,*,#101818,.T.); -#101818 = EDGE_CURVE('',#101155,#101236,#101819,.T.); -#101819 = SURFACE_CURVE('',#101820,(#101824,#101831),.PCURVE_S1.); -#101820 = LINE('',#101821,#101822); -#101821 = CARTESIAN_POINT('',(4.85,-1.,1.159810404338E-002)); -#101822 = VECTOR('',#101823,1.); -#101823 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#101824 = PCURVE('',#88758,#101825); -#101825 = DEFINITIONAL_REPRESENTATION('',(#101826),#101830); -#101826 = LINE('',#101827,#101828); -#101827 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#101828 = VECTOR('',#101829,1.); -#101829 = DIRECTION('',(-1.,2.101748079665E-016)); -#101830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101831 = PCURVE('',#101170,#101832); -#101832 = DEFINITIONAL_REPRESENTATION('',(#101833),#101837); -#101833 = LINE('',#101834,#101835); -#101834 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#101835 = VECTOR('',#101836,1.); -#101836 = DIRECTION('',(1.,0.E+000)); -#101837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101838 = ORIENTED_EDGE('',*,*,#101233,.F.); -#101839 = ORIENTED_EDGE('',*,*,#101471,.F.); -#101840 = ORIENTED_EDGE('',*,*,#101524,.F.); -#101841 = ORIENTED_EDGE('',*,*,#101645,.F.); -#101842 = ORIENTED_EDGE('',*,*,#101843,.T.); -#101843 = EDGE_CURVE('',#101646,#88741,#101844,.T.); -#101844 = SURFACE_CURVE('',#101845,(#101849,#101856),.PCURVE_S1.); -#101845 = LINE('',#101846,#101847); -#101846 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); -#101847 = VECTOR('',#101848,1.); -#101848 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101849 = PCURVE('',#88758,#101850); -#101850 = DEFINITIONAL_REPRESENTATION('',(#101851),#101855); -#101851 = LINE('',#101852,#101853); -#101852 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101853 = VECTOR('',#101854,1.); -#101854 = DIRECTION('',(3.563627120235E-016,1.)); -#101855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101856 = PCURVE('',#88786,#101857); -#101857 = DEFINITIONAL_REPRESENTATION('',(#101858),#101862); -#101858 = LINE('',#101859,#101860); -#101859 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101860 = VECTOR('',#101861,1.); -#101861 = DIRECTION('',(-1.,0.E+000)); -#101862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101863 = ORIENTED_EDGE('',*,*,#88740,.T.); -#101864 = ADVANCED_FACE('',(#101865),#88840,.F.); -#101865 = FACE_BOUND('',#101866,.T.); -#101866 = EDGE_LOOP('',(#101867,#101868,#101869,#101870)); -#101867 = ORIENTED_EDGE('',*,*,#101770,.F.); -#101868 = ORIENTED_EDGE('',*,*,#101793,.T.); -#101869 = ORIENTED_EDGE('',*,*,#88826,.T.); -#101870 = ORIENTED_EDGE('',*,*,#101871,.F.); -#101871 = EDGE_CURVE('',#101720,#88799,#101872,.T.); -#101872 = SURFACE_CURVE('',#101873,(#101877,#101884),.PCURVE_S1.); -#101873 = LINE('',#101874,#101875); -#101874 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.75)); -#101875 = VECTOR('',#101876,1.); -#101876 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101877 = PCURVE('',#88840,#101878); -#101878 = DEFINITIONAL_REPRESENTATION('',(#101879),#101883); -#101879 = LINE('',#101880,#101881); -#101880 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#101881 = VECTOR('',#101882,1.); -#101882 = DIRECTION('',(1.,0.E+000)); -#101883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101884 = PCURVE('',#88814,#101885); -#101885 = DEFINITIONAL_REPRESENTATION('',(#101886),#101890); -#101886 = LINE('',#101887,#101888); -#101887 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#101888 = VECTOR('',#101889,1.); -#101889 = DIRECTION('',(-3.563627120235E-016,1.)); -#101890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101891 = ADVANCED_FACE('',(#101892),#88814,.F.); -#101892 = FACE_BOUND('',#101893,.T.); -#101893 = EDGE_LOOP('',(#101894,#101915,#101916,#101917,#101918,#101919, - #101940,#101941,#101942,#101943,#101944,#101945)); -#101894 = ORIENTED_EDGE('',*,*,#101895,.F.); -#101895 = EDGE_CURVE('',#101673,#88771,#101896,.T.); -#101896 = SURFACE_CURVE('',#101897,(#101901,#101908),.PCURVE_S1.); -#101897 = LINE('',#101898,#101899); -#101898 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.65)); -#101899 = VECTOR('',#101900,1.); -#101900 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#101901 = PCURVE('',#88814,#101902); -#101902 = DEFINITIONAL_REPRESENTATION('',(#101903),#101907); -#101903 = LINE('',#101904,#101905); -#101904 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#101905 = VECTOR('',#101906,1.); -#101906 = DIRECTION('',(-3.563627120235E-016,1.)); -#101907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101908 = PCURVE('',#88786,#101909); -#101909 = DEFINITIONAL_REPRESENTATION('',(#101910),#101914); -#101910 = LINE('',#101911,#101912); -#101911 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#101912 = VECTOR('',#101913,1.); -#101913 = DIRECTION('',(-1.,0.E+000)); -#101914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101915 = ORIENTED_EDGE('',*,*,#101694,.T.); -#101916 = ORIENTED_EDGE('',*,*,#101546,.T.); -#101917 = ORIENTED_EDGE('',*,*,#101417,.T.); -#101918 = ORIENTED_EDGE('',*,*,#101286,.T.); -#101919 = ORIENTED_EDGE('',*,*,#101920,.T.); -#101920 = EDGE_CURVE('',#101264,#101127,#101921,.T.); -#101921 = SURFACE_CURVE('',#101922,(#101926,#101933),.PCURVE_S1.); -#101922 = LINE('',#101923,#101924); -#101923 = CARTESIAN_POINT('',(4.65,-1.,1.159810404338E-002)); -#101924 = VECTOR('',#101925,1.); -#101925 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#101926 = PCURVE('',#88814,#101927); -#101927 = DEFINITIONAL_REPRESENTATION('',(#101928),#101932); -#101928 = LINE('',#101929,#101930); -#101929 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#101930 = VECTOR('',#101931,1.); -#101931 = DIRECTION('',(-1.,-2.101748079665E-016)); -#101932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101933 = PCURVE('',#101170,#101934); -#101934 = DEFINITIONAL_REPRESENTATION('',(#101935),#101939); -#101935 = LINE('',#101936,#101937); -#101936 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#101937 = VECTOR('',#101938,1.); -#101938 = DIRECTION('',(-1.,0.E+000)); -#101939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101940 = ORIENTED_EDGE('',*,*,#101124,.F.); -#101941 = ORIENTED_EDGE('',*,*,#101338,.F.); -#101942 = ORIENTED_EDGE('',*,*,#101599,.F.); -#101943 = ORIENTED_EDGE('',*,*,#101719,.F.); -#101944 = ORIENTED_EDGE('',*,*,#101871,.T.); -#101945 = ORIENTED_EDGE('',*,*,#88798,.T.); -#101946 = ADVANCED_FACE('',(#101947),#88786,.F.); -#101947 = FACE_BOUND('',#101948,.T.); -#101948 = EDGE_LOOP('',(#101949,#101950,#101951,#101952)); -#101949 = ORIENTED_EDGE('',*,*,#101672,.F.); -#101950 = ORIENTED_EDGE('',*,*,#101895,.T.); -#101951 = ORIENTED_EDGE('',*,*,#88770,.T.); -#101952 = ORIENTED_EDGE('',*,*,#101843,.F.); -#101953 = ADVANCED_FACE('',(#101954),#101170,.T.); -#101954 = FACE_BOUND('',#101955,.T.); -#101955 = EDGE_LOOP('',(#101956,#101957,#101958,#101959)); -#101956 = ORIENTED_EDGE('',*,*,#101920,.F.); -#101957 = ORIENTED_EDGE('',*,*,#101263,.F.); -#101958 = ORIENTED_EDGE('',*,*,#101818,.F.); -#101959 = ORIENTED_EDGE('',*,*,#101154,.F.); -#101960 = ADVANCED_FACE('',(#101961),#101975,.T.); -#101961 = FACE_BOUND('',#101962,.T.); -#101962 = EDGE_LOOP('',(#101963,#101993,#102021,#102044)); -#101963 = ORIENTED_EDGE('',*,*,#101964,.T.); -#101964 = EDGE_CURVE('',#101965,#101967,#101969,.T.); -#101965 = VERTEX_POINT('',#101966); -#101966 = CARTESIAN_POINT('',(5.85,-0.74341632541,-0.308197125857)); -#101967 = VERTEX_POINT('',#101968); -#101968 = CARTESIAN_POINT('',(5.85,-1.,-0.308197125857)); -#101969 = SURFACE_CURVE('',#101970,(#101974,#101986),.PCURVE_S1.); -#101970 = LINE('',#101971,#101972); -#101971 = CARTESIAN_POINT('',(5.85,-0.74341632541,-0.308197125857)); -#101972 = VECTOR('',#101973,1.); -#101973 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#101974 = PCURVE('',#101975,#101980); -#101975 = PLANE('',#101976); -#101976 = AXIS2_PLACEMENT_3D('',#101977,#101978,#101979); -#101977 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#101978 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#101979 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#101980 = DEFINITIONAL_REPRESENTATION('',(#101981),#101985); -#101981 = LINE('',#101982,#101983); -#101982 = CARTESIAN_POINT('',(4.15,0.E+000)); -#101983 = VECTOR('',#101984,1.); -#101984 = DIRECTION('',(0.E+000,-1.)); -#101985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101986 = PCURVE('',#89949,#101987); -#101987 = DEFINITIONAL_REPRESENTATION('',(#101988),#101992); -#101988 = LINE('',#101989,#101990); -#101989 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#101990 = VECTOR('',#101991,1.); -#101991 = DIRECTION('',(0.E+000,-1.)); -#101992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#101993 = ORIENTED_EDGE('',*,*,#101994,.T.); -#101994 = EDGE_CURVE('',#101967,#101995,#101997,.T.); -#101995 = VERTEX_POINT('',#101996); -#101996 = CARTESIAN_POINT('',(5.65,-1.,-0.308197125857)); -#101997 = SURFACE_CURVE('',#101998,(#102002,#102009),.PCURVE_S1.); -#101998 = LINE('',#101999,#102000); -#101999 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#102000 = VECTOR('',#102001,1.); -#102001 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102002 = PCURVE('',#101975,#102003); -#102003 = DEFINITIONAL_REPRESENTATION('',(#102004),#102008); -#102004 = LINE('',#102005,#102006); -#102005 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#102006 = VECTOR('',#102007,1.); -#102007 = DIRECTION('',(1.,0.E+000)); -#102008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102009 = PCURVE('',#102010,#102015); -#102010 = PLANE('',#102011); -#102011 = AXIS2_PLACEMENT_3D('',#102012,#102013,#102014); -#102012 = CARTESIAN_POINT('',(5.75,-1.,-0.258196742327)); -#102013 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#102014 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#102015 = DEFINITIONAL_REPRESENTATION('',(#102016),#102020); -#102016 = LINE('',#102017,#102018); -#102017 = CARTESIAN_POINT('',(5.000038352949E-002,4.25)); -#102018 = VECTOR('',#102019,1.); -#102019 = DIRECTION('',(0.E+000,-1.)); -#102020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102021 = ORIENTED_EDGE('',*,*,#102022,.F.); -#102022 = EDGE_CURVE('',#102023,#101995,#102025,.T.); -#102023 = VERTEX_POINT('',#102024); -#102024 = CARTESIAN_POINT('',(5.65,-0.74341632541,-0.308197125857)); -#102025 = SURFACE_CURVE('',#102026,(#102030,#102037),.PCURVE_S1.); -#102026 = LINE('',#102027,#102028); -#102027 = CARTESIAN_POINT('',(5.65,-0.74341632541,-0.308197125857)); -#102028 = VECTOR('',#102029,1.); -#102029 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102030 = PCURVE('',#101975,#102031); -#102031 = DEFINITIONAL_REPRESENTATION('',(#102032),#102036); -#102032 = LINE('',#102033,#102034); -#102033 = CARTESIAN_POINT('',(4.35,0.E+000)); -#102034 = VECTOR('',#102035,1.); -#102035 = DIRECTION('',(0.E+000,-1.)); -#102036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102037 = PCURVE('',#89893,#102038); -#102038 = DEFINITIONAL_REPRESENTATION('',(#102039),#102043); -#102039 = LINE('',#102040,#102041); -#102040 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#102041 = VECTOR('',#102042,1.); -#102042 = DIRECTION('',(0.E+000,-1.)); -#102043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102044 = ORIENTED_EDGE('',*,*,#102045,.T.); -#102045 = EDGE_CURVE('',#102023,#101965,#102046,.T.); -#102046 = SURFACE_CURVE('',#102047,(#102051,#102058),.PCURVE_S1.); -#102047 = LINE('',#102048,#102049); -#102048 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#102049 = VECTOR('',#102050,1.); -#102050 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102051 = PCURVE('',#101975,#102052); -#102052 = DEFINITIONAL_REPRESENTATION('',(#102053),#102057); -#102053 = LINE('',#102054,#102055); -#102054 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102055 = VECTOR('',#102056,1.); -#102056 = DIRECTION('',(-1.,0.E+000)); -#102057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102058 = PCURVE('',#102059,#102064); -#102059 = CYLINDRICAL_SURFACE('',#102060,0.308574064194); -#102060 = AXIS2_PLACEMENT_3D('',#102061,#102062,#102063); -#102061 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#102062 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102063 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102064 = DEFINITIONAL_REPRESENTATION('',(#102065),#102068); -#102065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102066,#102067), +#104171 = CARTESIAN_POINT('',(3.162095483347,-5.15)); +#104172 = CARTESIAN_POINT('',(3.162095483347,-5.35)); +#104173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104174 = PCURVE('',#91232,#104175); +#104175 = DEFINITIONAL_REPRESENTATION('',(#104176),#104180); +#104176 = LINE('',#104177,#104178); +#104177 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#104178 = VECTOR('',#104179,1.); +#104179 = DIRECTION('',(0.E+000,-1.)); +#104180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104181 = ADVANCED_FACE('',(#104182),#91150,.F.); +#104182 = FACE_BOUND('',#104183,.T.); +#104183 = EDGE_LOOP('',(#104184,#104205,#104206,#104207,#104208,#104209, + #104230,#104231,#104232,#104233,#104234,#104255)); +#104184 = ORIENTED_EDGE('',*,*,#104185,.F.); +#104185 = EDGE_CURVE('',#104136,#91135,#104186,.T.); +#104186 = SURFACE_CURVE('',#104187,(#104191,#104198),.PCURVE_S1.); +#104187 = LINE('',#104188,#104189); +#104188 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.75)); +#104189 = VECTOR('',#104190,1.); +#104190 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#104191 = PCURVE('',#91150,#104192); +#104192 = DEFINITIONAL_REPRESENTATION('',(#104193),#104197); +#104193 = LINE('',#104194,#104195); +#104194 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#104195 = VECTOR('',#104196,1.); +#104196 = DIRECTION('',(3.563627120235E-016,1.)); +#104197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104198 = PCURVE('',#91232,#104199); +#104199 = DEFINITIONAL_REPRESENTATION('',(#104200),#104204); +#104200 = LINE('',#104201,#104202); +#104201 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104202 = VECTOR('',#104203,1.); +#104203 = DIRECTION('',(1.,0.E+000)); +#104204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104205 = ORIENTED_EDGE('',*,*,#104135,.T.); +#104206 = ORIENTED_EDGE('',*,*,#104013,.T.); +#104207 = ORIENTED_EDGE('',*,*,#103784,.T.); +#104208 = ORIENTED_EDGE('',*,*,#103574,.T.); +#104209 = ORIENTED_EDGE('',*,*,#104210,.T.); +#104210 = EDGE_CURVE('',#103547,#103628,#104211,.T.); +#104211 = SURFACE_CURVE('',#104212,(#104216,#104223),.PCURVE_S1.); +#104212 = LINE('',#104213,#104214); +#104213 = CARTESIAN_POINT('',(4.85,-1.,1.159810404338E-002)); +#104214 = VECTOR('',#104215,1.); +#104215 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#104216 = PCURVE('',#91150,#104217); +#104217 = DEFINITIONAL_REPRESENTATION('',(#104218),#104222); +#104218 = LINE('',#104219,#104220); +#104219 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#104220 = VECTOR('',#104221,1.); +#104221 = DIRECTION('',(-1.,2.101748079665E-016)); +#104222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104223 = PCURVE('',#103562,#104224); +#104224 = DEFINITIONAL_REPRESENTATION('',(#104225),#104229); +#104225 = LINE('',#104226,#104227); +#104226 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#104227 = VECTOR('',#104228,1.); +#104228 = DIRECTION('',(1.,0.E+000)); +#104229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104230 = ORIENTED_EDGE('',*,*,#103625,.F.); +#104231 = ORIENTED_EDGE('',*,*,#103863,.F.); +#104232 = ORIENTED_EDGE('',*,*,#103916,.F.); +#104233 = ORIENTED_EDGE('',*,*,#104037,.F.); +#104234 = ORIENTED_EDGE('',*,*,#104235,.T.); +#104235 = EDGE_CURVE('',#104038,#91133,#104236,.T.); +#104236 = SURFACE_CURVE('',#104237,(#104241,#104248),.PCURVE_S1.); +#104237 = LINE('',#104238,#104239); +#104238 = CARTESIAN_POINT('',(4.85,-0.527847992439,0.65)); +#104239 = VECTOR('',#104240,1.); +#104240 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#104241 = PCURVE('',#91150,#104242); +#104242 = DEFINITIONAL_REPRESENTATION('',(#104243),#104247); +#104243 = LINE('',#104244,#104245); +#104244 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104245 = VECTOR('',#104246,1.); +#104246 = DIRECTION('',(3.563627120235E-016,1.)); +#104247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104248 = PCURVE('',#91178,#104249); +#104249 = DEFINITIONAL_REPRESENTATION('',(#104250),#104254); +#104250 = LINE('',#104251,#104252); +#104251 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104252 = VECTOR('',#104253,1.); +#104253 = DIRECTION('',(-1.,0.E+000)); +#104254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104255 = ORIENTED_EDGE('',*,*,#91132,.T.); +#104256 = ADVANCED_FACE('',(#104257),#91232,.F.); +#104257 = FACE_BOUND('',#104258,.T.); +#104258 = EDGE_LOOP('',(#104259,#104260,#104261,#104262)); +#104259 = ORIENTED_EDGE('',*,*,#104162,.F.); +#104260 = ORIENTED_EDGE('',*,*,#104185,.T.); +#104261 = ORIENTED_EDGE('',*,*,#91218,.T.); +#104262 = ORIENTED_EDGE('',*,*,#104263,.F.); +#104263 = EDGE_CURVE('',#104112,#91191,#104264,.T.); +#104264 = SURFACE_CURVE('',#104265,(#104269,#104276),.PCURVE_S1.); +#104265 = LINE('',#104266,#104267); +#104266 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.75)); +#104267 = VECTOR('',#104268,1.); +#104268 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#104269 = PCURVE('',#91232,#104270); +#104270 = DEFINITIONAL_REPRESENTATION('',(#104271),#104275); +#104271 = LINE('',#104272,#104273); +#104272 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#104273 = VECTOR('',#104274,1.); +#104274 = DIRECTION('',(1.,0.E+000)); +#104275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104276 = PCURVE('',#91206,#104277); +#104277 = DEFINITIONAL_REPRESENTATION('',(#104278),#104282); +#104278 = LINE('',#104279,#104280); +#104279 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#104280 = VECTOR('',#104281,1.); +#104281 = DIRECTION('',(-3.563627120235E-016,1.)); +#104282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104283 = ADVANCED_FACE('',(#104284),#91206,.F.); +#104284 = FACE_BOUND('',#104285,.T.); +#104285 = EDGE_LOOP('',(#104286,#104307,#104308,#104309,#104310,#104311, + #104332,#104333,#104334,#104335,#104336,#104337)); +#104286 = ORIENTED_EDGE('',*,*,#104287,.F.); +#104287 = EDGE_CURVE('',#104065,#91163,#104288,.T.); +#104288 = SURFACE_CURVE('',#104289,(#104293,#104300),.PCURVE_S1.); +#104289 = LINE('',#104290,#104291); +#104290 = CARTESIAN_POINT('',(4.65,-0.527847992439,0.65)); +#104291 = VECTOR('',#104292,1.); +#104292 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#104293 = PCURVE('',#91206,#104294); +#104294 = DEFINITIONAL_REPRESENTATION('',(#104295),#104299); +#104295 = LINE('',#104296,#104297); +#104296 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104297 = VECTOR('',#104298,1.); +#104298 = DIRECTION('',(-3.563627120235E-016,1.)); +#104299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104300 = PCURVE('',#91178,#104301); +#104301 = DEFINITIONAL_REPRESENTATION('',(#104302),#104306); +#104302 = LINE('',#104303,#104304); +#104303 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#104304 = VECTOR('',#104305,1.); +#104305 = DIRECTION('',(-1.,0.E+000)); +#104306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104307 = ORIENTED_EDGE('',*,*,#104086,.T.); +#104308 = ORIENTED_EDGE('',*,*,#103938,.T.); +#104309 = ORIENTED_EDGE('',*,*,#103809,.T.); +#104310 = ORIENTED_EDGE('',*,*,#103678,.T.); +#104311 = ORIENTED_EDGE('',*,*,#104312,.T.); +#104312 = EDGE_CURVE('',#103656,#103519,#104313,.T.); +#104313 = SURFACE_CURVE('',#104314,(#104318,#104325),.PCURVE_S1.); +#104314 = LINE('',#104315,#104316); +#104315 = CARTESIAN_POINT('',(4.65,-1.,1.159810404338E-002)); +#104316 = VECTOR('',#104317,1.); +#104317 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#104318 = PCURVE('',#91206,#104319); +#104319 = DEFINITIONAL_REPRESENTATION('',(#104320),#104324); +#104320 = LINE('',#104321,#104322); +#104321 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#104322 = VECTOR('',#104323,1.); +#104323 = DIRECTION('',(-1.,-2.101748079665E-016)); +#104324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104325 = PCURVE('',#103562,#104326); +#104326 = DEFINITIONAL_REPRESENTATION('',(#104327),#104331); +#104327 = LINE('',#104328,#104329); +#104328 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#104329 = VECTOR('',#104330,1.); +#104330 = DIRECTION('',(-1.,0.E+000)); +#104331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104332 = ORIENTED_EDGE('',*,*,#103516,.F.); +#104333 = ORIENTED_EDGE('',*,*,#103730,.F.); +#104334 = ORIENTED_EDGE('',*,*,#103991,.F.); +#104335 = ORIENTED_EDGE('',*,*,#104111,.F.); +#104336 = ORIENTED_EDGE('',*,*,#104263,.T.); +#104337 = ORIENTED_EDGE('',*,*,#91190,.T.); +#104338 = ADVANCED_FACE('',(#104339),#91178,.F.); +#104339 = FACE_BOUND('',#104340,.T.); +#104340 = EDGE_LOOP('',(#104341,#104342,#104343,#104344)); +#104341 = ORIENTED_EDGE('',*,*,#104064,.F.); +#104342 = ORIENTED_EDGE('',*,*,#104287,.T.); +#104343 = ORIENTED_EDGE('',*,*,#91162,.T.); +#104344 = ORIENTED_EDGE('',*,*,#104235,.F.); +#104345 = ADVANCED_FACE('',(#104346),#103562,.T.); +#104346 = FACE_BOUND('',#104347,.T.); +#104347 = EDGE_LOOP('',(#104348,#104349,#104350,#104351)); +#104348 = ORIENTED_EDGE('',*,*,#104312,.F.); +#104349 = ORIENTED_EDGE('',*,*,#103655,.F.); +#104350 = ORIENTED_EDGE('',*,*,#104210,.F.); +#104351 = ORIENTED_EDGE('',*,*,#103546,.F.); +#104352 = ADVANCED_FACE('',(#104353),#104367,.T.); +#104353 = FACE_BOUND('',#104354,.T.); +#104354 = EDGE_LOOP('',(#104355,#104385,#104413,#104436)); +#104355 = ORIENTED_EDGE('',*,*,#104356,.T.); +#104356 = EDGE_CURVE('',#104357,#104359,#104361,.T.); +#104357 = VERTEX_POINT('',#104358); +#104358 = CARTESIAN_POINT('',(5.85,-0.74341632541,-0.308197125857)); +#104359 = VERTEX_POINT('',#104360); +#104360 = CARTESIAN_POINT('',(5.85,-1.,-0.308197125857)); +#104361 = SURFACE_CURVE('',#104362,(#104366,#104378),.PCURVE_S1.); +#104362 = LINE('',#104363,#104364); +#104363 = CARTESIAN_POINT('',(5.85,-0.74341632541,-0.308197125857)); +#104364 = VECTOR('',#104365,1.); +#104365 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#104366 = PCURVE('',#104367,#104372); +#104367 = PLANE('',#104368); +#104368 = AXIS2_PLACEMENT_3D('',#104369,#104370,#104371); +#104369 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#104370 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104371 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104372 = DEFINITIONAL_REPRESENTATION('',(#104373),#104377); +#104373 = LINE('',#104374,#104375); +#104374 = CARTESIAN_POINT('',(4.15,0.E+000)); +#104375 = VECTOR('',#104376,1.); +#104376 = DIRECTION('',(0.E+000,-1.)); +#104377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104378 = PCURVE('',#92341,#104379); +#104379 = DEFINITIONAL_REPRESENTATION('',(#104380),#104384); +#104380 = LINE('',#104381,#104382); +#104381 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#104382 = VECTOR('',#104383,1.); +#104383 = DIRECTION('',(0.E+000,-1.)); +#104384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104385 = ORIENTED_EDGE('',*,*,#104386,.T.); +#104386 = EDGE_CURVE('',#104359,#104387,#104389,.T.); +#104387 = VERTEX_POINT('',#104388); +#104388 = CARTESIAN_POINT('',(5.65,-1.,-0.308197125857)); +#104389 = SURFACE_CURVE('',#104390,(#104394,#104401),.PCURVE_S1.); +#104390 = LINE('',#104391,#104392); +#104391 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#104392 = VECTOR('',#104393,1.); +#104393 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104394 = PCURVE('',#104367,#104395); +#104395 = DEFINITIONAL_REPRESENTATION('',(#104396),#104400); +#104396 = LINE('',#104397,#104398); +#104397 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#104398 = VECTOR('',#104399,1.); +#104399 = DIRECTION('',(1.,0.E+000)); +#104400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104401 = PCURVE('',#104402,#104407); +#104402 = PLANE('',#104403); +#104403 = AXIS2_PLACEMENT_3D('',#104404,#104405,#104406); +#104404 = CARTESIAN_POINT('',(5.75,-1.,-0.258196742327)); +#104405 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#104406 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#104407 = DEFINITIONAL_REPRESENTATION('',(#104408),#104412); +#104408 = LINE('',#104409,#104410); +#104409 = CARTESIAN_POINT('',(5.000038352949E-002,4.25)); +#104410 = VECTOR('',#104411,1.); +#104411 = DIRECTION('',(0.E+000,-1.)); +#104412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104413 = ORIENTED_EDGE('',*,*,#104414,.F.); +#104414 = EDGE_CURVE('',#104415,#104387,#104417,.T.); +#104415 = VERTEX_POINT('',#104416); +#104416 = CARTESIAN_POINT('',(5.65,-0.74341632541,-0.308197125857)); +#104417 = SURFACE_CURVE('',#104418,(#104422,#104429),.PCURVE_S1.); +#104418 = LINE('',#104419,#104420); +#104419 = CARTESIAN_POINT('',(5.65,-0.74341632541,-0.308197125857)); +#104420 = VECTOR('',#104421,1.); +#104421 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#104422 = PCURVE('',#104367,#104423); +#104423 = DEFINITIONAL_REPRESENTATION('',(#104424),#104428); +#104424 = LINE('',#104425,#104426); +#104425 = CARTESIAN_POINT('',(4.35,0.E+000)); +#104426 = VECTOR('',#104427,1.); +#104427 = DIRECTION('',(0.E+000,-1.)); +#104428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104429 = PCURVE('',#92285,#104430); +#104430 = DEFINITIONAL_REPRESENTATION('',(#104431),#104435); +#104431 = LINE('',#104432,#104433); +#104432 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#104433 = VECTOR('',#104434,1.); +#104434 = DIRECTION('',(0.E+000,-1.)); +#104435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104436 = ORIENTED_EDGE('',*,*,#104437,.T.); +#104437 = EDGE_CURVE('',#104415,#104357,#104438,.T.); +#104438 = SURFACE_CURVE('',#104439,(#104443,#104450),.PCURVE_S1.); +#104439 = LINE('',#104440,#104441); +#104440 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#104441 = VECTOR('',#104442,1.); +#104442 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104443 = PCURVE('',#104367,#104444); +#104444 = DEFINITIONAL_REPRESENTATION('',(#104445),#104449); +#104445 = LINE('',#104446,#104447); +#104446 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104447 = VECTOR('',#104448,1.); +#104448 = DIRECTION('',(-1.,0.E+000)); +#104449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104450 = PCURVE('',#104451,#104456); +#104451 = CYLINDRICAL_SURFACE('',#104452,0.308574064194); +#104452 = AXIS2_PLACEMENT_3D('',#104453,#104454,#104455); +#104453 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#104454 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104455 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104456 = DEFINITIONAL_REPRESENTATION('',(#104457),#104460); +#104457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104458,#104459), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#102066 = CARTESIAN_POINT('',(3.191025391152,4.35)); -#102067 = CARTESIAN_POINT('',(3.191025391152,4.15)); -#102068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102069 = ADVANCED_FACE('',(#102070),#102084,.T.); -#102070 = FACE_BOUND('',#102071,.T.); -#102071 = EDGE_LOOP('',(#102072,#102102,#102125,#102148)); -#102072 = ORIENTED_EDGE('',*,*,#102073,.T.); -#102073 = EDGE_CURVE('',#102074,#102076,#102078,.T.); -#102074 = VERTEX_POINT('',#102075); -#102075 = CARTESIAN_POINT('',(5.65,-0.740726081328,-0.208196358798)); -#102076 = VERTEX_POINT('',#102077); -#102077 = CARTESIAN_POINT('',(5.65,-1.,-0.208196358798)); -#102078 = SURFACE_CURVE('',#102079,(#102083,#102095),.PCURVE_S1.); -#102079 = LINE('',#102080,#102081); -#102080 = CARTESIAN_POINT('',(5.65,-0.740726081328,-0.208196358798)); -#102081 = VECTOR('',#102082,1.); -#102082 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102083 = PCURVE('',#102084,#102089); -#102084 = PLANE('',#102085); -#102085 = AXIS2_PLACEMENT_3D('',#102086,#102087,#102088); -#102086 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#102087 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102088 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102089 = DEFINITIONAL_REPRESENTATION('',(#102090),#102094); -#102090 = LINE('',#102091,#102092); -#102091 = CARTESIAN_POINT('',(-4.35,0.E+000)); -#102092 = VECTOR('',#102093,1.); -#102093 = DIRECTION('',(0.E+000,-1.)); -#102094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102095 = PCURVE('',#89893,#102096); -#102096 = DEFINITIONAL_REPRESENTATION('',(#102097),#102101); -#102097 = LINE('',#102098,#102099); -#102098 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#102099 = VECTOR('',#102100,1.); -#102100 = DIRECTION('',(0.E+000,-1.)); -#102101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102102 = ORIENTED_EDGE('',*,*,#102103,.T.); -#102103 = EDGE_CURVE('',#102076,#102104,#102106,.T.); -#102104 = VERTEX_POINT('',#102105); -#102105 = CARTESIAN_POINT('',(5.85,-1.,-0.208196358798)); -#102106 = SURFACE_CURVE('',#102107,(#102111,#102118),.PCURVE_S1.); -#102107 = LINE('',#102108,#102109); -#102108 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#102109 = VECTOR('',#102110,1.); -#102110 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102111 = PCURVE('',#102084,#102112); -#102112 = DEFINITIONAL_REPRESENTATION('',(#102113),#102117); -#102113 = LINE('',#102114,#102115); -#102114 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#102115 = VECTOR('',#102116,1.); -#102116 = DIRECTION('',(1.,0.E+000)); -#102117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102118 = PCURVE('',#102010,#102119); -#102119 = DEFINITIONAL_REPRESENTATION('',(#102120),#102124); -#102120 = LINE('',#102121,#102122); -#102121 = CARTESIAN_POINT('',(-5.000038352949E-002,4.25)); -#102122 = VECTOR('',#102123,1.); -#102123 = DIRECTION('',(0.E+000,1.)); -#102124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102125 = ORIENTED_EDGE('',*,*,#102126,.F.); -#102126 = EDGE_CURVE('',#102127,#102104,#102129,.T.); -#102127 = VERTEX_POINT('',#102128); -#102128 = CARTESIAN_POINT('',(5.85,-0.740726081328,-0.208196358798)); -#102129 = SURFACE_CURVE('',#102130,(#102134,#102141),.PCURVE_S1.); -#102130 = LINE('',#102131,#102132); -#102131 = CARTESIAN_POINT('',(5.85,-0.740726081328,-0.208196358798)); -#102132 = VECTOR('',#102133,1.); -#102133 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102134 = PCURVE('',#102084,#102135); -#102135 = DEFINITIONAL_REPRESENTATION('',(#102136),#102140); -#102136 = LINE('',#102137,#102138); -#102137 = CARTESIAN_POINT('',(-4.15,0.E+000)); -#102138 = VECTOR('',#102139,1.); -#102139 = DIRECTION('',(0.E+000,-1.)); -#102140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102141 = PCURVE('',#89949,#102142); -#102142 = DEFINITIONAL_REPRESENTATION('',(#102143),#102147); -#102143 = LINE('',#102144,#102145); -#102144 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#102145 = VECTOR('',#102146,1.); -#102146 = DIRECTION('',(0.E+000,-1.)); -#102147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102148 = ORIENTED_EDGE('',*,*,#102149,.T.); -#102149 = EDGE_CURVE('',#102127,#102074,#102150,.T.); -#102150 = SURFACE_CURVE('',#102151,(#102155,#102162),.PCURVE_S1.); -#102151 = LINE('',#102152,#102153); -#102152 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#102153 = VECTOR('',#102154,1.); -#102154 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102155 = PCURVE('',#102084,#102156); -#102156 = DEFINITIONAL_REPRESENTATION('',(#102157),#102161); -#102157 = LINE('',#102158,#102159); -#102158 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102159 = VECTOR('',#102160,1.); -#102160 = DIRECTION('',(-1.,0.E+000)); -#102161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102162 = PCURVE('',#102163,#102168); -#102163 = CYLINDRICAL_SURFACE('',#102164,0.208574704164); -#102164 = AXIS2_PLACEMENT_3D('',#102165,#102166,#102167); -#102165 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#102166 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102167 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102168 = DEFINITIONAL_REPRESENTATION('',(#102169),#102172); -#102169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102170,#102171), +#104458 = CARTESIAN_POINT('',(3.191025391152,4.35)); +#104459 = CARTESIAN_POINT('',(3.191025391152,4.15)); +#104460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104461 = ADVANCED_FACE('',(#104462),#104476,.T.); +#104462 = FACE_BOUND('',#104463,.T.); +#104463 = EDGE_LOOP('',(#104464,#104494,#104517,#104540)); +#104464 = ORIENTED_EDGE('',*,*,#104465,.T.); +#104465 = EDGE_CURVE('',#104466,#104468,#104470,.T.); +#104466 = VERTEX_POINT('',#104467); +#104467 = CARTESIAN_POINT('',(5.65,-0.740726081328,-0.208196358798)); +#104468 = VERTEX_POINT('',#104469); +#104469 = CARTESIAN_POINT('',(5.65,-1.,-0.208196358798)); +#104470 = SURFACE_CURVE('',#104471,(#104475,#104487),.PCURVE_S1.); +#104471 = LINE('',#104472,#104473); +#104472 = CARTESIAN_POINT('',(5.65,-0.740726081328,-0.208196358798)); +#104473 = VECTOR('',#104474,1.); +#104474 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#104475 = PCURVE('',#104476,#104481); +#104476 = PLANE('',#104477); +#104477 = AXIS2_PLACEMENT_3D('',#104478,#104479,#104480); +#104478 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#104479 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104480 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104481 = DEFINITIONAL_REPRESENTATION('',(#104482),#104486); +#104482 = LINE('',#104483,#104484); +#104483 = CARTESIAN_POINT('',(-4.35,0.E+000)); +#104484 = VECTOR('',#104485,1.); +#104485 = DIRECTION('',(0.E+000,-1.)); +#104486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104487 = PCURVE('',#92285,#104488); +#104488 = DEFINITIONAL_REPRESENTATION('',(#104489),#104493); +#104489 = LINE('',#104490,#104491); +#104490 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#104491 = VECTOR('',#104492,1.); +#104492 = DIRECTION('',(0.E+000,-1.)); +#104493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104494 = ORIENTED_EDGE('',*,*,#104495,.T.); +#104495 = EDGE_CURVE('',#104468,#104496,#104498,.T.); +#104496 = VERTEX_POINT('',#104497); +#104497 = CARTESIAN_POINT('',(5.85,-1.,-0.208196358798)); +#104498 = SURFACE_CURVE('',#104499,(#104503,#104510),.PCURVE_S1.); +#104499 = LINE('',#104500,#104501); +#104500 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#104501 = VECTOR('',#104502,1.); +#104502 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104503 = PCURVE('',#104476,#104504); +#104504 = DEFINITIONAL_REPRESENTATION('',(#104505),#104509); +#104505 = LINE('',#104506,#104507); +#104506 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#104507 = VECTOR('',#104508,1.); +#104508 = DIRECTION('',(1.,0.E+000)); +#104509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104510 = PCURVE('',#104402,#104511); +#104511 = DEFINITIONAL_REPRESENTATION('',(#104512),#104516); +#104512 = LINE('',#104513,#104514); +#104513 = CARTESIAN_POINT('',(-5.000038352949E-002,4.25)); +#104514 = VECTOR('',#104515,1.); +#104515 = DIRECTION('',(0.E+000,1.)); +#104516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104517 = ORIENTED_EDGE('',*,*,#104518,.F.); +#104518 = EDGE_CURVE('',#104519,#104496,#104521,.T.); +#104519 = VERTEX_POINT('',#104520); +#104520 = CARTESIAN_POINT('',(5.85,-0.740726081328,-0.208196358798)); +#104521 = SURFACE_CURVE('',#104522,(#104526,#104533),.PCURVE_S1.); +#104522 = LINE('',#104523,#104524); +#104523 = CARTESIAN_POINT('',(5.85,-0.740726081328,-0.208196358798)); +#104524 = VECTOR('',#104525,1.); +#104525 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#104526 = PCURVE('',#104476,#104527); +#104527 = DEFINITIONAL_REPRESENTATION('',(#104528),#104532); +#104528 = LINE('',#104529,#104530); +#104529 = CARTESIAN_POINT('',(-4.15,0.E+000)); +#104530 = VECTOR('',#104531,1.); +#104531 = DIRECTION('',(0.E+000,-1.)); +#104532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104533 = PCURVE('',#92341,#104534); +#104534 = DEFINITIONAL_REPRESENTATION('',(#104535),#104539); +#104535 = LINE('',#104536,#104537); +#104536 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#104537 = VECTOR('',#104538,1.); +#104538 = DIRECTION('',(0.E+000,-1.)); +#104539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104540 = ORIENTED_EDGE('',*,*,#104541,.T.); +#104541 = EDGE_CURVE('',#104519,#104466,#104542,.T.); +#104542 = SURFACE_CURVE('',#104543,(#104547,#104554),.PCURVE_S1.); +#104543 = LINE('',#104544,#104545); +#104544 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#104545 = VECTOR('',#104546,1.); +#104546 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104547 = PCURVE('',#104476,#104548); +#104548 = DEFINITIONAL_REPRESENTATION('',(#104549),#104553); +#104549 = LINE('',#104550,#104551); +#104550 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104551 = VECTOR('',#104552,1.); +#104552 = DIRECTION('',(-1.,0.E+000)); +#104553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104554 = PCURVE('',#104555,#104560); +#104555 = CYLINDRICAL_SURFACE('',#104556,0.208574704164); +#104556 = AXIS2_PLACEMENT_3D('',#104557,#104558,#104559); +#104557 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#104558 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104559 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104560 = DEFINITIONAL_REPRESENTATION('',(#104561),#104564); +#104561 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104562,#104563), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#102170 = CARTESIAN_POINT('',(3.201833915432,4.15)); -#102171 = CARTESIAN_POINT('',(3.201833915432,4.35)); -#102172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102173 = ADVANCED_FACE('',(#102174),#102059,.T.); -#102174 = FACE_BOUND('',#102175,.T.); -#102175 = EDGE_LOOP('',(#102176,#102177,#102204,#102231)); -#102176 = ORIENTED_EDGE('',*,*,#102045,.F.); -#102177 = ORIENTED_EDGE('',*,*,#102178,.F.); -#102178 = EDGE_CURVE('',#102179,#102023,#102181,.T.); -#102179 = VERTEX_POINT('',#102180); -#102180 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.E+000)); -#102181 = SURFACE_CURVE('',#102182,(#102187,#102193),.PCURVE_S1.); -#102182 = CIRCLE('',#102183,0.308574064194); -#102183 = AXIS2_PLACEMENT_3D('',#102184,#102185,#102186); -#102184 = CARTESIAN_POINT('',(5.65,-0.728168876214,2.640924866458E-017) - ); -#102185 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102186 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102187 = PCURVE('',#102059,#102188); -#102188 = DEFINITIONAL_REPRESENTATION('',(#102189),#102192); -#102189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102190,#102191), +#104562 = CARTESIAN_POINT('',(3.201833915432,4.15)); +#104563 = CARTESIAN_POINT('',(3.201833915432,4.35)); +#104564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104565 = ADVANCED_FACE('',(#104566),#104451,.T.); +#104566 = FACE_BOUND('',#104567,.T.); +#104567 = EDGE_LOOP('',(#104568,#104569,#104596,#104623)); +#104568 = ORIENTED_EDGE('',*,*,#104437,.F.); +#104569 = ORIENTED_EDGE('',*,*,#104570,.F.); +#104570 = EDGE_CURVE('',#104571,#104415,#104573,.T.); +#104571 = VERTEX_POINT('',#104572); +#104572 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.E+000)); +#104573 = SURFACE_CURVE('',#104574,(#104579,#104585),.PCURVE_S1.); +#104574 = CIRCLE('',#104575,0.308574064194); +#104575 = AXIS2_PLACEMENT_3D('',#104576,#104577,#104578); +#104576 = CARTESIAN_POINT('',(5.65,-0.728168876214,2.640924866458E-017) + ); +#104577 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104578 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104579 = PCURVE('',#104451,#104580); +#104580 = DEFINITIONAL_REPRESENTATION('',(#104581),#104584); +#104581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104582,#104583), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#102190 = CARTESIAN_POINT('',(1.570796326795,4.35)); -#102191 = CARTESIAN_POINT('',(3.191025391152,4.35)); -#102192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104582 = CARTESIAN_POINT('',(1.570796326795,4.35)); +#104583 = CARTESIAN_POINT('',(3.191025391152,4.35)); +#104584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102193 = PCURVE('',#89893,#102194); -#102194 = DEFINITIONAL_REPRESENTATION('',(#102195),#102203); -#102195 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102196,#102197,#102198, - #102199,#102200,#102201,#102202),.UNSPECIFIED.,.T.,.F.) +#104585 = PCURVE('',#92285,#104586); +#104586 = DEFINITIONAL_REPRESENTATION('',(#104587),#104595); +#104587 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104588,#104589,#104590, + #104591,#104592,#104593,#104594),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#102196 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#102197 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#102198 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#102199 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#102200 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#102201 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#102202 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#102203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102204 = ORIENTED_EDGE('',*,*,#102205,.F.); -#102205 = EDGE_CURVE('',#102206,#102179,#102208,.T.); -#102206 = VERTEX_POINT('',#102207); -#102207 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.E+000)); -#102208 = SURFACE_CURVE('',#102209,(#102213,#102219),.PCURVE_S1.); -#102209 = LINE('',#102210,#102211); -#102210 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#102211 = VECTOR('',#102212,1.); -#102212 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102213 = PCURVE('',#102059,#102214); -#102214 = DEFINITIONAL_REPRESENTATION('',(#102215),#102218); -#102215 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102216,#102217), +#104588 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#104589 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#104590 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#104591 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#104592 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#104593 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#104594 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#104595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104596 = ORIENTED_EDGE('',*,*,#104597,.F.); +#104597 = EDGE_CURVE('',#104598,#104571,#104600,.T.); +#104598 = VERTEX_POINT('',#104599); +#104599 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.E+000)); +#104600 = SURFACE_CURVE('',#104601,(#104605,#104611),.PCURVE_S1.); +#104601 = LINE('',#104602,#104603); +#104602 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#104603 = VECTOR('',#104604,1.); +#104604 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104605 = PCURVE('',#104451,#104606); +#104606 = DEFINITIONAL_REPRESENTATION('',(#104607),#104610); +#104607 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104608,#104609), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#102216 = CARTESIAN_POINT('',(1.570796326795,4.15)); -#102217 = CARTESIAN_POINT('',(1.570796326795,4.35)); -#102218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102219 = PCURVE('',#102220,#102225); -#102220 = PLANE('',#102221); -#102221 = AXIS2_PLACEMENT_3D('',#102222,#102223,#102224); -#102222 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#102223 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#102224 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#102225 = DEFINITIONAL_REPRESENTATION('',(#102226),#102230); -#102226 = LINE('',#102227,#102228); -#102227 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#102228 = VECTOR('',#102229,1.); -#102229 = DIRECTION('',(0.E+000,-1.)); -#102230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102231 = ORIENTED_EDGE('',*,*,#102232,.T.); -#102232 = EDGE_CURVE('',#102206,#101965,#102233,.T.); -#102233 = SURFACE_CURVE('',#102234,(#102239,#102245),.PCURVE_S1.); -#102234 = CIRCLE('',#102235,0.308574064194); -#102235 = AXIS2_PLACEMENT_3D('',#102236,#102237,#102238); -#102236 = CARTESIAN_POINT('',(5.85,-0.728168876214,2.640924866458E-017) - ); -#102237 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102238 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102239 = PCURVE('',#102059,#102240); -#102240 = DEFINITIONAL_REPRESENTATION('',(#102241),#102244); -#102241 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102242,#102243), +#104608 = CARTESIAN_POINT('',(1.570796326795,4.15)); +#104609 = CARTESIAN_POINT('',(1.570796326795,4.35)); +#104610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104611 = PCURVE('',#104612,#104617); +#104612 = PLANE('',#104613); +#104613 = AXIS2_PLACEMENT_3D('',#104614,#104615,#104616); +#104614 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#104615 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#104616 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104617 = DEFINITIONAL_REPRESENTATION('',(#104618),#104622); +#104618 = LINE('',#104619,#104620); +#104619 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#104620 = VECTOR('',#104621,1.); +#104621 = DIRECTION('',(0.E+000,-1.)); +#104622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104623 = ORIENTED_EDGE('',*,*,#104624,.T.); +#104624 = EDGE_CURVE('',#104598,#104357,#104625,.T.); +#104625 = SURFACE_CURVE('',#104626,(#104631,#104637),.PCURVE_S1.); +#104626 = CIRCLE('',#104627,0.308574064194); +#104627 = AXIS2_PLACEMENT_3D('',#104628,#104629,#104630); +#104628 = CARTESIAN_POINT('',(5.85,-0.728168876214,2.640924866458E-017) + ); +#104629 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104630 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104631 = PCURVE('',#104451,#104632); +#104632 = DEFINITIONAL_REPRESENTATION('',(#104633),#104636); +#104633 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104634,#104635), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#102242 = CARTESIAN_POINT('',(1.570796326795,4.15)); -#102243 = CARTESIAN_POINT('',(3.191025391152,4.15)); -#102244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102245 = PCURVE('',#89949,#102246); -#102246 = DEFINITIONAL_REPRESENTATION('',(#102247),#102251); -#102247 = CIRCLE('',#102248,0.308574064194); -#102248 = AXIS2_PLACEMENT_2D('',#102249,#102250); -#102249 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#102250 = DIRECTION('',(1.,0.E+000)); -#102251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102252 = ADVANCED_FACE('',(#102253),#102163,.F.); -#102253 = FACE_BOUND('',#102254,.F.); -#102254 = EDGE_LOOP('',(#102255,#102256,#102283,#102310)); -#102255 = ORIENTED_EDGE('',*,*,#102149,.T.); -#102256 = ORIENTED_EDGE('',*,*,#102257,.F.); -#102257 = EDGE_CURVE('',#102258,#102074,#102260,.T.); -#102258 = VERTEX_POINT('',#102259); -#102259 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.E+000)); -#102260 = SURFACE_CURVE('',#102261,(#102266,#102272),.PCURVE_S1.); -#102261 = CIRCLE('',#102262,0.208574704164); -#102262 = AXIS2_PLACEMENT_3D('',#102263,#102264,#102265); -#102263 = CARTESIAN_POINT('',(5.65,-0.728168876214,2.640924866458E-017) - ); -#102264 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102265 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102266 = PCURVE('',#102163,#102267); -#102267 = DEFINITIONAL_REPRESENTATION('',(#102268),#102271); -#102268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102269,#102270), +#104634 = CARTESIAN_POINT('',(1.570796326795,4.15)); +#104635 = CARTESIAN_POINT('',(3.191025391152,4.15)); +#104636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104637 = PCURVE('',#92341,#104638); +#104638 = DEFINITIONAL_REPRESENTATION('',(#104639),#104643); +#104639 = CIRCLE('',#104640,0.308574064194); +#104640 = AXIS2_PLACEMENT_2D('',#104641,#104642); +#104641 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#104642 = DIRECTION('',(1.,0.E+000)); +#104643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104644 = ADVANCED_FACE('',(#104645),#104555,.F.); +#104645 = FACE_BOUND('',#104646,.F.); +#104646 = EDGE_LOOP('',(#104647,#104648,#104675,#104702)); +#104647 = ORIENTED_EDGE('',*,*,#104541,.T.); +#104648 = ORIENTED_EDGE('',*,*,#104649,.F.); +#104649 = EDGE_CURVE('',#104650,#104466,#104652,.T.); +#104650 = VERTEX_POINT('',#104651); +#104651 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.E+000)); +#104652 = SURFACE_CURVE('',#104653,(#104658,#104664),.PCURVE_S1.); +#104653 = CIRCLE('',#104654,0.208574704164); +#104654 = AXIS2_PLACEMENT_3D('',#104655,#104656,#104657); +#104655 = CARTESIAN_POINT('',(5.65,-0.728168876214,2.640924866458E-017) + ); +#104656 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104657 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104658 = PCURVE('',#104555,#104659); +#104659 = DEFINITIONAL_REPRESENTATION('',(#104660),#104663); +#104660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104661,#104662), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#102269 = CARTESIAN_POINT('',(1.570796326795,4.35)); -#102270 = CARTESIAN_POINT('',(3.201833915432,4.35)); -#102271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104661 = CARTESIAN_POINT('',(1.570796326795,4.35)); +#104662 = CARTESIAN_POINT('',(3.201833915432,4.35)); +#104663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102272 = PCURVE('',#89893,#102273); -#102273 = DEFINITIONAL_REPRESENTATION('',(#102274),#102282); -#102274 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102275,#102276,#102277, - #102278,#102279,#102280,#102281),.UNSPECIFIED.,.F.,.F.) +#104664 = PCURVE('',#92285,#104665); +#104665 = DEFINITIONAL_REPRESENTATION('',(#104666),#104674); +#104666 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104667,#104668,#104669, + #104670,#104671,#104672,#104673),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#102275 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#102276 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#102277 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#102278 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#102279 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#102280 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#102281 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#102282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102283 = ORIENTED_EDGE('',*,*,#102284,.T.); -#102284 = EDGE_CURVE('',#102258,#102285,#102287,.T.); -#102285 = VERTEX_POINT('',#102286); -#102286 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.E+000)); -#102287 = SURFACE_CURVE('',#102288,(#102292,#102298),.PCURVE_S1.); -#102288 = LINE('',#102289,#102290); -#102289 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#102290 = VECTOR('',#102291,1.); -#102291 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102292 = PCURVE('',#102163,#102293); -#102293 = DEFINITIONAL_REPRESENTATION('',(#102294),#102297); -#102294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102295,#102296), +#104667 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#104668 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#104669 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#104670 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#104671 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#104672 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#104673 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#104674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104675 = ORIENTED_EDGE('',*,*,#104676,.T.); +#104676 = EDGE_CURVE('',#104650,#104677,#104679,.T.); +#104677 = VERTEX_POINT('',#104678); +#104678 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.E+000)); +#104679 = SURFACE_CURVE('',#104680,(#104684,#104690),.PCURVE_S1.); +#104680 = LINE('',#104681,#104682); +#104681 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#104682 = VECTOR('',#104683,1.); +#104683 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104684 = PCURVE('',#104555,#104685); +#104685 = DEFINITIONAL_REPRESENTATION('',(#104686),#104689); +#104686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104687,#104688), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#102295 = CARTESIAN_POINT('',(1.570796326795,4.35)); -#102296 = CARTESIAN_POINT('',(1.570796326795,4.15)); -#102297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102298 = PCURVE('',#102299,#102304); -#102299 = PLANE('',#102300); -#102300 = AXIS2_PLACEMENT_3D('',#102301,#102302,#102303); -#102301 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#102302 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#102303 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#102304 = DEFINITIONAL_REPRESENTATION('',(#102305),#102309); -#102305 = LINE('',#102306,#102307); -#102306 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#102307 = VECTOR('',#102308,1.); -#102308 = DIRECTION('',(0.E+000,1.)); -#102309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102310 = ORIENTED_EDGE('',*,*,#102311,.T.); -#102311 = EDGE_CURVE('',#102285,#102127,#102312,.T.); -#102312 = SURFACE_CURVE('',#102313,(#102318,#102324),.PCURVE_S1.); -#102313 = CIRCLE('',#102314,0.208574704164); -#102314 = AXIS2_PLACEMENT_3D('',#102315,#102316,#102317); -#102315 = CARTESIAN_POINT('',(5.85,-0.728168876214,2.640924866458E-017) - ); -#102316 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102317 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102318 = PCURVE('',#102163,#102319); -#102319 = DEFINITIONAL_REPRESENTATION('',(#102320),#102323); -#102320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102321,#102322), +#104687 = CARTESIAN_POINT('',(1.570796326795,4.35)); +#104688 = CARTESIAN_POINT('',(1.570796326795,4.15)); +#104689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104690 = PCURVE('',#104691,#104696); +#104691 = PLANE('',#104692); +#104692 = AXIS2_PLACEMENT_3D('',#104693,#104694,#104695); +#104693 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#104694 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#104695 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#104696 = DEFINITIONAL_REPRESENTATION('',(#104697),#104701); +#104697 = LINE('',#104698,#104699); +#104698 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#104699 = VECTOR('',#104700,1.); +#104700 = DIRECTION('',(0.E+000,1.)); +#104701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104702 = ORIENTED_EDGE('',*,*,#104703,.T.); +#104703 = EDGE_CURVE('',#104677,#104519,#104704,.T.); +#104704 = SURFACE_CURVE('',#104705,(#104710,#104716),.PCURVE_S1.); +#104705 = CIRCLE('',#104706,0.208574704164); +#104706 = AXIS2_PLACEMENT_3D('',#104707,#104708,#104709); +#104707 = CARTESIAN_POINT('',(5.85,-0.728168876214,2.640924866458E-017) + ); +#104708 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104709 = DIRECTION('',(0.E+000,0.E+000,1.)); +#104710 = PCURVE('',#104555,#104711); +#104711 = DEFINITIONAL_REPRESENTATION('',(#104712),#104715); +#104712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104713,#104714), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#102321 = CARTESIAN_POINT('',(1.570796326795,4.15)); -#102322 = CARTESIAN_POINT('',(3.201833915432,4.15)); -#102323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104713 = CARTESIAN_POINT('',(1.570796326795,4.15)); +#104714 = CARTESIAN_POINT('',(3.201833915432,4.15)); +#104715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104716 = PCURVE('',#92341,#104717); +#104717 = DEFINITIONAL_REPRESENTATION('',(#104718),#104722); +#104718 = CIRCLE('',#104719,0.208574704164); +#104719 = AXIS2_PLACEMENT_2D('',#104720,#104721); +#104720 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#104721 = DIRECTION('',(1.,0.E+000)); +#104722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104723 = ADVANCED_FACE('',(#104724),#104691,.F.); +#104724 = FACE_BOUND('',#104725,.T.); +#104725 = EDGE_LOOP('',(#104726,#104755,#104776,#104777)); +#104726 = ORIENTED_EDGE('',*,*,#104727,.F.); +#104727 = EDGE_CURVE('',#104728,#104730,#104732,.T.); +#104728 = VERTEX_POINT('',#104729); +#104729 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.530776333563)); +#104730 = VERTEX_POINT('',#104731); +#104731 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.530776333563)); +#104732 = SURFACE_CURVE('',#104733,(#104737,#104744),.PCURVE_S1.); +#104733 = LINE('',#104734,#104735); +#104734 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#104735 = VECTOR('',#104736,1.); +#104736 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104737 = PCURVE('',#104691,#104738); +#104738 = DEFINITIONAL_REPRESENTATION('',(#104739),#104743); +#104739 = LINE('',#104740,#104741); +#104740 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104741 = VECTOR('',#104742,1.); +#104742 = DIRECTION('',(0.E+000,1.)); +#104743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104744 = PCURVE('',#104745,#104750); +#104745 = CYLINDRICAL_SURFACE('',#104746,0.2192697516); +#104746 = AXIS2_PLACEMENT_3D('',#104747,#104748,#104749); +#104747 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#104748 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104749 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104750 = DEFINITIONAL_REPRESENTATION('',(#104751),#104754); +#104751 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104752,#104753), + .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); +#104752 = CARTESIAN_POINT('',(4.712388980385,-4.35)); +#104753 = CARTESIAN_POINT('',(4.712388980385,-4.15)); +#104754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104755 = ORIENTED_EDGE('',*,*,#104756,.T.); +#104756 = EDGE_CURVE('',#104728,#104650,#104757,.T.); +#104757 = SURFACE_CURVE('',#104758,(#104762,#104769),.PCURVE_S1.); +#104758 = LINE('',#104759,#104760); +#104759 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.530776333563)); +#104760 = VECTOR('',#104761,1.); +#104761 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104762 = PCURVE('',#104691,#104763); +#104763 = DEFINITIONAL_REPRESENTATION('',(#104764),#104768); +#104764 = LINE('',#104765,#104766); +#104765 = CARTESIAN_POINT('',(0.E+000,-4.35)); +#104766 = VECTOR('',#104767,1.); +#104767 = DIRECTION('',(-1.,0.E+000)); +#104768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104769 = PCURVE('',#92285,#104770); +#104770 = DEFINITIONAL_REPRESENTATION('',(#104771),#104775); +#104771 = LINE('',#104772,#104773); +#104772 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#104773 = VECTOR('',#104774,1.); +#104774 = DIRECTION('',(1.,-1.021336205033E-016)); +#104775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104776 = ORIENTED_EDGE('',*,*,#104676,.T.); +#104777 = ORIENTED_EDGE('',*,*,#104778,.F.); +#104778 = EDGE_CURVE('',#104730,#104677,#104779,.T.); +#104779 = SURFACE_CURVE('',#104780,(#104784,#104791),.PCURVE_S1.); +#104780 = LINE('',#104781,#104782); +#104781 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.530776333563)); +#104782 = VECTOR('',#104783,1.); +#104783 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104784 = PCURVE('',#104691,#104785); +#104785 = DEFINITIONAL_REPRESENTATION('',(#104786),#104790); +#104786 = LINE('',#104787,#104788); +#104787 = CARTESIAN_POINT('',(0.E+000,-4.15)); +#104788 = VECTOR('',#104789,1.); +#104789 = DIRECTION('',(-1.,0.E+000)); +#104790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104791 = PCURVE('',#92341,#104792); +#104792 = DEFINITIONAL_REPRESENTATION('',(#104793),#104797); +#104793 = LINE('',#104794,#104795); +#104794 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#104795 = VECTOR('',#104796,1.); +#104796 = DIRECTION('',(-1.,-1.021336205033E-016)); +#104797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104798 = ADVANCED_FACE('',(#104799),#104612,.F.); +#104799 = FACE_BOUND('',#104800,.T.); +#104800 = EDGE_LOOP('',(#104801,#104830,#104851,#104852)); +#104801 = ORIENTED_EDGE('',*,*,#104802,.F.); +#104802 = EDGE_CURVE('',#104803,#104805,#104807,.T.); +#104803 = VERTEX_POINT('',#104804); +#104804 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.530776333563)); +#104805 = VERTEX_POINT('',#104806); +#104806 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.530776333563)); +#104807 = SURFACE_CURVE('',#104808,(#104812,#104819),.PCURVE_S1.); +#104808 = LINE('',#104809,#104810); +#104809 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#104810 = VECTOR('',#104811,1.); +#104811 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104812 = PCURVE('',#104612,#104813); +#104813 = DEFINITIONAL_REPRESENTATION('',(#104814),#104818); +#104814 = LINE('',#104815,#104816); +#104815 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#104816 = VECTOR('',#104817,1.); +#104817 = DIRECTION('',(0.E+000,-1.)); +#104818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104819 = PCURVE('',#104820,#104825); +#104820 = CYLINDRICAL_SURFACE('',#104821,0.119270391569); +#104821 = AXIS2_PLACEMENT_3D('',#104822,#104823,#104824); +#104822 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#104823 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104824 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104825 = DEFINITIONAL_REPRESENTATION('',(#104826),#104829); +#104826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104827,#104828), + .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); +#104827 = CARTESIAN_POINT('',(4.712388980385,-4.15)); +#104828 = CARTESIAN_POINT('',(4.712388980385,-4.35)); +#104829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102324 = PCURVE('',#89949,#102325); -#102325 = DEFINITIONAL_REPRESENTATION('',(#102326),#102330); -#102326 = CIRCLE('',#102327,0.208574704164); -#102327 = AXIS2_PLACEMENT_2D('',#102328,#102329); -#102328 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#102329 = DIRECTION('',(1.,0.E+000)); -#102330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104830 = ORIENTED_EDGE('',*,*,#104831,.T.); +#104831 = EDGE_CURVE('',#104803,#104598,#104832,.T.); +#104832 = SURFACE_CURVE('',#104833,(#104837,#104844),.PCURVE_S1.); +#104833 = LINE('',#104834,#104835); +#104834 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.530776333563)); +#104835 = VECTOR('',#104836,1.); +#104836 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104837 = PCURVE('',#104612,#104838); +#104838 = DEFINITIONAL_REPRESENTATION('',(#104839),#104843); +#104839 = LINE('',#104840,#104841); +#104840 = CARTESIAN_POINT('',(0.E+000,-4.15)); +#104841 = VECTOR('',#104842,1.); +#104842 = DIRECTION('',(1.,0.E+000)); +#104843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102331 = ADVANCED_FACE('',(#102332),#102299,.F.); -#102332 = FACE_BOUND('',#102333,.T.); -#102333 = EDGE_LOOP('',(#102334,#102363,#102384,#102385)); -#102334 = ORIENTED_EDGE('',*,*,#102335,.F.); -#102335 = EDGE_CURVE('',#102336,#102338,#102340,.T.); -#102336 = VERTEX_POINT('',#102337); -#102337 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.530776333563)); -#102338 = VERTEX_POINT('',#102339); -#102339 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.530776333563)); -#102340 = SURFACE_CURVE('',#102341,(#102345,#102352),.PCURVE_S1.); -#102341 = LINE('',#102342,#102343); -#102342 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#102343 = VECTOR('',#102344,1.); -#102344 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102345 = PCURVE('',#102299,#102346); -#102346 = DEFINITIONAL_REPRESENTATION('',(#102347),#102351); -#102347 = LINE('',#102348,#102349); -#102348 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102349 = VECTOR('',#102350,1.); -#102350 = DIRECTION('',(0.E+000,1.)); -#102351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102352 = PCURVE('',#102353,#102358); -#102353 = CYLINDRICAL_SURFACE('',#102354,0.2192697516); -#102354 = AXIS2_PLACEMENT_3D('',#102355,#102356,#102357); -#102355 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#102356 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102357 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102358 = DEFINITIONAL_REPRESENTATION('',(#102359),#102362); -#102359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102360,#102361), - .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#102360 = CARTESIAN_POINT('',(4.712388980385,-4.35)); -#102361 = CARTESIAN_POINT('',(4.712388980385,-4.15)); -#102362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102363 = ORIENTED_EDGE('',*,*,#102364,.T.); -#102364 = EDGE_CURVE('',#102336,#102258,#102365,.T.); -#102365 = SURFACE_CURVE('',#102366,(#102370,#102377),.PCURVE_S1.); -#102366 = LINE('',#102367,#102368); -#102367 = CARTESIAN_POINT('',(5.65,-0.51959417205,0.530776333563)); -#102368 = VECTOR('',#102369,1.); -#102369 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#102370 = PCURVE('',#102299,#102371); -#102371 = DEFINITIONAL_REPRESENTATION('',(#102372),#102376); -#102372 = LINE('',#102373,#102374); -#102373 = CARTESIAN_POINT('',(0.E+000,-4.35)); -#102374 = VECTOR('',#102375,1.); -#102375 = DIRECTION('',(-1.,0.E+000)); -#102376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102377 = PCURVE('',#89893,#102378); -#102378 = DEFINITIONAL_REPRESENTATION('',(#102379),#102383); -#102379 = LINE('',#102380,#102381); -#102380 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#102381 = VECTOR('',#102382,1.); -#102382 = DIRECTION('',(1.,-1.021336205033E-016)); -#102383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102384 = ORIENTED_EDGE('',*,*,#102284,.T.); -#102385 = ORIENTED_EDGE('',*,*,#102386,.F.); -#102386 = EDGE_CURVE('',#102338,#102285,#102387,.T.); -#102387 = SURFACE_CURVE('',#102388,(#102392,#102399),.PCURVE_S1.); -#102388 = LINE('',#102389,#102390); -#102389 = CARTESIAN_POINT('',(5.85,-0.51959417205,0.530776333563)); -#102390 = VECTOR('',#102391,1.); -#102391 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#102392 = PCURVE('',#102299,#102393); -#102393 = DEFINITIONAL_REPRESENTATION('',(#102394),#102398); -#102394 = LINE('',#102395,#102396); -#102395 = CARTESIAN_POINT('',(0.E+000,-4.15)); -#102396 = VECTOR('',#102397,1.); -#102397 = DIRECTION('',(-1.,0.E+000)); -#102398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102399 = PCURVE('',#89949,#102400); -#102400 = DEFINITIONAL_REPRESENTATION('',(#102401),#102405); -#102401 = LINE('',#102402,#102403); -#102402 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#102403 = VECTOR('',#102404,1.); -#102404 = DIRECTION('',(-1.,-1.021336205033E-016)); -#102405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102406 = ADVANCED_FACE('',(#102407),#102220,.F.); -#102407 = FACE_BOUND('',#102408,.T.); -#102408 = EDGE_LOOP('',(#102409,#102438,#102459,#102460)); -#102409 = ORIENTED_EDGE('',*,*,#102410,.F.); -#102410 = EDGE_CURVE('',#102411,#102413,#102415,.T.); -#102411 = VERTEX_POINT('',#102412); -#102412 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.530776333563)); -#102413 = VERTEX_POINT('',#102414); -#102414 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.530776333563)); -#102415 = SURFACE_CURVE('',#102416,(#102420,#102427),.PCURVE_S1.); -#102416 = LINE('',#102417,#102418); -#102417 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#102418 = VECTOR('',#102419,1.); -#102419 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102420 = PCURVE('',#102220,#102421); -#102421 = DEFINITIONAL_REPRESENTATION('',(#102422),#102426); -#102422 = LINE('',#102423,#102424); -#102423 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102424 = VECTOR('',#102425,1.); -#102425 = DIRECTION('',(0.E+000,-1.)); -#102426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102427 = PCURVE('',#102428,#102433); -#102428 = CYLINDRICAL_SURFACE('',#102429,0.119270391569); -#102429 = AXIS2_PLACEMENT_3D('',#102430,#102431,#102432); -#102430 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#102431 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102432 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102433 = DEFINITIONAL_REPRESENTATION('',(#102434),#102437); -#102434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102435,#102436), - .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#102435 = CARTESIAN_POINT('',(4.712388980385,-4.15)); -#102436 = CARTESIAN_POINT('',(4.712388980385,-4.35)); -#102437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102438 = ORIENTED_EDGE('',*,*,#102439,.T.); -#102439 = EDGE_CURVE('',#102411,#102206,#102440,.T.); -#102440 = SURFACE_CURVE('',#102441,(#102445,#102452),.PCURVE_S1.); -#102441 = LINE('',#102442,#102443); -#102442 = CARTESIAN_POINT('',(5.85,-0.419594812019,0.530776333563)); -#102443 = VECTOR('',#102444,1.); -#102444 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#102445 = PCURVE('',#102220,#102446); -#102446 = DEFINITIONAL_REPRESENTATION('',(#102447),#102451); -#102447 = LINE('',#102448,#102449); -#102448 = CARTESIAN_POINT('',(0.E+000,-4.15)); -#102449 = VECTOR('',#102450,1.); -#102450 = DIRECTION('',(1.,0.E+000)); -#102451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102452 = PCURVE('',#89949,#102453); -#102453 = DEFINITIONAL_REPRESENTATION('',(#102454),#102458); -#102454 = LINE('',#102455,#102456); -#102455 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#102456 = VECTOR('',#102457,1.); -#102457 = DIRECTION('',(-1.,-1.021336205033E-016)); -#102458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102459 = ORIENTED_EDGE('',*,*,#102205,.T.); -#102460 = ORIENTED_EDGE('',*,*,#102461,.F.); -#102461 = EDGE_CURVE('',#102413,#102179,#102462,.T.); -#102462 = SURFACE_CURVE('',#102463,(#102467,#102474),.PCURVE_S1.); -#102463 = LINE('',#102464,#102465); -#102464 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.530776333563)); -#102465 = VECTOR('',#102466,1.); -#102466 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#102467 = PCURVE('',#102220,#102468); -#102468 = DEFINITIONAL_REPRESENTATION('',(#102469),#102473); -#102469 = LINE('',#102470,#102471); -#102470 = CARTESIAN_POINT('',(0.E+000,-4.35)); -#102471 = VECTOR('',#102472,1.); -#102472 = DIRECTION('',(1.,0.E+000)); -#102473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102474 = PCURVE('',#89893,#102475); -#102475 = DEFINITIONAL_REPRESENTATION('',(#102476),#102480); -#102476 = LINE('',#102477,#102478); -#102477 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#102478 = VECTOR('',#102479,1.); -#102479 = DIRECTION('',(1.,-1.021336205033E-016)); -#102480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104844 = PCURVE('',#92341,#104845); +#104845 = DEFINITIONAL_REPRESENTATION('',(#104846),#104850); +#104846 = LINE('',#104847,#104848); +#104847 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#104848 = VECTOR('',#104849,1.); +#104849 = DIRECTION('',(-1.,-1.021336205033E-016)); +#104850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102481 = ADVANCED_FACE('',(#102482),#102353,.T.); -#102482 = FACE_BOUND('',#102483,.T.); -#102483 = EDGE_LOOP('',(#102484,#102507,#102508,#102535)); -#102484 = ORIENTED_EDGE('',*,*,#102485,.T.); -#102485 = EDGE_CURVE('',#102486,#102336,#102488,.T.); -#102486 = VERTEX_POINT('',#102487); -#102487 = CARTESIAN_POINT('',(5.65,-0.304819755875,0.75)); -#102488 = SURFACE_CURVE('',#102489,(#102494,#102500),.PCURVE_S1.); -#102489 = CIRCLE('',#102490,0.2192697516); -#102490 = AXIS2_PLACEMENT_3D('',#102491,#102492,#102493); -#102491 = CARTESIAN_POINT('',(5.65,-0.30032442045,0.530776333563)); -#102492 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102493 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102494 = PCURVE('',#102353,#102495); -#102495 = DEFINITIONAL_REPRESENTATION('',(#102496),#102499); -#102496 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102497,#102498), +#104851 = ORIENTED_EDGE('',*,*,#104597,.T.); +#104852 = ORIENTED_EDGE('',*,*,#104853,.F.); +#104853 = EDGE_CURVE('',#104805,#104571,#104854,.T.); +#104854 = SURFACE_CURVE('',#104855,(#104859,#104866),.PCURVE_S1.); +#104855 = LINE('',#104856,#104857); +#104856 = CARTESIAN_POINT('',(5.65,-0.419594812019,0.530776333563)); +#104857 = VECTOR('',#104858,1.); +#104858 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#104859 = PCURVE('',#104612,#104860); +#104860 = DEFINITIONAL_REPRESENTATION('',(#104861),#104865); +#104861 = LINE('',#104862,#104863); +#104862 = CARTESIAN_POINT('',(0.E+000,-4.35)); +#104863 = VECTOR('',#104864,1.); +#104864 = DIRECTION('',(1.,0.E+000)); +#104865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104866 = PCURVE('',#92285,#104867); +#104867 = DEFINITIONAL_REPRESENTATION('',(#104868),#104872); +#104868 = LINE('',#104869,#104870); +#104869 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#104870 = VECTOR('',#104871,1.); +#104871 = DIRECTION('',(1.,-1.021336205033E-016)); +#104872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104873 = ADVANCED_FACE('',(#104874),#104745,.T.); +#104874 = FACE_BOUND('',#104875,.T.); +#104875 = EDGE_LOOP('',(#104876,#104899,#104900,#104927)); +#104876 = ORIENTED_EDGE('',*,*,#104877,.T.); +#104877 = EDGE_CURVE('',#104878,#104728,#104880,.T.); +#104878 = VERTEX_POINT('',#104879); +#104879 = CARTESIAN_POINT('',(5.65,-0.304819755875,0.75)); +#104880 = SURFACE_CURVE('',#104881,(#104886,#104892),.PCURVE_S1.); +#104881 = CIRCLE('',#104882,0.2192697516); +#104882 = AXIS2_PLACEMENT_3D('',#104883,#104884,#104885); +#104883 = CARTESIAN_POINT('',(5.65,-0.30032442045,0.530776333563)); +#104884 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104885 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104886 = PCURVE('',#104745,#104887); +#104887 = DEFINITIONAL_REPRESENTATION('',(#104888),#104891); +#104888 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104889,#104890), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#102497 = CARTESIAN_POINT('',(3.162095483347,-4.35)); -#102498 = CARTESIAN_POINT('',(4.712388980385,-4.35)); -#102499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102500 = PCURVE('',#89893,#102501); -#102501 = DEFINITIONAL_REPRESENTATION('',(#102502),#102506); -#102502 = CIRCLE('',#102503,0.2192697516); -#102503 = AXIS2_PLACEMENT_2D('',#102504,#102505); -#102504 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#102505 = DIRECTION('',(1.,0.E+000)); -#102506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102507 = ORIENTED_EDGE('',*,*,#102335,.T.); -#102508 = ORIENTED_EDGE('',*,*,#102509,.F.); -#102509 = EDGE_CURVE('',#102510,#102338,#102512,.T.); -#102510 = VERTEX_POINT('',#102511); -#102511 = CARTESIAN_POINT('',(5.85,-0.304819755875,0.75)); -#102512 = SURFACE_CURVE('',#102513,(#102518,#102524),.PCURVE_S1.); -#102513 = CIRCLE('',#102514,0.2192697516); -#102514 = AXIS2_PLACEMENT_3D('',#102515,#102516,#102517); -#102515 = CARTESIAN_POINT('',(5.85,-0.30032442045,0.530776333563)); -#102516 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102517 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102518 = PCURVE('',#102353,#102519); -#102519 = DEFINITIONAL_REPRESENTATION('',(#102520),#102523); -#102520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102521,#102522), +#104889 = CARTESIAN_POINT('',(3.162095483347,-4.35)); +#104890 = CARTESIAN_POINT('',(4.712388980385,-4.35)); +#104891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104892 = PCURVE('',#92285,#104893); +#104893 = DEFINITIONAL_REPRESENTATION('',(#104894),#104898); +#104894 = CIRCLE('',#104895,0.2192697516); +#104895 = AXIS2_PLACEMENT_2D('',#104896,#104897); +#104896 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#104897 = DIRECTION('',(1.,0.E+000)); +#104898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104899 = ORIENTED_EDGE('',*,*,#104727,.T.); +#104900 = ORIENTED_EDGE('',*,*,#104901,.F.); +#104901 = EDGE_CURVE('',#104902,#104730,#104904,.T.); +#104902 = VERTEX_POINT('',#104903); +#104903 = CARTESIAN_POINT('',(5.85,-0.304819755875,0.75)); +#104904 = SURFACE_CURVE('',#104905,(#104910,#104916),.PCURVE_S1.); +#104905 = CIRCLE('',#104906,0.2192697516); +#104906 = AXIS2_PLACEMENT_3D('',#104907,#104908,#104909); +#104907 = CARTESIAN_POINT('',(5.85,-0.30032442045,0.530776333563)); +#104908 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104909 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104910 = PCURVE('',#104745,#104911); +#104911 = DEFINITIONAL_REPRESENTATION('',(#104912),#104915); +#104912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104913,#104914), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#102521 = CARTESIAN_POINT('',(3.162095483347,-4.15)); -#102522 = CARTESIAN_POINT('',(4.712388980385,-4.15)); -#102523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104913 = CARTESIAN_POINT('',(3.162095483347,-4.15)); +#104914 = CARTESIAN_POINT('',(4.712388980385,-4.15)); +#104915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102524 = PCURVE('',#89949,#102525); -#102525 = DEFINITIONAL_REPRESENTATION('',(#102526),#102534); -#102526 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102527,#102528,#102529, - #102530,#102531,#102532,#102533),.UNSPECIFIED.,.F.,.F.) +#104916 = PCURVE('',#92341,#104917); +#104917 = DEFINITIONAL_REPRESENTATION('',(#104918),#104926); +#104918 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104919,#104920,#104921, + #104922,#104923,#104924,#104925),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#102527 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#102528 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#102529 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#102530 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#102531 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#102532 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#102533 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#102534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102535 = ORIENTED_EDGE('',*,*,#102536,.T.); -#102536 = EDGE_CURVE('',#102510,#102486,#102537,.T.); -#102537 = SURFACE_CURVE('',#102538,(#102542,#102548),.PCURVE_S1.); -#102538 = LINE('',#102539,#102540); -#102539 = CARTESIAN_POINT('',(5.65,-0.304819755875,0.75)); -#102540 = VECTOR('',#102541,1.); -#102541 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102542 = PCURVE('',#102353,#102543); -#102543 = DEFINITIONAL_REPRESENTATION('',(#102544),#102547); -#102544 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102545,#102546), +#104919 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#104920 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#104921 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#104922 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#104923 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#104924 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#104925 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#104926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104927 = ORIENTED_EDGE('',*,*,#104928,.T.); +#104928 = EDGE_CURVE('',#104902,#104878,#104929,.T.); +#104929 = SURFACE_CURVE('',#104930,(#104934,#104940),.PCURVE_S1.); +#104930 = LINE('',#104931,#104932); +#104931 = CARTESIAN_POINT('',(5.65,-0.304819755875,0.75)); +#104932 = VECTOR('',#104933,1.); +#104933 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#104934 = PCURVE('',#104745,#104935); +#104935 = DEFINITIONAL_REPRESENTATION('',(#104936),#104939); +#104936 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104937,#104938), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#102545 = CARTESIAN_POINT('',(3.162095483347,-4.15)); -#102546 = CARTESIAN_POINT('',(3.162095483347,-4.35)); -#102547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102548 = PCURVE('',#89921,#102549); -#102549 = DEFINITIONAL_REPRESENTATION('',(#102550),#102554); -#102550 = LINE('',#102551,#102552); -#102551 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#102552 = VECTOR('',#102553,1.); -#102553 = DIRECTION('',(0.E+000,-1.)); -#102554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102555 = ADVANCED_FACE('',(#102556),#102428,.F.); -#102556 = FACE_BOUND('',#102557,.F.); -#102557 = EDGE_LOOP('',(#102558,#102585,#102607,#102628)); -#102558 = ORIENTED_EDGE('',*,*,#102559,.F.); -#102559 = EDGE_CURVE('',#102560,#102411,#102562,.T.); -#102560 = VERTEX_POINT('',#102561); -#102561 = CARTESIAN_POINT('',(5.85,-0.303662633502,0.65)); -#102562 = SURFACE_CURVE('',#102563,(#102568,#102574),.PCURVE_S1.); -#102563 = CIRCLE('',#102564,0.119270391569); -#102564 = AXIS2_PLACEMENT_3D('',#102565,#102566,#102567); -#102565 = CARTESIAN_POINT('',(5.85,-0.30032442045,0.530776333563)); -#102566 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102567 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102568 = PCURVE('',#102428,#102569); -#102569 = DEFINITIONAL_REPRESENTATION('',(#102570),#102573); -#102570 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102571,#102572), +#104937 = CARTESIAN_POINT('',(3.162095483347,-4.15)); +#104938 = CARTESIAN_POINT('',(3.162095483347,-4.35)); +#104939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104940 = PCURVE('',#92313,#104941); +#104941 = DEFINITIONAL_REPRESENTATION('',(#104942),#104946); +#104942 = LINE('',#104943,#104944); +#104943 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#104944 = VECTOR('',#104945,1.); +#104945 = DIRECTION('',(0.E+000,-1.)); +#104946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104947 = ADVANCED_FACE('',(#104948),#104820,.F.); +#104948 = FACE_BOUND('',#104949,.F.); +#104949 = EDGE_LOOP('',(#104950,#104977,#104999,#105020)); +#104950 = ORIENTED_EDGE('',*,*,#104951,.F.); +#104951 = EDGE_CURVE('',#104952,#104803,#104954,.T.); +#104952 = VERTEX_POINT('',#104953); +#104953 = CARTESIAN_POINT('',(5.85,-0.303662633502,0.65)); +#104954 = SURFACE_CURVE('',#104955,(#104960,#104966),.PCURVE_S1.); +#104955 = CIRCLE('',#104956,0.119270391569); +#104956 = AXIS2_PLACEMENT_3D('',#104957,#104958,#104959); +#104957 = CARTESIAN_POINT('',(5.85,-0.30032442045,0.530776333563)); +#104958 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104959 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#104960 = PCURVE('',#104820,#104961); +#104961 = DEFINITIONAL_REPRESENTATION('',(#104962),#104965); +#104962 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104963,#104964), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#102571 = CARTESIAN_POINT('',(3.169584923929,-4.15)); -#102572 = CARTESIAN_POINT('',(4.712388980385,-4.15)); -#102573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#104963 = CARTESIAN_POINT('',(3.169584923929,-4.15)); +#104964 = CARTESIAN_POINT('',(4.712388980385,-4.15)); +#104965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#102574 = PCURVE('',#89949,#102575); -#102575 = DEFINITIONAL_REPRESENTATION('',(#102576),#102584); -#102576 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#102577,#102578,#102579, - #102580,#102581,#102582,#102583),.UNSPECIFIED.,.F.,.F.) +#104966 = PCURVE('',#92341,#104967); +#104967 = DEFINITIONAL_REPRESENTATION('',(#104968),#104976); +#104968 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104969,#104970,#104971, + #104972,#104973,#104974,#104975),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#102577 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#102578 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#102579 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#102580 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#102581 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#102582 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#102583 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#102584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102585 = ORIENTED_EDGE('',*,*,#102586,.F.); -#102586 = EDGE_CURVE('',#102587,#102560,#102589,.T.); -#102587 = VERTEX_POINT('',#102588); -#102588 = CARTESIAN_POINT('',(5.65,-0.303662633502,0.65)); -#102589 = SURFACE_CURVE('',#102590,(#102594,#102600),.PCURVE_S1.); -#102590 = LINE('',#102591,#102592); -#102591 = CARTESIAN_POINT('',(5.65,-0.303662633502,0.65)); -#102592 = VECTOR('',#102593,1.); -#102593 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102594 = PCURVE('',#102428,#102595); -#102595 = DEFINITIONAL_REPRESENTATION('',(#102596),#102599); -#102596 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102597,#102598), +#104969 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#104970 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#104971 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#104972 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#104973 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#104974 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#104975 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#104976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104977 = ORIENTED_EDGE('',*,*,#104978,.F.); +#104978 = EDGE_CURVE('',#104979,#104952,#104981,.T.); +#104979 = VERTEX_POINT('',#104980); +#104980 = CARTESIAN_POINT('',(5.65,-0.303662633502,0.65)); +#104981 = SURFACE_CURVE('',#104982,(#104986,#104992),.PCURVE_S1.); +#104982 = LINE('',#104983,#104984); +#104983 = CARTESIAN_POINT('',(5.65,-0.303662633502,0.65)); +#104984 = VECTOR('',#104985,1.); +#104985 = DIRECTION('',(1.,0.E+000,0.E+000)); +#104986 = PCURVE('',#104820,#104987); +#104987 = DEFINITIONAL_REPRESENTATION('',(#104988),#104991); +#104988 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104989,#104990), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#102597 = CARTESIAN_POINT('',(3.169584923929,-4.35)); -#102598 = CARTESIAN_POINT('',(3.169584923929,-4.15)); -#102599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102600 = PCURVE('',#89975,#102601); -#102601 = DEFINITIONAL_REPRESENTATION('',(#102602),#102606); -#102602 = LINE('',#102603,#102604); -#102603 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#102604 = VECTOR('',#102605,1.); -#102605 = DIRECTION('',(0.E+000,1.)); -#102606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102607 = ORIENTED_EDGE('',*,*,#102608,.T.); -#102608 = EDGE_CURVE('',#102587,#102413,#102609,.T.); -#102609 = SURFACE_CURVE('',#102610,(#102615,#102621),.PCURVE_S1.); -#102610 = CIRCLE('',#102611,0.119270391569); -#102611 = AXIS2_PLACEMENT_3D('',#102612,#102613,#102614); -#102612 = CARTESIAN_POINT('',(5.65,-0.30032442045,0.530776333563)); -#102613 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102614 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102615 = PCURVE('',#102428,#102616); -#102616 = DEFINITIONAL_REPRESENTATION('',(#102617),#102620); -#102617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102618,#102619), +#104989 = CARTESIAN_POINT('',(3.169584923929,-4.35)); +#104990 = CARTESIAN_POINT('',(3.169584923929,-4.15)); +#104991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104992 = PCURVE('',#92367,#104993); +#104993 = DEFINITIONAL_REPRESENTATION('',(#104994),#104998); +#104994 = LINE('',#104995,#104996); +#104995 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#104996 = VECTOR('',#104997,1.); +#104997 = DIRECTION('',(0.E+000,1.)); +#104998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#104999 = ORIENTED_EDGE('',*,*,#105000,.T.); +#105000 = EDGE_CURVE('',#104979,#104805,#105001,.T.); +#105001 = SURFACE_CURVE('',#105002,(#105007,#105013),.PCURVE_S1.); +#105002 = CIRCLE('',#105003,0.119270391569); +#105003 = AXIS2_PLACEMENT_3D('',#105004,#105005,#105006); +#105004 = CARTESIAN_POINT('',(5.65,-0.30032442045,0.530776333563)); +#105005 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105006 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105007 = PCURVE('',#104820,#105008); +#105008 = DEFINITIONAL_REPRESENTATION('',(#105009),#105012); +#105009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105010,#105011), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#102618 = CARTESIAN_POINT('',(3.169584923929,-4.35)); -#102619 = CARTESIAN_POINT('',(4.712388980385,-4.35)); -#102620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102621 = PCURVE('',#89893,#102622); -#102622 = DEFINITIONAL_REPRESENTATION('',(#102623),#102627); -#102623 = CIRCLE('',#102624,0.119270391569); -#102624 = AXIS2_PLACEMENT_2D('',#102625,#102626); -#102625 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#102626 = DIRECTION('',(1.,0.E+000)); -#102627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102628 = ORIENTED_EDGE('',*,*,#102410,.F.); -#102629 = ADVANCED_FACE('',(#102630),#89893,.F.); -#102630 = FACE_BOUND('',#102631,.T.); -#102631 = EDGE_LOOP('',(#102632,#102653,#102654,#102655,#102656,#102657, - #102678,#102679,#102680,#102681,#102682,#102703)); -#102632 = ORIENTED_EDGE('',*,*,#102633,.F.); -#102633 = EDGE_CURVE('',#102587,#89878,#102634,.T.); -#102634 = SURFACE_CURVE('',#102635,(#102639,#102646),.PCURVE_S1.); -#102635 = LINE('',#102636,#102637); -#102636 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); -#102637 = VECTOR('',#102638,1.); -#102638 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#102639 = PCURVE('',#89893,#102640); -#102640 = DEFINITIONAL_REPRESENTATION('',(#102641),#102645); -#102641 = LINE('',#102642,#102643); -#102642 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102643 = VECTOR('',#102644,1.); -#102644 = DIRECTION('',(-3.563627120235E-016,1.)); -#102645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102646 = PCURVE('',#89975,#102647); -#102647 = DEFINITIONAL_REPRESENTATION('',(#102648),#102652); -#102648 = LINE('',#102649,#102650); -#102649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102650 = VECTOR('',#102651,1.); -#102651 = DIRECTION('',(-1.,0.E+000)); -#102652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102653 = ORIENTED_EDGE('',*,*,#102608,.T.); -#102654 = ORIENTED_EDGE('',*,*,#102461,.T.); -#102655 = ORIENTED_EDGE('',*,*,#102178,.T.); -#102656 = ORIENTED_EDGE('',*,*,#102022,.T.); -#102657 = ORIENTED_EDGE('',*,*,#102658,.T.); -#102658 = EDGE_CURVE('',#101995,#102076,#102659,.T.); -#102659 = SURFACE_CURVE('',#102660,(#102664,#102671),.PCURVE_S1.); -#102660 = LINE('',#102661,#102662); -#102661 = CARTESIAN_POINT('',(5.65,-1.,1.159810404338E-002)); -#102662 = VECTOR('',#102663,1.); -#102663 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#102664 = PCURVE('',#89893,#102665); -#102665 = DEFINITIONAL_REPRESENTATION('',(#102666),#102670); -#102666 = LINE('',#102667,#102668); -#102667 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#102668 = VECTOR('',#102669,1.); -#102669 = DIRECTION('',(-1.,-2.101748079665E-016)); -#102670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102671 = PCURVE('',#102010,#102672); -#102672 = DEFINITIONAL_REPRESENTATION('',(#102673),#102677); -#102673 = LINE('',#102674,#102675); -#102674 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#102675 = VECTOR('',#102676,1.); -#102676 = DIRECTION('',(-1.,0.E+000)); -#102677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102678 = ORIENTED_EDGE('',*,*,#102073,.F.); -#102679 = ORIENTED_EDGE('',*,*,#102257,.F.); -#102680 = ORIENTED_EDGE('',*,*,#102364,.F.); -#102681 = ORIENTED_EDGE('',*,*,#102485,.F.); -#102682 = ORIENTED_EDGE('',*,*,#102683,.T.); -#102683 = EDGE_CURVE('',#102486,#89876,#102684,.T.); -#102684 = SURFACE_CURVE('',#102685,(#102689,#102696),.PCURVE_S1.); -#102685 = LINE('',#102686,#102687); -#102686 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.75)); -#102687 = VECTOR('',#102688,1.); -#102688 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#102689 = PCURVE('',#89893,#102690); -#102690 = DEFINITIONAL_REPRESENTATION('',(#102691),#102695); -#102691 = LINE('',#102692,#102693); -#102692 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#102693 = VECTOR('',#102694,1.); -#102694 = DIRECTION('',(-3.563627120235E-016,1.)); -#102695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102696 = PCURVE('',#89921,#102697); -#102697 = DEFINITIONAL_REPRESENTATION('',(#102698),#102702); -#102698 = LINE('',#102699,#102700); -#102699 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102700 = VECTOR('',#102701,1.); -#102701 = DIRECTION('',(1.,0.E+000)); -#102702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102703 = ORIENTED_EDGE('',*,*,#89875,.T.); -#102704 = ADVANCED_FACE('',(#102705),#89921,.F.); -#102705 = FACE_BOUND('',#102706,.T.); -#102706 = EDGE_LOOP('',(#102707,#102708,#102729,#102730)); -#102707 = ORIENTED_EDGE('',*,*,#102536,.F.); -#102708 = ORIENTED_EDGE('',*,*,#102709,.T.); -#102709 = EDGE_CURVE('',#102510,#89906,#102710,.T.); -#102710 = SURFACE_CURVE('',#102711,(#102715,#102722),.PCURVE_S1.); -#102711 = LINE('',#102712,#102713); -#102712 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.75)); -#102713 = VECTOR('',#102714,1.); -#102714 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#102715 = PCURVE('',#89921,#102716); -#102716 = DEFINITIONAL_REPRESENTATION('',(#102717),#102721); -#102717 = LINE('',#102718,#102719); -#102718 = CARTESIAN_POINT('',(0.E+000,0.2)); -#102719 = VECTOR('',#102720,1.); -#102720 = DIRECTION('',(1.,0.E+000)); -#102721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102722 = PCURVE('',#89949,#102723); -#102723 = DEFINITIONAL_REPRESENTATION('',(#102724),#102728); -#102724 = LINE('',#102725,#102726); -#102725 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#102726 = VECTOR('',#102727,1.); -#102727 = DIRECTION('',(3.563627120235E-016,1.)); -#102728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102729 = ORIENTED_EDGE('',*,*,#89905,.T.); -#102730 = ORIENTED_EDGE('',*,*,#102683,.F.); -#102731 = ADVANCED_FACE('',(#102732),#89949,.F.); -#102732 = FACE_BOUND('',#102733,.T.); -#102733 = EDGE_LOOP('',(#102734,#102735,#102736,#102737,#102738,#102739, - #102760,#102761,#102762,#102763,#102764,#102785)); -#102734 = ORIENTED_EDGE('',*,*,#102709,.F.); -#102735 = ORIENTED_EDGE('',*,*,#102509,.T.); -#102736 = ORIENTED_EDGE('',*,*,#102386,.T.); -#102737 = ORIENTED_EDGE('',*,*,#102311,.T.); -#102738 = ORIENTED_EDGE('',*,*,#102126,.T.); -#102739 = ORIENTED_EDGE('',*,*,#102740,.T.); -#102740 = EDGE_CURVE('',#102104,#101967,#102741,.T.); -#102741 = SURFACE_CURVE('',#102742,(#102746,#102753),.PCURVE_S1.); -#102742 = LINE('',#102743,#102744); -#102743 = CARTESIAN_POINT('',(5.85,-1.,1.159810404338E-002)); -#102744 = VECTOR('',#102745,1.); -#102745 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#102746 = PCURVE('',#89949,#102747); -#102747 = DEFINITIONAL_REPRESENTATION('',(#102748),#102752); -#102748 = LINE('',#102749,#102750); -#102749 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#102750 = VECTOR('',#102751,1.); -#102751 = DIRECTION('',(-1.,2.101748079665E-016)); -#102752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102753 = PCURVE('',#102010,#102754); -#102754 = DEFINITIONAL_REPRESENTATION('',(#102755),#102759); -#102755 = LINE('',#102756,#102757); -#102756 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#102757 = VECTOR('',#102758,1.); -#102758 = DIRECTION('',(1.,0.E+000)); -#102759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102760 = ORIENTED_EDGE('',*,*,#101964,.F.); -#102761 = ORIENTED_EDGE('',*,*,#102232,.F.); -#102762 = ORIENTED_EDGE('',*,*,#102439,.F.); -#102763 = ORIENTED_EDGE('',*,*,#102559,.F.); -#102764 = ORIENTED_EDGE('',*,*,#102765,.T.); -#102765 = EDGE_CURVE('',#102560,#89934,#102766,.T.); -#102766 = SURFACE_CURVE('',#102767,(#102771,#102778),.PCURVE_S1.); -#102767 = LINE('',#102768,#102769); -#102768 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.65)); -#102769 = VECTOR('',#102770,1.); -#102770 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#102771 = PCURVE('',#89949,#102772); -#102772 = DEFINITIONAL_REPRESENTATION('',(#102773),#102777); -#102773 = LINE('',#102774,#102775); -#102774 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102775 = VECTOR('',#102776,1.); -#102776 = DIRECTION('',(3.563627120235E-016,1.)); -#102777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102778 = PCURVE('',#89975,#102779); -#102779 = DEFINITIONAL_REPRESENTATION('',(#102780),#102784); -#102780 = LINE('',#102781,#102782); -#102781 = CARTESIAN_POINT('',(0.E+000,0.2)); -#102782 = VECTOR('',#102783,1.); -#102783 = DIRECTION('',(-1.,0.E+000)); -#102784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102785 = ORIENTED_EDGE('',*,*,#89933,.T.); -#102786 = ADVANCED_FACE('',(#102787),#89975,.F.); -#102787 = FACE_BOUND('',#102788,.T.); -#102788 = EDGE_LOOP('',(#102789,#102790,#102791,#102792)); -#102789 = ORIENTED_EDGE('',*,*,#102586,.F.); -#102790 = ORIENTED_EDGE('',*,*,#102633,.T.); -#102791 = ORIENTED_EDGE('',*,*,#89961,.T.); -#102792 = ORIENTED_EDGE('',*,*,#102765,.F.); -#102793 = ADVANCED_FACE('',(#102794),#102010,.T.); -#102794 = FACE_BOUND('',#102795,.T.); -#102795 = EDGE_LOOP('',(#102796,#102797,#102798,#102799)); -#102796 = ORIENTED_EDGE('',*,*,#102740,.F.); -#102797 = ORIENTED_EDGE('',*,*,#102103,.F.); -#102798 = ORIENTED_EDGE('',*,*,#102658,.F.); -#102799 = ORIENTED_EDGE('',*,*,#101994,.F.); -#102800 = ADVANCED_FACE('',(#102801),#102815,.T.); -#102801 = FACE_BOUND('',#102802,.T.); -#102802 = EDGE_LOOP('',(#102803,#102833,#102861,#102884)); -#102803 = ORIENTED_EDGE('',*,*,#102804,.T.); -#102804 = EDGE_CURVE('',#102805,#102807,#102809,.T.); -#102805 = VERTEX_POINT('',#102806); -#102806 = CARTESIAN_POINT('',(6.35,-0.74341632541,-0.308197125857)); -#102807 = VERTEX_POINT('',#102808); -#102808 = CARTESIAN_POINT('',(6.35,-1.,-0.308197125857)); -#102809 = SURFACE_CURVE('',#102810,(#102814,#102826),.PCURVE_S1.); -#102810 = LINE('',#102811,#102812); -#102811 = CARTESIAN_POINT('',(6.35,-0.74341632541,-0.308197125857)); -#102812 = VECTOR('',#102813,1.); -#102813 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102814 = PCURVE('',#102815,#102820); -#102815 = PLANE('',#102816); -#102816 = AXIS2_PLACEMENT_3D('',#102817,#102818,#102819); -#102817 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#102818 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#102819 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102820 = DEFINITIONAL_REPRESENTATION('',(#102821),#102825); -#102821 = LINE('',#102822,#102823); -#102822 = CARTESIAN_POINT('',(3.65,0.E+000)); -#102823 = VECTOR('',#102824,1.); -#102824 = DIRECTION('',(0.E+000,-1.)); -#102825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102826 = PCURVE('',#88700,#102827); -#102827 = DEFINITIONAL_REPRESENTATION('',(#102828),#102832); -#102828 = LINE('',#102829,#102830); -#102829 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#102830 = VECTOR('',#102831,1.); -#102831 = DIRECTION('',(0.E+000,-1.)); -#102832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102833 = ORIENTED_EDGE('',*,*,#102834,.T.); -#102834 = EDGE_CURVE('',#102807,#102835,#102837,.T.); -#102835 = VERTEX_POINT('',#102836); -#102836 = CARTESIAN_POINT('',(6.15,-1.,-0.308197125857)); -#102837 = SURFACE_CURVE('',#102838,(#102842,#102849),.PCURVE_S1.); -#102838 = LINE('',#102839,#102840); -#102839 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#102840 = VECTOR('',#102841,1.); -#102841 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102842 = PCURVE('',#102815,#102843); -#102843 = DEFINITIONAL_REPRESENTATION('',(#102844),#102848); -#102844 = LINE('',#102845,#102846); -#102845 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#102846 = VECTOR('',#102847,1.); -#102847 = DIRECTION('',(1.,0.E+000)); -#102848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102849 = PCURVE('',#102850,#102855); -#102850 = PLANE('',#102851); -#102851 = AXIS2_PLACEMENT_3D('',#102852,#102853,#102854); -#102852 = CARTESIAN_POINT('',(6.25,-1.,-0.258196742327)); -#102853 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#102854 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#102855 = DEFINITIONAL_REPRESENTATION('',(#102856),#102860); -#102856 = LINE('',#102857,#102858); -#102857 = CARTESIAN_POINT('',(5.000038352949E-002,3.75)); -#102858 = VECTOR('',#102859,1.); -#102859 = DIRECTION('',(0.E+000,-1.)); -#102860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102861 = ORIENTED_EDGE('',*,*,#102862,.F.); -#102862 = EDGE_CURVE('',#102863,#102835,#102865,.T.); -#102863 = VERTEX_POINT('',#102864); -#102864 = CARTESIAN_POINT('',(6.15,-0.74341632541,-0.308197125857)); -#102865 = SURFACE_CURVE('',#102866,(#102870,#102877),.PCURVE_S1.); -#102866 = LINE('',#102867,#102868); -#102867 = CARTESIAN_POINT('',(6.15,-0.74341632541,-0.308197125857)); -#102868 = VECTOR('',#102869,1.); -#102869 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102870 = PCURVE('',#102815,#102871); -#102871 = DEFINITIONAL_REPRESENTATION('',(#102872),#102876); -#102872 = LINE('',#102873,#102874); -#102873 = CARTESIAN_POINT('',(3.85,0.E+000)); -#102874 = VECTOR('',#102875,1.); -#102875 = DIRECTION('',(0.E+000,-1.)); -#102876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102877 = PCURVE('',#88644,#102878); -#102878 = DEFINITIONAL_REPRESENTATION('',(#102879),#102883); -#102879 = LINE('',#102880,#102881); -#102880 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#102881 = VECTOR('',#102882,1.); -#102882 = DIRECTION('',(0.E+000,-1.)); -#102883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102884 = ORIENTED_EDGE('',*,*,#102885,.T.); -#102885 = EDGE_CURVE('',#102863,#102805,#102886,.T.); -#102886 = SURFACE_CURVE('',#102887,(#102891,#102898),.PCURVE_S1.); -#102887 = LINE('',#102888,#102889); -#102888 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#102889 = VECTOR('',#102890,1.); -#102890 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102891 = PCURVE('',#102815,#102892); -#102892 = DEFINITIONAL_REPRESENTATION('',(#102893),#102897); -#102893 = LINE('',#102894,#102895); -#102894 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102895 = VECTOR('',#102896,1.); -#102896 = DIRECTION('',(-1.,0.E+000)); -#102897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102898 = PCURVE('',#102899,#102904); -#102899 = CYLINDRICAL_SURFACE('',#102900,0.308574064194); -#102900 = AXIS2_PLACEMENT_3D('',#102901,#102902,#102903); -#102901 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#102902 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102903 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102904 = DEFINITIONAL_REPRESENTATION('',(#102905),#102908); -#102905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#102906,#102907), +#105010 = CARTESIAN_POINT('',(3.169584923929,-4.35)); +#105011 = CARTESIAN_POINT('',(4.712388980385,-4.35)); +#105012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105013 = PCURVE('',#92285,#105014); +#105014 = DEFINITIONAL_REPRESENTATION('',(#105015),#105019); +#105015 = CIRCLE('',#105016,0.119270391569); +#105016 = AXIS2_PLACEMENT_2D('',#105017,#105018); +#105017 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#105018 = DIRECTION('',(1.,0.E+000)); +#105019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105020 = ORIENTED_EDGE('',*,*,#104802,.F.); +#105021 = ADVANCED_FACE('',(#105022),#92285,.F.); +#105022 = FACE_BOUND('',#105023,.T.); +#105023 = EDGE_LOOP('',(#105024,#105045,#105046,#105047,#105048,#105049, + #105070,#105071,#105072,#105073,#105074,#105095)); +#105024 = ORIENTED_EDGE('',*,*,#105025,.F.); +#105025 = EDGE_CURVE('',#104979,#92270,#105026,.T.); +#105026 = SURFACE_CURVE('',#105027,(#105031,#105038),.PCURVE_S1.); +#105027 = LINE('',#105028,#105029); +#105028 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.65)); +#105029 = VECTOR('',#105030,1.); +#105030 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105031 = PCURVE('',#92285,#105032); +#105032 = DEFINITIONAL_REPRESENTATION('',(#105033),#105037); +#105033 = LINE('',#105034,#105035); +#105034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105035 = VECTOR('',#105036,1.); +#105036 = DIRECTION('',(-3.563627120235E-016,1.)); +#105037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105038 = PCURVE('',#92367,#105039); +#105039 = DEFINITIONAL_REPRESENTATION('',(#105040),#105044); +#105040 = LINE('',#105041,#105042); +#105041 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105042 = VECTOR('',#105043,1.); +#105043 = DIRECTION('',(-1.,0.E+000)); +#105044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105045 = ORIENTED_EDGE('',*,*,#105000,.T.); +#105046 = ORIENTED_EDGE('',*,*,#104853,.T.); +#105047 = ORIENTED_EDGE('',*,*,#104570,.T.); +#105048 = ORIENTED_EDGE('',*,*,#104414,.T.); +#105049 = ORIENTED_EDGE('',*,*,#105050,.T.); +#105050 = EDGE_CURVE('',#104387,#104468,#105051,.T.); +#105051 = SURFACE_CURVE('',#105052,(#105056,#105063),.PCURVE_S1.); +#105052 = LINE('',#105053,#105054); +#105053 = CARTESIAN_POINT('',(5.65,-1.,1.159810404338E-002)); +#105054 = VECTOR('',#105055,1.); +#105055 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#105056 = PCURVE('',#92285,#105057); +#105057 = DEFINITIONAL_REPRESENTATION('',(#105058),#105062); +#105058 = LINE('',#105059,#105060); +#105059 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#105060 = VECTOR('',#105061,1.); +#105061 = DIRECTION('',(-1.,-2.101748079665E-016)); +#105062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105063 = PCURVE('',#104402,#105064); +#105064 = DEFINITIONAL_REPRESENTATION('',(#105065),#105069); +#105065 = LINE('',#105066,#105067); +#105066 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#105067 = VECTOR('',#105068,1.); +#105068 = DIRECTION('',(-1.,0.E+000)); +#105069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105070 = ORIENTED_EDGE('',*,*,#104465,.F.); +#105071 = ORIENTED_EDGE('',*,*,#104649,.F.); +#105072 = ORIENTED_EDGE('',*,*,#104756,.F.); +#105073 = ORIENTED_EDGE('',*,*,#104877,.F.); +#105074 = ORIENTED_EDGE('',*,*,#105075,.T.); +#105075 = EDGE_CURVE('',#104878,#92268,#105076,.T.); +#105076 = SURFACE_CURVE('',#105077,(#105081,#105088),.PCURVE_S1.); +#105077 = LINE('',#105078,#105079); +#105078 = CARTESIAN_POINT('',(5.65,-0.527847992439,0.75)); +#105079 = VECTOR('',#105080,1.); +#105080 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105081 = PCURVE('',#92285,#105082); +#105082 = DEFINITIONAL_REPRESENTATION('',(#105083),#105087); +#105083 = LINE('',#105084,#105085); +#105084 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#105085 = VECTOR('',#105086,1.); +#105086 = DIRECTION('',(-3.563627120235E-016,1.)); +#105087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105088 = PCURVE('',#92313,#105089); +#105089 = DEFINITIONAL_REPRESENTATION('',(#105090),#105094); +#105090 = LINE('',#105091,#105092); +#105091 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105092 = VECTOR('',#105093,1.); +#105093 = DIRECTION('',(1.,0.E+000)); +#105094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105095 = ORIENTED_EDGE('',*,*,#92267,.T.); +#105096 = ADVANCED_FACE('',(#105097),#92313,.F.); +#105097 = FACE_BOUND('',#105098,.T.); +#105098 = EDGE_LOOP('',(#105099,#105100,#105121,#105122)); +#105099 = ORIENTED_EDGE('',*,*,#104928,.F.); +#105100 = ORIENTED_EDGE('',*,*,#105101,.T.); +#105101 = EDGE_CURVE('',#104902,#92298,#105102,.T.); +#105102 = SURFACE_CURVE('',#105103,(#105107,#105114),.PCURVE_S1.); +#105103 = LINE('',#105104,#105105); +#105104 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.75)); +#105105 = VECTOR('',#105106,1.); +#105106 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105107 = PCURVE('',#92313,#105108); +#105108 = DEFINITIONAL_REPRESENTATION('',(#105109),#105113); +#105109 = LINE('',#105110,#105111); +#105110 = CARTESIAN_POINT('',(0.E+000,0.2)); +#105111 = VECTOR('',#105112,1.); +#105112 = DIRECTION('',(1.,0.E+000)); +#105113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105114 = PCURVE('',#92341,#105115); +#105115 = DEFINITIONAL_REPRESENTATION('',(#105116),#105120); +#105116 = LINE('',#105117,#105118); +#105117 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#105118 = VECTOR('',#105119,1.); +#105119 = DIRECTION('',(3.563627120235E-016,1.)); +#105120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105121 = ORIENTED_EDGE('',*,*,#92297,.T.); +#105122 = ORIENTED_EDGE('',*,*,#105075,.F.); +#105123 = ADVANCED_FACE('',(#105124),#92341,.F.); +#105124 = FACE_BOUND('',#105125,.T.); +#105125 = EDGE_LOOP('',(#105126,#105127,#105128,#105129,#105130,#105131, + #105152,#105153,#105154,#105155,#105156,#105177)); +#105126 = ORIENTED_EDGE('',*,*,#105101,.F.); +#105127 = ORIENTED_EDGE('',*,*,#104901,.T.); +#105128 = ORIENTED_EDGE('',*,*,#104778,.T.); +#105129 = ORIENTED_EDGE('',*,*,#104703,.T.); +#105130 = ORIENTED_EDGE('',*,*,#104518,.T.); +#105131 = ORIENTED_EDGE('',*,*,#105132,.T.); +#105132 = EDGE_CURVE('',#104496,#104359,#105133,.T.); +#105133 = SURFACE_CURVE('',#105134,(#105138,#105145),.PCURVE_S1.); +#105134 = LINE('',#105135,#105136); +#105135 = CARTESIAN_POINT('',(5.85,-1.,1.159810404338E-002)); +#105136 = VECTOR('',#105137,1.); +#105137 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#105138 = PCURVE('',#92341,#105139); +#105139 = DEFINITIONAL_REPRESENTATION('',(#105140),#105144); +#105140 = LINE('',#105141,#105142); +#105141 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#105142 = VECTOR('',#105143,1.); +#105143 = DIRECTION('',(-1.,2.101748079665E-016)); +#105144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105145 = PCURVE('',#104402,#105146); +#105146 = DEFINITIONAL_REPRESENTATION('',(#105147),#105151); +#105147 = LINE('',#105148,#105149); +#105148 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#105149 = VECTOR('',#105150,1.); +#105150 = DIRECTION('',(1.,0.E+000)); +#105151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105152 = ORIENTED_EDGE('',*,*,#104356,.F.); +#105153 = ORIENTED_EDGE('',*,*,#104624,.F.); +#105154 = ORIENTED_EDGE('',*,*,#104831,.F.); +#105155 = ORIENTED_EDGE('',*,*,#104951,.F.); +#105156 = ORIENTED_EDGE('',*,*,#105157,.T.); +#105157 = EDGE_CURVE('',#104952,#92326,#105158,.T.); +#105158 = SURFACE_CURVE('',#105159,(#105163,#105170),.PCURVE_S1.); +#105159 = LINE('',#105160,#105161); +#105160 = CARTESIAN_POINT('',(5.85,-0.527847992439,0.65)); +#105161 = VECTOR('',#105162,1.); +#105162 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105163 = PCURVE('',#92341,#105164); +#105164 = DEFINITIONAL_REPRESENTATION('',(#105165),#105169); +#105165 = LINE('',#105166,#105167); +#105166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105167 = VECTOR('',#105168,1.); +#105168 = DIRECTION('',(3.563627120235E-016,1.)); +#105169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105170 = PCURVE('',#92367,#105171); +#105171 = DEFINITIONAL_REPRESENTATION('',(#105172),#105176); +#105172 = LINE('',#105173,#105174); +#105173 = CARTESIAN_POINT('',(0.E+000,0.2)); +#105174 = VECTOR('',#105175,1.); +#105175 = DIRECTION('',(-1.,0.E+000)); +#105176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105177 = ORIENTED_EDGE('',*,*,#92325,.T.); +#105178 = ADVANCED_FACE('',(#105179),#92367,.F.); +#105179 = FACE_BOUND('',#105180,.T.); +#105180 = EDGE_LOOP('',(#105181,#105182,#105183,#105184)); +#105181 = ORIENTED_EDGE('',*,*,#104978,.F.); +#105182 = ORIENTED_EDGE('',*,*,#105025,.T.); +#105183 = ORIENTED_EDGE('',*,*,#92353,.T.); +#105184 = ORIENTED_EDGE('',*,*,#105157,.F.); +#105185 = ADVANCED_FACE('',(#105186),#104402,.T.); +#105186 = FACE_BOUND('',#105187,.T.); +#105187 = EDGE_LOOP('',(#105188,#105189,#105190,#105191)); +#105188 = ORIENTED_EDGE('',*,*,#105132,.F.); +#105189 = ORIENTED_EDGE('',*,*,#104495,.F.); +#105190 = ORIENTED_EDGE('',*,*,#105050,.F.); +#105191 = ORIENTED_EDGE('',*,*,#104386,.F.); +#105192 = ADVANCED_FACE('',(#105193),#105207,.T.); +#105193 = FACE_BOUND('',#105194,.T.); +#105194 = EDGE_LOOP('',(#105195,#105225,#105253,#105276)); +#105195 = ORIENTED_EDGE('',*,*,#105196,.T.); +#105196 = EDGE_CURVE('',#105197,#105199,#105201,.T.); +#105197 = VERTEX_POINT('',#105198); +#105198 = CARTESIAN_POINT('',(6.35,-0.74341632541,-0.308197125857)); +#105199 = VERTEX_POINT('',#105200); +#105200 = CARTESIAN_POINT('',(6.35,-1.,-0.308197125857)); +#105201 = SURFACE_CURVE('',#105202,(#105206,#105218),.PCURVE_S1.); +#105202 = LINE('',#105203,#105204); +#105203 = CARTESIAN_POINT('',(6.35,-0.74341632541,-0.308197125857)); +#105204 = VECTOR('',#105205,1.); +#105205 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#105206 = PCURVE('',#105207,#105212); +#105207 = PLANE('',#105208); +#105208 = AXIS2_PLACEMENT_3D('',#105209,#105210,#105211); +#105209 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#105210 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105211 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105212 = DEFINITIONAL_REPRESENTATION('',(#105213),#105217); +#105213 = LINE('',#105214,#105215); +#105214 = CARTESIAN_POINT('',(3.65,0.E+000)); +#105215 = VECTOR('',#105216,1.); +#105216 = DIRECTION('',(0.E+000,-1.)); +#105217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105218 = PCURVE('',#91092,#105219); +#105219 = DEFINITIONAL_REPRESENTATION('',(#105220),#105224); +#105220 = LINE('',#105221,#105222); +#105221 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#105222 = VECTOR('',#105223,1.); +#105223 = DIRECTION('',(0.E+000,-1.)); +#105224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105225 = ORIENTED_EDGE('',*,*,#105226,.T.); +#105226 = EDGE_CURVE('',#105199,#105227,#105229,.T.); +#105227 = VERTEX_POINT('',#105228); +#105228 = CARTESIAN_POINT('',(6.15,-1.,-0.308197125857)); +#105229 = SURFACE_CURVE('',#105230,(#105234,#105241),.PCURVE_S1.); +#105230 = LINE('',#105231,#105232); +#105231 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#105232 = VECTOR('',#105233,1.); +#105233 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105234 = PCURVE('',#105207,#105235); +#105235 = DEFINITIONAL_REPRESENTATION('',(#105236),#105240); +#105236 = LINE('',#105237,#105238); +#105237 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#105238 = VECTOR('',#105239,1.); +#105239 = DIRECTION('',(1.,0.E+000)); +#105240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105241 = PCURVE('',#105242,#105247); +#105242 = PLANE('',#105243); +#105243 = AXIS2_PLACEMENT_3D('',#105244,#105245,#105246); +#105244 = CARTESIAN_POINT('',(6.25,-1.,-0.258196742327)); +#105245 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#105246 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#105247 = DEFINITIONAL_REPRESENTATION('',(#105248),#105252); +#105248 = LINE('',#105249,#105250); +#105249 = CARTESIAN_POINT('',(5.000038352949E-002,3.75)); +#105250 = VECTOR('',#105251,1.); +#105251 = DIRECTION('',(0.E+000,-1.)); +#105252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105253 = ORIENTED_EDGE('',*,*,#105254,.F.); +#105254 = EDGE_CURVE('',#105255,#105227,#105257,.T.); +#105255 = VERTEX_POINT('',#105256); +#105256 = CARTESIAN_POINT('',(6.15,-0.74341632541,-0.308197125857)); +#105257 = SURFACE_CURVE('',#105258,(#105262,#105269),.PCURVE_S1.); +#105258 = LINE('',#105259,#105260); +#105259 = CARTESIAN_POINT('',(6.15,-0.74341632541,-0.308197125857)); +#105260 = VECTOR('',#105261,1.); +#105261 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#105262 = PCURVE('',#105207,#105263); +#105263 = DEFINITIONAL_REPRESENTATION('',(#105264),#105268); +#105264 = LINE('',#105265,#105266); +#105265 = CARTESIAN_POINT('',(3.85,0.E+000)); +#105266 = VECTOR('',#105267,1.); +#105267 = DIRECTION('',(0.E+000,-1.)); +#105268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105269 = PCURVE('',#91036,#105270); +#105270 = DEFINITIONAL_REPRESENTATION('',(#105271),#105275); +#105271 = LINE('',#105272,#105273); +#105272 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#105273 = VECTOR('',#105274,1.); +#105274 = DIRECTION('',(0.E+000,-1.)); +#105275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105276 = ORIENTED_EDGE('',*,*,#105277,.T.); +#105277 = EDGE_CURVE('',#105255,#105197,#105278,.T.); +#105278 = SURFACE_CURVE('',#105279,(#105283,#105290),.PCURVE_S1.); +#105279 = LINE('',#105280,#105281); +#105280 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#105281 = VECTOR('',#105282,1.); +#105282 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105283 = PCURVE('',#105207,#105284); +#105284 = DEFINITIONAL_REPRESENTATION('',(#105285),#105289); +#105285 = LINE('',#105286,#105287); +#105286 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105287 = VECTOR('',#105288,1.); +#105288 = DIRECTION('',(-1.,0.E+000)); +#105289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105290 = PCURVE('',#105291,#105296); +#105291 = CYLINDRICAL_SURFACE('',#105292,0.308574064194); +#105292 = AXIS2_PLACEMENT_3D('',#105293,#105294,#105295); +#105293 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#105294 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105295 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105296 = DEFINITIONAL_REPRESENTATION('',(#105297),#105300); +#105297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105298,#105299), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#102906 = CARTESIAN_POINT('',(3.191025391152,3.85)); -#102907 = CARTESIAN_POINT('',(3.191025391152,3.65)); -#102908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102909 = ADVANCED_FACE('',(#102910),#102924,.T.); -#102910 = FACE_BOUND('',#102911,.T.); -#102911 = EDGE_LOOP('',(#102912,#102942,#102965,#102988)); -#102912 = ORIENTED_EDGE('',*,*,#102913,.T.); -#102913 = EDGE_CURVE('',#102914,#102916,#102918,.T.); -#102914 = VERTEX_POINT('',#102915); -#102915 = CARTESIAN_POINT('',(6.15,-0.740726081328,-0.208196358798)); -#102916 = VERTEX_POINT('',#102917); -#102917 = CARTESIAN_POINT('',(6.15,-1.,-0.208196358798)); -#102918 = SURFACE_CURVE('',#102919,(#102923,#102935),.PCURVE_S1.); -#102919 = LINE('',#102920,#102921); -#102920 = CARTESIAN_POINT('',(6.15,-0.740726081328,-0.208196358798)); -#102921 = VECTOR('',#102922,1.); -#102922 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102923 = PCURVE('',#102924,#102929); -#102924 = PLANE('',#102925); -#102925 = AXIS2_PLACEMENT_3D('',#102926,#102927,#102928); -#102926 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#102927 = DIRECTION('',(0.E+000,0.E+000,1.)); -#102928 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102929 = DEFINITIONAL_REPRESENTATION('',(#102930),#102934); -#102930 = LINE('',#102931,#102932); -#102931 = CARTESIAN_POINT('',(-3.85,0.E+000)); -#102932 = VECTOR('',#102933,1.); -#102933 = DIRECTION('',(0.E+000,-1.)); -#102934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102935 = PCURVE('',#88644,#102936); -#102936 = DEFINITIONAL_REPRESENTATION('',(#102937),#102941); -#102937 = LINE('',#102938,#102939); -#102938 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#102939 = VECTOR('',#102940,1.); -#102940 = DIRECTION('',(0.E+000,-1.)); -#102941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102942 = ORIENTED_EDGE('',*,*,#102943,.T.); -#102943 = EDGE_CURVE('',#102916,#102944,#102946,.T.); -#102944 = VERTEX_POINT('',#102945); -#102945 = CARTESIAN_POINT('',(6.35,-1.,-0.208196358798)); -#102946 = SURFACE_CURVE('',#102947,(#102951,#102958),.PCURVE_S1.); -#102947 = LINE('',#102948,#102949); -#102948 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#102949 = VECTOR('',#102950,1.); -#102950 = DIRECTION('',(1.,0.E+000,0.E+000)); -#102951 = PCURVE('',#102924,#102952); -#102952 = DEFINITIONAL_REPRESENTATION('',(#102953),#102957); -#102953 = LINE('',#102954,#102955); -#102954 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#102955 = VECTOR('',#102956,1.); -#102956 = DIRECTION('',(1.,0.E+000)); -#102957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102958 = PCURVE('',#102850,#102959); -#102959 = DEFINITIONAL_REPRESENTATION('',(#102960),#102964); -#102960 = LINE('',#102961,#102962); -#102961 = CARTESIAN_POINT('',(-5.000038352949E-002,3.75)); -#102962 = VECTOR('',#102963,1.); -#102963 = DIRECTION('',(0.E+000,1.)); -#102964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102965 = ORIENTED_EDGE('',*,*,#102966,.F.); -#102966 = EDGE_CURVE('',#102967,#102944,#102969,.T.); -#102967 = VERTEX_POINT('',#102968); -#102968 = CARTESIAN_POINT('',(6.35,-0.740726081328,-0.208196358798)); -#102969 = SURFACE_CURVE('',#102970,(#102974,#102981),.PCURVE_S1.); -#102970 = LINE('',#102971,#102972); -#102971 = CARTESIAN_POINT('',(6.35,-0.740726081328,-0.208196358798)); -#102972 = VECTOR('',#102973,1.); -#102973 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#102974 = PCURVE('',#102924,#102975); -#102975 = DEFINITIONAL_REPRESENTATION('',(#102976),#102980); -#102976 = LINE('',#102977,#102978); -#102977 = CARTESIAN_POINT('',(-3.65,0.E+000)); -#102978 = VECTOR('',#102979,1.); -#102979 = DIRECTION('',(0.E+000,-1.)); -#102980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102981 = PCURVE('',#88700,#102982); -#102982 = DEFINITIONAL_REPRESENTATION('',(#102983),#102987); -#102983 = LINE('',#102984,#102985); -#102984 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#102985 = VECTOR('',#102986,1.); -#102986 = DIRECTION('',(0.E+000,-1.)); -#102987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#102988 = ORIENTED_EDGE('',*,*,#102989,.T.); -#102989 = EDGE_CURVE('',#102967,#102914,#102990,.T.); -#102990 = SURFACE_CURVE('',#102991,(#102995,#103002),.PCURVE_S1.); -#102991 = LINE('',#102992,#102993); -#102992 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#102993 = VECTOR('',#102994,1.); -#102994 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#102995 = PCURVE('',#102924,#102996); -#102996 = DEFINITIONAL_REPRESENTATION('',(#102997),#103001); -#102997 = LINE('',#102998,#102999); -#102998 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#102999 = VECTOR('',#103000,1.); -#103000 = DIRECTION('',(-1.,0.E+000)); -#103001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103002 = PCURVE('',#103003,#103008); -#103003 = CYLINDRICAL_SURFACE('',#103004,0.208574704164); -#103004 = AXIS2_PLACEMENT_3D('',#103005,#103006,#103007); -#103005 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#103006 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103007 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103008 = DEFINITIONAL_REPRESENTATION('',(#103009),#103012); -#103009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103010,#103011), +#105298 = CARTESIAN_POINT('',(3.191025391152,3.85)); +#105299 = CARTESIAN_POINT('',(3.191025391152,3.65)); +#105300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105301 = ADVANCED_FACE('',(#105302),#105316,.T.); +#105302 = FACE_BOUND('',#105303,.T.); +#105303 = EDGE_LOOP('',(#105304,#105334,#105357,#105380)); +#105304 = ORIENTED_EDGE('',*,*,#105305,.T.); +#105305 = EDGE_CURVE('',#105306,#105308,#105310,.T.); +#105306 = VERTEX_POINT('',#105307); +#105307 = CARTESIAN_POINT('',(6.15,-0.740726081328,-0.208196358798)); +#105308 = VERTEX_POINT('',#105309); +#105309 = CARTESIAN_POINT('',(6.15,-1.,-0.208196358798)); +#105310 = SURFACE_CURVE('',#105311,(#105315,#105327),.PCURVE_S1.); +#105311 = LINE('',#105312,#105313); +#105312 = CARTESIAN_POINT('',(6.15,-0.740726081328,-0.208196358798)); +#105313 = VECTOR('',#105314,1.); +#105314 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#105315 = PCURVE('',#105316,#105321); +#105316 = PLANE('',#105317); +#105317 = AXIS2_PLACEMENT_3D('',#105318,#105319,#105320); +#105318 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#105319 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105320 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105321 = DEFINITIONAL_REPRESENTATION('',(#105322),#105326); +#105322 = LINE('',#105323,#105324); +#105323 = CARTESIAN_POINT('',(-3.85,0.E+000)); +#105324 = VECTOR('',#105325,1.); +#105325 = DIRECTION('',(0.E+000,-1.)); +#105326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105327 = PCURVE('',#91036,#105328); +#105328 = DEFINITIONAL_REPRESENTATION('',(#105329),#105333); +#105329 = LINE('',#105330,#105331); +#105330 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#105331 = VECTOR('',#105332,1.); +#105332 = DIRECTION('',(0.E+000,-1.)); +#105333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105334 = ORIENTED_EDGE('',*,*,#105335,.T.); +#105335 = EDGE_CURVE('',#105308,#105336,#105338,.T.); +#105336 = VERTEX_POINT('',#105337); +#105337 = CARTESIAN_POINT('',(6.35,-1.,-0.208196358798)); +#105338 = SURFACE_CURVE('',#105339,(#105343,#105350),.PCURVE_S1.); +#105339 = LINE('',#105340,#105341); +#105340 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#105341 = VECTOR('',#105342,1.); +#105342 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105343 = PCURVE('',#105316,#105344); +#105344 = DEFINITIONAL_REPRESENTATION('',(#105345),#105349); +#105345 = LINE('',#105346,#105347); +#105346 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#105347 = VECTOR('',#105348,1.); +#105348 = DIRECTION('',(1.,0.E+000)); +#105349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105350 = PCURVE('',#105242,#105351); +#105351 = DEFINITIONAL_REPRESENTATION('',(#105352),#105356); +#105352 = LINE('',#105353,#105354); +#105353 = CARTESIAN_POINT('',(-5.000038352949E-002,3.75)); +#105354 = VECTOR('',#105355,1.); +#105355 = DIRECTION('',(0.E+000,1.)); +#105356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105357 = ORIENTED_EDGE('',*,*,#105358,.F.); +#105358 = EDGE_CURVE('',#105359,#105336,#105361,.T.); +#105359 = VERTEX_POINT('',#105360); +#105360 = CARTESIAN_POINT('',(6.35,-0.740726081328,-0.208196358798)); +#105361 = SURFACE_CURVE('',#105362,(#105366,#105373),.PCURVE_S1.); +#105362 = LINE('',#105363,#105364); +#105363 = CARTESIAN_POINT('',(6.35,-0.740726081328,-0.208196358798)); +#105364 = VECTOR('',#105365,1.); +#105365 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#105366 = PCURVE('',#105316,#105367); +#105367 = DEFINITIONAL_REPRESENTATION('',(#105368),#105372); +#105368 = LINE('',#105369,#105370); +#105369 = CARTESIAN_POINT('',(-3.65,0.E+000)); +#105370 = VECTOR('',#105371,1.); +#105371 = DIRECTION('',(0.E+000,-1.)); +#105372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105373 = PCURVE('',#91092,#105374); +#105374 = DEFINITIONAL_REPRESENTATION('',(#105375),#105379); +#105375 = LINE('',#105376,#105377); +#105376 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#105377 = VECTOR('',#105378,1.); +#105378 = DIRECTION('',(0.E+000,-1.)); +#105379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105380 = ORIENTED_EDGE('',*,*,#105381,.T.); +#105381 = EDGE_CURVE('',#105359,#105306,#105382,.T.); +#105382 = SURFACE_CURVE('',#105383,(#105387,#105394),.PCURVE_S1.); +#105383 = LINE('',#105384,#105385); +#105384 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#105385 = VECTOR('',#105386,1.); +#105386 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105387 = PCURVE('',#105316,#105388); +#105388 = DEFINITIONAL_REPRESENTATION('',(#105389),#105393); +#105389 = LINE('',#105390,#105391); +#105390 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105391 = VECTOR('',#105392,1.); +#105392 = DIRECTION('',(-1.,0.E+000)); +#105393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105394 = PCURVE('',#105395,#105400); +#105395 = CYLINDRICAL_SURFACE('',#105396,0.208574704164); +#105396 = AXIS2_PLACEMENT_3D('',#105397,#105398,#105399); +#105397 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#105398 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105399 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105400 = DEFINITIONAL_REPRESENTATION('',(#105401),#105404); +#105401 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105402,#105403), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#103010 = CARTESIAN_POINT('',(3.201833915432,3.65)); -#103011 = CARTESIAN_POINT('',(3.201833915432,3.85)); -#103012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103013 = ADVANCED_FACE('',(#103014),#102899,.T.); -#103014 = FACE_BOUND('',#103015,.T.); -#103015 = EDGE_LOOP('',(#103016,#103017,#103044,#103071)); -#103016 = ORIENTED_EDGE('',*,*,#102885,.F.); -#103017 = ORIENTED_EDGE('',*,*,#103018,.F.); -#103018 = EDGE_CURVE('',#103019,#102863,#103021,.T.); -#103019 = VERTEX_POINT('',#103020); -#103020 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.E+000)); -#103021 = SURFACE_CURVE('',#103022,(#103027,#103033),.PCURVE_S1.); -#103022 = CIRCLE('',#103023,0.308574064194); -#103023 = AXIS2_PLACEMENT_3D('',#103024,#103025,#103026); -#103024 = CARTESIAN_POINT('',(6.15,-0.728168876214,2.640924866458E-017) - ); -#103025 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103026 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103027 = PCURVE('',#102899,#103028); -#103028 = DEFINITIONAL_REPRESENTATION('',(#103029),#103032); -#103029 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103030,#103031), +#105402 = CARTESIAN_POINT('',(3.201833915432,3.65)); +#105403 = CARTESIAN_POINT('',(3.201833915432,3.85)); +#105404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105405 = ADVANCED_FACE('',(#105406),#105291,.T.); +#105406 = FACE_BOUND('',#105407,.T.); +#105407 = EDGE_LOOP('',(#105408,#105409,#105436,#105463)); +#105408 = ORIENTED_EDGE('',*,*,#105277,.F.); +#105409 = ORIENTED_EDGE('',*,*,#105410,.F.); +#105410 = EDGE_CURVE('',#105411,#105255,#105413,.T.); +#105411 = VERTEX_POINT('',#105412); +#105412 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.E+000)); +#105413 = SURFACE_CURVE('',#105414,(#105419,#105425),.PCURVE_S1.); +#105414 = CIRCLE('',#105415,0.308574064194); +#105415 = AXIS2_PLACEMENT_3D('',#105416,#105417,#105418); +#105416 = CARTESIAN_POINT('',(6.15,-0.728168876214,2.640924866458E-017) + ); +#105417 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105418 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105419 = PCURVE('',#105291,#105420); +#105420 = DEFINITIONAL_REPRESENTATION('',(#105421),#105424); +#105421 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105422,#105423), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#103030 = CARTESIAN_POINT('',(1.570796326795,3.85)); -#103031 = CARTESIAN_POINT('',(3.191025391152,3.85)); -#103032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105422 = CARTESIAN_POINT('',(1.570796326795,3.85)); +#105423 = CARTESIAN_POINT('',(3.191025391152,3.85)); +#105424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103033 = PCURVE('',#88644,#103034); -#103034 = DEFINITIONAL_REPRESENTATION('',(#103035),#103043); -#103035 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103036,#103037,#103038, - #103039,#103040,#103041,#103042),.UNSPECIFIED.,.T.,.F.) +#105425 = PCURVE('',#91036,#105426); +#105426 = DEFINITIONAL_REPRESENTATION('',(#105427),#105435); +#105427 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105428,#105429,#105430, + #105431,#105432,#105433,#105434),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103036 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#103037 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#103038 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#103039 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#103040 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#103041 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#103042 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#103043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103044 = ORIENTED_EDGE('',*,*,#103045,.F.); -#103045 = EDGE_CURVE('',#103046,#103019,#103048,.T.); -#103046 = VERTEX_POINT('',#103047); -#103047 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.E+000)); -#103048 = SURFACE_CURVE('',#103049,(#103053,#103059),.PCURVE_S1.); -#103049 = LINE('',#103050,#103051); -#103050 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#103051 = VECTOR('',#103052,1.); -#103052 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103053 = PCURVE('',#102899,#103054); -#103054 = DEFINITIONAL_REPRESENTATION('',(#103055),#103058); -#103055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103056,#103057), +#105428 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#105429 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#105430 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#105431 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#105432 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#105433 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#105434 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#105435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105436 = ORIENTED_EDGE('',*,*,#105437,.F.); +#105437 = EDGE_CURVE('',#105438,#105411,#105440,.T.); +#105438 = VERTEX_POINT('',#105439); +#105439 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.E+000)); +#105440 = SURFACE_CURVE('',#105441,(#105445,#105451),.PCURVE_S1.); +#105441 = LINE('',#105442,#105443); +#105442 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#105443 = VECTOR('',#105444,1.); +#105444 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105445 = PCURVE('',#105291,#105446); +#105446 = DEFINITIONAL_REPRESENTATION('',(#105447),#105450); +#105447 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105448,#105449), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#103056 = CARTESIAN_POINT('',(1.570796326795,3.65)); -#103057 = CARTESIAN_POINT('',(1.570796326795,3.85)); -#103058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103059 = PCURVE('',#103060,#103065); -#103060 = PLANE('',#103061); -#103061 = AXIS2_PLACEMENT_3D('',#103062,#103063,#103064); -#103062 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#103063 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#103064 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103065 = DEFINITIONAL_REPRESENTATION('',(#103066),#103070); -#103066 = LINE('',#103067,#103068); -#103067 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#103068 = VECTOR('',#103069,1.); -#103069 = DIRECTION('',(0.E+000,-1.)); -#103070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103071 = ORIENTED_EDGE('',*,*,#103072,.T.); -#103072 = EDGE_CURVE('',#103046,#102805,#103073,.T.); -#103073 = SURFACE_CURVE('',#103074,(#103079,#103085),.PCURVE_S1.); -#103074 = CIRCLE('',#103075,0.308574064194); -#103075 = AXIS2_PLACEMENT_3D('',#103076,#103077,#103078); -#103076 = CARTESIAN_POINT('',(6.35,-0.728168876214,2.640924866458E-017) - ); -#103077 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103078 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103079 = PCURVE('',#102899,#103080); -#103080 = DEFINITIONAL_REPRESENTATION('',(#103081),#103084); -#103081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103082,#103083), +#105448 = CARTESIAN_POINT('',(1.570796326795,3.65)); +#105449 = CARTESIAN_POINT('',(1.570796326795,3.85)); +#105450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105451 = PCURVE('',#105452,#105457); +#105452 = PLANE('',#105453); +#105453 = AXIS2_PLACEMENT_3D('',#105454,#105455,#105456); +#105454 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#105455 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#105456 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#105457 = DEFINITIONAL_REPRESENTATION('',(#105458),#105462); +#105458 = LINE('',#105459,#105460); +#105459 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#105460 = VECTOR('',#105461,1.); +#105461 = DIRECTION('',(0.E+000,-1.)); +#105462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105463 = ORIENTED_EDGE('',*,*,#105464,.T.); +#105464 = EDGE_CURVE('',#105438,#105197,#105465,.T.); +#105465 = SURFACE_CURVE('',#105466,(#105471,#105477),.PCURVE_S1.); +#105466 = CIRCLE('',#105467,0.308574064194); +#105467 = AXIS2_PLACEMENT_3D('',#105468,#105469,#105470); +#105468 = CARTESIAN_POINT('',(6.35,-0.728168876214,2.640924866458E-017) + ); +#105469 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105470 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105471 = PCURVE('',#105291,#105472); +#105472 = DEFINITIONAL_REPRESENTATION('',(#105473),#105476); +#105473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105474,#105475), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#103082 = CARTESIAN_POINT('',(1.570796326795,3.65)); -#103083 = CARTESIAN_POINT('',(3.191025391152,3.65)); -#103084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103085 = PCURVE('',#88700,#103086); -#103086 = DEFINITIONAL_REPRESENTATION('',(#103087),#103091); -#103087 = CIRCLE('',#103088,0.308574064194); -#103088 = AXIS2_PLACEMENT_2D('',#103089,#103090); -#103089 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#103090 = DIRECTION('',(1.,0.E+000)); -#103091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103092 = ADVANCED_FACE('',(#103093),#103003,.F.); -#103093 = FACE_BOUND('',#103094,.F.); -#103094 = EDGE_LOOP('',(#103095,#103096,#103123,#103150)); -#103095 = ORIENTED_EDGE('',*,*,#102989,.T.); -#103096 = ORIENTED_EDGE('',*,*,#103097,.F.); -#103097 = EDGE_CURVE('',#103098,#102914,#103100,.T.); -#103098 = VERTEX_POINT('',#103099); -#103099 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.E+000)); -#103100 = SURFACE_CURVE('',#103101,(#103106,#103112),.PCURVE_S1.); -#103101 = CIRCLE('',#103102,0.208574704164); -#103102 = AXIS2_PLACEMENT_3D('',#103103,#103104,#103105); -#103103 = CARTESIAN_POINT('',(6.15,-0.728168876214,2.640924866458E-017) - ); -#103104 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103105 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103106 = PCURVE('',#103003,#103107); -#103107 = DEFINITIONAL_REPRESENTATION('',(#103108),#103111); -#103108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103109,#103110), +#105474 = CARTESIAN_POINT('',(1.570796326795,3.65)); +#105475 = CARTESIAN_POINT('',(3.191025391152,3.65)); +#105476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105477 = PCURVE('',#91092,#105478); +#105478 = DEFINITIONAL_REPRESENTATION('',(#105479),#105483); +#105479 = CIRCLE('',#105480,0.308574064194); +#105480 = AXIS2_PLACEMENT_2D('',#105481,#105482); +#105481 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#105482 = DIRECTION('',(1.,0.E+000)); +#105483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105484 = ADVANCED_FACE('',(#105485),#105395,.F.); +#105485 = FACE_BOUND('',#105486,.F.); +#105486 = EDGE_LOOP('',(#105487,#105488,#105515,#105542)); +#105487 = ORIENTED_EDGE('',*,*,#105381,.T.); +#105488 = ORIENTED_EDGE('',*,*,#105489,.F.); +#105489 = EDGE_CURVE('',#105490,#105306,#105492,.T.); +#105490 = VERTEX_POINT('',#105491); +#105491 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.E+000)); +#105492 = SURFACE_CURVE('',#105493,(#105498,#105504),.PCURVE_S1.); +#105493 = CIRCLE('',#105494,0.208574704164); +#105494 = AXIS2_PLACEMENT_3D('',#105495,#105496,#105497); +#105495 = CARTESIAN_POINT('',(6.15,-0.728168876214,2.640924866458E-017) + ); +#105496 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105497 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105498 = PCURVE('',#105395,#105499); +#105499 = DEFINITIONAL_REPRESENTATION('',(#105500),#105503); +#105500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105501,#105502), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#103109 = CARTESIAN_POINT('',(1.570796326795,3.85)); -#103110 = CARTESIAN_POINT('',(3.201833915432,3.85)); -#103111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105501 = CARTESIAN_POINT('',(1.570796326795,3.85)); +#105502 = CARTESIAN_POINT('',(3.201833915432,3.85)); +#105503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103112 = PCURVE('',#88644,#103113); -#103113 = DEFINITIONAL_REPRESENTATION('',(#103114),#103122); -#103114 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103115,#103116,#103117, - #103118,#103119,#103120,#103121),.UNSPECIFIED.,.F.,.F.) +#105504 = PCURVE('',#91036,#105505); +#105505 = DEFINITIONAL_REPRESENTATION('',(#105506),#105514); +#105506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105507,#105508,#105509, + #105510,#105511,#105512,#105513),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103115 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#103116 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#103117 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#103118 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#103119 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#103120 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#103121 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#103122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103123 = ORIENTED_EDGE('',*,*,#103124,.T.); -#103124 = EDGE_CURVE('',#103098,#103125,#103127,.T.); -#103125 = VERTEX_POINT('',#103126); -#103126 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.E+000)); -#103127 = SURFACE_CURVE('',#103128,(#103132,#103138),.PCURVE_S1.); -#103128 = LINE('',#103129,#103130); -#103129 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#103130 = VECTOR('',#103131,1.); -#103131 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103132 = PCURVE('',#103003,#103133); -#103133 = DEFINITIONAL_REPRESENTATION('',(#103134),#103137); -#103134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103135,#103136), +#105507 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#105508 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#105509 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#105510 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#105511 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#105512 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#105513 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#105514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105515 = ORIENTED_EDGE('',*,*,#105516,.T.); +#105516 = EDGE_CURVE('',#105490,#105517,#105519,.T.); +#105517 = VERTEX_POINT('',#105518); +#105518 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.E+000)); +#105519 = SURFACE_CURVE('',#105520,(#105524,#105530),.PCURVE_S1.); +#105520 = LINE('',#105521,#105522); +#105521 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#105522 = VECTOR('',#105523,1.); +#105523 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105524 = PCURVE('',#105395,#105525); +#105525 = DEFINITIONAL_REPRESENTATION('',(#105526),#105529); +#105526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105527,#105528), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#103135 = CARTESIAN_POINT('',(1.570796326795,3.85)); -#103136 = CARTESIAN_POINT('',(1.570796326795,3.65)); -#103137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103138 = PCURVE('',#103139,#103144); -#103139 = PLANE('',#103140); -#103140 = AXIS2_PLACEMENT_3D('',#103141,#103142,#103143); -#103141 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#103142 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#103143 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#103144 = DEFINITIONAL_REPRESENTATION('',(#103145),#103149); -#103145 = LINE('',#103146,#103147); -#103146 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#103147 = VECTOR('',#103148,1.); -#103148 = DIRECTION('',(0.E+000,1.)); -#103149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103150 = ORIENTED_EDGE('',*,*,#103151,.T.); -#103151 = EDGE_CURVE('',#103125,#102967,#103152,.T.); -#103152 = SURFACE_CURVE('',#103153,(#103158,#103164),.PCURVE_S1.); -#103153 = CIRCLE('',#103154,0.208574704164); -#103154 = AXIS2_PLACEMENT_3D('',#103155,#103156,#103157); -#103155 = CARTESIAN_POINT('',(6.35,-0.728168876214,2.640924866458E-017) - ); -#103156 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103157 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103158 = PCURVE('',#103003,#103159); -#103159 = DEFINITIONAL_REPRESENTATION('',(#103160),#103163); -#103160 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103161,#103162), +#105527 = CARTESIAN_POINT('',(1.570796326795,3.85)); +#105528 = CARTESIAN_POINT('',(1.570796326795,3.65)); +#105529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105530 = PCURVE('',#105531,#105536); +#105531 = PLANE('',#105532); +#105532 = AXIS2_PLACEMENT_3D('',#105533,#105534,#105535); +#105533 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#105534 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#105535 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#105536 = DEFINITIONAL_REPRESENTATION('',(#105537),#105541); +#105537 = LINE('',#105538,#105539); +#105538 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#105539 = VECTOR('',#105540,1.); +#105540 = DIRECTION('',(0.E+000,1.)); +#105541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105542 = ORIENTED_EDGE('',*,*,#105543,.T.); +#105543 = EDGE_CURVE('',#105517,#105359,#105544,.T.); +#105544 = SURFACE_CURVE('',#105545,(#105550,#105556),.PCURVE_S1.); +#105545 = CIRCLE('',#105546,0.208574704164); +#105546 = AXIS2_PLACEMENT_3D('',#105547,#105548,#105549); +#105547 = CARTESIAN_POINT('',(6.35,-0.728168876214,2.640924866458E-017) + ); +#105548 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105549 = DIRECTION('',(0.E+000,0.E+000,1.)); +#105550 = PCURVE('',#105395,#105551); +#105551 = DEFINITIONAL_REPRESENTATION('',(#105552),#105555); +#105552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105553,#105554), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#103161 = CARTESIAN_POINT('',(1.570796326795,3.65)); -#103162 = CARTESIAN_POINT('',(3.201833915432,3.65)); -#103163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105553 = CARTESIAN_POINT('',(1.570796326795,3.65)); +#105554 = CARTESIAN_POINT('',(3.201833915432,3.65)); +#105555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105556 = PCURVE('',#91092,#105557); +#105557 = DEFINITIONAL_REPRESENTATION('',(#105558),#105562); +#105558 = CIRCLE('',#105559,0.208574704164); +#105559 = AXIS2_PLACEMENT_2D('',#105560,#105561); +#105560 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#105561 = DIRECTION('',(1.,0.E+000)); +#105562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105563 = ADVANCED_FACE('',(#105564),#105531,.F.); +#105564 = FACE_BOUND('',#105565,.T.); +#105565 = EDGE_LOOP('',(#105566,#105595,#105616,#105617)); +#105566 = ORIENTED_EDGE('',*,*,#105567,.F.); +#105567 = EDGE_CURVE('',#105568,#105570,#105572,.T.); +#105568 = VERTEX_POINT('',#105569); +#105569 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.530776333563)); +#105570 = VERTEX_POINT('',#105571); +#105571 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.530776333563)); +#105572 = SURFACE_CURVE('',#105573,(#105577,#105584),.PCURVE_S1.); +#105573 = LINE('',#105574,#105575); +#105574 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#105575 = VECTOR('',#105576,1.); +#105576 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105577 = PCURVE('',#105531,#105578); +#105578 = DEFINITIONAL_REPRESENTATION('',(#105579),#105583); +#105579 = LINE('',#105580,#105581); +#105580 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105581 = VECTOR('',#105582,1.); +#105582 = DIRECTION('',(0.E+000,1.)); +#105583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105584 = PCURVE('',#105585,#105590); +#105585 = CYLINDRICAL_SURFACE('',#105586,0.2192697516); +#105586 = AXIS2_PLACEMENT_3D('',#105587,#105588,#105589); +#105587 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#105588 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105589 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105590 = DEFINITIONAL_REPRESENTATION('',(#105591),#105594); +#105591 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105592,#105593), + .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); +#105592 = CARTESIAN_POINT('',(4.712388980385,-3.85)); +#105593 = CARTESIAN_POINT('',(4.712388980385,-3.65)); +#105594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105595 = ORIENTED_EDGE('',*,*,#105596,.T.); +#105596 = EDGE_CURVE('',#105568,#105490,#105597,.T.); +#105597 = SURFACE_CURVE('',#105598,(#105602,#105609),.PCURVE_S1.); +#105598 = LINE('',#105599,#105600); +#105599 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.530776333563)); +#105600 = VECTOR('',#105601,1.); +#105601 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#105602 = PCURVE('',#105531,#105603); +#105603 = DEFINITIONAL_REPRESENTATION('',(#105604),#105608); +#105604 = LINE('',#105605,#105606); +#105605 = CARTESIAN_POINT('',(0.E+000,-3.85)); +#105606 = VECTOR('',#105607,1.); +#105607 = DIRECTION('',(-1.,0.E+000)); +#105608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105609 = PCURVE('',#91036,#105610); +#105610 = DEFINITIONAL_REPRESENTATION('',(#105611),#105615); +#105611 = LINE('',#105612,#105613); +#105612 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#105613 = VECTOR('',#105614,1.); +#105614 = DIRECTION('',(1.,-1.021336205033E-016)); +#105615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105616 = ORIENTED_EDGE('',*,*,#105516,.T.); +#105617 = ORIENTED_EDGE('',*,*,#105618,.F.); +#105618 = EDGE_CURVE('',#105570,#105517,#105619,.T.); +#105619 = SURFACE_CURVE('',#105620,(#105624,#105631),.PCURVE_S1.); +#105620 = LINE('',#105621,#105622); +#105621 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.530776333563)); +#105622 = VECTOR('',#105623,1.); +#105623 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#105624 = PCURVE('',#105531,#105625); +#105625 = DEFINITIONAL_REPRESENTATION('',(#105626),#105630); +#105626 = LINE('',#105627,#105628); +#105627 = CARTESIAN_POINT('',(0.E+000,-3.65)); +#105628 = VECTOR('',#105629,1.); +#105629 = DIRECTION('',(-1.,0.E+000)); +#105630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105631 = PCURVE('',#91092,#105632); +#105632 = DEFINITIONAL_REPRESENTATION('',(#105633),#105637); +#105633 = LINE('',#105634,#105635); +#105634 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#105635 = VECTOR('',#105636,1.); +#105636 = DIRECTION('',(-1.,-1.021336205033E-016)); +#105637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105638 = ADVANCED_FACE('',(#105639),#105452,.F.); +#105639 = FACE_BOUND('',#105640,.T.); +#105640 = EDGE_LOOP('',(#105641,#105670,#105691,#105692)); +#105641 = ORIENTED_EDGE('',*,*,#105642,.F.); +#105642 = EDGE_CURVE('',#105643,#105645,#105647,.T.); +#105643 = VERTEX_POINT('',#105644); +#105644 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.530776333563)); +#105645 = VERTEX_POINT('',#105646); +#105646 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.530776333563)); +#105647 = SURFACE_CURVE('',#105648,(#105652,#105659),.PCURVE_S1.); +#105648 = LINE('',#105649,#105650); +#105649 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#105650 = VECTOR('',#105651,1.); +#105651 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105652 = PCURVE('',#105452,#105653); +#105653 = DEFINITIONAL_REPRESENTATION('',(#105654),#105658); +#105654 = LINE('',#105655,#105656); +#105655 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105656 = VECTOR('',#105657,1.); +#105657 = DIRECTION('',(0.E+000,-1.)); +#105658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105659 = PCURVE('',#105660,#105665); +#105660 = CYLINDRICAL_SURFACE('',#105661,0.119270391569); +#105661 = AXIS2_PLACEMENT_3D('',#105662,#105663,#105664); +#105662 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#105663 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105664 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105665 = DEFINITIONAL_REPRESENTATION('',(#105666),#105669); +#105666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105667,#105668), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); +#105667 = CARTESIAN_POINT('',(4.712388980385,-3.65)); +#105668 = CARTESIAN_POINT('',(4.712388980385,-3.85)); +#105669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103164 = PCURVE('',#88700,#103165); -#103165 = DEFINITIONAL_REPRESENTATION('',(#103166),#103170); -#103166 = CIRCLE('',#103167,0.208574704164); -#103167 = AXIS2_PLACEMENT_2D('',#103168,#103169); -#103168 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#103169 = DIRECTION('',(1.,0.E+000)); -#103170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105670 = ORIENTED_EDGE('',*,*,#105671,.T.); +#105671 = EDGE_CURVE('',#105643,#105438,#105672,.T.); +#105672 = SURFACE_CURVE('',#105673,(#105677,#105684),.PCURVE_S1.); +#105673 = LINE('',#105674,#105675); +#105674 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.530776333563)); +#105675 = VECTOR('',#105676,1.); +#105676 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#105677 = PCURVE('',#105452,#105678); +#105678 = DEFINITIONAL_REPRESENTATION('',(#105679),#105683); +#105679 = LINE('',#105680,#105681); +#105680 = CARTESIAN_POINT('',(0.E+000,-3.65)); +#105681 = VECTOR('',#105682,1.); +#105682 = DIRECTION('',(1.,0.E+000)); +#105683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103171 = ADVANCED_FACE('',(#103172),#103139,.F.); -#103172 = FACE_BOUND('',#103173,.T.); -#103173 = EDGE_LOOP('',(#103174,#103203,#103224,#103225)); -#103174 = ORIENTED_EDGE('',*,*,#103175,.F.); -#103175 = EDGE_CURVE('',#103176,#103178,#103180,.T.); -#103176 = VERTEX_POINT('',#103177); -#103177 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.530776333563)); -#103178 = VERTEX_POINT('',#103179); -#103179 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.530776333563)); -#103180 = SURFACE_CURVE('',#103181,(#103185,#103192),.PCURVE_S1.); -#103181 = LINE('',#103182,#103183); -#103182 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#103183 = VECTOR('',#103184,1.); -#103184 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103185 = PCURVE('',#103139,#103186); -#103186 = DEFINITIONAL_REPRESENTATION('',(#103187),#103191); -#103187 = LINE('',#103188,#103189); -#103188 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103189 = VECTOR('',#103190,1.); -#103190 = DIRECTION('',(0.E+000,1.)); -#103191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103192 = PCURVE('',#103193,#103198); -#103193 = CYLINDRICAL_SURFACE('',#103194,0.2192697516); -#103194 = AXIS2_PLACEMENT_3D('',#103195,#103196,#103197); -#103195 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#103196 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103197 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103198 = DEFINITIONAL_REPRESENTATION('',(#103199),#103202); -#103199 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103200,#103201), - .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#103200 = CARTESIAN_POINT('',(4.712388980385,-3.85)); -#103201 = CARTESIAN_POINT('',(4.712388980385,-3.65)); -#103202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103203 = ORIENTED_EDGE('',*,*,#103204,.T.); -#103204 = EDGE_CURVE('',#103176,#103098,#103205,.T.); -#103205 = SURFACE_CURVE('',#103206,(#103210,#103217),.PCURVE_S1.); -#103206 = LINE('',#103207,#103208); -#103207 = CARTESIAN_POINT('',(6.15,-0.51959417205,0.530776333563)); -#103208 = VECTOR('',#103209,1.); -#103209 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103210 = PCURVE('',#103139,#103211); -#103211 = DEFINITIONAL_REPRESENTATION('',(#103212),#103216); -#103212 = LINE('',#103213,#103214); -#103213 = CARTESIAN_POINT('',(0.E+000,-3.85)); -#103214 = VECTOR('',#103215,1.); -#103215 = DIRECTION('',(-1.,0.E+000)); -#103216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103217 = PCURVE('',#88644,#103218); -#103218 = DEFINITIONAL_REPRESENTATION('',(#103219),#103223); -#103219 = LINE('',#103220,#103221); -#103220 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#103221 = VECTOR('',#103222,1.); -#103222 = DIRECTION('',(1.,-1.021336205033E-016)); -#103223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103224 = ORIENTED_EDGE('',*,*,#103124,.T.); -#103225 = ORIENTED_EDGE('',*,*,#103226,.F.); -#103226 = EDGE_CURVE('',#103178,#103125,#103227,.T.); -#103227 = SURFACE_CURVE('',#103228,(#103232,#103239),.PCURVE_S1.); -#103228 = LINE('',#103229,#103230); -#103229 = CARTESIAN_POINT('',(6.35,-0.51959417205,0.530776333563)); -#103230 = VECTOR('',#103231,1.); -#103231 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103232 = PCURVE('',#103139,#103233); -#103233 = DEFINITIONAL_REPRESENTATION('',(#103234),#103238); -#103234 = LINE('',#103235,#103236); -#103235 = CARTESIAN_POINT('',(0.E+000,-3.65)); -#103236 = VECTOR('',#103237,1.); -#103237 = DIRECTION('',(-1.,0.E+000)); -#103238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103239 = PCURVE('',#88700,#103240); -#103240 = DEFINITIONAL_REPRESENTATION('',(#103241),#103245); -#103241 = LINE('',#103242,#103243); -#103242 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#103243 = VECTOR('',#103244,1.); -#103244 = DIRECTION('',(-1.,-1.021336205033E-016)); -#103245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103246 = ADVANCED_FACE('',(#103247),#103060,.F.); -#103247 = FACE_BOUND('',#103248,.T.); -#103248 = EDGE_LOOP('',(#103249,#103278,#103299,#103300)); -#103249 = ORIENTED_EDGE('',*,*,#103250,.F.); -#103250 = EDGE_CURVE('',#103251,#103253,#103255,.T.); -#103251 = VERTEX_POINT('',#103252); -#103252 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.530776333563)); -#103253 = VERTEX_POINT('',#103254); -#103254 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.530776333563)); -#103255 = SURFACE_CURVE('',#103256,(#103260,#103267),.PCURVE_S1.); -#103256 = LINE('',#103257,#103258); -#103257 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#103258 = VECTOR('',#103259,1.); -#103259 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103260 = PCURVE('',#103060,#103261); -#103261 = DEFINITIONAL_REPRESENTATION('',(#103262),#103266); -#103262 = LINE('',#103263,#103264); -#103263 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103264 = VECTOR('',#103265,1.); -#103265 = DIRECTION('',(0.E+000,-1.)); -#103266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103267 = PCURVE('',#103268,#103273); -#103268 = CYLINDRICAL_SURFACE('',#103269,0.119270391569); -#103269 = AXIS2_PLACEMENT_3D('',#103270,#103271,#103272); -#103270 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#103271 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103272 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103273 = DEFINITIONAL_REPRESENTATION('',(#103274),#103277); -#103274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103275,#103276), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#103275 = CARTESIAN_POINT('',(4.712388980385,-3.65)); -#103276 = CARTESIAN_POINT('',(4.712388980385,-3.85)); -#103277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103278 = ORIENTED_EDGE('',*,*,#103279,.T.); -#103279 = EDGE_CURVE('',#103251,#103046,#103280,.T.); -#103280 = SURFACE_CURVE('',#103281,(#103285,#103292),.PCURVE_S1.); -#103281 = LINE('',#103282,#103283); -#103282 = CARTESIAN_POINT('',(6.35,-0.419594812019,0.530776333563)); -#103283 = VECTOR('',#103284,1.); -#103284 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103285 = PCURVE('',#103060,#103286); -#103286 = DEFINITIONAL_REPRESENTATION('',(#103287),#103291); -#103287 = LINE('',#103288,#103289); -#103288 = CARTESIAN_POINT('',(0.E+000,-3.65)); -#103289 = VECTOR('',#103290,1.); -#103290 = DIRECTION('',(1.,0.E+000)); -#103291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103292 = PCURVE('',#88700,#103293); -#103293 = DEFINITIONAL_REPRESENTATION('',(#103294),#103298); -#103294 = LINE('',#103295,#103296); -#103295 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#103296 = VECTOR('',#103297,1.); -#103297 = DIRECTION('',(-1.,-1.021336205033E-016)); -#103298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103299 = ORIENTED_EDGE('',*,*,#103045,.T.); -#103300 = ORIENTED_EDGE('',*,*,#103301,.F.); -#103301 = EDGE_CURVE('',#103253,#103019,#103302,.T.); -#103302 = SURFACE_CURVE('',#103303,(#103307,#103314),.PCURVE_S1.); -#103303 = LINE('',#103304,#103305); -#103304 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.530776333563)); -#103305 = VECTOR('',#103306,1.); -#103306 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103307 = PCURVE('',#103060,#103308); -#103308 = DEFINITIONAL_REPRESENTATION('',(#103309),#103313); -#103309 = LINE('',#103310,#103311); -#103310 = CARTESIAN_POINT('',(0.E+000,-3.85)); -#103311 = VECTOR('',#103312,1.); -#103312 = DIRECTION('',(1.,0.E+000)); -#103313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103314 = PCURVE('',#88644,#103315); -#103315 = DEFINITIONAL_REPRESENTATION('',(#103316),#103320); -#103316 = LINE('',#103317,#103318); -#103317 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#103318 = VECTOR('',#103319,1.); -#103319 = DIRECTION('',(1.,-1.021336205033E-016)); -#103320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105684 = PCURVE('',#91092,#105685); +#105685 = DEFINITIONAL_REPRESENTATION('',(#105686),#105690); +#105686 = LINE('',#105687,#105688); +#105687 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#105688 = VECTOR('',#105689,1.); +#105689 = DIRECTION('',(-1.,-1.021336205033E-016)); +#105690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103321 = ADVANCED_FACE('',(#103322),#103193,.T.); -#103322 = FACE_BOUND('',#103323,.T.); -#103323 = EDGE_LOOP('',(#103324,#103347,#103348,#103375)); -#103324 = ORIENTED_EDGE('',*,*,#103325,.T.); -#103325 = EDGE_CURVE('',#103326,#103176,#103328,.T.); -#103326 = VERTEX_POINT('',#103327); -#103327 = CARTESIAN_POINT('',(6.15,-0.304819755875,0.75)); -#103328 = SURFACE_CURVE('',#103329,(#103334,#103340),.PCURVE_S1.); -#103329 = CIRCLE('',#103330,0.2192697516); -#103330 = AXIS2_PLACEMENT_3D('',#103331,#103332,#103333); -#103331 = CARTESIAN_POINT('',(6.15,-0.30032442045,0.530776333563)); -#103332 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103333 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103334 = PCURVE('',#103193,#103335); -#103335 = DEFINITIONAL_REPRESENTATION('',(#103336),#103339); -#103336 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103337,#103338), +#105691 = ORIENTED_EDGE('',*,*,#105437,.T.); +#105692 = ORIENTED_EDGE('',*,*,#105693,.F.); +#105693 = EDGE_CURVE('',#105645,#105411,#105694,.T.); +#105694 = SURFACE_CURVE('',#105695,(#105699,#105706),.PCURVE_S1.); +#105695 = LINE('',#105696,#105697); +#105696 = CARTESIAN_POINT('',(6.15,-0.419594812019,0.530776333563)); +#105697 = VECTOR('',#105698,1.); +#105698 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#105699 = PCURVE('',#105452,#105700); +#105700 = DEFINITIONAL_REPRESENTATION('',(#105701),#105705); +#105701 = LINE('',#105702,#105703); +#105702 = CARTESIAN_POINT('',(0.E+000,-3.85)); +#105703 = VECTOR('',#105704,1.); +#105704 = DIRECTION('',(1.,0.E+000)); +#105705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105706 = PCURVE('',#91036,#105707); +#105707 = DEFINITIONAL_REPRESENTATION('',(#105708),#105712); +#105708 = LINE('',#105709,#105710); +#105709 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#105710 = VECTOR('',#105711,1.); +#105711 = DIRECTION('',(1.,-1.021336205033E-016)); +#105712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105713 = ADVANCED_FACE('',(#105714),#105585,.T.); +#105714 = FACE_BOUND('',#105715,.T.); +#105715 = EDGE_LOOP('',(#105716,#105739,#105740,#105767)); +#105716 = ORIENTED_EDGE('',*,*,#105717,.T.); +#105717 = EDGE_CURVE('',#105718,#105568,#105720,.T.); +#105718 = VERTEX_POINT('',#105719); +#105719 = CARTESIAN_POINT('',(6.15,-0.304819755875,0.75)); +#105720 = SURFACE_CURVE('',#105721,(#105726,#105732),.PCURVE_S1.); +#105721 = CIRCLE('',#105722,0.2192697516); +#105722 = AXIS2_PLACEMENT_3D('',#105723,#105724,#105725); +#105723 = CARTESIAN_POINT('',(6.15,-0.30032442045,0.530776333563)); +#105724 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105725 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105726 = PCURVE('',#105585,#105727); +#105727 = DEFINITIONAL_REPRESENTATION('',(#105728),#105731); +#105728 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105729,#105730), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#103337 = CARTESIAN_POINT('',(3.162095483347,-3.85)); -#103338 = CARTESIAN_POINT('',(4.712388980385,-3.85)); -#103339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103340 = PCURVE('',#88644,#103341); -#103341 = DEFINITIONAL_REPRESENTATION('',(#103342),#103346); -#103342 = CIRCLE('',#103343,0.2192697516); -#103343 = AXIS2_PLACEMENT_2D('',#103344,#103345); -#103344 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#103345 = DIRECTION('',(1.,0.E+000)); -#103346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103347 = ORIENTED_EDGE('',*,*,#103175,.T.); -#103348 = ORIENTED_EDGE('',*,*,#103349,.F.); -#103349 = EDGE_CURVE('',#103350,#103178,#103352,.T.); -#103350 = VERTEX_POINT('',#103351); -#103351 = CARTESIAN_POINT('',(6.35,-0.304819755875,0.75)); -#103352 = SURFACE_CURVE('',#103353,(#103358,#103364),.PCURVE_S1.); -#103353 = CIRCLE('',#103354,0.2192697516); -#103354 = AXIS2_PLACEMENT_3D('',#103355,#103356,#103357); -#103355 = CARTESIAN_POINT('',(6.35,-0.30032442045,0.530776333563)); -#103356 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103357 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103358 = PCURVE('',#103193,#103359); -#103359 = DEFINITIONAL_REPRESENTATION('',(#103360),#103363); -#103360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103361,#103362), +#105729 = CARTESIAN_POINT('',(3.162095483347,-3.85)); +#105730 = CARTESIAN_POINT('',(4.712388980385,-3.85)); +#105731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105732 = PCURVE('',#91036,#105733); +#105733 = DEFINITIONAL_REPRESENTATION('',(#105734),#105738); +#105734 = CIRCLE('',#105735,0.2192697516); +#105735 = AXIS2_PLACEMENT_2D('',#105736,#105737); +#105736 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#105737 = DIRECTION('',(1.,0.E+000)); +#105738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105739 = ORIENTED_EDGE('',*,*,#105567,.T.); +#105740 = ORIENTED_EDGE('',*,*,#105741,.F.); +#105741 = EDGE_CURVE('',#105742,#105570,#105744,.T.); +#105742 = VERTEX_POINT('',#105743); +#105743 = CARTESIAN_POINT('',(6.35,-0.304819755875,0.75)); +#105744 = SURFACE_CURVE('',#105745,(#105750,#105756),.PCURVE_S1.); +#105745 = CIRCLE('',#105746,0.2192697516); +#105746 = AXIS2_PLACEMENT_3D('',#105747,#105748,#105749); +#105747 = CARTESIAN_POINT('',(6.35,-0.30032442045,0.530776333563)); +#105748 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105749 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105750 = PCURVE('',#105585,#105751); +#105751 = DEFINITIONAL_REPRESENTATION('',(#105752),#105755); +#105752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105753,#105754), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#103361 = CARTESIAN_POINT('',(3.162095483347,-3.65)); -#103362 = CARTESIAN_POINT('',(4.712388980385,-3.65)); -#103363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105753 = CARTESIAN_POINT('',(3.162095483347,-3.65)); +#105754 = CARTESIAN_POINT('',(4.712388980385,-3.65)); +#105755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103364 = PCURVE('',#88700,#103365); -#103365 = DEFINITIONAL_REPRESENTATION('',(#103366),#103374); -#103366 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103367,#103368,#103369, - #103370,#103371,#103372,#103373),.UNSPECIFIED.,.F.,.F.) +#105756 = PCURVE('',#91092,#105757); +#105757 = DEFINITIONAL_REPRESENTATION('',(#105758),#105766); +#105758 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105759,#105760,#105761, + #105762,#105763,#105764,#105765),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103367 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#103368 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#103369 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#103370 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#103371 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#103372 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#103373 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#103374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103375 = ORIENTED_EDGE('',*,*,#103376,.T.); -#103376 = EDGE_CURVE('',#103350,#103326,#103377,.T.); -#103377 = SURFACE_CURVE('',#103378,(#103382,#103388),.PCURVE_S1.); -#103378 = LINE('',#103379,#103380); -#103379 = CARTESIAN_POINT('',(6.15,-0.304819755875,0.75)); -#103380 = VECTOR('',#103381,1.); -#103381 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103382 = PCURVE('',#103193,#103383); -#103383 = DEFINITIONAL_REPRESENTATION('',(#103384),#103387); -#103384 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103385,#103386), +#105759 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#105760 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#105761 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#105762 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#105763 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#105764 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#105765 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#105766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105767 = ORIENTED_EDGE('',*,*,#105768,.T.); +#105768 = EDGE_CURVE('',#105742,#105718,#105769,.T.); +#105769 = SURFACE_CURVE('',#105770,(#105774,#105780),.PCURVE_S1.); +#105770 = LINE('',#105771,#105772); +#105771 = CARTESIAN_POINT('',(6.15,-0.304819755875,0.75)); +#105772 = VECTOR('',#105773,1.); +#105773 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#105774 = PCURVE('',#105585,#105775); +#105775 = DEFINITIONAL_REPRESENTATION('',(#105776),#105779); +#105776 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105777,#105778), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#103385 = CARTESIAN_POINT('',(3.162095483347,-3.65)); -#103386 = CARTESIAN_POINT('',(3.162095483347,-3.85)); -#103387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103388 = PCURVE('',#88672,#103389); -#103389 = DEFINITIONAL_REPRESENTATION('',(#103390),#103394); -#103390 = LINE('',#103391,#103392); -#103391 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#103392 = VECTOR('',#103393,1.); -#103393 = DIRECTION('',(0.E+000,-1.)); -#103394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103395 = ADVANCED_FACE('',(#103396),#103268,.F.); -#103396 = FACE_BOUND('',#103397,.F.); -#103397 = EDGE_LOOP('',(#103398,#103425,#103447,#103468)); -#103398 = ORIENTED_EDGE('',*,*,#103399,.F.); -#103399 = EDGE_CURVE('',#103400,#103251,#103402,.T.); -#103400 = VERTEX_POINT('',#103401); -#103401 = CARTESIAN_POINT('',(6.35,-0.303662633502,0.65)); -#103402 = SURFACE_CURVE('',#103403,(#103408,#103414),.PCURVE_S1.); -#103403 = CIRCLE('',#103404,0.119270391569); -#103404 = AXIS2_PLACEMENT_3D('',#103405,#103406,#103407); -#103405 = CARTESIAN_POINT('',(6.35,-0.30032442045,0.530776333563)); -#103406 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103407 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103408 = PCURVE('',#103268,#103409); -#103409 = DEFINITIONAL_REPRESENTATION('',(#103410),#103413); -#103410 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103411,#103412), +#105777 = CARTESIAN_POINT('',(3.162095483347,-3.65)); +#105778 = CARTESIAN_POINT('',(3.162095483347,-3.85)); +#105779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105780 = PCURVE('',#91064,#105781); +#105781 = DEFINITIONAL_REPRESENTATION('',(#105782),#105786); +#105782 = LINE('',#105783,#105784); +#105783 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#105784 = VECTOR('',#105785,1.); +#105785 = DIRECTION('',(0.E+000,-1.)); +#105786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105787 = ADVANCED_FACE('',(#105788),#105660,.F.); +#105788 = FACE_BOUND('',#105789,.F.); +#105789 = EDGE_LOOP('',(#105790,#105817,#105839,#105860)); +#105790 = ORIENTED_EDGE('',*,*,#105791,.F.); +#105791 = EDGE_CURVE('',#105792,#105643,#105794,.T.); +#105792 = VERTEX_POINT('',#105793); +#105793 = CARTESIAN_POINT('',(6.35,-0.303662633502,0.65)); +#105794 = SURFACE_CURVE('',#105795,(#105800,#105806),.PCURVE_S1.); +#105795 = CIRCLE('',#105796,0.119270391569); +#105796 = AXIS2_PLACEMENT_3D('',#105797,#105798,#105799); +#105797 = CARTESIAN_POINT('',(6.35,-0.30032442045,0.530776333563)); +#105798 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105799 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105800 = PCURVE('',#105660,#105801); +#105801 = DEFINITIONAL_REPRESENTATION('',(#105802),#105805); +#105802 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105803,#105804), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#103411 = CARTESIAN_POINT('',(3.169584923929,-3.65)); -#103412 = CARTESIAN_POINT('',(4.712388980385,-3.65)); -#103413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#105803 = CARTESIAN_POINT('',(3.169584923929,-3.65)); +#105804 = CARTESIAN_POINT('',(4.712388980385,-3.65)); +#105805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103414 = PCURVE('',#88700,#103415); -#103415 = DEFINITIONAL_REPRESENTATION('',(#103416),#103424); -#103416 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103417,#103418,#103419, - #103420,#103421,#103422,#103423),.UNSPECIFIED.,.F.,.F.) +#105806 = PCURVE('',#91092,#105807); +#105807 = DEFINITIONAL_REPRESENTATION('',(#105808),#105816); +#105808 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105809,#105810,#105811, + #105812,#105813,#105814,#105815),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103417 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#103418 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#103419 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#103420 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#103421 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#103422 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#103423 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#103424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103425 = ORIENTED_EDGE('',*,*,#103426,.F.); -#103426 = EDGE_CURVE('',#103427,#103400,#103429,.T.); -#103427 = VERTEX_POINT('',#103428); -#103428 = CARTESIAN_POINT('',(6.15,-0.303662633502,0.65)); -#103429 = SURFACE_CURVE('',#103430,(#103434,#103440),.PCURVE_S1.); -#103430 = LINE('',#103431,#103432); -#103431 = CARTESIAN_POINT('',(6.15,-0.303662633502,0.65)); -#103432 = VECTOR('',#103433,1.); -#103433 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103434 = PCURVE('',#103268,#103435); -#103435 = DEFINITIONAL_REPRESENTATION('',(#103436),#103439); -#103436 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103437,#103438), +#105809 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#105810 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#105811 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#105812 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#105813 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#105814 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#105815 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#105816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105817 = ORIENTED_EDGE('',*,*,#105818,.F.); +#105818 = EDGE_CURVE('',#105819,#105792,#105821,.T.); +#105819 = VERTEX_POINT('',#105820); +#105820 = CARTESIAN_POINT('',(6.15,-0.303662633502,0.65)); +#105821 = SURFACE_CURVE('',#105822,(#105826,#105832),.PCURVE_S1.); +#105822 = LINE('',#105823,#105824); +#105823 = CARTESIAN_POINT('',(6.15,-0.303662633502,0.65)); +#105824 = VECTOR('',#105825,1.); +#105825 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105826 = PCURVE('',#105660,#105827); +#105827 = DEFINITIONAL_REPRESENTATION('',(#105828),#105831); +#105828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105829,#105830), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#103437 = CARTESIAN_POINT('',(3.169584923929,-3.85)); -#103438 = CARTESIAN_POINT('',(3.169584923929,-3.65)); -#103439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103440 = PCURVE('',#88726,#103441); -#103441 = DEFINITIONAL_REPRESENTATION('',(#103442),#103446); -#103442 = LINE('',#103443,#103444); -#103443 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#103444 = VECTOR('',#103445,1.); -#103445 = DIRECTION('',(0.E+000,1.)); -#103446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103447 = ORIENTED_EDGE('',*,*,#103448,.T.); -#103448 = EDGE_CURVE('',#103427,#103253,#103449,.T.); -#103449 = SURFACE_CURVE('',#103450,(#103455,#103461),.PCURVE_S1.); -#103450 = CIRCLE('',#103451,0.119270391569); -#103451 = AXIS2_PLACEMENT_3D('',#103452,#103453,#103454); -#103452 = CARTESIAN_POINT('',(6.15,-0.30032442045,0.530776333563)); -#103453 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103454 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103455 = PCURVE('',#103268,#103456); -#103456 = DEFINITIONAL_REPRESENTATION('',(#103457),#103460); -#103457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103458,#103459), +#105829 = CARTESIAN_POINT('',(3.169584923929,-3.85)); +#105830 = CARTESIAN_POINT('',(3.169584923929,-3.65)); +#105831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105832 = PCURVE('',#91118,#105833); +#105833 = DEFINITIONAL_REPRESENTATION('',(#105834),#105838); +#105834 = LINE('',#105835,#105836); +#105835 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#105836 = VECTOR('',#105837,1.); +#105837 = DIRECTION('',(0.E+000,1.)); +#105838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105839 = ORIENTED_EDGE('',*,*,#105840,.T.); +#105840 = EDGE_CURVE('',#105819,#105645,#105841,.T.); +#105841 = SURFACE_CURVE('',#105842,(#105847,#105853),.PCURVE_S1.); +#105842 = CIRCLE('',#105843,0.119270391569); +#105843 = AXIS2_PLACEMENT_3D('',#105844,#105845,#105846); +#105844 = CARTESIAN_POINT('',(6.15,-0.30032442045,0.530776333563)); +#105845 = DIRECTION('',(1.,0.E+000,0.E+000)); +#105846 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#105847 = PCURVE('',#105660,#105848); +#105848 = DEFINITIONAL_REPRESENTATION('',(#105849),#105852); +#105849 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105850,#105851), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#103458 = CARTESIAN_POINT('',(3.169584923929,-3.85)); -#103459 = CARTESIAN_POINT('',(4.712388980385,-3.85)); -#103460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103461 = PCURVE('',#88644,#103462); -#103462 = DEFINITIONAL_REPRESENTATION('',(#103463),#103467); -#103463 = CIRCLE('',#103464,0.119270391569); -#103464 = AXIS2_PLACEMENT_2D('',#103465,#103466); -#103465 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#103466 = DIRECTION('',(1.,0.E+000)); -#103467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103468 = ORIENTED_EDGE('',*,*,#103250,.F.); -#103469 = ADVANCED_FACE('',(#103470),#88644,.F.); -#103470 = FACE_BOUND('',#103471,.T.); -#103471 = EDGE_LOOP('',(#103472,#103493,#103494,#103495,#103496,#103497, - #103518,#103519,#103520,#103521,#103522,#103543)); -#103472 = ORIENTED_EDGE('',*,*,#103473,.F.); -#103473 = EDGE_CURVE('',#103427,#88629,#103474,.T.); -#103474 = SURFACE_CURVE('',#103475,(#103479,#103486),.PCURVE_S1.); -#103475 = LINE('',#103476,#103477); -#103476 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); -#103477 = VECTOR('',#103478,1.); -#103478 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#103479 = PCURVE('',#88644,#103480); -#103480 = DEFINITIONAL_REPRESENTATION('',(#103481),#103485); -#103481 = LINE('',#103482,#103483); -#103482 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103483 = VECTOR('',#103484,1.); -#103484 = DIRECTION('',(-3.563627120235E-016,1.)); -#103485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103486 = PCURVE('',#88726,#103487); -#103487 = DEFINITIONAL_REPRESENTATION('',(#103488),#103492); -#103488 = LINE('',#103489,#103490); -#103489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103490 = VECTOR('',#103491,1.); -#103491 = DIRECTION('',(-1.,0.E+000)); -#103492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103493 = ORIENTED_EDGE('',*,*,#103448,.T.); -#103494 = ORIENTED_EDGE('',*,*,#103301,.T.); -#103495 = ORIENTED_EDGE('',*,*,#103018,.T.); -#103496 = ORIENTED_EDGE('',*,*,#102862,.T.); -#103497 = ORIENTED_EDGE('',*,*,#103498,.T.); -#103498 = EDGE_CURVE('',#102835,#102916,#103499,.T.); -#103499 = SURFACE_CURVE('',#103500,(#103504,#103511),.PCURVE_S1.); -#103500 = LINE('',#103501,#103502); -#103501 = CARTESIAN_POINT('',(6.15,-1.,1.159810404338E-002)); -#103502 = VECTOR('',#103503,1.); -#103503 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#103504 = PCURVE('',#88644,#103505); -#103505 = DEFINITIONAL_REPRESENTATION('',(#103506),#103510); -#103506 = LINE('',#103507,#103508); -#103507 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#103508 = VECTOR('',#103509,1.); -#103509 = DIRECTION('',(-1.,-2.101748079665E-016)); -#103510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103511 = PCURVE('',#102850,#103512); -#103512 = DEFINITIONAL_REPRESENTATION('',(#103513),#103517); -#103513 = LINE('',#103514,#103515); -#103514 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#103515 = VECTOR('',#103516,1.); -#103516 = DIRECTION('',(-1.,0.E+000)); -#103517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103518 = ORIENTED_EDGE('',*,*,#102913,.F.); -#103519 = ORIENTED_EDGE('',*,*,#103097,.F.); -#103520 = ORIENTED_EDGE('',*,*,#103204,.F.); -#103521 = ORIENTED_EDGE('',*,*,#103325,.F.); -#103522 = ORIENTED_EDGE('',*,*,#103523,.T.); -#103523 = EDGE_CURVE('',#103326,#88627,#103524,.T.); -#103524 = SURFACE_CURVE('',#103525,(#103529,#103536),.PCURVE_S1.); -#103525 = LINE('',#103526,#103527); -#103526 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.75)); -#103527 = VECTOR('',#103528,1.); -#103528 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#103529 = PCURVE('',#88644,#103530); -#103530 = DEFINITIONAL_REPRESENTATION('',(#103531),#103535); -#103531 = LINE('',#103532,#103533); -#103532 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#103533 = VECTOR('',#103534,1.); -#103534 = DIRECTION('',(-3.563627120235E-016,1.)); -#103535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103536 = PCURVE('',#88672,#103537); -#103537 = DEFINITIONAL_REPRESENTATION('',(#103538),#103542); -#103538 = LINE('',#103539,#103540); -#103539 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103540 = VECTOR('',#103541,1.); -#103541 = DIRECTION('',(1.,0.E+000)); -#103542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103543 = ORIENTED_EDGE('',*,*,#88626,.T.); -#103544 = ADVANCED_FACE('',(#103545),#88672,.F.); -#103545 = FACE_BOUND('',#103546,.T.); -#103546 = EDGE_LOOP('',(#103547,#103548,#103569,#103570)); -#103547 = ORIENTED_EDGE('',*,*,#103376,.F.); -#103548 = ORIENTED_EDGE('',*,*,#103549,.T.); -#103549 = EDGE_CURVE('',#103350,#88657,#103550,.T.); -#103550 = SURFACE_CURVE('',#103551,(#103555,#103562),.PCURVE_S1.); -#103551 = LINE('',#103552,#103553); -#103552 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.75)); -#103553 = VECTOR('',#103554,1.); -#103554 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#103555 = PCURVE('',#88672,#103556); -#103556 = DEFINITIONAL_REPRESENTATION('',(#103557),#103561); -#103557 = LINE('',#103558,#103559); -#103558 = CARTESIAN_POINT('',(0.E+000,0.2)); -#103559 = VECTOR('',#103560,1.); -#103560 = DIRECTION('',(1.,0.E+000)); -#103561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103562 = PCURVE('',#88700,#103563); -#103563 = DEFINITIONAL_REPRESENTATION('',(#103564),#103568); -#103564 = LINE('',#103565,#103566); -#103565 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#103566 = VECTOR('',#103567,1.); -#103567 = DIRECTION('',(3.563627120235E-016,1.)); -#103568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103569 = ORIENTED_EDGE('',*,*,#88656,.T.); -#103570 = ORIENTED_EDGE('',*,*,#103523,.F.); -#103571 = ADVANCED_FACE('',(#103572),#88700,.F.); -#103572 = FACE_BOUND('',#103573,.T.); -#103573 = EDGE_LOOP('',(#103574,#103575,#103576,#103577,#103578,#103579, - #103600,#103601,#103602,#103603,#103604,#103625)); -#103574 = ORIENTED_EDGE('',*,*,#103549,.F.); -#103575 = ORIENTED_EDGE('',*,*,#103349,.T.); -#103576 = ORIENTED_EDGE('',*,*,#103226,.T.); -#103577 = ORIENTED_EDGE('',*,*,#103151,.T.); -#103578 = ORIENTED_EDGE('',*,*,#102966,.T.); -#103579 = ORIENTED_EDGE('',*,*,#103580,.T.); -#103580 = EDGE_CURVE('',#102944,#102807,#103581,.T.); -#103581 = SURFACE_CURVE('',#103582,(#103586,#103593),.PCURVE_S1.); -#103582 = LINE('',#103583,#103584); -#103583 = CARTESIAN_POINT('',(6.35,-1.,1.159810404338E-002)); -#103584 = VECTOR('',#103585,1.); -#103585 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#103586 = PCURVE('',#88700,#103587); -#103587 = DEFINITIONAL_REPRESENTATION('',(#103588),#103592); -#103588 = LINE('',#103589,#103590); -#103589 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#103590 = VECTOR('',#103591,1.); -#103591 = DIRECTION('',(-1.,2.101748079665E-016)); -#103592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103593 = PCURVE('',#102850,#103594); -#103594 = DEFINITIONAL_REPRESENTATION('',(#103595),#103599); -#103595 = LINE('',#103596,#103597); -#103596 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); -#103597 = VECTOR('',#103598,1.); -#103598 = DIRECTION('',(1.,0.E+000)); -#103599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103600 = ORIENTED_EDGE('',*,*,#102804,.F.); -#103601 = ORIENTED_EDGE('',*,*,#103072,.F.); -#103602 = ORIENTED_EDGE('',*,*,#103279,.F.); -#103603 = ORIENTED_EDGE('',*,*,#103399,.F.); -#103604 = ORIENTED_EDGE('',*,*,#103605,.T.); -#103605 = EDGE_CURVE('',#103400,#88685,#103606,.T.); -#103606 = SURFACE_CURVE('',#103607,(#103611,#103618),.PCURVE_S1.); -#103607 = LINE('',#103608,#103609); -#103608 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.65)); -#103609 = VECTOR('',#103610,1.); -#103610 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#103611 = PCURVE('',#88700,#103612); -#103612 = DEFINITIONAL_REPRESENTATION('',(#103613),#103617); -#103613 = LINE('',#103614,#103615); -#103614 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103615 = VECTOR('',#103616,1.); -#103616 = DIRECTION('',(3.563627120235E-016,1.)); -#103617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103618 = PCURVE('',#88726,#103619); -#103619 = DEFINITIONAL_REPRESENTATION('',(#103620),#103624); -#103620 = LINE('',#103621,#103622); -#103621 = CARTESIAN_POINT('',(0.E+000,0.2)); -#103622 = VECTOR('',#103623,1.); -#103623 = DIRECTION('',(-1.,0.E+000)); -#103624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103625 = ORIENTED_EDGE('',*,*,#88684,.T.); -#103626 = ADVANCED_FACE('',(#103627),#88726,.F.); -#103627 = FACE_BOUND('',#103628,.T.); -#103628 = EDGE_LOOP('',(#103629,#103630,#103631,#103632)); -#103629 = ORIENTED_EDGE('',*,*,#103426,.F.); -#103630 = ORIENTED_EDGE('',*,*,#103473,.T.); -#103631 = ORIENTED_EDGE('',*,*,#88712,.T.); -#103632 = ORIENTED_EDGE('',*,*,#103605,.F.); -#103633 = ADVANCED_FACE('',(#103634),#102850,.T.); -#103634 = FACE_BOUND('',#103635,.T.); -#103635 = EDGE_LOOP('',(#103636,#103637,#103638,#103639)); -#103636 = ORIENTED_EDGE('',*,*,#103580,.F.); -#103637 = ORIENTED_EDGE('',*,*,#102943,.F.); -#103638 = ORIENTED_EDGE('',*,*,#103498,.F.); -#103639 = ORIENTED_EDGE('',*,*,#102834,.F.); -#103640 = ADVANCED_FACE('',(#103641),#103655,.T.); -#103641 = FACE_BOUND('',#103642,.T.); -#103642 = EDGE_LOOP('',(#103643,#103673,#103701,#103724)); -#103643 = ORIENTED_EDGE('',*,*,#103644,.T.); -#103644 = EDGE_CURVE('',#103645,#103647,#103649,.T.); -#103645 = VERTEX_POINT('',#103646); -#103646 = CARTESIAN_POINT('',(6.85,-0.74341632541,-0.308197125857)); -#103647 = VERTEX_POINT('',#103648); -#103648 = CARTESIAN_POINT('',(6.85,-1.,-0.308197125857)); -#103649 = SURFACE_CURVE('',#103650,(#103654,#103666),.PCURVE_S1.); -#103650 = LINE('',#103651,#103652); -#103651 = CARTESIAN_POINT('',(6.85,-0.74341632541,-0.308197125857)); -#103652 = VECTOR('',#103653,1.); -#103653 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#103654 = PCURVE('',#103655,#103660); -#103655 = PLANE('',#103656); -#103656 = AXIS2_PLACEMENT_3D('',#103657,#103658,#103659); -#103657 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#103658 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#103659 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103660 = DEFINITIONAL_REPRESENTATION('',(#103661),#103665); -#103661 = LINE('',#103662,#103663); -#103662 = CARTESIAN_POINT('',(3.15,0.E+000)); -#103663 = VECTOR('',#103664,1.); -#103664 = DIRECTION('',(0.E+000,-1.)); -#103665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103666 = PCURVE('',#90063,#103667); -#103667 = DEFINITIONAL_REPRESENTATION('',(#103668),#103672); -#103668 = LINE('',#103669,#103670); -#103669 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#103670 = VECTOR('',#103671,1.); -#103671 = DIRECTION('',(0.E+000,-1.)); -#103672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103673 = ORIENTED_EDGE('',*,*,#103674,.T.); -#103674 = EDGE_CURVE('',#103647,#103675,#103677,.T.); -#103675 = VERTEX_POINT('',#103676); -#103676 = CARTESIAN_POINT('',(6.65,-1.,-0.308197125857)); -#103677 = SURFACE_CURVE('',#103678,(#103682,#103689),.PCURVE_S1.); -#103678 = LINE('',#103679,#103680); -#103679 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#103680 = VECTOR('',#103681,1.); -#103681 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103682 = PCURVE('',#103655,#103683); -#103683 = DEFINITIONAL_REPRESENTATION('',(#103684),#103688); -#103684 = LINE('',#103685,#103686); -#103685 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#103686 = VECTOR('',#103687,1.); -#103687 = DIRECTION('',(1.,0.E+000)); -#103688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103689 = PCURVE('',#103690,#103695); -#103690 = PLANE('',#103691); -#103691 = AXIS2_PLACEMENT_3D('',#103692,#103693,#103694); -#103692 = CARTESIAN_POINT('',(6.75,-1.,-0.258196742327)); -#103693 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#103694 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#103695 = DEFINITIONAL_REPRESENTATION('',(#103696),#103700); -#103696 = LINE('',#103697,#103698); -#103697 = CARTESIAN_POINT('',(5.000038352949E-002,3.25)); -#103698 = VECTOR('',#103699,1.); -#103699 = DIRECTION('',(0.E+000,-1.)); -#103700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103701 = ORIENTED_EDGE('',*,*,#103702,.F.); -#103702 = EDGE_CURVE('',#103703,#103675,#103705,.T.); -#103703 = VERTEX_POINT('',#103704); -#103704 = CARTESIAN_POINT('',(6.65,-0.74341632541,-0.308197125857)); -#103705 = SURFACE_CURVE('',#103706,(#103710,#103717),.PCURVE_S1.); -#103706 = LINE('',#103707,#103708); -#103707 = CARTESIAN_POINT('',(6.65,-0.74341632541,-0.308197125857)); -#103708 = VECTOR('',#103709,1.); -#103709 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#103710 = PCURVE('',#103655,#103711); -#103711 = DEFINITIONAL_REPRESENTATION('',(#103712),#103716); -#103712 = LINE('',#103713,#103714); -#103713 = CARTESIAN_POINT('',(3.35,0.E+000)); -#103714 = VECTOR('',#103715,1.); -#103715 = DIRECTION('',(0.E+000,-1.)); -#103716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103717 = PCURVE('',#90007,#103718); -#103718 = DEFINITIONAL_REPRESENTATION('',(#103719),#103723); -#103719 = LINE('',#103720,#103721); -#103720 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#103721 = VECTOR('',#103722,1.); -#103722 = DIRECTION('',(0.E+000,-1.)); -#103723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103724 = ORIENTED_EDGE('',*,*,#103725,.T.); -#103725 = EDGE_CURVE('',#103703,#103645,#103726,.T.); -#103726 = SURFACE_CURVE('',#103727,(#103731,#103738),.PCURVE_S1.); -#103727 = LINE('',#103728,#103729); -#103728 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#103729 = VECTOR('',#103730,1.); -#103730 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103731 = PCURVE('',#103655,#103732); -#103732 = DEFINITIONAL_REPRESENTATION('',(#103733),#103737); -#103733 = LINE('',#103734,#103735); -#103734 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103735 = VECTOR('',#103736,1.); -#103736 = DIRECTION('',(-1.,0.E+000)); -#103737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103738 = PCURVE('',#103739,#103744); -#103739 = CYLINDRICAL_SURFACE('',#103740,0.308574064194); -#103740 = AXIS2_PLACEMENT_3D('',#103741,#103742,#103743); -#103741 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#103742 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103743 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103744 = DEFINITIONAL_REPRESENTATION('',(#103745),#103748); -#103745 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103746,#103747), +#105850 = CARTESIAN_POINT('',(3.169584923929,-3.85)); +#105851 = CARTESIAN_POINT('',(4.712388980385,-3.85)); +#105852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105853 = PCURVE('',#91036,#105854); +#105854 = DEFINITIONAL_REPRESENTATION('',(#105855),#105859); +#105855 = CIRCLE('',#105856,0.119270391569); +#105856 = AXIS2_PLACEMENT_2D('',#105857,#105858); +#105857 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#105858 = DIRECTION('',(1.,0.E+000)); +#105859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105860 = ORIENTED_EDGE('',*,*,#105642,.F.); +#105861 = ADVANCED_FACE('',(#105862),#91036,.F.); +#105862 = FACE_BOUND('',#105863,.T.); +#105863 = EDGE_LOOP('',(#105864,#105885,#105886,#105887,#105888,#105889, + #105910,#105911,#105912,#105913,#105914,#105935)); +#105864 = ORIENTED_EDGE('',*,*,#105865,.F.); +#105865 = EDGE_CURVE('',#105819,#91021,#105866,.T.); +#105866 = SURFACE_CURVE('',#105867,(#105871,#105878),.PCURVE_S1.); +#105867 = LINE('',#105868,#105869); +#105868 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.65)); +#105869 = VECTOR('',#105870,1.); +#105870 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105871 = PCURVE('',#91036,#105872); +#105872 = DEFINITIONAL_REPRESENTATION('',(#105873),#105877); +#105873 = LINE('',#105874,#105875); +#105874 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105875 = VECTOR('',#105876,1.); +#105876 = DIRECTION('',(-3.563627120235E-016,1.)); +#105877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105878 = PCURVE('',#91118,#105879); +#105879 = DEFINITIONAL_REPRESENTATION('',(#105880),#105884); +#105880 = LINE('',#105881,#105882); +#105881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105882 = VECTOR('',#105883,1.); +#105883 = DIRECTION('',(-1.,0.E+000)); +#105884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105885 = ORIENTED_EDGE('',*,*,#105840,.T.); +#105886 = ORIENTED_EDGE('',*,*,#105693,.T.); +#105887 = ORIENTED_EDGE('',*,*,#105410,.T.); +#105888 = ORIENTED_EDGE('',*,*,#105254,.T.); +#105889 = ORIENTED_EDGE('',*,*,#105890,.T.); +#105890 = EDGE_CURVE('',#105227,#105308,#105891,.T.); +#105891 = SURFACE_CURVE('',#105892,(#105896,#105903),.PCURVE_S1.); +#105892 = LINE('',#105893,#105894); +#105893 = CARTESIAN_POINT('',(6.15,-1.,1.159810404338E-002)); +#105894 = VECTOR('',#105895,1.); +#105895 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#105896 = PCURVE('',#91036,#105897); +#105897 = DEFINITIONAL_REPRESENTATION('',(#105898),#105902); +#105898 = LINE('',#105899,#105900); +#105899 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#105900 = VECTOR('',#105901,1.); +#105901 = DIRECTION('',(-1.,-2.101748079665E-016)); +#105902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105903 = PCURVE('',#105242,#105904); +#105904 = DEFINITIONAL_REPRESENTATION('',(#105905),#105909); +#105905 = LINE('',#105906,#105907); +#105906 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#105907 = VECTOR('',#105908,1.); +#105908 = DIRECTION('',(-1.,0.E+000)); +#105909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105910 = ORIENTED_EDGE('',*,*,#105305,.F.); +#105911 = ORIENTED_EDGE('',*,*,#105489,.F.); +#105912 = ORIENTED_EDGE('',*,*,#105596,.F.); +#105913 = ORIENTED_EDGE('',*,*,#105717,.F.); +#105914 = ORIENTED_EDGE('',*,*,#105915,.T.); +#105915 = EDGE_CURVE('',#105718,#91019,#105916,.T.); +#105916 = SURFACE_CURVE('',#105917,(#105921,#105928),.PCURVE_S1.); +#105917 = LINE('',#105918,#105919); +#105918 = CARTESIAN_POINT('',(6.15,-0.527847992439,0.75)); +#105919 = VECTOR('',#105920,1.); +#105920 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105921 = PCURVE('',#91036,#105922); +#105922 = DEFINITIONAL_REPRESENTATION('',(#105923),#105927); +#105923 = LINE('',#105924,#105925); +#105924 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#105925 = VECTOR('',#105926,1.); +#105926 = DIRECTION('',(-3.563627120235E-016,1.)); +#105927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105928 = PCURVE('',#91064,#105929); +#105929 = DEFINITIONAL_REPRESENTATION('',(#105930),#105934); +#105930 = LINE('',#105931,#105932); +#105931 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#105932 = VECTOR('',#105933,1.); +#105933 = DIRECTION('',(1.,0.E+000)); +#105934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105935 = ORIENTED_EDGE('',*,*,#91018,.T.); +#105936 = ADVANCED_FACE('',(#105937),#91064,.F.); +#105937 = FACE_BOUND('',#105938,.T.); +#105938 = EDGE_LOOP('',(#105939,#105940,#105961,#105962)); +#105939 = ORIENTED_EDGE('',*,*,#105768,.F.); +#105940 = ORIENTED_EDGE('',*,*,#105941,.T.); +#105941 = EDGE_CURVE('',#105742,#91049,#105942,.T.); +#105942 = SURFACE_CURVE('',#105943,(#105947,#105954),.PCURVE_S1.); +#105943 = LINE('',#105944,#105945); +#105944 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.75)); +#105945 = VECTOR('',#105946,1.); +#105946 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#105947 = PCURVE('',#91064,#105948); +#105948 = DEFINITIONAL_REPRESENTATION('',(#105949),#105953); +#105949 = LINE('',#105950,#105951); +#105950 = CARTESIAN_POINT('',(0.E+000,0.2)); +#105951 = VECTOR('',#105952,1.); +#105952 = DIRECTION('',(1.,0.E+000)); +#105953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105954 = PCURVE('',#91092,#105955); +#105955 = DEFINITIONAL_REPRESENTATION('',(#105956),#105960); +#105956 = LINE('',#105957,#105958); +#105957 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#105958 = VECTOR('',#105959,1.); +#105959 = DIRECTION('',(3.563627120235E-016,1.)); +#105960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105961 = ORIENTED_EDGE('',*,*,#91048,.T.); +#105962 = ORIENTED_EDGE('',*,*,#105915,.F.); +#105963 = ADVANCED_FACE('',(#105964),#91092,.F.); +#105964 = FACE_BOUND('',#105965,.T.); +#105965 = EDGE_LOOP('',(#105966,#105967,#105968,#105969,#105970,#105971, + #105992,#105993,#105994,#105995,#105996,#106017)); +#105966 = ORIENTED_EDGE('',*,*,#105941,.F.); +#105967 = ORIENTED_EDGE('',*,*,#105741,.T.); +#105968 = ORIENTED_EDGE('',*,*,#105618,.T.); +#105969 = ORIENTED_EDGE('',*,*,#105543,.T.); +#105970 = ORIENTED_EDGE('',*,*,#105358,.T.); +#105971 = ORIENTED_EDGE('',*,*,#105972,.T.); +#105972 = EDGE_CURVE('',#105336,#105199,#105973,.T.); +#105973 = SURFACE_CURVE('',#105974,(#105978,#105985),.PCURVE_S1.); +#105974 = LINE('',#105975,#105976); +#105975 = CARTESIAN_POINT('',(6.35,-1.,1.159810404338E-002)); +#105976 = VECTOR('',#105977,1.); +#105977 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#105978 = PCURVE('',#91092,#105979); +#105979 = DEFINITIONAL_REPRESENTATION('',(#105980),#105984); +#105980 = LINE('',#105981,#105982); +#105981 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#105982 = VECTOR('',#105983,1.); +#105983 = DIRECTION('',(-1.,2.101748079665E-016)); +#105984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105985 = PCURVE('',#105242,#105986); +#105986 = DEFINITIONAL_REPRESENTATION('',(#105987),#105991); +#105987 = LINE('',#105988,#105989); +#105988 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); +#105989 = VECTOR('',#105990,1.); +#105990 = DIRECTION('',(1.,0.E+000)); +#105991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#105992 = ORIENTED_EDGE('',*,*,#105196,.F.); +#105993 = ORIENTED_EDGE('',*,*,#105464,.F.); +#105994 = ORIENTED_EDGE('',*,*,#105671,.F.); +#105995 = ORIENTED_EDGE('',*,*,#105791,.F.); +#105996 = ORIENTED_EDGE('',*,*,#105997,.T.); +#105997 = EDGE_CURVE('',#105792,#91077,#105998,.T.); +#105998 = SURFACE_CURVE('',#105999,(#106003,#106010),.PCURVE_S1.); +#105999 = LINE('',#106000,#106001); +#106000 = CARTESIAN_POINT('',(6.35,-0.527847992439,0.65)); +#106001 = VECTOR('',#106002,1.); +#106002 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#106003 = PCURVE('',#91092,#106004); +#106004 = DEFINITIONAL_REPRESENTATION('',(#106005),#106009); +#106005 = LINE('',#106006,#106007); +#106006 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106007 = VECTOR('',#106008,1.); +#106008 = DIRECTION('',(3.563627120235E-016,1.)); +#106009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106010 = PCURVE('',#91118,#106011); +#106011 = DEFINITIONAL_REPRESENTATION('',(#106012),#106016); +#106012 = LINE('',#106013,#106014); +#106013 = CARTESIAN_POINT('',(0.E+000,0.2)); +#106014 = VECTOR('',#106015,1.); +#106015 = DIRECTION('',(-1.,0.E+000)); +#106016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106017 = ORIENTED_EDGE('',*,*,#91076,.T.); +#106018 = ADVANCED_FACE('',(#106019),#91118,.F.); +#106019 = FACE_BOUND('',#106020,.T.); +#106020 = EDGE_LOOP('',(#106021,#106022,#106023,#106024)); +#106021 = ORIENTED_EDGE('',*,*,#105818,.F.); +#106022 = ORIENTED_EDGE('',*,*,#105865,.T.); +#106023 = ORIENTED_EDGE('',*,*,#91104,.T.); +#106024 = ORIENTED_EDGE('',*,*,#105997,.F.); +#106025 = ADVANCED_FACE('',(#106026),#105242,.T.); +#106026 = FACE_BOUND('',#106027,.T.); +#106027 = EDGE_LOOP('',(#106028,#106029,#106030,#106031)); +#106028 = ORIENTED_EDGE('',*,*,#105972,.F.); +#106029 = ORIENTED_EDGE('',*,*,#105335,.F.); +#106030 = ORIENTED_EDGE('',*,*,#105890,.F.); +#106031 = ORIENTED_EDGE('',*,*,#105226,.F.); +#106032 = ADVANCED_FACE('',(#106033),#106047,.T.); +#106033 = FACE_BOUND('',#106034,.T.); +#106034 = EDGE_LOOP('',(#106035,#106065,#106093,#106116)); +#106035 = ORIENTED_EDGE('',*,*,#106036,.T.); +#106036 = EDGE_CURVE('',#106037,#106039,#106041,.T.); +#106037 = VERTEX_POINT('',#106038); +#106038 = CARTESIAN_POINT('',(6.85,-0.74341632541,-0.308197125857)); +#106039 = VERTEX_POINT('',#106040); +#106040 = CARTESIAN_POINT('',(6.85,-1.,-0.308197125857)); +#106041 = SURFACE_CURVE('',#106042,(#106046,#106058),.PCURVE_S1.); +#106042 = LINE('',#106043,#106044); +#106043 = CARTESIAN_POINT('',(6.85,-0.74341632541,-0.308197125857)); +#106044 = VECTOR('',#106045,1.); +#106045 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106046 = PCURVE('',#106047,#106052); +#106047 = PLANE('',#106048); +#106048 = AXIS2_PLACEMENT_3D('',#106049,#106050,#106051); +#106049 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#106050 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106051 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106052 = DEFINITIONAL_REPRESENTATION('',(#106053),#106057); +#106053 = LINE('',#106054,#106055); +#106054 = CARTESIAN_POINT('',(3.15,0.E+000)); +#106055 = VECTOR('',#106056,1.); +#106056 = DIRECTION('',(0.E+000,-1.)); +#106057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106058 = PCURVE('',#92455,#106059); +#106059 = DEFINITIONAL_REPRESENTATION('',(#106060),#106064); +#106060 = LINE('',#106061,#106062); +#106061 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#106062 = VECTOR('',#106063,1.); +#106063 = DIRECTION('',(0.E+000,-1.)); +#106064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106065 = ORIENTED_EDGE('',*,*,#106066,.T.); +#106066 = EDGE_CURVE('',#106039,#106067,#106069,.T.); +#106067 = VERTEX_POINT('',#106068); +#106068 = CARTESIAN_POINT('',(6.65,-1.,-0.308197125857)); +#106069 = SURFACE_CURVE('',#106070,(#106074,#106081),.PCURVE_S1.); +#106070 = LINE('',#106071,#106072); +#106071 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#106072 = VECTOR('',#106073,1.); +#106073 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106074 = PCURVE('',#106047,#106075); +#106075 = DEFINITIONAL_REPRESENTATION('',(#106076),#106080); +#106076 = LINE('',#106077,#106078); +#106077 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#106078 = VECTOR('',#106079,1.); +#106079 = DIRECTION('',(1.,0.E+000)); +#106080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106081 = PCURVE('',#106082,#106087); +#106082 = PLANE('',#106083); +#106083 = AXIS2_PLACEMENT_3D('',#106084,#106085,#106086); +#106084 = CARTESIAN_POINT('',(6.75,-1.,-0.258196742327)); +#106085 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#106086 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#106087 = DEFINITIONAL_REPRESENTATION('',(#106088),#106092); +#106088 = LINE('',#106089,#106090); +#106089 = CARTESIAN_POINT('',(5.000038352949E-002,3.25)); +#106090 = VECTOR('',#106091,1.); +#106091 = DIRECTION('',(0.E+000,-1.)); +#106092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106093 = ORIENTED_EDGE('',*,*,#106094,.F.); +#106094 = EDGE_CURVE('',#106095,#106067,#106097,.T.); +#106095 = VERTEX_POINT('',#106096); +#106096 = CARTESIAN_POINT('',(6.65,-0.74341632541,-0.308197125857)); +#106097 = SURFACE_CURVE('',#106098,(#106102,#106109),.PCURVE_S1.); +#106098 = LINE('',#106099,#106100); +#106099 = CARTESIAN_POINT('',(6.65,-0.74341632541,-0.308197125857)); +#106100 = VECTOR('',#106101,1.); +#106101 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106102 = PCURVE('',#106047,#106103); +#106103 = DEFINITIONAL_REPRESENTATION('',(#106104),#106108); +#106104 = LINE('',#106105,#106106); +#106105 = CARTESIAN_POINT('',(3.35,0.E+000)); +#106106 = VECTOR('',#106107,1.); +#106107 = DIRECTION('',(0.E+000,-1.)); +#106108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106109 = PCURVE('',#92399,#106110); +#106110 = DEFINITIONAL_REPRESENTATION('',(#106111),#106115); +#106111 = LINE('',#106112,#106113); +#106112 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#106113 = VECTOR('',#106114,1.); +#106114 = DIRECTION('',(0.E+000,-1.)); +#106115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106116 = ORIENTED_EDGE('',*,*,#106117,.T.); +#106117 = EDGE_CURVE('',#106095,#106037,#106118,.T.); +#106118 = SURFACE_CURVE('',#106119,(#106123,#106130),.PCURVE_S1.); +#106119 = LINE('',#106120,#106121); +#106120 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#106121 = VECTOR('',#106122,1.); +#106122 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106123 = PCURVE('',#106047,#106124); +#106124 = DEFINITIONAL_REPRESENTATION('',(#106125),#106129); +#106125 = LINE('',#106126,#106127); +#106126 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106127 = VECTOR('',#106128,1.); +#106128 = DIRECTION('',(-1.,0.E+000)); +#106129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106130 = PCURVE('',#106131,#106136); +#106131 = CYLINDRICAL_SURFACE('',#106132,0.308574064194); +#106132 = AXIS2_PLACEMENT_3D('',#106133,#106134,#106135); +#106133 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#106134 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106135 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106136 = DEFINITIONAL_REPRESENTATION('',(#106137),#106140); +#106137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106138,#106139), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#103746 = CARTESIAN_POINT('',(3.191025391152,3.35)); -#103747 = CARTESIAN_POINT('',(3.191025391152,3.15)); -#103748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103749 = ADVANCED_FACE('',(#103750),#103764,.T.); -#103750 = FACE_BOUND('',#103751,.T.); -#103751 = EDGE_LOOP('',(#103752,#103782,#103805,#103828)); -#103752 = ORIENTED_EDGE('',*,*,#103753,.T.); -#103753 = EDGE_CURVE('',#103754,#103756,#103758,.T.); -#103754 = VERTEX_POINT('',#103755); -#103755 = CARTESIAN_POINT('',(6.65,-0.740726081328,-0.208196358798)); -#103756 = VERTEX_POINT('',#103757); -#103757 = CARTESIAN_POINT('',(6.65,-1.,-0.208196358798)); -#103758 = SURFACE_CURVE('',#103759,(#103763,#103775),.PCURVE_S1.); -#103759 = LINE('',#103760,#103761); -#103760 = CARTESIAN_POINT('',(6.65,-0.740726081328,-0.208196358798)); -#103761 = VECTOR('',#103762,1.); -#103762 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#103763 = PCURVE('',#103764,#103769); -#103764 = PLANE('',#103765); -#103765 = AXIS2_PLACEMENT_3D('',#103766,#103767,#103768); -#103766 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#103767 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103768 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103769 = DEFINITIONAL_REPRESENTATION('',(#103770),#103774); -#103770 = LINE('',#103771,#103772); -#103771 = CARTESIAN_POINT('',(-3.35,0.E+000)); -#103772 = VECTOR('',#103773,1.); -#103773 = DIRECTION('',(0.E+000,-1.)); -#103774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103775 = PCURVE('',#90007,#103776); -#103776 = DEFINITIONAL_REPRESENTATION('',(#103777),#103781); -#103777 = LINE('',#103778,#103779); -#103778 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#103779 = VECTOR('',#103780,1.); -#103780 = DIRECTION('',(0.E+000,-1.)); -#103781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103782 = ORIENTED_EDGE('',*,*,#103783,.T.); -#103783 = EDGE_CURVE('',#103756,#103784,#103786,.T.); -#103784 = VERTEX_POINT('',#103785); -#103785 = CARTESIAN_POINT('',(6.85,-1.,-0.208196358798)); -#103786 = SURFACE_CURVE('',#103787,(#103791,#103798),.PCURVE_S1.); -#103787 = LINE('',#103788,#103789); -#103788 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#103789 = VECTOR('',#103790,1.); -#103790 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103791 = PCURVE('',#103764,#103792); -#103792 = DEFINITIONAL_REPRESENTATION('',(#103793),#103797); -#103793 = LINE('',#103794,#103795); -#103794 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#103795 = VECTOR('',#103796,1.); -#103796 = DIRECTION('',(1.,0.E+000)); -#103797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103798 = PCURVE('',#103690,#103799); -#103799 = DEFINITIONAL_REPRESENTATION('',(#103800),#103804); -#103800 = LINE('',#103801,#103802); -#103801 = CARTESIAN_POINT('',(-5.000038352949E-002,3.25)); -#103802 = VECTOR('',#103803,1.); -#103803 = DIRECTION('',(0.E+000,1.)); -#103804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103805 = ORIENTED_EDGE('',*,*,#103806,.F.); -#103806 = EDGE_CURVE('',#103807,#103784,#103809,.T.); -#103807 = VERTEX_POINT('',#103808); -#103808 = CARTESIAN_POINT('',(6.85,-0.740726081328,-0.208196358798)); -#103809 = SURFACE_CURVE('',#103810,(#103814,#103821),.PCURVE_S1.); -#103810 = LINE('',#103811,#103812); -#103811 = CARTESIAN_POINT('',(6.85,-0.740726081328,-0.208196358798)); -#103812 = VECTOR('',#103813,1.); -#103813 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#103814 = PCURVE('',#103764,#103815); -#103815 = DEFINITIONAL_REPRESENTATION('',(#103816),#103820); -#103816 = LINE('',#103817,#103818); -#103817 = CARTESIAN_POINT('',(-3.15,0.E+000)); -#103818 = VECTOR('',#103819,1.); -#103819 = DIRECTION('',(0.E+000,-1.)); -#103820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103821 = PCURVE('',#90063,#103822); -#103822 = DEFINITIONAL_REPRESENTATION('',(#103823),#103827); -#103823 = LINE('',#103824,#103825); -#103824 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#103825 = VECTOR('',#103826,1.); -#103826 = DIRECTION('',(0.E+000,-1.)); -#103827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103828 = ORIENTED_EDGE('',*,*,#103829,.T.); -#103829 = EDGE_CURVE('',#103807,#103754,#103830,.T.); -#103830 = SURFACE_CURVE('',#103831,(#103835,#103842),.PCURVE_S1.); -#103831 = LINE('',#103832,#103833); -#103832 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#103833 = VECTOR('',#103834,1.); -#103834 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103835 = PCURVE('',#103764,#103836); -#103836 = DEFINITIONAL_REPRESENTATION('',(#103837),#103841); -#103837 = LINE('',#103838,#103839); -#103838 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#103839 = VECTOR('',#103840,1.); -#103840 = DIRECTION('',(-1.,0.E+000)); -#103841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103842 = PCURVE('',#103843,#103848); -#103843 = CYLINDRICAL_SURFACE('',#103844,0.208574704164); -#103844 = AXIS2_PLACEMENT_3D('',#103845,#103846,#103847); -#103845 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#103846 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103847 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103848 = DEFINITIONAL_REPRESENTATION('',(#103849),#103852); -#103849 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103850,#103851), +#106138 = CARTESIAN_POINT('',(3.191025391152,3.35)); +#106139 = CARTESIAN_POINT('',(3.191025391152,3.15)); +#106140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106141 = ADVANCED_FACE('',(#106142),#106156,.T.); +#106142 = FACE_BOUND('',#106143,.T.); +#106143 = EDGE_LOOP('',(#106144,#106174,#106197,#106220)); +#106144 = ORIENTED_EDGE('',*,*,#106145,.T.); +#106145 = EDGE_CURVE('',#106146,#106148,#106150,.T.); +#106146 = VERTEX_POINT('',#106147); +#106147 = CARTESIAN_POINT('',(6.65,-0.740726081328,-0.208196358798)); +#106148 = VERTEX_POINT('',#106149); +#106149 = CARTESIAN_POINT('',(6.65,-1.,-0.208196358798)); +#106150 = SURFACE_CURVE('',#106151,(#106155,#106167),.PCURVE_S1.); +#106151 = LINE('',#106152,#106153); +#106152 = CARTESIAN_POINT('',(6.65,-0.740726081328,-0.208196358798)); +#106153 = VECTOR('',#106154,1.); +#106154 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106155 = PCURVE('',#106156,#106161); +#106156 = PLANE('',#106157); +#106157 = AXIS2_PLACEMENT_3D('',#106158,#106159,#106160); +#106158 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#106159 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106160 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106161 = DEFINITIONAL_REPRESENTATION('',(#106162),#106166); +#106162 = LINE('',#106163,#106164); +#106163 = CARTESIAN_POINT('',(-3.35,0.E+000)); +#106164 = VECTOR('',#106165,1.); +#106165 = DIRECTION('',(0.E+000,-1.)); +#106166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106167 = PCURVE('',#92399,#106168); +#106168 = DEFINITIONAL_REPRESENTATION('',(#106169),#106173); +#106169 = LINE('',#106170,#106171); +#106170 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#106171 = VECTOR('',#106172,1.); +#106172 = DIRECTION('',(0.E+000,-1.)); +#106173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106174 = ORIENTED_EDGE('',*,*,#106175,.T.); +#106175 = EDGE_CURVE('',#106148,#106176,#106178,.T.); +#106176 = VERTEX_POINT('',#106177); +#106177 = CARTESIAN_POINT('',(6.85,-1.,-0.208196358798)); +#106178 = SURFACE_CURVE('',#106179,(#106183,#106190),.PCURVE_S1.); +#106179 = LINE('',#106180,#106181); +#106180 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#106181 = VECTOR('',#106182,1.); +#106182 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106183 = PCURVE('',#106156,#106184); +#106184 = DEFINITIONAL_REPRESENTATION('',(#106185),#106189); +#106185 = LINE('',#106186,#106187); +#106186 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#106187 = VECTOR('',#106188,1.); +#106188 = DIRECTION('',(1.,0.E+000)); +#106189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106190 = PCURVE('',#106082,#106191); +#106191 = DEFINITIONAL_REPRESENTATION('',(#106192),#106196); +#106192 = LINE('',#106193,#106194); +#106193 = CARTESIAN_POINT('',(-5.000038352949E-002,3.25)); +#106194 = VECTOR('',#106195,1.); +#106195 = DIRECTION('',(0.E+000,1.)); +#106196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106197 = ORIENTED_EDGE('',*,*,#106198,.F.); +#106198 = EDGE_CURVE('',#106199,#106176,#106201,.T.); +#106199 = VERTEX_POINT('',#106200); +#106200 = CARTESIAN_POINT('',(6.85,-0.740726081328,-0.208196358798)); +#106201 = SURFACE_CURVE('',#106202,(#106206,#106213),.PCURVE_S1.); +#106202 = LINE('',#106203,#106204); +#106203 = CARTESIAN_POINT('',(6.85,-0.740726081328,-0.208196358798)); +#106204 = VECTOR('',#106205,1.); +#106205 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106206 = PCURVE('',#106156,#106207); +#106207 = DEFINITIONAL_REPRESENTATION('',(#106208),#106212); +#106208 = LINE('',#106209,#106210); +#106209 = CARTESIAN_POINT('',(-3.15,0.E+000)); +#106210 = VECTOR('',#106211,1.); +#106211 = DIRECTION('',(0.E+000,-1.)); +#106212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106213 = PCURVE('',#92455,#106214); +#106214 = DEFINITIONAL_REPRESENTATION('',(#106215),#106219); +#106215 = LINE('',#106216,#106217); +#106216 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#106217 = VECTOR('',#106218,1.); +#106218 = DIRECTION('',(0.E+000,-1.)); +#106219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106220 = ORIENTED_EDGE('',*,*,#106221,.T.); +#106221 = EDGE_CURVE('',#106199,#106146,#106222,.T.); +#106222 = SURFACE_CURVE('',#106223,(#106227,#106234),.PCURVE_S1.); +#106223 = LINE('',#106224,#106225); +#106224 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#106225 = VECTOR('',#106226,1.); +#106226 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106227 = PCURVE('',#106156,#106228); +#106228 = DEFINITIONAL_REPRESENTATION('',(#106229),#106233); +#106229 = LINE('',#106230,#106231); +#106230 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106231 = VECTOR('',#106232,1.); +#106232 = DIRECTION('',(-1.,0.E+000)); +#106233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106234 = PCURVE('',#106235,#106240); +#106235 = CYLINDRICAL_SURFACE('',#106236,0.208574704164); +#106236 = AXIS2_PLACEMENT_3D('',#106237,#106238,#106239); +#106237 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#106238 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106239 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106240 = DEFINITIONAL_REPRESENTATION('',(#106241),#106244); +#106241 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106242,#106243), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#103850 = CARTESIAN_POINT('',(3.201833915432,3.15)); -#103851 = CARTESIAN_POINT('',(3.201833915432,3.35)); -#103852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103853 = ADVANCED_FACE('',(#103854),#103739,.T.); -#103854 = FACE_BOUND('',#103855,.T.); -#103855 = EDGE_LOOP('',(#103856,#103857,#103884,#103911)); -#103856 = ORIENTED_EDGE('',*,*,#103725,.F.); -#103857 = ORIENTED_EDGE('',*,*,#103858,.F.); -#103858 = EDGE_CURVE('',#103859,#103703,#103861,.T.); -#103859 = VERTEX_POINT('',#103860); -#103860 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.E+000)); -#103861 = SURFACE_CURVE('',#103862,(#103867,#103873),.PCURVE_S1.); -#103862 = CIRCLE('',#103863,0.308574064194); -#103863 = AXIS2_PLACEMENT_3D('',#103864,#103865,#103866); -#103864 = CARTESIAN_POINT('',(6.65,-0.728168876214,2.640924866458E-017) - ); -#103865 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103866 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103867 = PCURVE('',#103739,#103868); -#103868 = DEFINITIONAL_REPRESENTATION('',(#103869),#103872); -#103869 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103870,#103871), +#106242 = CARTESIAN_POINT('',(3.201833915432,3.15)); +#106243 = CARTESIAN_POINT('',(3.201833915432,3.35)); +#106244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106245 = ADVANCED_FACE('',(#106246),#106131,.T.); +#106246 = FACE_BOUND('',#106247,.T.); +#106247 = EDGE_LOOP('',(#106248,#106249,#106276,#106303)); +#106248 = ORIENTED_EDGE('',*,*,#106117,.F.); +#106249 = ORIENTED_EDGE('',*,*,#106250,.F.); +#106250 = EDGE_CURVE('',#106251,#106095,#106253,.T.); +#106251 = VERTEX_POINT('',#106252); +#106252 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.E+000)); +#106253 = SURFACE_CURVE('',#106254,(#106259,#106265),.PCURVE_S1.); +#106254 = CIRCLE('',#106255,0.308574064194); +#106255 = AXIS2_PLACEMENT_3D('',#106256,#106257,#106258); +#106256 = CARTESIAN_POINT('',(6.65,-0.728168876214,2.640924866458E-017) + ); +#106257 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106258 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106259 = PCURVE('',#106131,#106260); +#106260 = DEFINITIONAL_REPRESENTATION('',(#106261),#106264); +#106261 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106262,#106263), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#103870 = CARTESIAN_POINT('',(1.570796326795,3.35)); -#103871 = CARTESIAN_POINT('',(3.191025391152,3.35)); -#103872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106262 = CARTESIAN_POINT('',(1.570796326795,3.35)); +#106263 = CARTESIAN_POINT('',(3.191025391152,3.35)); +#106264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103873 = PCURVE('',#90007,#103874); -#103874 = DEFINITIONAL_REPRESENTATION('',(#103875),#103883); -#103875 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103876,#103877,#103878, - #103879,#103880,#103881,#103882),.UNSPECIFIED.,.T.,.F.) +#106265 = PCURVE('',#92399,#106266); +#106266 = DEFINITIONAL_REPRESENTATION('',(#106267),#106275); +#106267 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106268,#106269,#106270, + #106271,#106272,#106273,#106274),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103876 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#103877 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#103878 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#103879 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#103880 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#103881 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#103882 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#103883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103884 = ORIENTED_EDGE('',*,*,#103885,.F.); -#103885 = EDGE_CURVE('',#103886,#103859,#103888,.T.); -#103886 = VERTEX_POINT('',#103887); -#103887 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.E+000)); -#103888 = SURFACE_CURVE('',#103889,(#103893,#103899),.PCURVE_S1.); -#103889 = LINE('',#103890,#103891); -#103890 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#103891 = VECTOR('',#103892,1.); -#103892 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103893 = PCURVE('',#103739,#103894); -#103894 = DEFINITIONAL_REPRESENTATION('',(#103895),#103898); -#103895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103896,#103897), +#106268 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#106269 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#106270 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#106271 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#106272 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#106273 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#106274 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#106275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106276 = ORIENTED_EDGE('',*,*,#106277,.F.); +#106277 = EDGE_CURVE('',#106278,#106251,#106280,.T.); +#106278 = VERTEX_POINT('',#106279); +#106279 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.E+000)); +#106280 = SURFACE_CURVE('',#106281,(#106285,#106291),.PCURVE_S1.); +#106281 = LINE('',#106282,#106283); +#106282 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#106283 = VECTOR('',#106284,1.); +#106284 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106285 = PCURVE('',#106131,#106286); +#106286 = DEFINITIONAL_REPRESENTATION('',(#106287),#106290); +#106287 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106288,#106289), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#103896 = CARTESIAN_POINT('',(1.570796326795,3.15)); -#103897 = CARTESIAN_POINT('',(1.570796326795,3.35)); -#103898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103899 = PCURVE('',#103900,#103905); -#103900 = PLANE('',#103901); -#103901 = AXIS2_PLACEMENT_3D('',#103902,#103903,#103904); -#103902 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#103903 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#103904 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#103905 = DEFINITIONAL_REPRESENTATION('',(#103906),#103910); -#103906 = LINE('',#103907,#103908); -#103907 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#103908 = VECTOR('',#103909,1.); -#103909 = DIRECTION('',(0.E+000,-1.)); -#103910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103911 = ORIENTED_EDGE('',*,*,#103912,.T.); -#103912 = EDGE_CURVE('',#103886,#103645,#103913,.T.); -#103913 = SURFACE_CURVE('',#103914,(#103919,#103925),.PCURVE_S1.); -#103914 = CIRCLE('',#103915,0.308574064194); -#103915 = AXIS2_PLACEMENT_3D('',#103916,#103917,#103918); -#103916 = CARTESIAN_POINT('',(6.85,-0.728168876214,2.640924866458E-017) - ); -#103917 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103918 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103919 = PCURVE('',#103739,#103920); -#103920 = DEFINITIONAL_REPRESENTATION('',(#103921),#103924); -#103921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103922,#103923), +#106288 = CARTESIAN_POINT('',(1.570796326795,3.15)); +#106289 = CARTESIAN_POINT('',(1.570796326795,3.35)); +#106290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106291 = PCURVE('',#106292,#106297); +#106292 = PLANE('',#106293); +#106293 = AXIS2_PLACEMENT_3D('',#106294,#106295,#106296); +#106294 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#106295 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#106296 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#106297 = DEFINITIONAL_REPRESENTATION('',(#106298),#106302); +#106298 = LINE('',#106299,#106300); +#106299 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#106300 = VECTOR('',#106301,1.); +#106301 = DIRECTION('',(0.E+000,-1.)); +#106302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106303 = ORIENTED_EDGE('',*,*,#106304,.T.); +#106304 = EDGE_CURVE('',#106278,#106037,#106305,.T.); +#106305 = SURFACE_CURVE('',#106306,(#106311,#106317),.PCURVE_S1.); +#106306 = CIRCLE('',#106307,0.308574064194); +#106307 = AXIS2_PLACEMENT_3D('',#106308,#106309,#106310); +#106308 = CARTESIAN_POINT('',(6.85,-0.728168876214,2.640924866458E-017) + ); +#106309 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106310 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106311 = PCURVE('',#106131,#106312); +#106312 = DEFINITIONAL_REPRESENTATION('',(#106313),#106316); +#106313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106314,#106315), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#103922 = CARTESIAN_POINT('',(1.570796326795,3.15)); -#103923 = CARTESIAN_POINT('',(3.191025391152,3.15)); -#103924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103925 = PCURVE('',#90063,#103926); -#103926 = DEFINITIONAL_REPRESENTATION('',(#103927),#103931); -#103927 = CIRCLE('',#103928,0.308574064194); -#103928 = AXIS2_PLACEMENT_2D('',#103929,#103930); -#103929 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#103930 = DIRECTION('',(1.,0.E+000)); -#103931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103932 = ADVANCED_FACE('',(#103933),#103843,.F.); -#103933 = FACE_BOUND('',#103934,.F.); -#103934 = EDGE_LOOP('',(#103935,#103936,#103963,#103990)); -#103935 = ORIENTED_EDGE('',*,*,#103829,.T.); -#103936 = ORIENTED_EDGE('',*,*,#103937,.F.); -#103937 = EDGE_CURVE('',#103938,#103754,#103940,.T.); -#103938 = VERTEX_POINT('',#103939); -#103939 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.E+000)); -#103940 = SURFACE_CURVE('',#103941,(#103946,#103952),.PCURVE_S1.); -#103941 = CIRCLE('',#103942,0.208574704164); -#103942 = AXIS2_PLACEMENT_3D('',#103943,#103944,#103945); -#103943 = CARTESIAN_POINT('',(6.65,-0.728168876214,2.640924866458E-017) - ); -#103944 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103945 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103946 = PCURVE('',#103843,#103947); -#103947 = DEFINITIONAL_REPRESENTATION('',(#103948),#103951); -#103948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103949,#103950), +#106314 = CARTESIAN_POINT('',(1.570796326795,3.15)); +#106315 = CARTESIAN_POINT('',(3.191025391152,3.15)); +#106316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106317 = PCURVE('',#92455,#106318); +#106318 = DEFINITIONAL_REPRESENTATION('',(#106319),#106323); +#106319 = CIRCLE('',#106320,0.308574064194); +#106320 = AXIS2_PLACEMENT_2D('',#106321,#106322); +#106321 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#106322 = DIRECTION('',(1.,0.E+000)); +#106323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106324 = ADVANCED_FACE('',(#106325),#106235,.F.); +#106325 = FACE_BOUND('',#106326,.F.); +#106326 = EDGE_LOOP('',(#106327,#106328,#106355,#106382)); +#106327 = ORIENTED_EDGE('',*,*,#106221,.T.); +#106328 = ORIENTED_EDGE('',*,*,#106329,.F.); +#106329 = EDGE_CURVE('',#106330,#106146,#106332,.T.); +#106330 = VERTEX_POINT('',#106331); +#106331 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.E+000)); +#106332 = SURFACE_CURVE('',#106333,(#106338,#106344),.PCURVE_S1.); +#106333 = CIRCLE('',#106334,0.208574704164); +#106334 = AXIS2_PLACEMENT_3D('',#106335,#106336,#106337); +#106335 = CARTESIAN_POINT('',(6.65,-0.728168876214,2.640924866458E-017) + ); +#106336 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106337 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106338 = PCURVE('',#106235,#106339); +#106339 = DEFINITIONAL_REPRESENTATION('',(#106340),#106343); +#106340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106341,#106342), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#103949 = CARTESIAN_POINT('',(1.570796326795,3.35)); -#103950 = CARTESIAN_POINT('',(3.201833915432,3.35)); -#103951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106341 = CARTESIAN_POINT('',(1.570796326795,3.35)); +#106342 = CARTESIAN_POINT('',(3.201833915432,3.35)); +#106343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#103952 = PCURVE('',#90007,#103953); -#103953 = DEFINITIONAL_REPRESENTATION('',(#103954),#103962); -#103954 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#103955,#103956,#103957, - #103958,#103959,#103960,#103961),.UNSPECIFIED.,.F.,.F.) +#106344 = PCURVE('',#92399,#106345); +#106345 = DEFINITIONAL_REPRESENTATION('',(#106346),#106354); +#106346 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106347,#106348,#106349, + #106350,#106351,#106352,#106353),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#103955 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#103956 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#103957 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#103958 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#103959 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#103960 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#103961 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#103962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103963 = ORIENTED_EDGE('',*,*,#103964,.T.); -#103964 = EDGE_CURVE('',#103938,#103965,#103967,.T.); -#103965 = VERTEX_POINT('',#103966); -#103966 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.E+000)); -#103967 = SURFACE_CURVE('',#103968,(#103972,#103978),.PCURVE_S1.); -#103968 = LINE('',#103969,#103970); -#103969 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#103970 = VECTOR('',#103971,1.); -#103971 = DIRECTION('',(1.,0.E+000,0.E+000)); -#103972 = PCURVE('',#103843,#103973); -#103973 = DEFINITIONAL_REPRESENTATION('',(#103974),#103977); -#103974 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#103975,#103976), +#106347 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#106348 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#106349 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#106350 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#106351 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#106352 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#106353 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#106354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106355 = ORIENTED_EDGE('',*,*,#106356,.T.); +#106356 = EDGE_CURVE('',#106330,#106357,#106359,.T.); +#106357 = VERTEX_POINT('',#106358); +#106358 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.E+000)); +#106359 = SURFACE_CURVE('',#106360,(#106364,#106370),.PCURVE_S1.); +#106360 = LINE('',#106361,#106362); +#106361 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#106362 = VECTOR('',#106363,1.); +#106363 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106364 = PCURVE('',#106235,#106365); +#106365 = DEFINITIONAL_REPRESENTATION('',(#106366),#106369); +#106366 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106367,#106368), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#103975 = CARTESIAN_POINT('',(1.570796326795,3.35)); -#103976 = CARTESIAN_POINT('',(1.570796326795,3.15)); -#103977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103978 = PCURVE('',#103979,#103984); -#103979 = PLANE('',#103980); -#103980 = AXIS2_PLACEMENT_3D('',#103981,#103982,#103983); -#103981 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#103982 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#103983 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#103984 = DEFINITIONAL_REPRESENTATION('',(#103985),#103989); -#103985 = LINE('',#103986,#103987); -#103986 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#103987 = VECTOR('',#103988,1.); -#103988 = DIRECTION('',(0.E+000,1.)); -#103989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#103990 = ORIENTED_EDGE('',*,*,#103991,.T.); -#103991 = EDGE_CURVE('',#103965,#103807,#103992,.T.); -#103992 = SURFACE_CURVE('',#103993,(#103998,#104004),.PCURVE_S1.); -#103993 = CIRCLE('',#103994,0.208574704164); -#103994 = AXIS2_PLACEMENT_3D('',#103995,#103996,#103997); -#103995 = CARTESIAN_POINT('',(6.85,-0.728168876214,2.640924866458E-017) - ); -#103996 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#103997 = DIRECTION('',(0.E+000,0.E+000,1.)); -#103998 = PCURVE('',#103843,#103999); -#103999 = DEFINITIONAL_REPRESENTATION('',(#104000),#104003); -#104000 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104001,#104002), +#106367 = CARTESIAN_POINT('',(1.570796326795,3.35)); +#106368 = CARTESIAN_POINT('',(1.570796326795,3.15)); +#106369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106370 = PCURVE('',#106371,#106376); +#106371 = PLANE('',#106372); +#106372 = AXIS2_PLACEMENT_3D('',#106373,#106374,#106375); +#106373 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#106374 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#106375 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#106376 = DEFINITIONAL_REPRESENTATION('',(#106377),#106381); +#106377 = LINE('',#106378,#106379); +#106378 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#106379 = VECTOR('',#106380,1.); +#106380 = DIRECTION('',(0.E+000,1.)); +#106381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106382 = ORIENTED_EDGE('',*,*,#106383,.T.); +#106383 = EDGE_CURVE('',#106357,#106199,#106384,.T.); +#106384 = SURFACE_CURVE('',#106385,(#106390,#106396),.PCURVE_S1.); +#106385 = CIRCLE('',#106386,0.208574704164); +#106386 = AXIS2_PLACEMENT_3D('',#106387,#106388,#106389); +#106387 = CARTESIAN_POINT('',(6.85,-0.728168876214,2.640924866458E-017) + ); +#106388 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106389 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106390 = PCURVE('',#106235,#106391); +#106391 = DEFINITIONAL_REPRESENTATION('',(#106392),#106395); +#106392 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106393,#106394), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#104001 = CARTESIAN_POINT('',(1.570796326795,3.15)); -#104002 = CARTESIAN_POINT('',(3.201833915432,3.15)); -#104003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106393 = CARTESIAN_POINT('',(1.570796326795,3.15)); +#106394 = CARTESIAN_POINT('',(3.201833915432,3.15)); +#106395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106396 = PCURVE('',#92455,#106397); +#106397 = DEFINITIONAL_REPRESENTATION('',(#106398),#106402); +#106398 = CIRCLE('',#106399,0.208574704164); +#106399 = AXIS2_PLACEMENT_2D('',#106400,#106401); +#106400 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#106401 = DIRECTION('',(1.,0.E+000)); +#106402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106403 = ADVANCED_FACE('',(#106404),#106371,.F.); +#106404 = FACE_BOUND('',#106405,.T.); +#106405 = EDGE_LOOP('',(#106406,#106435,#106456,#106457)); +#106406 = ORIENTED_EDGE('',*,*,#106407,.F.); +#106407 = EDGE_CURVE('',#106408,#106410,#106412,.T.); +#106408 = VERTEX_POINT('',#106409); +#106409 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.530776333563)); +#106410 = VERTEX_POINT('',#106411); +#106411 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.530776333563)); +#106412 = SURFACE_CURVE('',#106413,(#106417,#106424),.PCURVE_S1.); +#106413 = LINE('',#106414,#106415); +#106414 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#106415 = VECTOR('',#106416,1.); +#106416 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106417 = PCURVE('',#106371,#106418); +#106418 = DEFINITIONAL_REPRESENTATION('',(#106419),#106423); +#106419 = LINE('',#106420,#106421); +#106420 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106421 = VECTOR('',#106422,1.); +#106422 = DIRECTION('',(0.E+000,1.)); +#106423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106424 = PCURVE('',#106425,#106430); +#106425 = CYLINDRICAL_SURFACE('',#106426,0.2192697516); +#106426 = AXIS2_PLACEMENT_3D('',#106427,#106428,#106429); +#106427 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#106428 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106429 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106430 = DEFINITIONAL_REPRESENTATION('',(#106431),#106434); +#106431 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106432,#106433), + .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); +#106432 = CARTESIAN_POINT('',(4.712388980385,-3.35)); +#106433 = CARTESIAN_POINT('',(4.712388980385,-3.15)); +#106434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106435 = ORIENTED_EDGE('',*,*,#106436,.T.); +#106436 = EDGE_CURVE('',#106408,#106330,#106437,.T.); +#106437 = SURFACE_CURVE('',#106438,(#106442,#106449),.PCURVE_S1.); +#106438 = LINE('',#106439,#106440); +#106439 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.530776333563)); +#106440 = VECTOR('',#106441,1.); +#106441 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#106442 = PCURVE('',#106371,#106443); +#106443 = DEFINITIONAL_REPRESENTATION('',(#106444),#106448); +#106444 = LINE('',#106445,#106446); +#106445 = CARTESIAN_POINT('',(0.E+000,-3.35)); +#106446 = VECTOR('',#106447,1.); +#106447 = DIRECTION('',(-1.,0.E+000)); +#106448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106449 = PCURVE('',#92399,#106450); +#106450 = DEFINITIONAL_REPRESENTATION('',(#106451),#106455); +#106451 = LINE('',#106452,#106453); +#106452 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#106453 = VECTOR('',#106454,1.); +#106454 = DIRECTION('',(1.,-1.021336205033E-016)); +#106455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106456 = ORIENTED_EDGE('',*,*,#106356,.T.); +#106457 = ORIENTED_EDGE('',*,*,#106458,.F.); +#106458 = EDGE_CURVE('',#106410,#106357,#106459,.T.); +#106459 = SURFACE_CURVE('',#106460,(#106464,#106471),.PCURVE_S1.); +#106460 = LINE('',#106461,#106462); +#106461 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.530776333563)); +#106462 = VECTOR('',#106463,1.); +#106463 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#106464 = PCURVE('',#106371,#106465); +#106465 = DEFINITIONAL_REPRESENTATION('',(#106466),#106470); +#106466 = LINE('',#106467,#106468); +#106467 = CARTESIAN_POINT('',(0.E+000,-3.15)); +#106468 = VECTOR('',#106469,1.); +#106469 = DIRECTION('',(-1.,0.E+000)); +#106470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106471 = PCURVE('',#92455,#106472); +#106472 = DEFINITIONAL_REPRESENTATION('',(#106473),#106477); +#106473 = LINE('',#106474,#106475); +#106474 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#106475 = VECTOR('',#106476,1.); +#106476 = DIRECTION('',(-1.,-1.021336205033E-016)); +#106477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106478 = ADVANCED_FACE('',(#106479),#106292,.F.); +#106479 = FACE_BOUND('',#106480,.T.); +#106480 = EDGE_LOOP('',(#106481,#106510,#106531,#106532)); +#106481 = ORIENTED_EDGE('',*,*,#106482,.F.); +#106482 = EDGE_CURVE('',#106483,#106485,#106487,.T.); +#106483 = VERTEX_POINT('',#106484); +#106484 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.530776333563)); +#106485 = VERTEX_POINT('',#106486); +#106486 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.530776333563)); +#106487 = SURFACE_CURVE('',#106488,(#106492,#106499),.PCURVE_S1.); +#106488 = LINE('',#106489,#106490); +#106489 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#106490 = VECTOR('',#106491,1.); +#106491 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106492 = PCURVE('',#106292,#106493); +#106493 = DEFINITIONAL_REPRESENTATION('',(#106494),#106498); +#106494 = LINE('',#106495,#106496); +#106495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106496 = VECTOR('',#106497,1.); +#106497 = DIRECTION('',(0.E+000,-1.)); +#106498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106499 = PCURVE('',#106500,#106505); +#106500 = CYLINDRICAL_SURFACE('',#106501,0.119270391569); +#106501 = AXIS2_PLACEMENT_3D('',#106502,#106503,#106504); +#106502 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#106503 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106504 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106505 = DEFINITIONAL_REPRESENTATION('',(#106506),#106509); +#106506 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106507,#106508), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); +#106507 = CARTESIAN_POINT('',(4.712388980385,-3.15)); +#106508 = CARTESIAN_POINT('',(4.712388980385,-3.35)); +#106509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104004 = PCURVE('',#90063,#104005); -#104005 = DEFINITIONAL_REPRESENTATION('',(#104006),#104010); -#104006 = CIRCLE('',#104007,0.208574704164); -#104007 = AXIS2_PLACEMENT_2D('',#104008,#104009); -#104008 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#104009 = DIRECTION('',(1.,0.E+000)); -#104010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106510 = ORIENTED_EDGE('',*,*,#106511,.T.); +#106511 = EDGE_CURVE('',#106483,#106278,#106512,.T.); +#106512 = SURFACE_CURVE('',#106513,(#106517,#106524),.PCURVE_S1.); +#106513 = LINE('',#106514,#106515); +#106514 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.530776333563)); +#106515 = VECTOR('',#106516,1.); +#106516 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#106517 = PCURVE('',#106292,#106518); +#106518 = DEFINITIONAL_REPRESENTATION('',(#106519),#106523); +#106519 = LINE('',#106520,#106521); +#106520 = CARTESIAN_POINT('',(0.E+000,-3.15)); +#106521 = VECTOR('',#106522,1.); +#106522 = DIRECTION('',(1.,0.E+000)); +#106523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104011 = ADVANCED_FACE('',(#104012),#103979,.F.); -#104012 = FACE_BOUND('',#104013,.T.); -#104013 = EDGE_LOOP('',(#104014,#104043,#104064,#104065)); -#104014 = ORIENTED_EDGE('',*,*,#104015,.F.); -#104015 = EDGE_CURVE('',#104016,#104018,#104020,.T.); -#104016 = VERTEX_POINT('',#104017); -#104017 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.530776333563)); -#104018 = VERTEX_POINT('',#104019); -#104019 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.530776333563)); -#104020 = SURFACE_CURVE('',#104021,(#104025,#104032),.PCURVE_S1.); -#104021 = LINE('',#104022,#104023); -#104022 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#104023 = VECTOR('',#104024,1.); -#104024 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104025 = PCURVE('',#103979,#104026); -#104026 = DEFINITIONAL_REPRESENTATION('',(#104027),#104031); -#104027 = LINE('',#104028,#104029); -#104028 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104029 = VECTOR('',#104030,1.); -#104030 = DIRECTION('',(0.E+000,1.)); -#104031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104032 = PCURVE('',#104033,#104038); -#104033 = CYLINDRICAL_SURFACE('',#104034,0.2192697516); -#104034 = AXIS2_PLACEMENT_3D('',#104035,#104036,#104037); -#104035 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#104036 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104037 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104038 = DEFINITIONAL_REPRESENTATION('',(#104039),#104042); -#104039 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104040,#104041), - .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#104040 = CARTESIAN_POINT('',(4.712388980385,-3.35)); -#104041 = CARTESIAN_POINT('',(4.712388980385,-3.15)); -#104042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104043 = ORIENTED_EDGE('',*,*,#104044,.T.); -#104044 = EDGE_CURVE('',#104016,#103938,#104045,.T.); -#104045 = SURFACE_CURVE('',#104046,(#104050,#104057),.PCURVE_S1.); -#104046 = LINE('',#104047,#104048); -#104047 = CARTESIAN_POINT('',(6.65,-0.51959417205,0.530776333563)); -#104048 = VECTOR('',#104049,1.); -#104049 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104050 = PCURVE('',#103979,#104051); -#104051 = DEFINITIONAL_REPRESENTATION('',(#104052),#104056); -#104052 = LINE('',#104053,#104054); -#104053 = CARTESIAN_POINT('',(0.E+000,-3.35)); -#104054 = VECTOR('',#104055,1.); -#104055 = DIRECTION('',(-1.,0.E+000)); -#104056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104057 = PCURVE('',#90007,#104058); -#104058 = DEFINITIONAL_REPRESENTATION('',(#104059),#104063); -#104059 = LINE('',#104060,#104061); -#104060 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#104061 = VECTOR('',#104062,1.); -#104062 = DIRECTION('',(1.,-1.021336205033E-016)); -#104063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104064 = ORIENTED_EDGE('',*,*,#103964,.T.); -#104065 = ORIENTED_EDGE('',*,*,#104066,.F.); -#104066 = EDGE_CURVE('',#104018,#103965,#104067,.T.); -#104067 = SURFACE_CURVE('',#104068,(#104072,#104079),.PCURVE_S1.); -#104068 = LINE('',#104069,#104070); -#104069 = CARTESIAN_POINT('',(6.85,-0.51959417205,0.530776333563)); -#104070 = VECTOR('',#104071,1.); -#104071 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104072 = PCURVE('',#103979,#104073); -#104073 = DEFINITIONAL_REPRESENTATION('',(#104074),#104078); -#104074 = LINE('',#104075,#104076); -#104075 = CARTESIAN_POINT('',(0.E+000,-3.15)); -#104076 = VECTOR('',#104077,1.); -#104077 = DIRECTION('',(-1.,0.E+000)); -#104078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104079 = PCURVE('',#90063,#104080); -#104080 = DEFINITIONAL_REPRESENTATION('',(#104081),#104085); -#104081 = LINE('',#104082,#104083); -#104082 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#104083 = VECTOR('',#104084,1.); -#104084 = DIRECTION('',(-1.,-1.021336205033E-016)); -#104085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104086 = ADVANCED_FACE('',(#104087),#103900,.F.); -#104087 = FACE_BOUND('',#104088,.T.); -#104088 = EDGE_LOOP('',(#104089,#104118,#104139,#104140)); -#104089 = ORIENTED_EDGE('',*,*,#104090,.F.); -#104090 = EDGE_CURVE('',#104091,#104093,#104095,.T.); -#104091 = VERTEX_POINT('',#104092); -#104092 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.530776333563)); -#104093 = VERTEX_POINT('',#104094); -#104094 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.530776333563)); -#104095 = SURFACE_CURVE('',#104096,(#104100,#104107),.PCURVE_S1.); -#104096 = LINE('',#104097,#104098); -#104097 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#104098 = VECTOR('',#104099,1.); -#104099 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104100 = PCURVE('',#103900,#104101); -#104101 = DEFINITIONAL_REPRESENTATION('',(#104102),#104106); -#104102 = LINE('',#104103,#104104); -#104103 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104104 = VECTOR('',#104105,1.); -#104105 = DIRECTION('',(0.E+000,-1.)); -#104106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104107 = PCURVE('',#104108,#104113); -#104108 = CYLINDRICAL_SURFACE('',#104109,0.119270391569); -#104109 = AXIS2_PLACEMENT_3D('',#104110,#104111,#104112); -#104110 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#104111 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104112 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104113 = DEFINITIONAL_REPRESENTATION('',(#104114),#104117); -#104114 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104115,#104116), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#104115 = CARTESIAN_POINT('',(4.712388980385,-3.15)); -#104116 = CARTESIAN_POINT('',(4.712388980385,-3.35)); -#104117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104118 = ORIENTED_EDGE('',*,*,#104119,.T.); -#104119 = EDGE_CURVE('',#104091,#103886,#104120,.T.); -#104120 = SURFACE_CURVE('',#104121,(#104125,#104132),.PCURVE_S1.); -#104121 = LINE('',#104122,#104123); -#104122 = CARTESIAN_POINT('',(6.85,-0.419594812019,0.530776333563)); -#104123 = VECTOR('',#104124,1.); -#104124 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104125 = PCURVE('',#103900,#104126); -#104126 = DEFINITIONAL_REPRESENTATION('',(#104127),#104131); -#104127 = LINE('',#104128,#104129); -#104128 = CARTESIAN_POINT('',(0.E+000,-3.15)); -#104129 = VECTOR('',#104130,1.); -#104130 = DIRECTION('',(1.,0.E+000)); -#104131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104132 = PCURVE('',#90063,#104133); -#104133 = DEFINITIONAL_REPRESENTATION('',(#104134),#104138); -#104134 = LINE('',#104135,#104136); -#104135 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#104136 = VECTOR('',#104137,1.); -#104137 = DIRECTION('',(-1.,-1.021336205033E-016)); -#104138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104139 = ORIENTED_EDGE('',*,*,#103885,.T.); -#104140 = ORIENTED_EDGE('',*,*,#104141,.F.); -#104141 = EDGE_CURVE('',#104093,#103859,#104142,.T.); -#104142 = SURFACE_CURVE('',#104143,(#104147,#104154),.PCURVE_S1.); -#104143 = LINE('',#104144,#104145); -#104144 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.530776333563)); -#104145 = VECTOR('',#104146,1.); -#104146 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104147 = PCURVE('',#103900,#104148); -#104148 = DEFINITIONAL_REPRESENTATION('',(#104149),#104153); -#104149 = LINE('',#104150,#104151); -#104150 = CARTESIAN_POINT('',(0.E+000,-3.35)); -#104151 = VECTOR('',#104152,1.); -#104152 = DIRECTION('',(1.,0.E+000)); -#104153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104154 = PCURVE('',#90007,#104155); -#104155 = DEFINITIONAL_REPRESENTATION('',(#104156),#104160); -#104156 = LINE('',#104157,#104158); -#104157 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#104158 = VECTOR('',#104159,1.); -#104159 = DIRECTION('',(1.,-1.021336205033E-016)); -#104160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106524 = PCURVE('',#92455,#106525); +#106525 = DEFINITIONAL_REPRESENTATION('',(#106526),#106530); +#106526 = LINE('',#106527,#106528); +#106527 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#106528 = VECTOR('',#106529,1.); +#106529 = DIRECTION('',(-1.,-1.021336205033E-016)); +#106530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104161 = ADVANCED_FACE('',(#104162),#104033,.T.); -#104162 = FACE_BOUND('',#104163,.T.); -#104163 = EDGE_LOOP('',(#104164,#104187,#104188,#104215)); -#104164 = ORIENTED_EDGE('',*,*,#104165,.T.); -#104165 = EDGE_CURVE('',#104166,#104016,#104168,.T.); -#104166 = VERTEX_POINT('',#104167); -#104167 = CARTESIAN_POINT('',(6.65,-0.304819755875,0.75)); -#104168 = SURFACE_CURVE('',#104169,(#104174,#104180),.PCURVE_S1.); -#104169 = CIRCLE('',#104170,0.2192697516); -#104170 = AXIS2_PLACEMENT_3D('',#104171,#104172,#104173); -#104171 = CARTESIAN_POINT('',(6.65,-0.30032442045,0.530776333563)); -#104172 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104173 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104174 = PCURVE('',#104033,#104175); -#104175 = DEFINITIONAL_REPRESENTATION('',(#104176),#104179); -#104176 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104177,#104178), +#106531 = ORIENTED_EDGE('',*,*,#106277,.T.); +#106532 = ORIENTED_EDGE('',*,*,#106533,.F.); +#106533 = EDGE_CURVE('',#106485,#106251,#106534,.T.); +#106534 = SURFACE_CURVE('',#106535,(#106539,#106546),.PCURVE_S1.); +#106535 = LINE('',#106536,#106537); +#106536 = CARTESIAN_POINT('',(6.65,-0.419594812019,0.530776333563)); +#106537 = VECTOR('',#106538,1.); +#106538 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#106539 = PCURVE('',#106292,#106540); +#106540 = DEFINITIONAL_REPRESENTATION('',(#106541),#106545); +#106541 = LINE('',#106542,#106543); +#106542 = CARTESIAN_POINT('',(0.E+000,-3.35)); +#106543 = VECTOR('',#106544,1.); +#106544 = DIRECTION('',(1.,0.E+000)); +#106545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106546 = PCURVE('',#92399,#106547); +#106547 = DEFINITIONAL_REPRESENTATION('',(#106548),#106552); +#106548 = LINE('',#106549,#106550); +#106549 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#106550 = VECTOR('',#106551,1.); +#106551 = DIRECTION('',(1.,-1.021336205033E-016)); +#106552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106553 = ADVANCED_FACE('',(#106554),#106425,.T.); +#106554 = FACE_BOUND('',#106555,.T.); +#106555 = EDGE_LOOP('',(#106556,#106579,#106580,#106607)); +#106556 = ORIENTED_EDGE('',*,*,#106557,.T.); +#106557 = EDGE_CURVE('',#106558,#106408,#106560,.T.); +#106558 = VERTEX_POINT('',#106559); +#106559 = CARTESIAN_POINT('',(6.65,-0.304819755875,0.75)); +#106560 = SURFACE_CURVE('',#106561,(#106566,#106572),.PCURVE_S1.); +#106561 = CIRCLE('',#106562,0.2192697516); +#106562 = AXIS2_PLACEMENT_3D('',#106563,#106564,#106565); +#106563 = CARTESIAN_POINT('',(6.65,-0.30032442045,0.530776333563)); +#106564 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106565 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106566 = PCURVE('',#106425,#106567); +#106567 = DEFINITIONAL_REPRESENTATION('',(#106568),#106571); +#106568 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106569,#106570), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#104177 = CARTESIAN_POINT('',(3.162095483347,-3.35)); -#104178 = CARTESIAN_POINT('',(4.712388980385,-3.35)); -#104179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104180 = PCURVE('',#90007,#104181); -#104181 = DEFINITIONAL_REPRESENTATION('',(#104182),#104186); -#104182 = CIRCLE('',#104183,0.2192697516); -#104183 = AXIS2_PLACEMENT_2D('',#104184,#104185); -#104184 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#104185 = DIRECTION('',(1.,0.E+000)); -#104186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104187 = ORIENTED_EDGE('',*,*,#104015,.T.); -#104188 = ORIENTED_EDGE('',*,*,#104189,.F.); -#104189 = EDGE_CURVE('',#104190,#104018,#104192,.T.); -#104190 = VERTEX_POINT('',#104191); -#104191 = CARTESIAN_POINT('',(6.85,-0.304819755875,0.75)); -#104192 = SURFACE_CURVE('',#104193,(#104198,#104204),.PCURVE_S1.); -#104193 = CIRCLE('',#104194,0.2192697516); -#104194 = AXIS2_PLACEMENT_3D('',#104195,#104196,#104197); -#104195 = CARTESIAN_POINT('',(6.85,-0.30032442045,0.530776333563)); -#104196 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104197 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104198 = PCURVE('',#104033,#104199); -#104199 = DEFINITIONAL_REPRESENTATION('',(#104200),#104203); -#104200 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104201,#104202), +#106569 = CARTESIAN_POINT('',(3.162095483347,-3.35)); +#106570 = CARTESIAN_POINT('',(4.712388980385,-3.35)); +#106571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106572 = PCURVE('',#92399,#106573); +#106573 = DEFINITIONAL_REPRESENTATION('',(#106574),#106578); +#106574 = CIRCLE('',#106575,0.2192697516); +#106575 = AXIS2_PLACEMENT_2D('',#106576,#106577); +#106576 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#106577 = DIRECTION('',(1.,0.E+000)); +#106578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106579 = ORIENTED_EDGE('',*,*,#106407,.T.); +#106580 = ORIENTED_EDGE('',*,*,#106581,.F.); +#106581 = EDGE_CURVE('',#106582,#106410,#106584,.T.); +#106582 = VERTEX_POINT('',#106583); +#106583 = CARTESIAN_POINT('',(6.85,-0.304819755875,0.75)); +#106584 = SURFACE_CURVE('',#106585,(#106590,#106596),.PCURVE_S1.); +#106585 = CIRCLE('',#106586,0.2192697516); +#106586 = AXIS2_PLACEMENT_3D('',#106587,#106588,#106589); +#106587 = CARTESIAN_POINT('',(6.85,-0.30032442045,0.530776333563)); +#106588 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106589 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106590 = PCURVE('',#106425,#106591); +#106591 = DEFINITIONAL_REPRESENTATION('',(#106592),#106595); +#106592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106593,#106594), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#104201 = CARTESIAN_POINT('',(3.162095483347,-3.15)); -#104202 = CARTESIAN_POINT('',(4.712388980385,-3.15)); -#104203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106593 = CARTESIAN_POINT('',(3.162095483347,-3.15)); +#106594 = CARTESIAN_POINT('',(4.712388980385,-3.15)); +#106595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104204 = PCURVE('',#90063,#104205); -#104205 = DEFINITIONAL_REPRESENTATION('',(#104206),#104214); -#104206 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104207,#104208,#104209, - #104210,#104211,#104212,#104213),.UNSPECIFIED.,.F.,.F.) +#106596 = PCURVE('',#92455,#106597); +#106597 = DEFINITIONAL_REPRESENTATION('',(#106598),#106606); +#106598 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106599,#106600,#106601, + #106602,#106603,#106604,#106605),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#104207 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#104208 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#104209 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#104210 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#104211 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#104212 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#104213 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#104214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104215 = ORIENTED_EDGE('',*,*,#104216,.T.); -#104216 = EDGE_CURVE('',#104190,#104166,#104217,.T.); -#104217 = SURFACE_CURVE('',#104218,(#104222,#104228),.PCURVE_S1.); -#104218 = LINE('',#104219,#104220); -#104219 = CARTESIAN_POINT('',(6.65,-0.304819755875,0.75)); -#104220 = VECTOR('',#104221,1.); -#104221 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104222 = PCURVE('',#104033,#104223); -#104223 = DEFINITIONAL_REPRESENTATION('',(#104224),#104227); -#104224 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104225,#104226), +#106599 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#106600 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#106601 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#106602 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#106603 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#106604 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#106605 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#106606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106607 = ORIENTED_EDGE('',*,*,#106608,.T.); +#106608 = EDGE_CURVE('',#106582,#106558,#106609,.T.); +#106609 = SURFACE_CURVE('',#106610,(#106614,#106620),.PCURVE_S1.); +#106610 = LINE('',#106611,#106612); +#106611 = CARTESIAN_POINT('',(6.65,-0.304819755875,0.75)); +#106612 = VECTOR('',#106613,1.); +#106613 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106614 = PCURVE('',#106425,#106615); +#106615 = DEFINITIONAL_REPRESENTATION('',(#106616),#106619); +#106616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106617,#106618), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#104225 = CARTESIAN_POINT('',(3.162095483347,-3.15)); -#104226 = CARTESIAN_POINT('',(3.162095483347,-3.35)); -#104227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104228 = PCURVE('',#90035,#104229); -#104229 = DEFINITIONAL_REPRESENTATION('',(#104230),#104234); -#104230 = LINE('',#104231,#104232); -#104231 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#104232 = VECTOR('',#104233,1.); -#104233 = DIRECTION('',(0.E+000,-1.)); -#104234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104235 = ADVANCED_FACE('',(#104236),#104108,.F.); -#104236 = FACE_BOUND('',#104237,.F.); -#104237 = EDGE_LOOP('',(#104238,#104265,#104287,#104308)); -#104238 = ORIENTED_EDGE('',*,*,#104239,.F.); -#104239 = EDGE_CURVE('',#104240,#104091,#104242,.T.); -#104240 = VERTEX_POINT('',#104241); -#104241 = CARTESIAN_POINT('',(6.85,-0.303662633502,0.65)); -#104242 = SURFACE_CURVE('',#104243,(#104248,#104254),.PCURVE_S1.); -#104243 = CIRCLE('',#104244,0.119270391569); -#104244 = AXIS2_PLACEMENT_3D('',#104245,#104246,#104247); -#104245 = CARTESIAN_POINT('',(6.85,-0.30032442045,0.530776333563)); -#104246 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104247 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104248 = PCURVE('',#104108,#104249); -#104249 = DEFINITIONAL_REPRESENTATION('',(#104250),#104253); -#104250 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104251,#104252), +#106617 = CARTESIAN_POINT('',(3.162095483347,-3.15)); +#106618 = CARTESIAN_POINT('',(3.162095483347,-3.35)); +#106619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106620 = PCURVE('',#92427,#106621); +#106621 = DEFINITIONAL_REPRESENTATION('',(#106622),#106626); +#106622 = LINE('',#106623,#106624); +#106623 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#106624 = VECTOR('',#106625,1.); +#106625 = DIRECTION('',(0.E+000,-1.)); +#106626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106627 = ADVANCED_FACE('',(#106628),#106500,.F.); +#106628 = FACE_BOUND('',#106629,.F.); +#106629 = EDGE_LOOP('',(#106630,#106657,#106679,#106700)); +#106630 = ORIENTED_EDGE('',*,*,#106631,.F.); +#106631 = EDGE_CURVE('',#106632,#106483,#106634,.T.); +#106632 = VERTEX_POINT('',#106633); +#106633 = CARTESIAN_POINT('',(6.85,-0.303662633502,0.65)); +#106634 = SURFACE_CURVE('',#106635,(#106640,#106646),.PCURVE_S1.); +#106635 = CIRCLE('',#106636,0.119270391569); +#106636 = AXIS2_PLACEMENT_3D('',#106637,#106638,#106639); +#106637 = CARTESIAN_POINT('',(6.85,-0.30032442045,0.530776333563)); +#106638 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106639 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106640 = PCURVE('',#106500,#106641); +#106641 = DEFINITIONAL_REPRESENTATION('',(#106642),#106645); +#106642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106643,#106644), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#104251 = CARTESIAN_POINT('',(3.169584923929,-3.15)); -#104252 = CARTESIAN_POINT('',(4.712388980385,-3.15)); -#104253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#106643 = CARTESIAN_POINT('',(3.169584923929,-3.15)); +#106644 = CARTESIAN_POINT('',(4.712388980385,-3.15)); +#106645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104254 = PCURVE('',#90063,#104255); -#104255 = DEFINITIONAL_REPRESENTATION('',(#104256),#104264); -#104256 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104257,#104258,#104259, - #104260,#104261,#104262,#104263),.UNSPECIFIED.,.F.,.F.) +#106646 = PCURVE('',#92455,#106647); +#106647 = DEFINITIONAL_REPRESENTATION('',(#106648),#106656); +#106648 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106649,#106650,#106651, + #106652,#106653,#106654,#106655),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#104257 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#104258 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#104259 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#104260 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#104261 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#104262 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#104263 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#104264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104265 = ORIENTED_EDGE('',*,*,#104266,.F.); -#104266 = EDGE_CURVE('',#104267,#104240,#104269,.T.); -#104267 = VERTEX_POINT('',#104268); -#104268 = CARTESIAN_POINT('',(6.65,-0.303662633502,0.65)); -#104269 = SURFACE_CURVE('',#104270,(#104274,#104280),.PCURVE_S1.); -#104270 = LINE('',#104271,#104272); -#104271 = CARTESIAN_POINT('',(6.65,-0.303662633502,0.65)); -#104272 = VECTOR('',#104273,1.); -#104273 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104274 = PCURVE('',#104108,#104275); -#104275 = DEFINITIONAL_REPRESENTATION('',(#104276),#104279); -#104276 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104277,#104278), +#106649 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#106650 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#106651 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#106652 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#106653 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#106654 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#106655 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#106656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106657 = ORIENTED_EDGE('',*,*,#106658,.F.); +#106658 = EDGE_CURVE('',#106659,#106632,#106661,.T.); +#106659 = VERTEX_POINT('',#106660); +#106660 = CARTESIAN_POINT('',(6.65,-0.303662633502,0.65)); +#106661 = SURFACE_CURVE('',#106662,(#106666,#106672),.PCURVE_S1.); +#106662 = LINE('',#106663,#106664); +#106663 = CARTESIAN_POINT('',(6.65,-0.303662633502,0.65)); +#106664 = VECTOR('',#106665,1.); +#106665 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106666 = PCURVE('',#106500,#106667); +#106667 = DEFINITIONAL_REPRESENTATION('',(#106668),#106671); +#106668 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106669,#106670), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#104277 = CARTESIAN_POINT('',(3.169584923929,-3.35)); -#104278 = CARTESIAN_POINT('',(3.169584923929,-3.15)); -#104279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104280 = PCURVE('',#90089,#104281); -#104281 = DEFINITIONAL_REPRESENTATION('',(#104282),#104286); -#104282 = LINE('',#104283,#104284); -#104283 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#104284 = VECTOR('',#104285,1.); -#104285 = DIRECTION('',(0.E+000,1.)); -#104286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104287 = ORIENTED_EDGE('',*,*,#104288,.T.); -#104288 = EDGE_CURVE('',#104267,#104093,#104289,.T.); -#104289 = SURFACE_CURVE('',#104290,(#104295,#104301),.PCURVE_S1.); -#104290 = CIRCLE('',#104291,0.119270391569); -#104291 = AXIS2_PLACEMENT_3D('',#104292,#104293,#104294); -#104292 = CARTESIAN_POINT('',(6.65,-0.30032442045,0.530776333563)); -#104293 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104294 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104295 = PCURVE('',#104108,#104296); -#104296 = DEFINITIONAL_REPRESENTATION('',(#104297),#104300); -#104297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104298,#104299), +#106669 = CARTESIAN_POINT('',(3.169584923929,-3.35)); +#106670 = CARTESIAN_POINT('',(3.169584923929,-3.15)); +#106671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106672 = PCURVE('',#92481,#106673); +#106673 = DEFINITIONAL_REPRESENTATION('',(#106674),#106678); +#106674 = LINE('',#106675,#106676); +#106675 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#106676 = VECTOR('',#106677,1.); +#106677 = DIRECTION('',(0.E+000,1.)); +#106678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106679 = ORIENTED_EDGE('',*,*,#106680,.T.); +#106680 = EDGE_CURVE('',#106659,#106485,#106681,.T.); +#106681 = SURFACE_CURVE('',#106682,(#106687,#106693),.PCURVE_S1.); +#106682 = CIRCLE('',#106683,0.119270391569); +#106683 = AXIS2_PLACEMENT_3D('',#106684,#106685,#106686); +#106684 = CARTESIAN_POINT('',(6.65,-0.30032442045,0.530776333563)); +#106685 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106686 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106687 = PCURVE('',#106500,#106688); +#106688 = DEFINITIONAL_REPRESENTATION('',(#106689),#106692); +#106689 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106690,#106691), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#104298 = CARTESIAN_POINT('',(3.169584923929,-3.35)); -#104299 = CARTESIAN_POINT('',(4.712388980385,-3.35)); -#104300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104301 = PCURVE('',#90007,#104302); -#104302 = DEFINITIONAL_REPRESENTATION('',(#104303),#104307); -#104303 = CIRCLE('',#104304,0.119270391569); -#104304 = AXIS2_PLACEMENT_2D('',#104305,#104306); -#104305 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#104306 = DIRECTION('',(1.,0.E+000)); -#104307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104308 = ORIENTED_EDGE('',*,*,#104090,.F.); -#104309 = ADVANCED_FACE('',(#104310),#90007,.F.); -#104310 = FACE_BOUND('',#104311,.T.); -#104311 = EDGE_LOOP('',(#104312,#104333,#104334,#104335,#104336,#104337, - #104358,#104359,#104360,#104361,#104362,#104383)); -#104312 = ORIENTED_EDGE('',*,*,#104313,.F.); -#104313 = EDGE_CURVE('',#104267,#89992,#104314,.T.); -#104314 = SURFACE_CURVE('',#104315,(#104319,#104326),.PCURVE_S1.); -#104315 = LINE('',#104316,#104317); -#104316 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); -#104317 = VECTOR('',#104318,1.); -#104318 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#104319 = PCURVE('',#90007,#104320); -#104320 = DEFINITIONAL_REPRESENTATION('',(#104321),#104325); -#104321 = LINE('',#104322,#104323); -#104322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104323 = VECTOR('',#104324,1.); -#104324 = DIRECTION('',(-3.563627120235E-016,1.)); -#104325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104326 = PCURVE('',#90089,#104327); -#104327 = DEFINITIONAL_REPRESENTATION('',(#104328),#104332); -#104328 = LINE('',#104329,#104330); -#104329 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104330 = VECTOR('',#104331,1.); -#104331 = DIRECTION('',(-1.,0.E+000)); -#104332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104333 = ORIENTED_EDGE('',*,*,#104288,.T.); -#104334 = ORIENTED_EDGE('',*,*,#104141,.T.); -#104335 = ORIENTED_EDGE('',*,*,#103858,.T.); -#104336 = ORIENTED_EDGE('',*,*,#103702,.T.); -#104337 = ORIENTED_EDGE('',*,*,#104338,.T.); -#104338 = EDGE_CURVE('',#103675,#103756,#104339,.T.); -#104339 = SURFACE_CURVE('',#104340,(#104344,#104351),.PCURVE_S1.); -#104340 = LINE('',#104341,#104342); -#104341 = CARTESIAN_POINT('',(6.65,-1.,1.159810404338E-002)); -#104342 = VECTOR('',#104343,1.); -#104343 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#104344 = PCURVE('',#90007,#104345); -#104345 = DEFINITIONAL_REPRESENTATION('',(#104346),#104350); -#104346 = LINE('',#104347,#104348); -#104347 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#104348 = VECTOR('',#104349,1.); -#104349 = DIRECTION('',(-1.,-2.101748079665E-016)); -#104350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104351 = PCURVE('',#103690,#104352); -#104352 = DEFINITIONAL_REPRESENTATION('',(#104353),#104357); -#104353 = LINE('',#104354,#104355); -#104354 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#104355 = VECTOR('',#104356,1.); -#104356 = DIRECTION('',(-1.,0.E+000)); -#104357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104358 = ORIENTED_EDGE('',*,*,#103753,.F.); -#104359 = ORIENTED_EDGE('',*,*,#103937,.F.); -#104360 = ORIENTED_EDGE('',*,*,#104044,.F.); -#104361 = ORIENTED_EDGE('',*,*,#104165,.F.); -#104362 = ORIENTED_EDGE('',*,*,#104363,.T.); -#104363 = EDGE_CURVE('',#104166,#89990,#104364,.T.); -#104364 = SURFACE_CURVE('',#104365,(#104369,#104376),.PCURVE_S1.); -#104365 = LINE('',#104366,#104367); -#104366 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.75)); -#104367 = VECTOR('',#104368,1.); -#104368 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#104369 = PCURVE('',#90007,#104370); -#104370 = DEFINITIONAL_REPRESENTATION('',(#104371),#104375); -#104371 = LINE('',#104372,#104373); -#104372 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#104373 = VECTOR('',#104374,1.); -#104374 = DIRECTION('',(-3.563627120235E-016,1.)); -#104375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104376 = PCURVE('',#90035,#104377); -#104377 = DEFINITIONAL_REPRESENTATION('',(#104378),#104382); -#104378 = LINE('',#104379,#104380); -#104379 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104380 = VECTOR('',#104381,1.); -#104381 = DIRECTION('',(1.,0.E+000)); -#104382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104383 = ORIENTED_EDGE('',*,*,#89989,.T.); -#104384 = ADVANCED_FACE('',(#104385),#90035,.F.); -#104385 = FACE_BOUND('',#104386,.T.); -#104386 = EDGE_LOOP('',(#104387,#104388,#104409,#104410)); -#104387 = ORIENTED_EDGE('',*,*,#104216,.F.); -#104388 = ORIENTED_EDGE('',*,*,#104389,.T.); -#104389 = EDGE_CURVE('',#104190,#90020,#104390,.T.); -#104390 = SURFACE_CURVE('',#104391,(#104395,#104402),.PCURVE_S1.); -#104391 = LINE('',#104392,#104393); -#104392 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.75)); -#104393 = VECTOR('',#104394,1.); -#104394 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#104395 = PCURVE('',#90035,#104396); -#104396 = DEFINITIONAL_REPRESENTATION('',(#104397),#104401); -#104397 = LINE('',#104398,#104399); -#104398 = CARTESIAN_POINT('',(0.E+000,0.2)); -#104399 = VECTOR('',#104400,1.); -#104400 = DIRECTION('',(1.,0.E+000)); -#104401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104402 = PCURVE('',#90063,#104403); -#104403 = DEFINITIONAL_REPRESENTATION('',(#104404),#104408); -#104404 = LINE('',#104405,#104406); -#104405 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#104406 = VECTOR('',#104407,1.); -#104407 = DIRECTION('',(3.563627120235E-016,1.)); -#104408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104409 = ORIENTED_EDGE('',*,*,#90019,.T.); -#104410 = ORIENTED_EDGE('',*,*,#104363,.F.); -#104411 = ADVANCED_FACE('',(#104412),#90063,.F.); -#104412 = FACE_BOUND('',#104413,.T.); -#104413 = EDGE_LOOP('',(#104414,#104415,#104416,#104417,#104418,#104419, - #104440,#104441,#104442,#104443,#104444,#104465)); -#104414 = ORIENTED_EDGE('',*,*,#104389,.F.); -#104415 = ORIENTED_EDGE('',*,*,#104189,.T.); -#104416 = ORIENTED_EDGE('',*,*,#104066,.T.); -#104417 = ORIENTED_EDGE('',*,*,#103991,.T.); -#104418 = ORIENTED_EDGE('',*,*,#103806,.T.); -#104419 = ORIENTED_EDGE('',*,*,#104420,.T.); -#104420 = EDGE_CURVE('',#103784,#103647,#104421,.T.); -#104421 = SURFACE_CURVE('',#104422,(#104426,#104433),.PCURVE_S1.); -#104422 = LINE('',#104423,#104424); -#104423 = CARTESIAN_POINT('',(6.85,-1.,1.159810404338E-002)); -#104424 = VECTOR('',#104425,1.); -#104425 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#104426 = PCURVE('',#90063,#104427); -#104427 = DEFINITIONAL_REPRESENTATION('',(#104428),#104432); -#104428 = LINE('',#104429,#104430); -#104429 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#104430 = VECTOR('',#104431,1.); -#104431 = DIRECTION('',(-1.,2.101748079665E-016)); -#104432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104433 = PCURVE('',#103690,#104434); -#104434 = DEFINITIONAL_REPRESENTATION('',(#104435),#104439); -#104435 = LINE('',#104436,#104437); -#104436 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#104437 = VECTOR('',#104438,1.); -#104438 = DIRECTION('',(1.,0.E+000)); -#104439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104440 = ORIENTED_EDGE('',*,*,#103644,.F.); -#104441 = ORIENTED_EDGE('',*,*,#103912,.F.); -#104442 = ORIENTED_EDGE('',*,*,#104119,.F.); -#104443 = ORIENTED_EDGE('',*,*,#104239,.F.); -#104444 = ORIENTED_EDGE('',*,*,#104445,.T.); -#104445 = EDGE_CURVE('',#104240,#90048,#104446,.T.); -#104446 = SURFACE_CURVE('',#104447,(#104451,#104458),.PCURVE_S1.); -#104447 = LINE('',#104448,#104449); -#104448 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.65)); -#104449 = VECTOR('',#104450,1.); -#104450 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#104451 = PCURVE('',#90063,#104452); -#104452 = DEFINITIONAL_REPRESENTATION('',(#104453),#104457); -#104453 = LINE('',#104454,#104455); -#104454 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104455 = VECTOR('',#104456,1.); -#104456 = DIRECTION('',(3.563627120235E-016,1.)); -#104457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104458 = PCURVE('',#90089,#104459); -#104459 = DEFINITIONAL_REPRESENTATION('',(#104460),#104464); -#104460 = LINE('',#104461,#104462); -#104461 = CARTESIAN_POINT('',(0.E+000,0.2)); -#104462 = VECTOR('',#104463,1.); -#104463 = DIRECTION('',(-1.,0.E+000)); -#104464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104465 = ORIENTED_EDGE('',*,*,#90047,.T.); -#104466 = ADVANCED_FACE('',(#104467),#90089,.F.); -#104467 = FACE_BOUND('',#104468,.T.); -#104468 = EDGE_LOOP('',(#104469,#104470,#104471,#104472)); -#104469 = ORIENTED_EDGE('',*,*,#104266,.F.); -#104470 = ORIENTED_EDGE('',*,*,#104313,.T.); -#104471 = ORIENTED_EDGE('',*,*,#90075,.T.); -#104472 = ORIENTED_EDGE('',*,*,#104445,.F.); -#104473 = ADVANCED_FACE('',(#104474),#103690,.T.); -#104474 = FACE_BOUND('',#104475,.T.); -#104475 = EDGE_LOOP('',(#104476,#104477,#104478,#104479)); -#104476 = ORIENTED_EDGE('',*,*,#104420,.F.); -#104477 = ORIENTED_EDGE('',*,*,#103783,.F.); -#104478 = ORIENTED_EDGE('',*,*,#104338,.F.); -#104479 = ORIENTED_EDGE('',*,*,#103674,.F.); -#104480 = ADVANCED_FACE('',(#104481),#104495,.T.); -#104481 = FACE_BOUND('',#104482,.T.); -#104482 = EDGE_LOOP('',(#104483,#104513,#104541,#104564)); -#104483 = ORIENTED_EDGE('',*,*,#104484,.T.); -#104484 = EDGE_CURVE('',#104485,#104487,#104489,.T.); -#104485 = VERTEX_POINT('',#104486); -#104486 = CARTESIAN_POINT('',(7.35,-0.74341632541,-0.308197125857)); -#104487 = VERTEX_POINT('',#104488); -#104488 = CARTESIAN_POINT('',(7.35,-1.,-0.308197125857)); -#104489 = SURFACE_CURVE('',#104490,(#104494,#104506),.PCURVE_S1.); -#104490 = LINE('',#104491,#104492); -#104491 = CARTESIAN_POINT('',(7.35,-0.74341632541,-0.308197125857)); -#104492 = VECTOR('',#104493,1.); -#104493 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#104494 = PCURVE('',#104495,#104500); -#104495 = PLANE('',#104496); -#104496 = AXIS2_PLACEMENT_3D('',#104497,#104498,#104499); -#104497 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#104498 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104499 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104500 = DEFINITIONAL_REPRESENTATION('',(#104501),#104505); -#104501 = LINE('',#104502,#104503); -#104502 = CARTESIAN_POINT('',(2.65,0.E+000)); -#104503 = VECTOR('',#104504,1.); -#104504 = DIRECTION('',(0.E+000,-1.)); -#104505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104506 = PCURVE('',#88586,#104507); -#104507 = DEFINITIONAL_REPRESENTATION('',(#104508),#104512); -#104508 = LINE('',#104509,#104510); -#104509 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#104510 = VECTOR('',#104511,1.); -#104511 = DIRECTION('',(0.E+000,-1.)); -#104512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104513 = ORIENTED_EDGE('',*,*,#104514,.T.); -#104514 = EDGE_CURVE('',#104487,#104515,#104517,.T.); -#104515 = VERTEX_POINT('',#104516); -#104516 = CARTESIAN_POINT('',(7.15,-1.,-0.308197125857)); -#104517 = SURFACE_CURVE('',#104518,(#104522,#104529),.PCURVE_S1.); -#104518 = LINE('',#104519,#104520); -#104519 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#104520 = VECTOR('',#104521,1.); -#104521 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104522 = PCURVE('',#104495,#104523); -#104523 = DEFINITIONAL_REPRESENTATION('',(#104524),#104528); -#104524 = LINE('',#104525,#104526); -#104525 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#104526 = VECTOR('',#104527,1.); -#104527 = DIRECTION('',(1.,0.E+000)); -#104528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104529 = PCURVE('',#104530,#104535); -#104530 = PLANE('',#104531); -#104531 = AXIS2_PLACEMENT_3D('',#104532,#104533,#104534); -#104532 = CARTESIAN_POINT('',(7.25,-1.,-0.258196742327)); -#104533 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#104534 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#104535 = DEFINITIONAL_REPRESENTATION('',(#104536),#104540); -#104536 = LINE('',#104537,#104538); -#104537 = CARTESIAN_POINT('',(5.000038352949E-002,2.75)); -#104538 = VECTOR('',#104539,1.); -#104539 = DIRECTION('',(0.E+000,-1.)); -#104540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104541 = ORIENTED_EDGE('',*,*,#104542,.F.); -#104542 = EDGE_CURVE('',#104543,#104515,#104545,.T.); -#104543 = VERTEX_POINT('',#104544); -#104544 = CARTESIAN_POINT('',(7.15,-0.74341632541,-0.308197125857)); -#104545 = SURFACE_CURVE('',#104546,(#104550,#104557),.PCURVE_S1.); -#104546 = LINE('',#104547,#104548); -#104547 = CARTESIAN_POINT('',(7.15,-0.74341632541,-0.308197125857)); -#104548 = VECTOR('',#104549,1.); -#104549 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#104550 = PCURVE('',#104495,#104551); -#104551 = DEFINITIONAL_REPRESENTATION('',(#104552),#104556); -#104552 = LINE('',#104553,#104554); -#104553 = CARTESIAN_POINT('',(2.85,0.E+000)); -#104554 = VECTOR('',#104555,1.); -#104555 = DIRECTION('',(0.E+000,-1.)); -#104556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104557 = PCURVE('',#88530,#104558); -#104558 = DEFINITIONAL_REPRESENTATION('',(#104559),#104563); -#104559 = LINE('',#104560,#104561); -#104560 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#104561 = VECTOR('',#104562,1.); -#104562 = DIRECTION('',(0.E+000,-1.)); -#104563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104564 = ORIENTED_EDGE('',*,*,#104565,.T.); -#104565 = EDGE_CURVE('',#104543,#104485,#104566,.T.); -#104566 = SURFACE_CURVE('',#104567,(#104571,#104578),.PCURVE_S1.); -#104567 = LINE('',#104568,#104569); -#104568 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#104569 = VECTOR('',#104570,1.); -#104570 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104571 = PCURVE('',#104495,#104572); -#104572 = DEFINITIONAL_REPRESENTATION('',(#104573),#104577); -#104573 = LINE('',#104574,#104575); -#104574 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104575 = VECTOR('',#104576,1.); -#104576 = DIRECTION('',(-1.,0.E+000)); -#104577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104578 = PCURVE('',#104579,#104584); -#104579 = CYLINDRICAL_SURFACE('',#104580,0.308574064194); -#104580 = AXIS2_PLACEMENT_3D('',#104581,#104582,#104583); -#104581 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#104582 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104583 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104584 = DEFINITIONAL_REPRESENTATION('',(#104585),#104588); -#104585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104586,#104587), +#106690 = CARTESIAN_POINT('',(3.169584923929,-3.35)); +#106691 = CARTESIAN_POINT('',(4.712388980385,-3.35)); +#106692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106693 = PCURVE('',#92399,#106694); +#106694 = DEFINITIONAL_REPRESENTATION('',(#106695),#106699); +#106695 = CIRCLE('',#106696,0.119270391569); +#106696 = AXIS2_PLACEMENT_2D('',#106697,#106698); +#106697 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#106698 = DIRECTION('',(1.,0.E+000)); +#106699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106700 = ORIENTED_EDGE('',*,*,#106482,.F.); +#106701 = ADVANCED_FACE('',(#106702),#92399,.F.); +#106702 = FACE_BOUND('',#106703,.T.); +#106703 = EDGE_LOOP('',(#106704,#106725,#106726,#106727,#106728,#106729, + #106750,#106751,#106752,#106753,#106754,#106775)); +#106704 = ORIENTED_EDGE('',*,*,#106705,.F.); +#106705 = EDGE_CURVE('',#106659,#92384,#106706,.T.); +#106706 = SURFACE_CURVE('',#106707,(#106711,#106718),.PCURVE_S1.); +#106707 = LINE('',#106708,#106709); +#106708 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.65)); +#106709 = VECTOR('',#106710,1.); +#106710 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#106711 = PCURVE('',#92399,#106712); +#106712 = DEFINITIONAL_REPRESENTATION('',(#106713),#106717); +#106713 = LINE('',#106714,#106715); +#106714 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106715 = VECTOR('',#106716,1.); +#106716 = DIRECTION('',(-3.563627120235E-016,1.)); +#106717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106718 = PCURVE('',#92481,#106719); +#106719 = DEFINITIONAL_REPRESENTATION('',(#106720),#106724); +#106720 = LINE('',#106721,#106722); +#106721 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106722 = VECTOR('',#106723,1.); +#106723 = DIRECTION('',(-1.,0.E+000)); +#106724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106725 = ORIENTED_EDGE('',*,*,#106680,.T.); +#106726 = ORIENTED_EDGE('',*,*,#106533,.T.); +#106727 = ORIENTED_EDGE('',*,*,#106250,.T.); +#106728 = ORIENTED_EDGE('',*,*,#106094,.T.); +#106729 = ORIENTED_EDGE('',*,*,#106730,.T.); +#106730 = EDGE_CURVE('',#106067,#106148,#106731,.T.); +#106731 = SURFACE_CURVE('',#106732,(#106736,#106743),.PCURVE_S1.); +#106732 = LINE('',#106733,#106734); +#106733 = CARTESIAN_POINT('',(6.65,-1.,1.159810404338E-002)); +#106734 = VECTOR('',#106735,1.); +#106735 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#106736 = PCURVE('',#92399,#106737); +#106737 = DEFINITIONAL_REPRESENTATION('',(#106738),#106742); +#106738 = LINE('',#106739,#106740); +#106739 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#106740 = VECTOR('',#106741,1.); +#106741 = DIRECTION('',(-1.,-2.101748079665E-016)); +#106742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106743 = PCURVE('',#106082,#106744); +#106744 = DEFINITIONAL_REPRESENTATION('',(#106745),#106749); +#106745 = LINE('',#106746,#106747); +#106746 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#106747 = VECTOR('',#106748,1.); +#106748 = DIRECTION('',(-1.,0.E+000)); +#106749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106750 = ORIENTED_EDGE('',*,*,#106145,.F.); +#106751 = ORIENTED_EDGE('',*,*,#106329,.F.); +#106752 = ORIENTED_EDGE('',*,*,#106436,.F.); +#106753 = ORIENTED_EDGE('',*,*,#106557,.F.); +#106754 = ORIENTED_EDGE('',*,*,#106755,.T.); +#106755 = EDGE_CURVE('',#106558,#92382,#106756,.T.); +#106756 = SURFACE_CURVE('',#106757,(#106761,#106768),.PCURVE_S1.); +#106757 = LINE('',#106758,#106759); +#106758 = CARTESIAN_POINT('',(6.65,-0.527847992439,0.75)); +#106759 = VECTOR('',#106760,1.); +#106760 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#106761 = PCURVE('',#92399,#106762); +#106762 = DEFINITIONAL_REPRESENTATION('',(#106763),#106767); +#106763 = LINE('',#106764,#106765); +#106764 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#106765 = VECTOR('',#106766,1.); +#106766 = DIRECTION('',(-3.563627120235E-016,1.)); +#106767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106768 = PCURVE('',#92427,#106769); +#106769 = DEFINITIONAL_REPRESENTATION('',(#106770),#106774); +#106770 = LINE('',#106771,#106772); +#106771 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106772 = VECTOR('',#106773,1.); +#106773 = DIRECTION('',(1.,0.E+000)); +#106774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106775 = ORIENTED_EDGE('',*,*,#92381,.T.); +#106776 = ADVANCED_FACE('',(#106777),#92427,.F.); +#106777 = FACE_BOUND('',#106778,.T.); +#106778 = EDGE_LOOP('',(#106779,#106780,#106801,#106802)); +#106779 = ORIENTED_EDGE('',*,*,#106608,.F.); +#106780 = ORIENTED_EDGE('',*,*,#106781,.T.); +#106781 = EDGE_CURVE('',#106582,#92412,#106782,.T.); +#106782 = SURFACE_CURVE('',#106783,(#106787,#106794),.PCURVE_S1.); +#106783 = LINE('',#106784,#106785); +#106784 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.75)); +#106785 = VECTOR('',#106786,1.); +#106786 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#106787 = PCURVE('',#92427,#106788); +#106788 = DEFINITIONAL_REPRESENTATION('',(#106789),#106793); +#106789 = LINE('',#106790,#106791); +#106790 = CARTESIAN_POINT('',(0.E+000,0.2)); +#106791 = VECTOR('',#106792,1.); +#106792 = DIRECTION('',(1.,0.E+000)); +#106793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106794 = PCURVE('',#92455,#106795); +#106795 = DEFINITIONAL_REPRESENTATION('',(#106796),#106800); +#106796 = LINE('',#106797,#106798); +#106797 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#106798 = VECTOR('',#106799,1.); +#106799 = DIRECTION('',(3.563627120235E-016,1.)); +#106800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106801 = ORIENTED_EDGE('',*,*,#92411,.T.); +#106802 = ORIENTED_EDGE('',*,*,#106755,.F.); +#106803 = ADVANCED_FACE('',(#106804),#92455,.F.); +#106804 = FACE_BOUND('',#106805,.T.); +#106805 = EDGE_LOOP('',(#106806,#106807,#106808,#106809,#106810,#106811, + #106832,#106833,#106834,#106835,#106836,#106857)); +#106806 = ORIENTED_EDGE('',*,*,#106781,.F.); +#106807 = ORIENTED_EDGE('',*,*,#106581,.T.); +#106808 = ORIENTED_EDGE('',*,*,#106458,.T.); +#106809 = ORIENTED_EDGE('',*,*,#106383,.T.); +#106810 = ORIENTED_EDGE('',*,*,#106198,.T.); +#106811 = ORIENTED_EDGE('',*,*,#106812,.T.); +#106812 = EDGE_CURVE('',#106176,#106039,#106813,.T.); +#106813 = SURFACE_CURVE('',#106814,(#106818,#106825),.PCURVE_S1.); +#106814 = LINE('',#106815,#106816); +#106815 = CARTESIAN_POINT('',(6.85,-1.,1.159810404338E-002)); +#106816 = VECTOR('',#106817,1.); +#106817 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#106818 = PCURVE('',#92455,#106819); +#106819 = DEFINITIONAL_REPRESENTATION('',(#106820),#106824); +#106820 = LINE('',#106821,#106822); +#106821 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#106822 = VECTOR('',#106823,1.); +#106823 = DIRECTION('',(-1.,2.101748079665E-016)); +#106824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106825 = PCURVE('',#106082,#106826); +#106826 = DEFINITIONAL_REPRESENTATION('',(#106827),#106831); +#106827 = LINE('',#106828,#106829); +#106828 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#106829 = VECTOR('',#106830,1.); +#106830 = DIRECTION('',(1.,0.E+000)); +#106831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106832 = ORIENTED_EDGE('',*,*,#106036,.F.); +#106833 = ORIENTED_EDGE('',*,*,#106304,.F.); +#106834 = ORIENTED_EDGE('',*,*,#106511,.F.); +#106835 = ORIENTED_EDGE('',*,*,#106631,.F.); +#106836 = ORIENTED_EDGE('',*,*,#106837,.T.); +#106837 = EDGE_CURVE('',#106632,#92440,#106838,.T.); +#106838 = SURFACE_CURVE('',#106839,(#106843,#106850),.PCURVE_S1.); +#106839 = LINE('',#106840,#106841); +#106840 = CARTESIAN_POINT('',(6.85,-0.527847992439,0.65)); +#106841 = VECTOR('',#106842,1.); +#106842 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#106843 = PCURVE('',#92455,#106844); +#106844 = DEFINITIONAL_REPRESENTATION('',(#106845),#106849); +#106845 = LINE('',#106846,#106847); +#106846 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106847 = VECTOR('',#106848,1.); +#106848 = DIRECTION('',(3.563627120235E-016,1.)); +#106849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106850 = PCURVE('',#92481,#106851); +#106851 = DEFINITIONAL_REPRESENTATION('',(#106852),#106856); +#106852 = LINE('',#106853,#106854); +#106853 = CARTESIAN_POINT('',(0.E+000,0.2)); +#106854 = VECTOR('',#106855,1.); +#106855 = DIRECTION('',(-1.,0.E+000)); +#106856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106857 = ORIENTED_EDGE('',*,*,#92439,.T.); +#106858 = ADVANCED_FACE('',(#106859),#92481,.F.); +#106859 = FACE_BOUND('',#106860,.T.); +#106860 = EDGE_LOOP('',(#106861,#106862,#106863,#106864)); +#106861 = ORIENTED_EDGE('',*,*,#106658,.F.); +#106862 = ORIENTED_EDGE('',*,*,#106705,.T.); +#106863 = ORIENTED_EDGE('',*,*,#92467,.T.); +#106864 = ORIENTED_EDGE('',*,*,#106837,.F.); +#106865 = ADVANCED_FACE('',(#106866),#106082,.T.); +#106866 = FACE_BOUND('',#106867,.T.); +#106867 = EDGE_LOOP('',(#106868,#106869,#106870,#106871)); +#106868 = ORIENTED_EDGE('',*,*,#106812,.F.); +#106869 = ORIENTED_EDGE('',*,*,#106175,.F.); +#106870 = ORIENTED_EDGE('',*,*,#106730,.F.); +#106871 = ORIENTED_EDGE('',*,*,#106066,.F.); +#106872 = ADVANCED_FACE('',(#106873),#106887,.T.); +#106873 = FACE_BOUND('',#106874,.T.); +#106874 = EDGE_LOOP('',(#106875,#106905,#106933,#106956)); +#106875 = ORIENTED_EDGE('',*,*,#106876,.T.); +#106876 = EDGE_CURVE('',#106877,#106879,#106881,.T.); +#106877 = VERTEX_POINT('',#106878); +#106878 = CARTESIAN_POINT('',(7.35,-0.74341632541,-0.308197125857)); +#106879 = VERTEX_POINT('',#106880); +#106880 = CARTESIAN_POINT('',(7.35,-1.,-0.308197125857)); +#106881 = SURFACE_CURVE('',#106882,(#106886,#106898),.PCURVE_S1.); +#106882 = LINE('',#106883,#106884); +#106883 = CARTESIAN_POINT('',(7.35,-0.74341632541,-0.308197125857)); +#106884 = VECTOR('',#106885,1.); +#106885 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106886 = PCURVE('',#106887,#106892); +#106887 = PLANE('',#106888); +#106888 = AXIS2_PLACEMENT_3D('',#106889,#106890,#106891); +#106889 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#106890 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#106891 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106892 = DEFINITIONAL_REPRESENTATION('',(#106893),#106897); +#106893 = LINE('',#106894,#106895); +#106894 = CARTESIAN_POINT('',(2.65,0.E+000)); +#106895 = VECTOR('',#106896,1.); +#106896 = DIRECTION('',(0.E+000,-1.)); +#106897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106898 = PCURVE('',#90978,#106899); +#106899 = DEFINITIONAL_REPRESENTATION('',(#106900),#106904); +#106900 = LINE('',#106901,#106902); +#106901 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#106902 = VECTOR('',#106903,1.); +#106903 = DIRECTION('',(0.E+000,-1.)); +#106904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106905 = ORIENTED_EDGE('',*,*,#106906,.T.); +#106906 = EDGE_CURVE('',#106879,#106907,#106909,.T.); +#106907 = VERTEX_POINT('',#106908); +#106908 = CARTESIAN_POINT('',(7.15,-1.,-0.308197125857)); +#106909 = SURFACE_CURVE('',#106910,(#106914,#106921),.PCURVE_S1.); +#106910 = LINE('',#106911,#106912); +#106911 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#106912 = VECTOR('',#106913,1.); +#106913 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106914 = PCURVE('',#106887,#106915); +#106915 = DEFINITIONAL_REPRESENTATION('',(#106916),#106920); +#106916 = LINE('',#106917,#106918); +#106917 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#106918 = VECTOR('',#106919,1.); +#106919 = DIRECTION('',(1.,0.E+000)); +#106920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106921 = PCURVE('',#106922,#106927); +#106922 = PLANE('',#106923); +#106923 = AXIS2_PLACEMENT_3D('',#106924,#106925,#106926); +#106924 = CARTESIAN_POINT('',(7.25,-1.,-0.258196742327)); +#106925 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#106926 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#106927 = DEFINITIONAL_REPRESENTATION('',(#106928),#106932); +#106928 = LINE('',#106929,#106930); +#106929 = CARTESIAN_POINT('',(5.000038352949E-002,2.75)); +#106930 = VECTOR('',#106931,1.); +#106931 = DIRECTION('',(0.E+000,-1.)); +#106932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106933 = ORIENTED_EDGE('',*,*,#106934,.F.); +#106934 = EDGE_CURVE('',#106935,#106907,#106937,.T.); +#106935 = VERTEX_POINT('',#106936); +#106936 = CARTESIAN_POINT('',(7.15,-0.74341632541,-0.308197125857)); +#106937 = SURFACE_CURVE('',#106938,(#106942,#106949),.PCURVE_S1.); +#106938 = LINE('',#106939,#106940); +#106939 = CARTESIAN_POINT('',(7.15,-0.74341632541,-0.308197125857)); +#106940 = VECTOR('',#106941,1.); +#106941 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106942 = PCURVE('',#106887,#106943); +#106943 = DEFINITIONAL_REPRESENTATION('',(#106944),#106948); +#106944 = LINE('',#106945,#106946); +#106945 = CARTESIAN_POINT('',(2.85,0.E+000)); +#106946 = VECTOR('',#106947,1.); +#106947 = DIRECTION('',(0.E+000,-1.)); +#106948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106949 = PCURVE('',#90922,#106950); +#106950 = DEFINITIONAL_REPRESENTATION('',(#106951),#106955); +#106951 = LINE('',#106952,#106953); +#106952 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#106953 = VECTOR('',#106954,1.); +#106954 = DIRECTION('',(0.E+000,-1.)); +#106955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106956 = ORIENTED_EDGE('',*,*,#106957,.T.); +#106957 = EDGE_CURVE('',#106935,#106877,#106958,.T.); +#106958 = SURFACE_CURVE('',#106959,(#106963,#106970),.PCURVE_S1.); +#106959 = LINE('',#106960,#106961); +#106960 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#106961 = VECTOR('',#106962,1.); +#106962 = DIRECTION('',(1.,0.E+000,0.E+000)); +#106963 = PCURVE('',#106887,#106964); +#106964 = DEFINITIONAL_REPRESENTATION('',(#106965),#106969); +#106965 = LINE('',#106966,#106967); +#106966 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#106967 = VECTOR('',#106968,1.); +#106968 = DIRECTION('',(-1.,0.E+000)); +#106969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106970 = PCURVE('',#106971,#106976); +#106971 = CYLINDRICAL_SURFACE('',#106972,0.308574064194); +#106972 = AXIS2_PLACEMENT_3D('',#106973,#106974,#106975); +#106973 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#106974 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#106975 = DIRECTION('',(0.E+000,0.E+000,1.)); +#106976 = DEFINITIONAL_REPRESENTATION('',(#106977),#106980); +#106977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106978,#106979), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#104586 = CARTESIAN_POINT('',(3.191025391152,2.85)); -#104587 = CARTESIAN_POINT('',(3.191025391152,2.65)); -#104588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104589 = ADVANCED_FACE('',(#104590),#104604,.T.); -#104590 = FACE_BOUND('',#104591,.T.); -#104591 = EDGE_LOOP('',(#104592,#104622,#104645,#104668)); -#104592 = ORIENTED_EDGE('',*,*,#104593,.T.); -#104593 = EDGE_CURVE('',#104594,#104596,#104598,.T.); -#104594 = VERTEX_POINT('',#104595); -#104595 = CARTESIAN_POINT('',(7.15,-0.740726081328,-0.208196358798)); -#104596 = VERTEX_POINT('',#104597); -#104597 = CARTESIAN_POINT('',(7.15,-1.,-0.208196358798)); -#104598 = SURFACE_CURVE('',#104599,(#104603,#104615),.PCURVE_S1.); -#104599 = LINE('',#104600,#104601); -#104600 = CARTESIAN_POINT('',(7.15,-0.740726081328,-0.208196358798)); -#104601 = VECTOR('',#104602,1.); -#104602 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#104603 = PCURVE('',#104604,#104609); -#104604 = PLANE('',#104605); -#104605 = AXIS2_PLACEMENT_3D('',#104606,#104607,#104608); -#104606 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#104607 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104608 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104609 = DEFINITIONAL_REPRESENTATION('',(#104610),#104614); -#104610 = LINE('',#104611,#104612); -#104611 = CARTESIAN_POINT('',(-2.85,0.E+000)); -#104612 = VECTOR('',#104613,1.); -#104613 = DIRECTION('',(0.E+000,-1.)); -#104614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104615 = PCURVE('',#88530,#104616); -#104616 = DEFINITIONAL_REPRESENTATION('',(#104617),#104621); -#104617 = LINE('',#104618,#104619); -#104618 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#104619 = VECTOR('',#104620,1.); -#104620 = DIRECTION('',(0.E+000,-1.)); -#104621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104622 = ORIENTED_EDGE('',*,*,#104623,.T.); -#104623 = EDGE_CURVE('',#104596,#104624,#104626,.T.); -#104624 = VERTEX_POINT('',#104625); -#104625 = CARTESIAN_POINT('',(7.35,-1.,-0.208196358798)); -#104626 = SURFACE_CURVE('',#104627,(#104631,#104638),.PCURVE_S1.); -#104627 = LINE('',#104628,#104629); -#104628 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#104629 = VECTOR('',#104630,1.); -#104630 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104631 = PCURVE('',#104604,#104632); -#104632 = DEFINITIONAL_REPRESENTATION('',(#104633),#104637); -#104633 = LINE('',#104634,#104635); -#104634 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#104635 = VECTOR('',#104636,1.); -#104636 = DIRECTION('',(1.,0.E+000)); -#104637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104638 = PCURVE('',#104530,#104639); -#104639 = DEFINITIONAL_REPRESENTATION('',(#104640),#104644); -#104640 = LINE('',#104641,#104642); -#104641 = CARTESIAN_POINT('',(-5.000038352949E-002,2.75)); -#104642 = VECTOR('',#104643,1.); -#104643 = DIRECTION('',(0.E+000,1.)); -#104644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104645 = ORIENTED_EDGE('',*,*,#104646,.F.); -#104646 = EDGE_CURVE('',#104647,#104624,#104649,.T.); -#104647 = VERTEX_POINT('',#104648); -#104648 = CARTESIAN_POINT('',(7.35,-0.740726081328,-0.208196358798)); -#104649 = SURFACE_CURVE('',#104650,(#104654,#104661),.PCURVE_S1.); -#104650 = LINE('',#104651,#104652); -#104651 = CARTESIAN_POINT('',(7.35,-0.740726081328,-0.208196358798)); -#104652 = VECTOR('',#104653,1.); -#104653 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#104654 = PCURVE('',#104604,#104655); -#104655 = DEFINITIONAL_REPRESENTATION('',(#104656),#104660); -#104656 = LINE('',#104657,#104658); -#104657 = CARTESIAN_POINT('',(-2.65,0.E+000)); -#104658 = VECTOR('',#104659,1.); -#104659 = DIRECTION('',(0.E+000,-1.)); -#104660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104661 = PCURVE('',#88586,#104662); -#104662 = DEFINITIONAL_REPRESENTATION('',(#104663),#104667); -#104663 = LINE('',#104664,#104665); -#104664 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#104665 = VECTOR('',#104666,1.); -#104666 = DIRECTION('',(0.E+000,-1.)); -#104667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104668 = ORIENTED_EDGE('',*,*,#104669,.T.); -#104669 = EDGE_CURVE('',#104647,#104594,#104670,.T.); -#104670 = SURFACE_CURVE('',#104671,(#104675,#104682),.PCURVE_S1.); -#104671 = LINE('',#104672,#104673); -#104672 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#104673 = VECTOR('',#104674,1.); -#104674 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104675 = PCURVE('',#104604,#104676); -#104676 = DEFINITIONAL_REPRESENTATION('',(#104677),#104681); -#104677 = LINE('',#104678,#104679); -#104678 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104679 = VECTOR('',#104680,1.); -#104680 = DIRECTION('',(-1.,0.E+000)); -#104681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104682 = PCURVE('',#104683,#104688); -#104683 = CYLINDRICAL_SURFACE('',#104684,0.208574704164); -#104684 = AXIS2_PLACEMENT_3D('',#104685,#104686,#104687); -#104685 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#104686 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104687 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104688 = DEFINITIONAL_REPRESENTATION('',(#104689),#104692); -#104689 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104690,#104691), +#106978 = CARTESIAN_POINT('',(3.191025391152,2.85)); +#106979 = CARTESIAN_POINT('',(3.191025391152,2.65)); +#106980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#106981 = ADVANCED_FACE('',(#106982),#106996,.T.); +#106982 = FACE_BOUND('',#106983,.T.); +#106983 = EDGE_LOOP('',(#106984,#107014,#107037,#107060)); +#106984 = ORIENTED_EDGE('',*,*,#106985,.T.); +#106985 = EDGE_CURVE('',#106986,#106988,#106990,.T.); +#106986 = VERTEX_POINT('',#106987); +#106987 = CARTESIAN_POINT('',(7.15,-0.740726081328,-0.208196358798)); +#106988 = VERTEX_POINT('',#106989); +#106989 = CARTESIAN_POINT('',(7.15,-1.,-0.208196358798)); +#106990 = SURFACE_CURVE('',#106991,(#106995,#107007),.PCURVE_S1.); +#106991 = LINE('',#106992,#106993); +#106992 = CARTESIAN_POINT('',(7.15,-0.740726081328,-0.208196358798)); +#106993 = VECTOR('',#106994,1.); +#106994 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#106995 = PCURVE('',#106996,#107001); +#106996 = PLANE('',#106997); +#106997 = AXIS2_PLACEMENT_3D('',#106998,#106999,#107000); +#106998 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#106999 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107000 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107001 = DEFINITIONAL_REPRESENTATION('',(#107002),#107006); +#107002 = LINE('',#107003,#107004); +#107003 = CARTESIAN_POINT('',(-2.85,0.E+000)); +#107004 = VECTOR('',#107005,1.); +#107005 = DIRECTION('',(0.E+000,-1.)); +#107006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107007 = PCURVE('',#90922,#107008); +#107008 = DEFINITIONAL_REPRESENTATION('',(#107009),#107013); +#107009 = LINE('',#107010,#107011); +#107010 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#107011 = VECTOR('',#107012,1.); +#107012 = DIRECTION('',(0.E+000,-1.)); +#107013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107014 = ORIENTED_EDGE('',*,*,#107015,.T.); +#107015 = EDGE_CURVE('',#106988,#107016,#107018,.T.); +#107016 = VERTEX_POINT('',#107017); +#107017 = CARTESIAN_POINT('',(7.35,-1.,-0.208196358798)); +#107018 = SURFACE_CURVE('',#107019,(#107023,#107030),.PCURVE_S1.); +#107019 = LINE('',#107020,#107021); +#107020 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#107021 = VECTOR('',#107022,1.); +#107022 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107023 = PCURVE('',#106996,#107024); +#107024 = DEFINITIONAL_REPRESENTATION('',(#107025),#107029); +#107025 = LINE('',#107026,#107027); +#107026 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#107027 = VECTOR('',#107028,1.); +#107028 = DIRECTION('',(1.,0.E+000)); +#107029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107030 = PCURVE('',#106922,#107031); +#107031 = DEFINITIONAL_REPRESENTATION('',(#107032),#107036); +#107032 = LINE('',#107033,#107034); +#107033 = CARTESIAN_POINT('',(-5.000038352949E-002,2.75)); +#107034 = VECTOR('',#107035,1.); +#107035 = DIRECTION('',(0.E+000,1.)); +#107036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107037 = ORIENTED_EDGE('',*,*,#107038,.F.); +#107038 = EDGE_CURVE('',#107039,#107016,#107041,.T.); +#107039 = VERTEX_POINT('',#107040); +#107040 = CARTESIAN_POINT('',(7.35,-0.740726081328,-0.208196358798)); +#107041 = SURFACE_CURVE('',#107042,(#107046,#107053),.PCURVE_S1.); +#107042 = LINE('',#107043,#107044); +#107043 = CARTESIAN_POINT('',(7.35,-0.740726081328,-0.208196358798)); +#107044 = VECTOR('',#107045,1.); +#107045 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#107046 = PCURVE('',#106996,#107047); +#107047 = DEFINITIONAL_REPRESENTATION('',(#107048),#107052); +#107048 = LINE('',#107049,#107050); +#107049 = CARTESIAN_POINT('',(-2.65,0.E+000)); +#107050 = VECTOR('',#107051,1.); +#107051 = DIRECTION('',(0.E+000,-1.)); +#107052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107053 = PCURVE('',#90978,#107054); +#107054 = DEFINITIONAL_REPRESENTATION('',(#107055),#107059); +#107055 = LINE('',#107056,#107057); +#107056 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#107057 = VECTOR('',#107058,1.); +#107058 = DIRECTION('',(0.E+000,-1.)); +#107059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107060 = ORIENTED_EDGE('',*,*,#107061,.T.); +#107061 = EDGE_CURVE('',#107039,#106986,#107062,.T.); +#107062 = SURFACE_CURVE('',#107063,(#107067,#107074),.PCURVE_S1.); +#107063 = LINE('',#107064,#107065); +#107064 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#107065 = VECTOR('',#107066,1.); +#107066 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107067 = PCURVE('',#106996,#107068); +#107068 = DEFINITIONAL_REPRESENTATION('',(#107069),#107073); +#107069 = LINE('',#107070,#107071); +#107070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107071 = VECTOR('',#107072,1.); +#107072 = DIRECTION('',(-1.,0.E+000)); +#107073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107074 = PCURVE('',#107075,#107080); +#107075 = CYLINDRICAL_SURFACE('',#107076,0.208574704164); +#107076 = AXIS2_PLACEMENT_3D('',#107077,#107078,#107079); +#107077 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#107078 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107079 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107080 = DEFINITIONAL_REPRESENTATION('',(#107081),#107084); +#107081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107082,#107083), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#104690 = CARTESIAN_POINT('',(3.201833915432,2.65)); -#104691 = CARTESIAN_POINT('',(3.201833915432,2.85)); -#104692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104693 = ADVANCED_FACE('',(#104694),#104579,.T.); -#104694 = FACE_BOUND('',#104695,.T.); -#104695 = EDGE_LOOP('',(#104696,#104697,#104724,#104751)); -#104696 = ORIENTED_EDGE('',*,*,#104565,.F.); -#104697 = ORIENTED_EDGE('',*,*,#104698,.F.); -#104698 = EDGE_CURVE('',#104699,#104543,#104701,.T.); -#104699 = VERTEX_POINT('',#104700); -#104700 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.E+000)); -#104701 = SURFACE_CURVE('',#104702,(#104707,#104713),.PCURVE_S1.); -#104702 = CIRCLE('',#104703,0.308574064194); -#104703 = AXIS2_PLACEMENT_3D('',#104704,#104705,#104706); -#104704 = CARTESIAN_POINT('',(7.15,-0.728168876214,2.640924866458E-017) - ); -#104705 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104706 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104707 = PCURVE('',#104579,#104708); -#104708 = DEFINITIONAL_REPRESENTATION('',(#104709),#104712); -#104709 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104710,#104711), +#107082 = CARTESIAN_POINT('',(3.201833915432,2.65)); +#107083 = CARTESIAN_POINT('',(3.201833915432,2.85)); +#107084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107085 = ADVANCED_FACE('',(#107086),#106971,.T.); +#107086 = FACE_BOUND('',#107087,.T.); +#107087 = EDGE_LOOP('',(#107088,#107089,#107116,#107143)); +#107088 = ORIENTED_EDGE('',*,*,#106957,.F.); +#107089 = ORIENTED_EDGE('',*,*,#107090,.F.); +#107090 = EDGE_CURVE('',#107091,#106935,#107093,.T.); +#107091 = VERTEX_POINT('',#107092); +#107092 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.E+000)); +#107093 = SURFACE_CURVE('',#107094,(#107099,#107105),.PCURVE_S1.); +#107094 = CIRCLE('',#107095,0.308574064194); +#107095 = AXIS2_PLACEMENT_3D('',#107096,#107097,#107098); +#107096 = CARTESIAN_POINT('',(7.15,-0.728168876214,2.640924866458E-017) + ); +#107097 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107098 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107099 = PCURVE('',#106971,#107100); +#107100 = DEFINITIONAL_REPRESENTATION('',(#107101),#107104); +#107101 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107102,#107103), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#104710 = CARTESIAN_POINT('',(1.570796326795,2.85)); -#104711 = CARTESIAN_POINT('',(3.191025391152,2.85)); -#104712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107102 = CARTESIAN_POINT('',(1.570796326795,2.85)); +#107103 = CARTESIAN_POINT('',(3.191025391152,2.85)); +#107104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104713 = PCURVE('',#88530,#104714); -#104714 = DEFINITIONAL_REPRESENTATION('',(#104715),#104723); -#104715 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104716,#104717,#104718, - #104719,#104720,#104721,#104722),.UNSPECIFIED.,.T.,.F.) +#107105 = PCURVE('',#90922,#107106); +#107106 = DEFINITIONAL_REPRESENTATION('',(#107107),#107115); +#107107 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107108,#107109,#107110, + #107111,#107112,#107113,#107114),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#104716 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#104717 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#104718 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#104719 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#104720 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#104721 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#104722 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#104723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104724 = ORIENTED_EDGE('',*,*,#104725,.F.); -#104725 = EDGE_CURVE('',#104726,#104699,#104728,.T.); -#104726 = VERTEX_POINT('',#104727); -#104727 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.E+000)); -#104728 = SURFACE_CURVE('',#104729,(#104733,#104739),.PCURVE_S1.); -#104729 = LINE('',#104730,#104731); -#104730 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#104731 = VECTOR('',#104732,1.); -#104732 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104733 = PCURVE('',#104579,#104734); -#104734 = DEFINITIONAL_REPRESENTATION('',(#104735),#104738); -#104735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104736,#104737), +#107108 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#107109 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#107110 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#107111 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#107112 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#107113 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#107114 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#107115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107116 = ORIENTED_EDGE('',*,*,#107117,.F.); +#107117 = EDGE_CURVE('',#107118,#107091,#107120,.T.); +#107118 = VERTEX_POINT('',#107119); +#107119 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.E+000)); +#107120 = SURFACE_CURVE('',#107121,(#107125,#107131),.PCURVE_S1.); +#107121 = LINE('',#107122,#107123); +#107122 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#107123 = VECTOR('',#107124,1.); +#107124 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107125 = PCURVE('',#106971,#107126); +#107126 = DEFINITIONAL_REPRESENTATION('',(#107127),#107130); +#107127 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107128,#107129), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#104736 = CARTESIAN_POINT('',(1.570796326795,2.65)); -#104737 = CARTESIAN_POINT('',(1.570796326795,2.85)); -#104738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104739 = PCURVE('',#104740,#104745); -#104740 = PLANE('',#104741); -#104741 = AXIS2_PLACEMENT_3D('',#104742,#104743,#104744); -#104742 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#104743 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#104744 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104745 = DEFINITIONAL_REPRESENTATION('',(#104746),#104750); -#104746 = LINE('',#104747,#104748); -#104747 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#104748 = VECTOR('',#104749,1.); -#104749 = DIRECTION('',(0.E+000,-1.)); -#104750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104751 = ORIENTED_EDGE('',*,*,#104752,.T.); -#104752 = EDGE_CURVE('',#104726,#104485,#104753,.T.); -#104753 = SURFACE_CURVE('',#104754,(#104759,#104765),.PCURVE_S1.); -#104754 = CIRCLE('',#104755,0.308574064194); -#104755 = AXIS2_PLACEMENT_3D('',#104756,#104757,#104758); -#104756 = CARTESIAN_POINT('',(7.35,-0.728168876214,2.640924866458E-017) - ); -#104757 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104758 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104759 = PCURVE('',#104579,#104760); -#104760 = DEFINITIONAL_REPRESENTATION('',(#104761),#104764); -#104761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104762,#104763), +#107128 = CARTESIAN_POINT('',(1.570796326795,2.65)); +#107129 = CARTESIAN_POINT('',(1.570796326795,2.85)); +#107130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107131 = PCURVE('',#107132,#107137); +#107132 = PLANE('',#107133); +#107133 = AXIS2_PLACEMENT_3D('',#107134,#107135,#107136); +#107134 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#107135 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#107136 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107137 = DEFINITIONAL_REPRESENTATION('',(#107138),#107142); +#107138 = LINE('',#107139,#107140); +#107139 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#107140 = VECTOR('',#107141,1.); +#107141 = DIRECTION('',(0.E+000,-1.)); +#107142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107143 = ORIENTED_EDGE('',*,*,#107144,.T.); +#107144 = EDGE_CURVE('',#107118,#106877,#107145,.T.); +#107145 = SURFACE_CURVE('',#107146,(#107151,#107157),.PCURVE_S1.); +#107146 = CIRCLE('',#107147,0.308574064194); +#107147 = AXIS2_PLACEMENT_3D('',#107148,#107149,#107150); +#107148 = CARTESIAN_POINT('',(7.35,-0.728168876214,2.640924866458E-017) + ); +#107149 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107150 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107151 = PCURVE('',#106971,#107152); +#107152 = DEFINITIONAL_REPRESENTATION('',(#107153),#107156); +#107153 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107154,#107155), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#104762 = CARTESIAN_POINT('',(1.570796326795,2.65)); -#104763 = CARTESIAN_POINT('',(3.191025391152,2.65)); -#104764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104765 = PCURVE('',#88586,#104766); -#104766 = DEFINITIONAL_REPRESENTATION('',(#104767),#104771); -#104767 = CIRCLE('',#104768,0.308574064194); -#104768 = AXIS2_PLACEMENT_2D('',#104769,#104770); -#104769 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#104770 = DIRECTION('',(1.,0.E+000)); -#104771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104772 = ADVANCED_FACE('',(#104773),#104683,.F.); -#104773 = FACE_BOUND('',#104774,.F.); -#104774 = EDGE_LOOP('',(#104775,#104776,#104803,#104830)); -#104775 = ORIENTED_EDGE('',*,*,#104669,.T.); -#104776 = ORIENTED_EDGE('',*,*,#104777,.F.); -#104777 = EDGE_CURVE('',#104778,#104594,#104780,.T.); -#104778 = VERTEX_POINT('',#104779); -#104779 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.E+000)); -#104780 = SURFACE_CURVE('',#104781,(#104786,#104792),.PCURVE_S1.); -#104781 = CIRCLE('',#104782,0.208574704164); -#104782 = AXIS2_PLACEMENT_3D('',#104783,#104784,#104785); -#104783 = CARTESIAN_POINT('',(7.15,-0.728168876214,2.640924866458E-017) - ); -#104784 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104785 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104786 = PCURVE('',#104683,#104787); -#104787 = DEFINITIONAL_REPRESENTATION('',(#104788),#104791); -#104788 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104789,#104790), +#107154 = CARTESIAN_POINT('',(1.570796326795,2.65)); +#107155 = CARTESIAN_POINT('',(3.191025391152,2.65)); +#107156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107157 = PCURVE('',#90978,#107158); +#107158 = DEFINITIONAL_REPRESENTATION('',(#107159),#107163); +#107159 = CIRCLE('',#107160,0.308574064194); +#107160 = AXIS2_PLACEMENT_2D('',#107161,#107162); +#107161 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#107162 = DIRECTION('',(1.,0.E+000)); +#107163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107164 = ADVANCED_FACE('',(#107165),#107075,.F.); +#107165 = FACE_BOUND('',#107166,.F.); +#107166 = EDGE_LOOP('',(#107167,#107168,#107195,#107222)); +#107167 = ORIENTED_EDGE('',*,*,#107061,.T.); +#107168 = ORIENTED_EDGE('',*,*,#107169,.F.); +#107169 = EDGE_CURVE('',#107170,#106986,#107172,.T.); +#107170 = VERTEX_POINT('',#107171); +#107171 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.E+000)); +#107172 = SURFACE_CURVE('',#107173,(#107178,#107184),.PCURVE_S1.); +#107173 = CIRCLE('',#107174,0.208574704164); +#107174 = AXIS2_PLACEMENT_3D('',#107175,#107176,#107177); +#107175 = CARTESIAN_POINT('',(7.15,-0.728168876214,2.640924866458E-017) + ); +#107176 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107177 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107178 = PCURVE('',#107075,#107179); +#107179 = DEFINITIONAL_REPRESENTATION('',(#107180),#107183); +#107180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107181,#107182), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#104789 = CARTESIAN_POINT('',(1.570796326795,2.85)); -#104790 = CARTESIAN_POINT('',(3.201833915432,2.85)); -#104791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107181 = CARTESIAN_POINT('',(1.570796326795,2.85)); +#107182 = CARTESIAN_POINT('',(3.201833915432,2.85)); +#107183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104792 = PCURVE('',#88530,#104793); -#104793 = DEFINITIONAL_REPRESENTATION('',(#104794),#104802); -#104794 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#104795,#104796,#104797, - #104798,#104799,#104800,#104801),.UNSPECIFIED.,.F.,.F.) +#107184 = PCURVE('',#90922,#107185); +#107185 = DEFINITIONAL_REPRESENTATION('',(#107186),#107194); +#107186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107187,#107188,#107189, + #107190,#107191,#107192,#107193),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#104795 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#104796 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#104797 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#104798 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#104799 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#104800 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#104801 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#104802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104803 = ORIENTED_EDGE('',*,*,#104804,.T.); -#104804 = EDGE_CURVE('',#104778,#104805,#104807,.T.); -#104805 = VERTEX_POINT('',#104806); -#104806 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.E+000)); -#104807 = SURFACE_CURVE('',#104808,(#104812,#104818),.PCURVE_S1.); -#104808 = LINE('',#104809,#104810); -#104809 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#104810 = VECTOR('',#104811,1.); -#104811 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104812 = PCURVE('',#104683,#104813); -#104813 = DEFINITIONAL_REPRESENTATION('',(#104814),#104817); -#104814 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104815,#104816), +#107187 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#107188 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#107189 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#107190 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#107191 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#107192 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#107193 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#107194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107195 = ORIENTED_EDGE('',*,*,#107196,.T.); +#107196 = EDGE_CURVE('',#107170,#107197,#107199,.T.); +#107197 = VERTEX_POINT('',#107198); +#107198 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.E+000)); +#107199 = SURFACE_CURVE('',#107200,(#107204,#107210),.PCURVE_S1.); +#107200 = LINE('',#107201,#107202); +#107201 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#107202 = VECTOR('',#107203,1.); +#107203 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107204 = PCURVE('',#107075,#107205); +#107205 = DEFINITIONAL_REPRESENTATION('',(#107206),#107209); +#107206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107207,#107208), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#104815 = CARTESIAN_POINT('',(1.570796326795,2.85)); -#104816 = CARTESIAN_POINT('',(1.570796326795,2.65)); -#104817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104818 = PCURVE('',#104819,#104824); -#104819 = PLANE('',#104820); -#104820 = AXIS2_PLACEMENT_3D('',#104821,#104822,#104823); -#104821 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#104822 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#104823 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#104824 = DEFINITIONAL_REPRESENTATION('',(#104825),#104829); -#104825 = LINE('',#104826,#104827); -#104826 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#104827 = VECTOR('',#104828,1.); -#104828 = DIRECTION('',(0.E+000,1.)); -#104829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104830 = ORIENTED_EDGE('',*,*,#104831,.T.); -#104831 = EDGE_CURVE('',#104805,#104647,#104832,.T.); -#104832 = SURFACE_CURVE('',#104833,(#104838,#104844),.PCURVE_S1.); -#104833 = CIRCLE('',#104834,0.208574704164); -#104834 = AXIS2_PLACEMENT_3D('',#104835,#104836,#104837); -#104835 = CARTESIAN_POINT('',(7.35,-0.728168876214,2.640924866458E-017) - ); -#104836 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104837 = DIRECTION('',(0.E+000,0.E+000,1.)); -#104838 = PCURVE('',#104683,#104839); -#104839 = DEFINITIONAL_REPRESENTATION('',(#104840),#104843); -#104840 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104841,#104842), +#107207 = CARTESIAN_POINT('',(1.570796326795,2.85)); +#107208 = CARTESIAN_POINT('',(1.570796326795,2.65)); +#107209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107210 = PCURVE('',#107211,#107216); +#107211 = PLANE('',#107212); +#107212 = AXIS2_PLACEMENT_3D('',#107213,#107214,#107215); +#107213 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#107214 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#107215 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#107216 = DEFINITIONAL_REPRESENTATION('',(#107217),#107221); +#107217 = LINE('',#107218,#107219); +#107218 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#107219 = VECTOR('',#107220,1.); +#107220 = DIRECTION('',(0.E+000,1.)); +#107221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107222 = ORIENTED_EDGE('',*,*,#107223,.T.); +#107223 = EDGE_CURVE('',#107197,#107039,#107224,.T.); +#107224 = SURFACE_CURVE('',#107225,(#107230,#107236),.PCURVE_S1.); +#107225 = CIRCLE('',#107226,0.208574704164); +#107226 = AXIS2_PLACEMENT_3D('',#107227,#107228,#107229); +#107227 = CARTESIAN_POINT('',(7.35,-0.728168876214,2.640924866458E-017) + ); +#107228 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107229 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107230 = PCURVE('',#107075,#107231); +#107231 = DEFINITIONAL_REPRESENTATION('',(#107232),#107235); +#107232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107233,#107234), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#104841 = CARTESIAN_POINT('',(1.570796326795,2.65)); -#104842 = CARTESIAN_POINT('',(3.201833915432,2.65)); -#104843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107233 = CARTESIAN_POINT('',(1.570796326795,2.65)); +#107234 = CARTESIAN_POINT('',(3.201833915432,2.65)); +#107235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107236 = PCURVE('',#90978,#107237); +#107237 = DEFINITIONAL_REPRESENTATION('',(#107238),#107242); +#107238 = CIRCLE('',#107239,0.208574704164); +#107239 = AXIS2_PLACEMENT_2D('',#107240,#107241); +#107240 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#107241 = DIRECTION('',(1.,0.E+000)); +#107242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107243 = ADVANCED_FACE('',(#107244),#107211,.F.); +#107244 = FACE_BOUND('',#107245,.T.); +#107245 = EDGE_LOOP('',(#107246,#107275,#107296,#107297)); +#107246 = ORIENTED_EDGE('',*,*,#107247,.F.); +#107247 = EDGE_CURVE('',#107248,#107250,#107252,.T.); +#107248 = VERTEX_POINT('',#107249); +#107249 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.530776333563)); +#107250 = VERTEX_POINT('',#107251); +#107251 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.530776333563)); +#107252 = SURFACE_CURVE('',#107253,(#107257,#107264),.PCURVE_S1.); +#107253 = LINE('',#107254,#107255); +#107254 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#107255 = VECTOR('',#107256,1.); +#107256 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107257 = PCURVE('',#107211,#107258); +#107258 = DEFINITIONAL_REPRESENTATION('',(#107259),#107263); +#107259 = LINE('',#107260,#107261); +#107260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107261 = VECTOR('',#107262,1.); +#107262 = DIRECTION('',(0.E+000,1.)); +#107263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107264 = PCURVE('',#107265,#107270); +#107265 = CYLINDRICAL_SURFACE('',#107266,0.2192697516); +#107266 = AXIS2_PLACEMENT_3D('',#107267,#107268,#107269); +#107267 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#107268 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107269 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107270 = DEFINITIONAL_REPRESENTATION('',(#107271),#107274); +#107271 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107272,#107273), + .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); +#107272 = CARTESIAN_POINT('',(4.712388980385,-2.85)); +#107273 = CARTESIAN_POINT('',(4.712388980385,-2.65)); +#107274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107275 = ORIENTED_EDGE('',*,*,#107276,.T.); +#107276 = EDGE_CURVE('',#107248,#107170,#107277,.T.); +#107277 = SURFACE_CURVE('',#107278,(#107282,#107289),.PCURVE_S1.); +#107278 = LINE('',#107279,#107280); +#107279 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.530776333563)); +#107280 = VECTOR('',#107281,1.); +#107281 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107282 = PCURVE('',#107211,#107283); +#107283 = DEFINITIONAL_REPRESENTATION('',(#107284),#107288); +#107284 = LINE('',#107285,#107286); +#107285 = CARTESIAN_POINT('',(0.E+000,-2.85)); +#107286 = VECTOR('',#107287,1.); +#107287 = DIRECTION('',(-1.,0.E+000)); +#107288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107289 = PCURVE('',#90922,#107290); +#107290 = DEFINITIONAL_REPRESENTATION('',(#107291),#107295); +#107291 = LINE('',#107292,#107293); +#107292 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#107293 = VECTOR('',#107294,1.); +#107294 = DIRECTION('',(1.,-1.021336205033E-016)); +#107295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107296 = ORIENTED_EDGE('',*,*,#107196,.T.); +#107297 = ORIENTED_EDGE('',*,*,#107298,.F.); +#107298 = EDGE_CURVE('',#107250,#107197,#107299,.T.); +#107299 = SURFACE_CURVE('',#107300,(#107304,#107311),.PCURVE_S1.); +#107300 = LINE('',#107301,#107302); +#107301 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.530776333563)); +#107302 = VECTOR('',#107303,1.); +#107303 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107304 = PCURVE('',#107211,#107305); +#107305 = DEFINITIONAL_REPRESENTATION('',(#107306),#107310); +#107306 = LINE('',#107307,#107308); +#107307 = CARTESIAN_POINT('',(0.E+000,-2.65)); +#107308 = VECTOR('',#107309,1.); +#107309 = DIRECTION('',(-1.,0.E+000)); +#107310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107311 = PCURVE('',#90978,#107312); +#107312 = DEFINITIONAL_REPRESENTATION('',(#107313),#107317); +#107313 = LINE('',#107314,#107315); +#107314 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#107315 = VECTOR('',#107316,1.); +#107316 = DIRECTION('',(-1.,-1.021336205033E-016)); +#107317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107318 = ADVANCED_FACE('',(#107319),#107132,.F.); +#107319 = FACE_BOUND('',#107320,.T.); +#107320 = EDGE_LOOP('',(#107321,#107350,#107371,#107372)); +#107321 = ORIENTED_EDGE('',*,*,#107322,.F.); +#107322 = EDGE_CURVE('',#107323,#107325,#107327,.T.); +#107323 = VERTEX_POINT('',#107324); +#107324 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.530776333563)); +#107325 = VERTEX_POINT('',#107326); +#107326 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.530776333563)); +#107327 = SURFACE_CURVE('',#107328,(#107332,#107339),.PCURVE_S1.); +#107328 = LINE('',#107329,#107330); +#107329 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#107330 = VECTOR('',#107331,1.); +#107331 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107332 = PCURVE('',#107132,#107333); +#107333 = DEFINITIONAL_REPRESENTATION('',(#107334),#107338); +#107334 = LINE('',#107335,#107336); +#107335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107336 = VECTOR('',#107337,1.); +#107337 = DIRECTION('',(0.E+000,-1.)); +#107338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107339 = PCURVE('',#107340,#107345); +#107340 = CYLINDRICAL_SURFACE('',#107341,0.119270391569); +#107341 = AXIS2_PLACEMENT_3D('',#107342,#107343,#107344); +#107342 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#107343 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107344 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107345 = DEFINITIONAL_REPRESENTATION('',(#107346),#107349); +#107346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107347,#107348), + .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); +#107347 = CARTESIAN_POINT('',(4.712388980385,-2.65)); +#107348 = CARTESIAN_POINT('',(4.712388980385,-2.85)); +#107349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104844 = PCURVE('',#88586,#104845); -#104845 = DEFINITIONAL_REPRESENTATION('',(#104846),#104850); -#104846 = CIRCLE('',#104847,0.208574704164); -#104847 = AXIS2_PLACEMENT_2D('',#104848,#104849); -#104848 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#104849 = DIRECTION('',(1.,0.E+000)); -#104850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107350 = ORIENTED_EDGE('',*,*,#107351,.T.); +#107351 = EDGE_CURVE('',#107323,#107118,#107352,.T.); +#107352 = SURFACE_CURVE('',#107353,(#107357,#107364),.PCURVE_S1.); +#107353 = LINE('',#107354,#107355); +#107354 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.530776333563)); +#107355 = VECTOR('',#107356,1.); +#107356 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107357 = PCURVE('',#107132,#107358); +#107358 = DEFINITIONAL_REPRESENTATION('',(#107359),#107363); +#107359 = LINE('',#107360,#107361); +#107360 = CARTESIAN_POINT('',(0.E+000,-2.65)); +#107361 = VECTOR('',#107362,1.); +#107362 = DIRECTION('',(1.,0.E+000)); +#107363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104851 = ADVANCED_FACE('',(#104852),#104819,.F.); -#104852 = FACE_BOUND('',#104853,.T.); -#104853 = EDGE_LOOP('',(#104854,#104883,#104904,#104905)); -#104854 = ORIENTED_EDGE('',*,*,#104855,.F.); -#104855 = EDGE_CURVE('',#104856,#104858,#104860,.T.); -#104856 = VERTEX_POINT('',#104857); -#104857 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.530776333563)); -#104858 = VERTEX_POINT('',#104859); -#104859 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.530776333563)); -#104860 = SURFACE_CURVE('',#104861,(#104865,#104872),.PCURVE_S1.); -#104861 = LINE('',#104862,#104863); -#104862 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#104863 = VECTOR('',#104864,1.); -#104864 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104865 = PCURVE('',#104819,#104866); -#104866 = DEFINITIONAL_REPRESENTATION('',(#104867),#104871); -#104867 = LINE('',#104868,#104869); -#104868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104869 = VECTOR('',#104870,1.); -#104870 = DIRECTION('',(0.E+000,1.)); -#104871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104872 = PCURVE('',#104873,#104878); -#104873 = CYLINDRICAL_SURFACE('',#104874,0.2192697516); -#104874 = AXIS2_PLACEMENT_3D('',#104875,#104876,#104877); -#104875 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#104876 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104877 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104878 = DEFINITIONAL_REPRESENTATION('',(#104879),#104882); -#104879 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104880,#104881), - .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#104880 = CARTESIAN_POINT('',(4.712388980385,-2.85)); -#104881 = CARTESIAN_POINT('',(4.712388980385,-2.65)); -#104882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104883 = ORIENTED_EDGE('',*,*,#104884,.T.); -#104884 = EDGE_CURVE('',#104856,#104778,#104885,.T.); -#104885 = SURFACE_CURVE('',#104886,(#104890,#104897),.PCURVE_S1.); -#104886 = LINE('',#104887,#104888); -#104887 = CARTESIAN_POINT('',(7.15,-0.51959417205,0.530776333563)); -#104888 = VECTOR('',#104889,1.); -#104889 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104890 = PCURVE('',#104819,#104891); -#104891 = DEFINITIONAL_REPRESENTATION('',(#104892),#104896); -#104892 = LINE('',#104893,#104894); -#104893 = CARTESIAN_POINT('',(0.E+000,-2.85)); -#104894 = VECTOR('',#104895,1.); -#104895 = DIRECTION('',(-1.,0.E+000)); -#104896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104897 = PCURVE('',#88530,#104898); -#104898 = DEFINITIONAL_REPRESENTATION('',(#104899),#104903); -#104899 = LINE('',#104900,#104901); -#104900 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#104901 = VECTOR('',#104902,1.); -#104902 = DIRECTION('',(1.,-1.021336205033E-016)); -#104903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104904 = ORIENTED_EDGE('',*,*,#104804,.T.); -#104905 = ORIENTED_EDGE('',*,*,#104906,.F.); -#104906 = EDGE_CURVE('',#104858,#104805,#104907,.T.); -#104907 = SURFACE_CURVE('',#104908,(#104912,#104919),.PCURVE_S1.); -#104908 = LINE('',#104909,#104910); -#104909 = CARTESIAN_POINT('',(7.35,-0.51959417205,0.530776333563)); -#104910 = VECTOR('',#104911,1.); -#104911 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104912 = PCURVE('',#104819,#104913); -#104913 = DEFINITIONAL_REPRESENTATION('',(#104914),#104918); -#104914 = LINE('',#104915,#104916); -#104915 = CARTESIAN_POINT('',(0.E+000,-2.65)); -#104916 = VECTOR('',#104917,1.); -#104917 = DIRECTION('',(-1.,0.E+000)); -#104918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104919 = PCURVE('',#88586,#104920); -#104920 = DEFINITIONAL_REPRESENTATION('',(#104921),#104925); -#104921 = LINE('',#104922,#104923); -#104922 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#104923 = VECTOR('',#104924,1.); -#104924 = DIRECTION('',(-1.,-1.021336205033E-016)); -#104925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104926 = ADVANCED_FACE('',(#104927),#104740,.F.); -#104927 = FACE_BOUND('',#104928,.T.); -#104928 = EDGE_LOOP('',(#104929,#104958,#104979,#104980)); -#104929 = ORIENTED_EDGE('',*,*,#104930,.F.); -#104930 = EDGE_CURVE('',#104931,#104933,#104935,.T.); -#104931 = VERTEX_POINT('',#104932); -#104932 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.530776333563)); -#104933 = VERTEX_POINT('',#104934); -#104934 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.530776333563)); -#104935 = SURFACE_CURVE('',#104936,(#104940,#104947),.PCURVE_S1.); -#104936 = LINE('',#104937,#104938); -#104937 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#104938 = VECTOR('',#104939,1.); -#104939 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#104940 = PCURVE('',#104740,#104941); -#104941 = DEFINITIONAL_REPRESENTATION('',(#104942),#104946); -#104942 = LINE('',#104943,#104944); -#104943 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#104944 = VECTOR('',#104945,1.); -#104945 = DIRECTION('',(0.E+000,-1.)); -#104946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107364 = PCURVE('',#90978,#107365); +#107365 = DEFINITIONAL_REPRESENTATION('',(#107366),#107370); +#107366 = LINE('',#107367,#107368); +#107367 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#107368 = VECTOR('',#107369,1.); +#107369 = DIRECTION('',(-1.,-1.021336205033E-016)); +#107370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#104947 = PCURVE('',#104948,#104953); -#104948 = CYLINDRICAL_SURFACE('',#104949,0.119270391569); -#104949 = AXIS2_PLACEMENT_3D('',#104950,#104951,#104952); -#104950 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#104951 = DIRECTION('',(1.,0.E+000,0.E+000)); -#104952 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#104953 = DEFINITIONAL_REPRESENTATION('',(#104954),#104957); -#104954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#104955,#104956), - .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#104955 = CARTESIAN_POINT('',(4.712388980385,-2.65)); -#104956 = CARTESIAN_POINT('',(4.712388980385,-2.85)); -#104957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104958 = ORIENTED_EDGE('',*,*,#104959,.T.); -#104959 = EDGE_CURVE('',#104931,#104726,#104960,.T.); -#104960 = SURFACE_CURVE('',#104961,(#104965,#104972),.PCURVE_S1.); -#104961 = LINE('',#104962,#104963); -#104962 = CARTESIAN_POINT('',(7.35,-0.419594812019,0.530776333563)); -#104963 = VECTOR('',#104964,1.); -#104964 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104965 = PCURVE('',#104740,#104966); -#104966 = DEFINITIONAL_REPRESENTATION('',(#104967),#104971); -#104967 = LINE('',#104968,#104969); -#104968 = CARTESIAN_POINT('',(0.E+000,-2.65)); -#104969 = VECTOR('',#104970,1.); -#104970 = DIRECTION('',(1.,0.E+000)); -#104971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104972 = PCURVE('',#88586,#104973); -#104973 = DEFINITIONAL_REPRESENTATION('',(#104974),#104978); -#104974 = LINE('',#104975,#104976); -#104975 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#104976 = VECTOR('',#104977,1.); -#104977 = DIRECTION('',(-1.,-1.021336205033E-016)); -#104978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104979 = ORIENTED_EDGE('',*,*,#104725,.T.); -#104980 = ORIENTED_EDGE('',*,*,#104981,.F.); -#104981 = EDGE_CURVE('',#104933,#104699,#104982,.T.); -#104982 = SURFACE_CURVE('',#104983,(#104987,#104994),.PCURVE_S1.); -#104983 = LINE('',#104984,#104985); -#104984 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.530776333563)); -#104985 = VECTOR('',#104986,1.); -#104986 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#104987 = PCURVE('',#104740,#104988); -#104988 = DEFINITIONAL_REPRESENTATION('',(#104989),#104993); -#104989 = LINE('',#104990,#104991); -#104990 = CARTESIAN_POINT('',(0.E+000,-2.85)); -#104991 = VECTOR('',#104992,1.); -#104992 = DIRECTION('',(1.,0.E+000)); -#104993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#104994 = PCURVE('',#88530,#104995); -#104995 = DEFINITIONAL_REPRESENTATION('',(#104996),#105000); -#104996 = LINE('',#104997,#104998); -#104997 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#104998 = VECTOR('',#104999,1.); -#104999 = DIRECTION('',(1.,-1.021336205033E-016)); -#105000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105001 = ADVANCED_FACE('',(#105002),#104873,.T.); -#105002 = FACE_BOUND('',#105003,.T.); -#105003 = EDGE_LOOP('',(#105004,#105027,#105028,#105055)); -#105004 = ORIENTED_EDGE('',*,*,#105005,.T.); -#105005 = EDGE_CURVE('',#105006,#104856,#105008,.T.); -#105006 = VERTEX_POINT('',#105007); -#105007 = CARTESIAN_POINT('',(7.15,-0.304819755875,0.75)); -#105008 = SURFACE_CURVE('',#105009,(#105014,#105020),.PCURVE_S1.); -#105009 = CIRCLE('',#105010,0.2192697516); -#105010 = AXIS2_PLACEMENT_3D('',#105011,#105012,#105013); -#105011 = CARTESIAN_POINT('',(7.15,-0.30032442045,0.530776333563)); -#105012 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105013 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105014 = PCURVE('',#104873,#105015); -#105015 = DEFINITIONAL_REPRESENTATION('',(#105016),#105019); -#105016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105017,#105018), +#107371 = ORIENTED_EDGE('',*,*,#107117,.T.); +#107372 = ORIENTED_EDGE('',*,*,#107373,.F.); +#107373 = EDGE_CURVE('',#107325,#107091,#107374,.T.); +#107374 = SURFACE_CURVE('',#107375,(#107379,#107386),.PCURVE_S1.); +#107375 = LINE('',#107376,#107377); +#107376 = CARTESIAN_POINT('',(7.15,-0.419594812019,0.530776333563)); +#107377 = VECTOR('',#107378,1.); +#107378 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107379 = PCURVE('',#107132,#107380); +#107380 = DEFINITIONAL_REPRESENTATION('',(#107381),#107385); +#107381 = LINE('',#107382,#107383); +#107382 = CARTESIAN_POINT('',(0.E+000,-2.85)); +#107383 = VECTOR('',#107384,1.); +#107384 = DIRECTION('',(1.,0.E+000)); +#107385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107386 = PCURVE('',#90922,#107387); +#107387 = DEFINITIONAL_REPRESENTATION('',(#107388),#107392); +#107388 = LINE('',#107389,#107390); +#107389 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#107390 = VECTOR('',#107391,1.); +#107391 = DIRECTION('',(1.,-1.021336205033E-016)); +#107392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107393 = ADVANCED_FACE('',(#107394),#107265,.T.); +#107394 = FACE_BOUND('',#107395,.T.); +#107395 = EDGE_LOOP('',(#107396,#107419,#107420,#107447)); +#107396 = ORIENTED_EDGE('',*,*,#107397,.T.); +#107397 = EDGE_CURVE('',#107398,#107248,#107400,.T.); +#107398 = VERTEX_POINT('',#107399); +#107399 = CARTESIAN_POINT('',(7.15,-0.304819755875,0.75)); +#107400 = SURFACE_CURVE('',#107401,(#107406,#107412),.PCURVE_S1.); +#107401 = CIRCLE('',#107402,0.2192697516); +#107402 = AXIS2_PLACEMENT_3D('',#107403,#107404,#107405); +#107403 = CARTESIAN_POINT('',(7.15,-0.30032442045,0.530776333563)); +#107404 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107405 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107406 = PCURVE('',#107265,#107407); +#107407 = DEFINITIONAL_REPRESENTATION('',(#107408),#107411); +#107408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107409,#107410), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105017 = CARTESIAN_POINT('',(3.162095483347,-2.85)); -#105018 = CARTESIAN_POINT('',(4.712388980385,-2.85)); -#105019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105020 = PCURVE('',#88530,#105021); -#105021 = DEFINITIONAL_REPRESENTATION('',(#105022),#105026); -#105022 = CIRCLE('',#105023,0.2192697516); -#105023 = AXIS2_PLACEMENT_2D('',#105024,#105025); -#105024 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#105025 = DIRECTION('',(1.,0.E+000)); -#105026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105027 = ORIENTED_EDGE('',*,*,#104855,.T.); -#105028 = ORIENTED_EDGE('',*,*,#105029,.F.); -#105029 = EDGE_CURVE('',#105030,#104858,#105032,.T.); -#105030 = VERTEX_POINT('',#105031); -#105031 = CARTESIAN_POINT('',(7.35,-0.304819755875,0.75)); -#105032 = SURFACE_CURVE('',#105033,(#105038,#105044),.PCURVE_S1.); -#105033 = CIRCLE('',#105034,0.2192697516); -#105034 = AXIS2_PLACEMENT_3D('',#105035,#105036,#105037); -#105035 = CARTESIAN_POINT('',(7.35,-0.30032442045,0.530776333563)); -#105036 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105037 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105038 = PCURVE('',#104873,#105039); -#105039 = DEFINITIONAL_REPRESENTATION('',(#105040),#105043); -#105040 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105041,#105042), +#107409 = CARTESIAN_POINT('',(3.162095483347,-2.85)); +#107410 = CARTESIAN_POINT('',(4.712388980385,-2.85)); +#107411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107412 = PCURVE('',#90922,#107413); +#107413 = DEFINITIONAL_REPRESENTATION('',(#107414),#107418); +#107414 = CIRCLE('',#107415,0.2192697516); +#107415 = AXIS2_PLACEMENT_2D('',#107416,#107417); +#107416 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#107417 = DIRECTION('',(1.,0.E+000)); +#107418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107419 = ORIENTED_EDGE('',*,*,#107247,.T.); +#107420 = ORIENTED_EDGE('',*,*,#107421,.F.); +#107421 = EDGE_CURVE('',#107422,#107250,#107424,.T.); +#107422 = VERTEX_POINT('',#107423); +#107423 = CARTESIAN_POINT('',(7.35,-0.304819755875,0.75)); +#107424 = SURFACE_CURVE('',#107425,(#107430,#107436),.PCURVE_S1.); +#107425 = CIRCLE('',#107426,0.2192697516); +#107426 = AXIS2_PLACEMENT_3D('',#107427,#107428,#107429); +#107427 = CARTESIAN_POINT('',(7.35,-0.30032442045,0.530776333563)); +#107428 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107429 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107430 = PCURVE('',#107265,#107431); +#107431 = DEFINITIONAL_REPRESENTATION('',(#107432),#107435); +#107432 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107433,#107434), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105041 = CARTESIAN_POINT('',(3.162095483347,-2.65)); -#105042 = CARTESIAN_POINT('',(4.712388980385,-2.65)); -#105043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107433 = CARTESIAN_POINT('',(3.162095483347,-2.65)); +#107434 = CARTESIAN_POINT('',(4.712388980385,-2.65)); +#107435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105044 = PCURVE('',#88586,#105045); -#105045 = DEFINITIONAL_REPRESENTATION('',(#105046),#105054); -#105046 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105047,#105048,#105049, - #105050,#105051,#105052,#105053),.UNSPECIFIED.,.F.,.F.) +#107436 = PCURVE('',#90978,#107437); +#107437 = DEFINITIONAL_REPRESENTATION('',(#107438),#107446); +#107438 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107439,#107440,#107441, + #107442,#107443,#107444,#107445),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#105047 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#105048 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#105049 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#105050 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#105051 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#105052 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#105053 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#105054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105055 = ORIENTED_EDGE('',*,*,#105056,.T.); -#105056 = EDGE_CURVE('',#105030,#105006,#105057,.T.); -#105057 = SURFACE_CURVE('',#105058,(#105062,#105068),.PCURVE_S1.); -#105058 = LINE('',#105059,#105060); -#105059 = CARTESIAN_POINT('',(7.15,-0.304819755875,0.75)); -#105060 = VECTOR('',#105061,1.); -#105061 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105062 = PCURVE('',#104873,#105063); -#105063 = DEFINITIONAL_REPRESENTATION('',(#105064),#105067); -#105064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105065,#105066), +#107439 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#107440 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#107441 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#107442 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#107443 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#107444 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#107445 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#107446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107447 = ORIENTED_EDGE('',*,*,#107448,.T.); +#107448 = EDGE_CURVE('',#107422,#107398,#107449,.T.); +#107449 = SURFACE_CURVE('',#107450,(#107454,#107460),.PCURVE_S1.); +#107450 = LINE('',#107451,#107452); +#107451 = CARTESIAN_POINT('',(7.15,-0.304819755875,0.75)); +#107452 = VECTOR('',#107453,1.); +#107453 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107454 = PCURVE('',#107265,#107455); +#107455 = DEFINITIONAL_REPRESENTATION('',(#107456),#107459); +#107456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107457,#107458), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#105065 = CARTESIAN_POINT('',(3.162095483347,-2.65)); -#105066 = CARTESIAN_POINT('',(3.162095483347,-2.85)); -#105067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105068 = PCURVE('',#88558,#105069); -#105069 = DEFINITIONAL_REPRESENTATION('',(#105070),#105074); -#105070 = LINE('',#105071,#105072); -#105071 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#105072 = VECTOR('',#105073,1.); -#105073 = DIRECTION('',(0.E+000,-1.)); -#105074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105075 = ADVANCED_FACE('',(#105076),#104948,.F.); -#105076 = FACE_BOUND('',#105077,.F.); -#105077 = EDGE_LOOP('',(#105078,#105105,#105127,#105148)); -#105078 = ORIENTED_EDGE('',*,*,#105079,.F.); -#105079 = EDGE_CURVE('',#105080,#104931,#105082,.T.); -#105080 = VERTEX_POINT('',#105081); -#105081 = CARTESIAN_POINT('',(7.35,-0.303662633502,0.65)); -#105082 = SURFACE_CURVE('',#105083,(#105088,#105094),.PCURVE_S1.); -#105083 = CIRCLE('',#105084,0.119270391569); -#105084 = AXIS2_PLACEMENT_3D('',#105085,#105086,#105087); -#105085 = CARTESIAN_POINT('',(7.35,-0.30032442045,0.530776333563)); -#105086 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105087 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105088 = PCURVE('',#104948,#105089); -#105089 = DEFINITIONAL_REPRESENTATION('',(#105090),#105093); -#105090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105091,#105092), +#107457 = CARTESIAN_POINT('',(3.162095483347,-2.65)); +#107458 = CARTESIAN_POINT('',(3.162095483347,-2.85)); +#107459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107460 = PCURVE('',#90950,#107461); +#107461 = DEFINITIONAL_REPRESENTATION('',(#107462),#107466); +#107462 = LINE('',#107463,#107464); +#107463 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#107464 = VECTOR('',#107465,1.); +#107465 = DIRECTION('',(0.E+000,-1.)); +#107466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107467 = ADVANCED_FACE('',(#107468),#107340,.F.); +#107468 = FACE_BOUND('',#107469,.F.); +#107469 = EDGE_LOOP('',(#107470,#107497,#107519,#107540)); +#107470 = ORIENTED_EDGE('',*,*,#107471,.F.); +#107471 = EDGE_CURVE('',#107472,#107323,#107474,.T.); +#107472 = VERTEX_POINT('',#107473); +#107473 = CARTESIAN_POINT('',(7.35,-0.303662633502,0.65)); +#107474 = SURFACE_CURVE('',#107475,(#107480,#107486),.PCURVE_S1.); +#107475 = CIRCLE('',#107476,0.119270391569); +#107476 = AXIS2_PLACEMENT_3D('',#107477,#107478,#107479); +#107477 = CARTESIAN_POINT('',(7.35,-0.30032442045,0.530776333563)); +#107478 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107479 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107480 = PCURVE('',#107340,#107481); +#107481 = DEFINITIONAL_REPRESENTATION('',(#107482),#107485); +#107482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107483,#107484), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105091 = CARTESIAN_POINT('',(3.169584923929,-2.65)); -#105092 = CARTESIAN_POINT('',(4.712388980385,-2.65)); -#105093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107483 = CARTESIAN_POINT('',(3.169584923929,-2.65)); +#107484 = CARTESIAN_POINT('',(4.712388980385,-2.65)); +#107485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105094 = PCURVE('',#88586,#105095); -#105095 = DEFINITIONAL_REPRESENTATION('',(#105096),#105104); -#105096 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105097,#105098,#105099, - #105100,#105101,#105102,#105103),.UNSPECIFIED.,.F.,.F.) +#107486 = PCURVE('',#90978,#107487); +#107487 = DEFINITIONAL_REPRESENTATION('',(#107488),#107496); +#107488 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107489,#107490,#107491, + #107492,#107493,#107494,#107495),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#105097 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#105098 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#105099 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#105100 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#105101 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#105102 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#105103 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#105104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105105 = ORIENTED_EDGE('',*,*,#105106,.F.); -#105106 = EDGE_CURVE('',#105107,#105080,#105109,.T.); -#105107 = VERTEX_POINT('',#105108); -#105108 = CARTESIAN_POINT('',(7.15,-0.303662633502,0.65)); -#105109 = SURFACE_CURVE('',#105110,(#105114,#105120),.PCURVE_S1.); -#105110 = LINE('',#105111,#105112); -#105111 = CARTESIAN_POINT('',(7.15,-0.303662633502,0.65)); -#105112 = VECTOR('',#105113,1.); -#105113 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105114 = PCURVE('',#104948,#105115); -#105115 = DEFINITIONAL_REPRESENTATION('',(#105116),#105119); -#105116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105117,#105118), +#107489 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#107490 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#107491 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#107492 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#107493 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#107494 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#107495 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#107496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107497 = ORIENTED_EDGE('',*,*,#107498,.F.); +#107498 = EDGE_CURVE('',#107499,#107472,#107501,.T.); +#107499 = VERTEX_POINT('',#107500); +#107500 = CARTESIAN_POINT('',(7.15,-0.303662633502,0.65)); +#107501 = SURFACE_CURVE('',#107502,(#107506,#107512),.PCURVE_S1.); +#107502 = LINE('',#107503,#107504); +#107503 = CARTESIAN_POINT('',(7.15,-0.303662633502,0.65)); +#107504 = VECTOR('',#107505,1.); +#107505 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107506 = PCURVE('',#107340,#107507); +#107507 = DEFINITIONAL_REPRESENTATION('',(#107508),#107511); +#107508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107509,#107510), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#105117 = CARTESIAN_POINT('',(3.169584923929,-2.85)); -#105118 = CARTESIAN_POINT('',(3.169584923929,-2.65)); -#105119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105120 = PCURVE('',#88612,#105121); -#105121 = DEFINITIONAL_REPRESENTATION('',(#105122),#105126); -#105122 = LINE('',#105123,#105124); -#105123 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#105124 = VECTOR('',#105125,1.); -#105125 = DIRECTION('',(0.E+000,1.)); -#105126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105127 = ORIENTED_EDGE('',*,*,#105128,.T.); -#105128 = EDGE_CURVE('',#105107,#104933,#105129,.T.); -#105129 = SURFACE_CURVE('',#105130,(#105135,#105141),.PCURVE_S1.); -#105130 = CIRCLE('',#105131,0.119270391569); -#105131 = AXIS2_PLACEMENT_3D('',#105132,#105133,#105134); -#105132 = CARTESIAN_POINT('',(7.15,-0.30032442045,0.530776333563)); -#105133 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105134 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105135 = PCURVE('',#104948,#105136); -#105136 = DEFINITIONAL_REPRESENTATION('',(#105137),#105140); -#105137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105138,#105139), +#107509 = CARTESIAN_POINT('',(3.169584923929,-2.85)); +#107510 = CARTESIAN_POINT('',(3.169584923929,-2.65)); +#107511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107512 = PCURVE('',#91004,#107513); +#107513 = DEFINITIONAL_REPRESENTATION('',(#107514),#107518); +#107514 = LINE('',#107515,#107516); +#107515 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#107516 = VECTOR('',#107517,1.); +#107517 = DIRECTION('',(0.E+000,1.)); +#107518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107519 = ORIENTED_EDGE('',*,*,#107520,.T.); +#107520 = EDGE_CURVE('',#107499,#107325,#107521,.T.); +#107521 = SURFACE_CURVE('',#107522,(#107527,#107533),.PCURVE_S1.); +#107522 = CIRCLE('',#107523,0.119270391569); +#107523 = AXIS2_PLACEMENT_3D('',#107524,#107525,#107526); +#107524 = CARTESIAN_POINT('',(7.15,-0.30032442045,0.530776333563)); +#107525 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107526 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107527 = PCURVE('',#107340,#107528); +#107528 = DEFINITIONAL_REPRESENTATION('',(#107529),#107532); +#107529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107530,#107531), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105138 = CARTESIAN_POINT('',(3.169584923929,-2.85)); -#105139 = CARTESIAN_POINT('',(4.712388980385,-2.85)); -#105140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105141 = PCURVE('',#88530,#105142); -#105142 = DEFINITIONAL_REPRESENTATION('',(#105143),#105147); -#105143 = CIRCLE('',#105144,0.119270391569); -#105144 = AXIS2_PLACEMENT_2D('',#105145,#105146); -#105145 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#105146 = DIRECTION('',(1.,0.E+000)); -#105147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105148 = ORIENTED_EDGE('',*,*,#104930,.F.); -#105149 = ADVANCED_FACE('',(#105150),#88530,.F.); -#105150 = FACE_BOUND('',#105151,.T.); -#105151 = EDGE_LOOP('',(#105152,#105173,#105174,#105175,#105176,#105177, - #105198,#105199,#105200,#105201,#105202,#105223)); -#105152 = ORIENTED_EDGE('',*,*,#105153,.F.); -#105153 = EDGE_CURVE('',#105107,#88515,#105154,.T.); -#105154 = SURFACE_CURVE('',#105155,(#105159,#105166),.PCURVE_S1.); -#105155 = LINE('',#105156,#105157); -#105156 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); -#105157 = VECTOR('',#105158,1.); -#105158 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#105159 = PCURVE('',#88530,#105160); -#105160 = DEFINITIONAL_REPRESENTATION('',(#105161),#105165); -#105161 = LINE('',#105162,#105163); -#105162 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105163 = VECTOR('',#105164,1.); -#105164 = DIRECTION('',(-3.563627120235E-016,1.)); -#105165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105166 = PCURVE('',#88612,#105167); -#105167 = DEFINITIONAL_REPRESENTATION('',(#105168),#105172); -#105168 = LINE('',#105169,#105170); -#105169 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105170 = VECTOR('',#105171,1.); -#105171 = DIRECTION('',(-1.,0.E+000)); -#105172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105173 = ORIENTED_EDGE('',*,*,#105128,.T.); -#105174 = ORIENTED_EDGE('',*,*,#104981,.T.); -#105175 = ORIENTED_EDGE('',*,*,#104698,.T.); -#105176 = ORIENTED_EDGE('',*,*,#104542,.T.); -#105177 = ORIENTED_EDGE('',*,*,#105178,.T.); -#105178 = EDGE_CURVE('',#104515,#104596,#105179,.T.); -#105179 = SURFACE_CURVE('',#105180,(#105184,#105191),.PCURVE_S1.); -#105180 = LINE('',#105181,#105182); -#105181 = CARTESIAN_POINT('',(7.15,-1.,1.159810404338E-002)); -#105182 = VECTOR('',#105183,1.); -#105183 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#105184 = PCURVE('',#88530,#105185); -#105185 = DEFINITIONAL_REPRESENTATION('',(#105186),#105190); -#105186 = LINE('',#105187,#105188); -#105187 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#105188 = VECTOR('',#105189,1.); -#105189 = DIRECTION('',(-1.,-2.101748079665E-016)); -#105190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105191 = PCURVE('',#104530,#105192); -#105192 = DEFINITIONAL_REPRESENTATION('',(#105193),#105197); -#105193 = LINE('',#105194,#105195); -#105194 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#105195 = VECTOR('',#105196,1.); -#105196 = DIRECTION('',(-1.,0.E+000)); -#105197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105198 = ORIENTED_EDGE('',*,*,#104593,.F.); -#105199 = ORIENTED_EDGE('',*,*,#104777,.F.); -#105200 = ORIENTED_EDGE('',*,*,#104884,.F.); -#105201 = ORIENTED_EDGE('',*,*,#105005,.F.); -#105202 = ORIENTED_EDGE('',*,*,#105203,.T.); -#105203 = EDGE_CURVE('',#105006,#88513,#105204,.T.); -#105204 = SURFACE_CURVE('',#105205,(#105209,#105216),.PCURVE_S1.); -#105205 = LINE('',#105206,#105207); -#105206 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.75)); -#105207 = VECTOR('',#105208,1.); -#105208 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#105209 = PCURVE('',#88530,#105210); -#105210 = DEFINITIONAL_REPRESENTATION('',(#105211),#105215); -#105211 = LINE('',#105212,#105213); -#105212 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#105213 = VECTOR('',#105214,1.); -#105214 = DIRECTION('',(-3.563627120235E-016,1.)); -#105215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105216 = PCURVE('',#88558,#105217); -#105217 = DEFINITIONAL_REPRESENTATION('',(#105218),#105222); -#105218 = LINE('',#105219,#105220); -#105219 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105220 = VECTOR('',#105221,1.); -#105221 = DIRECTION('',(1.,0.E+000)); -#105222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105223 = ORIENTED_EDGE('',*,*,#88512,.T.); -#105224 = ADVANCED_FACE('',(#105225),#88558,.F.); -#105225 = FACE_BOUND('',#105226,.T.); -#105226 = EDGE_LOOP('',(#105227,#105228,#105249,#105250)); -#105227 = ORIENTED_EDGE('',*,*,#105056,.F.); -#105228 = ORIENTED_EDGE('',*,*,#105229,.T.); -#105229 = EDGE_CURVE('',#105030,#88543,#105230,.T.); -#105230 = SURFACE_CURVE('',#105231,(#105235,#105242),.PCURVE_S1.); -#105231 = LINE('',#105232,#105233); -#105232 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.75)); -#105233 = VECTOR('',#105234,1.); -#105234 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#105235 = PCURVE('',#88558,#105236); -#105236 = DEFINITIONAL_REPRESENTATION('',(#105237),#105241); -#105237 = LINE('',#105238,#105239); -#105238 = CARTESIAN_POINT('',(0.E+000,0.2)); -#105239 = VECTOR('',#105240,1.); -#105240 = DIRECTION('',(1.,0.E+000)); -#105241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105242 = PCURVE('',#88586,#105243); -#105243 = DEFINITIONAL_REPRESENTATION('',(#105244),#105248); -#105244 = LINE('',#105245,#105246); -#105245 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#105246 = VECTOR('',#105247,1.); -#105247 = DIRECTION('',(3.563627120235E-016,1.)); -#105248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105249 = ORIENTED_EDGE('',*,*,#88542,.T.); -#105250 = ORIENTED_EDGE('',*,*,#105203,.F.); -#105251 = ADVANCED_FACE('',(#105252),#88586,.F.); -#105252 = FACE_BOUND('',#105253,.T.); -#105253 = EDGE_LOOP('',(#105254,#105255,#105256,#105257,#105258,#105259, - #105280,#105281,#105282,#105283,#105284,#105305)); -#105254 = ORIENTED_EDGE('',*,*,#105229,.F.); -#105255 = ORIENTED_EDGE('',*,*,#105029,.T.); -#105256 = ORIENTED_EDGE('',*,*,#104906,.T.); -#105257 = ORIENTED_EDGE('',*,*,#104831,.T.); -#105258 = ORIENTED_EDGE('',*,*,#104646,.T.); -#105259 = ORIENTED_EDGE('',*,*,#105260,.T.); -#105260 = EDGE_CURVE('',#104624,#104487,#105261,.T.); -#105261 = SURFACE_CURVE('',#105262,(#105266,#105273),.PCURVE_S1.); -#105262 = LINE('',#105263,#105264); -#105263 = CARTESIAN_POINT('',(7.35,-1.,1.159810404338E-002)); -#105264 = VECTOR('',#105265,1.); -#105265 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#105266 = PCURVE('',#88586,#105267); -#105267 = DEFINITIONAL_REPRESENTATION('',(#105268),#105272); -#105268 = LINE('',#105269,#105270); -#105269 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#105270 = VECTOR('',#105271,1.); -#105271 = DIRECTION('',(-1.,2.101748079665E-016)); -#105272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105273 = PCURVE('',#104530,#105274); -#105274 = DEFINITIONAL_REPRESENTATION('',(#105275),#105279); -#105275 = LINE('',#105276,#105277); -#105276 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); -#105277 = VECTOR('',#105278,1.); -#105278 = DIRECTION('',(1.,0.E+000)); -#105279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105280 = ORIENTED_EDGE('',*,*,#104484,.F.); -#105281 = ORIENTED_EDGE('',*,*,#104752,.F.); -#105282 = ORIENTED_EDGE('',*,*,#104959,.F.); -#105283 = ORIENTED_EDGE('',*,*,#105079,.F.); -#105284 = ORIENTED_EDGE('',*,*,#105285,.T.); -#105285 = EDGE_CURVE('',#105080,#88571,#105286,.T.); -#105286 = SURFACE_CURVE('',#105287,(#105291,#105298),.PCURVE_S1.); -#105287 = LINE('',#105288,#105289); -#105288 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.65)); -#105289 = VECTOR('',#105290,1.); -#105290 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#105291 = PCURVE('',#88586,#105292); -#105292 = DEFINITIONAL_REPRESENTATION('',(#105293),#105297); -#105293 = LINE('',#105294,#105295); -#105294 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105295 = VECTOR('',#105296,1.); -#105296 = DIRECTION('',(3.563627120235E-016,1.)); -#105297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105298 = PCURVE('',#88612,#105299); -#105299 = DEFINITIONAL_REPRESENTATION('',(#105300),#105304); -#105300 = LINE('',#105301,#105302); -#105301 = CARTESIAN_POINT('',(0.E+000,0.2)); -#105302 = VECTOR('',#105303,1.); -#105303 = DIRECTION('',(-1.,0.E+000)); -#105304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105305 = ORIENTED_EDGE('',*,*,#88570,.T.); -#105306 = ADVANCED_FACE('',(#105307),#88612,.F.); -#105307 = FACE_BOUND('',#105308,.T.); -#105308 = EDGE_LOOP('',(#105309,#105310,#105311,#105312)); -#105309 = ORIENTED_EDGE('',*,*,#105106,.F.); -#105310 = ORIENTED_EDGE('',*,*,#105153,.T.); -#105311 = ORIENTED_EDGE('',*,*,#88598,.T.); -#105312 = ORIENTED_EDGE('',*,*,#105285,.F.); -#105313 = ADVANCED_FACE('',(#105314),#104530,.T.); -#105314 = FACE_BOUND('',#105315,.T.); -#105315 = EDGE_LOOP('',(#105316,#105317,#105318,#105319)); -#105316 = ORIENTED_EDGE('',*,*,#105260,.F.); -#105317 = ORIENTED_EDGE('',*,*,#104623,.F.); -#105318 = ORIENTED_EDGE('',*,*,#105178,.F.); -#105319 = ORIENTED_EDGE('',*,*,#104514,.F.); -#105320 = ADVANCED_FACE('',(#105321),#105335,.T.); -#105321 = FACE_BOUND('',#105322,.T.); -#105322 = EDGE_LOOP('',(#105323,#105353,#105381,#105404)); -#105323 = ORIENTED_EDGE('',*,*,#105324,.T.); -#105324 = EDGE_CURVE('',#105325,#105327,#105329,.T.); -#105325 = VERTEX_POINT('',#105326); -#105326 = CARTESIAN_POINT('',(7.85,-0.74341632541,-0.308197125857)); -#105327 = VERTEX_POINT('',#105328); -#105328 = CARTESIAN_POINT('',(7.85,-1.,-0.308197125857)); -#105329 = SURFACE_CURVE('',#105330,(#105334,#105346),.PCURVE_S1.); -#105330 = LINE('',#105331,#105332); -#105331 = CARTESIAN_POINT('',(7.85,-0.74341632541,-0.308197125857)); -#105332 = VECTOR('',#105333,1.); -#105333 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#105334 = PCURVE('',#105335,#105340); -#105335 = PLANE('',#105336); -#105336 = AXIS2_PLACEMENT_3D('',#105337,#105338,#105339); -#105337 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#105338 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105339 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105340 = DEFINITIONAL_REPRESENTATION('',(#105341),#105345); -#105341 = LINE('',#105342,#105343); -#105342 = CARTESIAN_POINT('',(2.15,0.E+000)); -#105343 = VECTOR('',#105344,1.); -#105344 = DIRECTION('',(0.E+000,-1.)); -#105345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105346 = PCURVE('',#90177,#105347); -#105347 = DEFINITIONAL_REPRESENTATION('',(#105348),#105352); -#105348 = LINE('',#105349,#105350); -#105349 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#105350 = VECTOR('',#105351,1.); -#105351 = DIRECTION('',(0.E+000,-1.)); -#105352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105353 = ORIENTED_EDGE('',*,*,#105354,.T.); -#105354 = EDGE_CURVE('',#105327,#105355,#105357,.T.); -#105355 = VERTEX_POINT('',#105356); -#105356 = CARTESIAN_POINT('',(7.65,-1.,-0.308197125857)); -#105357 = SURFACE_CURVE('',#105358,(#105362,#105369),.PCURVE_S1.); -#105358 = LINE('',#105359,#105360); -#105359 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#105360 = VECTOR('',#105361,1.); -#105361 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105362 = PCURVE('',#105335,#105363); -#105363 = DEFINITIONAL_REPRESENTATION('',(#105364),#105368); -#105364 = LINE('',#105365,#105366); -#105365 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#105366 = VECTOR('',#105367,1.); -#105367 = DIRECTION('',(1.,0.E+000)); -#105368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105369 = PCURVE('',#105370,#105375); -#105370 = PLANE('',#105371); -#105371 = AXIS2_PLACEMENT_3D('',#105372,#105373,#105374); -#105372 = CARTESIAN_POINT('',(7.75,-1.,-0.258196742327)); -#105373 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#105374 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#105375 = DEFINITIONAL_REPRESENTATION('',(#105376),#105380); -#105376 = LINE('',#105377,#105378); -#105377 = CARTESIAN_POINT('',(5.000038352949E-002,2.25)); -#105378 = VECTOR('',#105379,1.); -#105379 = DIRECTION('',(0.E+000,-1.)); -#105380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105381 = ORIENTED_EDGE('',*,*,#105382,.F.); -#105382 = EDGE_CURVE('',#105383,#105355,#105385,.T.); -#105383 = VERTEX_POINT('',#105384); -#105384 = CARTESIAN_POINT('',(7.65,-0.74341632541,-0.308197125857)); -#105385 = SURFACE_CURVE('',#105386,(#105390,#105397),.PCURVE_S1.); -#105386 = LINE('',#105387,#105388); -#105387 = CARTESIAN_POINT('',(7.65,-0.74341632541,-0.308197125857)); -#105388 = VECTOR('',#105389,1.); -#105389 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#105390 = PCURVE('',#105335,#105391); -#105391 = DEFINITIONAL_REPRESENTATION('',(#105392),#105396); -#105392 = LINE('',#105393,#105394); -#105393 = CARTESIAN_POINT('',(2.35,0.E+000)); -#105394 = VECTOR('',#105395,1.); -#105395 = DIRECTION('',(0.E+000,-1.)); -#105396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105397 = PCURVE('',#90121,#105398); -#105398 = DEFINITIONAL_REPRESENTATION('',(#105399),#105403); -#105399 = LINE('',#105400,#105401); -#105400 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#105401 = VECTOR('',#105402,1.); -#105402 = DIRECTION('',(0.E+000,-1.)); -#105403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105404 = ORIENTED_EDGE('',*,*,#105405,.T.); -#105405 = EDGE_CURVE('',#105383,#105325,#105406,.T.); -#105406 = SURFACE_CURVE('',#105407,(#105411,#105418),.PCURVE_S1.); -#105407 = LINE('',#105408,#105409); -#105408 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#105409 = VECTOR('',#105410,1.); -#105410 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105411 = PCURVE('',#105335,#105412); -#105412 = DEFINITIONAL_REPRESENTATION('',(#105413),#105417); -#105413 = LINE('',#105414,#105415); -#105414 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105415 = VECTOR('',#105416,1.); -#105416 = DIRECTION('',(-1.,0.E+000)); -#105417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105418 = PCURVE('',#105419,#105424); -#105419 = CYLINDRICAL_SURFACE('',#105420,0.308574064194); -#105420 = AXIS2_PLACEMENT_3D('',#105421,#105422,#105423); -#105421 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#105422 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105423 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105424 = DEFINITIONAL_REPRESENTATION('',(#105425),#105428); -#105425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105426,#105427), +#107530 = CARTESIAN_POINT('',(3.169584923929,-2.85)); +#107531 = CARTESIAN_POINT('',(4.712388980385,-2.85)); +#107532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107533 = PCURVE('',#90922,#107534); +#107534 = DEFINITIONAL_REPRESENTATION('',(#107535),#107539); +#107535 = CIRCLE('',#107536,0.119270391569); +#107536 = AXIS2_PLACEMENT_2D('',#107537,#107538); +#107537 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#107538 = DIRECTION('',(1.,0.E+000)); +#107539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107540 = ORIENTED_EDGE('',*,*,#107322,.F.); +#107541 = ADVANCED_FACE('',(#107542),#90922,.F.); +#107542 = FACE_BOUND('',#107543,.T.); +#107543 = EDGE_LOOP('',(#107544,#107565,#107566,#107567,#107568,#107569, + #107590,#107591,#107592,#107593,#107594,#107615)); +#107544 = ORIENTED_EDGE('',*,*,#107545,.F.); +#107545 = EDGE_CURVE('',#107499,#90907,#107546,.T.); +#107546 = SURFACE_CURVE('',#107547,(#107551,#107558),.PCURVE_S1.); +#107547 = LINE('',#107548,#107549); +#107548 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.65)); +#107549 = VECTOR('',#107550,1.); +#107550 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#107551 = PCURVE('',#90922,#107552); +#107552 = DEFINITIONAL_REPRESENTATION('',(#107553),#107557); +#107553 = LINE('',#107554,#107555); +#107554 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107555 = VECTOR('',#107556,1.); +#107556 = DIRECTION('',(-3.563627120235E-016,1.)); +#107557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107558 = PCURVE('',#91004,#107559); +#107559 = DEFINITIONAL_REPRESENTATION('',(#107560),#107564); +#107560 = LINE('',#107561,#107562); +#107561 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107562 = VECTOR('',#107563,1.); +#107563 = DIRECTION('',(-1.,0.E+000)); +#107564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107565 = ORIENTED_EDGE('',*,*,#107520,.T.); +#107566 = ORIENTED_EDGE('',*,*,#107373,.T.); +#107567 = ORIENTED_EDGE('',*,*,#107090,.T.); +#107568 = ORIENTED_EDGE('',*,*,#106934,.T.); +#107569 = ORIENTED_EDGE('',*,*,#107570,.T.); +#107570 = EDGE_CURVE('',#106907,#106988,#107571,.T.); +#107571 = SURFACE_CURVE('',#107572,(#107576,#107583),.PCURVE_S1.); +#107572 = LINE('',#107573,#107574); +#107573 = CARTESIAN_POINT('',(7.15,-1.,1.159810404338E-002)); +#107574 = VECTOR('',#107575,1.); +#107575 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#107576 = PCURVE('',#90922,#107577); +#107577 = DEFINITIONAL_REPRESENTATION('',(#107578),#107582); +#107578 = LINE('',#107579,#107580); +#107579 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#107580 = VECTOR('',#107581,1.); +#107581 = DIRECTION('',(-1.,-2.101748079665E-016)); +#107582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107583 = PCURVE('',#106922,#107584); +#107584 = DEFINITIONAL_REPRESENTATION('',(#107585),#107589); +#107585 = LINE('',#107586,#107587); +#107586 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#107587 = VECTOR('',#107588,1.); +#107588 = DIRECTION('',(-1.,0.E+000)); +#107589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107590 = ORIENTED_EDGE('',*,*,#106985,.F.); +#107591 = ORIENTED_EDGE('',*,*,#107169,.F.); +#107592 = ORIENTED_EDGE('',*,*,#107276,.F.); +#107593 = ORIENTED_EDGE('',*,*,#107397,.F.); +#107594 = ORIENTED_EDGE('',*,*,#107595,.T.); +#107595 = EDGE_CURVE('',#107398,#90905,#107596,.T.); +#107596 = SURFACE_CURVE('',#107597,(#107601,#107608),.PCURVE_S1.); +#107597 = LINE('',#107598,#107599); +#107598 = CARTESIAN_POINT('',(7.15,-0.527847992439,0.75)); +#107599 = VECTOR('',#107600,1.); +#107600 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#107601 = PCURVE('',#90922,#107602); +#107602 = DEFINITIONAL_REPRESENTATION('',(#107603),#107607); +#107603 = LINE('',#107604,#107605); +#107604 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#107605 = VECTOR('',#107606,1.); +#107606 = DIRECTION('',(-3.563627120235E-016,1.)); +#107607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107608 = PCURVE('',#90950,#107609); +#107609 = DEFINITIONAL_REPRESENTATION('',(#107610),#107614); +#107610 = LINE('',#107611,#107612); +#107611 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107612 = VECTOR('',#107613,1.); +#107613 = DIRECTION('',(1.,0.E+000)); +#107614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107615 = ORIENTED_EDGE('',*,*,#90904,.T.); +#107616 = ADVANCED_FACE('',(#107617),#90950,.F.); +#107617 = FACE_BOUND('',#107618,.T.); +#107618 = EDGE_LOOP('',(#107619,#107620,#107641,#107642)); +#107619 = ORIENTED_EDGE('',*,*,#107448,.F.); +#107620 = ORIENTED_EDGE('',*,*,#107621,.T.); +#107621 = EDGE_CURVE('',#107422,#90935,#107622,.T.); +#107622 = SURFACE_CURVE('',#107623,(#107627,#107634),.PCURVE_S1.); +#107623 = LINE('',#107624,#107625); +#107624 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.75)); +#107625 = VECTOR('',#107626,1.); +#107626 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#107627 = PCURVE('',#90950,#107628); +#107628 = DEFINITIONAL_REPRESENTATION('',(#107629),#107633); +#107629 = LINE('',#107630,#107631); +#107630 = CARTESIAN_POINT('',(0.E+000,0.2)); +#107631 = VECTOR('',#107632,1.); +#107632 = DIRECTION('',(1.,0.E+000)); +#107633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107634 = PCURVE('',#90978,#107635); +#107635 = DEFINITIONAL_REPRESENTATION('',(#107636),#107640); +#107636 = LINE('',#107637,#107638); +#107637 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#107638 = VECTOR('',#107639,1.); +#107639 = DIRECTION('',(3.563627120235E-016,1.)); +#107640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107641 = ORIENTED_EDGE('',*,*,#90934,.T.); +#107642 = ORIENTED_EDGE('',*,*,#107595,.F.); +#107643 = ADVANCED_FACE('',(#107644),#90978,.F.); +#107644 = FACE_BOUND('',#107645,.T.); +#107645 = EDGE_LOOP('',(#107646,#107647,#107648,#107649,#107650,#107651, + #107672,#107673,#107674,#107675,#107676,#107697)); +#107646 = ORIENTED_EDGE('',*,*,#107621,.F.); +#107647 = ORIENTED_EDGE('',*,*,#107421,.T.); +#107648 = ORIENTED_EDGE('',*,*,#107298,.T.); +#107649 = ORIENTED_EDGE('',*,*,#107223,.T.); +#107650 = ORIENTED_EDGE('',*,*,#107038,.T.); +#107651 = ORIENTED_EDGE('',*,*,#107652,.T.); +#107652 = EDGE_CURVE('',#107016,#106879,#107653,.T.); +#107653 = SURFACE_CURVE('',#107654,(#107658,#107665),.PCURVE_S1.); +#107654 = LINE('',#107655,#107656); +#107655 = CARTESIAN_POINT('',(7.35,-1.,1.159810404338E-002)); +#107656 = VECTOR('',#107657,1.); +#107657 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#107658 = PCURVE('',#90978,#107659); +#107659 = DEFINITIONAL_REPRESENTATION('',(#107660),#107664); +#107660 = LINE('',#107661,#107662); +#107661 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#107662 = VECTOR('',#107663,1.); +#107663 = DIRECTION('',(-1.,2.101748079665E-016)); +#107664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107665 = PCURVE('',#106922,#107666); +#107666 = DEFINITIONAL_REPRESENTATION('',(#107667),#107671); +#107667 = LINE('',#107668,#107669); +#107668 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); +#107669 = VECTOR('',#107670,1.); +#107670 = DIRECTION('',(1.,0.E+000)); +#107671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107672 = ORIENTED_EDGE('',*,*,#106876,.F.); +#107673 = ORIENTED_EDGE('',*,*,#107144,.F.); +#107674 = ORIENTED_EDGE('',*,*,#107351,.F.); +#107675 = ORIENTED_EDGE('',*,*,#107471,.F.); +#107676 = ORIENTED_EDGE('',*,*,#107677,.T.); +#107677 = EDGE_CURVE('',#107472,#90963,#107678,.T.); +#107678 = SURFACE_CURVE('',#107679,(#107683,#107690),.PCURVE_S1.); +#107679 = LINE('',#107680,#107681); +#107680 = CARTESIAN_POINT('',(7.35,-0.527847992439,0.65)); +#107681 = VECTOR('',#107682,1.); +#107682 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#107683 = PCURVE('',#90978,#107684); +#107684 = DEFINITIONAL_REPRESENTATION('',(#107685),#107689); +#107685 = LINE('',#107686,#107687); +#107686 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107687 = VECTOR('',#107688,1.); +#107688 = DIRECTION('',(3.563627120235E-016,1.)); +#107689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107690 = PCURVE('',#91004,#107691); +#107691 = DEFINITIONAL_REPRESENTATION('',(#107692),#107696); +#107692 = LINE('',#107693,#107694); +#107693 = CARTESIAN_POINT('',(0.E+000,0.2)); +#107694 = VECTOR('',#107695,1.); +#107695 = DIRECTION('',(-1.,0.E+000)); +#107696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107697 = ORIENTED_EDGE('',*,*,#90962,.T.); +#107698 = ADVANCED_FACE('',(#107699),#91004,.F.); +#107699 = FACE_BOUND('',#107700,.T.); +#107700 = EDGE_LOOP('',(#107701,#107702,#107703,#107704)); +#107701 = ORIENTED_EDGE('',*,*,#107498,.F.); +#107702 = ORIENTED_EDGE('',*,*,#107545,.T.); +#107703 = ORIENTED_EDGE('',*,*,#90990,.T.); +#107704 = ORIENTED_EDGE('',*,*,#107677,.F.); +#107705 = ADVANCED_FACE('',(#107706),#106922,.T.); +#107706 = FACE_BOUND('',#107707,.T.); +#107707 = EDGE_LOOP('',(#107708,#107709,#107710,#107711)); +#107708 = ORIENTED_EDGE('',*,*,#107652,.F.); +#107709 = ORIENTED_EDGE('',*,*,#107015,.F.); +#107710 = ORIENTED_EDGE('',*,*,#107570,.F.); +#107711 = ORIENTED_EDGE('',*,*,#106906,.F.); +#107712 = ADVANCED_FACE('',(#107713),#107727,.T.); +#107713 = FACE_BOUND('',#107714,.T.); +#107714 = EDGE_LOOP('',(#107715,#107745,#107773,#107796)); +#107715 = ORIENTED_EDGE('',*,*,#107716,.T.); +#107716 = EDGE_CURVE('',#107717,#107719,#107721,.T.); +#107717 = VERTEX_POINT('',#107718); +#107718 = CARTESIAN_POINT('',(7.85,-0.74341632541,-0.308197125857)); +#107719 = VERTEX_POINT('',#107720); +#107720 = CARTESIAN_POINT('',(7.85,-1.,-0.308197125857)); +#107721 = SURFACE_CURVE('',#107722,(#107726,#107738),.PCURVE_S1.); +#107722 = LINE('',#107723,#107724); +#107723 = CARTESIAN_POINT('',(7.85,-0.74341632541,-0.308197125857)); +#107724 = VECTOR('',#107725,1.); +#107725 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#107726 = PCURVE('',#107727,#107732); +#107727 = PLANE('',#107728); +#107728 = AXIS2_PLACEMENT_3D('',#107729,#107730,#107731); +#107729 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#107730 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#107731 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107732 = DEFINITIONAL_REPRESENTATION('',(#107733),#107737); +#107733 = LINE('',#107734,#107735); +#107734 = CARTESIAN_POINT('',(2.15,0.E+000)); +#107735 = VECTOR('',#107736,1.); +#107736 = DIRECTION('',(0.E+000,-1.)); +#107737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107738 = PCURVE('',#92569,#107739); +#107739 = DEFINITIONAL_REPRESENTATION('',(#107740),#107744); +#107740 = LINE('',#107741,#107742); +#107741 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#107742 = VECTOR('',#107743,1.); +#107743 = DIRECTION('',(0.E+000,-1.)); +#107744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107745 = ORIENTED_EDGE('',*,*,#107746,.T.); +#107746 = EDGE_CURVE('',#107719,#107747,#107749,.T.); +#107747 = VERTEX_POINT('',#107748); +#107748 = CARTESIAN_POINT('',(7.65,-1.,-0.308197125857)); +#107749 = SURFACE_CURVE('',#107750,(#107754,#107761),.PCURVE_S1.); +#107750 = LINE('',#107751,#107752); +#107751 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#107752 = VECTOR('',#107753,1.); +#107753 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107754 = PCURVE('',#107727,#107755); +#107755 = DEFINITIONAL_REPRESENTATION('',(#107756),#107760); +#107756 = LINE('',#107757,#107758); +#107757 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#107758 = VECTOR('',#107759,1.); +#107759 = DIRECTION('',(1.,0.E+000)); +#107760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107761 = PCURVE('',#107762,#107767); +#107762 = PLANE('',#107763); +#107763 = AXIS2_PLACEMENT_3D('',#107764,#107765,#107766); +#107764 = CARTESIAN_POINT('',(7.75,-1.,-0.258196742327)); +#107765 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#107766 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#107767 = DEFINITIONAL_REPRESENTATION('',(#107768),#107772); +#107768 = LINE('',#107769,#107770); +#107769 = CARTESIAN_POINT('',(5.000038352949E-002,2.25)); +#107770 = VECTOR('',#107771,1.); +#107771 = DIRECTION('',(0.E+000,-1.)); +#107772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107773 = ORIENTED_EDGE('',*,*,#107774,.F.); +#107774 = EDGE_CURVE('',#107775,#107747,#107777,.T.); +#107775 = VERTEX_POINT('',#107776); +#107776 = CARTESIAN_POINT('',(7.65,-0.74341632541,-0.308197125857)); +#107777 = SURFACE_CURVE('',#107778,(#107782,#107789),.PCURVE_S1.); +#107778 = LINE('',#107779,#107780); +#107779 = CARTESIAN_POINT('',(7.65,-0.74341632541,-0.308197125857)); +#107780 = VECTOR('',#107781,1.); +#107781 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#107782 = PCURVE('',#107727,#107783); +#107783 = DEFINITIONAL_REPRESENTATION('',(#107784),#107788); +#107784 = LINE('',#107785,#107786); +#107785 = CARTESIAN_POINT('',(2.35,0.E+000)); +#107786 = VECTOR('',#107787,1.); +#107787 = DIRECTION('',(0.E+000,-1.)); +#107788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107789 = PCURVE('',#92513,#107790); +#107790 = DEFINITIONAL_REPRESENTATION('',(#107791),#107795); +#107791 = LINE('',#107792,#107793); +#107792 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#107793 = VECTOR('',#107794,1.); +#107794 = DIRECTION('',(0.E+000,-1.)); +#107795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107796 = ORIENTED_EDGE('',*,*,#107797,.T.); +#107797 = EDGE_CURVE('',#107775,#107717,#107798,.T.); +#107798 = SURFACE_CURVE('',#107799,(#107803,#107810),.PCURVE_S1.); +#107799 = LINE('',#107800,#107801); +#107800 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#107801 = VECTOR('',#107802,1.); +#107802 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107803 = PCURVE('',#107727,#107804); +#107804 = DEFINITIONAL_REPRESENTATION('',(#107805),#107809); +#107805 = LINE('',#107806,#107807); +#107806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107807 = VECTOR('',#107808,1.); +#107808 = DIRECTION('',(-1.,0.E+000)); +#107809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107810 = PCURVE('',#107811,#107816); +#107811 = CYLINDRICAL_SURFACE('',#107812,0.308574064194); +#107812 = AXIS2_PLACEMENT_3D('',#107813,#107814,#107815); +#107813 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#107814 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107815 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107816 = DEFINITIONAL_REPRESENTATION('',(#107817),#107820); +#107817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107818,#107819), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#105426 = CARTESIAN_POINT('',(3.191025391152,2.35)); -#105427 = CARTESIAN_POINT('',(3.191025391152,2.15)); -#105428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105429 = ADVANCED_FACE('',(#105430),#105444,.T.); -#105430 = FACE_BOUND('',#105431,.T.); -#105431 = EDGE_LOOP('',(#105432,#105462,#105485,#105508)); -#105432 = ORIENTED_EDGE('',*,*,#105433,.T.); -#105433 = EDGE_CURVE('',#105434,#105436,#105438,.T.); -#105434 = VERTEX_POINT('',#105435); -#105435 = CARTESIAN_POINT('',(7.65,-0.740726081328,-0.208196358798)); -#105436 = VERTEX_POINT('',#105437); -#105437 = CARTESIAN_POINT('',(7.65,-1.,-0.208196358798)); -#105438 = SURFACE_CURVE('',#105439,(#105443,#105455),.PCURVE_S1.); -#105439 = LINE('',#105440,#105441); -#105440 = CARTESIAN_POINT('',(7.65,-0.740726081328,-0.208196358798)); -#105441 = VECTOR('',#105442,1.); -#105442 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#105443 = PCURVE('',#105444,#105449); -#105444 = PLANE('',#105445); -#105445 = AXIS2_PLACEMENT_3D('',#105446,#105447,#105448); -#105446 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#105447 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105448 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105449 = DEFINITIONAL_REPRESENTATION('',(#105450),#105454); -#105450 = LINE('',#105451,#105452); -#105451 = CARTESIAN_POINT('',(-2.35,0.E+000)); -#105452 = VECTOR('',#105453,1.); -#105453 = DIRECTION('',(0.E+000,-1.)); -#105454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105455 = PCURVE('',#90121,#105456); -#105456 = DEFINITIONAL_REPRESENTATION('',(#105457),#105461); -#105457 = LINE('',#105458,#105459); -#105458 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#105459 = VECTOR('',#105460,1.); -#105460 = DIRECTION('',(0.E+000,-1.)); -#105461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105462 = ORIENTED_EDGE('',*,*,#105463,.T.); -#105463 = EDGE_CURVE('',#105436,#105464,#105466,.T.); -#105464 = VERTEX_POINT('',#105465); -#105465 = CARTESIAN_POINT('',(7.85,-1.,-0.208196358798)); -#105466 = SURFACE_CURVE('',#105467,(#105471,#105478),.PCURVE_S1.); -#105467 = LINE('',#105468,#105469); -#105468 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#105469 = VECTOR('',#105470,1.); -#105470 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105471 = PCURVE('',#105444,#105472); -#105472 = DEFINITIONAL_REPRESENTATION('',(#105473),#105477); -#105473 = LINE('',#105474,#105475); -#105474 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#105475 = VECTOR('',#105476,1.); -#105476 = DIRECTION('',(1.,0.E+000)); -#105477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105478 = PCURVE('',#105370,#105479); -#105479 = DEFINITIONAL_REPRESENTATION('',(#105480),#105484); -#105480 = LINE('',#105481,#105482); -#105481 = CARTESIAN_POINT('',(-5.000038352949E-002,2.25)); -#105482 = VECTOR('',#105483,1.); -#105483 = DIRECTION('',(0.E+000,1.)); -#105484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105485 = ORIENTED_EDGE('',*,*,#105486,.F.); -#105486 = EDGE_CURVE('',#105487,#105464,#105489,.T.); -#105487 = VERTEX_POINT('',#105488); -#105488 = CARTESIAN_POINT('',(7.85,-0.740726081328,-0.208196358798)); -#105489 = SURFACE_CURVE('',#105490,(#105494,#105501),.PCURVE_S1.); -#105490 = LINE('',#105491,#105492); -#105491 = CARTESIAN_POINT('',(7.85,-0.740726081328,-0.208196358798)); -#105492 = VECTOR('',#105493,1.); -#105493 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#105494 = PCURVE('',#105444,#105495); -#105495 = DEFINITIONAL_REPRESENTATION('',(#105496),#105500); -#105496 = LINE('',#105497,#105498); -#105497 = CARTESIAN_POINT('',(-2.15,0.E+000)); -#105498 = VECTOR('',#105499,1.); -#105499 = DIRECTION('',(0.E+000,-1.)); -#105500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105501 = PCURVE('',#90177,#105502); -#105502 = DEFINITIONAL_REPRESENTATION('',(#105503),#105507); -#105503 = LINE('',#105504,#105505); -#105504 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#105505 = VECTOR('',#105506,1.); -#105506 = DIRECTION('',(0.E+000,-1.)); -#105507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105508 = ORIENTED_EDGE('',*,*,#105509,.T.); -#105509 = EDGE_CURVE('',#105487,#105434,#105510,.T.); -#105510 = SURFACE_CURVE('',#105511,(#105515,#105522),.PCURVE_S1.); -#105511 = LINE('',#105512,#105513); -#105512 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#105513 = VECTOR('',#105514,1.); -#105514 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105515 = PCURVE('',#105444,#105516); -#105516 = DEFINITIONAL_REPRESENTATION('',(#105517),#105521); -#105517 = LINE('',#105518,#105519); -#105518 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105519 = VECTOR('',#105520,1.); -#105520 = DIRECTION('',(-1.,0.E+000)); -#105521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105522 = PCURVE('',#105523,#105528); -#105523 = CYLINDRICAL_SURFACE('',#105524,0.208574704164); -#105524 = AXIS2_PLACEMENT_3D('',#105525,#105526,#105527); -#105525 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#105526 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105527 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105528 = DEFINITIONAL_REPRESENTATION('',(#105529),#105532); -#105529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105530,#105531), +#107818 = CARTESIAN_POINT('',(3.191025391152,2.35)); +#107819 = CARTESIAN_POINT('',(3.191025391152,2.15)); +#107820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107821 = ADVANCED_FACE('',(#107822),#107836,.T.); +#107822 = FACE_BOUND('',#107823,.T.); +#107823 = EDGE_LOOP('',(#107824,#107854,#107877,#107900)); +#107824 = ORIENTED_EDGE('',*,*,#107825,.T.); +#107825 = EDGE_CURVE('',#107826,#107828,#107830,.T.); +#107826 = VERTEX_POINT('',#107827); +#107827 = CARTESIAN_POINT('',(7.65,-0.740726081328,-0.208196358798)); +#107828 = VERTEX_POINT('',#107829); +#107829 = CARTESIAN_POINT('',(7.65,-1.,-0.208196358798)); +#107830 = SURFACE_CURVE('',#107831,(#107835,#107847),.PCURVE_S1.); +#107831 = LINE('',#107832,#107833); +#107832 = CARTESIAN_POINT('',(7.65,-0.740726081328,-0.208196358798)); +#107833 = VECTOR('',#107834,1.); +#107834 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#107835 = PCURVE('',#107836,#107841); +#107836 = PLANE('',#107837); +#107837 = AXIS2_PLACEMENT_3D('',#107838,#107839,#107840); +#107838 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#107839 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107840 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107841 = DEFINITIONAL_REPRESENTATION('',(#107842),#107846); +#107842 = LINE('',#107843,#107844); +#107843 = CARTESIAN_POINT('',(-2.35,0.E+000)); +#107844 = VECTOR('',#107845,1.); +#107845 = DIRECTION('',(0.E+000,-1.)); +#107846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107847 = PCURVE('',#92513,#107848); +#107848 = DEFINITIONAL_REPRESENTATION('',(#107849),#107853); +#107849 = LINE('',#107850,#107851); +#107850 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#107851 = VECTOR('',#107852,1.); +#107852 = DIRECTION('',(0.E+000,-1.)); +#107853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107854 = ORIENTED_EDGE('',*,*,#107855,.T.); +#107855 = EDGE_CURVE('',#107828,#107856,#107858,.T.); +#107856 = VERTEX_POINT('',#107857); +#107857 = CARTESIAN_POINT('',(7.85,-1.,-0.208196358798)); +#107858 = SURFACE_CURVE('',#107859,(#107863,#107870),.PCURVE_S1.); +#107859 = LINE('',#107860,#107861); +#107860 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#107861 = VECTOR('',#107862,1.); +#107862 = DIRECTION('',(1.,0.E+000,0.E+000)); +#107863 = PCURVE('',#107836,#107864); +#107864 = DEFINITIONAL_REPRESENTATION('',(#107865),#107869); +#107865 = LINE('',#107866,#107867); +#107866 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#107867 = VECTOR('',#107868,1.); +#107868 = DIRECTION('',(1.,0.E+000)); +#107869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107870 = PCURVE('',#107762,#107871); +#107871 = DEFINITIONAL_REPRESENTATION('',(#107872),#107876); +#107872 = LINE('',#107873,#107874); +#107873 = CARTESIAN_POINT('',(-5.000038352949E-002,2.25)); +#107874 = VECTOR('',#107875,1.); +#107875 = DIRECTION('',(0.E+000,1.)); +#107876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107877 = ORIENTED_EDGE('',*,*,#107878,.F.); +#107878 = EDGE_CURVE('',#107879,#107856,#107881,.T.); +#107879 = VERTEX_POINT('',#107880); +#107880 = CARTESIAN_POINT('',(7.85,-0.740726081328,-0.208196358798)); +#107881 = SURFACE_CURVE('',#107882,(#107886,#107893),.PCURVE_S1.); +#107882 = LINE('',#107883,#107884); +#107883 = CARTESIAN_POINT('',(7.85,-0.740726081328,-0.208196358798)); +#107884 = VECTOR('',#107885,1.); +#107885 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#107886 = PCURVE('',#107836,#107887); +#107887 = DEFINITIONAL_REPRESENTATION('',(#107888),#107892); +#107888 = LINE('',#107889,#107890); +#107889 = CARTESIAN_POINT('',(-2.15,0.E+000)); +#107890 = VECTOR('',#107891,1.); +#107891 = DIRECTION('',(0.E+000,-1.)); +#107892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107893 = PCURVE('',#92569,#107894); +#107894 = DEFINITIONAL_REPRESENTATION('',(#107895),#107899); +#107895 = LINE('',#107896,#107897); +#107896 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#107897 = VECTOR('',#107898,1.); +#107898 = DIRECTION('',(0.E+000,-1.)); +#107899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107900 = ORIENTED_EDGE('',*,*,#107901,.T.); +#107901 = EDGE_CURVE('',#107879,#107826,#107902,.T.); +#107902 = SURFACE_CURVE('',#107903,(#107907,#107914),.PCURVE_S1.); +#107903 = LINE('',#107904,#107905); +#107904 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#107905 = VECTOR('',#107906,1.); +#107906 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107907 = PCURVE('',#107836,#107908); +#107908 = DEFINITIONAL_REPRESENTATION('',(#107909),#107913); +#107909 = LINE('',#107910,#107911); +#107910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#107911 = VECTOR('',#107912,1.); +#107912 = DIRECTION('',(-1.,0.E+000)); +#107913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107914 = PCURVE('',#107915,#107920); +#107915 = CYLINDRICAL_SURFACE('',#107916,0.208574704164); +#107916 = AXIS2_PLACEMENT_3D('',#107917,#107918,#107919); +#107917 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#107918 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107919 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107920 = DEFINITIONAL_REPRESENTATION('',(#107921),#107924); +#107921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107922,#107923), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#105530 = CARTESIAN_POINT('',(3.201833915432,2.15)); -#105531 = CARTESIAN_POINT('',(3.201833915432,2.35)); -#105532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105533 = ADVANCED_FACE('',(#105534),#105419,.T.); -#105534 = FACE_BOUND('',#105535,.T.); -#105535 = EDGE_LOOP('',(#105536,#105537,#105564,#105591)); -#105536 = ORIENTED_EDGE('',*,*,#105405,.F.); -#105537 = ORIENTED_EDGE('',*,*,#105538,.F.); -#105538 = EDGE_CURVE('',#105539,#105383,#105541,.T.); -#105539 = VERTEX_POINT('',#105540); -#105540 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.E+000)); -#105541 = SURFACE_CURVE('',#105542,(#105547,#105553),.PCURVE_S1.); -#105542 = CIRCLE('',#105543,0.308574064194); -#105543 = AXIS2_PLACEMENT_3D('',#105544,#105545,#105546); -#105544 = CARTESIAN_POINT('',(7.65,-0.728168876214,2.640924866458E-017) - ); -#105545 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105546 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105547 = PCURVE('',#105419,#105548); -#105548 = DEFINITIONAL_REPRESENTATION('',(#105549),#105552); -#105549 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105550,#105551), +#107922 = CARTESIAN_POINT('',(3.201833915432,2.15)); +#107923 = CARTESIAN_POINT('',(3.201833915432,2.35)); +#107924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107925 = ADVANCED_FACE('',(#107926),#107811,.T.); +#107926 = FACE_BOUND('',#107927,.T.); +#107927 = EDGE_LOOP('',(#107928,#107929,#107956,#107983)); +#107928 = ORIENTED_EDGE('',*,*,#107797,.F.); +#107929 = ORIENTED_EDGE('',*,*,#107930,.F.); +#107930 = EDGE_CURVE('',#107931,#107775,#107933,.T.); +#107931 = VERTEX_POINT('',#107932); +#107932 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.E+000)); +#107933 = SURFACE_CURVE('',#107934,(#107939,#107945),.PCURVE_S1.); +#107934 = CIRCLE('',#107935,0.308574064194); +#107935 = AXIS2_PLACEMENT_3D('',#107936,#107937,#107938); +#107936 = CARTESIAN_POINT('',(7.65,-0.728168876214,2.640924866458E-017) + ); +#107937 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107938 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107939 = PCURVE('',#107811,#107940); +#107940 = DEFINITIONAL_REPRESENTATION('',(#107941),#107944); +#107941 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107942,#107943), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#105550 = CARTESIAN_POINT('',(1.570796326795,2.35)); -#105551 = CARTESIAN_POINT('',(3.191025391152,2.35)); -#105552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#107942 = CARTESIAN_POINT('',(1.570796326795,2.35)); +#107943 = CARTESIAN_POINT('',(3.191025391152,2.35)); +#107944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105553 = PCURVE('',#90121,#105554); -#105554 = DEFINITIONAL_REPRESENTATION('',(#105555),#105563); -#105555 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105556,#105557,#105558, - #105559,#105560,#105561,#105562),.UNSPECIFIED.,.T.,.F.) +#107945 = PCURVE('',#92513,#107946); +#107946 = DEFINITIONAL_REPRESENTATION('',(#107947),#107955); +#107947 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107948,#107949,#107950, + #107951,#107952,#107953,#107954),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#105556 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#105557 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#105558 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#105559 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#105560 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#105561 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#105562 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#105563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105564 = ORIENTED_EDGE('',*,*,#105565,.F.); -#105565 = EDGE_CURVE('',#105566,#105539,#105568,.T.); -#105566 = VERTEX_POINT('',#105567); -#105567 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.E+000)); -#105568 = SURFACE_CURVE('',#105569,(#105573,#105579),.PCURVE_S1.); -#105569 = LINE('',#105570,#105571); -#105570 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#105571 = VECTOR('',#105572,1.); -#105572 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105573 = PCURVE('',#105419,#105574); -#105574 = DEFINITIONAL_REPRESENTATION('',(#105575),#105578); -#105575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105576,#105577), +#107948 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#107949 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#107950 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#107951 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#107952 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#107953 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#107954 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#107955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107956 = ORIENTED_EDGE('',*,*,#107957,.F.); +#107957 = EDGE_CURVE('',#107958,#107931,#107960,.T.); +#107958 = VERTEX_POINT('',#107959); +#107959 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.E+000)); +#107960 = SURFACE_CURVE('',#107961,(#107965,#107971),.PCURVE_S1.); +#107961 = LINE('',#107962,#107963); +#107962 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#107963 = VECTOR('',#107964,1.); +#107964 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107965 = PCURVE('',#107811,#107966); +#107966 = DEFINITIONAL_REPRESENTATION('',(#107967),#107970); +#107967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107968,#107969), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#105576 = CARTESIAN_POINT('',(1.570796326795,2.15)); -#105577 = CARTESIAN_POINT('',(1.570796326795,2.35)); -#105578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105579 = PCURVE('',#105580,#105585); -#105580 = PLANE('',#105581); -#105581 = AXIS2_PLACEMENT_3D('',#105582,#105583,#105584); -#105582 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#105583 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#105584 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#105585 = DEFINITIONAL_REPRESENTATION('',(#105586),#105590); -#105586 = LINE('',#105587,#105588); -#105587 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#105588 = VECTOR('',#105589,1.); -#105589 = DIRECTION('',(0.E+000,-1.)); -#105590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105591 = ORIENTED_EDGE('',*,*,#105592,.T.); -#105592 = EDGE_CURVE('',#105566,#105325,#105593,.T.); -#105593 = SURFACE_CURVE('',#105594,(#105599,#105605),.PCURVE_S1.); -#105594 = CIRCLE('',#105595,0.308574064194); -#105595 = AXIS2_PLACEMENT_3D('',#105596,#105597,#105598); -#105596 = CARTESIAN_POINT('',(7.85,-0.728168876214,2.640924866458E-017) - ); -#105597 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105598 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105599 = PCURVE('',#105419,#105600); -#105600 = DEFINITIONAL_REPRESENTATION('',(#105601),#105604); -#105601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105602,#105603), +#107968 = CARTESIAN_POINT('',(1.570796326795,2.15)); +#107969 = CARTESIAN_POINT('',(1.570796326795,2.35)); +#107970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107971 = PCURVE('',#107972,#107977); +#107972 = PLANE('',#107973); +#107973 = AXIS2_PLACEMENT_3D('',#107974,#107975,#107976); +#107974 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#107975 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#107976 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#107977 = DEFINITIONAL_REPRESENTATION('',(#107978),#107982); +#107978 = LINE('',#107979,#107980); +#107979 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#107980 = VECTOR('',#107981,1.); +#107981 = DIRECTION('',(0.E+000,-1.)); +#107982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107983 = ORIENTED_EDGE('',*,*,#107984,.T.); +#107984 = EDGE_CURVE('',#107958,#107717,#107985,.T.); +#107985 = SURFACE_CURVE('',#107986,(#107991,#107997),.PCURVE_S1.); +#107986 = CIRCLE('',#107987,0.308574064194); +#107987 = AXIS2_PLACEMENT_3D('',#107988,#107989,#107990); +#107988 = CARTESIAN_POINT('',(7.85,-0.728168876214,2.640924866458E-017) + ); +#107989 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#107990 = DIRECTION('',(0.E+000,0.E+000,1.)); +#107991 = PCURVE('',#107811,#107992); +#107992 = DEFINITIONAL_REPRESENTATION('',(#107993),#107996); +#107993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107994,#107995), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#105602 = CARTESIAN_POINT('',(1.570796326795,2.15)); -#105603 = CARTESIAN_POINT('',(3.191025391152,2.15)); -#105604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105605 = PCURVE('',#90177,#105606); -#105606 = DEFINITIONAL_REPRESENTATION('',(#105607),#105611); -#105607 = CIRCLE('',#105608,0.308574064194); -#105608 = AXIS2_PLACEMENT_2D('',#105609,#105610); -#105609 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#105610 = DIRECTION('',(1.,0.E+000)); -#105611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105612 = ADVANCED_FACE('',(#105613),#105523,.F.); -#105613 = FACE_BOUND('',#105614,.F.); -#105614 = EDGE_LOOP('',(#105615,#105616,#105643,#105670)); -#105615 = ORIENTED_EDGE('',*,*,#105509,.T.); -#105616 = ORIENTED_EDGE('',*,*,#105617,.F.); -#105617 = EDGE_CURVE('',#105618,#105434,#105620,.T.); -#105618 = VERTEX_POINT('',#105619); -#105619 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.E+000)); -#105620 = SURFACE_CURVE('',#105621,(#105626,#105632),.PCURVE_S1.); -#105621 = CIRCLE('',#105622,0.208574704164); -#105622 = AXIS2_PLACEMENT_3D('',#105623,#105624,#105625); -#105623 = CARTESIAN_POINT('',(7.65,-0.728168876214,2.640924866458E-017) - ); -#105624 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105625 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105626 = PCURVE('',#105523,#105627); -#105627 = DEFINITIONAL_REPRESENTATION('',(#105628),#105631); -#105628 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105629,#105630), +#107994 = CARTESIAN_POINT('',(1.570796326795,2.15)); +#107995 = CARTESIAN_POINT('',(3.191025391152,2.15)); +#107996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#107997 = PCURVE('',#92569,#107998); +#107998 = DEFINITIONAL_REPRESENTATION('',(#107999),#108003); +#107999 = CIRCLE('',#108000,0.308574064194); +#108000 = AXIS2_PLACEMENT_2D('',#108001,#108002); +#108001 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#108002 = DIRECTION('',(1.,0.E+000)); +#108003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108004 = ADVANCED_FACE('',(#108005),#107915,.F.); +#108005 = FACE_BOUND('',#108006,.F.); +#108006 = EDGE_LOOP('',(#108007,#108008,#108035,#108062)); +#108007 = ORIENTED_EDGE('',*,*,#107901,.T.); +#108008 = ORIENTED_EDGE('',*,*,#108009,.F.); +#108009 = EDGE_CURVE('',#108010,#107826,#108012,.T.); +#108010 = VERTEX_POINT('',#108011); +#108011 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.E+000)); +#108012 = SURFACE_CURVE('',#108013,(#108018,#108024),.PCURVE_S1.); +#108013 = CIRCLE('',#108014,0.208574704164); +#108014 = AXIS2_PLACEMENT_3D('',#108015,#108016,#108017); +#108015 = CARTESIAN_POINT('',(7.65,-0.728168876214,2.640924866458E-017) + ); +#108016 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108017 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108018 = PCURVE('',#107915,#108019); +#108019 = DEFINITIONAL_REPRESENTATION('',(#108020),#108023); +#108020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108021,#108022), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#105629 = CARTESIAN_POINT('',(1.570796326795,2.35)); -#105630 = CARTESIAN_POINT('',(3.201833915432,2.35)); -#105631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108021 = CARTESIAN_POINT('',(1.570796326795,2.35)); +#108022 = CARTESIAN_POINT('',(3.201833915432,2.35)); +#108023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105632 = PCURVE('',#90121,#105633); -#105633 = DEFINITIONAL_REPRESENTATION('',(#105634),#105642); -#105634 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105635,#105636,#105637, - #105638,#105639,#105640,#105641),.UNSPECIFIED.,.F.,.F.) +#108024 = PCURVE('',#92513,#108025); +#108025 = DEFINITIONAL_REPRESENTATION('',(#108026),#108034); +#108026 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108027,#108028,#108029, + #108030,#108031,#108032,#108033),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#105635 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#105636 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#105637 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#105638 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#105639 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#105640 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#105641 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#105642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105643 = ORIENTED_EDGE('',*,*,#105644,.T.); -#105644 = EDGE_CURVE('',#105618,#105645,#105647,.T.); -#105645 = VERTEX_POINT('',#105646); -#105646 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.E+000)); -#105647 = SURFACE_CURVE('',#105648,(#105652,#105658),.PCURVE_S1.); -#105648 = LINE('',#105649,#105650); -#105649 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#105650 = VECTOR('',#105651,1.); -#105651 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105652 = PCURVE('',#105523,#105653); -#105653 = DEFINITIONAL_REPRESENTATION('',(#105654),#105657); -#105654 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105655,#105656), +#108027 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#108028 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#108029 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#108030 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#108031 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#108032 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#108033 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#108034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108035 = ORIENTED_EDGE('',*,*,#108036,.T.); +#108036 = EDGE_CURVE('',#108010,#108037,#108039,.T.); +#108037 = VERTEX_POINT('',#108038); +#108038 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.E+000)); +#108039 = SURFACE_CURVE('',#108040,(#108044,#108050),.PCURVE_S1.); +#108040 = LINE('',#108041,#108042); +#108041 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#108042 = VECTOR('',#108043,1.); +#108043 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108044 = PCURVE('',#107915,#108045); +#108045 = DEFINITIONAL_REPRESENTATION('',(#108046),#108049); +#108046 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108047,#108048), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#105655 = CARTESIAN_POINT('',(1.570796326795,2.35)); -#105656 = CARTESIAN_POINT('',(1.570796326795,2.15)); -#105657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105658 = PCURVE('',#105659,#105664); -#105659 = PLANE('',#105660); -#105660 = AXIS2_PLACEMENT_3D('',#105661,#105662,#105663); -#105661 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#105662 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#105663 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#105664 = DEFINITIONAL_REPRESENTATION('',(#105665),#105669); -#105665 = LINE('',#105666,#105667); -#105666 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#105667 = VECTOR('',#105668,1.); -#105668 = DIRECTION('',(0.E+000,1.)); -#105669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105670 = ORIENTED_EDGE('',*,*,#105671,.T.); -#105671 = EDGE_CURVE('',#105645,#105487,#105672,.T.); -#105672 = SURFACE_CURVE('',#105673,(#105678,#105684),.PCURVE_S1.); -#105673 = CIRCLE('',#105674,0.208574704164); -#105674 = AXIS2_PLACEMENT_3D('',#105675,#105676,#105677); -#105675 = CARTESIAN_POINT('',(7.85,-0.728168876214,2.640924866458E-017) - ); -#105676 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105677 = DIRECTION('',(0.E+000,0.E+000,1.)); -#105678 = PCURVE('',#105523,#105679); -#105679 = DEFINITIONAL_REPRESENTATION('',(#105680),#105683); -#105680 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105681,#105682), +#108047 = CARTESIAN_POINT('',(1.570796326795,2.35)); +#108048 = CARTESIAN_POINT('',(1.570796326795,2.15)); +#108049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108050 = PCURVE('',#108051,#108056); +#108051 = PLANE('',#108052); +#108052 = AXIS2_PLACEMENT_3D('',#108053,#108054,#108055); +#108053 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#108054 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#108055 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#108056 = DEFINITIONAL_REPRESENTATION('',(#108057),#108061); +#108057 = LINE('',#108058,#108059); +#108058 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#108059 = VECTOR('',#108060,1.); +#108060 = DIRECTION('',(0.E+000,1.)); +#108061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108062 = ORIENTED_EDGE('',*,*,#108063,.T.); +#108063 = EDGE_CURVE('',#108037,#107879,#108064,.T.); +#108064 = SURFACE_CURVE('',#108065,(#108070,#108076),.PCURVE_S1.); +#108065 = CIRCLE('',#108066,0.208574704164); +#108066 = AXIS2_PLACEMENT_3D('',#108067,#108068,#108069); +#108067 = CARTESIAN_POINT('',(7.85,-0.728168876214,2.640924866458E-017) + ); +#108068 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108069 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108070 = PCURVE('',#107915,#108071); +#108071 = DEFINITIONAL_REPRESENTATION('',(#108072),#108075); +#108072 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108073,#108074), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#105681 = CARTESIAN_POINT('',(1.570796326795,2.15)); -#105682 = CARTESIAN_POINT('',(3.201833915432,2.15)); -#105683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108073 = CARTESIAN_POINT('',(1.570796326795,2.15)); +#108074 = CARTESIAN_POINT('',(3.201833915432,2.15)); +#108075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105684 = PCURVE('',#90177,#105685); -#105685 = DEFINITIONAL_REPRESENTATION('',(#105686),#105690); -#105686 = CIRCLE('',#105687,0.208574704164); -#105687 = AXIS2_PLACEMENT_2D('',#105688,#105689); -#105688 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#105689 = DIRECTION('',(1.,0.E+000)); -#105690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108076 = PCURVE('',#92569,#108077); +#108077 = DEFINITIONAL_REPRESENTATION('',(#108078),#108082); +#108078 = CIRCLE('',#108079,0.208574704164); +#108079 = AXIS2_PLACEMENT_2D('',#108080,#108081); +#108080 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#108081 = DIRECTION('',(1.,0.E+000)); +#108082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105691 = ADVANCED_FACE('',(#105692),#105659,.F.); -#105692 = FACE_BOUND('',#105693,.T.); -#105693 = EDGE_LOOP('',(#105694,#105723,#105744,#105745)); -#105694 = ORIENTED_EDGE('',*,*,#105695,.F.); -#105695 = EDGE_CURVE('',#105696,#105698,#105700,.T.); -#105696 = VERTEX_POINT('',#105697); -#105697 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.530776333563)); -#105698 = VERTEX_POINT('',#105699); -#105699 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.530776333563)); -#105700 = SURFACE_CURVE('',#105701,(#105705,#105712),.PCURVE_S1.); -#105701 = LINE('',#105702,#105703); -#105702 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#105703 = VECTOR('',#105704,1.); -#105704 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105705 = PCURVE('',#105659,#105706); -#105706 = DEFINITIONAL_REPRESENTATION('',(#105707),#105711); -#105707 = LINE('',#105708,#105709); -#105708 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105709 = VECTOR('',#105710,1.); -#105710 = DIRECTION('',(0.E+000,1.)); -#105711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105712 = PCURVE('',#105713,#105718); -#105713 = CYLINDRICAL_SURFACE('',#105714,0.2192697516); -#105714 = AXIS2_PLACEMENT_3D('',#105715,#105716,#105717); -#105715 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#105716 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105717 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105718 = DEFINITIONAL_REPRESENTATION('',(#105719),#105722); -#105719 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105720,#105721), +#108083 = ADVANCED_FACE('',(#108084),#108051,.F.); +#108084 = FACE_BOUND('',#108085,.T.); +#108085 = EDGE_LOOP('',(#108086,#108115,#108136,#108137)); +#108086 = ORIENTED_EDGE('',*,*,#108087,.F.); +#108087 = EDGE_CURVE('',#108088,#108090,#108092,.T.); +#108088 = VERTEX_POINT('',#108089); +#108089 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.530776333563)); +#108090 = VERTEX_POINT('',#108091); +#108091 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.530776333563)); +#108092 = SURFACE_CURVE('',#108093,(#108097,#108104),.PCURVE_S1.); +#108093 = LINE('',#108094,#108095); +#108094 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#108095 = VECTOR('',#108096,1.); +#108096 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108097 = PCURVE('',#108051,#108098); +#108098 = DEFINITIONAL_REPRESENTATION('',(#108099),#108103); +#108099 = LINE('',#108100,#108101); +#108100 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108101 = VECTOR('',#108102,1.); +#108102 = DIRECTION('',(0.E+000,1.)); +#108103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108104 = PCURVE('',#108105,#108110); +#108105 = CYLINDRICAL_SURFACE('',#108106,0.2192697516); +#108106 = AXIS2_PLACEMENT_3D('',#108107,#108108,#108109); +#108107 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#108108 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108109 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108110 = DEFINITIONAL_REPRESENTATION('',(#108111),#108114); +#108111 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108112,#108113), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#105720 = CARTESIAN_POINT('',(4.712388980385,-2.35)); -#105721 = CARTESIAN_POINT('',(4.712388980385,-2.15)); -#105722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105723 = ORIENTED_EDGE('',*,*,#105724,.T.); -#105724 = EDGE_CURVE('',#105696,#105618,#105725,.T.); -#105725 = SURFACE_CURVE('',#105726,(#105730,#105737),.PCURVE_S1.); -#105726 = LINE('',#105727,#105728); -#105727 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.530776333563)); -#105728 = VECTOR('',#105729,1.); -#105729 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#105730 = PCURVE('',#105659,#105731); -#105731 = DEFINITIONAL_REPRESENTATION('',(#105732),#105736); -#105732 = LINE('',#105733,#105734); -#105733 = CARTESIAN_POINT('',(0.E+000,-2.35)); -#105734 = VECTOR('',#105735,1.); -#105735 = DIRECTION('',(-1.,0.E+000)); -#105736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105737 = PCURVE('',#90121,#105738); -#105738 = DEFINITIONAL_REPRESENTATION('',(#105739),#105743); -#105739 = LINE('',#105740,#105741); -#105740 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#105741 = VECTOR('',#105742,1.); -#105742 = DIRECTION('',(1.,-1.021336205033E-016)); -#105743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105744 = ORIENTED_EDGE('',*,*,#105644,.T.); -#105745 = ORIENTED_EDGE('',*,*,#105746,.F.); -#105746 = EDGE_CURVE('',#105698,#105645,#105747,.T.); -#105747 = SURFACE_CURVE('',#105748,(#105752,#105759),.PCURVE_S1.); -#105748 = LINE('',#105749,#105750); -#105749 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.530776333563)); -#105750 = VECTOR('',#105751,1.); -#105751 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#105752 = PCURVE('',#105659,#105753); -#105753 = DEFINITIONAL_REPRESENTATION('',(#105754),#105758); -#105754 = LINE('',#105755,#105756); -#105755 = CARTESIAN_POINT('',(0.E+000,-2.15)); -#105756 = VECTOR('',#105757,1.); -#105757 = DIRECTION('',(-1.,0.E+000)); -#105758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105759 = PCURVE('',#90177,#105760); -#105760 = DEFINITIONAL_REPRESENTATION('',(#105761),#105765); -#105761 = LINE('',#105762,#105763); -#105762 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#105763 = VECTOR('',#105764,1.); -#105764 = DIRECTION('',(-1.,-1.021336205033E-016)); -#105765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105766 = ADVANCED_FACE('',(#105767),#105580,.F.); -#105767 = FACE_BOUND('',#105768,.T.); -#105768 = EDGE_LOOP('',(#105769,#105798,#105819,#105820)); -#105769 = ORIENTED_EDGE('',*,*,#105770,.F.); -#105770 = EDGE_CURVE('',#105771,#105773,#105775,.T.); -#105771 = VERTEX_POINT('',#105772); -#105772 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.530776333563)); -#105773 = VERTEX_POINT('',#105774); -#105774 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.530776333563)); -#105775 = SURFACE_CURVE('',#105776,(#105780,#105787),.PCURVE_S1.); -#105776 = LINE('',#105777,#105778); -#105777 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#105778 = VECTOR('',#105779,1.); -#105779 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105780 = PCURVE('',#105580,#105781); -#105781 = DEFINITIONAL_REPRESENTATION('',(#105782),#105786); -#105782 = LINE('',#105783,#105784); -#105783 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#105784 = VECTOR('',#105785,1.); -#105785 = DIRECTION('',(0.E+000,-1.)); -#105786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108112 = CARTESIAN_POINT('',(4.712388980385,-2.35)); +#108113 = CARTESIAN_POINT('',(4.712388980385,-2.15)); +#108114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108115 = ORIENTED_EDGE('',*,*,#108116,.T.); +#108116 = EDGE_CURVE('',#108088,#108010,#108117,.T.); +#108117 = SURFACE_CURVE('',#108118,(#108122,#108129),.PCURVE_S1.); +#108118 = LINE('',#108119,#108120); +#108119 = CARTESIAN_POINT('',(7.65,-0.51959417205,0.530776333563)); +#108120 = VECTOR('',#108121,1.); +#108121 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108122 = PCURVE('',#108051,#108123); +#108123 = DEFINITIONAL_REPRESENTATION('',(#108124),#108128); +#108124 = LINE('',#108125,#108126); +#108125 = CARTESIAN_POINT('',(0.E+000,-2.35)); +#108126 = VECTOR('',#108127,1.); +#108127 = DIRECTION('',(-1.,0.E+000)); +#108128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108129 = PCURVE('',#92513,#108130); +#108130 = DEFINITIONAL_REPRESENTATION('',(#108131),#108135); +#108131 = LINE('',#108132,#108133); +#108132 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#108133 = VECTOR('',#108134,1.); +#108134 = DIRECTION('',(1.,-1.021336205033E-016)); +#108135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108136 = ORIENTED_EDGE('',*,*,#108036,.T.); +#108137 = ORIENTED_EDGE('',*,*,#108138,.F.); +#108138 = EDGE_CURVE('',#108090,#108037,#108139,.T.); +#108139 = SURFACE_CURVE('',#108140,(#108144,#108151),.PCURVE_S1.); +#108140 = LINE('',#108141,#108142); +#108141 = CARTESIAN_POINT('',(7.85,-0.51959417205,0.530776333563)); +#108142 = VECTOR('',#108143,1.); +#108143 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108144 = PCURVE('',#108051,#108145); +#108145 = DEFINITIONAL_REPRESENTATION('',(#108146),#108150); +#108146 = LINE('',#108147,#108148); +#108147 = CARTESIAN_POINT('',(0.E+000,-2.15)); +#108148 = VECTOR('',#108149,1.); +#108149 = DIRECTION('',(-1.,0.E+000)); +#108150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108151 = PCURVE('',#92569,#108152); +#108152 = DEFINITIONAL_REPRESENTATION('',(#108153),#108157); +#108153 = LINE('',#108154,#108155); +#108154 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#108155 = VECTOR('',#108156,1.); +#108156 = DIRECTION('',(-1.,-1.021336205033E-016)); +#108157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105787 = PCURVE('',#105788,#105793); -#105788 = CYLINDRICAL_SURFACE('',#105789,0.119270391569); -#105789 = AXIS2_PLACEMENT_3D('',#105790,#105791,#105792); -#105790 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#105791 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105792 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105793 = DEFINITIONAL_REPRESENTATION('',(#105794),#105797); -#105794 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105795,#105796), +#108158 = ADVANCED_FACE('',(#108159),#107972,.F.); +#108159 = FACE_BOUND('',#108160,.T.); +#108160 = EDGE_LOOP('',(#108161,#108190,#108211,#108212)); +#108161 = ORIENTED_EDGE('',*,*,#108162,.F.); +#108162 = EDGE_CURVE('',#108163,#108165,#108167,.T.); +#108163 = VERTEX_POINT('',#108164); +#108164 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.530776333563)); +#108165 = VERTEX_POINT('',#108166); +#108166 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.530776333563)); +#108167 = SURFACE_CURVE('',#108168,(#108172,#108179),.PCURVE_S1.); +#108168 = LINE('',#108169,#108170); +#108169 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#108170 = VECTOR('',#108171,1.); +#108171 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108172 = PCURVE('',#107972,#108173); +#108173 = DEFINITIONAL_REPRESENTATION('',(#108174),#108178); +#108174 = LINE('',#108175,#108176); +#108175 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108176 = VECTOR('',#108177,1.); +#108177 = DIRECTION('',(0.E+000,-1.)); +#108178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108179 = PCURVE('',#108180,#108185); +#108180 = CYLINDRICAL_SURFACE('',#108181,0.119270391569); +#108181 = AXIS2_PLACEMENT_3D('',#108182,#108183,#108184); +#108182 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#108183 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108184 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108185 = DEFINITIONAL_REPRESENTATION('',(#108186),#108189); +#108186 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108187,#108188), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#105795 = CARTESIAN_POINT('',(4.712388980385,-2.15)); -#105796 = CARTESIAN_POINT('',(4.712388980385,-2.35)); -#105797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105798 = ORIENTED_EDGE('',*,*,#105799,.T.); -#105799 = EDGE_CURVE('',#105771,#105566,#105800,.T.); -#105800 = SURFACE_CURVE('',#105801,(#105805,#105812),.PCURVE_S1.); -#105801 = LINE('',#105802,#105803); -#105802 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.530776333563)); -#105803 = VECTOR('',#105804,1.); -#105804 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#105805 = PCURVE('',#105580,#105806); -#105806 = DEFINITIONAL_REPRESENTATION('',(#105807),#105811); -#105807 = LINE('',#105808,#105809); -#105808 = CARTESIAN_POINT('',(0.E+000,-2.15)); -#105809 = VECTOR('',#105810,1.); -#105810 = DIRECTION('',(1.,0.E+000)); -#105811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105812 = PCURVE('',#90177,#105813); -#105813 = DEFINITIONAL_REPRESENTATION('',(#105814),#105818); -#105814 = LINE('',#105815,#105816); -#105815 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#105816 = VECTOR('',#105817,1.); -#105817 = DIRECTION('',(-1.,-1.021336205033E-016)); -#105818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105819 = ORIENTED_EDGE('',*,*,#105565,.T.); -#105820 = ORIENTED_EDGE('',*,*,#105821,.F.); -#105821 = EDGE_CURVE('',#105773,#105539,#105822,.T.); -#105822 = SURFACE_CURVE('',#105823,(#105827,#105834),.PCURVE_S1.); -#105823 = LINE('',#105824,#105825); -#105824 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.530776333563)); -#105825 = VECTOR('',#105826,1.); -#105826 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#105827 = PCURVE('',#105580,#105828); -#105828 = DEFINITIONAL_REPRESENTATION('',(#105829),#105833); -#105829 = LINE('',#105830,#105831); -#105830 = CARTESIAN_POINT('',(0.E+000,-2.35)); -#105831 = VECTOR('',#105832,1.); -#105832 = DIRECTION('',(1.,0.E+000)); -#105833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105834 = PCURVE('',#90121,#105835); -#105835 = DEFINITIONAL_REPRESENTATION('',(#105836),#105840); -#105836 = LINE('',#105837,#105838); -#105837 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#105838 = VECTOR('',#105839,1.); -#105839 = DIRECTION('',(1.,-1.021336205033E-016)); -#105840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105841 = ADVANCED_FACE('',(#105842),#105713,.T.); -#105842 = FACE_BOUND('',#105843,.T.); -#105843 = EDGE_LOOP('',(#105844,#105867,#105868,#105895)); -#105844 = ORIENTED_EDGE('',*,*,#105845,.T.); -#105845 = EDGE_CURVE('',#105846,#105696,#105848,.T.); -#105846 = VERTEX_POINT('',#105847); -#105847 = CARTESIAN_POINT('',(7.65,-0.304819755875,0.75)); -#105848 = SURFACE_CURVE('',#105849,(#105854,#105860),.PCURVE_S1.); -#105849 = CIRCLE('',#105850,0.2192697516); -#105850 = AXIS2_PLACEMENT_3D('',#105851,#105852,#105853); -#105851 = CARTESIAN_POINT('',(7.65,-0.30032442045,0.530776333563)); -#105852 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105853 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105854 = PCURVE('',#105713,#105855); -#105855 = DEFINITIONAL_REPRESENTATION('',(#105856),#105859); -#105856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105857,#105858), +#108187 = CARTESIAN_POINT('',(4.712388980385,-2.15)); +#108188 = CARTESIAN_POINT('',(4.712388980385,-2.35)); +#108189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108190 = ORIENTED_EDGE('',*,*,#108191,.T.); +#108191 = EDGE_CURVE('',#108163,#107958,#108192,.T.); +#108192 = SURFACE_CURVE('',#108193,(#108197,#108204),.PCURVE_S1.); +#108193 = LINE('',#108194,#108195); +#108194 = CARTESIAN_POINT('',(7.85,-0.419594812019,0.530776333563)); +#108195 = VECTOR('',#108196,1.); +#108196 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108197 = PCURVE('',#107972,#108198); +#108198 = DEFINITIONAL_REPRESENTATION('',(#108199),#108203); +#108199 = LINE('',#108200,#108201); +#108200 = CARTESIAN_POINT('',(0.E+000,-2.15)); +#108201 = VECTOR('',#108202,1.); +#108202 = DIRECTION('',(1.,0.E+000)); +#108203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108204 = PCURVE('',#92569,#108205); +#108205 = DEFINITIONAL_REPRESENTATION('',(#108206),#108210); +#108206 = LINE('',#108207,#108208); +#108207 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#108208 = VECTOR('',#108209,1.); +#108209 = DIRECTION('',(-1.,-1.021336205033E-016)); +#108210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108211 = ORIENTED_EDGE('',*,*,#107957,.T.); +#108212 = ORIENTED_EDGE('',*,*,#108213,.F.); +#108213 = EDGE_CURVE('',#108165,#107931,#108214,.T.); +#108214 = SURFACE_CURVE('',#108215,(#108219,#108226),.PCURVE_S1.); +#108215 = LINE('',#108216,#108217); +#108216 = CARTESIAN_POINT('',(7.65,-0.419594812019,0.530776333563)); +#108217 = VECTOR('',#108218,1.); +#108218 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108219 = PCURVE('',#107972,#108220); +#108220 = DEFINITIONAL_REPRESENTATION('',(#108221),#108225); +#108221 = LINE('',#108222,#108223); +#108222 = CARTESIAN_POINT('',(0.E+000,-2.35)); +#108223 = VECTOR('',#108224,1.); +#108224 = DIRECTION('',(1.,0.E+000)); +#108225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108226 = PCURVE('',#92513,#108227); +#108227 = DEFINITIONAL_REPRESENTATION('',(#108228),#108232); +#108228 = LINE('',#108229,#108230); +#108229 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#108230 = VECTOR('',#108231,1.); +#108231 = DIRECTION('',(1.,-1.021336205033E-016)); +#108232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108233 = ADVANCED_FACE('',(#108234),#108105,.T.); +#108234 = FACE_BOUND('',#108235,.T.); +#108235 = EDGE_LOOP('',(#108236,#108259,#108260,#108287)); +#108236 = ORIENTED_EDGE('',*,*,#108237,.T.); +#108237 = EDGE_CURVE('',#108238,#108088,#108240,.T.); +#108238 = VERTEX_POINT('',#108239); +#108239 = CARTESIAN_POINT('',(7.65,-0.304819755875,0.75)); +#108240 = SURFACE_CURVE('',#108241,(#108246,#108252),.PCURVE_S1.); +#108241 = CIRCLE('',#108242,0.2192697516); +#108242 = AXIS2_PLACEMENT_3D('',#108243,#108244,#108245); +#108243 = CARTESIAN_POINT('',(7.65,-0.30032442045,0.530776333563)); +#108244 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108245 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108246 = PCURVE('',#108105,#108247); +#108247 = DEFINITIONAL_REPRESENTATION('',(#108248),#108251); +#108248 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108249,#108250), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105857 = CARTESIAN_POINT('',(3.162095483347,-2.35)); -#105858 = CARTESIAN_POINT('',(4.712388980385,-2.35)); -#105859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105860 = PCURVE('',#90121,#105861); -#105861 = DEFINITIONAL_REPRESENTATION('',(#105862),#105866); -#105862 = CIRCLE('',#105863,0.2192697516); -#105863 = AXIS2_PLACEMENT_2D('',#105864,#105865); -#105864 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#105865 = DIRECTION('',(1.,0.E+000)); -#105866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105867 = ORIENTED_EDGE('',*,*,#105695,.T.); -#105868 = ORIENTED_EDGE('',*,*,#105869,.F.); -#105869 = EDGE_CURVE('',#105870,#105698,#105872,.T.); -#105870 = VERTEX_POINT('',#105871); -#105871 = CARTESIAN_POINT('',(7.85,-0.304819755875,0.75)); -#105872 = SURFACE_CURVE('',#105873,(#105878,#105884),.PCURVE_S1.); -#105873 = CIRCLE('',#105874,0.2192697516); -#105874 = AXIS2_PLACEMENT_3D('',#105875,#105876,#105877); -#105875 = CARTESIAN_POINT('',(7.85,-0.30032442045,0.530776333563)); -#105876 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105877 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105878 = PCURVE('',#105713,#105879); -#105879 = DEFINITIONAL_REPRESENTATION('',(#105880),#105883); -#105880 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105881,#105882), +#108249 = CARTESIAN_POINT('',(3.162095483347,-2.35)); +#108250 = CARTESIAN_POINT('',(4.712388980385,-2.35)); +#108251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108252 = PCURVE('',#92513,#108253); +#108253 = DEFINITIONAL_REPRESENTATION('',(#108254),#108258); +#108254 = CIRCLE('',#108255,0.2192697516); +#108255 = AXIS2_PLACEMENT_2D('',#108256,#108257); +#108256 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#108257 = DIRECTION('',(1.,0.E+000)); +#108258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108259 = ORIENTED_EDGE('',*,*,#108087,.T.); +#108260 = ORIENTED_EDGE('',*,*,#108261,.F.); +#108261 = EDGE_CURVE('',#108262,#108090,#108264,.T.); +#108262 = VERTEX_POINT('',#108263); +#108263 = CARTESIAN_POINT('',(7.85,-0.304819755875,0.75)); +#108264 = SURFACE_CURVE('',#108265,(#108270,#108276),.PCURVE_S1.); +#108265 = CIRCLE('',#108266,0.2192697516); +#108266 = AXIS2_PLACEMENT_3D('',#108267,#108268,#108269); +#108267 = CARTESIAN_POINT('',(7.85,-0.30032442045,0.530776333563)); +#108268 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108269 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108270 = PCURVE('',#108105,#108271); +#108271 = DEFINITIONAL_REPRESENTATION('',(#108272),#108275); +#108272 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108273,#108274), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105881 = CARTESIAN_POINT('',(3.162095483347,-2.15)); -#105882 = CARTESIAN_POINT('',(4.712388980385,-2.15)); -#105883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108273 = CARTESIAN_POINT('',(3.162095483347,-2.15)); +#108274 = CARTESIAN_POINT('',(4.712388980385,-2.15)); +#108275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105884 = PCURVE('',#90177,#105885); -#105885 = DEFINITIONAL_REPRESENTATION('',(#105886),#105894); -#105886 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105887,#105888,#105889, - #105890,#105891,#105892,#105893),.UNSPECIFIED.,.F.,.F.) +#108276 = PCURVE('',#92569,#108277); +#108277 = DEFINITIONAL_REPRESENTATION('',(#108278),#108286); +#108278 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108279,#108280,#108281, + #108282,#108283,#108284,#108285),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#105887 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#105888 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#105889 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#105890 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#105891 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#105892 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#105893 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#105894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105895 = ORIENTED_EDGE('',*,*,#105896,.T.); -#105896 = EDGE_CURVE('',#105870,#105846,#105897,.T.); -#105897 = SURFACE_CURVE('',#105898,(#105902,#105908),.PCURVE_S1.); -#105898 = LINE('',#105899,#105900); -#105899 = CARTESIAN_POINT('',(7.65,-0.304819755875,0.75)); -#105900 = VECTOR('',#105901,1.); -#105901 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#105902 = PCURVE('',#105713,#105903); -#105903 = DEFINITIONAL_REPRESENTATION('',(#105904),#105907); -#105904 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105905,#105906), +#108279 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#108280 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#108281 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#108282 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#108283 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#108284 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#108285 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#108286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108287 = ORIENTED_EDGE('',*,*,#108288,.T.); +#108288 = EDGE_CURVE('',#108262,#108238,#108289,.T.); +#108289 = SURFACE_CURVE('',#108290,(#108294,#108300),.PCURVE_S1.); +#108290 = LINE('',#108291,#108292); +#108291 = CARTESIAN_POINT('',(7.65,-0.304819755875,0.75)); +#108292 = VECTOR('',#108293,1.); +#108293 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108294 = PCURVE('',#108105,#108295); +#108295 = DEFINITIONAL_REPRESENTATION('',(#108296),#108299); +#108296 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108297,#108298), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#105905 = CARTESIAN_POINT('',(3.162095483347,-2.15)); -#105906 = CARTESIAN_POINT('',(3.162095483347,-2.35)); -#105907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105908 = PCURVE('',#90149,#105909); -#105909 = DEFINITIONAL_REPRESENTATION('',(#105910),#105914); -#105910 = LINE('',#105911,#105912); -#105911 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#105912 = VECTOR('',#105913,1.); -#105913 = DIRECTION('',(0.E+000,-1.)); -#105914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105915 = ADVANCED_FACE('',(#105916),#105788,.F.); -#105916 = FACE_BOUND('',#105917,.F.); -#105917 = EDGE_LOOP('',(#105918,#105945,#105967,#105988)); -#105918 = ORIENTED_EDGE('',*,*,#105919,.F.); -#105919 = EDGE_CURVE('',#105920,#105771,#105922,.T.); -#105920 = VERTEX_POINT('',#105921); -#105921 = CARTESIAN_POINT('',(7.85,-0.303662633502,0.65)); -#105922 = SURFACE_CURVE('',#105923,(#105928,#105934),.PCURVE_S1.); -#105923 = CIRCLE('',#105924,0.119270391569); -#105924 = AXIS2_PLACEMENT_3D('',#105925,#105926,#105927); -#105925 = CARTESIAN_POINT('',(7.85,-0.30032442045,0.530776333563)); -#105926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105927 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105928 = PCURVE('',#105788,#105929); -#105929 = DEFINITIONAL_REPRESENTATION('',(#105930),#105933); -#105930 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105931,#105932), +#108297 = CARTESIAN_POINT('',(3.162095483347,-2.15)); +#108298 = CARTESIAN_POINT('',(3.162095483347,-2.35)); +#108299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108300 = PCURVE('',#92541,#108301); +#108301 = DEFINITIONAL_REPRESENTATION('',(#108302),#108306); +#108302 = LINE('',#108303,#108304); +#108303 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#108304 = VECTOR('',#108305,1.); +#108305 = DIRECTION('',(0.E+000,-1.)); +#108306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108307 = ADVANCED_FACE('',(#108308),#108180,.F.); +#108308 = FACE_BOUND('',#108309,.F.); +#108309 = EDGE_LOOP('',(#108310,#108337,#108359,#108380)); +#108310 = ORIENTED_EDGE('',*,*,#108311,.F.); +#108311 = EDGE_CURVE('',#108312,#108163,#108314,.T.); +#108312 = VERTEX_POINT('',#108313); +#108313 = CARTESIAN_POINT('',(7.85,-0.303662633502,0.65)); +#108314 = SURFACE_CURVE('',#108315,(#108320,#108326),.PCURVE_S1.); +#108315 = CIRCLE('',#108316,0.119270391569); +#108316 = AXIS2_PLACEMENT_3D('',#108317,#108318,#108319); +#108317 = CARTESIAN_POINT('',(7.85,-0.30032442045,0.530776333563)); +#108318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108319 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108320 = PCURVE('',#108180,#108321); +#108321 = DEFINITIONAL_REPRESENTATION('',(#108322),#108325); +#108322 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108323,#108324), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), + .PIECEWISE_BEZIER_KNOTS.); +#108323 = CARTESIAN_POINT('',(3.169584923929,-2.15)); +#108324 = CARTESIAN_POINT('',(4.712388980385,-2.15)); +#108325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108326 = PCURVE('',#92569,#108327); +#108327 = DEFINITIONAL_REPRESENTATION('',(#108328),#108336); +#108328 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108329,#108330,#108331, + #108332,#108333,#108334,#108335),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#108329 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#108330 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#108331 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#108332 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#108333 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#108334 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#108335 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#108336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108337 = ORIENTED_EDGE('',*,*,#108338,.F.); +#108338 = EDGE_CURVE('',#108339,#108312,#108341,.T.); +#108339 = VERTEX_POINT('',#108340); +#108340 = CARTESIAN_POINT('',(7.65,-0.303662633502,0.65)); +#108341 = SURFACE_CURVE('',#108342,(#108346,#108352),.PCURVE_S1.); +#108342 = LINE('',#108343,#108344); +#108343 = CARTESIAN_POINT('',(7.65,-0.303662633502,0.65)); +#108344 = VECTOR('',#108345,1.); +#108345 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108346 = PCURVE('',#108180,#108347); +#108347 = DEFINITIONAL_REPRESENTATION('',(#108348),#108351); +#108348 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108349,#108350), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#108349 = CARTESIAN_POINT('',(3.169584923929,-2.35)); +#108350 = CARTESIAN_POINT('',(3.169584923929,-2.15)); +#108351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108352 = PCURVE('',#92595,#108353); +#108353 = DEFINITIONAL_REPRESENTATION('',(#108354),#108358); +#108354 = LINE('',#108355,#108356); +#108355 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#108356 = VECTOR('',#108357,1.); +#108357 = DIRECTION('',(0.E+000,1.)); +#108358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108359 = ORIENTED_EDGE('',*,*,#108360,.T.); +#108360 = EDGE_CURVE('',#108339,#108165,#108361,.T.); +#108361 = SURFACE_CURVE('',#108362,(#108367,#108373),.PCURVE_S1.); +#108362 = CIRCLE('',#108363,0.119270391569); +#108363 = AXIS2_PLACEMENT_3D('',#108364,#108365,#108366); +#108364 = CARTESIAN_POINT('',(7.65,-0.30032442045,0.530776333563)); +#108365 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108366 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108367 = PCURVE('',#108180,#108368); +#108368 = DEFINITIONAL_REPRESENTATION('',(#108369),#108372); +#108369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108370,#108371), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#105931 = CARTESIAN_POINT('',(3.169584923929,-2.15)); -#105932 = CARTESIAN_POINT('',(4.712388980385,-2.15)); -#105933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108370 = CARTESIAN_POINT('',(3.169584923929,-2.35)); +#108371 = CARTESIAN_POINT('',(4.712388980385,-2.35)); +#108372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108373 = PCURVE('',#92513,#108374); +#108374 = DEFINITIONAL_REPRESENTATION('',(#108375),#108379); +#108375 = CIRCLE('',#108376,0.119270391569); +#108376 = AXIS2_PLACEMENT_2D('',#108377,#108378); +#108377 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#108378 = DIRECTION('',(1.,0.E+000)); +#108379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108380 = ORIENTED_EDGE('',*,*,#108162,.F.); +#108381 = ADVANCED_FACE('',(#108382),#92513,.F.); +#108382 = FACE_BOUND('',#108383,.T.); +#108383 = EDGE_LOOP('',(#108384,#108405,#108406,#108407,#108408,#108409, + #108430,#108431,#108432,#108433,#108434,#108455)); +#108384 = ORIENTED_EDGE('',*,*,#108385,.F.); +#108385 = EDGE_CURVE('',#108339,#92498,#108386,.T.); +#108386 = SURFACE_CURVE('',#108387,(#108391,#108398),.PCURVE_S1.); +#108387 = LINE('',#108388,#108389); +#108388 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); +#108389 = VECTOR('',#108390,1.); +#108390 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#108391 = PCURVE('',#92513,#108392); +#108392 = DEFINITIONAL_REPRESENTATION('',(#108393),#108397); +#108393 = LINE('',#108394,#108395); +#108394 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108395 = VECTOR('',#108396,1.); +#108396 = DIRECTION('',(-3.563627120235E-016,1.)); +#108397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108398 = PCURVE('',#92595,#108399); +#108399 = DEFINITIONAL_REPRESENTATION('',(#108400),#108404); +#108400 = LINE('',#108401,#108402); +#108401 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108402 = VECTOR('',#108403,1.); +#108403 = DIRECTION('',(-1.,0.E+000)); +#108404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108405 = ORIENTED_EDGE('',*,*,#108360,.T.); +#108406 = ORIENTED_EDGE('',*,*,#108213,.T.); +#108407 = ORIENTED_EDGE('',*,*,#107930,.T.); +#108408 = ORIENTED_EDGE('',*,*,#107774,.T.); +#108409 = ORIENTED_EDGE('',*,*,#108410,.T.); +#108410 = EDGE_CURVE('',#107747,#107828,#108411,.T.); +#108411 = SURFACE_CURVE('',#108412,(#108416,#108423),.PCURVE_S1.); +#108412 = LINE('',#108413,#108414); +#108413 = CARTESIAN_POINT('',(7.65,-1.,1.159810404338E-002)); +#108414 = VECTOR('',#108415,1.); +#108415 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#108416 = PCURVE('',#92513,#108417); +#108417 = DEFINITIONAL_REPRESENTATION('',(#108418),#108422); +#108418 = LINE('',#108419,#108420); +#108419 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#108420 = VECTOR('',#108421,1.); +#108421 = DIRECTION('',(-1.,-2.101748079665E-016)); +#108422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108423 = PCURVE('',#107762,#108424); +#108424 = DEFINITIONAL_REPRESENTATION('',(#108425),#108429); +#108425 = LINE('',#108426,#108427); +#108426 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); +#108427 = VECTOR('',#108428,1.); +#108428 = DIRECTION('',(-1.,0.E+000)); +#108429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108430 = ORIENTED_EDGE('',*,*,#107825,.F.); +#108431 = ORIENTED_EDGE('',*,*,#108009,.F.); +#108432 = ORIENTED_EDGE('',*,*,#108116,.F.); +#108433 = ORIENTED_EDGE('',*,*,#108237,.F.); +#108434 = ORIENTED_EDGE('',*,*,#108435,.T.); +#108435 = EDGE_CURVE('',#108238,#92496,#108436,.T.); +#108436 = SURFACE_CURVE('',#108437,(#108441,#108448),.PCURVE_S1.); +#108437 = LINE('',#108438,#108439); +#108438 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.75)); +#108439 = VECTOR('',#108440,1.); +#108440 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#108441 = PCURVE('',#92513,#108442); +#108442 = DEFINITIONAL_REPRESENTATION('',(#108443),#108447); +#108443 = LINE('',#108444,#108445); +#108444 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#108445 = VECTOR('',#108446,1.); +#108446 = DIRECTION('',(-3.563627120235E-016,1.)); +#108447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108448 = PCURVE('',#92541,#108449); +#108449 = DEFINITIONAL_REPRESENTATION('',(#108450),#108454); +#108450 = LINE('',#108451,#108452); +#108451 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108452 = VECTOR('',#108453,1.); +#108453 = DIRECTION('',(1.,0.E+000)); +#108454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108455 = ORIENTED_EDGE('',*,*,#92495,.T.); +#108456 = ADVANCED_FACE('',(#108457),#92541,.F.); +#108457 = FACE_BOUND('',#108458,.T.); +#108458 = EDGE_LOOP('',(#108459,#108460,#108481,#108482)); +#108459 = ORIENTED_EDGE('',*,*,#108288,.F.); +#108460 = ORIENTED_EDGE('',*,*,#108461,.T.); +#108461 = EDGE_CURVE('',#108262,#92526,#108462,.T.); +#108462 = SURFACE_CURVE('',#108463,(#108467,#108474),.PCURVE_S1.); +#108463 = LINE('',#108464,#108465); +#108464 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.75)); +#108465 = VECTOR('',#108466,1.); +#108466 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#108467 = PCURVE('',#92541,#108468); +#108468 = DEFINITIONAL_REPRESENTATION('',(#108469),#108473); +#108469 = LINE('',#108470,#108471); +#108470 = CARTESIAN_POINT('',(0.E+000,0.2)); +#108471 = VECTOR('',#108472,1.); +#108472 = DIRECTION('',(1.,0.E+000)); +#108473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108474 = PCURVE('',#92569,#108475); +#108475 = DEFINITIONAL_REPRESENTATION('',(#108476),#108480); +#108476 = LINE('',#108477,#108478); +#108477 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#108478 = VECTOR('',#108479,1.); +#108479 = DIRECTION('',(3.563627120235E-016,1.)); +#108480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108481 = ORIENTED_EDGE('',*,*,#92525,.T.); +#108482 = ORIENTED_EDGE('',*,*,#108435,.F.); +#108483 = ADVANCED_FACE('',(#108484),#92569,.F.); +#108484 = FACE_BOUND('',#108485,.T.); +#108485 = EDGE_LOOP('',(#108486,#108487,#108488,#108489,#108490,#108491, + #108512,#108513,#108514,#108515,#108516,#108537)); +#108486 = ORIENTED_EDGE('',*,*,#108461,.F.); +#108487 = ORIENTED_EDGE('',*,*,#108261,.T.); +#108488 = ORIENTED_EDGE('',*,*,#108138,.T.); +#108489 = ORIENTED_EDGE('',*,*,#108063,.T.); +#108490 = ORIENTED_EDGE('',*,*,#107878,.T.); +#108491 = ORIENTED_EDGE('',*,*,#108492,.T.); +#108492 = EDGE_CURVE('',#107856,#107719,#108493,.T.); +#108493 = SURFACE_CURVE('',#108494,(#108498,#108505),.PCURVE_S1.); +#108494 = LINE('',#108495,#108496); +#108495 = CARTESIAN_POINT('',(7.85,-1.,1.159810404338E-002)); +#108496 = VECTOR('',#108497,1.); +#108497 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#108498 = PCURVE('',#92569,#108499); +#108499 = DEFINITIONAL_REPRESENTATION('',(#108500),#108504); +#108500 = LINE('',#108501,#108502); +#108501 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#108502 = VECTOR('',#108503,1.); +#108503 = DIRECTION('',(-1.,2.101748079665E-016)); +#108504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108505 = PCURVE('',#107762,#108506); +#108506 = DEFINITIONAL_REPRESENTATION('',(#108507),#108511); +#108507 = LINE('',#108508,#108509); +#108508 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#108509 = VECTOR('',#108510,1.); +#108510 = DIRECTION('',(1.,0.E+000)); +#108511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108512 = ORIENTED_EDGE('',*,*,#107716,.F.); +#108513 = ORIENTED_EDGE('',*,*,#107984,.F.); +#108514 = ORIENTED_EDGE('',*,*,#108191,.F.); +#108515 = ORIENTED_EDGE('',*,*,#108311,.F.); +#108516 = ORIENTED_EDGE('',*,*,#108517,.T.); +#108517 = EDGE_CURVE('',#108312,#92554,#108518,.T.); +#108518 = SURFACE_CURVE('',#108519,(#108523,#108530),.PCURVE_S1.); +#108519 = LINE('',#108520,#108521); +#108520 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.65)); +#108521 = VECTOR('',#108522,1.); +#108522 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#108523 = PCURVE('',#92569,#108524); +#108524 = DEFINITIONAL_REPRESENTATION('',(#108525),#108529); +#108525 = LINE('',#108526,#108527); +#108526 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108527 = VECTOR('',#108528,1.); +#108528 = DIRECTION('',(3.563627120235E-016,1.)); +#108529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108530 = PCURVE('',#92595,#108531); +#108531 = DEFINITIONAL_REPRESENTATION('',(#108532),#108536); +#108532 = LINE('',#108533,#108534); +#108533 = CARTESIAN_POINT('',(0.E+000,0.2)); +#108534 = VECTOR('',#108535,1.); +#108535 = DIRECTION('',(-1.,0.E+000)); +#108536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108537 = ORIENTED_EDGE('',*,*,#92553,.T.); +#108538 = ADVANCED_FACE('',(#108539),#92595,.F.); +#108539 = FACE_BOUND('',#108540,.T.); +#108540 = EDGE_LOOP('',(#108541,#108542,#108543,#108544)); +#108541 = ORIENTED_EDGE('',*,*,#108338,.F.); +#108542 = ORIENTED_EDGE('',*,*,#108385,.T.); +#108543 = ORIENTED_EDGE('',*,*,#92581,.T.); +#108544 = ORIENTED_EDGE('',*,*,#108517,.F.); +#108545 = ADVANCED_FACE('',(#108546),#107762,.T.); +#108546 = FACE_BOUND('',#108547,.T.); +#108547 = EDGE_LOOP('',(#108548,#108549,#108550,#108551)); +#108548 = ORIENTED_EDGE('',*,*,#108492,.F.); +#108549 = ORIENTED_EDGE('',*,*,#107855,.F.); +#108550 = ORIENTED_EDGE('',*,*,#108410,.F.); +#108551 = ORIENTED_EDGE('',*,*,#107746,.F.); +#108552 = ADVANCED_FACE('',(#108553),#108567,.T.); +#108553 = FACE_BOUND('',#108554,.T.); +#108554 = EDGE_LOOP('',(#108555,#108585,#108613,#108636)); +#108555 = ORIENTED_EDGE('',*,*,#108556,.T.); +#108556 = EDGE_CURVE('',#108557,#108559,#108561,.T.); +#108557 = VERTEX_POINT('',#108558); +#108558 = CARTESIAN_POINT('',(8.35,-0.74341632541,-0.308197125857)); +#108559 = VERTEX_POINT('',#108560); +#108560 = CARTESIAN_POINT('',(8.35,-1.,-0.308197125857)); +#108561 = SURFACE_CURVE('',#108562,(#108566,#108578),.PCURVE_S1.); +#108562 = LINE('',#108563,#108564); +#108563 = CARTESIAN_POINT('',(8.35,-0.74341632541,-0.308197125857)); +#108564 = VECTOR('',#108565,1.); +#108565 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#108566 = PCURVE('',#108567,#108572); +#108567 = PLANE('',#108568); +#108568 = AXIS2_PLACEMENT_3D('',#108569,#108570,#108571); +#108569 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#108570 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108571 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108572 = DEFINITIONAL_REPRESENTATION('',(#108573),#108577); +#108573 = LINE('',#108574,#108575); +#108574 = CARTESIAN_POINT('',(1.65,0.E+000)); +#108575 = VECTOR('',#108576,1.); +#108576 = DIRECTION('',(0.E+000,-1.)); +#108577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108578 = PCURVE('',#90864,#108579); +#108579 = DEFINITIONAL_REPRESENTATION('',(#108580),#108584); +#108580 = LINE('',#108581,#108582); +#108581 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#108582 = VECTOR('',#108583,1.); +#108583 = DIRECTION('',(0.E+000,-1.)); +#108584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108585 = ORIENTED_EDGE('',*,*,#108586,.T.); +#108586 = EDGE_CURVE('',#108559,#108587,#108589,.T.); +#108587 = VERTEX_POINT('',#108588); +#108588 = CARTESIAN_POINT('',(8.15,-1.,-0.308197125857)); +#108589 = SURFACE_CURVE('',#108590,(#108594,#108601),.PCURVE_S1.); +#108590 = LINE('',#108591,#108592); +#108591 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#108592 = VECTOR('',#108593,1.); +#108593 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108594 = PCURVE('',#108567,#108595); +#108595 = DEFINITIONAL_REPRESENTATION('',(#108596),#108600); +#108596 = LINE('',#108597,#108598); +#108597 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#108598 = VECTOR('',#108599,1.); +#108599 = DIRECTION('',(1.,0.E+000)); +#108600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#105934 = PCURVE('',#90177,#105935); -#105935 = DEFINITIONAL_REPRESENTATION('',(#105936),#105944); -#105936 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#105937,#105938,#105939, - #105940,#105941,#105942,#105943),.UNSPECIFIED.,.F.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#105937 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#105938 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#105939 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#105940 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#105941 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#105942 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#105943 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#105944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105945 = ORIENTED_EDGE('',*,*,#105946,.F.); -#105946 = EDGE_CURVE('',#105947,#105920,#105949,.T.); -#105947 = VERTEX_POINT('',#105948); -#105948 = CARTESIAN_POINT('',(7.65,-0.303662633502,0.65)); -#105949 = SURFACE_CURVE('',#105950,(#105954,#105960),.PCURVE_S1.); -#105950 = LINE('',#105951,#105952); -#105951 = CARTESIAN_POINT('',(7.65,-0.303662633502,0.65)); -#105952 = VECTOR('',#105953,1.); -#105953 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105954 = PCURVE('',#105788,#105955); -#105955 = DEFINITIONAL_REPRESENTATION('',(#105956),#105959); -#105956 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105957,#105958), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#105957 = CARTESIAN_POINT('',(3.169584923929,-2.35)); -#105958 = CARTESIAN_POINT('',(3.169584923929,-2.15)); -#105959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105960 = PCURVE('',#90203,#105961); -#105961 = DEFINITIONAL_REPRESENTATION('',(#105962),#105966); -#105962 = LINE('',#105963,#105964); -#105963 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#105964 = VECTOR('',#105965,1.); -#105965 = DIRECTION('',(0.E+000,1.)); -#105966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105967 = ORIENTED_EDGE('',*,*,#105968,.T.); -#105968 = EDGE_CURVE('',#105947,#105773,#105969,.T.); -#105969 = SURFACE_CURVE('',#105970,(#105975,#105981),.PCURVE_S1.); -#105970 = CIRCLE('',#105971,0.119270391569); -#105971 = AXIS2_PLACEMENT_3D('',#105972,#105973,#105974); -#105972 = CARTESIAN_POINT('',(7.65,-0.30032442045,0.530776333563)); -#105973 = DIRECTION('',(1.,0.E+000,0.E+000)); -#105974 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#105975 = PCURVE('',#105788,#105976); -#105976 = DEFINITIONAL_REPRESENTATION('',(#105977),#105980); -#105977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#105978,#105979), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), - .PIECEWISE_BEZIER_KNOTS.); -#105978 = CARTESIAN_POINT('',(3.169584923929,-2.35)); -#105979 = CARTESIAN_POINT('',(4.712388980385,-2.35)); -#105980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105981 = PCURVE('',#90121,#105982); -#105982 = DEFINITIONAL_REPRESENTATION('',(#105983),#105987); -#105983 = CIRCLE('',#105984,0.119270391569); -#105984 = AXIS2_PLACEMENT_2D('',#105985,#105986); -#105985 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#105986 = DIRECTION('',(1.,0.E+000)); -#105987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#105988 = ORIENTED_EDGE('',*,*,#105770,.F.); -#105989 = ADVANCED_FACE('',(#105990),#90121,.F.); -#105990 = FACE_BOUND('',#105991,.T.); -#105991 = EDGE_LOOP('',(#105992,#106013,#106014,#106015,#106016,#106017, - #106038,#106039,#106040,#106041,#106042,#106063)); -#105992 = ORIENTED_EDGE('',*,*,#105993,.F.); -#105993 = EDGE_CURVE('',#105947,#90106,#105994,.T.); -#105994 = SURFACE_CURVE('',#105995,(#105999,#106006),.PCURVE_S1.); -#105995 = LINE('',#105996,#105997); -#105996 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.65)); -#105997 = VECTOR('',#105998,1.); -#105998 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#105999 = PCURVE('',#90121,#106000); -#106000 = DEFINITIONAL_REPRESENTATION('',(#106001),#106005); -#106001 = LINE('',#106002,#106003); -#106002 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106003 = VECTOR('',#106004,1.); -#106004 = DIRECTION('',(-3.563627120235E-016,1.)); -#106005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106006 = PCURVE('',#90203,#106007); -#106007 = DEFINITIONAL_REPRESENTATION('',(#106008),#106012); -#106008 = LINE('',#106009,#106010); -#106009 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106010 = VECTOR('',#106011,1.); -#106011 = DIRECTION('',(-1.,0.E+000)); -#106012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106013 = ORIENTED_EDGE('',*,*,#105968,.T.); -#106014 = ORIENTED_EDGE('',*,*,#105821,.T.); -#106015 = ORIENTED_EDGE('',*,*,#105538,.T.); -#106016 = ORIENTED_EDGE('',*,*,#105382,.T.); -#106017 = ORIENTED_EDGE('',*,*,#106018,.T.); -#106018 = EDGE_CURVE('',#105355,#105436,#106019,.T.); -#106019 = SURFACE_CURVE('',#106020,(#106024,#106031),.PCURVE_S1.); -#106020 = LINE('',#106021,#106022); -#106021 = CARTESIAN_POINT('',(7.65,-1.,1.159810404338E-002)); -#106022 = VECTOR('',#106023,1.); -#106023 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#106024 = PCURVE('',#90121,#106025); -#106025 = DEFINITIONAL_REPRESENTATION('',(#106026),#106030); -#106026 = LINE('',#106027,#106028); -#106027 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#106028 = VECTOR('',#106029,1.); -#106029 = DIRECTION('',(-1.,-2.101748079665E-016)); -#106030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106031 = PCURVE('',#105370,#106032); -#106032 = DEFINITIONAL_REPRESENTATION('',(#106033),#106037); -#106033 = LINE('',#106034,#106035); -#106034 = CARTESIAN_POINT('',(-0.269794846371,-0.1)); -#106035 = VECTOR('',#106036,1.); -#106036 = DIRECTION('',(-1.,0.E+000)); -#106037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106038 = ORIENTED_EDGE('',*,*,#105433,.F.); -#106039 = ORIENTED_EDGE('',*,*,#105617,.F.); -#106040 = ORIENTED_EDGE('',*,*,#105724,.F.); -#106041 = ORIENTED_EDGE('',*,*,#105845,.F.); -#106042 = ORIENTED_EDGE('',*,*,#106043,.T.); -#106043 = EDGE_CURVE('',#105846,#90104,#106044,.T.); -#106044 = SURFACE_CURVE('',#106045,(#106049,#106056),.PCURVE_S1.); -#106045 = LINE('',#106046,#106047); -#106046 = CARTESIAN_POINT('',(7.65,-0.527847992439,0.75)); -#106047 = VECTOR('',#106048,1.); -#106048 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106049 = PCURVE('',#90121,#106050); -#106050 = DEFINITIONAL_REPRESENTATION('',(#106051),#106055); -#106051 = LINE('',#106052,#106053); -#106052 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#106053 = VECTOR('',#106054,1.); -#106054 = DIRECTION('',(-3.563627120235E-016,1.)); -#106055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106056 = PCURVE('',#90149,#106057); -#106057 = DEFINITIONAL_REPRESENTATION('',(#106058),#106062); -#106058 = LINE('',#106059,#106060); -#106059 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106060 = VECTOR('',#106061,1.); -#106061 = DIRECTION('',(1.,0.E+000)); -#106062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106063 = ORIENTED_EDGE('',*,*,#90103,.T.); -#106064 = ADVANCED_FACE('',(#106065),#90149,.F.); -#106065 = FACE_BOUND('',#106066,.T.); -#106066 = EDGE_LOOP('',(#106067,#106068,#106089,#106090)); -#106067 = ORIENTED_EDGE('',*,*,#105896,.F.); -#106068 = ORIENTED_EDGE('',*,*,#106069,.T.); -#106069 = EDGE_CURVE('',#105870,#90134,#106070,.T.); -#106070 = SURFACE_CURVE('',#106071,(#106075,#106082),.PCURVE_S1.); -#106071 = LINE('',#106072,#106073); -#106072 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.75)); -#106073 = VECTOR('',#106074,1.); -#106074 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106075 = PCURVE('',#90149,#106076); -#106076 = DEFINITIONAL_REPRESENTATION('',(#106077),#106081); -#106077 = LINE('',#106078,#106079); -#106078 = CARTESIAN_POINT('',(0.E+000,0.2)); -#106079 = VECTOR('',#106080,1.); -#106080 = DIRECTION('',(1.,0.E+000)); -#106081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106082 = PCURVE('',#90177,#106083); -#106083 = DEFINITIONAL_REPRESENTATION('',(#106084),#106088); -#106084 = LINE('',#106085,#106086); -#106085 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#106086 = VECTOR('',#106087,1.); -#106087 = DIRECTION('',(3.563627120235E-016,1.)); -#106088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106089 = ORIENTED_EDGE('',*,*,#90133,.T.); -#106090 = ORIENTED_EDGE('',*,*,#106043,.F.); -#106091 = ADVANCED_FACE('',(#106092),#90177,.F.); -#106092 = FACE_BOUND('',#106093,.T.); -#106093 = EDGE_LOOP('',(#106094,#106095,#106096,#106097,#106098,#106099, - #106120,#106121,#106122,#106123,#106124,#106145)); -#106094 = ORIENTED_EDGE('',*,*,#106069,.F.); -#106095 = ORIENTED_EDGE('',*,*,#105869,.T.); -#106096 = ORIENTED_EDGE('',*,*,#105746,.T.); -#106097 = ORIENTED_EDGE('',*,*,#105671,.T.); -#106098 = ORIENTED_EDGE('',*,*,#105486,.T.); -#106099 = ORIENTED_EDGE('',*,*,#106100,.T.); -#106100 = EDGE_CURVE('',#105464,#105327,#106101,.T.); -#106101 = SURFACE_CURVE('',#106102,(#106106,#106113),.PCURVE_S1.); -#106102 = LINE('',#106103,#106104); -#106103 = CARTESIAN_POINT('',(7.85,-1.,1.159810404338E-002)); -#106104 = VECTOR('',#106105,1.); -#106105 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#106106 = PCURVE('',#90177,#106107); -#106107 = DEFINITIONAL_REPRESENTATION('',(#106108),#106112); -#106108 = LINE('',#106109,#106110); -#106109 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#106110 = VECTOR('',#106111,1.); -#106111 = DIRECTION('',(-1.,2.101748079665E-016)); -#106112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106113 = PCURVE('',#105370,#106114); -#106114 = DEFINITIONAL_REPRESENTATION('',(#106115),#106119); -#106115 = LINE('',#106116,#106117); -#106116 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#106117 = VECTOR('',#106118,1.); -#106118 = DIRECTION('',(1.,0.E+000)); -#106119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106120 = ORIENTED_EDGE('',*,*,#105324,.F.); -#106121 = ORIENTED_EDGE('',*,*,#105592,.F.); -#106122 = ORIENTED_EDGE('',*,*,#105799,.F.); -#106123 = ORIENTED_EDGE('',*,*,#105919,.F.); -#106124 = ORIENTED_EDGE('',*,*,#106125,.T.); -#106125 = EDGE_CURVE('',#105920,#90162,#106126,.T.); -#106126 = SURFACE_CURVE('',#106127,(#106131,#106138),.PCURVE_S1.); -#106127 = LINE('',#106128,#106129); -#106128 = CARTESIAN_POINT('',(7.85,-0.527847992439,0.65)); -#106129 = VECTOR('',#106130,1.); -#106130 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106131 = PCURVE('',#90177,#106132); -#106132 = DEFINITIONAL_REPRESENTATION('',(#106133),#106137); -#106133 = LINE('',#106134,#106135); -#106134 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106135 = VECTOR('',#106136,1.); -#106136 = DIRECTION('',(3.563627120235E-016,1.)); -#106137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106138 = PCURVE('',#90203,#106139); -#106139 = DEFINITIONAL_REPRESENTATION('',(#106140),#106144); -#106140 = LINE('',#106141,#106142); -#106141 = CARTESIAN_POINT('',(0.E+000,0.2)); -#106142 = VECTOR('',#106143,1.); -#106143 = DIRECTION('',(-1.,0.E+000)); -#106144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106145 = ORIENTED_EDGE('',*,*,#90161,.T.); -#106146 = ADVANCED_FACE('',(#106147),#90203,.F.); -#106147 = FACE_BOUND('',#106148,.T.); -#106148 = EDGE_LOOP('',(#106149,#106150,#106151,#106152)); -#106149 = ORIENTED_EDGE('',*,*,#105946,.F.); -#106150 = ORIENTED_EDGE('',*,*,#105993,.T.); -#106151 = ORIENTED_EDGE('',*,*,#90189,.T.); -#106152 = ORIENTED_EDGE('',*,*,#106125,.F.); -#106153 = ADVANCED_FACE('',(#106154),#105370,.T.); -#106154 = FACE_BOUND('',#106155,.T.); -#106155 = EDGE_LOOP('',(#106156,#106157,#106158,#106159)); -#106156 = ORIENTED_EDGE('',*,*,#106100,.F.); -#106157 = ORIENTED_EDGE('',*,*,#105463,.F.); -#106158 = ORIENTED_EDGE('',*,*,#106018,.F.); -#106159 = ORIENTED_EDGE('',*,*,#105354,.F.); -#106160 = ADVANCED_FACE('',(#106161),#106175,.T.); -#106161 = FACE_BOUND('',#106162,.T.); -#106162 = EDGE_LOOP('',(#106163,#106193,#106221,#106244)); -#106163 = ORIENTED_EDGE('',*,*,#106164,.T.); -#106164 = EDGE_CURVE('',#106165,#106167,#106169,.T.); -#106165 = VERTEX_POINT('',#106166); -#106166 = CARTESIAN_POINT('',(8.35,-0.74341632541,-0.308197125857)); -#106167 = VERTEX_POINT('',#106168); -#106168 = CARTESIAN_POINT('',(8.35,-1.,-0.308197125857)); -#106169 = SURFACE_CURVE('',#106170,(#106174,#106186),.PCURVE_S1.); -#106170 = LINE('',#106171,#106172); -#106171 = CARTESIAN_POINT('',(8.35,-0.74341632541,-0.308197125857)); -#106172 = VECTOR('',#106173,1.); -#106173 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#106174 = PCURVE('',#106175,#106180); -#106175 = PLANE('',#106176); -#106176 = AXIS2_PLACEMENT_3D('',#106177,#106178,#106179); -#106177 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#106178 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106179 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106180 = DEFINITIONAL_REPRESENTATION('',(#106181),#106185); -#106181 = LINE('',#106182,#106183); -#106182 = CARTESIAN_POINT('',(1.65,0.E+000)); -#106183 = VECTOR('',#106184,1.); -#106184 = DIRECTION('',(0.E+000,-1.)); -#106185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106186 = PCURVE('',#88472,#106187); -#106187 = DEFINITIONAL_REPRESENTATION('',(#106188),#106192); -#106188 = LINE('',#106189,#106190); -#106189 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#106190 = VECTOR('',#106191,1.); -#106191 = DIRECTION('',(0.E+000,-1.)); -#106192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106193 = ORIENTED_EDGE('',*,*,#106194,.T.); -#106194 = EDGE_CURVE('',#106167,#106195,#106197,.T.); -#106195 = VERTEX_POINT('',#106196); -#106196 = CARTESIAN_POINT('',(8.15,-1.,-0.308197125857)); -#106197 = SURFACE_CURVE('',#106198,(#106202,#106209),.PCURVE_S1.); -#106198 = LINE('',#106199,#106200); -#106199 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#106200 = VECTOR('',#106201,1.); -#106201 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106202 = PCURVE('',#106175,#106203); -#106203 = DEFINITIONAL_REPRESENTATION('',(#106204),#106208); -#106204 = LINE('',#106205,#106206); -#106205 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#106206 = VECTOR('',#106207,1.); -#106207 = DIRECTION('',(1.,0.E+000)); -#106208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106209 = PCURVE('',#106210,#106215); -#106210 = PLANE('',#106211); -#106211 = AXIS2_PLACEMENT_3D('',#106212,#106213,#106214); -#106212 = CARTESIAN_POINT('',(8.25,-1.,-0.258196742327)); -#106213 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#106214 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#106215 = DEFINITIONAL_REPRESENTATION('',(#106216),#106220); -#106216 = LINE('',#106217,#106218); -#106217 = CARTESIAN_POINT('',(5.000038352949E-002,1.75)); -#106218 = VECTOR('',#106219,1.); -#106219 = DIRECTION('',(0.E+000,-1.)); -#106220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106221 = ORIENTED_EDGE('',*,*,#106222,.F.); -#106222 = EDGE_CURVE('',#106223,#106195,#106225,.T.); -#106223 = VERTEX_POINT('',#106224); -#106224 = CARTESIAN_POINT('',(8.15,-0.74341632541,-0.308197125857)); -#106225 = SURFACE_CURVE('',#106226,(#106230,#106237),.PCURVE_S1.); -#106226 = LINE('',#106227,#106228); -#106227 = CARTESIAN_POINT('',(8.15,-0.74341632541,-0.308197125857)); -#106228 = VECTOR('',#106229,1.); -#106229 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#106230 = PCURVE('',#106175,#106231); -#106231 = DEFINITIONAL_REPRESENTATION('',(#106232),#106236); -#106232 = LINE('',#106233,#106234); -#106233 = CARTESIAN_POINT('',(1.85,0.E+000)); -#106234 = VECTOR('',#106235,1.); -#106235 = DIRECTION('',(0.E+000,-1.)); -#106236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106237 = PCURVE('',#88416,#106238); -#106238 = DEFINITIONAL_REPRESENTATION('',(#106239),#106243); -#106239 = LINE('',#106240,#106241); -#106240 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#106241 = VECTOR('',#106242,1.); -#106242 = DIRECTION('',(0.E+000,-1.)); -#106243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106244 = ORIENTED_EDGE('',*,*,#106245,.T.); -#106245 = EDGE_CURVE('',#106223,#106165,#106246,.T.); -#106246 = SURFACE_CURVE('',#106247,(#106251,#106258),.PCURVE_S1.); -#106247 = LINE('',#106248,#106249); -#106248 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#106249 = VECTOR('',#106250,1.); -#106250 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106251 = PCURVE('',#106175,#106252); -#106252 = DEFINITIONAL_REPRESENTATION('',(#106253),#106257); -#106253 = LINE('',#106254,#106255); -#106254 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106255 = VECTOR('',#106256,1.); -#106256 = DIRECTION('',(-1.,0.E+000)); -#106257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106258 = PCURVE('',#106259,#106264); -#106259 = CYLINDRICAL_SURFACE('',#106260,0.308574064194); -#106260 = AXIS2_PLACEMENT_3D('',#106261,#106262,#106263); -#106261 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#106262 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106264 = DEFINITIONAL_REPRESENTATION('',(#106265),#106268); -#106265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106266,#106267), +#108601 = PCURVE('',#108602,#108607); +#108602 = PLANE('',#108603); +#108603 = AXIS2_PLACEMENT_3D('',#108604,#108605,#108606); +#108604 = CARTESIAN_POINT('',(8.25,-1.,-0.258196742327)); +#108605 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#108606 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#108607 = DEFINITIONAL_REPRESENTATION('',(#108608),#108612); +#108608 = LINE('',#108609,#108610); +#108609 = CARTESIAN_POINT('',(5.000038352949E-002,1.75)); +#108610 = VECTOR('',#108611,1.); +#108611 = DIRECTION('',(0.E+000,-1.)); +#108612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108613 = ORIENTED_EDGE('',*,*,#108614,.F.); +#108614 = EDGE_CURVE('',#108615,#108587,#108617,.T.); +#108615 = VERTEX_POINT('',#108616); +#108616 = CARTESIAN_POINT('',(8.15,-0.74341632541,-0.308197125857)); +#108617 = SURFACE_CURVE('',#108618,(#108622,#108629),.PCURVE_S1.); +#108618 = LINE('',#108619,#108620); +#108619 = CARTESIAN_POINT('',(8.15,-0.74341632541,-0.308197125857)); +#108620 = VECTOR('',#108621,1.); +#108621 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#108622 = PCURVE('',#108567,#108623); +#108623 = DEFINITIONAL_REPRESENTATION('',(#108624),#108628); +#108624 = LINE('',#108625,#108626); +#108625 = CARTESIAN_POINT('',(1.85,0.E+000)); +#108626 = VECTOR('',#108627,1.); +#108627 = DIRECTION('',(0.E+000,-1.)); +#108628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108629 = PCURVE('',#90808,#108630); +#108630 = DEFINITIONAL_REPRESENTATION('',(#108631),#108635); +#108631 = LINE('',#108632,#108633); +#108632 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#108633 = VECTOR('',#108634,1.); +#108634 = DIRECTION('',(0.E+000,-1.)); +#108635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108636 = ORIENTED_EDGE('',*,*,#108637,.T.); +#108637 = EDGE_CURVE('',#108615,#108557,#108638,.T.); +#108638 = SURFACE_CURVE('',#108639,(#108643,#108650),.PCURVE_S1.); +#108639 = LINE('',#108640,#108641); +#108640 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#108641 = VECTOR('',#108642,1.); +#108642 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108643 = PCURVE('',#108567,#108644); +#108644 = DEFINITIONAL_REPRESENTATION('',(#108645),#108649); +#108645 = LINE('',#108646,#108647); +#108646 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108647 = VECTOR('',#108648,1.); +#108648 = DIRECTION('',(-1.,0.E+000)); +#108649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108650 = PCURVE('',#108651,#108656); +#108651 = CYLINDRICAL_SURFACE('',#108652,0.308574064194); +#108652 = AXIS2_PLACEMENT_3D('',#108653,#108654,#108655); +#108653 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#108654 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108656 = DEFINITIONAL_REPRESENTATION('',(#108657),#108660); +#108657 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108658,#108659), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#106266 = CARTESIAN_POINT('',(3.191025391152,1.85)); -#106267 = CARTESIAN_POINT('',(3.191025391152,1.65)); -#106268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106269 = ADVANCED_FACE('',(#106270),#106284,.T.); -#106270 = FACE_BOUND('',#106271,.T.); -#106271 = EDGE_LOOP('',(#106272,#106302,#106325,#106348)); -#106272 = ORIENTED_EDGE('',*,*,#106273,.T.); -#106273 = EDGE_CURVE('',#106274,#106276,#106278,.T.); -#106274 = VERTEX_POINT('',#106275); -#106275 = CARTESIAN_POINT('',(8.15,-0.740726081328,-0.208196358798)); -#106276 = VERTEX_POINT('',#106277); -#106277 = CARTESIAN_POINT('',(8.15,-1.,-0.208196358798)); -#106278 = SURFACE_CURVE('',#106279,(#106283,#106295),.PCURVE_S1.); -#106279 = LINE('',#106280,#106281); -#106280 = CARTESIAN_POINT('',(8.15,-0.740726081328,-0.208196358798)); -#106281 = VECTOR('',#106282,1.); -#106282 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#106283 = PCURVE('',#106284,#106289); -#106284 = PLANE('',#106285); -#106285 = AXIS2_PLACEMENT_3D('',#106286,#106287,#106288); -#106286 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#106287 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106288 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106289 = DEFINITIONAL_REPRESENTATION('',(#106290),#106294); -#106290 = LINE('',#106291,#106292); -#106291 = CARTESIAN_POINT('',(-1.85,0.E+000)); -#106292 = VECTOR('',#106293,1.); -#106293 = DIRECTION('',(0.E+000,-1.)); -#106294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106295 = PCURVE('',#88416,#106296); -#106296 = DEFINITIONAL_REPRESENTATION('',(#106297),#106301); -#106297 = LINE('',#106298,#106299); -#106298 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#106299 = VECTOR('',#106300,1.); -#106300 = DIRECTION('',(0.E+000,-1.)); -#106301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106302 = ORIENTED_EDGE('',*,*,#106303,.T.); -#106303 = EDGE_CURVE('',#106276,#106304,#106306,.T.); -#106304 = VERTEX_POINT('',#106305); -#106305 = CARTESIAN_POINT('',(8.35,-1.,-0.208196358798)); -#106306 = SURFACE_CURVE('',#106307,(#106311,#106318),.PCURVE_S1.); -#106307 = LINE('',#106308,#106309); -#106308 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#106309 = VECTOR('',#106310,1.); -#106310 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106311 = PCURVE('',#106284,#106312); -#106312 = DEFINITIONAL_REPRESENTATION('',(#106313),#106317); -#106313 = LINE('',#106314,#106315); -#106314 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#106315 = VECTOR('',#106316,1.); -#106316 = DIRECTION('',(1.,0.E+000)); -#106317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106318 = PCURVE('',#106210,#106319); -#106319 = DEFINITIONAL_REPRESENTATION('',(#106320),#106324); -#106320 = LINE('',#106321,#106322); -#106321 = CARTESIAN_POINT('',(-5.000038352949E-002,1.75)); -#106322 = VECTOR('',#106323,1.); -#106323 = DIRECTION('',(0.E+000,1.)); -#106324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106325 = ORIENTED_EDGE('',*,*,#106326,.F.); -#106326 = EDGE_CURVE('',#106327,#106304,#106329,.T.); -#106327 = VERTEX_POINT('',#106328); -#106328 = CARTESIAN_POINT('',(8.35,-0.740726081328,-0.208196358798)); -#106329 = SURFACE_CURVE('',#106330,(#106334,#106341),.PCURVE_S1.); -#106330 = LINE('',#106331,#106332); -#106331 = CARTESIAN_POINT('',(8.35,-0.740726081328,-0.208196358798)); -#106332 = VECTOR('',#106333,1.); -#106333 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#106334 = PCURVE('',#106284,#106335); -#106335 = DEFINITIONAL_REPRESENTATION('',(#106336),#106340); -#106336 = LINE('',#106337,#106338); -#106337 = CARTESIAN_POINT('',(-1.65,0.E+000)); -#106338 = VECTOR('',#106339,1.); -#106339 = DIRECTION('',(0.E+000,-1.)); -#106340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106341 = PCURVE('',#88472,#106342); -#106342 = DEFINITIONAL_REPRESENTATION('',(#106343),#106347); -#106343 = LINE('',#106344,#106345); -#106344 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#106345 = VECTOR('',#106346,1.); -#106346 = DIRECTION('',(0.E+000,-1.)); -#106347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106348 = ORIENTED_EDGE('',*,*,#106349,.T.); -#106349 = EDGE_CURVE('',#106327,#106274,#106350,.T.); -#106350 = SURFACE_CURVE('',#106351,(#106355,#106362),.PCURVE_S1.); -#106351 = LINE('',#106352,#106353); -#106352 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#106353 = VECTOR('',#106354,1.); -#106354 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106355 = PCURVE('',#106284,#106356); -#106356 = DEFINITIONAL_REPRESENTATION('',(#106357),#106361); -#106357 = LINE('',#106358,#106359); -#106358 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106359 = VECTOR('',#106360,1.); -#106360 = DIRECTION('',(-1.,0.E+000)); -#106361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106362 = PCURVE('',#106363,#106368); -#106363 = CYLINDRICAL_SURFACE('',#106364,0.208574704164); -#106364 = AXIS2_PLACEMENT_3D('',#106365,#106366,#106367); -#106365 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#106366 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106367 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106368 = DEFINITIONAL_REPRESENTATION('',(#106369),#106372); -#106369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106370,#106371), +#108658 = CARTESIAN_POINT('',(3.191025391152,1.85)); +#108659 = CARTESIAN_POINT('',(3.191025391152,1.65)); +#108660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108661 = ADVANCED_FACE('',(#108662),#108676,.T.); +#108662 = FACE_BOUND('',#108663,.T.); +#108663 = EDGE_LOOP('',(#108664,#108694,#108717,#108740)); +#108664 = ORIENTED_EDGE('',*,*,#108665,.T.); +#108665 = EDGE_CURVE('',#108666,#108668,#108670,.T.); +#108666 = VERTEX_POINT('',#108667); +#108667 = CARTESIAN_POINT('',(8.15,-0.740726081328,-0.208196358798)); +#108668 = VERTEX_POINT('',#108669); +#108669 = CARTESIAN_POINT('',(8.15,-1.,-0.208196358798)); +#108670 = SURFACE_CURVE('',#108671,(#108675,#108687),.PCURVE_S1.); +#108671 = LINE('',#108672,#108673); +#108672 = CARTESIAN_POINT('',(8.15,-0.740726081328,-0.208196358798)); +#108673 = VECTOR('',#108674,1.); +#108674 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#108675 = PCURVE('',#108676,#108681); +#108676 = PLANE('',#108677); +#108677 = AXIS2_PLACEMENT_3D('',#108678,#108679,#108680); +#108678 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#108679 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108680 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108681 = DEFINITIONAL_REPRESENTATION('',(#108682),#108686); +#108682 = LINE('',#108683,#108684); +#108683 = CARTESIAN_POINT('',(-1.85,0.E+000)); +#108684 = VECTOR('',#108685,1.); +#108685 = DIRECTION('',(0.E+000,-1.)); +#108686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108687 = PCURVE('',#90808,#108688); +#108688 = DEFINITIONAL_REPRESENTATION('',(#108689),#108693); +#108689 = LINE('',#108690,#108691); +#108690 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#108691 = VECTOR('',#108692,1.); +#108692 = DIRECTION('',(0.E+000,-1.)); +#108693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108694 = ORIENTED_EDGE('',*,*,#108695,.T.); +#108695 = EDGE_CURVE('',#108668,#108696,#108698,.T.); +#108696 = VERTEX_POINT('',#108697); +#108697 = CARTESIAN_POINT('',(8.35,-1.,-0.208196358798)); +#108698 = SURFACE_CURVE('',#108699,(#108703,#108710),.PCURVE_S1.); +#108699 = LINE('',#108700,#108701); +#108700 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#108701 = VECTOR('',#108702,1.); +#108702 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108703 = PCURVE('',#108676,#108704); +#108704 = DEFINITIONAL_REPRESENTATION('',(#108705),#108709); +#108705 = LINE('',#108706,#108707); +#108706 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#108707 = VECTOR('',#108708,1.); +#108708 = DIRECTION('',(1.,0.E+000)); +#108709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108710 = PCURVE('',#108602,#108711); +#108711 = DEFINITIONAL_REPRESENTATION('',(#108712),#108716); +#108712 = LINE('',#108713,#108714); +#108713 = CARTESIAN_POINT('',(-5.000038352949E-002,1.75)); +#108714 = VECTOR('',#108715,1.); +#108715 = DIRECTION('',(0.E+000,1.)); +#108716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108717 = ORIENTED_EDGE('',*,*,#108718,.F.); +#108718 = EDGE_CURVE('',#108719,#108696,#108721,.T.); +#108719 = VERTEX_POINT('',#108720); +#108720 = CARTESIAN_POINT('',(8.35,-0.740726081328,-0.208196358798)); +#108721 = SURFACE_CURVE('',#108722,(#108726,#108733),.PCURVE_S1.); +#108722 = LINE('',#108723,#108724); +#108723 = CARTESIAN_POINT('',(8.35,-0.740726081328,-0.208196358798)); +#108724 = VECTOR('',#108725,1.); +#108725 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#108726 = PCURVE('',#108676,#108727); +#108727 = DEFINITIONAL_REPRESENTATION('',(#108728),#108732); +#108728 = LINE('',#108729,#108730); +#108729 = CARTESIAN_POINT('',(-1.65,0.E+000)); +#108730 = VECTOR('',#108731,1.); +#108731 = DIRECTION('',(0.E+000,-1.)); +#108732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108733 = PCURVE('',#90864,#108734); +#108734 = DEFINITIONAL_REPRESENTATION('',(#108735),#108739); +#108735 = LINE('',#108736,#108737); +#108736 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#108737 = VECTOR('',#108738,1.); +#108738 = DIRECTION('',(0.E+000,-1.)); +#108739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108740 = ORIENTED_EDGE('',*,*,#108741,.T.); +#108741 = EDGE_CURVE('',#108719,#108666,#108742,.T.); +#108742 = SURFACE_CURVE('',#108743,(#108747,#108754),.PCURVE_S1.); +#108743 = LINE('',#108744,#108745); +#108744 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#108745 = VECTOR('',#108746,1.); +#108746 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108747 = PCURVE('',#108676,#108748); +#108748 = DEFINITIONAL_REPRESENTATION('',(#108749),#108753); +#108749 = LINE('',#108750,#108751); +#108750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108751 = VECTOR('',#108752,1.); +#108752 = DIRECTION('',(-1.,0.E+000)); +#108753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108754 = PCURVE('',#108755,#108760); +#108755 = CYLINDRICAL_SURFACE('',#108756,0.208574704164); +#108756 = AXIS2_PLACEMENT_3D('',#108757,#108758,#108759); +#108757 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#108758 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108759 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108760 = DEFINITIONAL_REPRESENTATION('',(#108761),#108764); +#108761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108762,#108763), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#106370 = CARTESIAN_POINT('',(3.201833915432,1.65)); -#106371 = CARTESIAN_POINT('',(3.201833915432,1.85)); -#106372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106373 = ADVANCED_FACE('',(#106374),#106259,.T.); -#106374 = FACE_BOUND('',#106375,.T.); -#106375 = EDGE_LOOP('',(#106376,#106377,#106404,#106431)); -#106376 = ORIENTED_EDGE('',*,*,#106245,.F.); -#106377 = ORIENTED_EDGE('',*,*,#106378,.F.); -#106378 = EDGE_CURVE('',#106379,#106223,#106381,.T.); -#106379 = VERTEX_POINT('',#106380); -#106380 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.E+000)); -#106381 = SURFACE_CURVE('',#106382,(#106387,#106393),.PCURVE_S1.); -#106382 = CIRCLE('',#106383,0.308574064194); -#106383 = AXIS2_PLACEMENT_3D('',#106384,#106385,#106386); -#106384 = CARTESIAN_POINT('',(8.15,-0.728168876214,2.640924866458E-017) - ); -#106385 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106386 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106387 = PCURVE('',#106259,#106388); -#106388 = DEFINITIONAL_REPRESENTATION('',(#106389),#106392); -#106389 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106390,#106391), +#108762 = CARTESIAN_POINT('',(3.201833915432,1.65)); +#108763 = CARTESIAN_POINT('',(3.201833915432,1.85)); +#108764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108765 = ADVANCED_FACE('',(#108766),#108651,.T.); +#108766 = FACE_BOUND('',#108767,.T.); +#108767 = EDGE_LOOP('',(#108768,#108769,#108796,#108823)); +#108768 = ORIENTED_EDGE('',*,*,#108637,.F.); +#108769 = ORIENTED_EDGE('',*,*,#108770,.F.); +#108770 = EDGE_CURVE('',#108771,#108615,#108773,.T.); +#108771 = VERTEX_POINT('',#108772); +#108772 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.E+000)); +#108773 = SURFACE_CURVE('',#108774,(#108779,#108785),.PCURVE_S1.); +#108774 = CIRCLE('',#108775,0.308574064194); +#108775 = AXIS2_PLACEMENT_3D('',#108776,#108777,#108778); +#108776 = CARTESIAN_POINT('',(8.15,-0.728168876214,2.640924866458E-017) + ); +#108777 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108778 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108779 = PCURVE('',#108651,#108780); +#108780 = DEFINITIONAL_REPRESENTATION('',(#108781),#108784); +#108781 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108782,#108783), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#106390 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#106391 = CARTESIAN_POINT('',(3.191025391152,1.85)); -#106392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108782 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#108783 = CARTESIAN_POINT('',(3.191025391152,1.85)); +#108784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106393 = PCURVE('',#88416,#106394); -#106394 = DEFINITIONAL_REPRESENTATION('',(#106395),#106403); -#106395 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106396,#106397,#106398, - #106399,#106400,#106401,#106402),.UNSPECIFIED.,.T.,.F.) +#108785 = PCURVE('',#90808,#108786); +#108786 = DEFINITIONAL_REPRESENTATION('',(#108787),#108795); +#108787 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108788,#108789,#108790, + #108791,#108792,#108793,#108794),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#106396 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#106397 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#106398 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#106399 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#106400 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#106401 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#106402 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#106403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106404 = ORIENTED_EDGE('',*,*,#106405,.F.); -#106405 = EDGE_CURVE('',#106406,#106379,#106408,.T.); -#106406 = VERTEX_POINT('',#106407); -#106407 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.E+000)); -#106408 = SURFACE_CURVE('',#106409,(#106413,#106419),.PCURVE_S1.); -#106409 = LINE('',#106410,#106411); -#106410 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#106411 = VECTOR('',#106412,1.); -#106412 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106413 = PCURVE('',#106259,#106414); -#106414 = DEFINITIONAL_REPRESENTATION('',(#106415),#106418); -#106415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106416,#106417), +#108788 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#108789 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#108790 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#108791 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#108792 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#108793 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#108794 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#108795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108796 = ORIENTED_EDGE('',*,*,#108797,.F.); +#108797 = EDGE_CURVE('',#108798,#108771,#108800,.T.); +#108798 = VERTEX_POINT('',#108799); +#108799 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.E+000)); +#108800 = SURFACE_CURVE('',#108801,(#108805,#108811),.PCURVE_S1.); +#108801 = LINE('',#108802,#108803); +#108802 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#108803 = VECTOR('',#108804,1.); +#108804 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108805 = PCURVE('',#108651,#108806); +#108806 = DEFINITIONAL_REPRESENTATION('',(#108807),#108810); +#108807 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108808,#108809), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#106416 = CARTESIAN_POINT('',(1.570796326795,1.65)); -#106417 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#106418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106419 = PCURVE('',#106420,#106425); -#106420 = PLANE('',#106421); -#106421 = AXIS2_PLACEMENT_3D('',#106422,#106423,#106424); -#106422 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#106423 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#106424 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#106425 = DEFINITIONAL_REPRESENTATION('',(#106426),#106430); -#106426 = LINE('',#106427,#106428); -#106427 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#106428 = VECTOR('',#106429,1.); -#106429 = DIRECTION('',(0.E+000,-1.)); -#106430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106431 = ORIENTED_EDGE('',*,*,#106432,.T.); -#106432 = EDGE_CURVE('',#106406,#106165,#106433,.T.); -#106433 = SURFACE_CURVE('',#106434,(#106439,#106445),.PCURVE_S1.); -#106434 = CIRCLE('',#106435,0.308574064194); -#106435 = AXIS2_PLACEMENT_3D('',#106436,#106437,#106438); -#106436 = CARTESIAN_POINT('',(8.35,-0.728168876214,2.640924866458E-017) - ); -#106437 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106438 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106439 = PCURVE('',#106259,#106440); -#106440 = DEFINITIONAL_REPRESENTATION('',(#106441),#106444); -#106441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106442,#106443), +#108808 = CARTESIAN_POINT('',(1.570796326795,1.65)); +#108809 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#108810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108811 = PCURVE('',#108812,#108817); +#108812 = PLANE('',#108813); +#108813 = AXIS2_PLACEMENT_3D('',#108814,#108815,#108816); +#108814 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#108815 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#108816 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108817 = DEFINITIONAL_REPRESENTATION('',(#108818),#108822); +#108818 = LINE('',#108819,#108820); +#108819 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#108820 = VECTOR('',#108821,1.); +#108821 = DIRECTION('',(0.E+000,-1.)); +#108822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108823 = ORIENTED_EDGE('',*,*,#108824,.T.); +#108824 = EDGE_CURVE('',#108798,#108557,#108825,.T.); +#108825 = SURFACE_CURVE('',#108826,(#108831,#108837),.PCURVE_S1.); +#108826 = CIRCLE('',#108827,0.308574064194); +#108827 = AXIS2_PLACEMENT_3D('',#108828,#108829,#108830); +#108828 = CARTESIAN_POINT('',(8.35,-0.728168876214,2.640924866458E-017) + ); +#108829 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108830 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108831 = PCURVE('',#108651,#108832); +#108832 = DEFINITIONAL_REPRESENTATION('',(#108833),#108836); +#108833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108834,#108835), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#106442 = CARTESIAN_POINT('',(1.570796326795,1.65)); -#106443 = CARTESIAN_POINT('',(3.191025391152,1.65)); -#106444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106445 = PCURVE('',#88472,#106446); -#106446 = DEFINITIONAL_REPRESENTATION('',(#106447),#106451); -#106447 = CIRCLE('',#106448,0.308574064194); -#106448 = AXIS2_PLACEMENT_2D('',#106449,#106450); -#106449 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#106450 = DIRECTION('',(1.,0.E+000)); -#106451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106452 = ADVANCED_FACE('',(#106453),#106363,.F.); -#106453 = FACE_BOUND('',#106454,.F.); -#106454 = EDGE_LOOP('',(#106455,#106456,#106483,#106510)); -#106455 = ORIENTED_EDGE('',*,*,#106349,.T.); -#106456 = ORIENTED_EDGE('',*,*,#106457,.F.); -#106457 = EDGE_CURVE('',#106458,#106274,#106460,.T.); -#106458 = VERTEX_POINT('',#106459); -#106459 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.E+000)); -#106460 = SURFACE_CURVE('',#106461,(#106466,#106472),.PCURVE_S1.); -#106461 = CIRCLE('',#106462,0.208574704164); -#106462 = AXIS2_PLACEMENT_3D('',#106463,#106464,#106465); -#106463 = CARTESIAN_POINT('',(8.15,-0.728168876214,2.640924866458E-017) - ); -#106464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106465 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106466 = PCURVE('',#106363,#106467); -#106467 = DEFINITIONAL_REPRESENTATION('',(#106468),#106471); -#106468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106469,#106470), +#108834 = CARTESIAN_POINT('',(1.570796326795,1.65)); +#108835 = CARTESIAN_POINT('',(3.191025391152,1.65)); +#108836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108837 = PCURVE('',#90864,#108838); +#108838 = DEFINITIONAL_REPRESENTATION('',(#108839),#108843); +#108839 = CIRCLE('',#108840,0.308574064194); +#108840 = AXIS2_PLACEMENT_2D('',#108841,#108842); +#108841 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#108842 = DIRECTION('',(1.,0.E+000)); +#108843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108844 = ADVANCED_FACE('',(#108845),#108755,.F.); +#108845 = FACE_BOUND('',#108846,.F.); +#108846 = EDGE_LOOP('',(#108847,#108848,#108875,#108902)); +#108847 = ORIENTED_EDGE('',*,*,#108741,.T.); +#108848 = ORIENTED_EDGE('',*,*,#108849,.F.); +#108849 = EDGE_CURVE('',#108850,#108666,#108852,.T.); +#108850 = VERTEX_POINT('',#108851); +#108851 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.E+000)); +#108852 = SURFACE_CURVE('',#108853,(#108858,#108864),.PCURVE_S1.); +#108853 = CIRCLE('',#108854,0.208574704164); +#108854 = AXIS2_PLACEMENT_3D('',#108855,#108856,#108857); +#108855 = CARTESIAN_POINT('',(8.15,-0.728168876214,2.640924866458E-017) + ); +#108856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108857 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108858 = PCURVE('',#108755,#108859); +#108859 = DEFINITIONAL_REPRESENTATION('',(#108860),#108863); +#108860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108861,#108862), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#106469 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#106470 = CARTESIAN_POINT('',(3.201833915432,1.85)); -#106471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108861 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#108862 = CARTESIAN_POINT('',(3.201833915432,1.85)); +#108863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106472 = PCURVE('',#88416,#106473); -#106473 = DEFINITIONAL_REPRESENTATION('',(#106474),#106482); -#106474 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106475,#106476,#106477, - #106478,#106479,#106480,#106481),.UNSPECIFIED.,.F.,.F.) +#108864 = PCURVE('',#90808,#108865); +#108865 = DEFINITIONAL_REPRESENTATION('',(#108866),#108874); +#108866 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108867,#108868,#108869, + #108870,#108871,#108872,#108873),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#106475 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#106476 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#106477 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#106478 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#106479 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#106480 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#106481 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#106482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106483 = ORIENTED_EDGE('',*,*,#106484,.T.); -#106484 = EDGE_CURVE('',#106458,#106485,#106487,.T.); -#106485 = VERTEX_POINT('',#106486); -#106486 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.E+000)); -#106487 = SURFACE_CURVE('',#106488,(#106492,#106498),.PCURVE_S1.); -#106488 = LINE('',#106489,#106490); -#106489 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#106490 = VECTOR('',#106491,1.); -#106491 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106492 = PCURVE('',#106363,#106493); -#106493 = DEFINITIONAL_REPRESENTATION('',(#106494),#106497); -#106494 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106495,#106496), +#108867 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#108868 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#108869 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#108870 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#108871 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#108872 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#108873 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#108874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108875 = ORIENTED_EDGE('',*,*,#108876,.T.); +#108876 = EDGE_CURVE('',#108850,#108877,#108879,.T.); +#108877 = VERTEX_POINT('',#108878); +#108878 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.E+000)); +#108879 = SURFACE_CURVE('',#108880,(#108884,#108890),.PCURVE_S1.); +#108880 = LINE('',#108881,#108882); +#108881 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#108882 = VECTOR('',#108883,1.); +#108883 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108884 = PCURVE('',#108755,#108885); +#108885 = DEFINITIONAL_REPRESENTATION('',(#108886),#108889); +#108886 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108887,#108888), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#106495 = CARTESIAN_POINT('',(1.570796326795,1.85)); -#106496 = CARTESIAN_POINT('',(1.570796326795,1.65)); -#106497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106498 = PCURVE('',#106499,#106504); -#106499 = PLANE('',#106500); -#106500 = AXIS2_PLACEMENT_3D('',#106501,#106502,#106503); -#106501 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#106502 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#106503 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#106504 = DEFINITIONAL_REPRESENTATION('',(#106505),#106509); -#106505 = LINE('',#106506,#106507); -#106506 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#106507 = VECTOR('',#106508,1.); -#106508 = DIRECTION('',(0.E+000,1.)); -#106509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106510 = ORIENTED_EDGE('',*,*,#106511,.T.); -#106511 = EDGE_CURVE('',#106485,#106327,#106512,.T.); -#106512 = SURFACE_CURVE('',#106513,(#106518,#106524),.PCURVE_S1.); -#106513 = CIRCLE('',#106514,0.208574704164); -#106514 = AXIS2_PLACEMENT_3D('',#106515,#106516,#106517); -#106515 = CARTESIAN_POINT('',(8.35,-0.728168876214,2.640924866458E-017) - ); -#106516 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106517 = DIRECTION('',(0.E+000,0.E+000,1.)); -#106518 = PCURVE('',#106363,#106519); -#106519 = DEFINITIONAL_REPRESENTATION('',(#106520),#106523); -#106520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106521,#106522), +#108887 = CARTESIAN_POINT('',(1.570796326795,1.85)); +#108888 = CARTESIAN_POINT('',(1.570796326795,1.65)); +#108889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108890 = PCURVE('',#108891,#108896); +#108891 = PLANE('',#108892); +#108892 = AXIS2_PLACEMENT_3D('',#108893,#108894,#108895); +#108893 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#108894 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#108895 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#108896 = DEFINITIONAL_REPRESENTATION('',(#108897),#108901); +#108897 = LINE('',#108898,#108899); +#108898 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#108899 = VECTOR('',#108900,1.); +#108900 = DIRECTION('',(0.E+000,1.)); +#108901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108902 = ORIENTED_EDGE('',*,*,#108903,.T.); +#108903 = EDGE_CURVE('',#108877,#108719,#108904,.T.); +#108904 = SURFACE_CURVE('',#108905,(#108910,#108916),.PCURVE_S1.); +#108905 = CIRCLE('',#108906,0.208574704164); +#108906 = AXIS2_PLACEMENT_3D('',#108907,#108908,#108909); +#108907 = CARTESIAN_POINT('',(8.35,-0.728168876214,2.640924866458E-017) + ); +#108908 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#108909 = DIRECTION('',(0.E+000,0.E+000,1.)); +#108910 = PCURVE('',#108755,#108911); +#108911 = DEFINITIONAL_REPRESENTATION('',(#108912),#108915); +#108912 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108913,#108914), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#106521 = CARTESIAN_POINT('',(1.570796326795,1.65)); -#106522 = CARTESIAN_POINT('',(3.201833915432,1.65)); -#106523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106524 = PCURVE('',#88472,#106525); -#106525 = DEFINITIONAL_REPRESENTATION('',(#106526),#106530); -#106526 = CIRCLE('',#106527,0.208574704164); -#106527 = AXIS2_PLACEMENT_2D('',#106528,#106529); -#106528 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#106529 = DIRECTION('',(1.,0.E+000)); -#106530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106531 = ADVANCED_FACE('',(#106532),#106499,.F.); -#106532 = FACE_BOUND('',#106533,.T.); -#106533 = EDGE_LOOP('',(#106534,#106563,#106584,#106585)); -#106534 = ORIENTED_EDGE('',*,*,#106535,.F.); -#106535 = EDGE_CURVE('',#106536,#106538,#106540,.T.); -#106536 = VERTEX_POINT('',#106537); -#106537 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.530776333563)); -#106538 = VERTEX_POINT('',#106539); -#106539 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.530776333563)); -#106540 = SURFACE_CURVE('',#106541,(#106545,#106552),.PCURVE_S1.); -#106541 = LINE('',#106542,#106543); -#106542 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#106543 = VECTOR('',#106544,1.); -#106544 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106545 = PCURVE('',#106499,#106546); -#106546 = DEFINITIONAL_REPRESENTATION('',(#106547),#106551); -#106547 = LINE('',#106548,#106549); -#106548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106549 = VECTOR('',#106550,1.); -#106550 = DIRECTION('',(0.E+000,1.)); -#106551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106552 = PCURVE('',#106553,#106558); -#106553 = CYLINDRICAL_SURFACE('',#106554,0.2192697516); -#106554 = AXIS2_PLACEMENT_3D('',#106555,#106556,#106557); -#106555 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#106556 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106557 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106558 = DEFINITIONAL_REPRESENTATION('',(#106559),#106562); -#106559 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106560,#106561), +#108913 = CARTESIAN_POINT('',(1.570796326795,1.65)); +#108914 = CARTESIAN_POINT('',(3.201833915432,1.65)); +#108915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108916 = PCURVE('',#90864,#108917); +#108917 = DEFINITIONAL_REPRESENTATION('',(#108918),#108922); +#108918 = CIRCLE('',#108919,0.208574704164); +#108919 = AXIS2_PLACEMENT_2D('',#108920,#108921); +#108920 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#108921 = DIRECTION('',(1.,0.E+000)); +#108922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108923 = ADVANCED_FACE('',(#108924),#108891,.F.); +#108924 = FACE_BOUND('',#108925,.T.); +#108925 = EDGE_LOOP('',(#108926,#108955,#108976,#108977)); +#108926 = ORIENTED_EDGE('',*,*,#108927,.F.); +#108927 = EDGE_CURVE('',#108928,#108930,#108932,.T.); +#108928 = VERTEX_POINT('',#108929); +#108929 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.530776333563)); +#108930 = VERTEX_POINT('',#108931); +#108931 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.530776333563)); +#108932 = SURFACE_CURVE('',#108933,(#108937,#108944),.PCURVE_S1.); +#108933 = LINE('',#108934,#108935); +#108934 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#108935 = VECTOR('',#108936,1.); +#108936 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108937 = PCURVE('',#108891,#108938); +#108938 = DEFINITIONAL_REPRESENTATION('',(#108939),#108943); +#108939 = LINE('',#108940,#108941); +#108940 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#108941 = VECTOR('',#108942,1.); +#108942 = DIRECTION('',(0.E+000,1.)); +#108943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108944 = PCURVE('',#108945,#108950); +#108945 = CYLINDRICAL_SURFACE('',#108946,0.2192697516); +#108946 = AXIS2_PLACEMENT_3D('',#108947,#108948,#108949); +#108947 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#108948 = DIRECTION('',(1.,0.E+000,0.E+000)); +#108949 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#108950 = DEFINITIONAL_REPRESENTATION('',(#108951),#108954); +#108951 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108952,#108953), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#106560 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#106561 = CARTESIAN_POINT('',(4.712388980385,-1.65)); -#106562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106563 = ORIENTED_EDGE('',*,*,#106564,.T.); -#106564 = EDGE_CURVE('',#106536,#106458,#106565,.T.); -#106565 = SURFACE_CURVE('',#106566,(#106570,#106577),.PCURVE_S1.); -#106566 = LINE('',#106567,#106568); -#106567 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.530776333563)); -#106568 = VECTOR('',#106569,1.); -#106569 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#106570 = PCURVE('',#106499,#106571); -#106571 = DEFINITIONAL_REPRESENTATION('',(#106572),#106576); -#106572 = LINE('',#106573,#106574); -#106573 = CARTESIAN_POINT('',(0.E+000,-1.85)); -#106574 = VECTOR('',#106575,1.); -#106575 = DIRECTION('',(-1.,0.E+000)); -#106576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106577 = PCURVE('',#88416,#106578); -#106578 = DEFINITIONAL_REPRESENTATION('',(#106579),#106583); -#106579 = LINE('',#106580,#106581); -#106580 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#106581 = VECTOR('',#106582,1.); -#106582 = DIRECTION('',(1.,-1.021336205033E-016)); -#106583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106584 = ORIENTED_EDGE('',*,*,#106484,.T.); -#106585 = ORIENTED_EDGE('',*,*,#106586,.F.); -#106586 = EDGE_CURVE('',#106538,#106485,#106587,.T.); -#106587 = SURFACE_CURVE('',#106588,(#106592,#106599),.PCURVE_S1.); -#106588 = LINE('',#106589,#106590); -#106589 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.530776333563)); -#106590 = VECTOR('',#106591,1.); -#106591 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#106592 = PCURVE('',#106499,#106593); -#106593 = DEFINITIONAL_REPRESENTATION('',(#106594),#106598); -#106594 = LINE('',#106595,#106596); -#106595 = CARTESIAN_POINT('',(0.E+000,-1.65)); -#106596 = VECTOR('',#106597,1.); -#106597 = DIRECTION('',(-1.,0.E+000)); -#106598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106599 = PCURVE('',#88472,#106600); -#106600 = DEFINITIONAL_REPRESENTATION('',(#106601),#106605); -#106601 = LINE('',#106602,#106603); -#106602 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#106603 = VECTOR('',#106604,1.); -#106604 = DIRECTION('',(-1.,-1.021336205033E-016)); -#106605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106606 = ADVANCED_FACE('',(#106607),#106420,.F.); -#106607 = FACE_BOUND('',#106608,.T.); -#106608 = EDGE_LOOP('',(#106609,#106638,#106659,#106660)); -#106609 = ORIENTED_EDGE('',*,*,#106610,.F.); -#106610 = EDGE_CURVE('',#106611,#106613,#106615,.T.); -#106611 = VERTEX_POINT('',#106612); -#106612 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.530776333563)); -#106613 = VERTEX_POINT('',#106614); -#106614 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.530776333563)); -#106615 = SURFACE_CURVE('',#106616,(#106620,#106627),.PCURVE_S1.); -#106616 = LINE('',#106617,#106618); -#106617 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#106618 = VECTOR('',#106619,1.); -#106619 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106620 = PCURVE('',#106420,#106621); -#106621 = DEFINITIONAL_REPRESENTATION('',(#106622),#106626); -#106622 = LINE('',#106623,#106624); -#106623 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106624 = VECTOR('',#106625,1.); -#106625 = DIRECTION('',(0.E+000,-1.)); -#106626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#108952 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#108953 = CARTESIAN_POINT('',(4.712388980385,-1.65)); +#108954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108955 = ORIENTED_EDGE('',*,*,#108956,.T.); +#108956 = EDGE_CURVE('',#108928,#108850,#108957,.T.); +#108957 = SURFACE_CURVE('',#108958,(#108962,#108969),.PCURVE_S1.); +#108958 = LINE('',#108959,#108960); +#108959 = CARTESIAN_POINT('',(8.15,-0.51959417205,0.530776333563)); +#108960 = VECTOR('',#108961,1.); +#108961 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108962 = PCURVE('',#108891,#108963); +#108963 = DEFINITIONAL_REPRESENTATION('',(#108964),#108968); +#108964 = LINE('',#108965,#108966); +#108965 = CARTESIAN_POINT('',(0.E+000,-1.85)); +#108966 = VECTOR('',#108967,1.); +#108967 = DIRECTION('',(-1.,0.E+000)); +#108968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106627 = PCURVE('',#106628,#106633); -#106628 = CYLINDRICAL_SURFACE('',#106629,0.119270391569); -#106629 = AXIS2_PLACEMENT_3D('',#106630,#106631,#106632); -#106630 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#106631 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106632 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106633 = DEFINITIONAL_REPRESENTATION('',(#106634),#106637); -#106634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106635,#106636), +#108969 = PCURVE('',#90808,#108970); +#108970 = DEFINITIONAL_REPRESENTATION('',(#108971),#108975); +#108971 = LINE('',#108972,#108973); +#108972 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#108973 = VECTOR('',#108974,1.); +#108974 = DIRECTION('',(1.,-1.021336205033E-016)); +#108975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108976 = ORIENTED_EDGE('',*,*,#108876,.T.); +#108977 = ORIENTED_EDGE('',*,*,#108978,.F.); +#108978 = EDGE_CURVE('',#108930,#108877,#108979,.T.); +#108979 = SURFACE_CURVE('',#108980,(#108984,#108991),.PCURVE_S1.); +#108980 = LINE('',#108981,#108982); +#108981 = CARTESIAN_POINT('',(8.35,-0.51959417205,0.530776333563)); +#108982 = VECTOR('',#108983,1.); +#108983 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#108984 = PCURVE('',#108891,#108985); +#108985 = DEFINITIONAL_REPRESENTATION('',(#108986),#108990); +#108986 = LINE('',#108987,#108988); +#108987 = CARTESIAN_POINT('',(0.E+000,-1.65)); +#108988 = VECTOR('',#108989,1.); +#108989 = DIRECTION('',(-1.,0.E+000)); +#108990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108991 = PCURVE('',#90864,#108992); +#108992 = DEFINITIONAL_REPRESENTATION('',(#108993),#108997); +#108993 = LINE('',#108994,#108995); +#108994 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#108995 = VECTOR('',#108996,1.); +#108996 = DIRECTION('',(-1.,-1.021336205033E-016)); +#108997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#108998 = ADVANCED_FACE('',(#108999),#108812,.F.); +#108999 = FACE_BOUND('',#109000,.T.); +#109000 = EDGE_LOOP('',(#109001,#109030,#109051,#109052)); +#109001 = ORIENTED_EDGE('',*,*,#109002,.F.); +#109002 = EDGE_CURVE('',#109003,#109005,#109007,.T.); +#109003 = VERTEX_POINT('',#109004); +#109004 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.530776333563)); +#109005 = VERTEX_POINT('',#109006); +#109006 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.530776333563)); +#109007 = SURFACE_CURVE('',#109008,(#109012,#109019),.PCURVE_S1.); +#109008 = LINE('',#109009,#109010); +#109009 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#109010 = VECTOR('',#109011,1.); +#109011 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109012 = PCURVE('',#108812,#109013); +#109013 = DEFINITIONAL_REPRESENTATION('',(#109014),#109018); +#109014 = LINE('',#109015,#109016); +#109015 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109016 = VECTOR('',#109017,1.); +#109017 = DIRECTION('',(0.E+000,-1.)); +#109018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109019 = PCURVE('',#109020,#109025); +#109020 = CYLINDRICAL_SURFACE('',#109021,0.119270391569); +#109021 = AXIS2_PLACEMENT_3D('',#109022,#109023,#109024); +#109022 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#109023 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109024 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109025 = DEFINITIONAL_REPRESENTATION('',(#109026),#109029); +#109026 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109027,#109028), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#106635 = CARTESIAN_POINT('',(4.712388980385,-1.65)); -#106636 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#106637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106638 = ORIENTED_EDGE('',*,*,#106639,.T.); -#106639 = EDGE_CURVE('',#106611,#106406,#106640,.T.); -#106640 = SURFACE_CURVE('',#106641,(#106645,#106652),.PCURVE_S1.); -#106641 = LINE('',#106642,#106643); -#106642 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.530776333563)); -#106643 = VECTOR('',#106644,1.); -#106644 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#106645 = PCURVE('',#106420,#106646); -#106646 = DEFINITIONAL_REPRESENTATION('',(#106647),#106651); -#106647 = LINE('',#106648,#106649); -#106648 = CARTESIAN_POINT('',(0.E+000,-1.65)); -#106649 = VECTOR('',#106650,1.); -#106650 = DIRECTION('',(1.,0.E+000)); -#106651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106652 = PCURVE('',#88472,#106653); -#106653 = DEFINITIONAL_REPRESENTATION('',(#106654),#106658); -#106654 = LINE('',#106655,#106656); -#106655 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#106656 = VECTOR('',#106657,1.); -#106657 = DIRECTION('',(-1.,-1.021336205033E-016)); -#106658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106659 = ORIENTED_EDGE('',*,*,#106405,.T.); -#106660 = ORIENTED_EDGE('',*,*,#106661,.F.); -#106661 = EDGE_CURVE('',#106613,#106379,#106662,.T.); -#106662 = SURFACE_CURVE('',#106663,(#106667,#106674),.PCURVE_S1.); -#106663 = LINE('',#106664,#106665); -#106664 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.530776333563)); -#106665 = VECTOR('',#106666,1.); -#106666 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#106667 = PCURVE('',#106420,#106668); -#106668 = DEFINITIONAL_REPRESENTATION('',(#106669),#106673); -#106669 = LINE('',#106670,#106671); -#106670 = CARTESIAN_POINT('',(0.E+000,-1.85)); -#106671 = VECTOR('',#106672,1.); -#106672 = DIRECTION('',(1.,0.E+000)); -#106673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106674 = PCURVE('',#88416,#106675); -#106675 = DEFINITIONAL_REPRESENTATION('',(#106676),#106680); -#106676 = LINE('',#106677,#106678); -#106677 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#106678 = VECTOR('',#106679,1.); -#106679 = DIRECTION('',(1.,-1.021336205033E-016)); -#106680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106681 = ADVANCED_FACE('',(#106682),#106553,.T.); -#106682 = FACE_BOUND('',#106683,.T.); -#106683 = EDGE_LOOP('',(#106684,#106707,#106708,#106735)); -#106684 = ORIENTED_EDGE('',*,*,#106685,.T.); -#106685 = EDGE_CURVE('',#106686,#106536,#106688,.T.); -#106686 = VERTEX_POINT('',#106687); -#106687 = CARTESIAN_POINT('',(8.15,-0.304819755875,0.75)); -#106688 = SURFACE_CURVE('',#106689,(#106694,#106700),.PCURVE_S1.); -#106689 = CIRCLE('',#106690,0.2192697516); -#106690 = AXIS2_PLACEMENT_3D('',#106691,#106692,#106693); -#106691 = CARTESIAN_POINT('',(8.15,-0.30032442045,0.530776333563)); -#106692 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106693 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106694 = PCURVE('',#106553,#106695); -#106695 = DEFINITIONAL_REPRESENTATION('',(#106696),#106699); -#106696 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106697,#106698), +#109027 = CARTESIAN_POINT('',(4.712388980385,-1.65)); +#109028 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#109029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109030 = ORIENTED_EDGE('',*,*,#109031,.T.); +#109031 = EDGE_CURVE('',#109003,#108798,#109032,.T.); +#109032 = SURFACE_CURVE('',#109033,(#109037,#109044),.PCURVE_S1.); +#109033 = LINE('',#109034,#109035); +#109034 = CARTESIAN_POINT('',(8.35,-0.419594812019,0.530776333563)); +#109035 = VECTOR('',#109036,1.); +#109036 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109037 = PCURVE('',#108812,#109038); +#109038 = DEFINITIONAL_REPRESENTATION('',(#109039),#109043); +#109039 = LINE('',#109040,#109041); +#109040 = CARTESIAN_POINT('',(0.E+000,-1.65)); +#109041 = VECTOR('',#109042,1.); +#109042 = DIRECTION('',(1.,0.E+000)); +#109043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109044 = PCURVE('',#90864,#109045); +#109045 = DEFINITIONAL_REPRESENTATION('',(#109046),#109050); +#109046 = LINE('',#109047,#109048); +#109047 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#109048 = VECTOR('',#109049,1.); +#109049 = DIRECTION('',(-1.,-1.021336205033E-016)); +#109050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109051 = ORIENTED_EDGE('',*,*,#108797,.T.); +#109052 = ORIENTED_EDGE('',*,*,#109053,.F.); +#109053 = EDGE_CURVE('',#109005,#108771,#109054,.T.); +#109054 = SURFACE_CURVE('',#109055,(#109059,#109066),.PCURVE_S1.); +#109055 = LINE('',#109056,#109057); +#109056 = CARTESIAN_POINT('',(8.15,-0.419594812019,0.530776333563)); +#109057 = VECTOR('',#109058,1.); +#109058 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109059 = PCURVE('',#108812,#109060); +#109060 = DEFINITIONAL_REPRESENTATION('',(#109061),#109065); +#109061 = LINE('',#109062,#109063); +#109062 = CARTESIAN_POINT('',(0.E+000,-1.85)); +#109063 = VECTOR('',#109064,1.); +#109064 = DIRECTION('',(1.,0.E+000)); +#109065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109066 = PCURVE('',#90808,#109067); +#109067 = DEFINITIONAL_REPRESENTATION('',(#109068),#109072); +#109068 = LINE('',#109069,#109070); +#109069 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#109070 = VECTOR('',#109071,1.); +#109071 = DIRECTION('',(1.,-1.021336205033E-016)); +#109072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109073 = ADVANCED_FACE('',(#109074),#108945,.T.); +#109074 = FACE_BOUND('',#109075,.T.); +#109075 = EDGE_LOOP('',(#109076,#109099,#109100,#109127)); +#109076 = ORIENTED_EDGE('',*,*,#109077,.T.); +#109077 = EDGE_CURVE('',#109078,#108928,#109080,.T.); +#109078 = VERTEX_POINT('',#109079); +#109079 = CARTESIAN_POINT('',(8.15,-0.304819755875,0.75)); +#109080 = SURFACE_CURVE('',#109081,(#109086,#109092),.PCURVE_S1.); +#109081 = CIRCLE('',#109082,0.2192697516); +#109082 = AXIS2_PLACEMENT_3D('',#109083,#109084,#109085); +#109083 = CARTESIAN_POINT('',(8.15,-0.30032442045,0.530776333563)); +#109084 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109085 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109086 = PCURVE('',#108945,#109087); +#109087 = DEFINITIONAL_REPRESENTATION('',(#109088),#109091); +#109088 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109089,#109090), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#106697 = CARTESIAN_POINT('',(3.162095483347,-1.85)); -#106698 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#106699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109089 = CARTESIAN_POINT('',(3.162095483347,-1.85)); +#109090 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#109091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109092 = PCURVE('',#90808,#109093); +#109093 = DEFINITIONAL_REPRESENTATION('',(#109094),#109098); +#109094 = CIRCLE('',#109095,0.2192697516); +#109095 = AXIS2_PLACEMENT_2D('',#109096,#109097); +#109096 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#109097 = DIRECTION('',(1.,0.E+000)); +#109098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106700 = PCURVE('',#88416,#106701); -#106701 = DEFINITIONAL_REPRESENTATION('',(#106702),#106706); -#106702 = CIRCLE('',#106703,0.2192697516); -#106703 = AXIS2_PLACEMENT_2D('',#106704,#106705); -#106704 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#106705 = DIRECTION('',(1.,0.E+000)); -#106706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106707 = ORIENTED_EDGE('',*,*,#106535,.T.); -#106708 = ORIENTED_EDGE('',*,*,#106709,.F.); -#106709 = EDGE_CURVE('',#106710,#106538,#106712,.T.); -#106710 = VERTEX_POINT('',#106711); -#106711 = CARTESIAN_POINT('',(8.35,-0.304819755875,0.75)); -#106712 = SURFACE_CURVE('',#106713,(#106718,#106724),.PCURVE_S1.); -#106713 = CIRCLE('',#106714,0.2192697516); -#106714 = AXIS2_PLACEMENT_3D('',#106715,#106716,#106717); -#106715 = CARTESIAN_POINT('',(8.35,-0.30032442045,0.530776333563)); -#106716 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106717 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106718 = PCURVE('',#106553,#106719); -#106719 = DEFINITIONAL_REPRESENTATION('',(#106720),#106723); -#106720 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106721,#106722), +#109099 = ORIENTED_EDGE('',*,*,#108927,.T.); +#109100 = ORIENTED_EDGE('',*,*,#109101,.F.); +#109101 = EDGE_CURVE('',#109102,#108930,#109104,.T.); +#109102 = VERTEX_POINT('',#109103); +#109103 = CARTESIAN_POINT('',(8.35,-0.304819755875,0.75)); +#109104 = SURFACE_CURVE('',#109105,(#109110,#109116),.PCURVE_S1.); +#109105 = CIRCLE('',#109106,0.2192697516); +#109106 = AXIS2_PLACEMENT_3D('',#109107,#109108,#109109); +#109107 = CARTESIAN_POINT('',(8.35,-0.30032442045,0.530776333563)); +#109108 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109109 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109110 = PCURVE('',#108945,#109111); +#109111 = DEFINITIONAL_REPRESENTATION('',(#109112),#109115); +#109112 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109113,#109114), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#106721 = CARTESIAN_POINT('',(3.162095483347,-1.65)); -#106722 = CARTESIAN_POINT('',(4.712388980385,-1.65)); -#106723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109113 = CARTESIAN_POINT('',(3.162095483347,-1.65)); +#109114 = CARTESIAN_POINT('',(4.712388980385,-1.65)); +#109115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106724 = PCURVE('',#88472,#106725); -#106725 = DEFINITIONAL_REPRESENTATION('',(#106726),#106734); -#106726 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106727,#106728,#106729, - #106730,#106731,#106732,#106733),.UNSPECIFIED.,.T.,.F.) +#109116 = PCURVE('',#90864,#109117); +#109117 = DEFINITIONAL_REPRESENTATION('',(#109118),#109126); +#109118 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109119,#109120,#109121, + #109122,#109123,#109124,#109125),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#106727 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#106728 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#106729 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#106730 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#106731 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#106732 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#106733 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#106734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106735 = ORIENTED_EDGE('',*,*,#106736,.T.); -#106736 = EDGE_CURVE('',#106710,#106686,#106737,.T.); -#106737 = SURFACE_CURVE('',#106738,(#106742,#106748),.PCURVE_S1.); -#106738 = LINE('',#106739,#106740); -#106739 = CARTESIAN_POINT('',(8.15,-0.304819755875,0.75)); -#106740 = VECTOR('',#106741,1.); -#106741 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#106742 = PCURVE('',#106553,#106743); -#106743 = DEFINITIONAL_REPRESENTATION('',(#106744),#106747); -#106744 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106745,#106746), +#109119 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#109120 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#109121 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#109122 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#109123 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#109124 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#109125 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#109126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109127 = ORIENTED_EDGE('',*,*,#109128,.T.); +#109128 = EDGE_CURVE('',#109102,#109078,#109129,.T.); +#109129 = SURFACE_CURVE('',#109130,(#109134,#109140),.PCURVE_S1.); +#109130 = LINE('',#109131,#109132); +#109131 = CARTESIAN_POINT('',(8.15,-0.304819755875,0.75)); +#109132 = VECTOR('',#109133,1.); +#109133 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109134 = PCURVE('',#108945,#109135); +#109135 = DEFINITIONAL_REPRESENTATION('',(#109136),#109139); +#109136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109137,#109138), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#106745 = CARTESIAN_POINT('',(3.162095483347,-1.65)); -#106746 = CARTESIAN_POINT('',(3.162095483347,-1.85)); -#106747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106748 = PCURVE('',#88444,#106749); -#106749 = DEFINITIONAL_REPRESENTATION('',(#106750),#106754); -#106750 = LINE('',#106751,#106752); -#106751 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#106752 = VECTOR('',#106753,1.); -#106753 = DIRECTION('',(0.E+000,-1.)); -#106754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106755 = ADVANCED_FACE('',(#106756),#106628,.F.); -#106756 = FACE_BOUND('',#106757,.F.); -#106757 = EDGE_LOOP('',(#106758,#106785,#106807,#106828)); -#106758 = ORIENTED_EDGE('',*,*,#106759,.F.); -#106759 = EDGE_CURVE('',#106760,#106611,#106762,.T.); -#106760 = VERTEX_POINT('',#106761); -#106761 = CARTESIAN_POINT('',(8.35,-0.303662633502,0.65)); -#106762 = SURFACE_CURVE('',#106763,(#106768,#106774),.PCURVE_S1.); -#106763 = CIRCLE('',#106764,0.119270391569); -#106764 = AXIS2_PLACEMENT_3D('',#106765,#106766,#106767); -#106765 = CARTESIAN_POINT('',(8.35,-0.30032442045,0.530776333563)); -#106766 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106767 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106768 = PCURVE('',#106628,#106769); -#106769 = DEFINITIONAL_REPRESENTATION('',(#106770),#106773); -#106770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106771,#106772), +#109137 = CARTESIAN_POINT('',(3.162095483347,-1.65)); +#109138 = CARTESIAN_POINT('',(3.162095483347,-1.85)); +#109139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109140 = PCURVE('',#90836,#109141); +#109141 = DEFINITIONAL_REPRESENTATION('',(#109142),#109146); +#109142 = LINE('',#109143,#109144); +#109143 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#109144 = VECTOR('',#109145,1.); +#109145 = DIRECTION('',(0.E+000,-1.)); +#109146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109147 = ADVANCED_FACE('',(#109148),#109020,.F.); +#109148 = FACE_BOUND('',#109149,.F.); +#109149 = EDGE_LOOP('',(#109150,#109177,#109199,#109220)); +#109150 = ORIENTED_EDGE('',*,*,#109151,.F.); +#109151 = EDGE_CURVE('',#109152,#109003,#109154,.T.); +#109152 = VERTEX_POINT('',#109153); +#109153 = CARTESIAN_POINT('',(8.35,-0.303662633502,0.65)); +#109154 = SURFACE_CURVE('',#109155,(#109160,#109166),.PCURVE_S1.); +#109155 = CIRCLE('',#109156,0.119270391569); +#109156 = AXIS2_PLACEMENT_3D('',#109157,#109158,#109159); +#109157 = CARTESIAN_POINT('',(8.35,-0.30032442045,0.530776333563)); +#109158 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109159 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109160 = PCURVE('',#109020,#109161); +#109161 = DEFINITIONAL_REPRESENTATION('',(#109162),#109165); +#109162 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109163,#109164), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#106771 = CARTESIAN_POINT('',(3.169584923929,-1.65)); -#106772 = CARTESIAN_POINT('',(4.712388980385,-1.65)); -#106773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109163 = CARTESIAN_POINT('',(3.169584923929,-1.65)); +#109164 = CARTESIAN_POINT('',(4.712388980385,-1.65)); +#109165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#106774 = PCURVE('',#88472,#106775); -#106775 = DEFINITIONAL_REPRESENTATION('',(#106776),#106784); -#106776 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#106777,#106778,#106779, - #106780,#106781,#106782,#106783),.UNSPECIFIED.,.F.,.F.) +#109166 = PCURVE('',#90864,#109167); +#109167 = DEFINITIONAL_REPRESENTATION('',(#109168),#109176); +#109168 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109169,#109170,#109171, + #109172,#109173,#109174,#109175),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#106777 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#106778 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#106779 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#106780 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#106781 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#106782 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#106783 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#106784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106785 = ORIENTED_EDGE('',*,*,#106786,.F.); -#106786 = EDGE_CURVE('',#106787,#106760,#106789,.T.); -#106787 = VERTEX_POINT('',#106788); -#106788 = CARTESIAN_POINT('',(8.15,-0.303662633502,0.65)); -#106789 = SURFACE_CURVE('',#106790,(#106794,#106800),.PCURVE_S1.); -#106790 = LINE('',#106791,#106792); -#106791 = CARTESIAN_POINT('',(8.15,-0.303662633502,0.65)); -#106792 = VECTOR('',#106793,1.); -#106793 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106794 = PCURVE('',#106628,#106795); -#106795 = DEFINITIONAL_REPRESENTATION('',(#106796),#106799); -#106796 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106797,#106798), +#109169 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#109170 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#109171 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#109172 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#109173 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#109174 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#109175 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#109176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109177 = ORIENTED_EDGE('',*,*,#109178,.F.); +#109178 = EDGE_CURVE('',#109179,#109152,#109181,.T.); +#109179 = VERTEX_POINT('',#109180); +#109180 = CARTESIAN_POINT('',(8.15,-0.303662633502,0.65)); +#109181 = SURFACE_CURVE('',#109182,(#109186,#109192),.PCURVE_S1.); +#109182 = LINE('',#109183,#109184); +#109183 = CARTESIAN_POINT('',(8.15,-0.303662633502,0.65)); +#109184 = VECTOR('',#109185,1.); +#109185 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109186 = PCURVE('',#109020,#109187); +#109187 = DEFINITIONAL_REPRESENTATION('',(#109188),#109191); +#109188 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109189,#109190), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#106797 = CARTESIAN_POINT('',(3.169584923929,-1.85)); -#106798 = CARTESIAN_POINT('',(3.169584923929,-1.65)); -#106799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106800 = PCURVE('',#88498,#106801); -#106801 = DEFINITIONAL_REPRESENTATION('',(#106802),#106806); -#106802 = LINE('',#106803,#106804); -#106803 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#106804 = VECTOR('',#106805,1.); -#106805 = DIRECTION('',(0.E+000,1.)); -#106806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106807 = ORIENTED_EDGE('',*,*,#106808,.T.); -#106808 = EDGE_CURVE('',#106787,#106613,#106809,.T.); -#106809 = SURFACE_CURVE('',#106810,(#106815,#106821),.PCURVE_S1.); -#106810 = CIRCLE('',#106811,0.119270391569); -#106811 = AXIS2_PLACEMENT_3D('',#106812,#106813,#106814); -#106812 = CARTESIAN_POINT('',(8.15,-0.30032442045,0.530776333563)); -#106813 = DIRECTION('',(1.,0.E+000,0.E+000)); -#106814 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#106815 = PCURVE('',#106628,#106816); -#106816 = DEFINITIONAL_REPRESENTATION('',(#106817),#106820); -#106817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#106818,#106819), +#109189 = CARTESIAN_POINT('',(3.169584923929,-1.85)); +#109190 = CARTESIAN_POINT('',(3.169584923929,-1.65)); +#109191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109192 = PCURVE('',#90890,#109193); +#109193 = DEFINITIONAL_REPRESENTATION('',(#109194),#109198); +#109194 = LINE('',#109195,#109196); +#109195 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#109196 = VECTOR('',#109197,1.); +#109197 = DIRECTION('',(0.E+000,1.)); +#109198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109199 = ORIENTED_EDGE('',*,*,#109200,.T.); +#109200 = EDGE_CURVE('',#109179,#109005,#109201,.T.); +#109201 = SURFACE_CURVE('',#109202,(#109207,#109213),.PCURVE_S1.); +#109202 = CIRCLE('',#109203,0.119270391569); +#109203 = AXIS2_PLACEMENT_3D('',#109204,#109205,#109206); +#109204 = CARTESIAN_POINT('',(8.15,-0.30032442045,0.530776333563)); +#109205 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109206 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109207 = PCURVE('',#109020,#109208); +#109208 = DEFINITIONAL_REPRESENTATION('',(#109209),#109212); +#109209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109210,#109211), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#106818 = CARTESIAN_POINT('',(3.169584923929,-1.85)); -#106819 = CARTESIAN_POINT('',(4.712388980385,-1.85)); -#106820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106821 = PCURVE('',#88416,#106822); -#106822 = DEFINITIONAL_REPRESENTATION('',(#106823),#106827); -#106823 = CIRCLE('',#106824,0.119270391569); -#106824 = AXIS2_PLACEMENT_2D('',#106825,#106826); -#106825 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#106826 = DIRECTION('',(1.,0.E+000)); -#106827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106828 = ORIENTED_EDGE('',*,*,#106610,.F.); -#106829 = ADVANCED_FACE('',(#106830),#88416,.F.); -#106830 = FACE_BOUND('',#106831,.T.); -#106831 = EDGE_LOOP('',(#106832,#106853,#106854,#106855,#106856,#106857, - #106878,#106879,#106880,#106881,#106882,#106903)); -#106832 = ORIENTED_EDGE('',*,*,#106833,.F.); -#106833 = EDGE_CURVE('',#106787,#88396,#106834,.T.); -#106834 = SURFACE_CURVE('',#106835,(#106839,#106846),.PCURVE_S1.); -#106835 = LINE('',#106836,#106837); -#106836 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); -#106837 = VECTOR('',#106838,1.); -#106838 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106839 = PCURVE('',#88416,#106840); -#106840 = DEFINITIONAL_REPRESENTATION('',(#106841),#106845); -#106841 = LINE('',#106842,#106843); -#106842 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106843 = VECTOR('',#106844,1.); -#106844 = DIRECTION('',(-3.563627120235E-016,1.)); -#106845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106846 = PCURVE('',#88498,#106847); -#106847 = DEFINITIONAL_REPRESENTATION('',(#106848),#106852); -#106848 = LINE('',#106849,#106850); -#106849 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106850 = VECTOR('',#106851,1.); -#106851 = DIRECTION('',(-1.,0.E+000)); -#106852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106853 = ORIENTED_EDGE('',*,*,#106808,.T.); -#106854 = ORIENTED_EDGE('',*,*,#106661,.T.); -#106855 = ORIENTED_EDGE('',*,*,#106378,.T.); -#106856 = ORIENTED_EDGE('',*,*,#106222,.T.); -#106857 = ORIENTED_EDGE('',*,*,#106858,.T.); -#106858 = EDGE_CURVE('',#106195,#106276,#106859,.T.); -#106859 = SURFACE_CURVE('',#106860,(#106864,#106871),.PCURVE_S1.); -#106860 = LINE('',#106861,#106862); -#106861 = CARTESIAN_POINT('',(8.15,-1.,1.159810404338E-002)); -#106862 = VECTOR('',#106863,1.); -#106863 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#106864 = PCURVE('',#88416,#106865); -#106865 = DEFINITIONAL_REPRESENTATION('',(#106866),#106870); -#106866 = LINE('',#106867,#106868); -#106867 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#106868 = VECTOR('',#106869,1.); -#106869 = DIRECTION('',(-1.,-2.101748079665E-016)); -#106870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106871 = PCURVE('',#106210,#106872); -#106872 = DEFINITIONAL_REPRESENTATION('',(#106873),#106877); -#106873 = LINE('',#106874,#106875); -#106874 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#106875 = VECTOR('',#106876,1.); -#106876 = DIRECTION('',(-1.,0.E+000)); -#106877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106878 = ORIENTED_EDGE('',*,*,#106273,.F.); -#106879 = ORIENTED_EDGE('',*,*,#106457,.F.); -#106880 = ORIENTED_EDGE('',*,*,#106564,.F.); -#106881 = ORIENTED_EDGE('',*,*,#106685,.F.); -#106882 = ORIENTED_EDGE('',*,*,#106883,.T.); -#106883 = EDGE_CURVE('',#106686,#88394,#106884,.T.); -#106884 = SURFACE_CURVE('',#106885,(#106889,#106896),.PCURVE_S1.); -#106885 = LINE('',#106886,#106887); -#106886 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.75)); -#106887 = VECTOR('',#106888,1.); -#106888 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106889 = PCURVE('',#88416,#106890); -#106890 = DEFINITIONAL_REPRESENTATION('',(#106891),#106895); -#106891 = LINE('',#106892,#106893); -#106892 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#106893 = VECTOR('',#106894,1.); -#106894 = DIRECTION('',(-3.563627120235E-016,1.)); -#106895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106896 = PCURVE('',#88444,#106897); -#106897 = DEFINITIONAL_REPRESENTATION('',(#106898),#106902); -#106898 = LINE('',#106899,#106900); -#106899 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106900 = VECTOR('',#106901,1.); -#106901 = DIRECTION('',(1.,0.E+000)); -#106902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106903 = ORIENTED_EDGE('',*,*,#88393,.T.); -#106904 = ADVANCED_FACE('',(#106905),#88444,.F.); -#106905 = FACE_BOUND('',#106906,.T.); -#106906 = EDGE_LOOP('',(#106907,#106908,#106929,#106930)); -#106907 = ORIENTED_EDGE('',*,*,#106736,.F.); -#106908 = ORIENTED_EDGE('',*,*,#106909,.T.); -#106909 = EDGE_CURVE('',#106710,#88429,#106910,.T.); -#106910 = SURFACE_CURVE('',#106911,(#106915,#106922),.PCURVE_S1.); -#106911 = LINE('',#106912,#106913); -#106912 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.75)); -#106913 = VECTOR('',#106914,1.); -#106914 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106915 = PCURVE('',#88444,#106916); -#106916 = DEFINITIONAL_REPRESENTATION('',(#106917),#106921); -#106917 = LINE('',#106918,#106919); -#106918 = CARTESIAN_POINT('',(0.E+000,0.2)); -#106919 = VECTOR('',#106920,1.); -#106920 = DIRECTION('',(1.,0.E+000)); -#106921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106922 = PCURVE('',#88472,#106923); -#106923 = DEFINITIONAL_REPRESENTATION('',(#106924),#106928); -#106924 = LINE('',#106925,#106926); -#106925 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#106926 = VECTOR('',#106927,1.); -#106927 = DIRECTION('',(3.563627120235E-016,1.)); -#106928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106929 = ORIENTED_EDGE('',*,*,#88428,.T.); -#106930 = ORIENTED_EDGE('',*,*,#106883,.F.); -#106931 = ADVANCED_FACE('',(#106932),#88472,.F.); -#106932 = FACE_BOUND('',#106933,.T.); -#106933 = EDGE_LOOP('',(#106934,#106935,#106936,#106937,#106938,#106939, - #106960,#106961,#106962,#106963,#106964,#106985)); -#106934 = ORIENTED_EDGE('',*,*,#106909,.F.); -#106935 = ORIENTED_EDGE('',*,*,#106709,.T.); -#106936 = ORIENTED_EDGE('',*,*,#106586,.T.); -#106937 = ORIENTED_EDGE('',*,*,#106511,.T.); -#106938 = ORIENTED_EDGE('',*,*,#106326,.T.); -#106939 = ORIENTED_EDGE('',*,*,#106940,.T.); -#106940 = EDGE_CURVE('',#106304,#106167,#106941,.T.); -#106941 = SURFACE_CURVE('',#106942,(#106946,#106953),.PCURVE_S1.); -#106942 = LINE('',#106943,#106944); -#106943 = CARTESIAN_POINT('',(8.35,-1.,1.159810404338E-002)); -#106944 = VECTOR('',#106945,1.); -#106945 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#106946 = PCURVE('',#88472,#106947); -#106947 = DEFINITIONAL_REPRESENTATION('',(#106948),#106952); -#106948 = LINE('',#106949,#106950); -#106949 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#106950 = VECTOR('',#106951,1.); -#106951 = DIRECTION('',(-1.,2.101748079665E-016)); -#106952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106953 = PCURVE('',#106210,#106954); -#106954 = DEFINITIONAL_REPRESENTATION('',(#106955),#106959); -#106955 = LINE('',#106956,#106957); -#106956 = CARTESIAN_POINT('',(-0.269794846371,0.1)); -#106957 = VECTOR('',#106958,1.); -#106958 = DIRECTION('',(1.,0.E+000)); -#106959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106960 = ORIENTED_EDGE('',*,*,#106164,.F.); -#106961 = ORIENTED_EDGE('',*,*,#106432,.F.); -#106962 = ORIENTED_EDGE('',*,*,#106639,.F.); -#106963 = ORIENTED_EDGE('',*,*,#106759,.F.); -#106964 = ORIENTED_EDGE('',*,*,#106965,.T.); -#106965 = EDGE_CURVE('',#106760,#88457,#106966,.T.); -#106966 = SURFACE_CURVE('',#106967,(#106971,#106978),.PCURVE_S1.); -#106967 = LINE('',#106968,#106969); -#106968 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.65)); -#106969 = VECTOR('',#106970,1.); -#106970 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#106971 = PCURVE('',#88472,#106972); -#106972 = DEFINITIONAL_REPRESENTATION('',(#106973),#106977); -#106973 = LINE('',#106974,#106975); -#106974 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#106975 = VECTOR('',#106976,1.); -#106976 = DIRECTION('',(3.563627120235E-016,1.)); -#106977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106978 = PCURVE('',#88498,#106979); -#106979 = DEFINITIONAL_REPRESENTATION('',(#106980),#106984); -#106980 = LINE('',#106981,#106982); -#106981 = CARTESIAN_POINT('',(0.E+000,0.2)); -#106982 = VECTOR('',#106983,1.); -#106983 = DIRECTION('',(-1.,0.E+000)); -#106984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#106985 = ORIENTED_EDGE('',*,*,#88456,.T.); -#106986 = ADVANCED_FACE('',(#106987),#88498,.F.); -#106987 = FACE_BOUND('',#106988,.T.); -#106988 = EDGE_LOOP('',(#106989,#106990,#106991,#106992)); -#106989 = ORIENTED_EDGE('',*,*,#106786,.F.); -#106990 = ORIENTED_EDGE('',*,*,#106833,.T.); -#106991 = ORIENTED_EDGE('',*,*,#88484,.T.); -#106992 = ORIENTED_EDGE('',*,*,#106965,.F.); -#106993 = ADVANCED_FACE('',(#106994),#106210,.T.); -#106994 = FACE_BOUND('',#106995,.T.); -#106995 = EDGE_LOOP('',(#106996,#106997,#106998,#106999)); -#106996 = ORIENTED_EDGE('',*,*,#106940,.F.); -#106997 = ORIENTED_EDGE('',*,*,#106303,.F.); -#106998 = ORIENTED_EDGE('',*,*,#106858,.F.); -#106999 = ORIENTED_EDGE('',*,*,#106194,.F.); -#107000 = ADVANCED_FACE('',(#107001),#107015,.T.); -#107001 = FACE_BOUND('',#107002,.T.); -#107002 = EDGE_LOOP('',(#107003,#107033,#107061,#107084)); -#107003 = ORIENTED_EDGE('',*,*,#107004,.T.); -#107004 = EDGE_CURVE('',#107005,#107007,#107009,.T.); -#107005 = VERTEX_POINT('',#107006); -#107006 = CARTESIAN_POINT('',(8.85,-0.74341632541,-0.308197125857)); -#107007 = VERTEX_POINT('',#107008); -#107008 = CARTESIAN_POINT('',(8.85,-1.,-0.308197125857)); -#107009 = SURFACE_CURVE('',#107010,(#107014,#107026),.PCURVE_S1.); -#107010 = LINE('',#107011,#107012); -#107011 = CARTESIAN_POINT('',(8.85,-0.74341632541,-0.308197125857)); -#107012 = VECTOR('',#107013,1.); -#107013 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#107014 = PCURVE('',#107015,#107020); -#107015 = PLANE('',#107016); -#107016 = AXIS2_PLACEMENT_3D('',#107017,#107018,#107019); -#107017 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#107018 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107019 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107020 = DEFINITIONAL_REPRESENTATION('',(#107021),#107025); -#107021 = LINE('',#107022,#107023); -#107022 = CARTESIAN_POINT('',(1.15,0.E+000)); -#107023 = VECTOR('',#107024,1.); -#107024 = DIRECTION('',(0.E+000,-1.)); -#107025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107026 = PCURVE('',#90291,#107027); -#107027 = DEFINITIONAL_REPRESENTATION('',(#107028),#107032); -#107028 = LINE('',#107029,#107030); -#107029 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#107030 = VECTOR('',#107031,1.); -#107031 = DIRECTION('',(0.E+000,-1.)); -#107032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107033 = ORIENTED_EDGE('',*,*,#107034,.T.); -#107034 = EDGE_CURVE('',#107007,#107035,#107037,.T.); -#107035 = VERTEX_POINT('',#107036); -#107036 = CARTESIAN_POINT('',(8.65,-1.,-0.308197125857)); -#107037 = SURFACE_CURVE('',#107038,(#107042,#107049),.PCURVE_S1.); -#107038 = LINE('',#107039,#107040); -#107039 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); -#107040 = VECTOR('',#107041,1.); -#107041 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107042 = PCURVE('',#107015,#107043); -#107043 = DEFINITIONAL_REPRESENTATION('',(#107044),#107048); -#107044 = LINE('',#107045,#107046); -#107045 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); -#107046 = VECTOR('',#107047,1.); -#107047 = DIRECTION('',(1.,0.E+000)); -#107048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107049 = PCURVE('',#107050,#107055); -#107050 = PLANE('',#107051); -#107051 = AXIS2_PLACEMENT_3D('',#107052,#107053,#107054); -#107052 = CARTESIAN_POINT('',(8.75,-1.,-0.258196742327)); -#107053 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); -#107054 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#107055 = DEFINITIONAL_REPRESENTATION('',(#107056),#107060); -#107056 = LINE('',#107057,#107058); -#107057 = CARTESIAN_POINT('',(5.000038352949E-002,1.25)); -#107058 = VECTOR('',#107059,1.); -#107059 = DIRECTION('',(0.E+000,-1.)); -#107060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107061 = ORIENTED_EDGE('',*,*,#107062,.F.); -#107062 = EDGE_CURVE('',#107063,#107035,#107065,.T.); -#107063 = VERTEX_POINT('',#107064); -#107064 = CARTESIAN_POINT('',(8.65,-0.74341632541,-0.308197125857)); -#107065 = SURFACE_CURVE('',#107066,(#107070,#107077),.PCURVE_S1.); -#107066 = LINE('',#107067,#107068); -#107067 = CARTESIAN_POINT('',(8.65,-0.74341632541,-0.308197125857)); -#107068 = VECTOR('',#107069,1.); -#107069 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#107070 = PCURVE('',#107015,#107071); -#107071 = DEFINITIONAL_REPRESENTATION('',(#107072),#107076); -#107072 = LINE('',#107073,#107074); -#107073 = CARTESIAN_POINT('',(1.35,0.E+000)); -#107074 = VECTOR('',#107075,1.); -#107075 = DIRECTION('',(0.E+000,-1.)); -#107076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107077 = PCURVE('',#90235,#107078); -#107078 = DEFINITIONAL_REPRESENTATION('',(#107079),#107083); -#107079 = LINE('',#107080,#107081); -#107080 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#107081 = VECTOR('',#107082,1.); -#107082 = DIRECTION('',(0.E+000,-1.)); -#107083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107084 = ORIENTED_EDGE('',*,*,#107085,.T.); -#107085 = EDGE_CURVE('',#107063,#107005,#107086,.T.); -#107086 = SURFACE_CURVE('',#107087,(#107091,#107098),.PCURVE_S1.); -#107087 = LINE('',#107088,#107089); -#107088 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); -#107089 = VECTOR('',#107090,1.); -#107090 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107091 = PCURVE('',#107015,#107092); -#107092 = DEFINITIONAL_REPRESENTATION('',(#107093),#107097); -#107093 = LINE('',#107094,#107095); -#107094 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107095 = VECTOR('',#107096,1.); -#107096 = DIRECTION('',(-1.,0.E+000)); -#107097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107098 = PCURVE('',#107099,#107104); -#107099 = CYLINDRICAL_SURFACE('',#107100,0.308574064194); -#107100 = AXIS2_PLACEMENT_3D('',#107101,#107102,#107103); -#107101 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#107102 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107103 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107104 = DEFINITIONAL_REPRESENTATION('',(#107105),#107108); -#107105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107106,#107107), +#109210 = CARTESIAN_POINT('',(3.169584923929,-1.85)); +#109211 = CARTESIAN_POINT('',(4.712388980385,-1.85)); +#109212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109213 = PCURVE('',#90808,#109214); +#109214 = DEFINITIONAL_REPRESENTATION('',(#109215),#109219); +#109215 = CIRCLE('',#109216,0.119270391569); +#109216 = AXIS2_PLACEMENT_2D('',#109217,#109218); +#109217 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#109218 = DIRECTION('',(1.,0.E+000)); +#109219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109220 = ORIENTED_EDGE('',*,*,#109002,.F.); +#109221 = ADVANCED_FACE('',(#109222),#90808,.F.); +#109222 = FACE_BOUND('',#109223,.T.); +#109223 = EDGE_LOOP('',(#109224,#109245,#109246,#109247,#109248,#109249, + #109270,#109271,#109272,#109273,#109274,#109295)); +#109224 = ORIENTED_EDGE('',*,*,#109225,.F.); +#109225 = EDGE_CURVE('',#109179,#90788,#109226,.T.); +#109226 = SURFACE_CURVE('',#109227,(#109231,#109238),.PCURVE_S1.); +#109227 = LINE('',#109228,#109229); +#109228 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.65)); +#109229 = VECTOR('',#109230,1.); +#109230 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#109231 = PCURVE('',#90808,#109232); +#109232 = DEFINITIONAL_REPRESENTATION('',(#109233),#109237); +#109233 = LINE('',#109234,#109235); +#109234 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109235 = VECTOR('',#109236,1.); +#109236 = DIRECTION('',(-3.563627120235E-016,1.)); +#109237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109238 = PCURVE('',#90890,#109239); +#109239 = DEFINITIONAL_REPRESENTATION('',(#109240),#109244); +#109240 = LINE('',#109241,#109242); +#109241 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109242 = VECTOR('',#109243,1.); +#109243 = DIRECTION('',(-1.,0.E+000)); +#109244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109245 = ORIENTED_EDGE('',*,*,#109200,.T.); +#109246 = ORIENTED_EDGE('',*,*,#109053,.T.); +#109247 = ORIENTED_EDGE('',*,*,#108770,.T.); +#109248 = ORIENTED_EDGE('',*,*,#108614,.T.); +#109249 = ORIENTED_EDGE('',*,*,#109250,.T.); +#109250 = EDGE_CURVE('',#108587,#108668,#109251,.T.); +#109251 = SURFACE_CURVE('',#109252,(#109256,#109263),.PCURVE_S1.); +#109252 = LINE('',#109253,#109254); +#109253 = CARTESIAN_POINT('',(8.15,-1.,1.159810404338E-002)); +#109254 = VECTOR('',#109255,1.); +#109255 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#109256 = PCURVE('',#90808,#109257); +#109257 = DEFINITIONAL_REPRESENTATION('',(#109258),#109262); +#109258 = LINE('',#109259,#109260); +#109259 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#109260 = VECTOR('',#109261,1.); +#109261 = DIRECTION('',(-1.,-2.101748079665E-016)); +#109262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109263 = PCURVE('',#108602,#109264); +#109264 = DEFINITIONAL_REPRESENTATION('',(#109265),#109269); +#109265 = LINE('',#109266,#109267); +#109266 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#109267 = VECTOR('',#109268,1.); +#109268 = DIRECTION('',(-1.,0.E+000)); +#109269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109270 = ORIENTED_EDGE('',*,*,#108665,.F.); +#109271 = ORIENTED_EDGE('',*,*,#108849,.F.); +#109272 = ORIENTED_EDGE('',*,*,#108956,.F.); +#109273 = ORIENTED_EDGE('',*,*,#109077,.F.); +#109274 = ORIENTED_EDGE('',*,*,#109275,.T.); +#109275 = EDGE_CURVE('',#109078,#90786,#109276,.T.); +#109276 = SURFACE_CURVE('',#109277,(#109281,#109288),.PCURVE_S1.); +#109277 = LINE('',#109278,#109279); +#109278 = CARTESIAN_POINT('',(8.15,-0.527847992439,0.75)); +#109279 = VECTOR('',#109280,1.); +#109280 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#109281 = PCURVE('',#90808,#109282); +#109282 = DEFINITIONAL_REPRESENTATION('',(#109283),#109287); +#109283 = LINE('',#109284,#109285); +#109284 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#109285 = VECTOR('',#109286,1.); +#109286 = DIRECTION('',(-3.563627120235E-016,1.)); +#109287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109288 = PCURVE('',#90836,#109289); +#109289 = DEFINITIONAL_REPRESENTATION('',(#109290),#109294); +#109290 = LINE('',#109291,#109292); +#109291 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109292 = VECTOR('',#109293,1.); +#109293 = DIRECTION('',(1.,0.E+000)); +#109294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109295 = ORIENTED_EDGE('',*,*,#90785,.T.); +#109296 = ADVANCED_FACE('',(#109297),#90836,.F.); +#109297 = FACE_BOUND('',#109298,.T.); +#109298 = EDGE_LOOP('',(#109299,#109300,#109321,#109322)); +#109299 = ORIENTED_EDGE('',*,*,#109128,.F.); +#109300 = ORIENTED_EDGE('',*,*,#109301,.T.); +#109301 = EDGE_CURVE('',#109102,#90821,#109302,.T.); +#109302 = SURFACE_CURVE('',#109303,(#109307,#109314),.PCURVE_S1.); +#109303 = LINE('',#109304,#109305); +#109304 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.75)); +#109305 = VECTOR('',#109306,1.); +#109306 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#109307 = PCURVE('',#90836,#109308); +#109308 = DEFINITIONAL_REPRESENTATION('',(#109309),#109313); +#109309 = LINE('',#109310,#109311); +#109310 = CARTESIAN_POINT('',(0.E+000,0.2)); +#109311 = VECTOR('',#109312,1.); +#109312 = DIRECTION('',(1.,0.E+000)); +#109313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109314 = PCURVE('',#90864,#109315); +#109315 = DEFINITIONAL_REPRESENTATION('',(#109316),#109320); +#109316 = LINE('',#109317,#109318); +#109317 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#109318 = VECTOR('',#109319,1.); +#109319 = DIRECTION('',(3.563627120235E-016,1.)); +#109320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109321 = ORIENTED_EDGE('',*,*,#90820,.T.); +#109322 = ORIENTED_EDGE('',*,*,#109275,.F.); +#109323 = ADVANCED_FACE('',(#109324),#90864,.F.); +#109324 = FACE_BOUND('',#109325,.T.); +#109325 = EDGE_LOOP('',(#109326,#109327,#109328,#109329,#109330,#109331, + #109352,#109353,#109354,#109355,#109356,#109377)); +#109326 = ORIENTED_EDGE('',*,*,#109301,.F.); +#109327 = ORIENTED_EDGE('',*,*,#109101,.T.); +#109328 = ORIENTED_EDGE('',*,*,#108978,.T.); +#109329 = ORIENTED_EDGE('',*,*,#108903,.T.); +#109330 = ORIENTED_EDGE('',*,*,#108718,.T.); +#109331 = ORIENTED_EDGE('',*,*,#109332,.T.); +#109332 = EDGE_CURVE('',#108696,#108559,#109333,.T.); +#109333 = SURFACE_CURVE('',#109334,(#109338,#109345),.PCURVE_S1.); +#109334 = LINE('',#109335,#109336); +#109335 = CARTESIAN_POINT('',(8.35,-1.,1.159810404338E-002)); +#109336 = VECTOR('',#109337,1.); +#109337 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#109338 = PCURVE('',#90864,#109339); +#109339 = DEFINITIONAL_REPRESENTATION('',(#109340),#109344); +#109340 = LINE('',#109341,#109342); +#109341 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#109342 = VECTOR('',#109343,1.); +#109343 = DIRECTION('',(-1.,2.101748079665E-016)); +#109344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109345 = PCURVE('',#108602,#109346); +#109346 = DEFINITIONAL_REPRESENTATION('',(#109347),#109351); +#109347 = LINE('',#109348,#109349); +#109348 = CARTESIAN_POINT('',(-0.269794846371,0.1)); +#109349 = VECTOR('',#109350,1.); +#109350 = DIRECTION('',(1.,0.E+000)); +#109351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109352 = ORIENTED_EDGE('',*,*,#108556,.F.); +#109353 = ORIENTED_EDGE('',*,*,#108824,.F.); +#109354 = ORIENTED_EDGE('',*,*,#109031,.F.); +#109355 = ORIENTED_EDGE('',*,*,#109151,.F.); +#109356 = ORIENTED_EDGE('',*,*,#109357,.T.); +#109357 = EDGE_CURVE('',#109152,#90849,#109358,.T.); +#109358 = SURFACE_CURVE('',#109359,(#109363,#109370),.PCURVE_S1.); +#109359 = LINE('',#109360,#109361); +#109360 = CARTESIAN_POINT('',(8.35,-0.527847992439,0.65)); +#109361 = VECTOR('',#109362,1.); +#109362 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#109363 = PCURVE('',#90864,#109364); +#109364 = DEFINITIONAL_REPRESENTATION('',(#109365),#109369); +#109365 = LINE('',#109366,#109367); +#109366 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109367 = VECTOR('',#109368,1.); +#109368 = DIRECTION('',(3.563627120235E-016,1.)); +#109369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109370 = PCURVE('',#90890,#109371); +#109371 = DEFINITIONAL_REPRESENTATION('',(#109372),#109376); +#109372 = LINE('',#109373,#109374); +#109373 = CARTESIAN_POINT('',(0.E+000,0.2)); +#109374 = VECTOR('',#109375,1.); +#109375 = DIRECTION('',(-1.,0.E+000)); +#109376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109377 = ORIENTED_EDGE('',*,*,#90848,.T.); +#109378 = ADVANCED_FACE('',(#109379),#90890,.F.); +#109379 = FACE_BOUND('',#109380,.T.); +#109380 = EDGE_LOOP('',(#109381,#109382,#109383,#109384)); +#109381 = ORIENTED_EDGE('',*,*,#109178,.F.); +#109382 = ORIENTED_EDGE('',*,*,#109225,.T.); +#109383 = ORIENTED_EDGE('',*,*,#90876,.T.); +#109384 = ORIENTED_EDGE('',*,*,#109357,.F.); +#109385 = ADVANCED_FACE('',(#109386),#108602,.T.); +#109386 = FACE_BOUND('',#109387,.T.); +#109387 = EDGE_LOOP('',(#109388,#109389,#109390,#109391)); +#109388 = ORIENTED_EDGE('',*,*,#109332,.F.); +#109389 = ORIENTED_EDGE('',*,*,#108695,.F.); +#109390 = ORIENTED_EDGE('',*,*,#109250,.F.); +#109391 = ORIENTED_EDGE('',*,*,#108586,.F.); +#109392 = ADVANCED_FACE('',(#109393),#109407,.T.); +#109393 = FACE_BOUND('',#109394,.T.); +#109394 = EDGE_LOOP('',(#109395,#109425,#109453,#109476)); +#109395 = ORIENTED_EDGE('',*,*,#109396,.T.); +#109396 = EDGE_CURVE('',#109397,#109399,#109401,.T.); +#109397 = VERTEX_POINT('',#109398); +#109398 = CARTESIAN_POINT('',(8.85,-0.74341632541,-0.308197125857)); +#109399 = VERTEX_POINT('',#109400); +#109400 = CARTESIAN_POINT('',(8.85,-1.,-0.308197125857)); +#109401 = SURFACE_CURVE('',#109402,(#109406,#109418),.PCURVE_S1.); +#109402 = LINE('',#109403,#109404); +#109403 = CARTESIAN_POINT('',(8.85,-0.74341632541,-0.308197125857)); +#109404 = VECTOR('',#109405,1.); +#109405 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#109406 = PCURVE('',#109407,#109412); +#109407 = PLANE('',#109408); +#109408 = AXIS2_PLACEMENT_3D('',#109409,#109410,#109411); +#109409 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#109410 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109411 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109412 = DEFINITIONAL_REPRESENTATION('',(#109413),#109417); +#109413 = LINE('',#109414,#109415); +#109414 = CARTESIAN_POINT('',(1.15,0.E+000)); +#109415 = VECTOR('',#109416,1.); +#109416 = DIRECTION('',(0.E+000,-1.)); +#109417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109418 = PCURVE('',#92683,#109419); +#109419 = DEFINITIONAL_REPRESENTATION('',(#109420),#109424); +#109420 = LINE('',#109421,#109422); +#109421 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#109422 = VECTOR('',#109423,1.); +#109423 = DIRECTION('',(0.E+000,-1.)); +#109424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109425 = ORIENTED_EDGE('',*,*,#109426,.T.); +#109426 = EDGE_CURVE('',#109399,#109427,#109429,.T.); +#109427 = VERTEX_POINT('',#109428); +#109428 = CARTESIAN_POINT('',(8.65,-1.,-0.308197125857)); +#109429 = SURFACE_CURVE('',#109430,(#109434,#109441),.PCURVE_S1.); +#109430 = LINE('',#109431,#109432); +#109431 = CARTESIAN_POINT('',(10.,-1.,-0.308197125857)); +#109432 = VECTOR('',#109433,1.); +#109433 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109434 = PCURVE('',#109407,#109435); +#109435 = DEFINITIONAL_REPRESENTATION('',(#109436),#109440); +#109436 = LINE('',#109437,#109438); +#109437 = CARTESIAN_POINT('',(0.E+000,-0.25658367459)); +#109438 = VECTOR('',#109439,1.); +#109439 = DIRECTION('',(1.,0.E+000)); +#109440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109441 = PCURVE('',#109442,#109447); +#109442 = PLANE('',#109443); +#109443 = AXIS2_PLACEMENT_3D('',#109444,#109445,#109446); +#109444 = CARTESIAN_POINT('',(8.75,-1.,-0.258196742327)); +#109445 = DIRECTION('',(0.E+000,-1.,-2.101748079665E-016)); +#109446 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#109447 = DEFINITIONAL_REPRESENTATION('',(#109448),#109452); +#109448 = LINE('',#109449,#109450); +#109449 = CARTESIAN_POINT('',(5.000038352949E-002,1.25)); +#109450 = VECTOR('',#109451,1.); +#109451 = DIRECTION('',(0.E+000,-1.)); +#109452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109453 = ORIENTED_EDGE('',*,*,#109454,.F.); +#109454 = EDGE_CURVE('',#109455,#109427,#109457,.T.); +#109455 = VERTEX_POINT('',#109456); +#109456 = CARTESIAN_POINT('',(8.65,-0.74341632541,-0.308197125857)); +#109457 = SURFACE_CURVE('',#109458,(#109462,#109469),.PCURVE_S1.); +#109458 = LINE('',#109459,#109460); +#109459 = CARTESIAN_POINT('',(8.65,-0.74341632541,-0.308197125857)); +#109460 = VECTOR('',#109461,1.); +#109461 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#109462 = PCURVE('',#109407,#109463); +#109463 = DEFINITIONAL_REPRESENTATION('',(#109464),#109468); +#109464 = LINE('',#109465,#109466); +#109465 = CARTESIAN_POINT('',(1.35,0.E+000)); +#109466 = VECTOR('',#109467,1.); +#109467 = DIRECTION('',(0.E+000,-1.)); +#109468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109469 = PCURVE('',#92627,#109470); +#109470 = DEFINITIONAL_REPRESENTATION('',(#109471),#109475); +#109471 = LINE('',#109472,#109473); +#109472 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#109473 = VECTOR('',#109474,1.); +#109474 = DIRECTION('',(0.E+000,-1.)); +#109475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109476 = ORIENTED_EDGE('',*,*,#109477,.T.); +#109477 = EDGE_CURVE('',#109455,#109397,#109478,.T.); +#109478 = SURFACE_CURVE('',#109479,(#109483,#109490),.PCURVE_S1.); +#109479 = LINE('',#109480,#109481); +#109480 = CARTESIAN_POINT('',(10.,-0.74341632541,-0.308197125857)); +#109481 = VECTOR('',#109482,1.); +#109482 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109483 = PCURVE('',#109407,#109484); +#109484 = DEFINITIONAL_REPRESENTATION('',(#109485),#109489); +#109485 = LINE('',#109486,#109487); +#109486 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109487 = VECTOR('',#109488,1.); +#109488 = DIRECTION('',(-1.,0.E+000)); +#109489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109490 = PCURVE('',#109491,#109496); +#109491 = CYLINDRICAL_SURFACE('',#109492,0.308574064194); +#109492 = AXIS2_PLACEMENT_3D('',#109493,#109494,#109495); +#109493 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#109494 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109495 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109496 = DEFINITIONAL_REPRESENTATION('',(#109497),#109500); +#109497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109498,#109499), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#107106 = CARTESIAN_POINT('',(3.191025391152,1.35)); -#107107 = CARTESIAN_POINT('',(3.191025391152,1.15)); -#107108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107109 = ADVANCED_FACE('',(#107110),#107124,.T.); -#107110 = FACE_BOUND('',#107111,.T.); -#107111 = EDGE_LOOP('',(#107112,#107142,#107165,#107188)); -#107112 = ORIENTED_EDGE('',*,*,#107113,.T.); -#107113 = EDGE_CURVE('',#107114,#107116,#107118,.T.); -#107114 = VERTEX_POINT('',#107115); -#107115 = CARTESIAN_POINT('',(8.65,-0.740726081328,-0.208196358798)); -#107116 = VERTEX_POINT('',#107117); -#107117 = CARTESIAN_POINT('',(8.65,-1.,-0.208196358798)); -#107118 = SURFACE_CURVE('',#107119,(#107123,#107135),.PCURVE_S1.); -#107119 = LINE('',#107120,#107121); -#107120 = CARTESIAN_POINT('',(8.65,-0.740726081328,-0.208196358798)); -#107121 = VECTOR('',#107122,1.); -#107122 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#107123 = PCURVE('',#107124,#107129); -#107124 = PLANE('',#107125); -#107125 = AXIS2_PLACEMENT_3D('',#107126,#107127,#107128); -#107126 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#107127 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107128 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107129 = DEFINITIONAL_REPRESENTATION('',(#107130),#107134); -#107130 = LINE('',#107131,#107132); -#107131 = CARTESIAN_POINT('',(-1.35,0.E+000)); -#107132 = VECTOR('',#107133,1.); -#107133 = DIRECTION('',(0.E+000,-1.)); -#107134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107135 = PCURVE('',#90235,#107136); -#107136 = DEFINITIONAL_REPRESENTATION('',(#107137),#107141); -#107137 = LINE('',#107138,#107139); -#107138 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#107139 = VECTOR('',#107140,1.); -#107140 = DIRECTION('',(0.E+000,-1.)); -#107141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107142 = ORIENTED_EDGE('',*,*,#107143,.T.); -#107143 = EDGE_CURVE('',#107116,#107144,#107146,.T.); -#107144 = VERTEX_POINT('',#107145); -#107145 = CARTESIAN_POINT('',(8.85,-1.,-0.208196358798)); -#107146 = SURFACE_CURVE('',#107147,(#107151,#107158),.PCURVE_S1.); -#107147 = LINE('',#107148,#107149); -#107148 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); -#107149 = VECTOR('',#107150,1.); -#107150 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107151 = PCURVE('',#107124,#107152); -#107152 = DEFINITIONAL_REPRESENTATION('',(#107153),#107157); -#107153 = LINE('',#107154,#107155); -#107154 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); -#107155 = VECTOR('',#107156,1.); -#107156 = DIRECTION('',(1.,0.E+000)); -#107157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107158 = PCURVE('',#107050,#107159); -#107159 = DEFINITIONAL_REPRESENTATION('',(#107160),#107164); -#107160 = LINE('',#107161,#107162); -#107161 = CARTESIAN_POINT('',(-5.000038352949E-002,1.25)); -#107162 = VECTOR('',#107163,1.); -#107163 = DIRECTION('',(0.E+000,1.)); -#107164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107165 = ORIENTED_EDGE('',*,*,#107166,.F.); -#107166 = EDGE_CURVE('',#107167,#107144,#107169,.T.); -#107167 = VERTEX_POINT('',#107168); -#107168 = CARTESIAN_POINT('',(8.85,-0.740726081328,-0.208196358798)); -#107169 = SURFACE_CURVE('',#107170,(#107174,#107181),.PCURVE_S1.); -#107170 = LINE('',#107171,#107172); -#107171 = CARTESIAN_POINT('',(8.85,-0.740726081328,-0.208196358798)); -#107172 = VECTOR('',#107173,1.); -#107173 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#107174 = PCURVE('',#107124,#107175); -#107175 = DEFINITIONAL_REPRESENTATION('',(#107176),#107180); -#107176 = LINE('',#107177,#107178); -#107177 = CARTESIAN_POINT('',(-1.15,0.E+000)); -#107178 = VECTOR('',#107179,1.); -#107179 = DIRECTION('',(0.E+000,-1.)); -#107180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107181 = PCURVE('',#90291,#107182); -#107182 = DEFINITIONAL_REPRESENTATION('',(#107183),#107187); -#107183 = LINE('',#107184,#107185); -#107184 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#107185 = VECTOR('',#107186,1.); -#107186 = DIRECTION('',(0.E+000,-1.)); -#107187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107188 = ORIENTED_EDGE('',*,*,#107189,.T.); -#107189 = EDGE_CURVE('',#107167,#107114,#107190,.T.); -#107190 = SURFACE_CURVE('',#107191,(#107195,#107202),.PCURVE_S1.); -#107191 = LINE('',#107192,#107193); -#107192 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); -#107193 = VECTOR('',#107194,1.); -#107194 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107195 = PCURVE('',#107124,#107196); -#107196 = DEFINITIONAL_REPRESENTATION('',(#107197),#107201); -#107197 = LINE('',#107198,#107199); -#107198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107199 = VECTOR('',#107200,1.); -#107200 = DIRECTION('',(-1.,0.E+000)); -#107201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107202 = PCURVE('',#107203,#107208); -#107203 = CYLINDRICAL_SURFACE('',#107204,0.208574704164); -#107204 = AXIS2_PLACEMENT_3D('',#107205,#107206,#107207); -#107205 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); -#107206 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107207 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107208 = DEFINITIONAL_REPRESENTATION('',(#107209),#107212); -#107209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107210,#107211), +#109498 = CARTESIAN_POINT('',(3.191025391152,1.35)); +#109499 = CARTESIAN_POINT('',(3.191025391152,1.15)); +#109500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109501 = ADVANCED_FACE('',(#109502),#109516,.T.); +#109502 = FACE_BOUND('',#109503,.T.); +#109503 = EDGE_LOOP('',(#109504,#109534,#109557,#109580)); +#109504 = ORIENTED_EDGE('',*,*,#109505,.T.); +#109505 = EDGE_CURVE('',#109506,#109508,#109510,.T.); +#109506 = VERTEX_POINT('',#109507); +#109507 = CARTESIAN_POINT('',(8.65,-0.740726081328,-0.208196358798)); +#109508 = VERTEX_POINT('',#109509); +#109509 = CARTESIAN_POINT('',(8.65,-1.,-0.208196358798)); +#109510 = SURFACE_CURVE('',#109511,(#109515,#109527),.PCURVE_S1.); +#109511 = LINE('',#109512,#109513); +#109512 = CARTESIAN_POINT('',(8.65,-0.740726081328,-0.208196358798)); +#109513 = VECTOR('',#109514,1.); +#109514 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#109515 = PCURVE('',#109516,#109521); +#109516 = PLANE('',#109517); +#109517 = AXIS2_PLACEMENT_3D('',#109518,#109519,#109520); +#109518 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#109519 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109520 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109521 = DEFINITIONAL_REPRESENTATION('',(#109522),#109526); +#109522 = LINE('',#109523,#109524); +#109523 = CARTESIAN_POINT('',(-1.35,0.E+000)); +#109524 = VECTOR('',#109525,1.); +#109525 = DIRECTION('',(0.E+000,-1.)); +#109526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109527 = PCURVE('',#92627,#109528); +#109528 = DEFINITIONAL_REPRESENTATION('',(#109529),#109533); +#109529 = LINE('',#109530,#109531); +#109530 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#109531 = VECTOR('',#109532,1.); +#109532 = DIRECTION('',(0.E+000,-1.)); +#109533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109534 = ORIENTED_EDGE('',*,*,#109535,.T.); +#109535 = EDGE_CURVE('',#109508,#109536,#109538,.T.); +#109536 = VERTEX_POINT('',#109537); +#109537 = CARTESIAN_POINT('',(8.85,-1.,-0.208196358798)); +#109538 = SURFACE_CURVE('',#109539,(#109543,#109550),.PCURVE_S1.); +#109539 = LINE('',#109540,#109541); +#109540 = CARTESIAN_POINT('',(10.,-1.,-0.208196358798)); +#109541 = VECTOR('',#109542,1.); +#109542 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109543 = PCURVE('',#109516,#109544); +#109544 = DEFINITIONAL_REPRESENTATION('',(#109545),#109549); +#109545 = LINE('',#109546,#109547); +#109546 = CARTESIAN_POINT('',(0.E+000,-0.259273918672)); +#109547 = VECTOR('',#109548,1.); +#109548 = DIRECTION('',(1.,0.E+000)); +#109549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109550 = PCURVE('',#109442,#109551); +#109551 = DEFINITIONAL_REPRESENTATION('',(#109552),#109556); +#109552 = LINE('',#109553,#109554); +#109553 = CARTESIAN_POINT('',(-5.000038352949E-002,1.25)); +#109554 = VECTOR('',#109555,1.); +#109555 = DIRECTION('',(0.E+000,1.)); +#109556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109557 = ORIENTED_EDGE('',*,*,#109558,.F.); +#109558 = EDGE_CURVE('',#109559,#109536,#109561,.T.); +#109559 = VERTEX_POINT('',#109560); +#109560 = CARTESIAN_POINT('',(8.85,-0.740726081328,-0.208196358798)); +#109561 = SURFACE_CURVE('',#109562,(#109566,#109573),.PCURVE_S1.); +#109562 = LINE('',#109563,#109564); +#109563 = CARTESIAN_POINT('',(8.85,-0.740726081328,-0.208196358798)); +#109564 = VECTOR('',#109565,1.); +#109565 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#109566 = PCURVE('',#109516,#109567); +#109567 = DEFINITIONAL_REPRESENTATION('',(#109568),#109572); +#109568 = LINE('',#109569,#109570); +#109569 = CARTESIAN_POINT('',(-1.15,0.E+000)); +#109570 = VECTOR('',#109571,1.); +#109571 = DIRECTION('',(0.E+000,-1.)); +#109572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109573 = PCURVE('',#92683,#109574); +#109574 = DEFINITIONAL_REPRESENTATION('',(#109575),#109579); +#109575 = LINE('',#109576,#109577); +#109576 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#109577 = VECTOR('',#109578,1.); +#109578 = DIRECTION('',(0.E+000,-1.)); +#109579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109580 = ORIENTED_EDGE('',*,*,#109581,.T.); +#109581 = EDGE_CURVE('',#109559,#109506,#109582,.T.); +#109582 = SURFACE_CURVE('',#109583,(#109587,#109594),.PCURVE_S1.); +#109583 = LINE('',#109584,#109585); +#109584 = CARTESIAN_POINT('',(10.,-0.740726081328,-0.208196358798)); +#109585 = VECTOR('',#109586,1.); +#109586 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109587 = PCURVE('',#109516,#109588); +#109588 = DEFINITIONAL_REPRESENTATION('',(#109589),#109593); +#109589 = LINE('',#109590,#109591); +#109590 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109591 = VECTOR('',#109592,1.); +#109592 = DIRECTION('',(-1.,0.E+000)); +#109593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109594 = PCURVE('',#109595,#109600); +#109595 = CYLINDRICAL_SURFACE('',#109596,0.208574704164); +#109596 = AXIS2_PLACEMENT_3D('',#109597,#109598,#109599); +#109597 = CARTESIAN_POINT('',(10.,-0.728168876214,2.640924866458E-017)); +#109598 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109599 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109600 = DEFINITIONAL_REPRESENTATION('',(#109601),#109604); +#109601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109602,#109603), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#107210 = CARTESIAN_POINT('',(3.201833915432,1.15)); -#107211 = CARTESIAN_POINT('',(3.201833915432,1.35)); -#107212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107213 = ADVANCED_FACE('',(#107214),#107099,.T.); -#107214 = FACE_BOUND('',#107215,.T.); -#107215 = EDGE_LOOP('',(#107216,#107217,#107244,#107271)); -#107216 = ORIENTED_EDGE('',*,*,#107085,.F.); -#107217 = ORIENTED_EDGE('',*,*,#107218,.F.); -#107218 = EDGE_CURVE('',#107219,#107063,#107221,.T.); -#107219 = VERTEX_POINT('',#107220); -#107220 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.E+000)); -#107221 = SURFACE_CURVE('',#107222,(#107227,#107233),.PCURVE_S1.); -#107222 = CIRCLE('',#107223,0.308574064194); -#107223 = AXIS2_PLACEMENT_3D('',#107224,#107225,#107226); -#107224 = CARTESIAN_POINT('',(8.65,-0.728168876214,2.640924866458E-017) - ); -#107225 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107226 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107227 = PCURVE('',#107099,#107228); -#107228 = DEFINITIONAL_REPRESENTATION('',(#107229),#107232); -#107229 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107230,#107231), +#109602 = CARTESIAN_POINT('',(3.201833915432,1.15)); +#109603 = CARTESIAN_POINT('',(3.201833915432,1.35)); +#109604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109605 = ADVANCED_FACE('',(#109606),#109491,.T.); +#109606 = FACE_BOUND('',#109607,.T.); +#109607 = EDGE_LOOP('',(#109608,#109609,#109636,#109663)); +#109608 = ORIENTED_EDGE('',*,*,#109477,.F.); +#109609 = ORIENTED_EDGE('',*,*,#109610,.F.); +#109610 = EDGE_CURVE('',#109611,#109455,#109613,.T.); +#109611 = VERTEX_POINT('',#109612); +#109612 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.E+000)); +#109613 = SURFACE_CURVE('',#109614,(#109619,#109625),.PCURVE_S1.); +#109614 = CIRCLE('',#109615,0.308574064194); +#109615 = AXIS2_PLACEMENT_3D('',#109616,#109617,#109618); +#109616 = CARTESIAN_POINT('',(8.65,-0.728168876214,2.640924866458E-017) + ); +#109617 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109618 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109619 = PCURVE('',#109491,#109620); +#109620 = DEFINITIONAL_REPRESENTATION('',(#109621),#109624); +#109621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109622,#109623), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#107230 = CARTESIAN_POINT('',(1.570796326795,1.35)); -#107231 = CARTESIAN_POINT('',(3.191025391152,1.35)); -#107232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109622 = CARTESIAN_POINT('',(1.570796326795,1.35)); +#109623 = CARTESIAN_POINT('',(3.191025391152,1.35)); +#109624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#107233 = PCURVE('',#90235,#107234); -#107234 = DEFINITIONAL_REPRESENTATION('',(#107235),#107243); -#107235 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107236,#107237,#107238, - #107239,#107240,#107241,#107242),.UNSPECIFIED.,.T.,.F.) +#109625 = PCURVE('',#92627,#109626); +#109626 = DEFINITIONAL_REPRESENTATION('',(#109627),#109635); +#109627 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109628,#109629,#109630, + #109631,#109632,#109633,#109634),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#107236 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#107237 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); -#107238 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); -#107239 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); -#107240 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); -#107241 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); -#107242 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); -#107243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107244 = ORIENTED_EDGE('',*,*,#107245,.F.); -#107245 = EDGE_CURVE('',#107246,#107219,#107248,.T.); -#107246 = VERTEX_POINT('',#107247); -#107247 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.E+000)); -#107248 = SURFACE_CURVE('',#107249,(#107253,#107259),.PCURVE_S1.); -#107249 = LINE('',#107250,#107251); -#107250 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); -#107251 = VECTOR('',#107252,1.); -#107252 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107253 = PCURVE('',#107099,#107254); -#107254 = DEFINITIONAL_REPRESENTATION('',(#107255),#107258); -#107255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107256,#107257), +#109628 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#109629 = CARTESIAN_POINT('',(0.341425935806,0.334145073308)); +#109630 = CARTESIAN_POINT('',(0.804287032097,6.691209476628E-002)); +#109631 = CARTESIAN_POINT('',(1.267148128389,-0.200320883775)); +#109632 = CARTESIAN_POINT('',(0.804287032097,-0.467553862316)); +#109633 = CARTESIAN_POINT('',(0.341425935806,-0.734786840858)); +#109634 = CARTESIAN_POINT('',(0.341425935806,-0.200320883775)); +#109635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109636 = ORIENTED_EDGE('',*,*,#109637,.F.); +#109637 = EDGE_CURVE('',#109638,#109611,#109640,.T.); +#109638 = VERTEX_POINT('',#109639); +#109639 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.E+000)); +#109640 = SURFACE_CURVE('',#109641,(#109645,#109651),.PCURVE_S1.); +#109641 = LINE('',#109642,#109643); +#109642 = CARTESIAN_POINT('',(10.,-0.419594812019,0.E+000)); +#109643 = VECTOR('',#109644,1.); +#109644 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109645 = PCURVE('',#109491,#109646); +#109646 = DEFINITIONAL_REPRESENTATION('',(#109647),#109650); +#109647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109648,#109649), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#107256 = CARTESIAN_POINT('',(1.570796326795,1.15)); -#107257 = CARTESIAN_POINT('',(1.570796326795,1.35)); -#107258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107259 = PCURVE('',#107260,#107265); -#107260 = PLANE('',#107261); -#107261 = AXIS2_PLACEMENT_3D('',#107262,#107263,#107264); -#107262 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#107263 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); -#107264 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#107265 = DEFINITIONAL_REPRESENTATION('',(#107266),#107270); -#107266 = LINE('',#107267,#107268); -#107267 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); -#107268 = VECTOR('',#107269,1.); -#107269 = DIRECTION('',(0.E+000,-1.)); -#107270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107271 = ORIENTED_EDGE('',*,*,#107272,.T.); -#107272 = EDGE_CURVE('',#107246,#107005,#107273,.T.); -#107273 = SURFACE_CURVE('',#107274,(#107279,#107285),.PCURVE_S1.); -#107274 = CIRCLE('',#107275,0.308574064194); -#107275 = AXIS2_PLACEMENT_3D('',#107276,#107277,#107278); -#107276 = CARTESIAN_POINT('',(8.85,-0.728168876214,2.640924866458E-017) - ); -#107277 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107278 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107279 = PCURVE('',#107099,#107280); -#107280 = DEFINITIONAL_REPRESENTATION('',(#107281),#107284); -#107281 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107282,#107283), +#109648 = CARTESIAN_POINT('',(1.570796326795,1.15)); +#109649 = CARTESIAN_POINT('',(1.570796326795,1.35)); +#109650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109651 = PCURVE('',#109652,#109657); +#109652 = PLANE('',#109653); +#109653 = AXIS2_PLACEMENT_3D('',#109654,#109655,#109656); +#109654 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#109655 = DIRECTION('',(0.E+000,-1.,1.021336205033E-016)); +#109656 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109657 = DEFINITIONAL_REPRESENTATION('',(#109658),#109662); +#109658 = LINE('',#109659,#109660); +#109659 = CARTESIAN_POINT('',(0.530776333563,0.E+000)); +#109660 = VECTOR('',#109661,1.); +#109661 = DIRECTION('',(0.E+000,-1.)); +#109662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109663 = ORIENTED_EDGE('',*,*,#109664,.T.); +#109664 = EDGE_CURVE('',#109638,#109397,#109665,.T.); +#109665 = SURFACE_CURVE('',#109666,(#109671,#109677),.PCURVE_S1.); +#109666 = CIRCLE('',#109667,0.308574064194); +#109667 = AXIS2_PLACEMENT_3D('',#109668,#109669,#109670); +#109668 = CARTESIAN_POINT('',(8.85,-0.728168876214,2.640924866458E-017) + ); +#109669 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109670 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109671 = PCURVE('',#109491,#109672); +#109672 = DEFINITIONAL_REPRESENTATION('',(#109673),#109676); +#109673 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109674,#109675), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.191025391152), .PIECEWISE_BEZIER_KNOTS.); -#107282 = CARTESIAN_POINT('',(1.570796326795,1.15)); -#107283 = CARTESIAN_POINT('',(3.191025391152,1.15)); -#107284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107285 = PCURVE('',#90291,#107286); -#107286 = DEFINITIONAL_REPRESENTATION('',(#107287),#107291); -#107287 = CIRCLE('',#107288,0.308574064194); -#107288 = AXIS2_PLACEMENT_2D('',#107289,#107290); -#107289 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#107290 = DIRECTION('',(1.,0.E+000)); -#107291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107292 = ADVANCED_FACE('',(#107293),#107203,.F.); -#107293 = FACE_BOUND('',#107294,.F.); -#107294 = EDGE_LOOP('',(#107295,#107296,#107323,#107350)); -#107295 = ORIENTED_EDGE('',*,*,#107189,.T.); -#107296 = ORIENTED_EDGE('',*,*,#107297,.F.); -#107297 = EDGE_CURVE('',#107298,#107114,#107300,.T.); -#107298 = VERTEX_POINT('',#107299); -#107299 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.E+000)); -#107300 = SURFACE_CURVE('',#107301,(#107306,#107312),.PCURVE_S1.); -#107301 = CIRCLE('',#107302,0.208574704164); -#107302 = AXIS2_PLACEMENT_3D('',#107303,#107304,#107305); -#107303 = CARTESIAN_POINT('',(8.65,-0.728168876214,2.640924866458E-017) - ); -#107304 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107305 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107306 = PCURVE('',#107203,#107307); -#107307 = DEFINITIONAL_REPRESENTATION('',(#107308),#107311); -#107308 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107309,#107310), +#109674 = CARTESIAN_POINT('',(1.570796326795,1.15)); +#109675 = CARTESIAN_POINT('',(3.191025391152,1.15)); +#109676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109677 = PCURVE('',#92683,#109678); +#109678 = DEFINITIONAL_REPRESENTATION('',(#109679),#109683); +#109679 = CIRCLE('',#109680,0.308574064194); +#109680 = AXIS2_PLACEMENT_2D('',#109681,#109682); +#109681 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#109682 = DIRECTION('',(1.,0.E+000)); +#109683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109684 = ADVANCED_FACE('',(#109685),#109595,.F.); +#109685 = FACE_BOUND('',#109686,.F.); +#109686 = EDGE_LOOP('',(#109687,#109688,#109715,#109742)); +#109687 = ORIENTED_EDGE('',*,*,#109581,.T.); +#109688 = ORIENTED_EDGE('',*,*,#109689,.F.); +#109689 = EDGE_CURVE('',#109690,#109506,#109692,.T.); +#109690 = VERTEX_POINT('',#109691); +#109691 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.E+000)); +#109692 = SURFACE_CURVE('',#109693,(#109698,#109704),.PCURVE_S1.); +#109693 = CIRCLE('',#109694,0.208574704164); +#109694 = AXIS2_PLACEMENT_3D('',#109695,#109696,#109697); +#109695 = CARTESIAN_POINT('',(8.65,-0.728168876214,2.640924866458E-017) + ); +#109696 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109697 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109698 = PCURVE('',#109595,#109699); +#109699 = DEFINITIONAL_REPRESENTATION('',(#109700),#109703); +#109700 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109701,#109702), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#107309 = CARTESIAN_POINT('',(1.570796326795,1.35)); -#107310 = CARTESIAN_POINT('',(3.201833915432,1.35)); -#107311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109701 = CARTESIAN_POINT('',(1.570796326795,1.35)); +#109702 = CARTESIAN_POINT('',(3.201833915432,1.35)); +#109703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#107312 = PCURVE('',#90235,#107313); -#107313 = DEFINITIONAL_REPRESENTATION('',(#107314),#107322); -#107314 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107315,#107316,#107317, - #107318,#107319,#107320,#107321),.UNSPECIFIED.,.F.,.F.) +#109704 = PCURVE('',#92627,#109705); +#109705 = DEFINITIONAL_REPRESENTATION('',(#109706),#109714); +#109706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109707,#109708,#109709, + #109710,#109711,#109712,#109713),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#107315 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#107316 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); -#107317 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); -#107318 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); -#107319 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); -#107320 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); -#107321 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); -#107322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107323 = ORIENTED_EDGE('',*,*,#107324,.T.); -#107324 = EDGE_CURVE('',#107298,#107325,#107327,.T.); -#107325 = VERTEX_POINT('',#107326); -#107326 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.E+000)); -#107327 = SURFACE_CURVE('',#107328,(#107332,#107338),.PCURVE_S1.); -#107328 = LINE('',#107329,#107330); -#107329 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); -#107330 = VECTOR('',#107331,1.); -#107331 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107332 = PCURVE('',#107203,#107333); -#107333 = DEFINITIONAL_REPRESENTATION('',(#107334),#107337); -#107334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107335,#107336), +#109707 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#109708 = CARTESIAN_POINT('',(0.441425295836,0.16094110101)); +#109709 = CARTESIAN_POINT('',(0.754287352082,-1.968989138249E-002)); +#109710 = CARTESIAN_POINT('',(1.067149408327,-0.200320883775)); +#109711 = CARTESIAN_POINT('',(0.754287352082,-0.380951876168)); +#109712 = CARTESIAN_POINT('',(0.441425295836,-0.56158286856)); +#109713 = CARTESIAN_POINT('',(0.441425295836,-0.200320883775)); +#109714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109715 = ORIENTED_EDGE('',*,*,#109716,.T.); +#109716 = EDGE_CURVE('',#109690,#109717,#109719,.T.); +#109717 = VERTEX_POINT('',#109718); +#109718 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.E+000)); +#109719 = SURFACE_CURVE('',#109720,(#109724,#109730),.PCURVE_S1.); +#109720 = LINE('',#109721,#109722); +#109721 = CARTESIAN_POINT('',(10.,-0.51959417205,0.E+000)); +#109722 = VECTOR('',#109723,1.); +#109723 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109724 = PCURVE('',#109595,#109725); +#109725 = DEFINITIONAL_REPRESENTATION('',(#109726),#109729); +#109726 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109727,#109728), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#107335 = CARTESIAN_POINT('',(1.570796326795,1.35)); -#107336 = CARTESIAN_POINT('',(1.570796326795,1.15)); -#107337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107338 = PCURVE('',#107339,#107344); -#107339 = PLANE('',#107340); -#107340 = AXIS2_PLACEMENT_3D('',#107341,#107342,#107343); -#107341 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#107342 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); -#107343 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); -#107344 = DEFINITIONAL_REPRESENTATION('',(#107345),#107349); -#107345 = LINE('',#107346,#107347); -#107346 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); -#107347 = VECTOR('',#107348,1.); -#107348 = DIRECTION('',(0.E+000,1.)); -#107349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107350 = ORIENTED_EDGE('',*,*,#107351,.T.); -#107351 = EDGE_CURVE('',#107325,#107167,#107352,.T.); -#107352 = SURFACE_CURVE('',#107353,(#107358,#107364),.PCURVE_S1.); -#107353 = CIRCLE('',#107354,0.208574704164); -#107354 = AXIS2_PLACEMENT_3D('',#107355,#107356,#107357); -#107355 = CARTESIAN_POINT('',(8.85,-0.728168876214,2.640924866458E-017) - ); -#107356 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107357 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107358 = PCURVE('',#107203,#107359); -#107359 = DEFINITIONAL_REPRESENTATION('',(#107360),#107363); -#107360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107361,#107362), +#109727 = CARTESIAN_POINT('',(1.570796326795,1.35)); +#109728 = CARTESIAN_POINT('',(1.570796326795,1.15)); +#109729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109730 = PCURVE('',#109731,#109736); +#109731 = PLANE('',#109732); +#109732 = AXIS2_PLACEMENT_3D('',#109733,#109734,#109735); +#109733 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#109734 = DIRECTION('',(0.E+000,1.,-1.021336205033E-016)); +#109735 = DIRECTION('',(0.E+000,1.021336205033E-016,1.)); +#109736 = DEFINITIONAL_REPRESENTATION('',(#109737),#109741); +#109737 = LINE('',#109738,#109739); +#109738 = CARTESIAN_POINT('',(-0.530776333563,0.E+000)); +#109739 = VECTOR('',#109740,1.); +#109740 = DIRECTION('',(0.E+000,1.)); +#109741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109742 = ORIENTED_EDGE('',*,*,#109743,.T.); +#109743 = EDGE_CURVE('',#109717,#109559,#109744,.T.); +#109744 = SURFACE_CURVE('',#109745,(#109750,#109756),.PCURVE_S1.); +#109745 = CIRCLE('',#109746,0.208574704164); +#109746 = AXIS2_PLACEMENT_3D('',#109747,#109748,#109749); +#109747 = CARTESIAN_POINT('',(8.85,-0.728168876214,2.640924866458E-017) + ); +#109748 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109749 = DIRECTION('',(0.E+000,0.E+000,1.)); +#109750 = PCURVE('',#109595,#109751); +#109751 = DEFINITIONAL_REPRESENTATION('',(#109752),#109755); +#109752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109753,#109754), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.201833915432), .PIECEWISE_BEZIER_KNOTS.); -#107361 = CARTESIAN_POINT('',(1.570796326795,1.15)); -#107362 = CARTESIAN_POINT('',(3.201833915432,1.15)); -#107363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107364 = PCURVE('',#90291,#107365); -#107365 = DEFINITIONAL_REPRESENTATION('',(#107366),#107370); -#107366 = CIRCLE('',#107367,0.208574704164); -#107367 = AXIS2_PLACEMENT_2D('',#107368,#107369); -#107368 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#107369 = DIRECTION('',(1.,0.E+000)); -#107370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107371 = ADVANCED_FACE('',(#107372),#107339,.F.); -#107372 = FACE_BOUND('',#107373,.T.); -#107373 = EDGE_LOOP('',(#107374,#107403,#107424,#107425)); -#107374 = ORIENTED_EDGE('',*,*,#107375,.F.); -#107375 = EDGE_CURVE('',#107376,#107378,#107380,.T.); -#107376 = VERTEX_POINT('',#107377); -#107377 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.530776333563)); -#107378 = VERTEX_POINT('',#107379); -#107379 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.530776333563)); -#107380 = SURFACE_CURVE('',#107381,(#107385,#107392),.PCURVE_S1.); -#107381 = LINE('',#107382,#107383); -#107382 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); -#107383 = VECTOR('',#107384,1.); -#107384 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107385 = PCURVE('',#107339,#107386); -#107386 = DEFINITIONAL_REPRESENTATION('',(#107387),#107391); -#107387 = LINE('',#107388,#107389); -#107388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107389 = VECTOR('',#107390,1.); -#107390 = DIRECTION('',(0.E+000,1.)); -#107391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107392 = PCURVE('',#107393,#107398); -#107393 = CYLINDRICAL_SURFACE('',#107394,0.2192697516); -#107394 = AXIS2_PLACEMENT_3D('',#107395,#107396,#107397); -#107395 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#107396 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107397 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107398 = DEFINITIONAL_REPRESENTATION('',(#107399),#107402); -#107399 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107400,#107401), +#109753 = CARTESIAN_POINT('',(1.570796326795,1.15)); +#109754 = CARTESIAN_POINT('',(3.201833915432,1.15)); +#109755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109756 = PCURVE('',#92683,#109757); +#109757 = DEFINITIONAL_REPRESENTATION('',(#109758),#109762); +#109758 = CIRCLE('',#109759,0.208574704164); +#109759 = AXIS2_PLACEMENT_2D('',#109760,#109761); +#109760 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#109761 = DIRECTION('',(1.,0.E+000)); +#109762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109763 = ADVANCED_FACE('',(#109764),#109731,.F.); +#109764 = FACE_BOUND('',#109765,.T.); +#109765 = EDGE_LOOP('',(#109766,#109795,#109816,#109817)); +#109766 = ORIENTED_EDGE('',*,*,#109767,.F.); +#109767 = EDGE_CURVE('',#109768,#109770,#109772,.T.); +#109768 = VERTEX_POINT('',#109769); +#109769 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.530776333563)); +#109770 = VERTEX_POINT('',#109771); +#109771 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.530776333563)); +#109772 = SURFACE_CURVE('',#109773,(#109777,#109784),.PCURVE_S1.); +#109773 = LINE('',#109774,#109775); +#109774 = CARTESIAN_POINT('',(10.,-0.51959417205,0.530776333563)); +#109775 = VECTOR('',#109776,1.); +#109776 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109777 = PCURVE('',#109731,#109778); +#109778 = DEFINITIONAL_REPRESENTATION('',(#109779),#109783); +#109779 = LINE('',#109780,#109781); +#109780 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109781 = VECTOR('',#109782,1.); +#109782 = DIRECTION('',(0.E+000,1.)); +#109783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109784 = PCURVE('',#109785,#109790); +#109785 = CYLINDRICAL_SURFACE('',#109786,0.2192697516); +#109786 = AXIS2_PLACEMENT_3D('',#109787,#109788,#109789); +#109787 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#109788 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109789 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109790 = DEFINITIONAL_REPRESENTATION('',(#109791),#109794); +#109791 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109792,#109793), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#107400 = CARTESIAN_POINT('',(4.712388980385,-1.35)); -#107401 = CARTESIAN_POINT('',(4.712388980385,-1.15)); -#107402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107403 = ORIENTED_EDGE('',*,*,#107404,.T.); -#107404 = EDGE_CURVE('',#107376,#107298,#107405,.T.); -#107405 = SURFACE_CURVE('',#107406,(#107410,#107417),.PCURVE_S1.); -#107406 = LINE('',#107407,#107408); -#107407 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.530776333563)); -#107408 = VECTOR('',#107409,1.); -#107409 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#107410 = PCURVE('',#107339,#107411); -#107411 = DEFINITIONAL_REPRESENTATION('',(#107412),#107416); -#107412 = LINE('',#107413,#107414); -#107413 = CARTESIAN_POINT('',(0.E+000,-1.35)); -#107414 = VECTOR('',#107415,1.); -#107415 = DIRECTION('',(-1.,0.E+000)); -#107416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107417 = PCURVE('',#90235,#107418); -#107418 = DEFINITIONAL_REPRESENTATION('',(#107419),#107423); -#107419 = LINE('',#107420,#107421); -#107420 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#107421 = VECTOR('',#107422,1.); -#107422 = DIRECTION('',(1.,-1.021336205033E-016)); -#107423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107424 = ORIENTED_EDGE('',*,*,#107324,.T.); -#107425 = ORIENTED_EDGE('',*,*,#107426,.F.); -#107426 = EDGE_CURVE('',#107378,#107325,#107427,.T.); -#107427 = SURFACE_CURVE('',#107428,(#107432,#107439),.PCURVE_S1.); -#107428 = LINE('',#107429,#107430); -#107429 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.530776333563)); -#107430 = VECTOR('',#107431,1.); -#107431 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#107432 = PCURVE('',#107339,#107433); -#107433 = DEFINITIONAL_REPRESENTATION('',(#107434),#107438); -#107434 = LINE('',#107435,#107436); -#107435 = CARTESIAN_POINT('',(0.E+000,-1.15)); -#107436 = VECTOR('',#107437,1.); -#107437 = DIRECTION('',(-1.,0.E+000)); -#107438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107439 = PCURVE('',#90291,#107440); -#107440 = DEFINITIONAL_REPRESENTATION('',(#107441),#107445); -#107441 = LINE('',#107442,#107443); -#107442 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#107443 = VECTOR('',#107444,1.); -#107444 = DIRECTION('',(-1.,-1.021336205033E-016)); -#107445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107446 = ADVANCED_FACE('',(#107447),#107260,.F.); -#107447 = FACE_BOUND('',#107448,.T.); -#107448 = EDGE_LOOP('',(#107449,#107478,#107499,#107500)); -#107449 = ORIENTED_EDGE('',*,*,#107450,.F.); -#107450 = EDGE_CURVE('',#107451,#107453,#107455,.T.); -#107451 = VERTEX_POINT('',#107452); -#107452 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.530776333563)); -#107453 = VERTEX_POINT('',#107454); -#107454 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.530776333563)); -#107455 = SURFACE_CURVE('',#107456,(#107460,#107467),.PCURVE_S1.); -#107456 = LINE('',#107457,#107458); -#107457 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); -#107458 = VECTOR('',#107459,1.); -#107459 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107460 = PCURVE('',#107260,#107461); -#107461 = DEFINITIONAL_REPRESENTATION('',(#107462),#107466); -#107462 = LINE('',#107463,#107464); -#107463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107464 = VECTOR('',#107465,1.); -#107465 = DIRECTION('',(0.E+000,-1.)); -#107466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107467 = PCURVE('',#107468,#107473); -#107468 = CYLINDRICAL_SURFACE('',#107469,0.119270391569); -#107469 = AXIS2_PLACEMENT_3D('',#107470,#107471,#107472); -#107470 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); -#107471 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107472 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107473 = DEFINITIONAL_REPRESENTATION('',(#107474),#107477); -#107474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107475,#107476), +#109792 = CARTESIAN_POINT('',(4.712388980385,-1.35)); +#109793 = CARTESIAN_POINT('',(4.712388980385,-1.15)); +#109794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109795 = ORIENTED_EDGE('',*,*,#109796,.T.); +#109796 = EDGE_CURVE('',#109768,#109690,#109797,.T.); +#109797 = SURFACE_CURVE('',#109798,(#109802,#109809),.PCURVE_S1.); +#109798 = LINE('',#109799,#109800); +#109799 = CARTESIAN_POINT('',(8.65,-0.51959417205,0.530776333563)); +#109800 = VECTOR('',#109801,1.); +#109801 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109802 = PCURVE('',#109731,#109803); +#109803 = DEFINITIONAL_REPRESENTATION('',(#109804),#109808); +#109804 = LINE('',#109805,#109806); +#109805 = CARTESIAN_POINT('',(0.E+000,-1.35)); +#109806 = VECTOR('',#109807,1.); +#109807 = DIRECTION('',(-1.,0.E+000)); +#109808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109809 = PCURVE('',#92627,#109810); +#109810 = DEFINITIONAL_REPRESENTATION('',(#109811),#109815); +#109811 = LINE('',#109812,#109813); +#109812 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#109813 = VECTOR('',#109814,1.); +#109814 = DIRECTION('',(1.,-1.021336205033E-016)); +#109815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109816 = ORIENTED_EDGE('',*,*,#109716,.T.); +#109817 = ORIENTED_EDGE('',*,*,#109818,.F.); +#109818 = EDGE_CURVE('',#109770,#109717,#109819,.T.); +#109819 = SURFACE_CURVE('',#109820,(#109824,#109831),.PCURVE_S1.); +#109820 = LINE('',#109821,#109822); +#109821 = CARTESIAN_POINT('',(8.85,-0.51959417205,0.530776333563)); +#109822 = VECTOR('',#109823,1.); +#109823 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109824 = PCURVE('',#109731,#109825); +#109825 = DEFINITIONAL_REPRESENTATION('',(#109826),#109830); +#109826 = LINE('',#109827,#109828); +#109827 = CARTESIAN_POINT('',(0.E+000,-1.15)); +#109828 = VECTOR('',#109829,1.); +#109829 = DIRECTION('',(-1.,0.E+000)); +#109830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109831 = PCURVE('',#92683,#109832); +#109832 = DEFINITIONAL_REPRESENTATION('',(#109833),#109837); +#109833 = LINE('',#109834,#109835); +#109834 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#109835 = VECTOR('',#109836,1.); +#109836 = DIRECTION('',(-1.,-1.021336205033E-016)); +#109837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109838 = ADVANCED_FACE('',(#109839),#109652,.F.); +#109839 = FACE_BOUND('',#109840,.T.); +#109840 = EDGE_LOOP('',(#109841,#109870,#109891,#109892)); +#109841 = ORIENTED_EDGE('',*,*,#109842,.F.); +#109842 = EDGE_CURVE('',#109843,#109845,#109847,.T.); +#109843 = VERTEX_POINT('',#109844); +#109844 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.530776333563)); +#109845 = VERTEX_POINT('',#109846); +#109846 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.530776333563)); +#109847 = SURFACE_CURVE('',#109848,(#109852,#109859),.PCURVE_S1.); +#109848 = LINE('',#109849,#109850); +#109849 = CARTESIAN_POINT('',(10.,-0.419594812019,0.530776333563)); +#109850 = VECTOR('',#109851,1.); +#109851 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109852 = PCURVE('',#109652,#109853); +#109853 = DEFINITIONAL_REPRESENTATION('',(#109854),#109858); +#109854 = LINE('',#109855,#109856); +#109855 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#109856 = VECTOR('',#109857,1.); +#109857 = DIRECTION('',(0.E+000,-1.)); +#109858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109859 = PCURVE('',#109860,#109865); +#109860 = CYLINDRICAL_SURFACE('',#109861,0.119270391569); +#109861 = AXIS2_PLACEMENT_3D('',#109862,#109863,#109864); +#109862 = CARTESIAN_POINT('',(10.,-0.30032442045,0.530776333563)); +#109863 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109864 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109865 = DEFINITIONAL_REPRESENTATION('',(#109866),#109869); +#109866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109867,#109868), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#107475 = CARTESIAN_POINT('',(4.712388980385,-1.15)); -#107476 = CARTESIAN_POINT('',(4.712388980385,-1.35)); -#107477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107478 = ORIENTED_EDGE('',*,*,#107479,.T.); -#107479 = EDGE_CURVE('',#107451,#107246,#107480,.T.); -#107480 = SURFACE_CURVE('',#107481,(#107485,#107492),.PCURVE_S1.); -#107481 = LINE('',#107482,#107483); -#107482 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.530776333563)); -#107483 = VECTOR('',#107484,1.); -#107484 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#107485 = PCURVE('',#107260,#107486); -#107486 = DEFINITIONAL_REPRESENTATION('',(#107487),#107491); -#107487 = LINE('',#107488,#107489); -#107488 = CARTESIAN_POINT('',(0.E+000,-1.15)); -#107489 = VECTOR('',#107490,1.); -#107490 = DIRECTION('',(1.,0.E+000)); -#107491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107492 = PCURVE('',#90291,#107493); -#107493 = DEFINITIONAL_REPRESENTATION('',(#107494),#107498); -#107494 = LINE('',#107495,#107496); -#107495 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#107496 = VECTOR('',#107497,1.); -#107497 = DIRECTION('',(-1.,-1.021336205033E-016)); -#107498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107499 = ORIENTED_EDGE('',*,*,#107245,.T.); -#107500 = ORIENTED_EDGE('',*,*,#107501,.F.); -#107501 = EDGE_CURVE('',#107453,#107219,#107502,.T.); -#107502 = SURFACE_CURVE('',#107503,(#107507,#107514),.PCURVE_S1.); -#107503 = LINE('',#107504,#107505); -#107504 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.530776333563)); -#107505 = VECTOR('',#107506,1.); -#107506 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); -#107507 = PCURVE('',#107260,#107508); -#107508 = DEFINITIONAL_REPRESENTATION('',(#107509),#107513); -#107509 = LINE('',#107510,#107511); -#107510 = CARTESIAN_POINT('',(0.E+000,-1.35)); -#107511 = VECTOR('',#107512,1.); -#107512 = DIRECTION('',(1.,0.E+000)); -#107513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107514 = PCURVE('',#90235,#107515); -#107515 = DEFINITIONAL_REPRESENTATION('',(#107516),#107520); -#107516 = LINE('',#107517,#107518); -#107517 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#107518 = VECTOR('',#107519,1.); -#107519 = DIRECTION('',(1.,-1.021336205033E-016)); -#107520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107521 = ADVANCED_FACE('',(#107522),#107393,.T.); -#107522 = FACE_BOUND('',#107523,.T.); -#107523 = EDGE_LOOP('',(#107524,#107547,#107548,#107575)); -#107524 = ORIENTED_EDGE('',*,*,#107525,.T.); -#107525 = EDGE_CURVE('',#107526,#107376,#107528,.T.); -#107526 = VERTEX_POINT('',#107527); -#107527 = CARTESIAN_POINT('',(8.65,-0.304819755875,0.75)); -#107528 = SURFACE_CURVE('',#107529,(#107534,#107540),.PCURVE_S1.); -#107529 = CIRCLE('',#107530,0.2192697516); -#107530 = AXIS2_PLACEMENT_3D('',#107531,#107532,#107533); -#107531 = CARTESIAN_POINT('',(8.65,-0.30032442045,0.530776333563)); -#107532 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107533 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107534 = PCURVE('',#107393,#107535); -#107535 = DEFINITIONAL_REPRESENTATION('',(#107536),#107539); -#107536 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107537,#107538), +#109867 = CARTESIAN_POINT('',(4.712388980385,-1.15)); +#109868 = CARTESIAN_POINT('',(4.712388980385,-1.35)); +#109869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109870 = ORIENTED_EDGE('',*,*,#109871,.T.); +#109871 = EDGE_CURVE('',#109843,#109638,#109872,.T.); +#109872 = SURFACE_CURVE('',#109873,(#109877,#109884),.PCURVE_S1.); +#109873 = LINE('',#109874,#109875); +#109874 = CARTESIAN_POINT('',(8.85,-0.419594812019,0.530776333563)); +#109875 = VECTOR('',#109876,1.); +#109876 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109877 = PCURVE('',#109652,#109878); +#109878 = DEFINITIONAL_REPRESENTATION('',(#109879),#109883); +#109879 = LINE('',#109880,#109881); +#109880 = CARTESIAN_POINT('',(0.E+000,-1.15)); +#109881 = VECTOR('',#109882,1.); +#109882 = DIRECTION('',(1.,0.E+000)); +#109883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109884 = PCURVE('',#92683,#109885); +#109885 = DEFINITIONAL_REPRESENTATION('',(#109886),#109890); +#109886 = LINE('',#109887,#109888); +#109887 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#109888 = VECTOR('',#109889,1.); +#109889 = DIRECTION('',(-1.,-1.021336205033E-016)); +#109890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109891 = ORIENTED_EDGE('',*,*,#109637,.T.); +#109892 = ORIENTED_EDGE('',*,*,#109893,.F.); +#109893 = EDGE_CURVE('',#109845,#109611,#109894,.T.); +#109894 = SURFACE_CURVE('',#109895,(#109899,#109906),.PCURVE_S1.); +#109895 = LINE('',#109896,#109897); +#109896 = CARTESIAN_POINT('',(8.65,-0.419594812019,0.530776333563)); +#109897 = VECTOR('',#109898,1.); +#109898 = DIRECTION('',(0.E+000,-1.021336205033E-016,-1.)); +#109899 = PCURVE('',#109652,#109900); +#109900 = DEFINITIONAL_REPRESENTATION('',(#109901),#109905); +#109901 = LINE('',#109902,#109903); +#109902 = CARTESIAN_POINT('',(0.E+000,-1.35)); +#109903 = VECTOR('',#109904,1.); +#109904 = DIRECTION('',(1.,0.E+000)); +#109905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109906 = PCURVE('',#92627,#109907); +#109907 = DEFINITIONAL_REPRESENTATION('',(#109908),#109912); +#109908 = LINE('',#109909,#109910); +#109909 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#109910 = VECTOR('',#109911,1.); +#109911 = DIRECTION('',(1.,-1.021336205033E-016)); +#109912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109913 = ADVANCED_FACE('',(#109914),#109785,.T.); +#109914 = FACE_BOUND('',#109915,.T.); +#109915 = EDGE_LOOP('',(#109916,#109939,#109940,#109967)); +#109916 = ORIENTED_EDGE('',*,*,#109917,.T.); +#109917 = EDGE_CURVE('',#109918,#109768,#109920,.T.); +#109918 = VERTEX_POINT('',#109919); +#109919 = CARTESIAN_POINT('',(8.65,-0.304819755875,0.75)); +#109920 = SURFACE_CURVE('',#109921,(#109926,#109932),.PCURVE_S1.); +#109921 = CIRCLE('',#109922,0.2192697516); +#109922 = AXIS2_PLACEMENT_3D('',#109923,#109924,#109925); +#109923 = CARTESIAN_POINT('',(8.65,-0.30032442045,0.530776333563)); +#109924 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109925 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109926 = PCURVE('',#109785,#109927); +#109927 = DEFINITIONAL_REPRESENTATION('',(#109928),#109931); +#109928 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109929,#109930), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#107537 = CARTESIAN_POINT('',(3.162095483347,-1.35)); -#107538 = CARTESIAN_POINT('',(4.712388980385,-1.35)); -#107539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107540 = PCURVE('',#90235,#107541); -#107541 = DEFINITIONAL_REPRESENTATION('',(#107542),#107546); -#107542 = CIRCLE('',#107543,0.2192697516); -#107543 = AXIS2_PLACEMENT_2D('',#107544,#107545); -#107544 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#107545 = DIRECTION('',(1.,0.E+000)); -#107546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107547 = ORIENTED_EDGE('',*,*,#107375,.T.); -#107548 = ORIENTED_EDGE('',*,*,#107549,.F.); -#107549 = EDGE_CURVE('',#107550,#107378,#107552,.T.); -#107550 = VERTEX_POINT('',#107551); -#107551 = CARTESIAN_POINT('',(8.85,-0.304819755875,0.75)); -#107552 = SURFACE_CURVE('',#107553,(#107558,#107564),.PCURVE_S1.); -#107553 = CIRCLE('',#107554,0.2192697516); -#107554 = AXIS2_PLACEMENT_3D('',#107555,#107556,#107557); -#107555 = CARTESIAN_POINT('',(8.85,-0.30032442045,0.530776333563)); -#107556 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107557 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107558 = PCURVE('',#107393,#107559); -#107559 = DEFINITIONAL_REPRESENTATION('',(#107560),#107563); -#107560 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107561,#107562), +#109929 = CARTESIAN_POINT('',(3.162095483347,-1.35)); +#109930 = CARTESIAN_POINT('',(4.712388980385,-1.35)); +#109931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109932 = PCURVE('',#92627,#109933); +#109933 = DEFINITIONAL_REPRESENTATION('',(#109934),#109938); +#109934 = CIRCLE('',#109935,0.2192697516); +#109935 = AXIS2_PLACEMENT_2D('',#109936,#109937); +#109936 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#109937 = DIRECTION('',(1.,0.E+000)); +#109938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109939 = ORIENTED_EDGE('',*,*,#109767,.T.); +#109940 = ORIENTED_EDGE('',*,*,#109941,.F.); +#109941 = EDGE_CURVE('',#109942,#109770,#109944,.T.); +#109942 = VERTEX_POINT('',#109943); +#109943 = CARTESIAN_POINT('',(8.85,-0.304819755875,0.75)); +#109944 = SURFACE_CURVE('',#109945,(#109950,#109956),.PCURVE_S1.); +#109945 = CIRCLE('',#109946,0.2192697516); +#109946 = AXIS2_PLACEMENT_3D('',#109947,#109948,#109949); +#109947 = CARTESIAN_POINT('',(8.85,-0.30032442045,0.530776333563)); +#109948 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109949 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#109950 = PCURVE('',#109785,#109951); +#109951 = DEFINITIONAL_REPRESENTATION('',(#109952),#109955); +#109952 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109953,#109954), .UNSPECIFIED.,.F.,.F.,(2,2),(3.162095483347,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#107561 = CARTESIAN_POINT('',(3.162095483347,-1.15)); -#107562 = CARTESIAN_POINT('',(4.712388980385,-1.15)); -#107563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#109953 = CARTESIAN_POINT('',(3.162095483347,-1.15)); +#109954 = CARTESIAN_POINT('',(4.712388980385,-1.15)); +#109955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#107564 = PCURVE('',#90291,#107565); -#107565 = DEFINITIONAL_REPRESENTATION('',(#107566),#107574); -#107566 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107567,#107568,#107569, - #107570,#107571,#107572,#107573),.UNSPECIFIED.,.T.,.F.) +#109956 = PCURVE('',#92683,#109957); +#109957 = DEFINITIONAL_REPRESENTATION('',(#109958),#109966); +#109958 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109959,#109960,#109961, + #109962,#109963,#109964,#109965),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#107567 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#107568 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); -#107569 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); -#107570 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); -#107571 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); -#107572 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); -#107573 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); -#107574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107575 = ORIENTED_EDGE('',*,*,#107576,.T.); -#107576 = EDGE_CURVE('',#107550,#107526,#107577,.T.); -#107577 = SURFACE_CURVE('',#107578,(#107582,#107588),.PCURVE_S1.); -#107578 = LINE('',#107579,#107580); -#107579 = CARTESIAN_POINT('',(8.65,-0.304819755875,0.75)); -#107580 = VECTOR('',#107581,1.); -#107581 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107582 = PCURVE('',#107393,#107583); -#107583 = DEFINITIONAL_REPRESENTATION('',(#107584),#107587); -#107584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107585,#107586), +#109959 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#109960 = CARTESIAN_POINT('',(-0.338493418037,0.607309922322)); +#109961 = CARTESIAN_POINT('',(-9.588790637048E-003,0.417416747155)); +#109962 = CARTESIAN_POINT('',(0.319315836763,0.227523571988)); +#109963 = CARTESIAN_POINT('',(-9.588790637048E-003,3.76303968215E-002)); +#109964 = CARTESIAN_POINT('',(-0.338493418037,-0.152262778345)); +#109965 = CARTESIAN_POINT('',(-0.338493418037,0.227523571988)); +#109966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109967 = ORIENTED_EDGE('',*,*,#109968,.T.); +#109968 = EDGE_CURVE('',#109942,#109918,#109969,.T.); +#109969 = SURFACE_CURVE('',#109970,(#109974,#109980),.PCURVE_S1.); +#109970 = LINE('',#109971,#109972); +#109971 = CARTESIAN_POINT('',(8.65,-0.304819755875,0.75)); +#109972 = VECTOR('',#109973,1.); +#109973 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#109974 = PCURVE('',#109785,#109975); +#109975 = DEFINITIONAL_REPRESENTATION('',(#109976),#109979); +#109976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109977,#109978), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#107585 = CARTESIAN_POINT('',(3.162095483347,-1.15)); -#107586 = CARTESIAN_POINT('',(3.162095483347,-1.35)); -#107587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107588 = PCURVE('',#90263,#107589); -#107589 = DEFINITIONAL_REPRESENTATION('',(#107590),#107594); -#107590 = LINE('',#107591,#107592); -#107591 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); -#107592 = VECTOR('',#107593,1.); -#107593 = DIRECTION('',(0.E+000,-1.)); -#107594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107595 = ADVANCED_FACE('',(#107596),#107468,.F.); -#107596 = FACE_BOUND('',#107597,.F.); -#107597 = EDGE_LOOP('',(#107598,#107625,#107647,#107668)); -#107598 = ORIENTED_EDGE('',*,*,#107599,.F.); -#107599 = EDGE_CURVE('',#107600,#107451,#107602,.T.); -#107600 = VERTEX_POINT('',#107601); -#107601 = CARTESIAN_POINT('',(8.85,-0.303662633502,0.65)); -#107602 = SURFACE_CURVE('',#107603,(#107608,#107614),.PCURVE_S1.); -#107603 = CIRCLE('',#107604,0.119270391569); -#107604 = AXIS2_PLACEMENT_3D('',#107605,#107606,#107607); -#107605 = CARTESIAN_POINT('',(8.85,-0.30032442045,0.530776333563)); -#107606 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107607 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107608 = PCURVE('',#107468,#107609); -#107609 = DEFINITIONAL_REPRESENTATION('',(#107610),#107613); -#107610 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107611,#107612), +#109977 = CARTESIAN_POINT('',(3.162095483347,-1.15)); +#109978 = CARTESIAN_POINT('',(3.162095483347,-1.35)); +#109979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109980 = PCURVE('',#92655,#109981); +#109981 = DEFINITIONAL_REPRESENTATION('',(#109982),#109986); +#109982 = LINE('',#109983,#109984); +#109983 = CARTESIAN_POINT('',(0.223028236564,0.E+000)); +#109984 = VECTOR('',#109985,1.); +#109985 = DIRECTION('',(0.E+000,-1.)); +#109986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#109987 = ADVANCED_FACE('',(#109988),#109860,.F.); +#109988 = FACE_BOUND('',#109989,.F.); +#109989 = EDGE_LOOP('',(#109990,#110017,#110039,#110060)); +#109990 = ORIENTED_EDGE('',*,*,#109991,.F.); +#109991 = EDGE_CURVE('',#109992,#109843,#109994,.T.); +#109992 = VERTEX_POINT('',#109993); +#109993 = CARTESIAN_POINT('',(8.85,-0.303662633502,0.65)); +#109994 = SURFACE_CURVE('',#109995,(#110000,#110006),.PCURVE_S1.); +#109995 = CIRCLE('',#109996,0.119270391569); +#109996 = AXIS2_PLACEMENT_3D('',#109997,#109998,#109999); +#109997 = CARTESIAN_POINT('',(8.85,-0.30032442045,0.530776333563)); +#109998 = DIRECTION('',(1.,0.E+000,0.E+000)); +#109999 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#110000 = PCURVE('',#109860,#110001); +#110001 = DEFINITIONAL_REPRESENTATION('',(#110002),#110005); +#110002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110003,#110004), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#107611 = CARTESIAN_POINT('',(3.169584923929,-1.15)); -#107612 = CARTESIAN_POINT('',(4.712388980385,-1.15)); -#107613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110003 = CARTESIAN_POINT('',(3.169584923929,-1.15)); +#110004 = CARTESIAN_POINT('',(4.712388980385,-1.15)); +#110005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#107614 = PCURVE('',#90291,#107615); -#107615 = DEFINITIONAL_REPRESENTATION('',(#107616),#107624); -#107616 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#107617,#107618,#107619, - #107620,#107621,#107622,#107623),.UNSPECIFIED.,.F.,.F.) +#110006 = PCURVE('',#92683,#110007); +#110007 = DEFINITIONAL_REPRESENTATION('',(#110008),#110016); +#110008 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110009,#110010,#110011, + #110012,#110013,#110014,#110015),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#107617 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#107618 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); -#107619 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); -#107620 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); -#107621 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); -#107622 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); -#107623 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); -#107624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107625 = ORIENTED_EDGE('',*,*,#107626,.F.); -#107626 = EDGE_CURVE('',#107627,#107600,#107629,.T.); -#107627 = VERTEX_POINT('',#107628); -#107628 = CARTESIAN_POINT('',(8.65,-0.303662633502,0.65)); -#107629 = SURFACE_CURVE('',#107630,(#107634,#107640),.PCURVE_S1.); -#107630 = LINE('',#107631,#107632); -#107631 = CARTESIAN_POINT('',(8.65,-0.303662633502,0.65)); -#107632 = VECTOR('',#107633,1.); -#107633 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107634 = PCURVE('',#107468,#107635); -#107635 = DEFINITIONAL_REPRESENTATION('',(#107636),#107639); -#107636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107637,#107638), +#110009 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#110010 = CARTESIAN_POINT('',(-0.238494058006,0.434105950025)); +#110011 = CARTESIAN_POINT('',(-5.958847065239E-002,0.330814761007)); +#110012 = CARTESIAN_POINT('',(0.119317116701,0.227523571988)); +#110013 = CARTESIAN_POINT('',(-5.958847065239E-002,0.12423238297)); +#110014 = CARTESIAN_POINT('',(-0.238494058006,2.094119395209E-002)); +#110015 = CARTESIAN_POINT('',(-0.238494058006,0.227523571988)); +#110016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110017 = ORIENTED_EDGE('',*,*,#110018,.F.); +#110018 = EDGE_CURVE('',#110019,#109992,#110021,.T.); +#110019 = VERTEX_POINT('',#110020); +#110020 = CARTESIAN_POINT('',(8.65,-0.303662633502,0.65)); +#110021 = SURFACE_CURVE('',#110022,(#110026,#110032),.PCURVE_S1.); +#110022 = LINE('',#110023,#110024); +#110023 = CARTESIAN_POINT('',(8.65,-0.303662633502,0.65)); +#110024 = VECTOR('',#110025,1.); +#110025 = DIRECTION('',(1.,0.E+000,0.E+000)); +#110026 = PCURVE('',#109860,#110027); +#110027 = DEFINITIONAL_REPRESENTATION('',(#110028),#110031); +#110028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110029,#110030), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#107637 = CARTESIAN_POINT('',(3.169584923929,-1.35)); -#107638 = CARTESIAN_POINT('',(3.169584923929,-1.15)); -#107639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107640 = PCURVE('',#90317,#107641); -#107641 = DEFINITIONAL_REPRESENTATION('',(#107642),#107646); -#107642 = LINE('',#107643,#107644); -#107643 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); -#107644 = VECTOR('',#107645,1.); -#107645 = DIRECTION('',(0.E+000,1.)); -#107646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107647 = ORIENTED_EDGE('',*,*,#107648,.T.); -#107648 = EDGE_CURVE('',#107627,#107453,#107649,.T.); -#107649 = SURFACE_CURVE('',#107650,(#107655,#107661),.PCURVE_S1.); -#107650 = CIRCLE('',#107651,0.119270391569); -#107651 = AXIS2_PLACEMENT_3D('',#107652,#107653,#107654); -#107652 = CARTESIAN_POINT('',(8.65,-0.30032442045,0.530776333563)); -#107653 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107654 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107655 = PCURVE('',#107468,#107656); -#107656 = DEFINITIONAL_REPRESENTATION('',(#107657),#107660); -#107657 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107658,#107659), +#110029 = CARTESIAN_POINT('',(3.169584923929,-1.35)); +#110030 = CARTESIAN_POINT('',(3.169584923929,-1.15)); +#110031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110032 = PCURVE('',#92709,#110033); +#110033 = DEFINITIONAL_REPRESENTATION('',(#110034),#110038); +#110034 = LINE('',#110035,#110036); +#110035 = CARTESIAN_POINT('',(-0.224185358936,0.E+000)); +#110036 = VECTOR('',#110037,1.); +#110037 = DIRECTION('',(0.E+000,1.)); +#110038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110039 = ORIENTED_EDGE('',*,*,#110040,.T.); +#110040 = EDGE_CURVE('',#110019,#109845,#110041,.T.); +#110041 = SURFACE_CURVE('',#110042,(#110047,#110053),.PCURVE_S1.); +#110042 = CIRCLE('',#110043,0.119270391569); +#110043 = AXIS2_PLACEMENT_3D('',#110044,#110045,#110046); +#110044 = CARTESIAN_POINT('',(8.65,-0.30032442045,0.530776333563)); +#110045 = DIRECTION('',(1.,0.E+000,0.E+000)); +#110046 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#110047 = PCURVE('',#109860,#110048); +#110048 = DEFINITIONAL_REPRESENTATION('',(#110049),#110052); +#110049 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110050,#110051), .UNSPECIFIED.,.F.,.F.,(2,2),(3.169584923929,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#107658 = CARTESIAN_POINT('',(3.169584923929,-1.35)); -#107659 = CARTESIAN_POINT('',(4.712388980385,-1.35)); -#107660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107661 = PCURVE('',#90235,#107662); -#107662 = DEFINITIONAL_REPRESENTATION('',(#107663),#107667); -#107663 = CIRCLE('',#107664,0.119270391569); -#107664 = AXIS2_PLACEMENT_2D('',#107665,#107666); -#107665 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#107666 = DIRECTION('',(1.,0.E+000)); -#107667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107668 = ORIENTED_EDGE('',*,*,#107450,.F.); -#107669 = ADVANCED_FACE('',(#107670),#90235,.F.); -#107670 = FACE_BOUND('',#107671,.T.); -#107671 = EDGE_LOOP('',(#107672,#107693,#107694,#107695,#107696,#107697, - #107718,#107719,#107720,#107721,#107722,#107743)); -#107672 = ORIENTED_EDGE('',*,*,#107673,.F.); -#107673 = EDGE_CURVE('',#107627,#90220,#107674,.T.); -#107674 = SURFACE_CURVE('',#107675,(#107679,#107686),.PCURVE_S1.); -#107675 = LINE('',#107676,#107677); -#107676 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); -#107677 = VECTOR('',#107678,1.); -#107678 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#107679 = PCURVE('',#90235,#107680); -#107680 = DEFINITIONAL_REPRESENTATION('',(#107681),#107685); -#107681 = LINE('',#107682,#107683); -#107682 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107683 = VECTOR('',#107684,1.); -#107684 = DIRECTION('',(-3.563627120235E-016,1.)); -#107685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107686 = PCURVE('',#90317,#107687); -#107687 = DEFINITIONAL_REPRESENTATION('',(#107688),#107692); -#107688 = LINE('',#107689,#107690); -#107689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107690 = VECTOR('',#107691,1.); -#107691 = DIRECTION('',(-1.,0.E+000)); -#107692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107693 = ORIENTED_EDGE('',*,*,#107648,.T.); -#107694 = ORIENTED_EDGE('',*,*,#107501,.T.); -#107695 = ORIENTED_EDGE('',*,*,#107218,.T.); -#107696 = ORIENTED_EDGE('',*,*,#107062,.T.); -#107697 = ORIENTED_EDGE('',*,*,#107698,.T.); -#107698 = EDGE_CURVE('',#107035,#107116,#107699,.T.); -#107699 = SURFACE_CURVE('',#107700,(#107704,#107711),.PCURVE_S1.); -#107700 = LINE('',#107701,#107702); -#107701 = CARTESIAN_POINT('',(8.65,-1.,1.159810404338E-002)); -#107702 = VECTOR('',#107703,1.); -#107703 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); -#107704 = PCURVE('',#90235,#107705); -#107705 = DEFINITIONAL_REPRESENTATION('',(#107706),#107710); -#107706 = LINE('',#107707,#107708); -#107707 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#107708 = VECTOR('',#107709,1.); -#107709 = DIRECTION('',(-1.,-2.101748079665E-016)); -#107710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107711 = PCURVE('',#107050,#107712); -#107712 = DEFINITIONAL_REPRESENTATION('',(#107713),#107717); -#107713 = LINE('',#107714,#107715); -#107714 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); -#107715 = VECTOR('',#107716,1.); -#107716 = DIRECTION('',(-1.,0.E+000)); -#107717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107718 = ORIENTED_EDGE('',*,*,#107113,.F.); -#107719 = ORIENTED_EDGE('',*,*,#107297,.F.); -#107720 = ORIENTED_EDGE('',*,*,#107404,.F.); -#107721 = ORIENTED_EDGE('',*,*,#107525,.F.); -#107722 = ORIENTED_EDGE('',*,*,#107723,.T.); -#107723 = EDGE_CURVE('',#107526,#90218,#107724,.T.); -#107724 = SURFACE_CURVE('',#107725,(#107729,#107736),.PCURVE_S1.); -#107725 = LINE('',#107726,#107727); -#107726 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.75)); -#107727 = VECTOR('',#107728,1.); -#107728 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#107729 = PCURVE('',#90235,#107730); -#107730 = DEFINITIONAL_REPRESENTATION('',(#107731),#107735); -#107731 = LINE('',#107732,#107733); -#107732 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#107733 = VECTOR('',#107734,1.); -#107734 = DIRECTION('',(-3.563627120235E-016,1.)); -#107735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107736 = PCURVE('',#90263,#107737); -#107737 = DEFINITIONAL_REPRESENTATION('',(#107738),#107742); -#107738 = LINE('',#107739,#107740); -#107739 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107740 = VECTOR('',#107741,1.); -#107741 = DIRECTION('',(1.,0.E+000)); -#107742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107743 = ORIENTED_EDGE('',*,*,#90217,.T.); -#107744 = ADVANCED_FACE('',(#107745),#90263,.F.); -#107745 = FACE_BOUND('',#107746,.T.); -#107746 = EDGE_LOOP('',(#107747,#107748,#107769,#107770)); -#107747 = ORIENTED_EDGE('',*,*,#107576,.F.); -#107748 = ORIENTED_EDGE('',*,*,#107749,.T.); -#107749 = EDGE_CURVE('',#107550,#90248,#107750,.T.); -#107750 = SURFACE_CURVE('',#107751,(#107755,#107762),.PCURVE_S1.); -#107751 = LINE('',#107752,#107753); -#107752 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.75)); -#107753 = VECTOR('',#107754,1.); -#107754 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#107755 = PCURVE('',#90263,#107756); -#107756 = DEFINITIONAL_REPRESENTATION('',(#107757),#107761); -#107757 = LINE('',#107758,#107759); -#107758 = CARTESIAN_POINT('',(0.E+000,0.2)); -#107759 = VECTOR('',#107760,1.); -#107760 = DIRECTION('',(1.,0.E+000)); -#107761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107762 = PCURVE('',#90291,#107763); -#107763 = DEFINITIONAL_REPRESENTATION('',(#107764),#107768); -#107764 = LINE('',#107765,#107766); -#107765 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#107766 = VECTOR('',#107767,1.); -#107767 = DIRECTION('',(3.563627120235E-016,1.)); -#107768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107769 = ORIENTED_EDGE('',*,*,#90247,.T.); -#107770 = ORIENTED_EDGE('',*,*,#107723,.F.); -#107771 = ADVANCED_FACE('',(#107772),#90291,.F.); -#107772 = FACE_BOUND('',#107773,.T.); -#107773 = EDGE_LOOP('',(#107774,#107775,#107776,#107777,#107778,#107779, - #107800,#107801,#107802,#107803,#107804,#107825)); -#107774 = ORIENTED_EDGE('',*,*,#107749,.F.); -#107775 = ORIENTED_EDGE('',*,*,#107549,.T.); -#107776 = ORIENTED_EDGE('',*,*,#107426,.T.); -#107777 = ORIENTED_EDGE('',*,*,#107351,.T.); -#107778 = ORIENTED_EDGE('',*,*,#107166,.T.); -#107779 = ORIENTED_EDGE('',*,*,#107780,.T.); -#107780 = EDGE_CURVE('',#107144,#107007,#107781,.T.); -#107781 = SURFACE_CURVE('',#107782,(#107786,#107793),.PCURVE_S1.); -#107782 = LINE('',#107783,#107784); -#107783 = CARTESIAN_POINT('',(8.85,-1.,1.159810404338E-002)); -#107784 = VECTOR('',#107785,1.); -#107785 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); -#107786 = PCURVE('',#90291,#107787); -#107787 = DEFINITIONAL_REPRESENTATION('',(#107788),#107792); -#107788 = LINE('',#107789,#107790); -#107789 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#107790 = VECTOR('',#107791,1.); -#107791 = DIRECTION('',(-1.,2.101748079665E-016)); -#107792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107793 = PCURVE('',#107050,#107794); -#107794 = DEFINITIONAL_REPRESENTATION('',(#107795),#107799); -#107795 = LINE('',#107796,#107797); -#107796 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); -#107797 = VECTOR('',#107798,1.); -#107798 = DIRECTION('',(1.,0.E+000)); -#107799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107800 = ORIENTED_EDGE('',*,*,#107004,.F.); -#107801 = ORIENTED_EDGE('',*,*,#107272,.F.); -#107802 = ORIENTED_EDGE('',*,*,#107479,.F.); -#107803 = ORIENTED_EDGE('',*,*,#107599,.F.); -#107804 = ORIENTED_EDGE('',*,*,#107805,.T.); -#107805 = EDGE_CURVE('',#107600,#90276,#107806,.T.); -#107806 = SURFACE_CURVE('',#107807,(#107811,#107818),.PCURVE_S1.); -#107807 = LINE('',#107808,#107809); -#107808 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.65)); -#107809 = VECTOR('',#107810,1.); -#107810 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); -#107811 = PCURVE('',#90291,#107812); -#107812 = DEFINITIONAL_REPRESENTATION('',(#107813),#107817); -#107813 = LINE('',#107814,#107815); -#107814 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107815 = VECTOR('',#107816,1.); -#107816 = DIRECTION('',(3.563627120235E-016,1.)); -#107817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107818 = PCURVE('',#90317,#107819); -#107819 = DEFINITIONAL_REPRESENTATION('',(#107820),#107824); -#107820 = LINE('',#107821,#107822); -#107821 = CARTESIAN_POINT('',(0.E+000,0.2)); -#107822 = VECTOR('',#107823,1.); -#107823 = DIRECTION('',(-1.,0.E+000)); -#107824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107825 = ORIENTED_EDGE('',*,*,#90275,.T.); -#107826 = ADVANCED_FACE('',(#107827),#90317,.F.); -#107827 = FACE_BOUND('',#107828,.T.); -#107828 = EDGE_LOOP('',(#107829,#107830,#107831,#107832)); -#107829 = ORIENTED_EDGE('',*,*,#107626,.F.); -#107830 = ORIENTED_EDGE('',*,*,#107673,.T.); -#107831 = ORIENTED_EDGE('',*,*,#90303,.T.); -#107832 = ORIENTED_EDGE('',*,*,#107805,.F.); -#107833 = ADVANCED_FACE('',(#107834),#107050,.T.); -#107834 = FACE_BOUND('',#107835,.T.); -#107835 = EDGE_LOOP('',(#107836,#107837,#107838,#107839)); -#107836 = ORIENTED_EDGE('',*,*,#107780,.F.); -#107837 = ORIENTED_EDGE('',*,*,#107143,.F.); -#107838 = ORIENTED_EDGE('',*,*,#107698,.F.); -#107839 = ORIENTED_EDGE('',*,*,#107034,.F.); -#107840 = ADVANCED_FACE('',(#107841),#107855,.F.); -#107841 = FACE_BOUND('',#107842,.T.); -#107842 = EDGE_LOOP('',(#107843,#107878,#107901,#107928)); -#107843 = ORIENTED_EDGE('',*,*,#107844,.F.); -#107844 = EDGE_CURVE('',#107845,#107847,#107849,.T.); -#107845 = VERTEX_POINT('',#107846); -#107846 = CARTESIAN_POINT('',(-1.,1.35,-0.308197125857)); -#107847 = VERTEX_POINT('',#107848); -#107848 = CARTESIAN_POINT('',(-1.,1.15,-0.308197125857)); -#107849 = SURFACE_CURVE('',#107850,(#107854,#107866),.PCURVE_S1.); -#107850 = LINE('',#107851,#107852); -#107851 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#107852 = VECTOR('',#107853,1.); -#107853 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#107854 = PCURVE('',#107855,#107860); -#107855 = PLANE('',#107856); -#107856 = AXIS2_PLACEMENT_3D('',#107857,#107858,#107859); -#107857 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#107858 = DIRECTION('',(0.E+000,0.E+000,1.)); -#107859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#107860 = DEFINITIONAL_REPRESENTATION('',(#107861),#107865); -#107861 = LINE('',#107862,#107863); -#107862 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#107863 = VECTOR('',#107864,1.); -#107864 = DIRECTION('',(4.440892098501E-016,-1.)); -#107865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107866 = PCURVE('',#107867,#107872); -#107867 = PLANE('',#107868); -#107868 = AXIS2_PLACEMENT_3D('',#107869,#107870,#107871); -#107869 = CARTESIAN_POINT('',(-1.,1.25,-0.258196742327)); -#107870 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#107871 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#107872 = DEFINITIONAL_REPRESENTATION('',(#107873),#107877); -#107873 = LINE('',#107874,#107875); -#107874 = CARTESIAN_POINT('',(-8.75,-5.000038352949E-002)); -#107875 = VECTOR('',#107876,1.); -#107876 = DIRECTION('',(1.,0.E+000)); -#107877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107878 = ORIENTED_EDGE('',*,*,#107879,.F.); -#107879 = EDGE_CURVE('',#107880,#107845,#107882,.T.); -#107880 = VERTEX_POINT('',#107881); -#107881 = CARTESIAN_POINT('',(-0.74341632541,1.35,-0.308197125857)); -#107882 = SURFACE_CURVE('',#107883,(#107887,#107894),.PCURVE_S1.); -#107883 = LINE('',#107884,#107885); -#107884 = CARTESIAN_POINT('',(-0.74341632541,1.35,-0.308197125857)); -#107885 = VECTOR('',#107886,1.); -#107886 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107887 = PCURVE('',#107855,#107888); -#107888 = DEFINITIONAL_REPRESENTATION('',(#107889),#107893); -#107889 = LINE('',#107890,#107891); -#107890 = CARTESIAN_POINT('',(3.774758283726E-015,-8.65)); -#107891 = VECTOR('',#107892,1.); -#107892 = DIRECTION('',(-1.,0.E+000)); -#107893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107894 = PCURVE('',#92121,#107895); -#107895 = DEFINITIONAL_REPRESENTATION('',(#107896),#107900); -#107896 = LINE('',#107897,#107898); -#107897 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#107898 = VECTOR('',#107899,1.); -#107899 = DIRECTION('',(0.E+000,-1.)); -#107900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107901 = ORIENTED_EDGE('',*,*,#107902,.F.); -#107902 = EDGE_CURVE('',#107903,#107880,#107905,.T.); -#107903 = VERTEX_POINT('',#107904); -#107904 = CARTESIAN_POINT('',(-0.74341632541,1.15,-0.308197125857)); -#107905 = SURFACE_CURVE('',#107906,(#107910,#107917),.PCURVE_S1.); -#107906 = LINE('',#107907,#107908); -#107907 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#107908 = VECTOR('',#107909,1.); -#107909 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#107910 = PCURVE('',#107855,#107911); -#107911 = DEFINITIONAL_REPRESENTATION('',(#107912),#107916); -#107912 = LINE('',#107913,#107914); -#107913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#107914 = VECTOR('',#107915,1.); -#107915 = DIRECTION('',(-4.440892098501E-016,1.)); -#107916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107917 = PCURVE('',#107918,#107923); -#107918 = CYLINDRICAL_SURFACE('',#107919,0.308574064194); -#107919 = AXIS2_PLACEMENT_3D('',#107920,#107921,#107922); -#107920 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#107921 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#107922 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#107923 = DEFINITIONAL_REPRESENTATION('',(#107924),#107927); -#107924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#107925,#107926), +#110050 = CARTESIAN_POINT('',(3.169584923929,-1.35)); +#110051 = CARTESIAN_POINT('',(4.712388980385,-1.35)); +#110052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110053 = PCURVE('',#92627,#110054); +#110054 = DEFINITIONAL_REPRESENTATION('',(#110055),#110059); +#110055 = CIRCLE('',#110056,0.119270391569); +#110056 = AXIS2_PLACEMENT_2D('',#110057,#110058); +#110057 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#110058 = DIRECTION('',(1.,0.E+000)); +#110059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110060 = ORIENTED_EDGE('',*,*,#109842,.F.); +#110061 = ADVANCED_FACE('',(#110062),#92627,.F.); +#110062 = FACE_BOUND('',#110063,.T.); +#110063 = EDGE_LOOP('',(#110064,#110085,#110086,#110087,#110088,#110089, + #110110,#110111,#110112,#110113,#110114,#110135)); +#110064 = ORIENTED_EDGE('',*,*,#110065,.F.); +#110065 = EDGE_CURVE('',#110019,#92612,#110066,.T.); +#110066 = SURFACE_CURVE('',#110067,(#110071,#110078),.PCURVE_S1.); +#110067 = LINE('',#110068,#110069); +#110068 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.65)); +#110069 = VECTOR('',#110070,1.); +#110070 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#110071 = PCURVE('',#92627,#110072); +#110072 = DEFINITIONAL_REPRESENTATION('',(#110073),#110077); +#110073 = LINE('',#110074,#110075); +#110074 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110075 = VECTOR('',#110076,1.); +#110076 = DIRECTION('',(-3.563627120235E-016,1.)); +#110077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110078 = PCURVE('',#92709,#110079); +#110079 = DEFINITIONAL_REPRESENTATION('',(#110080),#110084); +#110080 = LINE('',#110081,#110082); +#110081 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110082 = VECTOR('',#110083,1.); +#110083 = DIRECTION('',(-1.,0.E+000)); +#110084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110085 = ORIENTED_EDGE('',*,*,#110040,.T.); +#110086 = ORIENTED_EDGE('',*,*,#109893,.T.); +#110087 = ORIENTED_EDGE('',*,*,#109610,.T.); +#110088 = ORIENTED_EDGE('',*,*,#109454,.T.); +#110089 = ORIENTED_EDGE('',*,*,#110090,.T.); +#110090 = EDGE_CURVE('',#109427,#109508,#110091,.T.); +#110091 = SURFACE_CURVE('',#110092,(#110096,#110103),.PCURVE_S1.); +#110092 = LINE('',#110093,#110094); +#110093 = CARTESIAN_POINT('',(8.65,-1.,1.159810404338E-002)); +#110094 = VECTOR('',#110095,1.); +#110095 = DIRECTION('',(0.E+000,-2.101748079665E-016,1.)); +#110096 = PCURVE('',#92627,#110097); +#110097 = DEFINITIONAL_REPRESENTATION('',(#110098),#110102); +#110098 = LINE('',#110099,#110100); +#110099 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#110100 = VECTOR('',#110101,1.); +#110101 = DIRECTION('',(-1.,-2.101748079665E-016)); +#110102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110103 = PCURVE('',#109442,#110104); +#110104 = DEFINITIONAL_REPRESENTATION('',(#110105),#110109); +#110105 = LINE('',#110106,#110107); +#110106 = CARTESIAN_POINT('',(-0.269794846371,-1.E-001)); +#110107 = VECTOR('',#110108,1.); +#110108 = DIRECTION('',(-1.,0.E+000)); +#110109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110110 = ORIENTED_EDGE('',*,*,#109505,.F.); +#110111 = ORIENTED_EDGE('',*,*,#109689,.F.); +#110112 = ORIENTED_EDGE('',*,*,#109796,.F.); +#110113 = ORIENTED_EDGE('',*,*,#109917,.F.); +#110114 = ORIENTED_EDGE('',*,*,#110115,.T.); +#110115 = EDGE_CURVE('',#109918,#92610,#110116,.T.); +#110116 = SURFACE_CURVE('',#110117,(#110121,#110128),.PCURVE_S1.); +#110117 = LINE('',#110118,#110119); +#110118 = CARTESIAN_POINT('',(8.65,-0.527847992439,0.75)); +#110119 = VECTOR('',#110120,1.); +#110120 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#110121 = PCURVE('',#92627,#110122); +#110122 = DEFINITIONAL_REPRESENTATION('',(#110123),#110127); +#110123 = LINE('',#110124,#110125); +#110124 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#110125 = VECTOR('',#110126,1.); +#110126 = DIRECTION('',(-3.563627120235E-016,1.)); +#110127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110128 = PCURVE('',#92655,#110129); +#110129 = DEFINITIONAL_REPRESENTATION('',(#110130),#110134); +#110130 = LINE('',#110131,#110132); +#110131 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110132 = VECTOR('',#110133,1.); +#110133 = DIRECTION('',(1.,0.E+000)); +#110134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110135 = ORIENTED_EDGE('',*,*,#92609,.T.); +#110136 = ADVANCED_FACE('',(#110137),#92655,.F.); +#110137 = FACE_BOUND('',#110138,.T.); +#110138 = EDGE_LOOP('',(#110139,#110140,#110161,#110162)); +#110139 = ORIENTED_EDGE('',*,*,#109968,.F.); +#110140 = ORIENTED_EDGE('',*,*,#110141,.T.); +#110141 = EDGE_CURVE('',#109942,#92640,#110142,.T.); +#110142 = SURFACE_CURVE('',#110143,(#110147,#110154),.PCURVE_S1.); +#110143 = LINE('',#110144,#110145); +#110144 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.75)); +#110145 = VECTOR('',#110146,1.); +#110146 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#110147 = PCURVE('',#92655,#110148); +#110148 = DEFINITIONAL_REPRESENTATION('',(#110149),#110153); +#110149 = LINE('',#110150,#110151); +#110150 = CARTESIAN_POINT('',(0.E+000,0.2)); +#110151 = VECTOR('',#110152,1.); +#110152 = DIRECTION('',(1.,0.E+000)); +#110153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110154 = PCURVE('',#92683,#110155); +#110155 = DEFINITIONAL_REPRESENTATION('',(#110156),#110160); +#110156 = LINE('',#110157,#110158); +#110157 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#110158 = VECTOR('',#110159,1.); +#110159 = DIRECTION('',(3.563627120235E-016,1.)); +#110160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110161 = ORIENTED_EDGE('',*,*,#92639,.T.); +#110162 = ORIENTED_EDGE('',*,*,#110115,.F.); +#110163 = ADVANCED_FACE('',(#110164),#92683,.F.); +#110164 = FACE_BOUND('',#110165,.T.); +#110165 = EDGE_LOOP('',(#110166,#110167,#110168,#110169,#110170,#110171, + #110192,#110193,#110194,#110195,#110196,#110217)); +#110166 = ORIENTED_EDGE('',*,*,#110141,.F.); +#110167 = ORIENTED_EDGE('',*,*,#109941,.T.); +#110168 = ORIENTED_EDGE('',*,*,#109818,.T.); +#110169 = ORIENTED_EDGE('',*,*,#109743,.T.); +#110170 = ORIENTED_EDGE('',*,*,#109558,.T.); +#110171 = ORIENTED_EDGE('',*,*,#110172,.T.); +#110172 = EDGE_CURVE('',#109536,#109399,#110173,.T.); +#110173 = SURFACE_CURVE('',#110174,(#110178,#110185),.PCURVE_S1.); +#110174 = LINE('',#110175,#110176); +#110175 = CARTESIAN_POINT('',(8.85,-1.,1.159810404338E-002)); +#110176 = VECTOR('',#110177,1.); +#110177 = DIRECTION('',(0.E+000,2.101748079665E-016,-1.)); +#110178 = PCURVE('',#92683,#110179); +#110179 = DEFINITIONAL_REPRESENTATION('',(#110180),#110184); +#110180 = LINE('',#110181,#110182); +#110181 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#110182 = VECTOR('',#110183,1.); +#110183 = DIRECTION('',(-1.,2.101748079665E-016)); +#110184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110185 = PCURVE('',#109442,#110186); +#110186 = DEFINITIONAL_REPRESENTATION('',(#110187),#110191); +#110187 = LINE('',#110188,#110189); +#110188 = CARTESIAN_POINT('',(-0.269794846371,1.E-001)); +#110189 = VECTOR('',#110190,1.); +#110190 = DIRECTION('',(1.,0.E+000)); +#110191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110192 = ORIENTED_EDGE('',*,*,#109396,.F.); +#110193 = ORIENTED_EDGE('',*,*,#109664,.F.); +#110194 = ORIENTED_EDGE('',*,*,#109871,.F.); +#110195 = ORIENTED_EDGE('',*,*,#109991,.F.); +#110196 = ORIENTED_EDGE('',*,*,#110197,.T.); +#110197 = EDGE_CURVE('',#109992,#92668,#110198,.T.); +#110198 = SURFACE_CURVE('',#110199,(#110203,#110210),.PCURVE_S1.); +#110199 = LINE('',#110200,#110201); +#110200 = CARTESIAN_POINT('',(8.85,-0.527847992439,0.65)); +#110201 = VECTOR('',#110202,1.); +#110202 = DIRECTION('',(0.E+000,1.,3.563627120235E-016)); +#110203 = PCURVE('',#92683,#110204); +#110204 = DEFINITIONAL_REPRESENTATION('',(#110205),#110209); +#110205 = LINE('',#110206,#110207); +#110206 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110207 = VECTOR('',#110208,1.); +#110208 = DIRECTION('',(3.563627120235E-016,1.)); +#110209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110210 = PCURVE('',#92709,#110211); +#110211 = DEFINITIONAL_REPRESENTATION('',(#110212),#110216); +#110212 = LINE('',#110213,#110214); +#110213 = CARTESIAN_POINT('',(0.E+000,0.2)); +#110214 = VECTOR('',#110215,1.); +#110215 = DIRECTION('',(-1.,0.E+000)); +#110216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110217 = ORIENTED_EDGE('',*,*,#92667,.T.); +#110218 = ADVANCED_FACE('',(#110219),#92709,.F.); +#110219 = FACE_BOUND('',#110220,.T.); +#110220 = EDGE_LOOP('',(#110221,#110222,#110223,#110224)); +#110221 = ORIENTED_EDGE('',*,*,#110018,.F.); +#110222 = ORIENTED_EDGE('',*,*,#110065,.T.); +#110223 = ORIENTED_EDGE('',*,*,#92695,.T.); +#110224 = ORIENTED_EDGE('',*,*,#110197,.F.); +#110225 = ADVANCED_FACE('',(#110226),#109442,.T.); +#110226 = FACE_BOUND('',#110227,.T.); +#110227 = EDGE_LOOP('',(#110228,#110229,#110230,#110231)); +#110228 = ORIENTED_EDGE('',*,*,#110172,.F.); +#110229 = ORIENTED_EDGE('',*,*,#109535,.F.); +#110230 = ORIENTED_EDGE('',*,*,#110090,.F.); +#110231 = ORIENTED_EDGE('',*,*,#109426,.F.); +#110232 = ADVANCED_FACE('',(#110233),#110247,.F.); +#110233 = FACE_BOUND('',#110234,.T.); +#110234 = EDGE_LOOP('',(#110235,#110270,#110293,#110320)); +#110235 = ORIENTED_EDGE('',*,*,#110236,.F.); +#110236 = EDGE_CURVE('',#110237,#110239,#110241,.T.); +#110237 = VERTEX_POINT('',#110238); +#110238 = CARTESIAN_POINT('',(-1.,1.35,-0.308197125857)); +#110239 = VERTEX_POINT('',#110240); +#110240 = CARTESIAN_POINT('',(-1.,1.15,-0.308197125857)); +#110241 = SURFACE_CURVE('',#110242,(#110246,#110258),.PCURVE_S1.); +#110242 = LINE('',#110243,#110244); +#110243 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#110244 = VECTOR('',#110245,1.); +#110245 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110246 = PCURVE('',#110247,#110252); +#110247 = PLANE('',#110248); +#110248 = AXIS2_PLACEMENT_3D('',#110249,#110250,#110251); +#110249 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#110250 = DIRECTION('',(0.E+000,0.E+000,1.)); +#110251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#110252 = DEFINITIONAL_REPRESENTATION('',(#110253),#110257); +#110253 = LINE('',#110254,#110255); +#110254 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#110255 = VECTOR('',#110256,1.); +#110256 = DIRECTION('',(4.440892098501E-016,-1.)); +#110257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110258 = PCURVE('',#110259,#110264); +#110259 = PLANE('',#110260); +#110260 = AXIS2_PLACEMENT_3D('',#110261,#110262,#110263); +#110261 = CARTESIAN_POINT('',(-1.,1.25,-0.258196742327)); +#110262 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#110263 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110264 = DEFINITIONAL_REPRESENTATION('',(#110265),#110269); +#110265 = LINE('',#110266,#110267); +#110266 = CARTESIAN_POINT('',(-8.75,-5.000038352949E-002)); +#110267 = VECTOR('',#110268,1.); +#110268 = DIRECTION('',(1.,0.E+000)); +#110269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110270 = ORIENTED_EDGE('',*,*,#110271,.F.); +#110271 = EDGE_CURVE('',#110272,#110237,#110274,.T.); +#110272 = VERTEX_POINT('',#110273); +#110273 = CARTESIAN_POINT('',(-0.74341632541,1.35,-0.308197125857)); +#110274 = SURFACE_CURVE('',#110275,(#110279,#110286),.PCURVE_S1.); +#110275 = LINE('',#110276,#110277); +#110276 = CARTESIAN_POINT('',(-0.74341632541,1.35,-0.308197125857)); +#110277 = VECTOR('',#110278,1.); +#110278 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#110279 = PCURVE('',#110247,#110280); +#110280 = DEFINITIONAL_REPRESENTATION('',(#110281),#110285); +#110281 = LINE('',#110282,#110283); +#110282 = CARTESIAN_POINT('',(3.774758283726E-015,-8.65)); +#110283 = VECTOR('',#110284,1.); +#110284 = DIRECTION('',(-1.,0.E+000)); +#110285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110286 = PCURVE('',#94513,#110287); +#110287 = DEFINITIONAL_REPRESENTATION('',(#110288),#110292); +#110288 = LINE('',#110289,#110290); +#110289 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#110290 = VECTOR('',#110291,1.); +#110291 = DIRECTION('',(0.E+000,-1.)); +#110292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110293 = ORIENTED_EDGE('',*,*,#110294,.F.); +#110294 = EDGE_CURVE('',#110295,#110272,#110297,.T.); +#110295 = VERTEX_POINT('',#110296); +#110296 = CARTESIAN_POINT('',(-0.74341632541,1.15,-0.308197125857)); +#110297 = SURFACE_CURVE('',#110298,(#110302,#110309),.PCURVE_S1.); +#110298 = LINE('',#110299,#110300); +#110299 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#110300 = VECTOR('',#110301,1.); +#110301 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110302 = PCURVE('',#110247,#110303); +#110303 = DEFINITIONAL_REPRESENTATION('',(#110304),#110308); +#110304 = LINE('',#110305,#110306); +#110305 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110306 = VECTOR('',#110307,1.); +#110307 = DIRECTION('',(-4.440892098501E-016,1.)); +#110308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110309 = PCURVE('',#110310,#110315); +#110310 = CYLINDRICAL_SURFACE('',#110311,0.308574064194); +#110311 = AXIS2_PLACEMENT_3D('',#110312,#110313,#110314); +#110312 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#110313 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110314 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110315 = DEFINITIONAL_REPRESENTATION('',(#110316),#110319); +#110316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110317,#110318), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#107925 = CARTESIAN_POINT('',(4.761821717947,-8.85)); -#107926 = CARTESIAN_POINT('',(4.761821717947,-8.65)); -#107927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107928 = ORIENTED_EDGE('',*,*,#107929,.T.); -#107929 = EDGE_CURVE('',#107903,#107847,#107930,.T.); -#107930 = SURFACE_CURVE('',#107931,(#107935,#107942),.PCURVE_S1.); -#107931 = LINE('',#107932,#107933); -#107932 = CARTESIAN_POINT('',(-0.74341632541,1.15,-0.308197125857)); -#107933 = VECTOR('',#107934,1.); -#107934 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107935 = PCURVE('',#107855,#107936); -#107936 = DEFINITIONAL_REPRESENTATION('',(#107937),#107941); -#107937 = LINE('',#107938,#107939); -#107938 = CARTESIAN_POINT('',(3.996802888651E-015,-8.85)); -#107939 = VECTOR('',#107940,1.); -#107940 = DIRECTION('',(-1.,0.E+000)); -#107941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107942 = PCURVE('',#92065,#107943); -#107943 = DEFINITIONAL_REPRESENTATION('',(#107944),#107948); -#107944 = LINE('',#107945,#107946); -#107945 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#107946 = VECTOR('',#107947,1.); -#107947 = DIRECTION('',(0.E+000,-1.)); -#107948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107949 = ADVANCED_FACE('',(#107950),#107964,.F.); -#107950 = FACE_BOUND('',#107951,.T.); -#107951 = EDGE_LOOP('',(#107952,#107982,#108005,#108032)); -#107952 = ORIENTED_EDGE('',*,*,#107953,.F.); -#107953 = EDGE_CURVE('',#107954,#107956,#107958,.T.); -#107954 = VERTEX_POINT('',#107955); -#107955 = CARTESIAN_POINT('',(-1.,1.15,-0.208196358798)); -#107956 = VERTEX_POINT('',#107957); -#107957 = CARTESIAN_POINT('',(-1.,1.35,-0.208196358798)); -#107958 = SURFACE_CURVE('',#107959,(#107963,#107975),.PCURVE_S1.); -#107959 = LINE('',#107960,#107961); -#107960 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#107961 = VECTOR('',#107962,1.); -#107962 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#107963 = PCURVE('',#107964,#107969); -#107964 = PLANE('',#107965); -#107965 = AXIS2_PLACEMENT_3D('',#107966,#107967,#107968); -#107966 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#107967 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#107968 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107969 = DEFINITIONAL_REPRESENTATION('',(#107970),#107974); -#107970 = LINE('',#107971,#107972); -#107971 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#107972 = VECTOR('',#107973,1.); -#107973 = DIRECTION('',(4.440892098501E-016,1.)); -#107974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107975 = PCURVE('',#107867,#107976); -#107976 = DEFINITIONAL_REPRESENTATION('',(#107977),#107981); -#107977 = LINE('',#107978,#107979); -#107978 = CARTESIAN_POINT('',(-8.75,5.000038352949E-002)); -#107979 = VECTOR('',#107980,1.); -#107980 = DIRECTION('',(-1.,0.E+000)); -#107981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107982 = ORIENTED_EDGE('',*,*,#107983,.F.); -#107983 = EDGE_CURVE('',#107984,#107954,#107986,.T.); -#107984 = VERTEX_POINT('',#107985); -#107985 = CARTESIAN_POINT('',(-0.740726081328,1.15,-0.208196358798)); -#107986 = SURFACE_CURVE('',#107987,(#107991,#107998),.PCURVE_S1.); -#107987 = LINE('',#107988,#107989); -#107988 = CARTESIAN_POINT('',(-0.740726081328,1.15,-0.208196358798)); -#107989 = VECTOR('',#107990,1.); -#107990 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#107991 = PCURVE('',#107964,#107992); -#107992 = DEFINITIONAL_REPRESENTATION('',(#107993),#107997); -#107993 = LINE('',#107994,#107995); -#107994 = CARTESIAN_POINT('',(-3.996802888651E-015,-8.85)); -#107995 = VECTOR('',#107996,1.); -#107996 = DIRECTION('',(1.,0.E+000)); -#107997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#107998 = PCURVE('',#92065,#107999); -#107999 = DEFINITIONAL_REPRESENTATION('',(#108000),#108004); -#108000 = LINE('',#108001,#108002); -#108001 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#108002 = VECTOR('',#108003,1.); -#108003 = DIRECTION('',(0.E+000,-1.)); -#108004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108005 = ORIENTED_EDGE('',*,*,#108006,.F.); -#108006 = EDGE_CURVE('',#108007,#107984,#108009,.T.); -#108007 = VERTEX_POINT('',#108008); -#108008 = CARTESIAN_POINT('',(-0.740726081328,1.35,-0.208196358798)); -#108009 = SURFACE_CURVE('',#108010,(#108014,#108021),.PCURVE_S1.); -#108010 = LINE('',#108011,#108012); -#108011 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#108012 = VECTOR('',#108013,1.); -#108013 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108014 = PCURVE('',#107964,#108015); -#108015 = DEFINITIONAL_REPRESENTATION('',(#108016),#108020); -#108016 = LINE('',#108017,#108018); -#108017 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108018 = VECTOR('',#108019,1.); -#108019 = DIRECTION('',(-4.440892098501E-016,-1.)); -#108020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108021 = PCURVE('',#108022,#108027); -#108022 = CYLINDRICAL_SURFACE('',#108023,0.208574704164); -#108023 = AXIS2_PLACEMENT_3D('',#108024,#108025,#108026); -#108024 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#108025 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108026 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108027 = DEFINITIONAL_REPRESENTATION('',(#108028),#108031); -#108028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108029,#108030), +#110317 = CARTESIAN_POINT('',(4.761821717947,-8.85)); +#110318 = CARTESIAN_POINT('',(4.761821717947,-8.65)); +#110319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110320 = ORIENTED_EDGE('',*,*,#110321,.T.); +#110321 = EDGE_CURVE('',#110295,#110239,#110322,.T.); +#110322 = SURFACE_CURVE('',#110323,(#110327,#110334),.PCURVE_S1.); +#110323 = LINE('',#110324,#110325); +#110324 = CARTESIAN_POINT('',(-0.74341632541,1.15,-0.308197125857)); +#110325 = VECTOR('',#110326,1.); +#110326 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#110327 = PCURVE('',#110247,#110328); +#110328 = DEFINITIONAL_REPRESENTATION('',(#110329),#110333); +#110329 = LINE('',#110330,#110331); +#110330 = CARTESIAN_POINT('',(3.996802888651E-015,-8.85)); +#110331 = VECTOR('',#110332,1.); +#110332 = DIRECTION('',(-1.,0.E+000)); +#110333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110334 = PCURVE('',#94457,#110335); +#110335 = DEFINITIONAL_REPRESENTATION('',(#110336),#110340); +#110336 = LINE('',#110337,#110338); +#110337 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#110338 = VECTOR('',#110339,1.); +#110339 = DIRECTION('',(0.E+000,-1.)); +#110340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110341 = ADVANCED_FACE('',(#110342),#110356,.F.); +#110342 = FACE_BOUND('',#110343,.T.); +#110343 = EDGE_LOOP('',(#110344,#110374,#110397,#110424)); +#110344 = ORIENTED_EDGE('',*,*,#110345,.F.); +#110345 = EDGE_CURVE('',#110346,#110348,#110350,.T.); +#110346 = VERTEX_POINT('',#110347); +#110347 = CARTESIAN_POINT('',(-1.,1.15,-0.208196358798)); +#110348 = VERTEX_POINT('',#110349); +#110349 = CARTESIAN_POINT('',(-1.,1.35,-0.208196358798)); +#110350 = SURFACE_CURVE('',#110351,(#110355,#110367),.PCURVE_S1.); +#110351 = LINE('',#110352,#110353); +#110352 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#110353 = VECTOR('',#110354,1.); +#110354 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110355 = PCURVE('',#110356,#110361); +#110356 = PLANE('',#110357); +#110357 = AXIS2_PLACEMENT_3D('',#110358,#110359,#110360); +#110358 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#110359 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#110360 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#110361 = DEFINITIONAL_REPRESENTATION('',(#110362),#110366); +#110362 = LINE('',#110363,#110364); +#110363 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#110364 = VECTOR('',#110365,1.); +#110365 = DIRECTION('',(4.440892098501E-016,1.)); +#110366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110367 = PCURVE('',#110259,#110368); +#110368 = DEFINITIONAL_REPRESENTATION('',(#110369),#110373); +#110369 = LINE('',#110370,#110371); +#110370 = CARTESIAN_POINT('',(-8.75,5.000038352949E-002)); +#110371 = VECTOR('',#110372,1.); +#110372 = DIRECTION('',(-1.,0.E+000)); +#110373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110374 = ORIENTED_EDGE('',*,*,#110375,.F.); +#110375 = EDGE_CURVE('',#110376,#110346,#110378,.T.); +#110376 = VERTEX_POINT('',#110377); +#110377 = CARTESIAN_POINT('',(-0.740726081328,1.15,-0.208196358798)); +#110378 = SURFACE_CURVE('',#110379,(#110383,#110390),.PCURVE_S1.); +#110379 = LINE('',#110380,#110381); +#110380 = CARTESIAN_POINT('',(-0.740726081328,1.15,-0.208196358798)); +#110381 = VECTOR('',#110382,1.); +#110382 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#110383 = PCURVE('',#110356,#110384); +#110384 = DEFINITIONAL_REPRESENTATION('',(#110385),#110389); +#110385 = LINE('',#110386,#110387); +#110386 = CARTESIAN_POINT('',(-3.996802888651E-015,-8.85)); +#110387 = VECTOR('',#110388,1.); +#110388 = DIRECTION('',(1.,0.E+000)); +#110389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110390 = PCURVE('',#94457,#110391); +#110391 = DEFINITIONAL_REPRESENTATION('',(#110392),#110396); +#110392 = LINE('',#110393,#110394); +#110393 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#110394 = VECTOR('',#110395,1.); +#110395 = DIRECTION('',(0.E+000,-1.)); +#110396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110397 = ORIENTED_EDGE('',*,*,#110398,.F.); +#110398 = EDGE_CURVE('',#110399,#110376,#110401,.T.); +#110399 = VERTEX_POINT('',#110400); +#110400 = CARTESIAN_POINT('',(-0.740726081328,1.35,-0.208196358798)); +#110401 = SURFACE_CURVE('',#110402,(#110406,#110413),.PCURVE_S1.); +#110402 = LINE('',#110403,#110404); +#110403 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#110404 = VECTOR('',#110405,1.); +#110405 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110406 = PCURVE('',#110356,#110407); +#110407 = DEFINITIONAL_REPRESENTATION('',(#110408),#110412); +#110408 = LINE('',#110409,#110410); +#110409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110410 = VECTOR('',#110411,1.); +#110411 = DIRECTION('',(-4.440892098501E-016,-1.)); +#110412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110413 = PCURVE('',#110414,#110419); +#110414 = CYLINDRICAL_SURFACE('',#110415,0.208574704164); +#110415 = AXIS2_PLACEMENT_3D('',#110416,#110417,#110418); +#110416 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#110417 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110418 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110419 = DEFINITIONAL_REPRESENTATION('',(#110420),#110423); +#110420 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110421,#110422), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#108029 = CARTESIAN_POINT('',(4.772630242227,-8.65)); -#108030 = CARTESIAN_POINT('',(4.772630242227,-8.85)); -#108031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108032 = ORIENTED_EDGE('',*,*,#108033,.T.); -#108033 = EDGE_CURVE('',#108007,#107956,#108034,.T.); -#108034 = SURFACE_CURVE('',#108035,(#108039,#108046),.PCURVE_S1.); -#108035 = LINE('',#108036,#108037); -#108036 = CARTESIAN_POINT('',(-0.740726081328,1.35,-0.208196358798)); -#108037 = VECTOR('',#108038,1.); -#108038 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108039 = PCURVE('',#107964,#108040); -#108040 = DEFINITIONAL_REPRESENTATION('',(#108041),#108045); -#108041 = LINE('',#108042,#108043); -#108042 = CARTESIAN_POINT('',(-3.774758283726E-015,-8.65)); -#108043 = VECTOR('',#108044,1.); -#108044 = DIRECTION('',(1.,0.E+000)); -#108045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108046 = PCURVE('',#92121,#108047); -#108047 = DEFINITIONAL_REPRESENTATION('',(#108048),#108052); -#108048 = LINE('',#108049,#108050); -#108049 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#108050 = VECTOR('',#108051,1.); -#108051 = DIRECTION('',(0.E+000,-1.)); -#108052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108053 = ADVANCED_FACE('',(#108054),#107918,.T.); -#108054 = FACE_BOUND('',#108055,.T.); -#108055 = EDGE_LOOP('',(#108056,#108083,#108084,#108107)); -#108056 = ORIENTED_EDGE('',*,*,#108057,.T.); -#108057 = EDGE_CURVE('',#108058,#107903,#108060,.T.); -#108058 = VERTEX_POINT('',#108059); -#108059 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.E+000)); -#108060 = SURFACE_CURVE('',#108061,(#108066,#108072),.PCURVE_S1.); -#108061 = CIRCLE('',#108062,0.308574064194); -#108062 = AXIS2_PLACEMENT_3D('',#108063,#108064,#108065); -#108063 = CARTESIAN_POINT('',(-0.728168876214,1.15,2.640924866458E-017) - ); -#108064 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108065 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108066 = PCURVE('',#107918,#108067); -#108067 = DEFINITIONAL_REPRESENTATION('',(#108068),#108071); -#108068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108069,#108070), +#110421 = CARTESIAN_POINT('',(4.772630242227,-8.65)); +#110422 = CARTESIAN_POINT('',(4.772630242227,-8.85)); +#110423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110424 = ORIENTED_EDGE('',*,*,#110425,.T.); +#110425 = EDGE_CURVE('',#110399,#110348,#110426,.T.); +#110426 = SURFACE_CURVE('',#110427,(#110431,#110438),.PCURVE_S1.); +#110427 = LINE('',#110428,#110429); +#110428 = CARTESIAN_POINT('',(-0.740726081328,1.35,-0.208196358798)); +#110429 = VECTOR('',#110430,1.); +#110430 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#110431 = PCURVE('',#110356,#110432); +#110432 = DEFINITIONAL_REPRESENTATION('',(#110433),#110437); +#110433 = LINE('',#110434,#110435); +#110434 = CARTESIAN_POINT('',(-3.774758283726E-015,-8.65)); +#110435 = VECTOR('',#110436,1.); +#110436 = DIRECTION('',(1.,0.E+000)); +#110437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110438 = PCURVE('',#94513,#110439); +#110439 = DEFINITIONAL_REPRESENTATION('',(#110440),#110444); +#110440 = LINE('',#110441,#110442); +#110441 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#110442 = VECTOR('',#110443,1.); +#110443 = DIRECTION('',(0.E+000,-1.)); +#110444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110445 = ADVANCED_FACE('',(#110446),#110310,.T.); +#110446 = FACE_BOUND('',#110447,.T.); +#110447 = EDGE_LOOP('',(#110448,#110475,#110476,#110499)); +#110448 = ORIENTED_EDGE('',*,*,#110449,.T.); +#110449 = EDGE_CURVE('',#110450,#110295,#110452,.T.); +#110450 = VERTEX_POINT('',#110451); +#110451 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.E+000)); +#110452 = SURFACE_CURVE('',#110453,(#110458,#110464),.PCURVE_S1.); +#110453 = CIRCLE('',#110454,0.308574064194); +#110454 = AXIS2_PLACEMENT_3D('',#110455,#110456,#110457); +#110455 = CARTESIAN_POINT('',(-0.728168876214,1.15,2.640924866458E-017) + ); +#110456 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110457 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110458 = PCURVE('',#110310,#110459); +#110459 = DEFINITIONAL_REPRESENTATION('',(#110460),#110463); +#110460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110461,#110462), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#108069 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#108070 = CARTESIAN_POINT('',(4.761821717947,-8.85)); -#108071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110461 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#110462 = CARTESIAN_POINT('',(4.761821717947,-8.85)); +#110463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108072 = PCURVE('',#92065,#108073); -#108073 = DEFINITIONAL_REPRESENTATION('',(#108074),#108082); -#108074 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108075,#108076,#108077, - #108078,#108079,#108080,#108081),.UNSPECIFIED.,.T.,.F.) +#110464 = PCURVE('',#94457,#110465); +#110465 = DEFINITIONAL_REPRESENTATION('',(#110466),#110474); +#110466 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110467,#110468,#110469, + #110470,#110471,#110472,#110473),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#108075 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#108076 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#108077 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#108078 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#108079 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#108080 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#108081 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#108082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108083 = ORIENTED_EDGE('',*,*,#107902,.T.); -#108084 = ORIENTED_EDGE('',*,*,#108085,.F.); -#108085 = EDGE_CURVE('',#108086,#107880,#108088,.T.); -#108086 = VERTEX_POINT('',#108087); -#108087 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.E+000)); -#108088 = SURFACE_CURVE('',#108089,(#108094,#108100),.PCURVE_S1.); -#108089 = CIRCLE('',#108090,0.308574064194); -#108090 = AXIS2_PLACEMENT_3D('',#108091,#108092,#108093); -#108091 = CARTESIAN_POINT('',(-0.728168876214,1.35,2.640924866458E-017) - ); -#108092 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108093 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108094 = PCURVE('',#107918,#108095); -#108095 = DEFINITIONAL_REPRESENTATION('',(#108096),#108099); -#108096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108097,#108098), +#110467 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#110468 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#110469 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#110470 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#110471 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#110472 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#110473 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#110474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110475 = ORIENTED_EDGE('',*,*,#110294,.T.); +#110476 = ORIENTED_EDGE('',*,*,#110477,.F.); +#110477 = EDGE_CURVE('',#110478,#110272,#110480,.T.); +#110478 = VERTEX_POINT('',#110479); +#110479 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.E+000)); +#110480 = SURFACE_CURVE('',#110481,(#110486,#110492),.PCURVE_S1.); +#110481 = CIRCLE('',#110482,0.308574064194); +#110482 = AXIS2_PLACEMENT_3D('',#110483,#110484,#110485); +#110483 = CARTESIAN_POINT('',(-0.728168876214,1.35,2.640924866458E-017) + ); +#110484 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110485 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110486 = PCURVE('',#110310,#110487); +#110487 = DEFINITIONAL_REPRESENTATION('',(#110488),#110491); +#110488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110489,#110490), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#108097 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#108098 = CARTESIAN_POINT('',(4.761821717947,-8.65)); -#108099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108100 = PCURVE('',#92121,#108101); -#108101 = DEFINITIONAL_REPRESENTATION('',(#108102),#108106); -#108102 = CIRCLE('',#108103,0.308574064194); -#108103 = AXIS2_PLACEMENT_2D('',#108104,#108105); -#108104 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#108105 = DIRECTION('',(0.E+000,-1.)); -#108106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108107 = ORIENTED_EDGE('',*,*,#108108,.T.); -#108108 = EDGE_CURVE('',#108086,#108058,#108109,.T.); -#108109 = SURFACE_CURVE('',#108110,(#108114,#108120),.PCURVE_S1.); -#108110 = LINE('',#108111,#108112); -#108111 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#108112 = VECTOR('',#108113,1.); -#108113 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108114 = PCURVE('',#107918,#108115); -#108115 = DEFINITIONAL_REPRESENTATION('',(#108116),#108119); -#108116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108117,#108118), +#110489 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#110490 = CARTESIAN_POINT('',(4.761821717947,-8.65)); +#110491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110492 = PCURVE('',#94513,#110493); +#110493 = DEFINITIONAL_REPRESENTATION('',(#110494),#110498); +#110494 = CIRCLE('',#110495,0.308574064194); +#110495 = AXIS2_PLACEMENT_2D('',#110496,#110497); +#110496 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#110497 = DIRECTION('',(0.E+000,-1.)); +#110498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110499 = ORIENTED_EDGE('',*,*,#110500,.T.); +#110500 = EDGE_CURVE('',#110478,#110450,#110501,.T.); +#110501 = SURFACE_CURVE('',#110502,(#110506,#110512),.PCURVE_S1.); +#110502 = LINE('',#110503,#110504); +#110503 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#110504 = VECTOR('',#110505,1.); +#110505 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110506 = PCURVE('',#110310,#110507); +#110507 = DEFINITIONAL_REPRESENTATION('',(#110508),#110511); +#110508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110509,#110510), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#108117 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#108118 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#108119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108120 = PCURVE('',#108121,#108126); -#108121 = PLANE('',#108122); -#108122 = AXIS2_PLACEMENT_3D('',#108123,#108124,#108125); -#108123 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#108124 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#108125 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108126 = DEFINITIONAL_REPRESENTATION('',(#108127),#108131); -#108127 = LINE('',#108128,#108129); -#108128 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#108129 = VECTOR('',#108130,1.); -#108130 = DIRECTION('',(-1.,0.E+000)); -#108131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108132 = ADVANCED_FACE('',(#108133),#108022,.F.); -#108133 = FACE_BOUND('',#108134,.F.); -#108134 = EDGE_LOOP('',(#108135,#108158,#108185,#108210)); -#108135 = ORIENTED_EDGE('',*,*,#108136,.F.); -#108136 = EDGE_CURVE('',#108137,#108007,#108139,.T.); -#108137 = VERTEX_POINT('',#108138); -#108138 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.E+000)); -#108139 = SURFACE_CURVE('',#108140,(#108145,#108151),.PCURVE_S1.); -#108140 = CIRCLE('',#108141,0.208574704164); -#108141 = AXIS2_PLACEMENT_3D('',#108142,#108143,#108144); -#108142 = CARTESIAN_POINT('',(-0.728168876214,1.35,2.640924866458E-017) - ); -#108143 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108144 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108145 = PCURVE('',#108022,#108146); -#108146 = DEFINITIONAL_REPRESENTATION('',(#108147),#108150); -#108147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108148,#108149), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), - .PIECEWISE_BEZIER_KNOTS.); -#108148 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#108149 = CARTESIAN_POINT('',(4.772630242227,-8.65)); -#108150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110509 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#110510 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#110511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108151 = PCURVE('',#92121,#108152); -#108152 = DEFINITIONAL_REPRESENTATION('',(#108153),#108157); -#108153 = CIRCLE('',#108154,0.208574704164); -#108154 = AXIS2_PLACEMENT_2D('',#108155,#108156); -#108155 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#108156 = DIRECTION('',(0.E+000,-1.)); -#108157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110512 = PCURVE('',#110513,#110518); +#110513 = PLANE('',#110514); +#110514 = AXIS2_PLACEMENT_3D('',#110515,#110516,#110517); +#110515 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#110516 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#110517 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110518 = DEFINITIONAL_REPRESENTATION('',(#110519),#110523); +#110519 = LINE('',#110520,#110521); +#110520 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#110521 = VECTOR('',#110522,1.); +#110522 = DIRECTION('',(-1.,0.E+000)); +#110523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108158 = ORIENTED_EDGE('',*,*,#108159,.F.); -#108159 = EDGE_CURVE('',#108160,#108137,#108162,.T.); -#108160 = VERTEX_POINT('',#108161); -#108161 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.E+000)); -#108162 = SURFACE_CURVE('',#108163,(#108167,#108173),.PCURVE_S1.); -#108163 = LINE('',#108164,#108165); -#108164 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#108165 = VECTOR('',#108166,1.); -#108166 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108167 = PCURVE('',#108022,#108168); -#108168 = DEFINITIONAL_REPRESENTATION('',(#108169),#108172); -#108169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108170,#108171), +#110524 = ADVANCED_FACE('',(#110525),#110414,.F.); +#110525 = FACE_BOUND('',#110526,.F.); +#110526 = EDGE_LOOP('',(#110527,#110550,#110577,#110602)); +#110527 = ORIENTED_EDGE('',*,*,#110528,.F.); +#110528 = EDGE_CURVE('',#110529,#110399,#110531,.T.); +#110529 = VERTEX_POINT('',#110530); +#110530 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.E+000)); +#110531 = SURFACE_CURVE('',#110532,(#110537,#110543),.PCURVE_S1.); +#110532 = CIRCLE('',#110533,0.208574704164); +#110533 = AXIS2_PLACEMENT_3D('',#110534,#110535,#110536); +#110534 = CARTESIAN_POINT('',(-0.728168876214,1.35,2.640924866458E-017) + ); +#110535 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110536 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110537 = PCURVE('',#110414,#110538); +#110538 = DEFINITIONAL_REPRESENTATION('',(#110539),#110542); +#110539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110540,#110541), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), + .PIECEWISE_BEZIER_KNOTS.); +#110540 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#110541 = CARTESIAN_POINT('',(4.772630242227,-8.65)); +#110542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110543 = PCURVE('',#94513,#110544); +#110544 = DEFINITIONAL_REPRESENTATION('',(#110545),#110549); +#110545 = CIRCLE('',#110546,0.208574704164); +#110546 = AXIS2_PLACEMENT_2D('',#110547,#110548); +#110547 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#110548 = DIRECTION('',(0.E+000,-1.)); +#110549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110550 = ORIENTED_EDGE('',*,*,#110551,.F.); +#110551 = EDGE_CURVE('',#110552,#110529,#110554,.T.); +#110552 = VERTEX_POINT('',#110553); +#110553 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.E+000)); +#110554 = SURFACE_CURVE('',#110555,(#110559,#110565),.PCURVE_S1.); +#110555 = LINE('',#110556,#110557); +#110556 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#110557 = VECTOR('',#110558,1.); +#110558 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110559 = PCURVE('',#110414,#110560); +#110560 = DEFINITIONAL_REPRESENTATION('',(#110561),#110564); +#110561 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110562,#110563), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#108170 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#108171 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#108172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108173 = PCURVE('',#108174,#108179); -#108174 = PLANE('',#108175); -#108175 = AXIS2_PLACEMENT_3D('',#108176,#108177,#108178); -#108176 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#108177 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#108178 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108179 = DEFINITIONAL_REPRESENTATION('',(#108180),#108184); -#108180 = LINE('',#108181,#108182); -#108181 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#108182 = VECTOR('',#108183,1.); -#108183 = DIRECTION('',(-1.,0.E+000)); -#108184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108185 = ORIENTED_EDGE('',*,*,#108186,.T.); -#108186 = EDGE_CURVE('',#108160,#107984,#108187,.T.); -#108187 = SURFACE_CURVE('',#108188,(#108193,#108199),.PCURVE_S1.); -#108188 = CIRCLE('',#108189,0.208574704164); -#108189 = AXIS2_PLACEMENT_3D('',#108190,#108191,#108192); -#108190 = CARTESIAN_POINT('',(-0.728168876214,1.15,2.640924866458E-017) - ); -#108191 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108192 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108193 = PCURVE('',#108022,#108194); -#108194 = DEFINITIONAL_REPRESENTATION('',(#108195),#108198); -#108195 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108196,#108197), +#110562 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#110563 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#110564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110565 = PCURVE('',#110566,#110571); +#110566 = PLANE('',#110567); +#110567 = AXIS2_PLACEMENT_3D('',#110568,#110569,#110570); +#110568 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#110569 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#110570 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110571 = DEFINITIONAL_REPRESENTATION('',(#110572),#110576); +#110572 = LINE('',#110573,#110574); +#110573 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#110574 = VECTOR('',#110575,1.); +#110575 = DIRECTION('',(-1.,0.E+000)); +#110576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110577 = ORIENTED_EDGE('',*,*,#110578,.T.); +#110578 = EDGE_CURVE('',#110552,#110376,#110579,.T.); +#110579 = SURFACE_CURVE('',#110580,(#110585,#110591),.PCURVE_S1.); +#110580 = CIRCLE('',#110581,0.208574704164); +#110581 = AXIS2_PLACEMENT_3D('',#110582,#110583,#110584); +#110582 = CARTESIAN_POINT('',(-0.728168876214,1.15,2.640924866458E-017) + ); +#110583 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110584 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#110585 = PCURVE('',#110414,#110586); +#110586 = DEFINITIONAL_REPRESENTATION('',(#110587),#110590); +#110587 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110588,#110589), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#108196 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#108197 = CARTESIAN_POINT('',(4.772630242227,-8.85)); -#108198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110588 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#110589 = CARTESIAN_POINT('',(4.772630242227,-8.85)); +#110590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108199 = PCURVE('',#92065,#108200); -#108200 = DEFINITIONAL_REPRESENTATION('',(#108201),#108209); -#108201 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108202,#108203,#108204, - #108205,#108206,#108207,#108208),.UNSPECIFIED.,.T.,.F.) +#110591 = PCURVE('',#94457,#110592); +#110592 = DEFINITIONAL_REPRESENTATION('',(#110593),#110601); +#110593 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110594,#110595,#110596, + #110597,#110598,#110599,#110600),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#108202 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#108203 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#108204 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#108205 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#108206 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#108207 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#108208 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#108209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108210 = ORIENTED_EDGE('',*,*,#108006,.F.); -#108211 = ADVANCED_FACE('',(#108212),#108174,.T.); -#108212 = FACE_BOUND('',#108213,.T.); -#108213 = EDGE_LOOP('',(#108214,#108243,#108264,#108265)); -#108214 = ORIENTED_EDGE('',*,*,#108215,.T.); -#108215 = EDGE_CURVE('',#108216,#108218,#108220,.T.); -#108216 = VERTEX_POINT('',#108217); -#108217 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.530776333563)); -#108218 = VERTEX_POINT('',#108219); -#108219 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.530776333563)); -#108220 = SURFACE_CURVE('',#108221,(#108225,#108232),.PCURVE_S1.); -#108221 = LINE('',#108222,#108223); -#108222 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#108223 = VECTOR('',#108224,1.); -#108224 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108225 = PCURVE('',#108174,#108226); -#108226 = DEFINITIONAL_REPRESENTATION('',(#108227),#108231); -#108227 = LINE('',#108228,#108229); -#108228 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108229 = VECTOR('',#108230,1.); -#108230 = DIRECTION('',(-1.,0.E+000)); -#108231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108232 = PCURVE('',#108233,#108238); -#108233 = CYLINDRICAL_SURFACE('',#108234,0.2192697516); -#108234 = AXIS2_PLACEMENT_3D('',#108235,#108236,#108237); -#108235 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#108236 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108237 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108238 = DEFINITIONAL_REPRESENTATION('',(#108239),#108242); -#108239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108240,#108241), +#110594 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#110595 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#110596 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#110597 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#110598 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#110599 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#110600 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#110601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110602 = ORIENTED_EDGE('',*,*,#110398,.F.); +#110603 = ADVANCED_FACE('',(#110604),#110566,.T.); +#110604 = FACE_BOUND('',#110605,.T.); +#110605 = EDGE_LOOP('',(#110606,#110635,#110656,#110657)); +#110606 = ORIENTED_EDGE('',*,*,#110607,.T.); +#110607 = EDGE_CURVE('',#110608,#110610,#110612,.T.); +#110608 = VERTEX_POINT('',#110609); +#110609 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.530776333563)); +#110610 = VERTEX_POINT('',#110611); +#110611 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.530776333563)); +#110612 = SURFACE_CURVE('',#110613,(#110617,#110624),.PCURVE_S1.); +#110613 = LINE('',#110614,#110615); +#110614 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#110615 = VECTOR('',#110616,1.); +#110616 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110617 = PCURVE('',#110566,#110618); +#110618 = DEFINITIONAL_REPRESENTATION('',(#110619),#110623); +#110619 = LINE('',#110620,#110621); +#110620 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110621 = VECTOR('',#110622,1.); +#110622 = DIRECTION('',(-1.,0.E+000)); +#110623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110624 = PCURVE('',#110625,#110630); +#110625 = CYLINDRICAL_SURFACE('',#110626,0.2192697516); +#110626 = AXIS2_PLACEMENT_3D('',#110627,#110628,#110629); +#110627 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#110628 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110629 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110630 = DEFINITIONAL_REPRESENTATION('',(#110631),#110634); +#110631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110632,#110633), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#108240 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#108241 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#108242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108243 = ORIENTED_EDGE('',*,*,#108244,.T.); -#108244 = EDGE_CURVE('',#108218,#108137,#108245,.T.); -#108245 = SURFACE_CURVE('',#108246,(#108250,#108257),.PCURVE_S1.); -#108246 = LINE('',#108247,#108248); -#108247 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.530776333563)); -#108248 = VECTOR('',#108249,1.); -#108249 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#108250 = PCURVE('',#108174,#108251); -#108251 = DEFINITIONAL_REPRESENTATION('',(#108252),#108256); -#108252 = LINE('',#108253,#108254); -#108253 = CARTESIAN_POINT('',(8.65,4.535643882845E-033)); -#108254 = VECTOR('',#108255,1.); -#108255 = DIRECTION('',(-4.535643882845E-032,-1.)); -#108256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108257 = PCURVE('',#92121,#108258); -#108258 = DEFINITIONAL_REPRESENTATION('',(#108259),#108263); -#108259 = LINE('',#108260,#108261); -#108260 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#108261 = VECTOR('',#108262,1.); -#108262 = DIRECTION('',(-1.,-1.021336205033E-016)); -#108263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108264 = ORIENTED_EDGE('',*,*,#108159,.F.); -#108265 = ORIENTED_EDGE('',*,*,#108266,.F.); -#108266 = EDGE_CURVE('',#108216,#108160,#108267,.T.); -#108267 = SURFACE_CURVE('',#108268,(#108272,#108279),.PCURVE_S1.); -#108268 = LINE('',#108269,#108270); -#108269 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.530776333563)); -#108270 = VECTOR('',#108271,1.); -#108271 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#108272 = PCURVE('',#108174,#108273); -#108273 = DEFINITIONAL_REPRESENTATION('',(#108274),#108278); -#108274 = LINE('',#108275,#108276); -#108275 = CARTESIAN_POINT('',(8.85,-4.535643882845E-033)); -#108276 = VECTOR('',#108277,1.); -#108277 = DIRECTION('',(-4.535643882845E-032,-1.)); -#108278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108279 = PCURVE('',#92065,#108280); -#108280 = DEFINITIONAL_REPRESENTATION('',(#108281),#108285); -#108281 = LINE('',#108282,#108283); -#108282 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#108283 = VECTOR('',#108284,1.); -#108284 = DIRECTION('',(1.,-1.021336205033E-016)); -#108285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108286 = ADVANCED_FACE('',(#108287),#108121,.T.); -#108287 = FACE_BOUND('',#108288,.T.); -#108288 = EDGE_LOOP('',(#108289,#108318,#108339,#108340)); -#108289 = ORIENTED_EDGE('',*,*,#108290,.T.); -#108290 = EDGE_CURVE('',#108291,#108293,#108295,.T.); -#108291 = VERTEX_POINT('',#108292); -#108292 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.530776333563)); -#108293 = VERTEX_POINT('',#108294); -#108294 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.530776333563)); -#108295 = SURFACE_CURVE('',#108296,(#108300,#108307),.PCURVE_S1.); -#108296 = LINE('',#108297,#108298); -#108297 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#108298 = VECTOR('',#108299,1.); -#108299 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108300 = PCURVE('',#108121,#108301); -#108301 = DEFINITIONAL_REPRESENTATION('',(#108302),#108306); -#108302 = LINE('',#108303,#108304); -#108303 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108304 = VECTOR('',#108305,1.); -#108305 = DIRECTION('',(-1.,0.E+000)); -#108306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110632 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#110633 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#110634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110635 = ORIENTED_EDGE('',*,*,#110636,.T.); +#110636 = EDGE_CURVE('',#110610,#110529,#110637,.T.); +#110637 = SURFACE_CURVE('',#110638,(#110642,#110649),.PCURVE_S1.); +#110638 = LINE('',#110639,#110640); +#110639 = CARTESIAN_POINT('',(-0.51959417205,1.35,0.530776333563)); +#110640 = VECTOR('',#110641,1.); +#110641 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#110642 = PCURVE('',#110566,#110643); +#110643 = DEFINITIONAL_REPRESENTATION('',(#110644),#110648); +#110644 = LINE('',#110645,#110646); +#110645 = CARTESIAN_POINT('',(8.65,4.535643882845E-033)); +#110646 = VECTOR('',#110647,1.); +#110647 = DIRECTION('',(-4.535643882845E-032,-1.)); +#110648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110649 = PCURVE('',#94513,#110650); +#110650 = DEFINITIONAL_REPRESENTATION('',(#110651),#110655); +#110651 = LINE('',#110652,#110653); +#110652 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#110653 = VECTOR('',#110654,1.); +#110654 = DIRECTION('',(-1.,-1.021336205033E-016)); +#110655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108307 = PCURVE('',#108308,#108313); -#108308 = CYLINDRICAL_SURFACE('',#108309,0.119270391569); -#108309 = AXIS2_PLACEMENT_3D('',#108310,#108311,#108312); -#108310 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#108311 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108312 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108313 = DEFINITIONAL_REPRESENTATION('',(#108314),#108317); -#108314 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108315,#108316), +#110656 = ORIENTED_EDGE('',*,*,#110551,.F.); +#110657 = ORIENTED_EDGE('',*,*,#110658,.F.); +#110658 = EDGE_CURVE('',#110608,#110552,#110659,.T.); +#110659 = SURFACE_CURVE('',#110660,(#110664,#110671),.PCURVE_S1.); +#110660 = LINE('',#110661,#110662); +#110661 = CARTESIAN_POINT('',(-0.51959417205,1.15,0.530776333563)); +#110662 = VECTOR('',#110663,1.); +#110663 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#110664 = PCURVE('',#110566,#110665); +#110665 = DEFINITIONAL_REPRESENTATION('',(#110666),#110670); +#110666 = LINE('',#110667,#110668); +#110667 = CARTESIAN_POINT('',(8.85,-4.535643882845E-033)); +#110668 = VECTOR('',#110669,1.); +#110669 = DIRECTION('',(-4.535643882845E-032,-1.)); +#110670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110671 = PCURVE('',#94457,#110672); +#110672 = DEFINITIONAL_REPRESENTATION('',(#110673),#110677); +#110673 = LINE('',#110674,#110675); +#110674 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#110675 = VECTOR('',#110676,1.); +#110676 = DIRECTION('',(1.,-1.021336205033E-016)); +#110677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110678 = ADVANCED_FACE('',(#110679),#110513,.T.); +#110679 = FACE_BOUND('',#110680,.T.); +#110680 = EDGE_LOOP('',(#110681,#110710,#110731,#110732)); +#110681 = ORIENTED_EDGE('',*,*,#110682,.T.); +#110682 = EDGE_CURVE('',#110683,#110685,#110687,.T.); +#110683 = VERTEX_POINT('',#110684); +#110684 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.530776333563)); +#110685 = VERTEX_POINT('',#110686); +#110686 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.530776333563)); +#110687 = SURFACE_CURVE('',#110688,(#110692,#110699),.PCURVE_S1.); +#110688 = LINE('',#110689,#110690); +#110689 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#110690 = VECTOR('',#110691,1.); +#110691 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110692 = PCURVE('',#110513,#110693); +#110693 = DEFINITIONAL_REPRESENTATION('',(#110694),#110698); +#110694 = LINE('',#110695,#110696); +#110695 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110696 = VECTOR('',#110697,1.); +#110697 = DIRECTION('',(-1.,0.E+000)); +#110698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110699 = PCURVE('',#110700,#110705); +#110700 = CYLINDRICAL_SURFACE('',#110701,0.119270391569); +#110701 = AXIS2_PLACEMENT_3D('',#110702,#110703,#110704); +#110702 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#110703 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110704 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110705 = DEFINITIONAL_REPRESENTATION('',(#110706),#110709); +#110706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110707,#110708), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#108315 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#108316 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#108317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108318 = ORIENTED_EDGE('',*,*,#108319,.T.); -#108319 = EDGE_CURVE('',#108293,#108058,#108320,.T.); -#108320 = SURFACE_CURVE('',#108321,(#108325,#108332),.PCURVE_S1.); -#108321 = LINE('',#108322,#108323); -#108322 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.530776333563)); -#108323 = VECTOR('',#108324,1.); -#108324 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#108325 = PCURVE('',#108121,#108326); -#108326 = DEFINITIONAL_REPRESENTATION('',(#108327),#108331); -#108327 = LINE('',#108328,#108329); -#108328 = CARTESIAN_POINT('',(-8.85,1.133910970711E-033)); -#108329 = VECTOR('',#108330,1.); -#108330 = DIRECTION('',(4.535643882845E-032,-1.)); -#108331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108332 = PCURVE('',#92065,#108333); -#108333 = DEFINITIONAL_REPRESENTATION('',(#108334),#108338); -#108334 = LINE('',#108335,#108336); -#108335 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#108336 = VECTOR('',#108337,1.); -#108337 = DIRECTION('',(1.,-1.021336205033E-016)); -#108338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108339 = ORIENTED_EDGE('',*,*,#108108,.F.); -#108340 = ORIENTED_EDGE('',*,*,#108341,.F.); -#108341 = EDGE_CURVE('',#108291,#108086,#108342,.T.); -#108342 = SURFACE_CURVE('',#108343,(#108347,#108354),.PCURVE_S1.); -#108343 = LINE('',#108344,#108345); -#108344 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.530776333563)); -#108345 = VECTOR('',#108346,1.); -#108346 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#108347 = PCURVE('',#108121,#108348); -#108348 = DEFINITIONAL_REPRESENTATION('',(#108349),#108353); -#108349 = LINE('',#108350,#108351); -#108350 = CARTESIAN_POINT('',(-8.65,-1.133910970711E-033)); -#108351 = VECTOR('',#108352,1.); -#108352 = DIRECTION('',(4.535643882845E-032,-1.)); -#108353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108354 = PCURVE('',#92121,#108355); -#108355 = DEFINITIONAL_REPRESENTATION('',(#108356),#108360); -#108356 = LINE('',#108357,#108358); -#108357 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#108358 = VECTOR('',#108359,1.); -#108359 = DIRECTION('',(-1.,-1.021336205033E-016)); -#108360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108361 = ADVANCED_FACE('',(#108362),#108308,.F.); -#108362 = FACE_BOUND('',#108363,.F.); -#108363 = EDGE_LOOP('',(#108364,#108365,#108388,#108433)); -#108364 = ORIENTED_EDGE('',*,*,#108290,.T.); -#108365 = ORIENTED_EDGE('',*,*,#108366,.F.); -#108366 = EDGE_CURVE('',#108367,#108293,#108369,.T.); -#108367 = VERTEX_POINT('',#108368); -#108368 = CARTESIAN_POINT('',(-0.303662633502,1.15,0.65)); -#108369 = SURFACE_CURVE('',#108370,(#108375,#108381),.PCURVE_S1.); -#108370 = CIRCLE('',#108371,0.119270391569); -#108371 = AXIS2_PLACEMENT_3D('',#108372,#108373,#108374); -#108372 = CARTESIAN_POINT('',(-0.30032442045,1.15,0.530776333563)); -#108373 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108374 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108375 = PCURVE('',#108308,#108376); -#108376 = DEFINITIONAL_REPRESENTATION('',(#108377),#108380); -#108377 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108378,#108379), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), - .PIECEWISE_BEZIER_KNOTS.); -#108378 = CARTESIAN_POINT('',(1.598788597134,8.85)); -#108379 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#108380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108381 = PCURVE('',#92065,#108382); -#108382 = DEFINITIONAL_REPRESENTATION('',(#108383),#108387); -#108383 = CIRCLE('',#108384,0.119270391569); -#108384 = AXIS2_PLACEMENT_2D('',#108385,#108386); -#108385 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#108386 = DIRECTION('',(0.E+000,1.)); -#108387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110707 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#110708 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#110709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110710 = ORIENTED_EDGE('',*,*,#110711,.T.); +#110711 = EDGE_CURVE('',#110685,#110450,#110712,.T.); +#110712 = SURFACE_CURVE('',#110713,(#110717,#110724),.PCURVE_S1.); +#110713 = LINE('',#110714,#110715); +#110714 = CARTESIAN_POINT('',(-0.419594812019,1.15,0.530776333563)); +#110715 = VECTOR('',#110716,1.); +#110716 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#110717 = PCURVE('',#110513,#110718); +#110718 = DEFINITIONAL_REPRESENTATION('',(#110719),#110723); +#110719 = LINE('',#110720,#110721); +#110720 = CARTESIAN_POINT('',(-8.85,1.133910970711E-033)); +#110721 = VECTOR('',#110722,1.); +#110722 = DIRECTION('',(4.535643882845E-032,-1.)); +#110723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110724 = PCURVE('',#94457,#110725); +#110725 = DEFINITIONAL_REPRESENTATION('',(#110726),#110730); +#110726 = LINE('',#110727,#110728); +#110727 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#110728 = VECTOR('',#110729,1.); +#110729 = DIRECTION('',(1.,-1.021336205033E-016)); +#110730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110731 = ORIENTED_EDGE('',*,*,#110500,.F.); +#110732 = ORIENTED_EDGE('',*,*,#110733,.F.); +#110733 = EDGE_CURVE('',#110683,#110478,#110734,.T.); +#110734 = SURFACE_CURVE('',#110735,(#110739,#110746),.PCURVE_S1.); +#110735 = LINE('',#110736,#110737); +#110736 = CARTESIAN_POINT('',(-0.419594812019,1.35,0.530776333563)); +#110737 = VECTOR('',#110738,1.); +#110738 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#110739 = PCURVE('',#110513,#110740); +#110740 = DEFINITIONAL_REPRESENTATION('',(#110741),#110745); +#110741 = LINE('',#110742,#110743); +#110742 = CARTESIAN_POINT('',(-8.65,-1.133910970711E-033)); +#110743 = VECTOR('',#110744,1.); +#110744 = DIRECTION('',(4.535643882845E-032,-1.)); +#110745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110746 = PCURVE('',#94513,#110747); +#110747 = DEFINITIONAL_REPRESENTATION('',(#110748),#110752); +#110748 = LINE('',#110749,#110750); +#110749 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#110750 = VECTOR('',#110751,1.); +#110751 = DIRECTION('',(-1.,-1.021336205033E-016)); +#110752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108388 = ORIENTED_EDGE('',*,*,#108389,.T.); -#108389 = EDGE_CURVE('',#108367,#108390,#108392,.T.); -#108390 = VERTEX_POINT('',#108391); -#108391 = CARTESIAN_POINT('',(-0.303662633502,1.35,0.65)); -#108392 = SURFACE_CURVE('',#108393,(#108397,#108426),.PCURVE_S1.); -#108393 = LINE('',#108394,#108395); -#108394 = CARTESIAN_POINT('',(-0.303662633502,1.35,0.65)); -#108395 = VECTOR('',#108396,1.); -#108396 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108397 = PCURVE('',#108308,#108398); -#108398 = DEFINITIONAL_REPRESENTATION('',(#108399),#108425); -#108399 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#108400,#108401,#108402, - #108403,#108404,#108405,#108406,#108407,#108408,#108409,#108410, - #108411,#108412,#108413,#108414,#108415,#108416,#108417,#108418, - #108419,#108420,#108421,#108422,#108423,#108424),.UNSPECIFIED.,.F., +#110753 = ADVANCED_FACE('',(#110754),#110700,.F.); +#110754 = FACE_BOUND('',#110755,.F.); +#110755 = EDGE_LOOP('',(#110756,#110757,#110780,#110825)); +#110756 = ORIENTED_EDGE('',*,*,#110682,.T.); +#110757 = ORIENTED_EDGE('',*,*,#110758,.F.); +#110758 = EDGE_CURVE('',#110759,#110685,#110761,.T.); +#110759 = VERTEX_POINT('',#110760); +#110760 = CARTESIAN_POINT('',(-0.303662633502,1.15,0.65)); +#110761 = SURFACE_CURVE('',#110762,(#110767,#110773),.PCURVE_S1.); +#110762 = CIRCLE('',#110763,0.119270391569); +#110763 = AXIS2_PLACEMENT_3D('',#110764,#110765,#110766); +#110764 = CARTESIAN_POINT('',(-0.30032442045,1.15,0.530776333563)); +#110765 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110766 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110767 = PCURVE('',#110700,#110768); +#110768 = DEFINITIONAL_REPRESENTATION('',(#110769),#110772); +#110769 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110770,#110771), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), + .PIECEWISE_BEZIER_KNOTS.); +#110770 = CARTESIAN_POINT('',(1.598788597134,8.85)); +#110771 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#110772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110773 = PCURVE('',#94457,#110774); +#110774 = DEFINITIONAL_REPRESENTATION('',(#110775),#110779); +#110775 = CIRCLE('',#110776,0.119270391569); +#110776 = AXIS2_PLACEMENT_2D('',#110777,#110778); +#110777 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#110778 = DIRECTION('',(0.E+000,1.)); +#110779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110780 = ORIENTED_EDGE('',*,*,#110781,.T.); +#110781 = EDGE_CURVE('',#110759,#110782,#110784,.T.); +#110782 = VERTEX_POINT('',#110783); +#110783 = CARTESIAN_POINT('',(-0.303662633502,1.35,0.65)); +#110784 = SURFACE_CURVE('',#110785,(#110789,#110818),.PCURVE_S1.); +#110785 = LINE('',#110786,#110787); +#110786 = CARTESIAN_POINT('',(-0.303662633502,1.35,0.65)); +#110787 = VECTOR('',#110788,1.); +#110788 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#110789 = PCURVE('',#110700,#110790); +#110790 = DEFINITIONAL_REPRESENTATION('',(#110791),#110817); +#110791 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110792,#110793,#110794, + #110795,#110796,#110797,#110798,#110799,#110800,#110801,#110802, + #110803,#110804,#110805,#110806,#110807,#110808,#110809,#110810, + #110811,#110812,#110813,#110814,#110815,#110816),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -133531,128 +136533,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.QUASI_UNIFORM_KNOTS.); -#108400 = CARTESIAN_POINT('',(1.598788597134,8.85)); -#108401 = CARTESIAN_POINT('',(1.598788597134,8.84696969697)); -#108402 = CARTESIAN_POINT('',(1.598788597134,8.840909090909)); -#108403 = CARTESIAN_POINT('',(1.598788597134,8.831818181818)); -#108404 = CARTESIAN_POINT('',(1.598788597134,8.822727272727)); -#108405 = CARTESIAN_POINT('',(1.598788597134,8.813636363636)); -#108406 = CARTESIAN_POINT('',(1.598788597134,8.804545454545)); -#108407 = CARTESIAN_POINT('',(1.598788597134,8.795454545455)); -#108408 = CARTESIAN_POINT('',(1.598788597134,8.786363636364)); -#108409 = CARTESIAN_POINT('',(1.598788597134,8.777272727273)); -#108410 = CARTESIAN_POINT('',(1.598788597134,8.768181818182)); -#108411 = CARTESIAN_POINT('',(1.598788597134,8.759090909091)); -#108412 = CARTESIAN_POINT('',(1.598788597134,8.75)); -#108413 = CARTESIAN_POINT('',(1.598788597134,8.740909090909)); -#108414 = CARTESIAN_POINT('',(1.598788597134,8.731818181818)); -#108415 = CARTESIAN_POINT('',(1.598788597134,8.722727272727)); -#108416 = CARTESIAN_POINT('',(1.598788597134,8.713636363636)); -#108417 = CARTESIAN_POINT('',(1.598788597134,8.704545454545)); -#108418 = CARTESIAN_POINT('',(1.598788597134,8.695454545455)); -#108419 = CARTESIAN_POINT('',(1.598788597134,8.686363636364)); -#108420 = CARTESIAN_POINT('',(1.598788597134,8.677272727273)); -#108421 = CARTESIAN_POINT('',(1.598788597134,8.668181818182)); -#108422 = CARTESIAN_POINT('',(1.598788597134,8.659090909091)); -#108423 = CARTESIAN_POINT('',(1.598788597134,8.65303030303)); -#108424 = CARTESIAN_POINT('',(1.598788597134,8.65)); -#108425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108426 = PCURVE('',#92093,#108427); -#108427 = DEFINITIONAL_REPRESENTATION('',(#108428),#108432); -#108428 = LINE('',#108429,#108430); -#108429 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#108430 = VECTOR('',#108431,1.); -#108431 = DIRECTION('',(4.440892098501E-016,1.)); -#108432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108433 = ORIENTED_EDGE('',*,*,#108434,.T.); -#108434 = EDGE_CURVE('',#108390,#108291,#108435,.T.); -#108435 = SURFACE_CURVE('',#108436,(#108441,#108447),.PCURVE_S1.); -#108436 = CIRCLE('',#108437,0.119270391569); -#108437 = AXIS2_PLACEMENT_3D('',#108438,#108439,#108440); -#108438 = CARTESIAN_POINT('',(-0.30032442045,1.35,0.530776333563)); -#108439 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108440 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108441 = PCURVE('',#108308,#108442); -#108442 = DEFINITIONAL_REPRESENTATION('',(#108443),#108446); -#108443 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108444,#108445), +#110792 = CARTESIAN_POINT('',(1.598788597134,8.85)); +#110793 = CARTESIAN_POINT('',(1.598788597134,8.84696969697)); +#110794 = CARTESIAN_POINT('',(1.598788597134,8.840909090909)); +#110795 = CARTESIAN_POINT('',(1.598788597134,8.831818181818)); +#110796 = CARTESIAN_POINT('',(1.598788597134,8.822727272727)); +#110797 = CARTESIAN_POINT('',(1.598788597134,8.813636363636)); +#110798 = CARTESIAN_POINT('',(1.598788597134,8.804545454545)); +#110799 = CARTESIAN_POINT('',(1.598788597134,8.795454545455)); +#110800 = CARTESIAN_POINT('',(1.598788597134,8.786363636364)); +#110801 = CARTESIAN_POINT('',(1.598788597134,8.777272727273)); +#110802 = CARTESIAN_POINT('',(1.598788597134,8.768181818182)); +#110803 = CARTESIAN_POINT('',(1.598788597134,8.759090909091)); +#110804 = CARTESIAN_POINT('',(1.598788597134,8.75)); +#110805 = CARTESIAN_POINT('',(1.598788597134,8.740909090909)); +#110806 = CARTESIAN_POINT('',(1.598788597134,8.731818181818)); +#110807 = CARTESIAN_POINT('',(1.598788597134,8.722727272727)); +#110808 = CARTESIAN_POINT('',(1.598788597134,8.713636363636)); +#110809 = CARTESIAN_POINT('',(1.598788597134,8.704545454545)); +#110810 = CARTESIAN_POINT('',(1.598788597134,8.695454545455)); +#110811 = CARTESIAN_POINT('',(1.598788597134,8.686363636364)); +#110812 = CARTESIAN_POINT('',(1.598788597134,8.677272727273)); +#110813 = CARTESIAN_POINT('',(1.598788597134,8.668181818182)); +#110814 = CARTESIAN_POINT('',(1.598788597134,8.659090909091)); +#110815 = CARTESIAN_POINT('',(1.598788597134,8.65303030303)); +#110816 = CARTESIAN_POINT('',(1.598788597134,8.65)); +#110817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110818 = PCURVE('',#94485,#110819); +#110819 = DEFINITIONAL_REPRESENTATION('',(#110820),#110824); +#110820 = LINE('',#110821,#110822); +#110821 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#110822 = VECTOR('',#110823,1.); +#110823 = DIRECTION('',(4.440892098501E-016,1.)); +#110824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110825 = ORIENTED_EDGE('',*,*,#110826,.T.); +#110826 = EDGE_CURVE('',#110782,#110683,#110827,.T.); +#110827 = SURFACE_CURVE('',#110828,(#110833,#110839),.PCURVE_S1.); +#110828 = CIRCLE('',#110829,0.119270391569); +#110829 = AXIS2_PLACEMENT_3D('',#110830,#110831,#110832); +#110830 = CARTESIAN_POINT('',(-0.30032442045,1.35,0.530776333563)); +#110831 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110832 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110833 = PCURVE('',#110700,#110834); +#110834 = DEFINITIONAL_REPRESENTATION('',(#110835),#110838); +#110835 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110836,#110837), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#108444 = CARTESIAN_POINT('',(1.598788597134,8.65)); -#108445 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#108446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110836 = CARTESIAN_POINT('',(1.598788597134,8.65)); +#110837 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#110838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108447 = PCURVE('',#92121,#108448); -#108448 = DEFINITIONAL_REPRESENTATION('',(#108449),#108457); -#108449 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108450,#108451,#108452, - #108453,#108454,#108455,#108456),.UNSPECIFIED.,.T.,.F.) +#110839 = PCURVE('',#94513,#110840); +#110840 = DEFINITIONAL_REPRESENTATION('',(#110841),#110849); +#110841 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110842,#110843,#110844, + #110845,#110846,#110847,#110848),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#108450 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#108451 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#108452 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#108453 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#108454 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#108455 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#108456 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#108457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108458 = ADVANCED_FACE('',(#108459),#108233,.T.); -#108459 = FACE_BOUND('',#108460,.T.); -#108460 = EDGE_LOOP('',(#108461,#108462,#108485,#108530)); -#108461 = ORIENTED_EDGE('',*,*,#108215,.F.); -#108462 = ORIENTED_EDGE('',*,*,#108463,.F.); -#108463 = EDGE_CURVE('',#108464,#108216,#108466,.T.); -#108464 = VERTEX_POINT('',#108465); -#108465 = CARTESIAN_POINT('',(-0.304819755875,1.15,0.75)); -#108466 = SURFACE_CURVE('',#108467,(#108472,#108478),.PCURVE_S1.); -#108467 = CIRCLE('',#108468,0.2192697516); -#108468 = AXIS2_PLACEMENT_3D('',#108469,#108470,#108471); -#108469 = CARTESIAN_POINT('',(-0.30032442045,1.15,0.530776333563)); -#108470 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108471 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108472 = PCURVE('',#108233,#108473); -#108473 = DEFINITIONAL_REPRESENTATION('',(#108474),#108477); -#108474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108475,#108476), +#110842 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#110843 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#110844 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#110845 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#110846 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#110847 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#110848 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#110849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110850 = ADVANCED_FACE('',(#110851),#110625,.T.); +#110851 = FACE_BOUND('',#110852,.T.); +#110852 = EDGE_LOOP('',(#110853,#110854,#110877,#110922)); +#110853 = ORIENTED_EDGE('',*,*,#110607,.F.); +#110854 = ORIENTED_EDGE('',*,*,#110855,.F.); +#110855 = EDGE_CURVE('',#110856,#110608,#110858,.T.); +#110856 = VERTEX_POINT('',#110857); +#110857 = CARTESIAN_POINT('',(-0.304819755875,1.15,0.75)); +#110858 = SURFACE_CURVE('',#110859,(#110864,#110870),.PCURVE_S1.); +#110859 = CIRCLE('',#110860,0.2192697516); +#110860 = AXIS2_PLACEMENT_3D('',#110861,#110862,#110863); +#110861 = CARTESIAN_POINT('',(-0.30032442045,1.15,0.530776333563)); +#110862 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110863 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110864 = PCURVE('',#110625,#110865); +#110865 = DEFINITIONAL_REPRESENTATION('',(#110866),#110869); +#110866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110867,#110868), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#108475 = CARTESIAN_POINT('',(1.591299156552,8.85)); -#108476 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#108477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108478 = PCURVE('',#92065,#108479); -#108479 = DEFINITIONAL_REPRESENTATION('',(#108480),#108484); -#108480 = CIRCLE('',#108481,0.2192697516); -#108481 = AXIS2_PLACEMENT_2D('',#108482,#108483); -#108482 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#108483 = DIRECTION('',(0.E+000,1.)); -#108484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108485 = ORIENTED_EDGE('',*,*,#108486,.F.); -#108486 = EDGE_CURVE('',#108487,#108464,#108489,.T.); -#108487 = VERTEX_POINT('',#108488); -#108488 = CARTESIAN_POINT('',(-0.304819755875,1.35,0.75)); -#108489 = SURFACE_CURVE('',#108490,(#108494,#108523),.PCURVE_S1.); -#108490 = LINE('',#108491,#108492); -#108491 = CARTESIAN_POINT('',(-0.304819755875,1.35,0.75)); -#108492 = VECTOR('',#108493,1.); -#108493 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108494 = PCURVE('',#108233,#108495); -#108495 = DEFINITIONAL_REPRESENTATION('',(#108496),#108522); -#108496 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#108497,#108498,#108499, - #108500,#108501,#108502,#108503,#108504,#108505,#108506,#108507, - #108508,#108509,#108510,#108511,#108512,#108513,#108514,#108515, - #108516,#108517,#108518,#108519,#108520,#108521),.UNSPECIFIED.,.F., +#110867 = CARTESIAN_POINT('',(1.591299156552,8.85)); +#110868 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#110869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110870 = PCURVE('',#94457,#110871); +#110871 = DEFINITIONAL_REPRESENTATION('',(#110872),#110876); +#110872 = CIRCLE('',#110873,0.2192697516); +#110873 = AXIS2_PLACEMENT_2D('',#110874,#110875); +#110874 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#110875 = DIRECTION('',(0.E+000,1.)); +#110876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110877 = ORIENTED_EDGE('',*,*,#110878,.F.); +#110878 = EDGE_CURVE('',#110879,#110856,#110881,.T.); +#110879 = VERTEX_POINT('',#110880); +#110880 = CARTESIAN_POINT('',(-0.304819755875,1.35,0.75)); +#110881 = SURFACE_CURVE('',#110882,(#110886,#110915),.PCURVE_S1.); +#110882 = LINE('',#110883,#110884); +#110883 = CARTESIAN_POINT('',(-0.304819755875,1.35,0.75)); +#110884 = VECTOR('',#110885,1.); +#110885 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110886 = PCURVE('',#110625,#110887); +#110887 = DEFINITIONAL_REPRESENTATION('',(#110888),#110914); +#110888 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110889,#110890,#110891, + #110892,#110893,#110894,#110895,#110896,#110897,#110898,#110899, + #110900,#110901,#110902,#110903,#110904,#110905,#110906,#110907, + #110908,#110909,#110910,#110911,#110912,#110913),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -133661,956 +136663,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#108497 = CARTESIAN_POINT('',(1.591299156552,8.65)); -#108498 = CARTESIAN_POINT('',(1.591299156552,8.65303030303)); -#108499 = CARTESIAN_POINT('',(1.591299156552,8.659090909091)); -#108500 = CARTESIAN_POINT('',(1.591299156552,8.668181818182)); -#108501 = CARTESIAN_POINT('',(1.591299156552,8.677272727273)); -#108502 = CARTESIAN_POINT('',(1.591299156552,8.686363636364)); -#108503 = CARTESIAN_POINT('',(1.591299156552,8.695454545455)); -#108504 = CARTESIAN_POINT('',(1.591299156552,8.704545454545)); -#108505 = CARTESIAN_POINT('',(1.591299156552,8.713636363636)); -#108506 = CARTESIAN_POINT('',(1.591299156552,8.722727272727)); -#108507 = CARTESIAN_POINT('',(1.591299156552,8.731818181818)); -#108508 = CARTESIAN_POINT('',(1.591299156552,8.740909090909)); -#108509 = CARTESIAN_POINT('',(1.591299156552,8.75)); -#108510 = CARTESIAN_POINT('',(1.591299156552,8.759090909091)); -#108511 = CARTESIAN_POINT('',(1.591299156552,8.768181818182)); -#108512 = CARTESIAN_POINT('',(1.591299156552,8.777272727273)); -#108513 = CARTESIAN_POINT('',(1.591299156552,8.786363636364)); -#108514 = CARTESIAN_POINT('',(1.591299156552,8.795454545455)); -#108515 = CARTESIAN_POINT('',(1.591299156552,8.804545454545)); -#108516 = CARTESIAN_POINT('',(1.591299156552,8.813636363636)); -#108517 = CARTESIAN_POINT('',(1.591299156552,8.822727272727)); -#108518 = CARTESIAN_POINT('',(1.591299156552,8.831818181818)); -#108519 = CARTESIAN_POINT('',(1.591299156552,8.840909090909)); -#108520 = CARTESIAN_POINT('',(1.591299156552,8.84696969697)); -#108521 = CARTESIAN_POINT('',(1.591299156552,8.85)); -#108522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108523 = PCURVE('',#92147,#108524); -#108524 = DEFINITIONAL_REPRESENTATION('',(#108525),#108529); -#108525 = LINE('',#108526,#108527); -#108526 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#108527 = VECTOR('',#108528,1.); -#108528 = DIRECTION('',(4.440892098501E-016,-1.)); -#108529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108530 = ORIENTED_EDGE('',*,*,#108531,.T.); -#108531 = EDGE_CURVE('',#108487,#108218,#108532,.T.); -#108532 = SURFACE_CURVE('',#108533,(#108538,#108544),.PCURVE_S1.); -#108533 = CIRCLE('',#108534,0.2192697516); -#108534 = AXIS2_PLACEMENT_3D('',#108535,#108536,#108537); -#108535 = CARTESIAN_POINT('',(-0.30032442045,1.35,0.530776333563)); -#108536 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108537 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#108538 = PCURVE('',#108233,#108539); -#108539 = DEFINITIONAL_REPRESENTATION('',(#108540),#108543); -#108540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108541,#108542), +#110889 = CARTESIAN_POINT('',(1.591299156552,8.65)); +#110890 = CARTESIAN_POINT('',(1.591299156552,8.65303030303)); +#110891 = CARTESIAN_POINT('',(1.591299156552,8.659090909091)); +#110892 = CARTESIAN_POINT('',(1.591299156552,8.668181818182)); +#110893 = CARTESIAN_POINT('',(1.591299156552,8.677272727273)); +#110894 = CARTESIAN_POINT('',(1.591299156552,8.686363636364)); +#110895 = CARTESIAN_POINT('',(1.591299156552,8.695454545455)); +#110896 = CARTESIAN_POINT('',(1.591299156552,8.704545454545)); +#110897 = CARTESIAN_POINT('',(1.591299156552,8.713636363636)); +#110898 = CARTESIAN_POINT('',(1.591299156552,8.722727272727)); +#110899 = CARTESIAN_POINT('',(1.591299156552,8.731818181818)); +#110900 = CARTESIAN_POINT('',(1.591299156552,8.740909090909)); +#110901 = CARTESIAN_POINT('',(1.591299156552,8.75)); +#110902 = CARTESIAN_POINT('',(1.591299156552,8.759090909091)); +#110903 = CARTESIAN_POINT('',(1.591299156552,8.768181818182)); +#110904 = CARTESIAN_POINT('',(1.591299156552,8.777272727273)); +#110905 = CARTESIAN_POINT('',(1.591299156552,8.786363636364)); +#110906 = CARTESIAN_POINT('',(1.591299156552,8.795454545455)); +#110907 = CARTESIAN_POINT('',(1.591299156552,8.804545454545)); +#110908 = CARTESIAN_POINT('',(1.591299156552,8.813636363636)); +#110909 = CARTESIAN_POINT('',(1.591299156552,8.822727272727)); +#110910 = CARTESIAN_POINT('',(1.591299156552,8.831818181818)); +#110911 = CARTESIAN_POINT('',(1.591299156552,8.840909090909)); +#110912 = CARTESIAN_POINT('',(1.591299156552,8.84696969697)); +#110913 = CARTESIAN_POINT('',(1.591299156552,8.85)); +#110914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110915 = PCURVE('',#94539,#110916); +#110916 = DEFINITIONAL_REPRESENTATION('',(#110917),#110921); +#110917 = LINE('',#110918,#110919); +#110918 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#110919 = VECTOR('',#110920,1.); +#110920 = DIRECTION('',(4.440892098501E-016,-1.)); +#110921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110922 = ORIENTED_EDGE('',*,*,#110923,.T.); +#110923 = EDGE_CURVE('',#110879,#110610,#110924,.T.); +#110924 = SURFACE_CURVE('',#110925,(#110930,#110936),.PCURVE_S1.); +#110925 = CIRCLE('',#110926,0.2192697516); +#110926 = AXIS2_PLACEMENT_3D('',#110927,#110928,#110929); +#110927 = CARTESIAN_POINT('',(-0.30032442045,1.35,0.530776333563)); +#110928 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#110929 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#110930 = PCURVE('',#110625,#110931); +#110931 = DEFINITIONAL_REPRESENTATION('',(#110932),#110935); +#110932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110933,#110934), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#108541 = CARTESIAN_POINT('',(1.591299156552,8.65)); -#108542 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#108543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110933 = CARTESIAN_POINT('',(1.591299156552,8.65)); +#110934 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#110935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108544 = PCURVE('',#92121,#108545); -#108545 = DEFINITIONAL_REPRESENTATION('',(#108546),#108554); -#108546 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108547,#108548,#108549, - #108550,#108551,#108552,#108553),.UNSPECIFIED.,.T.,.F.) +#110936 = PCURVE('',#94513,#110937); +#110937 = DEFINITIONAL_REPRESENTATION('',(#110938),#110946); +#110938 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110939,#110940,#110941, + #110942,#110943,#110944,#110945),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#108547 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#108548 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#108549 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#108550 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#108551 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#108552 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#108553 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#108554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108555 = ADVANCED_FACE('',(#108556),#92093,.T.); -#108556 = FACE_BOUND('',#108557,.T.); -#108557 = EDGE_LOOP('',(#108558,#108579,#108580,#108601)); -#108558 = ORIENTED_EDGE('',*,*,#108559,.F.); -#108559 = EDGE_CURVE('',#108367,#92050,#108560,.T.); -#108560 = SURFACE_CURVE('',#108561,(#108565,#108572),.PCURVE_S1.); -#108561 = LINE('',#108562,#108563); -#108562 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.65)); -#108563 = VECTOR('',#108564,1.); -#108564 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#108565 = PCURVE('',#92093,#108566); -#108566 = DEFINITIONAL_REPRESENTATION('',(#108567),#108571); -#108567 = LINE('',#108568,#108569); -#108568 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#108569 = VECTOR('',#108570,1.); -#108570 = DIRECTION('',(-1.,2.995851623787E-063)); -#108571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108572 = PCURVE('',#92065,#108573); -#108573 = DEFINITIONAL_REPRESENTATION('',(#108574),#108578); -#108574 = LINE('',#108575,#108576); -#108575 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108576 = VECTOR('',#108577,1.); -#108577 = DIRECTION('',(-3.563627120235E-016,1.)); -#108578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108579 = ORIENTED_EDGE('',*,*,#108389,.T.); -#108580 = ORIENTED_EDGE('',*,*,#108581,.T.); -#108581 = EDGE_CURVE('',#108390,#92078,#108582,.T.); -#108582 = SURFACE_CURVE('',#108583,(#108587,#108594),.PCURVE_S1.); -#108583 = LINE('',#108584,#108585); -#108584 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); -#108585 = VECTOR('',#108586,1.); -#108586 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#108587 = PCURVE('',#92093,#108588); -#108588 = DEFINITIONAL_REPRESENTATION('',(#108589),#108593); -#108589 = LINE('',#108590,#108591); -#108590 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108591 = VECTOR('',#108592,1.); -#108592 = DIRECTION('',(-1.,2.995851623787E-063)); -#108593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108594 = PCURVE('',#92121,#108595); -#108595 = DEFINITIONAL_REPRESENTATION('',(#108596),#108600); -#108596 = LINE('',#108597,#108598); -#108597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108598 = VECTOR('',#108599,1.); -#108599 = DIRECTION('',(3.563627120235E-016,1.)); -#108600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#110939 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#110940 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#110941 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#110942 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#110943 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#110944 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#110945 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#110946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108601 = ORIENTED_EDGE('',*,*,#92077,.F.); -#108602 = ADVANCED_FACE('',(#108603),#92065,.T.); -#108603 = FACE_BOUND('',#108604,.T.); -#108604 = EDGE_LOOP('',(#108605,#108626,#108627,#108628,#108629,#108630, - #108651,#108652,#108653,#108654,#108655,#108656)); -#108605 = ORIENTED_EDGE('',*,*,#108606,.F.); -#108606 = EDGE_CURVE('',#108464,#92048,#108607,.T.); -#108607 = SURFACE_CURVE('',#108608,(#108612,#108619),.PCURVE_S1.); -#108608 = LINE('',#108609,#108610); -#108609 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.75)); -#108610 = VECTOR('',#108611,1.); -#108611 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#108612 = PCURVE('',#92065,#108613); -#108613 = DEFINITIONAL_REPRESENTATION('',(#108614),#108618); -#108614 = LINE('',#108615,#108616); -#108615 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#108616 = VECTOR('',#108617,1.); -#108617 = DIRECTION('',(-3.563627120235E-016,1.)); -#108618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108619 = PCURVE('',#92147,#108620); -#108620 = DEFINITIONAL_REPRESENTATION('',(#108621),#108625); -#108621 = LINE('',#108622,#108623); -#108622 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#108623 = VECTOR('',#108624,1.); -#108624 = DIRECTION('',(1.,2.995851623787E-063)); -#108625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108626 = ORIENTED_EDGE('',*,*,#108463,.T.); -#108627 = ORIENTED_EDGE('',*,*,#108266,.T.); -#108628 = ORIENTED_EDGE('',*,*,#108186,.T.); -#108629 = ORIENTED_EDGE('',*,*,#107983,.T.); -#108630 = ORIENTED_EDGE('',*,*,#108631,.F.); -#108631 = EDGE_CURVE('',#107847,#107954,#108632,.T.); -#108632 = SURFACE_CURVE('',#108633,(#108637,#108644),.PCURVE_S1.); -#108633 = LINE('',#108634,#108635); -#108634 = CARTESIAN_POINT('',(-1.,1.15,1.159810404338E-002)); -#108635 = VECTOR('',#108636,1.); -#108636 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#108637 = PCURVE('',#92065,#108638); -#108638 = DEFINITIONAL_REPRESENTATION('',(#108639),#108643); -#108639 = LINE('',#108640,#108641); -#108640 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#108641 = VECTOR('',#108642,1.); -#108642 = DIRECTION('',(-1.,-2.101748079665E-016)); -#108643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108644 = PCURVE('',#107867,#108645); -#108645 = DEFINITIONAL_REPRESENTATION('',(#108646),#108650); -#108646 = LINE('',#108647,#108648); -#108647 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#108648 = VECTOR('',#108649,1.); -#108649 = DIRECTION('',(-1.194699204908E-017,1.)); -#108650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108651 = ORIENTED_EDGE('',*,*,#107929,.F.); -#108652 = ORIENTED_EDGE('',*,*,#108057,.F.); -#108653 = ORIENTED_EDGE('',*,*,#108319,.F.); -#108654 = ORIENTED_EDGE('',*,*,#108366,.F.); -#108655 = ORIENTED_EDGE('',*,*,#108559,.T.); -#108656 = ORIENTED_EDGE('',*,*,#92047,.F.); -#108657 = ADVANCED_FACE('',(#108658),#92147,.T.); -#108658 = FACE_BOUND('',#108659,.T.); -#108659 = EDGE_LOOP('',(#108660,#108681,#108682,#108683)); -#108660 = ORIENTED_EDGE('',*,*,#108661,.F.); -#108661 = EDGE_CURVE('',#108487,#92106,#108662,.T.); -#108662 = SURFACE_CURVE('',#108663,(#108667,#108674),.PCURVE_S1.); -#108663 = LINE('',#108664,#108665); -#108664 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.75)); -#108665 = VECTOR('',#108666,1.); -#108666 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#108667 = PCURVE('',#92147,#108668); -#108668 = DEFINITIONAL_REPRESENTATION('',(#108669),#108673); -#108669 = LINE('',#108670,#108671); -#108670 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108671 = VECTOR('',#108672,1.); -#108672 = DIRECTION('',(1.,2.995851623787E-063)); -#108673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108674 = PCURVE('',#92121,#108675); -#108675 = DEFINITIONAL_REPRESENTATION('',(#108676),#108680); -#108676 = LINE('',#108677,#108678); -#108677 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#108678 = VECTOR('',#108679,1.); -#108679 = DIRECTION('',(3.563627120235E-016,1.)); -#108680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108681 = ORIENTED_EDGE('',*,*,#108486,.T.); -#108682 = ORIENTED_EDGE('',*,*,#108606,.T.); -#108683 = ORIENTED_EDGE('',*,*,#92133,.F.); -#108684 = ADVANCED_FACE('',(#108685),#92121,.T.); -#108685 = FACE_BOUND('',#108686,.T.); -#108686 = EDGE_LOOP('',(#108687,#108688,#108689,#108690,#108691,#108692, - #108713,#108714,#108715,#108716,#108717,#108718)); -#108687 = ORIENTED_EDGE('',*,*,#108581,.F.); -#108688 = ORIENTED_EDGE('',*,*,#108434,.T.); -#108689 = ORIENTED_EDGE('',*,*,#108341,.T.); -#108690 = ORIENTED_EDGE('',*,*,#108085,.T.); -#108691 = ORIENTED_EDGE('',*,*,#107879,.T.); -#108692 = ORIENTED_EDGE('',*,*,#108693,.F.); -#108693 = EDGE_CURVE('',#107956,#107845,#108694,.T.); -#108694 = SURFACE_CURVE('',#108695,(#108699,#108706),.PCURVE_S1.); -#108695 = LINE('',#108696,#108697); -#108696 = CARTESIAN_POINT('',(-1.,1.35,1.159810404338E-002)); -#108697 = VECTOR('',#108698,1.); -#108698 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#108699 = PCURVE('',#92121,#108700); -#108700 = DEFINITIONAL_REPRESENTATION('',(#108701),#108705); -#108701 = LINE('',#108702,#108703); -#108702 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#108703 = VECTOR('',#108704,1.); -#108704 = DIRECTION('',(-1.,2.101748079665E-016)); -#108705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108706 = PCURVE('',#107867,#108707); -#108707 = DEFINITIONAL_REPRESENTATION('',(#108708),#108712); -#108708 = LINE('',#108709,#108710); -#108709 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#108710 = VECTOR('',#108711,1.); -#108711 = DIRECTION('',(1.194699204908E-017,-1.)); -#108712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108713 = ORIENTED_EDGE('',*,*,#108033,.F.); -#108714 = ORIENTED_EDGE('',*,*,#108136,.F.); -#108715 = ORIENTED_EDGE('',*,*,#108244,.F.); -#108716 = ORIENTED_EDGE('',*,*,#108531,.F.); -#108717 = ORIENTED_EDGE('',*,*,#108661,.T.); -#108718 = ORIENTED_EDGE('',*,*,#92105,.F.); -#108719 = ADVANCED_FACE('',(#108720),#107867,.T.); -#108720 = FACE_BOUND('',#108721,.T.); -#108721 = EDGE_LOOP('',(#108722,#108723,#108724,#108725)); -#108722 = ORIENTED_EDGE('',*,*,#108631,.T.); -#108723 = ORIENTED_EDGE('',*,*,#107953,.T.); -#108724 = ORIENTED_EDGE('',*,*,#108693,.T.); -#108725 = ORIENTED_EDGE('',*,*,#107844,.T.); -#108726 = ADVANCED_FACE('',(#108727),#108741,.F.); -#108727 = FACE_BOUND('',#108728,.T.); -#108728 = EDGE_LOOP('',(#108729,#108764,#108787,#108814)); -#108729 = ORIENTED_EDGE('',*,*,#108730,.F.); -#108730 = EDGE_CURVE('',#108731,#108733,#108735,.T.); -#108731 = VERTEX_POINT('',#108732); -#108732 = CARTESIAN_POINT('',(-1.,5.15,-0.208196358798)); -#108733 = VERTEX_POINT('',#108734); -#108734 = CARTESIAN_POINT('',(-1.,5.35,-0.208196358798)); -#108735 = SURFACE_CURVE('',#108736,(#108740,#108752),.PCURVE_S1.); -#108736 = LINE('',#108737,#108738); -#108737 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#108738 = VECTOR('',#108739,1.); -#108739 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108740 = PCURVE('',#108741,#108746); -#108741 = PLANE('',#108742); -#108742 = AXIS2_PLACEMENT_3D('',#108743,#108744,#108745); -#108743 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#108744 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#108745 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108746 = DEFINITIONAL_REPRESENTATION('',(#108747),#108751); -#108747 = LINE('',#108748,#108749); -#108748 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#108749 = VECTOR('',#108750,1.); -#108750 = DIRECTION('',(4.440892098501E-016,1.)); -#108751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108752 = PCURVE('',#108753,#108758); -#108753 = PLANE('',#108754); -#108754 = AXIS2_PLACEMENT_3D('',#108755,#108756,#108757); -#108755 = CARTESIAN_POINT('',(-1.,5.25,-0.258196742327)); -#108756 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#108757 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108758 = DEFINITIONAL_REPRESENTATION('',(#108759),#108763); -#108759 = LINE('',#108760,#108761); -#108760 = CARTESIAN_POINT('',(-4.75,5.000038352949E-002)); -#108761 = VECTOR('',#108762,1.); -#108762 = DIRECTION('',(-1.,0.E+000)); -#108763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108764 = ORIENTED_EDGE('',*,*,#108765,.F.); -#108765 = EDGE_CURVE('',#108766,#108731,#108768,.T.); -#108766 = VERTEX_POINT('',#108767); -#108767 = CARTESIAN_POINT('',(-0.740726081328,5.15,-0.208196358798)); -#108768 = SURFACE_CURVE('',#108769,(#108773,#108780),.PCURVE_S1.); -#108769 = LINE('',#108770,#108771); -#108770 = CARTESIAN_POINT('',(-0.740726081328,5.15,-0.208196358798)); -#108771 = VECTOR('',#108772,1.); -#108772 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108773 = PCURVE('',#108741,#108774); -#108774 = DEFINITIONAL_REPRESENTATION('',(#108775),#108779); -#108775 = LINE('',#108776,#108777); -#108776 = CARTESIAN_POINT('',(-2.22044604925E-015,-4.85)); -#108777 = VECTOR('',#108778,1.); -#108778 = DIRECTION('',(1.,0.E+000)); -#108779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108780 = PCURVE('',#91979,#108781); -#108781 = DEFINITIONAL_REPRESENTATION('',(#108782),#108786); -#108782 = LINE('',#108783,#108784); -#108783 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#108784 = VECTOR('',#108785,1.); -#108785 = DIRECTION('',(0.E+000,-1.)); -#108786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108787 = ORIENTED_EDGE('',*,*,#108788,.F.); -#108788 = EDGE_CURVE('',#108789,#108766,#108791,.T.); -#108789 = VERTEX_POINT('',#108790); -#108790 = CARTESIAN_POINT('',(-0.740726081328,5.35,-0.208196358798)); -#108791 = SURFACE_CURVE('',#108792,(#108796,#108803),.PCURVE_S1.); -#108792 = LINE('',#108793,#108794); -#108793 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#108794 = VECTOR('',#108795,1.); -#108795 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108796 = PCURVE('',#108741,#108797); -#108797 = DEFINITIONAL_REPRESENTATION('',(#108798),#108802); -#108798 = LINE('',#108799,#108800); -#108799 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108800 = VECTOR('',#108801,1.); -#108801 = DIRECTION('',(-4.440892098501E-016,-1.)); -#108802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108803 = PCURVE('',#108804,#108809); -#108804 = CYLINDRICAL_SURFACE('',#108805,0.208574704164); -#108805 = AXIS2_PLACEMENT_3D('',#108806,#108807,#108808); -#108806 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#108807 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108808 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108809 = DEFINITIONAL_REPRESENTATION('',(#108810),#108813); -#108810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108811,#108812), +#110947 = ADVANCED_FACE('',(#110948),#94485,.T.); +#110948 = FACE_BOUND('',#110949,.T.); +#110949 = EDGE_LOOP('',(#110950,#110971,#110972,#110993)); +#110950 = ORIENTED_EDGE('',*,*,#110951,.F.); +#110951 = EDGE_CURVE('',#110759,#94442,#110952,.T.); +#110952 = SURFACE_CURVE('',#110953,(#110957,#110964),.PCURVE_S1.); +#110953 = LINE('',#110954,#110955); +#110954 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.65)); +#110955 = VECTOR('',#110956,1.); +#110956 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#110957 = PCURVE('',#94485,#110958); +#110958 = DEFINITIONAL_REPRESENTATION('',(#110959),#110963); +#110959 = LINE('',#110960,#110961); +#110960 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#110961 = VECTOR('',#110962,1.); +#110962 = DIRECTION('',(-1.,2.995851623787E-063)); +#110963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110964 = PCURVE('',#94457,#110965); +#110965 = DEFINITIONAL_REPRESENTATION('',(#110966),#110970); +#110966 = LINE('',#110967,#110968); +#110967 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110968 = VECTOR('',#110969,1.); +#110969 = DIRECTION('',(-3.563627120235E-016,1.)); +#110970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110971 = ORIENTED_EDGE('',*,*,#110781,.T.); +#110972 = ORIENTED_EDGE('',*,*,#110973,.T.); +#110973 = EDGE_CURVE('',#110782,#94470,#110974,.T.); +#110974 = SURFACE_CURVE('',#110975,(#110979,#110986),.PCURVE_S1.); +#110975 = LINE('',#110976,#110977); +#110976 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.65)); +#110977 = VECTOR('',#110978,1.); +#110978 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#110979 = PCURVE('',#94485,#110980); +#110980 = DEFINITIONAL_REPRESENTATION('',(#110981),#110985); +#110981 = LINE('',#110982,#110983); +#110982 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110983 = VECTOR('',#110984,1.); +#110984 = DIRECTION('',(-1.,2.995851623787E-063)); +#110985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110986 = PCURVE('',#94513,#110987); +#110987 = DEFINITIONAL_REPRESENTATION('',(#110988),#110992); +#110988 = LINE('',#110989,#110990); +#110989 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#110990 = VECTOR('',#110991,1.); +#110991 = DIRECTION('',(3.563627120235E-016,1.)); +#110992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#110993 = ORIENTED_EDGE('',*,*,#94469,.F.); +#110994 = ADVANCED_FACE('',(#110995),#94457,.T.); +#110995 = FACE_BOUND('',#110996,.T.); +#110996 = EDGE_LOOP('',(#110997,#111018,#111019,#111020,#111021,#111022, + #111043,#111044,#111045,#111046,#111047,#111048)); +#110997 = ORIENTED_EDGE('',*,*,#110998,.F.); +#110998 = EDGE_CURVE('',#110856,#94440,#110999,.T.); +#110999 = SURFACE_CURVE('',#111000,(#111004,#111011),.PCURVE_S1.); +#111000 = LINE('',#111001,#111002); +#111001 = CARTESIAN_POINT('',(-0.527847992439,1.15,0.75)); +#111002 = VECTOR('',#111003,1.); +#111003 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111004 = PCURVE('',#94457,#111005); +#111005 = DEFINITIONAL_REPRESENTATION('',(#111006),#111010); +#111006 = LINE('',#111007,#111008); +#111007 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#111008 = VECTOR('',#111009,1.); +#111009 = DIRECTION('',(-3.563627120235E-016,1.)); +#111010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111011 = PCURVE('',#94539,#111012); +#111012 = DEFINITIONAL_REPRESENTATION('',(#111013),#111017); +#111013 = LINE('',#111014,#111015); +#111014 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#111015 = VECTOR('',#111016,1.); +#111016 = DIRECTION('',(1.,2.995851623787E-063)); +#111017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111018 = ORIENTED_EDGE('',*,*,#110855,.T.); +#111019 = ORIENTED_EDGE('',*,*,#110658,.T.); +#111020 = ORIENTED_EDGE('',*,*,#110578,.T.); +#111021 = ORIENTED_EDGE('',*,*,#110375,.T.); +#111022 = ORIENTED_EDGE('',*,*,#111023,.F.); +#111023 = EDGE_CURVE('',#110239,#110346,#111024,.T.); +#111024 = SURFACE_CURVE('',#111025,(#111029,#111036),.PCURVE_S1.); +#111025 = LINE('',#111026,#111027); +#111026 = CARTESIAN_POINT('',(-1.,1.15,1.159810404338E-002)); +#111027 = VECTOR('',#111028,1.); +#111028 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#111029 = PCURVE('',#94457,#111030); +#111030 = DEFINITIONAL_REPRESENTATION('',(#111031),#111035); +#111031 = LINE('',#111032,#111033); +#111032 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#111033 = VECTOR('',#111034,1.); +#111034 = DIRECTION('',(-1.,-2.101748079665E-016)); +#111035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111036 = PCURVE('',#110259,#111037); +#111037 = DEFINITIONAL_REPRESENTATION('',(#111038),#111042); +#111038 = LINE('',#111039,#111040); +#111039 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#111040 = VECTOR('',#111041,1.); +#111041 = DIRECTION('',(-1.194699204908E-017,1.)); +#111042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111043 = ORIENTED_EDGE('',*,*,#110321,.F.); +#111044 = ORIENTED_EDGE('',*,*,#110449,.F.); +#111045 = ORIENTED_EDGE('',*,*,#110711,.F.); +#111046 = ORIENTED_EDGE('',*,*,#110758,.F.); +#111047 = ORIENTED_EDGE('',*,*,#110951,.T.); +#111048 = ORIENTED_EDGE('',*,*,#94439,.F.); +#111049 = ADVANCED_FACE('',(#111050),#94539,.T.); +#111050 = FACE_BOUND('',#111051,.T.); +#111051 = EDGE_LOOP('',(#111052,#111073,#111074,#111075)); +#111052 = ORIENTED_EDGE('',*,*,#111053,.F.); +#111053 = EDGE_CURVE('',#110879,#94498,#111054,.T.); +#111054 = SURFACE_CURVE('',#111055,(#111059,#111066),.PCURVE_S1.); +#111055 = LINE('',#111056,#111057); +#111056 = CARTESIAN_POINT('',(-0.527847992439,1.35,0.75)); +#111057 = VECTOR('',#111058,1.); +#111058 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111059 = PCURVE('',#94539,#111060); +#111060 = DEFINITIONAL_REPRESENTATION('',(#111061),#111065); +#111061 = LINE('',#111062,#111063); +#111062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111063 = VECTOR('',#111064,1.); +#111064 = DIRECTION('',(1.,2.995851623787E-063)); +#111065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111066 = PCURVE('',#94513,#111067); +#111067 = DEFINITIONAL_REPRESENTATION('',(#111068),#111072); +#111068 = LINE('',#111069,#111070); +#111069 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#111070 = VECTOR('',#111071,1.); +#111071 = DIRECTION('',(3.563627120235E-016,1.)); +#111072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111073 = ORIENTED_EDGE('',*,*,#110878,.T.); +#111074 = ORIENTED_EDGE('',*,*,#110998,.T.); +#111075 = ORIENTED_EDGE('',*,*,#94525,.F.); +#111076 = ADVANCED_FACE('',(#111077),#94513,.T.); +#111077 = FACE_BOUND('',#111078,.T.); +#111078 = EDGE_LOOP('',(#111079,#111080,#111081,#111082,#111083,#111084, + #111105,#111106,#111107,#111108,#111109,#111110)); +#111079 = ORIENTED_EDGE('',*,*,#110973,.F.); +#111080 = ORIENTED_EDGE('',*,*,#110826,.T.); +#111081 = ORIENTED_EDGE('',*,*,#110733,.T.); +#111082 = ORIENTED_EDGE('',*,*,#110477,.T.); +#111083 = ORIENTED_EDGE('',*,*,#110271,.T.); +#111084 = ORIENTED_EDGE('',*,*,#111085,.F.); +#111085 = EDGE_CURVE('',#110348,#110237,#111086,.T.); +#111086 = SURFACE_CURVE('',#111087,(#111091,#111098),.PCURVE_S1.); +#111087 = LINE('',#111088,#111089); +#111088 = CARTESIAN_POINT('',(-1.,1.35,1.159810404338E-002)); +#111089 = VECTOR('',#111090,1.); +#111090 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#111091 = PCURVE('',#94513,#111092); +#111092 = DEFINITIONAL_REPRESENTATION('',(#111093),#111097); +#111093 = LINE('',#111094,#111095); +#111094 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#111095 = VECTOR('',#111096,1.); +#111096 = DIRECTION('',(-1.,2.101748079665E-016)); +#111097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111098 = PCURVE('',#110259,#111099); +#111099 = DEFINITIONAL_REPRESENTATION('',(#111100),#111104); +#111100 = LINE('',#111101,#111102); +#111101 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#111102 = VECTOR('',#111103,1.); +#111103 = DIRECTION('',(1.194699204908E-017,-1.)); +#111104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111105 = ORIENTED_EDGE('',*,*,#110425,.F.); +#111106 = ORIENTED_EDGE('',*,*,#110528,.F.); +#111107 = ORIENTED_EDGE('',*,*,#110636,.F.); +#111108 = ORIENTED_EDGE('',*,*,#110923,.F.); +#111109 = ORIENTED_EDGE('',*,*,#111053,.T.); +#111110 = ORIENTED_EDGE('',*,*,#94497,.F.); +#111111 = ADVANCED_FACE('',(#111112),#110259,.T.); +#111112 = FACE_BOUND('',#111113,.T.); +#111113 = EDGE_LOOP('',(#111114,#111115,#111116,#111117)); +#111114 = ORIENTED_EDGE('',*,*,#111023,.T.); +#111115 = ORIENTED_EDGE('',*,*,#110345,.T.); +#111116 = ORIENTED_EDGE('',*,*,#111085,.T.); +#111117 = ORIENTED_EDGE('',*,*,#110236,.T.); +#111118 = ADVANCED_FACE('',(#111119),#111133,.F.); +#111119 = FACE_BOUND('',#111120,.T.); +#111120 = EDGE_LOOP('',(#111121,#111156,#111179,#111206)); +#111121 = ORIENTED_EDGE('',*,*,#111122,.F.); +#111122 = EDGE_CURVE('',#111123,#111125,#111127,.T.); +#111123 = VERTEX_POINT('',#111124); +#111124 = CARTESIAN_POINT('',(-1.,5.15,-0.208196358798)); +#111125 = VERTEX_POINT('',#111126); +#111126 = CARTESIAN_POINT('',(-1.,5.35,-0.208196358798)); +#111127 = SURFACE_CURVE('',#111128,(#111132,#111144),.PCURVE_S1.); +#111128 = LINE('',#111129,#111130); +#111129 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#111130 = VECTOR('',#111131,1.); +#111131 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111132 = PCURVE('',#111133,#111138); +#111133 = PLANE('',#111134); +#111134 = AXIS2_PLACEMENT_3D('',#111135,#111136,#111137); +#111135 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#111136 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#111137 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#111138 = DEFINITIONAL_REPRESENTATION('',(#111139),#111143); +#111139 = LINE('',#111140,#111141); +#111140 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#111141 = VECTOR('',#111142,1.); +#111142 = DIRECTION('',(4.440892098501E-016,1.)); +#111143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111144 = PCURVE('',#111145,#111150); +#111145 = PLANE('',#111146); +#111146 = AXIS2_PLACEMENT_3D('',#111147,#111148,#111149); +#111147 = CARTESIAN_POINT('',(-1.,5.25,-0.258196742327)); +#111148 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#111149 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111150 = DEFINITIONAL_REPRESENTATION('',(#111151),#111155); +#111151 = LINE('',#111152,#111153); +#111152 = CARTESIAN_POINT('',(-4.75,5.000038352949E-002)); +#111153 = VECTOR('',#111154,1.); +#111154 = DIRECTION('',(-1.,0.E+000)); +#111155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111156 = ORIENTED_EDGE('',*,*,#111157,.F.); +#111157 = EDGE_CURVE('',#111158,#111123,#111160,.T.); +#111158 = VERTEX_POINT('',#111159); +#111159 = CARTESIAN_POINT('',(-0.740726081328,5.15,-0.208196358798)); +#111160 = SURFACE_CURVE('',#111161,(#111165,#111172),.PCURVE_S1.); +#111161 = LINE('',#111162,#111163); +#111162 = CARTESIAN_POINT('',(-0.740726081328,5.15,-0.208196358798)); +#111163 = VECTOR('',#111164,1.); +#111164 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#111165 = PCURVE('',#111133,#111166); +#111166 = DEFINITIONAL_REPRESENTATION('',(#111167),#111171); +#111167 = LINE('',#111168,#111169); +#111168 = CARTESIAN_POINT('',(-2.22044604925E-015,-4.85)); +#111169 = VECTOR('',#111170,1.); +#111170 = DIRECTION('',(1.,0.E+000)); +#111171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111172 = PCURVE('',#94371,#111173); +#111173 = DEFINITIONAL_REPRESENTATION('',(#111174),#111178); +#111174 = LINE('',#111175,#111176); +#111175 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#111176 = VECTOR('',#111177,1.); +#111177 = DIRECTION('',(0.E+000,-1.)); +#111178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111179 = ORIENTED_EDGE('',*,*,#111180,.F.); +#111180 = EDGE_CURVE('',#111181,#111158,#111183,.T.); +#111181 = VERTEX_POINT('',#111182); +#111182 = CARTESIAN_POINT('',(-0.740726081328,5.35,-0.208196358798)); +#111183 = SURFACE_CURVE('',#111184,(#111188,#111195),.PCURVE_S1.); +#111184 = LINE('',#111185,#111186); +#111185 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#111186 = VECTOR('',#111187,1.); +#111187 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111188 = PCURVE('',#111133,#111189); +#111189 = DEFINITIONAL_REPRESENTATION('',(#111190),#111194); +#111190 = LINE('',#111191,#111192); +#111191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111192 = VECTOR('',#111193,1.); +#111193 = DIRECTION('',(-4.440892098501E-016,-1.)); +#111194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111195 = PCURVE('',#111196,#111201); +#111196 = CYLINDRICAL_SURFACE('',#111197,0.208574704164); +#111197 = AXIS2_PLACEMENT_3D('',#111198,#111199,#111200); +#111198 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#111199 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111200 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111201 = DEFINITIONAL_REPRESENTATION('',(#111202),#111205); +#111202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111203,#111204), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#108811 = CARTESIAN_POINT('',(4.772630242227,-4.65)); -#108812 = CARTESIAN_POINT('',(4.772630242227,-4.85)); -#108813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108814 = ORIENTED_EDGE('',*,*,#108815,.T.); -#108815 = EDGE_CURVE('',#108789,#108733,#108816,.T.); -#108816 = SURFACE_CURVE('',#108817,(#108821,#108828),.PCURVE_S1.); -#108817 = LINE('',#108818,#108819); -#108818 = CARTESIAN_POINT('',(-0.740726081328,5.35,-0.208196358798)); -#108819 = VECTOR('',#108820,1.); -#108820 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108821 = PCURVE('',#108741,#108822); -#108822 = DEFINITIONAL_REPRESENTATION('',(#108823),#108827); -#108823 = LINE('',#108824,#108825); -#108824 = CARTESIAN_POINT('',(-2.109423746788E-015,-4.65)); -#108825 = VECTOR('',#108826,1.); -#108826 = DIRECTION('',(1.,0.E+000)); -#108827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108828 = PCURVE('',#92033,#108829); -#108829 = DEFINITIONAL_REPRESENTATION('',(#108830),#108834); -#108830 = LINE('',#108831,#108832); -#108831 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#108832 = VECTOR('',#108833,1.); -#108833 = DIRECTION('',(0.E+000,-1.)); -#108834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108835 = ADVANCED_FACE('',(#108836),#108850,.F.); -#108836 = FACE_BOUND('',#108837,.T.); -#108837 = EDGE_LOOP('',(#108838,#108868,#108891,#108918)); -#108838 = ORIENTED_EDGE('',*,*,#108839,.F.); -#108839 = EDGE_CURVE('',#108840,#108842,#108844,.T.); -#108840 = VERTEX_POINT('',#108841); -#108841 = CARTESIAN_POINT('',(-1.,5.35,-0.308197125857)); -#108842 = VERTEX_POINT('',#108843); -#108843 = CARTESIAN_POINT('',(-1.,5.15,-0.308197125857)); -#108844 = SURFACE_CURVE('',#108845,(#108849,#108861),.PCURVE_S1.); -#108845 = LINE('',#108846,#108847); -#108846 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#108847 = VECTOR('',#108848,1.); -#108848 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#108849 = PCURVE('',#108850,#108855); -#108850 = PLANE('',#108851); -#108851 = AXIS2_PLACEMENT_3D('',#108852,#108853,#108854); -#108852 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#108853 = DIRECTION('',(0.E+000,0.E+000,1.)); -#108854 = DIRECTION('',(1.,0.E+000,0.E+000)); -#108855 = DEFINITIONAL_REPRESENTATION('',(#108856),#108860); -#108856 = LINE('',#108857,#108858); -#108857 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#108858 = VECTOR('',#108859,1.); -#108859 = DIRECTION('',(4.440892098501E-016,-1.)); -#108860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108861 = PCURVE('',#108753,#108862); -#108862 = DEFINITIONAL_REPRESENTATION('',(#108863),#108867); -#108863 = LINE('',#108864,#108865); -#108864 = CARTESIAN_POINT('',(-4.75,-5.000038352949E-002)); -#108865 = VECTOR('',#108866,1.); -#108866 = DIRECTION('',(1.,0.E+000)); -#108867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108868 = ORIENTED_EDGE('',*,*,#108869,.F.); -#108869 = EDGE_CURVE('',#108870,#108840,#108872,.T.); -#108870 = VERTEX_POINT('',#108871); -#108871 = CARTESIAN_POINT('',(-0.74341632541,5.35,-0.308197125857)); -#108872 = SURFACE_CURVE('',#108873,(#108877,#108884),.PCURVE_S1.); -#108873 = LINE('',#108874,#108875); -#108874 = CARTESIAN_POINT('',(-0.74341632541,5.35,-0.308197125857)); -#108875 = VECTOR('',#108876,1.); -#108876 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108877 = PCURVE('',#108850,#108878); -#108878 = DEFINITIONAL_REPRESENTATION('',(#108879),#108883); -#108879 = LINE('',#108880,#108881); -#108880 = CARTESIAN_POINT('',(2.109423746788E-015,-4.65)); -#108881 = VECTOR('',#108882,1.); -#108882 = DIRECTION('',(-1.,0.E+000)); -#108883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108884 = PCURVE('',#92033,#108885); -#108885 = DEFINITIONAL_REPRESENTATION('',(#108886),#108890); -#108886 = LINE('',#108887,#108888); -#108887 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#108888 = VECTOR('',#108889,1.); -#108889 = DIRECTION('',(0.E+000,-1.)); -#108890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108891 = ORIENTED_EDGE('',*,*,#108892,.F.); -#108892 = EDGE_CURVE('',#108893,#108870,#108895,.T.); -#108893 = VERTEX_POINT('',#108894); -#108894 = CARTESIAN_POINT('',(-0.74341632541,5.15,-0.308197125857)); -#108895 = SURFACE_CURVE('',#108896,(#108900,#108907),.PCURVE_S1.); -#108896 = LINE('',#108897,#108898); -#108897 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#108898 = VECTOR('',#108899,1.); -#108899 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108900 = PCURVE('',#108850,#108901); -#108901 = DEFINITIONAL_REPRESENTATION('',(#108902),#108906); -#108902 = LINE('',#108903,#108904); -#108903 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#108904 = VECTOR('',#108905,1.); -#108905 = DIRECTION('',(-4.440892098501E-016,1.)); -#108906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108907 = PCURVE('',#108908,#108913); -#108908 = CYLINDRICAL_SURFACE('',#108909,0.308574064194); -#108909 = AXIS2_PLACEMENT_3D('',#108910,#108911,#108912); -#108910 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#108911 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108912 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108913 = DEFINITIONAL_REPRESENTATION('',(#108914),#108917); -#108914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108915,#108916), +#111203 = CARTESIAN_POINT('',(4.772630242227,-4.65)); +#111204 = CARTESIAN_POINT('',(4.772630242227,-4.85)); +#111205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111206 = ORIENTED_EDGE('',*,*,#111207,.T.); +#111207 = EDGE_CURVE('',#111181,#111125,#111208,.T.); +#111208 = SURFACE_CURVE('',#111209,(#111213,#111220),.PCURVE_S1.); +#111209 = LINE('',#111210,#111211); +#111210 = CARTESIAN_POINT('',(-0.740726081328,5.35,-0.208196358798)); +#111211 = VECTOR('',#111212,1.); +#111212 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#111213 = PCURVE('',#111133,#111214); +#111214 = DEFINITIONAL_REPRESENTATION('',(#111215),#111219); +#111215 = LINE('',#111216,#111217); +#111216 = CARTESIAN_POINT('',(-2.109423746788E-015,-4.65)); +#111217 = VECTOR('',#111218,1.); +#111218 = DIRECTION('',(1.,0.E+000)); +#111219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111220 = PCURVE('',#94425,#111221); +#111221 = DEFINITIONAL_REPRESENTATION('',(#111222),#111226); +#111222 = LINE('',#111223,#111224); +#111223 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#111224 = VECTOR('',#111225,1.); +#111225 = DIRECTION('',(0.E+000,-1.)); +#111226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111227 = ADVANCED_FACE('',(#111228),#111242,.F.); +#111228 = FACE_BOUND('',#111229,.T.); +#111229 = EDGE_LOOP('',(#111230,#111260,#111283,#111310)); +#111230 = ORIENTED_EDGE('',*,*,#111231,.F.); +#111231 = EDGE_CURVE('',#111232,#111234,#111236,.T.); +#111232 = VERTEX_POINT('',#111233); +#111233 = CARTESIAN_POINT('',(-1.,5.35,-0.308197125857)); +#111234 = VERTEX_POINT('',#111235); +#111235 = CARTESIAN_POINT('',(-1.,5.15,-0.308197125857)); +#111236 = SURFACE_CURVE('',#111237,(#111241,#111253),.PCURVE_S1.); +#111237 = LINE('',#111238,#111239); +#111238 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#111239 = VECTOR('',#111240,1.); +#111240 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111241 = PCURVE('',#111242,#111247); +#111242 = PLANE('',#111243); +#111243 = AXIS2_PLACEMENT_3D('',#111244,#111245,#111246); +#111244 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#111245 = DIRECTION('',(0.E+000,0.E+000,1.)); +#111246 = DIRECTION('',(1.,0.E+000,0.E+000)); +#111247 = DEFINITIONAL_REPRESENTATION('',(#111248),#111252); +#111248 = LINE('',#111249,#111250); +#111249 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#111250 = VECTOR('',#111251,1.); +#111251 = DIRECTION('',(4.440892098501E-016,-1.)); +#111252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111253 = PCURVE('',#111145,#111254); +#111254 = DEFINITIONAL_REPRESENTATION('',(#111255),#111259); +#111255 = LINE('',#111256,#111257); +#111256 = CARTESIAN_POINT('',(-4.75,-5.000038352949E-002)); +#111257 = VECTOR('',#111258,1.); +#111258 = DIRECTION('',(1.,0.E+000)); +#111259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111260 = ORIENTED_EDGE('',*,*,#111261,.F.); +#111261 = EDGE_CURVE('',#111262,#111232,#111264,.T.); +#111262 = VERTEX_POINT('',#111263); +#111263 = CARTESIAN_POINT('',(-0.74341632541,5.35,-0.308197125857)); +#111264 = SURFACE_CURVE('',#111265,(#111269,#111276),.PCURVE_S1.); +#111265 = LINE('',#111266,#111267); +#111266 = CARTESIAN_POINT('',(-0.74341632541,5.35,-0.308197125857)); +#111267 = VECTOR('',#111268,1.); +#111268 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#111269 = PCURVE('',#111242,#111270); +#111270 = DEFINITIONAL_REPRESENTATION('',(#111271),#111275); +#111271 = LINE('',#111272,#111273); +#111272 = CARTESIAN_POINT('',(2.109423746788E-015,-4.65)); +#111273 = VECTOR('',#111274,1.); +#111274 = DIRECTION('',(-1.,0.E+000)); +#111275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111276 = PCURVE('',#94425,#111277); +#111277 = DEFINITIONAL_REPRESENTATION('',(#111278),#111282); +#111278 = LINE('',#111279,#111280); +#111279 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#111280 = VECTOR('',#111281,1.); +#111281 = DIRECTION('',(0.E+000,-1.)); +#111282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111283 = ORIENTED_EDGE('',*,*,#111284,.F.); +#111284 = EDGE_CURVE('',#111285,#111262,#111287,.T.); +#111285 = VERTEX_POINT('',#111286); +#111286 = CARTESIAN_POINT('',(-0.74341632541,5.15,-0.308197125857)); +#111287 = SURFACE_CURVE('',#111288,(#111292,#111299),.PCURVE_S1.); +#111288 = LINE('',#111289,#111290); +#111289 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#111290 = VECTOR('',#111291,1.); +#111291 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111292 = PCURVE('',#111242,#111293); +#111293 = DEFINITIONAL_REPRESENTATION('',(#111294),#111298); +#111294 = LINE('',#111295,#111296); +#111295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111296 = VECTOR('',#111297,1.); +#111297 = DIRECTION('',(-4.440892098501E-016,1.)); +#111298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111299 = PCURVE('',#111300,#111305); +#111300 = CYLINDRICAL_SURFACE('',#111301,0.308574064194); +#111301 = AXIS2_PLACEMENT_3D('',#111302,#111303,#111304); +#111302 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#111303 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111304 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111305 = DEFINITIONAL_REPRESENTATION('',(#111306),#111309); +#111306 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111307,#111308), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#108915 = CARTESIAN_POINT('',(4.761821717947,-4.85)); -#108916 = CARTESIAN_POINT('',(4.761821717947,-4.65)); -#108917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108918 = ORIENTED_EDGE('',*,*,#108919,.T.); -#108919 = EDGE_CURVE('',#108893,#108842,#108920,.T.); -#108920 = SURFACE_CURVE('',#108921,(#108925,#108932),.PCURVE_S1.); -#108921 = LINE('',#108922,#108923); -#108922 = CARTESIAN_POINT('',(-0.74341632541,5.15,-0.308197125857)); -#108923 = VECTOR('',#108924,1.); -#108924 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#108925 = PCURVE('',#108850,#108926); -#108926 = DEFINITIONAL_REPRESENTATION('',(#108927),#108931); -#108927 = LINE('',#108928,#108929); -#108928 = CARTESIAN_POINT('',(2.22044604925E-015,-4.85)); -#108929 = VECTOR('',#108930,1.); -#108930 = DIRECTION('',(-1.,0.E+000)); -#108931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108932 = PCURVE('',#91979,#108933); -#108933 = DEFINITIONAL_REPRESENTATION('',(#108934),#108938); -#108934 = LINE('',#108935,#108936); -#108935 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#108936 = VECTOR('',#108937,1.); -#108937 = DIRECTION('',(0.E+000,-1.)); -#108938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108939 = ADVANCED_FACE('',(#108940),#108908,.T.); -#108940 = FACE_BOUND('',#108941,.T.); -#108941 = EDGE_LOOP('',(#108942,#108969,#108970,#108993)); -#108942 = ORIENTED_EDGE('',*,*,#108943,.T.); -#108943 = EDGE_CURVE('',#108944,#108893,#108946,.T.); -#108944 = VERTEX_POINT('',#108945); -#108945 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.E+000)); -#108946 = SURFACE_CURVE('',#108947,(#108952,#108958),.PCURVE_S1.); -#108947 = CIRCLE('',#108948,0.308574064194); -#108948 = AXIS2_PLACEMENT_3D('',#108949,#108950,#108951); -#108949 = CARTESIAN_POINT('',(-0.728168876214,5.15,2.640924866458E-017) - ); -#108950 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108951 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108952 = PCURVE('',#108908,#108953); -#108953 = DEFINITIONAL_REPRESENTATION('',(#108954),#108957); -#108954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108955,#108956), +#111307 = CARTESIAN_POINT('',(4.761821717947,-4.85)); +#111308 = CARTESIAN_POINT('',(4.761821717947,-4.65)); +#111309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111310 = ORIENTED_EDGE('',*,*,#111311,.T.); +#111311 = EDGE_CURVE('',#111285,#111234,#111312,.T.); +#111312 = SURFACE_CURVE('',#111313,(#111317,#111324),.PCURVE_S1.); +#111313 = LINE('',#111314,#111315); +#111314 = CARTESIAN_POINT('',(-0.74341632541,5.15,-0.308197125857)); +#111315 = VECTOR('',#111316,1.); +#111316 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#111317 = PCURVE('',#111242,#111318); +#111318 = DEFINITIONAL_REPRESENTATION('',(#111319),#111323); +#111319 = LINE('',#111320,#111321); +#111320 = CARTESIAN_POINT('',(2.22044604925E-015,-4.85)); +#111321 = VECTOR('',#111322,1.); +#111322 = DIRECTION('',(-1.,0.E+000)); +#111323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111324 = PCURVE('',#94371,#111325); +#111325 = DEFINITIONAL_REPRESENTATION('',(#111326),#111330); +#111326 = LINE('',#111327,#111328); +#111327 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#111328 = VECTOR('',#111329,1.); +#111329 = DIRECTION('',(0.E+000,-1.)); +#111330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111331 = ADVANCED_FACE('',(#111332),#111300,.T.); +#111332 = FACE_BOUND('',#111333,.T.); +#111333 = EDGE_LOOP('',(#111334,#111361,#111362,#111385)); +#111334 = ORIENTED_EDGE('',*,*,#111335,.T.); +#111335 = EDGE_CURVE('',#111336,#111285,#111338,.T.); +#111336 = VERTEX_POINT('',#111337); +#111337 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.E+000)); +#111338 = SURFACE_CURVE('',#111339,(#111344,#111350),.PCURVE_S1.); +#111339 = CIRCLE('',#111340,0.308574064194); +#111340 = AXIS2_PLACEMENT_3D('',#111341,#111342,#111343); +#111341 = CARTESIAN_POINT('',(-0.728168876214,5.15,2.640924866458E-017) + ); +#111342 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111343 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111344 = PCURVE('',#111300,#111345); +#111345 = DEFINITIONAL_REPRESENTATION('',(#111346),#111349); +#111346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111347,#111348), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#108955 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#108956 = CARTESIAN_POINT('',(4.761821717947,-4.85)); -#108957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111347 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#111348 = CARTESIAN_POINT('',(4.761821717947,-4.85)); +#111349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#108958 = PCURVE('',#91979,#108959); -#108959 = DEFINITIONAL_REPRESENTATION('',(#108960),#108968); -#108960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#108961,#108962,#108963, - #108964,#108965,#108966,#108967),.UNSPECIFIED.,.T.,.F.) +#111350 = PCURVE('',#94371,#111351); +#111351 = DEFINITIONAL_REPRESENTATION('',(#111352),#111360); +#111352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111353,#111354,#111355, + #111356,#111357,#111358,#111359),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#108961 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#108962 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#108963 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#108964 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#108965 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#108966 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#108967 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#108968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108969 = ORIENTED_EDGE('',*,*,#108892,.T.); -#108970 = ORIENTED_EDGE('',*,*,#108971,.F.); -#108971 = EDGE_CURVE('',#108972,#108870,#108974,.T.); -#108972 = VERTEX_POINT('',#108973); -#108973 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.E+000)); -#108974 = SURFACE_CURVE('',#108975,(#108980,#108986),.PCURVE_S1.); -#108975 = CIRCLE('',#108976,0.308574064194); -#108976 = AXIS2_PLACEMENT_3D('',#108977,#108978,#108979); -#108977 = CARTESIAN_POINT('',(-0.728168876214,5.35,2.640924866458E-017) - ); -#108978 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#108979 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#108980 = PCURVE('',#108908,#108981); -#108981 = DEFINITIONAL_REPRESENTATION('',(#108982),#108985); -#108982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#108983,#108984), +#111353 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#111354 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#111355 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#111356 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#111357 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#111358 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#111359 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#111360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111361 = ORIENTED_EDGE('',*,*,#111284,.T.); +#111362 = ORIENTED_EDGE('',*,*,#111363,.F.); +#111363 = EDGE_CURVE('',#111364,#111262,#111366,.T.); +#111364 = VERTEX_POINT('',#111365); +#111365 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.E+000)); +#111366 = SURFACE_CURVE('',#111367,(#111372,#111378),.PCURVE_S1.); +#111367 = CIRCLE('',#111368,0.308574064194); +#111368 = AXIS2_PLACEMENT_3D('',#111369,#111370,#111371); +#111369 = CARTESIAN_POINT('',(-0.728168876214,5.35,2.640924866458E-017) + ); +#111370 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111371 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111372 = PCURVE('',#111300,#111373); +#111373 = DEFINITIONAL_REPRESENTATION('',(#111374),#111377); +#111374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111375,#111376), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#108983 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#108984 = CARTESIAN_POINT('',(4.761821717947,-4.65)); -#108985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108986 = PCURVE('',#92033,#108987); -#108987 = DEFINITIONAL_REPRESENTATION('',(#108988),#108992); -#108988 = CIRCLE('',#108989,0.308574064194); -#108989 = AXIS2_PLACEMENT_2D('',#108990,#108991); -#108990 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#108991 = DIRECTION('',(0.E+000,-1.)); -#108992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#108993 = ORIENTED_EDGE('',*,*,#108994,.T.); -#108994 = EDGE_CURVE('',#108972,#108944,#108995,.T.); -#108995 = SURFACE_CURVE('',#108996,(#109000,#109006),.PCURVE_S1.); -#108996 = LINE('',#108997,#108998); -#108997 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#108998 = VECTOR('',#108999,1.); -#108999 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109000 = PCURVE('',#108908,#109001); -#109001 = DEFINITIONAL_REPRESENTATION('',(#109002),#109005); -#109002 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109003,#109004), +#111375 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#111376 = CARTESIAN_POINT('',(4.761821717947,-4.65)); +#111377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111378 = PCURVE('',#94425,#111379); +#111379 = DEFINITIONAL_REPRESENTATION('',(#111380),#111384); +#111380 = CIRCLE('',#111381,0.308574064194); +#111381 = AXIS2_PLACEMENT_2D('',#111382,#111383); +#111382 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#111383 = DIRECTION('',(0.E+000,-1.)); +#111384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111385 = ORIENTED_EDGE('',*,*,#111386,.T.); +#111386 = EDGE_CURVE('',#111364,#111336,#111387,.T.); +#111387 = SURFACE_CURVE('',#111388,(#111392,#111398),.PCURVE_S1.); +#111388 = LINE('',#111389,#111390); +#111389 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#111390 = VECTOR('',#111391,1.); +#111391 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111392 = PCURVE('',#111300,#111393); +#111393 = DEFINITIONAL_REPRESENTATION('',(#111394),#111397); +#111394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111395,#111396), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#109003 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#109004 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#109005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109006 = PCURVE('',#109007,#109012); -#109007 = PLANE('',#109008); -#109008 = AXIS2_PLACEMENT_3D('',#109009,#109010,#109011); -#109009 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#109010 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#109011 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109012 = DEFINITIONAL_REPRESENTATION('',(#109013),#109017); -#109013 = LINE('',#109014,#109015); -#109014 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#109015 = VECTOR('',#109016,1.); -#109016 = DIRECTION('',(-1.,0.E+000)); -#109017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109018 = ADVANCED_FACE('',(#109019),#108804,.F.); -#109019 = FACE_BOUND('',#109020,.F.); -#109020 = EDGE_LOOP('',(#109021,#109044,#109071,#109096)); -#109021 = ORIENTED_EDGE('',*,*,#109022,.F.); -#109022 = EDGE_CURVE('',#109023,#108789,#109025,.T.); -#109023 = VERTEX_POINT('',#109024); -#109024 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.E+000)); -#109025 = SURFACE_CURVE('',#109026,(#109031,#109037),.PCURVE_S1.); -#109026 = CIRCLE('',#109027,0.208574704164); -#109027 = AXIS2_PLACEMENT_3D('',#109028,#109029,#109030); -#109028 = CARTESIAN_POINT('',(-0.728168876214,5.35,2.640924866458E-017) - ); -#109029 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109030 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109031 = PCURVE('',#108804,#109032); -#109032 = DEFINITIONAL_REPRESENTATION('',(#109033),#109036); -#109033 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109034,#109035), +#111395 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#111396 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#111397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111398 = PCURVE('',#111399,#111404); +#111399 = PLANE('',#111400); +#111400 = AXIS2_PLACEMENT_3D('',#111401,#111402,#111403); +#111401 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#111402 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#111403 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111404 = DEFINITIONAL_REPRESENTATION('',(#111405),#111409); +#111405 = LINE('',#111406,#111407); +#111406 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#111407 = VECTOR('',#111408,1.); +#111408 = DIRECTION('',(-1.,0.E+000)); +#111409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111410 = ADVANCED_FACE('',(#111411),#111196,.F.); +#111411 = FACE_BOUND('',#111412,.F.); +#111412 = EDGE_LOOP('',(#111413,#111436,#111463,#111488)); +#111413 = ORIENTED_EDGE('',*,*,#111414,.F.); +#111414 = EDGE_CURVE('',#111415,#111181,#111417,.T.); +#111415 = VERTEX_POINT('',#111416); +#111416 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.E+000)); +#111417 = SURFACE_CURVE('',#111418,(#111423,#111429),.PCURVE_S1.); +#111418 = CIRCLE('',#111419,0.208574704164); +#111419 = AXIS2_PLACEMENT_3D('',#111420,#111421,#111422); +#111420 = CARTESIAN_POINT('',(-0.728168876214,5.35,2.640924866458E-017) + ); +#111421 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111422 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111423 = PCURVE('',#111196,#111424); +#111424 = DEFINITIONAL_REPRESENTATION('',(#111425),#111428); +#111425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111426,#111427), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#109034 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#109035 = CARTESIAN_POINT('',(4.772630242227,-4.65)); -#109036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111426 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#111427 = CARTESIAN_POINT('',(4.772630242227,-4.65)); +#111428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111429 = PCURVE('',#94425,#111430); +#111430 = DEFINITIONAL_REPRESENTATION('',(#111431),#111435); +#111431 = CIRCLE('',#111432,0.208574704164); +#111432 = AXIS2_PLACEMENT_2D('',#111433,#111434); +#111433 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#111434 = DIRECTION('',(0.E+000,-1.)); +#111435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111436 = ORIENTED_EDGE('',*,*,#111437,.F.); +#111437 = EDGE_CURVE('',#111438,#111415,#111440,.T.); +#111438 = VERTEX_POINT('',#111439); +#111439 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.E+000)); +#111440 = SURFACE_CURVE('',#111441,(#111445,#111451),.PCURVE_S1.); +#111441 = LINE('',#111442,#111443); +#111442 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#111443 = VECTOR('',#111444,1.); +#111444 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111445 = PCURVE('',#111196,#111446); +#111446 = DEFINITIONAL_REPRESENTATION('',(#111447),#111450); +#111447 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111448,#111449), + .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); +#111448 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#111449 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#111450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109037 = PCURVE('',#92033,#109038); -#109038 = DEFINITIONAL_REPRESENTATION('',(#109039),#109043); -#109039 = CIRCLE('',#109040,0.208574704164); -#109040 = AXIS2_PLACEMENT_2D('',#109041,#109042); -#109041 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#109042 = DIRECTION('',(0.E+000,-1.)); -#109043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111451 = PCURVE('',#111452,#111457); +#111452 = PLANE('',#111453); +#111453 = AXIS2_PLACEMENT_3D('',#111454,#111455,#111456); +#111454 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#111455 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#111456 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111457 = DEFINITIONAL_REPRESENTATION('',(#111458),#111462); +#111458 = LINE('',#111459,#111460); +#111459 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#111460 = VECTOR('',#111461,1.); +#111461 = DIRECTION('',(-1.,0.E+000)); +#111462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109044 = ORIENTED_EDGE('',*,*,#109045,.F.); -#109045 = EDGE_CURVE('',#109046,#109023,#109048,.T.); -#109046 = VERTEX_POINT('',#109047); -#109047 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.E+000)); -#109048 = SURFACE_CURVE('',#109049,(#109053,#109059),.PCURVE_S1.); -#109049 = LINE('',#109050,#109051); -#109050 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#109051 = VECTOR('',#109052,1.); -#109052 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109053 = PCURVE('',#108804,#109054); -#109054 = DEFINITIONAL_REPRESENTATION('',(#109055),#109058); -#109055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109056,#109057), - .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#109056 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#109057 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#109058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109059 = PCURVE('',#109060,#109065); -#109060 = PLANE('',#109061); -#109061 = AXIS2_PLACEMENT_3D('',#109062,#109063,#109064); -#109062 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#109063 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#109064 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109065 = DEFINITIONAL_REPRESENTATION('',(#109066),#109070); -#109066 = LINE('',#109067,#109068); -#109067 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#109068 = VECTOR('',#109069,1.); -#109069 = DIRECTION('',(-1.,0.E+000)); -#109070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109071 = ORIENTED_EDGE('',*,*,#109072,.T.); -#109072 = EDGE_CURVE('',#109046,#108766,#109073,.T.); -#109073 = SURFACE_CURVE('',#109074,(#109079,#109085),.PCURVE_S1.); -#109074 = CIRCLE('',#109075,0.208574704164); -#109075 = AXIS2_PLACEMENT_3D('',#109076,#109077,#109078); -#109076 = CARTESIAN_POINT('',(-0.728168876214,5.15,2.640924866458E-017) - ); -#109077 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109078 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109079 = PCURVE('',#108804,#109080); -#109080 = DEFINITIONAL_REPRESENTATION('',(#109081),#109084); -#109081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109082,#109083), +#111463 = ORIENTED_EDGE('',*,*,#111464,.T.); +#111464 = EDGE_CURVE('',#111438,#111158,#111465,.T.); +#111465 = SURFACE_CURVE('',#111466,(#111471,#111477),.PCURVE_S1.); +#111466 = CIRCLE('',#111467,0.208574704164); +#111467 = AXIS2_PLACEMENT_3D('',#111468,#111469,#111470); +#111468 = CARTESIAN_POINT('',(-0.728168876214,5.15,2.640924866458E-017) + ); +#111469 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111470 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#111471 = PCURVE('',#111196,#111472); +#111472 = DEFINITIONAL_REPRESENTATION('',(#111473),#111476); +#111473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111474,#111475), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#109082 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#109083 = CARTESIAN_POINT('',(4.772630242227,-4.85)); -#109084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111474 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#111475 = CARTESIAN_POINT('',(4.772630242227,-4.85)); +#111476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109085 = PCURVE('',#91979,#109086); -#109086 = DEFINITIONAL_REPRESENTATION('',(#109087),#109095); -#109087 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109088,#109089,#109090, - #109091,#109092,#109093,#109094),.UNSPECIFIED.,.T.,.F.) +#111477 = PCURVE('',#94371,#111478); +#111478 = DEFINITIONAL_REPRESENTATION('',(#111479),#111487); +#111479 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111480,#111481,#111482, + #111483,#111484,#111485,#111486),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#109088 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#109089 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#109090 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#109091 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#109092 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#109093 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#109094 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#109095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109096 = ORIENTED_EDGE('',*,*,#108788,.F.); -#109097 = ADVANCED_FACE('',(#109098),#109060,.T.); -#109098 = FACE_BOUND('',#109099,.T.); -#109099 = EDGE_LOOP('',(#109100,#109129,#109150,#109151)); -#109100 = ORIENTED_EDGE('',*,*,#109101,.T.); -#109101 = EDGE_CURVE('',#109102,#109104,#109106,.T.); -#109102 = VERTEX_POINT('',#109103); -#109103 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.530776333563)); -#109104 = VERTEX_POINT('',#109105); -#109105 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.530776333563)); -#109106 = SURFACE_CURVE('',#109107,(#109111,#109118),.PCURVE_S1.); -#109107 = LINE('',#109108,#109109); -#109108 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#109109 = VECTOR('',#109110,1.); -#109110 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109111 = PCURVE('',#109060,#109112); -#109112 = DEFINITIONAL_REPRESENTATION('',(#109113),#109117); -#109113 = LINE('',#109114,#109115); -#109114 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109115 = VECTOR('',#109116,1.); -#109116 = DIRECTION('',(-1.,0.E+000)); -#109117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109118 = PCURVE('',#109119,#109124); -#109119 = CYLINDRICAL_SURFACE('',#109120,0.2192697516); -#109120 = AXIS2_PLACEMENT_3D('',#109121,#109122,#109123); -#109121 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#109122 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109123 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109124 = DEFINITIONAL_REPRESENTATION('',(#109125),#109128); -#109125 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109126,#109127), +#111480 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#111481 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#111482 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#111483 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#111484 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#111485 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#111486 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#111487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111488 = ORIENTED_EDGE('',*,*,#111180,.F.); +#111489 = ADVANCED_FACE('',(#111490),#111452,.T.); +#111490 = FACE_BOUND('',#111491,.T.); +#111491 = EDGE_LOOP('',(#111492,#111521,#111542,#111543)); +#111492 = ORIENTED_EDGE('',*,*,#111493,.T.); +#111493 = EDGE_CURVE('',#111494,#111496,#111498,.T.); +#111494 = VERTEX_POINT('',#111495); +#111495 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.530776333563)); +#111496 = VERTEX_POINT('',#111497); +#111497 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.530776333563)); +#111498 = SURFACE_CURVE('',#111499,(#111503,#111510),.PCURVE_S1.); +#111499 = LINE('',#111500,#111501); +#111500 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#111501 = VECTOR('',#111502,1.); +#111502 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111503 = PCURVE('',#111452,#111504); +#111504 = DEFINITIONAL_REPRESENTATION('',(#111505),#111509); +#111505 = LINE('',#111506,#111507); +#111506 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111507 = VECTOR('',#111508,1.); +#111508 = DIRECTION('',(-1.,0.E+000)); +#111509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111510 = PCURVE('',#111511,#111516); +#111511 = CYLINDRICAL_SURFACE('',#111512,0.2192697516); +#111512 = AXIS2_PLACEMENT_3D('',#111513,#111514,#111515); +#111513 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#111514 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111515 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111516 = DEFINITIONAL_REPRESENTATION('',(#111517),#111520); +#111517 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111518,#111519), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#109126 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#109127 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#109128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109129 = ORIENTED_EDGE('',*,*,#109130,.T.); -#109130 = EDGE_CURVE('',#109104,#109023,#109131,.T.); -#109131 = SURFACE_CURVE('',#109132,(#109136,#109143),.PCURVE_S1.); -#109132 = LINE('',#109133,#109134); -#109133 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.530776333563)); -#109134 = VECTOR('',#109135,1.); -#109135 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#109136 = PCURVE('',#109060,#109137); -#109137 = DEFINITIONAL_REPRESENTATION('',(#109138),#109142); -#109138 = LINE('',#109139,#109140); -#109139 = CARTESIAN_POINT('',(4.65,4.535643882845E-033)); -#109140 = VECTOR('',#109141,1.); -#109141 = DIRECTION('',(-4.535643882845E-032,-1.)); -#109142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109143 = PCURVE('',#92033,#109144); -#109144 = DEFINITIONAL_REPRESENTATION('',(#109145),#109149); -#109145 = LINE('',#109146,#109147); -#109146 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#109147 = VECTOR('',#109148,1.); -#109148 = DIRECTION('',(-1.,-1.021336205033E-016)); -#109149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109150 = ORIENTED_EDGE('',*,*,#109045,.F.); -#109151 = ORIENTED_EDGE('',*,*,#109152,.F.); -#109152 = EDGE_CURVE('',#109102,#109046,#109153,.T.); -#109153 = SURFACE_CURVE('',#109154,(#109158,#109165),.PCURVE_S1.); -#109154 = LINE('',#109155,#109156); -#109155 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.530776333563)); -#109156 = VECTOR('',#109157,1.); -#109157 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#109158 = PCURVE('',#109060,#109159); -#109159 = DEFINITIONAL_REPRESENTATION('',(#109160),#109164); -#109160 = LINE('',#109161,#109162); -#109161 = CARTESIAN_POINT('',(4.85,-4.535643882845E-033)); -#109162 = VECTOR('',#109163,1.); -#109163 = DIRECTION('',(-4.535643882845E-032,-1.)); -#109164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109165 = PCURVE('',#91979,#109166); -#109166 = DEFINITIONAL_REPRESENTATION('',(#109167),#109171); -#109167 = LINE('',#109168,#109169); -#109168 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#109169 = VECTOR('',#109170,1.); -#109170 = DIRECTION('',(1.,-1.021336205033E-016)); -#109171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109172 = ADVANCED_FACE('',(#109173),#109007,.T.); -#109173 = FACE_BOUND('',#109174,.T.); -#109174 = EDGE_LOOP('',(#109175,#109204,#109225,#109226)); -#109175 = ORIENTED_EDGE('',*,*,#109176,.T.); -#109176 = EDGE_CURVE('',#109177,#109179,#109181,.T.); -#109177 = VERTEX_POINT('',#109178); -#109178 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.530776333563)); -#109179 = VERTEX_POINT('',#109180); -#109180 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.530776333563)); -#109181 = SURFACE_CURVE('',#109182,(#109186,#109193),.PCURVE_S1.); -#109182 = LINE('',#109183,#109184); -#109183 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#109184 = VECTOR('',#109185,1.); -#109185 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109186 = PCURVE('',#109007,#109187); -#109187 = DEFINITIONAL_REPRESENTATION('',(#109188),#109192); -#109188 = LINE('',#109189,#109190); -#109189 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109190 = VECTOR('',#109191,1.); -#109191 = DIRECTION('',(-1.,0.E+000)); -#109192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109193 = PCURVE('',#109194,#109199); -#109194 = CYLINDRICAL_SURFACE('',#109195,0.119270391569); -#109195 = AXIS2_PLACEMENT_3D('',#109196,#109197,#109198); -#109196 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#109197 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109198 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109199 = DEFINITIONAL_REPRESENTATION('',(#109200),#109203); -#109200 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109201,#109202), +#111518 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#111519 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#111520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111521 = ORIENTED_EDGE('',*,*,#111522,.T.); +#111522 = EDGE_CURVE('',#111496,#111415,#111523,.T.); +#111523 = SURFACE_CURVE('',#111524,(#111528,#111535),.PCURVE_S1.); +#111524 = LINE('',#111525,#111526); +#111525 = CARTESIAN_POINT('',(-0.51959417205,5.35,0.530776333563)); +#111526 = VECTOR('',#111527,1.); +#111527 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#111528 = PCURVE('',#111452,#111529); +#111529 = DEFINITIONAL_REPRESENTATION('',(#111530),#111534); +#111530 = LINE('',#111531,#111532); +#111531 = CARTESIAN_POINT('',(4.65,4.535643882845E-033)); +#111532 = VECTOR('',#111533,1.); +#111533 = DIRECTION('',(-4.535643882845E-032,-1.)); +#111534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111535 = PCURVE('',#94425,#111536); +#111536 = DEFINITIONAL_REPRESENTATION('',(#111537),#111541); +#111537 = LINE('',#111538,#111539); +#111538 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#111539 = VECTOR('',#111540,1.); +#111540 = DIRECTION('',(-1.,-1.021336205033E-016)); +#111541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111542 = ORIENTED_EDGE('',*,*,#111437,.F.); +#111543 = ORIENTED_EDGE('',*,*,#111544,.F.); +#111544 = EDGE_CURVE('',#111494,#111438,#111545,.T.); +#111545 = SURFACE_CURVE('',#111546,(#111550,#111557),.PCURVE_S1.); +#111546 = LINE('',#111547,#111548); +#111547 = CARTESIAN_POINT('',(-0.51959417205,5.15,0.530776333563)); +#111548 = VECTOR('',#111549,1.); +#111549 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#111550 = PCURVE('',#111452,#111551); +#111551 = DEFINITIONAL_REPRESENTATION('',(#111552),#111556); +#111552 = LINE('',#111553,#111554); +#111553 = CARTESIAN_POINT('',(4.85,-4.535643882845E-033)); +#111554 = VECTOR('',#111555,1.); +#111555 = DIRECTION('',(-4.535643882845E-032,-1.)); +#111556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111557 = PCURVE('',#94371,#111558); +#111558 = DEFINITIONAL_REPRESENTATION('',(#111559),#111563); +#111559 = LINE('',#111560,#111561); +#111560 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#111561 = VECTOR('',#111562,1.); +#111562 = DIRECTION('',(1.,-1.021336205033E-016)); +#111563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111564 = ADVANCED_FACE('',(#111565),#111399,.T.); +#111565 = FACE_BOUND('',#111566,.T.); +#111566 = EDGE_LOOP('',(#111567,#111596,#111617,#111618)); +#111567 = ORIENTED_EDGE('',*,*,#111568,.T.); +#111568 = EDGE_CURVE('',#111569,#111571,#111573,.T.); +#111569 = VERTEX_POINT('',#111570); +#111570 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.530776333563)); +#111571 = VERTEX_POINT('',#111572); +#111572 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.530776333563)); +#111573 = SURFACE_CURVE('',#111574,(#111578,#111585),.PCURVE_S1.); +#111574 = LINE('',#111575,#111576); +#111575 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#111576 = VECTOR('',#111577,1.); +#111577 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111578 = PCURVE('',#111399,#111579); +#111579 = DEFINITIONAL_REPRESENTATION('',(#111580),#111584); +#111580 = LINE('',#111581,#111582); +#111581 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111582 = VECTOR('',#111583,1.); +#111583 = DIRECTION('',(-1.,0.E+000)); +#111584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111585 = PCURVE('',#111586,#111591); +#111586 = CYLINDRICAL_SURFACE('',#111587,0.119270391569); +#111587 = AXIS2_PLACEMENT_3D('',#111588,#111589,#111590); +#111588 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#111589 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111590 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111591 = DEFINITIONAL_REPRESENTATION('',(#111592),#111595); +#111592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111593,#111594), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#109201 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#109202 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#109203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109204 = ORIENTED_EDGE('',*,*,#109205,.T.); -#109205 = EDGE_CURVE('',#109179,#108944,#109206,.T.); -#109206 = SURFACE_CURVE('',#109207,(#109211,#109218),.PCURVE_S1.); -#109207 = LINE('',#109208,#109209); -#109208 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.530776333563)); -#109209 = VECTOR('',#109210,1.); -#109210 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#109211 = PCURVE('',#109007,#109212); -#109212 = DEFINITIONAL_REPRESENTATION('',(#109213),#109217); -#109213 = LINE('',#109214,#109215); -#109214 = CARTESIAN_POINT('',(-4.85,1.133910970711E-033)); -#109215 = VECTOR('',#109216,1.); -#109216 = DIRECTION('',(4.535643882845E-032,-1.)); -#109217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109218 = PCURVE('',#91979,#109219); -#109219 = DEFINITIONAL_REPRESENTATION('',(#109220),#109224); -#109220 = LINE('',#109221,#109222); -#109221 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#109222 = VECTOR('',#109223,1.); -#109223 = DIRECTION('',(1.,-1.021336205033E-016)); -#109224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109225 = ORIENTED_EDGE('',*,*,#108994,.F.); -#109226 = ORIENTED_EDGE('',*,*,#109227,.F.); -#109227 = EDGE_CURVE('',#109177,#108972,#109228,.T.); -#109228 = SURFACE_CURVE('',#109229,(#109233,#109240),.PCURVE_S1.); -#109229 = LINE('',#109230,#109231); -#109230 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.530776333563)); -#109231 = VECTOR('',#109232,1.); -#109232 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#109233 = PCURVE('',#109007,#109234); -#109234 = DEFINITIONAL_REPRESENTATION('',(#109235),#109239); -#109235 = LINE('',#109236,#109237); -#109236 = CARTESIAN_POINT('',(-4.65,-1.133910970711E-033)); -#109237 = VECTOR('',#109238,1.); -#109238 = DIRECTION('',(4.535643882845E-032,-1.)); -#109239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109240 = PCURVE('',#92033,#109241); -#109241 = DEFINITIONAL_REPRESENTATION('',(#109242),#109246); -#109242 = LINE('',#109243,#109244); -#109243 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#109244 = VECTOR('',#109245,1.); -#109245 = DIRECTION('',(-1.,-1.021336205033E-016)); -#109246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109247 = ADVANCED_FACE('',(#109248),#109194,.F.); -#109248 = FACE_BOUND('',#109249,.F.); -#109249 = EDGE_LOOP('',(#109250,#109251,#109274,#109319)); -#109250 = ORIENTED_EDGE('',*,*,#109176,.T.); -#109251 = ORIENTED_EDGE('',*,*,#109252,.F.); -#109252 = EDGE_CURVE('',#109253,#109179,#109255,.T.); -#109253 = VERTEX_POINT('',#109254); -#109254 = CARTESIAN_POINT('',(-0.303662633502,5.15,0.65)); -#109255 = SURFACE_CURVE('',#109256,(#109261,#109267),.PCURVE_S1.); -#109256 = CIRCLE('',#109257,0.119270391569); -#109257 = AXIS2_PLACEMENT_3D('',#109258,#109259,#109260); -#109258 = CARTESIAN_POINT('',(-0.30032442045,5.15,0.530776333563)); -#109259 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109260 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109261 = PCURVE('',#109194,#109262); -#109262 = DEFINITIONAL_REPRESENTATION('',(#109263),#109266); -#109263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109264,#109265), +#111593 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#111594 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#111595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111596 = ORIENTED_EDGE('',*,*,#111597,.T.); +#111597 = EDGE_CURVE('',#111571,#111336,#111598,.T.); +#111598 = SURFACE_CURVE('',#111599,(#111603,#111610),.PCURVE_S1.); +#111599 = LINE('',#111600,#111601); +#111600 = CARTESIAN_POINT('',(-0.419594812019,5.15,0.530776333563)); +#111601 = VECTOR('',#111602,1.); +#111602 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#111603 = PCURVE('',#111399,#111604); +#111604 = DEFINITIONAL_REPRESENTATION('',(#111605),#111609); +#111605 = LINE('',#111606,#111607); +#111606 = CARTESIAN_POINT('',(-4.85,1.133910970711E-033)); +#111607 = VECTOR('',#111608,1.); +#111608 = DIRECTION('',(4.535643882845E-032,-1.)); +#111609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111610 = PCURVE('',#94371,#111611); +#111611 = DEFINITIONAL_REPRESENTATION('',(#111612),#111616); +#111612 = LINE('',#111613,#111614); +#111613 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#111614 = VECTOR('',#111615,1.); +#111615 = DIRECTION('',(1.,-1.021336205033E-016)); +#111616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111617 = ORIENTED_EDGE('',*,*,#111386,.F.); +#111618 = ORIENTED_EDGE('',*,*,#111619,.F.); +#111619 = EDGE_CURVE('',#111569,#111364,#111620,.T.); +#111620 = SURFACE_CURVE('',#111621,(#111625,#111632),.PCURVE_S1.); +#111621 = LINE('',#111622,#111623); +#111622 = CARTESIAN_POINT('',(-0.419594812019,5.35,0.530776333563)); +#111623 = VECTOR('',#111624,1.); +#111624 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#111625 = PCURVE('',#111399,#111626); +#111626 = DEFINITIONAL_REPRESENTATION('',(#111627),#111631); +#111627 = LINE('',#111628,#111629); +#111628 = CARTESIAN_POINT('',(-4.65,-1.133910970711E-033)); +#111629 = VECTOR('',#111630,1.); +#111630 = DIRECTION('',(4.535643882845E-032,-1.)); +#111631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111632 = PCURVE('',#94425,#111633); +#111633 = DEFINITIONAL_REPRESENTATION('',(#111634),#111638); +#111634 = LINE('',#111635,#111636); +#111635 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#111636 = VECTOR('',#111637,1.); +#111637 = DIRECTION('',(-1.,-1.021336205033E-016)); +#111638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111639 = ADVANCED_FACE('',(#111640),#111586,.F.); +#111640 = FACE_BOUND('',#111641,.F.); +#111641 = EDGE_LOOP('',(#111642,#111643,#111666,#111711)); +#111642 = ORIENTED_EDGE('',*,*,#111568,.T.); +#111643 = ORIENTED_EDGE('',*,*,#111644,.F.); +#111644 = EDGE_CURVE('',#111645,#111571,#111647,.T.); +#111645 = VERTEX_POINT('',#111646); +#111646 = CARTESIAN_POINT('',(-0.303662633502,5.15,0.65)); +#111647 = SURFACE_CURVE('',#111648,(#111653,#111659),.PCURVE_S1.); +#111648 = CIRCLE('',#111649,0.119270391569); +#111649 = AXIS2_PLACEMENT_3D('',#111650,#111651,#111652); +#111650 = CARTESIAN_POINT('',(-0.30032442045,5.15,0.530776333563)); +#111651 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111652 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111653 = PCURVE('',#111586,#111654); +#111654 = DEFINITIONAL_REPRESENTATION('',(#111655),#111658); +#111655 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111656,#111657), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#109264 = CARTESIAN_POINT('',(1.598788597134,4.85)); -#109265 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#109266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111656 = CARTESIAN_POINT('',(1.598788597134,4.85)); +#111657 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#111658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109267 = PCURVE('',#91979,#109268); -#109268 = DEFINITIONAL_REPRESENTATION('',(#109269),#109273); -#109269 = CIRCLE('',#109270,0.119270391569); -#109270 = AXIS2_PLACEMENT_2D('',#109271,#109272); -#109271 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#109272 = DIRECTION('',(0.E+000,1.)); -#109273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111659 = PCURVE('',#94371,#111660); +#111660 = DEFINITIONAL_REPRESENTATION('',(#111661),#111665); +#111661 = CIRCLE('',#111662,0.119270391569); +#111662 = AXIS2_PLACEMENT_2D('',#111663,#111664); +#111663 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#111664 = DIRECTION('',(0.E+000,1.)); +#111665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109274 = ORIENTED_EDGE('',*,*,#109275,.T.); -#109275 = EDGE_CURVE('',#109253,#109276,#109278,.T.); -#109276 = VERTEX_POINT('',#109277); -#109277 = CARTESIAN_POINT('',(-0.303662633502,5.35,0.65)); -#109278 = SURFACE_CURVE('',#109279,(#109283,#109312),.PCURVE_S1.); -#109279 = LINE('',#109280,#109281); -#109280 = CARTESIAN_POINT('',(-0.303662633502,5.15,0.65)); -#109281 = VECTOR('',#109282,1.); -#109282 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109283 = PCURVE('',#109194,#109284); -#109284 = DEFINITIONAL_REPRESENTATION('',(#109285),#109311); -#109285 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#109286,#109287,#109288, - #109289,#109290,#109291,#109292,#109293,#109294,#109295,#109296, - #109297,#109298,#109299,#109300,#109301,#109302,#109303,#109304, - #109305,#109306,#109307,#109308,#109309,#109310),.UNSPECIFIED.,.F., +#111666 = ORIENTED_EDGE('',*,*,#111667,.T.); +#111667 = EDGE_CURVE('',#111645,#111668,#111670,.T.); +#111668 = VERTEX_POINT('',#111669); +#111669 = CARTESIAN_POINT('',(-0.303662633502,5.35,0.65)); +#111670 = SURFACE_CURVE('',#111671,(#111675,#111704),.PCURVE_S1.); +#111671 = LINE('',#111672,#111673); +#111672 = CARTESIAN_POINT('',(-0.303662633502,5.15,0.65)); +#111673 = VECTOR('',#111674,1.); +#111674 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#111675 = PCURVE('',#111586,#111676); +#111676 = DEFINITIONAL_REPRESENTATION('',(#111677),#111703); +#111677 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111678,#111679,#111680, + #111681,#111682,#111683,#111684,#111685,#111686,#111687,#111688, + #111689,#111690,#111691,#111692,#111693,#111694,#111695,#111696, + #111697,#111698,#111699,#111700,#111701,#111702),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -134619,128 +137621,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#109286 = CARTESIAN_POINT('',(1.598788597134,4.85)); -#109287 = CARTESIAN_POINT('',(1.598788597134,4.84696969697)); -#109288 = CARTESIAN_POINT('',(1.598788597134,4.840909090909)); -#109289 = CARTESIAN_POINT('',(1.598788597134,4.831818181818)); -#109290 = CARTESIAN_POINT('',(1.598788597134,4.822727272727)); -#109291 = CARTESIAN_POINT('',(1.598788597134,4.813636363636)); -#109292 = CARTESIAN_POINT('',(1.598788597134,4.804545454545)); -#109293 = CARTESIAN_POINT('',(1.598788597134,4.795454545455)); -#109294 = CARTESIAN_POINT('',(1.598788597134,4.786363636364)); -#109295 = CARTESIAN_POINT('',(1.598788597134,4.777272727273)); -#109296 = CARTESIAN_POINT('',(1.598788597134,4.768181818182)); -#109297 = CARTESIAN_POINT('',(1.598788597134,4.759090909091)); -#109298 = CARTESIAN_POINT('',(1.598788597134,4.75)); -#109299 = CARTESIAN_POINT('',(1.598788597134,4.740909090909)); -#109300 = CARTESIAN_POINT('',(1.598788597134,4.731818181818)); -#109301 = CARTESIAN_POINT('',(1.598788597134,4.722727272727)); -#109302 = CARTESIAN_POINT('',(1.598788597134,4.713636363636)); -#109303 = CARTESIAN_POINT('',(1.598788597134,4.704545454545)); -#109304 = CARTESIAN_POINT('',(1.598788597134,4.695454545455)); -#109305 = CARTESIAN_POINT('',(1.598788597134,4.686363636364)); -#109306 = CARTESIAN_POINT('',(1.598788597134,4.677272727273)); -#109307 = CARTESIAN_POINT('',(1.598788597134,4.668181818182)); -#109308 = CARTESIAN_POINT('',(1.598788597134,4.659090909091)); -#109309 = CARTESIAN_POINT('',(1.598788597134,4.65303030303)); -#109310 = CARTESIAN_POINT('',(1.598788597134,4.65)); -#109311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109312 = PCURVE('',#92007,#109313); -#109313 = DEFINITIONAL_REPRESENTATION('',(#109314),#109318); -#109314 = LINE('',#109315,#109316); -#109315 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#109316 = VECTOR('',#109317,1.); -#109317 = DIRECTION('',(4.440892098501E-016,1.)); -#109318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109319 = ORIENTED_EDGE('',*,*,#109320,.T.); -#109320 = EDGE_CURVE('',#109276,#109177,#109321,.T.); -#109321 = SURFACE_CURVE('',#109322,(#109327,#109333),.PCURVE_S1.); -#109322 = CIRCLE('',#109323,0.119270391569); -#109323 = AXIS2_PLACEMENT_3D('',#109324,#109325,#109326); -#109324 = CARTESIAN_POINT('',(-0.30032442045,5.35,0.530776333563)); -#109325 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109326 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109327 = PCURVE('',#109194,#109328); -#109328 = DEFINITIONAL_REPRESENTATION('',(#109329),#109332); -#109329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109330,#109331), +#111678 = CARTESIAN_POINT('',(1.598788597134,4.85)); +#111679 = CARTESIAN_POINT('',(1.598788597134,4.84696969697)); +#111680 = CARTESIAN_POINT('',(1.598788597134,4.840909090909)); +#111681 = CARTESIAN_POINT('',(1.598788597134,4.831818181818)); +#111682 = CARTESIAN_POINT('',(1.598788597134,4.822727272727)); +#111683 = CARTESIAN_POINT('',(1.598788597134,4.813636363636)); +#111684 = CARTESIAN_POINT('',(1.598788597134,4.804545454545)); +#111685 = CARTESIAN_POINT('',(1.598788597134,4.795454545455)); +#111686 = CARTESIAN_POINT('',(1.598788597134,4.786363636364)); +#111687 = CARTESIAN_POINT('',(1.598788597134,4.777272727273)); +#111688 = CARTESIAN_POINT('',(1.598788597134,4.768181818182)); +#111689 = CARTESIAN_POINT('',(1.598788597134,4.759090909091)); +#111690 = CARTESIAN_POINT('',(1.598788597134,4.75)); +#111691 = CARTESIAN_POINT('',(1.598788597134,4.740909090909)); +#111692 = CARTESIAN_POINT('',(1.598788597134,4.731818181818)); +#111693 = CARTESIAN_POINT('',(1.598788597134,4.722727272727)); +#111694 = CARTESIAN_POINT('',(1.598788597134,4.713636363636)); +#111695 = CARTESIAN_POINT('',(1.598788597134,4.704545454545)); +#111696 = CARTESIAN_POINT('',(1.598788597134,4.695454545455)); +#111697 = CARTESIAN_POINT('',(1.598788597134,4.686363636364)); +#111698 = CARTESIAN_POINT('',(1.598788597134,4.677272727273)); +#111699 = CARTESIAN_POINT('',(1.598788597134,4.668181818182)); +#111700 = CARTESIAN_POINT('',(1.598788597134,4.659090909091)); +#111701 = CARTESIAN_POINT('',(1.598788597134,4.65303030303)); +#111702 = CARTESIAN_POINT('',(1.598788597134,4.65)); +#111703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111704 = PCURVE('',#94399,#111705); +#111705 = DEFINITIONAL_REPRESENTATION('',(#111706),#111710); +#111706 = LINE('',#111707,#111708); +#111707 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#111708 = VECTOR('',#111709,1.); +#111709 = DIRECTION('',(4.440892098501E-016,1.)); +#111710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111711 = ORIENTED_EDGE('',*,*,#111712,.T.); +#111712 = EDGE_CURVE('',#111668,#111569,#111713,.T.); +#111713 = SURFACE_CURVE('',#111714,(#111719,#111725),.PCURVE_S1.); +#111714 = CIRCLE('',#111715,0.119270391569); +#111715 = AXIS2_PLACEMENT_3D('',#111716,#111717,#111718); +#111716 = CARTESIAN_POINT('',(-0.30032442045,5.35,0.530776333563)); +#111717 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111718 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111719 = PCURVE('',#111586,#111720); +#111720 = DEFINITIONAL_REPRESENTATION('',(#111721),#111724); +#111721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111722,#111723), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#109330 = CARTESIAN_POINT('',(1.598788597134,4.65)); -#109331 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#109332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111722 = CARTESIAN_POINT('',(1.598788597134,4.65)); +#111723 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#111724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109333 = PCURVE('',#92033,#109334); -#109334 = DEFINITIONAL_REPRESENTATION('',(#109335),#109343); -#109335 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109336,#109337,#109338, - #109339,#109340,#109341,#109342),.UNSPECIFIED.,.T.,.F.) +#111725 = PCURVE('',#94425,#111726); +#111726 = DEFINITIONAL_REPRESENTATION('',(#111727),#111735); +#111727 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111728,#111729,#111730, + #111731,#111732,#111733,#111734),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#109336 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#109337 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#109338 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#109339 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#109340 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#109341 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#109342 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#109343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109344 = ADVANCED_FACE('',(#109345),#109119,.T.); -#109345 = FACE_BOUND('',#109346,.T.); -#109346 = EDGE_LOOP('',(#109347,#109348,#109371,#109416)); -#109347 = ORIENTED_EDGE('',*,*,#109101,.F.); -#109348 = ORIENTED_EDGE('',*,*,#109349,.F.); -#109349 = EDGE_CURVE('',#109350,#109102,#109352,.T.); -#109350 = VERTEX_POINT('',#109351); -#109351 = CARTESIAN_POINT('',(-0.304819755875,5.15,0.75)); -#109352 = SURFACE_CURVE('',#109353,(#109358,#109364),.PCURVE_S1.); -#109353 = CIRCLE('',#109354,0.2192697516); -#109354 = AXIS2_PLACEMENT_3D('',#109355,#109356,#109357); -#109355 = CARTESIAN_POINT('',(-0.30032442045,5.15,0.530776333563)); -#109356 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109357 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109358 = PCURVE('',#109119,#109359); -#109359 = DEFINITIONAL_REPRESENTATION('',(#109360),#109363); -#109360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109361,#109362), +#111728 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#111729 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#111730 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#111731 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#111732 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#111733 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#111734 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#111735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111736 = ADVANCED_FACE('',(#111737),#111511,.T.); +#111737 = FACE_BOUND('',#111738,.T.); +#111738 = EDGE_LOOP('',(#111739,#111740,#111763,#111808)); +#111739 = ORIENTED_EDGE('',*,*,#111493,.F.); +#111740 = ORIENTED_EDGE('',*,*,#111741,.F.); +#111741 = EDGE_CURVE('',#111742,#111494,#111744,.T.); +#111742 = VERTEX_POINT('',#111743); +#111743 = CARTESIAN_POINT('',(-0.304819755875,5.15,0.75)); +#111744 = SURFACE_CURVE('',#111745,(#111750,#111756),.PCURVE_S1.); +#111745 = CIRCLE('',#111746,0.2192697516); +#111746 = AXIS2_PLACEMENT_3D('',#111747,#111748,#111749); +#111747 = CARTESIAN_POINT('',(-0.30032442045,5.15,0.530776333563)); +#111748 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111749 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111750 = PCURVE('',#111511,#111751); +#111751 = DEFINITIONAL_REPRESENTATION('',(#111752),#111755); +#111752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111753,#111754), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#109361 = CARTESIAN_POINT('',(1.591299156552,4.85)); -#109362 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#109363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109364 = PCURVE('',#91979,#109365); -#109365 = DEFINITIONAL_REPRESENTATION('',(#109366),#109370); -#109366 = CIRCLE('',#109367,0.2192697516); -#109367 = AXIS2_PLACEMENT_2D('',#109368,#109369); -#109368 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#109369 = DIRECTION('',(0.E+000,1.)); -#109370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109371 = ORIENTED_EDGE('',*,*,#109372,.F.); -#109372 = EDGE_CURVE('',#109373,#109350,#109375,.T.); -#109373 = VERTEX_POINT('',#109374); -#109374 = CARTESIAN_POINT('',(-0.304819755875,5.35,0.75)); -#109375 = SURFACE_CURVE('',#109376,(#109380,#109409),.PCURVE_S1.); -#109376 = LINE('',#109377,#109378); -#109377 = CARTESIAN_POINT('',(-0.304819755875,5.15,0.75)); -#109378 = VECTOR('',#109379,1.); -#109379 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109380 = PCURVE('',#109119,#109381); -#109381 = DEFINITIONAL_REPRESENTATION('',(#109382),#109408); -#109382 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#109383,#109384,#109385, - #109386,#109387,#109388,#109389,#109390,#109391,#109392,#109393, - #109394,#109395,#109396,#109397,#109398,#109399,#109400,#109401, - #109402,#109403,#109404,#109405,#109406,#109407),.UNSPECIFIED.,.F., +#111753 = CARTESIAN_POINT('',(1.591299156552,4.85)); +#111754 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#111755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111756 = PCURVE('',#94371,#111757); +#111757 = DEFINITIONAL_REPRESENTATION('',(#111758),#111762); +#111758 = CIRCLE('',#111759,0.2192697516); +#111759 = AXIS2_PLACEMENT_2D('',#111760,#111761); +#111760 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#111761 = DIRECTION('',(0.E+000,1.)); +#111762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111763 = ORIENTED_EDGE('',*,*,#111764,.F.); +#111764 = EDGE_CURVE('',#111765,#111742,#111767,.T.); +#111765 = VERTEX_POINT('',#111766); +#111766 = CARTESIAN_POINT('',(-0.304819755875,5.35,0.75)); +#111767 = SURFACE_CURVE('',#111768,(#111772,#111801),.PCURVE_S1.); +#111768 = LINE('',#111769,#111770); +#111769 = CARTESIAN_POINT('',(-0.304819755875,5.15,0.75)); +#111770 = VECTOR('',#111771,1.); +#111771 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111772 = PCURVE('',#111511,#111773); +#111773 = DEFINITIONAL_REPRESENTATION('',(#111774),#111800); +#111774 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111775,#111776,#111777, + #111778,#111779,#111780,#111781,#111782,#111783,#111784,#111785, + #111786,#111787,#111788,#111789,#111790,#111791,#111792,#111793, + #111794,#111795,#111796,#111797,#111798,#111799),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -134749,956 +137751,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#109383 = CARTESIAN_POINT('',(1.591299156552,4.65)); -#109384 = CARTESIAN_POINT('',(1.591299156552,4.65303030303)); -#109385 = CARTESIAN_POINT('',(1.591299156552,4.659090909091)); -#109386 = CARTESIAN_POINT('',(1.591299156552,4.668181818182)); -#109387 = CARTESIAN_POINT('',(1.591299156552,4.677272727273)); -#109388 = CARTESIAN_POINT('',(1.591299156552,4.686363636364)); -#109389 = CARTESIAN_POINT('',(1.591299156552,4.695454545455)); -#109390 = CARTESIAN_POINT('',(1.591299156552,4.704545454545)); -#109391 = CARTESIAN_POINT('',(1.591299156552,4.713636363636)); -#109392 = CARTESIAN_POINT('',(1.591299156552,4.722727272727)); -#109393 = CARTESIAN_POINT('',(1.591299156552,4.731818181818)); -#109394 = CARTESIAN_POINT('',(1.591299156552,4.740909090909)); -#109395 = CARTESIAN_POINT('',(1.591299156552,4.75)); -#109396 = CARTESIAN_POINT('',(1.591299156552,4.759090909091)); -#109397 = CARTESIAN_POINT('',(1.591299156552,4.768181818182)); -#109398 = CARTESIAN_POINT('',(1.591299156552,4.777272727273)); -#109399 = CARTESIAN_POINT('',(1.591299156552,4.786363636364)); -#109400 = CARTESIAN_POINT('',(1.591299156552,4.795454545455)); -#109401 = CARTESIAN_POINT('',(1.591299156552,4.804545454545)); -#109402 = CARTESIAN_POINT('',(1.591299156552,4.813636363636)); -#109403 = CARTESIAN_POINT('',(1.591299156552,4.822727272727)); -#109404 = CARTESIAN_POINT('',(1.591299156552,4.831818181818)); -#109405 = CARTESIAN_POINT('',(1.591299156552,4.840909090909)); -#109406 = CARTESIAN_POINT('',(1.591299156552,4.84696969697)); -#109407 = CARTESIAN_POINT('',(1.591299156552,4.85)); -#109408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109409 = PCURVE('',#91951,#109410); -#109410 = DEFINITIONAL_REPRESENTATION('',(#109411),#109415); -#109411 = LINE('',#109412,#109413); -#109412 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#109413 = VECTOR('',#109414,1.); -#109414 = DIRECTION('',(4.440892098501E-016,-1.)); -#109415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109416 = ORIENTED_EDGE('',*,*,#109417,.T.); -#109417 = EDGE_CURVE('',#109373,#109104,#109418,.T.); -#109418 = SURFACE_CURVE('',#109419,(#109424,#109430),.PCURVE_S1.); -#109419 = CIRCLE('',#109420,0.2192697516); -#109420 = AXIS2_PLACEMENT_3D('',#109421,#109422,#109423); -#109421 = CARTESIAN_POINT('',(-0.30032442045,5.35,0.530776333563)); -#109422 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109423 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#109424 = PCURVE('',#109119,#109425); -#109425 = DEFINITIONAL_REPRESENTATION('',(#109426),#109429); -#109426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109427,#109428), +#111775 = CARTESIAN_POINT('',(1.591299156552,4.65)); +#111776 = CARTESIAN_POINT('',(1.591299156552,4.65303030303)); +#111777 = CARTESIAN_POINT('',(1.591299156552,4.659090909091)); +#111778 = CARTESIAN_POINT('',(1.591299156552,4.668181818182)); +#111779 = CARTESIAN_POINT('',(1.591299156552,4.677272727273)); +#111780 = CARTESIAN_POINT('',(1.591299156552,4.686363636364)); +#111781 = CARTESIAN_POINT('',(1.591299156552,4.695454545455)); +#111782 = CARTESIAN_POINT('',(1.591299156552,4.704545454545)); +#111783 = CARTESIAN_POINT('',(1.591299156552,4.713636363636)); +#111784 = CARTESIAN_POINT('',(1.591299156552,4.722727272727)); +#111785 = CARTESIAN_POINT('',(1.591299156552,4.731818181818)); +#111786 = CARTESIAN_POINT('',(1.591299156552,4.740909090909)); +#111787 = CARTESIAN_POINT('',(1.591299156552,4.75)); +#111788 = CARTESIAN_POINT('',(1.591299156552,4.759090909091)); +#111789 = CARTESIAN_POINT('',(1.591299156552,4.768181818182)); +#111790 = CARTESIAN_POINT('',(1.591299156552,4.777272727273)); +#111791 = CARTESIAN_POINT('',(1.591299156552,4.786363636364)); +#111792 = CARTESIAN_POINT('',(1.591299156552,4.795454545455)); +#111793 = CARTESIAN_POINT('',(1.591299156552,4.804545454545)); +#111794 = CARTESIAN_POINT('',(1.591299156552,4.813636363636)); +#111795 = CARTESIAN_POINT('',(1.591299156552,4.822727272727)); +#111796 = CARTESIAN_POINT('',(1.591299156552,4.831818181818)); +#111797 = CARTESIAN_POINT('',(1.591299156552,4.840909090909)); +#111798 = CARTESIAN_POINT('',(1.591299156552,4.84696969697)); +#111799 = CARTESIAN_POINT('',(1.591299156552,4.85)); +#111800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111801 = PCURVE('',#94343,#111802); +#111802 = DEFINITIONAL_REPRESENTATION('',(#111803),#111807); +#111803 = LINE('',#111804,#111805); +#111804 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#111805 = VECTOR('',#111806,1.); +#111806 = DIRECTION('',(4.440892098501E-016,-1.)); +#111807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111808 = ORIENTED_EDGE('',*,*,#111809,.T.); +#111809 = EDGE_CURVE('',#111765,#111496,#111810,.T.); +#111810 = SURFACE_CURVE('',#111811,(#111816,#111822),.PCURVE_S1.); +#111811 = CIRCLE('',#111812,0.2192697516); +#111812 = AXIS2_PLACEMENT_3D('',#111813,#111814,#111815); +#111813 = CARTESIAN_POINT('',(-0.30032442045,5.35,0.530776333563)); +#111814 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#111815 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#111816 = PCURVE('',#111511,#111817); +#111817 = DEFINITIONAL_REPRESENTATION('',(#111818),#111821); +#111818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111819,#111820), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#109427 = CARTESIAN_POINT('',(1.591299156552,4.65)); -#109428 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#109429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111819 = CARTESIAN_POINT('',(1.591299156552,4.65)); +#111820 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#111821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109430 = PCURVE('',#92033,#109431); -#109431 = DEFINITIONAL_REPRESENTATION('',(#109432),#109440); -#109432 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109433,#109434,#109435, - #109436,#109437,#109438,#109439),.UNSPECIFIED.,.T.,.F.) +#111822 = PCURVE('',#94425,#111823); +#111823 = DEFINITIONAL_REPRESENTATION('',(#111824),#111832); +#111824 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111825,#111826,#111827, + #111828,#111829,#111830,#111831),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#109433 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#109434 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#109435 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#109436 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#109437 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#109438 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#109439 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#109440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111825 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#111826 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#111827 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#111828 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#111829 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#111830 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#111831 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#111832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111833 = ADVANCED_FACE('',(#111834),#94371,.T.); +#111834 = FACE_BOUND('',#111835,.T.); +#111835 = EDGE_LOOP('',(#111836,#111857,#111858,#111859,#111860,#111861, + #111882,#111883,#111884,#111885,#111886,#111907)); +#111836 = ORIENTED_EDGE('',*,*,#111837,.F.); +#111837 = EDGE_CURVE('',#111742,#94328,#111838,.T.); +#111838 = SURFACE_CURVE('',#111839,(#111843,#111850),.PCURVE_S1.); +#111839 = LINE('',#111840,#111841); +#111840 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.75)); +#111841 = VECTOR('',#111842,1.); +#111842 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111843 = PCURVE('',#94371,#111844); +#111844 = DEFINITIONAL_REPRESENTATION('',(#111845),#111849); +#111845 = LINE('',#111846,#111847); +#111846 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#111847 = VECTOR('',#111848,1.); +#111848 = DIRECTION('',(-3.563627120235E-016,1.)); +#111849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111850 = PCURVE('',#94343,#111851); +#111851 = DEFINITIONAL_REPRESENTATION('',(#111852),#111856); +#111852 = LINE('',#111853,#111854); +#111853 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111854 = VECTOR('',#111855,1.); +#111855 = DIRECTION('',(1.,-4.804757279354E-063)); +#111856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111857 = ORIENTED_EDGE('',*,*,#111741,.T.); +#111858 = ORIENTED_EDGE('',*,*,#111544,.T.); +#111859 = ORIENTED_EDGE('',*,*,#111464,.T.); +#111860 = ORIENTED_EDGE('',*,*,#111157,.T.); +#111861 = ORIENTED_EDGE('',*,*,#111862,.F.); +#111862 = EDGE_CURVE('',#111234,#111123,#111863,.T.); +#111863 = SURFACE_CURVE('',#111864,(#111868,#111875),.PCURVE_S1.); +#111864 = LINE('',#111865,#111866); +#111865 = CARTESIAN_POINT('',(-1.,5.15,1.159810404338E-002)); +#111866 = VECTOR('',#111867,1.); +#111867 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#111868 = PCURVE('',#94371,#111869); +#111869 = DEFINITIONAL_REPRESENTATION('',(#111870),#111874); +#111870 = LINE('',#111871,#111872); +#111871 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#111872 = VECTOR('',#111873,1.); +#111873 = DIRECTION('',(-1.,-2.101748079665E-016)); +#111874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111875 = PCURVE('',#111145,#111876); +#111876 = DEFINITIONAL_REPRESENTATION('',(#111877),#111881); +#111877 = LINE('',#111878,#111879); +#111878 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#111879 = VECTOR('',#111880,1.); +#111880 = DIRECTION('',(-1.194699204908E-017,1.)); +#111881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111882 = ORIENTED_EDGE('',*,*,#111311,.F.); +#111883 = ORIENTED_EDGE('',*,*,#111335,.F.); +#111884 = ORIENTED_EDGE('',*,*,#111597,.F.); +#111885 = ORIENTED_EDGE('',*,*,#111644,.F.); +#111886 = ORIENTED_EDGE('',*,*,#111887,.T.); +#111887 = EDGE_CURVE('',#111645,#94356,#111888,.T.); +#111888 = SURFACE_CURVE('',#111889,(#111893,#111900),.PCURVE_S1.); +#111889 = LINE('',#111890,#111891); +#111890 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); +#111891 = VECTOR('',#111892,1.); +#111892 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111893 = PCURVE('',#94371,#111894); +#111894 = DEFINITIONAL_REPRESENTATION('',(#111895),#111899); +#111895 = LINE('',#111896,#111897); +#111896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111897 = VECTOR('',#111898,1.); +#111898 = DIRECTION('',(-3.563627120235E-016,1.)); +#111899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111900 = PCURVE('',#94399,#111901); +#111901 = DEFINITIONAL_REPRESENTATION('',(#111902),#111906); +#111902 = LINE('',#111903,#111904); +#111903 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111904 = VECTOR('',#111905,1.); +#111905 = DIRECTION('',(-1.,-4.804757279354E-063)); +#111906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111907 = ORIENTED_EDGE('',*,*,#94355,.F.); +#111908 = ADVANCED_FACE('',(#111909),#94343,.T.); +#111909 = FACE_BOUND('',#111910,.T.); +#111910 = EDGE_LOOP('',(#111911,#111932,#111933,#111934)); +#111911 = ORIENTED_EDGE('',*,*,#111912,.F.); +#111912 = EDGE_CURVE('',#111765,#94326,#111913,.T.); +#111913 = SURFACE_CURVE('',#111914,(#111918,#111925),.PCURVE_S1.); +#111914 = LINE('',#111915,#111916); +#111915 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.75)); +#111916 = VECTOR('',#111917,1.); +#111917 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111918 = PCURVE('',#94343,#111919); +#111919 = DEFINITIONAL_REPRESENTATION('',(#111920),#111924); +#111920 = LINE('',#111921,#111922); +#111921 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#111922 = VECTOR('',#111923,1.); +#111923 = DIRECTION('',(1.,-4.804757279354E-063)); +#111924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111925 = PCURVE('',#94425,#111926); +#111926 = DEFINITIONAL_REPRESENTATION('',(#111927),#111931); +#111927 = LINE('',#111928,#111929); +#111928 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#111929 = VECTOR('',#111930,1.); +#111930 = DIRECTION('',(3.563627120235E-016,1.)); +#111931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111932 = ORIENTED_EDGE('',*,*,#111764,.T.); +#111933 = ORIENTED_EDGE('',*,*,#111837,.T.); +#111934 = ORIENTED_EDGE('',*,*,#94325,.F.); +#111935 = ADVANCED_FACE('',(#111936),#94425,.T.); +#111936 = FACE_BOUND('',#111937,.T.); +#111937 = EDGE_LOOP('',(#111938,#111959,#111960,#111961,#111962,#111963, + #111984,#111985,#111986,#111987,#111988,#111989)); +#111938 = ORIENTED_EDGE('',*,*,#111939,.F.); +#111939 = EDGE_CURVE('',#111668,#94384,#111940,.T.); +#111940 = SURFACE_CURVE('',#111941,(#111945,#111952),.PCURVE_S1.); +#111941 = LINE('',#111942,#111943); +#111942 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.65)); +#111943 = VECTOR('',#111944,1.); +#111944 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#111945 = PCURVE('',#94425,#111946); +#111946 = DEFINITIONAL_REPRESENTATION('',(#111947),#111951); +#111947 = LINE('',#111948,#111949); +#111948 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#111949 = VECTOR('',#111950,1.); +#111950 = DIRECTION('',(3.563627120235E-016,1.)); +#111951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111952 = PCURVE('',#94399,#111953); +#111953 = DEFINITIONAL_REPRESENTATION('',(#111954),#111958); +#111954 = LINE('',#111955,#111956); +#111955 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#111956 = VECTOR('',#111957,1.); +#111957 = DIRECTION('',(-1.,-4.804757279354E-063)); +#111958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111959 = ORIENTED_EDGE('',*,*,#111712,.T.); +#111960 = ORIENTED_EDGE('',*,*,#111619,.T.); +#111961 = ORIENTED_EDGE('',*,*,#111363,.T.); +#111962 = ORIENTED_EDGE('',*,*,#111261,.T.); +#111963 = ORIENTED_EDGE('',*,*,#111964,.F.); +#111964 = EDGE_CURVE('',#111125,#111232,#111965,.T.); +#111965 = SURFACE_CURVE('',#111966,(#111970,#111977),.PCURVE_S1.); +#111966 = LINE('',#111967,#111968); +#111967 = CARTESIAN_POINT('',(-1.,5.35,1.159810404338E-002)); +#111968 = VECTOR('',#111969,1.); +#111969 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#111970 = PCURVE('',#94425,#111971); +#111971 = DEFINITIONAL_REPRESENTATION('',(#111972),#111976); +#111972 = LINE('',#111973,#111974); +#111973 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#111974 = VECTOR('',#111975,1.); +#111975 = DIRECTION('',(-1.,2.101748079665E-016)); +#111976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109441 = ADVANCED_FACE('',(#109442),#91979,.T.); -#109442 = FACE_BOUND('',#109443,.T.); -#109443 = EDGE_LOOP('',(#109444,#109465,#109466,#109467,#109468,#109469, - #109490,#109491,#109492,#109493,#109494,#109515)); -#109444 = ORIENTED_EDGE('',*,*,#109445,.F.); -#109445 = EDGE_CURVE('',#109350,#91936,#109446,.T.); -#109446 = SURFACE_CURVE('',#109447,(#109451,#109458),.PCURVE_S1.); -#109447 = LINE('',#109448,#109449); -#109448 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.75)); -#109449 = VECTOR('',#109450,1.); -#109450 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#109451 = PCURVE('',#91979,#109452); -#109452 = DEFINITIONAL_REPRESENTATION('',(#109453),#109457); -#109453 = LINE('',#109454,#109455); -#109454 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#109455 = VECTOR('',#109456,1.); -#109456 = DIRECTION('',(-3.563627120235E-016,1.)); -#109457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109458 = PCURVE('',#91951,#109459); -#109459 = DEFINITIONAL_REPRESENTATION('',(#109460),#109464); -#109460 = LINE('',#109461,#109462); -#109461 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109462 = VECTOR('',#109463,1.); -#109463 = DIRECTION('',(1.,-4.804757279354E-063)); -#109464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109465 = ORIENTED_EDGE('',*,*,#109349,.T.); -#109466 = ORIENTED_EDGE('',*,*,#109152,.T.); -#109467 = ORIENTED_EDGE('',*,*,#109072,.T.); -#109468 = ORIENTED_EDGE('',*,*,#108765,.T.); -#109469 = ORIENTED_EDGE('',*,*,#109470,.F.); -#109470 = EDGE_CURVE('',#108842,#108731,#109471,.T.); -#109471 = SURFACE_CURVE('',#109472,(#109476,#109483),.PCURVE_S1.); -#109472 = LINE('',#109473,#109474); -#109473 = CARTESIAN_POINT('',(-1.,5.15,1.159810404338E-002)); -#109474 = VECTOR('',#109475,1.); -#109475 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#109476 = PCURVE('',#91979,#109477); -#109477 = DEFINITIONAL_REPRESENTATION('',(#109478),#109482); -#109478 = LINE('',#109479,#109480); -#109479 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#109480 = VECTOR('',#109481,1.); -#109481 = DIRECTION('',(-1.,-2.101748079665E-016)); -#109482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109483 = PCURVE('',#108753,#109484); -#109484 = DEFINITIONAL_REPRESENTATION('',(#109485),#109489); -#109485 = LINE('',#109486,#109487); -#109486 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#109487 = VECTOR('',#109488,1.); -#109488 = DIRECTION('',(-1.194699204908E-017,1.)); -#109489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#111977 = PCURVE('',#111145,#111978); +#111978 = DEFINITIONAL_REPRESENTATION('',(#111979),#111983); +#111979 = LINE('',#111980,#111981); +#111980 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#111981 = VECTOR('',#111982,1.); +#111982 = DIRECTION('',(1.194699204908E-017,-1.)); +#111983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#111984 = ORIENTED_EDGE('',*,*,#111207,.F.); +#111985 = ORIENTED_EDGE('',*,*,#111414,.F.); +#111986 = ORIENTED_EDGE('',*,*,#111522,.F.); +#111987 = ORIENTED_EDGE('',*,*,#111809,.F.); +#111988 = ORIENTED_EDGE('',*,*,#111912,.T.); +#111989 = ORIENTED_EDGE('',*,*,#94411,.F.); +#111990 = ADVANCED_FACE('',(#111991),#94399,.T.); +#111991 = FACE_BOUND('',#111992,.T.); +#111992 = EDGE_LOOP('',(#111993,#111994,#111995,#111996)); +#111993 = ORIENTED_EDGE('',*,*,#111887,.F.); +#111994 = ORIENTED_EDGE('',*,*,#111667,.T.); +#111995 = ORIENTED_EDGE('',*,*,#111939,.T.); +#111996 = ORIENTED_EDGE('',*,*,#94383,.F.); +#111997 = ADVANCED_FACE('',(#111998),#111145,.T.); +#111998 = FACE_BOUND('',#111999,.T.); +#111999 = EDGE_LOOP('',(#112000,#112001,#112002,#112003)); +#112000 = ORIENTED_EDGE('',*,*,#111122,.T.); +#112001 = ORIENTED_EDGE('',*,*,#111964,.T.); +#112002 = ORIENTED_EDGE('',*,*,#111231,.T.); +#112003 = ORIENTED_EDGE('',*,*,#111862,.T.); +#112004 = ADVANCED_FACE('',(#112005),#112019,.F.); +#112005 = FACE_BOUND('',#112006,.T.); +#112006 = EDGE_LOOP('',(#112007,#112042,#112065,#112092)); +#112007 = ORIENTED_EDGE('',*,*,#112008,.F.); +#112008 = EDGE_CURVE('',#112009,#112011,#112013,.T.); +#112009 = VERTEX_POINT('',#112010); +#112010 = CARTESIAN_POINT('',(-1.,1.85,-0.308197125857)); +#112011 = VERTEX_POINT('',#112012); +#112012 = CARTESIAN_POINT('',(-1.,1.65,-0.308197125857)); +#112013 = SURFACE_CURVE('',#112014,(#112018,#112030),.PCURVE_S1.); +#112014 = LINE('',#112015,#112016); +#112015 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#112016 = VECTOR('',#112017,1.); +#112017 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112018 = PCURVE('',#112019,#112024); +#112019 = PLANE('',#112020); +#112020 = AXIS2_PLACEMENT_3D('',#112021,#112022,#112023); +#112021 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#112022 = DIRECTION('',(0.E+000,0.E+000,1.)); +#112023 = DIRECTION('',(1.,0.E+000,0.E+000)); +#112024 = DEFINITIONAL_REPRESENTATION('',(#112025),#112029); +#112025 = LINE('',#112026,#112027); +#112026 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#112027 = VECTOR('',#112028,1.); +#112028 = DIRECTION('',(4.440892098501E-016,-1.)); +#112029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112030 = PCURVE('',#112031,#112036); +#112031 = PLANE('',#112032); +#112032 = AXIS2_PLACEMENT_3D('',#112033,#112034,#112035); +#112033 = CARTESIAN_POINT('',(-1.,1.75,-0.258196742327)); +#112034 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#112035 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112036 = DEFINITIONAL_REPRESENTATION('',(#112037),#112041); +#112037 = LINE('',#112038,#112039); +#112038 = CARTESIAN_POINT('',(-8.25,-5.000038352949E-002)); +#112039 = VECTOR('',#112040,1.); +#112040 = DIRECTION('',(1.,0.E+000)); +#112041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112042 = ORIENTED_EDGE('',*,*,#112043,.F.); +#112043 = EDGE_CURVE('',#112044,#112009,#112046,.T.); +#112044 = VERTEX_POINT('',#112045); +#112045 = CARTESIAN_POINT('',(-0.74341632541,1.85,-0.308197125857)); +#112046 = SURFACE_CURVE('',#112047,(#112051,#112058),.PCURVE_S1.); +#112047 = LINE('',#112048,#112049); +#112048 = CARTESIAN_POINT('',(-0.74341632541,1.85,-0.308197125857)); +#112049 = VECTOR('',#112050,1.); +#112050 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112051 = PCURVE('',#112019,#112052); +#112052 = DEFINITIONAL_REPRESENTATION('',(#112053),#112057); +#112053 = LINE('',#112054,#112055); +#112054 = CARTESIAN_POINT('',(3.552713678801E-015,-8.15)); +#112055 = VECTOR('',#112056,1.); +#112056 = DIRECTION('',(-1.,0.E+000)); +#112057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112058 = PCURVE('',#94285,#112059); +#112059 = DEFINITIONAL_REPRESENTATION('',(#112060),#112064); +#112060 = LINE('',#112061,#112062); +#112061 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#112062 = VECTOR('',#112063,1.); +#112063 = DIRECTION('',(0.E+000,-1.)); +#112064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112065 = ORIENTED_EDGE('',*,*,#112066,.F.); +#112066 = EDGE_CURVE('',#112067,#112044,#112069,.T.); +#112067 = VERTEX_POINT('',#112068); +#112068 = CARTESIAN_POINT('',(-0.74341632541,1.65,-0.308197125857)); +#112069 = SURFACE_CURVE('',#112070,(#112074,#112081),.PCURVE_S1.); +#112070 = LINE('',#112071,#112072); +#112071 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#112072 = VECTOR('',#112073,1.); +#112073 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112074 = PCURVE('',#112019,#112075); +#112075 = DEFINITIONAL_REPRESENTATION('',(#112076),#112080); +#112076 = LINE('',#112077,#112078); +#112077 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112078 = VECTOR('',#112079,1.); +#112079 = DIRECTION('',(-4.440892098501E-016,1.)); +#112080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112081 = PCURVE('',#112082,#112087); +#112082 = CYLINDRICAL_SURFACE('',#112083,0.308574064194); +#112083 = AXIS2_PLACEMENT_3D('',#112084,#112085,#112086); +#112084 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#112085 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112086 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112087 = DEFINITIONAL_REPRESENTATION('',(#112088),#112091); +#112088 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112089,#112090), + .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); +#112089 = CARTESIAN_POINT('',(4.761821717947,-8.35)); +#112090 = CARTESIAN_POINT('',(4.761821717947,-8.15)); +#112091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109490 = ORIENTED_EDGE('',*,*,#108919,.F.); -#109491 = ORIENTED_EDGE('',*,*,#108943,.F.); -#109492 = ORIENTED_EDGE('',*,*,#109205,.F.); -#109493 = ORIENTED_EDGE('',*,*,#109252,.F.); -#109494 = ORIENTED_EDGE('',*,*,#109495,.T.); -#109495 = EDGE_CURVE('',#109253,#91964,#109496,.T.); -#109496 = SURFACE_CURVE('',#109497,(#109501,#109508),.PCURVE_S1.); -#109497 = LINE('',#109498,#109499); -#109498 = CARTESIAN_POINT('',(-0.527847992439,5.15,0.65)); -#109499 = VECTOR('',#109500,1.); -#109500 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#109501 = PCURVE('',#91979,#109502); -#109502 = DEFINITIONAL_REPRESENTATION('',(#109503),#109507); -#109503 = LINE('',#109504,#109505); -#109504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109505 = VECTOR('',#109506,1.); -#109506 = DIRECTION('',(-3.563627120235E-016,1.)); -#109507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109508 = PCURVE('',#92007,#109509); -#109509 = DEFINITIONAL_REPRESENTATION('',(#109510),#109514); -#109510 = LINE('',#109511,#109512); -#109511 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109512 = VECTOR('',#109513,1.); -#109513 = DIRECTION('',(-1.,-4.804757279354E-063)); -#109514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109515 = ORIENTED_EDGE('',*,*,#91963,.F.); -#109516 = ADVANCED_FACE('',(#109517),#91951,.T.); -#109517 = FACE_BOUND('',#109518,.T.); -#109518 = EDGE_LOOP('',(#109519,#109540,#109541,#109542)); -#109519 = ORIENTED_EDGE('',*,*,#109520,.F.); -#109520 = EDGE_CURVE('',#109373,#91934,#109521,.T.); -#109521 = SURFACE_CURVE('',#109522,(#109526,#109533),.PCURVE_S1.); -#109522 = LINE('',#109523,#109524); -#109523 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.75)); -#109524 = VECTOR('',#109525,1.); -#109525 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#109526 = PCURVE('',#91951,#109527); -#109527 = DEFINITIONAL_REPRESENTATION('',(#109528),#109532); -#109528 = LINE('',#109529,#109530); -#109529 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#109530 = VECTOR('',#109531,1.); -#109531 = DIRECTION('',(1.,-4.804757279354E-063)); -#109532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109533 = PCURVE('',#92033,#109534); -#109534 = DEFINITIONAL_REPRESENTATION('',(#109535),#109539); -#109535 = LINE('',#109536,#109537); -#109536 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#109537 = VECTOR('',#109538,1.); -#109538 = DIRECTION('',(3.563627120235E-016,1.)); -#109539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109540 = ORIENTED_EDGE('',*,*,#109372,.T.); -#109541 = ORIENTED_EDGE('',*,*,#109445,.T.); -#109542 = ORIENTED_EDGE('',*,*,#91933,.F.); -#109543 = ADVANCED_FACE('',(#109544),#92033,.T.); -#109544 = FACE_BOUND('',#109545,.T.); -#109545 = EDGE_LOOP('',(#109546,#109567,#109568,#109569,#109570,#109571, - #109592,#109593,#109594,#109595,#109596,#109597)); -#109546 = ORIENTED_EDGE('',*,*,#109547,.F.); -#109547 = EDGE_CURVE('',#109276,#91992,#109548,.T.); -#109548 = SURFACE_CURVE('',#109549,(#109553,#109560),.PCURVE_S1.); -#109549 = LINE('',#109550,#109551); -#109550 = CARTESIAN_POINT('',(-0.527847992439,5.35,0.65)); -#109551 = VECTOR('',#109552,1.); -#109552 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#109553 = PCURVE('',#92033,#109554); -#109554 = DEFINITIONAL_REPRESENTATION('',(#109555),#109559); -#109555 = LINE('',#109556,#109557); -#109556 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109557 = VECTOR('',#109558,1.); -#109558 = DIRECTION('',(3.563627120235E-016,1.)); -#109559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109560 = PCURVE('',#92007,#109561); -#109561 = DEFINITIONAL_REPRESENTATION('',(#109562),#109566); -#109562 = LINE('',#109563,#109564); -#109563 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#109564 = VECTOR('',#109565,1.); -#109565 = DIRECTION('',(-1.,-4.804757279354E-063)); -#109566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109567 = ORIENTED_EDGE('',*,*,#109320,.T.); -#109568 = ORIENTED_EDGE('',*,*,#109227,.T.); -#109569 = ORIENTED_EDGE('',*,*,#108971,.T.); -#109570 = ORIENTED_EDGE('',*,*,#108869,.T.); -#109571 = ORIENTED_EDGE('',*,*,#109572,.F.); -#109572 = EDGE_CURVE('',#108733,#108840,#109573,.T.); -#109573 = SURFACE_CURVE('',#109574,(#109578,#109585),.PCURVE_S1.); -#109574 = LINE('',#109575,#109576); -#109575 = CARTESIAN_POINT('',(-1.,5.35,1.159810404338E-002)); -#109576 = VECTOR('',#109577,1.); -#109577 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#109578 = PCURVE('',#92033,#109579); -#109579 = DEFINITIONAL_REPRESENTATION('',(#109580),#109584); -#109580 = LINE('',#109581,#109582); -#109581 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#109582 = VECTOR('',#109583,1.); -#109583 = DIRECTION('',(-1.,2.101748079665E-016)); -#109584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109585 = PCURVE('',#108753,#109586); -#109586 = DEFINITIONAL_REPRESENTATION('',(#109587),#109591); -#109587 = LINE('',#109588,#109589); -#109588 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#109589 = VECTOR('',#109590,1.); -#109590 = DIRECTION('',(1.194699204908E-017,-1.)); -#109591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109592 = ORIENTED_EDGE('',*,*,#108815,.F.); -#109593 = ORIENTED_EDGE('',*,*,#109022,.F.); -#109594 = ORIENTED_EDGE('',*,*,#109130,.F.); -#109595 = ORIENTED_EDGE('',*,*,#109417,.F.); -#109596 = ORIENTED_EDGE('',*,*,#109520,.T.); -#109597 = ORIENTED_EDGE('',*,*,#92019,.F.); -#109598 = ADVANCED_FACE('',(#109599),#92007,.T.); -#109599 = FACE_BOUND('',#109600,.T.); -#109600 = EDGE_LOOP('',(#109601,#109602,#109603,#109604)); -#109601 = ORIENTED_EDGE('',*,*,#109495,.F.); -#109602 = ORIENTED_EDGE('',*,*,#109275,.T.); -#109603 = ORIENTED_EDGE('',*,*,#109547,.T.); -#109604 = ORIENTED_EDGE('',*,*,#91991,.F.); -#109605 = ADVANCED_FACE('',(#109606),#108753,.T.); -#109606 = FACE_BOUND('',#109607,.T.); -#109607 = EDGE_LOOP('',(#109608,#109609,#109610,#109611)); -#109608 = ORIENTED_EDGE('',*,*,#108730,.T.); -#109609 = ORIENTED_EDGE('',*,*,#109572,.T.); -#109610 = ORIENTED_EDGE('',*,*,#108839,.T.); -#109611 = ORIENTED_EDGE('',*,*,#109470,.T.); -#109612 = ADVANCED_FACE('',(#109613),#109627,.F.); -#109613 = FACE_BOUND('',#109614,.T.); -#109614 = EDGE_LOOP('',(#109615,#109650,#109673,#109700)); -#109615 = ORIENTED_EDGE('',*,*,#109616,.F.); -#109616 = EDGE_CURVE('',#109617,#109619,#109621,.T.); -#109617 = VERTEX_POINT('',#109618); -#109618 = CARTESIAN_POINT('',(-1.,1.85,-0.308197125857)); -#109619 = VERTEX_POINT('',#109620); -#109620 = CARTESIAN_POINT('',(-1.,1.65,-0.308197125857)); -#109621 = SURFACE_CURVE('',#109622,(#109626,#109638),.PCURVE_S1.); -#109622 = LINE('',#109623,#109624); -#109623 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#109624 = VECTOR('',#109625,1.); -#109625 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109626 = PCURVE('',#109627,#109632); -#109627 = PLANE('',#109628); -#109628 = AXIS2_PLACEMENT_3D('',#109629,#109630,#109631); -#109629 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#109630 = DIRECTION('',(0.E+000,0.E+000,1.)); -#109631 = DIRECTION('',(1.,0.E+000,0.E+000)); -#109632 = DEFINITIONAL_REPRESENTATION('',(#109633),#109637); -#109633 = LINE('',#109634,#109635); -#109634 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#109635 = VECTOR('',#109636,1.); -#109636 = DIRECTION('',(4.440892098501E-016,-1.)); -#109637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109638 = PCURVE('',#109639,#109644); -#109639 = PLANE('',#109640); -#109640 = AXIS2_PLACEMENT_3D('',#109641,#109642,#109643); -#109641 = CARTESIAN_POINT('',(-1.,1.75,-0.258196742327)); -#109642 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#109643 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109644 = DEFINITIONAL_REPRESENTATION('',(#109645),#109649); -#109645 = LINE('',#109646,#109647); -#109646 = CARTESIAN_POINT('',(-8.25,-5.000038352949E-002)); -#109647 = VECTOR('',#109648,1.); -#109648 = DIRECTION('',(1.,0.E+000)); -#109649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109650 = ORIENTED_EDGE('',*,*,#109651,.F.); -#109651 = EDGE_CURVE('',#109652,#109617,#109654,.T.); -#109652 = VERTEX_POINT('',#109653); -#109653 = CARTESIAN_POINT('',(-0.74341632541,1.85,-0.308197125857)); -#109654 = SURFACE_CURVE('',#109655,(#109659,#109666),.PCURVE_S1.); -#109655 = LINE('',#109656,#109657); -#109656 = CARTESIAN_POINT('',(-0.74341632541,1.85,-0.308197125857)); -#109657 = VECTOR('',#109658,1.); -#109658 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#109659 = PCURVE('',#109627,#109660); -#109660 = DEFINITIONAL_REPRESENTATION('',(#109661),#109665); -#109661 = LINE('',#109662,#109663); -#109662 = CARTESIAN_POINT('',(3.552713678801E-015,-8.15)); -#109663 = VECTOR('',#109664,1.); -#109664 = DIRECTION('',(-1.,0.E+000)); -#109665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109666 = PCURVE('',#91893,#109667); -#109667 = DEFINITIONAL_REPRESENTATION('',(#109668),#109672); -#109668 = LINE('',#109669,#109670); -#109669 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#109670 = VECTOR('',#109671,1.); -#109671 = DIRECTION('',(0.E+000,-1.)); -#109672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109673 = ORIENTED_EDGE('',*,*,#109674,.F.); -#109674 = EDGE_CURVE('',#109675,#109652,#109677,.T.); -#109675 = VERTEX_POINT('',#109676); -#109676 = CARTESIAN_POINT('',(-0.74341632541,1.65,-0.308197125857)); -#109677 = SURFACE_CURVE('',#109678,(#109682,#109689),.PCURVE_S1.); -#109678 = LINE('',#109679,#109680); -#109679 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#109680 = VECTOR('',#109681,1.); -#109681 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109682 = PCURVE('',#109627,#109683); -#109683 = DEFINITIONAL_REPRESENTATION('',(#109684),#109688); -#109684 = LINE('',#109685,#109686); -#109685 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109686 = VECTOR('',#109687,1.); -#109687 = DIRECTION('',(-4.440892098501E-016,1.)); -#109688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109689 = PCURVE('',#109690,#109695); -#109690 = CYLINDRICAL_SURFACE('',#109691,0.308574064194); -#109691 = AXIS2_PLACEMENT_3D('',#109692,#109693,#109694); -#109692 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#109693 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109694 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109695 = DEFINITIONAL_REPRESENTATION('',(#109696),#109699); -#109696 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109697,#109698), - .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#109697 = CARTESIAN_POINT('',(4.761821717947,-8.35)); -#109698 = CARTESIAN_POINT('',(4.761821717947,-8.15)); -#109699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109700 = ORIENTED_EDGE('',*,*,#109701,.T.); -#109701 = EDGE_CURVE('',#109675,#109619,#109702,.T.); -#109702 = SURFACE_CURVE('',#109703,(#109707,#109714),.PCURVE_S1.); -#109703 = LINE('',#109704,#109705); -#109704 = CARTESIAN_POINT('',(-0.74341632541,1.65,-0.308197125857)); -#109705 = VECTOR('',#109706,1.); -#109706 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#109707 = PCURVE('',#109627,#109708); -#109708 = DEFINITIONAL_REPRESENTATION('',(#109709),#109713); -#109709 = LINE('',#109710,#109711); -#109710 = CARTESIAN_POINT('',(3.774758283726E-015,-8.35)); -#109711 = VECTOR('',#109712,1.); -#109712 = DIRECTION('',(-1.,0.E+000)); -#109713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109714 = PCURVE('',#91837,#109715); -#109715 = DEFINITIONAL_REPRESENTATION('',(#109716),#109720); -#109716 = LINE('',#109717,#109718); -#109717 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#109718 = VECTOR('',#109719,1.); -#109719 = DIRECTION('',(0.E+000,-1.)); -#109720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109721 = ADVANCED_FACE('',(#109722),#109736,.F.); -#109722 = FACE_BOUND('',#109723,.T.); -#109723 = EDGE_LOOP('',(#109724,#109754,#109777,#109804)); -#109724 = ORIENTED_EDGE('',*,*,#109725,.F.); -#109725 = EDGE_CURVE('',#109726,#109728,#109730,.T.); -#109726 = VERTEX_POINT('',#109727); -#109727 = CARTESIAN_POINT('',(-1.,1.65,-0.208196358798)); -#109728 = VERTEX_POINT('',#109729); -#109729 = CARTESIAN_POINT('',(-1.,1.85,-0.208196358798)); -#109730 = SURFACE_CURVE('',#109731,(#109735,#109747),.PCURVE_S1.); -#109731 = LINE('',#109732,#109733); -#109732 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#109733 = VECTOR('',#109734,1.); -#109734 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109735 = PCURVE('',#109736,#109741); -#109736 = PLANE('',#109737); -#109737 = AXIS2_PLACEMENT_3D('',#109738,#109739,#109740); -#109738 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#109739 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#109740 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#109741 = DEFINITIONAL_REPRESENTATION('',(#109742),#109746); -#109742 = LINE('',#109743,#109744); -#109743 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#109744 = VECTOR('',#109745,1.); -#109745 = DIRECTION('',(4.440892098501E-016,1.)); -#109746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109747 = PCURVE('',#109639,#109748); -#109748 = DEFINITIONAL_REPRESENTATION('',(#109749),#109753); -#109749 = LINE('',#109750,#109751); -#109750 = CARTESIAN_POINT('',(-8.25,5.000038352949E-002)); -#109751 = VECTOR('',#109752,1.); -#109752 = DIRECTION('',(-1.,0.E+000)); -#109753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109754 = ORIENTED_EDGE('',*,*,#109755,.F.); -#109755 = EDGE_CURVE('',#109756,#109726,#109758,.T.); -#109756 = VERTEX_POINT('',#109757); -#109757 = CARTESIAN_POINT('',(-0.740726081328,1.65,-0.208196358798)); -#109758 = SURFACE_CURVE('',#109759,(#109763,#109770),.PCURVE_S1.); -#109759 = LINE('',#109760,#109761); -#109760 = CARTESIAN_POINT('',(-0.740726081328,1.65,-0.208196358798)); -#109761 = VECTOR('',#109762,1.); -#109762 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#109763 = PCURVE('',#109736,#109764); -#109764 = DEFINITIONAL_REPRESENTATION('',(#109765),#109769); -#109765 = LINE('',#109766,#109767); -#109766 = CARTESIAN_POINT('',(-3.774758283726E-015,-8.35)); -#109767 = VECTOR('',#109768,1.); -#109768 = DIRECTION('',(1.,0.E+000)); -#109769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109770 = PCURVE('',#91837,#109771); -#109771 = DEFINITIONAL_REPRESENTATION('',(#109772),#109776); -#109772 = LINE('',#109773,#109774); -#109773 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#109774 = VECTOR('',#109775,1.); -#109775 = DIRECTION('',(0.E+000,-1.)); -#109776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109777 = ORIENTED_EDGE('',*,*,#109778,.F.); -#109778 = EDGE_CURVE('',#109779,#109756,#109781,.T.); -#109779 = VERTEX_POINT('',#109780); -#109780 = CARTESIAN_POINT('',(-0.740726081328,1.85,-0.208196358798)); -#109781 = SURFACE_CURVE('',#109782,(#109786,#109793),.PCURVE_S1.); -#109782 = LINE('',#109783,#109784); -#109783 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#109784 = VECTOR('',#109785,1.); -#109785 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109786 = PCURVE('',#109736,#109787); -#109787 = DEFINITIONAL_REPRESENTATION('',(#109788),#109792); -#109788 = LINE('',#109789,#109790); -#109789 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#109790 = VECTOR('',#109791,1.); -#109791 = DIRECTION('',(-4.440892098501E-016,-1.)); -#109792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109793 = PCURVE('',#109794,#109799); -#109794 = CYLINDRICAL_SURFACE('',#109795,0.208574704164); -#109795 = AXIS2_PLACEMENT_3D('',#109796,#109797,#109798); -#109796 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#109797 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109798 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109799 = DEFINITIONAL_REPRESENTATION('',(#109800),#109803); -#109800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109801,#109802), +#112092 = ORIENTED_EDGE('',*,*,#112093,.T.); +#112093 = EDGE_CURVE('',#112067,#112011,#112094,.T.); +#112094 = SURFACE_CURVE('',#112095,(#112099,#112106),.PCURVE_S1.); +#112095 = LINE('',#112096,#112097); +#112096 = CARTESIAN_POINT('',(-0.74341632541,1.65,-0.308197125857)); +#112097 = VECTOR('',#112098,1.); +#112098 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112099 = PCURVE('',#112019,#112100); +#112100 = DEFINITIONAL_REPRESENTATION('',(#112101),#112105); +#112101 = LINE('',#112102,#112103); +#112102 = CARTESIAN_POINT('',(3.774758283726E-015,-8.35)); +#112103 = VECTOR('',#112104,1.); +#112104 = DIRECTION('',(-1.,0.E+000)); +#112105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112106 = PCURVE('',#94229,#112107); +#112107 = DEFINITIONAL_REPRESENTATION('',(#112108),#112112); +#112108 = LINE('',#112109,#112110); +#112109 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#112110 = VECTOR('',#112111,1.); +#112111 = DIRECTION('',(0.E+000,-1.)); +#112112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112113 = ADVANCED_FACE('',(#112114),#112128,.F.); +#112114 = FACE_BOUND('',#112115,.T.); +#112115 = EDGE_LOOP('',(#112116,#112146,#112169,#112196)); +#112116 = ORIENTED_EDGE('',*,*,#112117,.F.); +#112117 = EDGE_CURVE('',#112118,#112120,#112122,.T.); +#112118 = VERTEX_POINT('',#112119); +#112119 = CARTESIAN_POINT('',(-1.,1.65,-0.208196358798)); +#112120 = VERTEX_POINT('',#112121); +#112121 = CARTESIAN_POINT('',(-1.,1.85,-0.208196358798)); +#112122 = SURFACE_CURVE('',#112123,(#112127,#112139),.PCURVE_S1.); +#112123 = LINE('',#112124,#112125); +#112124 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#112125 = VECTOR('',#112126,1.); +#112126 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112127 = PCURVE('',#112128,#112133); +#112128 = PLANE('',#112129); +#112129 = AXIS2_PLACEMENT_3D('',#112130,#112131,#112132); +#112130 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#112131 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#112132 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112133 = DEFINITIONAL_REPRESENTATION('',(#112134),#112138); +#112134 = LINE('',#112135,#112136); +#112135 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#112136 = VECTOR('',#112137,1.); +#112137 = DIRECTION('',(4.440892098501E-016,1.)); +#112138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112139 = PCURVE('',#112031,#112140); +#112140 = DEFINITIONAL_REPRESENTATION('',(#112141),#112145); +#112141 = LINE('',#112142,#112143); +#112142 = CARTESIAN_POINT('',(-8.25,5.000038352949E-002)); +#112143 = VECTOR('',#112144,1.); +#112144 = DIRECTION('',(-1.,0.E+000)); +#112145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112146 = ORIENTED_EDGE('',*,*,#112147,.F.); +#112147 = EDGE_CURVE('',#112148,#112118,#112150,.T.); +#112148 = VERTEX_POINT('',#112149); +#112149 = CARTESIAN_POINT('',(-0.740726081328,1.65,-0.208196358798)); +#112150 = SURFACE_CURVE('',#112151,(#112155,#112162),.PCURVE_S1.); +#112151 = LINE('',#112152,#112153); +#112152 = CARTESIAN_POINT('',(-0.740726081328,1.65,-0.208196358798)); +#112153 = VECTOR('',#112154,1.); +#112154 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112155 = PCURVE('',#112128,#112156); +#112156 = DEFINITIONAL_REPRESENTATION('',(#112157),#112161); +#112157 = LINE('',#112158,#112159); +#112158 = CARTESIAN_POINT('',(-3.774758283726E-015,-8.35)); +#112159 = VECTOR('',#112160,1.); +#112160 = DIRECTION('',(1.,0.E+000)); +#112161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112162 = PCURVE('',#94229,#112163); +#112163 = DEFINITIONAL_REPRESENTATION('',(#112164),#112168); +#112164 = LINE('',#112165,#112166); +#112165 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#112166 = VECTOR('',#112167,1.); +#112167 = DIRECTION('',(0.E+000,-1.)); +#112168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112169 = ORIENTED_EDGE('',*,*,#112170,.F.); +#112170 = EDGE_CURVE('',#112171,#112148,#112173,.T.); +#112171 = VERTEX_POINT('',#112172); +#112172 = CARTESIAN_POINT('',(-0.740726081328,1.85,-0.208196358798)); +#112173 = SURFACE_CURVE('',#112174,(#112178,#112185),.PCURVE_S1.); +#112174 = LINE('',#112175,#112176); +#112175 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#112176 = VECTOR('',#112177,1.); +#112177 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112178 = PCURVE('',#112128,#112179); +#112179 = DEFINITIONAL_REPRESENTATION('',(#112180),#112184); +#112180 = LINE('',#112181,#112182); +#112181 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112182 = VECTOR('',#112183,1.); +#112183 = DIRECTION('',(-4.440892098501E-016,-1.)); +#112184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112185 = PCURVE('',#112186,#112191); +#112186 = CYLINDRICAL_SURFACE('',#112187,0.208574704164); +#112187 = AXIS2_PLACEMENT_3D('',#112188,#112189,#112190); +#112188 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#112189 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112190 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112191 = DEFINITIONAL_REPRESENTATION('',(#112192),#112195); +#112192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112193,#112194), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#109801 = CARTESIAN_POINT('',(4.772630242227,-8.15)); -#109802 = CARTESIAN_POINT('',(4.772630242227,-8.35)); -#109803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109804 = ORIENTED_EDGE('',*,*,#109805,.T.); -#109805 = EDGE_CURVE('',#109779,#109728,#109806,.T.); -#109806 = SURFACE_CURVE('',#109807,(#109811,#109818),.PCURVE_S1.); -#109807 = LINE('',#109808,#109809); -#109808 = CARTESIAN_POINT('',(-0.740726081328,1.85,-0.208196358798)); -#109809 = VECTOR('',#109810,1.); -#109810 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#109811 = PCURVE('',#109736,#109812); -#109812 = DEFINITIONAL_REPRESENTATION('',(#109813),#109817); -#109813 = LINE('',#109814,#109815); -#109814 = CARTESIAN_POINT('',(-3.552713678801E-015,-8.15)); -#109815 = VECTOR('',#109816,1.); -#109816 = DIRECTION('',(1.,0.E+000)); -#109817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109818 = PCURVE('',#91893,#109819); -#109819 = DEFINITIONAL_REPRESENTATION('',(#109820),#109824); -#109820 = LINE('',#109821,#109822); -#109821 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#109822 = VECTOR('',#109823,1.); -#109823 = DIRECTION('',(0.E+000,-1.)); -#109824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109825 = ADVANCED_FACE('',(#109826),#109690,.T.); -#109826 = FACE_BOUND('',#109827,.T.); -#109827 = EDGE_LOOP('',(#109828,#109855,#109856,#109879)); -#109828 = ORIENTED_EDGE('',*,*,#109829,.T.); -#109829 = EDGE_CURVE('',#109830,#109675,#109832,.T.); -#109830 = VERTEX_POINT('',#109831); -#109831 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.E+000)); -#109832 = SURFACE_CURVE('',#109833,(#109838,#109844),.PCURVE_S1.); -#109833 = CIRCLE('',#109834,0.308574064194); -#109834 = AXIS2_PLACEMENT_3D('',#109835,#109836,#109837); -#109835 = CARTESIAN_POINT('',(-0.728168876214,1.65,2.640924866458E-017) - ); -#109836 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109837 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109838 = PCURVE('',#109690,#109839); -#109839 = DEFINITIONAL_REPRESENTATION('',(#109840),#109843); -#109840 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109841,#109842), +#112193 = CARTESIAN_POINT('',(4.772630242227,-8.15)); +#112194 = CARTESIAN_POINT('',(4.772630242227,-8.35)); +#112195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112196 = ORIENTED_EDGE('',*,*,#112197,.T.); +#112197 = EDGE_CURVE('',#112171,#112120,#112198,.T.); +#112198 = SURFACE_CURVE('',#112199,(#112203,#112210),.PCURVE_S1.); +#112199 = LINE('',#112200,#112201); +#112200 = CARTESIAN_POINT('',(-0.740726081328,1.85,-0.208196358798)); +#112201 = VECTOR('',#112202,1.); +#112202 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112203 = PCURVE('',#112128,#112204); +#112204 = DEFINITIONAL_REPRESENTATION('',(#112205),#112209); +#112205 = LINE('',#112206,#112207); +#112206 = CARTESIAN_POINT('',(-3.552713678801E-015,-8.15)); +#112207 = VECTOR('',#112208,1.); +#112208 = DIRECTION('',(1.,0.E+000)); +#112209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112210 = PCURVE('',#94285,#112211); +#112211 = DEFINITIONAL_REPRESENTATION('',(#112212),#112216); +#112212 = LINE('',#112213,#112214); +#112213 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#112214 = VECTOR('',#112215,1.); +#112215 = DIRECTION('',(0.E+000,-1.)); +#112216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112217 = ADVANCED_FACE('',(#112218),#112082,.T.); +#112218 = FACE_BOUND('',#112219,.T.); +#112219 = EDGE_LOOP('',(#112220,#112247,#112248,#112271)); +#112220 = ORIENTED_EDGE('',*,*,#112221,.T.); +#112221 = EDGE_CURVE('',#112222,#112067,#112224,.T.); +#112222 = VERTEX_POINT('',#112223); +#112223 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.E+000)); +#112224 = SURFACE_CURVE('',#112225,(#112230,#112236),.PCURVE_S1.); +#112225 = CIRCLE('',#112226,0.308574064194); +#112226 = AXIS2_PLACEMENT_3D('',#112227,#112228,#112229); +#112227 = CARTESIAN_POINT('',(-0.728168876214,1.65,2.640924866458E-017) + ); +#112228 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112229 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112230 = PCURVE('',#112082,#112231); +#112231 = DEFINITIONAL_REPRESENTATION('',(#112232),#112235); +#112232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112233,#112234), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#109841 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#109842 = CARTESIAN_POINT('',(4.761821717947,-8.35)); -#109843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#112233 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#112234 = CARTESIAN_POINT('',(4.761821717947,-8.35)); +#112235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109844 = PCURVE('',#91837,#109845); -#109845 = DEFINITIONAL_REPRESENTATION('',(#109846),#109854); -#109846 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109847,#109848,#109849, - #109850,#109851,#109852,#109853),.UNSPECIFIED.,.T.,.F.) +#112236 = PCURVE('',#94229,#112237); +#112237 = DEFINITIONAL_REPRESENTATION('',(#112238),#112246); +#112238 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112239,#112240,#112241, + #112242,#112243,#112244,#112245),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#109847 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#109848 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#109849 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#109850 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#109851 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#109852 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#109853 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#109854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109855 = ORIENTED_EDGE('',*,*,#109674,.T.); -#109856 = ORIENTED_EDGE('',*,*,#109857,.F.); -#109857 = EDGE_CURVE('',#109858,#109652,#109860,.T.); -#109858 = VERTEX_POINT('',#109859); -#109859 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.E+000)); -#109860 = SURFACE_CURVE('',#109861,(#109866,#109872),.PCURVE_S1.); -#109861 = CIRCLE('',#109862,0.308574064194); -#109862 = AXIS2_PLACEMENT_3D('',#109863,#109864,#109865); -#109863 = CARTESIAN_POINT('',(-0.728168876214,1.85,2.640924866458E-017) - ); -#109864 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109865 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109866 = PCURVE('',#109690,#109867); -#109867 = DEFINITIONAL_REPRESENTATION('',(#109868),#109871); -#109868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109869,#109870), +#112239 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#112240 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#112241 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#112242 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#112243 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#112244 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#112245 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#112246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112247 = ORIENTED_EDGE('',*,*,#112066,.T.); +#112248 = ORIENTED_EDGE('',*,*,#112249,.F.); +#112249 = EDGE_CURVE('',#112250,#112044,#112252,.T.); +#112250 = VERTEX_POINT('',#112251); +#112251 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.E+000)); +#112252 = SURFACE_CURVE('',#112253,(#112258,#112264),.PCURVE_S1.); +#112253 = CIRCLE('',#112254,0.308574064194); +#112254 = AXIS2_PLACEMENT_3D('',#112255,#112256,#112257); +#112255 = CARTESIAN_POINT('',(-0.728168876214,1.85,2.640924866458E-017) + ); +#112256 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112257 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112258 = PCURVE('',#112082,#112259); +#112259 = DEFINITIONAL_REPRESENTATION('',(#112260),#112263); +#112260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112261,#112262), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#109869 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#109870 = CARTESIAN_POINT('',(4.761821717947,-8.15)); -#109871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109872 = PCURVE('',#91893,#109873); -#109873 = DEFINITIONAL_REPRESENTATION('',(#109874),#109878); -#109874 = CIRCLE('',#109875,0.308574064194); -#109875 = AXIS2_PLACEMENT_2D('',#109876,#109877); -#109876 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#109877 = DIRECTION('',(0.E+000,-1.)); -#109878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109879 = ORIENTED_EDGE('',*,*,#109880,.T.); -#109880 = EDGE_CURVE('',#109858,#109830,#109881,.T.); -#109881 = SURFACE_CURVE('',#109882,(#109886,#109892),.PCURVE_S1.); -#109882 = LINE('',#109883,#109884); -#109883 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#109884 = VECTOR('',#109885,1.); -#109885 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109886 = PCURVE('',#109690,#109887); -#109887 = DEFINITIONAL_REPRESENTATION('',(#109888),#109891); -#109888 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109889,#109890), +#112261 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#112262 = CARTESIAN_POINT('',(4.761821717947,-8.15)); +#112263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112264 = PCURVE('',#94285,#112265); +#112265 = DEFINITIONAL_REPRESENTATION('',(#112266),#112270); +#112266 = CIRCLE('',#112267,0.308574064194); +#112267 = AXIS2_PLACEMENT_2D('',#112268,#112269); +#112268 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#112269 = DIRECTION('',(0.E+000,-1.)); +#112270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112271 = ORIENTED_EDGE('',*,*,#112272,.T.); +#112272 = EDGE_CURVE('',#112250,#112222,#112273,.T.); +#112273 = SURFACE_CURVE('',#112274,(#112278,#112284),.PCURVE_S1.); +#112274 = LINE('',#112275,#112276); +#112275 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#112276 = VECTOR('',#112277,1.); +#112277 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112278 = PCURVE('',#112082,#112279); +#112279 = DEFINITIONAL_REPRESENTATION('',(#112280),#112283); +#112280 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112281,#112282), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#109889 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#109890 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#109891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109892 = PCURVE('',#109893,#109898); -#109893 = PLANE('',#109894); -#109894 = AXIS2_PLACEMENT_3D('',#109895,#109896,#109897); -#109895 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#109896 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#109897 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109898 = DEFINITIONAL_REPRESENTATION('',(#109899),#109903); -#109899 = LINE('',#109900,#109901); -#109900 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#109901 = VECTOR('',#109902,1.); -#109902 = DIRECTION('',(-1.,0.E+000)); -#109903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109904 = ADVANCED_FACE('',(#109905),#109794,.F.); -#109905 = FACE_BOUND('',#109906,.F.); -#109906 = EDGE_LOOP('',(#109907,#109930,#109957,#109982)); -#109907 = ORIENTED_EDGE('',*,*,#109908,.F.); -#109908 = EDGE_CURVE('',#109909,#109779,#109911,.T.); -#109909 = VERTEX_POINT('',#109910); -#109910 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.E+000)); -#109911 = SURFACE_CURVE('',#109912,(#109917,#109923),.PCURVE_S1.); -#109912 = CIRCLE('',#109913,0.208574704164); -#109913 = AXIS2_PLACEMENT_3D('',#109914,#109915,#109916); -#109914 = CARTESIAN_POINT('',(-0.728168876214,1.85,2.640924866458E-017) - ); -#109915 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109916 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109917 = PCURVE('',#109794,#109918); -#109918 = DEFINITIONAL_REPRESENTATION('',(#109919),#109922); -#109919 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109920,#109921), +#112281 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#112282 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#112283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112284 = PCURVE('',#112285,#112290); +#112285 = PLANE('',#112286); +#112286 = AXIS2_PLACEMENT_3D('',#112287,#112288,#112289); +#112287 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#112288 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#112289 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112290 = DEFINITIONAL_REPRESENTATION('',(#112291),#112295); +#112291 = LINE('',#112292,#112293); +#112292 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#112293 = VECTOR('',#112294,1.); +#112294 = DIRECTION('',(-1.,0.E+000)); +#112295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112296 = ADVANCED_FACE('',(#112297),#112186,.F.); +#112297 = FACE_BOUND('',#112298,.F.); +#112298 = EDGE_LOOP('',(#112299,#112322,#112349,#112374)); +#112299 = ORIENTED_EDGE('',*,*,#112300,.F.); +#112300 = EDGE_CURVE('',#112301,#112171,#112303,.T.); +#112301 = VERTEX_POINT('',#112302); +#112302 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.E+000)); +#112303 = SURFACE_CURVE('',#112304,(#112309,#112315),.PCURVE_S1.); +#112304 = CIRCLE('',#112305,0.208574704164); +#112305 = AXIS2_PLACEMENT_3D('',#112306,#112307,#112308); +#112306 = CARTESIAN_POINT('',(-0.728168876214,1.85,2.640924866458E-017) + ); +#112307 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112308 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112309 = PCURVE('',#112186,#112310); +#112310 = DEFINITIONAL_REPRESENTATION('',(#112311),#112314); +#112311 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112312,#112313), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#109920 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#109921 = CARTESIAN_POINT('',(4.772630242227,-8.15)); -#109922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109923 = PCURVE('',#91893,#109924); -#109924 = DEFINITIONAL_REPRESENTATION('',(#109925),#109929); -#109925 = CIRCLE('',#109926,0.208574704164); -#109926 = AXIS2_PLACEMENT_2D('',#109927,#109928); -#109927 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#109928 = DIRECTION('',(0.E+000,-1.)); -#109929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109930 = ORIENTED_EDGE('',*,*,#109931,.F.); -#109931 = EDGE_CURVE('',#109932,#109909,#109934,.T.); -#109932 = VERTEX_POINT('',#109933); -#109933 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.E+000)); -#109934 = SURFACE_CURVE('',#109935,(#109939,#109945),.PCURVE_S1.); -#109935 = LINE('',#109936,#109937); -#109936 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#109937 = VECTOR('',#109938,1.); -#109938 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109939 = PCURVE('',#109794,#109940); -#109940 = DEFINITIONAL_REPRESENTATION('',(#109941),#109944); -#109941 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109942,#109943), +#112312 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#112313 = CARTESIAN_POINT('',(4.772630242227,-8.15)); +#112314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112315 = PCURVE('',#94285,#112316); +#112316 = DEFINITIONAL_REPRESENTATION('',(#112317),#112321); +#112317 = CIRCLE('',#112318,0.208574704164); +#112318 = AXIS2_PLACEMENT_2D('',#112319,#112320); +#112319 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#112320 = DIRECTION('',(0.E+000,-1.)); +#112321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112322 = ORIENTED_EDGE('',*,*,#112323,.F.); +#112323 = EDGE_CURVE('',#112324,#112301,#112326,.T.); +#112324 = VERTEX_POINT('',#112325); +#112325 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.E+000)); +#112326 = SURFACE_CURVE('',#112327,(#112331,#112337),.PCURVE_S1.); +#112327 = LINE('',#112328,#112329); +#112328 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#112329 = VECTOR('',#112330,1.); +#112330 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112331 = PCURVE('',#112186,#112332); +#112332 = DEFINITIONAL_REPRESENTATION('',(#112333),#112336); +#112333 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112334,#112335), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#109942 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#109943 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#109944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109945 = PCURVE('',#109946,#109951); -#109946 = PLANE('',#109947); -#109947 = AXIS2_PLACEMENT_3D('',#109948,#109949,#109950); -#109948 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#109949 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#109950 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#109951 = DEFINITIONAL_REPRESENTATION('',(#109952),#109956); -#109952 = LINE('',#109953,#109954); -#109953 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#109954 = VECTOR('',#109955,1.); -#109955 = DIRECTION('',(-1.,0.E+000)); -#109956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109957 = ORIENTED_EDGE('',*,*,#109958,.T.); -#109958 = EDGE_CURVE('',#109932,#109756,#109959,.T.); -#109959 = SURFACE_CURVE('',#109960,(#109965,#109971),.PCURVE_S1.); -#109960 = CIRCLE('',#109961,0.208574704164); -#109961 = AXIS2_PLACEMENT_3D('',#109962,#109963,#109964); -#109962 = CARTESIAN_POINT('',(-0.728168876214,1.65,2.640924866458E-017) - ); -#109963 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109964 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#109965 = PCURVE('',#109794,#109966); -#109966 = DEFINITIONAL_REPRESENTATION('',(#109967),#109970); -#109967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#109968,#109969), +#112334 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#112335 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#112336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112337 = PCURVE('',#112338,#112343); +#112338 = PLANE('',#112339); +#112339 = AXIS2_PLACEMENT_3D('',#112340,#112341,#112342); +#112340 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#112341 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#112342 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112343 = DEFINITIONAL_REPRESENTATION('',(#112344),#112348); +#112344 = LINE('',#112345,#112346); +#112345 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#112346 = VECTOR('',#112347,1.); +#112347 = DIRECTION('',(-1.,0.E+000)); +#112348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112349 = ORIENTED_EDGE('',*,*,#112350,.T.); +#112350 = EDGE_CURVE('',#112324,#112148,#112351,.T.); +#112351 = SURFACE_CURVE('',#112352,(#112357,#112363),.PCURVE_S1.); +#112352 = CIRCLE('',#112353,0.208574704164); +#112353 = AXIS2_PLACEMENT_3D('',#112354,#112355,#112356); +#112354 = CARTESIAN_POINT('',(-0.728168876214,1.65,2.640924866458E-017) + ); +#112355 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112356 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112357 = PCURVE('',#112186,#112358); +#112358 = DEFINITIONAL_REPRESENTATION('',(#112359),#112362); +#112359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112360,#112361), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#109968 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#109969 = CARTESIAN_POINT('',(4.772630242227,-8.35)); -#109970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#112360 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#112361 = CARTESIAN_POINT('',(4.772630242227,-8.35)); +#112362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#109971 = PCURVE('',#91837,#109972); -#109972 = DEFINITIONAL_REPRESENTATION('',(#109973),#109981); -#109973 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#109974,#109975,#109976, - #109977,#109978,#109979,#109980),.UNSPECIFIED.,.T.,.F.) +#112363 = PCURVE('',#94229,#112364); +#112364 = DEFINITIONAL_REPRESENTATION('',(#112365),#112373); +#112365 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112366,#112367,#112368, + #112369,#112370,#112371,#112372),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#109974 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#109975 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#109976 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#109977 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#109978 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#109979 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#109980 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#109981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#109982 = ORIENTED_EDGE('',*,*,#109778,.F.); -#109983 = ADVANCED_FACE('',(#109984),#109946,.T.); -#109984 = FACE_BOUND('',#109985,.T.); -#109985 = EDGE_LOOP('',(#109986,#110015,#110036,#110037)); -#109986 = ORIENTED_EDGE('',*,*,#109987,.T.); -#109987 = EDGE_CURVE('',#109988,#109990,#109992,.T.); -#109988 = VERTEX_POINT('',#109989); -#109989 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.530776333563)); -#109990 = VERTEX_POINT('',#109991); -#109991 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.530776333563)); -#109992 = SURFACE_CURVE('',#109993,(#109997,#110004),.PCURVE_S1.); -#109993 = LINE('',#109994,#109995); -#109994 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#109995 = VECTOR('',#109996,1.); -#109996 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#109997 = PCURVE('',#109946,#109998); -#109998 = DEFINITIONAL_REPRESENTATION('',(#109999),#110003); -#109999 = LINE('',#110000,#110001); -#110000 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110001 = VECTOR('',#110002,1.); -#110002 = DIRECTION('',(-1.,0.E+000)); -#110003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110004 = PCURVE('',#110005,#110010); -#110005 = CYLINDRICAL_SURFACE('',#110006,0.2192697516); -#110006 = AXIS2_PLACEMENT_3D('',#110007,#110008,#110009); -#110007 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#110008 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110009 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110010 = DEFINITIONAL_REPRESENTATION('',(#110011),#110014); -#110011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110012,#110013), +#112366 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#112367 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#112368 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#112369 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#112370 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#112371 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#112372 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#112373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112374 = ORIENTED_EDGE('',*,*,#112170,.F.); +#112375 = ADVANCED_FACE('',(#112376),#112338,.T.); +#112376 = FACE_BOUND('',#112377,.T.); +#112377 = EDGE_LOOP('',(#112378,#112407,#112428,#112429)); +#112378 = ORIENTED_EDGE('',*,*,#112379,.T.); +#112379 = EDGE_CURVE('',#112380,#112382,#112384,.T.); +#112380 = VERTEX_POINT('',#112381); +#112381 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.530776333563)); +#112382 = VERTEX_POINT('',#112383); +#112383 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.530776333563)); +#112384 = SURFACE_CURVE('',#112385,(#112389,#112396),.PCURVE_S1.); +#112385 = LINE('',#112386,#112387); +#112386 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#112387 = VECTOR('',#112388,1.); +#112388 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112389 = PCURVE('',#112338,#112390); +#112390 = DEFINITIONAL_REPRESENTATION('',(#112391),#112395); +#112391 = LINE('',#112392,#112393); +#112392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112393 = VECTOR('',#112394,1.); +#112394 = DIRECTION('',(-1.,0.E+000)); +#112395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112396 = PCURVE('',#112397,#112402); +#112397 = CYLINDRICAL_SURFACE('',#112398,0.2192697516); +#112398 = AXIS2_PLACEMENT_3D('',#112399,#112400,#112401); +#112399 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#112400 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112401 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112402 = DEFINITIONAL_REPRESENTATION('',(#112403),#112406); +#112403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112404,#112405), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#110012 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#110013 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#110014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110015 = ORIENTED_EDGE('',*,*,#110016,.T.); -#110016 = EDGE_CURVE('',#109990,#109909,#110017,.T.); -#110017 = SURFACE_CURVE('',#110018,(#110022,#110029),.PCURVE_S1.); -#110018 = LINE('',#110019,#110020); -#110019 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.530776333563)); -#110020 = VECTOR('',#110021,1.); -#110021 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110022 = PCURVE('',#109946,#110023); -#110023 = DEFINITIONAL_REPRESENTATION('',(#110024),#110028); -#110024 = LINE('',#110025,#110026); -#110025 = CARTESIAN_POINT('',(8.15,4.535643882845E-033)); -#110026 = VECTOR('',#110027,1.); -#110027 = DIRECTION('',(-4.535643882845E-032,-1.)); -#110028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110029 = PCURVE('',#91893,#110030); -#110030 = DEFINITIONAL_REPRESENTATION('',(#110031),#110035); -#110031 = LINE('',#110032,#110033); -#110032 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#110033 = VECTOR('',#110034,1.); -#110034 = DIRECTION('',(-1.,-1.021336205033E-016)); -#110035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110036 = ORIENTED_EDGE('',*,*,#109931,.F.); -#110037 = ORIENTED_EDGE('',*,*,#110038,.F.); -#110038 = EDGE_CURVE('',#109988,#109932,#110039,.T.); -#110039 = SURFACE_CURVE('',#110040,(#110044,#110051),.PCURVE_S1.); -#110040 = LINE('',#110041,#110042); -#110041 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.530776333563)); -#110042 = VECTOR('',#110043,1.); -#110043 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110044 = PCURVE('',#109946,#110045); -#110045 = DEFINITIONAL_REPRESENTATION('',(#110046),#110050); -#110046 = LINE('',#110047,#110048); -#110047 = CARTESIAN_POINT('',(8.35,-4.535643882845E-033)); -#110048 = VECTOR('',#110049,1.); -#110049 = DIRECTION('',(-4.535643882845E-032,-1.)); -#110050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110051 = PCURVE('',#91837,#110052); -#110052 = DEFINITIONAL_REPRESENTATION('',(#110053),#110057); -#110053 = LINE('',#110054,#110055); -#110054 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#110055 = VECTOR('',#110056,1.); -#110056 = DIRECTION('',(1.,-1.021336205033E-016)); -#110057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110058 = ADVANCED_FACE('',(#110059),#109893,.T.); -#110059 = FACE_BOUND('',#110060,.T.); -#110060 = EDGE_LOOP('',(#110061,#110090,#110111,#110112)); -#110061 = ORIENTED_EDGE('',*,*,#110062,.T.); -#110062 = EDGE_CURVE('',#110063,#110065,#110067,.T.); -#110063 = VERTEX_POINT('',#110064); -#110064 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.530776333563)); -#110065 = VERTEX_POINT('',#110066); -#110066 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.530776333563)); -#110067 = SURFACE_CURVE('',#110068,(#110072,#110079),.PCURVE_S1.); -#110068 = LINE('',#110069,#110070); -#110069 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#110070 = VECTOR('',#110071,1.); -#110071 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110072 = PCURVE('',#109893,#110073); -#110073 = DEFINITIONAL_REPRESENTATION('',(#110074),#110078); -#110074 = LINE('',#110075,#110076); -#110075 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110076 = VECTOR('',#110077,1.); -#110077 = DIRECTION('',(-1.,0.E+000)); -#110078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110079 = PCURVE('',#110080,#110085); -#110080 = CYLINDRICAL_SURFACE('',#110081,0.119270391569); -#110081 = AXIS2_PLACEMENT_3D('',#110082,#110083,#110084); -#110082 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#110083 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110084 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110085 = DEFINITIONAL_REPRESENTATION('',(#110086),#110089); -#110086 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110087,#110088), +#112404 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#112405 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#112406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112407 = ORIENTED_EDGE('',*,*,#112408,.T.); +#112408 = EDGE_CURVE('',#112382,#112301,#112409,.T.); +#112409 = SURFACE_CURVE('',#112410,(#112414,#112421),.PCURVE_S1.); +#112410 = LINE('',#112411,#112412); +#112411 = CARTESIAN_POINT('',(-0.51959417205,1.85,0.530776333563)); +#112412 = VECTOR('',#112413,1.); +#112413 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#112414 = PCURVE('',#112338,#112415); +#112415 = DEFINITIONAL_REPRESENTATION('',(#112416),#112420); +#112416 = LINE('',#112417,#112418); +#112417 = CARTESIAN_POINT('',(8.15,4.535643882845E-033)); +#112418 = VECTOR('',#112419,1.); +#112419 = DIRECTION('',(-4.535643882845E-032,-1.)); +#112420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112421 = PCURVE('',#94285,#112422); +#112422 = DEFINITIONAL_REPRESENTATION('',(#112423),#112427); +#112423 = LINE('',#112424,#112425); +#112424 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#112425 = VECTOR('',#112426,1.); +#112426 = DIRECTION('',(-1.,-1.021336205033E-016)); +#112427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112428 = ORIENTED_EDGE('',*,*,#112323,.F.); +#112429 = ORIENTED_EDGE('',*,*,#112430,.F.); +#112430 = EDGE_CURVE('',#112380,#112324,#112431,.T.); +#112431 = SURFACE_CURVE('',#112432,(#112436,#112443),.PCURVE_S1.); +#112432 = LINE('',#112433,#112434); +#112433 = CARTESIAN_POINT('',(-0.51959417205,1.65,0.530776333563)); +#112434 = VECTOR('',#112435,1.); +#112435 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#112436 = PCURVE('',#112338,#112437); +#112437 = DEFINITIONAL_REPRESENTATION('',(#112438),#112442); +#112438 = LINE('',#112439,#112440); +#112439 = CARTESIAN_POINT('',(8.35,-4.535643882845E-033)); +#112440 = VECTOR('',#112441,1.); +#112441 = DIRECTION('',(-4.535643882845E-032,-1.)); +#112442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112443 = PCURVE('',#94229,#112444); +#112444 = DEFINITIONAL_REPRESENTATION('',(#112445),#112449); +#112445 = LINE('',#112446,#112447); +#112446 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#112447 = VECTOR('',#112448,1.); +#112448 = DIRECTION('',(1.,-1.021336205033E-016)); +#112449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112450 = ADVANCED_FACE('',(#112451),#112285,.T.); +#112451 = FACE_BOUND('',#112452,.T.); +#112452 = EDGE_LOOP('',(#112453,#112482,#112503,#112504)); +#112453 = ORIENTED_EDGE('',*,*,#112454,.T.); +#112454 = EDGE_CURVE('',#112455,#112457,#112459,.T.); +#112455 = VERTEX_POINT('',#112456); +#112456 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.530776333563)); +#112457 = VERTEX_POINT('',#112458); +#112458 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.530776333563)); +#112459 = SURFACE_CURVE('',#112460,(#112464,#112471),.PCURVE_S1.); +#112460 = LINE('',#112461,#112462); +#112461 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#112462 = VECTOR('',#112463,1.); +#112463 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112464 = PCURVE('',#112285,#112465); +#112465 = DEFINITIONAL_REPRESENTATION('',(#112466),#112470); +#112466 = LINE('',#112467,#112468); +#112467 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112468 = VECTOR('',#112469,1.); +#112469 = DIRECTION('',(-1.,0.E+000)); +#112470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112471 = PCURVE('',#112472,#112477); +#112472 = CYLINDRICAL_SURFACE('',#112473,0.119270391569); +#112473 = AXIS2_PLACEMENT_3D('',#112474,#112475,#112476); +#112474 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#112475 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112476 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112477 = DEFINITIONAL_REPRESENTATION('',(#112478),#112481); +#112478 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112479,#112480), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#110087 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#110088 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#110089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110090 = ORIENTED_EDGE('',*,*,#110091,.T.); -#110091 = EDGE_CURVE('',#110065,#109830,#110092,.T.); -#110092 = SURFACE_CURVE('',#110093,(#110097,#110104),.PCURVE_S1.); -#110093 = LINE('',#110094,#110095); -#110094 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.530776333563)); -#110095 = VECTOR('',#110096,1.); -#110096 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110097 = PCURVE('',#109893,#110098); -#110098 = DEFINITIONAL_REPRESENTATION('',(#110099),#110103); -#110099 = LINE('',#110100,#110101); -#110100 = CARTESIAN_POINT('',(-8.35,1.133910970711E-033)); -#110101 = VECTOR('',#110102,1.); -#110102 = DIRECTION('',(4.535643882845E-032,-1.)); -#110103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110104 = PCURVE('',#91837,#110105); -#110105 = DEFINITIONAL_REPRESENTATION('',(#110106),#110110); -#110106 = LINE('',#110107,#110108); -#110107 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#110108 = VECTOR('',#110109,1.); -#110109 = DIRECTION('',(1.,-1.021336205033E-016)); -#110110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110111 = ORIENTED_EDGE('',*,*,#109880,.F.); -#110112 = ORIENTED_EDGE('',*,*,#110113,.F.); -#110113 = EDGE_CURVE('',#110063,#109858,#110114,.T.); -#110114 = SURFACE_CURVE('',#110115,(#110119,#110126),.PCURVE_S1.); -#110115 = LINE('',#110116,#110117); -#110116 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.530776333563)); -#110117 = VECTOR('',#110118,1.); -#110118 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110119 = PCURVE('',#109893,#110120); -#110120 = DEFINITIONAL_REPRESENTATION('',(#110121),#110125); -#110121 = LINE('',#110122,#110123); -#110122 = CARTESIAN_POINT('',(-8.15,-1.133910970711E-033)); -#110123 = VECTOR('',#110124,1.); -#110124 = DIRECTION('',(4.535643882845E-032,-1.)); -#110125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110126 = PCURVE('',#91893,#110127); -#110127 = DEFINITIONAL_REPRESENTATION('',(#110128),#110132); -#110128 = LINE('',#110129,#110130); -#110129 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#110130 = VECTOR('',#110131,1.); -#110131 = DIRECTION('',(-1.,-1.021336205033E-016)); -#110132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110133 = ADVANCED_FACE('',(#110134),#110080,.F.); -#110134 = FACE_BOUND('',#110135,.F.); -#110135 = EDGE_LOOP('',(#110136,#110137,#110160,#110205)); -#110136 = ORIENTED_EDGE('',*,*,#110062,.T.); -#110137 = ORIENTED_EDGE('',*,*,#110138,.F.); -#110138 = EDGE_CURVE('',#110139,#110065,#110141,.T.); -#110139 = VERTEX_POINT('',#110140); -#110140 = CARTESIAN_POINT('',(-0.303662633502,1.65,0.65)); -#110141 = SURFACE_CURVE('',#110142,(#110147,#110153),.PCURVE_S1.); -#110142 = CIRCLE('',#110143,0.119270391569); -#110143 = AXIS2_PLACEMENT_3D('',#110144,#110145,#110146); -#110144 = CARTESIAN_POINT('',(-0.30032442045,1.65,0.530776333563)); -#110145 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110146 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110147 = PCURVE('',#110080,#110148); -#110148 = DEFINITIONAL_REPRESENTATION('',(#110149),#110152); -#110149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110150,#110151), +#112479 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#112480 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#112481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112482 = ORIENTED_EDGE('',*,*,#112483,.T.); +#112483 = EDGE_CURVE('',#112457,#112222,#112484,.T.); +#112484 = SURFACE_CURVE('',#112485,(#112489,#112496),.PCURVE_S1.); +#112485 = LINE('',#112486,#112487); +#112486 = CARTESIAN_POINT('',(-0.419594812019,1.65,0.530776333563)); +#112487 = VECTOR('',#112488,1.); +#112488 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#112489 = PCURVE('',#112285,#112490); +#112490 = DEFINITIONAL_REPRESENTATION('',(#112491),#112495); +#112491 = LINE('',#112492,#112493); +#112492 = CARTESIAN_POINT('',(-8.35,1.133910970711E-033)); +#112493 = VECTOR('',#112494,1.); +#112494 = DIRECTION('',(4.535643882845E-032,-1.)); +#112495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112496 = PCURVE('',#94229,#112497); +#112497 = DEFINITIONAL_REPRESENTATION('',(#112498),#112502); +#112498 = LINE('',#112499,#112500); +#112499 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#112500 = VECTOR('',#112501,1.); +#112501 = DIRECTION('',(1.,-1.021336205033E-016)); +#112502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112503 = ORIENTED_EDGE('',*,*,#112272,.F.); +#112504 = ORIENTED_EDGE('',*,*,#112505,.F.); +#112505 = EDGE_CURVE('',#112455,#112250,#112506,.T.); +#112506 = SURFACE_CURVE('',#112507,(#112511,#112518),.PCURVE_S1.); +#112507 = LINE('',#112508,#112509); +#112508 = CARTESIAN_POINT('',(-0.419594812019,1.85,0.530776333563)); +#112509 = VECTOR('',#112510,1.); +#112510 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#112511 = PCURVE('',#112285,#112512); +#112512 = DEFINITIONAL_REPRESENTATION('',(#112513),#112517); +#112513 = LINE('',#112514,#112515); +#112514 = CARTESIAN_POINT('',(-8.15,-1.133910970711E-033)); +#112515 = VECTOR('',#112516,1.); +#112516 = DIRECTION('',(4.535643882845E-032,-1.)); +#112517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112518 = PCURVE('',#94285,#112519); +#112519 = DEFINITIONAL_REPRESENTATION('',(#112520),#112524); +#112520 = LINE('',#112521,#112522); +#112521 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#112522 = VECTOR('',#112523,1.); +#112523 = DIRECTION('',(-1.,-1.021336205033E-016)); +#112524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112525 = ADVANCED_FACE('',(#112526),#112472,.F.); +#112526 = FACE_BOUND('',#112527,.F.); +#112527 = EDGE_LOOP('',(#112528,#112529,#112552,#112597)); +#112528 = ORIENTED_EDGE('',*,*,#112454,.T.); +#112529 = ORIENTED_EDGE('',*,*,#112530,.F.); +#112530 = EDGE_CURVE('',#112531,#112457,#112533,.T.); +#112531 = VERTEX_POINT('',#112532); +#112532 = CARTESIAN_POINT('',(-0.303662633502,1.65,0.65)); +#112533 = SURFACE_CURVE('',#112534,(#112539,#112545),.PCURVE_S1.); +#112534 = CIRCLE('',#112535,0.119270391569); +#112535 = AXIS2_PLACEMENT_3D('',#112536,#112537,#112538); +#112536 = CARTESIAN_POINT('',(-0.30032442045,1.65,0.530776333563)); +#112537 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112538 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112539 = PCURVE('',#112472,#112540); +#112540 = DEFINITIONAL_REPRESENTATION('',(#112541),#112544); +#112541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112542,#112543), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#110150 = CARTESIAN_POINT('',(1.598788597134,8.35)); -#110151 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#110152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110153 = PCURVE('',#91837,#110154); -#110154 = DEFINITIONAL_REPRESENTATION('',(#110155),#110159); -#110155 = CIRCLE('',#110156,0.119270391569); -#110156 = AXIS2_PLACEMENT_2D('',#110157,#110158); -#110157 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#110158 = DIRECTION('',(0.E+000,1.)); -#110159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110160 = ORIENTED_EDGE('',*,*,#110161,.T.); -#110161 = EDGE_CURVE('',#110139,#110162,#110164,.T.); -#110162 = VERTEX_POINT('',#110163); -#110163 = CARTESIAN_POINT('',(-0.303662633502,1.85,0.65)); -#110164 = SURFACE_CURVE('',#110165,(#110169,#110198),.PCURVE_S1.); -#110165 = LINE('',#110166,#110167); -#110166 = CARTESIAN_POINT('',(-0.303662633502,1.85,0.65)); -#110167 = VECTOR('',#110168,1.); -#110168 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110169 = PCURVE('',#110080,#110170); -#110170 = DEFINITIONAL_REPRESENTATION('',(#110171),#110197); -#110171 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110172,#110173,#110174, - #110175,#110176,#110177,#110178,#110179,#110180,#110181,#110182, - #110183,#110184,#110185,#110186,#110187,#110188,#110189,#110190, - #110191,#110192,#110193,#110194,#110195,#110196),.UNSPECIFIED.,.F., +#112542 = CARTESIAN_POINT('',(1.598788597134,8.35)); +#112543 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#112544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112545 = PCURVE('',#94229,#112546); +#112546 = DEFINITIONAL_REPRESENTATION('',(#112547),#112551); +#112547 = CIRCLE('',#112548,0.119270391569); +#112548 = AXIS2_PLACEMENT_2D('',#112549,#112550); +#112549 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#112550 = DIRECTION('',(0.E+000,1.)); +#112551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112552 = ORIENTED_EDGE('',*,*,#112553,.T.); +#112553 = EDGE_CURVE('',#112531,#112554,#112556,.T.); +#112554 = VERTEX_POINT('',#112555); +#112555 = CARTESIAN_POINT('',(-0.303662633502,1.85,0.65)); +#112556 = SURFACE_CURVE('',#112557,(#112561,#112590),.PCURVE_S1.); +#112557 = LINE('',#112558,#112559); +#112558 = CARTESIAN_POINT('',(-0.303662633502,1.85,0.65)); +#112559 = VECTOR('',#112560,1.); +#112560 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112561 = PCURVE('',#112472,#112562); +#112562 = DEFINITIONAL_REPRESENTATION('',(#112563),#112589); +#112563 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112564,#112565,#112566, + #112567,#112568,#112569,#112570,#112571,#112572,#112573,#112574, + #112575,#112576,#112577,#112578,#112579,#112580,#112581,#112582, + #112583,#112584,#112585,#112586,#112587,#112588),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -135707,128 +138709,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.QUASI_UNIFORM_KNOTS.); -#110172 = CARTESIAN_POINT('',(1.598788597134,8.35)); -#110173 = CARTESIAN_POINT('',(1.598788597134,8.34696969697)); -#110174 = CARTESIAN_POINT('',(1.598788597134,8.340909090909)); -#110175 = CARTESIAN_POINT('',(1.598788597134,8.331818181818)); -#110176 = CARTESIAN_POINT('',(1.598788597134,8.322727272727)); -#110177 = CARTESIAN_POINT('',(1.598788597134,8.313636363636)); -#110178 = CARTESIAN_POINT('',(1.598788597134,8.304545454545)); -#110179 = CARTESIAN_POINT('',(1.598788597134,8.295454545455)); -#110180 = CARTESIAN_POINT('',(1.598788597134,8.286363636364)); -#110181 = CARTESIAN_POINT('',(1.598788597134,8.277272727273)); -#110182 = CARTESIAN_POINT('',(1.598788597134,8.268181818182)); -#110183 = CARTESIAN_POINT('',(1.598788597134,8.259090909091)); -#110184 = CARTESIAN_POINT('',(1.598788597134,8.25)); -#110185 = CARTESIAN_POINT('',(1.598788597134,8.240909090909)); -#110186 = CARTESIAN_POINT('',(1.598788597134,8.231818181818)); -#110187 = CARTESIAN_POINT('',(1.598788597134,8.222727272727)); -#110188 = CARTESIAN_POINT('',(1.598788597134,8.213636363636)); -#110189 = CARTESIAN_POINT('',(1.598788597134,8.204545454545)); -#110190 = CARTESIAN_POINT('',(1.598788597134,8.195454545455)); -#110191 = CARTESIAN_POINT('',(1.598788597134,8.186363636364)); -#110192 = CARTESIAN_POINT('',(1.598788597134,8.177272727273)); -#110193 = CARTESIAN_POINT('',(1.598788597134,8.168181818182)); -#110194 = CARTESIAN_POINT('',(1.598788597134,8.159090909091)); -#110195 = CARTESIAN_POINT('',(1.598788597134,8.15303030303)); -#110196 = CARTESIAN_POINT('',(1.598788597134,8.15)); -#110197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110198 = PCURVE('',#91865,#110199); -#110199 = DEFINITIONAL_REPRESENTATION('',(#110200),#110204); -#110200 = LINE('',#110201,#110202); -#110201 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#110202 = VECTOR('',#110203,1.); -#110203 = DIRECTION('',(4.440892098501E-016,1.)); -#110204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110205 = ORIENTED_EDGE('',*,*,#110206,.T.); -#110206 = EDGE_CURVE('',#110162,#110063,#110207,.T.); -#110207 = SURFACE_CURVE('',#110208,(#110213,#110219),.PCURVE_S1.); -#110208 = CIRCLE('',#110209,0.119270391569); -#110209 = AXIS2_PLACEMENT_3D('',#110210,#110211,#110212); -#110210 = CARTESIAN_POINT('',(-0.30032442045,1.85,0.530776333563)); -#110211 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110212 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110213 = PCURVE('',#110080,#110214); -#110214 = DEFINITIONAL_REPRESENTATION('',(#110215),#110218); -#110215 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110216,#110217), +#112564 = CARTESIAN_POINT('',(1.598788597134,8.35)); +#112565 = CARTESIAN_POINT('',(1.598788597134,8.34696969697)); +#112566 = CARTESIAN_POINT('',(1.598788597134,8.340909090909)); +#112567 = CARTESIAN_POINT('',(1.598788597134,8.331818181818)); +#112568 = CARTESIAN_POINT('',(1.598788597134,8.322727272727)); +#112569 = CARTESIAN_POINT('',(1.598788597134,8.313636363636)); +#112570 = CARTESIAN_POINT('',(1.598788597134,8.304545454545)); +#112571 = CARTESIAN_POINT('',(1.598788597134,8.295454545455)); +#112572 = CARTESIAN_POINT('',(1.598788597134,8.286363636364)); +#112573 = CARTESIAN_POINT('',(1.598788597134,8.277272727273)); +#112574 = CARTESIAN_POINT('',(1.598788597134,8.268181818182)); +#112575 = CARTESIAN_POINT('',(1.598788597134,8.259090909091)); +#112576 = CARTESIAN_POINT('',(1.598788597134,8.25)); +#112577 = CARTESIAN_POINT('',(1.598788597134,8.240909090909)); +#112578 = CARTESIAN_POINT('',(1.598788597134,8.231818181818)); +#112579 = CARTESIAN_POINT('',(1.598788597134,8.222727272727)); +#112580 = CARTESIAN_POINT('',(1.598788597134,8.213636363636)); +#112581 = CARTESIAN_POINT('',(1.598788597134,8.204545454545)); +#112582 = CARTESIAN_POINT('',(1.598788597134,8.195454545455)); +#112583 = CARTESIAN_POINT('',(1.598788597134,8.186363636364)); +#112584 = CARTESIAN_POINT('',(1.598788597134,8.177272727273)); +#112585 = CARTESIAN_POINT('',(1.598788597134,8.168181818182)); +#112586 = CARTESIAN_POINT('',(1.598788597134,8.159090909091)); +#112587 = CARTESIAN_POINT('',(1.598788597134,8.15303030303)); +#112588 = CARTESIAN_POINT('',(1.598788597134,8.15)); +#112589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112590 = PCURVE('',#94257,#112591); +#112591 = DEFINITIONAL_REPRESENTATION('',(#112592),#112596); +#112592 = LINE('',#112593,#112594); +#112593 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#112594 = VECTOR('',#112595,1.); +#112595 = DIRECTION('',(4.440892098501E-016,1.)); +#112596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112597 = ORIENTED_EDGE('',*,*,#112598,.T.); +#112598 = EDGE_CURVE('',#112554,#112455,#112599,.T.); +#112599 = SURFACE_CURVE('',#112600,(#112605,#112611),.PCURVE_S1.); +#112600 = CIRCLE('',#112601,0.119270391569); +#112601 = AXIS2_PLACEMENT_3D('',#112602,#112603,#112604); +#112602 = CARTESIAN_POINT('',(-0.30032442045,1.85,0.530776333563)); +#112603 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112604 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112605 = PCURVE('',#112472,#112606); +#112606 = DEFINITIONAL_REPRESENTATION('',(#112607),#112610); +#112607 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112608,#112609), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#110216 = CARTESIAN_POINT('',(1.598788597134,8.15)); -#110217 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#110218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#112608 = CARTESIAN_POINT('',(1.598788597134,8.15)); +#112609 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#112610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110219 = PCURVE('',#91893,#110220); -#110220 = DEFINITIONAL_REPRESENTATION('',(#110221),#110229); -#110221 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110222,#110223,#110224, - #110225,#110226,#110227,#110228),.UNSPECIFIED.,.T.,.F.) +#112611 = PCURVE('',#94285,#112612); +#112612 = DEFINITIONAL_REPRESENTATION('',(#112613),#112621); +#112613 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112614,#112615,#112616, + #112617,#112618,#112619,#112620),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#110222 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#110223 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#110224 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#110225 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#110226 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#110227 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#110228 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#110229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110230 = ADVANCED_FACE('',(#110231),#110005,.T.); -#110231 = FACE_BOUND('',#110232,.T.); -#110232 = EDGE_LOOP('',(#110233,#110234,#110257,#110302)); -#110233 = ORIENTED_EDGE('',*,*,#109987,.F.); -#110234 = ORIENTED_EDGE('',*,*,#110235,.F.); -#110235 = EDGE_CURVE('',#110236,#109988,#110238,.T.); -#110236 = VERTEX_POINT('',#110237); -#110237 = CARTESIAN_POINT('',(-0.304819755875,1.65,0.75)); -#110238 = SURFACE_CURVE('',#110239,(#110244,#110250),.PCURVE_S1.); -#110239 = CIRCLE('',#110240,0.2192697516); -#110240 = AXIS2_PLACEMENT_3D('',#110241,#110242,#110243); -#110241 = CARTESIAN_POINT('',(-0.30032442045,1.65,0.530776333563)); -#110242 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110243 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110244 = PCURVE('',#110005,#110245); -#110245 = DEFINITIONAL_REPRESENTATION('',(#110246),#110249); -#110246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110247,#110248), +#112614 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#112615 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#112616 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#112617 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#112618 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#112619 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#112620 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#112621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112622 = ADVANCED_FACE('',(#112623),#112397,.T.); +#112623 = FACE_BOUND('',#112624,.T.); +#112624 = EDGE_LOOP('',(#112625,#112626,#112649,#112694)); +#112625 = ORIENTED_EDGE('',*,*,#112379,.F.); +#112626 = ORIENTED_EDGE('',*,*,#112627,.F.); +#112627 = EDGE_CURVE('',#112628,#112380,#112630,.T.); +#112628 = VERTEX_POINT('',#112629); +#112629 = CARTESIAN_POINT('',(-0.304819755875,1.65,0.75)); +#112630 = SURFACE_CURVE('',#112631,(#112636,#112642),.PCURVE_S1.); +#112631 = CIRCLE('',#112632,0.2192697516); +#112632 = AXIS2_PLACEMENT_3D('',#112633,#112634,#112635); +#112633 = CARTESIAN_POINT('',(-0.30032442045,1.65,0.530776333563)); +#112634 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112635 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112636 = PCURVE('',#112397,#112637); +#112637 = DEFINITIONAL_REPRESENTATION('',(#112638),#112641); +#112638 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112639,#112640), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#110247 = CARTESIAN_POINT('',(1.591299156552,8.35)); -#110248 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#110249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110250 = PCURVE('',#91837,#110251); -#110251 = DEFINITIONAL_REPRESENTATION('',(#110252),#110256); -#110252 = CIRCLE('',#110253,0.2192697516); -#110253 = AXIS2_PLACEMENT_2D('',#110254,#110255); -#110254 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#110255 = DIRECTION('',(0.E+000,1.)); -#110256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110257 = ORIENTED_EDGE('',*,*,#110258,.F.); -#110258 = EDGE_CURVE('',#110259,#110236,#110261,.T.); -#110259 = VERTEX_POINT('',#110260); -#110260 = CARTESIAN_POINT('',(-0.304819755875,1.85,0.75)); -#110261 = SURFACE_CURVE('',#110262,(#110266,#110295),.PCURVE_S1.); -#110262 = LINE('',#110263,#110264); -#110263 = CARTESIAN_POINT('',(-0.304819755875,1.85,0.75)); -#110264 = VECTOR('',#110265,1.); -#110265 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110266 = PCURVE('',#110005,#110267); -#110267 = DEFINITIONAL_REPRESENTATION('',(#110268),#110294); -#110268 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110269,#110270,#110271, - #110272,#110273,#110274,#110275,#110276,#110277,#110278,#110279, - #110280,#110281,#110282,#110283,#110284,#110285,#110286,#110287, - #110288,#110289,#110290,#110291,#110292,#110293),.UNSPECIFIED.,.F., +#112639 = CARTESIAN_POINT('',(1.591299156552,8.35)); +#112640 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#112641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112642 = PCURVE('',#94229,#112643); +#112643 = DEFINITIONAL_REPRESENTATION('',(#112644),#112648); +#112644 = CIRCLE('',#112645,0.2192697516); +#112645 = AXIS2_PLACEMENT_2D('',#112646,#112647); +#112646 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#112647 = DIRECTION('',(0.E+000,1.)); +#112648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112649 = ORIENTED_EDGE('',*,*,#112650,.F.); +#112650 = EDGE_CURVE('',#112651,#112628,#112653,.T.); +#112651 = VERTEX_POINT('',#112652); +#112652 = CARTESIAN_POINT('',(-0.304819755875,1.85,0.75)); +#112653 = SURFACE_CURVE('',#112654,(#112658,#112687),.PCURVE_S1.); +#112654 = LINE('',#112655,#112656); +#112655 = CARTESIAN_POINT('',(-0.304819755875,1.85,0.75)); +#112656 = VECTOR('',#112657,1.); +#112657 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112658 = PCURVE('',#112397,#112659); +#112659 = DEFINITIONAL_REPRESENTATION('',(#112660),#112686); +#112660 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112661,#112662,#112663, + #112664,#112665,#112666,#112667,#112668,#112669,#112670,#112671, + #112672,#112673,#112674,#112675,#112676,#112677,#112678,#112679, + #112680,#112681,#112682,#112683,#112684,#112685),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -135837,544 +138839,544 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#110269 = CARTESIAN_POINT('',(1.591299156552,8.15)); -#110270 = CARTESIAN_POINT('',(1.591299156552,8.15303030303)); -#110271 = CARTESIAN_POINT('',(1.591299156552,8.159090909091)); -#110272 = CARTESIAN_POINT('',(1.591299156552,8.168181818182)); -#110273 = CARTESIAN_POINT('',(1.591299156552,8.177272727273)); -#110274 = CARTESIAN_POINT('',(1.591299156552,8.186363636364)); -#110275 = CARTESIAN_POINT('',(1.591299156552,8.195454545455)); -#110276 = CARTESIAN_POINT('',(1.591299156552,8.204545454545)); -#110277 = CARTESIAN_POINT('',(1.591299156552,8.213636363636)); -#110278 = CARTESIAN_POINT('',(1.591299156552,8.222727272727)); -#110279 = CARTESIAN_POINT('',(1.591299156552,8.231818181818)); -#110280 = CARTESIAN_POINT('',(1.591299156552,8.240909090909)); -#110281 = CARTESIAN_POINT('',(1.591299156552,8.25)); -#110282 = CARTESIAN_POINT('',(1.591299156552,8.259090909091)); -#110283 = CARTESIAN_POINT('',(1.591299156552,8.268181818182)); -#110284 = CARTESIAN_POINT('',(1.591299156552,8.277272727273)); -#110285 = CARTESIAN_POINT('',(1.591299156552,8.286363636364)); -#110286 = CARTESIAN_POINT('',(1.591299156552,8.295454545455)); -#110287 = CARTESIAN_POINT('',(1.591299156552,8.304545454545)); -#110288 = CARTESIAN_POINT('',(1.591299156552,8.313636363636)); -#110289 = CARTESIAN_POINT('',(1.591299156552,8.322727272727)); -#110290 = CARTESIAN_POINT('',(1.591299156552,8.331818181818)); -#110291 = CARTESIAN_POINT('',(1.591299156552,8.340909090909)); -#110292 = CARTESIAN_POINT('',(1.591299156552,8.34696969697)); -#110293 = CARTESIAN_POINT('',(1.591299156552,8.35)); -#110294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110295 = PCURVE('',#91919,#110296); -#110296 = DEFINITIONAL_REPRESENTATION('',(#110297),#110301); -#110297 = LINE('',#110298,#110299); -#110298 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#110299 = VECTOR('',#110300,1.); -#110300 = DIRECTION('',(4.440892098501E-016,-1.)); -#110301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110302 = ORIENTED_EDGE('',*,*,#110303,.T.); -#110303 = EDGE_CURVE('',#110259,#109990,#110304,.T.); -#110304 = SURFACE_CURVE('',#110305,(#110310,#110316),.PCURVE_S1.); -#110305 = CIRCLE('',#110306,0.2192697516); -#110306 = AXIS2_PLACEMENT_3D('',#110307,#110308,#110309); -#110307 = CARTESIAN_POINT('',(-0.30032442045,1.85,0.530776333563)); -#110308 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110309 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110310 = PCURVE('',#110005,#110311); -#110311 = DEFINITIONAL_REPRESENTATION('',(#110312),#110315); -#110312 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110313,#110314), +#112661 = CARTESIAN_POINT('',(1.591299156552,8.15)); +#112662 = CARTESIAN_POINT('',(1.591299156552,8.15303030303)); +#112663 = CARTESIAN_POINT('',(1.591299156552,8.159090909091)); +#112664 = CARTESIAN_POINT('',(1.591299156552,8.168181818182)); +#112665 = CARTESIAN_POINT('',(1.591299156552,8.177272727273)); +#112666 = CARTESIAN_POINT('',(1.591299156552,8.186363636364)); +#112667 = CARTESIAN_POINT('',(1.591299156552,8.195454545455)); +#112668 = CARTESIAN_POINT('',(1.591299156552,8.204545454545)); +#112669 = CARTESIAN_POINT('',(1.591299156552,8.213636363636)); +#112670 = CARTESIAN_POINT('',(1.591299156552,8.222727272727)); +#112671 = CARTESIAN_POINT('',(1.591299156552,8.231818181818)); +#112672 = CARTESIAN_POINT('',(1.591299156552,8.240909090909)); +#112673 = CARTESIAN_POINT('',(1.591299156552,8.25)); +#112674 = CARTESIAN_POINT('',(1.591299156552,8.259090909091)); +#112675 = CARTESIAN_POINT('',(1.591299156552,8.268181818182)); +#112676 = CARTESIAN_POINT('',(1.591299156552,8.277272727273)); +#112677 = CARTESIAN_POINT('',(1.591299156552,8.286363636364)); +#112678 = CARTESIAN_POINT('',(1.591299156552,8.295454545455)); +#112679 = CARTESIAN_POINT('',(1.591299156552,8.304545454545)); +#112680 = CARTESIAN_POINT('',(1.591299156552,8.313636363636)); +#112681 = CARTESIAN_POINT('',(1.591299156552,8.322727272727)); +#112682 = CARTESIAN_POINT('',(1.591299156552,8.331818181818)); +#112683 = CARTESIAN_POINT('',(1.591299156552,8.340909090909)); +#112684 = CARTESIAN_POINT('',(1.591299156552,8.34696969697)); +#112685 = CARTESIAN_POINT('',(1.591299156552,8.35)); +#112686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112687 = PCURVE('',#94311,#112688); +#112688 = DEFINITIONAL_REPRESENTATION('',(#112689),#112693); +#112689 = LINE('',#112690,#112691); +#112690 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#112691 = VECTOR('',#112692,1.); +#112692 = DIRECTION('',(4.440892098501E-016,-1.)); +#112693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112694 = ORIENTED_EDGE('',*,*,#112695,.T.); +#112695 = EDGE_CURVE('',#112651,#112382,#112696,.T.); +#112696 = SURFACE_CURVE('',#112697,(#112702,#112708),.PCURVE_S1.); +#112697 = CIRCLE('',#112698,0.2192697516); +#112698 = AXIS2_PLACEMENT_3D('',#112699,#112700,#112701); +#112699 = CARTESIAN_POINT('',(-0.30032442045,1.85,0.530776333563)); +#112700 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112701 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#112702 = PCURVE('',#112397,#112703); +#112703 = DEFINITIONAL_REPRESENTATION('',(#112704),#112707); +#112704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112705,#112706), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#110313 = CARTESIAN_POINT('',(1.591299156552,8.15)); -#110314 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#110315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#112705 = CARTESIAN_POINT('',(1.591299156552,8.15)); +#112706 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#112707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110316 = PCURVE('',#91893,#110317); -#110317 = DEFINITIONAL_REPRESENTATION('',(#110318),#110326); -#110318 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110319,#110320,#110321, - #110322,#110323,#110324,#110325),.UNSPECIFIED.,.T.,.F.) +#112708 = PCURVE('',#94285,#112709); +#112709 = DEFINITIONAL_REPRESENTATION('',(#112710),#112718); +#112710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112711,#112712,#112713, + #112714,#112715,#112716,#112717),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#110319 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#110320 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#110321 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#110322 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#110323 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#110324 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#110325 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#110326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110327 = ADVANCED_FACE('',(#110328),#91865,.T.); -#110328 = FACE_BOUND('',#110329,.T.); -#110329 = EDGE_LOOP('',(#110330,#110351,#110352,#110373)); -#110330 = ORIENTED_EDGE('',*,*,#110331,.F.); -#110331 = EDGE_CURVE('',#110139,#91822,#110332,.T.); -#110332 = SURFACE_CURVE('',#110333,(#110337,#110344),.PCURVE_S1.); -#110333 = LINE('',#110334,#110335); -#110334 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.65)); -#110335 = VECTOR('',#110336,1.); -#110336 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#110337 = PCURVE('',#91865,#110338); -#110338 = DEFINITIONAL_REPRESENTATION('',(#110339),#110343); -#110339 = LINE('',#110340,#110341); -#110340 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#110341 = VECTOR('',#110342,1.); -#110342 = DIRECTION('',(-1.,2.995851623787E-063)); -#110343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110344 = PCURVE('',#91837,#110345); -#110345 = DEFINITIONAL_REPRESENTATION('',(#110346),#110350); -#110346 = LINE('',#110347,#110348); -#110347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110348 = VECTOR('',#110349,1.); -#110349 = DIRECTION('',(-3.563627120235E-016,1.)); -#110350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110351 = ORIENTED_EDGE('',*,*,#110161,.T.); -#110352 = ORIENTED_EDGE('',*,*,#110353,.T.); -#110353 = EDGE_CURVE('',#110162,#91850,#110354,.T.); -#110354 = SURFACE_CURVE('',#110355,(#110359,#110366),.PCURVE_S1.); -#110355 = LINE('',#110356,#110357); -#110356 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); -#110357 = VECTOR('',#110358,1.); -#110358 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#110359 = PCURVE('',#91865,#110360); -#110360 = DEFINITIONAL_REPRESENTATION('',(#110361),#110365); -#110361 = LINE('',#110362,#110363); -#110362 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110363 = VECTOR('',#110364,1.); -#110364 = DIRECTION('',(-1.,2.995851623787E-063)); -#110365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110366 = PCURVE('',#91893,#110367); -#110367 = DEFINITIONAL_REPRESENTATION('',(#110368),#110372); -#110368 = LINE('',#110369,#110370); -#110369 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110370 = VECTOR('',#110371,1.); -#110371 = DIRECTION('',(3.563627120235E-016,1.)); -#110372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110373 = ORIENTED_EDGE('',*,*,#91849,.F.); -#110374 = ADVANCED_FACE('',(#110375),#91837,.T.); -#110375 = FACE_BOUND('',#110376,.T.); -#110376 = EDGE_LOOP('',(#110377,#110398,#110399,#110400,#110401,#110402, - #110423,#110424,#110425,#110426,#110427,#110428)); -#110377 = ORIENTED_EDGE('',*,*,#110378,.F.); -#110378 = EDGE_CURVE('',#110236,#91820,#110379,.T.); -#110379 = SURFACE_CURVE('',#110380,(#110384,#110391),.PCURVE_S1.); -#110380 = LINE('',#110381,#110382); -#110381 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.75)); -#110382 = VECTOR('',#110383,1.); -#110383 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#110384 = PCURVE('',#91837,#110385); -#110385 = DEFINITIONAL_REPRESENTATION('',(#110386),#110390); -#110386 = LINE('',#110387,#110388); -#110387 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#110388 = VECTOR('',#110389,1.); -#110389 = DIRECTION('',(-3.563627120235E-016,1.)); -#110390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110391 = PCURVE('',#91919,#110392); -#110392 = DEFINITIONAL_REPRESENTATION('',(#110393),#110397); -#110393 = LINE('',#110394,#110395); -#110394 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#110395 = VECTOR('',#110396,1.); -#110396 = DIRECTION('',(1.,2.995851623787E-063)); -#110397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110398 = ORIENTED_EDGE('',*,*,#110235,.T.); -#110399 = ORIENTED_EDGE('',*,*,#110038,.T.); -#110400 = ORIENTED_EDGE('',*,*,#109958,.T.); -#110401 = ORIENTED_EDGE('',*,*,#109755,.T.); -#110402 = ORIENTED_EDGE('',*,*,#110403,.F.); -#110403 = EDGE_CURVE('',#109619,#109726,#110404,.T.); -#110404 = SURFACE_CURVE('',#110405,(#110409,#110416),.PCURVE_S1.); -#110405 = LINE('',#110406,#110407); -#110406 = CARTESIAN_POINT('',(-1.,1.65,1.159810404338E-002)); -#110407 = VECTOR('',#110408,1.); -#110408 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#110409 = PCURVE('',#91837,#110410); -#110410 = DEFINITIONAL_REPRESENTATION('',(#110411),#110415); -#110411 = LINE('',#110412,#110413); -#110412 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#110413 = VECTOR('',#110414,1.); -#110414 = DIRECTION('',(-1.,-2.101748079665E-016)); -#110415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110416 = PCURVE('',#109639,#110417); -#110417 = DEFINITIONAL_REPRESENTATION('',(#110418),#110422); -#110418 = LINE('',#110419,#110420); -#110419 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#110420 = VECTOR('',#110421,1.); -#110421 = DIRECTION('',(-1.194699204908E-017,1.)); -#110422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110423 = ORIENTED_EDGE('',*,*,#109701,.F.); -#110424 = ORIENTED_EDGE('',*,*,#109829,.F.); -#110425 = ORIENTED_EDGE('',*,*,#110091,.F.); -#110426 = ORIENTED_EDGE('',*,*,#110138,.F.); -#110427 = ORIENTED_EDGE('',*,*,#110331,.T.); -#110428 = ORIENTED_EDGE('',*,*,#91819,.F.); -#110429 = ADVANCED_FACE('',(#110430),#91919,.T.); -#110430 = FACE_BOUND('',#110431,.T.); -#110431 = EDGE_LOOP('',(#110432,#110453,#110454,#110455)); -#110432 = ORIENTED_EDGE('',*,*,#110433,.F.); -#110433 = EDGE_CURVE('',#110259,#91878,#110434,.T.); -#110434 = SURFACE_CURVE('',#110435,(#110439,#110446),.PCURVE_S1.); -#110435 = LINE('',#110436,#110437); -#110436 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.75)); -#110437 = VECTOR('',#110438,1.); -#110438 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#110439 = PCURVE('',#91919,#110440); -#110440 = DEFINITIONAL_REPRESENTATION('',(#110441),#110445); -#110441 = LINE('',#110442,#110443); -#110442 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110443 = VECTOR('',#110444,1.); -#110444 = DIRECTION('',(1.,2.995851623787E-063)); -#110445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110446 = PCURVE('',#91893,#110447); -#110447 = DEFINITIONAL_REPRESENTATION('',(#110448),#110452); -#110448 = LINE('',#110449,#110450); -#110449 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#110450 = VECTOR('',#110451,1.); -#110451 = DIRECTION('',(3.563627120235E-016,1.)); -#110452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110453 = ORIENTED_EDGE('',*,*,#110258,.T.); -#110454 = ORIENTED_EDGE('',*,*,#110378,.T.); -#110455 = ORIENTED_EDGE('',*,*,#91905,.F.); -#110456 = ADVANCED_FACE('',(#110457),#91893,.T.); -#110457 = FACE_BOUND('',#110458,.T.); -#110458 = EDGE_LOOP('',(#110459,#110460,#110461,#110462,#110463,#110464, - #110485,#110486,#110487,#110488,#110489,#110490)); -#110459 = ORIENTED_EDGE('',*,*,#110353,.F.); -#110460 = ORIENTED_EDGE('',*,*,#110206,.T.); -#110461 = ORIENTED_EDGE('',*,*,#110113,.T.); -#110462 = ORIENTED_EDGE('',*,*,#109857,.T.); -#110463 = ORIENTED_EDGE('',*,*,#109651,.T.); -#110464 = ORIENTED_EDGE('',*,*,#110465,.F.); -#110465 = EDGE_CURVE('',#109728,#109617,#110466,.T.); -#110466 = SURFACE_CURVE('',#110467,(#110471,#110478),.PCURVE_S1.); -#110467 = LINE('',#110468,#110469); -#110468 = CARTESIAN_POINT('',(-1.,1.85,1.159810404338E-002)); -#110469 = VECTOR('',#110470,1.); -#110470 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#110471 = PCURVE('',#91893,#110472); -#110472 = DEFINITIONAL_REPRESENTATION('',(#110473),#110477); -#110473 = LINE('',#110474,#110475); -#110474 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#110475 = VECTOR('',#110476,1.); -#110476 = DIRECTION('',(-1.,2.101748079665E-016)); -#110477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110478 = PCURVE('',#109639,#110479); -#110479 = DEFINITIONAL_REPRESENTATION('',(#110480),#110484); -#110480 = LINE('',#110481,#110482); -#110481 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#110482 = VECTOR('',#110483,1.); -#110483 = DIRECTION('',(1.194699204908E-017,-1.)); -#110484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110485 = ORIENTED_EDGE('',*,*,#109805,.F.); -#110486 = ORIENTED_EDGE('',*,*,#109908,.F.); -#110487 = ORIENTED_EDGE('',*,*,#110016,.F.); -#110488 = ORIENTED_EDGE('',*,*,#110303,.F.); -#110489 = ORIENTED_EDGE('',*,*,#110433,.T.); -#110490 = ORIENTED_EDGE('',*,*,#91877,.F.); -#110491 = ADVANCED_FACE('',(#110492),#109639,.T.); -#110492 = FACE_BOUND('',#110493,.T.); -#110493 = EDGE_LOOP('',(#110494,#110495,#110496,#110497)); -#110494 = ORIENTED_EDGE('',*,*,#110403,.T.); -#110495 = ORIENTED_EDGE('',*,*,#109725,.T.); -#110496 = ORIENTED_EDGE('',*,*,#110465,.T.); -#110497 = ORIENTED_EDGE('',*,*,#109616,.T.); -#110498 = ADVANCED_FACE('',(#110499),#110513,.F.); -#110499 = FACE_BOUND('',#110500,.T.); -#110500 = EDGE_LOOP('',(#110501,#110536,#110559,#110586)); -#110501 = ORIENTED_EDGE('',*,*,#110502,.F.); -#110502 = EDGE_CURVE('',#110503,#110505,#110507,.T.); -#110503 = VERTEX_POINT('',#110504); -#110504 = CARTESIAN_POINT('',(-1.,2.35,-0.308197125857)); -#110505 = VERTEX_POINT('',#110506); -#110506 = CARTESIAN_POINT('',(-1.,2.15,-0.308197125857)); -#110507 = SURFACE_CURVE('',#110508,(#110512,#110524),.PCURVE_S1.); -#110508 = LINE('',#110509,#110510); -#110509 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#110510 = VECTOR('',#110511,1.); -#110511 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110512 = PCURVE('',#110513,#110518); -#110513 = PLANE('',#110514); -#110514 = AXIS2_PLACEMENT_3D('',#110515,#110516,#110517); -#110515 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#110516 = DIRECTION('',(0.E+000,0.E+000,1.)); -#110517 = DIRECTION('',(1.,0.E+000,0.E+000)); -#110518 = DEFINITIONAL_REPRESENTATION('',(#110519),#110523); -#110519 = LINE('',#110520,#110521); -#110520 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#110521 = VECTOR('',#110522,1.); -#110522 = DIRECTION('',(4.440892098501E-016,-1.)); -#110523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110524 = PCURVE('',#110525,#110530); -#110525 = PLANE('',#110526); -#110526 = AXIS2_PLACEMENT_3D('',#110527,#110528,#110529); -#110527 = CARTESIAN_POINT('',(-1.,2.25,-0.258196742327)); -#110528 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#110529 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110530 = DEFINITIONAL_REPRESENTATION('',(#110531),#110535); -#110531 = LINE('',#110532,#110533); -#110532 = CARTESIAN_POINT('',(-7.75,-5.000038352949E-002)); -#110533 = VECTOR('',#110534,1.); -#110534 = DIRECTION('',(1.,0.E+000)); -#110535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110536 = ORIENTED_EDGE('',*,*,#110537,.F.); -#110537 = EDGE_CURVE('',#110538,#110503,#110540,.T.); -#110538 = VERTEX_POINT('',#110539); -#110539 = CARTESIAN_POINT('',(-0.74341632541,2.35,-0.308197125857)); -#110540 = SURFACE_CURVE('',#110541,(#110545,#110552),.PCURVE_S1.); -#110541 = LINE('',#110542,#110543); -#110542 = CARTESIAN_POINT('',(-0.74341632541,2.35,-0.308197125857)); -#110543 = VECTOR('',#110544,1.); -#110544 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#110545 = PCURVE('',#110513,#110546); -#110546 = DEFINITIONAL_REPRESENTATION('',(#110547),#110551); -#110547 = LINE('',#110548,#110549); -#110548 = CARTESIAN_POINT('',(3.330669073875E-015,-7.65)); -#110549 = VECTOR('',#110550,1.); -#110550 = DIRECTION('',(-1.,0.E+000)); -#110551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110552 = PCURVE('',#91779,#110553); -#110553 = DEFINITIONAL_REPRESENTATION('',(#110554),#110558); -#110554 = LINE('',#110555,#110556); -#110555 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#110556 = VECTOR('',#110557,1.); -#110557 = DIRECTION('',(0.E+000,-1.)); -#110558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110559 = ORIENTED_EDGE('',*,*,#110560,.F.); -#110560 = EDGE_CURVE('',#110561,#110538,#110563,.T.); -#110561 = VERTEX_POINT('',#110562); -#110562 = CARTESIAN_POINT('',(-0.74341632541,2.15,-0.308197125857)); -#110563 = SURFACE_CURVE('',#110564,(#110568,#110575),.PCURVE_S1.); -#110564 = LINE('',#110565,#110566); -#110565 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#110566 = VECTOR('',#110567,1.); -#110567 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110568 = PCURVE('',#110513,#110569); -#110569 = DEFINITIONAL_REPRESENTATION('',(#110570),#110574); -#110570 = LINE('',#110571,#110572); -#110571 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110572 = VECTOR('',#110573,1.); -#110573 = DIRECTION('',(-4.440892098501E-016,1.)); -#110574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110575 = PCURVE('',#110576,#110581); -#110576 = CYLINDRICAL_SURFACE('',#110577,0.308574064194); -#110577 = AXIS2_PLACEMENT_3D('',#110578,#110579,#110580); -#110578 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#110579 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110580 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110581 = DEFINITIONAL_REPRESENTATION('',(#110582),#110585); -#110582 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110583,#110584), - .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#110583 = CARTESIAN_POINT('',(4.761821717947,-7.85)); -#110584 = CARTESIAN_POINT('',(4.761821717947,-7.65)); -#110585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110586 = ORIENTED_EDGE('',*,*,#110587,.T.); -#110587 = EDGE_CURVE('',#110561,#110505,#110588,.T.); -#110588 = SURFACE_CURVE('',#110589,(#110593,#110600),.PCURVE_S1.); -#110589 = LINE('',#110590,#110591); -#110590 = CARTESIAN_POINT('',(-0.74341632541,2.15,-0.308197125857)); -#110591 = VECTOR('',#110592,1.); -#110592 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#110593 = PCURVE('',#110513,#110594); -#110594 = DEFINITIONAL_REPRESENTATION('',(#110595),#110599); -#110595 = LINE('',#110596,#110597); -#110596 = CARTESIAN_POINT('',(3.552713678801E-015,-7.85)); -#110597 = VECTOR('',#110598,1.); -#110598 = DIRECTION('',(-1.,0.E+000)); -#110599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110600 = PCURVE('',#91723,#110601); -#110601 = DEFINITIONAL_REPRESENTATION('',(#110602),#110606); -#110602 = LINE('',#110603,#110604); -#110603 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#110604 = VECTOR('',#110605,1.); -#110605 = DIRECTION('',(0.E+000,-1.)); -#110606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110607 = ADVANCED_FACE('',(#110608),#110622,.F.); -#110608 = FACE_BOUND('',#110609,.T.); -#110609 = EDGE_LOOP('',(#110610,#110640,#110663,#110690)); -#110610 = ORIENTED_EDGE('',*,*,#110611,.F.); -#110611 = EDGE_CURVE('',#110612,#110614,#110616,.T.); -#110612 = VERTEX_POINT('',#110613); -#110613 = CARTESIAN_POINT('',(-1.,2.15,-0.208196358798)); -#110614 = VERTEX_POINT('',#110615); -#110615 = CARTESIAN_POINT('',(-1.,2.35,-0.208196358798)); -#110616 = SURFACE_CURVE('',#110617,(#110621,#110633),.PCURVE_S1.); -#110617 = LINE('',#110618,#110619); -#110618 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#110619 = VECTOR('',#110620,1.); -#110620 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110621 = PCURVE('',#110622,#110627); -#110622 = PLANE('',#110623); -#110623 = AXIS2_PLACEMENT_3D('',#110624,#110625,#110626); -#110624 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#110625 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#110626 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#110627 = DEFINITIONAL_REPRESENTATION('',(#110628),#110632); -#110628 = LINE('',#110629,#110630); -#110629 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#110630 = VECTOR('',#110631,1.); -#110631 = DIRECTION('',(4.440892098501E-016,1.)); -#110632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110633 = PCURVE('',#110525,#110634); -#110634 = DEFINITIONAL_REPRESENTATION('',(#110635),#110639); -#110635 = LINE('',#110636,#110637); -#110636 = CARTESIAN_POINT('',(-7.75,5.000038352949E-002)); -#110637 = VECTOR('',#110638,1.); -#110638 = DIRECTION('',(-1.,0.E+000)); -#110639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110640 = ORIENTED_EDGE('',*,*,#110641,.F.); -#110641 = EDGE_CURVE('',#110642,#110612,#110644,.T.); -#110642 = VERTEX_POINT('',#110643); -#110643 = CARTESIAN_POINT('',(-0.740726081328,2.15,-0.208196358798)); -#110644 = SURFACE_CURVE('',#110645,(#110649,#110656),.PCURVE_S1.); -#110645 = LINE('',#110646,#110647); -#110646 = CARTESIAN_POINT('',(-0.740726081328,2.15,-0.208196358798)); -#110647 = VECTOR('',#110648,1.); -#110648 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#110649 = PCURVE('',#110622,#110650); -#110650 = DEFINITIONAL_REPRESENTATION('',(#110651),#110655); -#110651 = LINE('',#110652,#110653); -#110652 = CARTESIAN_POINT('',(-3.552713678801E-015,-7.85)); -#110653 = VECTOR('',#110654,1.); -#110654 = DIRECTION('',(1.,0.E+000)); -#110655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#112711 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#112712 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#112713 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#112714 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#112715 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#112716 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#112717 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#112718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110656 = PCURVE('',#91723,#110657); -#110657 = DEFINITIONAL_REPRESENTATION('',(#110658),#110662); -#110658 = LINE('',#110659,#110660); -#110659 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#110660 = VECTOR('',#110661,1.); -#110661 = DIRECTION('',(0.E+000,-1.)); -#110662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110663 = ORIENTED_EDGE('',*,*,#110664,.F.); -#110664 = EDGE_CURVE('',#110665,#110642,#110667,.T.); -#110665 = VERTEX_POINT('',#110666); -#110666 = CARTESIAN_POINT('',(-0.740726081328,2.35,-0.208196358798)); -#110667 = SURFACE_CURVE('',#110668,(#110672,#110679),.PCURVE_S1.); -#110668 = LINE('',#110669,#110670); -#110669 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#110670 = VECTOR('',#110671,1.); -#110671 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110672 = PCURVE('',#110622,#110673); -#110673 = DEFINITIONAL_REPRESENTATION('',(#110674),#110678); -#110674 = LINE('',#110675,#110676); -#110675 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110676 = VECTOR('',#110677,1.); -#110677 = DIRECTION('',(-4.440892098501E-016,-1.)); -#110678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110679 = PCURVE('',#110680,#110685); -#110680 = CYLINDRICAL_SURFACE('',#110681,0.208574704164); -#110681 = AXIS2_PLACEMENT_3D('',#110682,#110683,#110684); -#110682 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#110683 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110684 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110685 = DEFINITIONAL_REPRESENTATION('',(#110686),#110689); -#110686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110687,#110688), +#112719 = ADVANCED_FACE('',(#112720),#94257,.T.); +#112720 = FACE_BOUND('',#112721,.T.); +#112721 = EDGE_LOOP('',(#112722,#112743,#112744,#112765)); +#112722 = ORIENTED_EDGE('',*,*,#112723,.F.); +#112723 = EDGE_CURVE('',#112531,#94214,#112724,.T.); +#112724 = SURFACE_CURVE('',#112725,(#112729,#112736),.PCURVE_S1.); +#112725 = LINE('',#112726,#112727); +#112726 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.65)); +#112727 = VECTOR('',#112728,1.); +#112728 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#112729 = PCURVE('',#94257,#112730); +#112730 = DEFINITIONAL_REPRESENTATION('',(#112731),#112735); +#112731 = LINE('',#112732,#112733); +#112732 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#112733 = VECTOR('',#112734,1.); +#112734 = DIRECTION('',(-1.,2.995851623787E-063)); +#112735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112736 = PCURVE('',#94229,#112737); +#112737 = DEFINITIONAL_REPRESENTATION('',(#112738),#112742); +#112738 = LINE('',#112739,#112740); +#112739 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112740 = VECTOR('',#112741,1.); +#112741 = DIRECTION('',(-3.563627120235E-016,1.)); +#112742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112743 = ORIENTED_EDGE('',*,*,#112553,.T.); +#112744 = ORIENTED_EDGE('',*,*,#112745,.T.); +#112745 = EDGE_CURVE('',#112554,#94242,#112746,.T.); +#112746 = SURFACE_CURVE('',#112747,(#112751,#112758),.PCURVE_S1.); +#112747 = LINE('',#112748,#112749); +#112748 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.65)); +#112749 = VECTOR('',#112750,1.); +#112750 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#112751 = PCURVE('',#94257,#112752); +#112752 = DEFINITIONAL_REPRESENTATION('',(#112753),#112757); +#112753 = LINE('',#112754,#112755); +#112754 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112755 = VECTOR('',#112756,1.); +#112756 = DIRECTION('',(-1.,2.995851623787E-063)); +#112757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112758 = PCURVE('',#94285,#112759); +#112759 = DEFINITIONAL_REPRESENTATION('',(#112760),#112764); +#112760 = LINE('',#112761,#112762); +#112761 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112762 = VECTOR('',#112763,1.); +#112763 = DIRECTION('',(3.563627120235E-016,1.)); +#112764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112765 = ORIENTED_EDGE('',*,*,#94241,.F.); +#112766 = ADVANCED_FACE('',(#112767),#94229,.T.); +#112767 = FACE_BOUND('',#112768,.T.); +#112768 = EDGE_LOOP('',(#112769,#112790,#112791,#112792,#112793,#112794, + #112815,#112816,#112817,#112818,#112819,#112820)); +#112769 = ORIENTED_EDGE('',*,*,#112770,.F.); +#112770 = EDGE_CURVE('',#112628,#94212,#112771,.T.); +#112771 = SURFACE_CURVE('',#112772,(#112776,#112783),.PCURVE_S1.); +#112772 = LINE('',#112773,#112774); +#112773 = CARTESIAN_POINT('',(-0.527847992439,1.65,0.75)); +#112774 = VECTOR('',#112775,1.); +#112775 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#112776 = PCURVE('',#94229,#112777); +#112777 = DEFINITIONAL_REPRESENTATION('',(#112778),#112782); +#112778 = LINE('',#112779,#112780); +#112779 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#112780 = VECTOR('',#112781,1.); +#112781 = DIRECTION('',(-3.563627120235E-016,1.)); +#112782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112783 = PCURVE('',#94311,#112784); +#112784 = DEFINITIONAL_REPRESENTATION('',(#112785),#112789); +#112785 = LINE('',#112786,#112787); +#112786 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#112787 = VECTOR('',#112788,1.); +#112788 = DIRECTION('',(1.,2.995851623787E-063)); +#112789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112790 = ORIENTED_EDGE('',*,*,#112627,.T.); +#112791 = ORIENTED_EDGE('',*,*,#112430,.T.); +#112792 = ORIENTED_EDGE('',*,*,#112350,.T.); +#112793 = ORIENTED_EDGE('',*,*,#112147,.T.); +#112794 = ORIENTED_EDGE('',*,*,#112795,.F.); +#112795 = EDGE_CURVE('',#112011,#112118,#112796,.T.); +#112796 = SURFACE_CURVE('',#112797,(#112801,#112808),.PCURVE_S1.); +#112797 = LINE('',#112798,#112799); +#112798 = CARTESIAN_POINT('',(-1.,1.65,1.159810404338E-002)); +#112799 = VECTOR('',#112800,1.); +#112800 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#112801 = PCURVE('',#94229,#112802); +#112802 = DEFINITIONAL_REPRESENTATION('',(#112803),#112807); +#112803 = LINE('',#112804,#112805); +#112804 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#112805 = VECTOR('',#112806,1.); +#112806 = DIRECTION('',(-1.,-2.101748079665E-016)); +#112807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112808 = PCURVE('',#112031,#112809); +#112809 = DEFINITIONAL_REPRESENTATION('',(#112810),#112814); +#112810 = LINE('',#112811,#112812); +#112811 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#112812 = VECTOR('',#112813,1.); +#112813 = DIRECTION('',(-1.194699204908E-017,1.)); +#112814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112815 = ORIENTED_EDGE('',*,*,#112093,.F.); +#112816 = ORIENTED_EDGE('',*,*,#112221,.F.); +#112817 = ORIENTED_EDGE('',*,*,#112483,.F.); +#112818 = ORIENTED_EDGE('',*,*,#112530,.F.); +#112819 = ORIENTED_EDGE('',*,*,#112723,.T.); +#112820 = ORIENTED_EDGE('',*,*,#94211,.F.); +#112821 = ADVANCED_FACE('',(#112822),#94311,.T.); +#112822 = FACE_BOUND('',#112823,.T.); +#112823 = EDGE_LOOP('',(#112824,#112845,#112846,#112847)); +#112824 = ORIENTED_EDGE('',*,*,#112825,.F.); +#112825 = EDGE_CURVE('',#112651,#94270,#112826,.T.); +#112826 = SURFACE_CURVE('',#112827,(#112831,#112838),.PCURVE_S1.); +#112827 = LINE('',#112828,#112829); +#112828 = CARTESIAN_POINT('',(-0.527847992439,1.85,0.75)); +#112829 = VECTOR('',#112830,1.); +#112830 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#112831 = PCURVE('',#94311,#112832); +#112832 = DEFINITIONAL_REPRESENTATION('',(#112833),#112837); +#112833 = LINE('',#112834,#112835); +#112834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112835 = VECTOR('',#112836,1.); +#112836 = DIRECTION('',(1.,2.995851623787E-063)); +#112837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112838 = PCURVE('',#94285,#112839); +#112839 = DEFINITIONAL_REPRESENTATION('',(#112840),#112844); +#112840 = LINE('',#112841,#112842); +#112841 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#112842 = VECTOR('',#112843,1.); +#112843 = DIRECTION('',(3.563627120235E-016,1.)); +#112844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112845 = ORIENTED_EDGE('',*,*,#112650,.T.); +#112846 = ORIENTED_EDGE('',*,*,#112770,.T.); +#112847 = ORIENTED_EDGE('',*,*,#94297,.F.); +#112848 = ADVANCED_FACE('',(#112849),#94285,.T.); +#112849 = FACE_BOUND('',#112850,.T.); +#112850 = EDGE_LOOP('',(#112851,#112852,#112853,#112854,#112855,#112856, + #112877,#112878,#112879,#112880,#112881,#112882)); +#112851 = ORIENTED_EDGE('',*,*,#112745,.F.); +#112852 = ORIENTED_EDGE('',*,*,#112598,.T.); +#112853 = ORIENTED_EDGE('',*,*,#112505,.T.); +#112854 = ORIENTED_EDGE('',*,*,#112249,.T.); +#112855 = ORIENTED_EDGE('',*,*,#112043,.T.); +#112856 = ORIENTED_EDGE('',*,*,#112857,.F.); +#112857 = EDGE_CURVE('',#112120,#112009,#112858,.T.); +#112858 = SURFACE_CURVE('',#112859,(#112863,#112870),.PCURVE_S1.); +#112859 = LINE('',#112860,#112861); +#112860 = CARTESIAN_POINT('',(-1.,1.85,1.159810404338E-002)); +#112861 = VECTOR('',#112862,1.); +#112862 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#112863 = PCURVE('',#94285,#112864); +#112864 = DEFINITIONAL_REPRESENTATION('',(#112865),#112869); +#112865 = LINE('',#112866,#112867); +#112866 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#112867 = VECTOR('',#112868,1.); +#112868 = DIRECTION('',(-1.,2.101748079665E-016)); +#112869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112870 = PCURVE('',#112031,#112871); +#112871 = DEFINITIONAL_REPRESENTATION('',(#112872),#112876); +#112872 = LINE('',#112873,#112874); +#112873 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#112874 = VECTOR('',#112875,1.); +#112875 = DIRECTION('',(1.194699204908E-017,-1.)); +#112876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112877 = ORIENTED_EDGE('',*,*,#112197,.F.); +#112878 = ORIENTED_EDGE('',*,*,#112300,.F.); +#112879 = ORIENTED_EDGE('',*,*,#112408,.F.); +#112880 = ORIENTED_EDGE('',*,*,#112695,.F.); +#112881 = ORIENTED_EDGE('',*,*,#112825,.T.); +#112882 = ORIENTED_EDGE('',*,*,#94269,.F.); +#112883 = ADVANCED_FACE('',(#112884),#112031,.T.); +#112884 = FACE_BOUND('',#112885,.T.); +#112885 = EDGE_LOOP('',(#112886,#112887,#112888,#112889)); +#112886 = ORIENTED_EDGE('',*,*,#112795,.T.); +#112887 = ORIENTED_EDGE('',*,*,#112117,.T.); +#112888 = ORIENTED_EDGE('',*,*,#112857,.T.); +#112889 = ORIENTED_EDGE('',*,*,#112008,.T.); +#112890 = ADVANCED_FACE('',(#112891),#112905,.F.); +#112891 = FACE_BOUND('',#112892,.T.); +#112892 = EDGE_LOOP('',(#112893,#112928,#112951,#112978)); +#112893 = ORIENTED_EDGE('',*,*,#112894,.F.); +#112894 = EDGE_CURVE('',#112895,#112897,#112899,.T.); +#112895 = VERTEX_POINT('',#112896); +#112896 = CARTESIAN_POINT('',(-1.,2.35,-0.308197125857)); +#112897 = VERTEX_POINT('',#112898); +#112898 = CARTESIAN_POINT('',(-1.,2.15,-0.308197125857)); +#112899 = SURFACE_CURVE('',#112900,(#112904,#112916),.PCURVE_S1.); +#112900 = LINE('',#112901,#112902); +#112901 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#112902 = VECTOR('',#112903,1.); +#112903 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112904 = PCURVE('',#112905,#112910); +#112905 = PLANE('',#112906); +#112906 = AXIS2_PLACEMENT_3D('',#112907,#112908,#112909); +#112907 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#112908 = DIRECTION('',(0.E+000,0.E+000,1.)); +#112909 = DIRECTION('',(1.,0.E+000,0.E+000)); +#112910 = DEFINITIONAL_REPRESENTATION('',(#112911),#112915); +#112911 = LINE('',#112912,#112913); +#112912 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#112913 = VECTOR('',#112914,1.); +#112914 = DIRECTION('',(4.440892098501E-016,-1.)); +#112915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112916 = PCURVE('',#112917,#112922); +#112917 = PLANE('',#112918); +#112918 = AXIS2_PLACEMENT_3D('',#112919,#112920,#112921); +#112919 = CARTESIAN_POINT('',(-1.,2.25,-0.258196742327)); +#112920 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#112921 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#112922 = DEFINITIONAL_REPRESENTATION('',(#112923),#112927); +#112923 = LINE('',#112924,#112925); +#112924 = CARTESIAN_POINT('',(-7.75,-5.000038352949E-002)); +#112925 = VECTOR('',#112926,1.); +#112926 = DIRECTION('',(1.,0.E+000)); +#112927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112928 = ORIENTED_EDGE('',*,*,#112929,.F.); +#112929 = EDGE_CURVE('',#112930,#112895,#112932,.T.); +#112930 = VERTEX_POINT('',#112931); +#112931 = CARTESIAN_POINT('',(-0.74341632541,2.35,-0.308197125857)); +#112932 = SURFACE_CURVE('',#112933,(#112937,#112944),.PCURVE_S1.); +#112933 = LINE('',#112934,#112935); +#112934 = CARTESIAN_POINT('',(-0.74341632541,2.35,-0.308197125857)); +#112935 = VECTOR('',#112936,1.); +#112936 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112937 = PCURVE('',#112905,#112938); +#112938 = DEFINITIONAL_REPRESENTATION('',(#112939),#112943); +#112939 = LINE('',#112940,#112941); +#112940 = CARTESIAN_POINT('',(3.330669073875E-015,-7.65)); +#112941 = VECTOR('',#112942,1.); +#112942 = DIRECTION('',(-1.,0.E+000)); +#112943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112944 = PCURVE('',#94171,#112945); +#112945 = DEFINITIONAL_REPRESENTATION('',(#112946),#112950); +#112946 = LINE('',#112947,#112948); +#112947 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#112948 = VECTOR('',#112949,1.); +#112949 = DIRECTION('',(0.E+000,-1.)); +#112950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112951 = ORIENTED_EDGE('',*,*,#112952,.F.); +#112952 = EDGE_CURVE('',#112953,#112930,#112955,.T.); +#112953 = VERTEX_POINT('',#112954); +#112954 = CARTESIAN_POINT('',(-0.74341632541,2.15,-0.308197125857)); +#112955 = SURFACE_CURVE('',#112956,(#112960,#112967),.PCURVE_S1.); +#112956 = LINE('',#112957,#112958); +#112957 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#112958 = VECTOR('',#112959,1.); +#112959 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112960 = PCURVE('',#112905,#112961); +#112961 = DEFINITIONAL_REPRESENTATION('',(#112962),#112966); +#112962 = LINE('',#112963,#112964); +#112963 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#112964 = VECTOR('',#112965,1.); +#112965 = DIRECTION('',(-4.440892098501E-016,1.)); +#112966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112967 = PCURVE('',#112968,#112973); +#112968 = CYLINDRICAL_SURFACE('',#112969,0.308574064194); +#112969 = AXIS2_PLACEMENT_3D('',#112970,#112971,#112972); +#112970 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#112971 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#112972 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#112973 = DEFINITIONAL_REPRESENTATION('',(#112974),#112977); +#112974 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112975,#112976), + .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); +#112975 = CARTESIAN_POINT('',(4.761821717947,-7.85)); +#112976 = CARTESIAN_POINT('',(4.761821717947,-7.65)); +#112977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112978 = ORIENTED_EDGE('',*,*,#112979,.T.); +#112979 = EDGE_CURVE('',#112953,#112897,#112980,.T.); +#112980 = SURFACE_CURVE('',#112981,(#112985,#112992),.PCURVE_S1.); +#112981 = LINE('',#112982,#112983); +#112982 = CARTESIAN_POINT('',(-0.74341632541,2.15,-0.308197125857)); +#112983 = VECTOR('',#112984,1.); +#112984 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#112985 = PCURVE('',#112905,#112986); +#112986 = DEFINITIONAL_REPRESENTATION('',(#112987),#112991); +#112987 = LINE('',#112988,#112989); +#112988 = CARTESIAN_POINT('',(3.552713678801E-015,-7.85)); +#112989 = VECTOR('',#112990,1.); +#112990 = DIRECTION('',(-1.,0.E+000)); +#112991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112992 = PCURVE('',#94115,#112993); +#112993 = DEFINITIONAL_REPRESENTATION('',(#112994),#112998); +#112994 = LINE('',#112995,#112996); +#112995 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#112996 = VECTOR('',#112997,1.); +#112997 = DIRECTION('',(0.E+000,-1.)); +#112998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#112999 = ADVANCED_FACE('',(#113000),#113014,.F.); +#113000 = FACE_BOUND('',#113001,.T.); +#113001 = EDGE_LOOP('',(#113002,#113032,#113055,#113082)); +#113002 = ORIENTED_EDGE('',*,*,#113003,.F.); +#113003 = EDGE_CURVE('',#113004,#113006,#113008,.T.); +#113004 = VERTEX_POINT('',#113005); +#113005 = CARTESIAN_POINT('',(-1.,2.15,-0.208196358798)); +#113006 = VERTEX_POINT('',#113007); +#113007 = CARTESIAN_POINT('',(-1.,2.35,-0.208196358798)); +#113008 = SURFACE_CURVE('',#113009,(#113013,#113025),.PCURVE_S1.); +#113009 = LINE('',#113010,#113011); +#113010 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#113011 = VECTOR('',#113012,1.); +#113012 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113013 = PCURVE('',#113014,#113019); +#113014 = PLANE('',#113015); +#113015 = AXIS2_PLACEMENT_3D('',#113016,#113017,#113018); +#113016 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#113017 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#113018 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113019 = DEFINITIONAL_REPRESENTATION('',(#113020),#113024); +#113020 = LINE('',#113021,#113022); +#113021 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#113022 = VECTOR('',#113023,1.); +#113023 = DIRECTION('',(4.440892098501E-016,1.)); +#113024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113025 = PCURVE('',#112917,#113026); +#113026 = DEFINITIONAL_REPRESENTATION('',(#113027),#113031); +#113027 = LINE('',#113028,#113029); +#113028 = CARTESIAN_POINT('',(-7.75,5.000038352949E-002)); +#113029 = VECTOR('',#113030,1.); +#113030 = DIRECTION('',(-1.,0.E+000)); +#113031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113032 = ORIENTED_EDGE('',*,*,#113033,.F.); +#113033 = EDGE_CURVE('',#113034,#113004,#113036,.T.); +#113034 = VERTEX_POINT('',#113035); +#113035 = CARTESIAN_POINT('',(-0.740726081328,2.15,-0.208196358798)); +#113036 = SURFACE_CURVE('',#113037,(#113041,#113048),.PCURVE_S1.); +#113037 = LINE('',#113038,#113039); +#113038 = CARTESIAN_POINT('',(-0.740726081328,2.15,-0.208196358798)); +#113039 = VECTOR('',#113040,1.); +#113040 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113041 = PCURVE('',#113014,#113042); +#113042 = DEFINITIONAL_REPRESENTATION('',(#113043),#113047); +#113043 = LINE('',#113044,#113045); +#113044 = CARTESIAN_POINT('',(-3.552713678801E-015,-7.85)); +#113045 = VECTOR('',#113046,1.); +#113046 = DIRECTION('',(1.,0.E+000)); +#113047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113048 = PCURVE('',#94115,#113049); +#113049 = DEFINITIONAL_REPRESENTATION('',(#113050),#113054); +#113050 = LINE('',#113051,#113052); +#113051 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#113052 = VECTOR('',#113053,1.); +#113053 = DIRECTION('',(0.E+000,-1.)); +#113054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113055 = ORIENTED_EDGE('',*,*,#113056,.F.); +#113056 = EDGE_CURVE('',#113057,#113034,#113059,.T.); +#113057 = VERTEX_POINT('',#113058); +#113058 = CARTESIAN_POINT('',(-0.740726081328,2.35,-0.208196358798)); +#113059 = SURFACE_CURVE('',#113060,(#113064,#113071),.PCURVE_S1.); +#113060 = LINE('',#113061,#113062); +#113061 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#113062 = VECTOR('',#113063,1.); +#113063 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113064 = PCURVE('',#113014,#113065); +#113065 = DEFINITIONAL_REPRESENTATION('',(#113066),#113070); +#113066 = LINE('',#113067,#113068); +#113067 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113068 = VECTOR('',#113069,1.); +#113069 = DIRECTION('',(-4.440892098501E-016,-1.)); +#113070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113071 = PCURVE('',#113072,#113077); +#113072 = CYLINDRICAL_SURFACE('',#113073,0.208574704164); +#113073 = AXIS2_PLACEMENT_3D('',#113074,#113075,#113076); +#113074 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#113075 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113076 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113077 = DEFINITIONAL_REPRESENTATION('',(#113078),#113081); +#113078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113079,#113080), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#110687 = CARTESIAN_POINT('',(4.772630242227,-7.65)); -#110688 = CARTESIAN_POINT('',(4.772630242227,-7.85)); -#110689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110690 = ORIENTED_EDGE('',*,*,#110691,.T.); -#110691 = EDGE_CURVE('',#110665,#110614,#110692,.T.); -#110692 = SURFACE_CURVE('',#110693,(#110697,#110704),.PCURVE_S1.); -#110693 = LINE('',#110694,#110695); -#110694 = CARTESIAN_POINT('',(-0.740726081328,2.35,-0.208196358798)); -#110695 = VECTOR('',#110696,1.); -#110696 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#110697 = PCURVE('',#110622,#110698); -#110698 = DEFINITIONAL_REPRESENTATION('',(#110699),#110703); -#110699 = LINE('',#110700,#110701); -#110700 = CARTESIAN_POINT('',(-3.330669073875E-015,-7.65)); -#110701 = VECTOR('',#110702,1.); -#110702 = DIRECTION('',(1.,0.E+000)); -#110703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110704 = PCURVE('',#91779,#110705); -#110705 = DEFINITIONAL_REPRESENTATION('',(#110706),#110710); -#110706 = LINE('',#110707,#110708); -#110707 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#110708 = VECTOR('',#110709,1.); -#110709 = DIRECTION('',(0.E+000,-1.)); -#110710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110711 = ADVANCED_FACE('',(#110712),#110576,.T.); -#110712 = FACE_BOUND('',#110713,.T.); -#110713 = EDGE_LOOP('',(#110714,#110764,#110765,#110811)); -#110714 = ORIENTED_EDGE('',*,*,#110715,.T.); -#110715 = EDGE_CURVE('',#110716,#110561,#110718,.T.); -#110716 = VERTEX_POINT('',#110717); -#110717 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.E+000)); -#110718 = SURFACE_CURVE('',#110719,(#110724,#110753),.PCURVE_S1.); -#110719 = CIRCLE('',#110720,0.308574064194); -#110720 = AXIS2_PLACEMENT_3D('',#110721,#110722,#110723); -#110721 = CARTESIAN_POINT('',(-0.728168876214,2.15,2.640924866458E-017) - ); -#110722 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110723 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110724 = PCURVE('',#110576,#110725); -#110725 = DEFINITIONAL_REPRESENTATION('',(#110726),#110752); -#110726 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110727,#110728,#110729, - #110730,#110731,#110732,#110733,#110734,#110735,#110736,#110737, - #110738,#110739,#110740,#110741,#110742,#110743,#110744,#110745, - #110746,#110747,#110748,#110749,#110750,#110751),.UNSPECIFIED.,.F., +#113079 = CARTESIAN_POINT('',(4.772630242227,-7.65)); +#113080 = CARTESIAN_POINT('',(4.772630242227,-7.85)); +#113081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113082 = ORIENTED_EDGE('',*,*,#113083,.T.); +#113083 = EDGE_CURVE('',#113057,#113006,#113084,.T.); +#113084 = SURFACE_CURVE('',#113085,(#113089,#113096),.PCURVE_S1.); +#113085 = LINE('',#113086,#113087); +#113086 = CARTESIAN_POINT('',(-0.740726081328,2.35,-0.208196358798)); +#113087 = VECTOR('',#113088,1.); +#113088 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113089 = PCURVE('',#113014,#113090); +#113090 = DEFINITIONAL_REPRESENTATION('',(#113091),#113095); +#113091 = LINE('',#113092,#113093); +#113092 = CARTESIAN_POINT('',(-3.330669073875E-015,-7.65)); +#113093 = VECTOR('',#113094,1.); +#113094 = DIRECTION('',(1.,0.E+000)); +#113095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113096 = PCURVE('',#94171,#113097); +#113097 = DEFINITIONAL_REPRESENTATION('',(#113098),#113102); +#113098 = LINE('',#113099,#113100); +#113099 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#113100 = VECTOR('',#113101,1.); +#113101 = DIRECTION('',(0.E+000,-1.)); +#113102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113103 = ADVANCED_FACE('',(#113104),#112968,.T.); +#113104 = FACE_BOUND('',#113105,.T.); +#113105 = EDGE_LOOP('',(#113106,#113156,#113157,#113203)); +#113106 = ORIENTED_EDGE('',*,*,#113107,.T.); +#113107 = EDGE_CURVE('',#113108,#112953,#113110,.T.); +#113108 = VERTEX_POINT('',#113109); +#113109 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.E+000)); +#113110 = SURFACE_CURVE('',#113111,(#113116,#113145),.PCURVE_S1.); +#113111 = CIRCLE('',#113112,0.308574064194); +#113112 = AXIS2_PLACEMENT_3D('',#113113,#113114,#113115); +#113113 = CARTESIAN_POINT('',(-0.728168876214,2.15,2.640924866458E-017) + ); +#113114 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113115 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113116 = PCURVE('',#112968,#113117); +#113117 = DEFINITIONAL_REPRESENTATION('',(#113118),#113144); +#113118 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113119,#113120,#113121, + #113122,#113123,#113124,#113125,#113126,#113127,#113128,#113129, + #113130,#113131,#113132,#113133,#113134,#113135,#113136,#113137, + #113138,#113139,#113140,#113141,#113142,#113143),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -136382,71 +139384,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#110727 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#110728 = CARTESIAN_POINT('',(3.166141578807,-7.85)); -#110729 = CARTESIAN_POINT('',(3.215239429242,-7.85)); -#110730 = CARTESIAN_POINT('',(3.288886204895,-7.85)); -#110731 = CARTESIAN_POINT('',(3.362532980548,-7.85)); -#110732 = CARTESIAN_POINT('',(3.4361797562,-7.85)); -#110733 = CARTESIAN_POINT('',(3.509826531853,-7.85)); -#110734 = CARTESIAN_POINT('',(3.583473307505,-7.85)); -#110735 = CARTESIAN_POINT('',(3.657120083158,-7.85)); -#110736 = CARTESIAN_POINT('',(3.730766858811,-7.85)); -#110737 = CARTESIAN_POINT('',(3.804413634463,-7.85)); -#110738 = CARTESIAN_POINT('',(3.878060410116,-7.85)); -#110739 = CARTESIAN_POINT('',(3.951707185768,-7.85)); -#110740 = CARTESIAN_POINT('',(4.025353961421,-7.85)); -#110741 = CARTESIAN_POINT('',(4.099000737074,-7.85)); -#110742 = CARTESIAN_POINT('',(4.172647512726,-7.85)); -#110743 = CARTESIAN_POINT('',(4.246294288379,-7.85)); -#110744 = CARTESIAN_POINT('',(4.319941064031,-7.85)); -#110745 = CARTESIAN_POINT('',(4.393587839684,-7.85)); -#110746 = CARTESIAN_POINT('',(4.467234615337,-7.85)); -#110747 = CARTESIAN_POINT('',(4.540881390989,-7.85)); -#110748 = CARTESIAN_POINT('',(4.614528166642,-7.85)); -#110749 = CARTESIAN_POINT('',(4.688174942294,-7.85)); -#110750 = CARTESIAN_POINT('',(4.737272792729,-7.85)); -#110751 = CARTESIAN_POINT('',(4.761821717947,-7.85)); -#110752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110753 = PCURVE('',#91723,#110754); -#110754 = DEFINITIONAL_REPRESENTATION('',(#110755),#110763); -#110755 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110756,#110757,#110758, - #110759,#110760,#110761,#110762),.UNSPECIFIED.,.T.,.F.) +#113119 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#113120 = CARTESIAN_POINT('',(3.166141578807,-7.85)); +#113121 = CARTESIAN_POINT('',(3.215239429242,-7.85)); +#113122 = CARTESIAN_POINT('',(3.288886204895,-7.85)); +#113123 = CARTESIAN_POINT('',(3.362532980548,-7.85)); +#113124 = CARTESIAN_POINT('',(3.4361797562,-7.85)); +#113125 = CARTESIAN_POINT('',(3.509826531853,-7.85)); +#113126 = CARTESIAN_POINT('',(3.583473307505,-7.85)); +#113127 = CARTESIAN_POINT('',(3.657120083158,-7.85)); +#113128 = CARTESIAN_POINT('',(3.730766858811,-7.85)); +#113129 = CARTESIAN_POINT('',(3.804413634463,-7.85)); +#113130 = CARTESIAN_POINT('',(3.878060410116,-7.85)); +#113131 = CARTESIAN_POINT('',(3.951707185768,-7.85)); +#113132 = CARTESIAN_POINT('',(4.025353961421,-7.85)); +#113133 = CARTESIAN_POINT('',(4.099000737074,-7.85)); +#113134 = CARTESIAN_POINT('',(4.172647512726,-7.85)); +#113135 = CARTESIAN_POINT('',(4.246294288379,-7.85)); +#113136 = CARTESIAN_POINT('',(4.319941064031,-7.85)); +#113137 = CARTESIAN_POINT('',(4.393587839684,-7.85)); +#113138 = CARTESIAN_POINT('',(4.467234615337,-7.85)); +#113139 = CARTESIAN_POINT('',(4.540881390989,-7.85)); +#113140 = CARTESIAN_POINT('',(4.614528166642,-7.85)); +#113141 = CARTESIAN_POINT('',(4.688174942294,-7.85)); +#113142 = CARTESIAN_POINT('',(4.737272792729,-7.85)); +#113143 = CARTESIAN_POINT('',(4.761821717947,-7.85)); +#113144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113145 = PCURVE('',#94115,#113146); +#113146 = DEFINITIONAL_REPRESENTATION('',(#113147),#113155); +#113147 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113148,#113149,#113150, + #113151,#113152,#113153,#113154),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#110756 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#110757 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#110758 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#110759 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#110760 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#110761 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#110762 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#110763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110764 = ORIENTED_EDGE('',*,*,#110560,.T.); -#110765 = ORIENTED_EDGE('',*,*,#110766,.F.); -#110766 = EDGE_CURVE('',#110767,#110538,#110769,.T.); -#110767 = VERTEX_POINT('',#110768); -#110768 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.E+000)); -#110769 = SURFACE_CURVE('',#110770,(#110775,#110804),.PCURVE_S1.); -#110770 = CIRCLE('',#110771,0.308574064194); -#110771 = AXIS2_PLACEMENT_3D('',#110772,#110773,#110774); -#110772 = CARTESIAN_POINT('',(-0.728168876214,2.35,2.640924866458E-017) - ); -#110773 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110774 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110775 = PCURVE('',#110576,#110776); -#110776 = DEFINITIONAL_REPRESENTATION('',(#110777),#110803); -#110777 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#110778,#110779,#110780, - #110781,#110782,#110783,#110784,#110785,#110786,#110787,#110788, - #110789,#110790,#110791,#110792,#110793,#110794,#110795,#110796, - #110797,#110798,#110799,#110800,#110801,#110802),.UNSPECIFIED.,.F., +#113148 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#113149 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#113150 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#113151 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#113152 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#113153 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#113154 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#113155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113156 = ORIENTED_EDGE('',*,*,#112952,.T.); +#113157 = ORIENTED_EDGE('',*,*,#113158,.F.); +#113158 = EDGE_CURVE('',#113159,#112930,#113161,.T.); +#113159 = VERTEX_POINT('',#113160); +#113160 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.E+000)); +#113161 = SURFACE_CURVE('',#113162,(#113167,#113196),.PCURVE_S1.); +#113162 = CIRCLE('',#113163,0.308574064194); +#113163 = AXIS2_PLACEMENT_3D('',#113164,#113165,#113166); +#113164 = CARTESIAN_POINT('',(-0.728168876214,2.35,2.640924866458E-017) + ); +#113165 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113166 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113167 = PCURVE('',#112968,#113168); +#113168 = DEFINITIONAL_REPRESENTATION('',(#113169),#113195); +#113169 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113170,#113171,#113172, + #113173,#113174,#113175,#113176,#113177,#113178,#113179,#113180, + #113181,#113182,#113183,#113184,#113185,#113186,#113187,#113188, + #113189,#113190,#113191,#113192,#113193,#113194),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -136454,401 +139456,401 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#110778 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#110779 = CARTESIAN_POINT('',(3.166141578807,-7.65)); -#110780 = CARTESIAN_POINT('',(3.215239429242,-7.65)); -#110781 = CARTESIAN_POINT('',(3.288886204895,-7.65)); -#110782 = CARTESIAN_POINT('',(3.362532980548,-7.65)); -#110783 = CARTESIAN_POINT('',(3.4361797562,-7.65)); -#110784 = CARTESIAN_POINT('',(3.509826531853,-7.65)); -#110785 = CARTESIAN_POINT('',(3.583473307505,-7.65)); -#110786 = CARTESIAN_POINT('',(3.657120083158,-7.65)); -#110787 = CARTESIAN_POINT('',(3.730766858811,-7.65)); -#110788 = CARTESIAN_POINT('',(3.804413634463,-7.65)); -#110789 = CARTESIAN_POINT('',(3.878060410116,-7.65)); -#110790 = CARTESIAN_POINT('',(3.951707185768,-7.65)); -#110791 = CARTESIAN_POINT('',(4.025353961421,-7.65)); -#110792 = CARTESIAN_POINT('',(4.099000737074,-7.65)); -#110793 = CARTESIAN_POINT('',(4.172647512726,-7.65)); -#110794 = CARTESIAN_POINT('',(4.246294288379,-7.65)); -#110795 = CARTESIAN_POINT('',(4.319941064031,-7.65)); -#110796 = CARTESIAN_POINT('',(4.393587839684,-7.65)); -#110797 = CARTESIAN_POINT('',(4.467234615337,-7.65)); -#110798 = CARTESIAN_POINT('',(4.540881390989,-7.65)); -#110799 = CARTESIAN_POINT('',(4.614528166642,-7.65)); -#110800 = CARTESIAN_POINT('',(4.688174942294,-7.65)); -#110801 = CARTESIAN_POINT('',(4.737272792729,-7.65)); -#110802 = CARTESIAN_POINT('',(4.761821717947,-7.65)); -#110803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110804 = PCURVE('',#91779,#110805); -#110805 = DEFINITIONAL_REPRESENTATION('',(#110806),#110810); -#110806 = CIRCLE('',#110807,0.308574064194); -#110807 = AXIS2_PLACEMENT_2D('',#110808,#110809); -#110808 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#110809 = DIRECTION('',(0.E+000,-1.)); -#110810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110811 = ORIENTED_EDGE('',*,*,#110812,.T.); -#110812 = EDGE_CURVE('',#110767,#110716,#110813,.T.); -#110813 = SURFACE_CURVE('',#110814,(#110818,#110824),.PCURVE_S1.); -#110814 = LINE('',#110815,#110816); -#110815 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#110816 = VECTOR('',#110817,1.); -#110817 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110818 = PCURVE('',#110576,#110819); -#110819 = DEFINITIONAL_REPRESENTATION('',(#110820),#110823); -#110820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110821,#110822), +#113170 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#113171 = CARTESIAN_POINT('',(3.166141578807,-7.65)); +#113172 = CARTESIAN_POINT('',(3.215239429242,-7.65)); +#113173 = CARTESIAN_POINT('',(3.288886204895,-7.65)); +#113174 = CARTESIAN_POINT('',(3.362532980548,-7.65)); +#113175 = CARTESIAN_POINT('',(3.4361797562,-7.65)); +#113176 = CARTESIAN_POINT('',(3.509826531853,-7.65)); +#113177 = CARTESIAN_POINT('',(3.583473307505,-7.65)); +#113178 = CARTESIAN_POINT('',(3.657120083158,-7.65)); +#113179 = CARTESIAN_POINT('',(3.730766858811,-7.65)); +#113180 = CARTESIAN_POINT('',(3.804413634463,-7.65)); +#113181 = CARTESIAN_POINT('',(3.878060410116,-7.65)); +#113182 = CARTESIAN_POINT('',(3.951707185768,-7.65)); +#113183 = CARTESIAN_POINT('',(4.025353961421,-7.65)); +#113184 = CARTESIAN_POINT('',(4.099000737074,-7.65)); +#113185 = CARTESIAN_POINT('',(4.172647512726,-7.65)); +#113186 = CARTESIAN_POINT('',(4.246294288379,-7.65)); +#113187 = CARTESIAN_POINT('',(4.319941064031,-7.65)); +#113188 = CARTESIAN_POINT('',(4.393587839684,-7.65)); +#113189 = CARTESIAN_POINT('',(4.467234615337,-7.65)); +#113190 = CARTESIAN_POINT('',(4.540881390989,-7.65)); +#113191 = CARTESIAN_POINT('',(4.614528166642,-7.65)); +#113192 = CARTESIAN_POINT('',(4.688174942294,-7.65)); +#113193 = CARTESIAN_POINT('',(4.737272792729,-7.65)); +#113194 = CARTESIAN_POINT('',(4.761821717947,-7.65)); +#113195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113196 = PCURVE('',#94171,#113197); +#113197 = DEFINITIONAL_REPRESENTATION('',(#113198),#113202); +#113198 = CIRCLE('',#113199,0.308574064194); +#113199 = AXIS2_PLACEMENT_2D('',#113200,#113201); +#113200 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#113201 = DIRECTION('',(0.E+000,-1.)); +#113202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113203 = ORIENTED_EDGE('',*,*,#113204,.T.); +#113204 = EDGE_CURVE('',#113159,#113108,#113205,.T.); +#113205 = SURFACE_CURVE('',#113206,(#113210,#113216),.PCURVE_S1.); +#113206 = LINE('',#113207,#113208); +#113207 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#113208 = VECTOR('',#113209,1.); +#113209 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113210 = PCURVE('',#112968,#113211); +#113211 = DEFINITIONAL_REPRESENTATION('',(#113212),#113215); +#113212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113213,#113214), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#110821 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#110822 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#110823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110824 = PCURVE('',#110825,#110830); -#110825 = PLANE('',#110826); -#110826 = AXIS2_PLACEMENT_3D('',#110827,#110828,#110829); -#110827 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#110828 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#110829 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110830 = DEFINITIONAL_REPRESENTATION('',(#110831),#110835); -#110831 = LINE('',#110832,#110833); -#110832 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#110833 = VECTOR('',#110834,1.); -#110834 = DIRECTION('',(-1.,0.E+000)); -#110835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110836 = ADVANCED_FACE('',(#110837),#110680,.F.); -#110837 = FACE_BOUND('',#110838,.F.); -#110838 = EDGE_LOOP('',(#110839,#110862,#110889,#110914)); -#110839 = ORIENTED_EDGE('',*,*,#110840,.F.); -#110840 = EDGE_CURVE('',#110841,#110665,#110843,.T.); -#110841 = VERTEX_POINT('',#110842); -#110842 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.E+000)); -#110843 = SURFACE_CURVE('',#110844,(#110849,#110855),.PCURVE_S1.); -#110844 = CIRCLE('',#110845,0.208574704164); -#110845 = AXIS2_PLACEMENT_3D('',#110846,#110847,#110848); -#110846 = CARTESIAN_POINT('',(-0.728168876214,2.35,2.640924866458E-017) - ); -#110847 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110848 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110849 = PCURVE('',#110680,#110850); -#110850 = DEFINITIONAL_REPRESENTATION('',(#110851),#110854); -#110851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110852,#110853), +#113213 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#113214 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#113215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113216 = PCURVE('',#113217,#113222); +#113217 = PLANE('',#113218); +#113218 = AXIS2_PLACEMENT_3D('',#113219,#113220,#113221); +#113219 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#113220 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#113221 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113222 = DEFINITIONAL_REPRESENTATION('',(#113223),#113227); +#113223 = LINE('',#113224,#113225); +#113224 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#113225 = VECTOR('',#113226,1.); +#113226 = DIRECTION('',(-1.,0.E+000)); +#113227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113228 = ADVANCED_FACE('',(#113229),#113072,.F.); +#113229 = FACE_BOUND('',#113230,.F.); +#113230 = EDGE_LOOP('',(#113231,#113254,#113281,#113306)); +#113231 = ORIENTED_EDGE('',*,*,#113232,.F.); +#113232 = EDGE_CURVE('',#113233,#113057,#113235,.T.); +#113233 = VERTEX_POINT('',#113234); +#113234 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.E+000)); +#113235 = SURFACE_CURVE('',#113236,(#113241,#113247),.PCURVE_S1.); +#113236 = CIRCLE('',#113237,0.208574704164); +#113237 = AXIS2_PLACEMENT_3D('',#113238,#113239,#113240); +#113238 = CARTESIAN_POINT('',(-0.728168876214,2.35,2.640924866458E-017) + ); +#113239 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113240 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113241 = PCURVE('',#113072,#113242); +#113242 = DEFINITIONAL_REPRESENTATION('',(#113243),#113246); +#113243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113244,#113245), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#110852 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#110853 = CARTESIAN_POINT('',(4.772630242227,-7.65)); -#110854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110855 = PCURVE('',#91779,#110856); -#110856 = DEFINITIONAL_REPRESENTATION('',(#110857),#110861); -#110857 = CIRCLE('',#110858,0.208574704164); -#110858 = AXIS2_PLACEMENT_2D('',#110859,#110860); -#110859 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#110860 = DIRECTION('',(0.E+000,-1.)); -#110861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110862 = ORIENTED_EDGE('',*,*,#110863,.F.); -#110863 = EDGE_CURVE('',#110864,#110841,#110866,.T.); -#110864 = VERTEX_POINT('',#110865); -#110865 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.E+000)); -#110866 = SURFACE_CURVE('',#110867,(#110871,#110877),.PCURVE_S1.); -#110867 = LINE('',#110868,#110869); -#110868 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#110869 = VECTOR('',#110870,1.); -#110870 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110871 = PCURVE('',#110680,#110872); -#110872 = DEFINITIONAL_REPRESENTATION('',(#110873),#110876); -#110873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110874,#110875), +#113244 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#113245 = CARTESIAN_POINT('',(4.772630242227,-7.65)); +#113246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113247 = PCURVE('',#94171,#113248); +#113248 = DEFINITIONAL_REPRESENTATION('',(#113249),#113253); +#113249 = CIRCLE('',#113250,0.208574704164); +#113250 = AXIS2_PLACEMENT_2D('',#113251,#113252); +#113251 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#113252 = DIRECTION('',(0.E+000,-1.)); +#113253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113254 = ORIENTED_EDGE('',*,*,#113255,.F.); +#113255 = EDGE_CURVE('',#113256,#113233,#113258,.T.); +#113256 = VERTEX_POINT('',#113257); +#113257 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.E+000)); +#113258 = SURFACE_CURVE('',#113259,(#113263,#113269),.PCURVE_S1.); +#113259 = LINE('',#113260,#113261); +#113260 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#113261 = VECTOR('',#113262,1.); +#113262 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113263 = PCURVE('',#113072,#113264); +#113264 = DEFINITIONAL_REPRESENTATION('',(#113265),#113268); +#113265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113266,#113267), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#110874 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#110875 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#110876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113266 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#113267 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#113268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110877 = PCURVE('',#110878,#110883); -#110878 = PLANE('',#110879); -#110879 = AXIS2_PLACEMENT_3D('',#110880,#110881,#110882); -#110880 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#110881 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#110882 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110883 = DEFINITIONAL_REPRESENTATION('',(#110884),#110888); -#110884 = LINE('',#110885,#110886); -#110885 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#110886 = VECTOR('',#110887,1.); -#110887 = DIRECTION('',(-1.,0.E+000)); -#110888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110889 = ORIENTED_EDGE('',*,*,#110890,.T.); -#110890 = EDGE_CURVE('',#110864,#110642,#110891,.T.); -#110891 = SURFACE_CURVE('',#110892,(#110897,#110903),.PCURVE_S1.); -#110892 = CIRCLE('',#110893,0.208574704164); -#110893 = AXIS2_PLACEMENT_3D('',#110894,#110895,#110896); -#110894 = CARTESIAN_POINT('',(-0.728168876214,2.15,2.640924866458E-017) - ); -#110895 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110896 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#110897 = PCURVE('',#110680,#110898); -#110898 = DEFINITIONAL_REPRESENTATION('',(#110899),#110902); -#110899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110900,#110901), +#113269 = PCURVE('',#113270,#113275); +#113270 = PLANE('',#113271); +#113271 = AXIS2_PLACEMENT_3D('',#113272,#113273,#113274); +#113272 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#113273 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#113274 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113275 = DEFINITIONAL_REPRESENTATION('',(#113276),#113280); +#113276 = LINE('',#113277,#113278); +#113277 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#113278 = VECTOR('',#113279,1.); +#113279 = DIRECTION('',(-1.,0.E+000)); +#113280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113281 = ORIENTED_EDGE('',*,*,#113282,.T.); +#113282 = EDGE_CURVE('',#113256,#113034,#113283,.T.); +#113283 = SURFACE_CURVE('',#113284,(#113289,#113295),.PCURVE_S1.); +#113284 = CIRCLE('',#113285,0.208574704164); +#113285 = AXIS2_PLACEMENT_3D('',#113286,#113287,#113288); +#113286 = CARTESIAN_POINT('',(-0.728168876214,2.15,2.640924866458E-017) + ); +#113287 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113288 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113289 = PCURVE('',#113072,#113290); +#113290 = DEFINITIONAL_REPRESENTATION('',(#113291),#113294); +#113291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113292,#113293), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#110900 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#110901 = CARTESIAN_POINT('',(4.772630242227,-7.85)); -#110902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113292 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#113293 = CARTESIAN_POINT('',(4.772630242227,-7.85)); +#113294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110903 = PCURVE('',#91723,#110904); -#110904 = DEFINITIONAL_REPRESENTATION('',(#110905),#110913); -#110905 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#110906,#110907,#110908, - #110909,#110910,#110911,#110912),.UNSPECIFIED.,.T.,.F.) +#113295 = PCURVE('',#94115,#113296); +#113296 = DEFINITIONAL_REPRESENTATION('',(#113297),#113305); +#113297 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113298,#113299,#113300, + #113301,#113302,#113303,#113304),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#110906 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#110907 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#110908 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#110909 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#110910 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#110911 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#110912 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#110913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110914 = ORIENTED_EDGE('',*,*,#110664,.F.); -#110915 = ADVANCED_FACE('',(#110916),#110878,.T.); -#110916 = FACE_BOUND('',#110917,.T.); -#110917 = EDGE_LOOP('',(#110918,#110947,#110968,#110969)); -#110918 = ORIENTED_EDGE('',*,*,#110919,.T.); -#110919 = EDGE_CURVE('',#110920,#110922,#110924,.T.); -#110920 = VERTEX_POINT('',#110921); -#110921 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.530776333563)); -#110922 = VERTEX_POINT('',#110923); -#110923 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.530776333563)); -#110924 = SURFACE_CURVE('',#110925,(#110929,#110936),.PCURVE_S1.); -#110925 = LINE('',#110926,#110927); -#110926 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#110927 = VECTOR('',#110928,1.); -#110928 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#110929 = PCURVE('',#110878,#110930); -#110930 = DEFINITIONAL_REPRESENTATION('',(#110931),#110935); -#110931 = LINE('',#110932,#110933); -#110932 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#110933 = VECTOR('',#110934,1.); -#110934 = DIRECTION('',(-1.,0.E+000)); -#110935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110936 = PCURVE('',#110937,#110942); -#110937 = CYLINDRICAL_SURFACE('',#110938,0.2192697516); -#110938 = AXIS2_PLACEMENT_3D('',#110939,#110940,#110941); -#110939 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#110940 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#110941 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#110942 = DEFINITIONAL_REPRESENTATION('',(#110943),#110946); -#110943 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#110944,#110945), +#113298 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#113299 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#113300 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#113301 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#113302 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#113303 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#113304 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#113305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113306 = ORIENTED_EDGE('',*,*,#113056,.F.); +#113307 = ADVANCED_FACE('',(#113308),#113270,.T.); +#113308 = FACE_BOUND('',#113309,.T.); +#113309 = EDGE_LOOP('',(#113310,#113339,#113360,#113361)); +#113310 = ORIENTED_EDGE('',*,*,#113311,.T.); +#113311 = EDGE_CURVE('',#113312,#113314,#113316,.T.); +#113312 = VERTEX_POINT('',#113313); +#113313 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.530776333563)); +#113314 = VERTEX_POINT('',#113315); +#113315 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.530776333563)); +#113316 = SURFACE_CURVE('',#113317,(#113321,#113328),.PCURVE_S1.); +#113317 = LINE('',#113318,#113319); +#113318 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#113319 = VECTOR('',#113320,1.); +#113320 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113321 = PCURVE('',#113270,#113322); +#113322 = DEFINITIONAL_REPRESENTATION('',(#113323),#113327); +#113323 = LINE('',#113324,#113325); +#113324 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113325 = VECTOR('',#113326,1.); +#113326 = DIRECTION('',(-1.,0.E+000)); +#113327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113328 = PCURVE('',#113329,#113334); +#113329 = CYLINDRICAL_SURFACE('',#113330,0.2192697516); +#113330 = AXIS2_PLACEMENT_3D('',#113331,#113332,#113333); +#113331 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#113332 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113333 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113334 = DEFINITIONAL_REPRESENTATION('',(#113335),#113338); +#113335 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113336,#113337), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#110944 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#110945 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#110946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113336 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#113337 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#113338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113339 = ORIENTED_EDGE('',*,*,#113340,.T.); +#113340 = EDGE_CURVE('',#113314,#113233,#113341,.T.); +#113341 = SURFACE_CURVE('',#113342,(#113346,#113353),.PCURVE_S1.); +#113342 = LINE('',#113343,#113344); +#113343 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.530776333563)); +#113344 = VECTOR('',#113345,1.); +#113345 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#113346 = PCURVE('',#113270,#113347); +#113347 = DEFINITIONAL_REPRESENTATION('',(#113348),#113352); +#113348 = LINE('',#113349,#113350); +#113349 = CARTESIAN_POINT('',(7.65,4.535643882845E-033)); +#113350 = VECTOR('',#113351,1.); +#113351 = DIRECTION('',(-4.535643882845E-032,-1.)); +#113352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113353 = PCURVE('',#94171,#113354); +#113354 = DEFINITIONAL_REPRESENTATION('',(#113355),#113359); +#113355 = LINE('',#113356,#113357); +#113356 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#113357 = VECTOR('',#113358,1.); +#113358 = DIRECTION('',(-1.,-1.021336205033E-016)); +#113359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113360 = ORIENTED_EDGE('',*,*,#113255,.F.); +#113361 = ORIENTED_EDGE('',*,*,#113362,.F.); +#113362 = EDGE_CURVE('',#113312,#113256,#113363,.T.); +#113363 = SURFACE_CURVE('',#113364,(#113368,#113375),.PCURVE_S1.); +#113364 = LINE('',#113365,#113366); +#113365 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.530776333563)); +#113366 = VECTOR('',#113367,1.); +#113367 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#113368 = PCURVE('',#113270,#113369); +#113369 = DEFINITIONAL_REPRESENTATION('',(#113370),#113374); +#113370 = LINE('',#113371,#113372); +#113371 = CARTESIAN_POINT('',(7.85,-4.535643882845E-033)); +#113372 = VECTOR('',#113373,1.); +#113373 = DIRECTION('',(-4.535643882845E-032,-1.)); +#113374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113375 = PCURVE('',#94115,#113376); +#113376 = DEFINITIONAL_REPRESENTATION('',(#113377),#113381); +#113377 = LINE('',#113378,#113379); +#113378 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#113379 = VECTOR('',#113380,1.); +#113380 = DIRECTION('',(1.,-1.021336205033E-016)); +#113381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#110947 = ORIENTED_EDGE('',*,*,#110948,.T.); -#110948 = EDGE_CURVE('',#110922,#110841,#110949,.T.); -#110949 = SURFACE_CURVE('',#110950,(#110954,#110961),.PCURVE_S1.); -#110950 = LINE('',#110951,#110952); -#110951 = CARTESIAN_POINT('',(-0.51959417205,2.35,0.530776333563)); -#110952 = VECTOR('',#110953,1.); -#110953 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110954 = PCURVE('',#110878,#110955); -#110955 = DEFINITIONAL_REPRESENTATION('',(#110956),#110960); -#110956 = LINE('',#110957,#110958); -#110957 = CARTESIAN_POINT('',(7.65,4.535643882845E-033)); -#110958 = VECTOR('',#110959,1.); -#110959 = DIRECTION('',(-4.535643882845E-032,-1.)); -#110960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110961 = PCURVE('',#91779,#110962); -#110962 = DEFINITIONAL_REPRESENTATION('',(#110963),#110967); -#110963 = LINE('',#110964,#110965); -#110964 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#110965 = VECTOR('',#110966,1.); -#110966 = DIRECTION('',(-1.,-1.021336205033E-016)); -#110967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110968 = ORIENTED_EDGE('',*,*,#110863,.F.); -#110969 = ORIENTED_EDGE('',*,*,#110970,.F.); -#110970 = EDGE_CURVE('',#110920,#110864,#110971,.T.); -#110971 = SURFACE_CURVE('',#110972,(#110976,#110983),.PCURVE_S1.); -#110972 = LINE('',#110973,#110974); -#110973 = CARTESIAN_POINT('',(-0.51959417205,2.15,0.530776333563)); -#110974 = VECTOR('',#110975,1.); -#110975 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#110976 = PCURVE('',#110878,#110977); -#110977 = DEFINITIONAL_REPRESENTATION('',(#110978),#110982); -#110978 = LINE('',#110979,#110980); -#110979 = CARTESIAN_POINT('',(7.85,-4.535643882845E-033)); -#110980 = VECTOR('',#110981,1.); -#110981 = DIRECTION('',(-4.535643882845E-032,-1.)); -#110982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110983 = PCURVE('',#91723,#110984); -#110984 = DEFINITIONAL_REPRESENTATION('',(#110985),#110989); -#110985 = LINE('',#110986,#110987); -#110986 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#110987 = VECTOR('',#110988,1.); -#110988 = DIRECTION('',(1.,-1.021336205033E-016)); -#110989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#110990 = ADVANCED_FACE('',(#110991),#110825,.T.); -#110991 = FACE_BOUND('',#110992,.T.); -#110992 = EDGE_LOOP('',(#110993,#111022,#111043,#111044)); -#110993 = ORIENTED_EDGE('',*,*,#110994,.T.); -#110994 = EDGE_CURVE('',#110995,#110997,#110999,.T.); -#110995 = VERTEX_POINT('',#110996); -#110996 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.530776333563)); -#110997 = VERTEX_POINT('',#110998); -#110998 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.530776333563)); -#110999 = SURFACE_CURVE('',#111000,(#111004,#111011),.PCURVE_S1.); -#111000 = LINE('',#111001,#111002); -#111001 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#111002 = VECTOR('',#111003,1.); -#111003 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111004 = PCURVE('',#110825,#111005); -#111005 = DEFINITIONAL_REPRESENTATION('',(#111006),#111010); -#111006 = LINE('',#111007,#111008); -#111007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111008 = VECTOR('',#111009,1.); -#111009 = DIRECTION('',(-1.,0.E+000)); -#111010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113382 = ADVANCED_FACE('',(#113383),#113217,.T.); +#113383 = FACE_BOUND('',#113384,.T.); +#113384 = EDGE_LOOP('',(#113385,#113414,#113435,#113436)); +#113385 = ORIENTED_EDGE('',*,*,#113386,.T.); +#113386 = EDGE_CURVE('',#113387,#113389,#113391,.T.); +#113387 = VERTEX_POINT('',#113388); +#113388 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.530776333563)); +#113389 = VERTEX_POINT('',#113390); +#113390 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.530776333563)); +#113391 = SURFACE_CURVE('',#113392,(#113396,#113403),.PCURVE_S1.); +#113392 = LINE('',#113393,#113394); +#113393 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#113394 = VECTOR('',#113395,1.); +#113395 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113396 = PCURVE('',#113217,#113397); +#113397 = DEFINITIONAL_REPRESENTATION('',(#113398),#113402); +#113398 = LINE('',#113399,#113400); +#113399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113400 = VECTOR('',#113401,1.); +#113401 = DIRECTION('',(-1.,0.E+000)); +#113402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111011 = PCURVE('',#111012,#111017); -#111012 = CYLINDRICAL_SURFACE('',#111013,0.119270391569); -#111013 = AXIS2_PLACEMENT_3D('',#111014,#111015,#111016); -#111014 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#111015 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111016 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111017 = DEFINITIONAL_REPRESENTATION('',(#111018),#111021); -#111018 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111019,#111020), +#113403 = PCURVE('',#113404,#113409); +#113404 = CYLINDRICAL_SURFACE('',#113405,0.119270391569); +#113405 = AXIS2_PLACEMENT_3D('',#113406,#113407,#113408); +#113406 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#113407 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113408 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113409 = DEFINITIONAL_REPRESENTATION('',(#113410),#113413); +#113410 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113411,#113412), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#111019 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#111020 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#111021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111022 = ORIENTED_EDGE('',*,*,#111023,.T.); -#111023 = EDGE_CURVE('',#110997,#110716,#111024,.T.); -#111024 = SURFACE_CURVE('',#111025,(#111029,#111036),.PCURVE_S1.); -#111025 = LINE('',#111026,#111027); -#111026 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.530776333563)); -#111027 = VECTOR('',#111028,1.); -#111028 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#111029 = PCURVE('',#110825,#111030); -#111030 = DEFINITIONAL_REPRESENTATION('',(#111031),#111035); -#111031 = LINE('',#111032,#111033); -#111032 = CARTESIAN_POINT('',(-7.85,1.133910970711E-033)); -#111033 = VECTOR('',#111034,1.); -#111034 = DIRECTION('',(4.535643882845E-032,-1.)); -#111035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113411 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#113412 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#113413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113414 = ORIENTED_EDGE('',*,*,#113415,.T.); +#113415 = EDGE_CURVE('',#113389,#113108,#113416,.T.); +#113416 = SURFACE_CURVE('',#113417,(#113421,#113428),.PCURVE_S1.); +#113417 = LINE('',#113418,#113419); +#113418 = CARTESIAN_POINT('',(-0.419594812019,2.15,0.530776333563)); +#113419 = VECTOR('',#113420,1.); +#113420 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#113421 = PCURVE('',#113217,#113422); +#113422 = DEFINITIONAL_REPRESENTATION('',(#113423),#113427); +#113423 = LINE('',#113424,#113425); +#113424 = CARTESIAN_POINT('',(-7.85,1.133910970711E-033)); +#113425 = VECTOR('',#113426,1.); +#113426 = DIRECTION('',(4.535643882845E-032,-1.)); +#113427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113428 = PCURVE('',#94115,#113429); +#113429 = DEFINITIONAL_REPRESENTATION('',(#113430),#113434); +#113430 = LINE('',#113431,#113432); +#113431 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#113432 = VECTOR('',#113433,1.); +#113433 = DIRECTION('',(1.,-1.021336205033E-016)); +#113434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113435 = ORIENTED_EDGE('',*,*,#113204,.F.); +#113436 = ORIENTED_EDGE('',*,*,#113437,.F.); +#113437 = EDGE_CURVE('',#113387,#113159,#113438,.T.); +#113438 = SURFACE_CURVE('',#113439,(#113443,#113450),.PCURVE_S1.); +#113439 = LINE('',#113440,#113441); +#113440 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.530776333563)); +#113441 = VECTOR('',#113442,1.); +#113442 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#113443 = PCURVE('',#113217,#113444); +#113444 = DEFINITIONAL_REPRESENTATION('',(#113445),#113449); +#113445 = LINE('',#113446,#113447); +#113446 = CARTESIAN_POINT('',(-7.65,-1.133910970711E-033)); +#113447 = VECTOR('',#113448,1.); +#113448 = DIRECTION('',(4.535643882845E-032,-1.)); +#113449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113450 = PCURVE('',#94171,#113451); +#113451 = DEFINITIONAL_REPRESENTATION('',(#113452),#113456); +#113452 = LINE('',#113453,#113454); +#113453 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#113454 = VECTOR('',#113455,1.); +#113455 = DIRECTION('',(-1.,-1.021336205033E-016)); +#113456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113457 = ADVANCED_FACE('',(#113458),#113404,.F.); +#113458 = FACE_BOUND('',#113459,.F.); +#113459 = EDGE_LOOP('',(#113460,#113461,#113484,#113529)); +#113460 = ORIENTED_EDGE('',*,*,#113386,.T.); +#113461 = ORIENTED_EDGE('',*,*,#113462,.F.); +#113462 = EDGE_CURVE('',#113463,#113389,#113465,.T.); +#113463 = VERTEX_POINT('',#113464); +#113464 = CARTESIAN_POINT('',(-0.303662633502,2.15,0.65)); +#113465 = SURFACE_CURVE('',#113466,(#113471,#113477),.PCURVE_S1.); +#113466 = CIRCLE('',#113467,0.119270391569); +#113467 = AXIS2_PLACEMENT_3D('',#113468,#113469,#113470); +#113468 = CARTESIAN_POINT('',(-0.30032442045,2.15,0.530776333563)); +#113469 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113470 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113471 = PCURVE('',#113404,#113472); +#113472 = DEFINITIONAL_REPRESENTATION('',(#113473),#113476); +#113473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113474,#113475), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), + .PIECEWISE_BEZIER_KNOTS.); +#113474 = CARTESIAN_POINT('',(1.598788597134,7.85)); +#113475 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#113476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111036 = PCURVE('',#91723,#111037); -#111037 = DEFINITIONAL_REPRESENTATION('',(#111038),#111042); -#111038 = LINE('',#111039,#111040); -#111039 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#111040 = VECTOR('',#111041,1.); -#111041 = DIRECTION('',(1.,-1.021336205033E-016)); -#111042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113477 = PCURVE('',#94115,#113478); +#113478 = DEFINITIONAL_REPRESENTATION('',(#113479),#113483); +#113479 = CIRCLE('',#113480,0.119270391569); +#113480 = AXIS2_PLACEMENT_2D('',#113481,#113482); +#113481 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#113482 = DIRECTION('',(0.E+000,1.)); +#113483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111043 = ORIENTED_EDGE('',*,*,#110812,.F.); -#111044 = ORIENTED_EDGE('',*,*,#111045,.F.); -#111045 = EDGE_CURVE('',#110995,#110767,#111046,.T.); -#111046 = SURFACE_CURVE('',#111047,(#111051,#111058),.PCURVE_S1.); -#111047 = LINE('',#111048,#111049); -#111048 = CARTESIAN_POINT('',(-0.419594812019,2.35,0.530776333563)); -#111049 = VECTOR('',#111050,1.); -#111050 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#111051 = PCURVE('',#110825,#111052); -#111052 = DEFINITIONAL_REPRESENTATION('',(#111053),#111057); -#111053 = LINE('',#111054,#111055); -#111054 = CARTESIAN_POINT('',(-7.65,-1.133910970711E-033)); -#111055 = VECTOR('',#111056,1.); -#111056 = DIRECTION('',(4.535643882845E-032,-1.)); -#111057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111058 = PCURVE('',#91779,#111059); -#111059 = DEFINITIONAL_REPRESENTATION('',(#111060),#111064); -#111060 = LINE('',#111061,#111062); -#111061 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#111062 = VECTOR('',#111063,1.); -#111063 = DIRECTION('',(-1.,-1.021336205033E-016)); -#111064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111065 = ADVANCED_FACE('',(#111066),#111012,.F.); -#111066 = FACE_BOUND('',#111067,.F.); -#111067 = EDGE_LOOP('',(#111068,#111069,#111092,#111137)); -#111068 = ORIENTED_EDGE('',*,*,#110994,.T.); -#111069 = ORIENTED_EDGE('',*,*,#111070,.F.); -#111070 = EDGE_CURVE('',#111071,#110997,#111073,.T.); -#111071 = VERTEX_POINT('',#111072); -#111072 = CARTESIAN_POINT('',(-0.303662633502,2.15,0.65)); -#111073 = SURFACE_CURVE('',#111074,(#111079,#111085),.PCURVE_S1.); -#111074 = CIRCLE('',#111075,0.119270391569); -#111075 = AXIS2_PLACEMENT_3D('',#111076,#111077,#111078); -#111076 = CARTESIAN_POINT('',(-0.30032442045,2.15,0.530776333563)); -#111077 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111078 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111079 = PCURVE('',#111012,#111080); -#111080 = DEFINITIONAL_REPRESENTATION('',(#111081),#111084); -#111081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111082,#111083), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), - .PIECEWISE_BEZIER_KNOTS.); -#111082 = CARTESIAN_POINT('',(1.598788597134,7.85)); -#111083 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#111084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111085 = PCURVE('',#91723,#111086); -#111086 = DEFINITIONAL_REPRESENTATION('',(#111087),#111091); -#111087 = CIRCLE('',#111088,0.119270391569); -#111088 = AXIS2_PLACEMENT_2D('',#111089,#111090); -#111089 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#111090 = DIRECTION('',(0.E+000,1.)); -#111091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111092 = ORIENTED_EDGE('',*,*,#111093,.T.); -#111093 = EDGE_CURVE('',#111071,#111094,#111096,.T.); -#111094 = VERTEX_POINT('',#111095); -#111095 = CARTESIAN_POINT('',(-0.303662633502,2.35,0.65)); -#111096 = SURFACE_CURVE('',#111097,(#111101,#111130),.PCURVE_S1.); -#111097 = LINE('',#111098,#111099); -#111098 = CARTESIAN_POINT('',(-0.303662633502,2.35,0.65)); -#111099 = VECTOR('',#111100,1.); -#111100 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111101 = PCURVE('',#111012,#111102); -#111102 = DEFINITIONAL_REPRESENTATION('',(#111103),#111129); -#111103 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111104,#111105,#111106, - #111107,#111108,#111109,#111110,#111111,#111112,#111113,#111114, - #111115,#111116,#111117,#111118,#111119,#111120,#111121,#111122, - #111123,#111124,#111125,#111126,#111127,#111128),.UNSPECIFIED.,.F., +#113484 = ORIENTED_EDGE('',*,*,#113485,.T.); +#113485 = EDGE_CURVE('',#113463,#113486,#113488,.T.); +#113486 = VERTEX_POINT('',#113487); +#113487 = CARTESIAN_POINT('',(-0.303662633502,2.35,0.65)); +#113488 = SURFACE_CURVE('',#113489,(#113493,#113522),.PCURVE_S1.); +#113489 = LINE('',#113490,#113491); +#113490 = CARTESIAN_POINT('',(-0.303662633502,2.35,0.65)); +#113491 = VECTOR('',#113492,1.); +#113492 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113493 = PCURVE('',#113404,#113494); +#113494 = DEFINITIONAL_REPRESENTATION('',(#113495),#113521); +#113495 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113496,#113497,#113498, + #113499,#113500,#113501,#113502,#113503,#113504,#113505,#113506, + #113507,#113508,#113509,#113510,#113511,#113512,#113513,#113514, + #113515,#113516,#113517,#113518,#113519,#113520),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -136857,100 +139859,100 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#111104 = CARTESIAN_POINT('',(1.598788597134,7.85)); -#111105 = CARTESIAN_POINT('',(1.598788597134,7.84696969697)); -#111106 = CARTESIAN_POINT('',(1.598788597134,7.840909090909)); -#111107 = CARTESIAN_POINT('',(1.598788597134,7.831818181818)); -#111108 = CARTESIAN_POINT('',(1.598788597134,7.822727272727)); -#111109 = CARTESIAN_POINT('',(1.598788597134,7.813636363636)); -#111110 = CARTESIAN_POINT('',(1.598788597134,7.804545454545)); -#111111 = CARTESIAN_POINT('',(1.598788597134,7.795454545455)); -#111112 = CARTESIAN_POINT('',(1.598788597134,7.786363636364)); -#111113 = CARTESIAN_POINT('',(1.598788597134,7.777272727273)); -#111114 = CARTESIAN_POINT('',(1.598788597134,7.768181818182)); -#111115 = CARTESIAN_POINT('',(1.598788597134,7.759090909091)); -#111116 = CARTESIAN_POINT('',(1.598788597134,7.75)); -#111117 = CARTESIAN_POINT('',(1.598788597134,7.740909090909)); -#111118 = CARTESIAN_POINT('',(1.598788597134,7.731818181818)); -#111119 = CARTESIAN_POINT('',(1.598788597134,7.722727272727)); -#111120 = CARTESIAN_POINT('',(1.598788597134,7.713636363636)); -#111121 = CARTESIAN_POINT('',(1.598788597134,7.704545454545)); -#111122 = CARTESIAN_POINT('',(1.598788597134,7.695454545455)); -#111123 = CARTESIAN_POINT('',(1.598788597134,7.686363636364)); -#111124 = CARTESIAN_POINT('',(1.598788597134,7.677272727273)); -#111125 = CARTESIAN_POINT('',(1.598788597134,7.668181818182)); -#111126 = CARTESIAN_POINT('',(1.598788597134,7.659090909091)); -#111127 = CARTESIAN_POINT('',(1.598788597134,7.65303030303)); -#111128 = CARTESIAN_POINT('',(1.598788597134,7.65)); -#111129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111130 = PCURVE('',#91751,#111131); -#111131 = DEFINITIONAL_REPRESENTATION('',(#111132),#111136); -#111132 = LINE('',#111133,#111134); -#111133 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#111134 = VECTOR('',#111135,1.); -#111135 = DIRECTION('',(4.440892098501E-016,1.)); -#111136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111137 = ORIENTED_EDGE('',*,*,#111138,.T.); -#111138 = EDGE_CURVE('',#111094,#110995,#111139,.T.); -#111139 = SURFACE_CURVE('',#111140,(#111145,#111151),.PCURVE_S1.); -#111140 = CIRCLE('',#111141,0.119270391569); -#111141 = AXIS2_PLACEMENT_3D('',#111142,#111143,#111144); -#111142 = CARTESIAN_POINT('',(-0.30032442045,2.35,0.530776333563)); -#111143 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111144 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111145 = PCURVE('',#111012,#111146); -#111146 = DEFINITIONAL_REPRESENTATION('',(#111147),#111150); -#111147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111148,#111149), +#113496 = CARTESIAN_POINT('',(1.598788597134,7.85)); +#113497 = CARTESIAN_POINT('',(1.598788597134,7.84696969697)); +#113498 = CARTESIAN_POINT('',(1.598788597134,7.840909090909)); +#113499 = CARTESIAN_POINT('',(1.598788597134,7.831818181818)); +#113500 = CARTESIAN_POINT('',(1.598788597134,7.822727272727)); +#113501 = CARTESIAN_POINT('',(1.598788597134,7.813636363636)); +#113502 = CARTESIAN_POINT('',(1.598788597134,7.804545454545)); +#113503 = CARTESIAN_POINT('',(1.598788597134,7.795454545455)); +#113504 = CARTESIAN_POINT('',(1.598788597134,7.786363636364)); +#113505 = CARTESIAN_POINT('',(1.598788597134,7.777272727273)); +#113506 = CARTESIAN_POINT('',(1.598788597134,7.768181818182)); +#113507 = CARTESIAN_POINT('',(1.598788597134,7.759090909091)); +#113508 = CARTESIAN_POINT('',(1.598788597134,7.75)); +#113509 = CARTESIAN_POINT('',(1.598788597134,7.740909090909)); +#113510 = CARTESIAN_POINT('',(1.598788597134,7.731818181818)); +#113511 = CARTESIAN_POINT('',(1.598788597134,7.722727272727)); +#113512 = CARTESIAN_POINT('',(1.598788597134,7.713636363636)); +#113513 = CARTESIAN_POINT('',(1.598788597134,7.704545454545)); +#113514 = CARTESIAN_POINT('',(1.598788597134,7.695454545455)); +#113515 = CARTESIAN_POINT('',(1.598788597134,7.686363636364)); +#113516 = CARTESIAN_POINT('',(1.598788597134,7.677272727273)); +#113517 = CARTESIAN_POINT('',(1.598788597134,7.668181818182)); +#113518 = CARTESIAN_POINT('',(1.598788597134,7.659090909091)); +#113519 = CARTESIAN_POINT('',(1.598788597134,7.65303030303)); +#113520 = CARTESIAN_POINT('',(1.598788597134,7.65)); +#113521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113522 = PCURVE('',#94143,#113523); +#113523 = DEFINITIONAL_REPRESENTATION('',(#113524),#113528); +#113524 = LINE('',#113525,#113526); +#113525 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#113526 = VECTOR('',#113527,1.); +#113527 = DIRECTION('',(4.440892098501E-016,1.)); +#113528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113529 = ORIENTED_EDGE('',*,*,#113530,.T.); +#113530 = EDGE_CURVE('',#113486,#113387,#113531,.T.); +#113531 = SURFACE_CURVE('',#113532,(#113537,#113543),.PCURVE_S1.); +#113532 = CIRCLE('',#113533,0.119270391569); +#113533 = AXIS2_PLACEMENT_3D('',#113534,#113535,#113536); +#113534 = CARTESIAN_POINT('',(-0.30032442045,2.35,0.530776333563)); +#113535 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113536 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113537 = PCURVE('',#113404,#113538); +#113538 = DEFINITIONAL_REPRESENTATION('',(#113539),#113542); +#113539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113540,#113541), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#111148 = CARTESIAN_POINT('',(1.598788597134,7.65)); -#111149 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#111150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113540 = CARTESIAN_POINT('',(1.598788597134,7.65)); +#113541 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#113542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111151 = PCURVE('',#91779,#111152); -#111152 = DEFINITIONAL_REPRESENTATION('',(#111153),#111161); -#111153 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111154,#111155,#111156, - #111157,#111158,#111159,#111160),.UNSPECIFIED.,.T.,.F.) +#113543 = PCURVE('',#94171,#113544); +#113544 = DEFINITIONAL_REPRESENTATION('',(#113545),#113553); +#113545 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113546,#113547,#113548, + #113549,#113550,#113551,#113552),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#111154 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#111155 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#111156 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#111157 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#111158 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#111159 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#111160 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#111161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111162 = ADVANCED_FACE('',(#111163),#110937,.T.); -#111163 = FACE_BOUND('',#111164,.T.); -#111164 = EDGE_LOOP('',(#111165,#111166,#111212,#111257)); -#111165 = ORIENTED_EDGE('',*,*,#110919,.F.); -#111166 = ORIENTED_EDGE('',*,*,#111167,.F.); -#111167 = EDGE_CURVE('',#111168,#110920,#111170,.T.); -#111168 = VERTEX_POINT('',#111169); -#111169 = CARTESIAN_POINT('',(-0.304819755875,2.15,0.75)); -#111170 = SURFACE_CURVE('',#111171,(#111176,#111205),.PCURVE_S1.); -#111171 = CIRCLE('',#111172,0.2192697516); -#111172 = AXIS2_PLACEMENT_3D('',#111173,#111174,#111175); -#111173 = CARTESIAN_POINT('',(-0.30032442045,2.15,0.530776333563)); -#111174 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111175 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111176 = PCURVE('',#110937,#111177); -#111177 = DEFINITIONAL_REPRESENTATION('',(#111178),#111204); -#111178 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111179,#111180,#111181, - #111182,#111183,#111184,#111185,#111186,#111187,#111188,#111189, - #111190,#111191,#111192,#111193,#111194,#111195,#111196,#111197, - #111198,#111199,#111200,#111201,#111202,#111203),.UNSPECIFIED.,.F., +#113546 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#113547 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#113548 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#113549 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#113550 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#113551 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#113552 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#113553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113554 = ADVANCED_FACE('',(#113555),#113329,.T.); +#113555 = FACE_BOUND('',#113556,.T.); +#113556 = EDGE_LOOP('',(#113557,#113558,#113604,#113649)); +#113557 = ORIENTED_EDGE('',*,*,#113311,.F.); +#113558 = ORIENTED_EDGE('',*,*,#113559,.F.); +#113559 = EDGE_CURVE('',#113560,#113312,#113562,.T.); +#113560 = VERTEX_POINT('',#113561); +#113561 = CARTESIAN_POINT('',(-0.304819755875,2.15,0.75)); +#113562 = SURFACE_CURVE('',#113563,(#113568,#113597),.PCURVE_S1.); +#113563 = CIRCLE('',#113564,0.2192697516); +#113564 = AXIS2_PLACEMENT_3D('',#113565,#113566,#113567); +#113565 = CARTESIAN_POINT('',(-0.30032442045,2.15,0.530776333563)); +#113566 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113567 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113568 = PCURVE('',#113329,#113569); +#113569 = DEFINITIONAL_REPRESENTATION('',(#113570),#113596); +#113570 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113571,#113572,#113573, + #113574,#113575,#113576,#113577,#113578,#113579,#113580,#113581, + #113582,#113583,#113584,#113585,#113586,#113587,#113588,#113589, + #113590,#113591,#113592,#113593,#113594,#113595),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -136958,58 +139960,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#111179 = CARTESIAN_POINT('',(1.591299156552,7.85)); -#111180 = CARTESIAN_POINT('',(1.614788451962,7.85)); -#111181 = CARTESIAN_POINT('',(1.661767042781,7.85)); -#111182 = CARTESIAN_POINT('',(1.73223492901,7.85)); -#111183 = CARTESIAN_POINT('',(1.802702815239,7.85)); -#111184 = CARTESIAN_POINT('',(1.873170701468,7.85)); -#111185 = CARTESIAN_POINT('',(1.943638587697,7.85)); -#111186 = CARTESIAN_POINT('',(2.014106473926,7.85)); -#111187 = CARTESIAN_POINT('',(2.084574360155,7.85)); -#111188 = CARTESIAN_POINT('',(2.155042246384,7.85)); -#111189 = CARTESIAN_POINT('',(2.225510132613,7.85)); -#111190 = CARTESIAN_POINT('',(2.295978018842,7.85)); -#111191 = CARTESIAN_POINT('',(2.366445905071,7.85)); -#111192 = CARTESIAN_POINT('',(2.4369137913,7.85)); -#111193 = CARTESIAN_POINT('',(2.507381677529,7.85)); -#111194 = CARTESIAN_POINT('',(2.577849563758,7.85)); -#111195 = CARTESIAN_POINT('',(2.648317449987,7.85)); -#111196 = CARTESIAN_POINT('',(2.718785336216,7.85)); -#111197 = CARTESIAN_POINT('',(2.789253222445,7.85)); -#111198 = CARTESIAN_POINT('',(2.859721108674,7.85)); -#111199 = CARTESIAN_POINT('',(2.930188994903,7.85)); -#111200 = CARTESIAN_POINT('',(3.000656881132,7.85)); -#111201 = CARTESIAN_POINT('',(3.071124767361,7.85)); -#111202 = CARTESIAN_POINT('',(3.11810335818,7.85)); -#111203 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#111204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111205 = PCURVE('',#91723,#111206); -#111206 = DEFINITIONAL_REPRESENTATION('',(#111207),#111211); -#111207 = CIRCLE('',#111208,0.2192697516); -#111208 = AXIS2_PLACEMENT_2D('',#111209,#111210); -#111209 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#111210 = DIRECTION('',(0.E+000,1.)); -#111211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111212 = ORIENTED_EDGE('',*,*,#111213,.F.); -#111213 = EDGE_CURVE('',#111214,#111168,#111216,.T.); -#111214 = VERTEX_POINT('',#111215); -#111215 = CARTESIAN_POINT('',(-0.304819755875,2.35,0.75)); -#111216 = SURFACE_CURVE('',#111217,(#111221,#111250),.PCURVE_S1.); -#111217 = LINE('',#111218,#111219); -#111218 = CARTESIAN_POINT('',(-0.304819755875,2.35,0.75)); -#111219 = VECTOR('',#111220,1.); -#111220 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111221 = PCURVE('',#110937,#111222); -#111222 = DEFINITIONAL_REPRESENTATION('',(#111223),#111249); -#111223 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111224,#111225,#111226, - #111227,#111228,#111229,#111230,#111231,#111232,#111233,#111234, - #111235,#111236,#111237,#111238,#111239,#111240,#111241,#111242, - #111243,#111244,#111245,#111246,#111247,#111248),.UNSPECIFIED.,.F., +#113571 = CARTESIAN_POINT('',(1.591299156552,7.85)); +#113572 = CARTESIAN_POINT('',(1.614788451962,7.85)); +#113573 = CARTESIAN_POINT('',(1.661767042781,7.85)); +#113574 = CARTESIAN_POINT('',(1.73223492901,7.85)); +#113575 = CARTESIAN_POINT('',(1.802702815239,7.85)); +#113576 = CARTESIAN_POINT('',(1.873170701468,7.85)); +#113577 = CARTESIAN_POINT('',(1.943638587697,7.85)); +#113578 = CARTESIAN_POINT('',(2.014106473926,7.85)); +#113579 = CARTESIAN_POINT('',(2.084574360155,7.85)); +#113580 = CARTESIAN_POINT('',(2.155042246384,7.85)); +#113581 = CARTESIAN_POINT('',(2.225510132613,7.85)); +#113582 = CARTESIAN_POINT('',(2.295978018842,7.85)); +#113583 = CARTESIAN_POINT('',(2.366445905071,7.85)); +#113584 = CARTESIAN_POINT('',(2.4369137913,7.85)); +#113585 = CARTESIAN_POINT('',(2.507381677529,7.85)); +#113586 = CARTESIAN_POINT('',(2.577849563758,7.85)); +#113587 = CARTESIAN_POINT('',(2.648317449987,7.85)); +#113588 = CARTESIAN_POINT('',(2.718785336216,7.85)); +#113589 = CARTESIAN_POINT('',(2.789253222445,7.85)); +#113590 = CARTESIAN_POINT('',(2.859721108674,7.85)); +#113591 = CARTESIAN_POINT('',(2.930188994903,7.85)); +#113592 = CARTESIAN_POINT('',(3.000656881132,7.85)); +#113593 = CARTESIAN_POINT('',(3.071124767361,7.85)); +#113594 = CARTESIAN_POINT('',(3.11810335818,7.85)); +#113595 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#113596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113597 = PCURVE('',#94115,#113598); +#113598 = DEFINITIONAL_REPRESENTATION('',(#113599),#113603); +#113599 = CIRCLE('',#113600,0.2192697516); +#113600 = AXIS2_PLACEMENT_2D('',#113601,#113602); +#113601 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#113602 = DIRECTION('',(0.E+000,1.)); +#113603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113604 = ORIENTED_EDGE('',*,*,#113605,.F.); +#113605 = EDGE_CURVE('',#113606,#113560,#113608,.T.); +#113606 = VERTEX_POINT('',#113607); +#113607 = CARTESIAN_POINT('',(-0.304819755875,2.35,0.75)); +#113608 = SURFACE_CURVE('',#113609,(#113613,#113642),.PCURVE_S1.); +#113609 = LINE('',#113610,#113611); +#113610 = CARTESIAN_POINT('',(-0.304819755875,2.35,0.75)); +#113611 = VECTOR('',#113612,1.); +#113612 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113613 = PCURVE('',#113329,#113614); +#113614 = DEFINITIONAL_REPRESENTATION('',(#113615),#113641); +#113615 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113616,#113617,#113618, + #113619,#113620,#113621,#113622,#113623,#113624,#113625,#113626, + #113627,#113628,#113629,#113630,#113631,#113632,#113633,#113634, + #113635,#113636,#113637,#113638,#113639,#113640),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -137018,57 +140020,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#111224 = CARTESIAN_POINT('',(1.591299156552,7.65)); -#111225 = CARTESIAN_POINT('',(1.591299156552,7.65303030303)); -#111226 = CARTESIAN_POINT('',(1.591299156552,7.659090909091)); -#111227 = CARTESIAN_POINT('',(1.591299156552,7.668181818182)); -#111228 = CARTESIAN_POINT('',(1.591299156552,7.677272727273)); -#111229 = CARTESIAN_POINT('',(1.591299156552,7.686363636364)); -#111230 = CARTESIAN_POINT('',(1.591299156552,7.695454545455)); -#111231 = CARTESIAN_POINT('',(1.591299156552,7.704545454545)); -#111232 = CARTESIAN_POINT('',(1.591299156552,7.713636363636)); -#111233 = CARTESIAN_POINT('',(1.591299156552,7.722727272727)); -#111234 = CARTESIAN_POINT('',(1.591299156552,7.731818181818)); -#111235 = CARTESIAN_POINT('',(1.591299156552,7.740909090909)); -#111236 = CARTESIAN_POINT('',(1.591299156552,7.75)); -#111237 = CARTESIAN_POINT('',(1.591299156552,7.759090909091)); -#111238 = CARTESIAN_POINT('',(1.591299156552,7.768181818182)); -#111239 = CARTESIAN_POINT('',(1.591299156552,7.777272727273)); -#111240 = CARTESIAN_POINT('',(1.591299156552,7.786363636364)); -#111241 = CARTESIAN_POINT('',(1.591299156552,7.795454545455)); -#111242 = CARTESIAN_POINT('',(1.591299156552,7.804545454545)); -#111243 = CARTESIAN_POINT('',(1.591299156552,7.813636363636)); -#111244 = CARTESIAN_POINT('',(1.591299156552,7.822727272727)); -#111245 = CARTESIAN_POINT('',(1.591299156552,7.831818181818)); -#111246 = CARTESIAN_POINT('',(1.591299156552,7.840909090909)); -#111247 = CARTESIAN_POINT('',(1.591299156552,7.84696969697)); -#111248 = CARTESIAN_POINT('',(1.591299156552,7.85)); -#111249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111250 = PCURVE('',#91805,#111251); -#111251 = DEFINITIONAL_REPRESENTATION('',(#111252),#111256); -#111252 = LINE('',#111253,#111254); -#111253 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#111254 = VECTOR('',#111255,1.); -#111255 = DIRECTION('',(4.440892098501E-016,-1.)); -#111256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111257 = ORIENTED_EDGE('',*,*,#111258,.T.); -#111258 = EDGE_CURVE('',#111214,#110922,#111259,.T.); -#111259 = SURFACE_CURVE('',#111260,(#111265,#111294),.PCURVE_S1.); -#111260 = CIRCLE('',#111261,0.2192697516); -#111261 = AXIS2_PLACEMENT_3D('',#111262,#111263,#111264); -#111262 = CARTESIAN_POINT('',(-0.30032442045,2.35,0.530776333563)); -#111263 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111264 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111265 = PCURVE('',#110937,#111266); -#111266 = DEFINITIONAL_REPRESENTATION('',(#111267),#111293); -#111267 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111268,#111269,#111270, - #111271,#111272,#111273,#111274,#111275,#111276,#111277,#111278, - #111279,#111280,#111281,#111282,#111283,#111284,#111285,#111286, - #111287,#111288,#111289,#111290,#111291,#111292),.UNSPECIFIED.,.F., +#113616 = CARTESIAN_POINT('',(1.591299156552,7.65)); +#113617 = CARTESIAN_POINT('',(1.591299156552,7.65303030303)); +#113618 = CARTESIAN_POINT('',(1.591299156552,7.659090909091)); +#113619 = CARTESIAN_POINT('',(1.591299156552,7.668181818182)); +#113620 = CARTESIAN_POINT('',(1.591299156552,7.677272727273)); +#113621 = CARTESIAN_POINT('',(1.591299156552,7.686363636364)); +#113622 = CARTESIAN_POINT('',(1.591299156552,7.695454545455)); +#113623 = CARTESIAN_POINT('',(1.591299156552,7.704545454545)); +#113624 = CARTESIAN_POINT('',(1.591299156552,7.713636363636)); +#113625 = CARTESIAN_POINT('',(1.591299156552,7.722727272727)); +#113626 = CARTESIAN_POINT('',(1.591299156552,7.731818181818)); +#113627 = CARTESIAN_POINT('',(1.591299156552,7.740909090909)); +#113628 = CARTESIAN_POINT('',(1.591299156552,7.75)); +#113629 = CARTESIAN_POINT('',(1.591299156552,7.759090909091)); +#113630 = CARTESIAN_POINT('',(1.591299156552,7.768181818182)); +#113631 = CARTESIAN_POINT('',(1.591299156552,7.777272727273)); +#113632 = CARTESIAN_POINT('',(1.591299156552,7.786363636364)); +#113633 = CARTESIAN_POINT('',(1.591299156552,7.795454545455)); +#113634 = CARTESIAN_POINT('',(1.591299156552,7.804545454545)); +#113635 = CARTESIAN_POINT('',(1.591299156552,7.813636363636)); +#113636 = CARTESIAN_POINT('',(1.591299156552,7.822727272727)); +#113637 = CARTESIAN_POINT('',(1.591299156552,7.831818181818)); +#113638 = CARTESIAN_POINT('',(1.591299156552,7.840909090909)); +#113639 = CARTESIAN_POINT('',(1.591299156552,7.84696969697)); +#113640 = CARTESIAN_POINT('',(1.591299156552,7.85)); +#113641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113642 = PCURVE('',#94197,#113643); +#113643 = DEFINITIONAL_REPRESENTATION('',(#113644),#113648); +#113644 = LINE('',#113645,#113646); +#113645 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#113646 = VECTOR('',#113647,1.); +#113647 = DIRECTION('',(4.440892098501E-016,-1.)); +#113648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113649 = ORIENTED_EDGE('',*,*,#113650,.T.); +#113650 = EDGE_CURVE('',#113606,#113314,#113651,.T.); +#113651 = SURFACE_CURVE('',#113652,(#113657,#113686),.PCURVE_S1.); +#113652 = CIRCLE('',#113653,0.2192697516); +#113653 = AXIS2_PLACEMENT_3D('',#113654,#113655,#113656); +#113654 = CARTESIAN_POINT('',(-0.30032442045,2.35,0.530776333563)); +#113655 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113656 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#113657 = PCURVE('',#113329,#113658); +#113658 = DEFINITIONAL_REPRESENTATION('',(#113659),#113685); +#113659 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113660,#113661,#113662, + #113663,#113664,#113665,#113666,#113667,#113668,#113669,#113670, + #113671,#113672,#113673,#113674,#113675,#113676,#113677,#113678, + #113679,#113680,#113681,#113682,#113683,#113684),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -137076,558 +140078,558 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#111268 = CARTESIAN_POINT('',(1.591299156552,7.65)); -#111269 = CARTESIAN_POINT('',(1.614788451962,7.65)); -#111270 = CARTESIAN_POINT('',(1.661767042781,7.65)); -#111271 = CARTESIAN_POINT('',(1.73223492901,7.65)); -#111272 = CARTESIAN_POINT('',(1.802702815239,7.65)); -#111273 = CARTESIAN_POINT('',(1.873170701468,7.65)); -#111274 = CARTESIAN_POINT('',(1.943638587697,7.65)); -#111275 = CARTESIAN_POINT('',(2.014106473926,7.65)); -#111276 = CARTESIAN_POINT('',(2.084574360155,7.65)); -#111277 = CARTESIAN_POINT('',(2.155042246384,7.65)); -#111278 = CARTESIAN_POINT('',(2.225510132613,7.65)); -#111279 = CARTESIAN_POINT('',(2.295978018842,7.65)); -#111280 = CARTESIAN_POINT('',(2.366445905071,7.65)); -#111281 = CARTESIAN_POINT('',(2.4369137913,7.65)); -#111282 = CARTESIAN_POINT('',(2.507381677529,7.65)); -#111283 = CARTESIAN_POINT('',(2.577849563758,7.65)); -#111284 = CARTESIAN_POINT('',(2.648317449987,7.65)); -#111285 = CARTESIAN_POINT('',(2.718785336216,7.65)); -#111286 = CARTESIAN_POINT('',(2.789253222445,7.65)); -#111287 = CARTESIAN_POINT('',(2.859721108674,7.65)); -#111288 = CARTESIAN_POINT('',(2.930188994903,7.65)); -#111289 = CARTESIAN_POINT('',(3.000656881132,7.65)); -#111290 = CARTESIAN_POINT('',(3.071124767361,7.65)); -#111291 = CARTESIAN_POINT('',(3.11810335818,7.65)); -#111292 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#111293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111294 = PCURVE('',#91779,#111295); -#111295 = DEFINITIONAL_REPRESENTATION('',(#111296),#111304); -#111296 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111297,#111298,#111299, - #111300,#111301,#111302,#111303),.UNSPECIFIED.,.T.,.F.) +#113660 = CARTESIAN_POINT('',(1.591299156552,7.65)); +#113661 = CARTESIAN_POINT('',(1.614788451962,7.65)); +#113662 = CARTESIAN_POINT('',(1.661767042781,7.65)); +#113663 = CARTESIAN_POINT('',(1.73223492901,7.65)); +#113664 = CARTESIAN_POINT('',(1.802702815239,7.65)); +#113665 = CARTESIAN_POINT('',(1.873170701468,7.65)); +#113666 = CARTESIAN_POINT('',(1.943638587697,7.65)); +#113667 = CARTESIAN_POINT('',(2.014106473926,7.65)); +#113668 = CARTESIAN_POINT('',(2.084574360155,7.65)); +#113669 = CARTESIAN_POINT('',(2.155042246384,7.65)); +#113670 = CARTESIAN_POINT('',(2.225510132613,7.65)); +#113671 = CARTESIAN_POINT('',(2.295978018842,7.65)); +#113672 = CARTESIAN_POINT('',(2.366445905071,7.65)); +#113673 = CARTESIAN_POINT('',(2.4369137913,7.65)); +#113674 = CARTESIAN_POINT('',(2.507381677529,7.65)); +#113675 = CARTESIAN_POINT('',(2.577849563758,7.65)); +#113676 = CARTESIAN_POINT('',(2.648317449987,7.65)); +#113677 = CARTESIAN_POINT('',(2.718785336216,7.65)); +#113678 = CARTESIAN_POINT('',(2.789253222445,7.65)); +#113679 = CARTESIAN_POINT('',(2.859721108674,7.65)); +#113680 = CARTESIAN_POINT('',(2.930188994903,7.65)); +#113681 = CARTESIAN_POINT('',(3.000656881132,7.65)); +#113682 = CARTESIAN_POINT('',(3.071124767361,7.65)); +#113683 = CARTESIAN_POINT('',(3.11810335818,7.65)); +#113684 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#113685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113686 = PCURVE('',#94171,#113687); +#113687 = DEFINITIONAL_REPRESENTATION('',(#113688),#113696); +#113688 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113689,#113690,#113691, + #113692,#113693,#113694,#113695),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#111297 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#111298 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#111299 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#111300 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#111301 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#111302 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#111303 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#111304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111305 = ADVANCED_FACE('',(#111306),#91751,.T.); -#111306 = FACE_BOUND('',#111307,.T.); -#111307 = EDGE_LOOP('',(#111308,#111329,#111330,#111351)); -#111308 = ORIENTED_EDGE('',*,*,#111309,.F.); -#111309 = EDGE_CURVE('',#111071,#91708,#111310,.T.); -#111310 = SURFACE_CURVE('',#111311,(#111315,#111322),.PCURVE_S1.); -#111311 = LINE('',#111312,#111313); -#111312 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.65)); -#111313 = VECTOR('',#111314,1.); -#111314 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#111315 = PCURVE('',#91751,#111316); -#111316 = DEFINITIONAL_REPRESENTATION('',(#111317),#111321); -#111317 = LINE('',#111318,#111319); -#111318 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#111319 = VECTOR('',#111320,1.); -#111320 = DIRECTION('',(-1.,-4.804757279354E-063)); -#111321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111322 = PCURVE('',#91723,#111323); -#111323 = DEFINITIONAL_REPRESENTATION('',(#111324),#111328); -#111324 = LINE('',#111325,#111326); -#111325 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111326 = VECTOR('',#111327,1.); -#111327 = DIRECTION('',(-3.563627120235E-016,1.)); -#111328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111329 = ORIENTED_EDGE('',*,*,#111093,.T.); -#111330 = ORIENTED_EDGE('',*,*,#111331,.T.); -#111331 = EDGE_CURVE('',#111094,#91736,#111332,.T.); -#111332 = SURFACE_CURVE('',#111333,(#111337,#111344),.PCURVE_S1.); -#111333 = LINE('',#111334,#111335); -#111334 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); -#111335 = VECTOR('',#111336,1.); -#111336 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#111337 = PCURVE('',#91751,#111338); -#111338 = DEFINITIONAL_REPRESENTATION('',(#111339),#111343); -#111339 = LINE('',#111340,#111341); -#111340 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111341 = VECTOR('',#111342,1.); -#111342 = DIRECTION('',(-1.,-4.804757279354E-063)); -#111343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111344 = PCURVE('',#91779,#111345); -#111345 = DEFINITIONAL_REPRESENTATION('',(#111346),#111350); -#111346 = LINE('',#111347,#111348); -#111347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111348 = VECTOR('',#111349,1.); -#111349 = DIRECTION('',(3.563627120235E-016,1.)); -#111350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111351 = ORIENTED_EDGE('',*,*,#91735,.F.); -#111352 = ADVANCED_FACE('',(#111353),#91723,.T.); -#111353 = FACE_BOUND('',#111354,.T.); -#111354 = EDGE_LOOP('',(#111355,#111376,#111377,#111378,#111379,#111380, - #111401,#111402,#111403,#111404,#111405,#111406)); -#111355 = ORIENTED_EDGE('',*,*,#111356,.F.); -#111356 = EDGE_CURVE('',#111168,#91706,#111357,.T.); -#111357 = SURFACE_CURVE('',#111358,(#111362,#111369),.PCURVE_S1.); -#111358 = LINE('',#111359,#111360); -#111359 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.75)); -#111360 = VECTOR('',#111361,1.); -#111361 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#111362 = PCURVE('',#91723,#111363); -#111363 = DEFINITIONAL_REPRESENTATION('',(#111364),#111368); -#111364 = LINE('',#111365,#111366); -#111365 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#111366 = VECTOR('',#111367,1.); -#111367 = DIRECTION('',(-3.563627120235E-016,1.)); -#111368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111369 = PCURVE('',#91805,#111370); -#111370 = DEFINITIONAL_REPRESENTATION('',(#111371),#111375); -#111371 = LINE('',#111372,#111373); -#111372 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#111373 = VECTOR('',#111374,1.); -#111374 = DIRECTION('',(1.,-4.804757279354E-063)); -#111375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111376 = ORIENTED_EDGE('',*,*,#111167,.T.); -#111377 = ORIENTED_EDGE('',*,*,#110970,.T.); -#111378 = ORIENTED_EDGE('',*,*,#110890,.T.); -#111379 = ORIENTED_EDGE('',*,*,#110641,.T.); -#111380 = ORIENTED_EDGE('',*,*,#111381,.F.); -#111381 = EDGE_CURVE('',#110505,#110612,#111382,.T.); -#111382 = SURFACE_CURVE('',#111383,(#111387,#111394),.PCURVE_S1.); -#111383 = LINE('',#111384,#111385); -#111384 = CARTESIAN_POINT('',(-1.,2.15,1.159810404338E-002)); -#111385 = VECTOR('',#111386,1.); -#111386 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#111387 = PCURVE('',#91723,#111388); -#111388 = DEFINITIONAL_REPRESENTATION('',(#111389),#111393); -#111389 = LINE('',#111390,#111391); -#111390 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#111391 = VECTOR('',#111392,1.); -#111392 = DIRECTION('',(-1.,-2.101748079665E-016)); -#111393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111394 = PCURVE('',#110525,#111395); -#111395 = DEFINITIONAL_REPRESENTATION('',(#111396),#111400); -#111396 = LINE('',#111397,#111398); -#111397 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#111398 = VECTOR('',#111399,1.); -#111399 = DIRECTION('',(-1.194699204908E-017,1.)); -#111400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111401 = ORIENTED_EDGE('',*,*,#110587,.F.); -#111402 = ORIENTED_EDGE('',*,*,#110715,.F.); -#111403 = ORIENTED_EDGE('',*,*,#111023,.F.); -#111404 = ORIENTED_EDGE('',*,*,#111070,.F.); -#111405 = ORIENTED_EDGE('',*,*,#111309,.T.); -#111406 = ORIENTED_EDGE('',*,*,#91705,.F.); -#111407 = ADVANCED_FACE('',(#111408),#91805,.T.); -#111408 = FACE_BOUND('',#111409,.T.); -#111409 = EDGE_LOOP('',(#111410,#111431,#111432,#111433)); -#111410 = ORIENTED_EDGE('',*,*,#111411,.F.); -#111411 = EDGE_CURVE('',#111214,#91764,#111412,.T.); -#111412 = SURFACE_CURVE('',#111413,(#111417,#111424),.PCURVE_S1.); -#111413 = LINE('',#111414,#111415); -#111414 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.75)); -#111415 = VECTOR('',#111416,1.); -#111416 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#111417 = PCURVE('',#91805,#111418); -#111418 = DEFINITIONAL_REPRESENTATION('',(#111419),#111423); -#111419 = LINE('',#111420,#111421); -#111420 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111421 = VECTOR('',#111422,1.); -#111422 = DIRECTION('',(1.,-4.804757279354E-063)); -#111423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111424 = PCURVE('',#91779,#111425); -#111425 = DEFINITIONAL_REPRESENTATION('',(#111426),#111430); -#111426 = LINE('',#111427,#111428); -#111427 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#111428 = VECTOR('',#111429,1.); -#111429 = DIRECTION('',(3.563627120235E-016,1.)); -#111430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111431 = ORIENTED_EDGE('',*,*,#111213,.T.); -#111432 = ORIENTED_EDGE('',*,*,#111356,.T.); -#111433 = ORIENTED_EDGE('',*,*,#91791,.F.); -#111434 = ADVANCED_FACE('',(#111435),#91779,.T.); -#111435 = FACE_BOUND('',#111436,.T.); -#111436 = EDGE_LOOP('',(#111437,#111438,#111439,#111440,#111441,#111442, - #111463,#111464,#111465,#111466,#111467,#111468)); -#111437 = ORIENTED_EDGE('',*,*,#111331,.F.); -#111438 = ORIENTED_EDGE('',*,*,#111138,.T.); -#111439 = ORIENTED_EDGE('',*,*,#111045,.T.); -#111440 = ORIENTED_EDGE('',*,*,#110766,.T.); -#111441 = ORIENTED_EDGE('',*,*,#110537,.T.); -#111442 = ORIENTED_EDGE('',*,*,#111443,.F.); -#111443 = EDGE_CURVE('',#110614,#110503,#111444,.T.); -#111444 = SURFACE_CURVE('',#111445,(#111449,#111456),.PCURVE_S1.); -#111445 = LINE('',#111446,#111447); -#111446 = CARTESIAN_POINT('',(-1.,2.35,1.159810404338E-002)); -#111447 = VECTOR('',#111448,1.); -#111448 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#111449 = PCURVE('',#91779,#111450); -#111450 = DEFINITIONAL_REPRESENTATION('',(#111451),#111455); -#111451 = LINE('',#111452,#111453); -#111452 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#111453 = VECTOR('',#111454,1.); -#111454 = DIRECTION('',(-1.,2.101748079665E-016)); -#111455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111456 = PCURVE('',#110525,#111457); -#111457 = DEFINITIONAL_REPRESENTATION('',(#111458),#111462); -#111458 = LINE('',#111459,#111460); -#111459 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#111460 = VECTOR('',#111461,1.); -#111461 = DIRECTION('',(1.194699204908E-017,-1.)); -#111462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#113689 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#113690 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#113691 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#113692 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#113693 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#113694 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#113695 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#113696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113697 = ADVANCED_FACE('',(#113698),#94143,.T.); +#113698 = FACE_BOUND('',#113699,.T.); +#113699 = EDGE_LOOP('',(#113700,#113721,#113722,#113743)); +#113700 = ORIENTED_EDGE('',*,*,#113701,.F.); +#113701 = EDGE_CURVE('',#113463,#94100,#113702,.T.); +#113702 = SURFACE_CURVE('',#113703,(#113707,#113714),.PCURVE_S1.); +#113703 = LINE('',#113704,#113705); +#113704 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.65)); +#113705 = VECTOR('',#113706,1.); +#113706 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#113707 = PCURVE('',#94143,#113708); +#113708 = DEFINITIONAL_REPRESENTATION('',(#113709),#113713); +#113709 = LINE('',#113710,#113711); +#113710 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#113711 = VECTOR('',#113712,1.); +#113712 = DIRECTION('',(-1.,-4.804757279354E-063)); +#113713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113714 = PCURVE('',#94115,#113715); +#113715 = DEFINITIONAL_REPRESENTATION('',(#113716),#113720); +#113716 = LINE('',#113717,#113718); +#113717 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113718 = VECTOR('',#113719,1.); +#113719 = DIRECTION('',(-3.563627120235E-016,1.)); +#113720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113721 = ORIENTED_EDGE('',*,*,#113485,.T.); +#113722 = ORIENTED_EDGE('',*,*,#113723,.T.); +#113723 = EDGE_CURVE('',#113486,#94128,#113724,.T.); +#113724 = SURFACE_CURVE('',#113725,(#113729,#113736),.PCURVE_S1.); +#113725 = LINE('',#113726,#113727); +#113726 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.65)); +#113727 = VECTOR('',#113728,1.); +#113728 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#113729 = PCURVE('',#94143,#113730); +#113730 = DEFINITIONAL_REPRESENTATION('',(#113731),#113735); +#113731 = LINE('',#113732,#113733); +#113732 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113733 = VECTOR('',#113734,1.); +#113734 = DIRECTION('',(-1.,-4.804757279354E-063)); +#113735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113736 = PCURVE('',#94171,#113737); +#113737 = DEFINITIONAL_REPRESENTATION('',(#113738),#113742); +#113738 = LINE('',#113739,#113740); +#113739 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113740 = VECTOR('',#113741,1.); +#113741 = DIRECTION('',(3.563627120235E-016,1.)); +#113742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113743 = ORIENTED_EDGE('',*,*,#94127,.F.); +#113744 = ADVANCED_FACE('',(#113745),#94115,.T.); +#113745 = FACE_BOUND('',#113746,.T.); +#113746 = EDGE_LOOP('',(#113747,#113768,#113769,#113770,#113771,#113772, + #113793,#113794,#113795,#113796,#113797,#113798)); +#113747 = ORIENTED_EDGE('',*,*,#113748,.F.); +#113748 = EDGE_CURVE('',#113560,#94098,#113749,.T.); +#113749 = SURFACE_CURVE('',#113750,(#113754,#113761),.PCURVE_S1.); +#113750 = LINE('',#113751,#113752); +#113751 = CARTESIAN_POINT('',(-0.527847992439,2.15,0.75)); +#113752 = VECTOR('',#113753,1.); +#113753 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#113754 = PCURVE('',#94115,#113755); +#113755 = DEFINITIONAL_REPRESENTATION('',(#113756),#113760); +#113756 = LINE('',#113757,#113758); +#113757 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#113758 = VECTOR('',#113759,1.); +#113759 = DIRECTION('',(-3.563627120235E-016,1.)); +#113760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113761 = PCURVE('',#94197,#113762); +#113762 = DEFINITIONAL_REPRESENTATION('',(#113763),#113767); +#113763 = LINE('',#113764,#113765); +#113764 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#113765 = VECTOR('',#113766,1.); +#113766 = DIRECTION('',(1.,-4.804757279354E-063)); +#113767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113768 = ORIENTED_EDGE('',*,*,#113559,.T.); +#113769 = ORIENTED_EDGE('',*,*,#113362,.T.); +#113770 = ORIENTED_EDGE('',*,*,#113282,.T.); +#113771 = ORIENTED_EDGE('',*,*,#113033,.T.); +#113772 = ORIENTED_EDGE('',*,*,#113773,.F.); +#113773 = EDGE_CURVE('',#112897,#113004,#113774,.T.); +#113774 = SURFACE_CURVE('',#113775,(#113779,#113786),.PCURVE_S1.); +#113775 = LINE('',#113776,#113777); +#113776 = CARTESIAN_POINT('',(-1.,2.15,1.159810404338E-002)); +#113777 = VECTOR('',#113778,1.); +#113778 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#113779 = PCURVE('',#94115,#113780); +#113780 = DEFINITIONAL_REPRESENTATION('',(#113781),#113785); +#113781 = LINE('',#113782,#113783); +#113782 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#113783 = VECTOR('',#113784,1.); +#113784 = DIRECTION('',(-1.,-2.101748079665E-016)); +#113785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113786 = PCURVE('',#112917,#113787); +#113787 = DEFINITIONAL_REPRESENTATION('',(#113788),#113792); +#113788 = LINE('',#113789,#113790); +#113789 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#113790 = VECTOR('',#113791,1.); +#113791 = DIRECTION('',(-1.194699204908E-017,1.)); +#113792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113793 = ORIENTED_EDGE('',*,*,#112979,.F.); +#113794 = ORIENTED_EDGE('',*,*,#113107,.F.); +#113795 = ORIENTED_EDGE('',*,*,#113415,.F.); +#113796 = ORIENTED_EDGE('',*,*,#113462,.F.); +#113797 = ORIENTED_EDGE('',*,*,#113701,.T.); +#113798 = ORIENTED_EDGE('',*,*,#94097,.F.); +#113799 = ADVANCED_FACE('',(#113800),#94197,.T.); +#113800 = FACE_BOUND('',#113801,.T.); +#113801 = EDGE_LOOP('',(#113802,#113823,#113824,#113825)); +#113802 = ORIENTED_EDGE('',*,*,#113803,.F.); +#113803 = EDGE_CURVE('',#113606,#94156,#113804,.T.); +#113804 = SURFACE_CURVE('',#113805,(#113809,#113816),.PCURVE_S1.); +#113805 = LINE('',#113806,#113807); +#113806 = CARTESIAN_POINT('',(-0.527847992439,2.35,0.75)); +#113807 = VECTOR('',#113808,1.); +#113808 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#113809 = PCURVE('',#94197,#113810); +#113810 = DEFINITIONAL_REPRESENTATION('',(#113811),#113815); +#113811 = LINE('',#113812,#113813); +#113812 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113813 = VECTOR('',#113814,1.); +#113814 = DIRECTION('',(1.,-4.804757279354E-063)); +#113815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111463 = ORIENTED_EDGE('',*,*,#110691,.F.); -#111464 = ORIENTED_EDGE('',*,*,#110840,.F.); -#111465 = ORIENTED_EDGE('',*,*,#110948,.F.); -#111466 = ORIENTED_EDGE('',*,*,#111258,.F.); -#111467 = ORIENTED_EDGE('',*,*,#111411,.T.); -#111468 = ORIENTED_EDGE('',*,*,#91763,.F.); -#111469 = ADVANCED_FACE('',(#111470),#110525,.T.); -#111470 = FACE_BOUND('',#111471,.T.); -#111471 = EDGE_LOOP('',(#111472,#111473,#111474,#111475)); -#111472 = ORIENTED_EDGE('',*,*,#111381,.T.); -#111473 = ORIENTED_EDGE('',*,*,#110611,.T.); -#111474 = ORIENTED_EDGE('',*,*,#111443,.T.); -#111475 = ORIENTED_EDGE('',*,*,#110502,.T.); -#111476 = ADVANCED_FACE('',(#111477),#111491,.F.); -#111477 = FACE_BOUND('',#111478,.T.); -#111478 = EDGE_LOOP('',(#111479,#111514,#111537,#111564)); -#111479 = ORIENTED_EDGE('',*,*,#111480,.F.); -#111480 = EDGE_CURVE('',#111481,#111483,#111485,.T.); -#111481 = VERTEX_POINT('',#111482); -#111482 = CARTESIAN_POINT('',(-1.,2.85,-0.308197125857)); -#111483 = VERTEX_POINT('',#111484); -#111484 = CARTESIAN_POINT('',(-1.,2.65,-0.308197125857)); -#111485 = SURFACE_CURVE('',#111486,(#111490,#111502),.PCURVE_S1.); -#111486 = LINE('',#111487,#111488); -#111487 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#111488 = VECTOR('',#111489,1.); -#111489 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111490 = PCURVE('',#111491,#111496); -#111491 = PLANE('',#111492); -#111492 = AXIS2_PLACEMENT_3D('',#111493,#111494,#111495); -#111493 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#111494 = DIRECTION('',(0.E+000,0.E+000,1.)); -#111495 = DIRECTION('',(1.,0.E+000,0.E+000)); -#111496 = DEFINITIONAL_REPRESENTATION('',(#111497),#111501); -#111497 = LINE('',#111498,#111499); -#111498 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#111499 = VECTOR('',#111500,1.); -#111500 = DIRECTION('',(4.440892098501E-016,-1.)); -#111501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111502 = PCURVE('',#111503,#111508); -#111503 = PLANE('',#111504); -#111504 = AXIS2_PLACEMENT_3D('',#111505,#111506,#111507); -#111505 = CARTESIAN_POINT('',(-1.,2.75,-0.258196742327)); -#111506 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#111507 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111508 = DEFINITIONAL_REPRESENTATION('',(#111509),#111513); -#111509 = LINE('',#111510,#111511); -#111510 = CARTESIAN_POINT('',(-7.25,-5.000038352949E-002)); -#111511 = VECTOR('',#111512,1.); -#111512 = DIRECTION('',(1.,0.E+000)); -#111513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111514 = ORIENTED_EDGE('',*,*,#111515,.F.); -#111515 = EDGE_CURVE('',#111516,#111481,#111518,.T.); -#111516 = VERTEX_POINT('',#111517); -#111517 = CARTESIAN_POINT('',(-0.74341632541,2.85,-0.308197125857)); -#111518 = SURFACE_CURVE('',#111519,(#111523,#111530),.PCURVE_S1.); -#111519 = LINE('',#111520,#111521); -#111520 = CARTESIAN_POINT('',(-0.74341632541,2.85,-0.308197125857)); -#111521 = VECTOR('',#111522,1.); -#111522 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#111523 = PCURVE('',#111491,#111524); -#111524 = DEFINITIONAL_REPRESENTATION('',(#111525),#111529); -#111525 = LINE('',#111526,#111527); -#111526 = CARTESIAN_POINT('',(3.10862446895E-015,-7.15)); -#111527 = VECTOR('',#111528,1.); -#111528 = DIRECTION('',(-1.,0.E+000)); -#111529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111530 = PCURVE('',#91665,#111531); -#111531 = DEFINITIONAL_REPRESENTATION('',(#111532),#111536); -#111532 = LINE('',#111533,#111534); -#111533 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#111534 = VECTOR('',#111535,1.); -#111535 = DIRECTION('',(0.E+000,-1.)); -#111536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111537 = ORIENTED_EDGE('',*,*,#111538,.F.); -#111538 = EDGE_CURVE('',#111539,#111516,#111541,.T.); -#111539 = VERTEX_POINT('',#111540); -#111540 = CARTESIAN_POINT('',(-0.74341632541,2.65,-0.308197125857)); -#111541 = SURFACE_CURVE('',#111542,(#111546,#111553),.PCURVE_S1.); -#111542 = LINE('',#111543,#111544); -#111543 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#111544 = VECTOR('',#111545,1.); -#111545 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111546 = PCURVE('',#111491,#111547); -#111547 = DEFINITIONAL_REPRESENTATION('',(#111548),#111552); -#111548 = LINE('',#111549,#111550); -#111549 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111550 = VECTOR('',#111551,1.); -#111551 = DIRECTION('',(-4.440892098501E-016,1.)); -#111552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111553 = PCURVE('',#111554,#111559); -#111554 = CYLINDRICAL_SURFACE('',#111555,0.308574064194); -#111555 = AXIS2_PLACEMENT_3D('',#111556,#111557,#111558); -#111556 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#111557 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111558 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111559 = DEFINITIONAL_REPRESENTATION('',(#111560),#111563); -#111560 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111561,#111562), +#113816 = PCURVE('',#94171,#113817); +#113817 = DEFINITIONAL_REPRESENTATION('',(#113818),#113822); +#113818 = LINE('',#113819,#113820); +#113819 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#113820 = VECTOR('',#113821,1.); +#113821 = DIRECTION('',(3.563627120235E-016,1.)); +#113822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113823 = ORIENTED_EDGE('',*,*,#113605,.T.); +#113824 = ORIENTED_EDGE('',*,*,#113748,.T.); +#113825 = ORIENTED_EDGE('',*,*,#94183,.F.); +#113826 = ADVANCED_FACE('',(#113827),#94171,.T.); +#113827 = FACE_BOUND('',#113828,.T.); +#113828 = EDGE_LOOP('',(#113829,#113830,#113831,#113832,#113833,#113834, + #113855,#113856,#113857,#113858,#113859,#113860)); +#113829 = ORIENTED_EDGE('',*,*,#113723,.F.); +#113830 = ORIENTED_EDGE('',*,*,#113530,.T.); +#113831 = ORIENTED_EDGE('',*,*,#113437,.T.); +#113832 = ORIENTED_EDGE('',*,*,#113158,.T.); +#113833 = ORIENTED_EDGE('',*,*,#112929,.T.); +#113834 = ORIENTED_EDGE('',*,*,#113835,.F.); +#113835 = EDGE_CURVE('',#113006,#112895,#113836,.T.); +#113836 = SURFACE_CURVE('',#113837,(#113841,#113848),.PCURVE_S1.); +#113837 = LINE('',#113838,#113839); +#113838 = CARTESIAN_POINT('',(-1.,2.35,1.159810404338E-002)); +#113839 = VECTOR('',#113840,1.); +#113840 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#113841 = PCURVE('',#94171,#113842); +#113842 = DEFINITIONAL_REPRESENTATION('',(#113843),#113847); +#113843 = LINE('',#113844,#113845); +#113844 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#113845 = VECTOR('',#113846,1.); +#113846 = DIRECTION('',(-1.,2.101748079665E-016)); +#113847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113848 = PCURVE('',#112917,#113849); +#113849 = DEFINITIONAL_REPRESENTATION('',(#113850),#113854); +#113850 = LINE('',#113851,#113852); +#113851 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#113852 = VECTOR('',#113853,1.); +#113853 = DIRECTION('',(1.194699204908E-017,-1.)); +#113854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113855 = ORIENTED_EDGE('',*,*,#113083,.F.); +#113856 = ORIENTED_EDGE('',*,*,#113232,.F.); +#113857 = ORIENTED_EDGE('',*,*,#113340,.F.); +#113858 = ORIENTED_EDGE('',*,*,#113650,.F.); +#113859 = ORIENTED_EDGE('',*,*,#113803,.T.); +#113860 = ORIENTED_EDGE('',*,*,#94155,.F.); +#113861 = ADVANCED_FACE('',(#113862),#112917,.T.); +#113862 = FACE_BOUND('',#113863,.T.); +#113863 = EDGE_LOOP('',(#113864,#113865,#113866,#113867)); +#113864 = ORIENTED_EDGE('',*,*,#113773,.T.); +#113865 = ORIENTED_EDGE('',*,*,#113003,.T.); +#113866 = ORIENTED_EDGE('',*,*,#113835,.T.); +#113867 = ORIENTED_EDGE('',*,*,#112894,.T.); +#113868 = ADVANCED_FACE('',(#113869),#113883,.F.); +#113869 = FACE_BOUND('',#113870,.T.); +#113870 = EDGE_LOOP('',(#113871,#113906,#113929,#113956)); +#113871 = ORIENTED_EDGE('',*,*,#113872,.F.); +#113872 = EDGE_CURVE('',#113873,#113875,#113877,.T.); +#113873 = VERTEX_POINT('',#113874); +#113874 = CARTESIAN_POINT('',(-1.,2.85,-0.308197125857)); +#113875 = VERTEX_POINT('',#113876); +#113876 = CARTESIAN_POINT('',(-1.,2.65,-0.308197125857)); +#113877 = SURFACE_CURVE('',#113878,(#113882,#113894),.PCURVE_S1.); +#113878 = LINE('',#113879,#113880); +#113879 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#113880 = VECTOR('',#113881,1.); +#113881 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113882 = PCURVE('',#113883,#113888); +#113883 = PLANE('',#113884); +#113884 = AXIS2_PLACEMENT_3D('',#113885,#113886,#113887); +#113885 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#113886 = DIRECTION('',(0.E+000,0.E+000,1.)); +#113887 = DIRECTION('',(1.,0.E+000,0.E+000)); +#113888 = DEFINITIONAL_REPRESENTATION('',(#113889),#113893); +#113889 = LINE('',#113890,#113891); +#113890 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#113891 = VECTOR('',#113892,1.); +#113892 = DIRECTION('',(4.440892098501E-016,-1.)); +#113893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113894 = PCURVE('',#113895,#113900); +#113895 = PLANE('',#113896); +#113896 = AXIS2_PLACEMENT_3D('',#113897,#113898,#113899); +#113897 = CARTESIAN_POINT('',(-1.,2.75,-0.258196742327)); +#113898 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#113899 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#113900 = DEFINITIONAL_REPRESENTATION('',(#113901),#113905); +#113901 = LINE('',#113902,#113903); +#113902 = CARTESIAN_POINT('',(-7.25,-5.000038352949E-002)); +#113903 = VECTOR('',#113904,1.); +#113904 = DIRECTION('',(1.,0.E+000)); +#113905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113906 = ORIENTED_EDGE('',*,*,#113907,.F.); +#113907 = EDGE_CURVE('',#113908,#113873,#113910,.T.); +#113908 = VERTEX_POINT('',#113909); +#113909 = CARTESIAN_POINT('',(-0.74341632541,2.85,-0.308197125857)); +#113910 = SURFACE_CURVE('',#113911,(#113915,#113922),.PCURVE_S1.); +#113911 = LINE('',#113912,#113913); +#113912 = CARTESIAN_POINT('',(-0.74341632541,2.85,-0.308197125857)); +#113913 = VECTOR('',#113914,1.); +#113914 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113915 = PCURVE('',#113883,#113916); +#113916 = DEFINITIONAL_REPRESENTATION('',(#113917),#113921); +#113917 = LINE('',#113918,#113919); +#113918 = CARTESIAN_POINT('',(3.10862446895E-015,-7.15)); +#113919 = VECTOR('',#113920,1.); +#113920 = DIRECTION('',(-1.,0.E+000)); +#113921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113922 = PCURVE('',#94057,#113923); +#113923 = DEFINITIONAL_REPRESENTATION('',(#113924),#113928); +#113924 = LINE('',#113925,#113926); +#113925 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#113926 = VECTOR('',#113927,1.); +#113927 = DIRECTION('',(0.E+000,-1.)); +#113928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113929 = ORIENTED_EDGE('',*,*,#113930,.F.); +#113930 = EDGE_CURVE('',#113931,#113908,#113933,.T.); +#113931 = VERTEX_POINT('',#113932); +#113932 = CARTESIAN_POINT('',(-0.74341632541,2.65,-0.308197125857)); +#113933 = SURFACE_CURVE('',#113934,(#113938,#113945),.PCURVE_S1.); +#113934 = LINE('',#113935,#113936); +#113935 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#113936 = VECTOR('',#113937,1.); +#113937 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113938 = PCURVE('',#113883,#113939); +#113939 = DEFINITIONAL_REPRESENTATION('',(#113940),#113944); +#113940 = LINE('',#113941,#113942); +#113941 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#113942 = VECTOR('',#113943,1.); +#113943 = DIRECTION('',(-4.440892098501E-016,1.)); +#113944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113945 = PCURVE('',#113946,#113951); +#113946 = CYLINDRICAL_SURFACE('',#113947,0.308574064194); +#113947 = AXIS2_PLACEMENT_3D('',#113948,#113949,#113950); +#113948 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#113949 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113950 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#113951 = DEFINITIONAL_REPRESENTATION('',(#113952),#113955); +#113952 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113953,#113954), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#111561 = CARTESIAN_POINT('',(4.761821717947,-7.35)); -#111562 = CARTESIAN_POINT('',(4.761821717947,-7.15)); -#111563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111564 = ORIENTED_EDGE('',*,*,#111565,.T.); -#111565 = EDGE_CURVE('',#111539,#111483,#111566,.T.); -#111566 = SURFACE_CURVE('',#111567,(#111571,#111578),.PCURVE_S1.); -#111567 = LINE('',#111568,#111569); -#111568 = CARTESIAN_POINT('',(-0.74341632541,2.65,-0.308197125857)); -#111569 = VECTOR('',#111570,1.); -#111570 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#111571 = PCURVE('',#111491,#111572); -#111572 = DEFINITIONAL_REPRESENTATION('',(#111573),#111577); -#111573 = LINE('',#111574,#111575); -#111574 = CARTESIAN_POINT('',(3.330669073875E-015,-7.35)); -#111575 = VECTOR('',#111576,1.); -#111576 = DIRECTION('',(-1.,0.E+000)); -#111577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111578 = PCURVE('',#91609,#111579); -#111579 = DEFINITIONAL_REPRESENTATION('',(#111580),#111584); -#111580 = LINE('',#111581,#111582); -#111581 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#111582 = VECTOR('',#111583,1.); -#111583 = DIRECTION('',(0.E+000,-1.)); -#111584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111585 = ADVANCED_FACE('',(#111586),#111600,.F.); -#111586 = FACE_BOUND('',#111587,.T.); -#111587 = EDGE_LOOP('',(#111588,#111618,#111641,#111668)); -#111588 = ORIENTED_EDGE('',*,*,#111589,.F.); -#111589 = EDGE_CURVE('',#111590,#111592,#111594,.T.); -#111590 = VERTEX_POINT('',#111591); -#111591 = CARTESIAN_POINT('',(-1.,2.65,-0.208196358798)); -#111592 = VERTEX_POINT('',#111593); -#111593 = CARTESIAN_POINT('',(-1.,2.85,-0.208196358798)); -#111594 = SURFACE_CURVE('',#111595,(#111599,#111611),.PCURVE_S1.); -#111595 = LINE('',#111596,#111597); -#111596 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#111597 = VECTOR('',#111598,1.); -#111598 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111599 = PCURVE('',#111600,#111605); -#111600 = PLANE('',#111601); -#111601 = AXIS2_PLACEMENT_3D('',#111602,#111603,#111604); -#111602 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#111603 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#111604 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#111605 = DEFINITIONAL_REPRESENTATION('',(#111606),#111610); -#111606 = LINE('',#111607,#111608); -#111607 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#111608 = VECTOR('',#111609,1.); -#111609 = DIRECTION('',(4.440892098501E-016,1.)); -#111610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111611 = PCURVE('',#111503,#111612); -#111612 = DEFINITIONAL_REPRESENTATION('',(#111613),#111617); -#111613 = LINE('',#111614,#111615); -#111614 = CARTESIAN_POINT('',(-7.25,5.000038352949E-002)); -#111615 = VECTOR('',#111616,1.); -#111616 = DIRECTION('',(-1.,0.E+000)); -#111617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111618 = ORIENTED_EDGE('',*,*,#111619,.F.); -#111619 = EDGE_CURVE('',#111620,#111590,#111622,.T.); -#111620 = VERTEX_POINT('',#111621); -#111621 = CARTESIAN_POINT('',(-0.740726081328,2.65,-0.208196358798)); -#111622 = SURFACE_CURVE('',#111623,(#111627,#111634),.PCURVE_S1.); -#111623 = LINE('',#111624,#111625); -#111624 = CARTESIAN_POINT('',(-0.740726081328,2.65,-0.208196358798)); -#111625 = VECTOR('',#111626,1.); -#111626 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#111627 = PCURVE('',#111600,#111628); -#111628 = DEFINITIONAL_REPRESENTATION('',(#111629),#111633); -#111629 = LINE('',#111630,#111631); -#111630 = CARTESIAN_POINT('',(-3.330669073875E-015,-7.35)); -#111631 = VECTOR('',#111632,1.); -#111632 = DIRECTION('',(1.,0.E+000)); -#111633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111634 = PCURVE('',#91609,#111635); -#111635 = DEFINITIONAL_REPRESENTATION('',(#111636),#111640); -#111636 = LINE('',#111637,#111638); -#111637 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#111638 = VECTOR('',#111639,1.); -#111639 = DIRECTION('',(0.E+000,-1.)); -#111640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111641 = ORIENTED_EDGE('',*,*,#111642,.F.); -#111642 = EDGE_CURVE('',#111643,#111620,#111645,.T.); -#111643 = VERTEX_POINT('',#111644); -#111644 = CARTESIAN_POINT('',(-0.740726081328,2.85,-0.208196358798)); -#111645 = SURFACE_CURVE('',#111646,(#111650,#111657),.PCURVE_S1.); -#111646 = LINE('',#111647,#111648); -#111647 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#111648 = VECTOR('',#111649,1.); -#111649 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111650 = PCURVE('',#111600,#111651); -#111651 = DEFINITIONAL_REPRESENTATION('',(#111652),#111656); -#111652 = LINE('',#111653,#111654); -#111653 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111654 = VECTOR('',#111655,1.); -#111655 = DIRECTION('',(-4.440892098501E-016,-1.)); -#111656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111657 = PCURVE('',#111658,#111663); -#111658 = CYLINDRICAL_SURFACE('',#111659,0.208574704164); -#111659 = AXIS2_PLACEMENT_3D('',#111660,#111661,#111662); -#111660 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#111661 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111662 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111663 = DEFINITIONAL_REPRESENTATION('',(#111664),#111667); -#111664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111665,#111666), +#113953 = CARTESIAN_POINT('',(4.761821717947,-7.35)); +#113954 = CARTESIAN_POINT('',(4.761821717947,-7.15)); +#113955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113956 = ORIENTED_EDGE('',*,*,#113957,.T.); +#113957 = EDGE_CURVE('',#113931,#113875,#113958,.T.); +#113958 = SURFACE_CURVE('',#113959,(#113963,#113970),.PCURVE_S1.); +#113959 = LINE('',#113960,#113961); +#113960 = CARTESIAN_POINT('',(-0.74341632541,2.65,-0.308197125857)); +#113961 = VECTOR('',#113962,1.); +#113962 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113963 = PCURVE('',#113883,#113964); +#113964 = DEFINITIONAL_REPRESENTATION('',(#113965),#113969); +#113965 = LINE('',#113966,#113967); +#113966 = CARTESIAN_POINT('',(3.330669073875E-015,-7.35)); +#113967 = VECTOR('',#113968,1.); +#113968 = DIRECTION('',(-1.,0.E+000)); +#113969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113970 = PCURVE('',#94001,#113971); +#113971 = DEFINITIONAL_REPRESENTATION('',(#113972),#113976); +#113972 = LINE('',#113973,#113974); +#113973 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#113974 = VECTOR('',#113975,1.); +#113975 = DIRECTION('',(0.E+000,-1.)); +#113976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#113977 = ADVANCED_FACE('',(#113978),#113992,.F.); +#113978 = FACE_BOUND('',#113979,.T.); +#113979 = EDGE_LOOP('',(#113980,#114010,#114033,#114060)); +#113980 = ORIENTED_EDGE('',*,*,#113981,.F.); +#113981 = EDGE_CURVE('',#113982,#113984,#113986,.T.); +#113982 = VERTEX_POINT('',#113983); +#113983 = CARTESIAN_POINT('',(-1.,2.65,-0.208196358798)); +#113984 = VERTEX_POINT('',#113985); +#113985 = CARTESIAN_POINT('',(-1.,2.85,-0.208196358798)); +#113986 = SURFACE_CURVE('',#113987,(#113991,#114003),.PCURVE_S1.); +#113987 = LINE('',#113988,#113989); +#113988 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#113989 = VECTOR('',#113990,1.); +#113990 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#113991 = PCURVE('',#113992,#113997); +#113992 = PLANE('',#113993); +#113993 = AXIS2_PLACEMENT_3D('',#113994,#113995,#113996); +#113994 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#113995 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#113996 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#113997 = DEFINITIONAL_REPRESENTATION('',(#113998),#114002); +#113998 = LINE('',#113999,#114000); +#113999 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#114000 = VECTOR('',#114001,1.); +#114001 = DIRECTION('',(4.440892098501E-016,1.)); +#114002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114003 = PCURVE('',#113895,#114004); +#114004 = DEFINITIONAL_REPRESENTATION('',(#114005),#114009); +#114005 = LINE('',#114006,#114007); +#114006 = CARTESIAN_POINT('',(-7.25,5.000038352949E-002)); +#114007 = VECTOR('',#114008,1.); +#114008 = DIRECTION('',(-1.,0.E+000)); +#114009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114010 = ORIENTED_EDGE('',*,*,#114011,.F.); +#114011 = EDGE_CURVE('',#114012,#113982,#114014,.T.); +#114012 = VERTEX_POINT('',#114013); +#114013 = CARTESIAN_POINT('',(-0.740726081328,2.65,-0.208196358798)); +#114014 = SURFACE_CURVE('',#114015,(#114019,#114026),.PCURVE_S1.); +#114015 = LINE('',#114016,#114017); +#114016 = CARTESIAN_POINT('',(-0.740726081328,2.65,-0.208196358798)); +#114017 = VECTOR('',#114018,1.); +#114018 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114019 = PCURVE('',#113992,#114020); +#114020 = DEFINITIONAL_REPRESENTATION('',(#114021),#114025); +#114021 = LINE('',#114022,#114023); +#114022 = CARTESIAN_POINT('',(-3.330669073875E-015,-7.35)); +#114023 = VECTOR('',#114024,1.); +#114024 = DIRECTION('',(1.,0.E+000)); +#114025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114026 = PCURVE('',#94001,#114027); +#114027 = DEFINITIONAL_REPRESENTATION('',(#114028),#114032); +#114028 = LINE('',#114029,#114030); +#114029 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#114030 = VECTOR('',#114031,1.); +#114031 = DIRECTION('',(0.E+000,-1.)); +#114032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114033 = ORIENTED_EDGE('',*,*,#114034,.F.); +#114034 = EDGE_CURVE('',#114035,#114012,#114037,.T.); +#114035 = VERTEX_POINT('',#114036); +#114036 = CARTESIAN_POINT('',(-0.740726081328,2.85,-0.208196358798)); +#114037 = SURFACE_CURVE('',#114038,(#114042,#114049),.PCURVE_S1.); +#114038 = LINE('',#114039,#114040); +#114039 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#114040 = VECTOR('',#114041,1.); +#114041 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114042 = PCURVE('',#113992,#114043); +#114043 = DEFINITIONAL_REPRESENTATION('',(#114044),#114048); +#114044 = LINE('',#114045,#114046); +#114045 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114046 = VECTOR('',#114047,1.); +#114047 = DIRECTION('',(-4.440892098501E-016,-1.)); +#114048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114049 = PCURVE('',#114050,#114055); +#114050 = CYLINDRICAL_SURFACE('',#114051,0.208574704164); +#114051 = AXIS2_PLACEMENT_3D('',#114052,#114053,#114054); +#114052 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#114053 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114054 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114055 = DEFINITIONAL_REPRESENTATION('',(#114056),#114059); +#114056 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114057,#114058), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#111665 = CARTESIAN_POINT('',(4.772630242227,-7.15)); -#111666 = CARTESIAN_POINT('',(4.772630242227,-7.35)); -#111667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111668 = ORIENTED_EDGE('',*,*,#111669,.T.); -#111669 = EDGE_CURVE('',#111643,#111592,#111670,.T.); -#111670 = SURFACE_CURVE('',#111671,(#111675,#111682),.PCURVE_S1.); -#111671 = LINE('',#111672,#111673); -#111672 = CARTESIAN_POINT('',(-0.740726081328,2.85,-0.208196358798)); -#111673 = VECTOR('',#111674,1.); -#111674 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#111675 = PCURVE('',#111600,#111676); -#111676 = DEFINITIONAL_REPRESENTATION('',(#111677),#111681); -#111677 = LINE('',#111678,#111679); -#111678 = CARTESIAN_POINT('',(-3.219646771413E-015,-7.15)); -#111679 = VECTOR('',#111680,1.); -#111680 = DIRECTION('',(1.,0.E+000)); -#111681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111682 = PCURVE('',#91665,#111683); -#111683 = DEFINITIONAL_REPRESENTATION('',(#111684),#111688); -#111684 = LINE('',#111685,#111686); -#111685 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#111686 = VECTOR('',#111687,1.); -#111687 = DIRECTION('',(0.E+000,-1.)); -#111688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111689 = ADVANCED_FACE('',(#111690),#111554,.T.); -#111690 = FACE_BOUND('',#111691,.T.); -#111691 = EDGE_LOOP('',(#111692,#111719,#111720,#111766)); -#111692 = ORIENTED_EDGE('',*,*,#111693,.T.); -#111693 = EDGE_CURVE('',#111694,#111539,#111696,.T.); -#111694 = VERTEX_POINT('',#111695); -#111695 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.E+000)); -#111696 = SURFACE_CURVE('',#111697,(#111702,#111708),.PCURVE_S1.); -#111697 = CIRCLE('',#111698,0.308574064194); -#111698 = AXIS2_PLACEMENT_3D('',#111699,#111700,#111701); -#111699 = CARTESIAN_POINT('',(-0.728168876214,2.65,2.640924866458E-017) - ); -#111700 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111701 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111702 = PCURVE('',#111554,#111703); -#111703 = DEFINITIONAL_REPRESENTATION('',(#111704),#111707); -#111704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111705,#111706), +#114057 = CARTESIAN_POINT('',(4.772630242227,-7.15)); +#114058 = CARTESIAN_POINT('',(4.772630242227,-7.35)); +#114059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114060 = ORIENTED_EDGE('',*,*,#114061,.T.); +#114061 = EDGE_CURVE('',#114035,#113984,#114062,.T.); +#114062 = SURFACE_CURVE('',#114063,(#114067,#114074),.PCURVE_S1.); +#114063 = LINE('',#114064,#114065); +#114064 = CARTESIAN_POINT('',(-0.740726081328,2.85,-0.208196358798)); +#114065 = VECTOR('',#114066,1.); +#114066 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114067 = PCURVE('',#113992,#114068); +#114068 = DEFINITIONAL_REPRESENTATION('',(#114069),#114073); +#114069 = LINE('',#114070,#114071); +#114070 = CARTESIAN_POINT('',(-3.219646771413E-015,-7.15)); +#114071 = VECTOR('',#114072,1.); +#114072 = DIRECTION('',(1.,0.E+000)); +#114073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114074 = PCURVE('',#94057,#114075); +#114075 = DEFINITIONAL_REPRESENTATION('',(#114076),#114080); +#114076 = LINE('',#114077,#114078); +#114077 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#114078 = VECTOR('',#114079,1.); +#114079 = DIRECTION('',(0.E+000,-1.)); +#114080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114081 = ADVANCED_FACE('',(#114082),#113946,.T.); +#114082 = FACE_BOUND('',#114083,.T.); +#114083 = EDGE_LOOP('',(#114084,#114111,#114112,#114158)); +#114084 = ORIENTED_EDGE('',*,*,#114085,.T.); +#114085 = EDGE_CURVE('',#114086,#113931,#114088,.T.); +#114086 = VERTEX_POINT('',#114087); +#114087 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.E+000)); +#114088 = SURFACE_CURVE('',#114089,(#114094,#114100),.PCURVE_S1.); +#114089 = CIRCLE('',#114090,0.308574064194); +#114090 = AXIS2_PLACEMENT_3D('',#114091,#114092,#114093); +#114091 = CARTESIAN_POINT('',(-0.728168876214,2.65,2.640924866458E-017) + ); +#114092 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114093 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114094 = PCURVE('',#113946,#114095); +#114095 = DEFINITIONAL_REPRESENTATION('',(#114096),#114099); +#114096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114097,#114098), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#111705 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#111706 = CARTESIAN_POINT('',(4.761821717947,-7.35)); -#111707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#114097 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#114098 = CARTESIAN_POINT('',(4.761821717947,-7.35)); +#114099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111708 = PCURVE('',#91609,#111709); -#111709 = DEFINITIONAL_REPRESENTATION('',(#111710),#111718); -#111710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111711,#111712,#111713, - #111714,#111715,#111716,#111717),.UNSPECIFIED.,.T.,.F.) +#114100 = PCURVE('',#94001,#114101); +#114101 = DEFINITIONAL_REPRESENTATION('',(#114102),#114110); +#114102 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114103,#114104,#114105, + #114106,#114107,#114108,#114109),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#111711 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#111712 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#111713 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#111714 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#111715 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#111716 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#111717 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#111718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111719 = ORIENTED_EDGE('',*,*,#111538,.T.); -#111720 = ORIENTED_EDGE('',*,*,#111721,.F.); -#111721 = EDGE_CURVE('',#111722,#111516,#111724,.T.); -#111722 = VERTEX_POINT('',#111723); -#111723 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.E+000)); -#111724 = SURFACE_CURVE('',#111725,(#111730,#111759),.PCURVE_S1.); -#111725 = CIRCLE('',#111726,0.308574064194); -#111726 = AXIS2_PLACEMENT_3D('',#111727,#111728,#111729); -#111727 = CARTESIAN_POINT('',(-0.728168876214,2.85,2.640924866458E-017) - ); -#111728 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111729 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111730 = PCURVE('',#111554,#111731); -#111731 = DEFINITIONAL_REPRESENTATION('',(#111732),#111758); -#111732 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#111733,#111734,#111735, - #111736,#111737,#111738,#111739,#111740,#111741,#111742,#111743, - #111744,#111745,#111746,#111747,#111748,#111749,#111750,#111751, - #111752,#111753,#111754,#111755,#111756,#111757),.UNSPECIFIED.,.F., +#114103 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#114104 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#114105 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#114106 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#114107 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#114108 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#114109 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#114110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114111 = ORIENTED_EDGE('',*,*,#113930,.T.); +#114112 = ORIENTED_EDGE('',*,*,#114113,.F.); +#114113 = EDGE_CURVE('',#114114,#113908,#114116,.T.); +#114114 = VERTEX_POINT('',#114115); +#114115 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.E+000)); +#114116 = SURFACE_CURVE('',#114117,(#114122,#114151),.PCURVE_S1.); +#114117 = CIRCLE('',#114118,0.308574064194); +#114118 = AXIS2_PLACEMENT_3D('',#114119,#114120,#114121); +#114119 = CARTESIAN_POINT('',(-0.728168876214,2.85,2.640924866458E-017) + ); +#114120 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114121 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114122 = PCURVE('',#113946,#114123); +#114123 = DEFINITIONAL_REPRESENTATION('',(#114124),#114150); +#114124 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114125,#114126,#114127, + #114128,#114129,#114130,#114131,#114132,#114133,#114134,#114135, + #114136,#114137,#114138,#114139,#114140,#114141,#114142,#114143, + #114144,#114145,#114146,#114147,#114148,#114149),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -137635,401 +140637,401 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#111733 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#111734 = CARTESIAN_POINT('',(3.166141578807,-7.15)); -#111735 = CARTESIAN_POINT('',(3.215239429242,-7.15)); -#111736 = CARTESIAN_POINT('',(3.288886204895,-7.15)); -#111737 = CARTESIAN_POINT('',(3.362532980548,-7.15)); -#111738 = CARTESIAN_POINT('',(3.4361797562,-7.15)); -#111739 = CARTESIAN_POINT('',(3.509826531853,-7.15)); -#111740 = CARTESIAN_POINT('',(3.583473307505,-7.15)); -#111741 = CARTESIAN_POINT('',(3.657120083158,-7.15)); -#111742 = CARTESIAN_POINT('',(3.730766858811,-7.15)); -#111743 = CARTESIAN_POINT('',(3.804413634463,-7.15)); -#111744 = CARTESIAN_POINT('',(3.878060410116,-7.15)); -#111745 = CARTESIAN_POINT('',(3.951707185768,-7.15)); -#111746 = CARTESIAN_POINT('',(4.025353961421,-7.15)); -#111747 = CARTESIAN_POINT('',(4.099000737074,-7.15)); -#111748 = CARTESIAN_POINT('',(4.172647512726,-7.15)); -#111749 = CARTESIAN_POINT('',(4.246294288379,-7.15)); -#111750 = CARTESIAN_POINT('',(4.319941064031,-7.15)); -#111751 = CARTESIAN_POINT('',(4.393587839684,-7.15)); -#111752 = CARTESIAN_POINT('',(4.467234615337,-7.15)); -#111753 = CARTESIAN_POINT('',(4.540881390989,-7.15)); -#111754 = CARTESIAN_POINT('',(4.614528166642,-7.15)); -#111755 = CARTESIAN_POINT('',(4.688174942294,-7.15)); -#111756 = CARTESIAN_POINT('',(4.737272792729,-7.15)); -#111757 = CARTESIAN_POINT('',(4.761821717947,-7.15)); -#111758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111759 = PCURVE('',#91665,#111760); -#111760 = DEFINITIONAL_REPRESENTATION('',(#111761),#111765); -#111761 = CIRCLE('',#111762,0.308574064194); -#111762 = AXIS2_PLACEMENT_2D('',#111763,#111764); -#111763 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#111764 = DIRECTION('',(0.E+000,-1.)); -#111765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111766 = ORIENTED_EDGE('',*,*,#111767,.T.); -#111767 = EDGE_CURVE('',#111722,#111694,#111768,.T.); -#111768 = SURFACE_CURVE('',#111769,(#111773,#111779),.PCURVE_S1.); -#111769 = LINE('',#111770,#111771); -#111770 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#111771 = VECTOR('',#111772,1.); -#111772 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111773 = PCURVE('',#111554,#111774); -#111774 = DEFINITIONAL_REPRESENTATION('',(#111775),#111778); -#111775 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111776,#111777), +#114125 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#114126 = CARTESIAN_POINT('',(3.166141578807,-7.15)); +#114127 = CARTESIAN_POINT('',(3.215239429242,-7.15)); +#114128 = CARTESIAN_POINT('',(3.288886204895,-7.15)); +#114129 = CARTESIAN_POINT('',(3.362532980548,-7.15)); +#114130 = CARTESIAN_POINT('',(3.4361797562,-7.15)); +#114131 = CARTESIAN_POINT('',(3.509826531853,-7.15)); +#114132 = CARTESIAN_POINT('',(3.583473307505,-7.15)); +#114133 = CARTESIAN_POINT('',(3.657120083158,-7.15)); +#114134 = CARTESIAN_POINT('',(3.730766858811,-7.15)); +#114135 = CARTESIAN_POINT('',(3.804413634463,-7.15)); +#114136 = CARTESIAN_POINT('',(3.878060410116,-7.15)); +#114137 = CARTESIAN_POINT('',(3.951707185768,-7.15)); +#114138 = CARTESIAN_POINT('',(4.025353961421,-7.15)); +#114139 = CARTESIAN_POINT('',(4.099000737074,-7.15)); +#114140 = CARTESIAN_POINT('',(4.172647512726,-7.15)); +#114141 = CARTESIAN_POINT('',(4.246294288379,-7.15)); +#114142 = CARTESIAN_POINT('',(4.319941064031,-7.15)); +#114143 = CARTESIAN_POINT('',(4.393587839684,-7.15)); +#114144 = CARTESIAN_POINT('',(4.467234615337,-7.15)); +#114145 = CARTESIAN_POINT('',(4.540881390989,-7.15)); +#114146 = CARTESIAN_POINT('',(4.614528166642,-7.15)); +#114147 = CARTESIAN_POINT('',(4.688174942294,-7.15)); +#114148 = CARTESIAN_POINT('',(4.737272792729,-7.15)); +#114149 = CARTESIAN_POINT('',(4.761821717947,-7.15)); +#114150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114151 = PCURVE('',#94057,#114152); +#114152 = DEFINITIONAL_REPRESENTATION('',(#114153),#114157); +#114153 = CIRCLE('',#114154,0.308574064194); +#114154 = AXIS2_PLACEMENT_2D('',#114155,#114156); +#114155 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#114156 = DIRECTION('',(0.E+000,-1.)); +#114157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114158 = ORIENTED_EDGE('',*,*,#114159,.T.); +#114159 = EDGE_CURVE('',#114114,#114086,#114160,.T.); +#114160 = SURFACE_CURVE('',#114161,(#114165,#114171),.PCURVE_S1.); +#114161 = LINE('',#114162,#114163); +#114162 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#114163 = VECTOR('',#114164,1.); +#114164 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114165 = PCURVE('',#113946,#114166); +#114166 = DEFINITIONAL_REPRESENTATION('',(#114167),#114170); +#114167 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114168,#114169), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#111776 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#111777 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#111778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111779 = PCURVE('',#111780,#111785); -#111780 = PLANE('',#111781); -#111781 = AXIS2_PLACEMENT_3D('',#111782,#111783,#111784); -#111782 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#111783 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#111784 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111785 = DEFINITIONAL_REPRESENTATION('',(#111786),#111790); -#111786 = LINE('',#111787,#111788); -#111787 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#111788 = VECTOR('',#111789,1.); -#111789 = DIRECTION('',(-1.,0.E+000)); -#111790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111791 = ADVANCED_FACE('',(#111792),#111658,.F.); -#111792 = FACE_BOUND('',#111793,.F.); -#111793 = EDGE_LOOP('',(#111794,#111817,#111844,#111869)); -#111794 = ORIENTED_EDGE('',*,*,#111795,.F.); -#111795 = EDGE_CURVE('',#111796,#111643,#111798,.T.); -#111796 = VERTEX_POINT('',#111797); -#111797 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.E+000)); -#111798 = SURFACE_CURVE('',#111799,(#111804,#111810),.PCURVE_S1.); -#111799 = CIRCLE('',#111800,0.208574704164); -#111800 = AXIS2_PLACEMENT_3D('',#111801,#111802,#111803); -#111801 = CARTESIAN_POINT('',(-0.728168876214,2.85,2.640924866458E-017) - ); -#111802 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111803 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111804 = PCURVE('',#111658,#111805); -#111805 = DEFINITIONAL_REPRESENTATION('',(#111806),#111809); -#111806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111807,#111808), +#114168 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#114169 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#114170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114171 = PCURVE('',#114172,#114177); +#114172 = PLANE('',#114173); +#114173 = AXIS2_PLACEMENT_3D('',#114174,#114175,#114176); +#114174 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#114175 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#114176 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114177 = DEFINITIONAL_REPRESENTATION('',(#114178),#114182); +#114178 = LINE('',#114179,#114180); +#114179 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#114180 = VECTOR('',#114181,1.); +#114181 = DIRECTION('',(-1.,0.E+000)); +#114182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114183 = ADVANCED_FACE('',(#114184),#114050,.F.); +#114184 = FACE_BOUND('',#114185,.F.); +#114185 = EDGE_LOOP('',(#114186,#114209,#114236,#114261)); +#114186 = ORIENTED_EDGE('',*,*,#114187,.F.); +#114187 = EDGE_CURVE('',#114188,#114035,#114190,.T.); +#114188 = VERTEX_POINT('',#114189); +#114189 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.E+000)); +#114190 = SURFACE_CURVE('',#114191,(#114196,#114202),.PCURVE_S1.); +#114191 = CIRCLE('',#114192,0.208574704164); +#114192 = AXIS2_PLACEMENT_3D('',#114193,#114194,#114195); +#114193 = CARTESIAN_POINT('',(-0.728168876214,2.85,2.640924866458E-017) + ); +#114194 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114195 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114196 = PCURVE('',#114050,#114197); +#114197 = DEFINITIONAL_REPRESENTATION('',(#114198),#114201); +#114198 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114199,#114200), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#111807 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#111808 = CARTESIAN_POINT('',(4.772630242227,-7.15)); -#111809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111810 = PCURVE('',#91665,#111811); -#111811 = DEFINITIONAL_REPRESENTATION('',(#111812),#111816); -#111812 = CIRCLE('',#111813,0.208574704164); -#111813 = AXIS2_PLACEMENT_2D('',#111814,#111815); -#111814 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#111815 = DIRECTION('',(0.E+000,-1.)); -#111816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111817 = ORIENTED_EDGE('',*,*,#111818,.F.); -#111818 = EDGE_CURVE('',#111819,#111796,#111821,.T.); -#111819 = VERTEX_POINT('',#111820); -#111820 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.E+000)); -#111821 = SURFACE_CURVE('',#111822,(#111826,#111832),.PCURVE_S1.); -#111822 = LINE('',#111823,#111824); -#111823 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#111824 = VECTOR('',#111825,1.); -#111825 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111826 = PCURVE('',#111658,#111827); -#111827 = DEFINITIONAL_REPRESENTATION('',(#111828),#111831); -#111828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111829,#111830), +#114199 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#114200 = CARTESIAN_POINT('',(4.772630242227,-7.15)); +#114201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114202 = PCURVE('',#94057,#114203); +#114203 = DEFINITIONAL_REPRESENTATION('',(#114204),#114208); +#114204 = CIRCLE('',#114205,0.208574704164); +#114205 = AXIS2_PLACEMENT_2D('',#114206,#114207); +#114206 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#114207 = DIRECTION('',(0.E+000,-1.)); +#114208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114209 = ORIENTED_EDGE('',*,*,#114210,.F.); +#114210 = EDGE_CURVE('',#114211,#114188,#114213,.T.); +#114211 = VERTEX_POINT('',#114212); +#114212 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.E+000)); +#114213 = SURFACE_CURVE('',#114214,(#114218,#114224),.PCURVE_S1.); +#114214 = LINE('',#114215,#114216); +#114215 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#114216 = VECTOR('',#114217,1.); +#114217 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114218 = PCURVE('',#114050,#114219); +#114219 = DEFINITIONAL_REPRESENTATION('',(#114220),#114223); +#114220 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114221,#114222), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#111829 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#111830 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#111831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111832 = PCURVE('',#111833,#111838); -#111833 = PLANE('',#111834); -#111834 = AXIS2_PLACEMENT_3D('',#111835,#111836,#111837); -#111835 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#111836 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#111837 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111838 = DEFINITIONAL_REPRESENTATION('',(#111839),#111843); -#111839 = LINE('',#111840,#111841); -#111840 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#111841 = VECTOR('',#111842,1.); -#111842 = DIRECTION('',(-1.,0.E+000)); -#111843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111844 = ORIENTED_EDGE('',*,*,#111845,.T.); -#111845 = EDGE_CURVE('',#111819,#111620,#111846,.T.); -#111846 = SURFACE_CURVE('',#111847,(#111852,#111858),.PCURVE_S1.); -#111847 = CIRCLE('',#111848,0.208574704164); -#111848 = AXIS2_PLACEMENT_3D('',#111849,#111850,#111851); -#111849 = CARTESIAN_POINT('',(-0.728168876214,2.65,2.640924866458E-017) - ); -#111850 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111851 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#111852 = PCURVE('',#111658,#111853); -#111853 = DEFINITIONAL_REPRESENTATION('',(#111854),#111857); -#111854 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111855,#111856), +#114221 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#114222 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#114223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114224 = PCURVE('',#114225,#114230); +#114225 = PLANE('',#114226); +#114226 = AXIS2_PLACEMENT_3D('',#114227,#114228,#114229); +#114227 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#114228 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#114229 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114230 = DEFINITIONAL_REPRESENTATION('',(#114231),#114235); +#114231 = LINE('',#114232,#114233); +#114232 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#114233 = VECTOR('',#114234,1.); +#114234 = DIRECTION('',(-1.,0.E+000)); +#114235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114236 = ORIENTED_EDGE('',*,*,#114237,.T.); +#114237 = EDGE_CURVE('',#114211,#114012,#114238,.T.); +#114238 = SURFACE_CURVE('',#114239,(#114244,#114250),.PCURVE_S1.); +#114239 = CIRCLE('',#114240,0.208574704164); +#114240 = AXIS2_PLACEMENT_3D('',#114241,#114242,#114243); +#114241 = CARTESIAN_POINT('',(-0.728168876214,2.65,2.640924866458E-017) + ); +#114242 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114243 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114244 = PCURVE('',#114050,#114245); +#114245 = DEFINITIONAL_REPRESENTATION('',(#114246),#114249); +#114246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114247,#114248), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#111855 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#111856 = CARTESIAN_POINT('',(4.772630242227,-7.35)); -#111857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#114247 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#114248 = CARTESIAN_POINT('',(4.772630242227,-7.35)); +#114249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#111858 = PCURVE('',#91609,#111859); -#111859 = DEFINITIONAL_REPRESENTATION('',(#111860),#111868); -#111860 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#111861,#111862,#111863, - #111864,#111865,#111866,#111867),.UNSPECIFIED.,.T.,.F.) +#114250 = PCURVE('',#94001,#114251); +#114251 = DEFINITIONAL_REPRESENTATION('',(#114252),#114260); +#114252 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114253,#114254,#114255, + #114256,#114257,#114258,#114259),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#111861 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#111862 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#111863 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#111864 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#111865 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#111866 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#111867 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#111868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111869 = ORIENTED_EDGE('',*,*,#111642,.F.); -#111870 = ADVANCED_FACE('',(#111871),#111833,.T.); -#111871 = FACE_BOUND('',#111872,.T.); -#111872 = EDGE_LOOP('',(#111873,#111902,#111923,#111924)); -#111873 = ORIENTED_EDGE('',*,*,#111874,.T.); -#111874 = EDGE_CURVE('',#111875,#111877,#111879,.T.); -#111875 = VERTEX_POINT('',#111876); -#111876 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.530776333563)); -#111877 = VERTEX_POINT('',#111878); -#111878 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.530776333563)); -#111879 = SURFACE_CURVE('',#111880,(#111884,#111891),.PCURVE_S1.); -#111880 = LINE('',#111881,#111882); -#111881 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#111882 = VECTOR('',#111883,1.); -#111883 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#111884 = PCURVE('',#111833,#111885); -#111885 = DEFINITIONAL_REPRESENTATION('',(#111886),#111890); -#111886 = LINE('',#111887,#111888); -#111887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111888 = VECTOR('',#111889,1.); -#111889 = DIRECTION('',(-1.,0.E+000)); -#111890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111891 = PCURVE('',#111892,#111897); -#111892 = CYLINDRICAL_SURFACE('',#111893,0.2192697516); -#111893 = AXIS2_PLACEMENT_3D('',#111894,#111895,#111896); -#111894 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#111895 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111896 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111897 = DEFINITIONAL_REPRESENTATION('',(#111898),#111901); -#111898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111899,#111900), +#114253 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#114254 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#114255 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#114256 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#114257 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#114258 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#114259 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#114260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114261 = ORIENTED_EDGE('',*,*,#114034,.F.); +#114262 = ADVANCED_FACE('',(#114263),#114225,.T.); +#114263 = FACE_BOUND('',#114264,.T.); +#114264 = EDGE_LOOP('',(#114265,#114294,#114315,#114316)); +#114265 = ORIENTED_EDGE('',*,*,#114266,.T.); +#114266 = EDGE_CURVE('',#114267,#114269,#114271,.T.); +#114267 = VERTEX_POINT('',#114268); +#114268 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.530776333563)); +#114269 = VERTEX_POINT('',#114270); +#114270 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.530776333563)); +#114271 = SURFACE_CURVE('',#114272,(#114276,#114283),.PCURVE_S1.); +#114272 = LINE('',#114273,#114274); +#114273 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#114274 = VECTOR('',#114275,1.); +#114275 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114276 = PCURVE('',#114225,#114277); +#114277 = DEFINITIONAL_REPRESENTATION('',(#114278),#114282); +#114278 = LINE('',#114279,#114280); +#114279 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114280 = VECTOR('',#114281,1.); +#114281 = DIRECTION('',(-1.,0.E+000)); +#114282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114283 = PCURVE('',#114284,#114289); +#114284 = CYLINDRICAL_SURFACE('',#114285,0.2192697516); +#114285 = AXIS2_PLACEMENT_3D('',#114286,#114287,#114288); +#114286 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#114287 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114288 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114289 = DEFINITIONAL_REPRESENTATION('',(#114290),#114293); +#114290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114291,#114292), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#111899 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#111900 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#111901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111902 = ORIENTED_EDGE('',*,*,#111903,.T.); -#111903 = EDGE_CURVE('',#111877,#111796,#111904,.T.); -#111904 = SURFACE_CURVE('',#111905,(#111909,#111916),.PCURVE_S1.); -#111905 = LINE('',#111906,#111907); -#111906 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.530776333563)); -#111907 = VECTOR('',#111908,1.); -#111908 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#111909 = PCURVE('',#111833,#111910); -#111910 = DEFINITIONAL_REPRESENTATION('',(#111911),#111915); -#111911 = LINE('',#111912,#111913); -#111912 = CARTESIAN_POINT('',(7.15,4.535643882845E-033)); -#111913 = VECTOR('',#111914,1.); -#111914 = DIRECTION('',(-4.535643882845E-032,-1.)); -#111915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111916 = PCURVE('',#91665,#111917); -#111917 = DEFINITIONAL_REPRESENTATION('',(#111918),#111922); -#111918 = LINE('',#111919,#111920); -#111919 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#111920 = VECTOR('',#111921,1.); -#111921 = DIRECTION('',(-1.,-1.021336205033E-016)); -#111922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111923 = ORIENTED_EDGE('',*,*,#111818,.F.); -#111924 = ORIENTED_EDGE('',*,*,#111925,.F.); -#111925 = EDGE_CURVE('',#111875,#111819,#111926,.T.); -#111926 = SURFACE_CURVE('',#111927,(#111931,#111938),.PCURVE_S1.); -#111927 = LINE('',#111928,#111929); -#111928 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.530776333563)); -#111929 = VECTOR('',#111930,1.); -#111930 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#111931 = PCURVE('',#111833,#111932); -#111932 = DEFINITIONAL_REPRESENTATION('',(#111933),#111937); -#111933 = LINE('',#111934,#111935); -#111934 = CARTESIAN_POINT('',(7.35,-4.535643882845E-033)); -#111935 = VECTOR('',#111936,1.); -#111936 = DIRECTION('',(-4.535643882845E-032,-1.)); -#111937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111938 = PCURVE('',#91609,#111939); -#111939 = DEFINITIONAL_REPRESENTATION('',(#111940),#111944); -#111940 = LINE('',#111941,#111942); -#111941 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#111942 = VECTOR('',#111943,1.); -#111943 = DIRECTION('',(1.,-1.021336205033E-016)); -#111944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111945 = ADVANCED_FACE('',(#111946),#111780,.T.); -#111946 = FACE_BOUND('',#111947,.T.); -#111947 = EDGE_LOOP('',(#111948,#111977,#111998,#111999)); -#111948 = ORIENTED_EDGE('',*,*,#111949,.T.); -#111949 = EDGE_CURVE('',#111950,#111952,#111954,.T.); -#111950 = VERTEX_POINT('',#111951); -#111951 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.530776333563)); -#111952 = VERTEX_POINT('',#111953); -#111953 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.530776333563)); -#111954 = SURFACE_CURVE('',#111955,(#111959,#111966),.PCURVE_S1.); -#111955 = LINE('',#111956,#111957); -#111956 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#111957 = VECTOR('',#111958,1.); -#111958 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111959 = PCURVE('',#111780,#111960); -#111960 = DEFINITIONAL_REPRESENTATION('',(#111961),#111965); -#111961 = LINE('',#111962,#111963); -#111962 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#111963 = VECTOR('',#111964,1.); -#111964 = DIRECTION('',(-1.,0.E+000)); -#111965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111966 = PCURVE('',#111967,#111972); -#111967 = CYLINDRICAL_SURFACE('',#111968,0.119270391569); -#111968 = AXIS2_PLACEMENT_3D('',#111969,#111970,#111971); -#111969 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#111970 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#111971 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#111972 = DEFINITIONAL_REPRESENTATION('',(#111973),#111976); -#111973 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#111974,#111975), +#114291 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#114292 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#114293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114294 = ORIENTED_EDGE('',*,*,#114295,.T.); +#114295 = EDGE_CURVE('',#114269,#114188,#114296,.T.); +#114296 = SURFACE_CURVE('',#114297,(#114301,#114308),.PCURVE_S1.); +#114297 = LINE('',#114298,#114299); +#114298 = CARTESIAN_POINT('',(-0.51959417205,2.85,0.530776333563)); +#114299 = VECTOR('',#114300,1.); +#114300 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#114301 = PCURVE('',#114225,#114302); +#114302 = DEFINITIONAL_REPRESENTATION('',(#114303),#114307); +#114303 = LINE('',#114304,#114305); +#114304 = CARTESIAN_POINT('',(7.15,4.535643882845E-033)); +#114305 = VECTOR('',#114306,1.); +#114306 = DIRECTION('',(-4.535643882845E-032,-1.)); +#114307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114308 = PCURVE('',#94057,#114309); +#114309 = DEFINITIONAL_REPRESENTATION('',(#114310),#114314); +#114310 = LINE('',#114311,#114312); +#114311 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#114312 = VECTOR('',#114313,1.); +#114313 = DIRECTION('',(-1.,-1.021336205033E-016)); +#114314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114315 = ORIENTED_EDGE('',*,*,#114210,.F.); +#114316 = ORIENTED_EDGE('',*,*,#114317,.F.); +#114317 = EDGE_CURVE('',#114267,#114211,#114318,.T.); +#114318 = SURFACE_CURVE('',#114319,(#114323,#114330),.PCURVE_S1.); +#114319 = LINE('',#114320,#114321); +#114320 = CARTESIAN_POINT('',(-0.51959417205,2.65,0.530776333563)); +#114321 = VECTOR('',#114322,1.); +#114322 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#114323 = PCURVE('',#114225,#114324); +#114324 = DEFINITIONAL_REPRESENTATION('',(#114325),#114329); +#114325 = LINE('',#114326,#114327); +#114326 = CARTESIAN_POINT('',(7.35,-4.535643882845E-033)); +#114327 = VECTOR('',#114328,1.); +#114328 = DIRECTION('',(-4.535643882845E-032,-1.)); +#114329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114330 = PCURVE('',#94001,#114331); +#114331 = DEFINITIONAL_REPRESENTATION('',(#114332),#114336); +#114332 = LINE('',#114333,#114334); +#114333 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#114334 = VECTOR('',#114335,1.); +#114335 = DIRECTION('',(1.,-1.021336205033E-016)); +#114336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114337 = ADVANCED_FACE('',(#114338),#114172,.T.); +#114338 = FACE_BOUND('',#114339,.T.); +#114339 = EDGE_LOOP('',(#114340,#114369,#114390,#114391)); +#114340 = ORIENTED_EDGE('',*,*,#114341,.T.); +#114341 = EDGE_CURVE('',#114342,#114344,#114346,.T.); +#114342 = VERTEX_POINT('',#114343); +#114343 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.530776333563)); +#114344 = VERTEX_POINT('',#114345); +#114345 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.530776333563)); +#114346 = SURFACE_CURVE('',#114347,(#114351,#114358),.PCURVE_S1.); +#114347 = LINE('',#114348,#114349); +#114348 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#114349 = VECTOR('',#114350,1.); +#114350 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114351 = PCURVE('',#114172,#114352); +#114352 = DEFINITIONAL_REPRESENTATION('',(#114353),#114357); +#114353 = LINE('',#114354,#114355); +#114354 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114355 = VECTOR('',#114356,1.); +#114356 = DIRECTION('',(-1.,0.E+000)); +#114357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114358 = PCURVE('',#114359,#114364); +#114359 = CYLINDRICAL_SURFACE('',#114360,0.119270391569); +#114360 = AXIS2_PLACEMENT_3D('',#114361,#114362,#114363); +#114361 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#114362 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114363 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114364 = DEFINITIONAL_REPRESENTATION('',(#114365),#114368); +#114365 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114366,#114367), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#111974 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#111975 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#111976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111977 = ORIENTED_EDGE('',*,*,#111978,.T.); -#111978 = EDGE_CURVE('',#111952,#111694,#111979,.T.); -#111979 = SURFACE_CURVE('',#111980,(#111984,#111991),.PCURVE_S1.); -#111980 = LINE('',#111981,#111982); -#111981 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.530776333563)); -#111982 = VECTOR('',#111983,1.); -#111983 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#111984 = PCURVE('',#111780,#111985); -#111985 = DEFINITIONAL_REPRESENTATION('',(#111986),#111990); -#111986 = LINE('',#111987,#111988); -#111987 = CARTESIAN_POINT('',(-7.35,1.133910970711E-033)); -#111988 = VECTOR('',#111989,1.); -#111989 = DIRECTION('',(4.535643882845E-032,-1.)); -#111990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111991 = PCURVE('',#91609,#111992); -#111992 = DEFINITIONAL_REPRESENTATION('',(#111993),#111997); -#111993 = LINE('',#111994,#111995); -#111994 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#111995 = VECTOR('',#111996,1.); -#111996 = DIRECTION('',(1.,-1.021336205033E-016)); -#111997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#111998 = ORIENTED_EDGE('',*,*,#111767,.F.); -#111999 = ORIENTED_EDGE('',*,*,#112000,.F.); -#112000 = EDGE_CURVE('',#111950,#111722,#112001,.T.); -#112001 = SURFACE_CURVE('',#112002,(#112006,#112013),.PCURVE_S1.); -#112002 = LINE('',#112003,#112004); -#112003 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.530776333563)); -#112004 = VECTOR('',#112005,1.); -#112005 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#112006 = PCURVE('',#111780,#112007); -#112007 = DEFINITIONAL_REPRESENTATION('',(#112008),#112012); -#112008 = LINE('',#112009,#112010); -#112009 = CARTESIAN_POINT('',(-7.15,-1.133910970711E-033)); -#112010 = VECTOR('',#112011,1.); -#112011 = DIRECTION('',(4.535643882845E-032,-1.)); -#112012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112013 = PCURVE('',#91665,#112014); -#112014 = DEFINITIONAL_REPRESENTATION('',(#112015),#112019); -#112015 = LINE('',#112016,#112017); -#112016 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#112017 = VECTOR('',#112018,1.); -#112018 = DIRECTION('',(-1.,-1.021336205033E-016)); -#112019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112020 = ADVANCED_FACE('',(#112021),#111967,.F.); -#112021 = FACE_BOUND('',#112022,.F.); -#112022 = EDGE_LOOP('',(#112023,#112024,#112047,#112092)); -#112023 = ORIENTED_EDGE('',*,*,#111949,.T.); -#112024 = ORIENTED_EDGE('',*,*,#112025,.F.); -#112025 = EDGE_CURVE('',#112026,#111952,#112028,.T.); -#112026 = VERTEX_POINT('',#112027); -#112027 = CARTESIAN_POINT('',(-0.303662633502,2.65,0.65)); -#112028 = SURFACE_CURVE('',#112029,(#112034,#112040),.PCURVE_S1.); -#112029 = CIRCLE('',#112030,0.119270391569); -#112030 = AXIS2_PLACEMENT_3D('',#112031,#112032,#112033); -#112031 = CARTESIAN_POINT('',(-0.30032442045,2.65,0.530776333563)); -#112032 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112033 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112034 = PCURVE('',#111967,#112035); -#112035 = DEFINITIONAL_REPRESENTATION('',(#112036),#112039); -#112036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112037,#112038), +#114366 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#114367 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#114368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114369 = ORIENTED_EDGE('',*,*,#114370,.T.); +#114370 = EDGE_CURVE('',#114344,#114086,#114371,.T.); +#114371 = SURFACE_CURVE('',#114372,(#114376,#114383),.PCURVE_S1.); +#114372 = LINE('',#114373,#114374); +#114373 = CARTESIAN_POINT('',(-0.419594812019,2.65,0.530776333563)); +#114374 = VECTOR('',#114375,1.); +#114375 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#114376 = PCURVE('',#114172,#114377); +#114377 = DEFINITIONAL_REPRESENTATION('',(#114378),#114382); +#114378 = LINE('',#114379,#114380); +#114379 = CARTESIAN_POINT('',(-7.35,1.133910970711E-033)); +#114380 = VECTOR('',#114381,1.); +#114381 = DIRECTION('',(4.535643882845E-032,-1.)); +#114382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114383 = PCURVE('',#94001,#114384); +#114384 = DEFINITIONAL_REPRESENTATION('',(#114385),#114389); +#114385 = LINE('',#114386,#114387); +#114386 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#114387 = VECTOR('',#114388,1.); +#114388 = DIRECTION('',(1.,-1.021336205033E-016)); +#114389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114390 = ORIENTED_EDGE('',*,*,#114159,.F.); +#114391 = ORIENTED_EDGE('',*,*,#114392,.F.); +#114392 = EDGE_CURVE('',#114342,#114114,#114393,.T.); +#114393 = SURFACE_CURVE('',#114394,(#114398,#114405),.PCURVE_S1.); +#114394 = LINE('',#114395,#114396); +#114395 = CARTESIAN_POINT('',(-0.419594812019,2.85,0.530776333563)); +#114396 = VECTOR('',#114397,1.); +#114397 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#114398 = PCURVE('',#114172,#114399); +#114399 = DEFINITIONAL_REPRESENTATION('',(#114400),#114404); +#114400 = LINE('',#114401,#114402); +#114401 = CARTESIAN_POINT('',(-7.15,-1.133910970711E-033)); +#114402 = VECTOR('',#114403,1.); +#114403 = DIRECTION('',(4.535643882845E-032,-1.)); +#114404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114405 = PCURVE('',#94057,#114406); +#114406 = DEFINITIONAL_REPRESENTATION('',(#114407),#114411); +#114407 = LINE('',#114408,#114409); +#114408 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#114409 = VECTOR('',#114410,1.); +#114410 = DIRECTION('',(-1.,-1.021336205033E-016)); +#114411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114412 = ADVANCED_FACE('',(#114413),#114359,.F.); +#114413 = FACE_BOUND('',#114414,.F.); +#114414 = EDGE_LOOP('',(#114415,#114416,#114439,#114484)); +#114415 = ORIENTED_EDGE('',*,*,#114341,.T.); +#114416 = ORIENTED_EDGE('',*,*,#114417,.F.); +#114417 = EDGE_CURVE('',#114418,#114344,#114420,.T.); +#114418 = VERTEX_POINT('',#114419); +#114419 = CARTESIAN_POINT('',(-0.303662633502,2.65,0.65)); +#114420 = SURFACE_CURVE('',#114421,(#114426,#114432),.PCURVE_S1.); +#114421 = CIRCLE('',#114422,0.119270391569); +#114422 = AXIS2_PLACEMENT_3D('',#114423,#114424,#114425); +#114423 = CARTESIAN_POINT('',(-0.30032442045,2.65,0.530776333563)); +#114424 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114425 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114426 = PCURVE('',#114359,#114427); +#114427 = DEFINITIONAL_REPRESENTATION('',(#114428),#114431); +#114428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114429,#114430), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#112037 = CARTESIAN_POINT('',(1.598788597134,7.35)); -#112038 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#112039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112040 = PCURVE('',#91609,#112041); -#112041 = DEFINITIONAL_REPRESENTATION('',(#112042),#112046); -#112042 = CIRCLE('',#112043,0.119270391569); -#112043 = AXIS2_PLACEMENT_2D('',#112044,#112045); -#112044 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#112045 = DIRECTION('',(0.E+000,1.)); -#112046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112047 = ORIENTED_EDGE('',*,*,#112048,.T.); -#112048 = EDGE_CURVE('',#112026,#112049,#112051,.T.); -#112049 = VERTEX_POINT('',#112050); -#112050 = CARTESIAN_POINT('',(-0.303662633502,2.85,0.65)); -#112051 = SURFACE_CURVE('',#112052,(#112056,#112085),.PCURVE_S1.); -#112052 = LINE('',#112053,#112054); -#112053 = CARTESIAN_POINT('',(-0.303662633502,2.85,0.65)); -#112054 = VECTOR('',#112055,1.); -#112055 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112056 = PCURVE('',#111967,#112057); -#112057 = DEFINITIONAL_REPRESENTATION('',(#112058),#112084); -#112058 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112059,#112060,#112061, - #112062,#112063,#112064,#112065,#112066,#112067,#112068,#112069, - #112070,#112071,#112072,#112073,#112074,#112075,#112076,#112077, - #112078,#112079,#112080,#112081,#112082,#112083),.UNSPECIFIED.,.F., +#114429 = CARTESIAN_POINT('',(1.598788597134,7.35)); +#114430 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#114431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114432 = PCURVE('',#94001,#114433); +#114433 = DEFINITIONAL_REPRESENTATION('',(#114434),#114438); +#114434 = CIRCLE('',#114435,0.119270391569); +#114435 = AXIS2_PLACEMENT_2D('',#114436,#114437); +#114436 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#114437 = DIRECTION('',(0.E+000,1.)); +#114438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114439 = ORIENTED_EDGE('',*,*,#114440,.T.); +#114440 = EDGE_CURVE('',#114418,#114441,#114443,.T.); +#114441 = VERTEX_POINT('',#114442); +#114442 = CARTESIAN_POINT('',(-0.303662633502,2.85,0.65)); +#114443 = SURFACE_CURVE('',#114444,(#114448,#114477),.PCURVE_S1.); +#114444 = LINE('',#114445,#114446); +#114445 = CARTESIAN_POINT('',(-0.303662633502,2.85,0.65)); +#114446 = VECTOR('',#114447,1.); +#114447 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114448 = PCURVE('',#114359,#114449); +#114449 = DEFINITIONAL_REPRESENTATION('',(#114450),#114476); +#114450 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114451,#114452,#114453, + #114454,#114455,#114456,#114457,#114458,#114459,#114460,#114461, + #114462,#114463,#114464,#114465,#114466,#114467,#114468,#114469, + #114470,#114471,#114472,#114473,#114474,#114475),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -138038,128 +141040,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#112059 = CARTESIAN_POINT('',(1.598788597134,7.35)); -#112060 = CARTESIAN_POINT('',(1.598788597134,7.34696969697)); -#112061 = CARTESIAN_POINT('',(1.598788597134,7.340909090909)); -#112062 = CARTESIAN_POINT('',(1.598788597134,7.331818181818)); -#112063 = CARTESIAN_POINT('',(1.598788597134,7.322727272727)); -#112064 = CARTESIAN_POINT('',(1.598788597134,7.313636363636)); -#112065 = CARTESIAN_POINT('',(1.598788597134,7.304545454545)); -#112066 = CARTESIAN_POINT('',(1.598788597134,7.295454545455)); -#112067 = CARTESIAN_POINT('',(1.598788597134,7.286363636364)); -#112068 = CARTESIAN_POINT('',(1.598788597134,7.277272727273)); -#112069 = CARTESIAN_POINT('',(1.598788597134,7.268181818182)); -#112070 = CARTESIAN_POINT('',(1.598788597134,7.259090909091)); -#112071 = CARTESIAN_POINT('',(1.598788597134,7.25)); -#112072 = CARTESIAN_POINT('',(1.598788597134,7.240909090909)); -#112073 = CARTESIAN_POINT('',(1.598788597134,7.231818181818)); -#112074 = CARTESIAN_POINT('',(1.598788597134,7.222727272727)); -#112075 = CARTESIAN_POINT('',(1.598788597134,7.213636363636)); -#112076 = CARTESIAN_POINT('',(1.598788597134,7.204545454545)); -#112077 = CARTESIAN_POINT('',(1.598788597134,7.195454545455)); -#112078 = CARTESIAN_POINT('',(1.598788597134,7.186363636364)); -#112079 = CARTESIAN_POINT('',(1.598788597134,7.177272727273)); -#112080 = CARTESIAN_POINT('',(1.598788597134,7.168181818182)); -#112081 = CARTESIAN_POINT('',(1.598788597134,7.159090909091)); -#112082 = CARTESIAN_POINT('',(1.598788597134,7.15303030303)); -#112083 = CARTESIAN_POINT('',(1.598788597134,7.15)); -#112084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112085 = PCURVE('',#91637,#112086); -#112086 = DEFINITIONAL_REPRESENTATION('',(#112087),#112091); -#112087 = LINE('',#112088,#112089); -#112088 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#112089 = VECTOR('',#112090,1.); -#112090 = DIRECTION('',(4.440892098501E-016,1.)); -#112091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112092 = ORIENTED_EDGE('',*,*,#112093,.T.); -#112093 = EDGE_CURVE('',#112049,#111950,#112094,.T.); -#112094 = SURFACE_CURVE('',#112095,(#112100,#112106),.PCURVE_S1.); -#112095 = CIRCLE('',#112096,0.119270391569); -#112096 = AXIS2_PLACEMENT_3D('',#112097,#112098,#112099); -#112097 = CARTESIAN_POINT('',(-0.30032442045,2.85,0.530776333563)); -#112098 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112099 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112100 = PCURVE('',#111967,#112101); -#112101 = DEFINITIONAL_REPRESENTATION('',(#112102),#112105); -#112102 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112103,#112104), +#114451 = CARTESIAN_POINT('',(1.598788597134,7.35)); +#114452 = CARTESIAN_POINT('',(1.598788597134,7.34696969697)); +#114453 = CARTESIAN_POINT('',(1.598788597134,7.340909090909)); +#114454 = CARTESIAN_POINT('',(1.598788597134,7.331818181818)); +#114455 = CARTESIAN_POINT('',(1.598788597134,7.322727272727)); +#114456 = CARTESIAN_POINT('',(1.598788597134,7.313636363636)); +#114457 = CARTESIAN_POINT('',(1.598788597134,7.304545454545)); +#114458 = CARTESIAN_POINT('',(1.598788597134,7.295454545455)); +#114459 = CARTESIAN_POINT('',(1.598788597134,7.286363636364)); +#114460 = CARTESIAN_POINT('',(1.598788597134,7.277272727273)); +#114461 = CARTESIAN_POINT('',(1.598788597134,7.268181818182)); +#114462 = CARTESIAN_POINT('',(1.598788597134,7.259090909091)); +#114463 = CARTESIAN_POINT('',(1.598788597134,7.25)); +#114464 = CARTESIAN_POINT('',(1.598788597134,7.240909090909)); +#114465 = CARTESIAN_POINT('',(1.598788597134,7.231818181818)); +#114466 = CARTESIAN_POINT('',(1.598788597134,7.222727272727)); +#114467 = CARTESIAN_POINT('',(1.598788597134,7.213636363636)); +#114468 = CARTESIAN_POINT('',(1.598788597134,7.204545454545)); +#114469 = CARTESIAN_POINT('',(1.598788597134,7.195454545455)); +#114470 = CARTESIAN_POINT('',(1.598788597134,7.186363636364)); +#114471 = CARTESIAN_POINT('',(1.598788597134,7.177272727273)); +#114472 = CARTESIAN_POINT('',(1.598788597134,7.168181818182)); +#114473 = CARTESIAN_POINT('',(1.598788597134,7.159090909091)); +#114474 = CARTESIAN_POINT('',(1.598788597134,7.15303030303)); +#114475 = CARTESIAN_POINT('',(1.598788597134,7.15)); +#114476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114477 = PCURVE('',#94029,#114478); +#114478 = DEFINITIONAL_REPRESENTATION('',(#114479),#114483); +#114479 = LINE('',#114480,#114481); +#114480 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#114481 = VECTOR('',#114482,1.); +#114482 = DIRECTION('',(4.440892098501E-016,1.)); +#114483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114484 = ORIENTED_EDGE('',*,*,#114485,.T.); +#114485 = EDGE_CURVE('',#114441,#114342,#114486,.T.); +#114486 = SURFACE_CURVE('',#114487,(#114492,#114498),.PCURVE_S1.); +#114487 = CIRCLE('',#114488,0.119270391569); +#114488 = AXIS2_PLACEMENT_3D('',#114489,#114490,#114491); +#114489 = CARTESIAN_POINT('',(-0.30032442045,2.85,0.530776333563)); +#114490 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114491 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114492 = PCURVE('',#114359,#114493); +#114493 = DEFINITIONAL_REPRESENTATION('',(#114494),#114497); +#114494 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114495,#114496), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#112103 = CARTESIAN_POINT('',(1.598788597134,7.15)); -#112104 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#112105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#114495 = CARTESIAN_POINT('',(1.598788597134,7.15)); +#114496 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#114497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112106 = PCURVE('',#91665,#112107); -#112107 = DEFINITIONAL_REPRESENTATION('',(#112108),#112116); -#112108 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112109,#112110,#112111, - #112112,#112113,#112114,#112115),.UNSPECIFIED.,.T.,.F.) +#114498 = PCURVE('',#94057,#114499); +#114499 = DEFINITIONAL_REPRESENTATION('',(#114500),#114508); +#114500 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114501,#114502,#114503, + #114504,#114505,#114506,#114507),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#112109 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#112110 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#112111 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#112112 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#112113 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#112114 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#112115 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#112116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112117 = ADVANCED_FACE('',(#112118),#111892,.T.); -#112118 = FACE_BOUND('',#112119,.T.); -#112119 = EDGE_LOOP('',(#112120,#112121,#112144,#112189)); -#112120 = ORIENTED_EDGE('',*,*,#111874,.F.); -#112121 = ORIENTED_EDGE('',*,*,#112122,.F.); -#112122 = EDGE_CURVE('',#112123,#111875,#112125,.T.); -#112123 = VERTEX_POINT('',#112124); -#112124 = CARTESIAN_POINT('',(-0.304819755875,2.65,0.75)); -#112125 = SURFACE_CURVE('',#112126,(#112131,#112137),.PCURVE_S1.); -#112126 = CIRCLE('',#112127,0.2192697516); -#112127 = AXIS2_PLACEMENT_3D('',#112128,#112129,#112130); -#112128 = CARTESIAN_POINT('',(-0.30032442045,2.65,0.530776333563)); -#112129 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112130 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112131 = PCURVE('',#111892,#112132); -#112132 = DEFINITIONAL_REPRESENTATION('',(#112133),#112136); -#112133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112134,#112135), +#114501 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#114502 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#114503 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#114504 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#114505 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#114506 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#114507 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#114508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114509 = ADVANCED_FACE('',(#114510),#114284,.T.); +#114510 = FACE_BOUND('',#114511,.T.); +#114511 = EDGE_LOOP('',(#114512,#114513,#114536,#114581)); +#114512 = ORIENTED_EDGE('',*,*,#114266,.F.); +#114513 = ORIENTED_EDGE('',*,*,#114514,.F.); +#114514 = EDGE_CURVE('',#114515,#114267,#114517,.T.); +#114515 = VERTEX_POINT('',#114516); +#114516 = CARTESIAN_POINT('',(-0.304819755875,2.65,0.75)); +#114517 = SURFACE_CURVE('',#114518,(#114523,#114529),.PCURVE_S1.); +#114518 = CIRCLE('',#114519,0.2192697516); +#114519 = AXIS2_PLACEMENT_3D('',#114520,#114521,#114522); +#114520 = CARTESIAN_POINT('',(-0.30032442045,2.65,0.530776333563)); +#114521 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114522 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114523 = PCURVE('',#114284,#114524); +#114524 = DEFINITIONAL_REPRESENTATION('',(#114525),#114528); +#114525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114526,#114527), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#112134 = CARTESIAN_POINT('',(1.591299156552,7.35)); -#112135 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#112136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112137 = PCURVE('',#91609,#112138); -#112138 = DEFINITIONAL_REPRESENTATION('',(#112139),#112143); -#112139 = CIRCLE('',#112140,0.2192697516); -#112140 = AXIS2_PLACEMENT_2D('',#112141,#112142); -#112141 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#112142 = DIRECTION('',(0.E+000,1.)); -#112143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112144 = ORIENTED_EDGE('',*,*,#112145,.F.); -#112145 = EDGE_CURVE('',#112146,#112123,#112148,.T.); -#112146 = VERTEX_POINT('',#112147); -#112147 = CARTESIAN_POINT('',(-0.304819755875,2.85,0.75)); -#112148 = SURFACE_CURVE('',#112149,(#112153,#112182),.PCURVE_S1.); -#112149 = LINE('',#112150,#112151); -#112150 = CARTESIAN_POINT('',(-0.304819755875,2.85,0.75)); -#112151 = VECTOR('',#112152,1.); -#112152 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112153 = PCURVE('',#111892,#112154); -#112154 = DEFINITIONAL_REPRESENTATION('',(#112155),#112181); -#112155 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112156,#112157,#112158, - #112159,#112160,#112161,#112162,#112163,#112164,#112165,#112166, - #112167,#112168,#112169,#112170,#112171,#112172,#112173,#112174, - #112175,#112176,#112177,#112178,#112179,#112180),.UNSPECIFIED.,.F., +#114526 = CARTESIAN_POINT('',(1.591299156552,7.35)); +#114527 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#114528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114529 = PCURVE('',#94001,#114530); +#114530 = DEFINITIONAL_REPRESENTATION('',(#114531),#114535); +#114531 = CIRCLE('',#114532,0.2192697516); +#114532 = AXIS2_PLACEMENT_2D('',#114533,#114534); +#114533 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#114534 = DIRECTION('',(0.E+000,1.)); +#114535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114536 = ORIENTED_EDGE('',*,*,#114537,.F.); +#114537 = EDGE_CURVE('',#114538,#114515,#114540,.T.); +#114538 = VERTEX_POINT('',#114539); +#114539 = CARTESIAN_POINT('',(-0.304819755875,2.85,0.75)); +#114540 = SURFACE_CURVE('',#114541,(#114545,#114574),.PCURVE_S1.); +#114541 = LINE('',#114542,#114543); +#114542 = CARTESIAN_POINT('',(-0.304819755875,2.85,0.75)); +#114543 = VECTOR('',#114544,1.); +#114544 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114545 = PCURVE('',#114284,#114546); +#114546 = DEFINITIONAL_REPRESENTATION('',(#114547),#114573); +#114547 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114548,#114549,#114550, + #114551,#114552,#114553,#114554,#114555,#114556,#114557,#114558, + #114559,#114560,#114561,#114562,#114563,#114564,#114565,#114566, + #114567,#114568,#114569,#114570,#114571,#114572),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -138168,57 +141170,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#112156 = CARTESIAN_POINT('',(1.591299156552,7.15)); -#112157 = CARTESIAN_POINT('',(1.591299156552,7.15303030303)); -#112158 = CARTESIAN_POINT('',(1.591299156552,7.159090909091)); -#112159 = CARTESIAN_POINT('',(1.591299156552,7.168181818182)); -#112160 = CARTESIAN_POINT('',(1.591299156552,7.177272727273)); -#112161 = CARTESIAN_POINT('',(1.591299156552,7.186363636364)); -#112162 = CARTESIAN_POINT('',(1.591299156552,7.195454545455)); -#112163 = CARTESIAN_POINT('',(1.591299156552,7.204545454545)); -#112164 = CARTESIAN_POINT('',(1.591299156552,7.213636363636)); -#112165 = CARTESIAN_POINT('',(1.591299156552,7.222727272727)); -#112166 = CARTESIAN_POINT('',(1.591299156552,7.231818181818)); -#112167 = CARTESIAN_POINT('',(1.591299156552,7.240909090909)); -#112168 = CARTESIAN_POINT('',(1.591299156552,7.25)); -#112169 = CARTESIAN_POINT('',(1.591299156552,7.259090909091)); -#112170 = CARTESIAN_POINT('',(1.591299156552,7.268181818182)); -#112171 = CARTESIAN_POINT('',(1.591299156552,7.277272727273)); -#112172 = CARTESIAN_POINT('',(1.591299156552,7.286363636364)); -#112173 = CARTESIAN_POINT('',(1.591299156552,7.295454545455)); -#112174 = CARTESIAN_POINT('',(1.591299156552,7.304545454545)); -#112175 = CARTESIAN_POINT('',(1.591299156552,7.313636363636)); -#112176 = CARTESIAN_POINT('',(1.591299156552,7.322727272727)); -#112177 = CARTESIAN_POINT('',(1.591299156552,7.331818181818)); -#112178 = CARTESIAN_POINT('',(1.591299156552,7.340909090909)); -#112179 = CARTESIAN_POINT('',(1.591299156552,7.34696969697)); -#112180 = CARTESIAN_POINT('',(1.591299156552,7.35)); -#112181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112182 = PCURVE('',#91691,#112183); -#112183 = DEFINITIONAL_REPRESENTATION('',(#112184),#112188); -#112184 = LINE('',#112185,#112186); -#112185 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#112186 = VECTOR('',#112187,1.); -#112187 = DIRECTION('',(4.440892098501E-016,-1.)); -#112188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112189 = ORIENTED_EDGE('',*,*,#112190,.T.); -#112190 = EDGE_CURVE('',#112146,#111877,#112191,.T.); -#112191 = SURFACE_CURVE('',#112192,(#112197,#112226),.PCURVE_S1.); -#112192 = CIRCLE('',#112193,0.2192697516); -#112193 = AXIS2_PLACEMENT_3D('',#112194,#112195,#112196); -#112194 = CARTESIAN_POINT('',(-0.30032442045,2.85,0.530776333563)); -#112195 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112196 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112197 = PCURVE('',#111892,#112198); -#112198 = DEFINITIONAL_REPRESENTATION('',(#112199),#112225); -#112199 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112200,#112201,#112202, - #112203,#112204,#112205,#112206,#112207,#112208,#112209,#112210, - #112211,#112212,#112213,#112214,#112215,#112216,#112217,#112218, - #112219,#112220,#112221,#112222,#112223,#112224),.UNSPECIFIED.,.F., +#114548 = CARTESIAN_POINT('',(1.591299156552,7.15)); +#114549 = CARTESIAN_POINT('',(1.591299156552,7.15303030303)); +#114550 = CARTESIAN_POINT('',(1.591299156552,7.159090909091)); +#114551 = CARTESIAN_POINT('',(1.591299156552,7.168181818182)); +#114552 = CARTESIAN_POINT('',(1.591299156552,7.177272727273)); +#114553 = CARTESIAN_POINT('',(1.591299156552,7.186363636364)); +#114554 = CARTESIAN_POINT('',(1.591299156552,7.195454545455)); +#114555 = CARTESIAN_POINT('',(1.591299156552,7.204545454545)); +#114556 = CARTESIAN_POINT('',(1.591299156552,7.213636363636)); +#114557 = CARTESIAN_POINT('',(1.591299156552,7.222727272727)); +#114558 = CARTESIAN_POINT('',(1.591299156552,7.231818181818)); +#114559 = CARTESIAN_POINT('',(1.591299156552,7.240909090909)); +#114560 = CARTESIAN_POINT('',(1.591299156552,7.25)); +#114561 = CARTESIAN_POINT('',(1.591299156552,7.259090909091)); +#114562 = CARTESIAN_POINT('',(1.591299156552,7.268181818182)); +#114563 = CARTESIAN_POINT('',(1.591299156552,7.277272727273)); +#114564 = CARTESIAN_POINT('',(1.591299156552,7.286363636364)); +#114565 = CARTESIAN_POINT('',(1.591299156552,7.295454545455)); +#114566 = CARTESIAN_POINT('',(1.591299156552,7.304545454545)); +#114567 = CARTESIAN_POINT('',(1.591299156552,7.313636363636)); +#114568 = CARTESIAN_POINT('',(1.591299156552,7.322727272727)); +#114569 = CARTESIAN_POINT('',(1.591299156552,7.331818181818)); +#114570 = CARTESIAN_POINT('',(1.591299156552,7.340909090909)); +#114571 = CARTESIAN_POINT('',(1.591299156552,7.34696969697)); +#114572 = CARTESIAN_POINT('',(1.591299156552,7.35)); +#114573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114574 = PCURVE('',#94083,#114575); +#114575 = DEFINITIONAL_REPRESENTATION('',(#114576),#114580); +#114576 = LINE('',#114577,#114578); +#114577 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#114578 = VECTOR('',#114579,1.); +#114579 = DIRECTION('',(4.440892098501E-016,-1.)); +#114580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114581 = ORIENTED_EDGE('',*,*,#114582,.T.); +#114582 = EDGE_CURVE('',#114538,#114269,#114583,.T.); +#114583 = SURFACE_CURVE('',#114584,(#114589,#114618),.PCURVE_S1.); +#114584 = CIRCLE('',#114585,0.2192697516); +#114585 = AXIS2_PLACEMENT_3D('',#114586,#114587,#114588); +#114586 = CARTESIAN_POINT('',(-0.30032442045,2.85,0.530776333563)); +#114587 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114588 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#114589 = PCURVE('',#114284,#114590); +#114590 = DEFINITIONAL_REPRESENTATION('',(#114591),#114617); +#114591 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114592,#114593,#114594, + #114595,#114596,#114597,#114598,#114599,#114600,#114601,#114602, + #114603,#114604,#114605,#114606,#114607,#114608,#114609,#114610, + #114611,#114612,#114613,#114614,#114615,#114616),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -138226,929 +141228,929 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#112200 = CARTESIAN_POINT('',(1.591299156552,7.15)); -#112201 = CARTESIAN_POINT('',(1.614788451962,7.15)); -#112202 = CARTESIAN_POINT('',(1.661767042781,7.15)); -#112203 = CARTESIAN_POINT('',(1.73223492901,7.15)); -#112204 = CARTESIAN_POINT('',(1.802702815239,7.15)); -#112205 = CARTESIAN_POINT('',(1.873170701468,7.15)); -#112206 = CARTESIAN_POINT('',(1.943638587697,7.15)); -#112207 = CARTESIAN_POINT('',(2.014106473926,7.15)); -#112208 = CARTESIAN_POINT('',(2.084574360155,7.15)); -#112209 = CARTESIAN_POINT('',(2.155042246384,7.15)); -#112210 = CARTESIAN_POINT('',(2.225510132613,7.15)); -#112211 = CARTESIAN_POINT('',(2.295978018842,7.15)); -#112212 = CARTESIAN_POINT('',(2.366445905071,7.15)); -#112213 = CARTESIAN_POINT('',(2.4369137913,7.15)); -#112214 = CARTESIAN_POINT('',(2.507381677529,7.15)); -#112215 = CARTESIAN_POINT('',(2.577849563758,7.15)); -#112216 = CARTESIAN_POINT('',(2.648317449987,7.15)); -#112217 = CARTESIAN_POINT('',(2.718785336216,7.15)); -#112218 = CARTESIAN_POINT('',(2.789253222445,7.15)); -#112219 = CARTESIAN_POINT('',(2.859721108674,7.15)); -#112220 = CARTESIAN_POINT('',(2.930188994903,7.15)); -#112221 = CARTESIAN_POINT('',(3.000656881132,7.15)); -#112222 = CARTESIAN_POINT('',(3.071124767361,7.15)); -#112223 = CARTESIAN_POINT('',(3.11810335818,7.15)); -#112224 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#112225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112226 = PCURVE('',#91665,#112227); -#112227 = DEFINITIONAL_REPRESENTATION('',(#112228),#112236); -#112228 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112229,#112230,#112231, - #112232,#112233,#112234,#112235),.UNSPECIFIED.,.T.,.F.) +#114592 = CARTESIAN_POINT('',(1.591299156552,7.15)); +#114593 = CARTESIAN_POINT('',(1.614788451962,7.15)); +#114594 = CARTESIAN_POINT('',(1.661767042781,7.15)); +#114595 = CARTESIAN_POINT('',(1.73223492901,7.15)); +#114596 = CARTESIAN_POINT('',(1.802702815239,7.15)); +#114597 = CARTESIAN_POINT('',(1.873170701468,7.15)); +#114598 = CARTESIAN_POINT('',(1.943638587697,7.15)); +#114599 = CARTESIAN_POINT('',(2.014106473926,7.15)); +#114600 = CARTESIAN_POINT('',(2.084574360155,7.15)); +#114601 = CARTESIAN_POINT('',(2.155042246384,7.15)); +#114602 = CARTESIAN_POINT('',(2.225510132613,7.15)); +#114603 = CARTESIAN_POINT('',(2.295978018842,7.15)); +#114604 = CARTESIAN_POINT('',(2.366445905071,7.15)); +#114605 = CARTESIAN_POINT('',(2.4369137913,7.15)); +#114606 = CARTESIAN_POINT('',(2.507381677529,7.15)); +#114607 = CARTESIAN_POINT('',(2.577849563758,7.15)); +#114608 = CARTESIAN_POINT('',(2.648317449987,7.15)); +#114609 = CARTESIAN_POINT('',(2.718785336216,7.15)); +#114610 = CARTESIAN_POINT('',(2.789253222445,7.15)); +#114611 = CARTESIAN_POINT('',(2.859721108674,7.15)); +#114612 = CARTESIAN_POINT('',(2.930188994903,7.15)); +#114613 = CARTESIAN_POINT('',(3.000656881132,7.15)); +#114614 = CARTESIAN_POINT('',(3.071124767361,7.15)); +#114615 = CARTESIAN_POINT('',(3.11810335818,7.15)); +#114616 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#114617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114618 = PCURVE('',#94057,#114619); +#114619 = DEFINITIONAL_REPRESENTATION('',(#114620),#114628); +#114620 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114621,#114622,#114623, + #114624,#114625,#114626,#114627),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#112229 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#112230 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#112231 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#112232 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#112233 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#112234 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#112235 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#112236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112237 = ADVANCED_FACE('',(#112238),#91637,.T.); -#112238 = FACE_BOUND('',#112239,.T.); -#112239 = EDGE_LOOP('',(#112240,#112261,#112262,#112283)); -#112240 = ORIENTED_EDGE('',*,*,#112241,.F.); -#112241 = EDGE_CURVE('',#112026,#91594,#112242,.T.); -#112242 = SURFACE_CURVE('',#112243,(#112247,#112254),.PCURVE_S1.); -#112243 = LINE('',#112244,#112245); -#112244 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.65)); -#112245 = VECTOR('',#112246,1.); -#112246 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#112247 = PCURVE('',#91637,#112248); -#112248 = DEFINITIONAL_REPRESENTATION('',(#112249),#112253); -#112249 = LINE('',#112250,#112251); -#112250 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#112251 = VECTOR('',#112252,1.); -#112252 = DIRECTION('',(-1.,-4.804757279354E-063)); -#112253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112254 = PCURVE('',#91609,#112255); -#112255 = DEFINITIONAL_REPRESENTATION('',(#112256),#112260); -#112256 = LINE('',#112257,#112258); -#112257 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112258 = VECTOR('',#112259,1.); -#112259 = DIRECTION('',(-3.563627120235E-016,1.)); -#112260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112261 = ORIENTED_EDGE('',*,*,#112048,.T.); -#112262 = ORIENTED_EDGE('',*,*,#112263,.T.); -#112263 = EDGE_CURVE('',#112049,#91622,#112264,.T.); -#112264 = SURFACE_CURVE('',#112265,(#112269,#112276),.PCURVE_S1.); -#112265 = LINE('',#112266,#112267); -#112266 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); -#112267 = VECTOR('',#112268,1.); -#112268 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#112269 = PCURVE('',#91637,#112270); -#112270 = DEFINITIONAL_REPRESENTATION('',(#112271),#112275); -#112271 = LINE('',#112272,#112273); -#112272 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112273 = VECTOR('',#112274,1.); -#112274 = DIRECTION('',(-1.,-4.804757279354E-063)); -#112275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112276 = PCURVE('',#91665,#112277); -#112277 = DEFINITIONAL_REPRESENTATION('',(#112278),#112282); -#112278 = LINE('',#112279,#112280); -#112279 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112280 = VECTOR('',#112281,1.); -#112281 = DIRECTION('',(3.563627120235E-016,1.)); -#112282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112283 = ORIENTED_EDGE('',*,*,#91621,.F.); -#112284 = ADVANCED_FACE('',(#112285),#91609,.T.); -#112285 = FACE_BOUND('',#112286,.T.); -#112286 = EDGE_LOOP('',(#112287,#112308,#112309,#112310,#112311,#112312, - #112333,#112334,#112335,#112336,#112337,#112338)); -#112287 = ORIENTED_EDGE('',*,*,#112288,.F.); -#112288 = EDGE_CURVE('',#112123,#91592,#112289,.T.); -#112289 = SURFACE_CURVE('',#112290,(#112294,#112301),.PCURVE_S1.); -#112290 = LINE('',#112291,#112292); -#112291 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.75)); -#112292 = VECTOR('',#112293,1.); -#112293 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#112294 = PCURVE('',#91609,#112295); -#112295 = DEFINITIONAL_REPRESENTATION('',(#112296),#112300); -#112296 = LINE('',#112297,#112298); -#112297 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#112298 = VECTOR('',#112299,1.); -#112299 = DIRECTION('',(-3.563627120235E-016,1.)); -#112300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112301 = PCURVE('',#91691,#112302); -#112302 = DEFINITIONAL_REPRESENTATION('',(#112303),#112307); -#112303 = LINE('',#112304,#112305); -#112304 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#112305 = VECTOR('',#112306,1.); -#112306 = DIRECTION('',(1.,-4.804757279354E-063)); -#112307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112308 = ORIENTED_EDGE('',*,*,#112122,.T.); -#112309 = ORIENTED_EDGE('',*,*,#111925,.T.); -#112310 = ORIENTED_EDGE('',*,*,#111845,.T.); -#112311 = ORIENTED_EDGE('',*,*,#111619,.T.); -#112312 = ORIENTED_EDGE('',*,*,#112313,.F.); -#112313 = EDGE_CURVE('',#111483,#111590,#112314,.T.); -#112314 = SURFACE_CURVE('',#112315,(#112319,#112326),.PCURVE_S1.); -#112315 = LINE('',#112316,#112317); -#112316 = CARTESIAN_POINT('',(-1.,2.65,1.159810404338E-002)); -#112317 = VECTOR('',#112318,1.); -#112318 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#112319 = PCURVE('',#91609,#112320); -#112320 = DEFINITIONAL_REPRESENTATION('',(#112321),#112325); -#112321 = LINE('',#112322,#112323); -#112322 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#112323 = VECTOR('',#112324,1.); -#112324 = DIRECTION('',(-1.,-2.101748079665E-016)); -#112325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112326 = PCURVE('',#111503,#112327); -#112327 = DEFINITIONAL_REPRESENTATION('',(#112328),#112332); -#112328 = LINE('',#112329,#112330); -#112329 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#112330 = VECTOR('',#112331,1.); -#112331 = DIRECTION('',(-1.194699204908E-017,1.)); -#112332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112333 = ORIENTED_EDGE('',*,*,#111565,.F.); -#112334 = ORIENTED_EDGE('',*,*,#111693,.F.); -#112335 = ORIENTED_EDGE('',*,*,#111978,.F.); -#112336 = ORIENTED_EDGE('',*,*,#112025,.F.); -#112337 = ORIENTED_EDGE('',*,*,#112241,.T.); -#112338 = ORIENTED_EDGE('',*,*,#91591,.F.); -#112339 = ADVANCED_FACE('',(#112340),#91691,.T.); -#112340 = FACE_BOUND('',#112341,.T.); -#112341 = EDGE_LOOP('',(#112342,#112363,#112364,#112365)); -#112342 = ORIENTED_EDGE('',*,*,#112343,.F.); -#112343 = EDGE_CURVE('',#112146,#91650,#112344,.T.); -#112344 = SURFACE_CURVE('',#112345,(#112349,#112356),.PCURVE_S1.); -#112345 = LINE('',#112346,#112347); -#112346 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.75)); -#112347 = VECTOR('',#112348,1.); -#112348 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#112349 = PCURVE('',#91691,#112350); -#112350 = DEFINITIONAL_REPRESENTATION('',(#112351),#112355); -#112351 = LINE('',#112352,#112353); -#112352 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112353 = VECTOR('',#112354,1.); -#112354 = DIRECTION('',(1.,-4.804757279354E-063)); -#112355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112356 = PCURVE('',#91665,#112357); -#112357 = DEFINITIONAL_REPRESENTATION('',(#112358),#112362); -#112358 = LINE('',#112359,#112360); -#112359 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#112360 = VECTOR('',#112361,1.); -#112361 = DIRECTION('',(3.563627120235E-016,1.)); -#112362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#114621 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#114622 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#114623 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#114624 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#114625 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#114626 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#114627 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#114628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114629 = ADVANCED_FACE('',(#114630),#94029,.T.); +#114630 = FACE_BOUND('',#114631,.T.); +#114631 = EDGE_LOOP('',(#114632,#114653,#114654,#114675)); +#114632 = ORIENTED_EDGE('',*,*,#114633,.F.); +#114633 = EDGE_CURVE('',#114418,#93986,#114634,.T.); +#114634 = SURFACE_CURVE('',#114635,(#114639,#114646),.PCURVE_S1.); +#114635 = LINE('',#114636,#114637); +#114636 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.65)); +#114637 = VECTOR('',#114638,1.); +#114638 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#114639 = PCURVE('',#94029,#114640); +#114640 = DEFINITIONAL_REPRESENTATION('',(#114641),#114645); +#114641 = LINE('',#114642,#114643); +#114642 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#114643 = VECTOR('',#114644,1.); +#114644 = DIRECTION('',(-1.,-4.804757279354E-063)); +#114645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114646 = PCURVE('',#94001,#114647); +#114647 = DEFINITIONAL_REPRESENTATION('',(#114648),#114652); +#114648 = LINE('',#114649,#114650); +#114649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114650 = VECTOR('',#114651,1.); +#114651 = DIRECTION('',(-3.563627120235E-016,1.)); +#114652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114653 = ORIENTED_EDGE('',*,*,#114440,.T.); +#114654 = ORIENTED_EDGE('',*,*,#114655,.T.); +#114655 = EDGE_CURVE('',#114441,#94014,#114656,.T.); +#114656 = SURFACE_CURVE('',#114657,(#114661,#114668),.PCURVE_S1.); +#114657 = LINE('',#114658,#114659); +#114658 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.65)); +#114659 = VECTOR('',#114660,1.); +#114660 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#114661 = PCURVE('',#94029,#114662); +#114662 = DEFINITIONAL_REPRESENTATION('',(#114663),#114667); +#114663 = LINE('',#114664,#114665); +#114664 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114665 = VECTOR('',#114666,1.); +#114666 = DIRECTION('',(-1.,-4.804757279354E-063)); +#114667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114668 = PCURVE('',#94057,#114669); +#114669 = DEFINITIONAL_REPRESENTATION('',(#114670),#114674); +#114670 = LINE('',#114671,#114672); +#114671 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114672 = VECTOR('',#114673,1.); +#114673 = DIRECTION('',(3.563627120235E-016,1.)); +#114674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114675 = ORIENTED_EDGE('',*,*,#94013,.F.); +#114676 = ADVANCED_FACE('',(#114677),#94001,.T.); +#114677 = FACE_BOUND('',#114678,.T.); +#114678 = EDGE_LOOP('',(#114679,#114700,#114701,#114702,#114703,#114704, + #114725,#114726,#114727,#114728,#114729,#114730)); +#114679 = ORIENTED_EDGE('',*,*,#114680,.F.); +#114680 = EDGE_CURVE('',#114515,#93984,#114681,.T.); +#114681 = SURFACE_CURVE('',#114682,(#114686,#114693),.PCURVE_S1.); +#114682 = LINE('',#114683,#114684); +#114683 = CARTESIAN_POINT('',(-0.527847992439,2.65,0.75)); +#114684 = VECTOR('',#114685,1.); +#114685 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#114686 = PCURVE('',#94001,#114687); +#114687 = DEFINITIONAL_REPRESENTATION('',(#114688),#114692); +#114688 = LINE('',#114689,#114690); +#114689 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#114690 = VECTOR('',#114691,1.); +#114691 = DIRECTION('',(-3.563627120235E-016,1.)); +#114692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114693 = PCURVE('',#94083,#114694); +#114694 = DEFINITIONAL_REPRESENTATION('',(#114695),#114699); +#114695 = LINE('',#114696,#114697); +#114696 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#114697 = VECTOR('',#114698,1.); +#114698 = DIRECTION('',(1.,-4.804757279354E-063)); +#114699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114700 = ORIENTED_EDGE('',*,*,#114514,.T.); +#114701 = ORIENTED_EDGE('',*,*,#114317,.T.); +#114702 = ORIENTED_EDGE('',*,*,#114237,.T.); +#114703 = ORIENTED_EDGE('',*,*,#114011,.T.); +#114704 = ORIENTED_EDGE('',*,*,#114705,.F.); +#114705 = EDGE_CURVE('',#113875,#113982,#114706,.T.); +#114706 = SURFACE_CURVE('',#114707,(#114711,#114718),.PCURVE_S1.); +#114707 = LINE('',#114708,#114709); +#114708 = CARTESIAN_POINT('',(-1.,2.65,1.159810404338E-002)); +#114709 = VECTOR('',#114710,1.); +#114710 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#114711 = PCURVE('',#94001,#114712); +#114712 = DEFINITIONAL_REPRESENTATION('',(#114713),#114717); +#114713 = LINE('',#114714,#114715); +#114714 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#114715 = VECTOR('',#114716,1.); +#114716 = DIRECTION('',(-1.,-2.101748079665E-016)); +#114717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114718 = PCURVE('',#113895,#114719); +#114719 = DEFINITIONAL_REPRESENTATION('',(#114720),#114724); +#114720 = LINE('',#114721,#114722); +#114721 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#114722 = VECTOR('',#114723,1.); +#114723 = DIRECTION('',(-1.194699204908E-017,1.)); +#114724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112363 = ORIENTED_EDGE('',*,*,#112145,.T.); -#112364 = ORIENTED_EDGE('',*,*,#112288,.T.); -#112365 = ORIENTED_EDGE('',*,*,#91677,.F.); -#112366 = ADVANCED_FACE('',(#112367),#91665,.T.); -#112367 = FACE_BOUND('',#112368,.T.); -#112368 = EDGE_LOOP('',(#112369,#112370,#112371,#112372,#112373,#112374, - #112395,#112396,#112397,#112398,#112399,#112400)); -#112369 = ORIENTED_EDGE('',*,*,#112263,.F.); -#112370 = ORIENTED_EDGE('',*,*,#112093,.T.); -#112371 = ORIENTED_EDGE('',*,*,#112000,.T.); -#112372 = ORIENTED_EDGE('',*,*,#111721,.T.); -#112373 = ORIENTED_EDGE('',*,*,#111515,.T.); -#112374 = ORIENTED_EDGE('',*,*,#112375,.F.); -#112375 = EDGE_CURVE('',#111592,#111481,#112376,.T.); -#112376 = SURFACE_CURVE('',#112377,(#112381,#112388),.PCURVE_S1.); -#112377 = LINE('',#112378,#112379); -#112378 = CARTESIAN_POINT('',(-1.,2.85,1.159810404338E-002)); -#112379 = VECTOR('',#112380,1.); -#112380 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#112381 = PCURVE('',#91665,#112382); -#112382 = DEFINITIONAL_REPRESENTATION('',(#112383),#112387); -#112383 = LINE('',#112384,#112385); -#112384 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#112385 = VECTOR('',#112386,1.); -#112386 = DIRECTION('',(-1.,2.101748079665E-016)); -#112387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112388 = PCURVE('',#111503,#112389); -#112389 = DEFINITIONAL_REPRESENTATION('',(#112390),#112394); -#112390 = LINE('',#112391,#112392); -#112391 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#112392 = VECTOR('',#112393,1.); -#112393 = DIRECTION('',(1.194699204908E-017,-1.)); -#112394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112395 = ORIENTED_EDGE('',*,*,#111669,.F.); -#112396 = ORIENTED_EDGE('',*,*,#111795,.F.); -#112397 = ORIENTED_EDGE('',*,*,#111903,.F.); -#112398 = ORIENTED_EDGE('',*,*,#112190,.F.); -#112399 = ORIENTED_EDGE('',*,*,#112343,.T.); -#112400 = ORIENTED_EDGE('',*,*,#91649,.F.); -#112401 = ADVANCED_FACE('',(#112402),#111503,.T.); -#112402 = FACE_BOUND('',#112403,.T.); -#112403 = EDGE_LOOP('',(#112404,#112405,#112406,#112407)); -#112404 = ORIENTED_EDGE('',*,*,#112313,.T.); -#112405 = ORIENTED_EDGE('',*,*,#111589,.T.); -#112406 = ORIENTED_EDGE('',*,*,#112375,.T.); -#112407 = ORIENTED_EDGE('',*,*,#111480,.T.); -#112408 = ADVANCED_FACE('',(#112409),#112423,.F.); -#112409 = FACE_BOUND('',#112410,.T.); -#112410 = EDGE_LOOP('',(#112411,#112446,#112469,#112496)); -#112411 = ORIENTED_EDGE('',*,*,#112412,.F.); -#112412 = EDGE_CURVE('',#112413,#112415,#112417,.T.); -#112413 = VERTEX_POINT('',#112414); -#112414 = CARTESIAN_POINT('',(-1.,3.35,-0.308197125857)); -#112415 = VERTEX_POINT('',#112416); -#112416 = CARTESIAN_POINT('',(-1.,3.15,-0.308197125857)); -#112417 = SURFACE_CURVE('',#112418,(#112422,#112434),.PCURVE_S1.); -#112418 = LINE('',#112419,#112420); -#112419 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#112420 = VECTOR('',#112421,1.); -#112421 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112422 = PCURVE('',#112423,#112428); -#112423 = PLANE('',#112424); -#112424 = AXIS2_PLACEMENT_3D('',#112425,#112426,#112427); -#112425 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#112426 = DIRECTION('',(0.E+000,0.E+000,1.)); -#112427 = DIRECTION('',(1.,0.E+000,0.E+000)); -#112428 = DEFINITIONAL_REPRESENTATION('',(#112429),#112433); -#112429 = LINE('',#112430,#112431); -#112430 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#112431 = VECTOR('',#112432,1.); -#112432 = DIRECTION('',(4.440892098501E-016,-1.)); -#112433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112434 = PCURVE('',#112435,#112440); -#112435 = PLANE('',#112436); -#112436 = AXIS2_PLACEMENT_3D('',#112437,#112438,#112439); -#112437 = CARTESIAN_POINT('',(-1.,3.25,-0.258196742327)); -#112438 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#112439 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112440 = DEFINITIONAL_REPRESENTATION('',(#112441),#112445); -#112441 = LINE('',#112442,#112443); -#112442 = CARTESIAN_POINT('',(-6.75,-5.000038352949E-002)); -#112443 = VECTOR('',#112444,1.); -#112444 = DIRECTION('',(1.,0.E+000)); -#112445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112446 = ORIENTED_EDGE('',*,*,#112447,.F.); -#112447 = EDGE_CURVE('',#112448,#112413,#112450,.T.); -#112448 = VERTEX_POINT('',#112449); -#112449 = CARTESIAN_POINT('',(-0.74341632541,3.35,-0.308197125857)); -#112450 = SURFACE_CURVE('',#112451,(#112455,#112462),.PCURVE_S1.); -#112451 = LINE('',#112452,#112453); -#112452 = CARTESIAN_POINT('',(-0.74341632541,3.35,-0.308197125857)); -#112453 = VECTOR('',#112454,1.); -#112454 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#112455 = PCURVE('',#112423,#112456); -#112456 = DEFINITIONAL_REPRESENTATION('',(#112457),#112461); -#112457 = LINE('',#112458,#112459); -#112458 = CARTESIAN_POINT('',(2.886579864025E-015,-6.65)); -#112459 = VECTOR('',#112460,1.); -#112460 = DIRECTION('',(-1.,0.E+000)); -#112461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112462 = PCURVE('',#91551,#112463); -#112463 = DEFINITIONAL_REPRESENTATION('',(#112464),#112468); -#112464 = LINE('',#112465,#112466); -#112465 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#112466 = VECTOR('',#112467,1.); -#112467 = DIRECTION('',(0.E+000,-1.)); -#112468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112469 = ORIENTED_EDGE('',*,*,#112470,.F.); -#112470 = EDGE_CURVE('',#112471,#112448,#112473,.T.); -#112471 = VERTEX_POINT('',#112472); -#112472 = CARTESIAN_POINT('',(-0.74341632541,3.15,-0.308197125857)); -#112473 = SURFACE_CURVE('',#112474,(#112478,#112485),.PCURVE_S1.); -#112474 = LINE('',#112475,#112476); -#112475 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#112476 = VECTOR('',#112477,1.); -#112477 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112478 = PCURVE('',#112423,#112479); -#112479 = DEFINITIONAL_REPRESENTATION('',(#112480),#112484); -#112480 = LINE('',#112481,#112482); -#112481 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112482 = VECTOR('',#112483,1.); -#112483 = DIRECTION('',(-4.440892098501E-016,1.)); -#112484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112485 = PCURVE('',#112486,#112491); -#112486 = CYLINDRICAL_SURFACE('',#112487,0.308574064194); -#112487 = AXIS2_PLACEMENT_3D('',#112488,#112489,#112490); -#112488 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#112489 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112490 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112491 = DEFINITIONAL_REPRESENTATION('',(#112492),#112495); -#112492 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112493,#112494), +#114725 = ORIENTED_EDGE('',*,*,#113957,.F.); +#114726 = ORIENTED_EDGE('',*,*,#114085,.F.); +#114727 = ORIENTED_EDGE('',*,*,#114370,.F.); +#114728 = ORIENTED_EDGE('',*,*,#114417,.F.); +#114729 = ORIENTED_EDGE('',*,*,#114633,.T.); +#114730 = ORIENTED_EDGE('',*,*,#93983,.F.); +#114731 = ADVANCED_FACE('',(#114732),#94083,.T.); +#114732 = FACE_BOUND('',#114733,.T.); +#114733 = EDGE_LOOP('',(#114734,#114755,#114756,#114757)); +#114734 = ORIENTED_EDGE('',*,*,#114735,.F.); +#114735 = EDGE_CURVE('',#114538,#94042,#114736,.T.); +#114736 = SURFACE_CURVE('',#114737,(#114741,#114748),.PCURVE_S1.); +#114737 = LINE('',#114738,#114739); +#114738 = CARTESIAN_POINT('',(-0.527847992439,2.85,0.75)); +#114739 = VECTOR('',#114740,1.); +#114740 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#114741 = PCURVE('',#94083,#114742); +#114742 = DEFINITIONAL_REPRESENTATION('',(#114743),#114747); +#114743 = LINE('',#114744,#114745); +#114744 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114745 = VECTOR('',#114746,1.); +#114746 = DIRECTION('',(1.,-4.804757279354E-063)); +#114747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114748 = PCURVE('',#94057,#114749); +#114749 = DEFINITIONAL_REPRESENTATION('',(#114750),#114754); +#114750 = LINE('',#114751,#114752); +#114751 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#114752 = VECTOR('',#114753,1.); +#114753 = DIRECTION('',(3.563627120235E-016,1.)); +#114754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114755 = ORIENTED_EDGE('',*,*,#114537,.T.); +#114756 = ORIENTED_EDGE('',*,*,#114680,.T.); +#114757 = ORIENTED_EDGE('',*,*,#94069,.F.); +#114758 = ADVANCED_FACE('',(#114759),#94057,.T.); +#114759 = FACE_BOUND('',#114760,.T.); +#114760 = EDGE_LOOP('',(#114761,#114762,#114763,#114764,#114765,#114766, + #114787,#114788,#114789,#114790,#114791,#114792)); +#114761 = ORIENTED_EDGE('',*,*,#114655,.F.); +#114762 = ORIENTED_EDGE('',*,*,#114485,.T.); +#114763 = ORIENTED_EDGE('',*,*,#114392,.T.); +#114764 = ORIENTED_EDGE('',*,*,#114113,.T.); +#114765 = ORIENTED_EDGE('',*,*,#113907,.T.); +#114766 = ORIENTED_EDGE('',*,*,#114767,.F.); +#114767 = EDGE_CURVE('',#113984,#113873,#114768,.T.); +#114768 = SURFACE_CURVE('',#114769,(#114773,#114780),.PCURVE_S1.); +#114769 = LINE('',#114770,#114771); +#114770 = CARTESIAN_POINT('',(-1.,2.85,1.159810404338E-002)); +#114771 = VECTOR('',#114772,1.); +#114772 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#114773 = PCURVE('',#94057,#114774); +#114774 = DEFINITIONAL_REPRESENTATION('',(#114775),#114779); +#114775 = LINE('',#114776,#114777); +#114776 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#114777 = VECTOR('',#114778,1.); +#114778 = DIRECTION('',(-1.,2.101748079665E-016)); +#114779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114780 = PCURVE('',#113895,#114781); +#114781 = DEFINITIONAL_REPRESENTATION('',(#114782),#114786); +#114782 = LINE('',#114783,#114784); +#114783 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#114784 = VECTOR('',#114785,1.); +#114785 = DIRECTION('',(1.194699204908E-017,-1.)); +#114786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114787 = ORIENTED_EDGE('',*,*,#114061,.F.); +#114788 = ORIENTED_EDGE('',*,*,#114187,.F.); +#114789 = ORIENTED_EDGE('',*,*,#114295,.F.); +#114790 = ORIENTED_EDGE('',*,*,#114582,.F.); +#114791 = ORIENTED_EDGE('',*,*,#114735,.T.); +#114792 = ORIENTED_EDGE('',*,*,#94041,.F.); +#114793 = ADVANCED_FACE('',(#114794),#113895,.T.); +#114794 = FACE_BOUND('',#114795,.T.); +#114795 = EDGE_LOOP('',(#114796,#114797,#114798,#114799)); +#114796 = ORIENTED_EDGE('',*,*,#114705,.T.); +#114797 = ORIENTED_EDGE('',*,*,#113981,.T.); +#114798 = ORIENTED_EDGE('',*,*,#114767,.T.); +#114799 = ORIENTED_EDGE('',*,*,#113872,.T.); +#114800 = ADVANCED_FACE('',(#114801),#114815,.F.); +#114801 = FACE_BOUND('',#114802,.T.); +#114802 = EDGE_LOOP('',(#114803,#114838,#114861,#114888)); +#114803 = ORIENTED_EDGE('',*,*,#114804,.F.); +#114804 = EDGE_CURVE('',#114805,#114807,#114809,.T.); +#114805 = VERTEX_POINT('',#114806); +#114806 = CARTESIAN_POINT('',(-1.,3.35,-0.308197125857)); +#114807 = VERTEX_POINT('',#114808); +#114808 = CARTESIAN_POINT('',(-1.,3.15,-0.308197125857)); +#114809 = SURFACE_CURVE('',#114810,(#114814,#114826),.PCURVE_S1.); +#114810 = LINE('',#114811,#114812); +#114811 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#114812 = VECTOR('',#114813,1.); +#114813 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114814 = PCURVE('',#114815,#114820); +#114815 = PLANE('',#114816); +#114816 = AXIS2_PLACEMENT_3D('',#114817,#114818,#114819); +#114817 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#114818 = DIRECTION('',(0.E+000,0.E+000,1.)); +#114819 = DIRECTION('',(1.,0.E+000,0.E+000)); +#114820 = DEFINITIONAL_REPRESENTATION('',(#114821),#114825); +#114821 = LINE('',#114822,#114823); +#114822 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#114823 = VECTOR('',#114824,1.); +#114824 = DIRECTION('',(4.440892098501E-016,-1.)); +#114825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114826 = PCURVE('',#114827,#114832); +#114827 = PLANE('',#114828); +#114828 = AXIS2_PLACEMENT_3D('',#114829,#114830,#114831); +#114829 = CARTESIAN_POINT('',(-1.,3.25,-0.258196742327)); +#114830 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#114831 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114832 = DEFINITIONAL_REPRESENTATION('',(#114833),#114837); +#114833 = LINE('',#114834,#114835); +#114834 = CARTESIAN_POINT('',(-6.75,-5.000038352949E-002)); +#114835 = VECTOR('',#114836,1.); +#114836 = DIRECTION('',(1.,0.E+000)); +#114837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114838 = ORIENTED_EDGE('',*,*,#114839,.F.); +#114839 = EDGE_CURVE('',#114840,#114805,#114842,.T.); +#114840 = VERTEX_POINT('',#114841); +#114841 = CARTESIAN_POINT('',(-0.74341632541,3.35,-0.308197125857)); +#114842 = SURFACE_CURVE('',#114843,(#114847,#114854),.PCURVE_S1.); +#114843 = LINE('',#114844,#114845); +#114844 = CARTESIAN_POINT('',(-0.74341632541,3.35,-0.308197125857)); +#114845 = VECTOR('',#114846,1.); +#114846 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114847 = PCURVE('',#114815,#114848); +#114848 = DEFINITIONAL_REPRESENTATION('',(#114849),#114853); +#114849 = LINE('',#114850,#114851); +#114850 = CARTESIAN_POINT('',(2.886579864025E-015,-6.65)); +#114851 = VECTOR('',#114852,1.); +#114852 = DIRECTION('',(-1.,0.E+000)); +#114853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114854 = PCURVE('',#93943,#114855); +#114855 = DEFINITIONAL_REPRESENTATION('',(#114856),#114860); +#114856 = LINE('',#114857,#114858); +#114857 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#114858 = VECTOR('',#114859,1.); +#114859 = DIRECTION('',(0.E+000,-1.)); +#114860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114861 = ORIENTED_EDGE('',*,*,#114862,.F.); +#114862 = EDGE_CURVE('',#114863,#114840,#114865,.T.); +#114863 = VERTEX_POINT('',#114864); +#114864 = CARTESIAN_POINT('',(-0.74341632541,3.15,-0.308197125857)); +#114865 = SURFACE_CURVE('',#114866,(#114870,#114877),.PCURVE_S1.); +#114866 = LINE('',#114867,#114868); +#114867 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#114868 = VECTOR('',#114869,1.); +#114869 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114870 = PCURVE('',#114815,#114871); +#114871 = DEFINITIONAL_REPRESENTATION('',(#114872),#114876); +#114872 = LINE('',#114873,#114874); +#114873 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114874 = VECTOR('',#114875,1.); +#114875 = DIRECTION('',(-4.440892098501E-016,1.)); +#114876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114877 = PCURVE('',#114878,#114883); +#114878 = CYLINDRICAL_SURFACE('',#114879,0.308574064194); +#114879 = AXIS2_PLACEMENT_3D('',#114880,#114881,#114882); +#114880 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#114881 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114882 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114883 = DEFINITIONAL_REPRESENTATION('',(#114884),#114887); +#114884 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114885,#114886), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#112493 = CARTESIAN_POINT('',(4.761821717947,-6.85)); -#112494 = CARTESIAN_POINT('',(4.761821717947,-6.65)); -#112495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#114885 = CARTESIAN_POINT('',(4.761821717947,-6.85)); +#114886 = CARTESIAN_POINT('',(4.761821717947,-6.65)); +#114887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114888 = ORIENTED_EDGE('',*,*,#114889,.T.); +#114889 = EDGE_CURVE('',#114863,#114807,#114890,.T.); +#114890 = SURFACE_CURVE('',#114891,(#114895,#114902),.PCURVE_S1.); +#114891 = LINE('',#114892,#114893); +#114892 = CARTESIAN_POINT('',(-0.74341632541,3.15,-0.308197125857)); +#114893 = VECTOR('',#114894,1.); +#114894 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114895 = PCURVE('',#114815,#114896); +#114896 = DEFINITIONAL_REPRESENTATION('',(#114897),#114901); +#114897 = LINE('',#114898,#114899); +#114898 = CARTESIAN_POINT('',(3.10862446895E-015,-6.85)); +#114899 = VECTOR('',#114900,1.); +#114900 = DIRECTION('',(-1.,0.E+000)); +#114901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114902 = PCURVE('',#93887,#114903); +#114903 = DEFINITIONAL_REPRESENTATION('',(#114904),#114908); +#114904 = LINE('',#114905,#114906); +#114905 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#114906 = VECTOR('',#114907,1.); +#114907 = DIRECTION('',(0.E+000,-1.)); +#114908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114909 = ADVANCED_FACE('',(#114910),#114924,.F.); +#114910 = FACE_BOUND('',#114911,.T.); +#114911 = EDGE_LOOP('',(#114912,#114942,#114965,#114992)); +#114912 = ORIENTED_EDGE('',*,*,#114913,.F.); +#114913 = EDGE_CURVE('',#114914,#114916,#114918,.T.); +#114914 = VERTEX_POINT('',#114915); +#114915 = CARTESIAN_POINT('',(-1.,3.15,-0.208196358798)); +#114916 = VERTEX_POINT('',#114917); +#114917 = CARTESIAN_POINT('',(-1.,3.35,-0.208196358798)); +#114918 = SURFACE_CURVE('',#114919,(#114923,#114935),.PCURVE_S1.); +#114919 = LINE('',#114920,#114921); +#114920 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#114921 = VECTOR('',#114922,1.); +#114922 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114923 = PCURVE('',#114924,#114929); +#114924 = PLANE('',#114925); +#114925 = AXIS2_PLACEMENT_3D('',#114926,#114927,#114928); +#114926 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#114927 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#114928 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114929 = DEFINITIONAL_REPRESENTATION('',(#114930),#114934); +#114930 = LINE('',#114931,#114932); +#114931 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#114932 = VECTOR('',#114933,1.); +#114933 = DIRECTION('',(4.440892098501E-016,1.)); +#114934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114935 = PCURVE('',#114827,#114936); +#114936 = DEFINITIONAL_REPRESENTATION('',(#114937),#114941); +#114937 = LINE('',#114938,#114939); +#114938 = CARTESIAN_POINT('',(-6.75,5.000038352949E-002)); +#114939 = VECTOR('',#114940,1.); +#114940 = DIRECTION('',(-1.,0.E+000)); +#114941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114942 = ORIENTED_EDGE('',*,*,#114943,.F.); +#114943 = EDGE_CURVE('',#114944,#114914,#114946,.T.); +#114944 = VERTEX_POINT('',#114945); +#114945 = CARTESIAN_POINT('',(-0.740726081328,3.15,-0.208196358798)); +#114946 = SURFACE_CURVE('',#114947,(#114951,#114958),.PCURVE_S1.); +#114947 = LINE('',#114948,#114949); +#114948 = CARTESIAN_POINT('',(-0.740726081328,3.15,-0.208196358798)); +#114949 = VECTOR('',#114950,1.); +#114950 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114951 = PCURVE('',#114924,#114952); +#114952 = DEFINITIONAL_REPRESENTATION('',(#114953),#114957); +#114953 = LINE('',#114954,#114955); +#114954 = CARTESIAN_POINT('',(-3.219646771413E-015,-6.85)); +#114955 = VECTOR('',#114956,1.); +#114956 = DIRECTION('',(1.,0.E+000)); +#114957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114958 = PCURVE('',#93887,#114959); +#114959 = DEFINITIONAL_REPRESENTATION('',(#114960),#114964); +#114960 = LINE('',#114961,#114962); +#114961 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#114962 = VECTOR('',#114963,1.); +#114963 = DIRECTION('',(0.E+000,-1.)); +#114964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112496 = ORIENTED_EDGE('',*,*,#112497,.T.); -#112497 = EDGE_CURVE('',#112471,#112415,#112498,.T.); -#112498 = SURFACE_CURVE('',#112499,(#112503,#112510),.PCURVE_S1.); -#112499 = LINE('',#112500,#112501); -#112500 = CARTESIAN_POINT('',(-0.74341632541,3.15,-0.308197125857)); -#112501 = VECTOR('',#112502,1.); -#112502 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#112503 = PCURVE('',#112423,#112504); -#112504 = DEFINITIONAL_REPRESENTATION('',(#112505),#112509); -#112505 = LINE('',#112506,#112507); -#112506 = CARTESIAN_POINT('',(3.10862446895E-015,-6.85)); -#112507 = VECTOR('',#112508,1.); -#112508 = DIRECTION('',(-1.,0.E+000)); -#112509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112510 = PCURVE('',#91495,#112511); -#112511 = DEFINITIONAL_REPRESENTATION('',(#112512),#112516); -#112512 = LINE('',#112513,#112514); -#112513 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#112514 = VECTOR('',#112515,1.); -#112515 = DIRECTION('',(0.E+000,-1.)); -#112516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112517 = ADVANCED_FACE('',(#112518),#112532,.F.); -#112518 = FACE_BOUND('',#112519,.T.); -#112519 = EDGE_LOOP('',(#112520,#112550,#112573,#112600)); -#112520 = ORIENTED_EDGE('',*,*,#112521,.F.); -#112521 = EDGE_CURVE('',#112522,#112524,#112526,.T.); -#112522 = VERTEX_POINT('',#112523); -#112523 = CARTESIAN_POINT('',(-1.,3.15,-0.208196358798)); -#112524 = VERTEX_POINT('',#112525); -#112525 = CARTESIAN_POINT('',(-1.,3.35,-0.208196358798)); -#112526 = SURFACE_CURVE('',#112527,(#112531,#112543),.PCURVE_S1.); -#112527 = LINE('',#112528,#112529); -#112528 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#112529 = VECTOR('',#112530,1.); -#112530 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112531 = PCURVE('',#112532,#112537); -#112532 = PLANE('',#112533); -#112533 = AXIS2_PLACEMENT_3D('',#112534,#112535,#112536); -#112534 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#112535 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#112536 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#112537 = DEFINITIONAL_REPRESENTATION('',(#112538),#112542); -#112538 = LINE('',#112539,#112540); -#112539 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#112540 = VECTOR('',#112541,1.); -#112541 = DIRECTION('',(4.440892098501E-016,1.)); -#112542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112543 = PCURVE('',#112435,#112544); -#112544 = DEFINITIONAL_REPRESENTATION('',(#112545),#112549); -#112545 = LINE('',#112546,#112547); -#112546 = CARTESIAN_POINT('',(-6.75,5.000038352949E-002)); -#112547 = VECTOR('',#112548,1.); -#112548 = DIRECTION('',(-1.,0.E+000)); -#112549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112550 = ORIENTED_EDGE('',*,*,#112551,.F.); -#112551 = EDGE_CURVE('',#112552,#112522,#112554,.T.); -#112552 = VERTEX_POINT('',#112553); -#112553 = CARTESIAN_POINT('',(-0.740726081328,3.15,-0.208196358798)); -#112554 = SURFACE_CURVE('',#112555,(#112559,#112566),.PCURVE_S1.); -#112555 = LINE('',#112556,#112557); -#112556 = CARTESIAN_POINT('',(-0.740726081328,3.15,-0.208196358798)); -#112557 = VECTOR('',#112558,1.); -#112558 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#112559 = PCURVE('',#112532,#112560); -#112560 = DEFINITIONAL_REPRESENTATION('',(#112561),#112565); -#112561 = LINE('',#112562,#112563); -#112562 = CARTESIAN_POINT('',(-3.219646771413E-015,-6.85)); -#112563 = VECTOR('',#112564,1.); -#112564 = DIRECTION('',(1.,0.E+000)); -#112565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112566 = PCURVE('',#91495,#112567); -#112567 = DEFINITIONAL_REPRESENTATION('',(#112568),#112572); -#112568 = LINE('',#112569,#112570); -#112569 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#112570 = VECTOR('',#112571,1.); -#112571 = DIRECTION('',(0.E+000,-1.)); -#112572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112573 = ORIENTED_EDGE('',*,*,#112574,.F.); -#112574 = EDGE_CURVE('',#112575,#112552,#112577,.T.); -#112575 = VERTEX_POINT('',#112576); -#112576 = CARTESIAN_POINT('',(-0.740726081328,3.35,-0.208196358798)); -#112577 = SURFACE_CURVE('',#112578,(#112582,#112589),.PCURVE_S1.); -#112578 = LINE('',#112579,#112580); -#112579 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#112580 = VECTOR('',#112581,1.); -#112581 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112582 = PCURVE('',#112532,#112583); -#112583 = DEFINITIONAL_REPRESENTATION('',(#112584),#112588); -#112584 = LINE('',#112585,#112586); -#112585 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112586 = VECTOR('',#112587,1.); -#112587 = DIRECTION('',(-4.440892098501E-016,-1.)); -#112588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112589 = PCURVE('',#112590,#112595); -#112590 = CYLINDRICAL_SURFACE('',#112591,0.208574704164); -#112591 = AXIS2_PLACEMENT_3D('',#112592,#112593,#112594); -#112592 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#112593 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112594 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112595 = DEFINITIONAL_REPRESENTATION('',(#112596),#112599); -#112596 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112597,#112598), +#114965 = ORIENTED_EDGE('',*,*,#114966,.F.); +#114966 = EDGE_CURVE('',#114967,#114944,#114969,.T.); +#114967 = VERTEX_POINT('',#114968); +#114968 = CARTESIAN_POINT('',(-0.740726081328,3.35,-0.208196358798)); +#114969 = SURFACE_CURVE('',#114970,(#114974,#114981),.PCURVE_S1.); +#114970 = LINE('',#114971,#114972); +#114971 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#114972 = VECTOR('',#114973,1.); +#114973 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#114974 = PCURVE('',#114924,#114975); +#114975 = DEFINITIONAL_REPRESENTATION('',(#114976),#114980); +#114976 = LINE('',#114977,#114978); +#114977 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#114978 = VECTOR('',#114979,1.); +#114979 = DIRECTION('',(-4.440892098501E-016,-1.)); +#114980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114981 = PCURVE('',#114982,#114987); +#114982 = CYLINDRICAL_SURFACE('',#114983,0.208574704164); +#114983 = AXIS2_PLACEMENT_3D('',#114984,#114985,#114986); +#114984 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#114985 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#114986 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#114987 = DEFINITIONAL_REPRESENTATION('',(#114988),#114991); +#114988 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114989,#114990), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#112597 = CARTESIAN_POINT('',(4.772630242227,-6.65)); -#112598 = CARTESIAN_POINT('',(4.772630242227,-6.85)); -#112599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112600 = ORIENTED_EDGE('',*,*,#112601,.T.); -#112601 = EDGE_CURVE('',#112575,#112524,#112602,.T.); -#112602 = SURFACE_CURVE('',#112603,(#112607,#112614),.PCURVE_S1.); -#112603 = LINE('',#112604,#112605); -#112604 = CARTESIAN_POINT('',(-0.740726081328,3.35,-0.208196358798)); -#112605 = VECTOR('',#112606,1.); -#112606 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#112607 = PCURVE('',#112532,#112608); -#112608 = DEFINITIONAL_REPRESENTATION('',(#112609),#112613); -#112609 = LINE('',#112610,#112611); -#112610 = CARTESIAN_POINT('',(-2.997602166488E-015,-6.65)); -#112611 = VECTOR('',#112612,1.); -#112612 = DIRECTION('',(1.,0.E+000)); -#112613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112614 = PCURVE('',#91551,#112615); -#112615 = DEFINITIONAL_REPRESENTATION('',(#112616),#112620); -#112616 = LINE('',#112617,#112618); -#112617 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#112618 = VECTOR('',#112619,1.); -#112619 = DIRECTION('',(0.E+000,-1.)); -#112620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112621 = ADVANCED_FACE('',(#112622),#112486,.T.); -#112622 = FACE_BOUND('',#112623,.T.); -#112623 = EDGE_LOOP('',(#112624,#112651,#112652,#112675)); -#112624 = ORIENTED_EDGE('',*,*,#112625,.T.); -#112625 = EDGE_CURVE('',#112626,#112471,#112628,.T.); -#112626 = VERTEX_POINT('',#112627); -#112627 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.E+000)); -#112628 = SURFACE_CURVE('',#112629,(#112634,#112640),.PCURVE_S1.); -#112629 = CIRCLE('',#112630,0.308574064194); -#112630 = AXIS2_PLACEMENT_3D('',#112631,#112632,#112633); -#112631 = CARTESIAN_POINT('',(-0.728168876214,3.15,2.640924866458E-017) - ); -#112632 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112633 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112634 = PCURVE('',#112486,#112635); -#112635 = DEFINITIONAL_REPRESENTATION('',(#112636),#112639); -#112636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112637,#112638), +#114989 = CARTESIAN_POINT('',(4.772630242227,-6.65)); +#114990 = CARTESIAN_POINT('',(4.772630242227,-6.85)); +#114991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#114992 = ORIENTED_EDGE('',*,*,#114993,.T.); +#114993 = EDGE_CURVE('',#114967,#114916,#114994,.T.); +#114994 = SURFACE_CURVE('',#114995,(#114999,#115006),.PCURVE_S1.); +#114995 = LINE('',#114996,#114997); +#114996 = CARTESIAN_POINT('',(-0.740726081328,3.35,-0.208196358798)); +#114997 = VECTOR('',#114998,1.); +#114998 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#114999 = PCURVE('',#114924,#115000); +#115000 = DEFINITIONAL_REPRESENTATION('',(#115001),#115005); +#115001 = LINE('',#115002,#115003); +#115002 = CARTESIAN_POINT('',(-2.997602166488E-015,-6.65)); +#115003 = VECTOR('',#115004,1.); +#115004 = DIRECTION('',(1.,0.E+000)); +#115005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115006 = PCURVE('',#93943,#115007); +#115007 = DEFINITIONAL_REPRESENTATION('',(#115008),#115012); +#115008 = LINE('',#115009,#115010); +#115009 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#115010 = VECTOR('',#115011,1.); +#115011 = DIRECTION('',(0.E+000,-1.)); +#115012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115013 = ADVANCED_FACE('',(#115014),#114878,.T.); +#115014 = FACE_BOUND('',#115015,.T.); +#115015 = EDGE_LOOP('',(#115016,#115043,#115044,#115067)); +#115016 = ORIENTED_EDGE('',*,*,#115017,.T.); +#115017 = EDGE_CURVE('',#115018,#114863,#115020,.T.); +#115018 = VERTEX_POINT('',#115019); +#115019 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.E+000)); +#115020 = SURFACE_CURVE('',#115021,(#115026,#115032),.PCURVE_S1.); +#115021 = CIRCLE('',#115022,0.308574064194); +#115022 = AXIS2_PLACEMENT_3D('',#115023,#115024,#115025); +#115023 = CARTESIAN_POINT('',(-0.728168876214,3.15,2.640924866458E-017) + ); +#115024 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115025 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115026 = PCURVE('',#114878,#115027); +#115027 = DEFINITIONAL_REPRESENTATION('',(#115028),#115031); +#115028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115029,#115030), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#112637 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#112638 = CARTESIAN_POINT('',(4.761821717947,-6.85)); -#112639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115029 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#115030 = CARTESIAN_POINT('',(4.761821717947,-6.85)); +#115031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112640 = PCURVE('',#91495,#112641); -#112641 = DEFINITIONAL_REPRESENTATION('',(#112642),#112650); -#112642 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112643,#112644,#112645, - #112646,#112647,#112648,#112649),.UNSPECIFIED.,.T.,.F.) +#115032 = PCURVE('',#93887,#115033); +#115033 = DEFINITIONAL_REPRESENTATION('',(#115034),#115042); +#115034 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115035,#115036,#115037, + #115038,#115039,#115040,#115041),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#112643 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#112644 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#112645 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#112646 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#112647 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#112648 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#112649 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#112650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112651 = ORIENTED_EDGE('',*,*,#112470,.T.); -#112652 = ORIENTED_EDGE('',*,*,#112653,.F.); -#112653 = EDGE_CURVE('',#112654,#112448,#112656,.T.); -#112654 = VERTEX_POINT('',#112655); -#112655 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.E+000)); -#112656 = SURFACE_CURVE('',#112657,(#112662,#112668),.PCURVE_S1.); -#112657 = CIRCLE('',#112658,0.308574064194); -#112658 = AXIS2_PLACEMENT_3D('',#112659,#112660,#112661); -#112659 = CARTESIAN_POINT('',(-0.728168876214,3.35,2.640924866458E-017) - ); -#112660 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112661 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112662 = PCURVE('',#112486,#112663); -#112663 = DEFINITIONAL_REPRESENTATION('',(#112664),#112667); -#112664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112665,#112666), +#115035 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#115036 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#115037 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#115038 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#115039 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#115040 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#115041 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#115042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115043 = ORIENTED_EDGE('',*,*,#114862,.T.); +#115044 = ORIENTED_EDGE('',*,*,#115045,.F.); +#115045 = EDGE_CURVE('',#115046,#114840,#115048,.T.); +#115046 = VERTEX_POINT('',#115047); +#115047 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.E+000)); +#115048 = SURFACE_CURVE('',#115049,(#115054,#115060),.PCURVE_S1.); +#115049 = CIRCLE('',#115050,0.308574064194); +#115050 = AXIS2_PLACEMENT_3D('',#115051,#115052,#115053); +#115051 = CARTESIAN_POINT('',(-0.728168876214,3.35,2.640924866458E-017) + ); +#115052 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115053 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115054 = PCURVE('',#114878,#115055); +#115055 = DEFINITIONAL_REPRESENTATION('',(#115056),#115059); +#115056 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115057,#115058), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#112665 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#112666 = CARTESIAN_POINT('',(4.761821717947,-6.65)); -#112667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112668 = PCURVE('',#91551,#112669); -#112669 = DEFINITIONAL_REPRESENTATION('',(#112670),#112674); -#112670 = CIRCLE('',#112671,0.308574064194); -#112671 = AXIS2_PLACEMENT_2D('',#112672,#112673); -#112672 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#112673 = DIRECTION('',(0.E+000,-1.)); -#112674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112675 = ORIENTED_EDGE('',*,*,#112676,.T.); -#112676 = EDGE_CURVE('',#112654,#112626,#112677,.T.); -#112677 = SURFACE_CURVE('',#112678,(#112682,#112688),.PCURVE_S1.); -#112678 = LINE('',#112679,#112680); -#112679 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#112680 = VECTOR('',#112681,1.); -#112681 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112682 = PCURVE('',#112486,#112683); -#112683 = DEFINITIONAL_REPRESENTATION('',(#112684),#112687); -#112684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112685,#112686), +#115057 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#115058 = CARTESIAN_POINT('',(4.761821717947,-6.65)); +#115059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115060 = PCURVE('',#93943,#115061); +#115061 = DEFINITIONAL_REPRESENTATION('',(#115062),#115066); +#115062 = CIRCLE('',#115063,0.308574064194); +#115063 = AXIS2_PLACEMENT_2D('',#115064,#115065); +#115064 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#115065 = DIRECTION('',(0.E+000,-1.)); +#115066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115067 = ORIENTED_EDGE('',*,*,#115068,.T.); +#115068 = EDGE_CURVE('',#115046,#115018,#115069,.T.); +#115069 = SURFACE_CURVE('',#115070,(#115074,#115080),.PCURVE_S1.); +#115070 = LINE('',#115071,#115072); +#115071 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#115072 = VECTOR('',#115073,1.); +#115073 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115074 = PCURVE('',#114878,#115075); +#115075 = DEFINITIONAL_REPRESENTATION('',(#115076),#115079); +#115076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115077,#115078), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#112685 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#112686 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#112687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112688 = PCURVE('',#112689,#112694); -#112689 = PLANE('',#112690); -#112690 = AXIS2_PLACEMENT_3D('',#112691,#112692,#112693); -#112691 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#112692 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#112693 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112694 = DEFINITIONAL_REPRESENTATION('',(#112695),#112699); -#112695 = LINE('',#112696,#112697); -#112696 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#112697 = VECTOR('',#112698,1.); -#112698 = DIRECTION('',(-1.,0.E+000)); -#112699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112700 = ADVANCED_FACE('',(#112701),#112590,.F.); -#112701 = FACE_BOUND('',#112702,.F.); -#112702 = EDGE_LOOP('',(#112703,#112726,#112753,#112778)); -#112703 = ORIENTED_EDGE('',*,*,#112704,.F.); -#112704 = EDGE_CURVE('',#112705,#112575,#112707,.T.); -#112705 = VERTEX_POINT('',#112706); -#112706 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.E+000)); -#112707 = SURFACE_CURVE('',#112708,(#112713,#112719),.PCURVE_S1.); -#112708 = CIRCLE('',#112709,0.208574704164); -#112709 = AXIS2_PLACEMENT_3D('',#112710,#112711,#112712); -#112710 = CARTESIAN_POINT('',(-0.728168876214,3.35,2.640924866458E-017) - ); -#112711 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112712 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112713 = PCURVE('',#112590,#112714); -#112714 = DEFINITIONAL_REPRESENTATION('',(#112715),#112718); -#112715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112716,#112717), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), - .PIECEWISE_BEZIER_KNOTS.); -#112716 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#112717 = CARTESIAN_POINT('',(4.772630242227,-6.65)); -#112718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115077 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#115078 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#115079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112719 = PCURVE('',#91551,#112720); -#112720 = DEFINITIONAL_REPRESENTATION('',(#112721),#112725); -#112721 = CIRCLE('',#112722,0.208574704164); -#112722 = AXIS2_PLACEMENT_2D('',#112723,#112724); -#112723 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#112724 = DIRECTION('',(0.E+000,-1.)); -#112725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115080 = PCURVE('',#115081,#115086); +#115081 = PLANE('',#115082); +#115082 = AXIS2_PLACEMENT_3D('',#115083,#115084,#115085); +#115083 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#115084 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#115085 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115086 = DEFINITIONAL_REPRESENTATION('',(#115087),#115091); +#115087 = LINE('',#115088,#115089); +#115088 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#115089 = VECTOR('',#115090,1.); +#115090 = DIRECTION('',(-1.,0.E+000)); +#115091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112726 = ORIENTED_EDGE('',*,*,#112727,.F.); -#112727 = EDGE_CURVE('',#112728,#112705,#112730,.T.); -#112728 = VERTEX_POINT('',#112729); -#112729 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.E+000)); -#112730 = SURFACE_CURVE('',#112731,(#112735,#112741),.PCURVE_S1.); -#112731 = LINE('',#112732,#112733); -#112732 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#112733 = VECTOR('',#112734,1.); -#112734 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112735 = PCURVE('',#112590,#112736); -#112736 = DEFINITIONAL_REPRESENTATION('',(#112737),#112740); -#112737 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112738,#112739), +#115092 = ADVANCED_FACE('',(#115093),#114982,.F.); +#115093 = FACE_BOUND('',#115094,.F.); +#115094 = EDGE_LOOP('',(#115095,#115118,#115145,#115170)); +#115095 = ORIENTED_EDGE('',*,*,#115096,.F.); +#115096 = EDGE_CURVE('',#115097,#114967,#115099,.T.); +#115097 = VERTEX_POINT('',#115098); +#115098 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.E+000)); +#115099 = SURFACE_CURVE('',#115100,(#115105,#115111),.PCURVE_S1.); +#115100 = CIRCLE('',#115101,0.208574704164); +#115101 = AXIS2_PLACEMENT_3D('',#115102,#115103,#115104); +#115102 = CARTESIAN_POINT('',(-0.728168876214,3.35,2.640924866458E-017) + ); +#115103 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115104 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115105 = PCURVE('',#114982,#115106); +#115106 = DEFINITIONAL_REPRESENTATION('',(#115107),#115110); +#115107 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115108,#115109), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), + .PIECEWISE_BEZIER_KNOTS.); +#115108 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#115109 = CARTESIAN_POINT('',(4.772630242227,-6.65)); +#115110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115111 = PCURVE('',#93943,#115112); +#115112 = DEFINITIONAL_REPRESENTATION('',(#115113),#115117); +#115113 = CIRCLE('',#115114,0.208574704164); +#115114 = AXIS2_PLACEMENT_2D('',#115115,#115116); +#115115 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#115116 = DIRECTION('',(0.E+000,-1.)); +#115117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115118 = ORIENTED_EDGE('',*,*,#115119,.F.); +#115119 = EDGE_CURVE('',#115120,#115097,#115122,.T.); +#115120 = VERTEX_POINT('',#115121); +#115121 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.E+000)); +#115122 = SURFACE_CURVE('',#115123,(#115127,#115133),.PCURVE_S1.); +#115123 = LINE('',#115124,#115125); +#115124 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#115125 = VECTOR('',#115126,1.); +#115126 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115127 = PCURVE('',#114982,#115128); +#115128 = DEFINITIONAL_REPRESENTATION('',(#115129),#115132); +#115129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115130,#115131), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#112738 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#112739 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#112740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112741 = PCURVE('',#112742,#112747); -#112742 = PLANE('',#112743); -#112743 = AXIS2_PLACEMENT_3D('',#112744,#112745,#112746); -#112744 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#112745 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#112746 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112747 = DEFINITIONAL_REPRESENTATION('',(#112748),#112752); -#112748 = LINE('',#112749,#112750); -#112749 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#112750 = VECTOR('',#112751,1.); -#112751 = DIRECTION('',(-1.,0.E+000)); -#112752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112753 = ORIENTED_EDGE('',*,*,#112754,.T.); -#112754 = EDGE_CURVE('',#112728,#112552,#112755,.T.); -#112755 = SURFACE_CURVE('',#112756,(#112761,#112767),.PCURVE_S1.); -#112756 = CIRCLE('',#112757,0.208574704164); -#112757 = AXIS2_PLACEMENT_3D('',#112758,#112759,#112760); -#112758 = CARTESIAN_POINT('',(-0.728168876214,3.15,2.640924866458E-017) - ); -#112759 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112760 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#112761 = PCURVE('',#112590,#112762); -#112762 = DEFINITIONAL_REPRESENTATION('',(#112763),#112766); -#112763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112764,#112765), +#115130 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#115131 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#115132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115133 = PCURVE('',#115134,#115139); +#115134 = PLANE('',#115135); +#115135 = AXIS2_PLACEMENT_3D('',#115136,#115137,#115138); +#115136 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#115137 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#115138 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115139 = DEFINITIONAL_REPRESENTATION('',(#115140),#115144); +#115140 = LINE('',#115141,#115142); +#115141 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#115142 = VECTOR('',#115143,1.); +#115143 = DIRECTION('',(-1.,0.E+000)); +#115144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115145 = ORIENTED_EDGE('',*,*,#115146,.T.); +#115146 = EDGE_CURVE('',#115120,#114944,#115147,.T.); +#115147 = SURFACE_CURVE('',#115148,(#115153,#115159),.PCURVE_S1.); +#115148 = CIRCLE('',#115149,0.208574704164); +#115149 = AXIS2_PLACEMENT_3D('',#115150,#115151,#115152); +#115150 = CARTESIAN_POINT('',(-0.728168876214,3.15,2.640924866458E-017) + ); +#115151 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115152 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115153 = PCURVE('',#114982,#115154); +#115154 = DEFINITIONAL_REPRESENTATION('',(#115155),#115158); +#115155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115156,#115157), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#112764 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#112765 = CARTESIAN_POINT('',(4.772630242227,-6.85)); -#112766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115156 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#115157 = CARTESIAN_POINT('',(4.772630242227,-6.85)); +#115158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#112767 = PCURVE('',#91495,#112768); -#112768 = DEFINITIONAL_REPRESENTATION('',(#112769),#112777); -#112769 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#112770,#112771,#112772, - #112773,#112774,#112775,#112776),.UNSPECIFIED.,.T.,.F.) +#115159 = PCURVE('',#93887,#115160); +#115160 = DEFINITIONAL_REPRESENTATION('',(#115161),#115169); +#115161 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115162,#115163,#115164, + #115165,#115166,#115167,#115168),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#112770 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#112771 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#112772 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#112773 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#112774 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#112775 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#112776 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#112777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112778 = ORIENTED_EDGE('',*,*,#112574,.F.); -#112779 = ADVANCED_FACE('',(#112780),#112742,.T.); -#112780 = FACE_BOUND('',#112781,.T.); -#112781 = EDGE_LOOP('',(#112782,#112811,#112832,#112833)); -#112782 = ORIENTED_EDGE('',*,*,#112783,.T.); -#112783 = EDGE_CURVE('',#112784,#112786,#112788,.T.); -#112784 = VERTEX_POINT('',#112785); -#112785 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.530776333563)); -#112786 = VERTEX_POINT('',#112787); -#112787 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.530776333563)); -#112788 = SURFACE_CURVE('',#112789,(#112793,#112800),.PCURVE_S1.); -#112789 = LINE('',#112790,#112791); -#112790 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#112791 = VECTOR('',#112792,1.); -#112792 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112793 = PCURVE('',#112742,#112794); -#112794 = DEFINITIONAL_REPRESENTATION('',(#112795),#112799); -#112795 = LINE('',#112796,#112797); -#112796 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112797 = VECTOR('',#112798,1.); -#112798 = DIRECTION('',(-1.,0.E+000)); -#112799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112800 = PCURVE('',#112801,#112806); -#112801 = CYLINDRICAL_SURFACE('',#112802,0.2192697516); -#112802 = AXIS2_PLACEMENT_3D('',#112803,#112804,#112805); -#112803 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#112804 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112805 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112806 = DEFINITIONAL_REPRESENTATION('',(#112807),#112810); -#112807 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112808,#112809), +#115162 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#115163 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#115164 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#115165 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#115166 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#115167 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#115168 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#115169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115170 = ORIENTED_EDGE('',*,*,#114966,.F.); +#115171 = ADVANCED_FACE('',(#115172),#115134,.T.); +#115172 = FACE_BOUND('',#115173,.T.); +#115173 = EDGE_LOOP('',(#115174,#115203,#115224,#115225)); +#115174 = ORIENTED_EDGE('',*,*,#115175,.T.); +#115175 = EDGE_CURVE('',#115176,#115178,#115180,.T.); +#115176 = VERTEX_POINT('',#115177); +#115177 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.530776333563)); +#115178 = VERTEX_POINT('',#115179); +#115179 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.530776333563)); +#115180 = SURFACE_CURVE('',#115181,(#115185,#115192),.PCURVE_S1.); +#115181 = LINE('',#115182,#115183); +#115182 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#115183 = VECTOR('',#115184,1.); +#115184 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115185 = PCURVE('',#115134,#115186); +#115186 = DEFINITIONAL_REPRESENTATION('',(#115187),#115191); +#115187 = LINE('',#115188,#115189); +#115188 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115189 = VECTOR('',#115190,1.); +#115190 = DIRECTION('',(-1.,0.E+000)); +#115191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115192 = PCURVE('',#115193,#115198); +#115193 = CYLINDRICAL_SURFACE('',#115194,0.2192697516); +#115194 = AXIS2_PLACEMENT_3D('',#115195,#115196,#115197); +#115195 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#115196 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115197 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115198 = DEFINITIONAL_REPRESENTATION('',(#115199),#115202); +#115199 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115200,#115201), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#112808 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#112809 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#112810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112811 = ORIENTED_EDGE('',*,*,#112812,.T.); -#112812 = EDGE_CURVE('',#112786,#112705,#112813,.T.); -#112813 = SURFACE_CURVE('',#112814,(#112818,#112825),.PCURVE_S1.); -#112814 = LINE('',#112815,#112816); -#112815 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.530776333563)); -#112816 = VECTOR('',#112817,1.); -#112817 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#112818 = PCURVE('',#112742,#112819); -#112819 = DEFINITIONAL_REPRESENTATION('',(#112820),#112824); -#112820 = LINE('',#112821,#112822); -#112821 = CARTESIAN_POINT('',(6.65,4.535643882845E-033)); -#112822 = VECTOR('',#112823,1.); -#112823 = DIRECTION('',(-4.535643882845E-032,-1.)); -#112824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112825 = PCURVE('',#91551,#112826); -#112826 = DEFINITIONAL_REPRESENTATION('',(#112827),#112831); -#112827 = LINE('',#112828,#112829); -#112828 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#112829 = VECTOR('',#112830,1.); -#112830 = DIRECTION('',(-1.,-1.021336205033E-016)); -#112831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112832 = ORIENTED_EDGE('',*,*,#112727,.F.); -#112833 = ORIENTED_EDGE('',*,*,#112834,.F.); -#112834 = EDGE_CURVE('',#112784,#112728,#112835,.T.); -#112835 = SURFACE_CURVE('',#112836,(#112840,#112847),.PCURVE_S1.); -#112836 = LINE('',#112837,#112838); -#112837 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.530776333563)); -#112838 = VECTOR('',#112839,1.); -#112839 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#112840 = PCURVE('',#112742,#112841); -#112841 = DEFINITIONAL_REPRESENTATION('',(#112842),#112846); -#112842 = LINE('',#112843,#112844); -#112843 = CARTESIAN_POINT('',(6.85,-4.535643882845E-033)); -#112844 = VECTOR('',#112845,1.); -#112845 = DIRECTION('',(-4.535643882845E-032,-1.)); -#112846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112847 = PCURVE('',#91495,#112848); -#112848 = DEFINITIONAL_REPRESENTATION('',(#112849),#112853); -#112849 = LINE('',#112850,#112851); -#112850 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#112851 = VECTOR('',#112852,1.); -#112852 = DIRECTION('',(1.,-1.021336205033E-016)); -#112853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112854 = ADVANCED_FACE('',(#112855),#112689,.T.); -#112855 = FACE_BOUND('',#112856,.T.); -#112856 = EDGE_LOOP('',(#112857,#112886,#112907,#112908)); -#112857 = ORIENTED_EDGE('',*,*,#112858,.T.); -#112858 = EDGE_CURVE('',#112859,#112861,#112863,.T.); -#112859 = VERTEX_POINT('',#112860); -#112860 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.530776333563)); -#112861 = VERTEX_POINT('',#112862); -#112862 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.530776333563)); -#112863 = SURFACE_CURVE('',#112864,(#112868,#112875),.PCURVE_S1.); -#112864 = LINE('',#112865,#112866); -#112865 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#112866 = VECTOR('',#112867,1.); -#112867 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112868 = PCURVE('',#112689,#112869); -#112869 = DEFINITIONAL_REPRESENTATION('',(#112870),#112874); -#112870 = LINE('',#112871,#112872); -#112871 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#112872 = VECTOR('',#112873,1.); -#112873 = DIRECTION('',(-1.,0.E+000)); -#112874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112875 = PCURVE('',#112876,#112881); -#112876 = CYLINDRICAL_SURFACE('',#112877,0.119270391569); -#112877 = AXIS2_PLACEMENT_3D('',#112878,#112879,#112880); -#112878 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#112879 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112880 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112881 = DEFINITIONAL_REPRESENTATION('',(#112882),#112885); -#112882 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112883,#112884), +#115200 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#115201 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#115202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115203 = ORIENTED_EDGE('',*,*,#115204,.T.); +#115204 = EDGE_CURVE('',#115178,#115097,#115205,.T.); +#115205 = SURFACE_CURVE('',#115206,(#115210,#115217),.PCURVE_S1.); +#115206 = LINE('',#115207,#115208); +#115207 = CARTESIAN_POINT('',(-0.51959417205,3.35,0.530776333563)); +#115208 = VECTOR('',#115209,1.); +#115209 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#115210 = PCURVE('',#115134,#115211); +#115211 = DEFINITIONAL_REPRESENTATION('',(#115212),#115216); +#115212 = LINE('',#115213,#115214); +#115213 = CARTESIAN_POINT('',(6.65,4.535643882845E-033)); +#115214 = VECTOR('',#115215,1.); +#115215 = DIRECTION('',(-4.535643882845E-032,-1.)); +#115216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115217 = PCURVE('',#93943,#115218); +#115218 = DEFINITIONAL_REPRESENTATION('',(#115219),#115223); +#115219 = LINE('',#115220,#115221); +#115220 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#115221 = VECTOR('',#115222,1.); +#115222 = DIRECTION('',(-1.,-1.021336205033E-016)); +#115223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115224 = ORIENTED_EDGE('',*,*,#115119,.F.); +#115225 = ORIENTED_EDGE('',*,*,#115226,.F.); +#115226 = EDGE_CURVE('',#115176,#115120,#115227,.T.); +#115227 = SURFACE_CURVE('',#115228,(#115232,#115239),.PCURVE_S1.); +#115228 = LINE('',#115229,#115230); +#115229 = CARTESIAN_POINT('',(-0.51959417205,3.15,0.530776333563)); +#115230 = VECTOR('',#115231,1.); +#115231 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#115232 = PCURVE('',#115134,#115233); +#115233 = DEFINITIONAL_REPRESENTATION('',(#115234),#115238); +#115234 = LINE('',#115235,#115236); +#115235 = CARTESIAN_POINT('',(6.85,-4.535643882845E-033)); +#115236 = VECTOR('',#115237,1.); +#115237 = DIRECTION('',(-4.535643882845E-032,-1.)); +#115238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115239 = PCURVE('',#93887,#115240); +#115240 = DEFINITIONAL_REPRESENTATION('',(#115241),#115245); +#115241 = LINE('',#115242,#115243); +#115242 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#115243 = VECTOR('',#115244,1.); +#115244 = DIRECTION('',(1.,-1.021336205033E-016)); +#115245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115246 = ADVANCED_FACE('',(#115247),#115081,.T.); +#115247 = FACE_BOUND('',#115248,.T.); +#115248 = EDGE_LOOP('',(#115249,#115278,#115299,#115300)); +#115249 = ORIENTED_EDGE('',*,*,#115250,.T.); +#115250 = EDGE_CURVE('',#115251,#115253,#115255,.T.); +#115251 = VERTEX_POINT('',#115252); +#115252 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.530776333563)); +#115253 = VERTEX_POINT('',#115254); +#115254 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.530776333563)); +#115255 = SURFACE_CURVE('',#115256,(#115260,#115267),.PCURVE_S1.); +#115256 = LINE('',#115257,#115258); +#115257 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#115258 = VECTOR('',#115259,1.); +#115259 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115260 = PCURVE('',#115081,#115261); +#115261 = DEFINITIONAL_REPRESENTATION('',(#115262),#115266); +#115262 = LINE('',#115263,#115264); +#115263 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115264 = VECTOR('',#115265,1.); +#115265 = DIRECTION('',(-1.,0.E+000)); +#115266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115267 = PCURVE('',#115268,#115273); +#115268 = CYLINDRICAL_SURFACE('',#115269,0.119270391569); +#115269 = AXIS2_PLACEMENT_3D('',#115270,#115271,#115272); +#115270 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#115271 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115272 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115273 = DEFINITIONAL_REPRESENTATION('',(#115274),#115277); +#115274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115275,#115276), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#112883 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#112884 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#112885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112886 = ORIENTED_EDGE('',*,*,#112887,.T.); -#112887 = EDGE_CURVE('',#112861,#112626,#112888,.T.); -#112888 = SURFACE_CURVE('',#112889,(#112893,#112900),.PCURVE_S1.); -#112889 = LINE('',#112890,#112891); -#112890 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.530776333563)); -#112891 = VECTOR('',#112892,1.); -#112892 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#112893 = PCURVE('',#112689,#112894); -#112894 = DEFINITIONAL_REPRESENTATION('',(#112895),#112899); -#112895 = LINE('',#112896,#112897); -#112896 = CARTESIAN_POINT('',(-6.85,1.133910970711E-033)); -#112897 = VECTOR('',#112898,1.); -#112898 = DIRECTION('',(4.535643882845E-032,-1.)); -#112899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112900 = PCURVE('',#91495,#112901); -#112901 = DEFINITIONAL_REPRESENTATION('',(#112902),#112906); -#112902 = LINE('',#112903,#112904); -#112903 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#112904 = VECTOR('',#112905,1.); -#112905 = DIRECTION('',(1.,-1.021336205033E-016)); -#112906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112907 = ORIENTED_EDGE('',*,*,#112676,.F.); -#112908 = ORIENTED_EDGE('',*,*,#112909,.F.); -#112909 = EDGE_CURVE('',#112859,#112654,#112910,.T.); -#112910 = SURFACE_CURVE('',#112911,(#112915,#112922),.PCURVE_S1.); -#112911 = LINE('',#112912,#112913); -#112912 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.530776333563)); -#112913 = VECTOR('',#112914,1.); -#112914 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#112915 = PCURVE('',#112689,#112916); -#112916 = DEFINITIONAL_REPRESENTATION('',(#112917),#112921); -#112917 = LINE('',#112918,#112919); -#112918 = CARTESIAN_POINT('',(-6.65,-1.133910970711E-033)); -#112919 = VECTOR('',#112920,1.); -#112920 = DIRECTION('',(4.535643882845E-032,-1.)); -#112921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112922 = PCURVE('',#91551,#112923); -#112923 = DEFINITIONAL_REPRESENTATION('',(#112924),#112928); -#112924 = LINE('',#112925,#112926); -#112925 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#112926 = VECTOR('',#112927,1.); -#112927 = DIRECTION('',(-1.,-1.021336205033E-016)); -#112928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112929 = ADVANCED_FACE('',(#112930),#112876,.F.); -#112930 = FACE_BOUND('',#112931,.F.); -#112931 = EDGE_LOOP('',(#112932,#112933,#112956,#113001)); -#112932 = ORIENTED_EDGE('',*,*,#112858,.T.); -#112933 = ORIENTED_EDGE('',*,*,#112934,.F.); -#112934 = EDGE_CURVE('',#112935,#112861,#112937,.T.); -#112935 = VERTEX_POINT('',#112936); -#112936 = CARTESIAN_POINT('',(-0.303662633502,3.15,0.65)); -#112937 = SURFACE_CURVE('',#112938,(#112943,#112949),.PCURVE_S1.); -#112938 = CIRCLE('',#112939,0.119270391569); -#112939 = AXIS2_PLACEMENT_3D('',#112940,#112941,#112942); -#112940 = CARTESIAN_POINT('',(-0.30032442045,3.15,0.530776333563)); -#112941 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#112942 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#112943 = PCURVE('',#112876,#112944); -#112944 = DEFINITIONAL_REPRESENTATION('',(#112945),#112948); -#112945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#112946,#112947), +#115275 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#115276 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#115277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115278 = ORIENTED_EDGE('',*,*,#115279,.T.); +#115279 = EDGE_CURVE('',#115253,#115018,#115280,.T.); +#115280 = SURFACE_CURVE('',#115281,(#115285,#115292),.PCURVE_S1.); +#115281 = LINE('',#115282,#115283); +#115282 = CARTESIAN_POINT('',(-0.419594812019,3.15,0.530776333563)); +#115283 = VECTOR('',#115284,1.); +#115284 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#115285 = PCURVE('',#115081,#115286); +#115286 = DEFINITIONAL_REPRESENTATION('',(#115287),#115291); +#115287 = LINE('',#115288,#115289); +#115288 = CARTESIAN_POINT('',(-6.85,1.133910970711E-033)); +#115289 = VECTOR('',#115290,1.); +#115290 = DIRECTION('',(4.535643882845E-032,-1.)); +#115291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115292 = PCURVE('',#93887,#115293); +#115293 = DEFINITIONAL_REPRESENTATION('',(#115294),#115298); +#115294 = LINE('',#115295,#115296); +#115295 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#115296 = VECTOR('',#115297,1.); +#115297 = DIRECTION('',(1.,-1.021336205033E-016)); +#115298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115299 = ORIENTED_EDGE('',*,*,#115068,.F.); +#115300 = ORIENTED_EDGE('',*,*,#115301,.F.); +#115301 = EDGE_CURVE('',#115251,#115046,#115302,.T.); +#115302 = SURFACE_CURVE('',#115303,(#115307,#115314),.PCURVE_S1.); +#115303 = LINE('',#115304,#115305); +#115304 = CARTESIAN_POINT('',(-0.419594812019,3.35,0.530776333563)); +#115305 = VECTOR('',#115306,1.); +#115306 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#115307 = PCURVE('',#115081,#115308); +#115308 = DEFINITIONAL_REPRESENTATION('',(#115309),#115313); +#115309 = LINE('',#115310,#115311); +#115310 = CARTESIAN_POINT('',(-6.65,-1.133910970711E-033)); +#115311 = VECTOR('',#115312,1.); +#115312 = DIRECTION('',(4.535643882845E-032,-1.)); +#115313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115314 = PCURVE('',#93943,#115315); +#115315 = DEFINITIONAL_REPRESENTATION('',(#115316),#115320); +#115316 = LINE('',#115317,#115318); +#115317 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#115318 = VECTOR('',#115319,1.); +#115319 = DIRECTION('',(-1.,-1.021336205033E-016)); +#115320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115321 = ADVANCED_FACE('',(#115322),#115268,.F.); +#115322 = FACE_BOUND('',#115323,.F.); +#115323 = EDGE_LOOP('',(#115324,#115325,#115348,#115393)); +#115324 = ORIENTED_EDGE('',*,*,#115250,.T.); +#115325 = ORIENTED_EDGE('',*,*,#115326,.F.); +#115326 = EDGE_CURVE('',#115327,#115253,#115329,.T.); +#115327 = VERTEX_POINT('',#115328); +#115328 = CARTESIAN_POINT('',(-0.303662633502,3.15,0.65)); +#115329 = SURFACE_CURVE('',#115330,(#115335,#115341),.PCURVE_S1.); +#115330 = CIRCLE('',#115331,0.119270391569); +#115331 = AXIS2_PLACEMENT_3D('',#115332,#115333,#115334); +#115332 = CARTESIAN_POINT('',(-0.30032442045,3.15,0.530776333563)); +#115333 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115334 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115335 = PCURVE('',#115268,#115336); +#115336 = DEFINITIONAL_REPRESENTATION('',(#115337),#115340); +#115337 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115338,#115339), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#112946 = CARTESIAN_POINT('',(1.598788597134,6.85)); -#112947 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#112948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112949 = PCURVE('',#91495,#112950); -#112950 = DEFINITIONAL_REPRESENTATION('',(#112951),#112955); -#112951 = CIRCLE('',#112952,0.119270391569); -#112952 = AXIS2_PLACEMENT_2D('',#112953,#112954); -#112953 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#112954 = DIRECTION('',(0.E+000,1.)); -#112955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112956 = ORIENTED_EDGE('',*,*,#112957,.T.); -#112957 = EDGE_CURVE('',#112935,#112958,#112960,.T.); -#112958 = VERTEX_POINT('',#112959); -#112959 = CARTESIAN_POINT('',(-0.303662633502,3.35,0.65)); -#112960 = SURFACE_CURVE('',#112961,(#112965,#112994),.PCURVE_S1.); -#112961 = LINE('',#112962,#112963); -#112962 = CARTESIAN_POINT('',(-0.303662633502,3.35,0.65)); -#112963 = VECTOR('',#112964,1.); -#112964 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#112965 = PCURVE('',#112876,#112966); -#112966 = DEFINITIONAL_REPRESENTATION('',(#112967),#112993); -#112967 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#112968,#112969,#112970, - #112971,#112972,#112973,#112974,#112975,#112976,#112977,#112978, - #112979,#112980,#112981,#112982,#112983,#112984,#112985,#112986, - #112987,#112988,#112989,#112990,#112991,#112992),.UNSPECIFIED.,.F., +#115338 = CARTESIAN_POINT('',(1.598788597134,6.85)); +#115339 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#115340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115341 = PCURVE('',#93887,#115342); +#115342 = DEFINITIONAL_REPRESENTATION('',(#115343),#115347); +#115343 = CIRCLE('',#115344,0.119270391569); +#115344 = AXIS2_PLACEMENT_2D('',#115345,#115346); +#115345 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#115346 = DIRECTION('',(0.E+000,1.)); +#115347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115348 = ORIENTED_EDGE('',*,*,#115349,.T.); +#115349 = EDGE_CURVE('',#115327,#115350,#115352,.T.); +#115350 = VERTEX_POINT('',#115351); +#115351 = CARTESIAN_POINT('',(-0.303662633502,3.35,0.65)); +#115352 = SURFACE_CURVE('',#115353,(#115357,#115386),.PCURVE_S1.); +#115353 = LINE('',#115354,#115355); +#115354 = CARTESIAN_POINT('',(-0.303662633502,3.35,0.65)); +#115355 = VECTOR('',#115356,1.); +#115356 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115357 = PCURVE('',#115268,#115358); +#115358 = DEFINITIONAL_REPRESENTATION('',(#115359),#115385); +#115359 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#115360,#115361,#115362, + #115363,#115364,#115365,#115366,#115367,#115368,#115369,#115370, + #115371,#115372,#115373,#115374,#115375,#115376,#115377,#115378, + #115379,#115380,#115381,#115382,#115383,#115384),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -139157,128 +142159,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#112968 = CARTESIAN_POINT('',(1.598788597134,6.85)); -#112969 = CARTESIAN_POINT('',(1.598788597134,6.84696969697)); -#112970 = CARTESIAN_POINT('',(1.598788597134,6.840909090909)); -#112971 = CARTESIAN_POINT('',(1.598788597134,6.831818181818)); -#112972 = CARTESIAN_POINT('',(1.598788597134,6.822727272727)); -#112973 = CARTESIAN_POINT('',(1.598788597134,6.813636363636)); -#112974 = CARTESIAN_POINT('',(1.598788597134,6.804545454545)); -#112975 = CARTESIAN_POINT('',(1.598788597134,6.795454545455)); -#112976 = CARTESIAN_POINT('',(1.598788597134,6.786363636364)); -#112977 = CARTESIAN_POINT('',(1.598788597134,6.777272727273)); -#112978 = CARTESIAN_POINT('',(1.598788597134,6.768181818182)); -#112979 = CARTESIAN_POINT('',(1.598788597134,6.759090909091)); -#112980 = CARTESIAN_POINT('',(1.598788597134,6.75)); -#112981 = CARTESIAN_POINT('',(1.598788597134,6.740909090909)); -#112982 = CARTESIAN_POINT('',(1.598788597134,6.731818181818)); -#112983 = CARTESIAN_POINT('',(1.598788597134,6.722727272727)); -#112984 = CARTESIAN_POINT('',(1.598788597134,6.713636363636)); -#112985 = CARTESIAN_POINT('',(1.598788597134,6.704545454545)); -#112986 = CARTESIAN_POINT('',(1.598788597134,6.695454545455)); -#112987 = CARTESIAN_POINT('',(1.598788597134,6.686363636364)); -#112988 = CARTESIAN_POINT('',(1.598788597134,6.677272727273)); -#112989 = CARTESIAN_POINT('',(1.598788597134,6.668181818182)); -#112990 = CARTESIAN_POINT('',(1.598788597134,6.659090909091)); -#112991 = CARTESIAN_POINT('',(1.598788597134,6.65303030303)); -#112992 = CARTESIAN_POINT('',(1.598788597134,6.65)); -#112993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#112994 = PCURVE('',#91523,#112995); -#112995 = DEFINITIONAL_REPRESENTATION('',(#112996),#113000); -#112996 = LINE('',#112997,#112998); -#112997 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#112998 = VECTOR('',#112999,1.); -#112999 = DIRECTION('',(4.440892098501E-016,1.)); -#113000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113001 = ORIENTED_EDGE('',*,*,#113002,.T.); -#113002 = EDGE_CURVE('',#112958,#112859,#113003,.T.); -#113003 = SURFACE_CURVE('',#113004,(#113009,#113015),.PCURVE_S1.); -#113004 = CIRCLE('',#113005,0.119270391569); -#113005 = AXIS2_PLACEMENT_3D('',#113006,#113007,#113008); -#113006 = CARTESIAN_POINT('',(-0.30032442045,3.35,0.530776333563)); -#113007 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113008 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113009 = PCURVE('',#112876,#113010); -#113010 = DEFINITIONAL_REPRESENTATION('',(#113011),#113014); -#113011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113012,#113013), +#115360 = CARTESIAN_POINT('',(1.598788597134,6.85)); +#115361 = CARTESIAN_POINT('',(1.598788597134,6.84696969697)); +#115362 = CARTESIAN_POINT('',(1.598788597134,6.840909090909)); +#115363 = CARTESIAN_POINT('',(1.598788597134,6.831818181818)); +#115364 = CARTESIAN_POINT('',(1.598788597134,6.822727272727)); +#115365 = CARTESIAN_POINT('',(1.598788597134,6.813636363636)); +#115366 = CARTESIAN_POINT('',(1.598788597134,6.804545454545)); +#115367 = CARTESIAN_POINT('',(1.598788597134,6.795454545455)); +#115368 = CARTESIAN_POINT('',(1.598788597134,6.786363636364)); +#115369 = CARTESIAN_POINT('',(1.598788597134,6.777272727273)); +#115370 = CARTESIAN_POINT('',(1.598788597134,6.768181818182)); +#115371 = CARTESIAN_POINT('',(1.598788597134,6.759090909091)); +#115372 = CARTESIAN_POINT('',(1.598788597134,6.75)); +#115373 = CARTESIAN_POINT('',(1.598788597134,6.740909090909)); +#115374 = CARTESIAN_POINT('',(1.598788597134,6.731818181818)); +#115375 = CARTESIAN_POINT('',(1.598788597134,6.722727272727)); +#115376 = CARTESIAN_POINT('',(1.598788597134,6.713636363636)); +#115377 = CARTESIAN_POINT('',(1.598788597134,6.704545454545)); +#115378 = CARTESIAN_POINT('',(1.598788597134,6.695454545455)); +#115379 = CARTESIAN_POINT('',(1.598788597134,6.686363636364)); +#115380 = CARTESIAN_POINT('',(1.598788597134,6.677272727273)); +#115381 = CARTESIAN_POINT('',(1.598788597134,6.668181818182)); +#115382 = CARTESIAN_POINT('',(1.598788597134,6.659090909091)); +#115383 = CARTESIAN_POINT('',(1.598788597134,6.65303030303)); +#115384 = CARTESIAN_POINT('',(1.598788597134,6.65)); +#115385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115386 = PCURVE('',#93915,#115387); +#115387 = DEFINITIONAL_REPRESENTATION('',(#115388),#115392); +#115388 = LINE('',#115389,#115390); +#115389 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#115390 = VECTOR('',#115391,1.); +#115391 = DIRECTION('',(4.440892098501E-016,1.)); +#115392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115393 = ORIENTED_EDGE('',*,*,#115394,.T.); +#115394 = EDGE_CURVE('',#115350,#115251,#115395,.T.); +#115395 = SURFACE_CURVE('',#115396,(#115401,#115407),.PCURVE_S1.); +#115396 = CIRCLE('',#115397,0.119270391569); +#115397 = AXIS2_PLACEMENT_3D('',#115398,#115399,#115400); +#115398 = CARTESIAN_POINT('',(-0.30032442045,3.35,0.530776333563)); +#115399 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115400 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115401 = PCURVE('',#115268,#115402); +#115402 = DEFINITIONAL_REPRESENTATION('',(#115403),#115406); +#115403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115404,#115405), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#113012 = CARTESIAN_POINT('',(1.598788597134,6.65)); -#113013 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#113014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115404 = CARTESIAN_POINT('',(1.598788597134,6.65)); +#115405 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#115406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113015 = PCURVE('',#91551,#113016); -#113016 = DEFINITIONAL_REPRESENTATION('',(#113017),#113025); -#113017 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113018,#113019,#113020, - #113021,#113022,#113023,#113024),.UNSPECIFIED.,.T.,.F.) +#115407 = PCURVE('',#93943,#115408); +#115408 = DEFINITIONAL_REPRESENTATION('',(#115409),#115417); +#115409 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115410,#115411,#115412, + #115413,#115414,#115415,#115416),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#113018 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#113019 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#113020 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#113021 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#113022 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#113023 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#113024 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#113025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113026 = ADVANCED_FACE('',(#113027),#112801,.T.); -#113027 = FACE_BOUND('',#113028,.T.); -#113028 = EDGE_LOOP('',(#113029,#113030,#113053,#113098)); -#113029 = ORIENTED_EDGE('',*,*,#112783,.F.); -#113030 = ORIENTED_EDGE('',*,*,#113031,.F.); -#113031 = EDGE_CURVE('',#113032,#112784,#113034,.T.); -#113032 = VERTEX_POINT('',#113033); -#113033 = CARTESIAN_POINT('',(-0.304819755875,3.15,0.75)); -#113034 = SURFACE_CURVE('',#113035,(#113040,#113046),.PCURVE_S1.); -#113035 = CIRCLE('',#113036,0.2192697516); -#113036 = AXIS2_PLACEMENT_3D('',#113037,#113038,#113039); -#113037 = CARTESIAN_POINT('',(-0.30032442045,3.15,0.530776333563)); -#113038 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113039 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113040 = PCURVE('',#112801,#113041); -#113041 = DEFINITIONAL_REPRESENTATION('',(#113042),#113045); -#113042 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113043,#113044), +#115410 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#115411 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#115412 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#115413 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#115414 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#115415 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#115416 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#115417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115418 = ADVANCED_FACE('',(#115419),#115193,.T.); +#115419 = FACE_BOUND('',#115420,.T.); +#115420 = EDGE_LOOP('',(#115421,#115422,#115445,#115490)); +#115421 = ORIENTED_EDGE('',*,*,#115175,.F.); +#115422 = ORIENTED_EDGE('',*,*,#115423,.F.); +#115423 = EDGE_CURVE('',#115424,#115176,#115426,.T.); +#115424 = VERTEX_POINT('',#115425); +#115425 = CARTESIAN_POINT('',(-0.304819755875,3.15,0.75)); +#115426 = SURFACE_CURVE('',#115427,(#115432,#115438),.PCURVE_S1.); +#115427 = CIRCLE('',#115428,0.2192697516); +#115428 = AXIS2_PLACEMENT_3D('',#115429,#115430,#115431); +#115429 = CARTESIAN_POINT('',(-0.30032442045,3.15,0.530776333563)); +#115430 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115431 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115432 = PCURVE('',#115193,#115433); +#115433 = DEFINITIONAL_REPRESENTATION('',(#115434),#115437); +#115434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115435,#115436), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#113043 = CARTESIAN_POINT('',(1.591299156552,6.85)); -#113044 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#113045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113046 = PCURVE('',#91495,#113047); -#113047 = DEFINITIONAL_REPRESENTATION('',(#113048),#113052); -#113048 = CIRCLE('',#113049,0.2192697516); -#113049 = AXIS2_PLACEMENT_2D('',#113050,#113051); -#113050 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#113051 = DIRECTION('',(0.E+000,1.)); -#113052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113053 = ORIENTED_EDGE('',*,*,#113054,.F.); -#113054 = EDGE_CURVE('',#113055,#113032,#113057,.T.); -#113055 = VERTEX_POINT('',#113056); -#113056 = CARTESIAN_POINT('',(-0.304819755875,3.35,0.75)); -#113057 = SURFACE_CURVE('',#113058,(#113062,#113091),.PCURVE_S1.); -#113058 = LINE('',#113059,#113060); -#113059 = CARTESIAN_POINT('',(-0.304819755875,3.35,0.75)); -#113060 = VECTOR('',#113061,1.); -#113061 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113062 = PCURVE('',#112801,#113063); -#113063 = DEFINITIONAL_REPRESENTATION('',(#113064),#113090); -#113064 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113065,#113066,#113067, - #113068,#113069,#113070,#113071,#113072,#113073,#113074,#113075, - #113076,#113077,#113078,#113079,#113080,#113081,#113082,#113083, - #113084,#113085,#113086,#113087,#113088,#113089),.UNSPECIFIED.,.F., +#115435 = CARTESIAN_POINT('',(1.591299156552,6.85)); +#115436 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#115437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115438 = PCURVE('',#93887,#115439); +#115439 = DEFINITIONAL_REPRESENTATION('',(#115440),#115444); +#115440 = CIRCLE('',#115441,0.2192697516); +#115441 = AXIS2_PLACEMENT_2D('',#115442,#115443); +#115442 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#115443 = DIRECTION('',(0.E+000,1.)); +#115444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115445 = ORIENTED_EDGE('',*,*,#115446,.F.); +#115446 = EDGE_CURVE('',#115447,#115424,#115449,.T.); +#115447 = VERTEX_POINT('',#115448); +#115448 = CARTESIAN_POINT('',(-0.304819755875,3.35,0.75)); +#115449 = SURFACE_CURVE('',#115450,(#115454,#115483),.PCURVE_S1.); +#115450 = LINE('',#115451,#115452); +#115451 = CARTESIAN_POINT('',(-0.304819755875,3.35,0.75)); +#115452 = VECTOR('',#115453,1.); +#115453 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115454 = PCURVE('',#115193,#115455); +#115455 = DEFINITIONAL_REPRESENTATION('',(#115456),#115482); +#115456 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#115457,#115458,#115459, + #115460,#115461,#115462,#115463,#115464,#115465,#115466,#115467, + #115468,#115469,#115470,#115471,#115472,#115473,#115474,#115475, + #115476,#115477,#115478,#115479,#115480,#115481),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -139287,544 +142289,544 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#113065 = CARTESIAN_POINT('',(1.591299156552,6.65)); -#113066 = CARTESIAN_POINT('',(1.591299156552,6.65303030303)); -#113067 = CARTESIAN_POINT('',(1.591299156552,6.659090909091)); -#113068 = CARTESIAN_POINT('',(1.591299156552,6.668181818182)); -#113069 = CARTESIAN_POINT('',(1.591299156552,6.677272727273)); -#113070 = CARTESIAN_POINT('',(1.591299156552,6.686363636364)); -#113071 = CARTESIAN_POINT('',(1.591299156552,6.695454545455)); -#113072 = CARTESIAN_POINT('',(1.591299156552,6.704545454545)); -#113073 = CARTESIAN_POINT('',(1.591299156552,6.713636363636)); -#113074 = CARTESIAN_POINT('',(1.591299156552,6.722727272727)); -#113075 = CARTESIAN_POINT('',(1.591299156552,6.731818181818)); -#113076 = CARTESIAN_POINT('',(1.591299156552,6.740909090909)); -#113077 = CARTESIAN_POINT('',(1.591299156552,6.75)); -#113078 = CARTESIAN_POINT('',(1.591299156552,6.759090909091)); -#113079 = CARTESIAN_POINT('',(1.591299156552,6.768181818182)); -#113080 = CARTESIAN_POINT('',(1.591299156552,6.777272727273)); -#113081 = CARTESIAN_POINT('',(1.591299156552,6.786363636364)); -#113082 = CARTESIAN_POINT('',(1.591299156552,6.795454545455)); -#113083 = CARTESIAN_POINT('',(1.591299156552,6.804545454545)); -#113084 = CARTESIAN_POINT('',(1.591299156552,6.813636363636)); -#113085 = CARTESIAN_POINT('',(1.591299156552,6.822727272727)); -#113086 = CARTESIAN_POINT('',(1.591299156552,6.831818181818)); -#113087 = CARTESIAN_POINT('',(1.591299156552,6.840909090909)); -#113088 = CARTESIAN_POINT('',(1.591299156552,6.84696969697)); -#113089 = CARTESIAN_POINT('',(1.591299156552,6.85)); -#113090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113091 = PCURVE('',#91577,#113092); -#113092 = DEFINITIONAL_REPRESENTATION('',(#113093),#113097); -#113093 = LINE('',#113094,#113095); -#113094 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#113095 = VECTOR('',#113096,1.); -#113096 = DIRECTION('',(4.440892098501E-016,-1.)); -#113097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113098 = ORIENTED_EDGE('',*,*,#113099,.T.); -#113099 = EDGE_CURVE('',#113055,#112786,#113100,.T.); -#113100 = SURFACE_CURVE('',#113101,(#113106,#113112),.PCURVE_S1.); -#113101 = CIRCLE('',#113102,0.2192697516); -#113102 = AXIS2_PLACEMENT_3D('',#113103,#113104,#113105); -#113103 = CARTESIAN_POINT('',(-0.30032442045,3.35,0.530776333563)); -#113104 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113105 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113106 = PCURVE('',#112801,#113107); -#113107 = DEFINITIONAL_REPRESENTATION('',(#113108),#113111); -#113108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113109,#113110), +#115457 = CARTESIAN_POINT('',(1.591299156552,6.65)); +#115458 = CARTESIAN_POINT('',(1.591299156552,6.65303030303)); +#115459 = CARTESIAN_POINT('',(1.591299156552,6.659090909091)); +#115460 = CARTESIAN_POINT('',(1.591299156552,6.668181818182)); +#115461 = CARTESIAN_POINT('',(1.591299156552,6.677272727273)); +#115462 = CARTESIAN_POINT('',(1.591299156552,6.686363636364)); +#115463 = CARTESIAN_POINT('',(1.591299156552,6.695454545455)); +#115464 = CARTESIAN_POINT('',(1.591299156552,6.704545454545)); +#115465 = CARTESIAN_POINT('',(1.591299156552,6.713636363636)); +#115466 = CARTESIAN_POINT('',(1.591299156552,6.722727272727)); +#115467 = CARTESIAN_POINT('',(1.591299156552,6.731818181818)); +#115468 = CARTESIAN_POINT('',(1.591299156552,6.740909090909)); +#115469 = CARTESIAN_POINT('',(1.591299156552,6.75)); +#115470 = CARTESIAN_POINT('',(1.591299156552,6.759090909091)); +#115471 = CARTESIAN_POINT('',(1.591299156552,6.768181818182)); +#115472 = CARTESIAN_POINT('',(1.591299156552,6.777272727273)); +#115473 = CARTESIAN_POINT('',(1.591299156552,6.786363636364)); +#115474 = CARTESIAN_POINT('',(1.591299156552,6.795454545455)); +#115475 = CARTESIAN_POINT('',(1.591299156552,6.804545454545)); +#115476 = CARTESIAN_POINT('',(1.591299156552,6.813636363636)); +#115477 = CARTESIAN_POINT('',(1.591299156552,6.822727272727)); +#115478 = CARTESIAN_POINT('',(1.591299156552,6.831818181818)); +#115479 = CARTESIAN_POINT('',(1.591299156552,6.840909090909)); +#115480 = CARTESIAN_POINT('',(1.591299156552,6.84696969697)); +#115481 = CARTESIAN_POINT('',(1.591299156552,6.85)); +#115482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115483 = PCURVE('',#93969,#115484); +#115484 = DEFINITIONAL_REPRESENTATION('',(#115485),#115489); +#115485 = LINE('',#115486,#115487); +#115486 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#115487 = VECTOR('',#115488,1.); +#115488 = DIRECTION('',(4.440892098501E-016,-1.)); +#115489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115490 = ORIENTED_EDGE('',*,*,#115491,.T.); +#115491 = EDGE_CURVE('',#115447,#115178,#115492,.T.); +#115492 = SURFACE_CURVE('',#115493,(#115498,#115504),.PCURVE_S1.); +#115493 = CIRCLE('',#115494,0.2192697516); +#115494 = AXIS2_PLACEMENT_3D('',#115495,#115496,#115497); +#115495 = CARTESIAN_POINT('',(-0.30032442045,3.35,0.530776333563)); +#115496 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115497 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#115498 = PCURVE('',#115193,#115499); +#115499 = DEFINITIONAL_REPRESENTATION('',(#115500),#115503); +#115500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115501,#115502), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#113109 = CARTESIAN_POINT('',(1.591299156552,6.65)); -#113110 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#113111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115501 = CARTESIAN_POINT('',(1.591299156552,6.65)); +#115502 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#115503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113112 = PCURVE('',#91551,#113113); -#113113 = DEFINITIONAL_REPRESENTATION('',(#113114),#113122); -#113114 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113115,#113116,#113117, - #113118,#113119,#113120,#113121),.UNSPECIFIED.,.T.,.F.) +#115504 = PCURVE('',#93943,#115505); +#115505 = DEFINITIONAL_REPRESENTATION('',(#115506),#115514); +#115506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115507,#115508,#115509, + #115510,#115511,#115512,#115513),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#113115 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#113116 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#113117 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#113118 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#113119 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#113120 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#113121 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#113122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113123 = ADVANCED_FACE('',(#113124),#91523,.T.); -#113124 = FACE_BOUND('',#113125,.T.); -#113125 = EDGE_LOOP('',(#113126,#113147,#113148,#113169)); -#113126 = ORIENTED_EDGE('',*,*,#113127,.F.); -#113127 = EDGE_CURVE('',#112935,#91480,#113128,.T.); -#113128 = SURFACE_CURVE('',#113129,(#113133,#113140),.PCURVE_S1.); -#113129 = LINE('',#113130,#113131); -#113130 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.65)); -#113131 = VECTOR('',#113132,1.); -#113132 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#113133 = PCURVE('',#91523,#113134); -#113134 = DEFINITIONAL_REPRESENTATION('',(#113135),#113139); -#113135 = LINE('',#113136,#113137); -#113136 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#113137 = VECTOR('',#113138,1.); -#113138 = DIRECTION('',(-1.,-4.804757279354E-063)); -#113139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113140 = PCURVE('',#91495,#113141); -#113141 = DEFINITIONAL_REPRESENTATION('',(#113142),#113146); -#113142 = LINE('',#113143,#113144); -#113143 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113144 = VECTOR('',#113145,1.); -#113145 = DIRECTION('',(-3.563627120235E-016,1.)); -#113146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113147 = ORIENTED_EDGE('',*,*,#112957,.T.); -#113148 = ORIENTED_EDGE('',*,*,#113149,.T.); -#113149 = EDGE_CURVE('',#112958,#91508,#113150,.T.); -#113150 = SURFACE_CURVE('',#113151,(#113155,#113162),.PCURVE_S1.); -#113151 = LINE('',#113152,#113153); -#113152 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); -#113153 = VECTOR('',#113154,1.); -#113154 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#113155 = PCURVE('',#91523,#113156); -#113156 = DEFINITIONAL_REPRESENTATION('',(#113157),#113161); -#113157 = LINE('',#113158,#113159); -#113158 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113159 = VECTOR('',#113160,1.); -#113160 = DIRECTION('',(-1.,-4.804757279354E-063)); -#113161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113162 = PCURVE('',#91551,#113163); -#113163 = DEFINITIONAL_REPRESENTATION('',(#113164),#113168); -#113164 = LINE('',#113165,#113166); -#113165 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113166 = VECTOR('',#113167,1.); -#113167 = DIRECTION('',(3.563627120235E-016,1.)); -#113168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113169 = ORIENTED_EDGE('',*,*,#91507,.F.); -#113170 = ADVANCED_FACE('',(#113171),#91495,.T.); -#113171 = FACE_BOUND('',#113172,.T.); -#113172 = EDGE_LOOP('',(#113173,#113194,#113195,#113196,#113197,#113198, - #113219,#113220,#113221,#113222,#113223,#113224)); -#113173 = ORIENTED_EDGE('',*,*,#113174,.F.); -#113174 = EDGE_CURVE('',#113032,#91478,#113175,.T.); -#113175 = SURFACE_CURVE('',#113176,(#113180,#113187),.PCURVE_S1.); -#113176 = LINE('',#113177,#113178); -#113177 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.75)); -#113178 = VECTOR('',#113179,1.); -#113179 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#113180 = PCURVE('',#91495,#113181); -#113181 = DEFINITIONAL_REPRESENTATION('',(#113182),#113186); -#113182 = LINE('',#113183,#113184); -#113183 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#113184 = VECTOR('',#113185,1.); -#113185 = DIRECTION('',(-3.563627120235E-016,1.)); -#113186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113187 = PCURVE('',#91577,#113188); -#113188 = DEFINITIONAL_REPRESENTATION('',(#113189),#113193); -#113189 = LINE('',#113190,#113191); -#113190 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#113191 = VECTOR('',#113192,1.); -#113192 = DIRECTION('',(1.,-4.804757279354E-063)); -#113193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113194 = ORIENTED_EDGE('',*,*,#113031,.T.); -#113195 = ORIENTED_EDGE('',*,*,#112834,.T.); -#113196 = ORIENTED_EDGE('',*,*,#112754,.T.); -#113197 = ORIENTED_EDGE('',*,*,#112551,.T.); -#113198 = ORIENTED_EDGE('',*,*,#113199,.F.); -#113199 = EDGE_CURVE('',#112415,#112522,#113200,.T.); -#113200 = SURFACE_CURVE('',#113201,(#113205,#113212),.PCURVE_S1.); -#113201 = LINE('',#113202,#113203); -#113202 = CARTESIAN_POINT('',(-1.,3.15,1.159810404338E-002)); -#113203 = VECTOR('',#113204,1.); -#113204 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#113205 = PCURVE('',#91495,#113206); -#113206 = DEFINITIONAL_REPRESENTATION('',(#113207),#113211); -#113207 = LINE('',#113208,#113209); -#113208 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#113209 = VECTOR('',#113210,1.); -#113210 = DIRECTION('',(-1.,-2.101748079665E-016)); -#113211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113212 = PCURVE('',#112435,#113213); -#113213 = DEFINITIONAL_REPRESENTATION('',(#113214),#113218); -#113214 = LINE('',#113215,#113216); -#113215 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#113216 = VECTOR('',#113217,1.); -#113217 = DIRECTION('',(-1.194699204908E-017,1.)); -#113218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113219 = ORIENTED_EDGE('',*,*,#112497,.F.); -#113220 = ORIENTED_EDGE('',*,*,#112625,.F.); -#113221 = ORIENTED_EDGE('',*,*,#112887,.F.); -#113222 = ORIENTED_EDGE('',*,*,#112934,.F.); -#113223 = ORIENTED_EDGE('',*,*,#113127,.T.); -#113224 = ORIENTED_EDGE('',*,*,#91477,.F.); -#113225 = ADVANCED_FACE('',(#113226),#91577,.T.); -#113226 = FACE_BOUND('',#113227,.T.); -#113227 = EDGE_LOOP('',(#113228,#113249,#113250,#113251)); -#113228 = ORIENTED_EDGE('',*,*,#113229,.F.); -#113229 = EDGE_CURVE('',#113055,#91536,#113230,.T.); -#113230 = SURFACE_CURVE('',#113231,(#113235,#113242),.PCURVE_S1.); -#113231 = LINE('',#113232,#113233); -#113232 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.75)); -#113233 = VECTOR('',#113234,1.); -#113234 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#113235 = PCURVE('',#91577,#113236); -#113236 = DEFINITIONAL_REPRESENTATION('',(#113237),#113241); -#113237 = LINE('',#113238,#113239); -#113238 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113239 = VECTOR('',#113240,1.); -#113240 = DIRECTION('',(1.,-4.804757279354E-063)); -#113241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113242 = PCURVE('',#91551,#113243); -#113243 = DEFINITIONAL_REPRESENTATION('',(#113244),#113248); -#113244 = LINE('',#113245,#113246); -#113245 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#113246 = VECTOR('',#113247,1.); -#113247 = DIRECTION('',(3.563627120235E-016,1.)); -#113248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113249 = ORIENTED_EDGE('',*,*,#113054,.T.); -#113250 = ORIENTED_EDGE('',*,*,#113174,.T.); -#113251 = ORIENTED_EDGE('',*,*,#91563,.F.); -#113252 = ADVANCED_FACE('',(#113253),#91551,.T.); -#113253 = FACE_BOUND('',#113254,.T.); -#113254 = EDGE_LOOP('',(#113255,#113256,#113257,#113258,#113259,#113260, - #113281,#113282,#113283,#113284,#113285,#113286)); -#113255 = ORIENTED_EDGE('',*,*,#113149,.F.); -#113256 = ORIENTED_EDGE('',*,*,#113002,.T.); -#113257 = ORIENTED_EDGE('',*,*,#112909,.T.); -#113258 = ORIENTED_EDGE('',*,*,#112653,.T.); -#113259 = ORIENTED_EDGE('',*,*,#112447,.T.); -#113260 = ORIENTED_EDGE('',*,*,#113261,.F.); -#113261 = EDGE_CURVE('',#112524,#112413,#113262,.T.); -#113262 = SURFACE_CURVE('',#113263,(#113267,#113274),.PCURVE_S1.); -#113263 = LINE('',#113264,#113265); -#113264 = CARTESIAN_POINT('',(-1.,3.35,1.159810404338E-002)); -#113265 = VECTOR('',#113266,1.); -#113266 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#113267 = PCURVE('',#91551,#113268); -#113268 = DEFINITIONAL_REPRESENTATION('',(#113269),#113273); -#113269 = LINE('',#113270,#113271); -#113270 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#113271 = VECTOR('',#113272,1.); -#113272 = DIRECTION('',(-1.,2.101748079665E-016)); -#113273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113274 = PCURVE('',#112435,#113275); -#113275 = DEFINITIONAL_REPRESENTATION('',(#113276),#113280); -#113276 = LINE('',#113277,#113278); -#113277 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#113278 = VECTOR('',#113279,1.); -#113279 = DIRECTION('',(1.194699204908E-017,-1.)); -#113280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115507 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#115508 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#115509 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#115510 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#115511 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#115512 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#115513 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#115514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113281 = ORIENTED_EDGE('',*,*,#112601,.F.); -#113282 = ORIENTED_EDGE('',*,*,#112704,.F.); -#113283 = ORIENTED_EDGE('',*,*,#112812,.F.); -#113284 = ORIENTED_EDGE('',*,*,#113099,.F.); -#113285 = ORIENTED_EDGE('',*,*,#113229,.T.); -#113286 = ORIENTED_EDGE('',*,*,#91535,.F.); -#113287 = ADVANCED_FACE('',(#113288),#112435,.T.); -#113288 = FACE_BOUND('',#113289,.T.); -#113289 = EDGE_LOOP('',(#113290,#113291,#113292,#113293)); -#113290 = ORIENTED_EDGE('',*,*,#113199,.T.); -#113291 = ORIENTED_EDGE('',*,*,#112521,.T.); -#113292 = ORIENTED_EDGE('',*,*,#113261,.T.); -#113293 = ORIENTED_EDGE('',*,*,#112412,.T.); -#113294 = ADVANCED_FACE('',(#113295),#113309,.F.); -#113295 = FACE_BOUND('',#113296,.T.); -#113296 = EDGE_LOOP('',(#113297,#113332,#113355,#113382)); -#113297 = ORIENTED_EDGE('',*,*,#113298,.F.); -#113298 = EDGE_CURVE('',#113299,#113301,#113303,.T.); -#113299 = VERTEX_POINT('',#113300); -#113300 = CARTESIAN_POINT('',(-1.,3.85,-0.308197125857)); -#113301 = VERTEX_POINT('',#113302); -#113302 = CARTESIAN_POINT('',(-1.,3.65,-0.308197125857)); -#113303 = SURFACE_CURVE('',#113304,(#113308,#113320),.PCURVE_S1.); -#113304 = LINE('',#113305,#113306); -#113305 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#113306 = VECTOR('',#113307,1.); -#113307 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113308 = PCURVE('',#113309,#113314); -#113309 = PLANE('',#113310); -#113310 = AXIS2_PLACEMENT_3D('',#113311,#113312,#113313); -#113311 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#113312 = DIRECTION('',(0.E+000,0.E+000,1.)); -#113313 = DIRECTION('',(1.,0.E+000,0.E+000)); -#113314 = DEFINITIONAL_REPRESENTATION('',(#113315),#113319); -#113315 = LINE('',#113316,#113317); -#113316 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#113317 = VECTOR('',#113318,1.); -#113318 = DIRECTION('',(4.440892098501E-016,-1.)); -#113319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113320 = PCURVE('',#113321,#113326); -#113321 = PLANE('',#113322); -#113322 = AXIS2_PLACEMENT_3D('',#113323,#113324,#113325); -#113323 = CARTESIAN_POINT('',(-1.,3.75,-0.258196742327)); -#113324 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#113325 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113326 = DEFINITIONAL_REPRESENTATION('',(#113327),#113331); -#113327 = LINE('',#113328,#113329); -#113328 = CARTESIAN_POINT('',(-6.25,-5.000038352949E-002)); -#113329 = VECTOR('',#113330,1.); -#113330 = DIRECTION('',(1.,0.E+000)); -#113331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113332 = ORIENTED_EDGE('',*,*,#113333,.F.); -#113333 = EDGE_CURVE('',#113334,#113299,#113336,.T.); -#113334 = VERTEX_POINT('',#113335); -#113335 = CARTESIAN_POINT('',(-0.74341632541,3.85,-0.308197125857)); -#113336 = SURFACE_CURVE('',#113337,(#113341,#113348),.PCURVE_S1.); -#113337 = LINE('',#113338,#113339); -#113338 = CARTESIAN_POINT('',(-0.74341632541,3.85,-0.308197125857)); -#113339 = VECTOR('',#113340,1.); -#113340 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#113341 = PCURVE('',#113309,#113342); -#113342 = DEFINITIONAL_REPRESENTATION('',(#113343),#113347); -#113343 = LINE('',#113344,#113345); -#113344 = CARTESIAN_POINT('',(2.775557561563E-015,-6.15)); -#113345 = VECTOR('',#113346,1.); -#113346 = DIRECTION('',(-1.,0.E+000)); -#113347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113348 = PCURVE('',#91437,#113349); -#113349 = DEFINITIONAL_REPRESENTATION('',(#113350),#113354); -#113350 = LINE('',#113351,#113352); -#113351 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#113352 = VECTOR('',#113353,1.); -#113353 = DIRECTION('',(0.E+000,-1.)); -#113354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113355 = ORIENTED_EDGE('',*,*,#113356,.F.); -#113356 = EDGE_CURVE('',#113357,#113334,#113359,.T.); -#113357 = VERTEX_POINT('',#113358); -#113358 = CARTESIAN_POINT('',(-0.74341632541,3.65,-0.308197125857)); -#113359 = SURFACE_CURVE('',#113360,(#113364,#113371),.PCURVE_S1.); -#113360 = LINE('',#113361,#113362); -#113361 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#113362 = VECTOR('',#113363,1.); -#113363 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113364 = PCURVE('',#113309,#113365); -#113365 = DEFINITIONAL_REPRESENTATION('',(#113366),#113370); -#113366 = LINE('',#113367,#113368); -#113367 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113368 = VECTOR('',#113369,1.); -#113369 = DIRECTION('',(-4.440892098501E-016,1.)); -#113370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113371 = PCURVE('',#113372,#113377); -#113372 = CYLINDRICAL_SURFACE('',#113373,0.308574064194); -#113373 = AXIS2_PLACEMENT_3D('',#113374,#113375,#113376); -#113374 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#113375 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113376 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113377 = DEFINITIONAL_REPRESENTATION('',(#113378),#113381); -#113378 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113379,#113380), - .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#113379 = CARTESIAN_POINT('',(4.761821717947,-6.35)); -#113380 = CARTESIAN_POINT('',(4.761821717947,-6.15)); -#113381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115515 = ADVANCED_FACE('',(#115516),#93915,.T.); +#115516 = FACE_BOUND('',#115517,.T.); +#115517 = EDGE_LOOP('',(#115518,#115539,#115540,#115561)); +#115518 = ORIENTED_EDGE('',*,*,#115519,.F.); +#115519 = EDGE_CURVE('',#115327,#93872,#115520,.T.); +#115520 = SURFACE_CURVE('',#115521,(#115525,#115532),.PCURVE_S1.); +#115521 = LINE('',#115522,#115523); +#115522 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.65)); +#115523 = VECTOR('',#115524,1.); +#115524 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#115525 = PCURVE('',#93915,#115526); +#115526 = DEFINITIONAL_REPRESENTATION('',(#115527),#115531); +#115527 = LINE('',#115528,#115529); +#115528 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#115529 = VECTOR('',#115530,1.); +#115530 = DIRECTION('',(-1.,-4.804757279354E-063)); +#115531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115532 = PCURVE('',#93887,#115533); +#115533 = DEFINITIONAL_REPRESENTATION('',(#115534),#115538); +#115534 = LINE('',#115535,#115536); +#115535 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115536 = VECTOR('',#115537,1.); +#115537 = DIRECTION('',(-3.563627120235E-016,1.)); +#115538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115539 = ORIENTED_EDGE('',*,*,#115349,.T.); +#115540 = ORIENTED_EDGE('',*,*,#115541,.T.); +#115541 = EDGE_CURVE('',#115350,#93900,#115542,.T.); +#115542 = SURFACE_CURVE('',#115543,(#115547,#115554),.PCURVE_S1.); +#115543 = LINE('',#115544,#115545); +#115544 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.65)); +#115545 = VECTOR('',#115546,1.); +#115546 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#115547 = PCURVE('',#93915,#115548); +#115548 = DEFINITIONAL_REPRESENTATION('',(#115549),#115553); +#115549 = LINE('',#115550,#115551); +#115550 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115551 = VECTOR('',#115552,1.); +#115552 = DIRECTION('',(-1.,-4.804757279354E-063)); +#115553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115554 = PCURVE('',#93943,#115555); +#115555 = DEFINITIONAL_REPRESENTATION('',(#115556),#115560); +#115556 = LINE('',#115557,#115558); +#115557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115558 = VECTOR('',#115559,1.); +#115559 = DIRECTION('',(3.563627120235E-016,1.)); +#115560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115561 = ORIENTED_EDGE('',*,*,#93899,.F.); +#115562 = ADVANCED_FACE('',(#115563),#93887,.T.); +#115563 = FACE_BOUND('',#115564,.T.); +#115564 = EDGE_LOOP('',(#115565,#115586,#115587,#115588,#115589,#115590, + #115611,#115612,#115613,#115614,#115615,#115616)); +#115565 = ORIENTED_EDGE('',*,*,#115566,.F.); +#115566 = EDGE_CURVE('',#115424,#93870,#115567,.T.); +#115567 = SURFACE_CURVE('',#115568,(#115572,#115579),.PCURVE_S1.); +#115568 = LINE('',#115569,#115570); +#115569 = CARTESIAN_POINT('',(-0.527847992439,3.15,0.75)); +#115570 = VECTOR('',#115571,1.); +#115571 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#115572 = PCURVE('',#93887,#115573); +#115573 = DEFINITIONAL_REPRESENTATION('',(#115574),#115578); +#115574 = LINE('',#115575,#115576); +#115575 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#115576 = VECTOR('',#115577,1.); +#115577 = DIRECTION('',(-3.563627120235E-016,1.)); +#115578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113382 = ORIENTED_EDGE('',*,*,#113383,.T.); -#113383 = EDGE_CURVE('',#113357,#113301,#113384,.T.); -#113384 = SURFACE_CURVE('',#113385,(#113389,#113396),.PCURVE_S1.); -#113385 = LINE('',#113386,#113387); -#113386 = CARTESIAN_POINT('',(-0.74341632541,3.65,-0.308197125857)); -#113387 = VECTOR('',#113388,1.); -#113388 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#113389 = PCURVE('',#113309,#113390); -#113390 = DEFINITIONAL_REPRESENTATION('',(#113391),#113395); -#113391 = LINE('',#113392,#113393); -#113392 = CARTESIAN_POINT('',(2.886579864025E-015,-6.35)); -#113393 = VECTOR('',#113394,1.); -#113394 = DIRECTION('',(-1.,0.E+000)); -#113395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115579 = PCURVE('',#93969,#115580); +#115580 = DEFINITIONAL_REPRESENTATION('',(#115581),#115585); +#115581 = LINE('',#115582,#115583); +#115582 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#115583 = VECTOR('',#115584,1.); +#115584 = DIRECTION('',(1.,-4.804757279354E-063)); +#115585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113396 = PCURVE('',#91381,#113397); -#113397 = DEFINITIONAL_REPRESENTATION('',(#113398),#113402); -#113398 = LINE('',#113399,#113400); -#113399 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#113400 = VECTOR('',#113401,1.); -#113401 = DIRECTION('',(0.E+000,-1.)); -#113402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115586 = ORIENTED_EDGE('',*,*,#115423,.T.); +#115587 = ORIENTED_EDGE('',*,*,#115226,.T.); +#115588 = ORIENTED_EDGE('',*,*,#115146,.T.); +#115589 = ORIENTED_EDGE('',*,*,#114943,.T.); +#115590 = ORIENTED_EDGE('',*,*,#115591,.F.); +#115591 = EDGE_CURVE('',#114807,#114914,#115592,.T.); +#115592 = SURFACE_CURVE('',#115593,(#115597,#115604),.PCURVE_S1.); +#115593 = LINE('',#115594,#115595); +#115594 = CARTESIAN_POINT('',(-1.,3.15,1.159810404338E-002)); +#115595 = VECTOR('',#115596,1.); +#115596 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#115597 = PCURVE('',#93887,#115598); +#115598 = DEFINITIONAL_REPRESENTATION('',(#115599),#115603); +#115599 = LINE('',#115600,#115601); +#115600 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#115601 = VECTOR('',#115602,1.); +#115602 = DIRECTION('',(-1.,-2.101748079665E-016)); +#115603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113403 = ADVANCED_FACE('',(#113404),#113418,.F.); -#113404 = FACE_BOUND('',#113405,.T.); -#113405 = EDGE_LOOP('',(#113406,#113436,#113459,#113486)); -#113406 = ORIENTED_EDGE('',*,*,#113407,.F.); -#113407 = EDGE_CURVE('',#113408,#113410,#113412,.T.); -#113408 = VERTEX_POINT('',#113409); -#113409 = CARTESIAN_POINT('',(-1.,3.65,-0.208196358798)); -#113410 = VERTEX_POINT('',#113411); -#113411 = CARTESIAN_POINT('',(-1.,3.85,-0.208196358798)); -#113412 = SURFACE_CURVE('',#113413,(#113417,#113429),.PCURVE_S1.); -#113413 = LINE('',#113414,#113415); -#113414 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#113415 = VECTOR('',#113416,1.); -#113416 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113417 = PCURVE('',#113418,#113423); -#113418 = PLANE('',#113419); -#113419 = AXIS2_PLACEMENT_3D('',#113420,#113421,#113422); -#113420 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#113421 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#113422 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#113423 = DEFINITIONAL_REPRESENTATION('',(#113424),#113428); -#113424 = LINE('',#113425,#113426); -#113425 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#113426 = VECTOR('',#113427,1.); -#113427 = DIRECTION('',(4.440892098501E-016,1.)); -#113428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113429 = PCURVE('',#113321,#113430); -#113430 = DEFINITIONAL_REPRESENTATION('',(#113431),#113435); -#113431 = LINE('',#113432,#113433); -#113432 = CARTESIAN_POINT('',(-6.25,5.000038352949E-002)); -#113433 = VECTOR('',#113434,1.); -#113434 = DIRECTION('',(-1.,0.E+000)); -#113435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115604 = PCURVE('',#114827,#115605); +#115605 = DEFINITIONAL_REPRESENTATION('',(#115606),#115610); +#115606 = LINE('',#115607,#115608); +#115607 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#115608 = VECTOR('',#115609,1.); +#115609 = DIRECTION('',(-1.194699204908E-017,1.)); +#115610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113436 = ORIENTED_EDGE('',*,*,#113437,.F.); -#113437 = EDGE_CURVE('',#113438,#113408,#113440,.T.); -#113438 = VERTEX_POINT('',#113439); -#113439 = CARTESIAN_POINT('',(-0.740726081328,3.65,-0.208196358798)); -#113440 = SURFACE_CURVE('',#113441,(#113445,#113452),.PCURVE_S1.); -#113441 = LINE('',#113442,#113443); -#113442 = CARTESIAN_POINT('',(-0.740726081328,3.65,-0.208196358798)); -#113443 = VECTOR('',#113444,1.); -#113444 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#113445 = PCURVE('',#113418,#113446); -#113446 = DEFINITIONAL_REPRESENTATION('',(#113447),#113451); -#113447 = LINE('',#113448,#113449); -#113448 = CARTESIAN_POINT('',(-2.997602166488E-015,-6.35)); -#113449 = VECTOR('',#113450,1.); -#113450 = DIRECTION('',(1.,0.E+000)); -#113451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113452 = PCURVE('',#91381,#113453); -#113453 = DEFINITIONAL_REPRESENTATION('',(#113454),#113458); -#113454 = LINE('',#113455,#113456); -#113455 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#113456 = VECTOR('',#113457,1.); -#113457 = DIRECTION('',(0.E+000,-1.)); -#113458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113459 = ORIENTED_EDGE('',*,*,#113460,.F.); -#113460 = EDGE_CURVE('',#113461,#113438,#113463,.T.); -#113461 = VERTEX_POINT('',#113462); -#113462 = CARTESIAN_POINT('',(-0.740726081328,3.85,-0.208196358798)); -#113463 = SURFACE_CURVE('',#113464,(#113468,#113475),.PCURVE_S1.); -#113464 = LINE('',#113465,#113466); -#113465 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#113466 = VECTOR('',#113467,1.); -#113467 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113468 = PCURVE('',#113418,#113469); -#113469 = DEFINITIONAL_REPRESENTATION('',(#113470),#113474); -#113470 = LINE('',#113471,#113472); -#113471 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113472 = VECTOR('',#113473,1.); -#113473 = DIRECTION('',(-4.440892098501E-016,-1.)); -#113474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113475 = PCURVE('',#113476,#113481); -#113476 = CYLINDRICAL_SURFACE('',#113477,0.208574704164); -#113477 = AXIS2_PLACEMENT_3D('',#113478,#113479,#113480); -#113478 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#113479 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113480 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113481 = DEFINITIONAL_REPRESENTATION('',(#113482),#113485); -#113482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113483,#113484), - .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#113483 = CARTESIAN_POINT('',(4.772630242227,-6.15)); -#113484 = CARTESIAN_POINT('',(4.772630242227,-6.35)); -#113485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#115611 = ORIENTED_EDGE('',*,*,#114889,.F.); +#115612 = ORIENTED_EDGE('',*,*,#115017,.F.); +#115613 = ORIENTED_EDGE('',*,*,#115279,.F.); +#115614 = ORIENTED_EDGE('',*,*,#115326,.F.); +#115615 = ORIENTED_EDGE('',*,*,#115519,.T.); +#115616 = ORIENTED_EDGE('',*,*,#93869,.F.); +#115617 = ADVANCED_FACE('',(#115618),#93969,.T.); +#115618 = FACE_BOUND('',#115619,.T.); +#115619 = EDGE_LOOP('',(#115620,#115641,#115642,#115643)); +#115620 = ORIENTED_EDGE('',*,*,#115621,.F.); +#115621 = EDGE_CURVE('',#115447,#93928,#115622,.T.); +#115622 = SURFACE_CURVE('',#115623,(#115627,#115634),.PCURVE_S1.); +#115623 = LINE('',#115624,#115625); +#115624 = CARTESIAN_POINT('',(-0.527847992439,3.35,0.75)); +#115625 = VECTOR('',#115626,1.); +#115626 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#115627 = PCURVE('',#93969,#115628); +#115628 = DEFINITIONAL_REPRESENTATION('',(#115629),#115633); +#115629 = LINE('',#115630,#115631); +#115630 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115631 = VECTOR('',#115632,1.); +#115632 = DIRECTION('',(1.,-4.804757279354E-063)); +#115633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115634 = PCURVE('',#93943,#115635); +#115635 = DEFINITIONAL_REPRESENTATION('',(#115636),#115640); +#115636 = LINE('',#115637,#115638); +#115637 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#115638 = VECTOR('',#115639,1.); +#115639 = DIRECTION('',(3.563627120235E-016,1.)); +#115640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115641 = ORIENTED_EDGE('',*,*,#115446,.T.); +#115642 = ORIENTED_EDGE('',*,*,#115566,.T.); +#115643 = ORIENTED_EDGE('',*,*,#93955,.F.); +#115644 = ADVANCED_FACE('',(#115645),#93943,.T.); +#115645 = FACE_BOUND('',#115646,.T.); +#115646 = EDGE_LOOP('',(#115647,#115648,#115649,#115650,#115651,#115652, + #115673,#115674,#115675,#115676,#115677,#115678)); +#115647 = ORIENTED_EDGE('',*,*,#115541,.F.); +#115648 = ORIENTED_EDGE('',*,*,#115394,.T.); +#115649 = ORIENTED_EDGE('',*,*,#115301,.T.); +#115650 = ORIENTED_EDGE('',*,*,#115045,.T.); +#115651 = ORIENTED_EDGE('',*,*,#114839,.T.); +#115652 = ORIENTED_EDGE('',*,*,#115653,.F.); +#115653 = EDGE_CURVE('',#114916,#114805,#115654,.T.); +#115654 = SURFACE_CURVE('',#115655,(#115659,#115666),.PCURVE_S1.); +#115655 = LINE('',#115656,#115657); +#115656 = CARTESIAN_POINT('',(-1.,3.35,1.159810404338E-002)); +#115657 = VECTOR('',#115658,1.); +#115658 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#115659 = PCURVE('',#93943,#115660); +#115660 = DEFINITIONAL_REPRESENTATION('',(#115661),#115665); +#115661 = LINE('',#115662,#115663); +#115662 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#115663 = VECTOR('',#115664,1.); +#115664 = DIRECTION('',(-1.,2.101748079665E-016)); +#115665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115666 = PCURVE('',#114827,#115667); +#115667 = DEFINITIONAL_REPRESENTATION('',(#115668),#115672); +#115668 = LINE('',#115669,#115670); +#115669 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#115670 = VECTOR('',#115671,1.); +#115671 = DIRECTION('',(1.194699204908E-017,-1.)); +#115672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115673 = ORIENTED_EDGE('',*,*,#114993,.F.); +#115674 = ORIENTED_EDGE('',*,*,#115096,.F.); +#115675 = ORIENTED_EDGE('',*,*,#115204,.F.); +#115676 = ORIENTED_EDGE('',*,*,#115491,.F.); +#115677 = ORIENTED_EDGE('',*,*,#115621,.T.); +#115678 = ORIENTED_EDGE('',*,*,#93927,.F.); +#115679 = ADVANCED_FACE('',(#115680),#114827,.T.); +#115680 = FACE_BOUND('',#115681,.T.); +#115681 = EDGE_LOOP('',(#115682,#115683,#115684,#115685)); +#115682 = ORIENTED_EDGE('',*,*,#115591,.T.); +#115683 = ORIENTED_EDGE('',*,*,#114913,.T.); +#115684 = ORIENTED_EDGE('',*,*,#115653,.T.); +#115685 = ORIENTED_EDGE('',*,*,#114804,.T.); +#115686 = ADVANCED_FACE('',(#115687),#115701,.F.); +#115687 = FACE_BOUND('',#115688,.T.); +#115688 = EDGE_LOOP('',(#115689,#115724,#115747,#115774)); +#115689 = ORIENTED_EDGE('',*,*,#115690,.F.); +#115690 = EDGE_CURVE('',#115691,#115693,#115695,.T.); +#115691 = VERTEX_POINT('',#115692); +#115692 = CARTESIAN_POINT('',(-1.,3.85,-0.308197125857)); +#115693 = VERTEX_POINT('',#115694); +#115694 = CARTESIAN_POINT('',(-1.,3.65,-0.308197125857)); +#115695 = SURFACE_CURVE('',#115696,(#115700,#115712),.PCURVE_S1.); +#115696 = LINE('',#115697,#115698); +#115697 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#115698 = VECTOR('',#115699,1.); +#115699 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115700 = PCURVE('',#115701,#115706); +#115701 = PLANE('',#115702); +#115702 = AXIS2_PLACEMENT_3D('',#115703,#115704,#115705); +#115703 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#115704 = DIRECTION('',(0.E+000,0.E+000,1.)); +#115705 = DIRECTION('',(1.,0.E+000,0.E+000)); +#115706 = DEFINITIONAL_REPRESENTATION('',(#115707),#115711); +#115707 = LINE('',#115708,#115709); +#115708 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#115709 = VECTOR('',#115710,1.); +#115710 = DIRECTION('',(4.440892098501E-016,-1.)); +#115711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115712 = PCURVE('',#115713,#115718); +#115713 = PLANE('',#115714); +#115714 = AXIS2_PLACEMENT_3D('',#115715,#115716,#115717); +#115715 = CARTESIAN_POINT('',(-1.,3.75,-0.258196742327)); +#115716 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#115717 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115718 = DEFINITIONAL_REPRESENTATION('',(#115719),#115723); +#115719 = LINE('',#115720,#115721); +#115720 = CARTESIAN_POINT('',(-6.25,-5.000038352949E-002)); +#115721 = VECTOR('',#115722,1.); +#115722 = DIRECTION('',(1.,0.E+000)); +#115723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115724 = ORIENTED_EDGE('',*,*,#115725,.F.); +#115725 = EDGE_CURVE('',#115726,#115691,#115728,.T.); +#115726 = VERTEX_POINT('',#115727); +#115727 = CARTESIAN_POINT('',(-0.74341632541,3.85,-0.308197125857)); +#115728 = SURFACE_CURVE('',#115729,(#115733,#115740),.PCURVE_S1.); +#115729 = LINE('',#115730,#115731); +#115730 = CARTESIAN_POINT('',(-0.74341632541,3.85,-0.308197125857)); +#115731 = VECTOR('',#115732,1.); +#115732 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#115733 = PCURVE('',#115701,#115734); +#115734 = DEFINITIONAL_REPRESENTATION('',(#115735),#115739); +#115735 = LINE('',#115736,#115737); +#115736 = CARTESIAN_POINT('',(2.775557561563E-015,-6.15)); +#115737 = VECTOR('',#115738,1.); +#115738 = DIRECTION('',(-1.,0.E+000)); +#115739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115740 = PCURVE('',#93829,#115741); +#115741 = DEFINITIONAL_REPRESENTATION('',(#115742),#115746); +#115742 = LINE('',#115743,#115744); +#115743 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#115744 = VECTOR('',#115745,1.); +#115745 = DIRECTION('',(0.E+000,-1.)); +#115746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115747 = ORIENTED_EDGE('',*,*,#115748,.F.); +#115748 = EDGE_CURVE('',#115749,#115726,#115751,.T.); +#115749 = VERTEX_POINT('',#115750); +#115750 = CARTESIAN_POINT('',(-0.74341632541,3.65,-0.308197125857)); +#115751 = SURFACE_CURVE('',#115752,(#115756,#115763),.PCURVE_S1.); +#115752 = LINE('',#115753,#115754); +#115753 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#115754 = VECTOR('',#115755,1.); +#115755 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115756 = PCURVE('',#115701,#115757); +#115757 = DEFINITIONAL_REPRESENTATION('',(#115758),#115762); +#115758 = LINE('',#115759,#115760); +#115759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115760 = VECTOR('',#115761,1.); +#115761 = DIRECTION('',(-4.440892098501E-016,1.)); +#115762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115763 = PCURVE('',#115764,#115769); +#115764 = CYLINDRICAL_SURFACE('',#115765,0.308574064194); +#115765 = AXIS2_PLACEMENT_3D('',#115766,#115767,#115768); +#115766 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#115767 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115768 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115769 = DEFINITIONAL_REPRESENTATION('',(#115770),#115773); +#115770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115771,#115772), + .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); +#115771 = CARTESIAN_POINT('',(4.761821717947,-6.35)); +#115772 = CARTESIAN_POINT('',(4.761821717947,-6.15)); +#115773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115774 = ORIENTED_EDGE('',*,*,#115775,.T.); +#115775 = EDGE_CURVE('',#115749,#115693,#115776,.T.); +#115776 = SURFACE_CURVE('',#115777,(#115781,#115788),.PCURVE_S1.); +#115777 = LINE('',#115778,#115779); +#115778 = CARTESIAN_POINT('',(-0.74341632541,3.65,-0.308197125857)); +#115779 = VECTOR('',#115780,1.); +#115780 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#115781 = PCURVE('',#115701,#115782); +#115782 = DEFINITIONAL_REPRESENTATION('',(#115783),#115787); +#115783 = LINE('',#115784,#115785); +#115784 = CARTESIAN_POINT('',(2.886579864025E-015,-6.35)); +#115785 = VECTOR('',#115786,1.); +#115786 = DIRECTION('',(-1.,0.E+000)); +#115787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115788 = PCURVE('',#93773,#115789); +#115789 = DEFINITIONAL_REPRESENTATION('',(#115790),#115794); +#115790 = LINE('',#115791,#115792); +#115791 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#115792 = VECTOR('',#115793,1.); +#115793 = DIRECTION('',(0.E+000,-1.)); +#115794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113486 = ORIENTED_EDGE('',*,*,#113487,.T.); -#113487 = EDGE_CURVE('',#113461,#113410,#113488,.T.); -#113488 = SURFACE_CURVE('',#113489,(#113493,#113500),.PCURVE_S1.); -#113489 = LINE('',#113490,#113491); -#113490 = CARTESIAN_POINT('',(-0.740726081328,3.85,-0.208196358798)); -#113491 = VECTOR('',#113492,1.); -#113492 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#113493 = PCURVE('',#113418,#113494); -#113494 = DEFINITIONAL_REPRESENTATION('',(#113495),#113499); -#113495 = LINE('',#113496,#113497); -#113496 = CARTESIAN_POINT('',(-2.775557561563E-015,-6.15)); -#113497 = VECTOR('',#113498,1.); -#113498 = DIRECTION('',(1.,0.E+000)); -#113499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113500 = PCURVE('',#91437,#113501); -#113501 = DEFINITIONAL_REPRESENTATION('',(#113502),#113506); -#113502 = LINE('',#113503,#113504); -#113503 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#113504 = VECTOR('',#113505,1.); -#113505 = DIRECTION('',(0.E+000,-1.)); -#113506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113507 = ADVANCED_FACE('',(#113508),#113372,.T.); -#113508 = FACE_BOUND('',#113509,.T.); -#113509 = EDGE_LOOP('',(#113510,#113560,#113561,#113584)); -#113510 = ORIENTED_EDGE('',*,*,#113511,.T.); -#113511 = EDGE_CURVE('',#113512,#113357,#113514,.T.); -#113512 = VERTEX_POINT('',#113513); -#113513 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.E+000)); -#113514 = SURFACE_CURVE('',#113515,(#113520,#113549),.PCURVE_S1.); -#113515 = CIRCLE('',#113516,0.308574064194); -#113516 = AXIS2_PLACEMENT_3D('',#113517,#113518,#113519); -#113517 = CARTESIAN_POINT('',(-0.728168876214,3.65,2.640924866458E-017) - ); -#113518 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113519 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113520 = PCURVE('',#113372,#113521); -#113521 = DEFINITIONAL_REPRESENTATION('',(#113522),#113548); -#113522 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113523,#113524,#113525, - #113526,#113527,#113528,#113529,#113530,#113531,#113532,#113533, - #113534,#113535,#113536,#113537,#113538,#113539,#113540,#113541, - #113542,#113543,#113544,#113545,#113546,#113547),.UNSPECIFIED.,.F., +#115795 = ADVANCED_FACE('',(#115796),#115810,.F.); +#115796 = FACE_BOUND('',#115797,.T.); +#115797 = EDGE_LOOP('',(#115798,#115828,#115851,#115878)); +#115798 = ORIENTED_EDGE('',*,*,#115799,.F.); +#115799 = EDGE_CURVE('',#115800,#115802,#115804,.T.); +#115800 = VERTEX_POINT('',#115801); +#115801 = CARTESIAN_POINT('',(-1.,3.65,-0.208196358798)); +#115802 = VERTEX_POINT('',#115803); +#115803 = CARTESIAN_POINT('',(-1.,3.85,-0.208196358798)); +#115804 = SURFACE_CURVE('',#115805,(#115809,#115821),.PCURVE_S1.); +#115805 = LINE('',#115806,#115807); +#115806 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#115807 = VECTOR('',#115808,1.); +#115808 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115809 = PCURVE('',#115810,#115815); +#115810 = PLANE('',#115811); +#115811 = AXIS2_PLACEMENT_3D('',#115812,#115813,#115814); +#115812 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#115813 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#115814 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#115815 = DEFINITIONAL_REPRESENTATION('',(#115816),#115820); +#115816 = LINE('',#115817,#115818); +#115817 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#115818 = VECTOR('',#115819,1.); +#115819 = DIRECTION('',(4.440892098501E-016,1.)); +#115820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115821 = PCURVE('',#115713,#115822); +#115822 = DEFINITIONAL_REPRESENTATION('',(#115823),#115827); +#115823 = LINE('',#115824,#115825); +#115824 = CARTESIAN_POINT('',(-6.25,5.000038352949E-002)); +#115825 = VECTOR('',#115826,1.); +#115826 = DIRECTION('',(-1.,0.E+000)); +#115827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115828 = ORIENTED_EDGE('',*,*,#115829,.F.); +#115829 = EDGE_CURVE('',#115830,#115800,#115832,.T.); +#115830 = VERTEX_POINT('',#115831); +#115831 = CARTESIAN_POINT('',(-0.740726081328,3.65,-0.208196358798)); +#115832 = SURFACE_CURVE('',#115833,(#115837,#115844),.PCURVE_S1.); +#115833 = LINE('',#115834,#115835); +#115834 = CARTESIAN_POINT('',(-0.740726081328,3.65,-0.208196358798)); +#115835 = VECTOR('',#115836,1.); +#115836 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#115837 = PCURVE('',#115810,#115838); +#115838 = DEFINITIONAL_REPRESENTATION('',(#115839),#115843); +#115839 = LINE('',#115840,#115841); +#115840 = CARTESIAN_POINT('',(-2.997602166488E-015,-6.35)); +#115841 = VECTOR('',#115842,1.); +#115842 = DIRECTION('',(1.,0.E+000)); +#115843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115844 = PCURVE('',#93773,#115845); +#115845 = DEFINITIONAL_REPRESENTATION('',(#115846),#115850); +#115846 = LINE('',#115847,#115848); +#115847 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#115848 = VECTOR('',#115849,1.); +#115849 = DIRECTION('',(0.E+000,-1.)); +#115850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115851 = ORIENTED_EDGE('',*,*,#115852,.F.); +#115852 = EDGE_CURVE('',#115853,#115830,#115855,.T.); +#115853 = VERTEX_POINT('',#115854); +#115854 = CARTESIAN_POINT('',(-0.740726081328,3.85,-0.208196358798)); +#115855 = SURFACE_CURVE('',#115856,(#115860,#115867),.PCURVE_S1.); +#115856 = LINE('',#115857,#115858); +#115857 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#115858 = VECTOR('',#115859,1.); +#115859 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115860 = PCURVE('',#115810,#115861); +#115861 = DEFINITIONAL_REPRESENTATION('',(#115862),#115866); +#115862 = LINE('',#115863,#115864); +#115863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#115864 = VECTOR('',#115865,1.); +#115865 = DIRECTION('',(-4.440892098501E-016,-1.)); +#115866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115867 = PCURVE('',#115868,#115873); +#115868 = CYLINDRICAL_SURFACE('',#115869,0.208574704164); +#115869 = AXIS2_PLACEMENT_3D('',#115870,#115871,#115872); +#115870 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#115871 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115872 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115873 = DEFINITIONAL_REPRESENTATION('',(#115874),#115877); +#115874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115875,#115876), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); +#115875 = CARTESIAN_POINT('',(4.772630242227,-6.15)); +#115876 = CARTESIAN_POINT('',(4.772630242227,-6.35)); +#115877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115878 = ORIENTED_EDGE('',*,*,#115879,.T.); +#115879 = EDGE_CURVE('',#115853,#115802,#115880,.T.); +#115880 = SURFACE_CURVE('',#115881,(#115885,#115892),.PCURVE_S1.); +#115881 = LINE('',#115882,#115883); +#115882 = CARTESIAN_POINT('',(-0.740726081328,3.85,-0.208196358798)); +#115883 = VECTOR('',#115884,1.); +#115884 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#115885 = PCURVE('',#115810,#115886); +#115886 = DEFINITIONAL_REPRESENTATION('',(#115887),#115891); +#115887 = LINE('',#115888,#115889); +#115888 = CARTESIAN_POINT('',(-2.775557561563E-015,-6.15)); +#115889 = VECTOR('',#115890,1.); +#115890 = DIRECTION('',(1.,0.E+000)); +#115891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115892 = PCURVE('',#93829,#115893); +#115893 = DEFINITIONAL_REPRESENTATION('',(#115894),#115898); +#115894 = LINE('',#115895,#115896); +#115895 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#115896 = VECTOR('',#115897,1.); +#115897 = DIRECTION('',(0.E+000,-1.)); +#115898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115899 = ADVANCED_FACE('',(#115900),#115764,.T.); +#115900 = FACE_BOUND('',#115901,.T.); +#115901 = EDGE_LOOP('',(#115902,#115952,#115953,#115976)); +#115902 = ORIENTED_EDGE('',*,*,#115903,.T.); +#115903 = EDGE_CURVE('',#115904,#115749,#115906,.T.); +#115904 = VERTEX_POINT('',#115905); +#115905 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.E+000)); +#115906 = SURFACE_CURVE('',#115907,(#115912,#115941),.PCURVE_S1.); +#115907 = CIRCLE('',#115908,0.308574064194); +#115908 = AXIS2_PLACEMENT_3D('',#115909,#115910,#115911); +#115909 = CARTESIAN_POINT('',(-0.728168876214,3.65,2.640924866458E-017) + ); +#115910 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115911 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115912 = PCURVE('',#115764,#115913); +#115913 = DEFINITIONAL_REPRESENTATION('',(#115914),#115940); +#115914 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#115915,#115916,#115917, + #115918,#115919,#115920,#115921,#115922,#115923,#115924,#115925, + #115926,#115927,#115928,#115929,#115930,#115931,#115932,#115933, + #115934,#115935,#115936,#115937,#115938,#115939),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -139832,442 +142834,442 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#113523 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#113524 = CARTESIAN_POINT('',(3.166141578807,-6.35)); -#113525 = CARTESIAN_POINT('',(3.215239429242,-6.35)); -#113526 = CARTESIAN_POINT('',(3.288886204895,-6.35)); -#113527 = CARTESIAN_POINT('',(3.362532980548,-6.35)); -#113528 = CARTESIAN_POINT('',(3.4361797562,-6.35)); -#113529 = CARTESIAN_POINT('',(3.509826531853,-6.35)); -#113530 = CARTESIAN_POINT('',(3.583473307505,-6.35)); -#113531 = CARTESIAN_POINT('',(3.657120083158,-6.35)); -#113532 = CARTESIAN_POINT('',(3.730766858811,-6.35)); -#113533 = CARTESIAN_POINT('',(3.804413634463,-6.35)); -#113534 = CARTESIAN_POINT('',(3.878060410116,-6.35)); -#113535 = CARTESIAN_POINT('',(3.951707185768,-6.35)); -#113536 = CARTESIAN_POINT('',(4.025353961421,-6.35)); -#113537 = CARTESIAN_POINT('',(4.099000737074,-6.35)); -#113538 = CARTESIAN_POINT('',(4.172647512726,-6.35)); -#113539 = CARTESIAN_POINT('',(4.246294288379,-6.35)); -#113540 = CARTESIAN_POINT('',(4.319941064031,-6.35)); -#113541 = CARTESIAN_POINT('',(4.393587839684,-6.35)); -#113542 = CARTESIAN_POINT('',(4.467234615337,-6.35)); -#113543 = CARTESIAN_POINT('',(4.540881390989,-6.35)); -#113544 = CARTESIAN_POINT('',(4.614528166642,-6.35)); -#113545 = CARTESIAN_POINT('',(4.688174942294,-6.35)); -#113546 = CARTESIAN_POINT('',(4.737272792729,-6.35)); -#113547 = CARTESIAN_POINT('',(4.761821717947,-6.35)); -#113548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113549 = PCURVE('',#91381,#113550); -#113550 = DEFINITIONAL_REPRESENTATION('',(#113551),#113559); -#113551 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113552,#113553,#113554, - #113555,#113556,#113557,#113558),.UNSPECIFIED.,.T.,.F.) +#115915 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#115916 = CARTESIAN_POINT('',(3.166141578807,-6.35)); +#115917 = CARTESIAN_POINT('',(3.215239429242,-6.35)); +#115918 = CARTESIAN_POINT('',(3.288886204895,-6.35)); +#115919 = CARTESIAN_POINT('',(3.362532980548,-6.35)); +#115920 = CARTESIAN_POINT('',(3.4361797562,-6.35)); +#115921 = CARTESIAN_POINT('',(3.509826531853,-6.35)); +#115922 = CARTESIAN_POINT('',(3.583473307505,-6.35)); +#115923 = CARTESIAN_POINT('',(3.657120083158,-6.35)); +#115924 = CARTESIAN_POINT('',(3.730766858811,-6.35)); +#115925 = CARTESIAN_POINT('',(3.804413634463,-6.35)); +#115926 = CARTESIAN_POINT('',(3.878060410116,-6.35)); +#115927 = CARTESIAN_POINT('',(3.951707185768,-6.35)); +#115928 = CARTESIAN_POINT('',(4.025353961421,-6.35)); +#115929 = CARTESIAN_POINT('',(4.099000737074,-6.35)); +#115930 = CARTESIAN_POINT('',(4.172647512726,-6.35)); +#115931 = CARTESIAN_POINT('',(4.246294288379,-6.35)); +#115932 = CARTESIAN_POINT('',(4.319941064031,-6.35)); +#115933 = CARTESIAN_POINT('',(4.393587839684,-6.35)); +#115934 = CARTESIAN_POINT('',(4.467234615337,-6.35)); +#115935 = CARTESIAN_POINT('',(4.540881390989,-6.35)); +#115936 = CARTESIAN_POINT('',(4.614528166642,-6.35)); +#115937 = CARTESIAN_POINT('',(4.688174942294,-6.35)); +#115938 = CARTESIAN_POINT('',(4.737272792729,-6.35)); +#115939 = CARTESIAN_POINT('',(4.761821717947,-6.35)); +#115940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115941 = PCURVE('',#93773,#115942); +#115942 = DEFINITIONAL_REPRESENTATION('',(#115943),#115951); +#115943 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115944,#115945,#115946, + #115947,#115948,#115949,#115950),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#113552 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#113553 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#113554 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#113555 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#113556 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#113557 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#113558 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#113559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113560 = ORIENTED_EDGE('',*,*,#113356,.T.); -#113561 = ORIENTED_EDGE('',*,*,#113562,.F.); -#113562 = EDGE_CURVE('',#113563,#113334,#113565,.T.); -#113563 = VERTEX_POINT('',#113564); -#113564 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.E+000)); -#113565 = SURFACE_CURVE('',#113566,(#113571,#113577),.PCURVE_S1.); -#113566 = CIRCLE('',#113567,0.308574064194); -#113567 = AXIS2_PLACEMENT_3D('',#113568,#113569,#113570); -#113568 = CARTESIAN_POINT('',(-0.728168876214,3.85,2.640924866458E-017) - ); -#113569 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113570 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113571 = PCURVE('',#113372,#113572); -#113572 = DEFINITIONAL_REPRESENTATION('',(#113573),#113576); -#113573 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113574,#113575), +#115944 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#115945 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#115946 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#115947 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#115948 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#115949 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#115950 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#115951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115952 = ORIENTED_EDGE('',*,*,#115748,.T.); +#115953 = ORIENTED_EDGE('',*,*,#115954,.F.); +#115954 = EDGE_CURVE('',#115955,#115726,#115957,.T.); +#115955 = VERTEX_POINT('',#115956); +#115956 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.E+000)); +#115957 = SURFACE_CURVE('',#115958,(#115963,#115969),.PCURVE_S1.); +#115958 = CIRCLE('',#115959,0.308574064194); +#115959 = AXIS2_PLACEMENT_3D('',#115960,#115961,#115962); +#115960 = CARTESIAN_POINT('',(-0.728168876214,3.85,2.640924866458E-017) + ); +#115961 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115962 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#115963 = PCURVE('',#115764,#115964); +#115964 = DEFINITIONAL_REPRESENTATION('',(#115965),#115968); +#115965 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115966,#115967), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#113574 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#113575 = CARTESIAN_POINT('',(4.761821717947,-6.15)); -#113576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113577 = PCURVE('',#91437,#113578); -#113578 = DEFINITIONAL_REPRESENTATION('',(#113579),#113583); -#113579 = CIRCLE('',#113580,0.308574064194); -#113580 = AXIS2_PLACEMENT_2D('',#113581,#113582); -#113581 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#113582 = DIRECTION('',(0.E+000,-1.)); -#113583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113584 = ORIENTED_EDGE('',*,*,#113585,.T.); -#113585 = EDGE_CURVE('',#113563,#113512,#113586,.T.); -#113586 = SURFACE_CURVE('',#113587,(#113591,#113597),.PCURVE_S1.); -#113587 = LINE('',#113588,#113589); -#113588 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#113589 = VECTOR('',#113590,1.); -#113590 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113591 = PCURVE('',#113372,#113592); -#113592 = DEFINITIONAL_REPRESENTATION('',(#113593),#113596); -#113593 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113594,#113595), +#115966 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#115967 = CARTESIAN_POINT('',(4.761821717947,-6.15)); +#115968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115969 = PCURVE('',#93829,#115970); +#115970 = DEFINITIONAL_REPRESENTATION('',(#115971),#115975); +#115971 = CIRCLE('',#115972,0.308574064194); +#115972 = AXIS2_PLACEMENT_2D('',#115973,#115974); +#115973 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#115974 = DIRECTION('',(0.E+000,-1.)); +#115975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115976 = ORIENTED_EDGE('',*,*,#115977,.T.); +#115977 = EDGE_CURVE('',#115955,#115904,#115978,.T.); +#115978 = SURFACE_CURVE('',#115979,(#115983,#115989),.PCURVE_S1.); +#115979 = LINE('',#115980,#115981); +#115980 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#115981 = VECTOR('',#115982,1.); +#115982 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#115983 = PCURVE('',#115764,#115984); +#115984 = DEFINITIONAL_REPRESENTATION('',(#115985),#115988); +#115985 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115986,#115987), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#113594 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#113595 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#113596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113597 = PCURVE('',#113598,#113603); -#113598 = PLANE('',#113599); -#113599 = AXIS2_PLACEMENT_3D('',#113600,#113601,#113602); -#113600 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#113601 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#113602 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113603 = DEFINITIONAL_REPRESENTATION('',(#113604),#113608); -#113604 = LINE('',#113605,#113606); -#113605 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#113606 = VECTOR('',#113607,1.); -#113607 = DIRECTION('',(-1.,0.E+000)); -#113608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113609 = ADVANCED_FACE('',(#113610),#113476,.F.); -#113610 = FACE_BOUND('',#113611,.F.); -#113611 = EDGE_LOOP('',(#113612,#113635,#113662,#113687)); -#113612 = ORIENTED_EDGE('',*,*,#113613,.F.); -#113613 = EDGE_CURVE('',#113614,#113461,#113616,.T.); -#113614 = VERTEX_POINT('',#113615); -#113615 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.E+000)); -#113616 = SURFACE_CURVE('',#113617,(#113622,#113628),.PCURVE_S1.); -#113617 = CIRCLE('',#113618,0.208574704164); -#113618 = AXIS2_PLACEMENT_3D('',#113619,#113620,#113621); -#113619 = CARTESIAN_POINT('',(-0.728168876214,3.85,2.640924866458E-017) - ); -#113620 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113621 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113622 = PCURVE('',#113476,#113623); -#113623 = DEFINITIONAL_REPRESENTATION('',(#113624),#113627); -#113624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113625,#113626), +#115986 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#115987 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#115988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#115989 = PCURVE('',#115990,#115995); +#115990 = PLANE('',#115991); +#115991 = AXIS2_PLACEMENT_3D('',#115992,#115993,#115994); +#115992 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#115993 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#115994 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#115995 = DEFINITIONAL_REPRESENTATION('',(#115996),#116000); +#115996 = LINE('',#115997,#115998); +#115997 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#115998 = VECTOR('',#115999,1.); +#115999 = DIRECTION('',(-1.,0.E+000)); +#116000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116001 = ADVANCED_FACE('',(#116002),#115868,.F.); +#116002 = FACE_BOUND('',#116003,.F.); +#116003 = EDGE_LOOP('',(#116004,#116027,#116054,#116079)); +#116004 = ORIENTED_EDGE('',*,*,#116005,.F.); +#116005 = EDGE_CURVE('',#116006,#115853,#116008,.T.); +#116006 = VERTEX_POINT('',#116007); +#116007 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.E+000)); +#116008 = SURFACE_CURVE('',#116009,(#116014,#116020),.PCURVE_S1.); +#116009 = CIRCLE('',#116010,0.208574704164); +#116010 = AXIS2_PLACEMENT_3D('',#116011,#116012,#116013); +#116011 = CARTESIAN_POINT('',(-0.728168876214,3.85,2.640924866458E-017) + ); +#116012 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116013 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116014 = PCURVE('',#115868,#116015); +#116015 = DEFINITIONAL_REPRESENTATION('',(#116016),#116019); +#116016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116017,#116018), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#113625 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#113626 = CARTESIAN_POINT('',(4.772630242227,-6.15)); -#113627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113628 = PCURVE('',#91437,#113629); -#113629 = DEFINITIONAL_REPRESENTATION('',(#113630),#113634); -#113630 = CIRCLE('',#113631,0.208574704164); -#113631 = AXIS2_PLACEMENT_2D('',#113632,#113633); -#113632 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#113633 = DIRECTION('',(0.E+000,-1.)); -#113634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113635 = ORIENTED_EDGE('',*,*,#113636,.F.); -#113636 = EDGE_CURVE('',#113637,#113614,#113639,.T.); -#113637 = VERTEX_POINT('',#113638); -#113638 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.E+000)); -#113639 = SURFACE_CURVE('',#113640,(#113644,#113650),.PCURVE_S1.); -#113640 = LINE('',#113641,#113642); -#113641 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#113642 = VECTOR('',#113643,1.); -#113643 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113644 = PCURVE('',#113476,#113645); -#113645 = DEFINITIONAL_REPRESENTATION('',(#113646),#113649); -#113646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113647,#113648), +#116017 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#116018 = CARTESIAN_POINT('',(4.772630242227,-6.15)); +#116019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116020 = PCURVE('',#93829,#116021); +#116021 = DEFINITIONAL_REPRESENTATION('',(#116022),#116026); +#116022 = CIRCLE('',#116023,0.208574704164); +#116023 = AXIS2_PLACEMENT_2D('',#116024,#116025); +#116024 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#116025 = DIRECTION('',(0.E+000,-1.)); +#116026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116027 = ORIENTED_EDGE('',*,*,#116028,.F.); +#116028 = EDGE_CURVE('',#116029,#116006,#116031,.T.); +#116029 = VERTEX_POINT('',#116030); +#116030 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.E+000)); +#116031 = SURFACE_CURVE('',#116032,(#116036,#116042),.PCURVE_S1.); +#116032 = LINE('',#116033,#116034); +#116033 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#116034 = VECTOR('',#116035,1.); +#116035 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116036 = PCURVE('',#115868,#116037); +#116037 = DEFINITIONAL_REPRESENTATION('',(#116038),#116041); +#116038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116039,#116040), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#113647 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#113648 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#113649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113650 = PCURVE('',#113651,#113656); -#113651 = PLANE('',#113652); -#113652 = AXIS2_PLACEMENT_3D('',#113653,#113654,#113655); -#113653 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#113654 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#113655 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113656 = DEFINITIONAL_REPRESENTATION('',(#113657),#113661); -#113657 = LINE('',#113658,#113659); -#113658 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#113659 = VECTOR('',#113660,1.); -#113660 = DIRECTION('',(-1.,0.E+000)); -#113661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113662 = ORIENTED_EDGE('',*,*,#113663,.T.); -#113663 = EDGE_CURVE('',#113637,#113438,#113664,.T.); -#113664 = SURFACE_CURVE('',#113665,(#113670,#113676),.PCURVE_S1.); -#113665 = CIRCLE('',#113666,0.208574704164); -#113666 = AXIS2_PLACEMENT_3D('',#113667,#113668,#113669); -#113667 = CARTESIAN_POINT('',(-0.728168876214,3.65,2.640924866458E-017) - ); -#113668 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113669 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#113670 = PCURVE('',#113476,#113671); -#113671 = DEFINITIONAL_REPRESENTATION('',(#113672),#113675); -#113672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113673,#113674), +#116039 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#116040 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#116041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116042 = PCURVE('',#116043,#116048); +#116043 = PLANE('',#116044); +#116044 = AXIS2_PLACEMENT_3D('',#116045,#116046,#116047); +#116045 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#116046 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#116047 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116048 = DEFINITIONAL_REPRESENTATION('',(#116049),#116053); +#116049 = LINE('',#116050,#116051); +#116050 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#116051 = VECTOR('',#116052,1.); +#116052 = DIRECTION('',(-1.,0.E+000)); +#116053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116054 = ORIENTED_EDGE('',*,*,#116055,.T.); +#116055 = EDGE_CURVE('',#116029,#115830,#116056,.T.); +#116056 = SURFACE_CURVE('',#116057,(#116062,#116068),.PCURVE_S1.); +#116057 = CIRCLE('',#116058,0.208574704164); +#116058 = AXIS2_PLACEMENT_3D('',#116059,#116060,#116061); +#116059 = CARTESIAN_POINT('',(-0.728168876214,3.65,2.640924866458E-017) + ); +#116060 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116061 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116062 = PCURVE('',#115868,#116063); +#116063 = DEFINITIONAL_REPRESENTATION('',(#116064),#116067); +#116064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116065,#116066), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#113673 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#113674 = CARTESIAN_POINT('',(4.772630242227,-6.35)); -#113675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116065 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#116066 = CARTESIAN_POINT('',(4.772630242227,-6.35)); +#116067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113676 = PCURVE('',#91381,#113677); -#113677 = DEFINITIONAL_REPRESENTATION('',(#113678),#113686); -#113678 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113679,#113680,#113681, - #113682,#113683,#113684,#113685),.UNSPECIFIED.,.T.,.F.) +#116068 = PCURVE('',#93773,#116069); +#116069 = DEFINITIONAL_REPRESENTATION('',(#116070),#116078); +#116070 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116071,#116072,#116073, + #116074,#116075,#116076,#116077),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#113679 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#113680 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#113681 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#113682 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#113683 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#113684 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#113685 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#113686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113687 = ORIENTED_EDGE('',*,*,#113460,.F.); -#113688 = ADVANCED_FACE('',(#113689),#113651,.T.); -#113689 = FACE_BOUND('',#113690,.T.); -#113690 = EDGE_LOOP('',(#113691,#113720,#113741,#113742)); -#113691 = ORIENTED_EDGE('',*,*,#113692,.T.); -#113692 = EDGE_CURVE('',#113693,#113695,#113697,.T.); -#113693 = VERTEX_POINT('',#113694); -#113694 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.530776333563)); -#113695 = VERTEX_POINT('',#113696); -#113696 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.530776333563)); -#113697 = SURFACE_CURVE('',#113698,(#113702,#113709),.PCURVE_S1.); -#113698 = LINE('',#113699,#113700); -#113699 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#113700 = VECTOR('',#113701,1.); -#113701 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113702 = PCURVE('',#113651,#113703); -#113703 = DEFINITIONAL_REPRESENTATION('',(#113704),#113708); -#113704 = LINE('',#113705,#113706); -#113705 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113706 = VECTOR('',#113707,1.); -#113707 = DIRECTION('',(-1.,0.E+000)); -#113708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113709 = PCURVE('',#113710,#113715); -#113710 = CYLINDRICAL_SURFACE('',#113711,0.2192697516); -#113711 = AXIS2_PLACEMENT_3D('',#113712,#113713,#113714); -#113712 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#113713 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113714 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113715 = DEFINITIONAL_REPRESENTATION('',(#113716),#113719); -#113716 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113717,#113718), +#116071 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#116072 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#116073 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#116074 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#116075 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#116076 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#116077 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#116078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116079 = ORIENTED_EDGE('',*,*,#115852,.F.); +#116080 = ADVANCED_FACE('',(#116081),#116043,.T.); +#116081 = FACE_BOUND('',#116082,.T.); +#116082 = EDGE_LOOP('',(#116083,#116112,#116133,#116134)); +#116083 = ORIENTED_EDGE('',*,*,#116084,.T.); +#116084 = EDGE_CURVE('',#116085,#116087,#116089,.T.); +#116085 = VERTEX_POINT('',#116086); +#116086 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.530776333563)); +#116087 = VERTEX_POINT('',#116088); +#116088 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.530776333563)); +#116089 = SURFACE_CURVE('',#116090,(#116094,#116101),.PCURVE_S1.); +#116090 = LINE('',#116091,#116092); +#116091 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#116092 = VECTOR('',#116093,1.); +#116093 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116094 = PCURVE('',#116043,#116095); +#116095 = DEFINITIONAL_REPRESENTATION('',(#116096),#116100); +#116096 = LINE('',#116097,#116098); +#116097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116098 = VECTOR('',#116099,1.); +#116099 = DIRECTION('',(-1.,0.E+000)); +#116100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116101 = PCURVE('',#116102,#116107); +#116102 = CYLINDRICAL_SURFACE('',#116103,0.2192697516); +#116103 = AXIS2_PLACEMENT_3D('',#116104,#116105,#116106); +#116104 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#116105 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116106 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116107 = DEFINITIONAL_REPRESENTATION('',(#116108),#116111); +#116108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116109,#116110), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#113717 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#113718 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#113719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113720 = ORIENTED_EDGE('',*,*,#113721,.T.); -#113721 = EDGE_CURVE('',#113695,#113614,#113722,.T.); -#113722 = SURFACE_CURVE('',#113723,(#113727,#113734),.PCURVE_S1.); -#113723 = LINE('',#113724,#113725); -#113724 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.530776333563)); -#113725 = VECTOR('',#113726,1.); -#113726 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#113727 = PCURVE('',#113651,#113728); -#113728 = DEFINITIONAL_REPRESENTATION('',(#113729),#113733); -#113729 = LINE('',#113730,#113731); -#113730 = CARTESIAN_POINT('',(6.15,4.535643882845E-033)); -#113731 = VECTOR('',#113732,1.); -#113732 = DIRECTION('',(-4.535643882845E-032,-1.)); -#113733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113734 = PCURVE('',#91437,#113735); -#113735 = DEFINITIONAL_REPRESENTATION('',(#113736),#113740); -#113736 = LINE('',#113737,#113738); -#113737 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#113738 = VECTOR('',#113739,1.); -#113739 = DIRECTION('',(-1.,-1.021336205033E-016)); -#113740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113741 = ORIENTED_EDGE('',*,*,#113636,.F.); -#113742 = ORIENTED_EDGE('',*,*,#113743,.F.); -#113743 = EDGE_CURVE('',#113693,#113637,#113744,.T.); -#113744 = SURFACE_CURVE('',#113745,(#113749,#113756),.PCURVE_S1.); -#113745 = LINE('',#113746,#113747); -#113746 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.530776333563)); -#113747 = VECTOR('',#113748,1.); -#113748 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#113749 = PCURVE('',#113651,#113750); -#113750 = DEFINITIONAL_REPRESENTATION('',(#113751),#113755); -#113751 = LINE('',#113752,#113753); -#113752 = CARTESIAN_POINT('',(6.35,-4.535643882845E-033)); -#113753 = VECTOR('',#113754,1.); -#113754 = DIRECTION('',(-4.535643882845E-032,-1.)); -#113755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113756 = PCURVE('',#91381,#113757); -#113757 = DEFINITIONAL_REPRESENTATION('',(#113758),#113762); -#113758 = LINE('',#113759,#113760); -#113759 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#113760 = VECTOR('',#113761,1.); -#113761 = DIRECTION('',(1.,-1.021336205033E-016)); -#113762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113763 = ADVANCED_FACE('',(#113764),#113598,.T.); -#113764 = FACE_BOUND('',#113765,.T.); -#113765 = EDGE_LOOP('',(#113766,#113795,#113816,#113817)); -#113766 = ORIENTED_EDGE('',*,*,#113767,.T.); -#113767 = EDGE_CURVE('',#113768,#113770,#113772,.T.); -#113768 = VERTEX_POINT('',#113769); -#113769 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.530776333563)); -#113770 = VERTEX_POINT('',#113771); -#113771 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.530776333563)); -#113772 = SURFACE_CURVE('',#113773,(#113777,#113784),.PCURVE_S1.); -#113773 = LINE('',#113774,#113775); -#113774 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#113775 = VECTOR('',#113776,1.); -#113776 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113777 = PCURVE('',#113598,#113778); -#113778 = DEFINITIONAL_REPRESENTATION('',(#113779),#113783); -#113779 = LINE('',#113780,#113781); -#113780 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#113781 = VECTOR('',#113782,1.); -#113782 = DIRECTION('',(-1.,0.E+000)); -#113783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113784 = PCURVE('',#113785,#113790); -#113785 = CYLINDRICAL_SURFACE('',#113786,0.119270391569); -#113786 = AXIS2_PLACEMENT_3D('',#113787,#113788,#113789); -#113787 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#113788 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113789 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113790 = DEFINITIONAL_REPRESENTATION('',(#113791),#113794); -#113791 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113792,#113793), +#116109 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#116110 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#116111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116112 = ORIENTED_EDGE('',*,*,#116113,.T.); +#116113 = EDGE_CURVE('',#116087,#116006,#116114,.T.); +#116114 = SURFACE_CURVE('',#116115,(#116119,#116126),.PCURVE_S1.); +#116115 = LINE('',#116116,#116117); +#116116 = CARTESIAN_POINT('',(-0.51959417205,3.85,0.530776333563)); +#116117 = VECTOR('',#116118,1.); +#116118 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#116119 = PCURVE('',#116043,#116120); +#116120 = DEFINITIONAL_REPRESENTATION('',(#116121),#116125); +#116121 = LINE('',#116122,#116123); +#116122 = CARTESIAN_POINT('',(6.15,4.535643882845E-033)); +#116123 = VECTOR('',#116124,1.); +#116124 = DIRECTION('',(-4.535643882845E-032,-1.)); +#116125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116126 = PCURVE('',#93829,#116127); +#116127 = DEFINITIONAL_REPRESENTATION('',(#116128),#116132); +#116128 = LINE('',#116129,#116130); +#116129 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#116130 = VECTOR('',#116131,1.); +#116131 = DIRECTION('',(-1.,-1.021336205033E-016)); +#116132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116133 = ORIENTED_EDGE('',*,*,#116028,.F.); +#116134 = ORIENTED_EDGE('',*,*,#116135,.F.); +#116135 = EDGE_CURVE('',#116085,#116029,#116136,.T.); +#116136 = SURFACE_CURVE('',#116137,(#116141,#116148),.PCURVE_S1.); +#116137 = LINE('',#116138,#116139); +#116138 = CARTESIAN_POINT('',(-0.51959417205,3.65,0.530776333563)); +#116139 = VECTOR('',#116140,1.); +#116140 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#116141 = PCURVE('',#116043,#116142); +#116142 = DEFINITIONAL_REPRESENTATION('',(#116143),#116147); +#116143 = LINE('',#116144,#116145); +#116144 = CARTESIAN_POINT('',(6.35,-4.535643882845E-033)); +#116145 = VECTOR('',#116146,1.); +#116146 = DIRECTION('',(-4.535643882845E-032,-1.)); +#116147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116148 = PCURVE('',#93773,#116149); +#116149 = DEFINITIONAL_REPRESENTATION('',(#116150),#116154); +#116150 = LINE('',#116151,#116152); +#116151 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#116152 = VECTOR('',#116153,1.); +#116153 = DIRECTION('',(1.,-1.021336205033E-016)); +#116154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116155 = ADVANCED_FACE('',(#116156),#115990,.T.); +#116156 = FACE_BOUND('',#116157,.T.); +#116157 = EDGE_LOOP('',(#116158,#116187,#116208,#116209)); +#116158 = ORIENTED_EDGE('',*,*,#116159,.T.); +#116159 = EDGE_CURVE('',#116160,#116162,#116164,.T.); +#116160 = VERTEX_POINT('',#116161); +#116161 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.530776333563)); +#116162 = VERTEX_POINT('',#116163); +#116163 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.530776333563)); +#116164 = SURFACE_CURVE('',#116165,(#116169,#116176),.PCURVE_S1.); +#116165 = LINE('',#116166,#116167); +#116166 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#116167 = VECTOR('',#116168,1.); +#116168 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116169 = PCURVE('',#115990,#116170); +#116170 = DEFINITIONAL_REPRESENTATION('',(#116171),#116175); +#116171 = LINE('',#116172,#116173); +#116172 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116173 = VECTOR('',#116174,1.); +#116174 = DIRECTION('',(-1.,0.E+000)); +#116175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116176 = PCURVE('',#116177,#116182); +#116177 = CYLINDRICAL_SURFACE('',#116178,0.119270391569); +#116178 = AXIS2_PLACEMENT_3D('',#116179,#116180,#116181); +#116179 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#116180 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116181 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116182 = DEFINITIONAL_REPRESENTATION('',(#116183),#116186); +#116183 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116184,#116185), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#113792 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#113793 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#113794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113795 = ORIENTED_EDGE('',*,*,#113796,.T.); -#113796 = EDGE_CURVE('',#113770,#113512,#113797,.T.); -#113797 = SURFACE_CURVE('',#113798,(#113802,#113809),.PCURVE_S1.); -#113798 = LINE('',#113799,#113800); -#113799 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.530776333563)); -#113800 = VECTOR('',#113801,1.); -#113801 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#113802 = PCURVE('',#113598,#113803); -#113803 = DEFINITIONAL_REPRESENTATION('',(#113804),#113808); -#113804 = LINE('',#113805,#113806); -#113805 = CARTESIAN_POINT('',(-6.35,1.133910970711E-033)); -#113806 = VECTOR('',#113807,1.); -#113807 = DIRECTION('',(4.535643882845E-032,-1.)); -#113808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113809 = PCURVE('',#91381,#113810); -#113810 = DEFINITIONAL_REPRESENTATION('',(#113811),#113815); -#113811 = LINE('',#113812,#113813); -#113812 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#113813 = VECTOR('',#113814,1.); -#113814 = DIRECTION('',(1.,-1.021336205033E-016)); -#113815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116184 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#116185 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#116186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116187 = ORIENTED_EDGE('',*,*,#116188,.T.); +#116188 = EDGE_CURVE('',#116162,#115904,#116189,.T.); +#116189 = SURFACE_CURVE('',#116190,(#116194,#116201),.PCURVE_S1.); +#116190 = LINE('',#116191,#116192); +#116191 = CARTESIAN_POINT('',(-0.419594812019,3.65,0.530776333563)); +#116192 = VECTOR('',#116193,1.); +#116193 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#116194 = PCURVE('',#115990,#116195); +#116195 = DEFINITIONAL_REPRESENTATION('',(#116196),#116200); +#116196 = LINE('',#116197,#116198); +#116197 = CARTESIAN_POINT('',(-6.35,1.133910970711E-033)); +#116198 = VECTOR('',#116199,1.); +#116199 = DIRECTION('',(4.535643882845E-032,-1.)); +#116200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116201 = PCURVE('',#93773,#116202); +#116202 = DEFINITIONAL_REPRESENTATION('',(#116203),#116207); +#116203 = LINE('',#116204,#116205); +#116204 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#116205 = VECTOR('',#116206,1.); +#116206 = DIRECTION('',(1.,-1.021336205033E-016)); +#116207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116208 = ORIENTED_EDGE('',*,*,#115977,.F.); +#116209 = ORIENTED_EDGE('',*,*,#116210,.F.); +#116210 = EDGE_CURVE('',#116160,#115955,#116211,.T.); +#116211 = SURFACE_CURVE('',#116212,(#116216,#116223),.PCURVE_S1.); +#116212 = LINE('',#116213,#116214); +#116213 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.530776333563)); +#116214 = VECTOR('',#116215,1.); +#116215 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#116216 = PCURVE('',#115990,#116217); +#116217 = DEFINITIONAL_REPRESENTATION('',(#116218),#116222); +#116218 = LINE('',#116219,#116220); +#116219 = CARTESIAN_POINT('',(-6.15,-1.133910970711E-033)); +#116220 = VECTOR('',#116221,1.); +#116221 = DIRECTION('',(4.535643882845E-032,-1.)); +#116222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116223 = PCURVE('',#93829,#116224); +#116224 = DEFINITIONAL_REPRESENTATION('',(#116225),#116229); +#116225 = LINE('',#116226,#116227); +#116226 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#116227 = VECTOR('',#116228,1.); +#116228 = DIRECTION('',(-1.,-1.021336205033E-016)); +#116229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113816 = ORIENTED_EDGE('',*,*,#113585,.F.); -#113817 = ORIENTED_EDGE('',*,*,#113818,.F.); -#113818 = EDGE_CURVE('',#113768,#113563,#113819,.T.); -#113819 = SURFACE_CURVE('',#113820,(#113824,#113831),.PCURVE_S1.); -#113820 = LINE('',#113821,#113822); -#113821 = CARTESIAN_POINT('',(-0.419594812019,3.85,0.530776333563)); -#113822 = VECTOR('',#113823,1.); -#113823 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#113824 = PCURVE('',#113598,#113825); -#113825 = DEFINITIONAL_REPRESENTATION('',(#113826),#113830); -#113826 = LINE('',#113827,#113828); -#113827 = CARTESIAN_POINT('',(-6.15,-1.133910970711E-033)); -#113828 = VECTOR('',#113829,1.); -#113829 = DIRECTION('',(4.535643882845E-032,-1.)); -#113830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113831 = PCURVE('',#91437,#113832); -#113832 = DEFINITIONAL_REPRESENTATION('',(#113833),#113837); -#113833 = LINE('',#113834,#113835); -#113834 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#113835 = VECTOR('',#113836,1.); -#113836 = DIRECTION('',(-1.,-1.021336205033E-016)); -#113837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113838 = ADVANCED_FACE('',(#113839),#113785,.F.); -#113839 = FACE_BOUND('',#113840,.F.); -#113840 = EDGE_LOOP('',(#113841,#113842,#113865,#113910)); -#113841 = ORIENTED_EDGE('',*,*,#113767,.T.); -#113842 = ORIENTED_EDGE('',*,*,#113843,.F.); -#113843 = EDGE_CURVE('',#113844,#113770,#113846,.T.); -#113844 = VERTEX_POINT('',#113845); -#113845 = CARTESIAN_POINT('',(-0.303662633502,3.65,0.65)); -#113846 = SURFACE_CURVE('',#113847,(#113852,#113858),.PCURVE_S1.); -#113847 = CIRCLE('',#113848,0.119270391569); -#113848 = AXIS2_PLACEMENT_3D('',#113849,#113850,#113851); -#113849 = CARTESIAN_POINT('',(-0.30032442045,3.65,0.530776333563)); -#113850 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113851 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113852 = PCURVE('',#113785,#113853); -#113853 = DEFINITIONAL_REPRESENTATION('',(#113854),#113857); -#113854 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113855,#113856), +#116230 = ADVANCED_FACE('',(#116231),#116177,.F.); +#116231 = FACE_BOUND('',#116232,.F.); +#116232 = EDGE_LOOP('',(#116233,#116234,#116257,#116302)); +#116233 = ORIENTED_EDGE('',*,*,#116159,.T.); +#116234 = ORIENTED_EDGE('',*,*,#116235,.F.); +#116235 = EDGE_CURVE('',#116236,#116162,#116238,.T.); +#116236 = VERTEX_POINT('',#116237); +#116237 = CARTESIAN_POINT('',(-0.303662633502,3.65,0.65)); +#116238 = SURFACE_CURVE('',#116239,(#116244,#116250),.PCURVE_S1.); +#116239 = CIRCLE('',#116240,0.119270391569); +#116240 = AXIS2_PLACEMENT_3D('',#116241,#116242,#116243); +#116241 = CARTESIAN_POINT('',(-0.30032442045,3.65,0.530776333563)); +#116242 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116243 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116244 = PCURVE('',#116177,#116245); +#116245 = DEFINITIONAL_REPRESENTATION('',(#116246),#116249); +#116246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116247,#116248), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#113855 = CARTESIAN_POINT('',(1.598788597134,6.35)); -#113856 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#113857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113858 = PCURVE('',#91381,#113859); -#113859 = DEFINITIONAL_REPRESENTATION('',(#113860),#113864); -#113860 = CIRCLE('',#113861,0.119270391569); -#113861 = AXIS2_PLACEMENT_2D('',#113862,#113863); -#113862 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#113863 = DIRECTION('',(0.E+000,1.)); -#113864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113865 = ORIENTED_EDGE('',*,*,#113866,.T.); -#113866 = EDGE_CURVE('',#113844,#113867,#113869,.T.); -#113867 = VERTEX_POINT('',#113868); -#113868 = CARTESIAN_POINT('',(-0.303662633502,3.85,0.65)); -#113869 = SURFACE_CURVE('',#113870,(#113874,#113903),.PCURVE_S1.); -#113870 = LINE('',#113871,#113872); -#113871 = CARTESIAN_POINT('',(-0.303662633502,3.85,0.65)); -#113872 = VECTOR('',#113873,1.); -#113873 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#113874 = PCURVE('',#113785,#113875); -#113875 = DEFINITIONAL_REPRESENTATION('',(#113876),#113902); -#113876 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113877,#113878,#113879, - #113880,#113881,#113882,#113883,#113884,#113885,#113886,#113887, - #113888,#113889,#113890,#113891,#113892,#113893,#113894,#113895, - #113896,#113897,#113898,#113899,#113900,#113901),.UNSPECIFIED.,.F., +#116247 = CARTESIAN_POINT('',(1.598788597134,6.35)); +#116248 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#116249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116250 = PCURVE('',#93773,#116251); +#116251 = DEFINITIONAL_REPRESENTATION('',(#116252),#116256); +#116252 = CIRCLE('',#116253,0.119270391569); +#116253 = AXIS2_PLACEMENT_2D('',#116254,#116255); +#116254 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#116255 = DIRECTION('',(0.E+000,1.)); +#116256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116257 = ORIENTED_EDGE('',*,*,#116258,.T.); +#116258 = EDGE_CURVE('',#116236,#116259,#116261,.T.); +#116259 = VERTEX_POINT('',#116260); +#116260 = CARTESIAN_POINT('',(-0.303662633502,3.85,0.65)); +#116261 = SURFACE_CURVE('',#116262,(#116266,#116295),.PCURVE_S1.); +#116262 = LINE('',#116263,#116264); +#116263 = CARTESIAN_POINT('',(-0.303662633502,3.85,0.65)); +#116264 = VECTOR('',#116265,1.); +#116265 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116266 = PCURVE('',#116177,#116267); +#116267 = DEFINITIONAL_REPRESENTATION('',(#116268),#116294); +#116268 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#116269,#116270,#116271, + #116272,#116273,#116274,#116275,#116276,#116277,#116278,#116279, + #116280,#116281,#116282,#116283,#116284,#116285,#116286,#116287, + #116288,#116289,#116290,#116291,#116292,#116293),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -140276,100 +143278,100 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#113877 = CARTESIAN_POINT('',(1.598788597134,6.35)); -#113878 = CARTESIAN_POINT('',(1.598788597134,6.34696969697)); -#113879 = CARTESIAN_POINT('',(1.598788597134,6.340909090909)); -#113880 = CARTESIAN_POINT('',(1.598788597134,6.331818181818)); -#113881 = CARTESIAN_POINT('',(1.598788597134,6.322727272727)); -#113882 = CARTESIAN_POINT('',(1.598788597134,6.313636363636)); -#113883 = CARTESIAN_POINT('',(1.598788597134,6.304545454545)); -#113884 = CARTESIAN_POINT('',(1.598788597134,6.295454545455)); -#113885 = CARTESIAN_POINT('',(1.598788597134,6.286363636364)); -#113886 = CARTESIAN_POINT('',(1.598788597134,6.277272727273)); -#113887 = CARTESIAN_POINT('',(1.598788597134,6.268181818182)); -#113888 = CARTESIAN_POINT('',(1.598788597134,6.259090909091)); -#113889 = CARTESIAN_POINT('',(1.598788597134,6.25)); -#113890 = CARTESIAN_POINT('',(1.598788597134,6.240909090909)); -#113891 = CARTESIAN_POINT('',(1.598788597134,6.231818181818)); -#113892 = CARTESIAN_POINT('',(1.598788597134,6.222727272727)); -#113893 = CARTESIAN_POINT('',(1.598788597134,6.213636363636)); -#113894 = CARTESIAN_POINT('',(1.598788597134,6.204545454545)); -#113895 = CARTESIAN_POINT('',(1.598788597134,6.195454545455)); -#113896 = CARTESIAN_POINT('',(1.598788597134,6.186363636364)); -#113897 = CARTESIAN_POINT('',(1.598788597134,6.177272727273)); -#113898 = CARTESIAN_POINT('',(1.598788597134,6.168181818182)); -#113899 = CARTESIAN_POINT('',(1.598788597134,6.159090909091)); -#113900 = CARTESIAN_POINT('',(1.598788597134,6.15303030303)); -#113901 = CARTESIAN_POINT('',(1.598788597134,6.15)); -#113902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113903 = PCURVE('',#91409,#113904); -#113904 = DEFINITIONAL_REPRESENTATION('',(#113905),#113909); -#113905 = LINE('',#113906,#113907); -#113906 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#113907 = VECTOR('',#113908,1.); -#113908 = DIRECTION('',(4.440892098501E-016,1.)); -#113909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113910 = ORIENTED_EDGE('',*,*,#113911,.T.); -#113911 = EDGE_CURVE('',#113867,#113768,#113912,.T.); -#113912 = SURFACE_CURVE('',#113913,(#113918,#113924),.PCURVE_S1.); -#113913 = CIRCLE('',#113914,0.119270391569); -#113914 = AXIS2_PLACEMENT_3D('',#113915,#113916,#113917); -#113915 = CARTESIAN_POINT('',(-0.30032442045,3.85,0.530776333563)); -#113916 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113917 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113918 = PCURVE('',#113785,#113919); -#113919 = DEFINITIONAL_REPRESENTATION('',(#113920),#113923); -#113920 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#113921,#113922), +#116269 = CARTESIAN_POINT('',(1.598788597134,6.35)); +#116270 = CARTESIAN_POINT('',(1.598788597134,6.34696969697)); +#116271 = CARTESIAN_POINT('',(1.598788597134,6.340909090909)); +#116272 = CARTESIAN_POINT('',(1.598788597134,6.331818181818)); +#116273 = CARTESIAN_POINT('',(1.598788597134,6.322727272727)); +#116274 = CARTESIAN_POINT('',(1.598788597134,6.313636363636)); +#116275 = CARTESIAN_POINT('',(1.598788597134,6.304545454545)); +#116276 = CARTESIAN_POINT('',(1.598788597134,6.295454545455)); +#116277 = CARTESIAN_POINT('',(1.598788597134,6.286363636364)); +#116278 = CARTESIAN_POINT('',(1.598788597134,6.277272727273)); +#116279 = CARTESIAN_POINT('',(1.598788597134,6.268181818182)); +#116280 = CARTESIAN_POINT('',(1.598788597134,6.259090909091)); +#116281 = CARTESIAN_POINT('',(1.598788597134,6.25)); +#116282 = CARTESIAN_POINT('',(1.598788597134,6.240909090909)); +#116283 = CARTESIAN_POINT('',(1.598788597134,6.231818181818)); +#116284 = CARTESIAN_POINT('',(1.598788597134,6.222727272727)); +#116285 = CARTESIAN_POINT('',(1.598788597134,6.213636363636)); +#116286 = CARTESIAN_POINT('',(1.598788597134,6.204545454545)); +#116287 = CARTESIAN_POINT('',(1.598788597134,6.195454545455)); +#116288 = CARTESIAN_POINT('',(1.598788597134,6.186363636364)); +#116289 = CARTESIAN_POINT('',(1.598788597134,6.177272727273)); +#116290 = CARTESIAN_POINT('',(1.598788597134,6.168181818182)); +#116291 = CARTESIAN_POINT('',(1.598788597134,6.159090909091)); +#116292 = CARTESIAN_POINT('',(1.598788597134,6.15303030303)); +#116293 = CARTESIAN_POINT('',(1.598788597134,6.15)); +#116294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116295 = PCURVE('',#93801,#116296); +#116296 = DEFINITIONAL_REPRESENTATION('',(#116297),#116301); +#116297 = LINE('',#116298,#116299); +#116298 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#116299 = VECTOR('',#116300,1.); +#116300 = DIRECTION('',(4.440892098501E-016,1.)); +#116301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116302 = ORIENTED_EDGE('',*,*,#116303,.T.); +#116303 = EDGE_CURVE('',#116259,#116160,#116304,.T.); +#116304 = SURFACE_CURVE('',#116305,(#116310,#116316),.PCURVE_S1.); +#116305 = CIRCLE('',#116306,0.119270391569); +#116306 = AXIS2_PLACEMENT_3D('',#116307,#116308,#116309); +#116307 = CARTESIAN_POINT('',(-0.30032442045,3.85,0.530776333563)); +#116308 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116309 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116310 = PCURVE('',#116177,#116311); +#116311 = DEFINITIONAL_REPRESENTATION('',(#116312),#116315); +#116312 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116313,#116314), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#113921 = CARTESIAN_POINT('',(1.598788597134,6.15)); -#113922 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#113923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116313 = CARTESIAN_POINT('',(1.598788597134,6.15)); +#116314 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#116315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#113924 = PCURVE('',#91437,#113925); -#113925 = DEFINITIONAL_REPRESENTATION('',(#113926),#113934); -#113926 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#113927,#113928,#113929, - #113930,#113931,#113932,#113933),.UNSPECIFIED.,.T.,.F.) +#116316 = PCURVE('',#93829,#116317); +#116317 = DEFINITIONAL_REPRESENTATION('',(#116318),#116326); +#116318 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116319,#116320,#116321, + #116322,#116323,#116324,#116325),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#113927 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#113928 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#113929 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#113930 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#113931 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#113932 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#113933 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#113934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113935 = ADVANCED_FACE('',(#113936),#113710,.T.); -#113936 = FACE_BOUND('',#113937,.T.); -#113937 = EDGE_LOOP('',(#113938,#113939,#113985,#114030)); -#113938 = ORIENTED_EDGE('',*,*,#113692,.F.); -#113939 = ORIENTED_EDGE('',*,*,#113940,.F.); -#113940 = EDGE_CURVE('',#113941,#113693,#113943,.T.); -#113941 = VERTEX_POINT('',#113942); -#113942 = CARTESIAN_POINT('',(-0.304819755875,3.65,0.75)); -#113943 = SURFACE_CURVE('',#113944,(#113949,#113978),.PCURVE_S1.); -#113944 = CIRCLE('',#113945,0.2192697516); -#113945 = AXIS2_PLACEMENT_3D('',#113946,#113947,#113948); -#113946 = CARTESIAN_POINT('',(-0.30032442045,3.65,0.530776333563)); -#113947 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113948 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#113949 = PCURVE('',#113710,#113950); -#113950 = DEFINITIONAL_REPRESENTATION('',(#113951),#113977); -#113951 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113952,#113953,#113954, - #113955,#113956,#113957,#113958,#113959,#113960,#113961,#113962, - #113963,#113964,#113965,#113966,#113967,#113968,#113969,#113970, - #113971,#113972,#113973,#113974,#113975,#113976),.UNSPECIFIED.,.F., +#116319 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#116320 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#116321 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#116322 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#116323 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#116324 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#116325 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#116326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116327 = ADVANCED_FACE('',(#116328),#116102,.T.); +#116328 = FACE_BOUND('',#116329,.T.); +#116329 = EDGE_LOOP('',(#116330,#116331,#116377,#116422)); +#116330 = ORIENTED_EDGE('',*,*,#116084,.F.); +#116331 = ORIENTED_EDGE('',*,*,#116332,.F.); +#116332 = EDGE_CURVE('',#116333,#116085,#116335,.T.); +#116333 = VERTEX_POINT('',#116334); +#116334 = CARTESIAN_POINT('',(-0.304819755875,3.65,0.75)); +#116335 = SURFACE_CURVE('',#116336,(#116341,#116370),.PCURVE_S1.); +#116336 = CIRCLE('',#116337,0.2192697516); +#116337 = AXIS2_PLACEMENT_3D('',#116338,#116339,#116340); +#116338 = CARTESIAN_POINT('',(-0.30032442045,3.65,0.530776333563)); +#116339 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116340 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116341 = PCURVE('',#116102,#116342); +#116342 = DEFINITIONAL_REPRESENTATION('',(#116343),#116369); +#116343 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#116344,#116345,#116346, + #116347,#116348,#116349,#116350,#116351,#116352,#116353,#116354, + #116355,#116356,#116357,#116358,#116359,#116360,#116361,#116362, + #116363,#116364,#116365,#116366,#116367,#116368),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -140377,58 +143379,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#113952 = CARTESIAN_POINT('',(1.591299156552,6.35)); -#113953 = CARTESIAN_POINT('',(1.614788451962,6.35)); -#113954 = CARTESIAN_POINT('',(1.661767042781,6.35)); -#113955 = CARTESIAN_POINT('',(1.73223492901,6.35)); -#113956 = CARTESIAN_POINT('',(1.802702815239,6.35)); -#113957 = CARTESIAN_POINT('',(1.873170701468,6.35)); -#113958 = CARTESIAN_POINT('',(1.943638587697,6.35)); -#113959 = CARTESIAN_POINT('',(2.014106473926,6.35)); -#113960 = CARTESIAN_POINT('',(2.084574360155,6.35)); -#113961 = CARTESIAN_POINT('',(2.155042246384,6.35)); -#113962 = CARTESIAN_POINT('',(2.225510132613,6.35)); -#113963 = CARTESIAN_POINT('',(2.295978018842,6.35)); -#113964 = CARTESIAN_POINT('',(2.366445905071,6.35)); -#113965 = CARTESIAN_POINT('',(2.4369137913,6.35)); -#113966 = CARTESIAN_POINT('',(2.507381677529,6.35)); -#113967 = CARTESIAN_POINT('',(2.577849563758,6.35)); -#113968 = CARTESIAN_POINT('',(2.648317449987,6.35)); -#113969 = CARTESIAN_POINT('',(2.718785336216,6.35)); -#113970 = CARTESIAN_POINT('',(2.789253222445,6.35)); -#113971 = CARTESIAN_POINT('',(2.859721108674,6.35)); -#113972 = CARTESIAN_POINT('',(2.930188994903,6.35)); -#113973 = CARTESIAN_POINT('',(3.000656881132,6.35)); -#113974 = CARTESIAN_POINT('',(3.071124767361,6.35)); -#113975 = CARTESIAN_POINT('',(3.11810335818,6.35)); -#113976 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#113977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113978 = PCURVE('',#91381,#113979); -#113979 = DEFINITIONAL_REPRESENTATION('',(#113980),#113984); -#113980 = CIRCLE('',#113981,0.2192697516); -#113981 = AXIS2_PLACEMENT_2D('',#113982,#113983); -#113982 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#113983 = DIRECTION('',(0.E+000,1.)); -#113984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#113985 = ORIENTED_EDGE('',*,*,#113986,.F.); -#113986 = EDGE_CURVE('',#113987,#113941,#113989,.T.); -#113987 = VERTEX_POINT('',#113988); -#113988 = CARTESIAN_POINT('',(-0.304819755875,3.85,0.75)); -#113989 = SURFACE_CURVE('',#113990,(#113994,#114023),.PCURVE_S1.); -#113990 = LINE('',#113991,#113992); -#113991 = CARTESIAN_POINT('',(-0.304819755875,3.85,0.75)); -#113992 = VECTOR('',#113993,1.); -#113993 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#113994 = PCURVE('',#113710,#113995); -#113995 = DEFINITIONAL_REPRESENTATION('',(#113996),#114022); -#113996 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#113997,#113998,#113999, - #114000,#114001,#114002,#114003,#114004,#114005,#114006,#114007, - #114008,#114009,#114010,#114011,#114012,#114013,#114014,#114015, - #114016,#114017,#114018,#114019,#114020,#114021),.UNSPECIFIED.,.F., +#116344 = CARTESIAN_POINT('',(1.591299156552,6.35)); +#116345 = CARTESIAN_POINT('',(1.614788451962,6.35)); +#116346 = CARTESIAN_POINT('',(1.661767042781,6.35)); +#116347 = CARTESIAN_POINT('',(1.73223492901,6.35)); +#116348 = CARTESIAN_POINT('',(1.802702815239,6.35)); +#116349 = CARTESIAN_POINT('',(1.873170701468,6.35)); +#116350 = CARTESIAN_POINT('',(1.943638587697,6.35)); +#116351 = CARTESIAN_POINT('',(2.014106473926,6.35)); +#116352 = CARTESIAN_POINT('',(2.084574360155,6.35)); +#116353 = CARTESIAN_POINT('',(2.155042246384,6.35)); +#116354 = CARTESIAN_POINT('',(2.225510132613,6.35)); +#116355 = CARTESIAN_POINT('',(2.295978018842,6.35)); +#116356 = CARTESIAN_POINT('',(2.366445905071,6.35)); +#116357 = CARTESIAN_POINT('',(2.4369137913,6.35)); +#116358 = CARTESIAN_POINT('',(2.507381677529,6.35)); +#116359 = CARTESIAN_POINT('',(2.577849563758,6.35)); +#116360 = CARTESIAN_POINT('',(2.648317449987,6.35)); +#116361 = CARTESIAN_POINT('',(2.718785336216,6.35)); +#116362 = CARTESIAN_POINT('',(2.789253222445,6.35)); +#116363 = CARTESIAN_POINT('',(2.859721108674,6.35)); +#116364 = CARTESIAN_POINT('',(2.930188994903,6.35)); +#116365 = CARTESIAN_POINT('',(3.000656881132,6.35)); +#116366 = CARTESIAN_POINT('',(3.071124767361,6.35)); +#116367 = CARTESIAN_POINT('',(3.11810335818,6.35)); +#116368 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#116369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116370 = PCURVE('',#93773,#116371); +#116371 = DEFINITIONAL_REPRESENTATION('',(#116372),#116376); +#116372 = CIRCLE('',#116373,0.2192697516); +#116373 = AXIS2_PLACEMENT_2D('',#116374,#116375); +#116374 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#116375 = DIRECTION('',(0.E+000,1.)); +#116376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116377 = ORIENTED_EDGE('',*,*,#116378,.F.); +#116378 = EDGE_CURVE('',#116379,#116333,#116381,.T.); +#116379 = VERTEX_POINT('',#116380); +#116380 = CARTESIAN_POINT('',(-0.304819755875,3.85,0.75)); +#116381 = SURFACE_CURVE('',#116382,(#116386,#116415),.PCURVE_S1.); +#116382 = LINE('',#116383,#116384); +#116383 = CARTESIAN_POINT('',(-0.304819755875,3.85,0.75)); +#116384 = VECTOR('',#116385,1.); +#116385 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116386 = PCURVE('',#116102,#116387); +#116387 = DEFINITIONAL_REPRESENTATION('',(#116388),#116414); +#116388 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#116389,#116390,#116391, + #116392,#116393,#116394,#116395,#116396,#116397,#116398,#116399, + #116400,#116401,#116402,#116403,#116404,#116405,#116406,#116407, + #116408,#116409,#116410,#116411,#116412,#116413),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -140437,956 +143439,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#113997 = CARTESIAN_POINT('',(1.591299156552,6.15)); -#113998 = CARTESIAN_POINT('',(1.591299156552,6.15303030303)); -#113999 = CARTESIAN_POINT('',(1.591299156552,6.159090909091)); -#114000 = CARTESIAN_POINT('',(1.591299156552,6.168181818182)); -#114001 = CARTESIAN_POINT('',(1.591299156552,6.177272727273)); -#114002 = CARTESIAN_POINT('',(1.591299156552,6.186363636364)); -#114003 = CARTESIAN_POINT('',(1.591299156552,6.195454545455)); -#114004 = CARTESIAN_POINT('',(1.591299156552,6.204545454545)); -#114005 = CARTESIAN_POINT('',(1.591299156552,6.213636363636)); -#114006 = CARTESIAN_POINT('',(1.591299156552,6.222727272727)); -#114007 = CARTESIAN_POINT('',(1.591299156552,6.231818181818)); -#114008 = CARTESIAN_POINT('',(1.591299156552,6.240909090909)); -#114009 = CARTESIAN_POINT('',(1.591299156552,6.25)); -#114010 = CARTESIAN_POINT('',(1.591299156552,6.259090909091)); -#114011 = CARTESIAN_POINT('',(1.591299156552,6.268181818182)); -#114012 = CARTESIAN_POINT('',(1.591299156552,6.277272727273)); -#114013 = CARTESIAN_POINT('',(1.591299156552,6.286363636364)); -#114014 = CARTESIAN_POINT('',(1.591299156552,6.295454545455)); -#114015 = CARTESIAN_POINT('',(1.591299156552,6.304545454545)); -#114016 = CARTESIAN_POINT('',(1.591299156552,6.313636363636)); -#114017 = CARTESIAN_POINT('',(1.591299156552,6.322727272727)); -#114018 = CARTESIAN_POINT('',(1.591299156552,6.331818181818)); -#114019 = CARTESIAN_POINT('',(1.591299156552,6.340909090909)); -#114020 = CARTESIAN_POINT('',(1.591299156552,6.34696969697)); -#114021 = CARTESIAN_POINT('',(1.591299156552,6.35)); -#114022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114023 = PCURVE('',#91463,#114024); -#114024 = DEFINITIONAL_REPRESENTATION('',(#114025),#114029); -#114025 = LINE('',#114026,#114027); -#114026 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#114027 = VECTOR('',#114028,1.); -#114028 = DIRECTION('',(4.440892098501E-016,-1.)); -#114029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114030 = ORIENTED_EDGE('',*,*,#114031,.T.); -#114031 = EDGE_CURVE('',#113987,#113695,#114032,.T.); -#114032 = SURFACE_CURVE('',#114033,(#114038,#114044),.PCURVE_S1.); -#114033 = CIRCLE('',#114034,0.2192697516); -#114034 = AXIS2_PLACEMENT_3D('',#114035,#114036,#114037); -#114035 = CARTESIAN_POINT('',(-0.30032442045,3.85,0.530776333563)); -#114036 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114037 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114038 = PCURVE('',#113710,#114039); -#114039 = DEFINITIONAL_REPRESENTATION('',(#114040),#114043); -#114040 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114041,#114042), +#116389 = CARTESIAN_POINT('',(1.591299156552,6.15)); +#116390 = CARTESIAN_POINT('',(1.591299156552,6.15303030303)); +#116391 = CARTESIAN_POINT('',(1.591299156552,6.159090909091)); +#116392 = CARTESIAN_POINT('',(1.591299156552,6.168181818182)); +#116393 = CARTESIAN_POINT('',(1.591299156552,6.177272727273)); +#116394 = CARTESIAN_POINT('',(1.591299156552,6.186363636364)); +#116395 = CARTESIAN_POINT('',(1.591299156552,6.195454545455)); +#116396 = CARTESIAN_POINT('',(1.591299156552,6.204545454545)); +#116397 = CARTESIAN_POINT('',(1.591299156552,6.213636363636)); +#116398 = CARTESIAN_POINT('',(1.591299156552,6.222727272727)); +#116399 = CARTESIAN_POINT('',(1.591299156552,6.231818181818)); +#116400 = CARTESIAN_POINT('',(1.591299156552,6.240909090909)); +#116401 = CARTESIAN_POINT('',(1.591299156552,6.25)); +#116402 = CARTESIAN_POINT('',(1.591299156552,6.259090909091)); +#116403 = CARTESIAN_POINT('',(1.591299156552,6.268181818182)); +#116404 = CARTESIAN_POINT('',(1.591299156552,6.277272727273)); +#116405 = CARTESIAN_POINT('',(1.591299156552,6.286363636364)); +#116406 = CARTESIAN_POINT('',(1.591299156552,6.295454545455)); +#116407 = CARTESIAN_POINT('',(1.591299156552,6.304545454545)); +#116408 = CARTESIAN_POINT('',(1.591299156552,6.313636363636)); +#116409 = CARTESIAN_POINT('',(1.591299156552,6.322727272727)); +#116410 = CARTESIAN_POINT('',(1.591299156552,6.331818181818)); +#116411 = CARTESIAN_POINT('',(1.591299156552,6.340909090909)); +#116412 = CARTESIAN_POINT('',(1.591299156552,6.34696969697)); +#116413 = CARTESIAN_POINT('',(1.591299156552,6.35)); +#116414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116415 = PCURVE('',#93855,#116416); +#116416 = DEFINITIONAL_REPRESENTATION('',(#116417),#116421); +#116417 = LINE('',#116418,#116419); +#116418 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#116419 = VECTOR('',#116420,1.); +#116420 = DIRECTION('',(4.440892098501E-016,-1.)); +#116421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116422 = ORIENTED_EDGE('',*,*,#116423,.T.); +#116423 = EDGE_CURVE('',#116379,#116087,#116424,.T.); +#116424 = SURFACE_CURVE('',#116425,(#116430,#116436),.PCURVE_S1.); +#116425 = CIRCLE('',#116426,0.2192697516); +#116426 = AXIS2_PLACEMENT_3D('',#116427,#116428,#116429); +#116427 = CARTESIAN_POINT('',(-0.30032442045,3.85,0.530776333563)); +#116428 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116429 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#116430 = PCURVE('',#116102,#116431); +#116431 = DEFINITIONAL_REPRESENTATION('',(#116432),#116435); +#116432 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116433,#116434), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#114041 = CARTESIAN_POINT('',(1.591299156552,6.15)); -#114042 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#114043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116433 = CARTESIAN_POINT('',(1.591299156552,6.15)); +#116434 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#116435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114044 = PCURVE('',#91437,#114045); -#114045 = DEFINITIONAL_REPRESENTATION('',(#114046),#114054); -#114046 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114047,#114048,#114049, - #114050,#114051,#114052,#114053),.UNSPECIFIED.,.T.,.F.) +#116436 = PCURVE('',#93829,#116437); +#116437 = DEFINITIONAL_REPRESENTATION('',(#116438),#116446); +#116438 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116439,#116440,#116441, + #116442,#116443,#116444,#116445),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#114047 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#114048 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#114049 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#114050 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#114051 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#114052 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#114053 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#114054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114055 = ADVANCED_FACE('',(#114056),#91409,.T.); -#114056 = FACE_BOUND('',#114057,.T.); -#114057 = EDGE_LOOP('',(#114058,#114079,#114080,#114101)); -#114058 = ORIENTED_EDGE('',*,*,#114059,.F.); -#114059 = EDGE_CURVE('',#113844,#91366,#114060,.T.); -#114060 = SURFACE_CURVE('',#114061,(#114065,#114072),.PCURVE_S1.); -#114061 = LINE('',#114062,#114063); -#114062 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.65)); -#114063 = VECTOR('',#114064,1.); -#114064 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114065 = PCURVE('',#91409,#114066); -#114066 = DEFINITIONAL_REPRESENTATION('',(#114067),#114071); -#114067 = LINE('',#114068,#114069); -#114068 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#114069 = VECTOR('',#114070,1.); -#114070 = DIRECTION('',(-1.,-4.804757279354E-063)); -#114071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114072 = PCURVE('',#91381,#114073); -#114073 = DEFINITIONAL_REPRESENTATION('',(#114074),#114078); -#114074 = LINE('',#114075,#114076); -#114075 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114076 = VECTOR('',#114077,1.); -#114077 = DIRECTION('',(-3.563627120235E-016,1.)); -#114078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114079 = ORIENTED_EDGE('',*,*,#113866,.T.); -#114080 = ORIENTED_EDGE('',*,*,#114081,.T.); -#114081 = EDGE_CURVE('',#113867,#91394,#114082,.T.); -#114082 = SURFACE_CURVE('',#114083,(#114087,#114094),.PCURVE_S1.); -#114083 = LINE('',#114084,#114085); -#114084 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); -#114085 = VECTOR('',#114086,1.); -#114086 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114087 = PCURVE('',#91409,#114088); -#114088 = DEFINITIONAL_REPRESENTATION('',(#114089),#114093); -#114089 = LINE('',#114090,#114091); -#114090 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114091 = VECTOR('',#114092,1.); -#114092 = DIRECTION('',(-1.,-4.804757279354E-063)); -#114093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114094 = PCURVE('',#91437,#114095); -#114095 = DEFINITIONAL_REPRESENTATION('',(#114096),#114100); -#114096 = LINE('',#114097,#114098); -#114097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114098 = VECTOR('',#114099,1.); -#114099 = DIRECTION('',(3.563627120235E-016,1.)); -#114100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114101 = ORIENTED_EDGE('',*,*,#91393,.F.); -#114102 = ADVANCED_FACE('',(#114103),#91381,.T.); -#114103 = FACE_BOUND('',#114104,.T.); -#114104 = EDGE_LOOP('',(#114105,#114126,#114127,#114128,#114129,#114130, - #114151,#114152,#114153,#114154,#114155,#114156)); -#114105 = ORIENTED_EDGE('',*,*,#114106,.F.); -#114106 = EDGE_CURVE('',#113941,#91364,#114107,.T.); -#114107 = SURFACE_CURVE('',#114108,(#114112,#114119),.PCURVE_S1.); -#114108 = LINE('',#114109,#114110); -#114109 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.75)); -#114110 = VECTOR('',#114111,1.); -#114111 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114112 = PCURVE('',#91381,#114113); -#114113 = DEFINITIONAL_REPRESENTATION('',(#114114),#114118); -#114114 = LINE('',#114115,#114116); -#114115 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#114116 = VECTOR('',#114117,1.); -#114117 = DIRECTION('',(-3.563627120235E-016,1.)); -#114118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114119 = PCURVE('',#91463,#114120); -#114120 = DEFINITIONAL_REPRESENTATION('',(#114121),#114125); -#114121 = LINE('',#114122,#114123); -#114122 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#114123 = VECTOR('',#114124,1.); -#114124 = DIRECTION('',(1.,-4.804757279354E-063)); -#114125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114126 = ORIENTED_EDGE('',*,*,#113940,.T.); -#114127 = ORIENTED_EDGE('',*,*,#113743,.T.); -#114128 = ORIENTED_EDGE('',*,*,#113663,.T.); -#114129 = ORIENTED_EDGE('',*,*,#113437,.T.); -#114130 = ORIENTED_EDGE('',*,*,#114131,.F.); -#114131 = EDGE_CURVE('',#113301,#113408,#114132,.T.); -#114132 = SURFACE_CURVE('',#114133,(#114137,#114144),.PCURVE_S1.); -#114133 = LINE('',#114134,#114135); -#114134 = CARTESIAN_POINT('',(-1.,3.65,1.159810404338E-002)); -#114135 = VECTOR('',#114136,1.); -#114136 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#114137 = PCURVE('',#91381,#114138); -#114138 = DEFINITIONAL_REPRESENTATION('',(#114139),#114143); -#114139 = LINE('',#114140,#114141); -#114140 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#114141 = VECTOR('',#114142,1.); -#114142 = DIRECTION('',(-1.,-2.101748079665E-016)); -#114143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114144 = PCURVE('',#113321,#114145); -#114145 = DEFINITIONAL_REPRESENTATION('',(#114146),#114150); -#114146 = LINE('',#114147,#114148); -#114147 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#114148 = VECTOR('',#114149,1.); -#114149 = DIRECTION('',(-1.194699204908E-017,1.)); -#114150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116439 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#116440 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#116441 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#116442 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#116443 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#116444 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#116445 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#116446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116447 = ADVANCED_FACE('',(#116448),#93801,.T.); +#116448 = FACE_BOUND('',#116449,.T.); +#116449 = EDGE_LOOP('',(#116450,#116471,#116472,#116493)); +#116450 = ORIENTED_EDGE('',*,*,#116451,.F.); +#116451 = EDGE_CURVE('',#116236,#93758,#116452,.T.); +#116452 = SURFACE_CURVE('',#116453,(#116457,#116464),.PCURVE_S1.); +#116453 = LINE('',#116454,#116455); +#116454 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.65)); +#116455 = VECTOR('',#116456,1.); +#116456 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#116457 = PCURVE('',#93801,#116458); +#116458 = DEFINITIONAL_REPRESENTATION('',(#116459),#116463); +#116459 = LINE('',#116460,#116461); +#116460 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#116461 = VECTOR('',#116462,1.); +#116462 = DIRECTION('',(-1.,-4.804757279354E-063)); +#116463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116464 = PCURVE('',#93773,#116465); +#116465 = DEFINITIONAL_REPRESENTATION('',(#116466),#116470); +#116466 = LINE('',#116467,#116468); +#116467 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116468 = VECTOR('',#116469,1.); +#116469 = DIRECTION('',(-3.563627120235E-016,1.)); +#116470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116471 = ORIENTED_EDGE('',*,*,#116258,.T.); +#116472 = ORIENTED_EDGE('',*,*,#116473,.T.); +#116473 = EDGE_CURVE('',#116259,#93786,#116474,.T.); +#116474 = SURFACE_CURVE('',#116475,(#116479,#116486),.PCURVE_S1.); +#116475 = LINE('',#116476,#116477); +#116476 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.65)); +#116477 = VECTOR('',#116478,1.); +#116478 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#116479 = PCURVE('',#93801,#116480); +#116480 = DEFINITIONAL_REPRESENTATION('',(#116481),#116485); +#116481 = LINE('',#116482,#116483); +#116482 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116483 = VECTOR('',#116484,1.); +#116484 = DIRECTION('',(-1.,-4.804757279354E-063)); +#116485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116486 = PCURVE('',#93829,#116487); +#116487 = DEFINITIONAL_REPRESENTATION('',(#116488),#116492); +#116488 = LINE('',#116489,#116490); +#116489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116490 = VECTOR('',#116491,1.); +#116491 = DIRECTION('',(3.563627120235E-016,1.)); +#116492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116493 = ORIENTED_EDGE('',*,*,#93785,.F.); +#116494 = ADVANCED_FACE('',(#116495),#93773,.T.); +#116495 = FACE_BOUND('',#116496,.T.); +#116496 = EDGE_LOOP('',(#116497,#116518,#116519,#116520,#116521,#116522, + #116543,#116544,#116545,#116546,#116547,#116548)); +#116497 = ORIENTED_EDGE('',*,*,#116498,.F.); +#116498 = EDGE_CURVE('',#116333,#93756,#116499,.T.); +#116499 = SURFACE_CURVE('',#116500,(#116504,#116511),.PCURVE_S1.); +#116500 = LINE('',#116501,#116502); +#116501 = CARTESIAN_POINT('',(-0.527847992439,3.65,0.75)); +#116502 = VECTOR('',#116503,1.); +#116503 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#116504 = PCURVE('',#93773,#116505); +#116505 = DEFINITIONAL_REPRESENTATION('',(#116506),#116510); +#116506 = LINE('',#116507,#116508); +#116507 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#116508 = VECTOR('',#116509,1.); +#116509 = DIRECTION('',(-3.563627120235E-016,1.)); +#116510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116511 = PCURVE('',#93855,#116512); +#116512 = DEFINITIONAL_REPRESENTATION('',(#116513),#116517); +#116513 = LINE('',#116514,#116515); +#116514 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#116515 = VECTOR('',#116516,1.); +#116516 = DIRECTION('',(1.,-4.804757279354E-063)); +#116517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116518 = ORIENTED_EDGE('',*,*,#116332,.T.); +#116519 = ORIENTED_EDGE('',*,*,#116135,.T.); +#116520 = ORIENTED_EDGE('',*,*,#116055,.T.); +#116521 = ORIENTED_EDGE('',*,*,#115829,.T.); +#116522 = ORIENTED_EDGE('',*,*,#116523,.F.); +#116523 = EDGE_CURVE('',#115693,#115800,#116524,.T.); +#116524 = SURFACE_CURVE('',#116525,(#116529,#116536),.PCURVE_S1.); +#116525 = LINE('',#116526,#116527); +#116526 = CARTESIAN_POINT('',(-1.,3.65,1.159810404338E-002)); +#116527 = VECTOR('',#116528,1.); +#116528 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#116529 = PCURVE('',#93773,#116530); +#116530 = DEFINITIONAL_REPRESENTATION('',(#116531),#116535); +#116531 = LINE('',#116532,#116533); +#116532 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#116533 = VECTOR('',#116534,1.); +#116534 = DIRECTION('',(-1.,-2.101748079665E-016)); +#116535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116536 = PCURVE('',#115713,#116537); +#116537 = DEFINITIONAL_REPRESENTATION('',(#116538),#116542); +#116538 = LINE('',#116539,#116540); +#116539 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#116540 = VECTOR('',#116541,1.); +#116541 = DIRECTION('',(-1.194699204908E-017,1.)); +#116542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116543 = ORIENTED_EDGE('',*,*,#115775,.F.); +#116544 = ORIENTED_EDGE('',*,*,#115903,.F.); +#116545 = ORIENTED_EDGE('',*,*,#116188,.F.); +#116546 = ORIENTED_EDGE('',*,*,#116235,.F.); +#116547 = ORIENTED_EDGE('',*,*,#116451,.T.); +#116548 = ORIENTED_EDGE('',*,*,#93755,.F.); +#116549 = ADVANCED_FACE('',(#116550),#93855,.T.); +#116550 = FACE_BOUND('',#116551,.T.); +#116551 = EDGE_LOOP('',(#116552,#116573,#116574,#116575)); +#116552 = ORIENTED_EDGE('',*,*,#116553,.F.); +#116553 = EDGE_CURVE('',#116379,#93814,#116554,.T.); +#116554 = SURFACE_CURVE('',#116555,(#116559,#116566),.PCURVE_S1.); +#116555 = LINE('',#116556,#116557); +#116556 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.75)); +#116557 = VECTOR('',#116558,1.); +#116558 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#116559 = PCURVE('',#93855,#116560); +#116560 = DEFINITIONAL_REPRESENTATION('',(#116561),#116565); +#116561 = LINE('',#116562,#116563); +#116562 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116563 = VECTOR('',#116564,1.); +#116564 = DIRECTION('',(1.,-4.804757279354E-063)); +#116565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116566 = PCURVE('',#93829,#116567); +#116567 = DEFINITIONAL_REPRESENTATION('',(#116568),#116572); +#116568 = LINE('',#116569,#116570); +#116569 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#116570 = VECTOR('',#116571,1.); +#116571 = DIRECTION('',(3.563627120235E-016,1.)); +#116572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116573 = ORIENTED_EDGE('',*,*,#116378,.T.); +#116574 = ORIENTED_EDGE('',*,*,#116498,.T.); +#116575 = ORIENTED_EDGE('',*,*,#93841,.F.); +#116576 = ADVANCED_FACE('',(#116577),#93829,.T.); +#116577 = FACE_BOUND('',#116578,.T.); +#116578 = EDGE_LOOP('',(#116579,#116580,#116581,#116582,#116583,#116584, + #116605,#116606,#116607,#116608,#116609,#116610)); +#116579 = ORIENTED_EDGE('',*,*,#116473,.F.); +#116580 = ORIENTED_EDGE('',*,*,#116303,.T.); +#116581 = ORIENTED_EDGE('',*,*,#116210,.T.); +#116582 = ORIENTED_EDGE('',*,*,#115954,.T.); +#116583 = ORIENTED_EDGE('',*,*,#115725,.T.); +#116584 = ORIENTED_EDGE('',*,*,#116585,.F.); +#116585 = EDGE_CURVE('',#115802,#115691,#116586,.T.); +#116586 = SURFACE_CURVE('',#116587,(#116591,#116598),.PCURVE_S1.); +#116587 = LINE('',#116588,#116589); +#116588 = CARTESIAN_POINT('',(-1.,3.85,1.159810404338E-002)); +#116589 = VECTOR('',#116590,1.); +#116590 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#116591 = PCURVE('',#93829,#116592); +#116592 = DEFINITIONAL_REPRESENTATION('',(#116593),#116597); +#116593 = LINE('',#116594,#116595); +#116594 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#116595 = VECTOR('',#116596,1.); +#116596 = DIRECTION('',(-1.,2.101748079665E-016)); +#116597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116598 = PCURVE('',#115713,#116599); +#116599 = DEFINITIONAL_REPRESENTATION('',(#116600),#116604); +#116600 = LINE('',#116601,#116602); +#116601 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#116602 = VECTOR('',#116603,1.); +#116603 = DIRECTION('',(1.194699204908E-017,-1.)); +#116604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114151 = ORIENTED_EDGE('',*,*,#113383,.F.); -#114152 = ORIENTED_EDGE('',*,*,#113511,.F.); -#114153 = ORIENTED_EDGE('',*,*,#113796,.F.); -#114154 = ORIENTED_EDGE('',*,*,#113843,.F.); -#114155 = ORIENTED_EDGE('',*,*,#114059,.T.); -#114156 = ORIENTED_EDGE('',*,*,#91363,.F.); -#114157 = ADVANCED_FACE('',(#114158),#91463,.T.); -#114158 = FACE_BOUND('',#114159,.T.); -#114159 = EDGE_LOOP('',(#114160,#114181,#114182,#114183)); -#114160 = ORIENTED_EDGE('',*,*,#114161,.F.); -#114161 = EDGE_CURVE('',#113987,#91422,#114162,.T.); -#114162 = SURFACE_CURVE('',#114163,(#114167,#114174),.PCURVE_S1.); -#114163 = LINE('',#114164,#114165); -#114164 = CARTESIAN_POINT('',(-0.527847992439,3.85,0.75)); -#114165 = VECTOR('',#114166,1.); -#114166 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114167 = PCURVE('',#91463,#114168); -#114168 = DEFINITIONAL_REPRESENTATION('',(#114169),#114173); -#114169 = LINE('',#114170,#114171); -#114170 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114171 = VECTOR('',#114172,1.); -#114172 = DIRECTION('',(1.,-4.804757279354E-063)); -#114173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114174 = PCURVE('',#91437,#114175); -#114175 = DEFINITIONAL_REPRESENTATION('',(#114176),#114180); -#114176 = LINE('',#114177,#114178); -#114177 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#114178 = VECTOR('',#114179,1.); -#114179 = DIRECTION('',(3.563627120235E-016,1.)); -#114180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114181 = ORIENTED_EDGE('',*,*,#113986,.T.); -#114182 = ORIENTED_EDGE('',*,*,#114106,.T.); -#114183 = ORIENTED_EDGE('',*,*,#91449,.F.); -#114184 = ADVANCED_FACE('',(#114185),#91437,.T.); -#114185 = FACE_BOUND('',#114186,.T.); -#114186 = EDGE_LOOP('',(#114187,#114188,#114189,#114190,#114191,#114192, - #114213,#114214,#114215,#114216,#114217,#114218)); -#114187 = ORIENTED_EDGE('',*,*,#114081,.F.); -#114188 = ORIENTED_EDGE('',*,*,#113911,.T.); -#114189 = ORIENTED_EDGE('',*,*,#113818,.T.); -#114190 = ORIENTED_EDGE('',*,*,#113562,.T.); -#114191 = ORIENTED_EDGE('',*,*,#113333,.T.); -#114192 = ORIENTED_EDGE('',*,*,#114193,.F.); -#114193 = EDGE_CURVE('',#113410,#113299,#114194,.T.); -#114194 = SURFACE_CURVE('',#114195,(#114199,#114206),.PCURVE_S1.); -#114195 = LINE('',#114196,#114197); -#114196 = CARTESIAN_POINT('',(-1.,3.85,1.159810404338E-002)); -#114197 = VECTOR('',#114198,1.); -#114198 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#114199 = PCURVE('',#91437,#114200); -#114200 = DEFINITIONAL_REPRESENTATION('',(#114201),#114205); -#114201 = LINE('',#114202,#114203); -#114202 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#114203 = VECTOR('',#114204,1.); -#114204 = DIRECTION('',(-1.,2.101748079665E-016)); -#114205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114206 = PCURVE('',#113321,#114207); -#114207 = DEFINITIONAL_REPRESENTATION('',(#114208),#114212); -#114208 = LINE('',#114209,#114210); -#114209 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#114210 = VECTOR('',#114211,1.); -#114211 = DIRECTION('',(1.194699204908E-017,-1.)); -#114212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114213 = ORIENTED_EDGE('',*,*,#113487,.F.); -#114214 = ORIENTED_EDGE('',*,*,#113613,.F.); -#114215 = ORIENTED_EDGE('',*,*,#113721,.F.); -#114216 = ORIENTED_EDGE('',*,*,#114031,.F.); -#114217 = ORIENTED_EDGE('',*,*,#114161,.T.); -#114218 = ORIENTED_EDGE('',*,*,#91421,.F.); -#114219 = ADVANCED_FACE('',(#114220),#113321,.T.); -#114220 = FACE_BOUND('',#114221,.T.); -#114221 = EDGE_LOOP('',(#114222,#114223,#114224,#114225)); -#114222 = ORIENTED_EDGE('',*,*,#114131,.T.); -#114223 = ORIENTED_EDGE('',*,*,#113407,.T.); -#114224 = ORIENTED_EDGE('',*,*,#114193,.T.); -#114225 = ORIENTED_EDGE('',*,*,#113298,.T.); -#114226 = ADVANCED_FACE('',(#114227),#114241,.F.); -#114227 = FACE_BOUND('',#114228,.T.); -#114228 = EDGE_LOOP('',(#114229,#114264,#114287,#114314)); -#114229 = ORIENTED_EDGE('',*,*,#114230,.F.); -#114230 = EDGE_CURVE('',#114231,#114233,#114235,.T.); -#114231 = VERTEX_POINT('',#114232); -#114232 = CARTESIAN_POINT('',(-1.,4.35,-0.308197125857)); -#114233 = VERTEX_POINT('',#114234); -#114234 = CARTESIAN_POINT('',(-1.,4.15,-0.308197125857)); -#114235 = SURFACE_CURVE('',#114236,(#114240,#114252),.PCURVE_S1.); -#114236 = LINE('',#114237,#114238); -#114237 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#114238 = VECTOR('',#114239,1.); -#114239 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114240 = PCURVE('',#114241,#114246); -#114241 = PLANE('',#114242); -#114242 = AXIS2_PLACEMENT_3D('',#114243,#114244,#114245); -#114243 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#114244 = DIRECTION('',(0.E+000,0.E+000,1.)); -#114245 = DIRECTION('',(1.,0.E+000,0.E+000)); -#114246 = DEFINITIONAL_REPRESENTATION('',(#114247),#114251); -#114247 = LINE('',#114248,#114249); -#114248 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#114249 = VECTOR('',#114250,1.); -#114250 = DIRECTION('',(4.440892098501E-016,-1.)); -#114251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114252 = PCURVE('',#114253,#114258); -#114253 = PLANE('',#114254); -#114254 = AXIS2_PLACEMENT_3D('',#114255,#114256,#114257); -#114255 = CARTESIAN_POINT('',(-1.,4.25,-0.258196742327)); -#114256 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#114257 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114258 = DEFINITIONAL_REPRESENTATION('',(#114259),#114263); -#114259 = LINE('',#114260,#114261); -#114260 = CARTESIAN_POINT('',(-5.75,-5.000038352949E-002)); -#114261 = VECTOR('',#114262,1.); -#114262 = DIRECTION('',(1.,0.E+000)); -#114263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114264 = ORIENTED_EDGE('',*,*,#114265,.F.); -#114265 = EDGE_CURVE('',#114266,#114231,#114268,.T.); -#114266 = VERTEX_POINT('',#114267); -#114267 = CARTESIAN_POINT('',(-0.74341632541,4.35,-0.308197125857)); -#114268 = SURFACE_CURVE('',#114269,(#114273,#114280),.PCURVE_S1.); -#114269 = LINE('',#114270,#114271); -#114270 = CARTESIAN_POINT('',(-0.74341632541,4.35,-0.308197125857)); -#114271 = VECTOR('',#114272,1.); -#114272 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#114273 = PCURVE('',#114241,#114274); -#114274 = DEFINITIONAL_REPRESENTATION('',(#114275),#114279); -#114275 = LINE('',#114276,#114277); -#114276 = CARTESIAN_POINT('',(2.553512956638E-015,-5.65)); -#114277 = VECTOR('',#114278,1.); -#114278 = DIRECTION('',(-1.,0.E+000)); -#114279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114280 = PCURVE('',#91323,#114281); -#114281 = DEFINITIONAL_REPRESENTATION('',(#114282),#114286); -#114282 = LINE('',#114283,#114284); -#114283 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#114284 = VECTOR('',#114285,1.); -#114285 = DIRECTION('',(0.E+000,-1.)); -#114286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114287 = ORIENTED_EDGE('',*,*,#114288,.F.); -#114288 = EDGE_CURVE('',#114289,#114266,#114291,.T.); -#114289 = VERTEX_POINT('',#114290); -#114290 = CARTESIAN_POINT('',(-0.74341632541,4.15,-0.308197125857)); -#114291 = SURFACE_CURVE('',#114292,(#114296,#114303),.PCURVE_S1.); -#114292 = LINE('',#114293,#114294); -#114293 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#114294 = VECTOR('',#114295,1.); -#114295 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114296 = PCURVE('',#114241,#114297); -#114297 = DEFINITIONAL_REPRESENTATION('',(#114298),#114302); -#114298 = LINE('',#114299,#114300); -#114299 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114300 = VECTOR('',#114301,1.); -#114301 = DIRECTION('',(-4.440892098501E-016,1.)); -#114302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114303 = PCURVE('',#114304,#114309); -#114304 = CYLINDRICAL_SURFACE('',#114305,0.308574064194); -#114305 = AXIS2_PLACEMENT_3D('',#114306,#114307,#114308); -#114306 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#114307 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114308 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114309 = DEFINITIONAL_REPRESENTATION('',(#114310),#114313); -#114310 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114311,#114312), +#116605 = ORIENTED_EDGE('',*,*,#115879,.F.); +#116606 = ORIENTED_EDGE('',*,*,#116005,.F.); +#116607 = ORIENTED_EDGE('',*,*,#116113,.F.); +#116608 = ORIENTED_EDGE('',*,*,#116423,.F.); +#116609 = ORIENTED_EDGE('',*,*,#116553,.T.); +#116610 = ORIENTED_EDGE('',*,*,#93813,.F.); +#116611 = ADVANCED_FACE('',(#116612),#115713,.T.); +#116612 = FACE_BOUND('',#116613,.T.); +#116613 = EDGE_LOOP('',(#116614,#116615,#116616,#116617)); +#116614 = ORIENTED_EDGE('',*,*,#116523,.T.); +#116615 = ORIENTED_EDGE('',*,*,#115799,.T.); +#116616 = ORIENTED_EDGE('',*,*,#116585,.T.); +#116617 = ORIENTED_EDGE('',*,*,#115690,.T.); +#116618 = ADVANCED_FACE('',(#116619),#116633,.F.); +#116619 = FACE_BOUND('',#116620,.T.); +#116620 = EDGE_LOOP('',(#116621,#116656,#116679,#116706)); +#116621 = ORIENTED_EDGE('',*,*,#116622,.F.); +#116622 = EDGE_CURVE('',#116623,#116625,#116627,.T.); +#116623 = VERTEX_POINT('',#116624); +#116624 = CARTESIAN_POINT('',(-1.,4.35,-0.308197125857)); +#116625 = VERTEX_POINT('',#116626); +#116626 = CARTESIAN_POINT('',(-1.,4.15,-0.308197125857)); +#116627 = SURFACE_CURVE('',#116628,(#116632,#116644),.PCURVE_S1.); +#116628 = LINE('',#116629,#116630); +#116629 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#116630 = VECTOR('',#116631,1.); +#116631 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116632 = PCURVE('',#116633,#116638); +#116633 = PLANE('',#116634); +#116634 = AXIS2_PLACEMENT_3D('',#116635,#116636,#116637); +#116635 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#116636 = DIRECTION('',(0.E+000,0.E+000,1.)); +#116637 = DIRECTION('',(1.,0.E+000,0.E+000)); +#116638 = DEFINITIONAL_REPRESENTATION('',(#116639),#116643); +#116639 = LINE('',#116640,#116641); +#116640 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#116641 = VECTOR('',#116642,1.); +#116642 = DIRECTION('',(4.440892098501E-016,-1.)); +#116643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116644 = PCURVE('',#116645,#116650); +#116645 = PLANE('',#116646); +#116646 = AXIS2_PLACEMENT_3D('',#116647,#116648,#116649); +#116647 = CARTESIAN_POINT('',(-1.,4.25,-0.258196742327)); +#116648 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#116649 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116650 = DEFINITIONAL_REPRESENTATION('',(#116651),#116655); +#116651 = LINE('',#116652,#116653); +#116652 = CARTESIAN_POINT('',(-5.75,-5.000038352949E-002)); +#116653 = VECTOR('',#116654,1.); +#116654 = DIRECTION('',(1.,0.E+000)); +#116655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116656 = ORIENTED_EDGE('',*,*,#116657,.F.); +#116657 = EDGE_CURVE('',#116658,#116623,#116660,.T.); +#116658 = VERTEX_POINT('',#116659); +#116659 = CARTESIAN_POINT('',(-0.74341632541,4.35,-0.308197125857)); +#116660 = SURFACE_CURVE('',#116661,(#116665,#116672),.PCURVE_S1.); +#116661 = LINE('',#116662,#116663); +#116662 = CARTESIAN_POINT('',(-0.74341632541,4.35,-0.308197125857)); +#116663 = VECTOR('',#116664,1.); +#116664 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#116665 = PCURVE('',#116633,#116666); +#116666 = DEFINITIONAL_REPRESENTATION('',(#116667),#116671); +#116667 = LINE('',#116668,#116669); +#116668 = CARTESIAN_POINT('',(2.553512956638E-015,-5.65)); +#116669 = VECTOR('',#116670,1.); +#116670 = DIRECTION('',(-1.,0.E+000)); +#116671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116672 = PCURVE('',#93715,#116673); +#116673 = DEFINITIONAL_REPRESENTATION('',(#116674),#116678); +#116674 = LINE('',#116675,#116676); +#116675 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#116676 = VECTOR('',#116677,1.); +#116677 = DIRECTION('',(0.E+000,-1.)); +#116678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116679 = ORIENTED_EDGE('',*,*,#116680,.F.); +#116680 = EDGE_CURVE('',#116681,#116658,#116683,.T.); +#116681 = VERTEX_POINT('',#116682); +#116682 = CARTESIAN_POINT('',(-0.74341632541,4.15,-0.308197125857)); +#116683 = SURFACE_CURVE('',#116684,(#116688,#116695),.PCURVE_S1.); +#116684 = LINE('',#116685,#116686); +#116685 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#116686 = VECTOR('',#116687,1.); +#116687 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116688 = PCURVE('',#116633,#116689); +#116689 = DEFINITIONAL_REPRESENTATION('',(#116690),#116694); +#116690 = LINE('',#116691,#116692); +#116691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116692 = VECTOR('',#116693,1.); +#116693 = DIRECTION('',(-4.440892098501E-016,1.)); +#116694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116695 = PCURVE('',#116696,#116701); +#116696 = CYLINDRICAL_SURFACE('',#116697,0.308574064194); +#116697 = AXIS2_PLACEMENT_3D('',#116698,#116699,#116700); +#116698 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#116699 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116700 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116701 = DEFINITIONAL_REPRESENTATION('',(#116702),#116705); +#116702 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116703,#116704), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#114311 = CARTESIAN_POINT('',(4.761821717947,-5.85)); -#114312 = CARTESIAN_POINT('',(4.761821717947,-5.65)); -#114313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114314 = ORIENTED_EDGE('',*,*,#114315,.T.); -#114315 = EDGE_CURVE('',#114289,#114233,#114316,.T.); -#114316 = SURFACE_CURVE('',#114317,(#114321,#114328),.PCURVE_S1.); -#114317 = LINE('',#114318,#114319); -#114318 = CARTESIAN_POINT('',(-0.74341632541,4.15,-0.308197125857)); -#114319 = VECTOR('',#114320,1.); -#114320 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#114321 = PCURVE('',#114241,#114322); -#114322 = DEFINITIONAL_REPRESENTATION('',(#114323),#114327); -#114323 = LINE('',#114324,#114325); -#114324 = CARTESIAN_POINT('',(2.775557561563E-015,-5.85)); -#114325 = VECTOR('',#114326,1.); -#114326 = DIRECTION('',(-1.,0.E+000)); -#114327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114328 = PCURVE('',#91267,#114329); -#114329 = DEFINITIONAL_REPRESENTATION('',(#114330),#114334); -#114330 = LINE('',#114331,#114332); -#114331 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#114332 = VECTOR('',#114333,1.); -#114333 = DIRECTION('',(0.E+000,-1.)); -#114334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114335 = ADVANCED_FACE('',(#114336),#114350,.F.); -#114336 = FACE_BOUND('',#114337,.T.); -#114337 = EDGE_LOOP('',(#114338,#114368,#114391,#114418)); -#114338 = ORIENTED_EDGE('',*,*,#114339,.F.); -#114339 = EDGE_CURVE('',#114340,#114342,#114344,.T.); -#114340 = VERTEX_POINT('',#114341); -#114341 = CARTESIAN_POINT('',(-1.,4.15,-0.208196358798)); -#114342 = VERTEX_POINT('',#114343); -#114343 = CARTESIAN_POINT('',(-1.,4.35,-0.208196358798)); -#114344 = SURFACE_CURVE('',#114345,(#114349,#114361),.PCURVE_S1.); -#114345 = LINE('',#114346,#114347); -#114346 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#114347 = VECTOR('',#114348,1.); -#114348 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114349 = PCURVE('',#114350,#114355); -#114350 = PLANE('',#114351); -#114351 = AXIS2_PLACEMENT_3D('',#114352,#114353,#114354); -#114352 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#114353 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#114354 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#114355 = DEFINITIONAL_REPRESENTATION('',(#114356),#114360); -#114356 = LINE('',#114357,#114358); -#114357 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#114358 = VECTOR('',#114359,1.); -#114359 = DIRECTION('',(4.440892098501E-016,1.)); -#114360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114361 = PCURVE('',#114253,#114362); -#114362 = DEFINITIONAL_REPRESENTATION('',(#114363),#114367); -#114363 = LINE('',#114364,#114365); -#114364 = CARTESIAN_POINT('',(-5.75,5.000038352949E-002)); -#114365 = VECTOR('',#114366,1.); -#114366 = DIRECTION('',(-1.,0.E+000)); -#114367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114368 = ORIENTED_EDGE('',*,*,#114369,.F.); -#114369 = EDGE_CURVE('',#114370,#114340,#114372,.T.); -#114370 = VERTEX_POINT('',#114371); -#114371 = CARTESIAN_POINT('',(-0.740726081328,4.15,-0.208196358798)); -#114372 = SURFACE_CURVE('',#114373,(#114377,#114384),.PCURVE_S1.); -#114373 = LINE('',#114374,#114375); -#114374 = CARTESIAN_POINT('',(-0.740726081328,4.15,-0.208196358798)); -#114375 = VECTOR('',#114376,1.); -#114376 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#114377 = PCURVE('',#114350,#114378); -#114378 = DEFINITIONAL_REPRESENTATION('',(#114379),#114383); -#114379 = LINE('',#114380,#114381); -#114380 = CARTESIAN_POINT('',(-2.775557561563E-015,-5.85)); -#114381 = VECTOR('',#114382,1.); -#114382 = DIRECTION('',(1.,0.E+000)); -#114383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114384 = PCURVE('',#91267,#114385); -#114385 = DEFINITIONAL_REPRESENTATION('',(#114386),#114390); -#114386 = LINE('',#114387,#114388); -#114387 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#114388 = VECTOR('',#114389,1.); -#114389 = DIRECTION('',(0.E+000,-1.)); -#114390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114391 = ORIENTED_EDGE('',*,*,#114392,.F.); -#114392 = EDGE_CURVE('',#114393,#114370,#114395,.T.); -#114393 = VERTEX_POINT('',#114394); -#114394 = CARTESIAN_POINT('',(-0.740726081328,4.35,-0.208196358798)); -#114395 = SURFACE_CURVE('',#114396,(#114400,#114407),.PCURVE_S1.); -#114396 = LINE('',#114397,#114398); -#114397 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#114398 = VECTOR('',#114399,1.); -#114399 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114400 = PCURVE('',#114350,#114401); -#114401 = DEFINITIONAL_REPRESENTATION('',(#114402),#114406); -#114402 = LINE('',#114403,#114404); -#114403 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114404 = VECTOR('',#114405,1.); -#114405 = DIRECTION('',(-4.440892098501E-016,-1.)); -#114406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114407 = PCURVE('',#114408,#114413); -#114408 = CYLINDRICAL_SURFACE('',#114409,0.208574704164); -#114409 = AXIS2_PLACEMENT_3D('',#114410,#114411,#114412); -#114410 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#114411 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114412 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114413 = DEFINITIONAL_REPRESENTATION('',(#114414),#114417); -#114414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114415,#114416), +#116703 = CARTESIAN_POINT('',(4.761821717947,-5.85)); +#116704 = CARTESIAN_POINT('',(4.761821717947,-5.65)); +#116705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116706 = ORIENTED_EDGE('',*,*,#116707,.T.); +#116707 = EDGE_CURVE('',#116681,#116625,#116708,.T.); +#116708 = SURFACE_CURVE('',#116709,(#116713,#116720),.PCURVE_S1.); +#116709 = LINE('',#116710,#116711); +#116710 = CARTESIAN_POINT('',(-0.74341632541,4.15,-0.308197125857)); +#116711 = VECTOR('',#116712,1.); +#116712 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#116713 = PCURVE('',#116633,#116714); +#116714 = DEFINITIONAL_REPRESENTATION('',(#116715),#116719); +#116715 = LINE('',#116716,#116717); +#116716 = CARTESIAN_POINT('',(2.775557561563E-015,-5.85)); +#116717 = VECTOR('',#116718,1.); +#116718 = DIRECTION('',(-1.,0.E+000)); +#116719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116720 = PCURVE('',#93659,#116721); +#116721 = DEFINITIONAL_REPRESENTATION('',(#116722),#116726); +#116722 = LINE('',#116723,#116724); +#116723 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#116724 = VECTOR('',#116725,1.); +#116725 = DIRECTION('',(0.E+000,-1.)); +#116726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116727 = ADVANCED_FACE('',(#116728),#116742,.F.); +#116728 = FACE_BOUND('',#116729,.T.); +#116729 = EDGE_LOOP('',(#116730,#116760,#116783,#116810)); +#116730 = ORIENTED_EDGE('',*,*,#116731,.F.); +#116731 = EDGE_CURVE('',#116732,#116734,#116736,.T.); +#116732 = VERTEX_POINT('',#116733); +#116733 = CARTESIAN_POINT('',(-1.,4.15,-0.208196358798)); +#116734 = VERTEX_POINT('',#116735); +#116735 = CARTESIAN_POINT('',(-1.,4.35,-0.208196358798)); +#116736 = SURFACE_CURVE('',#116737,(#116741,#116753),.PCURVE_S1.); +#116737 = LINE('',#116738,#116739); +#116738 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#116739 = VECTOR('',#116740,1.); +#116740 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116741 = PCURVE('',#116742,#116747); +#116742 = PLANE('',#116743); +#116743 = AXIS2_PLACEMENT_3D('',#116744,#116745,#116746); +#116744 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#116745 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#116746 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#116747 = DEFINITIONAL_REPRESENTATION('',(#116748),#116752); +#116748 = LINE('',#116749,#116750); +#116749 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#116750 = VECTOR('',#116751,1.); +#116751 = DIRECTION('',(4.440892098501E-016,1.)); +#116752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116753 = PCURVE('',#116645,#116754); +#116754 = DEFINITIONAL_REPRESENTATION('',(#116755),#116759); +#116755 = LINE('',#116756,#116757); +#116756 = CARTESIAN_POINT('',(-5.75,5.000038352949E-002)); +#116757 = VECTOR('',#116758,1.); +#116758 = DIRECTION('',(-1.,0.E+000)); +#116759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116760 = ORIENTED_EDGE('',*,*,#116761,.F.); +#116761 = EDGE_CURVE('',#116762,#116732,#116764,.T.); +#116762 = VERTEX_POINT('',#116763); +#116763 = CARTESIAN_POINT('',(-0.740726081328,4.15,-0.208196358798)); +#116764 = SURFACE_CURVE('',#116765,(#116769,#116776),.PCURVE_S1.); +#116765 = LINE('',#116766,#116767); +#116766 = CARTESIAN_POINT('',(-0.740726081328,4.15,-0.208196358798)); +#116767 = VECTOR('',#116768,1.); +#116768 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#116769 = PCURVE('',#116742,#116770); +#116770 = DEFINITIONAL_REPRESENTATION('',(#116771),#116775); +#116771 = LINE('',#116772,#116773); +#116772 = CARTESIAN_POINT('',(-2.775557561563E-015,-5.85)); +#116773 = VECTOR('',#116774,1.); +#116774 = DIRECTION('',(1.,0.E+000)); +#116775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116776 = PCURVE('',#93659,#116777); +#116777 = DEFINITIONAL_REPRESENTATION('',(#116778),#116782); +#116778 = LINE('',#116779,#116780); +#116779 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#116780 = VECTOR('',#116781,1.); +#116781 = DIRECTION('',(0.E+000,-1.)); +#116782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116783 = ORIENTED_EDGE('',*,*,#116784,.F.); +#116784 = EDGE_CURVE('',#116785,#116762,#116787,.T.); +#116785 = VERTEX_POINT('',#116786); +#116786 = CARTESIAN_POINT('',(-0.740726081328,4.35,-0.208196358798)); +#116787 = SURFACE_CURVE('',#116788,(#116792,#116799),.PCURVE_S1.); +#116788 = LINE('',#116789,#116790); +#116789 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#116790 = VECTOR('',#116791,1.); +#116791 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116792 = PCURVE('',#116742,#116793); +#116793 = DEFINITIONAL_REPRESENTATION('',(#116794),#116798); +#116794 = LINE('',#116795,#116796); +#116795 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#116796 = VECTOR('',#116797,1.); +#116797 = DIRECTION('',(-4.440892098501E-016,-1.)); +#116798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116799 = PCURVE('',#116800,#116805); +#116800 = CYLINDRICAL_SURFACE('',#116801,0.208574704164); +#116801 = AXIS2_PLACEMENT_3D('',#116802,#116803,#116804); +#116802 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#116803 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116804 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116805 = DEFINITIONAL_REPRESENTATION('',(#116806),#116809); +#116806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116807,#116808), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#114415 = CARTESIAN_POINT('',(4.772630242227,-5.65)); -#114416 = CARTESIAN_POINT('',(4.772630242227,-5.85)); -#114417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114418 = ORIENTED_EDGE('',*,*,#114419,.T.); -#114419 = EDGE_CURVE('',#114393,#114342,#114420,.T.); -#114420 = SURFACE_CURVE('',#114421,(#114425,#114432),.PCURVE_S1.); -#114421 = LINE('',#114422,#114423); -#114422 = CARTESIAN_POINT('',(-0.740726081328,4.35,-0.208196358798)); -#114423 = VECTOR('',#114424,1.); -#114424 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#114425 = PCURVE('',#114350,#114426); -#114426 = DEFINITIONAL_REPRESENTATION('',(#114427),#114431); -#114427 = LINE('',#114428,#114429); -#114428 = CARTESIAN_POINT('',(-2.553512956638E-015,-5.65)); -#114429 = VECTOR('',#114430,1.); -#114430 = DIRECTION('',(1.,0.E+000)); -#114431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114432 = PCURVE('',#91323,#114433); -#114433 = DEFINITIONAL_REPRESENTATION('',(#114434),#114438); -#114434 = LINE('',#114435,#114436); -#114435 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#114436 = VECTOR('',#114437,1.); -#114437 = DIRECTION('',(0.E+000,-1.)); -#114438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114439 = ADVANCED_FACE('',(#114440),#114304,.T.); -#114440 = FACE_BOUND('',#114441,.T.); -#114441 = EDGE_LOOP('',(#114442,#114469,#114470,#114493)); -#114442 = ORIENTED_EDGE('',*,*,#114443,.T.); -#114443 = EDGE_CURVE('',#114444,#114289,#114446,.T.); -#114444 = VERTEX_POINT('',#114445); -#114445 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.E+000)); -#114446 = SURFACE_CURVE('',#114447,(#114452,#114458),.PCURVE_S1.); -#114447 = CIRCLE('',#114448,0.308574064194); -#114448 = AXIS2_PLACEMENT_3D('',#114449,#114450,#114451); -#114449 = CARTESIAN_POINT('',(-0.728168876214,4.15,2.640924866458E-017) - ); -#114450 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114451 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114452 = PCURVE('',#114304,#114453); -#114453 = DEFINITIONAL_REPRESENTATION('',(#114454),#114457); -#114454 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114455,#114456), +#116807 = CARTESIAN_POINT('',(4.772630242227,-5.65)); +#116808 = CARTESIAN_POINT('',(4.772630242227,-5.85)); +#116809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116810 = ORIENTED_EDGE('',*,*,#116811,.T.); +#116811 = EDGE_CURVE('',#116785,#116734,#116812,.T.); +#116812 = SURFACE_CURVE('',#116813,(#116817,#116824),.PCURVE_S1.); +#116813 = LINE('',#116814,#116815); +#116814 = CARTESIAN_POINT('',(-0.740726081328,4.35,-0.208196358798)); +#116815 = VECTOR('',#116816,1.); +#116816 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#116817 = PCURVE('',#116742,#116818); +#116818 = DEFINITIONAL_REPRESENTATION('',(#116819),#116823); +#116819 = LINE('',#116820,#116821); +#116820 = CARTESIAN_POINT('',(-2.553512956638E-015,-5.65)); +#116821 = VECTOR('',#116822,1.); +#116822 = DIRECTION('',(1.,0.E+000)); +#116823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116824 = PCURVE('',#93715,#116825); +#116825 = DEFINITIONAL_REPRESENTATION('',(#116826),#116830); +#116826 = LINE('',#116827,#116828); +#116827 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#116828 = VECTOR('',#116829,1.); +#116829 = DIRECTION('',(0.E+000,-1.)); +#116830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116831 = ADVANCED_FACE('',(#116832),#116696,.T.); +#116832 = FACE_BOUND('',#116833,.T.); +#116833 = EDGE_LOOP('',(#116834,#116861,#116862,#116885)); +#116834 = ORIENTED_EDGE('',*,*,#116835,.T.); +#116835 = EDGE_CURVE('',#116836,#116681,#116838,.T.); +#116836 = VERTEX_POINT('',#116837); +#116837 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.E+000)); +#116838 = SURFACE_CURVE('',#116839,(#116844,#116850),.PCURVE_S1.); +#116839 = CIRCLE('',#116840,0.308574064194); +#116840 = AXIS2_PLACEMENT_3D('',#116841,#116842,#116843); +#116841 = CARTESIAN_POINT('',(-0.728168876214,4.15,2.640924866458E-017) + ); +#116842 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116843 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116844 = PCURVE('',#116696,#116845); +#116845 = DEFINITIONAL_REPRESENTATION('',(#116846),#116849); +#116846 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116847,#116848), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#114455 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#114456 = CARTESIAN_POINT('',(4.761821717947,-5.85)); -#114457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116847 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#116848 = CARTESIAN_POINT('',(4.761821717947,-5.85)); +#116849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114458 = PCURVE('',#91267,#114459); -#114459 = DEFINITIONAL_REPRESENTATION('',(#114460),#114468); -#114460 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114461,#114462,#114463, - #114464,#114465,#114466,#114467),.UNSPECIFIED.,.T.,.F.) +#116850 = PCURVE('',#93659,#116851); +#116851 = DEFINITIONAL_REPRESENTATION('',(#116852),#116860); +#116852 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116853,#116854,#116855, + #116856,#116857,#116858,#116859),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#114461 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#114462 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#114463 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#114464 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#114465 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#114466 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#114467 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#114468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114469 = ORIENTED_EDGE('',*,*,#114288,.T.); -#114470 = ORIENTED_EDGE('',*,*,#114471,.F.); -#114471 = EDGE_CURVE('',#114472,#114266,#114474,.T.); -#114472 = VERTEX_POINT('',#114473); -#114473 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.E+000)); -#114474 = SURFACE_CURVE('',#114475,(#114480,#114486),.PCURVE_S1.); -#114475 = CIRCLE('',#114476,0.308574064194); -#114476 = AXIS2_PLACEMENT_3D('',#114477,#114478,#114479); -#114477 = CARTESIAN_POINT('',(-0.728168876214,4.35,2.640924866458E-017) - ); -#114478 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114479 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114480 = PCURVE('',#114304,#114481); -#114481 = DEFINITIONAL_REPRESENTATION('',(#114482),#114485); -#114482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114483,#114484), +#116853 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#116854 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#116855 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#116856 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#116857 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#116858 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#116859 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#116860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116861 = ORIENTED_EDGE('',*,*,#116680,.T.); +#116862 = ORIENTED_EDGE('',*,*,#116863,.F.); +#116863 = EDGE_CURVE('',#116864,#116658,#116866,.T.); +#116864 = VERTEX_POINT('',#116865); +#116865 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.E+000)); +#116866 = SURFACE_CURVE('',#116867,(#116872,#116878),.PCURVE_S1.); +#116867 = CIRCLE('',#116868,0.308574064194); +#116868 = AXIS2_PLACEMENT_3D('',#116869,#116870,#116871); +#116869 = CARTESIAN_POINT('',(-0.728168876214,4.35,2.640924866458E-017) + ); +#116870 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116871 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116872 = PCURVE('',#116696,#116873); +#116873 = DEFINITIONAL_REPRESENTATION('',(#116874),#116877); +#116874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116875,#116876), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#114483 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#114484 = CARTESIAN_POINT('',(4.761821717947,-5.65)); -#114485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114486 = PCURVE('',#91323,#114487); -#114487 = DEFINITIONAL_REPRESENTATION('',(#114488),#114492); -#114488 = CIRCLE('',#114489,0.308574064194); -#114489 = AXIS2_PLACEMENT_2D('',#114490,#114491); -#114490 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#114491 = DIRECTION('',(0.E+000,-1.)); -#114492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114493 = ORIENTED_EDGE('',*,*,#114494,.T.); -#114494 = EDGE_CURVE('',#114472,#114444,#114495,.T.); -#114495 = SURFACE_CURVE('',#114496,(#114500,#114506),.PCURVE_S1.); -#114496 = LINE('',#114497,#114498); -#114497 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#114498 = VECTOR('',#114499,1.); -#114499 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114500 = PCURVE('',#114304,#114501); -#114501 = DEFINITIONAL_REPRESENTATION('',(#114502),#114505); -#114502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114503,#114504), +#116875 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#116876 = CARTESIAN_POINT('',(4.761821717947,-5.65)); +#116877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116878 = PCURVE('',#93715,#116879); +#116879 = DEFINITIONAL_REPRESENTATION('',(#116880),#116884); +#116880 = CIRCLE('',#116881,0.308574064194); +#116881 = AXIS2_PLACEMENT_2D('',#116882,#116883); +#116882 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#116883 = DIRECTION('',(0.E+000,-1.)); +#116884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116885 = ORIENTED_EDGE('',*,*,#116886,.T.); +#116886 = EDGE_CURVE('',#116864,#116836,#116887,.T.); +#116887 = SURFACE_CURVE('',#116888,(#116892,#116898),.PCURVE_S1.); +#116888 = LINE('',#116889,#116890); +#116889 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#116890 = VECTOR('',#116891,1.); +#116891 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116892 = PCURVE('',#116696,#116893); +#116893 = DEFINITIONAL_REPRESENTATION('',(#116894),#116897); +#116894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116895,#116896), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#114503 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#114504 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#114505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114506 = PCURVE('',#114507,#114512); -#114507 = PLANE('',#114508); -#114508 = AXIS2_PLACEMENT_3D('',#114509,#114510,#114511); -#114509 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#114510 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#114511 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114512 = DEFINITIONAL_REPRESENTATION('',(#114513),#114517); -#114513 = LINE('',#114514,#114515); -#114514 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#114515 = VECTOR('',#114516,1.); -#114516 = DIRECTION('',(-1.,0.E+000)); -#114517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114518 = ADVANCED_FACE('',(#114519),#114408,.F.); -#114519 = FACE_BOUND('',#114520,.F.); -#114520 = EDGE_LOOP('',(#114521,#114544,#114571,#114596)); -#114521 = ORIENTED_EDGE('',*,*,#114522,.F.); -#114522 = EDGE_CURVE('',#114523,#114393,#114525,.T.); -#114523 = VERTEX_POINT('',#114524); -#114524 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.E+000)); -#114525 = SURFACE_CURVE('',#114526,(#114531,#114537),.PCURVE_S1.); -#114526 = CIRCLE('',#114527,0.208574704164); -#114527 = AXIS2_PLACEMENT_3D('',#114528,#114529,#114530); -#114528 = CARTESIAN_POINT('',(-0.728168876214,4.35,2.640924866458E-017) - ); -#114529 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114530 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114531 = PCURVE('',#114408,#114532); -#114532 = DEFINITIONAL_REPRESENTATION('',(#114533),#114536); -#114533 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114534,#114535), +#116895 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#116896 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#116897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116898 = PCURVE('',#116899,#116904); +#116899 = PLANE('',#116900); +#116900 = AXIS2_PLACEMENT_3D('',#116901,#116902,#116903); +#116901 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#116902 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#116903 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116904 = DEFINITIONAL_REPRESENTATION('',(#116905),#116909); +#116905 = LINE('',#116906,#116907); +#116906 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#116907 = VECTOR('',#116908,1.); +#116908 = DIRECTION('',(-1.,0.E+000)); +#116909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116910 = ADVANCED_FACE('',(#116911),#116800,.F.); +#116911 = FACE_BOUND('',#116912,.F.); +#116912 = EDGE_LOOP('',(#116913,#116936,#116963,#116988)); +#116913 = ORIENTED_EDGE('',*,*,#116914,.F.); +#116914 = EDGE_CURVE('',#116915,#116785,#116917,.T.); +#116915 = VERTEX_POINT('',#116916); +#116916 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.E+000)); +#116917 = SURFACE_CURVE('',#116918,(#116923,#116929),.PCURVE_S1.); +#116918 = CIRCLE('',#116919,0.208574704164); +#116919 = AXIS2_PLACEMENT_3D('',#116920,#116921,#116922); +#116920 = CARTESIAN_POINT('',(-0.728168876214,4.35,2.640924866458E-017) + ); +#116921 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116922 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116923 = PCURVE('',#116800,#116924); +#116924 = DEFINITIONAL_REPRESENTATION('',(#116925),#116928); +#116925 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116926,#116927), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#114534 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#114535 = CARTESIAN_POINT('',(4.772630242227,-5.65)); -#114536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114537 = PCURVE('',#91323,#114538); -#114538 = DEFINITIONAL_REPRESENTATION('',(#114539),#114543); -#114539 = CIRCLE('',#114540,0.208574704164); -#114540 = AXIS2_PLACEMENT_2D('',#114541,#114542); -#114541 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#114542 = DIRECTION('',(0.E+000,-1.)); -#114543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114544 = ORIENTED_EDGE('',*,*,#114545,.F.); -#114545 = EDGE_CURVE('',#114546,#114523,#114548,.T.); -#114546 = VERTEX_POINT('',#114547); -#114547 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.E+000)); -#114548 = SURFACE_CURVE('',#114549,(#114553,#114559),.PCURVE_S1.); -#114549 = LINE('',#114550,#114551); -#114550 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#114551 = VECTOR('',#114552,1.); -#114552 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114553 = PCURVE('',#114408,#114554); -#114554 = DEFINITIONAL_REPRESENTATION('',(#114555),#114558); -#114555 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114556,#114557), +#116926 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#116927 = CARTESIAN_POINT('',(4.772630242227,-5.65)); +#116928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116929 = PCURVE('',#93715,#116930); +#116930 = DEFINITIONAL_REPRESENTATION('',(#116931),#116935); +#116931 = CIRCLE('',#116932,0.208574704164); +#116932 = AXIS2_PLACEMENT_2D('',#116933,#116934); +#116933 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#116934 = DIRECTION('',(0.E+000,-1.)); +#116935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116936 = ORIENTED_EDGE('',*,*,#116937,.F.); +#116937 = EDGE_CURVE('',#116938,#116915,#116940,.T.); +#116938 = VERTEX_POINT('',#116939); +#116939 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.E+000)); +#116940 = SURFACE_CURVE('',#116941,(#116945,#116951),.PCURVE_S1.); +#116941 = LINE('',#116942,#116943); +#116942 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#116943 = VECTOR('',#116944,1.); +#116944 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116945 = PCURVE('',#116800,#116946); +#116946 = DEFINITIONAL_REPRESENTATION('',(#116947),#116950); +#116947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116948,#116949), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#114556 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#114557 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#114558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114559 = PCURVE('',#114560,#114565); -#114560 = PLANE('',#114561); -#114561 = AXIS2_PLACEMENT_3D('',#114562,#114563,#114564); -#114562 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#114563 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#114564 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114565 = DEFINITIONAL_REPRESENTATION('',(#114566),#114570); -#114566 = LINE('',#114567,#114568); -#114567 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#114568 = VECTOR('',#114569,1.); -#114569 = DIRECTION('',(-1.,0.E+000)); -#114570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114571 = ORIENTED_EDGE('',*,*,#114572,.T.); -#114572 = EDGE_CURVE('',#114546,#114370,#114573,.T.); -#114573 = SURFACE_CURVE('',#114574,(#114579,#114585),.PCURVE_S1.); -#114574 = CIRCLE('',#114575,0.208574704164); -#114575 = AXIS2_PLACEMENT_3D('',#114576,#114577,#114578); -#114576 = CARTESIAN_POINT('',(-0.728168876214,4.15,2.640924866458E-017) - ); -#114577 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114578 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#114579 = PCURVE('',#114408,#114580); -#114580 = DEFINITIONAL_REPRESENTATION('',(#114581),#114584); -#114581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114582,#114583), +#116948 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#116949 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#116950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116951 = PCURVE('',#116952,#116957); +#116952 = PLANE('',#116953); +#116953 = AXIS2_PLACEMENT_3D('',#116954,#116955,#116956); +#116954 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#116955 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#116956 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#116957 = DEFINITIONAL_REPRESENTATION('',(#116958),#116962); +#116958 = LINE('',#116959,#116960); +#116959 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#116960 = VECTOR('',#116961,1.); +#116961 = DIRECTION('',(-1.,0.E+000)); +#116962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116963 = ORIENTED_EDGE('',*,*,#116964,.T.); +#116964 = EDGE_CURVE('',#116938,#116762,#116965,.T.); +#116965 = SURFACE_CURVE('',#116966,(#116971,#116977),.PCURVE_S1.); +#116966 = CIRCLE('',#116967,0.208574704164); +#116967 = AXIS2_PLACEMENT_3D('',#116968,#116969,#116970); +#116968 = CARTESIAN_POINT('',(-0.728168876214,4.15,2.640924866458E-017) + ); +#116969 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#116970 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#116971 = PCURVE('',#116800,#116972); +#116972 = DEFINITIONAL_REPRESENTATION('',(#116973),#116976); +#116973 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116974,#116975), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#114582 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#114583 = CARTESIAN_POINT('',(4.772630242227,-5.85)); -#114584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#116974 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#116975 = CARTESIAN_POINT('',(4.772630242227,-5.85)); +#116976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114585 = PCURVE('',#91267,#114586); -#114586 = DEFINITIONAL_REPRESENTATION('',(#114587),#114595); -#114587 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114588,#114589,#114590, - #114591,#114592,#114593,#114594),.UNSPECIFIED.,.T.,.F.) +#116977 = PCURVE('',#93659,#116978); +#116978 = DEFINITIONAL_REPRESENTATION('',(#116979),#116987); +#116979 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116980,#116981,#116982, + #116983,#116984,#116985,#116986),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#114588 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#114589 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#114590 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#114591 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#114592 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#114593 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#114594 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#114595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114596 = ORIENTED_EDGE('',*,*,#114392,.F.); -#114597 = ADVANCED_FACE('',(#114598),#114560,.T.); -#114598 = FACE_BOUND('',#114599,.T.); -#114599 = EDGE_LOOP('',(#114600,#114629,#114650,#114651)); -#114600 = ORIENTED_EDGE('',*,*,#114601,.T.); -#114601 = EDGE_CURVE('',#114602,#114604,#114606,.T.); -#114602 = VERTEX_POINT('',#114603); -#114603 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.530776333563)); -#114604 = VERTEX_POINT('',#114605); -#114605 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.530776333563)); -#114606 = SURFACE_CURVE('',#114607,(#114611,#114618),.PCURVE_S1.); -#114607 = LINE('',#114608,#114609); -#114608 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#114609 = VECTOR('',#114610,1.); -#114610 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114611 = PCURVE('',#114560,#114612); -#114612 = DEFINITIONAL_REPRESENTATION('',(#114613),#114617); -#114613 = LINE('',#114614,#114615); -#114614 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114615 = VECTOR('',#114616,1.); -#114616 = DIRECTION('',(-1.,0.E+000)); -#114617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114618 = PCURVE('',#114619,#114624); -#114619 = CYLINDRICAL_SURFACE('',#114620,0.2192697516); -#114620 = AXIS2_PLACEMENT_3D('',#114621,#114622,#114623); -#114621 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#114622 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114623 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114624 = DEFINITIONAL_REPRESENTATION('',(#114625),#114628); -#114625 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114626,#114627), +#116980 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#116981 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#116982 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#116983 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#116984 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#116985 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#116986 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#116987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#116988 = ORIENTED_EDGE('',*,*,#116784,.F.); +#116989 = ADVANCED_FACE('',(#116990),#116952,.T.); +#116990 = FACE_BOUND('',#116991,.T.); +#116991 = EDGE_LOOP('',(#116992,#117021,#117042,#117043)); +#116992 = ORIENTED_EDGE('',*,*,#116993,.T.); +#116993 = EDGE_CURVE('',#116994,#116996,#116998,.T.); +#116994 = VERTEX_POINT('',#116995); +#116995 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.530776333563)); +#116996 = VERTEX_POINT('',#116997); +#116997 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.530776333563)); +#116998 = SURFACE_CURVE('',#116999,(#117003,#117010),.PCURVE_S1.); +#116999 = LINE('',#117000,#117001); +#117000 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#117001 = VECTOR('',#117002,1.); +#117002 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117003 = PCURVE('',#116952,#117004); +#117004 = DEFINITIONAL_REPRESENTATION('',(#117005),#117009); +#117005 = LINE('',#117006,#117007); +#117006 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117007 = VECTOR('',#117008,1.); +#117008 = DIRECTION('',(-1.,0.E+000)); +#117009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117010 = PCURVE('',#117011,#117016); +#117011 = CYLINDRICAL_SURFACE('',#117012,0.2192697516); +#117012 = AXIS2_PLACEMENT_3D('',#117013,#117014,#117015); +#117013 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#117014 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117015 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117016 = DEFINITIONAL_REPRESENTATION('',(#117017),#117020); +#117017 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117018,#117019), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#114626 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#114627 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#114628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114629 = ORIENTED_EDGE('',*,*,#114630,.T.); -#114630 = EDGE_CURVE('',#114604,#114523,#114631,.T.); -#114631 = SURFACE_CURVE('',#114632,(#114636,#114643),.PCURVE_S1.); -#114632 = LINE('',#114633,#114634); -#114633 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.530776333563)); -#114634 = VECTOR('',#114635,1.); -#114635 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#114636 = PCURVE('',#114560,#114637); -#114637 = DEFINITIONAL_REPRESENTATION('',(#114638),#114642); -#114638 = LINE('',#114639,#114640); -#114639 = CARTESIAN_POINT('',(5.65,4.535643882845E-033)); -#114640 = VECTOR('',#114641,1.); -#114641 = DIRECTION('',(-4.535643882845E-032,-1.)); -#114642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114643 = PCURVE('',#91323,#114644); -#114644 = DEFINITIONAL_REPRESENTATION('',(#114645),#114649); -#114645 = LINE('',#114646,#114647); -#114646 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#114647 = VECTOR('',#114648,1.); -#114648 = DIRECTION('',(-1.,-1.021336205033E-016)); -#114649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114650 = ORIENTED_EDGE('',*,*,#114545,.F.); -#114651 = ORIENTED_EDGE('',*,*,#114652,.F.); -#114652 = EDGE_CURVE('',#114602,#114546,#114653,.T.); -#114653 = SURFACE_CURVE('',#114654,(#114658,#114665),.PCURVE_S1.); -#114654 = LINE('',#114655,#114656); -#114655 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.530776333563)); -#114656 = VECTOR('',#114657,1.); -#114657 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#114658 = PCURVE('',#114560,#114659); -#114659 = DEFINITIONAL_REPRESENTATION('',(#114660),#114664); -#114660 = LINE('',#114661,#114662); -#114661 = CARTESIAN_POINT('',(5.85,-4.535643882845E-033)); -#114662 = VECTOR('',#114663,1.); -#114663 = DIRECTION('',(-4.535643882845E-032,-1.)); -#114664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114665 = PCURVE('',#91267,#114666); -#114666 = DEFINITIONAL_REPRESENTATION('',(#114667),#114671); -#114667 = LINE('',#114668,#114669); -#114668 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#114669 = VECTOR('',#114670,1.); -#114670 = DIRECTION('',(1.,-1.021336205033E-016)); -#114671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114672 = ADVANCED_FACE('',(#114673),#114507,.T.); -#114673 = FACE_BOUND('',#114674,.T.); -#114674 = EDGE_LOOP('',(#114675,#114704,#114725,#114726)); -#114675 = ORIENTED_EDGE('',*,*,#114676,.T.); -#114676 = EDGE_CURVE('',#114677,#114679,#114681,.T.); -#114677 = VERTEX_POINT('',#114678); -#114678 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.530776333563)); -#114679 = VERTEX_POINT('',#114680); -#114680 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.530776333563)); -#114681 = SURFACE_CURVE('',#114682,(#114686,#114693),.PCURVE_S1.); -#114682 = LINE('',#114683,#114684); -#114683 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#114684 = VECTOR('',#114685,1.); -#114685 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114686 = PCURVE('',#114507,#114687); -#114687 = DEFINITIONAL_REPRESENTATION('',(#114688),#114692); -#114688 = LINE('',#114689,#114690); -#114689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114690 = VECTOR('',#114691,1.); -#114691 = DIRECTION('',(-1.,0.E+000)); -#114692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117018 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#117019 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#117020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117021 = ORIENTED_EDGE('',*,*,#117022,.T.); +#117022 = EDGE_CURVE('',#116996,#116915,#117023,.T.); +#117023 = SURFACE_CURVE('',#117024,(#117028,#117035),.PCURVE_S1.); +#117024 = LINE('',#117025,#117026); +#117025 = CARTESIAN_POINT('',(-0.51959417205,4.35,0.530776333563)); +#117026 = VECTOR('',#117027,1.); +#117027 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117028 = PCURVE('',#116952,#117029); +#117029 = DEFINITIONAL_REPRESENTATION('',(#117030),#117034); +#117030 = LINE('',#117031,#117032); +#117031 = CARTESIAN_POINT('',(5.65,4.535643882845E-033)); +#117032 = VECTOR('',#117033,1.); +#117033 = DIRECTION('',(-4.535643882845E-032,-1.)); +#117034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117035 = PCURVE('',#93715,#117036); +#117036 = DEFINITIONAL_REPRESENTATION('',(#117037),#117041); +#117037 = LINE('',#117038,#117039); +#117038 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#117039 = VECTOR('',#117040,1.); +#117040 = DIRECTION('',(-1.,-1.021336205033E-016)); +#117041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114693 = PCURVE('',#114694,#114699); -#114694 = CYLINDRICAL_SURFACE('',#114695,0.119270391569); -#114695 = AXIS2_PLACEMENT_3D('',#114696,#114697,#114698); -#114696 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#114697 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114698 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114699 = DEFINITIONAL_REPRESENTATION('',(#114700),#114703); -#114700 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114701,#114702), +#117042 = ORIENTED_EDGE('',*,*,#116937,.F.); +#117043 = ORIENTED_EDGE('',*,*,#117044,.F.); +#117044 = EDGE_CURVE('',#116994,#116938,#117045,.T.); +#117045 = SURFACE_CURVE('',#117046,(#117050,#117057),.PCURVE_S1.); +#117046 = LINE('',#117047,#117048); +#117047 = CARTESIAN_POINT('',(-0.51959417205,4.15,0.530776333563)); +#117048 = VECTOR('',#117049,1.); +#117049 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117050 = PCURVE('',#116952,#117051); +#117051 = DEFINITIONAL_REPRESENTATION('',(#117052),#117056); +#117052 = LINE('',#117053,#117054); +#117053 = CARTESIAN_POINT('',(5.85,-4.535643882845E-033)); +#117054 = VECTOR('',#117055,1.); +#117055 = DIRECTION('',(-4.535643882845E-032,-1.)); +#117056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117057 = PCURVE('',#93659,#117058); +#117058 = DEFINITIONAL_REPRESENTATION('',(#117059),#117063); +#117059 = LINE('',#117060,#117061); +#117060 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#117061 = VECTOR('',#117062,1.); +#117062 = DIRECTION('',(1.,-1.021336205033E-016)); +#117063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117064 = ADVANCED_FACE('',(#117065),#116899,.T.); +#117065 = FACE_BOUND('',#117066,.T.); +#117066 = EDGE_LOOP('',(#117067,#117096,#117117,#117118)); +#117067 = ORIENTED_EDGE('',*,*,#117068,.T.); +#117068 = EDGE_CURVE('',#117069,#117071,#117073,.T.); +#117069 = VERTEX_POINT('',#117070); +#117070 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.530776333563)); +#117071 = VERTEX_POINT('',#117072); +#117072 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.530776333563)); +#117073 = SURFACE_CURVE('',#117074,(#117078,#117085),.PCURVE_S1.); +#117074 = LINE('',#117075,#117076); +#117075 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#117076 = VECTOR('',#117077,1.); +#117077 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117078 = PCURVE('',#116899,#117079); +#117079 = DEFINITIONAL_REPRESENTATION('',(#117080),#117084); +#117080 = LINE('',#117081,#117082); +#117081 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117082 = VECTOR('',#117083,1.); +#117083 = DIRECTION('',(-1.,0.E+000)); +#117084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117085 = PCURVE('',#117086,#117091); +#117086 = CYLINDRICAL_SURFACE('',#117087,0.119270391569); +#117087 = AXIS2_PLACEMENT_3D('',#117088,#117089,#117090); +#117088 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#117089 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117090 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117091 = DEFINITIONAL_REPRESENTATION('',(#117092),#117095); +#117092 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117093,#117094), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#114701 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#114702 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#114703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114704 = ORIENTED_EDGE('',*,*,#114705,.T.); -#114705 = EDGE_CURVE('',#114679,#114444,#114706,.T.); -#114706 = SURFACE_CURVE('',#114707,(#114711,#114718),.PCURVE_S1.); -#114707 = LINE('',#114708,#114709); -#114708 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.530776333563)); -#114709 = VECTOR('',#114710,1.); -#114710 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#114711 = PCURVE('',#114507,#114712); -#114712 = DEFINITIONAL_REPRESENTATION('',(#114713),#114717); -#114713 = LINE('',#114714,#114715); -#114714 = CARTESIAN_POINT('',(-5.85,1.133910970711E-033)); -#114715 = VECTOR('',#114716,1.); -#114716 = DIRECTION('',(4.535643882845E-032,-1.)); -#114717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114718 = PCURVE('',#91267,#114719); -#114719 = DEFINITIONAL_REPRESENTATION('',(#114720),#114724); -#114720 = LINE('',#114721,#114722); -#114721 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#114722 = VECTOR('',#114723,1.); -#114723 = DIRECTION('',(1.,-1.021336205033E-016)); -#114724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114725 = ORIENTED_EDGE('',*,*,#114494,.F.); -#114726 = ORIENTED_EDGE('',*,*,#114727,.F.); -#114727 = EDGE_CURVE('',#114677,#114472,#114728,.T.); -#114728 = SURFACE_CURVE('',#114729,(#114733,#114740),.PCURVE_S1.); -#114729 = LINE('',#114730,#114731); -#114730 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.530776333563)); -#114731 = VECTOR('',#114732,1.); -#114732 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#114733 = PCURVE('',#114507,#114734); -#114734 = DEFINITIONAL_REPRESENTATION('',(#114735),#114739); -#114735 = LINE('',#114736,#114737); -#114736 = CARTESIAN_POINT('',(-5.65,-1.133910970711E-033)); -#114737 = VECTOR('',#114738,1.); -#114738 = DIRECTION('',(4.535643882845E-032,-1.)); -#114739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114740 = PCURVE('',#91323,#114741); -#114741 = DEFINITIONAL_REPRESENTATION('',(#114742),#114746); -#114742 = LINE('',#114743,#114744); -#114743 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#114744 = VECTOR('',#114745,1.); -#114745 = DIRECTION('',(-1.,-1.021336205033E-016)); -#114746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114747 = ADVANCED_FACE('',(#114748),#114694,.F.); -#114748 = FACE_BOUND('',#114749,.F.); -#114749 = EDGE_LOOP('',(#114750,#114751,#114774,#114819)); -#114750 = ORIENTED_EDGE('',*,*,#114676,.T.); -#114751 = ORIENTED_EDGE('',*,*,#114752,.F.); -#114752 = EDGE_CURVE('',#114753,#114679,#114755,.T.); -#114753 = VERTEX_POINT('',#114754); -#114754 = CARTESIAN_POINT('',(-0.303662633502,4.15,0.65)); -#114755 = SURFACE_CURVE('',#114756,(#114761,#114767),.PCURVE_S1.); -#114756 = CIRCLE('',#114757,0.119270391569); -#114757 = AXIS2_PLACEMENT_3D('',#114758,#114759,#114760); -#114758 = CARTESIAN_POINT('',(-0.30032442045,4.15,0.530776333563)); -#114759 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114760 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114761 = PCURVE('',#114694,#114762); -#114762 = DEFINITIONAL_REPRESENTATION('',(#114763),#114766); -#114763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114764,#114765), +#117093 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#117094 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#117095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117096 = ORIENTED_EDGE('',*,*,#117097,.T.); +#117097 = EDGE_CURVE('',#117071,#116836,#117098,.T.); +#117098 = SURFACE_CURVE('',#117099,(#117103,#117110),.PCURVE_S1.); +#117099 = LINE('',#117100,#117101); +#117100 = CARTESIAN_POINT('',(-0.419594812019,4.15,0.530776333563)); +#117101 = VECTOR('',#117102,1.); +#117102 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117103 = PCURVE('',#116899,#117104); +#117104 = DEFINITIONAL_REPRESENTATION('',(#117105),#117109); +#117105 = LINE('',#117106,#117107); +#117106 = CARTESIAN_POINT('',(-5.85,1.133910970711E-033)); +#117107 = VECTOR('',#117108,1.); +#117108 = DIRECTION('',(4.535643882845E-032,-1.)); +#117109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117110 = PCURVE('',#93659,#117111); +#117111 = DEFINITIONAL_REPRESENTATION('',(#117112),#117116); +#117112 = LINE('',#117113,#117114); +#117113 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#117114 = VECTOR('',#117115,1.); +#117115 = DIRECTION('',(1.,-1.021336205033E-016)); +#117116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117117 = ORIENTED_EDGE('',*,*,#116886,.F.); +#117118 = ORIENTED_EDGE('',*,*,#117119,.F.); +#117119 = EDGE_CURVE('',#117069,#116864,#117120,.T.); +#117120 = SURFACE_CURVE('',#117121,(#117125,#117132),.PCURVE_S1.); +#117121 = LINE('',#117122,#117123); +#117122 = CARTESIAN_POINT('',(-0.419594812019,4.35,0.530776333563)); +#117123 = VECTOR('',#117124,1.); +#117124 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117125 = PCURVE('',#116899,#117126); +#117126 = DEFINITIONAL_REPRESENTATION('',(#117127),#117131); +#117127 = LINE('',#117128,#117129); +#117128 = CARTESIAN_POINT('',(-5.65,-1.133910970711E-033)); +#117129 = VECTOR('',#117130,1.); +#117130 = DIRECTION('',(4.535643882845E-032,-1.)); +#117131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117132 = PCURVE('',#93715,#117133); +#117133 = DEFINITIONAL_REPRESENTATION('',(#117134),#117138); +#117134 = LINE('',#117135,#117136); +#117135 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#117136 = VECTOR('',#117137,1.); +#117137 = DIRECTION('',(-1.,-1.021336205033E-016)); +#117138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117139 = ADVANCED_FACE('',(#117140),#117086,.F.); +#117140 = FACE_BOUND('',#117141,.F.); +#117141 = EDGE_LOOP('',(#117142,#117143,#117166,#117211)); +#117142 = ORIENTED_EDGE('',*,*,#117068,.T.); +#117143 = ORIENTED_EDGE('',*,*,#117144,.F.); +#117144 = EDGE_CURVE('',#117145,#117071,#117147,.T.); +#117145 = VERTEX_POINT('',#117146); +#117146 = CARTESIAN_POINT('',(-0.303662633502,4.15,0.65)); +#117147 = SURFACE_CURVE('',#117148,(#117153,#117159),.PCURVE_S1.); +#117148 = CIRCLE('',#117149,0.119270391569); +#117149 = AXIS2_PLACEMENT_3D('',#117150,#117151,#117152); +#117150 = CARTESIAN_POINT('',(-0.30032442045,4.15,0.530776333563)); +#117151 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117152 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117153 = PCURVE('',#117086,#117154); +#117154 = DEFINITIONAL_REPRESENTATION('',(#117155),#117158); +#117155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117156,#117157), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#114764 = CARTESIAN_POINT('',(1.598788597134,5.85)); -#114765 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#114766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114767 = PCURVE('',#91267,#114768); -#114768 = DEFINITIONAL_REPRESENTATION('',(#114769),#114773); -#114769 = CIRCLE('',#114770,0.119270391569); -#114770 = AXIS2_PLACEMENT_2D('',#114771,#114772); -#114771 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#114772 = DIRECTION('',(0.E+000,1.)); -#114773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114774 = ORIENTED_EDGE('',*,*,#114775,.T.); -#114775 = EDGE_CURVE('',#114753,#114776,#114778,.T.); -#114776 = VERTEX_POINT('',#114777); -#114777 = CARTESIAN_POINT('',(-0.303662633502,4.35,0.65)); -#114778 = SURFACE_CURVE('',#114779,(#114783,#114812),.PCURVE_S1.); -#114779 = LINE('',#114780,#114781); -#114780 = CARTESIAN_POINT('',(-0.303662633502,4.35,0.65)); -#114781 = VECTOR('',#114782,1.); -#114782 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#114783 = PCURVE('',#114694,#114784); -#114784 = DEFINITIONAL_REPRESENTATION('',(#114785),#114811); -#114785 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114786,#114787,#114788, - #114789,#114790,#114791,#114792,#114793,#114794,#114795,#114796, - #114797,#114798,#114799,#114800,#114801,#114802,#114803,#114804, - #114805,#114806,#114807,#114808,#114809,#114810),.UNSPECIFIED.,.F., +#117156 = CARTESIAN_POINT('',(1.598788597134,5.85)); +#117157 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#117158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117159 = PCURVE('',#93659,#117160); +#117160 = DEFINITIONAL_REPRESENTATION('',(#117161),#117165); +#117161 = CIRCLE('',#117162,0.119270391569); +#117162 = AXIS2_PLACEMENT_2D('',#117163,#117164); +#117163 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#117164 = DIRECTION('',(0.E+000,1.)); +#117165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117166 = ORIENTED_EDGE('',*,*,#117167,.T.); +#117167 = EDGE_CURVE('',#117145,#117168,#117170,.T.); +#117168 = VERTEX_POINT('',#117169); +#117169 = CARTESIAN_POINT('',(-0.303662633502,4.35,0.65)); +#117170 = SURFACE_CURVE('',#117171,(#117175,#117204),.PCURVE_S1.); +#117171 = LINE('',#117172,#117173); +#117172 = CARTESIAN_POINT('',(-0.303662633502,4.35,0.65)); +#117173 = VECTOR('',#117174,1.); +#117174 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117175 = PCURVE('',#117086,#117176); +#117176 = DEFINITIONAL_REPRESENTATION('',(#117177),#117203); +#117177 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#117178,#117179,#117180, + #117181,#117182,#117183,#117184,#117185,#117186,#117187,#117188, + #117189,#117190,#117191,#117192,#117193,#117194,#117195,#117196, + #117197,#117198,#117199,#117200,#117201,#117202),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -141395,128 +144397,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.UNSPECIFIED.); -#114786 = CARTESIAN_POINT('',(1.598788597134,5.85)); -#114787 = CARTESIAN_POINT('',(1.598788597134,5.84696969697)); -#114788 = CARTESIAN_POINT('',(1.598788597134,5.840909090909)); -#114789 = CARTESIAN_POINT('',(1.598788597134,5.831818181818)); -#114790 = CARTESIAN_POINT('',(1.598788597134,5.822727272727)); -#114791 = CARTESIAN_POINT('',(1.598788597134,5.813636363636)); -#114792 = CARTESIAN_POINT('',(1.598788597134,5.804545454545)); -#114793 = CARTESIAN_POINT('',(1.598788597134,5.795454545455)); -#114794 = CARTESIAN_POINT('',(1.598788597134,5.786363636364)); -#114795 = CARTESIAN_POINT('',(1.598788597134,5.777272727273)); -#114796 = CARTESIAN_POINT('',(1.598788597134,5.768181818182)); -#114797 = CARTESIAN_POINT('',(1.598788597134,5.759090909091)); -#114798 = CARTESIAN_POINT('',(1.598788597134,5.75)); -#114799 = CARTESIAN_POINT('',(1.598788597134,5.740909090909)); -#114800 = CARTESIAN_POINT('',(1.598788597134,5.731818181818)); -#114801 = CARTESIAN_POINT('',(1.598788597134,5.722727272727)); -#114802 = CARTESIAN_POINT('',(1.598788597134,5.713636363636)); -#114803 = CARTESIAN_POINT('',(1.598788597134,5.704545454545)); -#114804 = CARTESIAN_POINT('',(1.598788597134,5.695454545455)); -#114805 = CARTESIAN_POINT('',(1.598788597134,5.686363636364)); -#114806 = CARTESIAN_POINT('',(1.598788597134,5.677272727273)); -#114807 = CARTESIAN_POINT('',(1.598788597134,5.668181818182)); -#114808 = CARTESIAN_POINT('',(1.598788597134,5.659090909091)); -#114809 = CARTESIAN_POINT('',(1.598788597134,5.65303030303)); -#114810 = CARTESIAN_POINT('',(1.598788597134,5.65)); -#114811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114812 = PCURVE('',#91295,#114813); -#114813 = DEFINITIONAL_REPRESENTATION('',(#114814),#114818); -#114814 = LINE('',#114815,#114816); -#114815 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#114816 = VECTOR('',#114817,1.); -#114817 = DIRECTION('',(4.440892098501E-016,1.)); -#114818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114819 = ORIENTED_EDGE('',*,*,#114820,.T.); -#114820 = EDGE_CURVE('',#114776,#114677,#114821,.T.); -#114821 = SURFACE_CURVE('',#114822,(#114827,#114833),.PCURVE_S1.); -#114822 = CIRCLE('',#114823,0.119270391569); -#114823 = AXIS2_PLACEMENT_3D('',#114824,#114825,#114826); -#114824 = CARTESIAN_POINT('',(-0.30032442045,4.35,0.530776333563)); -#114825 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114826 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114827 = PCURVE('',#114694,#114828); -#114828 = DEFINITIONAL_REPRESENTATION('',(#114829),#114832); -#114829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114830,#114831), +#117178 = CARTESIAN_POINT('',(1.598788597134,5.85)); +#117179 = CARTESIAN_POINT('',(1.598788597134,5.84696969697)); +#117180 = CARTESIAN_POINT('',(1.598788597134,5.840909090909)); +#117181 = CARTESIAN_POINT('',(1.598788597134,5.831818181818)); +#117182 = CARTESIAN_POINT('',(1.598788597134,5.822727272727)); +#117183 = CARTESIAN_POINT('',(1.598788597134,5.813636363636)); +#117184 = CARTESIAN_POINT('',(1.598788597134,5.804545454545)); +#117185 = CARTESIAN_POINT('',(1.598788597134,5.795454545455)); +#117186 = CARTESIAN_POINT('',(1.598788597134,5.786363636364)); +#117187 = CARTESIAN_POINT('',(1.598788597134,5.777272727273)); +#117188 = CARTESIAN_POINT('',(1.598788597134,5.768181818182)); +#117189 = CARTESIAN_POINT('',(1.598788597134,5.759090909091)); +#117190 = CARTESIAN_POINT('',(1.598788597134,5.75)); +#117191 = CARTESIAN_POINT('',(1.598788597134,5.740909090909)); +#117192 = CARTESIAN_POINT('',(1.598788597134,5.731818181818)); +#117193 = CARTESIAN_POINT('',(1.598788597134,5.722727272727)); +#117194 = CARTESIAN_POINT('',(1.598788597134,5.713636363636)); +#117195 = CARTESIAN_POINT('',(1.598788597134,5.704545454545)); +#117196 = CARTESIAN_POINT('',(1.598788597134,5.695454545455)); +#117197 = CARTESIAN_POINT('',(1.598788597134,5.686363636364)); +#117198 = CARTESIAN_POINT('',(1.598788597134,5.677272727273)); +#117199 = CARTESIAN_POINT('',(1.598788597134,5.668181818182)); +#117200 = CARTESIAN_POINT('',(1.598788597134,5.659090909091)); +#117201 = CARTESIAN_POINT('',(1.598788597134,5.65303030303)); +#117202 = CARTESIAN_POINT('',(1.598788597134,5.65)); +#117203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117204 = PCURVE('',#93687,#117205); +#117205 = DEFINITIONAL_REPRESENTATION('',(#117206),#117210); +#117206 = LINE('',#117207,#117208); +#117207 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#117208 = VECTOR('',#117209,1.); +#117209 = DIRECTION('',(4.440892098501E-016,1.)); +#117210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117211 = ORIENTED_EDGE('',*,*,#117212,.T.); +#117212 = EDGE_CURVE('',#117168,#117069,#117213,.T.); +#117213 = SURFACE_CURVE('',#117214,(#117219,#117225),.PCURVE_S1.); +#117214 = CIRCLE('',#117215,0.119270391569); +#117215 = AXIS2_PLACEMENT_3D('',#117216,#117217,#117218); +#117216 = CARTESIAN_POINT('',(-0.30032442045,4.35,0.530776333563)); +#117217 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117218 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117219 = PCURVE('',#117086,#117220); +#117220 = DEFINITIONAL_REPRESENTATION('',(#117221),#117224); +#117221 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117222,#117223), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#114830 = CARTESIAN_POINT('',(1.598788597134,5.65)); -#114831 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#114832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117222 = CARTESIAN_POINT('',(1.598788597134,5.65)); +#117223 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#117224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114833 = PCURVE('',#91323,#114834); -#114834 = DEFINITIONAL_REPRESENTATION('',(#114835),#114843); -#114835 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114836,#114837,#114838, - #114839,#114840,#114841,#114842),.UNSPECIFIED.,.T.,.F.) +#117225 = PCURVE('',#93715,#117226); +#117226 = DEFINITIONAL_REPRESENTATION('',(#117227),#117235); +#117227 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117228,#117229,#117230, + #117231,#117232,#117233,#117234),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#114836 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#114837 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#114838 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#114839 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#114840 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#114841 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#114842 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#114843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114844 = ADVANCED_FACE('',(#114845),#114619,.T.); -#114845 = FACE_BOUND('',#114846,.T.); -#114846 = EDGE_LOOP('',(#114847,#114848,#114871,#114916)); -#114847 = ORIENTED_EDGE('',*,*,#114601,.F.); -#114848 = ORIENTED_EDGE('',*,*,#114849,.F.); -#114849 = EDGE_CURVE('',#114850,#114602,#114852,.T.); -#114850 = VERTEX_POINT('',#114851); -#114851 = CARTESIAN_POINT('',(-0.304819755875,4.15,0.75)); -#114852 = SURFACE_CURVE('',#114853,(#114858,#114864),.PCURVE_S1.); -#114853 = CIRCLE('',#114854,0.2192697516); -#114854 = AXIS2_PLACEMENT_3D('',#114855,#114856,#114857); -#114855 = CARTESIAN_POINT('',(-0.30032442045,4.15,0.530776333563)); -#114856 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114857 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114858 = PCURVE('',#114619,#114859); -#114859 = DEFINITIONAL_REPRESENTATION('',(#114860),#114863); -#114860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114861,#114862), +#117228 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#117229 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#117230 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#117231 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#117232 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#117233 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#117234 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#117235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117236 = ADVANCED_FACE('',(#117237),#117011,.T.); +#117237 = FACE_BOUND('',#117238,.T.); +#117238 = EDGE_LOOP('',(#117239,#117240,#117263,#117308)); +#117239 = ORIENTED_EDGE('',*,*,#116993,.F.); +#117240 = ORIENTED_EDGE('',*,*,#117241,.F.); +#117241 = EDGE_CURVE('',#117242,#116994,#117244,.T.); +#117242 = VERTEX_POINT('',#117243); +#117243 = CARTESIAN_POINT('',(-0.304819755875,4.15,0.75)); +#117244 = SURFACE_CURVE('',#117245,(#117250,#117256),.PCURVE_S1.); +#117245 = CIRCLE('',#117246,0.2192697516); +#117246 = AXIS2_PLACEMENT_3D('',#117247,#117248,#117249); +#117247 = CARTESIAN_POINT('',(-0.30032442045,4.15,0.530776333563)); +#117248 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117249 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117250 = PCURVE('',#117011,#117251); +#117251 = DEFINITIONAL_REPRESENTATION('',(#117252),#117255); +#117252 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117253,#117254), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#114861 = CARTESIAN_POINT('',(1.591299156552,5.85)); -#114862 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#114863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114864 = PCURVE('',#91267,#114865); -#114865 = DEFINITIONAL_REPRESENTATION('',(#114866),#114870); -#114866 = CIRCLE('',#114867,0.2192697516); -#114867 = AXIS2_PLACEMENT_2D('',#114868,#114869); -#114868 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#114869 = DIRECTION('',(0.E+000,1.)); -#114870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114871 = ORIENTED_EDGE('',*,*,#114872,.F.); -#114872 = EDGE_CURVE('',#114873,#114850,#114875,.T.); -#114873 = VERTEX_POINT('',#114874); -#114874 = CARTESIAN_POINT('',(-0.304819755875,4.35,0.75)); -#114875 = SURFACE_CURVE('',#114876,(#114880,#114909),.PCURVE_S1.); -#114876 = LINE('',#114877,#114878); -#114877 = CARTESIAN_POINT('',(-0.304819755875,4.35,0.75)); -#114878 = VECTOR('',#114879,1.); -#114879 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114880 = PCURVE('',#114619,#114881); -#114881 = DEFINITIONAL_REPRESENTATION('',(#114882),#114908); -#114882 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#114883,#114884,#114885, - #114886,#114887,#114888,#114889,#114890,#114891,#114892,#114893, - #114894,#114895,#114896,#114897,#114898,#114899,#114900,#114901, - #114902,#114903,#114904,#114905,#114906,#114907),.UNSPECIFIED.,.F., +#117253 = CARTESIAN_POINT('',(1.591299156552,5.85)); +#117254 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#117255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117256 = PCURVE('',#93659,#117257); +#117257 = DEFINITIONAL_REPRESENTATION('',(#117258),#117262); +#117258 = CIRCLE('',#117259,0.2192697516); +#117259 = AXIS2_PLACEMENT_2D('',#117260,#117261); +#117260 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#117261 = DIRECTION('',(0.E+000,1.)); +#117262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117263 = ORIENTED_EDGE('',*,*,#117264,.F.); +#117264 = EDGE_CURVE('',#117265,#117242,#117267,.T.); +#117265 = VERTEX_POINT('',#117266); +#117266 = CARTESIAN_POINT('',(-0.304819755875,4.35,0.75)); +#117267 = SURFACE_CURVE('',#117268,(#117272,#117301),.PCURVE_S1.); +#117268 = LINE('',#117269,#117270); +#117269 = CARTESIAN_POINT('',(-0.304819755875,4.35,0.75)); +#117270 = VECTOR('',#117271,1.); +#117271 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117272 = PCURVE('',#117011,#117273); +#117273 = DEFINITIONAL_REPRESENTATION('',(#117274),#117300); +#117274 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#117275,#117276,#117277, + #117278,#117279,#117280,#117281,#117282,#117283,#117284,#117285, + #117286,#117287,#117288,#117289,#117290,#117291,#117292,#117293, + #117294,#117295,#117296,#117297,#117298,#117299),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -141525,956 +144527,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#114883 = CARTESIAN_POINT('',(1.591299156552,5.65)); -#114884 = CARTESIAN_POINT('',(1.591299156552,5.65303030303)); -#114885 = CARTESIAN_POINT('',(1.591299156552,5.659090909091)); -#114886 = CARTESIAN_POINT('',(1.591299156552,5.668181818182)); -#114887 = CARTESIAN_POINT('',(1.591299156552,5.677272727273)); -#114888 = CARTESIAN_POINT('',(1.591299156552,5.686363636364)); -#114889 = CARTESIAN_POINT('',(1.591299156552,5.695454545455)); -#114890 = CARTESIAN_POINT('',(1.591299156552,5.704545454545)); -#114891 = CARTESIAN_POINT('',(1.591299156552,5.713636363636)); -#114892 = CARTESIAN_POINT('',(1.591299156552,5.722727272727)); -#114893 = CARTESIAN_POINT('',(1.591299156552,5.731818181818)); -#114894 = CARTESIAN_POINT('',(1.591299156552,5.740909090909)); -#114895 = CARTESIAN_POINT('',(1.591299156552,5.75)); -#114896 = CARTESIAN_POINT('',(1.591299156552,5.759090909091)); -#114897 = CARTESIAN_POINT('',(1.591299156552,5.768181818182)); -#114898 = CARTESIAN_POINT('',(1.591299156552,5.777272727273)); -#114899 = CARTESIAN_POINT('',(1.591299156552,5.786363636364)); -#114900 = CARTESIAN_POINT('',(1.591299156552,5.795454545455)); -#114901 = CARTESIAN_POINT('',(1.591299156552,5.804545454545)); -#114902 = CARTESIAN_POINT('',(1.591299156552,5.813636363636)); -#114903 = CARTESIAN_POINT('',(1.591299156552,5.822727272727)); -#114904 = CARTESIAN_POINT('',(1.591299156552,5.831818181818)); -#114905 = CARTESIAN_POINT('',(1.591299156552,5.840909090909)); -#114906 = CARTESIAN_POINT('',(1.591299156552,5.84696969697)); -#114907 = CARTESIAN_POINT('',(1.591299156552,5.85)); -#114908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117275 = CARTESIAN_POINT('',(1.591299156552,5.65)); +#117276 = CARTESIAN_POINT('',(1.591299156552,5.65303030303)); +#117277 = CARTESIAN_POINT('',(1.591299156552,5.659090909091)); +#117278 = CARTESIAN_POINT('',(1.591299156552,5.668181818182)); +#117279 = CARTESIAN_POINT('',(1.591299156552,5.677272727273)); +#117280 = CARTESIAN_POINT('',(1.591299156552,5.686363636364)); +#117281 = CARTESIAN_POINT('',(1.591299156552,5.695454545455)); +#117282 = CARTESIAN_POINT('',(1.591299156552,5.704545454545)); +#117283 = CARTESIAN_POINT('',(1.591299156552,5.713636363636)); +#117284 = CARTESIAN_POINT('',(1.591299156552,5.722727272727)); +#117285 = CARTESIAN_POINT('',(1.591299156552,5.731818181818)); +#117286 = CARTESIAN_POINT('',(1.591299156552,5.740909090909)); +#117287 = CARTESIAN_POINT('',(1.591299156552,5.75)); +#117288 = CARTESIAN_POINT('',(1.591299156552,5.759090909091)); +#117289 = CARTESIAN_POINT('',(1.591299156552,5.768181818182)); +#117290 = CARTESIAN_POINT('',(1.591299156552,5.777272727273)); +#117291 = CARTESIAN_POINT('',(1.591299156552,5.786363636364)); +#117292 = CARTESIAN_POINT('',(1.591299156552,5.795454545455)); +#117293 = CARTESIAN_POINT('',(1.591299156552,5.804545454545)); +#117294 = CARTESIAN_POINT('',(1.591299156552,5.813636363636)); +#117295 = CARTESIAN_POINT('',(1.591299156552,5.822727272727)); +#117296 = CARTESIAN_POINT('',(1.591299156552,5.831818181818)); +#117297 = CARTESIAN_POINT('',(1.591299156552,5.840909090909)); +#117298 = CARTESIAN_POINT('',(1.591299156552,5.84696969697)); +#117299 = CARTESIAN_POINT('',(1.591299156552,5.85)); +#117300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114909 = PCURVE('',#91349,#114910); -#114910 = DEFINITIONAL_REPRESENTATION('',(#114911),#114915); -#114911 = LINE('',#114912,#114913); -#114912 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#114913 = VECTOR('',#114914,1.); -#114914 = DIRECTION('',(4.440892098501E-016,-1.)); -#114915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114916 = ORIENTED_EDGE('',*,*,#114917,.T.); -#114917 = EDGE_CURVE('',#114873,#114604,#114918,.T.); -#114918 = SURFACE_CURVE('',#114919,(#114924,#114930),.PCURVE_S1.); -#114919 = CIRCLE('',#114920,0.2192697516); -#114920 = AXIS2_PLACEMENT_3D('',#114921,#114922,#114923); -#114921 = CARTESIAN_POINT('',(-0.30032442045,4.35,0.530776333563)); -#114922 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#114923 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#114924 = PCURVE('',#114619,#114925); -#114925 = DEFINITIONAL_REPRESENTATION('',(#114926),#114929); -#114926 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#114927,#114928), +#117301 = PCURVE('',#93741,#117302); +#117302 = DEFINITIONAL_REPRESENTATION('',(#117303),#117307); +#117303 = LINE('',#117304,#117305); +#117304 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#117305 = VECTOR('',#117306,1.); +#117306 = DIRECTION('',(4.440892098501E-016,-1.)); +#117307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117308 = ORIENTED_EDGE('',*,*,#117309,.T.); +#117309 = EDGE_CURVE('',#117265,#116996,#117310,.T.); +#117310 = SURFACE_CURVE('',#117311,(#117316,#117322),.PCURVE_S1.); +#117311 = CIRCLE('',#117312,0.2192697516); +#117312 = AXIS2_PLACEMENT_3D('',#117313,#117314,#117315); +#117313 = CARTESIAN_POINT('',(-0.30032442045,4.35,0.530776333563)); +#117314 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117315 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117316 = PCURVE('',#117011,#117317); +#117317 = DEFINITIONAL_REPRESENTATION('',(#117318),#117321); +#117318 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117319,#117320), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#114927 = CARTESIAN_POINT('',(1.591299156552,5.65)); -#114928 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#114929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117319 = CARTESIAN_POINT('',(1.591299156552,5.65)); +#117320 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#117321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#114930 = PCURVE('',#91323,#114931); -#114931 = DEFINITIONAL_REPRESENTATION('',(#114932),#114940); -#114932 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#114933,#114934,#114935, - #114936,#114937,#114938,#114939),.UNSPECIFIED.,.T.,.F.) +#117322 = PCURVE('',#93715,#117323); +#117323 = DEFINITIONAL_REPRESENTATION('',(#117324),#117332); +#117324 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117325,#117326,#117327, + #117328,#117329,#117330,#117331),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#114933 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#114934 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#114935 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#114936 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#114937 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#114938 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#114939 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#114940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114941 = ADVANCED_FACE('',(#114942),#91295,.T.); -#114942 = FACE_BOUND('',#114943,.T.); -#114943 = EDGE_LOOP('',(#114944,#114965,#114966,#114987)); -#114944 = ORIENTED_EDGE('',*,*,#114945,.F.); -#114945 = EDGE_CURVE('',#114753,#91252,#114946,.T.); -#114946 = SURFACE_CURVE('',#114947,(#114951,#114958),.PCURVE_S1.); -#114947 = LINE('',#114948,#114949); -#114948 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.65)); -#114949 = VECTOR('',#114950,1.); -#114950 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114951 = PCURVE('',#91295,#114952); -#114952 = DEFINITIONAL_REPRESENTATION('',(#114953),#114957); -#114953 = LINE('',#114954,#114955); -#114954 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#114955 = VECTOR('',#114956,1.); -#114956 = DIRECTION('',(-1.,-4.804757279354E-063)); -#114957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114958 = PCURVE('',#91267,#114959); -#114959 = DEFINITIONAL_REPRESENTATION('',(#114960),#114964); -#114960 = LINE('',#114961,#114962); -#114961 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114962 = VECTOR('',#114963,1.); -#114963 = DIRECTION('',(-3.563627120235E-016,1.)); -#114964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114965 = ORIENTED_EDGE('',*,*,#114775,.T.); -#114966 = ORIENTED_EDGE('',*,*,#114967,.T.); -#114967 = EDGE_CURVE('',#114776,#91280,#114968,.T.); -#114968 = SURFACE_CURVE('',#114969,(#114973,#114980),.PCURVE_S1.); -#114969 = LINE('',#114970,#114971); -#114970 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); -#114971 = VECTOR('',#114972,1.); -#114972 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114973 = PCURVE('',#91295,#114974); -#114974 = DEFINITIONAL_REPRESENTATION('',(#114975),#114979); -#114975 = LINE('',#114976,#114977); -#114976 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114977 = VECTOR('',#114978,1.); -#114978 = DIRECTION('',(-1.,-4.804757279354E-063)); -#114979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114980 = PCURVE('',#91323,#114981); -#114981 = DEFINITIONAL_REPRESENTATION('',(#114982),#114986); -#114982 = LINE('',#114983,#114984); -#114983 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#114984 = VECTOR('',#114985,1.); -#114985 = DIRECTION('',(3.563627120235E-016,1.)); -#114986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#114987 = ORIENTED_EDGE('',*,*,#91279,.F.); -#114988 = ADVANCED_FACE('',(#114989),#91267,.T.); -#114989 = FACE_BOUND('',#114990,.T.); -#114990 = EDGE_LOOP('',(#114991,#115012,#115013,#115014,#115015,#115016, - #115037,#115038,#115039,#115040,#115041,#115042)); -#114991 = ORIENTED_EDGE('',*,*,#114992,.F.); -#114992 = EDGE_CURVE('',#114850,#91250,#114993,.T.); -#114993 = SURFACE_CURVE('',#114994,(#114998,#115005),.PCURVE_S1.); -#114994 = LINE('',#114995,#114996); -#114995 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.75)); -#114996 = VECTOR('',#114997,1.); -#114997 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#114998 = PCURVE('',#91267,#114999); -#114999 = DEFINITIONAL_REPRESENTATION('',(#115000),#115004); -#115000 = LINE('',#115001,#115002); -#115001 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#115002 = VECTOR('',#115003,1.); -#115003 = DIRECTION('',(-3.563627120235E-016,1.)); -#115004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115005 = PCURVE('',#91349,#115006); -#115006 = DEFINITIONAL_REPRESENTATION('',(#115007),#115011); -#115007 = LINE('',#115008,#115009); -#115008 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#115009 = VECTOR('',#115010,1.); -#115010 = DIRECTION('',(1.,-4.804757279354E-063)); -#115011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115012 = ORIENTED_EDGE('',*,*,#114849,.T.); -#115013 = ORIENTED_EDGE('',*,*,#114652,.T.); -#115014 = ORIENTED_EDGE('',*,*,#114572,.T.); -#115015 = ORIENTED_EDGE('',*,*,#114369,.T.); -#115016 = ORIENTED_EDGE('',*,*,#115017,.F.); -#115017 = EDGE_CURVE('',#114233,#114340,#115018,.T.); -#115018 = SURFACE_CURVE('',#115019,(#115023,#115030),.PCURVE_S1.); -#115019 = LINE('',#115020,#115021); -#115020 = CARTESIAN_POINT('',(-1.,4.15,1.159810404338E-002)); -#115021 = VECTOR('',#115022,1.); -#115022 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#115023 = PCURVE('',#91267,#115024); -#115024 = DEFINITIONAL_REPRESENTATION('',(#115025),#115029); -#115025 = LINE('',#115026,#115027); -#115026 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#115027 = VECTOR('',#115028,1.); -#115028 = DIRECTION('',(-1.,-2.101748079665E-016)); -#115029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115030 = PCURVE('',#114253,#115031); -#115031 = DEFINITIONAL_REPRESENTATION('',(#115032),#115036); -#115032 = LINE('',#115033,#115034); -#115033 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#115034 = VECTOR('',#115035,1.); -#115035 = DIRECTION('',(-1.194699204908E-017,1.)); -#115036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115037 = ORIENTED_EDGE('',*,*,#114315,.F.); -#115038 = ORIENTED_EDGE('',*,*,#114443,.F.); -#115039 = ORIENTED_EDGE('',*,*,#114705,.F.); -#115040 = ORIENTED_EDGE('',*,*,#114752,.F.); -#115041 = ORIENTED_EDGE('',*,*,#114945,.T.); -#115042 = ORIENTED_EDGE('',*,*,#91249,.F.); -#115043 = ADVANCED_FACE('',(#115044),#91349,.T.); -#115044 = FACE_BOUND('',#115045,.T.); -#115045 = EDGE_LOOP('',(#115046,#115067,#115068,#115069)); -#115046 = ORIENTED_EDGE('',*,*,#115047,.F.); -#115047 = EDGE_CURVE('',#114873,#91308,#115048,.T.); -#115048 = SURFACE_CURVE('',#115049,(#115053,#115060),.PCURVE_S1.); -#115049 = LINE('',#115050,#115051); -#115050 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.75)); -#115051 = VECTOR('',#115052,1.); -#115052 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#115053 = PCURVE('',#91349,#115054); -#115054 = DEFINITIONAL_REPRESENTATION('',(#115055),#115059); -#115055 = LINE('',#115056,#115057); -#115056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115057 = VECTOR('',#115058,1.); -#115058 = DIRECTION('',(1.,-4.804757279354E-063)); -#115059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115060 = PCURVE('',#91323,#115061); -#115061 = DEFINITIONAL_REPRESENTATION('',(#115062),#115066); -#115062 = LINE('',#115063,#115064); -#115063 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#115064 = VECTOR('',#115065,1.); -#115065 = DIRECTION('',(3.563627120235E-016,1.)); -#115066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115067 = ORIENTED_EDGE('',*,*,#114872,.T.); -#115068 = ORIENTED_EDGE('',*,*,#114992,.T.); -#115069 = ORIENTED_EDGE('',*,*,#91335,.F.); -#115070 = ADVANCED_FACE('',(#115071),#91323,.T.); -#115071 = FACE_BOUND('',#115072,.T.); -#115072 = EDGE_LOOP('',(#115073,#115074,#115075,#115076,#115077,#115078, - #115099,#115100,#115101,#115102,#115103,#115104)); -#115073 = ORIENTED_EDGE('',*,*,#114967,.F.); -#115074 = ORIENTED_EDGE('',*,*,#114820,.T.); -#115075 = ORIENTED_EDGE('',*,*,#114727,.T.); -#115076 = ORIENTED_EDGE('',*,*,#114471,.T.); -#115077 = ORIENTED_EDGE('',*,*,#114265,.T.); -#115078 = ORIENTED_EDGE('',*,*,#115079,.F.); -#115079 = EDGE_CURVE('',#114342,#114231,#115080,.T.); -#115080 = SURFACE_CURVE('',#115081,(#115085,#115092),.PCURVE_S1.); -#115081 = LINE('',#115082,#115083); -#115082 = CARTESIAN_POINT('',(-1.,4.35,1.159810404338E-002)); -#115083 = VECTOR('',#115084,1.); -#115084 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#115085 = PCURVE('',#91323,#115086); -#115086 = DEFINITIONAL_REPRESENTATION('',(#115087),#115091); -#115087 = LINE('',#115088,#115089); -#115088 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#115089 = VECTOR('',#115090,1.); -#115090 = DIRECTION('',(-1.,2.101748079665E-016)); -#115091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117325 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#117326 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#117327 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#117328 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#117329 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#117330 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#117331 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#117332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117333 = ADVANCED_FACE('',(#117334),#93687,.T.); +#117334 = FACE_BOUND('',#117335,.T.); +#117335 = EDGE_LOOP('',(#117336,#117357,#117358,#117379)); +#117336 = ORIENTED_EDGE('',*,*,#117337,.F.); +#117337 = EDGE_CURVE('',#117145,#93644,#117338,.T.); +#117338 = SURFACE_CURVE('',#117339,(#117343,#117350),.PCURVE_S1.); +#117339 = LINE('',#117340,#117341); +#117340 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.65)); +#117341 = VECTOR('',#117342,1.); +#117342 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#117343 = PCURVE('',#93687,#117344); +#117344 = DEFINITIONAL_REPRESENTATION('',(#117345),#117349); +#117345 = LINE('',#117346,#117347); +#117346 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#117347 = VECTOR('',#117348,1.); +#117348 = DIRECTION('',(-1.,-4.804757279354E-063)); +#117349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117350 = PCURVE('',#93659,#117351); +#117351 = DEFINITIONAL_REPRESENTATION('',(#117352),#117356); +#117352 = LINE('',#117353,#117354); +#117353 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117354 = VECTOR('',#117355,1.); +#117355 = DIRECTION('',(-3.563627120235E-016,1.)); +#117356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117357 = ORIENTED_EDGE('',*,*,#117167,.T.); +#117358 = ORIENTED_EDGE('',*,*,#117359,.T.); +#117359 = EDGE_CURVE('',#117168,#93672,#117360,.T.); +#117360 = SURFACE_CURVE('',#117361,(#117365,#117372),.PCURVE_S1.); +#117361 = LINE('',#117362,#117363); +#117362 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.65)); +#117363 = VECTOR('',#117364,1.); +#117364 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#117365 = PCURVE('',#93687,#117366); +#117366 = DEFINITIONAL_REPRESENTATION('',(#117367),#117371); +#117367 = LINE('',#117368,#117369); +#117368 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117369 = VECTOR('',#117370,1.); +#117370 = DIRECTION('',(-1.,-4.804757279354E-063)); +#117371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117372 = PCURVE('',#93715,#117373); +#117373 = DEFINITIONAL_REPRESENTATION('',(#117374),#117378); +#117374 = LINE('',#117375,#117376); +#117375 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117376 = VECTOR('',#117377,1.); +#117377 = DIRECTION('',(3.563627120235E-016,1.)); +#117378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117379 = ORIENTED_EDGE('',*,*,#93671,.F.); +#117380 = ADVANCED_FACE('',(#117381),#93659,.T.); +#117381 = FACE_BOUND('',#117382,.T.); +#117382 = EDGE_LOOP('',(#117383,#117404,#117405,#117406,#117407,#117408, + #117429,#117430,#117431,#117432,#117433,#117434)); +#117383 = ORIENTED_EDGE('',*,*,#117384,.F.); +#117384 = EDGE_CURVE('',#117242,#93642,#117385,.T.); +#117385 = SURFACE_CURVE('',#117386,(#117390,#117397),.PCURVE_S1.); +#117386 = LINE('',#117387,#117388); +#117387 = CARTESIAN_POINT('',(-0.527847992439,4.15,0.75)); +#117388 = VECTOR('',#117389,1.); +#117389 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#117390 = PCURVE('',#93659,#117391); +#117391 = DEFINITIONAL_REPRESENTATION('',(#117392),#117396); +#117392 = LINE('',#117393,#117394); +#117393 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#117394 = VECTOR('',#117395,1.); +#117395 = DIRECTION('',(-3.563627120235E-016,1.)); +#117396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117397 = PCURVE('',#93741,#117398); +#117398 = DEFINITIONAL_REPRESENTATION('',(#117399),#117403); +#117399 = LINE('',#117400,#117401); +#117400 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#117401 = VECTOR('',#117402,1.); +#117402 = DIRECTION('',(1.,-4.804757279354E-063)); +#117403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117404 = ORIENTED_EDGE('',*,*,#117241,.T.); +#117405 = ORIENTED_EDGE('',*,*,#117044,.T.); +#117406 = ORIENTED_EDGE('',*,*,#116964,.T.); +#117407 = ORIENTED_EDGE('',*,*,#116761,.T.); +#117408 = ORIENTED_EDGE('',*,*,#117409,.F.); +#117409 = EDGE_CURVE('',#116625,#116732,#117410,.T.); +#117410 = SURFACE_CURVE('',#117411,(#117415,#117422),.PCURVE_S1.); +#117411 = LINE('',#117412,#117413); +#117412 = CARTESIAN_POINT('',(-1.,4.15,1.159810404338E-002)); +#117413 = VECTOR('',#117414,1.); +#117414 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#117415 = PCURVE('',#93659,#117416); +#117416 = DEFINITIONAL_REPRESENTATION('',(#117417),#117421); +#117417 = LINE('',#117418,#117419); +#117418 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#117419 = VECTOR('',#117420,1.); +#117420 = DIRECTION('',(-1.,-2.101748079665E-016)); +#117421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117422 = PCURVE('',#116645,#117423); +#117423 = DEFINITIONAL_REPRESENTATION('',(#117424),#117428); +#117424 = LINE('',#117425,#117426); +#117425 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#117426 = VECTOR('',#117427,1.); +#117427 = DIRECTION('',(-1.194699204908E-017,1.)); +#117428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117429 = ORIENTED_EDGE('',*,*,#116707,.F.); +#117430 = ORIENTED_EDGE('',*,*,#116835,.F.); +#117431 = ORIENTED_EDGE('',*,*,#117097,.F.); +#117432 = ORIENTED_EDGE('',*,*,#117144,.F.); +#117433 = ORIENTED_EDGE('',*,*,#117337,.T.); +#117434 = ORIENTED_EDGE('',*,*,#93641,.F.); +#117435 = ADVANCED_FACE('',(#117436),#93741,.T.); +#117436 = FACE_BOUND('',#117437,.T.); +#117437 = EDGE_LOOP('',(#117438,#117459,#117460,#117461)); +#117438 = ORIENTED_EDGE('',*,*,#117439,.F.); +#117439 = EDGE_CURVE('',#117265,#93700,#117440,.T.); +#117440 = SURFACE_CURVE('',#117441,(#117445,#117452),.PCURVE_S1.); +#117441 = LINE('',#117442,#117443); +#117442 = CARTESIAN_POINT('',(-0.527847992439,4.35,0.75)); +#117443 = VECTOR('',#117444,1.); +#117444 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#117445 = PCURVE('',#93741,#117446); +#117446 = DEFINITIONAL_REPRESENTATION('',(#117447),#117451); +#117447 = LINE('',#117448,#117449); +#117448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117449 = VECTOR('',#117450,1.); +#117450 = DIRECTION('',(1.,-4.804757279354E-063)); +#117451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117452 = PCURVE('',#93715,#117453); +#117453 = DEFINITIONAL_REPRESENTATION('',(#117454),#117458); +#117454 = LINE('',#117455,#117456); +#117455 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#117456 = VECTOR('',#117457,1.); +#117457 = DIRECTION('',(3.563627120235E-016,1.)); +#117458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117459 = ORIENTED_EDGE('',*,*,#117264,.T.); +#117460 = ORIENTED_EDGE('',*,*,#117384,.T.); +#117461 = ORIENTED_EDGE('',*,*,#93727,.F.); +#117462 = ADVANCED_FACE('',(#117463),#93715,.T.); +#117463 = FACE_BOUND('',#117464,.T.); +#117464 = EDGE_LOOP('',(#117465,#117466,#117467,#117468,#117469,#117470, + #117491,#117492,#117493,#117494,#117495,#117496)); +#117465 = ORIENTED_EDGE('',*,*,#117359,.F.); +#117466 = ORIENTED_EDGE('',*,*,#117212,.T.); +#117467 = ORIENTED_EDGE('',*,*,#117119,.T.); +#117468 = ORIENTED_EDGE('',*,*,#116863,.T.); +#117469 = ORIENTED_EDGE('',*,*,#116657,.T.); +#117470 = ORIENTED_EDGE('',*,*,#117471,.F.); +#117471 = EDGE_CURVE('',#116734,#116623,#117472,.T.); +#117472 = SURFACE_CURVE('',#117473,(#117477,#117484),.PCURVE_S1.); +#117473 = LINE('',#117474,#117475); +#117474 = CARTESIAN_POINT('',(-1.,4.35,1.159810404338E-002)); +#117475 = VECTOR('',#117476,1.); +#117476 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#117477 = PCURVE('',#93715,#117478); +#117478 = DEFINITIONAL_REPRESENTATION('',(#117479),#117483); +#117479 = LINE('',#117480,#117481); +#117480 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#117481 = VECTOR('',#117482,1.); +#117482 = DIRECTION('',(-1.,2.101748079665E-016)); +#117483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117484 = PCURVE('',#116645,#117485); +#117485 = DEFINITIONAL_REPRESENTATION('',(#117486),#117490); +#117486 = LINE('',#117487,#117488); +#117487 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#117488 = VECTOR('',#117489,1.); +#117489 = DIRECTION('',(1.194699204908E-017,-1.)); +#117490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115092 = PCURVE('',#114253,#115093); -#115093 = DEFINITIONAL_REPRESENTATION('',(#115094),#115098); -#115094 = LINE('',#115095,#115096); -#115095 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#115096 = VECTOR('',#115097,1.); -#115097 = DIRECTION('',(1.194699204908E-017,-1.)); -#115098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115099 = ORIENTED_EDGE('',*,*,#114419,.F.); -#115100 = ORIENTED_EDGE('',*,*,#114522,.F.); -#115101 = ORIENTED_EDGE('',*,*,#114630,.F.); -#115102 = ORIENTED_EDGE('',*,*,#114917,.F.); -#115103 = ORIENTED_EDGE('',*,*,#115047,.T.); -#115104 = ORIENTED_EDGE('',*,*,#91307,.F.); -#115105 = ADVANCED_FACE('',(#115106),#114253,.T.); -#115106 = FACE_BOUND('',#115107,.T.); -#115107 = EDGE_LOOP('',(#115108,#115109,#115110,#115111)); -#115108 = ORIENTED_EDGE('',*,*,#115017,.T.); -#115109 = ORIENTED_EDGE('',*,*,#114339,.T.); -#115110 = ORIENTED_EDGE('',*,*,#115079,.T.); -#115111 = ORIENTED_EDGE('',*,*,#114230,.T.); -#115112 = ADVANCED_FACE('',(#115113),#115127,.F.); -#115113 = FACE_BOUND('',#115114,.T.); -#115114 = EDGE_LOOP('',(#115115,#115150,#115173,#115200)); -#115115 = ORIENTED_EDGE('',*,*,#115116,.F.); -#115116 = EDGE_CURVE('',#115117,#115119,#115121,.T.); -#115117 = VERTEX_POINT('',#115118); -#115118 = CARTESIAN_POINT('',(-1.,4.85,-0.308197125857)); -#115119 = VERTEX_POINT('',#115120); -#115120 = CARTESIAN_POINT('',(-1.,4.65,-0.308197125857)); -#115121 = SURFACE_CURVE('',#115122,(#115126,#115138),.PCURVE_S1.); -#115122 = LINE('',#115123,#115124); -#115123 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#115124 = VECTOR('',#115125,1.); -#115125 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115126 = PCURVE('',#115127,#115132); -#115127 = PLANE('',#115128); -#115128 = AXIS2_PLACEMENT_3D('',#115129,#115130,#115131); -#115129 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#115130 = DIRECTION('',(0.E+000,0.E+000,1.)); -#115131 = DIRECTION('',(1.,0.E+000,0.E+000)); -#115132 = DEFINITIONAL_REPRESENTATION('',(#115133),#115137); -#115133 = LINE('',#115134,#115135); -#115134 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#115135 = VECTOR('',#115136,1.); -#115136 = DIRECTION('',(4.440892098501E-016,-1.)); -#115137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115138 = PCURVE('',#115139,#115144); -#115139 = PLANE('',#115140); -#115140 = AXIS2_PLACEMENT_3D('',#115141,#115142,#115143); -#115141 = CARTESIAN_POINT('',(-1.,4.75,-0.258196742327)); -#115142 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#115143 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115144 = DEFINITIONAL_REPRESENTATION('',(#115145),#115149); -#115145 = LINE('',#115146,#115147); -#115146 = CARTESIAN_POINT('',(-5.25,-5.000038352949E-002)); -#115147 = VECTOR('',#115148,1.); -#115148 = DIRECTION('',(1.,0.E+000)); -#115149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115150 = ORIENTED_EDGE('',*,*,#115151,.F.); -#115151 = EDGE_CURVE('',#115152,#115117,#115154,.T.); -#115152 = VERTEX_POINT('',#115153); -#115153 = CARTESIAN_POINT('',(-0.74341632541,4.85,-0.308197125857)); -#115154 = SURFACE_CURVE('',#115155,(#115159,#115166),.PCURVE_S1.); -#115155 = LINE('',#115156,#115157); -#115156 = CARTESIAN_POINT('',(-0.74341632541,4.85,-0.308197125857)); -#115157 = VECTOR('',#115158,1.); -#115158 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#115159 = PCURVE('',#115127,#115160); -#115160 = DEFINITIONAL_REPRESENTATION('',(#115161),#115165); -#115161 = LINE('',#115162,#115163); -#115162 = CARTESIAN_POINT('',(2.331468351713E-015,-5.15)); -#115163 = VECTOR('',#115164,1.); -#115164 = DIRECTION('',(-1.,0.E+000)); -#115165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115166 = PCURVE('',#91209,#115167); -#115167 = DEFINITIONAL_REPRESENTATION('',(#115168),#115172); -#115168 = LINE('',#115169,#115170); -#115169 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#115170 = VECTOR('',#115171,1.); -#115171 = DIRECTION('',(0.E+000,-1.)); -#115172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115173 = ORIENTED_EDGE('',*,*,#115174,.F.); -#115174 = EDGE_CURVE('',#115175,#115152,#115177,.T.); -#115175 = VERTEX_POINT('',#115176); -#115176 = CARTESIAN_POINT('',(-0.74341632541,4.65,-0.308197125857)); -#115177 = SURFACE_CURVE('',#115178,(#115182,#115189),.PCURVE_S1.); -#115178 = LINE('',#115179,#115180); -#115179 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#115180 = VECTOR('',#115181,1.); -#115181 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115182 = PCURVE('',#115127,#115183); -#115183 = DEFINITIONAL_REPRESENTATION('',(#115184),#115188); -#115184 = LINE('',#115185,#115186); -#115185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115186 = VECTOR('',#115187,1.); -#115187 = DIRECTION('',(-4.440892098501E-016,1.)); -#115188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115189 = PCURVE('',#115190,#115195); -#115190 = CYLINDRICAL_SURFACE('',#115191,0.308574064194); -#115191 = AXIS2_PLACEMENT_3D('',#115192,#115193,#115194); -#115192 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#115193 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115194 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115195 = DEFINITIONAL_REPRESENTATION('',(#115196),#115199); -#115196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115197,#115198), +#117491 = ORIENTED_EDGE('',*,*,#116811,.F.); +#117492 = ORIENTED_EDGE('',*,*,#116914,.F.); +#117493 = ORIENTED_EDGE('',*,*,#117022,.F.); +#117494 = ORIENTED_EDGE('',*,*,#117309,.F.); +#117495 = ORIENTED_EDGE('',*,*,#117439,.T.); +#117496 = ORIENTED_EDGE('',*,*,#93699,.F.); +#117497 = ADVANCED_FACE('',(#117498),#116645,.T.); +#117498 = FACE_BOUND('',#117499,.T.); +#117499 = EDGE_LOOP('',(#117500,#117501,#117502,#117503)); +#117500 = ORIENTED_EDGE('',*,*,#117409,.T.); +#117501 = ORIENTED_EDGE('',*,*,#116731,.T.); +#117502 = ORIENTED_EDGE('',*,*,#117471,.T.); +#117503 = ORIENTED_EDGE('',*,*,#116622,.T.); +#117504 = ADVANCED_FACE('',(#117505),#117519,.F.); +#117505 = FACE_BOUND('',#117506,.T.); +#117506 = EDGE_LOOP('',(#117507,#117542,#117565,#117592)); +#117507 = ORIENTED_EDGE('',*,*,#117508,.F.); +#117508 = EDGE_CURVE('',#117509,#117511,#117513,.T.); +#117509 = VERTEX_POINT('',#117510); +#117510 = CARTESIAN_POINT('',(-1.,4.85,-0.308197125857)); +#117511 = VERTEX_POINT('',#117512); +#117512 = CARTESIAN_POINT('',(-1.,4.65,-0.308197125857)); +#117513 = SURFACE_CURVE('',#117514,(#117518,#117530),.PCURVE_S1.); +#117514 = LINE('',#117515,#117516); +#117515 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#117516 = VECTOR('',#117517,1.); +#117517 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117518 = PCURVE('',#117519,#117524); +#117519 = PLANE('',#117520); +#117520 = AXIS2_PLACEMENT_3D('',#117521,#117522,#117523); +#117521 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#117522 = DIRECTION('',(0.E+000,0.E+000,1.)); +#117523 = DIRECTION('',(1.,0.E+000,0.E+000)); +#117524 = DEFINITIONAL_REPRESENTATION('',(#117525),#117529); +#117525 = LINE('',#117526,#117527); +#117526 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#117527 = VECTOR('',#117528,1.); +#117528 = DIRECTION('',(4.440892098501E-016,-1.)); +#117529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117530 = PCURVE('',#117531,#117536); +#117531 = PLANE('',#117532); +#117532 = AXIS2_PLACEMENT_3D('',#117533,#117534,#117535); +#117533 = CARTESIAN_POINT('',(-1.,4.75,-0.258196742327)); +#117534 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#117535 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117536 = DEFINITIONAL_REPRESENTATION('',(#117537),#117541); +#117537 = LINE('',#117538,#117539); +#117538 = CARTESIAN_POINT('',(-5.25,-5.000038352949E-002)); +#117539 = VECTOR('',#117540,1.); +#117540 = DIRECTION('',(1.,0.E+000)); +#117541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117542 = ORIENTED_EDGE('',*,*,#117543,.F.); +#117543 = EDGE_CURVE('',#117544,#117509,#117546,.T.); +#117544 = VERTEX_POINT('',#117545); +#117545 = CARTESIAN_POINT('',(-0.74341632541,4.85,-0.308197125857)); +#117546 = SURFACE_CURVE('',#117547,(#117551,#117558),.PCURVE_S1.); +#117547 = LINE('',#117548,#117549); +#117548 = CARTESIAN_POINT('',(-0.74341632541,4.85,-0.308197125857)); +#117549 = VECTOR('',#117550,1.); +#117550 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#117551 = PCURVE('',#117519,#117552); +#117552 = DEFINITIONAL_REPRESENTATION('',(#117553),#117557); +#117553 = LINE('',#117554,#117555); +#117554 = CARTESIAN_POINT('',(2.331468351713E-015,-5.15)); +#117555 = VECTOR('',#117556,1.); +#117556 = DIRECTION('',(-1.,0.E+000)); +#117557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117558 = PCURVE('',#93601,#117559); +#117559 = DEFINITIONAL_REPRESENTATION('',(#117560),#117564); +#117560 = LINE('',#117561,#117562); +#117561 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#117562 = VECTOR('',#117563,1.); +#117563 = DIRECTION('',(0.E+000,-1.)); +#117564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117565 = ORIENTED_EDGE('',*,*,#117566,.F.); +#117566 = EDGE_CURVE('',#117567,#117544,#117569,.T.); +#117567 = VERTEX_POINT('',#117568); +#117568 = CARTESIAN_POINT('',(-0.74341632541,4.65,-0.308197125857)); +#117569 = SURFACE_CURVE('',#117570,(#117574,#117581),.PCURVE_S1.); +#117570 = LINE('',#117571,#117572); +#117571 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#117572 = VECTOR('',#117573,1.); +#117573 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117574 = PCURVE('',#117519,#117575); +#117575 = DEFINITIONAL_REPRESENTATION('',(#117576),#117580); +#117576 = LINE('',#117577,#117578); +#117577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117578 = VECTOR('',#117579,1.); +#117579 = DIRECTION('',(-4.440892098501E-016,1.)); +#117580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117581 = PCURVE('',#117582,#117587); +#117582 = CYLINDRICAL_SURFACE('',#117583,0.308574064194); +#117583 = AXIS2_PLACEMENT_3D('',#117584,#117585,#117586); +#117584 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#117585 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117586 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117587 = DEFINITIONAL_REPRESENTATION('',(#117588),#117591); +#117588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117589,#117590), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#115197 = CARTESIAN_POINT('',(4.761821717947,-5.35)); -#115198 = CARTESIAN_POINT('',(4.761821717947,-5.15)); -#115199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115200 = ORIENTED_EDGE('',*,*,#115201,.T.); -#115201 = EDGE_CURVE('',#115175,#115119,#115202,.T.); -#115202 = SURFACE_CURVE('',#115203,(#115207,#115214),.PCURVE_S1.); -#115203 = LINE('',#115204,#115205); -#115204 = CARTESIAN_POINT('',(-0.74341632541,4.65,-0.308197125857)); -#115205 = VECTOR('',#115206,1.); -#115206 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#115207 = PCURVE('',#115127,#115208); -#115208 = DEFINITIONAL_REPRESENTATION('',(#115209),#115213); -#115209 = LINE('',#115210,#115211); -#115210 = CARTESIAN_POINT('',(2.553512956638E-015,-5.35)); -#115211 = VECTOR('',#115212,1.); -#115212 = DIRECTION('',(-1.,0.E+000)); -#115213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115214 = PCURVE('',#91153,#115215); -#115215 = DEFINITIONAL_REPRESENTATION('',(#115216),#115220); -#115216 = LINE('',#115217,#115218); -#115217 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#115218 = VECTOR('',#115219,1.); -#115219 = DIRECTION('',(0.E+000,-1.)); -#115220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115221 = ADVANCED_FACE('',(#115222),#115236,.F.); -#115222 = FACE_BOUND('',#115223,.T.); -#115223 = EDGE_LOOP('',(#115224,#115254,#115277,#115304)); -#115224 = ORIENTED_EDGE('',*,*,#115225,.F.); -#115225 = EDGE_CURVE('',#115226,#115228,#115230,.T.); -#115226 = VERTEX_POINT('',#115227); -#115227 = CARTESIAN_POINT('',(-1.,4.65,-0.208196358798)); -#115228 = VERTEX_POINT('',#115229); -#115229 = CARTESIAN_POINT('',(-1.,4.85,-0.208196358798)); -#115230 = SURFACE_CURVE('',#115231,(#115235,#115247),.PCURVE_S1.); -#115231 = LINE('',#115232,#115233); -#115232 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#115233 = VECTOR('',#115234,1.); -#115234 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115235 = PCURVE('',#115236,#115241); -#115236 = PLANE('',#115237); -#115237 = AXIS2_PLACEMENT_3D('',#115238,#115239,#115240); -#115238 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#115239 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#115240 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#115241 = DEFINITIONAL_REPRESENTATION('',(#115242),#115246); -#115242 = LINE('',#115243,#115244); -#115243 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#115244 = VECTOR('',#115245,1.); -#115245 = DIRECTION('',(4.440892098501E-016,1.)); -#115246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115247 = PCURVE('',#115139,#115248); -#115248 = DEFINITIONAL_REPRESENTATION('',(#115249),#115253); -#115249 = LINE('',#115250,#115251); -#115250 = CARTESIAN_POINT('',(-5.25,5.000038352949E-002)); -#115251 = VECTOR('',#115252,1.); -#115252 = DIRECTION('',(-1.,0.E+000)); -#115253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115254 = ORIENTED_EDGE('',*,*,#115255,.F.); -#115255 = EDGE_CURVE('',#115256,#115226,#115258,.T.); -#115256 = VERTEX_POINT('',#115257); -#115257 = CARTESIAN_POINT('',(-0.740726081328,4.65,-0.208196358798)); -#115258 = SURFACE_CURVE('',#115259,(#115263,#115270),.PCURVE_S1.); -#115259 = LINE('',#115260,#115261); -#115260 = CARTESIAN_POINT('',(-0.740726081328,4.65,-0.208196358798)); -#115261 = VECTOR('',#115262,1.); -#115262 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#115263 = PCURVE('',#115236,#115264); -#115264 = DEFINITIONAL_REPRESENTATION('',(#115265),#115269); -#115265 = LINE('',#115266,#115267); -#115266 = CARTESIAN_POINT('',(-2.553512956638E-015,-5.35)); -#115267 = VECTOR('',#115268,1.); -#115268 = DIRECTION('',(1.,0.E+000)); -#115269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115270 = PCURVE('',#91153,#115271); -#115271 = DEFINITIONAL_REPRESENTATION('',(#115272),#115276); -#115272 = LINE('',#115273,#115274); -#115273 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#115274 = VECTOR('',#115275,1.); -#115275 = DIRECTION('',(0.E+000,-1.)); -#115276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115277 = ORIENTED_EDGE('',*,*,#115278,.F.); -#115278 = EDGE_CURVE('',#115279,#115256,#115281,.T.); -#115279 = VERTEX_POINT('',#115280); -#115280 = CARTESIAN_POINT('',(-0.740726081328,4.85,-0.208196358798)); -#115281 = SURFACE_CURVE('',#115282,(#115286,#115293),.PCURVE_S1.); -#115282 = LINE('',#115283,#115284); -#115283 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#115284 = VECTOR('',#115285,1.); -#115285 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115286 = PCURVE('',#115236,#115287); -#115287 = DEFINITIONAL_REPRESENTATION('',(#115288),#115292); -#115288 = LINE('',#115289,#115290); -#115289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115290 = VECTOR('',#115291,1.); -#115291 = DIRECTION('',(-4.440892098501E-016,-1.)); -#115292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115293 = PCURVE('',#115294,#115299); -#115294 = CYLINDRICAL_SURFACE('',#115295,0.208574704164); -#115295 = AXIS2_PLACEMENT_3D('',#115296,#115297,#115298); -#115296 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#115297 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115298 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115299 = DEFINITIONAL_REPRESENTATION('',(#115300),#115303); -#115300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115301,#115302), +#117589 = CARTESIAN_POINT('',(4.761821717947,-5.35)); +#117590 = CARTESIAN_POINT('',(4.761821717947,-5.15)); +#117591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117592 = ORIENTED_EDGE('',*,*,#117593,.T.); +#117593 = EDGE_CURVE('',#117567,#117511,#117594,.T.); +#117594 = SURFACE_CURVE('',#117595,(#117599,#117606),.PCURVE_S1.); +#117595 = LINE('',#117596,#117597); +#117596 = CARTESIAN_POINT('',(-0.74341632541,4.65,-0.308197125857)); +#117597 = VECTOR('',#117598,1.); +#117598 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#117599 = PCURVE('',#117519,#117600); +#117600 = DEFINITIONAL_REPRESENTATION('',(#117601),#117605); +#117601 = LINE('',#117602,#117603); +#117602 = CARTESIAN_POINT('',(2.553512956638E-015,-5.35)); +#117603 = VECTOR('',#117604,1.); +#117604 = DIRECTION('',(-1.,0.E+000)); +#117605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117606 = PCURVE('',#93545,#117607); +#117607 = DEFINITIONAL_REPRESENTATION('',(#117608),#117612); +#117608 = LINE('',#117609,#117610); +#117609 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#117610 = VECTOR('',#117611,1.); +#117611 = DIRECTION('',(0.E+000,-1.)); +#117612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117613 = ADVANCED_FACE('',(#117614),#117628,.F.); +#117614 = FACE_BOUND('',#117615,.T.); +#117615 = EDGE_LOOP('',(#117616,#117646,#117669,#117696)); +#117616 = ORIENTED_EDGE('',*,*,#117617,.F.); +#117617 = EDGE_CURVE('',#117618,#117620,#117622,.T.); +#117618 = VERTEX_POINT('',#117619); +#117619 = CARTESIAN_POINT('',(-1.,4.65,-0.208196358798)); +#117620 = VERTEX_POINT('',#117621); +#117621 = CARTESIAN_POINT('',(-1.,4.85,-0.208196358798)); +#117622 = SURFACE_CURVE('',#117623,(#117627,#117639),.PCURVE_S1.); +#117623 = LINE('',#117624,#117625); +#117624 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#117625 = VECTOR('',#117626,1.); +#117626 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117627 = PCURVE('',#117628,#117633); +#117628 = PLANE('',#117629); +#117629 = AXIS2_PLACEMENT_3D('',#117630,#117631,#117632); +#117630 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#117631 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#117632 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#117633 = DEFINITIONAL_REPRESENTATION('',(#117634),#117638); +#117634 = LINE('',#117635,#117636); +#117635 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#117636 = VECTOR('',#117637,1.); +#117637 = DIRECTION('',(4.440892098501E-016,1.)); +#117638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117639 = PCURVE('',#117531,#117640); +#117640 = DEFINITIONAL_REPRESENTATION('',(#117641),#117645); +#117641 = LINE('',#117642,#117643); +#117642 = CARTESIAN_POINT('',(-5.25,5.000038352949E-002)); +#117643 = VECTOR('',#117644,1.); +#117644 = DIRECTION('',(-1.,0.E+000)); +#117645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117646 = ORIENTED_EDGE('',*,*,#117647,.F.); +#117647 = EDGE_CURVE('',#117648,#117618,#117650,.T.); +#117648 = VERTEX_POINT('',#117649); +#117649 = CARTESIAN_POINT('',(-0.740726081328,4.65,-0.208196358798)); +#117650 = SURFACE_CURVE('',#117651,(#117655,#117662),.PCURVE_S1.); +#117651 = LINE('',#117652,#117653); +#117652 = CARTESIAN_POINT('',(-0.740726081328,4.65,-0.208196358798)); +#117653 = VECTOR('',#117654,1.); +#117654 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#117655 = PCURVE('',#117628,#117656); +#117656 = DEFINITIONAL_REPRESENTATION('',(#117657),#117661); +#117657 = LINE('',#117658,#117659); +#117658 = CARTESIAN_POINT('',(-2.553512956638E-015,-5.35)); +#117659 = VECTOR('',#117660,1.); +#117660 = DIRECTION('',(1.,0.E+000)); +#117661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117662 = PCURVE('',#93545,#117663); +#117663 = DEFINITIONAL_REPRESENTATION('',(#117664),#117668); +#117664 = LINE('',#117665,#117666); +#117665 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#117666 = VECTOR('',#117667,1.); +#117667 = DIRECTION('',(0.E+000,-1.)); +#117668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117669 = ORIENTED_EDGE('',*,*,#117670,.F.); +#117670 = EDGE_CURVE('',#117671,#117648,#117673,.T.); +#117671 = VERTEX_POINT('',#117672); +#117672 = CARTESIAN_POINT('',(-0.740726081328,4.85,-0.208196358798)); +#117673 = SURFACE_CURVE('',#117674,(#117678,#117685),.PCURVE_S1.); +#117674 = LINE('',#117675,#117676); +#117675 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#117676 = VECTOR('',#117677,1.); +#117677 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117678 = PCURVE('',#117628,#117679); +#117679 = DEFINITIONAL_REPRESENTATION('',(#117680),#117684); +#117680 = LINE('',#117681,#117682); +#117681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117682 = VECTOR('',#117683,1.); +#117683 = DIRECTION('',(-4.440892098501E-016,-1.)); +#117684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117685 = PCURVE('',#117686,#117691); +#117686 = CYLINDRICAL_SURFACE('',#117687,0.208574704164); +#117687 = AXIS2_PLACEMENT_3D('',#117688,#117689,#117690); +#117688 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#117689 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117690 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117691 = DEFINITIONAL_REPRESENTATION('',(#117692),#117695); +#117692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117693,#117694), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#115301 = CARTESIAN_POINT('',(4.772630242227,-5.15)); -#115302 = CARTESIAN_POINT('',(4.772630242227,-5.35)); -#115303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115304 = ORIENTED_EDGE('',*,*,#115305,.T.); -#115305 = EDGE_CURVE('',#115279,#115228,#115306,.T.); -#115306 = SURFACE_CURVE('',#115307,(#115311,#115318),.PCURVE_S1.); -#115307 = LINE('',#115308,#115309); -#115308 = CARTESIAN_POINT('',(-0.740726081328,4.85,-0.208196358798)); -#115309 = VECTOR('',#115310,1.); -#115310 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#115311 = PCURVE('',#115236,#115312); -#115312 = DEFINITIONAL_REPRESENTATION('',(#115313),#115317); -#115313 = LINE('',#115314,#115315); -#115314 = CARTESIAN_POINT('',(-2.331468351713E-015,-5.15)); -#115315 = VECTOR('',#115316,1.); -#115316 = DIRECTION('',(1.,0.E+000)); -#115317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115318 = PCURVE('',#91209,#115319); -#115319 = DEFINITIONAL_REPRESENTATION('',(#115320),#115324); -#115320 = LINE('',#115321,#115322); -#115321 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#115322 = VECTOR('',#115323,1.); -#115323 = DIRECTION('',(0.E+000,-1.)); -#115324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115325 = ADVANCED_FACE('',(#115326),#115190,.T.); -#115326 = FACE_BOUND('',#115327,.T.); -#115327 = EDGE_LOOP('',(#115328,#115355,#115356,#115379)); -#115328 = ORIENTED_EDGE('',*,*,#115329,.T.); -#115329 = EDGE_CURVE('',#115330,#115175,#115332,.T.); -#115330 = VERTEX_POINT('',#115331); -#115331 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.E+000)); -#115332 = SURFACE_CURVE('',#115333,(#115338,#115344),.PCURVE_S1.); -#115333 = CIRCLE('',#115334,0.308574064194); -#115334 = AXIS2_PLACEMENT_3D('',#115335,#115336,#115337); -#115335 = CARTESIAN_POINT('',(-0.728168876214,4.65,2.640924866458E-017) - ); -#115336 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115337 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115338 = PCURVE('',#115190,#115339); -#115339 = DEFINITIONAL_REPRESENTATION('',(#115340),#115343); -#115340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115341,#115342), +#117693 = CARTESIAN_POINT('',(4.772630242227,-5.15)); +#117694 = CARTESIAN_POINT('',(4.772630242227,-5.35)); +#117695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117696 = ORIENTED_EDGE('',*,*,#117697,.T.); +#117697 = EDGE_CURVE('',#117671,#117620,#117698,.T.); +#117698 = SURFACE_CURVE('',#117699,(#117703,#117710),.PCURVE_S1.); +#117699 = LINE('',#117700,#117701); +#117700 = CARTESIAN_POINT('',(-0.740726081328,4.85,-0.208196358798)); +#117701 = VECTOR('',#117702,1.); +#117702 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#117703 = PCURVE('',#117628,#117704); +#117704 = DEFINITIONAL_REPRESENTATION('',(#117705),#117709); +#117705 = LINE('',#117706,#117707); +#117706 = CARTESIAN_POINT('',(-2.331468351713E-015,-5.15)); +#117707 = VECTOR('',#117708,1.); +#117708 = DIRECTION('',(1.,0.E+000)); +#117709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117710 = PCURVE('',#93601,#117711); +#117711 = DEFINITIONAL_REPRESENTATION('',(#117712),#117716); +#117712 = LINE('',#117713,#117714); +#117713 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#117714 = VECTOR('',#117715,1.); +#117715 = DIRECTION('',(0.E+000,-1.)); +#117716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117717 = ADVANCED_FACE('',(#117718),#117582,.T.); +#117718 = FACE_BOUND('',#117719,.T.); +#117719 = EDGE_LOOP('',(#117720,#117747,#117748,#117771)); +#117720 = ORIENTED_EDGE('',*,*,#117721,.T.); +#117721 = EDGE_CURVE('',#117722,#117567,#117724,.T.); +#117722 = VERTEX_POINT('',#117723); +#117723 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.E+000)); +#117724 = SURFACE_CURVE('',#117725,(#117730,#117736),.PCURVE_S1.); +#117725 = CIRCLE('',#117726,0.308574064194); +#117726 = AXIS2_PLACEMENT_3D('',#117727,#117728,#117729); +#117727 = CARTESIAN_POINT('',(-0.728168876214,4.65,2.640924866458E-017) + ); +#117728 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117729 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117730 = PCURVE('',#117582,#117731); +#117731 = DEFINITIONAL_REPRESENTATION('',(#117732),#117735); +#117732 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117733,#117734), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#115341 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#115342 = CARTESIAN_POINT('',(4.761821717947,-5.35)); -#115343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117733 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#117734 = CARTESIAN_POINT('',(4.761821717947,-5.35)); +#117735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115344 = PCURVE('',#91153,#115345); -#115345 = DEFINITIONAL_REPRESENTATION('',(#115346),#115354); -#115346 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115347,#115348,#115349, - #115350,#115351,#115352,#115353),.UNSPECIFIED.,.T.,.F.) +#117736 = PCURVE('',#93545,#117737); +#117737 = DEFINITIONAL_REPRESENTATION('',(#117738),#117746); +#117738 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117739,#117740,#117741, + #117742,#117743,#117744,#117745),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#115347 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#115348 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#115349 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#115350 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#115351 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#115352 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#115353 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#115354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115355 = ORIENTED_EDGE('',*,*,#115174,.T.); -#115356 = ORIENTED_EDGE('',*,*,#115357,.F.); -#115357 = EDGE_CURVE('',#115358,#115152,#115360,.T.); -#115358 = VERTEX_POINT('',#115359); -#115359 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.E+000)); -#115360 = SURFACE_CURVE('',#115361,(#115366,#115372),.PCURVE_S1.); -#115361 = CIRCLE('',#115362,0.308574064194); -#115362 = AXIS2_PLACEMENT_3D('',#115363,#115364,#115365); -#115363 = CARTESIAN_POINT('',(-0.728168876214,4.85,2.640924866458E-017) - ); -#115364 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115365 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115366 = PCURVE('',#115190,#115367); -#115367 = DEFINITIONAL_REPRESENTATION('',(#115368),#115371); -#115368 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115369,#115370), +#117739 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#117740 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#117741 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#117742 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#117743 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#117744 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#117745 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#117746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117747 = ORIENTED_EDGE('',*,*,#117566,.T.); +#117748 = ORIENTED_EDGE('',*,*,#117749,.F.); +#117749 = EDGE_CURVE('',#117750,#117544,#117752,.T.); +#117750 = VERTEX_POINT('',#117751); +#117751 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.E+000)); +#117752 = SURFACE_CURVE('',#117753,(#117758,#117764),.PCURVE_S1.); +#117753 = CIRCLE('',#117754,0.308574064194); +#117754 = AXIS2_PLACEMENT_3D('',#117755,#117756,#117757); +#117755 = CARTESIAN_POINT('',(-0.728168876214,4.85,2.640924866458E-017) + ); +#117756 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117757 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117758 = PCURVE('',#117582,#117759); +#117759 = DEFINITIONAL_REPRESENTATION('',(#117760),#117763); +#117760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117761,#117762), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#115369 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#115370 = CARTESIAN_POINT('',(4.761821717947,-5.15)); -#115371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115372 = PCURVE('',#91209,#115373); -#115373 = DEFINITIONAL_REPRESENTATION('',(#115374),#115378); -#115374 = CIRCLE('',#115375,0.308574064194); -#115375 = AXIS2_PLACEMENT_2D('',#115376,#115377); -#115376 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#115377 = DIRECTION('',(0.E+000,-1.)); -#115378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115379 = ORIENTED_EDGE('',*,*,#115380,.T.); -#115380 = EDGE_CURVE('',#115358,#115330,#115381,.T.); -#115381 = SURFACE_CURVE('',#115382,(#115386,#115392),.PCURVE_S1.); -#115382 = LINE('',#115383,#115384); -#115383 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#115384 = VECTOR('',#115385,1.); -#115385 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115386 = PCURVE('',#115190,#115387); -#115387 = DEFINITIONAL_REPRESENTATION('',(#115388),#115391); -#115388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115389,#115390), +#117761 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#117762 = CARTESIAN_POINT('',(4.761821717947,-5.15)); +#117763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117764 = PCURVE('',#93601,#117765); +#117765 = DEFINITIONAL_REPRESENTATION('',(#117766),#117770); +#117766 = CIRCLE('',#117767,0.308574064194); +#117767 = AXIS2_PLACEMENT_2D('',#117768,#117769); +#117768 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#117769 = DIRECTION('',(0.E+000,-1.)); +#117770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117771 = ORIENTED_EDGE('',*,*,#117772,.T.); +#117772 = EDGE_CURVE('',#117750,#117722,#117773,.T.); +#117773 = SURFACE_CURVE('',#117774,(#117778,#117784),.PCURVE_S1.); +#117774 = LINE('',#117775,#117776); +#117775 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#117776 = VECTOR('',#117777,1.); +#117777 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117778 = PCURVE('',#117582,#117779); +#117779 = DEFINITIONAL_REPRESENTATION('',(#117780),#117783); +#117780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117781,#117782), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#115389 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#115390 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#115391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115392 = PCURVE('',#115393,#115398); -#115393 = PLANE('',#115394); -#115394 = AXIS2_PLACEMENT_3D('',#115395,#115396,#115397); -#115395 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#115396 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#115397 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115398 = DEFINITIONAL_REPRESENTATION('',(#115399),#115403); -#115399 = LINE('',#115400,#115401); -#115400 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#115401 = VECTOR('',#115402,1.); -#115402 = DIRECTION('',(-1.,0.E+000)); -#115403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115404 = ADVANCED_FACE('',(#115405),#115294,.F.); -#115405 = FACE_BOUND('',#115406,.F.); -#115406 = EDGE_LOOP('',(#115407,#115430,#115457,#115482)); -#115407 = ORIENTED_EDGE('',*,*,#115408,.F.); -#115408 = EDGE_CURVE('',#115409,#115279,#115411,.T.); -#115409 = VERTEX_POINT('',#115410); -#115410 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.E+000)); -#115411 = SURFACE_CURVE('',#115412,(#115417,#115423),.PCURVE_S1.); -#115412 = CIRCLE('',#115413,0.208574704164); -#115413 = AXIS2_PLACEMENT_3D('',#115414,#115415,#115416); -#115414 = CARTESIAN_POINT('',(-0.728168876214,4.85,2.640924866458E-017) - ); -#115415 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115416 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115417 = PCURVE('',#115294,#115418); -#115418 = DEFINITIONAL_REPRESENTATION('',(#115419),#115422); -#115419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115420,#115421), +#117781 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#117782 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#117783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117784 = PCURVE('',#117785,#117790); +#117785 = PLANE('',#117786); +#117786 = AXIS2_PLACEMENT_3D('',#117787,#117788,#117789); +#117787 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#117788 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#117789 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117790 = DEFINITIONAL_REPRESENTATION('',(#117791),#117795); +#117791 = LINE('',#117792,#117793); +#117792 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#117793 = VECTOR('',#117794,1.); +#117794 = DIRECTION('',(-1.,0.E+000)); +#117795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117796 = ADVANCED_FACE('',(#117797),#117686,.F.); +#117797 = FACE_BOUND('',#117798,.F.); +#117798 = EDGE_LOOP('',(#117799,#117822,#117849,#117874)); +#117799 = ORIENTED_EDGE('',*,*,#117800,.F.); +#117800 = EDGE_CURVE('',#117801,#117671,#117803,.T.); +#117801 = VERTEX_POINT('',#117802); +#117802 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.E+000)); +#117803 = SURFACE_CURVE('',#117804,(#117809,#117815),.PCURVE_S1.); +#117804 = CIRCLE('',#117805,0.208574704164); +#117805 = AXIS2_PLACEMENT_3D('',#117806,#117807,#117808); +#117806 = CARTESIAN_POINT('',(-0.728168876214,4.85,2.640924866458E-017) + ); +#117807 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117808 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117809 = PCURVE('',#117686,#117810); +#117810 = DEFINITIONAL_REPRESENTATION('',(#117811),#117814); +#117811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117812,#117813), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#115420 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#115421 = CARTESIAN_POINT('',(4.772630242227,-5.15)); -#115422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115423 = PCURVE('',#91209,#115424); -#115424 = DEFINITIONAL_REPRESENTATION('',(#115425),#115429); -#115425 = CIRCLE('',#115426,0.208574704164); -#115426 = AXIS2_PLACEMENT_2D('',#115427,#115428); -#115427 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#115428 = DIRECTION('',(0.E+000,-1.)); -#115429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115430 = ORIENTED_EDGE('',*,*,#115431,.F.); -#115431 = EDGE_CURVE('',#115432,#115409,#115434,.T.); -#115432 = VERTEX_POINT('',#115433); -#115433 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.E+000)); -#115434 = SURFACE_CURVE('',#115435,(#115439,#115445),.PCURVE_S1.); -#115435 = LINE('',#115436,#115437); -#115436 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#115437 = VECTOR('',#115438,1.); -#115438 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115439 = PCURVE('',#115294,#115440); -#115440 = DEFINITIONAL_REPRESENTATION('',(#115441),#115444); -#115441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115442,#115443), +#117812 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#117813 = CARTESIAN_POINT('',(4.772630242227,-5.15)); +#117814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117815 = PCURVE('',#93601,#117816); +#117816 = DEFINITIONAL_REPRESENTATION('',(#117817),#117821); +#117817 = CIRCLE('',#117818,0.208574704164); +#117818 = AXIS2_PLACEMENT_2D('',#117819,#117820); +#117819 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#117820 = DIRECTION('',(0.E+000,-1.)); +#117821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117822 = ORIENTED_EDGE('',*,*,#117823,.F.); +#117823 = EDGE_CURVE('',#117824,#117801,#117826,.T.); +#117824 = VERTEX_POINT('',#117825); +#117825 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.E+000)); +#117826 = SURFACE_CURVE('',#117827,(#117831,#117837),.PCURVE_S1.); +#117827 = LINE('',#117828,#117829); +#117828 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#117829 = VECTOR('',#117830,1.); +#117830 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117831 = PCURVE('',#117686,#117832); +#117832 = DEFINITIONAL_REPRESENTATION('',(#117833),#117836); +#117833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117834,#117835), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#115442 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#115443 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#115444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115445 = PCURVE('',#115446,#115451); -#115446 = PLANE('',#115447); -#115447 = AXIS2_PLACEMENT_3D('',#115448,#115449,#115450); -#115448 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#115449 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#115450 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115451 = DEFINITIONAL_REPRESENTATION('',(#115452),#115456); -#115452 = LINE('',#115453,#115454); -#115453 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#115454 = VECTOR('',#115455,1.); -#115455 = DIRECTION('',(-1.,0.E+000)); -#115456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115457 = ORIENTED_EDGE('',*,*,#115458,.T.); -#115458 = EDGE_CURVE('',#115432,#115256,#115459,.T.); -#115459 = SURFACE_CURVE('',#115460,(#115465,#115471),.PCURVE_S1.); -#115460 = CIRCLE('',#115461,0.208574704164); -#115461 = AXIS2_PLACEMENT_3D('',#115462,#115463,#115464); -#115462 = CARTESIAN_POINT('',(-0.728168876214,4.65,2.640924866458E-017) - ); -#115463 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115464 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#115465 = PCURVE('',#115294,#115466); -#115466 = DEFINITIONAL_REPRESENTATION('',(#115467),#115470); -#115467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115468,#115469), +#117834 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#117835 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#117836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117837 = PCURVE('',#117838,#117843); +#117838 = PLANE('',#117839); +#117839 = AXIS2_PLACEMENT_3D('',#117840,#117841,#117842); +#117840 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#117841 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#117842 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117843 = DEFINITIONAL_REPRESENTATION('',(#117844),#117848); +#117844 = LINE('',#117845,#117846); +#117845 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#117846 = VECTOR('',#117847,1.); +#117847 = DIRECTION('',(-1.,0.E+000)); +#117848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117849 = ORIENTED_EDGE('',*,*,#117850,.T.); +#117850 = EDGE_CURVE('',#117824,#117648,#117851,.T.); +#117851 = SURFACE_CURVE('',#117852,(#117857,#117863),.PCURVE_S1.); +#117852 = CIRCLE('',#117853,0.208574704164); +#117853 = AXIS2_PLACEMENT_3D('',#117854,#117855,#117856); +#117854 = CARTESIAN_POINT('',(-0.728168876214,4.65,2.640924866458E-017) + ); +#117855 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117856 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#117857 = PCURVE('',#117686,#117858); +#117858 = DEFINITIONAL_REPRESENTATION('',(#117859),#117862); +#117859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117860,#117861), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#115468 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#115469 = CARTESIAN_POINT('',(4.772630242227,-5.35)); -#115470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117860 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#117861 = CARTESIAN_POINT('',(4.772630242227,-5.35)); +#117862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115471 = PCURVE('',#91153,#115472); -#115472 = DEFINITIONAL_REPRESENTATION('',(#115473),#115481); -#115473 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115474,#115475,#115476, - #115477,#115478,#115479,#115480),.UNSPECIFIED.,.T.,.F.) +#117863 = PCURVE('',#93545,#117864); +#117864 = DEFINITIONAL_REPRESENTATION('',(#117865),#117873); +#117865 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117866,#117867,#117868, + #117869,#117870,#117871,#117872),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#115474 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#115475 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#115476 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#115477 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#115478 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#115479 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#115480 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#115481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115482 = ORIENTED_EDGE('',*,*,#115278,.F.); -#115483 = ADVANCED_FACE('',(#115484),#115446,.T.); -#115484 = FACE_BOUND('',#115485,.T.); -#115485 = EDGE_LOOP('',(#115486,#115515,#115536,#115537)); -#115486 = ORIENTED_EDGE('',*,*,#115487,.T.); -#115487 = EDGE_CURVE('',#115488,#115490,#115492,.T.); -#115488 = VERTEX_POINT('',#115489); -#115489 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.530776333563)); -#115490 = VERTEX_POINT('',#115491); -#115491 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.530776333563)); -#115492 = SURFACE_CURVE('',#115493,(#115497,#115504),.PCURVE_S1.); -#115493 = LINE('',#115494,#115495); -#115494 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#115495 = VECTOR('',#115496,1.); -#115496 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115497 = PCURVE('',#115446,#115498); -#115498 = DEFINITIONAL_REPRESENTATION('',(#115499),#115503); -#115499 = LINE('',#115500,#115501); -#115500 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115501 = VECTOR('',#115502,1.); -#115502 = DIRECTION('',(-1.,0.E+000)); -#115503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115504 = PCURVE('',#115505,#115510); -#115505 = CYLINDRICAL_SURFACE('',#115506,0.2192697516); -#115506 = AXIS2_PLACEMENT_3D('',#115507,#115508,#115509); -#115507 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#115508 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115509 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115510 = DEFINITIONAL_REPRESENTATION('',(#115511),#115514); -#115511 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115512,#115513), +#117866 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#117867 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#117868 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#117869 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#117870 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#117871 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#117872 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#117873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117874 = ORIENTED_EDGE('',*,*,#117670,.F.); +#117875 = ADVANCED_FACE('',(#117876),#117838,.T.); +#117876 = FACE_BOUND('',#117877,.T.); +#117877 = EDGE_LOOP('',(#117878,#117907,#117928,#117929)); +#117878 = ORIENTED_EDGE('',*,*,#117879,.T.); +#117879 = EDGE_CURVE('',#117880,#117882,#117884,.T.); +#117880 = VERTEX_POINT('',#117881); +#117881 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.530776333563)); +#117882 = VERTEX_POINT('',#117883); +#117883 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.530776333563)); +#117884 = SURFACE_CURVE('',#117885,(#117889,#117896),.PCURVE_S1.); +#117885 = LINE('',#117886,#117887); +#117886 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#117887 = VECTOR('',#117888,1.); +#117888 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#117889 = PCURVE('',#117838,#117890); +#117890 = DEFINITIONAL_REPRESENTATION('',(#117891),#117895); +#117891 = LINE('',#117892,#117893); +#117892 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117893 = VECTOR('',#117894,1.); +#117894 = DIRECTION('',(-1.,0.E+000)); +#117895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117896 = PCURVE('',#117897,#117902); +#117897 = CYLINDRICAL_SURFACE('',#117898,0.2192697516); +#117898 = AXIS2_PLACEMENT_3D('',#117899,#117900,#117901); +#117899 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#117900 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117901 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117902 = DEFINITIONAL_REPRESENTATION('',(#117903),#117906); +#117903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117904,#117905), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#115512 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#115513 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#115514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115515 = ORIENTED_EDGE('',*,*,#115516,.T.); -#115516 = EDGE_CURVE('',#115490,#115409,#115517,.T.); -#115517 = SURFACE_CURVE('',#115518,(#115522,#115529),.PCURVE_S1.); -#115518 = LINE('',#115519,#115520); -#115519 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.530776333563)); -#115520 = VECTOR('',#115521,1.); -#115521 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#115522 = PCURVE('',#115446,#115523); -#115523 = DEFINITIONAL_REPRESENTATION('',(#115524),#115528); -#115524 = LINE('',#115525,#115526); -#115525 = CARTESIAN_POINT('',(5.15,4.535643882845E-033)); -#115526 = VECTOR('',#115527,1.); -#115527 = DIRECTION('',(-4.535643882845E-032,-1.)); -#115528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115529 = PCURVE('',#91209,#115530); -#115530 = DEFINITIONAL_REPRESENTATION('',(#115531),#115535); -#115531 = LINE('',#115532,#115533); -#115532 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#115533 = VECTOR('',#115534,1.); -#115534 = DIRECTION('',(-1.,-1.021336205033E-016)); -#115535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115536 = ORIENTED_EDGE('',*,*,#115431,.F.); -#115537 = ORIENTED_EDGE('',*,*,#115538,.F.); -#115538 = EDGE_CURVE('',#115488,#115432,#115539,.T.); -#115539 = SURFACE_CURVE('',#115540,(#115544,#115551),.PCURVE_S1.); -#115540 = LINE('',#115541,#115542); -#115541 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.530776333563)); -#115542 = VECTOR('',#115543,1.); -#115543 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#115544 = PCURVE('',#115446,#115545); -#115545 = DEFINITIONAL_REPRESENTATION('',(#115546),#115550); -#115546 = LINE('',#115547,#115548); -#115547 = CARTESIAN_POINT('',(5.35,-4.535643882845E-033)); -#115548 = VECTOR('',#115549,1.); -#115549 = DIRECTION('',(-4.535643882845E-032,-1.)); -#115550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115551 = PCURVE('',#91153,#115552); -#115552 = DEFINITIONAL_REPRESENTATION('',(#115553),#115557); -#115553 = LINE('',#115554,#115555); -#115554 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#115555 = VECTOR('',#115556,1.); -#115556 = DIRECTION('',(1.,-1.021336205033E-016)); -#115557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115558 = ADVANCED_FACE('',(#115559),#115393,.T.); -#115559 = FACE_BOUND('',#115560,.T.); -#115560 = EDGE_LOOP('',(#115561,#115590,#115611,#115612)); -#115561 = ORIENTED_EDGE('',*,*,#115562,.T.); -#115562 = EDGE_CURVE('',#115563,#115565,#115567,.T.); -#115563 = VERTEX_POINT('',#115564); -#115564 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.530776333563)); -#115565 = VERTEX_POINT('',#115566); -#115566 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.530776333563)); -#115567 = SURFACE_CURVE('',#115568,(#115572,#115579),.PCURVE_S1.); -#115568 = LINE('',#115569,#115570); -#115569 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#115570 = VECTOR('',#115571,1.); -#115571 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115572 = PCURVE('',#115393,#115573); -#115573 = DEFINITIONAL_REPRESENTATION('',(#115574),#115578); -#115574 = LINE('',#115575,#115576); -#115575 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115576 = VECTOR('',#115577,1.); -#115577 = DIRECTION('',(-1.,0.E+000)); -#115578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#117904 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#117905 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#117906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117907 = ORIENTED_EDGE('',*,*,#117908,.T.); +#117908 = EDGE_CURVE('',#117882,#117801,#117909,.T.); +#117909 = SURFACE_CURVE('',#117910,(#117914,#117921),.PCURVE_S1.); +#117910 = LINE('',#117911,#117912); +#117911 = CARTESIAN_POINT('',(-0.51959417205,4.85,0.530776333563)); +#117912 = VECTOR('',#117913,1.); +#117913 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117914 = PCURVE('',#117838,#117915); +#117915 = DEFINITIONAL_REPRESENTATION('',(#117916),#117920); +#117916 = LINE('',#117917,#117918); +#117917 = CARTESIAN_POINT('',(5.15,4.535643882845E-033)); +#117918 = VECTOR('',#117919,1.); +#117919 = DIRECTION('',(-4.535643882845E-032,-1.)); +#117920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117921 = PCURVE('',#93601,#117922); +#117922 = DEFINITIONAL_REPRESENTATION('',(#117923),#117927); +#117923 = LINE('',#117924,#117925); +#117924 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#117925 = VECTOR('',#117926,1.); +#117926 = DIRECTION('',(-1.,-1.021336205033E-016)); +#117927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115579 = PCURVE('',#115580,#115585); -#115580 = CYLINDRICAL_SURFACE('',#115581,0.119270391569); -#115581 = AXIS2_PLACEMENT_3D('',#115582,#115583,#115584); -#115582 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#115583 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115584 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115585 = DEFINITIONAL_REPRESENTATION('',(#115586),#115589); -#115586 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115587,#115588), +#117928 = ORIENTED_EDGE('',*,*,#117823,.F.); +#117929 = ORIENTED_EDGE('',*,*,#117930,.F.); +#117930 = EDGE_CURVE('',#117880,#117824,#117931,.T.); +#117931 = SURFACE_CURVE('',#117932,(#117936,#117943),.PCURVE_S1.); +#117932 = LINE('',#117933,#117934); +#117933 = CARTESIAN_POINT('',(-0.51959417205,4.65,0.530776333563)); +#117934 = VECTOR('',#117935,1.); +#117935 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117936 = PCURVE('',#117838,#117937); +#117937 = DEFINITIONAL_REPRESENTATION('',(#117938),#117942); +#117938 = LINE('',#117939,#117940); +#117939 = CARTESIAN_POINT('',(5.35,-4.535643882845E-033)); +#117940 = VECTOR('',#117941,1.); +#117941 = DIRECTION('',(-4.535643882845E-032,-1.)); +#117942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117943 = PCURVE('',#93545,#117944); +#117944 = DEFINITIONAL_REPRESENTATION('',(#117945),#117949); +#117945 = LINE('',#117946,#117947); +#117946 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#117947 = VECTOR('',#117948,1.); +#117948 = DIRECTION('',(1.,-1.021336205033E-016)); +#117949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117950 = ADVANCED_FACE('',(#117951),#117785,.T.); +#117951 = FACE_BOUND('',#117952,.T.); +#117952 = EDGE_LOOP('',(#117953,#117982,#118003,#118004)); +#117953 = ORIENTED_EDGE('',*,*,#117954,.T.); +#117954 = EDGE_CURVE('',#117955,#117957,#117959,.T.); +#117955 = VERTEX_POINT('',#117956); +#117956 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.530776333563)); +#117957 = VERTEX_POINT('',#117958); +#117958 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.530776333563)); +#117959 = SURFACE_CURVE('',#117960,(#117964,#117971),.PCURVE_S1.); +#117960 = LINE('',#117961,#117962); +#117961 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#117962 = VECTOR('',#117963,1.); +#117963 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117964 = PCURVE('',#117785,#117965); +#117965 = DEFINITIONAL_REPRESENTATION('',(#117966),#117970); +#117966 = LINE('',#117967,#117968); +#117967 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#117968 = VECTOR('',#117969,1.); +#117969 = DIRECTION('',(-1.,0.E+000)); +#117970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117971 = PCURVE('',#117972,#117977); +#117972 = CYLINDRICAL_SURFACE('',#117973,0.119270391569); +#117973 = AXIS2_PLACEMENT_3D('',#117974,#117975,#117976); +#117974 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#117975 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#117976 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#117977 = DEFINITIONAL_REPRESENTATION('',(#117978),#117981); +#117978 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117979,#117980), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#115587 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#115588 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#115589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115590 = ORIENTED_EDGE('',*,*,#115591,.T.); -#115591 = EDGE_CURVE('',#115565,#115330,#115592,.T.); -#115592 = SURFACE_CURVE('',#115593,(#115597,#115604),.PCURVE_S1.); -#115593 = LINE('',#115594,#115595); -#115594 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.530776333563)); -#115595 = VECTOR('',#115596,1.); -#115596 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#115597 = PCURVE('',#115393,#115598); -#115598 = DEFINITIONAL_REPRESENTATION('',(#115599),#115603); -#115599 = LINE('',#115600,#115601); -#115600 = CARTESIAN_POINT('',(-5.35,1.133910970711E-033)); -#115601 = VECTOR('',#115602,1.); -#115602 = DIRECTION('',(4.535643882845E-032,-1.)); -#115603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115604 = PCURVE('',#91153,#115605); -#115605 = DEFINITIONAL_REPRESENTATION('',(#115606),#115610); -#115606 = LINE('',#115607,#115608); -#115607 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#115608 = VECTOR('',#115609,1.); -#115609 = DIRECTION('',(1.,-1.021336205033E-016)); -#115610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115611 = ORIENTED_EDGE('',*,*,#115380,.F.); -#115612 = ORIENTED_EDGE('',*,*,#115613,.F.); -#115613 = EDGE_CURVE('',#115563,#115358,#115614,.T.); -#115614 = SURFACE_CURVE('',#115615,(#115619,#115626),.PCURVE_S1.); -#115615 = LINE('',#115616,#115617); -#115616 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.530776333563)); -#115617 = VECTOR('',#115618,1.); -#115618 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#115619 = PCURVE('',#115393,#115620); -#115620 = DEFINITIONAL_REPRESENTATION('',(#115621),#115625); -#115621 = LINE('',#115622,#115623); -#115622 = CARTESIAN_POINT('',(-5.15,-1.133910970711E-033)); -#115623 = VECTOR('',#115624,1.); -#115624 = DIRECTION('',(4.535643882845E-032,-1.)); -#115625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115626 = PCURVE('',#91209,#115627); -#115627 = DEFINITIONAL_REPRESENTATION('',(#115628),#115632); -#115628 = LINE('',#115629,#115630); -#115629 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#115630 = VECTOR('',#115631,1.); -#115631 = DIRECTION('',(-1.,-1.021336205033E-016)); -#115632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115633 = ADVANCED_FACE('',(#115634),#115580,.F.); -#115634 = FACE_BOUND('',#115635,.F.); -#115635 = EDGE_LOOP('',(#115636,#115637,#115660,#115705)); -#115636 = ORIENTED_EDGE('',*,*,#115562,.T.); -#115637 = ORIENTED_EDGE('',*,*,#115638,.F.); -#115638 = EDGE_CURVE('',#115639,#115565,#115641,.T.); -#115639 = VERTEX_POINT('',#115640); -#115640 = CARTESIAN_POINT('',(-0.303662633502,4.65,0.65)); -#115641 = SURFACE_CURVE('',#115642,(#115647,#115653),.PCURVE_S1.); -#115642 = CIRCLE('',#115643,0.119270391569); -#115643 = AXIS2_PLACEMENT_3D('',#115644,#115645,#115646); -#115644 = CARTESIAN_POINT('',(-0.30032442045,4.65,0.530776333563)); -#115645 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115646 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115647 = PCURVE('',#115580,#115648); -#115648 = DEFINITIONAL_REPRESENTATION('',(#115649),#115652); -#115649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115650,#115651), +#117979 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#117980 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#117981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117982 = ORIENTED_EDGE('',*,*,#117983,.T.); +#117983 = EDGE_CURVE('',#117957,#117722,#117984,.T.); +#117984 = SURFACE_CURVE('',#117985,(#117989,#117996),.PCURVE_S1.); +#117985 = LINE('',#117986,#117987); +#117986 = CARTESIAN_POINT('',(-0.419594812019,4.65,0.530776333563)); +#117987 = VECTOR('',#117988,1.); +#117988 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#117989 = PCURVE('',#117785,#117990); +#117990 = DEFINITIONAL_REPRESENTATION('',(#117991),#117995); +#117991 = LINE('',#117992,#117993); +#117992 = CARTESIAN_POINT('',(-5.35,1.133910970711E-033)); +#117993 = VECTOR('',#117994,1.); +#117994 = DIRECTION('',(4.535643882845E-032,-1.)); +#117995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#117996 = PCURVE('',#93545,#117997); +#117997 = DEFINITIONAL_REPRESENTATION('',(#117998),#118002); +#117998 = LINE('',#117999,#118000); +#117999 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#118000 = VECTOR('',#118001,1.); +#118001 = DIRECTION('',(1.,-1.021336205033E-016)); +#118002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118003 = ORIENTED_EDGE('',*,*,#117772,.F.); +#118004 = ORIENTED_EDGE('',*,*,#118005,.F.); +#118005 = EDGE_CURVE('',#117955,#117750,#118006,.T.); +#118006 = SURFACE_CURVE('',#118007,(#118011,#118018),.PCURVE_S1.); +#118007 = LINE('',#118008,#118009); +#118008 = CARTESIAN_POINT('',(-0.419594812019,4.85,0.530776333563)); +#118009 = VECTOR('',#118010,1.); +#118010 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#118011 = PCURVE('',#117785,#118012); +#118012 = DEFINITIONAL_REPRESENTATION('',(#118013),#118017); +#118013 = LINE('',#118014,#118015); +#118014 = CARTESIAN_POINT('',(-5.15,-1.133910970711E-033)); +#118015 = VECTOR('',#118016,1.); +#118016 = DIRECTION('',(4.535643882845E-032,-1.)); +#118017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118018 = PCURVE('',#93601,#118019); +#118019 = DEFINITIONAL_REPRESENTATION('',(#118020),#118024); +#118020 = LINE('',#118021,#118022); +#118021 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#118022 = VECTOR('',#118023,1.); +#118023 = DIRECTION('',(-1.,-1.021336205033E-016)); +#118024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118025 = ADVANCED_FACE('',(#118026),#117972,.F.); +#118026 = FACE_BOUND('',#118027,.F.); +#118027 = EDGE_LOOP('',(#118028,#118029,#118052,#118097)); +#118028 = ORIENTED_EDGE('',*,*,#117954,.T.); +#118029 = ORIENTED_EDGE('',*,*,#118030,.F.); +#118030 = EDGE_CURVE('',#118031,#117957,#118033,.T.); +#118031 = VERTEX_POINT('',#118032); +#118032 = CARTESIAN_POINT('',(-0.303662633502,4.65,0.65)); +#118033 = SURFACE_CURVE('',#118034,(#118039,#118045),.PCURVE_S1.); +#118034 = CIRCLE('',#118035,0.119270391569); +#118035 = AXIS2_PLACEMENT_3D('',#118036,#118037,#118038); +#118036 = CARTESIAN_POINT('',(-0.30032442045,4.65,0.530776333563)); +#118037 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118038 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118039 = PCURVE('',#117972,#118040); +#118040 = DEFINITIONAL_REPRESENTATION('',(#118041),#118044); +#118041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118042,#118043), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#115650 = CARTESIAN_POINT('',(1.598788597134,5.35)); -#115651 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#115652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115653 = PCURVE('',#91153,#115654); -#115654 = DEFINITIONAL_REPRESENTATION('',(#115655),#115659); -#115655 = CIRCLE('',#115656,0.119270391569); -#115656 = AXIS2_PLACEMENT_2D('',#115657,#115658); -#115657 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#115658 = DIRECTION('',(0.E+000,1.)); -#115659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115660 = ORIENTED_EDGE('',*,*,#115661,.T.); -#115661 = EDGE_CURVE('',#115639,#115662,#115664,.T.); -#115662 = VERTEX_POINT('',#115663); -#115663 = CARTESIAN_POINT('',(-0.303662633502,4.85,0.65)); -#115664 = SURFACE_CURVE('',#115665,(#115669,#115698),.PCURVE_S1.); -#115665 = LINE('',#115666,#115667); -#115666 = CARTESIAN_POINT('',(-0.303662633502,4.85,0.65)); -#115667 = VECTOR('',#115668,1.); -#115668 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#115669 = PCURVE('',#115580,#115670); -#115670 = DEFINITIONAL_REPRESENTATION('',(#115671),#115697); -#115671 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#115672,#115673,#115674, - #115675,#115676,#115677,#115678,#115679,#115680,#115681,#115682, - #115683,#115684,#115685,#115686,#115687,#115688,#115689,#115690, - #115691,#115692,#115693,#115694,#115695,#115696),.UNSPECIFIED.,.F., +#118042 = CARTESIAN_POINT('',(1.598788597134,5.35)); +#118043 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#118044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118045 = PCURVE('',#93545,#118046); +#118046 = DEFINITIONAL_REPRESENTATION('',(#118047),#118051); +#118047 = CIRCLE('',#118048,0.119270391569); +#118048 = AXIS2_PLACEMENT_2D('',#118049,#118050); +#118049 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#118050 = DIRECTION('',(0.E+000,1.)); +#118051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118052 = ORIENTED_EDGE('',*,*,#118053,.T.); +#118053 = EDGE_CURVE('',#118031,#118054,#118056,.T.); +#118054 = VERTEX_POINT('',#118055); +#118055 = CARTESIAN_POINT('',(-0.303662633502,4.85,0.65)); +#118056 = SURFACE_CURVE('',#118057,(#118061,#118090),.PCURVE_S1.); +#118057 = LINE('',#118058,#118059); +#118058 = CARTESIAN_POINT('',(-0.303662633502,4.85,0.65)); +#118059 = VECTOR('',#118060,1.); +#118060 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118061 = PCURVE('',#117972,#118062); +#118062 = DEFINITIONAL_REPRESENTATION('',(#118063),#118089); +#118063 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#118064,#118065,#118066, + #118067,#118068,#118069,#118070,#118071,#118072,#118073,#118074, + #118075,#118076,#118077,#118078,#118079,#118080,#118081,#118082, + #118083,#118084,#118085,#118086,#118087,#118088),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -142483,128 +145485,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, -2.465190328816E-032),.QUASI_UNIFORM_KNOTS.); -#115672 = CARTESIAN_POINT('',(1.598788597134,5.35)); -#115673 = CARTESIAN_POINT('',(1.598788597134,5.34696969697)); -#115674 = CARTESIAN_POINT('',(1.598788597134,5.340909090909)); -#115675 = CARTESIAN_POINT('',(1.598788597134,5.331818181818)); -#115676 = CARTESIAN_POINT('',(1.598788597134,5.322727272727)); -#115677 = CARTESIAN_POINT('',(1.598788597134,5.313636363636)); -#115678 = CARTESIAN_POINT('',(1.598788597134,5.304545454545)); -#115679 = CARTESIAN_POINT('',(1.598788597134,5.295454545455)); -#115680 = CARTESIAN_POINT('',(1.598788597134,5.286363636364)); -#115681 = CARTESIAN_POINT('',(1.598788597134,5.277272727273)); -#115682 = CARTESIAN_POINT('',(1.598788597134,5.268181818182)); -#115683 = CARTESIAN_POINT('',(1.598788597134,5.259090909091)); -#115684 = CARTESIAN_POINT('',(1.598788597134,5.25)); -#115685 = CARTESIAN_POINT('',(1.598788597134,5.240909090909)); -#115686 = CARTESIAN_POINT('',(1.598788597134,5.231818181818)); -#115687 = CARTESIAN_POINT('',(1.598788597134,5.222727272727)); -#115688 = CARTESIAN_POINT('',(1.598788597134,5.213636363636)); -#115689 = CARTESIAN_POINT('',(1.598788597134,5.204545454545)); -#115690 = CARTESIAN_POINT('',(1.598788597134,5.195454545455)); -#115691 = CARTESIAN_POINT('',(1.598788597134,5.186363636364)); -#115692 = CARTESIAN_POINT('',(1.598788597134,5.177272727273)); -#115693 = CARTESIAN_POINT('',(1.598788597134,5.168181818182)); -#115694 = CARTESIAN_POINT('',(1.598788597134,5.159090909091)); -#115695 = CARTESIAN_POINT('',(1.598788597134,5.15303030303)); -#115696 = CARTESIAN_POINT('',(1.598788597134,5.15)); -#115697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115698 = PCURVE('',#91181,#115699); -#115699 = DEFINITIONAL_REPRESENTATION('',(#115700),#115704); -#115700 = LINE('',#115701,#115702); -#115701 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#115702 = VECTOR('',#115703,1.); -#115703 = DIRECTION('',(4.440892098501E-016,1.)); -#115704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115705 = ORIENTED_EDGE('',*,*,#115706,.T.); -#115706 = EDGE_CURVE('',#115662,#115563,#115707,.T.); -#115707 = SURFACE_CURVE('',#115708,(#115713,#115719),.PCURVE_S1.); -#115708 = CIRCLE('',#115709,0.119270391569); -#115709 = AXIS2_PLACEMENT_3D('',#115710,#115711,#115712); -#115710 = CARTESIAN_POINT('',(-0.30032442045,4.85,0.530776333563)); -#115711 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115712 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115713 = PCURVE('',#115580,#115714); -#115714 = DEFINITIONAL_REPRESENTATION('',(#115715),#115718); -#115715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115716,#115717), +#118064 = CARTESIAN_POINT('',(1.598788597134,5.35)); +#118065 = CARTESIAN_POINT('',(1.598788597134,5.34696969697)); +#118066 = CARTESIAN_POINT('',(1.598788597134,5.340909090909)); +#118067 = CARTESIAN_POINT('',(1.598788597134,5.331818181818)); +#118068 = CARTESIAN_POINT('',(1.598788597134,5.322727272727)); +#118069 = CARTESIAN_POINT('',(1.598788597134,5.313636363636)); +#118070 = CARTESIAN_POINT('',(1.598788597134,5.304545454545)); +#118071 = CARTESIAN_POINT('',(1.598788597134,5.295454545455)); +#118072 = CARTESIAN_POINT('',(1.598788597134,5.286363636364)); +#118073 = CARTESIAN_POINT('',(1.598788597134,5.277272727273)); +#118074 = CARTESIAN_POINT('',(1.598788597134,5.268181818182)); +#118075 = CARTESIAN_POINT('',(1.598788597134,5.259090909091)); +#118076 = CARTESIAN_POINT('',(1.598788597134,5.25)); +#118077 = CARTESIAN_POINT('',(1.598788597134,5.240909090909)); +#118078 = CARTESIAN_POINT('',(1.598788597134,5.231818181818)); +#118079 = CARTESIAN_POINT('',(1.598788597134,5.222727272727)); +#118080 = CARTESIAN_POINT('',(1.598788597134,5.213636363636)); +#118081 = CARTESIAN_POINT('',(1.598788597134,5.204545454545)); +#118082 = CARTESIAN_POINT('',(1.598788597134,5.195454545455)); +#118083 = CARTESIAN_POINT('',(1.598788597134,5.186363636364)); +#118084 = CARTESIAN_POINT('',(1.598788597134,5.177272727273)); +#118085 = CARTESIAN_POINT('',(1.598788597134,5.168181818182)); +#118086 = CARTESIAN_POINT('',(1.598788597134,5.159090909091)); +#118087 = CARTESIAN_POINT('',(1.598788597134,5.15303030303)); +#118088 = CARTESIAN_POINT('',(1.598788597134,5.15)); +#118089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118090 = PCURVE('',#93573,#118091); +#118091 = DEFINITIONAL_REPRESENTATION('',(#118092),#118096); +#118092 = LINE('',#118093,#118094); +#118093 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#118094 = VECTOR('',#118095,1.); +#118095 = DIRECTION('',(4.440892098501E-016,1.)); +#118096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118097 = ORIENTED_EDGE('',*,*,#118098,.T.); +#118098 = EDGE_CURVE('',#118054,#117955,#118099,.T.); +#118099 = SURFACE_CURVE('',#118100,(#118105,#118111),.PCURVE_S1.); +#118100 = CIRCLE('',#118101,0.119270391569); +#118101 = AXIS2_PLACEMENT_3D('',#118102,#118103,#118104); +#118102 = CARTESIAN_POINT('',(-0.30032442045,4.85,0.530776333563)); +#118103 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118104 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118105 = PCURVE('',#117972,#118106); +#118106 = DEFINITIONAL_REPRESENTATION('',(#118107),#118110); +#118107 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118108,#118109), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#115716 = CARTESIAN_POINT('',(1.598788597134,5.15)); -#115717 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#115718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118108 = CARTESIAN_POINT('',(1.598788597134,5.15)); +#118109 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#118110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115719 = PCURVE('',#91209,#115720); -#115720 = DEFINITIONAL_REPRESENTATION('',(#115721),#115729); -#115721 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115722,#115723,#115724, - #115725,#115726,#115727,#115728),.UNSPECIFIED.,.T.,.F.) +#118111 = PCURVE('',#93601,#118112); +#118112 = DEFINITIONAL_REPRESENTATION('',(#118113),#118121); +#118113 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118114,#118115,#118116, + #118117,#118118,#118119,#118120),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#115722 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#115723 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#115724 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#115725 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#115726 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#115727 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#115728 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#115729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115730 = ADVANCED_FACE('',(#115731),#115505,.T.); -#115731 = FACE_BOUND('',#115732,.T.); -#115732 = EDGE_LOOP('',(#115733,#115734,#115757,#115802)); -#115733 = ORIENTED_EDGE('',*,*,#115487,.F.); -#115734 = ORIENTED_EDGE('',*,*,#115735,.F.); -#115735 = EDGE_CURVE('',#115736,#115488,#115738,.T.); -#115736 = VERTEX_POINT('',#115737); -#115737 = CARTESIAN_POINT('',(-0.304819755875,4.65,0.75)); -#115738 = SURFACE_CURVE('',#115739,(#115744,#115750),.PCURVE_S1.); -#115739 = CIRCLE('',#115740,0.2192697516); -#115740 = AXIS2_PLACEMENT_3D('',#115741,#115742,#115743); -#115741 = CARTESIAN_POINT('',(-0.30032442045,4.65,0.530776333563)); -#115742 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115743 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115744 = PCURVE('',#115505,#115745); -#115745 = DEFINITIONAL_REPRESENTATION('',(#115746),#115749); -#115746 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115747,#115748), +#118114 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#118115 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#118116 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#118117 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#118118 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#118119 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#118120 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#118121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118122 = ADVANCED_FACE('',(#118123),#117897,.T.); +#118123 = FACE_BOUND('',#118124,.T.); +#118124 = EDGE_LOOP('',(#118125,#118126,#118149,#118194)); +#118125 = ORIENTED_EDGE('',*,*,#117879,.F.); +#118126 = ORIENTED_EDGE('',*,*,#118127,.F.); +#118127 = EDGE_CURVE('',#118128,#117880,#118130,.T.); +#118128 = VERTEX_POINT('',#118129); +#118129 = CARTESIAN_POINT('',(-0.304819755875,4.65,0.75)); +#118130 = SURFACE_CURVE('',#118131,(#118136,#118142),.PCURVE_S1.); +#118131 = CIRCLE('',#118132,0.2192697516); +#118132 = AXIS2_PLACEMENT_3D('',#118133,#118134,#118135); +#118133 = CARTESIAN_POINT('',(-0.30032442045,4.65,0.530776333563)); +#118134 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118135 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118136 = PCURVE('',#117897,#118137); +#118137 = DEFINITIONAL_REPRESENTATION('',(#118138),#118141); +#118138 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118139,#118140), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#115747 = CARTESIAN_POINT('',(1.591299156552,5.35)); -#115748 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#115749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115750 = PCURVE('',#91153,#115751); -#115751 = DEFINITIONAL_REPRESENTATION('',(#115752),#115756); -#115752 = CIRCLE('',#115753,0.2192697516); -#115753 = AXIS2_PLACEMENT_2D('',#115754,#115755); -#115754 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#115755 = DIRECTION('',(0.E+000,1.)); -#115756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115757 = ORIENTED_EDGE('',*,*,#115758,.F.); -#115758 = EDGE_CURVE('',#115759,#115736,#115761,.T.); -#115759 = VERTEX_POINT('',#115760); -#115760 = CARTESIAN_POINT('',(-0.304819755875,4.85,0.75)); -#115761 = SURFACE_CURVE('',#115762,(#115766,#115795),.PCURVE_S1.); -#115762 = LINE('',#115763,#115764); -#115763 = CARTESIAN_POINT('',(-0.304819755875,4.85,0.75)); -#115764 = VECTOR('',#115765,1.); -#115765 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115766 = PCURVE('',#115505,#115767); -#115767 = DEFINITIONAL_REPRESENTATION('',(#115768),#115794); -#115768 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#115769,#115770,#115771, - #115772,#115773,#115774,#115775,#115776,#115777,#115778,#115779, - #115780,#115781,#115782,#115783,#115784,#115785,#115786,#115787, - #115788,#115789,#115790,#115791,#115792,#115793),.UNSPECIFIED.,.F., +#118139 = CARTESIAN_POINT('',(1.591299156552,5.35)); +#118140 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#118141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118142 = PCURVE('',#93545,#118143); +#118143 = DEFINITIONAL_REPRESENTATION('',(#118144),#118148); +#118144 = CIRCLE('',#118145,0.2192697516); +#118145 = AXIS2_PLACEMENT_2D('',#118146,#118147); +#118146 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#118147 = DIRECTION('',(0.E+000,1.)); +#118148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118149 = ORIENTED_EDGE('',*,*,#118150,.F.); +#118150 = EDGE_CURVE('',#118151,#118128,#118153,.T.); +#118151 = VERTEX_POINT('',#118152); +#118152 = CARTESIAN_POINT('',(-0.304819755875,4.85,0.75)); +#118153 = SURFACE_CURVE('',#118154,(#118158,#118187),.PCURVE_S1.); +#118154 = LINE('',#118155,#118156); +#118155 = CARTESIAN_POINT('',(-0.304819755875,4.85,0.75)); +#118156 = VECTOR('',#118157,1.); +#118157 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118158 = PCURVE('',#117897,#118159); +#118159 = DEFINITIONAL_REPRESENTATION('',(#118160),#118186); +#118160 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#118161,#118162,#118163, + #118164,#118165,#118166,#118167,#118168,#118169,#118170,#118171, + #118172,#118173,#118174,#118175,#118176,#118177,#118178,#118179, + #118180,#118181,#118182,#118183,#118184,#118185),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -142613,956 +145615,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ,0.136363636364,0.145454545455,0.154545454545,0.163636363636, 0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#115769 = CARTESIAN_POINT('',(1.591299156552,5.15)); -#115770 = CARTESIAN_POINT('',(1.591299156552,5.15303030303)); -#115771 = CARTESIAN_POINT('',(1.591299156552,5.159090909091)); -#115772 = CARTESIAN_POINT('',(1.591299156552,5.168181818182)); -#115773 = CARTESIAN_POINT('',(1.591299156552,5.177272727273)); -#115774 = CARTESIAN_POINT('',(1.591299156552,5.186363636364)); -#115775 = CARTESIAN_POINT('',(1.591299156552,5.195454545455)); -#115776 = CARTESIAN_POINT('',(1.591299156552,5.204545454545)); -#115777 = CARTESIAN_POINT('',(1.591299156552,5.213636363636)); -#115778 = CARTESIAN_POINT('',(1.591299156552,5.222727272727)); -#115779 = CARTESIAN_POINT('',(1.591299156552,5.231818181818)); -#115780 = CARTESIAN_POINT('',(1.591299156552,5.240909090909)); -#115781 = CARTESIAN_POINT('',(1.591299156552,5.25)); -#115782 = CARTESIAN_POINT('',(1.591299156552,5.259090909091)); -#115783 = CARTESIAN_POINT('',(1.591299156552,5.268181818182)); -#115784 = CARTESIAN_POINT('',(1.591299156552,5.277272727273)); -#115785 = CARTESIAN_POINT('',(1.591299156552,5.286363636364)); -#115786 = CARTESIAN_POINT('',(1.591299156552,5.295454545455)); -#115787 = CARTESIAN_POINT('',(1.591299156552,5.304545454545)); -#115788 = CARTESIAN_POINT('',(1.591299156552,5.313636363636)); -#115789 = CARTESIAN_POINT('',(1.591299156552,5.322727272727)); -#115790 = CARTESIAN_POINT('',(1.591299156552,5.331818181818)); -#115791 = CARTESIAN_POINT('',(1.591299156552,5.340909090909)); -#115792 = CARTESIAN_POINT('',(1.591299156552,5.34696969697)); -#115793 = CARTESIAN_POINT('',(1.591299156552,5.35)); -#115794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118161 = CARTESIAN_POINT('',(1.591299156552,5.15)); +#118162 = CARTESIAN_POINT('',(1.591299156552,5.15303030303)); +#118163 = CARTESIAN_POINT('',(1.591299156552,5.159090909091)); +#118164 = CARTESIAN_POINT('',(1.591299156552,5.168181818182)); +#118165 = CARTESIAN_POINT('',(1.591299156552,5.177272727273)); +#118166 = CARTESIAN_POINT('',(1.591299156552,5.186363636364)); +#118167 = CARTESIAN_POINT('',(1.591299156552,5.195454545455)); +#118168 = CARTESIAN_POINT('',(1.591299156552,5.204545454545)); +#118169 = CARTESIAN_POINT('',(1.591299156552,5.213636363636)); +#118170 = CARTESIAN_POINT('',(1.591299156552,5.222727272727)); +#118171 = CARTESIAN_POINT('',(1.591299156552,5.231818181818)); +#118172 = CARTESIAN_POINT('',(1.591299156552,5.240909090909)); +#118173 = CARTESIAN_POINT('',(1.591299156552,5.25)); +#118174 = CARTESIAN_POINT('',(1.591299156552,5.259090909091)); +#118175 = CARTESIAN_POINT('',(1.591299156552,5.268181818182)); +#118176 = CARTESIAN_POINT('',(1.591299156552,5.277272727273)); +#118177 = CARTESIAN_POINT('',(1.591299156552,5.286363636364)); +#118178 = CARTESIAN_POINT('',(1.591299156552,5.295454545455)); +#118179 = CARTESIAN_POINT('',(1.591299156552,5.304545454545)); +#118180 = CARTESIAN_POINT('',(1.591299156552,5.313636363636)); +#118181 = CARTESIAN_POINT('',(1.591299156552,5.322727272727)); +#118182 = CARTESIAN_POINT('',(1.591299156552,5.331818181818)); +#118183 = CARTESIAN_POINT('',(1.591299156552,5.340909090909)); +#118184 = CARTESIAN_POINT('',(1.591299156552,5.34696969697)); +#118185 = CARTESIAN_POINT('',(1.591299156552,5.35)); +#118186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118187 = PCURVE('',#93627,#118188); +#118188 = DEFINITIONAL_REPRESENTATION('',(#118189),#118193); +#118189 = LINE('',#118190,#118191); +#118190 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#118191 = VECTOR('',#118192,1.); +#118192 = DIRECTION('',(4.440892098501E-016,-1.)); +#118193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115795 = PCURVE('',#91235,#115796); -#115796 = DEFINITIONAL_REPRESENTATION('',(#115797),#115801); -#115797 = LINE('',#115798,#115799); -#115798 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#115799 = VECTOR('',#115800,1.); -#115800 = DIRECTION('',(4.440892098501E-016,-1.)); -#115801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115802 = ORIENTED_EDGE('',*,*,#115803,.T.); -#115803 = EDGE_CURVE('',#115759,#115490,#115804,.T.); -#115804 = SURFACE_CURVE('',#115805,(#115810,#115816),.PCURVE_S1.); -#115805 = CIRCLE('',#115806,0.2192697516); -#115806 = AXIS2_PLACEMENT_3D('',#115807,#115808,#115809); -#115807 = CARTESIAN_POINT('',(-0.30032442045,4.85,0.530776333563)); -#115808 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#115809 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#115810 = PCURVE('',#115505,#115811); -#115811 = DEFINITIONAL_REPRESENTATION('',(#115812),#115815); -#115812 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#115813,#115814), +#118194 = ORIENTED_EDGE('',*,*,#118195,.T.); +#118195 = EDGE_CURVE('',#118151,#117882,#118196,.T.); +#118196 = SURFACE_CURVE('',#118197,(#118202,#118208),.PCURVE_S1.); +#118197 = CIRCLE('',#118198,0.2192697516); +#118198 = AXIS2_PLACEMENT_3D('',#118199,#118200,#118201); +#118199 = CARTESIAN_POINT('',(-0.30032442045,4.85,0.530776333563)); +#118200 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118201 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118202 = PCURVE('',#117897,#118203); +#118203 = DEFINITIONAL_REPRESENTATION('',(#118204),#118207); +#118204 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118205,#118206), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#115813 = CARTESIAN_POINT('',(1.591299156552,5.15)); -#115814 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#115815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118205 = CARTESIAN_POINT('',(1.591299156552,5.15)); +#118206 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#118207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115816 = PCURVE('',#91209,#115817); -#115817 = DEFINITIONAL_REPRESENTATION('',(#115818),#115826); -#115818 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#115819,#115820,#115821, - #115822,#115823,#115824,#115825),.UNSPECIFIED.,.T.,.F.) +#118208 = PCURVE('',#93601,#118209); +#118209 = DEFINITIONAL_REPRESENTATION('',(#118210),#118218); +#118210 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118211,#118212,#118213, + #118214,#118215,#118216,#118217),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#115819 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#115820 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#115821 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#115822 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#115823 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#115824 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#115825 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#115826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115827 = ADVANCED_FACE('',(#115828),#91181,.T.); -#115828 = FACE_BOUND('',#115829,.T.); -#115829 = EDGE_LOOP('',(#115830,#115851,#115852,#115873)); -#115830 = ORIENTED_EDGE('',*,*,#115831,.F.); -#115831 = EDGE_CURVE('',#115639,#91138,#115832,.T.); -#115832 = SURFACE_CURVE('',#115833,(#115837,#115844),.PCURVE_S1.); -#115833 = LINE('',#115834,#115835); -#115834 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.65)); -#115835 = VECTOR('',#115836,1.); -#115836 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#115837 = PCURVE('',#91181,#115838); -#115838 = DEFINITIONAL_REPRESENTATION('',(#115839),#115843); -#115839 = LINE('',#115840,#115841); -#115840 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); -#115841 = VECTOR('',#115842,1.); -#115842 = DIRECTION('',(-1.,-4.804757279354E-063)); -#115843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115844 = PCURVE('',#91153,#115845); -#115845 = DEFINITIONAL_REPRESENTATION('',(#115846),#115850); -#115846 = LINE('',#115847,#115848); -#115847 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115848 = VECTOR('',#115849,1.); -#115849 = DIRECTION('',(-3.563627120235E-016,1.)); -#115850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118211 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#118212 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#118213 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#118214 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#118215 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#118216 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#118217 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#118218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118219 = ADVANCED_FACE('',(#118220),#93573,.T.); +#118220 = FACE_BOUND('',#118221,.T.); +#118221 = EDGE_LOOP('',(#118222,#118243,#118244,#118265)); +#118222 = ORIENTED_EDGE('',*,*,#118223,.F.); +#118223 = EDGE_CURVE('',#118031,#93530,#118224,.T.); +#118224 = SURFACE_CURVE('',#118225,(#118229,#118236),.PCURVE_S1.); +#118225 = LINE('',#118226,#118227); +#118226 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.65)); +#118227 = VECTOR('',#118228,1.); +#118228 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#118229 = PCURVE('',#93573,#118230); +#118230 = DEFINITIONAL_REPRESENTATION('',(#118231),#118235); +#118231 = LINE('',#118232,#118233); +#118232 = CARTESIAN_POINT('',(-1.110223024625E-016,-0.2)); +#118233 = VECTOR('',#118234,1.); +#118234 = DIRECTION('',(-1.,-4.804757279354E-063)); +#118235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118236 = PCURVE('',#93545,#118237); +#118237 = DEFINITIONAL_REPRESENTATION('',(#118238),#118242); +#118238 = LINE('',#118239,#118240); +#118239 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118240 = VECTOR('',#118241,1.); +#118241 = DIRECTION('',(-3.563627120235E-016,1.)); +#118242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118243 = ORIENTED_EDGE('',*,*,#118053,.T.); +#118244 = ORIENTED_EDGE('',*,*,#118245,.T.); +#118245 = EDGE_CURVE('',#118054,#93558,#118246,.T.); +#118246 = SURFACE_CURVE('',#118247,(#118251,#118258),.PCURVE_S1.); +#118247 = LINE('',#118248,#118249); +#118248 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); +#118249 = VECTOR('',#118250,1.); +#118250 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#118251 = PCURVE('',#93573,#118252); +#118252 = DEFINITIONAL_REPRESENTATION('',(#118253),#118257); +#118253 = LINE('',#118254,#118255); +#118254 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118255 = VECTOR('',#118256,1.); +#118256 = DIRECTION('',(-1.,-4.804757279354E-063)); +#118257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118258 = PCURVE('',#93601,#118259); +#118259 = DEFINITIONAL_REPRESENTATION('',(#118260),#118264); +#118260 = LINE('',#118261,#118262); +#118261 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118262 = VECTOR('',#118263,1.); +#118263 = DIRECTION('',(3.563627120235E-016,1.)); +#118264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118265 = ORIENTED_EDGE('',*,*,#93557,.F.); +#118266 = ADVANCED_FACE('',(#118267),#93545,.T.); +#118267 = FACE_BOUND('',#118268,.T.); +#118268 = EDGE_LOOP('',(#118269,#118290,#118291,#118292,#118293,#118294, + #118315,#118316,#118317,#118318,#118319,#118320)); +#118269 = ORIENTED_EDGE('',*,*,#118270,.F.); +#118270 = EDGE_CURVE('',#118128,#93528,#118271,.T.); +#118271 = SURFACE_CURVE('',#118272,(#118276,#118283),.PCURVE_S1.); +#118272 = LINE('',#118273,#118274); +#118273 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.75)); +#118274 = VECTOR('',#118275,1.); +#118275 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#118276 = PCURVE('',#93545,#118277); +#118277 = DEFINITIONAL_REPRESENTATION('',(#118278),#118282); +#118278 = LINE('',#118279,#118280); +#118279 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#118280 = VECTOR('',#118281,1.); +#118281 = DIRECTION('',(-3.563627120235E-016,1.)); +#118282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118283 = PCURVE('',#93627,#118284); +#118284 = DEFINITIONAL_REPRESENTATION('',(#118285),#118289); +#118285 = LINE('',#118286,#118287); +#118286 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); +#118287 = VECTOR('',#118288,1.); +#118288 = DIRECTION('',(1.,-4.804757279354E-063)); +#118289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118290 = ORIENTED_EDGE('',*,*,#118127,.T.); +#118291 = ORIENTED_EDGE('',*,*,#117930,.T.); +#118292 = ORIENTED_EDGE('',*,*,#117850,.T.); +#118293 = ORIENTED_EDGE('',*,*,#117647,.T.); +#118294 = ORIENTED_EDGE('',*,*,#118295,.F.); +#118295 = EDGE_CURVE('',#117511,#117618,#118296,.T.); +#118296 = SURFACE_CURVE('',#118297,(#118301,#118308),.PCURVE_S1.); +#118297 = LINE('',#118298,#118299); +#118298 = CARTESIAN_POINT('',(-1.,4.65,1.159810404338E-002)); +#118299 = VECTOR('',#118300,1.); +#118300 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#118301 = PCURVE('',#93545,#118302); +#118302 = DEFINITIONAL_REPRESENTATION('',(#118303),#118307); +#118303 = LINE('',#118304,#118305); +#118304 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#118305 = VECTOR('',#118306,1.); +#118306 = DIRECTION('',(-1.,-2.101748079665E-016)); +#118307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118308 = PCURVE('',#117531,#118309); +#118309 = DEFINITIONAL_REPRESENTATION('',(#118310),#118314); +#118310 = LINE('',#118311,#118312); +#118311 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#118312 = VECTOR('',#118313,1.); +#118313 = DIRECTION('',(-1.194699204908E-017,1.)); +#118314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118315 = ORIENTED_EDGE('',*,*,#117593,.F.); +#118316 = ORIENTED_EDGE('',*,*,#117721,.F.); +#118317 = ORIENTED_EDGE('',*,*,#117983,.F.); +#118318 = ORIENTED_EDGE('',*,*,#118030,.F.); +#118319 = ORIENTED_EDGE('',*,*,#118223,.T.); +#118320 = ORIENTED_EDGE('',*,*,#93527,.F.); +#118321 = ADVANCED_FACE('',(#118322),#93627,.T.); +#118322 = FACE_BOUND('',#118323,.T.); +#118323 = EDGE_LOOP('',(#118324,#118345,#118346,#118347)); +#118324 = ORIENTED_EDGE('',*,*,#118325,.F.); +#118325 = EDGE_CURVE('',#118151,#93586,#118326,.T.); +#118326 = SURFACE_CURVE('',#118327,(#118331,#118338),.PCURVE_S1.); +#118327 = LINE('',#118328,#118329); +#118328 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.75)); +#118329 = VECTOR('',#118330,1.); +#118330 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#118331 = PCURVE('',#93627,#118332); +#118332 = DEFINITIONAL_REPRESENTATION('',(#118333),#118337); +#118333 = LINE('',#118334,#118335); +#118334 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118335 = VECTOR('',#118336,1.); +#118336 = DIRECTION('',(1.,-4.804757279354E-063)); +#118337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118338 = PCURVE('',#93601,#118339); +#118339 = DEFINITIONAL_REPRESENTATION('',(#118340),#118344); +#118340 = LINE('',#118341,#118342); +#118341 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#118342 = VECTOR('',#118343,1.); +#118343 = DIRECTION('',(3.563627120235E-016,1.)); +#118344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118345 = ORIENTED_EDGE('',*,*,#118150,.T.); +#118346 = ORIENTED_EDGE('',*,*,#118270,.T.); +#118347 = ORIENTED_EDGE('',*,*,#93613,.F.); +#118348 = ADVANCED_FACE('',(#118349),#93601,.T.); +#118349 = FACE_BOUND('',#118350,.T.); +#118350 = EDGE_LOOP('',(#118351,#118352,#118353,#118354,#118355,#118356, + #118377,#118378,#118379,#118380,#118381,#118382)); +#118351 = ORIENTED_EDGE('',*,*,#118245,.F.); +#118352 = ORIENTED_EDGE('',*,*,#118098,.T.); +#118353 = ORIENTED_EDGE('',*,*,#118005,.T.); +#118354 = ORIENTED_EDGE('',*,*,#117749,.T.); +#118355 = ORIENTED_EDGE('',*,*,#117543,.T.); +#118356 = ORIENTED_EDGE('',*,*,#118357,.F.); +#118357 = EDGE_CURVE('',#117620,#117509,#118358,.T.); +#118358 = SURFACE_CURVE('',#118359,(#118363,#118370),.PCURVE_S1.); +#118359 = LINE('',#118360,#118361); +#118360 = CARTESIAN_POINT('',(-1.,4.85,1.159810404338E-002)); +#118361 = VECTOR('',#118362,1.); +#118362 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#118363 = PCURVE('',#93601,#118364); +#118364 = DEFINITIONAL_REPRESENTATION('',(#118365),#118369); +#118365 = LINE('',#118366,#118367); +#118366 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#118367 = VECTOR('',#118368,1.); +#118368 = DIRECTION('',(-1.,2.101748079665E-016)); +#118369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118370 = PCURVE('',#117531,#118371); +#118371 = DEFINITIONAL_REPRESENTATION('',(#118372),#118376); +#118372 = LINE('',#118373,#118374); +#118373 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#118374 = VECTOR('',#118375,1.); +#118375 = DIRECTION('',(1.194699204908E-017,-1.)); +#118376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#115851 = ORIENTED_EDGE('',*,*,#115661,.T.); -#115852 = ORIENTED_EDGE('',*,*,#115853,.T.); -#115853 = EDGE_CURVE('',#115662,#91166,#115854,.T.); -#115854 = SURFACE_CURVE('',#115855,(#115859,#115866),.PCURVE_S1.); -#115855 = LINE('',#115856,#115857); -#115856 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.65)); -#115857 = VECTOR('',#115858,1.); -#115858 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#115859 = PCURVE('',#91181,#115860); -#115860 = DEFINITIONAL_REPRESENTATION('',(#115861),#115865); -#115861 = LINE('',#115862,#115863); -#115862 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115863 = VECTOR('',#115864,1.); -#115864 = DIRECTION('',(-1.,-4.804757279354E-063)); -#115865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115866 = PCURVE('',#91209,#115867); -#115867 = DEFINITIONAL_REPRESENTATION('',(#115868),#115872); -#115868 = LINE('',#115869,#115870); -#115869 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115870 = VECTOR('',#115871,1.); -#115871 = DIRECTION('',(3.563627120235E-016,1.)); -#115872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115873 = ORIENTED_EDGE('',*,*,#91165,.F.); -#115874 = ADVANCED_FACE('',(#115875),#91153,.T.); -#115875 = FACE_BOUND('',#115876,.T.); -#115876 = EDGE_LOOP('',(#115877,#115898,#115899,#115900,#115901,#115902, - #115923,#115924,#115925,#115926,#115927,#115928)); -#115877 = ORIENTED_EDGE('',*,*,#115878,.F.); -#115878 = EDGE_CURVE('',#115736,#91136,#115879,.T.); -#115879 = SURFACE_CURVE('',#115880,(#115884,#115891),.PCURVE_S1.); -#115880 = LINE('',#115881,#115882); -#115881 = CARTESIAN_POINT('',(-0.527847992439,4.65,0.75)); -#115882 = VECTOR('',#115883,1.); -#115883 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#115884 = PCURVE('',#91153,#115885); -#115885 = DEFINITIONAL_REPRESENTATION('',(#115886),#115890); -#115886 = LINE('',#115887,#115888); -#115887 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#115888 = VECTOR('',#115889,1.); -#115889 = DIRECTION('',(-3.563627120235E-016,1.)); -#115890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115891 = PCURVE('',#91235,#115892); -#115892 = DEFINITIONAL_REPRESENTATION('',(#115893),#115897); -#115893 = LINE('',#115894,#115895); -#115894 = CARTESIAN_POINT('',(1.110223024625E-016,-0.2)); -#115895 = VECTOR('',#115896,1.); -#115896 = DIRECTION('',(1.,-4.804757279354E-063)); -#115897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115898 = ORIENTED_EDGE('',*,*,#115735,.T.); -#115899 = ORIENTED_EDGE('',*,*,#115538,.T.); -#115900 = ORIENTED_EDGE('',*,*,#115458,.T.); -#115901 = ORIENTED_EDGE('',*,*,#115255,.T.); -#115902 = ORIENTED_EDGE('',*,*,#115903,.F.); -#115903 = EDGE_CURVE('',#115119,#115226,#115904,.T.); -#115904 = SURFACE_CURVE('',#115905,(#115909,#115916),.PCURVE_S1.); -#115905 = LINE('',#115906,#115907); -#115906 = CARTESIAN_POINT('',(-1.,4.65,1.159810404338E-002)); -#115907 = VECTOR('',#115908,1.); -#115908 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#115909 = PCURVE('',#91153,#115910); -#115910 = DEFINITIONAL_REPRESENTATION('',(#115911),#115915); -#115911 = LINE('',#115912,#115913); -#115912 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#115913 = VECTOR('',#115914,1.); -#115914 = DIRECTION('',(-1.,-2.101748079665E-016)); -#115915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115916 = PCURVE('',#115139,#115917); -#115917 = DEFINITIONAL_REPRESENTATION('',(#115918),#115922); -#115918 = LINE('',#115919,#115920); -#115919 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#115920 = VECTOR('',#115921,1.); -#115921 = DIRECTION('',(-1.194699204908E-017,1.)); -#115922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115923 = ORIENTED_EDGE('',*,*,#115201,.F.); -#115924 = ORIENTED_EDGE('',*,*,#115329,.F.); -#115925 = ORIENTED_EDGE('',*,*,#115591,.F.); -#115926 = ORIENTED_EDGE('',*,*,#115638,.F.); -#115927 = ORIENTED_EDGE('',*,*,#115831,.T.); -#115928 = ORIENTED_EDGE('',*,*,#91135,.F.); -#115929 = ADVANCED_FACE('',(#115930),#91235,.T.); -#115930 = FACE_BOUND('',#115931,.T.); -#115931 = EDGE_LOOP('',(#115932,#115953,#115954,#115955)); -#115932 = ORIENTED_EDGE('',*,*,#115933,.F.); -#115933 = EDGE_CURVE('',#115759,#91194,#115934,.T.); -#115934 = SURFACE_CURVE('',#115935,(#115939,#115946),.PCURVE_S1.); -#115935 = LINE('',#115936,#115937); -#115936 = CARTESIAN_POINT('',(-0.527847992439,4.85,0.75)); -#115937 = VECTOR('',#115938,1.); -#115938 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#115939 = PCURVE('',#91235,#115940); -#115940 = DEFINITIONAL_REPRESENTATION('',(#115941),#115945); -#115941 = LINE('',#115942,#115943); -#115942 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#115943 = VECTOR('',#115944,1.); -#115944 = DIRECTION('',(1.,-4.804757279354E-063)); -#115945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115946 = PCURVE('',#91209,#115947); -#115947 = DEFINITIONAL_REPRESENTATION('',(#115948),#115952); -#115948 = LINE('',#115949,#115950); -#115949 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#115950 = VECTOR('',#115951,1.); -#115951 = DIRECTION('',(3.563627120235E-016,1.)); -#115952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115953 = ORIENTED_EDGE('',*,*,#115758,.T.); -#115954 = ORIENTED_EDGE('',*,*,#115878,.T.); -#115955 = ORIENTED_EDGE('',*,*,#91221,.F.); -#115956 = ADVANCED_FACE('',(#115957),#91209,.T.); -#115957 = FACE_BOUND('',#115958,.T.); -#115958 = EDGE_LOOP('',(#115959,#115960,#115961,#115962,#115963,#115964, - #115985,#115986,#115987,#115988,#115989,#115990)); -#115959 = ORIENTED_EDGE('',*,*,#115853,.F.); -#115960 = ORIENTED_EDGE('',*,*,#115706,.T.); -#115961 = ORIENTED_EDGE('',*,*,#115613,.T.); -#115962 = ORIENTED_EDGE('',*,*,#115357,.T.); -#115963 = ORIENTED_EDGE('',*,*,#115151,.T.); -#115964 = ORIENTED_EDGE('',*,*,#115965,.F.); -#115965 = EDGE_CURVE('',#115228,#115117,#115966,.T.); -#115966 = SURFACE_CURVE('',#115967,(#115971,#115978),.PCURVE_S1.); -#115967 = LINE('',#115968,#115969); -#115968 = CARTESIAN_POINT('',(-1.,4.85,1.159810404338E-002)); -#115969 = VECTOR('',#115970,1.); -#115970 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#115971 = PCURVE('',#91209,#115972); -#115972 = DEFINITIONAL_REPRESENTATION('',(#115973),#115977); -#115973 = LINE('',#115974,#115975); -#115974 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#115975 = VECTOR('',#115976,1.); -#115976 = DIRECTION('',(-1.,2.101748079665E-016)); -#115977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115978 = PCURVE('',#115139,#115979); -#115979 = DEFINITIONAL_REPRESENTATION('',(#115980),#115984); -#115980 = LINE('',#115981,#115982); -#115981 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#115982 = VECTOR('',#115983,1.); -#115983 = DIRECTION('',(1.194699204908E-017,-1.)); -#115984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#115985 = ORIENTED_EDGE('',*,*,#115305,.F.); -#115986 = ORIENTED_EDGE('',*,*,#115408,.F.); -#115987 = ORIENTED_EDGE('',*,*,#115516,.F.); -#115988 = ORIENTED_EDGE('',*,*,#115803,.F.); -#115989 = ORIENTED_EDGE('',*,*,#115933,.T.); -#115990 = ORIENTED_EDGE('',*,*,#91193,.F.); -#115991 = ADVANCED_FACE('',(#115992),#115139,.T.); -#115992 = FACE_BOUND('',#115993,.T.); -#115993 = EDGE_LOOP('',(#115994,#115995,#115996,#115997)); -#115994 = ORIENTED_EDGE('',*,*,#115903,.T.); -#115995 = ORIENTED_EDGE('',*,*,#115225,.T.); -#115996 = ORIENTED_EDGE('',*,*,#115965,.T.); -#115997 = ORIENTED_EDGE('',*,*,#115116,.T.); -#115998 = ADVANCED_FACE('',(#115999),#116013,.F.); -#115999 = FACE_BOUND('',#116000,.T.); -#116000 = EDGE_LOOP('',(#116001,#116036,#116059,#116086)); -#116001 = ORIENTED_EDGE('',*,*,#116002,.F.); -#116002 = EDGE_CURVE('',#116003,#116005,#116007,.T.); -#116003 = VERTEX_POINT('',#116004); -#116004 = CARTESIAN_POINT('',(-1.,5.65,-0.208196358798)); -#116005 = VERTEX_POINT('',#116006); -#116006 = CARTESIAN_POINT('',(-1.,5.85,-0.208196358798)); -#116007 = SURFACE_CURVE('',#116008,(#116012,#116024),.PCURVE_S1.); -#116008 = LINE('',#116009,#116010); -#116009 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#116010 = VECTOR('',#116011,1.); -#116011 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116012 = PCURVE('',#116013,#116018); -#116013 = PLANE('',#116014); -#116014 = AXIS2_PLACEMENT_3D('',#116015,#116016,#116017); -#116015 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#116016 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#116017 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116018 = DEFINITIONAL_REPRESENTATION('',(#116019),#116023); -#116019 = LINE('',#116020,#116021); -#116020 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#116021 = VECTOR('',#116022,1.); -#116022 = DIRECTION('',(4.440892098501E-016,1.)); -#116023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116024 = PCURVE('',#116025,#116030); -#116025 = PLANE('',#116026); -#116026 = AXIS2_PLACEMENT_3D('',#116027,#116028,#116029); -#116027 = CARTESIAN_POINT('',(-1.,5.75,-0.258196742327)); -#116028 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#116029 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116030 = DEFINITIONAL_REPRESENTATION('',(#116031),#116035); -#116031 = LINE('',#116032,#116033); -#116032 = CARTESIAN_POINT('',(-4.25,5.000038352949E-002)); -#116033 = VECTOR('',#116034,1.); -#116034 = DIRECTION('',(-1.,0.E+000)); -#116035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116036 = ORIENTED_EDGE('',*,*,#116037,.F.); -#116037 = EDGE_CURVE('',#116038,#116003,#116040,.T.); -#116038 = VERTEX_POINT('',#116039); -#116039 = CARTESIAN_POINT('',(-0.740726081328,5.65,-0.208196358798)); -#116040 = SURFACE_CURVE('',#116041,(#116045,#116052),.PCURVE_S1.); -#116041 = LINE('',#116042,#116043); -#116042 = CARTESIAN_POINT('',(-0.740726081328,5.65,-0.208196358798)); -#116043 = VECTOR('',#116044,1.); -#116044 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116045 = PCURVE('',#116013,#116046); -#116046 = DEFINITIONAL_REPRESENTATION('',(#116047),#116051); -#116047 = LINE('',#116048,#116049); -#116048 = CARTESIAN_POINT('',(-1.998401444325E-015,-4.35)); -#116049 = VECTOR('',#116050,1.); -#116050 = DIRECTION('',(1.,0.E+000)); -#116051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116052 = PCURVE('',#91039,#116053); -#116053 = DEFINITIONAL_REPRESENTATION('',(#116054),#116058); -#116054 = LINE('',#116055,#116056); -#116055 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#116056 = VECTOR('',#116057,1.); -#116057 = DIRECTION('',(0.E+000,-1.)); -#116058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116059 = ORIENTED_EDGE('',*,*,#116060,.F.); -#116060 = EDGE_CURVE('',#116061,#116038,#116063,.T.); -#116061 = VERTEX_POINT('',#116062); -#116062 = CARTESIAN_POINT('',(-0.740726081328,5.85,-0.208196358798)); -#116063 = SURFACE_CURVE('',#116064,(#116068,#116075),.PCURVE_S1.); -#116064 = LINE('',#116065,#116066); -#116065 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#116066 = VECTOR('',#116067,1.); -#116067 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116068 = PCURVE('',#116013,#116069); -#116069 = DEFINITIONAL_REPRESENTATION('',(#116070),#116074); -#116070 = LINE('',#116071,#116072); -#116071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116072 = VECTOR('',#116073,1.); -#116073 = DIRECTION('',(-4.440892098501E-016,-1.)); -#116074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116075 = PCURVE('',#116076,#116081); -#116076 = CYLINDRICAL_SURFACE('',#116077,0.208574704164); -#116077 = AXIS2_PLACEMENT_3D('',#116078,#116079,#116080); -#116078 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#116079 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116080 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116081 = DEFINITIONAL_REPRESENTATION('',(#116082),#116085); -#116082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116083,#116084), +#118377 = ORIENTED_EDGE('',*,*,#117697,.F.); +#118378 = ORIENTED_EDGE('',*,*,#117800,.F.); +#118379 = ORIENTED_EDGE('',*,*,#117908,.F.); +#118380 = ORIENTED_EDGE('',*,*,#118195,.F.); +#118381 = ORIENTED_EDGE('',*,*,#118325,.T.); +#118382 = ORIENTED_EDGE('',*,*,#93585,.F.); +#118383 = ADVANCED_FACE('',(#118384),#117531,.T.); +#118384 = FACE_BOUND('',#118385,.T.); +#118385 = EDGE_LOOP('',(#118386,#118387,#118388,#118389)); +#118386 = ORIENTED_EDGE('',*,*,#118295,.T.); +#118387 = ORIENTED_EDGE('',*,*,#117617,.T.); +#118388 = ORIENTED_EDGE('',*,*,#118357,.T.); +#118389 = ORIENTED_EDGE('',*,*,#117508,.T.); +#118390 = ADVANCED_FACE('',(#118391),#118405,.F.); +#118391 = FACE_BOUND('',#118392,.T.); +#118392 = EDGE_LOOP('',(#118393,#118428,#118451,#118478)); +#118393 = ORIENTED_EDGE('',*,*,#118394,.F.); +#118394 = EDGE_CURVE('',#118395,#118397,#118399,.T.); +#118395 = VERTEX_POINT('',#118396); +#118396 = CARTESIAN_POINT('',(-1.,5.65,-0.208196358798)); +#118397 = VERTEX_POINT('',#118398); +#118398 = CARTESIAN_POINT('',(-1.,5.85,-0.208196358798)); +#118399 = SURFACE_CURVE('',#118400,(#118404,#118416),.PCURVE_S1.); +#118400 = LINE('',#118401,#118402); +#118401 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#118402 = VECTOR('',#118403,1.); +#118403 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118404 = PCURVE('',#118405,#118410); +#118405 = PLANE('',#118406); +#118406 = AXIS2_PLACEMENT_3D('',#118407,#118408,#118409); +#118407 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#118408 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#118409 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#118410 = DEFINITIONAL_REPRESENTATION('',(#118411),#118415); +#118411 = LINE('',#118412,#118413); +#118412 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#118413 = VECTOR('',#118414,1.); +#118414 = DIRECTION('',(4.440892098501E-016,1.)); +#118415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118416 = PCURVE('',#118417,#118422); +#118417 = PLANE('',#118418); +#118418 = AXIS2_PLACEMENT_3D('',#118419,#118420,#118421); +#118419 = CARTESIAN_POINT('',(-1.,5.75,-0.258196742327)); +#118420 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#118421 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118422 = DEFINITIONAL_REPRESENTATION('',(#118423),#118427); +#118423 = LINE('',#118424,#118425); +#118424 = CARTESIAN_POINT('',(-4.25,5.000038352949E-002)); +#118425 = VECTOR('',#118426,1.); +#118426 = DIRECTION('',(-1.,0.E+000)); +#118427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118428 = ORIENTED_EDGE('',*,*,#118429,.F.); +#118429 = EDGE_CURVE('',#118430,#118395,#118432,.T.); +#118430 = VERTEX_POINT('',#118431); +#118431 = CARTESIAN_POINT('',(-0.740726081328,5.65,-0.208196358798)); +#118432 = SURFACE_CURVE('',#118433,(#118437,#118444),.PCURVE_S1.); +#118433 = LINE('',#118434,#118435); +#118434 = CARTESIAN_POINT('',(-0.740726081328,5.65,-0.208196358798)); +#118435 = VECTOR('',#118436,1.); +#118436 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#118437 = PCURVE('',#118405,#118438); +#118438 = DEFINITIONAL_REPRESENTATION('',(#118439),#118443); +#118439 = LINE('',#118440,#118441); +#118440 = CARTESIAN_POINT('',(-1.998401444325E-015,-4.35)); +#118441 = VECTOR('',#118442,1.); +#118442 = DIRECTION('',(1.,0.E+000)); +#118443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118444 = PCURVE('',#93431,#118445); +#118445 = DEFINITIONAL_REPRESENTATION('',(#118446),#118450); +#118446 = LINE('',#118447,#118448); +#118447 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#118448 = VECTOR('',#118449,1.); +#118449 = DIRECTION('',(0.E+000,-1.)); +#118450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118451 = ORIENTED_EDGE('',*,*,#118452,.F.); +#118452 = EDGE_CURVE('',#118453,#118430,#118455,.T.); +#118453 = VERTEX_POINT('',#118454); +#118454 = CARTESIAN_POINT('',(-0.740726081328,5.85,-0.208196358798)); +#118455 = SURFACE_CURVE('',#118456,(#118460,#118467),.PCURVE_S1.); +#118456 = LINE('',#118457,#118458); +#118457 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#118458 = VECTOR('',#118459,1.); +#118459 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118460 = PCURVE('',#118405,#118461); +#118461 = DEFINITIONAL_REPRESENTATION('',(#118462),#118466); +#118462 = LINE('',#118463,#118464); +#118463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118464 = VECTOR('',#118465,1.); +#118465 = DIRECTION('',(-4.440892098501E-016,-1.)); +#118466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118467 = PCURVE('',#118468,#118473); +#118468 = CYLINDRICAL_SURFACE('',#118469,0.208574704164); +#118469 = AXIS2_PLACEMENT_3D('',#118470,#118471,#118472); +#118470 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#118471 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118472 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118473 = DEFINITIONAL_REPRESENTATION('',(#118474),#118477); +#118474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118475,#118476), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#116083 = CARTESIAN_POINT('',(4.772630242227,-4.15)); -#116084 = CARTESIAN_POINT('',(4.772630242227,-4.35)); -#116085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116086 = ORIENTED_EDGE('',*,*,#116087,.T.); -#116087 = EDGE_CURVE('',#116061,#116005,#116088,.T.); -#116088 = SURFACE_CURVE('',#116089,(#116093,#116100),.PCURVE_S1.); -#116089 = LINE('',#116090,#116091); -#116090 = CARTESIAN_POINT('',(-0.740726081328,5.85,-0.208196358798)); -#116091 = VECTOR('',#116092,1.); -#116092 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116093 = PCURVE('',#116013,#116094); -#116094 = DEFINITIONAL_REPRESENTATION('',(#116095),#116099); -#116095 = LINE('',#116096,#116097); -#116096 = CARTESIAN_POINT('',(-1.7763568394E-015,-4.15)); -#116097 = VECTOR('',#116098,1.); -#116098 = DIRECTION('',(1.,0.E+000)); -#116099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116100 = PCURVE('',#91095,#116101); -#116101 = DEFINITIONAL_REPRESENTATION('',(#116102),#116106); -#116102 = LINE('',#116103,#116104); -#116103 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#116104 = VECTOR('',#116105,1.); -#116105 = DIRECTION('',(0.E+000,-1.)); -#116106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116107 = ADVANCED_FACE('',(#116108),#116122,.F.); -#116108 = FACE_BOUND('',#116109,.T.); -#116109 = EDGE_LOOP('',(#116110,#116140,#116163,#116190)); -#116110 = ORIENTED_EDGE('',*,*,#116111,.F.); -#116111 = EDGE_CURVE('',#116112,#116114,#116116,.T.); -#116112 = VERTEX_POINT('',#116113); -#116113 = CARTESIAN_POINT('',(-1.,5.85,-0.308197125857)); -#116114 = VERTEX_POINT('',#116115); -#116115 = CARTESIAN_POINT('',(-1.,5.65,-0.308197125857)); -#116116 = SURFACE_CURVE('',#116117,(#116121,#116133),.PCURVE_S1.); -#116117 = LINE('',#116118,#116119); -#116118 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#116119 = VECTOR('',#116120,1.); -#116120 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116121 = PCURVE('',#116122,#116127); -#116122 = PLANE('',#116123); -#116123 = AXIS2_PLACEMENT_3D('',#116124,#116125,#116126); -#116124 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#116125 = DIRECTION('',(0.E+000,0.E+000,1.)); -#116126 = DIRECTION('',(1.,0.E+000,0.E+000)); -#116127 = DEFINITIONAL_REPRESENTATION('',(#116128),#116132); -#116128 = LINE('',#116129,#116130); -#116129 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#116130 = VECTOR('',#116131,1.); -#116131 = DIRECTION('',(4.440892098501E-016,-1.)); -#116132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116133 = PCURVE('',#116025,#116134); -#116134 = DEFINITIONAL_REPRESENTATION('',(#116135),#116139); -#116135 = LINE('',#116136,#116137); -#116136 = CARTESIAN_POINT('',(-4.25,-5.000038352949E-002)); -#116137 = VECTOR('',#116138,1.); -#116138 = DIRECTION('',(1.,0.E+000)); -#116139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116140 = ORIENTED_EDGE('',*,*,#116141,.F.); -#116141 = EDGE_CURVE('',#116142,#116112,#116144,.T.); -#116142 = VERTEX_POINT('',#116143); -#116143 = CARTESIAN_POINT('',(-0.74341632541,5.85,-0.308197125857)); -#116144 = SURFACE_CURVE('',#116145,(#116149,#116156),.PCURVE_S1.); -#116145 = LINE('',#116146,#116147); -#116146 = CARTESIAN_POINT('',(-0.74341632541,5.85,-0.308197125857)); -#116147 = VECTOR('',#116148,1.); -#116148 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116149 = PCURVE('',#116122,#116150); -#116150 = DEFINITIONAL_REPRESENTATION('',(#116151),#116155); -#116151 = LINE('',#116152,#116153); -#116152 = CARTESIAN_POINT('',(1.7763568394E-015,-4.15)); -#116153 = VECTOR('',#116154,1.); -#116154 = DIRECTION('',(-1.,0.E+000)); -#116155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116156 = PCURVE('',#91095,#116157); -#116157 = DEFINITIONAL_REPRESENTATION('',(#116158),#116162); -#116158 = LINE('',#116159,#116160); -#116159 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#116160 = VECTOR('',#116161,1.); -#116161 = DIRECTION('',(0.E+000,-1.)); -#116162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116163 = ORIENTED_EDGE('',*,*,#116164,.F.); -#116164 = EDGE_CURVE('',#116165,#116142,#116167,.T.); -#116165 = VERTEX_POINT('',#116166); -#116166 = CARTESIAN_POINT('',(-0.74341632541,5.65,-0.308197125857)); -#116167 = SURFACE_CURVE('',#116168,(#116172,#116179),.PCURVE_S1.); -#116168 = LINE('',#116169,#116170); -#116169 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#116170 = VECTOR('',#116171,1.); -#116171 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116172 = PCURVE('',#116122,#116173); -#116173 = DEFINITIONAL_REPRESENTATION('',(#116174),#116178); -#116174 = LINE('',#116175,#116176); -#116175 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116176 = VECTOR('',#116177,1.); -#116177 = DIRECTION('',(-4.440892098501E-016,1.)); -#116178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116179 = PCURVE('',#116180,#116185); -#116180 = CYLINDRICAL_SURFACE('',#116181,0.308574064194); -#116181 = AXIS2_PLACEMENT_3D('',#116182,#116183,#116184); -#116182 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#116183 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116184 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116185 = DEFINITIONAL_REPRESENTATION('',(#116186),#116189); -#116186 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116187,#116188), +#118475 = CARTESIAN_POINT('',(4.772630242227,-4.15)); +#118476 = CARTESIAN_POINT('',(4.772630242227,-4.35)); +#118477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118478 = ORIENTED_EDGE('',*,*,#118479,.T.); +#118479 = EDGE_CURVE('',#118453,#118397,#118480,.T.); +#118480 = SURFACE_CURVE('',#118481,(#118485,#118492),.PCURVE_S1.); +#118481 = LINE('',#118482,#118483); +#118482 = CARTESIAN_POINT('',(-0.740726081328,5.85,-0.208196358798)); +#118483 = VECTOR('',#118484,1.); +#118484 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#118485 = PCURVE('',#118405,#118486); +#118486 = DEFINITIONAL_REPRESENTATION('',(#118487),#118491); +#118487 = LINE('',#118488,#118489); +#118488 = CARTESIAN_POINT('',(-1.7763568394E-015,-4.15)); +#118489 = VECTOR('',#118490,1.); +#118490 = DIRECTION('',(1.,0.E+000)); +#118491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118492 = PCURVE('',#93487,#118493); +#118493 = DEFINITIONAL_REPRESENTATION('',(#118494),#118498); +#118494 = LINE('',#118495,#118496); +#118495 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#118496 = VECTOR('',#118497,1.); +#118497 = DIRECTION('',(0.E+000,-1.)); +#118498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118499 = ADVANCED_FACE('',(#118500),#118514,.F.); +#118500 = FACE_BOUND('',#118501,.T.); +#118501 = EDGE_LOOP('',(#118502,#118532,#118555,#118582)); +#118502 = ORIENTED_EDGE('',*,*,#118503,.F.); +#118503 = EDGE_CURVE('',#118504,#118506,#118508,.T.); +#118504 = VERTEX_POINT('',#118505); +#118505 = CARTESIAN_POINT('',(-1.,5.85,-0.308197125857)); +#118506 = VERTEX_POINT('',#118507); +#118507 = CARTESIAN_POINT('',(-1.,5.65,-0.308197125857)); +#118508 = SURFACE_CURVE('',#118509,(#118513,#118525),.PCURVE_S1.); +#118509 = LINE('',#118510,#118511); +#118510 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#118511 = VECTOR('',#118512,1.); +#118512 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118513 = PCURVE('',#118514,#118519); +#118514 = PLANE('',#118515); +#118515 = AXIS2_PLACEMENT_3D('',#118516,#118517,#118518); +#118516 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#118517 = DIRECTION('',(0.E+000,0.E+000,1.)); +#118518 = DIRECTION('',(1.,0.E+000,0.E+000)); +#118519 = DEFINITIONAL_REPRESENTATION('',(#118520),#118524); +#118520 = LINE('',#118521,#118522); +#118521 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#118522 = VECTOR('',#118523,1.); +#118523 = DIRECTION('',(4.440892098501E-016,-1.)); +#118524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118525 = PCURVE('',#118417,#118526); +#118526 = DEFINITIONAL_REPRESENTATION('',(#118527),#118531); +#118527 = LINE('',#118528,#118529); +#118528 = CARTESIAN_POINT('',(-4.25,-5.000038352949E-002)); +#118529 = VECTOR('',#118530,1.); +#118530 = DIRECTION('',(1.,0.E+000)); +#118531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118532 = ORIENTED_EDGE('',*,*,#118533,.F.); +#118533 = EDGE_CURVE('',#118534,#118504,#118536,.T.); +#118534 = VERTEX_POINT('',#118535); +#118535 = CARTESIAN_POINT('',(-0.74341632541,5.85,-0.308197125857)); +#118536 = SURFACE_CURVE('',#118537,(#118541,#118548),.PCURVE_S1.); +#118537 = LINE('',#118538,#118539); +#118538 = CARTESIAN_POINT('',(-0.74341632541,5.85,-0.308197125857)); +#118539 = VECTOR('',#118540,1.); +#118540 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#118541 = PCURVE('',#118514,#118542); +#118542 = DEFINITIONAL_REPRESENTATION('',(#118543),#118547); +#118543 = LINE('',#118544,#118545); +#118544 = CARTESIAN_POINT('',(1.7763568394E-015,-4.15)); +#118545 = VECTOR('',#118546,1.); +#118546 = DIRECTION('',(-1.,0.E+000)); +#118547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118548 = PCURVE('',#93487,#118549); +#118549 = DEFINITIONAL_REPRESENTATION('',(#118550),#118554); +#118550 = LINE('',#118551,#118552); +#118551 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#118552 = VECTOR('',#118553,1.); +#118553 = DIRECTION('',(0.E+000,-1.)); +#118554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118555 = ORIENTED_EDGE('',*,*,#118556,.F.); +#118556 = EDGE_CURVE('',#118557,#118534,#118559,.T.); +#118557 = VERTEX_POINT('',#118558); +#118558 = CARTESIAN_POINT('',(-0.74341632541,5.65,-0.308197125857)); +#118559 = SURFACE_CURVE('',#118560,(#118564,#118571),.PCURVE_S1.); +#118560 = LINE('',#118561,#118562); +#118561 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#118562 = VECTOR('',#118563,1.); +#118563 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118564 = PCURVE('',#118514,#118565); +#118565 = DEFINITIONAL_REPRESENTATION('',(#118566),#118570); +#118566 = LINE('',#118567,#118568); +#118567 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118568 = VECTOR('',#118569,1.); +#118569 = DIRECTION('',(-4.440892098501E-016,1.)); +#118570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118571 = PCURVE('',#118572,#118577); +#118572 = CYLINDRICAL_SURFACE('',#118573,0.308574064194); +#118573 = AXIS2_PLACEMENT_3D('',#118574,#118575,#118576); +#118574 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#118575 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118576 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118577 = DEFINITIONAL_REPRESENTATION('',(#118578),#118581); +#118578 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118579,#118580), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#116187 = CARTESIAN_POINT('',(4.761821717947,-4.35)); -#116188 = CARTESIAN_POINT('',(4.761821717947,-4.15)); -#116189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116190 = ORIENTED_EDGE('',*,*,#116191,.T.); -#116191 = EDGE_CURVE('',#116165,#116114,#116192,.T.); -#116192 = SURFACE_CURVE('',#116193,(#116197,#116204),.PCURVE_S1.); -#116193 = LINE('',#116194,#116195); -#116194 = CARTESIAN_POINT('',(-0.74341632541,5.65,-0.308197125857)); -#116195 = VECTOR('',#116196,1.); -#116196 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116197 = PCURVE('',#116122,#116198); -#116198 = DEFINITIONAL_REPRESENTATION('',(#116199),#116203); -#116199 = LINE('',#116200,#116201); -#116200 = CARTESIAN_POINT('',(1.998401444325E-015,-4.35)); -#116201 = VECTOR('',#116202,1.); -#116202 = DIRECTION('',(-1.,0.E+000)); -#116203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116204 = PCURVE('',#91039,#116205); -#116205 = DEFINITIONAL_REPRESENTATION('',(#116206),#116210); -#116206 = LINE('',#116207,#116208); -#116207 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#116208 = VECTOR('',#116209,1.); -#116209 = DIRECTION('',(0.E+000,-1.)); -#116210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116211 = ADVANCED_FACE('',(#116212),#116076,.F.); -#116212 = FACE_BOUND('',#116213,.F.); -#116213 = EDGE_LOOP('',(#116214,#116237,#116264,#116289)); -#116214 = ORIENTED_EDGE('',*,*,#116215,.F.); -#116215 = EDGE_CURVE('',#116216,#116061,#116218,.T.); -#116216 = VERTEX_POINT('',#116217); -#116217 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.E+000)); -#116218 = SURFACE_CURVE('',#116219,(#116224,#116230),.PCURVE_S1.); -#116219 = CIRCLE('',#116220,0.208574704164); -#116220 = AXIS2_PLACEMENT_3D('',#116221,#116222,#116223); -#116221 = CARTESIAN_POINT('',(-0.728168876214,5.85,2.640924866458E-017) - ); -#116222 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116223 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116224 = PCURVE('',#116076,#116225); -#116225 = DEFINITIONAL_REPRESENTATION('',(#116226),#116229); -#116226 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116227,#116228), +#118579 = CARTESIAN_POINT('',(4.761821717947,-4.35)); +#118580 = CARTESIAN_POINT('',(4.761821717947,-4.15)); +#118581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118582 = ORIENTED_EDGE('',*,*,#118583,.T.); +#118583 = EDGE_CURVE('',#118557,#118506,#118584,.T.); +#118584 = SURFACE_CURVE('',#118585,(#118589,#118596),.PCURVE_S1.); +#118585 = LINE('',#118586,#118587); +#118586 = CARTESIAN_POINT('',(-0.74341632541,5.65,-0.308197125857)); +#118587 = VECTOR('',#118588,1.); +#118588 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#118589 = PCURVE('',#118514,#118590); +#118590 = DEFINITIONAL_REPRESENTATION('',(#118591),#118595); +#118591 = LINE('',#118592,#118593); +#118592 = CARTESIAN_POINT('',(1.998401444325E-015,-4.35)); +#118593 = VECTOR('',#118594,1.); +#118594 = DIRECTION('',(-1.,0.E+000)); +#118595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118596 = PCURVE('',#93431,#118597); +#118597 = DEFINITIONAL_REPRESENTATION('',(#118598),#118602); +#118598 = LINE('',#118599,#118600); +#118599 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#118600 = VECTOR('',#118601,1.); +#118601 = DIRECTION('',(0.E+000,-1.)); +#118602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118603 = ADVANCED_FACE('',(#118604),#118468,.F.); +#118604 = FACE_BOUND('',#118605,.F.); +#118605 = EDGE_LOOP('',(#118606,#118629,#118656,#118681)); +#118606 = ORIENTED_EDGE('',*,*,#118607,.F.); +#118607 = EDGE_CURVE('',#118608,#118453,#118610,.T.); +#118608 = VERTEX_POINT('',#118609); +#118609 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.E+000)); +#118610 = SURFACE_CURVE('',#118611,(#118616,#118622),.PCURVE_S1.); +#118611 = CIRCLE('',#118612,0.208574704164); +#118612 = AXIS2_PLACEMENT_3D('',#118613,#118614,#118615); +#118613 = CARTESIAN_POINT('',(-0.728168876214,5.85,2.640924866458E-017) + ); +#118614 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118615 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118616 = PCURVE('',#118468,#118617); +#118617 = DEFINITIONAL_REPRESENTATION('',(#118618),#118621); +#118618 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118619,#118620), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#116227 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#116228 = CARTESIAN_POINT('',(4.772630242227,-4.15)); -#116229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116230 = PCURVE('',#91095,#116231); -#116231 = DEFINITIONAL_REPRESENTATION('',(#116232),#116236); -#116232 = CIRCLE('',#116233,0.208574704164); -#116233 = AXIS2_PLACEMENT_2D('',#116234,#116235); -#116234 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#116235 = DIRECTION('',(0.E+000,-1.)); -#116236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116237 = ORIENTED_EDGE('',*,*,#116238,.F.); -#116238 = EDGE_CURVE('',#116239,#116216,#116241,.T.); -#116239 = VERTEX_POINT('',#116240); -#116240 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.E+000)); -#116241 = SURFACE_CURVE('',#116242,(#116246,#116252),.PCURVE_S1.); -#116242 = LINE('',#116243,#116244); -#116243 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#116244 = VECTOR('',#116245,1.); -#116245 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116246 = PCURVE('',#116076,#116247); -#116247 = DEFINITIONAL_REPRESENTATION('',(#116248),#116251); -#116248 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116249,#116250), +#118619 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#118620 = CARTESIAN_POINT('',(4.772630242227,-4.15)); +#118621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118622 = PCURVE('',#93487,#118623); +#118623 = DEFINITIONAL_REPRESENTATION('',(#118624),#118628); +#118624 = CIRCLE('',#118625,0.208574704164); +#118625 = AXIS2_PLACEMENT_2D('',#118626,#118627); +#118626 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#118627 = DIRECTION('',(0.E+000,-1.)); +#118628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118629 = ORIENTED_EDGE('',*,*,#118630,.F.); +#118630 = EDGE_CURVE('',#118631,#118608,#118633,.T.); +#118631 = VERTEX_POINT('',#118632); +#118632 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.E+000)); +#118633 = SURFACE_CURVE('',#118634,(#118638,#118644),.PCURVE_S1.); +#118634 = LINE('',#118635,#118636); +#118635 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#118636 = VECTOR('',#118637,1.); +#118637 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118638 = PCURVE('',#118468,#118639); +#118639 = DEFINITIONAL_REPRESENTATION('',(#118640),#118643); +#118640 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118641,#118642), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#116249 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#116250 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#116251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116252 = PCURVE('',#116253,#116258); -#116253 = PLANE('',#116254); -#116254 = AXIS2_PLACEMENT_3D('',#116255,#116256,#116257); -#116255 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#116256 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#116257 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116258 = DEFINITIONAL_REPRESENTATION('',(#116259),#116263); -#116259 = LINE('',#116260,#116261); -#116260 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#116261 = VECTOR('',#116262,1.); -#116262 = DIRECTION('',(-1.,0.E+000)); -#116263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116264 = ORIENTED_EDGE('',*,*,#116265,.T.); -#116265 = EDGE_CURVE('',#116239,#116038,#116266,.T.); -#116266 = SURFACE_CURVE('',#116267,(#116272,#116278),.PCURVE_S1.); -#116267 = CIRCLE('',#116268,0.208574704164); -#116268 = AXIS2_PLACEMENT_3D('',#116269,#116270,#116271); -#116269 = CARTESIAN_POINT('',(-0.728168876214,5.65,2.640924866458E-017) - ); -#116270 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116271 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116272 = PCURVE('',#116076,#116273); -#116273 = DEFINITIONAL_REPRESENTATION('',(#116274),#116277); -#116274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116275,#116276), +#118641 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#118642 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#118643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118644 = PCURVE('',#118645,#118650); +#118645 = PLANE('',#118646); +#118646 = AXIS2_PLACEMENT_3D('',#118647,#118648,#118649); +#118647 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#118648 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#118649 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118650 = DEFINITIONAL_REPRESENTATION('',(#118651),#118655); +#118651 = LINE('',#118652,#118653); +#118652 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#118653 = VECTOR('',#118654,1.); +#118654 = DIRECTION('',(-1.,0.E+000)); +#118655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118656 = ORIENTED_EDGE('',*,*,#118657,.T.); +#118657 = EDGE_CURVE('',#118631,#118430,#118658,.T.); +#118658 = SURFACE_CURVE('',#118659,(#118664,#118670),.PCURVE_S1.); +#118659 = CIRCLE('',#118660,0.208574704164); +#118660 = AXIS2_PLACEMENT_3D('',#118661,#118662,#118663); +#118661 = CARTESIAN_POINT('',(-0.728168876214,5.65,2.640924866458E-017) + ); +#118662 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118663 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118664 = PCURVE('',#118468,#118665); +#118665 = DEFINITIONAL_REPRESENTATION('',(#118666),#118669); +#118666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118667,#118668), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#116275 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#116276 = CARTESIAN_POINT('',(4.772630242227,-4.35)); -#116277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118667 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#118668 = CARTESIAN_POINT('',(4.772630242227,-4.35)); +#118669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116278 = PCURVE('',#91039,#116279); -#116279 = DEFINITIONAL_REPRESENTATION('',(#116280),#116288); -#116280 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116281,#116282,#116283, - #116284,#116285,#116286,#116287),.UNSPECIFIED.,.T.,.F.) +#118670 = PCURVE('',#93431,#118671); +#118671 = DEFINITIONAL_REPRESENTATION('',(#118672),#118680); +#118672 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118673,#118674,#118675, + #118676,#118677,#118678,#118679),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#116281 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#116282 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#116283 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#116284 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#116285 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#116286 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#116287 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#116288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116289 = ORIENTED_EDGE('',*,*,#116060,.F.); -#116290 = ADVANCED_FACE('',(#116291),#116180,.T.); -#116291 = FACE_BOUND('',#116292,.T.); -#116292 = EDGE_LOOP('',(#116293,#116320,#116321,#116344)); -#116293 = ORIENTED_EDGE('',*,*,#116294,.T.); -#116294 = EDGE_CURVE('',#116295,#116165,#116297,.T.); -#116295 = VERTEX_POINT('',#116296); -#116296 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.E+000)); -#116297 = SURFACE_CURVE('',#116298,(#116303,#116309),.PCURVE_S1.); -#116298 = CIRCLE('',#116299,0.308574064194); -#116299 = AXIS2_PLACEMENT_3D('',#116300,#116301,#116302); -#116300 = CARTESIAN_POINT('',(-0.728168876214,5.65,2.640924866458E-017) - ); -#116301 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116302 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116303 = PCURVE('',#116180,#116304); -#116304 = DEFINITIONAL_REPRESENTATION('',(#116305),#116308); -#116305 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116306,#116307), +#118673 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#118674 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#118675 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#118676 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#118677 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#118678 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#118679 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#118680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118681 = ORIENTED_EDGE('',*,*,#118452,.F.); +#118682 = ADVANCED_FACE('',(#118683),#118572,.T.); +#118683 = FACE_BOUND('',#118684,.T.); +#118684 = EDGE_LOOP('',(#118685,#118712,#118713,#118736)); +#118685 = ORIENTED_EDGE('',*,*,#118686,.T.); +#118686 = EDGE_CURVE('',#118687,#118557,#118689,.T.); +#118687 = VERTEX_POINT('',#118688); +#118688 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.E+000)); +#118689 = SURFACE_CURVE('',#118690,(#118695,#118701),.PCURVE_S1.); +#118690 = CIRCLE('',#118691,0.308574064194); +#118691 = AXIS2_PLACEMENT_3D('',#118692,#118693,#118694); +#118692 = CARTESIAN_POINT('',(-0.728168876214,5.65,2.640924866458E-017) + ); +#118693 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118694 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118695 = PCURVE('',#118572,#118696); +#118696 = DEFINITIONAL_REPRESENTATION('',(#118697),#118700); +#118697 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118698,#118699), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#116306 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#116307 = CARTESIAN_POINT('',(4.761821717947,-4.35)); -#116308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118698 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#118699 = CARTESIAN_POINT('',(4.761821717947,-4.35)); +#118700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116309 = PCURVE('',#91039,#116310); -#116310 = DEFINITIONAL_REPRESENTATION('',(#116311),#116319); -#116311 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116312,#116313,#116314, - #116315,#116316,#116317,#116318),.UNSPECIFIED.,.T.,.F.) +#118701 = PCURVE('',#93431,#118702); +#118702 = DEFINITIONAL_REPRESENTATION('',(#118703),#118711); +#118703 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118704,#118705,#118706, + #118707,#118708,#118709,#118710),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#116312 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#116313 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#116314 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#116315 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#116316 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#116317 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#116318 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#116319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116320 = ORIENTED_EDGE('',*,*,#116164,.T.); -#116321 = ORIENTED_EDGE('',*,*,#116322,.F.); -#116322 = EDGE_CURVE('',#116323,#116142,#116325,.T.); -#116323 = VERTEX_POINT('',#116324); -#116324 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.E+000)); -#116325 = SURFACE_CURVE('',#116326,(#116331,#116337),.PCURVE_S1.); -#116326 = CIRCLE('',#116327,0.308574064194); -#116327 = AXIS2_PLACEMENT_3D('',#116328,#116329,#116330); -#116328 = CARTESIAN_POINT('',(-0.728168876214,5.85,2.640924866458E-017) - ); -#116329 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116330 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116331 = PCURVE('',#116180,#116332); -#116332 = DEFINITIONAL_REPRESENTATION('',(#116333),#116336); -#116333 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116334,#116335), +#118704 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#118705 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#118706 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#118707 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#118708 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#118709 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#118710 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#118711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118712 = ORIENTED_EDGE('',*,*,#118556,.T.); +#118713 = ORIENTED_EDGE('',*,*,#118714,.F.); +#118714 = EDGE_CURVE('',#118715,#118534,#118717,.T.); +#118715 = VERTEX_POINT('',#118716); +#118716 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.E+000)); +#118717 = SURFACE_CURVE('',#118718,(#118723,#118729),.PCURVE_S1.); +#118718 = CIRCLE('',#118719,0.308574064194); +#118719 = AXIS2_PLACEMENT_3D('',#118720,#118721,#118722); +#118720 = CARTESIAN_POINT('',(-0.728168876214,5.85,2.640924866458E-017) + ); +#118721 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118722 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#118723 = PCURVE('',#118572,#118724); +#118724 = DEFINITIONAL_REPRESENTATION('',(#118725),#118728); +#118725 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118726,#118727), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#116334 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#116335 = CARTESIAN_POINT('',(4.761821717947,-4.15)); -#116336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116337 = PCURVE('',#91095,#116338); -#116338 = DEFINITIONAL_REPRESENTATION('',(#116339),#116343); -#116339 = CIRCLE('',#116340,0.308574064194); -#116340 = AXIS2_PLACEMENT_2D('',#116341,#116342); -#116341 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#116342 = DIRECTION('',(0.E+000,-1.)); -#116343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116344 = ORIENTED_EDGE('',*,*,#116345,.T.); -#116345 = EDGE_CURVE('',#116323,#116295,#116346,.T.); -#116346 = SURFACE_CURVE('',#116347,(#116351,#116357),.PCURVE_S1.); -#116347 = LINE('',#116348,#116349); -#116348 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#116349 = VECTOR('',#116350,1.); -#116350 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116351 = PCURVE('',#116180,#116352); -#116352 = DEFINITIONAL_REPRESENTATION('',(#116353),#116356); -#116353 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116354,#116355), +#118726 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#118727 = CARTESIAN_POINT('',(4.761821717947,-4.15)); +#118728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118729 = PCURVE('',#93487,#118730); +#118730 = DEFINITIONAL_REPRESENTATION('',(#118731),#118735); +#118731 = CIRCLE('',#118732,0.308574064194); +#118732 = AXIS2_PLACEMENT_2D('',#118733,#118734); +#118733 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#118734 = DIRECTION('',(0.E+000,-1.)); +#118735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118736 = ORIENTED_EDGE('',*,*,#118737,.T.); +#118737 = EDGE_CURVE('',#118715,#118687,#118738,.T.); +#118738 = SURFACE_CURVE('',#118739,(#118743,#118749),.PCURVE_S1.); +#118739 = LINE('',#118740,#118741); +#118740 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#118741 = VECTOR('',#118742,1.); +#118742 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118743 = PCURVE('',#118572,#118744); +#118744 = DEFINITIONAL_REPRESENTATION('',(#118745),#118748); +#118745 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118746,#118747), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#116354 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#116355 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#116356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116357 = PCURVE('',#116358,#116363); -#116358 = PLANE('',#116359); -#116359 = AXIS2_PLACEMENT_3D('',#116360,#116361,#116362); -#116360 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#116361 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#116362 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116363 = DEFINITIONAL_REPRESENTATION('',(#116364),#116368); -#116364 = LINE('',#116365,#116366); -#116365 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#116366 = VECTOR('',#116367,1.); -#116367 = DIRECTION('',(-1.,0.E+000)); -#116368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116369 = ADVANCED_FACE('',(#116370),#116358,.T.); -#116370 = FACE_BOUND('',#116371,.T.); -#116371 = EDGE_LOOP('',(#116372,#116401,#116422,#116423)); -#116372 = ORIENTED_EDGE('',*,*,#116373,.T.); -#116373 = EDGE_CURVE('',#116374,#116376,#116378,.T.); -#116374 = VERTEX_POINT('',#116375); -#116375 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.530776333563)); -#116376 = VERTEX_POINT('',#116377); -#116377 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.530776333563)); -#116378 = SURFACE_CURVE('',#116379,(#116383,#116390),.PCURVE_S1.); -#116379 = LINE('',#116380,#116381); -#116380 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#116381 = VECTOR('',#116382,1.); -#116382 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116383 = PCURVE('',#116358,#116384); -#116384 = DEFINITIONAL_REPRESENTATION('',(#116385),#116389); -#116385 = LINE('',#116386,#116387); -#116386 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116387 = VECTOR('',#116388,1.); -#116388 = DIRECTION('',(-1.,0.E+000)); -#116389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116390 = PCURVE('',#116391,#116396); -#116391 = CYLINDRICAL_SURFACE('',#116392,0.119270391569); -#116392 = AXIS2_PLACEMENT_3D('',#116393,#116394,#116395); -#116393 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#116394 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116395 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116396 = DEFINITIONAL_REPRESENTATION('',(#116397),#116400); -#116397 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116398,#116399), +#118746 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#118747 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#118748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118749 = PCURVE('',#118750,#118755); +#118750 = PLANE('',#118751); +#118751 = AXIS2_PLACEMENT_3D('',#118752,#118753,#118754); +#118752 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#118753 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#118754 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118755 = DEFINITIONAL_REPRESENTATION('',(#118756),#118760); +#118756 = LINE('',#118757,#118758); +#118757 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#118758 = VECTOR('',#118759,1.); +#118759 = DIRECTION('',(-1.,0.E+000)); +#118760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118761 = ADVANCED_FACE('',(#118762),#118750,.T.); +#118762 = FACE_BOUND('',#118763,.T.); +#118763 = EDGE_LOOP('',(#118764,#118793,#118814,#118815)); +#118764 = ORIENTED_EDGE('',*,*,#118765,.T.); +#118765 = EDGE_CURVE('',#118766,#118768,#118770,.T.); +#118766 = VERTEX_POINT('',#118767); +#118767 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.530776333563)); +#118768 = VERTEX_POINT('',#118769); +#118769 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.530776333563)); +#118770 = SURFACE_CURVE('',#118771,(#118775,#118782),.PCURVE_S1.); +#118771 = LINE('',#118772,#118773); +#118772 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#118773 = VECTOR('',#118774,1.); +#118774 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118775 = PCURVE('',#118750,#118776); +#118776 = DEFINITIONAL_REPRESENTATION('',(#118777),#118781); +#118777 = LINE('',#118778,#118779); +#118778 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118779 = VECTOR('',#118780,1.); +#118780 = DIRECTION('',(-1.,0.E+000)); +#118781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118782 = PCURVE('',#118783,#118788); +#118783 = CYLINDRICAL_SURFACE('',#118784,0.119270391569); +#118784 = AXIS2_PLACEMENT_3D('',#118785,#118786,#118787); +#118785 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#118786 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118787 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118788 = DEFINITIONAL_REPRESENTATION('',(#118789),#118792); +#118789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118790,#118791), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#116398 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#116399 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#116400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116401 = ORIENTED_EDGE('',*,*,#116402,.T.); -#116402 = EDGE_CURVE('',#116376,#116295,#116403,.T.); -#116403 = SURFACE_CURVE('',#116404,(#116408,#116415),.PCURVE_S1.); -#116404 = LINE('',#116405,#116406); -#116405 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.530776333563)); -#116406 = VECTOR('',#116407,1.); -#116407 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#116408 = PCURVE('',#116358,#116409); -#116409 = DEFINITIONAL_REPRESENTATION('',(#116410),#116414); -#116410 = LINE('',#116411,#116412); -#116411 = CARTESIAN_POINT('',(-4.35,1.133910970711E-033)); -#116412 = VECTOR('',#116413,1.); -#116413 = DIRECTION('',(4.535643882845E-032,-1.)); -#116414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116415 = PCURVE('',#91039,#116416); -#116416 = DEFINITIONAL_REPRESENTATION('',(#116417),#116421); -#116417 = LINE('',#116418,#116419); -#116418 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#116419 = VECTOR('',#116420,1.); -#116420 = DIRECTION('',(1.,-1.021336205033E-016)); -#116421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118790 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#118791 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#118792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118793 = ORIENTED_EDGE('',*,*,#118794,.T.); +#118794 = EDGE_CURVE('',#118768,#118687,#118795,.T.); +#118795 = SURFACE_CURVE('',#118796,(#118800,#118807),.PCURVE_S1.); +#118796 = LINE('',#118797,#118798); +#118797 = CARTESIAN_POINT('',(-0.419594812019,5.65,0.530776333563)); +#118798 = VECTOR('',#118799,1.); +#118799 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#118800 = PCURVE('',#118750,#118801); +#118801 = DEFINITIONAL_REPRESENTATION('',(#118802),#118806); +#118802 = LINE('',#118803,#118804); +#118803 = CARTESIAN_POINT('',(-4.35,1.133910970711E-033)); +#118804 = VECTOR('',#118805,1.); +#118805 = DIRECTION('',(4.535643882845E-032,-1.)); +#118806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118807 = PCURVE('',#93431,#118808); +#118808 = DEFINITIONAL_REPRESENTATION('',(#118809),#118813); +#118809 = LINE('',#118810,#118811); +#118810 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#118811 = VECTOR('',#118812,1.); +#118812 = DIRECTION('',(1.,-1.021336205033E-016)); +#118813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116422 = ORIENTED_EDGE('',*,*,#116345,.F.); -#116423 = ORIENTED_EDGE('',*,*,#116424,.F.); -#116424 = EDGE_CURVE('',#116374,#116323,#116425,.T.); -#116425 = SURFACE_CURVE('',#116426,(#116430,#116437),.PCURVE_S1.); -#116426 = LINE('',#116427,#116428); -#116427 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.530776333563)); -#116428 = VECTOR('',#116429,1.); -#116429 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#116430 = PCURVE('',#116358,#116431); -#116431 = DEFINITIONAL_REPRESENTATION('',(#116432),#116436); -#116432 = LINE('',#116433,#116434); -#116433 = CARTESIAN_POINT('',(-4.15,-1.133910970711E-033)); -#116434 = VECTOR('',#116435,1.); -#116435 = DIRECTION('',(4.535643882845E-032,-1.)); -#116436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116437 = PCURVE('',#91095,#116438); -#116438 = DEFINITIONAL_REPRESENTATION('',(#116439),#116443); -#116439 = LINE('',#116440,#116441); -#116440 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#116441 = VECTOR('',#116442,1.); -#116442 = DIRECTION('',(-1.,-1.021336205033E-016)); -#116443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116444 = ADVANCED_FACE('',(#116445),#116253,.T.); -#116445 = FACE_BOUND('',#116446,.T.); -#116446 = EDGE_LOOP('',(#116447,#116476,#116497,#116498)); -#116447 = ORIENTED_EDGE('',*,*,#116448,.T.); -#116448 = EDGE_CURVE('',#116449,#116451,#116453,.T.); -#116449 = VERTEX_POINT('',#116450); -#116450 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.530776333563)); -#116451 = VERTEX_POINT('',#116452); -#116452 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.530776333563)); -#116453 = SURFACE_CURVE('',#116454,(#116458,#116465),.PCURVE_S1.); -#116454 = LINE('',#116455,#116456); -#116455 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#116456 = VECTOR('',#116457,1.); -#116457 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116458 = PCURVE('',#116253,#116459); -#116459 = DEFINITIONAL_REPRESENTATION('',(#116460),#116464); -#116460 = LINE('',#116461,#116462); -#116461 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116462 = VECTOR('',#116463,1.); -#116463 = DIRECTION('',(-1.,0.E+000)); -#116464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116465 = PCURVE('',#116466,#116471); -#116466 = CYLINDRICAL_SURFACE('',#116467,0.2192697516); -#116467 = AXIS2_PLACEMENT_3D('',#116468,#116469,#116470); -#116468 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#116469 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116470 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116471 = DEFINITIONAL_REPRESENTATION('',(#116472),#116475); -#116472 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116473,#116474), +#118814 = ORIENTED_EDGE('',*,*,#118737,.F.); +#118815 = ORIENTED_EDGE('',*,*,#118816,.F.); +#118816 = EDGE_CURVE('',#118766,#118715,#118817,.T.); +#118817 = SURFACE_CURVE('',#118818,(#118822,#118829),.PCURVE_S1.); +#118818 = LINE('',#118819,#118820); +#118819 = CARTESIAN_POINT('',(-0.419594812019,5.85,0.530776333563)); +#118820 = VECTOR('',#118821,1.); +#118821 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#118822 = PCURVE('',#118750,#118823); +#118823 = DEFINITIONAL_REPRESENTATION('',(#118824),#118828); +#118824 = LINE('',#118825,#118826); +#118825 = CARTESIAN_POINT('',(-4.15,-1.133910970711E-033)); +#118826 = VECTOR('',#118827,1.); +#118827 = DIRECTION('',(4.535643882845E-032,-1.)); +#118828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118829 = PCURVE('',#93487,#118830); +#118830 = DEFINITIONAL_REPRESENTATION('',(#118831),#118835); +#118831 = LINE('',#118832,#118833); +#118832 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#118833 = VECTOR('',#118834,1.); +#118834 = DIRECTION('',(-1.,-1.021336205033E-016)); +#118835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118836 = ADVANCED_FACE('',(#118837),#118645,.T.); +#118837 = FACE_BOUND('',#118838,.T.); +#118838 = EDGE_LOOP('',(#118839,#118868,#118889,#118890)); +#118839 = ORIENTED_EDGE('',*,*,#118840,.T.); +#118840 = EDGE_CURVE('',#118841,#118843,#118845,.T.); +#118841 = VERTEX_POINT('',#118842); +#118842 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.530776333563)); +#118843 = VERTEX_POINT('',#118844); +#118844 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.530776333563)); +#118845 = SURFACE_CURVE('',#118846,(#118850,#118857),.PCURVE_S1.); +#118846 = LINE('',#118847,#118848); +#118847 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#118848 = VECTOR('',#118849,1.); +#118849 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#118850 = PCURVE('',#118645,#118851); +#118851 = DEFINITIONAL_REPRESENTATION('',(#118852),#118856); +#118852 = LINE('',#118853,#118854); +#118853 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#118854 = VECTOR('',#118855,1.); +#118855 = DIRECTION('',(-1.,0.E+000)); +#118856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118857 = PCURVE('',#118858,#118863); +#118858 = CYLINDRICAL_SURFACE('',#118859,0.2192697516); +#118859 = AXIS2_PLACEMENT_3D('',#118860,#118861,#118862); +#118860 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#118861 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118862 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118863 = DEFINITIONAL_REPRESENTATION('',(#118864),#118867); +#118864 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118865,#118866), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#116473 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#116474 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#116475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116476 = ORIENTED_EDGE('',*,*,#116477,.T.); -#116477 = EDGE_CURVE('',#116451,#116216,#116478,.T.); -#116478 = SURFACE_CURVE('',#116479,(#116483,#116490),.PCURVE_S1.); -#116479 = LINE('',#116480,#116481); -#116480 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.530776333563)); -#116481 = VECTOR('',#116482,1.); -#116482 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#116483 = PCURVE('',#116253,#116484); -#116484 = DEFINITIONAL_REPRESENTATION('',(#116485),#116489); -#116485 = LINE('',#116486,#116487); -#116486 = CARTESIAN_POINT('',(4.15,4.535643882845E-033)); -#116487 = VECTOR('',#116488,1.); -#116488 = DIRECTION('',(-4.535643882845E-032,-1.)); -#116489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116490 = PCURVE('',#91095,#116491); -#116491 = DEFINITIONAL_REPRESENTATION('',(#116492),#116496); -#116492 = LINE('',#116493,#116494); -#116493 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#116494 = VECTOR('',#116495,1.); -#116495 = DIRECTION('',(-1.,-1.021336205033E-016)); -#116496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116497 = ORIENTED_EDGE('',*,*,#116238,.F.); -#116498 = ORIENTED_EDGE('',*,*,#116499,.F.); -#116499 = EDGE_CURVE('',#116449,#116239,#116500,.T.); -#116500 = SURFACE_CURVE('',#116501,(#116505,#116512),.PCURVE_S1.); -#116501 = LINE('',#116502,#116503); -#116502 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.530776333563)); -#116503 = VECTOR('',#116504,1.); -#116504 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#116505 = PCURVE('',#116253,#116506); -#116506 = DEFINITIONAL_REPRESENTATION('',(#116507),#116511); -#116507 = LINE('',#116508,#116509); -#116508 = CARTESIAN_POINT('',(4.35,-4.535643882845E-033)); -#116509 = VECTOR('',#116510,1.); -#116510 = DIRECTION('',(-4.535643882845E-032,-1.)); -#116511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116512 = PCURVE('',#91039,#116513); -#116513 = DEFINITIONAL_REPRESENTATION('',(#116514),#116518); -#116514 = LINE('',#116515,#116516); -#116515 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#116516 = VECTOR('',#116517,1.); -#116517 = DIRECTION('',(1.,-1.021336205033E-016)); -#116518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116519 = ADVANCED_FACE('',(#116520),#116466,.T.); -#116520 = FACE_BOUND('',#116521,.T.); -#116521 = EDGE_LOOP('',(#116522,#116523,#116546,#116591)); -#116522 = ORIENTED_EDGE('',*,*,#116448,.F.); -#116523 = ORIENTED_EDGE('',*,*,#116524,.F.); -#116524 = EDGE_CURVE('',#116525,#116449,#116527,.T.); -#116525 = VERTEX_POINT('',#116526); -#116526 = CARTESIAN_POINT('',(-0.304819755875,5.65,0.75)); -#116527 = SURFACE_CURVE('',#116528,(#116533,#116539),.PCURVE_S1.); -#116528 = CIRCLE('',#116529,0.2192697516); -#116529 = AXIS2_PLACEMENT_3D('',#116530,#116531,#116532); -#116530 = CARTESIAN_POINT('',(-0.30032442045,5.65,0.530776333563)); -#116531 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116532 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116533 = PCURVE('',#116466,#116534); -#116534 = DEFINITIONAL_REPRESENTATION('',(#116535),#116538); -#116535 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116536,#116537), +#118865 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#118866 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#118867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118868 = ORIENTED_EDGE('',*,*,#118869,.T.); +#118869 = EDGE_CURVE('',#118843,#118608,#118870,.T.); +#118870 = SURFACE_CURVE('',#118871,(#118875,#118882),.PCURVE_S1.); +#118871 = LINE('',#118872,#118873); +#118872 = CARTESIAN_POINT('',(-0.51959417205,5.85,0.530776333563)); +#118873 = VECTOR('',#118874,1.); +#118874 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#118875 = PCURVE('',#118645,#118876); +#118876 = DEFINITIONAL_REPRESENTATION('',(#118877),#118881); +#118877 = LINE('',#118878,#118879); +#118878 = CARTESIAN_POINT('',(4.15,4.535643882845E-033)); +#118879 = VECTOR('',#118880,1.); +#118880 = DIRECTION('',(-4.535643882845E-032,-1.)); +#118881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118882 = PCURVE('',#93487,#118883); +#118883 = DEFINITIONAL_REPRESENTATION('',(#118884),#118888); +#118884 = LINE('',#118885,#118886); +#118885 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#118886 = VECTOR('',#118887,1.); +#118887 = DIRECTION('',(-1.,-1.021336205033E-016)); +#118888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118889 = ORIENTED_EDGE('',*,*,#118630,.F.); +#118890 = ORIENTED_EDGE('',*,*,#118891,.F.); +#118891 = EDGE_CURVE('',#118841,#118631,#118892,.T.); +#118892 = SURFACE_CURVE('',#118893,(#118897,#118904),.PCURVE_S1.); +#118893 = LINE('',#118894,#118895); +#118894 = CARTESIAN_POINT('',(-0.51959417205,5.65,0.530776333563)); +#118895 = VECTOR('',#118896,1.); +#118896 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#118897 = PCURVE('',#118645,#118898); +#118898 = DEFINITIONAL_REPRESENTATION('',(#118899),#118903); +#118899 = LINE('',#118900,#118901); +#118900 = CARTESIAN_POINT('',(4.35,-4.535643882845E-033)); +#118901 = VECTOR('',#118902,1.); +#118902 = DIRECTION('',(-4.535643882845E-032,-1.)); +#118903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118904 = PCURVE('',#93431,#118905); +#118905 = DEFINITIONAL_REPRESENTATION('',(#118906),#118910); +#118906 = LINE('',#118907,#118908); +#118907 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#118908 = VECTOR('',#118909,1.); +#118909 = DIRECTION('',(1.,-1.021336205033E-016)); +#118910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118911 = ADVANCED_FACE('',(#118912),#118858,.T.); +#118912 = FACE_BOUND('',#118913,.T.); +#118913 = EDGE_LOOP('',(#118914,#118915,#118938,#118983)); +#118914 = ORIENTED_EDGE('',*,*,#118840,.F.); +#118915 = ORIENTED_EDGE('',*,*,#118916,.F.); +#118916 = EDGE_CURVE('',#118917,#118841,#118919,.T.); +#118917 = VERTEX_POINT('',#118918); +#118918 = CARTESIAN_POINT('',(-0.304819755875,5.65,0.75)); +#118919 = SURFACE_CURVE('',#118920,(#118925,#118931),.PCURVE_S1.); +#118920 = CIRCLE('',#118921,0.2192697516); +#118921 = AXIS2_PLACEMENT_3D('',#118922,#118923,#118924); +#118922 = CARTESIAN_POINT('',(-0.30032442045,5.65,0.530776333563)); +#118923 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118924 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118925 = PCURVE('',#118858,#118926); +#118926 = DEFINITIONAL_REPRESENTATION('',(#118927),#118930); +#118927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118928,#118929), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#116536 = CARTESIAN_POINT('',(1.591299156552,4.35)); -#116537 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#116538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116539 = PCURVE('',#91039,#116540); -#116540 = DEFINITIONAL_REPRESENTATION('',(#116541),#116545); -#116541 = CIRCLE('',#116542,0.2192697516); -#116542 = AXIS2_PLACEMENT_2D('',#116543,#116544); -#116543 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#116544 = DIRECTION('',(0.E+000,1.)); -#116545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116546 = ORIENTED_EDGE('',*,*,#116547,.F.); -#116547 = EDGE_CURVE('',#116548,#116525,#116550,.T.); -#116548 = VERTEX_POINT('',#116549); -#116549 = CARTESIAN_POINT('',(-0.304819755875,5.85,0.75)); -#116550 = SURFACE_CURVE('',#116551,(#116555,#116584),.PCURVE_S1.); -#116551 = LINE('',#116552,#116553); -#116552 = CARTESIAN_POINT('',(-0.304819755875,5.65,0.75)); -#116553 = VECTOR('',#116554,1.); -#116554 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116555 = PCURVE('',#116466,#116556); -#116556 = DEFINITIONAL_REPRESENTATION('',(#116557),#116583); -#116557 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#116558,#116559,#116560, - #116561,#116562,#116563,#116564,#116565,#116566,#116567,#116568, - #116569,#116570,#116571,#116572,#116573,#116574,#116575,#116576, - #116577,#116578,#116579,#116580,#116581,#116582),.UNSPECIFIED.,.F., +#118928 = CARTESIAN_POINT('',(1.591299156552,4.35)); +#118929 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#118930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118931 = PCURVE('',#93431,#118932); +#118932 = DEFINITIONAL_REPRESENTATION('',(#118933),#118937); +#118933 = CIRCLE('',#118934,0.2192697516); +#118934 = AXIS2_PLACEMENT_2D('',#118935,#118936); +#118935 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#118936 = DIRECTION('',(0.E+000,1.)); +#118937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118938 = ORIENTED_EDGE('',*,*,#118939,.F.); +#118939 = EDGE_CURVE('',#118940,#118917,#118942,.T.); +#118940 = VERTEX_POINT('',#118941); +#118941 = CARTESIAN_POINT('',(-0.304819755875,5.85,0.75)); +#118942 = SURFACE_CURVE('',#118943,(#118947,#118976),.PCURVE_S1.); +#118943 = LINE('',#118944,#118945); +#118944 = CARTESIAN_POINT('',(-0.304819755875,5.65,0.75)); +#118945 = VECTOR('',#118946,1.); +#118946 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118947 = PCURVE('',#118858,#118948); +#118948 = DEFINITIONAL_REPRESENTATION('',(#118949),#118975); +#118949 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#118950,#118951,#118952, + #118953,#118954,#118955,#118956,#118957,#118958,#118959,#118960, + #118961,#118962,#118963,#118964,#118965,#118966,#118967,#118968, + #118969,#118970,#118971,#118972,#118973,#118974),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -143571,128 +146573,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.QUASI_UNIFORM_KNOTS.); -#116558 = CARTESIAN_POINT('',(1.591299156552,4.15)); -#116559 = CARTESIAN_POINT('',(1.591299156552,4.15303030303)); -#116560 = CARTESIAN_POINT('',(1.591299156552,4.159090909091)); -#116561 = CARTESIAN_POINT('',(1.591299156552,4.168181818182)); -#116562 = CARTESIAN_POINT('',(1.591299156552,4.177272727273)); -#116563 = CARTESIAN_POINT('',(1.591299156552,4.186363636364)); -#116564 = CARTESIAN_POINT('',(1.591299156552,4.195454545455)); -#116565 = CARTESIAN_POINT('',(1.591299156552,4.204545454545)); -#116566 = CARTESIAN_POINT('',(1.591299156552,4.213636363636)); -#116567 = CARTESIAN_POINT('',(1.591299156552,4.222727272727)); -#116568 = CARTESIAN_POINT('',(1.591299156552,4.231818181818)); -#116569 = CARTESIAN_POINT('',(1.591299156552,4.240909090909)); -#116570 = CARTESIAN_POINT('',(1.591299156552,4.25)); -#116571 = CARTESIAN_POINT('',(1.591299156552,4.259090909091)); -#116572 = CARTESIAN_POINT('',(1.591299156552,4.268181818182)); -#116573 = CARTESIAN_POINT('',(1.591299156552,4.277272727273)); -#116574 = CARTESIAN_POINT('',(1.591299156552,4.286363636364)); -#116575 = CARTESIAN_POINT('',(1.591299156552,4.295454545455)); -#116576 = CARTESIAN_POINT('',(1.591299156552,4.304545454545)); -#116577 = CARTESIAN_POINT('',(1.591299156552,4.313636363636)); -#116578 = CARTESIAN_POINT('',(1.591299156552,4.322727272727)); -#116579 = CARTESIAN_POINT('',(1.591299156552,4.331818181818)); -#116580 = CARTESIAN_POINT('',(1.591299156552,4.340909090909)); -#116581 = CARTESIAN_POINT('',(1.591299156552,4.34696969697)); -#116582 = CARTESIAN_POINT('',(1.591299156552,4.35)); -#116583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116584 = PCURVE('',#91121,#116585); -#116585 = DEFINITIONAL_REPRESENTATION('',(#116586),#116590); -#116586 = LINE('',#116587,#116588); -#116587 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#116588 = VECTOR('',#116589,1.); -#116589 = DIRECTION('',(4.440892098501E-016,-1.)); -#116590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116591 = ORIENTED_EDGE('',*,*,#116592,.T.); -#116592 = EDGE_CURVE('',#116548,#116451,#116593,.T.); -#116593 = SURFACE_CURVE('',#116594,(#116599,#116605),.PCURVE_S1.); -#116594 = CIRCLE('',#116595,0.2192697516); -#116595 = AXIS2_PLACEMENT_3D('',#116596,#116597,#116598); -#116596 = CARTESIAN_POINT('',(-0.30032442045,5.85,0.530776333563)); -#116597 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116598 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116599 = PCURVE('',#116466,#116600); -#116600 = DEFINITIONAL_REPRESENTATION('',(#116601),#116604); -#116601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116602,#116603), +#118950 = CARTESIAN_POINT('',(1.591299156552,4.15)); +#118951 = CARTESIAN_POINT('',(1.591299156552,4.15303030303)); +#118952 = CARTESIAN_POINT('',(1.591299156552,4.159090909091)); +#118953 = CARTESIAN_POINT('',(1.591299156552,4.168181818182)); +#118954 = CARTESIAN_POINT('',(1.591299156552,4.177272727273)); +#118955 = CARTESIAN_POINT('',(1.591299156552,4.186363636364)); +#118956 = CARTESIAN_POINT('',(1.591299156552,4.195454545455)); +#118957 = CARTESIAN_POINT('',(1.591299156552,4.204545454545)); +#118958 = CARTESIAN_POINT('',(1.591299156552,4.213636363636)); +#118959 = CARTESIAN_POINT('',(1.591299156552,4.222727272727)); +#118960 = CARTESIAN_POINT('',(1.591299156552,4.231818181818)); +#118961 = CARTESIAN_POINT('',(1.591299156552,4.240909090909)); +#118962 = CARTESIAN_POINT('',(1.591299156552,4.25)); +#118963 = CARTESIAN_POINT('',(1.591299156552,4.259090909091)); +#118964 = CARTESIAN_POINT('',(1.591299156552,4.268181818182)); +#118965 = CARTESIAN_POINT('',(1.591299156552,4.277272727273)); +#118966 = CARTESIAN_POINT('',(1.591299156552,4.286363636364)); +#118967 = CARTESIAN_POINT('',(1.591299156552,4.295454545455)); +#118968 = CARTESIAN_POINT('',(1.591299156552,4.304545454545)); +#118969 = CARTESIAN_POINT('',(1.591299156552,4.313636363636)); +#118970 = CARTESIAN_POINT('',(1.591299156552,4.322727272727)); +#118971 = CARTESIAN_POINT('',(1.591299156552,4.331818181818)); +#118972 = CARTESIAN_POINT('',(1.591299156552,4.340909090909)); +#118973 = CARTESIAN_POINT('',(1.591299156552,4.34696969697)); +#118974 = CARTESIAN_POINT('',(1.591299156552,4.35)); +#118975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118976 = PCURVE('',#93513,#118977); +#118977 = DEFINITIONAL_REPRESENTATION('',(#118978),#118982); +#118978 = LINE('',#118979,#118980); +#118979 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#118980 = VECTOR('',#118981,1.); +#118981 = DIRECTION('',(4.440892098501E-016,-1.)); +#118982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#118983 = ORIENTED_EDGE('',*,*,#118984,.T.); +#118984 = EDGE_CURVE('',#118940,#118843,#118985,.T.); +#118985 = SURFACE_CURVE('',#118986,(#118991,#118997),.PCURVE_S1.); +#118986 = CIRCLE('',#118987,0.2192697516); +#118987 = AXIS2_PLACEMENT_3D('',#118988,#118989,#118990); +#118988 = CARTESIAN_POINT('',(-0.30032442045,5.85,0.530776333563)); +#118989 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#118990 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#118991 = PCURVE('',#118858,#118992); +#118992 = DEFINITIONAL_REPRESENTATION('',(#118993),#118996); +#118993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118994,#118995), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#116602 = CARTESIAN_POINT('',(1.591299156552,4.15)); -#116603 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#116604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#118994 = CARTESIAN_POINT('',(1.591299156552,4.15)); +#118995 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#118996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116605 = PCURVE('',#91095,#116606); -#116606 = DEFINITIONAL_REPRESENTATION('',(#116607),#116615); -#116607 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116608,#116609,#116610, - #116611,#116612,#116613,#116614),.UNSPECIFIED.,.T.,.F.) +#118997 = PCURVE('',#93487,#118998); +#118998 = DEFINITIONAL_REPRESENTATION('',(#118999),#119007); +#118999 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119000,#119001,#119002, + #119003,#119004,#119005,#119006),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#116608 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#116609 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#116610 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#116611 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#116612 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#116613 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#116614 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#116615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116616 = ADVANCED_FACE('',(#116617),#116391,.F.); -#116617 = FACE_BOUND('',#116618,.F.); -#116618 = EDGE_LOOP('',(#116619,#116620,#116643,#116688)); -#116619 = ORIENTED_EDGE('',*,*,#116373,.T.); -#116620 = ORIENTED_EDGE('',*,*,#116621,.F.); -#116621 = EDGE_CURVE('',#116622,#116376,#116624,.T.); -#116622 = VERTEX_POINT('',#116623); -#116623 = CARTESIAN_POINT('',(-0.303662633502,5.65,0.65)); -#116624 = SURFACE_CURVE('',#116625,(#116630,#116636),.PCURVE_S1.); -#116625 = CIRCLE('',#116626,0.119270391569); -#116626 = AXIS2_PLACEMENT_3D('',#116627,#116628,#116629); -#116627 = CARTESIAN_POINT('',(-0.30032442045,5.65,0.530776333563)); -#116628 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116629 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116630 = PCURVE('',#116391,#116631); -#116631 = DEFINITIONAL_REPRESENTATION('',(#116632),#116635); -#116632 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116633,#116634), +#119000 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#119001 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#119002 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#119003 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#119004 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#119005 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#119006 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#119007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119008 = ADVANCED_FACE('',(#119009),#118783,.F.); +#119009 = FACE_BOUND('',#119010,.F.); +#119010 = EDGE_LOOP('',(#119011,#119012,#119035,#119080)); +#119011 = ORIENTED_EDGE('',*,*,#118765,.T.); +#119012 = ORIENTED_EDGE('',*,*,#119013,.F.); +#119013 = EDGE_CURVE('',#119014,#118768,#119016,.T.); +#119014 = VERTEX_POINT('',#119015); +#119015 = CARTESIAN_POINT('',(-0.303662633502,5.65,0.65)); +#119016 = SURFACE_CURVE('',#119017,(#119022,#119028),.PCURVE_S1.); +#119017 = CIRCLE('',#119018,0.119270391569); +#119018 = AXIS2_PLACEMENT_3D('',#119019,#119020,#119021); +#119019 = CARTESIAN_POINT('',(-0.30032442045,5.65,0.530776333563)); +#119020 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119021 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119022 = PCURVE('',#118783,#119023); +#119023 = DEFINITIONAL_REPRESENTATION('',(#119024),#119027); +#119024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119025,#119026), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#116633 = CARTESIAN_POINT('',(1.598788597134,4.35)); -#116634 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#116635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116636 = PCURVE('',#91039,#116637); -#116637 = DEFINITIONAL_REPRESENTATION('',(#116638),#116642); -#116638 = CIRCLE('',#116639,0.119270391569); -#116639 = AXIS2_PLACEMENT_2D('',#116640,#116641); -#116640 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#116641 = DIRECTION('',(0.E+000,1.)); -#116642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116643 = ORIENTED_EDGE('',*,*,#116644,.T.); -#116644 = EDGE_CURVE('',#116622,#116645,#116647,.T.); -#116645 = VERTEX_POINT('',#116646); -#116646 = CARTESIAN_POINT('',(-0.303662633502,5.85,0.65)); -#116647 = SURFACE_CURVE('',#116648,(#116652,#116681),.PCURVE_S1.); -#116648 = LINE('',#116649,#116650); -#116649 = CARTESIAN_POINT('',(-0.303662633502,5.65,0.65)); -#116650 = VECTOR('',#116651,1.); -#116651 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116652 = PCURVE('',#116391,#116653); -#116653 = DEFINITIONAL_REPRESENTATION('',(#116654),#116680); -#116654 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#116655,#116656,#116657, - #116658,#116659,#116660,#116661,#116662,#116663,#116664,#116665, - #116666,#116667,#116668,#116669,#116670,#116671,#116672,#116673, - #116674,#116675,#116676,#116677,#116678,#116679),.UNSPECIFIED.,.F., +#119025 = CARTESIAN_POINT('',(1.598788597134,4.35)); +#119026 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#119027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119028 = PCURVE('',#93431,#119029); +#119029 = DEFINITIONAL_REPRESENTATION('',(#119030),#119034); +#119030 = CIRCLE('',#119031,0.119270391569); +#119031 = AXIS2_PLACEMENT_2D('',#119032,#119033); +#119032 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#119033 = DIRECTION('',(0.E+000,1.)); +#119034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119035 = ORIENTED_EDGE('',*,*,#119036,.T.); +#119036 = EDGE_CURVE('',#119014,#119037,#119039,.T.); +#119037 = VERTEX_POINT('',#119038); +#119038 = CARTESIAN_POINT('',(-0.303662633502,5.85,0.65)); +#119039 = SURFACE_CURVE('',#119040,(#119044,#119073),.PCURVE_S1.); +#119040 = LINE('',#119041,#119042); +#119041 = CARTESIAN_POINT('',(-0.303662633502,5.65,0.65)); +#119042 = VECTOR('',#119043,1.); +#119043 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119044 = PCURVE('',#118783,#119045); +#119045 = DEFINITIONAL_REPRESENTATION('',(#119046),#119072); +#119046 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#119047,#119048,#119049, + #119050,#119051,#119052,#119053,#119054,#119055,#119056,#119057, + #119058,#119059,#119060,#119061,#119062,#119063,#119064,#119065, + #119066,#119067,#119068,#119069,#119070,#119071),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -143701,956 +146703,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ,0.136363636364,0.145454545455,0.154545454545,0.163636363636, 0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#116655 = CARTESIAN_POINT('',(1.598788597134,4.35)); -#116656 = CARTESIAN_POINT('',(1.598788597134,4.34696969697)); -#116657 = CARTESIAN_POINT('',(1.598788597134,4.340909090909)); -#116658 = CARTESIAN_POINT('',(1.598788597134,4.331818181818)); -#116659 = CARTESIAN_POINT('',(1.598788597134,4.322727272727)); -#116660 = CARTESIAN_POINT('',(1.598788597134,4.313636363636)); -#116661 = CARTESIAN_POINT('',(1.598788597134,4.304545454545)); -#116662 = CARTESIAN_POINT('',(1.598788597134,4.295454545455)); -#116663 = CARTESIAN_POINT('',(1.598788597134,4.286363636364)); -#116664 = CARTESIAN_POINT('',(1.598788597134,4.277272727273)); -#116665 = CARTESIAN_POINT('',(1.598788597134,4.268181818182)); -#116666 = CARTESIAN_POINT('',(1.598788597134,4.259090909091)); -#116667 = CARTESIAN_POINT('',(1.598788597134,4.25)); -#116668 = CARTESIAN_POINT('',(1.598788597134,4.240909090909)); -#116669 = CARTESIAN_POINT('',(1.598788597134,4.231818181818)); -#116670 = CARTESIAN_POINT('',(1.598788597134,4.222727272727)); -#116671 = CARTESIAN_POINT('',(1.598788597134,4.213636363636)); -#116672 = CARTESIAN_POINT('',(1.598788597134,4.204545454545)); -#116673 = CARTESIAN_POINT('',(1.598788597134,4.195454545455)); -#116674 = CARTESIAN_POINT('',(1.598788597134,4.186363636364)); -#116675 = CARTESIAN_POINT('',(1.598788597134,4.177272727273)); -#116676 = CARTESIAN_POINT('',(1.598788597134,4.168181818182)); -#116677 = CARTESIAN_POINT('',(1.598788597134,4.159090909091)); -#116678 = CARTESIAN_POINT('',(1.598788597134,4.15303030303)); -#116679 = CARTESIAN_POINT('',(1.598788597134,4.15)); -#116680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116681 = PCURVE('',#91067,#116682); -#116682 = DEFINITIONAL_REPRESENTATION('',(#116683),#116687); -#116683 = LINE('',#116684,#116685); -#116684 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#116685 = VECTOR('',#116686,1.); -#116686 = DIRECTION('',(4.440892098501E-016,1.)); -#116687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116688 = ORIENTED_EDGE('',*,*,#116689,.T.); -#116689 = EDGE_CURVE('',#116645,#116374,#116690,.T.); -#116690 = SURFACE_CURVE('',#116691,(#116696,#116702),.PCURVE_S1.); -#116691 = CIRCLE('',#116692,0.119270391569); -#116692 = AXIS2_PLACEMENT_3D('',#116693,#116694,#116695); -#116693 = CARTESIAN_POINT('',(-0.30032442045,5.85,0.530776333563)); -#116694 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116695 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#116696 = PCURVE('',#116391,#116697); -#116697 = DEFINITIONAL_REPRESENTATION('',(#116698),#116701); -#116698 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116699,#116700), +#119047 = CARTESIAN_POINT('',(1.598788597134,4.35)); +#119048 = CARTESIAN_POINT('',(1.598788597134,4.34696969697)); +#119049 = CARTESIAN_POINT('',(1.598788597134,4.340909090909)); +#119050 = CARTESIAN_POINT('',(1.598788597134,4.331818181818)); +#119051 = CARTESIAN_POINT('',(1.598788597134,4.322727272727)); +#119052 = CARTESIAN_POINT('',(1.598788597134,4.313636363636)); +#119053 = CARTESIAN_POINT('',(1.598788597134,4.304545454545)); +#119054 = CARTESIAN_POINT('',(1.598788597134,4.295454545455)); +#119055 = CARTESIAN_POINT('',(1.598788597134,4.286363636364)); +#119056 = CARTESIAN_POINT('',(1.598788597134,4.277272727273)); +#119057 = CARTESIAN_POINT('',(1.598788597134,4.268181818182)); +#119058 = CARTESIAN_POINT('',(1.598788597134,4.259090909091)); +#119059 = CARTESIAN_POINT('',(1.598788597134,4.25)); +#119060 = CARTESIAN_POINT('',(1.598788597134,4.240909090909)); +#119061 = CARTESIAN_POINT('',(1.598788597134,4.231818181818)); +#119062 = CARTESIAN_POINT('',(1.598788597134,4.222727272727)); +#119063 = CARTESIAN_POINT('',(1.598788597134,4.213636363636)); +#119064 = CARTESIAN_POINT('',(1.598788597134,4.204545454545)); +#119065 = CARTESIAN_POINT('',(1.598788597134,4.195454545455)); +#119066 = CARTESIAN_POINT('',(1.598788597134,4.186363636364)); +#119067 = CARTESIAN_POINT('',(1.598788597134,4.177272727273)); +#119068 = CARTESIAN_POINT('',(1.598788597134,4.168181818182)); +#119069 = CARTESIAN_POINT('',(1.598788597134,4.159090909091)); +#119070 = CARTESIAN_POINT('',(1.598788597134,4.15303030303)); +#119071 = CARTESIAN_POINT('',(1.598788597134,4.15)); +#119072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119073 = PCURVE('',#93459,#119074); +#119074 = DEFINITIONAL_REPRESENTATION('',(#119075),#119079); +#119075 = LINE('',#119076,#119077); +#119076 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#119077 = VECTOR('',#119078,1.); +#119078 = DIRECTION('',(4.440892098501E-016,1.)); +#119079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119080 = ORIENTED_EDGE('',*,*,#119081,.T.); +#119081 = EDGE_CURVE('',#119037,#118766,#119082,.T.); +#119082 = SURFACE_CURVE('',#119083,(#119088,#119094),.PCURVE_S1.); +#119083 = CIRCLE('',#119084,0.119270391569); +#119084 = AXIS2_PLACEMENT_3D('',#119085,#119086,#119087); +#119085 = CARTESIAN_POINT('',(-0.30032442045,5.85,0.530776333563)); +#119086 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119087 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119088 = PCURVE('',#118783,#119089); +#119089 = DEFINITIONAL_REPRESENTATION('',(#119090),#119093); +#119090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119091,#119092), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#116699 = CARTESIAN_POINT('',(1.598788597134,4.15)); -#116700 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#116701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119091 = CARTESIAN_POINT('',(1.598788597134,4.15)); +#119092 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#119093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116702 = PCURVE('',#91095,#116703); -#116703 = DEFINITIONAL_REPRESENTATION('',(#116704),#116712); -#116704 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#116705,#116706,#116707, - #116708,#116709,#116710,#116711),.UNSPECIFIED.,.T.,.F.) +#119094 = PCURVE('',#93487,#119095); +#119095 = DEFINITIONAL_REPRESENTATION('',(#119096),#119104); +#119096 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119097,#119098,#119099, + #119100,#119101,#119102,#119103),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#116705 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#116706 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#116707 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#116708 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#116709 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#116710 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#116711 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#116712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116713 = ADVANCED_FACE('',(#116714),#91067,.T.); -#116714 = FACE_BOUND('',#116715,.T.); -#116715 = EDGE_LOOP('',(#116716,#116737,#116738,#116759)); -#116716 = ORIENTED_EDGE('',*,*,#116717,.F.); -#116717 = EDGE_CURVE('',#116622,#91024,#116718,.T.); -#116718 = SURFACE_CURVE('',#116719,(#116723,#116730),.PCURVE_S1.); -#116719 = LINE('',#116720,#116721); -#116720 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); -#116721 = VECTOR('',#116722,1.); -#116722 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#116723 = PCURVE('',#91067,#116724); -#116724 = DEFINITIONAL_REPRESENTATION('',(#116725),#116729); -#116725 = LINE('',#116726,#116727); -#116726 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116727 = VECTOR('',#116728,1.); -#116728 = DIRECTION('',(-1.,-4.804757279354E-063)); -#116729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116730 = PCURVE('',#91039,#116731); -#116731 = DEFINITIONAL_REPRESENTATION('',(#116732),#116736); -#116732 = LINE('',#116733,#116734); -#116733 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116734 = VECTOR('',#116735,1.); -#116735 = DIRECTION('',(-3.563627120235E-016,1.)); -#116736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116737 = ORIENTED_EDGE('',*,*,#116644,.T.); -#116738 = ORIENTED_EDGE('',*,*,#116739,.T.); -#116739 = EDGE_CURVE('',#116645,#91052,#116740,.T.); -#116740 = SURFACE_CURVE('',#116741,(#116745,#116752),.PCURVE_S1.); -#116741 = LINE('',#116742,#116743); -#116742 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.65)); -#116743 = VECTOR('',#116744,1.); -#116744 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#116745 = PCURVE('',#91067,#116746); -#116746 = DEFINITIONAL_REPRESENTATION('',(#116747),#116751); -#116747 = LINE('',#116748,#116749); -#116748 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#116749 = VECTOR('',#116750,1.); -#116750 = DIRECTION('',(-1.,-4.804757279354E-063)); -#116751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116752 = PCURVE('',#91095,#116753); -#116753 = DEFINITIONAL_REPRESENTATION('',(#116754),#116758); -#116754 = LINE('',#116755,#116756); -#116755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116756 = VECTOR('',#116757,1.); -#116757 = DIRECTION('',(3.563627120235E-016,1.)); -#116758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116759 = ORIENTED_EDGE('',*,*,#91051,.F.); -#116760 = ADVANCED_FACE('',(#116761),#91095,.T.); -#116761 = FACE_BOUND('',#116762,.T.); -#116762 = EDGE_LOOP('',(#116763,#116764,#116765,#116766,#116767,#116768, - #116789,#116790,#116791,#116792,#116793,#116814)); -#116763 = ORIENTED_EDGE('',*,*,#116739,.F.); -#116764 = ORIENTED_EDGE('',*,*,#116689,.T.); -#116765 = ORIENTED_EDGE('',*,*,#116424,.T.); -#116766 = ORIENTED_EDGE('',*,*,#116322,.T.); -#116767 = ORIENTED_EDGE('',*,*,#116141,.T.); -#116768 = ORIENTED_EDGE('',*,*,#116769,.F.); -#116769 = EDGE_CURVE('',#116005,#116112,#116770,.T.); -#116770 = SURFACE_CURVE('',#116771,(#116775,#116782),.PCURVE_S1.); -#116771 = LINE('',#116772,#116773); -#116772 = CARTESIAN_POINT('',(-1.,5.85,1.159810404338E-002)); -#116773 = VECTOR('',#116774,1.); -#116774 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#116775 = PCURVE('',#91095,#116776); -#116776 = DEFINITIONAL_REPRESENTATION('',(#116777),#116781); -#116777 = LINE('',#116778,#116779); -#116778 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#116779 = VECTOR('',#116780,1.); -#116780 = DIRECTION('',(-1.,2.101748079665E-016)); -#116781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116782 = PCURVE('',#116025,#116783); -#116783 = DEFINITIONAL_REPRESENTATION('',(#116784),#116788); -#116784 = LINE('',#116785,#116786); -#116785 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#116786 = VECTOR('',#116787,1.); -#116787 = DIRECTION('',(1.194699204908E-017,-1.)); -#116788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116789 = ORIENTED_EDGE('',*,*,#116087,.F.); -#116790 = ORIENTED_EDGE('',*,*,#116215,.F.); -#116791 = ORIENTED_EDGE('',*,*,#116477,.F.); -#116792 = ORIENTED_EDGE('',*,*,#116592,.F.); -#116793 = ORIENTED_EDGE('',*,*,#116794,.T.); -#116794 = EDGE_CURVE('',#116548,#91080,#116795,.T.); -#116795 = SURFACE_CURVE('',#116796,(#116800,#116807),.PCURVE_S1.); -#116796 = LINE('',#116797,#116798); -#116797 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.75)); -#116798 = VECTOR('',#116799,1.); -#116799 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#116800 = PCURVE('',#91095,#116801); -#116801 = DEFINITIONAL_REPRESENTATION('',(#116802),#116806); -#116802 = LINE('',#116803,#116804); -#116803 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#116804 = VECTOR('',#116805,1.); -#116805 = DIRECTION('',(3.563627120235E-016,1.)); -#116806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116807 = PCURVE('',#91121,#116808); -#116808 = DEFINITIONAL_REPRESENTATION('',(#116809),#116813); -#116809 = LINE('',#116810,#116811); -#116810 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#116811 = VECTOR('',#116812,1.); -#116812 = DIRECTION('',(1.,-4.804757279354E-063)); -#116813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116814 = ORIENTED_EDGE('',*,*,#91079,.F.); -#116815 = ADVANCED_FACE('',(#116816),#91121,.T.); -#116816 = FACE_BOUND('',#116817,.T.); -#116817 = EDGE_LOOP('',(#116818,#116819,#116820,#116841)); -#116818 = ORIENTED_EDGE('',*,*,#116794,.F.); -#116819 = ORIENTED_EDGE('',*,*,#116547,.T.); -#116820 = ORIENTED_EDGE('',*,*,#116821,.T.); -#116821 = EDGE_CURVE('',#116525,#91022,#116822,.T.); -#116822 = SURFACE_CURVE('',#116823,(#116827,#116834),.PCURVE_S1.); -#116823 = LINE('',#116824,#116825); -#116824 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.75)); -#116825 = VECTOR('',#116826,1.); -#116826 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#116827 = PCURVE('',#91121,#116828); -#116828 = DEFINITIONAL_REPRESENTATION('',(#116829),#116833); -#116829 = LINE('',#116830,#116831); -#116830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116831 = VECTOR('',#116832,1.); -#116832 = DIRECTION('',(1.,-4.804757279354E-063)); -#116833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116834 = PCURVE('',#91039,#116835); -#116835 = DEFINITIONAL_REPRESENTATION('',(#116836),#116840); -#116836 = LINE('',#116837,#116838); -#116837 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#116838 = VECTOR('',#116839,1.); -#116839 = DIRECTION('',(-3.563627120235E-016,1.)); -#116840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116841 = ORIENTED_EDGE('',*,*,#91107,.F.); -#116842 = ADVANCED_FACE('',(#116843),#91039,.T.); -#116843 = FACE_BOUND('',#116844,.T.); -#116844 = EDGE_LOOP('',(#116845,#116846,#116847,#116848,#116849,#116850, - #116871,#116872,#116873,#116874,#116875,#116876)); -#116845 = ORIENTED_EDGE('',*,*,#116821,.F.); -#116846 = ORIENTED_EDGE('',*,*,#116524,.T.); -#116847 = ORIENTED_EDGE('',*,*,#116499,.T.); -#116848 = ORIENTED_EDGE('',*,*,#116265,.T.); -#116849 = ORIENTED_EDGE('',*,*,#116037,.T.); -#116850 = ORIENTED_EDGE('',*,*,#116851,.F.); -#116851 = EDGE_CURVE('',#116114,#116003,#116852,.T.); -#116852 = SURFACE_CURVE('',#116853,(#116857,#116864),.PCURVE_S1.); -#116853 = LINE('',#116854,#116855); -#116854 = CARTESIAN_POINT('',(-1.,5.65,1.159810404338E-002)); -#116855 = VECTOR('',#116856,1.); -#116856 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#116857 = PCURVE('',#91039,#116858); -#116858 = DEFINITIONAL_REPRESENTATION('',(#116859),#116863); -#116859 = LINE('',#116860,#116861); -#116860 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#116861 = VECTOR('',#116862,1.); -#116862 = DIRECTION('',(-1.,-2.101748079665E-016)); -#116863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116864 = PCURVE('',#116025,#116865); -#116865 = DEFINITIONAL_REPRESENTATION('',(#116866),#116870); -#116866 = LINE('',#116867,#116868); -#116867 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#116868 = VECTOR('',#116869,1.); -#116869 = DIRECTION('',(-1.194699204908E-017,1.)); -#116870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116871 = ORIENTED_EDGE('',*,*,#116191,.F.); -#116872 = ORIENTED_EDGE('',*,*,#116294,.F.); -#116873 = ORIENTED_EDGE('',*,*,#116402,.F.); -#116874 = ORIENTED_EDGE('',*,*,#116621,.F.); -#116875 = ORIENTED_EDGE('',*,*,#116717,.T.); -#116876 = ORIENTED_EDGE('',*,*,#91021,.F.); -#116877 = ADVANCED_FACE('',(#116878),#116025,.T.); -#116878 = FACE_BOUND('',#116879,.T.); -#116879 = EDGE_LOOP('',(#116880,#116881,#116882,#116883)); -#116880 = ORIENTED_EDGE('',*,*,#116769,.T.); -#116881 = ORIENTED_EDGE('',*,*,#116111,.T.); -#116882 = ORIENTED_EDGE('',*,*,#116851,.T.); -#116883 = ORIENTED_EDGE('',*,*,#116002,.T.); -#116884 = ADVANCED_FACE('',(#116885),#116899,.F.); -#116885 = FACE_BOUND('',#116886,.T.); -#116886 = EDGE_LOOP('',(#116887,#116922,#116945,#116972)); -#116887 = ORIENTED_EDGE('',*,*,#116888,.F.); -#116888 = EDGE_CURVE('',#116889,#116891,#116893,.T.); -#116889 = VERTEX_POINT('',#116890); -#116890 = CARTESIAN_POINT('',(-1.,6.15,-0.208196358798)); -#116891 = VERTEX_POINT('',#116892); -#116892 = CARTESIAN_POINT('',(-1.,6.35,-0.208196358798)); -#116893 = SURFACE_CURVE('',#116894,(#116898,#116910),.PCURVE_S1.); -#116894 = LINE('',#116895,#116896); -#116895 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#116896 = VECTOR('',#116897,1.); -#116897 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116898 = PCURVE('',#116899,#116904); -#116899 = PLANE('',#116900); -#116900 = AXIS2_PLACEMENT_3D('',#116901,#116902,#116903); -#116901 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#116902 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#116903 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116904 = DEFINITIONAL_REPRESENTATION('',(#116905),#116909); -#116905 = LINE('',#116906,#116907); -#116906 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#116907 = VECTOR('',#116908,1.); -#116908 = DIRECTION('',(4.440892098501E-016,1.)); -#116909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119097 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#119098 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#119099 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#119100 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#119101 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#119102 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#119103 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#119104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119105 = ADVANCED_FACE('',(#119106),#93459,.T.); +#119106 = FACE_BOUND('',#119107,.T.); +#119107 = EDGE_LOOP('',(#119108,#119129,#119130,#119151)); +#119108 = ORIENTED_EDGE('',*,*,#119109,.F.); +#119109 = EDGE_CURVE('',#119014,#93416,#119110,.T.); +#119110 = SURFACE_CURVE('',#119111,(#119115,#119122),.PCURVE_S1.); +#119111 = LINE('',#119112,#119113); +#119112 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.65)); +#119113 = VECTOR('',#119114,1.); +#119114 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#119115 = PCURVE('',#93459,#119116); +#119116 = DEFINITIONAL_REPRESENTATION('',(#119117),#119121); +#119117 = LINE('',#119118,#119119); +#119118 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119119 = VECTOR('',#119120,1.); +#119120 = DIRECTION('',(-1.,-4.804757279354E-063)); +#119121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119122 = PCURVE('',#93431,#119123); +#119123 = DEFINITIONAL_REPRESENTATION('',(#119124),#119128); +#119124 = LINE('',#119125,#119126); +#119125 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119126 = VECTOR('',#119127,1.); +#119127 = DIRECTION('',(-3.563627120235E-016,1.)); +#119128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119129 = ORIENTED_EDGE('',*,*,#119036,.T.); +#119130 = ORIENTED_EDGE('',*,*,#119131,.T.); +#119131 = EDGE_CURVE('',#119037,#93444,#119132,.T.); +#119132 = SURFACE_CURVE('',#119133,(#119137,#119144),.PCURVE_S1.); +#119133 = LINE('',#119134,#119135); +#119134 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.65)); +#119135 = VECTOR('',#119136,1.); +#119136 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#119137 = PCURVE('',#93459,#119138); +#119138 = DEFINITIONAL_REPRESENTATION('',(#119139),#119143); +#119139 = LINE('',#119140,#119141); +#119140 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#119141 = VECTOR('',#119142,1.); +#119142 = DIRECTION('',(-1.,-4.804757279354E-063)); +#119143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119144 = PCURVE('',#93487,#119145); +#119145 = DEFINITIONAL_REPRESENTATION('',(#119146),#119150); +#119146 = LINE('',#119147,#119148); +#119147 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119148 = VECTOR('',#119149,1.); +#119149 = DIRECTION('',(3.563627120235E-016,1.)); +#119150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119151 = ORIENTED_EDGE('',*,*,#93443,.F.); +#119152 = ADVANCED_FACE('',(#119153),#93487,.T.); +#119153 = FACE_BOUND('',#119154,.T.); +#119154 = EDGE_LOOP('',(#119155,#119156,#119157,#119158,#119159,#119160, + #119181,#119182,#119183,#119184,#119185,#119206)); +#119155 = ORIENTED_EDGE('',*,*,#119131,.F.); +#119156 = ORIENTED_EDGE('',*,*,#119081,.T.); +#119157 = ORIENTED_EDGE('',*,*,#118816,.T.); +#119158 = ORIENTED_EDGE('',*,*,#118714,.T.); +#119159 = ORIENTED_EDGE('',*,*,#118533,.T.); +#119160 = ORIENTED_EDGE('',*,*,#119161,.F.); +#119161 = EDGE_CURVE('',#118397,#118504,#119162,.T.); +#119162 = SURFACE_CURVE('',#119163,(#119167,#119174),.PCURVE_S1.); +#119163 = LINE('',#119164,#119165); +#119164 = CARTESIAN_POINT('',(-1.,5.85,1.159810404338E-002)); +#119165 = VECTOR('',#119166,1.); +#119166 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#119167 = PCURVE('',#93487,#119168); +#119168 = DEFINITIONAL_REPRESENTATION('',(#119169),#119173); +#119169 = LINE('',#119170,#119171); +#119170 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#119171 = VECTOR('',#119172,1.); +#119172 = DIRECTION('',(-1.,2.101748079665E-016)); +#119173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119174 = PCURVE('',#118417,#119175); +#119175 = DEFINITIONAL_REPRESENTATION('',(#119176),#119180); +#119176 = LINE('',#119177,#119178); +#119177 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#119178 = VECTOR('',#119179,1.); +#119179 = DIRECTION('',(1.194699204908E-017,-1.)); +#119180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119181 = ORIENTED_EDGE('',*,*,#118479,.F.); +#119182 = ORIENTED_EDGE('',*,*,#118607,.F.); +#119183 = ORIENTED_EDGE('',*,*,#118869,.F.); +#119184 = ORIENTED_EDGE('',*,*,#118984,.F.); +#119185 = ORIENTED_EDGE('',*,*,#119186,.T.); +#119186 = EDGE_CURVE('',#118940,#93472,#119187,.T.); +#119187 = SURFACE_CURVE('',#119188,(#119192,#119199),.PCURVE_S1.); +#119188 = LINE('',#119189,#119190); +#119189 = CARTESIAN_POINT('',(-0.527847992439,5.85,0.75)); +#119190 = VECTOR('',#119191,1.); +#119191 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#119192 = PCURVE('',#93487,#119193); +#119193 = DEFINITIONAL_REPRESENTATION('',(#119194),#119198); +#119194 = LINE('',#119195,#119196); +#119195 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#119196 = VECTOR('',#119197,1.); +#119197 = DIRECTION('',(3.563627120235E-016,1.)); +#119198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119199 = PCURVE('',#93513,#119200); +#119200 = DEFINITIONAL_REPRESENTATION('',(#119201),#119205); +#119201 = LINE('',#119202,#119203); +#119202 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#119203 = VECTOR('',#119204,1.); +#119204 = DIRECTION('',(1.,-4.804757279354E-063)); +#119205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119206 = ORIENTED_EDGE('',*,*,#93471,.F.); +#119207 = ADVANCED_FACE('',(#119208),#93513,.T.); +#119208 = FACE_BOUND('',#119209,.T.); +#119209 = EDGE_LOOP('',(#119210,#119211,#119212,#119233)); +#119210 = ORIENTED_EDGE('',*,*,#119186,.F.); +#119211 = ORIENTED_EDGE('',*,*,#118939,.T.); +#119212 = ORIENTED_EDGE('',*,*,#119213,.T.); +#119213 = EDGE_CURVE('',#118917,#93414,#119214,.T.); +#119214 = SURFACE_CURVE('',#119215,(#119219,#119226),.PCURVE_S1.); +#119215 = LINE('',#119216,#119217); +#119216 = CARTESIAN_POINT('',(-0.527847992439,5.65,0.75)); +#119217 = VECTOR('',#119218,1.); +#119218 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#119219 = PCURVE('',#93513,#119220); +#119220 = DEFINITIONAL_REPRESENTATION('',(#119221),#119225); +#119221 = LINE('',#119222,#119223); +#119222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119223 = VECTOR('',#119224,1.); +#119224 = DIRECTION('',(1.,-4.804757279354E-063)); +#119225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119226 = PCURVE('',#93431,#119227); +#119227 = DEFINITIONAL_REPRESENTATION('',(#119228),#119232); +#119228 = LINE('',#119229,#119230); +#119229 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#119230 = VECTOR('',#119231,1.); +#119231 = DIRECTION('',(-3.563627120235E-016,1.)); +#119232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119233 = ORIENTED_EDGE('',*,*,#93499,.F.); +#119234 = ADVANCED_FACE('',(#119235),#93431,.T.); +#119235 = FACE_BOUND('',#119236,.T.); +#119236 = EDGE_LOOP('',(#119237,#119238,#119239,#119240,#119241,#119242, + #119263,#119264,#119265,#119266,#119267,#119268)); +#119237 = ORIENTED_EDGE('',*,*,#119213,.F.); +#119238 = ORIENTED_EDGE('',*,*,#118916,.T.); +#119239 = ORIENTED_EDGE('',*,*,#118891,.T.); +#119240 = ORIENTED_EDGE('',*,*,#118657,.T.); +#119241 = ORIENTED_EDGE('',*,*,#118429,.T.); +#119242 = ORIENTED_EDGE('',*,*,#119243,.F.); +#119243 = EDGE_CURVE('',#118506,#118395,#119244,.T.); +#119244 = SURFACE_CURVE('',#119245,(#119249,#119256),.PCURVE_S1.); +#119245 = LINE('',#119246,#119247); +#119246 = CARTESIAN_POINT('',(-1.,5.65,1.159810404338E-002)); +#119247 = VECTOR('',#119248,1.); +#119248 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#119249 = PCURVE('',#93431,#119250); +#119250 = DEFINITIONAL_REPRESENTATION('',(#119251),#119255); +#119251 = LINE('',#119252,#119253); +#119252 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#119253 = VECTOR('',#119254,1.); +#119254 = DIRECTION('',(-1.,-2.101748079665E-016)); +#119255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119256 = PCURVE('',#118417,#119257); +#119257 = DEFINITIONAL_REPRESENTATION('',(#119258),#119262); +#119258 = LINE('',#119259,#119260); +#119259 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#119260 = VECTOR('',#119261,1.); +#119261 = DIRECTION('',(-1.194699204908E-017,1.)); +#119262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#116910 = PCURVE('',#116911,#116916); -#116911 = PLANE('',#116912); -#116912 = AXIS2_PLACEMENT_3D('',#116913,#116914,#116915); -#116913 = CARTESIAN_POINT('',(-1.,6.25,-0.258196742327)); -#116914 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#116915 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116916 = DEFINITIONAL_REPRESENTATION('',(#116917),#116921); -#116917 = LINE('',#116918,#116919); -#116918 = CARTESIAN_POINT('',(-3.75,5.000038352949E-002)); -#116919 = VECTOR('',#116920,1.); -#116920 = DIRECTION('',(-1.,0.E+000)); -#116921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116922 = ORIENTED_EDGE('',*,*,#116923,.F.); -#116923 = EDGE_CURVE('',#116924,#116889,#116926,.T.); -#116924 = VERTEX_POINT('',#116925); -#116925 = CARTESIAN_POINT('',(-0.740726081328,6.15,-0.208196358798)); -#116926 = SURFACE_CURVE('',#116927,(#116931,#116938),.PCURVE_S1.); -#116927 = LINE('',#116928,#116929); -#116928 = CARTESIAN_POINT('',(-0.740726081328,6.15,-0.208196358798)); -#116929 = VECTOR('',#116930,1.); -#116930 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116931 = PCURVE('',#116899,#116932); -#116932 = DEFINITIONAL_REPRESENTATION('',(#116933),#116937); -#116933 = LINE('',#116934,#116935); -#116934 = CARTESIAN_POINT('',(-1.7763568394E-015,-3.85)); -#116935 = VECTOR('',#116936,1.); -#116936 = DIRECTION('',(1.,0.E+000)); -#116937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116938 = PCURVE('',#90925,#116939); -#116939 = DEFINITIONAL_REPRESENTATION('',(#116940),#116944); -#116940 = LINE('',#116941,#116942); -#116941 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#116942 = VECTOR('',#116943,1.); -#116943 = DIRECTION('',(0.E+000,-1.)); -#116944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116945 = ORIENTED_EDGE('',*,*,#116946,.F.); -#116946 = EDGE_CURVE('',#116947,#116924,#116949,.T.); -#116947 = VERTEX_POINT('',#116948); -#116948 = CARTESIAN_POINT('',(-0.740726081328,6.35,-0.208196358798)); -#116949 = SURFACE_CURVE('',#116950,(#116954,#116961),.PCURVE_S1.); -#116950 = LINE('',#116951,#116952); -#116951 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#116952 = VECTOR('',#116953,1.); -#116953 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#116954 = PCURVE('',#116899,#116955); -#116955 = DEFINITIONAL_REPRESENTATION('',(#116956),#116960); -#116956 = LINE('',#116957,#116958); -#116957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#116958 = VECTOR('',#116959,1.); -#116959 = DIRECTION('',(-4.440892098501E-016,-1.)); -#116960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116961 = PCURVE('',#116962,#116967); -#116962 = CYLINDRICAL_SURFACE('',#116963,0.208574704164); -#116963 = AXIS2_PLACEMENT_3D('',#116964,#116965,#116966); -#116964 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#116965 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#116966 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#116967 = DEFINITIONAL_REPRESENTATION('',(#116968),#116971); -#116968 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#116969,#116970), +#119263 = ORIENTED_EDGE('',*,*,#118583,.F.); +#119264 = ORIENTED_EDGE('',*,*,#118686,.F.); +#119265 = ORIENTED_EDGE('',*,*,#118794,.F.); +#119266 = ORIENTED_EDGE('',*,*,#119013,.F.); +#119267 = ORIENTED_EDGE('',*,*,#119109,.T.); +#119268 = ORIENTED_EDGE('',*,*,#93413,.F.); +#119269 = ADVANCED_FACE('',(#119270),#118417,.T.); +#119270 = FACE_BOUND('',#119271,.T.); +#119271 = EDGE_LOOP('',(#119272,#119273,#119274,#119275)); +#119272 = ORIENTED_EDGE('',*,*,#119161,.T.); +#119273 = ORIENTED_EDGE('',*,*,#118503,.T.); +#119274 = ORIENTED_EDGE('',*,*,#119243,.T.); +#119275 = ORIENTED_EDGE('',*,*,#118394,.T.); +#119276 = ADVANCED_FACE('',(#119277),#119291,.F.); +#119277 = FACE_BOUND('',#119278,.T.); +#119278 = EDGE_LOOP('',(#119279,#119314,#119337,#119364)); +#119279 = ORIENTED_EDGE('',*,*,#119280,.F.); +#119280 = EDGE_CURVE('',#119281,#119283,#119285,.T.); +#119281 = VERTEX_POINT('',#119282); +#119282 = CARTESIAN_POINT('',(-1.,6.15,-0.208196358798)); +#119283 = VERTEX_POINT('',#119284); +#119284 = CARTESIAN_POINT('',(-1.,6.35,-0.208196358798)); +#119285 = SURFACE_CURVE('',#119286,(#119290,#119302),.PCURVE_S1.); +#119286 = LINE('',#119287,#119288); +#119287 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#119288 = VECTOR('',#119289,1.); +#119289 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119290 = PCURVE('',#119291,#119296); +#119291 = PLANE('',#119292); +#119292 = AXIS2_PLACEMENT_3D('',#119293,#119294,#119295); +#119293 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#119294 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#119295 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#119296 = DEFINITIONAL_REPRESENTATION('',(#119297),#119301); +#119297 = LINE('',#119298,#119299); +#119298 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#119299 = VECTOR('',#119300,1.); +#119300 = DIRECTION('',(4.440892098501E-016,1.)); +#119301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119302 = PCURVE('',#119303,#119308); +#119303 = PLANE('',#119304); +#119304 = AXIS2_PLACEMENT_3D('',#119305,#119306,#119307); +#119305 = CARTESIAN_POINT('',(-1.,6.25,-0.258196742327)); +#119306 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#119307 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119308 = DEFINITIONAL_REPRESENTATION('',(#119309),#119313); +#119309 = LINE('',#119310,#119311); +#119310 = CARTESIAN_POINT('',(-3.75,5.000038352949E-002)); +#119311 = VECTOR('',#119312,1.); +#119312 = DIRECTION('',(-1.,0.E+000)); +#119313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119314 = ORIENTED_EDGE('',*,*,#119315,.F.); +#119315 = EDGE_CURVE('',#119316,#119281,#119318,.T.); +#119316 = VERTEX_POINT('',#119317); +#119317 = CARTESIAN_POINT('',(-0.740726081328,6.15,-0.208196358798)); +#119318 = SURFACE_CURVE('',#119319,(#119323,#119330),.PCURVE_S1.); +#119319 = LINE('',#119320,#119321); +#119320 = CARTESIAN_POINT('',(-0.740726081328,6.15,-0.208196358798)); +#119321 = VECTOR('',#119322,1.); +#119322 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#119323 = PCURVE('',#119291,#119324); +#119324 = DEFINITIONAL_REPRESENTATION('',(#119325),#119329); +#119325 = LINE('',#119326,#119327); +#119326 = CARTESIAN_POINT('',(-1.7763568394E-015,-3.85)); +#119327 = VECTOR('',#119328,1.); +#119328 = DIRECTION('',(1.,0.E+000)); +#119329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119330 = PCURVE('',#93317,#119331); +#119331 = DEFINITIONAL_REPRESENTATION('',(#119332),#119336); +#119332 = LINE('',#119333,#119334); +#119333 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#119334 = VECTOR('',#119335,1.); +#119335 = DIRECTION('',(0.E+000,-1.)); +#119336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119337 = ORIENTED_EDGE('',*,*,#119338,.F.); +#119338 = EDGE_CURVE('',#119339,#119316,#119341,.T.); +#119339 = VERTEX_POINT('',#119340); +#119340 = CARTESIAN_POINT('',(-0.740726081328,6.35,-0.208196358798)); +#119341 = SURFACE_CURVE('',#119342,(#119346,#119353),.PCURVE_S1.); +#119342 = LINE('',#119343,#119344); +#119343 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#119344 = VECTOR('',#119345,1.); +#119345 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119346 = PCURVE('',#119291,#119347); +#119347 = DEFINITIONAL_REPRESENTATION('',(#119348),#119352); +#119348 = LINE('',#119349,#119350); +#119349 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119350 = VECTOR('',#119351,1.); +#119351 = DIRECTION('',(-4.440892098501E-016,-1.)); +#119352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119353 = PCURVE('',#119354,#119359); +#119354 = CYLINDRICAL_SURFACE('',#119355,0.208574704164); +#119355 = AXIS2_PLACEMENT_3D('',#119356,#119357,#119358); +#119356 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#119357 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119358 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119359 = DEFINITIONAL_REPRESENTATION('',(#119360),#119363); +#119360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119361,#119362), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#116969 = CARTESIAN_POINT('',(4.772630242227,-3.65)); -#116970 = CARTESIAN_POINT('',(4.772630242227,-3.85)); -#116971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116972 = ORIENTED_EDGE('',*,*,#116973,.T.); -#116973 = EDGE_CURVE('',#116947,#116891,#116974,.T.); -#116974 = SURFACE_CURVE('',#116975,(#116979,#116986),.PCURVE_S1.); -#116975 = LINE('',#116976,#116977); -#116976 = CARTESIAN_POINT('',(-0.740726081328,6.35,-0.208196358798)); -#116977 = VECTOR('',#116978,1.); -#116978 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#116979 = PCURVE('',#116899,#116980); -#116980 = DEFINITIONAL_REPRESENTATION('',(#116981),#116985); -#116981 = LINE('',#116982,#116983); -#116982 = CARTESIAN_POINT('',(-1.554312234475E-015,-3.65)); -#116983 = VECTOR('',#116984,1.); -#116984 = DIRECTION('',(1.,0.E+000)); -#116985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116986 = PCURVE('',#90981,#116987); -#116987 = DEFINITIONAL_REPRESENTATION('',(#116988),#116992); -#116988 = LINE('',#116989,#116990); -#116989 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#116990 = VECTOR('',#116991,1.); -#116991 = DIRECTION('',(0.E+000,-1.)); -#116992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#116993 = ADVANCED_FACE('',(#116994),#117008,.F.); -#116994 = FACE_BOUND('',#116995,.T.); -#116995 = EDGE_LOOP('',(#116996,#117026,#117049,#117076)); -#116996 = ORIENTED_EDGE('',*,*,#116997,.F.); -#116997 = EDGE_CURVE('',#116998,#117000,#117002,.T.); -#116998 = VERTEX_POINT('',#116999); -#116999 = CARTESIAN_POINT('',(-1.,6.35,-0.308197125857)); -#117000 = VERTEX_POINT('',#117001); -#117001 = CARTESIAN_POINT('',(-1.,6.15,-0.308197125857)); -#117002 = SURFACE_CURVE('',#117003,(#117007,#117019),.PCURVE_S1.); -#117003 = LINE('',#117004,#117005); -#117004 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#117005 = VECTOR('',#117006,1.); -#117006 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117007 = PCURVE('',#117008,#117013); -#117008 = PLANE('',#117009); -#117009 = AXIS2_PLACEMENT_3D('',#117010,#117011,#117012); -#117010 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#117011 = DIRECTION('',(0.E+000,0.E+000,1.)); -#117012 = DIRECTION('',(1.,0.E+000,0.E+000)); -#117013 = DEFINITIONAL_REPRESENTATION('',(#117014),#117018); -#117014 = LINE('',#117015,#117016); -#117015 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#117016 = VECTOR('',#117017,1.); -#117017 = DIRECTION('',(4.440892098501E-016,-1.)); -#117018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117019 = PCURVE('',#116911,#117020); -#117020 = DEFINITIONAL_REPRESENTATION('',(#117021),#117025); -#117021 = LINE('',#117022,#117023); -#117022 = CARTESIAN_POINT('',(-3.75,-5.000038352949E-002)); -#117023 = VECTOR('',#117024,1.); -#117024 = DIRECTION('',(1.,0.E+000)); -#117025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117026 = ORIENTED_EDGE('',*,*,#117027,.F.); -#117027 = EDGE_CURVE('',#117028,#116998,#117030,.T.); -#117028 = VERTEX_POINT('',#117029); -#117029 = CARTESIAN_POINT('',(-0.74341632541,6.35,-0.308197125857)); -#117030 = SURFACE_CURVE('',#117031,(#117035,#117042),.PCURVE_S1.); -#117031 = LINE('',#117032,#117033); -#117032 = CARTESIAN_POINT('',(-0.74341632541,6.35,-0.308197125857)); -#117033 = VECTOR('',#117034,1.); -#117034 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117035 = PCURVE('',#117008,#117036); -#117036 = DEFINITIONAL_REPRESENTATION('',(#117037),#117041); -#117037 = LINE('',#117038,#117039); -#117038 = CARTESIAN_POINT('',(1.554312234475E-015,-3.65)); -#117039 = VECTOR('',#117040,1.); -#117040 = DIRECTION('',(-1.,0.E+000)); -#117041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117042 = PCURVE('',#90981,#117043); -#117043 = DEFINITIONAL_REPRESENTATION('',(#117044),#117048); -#117044 = LINE('',#117045,#117046); -#117045 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#117046 = VECTOR('',#117047,1.); -#117047 = DIRECTION('',(0.E+000,-1.)); -#117048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117049 = ORIENTED_EDGE('',*,*,#117050,.F.); -#117050 = EDGE_CURVE('',#117051,#117028,#117053,.T.); -#117051 = VERTEX_POINT('',#117052); -#117052 = CARTESIAN_POINT('',(-0.74341632541,6.15,-0.308197125857)); -#117053 = SURFACE_CURVE('',#117054,(#117058,#117065),.PCURVE_S1.); -#117054 = LINE('',#117055,#117056); -#117055 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#117056 = VECTOR('',#117057,1.); -#117057 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117058 = PCURVE('',#117008,#117059); -#117059 = DEFINITIONAL_REPRESENTATION('',(#117060),#117064); -#117060 = LINE('',#117061,#117062); -#117061 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117062 = VECTOR('',#117063,1.); -#117063 = DIRECTION('',(-4.440892098501E-016,1.)); -#117064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117065 = PCURVE('',#117066,#117071); -#117066 = CYLINDRICAL_SURFACE('',#117067,0.308574064194); -#117067 = AXIS2_PLACEMENT_3D('',#117068,#117069,#117070); -#117068 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#117069 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117070 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117071 = DEFINITIONAL_REPRESENTATION('',(#117072),#117075); -#117072 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117073,#117074), +#119361 = CARTESIAN_POINT('',(4.772630242227,-3.65)); +#119362 = CARTESIAN_POINT('',(4.772630242227,-3.85)); +#119363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119364 = ORIENTED_EDGE('',*,*,#119365,.T.); +#119365 = EDGE_CURVE('',#119339,#119283,#119366,.T.); +#119366 = SURFACE_CURVE('',#119367,(#119371,#119378),.PCURVE_S1.); +#119367 = LINE('',#119368,#119369); +#119368 = CARTESIAN_POINT('',(-0.740726081328,6.35,-0.208196358798)); +#119369 = VECTOR('',#119370,1.); +#119370 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#119371 = PCURVE('',#119291,#119372); +#119372 = DEFINITIONAL_REPRESENTATION('',(#119373),#119377); +#119373 = LINE('',#119374,#119375); +#119374 = CARTESIAN_POINT('',(-1.554312234475E-015,-3.65)); +#119375 = VECTOR('',#119376,1.); +#119376 = DIRECTION('',(1.,0.E+000)); +#119377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119378 = PCURVE('',#93373,#119379); +#119379 = DEFINITIONAL_REPRESENTATION('',(#119380),#119384); +#119380 = LINE('',#119381,#119382); +#119381 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#119382 = VECTOR('',#119383,1.); +#119383 = DIRECTION('',(0.E+000,-1.)); +#119384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119385 = ADVANCED_FACE('',(#119386),#119400,.F.); +#119386 = FACE_BOUND('',#119387,.T.); +#119387 = EDGE_LOOP('',(#119388,#119418,#119441,#119468)); +#119388 = ORIENTED_EDGE('',*,*,#119389,.F.); +#119389 = EDGE_CURVE('',#119390,#119392,#119394,.T.); +#119390 = VERTEX_POINT('',#119391); +#119391 = CARTESIAN_POINT('',(-1.,6.35,-0.308197125857)); +#119392 = VERTEX_POINT('',#119393); +#119393 = CARTESIAN_POINT('',(-1.,6.15,-0.308197125857)); +#119394 = SURFACE_CURVE('',#119395,(#119399,#119411),.PCURVE_S1.); +#119395 = LINE('',#119396,#119397); +#119396 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#119397 = VECTOR('',#119398,1.); +#119398 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119399 = PCURVE('',#119400,#119405); +#119400 = PLANE('',#119401); +#119401 = AXIS2_PLACEMENT_3D('',#119402,#119403,#119404); +#119402 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#119403 = DIRECTION('',(0.E+000,0.E+000,1.)); +#119404 = DIRECTION('',(1.,0.E+000,0.E+000)); +#119405 = DEFINITIONAL_REPRESENTATION('',(#119406),#119410); +#119406 = LINE('',#119407,#119408); +#119407 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#119408 = VECTOR('',#119409,1.); +#119409 = DIRECTION('',(4.440892098501E-016,-1.)); +#119410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119411 = PCURVE('',#119303,#119412); +#119412 = DEFINITIONAL_REPRESENTATION('',(#119413),#119417); +#119413 = LINE('',#119414,#119415); +#119414 = CARTESIAN_POINT('',(-3.75,-5.000038352949E-002)); +#119415 = VECTOR('',#119416,1.); +#119416 = DIRECTION('',(1.,0.E+000)); +#119417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119418 = ORIENTED_EDGE('',*,*,#119419,.F.); +#119419 = EDGE_CURVE('',#119420,#119390,#119422,.T.); +#119420 = VERTEX_POINT('',#119421); +#119421 = CARTESIAN_POINT('',(-0.74341632541,6.35,-0.308197125857)); +#119422 = SURFACE_CURVE('',#119423,(#119427,#119434),.PCURVE_S1.); +#119423 = LINE('',#119424,#119425); +#119424 = CARTESIAN_POINT('',(-0.74341632541,6.35,-0.308197125857)); +#119425 = VECTOR('',#119426,1.); +#119426 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#119427 = PCURVE('',#119400,#119428); +#119428 = DEFINITIONAL_REPRESENTATION('',(#119429),#119433); +#119429 = LINE('',#119430,#119431); +#119430 = CARTESIAN_POINT('',(1.554312234475E-015,-3.65)); +#119431 = VECTOR('',#119432,1.); +#119432 = DIRECTION('',(-1.,0.E+000)); +#119433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119434 = PCURVE('',#93373,#119435); +#119435 = DEFINITIONAL_REPRESENTATION('',(#119436),#119440); +#119436 = LINE('',#119437,#119438); +#119437 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#119438 = VECTOR('',#119439,1.); +#119439 = DIRECTION('',(0.E+000,-1.)); +#119440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119441 = ORIENTED_EDGE('',*,*,#119442,.F.); +#119442 = EDGE_CURVE('',#119443,#119420,#119445,.T.); +#119443 = VERTEX_POINT('',#119444); +#119444 = CARTESIAN_POINT('',(-0.74341632541,6.15,-0.308197125857)); +#119445 = SURFACE_CURVE('',#119446,(#119450,#119457),.PCURVE_S1.); +#119446 = LINE('',#119447,#119448); +#119447 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#119448 = VECTOR('',#119449,1.); +#119449 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119450 = PCURVE('',#119400,#119451); +#119451 = DEFINITIONAL_REPRESENTATION('',(#119452),#119456); +#119452 = LINE('',#119453,#119454); +#119453 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119454 = VECTOR('',#119455,1.); +#119455 = DIRECTION('',(-4.440892098501E-016,1.)); +#119456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119457 = PCURVE('',#119458,#119463); +#119458 = CYLINDRICAL_SURFACE('',#119459,0.308574064194); +#119459 = AXIS2_PLACEMENT_3D('',#119460,#119461,#119462); +#119460 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#119461 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119462 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119463 = DEFINITIONAL_REPRESENTATION('',(#119464),#119467); +#119464 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119465,#119466), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#117073 = CARTESIAN_POINT('',(4.761821717947,-3.85)); -#117074 = CARTESIAN_POINT('',(4.761821717947,-3.65)); -#117075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117076 = ORIENTED_EDGE('',*,*,#117077,.T.); -#117077 = EDGE_CURVE('',#117051,#117000,#117078,.T.); -#117078 = SURFACE_CURVE('',#117079,(#117083,#117090),.PCURVE_S1.); -#117079 = LINE('',#117080,#117081); -#117080 = CARTESIAN_POINT('',(-0.74341632541,6.15,-0.308197125857)); -#117081 = VECTOR('',#117082,1.); -#117082 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117083 = PCURVE('',#117008,#117084); -#117084 = DEFINITIONAL_REPRESENTATION('',(#117085),#117089); -#117085 = LINE('',#117086,#117087); -#117086 = CARTESIAN_POINT('',(1.7763568394E-015,-3.85)); -#117087 = VECTOR('',#117088,1.); -#117088 = DIRECTION('',(-1.,0.E+000)); -#117089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117090 = PCURVE('',#90925,#117091); -#117091 = DEFINITIONAL_REPRESENTATION('',(#117092),#117096); -#117092 = LINE('',#117093,#117094); -#117093 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#117094 = VECTOR('',#117095,1.); -#117095 = DIRECTION('',(0.E+000,-1.)); -#117096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117097 = ADVANCED_FACE('',(#117098),#116962,.F.); -#117098 = FACE_BOUND('',#117099,.F.); -#117099 = EDGE_LOOP('',(#117100,#117123,#117150,#117175)); -#117100 = ORIENTED_EDGE('',*,*,#117101,.F.); -#117101 = EDGE_CURVE('',#117102,#116947,#117104,.T.); -#117102 = VERTEX_POINT('',#117103); -#117103 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.E+000)); -#117104 = SURFACE_CURVE('',#117105,(#117110,#117116),.PCURVE_S1.); -#117105 = CIRCLE('',#117106,0.208574704164); -#117106 = AXIS2_PLACEMENT_3D('',#117107,#117108,#117109); -#117107 = CARTESIAN_POINT('',(-0.728168876214,6.35,2.640924866458E-017) - ); -#117108 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117109 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117110 = PCURVE('',#116962,#117111); -#117111 = DEFINITIONAL_REPRESENTATION('',(#117112),#117115); -#117112 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117113,#117114), +#119465 = CARTESIAN_POINT('',(4.761821717947,-3.85)); +#119466 = CARTESIAN_POINT('',(4.761821717947,-3.65)); +#119467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119468 = ORIENTED_EDGE('',*,*,#119469,.T.); +#119469 = EDGE_CURVE('',#119443,#119392,#119470,.T.); +#119470 = SURFACE_CURVE('',#119471,(#119475,#119482),.PCURVE_S1.); +#119471 = LINE('',#119472,#119473); +#119472 = CARTESIAN_POINT('',(-0.74341632541,6.15,-0.308197125857)); +#119473 = VECTOR('',#119474,1.); +#119474 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#119475 = PCURVE('',#119400,#119476); +#119476 = DEFINITIONAL_REPRESENTATION('',(#119477),#119481); +#119477 = LINE('',#119478,#119479); +#119478 = CARTESIAN_POINT('',(1.7763568394E-015,-3.85)); +#119479 = VECTOR('',#119480,1.); +#119480 = DIRECTION('',(-1.,0.E+000)); +#119481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119482 = PCURVE('',#93317,#119483); +#119483 = DEFINITIONAL_REPRESENTATION('',(#119484),#119488); +#119484 = LINE('',#119485,#119486); +#119485 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#119486 = VECTOR('',#119487,1.); +#119487 = DIRECTION('',(0.E+000,-1.)); +#119488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119489 = ADVANCED_FACE('',(#119490),#119354,.F.); +#119490 = FACE_BOUND('',#119491,.F.); +#119491 = EDGE_LOOP('',(#119492,#119515,#119542,#119567)); +#119492 = ORIENTED_EDGE('',*,*,#119493,.F.); +#119493 = EDGE_CURVE('',#119494,#119339,#119496,.T.); +#119494 = VERTEX_POINT('',#119495); +#119495 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.E+000)); +#119496 = SURFACE_CURVE('',#119497,(#119502,#119508),.PCURVE_S1.); +#119497 = CIRCLE('',#119498,0.208574704164); +#119498 = AXIS2_PLACEMENT_3D('',#119499,#119500,#119501); +#119499 = CARTESIAN_POINT('',(-0.728168876214,6.35,2.640924866458E-017) + ); +#119500 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119501 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119502 = PCURVE('',#119354,#119503); +#119503 = DEFINITIONAL_REPRESENTATION('',(#119504),#119507); +#119504 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119505,#119506), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#117113 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#117114 = CARTESIAN_POINT('',(4.772630242227,-3.65)); -#117115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117116 = PCURVE('',#90981,#117117); -#117117 = DEFINITIONAL_REPRESENTATION('',(#117118),#117122); -#117118 = CIRCLE('',#117119,0.208574704164); -#117119 = AXIS2_PLACEMENT_2D('',#117120,#117121); -#117120 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#117121 = DIRECTION('',(0.E+000,-1.)); -#117122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117123 = ORIENTED_EDGE('',*,*,#117124,.F.); -#117124 = EDGE_CURVE('',#117125,#117102,#117127,.T.); -#117125 = VERTEX_POINT('',#117126); -#117126 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.E+000)); -#117127 = SURFACE_CURVE('',#117128,(#117132,#117138),.PCURVE_S1.); -#117128 = LINE('',#117129,#117130); -#117129 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#117130 = VECTOR('',#117131,1.); -#117131 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117132 = PCURVE('',#116962,#117133); -#117133 = DEFINITIONAL_REPRESENTATION('',(#117134),#117137); -#117134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117135,#117136), +#119505 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#119506 = CARTESIAN_POINT('',(4.772630242227,-3.65)); +#119507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119508 = PCURVE('',#93373,#119509); +#119509 = DEFINITIONAL_REPRESENTATION('',(#119510),#119514); +#119510 = CIRCLE('',#119511,0.208574704164); +#119511 = AXIS2_PLACEMENT_2D('',#119512,#119513); +#119512 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#119513 = DIRECTION('',(0.E+000,-1.)); +#119514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119515 = ORIENTED_EDGE('',*,*,#119516,.F.); +#119516 = EDGE_CURVE('',#119517,#119494,#119519,.T.); +#119517 = VERTEX_POINT('',#119518); +#119518 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.E+000)); +#119519 = SURFACE_CURVE('',#119520,(#119524,#119530),.PCURVE_S1.); +#119520 = LINE('',#119521,#119522); +#119521 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#119522 = VECTOR('',#119523,1.); +#119523 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119524 = PCURVE('',#119354,#119525); +#119525 = DEFINITIONAL_REPRESENTATION('',(#119526),#119529); +#119526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119527,#119528), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#117135 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#117136 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#117137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117138 = PCURVE('',#117139,#117144); -#117139 = PLANE('',#117140); -#117140 = AXIS2_PLACEMENT_3D('',#117141,#117142,#117143); -#117141 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#117142 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#117143 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117144 = DEFINITIONAL_REPRESENTATION('',(#117145),#117149); -#117145 = LINE('',#117146,#117147); -#117146 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#117147 = VECTOR('',#117148,1.); -#117148 = DIRECTION('',(-1.,0.E+000)); -#117149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117150 = ORIENTED_EDGE('',*,*,#117151,.T.); -#117151 = EDGE_CURVE('',#117125,#116924,#117152,.T.); -#117152 = SURFACE_CURVE('',#117153,(#117158,#117164),.PCURVE_S1.); -#117153 = CIRCLE('',#117154,0.208574704164); -#117154 = AXIS2_PLACEMENT_3D('',#117155,#117156,#117157); -#117155 = CARTESIAN_POINT('',(-0.728168876214,6.15,2.640924866458E-017) - ); -#117156 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117157 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117158 = PCURVE('',#116962,#117159); -#117159 = DEFINITIONAL_REPRESENTATION('',(#117160),#117163); -#117160 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117161,#117162), +#119527 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#119528 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#119529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119530 = PCURVE('',#119531,#119536); +#119531 = PLANE('',#119532); +#119532 = AXIS2_PLACEMENT_3D('',#119533,#119534,#119535); +#119533 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#119534 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#119535 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119536 = DEFINITIONAL_REPRESENTATION('',(#119537),#119541); +#119537 = LINE('',#119538,#119539); +#119538 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#119539 = VECTOR('',#119540,1.); +#119540 = DIRECTION('',(-1.,0.E+000)); +#119541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119542 = ORIENTED_EDGE('',*,*,#119543,.T.); +#119543 = EDGE_CURVE('',#119517,#119316,#119544,.T.); +#119544 = SURFACE_CURVE('',#119545,(#119550,#119556),.PCURVE_S1.); +#119545 = CIRCLE('',#119546,0.208574704164); +#119546 = AXIS2_PLACEMENT_3D('',#119547,#119548,#119549); +#119547 = CARTESIAN_POINT('',(-0.728168876214,6.15,2.640924866458E-017) + ); +#119548 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119549 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119550 = PCURVE('',#119354,#119551); +#119551 = DEFINITIONAL_REPRESENTATION('',(#119552),#119555); +#119552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119553,#119554), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#117161 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#117162 = CARTESIAN_POINT('',(4.772630242227,-3.85)); -#117163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119553 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#119554 = CARTESIAN_POINT('',(4.772630242227,-3.85)); +#119555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117164 = PCURVE('',#90925,#117165); -#117165 = DEFINITIONAL_REPRESENTATION('',(#117166),#117174); -#117166 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117167,#117168,#117169, - #117170,#117171,#117172,#117173),.UNSPECIFIED.,.T.,.F.) +#119556 = PCURVE('',#93317,#119557); +#119557 = DEFINITIONAL_REPRESENTATION('',(#119558),#119566); +#119558 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119559,#119560,#119561, + #119562,#119563,#119564,#119565),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#117167 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#117168 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#117169 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#117170 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#117171 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#117172 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#117173 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#117174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117175 = ORIENTED_EDGE('',*,*,#116946,.F.); -#117176 = ADVANCED_FACE('',(#117177),#117066,.T.); -#117177 = FACE_BOUND('',#117178,.T.); -#117178 = EDGE_LOOP('',(#117179,#117206,#117207,#117230)); -#117179 = ORIENTED_EDGE('',*,*,#117180,.T.); -#117180 = EDGE_CURVE('',#117181,#117051,#117183,.T.); -#117181 = VERTEX_POINT('',#117182); -#117182 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.E+000)); -#117183 = SURFACE_CURVE('',#117184,(#117189,#117195),.PCURVE_S1.); -#117184 = CIRCLE('',#117185,0.308574064194); -#117185 = AXIS2_PLACEMENT_3D('',#117186,#117187,#117188); -#117186 = CARTESIAN_POINT('',(-0.728168876214,6.15,2.640924866458E-017) - ); -#117187 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117188 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117189 = PCURVE('',#117066,#117190); -#117190 = DEFINITIONAL_REPRESENTATION('',(#117191),#117194); -#117191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117192,#117193), +#119559 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#119560 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#119561 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#119562 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#119563 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#119564 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#119565 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#119566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119567 = ORIENTED_EDGE('',*,*,#119338,.F.); +#119568 = ADVANCED_FACE('',(#119569),#119458,.T.); +#119569 = FACE_BOUND('',#119570,.T.); +#119570 = EDGE_LOOP('',(#119571,#119598,#119599,#119622)); +#119571 = ORIENTED_EDGE('',*,*,#119572,.T.); +#119572 = EDGE_CURVE('',#119573,#119443,#119575,.T.); +#119573 = VERTEX_POINT('',#119574); +#119574 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.E+000)); +#119575 = SURFACE_CURVE('',#119576,(#119581,#119587),.PCURVE_S1.); +#119576 = CIRCLE('',#119577,0.308574064194); +#119577 = AXIS2_PLACEMENT_3D('',#119578,#119579,#119580); +#119578 = CARTESIAN_POINT('',(-0.728168876214,6.15,2.640924866458E-017) + ); +#119579 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119580 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119581 = PCURVE('',#119458,#119582); +#119582 = DEFINITIONAL_REPRESENTATION('',(#119583),#119586); +#119583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119584,#119585), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#117192 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#117193 = CARTESIAN_POINT('',(4.761821717947,-3.85)); -#117194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119584 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#119585 = CARTESIAN_POINT('',(4.761821717947,-3.85)); +#119586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117195 = PCURVE('',#90925,#117196); -#117196 = DEFINITIONAL_REPRESENTATION('',(#117197),#117205); -#117197 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117198,#117199,#117200, - #117201,#117202,#117203,#117204),.UNSPECIFIED.,.T.,.F.) +#119587 = PCURVE('',#93317,#119588); +#119588 = DEFINITIONAL_REPRESENTATION('',(#119589),#119597); +#119589 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119590,#119591,#119592, + #119593,#119594,#119595,#119596),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#117198 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#117199 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#117200 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#117201 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#117202 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#117203 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#117204 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#117205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117206 = ORIENTED_EDGE('',*,*,#117050,.T.); -#117207 = ORIENTED_EDGE('',*,*,#117208,.F.); -#117208 = EDGE_CURVE('',#117209,#117028,#117211,.T.); -#117209 = VERTEX_POINT('',#117210); -#117210 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.E+000)); -#117211 = SURFACE_CURVE('',#117212,(#117217,#117223),.PCURVE_S1.); -#117212 = CIRCLE('',#117213,0.308574064194); -#117213 = AXIS2_PLACEMENT_3D('',#117214,#117215,#117216); -#117214 = CARTESIAN_POINT('',(-0.728168876214,6.35,2.640924866458E-017) - ); -#117215 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117216 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117217 = PCURVE('',#117066,#117218); -#117218 = DEFINITIONAL_REPRESENTATION('',(#117219),#117222); -#117219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117220,#117221), +#119590 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#119591 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#119592 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#119593 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#119594 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#119595 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#119596 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#119597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119598 = ORIENTED_EDGE('',*,*,#119442,.T.); +#119599 = ORIENTED_EDGE('',*,*,#119600,.F.); +#119600 = EDGE_CURVE('',#119601,#119420,#119603,.T.); +#119601 = VERTEX_POINT('',#119602); +#119602 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.E+000)); +#119603 = SURFACE_CURVE('',#119604,(#119609,#119615),.PCURVE_S1.); +#119604 = CIRCLE('',#119605,0.308574064194); +#119605 = AXIS2_PLACEMENT_3D('',#119606,#119607,#119608); +#119606 = CARTESIAN_POINT('',(-0.728168876214,6.35,2.640924866458E-017) + ); +#119607 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119608 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#119609 = PCURVE('',#119458,#119610); +#119610 = DEFINITIONAL_REPRESENTATION('',(#119611),#119614); +#119611 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119612,#119613), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#117220 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#117221 = CARTESIAN_POINT('',(4.761821717947,-3.65)); -#117222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117223 = PCURVE('',#90981,#117224); -#117224 = DEFINITIONAL_REPRESENTATION('',(#117225),#117229); -#117225 = CIRCLE('',#117226,0.308574064194); -#117226 = AXIS2_PLACEMENT_2D('',#117227,#117228); -#117227 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#117228 = DIRECTION('',(0.E+000,-1.)); -#117229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117230 = ORIENTED_EDGE('',*,*,#117231,.T.); -#117231 = EDGE_CURVE('',#117209,#117181,#117232,.T.); -#117232 = SURFACE_CURVE('',#117233,(#117237,#117243),.PCURVE_S1.); -#117233 = LINE('',#117234,#117235); -#117234 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#117235 = VECTOR('',#117236,1.); -#117236 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117237 = PCURVE('',#117066,#117238); -#117238 = DEFINITIONAL_REPRESENTATION('',(#117239),#117242); -#117239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117240,#117241), +#119612 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#119613 = CARTESIAN_POINT('',(4.761821717947,-3.65)); +#119614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119615 = PCURVE('',#93373,#119616); +#119616 = DEFINITIONAL_REPRESENTATION('',(#119617),#119621); +#119617 = CIRCLE('',#119618,0.308574064194); +#119618 = AXIS2_PLACEMENT_2D('',#119619,#119620); +#119619 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#119620 = DIRECTION('',(0.E+000,-1.)); +#119621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119622 = ORIENTED_EDGE('',*,*,#119623,.T.); +#119623 = EDGE_CURVE('',#119601,#119573,#119624,.T.); +#119624 = SURFACE_CURVE('',#119625,(#119629,#119635),.PCURVE_S1.); +#119625 = LINE('',#119626,#119627); +#119626 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#119627 = VECTOR('',#119628,1.); +#119628 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119629 = PCURVE('',#119458,#119630); +#119630 = DEFINITIONAL_REPRESENTATION('',(#119631),#119634); +#119631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119632,#119633), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#117240 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#117241 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#117242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117243 = PCURVE('',#117244,#117249); -#117244 = PLANE('',#117245); -#117245 = AXIS2_PLACEMENT_3D('',#117246,#117247,#117248); -#117246 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#117247 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#117248 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117249 = DEFINITIONAL_REPRESENTATION('',(#117250),#117254); -#117250 = LINE('',#117251,#117252); -#117251 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#117252 = VECTOR('',#117253,1.); -#117253 = DIRECTION('',(-1.,0.E+000)); -#117254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117255 = ADVANCED_FACE('',(#117256),#117244,.T.); -#117256 = FACE_BOUND('',#117257,.T.); -#117257 = EDGE_LOOP('',(#117258,#117287,#117308,#117309)); -#117258 = ORIENTED_EDGE('',*,*,#117259,.T.); -#117259 = EDGE_CURVE('',#117260,#117262,#117264,.T.); -#117260 = VERTEX_POINT('',#117261); -#117261 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.530776333563)); -#117262 = VERTEX_POINT('',#117263); -#117263 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.530776333563)); -#117264 = SURFACE_CURVE('',#117265,(#117269,#117276),.PCURVE_S1.); -#117265 = LINE('',#117266,#117267); -#117266 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#117267 = VECTOR('',#117268,1.); -#117268 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117269 = PCURVE('',#117244,#117270); -#117270 = DEFINITIONAL_REPRESENTATION('',(#117271),#117275); -#117271 = LINE('',#117272,#117273); -#117272 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117273 = VECTOR('',#117274,1.); -#117274 = DIRECTION('',(-1.,0.E+000)); -#117275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117276 = PCURVE('',#117277,#117282); -#117277 = CYLINDRICAL_SURFACE('',#117278,0.119270391569); -#117278 = AXIS2_PLACEMENT_3D('',#117279,#117280,#117281); -#117279 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#117280 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117281 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117282 = DEFINITIONAL_REPRESENTATION('',(#117283),#117286); -#117283 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117284,#117285), +#119632 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#119633 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#119634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119635 = PCURVE('',#119636,#119641); +#119636 = PLANE('',#119637); +#119637 = AXIS2_PLACEMENT_3D('',#119638,#119639,#119640); +#119638 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#119639 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#119640 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119641 = DEFINITIONAL_REPRESENTATION('',(#119642),#119646); +#119642 = LINE('',#119643,#119644); +#119643 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#119644 = VECTOR('',#119645,1.); +#119645 = DIRECTION('',(-1.,0.E+000)); +#119646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119647 = ADVANCED_FACE('',(#119648),#119636,.T.); +#119648 = FACE_BOUND('',#119649,.T.); +#119649 = EDGE_LOOP('',(#119650,#119679,#119700,#119701)); +#119650 = ORIENTED_EDGE('',*,*,#119651,.T.); +#119651 = EDGE_CURVE('',#119652,#119654,#119656,.T.); +#119652 = VERTEX_POINT('',#119653); +#119653 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.530776333563)); +#119654 = VERTEX_POINT('',#119655); +#119655 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.530776333563)); +#119656 = SURFACE_CURVE('',#119657,(#119661,#119668),.PCURVE_S1.); +#119657 = LINE('',#119658,#119659); +#119658 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#119659 = VECTOR('',#119660,1.); +#119660 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119661 = PCURVE('',#119636,#119662); +#119662 = DEFINITIONAL_REPRESENTATION('',(#119663),#119667); +#119663 = LINE('',#119664,#119665); +#119664 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119665 = VECTOR('',#119666,1.); +#119666 = DIRECTION('',(-1.,0.E+000)); +#119667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119668 = PCURVE('',#119669,#119674); +#119669 = CYLINDRICAL_SURFACE('',#119670,0.119270391569); +#119670 = AXIS2_PLACEMENT_3D('',#119671,#119672,#119673); +#119671 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#119672 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119673 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119674 = DEFINITIONAL_REPRESENTATION('',(#119675),#119678); +#119675 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119676,#119677), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#117284 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#117285 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#117286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117287 = ORIENTED_EDGE('',*,*,#117288,.T.); -#117288 = EDGE_CURVE('',#117262,#117181,#117289,.T.); -#117289 = SURFACE_CURVE('',#117290,(#117294,#117301),.PCURVE_S1.); -#117290 = LINE('',#117291,#117292); -#117291 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.530776333563)); -#117292 = VECTOR('',#117293,1.); -#117293 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#117294 = PCURVE('',#117244,#117295); -#117295 = DEFINITIONAL_REPRESENTATION('',(#117296),#117300); -#117296 = LINE('',#117297,#117298); -#117297 = CARTESIAN_POINT('',(-3.85,1.133910970711E-033)); -#117298 = VECTOR('',#117299,1.); -#117299 = DIRECTION('',(4.535643882845E-032,-1.)); -#117300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117301 = PCURVE('',#90925,#117302); -#117302 = DEFINITIONAL_REPRESENTATION('',(#117303),#117307); -#117303 = LINE('',#117304,#117305); -#117304 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#117305 = VECTOR('',#117306,1.); -#117306 = DIRECTION('',(1.,-1.021336205033E-016)); -#117307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119676 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#119677 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#119678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119679 = ORIENTED_EDGE('',*,*,#119680,.T.); +#119680 = EDGE_CURVE('',#119654,#119573,#119681,.T.); +#119681 = SURFACE_CURVE('',#119682,(#119686,#119693),.PCURVE_S1.); +#119682 = LINE('',#119683,#119684); +#119683 = CARTESIAN_POINT('',(-0.419594812019,6.15,0.530776333563)); +#119684 = VECTOR('',#119685,1.); +#119685 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#119686 = PCURVE('',#119636,#119687); +#119687 = DEFINITIONAL_REPRESENTATION('',(#119688),#119692); +#119688 = LINE('',#119689,#119690); +#119689 = CARTESIAN_POINT('',(-3.85,1.133910970711E-033)); +#119690 = VECTOR('',#119691,1.); +#119691 = DIRECTION('',(4.535643882845E-032,-1.)); +#119692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119693 = PCURVE('',#93317,#119694); +#119694 = DEFINITIONAL_REPRESENTATION('',(#119695),#119699); +#119695 = LINE('',#119696,#119697); +#119696 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#119697 = VECTOR('',#119698,1.); +#119698 = DIRECTION('',(1.,-1.021336205033E-016)); +#119699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117308 = ORIENTED_EDGE('',*,*,#117231,.F.); -#117309 = ORIENTED_EDGE('',*,*,#117310,.F.); -#117310 = EDGE_CURVE('',#117260,#117209,#117311,.T.); -#117311 = SURFACE_CURVE('',#117312,(#117316,#117323),.PCURVE_S1.); -#117312 = LINE('',#117313,#117314); -#117313 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.530776333563)); -#117314 = VECTOR('',#117315,1.); -#117315 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#117316 = PCURVE('',#117244,#117317); -#117317 = DEFINITIONAL_REPRESENTATION('',(#117318),#117322); -#117318 = LINE('',#117319,#117320); -#117319 = CARTESIAN_POINT('',(-3.65,-1.133910970711E-033)); -#117320 = VECTOR('',#117321,1.); -#117321 = DIRECTION('',(4.535643882845E-032,-1.)); -#117322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117323 = PCURVE('',#90981,#117324); -#117324 = DEFINITIONAL_REPRESENTATION('',(#117325),#117329); -#117325 = LINE('',#117326,#117327); -#117326 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#117327 = VECTOR('',#117328,1.); -#117328 = DIRECTION('',(-1.,-1.021336205033E-016)); -#117329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117330 = ADVANCED_FACE('',(#117331),#117139,.T.); -#117331 = FACE_BOUND('',#117332,.T.); -#117332 = EDGE_LOOP('',(#117333,#117362,#117383,#117384)); -#117333 = ORIENTED_EDGE('',*,*,#117334,.T.); -#117334 = EDGE_CURVE('',#117335,#117337,#117339,.T.); -#117335 = VERTEX_POINT('',#117336); -#117336 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.530776333563)); -#117337 = VERTEX_POINT('',#117338); -#117338 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.530776333563)); -#117339 = SURFACE_CURVE('',#117340,(#117344,#117351),.PCURVE_S1.); -#117340 = LINE('',#117341,#117342); -#117341 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#117342 = VECTOR('',#117343,1.); -#117343 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117344 = PCURVE('',#117139,#117345); -#117345 = DEFINITIONAL_REPRESENTATION('',(#117346),#117350); -#117346 = LINE('',#117347,#117348); -#117347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117348 = VECTOR('',#117349,1.); -#117349 = DIRECTION('',(-1.,0.E+000)); -#117350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117351 = PCURVE('',#117352,#117357); -#117352 = CYLINDRICAL_SURFACE('',#117353,0.2192697516); -#117353 = AXIS2_PLACEMENT_3D('',#117354,#117355,#117356); -#117354 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#117355 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117356 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117357 = DEFINITIONAL_REPRESENTATION('',(#117358),#117361); -#117358 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117359,#117360), +#119700 = ORIENTED_EDGE('',*,*,#119623,.F.); +#119701 = ORIENTED_EDGE('',*,*,#119702,.F.); +#119702 = EDGE_CURVE('',#119652,#119601,#119703,.T.); +#119703 = SURFACE_CURVE('',#119704,(#119708,#119715),.PCURVE_S1.); +#119704 = LINE('',#119705,#119706); +#119705 = CARTESIAN_POINT('',(-0.419594812019,6.35,0.530776333563)); +#119706 = VECTOR('',#119707,1.); +#119707 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#119708 = PCURVE('',#119636,#119709); +#119709 = DEFINITIONAL_REPRESENTATION('',(#119710),#119714); +#119710 = LINE('',#119711,#119712); +#119711 = CARTESIAN_POINT('',(-3.65,-1.133910970711E-033)); +#119712 = VECTOR('',#119713,1.); +#119713 = DIRECTION('',(4.535643882845E-032,-1.)); +#119714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119715 = PCURVE('',#93373,#119716); +#119716 = DEFINITIONAL_REPRESENTATION('',(#119717),#119721); +#119717 = LINE('',#119718,#119719); +#119718 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#119719 = VECTOR('',#119720,1.); +#119720 = DIRECTION('',(-1.,-1.021336205033E-016)); +#119721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119722 = ADVANCED_FACE('',(#119723),#119531,.T.); +#119723 = FACE_BOUND('',#119724,.T.); +#119724 = EDGE_LOOP('',(#119725,#119754,#119775,#119776)); +#119725 = ORIENTED_EDGE('',*,*,#119726,.T.); +#119726 = EDGE_CURVE('',#119727,#119729,#119731,.T.); +#119727 = VERTEX_POINT('',#119728); +#119728 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.530776333563)); +#119729 = VERTEX_POINT('',#119730); +#119730 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.530776333563)); +#119731 = SURFACE_CURVE('',#119732,(#119736,#119743),.PCURVE_S1.); +#119732 = LINE('',#119733,#119734); +#119733 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#119734 = VECTOR('',#119735,1.); +#119735 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119736 = PCURVE('',#119531,#119737); +#119737 = DEFINITIONAL_REPRESENTATION('',(#119738),#119742); +#119738 = LINE('',#119739,#119740); +#119739 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#119740 = VECTOR('',#119741,1.); +#119741 = DIRECTION('',(-1.,0.E+000)); +#119742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119743 = PCURVE('',#119744,#119749); +#119744 = CYLINDRICAL_SURFACE('',#119745,0.2192697516); +#119745 = AXIS2_PLACEMENT_3D('',#119746,#119747,#119748); +#119746 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#119747 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119748 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119749 = DEFINITIONAL_REPRESENTATION('',(#119750),#119753); +#119750 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119751,#119752), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#117359 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#117360 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#117361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117362 = ORIENTED_EDGE('',*,*,#117363,.T.); -#117363 = EDGE_CURVE('',#117337,#117102,#117364,.T.); -#117364 = SURFACE_CURVE('',#117365,(#117369,#117376),.PCURVE_S1.); -#117365 = LINE('',#117366,#117367); -#117366 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.530776333563)); -#117367 = VECTOR('',#117368,1.); -#117368 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#117369 = PCURVE('',#117139,#117370); -#117370 = DEFINITIONAL_REPRESENTATION('',(#117371),#117375); -#117371 = LINE('',#117372,#117373); -#117372 = CARTESIAN_POINT('',(3.65,4.535643882845E-033)); -#117373 = VECTOR('',#117374,1.); -#117374 = DIRECTION('',(-4.535643882845E-032,-1.)); -#117375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117376 = PCURVE('',#90981,#117377); -#117377 = DEFINITIONAL_REPRESENTATION('',(#117378),#117382); -#117378 = LINE('',#117379,#117380); -#117379 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#117380 = VECTOR('',#117381,1.); -#117381 = DIRECTION('',(-1.,-1.021336205033E-016)); -#117382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117383 = ORIENTED_EDGE('',*,*,#117124,.F.); -#117384 = ORIENTED_EDGE('',*,*,#117385,.F.); -#117385 = EDGE_CURVE('',#117335,#117125,#117386,.T.); -#117386 = SURFACE_CURVE('',#117387,(#117391,#117398),.PCURVE_S1.); -#117387 = LINE('',#117388,#117389); -#117388 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.530776333563)); -#117389 = VECTOR('',#117390,1.); -#117390 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#117391 = PCURVE('',#117139,#117392); -#117392 = DEFINITIONAL_REPRESENTATION('',(#117393),#117397); -#117393 = LINE('',#117394,#117395); -#117394 = CARTESIAN_POINT('',(3.85,-4.535643882845E-033)); -#117395 = VECTOR('',#117396,1.); -#117396 = DIRECTION('',(-4.535643882845E-032,-1.)); -#117397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117398 = PCURVE('',#90925,#117399); -#117399 = DEFINITIONAL_REPRESENTATION('',(#117400),#117404); -#117400 = LINE('',#117401,#117402); -#117401 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#117402 = VECTOR('',#117403,1.); -#117403 = DIRECTION('',(1.,-1.021336205033E-016)); -#117404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117405 = ADVANCED_FACE('',(#117406),#117352,.T.); -#117406 = FACE_BOUND('',#117407,.T.); -#117407 = EDGE_LOOP('',(#117408,#117409,#117432,#117477)); -#117408 = ORIENTED_EDGE('',*,*,#117334,.F.); -#117409 = ORIENTED_EDGE('',*,*,#117410,.F.); -#117410 = EDGE_CURVE('',#117411,#117335,#117413,.T.); -#117411 = VERTEX_POINT('',#117412); -#117412 = CARTESIAN_POINT('',(-0.304819755875,6.15,0.75)); -#117413 = SURFACE_CURVE('',#117414,(#117419,#117425),.PCURVE_S1.); -#117414 = CIRCLE('',#117415,0.2192697516); -#117415 = AXIS2_PLACEMENT_3D('',#117416,#117417,#117418); -#117416 = CARTESIAN_POINT('',(-0.30032442045,6.15,0.530776333563)); -#117417 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117418 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117419 = PCURVE('',#117352,#117420); -#117420 = DEFINITIONAL_REPRESENTATION('',(#117421),#117424); -#117421 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117422,#117423), +#119751 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#119752 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#119753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119754 = ORIENTED_EDGE('',*,*,#119755,.T.); +#119755 = EDGE_CURVE('',#119729,#119494,#119756,.T.); +#119756 = SURFACE_CURVE('',#119757,(#119761,#119768),.PCURVE_S1.); +#119757 = LINE('',#119758,#119759); +#119758 = CARTESIAN_POINT('',(-0.51959417205,6.35,0.530776333563)); +#119759 = VECTOR('',#119760,1.); +#119760 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#119761 = PCURVE('',#119531,#119762); +#119762 = DEFINITIONAL_REPRESENTATION('',(#119763),#119767); +#119763 = LINE('',#119764,#119765); +#119764 = CARTESIAN_POINT('',(3.65,4.535643882845E-033)); +#119765 = VECTOR('',#119766,1.); +#119766 = DIRECTION('',(-4.535643882845E-032,-1.)); +#119767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119768 = PCURVE('',#93373,#119769); +#119769 = DEFINITIONAL_REPRESENTATION('',(#119770),#119774); +#119770 = LINE('',#119771,#119772); +#119771 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#119772 = VECTOR('',#119773,1.); +#119773 = DIRECTION('',(-1.,-1.021336205033E-016)); +#119774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119775 = ORIENTED_EDGE('',*,*,#119516,.F.); +#119776 = ORIENTED_EDGE('',*,*,#119777,.F.); +#119777 = EDGE_CURVE('',#119727,#119517,#119778,.T.); +#119778 = SURFACE_CURVE('',#119779,(#119783,#119790),.PCURVE_S1.); +#119779 = LINE('',#119780,#119781); +#119780 = CARTESIAN_POINT('',(-0.51959417205,6.15,0.530776333563)); +#119781 = VECTOR('',#119782,1.); +#119782 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#119783 = PCURVE('',#119531,#119784); +#119784 = DEFINITIONAL_REPRESENTATION('',(#119785),#119789); +#119785 = LINE('',#119786,#119787); +#119786 = CARTESIAN_POINT('',(3.85,-4.535643882845E-033)); +#119787 = VECTOR('',#119788,1.); +#119788 = DIRECTION('',(-4.535643882845E-032,-1.)); +#119789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119790 = PCURVE('',#93317,#119791); +#119791 = DEFINITIONAL_REPRESENTATION('',(#119792),#119796); +#119792 = LINE('',#119793,#119794); +#119793 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#119794 = VECTOR('',#119795,1.); +#119795 = DIRECTION('',(1.,-1.021336205033E-016)); +#119796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119797 = ADVANCED_FACE('',(#119798),#119744,.T.); +#119798 = FACE_BOUND('',#119799,.T.); +#119799 = EDGE_LOOP('',(#119800,#119801,#119824,#119869)); +#119800 = ORIENTED_EDGE('',*,*,#119726,.F.); +#119801 = ORIENTED_EDGE('',*,*,#119802,.F.); +#119802 = EDGE_CURVE('',#119803,#119727,#119805,.T.); +#119803 = VERTEX_POINT('',#119804); +#119804 = CARTESIAN_POINT('',(-0.304819755875,6.15,0.75)); +#119805 = SURFACE_CURVE('',#119806,(#119811,#119817),.PCURVE_S1.); +#119806 = CIRCLE('',#119807,0.2192697516); +#119807 = AXIS2_PLACEMENT_3D('',#119808,#119809,#119810); +#119808 = CARTESIAN_POINT('',(-0.30032442045,6.15,0.530776333563)); +#119809 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119810 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119811 = PCURVE('',#119744,#119812); +#119812 = DEFINITIONAL_REPRESENTATION('',(#119813),#119816); +#119813 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119814,#119815), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#117422 = CARTESIAN_POINT('',(1.591299156552,3.85)); -#117423 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#117424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117425 = PCURVE('',#90925,#117426); -#117426 = DEFINITIONAL_REPRESENTATION('',(#117427),#117431); -#117427 = CIRCLE('',#117428,0.2192697516); -#117428 = AXIS2_PLACEMENT_2D('',#117429,#117430); -#117429 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#117430 = DIRECTION('',(0.E+000,1.)); -#117431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117432 = ORIENTED_EDGE('',*,*,#117433,.F.); -#117433 = EDGE_CURVE('',#117434,#117411,#117436,.T.); -#117434 = VERTEX_POINT('',#117435); -#117435 = CARTESIAN_POINT('',(-0.304819755875,6.35,0.75)); -#117436 = SURFACE_CURVE('',#117437,(#117441,#117470),.PCURVE_S1.); -#117437 = LINE('',#117438,#117439); -#117438 = CARTESIAN_POINT('',(-0.304819755875,6.15,0.75)); -#117439 = VECTOR('',#117440,1.); -#117440 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117441 = PCURVE('',#117352,#117442); -#117442 = DEFINITIONAL_REPRESENTATION('',(#117443),#117469); -#117443 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#117444,#117445,#117446, - #117447,#117448,#117449,#117450,#117451,#117452,#117453,#117454, - #117455,#117456,#117457,#117458,#117459,#117460,#117461,#117462, - #117463,#117464,#117465,#117466,#117467,#117468),.UNSPECIFIED.,.F., +#119814 = CARTESIAN_POINT('',(1.591299156552,3.85)); +#119815 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#119816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119817 = PCURVE('',#93317,#119818); +#119818 = DEFINITIONAL_REPRESENTATION('',(#119819),#119823); +#119819 = CIRCLE('',#119820,0.2192697516); +#119820 = AXIS2_PLACEMENT_2D('',#119821,#119822); +#119821 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#119822 = DIRECTION('',(0.E+000,1.)); +#119823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119824 = ORIENTED_EDGE('',*,*,#119825,.F.); +#119825 = EDGE_CURVE('',#119826,#119803,#119828,.T.); +#119826 = VERTEX_POINT('',#119827); +#119827 = CARTESIAN_POINT('',(-0.304819755875,6.35,0.75)); +#119828 = SURFACE_CURVE('',#119829,(#119833,#119862),.PCURVE_S1.); +#119829 = LINE('',#119830,#119831); +#119830 = CARTESIAN_POINT('',(-0.304819755875,6.15,0.75)); +#119831 = VECTOR('',#119832,1.); +#119832 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119833 = PCURVE('',#119744,#119834); +#119834 = DEFINITIONAL_REPRESENTATION('',(#119835),#119861); +#119835 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#119836,#119837,#119838, + #119839,#119840,#119841,#119842,#119843,#119844,#119845,#119846, + #119847,#119848,#119849,#119850,#119851,#119852,#119853,#119854, + #119855,#119856,#119857,#119858,#119859,#119860),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -144659,128 +147661,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.UNSPECIFIED.); -#117444 = CARTESIAN_POINT('',(1.591299156552,3.65)); -#117445 = CARTESIAN_POINT('',(1.591299156552,3.65303030303)); -#117446 = CARTESIAN_POINT('',(1.591299156552,3.659090909091)); -#117447 = CARTESIAN_POINT('',(1.591299156552,3.668181818182)); -#117448 = CARTESIAN_POINT('',(1.591299156552,3.677272727273)); -#117449 = CARTESIAN_POINT('',(1.591299156552,3.686363636364)); -#117450 = CARTESIAN_POINT('',(1.591299156552,3.695454545455)); -#117451 = CARTESIAN_POINT('',(1.591299156552,3.704545454545)); -#117452 = CARTESIAN_POINT('',(1.591299156552,3.713636363636)); -#117453 = CARTESIAN_POINT('',(1.591299156552,3.722727272727)); -#117454 = CARTESIAN_POINT('',(1.591299156552,3.731818181818)); -#117455 = CARTESIAN_POINT('',(1.591299156552,3.740909090909)); -#117456 = CARTESIAN_POINT('',(1.591299156552,3.75)); -#117457 = CARTESIAN_POINT('',(1.591299156552,3.759090909091)); -#117458 = CARTESIAN_POINT('',(1.591299156552,3.768181818182)); -#117459 = CARTESIAN_POINT('',(1.591299156552,3.777272727273)); -#117460 = CARTESIAN_POINT('',(1.591299156552,3.786363636364)); -#117461 = CARTESIAN_POINT('',(1.591299156552,3.795454545455)); -#117462 = CARTESIAN_POINT('',(1.591299156552,3.804545454545)); -#117463 = CARTESIAN_POINT('',(1.591299156552,3.813636363636)); -#117464 = CARTESIAN_POINT('',(1.591299156552,3.822727272727)); -#117465 = CARTESIAN_POINT('',(1.591299156552,3.831818181818)); -#117466 = CARTESIAN_POINT('',(1.591299156552,3.840909090909)); -#117467 = CARTESIAN_POINT('',(1.591299156552,3.84696969697)); -#117468 = CARTESIAN_POINT('',(1.591299156552,3.85)); -#117469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117470 = PCURVE('',#91007,#117471); -#117471 = DEFINITIONAL_REPRESENTATION('',(#117472),#117476); -#117472 = LINE('',#117473,#117474); -#117473 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#117474 = VECTOR('',#117475,1.); -#117475 = DIRECTION('',(4.440892098501E-016,-1.)); -#117476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117477 = ORIENTED_EDGE('',*,*,#117478,.T.); -#117478 = EDGE_CURVE('',#117434,#117337,#117479,.T.); -#117479 = SURFACE_CURVE('',#117480,(#117485,#117491),.PCURVE_S1.); -#117480 = CIRCLE('',#117481,0.2192697516); -#117481 = AXIS2_PLACEMENT_3D('',#117482,#117483,#117484); -#117482 = CARTESIAN_POINT('',(-0.30032442045,6.35,0.530776333563)); -#117483 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117484 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117485 = PCURVE('',#117352,#117486); -#117486 = DEFINITIONAL_REPRESENTATION('',(#117487),#117490); -#117487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117488,#117489), +#119836 = CARTESIAN_POINT('',(1.591299156552,3.65)); +#119837 = CARTESIAN_POINT('',(1.591299156552,3.65303030303)); +#119838 = CARTESIAN_POINT('',(1.591299156552,3.659090909091)); +#119839 = CARTESIAN_POINT('',(1.591299156552,3.668181818182)); +#119840 = CARTESIAN_POINT('',(1.591299156552,3.677272727273)); +#119841 = CARTESIAN_POINT('',(1.591299156552,3.686363636364)); +#119842 = CARTESIAN_POINT('',(1.591299156552,3.695454545455)); +#119843 = CARTESIAN_POINT('',(1.591299156552,3.704545454545)); +#119844 = CARTESIAN_POINT('',(1.591299156552,3.713636363636)); +#119845 = CARTESIAN_POINT('',(1.591299156552,3.722727272727)); +#119846 = CARTESIAN_POINT('',(1.591299156552,3.731818181818)); +#119847 = CARTESIAN_POINT('',(1.591299156552,3.740909090909)); +#119848 = CARTESIAN_POINT('',(1.591299156552,3.75)); +#119849 = CARTESIAN_POINT('',(1.591299156552,3.759090909091)); +#119850 = CARTESIAN_POINT('',(1.591299156552,3.768181818182)); +#119851 = CARTESIAN_POINT('',(1.591299156552,3.777272727273)); +#119852 = CARTESIAN_POINT('',(1.591299156552,3.786363636364)); +#119853 = CARTESIAN_POINT('',(1.591299156552,3.795454545455)); +#119854 = CARTESIAN_POINT('',(1.591299156552,3.804545454545)); +#119855 = CARTESIAN_POINT('',(1.591299156552,3.813636363636)); +#119856 = CARTESIAN_POINT('',(1.591299156552,3.822727272727)); +#119857 = CARTESIAN_POINT('',(1.591299156552,3.831818181818)); +#119858 = CARTESIAN_POINT('',(1.591299156552,3.840909090909)); +#119859 = CARTESIAN_POINT('',(1.591299156552,3.84696969697)); +#119860 = CARTESIAN_POINT('',(1.591299156552,3.85)); +#119861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119862 = PCURVE('',#93399,#119863); +#119863 = DEFINITIONAL_REPRESENTATION('',(#119864),#119868); +#119864 = LINE('',#119865,#119866); +#119865 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#119866 = VECTOR('',#119867,1.); +#119867 = DIRECTION('',(4.440892098501E-016,-1.)); +#119868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119869 = ORIENTED_EDGE('',*,*,#119870,.T.); +#119870 = EDGE_CURVE('',#119826,#119729,#119871,.T.); +#119871 = SURFACE_CURVE('',#119872,(#119877,#119883),.PCURVE_S1.); +#119872 = CIRCLE('',#119873,0.2192697516); +#119873 = AXIS2_PLACEMENT_3D('',#119874,#119875,#119876); +#119874 = CARTESIAN_POINT('',(-0.30032442045,6.35,0.530776333563)); +#119875 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119876 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119877 = PCURVE('',#119744,#119878); +#119878 = DEFINITIONAL_REPRESENTATION('',(#119879),#119882); +#119879 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119880,#119881), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#117488 = CARTESIAN_POINT('',(1.591299156552,3.65)); -#117489 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#117490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119880 = CARTESIAN_POINT('',(1.591299156552,3.65)); +#119881 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#119882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117491 = PCURVE('',#90981,#117492); -#117492 = DEFINITIONAL_REPRESENTATION('',(#117493),#117501); -#117493 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117494,#117495,#117496, - #117497,#117498,#117499,#117500),.UNSPECIFIED.,.T.,.F.) +#119883 = PCURVE('',#93373,#119884); +#119884 = DEFINITIONAL_REPRESENTATION('',(#119885),#119893); +#119885 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119886,#119887,#119888, + #119889,#119890,#119891,#119892),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#117494 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#117495 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#117496 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#117497 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#117498 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#117499 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#117500 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#117501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117502 = ADVANCED_FACE('',(#117503),#117277,.F.); -#117503 = FACE_BOUND('',#117504,.F.); -#117504 = EDGE_LOOP('',(#117505,#117506,#117529,#117574)); -#117505 = ORIENTED_EDGE('',*,*,#117259,.T.); -#117506 = ORIENTED_EDGE('',*,*,#117507,.F.); -#117507 = EDGE_CURVE('',#117508,#117262,#117510,.T.); -#117508 = VERTEX_POINT('',#117509); -#117509 = CARTESIAN_POINT('',(-0.303662633502,6.15,0.65)); -#117510 = SURFACE_CURVE('',#117511,(#117516,#117522),.PCURVE_S1.); -#117511 = CIRCLE('',#117512,0.119270391569); -#117512 = AXIS2_PLACEMENT_3D('',#117513,#117514,#117515); -#117513 = CARTESIAN_POINT('',(-0.30032442045,6.15,0.530776333563)); -#117514 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117515 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117516 = PCURVE('',#117277,#117517); -#117517 = DEFINITIONAL_REPRESENTATION('',(#117518),#117521); -#117518 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117519,#117520), +#119886 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#119887 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#119888 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#119889 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#119890 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#119891 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#119892 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#119893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119894 = ADVANCED_FACE('',(#119895),#119669,.F.); +#119895 = FACE_BOUND('',#119896,.F.); +#119896 = EDGE_LOOP('',(#119897,#119898,#119921,#119966)); +#119897 = ORIENTED_EDGE('',*,*,#119651,.T.); +#119898 = ORIENTED_EDGE('',*,*,#119899,.F.); +#119899 = EDGE_CURVE('',#119900,#119654,#119902,.T.); +#119900 = VERTEX_POINT('',#119901); +#119901 = CARTESIAN_POINT('',(-0.303662633502,6.15,0.65)); +#119902 = SURFACE_CURVE('',#119903,(#119908,#119914),.PCURVE_S1.); +#119903 = CIRCLE('',#119904,0.119270391569); +#119904 = AXIS2_PLACEMENT_3D('',#119905,#119906,#119907); +#119905 = CARTESIAN_POINT('',(-0.30032442045,6.15,0.530776333563)); +#119906 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119907 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119908 = PCURVE('',#119669,#119909); +#119909 = DEFINITIONAL_REPRESENTATION('',(#119910),#119913); +#119910 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119911,#119912), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#117519 = CARTESIAN_POINT('',(1.598788597134,3.85)); -#117520 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#117521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117522 = PCURVE('',#90925,#117523); -#117523 = DEFINITIONAL_REPRESENTATION('',(#117524),#117528); -#117524 = CIRCLE('',#117525,0.119270391569); -#117525 = AXIS2_PLACEMENT_2D('',#117526,#117527); -#117526 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#117527 = DIRECTION('',(0.E+000,1.)); -#117528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117529 = ORIENTED_EDGE('',*,*,#117530,.T.); -#117530 = EDGE_CURVE('',#117508,#117531,#117533,.T.); -#117531 = VERTEX_POINT('',#117532); -#117532 = CARTESIAN_POINT('',(-0.303662633502,6.35,0.65)); -#117533 = SURFACE_CURVE('',#117534,(#117538,#117567),.PCURVE_S1.); -#117534 = LINE('',#117535,#117536); -#117535 = CARTESIAN_POINT('',(-0.303662633502,6.15,0.65)); -#117536 = VECTOR('',#117537,1.); -#117537 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117538 = PCURVE('',#117277,#117539); -#117539 = DEFINITIONAL_REPRESENTATION('',(#117540),#117566); -#117540 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#117541,#117542,#117543, - #117544,#117545,#117546,#117547,#117548,#117549,#117550,#117551, - #117552,#117553,#117554,#117555,#117556,#117557,#117558,#117559, - #117560,#117561,#117562,#117563,#117564,#117565),.UNSPECIFIED.,.F., +#119911 = CARTESIAN_POINT('',(1.598788597134,3.85)); +#119912 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#119913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119914 = PCURVE('',#93317,#119915); +#119915 = DEFINITIONAL_REPRESENTATION('',(#119916),#119920); +#119916 = CIRCLE('',#119917,0.119270391569); +#119917 = AXIS2_PLACEMENT_2D('',#119918,#119919); +#119918 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#119919 = DIRECTION('',(0.E+000,1.)); +#119920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119921 = ORIENTED_EDGE('',*,*,#119922,.T.); +#119922 = EDGE_CURVE('',#119900,#119923,#119925,.T.); +#119923 = VERTEX_POINT('',#119924); +#119924 = CARTESIAN_POINT('',(-0.303662633502,6.35,0.65)); +#119925 = SURFACE_CURVE('',#119926,(#119930,#119959),.PCURVE_S1.); +#119926 = LINE('',#119927,#119928); +#119927 = CARTESIAN_POINT('',(-0.303662633502,6.15,0.65)); +#119928 = VECTOR('',#119929,1.); +#119929 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#119930 = PCURVE('',#119669,#119931); +#119931 = DEFINITIONAL_REPRESENTATION('',(#119932),#119958); +#119932 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#119933,#119934,#119935, + #119936,#119937,#119938,#119939,#119940,#119941,#119942,#119943, + #119944,#119945,#119946,#119947,#119948,#119949,#119950,#119951, + #119952,#119953,#119954,#119955,#119956,#119957),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -144789,956 +147791,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#117541 = CARTESIAN_POINT('',(1.598788597134,3.85)); -#117542 = CARTESIAN_POINT('',(1.598788597134,3.84696969697)); -#117543 = CARTESIAN_POINT('',(1.598788597134,3.840909090909)); -#117544 = CARTESIAN_POINT('',(1.598788597134,3.831818181818)); -#117545 = CARTESIAN_POINT('',(1.598788597134,3.822727272727)); -#117546 = CARTESIAN_POINT('',(1.598788597134,3.813636363636)); -#117547 = CARTESIAN_POINT('',(1.598788597134,3.804545454545)); -#117548 = CARTESIAN_POINT('',(1.598788597134,3.795454545455)); -#117549 = CARTESIAN_POINT('',(1.598788597134,3.786363636364)); -#117550 = CARTESIAN_POINT('',(1.598788597134,3.777272727273)); -#117551 = CARTESIAN_POINT('',(1.598788597134,3.768181818182)); -#117552 = CARTESIAN_POINT('',(1.598788597134,3.759090909091)); -#117553 = CARTESIAN_POINT('',(1.598788597134,3.75)); -#117554 = CARTESIAN_POINT('',(1.598788597134,3.740909090909)); -#117555 = CARTESIAN_POINT('',(1.598788597134,3.731818181818)); -#117556 = CARTESIAN_POINT('',(1.598788597134,3.722727272727)); -#117557 = CARTESIAN_POINT('',(1.598788597134,3.713636363636)); -#117558 = CARTESIAN_POINT('',(1.598788597134,3.704545454545)); -#117559 = CARTESIAN_POINT('',(1.598788597134,3.695454545455)); -#117560 = CARTESIAN_POINT('',(1.598788597134,3.686363636364)); -#117561 = CARTESIAN_POINT('',(1.598788597134,3.677272727273)); -#117562 = CARTESIAN_POINT('',(1.598788597134,3.668181818182)); -#117563 = CARTESIAN_POINT('',(1.598788597134,3.659090909091)); -#117564 = CARTESIAN_POINT('',(1.598788597134,3.65303030303)); -#117565 = CARTESIAN_POINT('',(1.598788597134,3.65)); -#117566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117567 = PCURVE('',#90953,#117568); -#117568 = DEFINITIONAL_REPRESENTATION('',(#117569),#117573); -#117569 = LINE('',#117570,#117571); -#117570 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#117571 = VECTOR('',#117572,1.); -#117572 = DIRECTION('',(4.440892098501E-016,1.)); -#117573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117574 = ORIENTED_EDGE('',*,*,#117575,.T.); -#117575 = EDGE_CURVE('',#117531,#117260,#117576,.T.); -#117576 = SURFACE_CURVE('',#117577,(#117582,#117588),.PCURVE_S1.); -#117577 = CIRCLE('',#117578,0.119270391569); -#117578 = AXIS2_PLACEMENT_3D('',#117579,#117580,#117581); -#117579 = CARTESIAN_POINT('',(-0.30032442045,6.35,0.530776333563)); -#117580 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117581 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#117582 = PCURVE('',#117277,#117583); -#117583 = DEFINITIONAL_REPRESENTATION('',(#117584),#117587); -#117584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117585,#117586), +#119933 = CARTESIAN_POINT('',(1.598788597134,3.85)); +#119934 = CARTESIAN_POINT('',(1.598788597134,3.84696969697)); +#119935 = CARTESIAN_POINT('',(1.598788597134,3.840909090909)); +#119936 = CARTESIAN_POINT('',(1.598788597134,3.831818181818)); +#119937 = CARTESIAN_POINT('',(1.598788597134,3.822727272727)); +#119938 = CARTESIAN_POINT('',(1.598788597134,3.813636363636)); +#119939 = CARTESIAN_POINT('',(1.598788597134,3.804545454545)); +#119940 = CARTESIAN_POINT('',(1.598788597134,3.795454545455)); +#119941 = CARTESIAN_POINT('',(1.598788597134,3.786363636364)); +#119942 = CARTESIAN_POINT('',(1.598788597134,3.777272727273)); +#119943 = CARTESIAN_POINT('',(1.598788597134,3.768181818182)); +#119944 = CARTESIAN_POINT('',(1.598788597134,3.759090909091)); +#119945 = CARTESIAN_POINT('',(1.598788597134,3.75)); +#119946 = CARTESIAN_POINT('',(1.598788597134,3.740909090909)); +#119947 = CARTESIAN_POINT('',(1.598788597134,3.731818181818)); +#119948 = CARTESIAN_POINT('',(1.598788597134,3.722727272727)); +#119949 = CARTESIAN_POINT('',(1.598788597134,3.713636363636)); +#119950 = CARTESIAN_POINT('',(1.598788597134,3.704545454545)); +#119951 = CARTESIAN_POINT('',(1.598788597134,3.695454545455)); +#119952 = CARTESIAN_POINT('',(1.598788597134,3.686363636364)); +#119953 = CARTESIAN_POINT('',(1.598788597134,3.677272727273)); +#119954 = CARTESIAN_POINT('',(1.598788597134,3.668181818182)); +#119955 = CARTESIAN_POINT('',(1.598788597134,3.659090909091)); +#119956 = CARTESIAN_POINT('',(1.598788597134,3.65303030303)); +#119957 = CARTESIAN_POINT('',(1.598788597134,3.65)); +#119958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119959 = PCURVE('',#93345,#119960); +#119960 = DEFINITIONAL_REPRESENTATION('',(#119961),#119965); +#119961 = LINE('',#119962,#119963); +#119962 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#119963 = VECTOR('',#119964,1.); +#119964 = DIRECTION('',(4.440892098501E-016,1.)); +#119965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119966 = ORIENTED_EDGE('',*,*,#119967,.T.); +#119967 = EDGE_CURVE('',#119923,#119652,#119968,.T.); +#119968 = SURFACE_CURVE('',#119969,(#119974,#119980),.PCURVE_S1.); +#119969 = CIRCLE('',#119970,0.119270391569); +#119970 = AXIS2_PLACEMENT_3D('',#119971,#119972,#119973); +#119971 = CARTESIAN_POINT('',(-0.30032442045,6.35,0.530776333563)); +#119972 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#119973 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#119974 = PCURVE('',#119669,#119975); +#119975 = DEFINITIONAL_REPRESENTATION('',(#119976),#119979); +#119976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119977,#119978), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#117585 = CARTESIAN_POINT('',(1.598788597134,3.65)); -#117586 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#117587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119977 = CARTESIAN_POINT('',(1.598788597134,3.65)); +#119978 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#119979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117588 = PCURVE('',#90981,#117589); -#117589 = DEFINITIONAL_REPRESENTATION('',(#117590),#117598); -#117590 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#117591,#117592,#117593, - #117594,#117595,#117596,#117597),.UNSPECIFIED.,.T.,.F.) +#119980 = PCURVE('',#93373,#119981); +#119981 = DEFINITIONAL_REPRESENTATION('',(#119982),#119990); +#119982 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119983,#119984,#119985, + #119986,#119987,#119988,#119989),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#117591 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#117592 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#117593 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#117594 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#117595 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#117596 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#117597 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#117598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117599 = ADVANCED_FACE('',(#117600),#90953,.T.); -#117600 = FACE_BOUND('',#117601,.T.); -#117601 = EDGE_LOOP('',(#117602,#117623,#117624,#117645)); -#117602 = ORIENTED_EDGE('',*,*,#117603,.F.); -#117603 = EDGE_CURVE('',#117508,#90910,#117604,.T.); -#117604 = SURFACE_CURVE('',#117605,(#117609,#117616),.PCURVE_S1.); -#117605 = LINE('',#117606,#117607); -#117606 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); -#117607 = VECTOR('',#117608,1.); -#117608 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#117609 = PCURVE('',#90953,#117610); -#117610 = DEFINITIONAL_REPRESENTATION('',(#117611),#117615); -#117611 = LINE('',#117612,#117613); -#117612 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117613 = VECTOR('',#117614,1.); -#117614 = DIRECTION('',(-1.,-4.804757279354E-063)); -#117615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117616 = PCURVE('',#90925,#117617); -#117617 = DEFINITIONAL_REPRESENTATION('',(#117618),#117622); -#117618 = LINE('',#117619,#117620); -#117619 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117620 = VECTOR('',#117621,1.); -#117621 = DIRECTION('',(-3.563627120235E-016,1.)); -#117622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117623 = ORIENTED_EDGE('',*,*,#117530,.T.); -#117624 = ORIENTED_EDGE('',*,*,#117625,.T.); -#117625 = EDGE_CURVE('',#117531,#90938,#117626,.T.); -#117626 = SURFACE_CURVE('',#117627,(#117631,#117638),.PCURVE_S1.); -#117627 = LINE('',#117628,#117629); -#117628 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.65)); -#117629 = VECTOR('',#117630,1.); -#117630 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#117631 = PCURVE('',#90953,#117632); -#117632 = DEFINITIONAL_REPRESENTATION('',(#117633),#117637); -#117633 = LINE('',#117634,#117635); -#117634 = CARTESIAN_POINT('',(0.E+000,0.2)); -#117635 = VECTOR('',#117636,1.); -#117636 = DIRECTION('',(-1.,-4.804757279354E-063)); -#117637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117638 = PCURVE('',#90981,#117639); -#117639 = DEFINITIONAL_REPRESENTATION('',(#117640),#117644); -#117640 = LINE('',#117641,#117642); -#117641 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117642 = VECTOR('',#117643,1.); -#117643 = DIRECTION('',(3.563627120235E-016,1.)); -#117644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117645 = ORIENTED_EDGE('',*,*,#90937,.F.); -#117646 = ADVANCED_FACE('',(#117647),#90981,.T.); -#117647 = FACE_BOUND('',#117648,.T.); -#117648 = EDGE_LOOP('',(#117649,#117650,#117651,#117652,#117653,#117654, - #117675,#117676,#117677,#117678,#117679,#117700)); -#117649 = ORIENTED_EDGE('',*,*,#117625,.F.); -#117650 = ORIENTED_EDGE('',*,*,#117575,.T.); -#117651 = ORIENTED_EDGE('',*,*,#117310,.T.); -#117652 = ORIENTED_EDGE('',*,*,#117208,.T.); -#117653 = ORIENTED_EDGE('',*,*,#117027,.T.); -#117654 = ORIENTED_EDGE('',*,*,#117655,.F.); -#117655 = EDGE_CURVE('',#116891,#116998,#117656,.T.); -#117656 = SURFACE_CURVE('',#117657,(#117661,#117668),.PCURVE_S1.); -#117657 = LINE('',#117658,#117659); -#117658 = CARTESIAN_POINT('',(-1.,6.35,1.159810404338E-002)); -#117659 = VECTOR('',#117660,1.); -#117660 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#117661 = PCURVE('',#90981,#117662); -#117662 = DEFINITIONAL_REPRESENTATION('',(#117663),#117667); -#117663 = LINE('',#117664,#117665); -#117664 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#117665 = VECTOR('',#117666,1.); -#117666 = DIRECTION('',(-1.,2.101748079665E-016)); -#117667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117668 = PCURVE('',#116911,#117669); -#117669 = DEFINITIONAL_REPRESENTATION('',(#117670),#117674); -#117670 = LINE('',#117671,#117672); -#117671 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#117672 = VECTOR('',#117673,1.); -#117673 = DIRECTION('',(1.194699204908E-017,-1.)); -#117674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117675 = ORIENTED_EDGE('',*,*,#116973,.F.); -#117676 = ORIENTED_EDGE('',*,*,#117101,.F.); -#117677 = ORIENTED_EDGE('',*,*,#117363,.F.); -#117678 = ORIENTED_EDGE('',*,*,#117478,.F.); -#117679 = ORIENTED_EDGE('',*,*,#117680,.T.); -#117680 = EDGE_CURVE('',#117434,#90966,#117681,.T.); -#117681 = SURFACE_CURVE('',#117682,(#117686,#117693),.PCURVE_S1.); -#117682 = LINE('',#117683,#117684); -#117683 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.75)); -#117684 = VECTOR('',#117685,1.); -#117685 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#117686 = PCURVE('',#90981,#117687); -#117687 = DEFINITIONAL_REPRESENTATION('',(#117688),#117692); -#117688 = LINE('',#117689,#117690); -#117689 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#117690 = VECTOR('',#117691,1.); -#117691 = DIRECTION('',(3.563627120235E-016,1.)); -#117692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117693 = PCURVE('',#91007,#117694); -#117694 = DEFINITIONAL_REPRESENTATION('',(#117695),#117699); -#117695 = LINE('',#117696,#117697); -#117696 = CARTESIAN_POINT('',(0.E+000,0.2)); -#117697 = VECTOR('',#117698,1.); -#117698 = DIRECTION('',(1.,-4.804757279354E-063)); -#117699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117700 = ORIENTED_EDGE('',*,*,#90965,.F.); -#117701 = ADVANCED_FACE('',(#117702),#91007,.T.); -#117702 = FACE_BOUND('',#117703,.T.); -#117703 = EDGE_LOOP('',(#117704,#117705,#117706,#117727)); -#117704 = ORIENTED_EDGE('',*,*,#117680,.F.); -#117705 = ORIENTED_EDGE('',*,*,#117433,.T.); -#117706 = ORIENTED_EDGE('',*,*,#117707,.T.); -#117707 = EDGE_CURVE('',#117411,#90908,#117708,.T.); -#117708 = SURFACE_CURVE('',#117709,(#117713,#117720),.PCURVE_S1.); -#117709 = LINE('',#117710,#117711); -#117710 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.75)); -#117711 = VECTOR('',#117712,1.); -#117712 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#117713 = PCURVE('',#91007,#117714); -#117714 = DEFINITIONAL_REPRESENTATION('',(#117715),#117719); -#117715 = LINE('',#117716,#117717); -#117716 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117717 = VECTOR('',#117718,1.); -#117718 = DIRECTION('',(1.,-4.804757279354E-063)); -#117719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117720 = PCURVE('',#90925,#117721); -#117721 = DEFINITIONAL_REPRESENTATION('',(#117722),#117726); -#117722 = LINE('',#117723,#117724); -#117723 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#117724 = VECTOR('',#117725,1.); -#117725 = DIRECTION('',(-3.563627120235E-016,1.)); -#117726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117727 = ORIENTED_EDGE('',*,*,#90993,.F.); -#117728 = ADVANCED_FACE('',(#117729),#90925,.T.); -#117729 = FACE_BOUND('',#117730,.T.); -#117730 = EDGE_LOOP('',(#117731,#117732,#117733,#117734,#117735,#117736, - #117757,#117758,#117759,#117760,#117761,#117762)); -#117731 = ORIENTED_EDGE('',*,*,#117707,.F.); -#117732 = ORIENTED_EDGE('',*,*,#117410,.T.); -#117733 = ORIENTED_EDGE('',*,*,#117385,.T.); -#117734 = ORIENTED_EDGE('',*,*,#117151,.T.); -#117735 = ORIENTED_EDGE('',*,*,#116923,.T.); -#117736 = ORIENTED_EDGE('',*,*,#117737,.F.); -#117737 = EDGE_CURVE('',#117000,#116889,#117738,.T.); -#117738 = SURFACE_CURVE('',#117739,(#117743,#117750),.PCURVE_S1.); -#117739 = LINE('',#117740,#117741); -#117740 = CARTESIAN_POINT('',(-1.,6.15,1.159810404338E-002)); -#117741 = VECTOR('',#117742,1.); -#117742 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#117743 = PCURVE('',#90925,#117744); -#117744 = DEFINITIONAL_REPRESENTATION('',(#117745),#117749); -#117745 = LINE('',#117746,#117747); -#117746 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#117747 = VECTOR('',#117748,1.); -#117748 = DIRECTION('',(-1.,-2.101748079665E-016)); -#117749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117750 = PCURVE('',#116911,#117751); -#117751 = DEFINITIONAL_REPRESENTATION('',(#117752),#117756); -#117752 = LINE('',#117753,#117754); -#117753 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#117754 = VECTOR('',#117755,1.); -#117755 = DIRECTION('',(-1.194699204908E-017,1.)); -#117756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117757 = ORIENTED_EDGE('',*,*,#117077,.F.); -#117758 = ORIENTED_EDGE('',*,*,#117180,.F.); -#117759 = ORIENTED_EDGE('',*,*,#117288,.F.); -#117760 = ORIENTED_EDGE('',*,*,#117507,.F.); -#117761 = ORIENTED_EDGE('',*,*,#117603,.T.); -#117762 = ORIENTED_EDGE('',*,*,#90907,.F.); -#117763 = ADVANCED_FACE('',(#117764),#116911,.T.); -#117764 = FACE_BOUND('',#117765,.T.); -#117765 = EDGE_LOOP('',(#117766,#117767,#117768,#117769)); -#117766 = ORIENTED_EDGE('',*,*,#117655,.T.); -#117767 = ORIENTED_EDGE('',*,*,#116997,.T.); -#117768 = ORIENTED_EDGE('',*,*,#117737,.T.); -#117769 = ORIENTED_EDGE('',*,*,#116888,.T.); -#117770 = ADVANCED_FACE('',(#117771),#117785,.F.); -#117771 = FACE_BOUND('',#117772,.T.); -#117772 = EDGE_LOOP('',(#117773,#117808,#117831,#117858)); -#117773 = ORIENTED_EDGE('',*,*,#117774,.F.); -#117774 = EDGE_CURVE('',#117775,#117777,#117779,.T.); -#117775 = VERTEX_POINT('',#117776); -#117776 = CARTESIAN_POINT('',(-1.,6.65,-0.208196358798)); -#117777 = VERTEX_POINT('',#117778); -#117778 = CARTESIAN_POINT('',(-1.,6.85,-0.208196358798)); -#117779 = SURFACE_CURVE('',#117780,(#117784,#117796),.PCURVE_S1.); -#117780 = LINE('',#117781,#117782); -#117781 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#117782 = VECTOR('',#117783,1.); -#117783 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117784 = PCURVE('',#117785,#117790); -#117785 = PLANE('',#117786); -#117786 = AXIS2_PLACEMENT_3D('',#117787,#117788,#117789); -#117787 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#117788 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#117789 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117790 = DEFINITIONAL_REPRESENTATION('',(#117791),#117795); -#117791 = LINE('',#117792,#117793); -#117792 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#117793 = VECTOR('',#117794,1.); -#117794 = DIRECTION('',(4.440892098501E-016,1.)); -#117795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#119983 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#119984 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#119985 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#119986 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#119987 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#119988 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#119989 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#119990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#119991 = ADVANCED_FACE('',(#119992),#93345,.T.); +#119992 = FACE_BOUND('',#119993,.T.); +#119993 = EDGE_LOOP('',(#119994,#120015,#120016,#120037)); +#119994 = ORIENTED_EDGE('',*,*,#119995,.F.); +#119995 = EDGE_CURVE('',#119900,#93302,#119996,.T.); +#119996 = SURFACE_CURVE('',#119997,(#120001,#120008),.PCURVE_S1.); +#119997 = LINE('',#119998,#119999); +#119998 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.65)); +#119999 = VECTOR('',#120000,1.); +#120000 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120001 = PCURVE('',#93345,#120002); +#120002 = DEFINITIONAL_REPRESENTATION('',(#120003),#120007); +#120003 = LINE('',#120004,#120005); +#120004 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120005 = VECTOR('',#120006,1.); +#120006 = DIRECTION('',(-1.,-4.804757279354E-063)); +#120007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120008 = PCURVE('',#93317,#120009); +#120009 = DEFINITIONAL_REPRESENTATION('',(#120010),#120014); +#120010 = LINE('',#120011,#120012); +#120011 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120012 = VECTOR('',#120013,1.); +#120013 = DIRECTION('',(-3.563627120235E-016,1.)); +#120014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120015 = ORIENTED_EDGE('',*,*,#119922,.T.); +#120016 = ORIENTED_EDGE('',*,*,#120017,.T.); +#120017 = EDGE_CURVE('',#119923,#93330,#120018,.T.); +#120018 = SURFACE_CURVE('',#120019,(#120023,#120030),.PCURVE_S1.); +#120019 = LINE('',#120020,#120021); +#120020 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.65)); +#120021 = VECTOR('',#120022,1.); +#120022 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120023 = PCURVE('',#93345,#120024); +#120024 = DEFINITIONAL_REPRESENTATION('',(#120025),#120029); +#120025 = LINE('',#120026,#120027); +#120026 = CARTESIAN_POINT('',(0.E+000,0.2)); +#120027 = VECTOR('',#120028,1.); +#120028 = DIRECTION('',(-1.,-4.804757279354E-063)); +#120029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120030 = PCURVE('',#93373,#120031); +#120031 = DEFINITIONAL_REPRESENTATION('',(#120032),#120036); +#120032 = LINE('',#120033,#120034); +#120033 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120034 = VECTOR('',#120035,1.); +#120035 = DIRECTION('',(3.563627120235E-016,1.)); +#120036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120037 = ORIENTED_EDGE('',*,*,#93329,.F.); +#120038 = ADVANCED_FACE('',(#120039),#93373,.T.); +#120039 = FACE_BOUND('',#120040,.T.); +#120040 = EDGE_LOOP('',(#120041,#120042,#120043,#120044,#120045,#120046, + #120067,#120068,#120069,#120070,#120071,#120092)); +#120041 = ORIENTED_EDGE('',*,*,#120017,.F.); +#120042 = ORIENTED_EDGE('',*,*,#119967,.T.); +#120043 = ORIENTED_EDGE('',*,*,#119702,.T.); +#120044 = ORIENTED_EDGE('',*,*,#119600,.T.); +#120045 = ORIENTED_EDGE('',*,*,#119419,.T.); +#120046 = ORIENTED_EDGE('',*,*,#120047,.F.); +#120047 = EDGE_CURVE('',#119283,#119390,#120048,.T.); +#120048 = SURFACE_CURVE('',#120049,(#120053,#120060),.PCURVE_S1.); +#120049 = LINE('',#120050,#120051); +#120050 = CARTESIAN_POINT('',(-1.,6.35,1.159810404338E-002)); +#120051 = VECTOR('',#120052,1.); +#120052 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#120053 = PCURVE('',#93373,#120054); +#120054 = DEFINITIONAL_REPRESENTATION('',(#120055),#120059); +#120055 = LINE('',#120056,#120057); +#120056 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#120057 = VECTOR('',#120058,1.); +#120058 = DIRECTION('',(-1.,2.101748079665E-016)); +#120059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120060 = PCURVE('',#119303,#120061); +#120061 = DEFINITIONAL_REPRESENTATION('',(#120062),#120066); +#120062 = LINE('',#120063,#120064); +#120063 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#120064 = VECTOR('',#120065,1.); +#120065 = DIRECTION('',(1.194699204908E-017,-1.)); +#120066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120067 = ORIENTED_EDGE('',*,*,#119365,.F.); +#120068 = ORIENTED_EDGE('',*,*,#119493,.F.); +#120069 = ORIENTED_EDGE('',*,*,#119755,.F.); +#120070 = ORIENTED_EDGE('',*,*,#119870,.F.); +#120071 = ORIENTED_EDGE('',*,*,#120072,.T.); +#120072 = EDGE_CURVE('',#119826,#93358,#120073,.T.); +#120073 = SURFACE_CURVE('',#120074,(#120078,#120085),.PCURVE_S1.); +#120074 = LINE('',#120075,#120076); +#120075 = CARTESIAN_POINT('',(-0.527847992439,6.35,0.75)); +#120076 = VECTOR('',#120077,1.); +#120077 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120078 = PCURVE('',#93373,#120079); +#120079 = DEFINITIONAL_REPRESENTATION('',(#120080),#120084); +#120080 = LINE('',#120081,#120082); +#120081 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#120082 = VECTOR('',#120083,1.); +#120083 = DIRECTION('',(3.563627120235E-016,1.)); +#120084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120085 = PCURVE('',#93399,#120086); +#120086 = DEFINITIONAL_REPRESENTATION('',(#120087),#120091); +#120087 = LINE('',#120088,#120089); +#120088 = CARTESIAN_POINT('',(0.E+000,0.2)); +#120089 = VECTOR('',#120090,1.); +#120090 = DIRECTION('',(1.,-4.804757279354E-063)); +#120091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120092 = ORIENTED_EDGE('',*,*,#93357,.F.); +#120093 = ADVANCED_FACE('',(#120094),#93399,.T.); +#120094 = FACE_BOUND('',#120095,.T.); +#120095 = EDGE_LOOP('',(#120096,#120097,#120098,#120119)); +#120096 = ORIENTED_EDGE('',*,*,#120072,.F.); +#120097 = ORIENTED_EDGE('',*,*,#119825,.T.); +#120098 = ORIENTED_EDGE('',*,*,#120099,.T.); +#120099 = EDGE_CURVE('',#119803,#93300,#120100,.T.); +#120100 = SURFACE_CURVE('',#120101,(#120105,#120112),.PCURVE_S1.); +#120101 = LINE('',#120102,#120103); +#120102 = CARTESIAN_POINT('',(-0.527847992439,6.15,0.75)); +#120103 = VECTOR('',#120104,1.); +#120104 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120105 = PCURVE('',#93399,#120106); +#120106 = DEFINITIONAL_REPRESENTATION('',(#120107),#120111); +#120107 = LINE('',#120108,#120109); +#120108 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120109 = VECTOR('',#120110,1.); +#120110 = DIRECTION('',(1.,-4.804757279354E-063)); +#120111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120112 = PCURVE('',#93317,#120113); +#120113 = DEFINITIONAL_REPRESENTATION('',(#120114),#120118); +#120114 = LINE('',#120115,#120116); +#120115 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#120116 = VECTOR('',#120117,1.); +#120117 = DIRECTION('',(-3.563627120235E-016,1.)); +#120118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120119 = ORIENTED_EDGE('',*,*,#93385,.F.); +#120120 = ADVANCED_FACE('',(#120121),#93317,.T.); +#120121 = FACE_BOUND('',#120122,.T.); +#120122 = EDGE_LOOP('',(#120123,#120124,#120125,#120126,#120127,#120128, + #120149,#120150,#120151,#120152,#120153,#120154)); +#120123 = ORIENTED_EDGE('',*,*,#120099,.F.); +#120124 = ORIENTED_EDGE('',*,*,#119802,.T.); +#120125 = ORIENTED_EDGE('',*,*,#119777,.T.); +#120126 = ORIENTED_EDGE('',*,*,#119543,.T.); +#120127 = ORIENTED_EDGE('',*,*,#119315,.T.); +#120128 = ORIENTED_EDGE('',*,*,#120129,.F.); +#120129 = EDGE_CURVE('',#119392,#119281,#120130,.T.); +#120130 = SURFACE_CURVE('',#120131,(#120135,#120142),.PCURVE_S1.); +#120131 = LINE('',#120132,#120133); +#120132 = CARTESIAN_POINT('',(-1.,6.15,1.159810404338E-002)); +#120133 = VECTOR('',#120134,1.); +#120134 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#120135 = PCURVE('',#93317,#120136); +#120136 = DEFINITIONAL_REPRESENTATION('',(#120137),#120141); +#120137 = LINE('',#120138,#120139); +#120138 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#120139 = VECTOR('',#120140,1.); +#120140 = DIRECTION('',(-1.,-2.101748079665E-016)); +#120141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120142 = PCURVE('',#119303,#120143); +#120143 = DEFINITIONAL_REPRESENTATION('',(#120144),#120148); +#120144 = LINE('',#120145,#120146); +#120145 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#120146 = VECTOR('',#120147,1.); +#120147 = DIRECTION('',(-1.194699204908E-017,1.)); +#120148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#117796 = PCURVE('',#117797,#117802); -#117797 = PLANE('',#117798); -#117798 = AXIS2_PLACEMENT_3D('',#117799,#117800,#117801); -#117799 = CARTESIAN_POINT('',(-1.,6.75,-0.258196742327)); -#117800 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#117801 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117802 = DEFINITIONAL_REPRESENTATION('',(#117803),#117807); -#117803 = LINE('',#117804,#117805); -#117804 = CARTESIAN_POINT('',(-3.25,5.000038352949E-002)); -#117805 = VECTOR('',#117806,1.); -#117806 = DIRECTION('',(-1.,0.E+000)); -#117807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117808 = ORIENTED_EDGE('',*,*,#117809,.F.); -#117809 = EDGE_CURVE('',#117810,#117775,#117812,.T.); -#117810 = VERTEX_POINT('',#117811); -#117811 = CARTESIAN_POINT('',(-0.740726081328,6.65,-0.208196358798)); -#117812 = SURFACE_CURVE('',#117813,(#117817,#117824),.PCURVE_S1.); -#117813 = LINE('',#117814,#117815); -#117814 = CARTESIAN_POINT('',(-0.740726081328,6.65,-0.208196358798)); -#117815 = VECTOR('',#117816,1.); -#117816 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117817 = PCURVE('',#117785,#117818); -#117818 = DEFINITIONAL_REPRESENTATION('',(#117819),#117823); -#117819 = LINE('',#117820,#117821); -#117820 = CARTESIAN_POINT('',(-1.554312234475E-015,-3.35)); -#117821 = VECTOR('',#117822,1.); -#117822 = DIRECTION('',(1.,0.E+000)); -#117823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117824 = PCURVE('',#90811,#117825); -#117825 = DEFINITIONAL_REPRESENTATION('',(#117826),#117830); -#117826 = LINE('',#117827,#117828); -#117827 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#117828 = VECTOR('',#117829,1.); -#117829 = DIRECTION('',(0.E+000,-1.)); -#117830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117831 = ORIENTED_EDGE('',*,*,#117832,.F.); -#117832 = EDGE_CURVE('',#117833,#117810,#117835,.T.); -#117833 = VERTEX_POINT('',#117834); -#117834 = CARTESIAN_POINT('',(-0.740726081328,6.85,-0.208196358798)); -#117835 = SURFACE_CURVE('',#117836,(#117840,#117847),.PCURVE_S1.); -#117836 = LINE('',#117837,#117838); -#117837 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#117838 = VECTOR('',#117839,1.); -#117839 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117840 = PCURVE('',#117785,#117841); -#117841 = DEFINITIONAL_REPRESENTATION('',(#117842),#117846); -#117842 = LINE('',#117843,#117844); -#117843 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117844 = VECTOR('',#117845,1.); -#117845 = DIRECTION('',(-4.440892098501E-016,-1.)); -#117846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117847 = PCURVE('',#117848,#117853); -#117848 = CYLINDRICAL_SURFACE('',#117849,0.208574704164); -#117849 = AXIS2_PLACEMENT_3D('',#117850,#117851,#117852); -#117850 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#117851 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117852 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117853 = DEFINITIONAL_REPRESENTATION('',(#117854),#117857); -#117854 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117855,#117856), +#120149 = ORIENTED_EDGE('',*,*,#119469,.F.); +#120150 = ORIENTED_EDGE('',*,*,#119572,.F.); +#120151 = ORIENTED_EDGE('',*,*,#119680,.F.); +#120152 = ORIENTED_EDGE('',*,*,#119899,.F.); +#120153 = ORIENTED_EDGE('',*,*,#119995,.T.); +#120154 = ORIENTED_EDGE('',*,*,#93299,.F.); +#120155 = ADVANCED_FACE('',(#120156),#119303,.T.); +#120156 = FACE_BOUND('',#120157,.T.); +#120157 = EDGE_LOOP('',(#120158,#120159,#120160,#120161)); +#120158 = ORIENTED_EDGE('',*,*,#120047,.T.); +#120159 = ORIENTED_EDGE('',*,*,#119389,.T.); +#120160 = ORIENTED_EDGE('',*,*,#120129,.T.); +#120161 = ORIENTED_EDGE('',*,*,#119280,.T.); +#120162 = ADVANCED_FACE('',(#120163),#120177,.F.); +#120163 = FACE_BOUND('',#120164,.T.); +#120164 = EDGE_LOOP('',(#120165,#120200,#120223,#120250)); +#120165 = ORIENTED_EDGE('',*,*,#120166,.F.); +#120166 = EDGE_CURVE('',#120167,#120169,#120171,.T.); +#120167 = VERTEX_POINT('',#120168); +#120168 = CARTESIAN_POINT('',(-1.,6.65,-0.208196358798)); +#120169 = VERTEX_POINT('',#120170); +#120170 = CARTESIAN_POINT('',(-1.,6.85,-0.208196358798)); +#120171 = SURFACE_CURVE('',#120172,(#120176,#120188),.PCURVE_S1.); +#120172 = LINE('',#120173,#120174); +#120173 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#120174 = VECTOR('',#120175,1.); +#120175 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120176 = PCURVE('',#120177,#120182); +#120177 = PLANE('',#120178); +#120178 = AXIS2_PLACEMENT_3D('',#120179,#120180,#120181); +#120179 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#120180 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#120181 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#120182 = DEFINITIONAL_REPRESENTATION('',(#120183),#120187); +#120183 = LINE('',#120184,#120185); +#120184 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#120185 = VECTOR('',#120186,1.); +#120186 = DIRECTION('',(4.440892098501E-016,1.)); +#120187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120188 = PCURVE('',#120189,#120194); +#120189 = PLANE('',#120190); +#120190 = AXIS2_PLACEMENT_3D('',#120191,#120192,#120193); +#120191 = CARTESIAN_POINT('',(-1.,6.75,-0.258196742327)); +#120192 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#120193 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120194 = DEFINITIONAL_REPRESENTATION('',(#120195),#120199); +#120195 = LINE('',#120196,#120197); +#120196 = CARTESIAN_POINT('',(-3.25,5.000038352949E-002)); +#120197 = VECTOR('',#120198,1.); +#120198 = DIRECTION('',(-1.,0.E+000)); +#120199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120200 = ORIENTED_EDGE('',*,*,#120201,.F.); +#120201 = EDGE_CURVE('',#120202,#120167,#120204,.T.); +#120202 = VERTEX_POINT('',#120203); +#120203 = CARTESIAN_POINT('',(-0.740726081328,6.65,-0.208196358798)); +#120204 = SURFACE_CURVE('',#120205,(#120209,#120216),.PCURVE_S1.); +#120205 = LINE('',#120206,#120207); +#120206 = CARTESIAN_POINT('',(-0.740726081328,6.65,-0.208196358798)); +#120207 = VECTOR('',#120208,1.); +#120208 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#120209 = PCURVE('',#120177,#120210); +#120210 = DEFINITIONAL_REPRESENTATION('',(#120211),#120215); +#120211 = LINE('',#120212,#120213); +#120212 = CARTESIAN_POINT('',(-1.554312234475E-015,-3.35)); +#120213 = VECTOR('',#120214,1.); +#120214 = DIRECTION('',(1.,0.E+000)); +#120215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120216 = PCURVE('',#93203,#120217); +#120217 = DEFINITIONAL_REPRESENTATION('',(#120218),#120222); +#120218 = LINE('',#120219,#120220); +#120219 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#120220 = VECTOR('',#120221,1.); +#120221 = DIRECTION('',(0.E+000,-1.)); +#120222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120223 = ORIENTED_EDGE('',*,*,#120224,.F.); +#120224 = EDGE_CURVE('',#120225,#120202,#120227,.T.); +#120225 = VERTEX_POINT('',#120226); +#120226 = CARTESIAN_POINT('',(-0.740726081328,6.85,-0.208196358798)); +#120227 = SURFACE_CURVE('',#120228,(#120232,#120239),.PCURVE_S1.); +#120228 = LINE('',#120229,#120230); +#120229 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#120230 = VECTOR('',#120231,1.); +#120231 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120232 = PCURVE('',#120177,#120233); +#120233 = DEFINITIONAL_REPRESENTATION('',(#120234),#120238); +#120234 = LINE('',#120235,#120236); +#120235 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120236 = VECTOR('',#120237,1.); +#120237 = DIRECTION('',(-4.440892098501E-016,-1.)); +#120238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120239 = PCURVE('',#120240,#120245); +#120240 = CYLINDRICAL_SURFACE('',#120241,0.208574704164); +#120241 = AXIS2_PLACEMENT_3D('',#120242,#120243,#120244); +#120242 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#120243 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120244 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120245 = DEFINITIONAL_REPRESENTATION('',(#120246),#120249); +#120246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120247,#120248), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#117855 = CARTESIAN_POINT('',(4.772630242227,-3.15)); -#117856 = CARTESIAN_POINT('',(4.772630242227,-3.35)); -#117857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117858 = ORIENTED_EDGE('',*,*,#117859,.T.); -#117859 = EDGE_CURVE('',#117833,#117777,#117860,.T.); -#117860 = SURFACE_CURVE('',#117861,(#117865,#117872),.PCURVE_S1.); -#117861 = LINE('',#117862,#117863); -#117862 = CARTESIAN_POINT('',(-0.740726081328,6.85,-0.208196358798)); -#117863 = VECTOR('',#117864,1.); -#117864 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117865 = PCURVE('',#117785,#117866); -#117866 = DEFINITIONAL_REPRESENTATION('',(#117867),#117871); -#117867 = LINE('',#117868,#117869); -#117868 = CARTESIAN_POINT('',(-1.33226762955E-015,-3.15)); -#117869 = VECTOR('',#117870,1.); -#117870 = DIRECTION('',(1.,0.E+000)); -#117871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117872 = PCURVE('',#90867,#117873); -#117873 = DEFINITIONAL_REPRESENTATION('',(#117874),#117878); -#117874 = LINE('',#117875,#117876); -#117875 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#117876 = VECTOR('',#117877,1.); -#117877 = DIRECTION('',(0.E+000,-1.)); -#117878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117879 = ADVANCED_FACE('',(#117880),#117894,.F.); -#117880 = FACE_BOUND('',#117881,.T.); -#117881 = EDGE_LOOP('',(#117882,#117912,#117935,#117962)); -#117882 = ORIENTED_EDGE('',*,*,#117883,.F.); -#117883 = EDGE_CURVE('',#117884,#117886,#117888,.T.); -#117884 = VERTEX_POINT('',#117885); -#117885 = CARTESIAN_POINT('',(-1.,6.85,-0.308197125857)); -#117886 = VERTEX_POINT('',#117887); -#117887 = CARTESIAN_POINT('',(-1.,6.65,-0.308197125857)); -#117888 = SURFACE_CURVE('',#117889,(#117893,#117905),.PCURVE_S1.); -#117889 = LINE('',#117890,#117891); -#117890 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#117891 = VECTOR('',#117892,1.); -#117892 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#117893 = PCURVE('',#117894,#117899); -#117894 = PLANE('',#117895); -#117895 = AXIS2_PLACEMENT_3D('',#117896,#117897,#117898); -#117896 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#117897 = DIRECTION('',(0.E+000,0.E+000,1.)); -#117898 = DIRECTION('',(1.,0.E+000,0.E+000)); -#117899 = DEFINITIONAL_REPRESENTATION('',(#117900),#117904); -#117900 = LINE('',#117901,#117902); -#117901 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#117902 = VECTOR('',#117903,1.); -#117903 = DIRECTION('',(4.440892098501E-016,-1.)); -#117904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117905 = PCURVE('',#117797,#117906); -#117906 = DEFINITIONAL_REPRESENTATION('',(#117907),#117911); -#117907 = LINE('',#117908,#117909); -#117908 = CARTESIAN_POINT('',(-3.25,-5.000038352949E-002)); -#117909 = VECTOR('',#117910,1.); -#117910 = DIRECTION('',(1.,0.E+000)); -#117911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117912 = ORIENTED_EDGE('',*,*,#117913,.F.); -#117913 = EDGE_CURVE('',#117914,#117884,#117916,.T.); -#117914 = VERTEX_POINT('',#117915); -#117915 = CARTESIAN_POINT('',(-0.74341632541,6.85,-0.308197125857)); -#117916 = SURFACE_CURVE('',#117917,(#117921,#117928),.PCURVE_S1.); -#117917 = LINE('',#117918,#117919); -#117918 = CARTESIAN_POINT('',(-0.74341632541,6.85,-0.308197125857)); -#117919 = VECTOR('',#117920,1.); -#117920 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117921 = PCURVE('',#117894,#117922); -#117922 = DEFINITIONAL_REPRESENTATION('',(#117923),#117927); -#117923 = LINE('',#117924,#117925); -#117924 = CARTESIAN_POINT('',(1.33226762955E-015,-3.15)); -#117925 = VECTOR('',#117926,1.); -#117926 = DIRECTION('',(-1.,0.E+000)); -#117927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117928 = PCURVE('',#90867,#117929); -#117929 = DEFINITIONAL_REPRESENTATION('',(#117930),#117934); -#117930 = LINE('',#117931,#117932); -#117931 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#117932 = VECTOR('',#117933,1.); -#117933 = DIRECTION('',(0.E+000,-1.)); -#117934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117935 = ORIENTED_EDGE('',*,*,#117936,.F.); -#117936 = EDGE_CURVE('',#117937,#117914,#117939,.T.); -#117937 = VERTEX_POINT('',#117938); -#117938 = CARTESIAN_POINT('',(-0.74341632541,6.65,-0.308197125857)); -#117939 = SURFACE_CURVE('',#117940,(#117944,#117951),.PCURVE_S1.); -#117940 = LINE('',#117941,#117942); -#117941 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#117942 = VECTOR('',#117943,1.); -#117943 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117944 = PCURVE('',#117894,#117945); -#117945 = DEFINITIONAL_REPRESENTATION('',(#117946),#117950); -#117946 = LINE('',#117947,#117948); -#117947 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#117948 = VECTOR('',#117949,1.); -#117949 = DIRECTION('',(-4.440892098501E-016,1.)); -#117950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117951 = PCURVE('',#117952,#117957); -#117952 = CYLINDRICAL_SURFACE('',#117953,0.308574064194); -#117953 = AXIS2_PLACEMENT_3D('',#117954,#117955,#117956); -#117954 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#117955 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117956 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117957 = DEFINITIONAL_REPRESENTATION('',(#117958),#117961); -#117958 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117959,#117960), +#120247 = CARTESIAN_POINT('',(4.772630242227,-3.15)); +#120248 = CARTESIAN_POINT('',(4.772630242227,-3.35)); +#120249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120250 = ORIENTED_EDGE('',*,*,#120251,.T.); +#120251 = EDGE_CURVE('',#120225,#120169,#120252,.T.); +#120252 = SURFACE_CURVE('',#120253,(#120257,#120264),.PCURVE_S1.); +#120253 = LINE('',#120254,#120255); +#120254 = CARTESIAN_POINT('',(-0.740726081328,6.85,-0.208196358798)); +#120255 = VECTOR('',#120256,1.); +#120256 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#120257 = PCURVE('',#120177,#120258); +#120258 = DEFINITIONAL_REPRESENTATION('',(#120259),#120263); +#120259 = LINE('',#120260,#120261); +#120260 = CARTESIAN_POINT('',(-1.33226762955E-015,-3.15)); +#120261 = VECTOR('',#120262,1.); +#120262 = DIRECTION('',(1.,0.E+000)); +#120263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120264 = PCURVE('',#93259,#120265); +#120265 = DEFINITIONAL_REPRESENTATION('',(#120266),#120270); +#120266 = LINE('',#120267,#120268); +#120267 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#120268 = VECTOR('',#120269,1.); +#120269 = DIRECTION('',(0.E+000,-1.)); +#120270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120271 = ADVANCED_FACE('',(#120272),#120286,.F.); +#120272 = FACE_BOUND('',#120273,.T.); +#120273 = EDGE_LOOP('',(#120274,#120304,#120327,#120354)); +#120274 = ORIENTED_EDGE('',*,*,#120275,.F.); +#120275 = EDGE_CURVE('',#120276,#120278,#120280,.T.); +#120276 = VERTEX_POINT('',#120277); +#120277 = CARTESIAN_POINT('',(-1.,6.85,-0.308197125857)); +#120278 = VERTEX_POINT('',#120279); +#120279 = CARTESIAN_POINT('',(-1.,6.65,-0.308197125857)); +#120280 = SURFACE_CURVE('',#120281,(#120285,#120297),.PCURVE_S1.); +#120281 = LINE('',#120282,#120283); +#120282 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#120283 = VECTOR('',#120284,1.); +#120284 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120285 = PCURVE('',#120286,#120291); +#120286 = PLANE('',#120287); +#120287 = AXIS2_PLACEMENT_3D('',#120288,#120289,#120290); +#120288 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#120289 = DIRECTION('',(0.E+000,0.E+000,1.)); +#120290 = DIRECTION('',(1.,0.E+000,0.E+000)); +#120291 = DEFINITIONAL_REPRESENTATION('',(#120292),#120296); +#120292 = LINE('',#120293,#120294); +#120293 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#120294 = VECTOR('',#120295,1.); +#120295 = DIRECTION('',(4.440892098501E-016,-1.)); +#120296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120297 = PCURVE('',#120189,#120298); +#120298 = DEFINITIONAL_REPRESENTATION('',(#120299),#120303); +#120299 = LINE('',#120300,#120301); +#120300 = CARTESIAN_POINT('',(-3.25,-5.000038352949E-002)); +#120301 = VECTOR('',#120302,1.); +#120302 = DIRECTION('',(1.,0.E+000)); +#120303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120304 = ORIENTED_EDGE('',*,*,#120305,.F.); +#120305 = EDGE_CURVE('',#120306,#120276,#120308,.T.); +#120306 = VERTEX_POINT('',#120307); +#120307 = CARTESIAN_POINT('',(-0.74341632541,6.85,-0.308197125857)); +#120308 = SURFACE_CURVE('',#120309,(#120313,#120320),.PCURVE_S1.); +#120309 = LINE('',#120310,#120311); +#120310 = CARTESIAN_POINT('',(-0.74341632541,6.85,-0.308197125857)); +#120311 = VECTOR('',#120312,1.); +#120312 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#120313 = PCURVE('',#120286,#120314); +#120314 = DEFINITIONAL_REPRESENTATION('',(#120315),#120319); +#120315 = LINE('',#120316,#120317); +#120316 = CARTESIAN_POINT('',(1.33226762955E-015,-3.15)); +#120317 = VECTOR('',#120318,1.); +#120318 = DIRECTION('',(-1.,0.E+000)); +#120319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120320 = PCURVE('',#93259,#120321); +#120321 = DEFINITIONAL_REPRESENTATION('',(#120322),#120326); +#120322 = LINE('',#120323,#120324); +#120323 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#120324 = VECTOR('',#120325,1.); +#120325 = DIRECTION('',(0.E+000,-1.)); +#120326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120327 = ORIENTED_EDGE('',*,*,#120328,.F.); +#120328 = EDGE_CURVE('',#120329,#120306,#120331,.T.); +#120329 = VERTEX_POINT('',#120330); +#120330 = CARTESIAN_POINT('',(-0.74341632541,6.65,-0.308197125857)); +#120331 = SURFACE_CURVE('',#120332,(#120336,#120343),.PCURVE_S1.); +#120332 = LINE('',#120333,#120334); +#120333 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#120334 = VECTOR('',#120335,1.); +#120335 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120336 = PCURVE('',#120286,#120337); +#120337 = DEFINITIONAL_REPRESENTATION('',(#120338),#120342); +#120338 = LINE('',#120339,#120340); +#120339 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120340 = VECTOR('',#120341,1.); +#120341 = DIRECTION('',(-4.440892098501E-016,1.)); +#120342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120343 = PCURVE('',#120344,#120349); +#120344 = CYLINDRICAL_SURFACE('',#120345,0.308574064194); +#120345 = AXIS2_PLACEMENT_3D('',#120346,#120347,#120348); +#120346 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#120347 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120348 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120349 = DEFINITIONAL_REPRESENTATION('',(#120350),#120353); +#120350 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120351,#120352), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#117959 = CARTESIAN_POINT('',(4.761821717947,-3.35)); -#117960 = CARTESIAN_POINT('',(4.761821717947,-3.15)); -#117961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117962 = ORIENTED_EDGE('',*,*,#117963,.T.); -#117963 = EDGE_CURVE('',#117937,#117886,#117964,.T.); -#117964 = SURFACE_CURVE('',#117965,(#117969,#117976),.PCURVE_S1.); -#117965 = LINE('',#117966,#117967); -#117966 = CARTESIAN_POINT('',(-0.74341632541,6.65,-0.308197125857)); -#117967 = VECTOR('',#117968,1.); -#117968 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#117969 = PCURVE('',#117894,#117970); -#117970 = DEFINITIONAL_REPRESENTATION('',(#117971),#117975); -#117971 = LINE('',#117972,#117973); -#117972 = CARTESIAN_POINT('',(1.554312234475E-015,-3.35)); -#117973 = VECTOR('',#117974,1.); -#117974 = DIRECTION('',(-1.,0.E+000)); -#117975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117976 = PCURVE('',#90811,#117977); -#117977 = DEFINITIONAL_REPRESENTATION('',(#117978),#117982); -#117978 = LINE('',#117979,#117980); -#117979 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#117980 = VECTOR('',#117981,1.); -#117981 = DIRECTION('',(0.E+000,-1.)); -#117982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#117983 = ADVANCED_FACE('',(#117984),#117848,.F.); -#117984 = FACE_BOUND('',#117985,.F.); -#117985 = EDGE_LOOP('',(#117986,#118009,#118036,#118061)); -#117986 = ORIENTED_EDGE('',*,*,#117987,.F.); -#117987 = EDGE_CURVE('',#117988,#117833,#117990,.T.); -#117988 = VERTEX_POINT('',#117989); -#117989 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.E+000)); -#117990 = SURFACE_CURVE('',#117991,(#117996,#118002),.PCURVE_S1.); -#117991 = CIRCLE('',#117992,0.208574704164); -#117992 = AXIS2_PLACEMENT_3D('',#117993,#117994,#117995); -#117993 = CARTESIAN_POINT('',(-0.728168876214,6.85,2.640924866458E-017) - ); -#117994 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#117995 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#117996 = PCURVE('',#117848,#117997); -#117997 = DEFINITIONAL_REPRESENTATION('',(#117998),#118001); -#117998 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#117999,#118000), +#120351 = CARTESIAN_POINT('',(4.761821717947,-3.35)); +#120352 = CARTESIAN_POINT('',(4.761821717947,-3.15)); +#120353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120354 = ORIENTED_EDGE('',*,*,#120355,.T.); +#120355 = EDGE_CURVE('',#120329,#120278,#120356,.T.); +#120356 = SURFACE_CURVE('',#120357,(#120361,#120368),.PCURVE_S1.); +#120357 = LINE('',#120358,#120359); +#120358 = CARTESIAN_POINT('',(-0.74341632541,6.65,-0.308197125857)); +#120359 = VECTOR('',#120360,1.); +#120360 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#120361 = PCURVE('',#120286,#120362); +#120362 = DEFINITIONAL_REPRESENTATION('',(#120363),#120367); +#120363 = LINE('',#120364,#120365); +#120364 = CARTESIAN_POINT('',(1.554312234475E-015,-3.35)); +#120365 = VECTOR('',#120366,1.); +#120366 = DIRECTION('',(-1.,0.E+000)); +#120367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120368 = PCURVE('',#93203,#120369); +#120369 = DEFINITIONAL_REPRESENTATION('',(#120370),#120374); +#120370 = LINE('',#120371,#120372); +#120371 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#120372 = VECTOR('',#120373,1.); +#120373 = DIRECTION('',(0.E+000,-1.)); +#120374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120375 = ADVANCED_FACE('',(#120376),#120240,.F.); +#120376 = FACE_BOUND('',#120377,.F.); +#120377 = EDGE_LOOP('',(#120378,#120401,#120428,#120453)); +#120378 = ORIENTED_EDGE('',*,*,#120379,.F.); +#120379 = EDGE_CURVE('',#120380,#120225,#120382,.T.); +#120380 = VERTEX_POINT('',#120381); +#120381 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.E+000)); +#120382 = SURFACE_CURVE('',#120383,(#120388,#120394),.PCURVE_S1.); +#120383 = CIRCLE('',#120384,0.208574704164); +#120384 = AXIS2_PLACEMENT_3D('',#120385,#120386,#120387); +#120385 = CARTESIAN_POINT('',(-0.728168876214,6.85,2.640924866458E-017) + ); +#120386 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120387 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120388 = PCURVE('',#120240,#120389); +#120389 = DEFINITIONAL_REPRESENTATION('',(#120390),#120393); +#120390 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120391,#120392), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#117999 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#118000 = CARTESIAN_POINT('',(4.772630242227,-3.15)); -#118001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118002 = PCURVE('',#90867,#118003); -#118003 = DEFINITIONAL_REPRESENTATION('',(#118004),#118008); -#118004 = CIRCLE('',#118005,0.208574704164); -#118005 = AXIS2_PLACEMENT_2D('',#118006,#118007); -#118006 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#118007 = DIRECTION('',(0.E+000,-1.)); -#118008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118009 = ORIENTED_EDGE('',*,*,#118010,.F.); -#118010 = EDGE_CURVE('',#118011,#117988,#118013,.T.); -#118011 = VERTEX_POINT('',#118012); -#118012 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.E+000)); -#118013 = SURFACE_CURVE('',#118014,(#118018,#118024),.PCURVE_S1.); -#118014 = LINE('',#118015,#118016); -#118015 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#118016 = VECTOR('',#118017,1.); -#118017 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118018 = PCURVE('',#117848,#118019); -#118019 = DEFINITIONAL_REPRESENTATION('',(#118020),#118023); -#118020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118021,#118022), +#120391 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#120392 = CARTESIAN_POINT('',(4.772630242227,-3.15)); +#120393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120394 = PCURVE('',#93259,#120395); +#120395 = DEFINITIONAL_REPRESENTATION('',(#120396),#120400); +#120396 = CIRCLE('',#120397,0.208574704164); +#120397 = AXIS2_PLACEMENT_2D('',#120398,#120399); +#120398 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#120399 = DIRECTION('',(0.E+000,-1.)); +#120400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120401 = ORIENTED_EDGE('',*,*,#120402,.F.); +#120402 = EDGE_CURVE('',#120403,#120380,#120405,.T.); +#120403 = VERTEX_POINT('',#120404); +#120404 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.E+000)); +#120405 = SURFACE_CURVE('',#120406,(#120410,#120416),.PCURVE_S1.); +#120406 = LINE('',#120407,#120408); +#120407 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#120408 = VECTOR('',#120409,1.); +#120409 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120410 = PCURVE('',#120240,#120411); +#120411 = DEFINITIONAL_REPRESENTATION('',(#120412),#120415); +#120412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120413,#120414), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#118021 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#118022 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#118023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118024 = PCURVE('',#118025,#118030); -#118025 = PLANE('',#118026); -#118026 = AXIS2_PLACEMENT_3D('',#118027,#118028,#118029); -#118027 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#118028 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#118029 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118030 = DEFINITIONAL_REPRESENTATION('',(#118031),#118035); -#118031 = LINE('',#118032,#118033); -#118032 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#118033 = VECTOR('',#118034,1.); -#118034 = DIRECTION('',(-1.,0.E+000)); -#118035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118036 = ORIENTED_EDGE('',*,*,#118037,.T.); -#118037 = EDGE_CURVE('',#118011,#117810,#118038,.T.); -#118038 = SURFACE_CURVE('',#118039,(#118044,#118050),.PCURVE_S1.); -#118039 = CIRCLE('',#118040,0.208574704164); -#118040 = AXIS2_PLACEMENT_3D('',#118041,#118042,#118043); -#118041 = CARTESIAN_POINT('',(-0.728168876214,6.65,2.640924866458E-017) - ); -#118042 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118043 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118044 = PCURVE('',#117848,#118045); -#118045 = DEFINITIONAL_REPRESENTATION('',(#118046),#118049); -#118046 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118047,#118048), +#120413 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#120414 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#120415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120416 = PCURVE('',#120417,#120422); +#120417 = PLANE('',#120418); +#120418 = AXIS2_PLACEMENT_3D('',#120419,#120420,#120421); +#120419 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#120420 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#120421 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120422 = DEFINITIONAL_REPRESENTATION('',(#120423),#120427); +#120423 = LINE('',#120424,#120425); +#120424 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#120425 = VECTOR('',#120426,1.); +#120426 = DIRECTION('',(-1.,0.E+000)); +#120427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120428 = ORIENTED_EDGE('',*,*,#120429,.T.); +#120429 = EDGE_CURVE('',#120403,#120202,#120430,.T.); +#120430 = SURFACE_CURVE('',#120431,(#120436,#120442),.PCURVE_S1.); +#120431 = CIRCLE('',#120432,0.208574704164); +#120432 = AXIS2_PLACEMENT_3D('',#120433,#120434,#120435); +#120433 = CARTESIAN_POINT('',(-0.728168876214,6.65,2.640924866458E-017) + ); +#120434 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120435 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120436 = PCURVE('',#120240,#120437); +#120437 = DEFINITIONAL_REPRESENTATION('',(#120438),#120441); +#120438 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120439,#120440), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#118047 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#118048 = CARTESIAN_POINT('',(4.772630242227,-3.35)); -#118049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120439 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#120440 = CARTESIAN_POINT('',(4.772630242227,-3.35)); +#120441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118050 = PCURVE('',#90811,#118051); -#118051 = DEFINITIONAL_REPRESENTATION('',(#118052),#118060); -#118052 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118053,#118054,#118055, - #118056,#118057,#118058,#118059),.UNSPECIFIED.,.T.,.F.) +#120442 = PCURVE('',#93203,#120443); +#120443 = DEFINITIONAL_REPRESENTATION('',(#120444),#120452); +#120444 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120445,#120446,#120447, + #120448,#120449,#120450,#120451),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118053 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#118054 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#118055 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#118056 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#118057 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#118058 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#118059 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#118060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118061 = ORIENTED_EDGE('',*,*,#117832,.F.); -#118062 = ADVANCED_FACE('',(#118063),#117952,.T.); -#118063 = FACE_BOUND('',#118064,.T.); -#118064 = EDGE_LOOP('',(#118065,#118092,#118093,#118116)); -#118065 = ORIENTED_EDGE('',*,*,#118066,.T.); -#118066 = EDGE_CURVE('',#118067,#117937,#118069,.T.); -#118067 = VERTEX_POINT('',#118068); -#118068 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.E+000)); -#118069 = SURFACE_CURVE('',#118070,(#118075,#118081),.PCURVE_S1.); -#118070 = CIRCLE('',#118071,0.308574064194); -#118071 = AXIS2_PLACEMENT_3D('',#118072,#118073,#118074); -#118072 = CARTESIAN_POINT('',(-0.728168876214,6.65,2.640924866458E-017) - ); -#118073 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118074 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118075 = PCURVE('',#117952,#118076); -#118076 = DEFINITIONAL_REPRESENTATION('',(#118077),#118080); -#118077 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118078,#118079), +#120445 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#120446 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#120447 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#120448 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#120449 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#120450 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#120451 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#120452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120453 = ORIENTED_EDGE('',*,*,#120224,.F.); +#120454 = ADVANCED_FACE('',(#120455),#120344,.T.); +#120455 = FACE_BOUND('',#120456,.T.); +#120456 = EDGE_LOOP('',(#120457,#120484,#120485,#120508)); +#120457 = ORIENTED_EDGE('',*,*,#120458,.T.); +#120458 = EDGE_CURVE('',#120459,#120329,#120461,.T.); +#120459 = VERTEX_POINT('',#120460); +#120460 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.E+000)); +#120461 = SURFACE_CURVE('',#120462,(#120467,#120473),.PCURVE_S1.); +#120462 = CIRCLE('',#120463,0.308574064194); +#120463 = AXIS2_PLACEMENT_3D('',#120464,#120465,#120466); +#120464 = CARTESIAN_POINT('',(-0.728168876214,6.65,2.640924866458E-017) + ); +#120465 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120466 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120467 = PCURVE('',#120344,#120468); +#120468 = DEFINITIONAL_REPRESENTATION('',(#120469),#120472); +#120469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120470,#120471), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#118078 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#118079 = CARTESIAN_POINT('',(4.761821717947,-3.35)); -#118080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120470 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#120471 = CARTESIAN_POINT('',(4.761821717947,-3.35)); +#120472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118081 = PCURVE('',#90811,#118082); -#118082 = DEFINITIONAL_REPRESENTATION('',(#118083),#118091); -#118083 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118084,#118085,#118086, - #118087,#118088,#118089,#118090),.UNSPECIFIED.,.T.,.F.) +#120473 = PCURVE('',#93203,#120474); +#120474 = DEFINITIONAL_REPRESENTATION('',(#120475),#120483); +#120475 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120476,#120477,#120478, + #120479,#120480,#120481,#120482),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118084 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#118085 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#118086 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#118087 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#118088 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#118089 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#118090 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#118091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118092 = ORIENTED_EDGE('',*,*,#117936,.T.); -#118093 = ORIENTED_EDGE('',*,*,#118094,.F.); -#118094 = EDGE_CURVE('',#118095,#117914,#118097,.T.); -#118095 = VERTEX_POINT('',#118096); -#118096 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.E+000)); -#118097 = SURFACE_CURVE('',#118098,(#118103,#118109),.PCURVE_S1.); -#118098 = CIRCLE('',#118099,0.308574064194); -#118099 = AXIS2_PLACEMENT_3D('',#118100,#118101,#118102); -#118100 = CARTESIAN_POINT('',(-0.728168876214,6.85,2.640924866458E-017) - ); -#118101 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118102 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118103 = PCURVE('',#117952,#118104); -#118104 = DEFINITIONAL_REPRESENTATION('',(#118105),#118108); -#118105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118106,#118107), +#120476 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#120477 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#120478 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#120479 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#120480 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#120481 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#120482 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#120483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120484 = ORIENTED_EDGE('',*,*,#120328,.T.); +#120485 = ORIENTED_EDGE('',*,*,#120486,.F.); +#120486 = EDGE_CURVE('',#120487,#120306,#120489,.T.); +#120487 = VERTEX_POINT('',#120488); +#120488 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.E+000)); +#120489 = SURFACE_CURVE('',#120490,(#120495,#120501),.PCURVE_S1.); +#120490 = CIRCLE('',#120491,0.308574064194); +#120491 = AXIS2_PLACEMENT_3D('',#120492,#120493,#120494); +#120492 = CARTESIAN_POINT('',(-0.728168876214,6.85,2.640924866458E-017) + ); +#120493 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120494 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#120495 = PCURVE('',#120344,#120496); +#120496 = DEFINITIONAL_REPRESENTATION('',(#120497),#120500); +#120497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120498,#120499), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#118106 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#118107 = CARTESIAN_POINT('',(4.761821717947,-3.15)); -#118108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118109 = PCURVE('',#90867,#118110); -#118110 = DEFINITIONAL_REPRESENTATION('',(#118111),#118115); -#118111 = CIRCLE('',#118112,0.308574064194); -#118112 = AXIS2_PLACEMENT_2D('',#118113,#118114); -#118113 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#118114 = DIRECTION('',(0.E+000,-1.)); -#118115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118116 = ORIENTED_EDGE('',*,*,#118117,.T.); -#118117 = EDGE_CURVE('',#118095,#118067,#118118,.T.); -#118118 = SURFACE_CURVE('',#118119,(#118123,#118129),.PCURVE_S1.); -#118119 = LINE('',#118120,#118121); -#118120 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#118121 = VECTOR('',#118122,1.); -#118122 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118123 = PCURVE('',#117952,#118124); -#118124 = DEFINITIONAL_REPRESENTATION('',(#118125),#118128); -#118125 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118126,#118127), +#120498 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#120499 = CARTESIAN_POINT('',(4.761821717947,-3.15)); +#120500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120501 = PCURVE('',#93259,#120502); +#120502 = DEFINITIONAL_REPRESENTATION('',(#120503),#120507); +#120503 = CIRCLE('',#120504,0.308574064194); +#120504 = AXIS2_PLACEMENT_2D('',#120505,#120506); +#120505 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#120506 = DIRECTION('',(0.E+000,-1.)); +#120507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120508 = ORIENTED_EDGE('',*,*,#120509,.T.); +#120509 = EDGE_CURVE('',#120487,#120459,#120510,.T.); +#120510 = SURFACE_CURVE('',#120511,(#120515,#120521),.PCURVE_S1.); +#120511 = LINE('',#120512,#120513); +#120512 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#120513 = VECTOR('',#120514,1.); +#120514 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120515 = PCURVE('',#120344,#120516); +#120516 = DEFINITIONAL_REPRESENTATION('',(#120517),#120520); +#120517 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120518,#120519), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#118126 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#118127 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#118128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118129 = PCURVE('',#118130,#118135); -#118130 = PLANE('',#118131); -#118131 = AXIS2_PLACEMENT_3D('',#118132,#118133,#118134); -#118132 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#118133 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#118134 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118135 = DEFINITIONAL_REPRESENTATION('',(#118136),#118140); -#118136 = LINE('',#118137,#118138); -#118137 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#118138 = VECTOR('',#118139,1.); -#118139 = DIRECTION('',(-1.,0.E+000)); -#118140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118141 = ADVANCED_FACE('',(#118142),#118130,.T.); -#118142 = FACE_BOUND('',#118143,.T.); -#118143 = EDGE_LOOP('',(#118144,#118173,#118194,#118195)); -#118144 = ORIENTED_EDGE('',*,*,#118145,.T.); -#118145 = EDGE_CURVE('',#118146,#118148,#118150,.T.); -#118146 = VERTEX_POINT('',#118147); -#118147 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.530776333563)); -#118148 = VERTEX_POINT('',#118149); -#118149 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.530776333563)); -#118150 = SURFACE_CURVE('',#118151,(#118155,#118162),.PCURVE_S1.); -#118151 = LINE('',#118152,#118153); -#118152 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#118153 = VECTOR('',#118154,1.); -#118154 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118155 = PCURVE('',#118130,#118156); -#118156 = DEFINITIONAL_REPRESENTATION('',(#118157),#118161); -#118157 = LINE('',#118158,#118159); -#118158 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118159 = VECTOR('',#118160,1.); -#118160 = DIRECTION('',(-1.,0.E+000)); -#118161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118162 = PCURVE('',#118163,#118168); -#118163 = CYLINDRICAL_SURFACE('',#118164,0.119270391569); -#118164 = AXIS2_PLACEMENT_3D('',#118165,#118166,#118167); -#118165 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#118166 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118167 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118168 = DEFINITIONAL_REPRESENTATION('',(#118169),#118172); -#118169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118170,#118171), +#120518 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#120519 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#120520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120521 = PCURVE('',#120522,#120527); +#120522 = PLANE('',#120523); +#120523 = AXIS2_PLACEMENT_3D('',#120524,#120525,#120526); +#120524 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#120525 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#120526 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120527 = DEFINITIONAL_REPRESENTATION('',(#120528),#120532); +#120528 = LINE('',#120529,#120530); +#120529 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#120530 = VECTOR('',#120531,1.); +#120531 = DIRECTION('',(-1.,0.E+000)); +#120532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120533 = ADVANCED_FACE('',(#120534),#120522,.T.); +#120534 = FACE_BOUND('',#120535,.T.); +#120535 = EDGE_LOOP('',(#120536,#120565,#120586,#120587)); +#120536 = ORIENTED_EDGE('',*,*,#120537,.T.); +#120537 = EDGE_CURVE('',#120538,#120540,#120542,.T.); +#120538 = VERTEX_POINT('',#120539); +#120539 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.530776333563)); +#120540 = VERTEX_POINT('',#120541); +#120541 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.530776333563)); +#120542 = SURFACE_CURVE('',#120543,(#120547,#120554),.PCURVE_S1.); +#120543 = LINE('',#120544,#120545); +#120544 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#120545 = VECTOR('',#120546,1.); +#120546 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120547 = PCURVE('',#120522,#120548); +#120548 = DEFINITIONAL_REPRESENTATION('',(#120549),#120553); +#120549 = LINE('',#120550,#120551); +#120550 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120551 = VECTOR('',#120552,1.); +#120552 = DIRECTION('',(-1.,0.E+000)); +#120553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120554 = PCURVE('',#120555,#120560); +#120555 = CYLINDRICAL_SURFACE('',#120556,0.119270391569); +#120556 = AXIS2_PLACEMENT_3D('',#120557,#120558,#120559); +#120557 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#120558 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120559 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120560 = DEFINITIONAL_REPRESENTATION('',(#120561),#120564); +#120561 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120562,#120563), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#118170 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#118171 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#118172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118173 = ORIENTED_EDGE('',*,*,#118174,.T.); -#118174 = EDGE_CURVE('',#118148,#118067,#118175,.T.); -#118175 = SURFACE_CURVE('',#118176,(#118180,#118187),.PCURVE_S1.); -#118176 = LINE('',#118177,#118178); -#118177 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.530776333563)); -#118178 = VECTOR('',#118179,1.); -#118179 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#118180 = PCURVE('',#118130,#118181); -#118181 = DEFINITIONAL_REPRESENTATION('',(#118182),#118186); -#118182 = LINE('',#118183,#118184); -#118183 = CARTESIAN_POINT('',(-3.35,1.133910970711E-033)); -#118184 = VECTOR('',#118185,1.); -#118185 = DIRECTION('',(4.535643882845E-032,-1.)); -#118186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118187 = PCURVE('',#90811,#118188); -#118188 = DEFINITIONAL_REPRESENTATION('',(#118189),#118193); -#118189 = LINE('',#118190,#118191); -#118190 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#118191 = VECTOR('',#118192,1.); -#118192 = DIRECTION('',(1.,-1.021336205033E-016)); -#118193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120562 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#120563 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#120564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120565 = ORIENTED_EDGE('',*,*,#120566,.T.); +#120566 = EDGE_CURVE('',#120540,#120459,#120567,.T.); +#120567 = SURFACE_CURVE('',#120568,(#120572,#120579),.PCURVE_S1.); +#120568 = LINE('',#120569,#120570); +#120569 = CARTESIAN_POINT('',(-0.419594812019,6.65,0.530776333563)); +#120570 = VECTOR('',#120571,1.); +#120571 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#120572 = PCURVE('',#120522,#120573); +#120573 = DEFINITIONAL_REPRESENTATION('',(#120574),#120578); +#120574 = LINE('',#120575,#120576); +#120575 = CARTESIAN_POINT('',(-3.35,1.133910970711E-033)); +#120576 = VECTOR('',#120577,1.); +#120577 = DIRECTION('',(4.535643882845E-032,-1.)); +#120578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120579 = PCURVE('',#93203,#120580); +#120580 = DEFINITIONAL_REPRESENTATION('',(#120581),#120585); +#120581 = LINE('',#120582,#120583); +#120582 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#120583 = VECTOR('',#120584,1.); +#120584 = DIRECTION('',(1.,-1.021336205033E-016)); +#120585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118194 = ORIENTED_EDGE('',*,*,#118117,.F.); -#118195 = ORIENTED_EDGE('',*,*,#118196,.F.); -#118196 = EDGE_CURVE('',#118146,#118095,#118197,.T.); -#118197 = SURFACE_CURVE('',#118198,(#118202,#118209),.PCURVE_S1.); -#118198 = LINE('',#118199,#118200); -#118199 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.530776333563)); -#118200 = VECTOR('',#118201,1.); -#118201 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#118202 = PCURVE('',#118130,#118203); -#118203 = DEFINITIONAL_REPRESENTATION('',(#118204),#118208); -#118204 = LINE('',#118205,#118206); -#118205 = CARTESIAN_POINT('',(-3.15,-1.133910970711E-033)); -#118206 = VECTOR('',#118207,1.); -#118207 = DIRECTION('',(4.535643882845E-032,-1.)); -#118208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118209 = PCURVE('',#90867,#118210); -#118210 = DEFINITIONAL_REPRESENTATION('',(#118211),#118215); -#118211 = LINE('',#118212,#118213); -#118212 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#118213 = VECTOR('',#118214,1.); -#118214 = DIRECTION('',(-1.,-1.021336205033E-016)); -#118215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118216 = ADVANCED_FACE('',(#118217),#118025,.T.); -#118217 = FACE_BOUND('',#118218,.T.); -#118218 = EDGE_LOOP('',(#118219,#118248,#118269,#118270)); -#118219 = ORIENTED_EDGE('',*,*,#118220,.T.); -#118220 = EDGE_CURVE('',#118221,#118223,#118225,.T.); -#118221 = VERTEX_POINT('',#118222); -#118222 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.530776333563)); -#118223 = VERTEX_POINT('',#118224); -#118224 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.530776333563)); -#118225 = SURFACE_CURVE('',#118226,(#118230,#118237),.PCURVE_S1.); -#118226 = LINE('',#118227,#118228); -#118227 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#118228 = VECTOR('',#118229,1.); -#118229 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118230 = PCURVE('',#118025,#118231); -#118231 = DEFINITIONAL_REPRESENTATION('',(#118232),#118236); -#118232 = LINE('',#118233,#118234); -#118233 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118234 = VECTOR('',#118235,1.); -#118235 = DIRECTION('',(-1.,0.E+000)); -#118236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118237 = PCURVE('',#118238,#118243); -#118238 = CYLINDRICAL_SURFACE('',#118239,0.2192697516); -#118239 = AXIS2_PLACEMENT_3D('',#118240,#118241,#118242); -#118240 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#118241 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118242 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118243 = DEFINITIONAL_REPRESENTATION('',(#118244),#118247); -#118244 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118245,#118246), +#120586 = ORIENTED_EDGE('',*,*,#120509,.F.); +#120587 = ORIENTED_EDGE('',*,*,#120588,.F.); +#120588 = EDGE_CURVE('',#120538,#120487,#120589,.T.); +#120589 = SURFACE_CURVE('',#120590,(#120594,#120601),.PCURVE_S1.); +#120590 = LINE('',#120591,#120592); +#120591 = CARTESIAN_POINT('',(-0.419594812019,6.85,0.530776333563)); +#120592 = VECTOR('',#120593,1.); +#120593 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#120594 = PCURVE('',#120522,#120595); +#120595 = DEFINITIONAL_REPRESENTATION('',(#120596),#120600); +#120596 = LINE('',#120597,#120598); +#120597 = CARTESIAN_POINT('',(-3.15,-1.133910970711E-033)); +#120598 = VECTOR('',#120599,1.); +#120599 = DIRECTION('',(4.535643882845E-032,-1.)); +#120600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120601 = PCURVE('',#93259,#120602); +#120602 = DEFINITIONAL_REPRESENTATION('',(#120603),#120607); +#120603 = LINE('',#120604,#120605); +#120604 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#120605 = VECTOR('',#120606,1.); +#120606 = DIRECTION('',(-1.,-1.021336205033E-016)); +#120607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120608 = ADVANCED_FACE('',(#120609),#120417,.T.); +#120609 = FACE_BOUND('',#120610,.T.); +#120610 = EDGE_LOOP('',(#120611,#120640,#120661,#120662)); +#120611 = ORIENTED_EDGE('',*,*,#120612,.T.); +#120612 = EDGE_CURVE('',#120613,#120615,#120617,.T.); +#120613 = VERTEX_POINT('',#120614); +#120614 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.530776333563)); +#120615 = VERTEX_POINT('',#120616); +#120616 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.530776333563)); +#120617 = SURFACE_CURVE('',#120618,(#120622,#120629),.PCURVE_S1.); +#120618 = LINE('',#120619,#120620); +#120619 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#120620 = VECTOR('',#120621,1.); +#120621 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120622 = PCURVE('',#120417,#120623); +#120623 = DEFINITIONAL_REPRESENTATION('',(#120624),#120628); +#120624 = LINE('',#120625,#120626); +#120625 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120626 = VECTOR('',#120627,1.); +#120627 = DIRECTION('',(-1.,0.E+000)); +#120628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120629 = PCURVE('',#120630,#120635); +#120630 = CYLINDRICAL_SURFACE('',#120631,0.2192697516); +#120631 = AXIS2_PLACEMENT_3D('',#120632,#120633,#120634); +#120632 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#120633 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120634 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120635 = DEFINITIONAL_REPRESENTATION('',(#120636),#120639); +#120636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120637,#120638), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#118245 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#118246 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#118247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118248 = ORIENTED_EDGE('',*,*,#118249,.T.); -#118249 = EDGE_CURVE('',#118223,#117988,#118250,.T.); -#118250 = SURFACE_CURVE('',#118251,(#118255,#118262),.PCURVE_S1.); -#118251 = LINE('',#118252,#118253); -#118252 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.530776333563)); -#118253 = VECTOR('',#118254,1.); -#118254 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#118255 = PCURVE('',#118025,#118256); -#118256 = DEFINITIONAL_REPRESENTATION('',(#118257),#118261); -#118257 = LINE('',#118258,#118259); -#118258 = CARTESIAN_POINT('',(3.15,4.535643882845E-033)); -#118259 = VECTOR('',#118260,1.); -#118260 = DIRECTION('',(-4.535643882845E-032,-1.)); -#118261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118262 = PCURVE('',#90867,#118263); -#118263 = DEFINITIONAL_REPRESENTATION('',(#118264),#118268); -#118264 = LINE('',#118265,#118266); -#118265 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#118266 = VECTOR('',#118267,1.); -#118267 = DIRECTION('',(-1.,-1.021336205033E-016)); -#118268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118269 = ORIENTED_EDGE('',*,*,#118010,.F.); -#118270 = ORIENTED_EDGE('',*,*,#118271,.F.); -#118271 = EDGE_CURVE('',#118221,#118011,#118272,.T.); -#118272 = SURFACE_CURVE('',#118273,(#118277,#118284),.PCURVE_S1.); -#118273 = LINE('',#118274,#118275); -#118274 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.530776333563)); -#118275 = VECTOR('',#118276,1.); -#118276 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#118277 = PCURVE('',#118025,#118278); -#118278 = DEFINITIONAL_REPRESENTATION('',(#118279),#118283); -#118279 = LINE('',#118280,#118281); -#118280 = CARTESIAN_POINT('',(3.35,-4.535643882845E-033)); -#118281 = VECTOR('',#118282,1.); -#118282 = DIRECTION('',(-4.535643882845E-032,-1.)); -#118283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118284 = PCURVE('',#90811,#118285); -#118285 = DEFINITIONAL_REPRESENTATION('',(#118286),#118290); -#118286 = LINE('',#118287,#118288); -#118287 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#118288 = VECTOR('',#118289,1.); -#118289 = DIRECTION('',(1.,-1.021336205033E-016)); -#118290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118291 = ADVANCED_FACE('',(#118292),#118238,.T.); -#118292 = FACE_BOUND('',#118293,.T.); -#118293 = EDGE_LOOP('',(#118294,#118295,#118318,#118363)); -#118294 = ORIENTED_EDGE('',*,*,#118220,.F.); -#118295 = ORIENTED_EDGE('',*,*,#118296,.F.); -#118296 = EDGE_CURVE('',#118297,#118221,#118299,.T.); -#118297 = VERTEX_POINT('',#118298); -#118298 = CARTESIAN_POINT('',(-0.304819755875,6.65,0.75)); -#118299 = SURFACE_CURVE('',#118300,(#118305,#118311),.PCURVE_S1.); -#118300 = CIRCLE('',#118301,0.2192697516); -#118301 = AXIS2_PLACEMENT_3D('',#118302,#118303,#118304); -#118302 = CARTESIAN_POINT('',(-0.30032442045,6.65,0.530776333563)); -#118303 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118304 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118305 = PCURVE('',#118238,#118306); -#118306 = DEFINITIONAL_REPRESENTATION('',(#118307),#118310); -#118307 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118308,#118309), +#120637 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#120638 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#120639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120640 = ORIENTED_EDGE('',*,*,#120641,.T.); +#120641 = EDGE_CURVE('',#120615,#120380,#120642,.T.); +#120642 = SURFACE_CURVE('',#120643,(#120647,#120654),.PCURVE_S1.); +#120643 = LINE('',#120644,#120645); +#120644 = CARTESIAN_POINT('',(-0.51959417205,6.85,0.530776333563)); +#120645 = VECTOR('',#120646,1.); +#120646 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#120647 = PCURVE('',#120417,#120648); +#120648 = DEFINITIONAL_REPRESENTATION('',(#120649),#120653); +#120649 = LINE('',#120650,#120651); +#120650 = CARTESIAN_POINT('',(3.15,4.535643882845E-033)); +#120651 = VECTOR('',#120652,1.); +#120652 = DIRECTION('',(-4.535643882845E-032,-1.)); +#120653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120654 = PCURVE('',#93259,#120655); +#120655 = DEFINITIONAL_REPRESENTATION('',(#120656),#120660); +#120656 = LINE('',#120657,#120658); +#120657 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#120658 = VECTOR('',#120659,1.); +#120659 = DIRECTION('',(-1.,-1.021336205033E-016)); +#120660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120661 = ORIENTED_EDGE('',*,*,#120402,.F.); +#120662 = ORIENTED_EDGE('',*,*,#120663,.F.); +#120663 = EDGE_CURVE('',#120613,#120403,#120664,.T.); +#120664 = SURFACE_CURVE('',#120665,(#120669,#120676),.PCURVE_S1.); +#120665 = LINE('',#120666,#120667); +#120666 = CARTESIAN_POINT('',(-0.51959417205,6.65,0.530776333563)); +#120667 = VECTOR('',#120668,1.); +#120668 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#120669 = PCURVE('',#120417,#120670); +#120670 = DEFINITIONAL_REPRESENTATION('',(#120671),#120675); +#120671 = LINE('',#120672,#120673); +#120672 = CARTESIAN_POINT('',(3.35,-4.535643882845E-033)); +#120673 = VECTOR('',#120674,1.); +#120674 = DIRECTION('',(-4.535643882845E-032,-1.)); +#120675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120676 = PCURVE('',#93203,#120677); +#120677 = DEFINITIONAL_REPRESENTATION('',(#120678),#120682); +#120678 = LINE('',#120679,#120680); +#120679 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#120680 = VECTOR('',#120681,1.); +#120681 = DIRECTION('',(1.,-1.021336205033E-016)); +#120682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120683 = ADVANCED_FACE('',(#120684),#120630,.T.); +#120684 = FACE_BOUND('',#120685,.T.); +#120685 = EDGE_LOOP('',(#120686,#120687,#120710,#120755)); +#120686 = ORIENTED_EDGE('',*,*,#120612,.F.); +#120687 = ORIENTED_EDGE('',*,*,#120688,.F.); +#120688 = EDGE_CURVE('',#120689,#120613,#120691,.T.); +#120689 = VERTEX_POINT('',#120690); +#120690 = CARTESIAN_POINT('',(-0.304819755875,6.65,0.75)); +#120691 = SURFACE_CURVE('',#120692,(#120697,#120703),.PCURVE_S1.); +#120692 = CIRCLE('',#120693,0.2192697516); +#120693 = AXIS2_PLACEMENT_3D('',#120694,#120695,#120696); +#120694 = CARTESIAN_POINT('',(-0.30032442045,6.65,0.530776333563)); +#120695 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120696 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120697 = PCURVE('',#120630,#120698); +#120698 = DEFINITIONAL_REPRESENTATION('',(#120699),#120702); +#120699 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120700,#120701), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#118308 = CARTESIAN_POINT('',(1.591299156552,3.35)); -#118309 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#118310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118311 = PCURVE('',#90811,#118312); -#118312 = DEFINITIONAL_REPRESENTATION('',(#118313),#118317); -#118313 = CIRCLE('',#118314,0.2192697516); -#118314 = AXIS2_PLACEMENT_2D('',#118315,#118316); -#118315 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#118316 = DIRECTION('',(0.E+000,1.)); -#118317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118318 = ORIENTED_EDGE('',*,*,#118319,.F.); -#118319 = EDGE_CURVE('',#118320,#118297,#118322,.T.); -#118320 = VERTEX_POINT('',#118321); -#118321 = CARTESIAN_POINT('',(-0.304819755875,6.85,0.75)); -#118322 = SURFACE_CURVE('',#118323,(#118327,#118356),.PCURVE_S1.); -#118323 = LINE('',#118324,#118325); -#118324 = CARTESIAN_POINT('',(-0.304819755875,6.65,0.75)); -#118325 = VECTOR('',#118326,1.); -#118326 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118327 = PCURVE('',#118238,#118328); -#118328 = DEFINITIONAL_REPRESENTATION('',(#118329),#118355); -#118329 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#118330,#118331,#118332, - #118333,#118334,#118335,#118336,#118337,#118338,#118339,#118340, - #118341,#118342,#118343,#118344,#118345,#118346,#118347,#118348, - #118349,#118350,#118351,#118352,#118353,#118354),.UNSPECIFIED.,.F., +#120700 = CARTESIAN_POINT('',(1.591299156552,3.35)); +#120701 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#120702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120703 = PCURVE('',#93203,#120704); +#120704 = DEFINITIONAL_REPRESENTATION('',(#120705),#120709); +#120705 = CIRCLE('',#120706,0.2192697516); +#120706 = AXIS2_PLACEMENT_2D('',#120707,#120708); +#120707 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#120708 = DIRECTION('',(0.E+000,1.)); +#120709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120710 = ORIENTED_EDGE('',*,*,#120711,.F.); +#120711 = EDGE_CURVE('',#120712,#120689,#120714,.T.); +#120712 = VERTEX_POINT('',#120713); +#120713 = CARTESIAN_POINT('',(-0.304819755875,6.85,0.75)); +#120714 = SURFACE_CURVE('',#120715,(#120719,#120748),.PCURVE_S1.); +#120715 = LINE('',#120716,#120717); +#120716 = CARTESIAN_POINT('',(-0.304819755875,6.65,0.75)); +#120717 = VECTOR('',#120718,1.); +#120718 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120719 = PCURVE('',#120630,#120720); +#120720 = DEFINITIONAL_REPRESENTATION('',(#120721),#120747); +#120721 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#120722,#120723,#120724, + #120725,#120726,#120727,#120728,#120729,#120730,#120731,#120732, + #120733,#120734,#120735,#120736,#120737,#120738,#120739,#120740, + #120741,#120742,#120743,#120744,#120745,#120746),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -145747,128 +148749,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.QUASI_UNIFORM_KNOTS.); -#118330 = CARTESIAN_POINT('',(1.591299156552,3.15)); -#118331 = CARTESIAN_POINT('',(1.591299156552,3.15303030303)); -#118332 = CARTESIAN_POINT('',(1.591299156552,3.159090909091)); -#118333 = CARTESIAN_POINT('',(1.591299156552,3.168181818182)); -#118334 = CARTESIAN_POINT('',(1.591299156552,3.177272727273)); -#118335 = CARTESIAN_POINT('',(1.591299156552,3.186363636364)); -#118336 = CARTESIAN_POINT('',(1.591299156552,3.195454545455)); -#118337 = CARTESIAN_POINT('',(1.591299156552,3.204545454545)); -#118338 = CARTESIAN_POINT('',(1.591299156552,3.213636363636)); -#118339 = CARTESIAN_POINT('',(1.591299156552,3.222727272727)); -#118340 = CARTESIAN_POINT('',(1.591299156552,3.231818181818)); -#118341 = CARTESIAN_POINT('',(1.591299156552,3.240909090909)); -#118342 = CARTESIAN_POINT('',(1.591299156552,3.25)); -#118343 = CARTESIAN_POINT('',(1.591299156552,3.259090909091)); -#118344 = CARTESIAN_POINT('',(1.591299156552,3.268181818182)); -#118345 = CARTESIAN_POINT('',(1.591299156552,3.277272727273)); -#118346 = CARTESIAN_POINT('',(1.591299156552,3.286363636364)); -#118347 = CARTESIAN_POINT('',(1.591299156552,3.295454545455)); -#118348 = CARTESIAN_POINT('',(1.591299156552,3.304545454545)); -#118349 = CARTESIAN_POINT('',(1.591299156552,3.313636363636)); -#118350 = CARTESIAN_POINT('',(1.591299156552,3.322727272727)); -#118351 = CARTESIAN_POINT('',(1.591299156552,3.331818181818)); -#118352 = CARTESIAN_POINT('',(1.591299156552,3.340909090909)); -#118353 = CARTESIAN_POINT('',(1.591299156552,3.34696969697)); -#118354 = CARTESIAN_POINT('',(1.591299156552,3.35)); -#118355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118356 = PCURVE('',#90893,#118357); -#118357 = DEFINITIONAL_REPRESENTATION('',(#118358),#118362); -#118358 = LINE('',#118359,#118360); -#118359 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#118360 = VECTOR('',#118361,1.); -#118361 = DIRECTION('',(4.440892098501E-016,-1.)); -#118362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118363 = ORIENTED_EDGE('',*,*,#118364,.T.); -#118364 = EDGE_CURVE('',#118320,#118223,#118365,.T.); -#118365 = SURFACE_CURVE('',#118366,(#118371,#118377),.PCURVE_S1.); -#118366 = CIRCLE('',#118367,0.2192697516); -#118367 = AXIS2_PLACEMENT_3D('',#118368,#118369,#118370); -#118368 = CARTESIAN_POINT('',(-0.30032442045,6.85,0.530776333563)); -#118369 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118370 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118371 = PCURVE('',#118238,#118372); -#118372 = DEFINITIONAL_REPRESENTATION('',(#118373),#118376); -#118373 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118374,#118375), +#120722 = CARTESIAN_POINT('',(1.591299156552,3.15)); +#120723 = CARTESIAN_POINT('',(1.591299156552,3.15303030303)); +#120724 = CARTESIAN_POINT('',(1.591299156552,3.159090909091)); +#120725 = CARTESIAN_POINT('',(1.591299156552,3.168181818182)); +#120726 = CARTESIAN_POINT('',(1.591299156552,3.177272727273)); +#120727 = CARTESIAN_POINT('',(1.591299156552,3.186363636364)); +#120728 = CARTESIAN_POINT('',(1.591299156552,3.195454545455)); +#120729 = CARTESIAN_POINT('',(1.591299156552,3.204545454545)); +#120730 = CARTESIAN_POINT('',(1.591299156552,3.213636363636)); +#120731 = CARTESIAN_POINT('',(1.591299156552,3.222727272727)); +#120732 = CARTESIAN_POINT('',(1.591299156552,3.231818181818)); +#120733 = CARTESIAN_POINT('',(1.591299156552,3.240909090909)); +#120734 = CARTESIAN_POINT('',(1.591299156552,3.25)); +#120735 = CARTESIAN_POINT('',(1.591299156552,3.259090909091)); +#120736 = CARTESIAN_POINT('',(1.591299156552,3.268181818182)); +#120737 = CARTESIAN_POINT('',(1.591299156552,3.277272727273)); +#120738 = CARTESIAN_POINT('',(1.591299156552,3.286363636364)); +#120739 = CARTESIAN_POINT('',(1.591299156552,3.295454545455)); +#120740 = CARTESIAN_POINT('',(1.591299156552,3.304545454545)); +#120741 = CARTESIAN_POINT('',(1.591299156552,3.313636363636)); +#120742 = CARTESIAN_POINT('',(1.591299156552,3.322727272727)); +#120743 = CARTESIAN_POINT('',(1.591299156552,3.331818181818)); +#120744 = CARTESIAN_POINT('',(1.591299156552,3.340909090909)); +#120745 = CARTESIAN_POINT('',(1.591299156552,3.34696969697)); +#120746 = CARTESIAN_POINT('',(1.591299156552,3.35)); +#120747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120748 = PCURVE('',#93285,#120749); +#120749 = DEFINITIONAL_REPRESENTATION('',(#120750),#120754); +#120750 = LINE('',#120751,#120752); +#120751 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#120752 = VECTOR('',#120753,1.); +#120753 = DIRECTION('',(4.440892098501E-016,-1.)); +#120754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120755 = ORIENTED_EDGE('',*,*,#120756,.T.); +#120756 = EDGE_CURVE('',#120712,#120615,#120757,.T.); +#120757 = SURFACE_CURVE('',#120758,(#120763,#120769),.PCURVE_S1.); +#120758 = CIRCLE('',#120759,0.2192697516); +#120759 = AXIS2_PLACEMENT_3D('',#120760,#120761,#120762); +#120760 = CARTESIAN_POINT('',(-0.30032442045,6.85,0.530776333563)); +#120761 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120762 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120763 = PCURVE('',#120630,#120764); +#120764 = DEFINITIONAL_REPRESENTATION('',(#120765),#120768); +#120765 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120766,#120767), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#118374 = CARTESIAN_POINT('',(1.591299156552,3.15)); -#118375 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#118376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120766 = CARTESIAN_POINT('',(1.591299156552,3.15)); +#120767 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#120768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118377 = PCURVE('',#90867,#118378); -#118378 = DEFINITIONAL_REPRESENTATION('',(#118379),#118387); -#118379 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118380,#118381,#118382, - #118383,#118384,#118385,#118386),.UNSPECIFIED.,.T.,.F.) +#120769 = PCURVE('',#93259,#120770); +#120770 = DEFINITIONAL_REPRESENTATION('',(#120771),#120779); +#120771 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120772,#120773,#120774, + #120775,#120776,#120777,#120778),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118380 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#118381 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#118382 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#118383 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#118384 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#118385 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#118386 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#118387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118388 = ADVANCED_FACE('',(#118389),#118163,.F.); -#118389 = FACE_BOUND('',#118390,.F.); -#118390 = EDGE_LOOP('',(#118391,#118392,#118415,#118460)); -#118391 = ORIENTED_EDGE('',*,*,#118145,.T.); -#118392 = ORIENTED_EDGE('',*,*,#118393,.F.); -#118393 = EDGE_CURVE('',#118394,#118148,#118396,.T.); -#118394 = VERTEX_POINT('',#118395); -#118395 = CARTESIAN_POINT('',(-0.303662633502,6.65,0.65)); -#118396 = SURFACE_CURVE('',#118397,(#118402,#118408),.PCURVE_S1.); -#118397 = CIRCLE('',#118398,0.119270391569); -#118398 = AXIS2_PLACEMENT_3D('',#118399,#118400,#118401); -#118399 = CARTESIAN_POINT('',(-0.30032442045,6.65,0.530776333563)); -#118400 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118401 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118402 = PCURVE('',#118163,#118403); -#118403 = DEFINITIONAL_REPRESENTATION('',(#118404),#118407); -#118404 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118405,#118406), +#120772 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#120773 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#120774 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#120775 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#120776 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#120777 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#120778 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#120779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120780 = ADVANCED_FACE('',(#120781),#120555,.F.); +#120781 = FACE_BOUND('',#120782,.F.); +#120782 = EDGE_LOOP('',(#120783,#120784,#120807,#120852)); +#120783 = ORIENTED_EDGE('',*,*,#120537,.T.); +#120784 = ORIENTED_EDGE('',*,*,#120785,.F.); +#120785 = EDGE_CURVE('',#120786,#120540,#120788,.T.); +#120786 = VERTEX_POINT('',#120787); +#120787 = CARTESIAN_POINT('',(-0.303662633502,6.65,0.65)); +#120788 = SURFACE_CURVE('',#120789,(#120794,#120800),.PCURVE_S1.); +#120789 = CIRCLE('',#120790,0.119270391569); +#120790 = AXIS2_PLACEMENT_3D('',#120791,#120792,#120793); +#120791 = CARTESIAN_POINT('',(-0.30032442045,6.65,0.530776333563)); +#120792 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120793 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120794 = PCURVE('',#120555,#120795); +#120795 = DEFINITIONAL_REPRESENTATION('',(#120796),#120799); +#120796 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120797,#120798), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#118405 = CARTESIAN_POINT('',(1.598788597134,3.35)); -#118406 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#118407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118408 = PCURVE('',#90811,#118409); -#118409 = DEFINITIONAL_REPRESENTATION('',(#118410),#118414); -#118410 = CIRCLE('',#118411,0.119270391569); -#118411 = AXIS2_PLACEMENT_2D('',#118412,#118413); -#118412 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#118413 = DIRECTION('',(0.E+000,1.)); -#118414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118415 = ORIENTED_EDGE('',*,*,#118416,.T.); -#118416 = EDGE_CURVE('',#118394,#118417,#118419,.T.); -#118417 = VERTEX_POINT('',#118418); -#118418 = CARTESIAN_POINT('',(-0.303662633502,6.85,0.65)); -#118419 = SURFACE_CURVE('',#118420,(#118424,#118453),.PCURVE_S1.); -#118420 = LINE('',#118421,#118422); -#118421 = CARTESIAN_POINT('',(-0.303662633502,6.65,0.65)); -#118422 = VECTOR('',#118423,1.); -#118423 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118424 = PCURVE('',#118163,#118425); -#118425 = DEFINITIONAL_REPRESENTATION('',(#118426),#118452); -#118426 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#118427,#118428,#118429, - #118430,#118431,#118432,#118433,#118434,#118435,#118436,#118437, - #118438,#118439,#118440,#118441,#118442,#118443,#118444,#118445, - #118446,#118447,#118448,#118449,#118450,#118451),.UNSPECIFIED.,.F., +#120797 = CARTESIAN_POINT('',(1.598788597134,3.35)); +#120798 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#120799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120800 = PCURVE('',#93203,#120801); +#120801 = DEFINITIONAL_REPRESENTATION('',(#120802),#120806); +#120802 = CIRCLE('',#120803,0.119270391569); +#120803 = AXIS2_PLACEMENT_2D('',#120804,#120805); +#120804 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#120805 = DIRECTION('',(0.E+000,1.)); +#120806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120807 = ORIENTED_EDGE('',*,*,#120808,.T.); +#120808 = EDGE_CURVE('',#120786,#120809,#120811,.T.); +#120809 = VERTEX_POINT('',#120810); +#120810 = CARTESIAN_POINT('',(-0.303662633502,6.85,0.65)); +#120811 = SURFACE_CURVE('',#120812,(#120816,#120845),.PCURVE_S1.); +#120812 = LINE('',#120813,#120814); +#120813 = CARTESIAN_POINT('',(-0.303662633502,6.65,0.65)); +#120814 = VECTOR('',#120815,1.); +#120815 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#120816 = PCURVE('',#120555,#120817); +#120817 = DEFINITIONAL_REPRESENTATION('',(#120818),#120844); +#120818 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#120819,#120820,#120821, + #120822,#120823,#120824,#120825,#120826,#120827,#120828,#120829, + #120830,#120831,#120832,#120833,#120834,#120835,#120836,#120837, + #120838,#120839,#120840,#120841,#120842,#120843),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -145877,956 +148879,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ,0.136363636364,0.145454545455,0.154545454545,0.163636363636, 0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#118427 = CARTESIAN_POINT('',(1.598788597134,3.35)); -#118428 = CARTESIAN_POINT('',(1.598788597134,3.34696969697)); -#118429 = CARTESIAN_POINT('',(1.598788597134,3.340909090909)); -#118430 = CARTESIAN_POINT('',(1.598788597134,3.331818181818)); -#118431 = CARTESIAN_POINT('',(1.598788597134,3.322727272727)); -#118432 = CARTESIAN_POINT('',(1.598788597134,3.313636363636)); -#118433 = CARTESIAN_POINT('',(1.598788597134,3.304545454545)); -#118434 = CARTESIAN_POINT('',(1.598788597134,3.295454545455)); -#118435 = CARTESIAN_POINT('',(1.598788597134,3.286363636364)); -#118436 = CARTESIAN_POINT('',(1.598788597134,3.277272727273)); -#118437 = CARTESIAN_POINT('',(1.598788597134,3.268181818182)); -#118438 = CARTESIAN_POINT('',(1.598788597134,3.259090909091)); -#118439 = CARTESIAN_POINT('',(1.598788597134,3.25)); -#118440 = CARTESIAN_POINT('',(1.598788597134,3.240909090909)); -#118441 = CARTESIAN_POINT('',(1.598788597134,3.231818181818)); -#118442 = CARTESIAN_POINT('',(1.598788597134,3.222727272727)); -#118443 = CARTESIAN_POINT('',(1.598788597134,3.213636363636)); -#118444 = CARTESIAN_POINT('',(1.598788597134,3.204545454545)); -#118445 = CARTESIAN_POINT('',(1.598788597134,3.195454545455)); -#118446 = CARTESIAN_POINT('',(1.598788597134,3.186363636364)); -#118447 = CARTESIAN_POINT('',(1.598788597134,3.177272727273)); -#118448 = CARTESIAN_POINT('',(1.598788597134,3.168181818182)); -#118449 = CARTESIAN_POINT('',(1.598788597134,3.159090909091)); -#118450 = CARTESIAN_POINT('',(1.598788597134,3.15303030303)); -#118451 = CARTESIAN_POINT('',(1.598788597134,3.15)); -#118452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118453 = PCURVE('',#90839,#118454); -#118454 = DEFINITIONAL_REPRESENTATION('',(#118455),#118459); -#118455 = LINE('',#118456,#118457); -#118456 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#118457 = VECTOR('',#118458,1.); -#118458 = DIRECTION('',(4.440892098501E-016,1.)); -#118459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118460 = ORIENTED_EDGE('',*,*,#118461,.T.); -#118461 = EDGE_CURVE('',#118417,#118146,#118462,.T.); -#118462 = SURFACE_CURVE('',#118463,(#118468,#118474),.PCURVE_S1.); -#118463 = CIRCLE('',#118464,0.119270391569); -#118464 = AXIS2_PLACEMENT_3D('',#118465,#118466,#118467); -#118465 = CARTESIAN_POINT('',(-0.30032442045,6.85,0.530776333563)); -#118466 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118467 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#118468 = PCURVE('',#118163,#118469); -#118469 = DEFINITIONAL_REPRESENTATION('',(#118470),#118473); -#118470 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118471,#118472), +#120819 = CARTESIAN_POINT('',(1.598788597134,3.35)); +#120820 = CARTESIAN_POINT('',(1.598788597134,3.34696969697)); +#120821 = CARTESIAN_POINT('',(1.598788597134,3.340909090909)); +#120822 = CARTESIAN_POINT('',(1.598788597134,3.331818181818)); +#120823 = CARTESIAN_POINT('',(1.598788597134,3.322727272727)); +#120824 = CARTESIAN_POINT('',(1.598788597134,3.313636363636)); +#120825 = CARTESIAN_POINT('',(1.598788597134,3.304545454545)); +#120826 = CARTESIAN_POINT('',(1.598788597134,3.295454545455)); +#120827 = CARTESIAN_POINT('',(1.598788597134,3.286363636364)); +#120828 = CARTESIAN_POINT('',(1.598788597134,3.277272727273)); +#120829 = CARTESIAN_POINT('',(1.598788597134,3.268181818182)); +#120830 = CARTESIAN_POINT('',(1.598788597134,3.259090909091)); +#120831 = CARTESIAN_POINT('',(1.598788597134,3.25)); +#120832 = CARTESIAN_POINT('',(1.598788597134,3.240909090909)); +#120833 = CARTESIAN_POINT('',(1.598788597134,3.231818181818)); +#120834 = CARTESIAN_POINT('',(1.598788597134,3.222727272727)); +#120835 = CARTESIAN_POINT('',(1.598788597134,3.213636363636)); +#120836 = CARTESIAN_POINT('',(1.598788597134,3.204545454545)); +#120837 = CARTESIAN_POINT('',(1.598788597134,3.195454545455)); +#120838 = CARTESIAN_POINT('',(1.598788597134,3.186363636364)); +#120839 = CARTESIAN_POINT('',(1.598788597134,3.177272727273)); +#120840 = CARTESIAN_POINT('',(1.598788597134,3.168181818182)); +#120841 = CARTESIAN_POINT('',(1.598788597134,3.159090909091)); +#120842 = CARTESIAN_POINT('',(1.598788597134,3.15303030303)); +#120843 = CARTESIAN_POINT('',(1.598788597134,3.15)); +#120844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120845 = PCURVE('',#93231,#120846); +#120846 = DEFINITIONAL_REPRESENTATION('',(#120847),#120851); +#120847 = LINE('',#120848,#120849); +#120848 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#120849 = VECTOR('',#120850,1.); +#120850 = DIRECTION('',(4.440892098501E-016,1.)); +#120851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120852 = ORIENTED_EDGE('',*,*,#120853,.T.); +#120853 = EDGE_CURVE('',#120809,#120538,#120854,.T.); +#120854 = SURFACE_CURVE('',#120855,(#120860,#120866),.PCURVE_S1.); +#120855 = CIRCLE('',#120856,0.119270391569); +#120856 = AXIS2_PLACEMENT_3D('',#120857,#120858,#120859); +#120857 = CARTESIAN_POINT('',(-0.30032442045,6.85,0.530776333563)); +#120858 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#120859 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#120860 = PCURVE('',#120555,#120861); +#120861 = DEFINITIONAL_REPRESENTATION('',(#120862),#120865); +#120862 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120863,#120864), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#118471 = CARTESIAN_POINT('',(1.598788597134,3.15)); -#118472 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#118473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120863 = CARTESIAN_POINT('',(1.598788597134,3.15)); +#120864 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#120865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118474 = PCURVE('',#90867,#118475); -#118475 = DEFINITIONAL_REPRESENTATION('',(#118476),#118484); -#118476 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118477,#118478,#118479, - #118480,#118481,#118482,#118483),.UNSPECIFIED.,.T.,.F.) +#120866 = PCURVE('',#93259,#120867); +#120867 = DEFINITIONAL_REPRESENTATION('',(#120868),#120876); +#120868 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120869,#120870,#120871, + #120872,#120873,#120874,#120875),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118477 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#118478 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#118479 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#118480 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#118481 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#118482 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#118483 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#118484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118485 = ADVANCED_FACE('',(#118486),#90839,.T.); -#118486 = FACE_BOUND('',#118487,.T.); -#118487 = EDGE_LOOP('',(#118488,#118509,#118510,#118531)); -#118488 = ORIENTED_EDGE('',*,*,#118489,.F.); -#118489 = EDGE_CURVE('',#118394,#90796,#118490,.T.); -#118490 = SURFACE_CURVE('',#118491,(#118495,#118502),.PCURVE_S1.); -#118491 = LINE('',#118492,#118493); -#118492 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); -#118493 = VECTOR('',#118494,1.); -#118494 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#118495 = PCURVE('',#90839,#118496); -#118496 = DEFINITIONAL_REPRESENTATION('',(#118497),#118501); -#118497 = LINE('',#118498,#118499); -#118498 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118499 = VECTOR('',#118500,1.); -#118500 = DIRECTION('',(-1.,-4.804757279354E-063)); -#118501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118502 = PCURVE('',#90811,#118503); -#118503 = DEFINITIONAL_REPRESENTATION('',(#118504),#118508); -#118504 = LINE('',#118505,#118506); -#118505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118506 = VECTOR('',#118507,1.); -#118507 = DIRECTION('',(-3.563627120235E-016,1.)); -#118508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118509 = ORIENTED_EDGE('',*,*,#118416,.T.); -#118510 = ORIENTED_EDGE('',*,*,#118511,.T.); -#118511 = EDGE_CURVE('',#118417,#90824,#118512,.T.); -#118512 = SURFACE_CURVE('',#118513,(#118517,#118524),.PCURVE_S1.); -#118513 = LINE('',#118514,#118515); -#118514 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.65)); -#118515 = VECTOR('',#118516,1.); -#118516 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#118517 = PCURVE('',#90839,#118518); -#118518 = DEFINITIONAL_REPRESENTATION('',(#118519),#118523); -#118519 = LINE('',#118520,#118521); -#118520 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#118521 = VECTOR('',#118522,1.); -#118522 = DIRECTION('',(-1.,-4.804757279354E-063)); -#118523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118524 = PCURVE('',#90867,#118525); -#118525 = DEFINITIONAL_REPRESENTATION('',(#118526),#118530); -#118526 = LINE('',#118527,#118528); -#118527 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118528 = VECTOR('',#118529,1.); -#118529 = DIRECTION('',(3.563627120235E-016,1.)); -#118530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118531 = ORIENTED_EDGE('',*,*,#90823,.F.); -#118532 = ADVANCED_FACE('',(#118533),#90867,.T.); -#118533 = FACE_BOUND('',#118534,.T.); -#118534 = EDGE_LOOP('',(#118535,#118536,#118537,#118538,#118539,#118540, - #118561,#118562,#118563,#118564,#118565,#118586)); -#118535 = ORIENTED_EDGE('',*,*,#118511,.F.); -#118536 = ORIENTED_EDGE('',*,*,#118461,.T.); -#118537 = ORIENTED_EDGE('',*,*,#118196,.T.); -#118538 = ORIENTED_EDGE('',*,*,#118094,.T.); -#118539 = ORIENTED_EDGE('',*,*,#117913,.T.); -#118540 = ORIENTED_EDGE('',*,*,#118541,.F.); -#118541 = EDGE_CURVE('',#117777,#117884,#118542,.T.); -#118542 = SURFACE_CURVE('',#118543,(#118547,#118554),.PCURVE_S1.); -#118543 = LINE('',#118544,#118545); -#118544 = CARTESIAN_POINT('',(-1.,6.85,1.159810404338E-002)); -#118545 = VECTOR('',#118546,1.); -#118546 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#118547 = PCURVE('',#90867,#118548); -#118548 = DEFINITIONAL_REPRESENTATION('',(#118549),#118553); -#118549 = LINE('',#118550,#118551); -#118550 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#118551 = VECTOR('',#118552,1.); -#118552 = DIRECTION('',(-1.,2.101748079665E-016)); -#118553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118554 = PCURVE('',#117797,#118555); -#118555 = DEFINITIONAL_REPRESENTATION('',(#118556),#118560); -#118556 = LINE('',#118557,#118558); -#118557 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#118558 = VECTOR('',#118559,1.); -#118559 = DIRECTION('',(1.194699204908E-017,-1.)); -#118560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118561 = ORIENTED_EDGE('',*,*,#117859,.F.); -#118562 = ORIENTED_EDGE('',*,*,#117987,.F.); -#118563 = ORIENTED_EDGE('',*,*,#118249,.F.); -#118564 = ORIENTED_EDGE('',*,*,#118364,.F.); -#118565 = ORIENTED_EDGE('',*,*,#118566,.T.); -#118566 = EDGE_CURVE('',#118320,#90852,#118567,.T.); -#118567 = SURFACE_CURVE('',#118568,(#118572,#118579),.PCURVE_S1.); -#118568 = LINE('',#118569,#118570); -#118569 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.75)); -#118570 = VECTOR('',#118571,1.); -#118571 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#118572 = PCURVE('',#90867,#118573); -#118573 = DEFINITIONAL_REPRESENTATION('',(#118574),#118578); -#118574 = LINE('',#118575,#118576); -#118575 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#118576 = VECTOR('',#118577,1.); -#118577 = DIRECTION('',(3.563627120235E-016,1.)); -#118578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118579 = PCURVE('',#90893,#118580); -#118580 = DEFINITIONAL_REPRESENTATION('',(#118581),#118585); -#118581 = LINE('',#118582,#118583); -#118582 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#118583 = VECTOR('',#118584,1.); -#118584 = DIRECTION('',(1.,-4.804757279354E-063)); -#118585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118586 = ORIENTED_EDGE('',*,*,#90851,.F.); -#118587 = ADVANCED_FACE('',(#118588),#90893,.T.); -#118588 = FACE_BOUND('',#118589,.T.); -#118589 = EDGE_LOOP('',(#118590,#118591,#118592,#118613)); -#118590 = ORIENTED_EDGE('',*,*,#118566,.F.); -#118591 = ORIENTED_EDGE('',*,*,#118319,.T.); -#118592 = ORIENTED_EDGE('',*,*,#118593,.T.); -#118593 = EDGE_CURVE('',#118297,#90794,#118594,.T.); -#118594 = SURFACE_CURVE('',#118595,(#118599,#118606),.PCURVE_S1.); -#118595 = LINE('',#118596,#118597); -#118596 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.75)); -#118597 = VECTOR('',#118598,1.); -#118598 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#118599 = PCURVE('',#90893,#118600); -#118600 = DEFINITIONAL_REPRESENTATION('',(#118601),#118605); -#118601 = LINE('',#118602,#118603); -#118602 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118603 = VECTOR('',#118604,1.); -#118604 = DIRECTION('',(1.,-4.804757279354E-063)); -#118605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118606 = PCURVE('',#90811,#118607); -#118607 = DEFINITIONAL_REPRESENTATION('',(#118608),#118612); -#118608 = LINE('',#118609,#118610); -#118609 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#118610 = VECTOR('',#118611,1.); -#118611 = DIRECTION('',(-3.563627120235E-016,1.)); -#118612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118613 = ORIENTED_EDGE('',*,*,#90879,.F.); -#118614 = ADVANCED_FACE('',(#118615),#90811,.T.); -#118615 = FACE_BOUND('',#118616,.T.); -#118616 = EDGE_LOOP('',(#118617,#118618,#118619,#118620,#118621,#118622, - #118643,#118644,#118645,#118646,#118647,#118648)); -#118617 = ORIENTED_EDGE('',*,*,#118593,.F.); -#118618 = ORIENTED_EDGE('',*,*,#118296,.T.); -#118619 = ORIENTED_EDGE('',*,*,#118271,.T.); -#118620 = ORIENTED_EDGE('',*,*,#118037,.T.); -#118621 = ORIENTED_EDGE('',*,*,#117809,.T.); -#118622 = ORIENTED_EDGE('',*,*,#118623,.F.); -#118623 = EDGE_CURVE('',#117886,#117775,#118624,.T.); -#118624 = SURFACE_CURVE('',#118625,(#118629,#118636),.PCURVE_S1.); -#118625 = LINE('',#118626,#118627); -#118626 = CARTESIAN_POINT('',(-1.,6.65,1.159810404338E-002)); -#118627 = VECTOR('',#118628,1.); -#118628 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#118629 = PCURVE('',#90811,#118630); -#118630 = DEFINITIONAL_REPRESENTATION('',(#118631),#118635); -#118631 = LINE('',#118632,#118633); -#118632 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#118633 = VECTOR('',#118634,1.); -#118634 = DIRECTION('',(-1.,-2.101748079665E-016)); -#118635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118636 = PCURVE('',#117797,#118637); -#118637 = DEFINITIONAL_REPRESENTATION('',(#118638),#118642); -#118638 = LINE('',#118639,#118640); -#118639 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#118640 = VECTOR('',#118641,1.); -#118641 = DIRECTION('',(-1.194699204908E-017,1.)); -#118642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118643 = ORIENTED_EDGE('',*,*,#117963,.F.); -#118644 = ORIENTED_EDGE('',*,*,#118066,.F.); -#118645 = ORIENTED_EDGE('',*,*,#118174,.F.); -#118646 = ORIENTED_EDGE('',*,*,#118393,.F.); -#118647 = ORIENTED_EDGE('',*,*,#118489,.T.); -#118648 = ORIENTED_EDGE('',*,*,#90793,.F.); -#118649 = ADVANCED_FACE('',(#118650),#117797,.T.); -#118650 = FACE_BOUND('',#118651,.T.); -#118651 = EDGE_LOOP('',(#118652,#118653,#118654,#118655)); -#118652 = ORIENTED_EDGE('',*,*,#118541,.T.); -#118653 = ORIENTED_EDGE('',*,*,#117883,.T.); -#118654 = ORIENTED_EDGE('',*,*,#118623,.T.); -#118655 = ORIENTED_EDGE('',*,*,#117774,.T.); -#118656 = ADVANCED_FACE('',(#118657),#118671,.F.); -#118657 = FACE_BOUND('',#118658,.T.); -#118658 = EDGE_LOOP('',(#118659,#118694,#118717,#118744)); -#118659 = ORIENTED_EDGE('',*,*,#118660,.F.); -#118660 = EDGE_CURVE('',#118661,#118663,#118665,.T.); -#118661 = VERTEX_POINT('',#118662); -#118662 = CARTESIAN_POINT('',(-1.,7.15,-0.208196358798)); -#118663 = VERTEX_POINT('',#118664); -#118664 = CARTESIAN_POINT('',(-1.,7.35,-0.208196358798)); -#118665 = SURFACE_CURVE('',#118666,(#118670,#118682),.PCURVE_S1.); -#118666 = LINE('',#118667,#118668); -#118667 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#118668 = VECTOR('',#118669,1.); -#118669 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118670 = PCURVE('',#118671,#118676); -#118671 = PLANE('',#118672); -#118672 = AXIS2_PLACEMENT_3D('',#118673,#118674,#118675); -#118673 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#118674 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#118675 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#118676 = DEFINITIONAL_REPRESENTATION('',(#118677),#118681); -#118677 = LINE('',#118678,#118679); -#118678 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#118679 = VECTOR('',#118680,1.); -#118680 = DIRECTION('',(4.440892098501E-016,1.)); -#118681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118682 = PCURVE('',#118683,#118688); -#118683 = PLANE('',#118684); -#118684 = AXIS2_PLACEMENT_3D('',#118685,#118686,#118687); -#118685 = CARTESIAN_POINT('',(-1.,7.25,-0.258196742327)); -#118686 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#118687 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118688 = DEFINITIONAL_REPRESENTATION('',(#118689),#118693); -#118689 = LINE('',#118690,#118691); -#118690 = CARTESIAN_POINT('',(-2.75,5.000038352949E-002)); -#118691 = VECTOR('',#118692,1.); -#118692 = DIRECTION('',(-1.,0.E+000)); -#118693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118694 = ORIENTED_EDGE('',*,*,#118695,.F.); -#118695 = EDGE_CURVE('',#118696,#118661,#118698,.T.); -#118696 = VERTEX_POINT('',#118697); -#118697 = CARTESIAN_POINT('',(-0.740726081328,7.15,-0.208196358798)); -#118698 = SURFACE_CURVE('',#118699,(#118703,#118710),.PCURVE_S1.); -#118699 = LINE('',#118700,#118701); -#118700 = CARTESIAN_POINT('',(-0.740726081328,7.15,-0.208196358798)); -#118701 = VECTOR('',#118702,1.); -#118702 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#118703 = PCURVE('',#118671,#118704); -#118704 = DEFINITIONAL_REPRESENTATION('',(#118705),#118709); -#118705 = LINE('',#118706,#118707); -#118706 = CARTESIAN_POINT('',(-1.33226762955E-015,-2.85)); -#118707 = VECTOR('',#118708,1.); -#118708 = DIRECTION('',(1.,0.E+000)); -#118709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118710 = PCURVE('',#90697,#118711); -#118711 = DEFINITIONAL_REPRESENTATION('',(#118712),#118716); -#118712 = LINE('',#118713,#118714); -#118713 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#118714 = VECTOR('',#118715,1.); -#118715 = DIRECTION('',(0.E+000,-1.)); -#118716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118717 = ORIENTED_EDGE('',*,*,#118718,.F.); -#118718 = EDGE_CURVE('',#118719,#118696,#118721,.T.); -#118719 = VERTEX_POINT('',#118720); -#118720 = CARTESIAN_POINT('',(-0.740726081328,7.35,-0.208196358798)); -#118721 = SURFACE_CURVE('',#118722,(#118726,#118733),.PCURVE_S1.); -#118722 = LINE('',#118723,#118724); -#118723 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#118724 = VECTOR('',#118725,1.); -#118725 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118726 = PCURVE('',#118671,#118727); -#118727 = DEFINITIONAL_REPRESENTATION('',(#118728),#118732); -#118728 = LINE('',#118729,#118730); -#118729 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118730 = VECTOR('',#118731,1.); -#118731 = DIRECTION('',(-4.440892098501E-016,-1.)); -#118732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118733 = PCURVE('',#118734,#118739); -#118734 = CYLINDRICAL_SURFACE('',#118735,0.208574704164); -#118735 = AXIS2_PLACEMENT_3D('',#118736,#118737,#118738); -#118736 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#118737 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118738 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118739 = DEFINITIONAL_REPRESENTATION('',(#118740),#118743); -#118740 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118741,#118742), - .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#118741 = CARTESIAN_POINT('',(4.772630242227,-2.65)); -#118742 = CARTESIAN_POINT('',(4.772630242227,-2.85)); -#118743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118744 = ORIENTED_EDGE('',*,*,#118745,.T.); -#118745 = EDGE_CURVE('',#118719,#118663,#118746,.T.); -#118746 = SURFACE_CURVE('',#118747,(#118751,#118758),.PCURVE_S1.); -#118747 = LINE('',#118748,#118749); -#118748 = CARTESIAN_POINT('',(-0.740726081328,7.35,-0.208196358798)); -#118749 = VECTOR('',#118750,1.); -#118750 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#118751 = PCURVE('',#118671,#118752); -#118752 = DEFINITIONAL_REPRESENTATION('',(#118753),#118757); -#118753 = LINE('',#118754,#118755); -#118754 = CARTESIAN_POINT('',(-1.110223024625E-015,-2.65)); -#118755 = VECTOR('',#118756,1.); -#118756 = DIRECTION('',(1.,0.E+000)); -#118757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118758 = PCURVE('',#90753,#118759); -#118759 = DEFINITIONAL_REPRESENTATION('',(#118760),#118764); -#118760 = LINE('',#118761,#118762); -#118761 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#118762 = VECTOR('',#118763,1.); -#118763 = DIRECTION('',(0.E+000,-1.)); -#118764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118765 = ADVANCED_FACE('',(#118766),#118780,.F.); -#118766 = FACE_BOUND('',#118767,.T.); -#118767 = EDGE_LOOP('',(#118768,#118798,#118821,#118848)); -#118768 = ORIENTED_EDGE('',*,*,#118769,.F.); -#118769 = EDGE_CURVE('',#118770,#118772,#118774,.T.); -#118770 = VERTEX_POINT('',#118771); -#118771 = CARTESIAN_POINT('',(-1.,7.35,-0.308197125857)); -#118772 = VERTEX_POINT('',#118773); -#118773 = CARTESIAN_POINT('',(-1.,7.15,-0.308197125857)); -#118774 = SURFACE_CURVE('',#118775,(#118779,#118791),.PCURVE_S1.); -#118775 = LINE('',#118776,#118777); -#118776 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#118777 = VECTOR('',#118778,1.); -#118778 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118779 = PCURVE('',#118780,#118785); -#118780 = PLANE('',#118781); -#118781 = AXIS2_PLACEMENT_3D('',#118782,#118783,#118784); -#118782 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#118783 = DIRECTION('',(0.E+000,0.E+000,1.)); -#118784 = DIRECTION('',(1.,0.E+000,0.E+000)); -#118785 = DEFINITIONAL_REPRESENTATION('',(#118786),#118790); -#118786 = LINE('',#118787,#118788); -#118787 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#118788 = VECTOR('',#118789,1.); -#118789 = DIRECTION('',(4.440892098501E-016,-1.)); -#118790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118791 = PCURVE('',#118683,#118792); -#118792 = DEFINITIONAL_REPRESENTATION('',(#118793),#118797); -#118793 = LINE('',#118794,#118795); -#118794 = CARTESIAN_POINT('',(-2.75,-5.000038352949E-002)); -#118795 = VECTOR('',#118796,1.); -#118796 = DIRECTION('',(1.,0.E+000)); -#118797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118798 = ORIENTED_EDGE('',*,*,#118799,.F.); -#118799 = EDGE_CURVE('',#118800,#118770,#118802,.T.); -#118800 = VERTEX_POINT('',#118801); -#118801 = CARTESIAN_POINT('',(-0.74341632541,7.35,-0.308197125857)); -#118802 = SURFACE_CURVE('',#118803,(#118807,#118814),.PCURVE_S1.); -#118803 = LINE('',#118804,#118805); -#118804 = CARTESIAN_POINT('',(-0.74341632541,7.35,-0.308197125857)); -#118805 = VECTOR('',#118806,1.); -#118806 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#118807 = PCURVE('',#118780,#118808); -#118808 = DEFINITIONAL_REPRESENTATION('',(#118809),#118813); -#118809 = LINE('',#118810,#118811); -#118810 = CARTESIAN_POINT('',(1.110223024625E-015,-2.65)); -#118811 = VECTOR('',#118812,1.); -#118812 = DIRECTION('',(-1.,0.E+000)); -#118813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#120869 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#120870 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#120871 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#120872 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#120873 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#120874 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#120875 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#120876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120877 = ADVANCED_FACE('',(#120878),#93231,.T.); +#120878 = FACE_BOUND('',#120879,.T.); +#120879 = EDGE_LOOP('',(#120880,#120901,#120902,#120923)); +#120880 = ORIENTED_EDGE('',*,*,#120881,.F.); +#120881 = EDGE_CURVE('',#120786,#93188,#120882,.T.); +#120882 = SURFACE_CURVE('',#120883,(#120887,#120894),.PCURVE_S1.); +#120883 = LINE('',#120884,#120885); +#120884 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.65)); +#120885 = VECTOR('',#120886,1.); +#120886 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120887 = PCURVE('',#93231,#120888); +#120888 = DEFINITIONAL_REPRESENTATION('',(#120889),#120893); +#120889 = LINE('',#120890,#120891); +#120890 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120891 = VECTOR('',#120892,1.); +#120892 = DIRECTION('',(-1.,-4.804757279354E-063)); +#120893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120894 = PCURVE('',#93203,#120895); +#120895 = DEFINITIONAL_REPRESENTATION('',(#120896),#120900); +#120896 = LINE('',#120897,#120898); +#120897 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120898 = VECTOR('',#120899,1.); +#120899 = DIRECTION('',(-3.563627120235E-016,1.)); +#120900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120901 = ORIENTED_EDGE('',*,*,#120808,.T.); +#120902 = ORIENTED_EDGE('',*,*,#120903,.T.); +#120903 = EDGE_CURVE('',#120809,#93216,#120904,.T.); +#120904 = SURFACE_CURVE('',#120905,(#120909,#120916),.PCURVE_S1.); +#120905 = LINE('',#120906,#120907); +#120906 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.65)); +#120907 = VECTOR('',#120908,1.); +#120908 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120909 = PCURVE('',#93231,#120910); +#120910 = DEFINITIONAL_REPRESENTATION('',(#120911),#120915); +#120911 = LINE('',#120912,#120913); +#120912 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#120913 = VECTOR('',#120914,1.); +#120914 = DIRECTION('',(-1.,-4.804757279354E-063)); +#120915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120916 = PCURVE('',#93259,#120917); +#120917 = DEFINITIONAL_REPRESENTATION('',(#120918),#120922); +#120918 = LINE('',#120919,#120920); +#120919 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120920 = VECTOR('',#120921,1.); +#120921 = DIRECTION('',(3.563627120235E-016,1.)); +#120922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120923 = ORIENTED_EDGE('',*,*,#93215,.F.); +#120924 = ADVANCED_FACE('',(#120925),#93259,.T.); +#120925 = FACE_BOUND('',#120926,.T.); +#120926 = EDGE_LOOP('',(#120927,#120928,#120929,#120930,#120931,#120932, + #120953,#120954,#120955,#120956,#120957,#120978)); +#120927 = ORIENTED_EDGE('',*,*,#120903,.F.); +#120928 = ORIENTED_EDGE('',*,*,#120853,.T.); +#120929 = ORIENTED_EDGE('',*,*,#120588,.T.); +#120930 = ORIENTED_EDGE('',*,*,#120486,.T.); +#120931 = ORIENTED_EDGE('',*,*,#120305,.T.); +#120932 = ORIENTED_EDGE('',*,*,#120933,.F.); +#120933 = EDGE_CURVE('',#120169,#120276,#120934,.T.); +#120934 = SURFACE_CURVE('',#120935,(#120939,#120946),.PCURVE_S1.); +#120935 = LINE('',#120936,#120937); +#120936 = CARTESIAN_POINT('',(-1.,6.85,1.159810404338E-002)); +#120937 = VECTOR('',#120938,1.); +#120938 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#120939 = PCURVE('',#93259,#120940); +#120940 = DEFINITIONAL_REPRESENTATION('',(#120941),#120945); +#120941 = LINE('',#120942,#120943); +#120942 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#120943 = VECTOR('',#120944,1.); +#120944 = DIRECTION('',(-1.,2.101748079665E-016)); +#120945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120946 = PCURVE('',#120189,#120947); +#120947 = DEFINITIONAL_REPRESENTATION('',(#120948),#120952); +#120948 = LINE('',#120949,#120950); +#120949 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#120950 = VECTOR('',#120951,1.); +#120951 = DIRECTION('',(1.194699204908E-017,-1.)); +#120952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120953 = ORIENTED_EDGE('',*,*,#120251,.F.); +#120954 = ORIENTED_EDGE('',*,*,#120379,.F.); +#120955 = ORIENTED_EDGE('',*,*,#120641,.F.); +#120956 = ORIENTED_EDGE('',*,*,#120756,.F.); +#120957 = ORIENTED_EDGE('',*,*,#120958,.T.); +#120958 = EDGE_CURVE('',#120712,#93244,#120959,.T.); +#120959 = SURFACE_CURVE('',#120960,(#120964,#120971),.PCURVE_S1.); +#120960 = LINE('',#120961,#120962); +#120961 = CARTESIAN_POINT('',(-0.527847992439,6.85,0.75)); +#120962 = VECTOR('',#120963,1.); +#120963 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120964 = PCURVE('',#93259,#120965); +#120965 = DEFINITIONAL_REPRESENTATION('',(#120966),#120970); +#120966 = LINE('',#120967,#120968); +#120967 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#120968 = VECTOR('',#120969,1.); +#120969 = DIRECTION('',(3.563627120235E-016,1.)); +#120970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120971 = PCURVE('',#93285,#120972); +#120972 = DEFINITIONAL_REPRESENTATION('',(#120973),#120977); +#120973 = LINE('',#120974,#120975); +#120974 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#120975 = VECTOR('',#120976,1.); +#120976 = DIRECTION('',(1.,-4.804757279354E-063)); +#120977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120978 = ORIENTED_EDGE('',*,*,#93243,.F.); +#120979 = ADVANCED_FACE('',(#120980),#93285,.T.); +#120980 = FACE_BOUND('',#120981,.T.); +#120981 = EDGE_LOOP('',(#120982,#120983,#120984,#121005)); +#120982 = ORIENTED_EDGE('',*,*,#120958,.F.); +#120983 = ORIENTED_EDGE('',*,*,#120711,.T.); +#120984 = ORIENTED_EDGE('',*,*,#120985,.T.); +#120985 = EDGE_CURVE('',#120689,#93186,#120986,.T.); +#120986 = SURFACE_CURVE('',#120987,(#120991,#120998),.PCURVE_S1.); +#120987 = LINE('',#120988,#120989); +#120988 = CARTESIAN_POINT('',(-0.527847992439,6.65,0.75)); +#120989 = VECTOR('',#120990,1.); +#120990 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#120991 = PCURVE('',#93285,#120992); +#120992 = DEFINITIONAL_REPRESENTATION('',(#120993),#120997); +#120993 = LINE('',#120994,#120995); +#120994 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#120995 = VECTOR('',#120996,1.); +#120996 = DIRECTION('',(1.,-4.804757279354E-063)); +#120997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#120998 = PCURVE('',#93203,#120999); +#120999 = DEFINITIONAL_REPRESENTATION('',(#121000),#121004); +#121000 = LINE('',#121001,#121002); +#121001 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#121002 = VECTOR('',#121003,1.); +#121003 = DIRECTION('',(-3.563627120235E-016,1.)); +#121004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121005 = ORIENTED_EDGE('',*,*,#93271,.F.); +#121006 = ADVANCED_FACE('',(#121007),#93203,.T.); +#121007 = FACE_BOUND('',#121008,.T.); +#121008 = EDGE_LOOP('',(#121009,#121010,#121011,#121012,#121013,#121014, + #121035,#121036,#121037,#121038,#121039,#121040)); +#121009 = ORIENTED_EDGE('',*,*,#120985,.F.); +#121010 = ORIENTED_EDGE('',*,*,#120688,.T.); +#121011 = ORIENTED_EDGE('',*,*,#120663,.T.); +#121012 = ORIENTED_EDGE('',*,*,#120429,.T.); +#121013 = ORIENTED_EDGE('',*,*,#120201,.T.); +#121014 = ORIENTED_EDGE('',*,*,#121015,.F.); +#121015 = EDGE_CURVE('',#120278,#120167,#121016,.T.); +#121016 = SURFACE_CURVE('',#121017,(#121021,#121028),.PCURVE_S1.); +#121017 = LINE('',#121018,#121019); +#121018 = CARTESIAN_POINT('',(-1.,6.65,1.159810404338E-002)); +#121019 = VECTOR('',#121020,1.); +#121020 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#121021 = PCURVE('',#93203,#121022); +#121022 = DEFINITIONAL_REPRESENTATION('',(#121023),#121027); +#121023 = LINE('',#121024,#121025); +#121024 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#121025 = VECTOR('',#121026,1.); +#121026 = DIRECTION('',(-1.,-2.101748079665E-016)); +#121027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121028 = PCURVE('',#120189,#121029); +#121029 = DEFINITIONAL_REPRESENTATION('',(#121030),#121034); +#121030 = LINE('',#121031,#121032); +#121031 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#121032 = VECTOR('',#121033,1.); +#121033 = DIRECTION('',(-1.194699204908E-017,1.)); +#121034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118814 = PCURVE('',#90753,#118815); -#118815 = DEFINITIONAL_REPRESENTATION('',(#118816),#118820); -#118816 = LINE('',#118817,#118818); -#118817 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#118818 = VECTOR('',#118819,1.); -#118819 = DIRECTION('',(0.E+000,-1.)); -#118820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118821 = ORIENTED_EDGE('',*,*,#118822,.F.); -#118822 = EDGE_CURVE('',#118823,#118800,#118825,.T.); -#118823 = VERTEX_POINT('',#118824); -#118824 = CARTESIAN_POINT('',(-0.74341632541,7.15,-0.308197125857)); -#118825 = SURFACE_CURVE('',#118826,(#118830,#118837),.PCURVE_S1.); -#118826 = LINE('',#118827,#118828); -#118827 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#118828 = VECTOR('',#118829,1.); -#118829 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118830 = PCURVE('',#118780,#118831); -#118831 = DEFINITIONAL_REPRESENTATION('',(#118832),#118836); -#118832 = LINE('',#118833,#118834); -#118833 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#118834 = VECTOR('',#118835,1.); -#118835 = DIRECTION('',(-4.440892098501E-016,1.)); -#118836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118837 = PCURVE('',#118838,#118843); -#118838 = CYLINDRICAL_SURFACE('',#118839,0.308574064194); -#118839 = AXIS2_PLACEMENT_3D('',#118840,#118841,#118842); -#118840 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#118841 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118842 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118843 = DEFINITIONAL_REPRESENTATION('',(#118844),#118847); -#118844 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118845,#118846), +#121035 = ORIENTED_EDGE('',*,*,#120355,.F.); +#121036 = ORIENTED_EDGE('',*,*,#120458,.F.); +#121037 = ORIENTED_EDGE('',*,*,#120566,.F.); +#121038 = ORIENTED_EDGE('',*,*,#120785,.F.); +#121039 = ORIENTED_EDGE('',*,*,#120881,.T.); +#121040 = ORIENTED_EDGE('',*,*,#93185,.F.); +#121041 = ADVANCED_FACE('',(#121042),#120189,.T.); +#121042 = FACE_BOUND('',#121043,.T.); +#121043 = EDGE_LOOP('',(#121044,#121045,#121046,#121047)); +#121044 = ORIENTED_EDGE('',*,*,#120933,.T.); +#121045 = ORIENTED_EDGE('',*,*,#120275,.T.); +#121046 = ORIENTED_EDGE('',*,*,#121015,.T.); +#121047 = ORIENTED_EDGE('',*,*,#120166,.T.); +#121048 = ADVANCED_FACE('',(#121049),#121063,.F.); +#121049 = FACE_BOUND('',#121050,.T.); +#121050 = EDGE_LOOP('',(#121051,#121086,#121109,#121136)); +#121051 = ORIENTED_EDGE('',*,*,#121052,.F.); +#121052 = EDGE_CURVE('',#121053,#121055,#121057,.T.); +#121053 = VERTEX_POINT('',#121054); +#121054 = CARTESIAN_POINT('',(-1.,7.15,-0.208196358798)); +#121055 = VERTEX_POINT('',#121056); +#121056 = CARTESIAN_POINT('',(-1.,7.35,-0.208196358798)); +#121057 = SURFACE_CURVE('',#121058,(#121062,#121074),.PCURVE_S1.); +#121058 = LINE('',#121059,#121060); +#121059 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#121060 = VECTOR('',#121061,1.); +#121061 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121062 = PCURVE('',#121063,#121068); +#121063 = PLANE('',#121064); +#121064 = AXIS2_PLACEMENT_3D('',#121065,#121066,#121067); +#121065 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#121066 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#121067 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121068 = DEFINITIONAL_REPRESENTATION('',(#121069),#121073); +#121069 = LINE('',#121070,#121071); +#121070 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#121071 = VECTOR('',#121072,1.); +#121072 = DIRECTION('',(4.440892098501E-016,1.)); +#121073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121074 = PCURVE('',#121075,#121080); +#121075 = PLANE('',#121076); +#121076 = AXIS2_PLACEMENT_3D('',#121077,#121078,#121079); +#121077 = CARTESIAN_POINT('',(-1.,7.25,-0.258196742327)); +#121078 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#121079 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121080 = DEFINITIONAL_REPRESENTATION('',(#121081),#121085); +#121081 = LINE('',#121082,#121083); +#121082 = CARTESIAN_POINT('',(-2.75,5.000038352949E-002)); +#121083 = VECTOR('',#121084,1.); +#121084 = DIRECTION('',(-1.,0.E+000)); +#121085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121086 = ORIENTED_EDGE('',*,*,#121087,.F.); +#121087 = EDGE_CURVE('',#121088,#121053,#121090,.T.); +#121088 = VERTEX_POINT('',#121089); +#121089 = CARTESIAN_POINT('',(-0.740726081328,7.15,-0.208196358798)); +#121090 = SURFACE_CURVE('',#121091,(#121095,#121102),.PCURVE_S1.); +#121091 = LINE('',#121092,#121093); +#121092 = CARTESIAN_POINT('',(-0.740726081328,7.15,-0.208196358798)); +#121093 = VECTOR('',#121094,1.); +#121094 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121095 = PCURVE('',#121063,#121096); +#121096 = DEFINITIONAL_REPRESENTATION('',(#121097),#121101); +#121097 = LINE('',#121098,#121099); +#121098 = CARTESIAN_POINT('',(-1.33226762955E-015,-2.85)); +#121099 = VECTOR('',#121100,1.); +#121100 = DIRECTION('',(1.,0.E+000)); +#121101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121102 = PCURVE('',#93089,#121103); +#121103 = DEFINITIONAL_REPRESENTATION('',(#121104),#121108); +#121104 = LINE('',#121105,#121106); +#121105 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#121106 = VECTOR('',#121107,1.); +#121107 = DIRECTION('',(0.E+000,-1.)); +#121108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121109 = ORIENTED_EDGE('',*,*,#121110,.F.); +#121110 = EDGE_CURVE('',#121111,#121088,#121113,.T.); +#121111 = VERTEX_POINT('',#121112); +#121112 = CARTESIAN_POINT('',(-0.740726081328,7.35,-0.208196358798)); +#121113 = SURFACE_CURVE('',#121114,(#121118,#121125),.PCURVE_S1.); +#121114 = LINE('',#121115,#121116); +#121115 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#121116 = VECTOR('',#121117,1.); +#121117 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121118 = PCURVE('',#121063,#121119); +#121119 = DEFINITIONAL_REPRESENTATION('',(#121120),#121124); +#121120 = LINE('',#121121,#121122); +#121121 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121122 = VECTOR('',#121123,1.); +#121123 = DIRECTION('',(-4.440892098501E-016,-1.)); +#121124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121125 = PCURVE('',#121126,#121131); +#121126 = CYLINDRICAL_SURFACE('',#121127,0.208574704164); +#121127 = AXIS2_PLACEMENT_3D('',#121128,#121129,#121130); +#121128 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#121129 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121130 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121131 = DEFINITIONAL_REPRESENTATION('',(#121132),#121135); +#121132 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121133,#121134), + .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); +#121133 = CARTESIAN_POINT('',(4.772630242227,-2.65)); +#121134 = CARTESIAN_POINT('',(4.772630242227,-2.85)); +#121135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121136 = ORIENTED_EDGE('',*,*,#121137,.T.); +#121137 = EDGE_CURVE('',#121111,#121055,#121138,.T.); +#121138 = SURFACE_CURVE('',#121139,(#121143,#121150),.PCURVE_S1.); +#121139 = LINE('',#121140,#121141); +#121140 = CARTESIAN_POINT('',(-0.740726081328,7.35,-0.208196358798)); +#121141 = VECTOR('',#121142,1.); +#121142 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121143 = PCURVE('',#121063,#121144); +#121144 = DEFINITIONAL_REPRESENTATION('',(#121145),#121149); +#121145 = LINE('',#121146,#121147); +#121146 = CARTESIAN_POINT('',(-1.110223024625E-015,-2.65)); +#121147 = VECTOR('',#121148,1.); +#121148 = DIRECTION('',(1.,0.E+000)); +#121149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121150 = PCURVE('',#93145,#121151); +#121151 = DEFINITIONAL_REPRESENTATION('',(#121152),#121156); +#121152 = LINE('',#121153,#121154); +#121153 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#121154 = VECTOR('',#121155,1.); +#121155 = DIRECTION('',(0.E+000,-1.)); +#121156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121157 = ADVANCED_FACE('',(#121158),#121172,.F.); +#121158 = FACE_BOUND('',#121159,.T.); +#121159 = EDGE_LOOP('',(#121160,#121190,#121213,#121240)); +#121160 = ORIENTED_EDGE('',*,*,#121161,.F.); +#121161 = EDGE_CURVE('',#121162,#121164,#121166,.T.); +#121162 = VERTEX_POINT('',#121163); +#121163 = CARTESIAN_POINT('',(-1.,7.35,-0.308197125857)); +#121164 = VERTEX_POINT('',#121165); +#121165 = CARTESIAN_POINT('',(-1.,7.15,-0.308197125857)); +#121166 = SURFACE_CURVE('',#121167,(#121171,#121183),.PCURVE_S1.); +#121167 = LINE('',#121168,#121169); +#121168 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#121169 = VECTOR('',#121170,1.); +#121170 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121171 = PCURVE('',#121172,#121177); +#121172 = PLANE('',#121173); +#121173 = AXIS2_PLACEMENT_3D('',#121174,#121175,#121176); +#121174 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#121175 = DIRECTION('',(0.E+000,0.E+000,1.)); +#121176 = DIRECTION('',(1.,0.E+000,0.E+000)); +#121177 = DEFINITIONAL_REPRESENTATION('',(#121178),#121182); +#121178 = LINE('',#121179,#121180); +#121179 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#121180 = VECTOR('',#121181,1.); +#121181 = DIRECTION('',(4.440892098501E-016,-1.)); +#121182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121183 = PCURVE('',#121075,#121184); +#121184 = DEFINITIONAL_REPRESENTATION('',(#121185),#121189); +#121185 = LINE('',#121186,#121187); +#121186 = CARTESIAN_POINT('',(-2.75,-5.000038352949E-002)); +#121187 = VECTOR('',#121188,1.); +#121188 = DIRECTION('',(1.,0.E+000)); +#121189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121190 = ORIENTED_EDGE('',*,*,#121191,.F.); +#121191 = EDGE_CURVE('',#121192,#121162,#121194,.T.); +#121192 = VERTEX_POINT('',#121193); +#121193 = CARTESIAN_POINT('',(-0.74341632541,7.35,-0.308197125857)); +#121194 = SURFACE_CURVE('',#121195,(#121199,#121206),.PCURVE_S1.); +#121195 = LINE('',#121196,#121197); +#121196 = CARTESIAN_POINT('',(-0.74341632541,7.35,-0.308197125857)); +#121197 = VECTOR('',#121198,1.); +#121198 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121199 = PCURVE('',#121172,#121200); +#121200 = DEFINITIONAL_REPRESENTATION('',(#121201),#121205); +#121201 = LINE('',#121202,#121203); +#121202 = CARTESIAN_POINT('',(1.110223024625E-015,-2.65)); +#121203 = VECTOR('',#121204,1.); +#121204 = DIRECTION('',(-1.,0.E+000)); +#121205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121206 = PCURVE('',#93145,#121207); +#121207 = DEFINITIONAL_REPRESENTATION('',(#121208),#121212); +#121208 = LINE('',#121209,#121210); +#121209 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#121210 = VECTOR('',#121211,1.); +#121211 = DIRECTION('',(0.E+000,-1.)); +#121212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121213 = ORIENTED_EDGE('',*,*,#121214,.F.); +#121214 = EDGE_CURVE('',#121215,#121192,#121217,.T.); +#121215 = VERTEX_POINT('',#121216); +#121216 = CARTESIAN_POINT('',(-0.74341632541,7.15,-0.308197125857)); +#121217 = SURFACE_CURVE('',#121218,(#121222,#121229),.PCURVE_S1.); +#121218 = LINE('',#121219,#121220); +#121219 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#121220 = VECTOR('',#121221,1.); +#121221 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121222 = PCURVE('',#121172,#121223); +#121223 = DEFINITIONAL_REPRESENTATION('',(#121224),#121228); +#121224 = LINE('',#121225,#121226); +#121225 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121226 = VECTOR('',#121227,1.); +#121227 = DIRECTION('',(-4.440892098501E-016,1.)); +#121228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121229 = PCURVE('',#121230,#121235); +#121230 = CYLINDRICAL_SURFACE('',#121231,0.308574064194); +#121231 = AXIS2_PLACEMENT_3D('',#121232,#121233,#121234); +#121232 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#121233 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121234 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121235 = DEFINITIONAL_REPRESENTATION('',(#121236),#121239); +#121236 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121237,#121238), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#118845 = CARTESIAN_POINT('',(4.761821717947,-2.85)); -#118846 = CARTESIAN_POINT('',(4.761821717947,-2.65)); -#118847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118848 = ORIENTED_EDGE('',*,*,#118849,.T.); -#118849 = EDGE_CURVE('',#118823,#118772,#118850,.T.); -#118850 = SURFACE_CURVE('',#118851,(#118855,#118862),.PCURVE_S1.); -#118851 = LINE('',#118852,#118853); -#118852 = CARTESIAN_POINT('',(-0.74341632541,7.15,-0.308197125857)); -#118853 = VECTOR('',#118854,1.); -#118854 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#118855 = PCURVE('',#118780,#118856); -#118856 = DEFINITIONAL_REPRESENTATION('',(#118857),#118861); -#118857 = LINE('',#118858,#118859); -#118858 = CARTESIAN_POINT('',(1.33226762955E-015,-2.85)); -#118859 = VECTOR('',#118860,1.); -#118860 = DIRECTION('',(-1.,0.E+000)); -#118861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118862 = PCURVE('',#90697,#118863); -#118863 = DEFINITIONAL_REPRESENTATION('',(#118864),#118868); -#118864 = LINE('',#118865,#118866); -#118865 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#118866 = VECTOR('',#118867,1.); -#118867 = DIRECTION('',(0.E+000,-1.)); -#118868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118869 = ADVANCED_FACE('',(#118870),#118734,.F.); -#118870 = FACE_BOUND('',#118871,.F.); -#118871 = EDGE_LOOP('',(#118872,#118895,#118922,#118947)); -#118872 = ORIENTED_EDGE('',*,*,#118873,.F.); -#118873 = EDGE_CURVE('',#118874,#118719,#118876,.T.); -#118874 = VERTEX_POINT('',#118875); -#118875 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.E+000)); -#118876 = SURFACE_CURVE('',#118877,(#118882,#118888),.PCURVE_S1.); -#118877 = CIRCLE('',#118878,0.208574704164); -#118878 = AXIS2_PLACEMENT_3D('',#118879,#118880,#118881); -#118879 = CARTESIAN_POINT('',(-0.728168876214,7.35,2.640924866458E-017) - ); -#118880 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118881 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118882 = PCURVE('',#118734,#118883); -#118883 = DEFINITIONAL_REPRESENTATION('',(#118884),#118887); -#118884 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118885,#118886), +#121237 = CARTESIAN_POINT('',(4.761821717947,-2.85)); +#121238 = CARTESIAN_POINT('',(4.761821717947,-2.65)); +#121239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121240 = ORIENTED_EDGE('',*,*,#121241,.T.); +#121241 = EDGE_CURVE('',#121215,#121164,#121242,.T.); +#121242 = SURFACE_CURVE('',#121243,(#121247,#121254),.PCURVE_S1.); +#121243 = LINE('',#121244,#121245); +#121244 = CARTESIAN_POINT('',(-0.74341632541,7.15,-0.308197125857)); +#121245 = VECTOR('',#121246,1.); +#121246 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121247 = PCURVE('',#121172,#121248); +#121248 = DEFINITIONAL_REPRESENTATION('',(#121249),#121253); +#121249 = LINE('',#121250,#121251); +#121250 = CARTESIAN_POINT('',(1.33226762955E-015,-2.85)); +#121251 = VECTOR('',#121252,1.); +#121252 = DIRECTION('',(-1.,0.E+000)); +#121253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121254 = PCURVE('',#93089,#121255); +#121255 = DEFINITIONAL_REPRESENTATION('',(#121256),#121260); +#121256 = LINE('',#121257,#121258); +#121257 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#121258 = VECTOR('',#121259,1.); +#121259 = DIRECTION('',(0.E+000,-1.)); +#121260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121261 = ADVANCED_FACE('',(#121262),#121126,.F.); +#121262 = FACE_BOUND('',#121263,.F.); +#121263 = EDGE_LOOP('',(#121264,#121287,#121314,#121339)); +#121264 = ORIENTED_EDGE('',*,*,#121265,.F.); +#121265 = EDGE_CURVE('',#121266,#121111,#121268,.T.); +#121266 = VERTEX_POINT('',#121267); +#121267 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.E+000)); +#121268 = SURFACE_CURVE('',#121269,(#121274,#121280),.PCURVE_S1.); +#121269 = CIRCLE('',#121270,0.208574704164); +#121270 = AXIS2_PLACEMENT_3D('',#121271,#121272,#121273); +#121271 = CARTESIAN_POINT('',(-0.728168876214,7.35,2.640924866458E-017) + ); +#121272 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121273 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121274 = PCURVE('',#121126,#121275); +#121275 = DEFINITIONAL_REPRESENTATION('',(#121276),#121279); +#121276 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121277,#121278), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#118885 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#118886 = CARTESIAN_POINT('',(4.772630242227,-2.65)); -#118887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118888 = PCURVE('',#90753,#118889); -#118889 = DEFINITIONAL_REPRESENTATION('',(#118890),#118894); -#118890 = CIRCLE('',#118891,0.208574704164); -#118891 = AXIS2_PLACEMENT_2D('',#118892,#118893); -#118892 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#118893 = DIRECTION('',(0.E+000,-1.)); -#118894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118895 = ORIENTED_EDGE('',*,*,#118896,.F.); -#118896 = EDGE_CURVE('',#118897,#118874,#118899,.T.); -#118897 = VERTEX_POINT('',#118898); -#118898 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.E+000)); -#118899 = SURFACE_CURVE('',#118900,(#118904,#118910),.PCURVE_S1.); -#118900 = LINE('',#118901,#118902); -#118901 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#118902 = VECTOR('',#118903,1.); -#118903 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118904 = PCURVE('',#118734,#118905); -#118905 = DEFINITIONAL_REPRESENTATION('',(#118906),#118909); -#118906 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118907,#118908), +#121277 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#121278 = CARTESIAN_POINT('',(4.772630242227,-2.65)); +#121279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121280 = PCURVE('',#93145,#121281); +#121281 = DEFINITIONAL_REPRESENTATION('',(#121282),#121286); +#121282 = CIRCLE('',#121283,0.208574704164); +#121283 = AXIS2_PLACEMENT_2D('',#121284,#121285); +#121284 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#121285 = DIRECTION('',(0.E+000,-1.)); +#121286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121287 = ORIENTED_EDGE('',*,*,#121288,.F.); +#121288 = EDGE_CURVE('',#121289,#121266,#121291,.T.); +#121289 = VERTEX_POINT('',#121290); +#121290 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.E+000)); +#121291 = SURFACE_CURVE('',#121292,(#121296,#121302),.PCURVE_S1.); +#121292 = LINE('',#121293,#121294); +#121293 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#121294 = VECTOR('',#121295,1.); +#121295 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121296 = PCURVE('',#121126,#121297); +#121297 = DEFINITIONAL_REPRESENTATION('',(#121298),#121301); +#121298 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121299,#121300), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#118907 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#118908 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#118909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118910 = PCURVE('',#118911,#118916); -#118911 = PLANE('',#118912); -#118912 = AXIS2_PLACEMENT_3D('',#118913,#118914,#118915); -#118913 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#118914 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#118915 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#118916 = DEFINITIONAL_REPRESENTATION('',(#118917),#118921); -#118917 = LINE('',#118918,#118919); -#118918 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#118919 = VECTOR('',#118920,1.); -#118920 = DIRECTION('',(-1.,0.E+000)); -#118921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118922 = ORIENTED_EDGE('',*,*,#118923,.T.); -#118923 = EDGE_CURVE('',#118897,#118696,#118924,.T.); -#118924 = SURFACE_CURVE('',#118925,(#118930,#118936),.PCURVE_S1.); -#118925 = CIRCLE('',#118926,0.208574704164); -#118926 = AXIS2_PLACEMENT_3D('',#118927,#118928,#118929); -#118927 = CARTESIAN_POINT('',(-0.728168876214,7.15,2.640924866458E-017) - ); -#118928 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118929 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118930 = PCURVE('',#118734,#118931); -#118931 = DEFINITIONAL_REPRESENTATION('',(#118932),#118935); -#118932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118933,#118934), +#121299 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#121300 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#121301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121302 = PCURVE('',#121303,#121308); +#121303 = PLANE('',#121304); +#121304 = AXIS2_PLACEMENT_3D('',#121305,#121306,#121307); +#121305 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#121306 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#121307 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121308 = DEFINITIONAL_REPRESENTATION('',(#121309),#121313); +#121309 = LINE('',#121310,#121311); +#121310 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#121311 = VECTOR('',#121312,1.); +#121312 = DIRECTION('',(-1.,0.E+000)); +#121313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121314 = ORIENTED_EDGE('',*,*,#121315,.T.); +#121315 = EDGE_CURVE('',#121289,#121088,#121316,.T.); +#121316 = SURFACE_CURVE('',#121317,(#121322,#121328),.PCURVE_S1.); +#121317 = CIRCLE('',#121318,0.208574704164); +#121318 = AXIS2_PLACEMENT_3D('',#121319,#121320,#121321); +#121319 = CARTESIAN_POINT('',(-0.728168876214,7.15,2.640924866458E-017) + ); +#121320 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121321 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121322 = PCURVE('',#121126,#121323); +#121323 = DEFINITIONAL_REPRESENTATION('',(#121324),#121327); +#121324 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121325,#121326), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#118933 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#118934 = CARTESIAN_POINT('',(4.772630242227,-2.85)); -#118935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121325 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#121326 = CARTESIAN_POINT('',(4.772630242227,-2.85)); +#121327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118936 = PCURVE('',#90697,#118937); -#118937 = DEFINITIONAL_REPRESENTATION('',(#118938),#118946); -#118938 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118939,#118940,#118941, - #118942,#118943,#118944,#118945),.UNSPECIFIED.,.T.,.F.) +#121328 = PCURVE('',#93089,#121329); +#121329 = DEFINITIONAL_REPRESENTATION('',(#121330),#121338); +#121330 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121331,#121332,#121333, + #121334,#121335,#121336,#121337),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118939 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#118940 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#118941 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#118942 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#118943 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#118944 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#118945 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#118946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118947 = ORIENTED_EDGE('',*,*,#118718,.F.); -#118948 = ADVANCED_FACE('',(#118949),#118838,.T.); -#118949 = FACE_BOUND('',#118950,.T.); -#118950 = EDGE_LOOP('',(#118951,#118978,#118979,#119002)); -#118951 = ORIENTED_EDGE('',*,*,#118952,.T.); -#118952 = EDGE_CURVE('',#118953,#118823,#118955,.T.); -#118953 = VERTEX_POINT('',#118954); -#118954 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.E+000)); -#118955 = SURFACE_CURVE('',#118956,(#118961,#118967),.PCURVE_S1.); -#118956 = CIRCLE('',#118957,0.308574064194); -#118957 = AXIS2_PLACEMENT_3D('',#118958,#118959,#118960); -#118958 = CARTESIAN_POINT('',(-0.728168876214,7.15,2.640924866458E-017) - ); -#118959 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118960 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118961 = PCURVE('',#118838,#118962); -#118962 = DEFINITIONAL_REPRESENTATION('',(#118963),#118966); -#118963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118964,#118965), +#121331 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#121332 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#121333 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#121334 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#121335 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#121336 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#121337 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#121338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121339 = ORIENTED_EDGE('',*,*,#121110,.F.); +#121340 = ADVANCED_FACE('',(#121341),#121230,.T.); +#121341 = FACE_BOUND('',#121342,.T.); +#121342 = EDGE_LOOP('',(#121343,#121370,#121371,#121394)); +#121343 = ORIENTED_EDGE('',*,*,#121344,.T.); +#121344 = EDGE_CURVE('',#121345,#121215,#121347,.T.); +#121345 = VERTEX_POINT('',#121346); +#121346 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.E+000)); +#121347 = SURFACE_CURVE('',#121348,(#121353,#121359),.PCURVE_S1.); +#121348 = CIRCLE('',#121349,0.308574064194); +#121349 = AXIS2_PLACEMENT_3D('',#121350,#121351,#121352); +#121350 = CARTESIAN_POINT('',(-0.728168876214,7.15,2.640924866458E-017) + ); +#121351 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121352 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121353 = PCURVE('',#121230,#121354); +#121354 = DEFINITIONAL_REPRESENTATION('',(#121355),#121358); +#121355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121356,#121357), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#118964 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#118965 = CARTESIAN_POINT('',(4.761821717947,-2.85)); -#118966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121356 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#121357 = CARTESIAN_POINT('',(4.761821717947,-2.85)); +#121358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#118967 = PCURVE('',#90697,#118968); -#118968 = DEFINITIONAL_REPRESENTATION('',(#118969),#118977); -#118969 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#118970,#118971,#118972, - #118973,#118974,#118975,#118976),.UNSPECIFIED.,.T.,.F.) +#121359 = PCURVE('',#93089,#121360); +#121360 = DEFINITIONAL_REPRESENTATION('',(#121361),#121369); +#121361 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121362,#121363,#121364, + #121365,#121366,#121367,#121368),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#118970 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#118971 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#118972 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#118973 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#118974 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#118975 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#118976 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#118977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118978 = ORIENTED_EDGE('',*,*,#118822,.T.); -#118979 = ORIENTED_EDGE('',*,*,#118980,.F.); -#118980 = EDGE_CURVE('',#118981,#118800,#118983,.T.); -#118981 = VERTEX_POINT('',#118982); -#118982 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.E+000)); -#118983 = SURFACE_CURVE('',#118984,(#118989,#118995),.PCURVE_S1.); -#118984 = CIRCLE('',#118985,0.308574064194); -#118985 = AXIS2_PLACEMENT_3D('',#118986,#118987,#118988); -#118986 = CARTESIAN_POINT('',(-0.728168876214,7.35,2.640924866458E-017) - ); -#118987 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#118988 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#118989 = PCURVE('',#118838,#118990); -#118990 = DEFINITIONAL_REPRESENTATION('',(#118991),#118994); -#118991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#118992,#118993), +#121362 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#121363 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#121364 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#121365 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#121366 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#121367 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#121368 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#121369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121370 = ORIENTED_EDGE('',*,*,#121214,.T.); +#121371 = ORIENTED_EDGE('',*,*,#121372,.F.); +#121372 = EDGE_CURVE('',#121373,#121192,#121375,.T.); +#121373 = VERTEX_POINT('',#121374); +#121374 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.E+000)); +#121375 = SURFACE_CURVE('',#121376,(#121381,#121387),.PCURVE_S1.); +#121376 = CIRCLE('',#121377,0.308574064194); +#121377 = AXIS2_PLACEMENT_3D('',#121378,#121379,#121380); +#121378 = CARTESIAN_POINT('',(-0.728168876214,7.35,2.640924866458E-017) + ); +#121379 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121380 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#121381 = PCURVE('',#121230,#121382); +#121382 = DEFINITIONAL_REPRESENTATION('',(#121383),#121386); +#121383 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121384,#121385), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#118992 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#118993 = CARTESIAN_POINT('',(4.761821717947,-2.65)); -#118994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#118995 = PCURVE('',#90753,#118996); -#118996 = DEFINITIONAL_REPRESENTATION('',(#118997),#119001); -#118997 = CIRCLE('',#118998,0.308574064194); -#118998 = AXIS2_PLACEMENT_2D('',#118999,#119000); -#118999 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#119000 = DIRECTION('',(0.E+000,-1.)); -#119001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119002 = ORIENTED_EDGE('',*,*,#119003,.T.); -#119003 = EDGE_CURVE('',#118981,#118953,#119004,.T.); -#119004 = SURFACE_CURVE('',#119005,(#119009,#119015),.PCURVE_S1.); -#119005 = LINE('',#119006,#119007); -#119006 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#119007 = VECTOR('',#119008,1.); -#119008 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119009 = PCURVE('',#118838,#119010); -#119010 = DEFINITIONAL_REPRESENTATION('',(#119011),#119014); -#119011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119012,#119013), +#121384 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#121385 = CARTESIAN_POINT('',(4.761821717947,-2.65)); +#121386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121387 = PCURVE('',#93145,#121388); +#121388 = DEFINITIONAL_REPRESENTATION('',(#121389),#121393); +#121389 = CIRCLE('',#121390,0.308574064194); +#121390 = AXIS2_PLACEMENT_2D('',#121391,#121392); +#121391 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#121392 = DIRECTION('',(0.E+000,-1.)); +#121393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121394 = ORIENTED_EDGE('',*,*,#121395,.T.); +#121395 = EDGE_CURVE('',#121373,#121345,#121396,.T.); +#121396 = SURFACE_CURVE('',#121397,(#121401,#121407),.PCURVE_S1.); +#121397 = LINE('',#121398,#121399); +#121398 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#121399 = VECTOR('',#121400,1.); +#121400 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121401 = PCURVE('',#121230,#121402); +#121402 = DEFINITIONAL_REPRESENTATION('',(#121403),#121406); +#121403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121404,#121405), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#119012 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#119013 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#119014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119015 = PCURVE('',#119016,#119021); -#119016 = PLANE('',#119017); -#119017 = AXIS2_PLACEMENT_3D('',#119018,#119019,#119020); -#119018 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#119019 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#119020 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119021 = DEFINITIONAL_REPRESENTATION('',(#119022),#119026); -#119022 = LINE('',#119023,#119024); -#119023 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#119024 = VECTOR('',#119025,1.); -#119025 = DIRECTION('',(-1.,0.E+000)); -#119026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119027 = ADVANCED_FACE('',(#119028),#119016,.T.); -#119028 = FACE_BOUND('',#119029,.T.); -#119029 = EDGE_LOOP('',(#119030,#119059,#119080,#119081)); -#119030 = ORIENTED_EDGE('',*,*,#119031,.T.); -#119031 = EDGE_CURVE('',#119032,#119034,#119036,.T.); -#119032 = VERTEX_POINT('',#119033); -#119033 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.530776333563)); -#119034 = VERTEX_POINT('',#119035); -#119035 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.530776333563)); -#119036 = SURFACE_CURVE('',#119037,(#119041,#119048),.PCURVE_S1.); -#119037 = LINE('',#119038,#119039); -#119038 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#119039 = VECTOR('',#119040,1.); -#119040 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119041 = PCURVE('',#119016,#119042); -#119042 = DEFINITIONAL_REPRESENTATION('',(#119043),#119047); -#119043 = LINE('',#119044,#119045); -#119044 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119045 = VECTOR('',#119046,1.); -#119046 = DIRECTION('',(-1.,0.E+000)); -#119047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119048 = PCURVE('',#119049,#119054); -#119049 = CYLINDRICAL_SURFACE('',#119050,0.119270391569); -#119050 = AXIS2_PLACEMENT_3D('',#119051,#119052,#119053); -#119051 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#119052 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119053 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119054 = DEFINITIONAL_REPRESENTATION('',(#119055),#119058); -#119055 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119056,#119057), +#121404 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#121405 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#121406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121407 = PCURVE('',#121408,#121413); +#121408 = PLANE('',#121409); +#121409 = AXIS2_PLACEMENT_3D('',#121410,#121411,#121412); +#121410 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#121411 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#121412 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121413 = DEFINITIONAL_REPRESENTATION('',(#121414),#121418); +#121414 = LINE('',#121415,#121416); +#121415 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#121416 = VECTOR('',#121417,1.); +#121417 = DIRECTION('',(-1.,0.E+000)); +#121418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121419 = ADVANCED_FACE('',(#121420),#121408,.T.); +#121420 = FACE_BOUND('',#121421,.T.); +#121421 = EDGE_LOOP('',(#121422,#121451,#121472,#121473)); +#121422 = ORIENTED_EDGE('',*,*,#121423,.T.); +#121423 = EDGE_CURVE('',#121424,#121426,#121428,.T.); +#121424 = VERTEX_POINT('',#121425); +#121425 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.530776333563)); +#121426 = VERTEX_POINT('',#121427); +#121427 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.530776333563)); +#121428 = SURFACE_CURVE('',#121429,(#121433,#121440),.PCURVE_S1.); +#121429 = LINE('',#121430,#121431); +#121430 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#121431 = VECTOR('',#121432,1.); +#121432 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121433 = PCURVE('',#121408,#121434); +#121434 = DEFINITIONAL_REPRESENTATION('',(#121435),#121439); +#121435 = LINE('',#121436,#121437); +#121436 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121437 = VECTOR('',#121438,1.); +#121438 = DIRECTION('',(-1.,0.E+000)); +#121439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121440 = PCURVE('',#121441,#121446); +#121441 = CYLINDRICAL_SURFACE('',#121442,0.119270391569); +#121442 = AXIS2_PLACEMENT_3D('',#121443,#121444,#121445); +#121443 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#121444 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121445 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121446 = DEFINITIONAL_REPRESENTATION('',(#121447),#121450); +#121447 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121448,#121449), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#119056 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#119057 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#119058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119059 = ORIENTED_EDGE('',*,*,#119060,.T.); -#119060 = EDGE_CURVE('',#119034,#118953,#119061,.T.); -#119061 = SURFACE_CURVE('',#119062,(#119066,#119073),.PCURVE_S1.); -#119062 = LINE('',#119063,#119064); -#119063 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.530776333563)); -#119064 = VECTOR('',#119065,1.); -#119065 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119066 = PCURVE('',#119016,#119067); -#119067 = DEFINITIONAL_REPRESENTATION('',(#119068),#119072); -#119068 = LINE('',#119069,#119070); -#119069 = CARTESIAN_POINT('',(-2.85,1.133910970711E-033)); -#119070 = VECTOR('',#119071,1.); -#119071 = DIRECTION('',(4.535643882845E-032,-1.)); -#119072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119073 = PCURVE('',#90697,#119074); -#119074 = DEFINITIONAL_REPRESENTATION('',(#119075),#119079); -#119075 = LINE('',#119076,#119077); -#119076 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#119077 = VECTOR('',#119078,1.); -#119078 = DIRECTION('',(1.,-1.021336205033E-016)); -#119079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121448 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#121449 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#121450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121451 = ORIENTED_EDGE('',*,*,#121452,.T.); +#121452 = EDGE_CURVE('',#121426,#121345,#121453,.T.); +#121453 = SURFACE_CURVE('',#121454,(#121458,#121465),.PCURVE_S1.); +#121454 = LINE('',#121455,#121456); +#121455 = CARTESIAN_POINT('',(-0.419594812019,7.15,0.530776333563)); +#121456 = VECTOR('',#121457,1.); +#121457 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#121458 = PCURVE('',#121408,#121459); +#121459 = DEFINITIONAL_REPRESENTATION('',(#121460),#121464); +#121460 = LINE('',#121461,#121462); +#121461 = CARTESIAN_POINT('',(-2.85,1.133910970711E-033)); +#121462 = VECTOR('',#121463,1.); +#121463 = DIRECTION('',(4.535643882845E-032,-1.)); +#121464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121465 = PCURVE('',#93089,#121466); +#121466 = DEFINITIONAL_REPRESENTATION('',(#121467),#121471); +#121467 = LINE('',#121468,#121469); +#121468 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#121469 = VECTOR('',#121470,1.); +#121470 = DIRECTION('',(1.,-1.021336205033E-016)); +#121471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119080 = ORIENTED_EDGE('',*,*,#119003,.F.); -#119081 = ORIENTED_EDGE('',*,*,#119082,.F.); -#119082 = EDGE_CURVE('',#119032,#118981,#119083,.T.); -#119083 = SURFACE_CURVE('',#119084,(#119088,#119095),.PCURVE_S1.); -#119084 = LINE('',#119085,#119086); -#119085 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.530776333563)); -#119086 = VECTOR('',#119087,1.); -#119087 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119088 = PCURVE('',#119016,#119089); -#119089 = DEFINITIONAL_REPRESENTATION('',(#119090),#119094); -#119090 = LINE('',#119091,#119092); -#119091 = CARTESIAN_POINT('',(-2.65,-1.133910970711E-033)); -#119092 = VECTOR('',#119093,1.); -#119093 = DIRECTION('',(4.535643882845E-032,-1.)); -#119094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119095 = PCURVE('',#90753,#119096); -#119096 = DEFINITIONAL_REPRESENTATION('',(#119097),#119101); -#119097 = LINE('',#119098,#119099); -#119098 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#119099 = VECTOR('',#119100,1.); -#119100 = DIRECTION('',(-1.,-1.021336205033E-016)); -#119101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119102 = ADVANCED_FACE('',(#119103),#118911,.T.); -#119103 = FACE_BOUND('',#119104,.T.); -#119104 = EDGE_LOOP('',(#119105,#119134,#119155,#119156)); -#119105 = ORIENTED_EDGE('',*,*,#119106,.T.); -#119106 = EDGE_CURVE('',#119107,#119109,#119111,.T.); -#119107 = VERTEX_POINT('',#119108); -#119108 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.530776333563)); -#119109 = VERTEX_POINT('',#119110); -#119110 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.530776333563)); -#119111 = SURFACE_CURVE('',#119112,(#119116,#119123),.PCURVE_S1.); -#119112 = LINE('',#119113,#119114); -#119113 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#119114 = VECTOR('',#119115,1.); -#119115 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119116 = PCURVE('',#118911,#119117); -#119117 = DEFINITIONAL_REPRESENTATION('',(#119118),#119122); -#119118 = LINE('',#119119,#119120); -#119119 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119120 = VECTOR('',#119121,1.); -#119121 = DIRECTION('',(-1.,0.E+000)); -#119122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119123 = PCURVE('',#119124,#119129); -#119124 = CYLINDRICAL_SURFACE('',#119125,0.2192697516); -#119125 = AXIS2_PLACEMENT_3D('',#119126,#119127,#119128); -#119126 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#119127 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119128 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119129 = DEFINITIONAL_REPRESENTATION('',(#119130),#119133); -#119130 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119131,#119132), +#121472 = ORIENTED_EDGE('',*,*,#121395,.F.); +#121473 = ORIENTED_EDGE('',*,*,#121474,.F.); +#121474 = EDGE_CURVE('',#121424,#121373,#121475,.T.); +#121475 = SURFACE_CURVE('',#121476,(#121480,#121487),.PCURVE_S1.); +#121476 = LINE('',#121477,#121478); +#121477 = CARTESIAN_POINT('',(-0.419594812019,7.35,0.530776333563)); +#121478 = VECTOR('',#121479,1.); +#121479 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#121480 = PCURVE('',#121408,#121481); +#121481 = DEFINITIONAL_REPRESENTATION('',(#121482),#121486); +#121482 = LINE('',#121483,#121484); +#121483 = CARTESIAN_POINT('',(-2.65,-1.133910970711E-033)); +#121484 = VECTOR('',#121485,1.); +#121485 = DIRECTION('',(4.535643882845E-032,-1.)); +#121486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121487 = PCURVE('',#93145,#121488); +#121488 = DEFINITIONAL_REPRESENTATION('',(#121489),#121493); +#121489 = LINE('',#121490,#121491); +#121490 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#121491 = VECTOR('',#121492,1.); +#121492 = DIRECTION('',(-1.,-1.021336205033E-016)); +#121493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121494 = ADVANCED_FACE('',(#121495),#121303,.T.); +#121495 = FACE_BOUND('',#121496,.T.); +#121496 = EDGE_LOOP('',(#121497,#121526,#121547,#121548)); +#121497 = ORIENTED_EDGE('',*,*,#121498,.T.); +#121498 = EDGE_CURVE('',#121499,#121501,#121503,.T.); +#121499 = VERTEX_POINT('',#121500); +#121500 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.530776333563)); +#121501 = VERTEX_POINT('',#121502); +#121502 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.530776333563)); +#121503 = SURFACE_CURVE('',#121504,(#121508,#121515),.PCURVE_S1.); +#121504 = LINE('',#121505,#121506); +#121505 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#121506 = VECTOR('',#121507,1.); +#121507 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121508 = PCURVE('',#121303,#121509); +#121509 = DEFINITIONAL_REPRESENTATION('',(#121510),#121514); +#121510 = LINE('',#121511,#121512); +#121511 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121512 = VECTOR('',#121513,1.); +#121513 = DIRECTION('',(-1.,0.E+000)); +#121514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121515 = PCURVE('',#121516,#121521); +#121516 = CYLINDRICAL_SURFACE('',#121517,0.2192697516); +#121517 = AXIS2_PLACEMENT_3D('',#121518,#121519,#121520); +#121518 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#121519 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121520 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121521 = DEFINITIONAL_REPRESENTATION('',(#121522),#121525); +#121522 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121523,#121524), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#119131 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#119132 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#119133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119134 = ORIENTED_EDGE('',*,*,#119135,.T.); -#119135 = EDGE_CURVE('',#119109,#118874,#119136,.T.); -#119136 = SURFACE_CURVE('',#119137,(#119141,#119148),.PCURVE_S1.); -#119137 = LINE('',#119138,#119139); -#119138 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.530776333563)); -#119139 = VECTOR('',#119140,1.); -#119140 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119141 = PCURVE('',#118911,#119142); -#119142 = DEFINITIONAL_REPRESENTATION('',(#119143),#119147); -#119143 = LINE('',#119144,#119145); -#119144 = CARTESIAN_POINT('',(2.65,4.535643882845E-033)); -#119145 = VECTOR('',#119146,1.); -#119146 = DIRECTION('',(-4.535643882845E-032,-1.)); -#119147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119148 = PCURVE('',#90753,#119149); -#119149 = DEFINITIONAL_REPRESENTATION('',(#119150),#119154); -#119150 = LINE('',#119151,#119152); -#119151 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#119152 = VECTOR('',#119153,1.); -#119153 = DIRECTION('',(-1.,-1.021336205033E-016)); -#119154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119155 = ORIENTED_EDGE('',*,*,#118896,.F.); -#119156 = ORIENTED_EDGE('',*,*,#119157,.F.); -#119157 = EDGE_CURVE('',#119107,#118897,#119158,.T.); -#119158 = SURFACE_CURVE('',#119159,(#119163,#119170),.PCURVE_S1.); -#119159 = LINE('',#119160,#119161); -#119160 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.530776333563)); -#119161 = VECTOR('',#119162,1.); -#119162 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119163 = PCURVE('',#118911,#119164); -#119164 = DEFINITIONAL_REPRESENTATION('',(#119165),#119169); -#119165 = LINE('',#119166,#119167); -#119166 = CARTESIAN_POINT('',(2.85,-4.535643882845E-033)); -#119167 = VECTOR('',#119168,1.); -#119168 = DIRECTION('',(-4.535643882845E-032,-1.)); -#119169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119170 = PCURVE('',#90697,#119171); -#119171 = DEFINITIONAL_REPRESENTATION('',(#119172),#119176); -#119172 = LINE('',#119173,#119174); -#119173 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#119174 = VECTOR('',#119175,1.); -#119175 = DIRECTION('',(1.,-1.021336205033E-016)); -#119176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119177 = ADVANCED_FACE('',(#119178),#119124,.T.); -#119178 = FACE_BOUND('',#119179,.T.); -#119179 = EDGE_LOOP('',(#119180,#119181,#119204,#119249)); -#119180 = ORIENTED_EDGE('',*,*,#119106,.F.); -#119181 = ORIENTED_EDGE('',*,*,#119182,.F.); -#119182 = EDGE_CURVE('',#119183,#119107,#119185,.T.); -#119183 = VERTEX_POINT('',#119184); -#119184 = CARTESIAN_POINT('',(-0.304819755875,7.15,0.75)); -#119185 = SURFACE_CURVE('',#119186,(#119191,#119197),.PCURVE_S1.); -#119186 = CIRCLE('',#119187,0.2192697516); -#119187 = AXIS2_PLACEMENT_3D('',#119188,#119189,#119190); -#119188 = CARTESIAN_POINT('',(-0.30032442045,7.15,0.530776333563)); -#119189 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119190 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119191 = PCURVE('',#119124,#119192); -#119192 = DEFINITIONAL_REPRESENTATION('',(#119193),#119196); -#119193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119194,#119195), +#121523 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#121524 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#121525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121526 = ORIENTED_EDGE('',*,*,#121527,.T.); +#121527 = EDGE_CURVE('',#121501,#121266,#121528,.T.); +#121528 = SURFACE_CURVE('',#121529,(#121533,#121540),.PCURVE_S1.); +#121529 = LINE('',#121530,#121531); +#121530 = CARTESIAN_POINT('',(-0.51959417205,7.35,0.530776333563)); +#121531 = VECTOR('',#121532,1.); +#121532 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#121533 = PCURVE('',#121303,#121534); +#121534 = DEFINITIONAL_REPRESENTATION('',(#121535),#121539); +#121535 = LINE('',#121536,#121537); +#121536 = CARTESIAN_POINT('',(2.65,4.535643882845E-033)); +#121537 = VECTOR('',#121538,1.); +#121538 = DIRECTION('',(-4.535643882845E-032,-1.)); +#121539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121540 = PCURVE('',#93145,#121541); +#121541 = DEFINITIONAL_REPRESENTATION('',(#121542),#121546); +#121542 = LINE('',#121543,#121544); +#121543 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#121544 = VECTOR('',#121545,1.); +#121545 = DIRECTION('',(-1.,-1.021336205033E-016)); +#121546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121547 = ORIENTED_EDGE('',*,*,#121288,.F.); +#121548 = ORIENTED_EDGE('',*,*,#121549,.F.); +#121549 = EDGE_CURVE('',#121499,#121289,#121550,.T.); +#121550 = SURFACE_CURVE('',#121551,(#121555,#121562),.PCURVE_S1.); +#121551 = LINE('',#121552,#121553); +#121552 = CARTESIAN_POINT('',(-0.51959417205,7.15,0.530776333563)); +#121553 = VECTOR('',#121554,1.); +#121554 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#121555 = PCURVE('',#121303,#121556); +#121556 = DEFINITIONAL_REPRESENTATION('',(#121557),#121561); +#121557 = LINE('',#121558,#121559); +#121558 = CARTESIAN_POINT('',(2.85,-4.535643882845E-033)); +#121559 = VECTOR('',#121560,1.); +#121560 = DIRECTION('',(-4.535643882845E-032,-1.)); +#121561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121562 = PCURVE('',#93089,#121563); +#121563 = DEFINITIONAL_REPRESENTATION('',(#121564),#121568); +#121564 = LINE('',#121565,#121566); +#121565 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#121566 = VECTOR('',#121567,1.); +#121567 = DIRECTION('',(1.,-1.021336205033E-016)); +#121568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121569 = ADVANCED_FACE('',(#121570),#121516,.T.); +#121570 = FACE_BOUND('',#121571,.T.); +#121571 = EDGE_LOOP('',(#121572,#121573,#121596,#121641)); +#121572 = ORIENTED_EDGE('',*,*,#121498,.F.); +#121573 = ORIENTED_EDGE('',*,*,#121574,.F.); +#121574 = EDGE_CURVE('',#121575,#121499,#121577,.T.); +#121575 = VERTEX_POINT('',#121576); +#121576 = CARTESIAN_POINT('',(-0.304819755875,7.15,0.75)); +#121577 = SURFACE_CURVE('',#121578,(#121583,#121589),.PCURVE_S1.); +#121578 = CIRCLE('',#121579,0.2192697516); +#121579 = AXIS2_PLACEMENT_3D('',#121580,#121581,#121582); +#121580 = CARTESIAN_POINT('',(-0.30032442045,7.15,0.530776333563)); +#121581 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121582 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121583 = PCURVE('',#121516,#121584); +#121584 = DEFINITIONAL_REPRESENTATION('',(#121585),#121588); +#121585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121586,#121587), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#119194 = CARTESIAN_POINT('',(1.591299156552,2.85)); -#119195 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#119196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119197 = PCURVE('',#90697,#119198); -#119198 = DEFINITIONAL_REPRESENTATION('',(#119199),#119203); -#119199 = CIRCLE('',#119200,0.2192697516); -#119200 = AXIS2_PLACEMENT_2D('',#119201,#119202); -#119201 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#119202 = DIRECTION('',(0.E+000,1.)); -#119203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119204 = ORIENTED_EDGE('',*,*,#119205,.F.); -#119205 = EDGE_CURVE('',#119206,#119183,#119208,.T.); -#119206 = VERTEX_POINT('',#119207); -#119207 = CARTESIAN_POINT('',(-0.304819755875,7.35,0.75)); -#119208 = SURFACE_CURVE('',#119209,(#119213,#119242),.PCURVE_S1.); -#119209 = LINE('',#119210,#119211); -#119210 = CARTESIAN_POINT('',(-0.304819755875,7.15,0.75)); -#119211 = VECTOR('',#119212,1.); -#119212 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119213 = PCURVE('',#119124,#119214); -#119214 = DEFINITIONAL_REPRESENTATION('',(#119215),#119241); -#119215 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#119216,#119217,#119218, - #119219,#119220,#119221,#119222,#119223,#119224,#119225,#119226, - #119227,#119228,#119229,#119230,#119231,#119232,#119233,#119234, - #119235,#119236,#119237,#119238,#119239,#119240),.UNSPECIFIED.,.F., +#121586 = CARTESIAN_POINT('',(1.591299156552,2.85)); +#121587 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#121588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121589 = PCURVE('',#93089,#121590); +#121590 = DEFINITIONAL_REPRESENTATION('',(#121591),#121595); +#121591 = CIRCLE('',#121592,0.2192697516); +#121592 = AXIS2_PLACEMENT_2D('',#121593,#121594); +#121593 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#121594 = DIRECTION('',(0.E+000,1.)); +#121595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121596 = ORIENTED_EDGE('',*,*,#121597,.F.); +#121597 = EDGE_CURVE('',#121598,#121575,#121600,.T.); +#121598 = VERTEX_POINT('',#121599); +#121599 = CARTESIAN_POINT('',(-0.304819755875,7.35,0.75)); +#121600 = SURFACE_CURVE('',#121601,(#121605,#121634),.PCURVE_S1.); +#121601 = LINE('',#121602,#121603); +#121602 = CARTESIAN_POINT('',(-0.304819755875,7.15,0.75)); +#121603 = VECTOR('',#121604,1.); +#121604 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121605 = PCURVE('',#121516,#121606); +#121606 = DEFINITIONAL_REPRESENTATION('',(#121607),#121633); +#121607 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#121608,#121609,#121610, + #121611,#121612,#121613,#121614,#121615,#121616,#121617,#121618, + #121619,#121620,#121621,#121622,#121623,#121624,#121625,#121626, + #121627,#121628,#121629,#121630,#121631,#121632),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -146835,128 +149837,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.UNSPECIFIED.); -#119216 = CARTESIAN_POINT('',(1.591299156552,2.65)); -#119217 = CARTESIAN_POINT('',(1.591299156552,2.65303030303)); -#119218 = CARTESIAN_POINT('',(1.591299156552,2.659090909091)); -#119219 = CARTESIAN_POINT('',(1.591299156552,2.668181818182)); -#119220 = CARTESIAN_POINT('',(1.591299156552,2.677272727273)); -#119221 = CARTESIAN_POINT('',(1.591299156552,2.686363636364)); -#119222 = CARTESIAN_POINT('',(1.591299156552,2.695454545455)); -#119223 = CARTESIAN_POINT('',(1.591299156552,2.704545454545)); -#119224 = CARTESIAN_POINT('',(1.591299156552,2.713636363636)); -#119225 = CARTESIAN_POINT('',(1.591299156552,2.722727272727)); -#119226 = CARTESIAN_POINT('',(1.591299156552,2.731818181818)); -#119227 = CARTESIAN_POINT('',(1.591299156552,2.740909090909)); -#119228 = CARTESIAN_POINT('',(1.591299156552,2.75)); -#119229 = CARTESIAN_POINT('',(1.591299156552,2.759090909091)); -#119230 = CARTESIAN_POINT('',(1.591299156552,2.768181818182)); -#119231 = CARTESIAN_POINT('',(1.591299156552,2.777272727273)); -#119232 = CARTESIAN_POINT('',(1.591299156552,2.786363636364)); -#119233 = CARTESIAN_POINT('',(1.591299156552,2.795454545455)); -#119234 = CARTESIAN_POINT('',(1.591299156552,2.804545454545)); -#119235 = CARTESIAN_POINT('',(1.591299156552,2.813636363636)); -#119236 = CARTESIAN_POINT('',(1.591299156552,2.822727272727)); -#119237 = CARTESIAN_POINT('',(1.591299156552,2.831818181818)); -#119238 = CARTESIAN_POINT('',(1.591299156552,2.840909090909)); -#119239 = CARTESIAN_POINT('',(1.591299156552,2.84696969697)); -#119240 = CARTESIAN_POINT('',(1.591299156552,2.85)); -#119241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119242 = PCURVE('',#90779,#119243); -#119243 = DEFINITIONAL_REPRESENTATION('',(#119244),#119248); -#119244 = LINE('',#119245,#119246); -#119245 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#119246 = VECTOR('',#119247,1.); -#119247 = DIRECTION('',(4.440892098501E-016,-1.)); -#119248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119249 = ORIENTED_EDGE('',*,*,#119250,.T.); -#119250 = EDGE_CURVE('',#119206,#119109,#119251,.T.); -#119251 = SURFACE_CURVE('',#119252,(#119257,#119263),.PCURVE_S1.); -#119252 = CIRCLE('',#119253,0.2192697516); -#119253 = AXIS2_PLACEMENT_3D('',#119254,#119255,#119256); -#119254 = CARTESIAN_POINT('',(-0.30032442045,7.35,0.530776333563)); -#119255 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119256 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119257 = PCURVE('',#119124,#119258); -#119258 = DEFINITIONAL_REPRESENTATION('',(#119259),#119262); -#119259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119260,#119261), +#121608 = CARTESIAN_POINT('',(1.591299156552,2.65)); +#121609 = CARTESIAN_POINT('',(1.591299156552,2.65303030303)); +#121610 = CARTESIAN_POINT('',(1.591299156552,2.659090909091)); +#121611 = CARTESIAN_POINT('',(1.591299156552,2.668181818182)); +#121612 = CARTESIAN_POINT('',(1.591299156552,2.677272727273)); +#121613 = CARTESIAN_POINT('',(1.591299156552,2.686363636364)); +#121614 = CARTESIAN_POINT('',(1.591299156552,2.695454545455)); +#121615 = CARTESIAN_POINT('',(1.591299156552,2.704545454545)); +#121616 = CARTESIAN_POINT('',(1.591299156552,2.713636363636)); +#121617 = CARTESIAN_POINT('',(1.591299156552,2.722727272727)); +#121618 = CARTESIAN_POINT('',(1.591299156552,2.731818181818)); +#121619 = CARTESIAN_POINT('',(1.591299156552,2.740909090909)); +#121620 = CARTESIAN_POINT('',(1.591299156552,2.75)); +#121621 = CARTESIAN_POINT('',(1.591299156552,2.759090909091)); +#121622 = CARTESIAN_POINT('',(1.591299156552,2.768181818182)); +#121623 = CARTESIAN_POINT('',(1.591299156552,2.777272727273)); +#121624 = CARTESIAN_POINT('',(1.591299156552,2.786363636364)); +#121625 = CARTESIAN_POINT('',(1.591299156552,2.795454545455)); +#121626 = CARTESIAN_POINT('',(1.591299156552,2.804545454545)); +#121627 = CARTESIAN_POINT('',(1.591299156552,2.813636363636)); +#121628 = CARTESIAN_POINT('',(1.591299156552,2.822727272727)); +#121629 = CARTESIAN_POINT('',(1.591299156552,2.831818181818)); +#121630 = CARTESIAN_POINT('',(1.591299156552,2.840909090909)); +#121631 = CARTESIAN_POINT('',(1.591299156552,2.84696969697)); +#121632 = CARTESIAN_POINT('',(1.591299156552,2.85)); +#121633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121634 = PCURVE('',#93171,#121635); +#121635 = DEFINITIONAL_REPRESENTATION('',(#121636),#121640); +#121636 = LINE('',#121637,#121638); +#121637 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#121638 = VECTOR('',#121639,1.); +#121639 = DIRECTION('',(4.440892098501E-016,-1.)); +#121640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121641 = ORIENTED_EDGE('',*,*,#121642,.T.); +#121642 = EDGE_CURVE('',#121598,#121501,#121643,.T.); +#121643 = SURFACE_CURVE('',#121644,(#121649,#121655),.PCURVE_S1.); +#121644 = CIRCLE('',#121645,0.2192697516); +#121645 = AXIS2_PLACEMENT_3D('',#121646,#121647,#121648); +#121646 = CARTESIAN_POINT('',(-0.30032442045,7.35,0.530776333563)); +#121647 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121648 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121649 = PCURVE('',#121516,#121650); +#121650 = DEFINITIONAL_REPRESENTATION('',(#121651),#121654); +#121651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121652,#121653), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#119260 = CARTESIAN_POINT('',(1.591299156552,2.65)); -#119261 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#119262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121652 = CARTESIAN_POINT('',(1.591299156552,2.65)); +#121653 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#121654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119263 = PCURVE('',#90753,#119264); -#119264 = DEFINITIONAL_REPRESENTATION('',(#119265),#119273); -#119265 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119266,#119267,#119268, - #119269,#119270,#119271,#119272),.UNSPECIFIED.,.T.,.F.) +#121655 = PCURVE('',#93145,#121656); +#121656 = DEFINITIONAL_REPRESENTATION('',(#121657),#121665); +#121657 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121658,#121659,#121660, + #121661,#121662,#121663,#121664),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#119266 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#119267 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#119268 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#119269 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#119270 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#119271 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#119272 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#119273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119274 = ADVANCED_FACE('',(#119275),#119049,.F.); -#119275 = FACE_BOUND('',#119276,.F.); -#119276 = EDGE_LOOP('',(#119277,#119278,#119301,#119346)); -#119277 = ORIENTED_EDGE('',*,*,#119031,.T.); -#119278 = ORIENTED_EDGE('',*,*,#119279,.F.); -#119279 = EDGE_CURVE('',#119280,#119034,#119282,.T.); -#119280 = VERTEX_POINT('',#119281); -#119281 = CARTESIAN_POINT('',(-0.303662633502,7.15,0.65)); -#119282 = SURFACE_CURVE('',#119283,(#119288,#119294),.PCURVE_S1.); -#119283 = CIRCLE('',#119284,0.119270391569); -#119284 = AXIS2_PLACEMENT_3D('',#119285,#119286,#119287); -#119285 = CARTESIAN_POINT('',(-0.30032442045,7.15,0.530776333563)); -#119286 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119287 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119288 = PCURVE('',#119049,#119289); -#119289 = DEFINITIONAL_REPRESENTATION('',(#119290),#119293); -#119290 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119291,#119292), +#121658 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#121659 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#121660 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#121661 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#121662 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#121663 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#121664 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#121665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121666 = ADVANCED_FACE('',(#121667),#121441,.F.); +#121667 = FACE_BOUND('',#121668,.F.); +#121668 = EDGE_LOOP('',(#121669,#121670,#121693,#121738)); +#121669 = ORIENTED_EDGE('',*,*,#121423,.T.); +#121670 = ORIENTED_EDGE('',*,*,#121671,.F.); +#121671 = EDGE_CURVE('',#121672,#121426,#121674,.T.); +#121672 = VERTEX_POINT('',#121673); +#121673 = CARTESIAN_POINT('',(-0.303662633502,7.15,0.65)); +#121674 = SURFACE_CURVE('',#121675,(#121680,#121686),.PCURVE_S1.); +#121675 = CIRCLE('',#121676,0.119270391569); +#121676 = AXIS2_PLACEMENT_3D('',#121677,#121678,#121679); +#121677 = CARTESIAN_POINT('',(-0.30032442045,7.15,0.530776333563)); +#121678 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121679 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121680 = PCURVE('',#121441,#121681); +#121681 = DEFINITIONAL_REPRESENTATION('',(#121682),#121685); +#121682 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121683,#121684), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#119291 = CARTESIAN_POINT('',(1.598788597134,2.85)); -#119292 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#119293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119294 = PCURVE('',#90697,#119295); -#119295 = DEFINITIONAL_REPRESENTATION('',(#119296),#119300); -#119296 = CIRCLE('',#119297,0.119270391569); -#119297 = AXIS2_PLACEMENT_2D('',#119298,#119299); -#119298 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#119299 = DIRECTION('',(0.E+000,1.)); -#119300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119301 = ORIENTED_EDGE('',*,*,#119302,.T.); -#119302 = EDGE_CURVE('',#119280,#119303,#119305,.T.); -#119303 = VERTEX_POINT('',#119304); -#119304 = CARTESIAN_POINT('',(-0.303662633502,7.35,0.65)); -#119305 = SURFACE_CURVE('',#119306,(#119310,#119339),.PCURVE_S1.); -#119306 = LINE('',#119307,#119308); -#119307 = CARTESIAN_POINT('',(-0.303662633502,7.15,0.65)); -#119308 = VECTOR('',#119309,1.); -#119309 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119310 = PCURVE('',#119049,#119311); -#119311 = DEFINITIONAL_REPRESENTATION('',(#119312),#119338); -#119312 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#119313,#119314,#119315, - #119316,#119317,#119318,#119319,#119320,#119321,#119322,#119323, - #119324,#119325,#119326,#119327,#119328,#119329,#119330,#119331, - #119332,#119333,#119334,#119335,#119336,#119337),.UNSPECIFIED.,.F., +#121683 = CARTESIAN_POINT('',(1.598788597134,2.85)); +#121684 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#121685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121686 = PCURVE('',#93089,#121687); +#121687 = DEFINITIONAL_REPRESENTATION('',(#121688),#121692); +#121688 = CIRCLE('',#121689,0.119270391569); +#121689 = AXIS2_PLACEMENT_2D('',#121690,#121691); +#121690 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#121691 = DIRECTION('',(0.E+000,1.)); +#121692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121693 = ORIENTED_EDGE('',*,*,#121694,.T.); +#121694 = EDGE_CURVE('',#121672,#121695,#121697,.T.); +#121695 = VERTEX_POINT('',#121696); +#121696 = CARTESIAN_POINT('',(-0.303662633502,7.35,0.65)); +#121697 = SURFACE_CURVE('',#121698,(#121702,#121731),.PCURVE_S1.); +#121698 = LINE('',#121699,#121700); +#121699 = CARTESIAN_POINT('',(-0.303662633502,7.15,0.65)); +#121700 = VECTOR('',#121701,1.); +#121701 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121702 = PCURVE('',#121441,#121703); +#121703 = DEFINITIONAL_REPRESENTATION('',(#121704),#121730); +#121704 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#121705,#121706,#121707, + #121708,#121709,#121710,#121711,#121712,#121713,#121714,#121715, + #121716,#121717,#121718,#121719,#121720,#121721,#121722,#121723, + #121724,#121725,#121726,#121727,#121728,#121729),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -146965,956 +149967,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#119313 = CARTESIAN_POINT('',(1.598788597134,2.85)); -#119314 = CARTESIAN_POINT('',(1.598788597134,2.84696969697)); -#119315 = CARTESIAN_POINT('',(1.598788597134,2.840909090909)); -#119316 = CARTESIAN_POINT('',(1.598788597134,2.831818181818)); -#119317 = CARTESIAN_POINT('',(1.598788597134,2.822727272727)); -#119318 = CARTESIAN_POINT('',(1.598788597134,2.813636363636)); -#119319 = CARTESIAN_POINT('',(1.598788597134,2.804545454545)); -#119320 = CARTESIAN_POINT('',(1.598788597134,2.795454545455)); -#119321 = CARTESIAN_POINT('',(1.598788597134,2.786363636364)); -#119322 = CARTESIAN_POINT('',(1.598788597134,2.777272727273)); -#119323 = CARTESIAN_POINT('',(1.598788597134,2.768181818182)); -#119324 = CARTESIAN_POINT('',(1.598788597134,2.759090909091)); -#119325 = CARTESIAN_POINT('',(1.598788597134,2.75)); -#119326 = CARTESIAN_POINT('',(1.598788597134,2.740909090909)); -#119327 = CARTESIAN_POINT('',(1.598788597134,2.731818181818)); -#119328 = CARTESIAN_POINT('',(1.598788597134,2.722727272727)); -#119329 = CARTESIAN_POINT('',(1.598788597134,2.713636363636)); -#119330 = CARTESIAN_POINT('',(1.598788597134,2.704545454545)); -#119331 = CARTESIAN_POINT('',(1.598788597134,2.695454545455)); -#119332 = CARTESIAN_POINT('',(1.598788597134,2.686363636364)); -#119333 = CARTESIAN_POINT('',(1.598788597134,2.677272727273)); -#119334 = CARTESIAN_POINT('',(1.598788597134,2.668181818182)); -#119335 = CARTESIAN_POINT('',(1.598788597134,2.659090909091)); -#119336 = CARTESIAN_POINT('',(1.598788597134,2.65303030303)); -#119337 = CARTESIAN_POINT('',(1.598788597134,2.65)); -#119338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119339 = PCURVE('',#90725,#119340); -#119340 = DEFINITIONAL_REPRESENTATION('',(#119341),#119345); -#119341 = LINE('',#119342,#119343); -#119342 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#119343 = VECTOR('',#119344,1.); -#119344 = DIRECTION('',(4.440892098501E-016,1.)); -#119345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119346 = ORIENTED_EDGE('',*,*,#119347,.T.); -#119347 = EDGE_CURVE('',#119303,#119032,#119348,.T.); -#119348 = SURFACE_CURVE('',#119349,(#119354,#119360),.PCURVE_S1.); -#119349 = CIRCLE('',#119350,0.119270391569); -#119350 = AXIS2_PLACEMENT_3D('',#119351,#119352,#119353); -#119351 = CARTESIAN_POINT('',(-0.30032442045,7.35,0.530776333563)); -#119352 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119353 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119354 = PCURVE('',#119049,#119355); -#119355 = DEFINITIONAL_REPRESENTATION('',(#119356),#119359); -#119356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119357,#119358), +#121705 = CARTESIAN_POINT('',(1.598788597134,2.85)); +#121706 = CARTESIAN_POINT('',(1.598788597134,2.84696969697)); +#121707 = CARTESIAN_POINT('',(1.598788597134,2.840909090909)); +#121708 = CARTESIAN_POINT('',(1.598788597134,2.831818181818)); +#121709 = CARTESIAN_POINT('',(1.598788597134,2.822727272727)); +#121710 = CARTESIAN_POINT('',(1.598788597134,2.813636363636)); +#121711 = CARTESIAN_POINT('',(1.598788597134,2.804545454545)); +#121712 = CARTESIAN_POINT('',(1.598788597134,2.795454545455)); +#121713 = CARTESIAN_POINT('',(1.598788597134,2.786363636364)); +#121714 = CARTESIAN_POINT('',(1.598788597134,2.777272727273)); +#121715 = CARTESIAN_POINT('',(1.598788597134,2.768181818182)); +#121716 = CARTESIAN_POINT('',(1.598788597134,2.759090909091)); +#121717 = CARTESIAN_POINT('',(1.598788597134,2.75)); +#121718 = CARTESIAN_POINT('',(1.598788597134,2.740909090909)); +#121719 = CARTESIAN_POINT('',(1.598788597134,2.731818181818)); +#121720 = CARTESIAN_POINT('',(1.598788597134,2.722727272727)); +#121721 = CARTESIAN_POINT('',(1.598788597134,2.713636363636)); +#121722 = CARTESIAN_POINT('',(1.598788597134,2.704545454545)); +#121723 = CARTESIAN_POINT('',(1.598788597134,2.695454545455)); +#121724 = CARTESIAN_POINT('',(1.598788597134,2.686363636364)); +#121725 = CARTESIAN_POINT('',(1.598788597134,2.677272727273)); +#121726 = CARTESIAN_POINT('',(1.598788597134,2.668181818182)); +#121727 = CARTESIAN_POINT('',(1.598788597134,2.659090909091)); +#121728 = CARTESIAN_POINT('',(1.598788597134,2.65303030303)); +#121729 = CARTESIAN_POINT('',(1.598788597134,2.65)); +#121730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121731 = PCURVE('',#93117,#121732); +#121732 = DEFINITIONAL_REPRESENTATION('',(#121733),#121737); +#121733 = LINE('',#121734,#121735); +#121734 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#121735 = VECTOR('',#121736,1.); +#121736 = DIRECTION('',(4.440892098501E-016,1.)); +#121737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121738 = ORIENTED_EDGE('',*,*,#121739,.T.); +#121739 = EDGE_CURVE('',#121695,#121424,#121740,.T.); +#121740 = SURFACE_CURVE('',#121741,(#121746,#121752),.PCURVE_S1.); +#121741 = CIRCLE('',#121742,0.119270391569); +#121742 = AXIS2_PLACEMENT_3D('',#121743,#121744,#121745); +#121743 = CARTESIAN_POINT('',(-0.30032442045,7.35,0.530776333563)); +#121744 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121745 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#121746 = PCURVE('',#121441,#121747); +#121747 = DEFINITIONAL_REPRESENTATION('',(#121748),#121751); +#121748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121749,#121750), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#119357 = CARTESIAN_POINT('',(1.598788597134,2.65)); -#119358 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#119359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121749 = CARTESIAN_POINT('',(1.598788597134,2.65)); +#121750 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#121751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119360 = PCURVE('',#90753,#119361); -#119361 = DEFINITIONAL_REPRESENTATION('',(#119362),#119370); -#119362 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119363,#119364,#119365, - #119366,#119367,#119368,#119369),.UNSPECIFIED.,.T.,.F.) +#121752 = PCURVE('',#93145,#121753); +#121753 = DEFINITIONAL_REPRESENTATION('',(#121754),#121762); +#121754 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121755,#121756,#121757, + #121758,#121759,#121760,#121761),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#119363 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#119364 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#119365 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#119366 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#119367 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#119368 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#119369 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#119370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119371 = ADVANCED_FACE('',(#119372),#90725,.T.); -#119372 = FACE_BOUND('',#119373,.T.); -#119373 = EDGE_LOOP('',(#119374,#119395,#119396,#119417)); -#119374 = ORIENTED_EDGE('',*,*,#119375,.F.); -#119375 = EDGE_CURVE('',#119280,#90682,#119376,.T.); -#119376 = SURFACE_CURVE('',#119377,(#119381,#119388),.PCURVE_S1.); -#119377 = LINE('',#119378,#119379); -#119378 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); -#119379 = VECTOR('',#119380,1.); -#119380 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#119381 = PCURVE('',#90725,#119382); -#119382 = DEFINITIONAL_REPRESENTATION('',(#119383),#119387); -#119383 = LINE('',#119384,#119385); -#119384 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119385 = VECTOR('',#119386,1.); -#119386 = DIRECTION('',(-1.,-4.804757279354E-063)); -#119387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119388 = PCURVE('',#90697,#119389); -#119389 = DEFINITIONAL_REPRESENTATION('',(#119390),#119394); -#119390 = LINE('',#119391,#119392); -#119391 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119392 = VECTOR('',#119393,1.); -#119393 = DIRECTION('',(-3.563627120235E-016,1.)); -#119394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119395 = ORIENTED_EDGE('',*,*,#119302,.T.); -#119396 = ORIENTED_EDGE('',*,*,#119397,.T.); -#119397 = EDGE_CURVE('',#119303,#90710,#119398,.T.); -#119398 = SURFACE_CURVE('',#119399,(#119403,#119410),.PCURVE_S1.); -#119399 = LINE('',#119400,#119401); -#119400 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.65)); -#119401 = VECTOR('',#119402,1.); -#119402 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#119403 = PCURVE('',#90725,#119404); -#119404 = DEFINITIONAL_REPRESENTATION('',(#119405),#119409); -#119405 = LINE('',#119406,#119407); -#119406 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#119407 = VECTOR('',#119408,1.); -#119408 = DIRECTION('',(-1.,-4.804757279354E-063)); -#119409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119410 = PCURVE('',#90753,#119411); -#119411 = DEFINITIONAL_REPRESENTATION('',(#119412),#119416); -#119412 = LINE('',#119413,#119414); -#119413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119414 = VECTOR('',#119415,1.); -#119415 = DIRECTION('',(3.563627120235E-016,1.)); -#119416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119417 = ORIENTED_EDGE('',*,*,#90709,.F.); -#119418 = ADVANCED_FACE('',(#119419),#90753,.T.); -#119419 = FACE_BOUND('',#119420,.T.); -#119420 = EDGE_LOOP('',(#119421,#119422,#119423,#119424,#119425,#119426, - #119447,#119448,#119449,#119450,#119451,#119472)); -#119421 = ORIENTED_EDGE('',*,*,#119397,.F.); -#119422 = ORIENTED_EDGE('',*,*,#119347,.T.); -#119423 = ORIENTED_EDGE('',*,*,#119082,.T.); -#119424 = ORIENTED_EDGE('',*,*,#118980,.T.); -#119425 = ORIENTED_EDGE('',*,*,#118799,.T.); -#119426 = ORIENTED_EDGE('',*,*,#119427,.F.); -#119427 = EDGE_CURVE('',#118663,#118770,#119428,.T.); -#119428 = SURFACE_CURVE('',#119429,(#119433,#119440),.PCURVE_S1.); -#119429 = LINE('',#119430,#119431); -#119430 = CARTESIAN_POINT('',(-1.,7.35,1.159810404338E-002)); -#119431 = VECTOR('',#119432,1.); -#119432 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#119433 = PCURVE('',#90753,#119434); -#119434 = DEFINITIONAL_REPRESENTATION('',(#119435),#119439); -#119435 = LINE('',#119436,#119437); -#119436 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#119437 = VECTOR('',#119438,1.); -#119438 = DIRECTION('',(-1.,2.101748079665E-016)); -#119439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119440 = PCURVE('',#118683,#119441); -#119441 = DEFINITIONAL_REPRESENTATION('',(#119442),#119446); -#119442 = LINE('',#119443,#119444); -#119443 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#119444 = VECTOR('',#119445,1.); -#119445 = DIRECTION('',(1.194699204908E-017,-1.)); -#119446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119447 = ORIENTED_EDGE('',*,*,#118745,.F.); -#119448 = ORIENTED_EDGE('',*,*,#118873,.F.); -#119449 = ORIENTED_EDGE('',*,*,#119135,.F.); -#119450 = ORIENTED_EDGE('',*,*,#119250,.F.); -#119451 = ORIENTED_EDGE('',*,*,#119452,.T.); -#119452 = EDGE_CURVE('',#119206,#90738,#119453,.T.); -#119453 = SURFACE_CURVE('',#119454,(#119458,#119465),.PCURVE_S1.); -#119454 = LINE('',#119455,#119456); -#119455 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.75)); -#119456 = VECTOR('',#119457,1.); -#119457 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#119458 = PCURVE('',#90753,#119459); -#119459 = DEFINITIONAL_REPRESENTATION('',(#119460),#119464); -#119460 = LINE('',#119461,#119462); -#119461 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#119462 = VECTOR('',#119463,1.); -#119463 = DIRECTION('',(3.563627120235E-016,1.)); -#119464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119465 = PCURVE('',#90779,#119466); -#119466 = DEFINITIONAL_REPRESENTATION('',(#119467),#119471); -#119467 = LINE('',#119468,#119469); -#119468 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#119469 = VECTOR('',#119470,1.); -#119470 = DIRECTION('',(1.,-4.804757279354E-063)); -#119471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119472 = ORIENTED_EDGE('',*,*,#90737,.F.); -#119473 = ADVANCED_FACE('',(#119474),#90779,.T.); -#119474 = FACE_BOUND('',#119475,.T.); -#119475 = EDGE_LOOP('',(#119476,#119477,#119478,#119499)); -#119476 = ORIENTED_EDGE('',*,*,#119452,.F.); -#119477 = ORIENTED_EDGE('',*,*,#119205,.T.); -#119478 = ORIENTED_EDGE('',*,*,#119479,.T.); -#119479 = EDGE_CURVE('',#119183,#90680,#119480,.T.); -#119480 = SURFACE_CURVE('',#119481,(#119485,#119492),.PCURVE_S1.); -#119481 = LINE('',#119482,#119483); -#119482 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.75)); -#119483 = VECTOR('',#119484,1.); -#119484 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#119485 = PCURVE('',#90779,#119486); -#119486 = DEFINITIONAL_REPRESENTATION('',(#119487),#119491); -#119487 = LINE('',#119488,#119489); -#119488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119489 = VECTOR('',#119490,1.); -#119490 = DIRECTION('',(1.,-4.804757279354E-063)); -#119491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119492 = PCURVE('',#90697,#119493); -#119493 = DEFINITIONAL_REPRESENTATION('',(#119494),#119498); -#119494 = LINE('',#119495,#119496); -#119495 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#119496 = VECTOR('',#119497,1.); -#119497 = DIRECTION('',(-3.563627120235E-016,1.)); -#119498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119499 = ORIENTED_EDGE('',*,*,#90765,.F.); -#119500 = ADVANCED_FACE('',(#119501),#90697,.T.); -#119501 = FACE_BOUND('',#119502,.T.); -#119502 = EDGE_LOOP('',(#119503,#119504,#119505,#119506,#119507,#119508, - #119529,#119530,#119531,#119532,#119533,#119534)); -#119503 = ORIENTED_EDGE('',*,*,#119479,.F.); -#119504 = ORIENTED_EDGE('',*,*,#119182,.T.); -#119505 = ORIENTED_EDGE('',*,*,#119157,.T.); -#119506 = ORIENTED_EDGE('',*,*,#118923,.T.); -#119507 = ORIENTED_EDGE('',*,*,#118695,.T.); -#119508 = ORIENTED_EDGE('',*,*,#119509,.F.); -#119509 = EDGE_CURVE('',#118772,#118661,#119510,.T.); -#119510 = SURFACE_CURVE('',#119511,(#119515,#119522),.PCURVE_S1.); -#119511 = LINE('',#119512,#119513); -#119512 = CARTESIAN_POINT('',(-1.,7.15,1.159810404338E-002)); -#119513 = VECTOR('',#119514,1.); -#119514 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#119515 = PCURVE('',#90697,#119516); -#119516 = DEFINITIONAL_REPRESENTATION('',(#119517),#119521); -#119517 = LINE('',#119518,#119519); -#119518 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#119519 = VECTOR('',#119520,1.); -#119520 = DIRECTION('',(-1.,-2.101748079665E-016)); -#119521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119522 = PCURVE('',#118683,#119523); -#119523 = DEFINITIONAL_REPRESENTATION('',(#119524),#119528); -#119524 = LINE('',#119525,#119526); -#119525 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#119526 = VECTOR('',#119527,1.); -#119527 = DIRECTION('',(-1.194699204908E-017,1.)); -#119528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119529 = ORIENTED_EDGE('',*,*,#118849,.F.); -#119530 = ORIENTED_EDGE('',*,*,#118952,.F.); -#119531 = ORIENTED_EDGE('',*,*,#119060,.F.); -#119532 = ORIENTED_EDGE('',*,*,#119279,.F.); -#119533 = ORIENTED_EDGE('',*,*,#119375,.T.); -#119534 = ORIENTED_EDGE('',*,*,#90679,.F.); -#119535 = ADVANCED_FACE('',(#119536),#118683,.T.); -#119536 = FACE_BOUND('',#119537,.T.); -#119537 = EDGE_LOOP('',(#119538,#119539,#119540,#119541)); -#119538 = ORIENTED_EDGE('',*,*,#119427,.T.); -#119539 = ORIENTED_EDGE('',*,*,#118769,.T.); -#119540 = ORIENTED_EDGE('',*,*,#119509,.T.); -#119541 = ORIENTED_EDGE('',*,*,#118660,.T.); -#119542 = ADVANCED_FACE('',(#119543),#119557,.F.); -#119543 = FACE_BOUND('',#119544,.T.); -#119544 = EDGE_LOOP('',(#119545,#119580,#119603,#119630)); -#119545 = ORIENTED_EDGE('',*,*,#119546,.F.); -#119546 = EDGE_CURVE('',#119547,#119549,#119551,.T.); -#119547 = VERTEX_POINT('',#119548); -#119548 = CARTESIAN_POINT('',(-1.,7.65,-0.208196358798)); -#119549 = VERTEX_POINT('',#119550); -#119550 = CARTESIAN_POINT('',(-1.,7.85,-0.208196358798)); -#119551 = SURFACE_CURVE('',#119552,(#119556,#119568),.PCURVE_S1.); -#119552 = LINE('',#119553,#119554); -#119553 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#119554 = VECTOR('',#119555,1.); -#119555 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119556 = PCURVE('',#119557,#119562); -#119557 = PLANE('',#119558); -#119558 = AXIS2_PLACEMENT_3D('',#119559,#119560,#119561); -#119559 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#119560 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#119561 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#119562 = DEFINITIONAL_REPRESENTATION('',(#119563),#119567); -#119563 = LINE('',#119564,#119565); -#119564 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#119565 = VECTOR('',#119566,1.); -#119566 = DIRECTION('',(4.440892098501E-016,1.)); -#119567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119568 = PCURVE('',#119569,#119574); -#119569 = PLANE('',#119570); -#119570 = AXIS2_PLACEMENT_3D('',#119571,#119572,#119573); -#119571 = CARTESIAN_POINT('',(-1.,7.75,-0.258196742327)); -#119572 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#119573 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119574 = DEFINITIONAL_REPRESENTATION('',(#119575),#119579); -#119575 = LINE('',#119576,#119577); -#119576 = CARTESIAN_POINT('',(-2.25,5.000038352949E-002)); -#119577 = VECTOR('',#119578,1.); -#119578 = DIRECTION('',(-1.,0.E+000)); -#119579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119580 = ORIENTED_EDGE('',*,*,#119581,.F.); -#119581 = EDGE_CURVE('',#119582,#119547,#119584,.T.); -#119582 = VERTEX_POINT('',#119583); -#119583 = CARTESIAN_POINT('',(-0.740726081328,7.65,-0.208196358798)); -#119584 = SURFACE_CURVE('',#119585,(#119589,#119596),.PCURVE_S1.); -#119585 = LINE('',#119586,#119587); -#119586 = CARTESIAN_POINT('',(-0.740726081328,7.65,-0.208196358798)); -#119587 = VECTOR('',#119588,1.); -#119588 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#119589 = PCURVE('',#119557,#119590); -#119590 = DEFINITIONAL_REPRESENTATION('',(#119591),#119595); -#119591 = LINE('',#119592,#119593); -#119592 = CARTESIAN_POINT('',(-1.110223024625E-015,-2.35)); -#119593 = VECTOR('',#119594,1.); -#119594 = DIRECTION('',(1.,0.E+000)); -#119595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119596 = PCURVE('',#90583,#119597); -#119597 = DEFINITIONAL_REPRESENTATION('',(#119598),#119602); -#119598 = LINE('',#119599,#119600); -#119599 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#119600 = VECTOR('',#119601,1.); -#119601 = DIRECTION('',(0.E+000,-1.)); -#119602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119603 = ORIENTED_EDGE('',*,*,#119604,.F.); -#119604 = EDGE_CURVE('',#119605,#119582,#119607,.T.); -#119605 = VERTEX_POINT('',#119606); -#119606 = CARTESIAN_POINT('',(-0.740726081328,7.85,-0.208196358798)); -#119607 = SURFACE_CURVE('',#119608,(#119612,#119619),.PCURVE_S1.); -#119608 = LINE('',#119609,#119610); -#119609 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#119610 = VECTOR('',#119611,1.); -#119611 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119612 = PCURVE('',#119557,#119613); -#119613 = DEFINITIONAL_REPRESENTATION('',(#119614),#119618); -#119614 = LINE('',#119615,#119616); -#119615 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119616 = VECTOR('',#119617,1.); -#119617 = DIRECTION('',(-4.440892098501E-016,-1.)); -#119618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119619 = PCURVE('',#119620,#119625); -#119620 = CYLINDRICAL_SURFACE('',#119621,0.208574704164); -#119621 = AXIS2_PLACEMENT_3D('',#119622,#119623,#119624); -#119622 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#119623 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119624 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119625 = DEFINITIONAL_REPRESENTATION('',(#119626),#119629); -#119626 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119627,#119628), - .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#119627 = CARTESIAN_POINT('',(4.772630242227,-2.15)); -#119628 = CARTESIAN_POINT('',(4.772630242227,-2.35)); -#119629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119630 = ORIENTED_EDGE('',*,*,#119631,.T.); -#119631 = EDGE_CURVE('',#119605,#119549,#119632,.T.); -#119632 = SURFACE_CURVE('',#119633,(#119637,#119644),.PCURVE_S1.); -#119633 = LINE('',#119634,#119635); -#119634 = CARTESIAN_POINT('',(-0.740726081328,7.85,-0.208196358798)); -#119635 = VECTOR('',#119636,1.); -#119636 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#119637 = PCURVE('',#119557,#119638); -#119638 = DEFINITIONAL_REPRESENTATION('',(#119639),#119643); -#119639 = LINE('',#119640,#119641); -#119640 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.15)); -#119641 = VECTOR('',#119642,1.); -#119642 = DIRECTION('',(1.,0.E+000)); -#119643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119644 = PCURVE('',#90639,#119645); -#119645 = DEFINITIONAL_REPRESENTATION('',(#119646),#119650); -#119646 = LINE('',#119647,#119648); -#119647 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#119648 = VECTOR('',#119649,1.); -#119649 = DIRECTION('',(0.E+000,-1.)); -#119650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119651 = ADVANCED_FACE('',(#119652),#119666,.F.); -#119652 = FACE_BOUND('',#119653,.T.); -#119653 = EDGE_LOOP('',(#119654,#119684,#119707,#119734)); -#119654 = ORIENTED_EDGE('',*,*,#119655,.F.); -#119655 = EDGE_CURVE('',#119656,#119658,#119660,.T.); -#119656 = VERTEX_POINT('',#119657); -#119657 = CARTESIAN_POINT('',(-1.,7.85,-0.308197125857)); -#119658 = VERTEX_POINT('',#119659); -#119659 = CARTESIAN_POINT('',(-1.,7.65,-0.308197125857)); -#119660 = SURFACE_CURVE('',#119661,(#119665,#119677),.PCURVE_S1.); -#119661 = LINE('',#119662,#119663); -#119662 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#119663 = VECTOR('',#119664,1.); -#119664 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119665 = PCURVE('',#119666,#119671); -#119666 = PLANE('',#119667); -#119667 = AXIS2_PLACEMENT_3D('',#119668,#119669,#119670); -#119668 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#119669 = DIRECTION('',(0.E+000,0.E+000,1.)); -#119670 = DIRECTION('',(1.,0.E+000,0.E+000)); -#119671 = DEFINITIONAL_REPRESENTATION('',(#119672),#119676); -#119672 = LINE('',#119673,#119674); -#119673 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#119674 = VECTOR('',#119675,1.); -#119675 = DIRECTION('',(4.440892098501E-016,-1.)); -#119676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119677 = PCURVE('',#119569,#119678); -#119678 = DEFINITIONAL_REPRESENTATION('',(#119679),#119683); -#119679 = LINE('',#119680,#119681); -#119680 = CARTESIAN_POINT('',(-2.25,-5.000038352949E-002)); -#119681 = VECTOR('',#119682,1.); -#119682 = DIRECTION('',(1.,0.E+000)); -#119683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119684 = ORIENTED_EDGE('',*,*,#119685,.F.); -#119685 = EDGE_CURVE('',#119686,#119656,#119688,.T.); -#119686 = VERTEX_POINT('',#119687); -#119687 = CARTESIAN_POINT('',(-0.74341632541,7.85,-0.308197125857)); -#119688 = SURFACE_CURVE('',#119689,(#119693,#119700),.PCURVE_S1.); -#119689 = LINE('',#119690,#119691); -#119690 = CARTESIAN_POINT('',(-0.74341632541,7.85,-0.308197125857)); -#119691 = VECTOR('',#119692,1.); -#119692 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#119693 = PCURVE('',#119666,#119694); -#119694 = DEFINITIONAL_REPRESENTATION('',(#119695),#119699); -#119695 = LINE('',#119696,#119697); -#119696 = CARTESIAN_POINT('',(8.881784197001E-016,-2.15)); -#119697 = VECTOR('',#119698,1.); -#119698 = DIRECTION('',(-1.,0.E+000)); -#119699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#121755 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#121756 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#121757 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#121758 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#121759 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#121760 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#121761 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#121762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121763 = ADVANCED_FACE('',(#121764),#93117,.T.); +#121764 = FACE_BOUND('',#121765,.T.); +#121765 = EDGE_LOOP('',(#121766,#121787,#121788,#121809)); +#121766 = ORIENTED_EDGE('',*,*,#121767,.F.); +#121767 = EDGE_CURVE('',#121672,#93074,#121768,.T.); +#121768 = SURFACE_CURVE('',#121769,(#121773,#121780),.PCURVE_S1.); +#121769 = LINE('',#121770,#121771); +#121770 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.65)); +#121771 = VECTOR('',#121772,1.); +#121772 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#121773 = PCURVE('',#93117,#121774); +#121774 = DEFINITIONAL_REPRESENTATION('',(#121775),#121779); +#121775 = LINE('',#121776,#121777); +#121776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121777 = VECTOR('',#121778,1.); +#121778 = DIRECTION('',(-1.,-4.804757279354E-063)); +#121779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121780 = PCURVE('',#93089,#121781); +#121781 = DEFINITIONAL_REPRESENTATION('',(#121782),#121786); +#121782 = LINE('',#121783,#121784); +#121783 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121784 = VECTOR('',#121785,1.); +#121785 = DIRECTION('',(-3.563627120235E-016,1.)); +#121786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121787 = ORIENTED_EDGE('',*,*,#121694,.T.); +#121788 = ORIENTED_EDGE('',*,*,#121789,.T.); +#121789 = EDGE_CURVE('',#121695,#93102,#121790,.T.); +#121790 = SURFACE_CURVE('',#121791,(#121795,#121802),.PCURVE_S1.); +#121791 = LINE('',#121792,#121793); +#121792 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.65)); +#121793 = VECTOR('',#121794,1.); +#121794 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#121795 = PCURVE('',#93117,#121796); +#121796 = DEFINITIONAL_REPRESENTATION('',(#121797),#121801); +#121797 = LINE('',#121798,#121799); +#121798 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#121799 = VECTOR('',#121800,1.); +#121800 = DIRECTION('',(-1.,-4.804757279354E-063)); +#121801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121802 = PCURVE('',#93145,#121803); +#121803 = DEFINITIONAL_REPRESENTATION('',(#121804),#121808); +#121804 = LINE('',#121805,#121806); +#121805 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121806 = VECTOR('',#121807,1.); +#121807 = DIRECTION('',(3.563627120235E-016,1.)); +#121808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121809 = ORIENTED_EDGE('',*,*,#93101,.F.); +#121810 = ADVANCED_FACE('',(#121811),#93145,.T.); +#121811 = FACE_BOUND('',#121812,.T.); +#121812 = EDGE_LOOP('',(#121813,#121814,#121815,#121816,#121817,#121818, + #121839,#121840,#121841,#121842,#121843,#121864)); +#121813 = ORIENTED_EDGE('',*,*,#121789,.F.); +#121814 = ORIENTED_EDGE('',*,*,#121739,.T.); +#121815 = ORIENTED_EDGE('',*,*,#121474,.T.); +#121816 = ORIENTED_EDGE('',*,*,#121372,.T.); +#121817 = ORIENTED_EDGE('',*,*,#121191,.T.); +#121818 = ORIENTED_EDGE('',*,*,#121819,.F.); +#121819 = EDGE_CURVE('',#121055,#121162,#121820,.T.); +#121820 = SURFACE_CURVE('',#121821,(#121825,#121832),.PCURVE_S1.); +#121821 = LINE('',#121822,#121823); +#121822 = CARTESIAN_POINT('',(-1.,7.35,1.159810404338E-002)); +#121823 = VECTOR('',#121824,1.); +#121824 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#121825 = PCURVE('',#93145,#121826); +#121826 = DEFINITIONAL_REPRESENTATION('',(#121827),#121831); +#121827 = LINE('',#121828,#121829); +#121828 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#121829 = VECTOR('',#121830,1.); +#121830 = DIRECTION('',(-1.,2.101748079665E-016)); +#121831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121832 = PCURVE('',#121075,#121833); +#121833 = DEFINITIONAL_REPRESENTATION('',(#121834),#121838); +#121834 = LINE('',#121835,#121836); +#121835 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#121836 = VECTOR('',#121837,1.); +#121837 = DIRECTION('',(1.194699204908E-017,-1.)); +#121838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121839 = ORIENTED_EDGE('',*,*,#121137,.F.); +#121840 = ORIENTED_EDGE('',*,*,#121265,.F.); +#121841 = ORIENTED_EDGE('',*,*,#121527,.F.); +#121842 = ORIENTED_EDGE('',*,*,#121642,.F.); +#121843 = ORIENTED_EDGE('',*,*,#121844,.T.); +#121844 = EDGE_CURVE('',#121598,#93130,#121845,.T.); +#121845 = SURFACE_CURVE('',#121846,(#121850,#121857),.PCURVE_S1.); +#121846 = LINE('',#121847,#121848); +#121847 = CARTESIAN_POINT('',(-0.527847992439,7.35,0.75)); +#121848 = VECTOR('',#121849,1.); +#121849 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#121850 = PCURVE('',#93145,#121851); +#121851 = DEFINITIONAL_REPRESENTATION('',(#121852),#121856); +#121852 = LINE('',#121853,#121854); +#121853 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#121854 = VECTOR('',#121855,1.); +#121855 = DIRECTION('',(3.563627120235E-016,1.)); +#121856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121857 = PCURVE('',#93171,#121858); +#121858 = DEFINITIONAL_REPRESENTATION('',(#121859),#121863); +#121859 = LINE('',#121860,#121861); +#121860 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#121861 = VECTOR('',#121862,1.); +#121862 = DIRECTION('',(1.,-4.804757279354E-063)); +#121863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121864 = ORIENTED_EDGE('',*,*,#93129,.F.); +#121865 = ADVANCED_FACE('',(#121866),#93171,.T.); +#121866 = FACE_BOUND('',#121867,.T.); +#121867 = EDGE_LOOP('',(#121868,#121869,#121870,#121891)); +#121868 = ORIENTED_EDGE('',*,*,#121844,.F.); +#121869 = ORIENTED_EDGE('',*,*,#121597,.T.); +#121870 = ORIENTED_EDGE('',*,*,#121871,.T.); +#121871 = EDGE_CURVE('',#121575,#93072,#121872,.T.); +#121872 = SURFACE_CURVE('',#121873,(#121877,#121884),.PCURVE_S1.); +#121873 = LINE('',#121874,#121875); +#121874 = CARTESIAN_POINT('',(-0.527847992439,7.15,0.75)); +#121875 = VECTOR('',#121876,1.); +#121876 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#121877 = PCURVE('',#93171,#121878); +#121878 = DEFINITIONAL_REPRESENTATION('',(#121879),#121883); +#121879 = LINE('',#121880,#121881); +#121880 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#121881 = VECTOR('',#121882,1.); +#121882 = DIRECTION('',(1.,-4.804757279354E-063)); +#121883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121884 = PCURVE('',#93089,#121885); +#121885 = DEFINITIONAL_REPRESENTATION('',(#121886),#121890); +#121886 = LINE('',#121887,#121888); +#121887 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#121888 = VECTOR('',#121889,1.); +#121889 = DIRECTION('',(-3.563627120235E-016,1.)); +#121890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121891 = ORIENTED_EDGE('',*,*,#93157,.F.); +#121892 = ADVANCED_FACE('',(#121893),#93089,.T.); +#121893 = FACE_BOUND('',#121894,.T.); +#121894 = EDGE_LOOP('',(#121895,#121896,#121897,#121898,#121899,#121900, + #121921,#121922,#121923,#121924,#121925,#121926)); +#121895 = ORIENTED_EDGE('',*,*,#121871,.F.); +#121896 = ORIENTED_EDGE('',*,*,#121574,.T.); +#121897 = ORIENTED_EDGE('',*,*,#121549,.T.); +#121898 = ORIENTED_EDGE('',*,*,#121315,.T.); +#121899 = ORIENTED_EDGE('',*,*,#121087,.T.); +#121900 = ORIENTED_EDGE('',*,*,#121901,.F.); +#121901 = EDGE_CURVE('',#121164,#121053,#121902,.T.); +#121902 = SURFACE_CURVE('',#121903,(#121907,#121914),.PCURVE_S1.); +#121903 = LINE('',#121904,#121905); +#121904 = CARTESIAN_POINT('',(-1.,7.15,1.159810404338E-002)); +#121905 = VECTOR('',#121906,1.); +#121906 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#121907 = PCURVE('',#93089,#121908); +#121908 = DEFINITIONAL_REPRESENTATION('',(#121909),#121913); +#121909 = LINE('',#121910,#121911); +#121910 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#121911 = VECTOR('',#121912,1.); +#121912 = DIRECTION('',(-1.,-2.101748079665E-016)); +#121913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121914 = PCURVE('',#121075,#121915); +#121915 = DEFINITIONAL_REPRESENTATION('',(#121916),#121920); +#121916 = LINE('',#121917,#121918); +#121917 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#121918 = VECTOR('',#121919,1.); +#121919 = DIRECTION('',(-1.194699204908E-017,1.)); +#121920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119700 = PCURVE('',#90639,#119701); -#119701 = DEFINITIONAL_REPRESENTATION('',(#119702),#119706); -#119702 = LINE('',#119703,#119704); -#119703 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#119704 = VECTOR('',#119705,1.); -#119705 = DIRECTION('',(0.E+000,-1.)); -#119706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119707 = ORIENTED_EDGE('',*,*,#119708,.F.); -#119708 = EDGE_CURVE('',#119709,#119686,#119711,.T.); -#119709 = VERTEX_POINT('',#119710); -#119710 = CARTESIAN_POINT('',(-0.74341632541,7.65,-0.308197125857)); -#119711 = SURFACE_CURVE('',#119712,(#119716,#119723),.PCURVE_S1.); -#119712 = LINE('',#119713,#119714); -#119713 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#119714 = VECTOR('',#119715,1.); -#119715 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119716 = PCURVE('',#119666,#119717); -#119717 = DEFINITIONAL_REPRESENTATION('',(#119718),#119722); -#119718 = LINE('',#119719,#119720); -#119719 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119720 = VECTOR('',#119721,1.); -#119721 = DIRECTION('',(-4.440892098501E-016,1.)); -#119722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119723 = PCURVE('',#119724,#119729); -#119724 = CYLINDRICAL_SURFACE('',#119725,0.308574064194); -#119725 = AXIS2_PLACEMENT_3D('',#119726,#119727,#119728); -#119726 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#119727 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119728 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119729 = DEFINITIONAL_REPRESENTATION('',(#119730),#119733); -#119730 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119731,#119732), +#121921 = ORIENTED_EDGE('',*,*,#121241,.F.); +#121922 = ORIENTED_EDGE('',*,*,#121344,.F.); +#121923 = ORIENTED_EDGE('',*,*,#121452,.F.); +#121924 = ORIENTED_EDGE('',*,*,#121671,.F.); +#121925 = ORIENTED_EDGE('',*,*,#121767,.T.); +#121926 = ORIENTED_EDGE('',*,*,#93071,.F.); +#121927 = ADVANCED_FACE('',(#121928),#121075,.T.); +#121928 = FACE_BOUND('',#121929,.T.); +#121929 = EDGE_LOOP('',(#121930,#121931,#121932,#121933)); +#121930 = ORIENTED_EDGE('',*,*,#121819,.T.); +#121931 = ORIENTED_EDGE('',*,*,#121161,.T.); +#121932 = ORIENTED_EDGE('',*,*,#121901,.T.); +#121933 = ORIENTED_EDGE('',*,*,#121052,.T.); +#121934 = ADVANCED_FACE('',(#121935),#121949,.F.); +#121935 = FACE_BOUND('',#121936,.T.); +#121936 = EDGE_LOOP('',(#121937,#121972,#121995,#122022)); +#121937 = ORIENTED_EDGE('',*,*,#121938,.F.); +#121938 = EDGE_CURVE('',#121939,#121941,#121943,.T.); +#121939 = VERTEX_POINT('',#121940); +#121940 = CARTESIAN_POINT('',(-1.,7.65,-0.208196358798)); +#121941 = VERTEX_POINT('',#121942); +#121942 = CARTESIAN_POINT('',(-1.,7.85,-0.208196358798)); +#121943 = SURFACE_CURVE('',#121944,(#121948,#121960),.PCURVE_S1.); +#121944 = LINE('',#121945,#121946); +#121945 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#121946 = VECTOR('',#121947,1.); +#121947 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#121948 = PCURVE('',#121949,#121954); +#121949 = PLANE('',#121950); +#121950 = AXIS2_PLACEMENT_3D('',#121951,#121952,#121953); +#121951 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#121952 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#121953 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121954 = DEFINITIONAL_REPRESENTATION('',(#121955),#121959); +#121955 = LINE('',#121956,#121957); +#121956 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#121957 = VECTOR('',#121958,1.); +#121958 = DIRECTION('',(4.440892098501E-016,1.)); +#121959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121960 = PCURVE('',#121961,#121966); +#121961 = PLANE('',#121962); +#121962 = AXIS2_PLACEMENT_3D('',#121963,#121964,#121965); +#121963 = CARTESIAN_POINT('',(-1.,7.75,-0.258196742327)); +#121964 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#121965 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#121966 = DEFINITIONAL_REPRESENTATION('',(#121967),#121971); +#121967 = LINE('',#121968,#121969); +#121968 = CARTESIAN_POINT('',(-2.25,5.000038352949E-002)); +#121969 = VECTOR('',#121970,1.); +#121970 = DIRECTION('',(-1.,0.E+000)); +#121971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121972 = ORIENTED_EDGE('',*,*,#121973,.F.); +#121973 = EDGE_CURVE('',#121974,#121939,#121976,.T.); +#121974 = VERTEX_POINT('',#121975); +#121975 = CARTESIAN_POINT('',(-0.740726081328,7.65,-0.208196358798)); +#121976 = SURFACE_CURVE('',#121977,(#121981,#121988),.PCURVE_S1.); +#121977 = LINE('',#121978,#121979); +#121978 = CARTESIAN_POINT('',(-0.740726081328,7.65,-0.208196358798)); +#121979 = VECTOR('',#121980,1.); +#121980 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#121981 = PCURVE('',#121949,#121982); +#121982 = DEFINITIONAL_REPRESENTATION('',(#121983),#121987); +#121983 = LINE('',#121984,#121985); +#121984 = CARTESIAN_POINT('',(-1.110223024625E-015,-2.35)); +#121985 = VECTOR('',#121986,1.); +#121986 = DIRECTION('',(1.,0.E+000)); +#121987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121988 = PCURVE('',#92975,#121989); +#121989 = DEFINITIONAL_REPRESENTATION('',(#121990),#121994); +#121990 = LINE('',#121991,#121992); +#121991 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#121992 = VECTOR('',#121993,1.); +#121993 = DIRECTION('',(0.E+000,-1.)); +#121994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#121995 = ORIENTED_EDGE('',*,*,#121996,.F.); +#121996 = EDGE_CURVE('',#121997,#121974,#121999,.T.); +#121997 = VERTEX_POINT('',#121998); +#121998 = CARTESIAN_POINT('',(-0.740726081328,7.85,-0.208196358798)); +#121999 = SURFACE_CURVE('',#122000,(#122004,#122011),.PCURVE_S1.); +#122000 = LINE('',#122001,#122002); +#122001 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#122002 = VECTOR('',#122003,1.); +#122003 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122004 = PCURVE('',#121949,#122005); +#122005 = DEFINITIONAL_REPRESENTATION('',(#122006),#122010); +#122006 = LINE('',#122007,#122008); +#122007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122008 = VECTOR('',#122009,1.); +#122009 = DIRECTION('',(-4.440892098501E-016,-1.)); +#122010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122011 = PCURVE('',#122012,#122017); +#122012 = CYLINDRICAL_SURFACE('',#122013,0.208574704164); +#122013 = AXIS2_PLACEMENT_3D('',#122014,#122015,#122016); +#122014 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#122015 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122016 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122017 = DEFINITIONAL_REPRESENTATION('',(#122018),#122021); +#122018 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122019,#122020), + .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); +#122019 = CARTESIAN_POINT('',(4.772630242227,-2.15)); +#122020 = CARTESIAN_POINT('',(4.772630242227,-2.35)); +#122021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122022 = ORIENTED_EDGE('',*,*,#122023,.T.); +#122023 = EDGE_CURVE('',#121997,#121941,#122024,.T.); +#122024 = SURFACE_CURVE('',#122025,(#122029,#122036),.PCURVE_S1.); +#122025 = LINE('',#122026,#122027); +#122026 = CARTESIAN_POINT('',(-0.740726081328,7.85,-0.208196358798)); +#122027 = VECTOR('',#122028,1.); +#122028 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122029 = PCURVE('',#121949,#122030); +#122030 = DEFINITIONAL_REPRESENTATION('',(#122031),#122035); +#122031 = LINE('',#122032,#122033); +#122032 = CARTESIAN_POINT('',(-8.881784197001E-016,-2.15)); +#122033 = VECTOR('',#122034,1.); +#122034 = DIRECTION('',(1.,0.E+000)); +#122035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122036 = PCURVE('',#93031,#122037); +#122037 = DEFINITIONAL_REPRESENTATION('',(#122038),#122042); +#122038 = LINE('',#122039,#122040); +#122039 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#122040 = VECTOR('',#122041,1.); +#122041 = DIRECTION('',(0.E+000,-1.)); +#122042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122043 = ADVANCED_FACE('',(#122044),#122058,.F.); +#122044 = FACE_BOUND('',#122045,.T.); +#122045 = EDGE_LOOP('',(#122046,#122076,#122099,#122126)); +#122046 = ORIENTED_EDGE('',*,*,#122047,.F.); +#122047 = EDGE_CURVE('',#122048,#122050,#122052,.T.); +#122048 = VERTEX_POINT('',#122049); +#122049 = CARTESIAN_POINT('',(-1.,7.85,-0.308197125857)); +#122050 = VERTEX_POINT('',#122051); +#122051 = CARTESIAN_POINT('',(-1.,7.65,-0.308197125857)); +#122052 = SURFACE_CURVE('',#122053,(#122057,#122069),.PCURVE_S1.); +#122053 = LINE('',#122054,#122055); +#122054 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#122055 = VECTOR('',#122056,1.); +#122056 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122057 = PCURVE('',#122058,#122063); +#122058 = PLANE('',#122059); +#122059 = AXIS2_PLACEMENT_3D('',#122060,#122061,#122062); +#122060 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#122061 = DIRECTION('',(0.E+000,0.E+000,1.)); +#122062 = DIRECTION('',(1.,0.E+000,0.E+000)); +#122063 = DEFINITIONAL_REPRESENTATION('',(#122064),#122068); +#122064 = LINE('',#122065,#122066); +#122065 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#122066 = VECTOR('',#122067,1.); +#122067 = DIRECTION('',(4.440892098501E-016,-1.)); +#122068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122069 = PCURVE('',#121961,#122070); +#122070 = DEFINITIONAL_REPRESENTATION('',(#122071),#122075); +#122071 = LINE('',#122072,#122073); +#122072 = CARTESIAN_POINT('',(-2.25,-5.000038352949E-002)); +#122073 = VECTOR('',#122074,1.); +#122074 = DIRECTION('',(1.,0.E+000)); +#122075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122076 = ORIENTED_EDGE('',*,*,#122077,.F.); +#122077 = EDGE_CURVE('',#122078,#122048,#122080,.T.); +#122078 = VERTEX_POINT('',#122079); +#122079 = CARTESIAN_POINT('',(-0.74341632541,7.85,-0.308197125857)); +#122080 = SURFACE_CURVE('',#122081,(#122085,#122092),.PCURVE_S1.); +#122081 = LINE('',#122082,#122083); +#122082 = CARTESIAN_POINT('',(-0.74341632541,7.85,-0.308197125857)); +#122083 = VECTOR('',#122084,1.); +#122084 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122085 = PCURVE('',#122058,#122086); +#122086 = DEFINITIONAL_REPRESENTATION('',(#122087),#122091); +#122087 = LINE('',#122088,#122089); +#122088 = CARTESIAN_POINT('',(8.881784197001E-016,-2.15)); +#122089 = VECTOR('',#122090,1.); +#122090 = DIRECTION('',(-1.,0.E+000)); +#122091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122092 = PCURVE('',#93031,#122093); +#122093 = DEFINITIONAL_REPRESENTATION('',(#122094),#122098); +#122094 = LINE('',#122095,#122096); +#122095 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#122096 = VECTOR('',#122097,1.); +#122097 = DIRECTION('',(0.E+000,-1.)); +#122098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122099 = ORIENTED_EDGE('',*,*,#122100,.F.); +#122100 = EDGE_CURVE('',#122101,#122078,#122103,.T.); +#122101 = VERTEX_POINT('',#122102); +#122102 = CARTESIAN_POINT('',(-0.74341632541,7.65,-0.308197125857)); +#122103 = SURFACE_CURVE('',#122104,(#122108,#122115),.PCURVE_S1.); +#122104 = LINE('',#122105,#122106); +#122105 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#122106 = VECTOR('',#122107,1.); +#122107 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122108 = PCURVE('',#122058,#122109); +#122109 = DEFINITIONAL_REPRESENTATION('',(#122110),#122114); +#122110 = LINE('',#122111,#122112); +#122111 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122112 = VECTOR('',#122113,1.); +#122113 = DIRECTION('',(-4.440892098501E-016,1.)); +#122114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122115 = PCURVE('',#122116,#122121); +#122116 = CYLINDRICAL_SURFACE('',#122117,0.308574064194); +#122117 = AXIS2_PLACEMENT_3D('',#122118,#122119,#122120); +#122118 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#122119 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122120 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122121 = DEFINITIONAL_REPRESENTATION('',(#122122),#122125); +#122122 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122123,#122124), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#119731 = CARTESIAN_POINT('',(4.761821717947,-2.35)); -#119732 = CARTESIAN_POINT('',(4.761821717947,-2.15)); -#119733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119734 = ORIENTED_EDGE('',*,*,#119735,.T.); -#119735 = EDGE_CURVE('',#119709,#119658,#119736,.T.); -#119736 = SURFACE_CURVE('',#119737,(#119741,#119748),.PCURVE_S1.); -#119737 = LINE('',#119738,#119739); -#119738 = CARTESIAN_POINT('',(-0.74341632541,7.65,-0.308197125857)); -#119739 = VECTOR('',#119740,1.); -#119740 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#119741 = PCURVE('',#119666,#119742); -#119742 = DEFINITIONAL_REPRESENTATION('',(#119743),#119747); -#119743 = LINE('',#119744,#119745); -#119744 = CARTESIAN_POINT('',(1.110223024625E-015,-2.35)); -#119745 = VECTOR('',#119746,1.); -#119746 = DIRECTION('',(-1.,0.E+000)); -#119747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119748 = PCURVE('',#90583,#119749); -#119749 = DEFINITIONAL_REPRESENTATION('',(#119750),#119754); -#119750 = LINE('',#119751,#119752); -#119751 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#119752 = VECTOR('',#119753,1.); -#119753 = DIRECTION('',(0.E+000,-1.)); -#119754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119755 = ADVANCED_FACE('',(#119756),#119620,.F.); -#119756 = FACE_BOUND('',#119757,.F.); -#119757 = EDGE_LOOP('',(#119758,#119781,#119808,#119833)); -#119758 = ORIENTED_EDGE('',*,*,#119759,.F.); -#119759 = EDGE_CURVE('',#119760,#119605,#119762,.T.); -#119760 = VERTEX_POINT('',#119761); -#119761 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.E+000)); -#119762 = SURFACE_CURVE('',#119763,(#119768,#119774),.PCURVE_S1.); -#119763 = CIRCLE('',#119764,0.208574704164); -#119764 = AXIS2_PLACEMENT_3D('',#119765,#119766,#119767); -#119765 = CARTESIAN_POINT('',(-0.728168876214,7.85,2.640924866458E-017) - ); -#119766 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119767 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119768 = PCURVE('',#119620,#119769); -#119769 = DEFINITIONAL_REPRESENTATION('',(#119770),#119773); -#119770 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119771,#119772), +#122123 = CARTESIAN_POINT('',(4.761821717947,-2.35)); +#122124 = CARTESIAN_POINT('',(4.761821717947,-2.15)); +#122125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122126 = ORIENTED_EDGE('',*,*,#122127,.T.); +#122127 = EDGE_CURVE('',#122101,#122050,#122128,.T.); +#122128 = SURFACE_CURVE('',#122129,(#122133,#122140),.PCURVE_S1.); +#122129 = LINE('',#122130,#122131); +#122130 = CARTESIAN_POINT('',(-0.74341632541,7.65,-0.308197125857)); +#122131 = VECTOR('',#122132,1.); +#122132 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122133 = PCURVE('',#122058,#122134); +#122134 = DEFINITIONAL_REPRESENTATION('',(#122135),#122139); +#122135 = LINE('',#122136,#122137); +#122136 = CARTESIAN_POINT('',(1.110223024625E-015,-2.35)); +#122137 = VECTOR('',#122138,1.); +#122138 = DIRECTION('',(-1.,0.E+000)); +#122139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122140 = PCURVE('',#92975,#122141); +#122141 = DEFINITIONAL_REPRESENTATION('',(#122142),#122146); +#122142 = LINE('',#122143,#122144); +#122143 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#122144 = VECTOR('',#122145,1.); +#122145 = DIRECTION('',(0.E+000,-1.)); +#122146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122147 = ADVANCED_FACE('',(#122148),#122012,.F.); +#122148 = FACE_BOUND('',#122149,.F.); +#122149 = EDGE_LOOP('',(#122150,#122173,#122200,#122225)); +#122150 = ORIENTED_EDGE('',*,*,#122151,.F.); +#122151 = EDGE_CURVE('',#122152,#121997,#122154,.T.); +#122152 = VERTEX_POINT('',#122153); +#122153 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.E+000)); +#122154 = SURFACE_CURVE('',#122155,(#122160,#122166),.PCURVE_S1.); +#122155 = CIRCLE('',#122156,0.208574704164); +#122156 = AXIS2_PLACEMENT_3D('',#122157,#122158,#122159); +#122157 = CARTESIAN_POINT('',(-0.728168876214,7.85,2.640924866458E-017) + ); +#122158 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122159 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122160 = PCURVE('',#122012,#122161); +#122161 = DEFINITIONAL_REPRESENTATION('',(#122162),#122165); +#122162 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122163,#122164), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#119771 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#119772 = CARTESIAN_POINT('',(4.772630242227,-2.15)); -#119773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119774 = PCURVE('',#90639,#119775); -#119775 = DEFINITIONAL_REPRESENTATION('',(#119776),#119780); -#119776 = CIRCLE('',#119777,0.208574704164); -#119777 = AXIS2_PLACEMENT_2D('',#119778,#119779); -#119778 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#119779 = DIRECTION('',(0.E+000,-1.)); -#119780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119781 = ORIENTED_EDGE('',*,*,#119782,.F.); -#119782 = EDGE_CURVE('',#119783,#119760,#119785,.T.); -#119783 = VERTEX_POINT('',#119784); -#119784 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.E+000)); -#119785 = SURFACE_CURVE('',#119786,(#119790,#119796),.PCURVE_S1.); -#119786 = LINE('',#119787,#119788); -#119787 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#119788 = VECTOR('',#119789,1.); -#119789 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119790 = PCURVE('',#119620,#119791); -#119791 = DEFINITIONAL_REPRESENTATION('',(#119792),#119795); -#119792 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119793,#119794), +#122163 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#122164 = CARTESIAN_POINT('',(4.772630242227,-2.15)); +#122165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122166 = PCURVE('',#93031,#122167); +#122167 = DEFINITIONAL_REPRESENTATION('',(#122168),#122172); +#122168 = CIRCLE('',#122169,0.208574704164); +#122169 = AXIS2_PLACEMENT_2D('',#122170,#122171); +#122170 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#122171 = DIRECTION('',(0.E+000,-1.)); +#122172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122173 = ORIENTED_EDGE('',*,*,#122174,.F.); +#122174 = EDGE_CURVE('',#122175,#122152,#122177,.T.); +#122175 = VERTEX_POINT('',#122176); +#122176 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.E+000)); +#122177 = SURFACE_CURVE('',#122178,(#122182,#122188),.PCURVE_S1.); +#122178 = LINE('',#122179,#122180); +#122179 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#122180 = VECTOR('',#122181,1.); +#122181 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122182 = PCURVE('',#122012,#122183); +#122183 = DEFINITIONAL_REPRESENTATION('',(#122184),#122187); +#122184 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122185,#122186), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#119793 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#119794 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#119795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119796 = PCURVE('',#119797,#119802); -#119797 = PLANE('',#119798); -#119798 = AXIS2_PLACEMENT_3D('',#119799,#119800,#119801); -#119799 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#119800 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#119801 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119802 = DEFINITIONAL_REPRESENTATION('',(#119803),#119807); -#119803 = LINE('',#119804,#119805); -#119804 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#119805 = VECTOR('',#119806,1.); -#119806 = DIRECTION('',(-1.,0.E+000)); -#119807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119808 = ORIENTED_EDGE('',*,*,#119809,.T.); -#119809 = EDGE_CURVE('',#119783,#119582,#119810,.T.); -#119810 = SURFACE_CURVE('',#119811,(#119816,#119822),.PCURVE_S1.); -#119811 = CIRCLE('',#119812,0.208574704164); -#119812 = AXIS2_PLACEMENT_3D('',#119813,#119814,#119815); -#119813 = CARTESIAN_POINT('',(-0.728168876214,7.65,2.640924866458E-017) - ); -#119814 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119815 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119816 = PCURVE('',#119620,#119817); -#119817 = DEFINITIONAL_REPRESENTATION('',(#119818),#119821); -#119818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119819,#119820), +#122185 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#122186 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#122187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122188 = PCURVE('',#122189,#122194); +#122189 = PLANE('',#122190); +#122190 = AXIS2_PLACEMENT_3D('',#122191,#122192,#122193); +#122191 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#122192 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#122193 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122194 = DEFINITIONAL_REPRESENTATION('',(#122195),#122199); +#122195 = LINE('',#122196,#122197); +#122196 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#122197 = VECTOR('',#122198,1.); +#122198 = DIRECTION('',(-1.,0.E+000)); +#122199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122200 = ORIENTED_EDGE('',*,*,#122201,.T.); +#122201 = EDGE_CURVE('',#122175,#121974,#122202,.T.); +#122202 = SURFACE_CURVE('',#122203,(#122208,#122214),.PCURVE_S1.); +#122203 = CIRCLE('',#122204,0.208574704164); +#122204 = AXIS2_PLACEMENT_3D('',#122205,#122206,#122207); +#122205 = CARTESIAN_POINT('',(-0.728168876214,7.65,2.640924866458E-017) + ); +#122206 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122207 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122208 = PCURVE('',#122012,#122209); +#122209 = DEFINITIONAL_REPRESENTATION('',(#122210),#122213); +#122210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122211,#122212), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#119819 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#119820 = CARTESIAN_POINT('',(4.772630242227,-2.35)); -#119821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122211 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#122212 = CARTESIAN_POINT('',(4.772630242227,-2.35)); +#122213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119822 = PCURVE('',#90583,#119823); -#119823 = DEFINITIONAL_REPRESENTATION('',(#119824),#119832); -#119824 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119825,#119826,#119827, - #119828,#119829,#119830,#119831),.UNSPECIFIED.,.T.,.F.) +#122214 = PCURVE('',#92975,#122215); +#122215 = DEFINITIONAL_REPRESENTATION('',(#122216),#122224); +#122216 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122217,#122218,#122219, + #122220,#122221,#122222,#122223),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#119825 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#119826 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#119827 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#119828 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#119829 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#119830 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#119831 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#119832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119833 = ORIENTED_EDGE('',*,*,#119604,.F.); -#119834 = ADVANCED_FACE('',(#119835),#119724,.T.); -#119835 = FACE_BOUND('',#119836,.T.); -#119836 = EDGE_LOOP('',(#119837,#119864,#119865,#119888)); -#119837 = ORIENTED_EDGE('',*,*,#119838,.T.); -#119838 = EDGE_CURVE('',#119839,#119709,#119841,.T.); -#119839 = VERTEX_POINT('',#119840); -#119840 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.E+000)); -#119841 = SURFACE_CURVE('',#119842,(#119847,#119853),.PCURVE_S1.); -#119842 = CIRCLE('',#119843,0.308574064194); -#119843 = AXIS2_PLACEMENT_3D('',#119844,#119845,#119846); -#119844 = CARTESIAN_POINT('',(-0.728168876214,7.65,2.640924866458E-017) - ); -#119845 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119846 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119847 = PCURVE('',#119724,#119848); -#119848 = DEFINITIONAL_REPRESENTATION('',(#119849),#119852); -#119849 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119850,#119851), +#122217 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#122218 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#122219 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#122220 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#122221 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#122222 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#122223 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#122224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122225 = ORIENTED_EDGE('',*,*,#121996,.F.); +#122226 = ADVANCED_FACE('',(#122227),#122116,.T.); +#122227 = FACE_BOUND('',#122228,.T.); +#122228 = EDGE_LOOP('',(#122229,#122256,#122257,#122280)); +#122229 = ORIENTED_EDGE('',*,*,#122230,.T.); +#122230 = EDGE_CURVE('',#122231,#122101,#122233,.T.); +#122231 = VERTEX_POINT('',#122232); +#122232 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.E+000)); +#122233 = SURFACE_CURVE('',#122234,(#122239,#122245),.PCURVE_S1.); +#122234 = CIRCLE('',#122235,0.308574064194); +#122235 = AXIS2_PLACEMENT_3D('',#122236,#122237,#122238); +#122236 = CARTESIAN_POINT('',(-0.728168876214,7.65,2.640924866458E-017) + ); +#122237 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122238 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122239 = PCURVE('',#122116,#122240); +#122240 = DEFINITIONAL_REPRESENTATION('',(#122241),#122244); +#122241 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122242,#122243), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#119850 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#119851 = CARTESIAN_POINT('',(4.761821717947,-2.35)); -#119852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122242 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#122243 = CARTESIAN_POINT('',(4.761821717947,-2.35)); +#122244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119853 = PCURVE('',#90583,#119854); -#119854 = DEFINITIONAL_REPRESENTATION('',(#119855),#119863); -#119855 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#119856,#119857,#119858, - #119859,#119860,#119861,#119862),.UNSPECIFIED.,.T.,.F.) +#122245 = PCURVE('',#92975,#122246); +#122246 = DEFINITIONAL_REPRESENTATION('',(#122247),#122255); +#122247 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122248,#122249,#122250, + #122251,#122252,#122253,#122254),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#119856 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#119857 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#119858 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#119859 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#119860 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#119861 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#119862 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#119863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119864 = ORIENTED_EDGE('',*,*,#119708,.T.); -#119865 = ORIENTED_EDGE('',*,*,#119866,.F.); -#119866 = EDGE_CURVE('',#119867,#119686,#119869,.T.); -#119867 = VERTEX_POINT('',#119868); -#119868 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.E+000)); -#119869 = SURFACE_CURVE('',#119870,(#119875,#119881),.PCURVE_S1.); -#119870 = CIRCLE('',#119871,0.308574064194); -#119871 = AXIS2_PLACEMENT_3D('',#119872,#119873,#119874); -#119872 = CARTESIAN_POINT('',(-0.728168876214,7.85,2.640924866458E-017) - ); -#119873 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119874 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#119875 = PCURVE('',#119724,#119876); -#119876 = DEFINITIONAL_REPRESENTATION('',(#119877),#119880); -#119877 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119878,#119879), +#122248 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#122249 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#122250 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#122251 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#122252 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#122253 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#122254 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#122255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122256 = ORIENTED_EDGE('',*,*,#122100,.T.); +#122257 = ORIENTED_EDGE('',*,*,#122258,.F.); +#122258 = EDGE_CURVE('',#122259,#122078,#122261,.T.); +#122259 = VERTEX_POINT('',#122260); +#122260 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.E+000)); +#122261 = SURFACE_CURVE('',#122262,(#122267,#122273),.PCURVE_S1.); +#122262 = CIRCLE('',#122263,0.308574064194); +#122263 = AXIS2_PLACEMENT_3D('',#122264,#122265,#122266); +#122264 = CARTESIAN_POINT('',(-0.728168876214,7.85,2.640924866458E-017) + ); +#122265 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122266 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122267 = PCURVE('',#122116,#122268); +#122268 = DEFINITIONAL_REPRESENTATION('',(#122269),#122272); +#122269 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122270,#122271), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#119878 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#119879 = CARTESIAN_POINT('',(4.761821717947,-2.15)); -#119880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119881 = PCURVE('',#90639,#119882); -#119882 = DEFINITIONAL_REPRESENTATION('',(#119883),#119887); -#119883 = CIRCLE('',#119884,0.308574064194); -#119884 = AXIS2_PLACEMENT_2D('',#119885,#119886); -#119885 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#119886 = DIRECTION('',(0.E+000,-1.)); -#119887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119888 = ORIENTED_EDGE('',*,*,#119889,.T.); -#119889 = EDGE_CURVE('',#119867,#119839,#119890,.T.); -#119890 = SURFACE_CURVE('',#119891,(#119895,#119901),.PCURVE_S1.); -#119891 = LINE('',#119892,#119893); -#119892 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#119893 = VECTOR('',#119894,1.); -#119894 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119895 = PCURVE('',#119724,#119896); -#119896 = DEFINITIONAL_REPRESENTATION('',(#119897),#119900); -#119897 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119898,#119899), +#122270 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#122271 = CARTESIAN_POINT('',(4.761821717947,-2.15)); +#122272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122273 = PCURVE('',#93031,#122274); +#122274 = DEFINITIONAL_REPRESENTATION('',(#122275),#122279); +#122275 = CIRCLE('',#122276,0.308574064194); +#122276 = AXIS2_PLACEMENT_2D('',#122277,#122278); +#122277 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#122278 = DIRECTION('',(0.E+000,-1.)); +#122279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122280 = ORIENTED_EDGE('',*,*,#122281,.T.); +#122281 = EDGE_CURVE('',#122259,#122231,#122282,.T.); +#122282 = SURFACE_CURVE('',#122283,(#122287,#122293),.PCURVE_S1.); +#122283 = LINE('',#122284,#122285); +#122284 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#122285 = VECTOR('',#122286,1.); +#122286 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122287 = PCURVE('',#122116,#122288); +#122288 = DEFINITIONAL_REPRESENTATION('',(#122289),#122292); +#122289 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122290,#122291), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#119898 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#119899 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#119900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119901 = PCURVE('',#119902,#119907); -#119902 = PLANE('',#119903); -#119903 = AXIS2_PLACEMENT_3D('',#119904,#119905,#119906); -#119904 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#119905 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#119906 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#119907 = DEFINITIONAL_REPRESENTATION('',(#119908),#119912); -#119908 = LINE('',#119909,#119910); -#119909 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#119910 = VECTOR('',#119911,1.); -#119911 = DIRECTION('',(-1.,0.E+000)); -#119912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119913 = ADVANCED_FACE('',(#119914),#119902,.T.); -#119914 = FACE_BOUND('',#119915,.T.); -#119915 = EDGE_LOOP('',(#119916,#119945,#119966,#119967)); -#119916 = ORIENTED_EDGE('',*,*,#119917,.T.); -#119917 = EDGE_CURVE('',#119918,#119920,#119922,.T.); -#119918 = VERTEX_POINT('',#119919); -#119919 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.530776333563)); -#119920 = VERTEX_POINT('',#119921); -#119921 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.530776333563)); -#119922 = SURFACE_CURVE('',#119923,(#119927,#119934),.PCURVE_S1.); -#119923 = LINE('',#119924,#119925); -#119924 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#119925 = VECTOR('',#119926,1.); -#119926 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119927 = PCURVE('',#119902,#119928); -#119928 = DEFINITIONAL_REPRESENTATION('',(#119929),#119933); -#119929 = LINE('',#119930,#119931); -#119930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#119931 = VECTOR('',#119932,1.); -#119932 = DIRECTION('',(-1.,0.E+000)); -#119933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119934 = PCURVE('',#119935,#119940); -#119935 = CYLINDRICAL_SURFACE('',#119936,0.119270391569); -#119936 = AXIS2_PLACEMENT_3D('',#119937,#119938,#119939); -#119937 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#119938 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#119939 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#119940 = DEFINITIONAL_REPRESENTATION('',(#119941),#119944); -#119941 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#119942,#119943), +#122290 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#122291 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#122292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122293 = PCURVE('',#122294,#122299); +#122294 = PLANE('',#122295); +#122295 = AXIS2_PLACEMENT_3D('',#122296,#122297,#122298); +#122296 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#122297 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#122298 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122299 = DEFINITIONAL_REPRESENTATION('',(#122300),#122304); +#122300 = LINE('',#122301,#122302); +#122301 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#122302 = VECTOR('',#122303,1.); +#122303 = DIRECTION('',(-1.,0.E+000)); +#122304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122305 = ADVANCED_FACE('',(#122306),#122294,.T.); +#122306 = FACE_BOUND('',#122307,.T.); +#122307 = EDGE_LOOP('',(#122308,#122337,#122358,#122359)); +#122308 = ORIENTED_EDGE('',*,*,#122309,.T.); +#122309 = EDGE_CURVE('',#122310,#122312,#122314,.T.); +#122310 = VERTEX_POINT('',#122311); +#122311 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.530776333563)); +#122312 = VERTEX_POINT('',#122313); +#122313 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.530776333563)); +#122314 = SURFACE_CURVE('',#122315,(#122319,#122326),.PCURVE_S1.); +#122315 = LINE('',#122316,#122317); +#122316 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#122317 = VECTOR('',#122318,1.); +#122318 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122319 = PCURVE('',#122294,#122320); +#122320 = DEFINITIONAL_REPRESENTATION('',(#122321),#122325); +#122321 = LINE('',#122322,#122323); +#122322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122323 = VECTOR('',#122324,1.); +#122324 = DIRECTION('',(-1.,0.E+000)); +#122325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122326 = PCURVE('',#122327,#122332); +#122327 = CYLINDRICAL_SURFACE('',#122328,0.119270391569); +#122328 = AXIS2_PLACEMENT_3D('',#122329,#122330,#122331); +#122329 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#122330 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122331 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122332 = DEFINITIONAL_REPRESENTATION('',(#122333),#122336); +#122333 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122334,#122335), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#119942 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#119943 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#119944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119945 = ORIENTED_EDGE('',*,*,#119946,.T.); -#119946 = EDGE_CURVE('',#119920,#119839,#119947,.T.); -#119947 = SURFACE_CURVE('',#119948,(#119952,#119959),.PCURVE_S1.); -#119948 = LINE('',#119949,#119950); -#119949 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.530776333563)); -#119950 = VECTOR('',#119951,1.); -#119951 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119952 = PCURVE('',#119902,#119953); -#119953 = DEFINITIONAL_REPRESENTATION('',(#119954),#119958); -#119954 = LINE('',#119955,#119956); -#119955 = CARTESIAN_POINT('',(-2.35,1.133910970711E-033)); -#119956 = VECTOR('',#119957,1.); -#119957 = DIRECTION('',(4.535643882845E-032,-1.)); -#119958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119959 = PCURVE('',#90583,#119960); -#119960 = DEFINITIONAL_REPRESENTATION('',(#119961),#119965); -#119961 = LINE('',#119962,#119963); -#119962 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#119963 = VECTOR('',#119964,1.); -#119964 = DIRECTION('',(1.,-1.021336205033E-016)); -#119965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122334 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#122335 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#122336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122337 = ORIENTED_EDGE('',*,*,#122338,.T.); +#122338 = EDGE_CURVE('',#122312,#122231,#122339,.T.); +#122339 = SURFACE_CURVE('',#122340,(#122344,#122351),.PCURVE_S1.); +#122340 = LINE('',#122341,#122342); +#122341 = CARTESIAN_POINT('',(-0.419594812019,7.65,0.530776333563)); +#122342 = VECTOR('',#122343,1.); +#122343 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#122344 = PCURVE('',#122294,#122345); +#122345 = DEFINITIONAL_REPRESENTATION('',(#122346),#122350); +#122346 = LINE('',#122347,#122348); +#122347 = CARTESIAN_POINT('',(-2.35,1.133910970711E-033)); +#122348 = VECTOR('',#122349,1.); +#122349 = DIRECTION('',(4.535643882845E-032,-1.)); +#122350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122351 = PCURVE('',#92975,#122352); +#122352 = DEFINITIONAL_REPRESENTATION('',(#122353),#122357); +#122353 = LINE('',#122354,#122355); +#122354 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#122355 = VECTOR('',#122356,1.); +#122356 = DIRECTION('',(1.,-1.021336205033E-016)); +#122357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#119966 = ORIENTED_EDGE('',*,*,#119889,.F.); -#119967 = ORIENTED_EDGE('',*,*,#119968,.F.); -#119968 = EDGE_CURVE('',#119918,#119867,#119969,.T.); -#119969 = SURFACE_CURVE('',#119970,(#119974,#119981),.PCURVE_S1.); -#119970 = LINE('',#119971,#119972); -#119971 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.530776333563)); -#119972 = VECTOR('',#119973,1.); -#119973 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#119974 = PCURVE('',#119902,#119975); -#119975 = DEFINITIONAL_REPRESENTATION('',(#119976),#119980); -#119976 = LINE('',#119977,#119978); -#119977 = CARTESIAN_POINT('',(-2.15,-1.133910970711E-033)); -#119978 = VECTOR('',#119979,1.); -#119979 = DIRECTION('',(4.535643882845E-032,-1.)); -#119980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119981 = PCURVE('',#90639,#119982); -#119982 = DEFINITIONAL_REPRESENTATION('',(#119983),#119987); -#119983 = LINE('',#119984,#119985); -#119984 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#119985 = VECTOR('',#119986,1.); -#119986 = DIRECTION('',(-1.,-1.021336205033E-016)); -#119987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#119988 = ADVANCED_FACE('',(#119989),#119797,.T.); -#119989 = FACE_BOUND('',#119990,.T.); -#119990 = EDGE_LOOP('',(#119991,#120020,#120041,#120042)); -#119991 = ORIENTED_EDGE('',*,*,#119992,.T.); -#119992 = EDGE_CURVE('',#119993,#119995,#119997,.T.); -#119993 = VERTEX_POINT('',#119994); -#119994 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.530776333563)); -#119995 = VERTEX_POINT('',#119996); -#119996 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.530776333563)); -#119997 = SURFACE_CURVE('',#119998,(#120002,#120009),.PCURVE_S1.); -#119998 = LINE('',#119999,#120000); -#119999 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#120000 = VECTOR('',#120001,1.); -#120001 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120002 = PCURVE('',#119797,#120003); -#120003 = DEFINITIONAL_REPRESENTATION('',(#120004),#120008); -#120004 = LINE('',#120005,#120006); -#120005 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120006 = VECTOR('',#120007,1.); -#120007 = DIRECTION('',(-1.,0.E+000)); -#120008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120009 = PCURVE('',#120010,#120015); -#120010 = CYLINDRICAL_SURFACE('',#120011,0.2192697516); -#120011 = AXIS2_PLACEMENT_3D('',#120012,#120013,#120014); -#120012 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#120013 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120014 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120015 = DEFINITIONAL_REPRESENTATION('',(#120016),#120019); -#120016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120017,#120018), +#122358 = ORIENTED_EDGE('',*,*,#122281,.F.); +#122359 = ORIENTED_EDGE('',*,*,#122360,.F.); +#122360 = EDGE_CURVE('',#122310,#122259,#122361,.T.); +#122361 = SURFACE_CURVE('',#122362,(#122366,#122373),.PCURVE_S1.); +#122362 = LINE('',#122363,#122364); +#122363 = CARTESIAN_POINT('',(-0.419594812019,7.85,0.530776333563)); +#122364 = VECTOR('',#122365,1.); +#122365 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#122366 = PCURVE('',#122294,#122367); +#122367 = DEFINITIONAL_REPRESENTATION('',(#122368),#122372); +#122368 = LINE('',#122369,#122370); +#122369 = CARTESIAN_POINT('',(-2.15,-1.133910970711E-033)); +#122370 = VECTOR('',#122371,1.); +#122371 = DIRECTION('',(4.535643882845E-032,-1.)); +#122372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122373 = PCURVE('',#93031,#122374); +#122374 = DEFINITIONAL_REPRESENTATION('',(#122375),#122379); +#122375 = LINE('',#122376,#122377); +#122376 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#122377 = VECTOR('',#122378,1.); +#122378 = DIRECTION('',(-1.,-1.021336205033E-016)); +#122379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122380 = ADVANCED_FACE('',(#122381),#122189,.T.); +#122381 = FACE_BOUND('',#122382,.T.); +#122382 = EDGE_LOOP('',(#122383,#122412,#122433,#122434)); +#122383 = ORIENTED_EDGE('',*,*,#122384,.T.); +#122384 = EDGE_CURVE('',#122385,#122387,#122389,.T.); +#122385 = VERTEX_POINT('',#122386); +#122386 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.530776333563)); +#122387 = VERTEX_POINT('',#122388); +#122388 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.530776333563)); +#122389 = SURFACE_CURVE('',#122390,(#122394,#122401),.PCURVE_S1.); +#122390 = LINE('',#122391,#122392); +#122391 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#122392 = VECTOR('',#122393,1.); +#122393 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122394 = PCURVE('',#122189,#122395); +#122395 = DEFINITIONAL_REPRESENTATION('',(#122396),#122400); +#122396 = LINE('',#122397,#122398); +#122397 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122398 = VECTOR('',#122399,1.); +#122399 = DIRECTION('',(-1.,0.E+000)); +#122400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122401 = PCURVE('',#122402,#122407); +#122402 = CYLINDRICAL_SURFACE('',#122403,0.2192697516); +#122403 = AXIS2_PLACEMENT_3D('',#122404,#122405,#122406); +#122404 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#122405 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122406 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122407 = DEFINITIONAL_REPRESENTATION('',(#122408),#122411); +#122408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122409,#122410), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#120017 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#120018 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#120019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120020 = ORIENTED_EDGE('',*,*,#120021,.T.); -#120021 = EDGE_CURVE('',#119995,#119760,#120022,.T.); -#120022 = SURFACE_CURVE('',#120023,(#120027,#120034),.PCURVE_S1.); -#120023 = LINE('',#120024,#120025); -#120024 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.530776333563)); -#120025 = VECTOR('',#120026,1.); -#120026 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120027 = PCURVE('',#119797,#120028); -#120028 = DEFINITIONAL_REPRESENTATION('',(#120029),#120033); -#120029 = LINE('',#120030,#120031); -#120030 = CARTESIAN_POINT('',(2.15,4.535643882845E-033)); -#120031 = VECTOR('',#120032,1.); -#120032 = DIRECTION('',(-4.535643882845E-032,-1.)); -#120033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120034 = PCURVE('',#90639,#120035); -#120035 = DEFINITIONAL_REPRESENTATION('',(#120036),#120040); -#120036 = LINE('',#120037,#120038); -#120037 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); -#120038 = VECTOR('',#120039,1.); -#120039 = DIRECTION('',(-1.,-1.021336205033E-016)); -#120040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120041 = ORIENTED_EDGE('',*,*,#119782,.F.); -#120042 = ORIENTED_EDGE('',*,*,#120043,.F.); -#120043 = EDGE_CURVE('',#119993,#119783,#120044,.T.); -#120044 = SURFACE_CURVE('',#120045,(#120049,#120056),.PCURVE_S1.); -#120045 = LINE('',#120046,#120047); -#120046 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.530776333563)); -#120047 = VECTOR('',#120048,1.); -#120048 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120049 = PCURVE('',#119797,#120050); -#120050 = DEFINITIONAL_REPRESENTATION('',(#120051),#120055); -#120051 = LINE('',#120052,#120053); -#120052 = CARTESIAN_POINT('',(2.35,-4.535643882845E-033)); -#120053 = VECTOR('',#120054,1.); -#120054 = DIRECTION('',(-4.535643882845E-032,-1.)); -#120055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120056 = PCURVE('',#90583,#120057); -#120057 = DEFINITIONAL_REPRESENTATION('',(#120058),#120062); -#120058 = LINE('',#120059,#120060); -#120059 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); -#120060 = VECTOR('',#120061,1.); -#120061 = DIRECTION('',(1.,-1.021336205033E-016)); -#120062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120063 = ADVANCED_FACE('',(#120064),#120010,.T.); -#120064 = FACE_BOUND('',#120065,.T.); -#120065 = EDGE_LOOP('',(#120066,#120067,#120090,#120135)); -#120066 = ORIENTED_EDGE('',*,*,#119992,.F.); -#120067 = ORIENTED_EDGE('',*,*,#120068,.F.); -#120068 = EDGE_CURVE('',#120069,#119993,#120071,.T.); -#120069 = VERTEX_POINT('',#120070); -#120070 = CARTESIAN_POINT('',(-0.304819755875,7.65,0.75)); -#120071 = SURFACE_CURVE('',#120072,(#120077,#120083),.PCURVE_S1.); -#120072 = CIRCLE('',#120073,0.2192697516); -#120073 = AXIS2_PLACEMENT_3D('',#120074,#120075,#120076); -#120074 = CARTESIAN_POINT('',(-0.30032442045,7.65,0.530776333563)); -#120075 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120076 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120077 = PCURVE('',#120010,#120078); -#120078 = DEFINITIONAL_REPRESENTATION('',(#120079),#120082); -#120079 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120080,#120081), +#122409 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#122410 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#122411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122412 = ORIENTED_EDGE('',*,*,#122413,.T.); +#122413 = EDGE_CURVE('',#122387,#122152,#122414,.T.); +#122414 = SURFACE_CURVE('',#122415,(#122419,#122426),.PCURVE_S1.); +#122415 = LINE('',#122416,#122417); +#122416 = CARTESIAN_POINT('',(-0.51959417205,7.85,0.530776333563)); +#122417 = VECTOR('',#122418,1.); +#122418 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#122419 = PCURVE('',#122189,#122420); +#122420 = DEFINITIONAL_REPRESENTATION('',(#122421),#122425); +#122421 = LINE('',#122422,#122423); +#122422 = CARTESIAN_POINT('',(2.15,4.535643882845E-033)); +#122423 = VECTOR('',#122424,1.); +#122424 = DIRECTION('',(-4.535643882845E-032,-1.)); +#122425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122426 = PCURVE('',#93031,#122427); +#122427 = DEFINITIONAL_REPRESENTATION('',(#122428),#122432); +#122428 = LINE('',#122429,#122430); +#122429 = CARTESIAN_POINT('',(-0.119223666437,8.253820388629E-003)); +#122430 = VECTOR('',#122431,1.); +#122431 = DIRECTION('',(-1.,-1.021336205033E-016)); +#122432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122433 = ORIENTED_EDGE('',*,*,#122174,.F.); +#122434 = ORIENTED_EDGE('',*,*,#122435,.F.); +#122435 = EDGE_CURVE('',#122385,#122175,#122436,.T.); +#122436 = SURFACE_CURVE('',#122437,(#122441,#122448),.PCURVE_S1.); +#122437 = LINE('',#122438,#122439); +#122438 = CARTESIAN_POINT('',(-0.51959417205,7.65,0.530776333563)); +#122439 = VECTOR('',#122440,1.); +#122440 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#122441 = PCURVE('',#122189,#122442); +#122442 = DEFINITIONAL_REPRESENTATION('',(#122443),#122447); +#122443 = LINE('',#122444,#122445); +#122444 = CARTESIAN_POINT('',(2.35,-4.535643882845E-033)); +#122445 = VECTOR('',#122446,1.); +#122446 = DIRECTION('',(-4.535643882845E-032,-1.)); +#122447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122448 = PCURVE('',#92975,#122449); +#122449 = DEFINITIONAL_REPRESENTATION('',(#122450),#122454); +#122450 = LINE('',#122451,#122452); +#122451 = CARTESIAN_POINT('',(0.119223666437,8.253820388629E-003)); +#122452 = VECTOR('',#122453,1.); +#122453 = DIRECTION('',(1.,-1.021336205033E-016)); +#122454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122455 = ADVANCED_FACE('',(#122456),#122402,.T.); +#122456 = FACE_BOUND('',#122457,.T.); +#122457 = EDGE_LOOP('',(#122458,#122459,#122482,#122527)); +#122458 = ORIENTED_EDGE('',*,*,#122384,.F.); +#122459 = ORIENTED_EDGE('',*,*,#122460,.F.); +#122460 = EDGE_CURVE('',#122461,#122385,#122463,.T.); +#122461 = VERTEX_POINT('',#122462); +#122462 = CARTESIAN_POINT('',(-0.304819755875,7.65,0.75)); +#122463 = SURFACE_CURVE('',#122464,(#122469,#122475),.PCURVE_S1.); +#122464 = CIRCLE('',#122465,0.2192697516); +#122465 = AXIS2_PLACEMENT_3D('',#122466,#122467,#122468); +#122466 = CARTESIAN_POINT('',(-0.30032442045,7.65,0.530776333563)); +#122467 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122468 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122469 = PCURVE('',#122402,#122470); +#122470 = DEFINITIONAL_REPRESENTATION('',(#122471),#122474); +#122471 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122472,#122473), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#120080 = CARTESIAN_POINT('',(1.591299156552,2.35)); -#120081 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#120082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120083 = PCURVE('',#90583,#120084); -#120084 = DEFINITIONAL_REPRESENTATION('',(#120085),#120089); -#120085 = CIRCLE('',#120086,0.2192697516); -#120086 = AXIS2_PLACEMENT_2D('',#120087,#120088); -#120087 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#120088 = DIRECTION('',(0.E+000,1.)); -#120089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120090 = ORIENTED_EDGE('',*,*,#120091,.F.); -#120091 = EDGE_CURVE('',#120092,#120069,#120094,.T.); -#120092 = VERTEX_POINT('',#120093); -#120093 = CARTESIAN_POINT('',(-0.304819755875,7.85,0.75)); -#120094 = SURFACE_CURVE('',#120095,(#120099,#120128),.PCURVE_S1.); -#120095 = LINE('',#120096,#120097); -#120096 = CARTESIAN_POINT('',(-0.304819755875,7.65,0.75)); -#120097 = VECTOR('',#120098,1.); -#120098 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120099 = PCURVE('',#120010,#120100); -#120100 = DEFINITIONAL_REPRESENTATION('',(#120101),#120127); -#120101 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#120102,#120103,#120104, - #120105,#120106,#120107,#120108,#120109,#120110,#120111,#120112, - #120113,#120114,#120115,#120116,#120117,#120118,#120119,#120120, - #120121,#120122,#120123,#120124,#120125,#120126),.UNSPECIFIED.,.F., +#122472 = CARTESIAN_POINT('',(1.591299156552,2.35)); +#122473 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#122474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122475 = PCURVE('',#92975,#122476); +#122476 = DEFINITIONAL_REPRESENTATION('',(#122477),#122481); +#122477 = CIRCLE('',#122478,0.2192697516); +#122478 = AXIS2_PLACEMENT_2D('',#122479,#122480); +#122479 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#122480 = DIRECTION('',(0.E+000,1.)); +#122481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122482 = ORIENTED_EDGE('',*,*,#122483,.F.); +#122483 = EDGE_CURVE('',#122484,#122461,#122486,.T.); +#122484 = VERTEX_POINT('',#122485); +#122485 = CARTESIAN_POINT('',(-0.304819755875,7.85,0.75)); +#122486 = SURFACE_CURVE('',#122487,(#122491,#122520),.PCURVE_S1.); +#122487 = LINE('',#122488,#122489); +#122488 = CARTESIAN_POINT('',(-0.304819755875,7.65,0.75)); +#122489 = VECTOR('',#122490,1.); +#122490 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122491 = PCURVE('',#122402,#122492); +#122492 = DEFINITIONAL_REPRESENTATION('',(#122493),#122519); +#122493 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#122494,#122495,#122496, + #122497,#122498,#122499,#122500,#122501,#122502,#122503,#122504, + #122505,#122506,#122507,#122508,#122509,#122510,#122511,#122512, + #122513,#122514,#122515,#122516,#122517,#122518),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -147923,128 +150925,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.QUASI_UNIFORM_KNOTS.); -#120102 = CARTESIAN_POINT('',(1.591299156552,2.15)); -#120103 = CARTESIAN_POINT('',(1.591299156552,2.15303030303)); -#120104 = CARTESIAN_POINT('',(1.591299156552,2.159090909091)); -#120105 = CARTESIAN_POINT('',(1.591299156552,2.168181818182)); -#120106 = CARTESIAN_POINT('',(1.591299156552,2.177272727273)); -#120107 = CARTESIAN_POINT('',(1.591299156552,2.186363636364)); -#120108 = CARTESIAN_POINT('',(1.591299156552,2.195454545455)); -#120109 = CARTESIAN_POINT('',(1.591299156552,2.204545454545)); -#120110 = CARTESIAN_POINT('',(1.591299156552,2.213636363636)); -#120111 = CARTESIAN_POINT('',(1.591299156552,2.222727272727)); -#120112 = CARTESIAN_POINT('',(1.591299156552,2.231818181818)); -#120113 = CARTESIAN_POINT('',(1.591299156552,2.240909090909)); -#120114 = CARTESIAN_POINT('',(1.591299156552,2.25)); -#120115 = CARTESIAN_POINT('',(1.591299156552,2.259090909091)); -#120116 = CARTESIAN_POINT('',(1.591299156552,2.268181818182)); -#120117 = CARTESIAN_POINT('',(1.591299156552,2.277272727273)); -#120118 = CARTESIAN_POINT('',(1.591299156552,2.286363636364)); -#120119 = CARTESIAN_POINT('',(1.591299156552,2.295454545455)); -#120120 = CARTESIAN_POINT('',(1.591299156552,2.304545454545)); -#120121 = CARTESIAN_POINT('',(1.591299156552,2.313636363636)); -#120122 = CARTESIAN_POINT('',(1.591299156552,2.322727272727)); -#120123 = CARTESIAN_POINT('',(1.591299156552,2.331818181818)); -#120124 = CARTESIAN_POINT('',(1.591299156552,2.340909090909)); -#120125 = CARTESIAN_POINT('',(1.591299156552,2.34696969697)); -#120126 = CARTESIAN_POINT('',(1.591299156552,2.35)); -#120127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120128 = PCURVE('',#90665,#120129); -#120129 = DEFINITIONAL_REPRESENTATION('',(#120130),#120134); -#120130 = LINE('',#120131,#120132); -#120131 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#120132 = VECTOR('',#120133,1.); -#120133 = DIRECTION('',(4.440892098501E-016,-1.)); -#120134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120135 = ORIENTED_EDGE('',*,*,#120136,.T.); -#120136 = EDGE_CURVE('',#120092,#119995,#120137,.T.); -#120137 = SURFACE_CURVE('',#120138,(#120143,#120149),.PCURVE_S1.); -#120138 = CIRCLE('',#120139,0.2192697516); -#120139 = AXIS2_PLACEMENT_3D('',#120140,#120141,#120142); -#120140 = CARTESIAN_POINT('',(-0.30032442045,7.85,0.530776333563)); -#120141 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120142 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120143 = PCURVE('',#120010,#120144); -#120144 = DEFINITIONAL_REPRESENTATION('',(#120145),#120148); -#120145 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120146,#120147), +#122494 = CARTESIAN_POINT('',(1.591299156552,2.15)); +#122495 = CARTESIAN_POINT('',(1.591299156552,2.15303030303)); +#122496 = CARTESIAN_POINT('',(1.591299156552,2.159090909091)); +#122497 = CARTESIAN_POINT('',(1.591299156552,2.168181818182)); +#122498 = CARTESIAN_POINT('',(1.591299156552,2.177272727273)); +#122499 = CARTESIAN_POINT('',(1.591299156552,2.186363636364)); +#122500 = CARTESIAN_POINT('',(1.591299156552,2.195454545455)); +#122501 = CARTESIAN_POINT('',(1.591299156552,2.204545454545)); +#122502 = CARTESIAN_POINT('',(1.591299156552,2.213636363636)); +#122503 = CARTESIAN_POINT('',(1.591299156552,2.222727272727)); +#122504 = CARTESIAN_POINT('',(1.591299156552,2.231818181818)); +#122505 = CARTESIAN_POINT('',(1.591299156552,2.240909090909)); +#122506 = CARTESIAN_POINT('',(1.591299156552,2.25)); +#122507 = CARTESIAN_POINT('',(1.591299156552,2.259090909091)); +#122508 = CARTESIAN_POINT('',(1.591299156552,2.268181818182)); +#122509 = CARTESIAN_POINT('',(1.591299156552,2.277272727273)); +#122510 = CARTESIAN_POINT('',(1.591299156552,2.286363636364)); +#122511 = CARTESIAN_POINT('',(1.591299156552,2.295454545455)); +#122512 = CARTESIAN_POINT('',(1.591299156552,2.304545454545)); +#122513 = CARTESIAN_POINT('',(1.591299156552,2.313636363636)); +#122514 = CARTESIAN_POINT('',(1.591299156552,2.322727272727)); +#122515 = CARTESIAN_POINT('',(1.591299156552,2.331818181818)); +#122516 = CARTESIAN_POINT('',(1.591299156552,2.340909090909)); +#122517 = CARTESIAN_POINT('',(1.591299156552,2.34696969697)); +#122518 = CARTESIAN_POINT('',(1.591299156552,2.35)); +#122519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122520 = PCURVE('',#93057,#122521); +#122521 = DEFINITIONAL_REPRESENTATION('',(#122522),#122526); +#122522 = LINE('',#122523,#122524); +#122523 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#122524 = VECTOR('',#122525,1.); +#122525 = DIRECTION('',(4.440892098501E-016,-1.)); +#122526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122527 = ORIENTED_EDGE('',*,*,#122528,.T.); +#122528 = EDGE_CURVE('',#122484,#122387,#122529,.T.); +#122529 = SURFACE_CURVE('',#122530,(#122535,#122541),.PCURVE_S1.); +#122530 = CIRCLE('',#122531,0.2192697516); +#122531 = AXIS2_PLACEMENT_3D('',#122532,#122533,#122534); +#122532 = CARTESIAN_POINT('',(-0.30032442045,7.85,0.530776333563)); +#122533 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122534 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122535 = PCURVE('',#122402,#122536); +#122536 = DEFINITIONAL_REPRESENTATION('',(#122537),#122540); +#122537 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122538,#122539), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#120146 = CARTESIAN_POINT('',(1.591299156552,2.15)); -#120147 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#120148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122538 = CARTESIAN_POINT('',(1.591299156552,2.15)); +#122539 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#122540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#120149 = PCURVE('',#90639,#120150); -#120150 = DEFINITIONAL_REPRESENTATION('',(#120151),#120159); -#120151 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120152,#120153,#120154, - #120155,#120156,#120157,#120158),.UNSPECIFIED.,.T.,.F.) +#122541 = PCURVE('',#93031,#122542); +#122542 = DEFINITIONAL_REPRESENTATION('',(#122543),#122551); +#122543 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122544,#122545,#122546, + #122547,#122548,#122549,#122550),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#120152 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#120153 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#120154 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#120155 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#120156 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#120157 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#120158 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#120159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120160 = ADVANCED_FACE('',(#120161),#119935,.F.); -#120161 = FACE_BOUND('',#120162,.F.); -#120162 = EDGE_LOOP('',(#120163,#120164,#120187,#120232)); -#120163 = ORIENTED_EDGE('',*,*,#119917,.T.); -#120164 = ORIENTED_EDGE('',*,*,#120165,.F.); -#120165 = EDGE_CURVE('',#120166,#119920,#120168,.T.); -#120166 = VERTEX_POINT('',#120167); -#120167 = CARTESIAN_POINT('',(-0.303662633502,7.65,0.65)); -#120168 = SURFACE_CURVE('',#120169,(#120174,#120180),.PCURVE_S1.); -#120169 = CIRCLE('',#120170,0.119270391569); -#120170 = AXIS2_PLACEMENT_3D('',#120171,#120172,#120173); -#120171 = CARTESIAN_POINT('',(-0.30032442045,7.65,0.530776333563)); -#120172 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120173 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120174 = PCURVE('',#119935,#120175); -#120175 = DEFINITIONAL_REPRESENTATION('',(#120176),#120179); -#120176 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120177,#120178), +#122544 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#122545 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#122546 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#122547 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#122548 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#122549 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#122550 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#122551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122552 = ADVANCED_FACE('',(#122553),#122327,.F.); +#122553 = FACE_BOUND('',#122554,.F.); +#122554 = EDGE_LOOP('',(#122555,#122556,#122579,#122624)); +#122555 = ORIENTED_EDGE('',*,*,#122309,.T.); +#122556 = ORIENTED_EDGE('',*,*,#122557,.F.); +#122557 = EDGE_CURVE('',#122558,#122312,#122560,.T.); +#122558 = VERTEX_POINT('',#122559); +#122559 = CARTESIAN_POINT('',(-0.303662633502,7.65,0.65)); +#122560 = SURFACE_CURVE('',#122561,(#122566,#122572),.PCURVE_S1.); +#122561 = CIRCLE('',#122562,0.119270391569); +#122562 = AXIS2_PLACEMENT_3D('',#122563,#122564,#122565); +#122563 = CARTESIAN_POINT('',(-0.30032442045,7.65,0.530776333563)); +#122564 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122565 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122566 = PCURVE('',#122327,#122567); +#122567 = DEFINITIONAL_REPRESENTATION('',(#122568),#122571); +#122568 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122569,#122570), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#120177 = CARTESIAN_POINT('',(1.598788597134,2.35)); -#120178 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#120179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120180 = PCURVE('',#90583,#120181); -#120181 = DEFINITIONAL_REPRESENTATION('',(#120182),#120186); -#120182 = CIRCLE('',#120183,0.119270391569); -#120183 = AXIS2_PLACEMENT_2D('',#120184,#120185); -#120184 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#120185 = DIRECTION('',(0.E+000,1.)); -#120186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120187 = ORIENTED_EDGE('',*,*,#120188,.T.); -#120188 = EDGE_CURVE('',#120166,#120189,#120191,.T.); -#120189 = VERTEX_POINT('',#120190); -#120190 = CARTESIAN_POINT('',(-0.303662633502,7.85,0.65)); -#120191 = SURFACE_CURVE('',#120192,(#120196,#120225),.PCURVE_S1.); -#120192 = LINE('',#120193,#120194); -#120193 = CARTESIAN_POINT('',(-0.303662633502,7.65,0.65)); -#120194 = VECTOR('',#120195,1.); -#120195 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120196 = PCURVE('',#119935,#120197); -#120197 = DEFINITIONAL_REPRESENTATION('',(#120198),#120224); -#120198 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#120199,#120200,#120201, - #120202,#120203,#120204,#120205,#120206,#120207,#120208,#120209, - #120210,#120211,#120212,#120213,#120214,#120215,#120216,#120217, - #120218,#120219,#120220,#120221,#120222,#120223),.UNSPECIFIED.,.F., +#122569 = CARTESIAN_POINT('',(1.598788597134,2.35)); +#122570 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#122571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122572 = PCURVE('',#92975,#122573); +#122573 = DEFINITIONAL_REPRESENTATION('',(#122574),#122578); +#122574 = CIRCLE('',#122575,0.119270391569); +#122575 = AXIS2_PLACEMENT_2D('',#122576,#122577); +#122576 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#122577 = DIRECTION('',(0.E+000,1.)); +#122578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122579 = ORIENTED_EDGE('',*,*,#122580,.T.); +#122580 = EDGE_CURVE('',#122558,#122581,#122583,.T.); +#122581 = VERTEX_POINT('',#122582); +#122582 = CARTESIAN_POINT('',(-0.303662633502,7.85,0.65)); +#122583 = SURFACE_CURVE('',#122584,(#122588,#122617),.PCURVE_S1.); +#122584 = LINE('',#122585,#122586); +#122585 = CARTESIAN_POINT('',(-0.303662633502,7.65,0.65)); +#122586 = VECTOR('',#122587,1.); +#122587 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122588 = PCURVE('',#122327,#122589); +#122589 = DEFINITIONAL_REPRESENTATION('',(#122590),#122616); +#122590 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#122591,#122592,#122593, + #122594,#122595,#122596,#122597,#122598,#122599,#122600,#122601, + #122602,#122603,#122604,#122605,#122606,#122607,#122608,#122609, + #122610,#122611,#122612,#122613,#122614,#122615),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -148053,956 +151055,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ,0.136363636364,0.145454545455,0.154545454545,0.163636363636, 0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#120199 = CARTESIAN_POINT('',(1.598788597134,2.35)); -#120200 = CARTESIAN_POINT('',(1.598788597134,2.34696969697)); -#120201 = CARTESIAN_POINT('',(1.598788597134,2.340909090909)); -#120202 = CARTESIAN_POINT('',(1.598788597134,2.331818181818)); -#120203 = CARTESIAN_POINT('',(1.598788597134,2.322727272727)); -#120204 = CARTESIAN_POINT('',(1.598788597134,2.313636363636)); -#120205 = CARTESIAN_POINT('',(1.598788597134,2.304545454545)); -#120206 = CARTESIAN_POINT('',(1.598788597134,2.295454545455)); -#120207 = CARTESIAN_POINT('',(1.598788597134,2.286363636364)); -#120208 = CARTESIAN_POINT('',(1.598788597134,2.277272727273)); -#120209 = CARTESIAN_POINT('',(1.598788597134,2.268181818182)); -#120210 = CARTESIAN_POINT('',(1.598788597134,2.259090909091)); -#120211 = CARTESIAN_POINT('',(1.598788597134,2.25)); -#120212 = CARTESIAN_POINT('',(1.598788597134,2.240909090909)); -#120213 = CARTESIAN_POINT('',(1.598788597134,2.231818181818)); -#120214 = CARTESIAN_POINT('',(1.598788597134,2.222727272727)); -#120215 = CARTESIAN_POINT('',(1.598788597134,2.213636363636)); -#120216 = CARTESIAN_POINT('',(1.598788597134,2.204545454545)); -#120217 = CARTESIAN_POINT('',(1.598788597134,2.195454545455)); -#120218 = CARTESIAN_POINT('',(1.598788597134,2.186363636364)); -#120219 = CARTESIAN_POINT('',(1.598788597134,2.177272727273)); -#120220 = CARTESIAN_POINT('',(1.598788597134,2.168181818182)); -#120221 = CARTESIAN_POINT('',(1.598788597134,2.159090909091)); -#120222 = CARTESIAN_POINT('',(1.598788597134,2.15303030303)); -#120223 = CARTESIAN_POINT('',(1.598788597134,2.15)); -#120224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120225 = PCURVE('',#90611,#120226); -#120226 = DEFINITIONAL_REPRESENTATION('',(#120227),#120231); -#120227 = LINE('',#120228,#120229); -#120228 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#120229 = VECTOR('',#120230,1.); -#120230 = DIRECTION('',(4.440892098501E-016,1.)); -#120231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120232 = ORIENTED_EDGE('',*,*,#120233,.T.); -#120233 = EDGE_CURVE('',#120189,#119918,#120234,.T.); -#120234 = SURFACE_CURVE('',#120235,(#120240,#120246),.PCURVE_S1.); -#120235 = CIRCLE('',#120236,0.119270391569); -#120236 = AXIS2_PLACEMENT_3D('',#120237,#120238,#120239); -#120237 = CARTESIAN_POINT('',(-0.30032442045,7.85,0.530776333563)); -#120238 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120239 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120240 = PCURVE('',#119935,#120241); -#120241 = DEFINITIONAL_REPRESENTATION('',(#120242),#120245); -#120242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120243,#120244), +#122591 = CARTESIAN_POINT('',(1.598788597134,2.35)); +#122592 = CARTESIAN_POINT('',(1.598788597134,2.34696969697)); +#122593 = CARTESIAN_POINT('',(1.598788597134,2.340909090909)); +#122594 = CARTESIAN_POINT('',(1.598788597134,2.331818181818)); +#122595 = CARTESIAN_POINT('',(1.598788597134,2.322727272727)); +#122596 = CARTESIAN_POINT('',(1.598788597134,2.313636363636)); +#122597 = CARTESIAN_POINT('',(1.598788597134,2.304545454545)); +#122598 = CARTESIAN_POINT('',(1.598788597134,2.295454545455)); +#122599 = CARTESIAN_POINT('',(1.598788597134,2.286363636364)); +#122600 = CARTESIAN_POINT('',(1.598788597134,2.277272727273)); +#122601 = CARTESIAN_POINT('',(1.598788597134,2.268181818182)); +#122602 = CARTESIAN_POINT('',(1.598788597134,2.259090909091)); +#122603 = CARTESIAN_POINT('',(1.598788597134,2.25)); +#122604 = CARTESIAN_POINT('',(1.598788597134,2.240909090909)); +#122605 = CARTESIAN_POINT('',(1.598788597134,2.231818181818)); +#122606 = CARTESIAN_POINT('',(1.598788597134,2.222727272727)); +#122607 = CARTESIAN_POINT('',(1.598788597134,2.213636363636)); +#122608 = CARTESIAN_POINT('',(1.598788597134,2.204545454545)); +#122609 = CARTESIAN_POINT('',(1.598788597134,2.195454545455)); +#122610 = CARTESIAN_POINT('',(1.598788597134,2.186363636364)); +#122611 = CARTESIAN_POINT('',(1.598788597134,2.177272727273)); +#122612 = CARTESIAN_POINT('',(1.598788597134,2.168181818182)); +#122613 = CARTESIAN_POINT('',(1.598788597134,2.159090909091)); +#122614 = CARTESIAN_POINT('',(1.598788597134,2.15303030303)); +#122615 = CARTESIAN_POINT('',(1.598788597134,2.15)); +#122616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122617 = PCURVE('',#93003,#122618); +#122618 = DEFINITIONAL_REPRESENTATION('',(#122619),#122623); +#122619 = LINE('',#122620,#122621); +#122620 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#122621 = VECTOR('',#122622,1.); +#122622 = DIRECTION('',(4.440892098501E-016,1.)); +#122623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122624 = ORIENTED_EDGE('',*,*,#122625,.T.); +#122625 = EDGE_CURVE('',#122581,#122310,#122626,.T.); +#122626 = SURFACE_CURVE('',#122627,(#122632,#122638),.PCURVE_S1.); +#122627 = CIRCLE('',#122628,0.119270391569); +#122628 = AXIS2_PLACEMENT_3D('',#122629,#122630,#122631); +#122629 = CARTESIAN_POINT('',(-0.30032442045,7.85,0.530776333563)); +#122630 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122631 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#122632 = PCURVE('',#122327,#122633); +#122633 = DEFINITIONAL_REPRESENTATION('',(#122634),#122637); +#122634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122635,#122636), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#120243 = CARTESIAN_POINT('',(1.598788597134,2.15)); -#120244 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#120245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122635 = CARTESIAN_POINT('',(1.598788597134,2.15)); +#122636 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#122637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#120246 = PCURVE('',#90639,#120247); -#120247 = DEFINITIONAL_REPRESENTATION('',(#120248),#120256); -#120248 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120249,#120250,#120251, - #120252,#120253,#120254,#120255),.UNSPECIFIED.,.T.,.F.) +#122638 = PCURVE('',#93031,#122639); +#122639 = DEFINITIONAL_REPRESENTATION('',(#122640),#122648); +#122640 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122641,#122642,#122643, + #122644,#122645,#122646,#122647),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#120249 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#120250 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#120251 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#120252 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#120253 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#120254 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#120255 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#120256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120257 = ADVANCED_FACE('',(#120258),#90611,.T.); -#120258 = FACE_BOUND('',#120259,.T.); -#120259 = EDGE_LOOP('',(#120260,#120281,#120282,#120303)); -#120260 = ORIENTED_EDGE('',*,*,#120261,.F.); -#120261 = EDGE_CURVE('',#120166,#90568,#120262,.T.); -#120262 = SURFACE_CURVE('',#120263,(#120267,#120274),.PCURVE_S1.); -#120263 = LINE('',#120264,#120265); -#120264 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); -#120265 = VECTOR('',#120266,1.); -#120266 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#120267 = PCURVE('',#90611,#120268); -#120268 = DEFINITIONAL_REPRESENTATION('',(#120269),#120273); -#120269 = LINE('',#120270,#120271); -#120270 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120271 = VECTOR('',#120272,1.); -#120272 = DIRECTION('',(-1.,-4.804757279354E-063)); -#120273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120274 = PCURVE('',#90583,#120275); -#120275 = DEFINITIONAL_REPRESENTATION('',(#120276),#120280); -#120276 = LINE('',#120277,#120278); -#120277 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120278 = VECTOR('',#120279,1.); -#120279 = DIRECTION('',(-3.563627120235E-016,1.)); -#120280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120281 = ORIENTED_EDGE('',*,*,#120188,.T.); -#120282 = ORIENTED_EDGE('',*,*,#120283,.T.); -#120283 = EDGE_CURVE('',#120189,#90596,#120284,.T.); -#120284 = SURFACE_CURVE('',#120285,(#120289,#120296),.PCURVE_S1.); -#120285 = LINE('',#120286,#120287); -#120286 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.65)); -#120287 = VECTOR('',#120288,1.); -#120288 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#120289 = PCURVE('',#90611,#120290); -#120290 = DEFINITIONAL_REPRESENTATION('',(#120291),#120295); -#120291 = LINE('',#120292,#120293); -#120292 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#120293 = VECTOR('',#120294,1.); -#120294 = DIRECTION('',(-1.,-4.804757279354E-063)); -#120295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120296 = PCURVE('',#90639,#120297); -#120297 = DEFINITIONAL_REPRESENTATION('',(#120298),#120302); -#120298 = LINE('',#120299,#120300); -#120299 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120300 = VECTOR('',#120301,1.); -#120301 = DIRECTION('',(3.563627120235E-016,1.)); -#120302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120303 = ORIENTED_EDGE('',*,*,#90595,.F.); -#120304 = ADVANCED_FACE('',(#120305),#90639,.T.); -#120305 = FACE_BOUND('',#120306,.T.); -#120306 = EDGE_LOOP('',(#120307,#120308,#120309,#120310,#120311,#120312, - #120333,#120334,#120335,#120336,#120337,#120358)); -#120307 = ORIENTED_EDGE('',*,*,#120283,.F.); -#120308 = ORIENTED_EDGE('',*,*,#120233,.T.); -#120309 = ORIENTED_EDGE('',*,*,#119968,.T.); -#120310 = ORIENTED_EDGE('',*,*,#119866,.T.); -#120311 = ORIENTED_EDGE('',*,*,#119685,.T.); -#120312 = ORIENTED_EDGE('',*,*,#120313,.F.); -#120313 = EDGE_CURVE('',#119549,#119656,#120314,.T.); -#120314 = SURFACE_CURVE('',#120315,(#120319,#120326),.PCURVE_S1.); -#120315 = LINE('',#120316,#120317); -#120316 = CARTESIAN_POINT('',(-1.,7.85,1.159810404338E-002)); -#120317 = VECTOR('',#120318,1.); -#120318 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#120319 = PCURVE('',#90639,#120320); -#120320 = DEFINITIONAL_REPRESENTATION('',(#120321),#120325); -#120321 = LINE('',#120322,#120323); -#120322 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#120323 = VECTOR('',#120324,1.); -#120324 = DIRECTION('',(-1.,2.101748079665E-016)); -#120325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120326 = PCURVE('',#119569,#120327); -#120327 = DEFINITIONAL_REPRESENTATION('',(#120328),#120332); -#120328 = LINE('',#120329,#120330); -#120329 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#120330 = VECTOR('',#120331,1.); -#120331 = DIRECTION('',(1.194699204908E-017,-1.)); -#120332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120333 = ORIENTED_EDGE('',*,*,#119631,.F.); -#120334 = ORIENTED_EDGE('',*,*,#119759,.F.); -#120335 = ORIENTED_EDGE('',*,*,#120021,.F.); -#120336 = ORIENTED_EDGE('',*,*,#120136,.F.); -#120337 = ORIENTED_EDGE('',*,*,#120338,.T.); -#120338 = EDGE_CURVE('',#120092,#90624,#120339,.T.); -#120339 = SURFACE_CURVE('',#120340,(#120344,#120351),.PCURVE_S1.); -#120340 = LINE('',#120341,#120342); -#120341 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.75)); -#120342 = VECTOR('',#120343,1.); -#120343 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#120344 = PCURVE('',#90639,#120345); -#120345 = DEFINITIONAL_REPRESENTATION('',(#120346),#120350); -#120346 = LINE('',#120347,#120348); -#120347 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#120348 = VECTOR('',#120349,1.); -#120349 = DIRECTION('',(3.563627120235E-016,1.)); -#120350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120351 = PCURVE('',#90665,#120352); -#120352 = DEFINITIONAL_REPRESENTATION('',(#120353),#120357); -#120353 = LINE('',#120354,#120355); -#120354 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#120355 = VECTOR('',#120356,1.); -#120356 = DIRECTION('',(1.,-4.804757279354E-063)); -#120357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120358 = ORIENTED_EDGE('',*,*,#90623,.F.); -#120359 = ADVANCED_FACE('',(#120360),#90665,.T.); -#120360 = FACE_BOUND('',#120361,.T.); -#120361 = EDGE_LOOP('',(#120362,#120363,#120364,#120385)); -#120362 = ORIENTED_EDGE('',*,*,#120338,.F.); -#120363 = ORIENTED_EDGE('',*,*,#120091,.T.); -#120364 = ORIENTED_EDGE('',*,*,#120365,.T.); -#120365 = EDGE_CURVE('',#120069,#90566,#120366,.T.); -#120366 = SURFACE_CURVE('',#120367,(#120371,#120378),.PCURVE_S1.); -#120367 = LINE('',#120368,#120369); -#120368 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.75)); -#120369 = VECTOR('',#120370,1.); -#120370 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#120371 = PCURVE('',#90665,#120372); -#120372 = DEFINITIONAL_REPRESENTATION('',(#120373),#120377); -#120373 = LINE('',#120374,#120375); -#120374 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120375 = VECTOR('',#120376,1.); -#120376 = DIRECTION('',(1.,-4.804757279354E-063)); -#120377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120378 = PCURVE('',#90583,#120379); -#120379 = DEFINITIONAL_REPRESENTATION('',(#120380),#120384); -#120380 = LINE('',#120381,#120382); -#120381 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#120382 = VECTOR('',#120383,1.); -#120383 = DIRECTION('',(-3.563627120235E-016,1.)); -#120384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120385 = ORIENTED_EDGE('',*,*,#90651,.F.); -#120386 = ADVANCED_FACE('',(#120387),#90583,.T.); -#120387 = FACE_BOUND('',#120388,.T.); -#120388 = EDGE_LOOP('',(#120389,#120390,#120391,#120392,#120393,#120394, - #120415,#120416,#120417,#120418,#120419,#120420)); -#120389 = ORIENTED_EDGE('',*,*,#120365,.F.); -#120390 = ORIENTED_EDGE('',*,*,#120068,.T.); -#120391 = ORIENTED_EDGE('',*,*,#120043,.T.); -#120392 = ORIENTED_EDGE('',*,*,#119809,.T.); -#120393 = ORIENTED_EDGE('',*,*,#119581,.T.); -#120394 = ORIENTED_EDGE('',*,*,#120395,.F.); -#120395 = EDGE_CURVE('',#119658,#119547,#120396,.T.); -#120396 = SURFACE_CURVE('',#120397,(#120401,#120408),.PCURVE_S1.); -#120397 = LINE('',#120398,#120399); -#120398 = CARTESIAN_POINT('',(-1.,7.65,1.159810404338E-002)); -#120399 = VECTOR('',#120400,1.); -#120400 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#120401 = PCURVE('',#90583,#120402); -#120402 = DEFINITIONAL_REPRESENTATION('',(#120403),#120407); -#120403 = LINE('',#120404,#120405); -#120404 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#120405 = VECTOR('',#120406,1.); -#120406 = DIRECTION('',(-1.,-2.101748079665E-016)); -#120407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120408 = PCURVE('',#119569,#120409); -#120409 = DEFINITIONAL_REPRESENTATION('',(#120410),#120414); -#120410 = LINE('',#120411,#120412); -#120411 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#120412 = VECTOR('',#120413,1.); -#120413 = DIRECTION('',(-1.194699204908E-017,1.)); -#120414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120415 = ORIENTED_EDGE('',*,*,#119735,.F.); -#120416 = ORIENTED_EDGE('',*,*,#119838,.F.); -#120417 = ORIENTED_EDGE('',*,*,#119946,.F.); -#120418 = ORIENTED_EDGE('',*,*,#120165,.F.); -#120419 = ORIENTED_EDGE('',*,*,#120261,.T.); -#120420 = ORIENTED_EDGE('',*,*,#90565,.F.); -#120421 = ADVANCED_FACE('',(#120422),#119569,.T.); -#120422 = FACE_BOUND('',#120423,.T.); -#120423 = EDGE_LOOP('',(#120424,#120425,#120426,#120427)); -#120424 = ORIENTED_EDGE('',*,*,#120313,.T.); -#120425 = ORIENTED_EDGE('',*,*,#119655,.T.); -#120426 = ORIENTED_EDGE('',*,*,#120395,.T.); -#120427 = ORIENTED_EDGE('',*,*,#119546,.T.); -#120428 = ADVANCED_FACE('',(#120429),#120443,.F.); -#120429 = FACE_BOUND('',#120430,.T.); -#120430 = EDGE_LOOP('',(#120431,#120466,#120489,#120516)); -#120431 = ORIENTED_EDGE('',*,*,#120432,.F.); -#120432 = EDGE_CURVE('',#120433,#120435,#120437,.T.); -#120433 = VERTEX_POINT('',#120434); -#120434 = CARTESIAN_POINT('',(-1.,8.15,-0.208196358798)); -#120435 = VERTEX_POINT('',#120436); -#120436 = CARTESIAN_POINT('',(-1.,8.35,-0.208196358798)); -#120437 = SURFACE_CURVE('',#120438,(#120442,#120454),.PCURVE_S1.); -#120438 = LINE('',#120439,#120440); -#120439 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#120440 = VECTOR('',#120441,1.); -#120441 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120442 = PCURVE('',#120443,#120448); -#120443 = PLANE('',#120444); -#120444 = AXIS2_PLACEMENT_3D('',#120445,#120446,#120447); -#120445 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#120446 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#120447 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#120448 = DEFINITIONAL_REPRESENTATION('',(#120449),#120453); -#120449 = LINE('',#120450,#120451); -#120450 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#120451 = VECTOR('',#120452,1.); -#120452 = DIRECTION('',(4.440892098501E-016,1.)); -#120453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120454 = PCURVE('',#120455,#120460); -#120455 = PLANE('',#120456); -#120456 = AXIS2_PLACEMENT_3D('',#120457,#120458,#120459); -#120457 = CARTESIAN_POINT('',(-1.,8.25,-0.258196742327)); -#120458 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#120459 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120460 = DEFINITIONAL_REPRESENTATION('',(#120461),#120465); -#120461 = LINE('',#120462,#120463); -#120462 = CARTESIAN_POINT('',(-1.75,5.000038352949E-002)); -#120463 = VECTOR('',#120464,1.); -#120464 = DIRECTION('',(-1.,0.E+000)); -#120465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120466 = ORIENTED_EDGE('',*,*,#120467,.F.); -#120467 = EDGE_CURVE('',#120468,#120433,#120470,.T.); -#120468 = VERTEX_POINT('',#120469); -#120469 = CARTESIAN_POINT('',(-0.740726081328,8.15,-0.208196358798)); -#120470 = SURFACE_CURVE('',#120471,(#120475,#120482),.PCURVE_S1.); -#120471 = LINE('',#120472,#120473); -#120472 = CARTESIAN_POINT('',(-0.740726081328,8.15,-0.208196358798)); -#120473 = VECTOR('',#120474,1.); -#120474 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#120475 = PCURVE('',#120443,#120476); -#120476 = DEFINITIONAL_REPRESENTATION('',(#120477),#120481); -#120477 = LINE('',#120478,#120479); -#120478 = CARTESIAN_POINT('',(-8.881784197001E-016,-1.85)); -#120479 = VECTOR('',#120480,1.); -#120480 = DIRECTION('',(1.,0.E+000)); -#120481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120482 = PCURVE('',#90469,#120483); -#120483 = DEFINITIONAL_REPRESENTATION('',(#120484),#120488); -#120484 = LINE('',#120485,#120486); -#120485 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#120486 = VECTOR('',#120487,1.); -#120487 = DIRECTION('',(0.E+000,-1.)); -#120488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120489 = ORIENTED_EDGE('',*,*,#120490,.F.); -#120490 = EDGE_CURVE('',#120491,#120468,#120493,.T.); -#120491 = VERTEX_POINT('',#120492); -#120492 = CARTESIAN_POINT('',(-0.740726081328,8.35,-0.208196358798)); -#120493 = SURFACE_CURVE('',#120494,(#120498,#120505),.PCURVE_S1.); -#120494 = LINE('',#120495,#120496); -#120495 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#120496 = VECTOR('',#120497,1.); -#120497 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120498 = PCURVE('',#120443,#120499); -#120499 = DEFINITIONAL_REPRESENTATION('',(#120500),#120504); -#120500 = LINE('',#120501,#120502); -#120501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120502 = VECTOR('',#120503,1.); -#120503 = DIRECTION('',(-4.440892098501E-016,-1.)); -#120504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120505 = PCURVE('',#120506,#120511); -#120506 = CYLINDRICAL_SURFACE('',#120507,0.208574704164); -#120507 = AXIS2_PLACEMENT_3D('',#120508,#120509,#120510); -#120508 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#120509 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120510 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120511 = DEFINITIONAL_REPRESENTATION('',(#120512),#120515); -#120512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120513,#120514), +#122641 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#122642 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#122643 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#122644 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#122645 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#122646 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#122647 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#122648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122649 = ADVANCED_FACE('',(#122650),#93003,.T.); +#122650 = FACE_BOUND('',#122651,.T.); +#122651 = EDGE_LOOP('',(#122652,#122673,#122674,#122695)); +#122652 = ORIENTED_EDGE('',*,*,#122653,.F.); +#122653 = EDGE_CURVE('',#122558,#92960,#122654,.T.); +#122654 = SURFACE_CURVE('',#122655,(#122659,#122666),.PCURVE_S1.); +#122655 = LINE('',#122656,#122657); +#122656 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.65)); +#122657 = VECTOR('',#122658,1.); +#122658 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#122659 = PCURVE('',#93003,#122660); +#122660 = DEFINITIONAL_REPRESENTATION('',(#122661),#122665); +#122661 = LINE('',#122662,#122663); +#122662 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122663 = VECTOR('',#122664,1.); +#122664 = DIRECTION('',(-1.,-4.804757279354E-063)); +#122665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122666 = PCURVE('',#92975,#122667); +#122667 = DEFINITIONAL_REPRESENTATION('',(#122668),#122672); +#122668 = LINE('',#122669,#122670); +#122669 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122670 = VECTOR('',#122671,1.); +#122671 = DIRECTION('',(-3.563627120235E-016,1.)); +#122672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122673 = ORIENTED_EDGE('',*,*,#122580,.T.); +#122674 = ORIENTED_EDGE('',*,*,#122675,.T.); +#122675 = EDGE_CURVE('',#122581,#92988,#122676,.T.); +#122676 = SURFACE_CURVE('',#122677,(#122681,#122688),.PCURVE_S1.); +#122677 = LINE('',#122678,#122679); +#122678 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.65)); +#122679 = VECTOR('',#122680,1.); +#122680 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#122681 = PCURVE('',#93003,#122682); +#122682 = DEFINITIONAL_REPRESENTATION('',(#122683),#122687); +#122683 = LINE('',#122684,#122685); +#122684 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#122685 = VECTOR('',#122686,1.); +#122686 = DIRECTION('',(-1.,-4.804757279354E-063)); +#122687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122688 = PCURVE('',#93031,#122689); +#122689 = DEFINITIONAL_REPRESENTATION('',(#122690),#122694); +#122690 = LINE('',#122691,#122692); +#122691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122692 = VECTOR('',#122693,1.); +#122693 = DIRECTION('',(3.563627120235E-016,1.)); +#122694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122695 = ORIENTED_EDGE('',*,*,#92987,.F.); +#122696 = ADVANCED_FACE('',(#122697),#93031,.T.); +#122697 = FACE_BOUND('',#122698,.T.); +#122698 = EDGE_LOOP('',(#122699,#122700,#122701,#122702,#122703,#122704, + #122725,#122726,#122727,#122728,#122729,#122750)); +#122699 = ORIENTED_EDGE('',*,*,#122675,.F.); +#122700 = ORIENTED_EDGE('',*,*,#122625,.T.); +#122701 = ORIENTED_EDGE('',*,*,#122360,.T.); +#122702 = ORIENTED_EDGE('',*,*,#122258,.T.); +#122703 = ORIENTED_EDGE('',*,*,#122077,.T.); +#122704 = ORIENTED_EDGE('',*,*,#122705,.F.); +#122705 = EDGE_CURVE('',#121941,#122048,#122706,.T.); +#122706 = SURFACE_CURVE('',#122707,(#122711,#122718),.PCURVE_S1.); +#122707 = LINE('',#122708,#122709); +#122708 = CARTESIAN_POINT('',(-1.,7.85,1.159810404338E-002)); +#122709 = VECTOR('',#122710,1.); +#122710 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#122711 = PCURVE('',#93031,#122712); +#122712 = DEFINITIONAL_REPRESENTATION('',(#122713),#122717); +#122713 = LINE('',#122714,#122715); +#122714 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#122715 = VECTOR('',#122716,1.); +#122716 = DIRECTION('',(-1.,2.101748079665E-016)); +#122717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122718 = PCURVE('',#121961,#122719); +#122719 = DEFINITIONAL_REPRESENTATION('',(#122720),#122724); +#122720 = LINE('',#122721,#122722); +#122721 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#122722 = VECTOR('',#122723,1.); +#122723 = DIRECTION('',(1.194699204908E-017,-1.)); +#122724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122725 = ORIENTED_EDGE('',*,*,#122023,.F.); +#122726 = ORIENTED_EDGE('',*,*,#122151,.F.); +#122727 = ORIENTED_EDGE('',*,*,#122413,.F.); +#122728 = ORIENTED_EDGE('',*,*,#122528,.F.); +#122729 = ORIENTED_EDGE('',*,*,#122730,.T.); +#122730 = EDGE_CURVE('',#122484,#93016,#122731,.T.); +#122731 = SURFACE_CURVE('',#122732,(#122736,#122743),.PCURVE_S1.); +#122732 = LINE('',#122733,#122734); +#122733 = CARTESIAN_POINT('',(-0.527847992439,7.85,0.75)); +#122734 = VECTOR('',#122735,1.); +#122735 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#122736 = PCURVE('',#93031,#122737); +#122737 = DEFINITIONAL_REPRESENTATION('',(#122738),#122742); +#122738 = LINE('',#122739,#122740); +#122739 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#122740 = VECTOR('',#122741,1.); +#122741 = DIRECTION('',(3.563627120235E-016,1.)); +#122742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122743 = PCURVE('',#93057,#122744); +#122744 = DEFINITIONAL_REPRESENTATION('',(#122745),#122749); +#122745 = LINE('',#122746,#122747); +#122746 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#122747 = VECTOR('',#122748,1.); +#122748 = DIRECTION('',(1.,-4.804757279354E-063)); +#122749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122750 = ORIENTED_EDGE('',*,*,#93015,.F.); +#122751 = ADVANCED_FACE('',(#122752),#93057,.T.); +#122752 = FACE_BOUND('',#122753,.T.); +#122753 = EDGE_LOOP('',(#122754,#122755,#122756,#122777)); +#122754 = ORIENTED_EDGE('',*,*,#122730,.F.); +#122755 = ORIENTED_EDGE('',*,*,#122483,.T.); +#122756 = ORIENTED_EDGE('',*,*,#122757,.T.); +#122757 = EDGE_CURVE('',#122461,#92958,#122758,.T.); +#122758 = SURFACE_CURVE('',#122759,(#122763,#122770),.PCURVE_S1.); +#122759 = LINE('',#122760,#122761); +#122760 = CARTESIAN_POINT('',(-0.527847992439,7.65,0.75)); +#122761 = VECTOR('',#122762,1.); +#122762 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#122763 = PCURVE('',#93057,#122764); +#122764 = DEFINITIONAL_REPRESENTATION('',(#122765),#122769); +#122765 = LINE('',#122766,#122767); +#122766 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122767 = VECTOR('',#122768,1.); +#122768 = DIRECTION('',(1.,-4.804757279354E-063)); +#122769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122770 = PCURVE('',#92975,#122771); +#122771 = DEFINITIONAL_REPRESENTATION('',(#122772),#122776); +#122772 = LINE('',#122773,#122774); +#122773 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#122774 = VECTOR('',#122775,1.); +#122775 = DIRECTION('',(-3.563627120235E-016,1.)); +#122776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122777 = ORIENTED_EDGE('',*,*,#93043,.F.); +#122778 = ADVANCED_FACE('',(#122779),#92975,.T.); +#122779 = FACE_BOUND('',#122780,.T.); +#122780 = EDGE_LOOP('',(#122781,#122782,#122783,#122784,#122785,#122786, + #122807,#122808,#122809,#122810,#122811,#122812)); +#122781 = ORIENTED_EDGE('',*,*,#122757,.F.); +#122782 = ORIENTED_EDGE('',*,*,#122460,.T.); +#122783 = ORIENTED_EDGE('',*,*,#122435,.T.); +#122784 = ORIENTED_EDGE('',*,*,#122201,.T.); +#122785 = ORIENTED_EDGE('',*,*,#121973,.T.); +#122786 = ORIENTED_EDGE('',*,*,#122787,.F.); +#122787 = EDGE_CURVE('',#122050,#121939,#122788,.T.); +#122788 = SURFACE_CURVE('',#122789,(#122793,#122800),.PCURVE_S1.); +#122789 = LINE('',#122790,#122791); +#122790 = CARTESIAN_POINT('',(-1.,7.65,1.159810404338E-002)); +#122791 = VECTOR('',#122792,1.); +#122792 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#122793 = PCURVE('',#92975,#122794); +#122794 = DEFINITIONAL_REPRESENTATION('',(#122795),#122799); +#122795 = LINE('',#122796,#122797); +#122796 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#122797 = VECTOR('',#122798,1.); +#122798 = DIRECTION('',(-1.,-2.101748079665E-016)); +#122799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122800 = PCURVE('',#121961,#122801); +#122801 = DEFINITIONAL_REPRESENTATION('',(#122802),#122806); +#122802 = LINE('',#122803,#122804); +#122803 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#122804 = VECTOR('',#122805,1.); +#122805 = DIRECTION('',(-1.194699204908E-017,1.)); +#122806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122807 = ORIENTED_EDGE('',*,*,#122127,.F.); +#122808 = ORIENTED_EDGE('',*,*,#122230,.F.); +#122809 = ORIENTED_EDGE('',*,*,#122338,.F.); +#122810 = ORIENTED_EDGE('',*,*,#122557,.F.); +#122811 = ORIENTED_EDGE('',*,*,#122653,.T.); +#122812 = ORIENTED_EDGE('',*,*,#92957,.F.); +#122813 = ADVANCED_FACE('',(#122814),#121961,.T.); +#122814 = FACE_BOUND('',#122815,.T.); +#122815 = EDGE_LOOP('',(#122816,#122817,#122818,#122819)); +#122816 = ORIENTED_EDGE('',*,*,#122705,.T.); +#122817 = ORIENTED_EDGE('',*,*,#122047,.T.); +#122818 = ORIENTED_EDGE('',*,*,#122787,.T.); +#122819 = ORIENTED_EDGE('',*,*,#121938,.T.); +#122820 = ADVANCED_FACE('',(#122821),#122835,.F.); +#122821 = FACE_BOUND('',#122822,.T.); +#122822 = EDGE_LOOP('',(#122823,#122858,#122881,#122908)); +#122823 = ORIENTED_EDGE('',*,*,#122824,.F.); +#122824 = EDGE_CURVE('',#122825,#122827,#122829,.T.); +#122825 = VERTEX_POINT('',#122826); +#122826 = CARTESIAN_POINT('',(-1.,8.15,-0.208196358798)); +#122827 = VERTEX_POINT('',#122828); +#122828 = CARTESIAN_POINT('',(-1.,8.35,-0.208196358798)); +#122829 = SURFACE_CURVE('',#122830,(#122834,#122846),.PCURVE_S1.); +#122830 = LINE('',#122831,#122832); +#122831 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#122832 = VECTOR('',#122833,1.); +#122833 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122834 = PCURVE('',#122835,#122840); +#122835 = PLANE('',#122836); +#122836 = AXIS2_PLACEMENT_3D('',#122837,#122838,#122839); +#122837 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#122838 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#122839 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122840 = DEFINITIONAL_REPRESENTATION('',(#122841),#122845); +#122841 = LINE('',#122842,#122843); +#122842 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#122843 = VECTOR('',#122844,1.); +#122844 = DIRECTION('',(4.440892098501E-016,1.)); +#122845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122846 = PCURVE('',#122847,#122852); +#122847 = PLANE('',#122848); +#122848 = AXIS2_PLACEMENT_3D('',#122849,#122850,#122851); +#122849 = CARTESIAN_POINT('',(-1.,8.25,-0.258196742327)); +#122850 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#122851 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122852 = DEFINITIONAL_REPRESENTATION('',(#122853),#122857); +#122853 = LINE('',#122854,#122855); +#122854 = CARTESIAN_POINT('',(-1.75,5.000038352949E-002)); +#122855 = VECTOR('',#122856,1.); +#122856 = DIRECTION('',(-1.,0.E+000)); +#122857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122858 = ORIENTED_EDGE('',*,*,#122859,.F.); +#122859 = EDGE_CURVE('',#122860,#122825,#122862,.T.); +#122860 = VERTEX_POINT('',#122861); +#122861 = CARTESIAN_POINT('',(-0.740726081328,8.15,-0.208196358798)); +#122862 = SURFACE_CURVE('',#122863,(#122867,#122874),.PCURVE_S1.); +#122863 = LINE('',#122864,#122865); +#122864 = CARTESIAN_POINT('',(-0.740726081328,8.15,-0.208196358798)); +#122865 = VECTOR('',#122866,1.); +#122866 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122867 = PCURVE('',#122835,#122868); +#122868 = DEFINITIONAL_REPRESENTATION('',(#122869),#122873); +#122869 = LINE('',#122870,#122871); +#122870 = CARTESIAN_POINT('',(-8.881784197001E-016,-1.85)); +#122871 = VECTOR('',#122872,1.); +#122872 = DIRECTION('',(1.,0.E+000)); +#122873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122874 = PCURVE('',#92861,#122875); +#122875 = DEFINITIONAL_REPRESENTATION('',(#122876),#122880); +#122876 = LINE('',#122877,#122878); +#122877 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#122878 = VECTOR('',#122879,1.); +#122879 = DIRECTION('',(0.E+000,-1.)); +#122880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122881 = ORIENTED_EDGE('',*,*,#122882,.F.); +#122882 = EDGE_CURVE('',#122883,#122860,#122885,.T.); +#122883 = VERTEX_POINT('',#122884); +#122884 = CARTESIAN_POINT('',(-0.740726081328,8.35,-0.208196358798)); +#122885 = SURFACE_CURVE('',#122886,(#122890,#122897),.PCURVE_S1.); +#122886 = LINE('',#122887,#122888); +#122887 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#122888 = VECTOR('',#122889,1.); +#122889 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122890 = PCURVE('',#122835,#122891); +#122891 = DEFINITIONAL_REPRESENTATION('',(#122892),#122896); +#122892 = LINE('',#122893,#122894); +#122893 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122894 = VECTOR('',#122895,1.); +#122895 = DIRECTION('',(-4.440892098501E-016,-1.)); +#122896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122897 = PCURVE('',#122898,#122903); +#122898 = CYLINDRICAL_SURFACE('',#122899,0.208574704164); +#122899 = AXIS2_PLACEMENT_3D('',#122900,#122901,#122902); +#122900 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#122901 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122902 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#122903 = DEFINITIONAL_REPRESENTATION('',(#122904),#122907); +#122904 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122905,#122906), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#120513 = CARTESIAN_POINT('',(4.772630242227,-1.65)); -#120514 = CARTESIAN_POINT('',(4.772630242227,-1.85)); -#120515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120516 = ORIENTED_EDGE('',*,*,#120517,.T.); -#120517 = EDGE_CURVE('',#120491,#120435,#120518,.T.); -#120518 = SURFACE_CURVE('',#120519,(#120523,#120530),.PCURVE_S1.); -#120519 = LINE('',#120520,#120521); -#120520 = CARTESIAN_POINT('',(-0.740726081328,8.35,-0.208196358798)); -#120521 = VECTOR('',#120522,1.); -#120522 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#120523 = PCURVE('',#120443,#120524); -#120524 = DEFINITIONAL_REPRESENTATION('',(#120525),#120529); -#120525 = LINE('',#120526,#120527); -#120526 = CARTESIAN_POINT('',(-6.661338147751E-016,-1.65)); -#120527 = VECTOR('',#120528,1.); -#120528 = DIRECTION('',(1.,0.E+000)); -#120529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120530 = PCURVE('',#90525,#120531); -#120531 = DEFINITIONAL_REPRESENTATION('',(#120532),#120536); -#120532 = LINE('',#120533,#120534); -#120533 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#120534 = VECTOR('',#120535,1.); -#120535 = DIRECTION('',(0.E+000,-1.)); -#120536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120537 = ADVANCED_FACE('',(#120538),#120552,.F.); -#120538 = FACE_BOUND('',#120539,.T.); -#120539 = EDGE_LOOP('',(#120540,#120570,#120593,#120620)); -#120540 = ORIENTED_EDGE('',*,*,#120541,.F.); -#120541 = EDGE_CURVE('',#120542,#120544,#120546,.T.); -#120542 = VERTEX_POINT('',#120543); -#120543 = CARTESIAN_POINT('',(-1.,8.35,-0.308197125857)); -#120544 = VERTEX_POINT('',#120545); -#120545 = CARTESIAN_POINT('',(-1.,8.15,-0.308197125857)); -#120546 = SURFACE_CURVE('',#120547,(#120551,#120563),.PCURVE_S1.); -#120547 = LINE('',#120548,#120549); -#120548 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#120549 = VECTOR('',#120550,1.); -#120550 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120551 = PCURVE('',#120552,#120557); -#120552 = PLANE('',#120553); -#120553 = AXIS2_PLACEMENT_3D('',#120554,#120555,#120556); -#120554 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#120555 = DIRECTION('',(0.E+000,0.E+000,1.)); -#120556 = DIRECTION('',(1.,0.E+000,0.E+000)); -#120557 = DEFINITIONAL_REPRESENTATION('',(#120558),#120562); -#120558 = LINE('',#120559,#120560); -#120559 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#120560 = VECTOR('',#120561,1.); -#120561 = DIRECTION('',(4.440892098501E-016,-1.)); -#120562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120563 = PCURVE('',#120455,#120564); -#120564 = DEFINITIONAL_REPRESENTATION('',(#120565),#120569); -#120565 = LINE('',#120566,#120567); -#120566 = CARTESIAN_POINT('',(-1.75,-5.000038352949E-002)); -#120567 = VECTOR('',#120568,1.); -#120568 = DIRECTION('',(1.,0.E+000)); -#120569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120570 = ORIENTED_EDGE('',*,*,#120571,.F.); -#120571 = EDGE_CURVE('',#120572,#120542,#120574,.T.); -#120572 = VERTEX_POINT('',#120573); -#120573 = CARTESIAN_POINT('',(-0.74341632541,8.35,-0.308197125857)); -#120574 = SURFACE_CURVE('',#120575,(#120579,#120586),.PCURVE_S1.); -#120575 = LINE('',#120576,#120577); -#120576 = CARTESIAN_POINT('',(-0.74341632541,8.35,-0.308197125857)); -#120577 = VECTOR('',#120578,1.); -#120578 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#120579 = PCURVE('',#120552,#120580); -#120580 = DEFINITIONAL_REPRESENTATION('',(#120581),#120585); -#120581 = LINE('',#120582,#120583); -#120582 = CARTESIAN_POINT('',(6.661338147751E-016,-1.65)); -#120583 = VECTOR('',#120584,1.); -#120584 = DIRECTION('',(-1.,0.E+000)); -#120585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#122905 = CARTESIAN_POINT('',(4.772630242227,-1.65)); +#122906 = CARTESIAN_POINT('',(4.772630242227,-1.85)); +#122907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#120586 = PCURVE('',#90525,#120587); -#120587 = DEFINITIONAL_REPRESENTATION('',(#120588),#120592); -#120588 = LINE('',#120589,#120590); -#120589 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#120590 = VECTOR('',#120591,1.); -#120591 = DIRECTION('',(0.E+000,-1.)); -#120592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120593 = ORIENTED_EDGE('',*,*,#120594,.F.); -#120594 = EDGE_CURVE('',#120595,#120572,#120597,.T.); -#120595 = VERTEX_POINT('',#120596); -#120596 = CARTESIAN_POINT('',(-0.74341632541,8.15,-0.308197125857)); -#120597 = SURFACE_CURVE('',#120598,(#120602,#120609),.PCURVE_S1.); -#120598 = LINE('',#120599,#120600); -#120599 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#120600 = VECTOR('',#120601,1.); -#120601 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120602 = PCURVE('',#120552,#120603); -#120603 = DEFINITIONAL_REPRESENTATION('',(#120604),#120608); -#120604 = LINE('',#120605,#120606); -#120605 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120606 = VECTOR('',#120607,1.); -#120607 = DIRECTION('',(-4.440892098501E-016,1.)); -#120608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120609 = PCURVE('',#120610,#120615); -#120610 = CYLINDRICAL_SURFACE('',#120611,0.308574064194); -#120611 = AXIS2_PLACEMENT_3D('',#120612,#120613,#120614); -#120612 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#120613 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120614 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120615 = DEFINITIONAL_REPRESENTATION('',(#120616),#120619); -#120616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120617,#120618), +#122908 = ORIENTED_EDGE('',*,*,#122909,.T.); +#122909 = EDGE_CURVE('',#122883,#122827,#122910,.T.); +#122910 = SURFACE_CURVE('',#122911,(#122915,#122922),.PCURVE_S1.); +#122911 = LINE('',#122912,#122913); +#122912 = CARTESIAN_POINT('',(-0.740726081328,8.35,-0.208196358798)); +#122913 = VECTOR('',#122914,1.); +#122914 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122915 = PCURVE('',#122835,#122916); +#122916 = DEFINITIONAL_REPRESENTATION('',(#122917),#122921); +#122917 = LINE('',#122918,#122919); +#122918 = CARTESIAN_POINT('',(-6.661338147751E-016,-1.65)); +#122919 = VECTOR('',#122920,1.); +#122920 = DIRECTION('',(1.,0.E+000)); +#122921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122922 = PCURVE('',#92917,#122923); +#122923 = DEFINITIONAL_REPRESENTATION('',(#122924),#122928); +#122924 = LINE('',#122925,#122926); +#122925 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#122926 = VECTOR('',#122927,1.); +#122927 = DIRECTION('',(0.E+000,-1.)); +#122928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122929 = ADVANCED_FACE('',(#122930),#122944,.F.); +#122930 = FACE_BOUND('',#122931,.T.); +#122931 = EDGE_LOOP('',(#122932,#122962,#122985,#123012)); +#122932 = ORIENTED_EDGE('',*,*,#122933,.F.); +#122933 = EDGE_CURVE('',#122934,#122936,#122938,.T.); +#122934 = VERTEX_POINT('',#122935); +#122935 = CARTESIAN_POINT('',(-1.,8.35,-0.308197125857)); +#122936 = VERTEX_POINT('',#122937); +#122937 = CARTESIAN_POINT('',(-1.,8.15,-0.308197125857)); +#122938 = SURFACE_CURVE('',#122939,(#122943,#122955),.PCURVE_S1.); +#122939 = LINE('',#122940,#122941); +#122940 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#122941 = VECTOR('',#122942,1.); +#122942 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#122943 = PCURVE('',#122944,#122949); +#122944 = PLANE('',#122945); +#122945 = AXIS2_PLACEMENT_3D('',#122946,#122947,#122948); +#122946 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#122947 = DIRECTION('',(0.E+000,0.E+000,1.)); +#122948 = DIRECTION('',(1.,0.E+000,0.E+000)); +#122949 = DEFINITIONAL_REPRESENTATION('',(#122950),#122954); +#122950 = LINE('',#122951,#122952); +#122951 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#122952 = VECTOR('',#122953,1.); +#122953 = DIRECTION('',(4.440892098501E-016,-1.)); +#122954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122955 = PCURVE('',#122847,#122956); +#122956 = DEFINITIONAL_REPRESENTATION('',(#122957),#122961); +#122957 = LINE('',#122958,#122959); +#122958 = CARTESIAN_POINT('',(-1.75,-5.000038352949E-002)); +#122959 = VECTOR('',#122960,1.); +#122960 = DIRECTION('',(1.,0.E+000)); +#122961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122962 = ORIENTED_EDGE('',*,*,#122963,.F.); +#122963 = EDGE_CURVE('',#122964,#122934,#122966,.T.); +#122964 = VERTEX_POINT('',#122965); +#122965 = CARTESIAN_POINT('',(-0.74341632541,8.35,-0.308197125857)); +#122966 = SURFACE_CURVE('',#122967,(#122971,#122978),.PCURVE_S1.); +#122967 = LINE('',#122968,#122969); +#122968 = CARTESIAN_POINT('',(-0.74341632541,8.35,-0.308197125857)); +#122969 = VECTOR('',#122970,1.); +#122970 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#122971 = PCURVE('',#122944,#122972); +#122972 = DEFINITIONAL_REPRESENTATION('',(#122973),#122977); +#122973 = LINE('',#122974,#122975); +#122974 = CARTESIAN_POINT('',(6.661338147751E-016,-1.65)); +#122975 = VECTOR('',#122976,1.); +#122976 = DIRECTION('',(-1.,0.E+000)); +#122977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122978 = PCURVE('',#92917,#122979); +#122979 = DEFINITIONAL_REPRESENTATION('',(#122980),#122984); +#122980 = LINE('',#122981,#122982); +#122981 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#122982 = VECTOR('',#122983,1.); +#122983 = DIRECTION('',(0.E+000,-1.)); +#122984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#122985 = ORIENTED_EDGE('',*,*,#122986,.F.); +#122986 = EDGE_CURVE('',#122987,#122964,#122989,.T.); +#122987 = VERTEX_POINT('',#122988); +#122988 = CARTESIAN_POINT('',(-0.74341632541,8.15,-0.308197125857)); +#122989 = SURFACE_CURVE('',#122990,(#122994,#123001),.PCURVE_S1.); +#122990 = LINE('',#122991,#122992); +#122991 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#122992 = VECTOR('',#122993,1.); +#122993 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#122994 = PCURVE('',#122944,#122995); +#122995 = DEFINITIONAL_REPRESENTATION('',(#122996),#123000); +#122996 = LINE('',#122997,#122998); +#122997 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#122998 = VECTOR('',#122999,1.); +#122999 = DIRECTION('',(-4.440892098501E-016,1.)); +#123000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123001 = PCURVE('',#123002,#123007); +#123002 = CYLINDRICAL_SURFACE('',#123003,0.308574064194); +#123003 = AXIS2_PLACEMENT_3D('',#123004,#123005,#123006); +#123004 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#123005 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123006 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123007 = DEFINITIONAL_REPRESENTATION('',(#123008),#123011); +#123008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123009,#123010), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#120617 = CARTESIAN_POINT('',(4.761821717947,-1.85)); -#120618 = CARTESIAN_POINT('',(4.761821717947,-1.65)); -#120619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120620 = ORIENTED_EDGE('',*,*,#120621,.T.); -#120621 = EDGE_CURVE('',#120595,#120544,#120622,.T.); -#120622 = SURFACE_CURVE('',#120623,(#120627,#120634),.PCURVE_S1.); -#120623 = LINE('',#120624,#120625); -#120624 = CARTESIAN_POINT('',(-0.74341632541,8.15,-0.308197125857)); -#120625 = VECTOR('',#120626,1.); -#120626 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#120627 = PCURVE('',#120552,#120628); -#120628 = DEFINITIONAL_REPRESENTATION('',(#120629),#120633); -#120629 = LINE('',#120630,#120631); -#120630 = CARTESIAN_POINT('',(8.881784197001E-016,-1.85)); -#120631 = VECTOR('',#120632,1.); -#120632 = DIRECTION('',(-1.,0.E+000)); -#120633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120634 = PCURVE('',#90469,#120635); -#120635 = DEFINITIONAL_REPRESENTATION('',(#120636),#120640); -#120636 = LINE('',#120637,#120638); -#120637 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#120638 = VECTOR('',#120639,1.); -#120639 = DIRECTION('',(0.E+000,-1.)); -#120640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120641 = ADVANCED_FACE('',(#120642),#120506,.F.); -#120642 = FACE_BOUND('',#120643,.F.); -#120643 = EDGE_LOOP('',(#120644,#120667,#120694,#120719)); -#120644 = ORIENTED_EDGE('',*,*,#120645,.F.); -#120645 = EDGE_CURVE('',#120646,#120491,#120648,.T.); -#120646 = VERTEX_POINT('',#120647); -#120647 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.E+000)); -#120648 = SURFACE_CURVE('',#120649,(#120654,#120660),.PCURVE_S1.); -#120649 = CIRCLE('',#120650,0.208574704164); -#120650 = AXIS2_PLACEMENT_3D('',#120651,#120652,#120653); -#120651 = CARTESIAN_POINT('',(-0.728168876214,8.35,2.640924866458E-017) - ); -#120652 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120653 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120654 = PCURVE('',#120506,#120655); -#120655 = DEFINITIONAL_REPRESENTATION('',(#120656),#120659); -#120656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120657,#120658), +#123009 = CARTESIAN_POINT('',(4.761821717947,-1.85)); +#123010 = CARTESIAN_POINT('',(4.761821717947,-1.65)); +#123011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123012 = ORIENTED_EDGE('',*,*,#123013,.T.); +#123013 = EDGE_CURVE('',#122987,#122936,#123014,.T.); +#123014 = SURFACE_CURVE('',#123015,(#123019,#123026),.PCURVE_S1.); +#123015 = LINE('',#123016,#123017); +#123016 = CARTESIAN_POINT('',(-0.74341632541,8.15,-0.308197125857)); +#123017 = VECTOR('',#123018,1.); +#123018 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123019 = PCURVE('',#122944,#123020); +#123020 = DEFINITIONAL_REPRESENTATION('',(#123021),#123025); +#123021 = LINE('',#123022,#123023); +#123022 = CARTESIAN_POINT('',(8.881784197001E-016,-1.85)); +#123023 = VECTOR('',#123024,1.); +#123024 = DIRECTION('',(-1.,0.E+000)); +#123025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123026 = PCURVE('',#92861,#123027); +#123027 = DEFINITIONAL_REPRESENTATION('',(#123028),#123032); +#123028 = LINE('',#123029,#123030); +#123029 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#123030 = VECTOR('',#123031,1.); +#123031 = DIRECTION('',(0.E+000,-1.)); +#123032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123033 = ADVANCED_FACE('',(#123034),#122898,.F.); +#123034 = FACE_BOUND('',#123035,.F.); +#123035 = EDGE_LOOP('',(#123036,#123059,#123086,#123111)); +#123036 = ORIENTED_EDGE('',*,*,#123037,.F.); +#123037 = EDGE_CURVE('',#123038,#122883,#123040,.T.); +#123038 = VERTEX_POINT('',#123039); +#123039 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.E+000)); +#123040 = SURFACE_CURVE('',#123041,(#123046,#123052),.PCURVE_S1.); +#123041 = CIRCLE('',#123042,0.208574704164); +#123042 = AXIS2_PLACEMENT_3D('',#123043,#123044,#123045); +#123043 = CARTESIAN_POINT('',(-0.728168876214,8.35,2.640924866458E-017) + ); +#123044 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123045 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123046 = PCURVE('',#122898,#123047); +#123047 = DEFINITIONAL_REPRESENTATION('',(#123048),#123051); +#123048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123049,#123050), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#120657 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#120658 = CARTESIAN_POINT('',(4.772630242227,-1.65)); -#120659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120660 = PCURVE('',#90525,#120661); -#120661 = DEFINITIONAL_REPRESENTATION('',(#120662),#120666); -#120662 = CIRCLE('',#120663,0.208574704164); -#120663 = AXIS2_PLACEMENT_2D('',#120664,#120665); -#120664 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#120665 = DIRECTION('',(0.E+000,-1.)); -#120666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120667 = ORIENTED_EDGE('',*,*,#120668,.F.); -#120668 = EDGE_CURVE('',#120669,#120646,#120671,.T.); -#120669 = VERTEX_POINT('',#120670); -#120670 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.E+000)); -#120671 = SURFACE_CURVE('',#120672,(#120676,#120682),.PCURVE_S1.); -#120672 = LINE('',#120673,#120674); -#120673 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#120674 = VECTOR('',#120675,1.); -#120675 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120676 = PCURVE('',#120506,#120677); -#120677 = DEFINITIONAL_REPRESENTATION('',(#120678),#120681); -#120678 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120679,#120680), +#123049 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#123050 = CARTESIAN_POINT('',(4.772630242227,-1.65)); +#123051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123052 = PCURVE('',#92917,#123053); +#123053 = DEFINITIONAL_REPRESENTATION('',(#123054),#123058); +#123054 = CIRCLE('',#123055,0.208574704164); +#123055 = AXIS2_PLACEMENT_2D('',#123056,#123057); +#123056 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#123057 = DIRECTION('',(0.E+000,-1.)); +#123058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123059 = ORIENTED_EDGE('',*,*,#123060,.F.); +#123060 = EDGE_CURVE('',#123061,#123038,#123063,.T.); +#123061 = VERTEX_POINT('',#123062); +#123062 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.E+000)); +#123063 = SURFACE_CURVE('',#123064,(#123068,#123074),.PCURVE_S1.); +#123064 = LINE('',#123065,#123066); +#123065 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#123066 = VECTOR('',#123067,1.); +#123067 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123068 = PCURVE('',#122898,#123069); +#123069 = DEFINITIONAL_REPRESENTATION('',(#123070),#123073); +#123070 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123071,#123072), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#120679 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#120680 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#120681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120682 = PCURVE('',#120683,#120688); -#120683 = PLANE('',#120684); -#120684 = AXIS2_PLACEMENT_3D('',#120685,#120686,#120687); -#120685 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#120686 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#120687 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120688 = DEFINITIONAL_REPRESENTATION('',(#120689),#120693); -#120689 = LINE('',#120690,#120691); -#120690 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#120691 = VECTOR('',#120692,1.); -#120692 = DIRECTION('',(-1.,0.E+000)); -#120693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120694 = ORIENTED_EDGE('',*,*,#120695,.T.); -#120695 = EDGE_CURVE('',#120669,#120468,#120696,.T.); -#120696 = SURFACE_CURVE('',#120697,(#120702,#120708),.PCURVE_S1.); -#120697 = CIRCLE('',#120698,0.208574704164); -#120698 = AXIS2_PLACEMENT_3D('',#120699,#120700,#120701); -#120699 = CARTESIAN_POINT('',(-0.728168876214,8.15,2.640924866458E-017) - ); -#120700 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120701 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120702 = PCURVE('',#120506,#120703); -#120703 = DEFINITIONAL_REPRESENTATION('',(#120704),#120707); -#120704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120705,#120706), +#123071 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#123072 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#123073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123074 = PCURVE('',#123075,#123080); +#123075 = PLANE('',#123076); +#123076 = AXIS2_PLACEMENT_3D('',#123077,#123078,#123079); +#123077 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#123078 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#123079 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123080 = DEFINITIONAL_REPRESENTATION('',(#123081),#123085); +#123081 = LINE('',#123082,#123083); +#123082 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#123083 = VECTOR('',#123084,1.); +#123084 = DIRECTION('',(-1.,0.E+000)); +#123085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123086 = ORIENTED_EDGE('',*,*,#123087,.T.); +#123087 = EDGE_CURVE('',#123061,#122860,#123088,.T.); +#123088 = SURFACE_CURVE('',#123089,(#123094,#123100),.PCURVE_S1.); +#123089 = CIRCLE('',#123090,0.208574704164); +#123090 = AXIS2_PLACEMENT_3D('',#123091,#123092,#123093); +#123091 = CARTESIAN_POINT('',(-0.728168876214,8.15,2.640924866458E-017) + ); +#123092 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123093 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123094 = PCURVE('',#122898,#123095); +#123095 = DEFINITIONAL_REPRESENTATION('',(#123096),#123099); +#123096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123097,#123098), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#120705 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#120706 = CARTESIAN_POINT('',(4.772630242227,-1.85)); -#120707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123097 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#123098 = CARTESIAN_POINT('',(4.772630242227,-1.85)); +#123099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#120708 = PCURVE('',#90469,#120709); -#120709 = DEFINITIONAL_REPRESENTATION('',(#120710),#120718); -#120710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120711,#120712,#120713, - #120714,#120715,#120716,#120717),.UNSPECIFIED.,.T.,.F.) +#123100 = PCURVE('',#92861,#123101); +#123101 = DEFINITIONAL_REPRESENTATION('',(#123102),#123110); +#123102 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123103,#123104,#123105, + #123106,#123107,#123108,#123109),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#120711 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#120712 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#120713 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#120714 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#120715 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#120716 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#120717 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#120718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120719 = ORIENTED_EDGE('',*,*,#120490,.F.); -#120720 = ADVANCED_FACE('',(#120721),#120610,.T.); -#120721 = FACE_BOUND('',#120722,.T.); -#120722 = EDGE_LOOP('',(#120723,#120750,#120751,#120774)); -#120723 = ORIENTED_EDGE('',*,*,#120724,.T.); -#120724 = EDGE_CURVE('',#120725,#120595,#120727,.T.); -#120725 = VERTEX_POINT('',#120726); -#120726 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.E+000)); -#120727 = SURFACE_CURVE('',#120728,(#120733,#120739),.PCURVE_S1.); -#120728 = CIRCLE('',#120729,0.308574064194); -#120729 = AXIS2_PLACEMENT_3D('',#120730,#120731,#120732); -#120730 = CARTESIAN_POINT('',(-0.728168876214,8.15,2.640924866458E-017) - ); -#120731 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120732 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120733 = PCURVE('',#120610,#120734); -#120734 = DEFINITIONAL_REPRESENTATION('',(#120735),#120738); -#120735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120736,#120737), +#123103 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#123104 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#123105 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#123106 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#123107 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#123108 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#123109 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#123110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123111 = ORIENTED_EDGE('',*,*,#122882,.F.); +#123112 = ADVANCED_FACE('',(#123113),#123002,.T.); +#123113 = FACE_BOUND('',#123114,.T.); +#123114 = EDGE_LOOP('',(#123115,#123142,#123143,#123166)); +#123115 = ORIENTED_EDGE('',*,*,#123116,.T.); +#123116 = EDGE_CURVE('',#123117,#122987,#123119,.T.); +#123117 = VERTEX_POINT('',#123118); +#123118 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.E+000)); +#123119 = SURFACE_CURVE('',#123120,(#123125,#123131),.PCURVE_S1.); +#123120 = CIRCLE('',#123121,0.308574064194); +#123121 = AXIS2_PLACEMENT_3D('',#123122,#123123,#123124); +#123122 = CARTESIAN_POINT('',(-0.728168876214,8.15,2.640924866458E-017) + ); +#123123 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123124 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123125 = PCURVE('',#123002,#123126); +#123126 = DEFINITIONAL_REPRESENTATION('',(#123127),#123130); +#123127 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123128,#123129), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#120736 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#120737 = CARTESIAN_POINT('',(4.761821717947,-1.85)); -#120738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123128 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#123129 = CARTESIAN_POINT('',(4.761821717947,-1.85)); +#123130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#120739 = PCURVE('',#90469,#120740); -#120740 = DEFINITIONAL_REPRESENTATION('',(#120741),#120749); -#120741 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#120742,#120743,#120744, - #120745,#120746,#120747,#120748),.UNSPECIFIED.,.T.,.F.) +#123131 = PCURVE('',#92861,#123132); +#123132 = DEFINITIONAL_REPRESENTATION('',(#123133),#123141); +#123133 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123134,#123135,#123136, + #123137,#123138,#123139,#123140),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#120742 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#120743 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#120744 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#120745 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#120746 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#120747 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#120748 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#120749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120750 = ORIENTED_EDGE('',*,*,#120594,.T.); -#120751 = ORIENTED_EDGE('',*,*,#120752,.F.); -#120752 = EDGE_CURVE('',#120753,#120572,#120755,.T.); -#120753 = VERTEX_POINT('',#120754); -#120754 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.E+000)); -#120755 = SURFACE_CURVE('',#120756,(#120761,#120767),.PCURVE_S1.); -#120756 = CIRCLE('',#120757,0.308574064194); -#120757 = AXIS2_PLACEMENT_3D('',#120758,#120759,#120760); -#120758 = CARTESIAN_POINT('',(-0.728168876214,8.35,2.640924866458E-017) - ); -#120759 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120760 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#120761 = PCURVE('',#120610,#120762); -#120762 = DEFINITIONAL_REPRESENTATION('',(#120763),#120766); -#120763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120764,#120765), +#123134 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#123135 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#123136 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#123137 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#123138 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#123139 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#123140 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#123141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123142 = ORIENTED_EDGE('',*,*,#122986,.T.); +#123143 = ORIENTED_EDGE('',*,*,#123144,.F.); +#123144 = EDGE_CURVE('',#123145,#122964,#123147,.T.); +#123145 = VERTEX_POINT('',#123146); +#123146 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.E+000)); +#123147 = SURFACE_CURVE('',#123148,(#123153,#123159),.PCURVE_S1.); +#123148 = CIRCLE('',#123149,0.308574064194); +#123149 = AXIS2_PLACEMENT_3D('',#123150,#123151,#123152); +#123150 = CARTESIAN_POINT('',(-0.728168876214,8.35,2.640924866458E-017) + ); +#123151 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123152 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123153 = PCURVE('',#123002,#123154); +#123154 = DEFINITIONAL_REPRESENTATION('',(#123155),#123158); +#123155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123156,#123157), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#120764 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#120765 = CARTESIAN_POINT('',(4.761821717947,-1.65)); -#120766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120767 = PCURVE('',#90525,#120768); -#120768 = DEFINITIONAL_REPRESENTATION('',(#120769),#120773); -#120769 = CIRCLE('',#120770,0.308574064194); -#120770 = AXIS2_PLACEMENT_2D('',#120771,#120772); -#120771 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#120772 = DIRECTION('',(0.E+000,-1.)); -#120773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120774 = ORIENTED_EDGE('',*,*,#120775,.T.); -#120775 = EDGE_CURVE('',#120753,#120725,#120776,.T.); -#120776 = SURFACE_CURVE('',#120777,(#120781,#120787),.PCURVE_S1.); -#120777 = LINE('',#120778,#120779); -#120778 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#120779 = VECTOR('',#120780,1.); -#120780 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120781 = PCURVE('',#120610,#120782); -#120782 = DEFINITIONAL_REPRESENTATION('',(#120783),#120786); -#120783 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120784,#120785), +#123156 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#123157 = CARTESIAN_POINT('',(4.761821717947,-1.65)); +#123158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123159 = PCURVE('',#92917,#123160); +#123160 = DEFINITIONAL_REPRESENTATION('',(#123161),#123165); +#123161 = CIRCLE('',#123162,0.308574064194); +#123162 = AXIS2_PLACEMENT_2D('',#123163,#123164); +#123163 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#123164 = DIRECTION('',(0.E+000,-1.)); +#123165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123166 = ORIENTED_EDGE('',*,*,#123167,.T.); +#123167 = EDGE_CURVE('',#123145,#123117,#123168,.T.); +#123168 = SURFACE_CURVE('',#123169,(#123173,#123179),.PCURVE_S1.); +#123169 = LINE('',#123170,#123171); +#123170 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#123171 = VECTOR('',#123172,1.); +#123172 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123173 = PCURVE('',#123002,#123174); +#123174 = DEFINITIONAL_REPRESENTATION('',(#123175),#123178); +#123175 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123176,#123177), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#120784 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#120785 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#120786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120787 = PCURVE('',#120788,#120793); -#120788 = PLANE('',#120789); -#120789 = AXIS2_PLACEMENT_3D('',#120790,#120791,#120792); -#120790 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#120791 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#120792 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120793 = DEFINITIONAL_REPRESENTATION('',(#120794),#120798); -#120794 = LINE('',#120795,#120796); -#120795 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#120796 = VECTOR('',#120797,1.); -#120797 = DIRECTION('',(-1.,0.E+000)); -#120798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120799 = ADVANCED_FACE('',(#120800),#120788,.T.); -#120800 = FACE_BOUND('',#120801,.T.); -#120801 = EDGE_LOOP('',(#120802,#120831,#120852,#120853)); -#120802 = ORIENTED_EDGE('',*,*,#120803,.T.); -#120803 = EDGE_CURVE('',#120804,#120806,#120808,.T.); -#120804 = VERTEX_POINT('',#120805); -#120805 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.530776333563)); -#120806 = VERTEX_POINT('',#120807); -#120807 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.530776333563)); -#120808 = SURFACE_CURVE('',#120809,(#120813,#120820),.PCURVE_S1.); -#120809 = LINE('',#120810,#120811); -#120810 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#120811 = VECTOR('',#120812,1.); -#120812 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120813 = PCURVE('',#120788,#120814); -#120814 = DEFINITIONAL_REPRESENTATION('',(#120815),#120819); -#120815 = LINE('',#120816,#120817); -#120816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120817 = VECTOR('',#120818,1.); -#120818 = DIRECTION('',(-1.,0.E+000)); -#120819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120820 = PCURVE('',#120821,#120826); -#120821 = CYLINDRICAL_SURFACE('',#120822,0.119270391569); -#120822 = AXIS2_PLACEMENT_3D('',#120823,#120824,#120825); -#120823 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#120824 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120825 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120826 = DEFINITIONAL_REPRESENTATION('',(#120827),#120830); -#120827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120828,#120829), +#123176 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#123177 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#123178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123179 = PCURVE('',#123180,#123185); +#123180 = PLANE('',#123181); +#123181 = AXIS2_PLACEMENT_3D('',#123182,#123183,#123184); +#123182 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#123183 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#123184 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123185 = DEFINITIONAL_REPRESENTATION('',(#123186),#123190); +#123186 = LINE('',#123187,#123188); +#123187 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#123188 = VECTOR('',#123189,1.); +#123189 = DIRECTION('',(-1.,0.E+000)); +#123190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123191 = ADVANCED_FACE('',(#123192),#123180,.T.); +#123192 = FACE_BOUND('',#123193,.T.); +#123193 = EDGE_LOOP('',(#123194,#123223,#123244,#123245)); +#123194 = ORIENTED_EDGE('',*,*,#123195,.T.); +#123195 = EDGE_CURVE('',#123196,#123198,#123200,.T.); +#123196 = VERTEX_POINT('',#123197); +#123197 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.530776333563)); +#123198 = VERTEX_POINT('',#123199); +#123199 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.530776333563)); +#123200 = SURFACE_CURVE('',#123201,(#123205,#123212),.PCURVE_S1.); +#123201 = LINE('',#123202,#123203); +#123202 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#123203 = VECTOR('',#123204,1.); +#123204 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123205 = PCURVE('',#123180,#123206); +#123206 = DEFINITIONAL_REPRESENTATION('',(#123207),#123211); +#123207 = LINE('',#123208,#123209); +#123208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123209 = VECTOR('',#123210,1.); +#123210 = DIRECTION('',(-1.,0.E+000)); +#123211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123212 = PCURVE('',#123213,#123218); +#123213 = CYLINDRICAL_SURFACE('',#123214,0.119270391569); +#123214 = AXIS2_PLACEMENT_3D('',#123215,#123216,#123217); +#123215 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#123216 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123217 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123218 = DEFINITIONAL_REPRESENTATION('',(#123219),#123222); +#123219 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123220,#123221), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#120828 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#120829 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#120830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120831 = ORIENTED_EDGE('',*,*,#120832,.T.); -#120832 = EDGE_CURVE('',#120806,#120725,#120833,.T.); -#120833 = SURFACE_CURVE('',#120834,(#120838,#120845),.PCURVE_S1.); -#120834 = LINE('',#120835,#120836); -#120835 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.530776333563)); -#120836 = VECTOR('',#120837,1.); -#120837 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120838 = PCURVE('',#120788,#120839); -#120839 = DEFINITIONAL_REPRESENTATION('',(#120840),#120844); -#120840 = LINE('',#120841,#120842); -#120841 = CARTESIAN_POINT('',(-1.85,1.133910970711E-033)); -#120842 = VECTOR('',#120843,1.); -#120843 = DIRECTION('',(4.535643882845E-032,-1.)); -#120844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120845 = PCURVE('',#90469,#120846); -#120846 = DEFINITIONAL_REPRESENTATION('',(#120847),#120851); -#120847 = LINE('',#120848,#120849); -#120848 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#120849 = VECTOR('',#120850,1.); -#120850 = DIRECTION('',(1.,-1.021336205033E-016)); -#120851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120852 = ORIENTED_EDGE('',*,*,#120775,.F.); -#120853 = ORIENTED_EDGE('',*,*,#120854,.F.); -#120854 = EDGE_CURVE('',#120804,#120753,#120855,.T.); -#120855 = SURFACE_CURVE('',#120856,(#120860,#120867),.PCURVE_S1.); -#120856 = LINE('',#120857,#120858); -#120857 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.530776333563)); -#120858 = VECTOR('',#120859,1.); -#120859 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120860 = PCURVE('',#120788,#120861); -#120861 = DEFINITIONAL_REPRESENTATION('',(#120862),#120866); -#120862 = LINE('',#120863,#120864); -#120863 = CARTESIAN_POINT('',(-1.65,-1.133910970711E-033)); -#120864 = VECTOR('',#120865,1.); -#120865 = DIRECTION('',(4.535643882845E-032,-1.)); -#120866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120867 = PCURVE('',#90525,#120868); -#120868 = DEFINITIONAL_REPRESENTATION('',(#120869),#120873); -#120869 = LINE('',#120870,#120871); -#120870 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#120871 = VECTOR('',#120872,1.); -#120872 = DIRECTION('',(-1.,-1.021336205033E-016)); -#120873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120874 = ADVANCED_FACE('',(#120875),#120683,.T.); -#120875 = FACE_BOUND('',#120876,.T.); -#120876 = EDGE_LOOP('',(#120877,#120906,#120927,#120928)); -#120877 = ORIENTED_EDGE('',*,*,#120878,.T.); -#120878 = EDGE_CURVE('',#120879,#120881,#120883,.T.); -#120879 = VERTEX_POINT('',#120880); -#120880 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.530776333563)); -#120881 = VERTEX_POINT('',#120882); -#120882 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.530776333563)); -#120883 = SURFACE_CURVE('',#120884,(#120888,#120895),.PCURVE_S1.); -#120884 = LINE('',#120885,#120886); -#120885 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#120886 = VECTOR('',#120887,1.); -#120887 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#120888 = PCURVE('',#120683,#120889); -#120889 = DEFINITIONAL_REPRESENTATION('',(#120890),#120894); -#120890 = LINE('',#120891,#120892); -#120891 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#120892 = VECTOR('',#120893,1.); -#120893 = DIRECTION('',(-1.,0.E+000)); -#120894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120895 = PCURVE('',#120896,#120901); -#120896 = CYLINDRICAL_SURFACE('',#120897,0.2192697516); -#120897 = AXIS2_PLACEMENT_3D('',#120898,#120899,#120900); -#120898 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#120899 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120900 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120901 = DEFINITIONAL_REPRESENTATION('',(#120902),#120905); -#120902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120903,#120904), +#123220 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#123221 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#123222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123223 = ORIENTED_EDGE('',*,*,#123224,.T.); +#123224 = EDGE_CURVE('',#123198,#123117,#123225,.T.); +#123225 = SURFACE_CURVE('',#123226,(#123230,#123237),.PCURVE_S1.); +#123226 = LINE('',#123227,#123228); +#123227 = CARTESIAN_POINT('',(-0.419594812019,8.15,0.530776333563)); +#123228 = VECTOR('',#123229,1.); +#123229 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#123230 = PCURVE('',#123180,#123231); +#123231 = DEFINITIONAL_REPRESENTATION('',(#123232),#123236); +#123232 = LINE('',#123233,#123234); +#123233 = CARTESIAN_POINT('',(-1.85,1.133910970711E-033)); +#123234 = VECTOR('',#123235,1.); +#123235 = DIRECTION('',(4.535643882845E-032,-1.)); +#123236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123237 = PCURVE('',#92861,#123238); +#123238 = DEFINITIONAL_REPRESENTATION('',(#123239),#123243); +#123239 = LINE('',#123240,#123241); +#123240 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#123241 = VECTOR('',#123242,1.); +#123242 = DIRECTION('',(1.,-1.021336205033E-016)); +#123243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123244 = ORIENTED_EDGE('',*,*,#123167,.F.); +#123245 = ORIENTED_EDGE('',*,*,#123246,.F.); +#123246 = EDGE_CURVE('',#123196,#123145,#123247,.T.); +#123247 = SURFACE_CURVE('',#123248,(#123252,#123259),.PCURVE_S1.); +#123248 = LINE('',#123249,#123250); +#123249 = CARTESIAN_POINT('',(-0.419594812019,8.35,0.530776333563)); +#123250 = VECTOR('',#123251,1.); +#123251 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#123252 = PCURVE('',#123180,#123253); +#123253 = DEFINITIONAL_REPRESENTATION('',(#123254),#123258); +#123254 = LINE('',#123255,#123256); +#123255 = CARTESIAN_POINT('',(-1.65,-1.133910970711E-033)); +#123256 = VECTOR('',#123257,1.); +#123257 = DIRECTION('',(4.535643882845E-032,-1.)); +#123258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123259 = PCURVE('',#92917,#123260); +#123260 = DEFINITIONAL_REPRESENTATION('',(#123261),#123265); +#123261 = LINE('',#123262,#123263); +#123262 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#123263 = VECTOR('',#123264,1.); +#123264 = DIRECTION('',(-1.,-1.021336205033E-016)); +#123265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123266 = ADVANCED_FACE('',(#123267),#123075,.T.); +#123267 = FACE_BOUND('',#123268,.T.); +#123268 = EDGE_LOOP('',(#123269,#123298,#123319,#123320)); +#123269 = ORIENTED_EDGE('',*,*,#123270,.T.); +#123270 = EDGE_CURVE('',#123271,#123273,#123275,.T.); +#123271 = VERTEX_POINT('',#123272); +#123272 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.530776333563)); +#123273 = VERTEX_POINT('',#123274); +#123274 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.530776333563)); +#123275 = SURFACE_CURVE('',#123276,(#123280,#123287),.PCURVE_S1.); +#123276 = LINE('',#123277,#123278); +#123277 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#123278 = VECTOR('',#123279,1.); +#123279 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123280 = PCURVE('',#123075,#123281); +#123281 = DEFINITIONAL_REPRESENTATION('',(#123282),#123286); +#123282 = LINE('',#123283,#123284); +#123283 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123284 = VECTOR('',#123285,1.); +#123285 = DIRECTION('',(-1.,0.E+000)); +#123286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123287 = PCURVE('',#123288,#123293); +#123288 = CYLINDRICAL_SURFACE('',#123289,0.2192697516); +#123289 = AXIS2_PLACEMENT_3D('',#123290,#123291,#123292); +#123290 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#123291 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123292 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123293 = DEFINITIONAL_REPRESENTATION('',(#123294),#123297); +#123294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123295,#123296), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#120903 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#120904 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#120905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120906 = ORIENTED_EDGE('',*,*,#120907,.T.); -#120907 = EDGE_CURVE('',#120881,#120646,#120908,.T.); -#120908 = SURFACE_CURVE('',#120909,(#120913,#120920),.PCURVE_S1.); -#120909 = LINE('',#120910,#120911); -#120910 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.530776333563)); -#120911 = VECTOR('',#120912,1.); -#120912 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120913 = PCURVE('',#120683,#120914); -#120914 = DEFINITIONAL_REPRESENTATION('',(#120915),#120919); -#120915 = LINE('',#120916,#120917); -#120916 = CARTESIAN_POINT('',(1.65,4.535643882845E-033)); -#120917 = VECTOR('',#120918,1.); -#120918 = DIRECTION('',(-4.535643882845E-032,-1.)); -#120919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120920 = PCURVE('',#90525,#120921); -#120921 = DEFINITIONAL_REPRESENTATION('',(#120922),#120926); -#120922 = LINE('',#120923,#120924); -#120923 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#120924 = VECTOR('',#120925,1.); -#120925 = DIRECTION('',(-1.,-1.021336205033E-016)); -#120926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120927 = ORIENTED_EDGE('',*,*,#120668,.F.); -#120928 = ORIENTED_EDGE('',*,*,#120929,.F.); -#120929 = EDGE_CURVE('',#120879,#120669,#120930,.T.); -#120930 = SURFACE_CURVE('',#120931,(#120935,#120942),.PCURVE_S1.); -#120931 = LINE('',#120932,#120933); -#120932 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.530776333563)); -#120933 = VECTOR('',#120934,1.); -#120934 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#120935 = PCURVE('',#120683,#120936); -#120936 = DEFINITIONAL_REPRESENTATION('',(#120937),#120941); -#120937 = LINE('',#120938,#120939); -#120938 = CARTESIAN_POINT('',(1.85,-4.535643882845E-033)); -#120939 = VECTOR('',#120940,1.); -#120940 = DIRECTION('',(-4.535643882845E-032,-1.)); -#120941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120942 = PCURVE('',#90469,#120943); -#120943 = DEFINITIONAL_REPRESENTATION('',(#120944),#120948); -#120944 = LINE('',#120945,#120946); -#120945 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#120946 = VECTOR('',#120947,1.); -#120947 = DIRECTION('',(1.,-1.021336205033E-016)); -#120948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120949 = ADVANCED_FACE('',(#120950),#120896,.T.); -#120950 = FACE_BOUND('',#120951,.T.); -#120951 = EDGE_LOOP('',(#120952,#120953,#120976,#121021)); -#120952 = ORIENTED_EDGE('',*,*,#120878,.F.); -#120953 = ORIENTED_EDGE('',*,*,#120954,.F.); -#120954 = EDGE_CURVE('',#120955,#120879,#120957,.T.); -#120955 = VERTEX_POINT('',#120956); -#120956 = CARTESIAN_POINT('',(-0.304819755875,8.15,0.75)); -#120957 = SURFACE_CURVE('',#120958,(#120963,#120969),.PCURVE_S1.); -#120958 = CIRCLE('',#120959,0.2192697516); -#120959 = AXIS2_PLACEMENT_3D('',#120960,#120961,#120962); -#120960 = CARTESIAN_POINT('',(-0.30032442045,8.15,0.530776333563)); -#120961 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120962 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#120963 = PCURVE('',#120896,#120964); -#120964 = DEFINITIONAL_REPRESENTATION('',(#120965),#120968); -#120965 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#120966,#120967), +#123295 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#123296 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#123297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123298 = ORIENTED_EDGE('',*,*,#123299,.T.); +#123299 = EDGE_CURVE('',#123273,#123038,#123300,.T.); +#123300 = SURFACE_CURVE('',#123301,(#123305,#123312),.PCURVE_S1.); +#123301 = LINE('',#123302,#123303); +#123302 = CARTESIAN_POINT('',(-0.51959417205,8.35,0.530776333563)); +#123303 = VECTOR('',#123304,1.); +#123304 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#123305 = PCURVE('',#123075,#123306); +#123306 = DEFINITIONAL_REPRESENTATION('',(#123307),#123311); +#123307 = LINE('',#123308,#123309); +#123308 = CARTESIAN_POINT('',(1.65,4.535643882845E-033)); +#123309 = VECTOR('',#123310,1.); +#123310 = DIRECTION('',(-4.535643882845E-032,-1.)); +#123311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123312 = PCURVE('',#92917,#123313); +#123313 = DEFINITIONAL_REPRESENTATION('',(#123314),#123318); +#123314 = LINE('',#123315,#123316); +#123315 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#123316 = VECTOR('',#123317,1.); +#123317 = DIRECTION('',(-1.,-1.021336205033E-016)); +#123318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123319 = ORIENTED_EDGE('',*,*,#123060,.F.); +#123320 = ORIENTED_EDGE('',*,*,#123321,.F.); +#123321 = EDGE_CURVE('',#123271,#123061,#123322,.T.); +#123322 = SURFACE_CURVE('',#123323,(#123327,#123334),.PCURVE_S1.); +#123323 = LINE('',#123324,#123325); +#123324 = CARTESIAN_POINT('',(-0.51959417205,8.15,0.530776333563)); +#123325 = VECTOR('',#123326,1.); +#123326 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#123327 = PCURVE('',#123075,#123328); +#123328 = DEFINITIONAL_REPRESENTATION('',(#123329),#123333); +#123329 = LINE('',#123330,#123331); +#123330 = CARTESIAN_POINT('',(1.85,-4.535643882845E-033)); +#123331 = VECTOR('',#123332,1.); +#123332 = DIRECTION('',(-4.535643882845E-032,-1.)); +#123333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123334 = PCURVE('',#92861,#123335); +#123335 = DEFINITIONAL_REPRESENTATION('',(#123336),#123340); +#123336 = LINE('',#123337,#123338); +#123337 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#123338 = VECTOR('',#123339,1.); +#123339 = DIRECTION('',(1.,-1.021336205033E-016)); +#123340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123341 = ADVANCED_FACE('',(#123342),#123288,.T.); +#123342 = FACE_BOUND('',#123343,.T.); +#123343 = EDGE_LOOP('',(#123344,#123345,#123368,#123413)); +#123344 = ORIENTED_EDGE('',*,*,#123270,.F.); +#123345 = ORIENTED_EDGE('',*,*,#123346,.F.); +#123346 = EDGE_CURVE('',#123347,#123271,#123349,.T.); +#123347 = VERTEX_POINT('',#123348); +#123348 = CARTESIAN_POINT('',(-0.304819755875,8.15,0.75)); +#123349 = SURFACE_CURVE('',#123350,(#123355,#123361),.PCURVE_S1.); +#123350 = CIRCLE('',#123351,0.2192697516); +#123351 = AXIS2_PLACEMENT_3D('',#123352,#123353,#123354); +#123352 = CARTESIAN_POINT('',(-0.30032442045,8.15,0.530776333563)); +#123353 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123354 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123355 = PCURVE('',#123288,#123356); +#123356 = DEFINITIONAL_REPRESENTATION('',(#123357),#123360); +#123357 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123358,#123359), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#120966 = CARTESIAN_POINT('',(1.591299156552,1.85)); -#120967 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#120968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120969 = PCURVE('',#90469,#120970); -#120970 = DEFINITIONAL_REPRESENTATION('',(#120971),#120975); -#120971 = CIRCLE('',#120972,0.2192697516); -#120972 = AXIS2_PLACEMENT_2D('',#120973,#120974); -#120973 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#120974 = DIRECTION('',(0.E+000,1.)); -#120975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#120976 = ORIENTED_EDGE('',*,*,#120977,.F.); -#120977 = EDGE_CURVE('',#120978,#120955,#120980,.T.); -#120978 = VERTEX_POINT('',#120979); -#120979 = CARTESIAN_POINT('',(-0.304819755875,8.35,0.75)); -#120980 = SURFACE_CURVE('',#120981,(#120985,#121014),.PCURVE_S1.); -#120981 = LINE('',#120982,#120983); -#120982 = CARTESIAN_POINT('',(-0.304819755875,8.15,0.75)); -#120983 = VECTOR('',#120984,1.); -#120984 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#120985 = PCURVE('',#120896,#120986); -#120986 = DEFINITIONAL_REPRESENTATION('',(#120987),#121013); -#120987 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#120988,#120989,#120990, - #120991,#120992,#120993,#120994,#120995,#120996,#120997,#120998, - #120999,#121000,#121001,#121002,#121003,#121004,#121005,#121006, - #121007,#121008,#121009,#121010,#121011,#121012),.UNSPECIFIED.,.F., +#123358 = CARTESIAN_POINT('',(1.591299156552,1.85)); +#123359 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#123360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123361 = PCURVE('',#92861,#123362); +#123362 = DEFINITIONAL_REPRESENTATION('',(#123363),#123367); +#123363 = CIRCLE('',#123364,0.2192697516); +#123364 = AXIS2_PLACEMENT_2D('',#123365,#123366); +#123365 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#123366 = DIRECTION('',(0.E+000,1.)); +#123367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123368 = ORIENTED_EDGE('',*,*,#123369,.F.); +#123369 = EDGE_CURVE('',#123370,#123347,#123372,.T.); +#123370 = VERTEX_POINT('',#123371); +#123371 = CARTESIAN_POINT('',(-0.304819755875,8.35,0.75)); +#123372 = SURFACE_CURVE('',#123373,(#123377,#123406),.PCURVE_S1.); +#123373 = LINE('',#123374,#123375); +#123374 = CARTESIAN_POINT('',(-0.304819755875,8.15,0.75)); +#123375 = VECTOR('',#123376,1.); +#123376 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123377 = PCURVE('',#123288,#123378); +#123378 = DEFINITIONAL_REPRESENTATION('',(#123379),#123405); +#123379 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#123380,#123381,#123382, + #123383,#123384,#123385,#123386,#123387,#123388,#123389,#123390, + #123391,#123392,#123393,#123394,#123395,#123396,#123397,#123398, + #123399,#123400,#123401,#123402,#123403,#123404),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -149011,128 +152013,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545455E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.UNSPECIFIED.); -#120988 = CARTESIAN_POINT('',(1.591299156552,1.65)); -#120989 = CARTESIAN_POINT('',(1.591299156552,1.65303030303)); -#120990 = CARTESIAN_POINT('',(1.591299156552,1.659090909091)); -#120991 = CARTESIAN_POINT('',(1.591299156552,1.668181818182)); -#120992 = CARTESIAN_POINT('',(1.591299156552,1.677272727273)); -#120993 = CARTESIAN_POINT('',(1.591299156552,1.686363636364)); -#120994 = CARTESIAN_POINT('',(1.591299156552,1.695454545455)); -#120995 = CARTESIAN_POINT('',(1.591299156552,1.704545454545)); -#120996 = CARTESIAN_POINT('',(1.591299156552,1.713636363636)); -#120997 = CARTESIAN_POINT('',(1.591299156552,1.722727272727)); -#120998 = CARTESIAN_POINT('',(1.591299156552,1.731818181818)); -#120999 = CARTESIAN_POINT('',(1.591299156552,1.740909090909)); -#121000 = CARTESIAN_POINT('',(1.591299156552,1.75)); -#121001 = CARTESIAN_POINT('',(1.591299156552,1.759090909091)); -#121002 = CARTESIAN_POINT('',(1.591299156552,1.768181818182)); -#121003 = CARTESIAN_POINT('',(1.591299156552,1.777272727273)); -#121004 = CARTESIAN_POINT('',(1.591299156552,1.786363636364)); -#121005 = CARTESIAN_POINT('',(1.591299156552,1.795454545455)); -#121006 = CARTESIAN_POINT('',(1.591299156552,1.804545454545)); -#121007 = CARTESIAN_POINT('',(1.591299156552,1.813636363636)); -#121008 = CARTESIAN_POINT('',(1.591299156552,1.822727272727)); -#121009 = CARTESIAN_POINT('',(1.591299156552,1.831818181818)); -#121010 = CARTESIAN_POINT('',(1.591299156552,1.840909090909)); -#121011 = CARTESIAN_POINT('',(1.591299156552,1.84696969697)); -#121012 = CARTESIAN_POINT('',(1.591299156552,1.85)); -#121013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121014 = PCURVE('',#90551,#121015); -#121015 = DEFINITIONAL_REPRESENTATION('',(#121016),#121020); -#121016 = LINE('',#121017,#121018); -#121017 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#121018 = VECTOR('',#121019,1.); -#121019 = DIRECTION('',(4.440892098501E-016,-1.)); -#121020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121021 = ORIENTED_EDGE('',*,*,#121022,.T.); -#121022 = EDGE_CURVE('',#120978,#120881,#121023,.T.); -#121023 = SURFACE_CURVE('',#121024,(#121029,#121035),.PCURVE_S1.); -#121024 = CIRCLE('',#121025,0.2192697516); -#121025 = AXIS2_PLACEMENT_3D('',#121026,#121027,#121028); -#121026 = CARTESIAN_POINT('',(-0.30032442045,8.35,0.530776333563)); -#121027 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121028 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121029 = PCURVE('',#120896,#121030); -#121030 = DEFINITIONAL_REPRESENTATION('',(#121031),#121034); -#121031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121032,#121033), +#123380 = CARTESIAN_POINT('',(1.591299156552,1.65)); +#123381 = CARTESIAN_POINT('',(1.591299156552,1.65303030303)); +#123382 = CARTESIAN_POINT('',(1.591299156552,1.659090909091)); +#123383 = CARTESIAN_POINT('',(1.591299156552,1.668181818182)); +#123384 = CARTESIAN_POINT('',(1.591299156552,1.677272727273)); +#123385 = CARTESIAN_POINT('',(1.591299156552,1.686363636364)); +#123386 = CARTESIAN_POINT('',(1.591299156552,1.695454545455)); +#123387 = CARTESIAN_POINT('',(1.591299156552,1.704545454545)); +#123388 = CARTESIAN_POINT('',(1.591299156552,1.713636363636)); +#123389 = CARTESIAN_POINT('',(1.591299156552,1.722727272727)); +#123390 = CARTESIAN_POINT('',(1.591299156552,1.731818181818)); +#123391 = CARTESIAN_POINT('',(1.591299156552,1.740909090909)); +#123392 = CARTESIAN_POINT('',(1.591299156552,1.75)); +#123393 = CARTESIAN_POINT('',(1.591299156552,1.759090909091)); +#123394 = CARTESIAN_POINT('',(1.591299156552,1.768181818182)); +#123395 = CARTESIAN_POINT('',(1.591299156552,1.777272727273)); +#123396 = CARTESIAN_POINT('',(1.591299156552,1.786363636364)); +#123397 = CARTESIAN_POINT('',(1.591299156552,1.795454545455)); +#123398 = CARTESIAN_POINT('',(1.591299156552,1.804545454545)); +#123399 = CARTESIAN_POINT('',(1.591299156552,1.813636363636)); +#123400 = CARTESIAN_POINT('',(1.591299156552,1.822727272727)); +#123401 = CARTESIAN_POINT('',(1.591299156552,1.831818181818)); +#123402 = CARTESIAN_POINT('',(1.591299156552,1.840909090909)); +#123403 = CARTESIAN_POINT('',(1.591299156552,1.84696969697)); +#123404 = CARTESIAN_POINT('',(1.591299156552,1.85)); +#123405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123406 = PCURVE('',#92943,#123407); +#123407 = DEFINITIONAL_REPRESENTATION('',(#123408),#123412); +#123408 = LINE('',#123409,#123410); +#123409 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#123410 = VECTOR('',#123411,1.); +#123411 = DIRECTION('',(4.440892098501E-016,-1.)); +#123412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123413 = ORIENTED_EDGE('',*,*,#123414,.T.); +#123414 = EDGE_CURVE('',#123370,#123273,#123415,.T.); +#123415 = SURFACE_CURVE('',#123416,(#123421,#123427),.PCURVE_S1.); +#123416 = CIRCLE('',#123417,0.2192697516); +#123417 = AXIS2_PLACEMENT_3D('',#123418,#123419,#123420); +#123418 = CARTESIAN_POINT('',(-0.30032442045,8.35,0.530776333563)); +#123419 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123420 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123421 = PCURVE('',#123288,#123422); +#123422 = DEFINITIONAL_REPRESENTATION('',(#123423),#123426); +#123423 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123424,#123425), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121032 = CARTESIAN_POINT('',(1.591299156552,1.65)); -#121033 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#121034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123424 = CARTESIAN_POINT('',(1.591299156552,1.65)); +#123425 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#123426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121035 = PCURVE('',#90525,#121036); -#121036 = DEFINITIONAL_REPRESENTATION('',(#121037),#121045); -#121037 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121038,#121039,#121040, - #121041,#121042,#121043,#121044),.UNSPECIFIED.,.T.,.F.) +#123427 = PCURVE('',#92917,#123428); +#123428 = DEFINITIONAL_REPRESENTATION('',(#123429),#123437); +#123429 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123430,#123431,#123432, + #123433,#123434,#123435,#123436),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#121038 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#121039 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#121040 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#121041 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#121042 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#121043 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#121044 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#121045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121046 = ADVANCED_FACE('',(#121047),#120821,.F.); -#121047 = FACE_BOUND('',#121048,.F.); -#121048 = EDGE_LOOP('',(#121049,#121050,#121073,#121118)); -#121049 = ORIENTED_EDGE('',*,*,#120803,.T.); -#121050 = ORIENTED_EDGE('',*,*,#121051,.F.); -#121051 = EDGE_CURVE('',#121052,#120806,#121054,.T.); -#121052 = VERTEX_POINT('',#121053); -#121053 = CARTESIAN_POINT('',(-0.303662633502,8.15,0.65)); -#121054 = SURFACE_CURVE('',#121055,(#121060,#121066),.PCURVE_S1.); -#121055 = CIRCLE('',#121056,0.119270391569); -#121056 = AXIS2_PLACEMENT_3D('',#121057,#121058,#121059); -#121057 = CARTESIAN_POINT('',(-0.30032442045,8.15,0.530776333563)); -#121058 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121059 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121060 = PCURVE('',#120821,#121061); -#121061 = DEFINITIONAL_REPRESENTATION('',(#121062),#121065); -#121062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121063,#121064), +#123430 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#123431 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#123432 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#123433 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#123434 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#123435 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#123436 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#123437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123438 = ADVANCED_FACE('',(#123439),#123213,.F.); +#123439 = FACE_BOUND('',#123440,.F.); +#123440 = EDGE_LOOP('',(#123441,#123442,#123465,#123510)); +#123441 = ORIENTED_EDGE('',*,*,#123195,.T.); +#123442 = ORIENTED_EDGE('',*,*,#123443,.F.); +#123443 = EDGE_CURVE('',#123444,#123198,#123446,.T.); +#123444 = VERTEX_POINT('',#123445); +#123445 = CARTESIAN_POINT('',(-0.303662633502,8.15,0.65)); +#123446 = SURFACE_CURVE('',#123447,(#123452,#123458),.PCURVE_S1.); +#123447 = CIRCLE('',#123448,0.119270391569); +#123448 = AXIS2_PLACEMENT_3D('',#123449,#123450,#123451); +#123449 = CARTESIAN_POINT('',(-0.30032442045,8.15,0.530776333563)); +#123450 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123451 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123452 = PCURVE('',#123213,#123453); +#123453 = DEFINITIONAL_REPRESENTATION('',(#123454),#123457); +#123454 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123455,#123456), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121063 = CARTESIAN_POINT('',(1.598788597134,1.85)); -#121064 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#121065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121066 = PCURVE('',#90469,#121067); -#121067 = DEFINITIONAL_REPRESENTATION('',(#121068),#121072); -#121068 = CIRCLE('',#121069,0.119270391569); -#121069 = AXIS2_PLACEMENT_2D('',#121070,#121071); -#121070 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#121071 = DIRECTION('',(0.E+000,1.)); -#121072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121073 = ORIENTED_EDGE('',*,*,#121074,.T.); -#121074 = EDGE_CURVE('',#121052,#121075,#121077,.T.); -#121075 = VERTEX_POINT('',#121076); -#121076 = CARTESIAN_POINT('',(-0.303662633502,8.35,0.65)); -#121077 = SURFACE_CURVE('',#121078,(#121082,#121111),.PCURVE_S1.); -#121078 = LINE('',#121079,#121080); -#121079 = CARTESIAN_POINT('',(-0.303662633502,8.15,0.65)); -#121080 = VECTOR('',#121081,1.); -#121081 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121082 = PCURVE('',#120821,#121083); -#121083 = DEFINITIONAL_REPRESENTATION('',(#121084),#121110); -#121084 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#121085,#121086,#121087, - #121088,#121089,#121090,#121091,#121092,#121093,#121094,#121095, - #121096,#121097,#121098,#121099,#121100,#121101,#121102,#121103, - #121104,#121105,#121106,#121107,#121108,#121109),.UNSPECIFIED.,.F., +#123455 = CARTESIAN_POINT('',(1.598788597134,1.85)); +#123456 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#123457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123458 = PCURVE('',#92861,#123459); +#123459 = DEFINITIONAL_REPRESENTATION('',(#123460),#123464); +#123460 = CIRCLE('',#123461,0.119270391569); +#123461 = AXIS2_PLACEMENT_2D('',#123462,#123463); +#123462 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#123463 = DIRECTION('',(0.E+000,1.)); +#123464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123465 = ORIENTED_EDGE('',*,*,#123466,.T.); +#123466 = EDGE_CURVE('',#123444,#123467,#123469,.T.); +#123467 = VERTEX_POINT('',#123468); +#123468 = CARTESIAN_POINT('',(-0.303662633502,8.35,0.65)); +#123469 = SURFACE_CURVE('',#123470,(#123474,#123503),.PCURVE_S1.); +#123470 = LINE('',#123471,#123472); +#123471 = CARTESIAN_POINT('',(-0.303662633502,8.15,0.65)); +#123472 = VECTOR('',#123473,1.); +#123473 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123474 = PCURVE('',#123213,#123475); +#123475 = DEFINITIONAL_REPRESENTATION('',(#123476),#123502); +#123476 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#123477,#123478,#123479, + #123480,#123481,#123482,#123483,#123484,#123485,#123486,#123487, + #123488,#123489,#123490,#123491,#123492,#123493,#123494,#123495, + #123496,#123497,#123498,#123499,#123500,#123501),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545455E-002,5.454545454545E-002, @@ -149141,956 +152143,956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#121085 = CARTESIAN_POINT('',(1.598788597134,1.85)); -#121086 = CARTESIAN_POINT('',(1.598788597134,1.84696969697)); -#121087 = CARTESIAN_POINT('',(1.598788597134,1.840909090909)); -#121088 = CARTESIAN_POINT('',(1.598788597134,1.831818181818)); -#121089 = CARTESIAN_POINT('',(1.598788597134,1.822727272727)); -#121090 = CARTESIAN_POINT('',(1.598788597134,1.813636363636)); -#121091 = CARTESIAN_POINT('',(1.598788597134,1.804545454545)); -#121092 = CARTESIAN_POINT('',(1.598788597134,1.795454545455)); -#121093 = CARTESIAN_POINT('',(1.598788597134,1.786363636364)); -#121094 = CARTESIAN_POINT('',(1.598788597134,1.777272727273)); -#121095 = CARTESIAN_POINT('',(1.598788597134,1.768181818182)); -#121096 = CARTESIAN_POINT('',(1.598788597134,1.759090909091)); -#121097 = CARTESIAN_POINT('',(1.598788597134,1.75)); -#121098 = CARTESIAN_POINT('',(1.598788597134,1.740909090909)); -#121099 = CARTESIAN_POINT('',(1.598788597134,1.731818181818)); -#121100 = CARTESIAN_POINT('',(1.598788597134,1.722727272727)); -#121101 = CARTESIAN_POINT('',(1.598788597134,1.713636363636)); -#121102 = CARTESIAN_POINT('',(1.598788597134,1.704545454545)); -#121103 = CARTESIAN_POINT('',(1.598788597134,1.695454545455)); -#121104 = CARTESIAN_POINT('',(1.598788597134,1.686363636364)); -#121105 = CARTESIAN_POINT('',(1.598788597134,1.677272727273)); -#121106 = CARTESIAN_POINT('',(1.598788597134,1.668181818182)); -#121107 = CARTESIAN_POINT('',(1.598788597134,1.659090909091)); -#121108 = CARTESIAN_POINT('',(1.598788597134,1.65303030303)); -#121109 = CARTESIAN_POINT('',(1.598788597134,1.65)); -#121110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121111 = PCURVE('',#90497,#121112); -#121112 = DEFINITIONAL_REPRESENTATION('',(#121113),#121117); -#121113 = LINE('',#121114,#121115); -#121114 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#121115 = VECTOR('',#121116,1.); -#121116 = DIRECTION('',(4.440892098501E-016,1.)); -#121117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121118 = ORIENTED_EDGE('',*,*,#121119,.T.); -#121119 = EDGE_CURVE('',#121075,#120804,#121120,.T.); -#121120 = SURFACE_CURVE('',#121121,(#121126,#121132),.PCURVE_S1.); -#121121 = CIRCLE('',#121122,0.119270391569); -#121122 = AXIS2_PLACEMENT_3D('',#121123,#121124,#121125); -#121123 = CARTESIAN_POINT('',(-0.30032442045,8.35,0.530776333563)); -#121124 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121125 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121126 = PCURVE('',#120821,#121127); -#121127 = DEFINITIONAL_REPRESENTATION('',(#121128),#121131); -#121128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121129,#121130), +#123477 = CARTESIAN_POINT('',(1.598788597134,1.85)); +#123478 = CARTESIAN_POINT('',(1.598788597134,1.84696969697)); +#123479 = CARTESIAN_POINT('',(1.598788597134,1.840909090909)); +#123480 = CARTESIAN_POINT('',(1.598788597134,1.831818181818)); +#123481 = CARTESIAN_POINT('',(1.598788597134,1.822727272727)); +#123482 = CARTESIAN_POINT('',(1.598788597134,1.813636363636)); +#123483 = CARTESIAN_POINT('',(1.598788597134,1.804545454545)); +#123484 = CARTESIAN_POINT('',(1.598788597134,1.795454545455)); +#123485 = CARTESIAN_POINT('',(1.598788597134,1.786363636364)); +#123486 = CARTESIAN_POINT('',(1.598788597134,1.777272727273)); +#123487 = CARTESIAN_POINT('',(1.598788597134,1.768181818182)); +#123488 = CARTESIAN_POINT('',(1.598788597134,1.759090909091)); +#123489 = CARTESIAN_POINT('',(1.598788597134,1.75)); +#123490 = CARTESIAN_POINT('',(1.598788597134,1.740909090909)); +#123491 = CARTESIAN_POINT('',(1.598788597134,1.731818181818)); +#123492 = CARTESIAN_POINT('',(1.598788597134,1.722727272727)); +#123493 = CARTESIAN_POINT('',(1.598788597134,1.713636363636)); +#123494 = CARTESIAN_POINT('',(1.598788597134,1.704545454545)); +#123495 = CARTESIAN_POINT('',(1.598788597134,1.695454545455)); +#123496 = CARTESIAN_POINT('',(1.598788597134,1.686363636364)); +#123497 = CARTESIAN_POINT('',(1.598788597134,1.677272727273)); +#123498 = CARTESIAN_POINT('',(1.598788597134,1.668181818182)); +#123499 = CARTESIAN_POINT('',(1.598788597134,1.659090909091)); +#123500 = CARTESIAN_POINT('',(1.598788597134,1.65303030303)); +#123501 = CARTESIAN_POINT('',(1.598788597134,1.65)); +#123502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123503 = PCURVE('',#92889,#123504); +#123504 = DEFINITIONAL_REPRESENTATION('',(#123505),#123509); +#123505 = LINE('',#123506,#123507); +#123506 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#123507 = VECTOR('',#123508,1.); +#123508 = DIRECTION('',(4.440892098501E-016,1.)); +#123509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123510 = ORIENTED_EDGE('',*,*,#123511,.T.); +#123511 = EDGE_CURVE('',#123467,#123196,#123512,.T.); +#123512 = SURFACE_CURVE('',#123513,(#123518,#123524),.PCURVE_S1.); +#123513 = CIRCLE('',#123514,0.119270391569); +#123514 = AXIS2_PLACEMENT_3D('',#123515,#123516,#123517); +#123515 = CARTESIAN_POINT('',(-0.30032442045,8.35,0.530776333563)); +#123516 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123517 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#123518 = PCURVE('',#123213,#123519); +#123519 = DEFINITIONAL_REPRESENTATION('',(#123520),#123523); +#123520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123521,#123522), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121129 = CARTESIAN_POINT('',(1.598788597134,1.65)); -#121130 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#121131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123521 = CARTESIAN_POINT('',(1.598788597134,1.65)); +#123522 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#123523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121132 = PCURVE('',#90525,#121133); -#121133 = DEFINITIONAL_REPRESENTATION('',(#121134),#121142); -#121134 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121135,#121136,#121137, - #121138,#121139,#121140,#121141),.UNSPECIFIED.,.T.,.F.) +#123524 = PCURVE('',#92917,#123525); +#123525 = DEFINITIONAL_REPRESENTATION('',(#123526),#123534); +#123526 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123527,#123528,#123529, + #123530,#123531,#123532,#123533),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#121135 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#121136 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#121137 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#121138 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#121139 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#121140 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#121141 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#121142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121143 = ADVANCED_FACE('',(#121144),#90497,.T.); -#121144 = FACE_BOUND('',#121145,.T.); -#121145 = EDGE_LOOP('',(#121146,#121167,#121168,#121189)); -#121146 = ORIENTED_EDGE('',*,*,#121147,.F.); -#121147 = EDGE_CURVE('',#121052,#90454,#121148,.T.); -#121148 = SURFACE_CURVE('',#121149,(#121153,#121160),.PCURVE_S1.); -#121149 = LINE('',#121150,#121151); -#121150 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); -#121151 = VECTOR('',#121152,1.); -#121152 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#121153 = PCURVE('',#90497,#121154); -#121154 = DEFINITIONAL_REPRESENTATION('',(#121155),#121159); -#121155 = LINE('',#121156,#121157); -#121156 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121157 = VECTOR('',#121158,1.); -#121158 = DIRECTION('',(-1.,2.995851623787E-063)); -#121159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121160 = PCURVE('',#90469,#121161); -#121161 = DEFINITIONAL_REPRESENTATION('',(#121162),#121166); -#121162 = LINE('',#121163,#121164); -#121163 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121164 = VECTOR('',#121165,1.); -#121165 = DIRECTION('',(-3.563627120235E-016,1.)); -#121166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121167 = ORIENTED_EDGE('',*,*,#121074,.T.); -#121168 = ORIENTED_EDGE('',*,*,#121169,.T.); -#121169 = EDGE_CURVE('',#121075,#90482,#121170,.T.); -#121170 = SURFACE_CURVE('',#121171,(#121175,#121182),.PCURVE_S1.); -#121171 = LINE('',#121172,#121173); -#121172 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.65)); -#121173 = VECTOR('',#121174,1.); -#121174 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#121175 = PCURVE('',#90497,#121176); -#121176 = DEFINITIONAL_REPRESENTATION('',(#121177),#121181); -#121177 = LINE('',#121178,#121179); -#121178 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#121179 = VECTOR('',#121180,1.); -#121180 = DIRECTION('',(-1.,2.995851623787E-063)); -#121181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121182 = PCURVE('',#90525,#121183); -#121183 = DEFINITIONAL_REPRESENTATION('',(#121184),#121188); -#121184 = LINE('',#121185,#121186); -#121185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121186 = VECTOR('',#121187,1.); -#121187 = DIRECTION('',(3.563627120235E-016,1.)); -#121188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121189 = ORIENTED_EDGE('',*,*,#90481,.F.); -#121190 = ADVANCED_FACE('',(#121191),#90525,.T.); -#121191 = FACE_BOUND('',#121192,.T.); -#121192 = EDGE_LOOP('',(#121193,#121194,#121195,#121196,#121197,#121198, - #121219,#121220,#121221,#121222,#121223,#121244)); -#121193 = ORIENTED_EDGE('',*,*,#121169,.F.); -#121194 = ORIENTED_EDGE('',*,*,#121119,.T.); -#121195 = ORIENTED_EDGE('',*,*,#120854,.T.); -#121196 = ORIENTED_EDGE('',*,*,#120752,.T.); -#121197 = ORIENTED_EDGE('',*,*,#120571,.T.); -#121198 = ORIENTED_EDGE('',*,*,#121199,.F.); -#121199 = EDGE_CURVE('',#120435,#120542,#121200,.T.); -#121200 = SURFACE_CURVE('',#121201,(#121205,#121212),.PCURVE_S1.); -#121201 = LINE('',#121202,#121203); -#121202 = CARTESIAN_POINT('',(-1.,8.35,1.159810404338E-002)); -#121203 = VECTOR('',#121204,1.); -#121204 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#121205 = PCURVE('',#90525,#121206); -#121206 = DEFINITIONAL_REPRESENTATION('',(#121207),#121211); -#121207 = LINE('',#121208,#121209); -#121208 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#121209 = VECTOR('',#121210,1.); -#121210 = DIRECTION('',(-1.,2.101748079665E-016)); -#121211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121212 = PCURVE('',#120455,#121213); -#121213 = DEFINITIONAL_REPRESENTATION('',(#121214),#121218); -#121214 = LINE('',#121215,#121216); -#121215 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#121216 = VECTOR('',#121217,1.); -#121217 = DIRECTION('',(1.194699204908E-017,-1.)); -#121218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121219 = ORIENTED_EDGE('',*,*,#120517,.F.); -#121220 = ORIENTED_EDGE('',*,*,#120645,.F.); -#121221 = ORIENTED_EDGE('',*,*,#120907,.F.); -#121222 = ORIENTED_EDGE('',*,*,#121022,.F.); -#121223 = ORIENTED_EDGE('',*,*,#121224,.T.); -#121224 = EDGE_CURVE('',#120978,#90510,#121225,.T.); -#121225 = SURFACE_CURVE('',#121226,(#121230,#121237),.PCURVE_S1.); -#121226 = LINE('',#121227,#121228); -#121227 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.75)); -#121228 = VECTOR('',#121229,1.); -#121229 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#121230 = PCURVE('',#90525,#121231); -#121231 = DEFINITIONAL_REPRESENTATION('',(#121232),#121236); -#121232 = LINE('',#121233,#121234); -#121233 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#121234 = VECTOR('',#121235,1.); -#121235 = DIRECTION('',(3.563627120235E-016,1.)); -#121236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121237 = PCURVE('',#90551,#121238); -#121238 = DEFINITIONAL_REPRESENTATION('',(#121239),#121243); -#121239 = LINE('',#121240,#121241); -#121240 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#121241 = VECTOR('',#121242,1.); -#121242 = DIRECTION('',(1.,2.995851623787E-063)); -#121243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121244 = ORIENTED_EDGE('',*,*,#90509,.F.); -#121245 = ADVANCED_FACE('',(#121246),#90551,.T.); -#121246 = FACE_BOUND('',#121247,.T.); -#121247 = EDGE_LOOP('',(#121248,#121249,#121250,#121271)); -#121248 = ORIENTED_EDGE('',*,*,#121224,.F.); -#121249 = ORIENTED_EDGE('',*,*,#120977,.T.); -#121250 = ORIENTED_EDGE('',*,*,#121251,.T.); -#121251 = EDGE_CURVE('',#120955,#90452,#121252,.T.); -#121252 = SURFACE_CURVE('',#121253,(#121257,#121264),.PCURVE_S1.); -#121253 = LINE('',#121254,#121255); -#121254 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.75)); -#121255 = VECTOR('',#121256,1.); -#121256 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#121257 = PCURVE('',#90551,#121258); -#121258 = DEFINITIONAL_REPRESENTATION('',(#121259),#121263); -#121259 = LINE('',#121260,#121261); -#121260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121261 = VECTOR('',#121262,1.); -#121262 = DIRECTION('',(1.,2.995851623787E-063)); -#121263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121264 = PCURVE('',#90469,#121265); -#121265 = DEFINITIONAL_REPRESENTATION('',(#121266),#121270); -#121266 = LINE('',#121267,#121268); -#121267 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#121268 = VECTOR('',#121269,1.); -#121269 = DIRECTION('',(-3.563627120235E-016,1.)); -#121270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121271 = ORIENTED_EDGE('',*,*,#90537,.F.); -#121272 = ADVANCED_FACE('',(#121273),#90469,.T.); -#121273 = FACE_BOUND('',#121274,.T.); -#121274 = EDGE_LOOP('',(#121275,#121276,#121277,#121278,#121279,#121280, - #121301,#121302,#121303,#121304,#121305,#121306)); -#121275 = ORIENTED_EDGE('',*,*,#121251,.F.); -#121276 = ORIENTED_EDGE('',*,*,#120954,.T.); -#121277 = ORIENTED_EDGE('',*,*,#120929,.T.); -#121278 = ORIENTED_EDGE('',*,*,#120695,.T.); -#121279 = ORIENTED_EDGE('',*,*,#120467,.T.); -#121280 = ORIENTED_EDGE('',*,*,#121281,.F.); -#121281 = EDGE_CURVE('',#120544,#120433,#121282,.T.); -#121282 = SURFACE_CURVE('',#121283,(#121287,#121294),.PCURVE_S1.); -#121283 = LINE('',#121284,#121285); -#121284 = CARTESIAN_POINT('',(-1.,8.15,1.159810404338E-002)); -#121285 = VECTOR('',#121286,1.); -#121286 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#121287 = PCURVE('',#90469,#121288); -#121288 = DEFINITIONAL_REPRESENTATION('',(#121289),#121293); -#121289 = LINE('',#121290,#121291); -#121290 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#121291 = VECTOR('',#121292,1.); -#121292 = DIRECTION('',(-1.,-2.101748079665E-016)); -#121293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121294 = PCURVE('',#120455,#121295); -#121295 = DEFINITIONAL_REPRESENTATION('',(#121296),#121300); -#121296 = LINE('',#121297,#121298); -#121297 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#121298 = VECTOR('',#121299,1.); -#121299 = DIRECTION('',(-1.194699204908E-017,1.)); -#121300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121301 = ORIENTED_EDGE('',*,*,#120621,.F.); -#121302 = ORIENTED_EDGE('',*,*,#120724,.F.); -#121303 = ORIENTED_EDGE('',*,*,#120832,.F.); -#121304 = ORIENTED_EDGE('',*,*,#121051,.F.); -#121305 = ORIENTED_EDGE('',*,*,#121147,.T.); -#121306 = ORIENTED_EDGE('',*,*,#90451,.F.); -#121307 = ADVANCED_FACE('',(#121308),#120455,.T.); -#121308 = FACE_BOUND('',#121309,.T.); -#121309 = EDGE_LOOP('',(#121310,#121311,#121312,#121313)); -#121310 = ORIENTED_EDGE('',*,*,#121199,.T.); -#121311 = ORIENTED_EDGE('',*,*,#120541,.T.); -#121312 = ORIENTED_EDGE('',*,*,#121281,.T.); -#121313 = ORIENTED_EDGE('',*,*,#120432,.T.); -#121314 = ADVANCED_FACE('',(#121315),#121329,.F.); -#121315 = FACE_BOUND('',#121316,.T.); -#121316 = EDGE_LOOP('',(#121317,#121352,#121375,#121402)); -#121317 = ORIENTED_EDGE('',*,*,#121318,.F.); -#121318 = EDGE_CURVE('',#121319,#121321,#121323,.T.); -#121319 = VERTEX_POINT('',#121320); -#121320 = CARTESIAN_POINT('',(-1.,8.65,-0.208196358798)); -#121321 = VERTEX_POINT('',#121322); -#121322 = CARTESIAN_POINT('',(-1.,8.85,-0.208196358798)); -#121323 = SURFACE_CURVE('',#121324,(#121328,#121340),.PCURVE_S1.); -#121324 = LINE('',#121325,#121326); -#121325 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); -#121326 = VECTOR('',#121327,1.); -#121327 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121328 = PCURVE('',#121329,#121334); -#121329 = PLANE('',#121330); -#121330 = AXIS2_PLACEMENT_3D('',#121331,#121332,#121333); -#121331 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#121332 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#121333 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#121334 = DEFINITIONAL_REPRESENTATION('',(#121335),#121339); -#121335 = LINE('',#121336,#121337); -#121336 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); -#121337 = VECTOR('',#121338,1.); -#121338 = DIRECTION('',(4.440892098501E-016,1.)); -#121339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121340 = PCURVE('',#121341,#121346); -#121341 = PLANE('',#121342); -#121342 = AXIS2_PLACEMENT_3D('',#121343,#121344,#121345); -#121343 = CARTESIAN_POINT('',(-1.,8.75,-0.258196742327)); -#121344 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); -#121345 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121346 = DEFINITIONAL_REPRESENTATION('',(#121347),#121351); -#121347 = LINE('',#121348,#121349); -#121348 = CARTESIAN_POINT('',(-1.25,5.000038352949E-002)); -#121349 = VECTOR('',#121350,1.); -#121350 = DIRECTION('',(-1.,0.E+000)); -#121351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121352 = ORIENTED_EDGE('',*,*,#121353,.F.); -#121353 = EDGE_CURVE('',#121354,#121319,#121356,.T.); -#121354 = VERTEX_POINT('',#121355); -#121355 = CARTESIAN_POINT('',(-0.740726081328,8.65,-0.208196358798)); -#121356 = SURFACE_CURVE('',#121357,(#121361,#121368),.PCURVE_S1.); -#121357 = LINE('',#121358,#121359); -#121358 = CARTESIAN_POINT('',(-0.740726081328,8.65,-0.208196358798)); -#121359 = VECTOR('',#121360,1.); -#121360 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#121361 = PCURVE('',#121329,#121362); -#121362 = DEFINITIONAL_REPRESENTATION('',(#121363),#121367); -#121363 = LINE('',#121364,#121365); -#121364 = CARTESIAN_POINT('',(-6.661338147751E-016,-1.35)); -#121365 = VECTOR('',#121366,1.); -#121366 = DIRECTION('',(1.,0.E+000)); -#121367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121368 = PCURVE('',#90355,#121369); -#121369 = DEFINITIONAL_REPRESENTATION('',(#121370),#121374); -#121370 = LINE('',#121371,#121372); -#121371 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); -#121372 = VECTOR('',#121373,1.); -#121373 = DIRECTION('',(0.E+000,-1.)); -#121374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121375 = ORIENTED_EDGE('',*,*,#121376,.F.); -#121376 = EDGE_CURVE('',#121377,#121354,#121379,.T.); -#121377 = VERTEX_POINT('',#121378); -#121378 = CARTESIAN_POINT('',(-0.740726081328,8.85,-0.208196358798)); -#121379 = SURFACE_CURVE('',#121380,(#121384,#121391),.PCURVE_S1.); -#121380 = LINE('',#121381,#121382); -#121381 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); -#121382 = VECTOR('',#121383,1.); -#121383 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121384 = PCURVE('',#121329,#121385); -#121385 = DEFINITIONAL_REPRESENTATION('',(#121386),#121390); -#121386 = LINE('',#121387,#121388); -#121387 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121388 = VECTOR('',#121389,1.); -#121389 = DIRECTION('',(-4.440892098501E-016,-1.)); -#121390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121391 = PCURVE('',#121392,#121397); -#121392 = CYLINDRICAL_SURFACE('',#121393,0.208574704164); -#121393 = AXIS2_PLACEMENT_3D('',#121394,#121395,#121396); -#121394 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#121395 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121396 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121397 = DEFINITIONAL_REPRESENTATION('',(#121398),#121401); -#121398 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121399,#121400), +#123527 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#123528 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#123529 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#123530 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#123531 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#123532 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#123533 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#123534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123535 = ADVANCED_FACE('',(#123536),#92889,.T.); +#123536 = FACE_BOUND('',#123537,.T.); +#123537 = EDGE_LOOP('',(#123538,#123559,#123560,#123581)); +#123538 = ORIENTED_EDGE('',*,*,#123539,.F.); +#123539 = EDGE_CURVE('',#123444,#92846,#123540,.T.); +#123540 = SURFACE_CURVE('',#123541,(#123545,#123552),.PCURVE_S1.); +#123541 = LINE('',#123542,#123543); +#123542 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.65)); +#123543 = VECTOR('',#123544,1.); +#123544 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#123545 = PCURVE('',#92889,#123546); +#123546 = DEFINITIONAL_REPRESENTATION('',(#123547),#123551); +#123547 = LINE('',#123548,#123549); +#123548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123549 = VECTOR('',#123550,1.); +#123550 = DIRECTION('',(-1.,2.995851623787E-063)); +#123551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123552 = PCURVE('',#92861,#123553); +#123553 = DEFINITIONAL_REPRESENTATION('',(#123554),#123558); +#123554 = LINE('',#123555,#123556); +#123555 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123556 = VECTOR('',#123557,1.); +#123557 = DIRECTION('',(-3.563627120235E-016,1.)); +#123558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123559 = ORIENTED_EDGE('',*,*,#123466,.T.); +#123560 = ORIENTED_EDGE('',*,*,#123561,.T.); +#123561 = EDGE_CURVE('',#123467,#92874,#123562,.T.); +#123562 = SURFACE_CURVE('',#123563,(#123567,#123574),.PCURVE_S1.); +#123563 = LINE('',#123564,#123565); +#123564 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.65)); +#123565 = VECTOR('',#123566,1.); +#123566 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#123567 = PCURVE('',#92889,#123568); +#123568 = DEFINITIONAL_REPRESENTATION('',(#123569),#123573); +#123569 = LINE('',#123570,#123571); +#123570 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#123571 = VECTOR('',#123572,1.); +#123572 = DIRECTION('',(-1.,2.995851623787E-063)); +#123573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123574 = PCURVE('',#92917,#123575); +#123575 = DEFINITIONAL_REPRESENTATION('',(#123576),#123580); +#123576 = LINE('',#123577,#123578); +#123577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123578 = VECTOR('',#123579,1.); +#123579 = DIRECTION('',(3.563627120235E-016,1.)); +#123580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123581 = ORIENTED_EDGE('',*,*,#92873,.F.); +#123582 = ADVANCED_FACE('',(#123583),#92917,.T.); +#123583 = FACE_BOUND('',#123584,.T.); +#123584 = EDGE_LOOP('',(#123585,#123586,#123587,#123588,#123589,#123590, + #123611,#123612,#123613,#123614,#123615,#123636)); +#123585 = ORIENTED_EDGE('',*,*,#123561,.F.); +#123586 = ORIENTED_EDGE('',*,*,#123511,.T.); +#123587 = ORIENTED_EDGE('',*,*,#123246,.T.); +#123588 = ORIENTED_EDGE('',*,*,#123144,.T.); +#123589 = ORIENTED_EDGE('',*,*,#122963,.T.); +#123590 = ORIENTED_EDGE('',*,*,#123591,.F.); +#123591 = EDGE_CURVE('',#122827,#122934,#123592,.T.); +#123592 = SURFACE_CURVE('',#123593,(#123597,#123604),.PCURVE_S1.); +#123593 = LINE('',#123594,#123595); +#123594 = CARTESIAN_POINT('',(-1.,8.35,1.159810404338E-002)); +#123595 = VECTOR('',#123596,1.); +#123596 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#123597 = PCURVE('',#92917,#123598); +#123598 = DEFINITIONAL_REPRESENTATION('',(#123599),#123603); +#123599 = LINE('',#123600,#123601); +#123600 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#123601 = VECTOR('',#123602,1.); +#123602 = DIRECTION('',(-1.,2.101748079665E-016)); +#123603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123604 = PCURVE('',#122847,#123605); +#123605 = DEFINITIONAL_REPRESENTATION('',(#123606),#123610); +#123606 = LINE('',#123607,#123608); +#123607 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#123608 = VECTOR('',#123609,1.); +#123609 = DIRECTION('',(1.194699204908E-017,-1.)); +#123610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123611 = ORIENTED_EDGE('',*,*,#122909,.F.); +#123612 = ORIENTED_EDGE('',*,*,#123037,.F.); +#123613 = ORIENTED_EDGE('',*,*,#123299,.F.); +#123614 = ORIENTED_EDGE('',*,*,#123414,.F.); +#123615 = ORIENTED_EDGE('',*,*,#123616,.T.); +#123616 = EDGE_CURVE('',#123370,#92902,#123617,.T.); +#123617 = SURFACE_CURVE('',#123618,(#123622,#123629),.PCURVE_S1.); +#123618 = LINE('',#123619,#123620); +#123619 = CARTESIAN_POINT('',(-0.527847992439,8.35,0.75)); +#123620 = VECTOR('',#123621,1.); +#123621 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#123622 = PCURVE('',#92917,#123623); +#123623 = DEFINITIONAL_REPRESENTATION('',(#123624),#123628); +#123624 = LINE('',#123625,#123626); +#123625 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#123626 = VECTOR('',#123627,1.); +#123627 = DIRECTION('',(3.563627120235E-016,1.)); +#123628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123629 = PCURVE('',#92943,#123630); +#123630 = DEFINITIONAL_REPRESENTATION('',(#123631),#123635); +#123631 = LINE('',#123632,#123633); +#123632 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#123633 = VECTOR('',#123634,1.); +#123634 = DIRECTION('',(1.,2.995851623787E-063)); +#123635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123636 = ORIENTED_EDGE('',*,*,#92901,.F.); +#123637 = ADVANCED_FACE('',(#123638),#92943,.T.); +#123638 = FACE_BOUND('',#123639,.T.); +#123639 = EDGE_LOOP('',(#123640,#123641,#123642,#123663)); +#123640 = ORIENTED_EDGE('',*,*,#123616,.F.); +#123641 = ORIENTED_EDGE('',*,*,#123369,.T.); +#123642 = ORIENTED_EDGE('',*,*,#123643,.T.); +#123643 = EDGE_CURVE('',#123347,#92844,#123644,.T.); +#123644 = SURFACE_CURVE('',#123645,(#123649,#123656),.PCURVE_S1.); +#123645 = LINE('',#123646,#123647); +#123646 = CARTESIAN_POINT('',(-0.527847992439,8.15,0.75)); +#123647 = VECTOR('',#123648,1.); +#123648 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#123649 = PCURVE('',#92943,#123650); +#123650 = DEFINITIONAL_REPRESENTATION('',(#123651),#123655); +#123651 = LINE('',#123652,#123653); +#123652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123653 = VECTOR('',#123654,1.); +#123654 = DIRECTION('',(1.,2.995851623787E-063)); +#123655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123656 = PCURVE('',#92861,#123657); +#123657 = DEFINITIONAL_REPRESENTATION('',(#123658),#123662); +#123658 = LINE('',#123659,#123660); +#123659 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#123660 = VECTOR('',#123661,1.); +#123661 = DIRECTION('',(-3.563627120235E-016,1.)); +#123662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123663 = ORIENTED_EDGE('',*,*,#92929,.F.); +#123664 = ADVANCED_FACE('',(#123665),#92861,.T.); +#123665 = FACE_BOUND('',#123666,.T.); +#123666 = EDGE_LOOP('',(#123667,#123668,#123669,#123670,#123671,#123672, + #123693,#123694,#123695,#123696,#123697,#123698)); +#123667 = ORIENTED_EDGE('',*,*,#123643,.F.); +#123668 = ORIENTED_EDGE('',*,*,#123346,.T.); +#123669 = ORIENTED_EDGE('',*,*,#123321,.T.); +#123670 = ORIENTED_EDGE('',*,*,#123087,.T.); +#123671 = ORIENTED_EDGE('',*,*,#122859,.T.); +#123672 = ORIENTED_EDGE('',*,*,#123673,.F.); +#123673 = EDGE_CURVE('',#122936,#122825,#123674,.T.); +#123674 = SURFACE_CURVE('',#123675,(#123679,#123686),.PCURVE_S1.); +#123675 = LINE('',#123676,#123677); +#123676 = CARTESIAN_POINT('',(-1.,8.15,1.159810404338E-002)); +#123677 = VECTOR('',#123678,1.); +#123678 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#123679 = PCURVE('',#92861,#123680); +#123680 = DEFINITIONAL_REPRESENTATION('',(#123681),#123685); +#123681 = LINE('',#123682,#123683); +#123682 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#123683 = VECTOR('',#123684,1.); +#123684 = DIRECTION('',(-1.,-2.101748079665E-016)); +#123685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123686 = PCURVE('',#122847,#123687); +#123687 = DEFINITIONAL_REPRESENTATION('',(#123688),#123692); +#123688 = LINE('',#123689,#123690); +#123689 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#123690 = VECTOR('',#123691,1.); +#123691 = DIRECTION('',(-1.194699204908E-017,1.)); +#123692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123693 = ORIENTED_EDGE('',*,*,#123013,.F.); +#123694 = ORIENTED_EDGE('',*,*,#123116,.F.); +#123695 = ORIENTED_EDGE('',*,*,#123224,.F.); +#123696 = ORIENTED_EDGE('',*,*,#123443,.F.); +#123697 = ORIENTED_EDGE('',*,*,#123539,.T.); +#123698 = ORIENTED_EDGE('',*,*,#92843,.F.); +#123699 = ADVANCED_FACE('',(#123700),#122847,.T.); +#123700 = FACE_BOUND('',#123701,.T.); +#123701 = EDGE_LOOP('',(#123702,#123703,#123704,#123705)); +#123702 = ORIENTED_EDGE('',*,*,#123591,.T.); +#123703 = ORIENTED_EDGE('',*,*,#122933,.T.); +#123704 = ORIENTED_EDGE('',*,*,#123673,.T.); +#123705 = ORIENTED_EDGE('',*,*,#122824,.T.); +#123706 = ADVANCED_FACE('',(#123707),#123721,.F.); +#123707 = FACE_BOUND('',#123708,.T.); +#123708 = EDGE_LOOP('',(#123709,#123744,#123767,#123794)); +#123709 = ORIENTED_EDGE('',*,*,#123710,.F.); +#123710 = EDGE_CURVE('',#123711,#123713,#123715,.T.); +#123711 = VERTEX_POINT('',#123712); +#123712 = CARTESIAN_POINT('',(-1.,8.65,-0.208196358798)); +#123713 = VERTEX_POINT('',#123714); +#123714 = CARTESIAN_POINT('',(-1.,8.85,-0.208196358798)); +#123715 = SURFACE_CURVE('',#123716,(#123720,#123732),.PCURVE_S1.); +#123716 = LINE('',#123717,#123718); +#123717 = CARTESIAN_POINT('',(-1.,10.,-0.208196358798)); +#123718 = VECTOR('',#123719,1.); +#123719 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123720 = PCURVE('',#123721,#123726); +#123721 = PLANE('',#123722); +#123722 = AXIS2_PLACEMENT_3D('',#123723,#123724,#123725); +#123723 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#123724 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#123725 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123726 = DEFINITIONAL_REPRESENTATION('',(#123727),#123731); +#123727 = LINE('',#123728,#123729); +#123728 = CARTESIAN_POINT('',(0.259273918672,0.E+000)); +#123729 = VECTOR('',#123730,1.); +#123730 = DIRECTION('',(4.440892098501E-016,1.)); +#123731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123732 = PCURVE('',#123733,#123738); +#123733 = PLANE('',#123734); +#123734 = AXIS2_PLACEMENT_3D('',#123735,#123736,#123737); +#123735 = CARTESIAN_POINT('',(-1.,8.75,-0.258196742327)); +#123736 = DIRECTION('',(-1.,-4.440892098501E-016,-2.101748079665E-016)); +#123737 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123738 = DEFINITIONAL_REPRESENTATION('',(#123739),#123743); +#123739 = LINE('',#123740,#123741); +#123740 = CARTESIAN_POINT('',(-1.25,5.000038352949E-002)); +#123741 = VECTOR('',#123742,1.); +#123742 = DIRECTION('',(-1.,0.E+000)); +#123743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123744 = ORIENTED_EDGE('',*,*,#123745,.F.); +#123745 = EDGE_CURVE('',#123746,#123711,#123748,.T.); +#123746 = VERTEX_POINT('',#123747); +#123747 = CARTESIAN_POINT('',(-0.740726081328,8.65,-0.208196358798)); +#123748 = SURFACE_CURVE('',#123749,(#123753,#123760),.PCURVE_S1.); +#123749 = LINE('',#123750,#123751); +#123750 = CARTESIAN_POINT('',(-0.740726081328,8.65,-0.208196358798)); +#123751 = VECTOR('',#123752,1.); +#123752 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123753 = PCURVE('',#123721,#123754); +#123754 = DEFINITIONAL_REPRESENTATION('',(#123755),#123759); +#123755 = LINE('',#123756,#123757); +#123756 = CARTESIAN_POINT('',(-6.661338147751E-016,-1.35)); +#123757 = VECTOR('',#123758,1.); +#123758 = DIRECTION('',(1.,0.E+000)); +#123759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123760 = PCURVE('',#92747,#123761); +#123761 = DEFINITIONAL_REPRESENTATION('',(#123762),#123766); +#123762 = LINE('',#123763,#123764); +#123763 = CARTESIAN_POINT('',(0.858196358798,-0.212878088889)); +#123764 = VECTOR('',#123765,1.); +#123765 = DIRECTION('',(0.E+000,-1.)); +#123766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123767 = ORIENTED_EDGE('',*,*,#123768,.F.); +#123768 = EDGE_CURVE('',#123769,#123746,#123771,.T.); +#123769 = VERTEX_POINT('',#123770); +#123770 = CARTESIAN_POINT('',(-0.740726081328,8.85,-0.208196358798)); +#123771 = SURFACE_CURVE('',#123772,(#123776,#123783),.PCURVE_S1.); +#123772 = LINE('',#123773,#123774); +#123773 = CARTESIAN_POINT('',(-0.740726081328,10.,-0.208196358798)); +#123774 = VECTOR('',#123775,1.); +#123775 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123776 = PCURVE('',#123721,#123777); +#123777 = DEFINITIONAL_REPRESENTATION('',(#123778),#123782); +#123778 = LINE('',#123779,#123780); +#123779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123780 = VECTOR('',#123781,1.); +#123781 = DIRECTION('',(-4.440892098501E-016,-1.)); +#123782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123783 = PCURVE('',#123784,#123789); +#123784 = CYLINDRICAL_SURFACE('',#123785,0.208574704164); +#123785 = AXIS2_PLACEMENT_3D('',#123786,#123787,#123788); +#123786 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#123787 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123788 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123789 = DEFINITIONAL_REPRESENTATION('',(#123790),#123793); +#123790 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123791,#123792), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#121399 = CARTESIAN_POINT('',(4.772630242227,-1.15)); -#121400 = CARTESIAN_POINT('',(4.772630242227,-1.35)); -#121401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121402 = ORIENTED_EDGE('',*,*,#121403,.T.); -#121403 = EDGE_CURVE('',#121377,#121321,#121404,.T.); -#121404 = SURFACE_CURVE('',#121405,(#121409,#121416),.PCURVE_S1.); -#121405 = LINE('',#121406,#121407); -#121406 = CARTESIAN_POINT('',(-0.740726081328,8.85,-0.208196358798)); -#121407 = VECTOR('',#121408,1.); -#121408 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#121409 = PCURVE('',#121329,#121410); -#121410 = DEFINITIONAL_REPRESENTATION('',(#121411),#121415); -#121411 = LINE('',#121412,#121413); -#121412 = CARTESIAN_POINT('',(-4.440892098501E-016,-1.15)); -#121413 = VECTOR('',#121414,1.); -#121414 = DIRECTION('',(1.,0.E+000)); -#121415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121416 = PCURVE('',#90411,#121417); -#121417 = DEFINITIONAL_REPRESENTATION('',(#121418),#121422); -#121418 = LINE('',#121419,#121420); -#121419 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); -#121420 = VECTOR('',#121421,1.); -#121421 = DIRECTION('',(0.E+000,-1.)); -#121422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121423 = ADVANCED_FACE('',(#121424),#121438,.F.); -#121424 = FACE_BOUND('',#121425,.T.); -#121425 = EDGE_LOOP('',(#121426,#121456,#121479,#121506)); -#121426 = ORIENTED_EDGE('',*,*,#121427,.F.); -#121427 = EDGE_CURVE('',#121428,#121430,#121432,.T.); -#121428 = VERTEX_POINT('',#121429); -#121429 = CARTESIAN_POINT('',(-1.,8.85,-0.308197125857)); -#121430 = VERTEX_POINT('',#121431); -#121431 = CARTESIAN_POINT('',(-1.,8.65,-0.308197125857)); -#121432 = SURFACE_CURVE('',#121433,(#121437,#121449),.PCURVE_S1.); -#121433 = LINE('',#121434,#121435); -#121434 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); -#121435 = VECTOR('',#121436,1.); -#121436 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121437 = PCURVE('',#121438,#121443); -#121438 = PLANE('',#121439); -#121439 = AXIS2_PLACEMENT_3D('',#121440,#121441,#121442); -#121440 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#121441 = DIRECTION('',(0.E+000,0.E+000,1.)); -#121442 = DIRECTION('',(1.,0.E+000,0.E+000)); -#121443 = DEFINITIONAL_REPRESENTATION('',(#121444),#121448); -#121444 = LINE('',#121445,#121446); -#121445 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); -#121446 = VECTOR('',#121447,1.); -#121447 = DIRECTION('',(4.440892098501E-016,-1.)); -#121448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121449 = PCURVE('',#121341,#121450); -#121450 = DEFINITIONAL_REPRESENTATION('',(#121451),#121455); -#121451 = LINE('',#121452,#121453); -#121452 = CARTESIAN_POINT('',(-1.25,-5.000038352949E-002)); -#121453 = VECTOR('',#121454,1.); -#121454 = DIRECTION('',(1.,0.E+000)); -#121455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121456 = ORIENTED_EDGE('',*,*,#121457,.F.); -#121457 = EDGE_CURVE('',#121458,#121428,#121460,.T.); -#121458 = VERTEX_POINT('',#121459); -#121459 = CARTESIAN_POINT('',(-0.74341632541,8.85,-0.308197125857)); -#121460 = SURFACE_CURVE('',#121461,(#121465,#121472),.PCURVE_S1.); -#121461 = LINE('',#121462,#121463); -#121462 = CARTESIAN_POINT('',(-0.74341632541,8.85,-0.308197125857)); -#121463 = VECTOR('',#121464,1.); -#121464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#121465 = PCURVE('',#121438,#121466); -#121466 = DEFINITIONAL_REPRESENTATION('',(#121467),#121471); -#121467 = LINE('',#121468,#121469); -#121468 = CARTESIAN_POINT('',(4.440892098501E-016,-1.15)); -#121469 = VECTOR('',#121470,1.); -#121470 = DIRECTION('',(-1.,0.E+000)); -#121471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123791 = CARTESIAN_POINT('',(4.772630242227,-1.15)); +#123792 = CARTESIAN_POINT('',(4.772630242227,-1.35)); +#123793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123794 = ORIENTED_EDGE('',*,*,#123795,.T.); +#123795 = EDGE_CURVE('',#123769,#123713,#123796,.T.); +#123796 = SURFACE_CURVE('',#123797,(#123801,#123808),.PCURVE_S1.); +#123797 = LINE('',#123798,#123799); +#123798 = CARTESIAN_POINT('',(-0.740726081328,8.85,-0.208196358798)); +#123799 = VECTOR('',#123800,1.); +#123800 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123801 = PCURVE('',#123721,#123802); +#123802 = DEFINITIONAL_REPRESENTATION('',(#123803),#123807); +#123803 = LINE('',#123804,#123805); +#123804 = CARTESIAN_POINT('',(-4.440892098501E-016,-1.15)); +#123805 = VECTOR('',#123806,1.); +#123806 = DIRECTION('',(1.,0.E+000)); +#123807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121472 = PCURVE('',#90411,#121473); -#121473 = DEFINITIONAL_REPRESENTATION('',(#121474),#121478); -#121474 = LINE('',#121475,#121476); -#121475 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); -#121476 = VECTOR('',#121477,1.); -#121477 = DIRECTION('',(0.E+000,-1.)); -#121478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121479 = ORIENTED_EDGE('',*,*,#121480,.F.); -#121480 = EDGE_CURVE('',#121481,#121458,#121483,.T.); -#121481 = VERTEX_POINT('',#121482); -#121482 = CARTESIAN_POINT('',(-0.74341632541,8.65,-0.308197125857)); -#121483 = SURFACE_CURVE('',#121484,(#121488,#121495),.PCURVE_S1.); -#121484 = LINE('',#121485,#121486); -#121485 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); -#121486 = VECTOR('',#121487,1.); -#121487 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121488 = PCURVE('',#121438,#121489); -#121489 = DEFINITIONAL_REPRESENTATION('',(#121490),#121494); -#121490 = LINE('',#121491,#121492); -#121491 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121492 = VECTOR('',#121493,1.); -#121493 = DIRECTION('',(-4.440892098501E-016,1.)); -#121494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121495 = PCURVE('',#121496,#121501); -#121496 = CYLINDRICAL_SURFACE('',#121497,0.308574064194); -#121497 = AXIS2_PLACEMENT_3D('',#121498,#121499,#121500); -#121498 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); -#121499 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121500 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121501 = DEFINITIONAL_REPRESENTATION('',(#121502),#121505); -#121502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121503,#121504), +#123808 = PCURVE('',#92803,#123809); +#123809 = DEFINITIONAL_REPRESENTATION('',(#123810),#123814); +#123810 = LINE('',#123811,#123812); +#123811 = CARTESIAN_POINT('',(-0.858196358798,-0.212878088889)); +#123812 = VECTOR('',#123813,1.); +#123813 = DIRECTION('',(0.E+000,-1.)); +#123814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123815 = ADVANCED_FACE('',(#123816),#123830,.F.); +#123816 = FACE_BOUND('',#123817,.T.); +#123817 = EDGE_LOOP('',(#123818,#123848,#123871,#123898)); +#123818 = ORIENTED_EDGE('',*,*,#123819,.F.); +#123819 = EDGE_CURVE('',#123820,#123822,#123824,.T.); +#123820 = VERTEX_POINT('',#123821); +#123821 = CARTESIAN_POINT('',(-1.,8.85,-0.308197125857)); +#123822 = VERTEX_POINT('',#123823); +#123823 = CARTESIAN_POINT('',(-1.,8.65,-0.308197125857)); +#123824 = SURFACE_CURVE('',#123825,(#123829,#123841),.PCURVE_S1.); +#123825 = LINE('',#123826,#123827); +#123826 = CARTESIAN_POINT('',(-1.,10.,-0.308197125857)); +#123827 = VECTOR('',#123828,1.); +#123828 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123829 = PCURVE('',#123830,#123835); +#123830 = PLANE('',#123831); +#123831 = AXIS2_PLACEMENT_3D('',#123832,#123833,#123834); +#123832 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#123833 = DIRECTION('',(0.E+000,0.E+000,1.)); +#123834 = DIRECTION('',(1.,0.E+000,0.E+000)); +#123835 = DEFINITIONAL_REPRESENTATION('',(#123836),#123840); +#123836 = LINE('',#123837,#123838); +#123837 = CARTESIAN_POINT('',(-0.25658367459,0.E+000)); +#123838 = VECTOR('',#123839,1.); +#123839 = DIRECTION('',(4.440892098501E-016,-1.)); +#123840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123841 = PCURVE('',#123733,#123842); +#123842 = DEFINITIONAL_REPRESENTATION('',(#123843),#123847); +#123843 = LINE('',#123844,#123845); +#123844 = CARTESIAN_POINT('',(-1.25,-5.000038352949E-002)); +#123845 = VECTOR('',#123846,1.); +#123846 = DIRECTION('',(1.,0.E+000)); +#123847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123848 = ORIENTED_EDGE('',*,*,#123849,.F.); +#123849 = EDGE_CURVE('',#123850,#123820,#123852,.T.); +#123850 = VERTEX_POINT('',#123851); +#123851 = CARTESIAN_POINT('',(-0.74341632541,8.85,-0.308197125857)); +#123852 = SURFACE_CURVE('',#123853,(#123857,#123864),.PCURVE_S1.); +#123853 = LINE('',#123854,#123855); +#123854 = CARTESIAN_POINT('',(-0.74341632541,8.85,-0.308197125857)); +#123855 = VECTOR('',#123856,1.); +#123856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123857 = PCURVE('',#123830,#123858); +#123858 = DEFINITIONAL_REPRESENTATION('',(#123859),#123863); +#123859 = LINE('',#123860,#123861); +#123860 = CARTESIAN_POINT('',(4.440892098501E-016,-1.15)); +#123861 = VECTOR('',#123862,1.); +#123862 = DIRECTION('',(-1.,0.E+000)); +#123863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123864 = PCURVE('',#92803,#123865); +#123865 = DEFINITIONAL_REPRESENTATION('',(#123866),#123870); +#123866 = LINE('',#123867,#123868); +#123867 = CARTESIAN_POINT('',(-0.958197125857,-0.215568332972)); +#123868 = VECTOR('',#123869,1.); +#123869 = DIRECTION('',(0.E+000,-1.)); +#123870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123871 = ORIENTED_EDGE('',*,*,#123872,.F.); +#123872 = EDGE_CURVE('',#123873,#123850,#123875,.T.); +#123873 = VERTEX_POINT('',#123874); +#123874 = CARTESIAN_POINT('',(-0.74341632541,8.65,-0.308197125857)); +#123875 = SURFACE_CURVE('',#123876,(#123880,#123887),.PCURVE_S1.); +#123876 = LINE('',#123877,#123878); +#123877 = CARTESIAN_POINT('',(-0.74341632541,10.,-0.308197125857)); +#123878 = VECTOR('',#123879,1.); +#123879 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123880 = PCURVE('',#123830,#123881); +#123881 = DEFINITIONAL_REPRESENTATION('',(#123882),#123886); +#123882 = LINE('',#123883,#123884); +#123883 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#123884 = VECTOR('',#123885,1.); +#123885 = DIRECTION('',(-4.440892098501E-016,1.)); +#123886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123887 = PCURVE('',#123888,#123893); +#123888 = CYLINDRICAL_SURFACE('',#123889,0.308574064194); +#123889 = AXIS2_PLACEMENT_3D('',#123890,#123891,#123892); +#123890 = CARTESIAN_POINT('',(-0.728168876214,10.,2.640924866458E-017)); +#123891 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123892 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123893 = DEFINITIONAL_REPRESENTATION('',(#123894),#123897); +#123894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123895,#123896), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#121503 = CARTESIAN_POINT('',(4.761821717947,-1.35)); -#121504 = CARTESIAN_POINT('',(4.761821717947,-1.15)); -#121505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121506 = ORIENTED_EDGE('',*,*,#121507,.T.); -#121507 = EDGE_CURVE('',#121481,#121430,#121508,.T.); -#121508 = SURFACE_CURVE('',#121509,(#121513,#121520),.PCURVE_S1.); -#121509 = LINE('',#121510,#121511); -#121510 = CARTESIAN_POINT('',(-0.74341632541,8.65,-0.308197125857)); -#121511 = VECTOR('',#121512,1.); -#121512 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#121513 = PCURVE('',#121438,#121514); -#121514 = DEFINITIONAL_REPRESENTATION('',(#121515),#121519); -#121515 = LINE('',#121516,#121517); -#121516 = CARTESIAN_POINT('',(6.661338147751E-016,-1.35)); -#121517 = VECTOR('',#121518,1.); -#121518 = DIRECTION('',(-1.,0.E+000)); -#121519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121520 = PCURVE('',#90355,#121521); -#121521 = DEFINITIONAL_REPRESENTATION('',(#121522),#121526); -#121522 = LINE('',#121523,#121524); -#121523 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); -#121524 = VECTOR('',#121525,1.); -#121525 = DIRECTION('',(0.E+000,-1.)); -#121526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121527 = ADVANCED_FACE('',(#121528),#121392,.F.); -#121528 = FACE_BOUND('',#121529,.F.); -#121529 = EDGE_LOOP('',(#121530,#121553,#121580,#121605)); -#121530 = ORIENTED_EDGE('',*,*,#121531,.F.); -#121531 = EDGE_CURVE('',#121532,#121377,#121534,.T.); -#121532 = VERTEX_POINT('',#121533); -#121533 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.E+000)); -#121534 = SURFACE_CURVE('',#121535,(#121540,#121546),.PCURVE_S1.); -#121535 = CIRCLE('',#121536,0.208574704164); -#121536 = AXIS2_PLACEMENT_3D('',#121537,#121538,#121539); -#121537 = CARTESIAN_POINT('',(-0.728168876214,8.85,2.640924866458E-017) - ); -#121538 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121539 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121540 = PCURVE('',#121392,#121541); -#121541 = DEFINITIONAL_REPRESENTATION('',(#121542),#121545); -#121542 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121543,#121544), +#123895 = CARTESIAN_POINT('',(4.761821717947,-1.35)); +#123896 = CARTESIAN_POINT('',(4.761821717947,-1.15)); +#123897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123898 = ORIENTED_EDGE('',*,*,#123899,.T.); +#123899 = EDGE_CURVE('',#123873,#123822,#123900,.T.); +#123900 = SURFACE_CURVE('',#123901,(#123905,#123912),.PCURVE_S1.); +#123901 = LINE('',#123902,#123903); +#123902 = CARTESIAN_POINT('',(-0.74341632541,8.65,-0.308197125857)); +#123903 = VECTOR('',#123904,1.); +#123904 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#123905 = PCURVE('',#123830,#123906); +#123906 = DEFINITIONAL_REPRESENTATION('',(#123907),#123911); +#123907 = LINE('',#123908,#123909); +#123908 = CARTESIAN_POINT('',(6.661338147751E-016,-1.35)); +#123909 = VECTOR('',#123910,1.); +#123910 = DIRECTION('',(-1.,0.E+000)); +#123911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123912 = PCURVE('',#92747,#123913); +#123913 = DEFINITIONAL_REPRESENTATION('',(#123914),#123918); +#123914 = LINE('',#123915,#123916); +#123915 = CARTESIAN_POINT('',(0.958197125857,-0.215568332972)); +#123916 = VECTOR('',#123917,1.); +#123917 = DIRECTION('',(0.E+000,-1.)); +#123918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123919 = ADVANCED_FACE('',(#123920),#123784,.F.); +#123920 = FACE_BOUND('',#123921,.F.); +#123921 = EDGE_LOOP('',(#123922,#123945,#123972,#123997)); +#123922 = ORIENTED_EDGE('',*,*,#123923,.F.); +#123923 = EDGE_CURVE('',#123924,#123769,#123926,.T.); +#123924 = VERTEX_POINT('',#123925); +#123925 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.E+000)); +#123926 = SURFACE_CURVE('',#123927,(#123932,#123938),.PCURVE_S1.); +#123927 = CIRCLE('',#123928,0.208574704164); +#123928 = AXIS2_PLACEMENT_3D('',#123929,#123930,#123931); +#123929 = CARTESIAN_POINT('',(-0.728168876214,8.85,2.640924866458E-017) + ); +#123930 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123931 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123932 = PCURVE('',#123784,#123933); +#123933 = DEFINITIONAL_REPRESENTATION('',(#123934),#123937); +#123934 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123935,#123936), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#121543 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#121544 = CARTESIAN_POINT('',(4.772630242227,-1.15)); -#121545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121546 = PCURVE('',#90411,#121547); -#121547 = DEFINITIONAL_REPRESENTATION('',(#121548),#121552); -#121548 = CIRCLE('',#121549,0.208574704164); -#121549 = AXIS2_PLACEMENT_2D('',#121550,#121551); -#121550 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#121551 = DIRECTION('',(0.E+000,-1.)); -#121552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121553 = ORIENTED_EDGE('',*,*,#121554,.F.); -#121554 = EDGE_CURVE('',#121555,#121532,#121557,.T.); -#121555 = VERTEX_POINT('',#121556); -#121556 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.E+000)); -#121557 = SURFACE_CURVE('',#121558,(#121562,#121568),.PCURVE_S1.); -#121558 = LINE('',#121559,#121560); -#121559 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); -#121560 = VECTOR('',#121561,1.); -#121561 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121562 = PCURVE('',#121392,#121563); -#121563 = DEFINITIONAL_REPRESENTATION('',(#121564),#121567); -#121564 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121565,#121566), +#123935 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#123936 = CARTESIAN_POINT('',(4.772630242227,-1.15)); +#123937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123938 = PCURVE('',#92803,#123939); +#123939 = DEFINITIONAL_REPRESENTATION('',(#123940),#123944); +#123940 = CIRCLE('',#123941,0.208574704164); +#123941 = AXIS2_PLACEMENT_2D('',#123942,#123943); +#123942 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#123943 = DIRECTION('',(0.E+000,-1.)); +#123944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123945 = ORIENTED_EDGE('',*,*,#123946,.F.); +#123946 = EDGE_CURVE('',#123947,#123924,#123949,.T.); +#123947 = VERTEX_POINT('',#123948); +#123948 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.E+000)); +#123949 = SURFACE_CURVE('',#123950,(#123954,#123960),.PCURVE_S1.); +#123950 = LINE('',#123951,#123952); +#123951 = CARTESIAN_POINT('',(-0.51959417205,10.,0.E+000)); +#123952 = VECTOR('',#123953,1.); +#123953 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123954 = PCURVE('',#123784,#123955); +#123955 = DEFINITIONAL_REPRESENTATION('',(#123956),#123959); +#123956 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123957,#123958), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#121565 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#121566 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#121567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121568 = PCURVE('',#121569,#121574); -#121569 = PLANE('',#121570); -#121570 = AXIS2_PLACEMENT_3D('',#121571,#121572,#121573); -#121571 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#121572 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); -#121573 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121574 = DEFINITIONAL_REPRESENTATION('',(#121575),#121579); -#121575 = LINE('',#121576,#121577); -#121576 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#121577 = VECTOR('',#121578,1.); -#121578 = DIRECTION('',(-1.,0.E+000)); -#121579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121580 = ORIENTED_EDGE('',*,*,#121581,.T.); -#121581 = EDGE_CURVE('',#121555,#121354,#121582,.T.); -#121582 = SURFACE_CURVE('',#121583,(#121588,#121594),.PCURVE_S1.); -#121583 = CIRCLE('',#121584,0.208574704164); -#121584 = AXIS2_PLACEMENT_3D('',#121585,#121586,#121587); -#121585 = CARTESIAN_POINT('',(-0.728168876214,8.65,2.640924866458E-017) - ); -#121586 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121587 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121588 = PCURVE('',#121392,#121589); -#121589 = DEFINITIONAL_REPRESENTATION('',(#121590),#121593); -#121590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121591,#121592), +#123957 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#123958 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#123959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123960 = PCURVE('',#123961,#123966); +#123961 = PLANE('',#123962); +#123962 = AXIS2_PLACEMENT_3D('',#123963,#123964,#123965); +#123963 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#123964 = DIRECTION('',(-1.,-4.440892098501E-016,1.021336205033E-016)); +#123965 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#123966 = DEFINITIONAL_REPRESENTATION('',(#123967),#123971); +#123967 = LINE('',#123968,#123969); +#123968 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#123969 = VECTOR('',#123970,1.); +#123970 = DIRECTION('',(-1.,0.E+000)); +#123971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123972 = ORIENTED_EDGE('',*,*,#123973,.T.); +#123973 = EDGE_CURVE('',#123947,#123746,#123974,.T.); +#123974 = SURFACE_CURVE('',#123975,(#123980,#123986),.PCURVE_S1.); +#123975 = CIRCLE('',#123976,0.208574704164); +#123976 = AXIS2_PLACEMENT_3D('',#123977,#123978,#123979); +#123977 = CARTESIAN_POINT('',(-0.728168876214,8.65,2.640924866458E-017) + ); +#123978 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#123979 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#123980 = PCURVE('',#123784,#123981); +#123981 = DEFINITIONAL_REPRESENTATION('',(#123982),#123985); +#123982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123983,#123984), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#121591 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#121592 = CARTESIAN_POINT('',(4.772630242227,-1.35)); -#121593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#123983 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#123984 = CARTESIAN_POINT('',(4.772630242227,-1.35)); +#123985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121594 = PCURVE('',#90355,#121595); -#121595 = DEFINITIONAL_REPRESENTATION('',(#121596),#121604); -#121596 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121597,#121598,#121599, - #121600,#121601,#121602,#121603),.UNSPECIFIED.,.T.,.F.) +#123986 = PCURVE('',#92747,#123987); +#123987 = DEFINITIONAL_REPRESENTATION('',(#123988),#123996); +#123988 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123989,#123990,#123991, + #123992,#123993,#123994,#123995),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#121597 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#121598 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); -#121599 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); -#121600 = CARTESIAN_POINT('',(0.65,0.216828524552)); -#121601 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); -#121602 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); -#121603 = CARTESIAN_POINT('',(0.65,-0.408895587939)); -#121604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121605 = ORIENTED_EDGE('',*,*,#121376,.F.); -#121606 = ADVANCED_FACE('',(#121607),#121496,.T.); -#121607 = FACE_BOUND('',#121608,.T.); -#121608 = EDGE_LOOP('',(#121609,#121636,#121637,#121660)); -#121609 = ORIENTED_EDGE('',*,*,#121610,.T.); -#121610 = EDGE_CURVE('',#121611,#121481,#121613,.T.); -#121611 = VERTEX_POINT('',#121612); -#121612 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.E+000)); -#121613 = SURFACE_CURVE('',#121614,(#121619,#121625),.PCURVE_S1.); -#121614 = CIRCLE('',#121615,0.308574064194); -#121615 = AXIS2_PLACEMENT_3D('',#121616,#121617,#121618); -#121616 = CARTESIAN_POINT('',(-0.728168876214,8.65,2.640924866458E-017) - ); -#121617 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121618 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121619 = PCURVE('',#121496,#121620); -#121620 = DEFINITIONAL_REPRESENTATION('',(#121621),#121624); -#121621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121622,#121623), +#123989 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#123990 = CARTESIAN_POINT('',(0.288738015215,-0.408895587939)); +#123991 = CARTESIAN_POINT('',(0.469369007607,-9.603353169323E-002)); +#123992 = CARTESIAN_POINT('',(0.65,0.216828524552)); +#123993 = CARTESIAN_POINT('',(0.830630992393,-9.603353169323E-002)); +#123994 = CARTESIAN_POINT('',(1.011261984785,-0.408895587939)); +#123995 = CARTESIAN_POINT('',(0.65,-0.408895587939)); +#123996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#123997 = ORIENTED_EDGE('',*,*,#123768,.F.); +#123998 = ADVANCED_FACE('',(#123999),#123888,.T.); +#123999 = FACE_BOUND('',#124000,.T.); +#124000 = EDGE_LOOP('',(#124001,#124028,#124029,#124052)); +#124001 = ORIENTED_EDGE('',*,*,#124002,.T.); +#124002 = EDGE_CURVE('',#124003,#123873,#124005,.T.); +#124003 = VERTEX_POINT('',#124004); +#124004 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.E+000)); +#124005 = SURFACE_CURVE('',#124006,(#124011,#124017),.PCURVE_S1.); +#124006 = CIRCLE('',#124007,0.308574064194); +#124007 = AXIS2_PLACEMENT_3D('',#124008,#124009,#124010); +#124008 = CARTESIAN_POINT('',(-0.728168876214,8.65,2.640924866458E-017) + ); +#124009 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#124010 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#124011 = PCURVE('',#123888,#124012); +#124012 = DEFINITIONAL_REPRESENTATION('',(#124013),#124016); +#124013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124014,#124015), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#121622 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#121623 = CARTESIAN_POINT('',(4.761821717947,-1.35)); -#121624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124014 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#124015 = CARTESIAN_POINT('',(4.761821717947,-1.35)); +#124016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121625 = PCURVE('',#90355,#121626); -#121626 = DEFINITIONAL_REPRESENTATION('',(#121627),#121635); -#121627 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121628,#121629,#121630, - #121631,#121632,#121633,#121634),.UNSPECIFIED.,.T.,.F.) +#124017 = PCURVE('',#92747,#124018); +#124018 = DEFINITIONAL_REPRESENTATION('',(#124019),#124027); +#124019 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124020,#124021,#124022, + #124023,#124024,#124025,#124026),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#121628 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#121629 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); -#121630 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); -#121631 = CARTESIAN_POINT('',(0.65,0.416827244614)); -#121632 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); -#121633 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); -#121634 = CARTESIAN_POINT('',(0.65,-0.508894947969)); -#121635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121636 = ORIENTED_EDGE('',*,*,#121480,.T.); -#121637 = ORIENTED_EDGE('',*,*,#121638,.F.); -#121638 = EDGE_CURVE('',#121639,#121458,#121641,.T.); -#121639 = VERTEX_POINT('',#121640); -#121640 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.E+000)); -#121641 = SURFACE_CURVE('',#121642,(#121647,#121653),.PCURVE_S1.); -#121642 = CIRCLE('',#121643,0.308574064194); -#121643 = AXIS2_PLACEMENT_3D('',#121644,#121645,#121646); -#121644 = CARTESIAN_POINT('',(-0.728168876214,8.85,2.640924866458E-017) - ); -#121645 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121646 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); -#121647 = PCURVE('',#121496,#121648); -#121648 = DEFINITIONAL_REPRESENTATION('',(#121649),#121652); -#121649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121650,#121651), +#124020 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#124021 = CARTESIAN_POINT('',(0.115534042917,-0.508894947969)); +#124022 = CARTESIAN_POINT('',(0.382767021459,-4.603385167788E-002)); +#124023 = CARTESIAN_POINT('',(0.65,0.416827244614)); +#124024 = CARTESIAN_POINT('',(0.917232978541,-4.603385167788E-002)); +#124025 = CARTESIAN_POINT('',(1.184465957083,-0.508894947969)); +#124026 = CARTESIAN_POINT('',(0.65,-0.508894947969)); +#124027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124028 = ORIENTED_EDGE('',*,*,#123872,.T.); +#124029 = ORIENTED_EDGE('',*,*,#124030,.F.); +#124030 = EDGE_CURVE('',#124031,#123850,#124033,.T.); +#124031 = VERTEX_POINT('',#124032); +#124032 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.E+000)); +#124033 = SURFACE_CURVE('',#124034,(#124039,#124045),.PCURVE_S1.); +#124034 = CIRCLE('',#124035,0.308574064194); +#124035 = AXIS2_PLACEMENT_3D('',#124036,#124037,#124038); +#124036 = CARTESIAN_POINT('',(-0.728168876214,8.85,2.640924866458E-017) + ); +#124037 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#124038 = DIRECTION('',(-1.,-4.440892098501E-016,0.E+000)); +#124039 = PCURVE('',#123888,#124040); +#124040 = DEFINITIONAL_REPRESENTATION('',(#124041),#124044); +#124041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124042,#124043), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#121650 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#121651 = CARTESIAN_POINT('',(4.761821717947,-1.15)); -#121652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121653 = PCURVE('',#90411,#121654); -#121654 = DEFINITIONAL_REPRESENTATION('',(#121655),#121659); -#121655 = CIRCLE('',#121656,0.308574064194); -#121656 = AXIS2_PLACEMENT_2D('',#121657,#121658); -#121657 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); -#121658 = DIRECTION('',(0.E+000,-1.)); -#121659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121660 = ORIENTED_EDGE('',*,*,#121661,.T.); -#121661 = EDGE_CURVE('',#121639,#121611,#121662,.T.); -#121662 = SURFACE_CURVE('',#121663,(#121667,#121673),.PCURVE_S1.); -#121663 = LINE('',#121664,#121665); -#121664 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); -#121665 = VECTOR('',#121666,1.); -#121666 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121667 = PCURVE('',#121496,#121668); -#121668 = DEFINITIONAL_REPRESENTATION('',(#121669),#121672); -#121669 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121670,#121671), +#124042 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#124043 = CARTESIAN_POINT('',(4.761821717947,-1.15)); +#124044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124045 = PCURVE('',#92803,#124046); +#124046 = DEFINITIONAL_REPRESENTATION('',(#124047),#124051); +#124047 = CIRCLE('',#124048,0.308574064194); +#124048 = AXIS2_PLACEMENT_2D('',#124049,#124050); +#124049 = CARTESIAN_POINT('',(-0.65,-0.200320883775)); +#124050 = DIRECTION('',(0.E+000,-1.)); +#124051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124052 = ORIENTED_EDGE('',*,*,#124053,.T.); +#124053 = EDGE_CURVE('',#124031,#124003,#124054,.T.); +#124054 = SURFACE_CURVE('',#124055,(#124059,#124065),.PCURVE_S1.); +#124055 = LINE('',#124056,#124057); +#124056 = CARTESIAN_POINT('',(-0.419594812019,10.,0.E+000)); +#124057 = VECTOR('',#124058,1.); +#124058 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124059 = PCURVE('',#123888,#124060); +#124060 = DEFINITIONAL_REPRESENTATION('',(#124061),#124064); +#124061 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124062,#124063), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#121670 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#121671 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#121672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121673 = PCURVE('',#121674,#121679); -#121674 = PLANE('',#121675); -#121675 = AXIS2_PLACEMENT_3D('',#121676,#121677,#121678); -#121676 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#121677 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); -#121678 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121679 = DEFINITIONAL_REPRESENTATION('',(#121680),#121684); -#121680 = LINE('',#121681,#121682); -#121681 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); -#121682 = VECTOR('',#121683,1.); -#121683 = DIRECTION('',(-1.,0.E+000)); -#121684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121685 = ADVANCED_FACE('',(#121686),#121674,.T.); -#121686 = FACE_BOUND('',#121687,.T.); -#121687 = EDGE_LOOP('',(#121688,#121717,#121738,#121739)); -#121688 = ORIENTED_EDGE('',*,*,#121689,.T.); -#121689 = EDGE_CURVE('',#121690,#121692,#121694,.T.); -#121690 = VERTEX_POINT('',#121691); -#121691 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.530776333563)); -#121692 = VERTEX_POINT('',#121693); -#121693 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.530776333563)); -#121694 = SURFACE_CURVE('',#121695,(#121699,#121706),.PCURVE_S1.); -#121695 = LINE('',#121696,#121697); -#121696 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); -#121697 = VECTOR('',#121698,1.); -#121698 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121699 = PCURVE('',#121674,#121700); -#121700 = DEFINITIONAL_REPRESENTATION('',(#121701),#121705); -#121701 = LINE('',#121702,#121703); -#121702 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121703 = VECTOR('',#121704,1.); -#121704 = DIRECTION('',(-1.,0.E+000)); -#121705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121706 = PCURVE('',#121707,#121712); -#121707 = CYLINDRICAL_SURFACE('',#121708,0.119270391569); -#121708 = AXIS2_PLACEMENT_3D('',#121709,#121710,#121711); -#121709 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#121710 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121711 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121712 = DEFINITIONAL_REPRESENTATION('',(#121713),#121716); -#121713 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121714,#121715), +#124062 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#124063 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#124064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124065 = PCURVE('',#124066,#124071); +#124066 = PLANE('',#124067); +#124067 = AXIS2_PLACEMENT_3D('',#124068,#124069,#124070); +#124068 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#124069 = DIRECTION('',(1.,4.440892098501E-016,-1.021336205033E-016)); +#124070 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#124071 = DEFINITIONAL_REPRESENTATION('',(#124072),#124076); +#124072 = LINE('',#124073,#124074); +#124073 = CARTESIAN_POINT('',(2.465190328816E-032,-0.530776333563)); +#124074 = VECTOR('',#124075,1.); +#124075 = DIRECTION('',(-1.,0.E+000)); +#124076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124077 = ADVANCED_FACE('',(#124078),#124066,.T.); +#124078 = FACE_BOUND('',#124079,.T.); +#124079 = EDGE_LOOP('',(#124080,#124109,#124130,#124131)); +#124080 = ORIENTED_EDGE('',*,*,#124081,.T.); +#124081 = EDGE_CURVE('',#124082,#124084,#124086,.T.); +#124082 = VERTEX_POINT('',#124083); +#124083 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.530776333563)); +#124084 = VERTEX_POINT('',#124085); +#124085 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.530776333563)); +#124086 = SURFACE_CURVE('',#124087,(#124091,#124098),.PCURVE_S1.); +#124087 = LINE('',#124088,#124089); +#124088 = CARTESIAN_POINT('',(-0.419594812019,10.,0.530776333563)); +#124089 = VECTOR('',#124090,1.); +#124090 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124091 = PCURVE('',#124066,#124092); +#124092 = DEFINITIONAL_REPRESENTATION('',(#124093),#124097); +#124093 = LINE('',#124094,#124095); +#124094 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124095 = VECTOR('',#124096,1.); +#124096 = DIRECTION('',(-1.,0.E+000)); +#124097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124098 = PCURVE('',#124099,#124104); +#124099 = CYLINDRICAL_SURFACE('',#124100,0.119270391569); +#124100 = AXIS2_PLACEMENT_3D('',#124101,#124102,#124103); +#124101 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#124102 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124103 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124104 = DEFINITIONAL_REPRESENTATION('',(#124105),#124108); +#124105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124106,#124107), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#121714 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#121715 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#121716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121717 = ORIENTED_EDGE('',*,*,#121718,.T.); -#121718 = EDGE_CURVE('',#121692,#121611,#121719,.T.); -#121719 = SURFACE_CURVE('',#121720,(#121724,#121731),.PCURVE_S1.); -#121720 = LINE('',#121721,#121722); -#121721 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.530776333563)); -#121722 = VECTOR('',#121723,1.); -#121723 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#121724 = PCURVE('',#121674,#121725); -#121725 = DEFINITIONAL_REPRESENTATION('',(#121726),#121730); -#121726 = LINE('',#121727,#121728); -#121727 = CARTESIAN_POINT('',(-1.35,1.133910970711E-033)); -#121728 = VECTOR('',#121729,1.); -#121729 = DIRECTION('',(4.535643882845E-032,-1.)); -#121730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124106 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#124107 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#124108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124109 = ORIENTED_EDGE('',*,*,#124110,.T.); +#124110 = EDGE_CURVE('',#124084,#124003,#124111,.T.); +#124111 = SURFACE_CURVE('',#124112,(#124116,#124123),.PCURVE_S1.); +#124112 = LINE('',#124113,#124114); +#124113 = CARTESIAN_POINT('',(-0.419594812019,8.65,0.530776333563)); +#124114 = VECTOR('',#124115,1.); +#124115 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#124116 = PCURVE('',#124066,#124117); +#124117 = DEFINITIONAL_REPRESENTATION('',(#124118),#124122); +#124118 = LINE('',#124119,#124120); +#124119 = CARTESIAN_POINT('',(-1.35,1.133910970711E-033)); +#124120 = VECTOR('',#124121,1.); +#124121 = DIRECTION('',(4.535643882845E-032,-1.)); +#124122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121731 = PCURVE('',#90355,#121732); -#121732 = DEFINITIONAL_REPRESENTATION('',(#121733),#121737); -#121733 = LINE('',#121734,#121735); -#121734 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); -#121735 = VECTOR('',#121736,1.); -#121736 = DIRECTION('',(1.,-1.021336205033E-016)); -#121737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124123 = PCURVE('',#92747,#124124); +#124124 = DEFINITIONAL_REPRESENTATION('',(#124125),#124129); +#124125 = LINE('',#124126,#124127); +#124126 = CARTESIAN_POINT('',(0.119223666437,0.108253180419)); +#124127 = VECTOR('',#124128,1.); +#124128 = DIRECTION('',(1.,-1.021336205033E-016)); +#124129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124130 = ORIENTED_EDGE('',*,*,#124053,.F.); +#124131 = ORIENTED_EDGE('',*,*,#124132,.F.); +#124132 = EDGE_CURVE('',#124082,#124031,#124133,.T.); +#124133 = SURFACE_CURVE('',#124134,(#124138,#124145),.PCURVE_S1.); +#124134 = LINE('',#124135,#124136); +#124135 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.530776333563)); +#124136 = VECTOR('',#124137,1.); +#124137 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#124138 = PCURVE('',#124066,#124139); +#124139 = DEFINITIONAL_REPRESENTATION('',(#124140),#124144); +#124140 = LINE('',#124141,#124142); +#124141 = CARTESIAN_POINT('',(-1.15,-1.133910970711E-033)); +#124142 = VECTOR('',#124143,1.); +#124143 = DIRECTION('',(4.535643882845E-032,-1.)); +#124144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124145 = PCURVE('',#92803,#124146); +#124146 = DEFINITIONAL_REPRESENTATION('',(#124147),#124151); +#124147 = LINE('',#124148,#124149); +#124148 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); +#124149 = VECTOR('',#124150,1.); +#124150 = DIRECTION('',(-1.,-1.021336205033E-016)); +#124151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124152 = ADVANCED_FACE('',(#124153),#123961,.T.); +#124153 = FACE_BOUND('',#124154,.T.); +#124154 = EDGE_LOOP('',(#124155,#124184,#124205,#124206)); +#124155 = ORIENTED_EDGE('',*,*,#124156,.T.); +#124156 = EDGE_CURVE('',#124157,#124159,#124161,.T.); +#124157 = VERTEX_POINT('',#124158); +#124158 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.530776333563)); +#124159 = VERTEX_POINT('',#124160); +#124160 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.530776333563)); +#124161 = SURFACE_CURVE('',#124162,(#124166,#124173),.PCURVE_S1.); +#124162 = LINE('',#124163,#124164); +#124163 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); +#124164 = VECTOR('',#124165,1.); +#124165 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#124166 = PCURVE('',#123961,#124167); +#124167 = DEFINITIONAL_REPRESENTATION('',(#124168),#124172); +#124168 = LINE('',#124169,#124170); +#124169 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124170 = VECTOR('',#124171,1.); +#124171 = DIRECTION('',(-1.,0.E+000)); +#124172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124173 = PCURVE('',#124174,#124179); +#124174 = CYLINDRICAL_SURFACE('',#124175,0.2192697516); +#124175 = AXIS2_PLACEMENT_3D('',#124176,#124177,#124178); +#124176 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); +#124177 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124178 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124179 = DEFINITIONAL_REPRESENTATION('',(#124180),#124183); +#124180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124181,#124182), + .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); +#124181 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#124182 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#124183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124184 = ORIENTED_EDGE('',*,*,#124185,.T.); +#124185 = EDGE_CURVE('',#124159,#123924,#124186,.T.); +#124186 = SURFACE_CURVE('',#124187,(#124191,#124198),.PCURVE_S1.); +#124187 = LINE('',#124188,#124189); +#124188 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.530776333563)); +#124189 = VECTOR('',#124190,1.); +#124190 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#124191 = PCURVE('',#123961,#124192); +#124192 = DEFINITIONAL_REPRESENTATION('',(#124193),#124197); +#124193 = LINE('',#124194,#124195); +#124194 = CARTESIAN_POINT('',(1.15,4.535643882845E-033)); +#124195 = VECTOR('',#124196,1.); +#124196 = DIRECTION('',(-4.535643882845E-032,-1.)); +#124197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121738 = ORIENTED_EDGE('',*,*,#121661,.F.); -#121739 = ORIENTED_EDGE('',*,*,#121740,.F.); -#121740 = EDGE_CURVE('',#121690,#121639,#121741,.T.); -#121741 = SURFACE_CURVE('',#121742,(#121746,#121753),.PCURVE_S1.); -#121742 = LINE('',#121743,#121744); -#121743 = CARTESIAN_POINT('',(-0.419594812019,8.85,0.530776333563)); -#121744 = VECTOR('',#121745,1.); -#121745 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#121746 = PCURVE('',#121674,#121747); -#121747 = DEFINITIONAL_REPRESENTATION('',(#121748),#121752); -#121748 = LINE('',#121749,#121750); -#121749 = CARTESIAN_POINT('',(-1.15,-1.133910970711E-033)); -#121750 = VECTOR('',#121751,1.); -#121751 = DIRECTION('',(4.535643882845E-032,-1.)); -#121752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121753 = PCURVE('',#90411,#121754); -#121754 = DEFINITIONAL_REPRESENTATION('',(#121755),#121759); -#121755 = LINE('',#121756,#121757); -#121756 = CARTESIAN_POINT('',(-0.119223666437,0.108253180419)); -#121757 = VECTOR('',#121758,1.); -#121758 = DIRECTION('',(-1.,-1.021336205033E-016)); -#121759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121760 = ADVANCED_FACE('',(#121761),#121569,.T.); -#121761 = FACE_BOUND('',#121762,.T.); -#121762 = EDGE_LOOP('',(#121763,#121792,#121813,#121814)); -#121763 = ORIENTED_EDGE('',*,*,#121764,.T.); -#121764 = EDGE_CURVE('',#121765,#121767,#121769,.T.); -#121765 = VERTEX_POINT('',#121766); -#121766 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.530776333563)); -#121767 = VERTEX_POINT('',#121768); -#121768 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.530776333563)); -#121769 = SURFACE_CURVE('',#121770,(#121774,#121781),.PCURVE_S1.); -#121770 = LINE('',#121771,#121772); -#121771 = CARTESIAN_POINT('',(-0.51959417205,10.,0.530776333563)); -#121772 = VECTOR('',#121773,1.); -#121773 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121774 = PCURVE('',#121569,#121775); -#121775 = DEFINITIONAL_REPRESENTATION('',(#121776),#121780); -#121776 = LINE('',#121777,#121778); -#121777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#121778 = VECTOR('',#121779,1.); -#121779 = DIRECTION('',(-1.,0.E+000)); -#121780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121781 = PCURVE('',#121782,#121787); -#121782 = CYLINDRICAL_SURFACE('',#121783,0.2192697516); -#121783 = AXIS2_PLACEMENT_3D('',#121784,#121785,#121786); -#121784 = CARTESIAN_POINT('',(-0.30032442045,10.,0.530776333563)); -#121785 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121786 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121787 = DEFINITIONAL_REPRESENTATION('',(#121788),#121791); -#121788 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121789,#121790), - .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#121789 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#121790 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#121791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121792 = ORIENTED_EDGE('',*,*,#121793,.T.); -#121793 = EDGE_CURVE('',#121767,#121532,#121794,.T.); -#121794 = SURFACE_CURVE('',#121795,(#121799,#121806),.PCURVE_S1.); -#121795 = LINE('',#121796,#121797); -#121796 = CARTESIAN_POINT('',(-0.51959417205,8.85,0.530776333563)); -#121797 = VECTOR('',#121798,1.); -#121798 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#121799 = PCURVE('',#121569,#121800); -#121800 = DEFINITIONAL_REPRESENTATION('',(#121801),#121805); -#121801 = LINE('',#121802,#121803); -#121802 = CARTESIAN_POINT('',(1.15,4.535643882845E-033)); -#121803 = VECTOR('',#121804,1.); -#121804 = DIRECTION('',(-4.535643882845E-032,-1.)); -#121805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121806 = PCURVE('',#90411,#121807); -#121807 = DEFINITIONAL_REPRESENTATION('',(#121808),#121812); -#121808 = LINE('',#121809,#121810); -#121809 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); -#121810 = VECTOR('',#121811,1.); -#121811 = DIRECTION('',(-1.,-1.021336205033E-016)); -#121812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121813 = ORIENTED_EDGE('',*,*,#121554,.F.); -#121814 = ORIENTED_EDGE('',*,*,#121815,.F.); -#121815 = EDGE_CURVE('',#121765,#121555,#121816,.T.); -#121816 = SURFACE_CURVE('',#121817,(#121821,#121828),.PCURVE_S1.); -#121817 = LINE('',#121818,#121819); -#121818 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.530776333563)); -#121819 = VECTOR('',#121820,1.); -#121820 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); -#121821 = PCURVE('',#121569,#121822); -#121822 = DEFINITIONAL_REPRESENTATION('',(#121823),#121827); -#121823 = LINE('',#121824,#121825); -#121824 = CARTESIAN_POINT('',(1.35,-4.535643882845E-033)); -#121825 = VECTOR('',#121826,1.); -#121826 = DIRECTION('',(-4.535643882845E-032,-1.)); -#121827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121828 = PCURVE('',#90355,#121829); -#121829 = DEFINITIONAL_REPRESENTATION('',(#121830),#121834); -#121830 = LINE('',#121831,#121832); -#121831 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); -#121832 = VECTOR('',#121833,1.); -#121833 = DIRECTION('',(1.,-1.021336205033E-016)); -#121834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121835 = ADVANCED_FACE('',(#121836),#121782,.T.); -#121836 = FACE_BOUND('',#121837,.T.); -#121837 = EDGE_LOOP('',(#121838,#121839,#121862,#121907)); -#121838 = ORIENTED_EDGE('',*,*,#121764,.F.); -#121839 = ORIENTED_EDGE('',*,*,#121840,.F.); -#121840 = EDGE_CURVE('',#121841,#121765,#121843,.T.); -#121841 = VERTEX_POINT('',#121842); -#121842 = CARTESIAN_POINT('',(-0.304819755875,8.65,0.75)); -#121843 = SURFACE_CURVE('',#121844,(#121849,#121855),.PCURVE_S1.); -#121844 = CIRCLE('',#121845,0.2192697516); -#121845 = AXIS2_PLACEMENT_3D('',#121846,#121847,#121848); -#121846 = CARTESIAN_POINT('',(-0.30032442045,8.65,0.530776333563)); -#121847 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121848 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121849 = PCURVE('',#121782,#121850); -#121850 = DEFINITIONAL_REPRESENTATION('',(#121851),#121854); -#121851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121852,#121853), +#124198 = PCURVE('',#92803,#124199); +#124199 = DEFINITIONAL_REPRESENTATION('',(#124200),#124204); +#124200 = LINE('',#124201,#124202); +#124201 = CARTESIAN_POINT('',(-0.119223666437,8.253820388628E-003)); +#124202 = VECTOR('',#124203,1.); +#124203 = DIRECTION('',(-1.,-1.021336205033E-016)); +#124204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124205 = ORIENTED_EDGE('',*,*,#123946,.F.); +#124206 = ORIENTED_EDGE('',*,*,#124207,.F.); +#124207 = EDGE_CURVE('',#124157,#123947,#124208,.T.); +#124208 = SURFACE_CURVE('',#124209,(#124213,#124220),.PCURVE_S1.); +#124209 = LINE('',#124210,#124211); +#124210 = CARTESIAN_POINT('',(-0.51959417205,8.65,0.530776333563)); +#124211 = VECTOR('',#124212,1.); +#124212 = DIRECTION('',(-1.021336205033E-016,0.E+000,-1.)); +#124213 = PCURVE('',#123961,#124214); +#124214 = DEFINITIONAL_REPRESENTATION('',(#124215),#124219); +#124215 = LINE('',#124216,#124217); +#124216 = CARTESIAN_POINT('',(1.35,-4.535643882845E-033)); +#124217 = VECTOR('',#124218,1.); +#124218 = DIRECTION('',(-4.535643882845E-032,-1.)); +#124219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124220 = PCURVE('',#92747,#124221); +#124221 = DEFINITIONAL_REPRESENTATION('',(#124222),#124226); +#124222 = LINE('',#124223,#124224); +#124223 = CARTESIAN_POINT('',(0.119223666437,8.253820388628E-003)); +#124224 = VECTOR('',#124225,1.); +#124225 = DIRECTION('',(1.,-1.021336205033E-016)); +#124226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124227 = ADVANCED_FACE('',(#124228),#124174,.T.); +#124228 = FACE_BOUND('',#124229,.T.); +#124229 = EDGE_LOOP('',(#124230,#124231,#124254,#124299)); +#124230 = ORIENTED_EDGE('',*,*,#124156,.F.); +#124231 = ORIENTED_EDGE('',*,*,#124232,.F.); +#124232 = EDGE_CURVE('',#124233,#124157,#124235,.T.); +#124233 = VERTEX_POINT('',#124234); +#124234 = CARTESIAN_POINT('',(-0.304819755875,8.65,0.75)); +#124235 = SURFACE_CURVE('',#124236,(#124241,#124247),.PCURVE_S1.); +#124236 = CIRCLE('',#124237,0.2192697516); +#124237 = AXIS2_PLACEMENT_3D('',#124238,#124239,#124240); +#124238 = CARTESIAN_POINT('',(-0.30032442045,8.65,0.530776333563)); +#124239 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124240 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124241 = PCURVE('',#124174,#124242); +#124242 = DEFINITIONAL_REPRESENTATION('',(#124243),#124246); +#124243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124244,#124245), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121852 = CARTESIAN_POINT('',(1.591299156552,1.35)); -#121853 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#121854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121855 = PCURVE('',#90355,#121856); -#121856 = DEFINITIONAL_REPRESENTATION('',(#121857),#121861); -#121857 = CIRCLE('',#121858,0.2192697516); -#121858 = AXIS2_PLACEMENT_2D('',#121859,#121860); -#121859 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#121860 = DIRECTION('',(0.E+000,1.)); -#121861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121862 = ORIENTED_EDGE('',*,*,#121863,.F.); -#121863 = EDGE_CURVE('',#121864,#121841,#121866,.T.); -#121864 = VERTEX_POINT('',#121865); -#121865 = CARTESIAN_POINT('',(-0.304819755875,8.85,0.75)); -#121866 = SURFACE_CURVE('',#121867,(#121871,#121900),.PCURVE_S1.); -#121867 = LINE('',#121868,#121869); -#121868 = CARTESIAN_POINT('',(-0.304819755875,8.65,0.75)); -#121869 = VECTOR('',#121870,1.); -#121870 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121871 = PCURVE('',#121782,#121872); -#121872 = DEFINITIONAL_REPRESENTATION('',(#121873),#121899); -#121873 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#121874,#121875,#121876, - #121877,#121878,#121879,#121880,#121881,#121882,#121883,#121884, - #121885,#121886,#121887,#121888,#121889,#121890,#121891,#121892, - #121893,#121894,#121895,#121896,#121897,#121898),.UNSPECIFIED.,.F., +#124244 = CARTESIAN_POINT('',(1.591299156552,1.35)); +#124245 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#124246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124247 = PCURVE('',#92747,#124248); +#124248 = DEFINITIONAL_REPRESENTATION('',(#124249),#124253); +#124249 = CIRCLE('',#124250,0.2192697516); +#124250 = AXIS2_PLACEMENT_2D('',#124251,#124252); +#124251 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#124252 = DIRECTION('',(0.E+000,1.)); +#124253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124254 = ORIENTED_EDGE('',*,*,#124255,.F.); +#124255 = EDGE_CURVE('',#124256,#124233,#124258,.T.); +#124256 = VERTEX_POINT('',#124257); +#124257 = CARTESIAN_POINT('',(-0.304819755875,8.85,0.75)); +#124258 = SURFACE_CURVE('',#124259,(#124263,#124292),.PCURVE_S1.); +#124259 = LINE('',#124260,#124261); +#124260 = CARTESIAN_POINT('',(-0.304819755875,8.65,0.75)); +#124261 = VECTOR('',#124262,1.); +#124262 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124263 = PCURVE('',#124174,#124264); +#124264 = DEFINITIONAL_REPRESENTATION('',(#124265),#124291); +#124265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#124266,#124267,#124268, + #124269,#124270,#124271,#124272,#124273,#124274,#124275,#124276, + #124277,#124278,#124279,#124280,#124281,#124282,#124283,#124284, + #124285,#124286,#124287,#124288,#124289,#124290),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.2, -0.190909090909,-0.181818181818,-0.172727272727,-0.163636363636, -0.154545454545,-0.145454545455,-0.136363636364,-0.127272727273, @@ -150099,128 +153101,128 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -5.454545454545E-002,-4.545454545454E-002,-3.636363636364E-002, -2.727272727273E-002,-1.818181818182E-002,-9.090909090909E-003, 0.E+000),.QUASI_UNIFORM_KNOTS.); -#121874 = CARTESIAN_POINT('',(1.591299156552,1.15)); -#121875 = CARTESIAN_POINT('',(1.591299156552,1.15303030303)); -#121876 = CARTESIAN_POINT('',(1.591299156552,1.159090909091)); -#121877 = CARTESIAN_POINT('',(1.591299156552,1.168181818182)); -#121878 = CARTESIAN_POINT('',(1.591299156552,1.177272727273)); -#121879 = CARTESIAN_POINT('',(1.591299156552,1.186363636364)); -#121880 = CARTESIAN_POINT('',(1.591299156552,1.195454545455)); -#121881 = CARTESIAN_POINT('',(1.591299156552,1.204545454545)); -#121882 = CARTESIAN_POINT('',(1.591299156552,1.213636363636)); -#121883 = CARTESIAN_POINT('',(1.591299156552,1.222727272727)); -#121884 = CARTESIAN_POINT('',(1.591299156552,1.231818181818)); -#121885 = CARTESIAN_POINT('',(1.591299156552,1.240909090909)); -#121886 = CARTESIAN_POINT('',(1.591299156552,1.25)); -#121887 = CARTESIAN_POINT('',(1.591299156552,1.259090909091)); -#121888 = CARTESIAN_POINT('',(1.591299156552,1.268181818182)); -#121889 = CARTESIAN_POINT('',(1.591299156552,1.277272727273)); -#121890 = CARTESIAN_POINT('',(1.591299156552,1.286363636364)); -#121891 = CARTESIAN_POINT('',(1.591299156552,1.295454545455)); -#121892 = CARTESIAN_POINT('',(1.591299156552,1.304545454545)); -#121893 = CARTESIAN_POINT('',(1.591299156552,1.313636363636)); -#121894 = CARTESIAN_POINT('',(1.591299156552,1.322727272727)); -#121895 = CARTESIAN_POINT('',(1.591299156552,1.331818181818)); -#121896 = CARTESIAN_POINT('',(1.591299156552,1.340909090909)); -#121897 = CARTESIAN_POINT('',(1.591299156552,1.34696969697)); -#121898 = CARTESIAN_POINT('',(1.591299156552,1.35)); -#121899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121900 = PCURVE('',#90437,#121901); -#121901 = DEFINITIONAL_REPRESENTATION('',(#121902),#121906); -#121902 = LINE('',#121903,#121904); -#121903 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); -#121904 = VECTOR('',#121905,1.); -#121905 = DIRECTION('',(4.440892098501E-016,-1.)); -#121906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121907 = ORIENTED_EDGE('',*,*,#121908,.T.); -#121908 = EDGE_CURVE('',#121864,#121767,#121909,.T.); -#121909 = SURFACE_CURVE('',#121910,(#121915,#121921),.PCURVE_S1.); -#121910 = CIRCLE('',#121911,0.2192697516); -#121911 = AXIS2_PLACEMENT_3D('',#121912,#121913,#121914); -#121912 = CARTESIAN_POINT('',(-0.30032442045,8.85,0.530776333563)); -#121913 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121914 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121915 = PCURVE('',#121782,#121916); -#121916 = DEFINITIONAL_REPRESENTATION('',(#121917),#121920); -#121917 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121918,#121919), +#124266 = CARTESIAN_POINT('',(1.591299156552,1.15)); +#124267 = CARTESIAN_POINT('',(1.591299156552,1.15303030303)); +#124268 = CARTESIAN_POINT('',(1.591299156552,1.159090909091)); +#124269 = CARTESIAN_POINT('',(1.591299156552,1.168181818182)); +#124270 = CARTESIAN_POINT('',(1.591299156552,1.177272727273)); +#124271 = CARTESIAN_POINT('',(1.591299156552,1.186363636364)); +#124272 = CARTESIAN_POINT('',(1.591299156552,1.195454545455)); +#124273 = CARTESIAN_POINT('',(1.591299156552,1.204545454545)); +#124274 = CARTESIAN_POINT('',(1.591299156552,1.213636363636)); +#124275 = CARTESIAN_POINT('',(1.591299156552,1.222727272727)); +#124276 = CARTESIAN_POINT('',(1.591299156552,1.231818181818)); +#124277 = CARTESIAN_POINT('',(1.591299156552,1.240909090909)); +#124278 = CARTESIAN_POINT('',(1.591299156552,1.25)); +#124279 = CARTESIAN_POINT('',(1.591299156552,1.259090909091)); +#124280 = CARTESIAN_POINT('',(1.591299156552,1.268181818182)); +#124281 = CARTESIAN_POINT('',(1.591299156552,1.277272727273)); +#124282 = CARTESIAN_POINT('',(1.591299156552,1.286363636364)); +#124283 = CARTESIAN_POINT('',(1.591299156552,1.295454545455)); +#124284 = CARTESIAN_POINT('',(1.591299156552,1.304545454545)); +#124285 = CARTESIAN_POINT('',(1.591299156552,1.313636363636)); +#124286 = CARTESIAN_POINT('',(1.591299156552,1.322727272727)); +#124287 = CARTESIAN_POINT('',(1.591299156552,1.331818181818)); +#124288 = CARTESIAN_POINT('',(1.591299156552,1.340909090909)); +#124289 = CARTESIAN_POINT('',(1.591299156552,1.34696969697)); +#124290 = CARTESIAN_POINT('',(1.591299156552,1.35)); +#124291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124292 = PCURVE('',#92829,#124293); +#124293 = DEFINITIONAL_REPRESENTATION('',(#124294),#124298); +#124294 = LINE('',#124295,#124296); +#124295 = CARTESIAN_POINT('',(0.223028236564,4.991951569247E-048)); +#124296 = VECTOR('',#124297,1.); +#124297 = DIRECTION('',(4.440892098501E-016,-1.)); +#124298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124299 = ORIENTED_EDGE('',*,*,#124300,.T.); +#124300 = EDGE_CURVE('',#124256,#124159,#124301,.T.); +#124301 = SURFACE_CURVE('',#124302,(#124307,#124313),.PCURVE_S1.); +#124302 = CIRCLE('',#124303,0.2192697516); +#124303 = AXIS2_PLACEMENT_3D('',#124304,#124305,#124306); +#124304 = CARTESIAN_POINT('',(-0.30032442045,8.85,0.530776333563)); +#124305 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124306 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124307 = PCURVE('',#124174,#124308); +#124308 = DEFINITIONAL_REPRESENTATION('',(#124309),#124312); +#124309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124310,#124311), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121918 = CARTESIAN_POINT('',(1.591299156552,1.15)); -#121919 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#121920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124310 = CARTESIAN_POINT('',(1.591299156552,1.15)); +#124311 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#124312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#121921 = PCURVE('',#90411,#121922); -#121922 = DEFINITIONAL_REPRESENTATION('',(#121923),#121931); -#121923 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#121924,#121925,#121926, - #121927,#121928,#121929,#121930),.UNSPECIFIED.,.T.,.F.) +#124313 = PCURVE('',#92803,#124314); +#124314 = DEFINITIONAL_REPRESENTATION('',(#124315),#124323); +#124315 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124316,#124317,#124318, + #124319,#124320,#124321,#124322),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#121924 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#121925 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); -#121926 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); -#121927 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); -#121928 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); -#121929 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); -#121930 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); -#121931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121932 = ADVANCED_FACE('',(#121933),#121707,.F.); -#121933 = FACE_BOUND('',#121934,.F.); -#121934 = EDGE_LOOP('',(#121935,#121936,#121959,#122004)); -#121935 = ORIENTED_EDGE('',*,*,#121689,.T.); -#121936 = ORIENTED_EDGE('',*,*,#121937,.F.); -#121937 = EDGE_CURVE('',#121938,#121692,#121940,.T.); -#121938 = VERTEX_POINT('',#121939); -#121939 = CARTESIAN_POINT('',(-0.303662633502,8.65,0.65)); -#121940 = SURFACE_CURVE('',#121941,(#121946,#121952),.PCURVE_S1.); -#121941 = CIRCLE('',#121942,0.119270391569); -#121942 = AXIS2_PLACEMENT_3D('',#121943,#121944,#121945); -#121943 = CARTESIAN_POINT('',(-0.30032442045,8.65,0.530776333563)); -#121944 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#121945 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#121946 = PCURVE('',#121707,#121947); -#121947 = DEFINITIONAL_REPRESENTATION('',(#121948),#121951); -#121948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#121949,#121950), +#124316 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#124317 = CARTESIAN_POINT('',(0.260562683897,0.446793323588)); +#124318 = CARTESIAN_POINT('',(7.066950872999E-002,0.117888696189)); +#124319 = CARTESIAN_POINT('',(-0.119223666437,-0.211015931211)); +#124320 = CARTESIAN_POINT('',(-0.309116841604,0.117888696189)); +#124321 = CARTESIAN_POINT('',(-0.499010016771,0.446793323588)); +#124322 = CARTESIAN_POINT('',(-0.119223666437,0.446793323588)); +#124323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124324 = ADVANCED_FACE('',(#124325),#124099,.F.); +#124325 = FACE_BOUND('',#124326,.F.); +#124326 = EDGE_LOOP('',(#124327,#124328,#124351,#124396)); +#124327 = ORIENTED_EDGE('',*,*,#124081,.T.); +#124328 = ORIENTED_EDGE('',*,*,#124329,.F.); +#124329 = EDGE_CURVE('',#124330,#124084,#124332,.T.); +#124330 = VERTEX_POINT('',#124331); +#124331 = CARTESIAN_POINT('',(-0.303662633502,8.65,0.65)); +#124332 = SURFACE_CURVE('',#124333,(#124338,#124344),.PCURVE_S1.); +#124333 = CIRCLE('',#124334,0.119270391569); +#124334 = AXIS2_PLACEMENT_3D('',#124335,#124336,#124337); +#124335 = CARTESIAN_POINT('',(-0.30032442045,8.65,0.530776333563)); +#124336 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124337 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124338 = PCURVE('',#124099,#124339); +#124339 = DEFINITIONAL_REPRESENTATION('',(#124340),#124343); +#124340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124341,#124342), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#121949 = CARTESIAN_POINT('',(1.598788597134,1.35)); -#121950 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#121951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121952 = PCURVE('',#90355,#121953); -#121953 = DEFINITIONAL_REPRESENTATION('',(#121954),#121958); -#121954 = CIRCLE('',#121955,0.119270391569); -#121955 = AXIS2_PLACEMENT_2D('',#121956,#121957); -#121956 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); -#121957 = DIRECTION('',(0.E+000,1.)); -#121958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121959 = ORIENTED_EDGE('',*,*,#121960,.T.); -#121960 = EDGE_CURVE('',#121938,#121961,#121963,.T.); -#121961 = VERTEX_POINT('',#121962); -#121962 = CARTESIAN_POINT('',(-0.303662633502,8.85,0.65)); -#121963 = SURFACE_CURVE('',#121964,(#121968,#121997),.PCURVE_S1.); -#121964 = LINE('',#121965,#121966); -#121965 = CARTESIAN_POINT('',(-0.303662633502,8.65,0.65)); -#121966 = VECTOR('',#121967,1.); -#121967 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); -#121968 = PCURVE('',#121707,#121969); -#121969 = DEFINITIONAL_REPRESENTATION('',(#121970),#121996); -#121970 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#121971,#121972,#121973, - #121974,#121975,#121976,#121977,#121978,#121979,#121980,#121981, - #121982,#121983,#121984,#121985,#121986,#121987,#121988,#121989, - #121990,#121991,#121992,#121993,#121994,#121995),.UNSPECIFIED.,.F., +#124341 = CARTESIAN_POINT('',(1.598788597134,1.35)); +#124342 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#124343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124344 = PCURVE('',#92747,#124345); +#124345 = DEFINITIONAL_REPRESENTATION('',(#124346),#124350); +#124346 = CIRCLE('',#124347,0.119270391569); +#124347 = AXIS2_PLACEMENT_2D('',#124348,#124349); +#124348 = CARTESIAN_POINT('',(0.119223666437,0.227523571988)); +#124349 = DIRECTION('',(0.E+000,1.)); +#124350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124351 = ORIENTED_EDGE('',*,*,#124352,.T.); +#124352 = EDGE_CURVE('',#124330,#124353,#124355,.T.); +#124353 = VERTEX_POINT('',#124354); +#124354 = CARTESIAN_POINT('',(-0.303662633502,8.85,0.65)); +#124355 = SURFACE_CURVE('',#124356,(#124360,#124389),.PCURVE_S1.); +#124356 = LINE('',#124357,#124358); +#124357 = CARTESIAN_POINT('',(-0.303662633502,8.65,0.65)); +#124358 = VECTOR('',#124359,1.); +#124359 = DIRECTION('',(-4.440892098501E-016,1.,0.E+000)); +#124360 = PCURVE('',#124099,#124361); +#124361 = DEFINITIONAL_REPRESENTATION('',(#124362),#124388); +#124362 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#124363,#124364,#124365, + #124366,#124367,#124368,#124369,#124370,#124371,#124372,#124373, + #124374,#124375,#124376,#124377,#124378,#124379,#124380,#124381, + #124382,#124383,#124384,#124385,#124386,#124387),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 9.090909090909E-003,1.818181818182E-002,2.727272727273E-002, 3.636363636364E-002,4.545454545454E-002,5.454545454545E-002, @@ -150229,11038 +153231,11038 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.127272727273,0.136363636364,0.145454545455,0.154545454545, 0.163636363636,0.172727272727,0.181818181818,0.190909090909,0.2), .QUASI_UNIFORM_KNOTS.); -#121971 = CARTESIAN_POINT('',(1.598788597134,1.35)); -#121972 = CARTESIAN_POINT('',(1.598788597134,1.34696969697)); -#121973 = CARTESIAN_POINT('',(1.598788597134,1.340909090909)); -#121974 = CARTESIAN_POINT('',(1.598788597134,1.331818181818)); -#121975 = CARTESIAN_POINT('',(1.598788597134,1.322727272727)); -#121976 = CARTESIAN_POINT('',(1.598788597134,1.313636363636)); -#121977 = CARTESIAN_POINT('',(1.598788597134,1.304545454545)); -#121978 = CARTESIAN_POINT('',(1.598788597134,1.295454545455)); -#121979 = CARTESIAN_POINT('',(1.598788597134,1.286363636364)); -#121980 = CARTESIAN_POINT('',(1.598788597134,1.277272727273)); -#121981 = CARTESIAN_POINT('',(1.598788597134,1.268181818182)); -#121982 = CARTESIAN_POINT('',(1.598788597134,1.259090909091)); -#121983 = CARTESIAN_POINT('',(1.598788597134,1.25)); -#121984 = CARTESIAN_POINT('',(1.598788597134,1.240909090909)); -#121985 = CARTESIAN_POINT('',(1.598788597134,1.231818181818)); -#121986 = CARTESIAN_POINT('',(1.598788597134,1.222727272727)); -#121987 = CARTESIAN_POINT('',(1.598788597134,1.213636363636)); -#121988 = CARTESIAN_POINT('',(1.598788597134,1.204545454545)); -#121989 = CARTESIAN_POINT('',(1.598788597134,1.195454545455)); -#121990 = CARTESIAN_POINT('',(1.598788597134,1.186363636364)); -#121991 = CARTESIAN_POINT('',(1.598788597134,1.177272727273)); -#121992 = CARTESIAN_POINT('',(1.598788597134,1.168181818182)); -#121993 = CARTESIAN_POINT('',(1.598788597134,1.159090909091)); -#121994 = CARTESIAN_POINT('',(1.598788597134,1.15303030303)); -#121995 = CARTESIAN_POINT('',(1.598788597134,1.15)); -#121996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#121997 = PCURVE('',#90383,#121998); -#121998 = DEFINITIONAL_REPRESENTATION('',(#121999),#122003); -#121999 = LINE('',#122000,#122001); -#122000 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); -#122001 = VECTOR('',#122002,1.); -#122002 = DIRECTION('',(4.440892098501E-016,1.)); -#122003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122004 = ORIENTED_EDGE('',*,*,#122005,.T.); -#122005 = EDGE_CURVE('',#121961,#121690,#122006,.T.); -#122006 = SURFACE_CURVE('',#122007,(#122012,#122018),.PCURVE_S1.); -#122007 = CIRCLE('',#122008,0.119270391569); -#122008 = AXIS2_PLACEMENT_3D('',#122009,#122010,#122011); -#122009 = CARTESIAN_POINT('',(-0.30032442045,8.85,0.530776333563)); -#122010 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); -#122011 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); -#122012 = PCURVE('',#121707,#122013); -#122013 = DEFINITIONAL_REPRESENTATION('',(#122014),#122017); -#122014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122015,#122016), +#124363 = CARTESIAN_POINT('',(1.598788597134,1.35)); +#124364 = CARTESIAN_POINT('',(1.598788597134,1.34696969697)); +#124365 = CARTESIAN_POINT('',(1.598788597134,1.340909090909)); +#124366 = CARTESIAN_POINT('',(1.598788597134,1.331818181818)); +#124367 = CARTESIAN_POINT('',(1.598788597134,1.322727272727)); +#124368 = CARTESIAN_POINT('',(1.598788597134,1.313636363636)); +#124369 = CARTESIAN_POINT('',(1.598788597134,1.304545454545)); +#124370 = CARTESIAN_POINT('',(1.598788597134,1.295454545455)); +#124371 = CARTESIAN_POINT('',(1.598788597134,1.286363636364)); +#124372 = CARTESIAN_POINT('',(1.598788597134,1.277272727273)); +#124373 = CARTESIAN_POINT('',(1.598788597134,1.268181818182)); +#124374 = CARTESIAN_POINT('',(1.598788597134,1.259090909091)); +#124375 = CARTESIAN_POINT('',(1.598788597134,1.25)); +#124376 = CARTESIAN_POINT('',(1.598788597134,1.240909090909)); +#124377 = CARTESIAN_POINT('',(1.598788597134,1.231818181818)); +#124378 = CARTESIAN_POINT('',(1.598788597134,1.222727272727)); +#124379 = CARTESIAN_POINT('',(1.598788597134,1.213636363636)); +#124380 = CARTESIAN_POINT('',(1.598788597134,1.204545454545)); +#124381 = CARTESIAN_POINT('',(1.598788597134,1.195454545455)); +#124382 = CARTESIAN_POINT('',(1.598788597134,1.186363636364)); +#124383 = CARTESIAN_POINT('',(1.598788597134,1.177272727273)); +#124384 = CARTESIAN_POINT('',(1.598788597134,1.168181818182)); +#124385 = CARTESIAN_POINT('',(1.598788597134,1.159090909091)); +#124386 = CARTESIAN_POINT('',(1.598788597134,1.15303030303)); +#124387 = CARTESIAN_POINT('',(1.598788597134,1.15)); +#124388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124389 = PCURVE('',#92775,#124390); +#124390 = DEFINITIONAL_REPRESENTATION('',(#124391),#124395); +#124391 = LINE('',#124392,#124393); +#124392 = CARTESIAN_POINT('',(-0.224185358936,4.926693529724E-048)); +#124393 = VECTOR('',#124394,1.); +#124394 = DIRECTION('',(4.440892098501E-016,1.)); +#124395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124396 = ORIENTED_EDGE('',*,*,#124397,.T.); +#124397 = EDGE_CURVE('',#124353,#124082,#124398,.T.); +#124398 = SURFACE_CURVE('',#124399,(#124404,#124410),.PCURVE_S1.); +#124399 = CIRCLE('',#124400,0.119270391569); +#124400 = AXIS2_PLACEMENT_3D('',#124401,#124402,#124403); +#124401 = CARTESIAN_POINT('',(-0.30032442045,8.85,0.530776333563)); +#124402 = DIRECTION('',(4.440892098501E-016,-1.,0.E+000)); +#124403 = DIRECTION('',(1.,4.440892098501E-016,0.E+000)); +#124404 = PCURVE('',#124099,#124405); +#124405 = DEFINITIONAL_REPRESENTATION('',(#124406),#124409); +#124406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124407,#124408), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#122015 = CARTESIAN_POINT('',(1.598788597134,1.15)); -#122016 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#122017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124407 = CARTESIAN_POINT('',(1.598788597134,1.15)); +#124408 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#124409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122018 = PCURVE('',#90411,#122019); -#122019 = DEFINITIONAL_REPRESENTATION('',(#122020),#122028); -#122020 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122021,#122022,#122023, - #122024,#122025,#122026,#122027),.UNSPECIFIED.,.T.,.F.) +#124410 = PCURVE('',#92803,#124411); +#124411 = DEFINITIONAL_REPRESENTATION('',(#124412),#124420); +#124412 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124413,#124414,#124415, + #124416,#124417,#124418,#124419),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#122021 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#122022 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); -#122023 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); -#122024 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); -#122025 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); -#122026 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); -#122027 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); -#122028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122029 = ADVANCED_FACE('',(#122030),#90383,.T.); -#122030 = FACE_BOUND('',#122031,.T.); -#122031 = EDGE_LOOP('',(#122032,#122053,#122054,#122075)); -#122032 = ORIENTED_EDGE('',*,*,#122033,.F.); -#122033 = EDGE_CURVE('',#121938,#90335,#122034,.T.); -#122034 = SURFACE_CURVE('',#122035,(#122039,#122046),.PCURVE_S1.); -#122035 = LINE('',#122036,#122037); -#122036 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); -#122037 = VECTOR('',#122038,1.); -#122038 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#122039 = PCURVE('',#90383,#122040); -#122040 = DEFINITIONAL_REPRESENTATION('',(#122041),#122045); -#122041 = LINE('',#122042,#122043); -#122042 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122043 = VECTOR('',#122044,1.); -#122044 = DIRECTION('',(-1.,2.995851623787E-063)); -#122045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122046 = PCURVE('',#90355,#122047); -#122047 = DEFINITIONAL_REPRESENTATION('',(#122048),#122052); -#122048 = LINE('',#122049,#122050); -#122049 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122050 = VECTOR('',#122051,1.); -#122051 = DIRECTION('',(-3.563627120235E-016,1.)); -#122052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122053 = ORIENTED_EDGE('',*,*,#121960,.T.); -#122054 = ORIENTED_EDGE('',*,*,#122055,.T.); -#122055 = EDGE_CURVE('',#121961,#90368,#122056,.T.); -#122056 = SURFACE_CURVE('',#122057,(#122061,#122068),.PCURVE_S1.); -#122057 = LINE('',#122058,#122059); -#122058 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.65)); -#122059 = VECTOR('',#122060,1.); -#122060 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#122061 = PCURVE('',#90383,#122062); -#122062 = DEFINITIONAL_REPRESENTATION('',(#122063),#122067); -#122063 = LINE('',#122064,#122065); -#122064 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); -#122065 = VECTOR('',#122066,1.); -#122066 = DIRECTION('',(-1.,2.995851623787E-063)); -#122067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122068 = PCURVE('',#90411,#122069); -#122069 = DEFINITIONAL_REPRESENTATION('',(#122070),#122074); -#122070 = LINE('',#122071,#122072); -#122071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122072 = VECTOR('',#122073,1.); -#122073 = DIRECTION('',(3.563627120235E-016,1.)); -#122074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122075 = ORIENTED_EDGE('',*,*,#90367,.F.); -#122076 = ADVANCED_FACE('',(#122077),#90411,.T.); -#122077 = FACE_BOUND('',#122078,.T.); -#122078 = EDGE_LOOP('',(#122079,#122080,#122081,#122082,#122083,#122084, - #122105,#122106,#122107,#122108,#122109,#122130)); -#122079 = ORIENTED_EDGE('',*,*,#122055,.F.); -#122080 = ORIENTED_EDGE('',*,*,#122005,.T.); -#122081 = ORIENTED_EDGE('',*,*,#121740,.T.); -#122082 = ORIENTED_EDGE('',*,*,#121638,.T.); -#122083 = ORIENTED_EDGE('',*,*,#121457,.T.); -#122084 = ORIENTED_EDGE('',*,*,#122085,.F.); -#122085 = EDGE_CURVE('',#121321,#121428,#122086,.T.); -#122086 = SURFACE_CURVE('',#122087,(#122091,#122098),.PCURVE_S1.); -#122087 = LINE('',#122088,#122089); -#122088 = CARTESIAN_POINT('',(-1.,8.85,1.159810404338E-002)); -#122089 = VECTOR('',#122090,1.); -#122090 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); -#122091 = PCURVE('',#90411,#122092); -#122092 = DEFINITIONAL_REPRESENTATION('',(#122093),#122097); -#122093 = LINE('',#122094,#122095); -#122094 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); -#122095 = VECTOR('',#122096,1.); -#122096 = DIRECTION('',(-1.,2.101748079665E-016)); -#122097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122098 = PCURVE('',#121341,#122099); -#122099 = DEFINITIONAL_REPRESENTATION('',(#122100),#122104); -#122100 = LINE('',#122101,#122102); -#122101 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#122102 = VECTOR('',#122103,1.); -#122103 = DIRECTION('',(1.194699204908E-017,-1.)); -#122104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122105 = ORIENTED_EDGE('',*,*,#121403,.F.); -#122106 = ORIENTED_EDGE('',*,*,#121531,.F.); -#122107 = ORIENTED_EDGE('',*,*,#121793,.F.); -#122108 = ORIENTED_EDGE('',*,*,#121908,.F.); -#122109 = ORIENTED_EDGE('',*,*,#122110,.T.); -#122110 = EDGE_CURVE('',#121864,#90396,#122111,.T.); -#122111 = SURFACE_CURVE('',#122112,(#122116,#122123),.PCURVE_S1.); -#122112 = LINE('',#122113,#122114); -#122113 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.75)); -#122114 = VECTOR('',#122115,1.); -#122115 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#122116 = PCURVE('',#90411,#122117); -#122117 = DEFINITIONAL_REPRESENTATION('',(#122118),#122122); -#122118 = LINE('',#122119,#122120); -#122119 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#122120 = VECTOR('',#122121,1.); -#122121 = DIRECTION('',(3.563627120235E-016,1.)); -#122122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122123 = PCURVE('',#90437,#122124); -#122124 = DEFINITIONAL_REPRESENTATION('',(#122125),#122129); -#122125 = LINE('',#122126,#122127); -#122126 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); -#122127 = VECTOR('',#122128,1.); -#122128 = DIRECTION('',(1.,2.995851623787E-063)); -#122129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122130 = ORIENTED_EDGE('',*,*,#90395,.F.); -#122131 = ADVANCED_FACE('',(#122132),#90437,.T.); -#122132 = FACE_BOUND('',#122133,.T.); -#122133 = EDGE_LOOP('',(#122134,#122135,#122136,#122157)); -#122134 = ORIENTED_EDGE('',*,*,#122110,.F.); -#122135 = ORIENTED_EDGE('',*,*,#121863,.T.); -#122136 = ORIENTED_EDGE('',*,*,#122137,.T.); -#122137 = EDGE_CURVE('',#121841,#90333,#122138,.T.); -#122138 = SURFACE_CURVE('',#122139,(#122143,#122150),.PCURVE_S1.); -#122139 = LINE('',#122140,#122141); -#122140 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.75)); -#122141 = VECTOR('',#122142,1.); -#122142 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); -#122143 = PCURVE('',#90437,#122144); -#122144 = DEFINITIONAL_REPRESENTATION('',(#122145),#122149); -#122145 = LINE('',#122146,#122147); -#122146 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122147 = VECTOR('',#122148,1.); -#122148 = DIRECTION('',(1.,2.995851623787E-063)); -#122149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122150 = PCURVE('',#90355,#122151); -#122151 = DEFINITIONAL_REPRESENTATION('',(#122152),#122156); -#122152 = LINE('',#122153,#122154); -#122153 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#122154 = VECTOR('',#122155,1.); -#122155 = DIRECTION('',(-3.563627120235E-016,1.)); -#122156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122157 = ORIENTED_EDGE('',*,*,#90423,.F.); -#122158 = ADVANCED_FACE('',(#122159),#90355,.T.); -#122159 = FACE_BOUND('',#122160,.T.); -#122160 = EDGE_LOOP('',(#122161,#122162,#122163,#122164,#122165,#122166, - #122187,#122188,#122189,#122190,#122191,#122192)); -#122161 = ORIENTED_EDGE('',*,*,#122137,.F.); -#122162 = ORIENTED_EDGE('',*,*,#121840,.T.); -#122163 = ORIENTED_EDGE('',*,*,#121815,.T.); -#122164 = ORIENTED_EDGE('',*,*,#121581,.T.); -#122165 = ORIENTED_EDGE('',*,*,#121353,.T.); -#122166 = ORIENTED_EDGE('',*,*,#122167,.F.); -#122167 = EDGE_CURVE('',#121430,#121319,#122168,.T.); -#122168 = SURFACE_CURVE('',#122169,(#122173,#122180),.PCURVE_S1.); -#122169 = LINE('',#122170,#122171); -#122170 = CARTESIAN_POINT('',(-1.,8.65,1.159810404338E-002)); -#122171 = VECTOR('',#122172,1.); -#122172 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); -#122173 = PCURVE('',#90355,#122174); -#122174 = DEFINITIONAL_REPRESENTATION('',(#122175),#122179); -#122175 = LINE('',#122176,#122177); -#122176 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); -#122177 = VECTOR('',#122178,1.); -#122178 = DIRECTION('',(-1.,-2.101748079665E-016)); -#122179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122180 = PCURVE('',#121341,#122181); -#122181 = DEFINITIONAL_REPRESENTATION('',(#122182),#122186); -#122182 = LINE('',#122183,#122184); -#122183 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#122184 = VECTOR('',#122185,1.); -#122185 = DIRECTION('',(-1.194699204908E-017,1.)); -#122186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122187 = ORIENTED_EDGE('',*,*,#121507,.F.); -#122188 = ORIENTED_EDGE('',*,*,#121610,.F.); -#122189 = ORIENTED_EDGE('',*,*,#121718,.F.); -#122190 = ORIENTED_EDGE('',*,*,#121937,.F.); -#122191 = ORIENTED_EDGE('',*,*,#122033,.T.); -#122192 = ORIENTED_EDGE('',*,*,#90332,.F.); -#122193 = ADVANCED_FACE('',(#122194),#121341,.T.); -#122194 = FACE_BOUND('',#122195,.T.); -#122195 = EDGE_LOOP('',(#122196,#122197,#122198,#122199)); -#122196 = ORIENTED_EDGE('',*,*,#122085,.T.); -#122197 = ORIENTED_EDGE('',*,*,#121427,.T.); -#122198 = ORIENTED_EDGE('',*,*,#122167,.T.); -#122199 = ORIENTED_EDGE('',*,*,#121318,.T.); -#122200 = ADVANCED_FACE('',(#122201),#122215,.F.); -#122201 = FACE_BOUND('',#122202,.T.); -#122202 = EDGE_LOOP('',(#122203,#122238,#122261,#122288)); -#122203 = ORIENTED_EDGE('',*,*,#122204,.F.); -#122204 = EDGE_CURVE('',#122205,#122207,#122209,.T.); -#122205 = VERTEX_POINT('',#122206); -#122206 = CARTESIAN_POINT('',(11.,8.65,-0.308197125857)); -#122207 = VERTEX_POINT('',#122208); -#122208 = CARTESIAN_POINT('',(11.,8.85,-0.308197125857)); -#122209 = SURFACE_CURVE('',#122210,(#122214,#122226),.PCURVE_S1.); -#122210 = LINE('',#122211,#122212); -#122211 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#122212 = VECTOR('',#122213,1.); -#122213 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122214 = PCURVE('',#122215,#122220); -#122215 = PLANE('',#122216); -#122216 = AXIS2_PLACEMENT_3D('',#122217,#122218,#122219); -#122217 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#124413 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#124414 = CARTESIAN_POINT('',(8.735871159939E-002,0.346793963558)); +#124415 = CARTESIAN_POINT('',(-1.593247741878E-002,0.167888376204)); +#124416 = CARTESIAN_POINT('',(-0.119223666437,-1.10172111498E-002)); +#124417 = CARTESIAN_POINT('',(-0.222514855455,0.167888376204)); +#124418 = CARTESIAN_POINT('',(-0.325806044473,0.346793963558)); +#124419 = CARTESIAN_POINT('',(-0.119223666437,0.346793963558)); +#124420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124421 = ADVANCED_FACE('',(#124422),#92775,.T.); +#124422 = FACE_BOUND('',#124423,.T.); +#124423 = EDGE_LOOP('',(#124424,#124445,#124446,#124467)); +#124424 = ORIENTED_EDGE('',*,*,#124425,.F.); +#124425 = EDGE_CURVE('',#124330,#92727,#124426,.T.); +#124426 = SURFACE_CURVE('',#124427,(#124431,#124438),.PCURVE_S1.); +#124427 = LINE('',#124428,#124429); +#124428 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.65)); +#124429 = VECTOR('',#124430,1.); +#124430 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#124431 = PCURVE('',#92775,#124432); +#124432 = DEFINITIONAL_REPRESENTATION('',(#124433),#124437); +#124433 = LINE('',#124434,#124435); +#124434 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124435 = VECTOR('',#124436,1.); +#124436 = DIRECTION('',(-1.,2.995851623787E-063)); +#124437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124438 = PCURVE('',#92747,#124439); +#124439 = DEFINITIONAL_REPRESENTATION('',(#124440),#124444); +#124440 = LINE('',#124441,#124442); +#124441 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124442 = VECTOR('',#124443,1.); +#124443 = DIRECTION('',(-3.563627120235E-016,1.)); +#124444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124445 = ORIENTED_EDGE('',*,*,#124352,.T.); +#124446 = ORIENTED_EDGE('',*,*,#124447,.T.); +#124447 = EDGE_CURVE('',#124353,#92760,#124448,.T.); +#124448 = SURFACE_CURVE('',#124449,(#124453,#124460),.PCURVE_S1.); +#124449 = LINE('',#124450,#124451); +#124450 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.65)); +#124451 = VECTOR('',#124452,1.); +#124452 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#124453 = PCURVE('',#92775,#124454); +#124454 = DEFINITIONAL_REPRESENTATION('',(#124455),#124459); +#124455 = LINE('',#124456,#124457); +#124456 = CARTESIAN_POINT('',(1.110223024625E-016,0.2)); +#124457 = VECTOR('',#124458,1.); +#124458 = DIRECTION('',(-1.,2.995851623787E-063)); +#124459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124460 = PCURVE('',#92803,#124461); +#124461 = DEFINITIONAL_REPRESENTATION('',(#124462),#124466); +#124462 = LINE('',#124463,#124464); +#124463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124464 = VECTOR('',#124465,1.); +#124465 = DIRECTION('',(3.563627120235E-016,1.)); +#124466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124467 = ORIENTED_EDGE('',*,*,#92759,.F.); +#124468 = ADVANCED_FACE('',(#124469),#92803,.T.); +#124469 = FACE_BOUND('',#124470,.T.); +#124470 = EDGE_LOOP('',(#124471,#124472,#124473,#124474,#124475,#124476, + #124497,#124498,#124499,#124500,#124501,#124522)); +#124471 = ORIENTED_EDGE('',*,*,#124447,.F.); +#124472 = ORIENTED_EDGE('',*,*,#124397,.T.); +#124473 = ORIENTED_EDGE('',*,*,#124132,.T.); +#124474 = ORIENTED_EDGE('',*,*,#124030,.T.); +#124475 = ORIENTED_EDGE('',*,*,#123849,.T.); +#124476 = ORIENTED_EDGE('',*,*,#124477,.F.); +#124477 = EDGE_CURVE('',#123713,#123820,#124478,.T.); +#124478 = SURFACE_CURVE('',#124479,(#124483,#124490),.PCURVE_S1.); +#124479 = LINE('',#124480,#124481); +#124480 = CARTESIAN_POINT('',(-1.,8.85,1.159810404338E-002)); +#124481 = VECTOR('',#124482,1.); +#124482 = DIRECTION('',(2.101748079665E-016,-1.194699204908E-017,-1.)); +#124483 = PCURVE('',#92803,#124484); +#124484 = DEFINITIONAL_REPRESENTATION('',(#124485),#124489); +#124485 = LINE('',#124486,#124487); +#124486 = CARTESIAN_POINT('',(-0.638401895957,-0.472152007561)); +#124487 = VECTOR('',#124488,1.); +#124488 = DIRECTION('',(-1.,2.101748079665E-016)); +#124489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124490 = PCURVE('',#123733,#124491); +#124491 = DEFINITIONAL_REPRESENTATION('',(#124492),#124496); +#124492 = LINE('',#124493,#124494); +#124493 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#124494 = VECTOR('',#124495,1.); +#124495 = DIRECTION('',(1.194699204908E-017,-1.)); +#124496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124497 = ORIENTED_EDGE('',*,*,#123795,.F.); +#124498 = ORIENTED_EDGE('',*,*,#123923,.F.); +#124499 = ORIENTED_EDGE('',*,*,#124185,.F.); +#124500 = ORIENTED_EDGE('',*,*,#124300,.F.); +#124501 = ORIENTED_EDGE('',*,*,#124502,.T.); +#124502 = EDGE_CURVE('',#124256,#92788,#124503,.T.); +#124503 = SURFACE_CURVE('',#124504,(#124508,#124515),.PCURVE_S1.); +#124504 = LINE('',#124505,#124506); +#124505 = CARTESIAN_POINT('',(-0.527847992439,8.85,0.75)); +#124506 = VECTOR('',#124507,1.); +#124507 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#124508 = PCURVE('',#92803,#124509); +#124509 = DEFINITIONAL_REPRESENTATION('',(#124510),#124514); +#124510 = LINE('',#124511,#124512); +#124511 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#124512 = VECTOR('',#124513,1.); +#124513 = DIRECTION('',(3.563627120235E-016,1.)); +#124514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124515 = PCURVE('',#92829,#124516); +#124516 = DEFINITIONAL_REPRESENTATION('',(#124517),#124521); +#124517 = LINE('',#124518,#124519); +#124518 = CARTESIAN_POINT('',(-1.110223024625E-016,0.2)); +#124519 = VECTOR('',#124520,1.); +#124520 = DIRECTION('',(1.,2.995851623787E-063)); +#124521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124522 = ORIENTED_EDGE('',*,*,#92787,.F.); +#124523 = ADVANCED_FACE('',(#124524),#92829,.T.); +#124524 = FACE_BOUND('',#124525,.T.); +#124525 = EDGE_LOOP('',(#124526,#124527,#124528,#124549)); +#124526 = ORIENTED_EDGE('',*,*,#124502,.F.); +#124527 = ORIENTED_EDGE('',*,*,#124255,.T.); +#124528 = ORIENTED_EDGE('',*,*,#124529,.T.); +#124529 = EDGE_CURVE('',#124233,#92725,#124530,.T.); +#124530 = SURFACE_CURVE('',#124531,(#124535,#124542),.PCURVE_S1.); +#124531 = LINE('',#124532,#124533); +#124532 = CARTESIAN_POINT('',(-0.527847992439,8.65,0.75)); +#124533 = VECTOR('',#124534,1.); +#124534 = DIRECTION('',(1.,0.E+000,3.563627120235E-016)); +#124535 = PCURVE('',#92829,#124536); +#124536 = DEFINITIONAL_REPRESENTATION('',(#124537),#124541); +#124537 = LINE('',#124538,#124539); +#124538 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124539 = VECTOR('',#124540,1.); +#124540 = DIRECTION('',(1.,2.995851623787E-063)); +#124541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124542 = PCURVE('',#92747,#124543); +#124543 = DEFINITIONAL_REPRESENTATION('',(#124544),#124548); +#124544 = LINE('',#124545,#124546); +#124545 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#124546 = VECTOR('',#124547,1.); +#124547 = DIRECTION('',(-3.563627120235E-016,1.)); +#124548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124549 = ORIENTED_EDGE('',*,*,#92815,.F.); +#124550 = ADVANCED_FACE('',(#124551),#92747,.T.); +#124551 = FACE_BOUND('',#124552,.T.); +#124552 = EDGE_LOOP('',(#124553,#124554,#124555,#124556,#124557,#124558, + #124579,#124580,#124581,#124582,#124583,#124584)); +#124553 = ORIENTED_EDGE('',*,*,#124529,.F.); +#124554 = ORIENTED_EDGE('',*,*,#124232,.T.); +#124555 = ORIENTED_EDGE('',*,*,#124207,.T.); +#124556 = ORIENTED_EDGE('',*,*,#123973,.T.); +#124557 = ORIENTED_EDGE('',*,*,#123745,.T.); +#124558 = ORIENTED_EDGE('',*,*,#124559,.F.); +#124559 = EDGE_CURVE('',#123822,#123711,#124560,.T.); +#124560 = SURFACE_CURVE('',#124561,(#124565,#124572),.PCURVE_S1.); +#124561 = LINE('',#124562,#124563); +#124562 = CARTESIAN_POINT('',(-1.,8.65,1.159810404338E-002)); +#124563 = VECTOR('',#124564,1.); +#124564 = DIRECTION('',(-2.101748079665E-016,1.194699204908E-017,1.)); +#124565 = PCURVE('',#92747,#124566); +#124566 = DEFINITIONAL_REPRESENTATION('',(#124567),#124571); +#124567 = LINE('',#124568,#124569); +#124568 = CARTESIAN_POINT('',(0.638401895957,-0.472152007561)); +#124569 = VECTOR('',#124570,1.); +#124570 = DIRECTION('',(-1.,-2.101748079665E-016)); +#124571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124572 = PCURVE('',#123733,#124573); +#124573 = DEFINITIONAL_REPRESENTATION('',(#124574),#124578); +#124574 = LINE('',#124575,#124576); +#124575 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#124576 = VECTOR('',#124577,1.); +#124577 = DIRECTION('',(-1.194699204908E-017,1.)); +#124578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124579 = ORIENTED_EDGE('',*,*,#123899,.F.); +#124580 = ORIENTED_EDGE('',*,*,#124002,.F.); +#124581 = ORIENTED_EDGE('',*,*,#124110,.F.); +#124582 = ORIENTED_EDGE('',*,*,#124329,.F.); +#124583 = ORIENTED_EDGE('',*,*,#124425,.T.); +#124584 = ORIENTED_EDGE('',*,*,#92724,.F.); +#124585 = ADVANCED_FACE('',(#124586),#123733,.T.); +#124586 = FACE_BOUND('',#124587,.T.); +#124587 = EDGE_LOOP('',(#124588,#124589,#124590,#124591)); +#124588 = ORIENTED_EDGE('',*,*,#124477,.T.); +#124589 = ORIENTED_EDGE('',*,*,#123819,.T.); +#124590 = ORIENTED_EDGE('',*,*,#124559,.T.); +#124591 = ORIENTED_EDGE('',*,*,#123710,.T.); +#124592 = ADVANCED_FACE('',(#124593),#124607,.F.); +#124593 = FACE_BOUND('',#124594,.T.); +#124594 = EDGE_LOOP('',(#124595,#124630,#124653,#124680)); +#124595 = ORIENTED_EDGE('',*,*,#124596,.F.); +#124596 = EDGE_CURVE('',#124597,#124599,#124601,.T.); +#124597 = VERTEX_POINT('',#124598); +#124598 = CARTESIAN_POINT('',(11.,8.65,-0.308197125857)); +#124599 = VERTEX_POINT('',#124600); +#124600 = CARTESIAN_POINT('',(11.,8.85,-0.308197125857)); +#124601 = SURFACE_CURVE('',#124602,(#124606,#124618),.PCURVE_S1.); +#124602 = LINE('',#124603,#124604); +#124603 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#124604 = VECTOR('',#124605,1.); +#124605 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124606 = PCURVE('',#124607,#124612); +#124607 = PLANE('',#124608); +#124608 = AXIS2_PLACEMENT_3D('',#124609,#124610,#124611); +#124609 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#122218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#122219 = DIRECTION('',(1.,0.E+000,0.E+000)); -#122220 = DEFINITIONAL_REPRESENTATION('',(#122221),#122225); -#122221 = LINE('',#122222,#122223); -#122222 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#122223 = VECTOR('',#122224,1.); -#122224 = DIRECTION('',(4.440892098501E-016,1.)); -#122225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122226 = PCURVE('',#122227,#122232); -#122227 = PLANE('',#122228); -#122228 = AXIS2_PLACEMENT_3D('',#122229,#122230,#122231); -#122229 = CARTESIAN_POINT('',(11.,8.75,-0.258196742327)); -#122230 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#122231 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122232 = DEFINITIONAL_REPRESENTATION('',(#122233),#122237); -#122233 = LINE('',#122234,#122235); -#122234 = CARTESIAN_POINT('',(-8.75,-5.000038352949E-002)); -#122235 = VECTOR('',#122236,1.); -#122236 = DIRECTION('',(1.,0.E+000)); -#122237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122238 = ORIENTED_EDGE('',*,*,#122239,.F.); -#122239 = EDGE_CURVE('',#122240,#122205,#122242,.T.); -#122240 = VERTEX_POINT('',#122241); -#122241 = CARTESIAN_POINT('',(10.74341632541,8.65,-0.308197125857)); -#122242 = SURFACE_CURVE('',#122243,(#122247,#122254),.PCURVE_S1.); -#122243 = LINE('',#122244,#122245); -#122244 = CARTESIAN_POINT('',(10.74341632541,8.65,-0.308197125857)); -#122245 = VECTOR('',#122246,1.); -#122246 = DIRECTION('',(1.,0.E+000,0.E+000)); -#122247 = PCURVE('',#122215,#122248); -#122248 = DEFINITIONAL_REPRESENTATION('',(#122249),#122253); -#122249 = LINE('',#122250,#122251); -#122250 = CARTESIAN_POINT('',(3.552713678801E-015,8.65)); -#122251 = VECTOR('',#122252,1.); -#122252 = DIRECTION('',(1.,0.E+000)); -#122253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122254 = PCURVE('',#94050,#122255); -#122255 = DEFINITIONAL_REPRESENTATION('',(#122256),#122260); -#122256 = LINE('',#122257,#122258); -#122257 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#122258 = VECTOR('',#122259,1.); -#122259 = DIRECTION('',(0.E+000,1.)); -#122260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122261 = ORIENTED_EDGE('',*,*,#122262,.F.); -#122262 = EDGE_CURVE('',#122263,#122240,#122265,.T.); -#122263 = VERTEX_POINT('',#122264); -#122264 = CARTESIAN_POINT('',(10.74341632541,8.85,-0.308197125857)); -#122265 = SURFACE_CURVE('',#122266,(#122270,#122277),.PCURVE_S1.); -#122266 = LINE('',#122267,#122268); -#122267 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#124610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#124611 = DIRECTION('',(1.,0.E+000,0.E+000)); +#124612 = DEFINITIONAL_REPRESENTATION('',(#124613),#124617); +#124613 = LINE('',#124614,#124615); +#124614 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#124615 = VECTOR('',#124616,1.); +#124616 = DIRECTION('',(4.440892098501E-016,1.)); +#124617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124618 = PCURVE('',#124619,#124624); +#124619 = PLANE('',#124620); +#124620 = AXIS2_PLACEMENT_3D('',#124621,#124622,#124623); +#124621 = CARTESIAN_POINT('',(11.,8.75,-0.258196742327)); +#124622 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#124623 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124624 = DEFINITIONAL_REPRESENTATION('',(#124625),#124629); +#124625 = LINE('',#124626,#124627); +#124626 = CARTESIAN_POINT('',(-8.75,-5.000038352949E-002)); +#124627 = VECTOR('',#124628,1.); +#124628 = DIRECTION('',(1.,0.E+000)); +#124629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124630 = ORIENTED_EDGE('',*,*,#124631,.F.); +#124631 = EDGE_CURVE('',#124632,#124597,#124634,.T.); +#124632 = VERTEX_POINT('',#124633); +#124633 = CARTESIAN_POINT('',(10.74341632541,8.65,-0.308197125857)); +#124634 = SURFACE_CURVE('',#124635,(#124639,#124646),.PCURVE_S1.); +#124635 = LINE('',#124636,#124637); +#124636 = CARTESIAN_POINT('',(10.74341632541,8.65,-0.308197125857)); +#124637 = VECTOR('',#124638,1.); +#124638 = DIRECTION('',(1.,0.E+000,0.E+000)); +#124639 = PCURVE('',#124607,#124640); +#124640 = DEFINITIONAL_REPRESENTATION('',(#124641),#124645); +#124641 = LINE('',#124642,#124643); +#124642 = CARTESIAN_POINT('',(3.552713678801E-015,8.65)); +#124643 = VECTOR('',#124644,1.); +#124644 = DIRECTION('',(1.,0.E+000)); +#124645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124646 = PCURVE('',#96442,#124647); +#124647 = DEFINITIONAL_REPRESENTATION('',(#124648),#124652); +#124648 = LINE('',#124649,#124650); +#124649 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#124650 = VECTOR('',#124651,1.); +#124651 = DIRECTION('',(0.E+000,1.)); +#124652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124653 = ORIENTED_EDGE('',*,*,#124654,.F.); +#124654 = EDGE_CURVE('',#124655,#124632,#124657,.T.); +#124655 = VERTEX_POINT('',#124656); +#124656 = CARTESIAN_POINT('',(10.74341632541,8.85,-0.308197125857)); +#124657 = SURFACE_CURVE('',#124658,(#124662,#124669),.PCURVE_S1.); +#124658 = LINE('',#124659,#124660); +#124659 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#122268 = VECTOR('',#122269,1.); -#122269 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122270 = PCURVE('',#122215,#122271); -#122271 = DEFINITIONAL_REPRESENTATION('',(#122272),#122276); -#122272 = LINE('',#122273,#122274); -#122273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122274 = VECTOR('',#122275,1.); -#122275 = DIRECTION('',(-4.440892098501E-016,-1.)); -#122276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122277 = PCURVE('',#122278,#122283); -#122278 = CYLINDRICAL_SURFACE('',#122279,0.308574064194); -#122279 = AXIS2_PLACEMENT_3D('',#122280,#122281,#122282); -#122280 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#124660 = VECTOR('',#124661,1.); +#124661 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124662 = PCURVE('',#124607,#124663); +#124663 = DEFINITIONAL_REPRESENTATION('',(#124664),#124668); +#124664 = LINE('',#124665,#124666); +#124665 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124666 = VECTOR('',#124667,1.); +#124667 = DIRECTION('',(-4.440892098501E-016,-1.)); +#124668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124669 = PCURVE('',#124670,#124675); +#124670 = CYLINDRICAL_SURFACE('',#124671,0.308574064194); +#124671 = AXIS2_PLACEMENT_3D('',#124672,#124673,#124674); +#124672 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#122281 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122282 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122283 = DEFINITIONAL_REPRESENTATION('',(#122284),#122287); -#122284 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122285,#122286), +#124673 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124674 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124675 = DEFINITIONAL_REPRESENTATION('',(#124676),#124679); +#124676 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124677,#124678), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#122285 = CARTESIAN_POINT('',(4.761821717947,-8.85)); -#122286 = CARTESIAN_POINT('',(4.761821717947,-8.65)); -#122287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122288 = ORIENTED_EDGE('',*,*,#122289,.T.); -#122289 = EDGE_CURVE('',#122263,#122207,#122290,.T.); -#122290 = SURFACE_CURVE('',#122291,(#122295,#122302),.PCURVE_S1.); -#122291 = LINE('',#122292,#122293); -#122292 = CARTESIAN_POINT('',(10.74341632541,8.85,-0.308197125857)); -#122293 = VECTOR('',#122294,1.); -#122294 = DIRECTION('',(1.,0.E+000,0.E+000)); -#122295 = PCURVE('',#122215,#122296); -#122296 = DEFINITIONAL_REPRESENTATION('',(#122297),#122301); -#122297 = LINE('',#122298,#122299); -#122298 = CARTESIAN_POINT('',(3.552713678801E-015,8.85)); -#122299 = VECTOR('',#122300,1.); -#122300 = DIRECTION('',(1.,0.E+000)); -#122301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122302 = PCURVE('',#93994,#122303); -#122303 = DEFINITIONAL_REPRESENTATION('',(#122304),#122308); -#122304 = LINE('',#122305,#122306); -#122305 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#122306 = VECTOR('',#122307,1.); -#122307 = DIRECTION('',(0.E+000,1.)); -#122308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122309 = ADVANCED_FACE('',(#122310),#122324,.F.); -#122310 = FACE_BOUND('',#122311,.T.); -#122311 = EDGE_LOOP('',(#122312,#122342,#122365,#122392)); -#122312 = ORIENTED_EDGE('',*,*,#122313,.F.); -#122313 = EDGE_CURVE('',#122314,#122316,#122318,.T.); -#122314 = VERTEX_POINT('',#122315); -#122315 = CARTESIAN_POINT('',(11.,8.85,-0.208196358798)); -#122316 = VERTEX_POINT('',#122317); -#122317 = CARTESIAN_POINT('',(11.,8.65,-0.208196358798)); -#122318 = SURFACE_CURVE('',#122319,(#122323,#122335),.PCURVE_S1.); -#122319 = LINE('',#122320,#122321); -#122320 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#122321 = VECTOR('',#122322,1.); -#122322 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122323 = PCURVE('',#122324,#122329); -#122324 = PLANE('',#122325); -#122325 = AXIS2_PLACEMENT_3D('',#122326,#122327,#122328); -#122326 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#124677 = CARTESIAN_POINT('',(4.761821717947,-8.85)); +#124678 = CARTESIAN_POINT('',(4.761821717947,-8.65)); +#124679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124680 = ORIENTED_EDGE('',*,*,#124681,.T.); +#124681 = EDGE_CURVE('',#124655,#124599,#124682,.T.); +#124682 = SURFACE_CURVE('',#124683,(#124687,#124694),.PCURVE_S1.); +#124683 = LINE('',#124684,#124685); +#124684 = CARTESIAN_POINT('',(10.74341632541,8.85,-0.308197125857)); +#124685 = VECTOR('',#124686,1.); +#124686 = DIRECTION('',(1.,0.E+000,0.E+000)); +#124687 = PCURVE('',#124607,#124688); +#124688 = DEFINITIONAL_REPRESENTATION('',(#124689),#124693); +#124689 = LINE('',#124690,#124691); +#124690 = CARTESIAN_POINT('',(3.552713678801E-015,8.85)); +#124691 = VECTOR('',#124692,1.); +#124692 = DIRECTION('',(1.,0.E+000)); +#124693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124694 = PCURVE('',#96386,#124695); +#124695 = DEFINITIONAL_REPRESENTATION('',(#124696),#124700); +#124696 = LINE('',#124697,#124698); +#124697 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#124698 = VECTOR('',#124699,1.); +#124699 = DIRECTION('',(0.E+000,1.)); +#124700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124701 = ADVANCED_FACE('',(#124702),#124716,.F.); +#124702 = FACE_BOUND('',#124703,.T.); +#124703 = EDGE_LOOP('',(#124704,#124734,#124757,#124784)); +#124704 = ORIENTED_EDGE('',*,*,#124705,.F.); +#124705 = EDGE_CURVE('',#124706,#124708,#124710,.T.); +#124706 = VERTEX_POINT('',#124707); +#124707 = CARTESIAN_POINT('',(11.,8.85,-0.208196358798)); +#124708 = VERTEX_POINT('',#124709); +#124709 = CARTESIAN_POINT('',(11.,8.65,-0.208196358798)); +#124710 = SURFACE_CURVE('',#124711,(#124715,#124727),.PCURVE_S1.); +#124711 = LINE('',#124712,#124713); +#124712 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#124713 = VECTOR('',#124714,1.); +#124714 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124715 = PCURVE('',#124716,#124721); +#124716 = PLANE('',#124717); +#124717 = AXIS2_PLACEMENT_3D('',#124718,#124719,#124720); +#124718 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#122327 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#122328 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#122329 = DEFINITIONAL_REPRESENTATION('',(#122330),#122334); -#122330 = LINE('',#122331,#122332); -#122331 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#122332 = VECTOR('',#122333,1.); -#122333 = DIRECTION('',(4.440892098501E-016,-1.)); -#122334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122335 = PCURVE('',#122227,#122336); -#122336 = DEFINITIONAL_REPRESENTATION('',(#122337),#122341); -#122337 = LINE('',#122338,#122339); -#122338 = CARTESIAN_POINT('',(-8.75,5.000038352949E-002)); -#122339 = VECTOR('',#122340,1.); -#122340 = DIRECTION('',(-1.,0.E+000)); -#122341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122342 = ORIENTED_EDGE('',*,*,#122343,.F.); -#122343 = EDGE_CURVE('',#122344,#122314,#122346,.T.); -#122344 = VERTEX_POINT('',#122345); -#122345 = CARTESIAN_POINT('',(10.740726081328,8.85,-0.208196358798)); -#122346 = SURFACE_CURVE('',#122347,(#122351,#122358),.PCURVE_S1.); -#122347 = LINE('',#122348,#122349); -#122348 = CARTESIAN_POINT('',(10.740726081328,8.85,-0.208196358798)); -#122349 = VECTOR('',#122350,1.); -#122350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#122351 = PCURVE('',#122324,#122352); -#122352 = DEFINITIONAL_REPRESENTATION('',(#122353),#122357); -#122353 = LINE('',#122354,#122355); -#122354 = CARTESIAN_POINT('',(-3.552713678801E-015,8.85)); -#122355 = VECTOR('',#122356,1.); -#122356 = DIRECTION('',(-1.,0.E+000)); -#122357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122358 = PCURVE('',#93994,#122359); -#122359 = DEFINITIONAL_REPRESENTATION('',(#122360),#122364); -#122360 = LINE('',#122361,#122362); -#122361 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#122362 = VECTOR('',#122363,1.); -#122363 = DIRECTION('',(0.E+000,1.)); -#122364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122365 = ORIENTED_EDGE('',*,*,#122366,.F.); -#122366 = EDGE_CURVE('',#122367,#122344,#122369,.T.); -#122367 = VERTEX_POINT('',#122368); -#122368 = CARTESIAN_POINT('',(10.740726081328,8.65,-0.208196358798)); -#122369 = SURFACE_CURVE('',#122370,(#122374,#122381),.PCURVE_S1.); -#122370 = LINE('',#122371,#122372); -#122371 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#124719 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#124720 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#124721 = DEFINITIONAL_REPRESENTATION('',(#124722),#124726); +#124722 = LINE('',#124723,#124724); +#124723 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#124724 = VECTOR('',#124725,1.); +#124725 = DIRECTION('',(4.440892098501E-016,-1.)); +#124726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124727 = PCURVE('',#124619,#124728); +#124728 = DEFINITIONAL_REPRESENTATION('',(#124729),#124733); +#124729 = LINE('',#124730,#124731); +#124730 = CARTESIAN_POINT('',(-8.75,5.000038352949E-002)); +#124731 = VECTOR('',#124732,1.); +#124732 = DIRECTION('',(-1.,0.E+000)); +#124733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124734 = ORIENTED_EDGE('',*,*,#124735,.F.); +#124735 = EDGE_CURVE('',#124736,#124706,#124738,.T.); +#124736 = VERTEX_POINT('',#124737); +#124737 = CARTESIAN_POINT('',(10.740726081328,8.85,-0.208196358798)); +#124738 = SURFACE_CURVE('',#124739,(#124743,#124750),.PCURVE_S1.); +#124739 = LINE('',#124740,#124741); +#124740 = CARTESIAN_POINT('',(10.740726081328,8.85,-0.208196358798)); +#124741 = VECTOR('',#124742,1.); +#124742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#124743 = PCURVE('',#124716,#124744); +#124744 = DEFINITIONAL_REPRESENTATION('',(#124745),#124749); +#124745 = LINE('',#124746,#124747); +#124746 = CARTESIAN_POINT('',(-3.552713678801E-015,8.85)); +#124747 = VECTOR('',#124748,1.); +#124748 = DIRECTION('',(-1.,0.E+000)); +#124749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124750 = PCURVE('',#96386,#124751); +#124751 = DEFINITIONAL_REPRESENTATION('',(#124752),#124756); +#124752 = LINE('',#124753,#124754); +#124753 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#124754 = VECTOR('',#124755,1.); +#124755 = DIRECTION('',(0.E+000,1.)); +#124756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124757 = ORIENTED_EDGE('',*,*,#124758,.F.); +#124758 = EDGE_CURVE('',#124759,#124736,#124761,.T.); +#124759 = VERTEX_POINT('',#124760); +#124760 = CARTESIAN_POINT('',(10.740726081328,8.65,-0.208196358798)); +#124761 = SURFACE_CURVE('',#124762,(#124766,#124773),.PCURVE_S1.); +#124762 = LINE('',#124763,#124764); +#124763 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#122372 = VECTOR('',#122373,1.); -#122373 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122374 = PCURVE('',#122324,#122375); -#122375 = DEFINITIONAL_REPRESENTATION('',(#122376),#122380); -#122376 = LINE('',#122377,#122378); -#122377 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122378 = VECTOR('',#122379,1.); -#122379 = DIRECTION('',(-4.440892098501E-016,1.)); -#122380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122381 = PCURVE('',#122382,#122387); -#122382 = CYLINDRICAL_SURFACE('',#122383,0.208574704164); -#122383 = AXIS2_PLACEMENT_3D('',#122384,#122385,#122386); -#122384 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#124764 = VECTOR('',#124765,1.); +#124765 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124766 = PCURVE('',#124716,#124767); +#124767 = DEFINITIONAL_REPRESENTATION('',(#124768),#124772); +#124768 = LINE('',#124769,#124770); +#124769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124770 = VECTOR('',#124771,1.); +#124771 = DIRECTION('',(-4.440892098501E-016,1.)); +#124772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124773 = PCURVE('',#124774,#124779); +#124774 = CYLINDRICAL_SURFACE('',#124775,0.208574704164); +#124775 = AXIS2_PLACEMENT_3D('',#124776,#124777,#124778); +#124776 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#122385 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122386 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122387 = DEFINITIONAL_REPRESENTATION('',(#122388),#122391); -#122388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122389,#122390), +#124777 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124778 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124779 = DEFINITIONAL_REPRESENTATION('',(#124780),#124783); +#124780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124781,#124782), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#122389 = CARTESIAN_POINT('',(4.772630242227,-8.65)); -#122390 = CARTESIAN_POINT('',(4.772630242227,-8.85)); -#122391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122392 = ORIENTED_EDGE('',*,*,#122393,.T.); -#122393 = EDGE_CURVE('',#122367,#122316,#122394,.T.); -#122394 = SURFACE_CURVE('',#122395,(#122399,#122406),.PCURVE_S1.); -#122395 = LINE('',#122396,#122397); -#122396 = CARTESIAN_POINT('',(10.740726081328,8.65,-0.208196358798)); -#122397 = VECTOR('',#122398,1.); -#122398 = DIRECTION('',(1.,0.E+000,0.E+000)); -#122399 = PCURVE('',#122324,#122400); -#122400 = DEFINITIONAL_REPRESENTATION('',(#122401),#122405); -#122401 = LINE('',#122402,#122403); -#122402 = CARTESIAN_POINT('',(-3.552713678801E-015,8.65)); -#122403 = VECTOR('',#122404,1.); -#122404 = DIRECTION('',(-1.,0.E+000)); -#122405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122406 = PCURVE('',#94050,#122407); -#122407 = DEFINITIONAL_REPRESENTATION('',(#122408),#122412); -#122408 = LINE('',#122409,#122410); -#122409 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#122410 = VECTOR('',#122411,1.); -#122411 = DIRECTION('',(0.E+000,1.)); -#122412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122413 = ADVANCED_FACE('',(#122414),#122278,.T.); -#122414 = FACE_BOUND('',#122415,.T.); -#122415 = EDGE_LOOP('',(#122416,#122443,#122444,#122467)); -#122416 = ORIENTED_EDGE('',*,*,#122417,.T.); -#122417 = EDGE_CURVE('',#122418,#122263,#122420,.T.); -#122418 = VERTEX_POINT('',#122419); -#122419 = CARTESIAN_POINT('',(10.419594812019,8.85,0.E+000)); -#122420 = SURFACE_CURVE('',#122421,(#122426,#122432),.PCURVE_S1.); -#122421 = CIRCLE('',#122422,0.308574064194); -#122422 = AXIS2_PLACEMENT_3D('',#122423,#122424,#122425); -#122423 = CARTESIAN_POINT('',(10.728168876214,8.85,2.640924866458E-017) - ); -#122424 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122425 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122426 = PCURVE('',#122278,#122427); -#122427 = DEFINITIONAL_REPRESENTATION('',(#122428),#122431); -#122428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122429,#122430), +#124781 = CARTESIAN_POINT('',(4.772630242227,-8.65)); +#124782 = CARTESIAN_POINT('',(4.772630242227,-8.85)); +#124783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124784 = ORIENTED_EDGE('',*,*,#124785,.T.); +#124785 = EDGE_CURVE('',#124759,#124708,#124786,.T.); +#124786 = SURFACE_CURVE('',#124787,(#124791,#124798),.PCURVE_S1.); +#124787 = LINE('',#124788,#124789); +#124788 = CARTESIAN_POINT('',(10.740726081328,8.65,-0.208196358798)); +#124789 = VECTOR('',#124790,1.); +#124790 = DIRECTION('',(1.,0.E+000,0.E+000)); +#124791 = PCURVE('',#124716,#124792); +#124792 = DEFINITIONAL_REPRESENTATION('',(#124793),#124797); +#124793 = LINE('',#124794,#124795); +#124794 = CARTESIAN_POINT('',(-3.552713678801E-015,8.65)); +#124795 = VECTOR('',#124796,1.); +#124796 = DIRECTION('',(-1.,0.E+000)); +#124797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124798 = PCURVE('',#96442,#124799); +#124799 = DEFINITIONAL_REPRESENTATION('',(#124800),#124804); +#124800 = LINE('',#124801,#124802); +#124801 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#124802 = VECTOR('',#124803,1.); +#124803 = DIRECTION('',(0.E+000,1.)); +#124804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124805 = ADVANCED_FACE('',(#124806),#124670,.T.); +#124806 = FACE_BOUND('',#124807,.T.); +#124807 = EDGE_LOOP('',(#124808,#124835,#124836,#124859)); +#124808 = ORIENTED_EDGE('',*,*,#124809,.T.); +#124809 = EDGE_CURVE('',#124810,#124655,#124812,.T.); +#124810 = VERTEX_POINT('',#124811); +#124811 = CARTESIAN_POINT('',(10.419594812019,8.85,0.E+000)); +#124812 = SURFACE_CURVE('',#124813,(#124818,#124824),.PCURVE_S1.); +#124813 = CIRCLE('',#124814,0.308574064194); +#124814 = AXIS2_PLACEMENT_3D('',#124815,#124816,#124817); +#124815 = CARTESIAN_POINT('',(10.728168876214,8.85,2.640924866458E-017) + ); +#124816 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124817 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124818 = PCURVE('',#124670,#124819); +#124819 = DEFINITIONAL_REPRESENTATION('',(#124820),#124823); +#124820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124821,#124822), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#122429 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#122430 = CARTESIAN_POINT('',(4.761821717947,-8.85)); -#122431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124821 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#124822 = CARTESIAN_POINT('',(4.761821717947,-8.85)); +#124823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122432 = PCURVE('',#93994,#122433); -#122433 = DEFINITIONAL_REPRESENTATION('',(#122434),#122442); -#122434 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122435,#122436,#122437, - #122438,#122439,#122440,#122441),.UNSPECIFIED.,.T.,.F.) +#124824 = PCURVE('',#96386,#124825); +#124825 = DEFINITIONAL_REPRESENTATION('',(#124826),#124834); +#124826 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124827,#124828,#124829, + #124830,#124831,#124832,#124833),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#122435 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#122436 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#122437 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#122438 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#122439 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#122440 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#122441 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#122442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122443 = ORIENTED_EDGE('',*,*,#122262,.T.); -#122444 = ORIENTED_EDGE('',*,*,#122445,.F.); -#122445 = EDGE_CURVE('',#122446,#122240,#122448,.T.); -#122446 = VERTEX_POINT('',#122447); -#122447 = CARTESIAN_POINT('',(10.419594812019,8.65,0.E+000)); -#122448 = SURFACE_CURVE('',#122449,(#122454,#122460),.PCURVE_S1.); -#122449 = CIRCLE('',#122450,0.308574064194); -#122450 = AXIS2_PLACEMENT_3D('',#122451,#122452,#122453); -#122451 = CARTESIAN_POINT('',(10.728168876214,8.65,2.640924866458E-017) - ); -#122452 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122453 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122454 = PCURVE('',#122278,#122455); -#122455 = DEFINITIONAL_REPRESENTATION('',(#122456),#122459); -#122456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122457,#122458), +#124827 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#124828 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#124829 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#124830 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#124831 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#124832 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#124833 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#124834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124835 = ORIENTED_EDGE('',*,*,#124654,.T.); +#124836 = ORIENTED_EDGE('',*,*,#124837,.F.); +#124837 = EDGE_CURVE('',#124838,#124632,#124840,.T.); +#124838 = VERTEX_POINT('',#124839); +#124839 = CARTESIAN_POINT('',(10.419594812019,8.65,0.E+000)); +#124840 = SURFACE_CURVE('',#124841,(#124846,#124852),.PCURVE_S1.); +#124841 = CIRCLE('',#124842,0.308574064194); +#124842 = AXIS2_PLACEMENT_3D('',#124843,#124844,#124845); +#124843 = CARTESIAN_POINT('',(10.728168876214,8.65,2.640924866458E-017) + ); +#124844 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124845 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124846 = PCURVE('',#124670,#124847); +#124847 = DEFINITIONAL_REPRESENTATION('',(#124848),#124851); +#124848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124849,#124850), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#122457 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#122458 = CARTESIAN_POINT('',(4.761821717947,-8.65)); -#122459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124849 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#124850 = CARTESIAN_POINT('',(4.761821717947,-8.65)); +#124851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122460 = PCURVE('',#94050,#122461); -#122461 = DEFINITIONAL_REPRESENTATION('',(#122462),#122466); -#122462 = CIRCLE('',#122463,0.308574064194); -#122463 = AXIS2_PLACEMENT_2D('',#122464,#122465); -#122464 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#122465 = DIRECTION('',(0.E+000,1.)); -#122466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124852 = PCURVE('',#96442,#124853); +#124853 = DEFINITIONAL_REPRESENTATION('',(#124854),#124858); +#124854 = CIRCLE('',#124855,0.308574064194); +#124855 = AXIS2_PLACEMENT_2D('',#124856,#124857); +#124856 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#124857 = DIRECTION('',(0.E+000,1.)); +#124858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122467 = ORIENTED_EDGE('',*,*,#122468,.T.); -#122468 = EDGE_CURVE('',#122446,#122418,#122469,.T.); -#122469 = SURFACE_CURVE('',#122470,(#122474,#122480),.PCURVE_S1.); -#122470 = LINE('',#122471,#122472); -#122471 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#124859 = ORIENTED_EDGE('',*,*,#124860,.T.); +#124860 = EDGE_CURVE('',#124838,#124810,#124861,.T.); +#124861 = SURFACE_CURVE('',#124862,(#124866,#124872),.PCURVE_S1.); +#124862 = LINE('',#124863,#124864); +#124863 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#122472 = VECTOR('',#122473,1.); -#122473 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122474 = PCURVE('',#122278,#122475); -#122475 = DEFINITIONAL_REPRESENTATION('',(#122476),#122479); -#122476 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122477,#122478), +#124864 = VECTOR('',#124865,1.); +#124865 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124866 = PCURVE('',#124670,#124867); +#124867 = DEFINITIONAL_REPRESENTATION('',(#124868),#124871); +#124868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124869,#124870), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#122477 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#122478 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#122479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124869 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#124870 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#124871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122480 = PCURVE('',#122481,#122486); -#122481 = PLANE('',#122482); -#122482 = AXIS2_PLACEMENT_3D('',#122483,#122484,#122485); -#122483 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#124872 = PCURVE('',#124873,#124878); +#124873 = PLANE('',#124874); +#124874 = AXIS2_PLACEMENT_3D('',#124875,#124876,#124877); +#124875 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#122484 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122485 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122486 = DEFINITIONAL_REPRESENTATION('',(#122487),#122491); -#122487 = LINE('',#122488,#122489); -#122488 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#122489 = VECTOR('',#122490,1.); -#122490 = DIRECTION('',(-1.,0.E+000)); -#122491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122492 = ADVANCED_FACE('',(#122493),#122382,.F.); -#122493 = FACE_BOUND('',#122494,.F.); -#122494 = EDGE_LOOP('',(#122495,#122518,#122545,#122570)); -#122495 = ORIENTED_EDGE('',*,*,#122496,.F.); -#122496 = EDGE_CURVE('',#122497,#122367,#122499,.T.); -#122497 = VERTEX_POINT('',#122498); -#122498 = CARTESIAN_POINT('',(10.51959417205,8.65,0.E+000)); -#122499 = SURFACE_CURVE('',#122500,(#122505,#122511),.PCURVE_S1.); -#122500 = CIRCLE('',#122501,0.208574704164); -#122501 = AXIS2_PLACEMENT_3D('',#122502,#122503,#122504); -#122502 = CARTESIAN_POINT('',(10.728168876214,8.65,2.640924866458E-017) - ); -#122503 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122504 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122505 = PCURVE('',#122382,#122506); -#122506 = DEFINITIONAL_REPRESENTATION('',(#122507),#122510); -#122507 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122508,#122509), +#124876 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#124877 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124878 = DEFINITIONAL_REPRESENTATION('',(#124879),#124883); +#124879 = LINE('',#124880,#124881); +#124880 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#124881 = VECTOR('',#124882,1.); +#124882 = DIRECTION('',(-1.,0.E+000)); +#124883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124884 = ADVANCED_FACE('',(#124885),#124774,.F.); +#124885 = FACE_BOUND('',#124886,.F.); +#124886 = EDGE_LOOP('',(#124887,#124910,#124937,#124962)); +#124887 = ORIENTED_EDGE('',*,*,#124888,.F.); +#124888 = EDGE_CURVE('',#124889,#124759,#124891,.T.); +#124889 = VERTEX_POINT('',#124890); +#124890 = CARTESIAN_POINT('',(10.51959417205,8.65,0.E+000)); +#124891 = SURFACE_CURVE('',#124892,(#124897,#124903),.PCURVE_S1.); +#124892 = CIRCLE('',#124893,0.208574704164); +#124893 = AXIS2_PLACEMENT_3D('',#124894,#124895,#124896); +#124894 = CARTESIAN_POINT('',(10.728168876214,8.65,2.640924866458E-017) + ); +#124895 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124896 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124897 = PCURVE('',#124774,#124898); +#124898 = DEFINITIONAL_REPRESENTATION('',(#124899),#124902); +#124899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124900,#124901), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#122508 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#122509 = CARTESIAN_POINT('',(4.772630242227,-8.65)); -#122510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124900 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#124901 = CARTESIAN_POINT('',(4.772630242227,-8.65)); +#124902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122511 = PCURVE('',#94050,#122512); -#122512 = DEFINITIONAL_REPRESENTATION('',(#122513),#122517); -#122513 = CIRCLE('',#122514,0.208574704164); -#122514 = AXIS2_PLACEMENT_2D('',#122515,#122516); -#122515 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#122516 = DIRECTION('',(0.E+000,1.)); -#122517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124903 = PCURVE('',#96442,#124904); +#124904 = DEFINITIONAL_REPRESENTATION('',(#124905),#124909); +#124905 = CIRCLE('',#124906,0.208574704164); +#124906 = AXIS2_PLACEMENT_2D('',#124907,#124908); +#124907 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#124908 = DIRECTION('',(0.E+000,1.)); +#124909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122518 = ORIENTED_EDGE('',*,*,#122519,.F.); -#122519 = EDGE_CURVE('',#122520,#122497,#122522,.T.); -#122520 = VERTEX_POINT('',#122521); -#122521 = CARTESIAN_POINT('',(10.51959417205,8.85,0.E+000)); -#122522 = SURFACE_CURVE('',#122523,(#122527,#122533),.PCURVE_S1.); -#122523 = LINE('',#122524,#122525); -#122524 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#124910 = ORIENTED_EDGE('',*,*,#124911,.F.); +#124911 = EDGE_CURVE('',#124912,#124889,#124914,.T.); +#124912 = VERTEX_POINT('',#124913); +#124913 = CARTESIAN_POINT('',(10.51959417205,8.85,0.E+000)); +#124914 = SURFACE_CURVE('',#124915,(#124919,#124925),.PCURVE_S1.); +#124915 = LINE('',#124916,#124917); +#124916 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#122525 = VECTOR('',#122526,1.); -#122526 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122527 = PCURVE('',#122382,#122528); -#122528 = DEFINITIONAL_REPRESENTATION('',(#122529),#122532); -#122529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122530,#122531), +#124917 = VECTOR('',#124918,1.); +#124918 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124919 = PCURVE('',#124774,#124920); +#124920 = DEFINITIONAL_REPRESENTATION('',(#124921),#124924); +#124921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124922,#124923), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#122530 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#122531 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#122532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124922 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#124923 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#124924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122533 = PCURVE('',#122534,#122539); -#122534 = PLANE('',#122535); -#122535 = AXIS2_PLACEMENT_3D('',#122536,#122537,#122538); -#122536 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#124925 = PCURVE('',#124926,#124931); +#124926 = PLANE('',#124927); +#124927 = AXIS2_PLACEMENT_3D('',#124928,#124929,#124930); +#124928 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#122537 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122538 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122539 = DEFINITIONAL_REPRESENTATION('',(#122540),#122544); -#122540 = LINE('',#122541,#122542); -#122541 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#122542 = VECTOR('',#122543,1.); -#122543 = DIRECTION('',(-1.,0.E+000)); -#122544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122545 = ORIENTED_EDGE('',*,*,#122546,.T.); -#122546 = EDGE_CURVE('',#122520,#122344,#122547,.T.); -#122547 = SURFACE_CURVE('',#122548,(#122553,#122559),.PCURVE_S1.); -#122548 = CIRCLE('',#122549,0.208574704164); -#122549 = AXIS2_PLACEMENT_3D('',#122550,#122551,#122552); -#122550 = CARTESIAN_POINT('',(10.728168876214,8.85,2.640924866458E-017) - ); -#122551 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122552 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#122553 = PCURVE('',#122382,#122554); -#122554 = DEFINITIONAL_REPRESENTATION('',(#122555),#122558); -#122555 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122556,#122557), +#124929 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124930 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124931 = DEFINITIONAL_REPRESENTATION('',(#124932),#124936); +#124932 = LINE('',#124933,#124934); +#124933 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#124934 = VECTOR('',#124935,1.); +#124935 = DIRECTION('',(-1.,0.E+000)); +#124936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124937 = ORIENTED_EDGE('',*,*,#124938,.T.); +#124938 = EDGE_CURVE('',#124912,#124736,#124939,.T.); +#124939 = SURFACE_CURVE('',#124940,(#124945,#124951),.PCURVE_S1.); +#124940 = CIRCLE('',#124941,0.208574704164); +#124941 = AXIS2_PLACEMENT_3D('',#124942,#124943,#124944); +#124942 = CARTESIAN_POINT('',(10.728168876214,8.85,2.640924866458E-017) + ); +#124943 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124944 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#124945 = PCURVE('',#124774,#124946); +#124946 = DEFINITIONAL_REPRESENTATION('',(#124947),#124950); +#124947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124948,#124949), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#122556 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#122557 = CARTESIAN_POINT('',(4.772630242227,-8.85)); -#122558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124948 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#124949 = CARTESIAN_POINT('',(4.772630242227,-8.85)); +#124950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122559 = PCURVE('',#93994,#122560); -#122560 = DEFINITIONAL_REPRESENTATION('',(#122561),#122569); -#122561 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122562,#122563,#122564, - #122565,#122566,#122567,#122568),.UNSPECIFIED.,.T.,.F.) +#124951 = PCURVE('',#96386,#124952); +#124952 = DEFINITIONAL_REPRESENTATION('',(#124953),#124961); +#124953 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124954,#124955,#124956, + #124957,#124958,#124959,#124960),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#122562 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#122563 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#122564 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#122565 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#122566 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#122567 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#122568 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#122569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122570 = ORIENTED_EDGE('',*,*,#122366,.F.); -#122571 = ADVANCED_FACE('',(#122572),#122534,.T.); -#122572 = FACE_BOUND('',#122573,.T.); -#122573 = EDGE_LOOP('',(#122574,#122603,#122624,#122625)); -#122574 = ORIENTED_EDGE('',*,*,#122575,.T.); -#122575 = EDGE_CURVE('',#122576,#122578,#122580,.T.); -#122576 = VERTEX_POINT('',#122577); -#122577 = CARTESIAN_POINT('',(10.51959417205,8.85,0.530776333563)); -#122578 = VERTEX_POINT('',#122579); -#122579 = CARTESIAN_POINT('',(10.51959417205,8.65,0.530776333563)); -#122580 = SURFACE_CURVE('',#122581,(#122585,#122592),.PCURVE_S1.); -#122581 = LINE('',#122582,#122583); -#122582 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#124954 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#124955 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#124956 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#124957 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#124958 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#124959 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#124960 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#124961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124962 = ORIENTED_EDGE('',*,*,#124758,.F.); +#124963 = ADVANCED_FACE('',(#124964),#124926,.T.); +#124964 = FACE_BOUND('',#124965,.T.); +#124965 = EDGE_LOOP('',(#124966,#124995,#125016,#125017)); +#124966 = ORIENTED_EDGE('',*,*,#124967,.T.); +#124967 = EDGE_CURVE('',#124968,#124970,#124972,.T.); +#124968 = VERTEX_POINT('',#124969); +#124969 = CARTESIAN_POINT('',(10.51959417205,8.85,0.530776333563)); +#124970 = VERTEX_POINT('',#124971); +#124971 = CARTESIAN_POINT('',(10.51959417205,8.65,0.530776333563)); +#124972 = SURFACE_CURVE('',#124973,(#124977,#124984),.PCURVE_S1.); +#124973 = LINE('',#124974,#124975); +#124974 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#122583 = VECTOR('',#122584,1.); -#122584 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122585 = PCURVE('',#122534,#122586); -#122586 = DEFINITIONAL_REPRESENTATION('',(#122587),#122591); -#122587 = LINE('',#122588,#122589); -#122588 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122589 = VECTOR('',#122590,1.); -#122590 = DIRECTION('',(-1.,0.E+000)); -#122591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122592 = PCURVE('',#122593,#122598); -#122593 = CYLINDRICAL_SURFACE('',#122594,0.2192697516); -#122594 = AXIS2_PLACEMENT_3D('',#122595,#122596,#122597); -#122595 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#124975 = VECTOR('',#124976,1.); +#124976 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#124977 = PCURVE('',#124926,#124978); +#124978 = DEFINITIONAL_REPRESENTATION('',(#124979),#124983); +#124979 = LINE('',#124980,#124981); +#124980 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#124981 = VECTOR('',#124982,1.); +#124982 = DIRECTION('',(-1.,0.E+000)); +#124983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124984 = PCURVE('',#124985,#124990); +#124985 = CYLINDRICAL_SURFACE('',#124986,0.2192697516); +#124986 = AXIS2_PLACEMENT_3D('',#124987,#124988,#124989); +#124987 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#122596 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122597 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122598 = DEFINITIONAL_REPRESENTATION('',(#122599),#122602); -#122599 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122600,#122601), +#124988 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#124989 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#124990 = DEFINITIONAL_REPRESENTATION('',(#124991),#124994); +#124991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124992,#124993), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#122600 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#122601 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#122602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122603 = ORIENTED_EDGE('',*,*,#122604,.T.); -#122604 = EDGE_CURVE('',#122578,#122497,#122605,.T.); -#122605 = SURFACE_CURVE('',#122606,(#122610,#122617),.PCURVE_S1.); -#122606 = LINE('',#122607,#122608); -#122607 = CARTESIAN_POINT('',(10.51959417205,8.65,0.530776333563)); -#122608 = VECTOR('',#122609,1.); -#122609 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#122610 = PCURVE('',#122534,#122611); -#122611 = DEFINITIONAL_REPRESENTATION('',(#122612),#122616); -#122612 = LINE('',#122613,#122614); -#122613 = CARTESIAN_POINT('',(8.65,0.E+000)); -#122614 = VECTOR('',#122615,1.); -#122615 = DIRECTION('',(0.E+000,-1.)); -#122616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#124992 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#124993 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#124994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#124995 = ORIENTED_EDGE('',*,*,#124996,.T.); +#124996 = EDGE_CURVE('',#124970,#124889,#124997,.T.); +#124997 = SURFACE_CURVE('',#124998,(#125002,#125009),.PCURVE_S1.); +#124998 = LINE('',#124999,#125000); +#124999 = CARTESIAN_POINT('',(10.51959417205,8.65,0.530776333563)); +#125000 = VECTOR('',#125001,1.); +#125001 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125002 = PCURVE('',#124926,#125003); +#125003 = DEFINITIONAL_REPRESENTATION('',(#125004),#125008); +#125004 = LINE('',#125005,#125006); +#125005 = CARTESIAN_POINT('',(8.65,0.E+000)); +#125006 = VECTOR('',#125007,1.); +#125007 = DIRECTION('',(0.E+000,-1.)); +#125008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125009 = PCURVE('',#96442,#125010); +#125010 = DEFINITIONAL_REPRESENTATION('',(#125011),#125015); +#125011 = LINE('',#125012,#125013); +#125012 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#125013 = VECTOR('',#125014,1.); +#125014 = DIRECTION('',(1.,0.E+000)); +#125015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125016 = ORIENTED_EDGE('',*,*,#124911,.F.); +#125017 = ORIENTED_EDGE('',*,*,#125018,.F.); +#125018 = EDGE_CURVE('',#124968,#124912,#125019,.T.); +#125019 = SURFACE_CURVE('',#125020,(#125024,#125031),.PCURVE_S1.); +#125020 = LINE('',#125021,#125022); +#125021 = CARTESIAN_POINT('',(10.51959417205,8.85,0.530776333563)); +#125022 = VECTOR('',#125023,1.); +#125023 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125024 = PCURVE('',#124926,#125025); +#125025 = DEFINITIONAL_REPRESENTATION('',(#125026),#125030); +#125026 = LINE('',#125027,#125028); +#125027 = CARTESIAN_POINT('',(8.85,0.E+000)); +#125028 = VECTOR('',#125029,1.); +#125029 = DIRECTION('',(0.E+000,-1.)); +#125030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122617 = PCURVE('',#94050,#122618); -#122618 = DEFINITIONAL_REPRESENTATION('',(#122619),#122623); -#122619 = LINE('',#122620,#122621); -#122620 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#122621 = VECTOR('',#122622,1.); -#122622 = DIRECTION('',(1.,0.E+000)); -#122623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125031 = PCURVE('',#96386,#125032); +#125032 = DEFINITIONAL_REPRESENTATION('',(#125033),#125037); +#125033 = LINE('',#125034,#125035); +#125034 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#125035 = VECTOR('',#125036,1.); +#125036 = DIRECTION('',(-1.,0.E+000)); +#125037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122624 = ORIENTED_EDGE('',*,*,#122519,.F.); -#122625 = ORIENTED_EDGE('',*,*,#122626,.F.); -#122626 = EDGE_CURVE('',#122576,#122520,#122627,.T.); -#122627 = SURFACE_CURVE('',#122628,(#122632,#122639),.PCURVE_S1.); -#122628 = LINE('',#122629,#122630); -#122629 = CARTESIAN_POINT('',(10.51959417205,8.85,0.530776333563)); -#122630 = VECTOR('',#122631,1.); -#122631 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#122632 = PCURVE('',#122534,#122633); -#122633 = DEFINITIONAL_REPRESENTATION('',(#122634),#122638); -#122634 = LINE('',#122635,#122636); -#122635 = CARTESIAN_POINT('',(8.85,0.E+000)); -#122636 = VECTOR('',#122637,1.); -#122637 = DIRECTION('',(0.E+000,-1.)); -#122638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122639 = PCURVE('',#93994,#122640); -#122640 = DEFINITIONAL_REPRESENTATION('',(#122641),#122645); -#122641 = LINE('',#122642,#122643); -#122642 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#122643 = VECTOR('',#122644,1.); -#122644 = DIRECTION('',(-1.,0.E+000)); -#122645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122646 = ADVANCED_FACE('',(#122647),#122481,.T.); -#122647 = FACE_BOUND('',#122648,.T.); -#122648 = EDGE_LOOP('',(#122649,#122678,#122699,#122700)); -#122649 = ORIENTED_EDGE('',*,*,#122650,.T.); -#122650 = EDGE_CURVE('',#122651,#122653,#122655,.T.); -#122651 = VERTEX_POINT('',#122652); -#122652 = CARTESIAN_POINT('',(10.419594812019,8.65,0.530776333563)); -#122653 = VERTEX_POINT('',#122654); -#122654 = CARTESIAN_POINT('',(10.419594812019,8.85,0.530776333563)); -#122655 = SURFACE_CURVE('',#122656,(#122660,#122667),.PCURVE_S1.); -#122656 = LINE('',#122657,#122658); -#122657 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#125038 = ADVANCED_FACE('',(#125039),#124873,.T.); +#125039 = FACE_BOUND('',#125040,.T.); +#125040 = EDGE_LOOP('',(#125041,#125070,#125091,#125092)); +#125041 = ORIENTED_EDGE('',*,*,#125042,.T.); +#125042 = EDGE_CURVE('',#125043,#125045,#125047,.T.); +#125043 = VERTEX_POINT('',#125044); +#125044 = CARTESIAN_POINT('',(10.419594812019,8.65,0.530776333563)); +#125045 = VERTEX_POINT('',#125046); +#125046 = CARTESIAN_POINT('',(10.419594812019,8.85,0.530776333563)); +#125047 = SURFACE_CURVE('',#125048,(#125052,#125059),.PCURVE_S1.); +#125048 = LINE('',#125049,#125050); +#125049 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#122658 = VECTOR('',#122659,1.); -#122659 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122660 = PCURVE('',#122481,#122661); -#122661 = DEFINITIONAL_REPRESENTATION('',(#122662),#122666); -#122662 = LINE('',#122663,#122664); -#122663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122664 = VECTOR('',#122665,1.); -#122665 = DIRECTION('',(-1.,0.E+000)); -#122666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122667 = PCURVE('',#122668,#122673); -#122668 = CYLINDRICAL_SURFACE('',#122669,0.119270391569); -#122669 = AXIS2_PLACEMENT_3D('',#122670,#122671,#122672); -#122670 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#125050 = VECTOR('',#125051,1.); +#125051 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125052 = PCURVE('',#124873,#125053); +#125053 = DEFINITIONAL_REPRESENTATION('',(#125054),#125058); +#125054 = LINE('',#125055,#125056); +#125055 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125056 = VECTOR('',#125057,1.); +#125057 = DIRECTION('',(-1.,0.E+000)); +#125058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125059 = PCURVE('',#125060,#125065); +#125060 = CYLINDRICAL_SURFACE('',#125061,0.119270391569); +#125061 = AXIS2_PLACEMENT_3D('',#125062,#125063,#125064); +#125062 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#122671 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122672 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122673 = DEFINITIONAL_REPRESENTATION('',(#122674),#122677); -#122674 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122675,#122676), +#125063 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125064 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125065 = DEFINITIONAL_REPRESENTATION('',(#125066),#125069); +#125066 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125067,#125068), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#122675 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#122676 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#122677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122678 = ORIENTED_EDGE('',*,*,#122679,.T.); -#122679 = EDGE_CURVE('',#122653,#122418,#122680,.T.); -#122680 = SURFACE_CURVE('',#122681,(#122685,#122692),.PCURVE_S1.); -#122681 = LINE('',#122682,#122683); -#122682 = CARTESIAN_POINT('',(10.419594812019,8.85,0.530776333563)); -#122683 = VECTOR('',#122684,1.); -#122684 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#122685 = PCURVE('',#122481,#122686); -#122686 = DEFINITIONAL_REPRESENTATION('',(#122687),#122691); -#122687 = LINE('',#122688,#122689); -#122688 = CARTESIAN_POINT('',(-8.85,0.E+000)); -#122689 = VECTOR('',#122690,1.); -#122690 = DIRECTION('',(0.E+000,-1.)); -#122691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122692 = PCURVE('',#93994,#122693); -#122693 = DEFINITIONAL_REPRESENTATION('',(#122694),#122698); -#122694 = LINE('',#122695,#122696); -#122695 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#122696 = VECTOR('',#122697,1.); -#122697 = DIRECTION('',(-1.,0.E+000)); -#122698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122699 = ORIENTED_EDGE('',*,*,#122468,.F.); -#122700 = ORIENTED_EDGE('',*,*,#122701,.F.); -#122701 = EDGE_CURVE('',#122651,#122446,#122702,.T.); -#122702 = SURFACE_CURVE('',#122703,(#122707,#122714),.PCURVE_S1.); -#122703 = LINE('',#122704,#122705); -#122704 = CARTESIAN_POINT('',(10.419594812019,8.65,0.530776333563)); -#122705 = VECTOR('',#122706,1.); -#122706 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#122707 = PCURVE('',#122481,#122708); -#122708 = DEFINITIONAL_REPRESENTATION('',(#122709),#122713); -#122709 = LINE('',#122710,#122711); -#122710 = CARTESIAN_POINT('',(-8.65,0.E+000)); -#122711 = VECTOR('',#122712,1.); -#122712 = DIRECTION('',(0.E+000,-1.)); -#122713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122714 = PCURVE('',#94050,#122715); -#122715 = DEFINITIONAL_REPRESENTATION('',(#122716),#122720); -#122716 = LINE('',#122717,#122718); -#122717 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#122718 = VECTOR('',#122719,1.); -#122719 = DIRECTION('',(1.,0.E+000)); -#122720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122721 = ADVANCED_FACE('',(#122722),#122668,.F.); -#122722 = FACE_BOUND('',#122723,.F.); -#122723 = EDGE_LOOP('',(#122724,#122725,#122748,#122770)); -#122724 = ORIENTED_EDGE('',*,*,#122650,.T.); -#122725 = ORIENTED_EDGE('',*,*,#122726,.F.); -#122726 = EDGE_CURVE('',#122727,#122653,#122729,.T.); -#122727 = VERTEX_POINT('',#122728); -#122728 = CARTESIAN_POINT('',(10.303662633502,8.85,0.65)); -#122729 = SURFACE_CURVE('',#122730,(#122735,#122741),.PCURVE_S1.); -#122730 = CIRCLE('',#122731,0.119270391569); -#122731 = AXIS2_PLACEMENT_3D('',#122732,#122733,#122734); -#122732 = CARTESIAN_POINT('',(10.30032442045,8.85,0.530776333563)); -#122733 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122734 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122735 = PCURVE('',#122668,#122736); -#122736 = DEFINITIONAL_REPRESENTATION('',(#122737),#122740); -#122737 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122738,#122739), +#125067 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#125068 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#125069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125070 = ORIENTED_EDGE('',*,*,#125071,.T.); +#125071 = EDGE_CURVE('',#125045,#124810,#125072,.T.); +#125072 = SURFACE_CURVE('',#125073,(#125077,#125084),.PCURVE_S1.); +#125073 = LINE('',#125074,#125075); +#125074 = CARTESIAN_POINT('',(10.419594812019,8.85,0.530776333563)); +#125075 = VECTOR('',#125076,1.); +#125076 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125077 = PCURVE('',#124873,#125078); +#125078 = DEFINITIONAL_REPRESENTATION('',(#125079),#125083); +#125079 = LINE('',#125080,#125081); +#125080 = CARTESIAN_POINT('',(-8.85,0.E+000)); +#125081 = VECTOR('',#125082,1.); +#125082 = DIRECTION('',(0.E+000,-1.)); +#125083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125084 = PCURVE('',#96386,#125085); +#125085 = DEFINITIONAL_REPRESENTATION('',(#125086),#125090); +#125086 = LINE('',#125087,#125088); +#125087 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#125088 = VECTOR('',#125089,1.); +#125089 = DIRECTION('',(-1.,0.E+000)); +#125090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125091 = ORIENTED_EDGE('',*,*,#124860,.F.); +#125092 = ORIENTED_EDGE('',*,*,#125093,.F.); +#125093 = EDGE_CURVE('',#125043,#124838,#125094,.T.); +#125094 = SURFACE_CURVE('',#125095,(#125099,#125106),.PCURVE_S1.); +#125095 = LINE('',#125096,#125097); +#125096 = CARTESIAN_POINT('',(10.419594812019,8.65,0.530776333563)); +#125097 = VECTOR('',#125098,1.); +#125098 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125099 = PCURVE('',#124873,#125100); +#125100 = DEFINITIONAL_REPRESENTATION('',(#125101),#125105); +#125101 = LINE('',#125102,#125103); +#125102 = CARTESIAN_POINT('',(-8.65,0.E+000)); +#125103 = VECTOR('',#125104,1.); +#125104 = DIRECTION('',(0.E+000,-1.)); +#125105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125106 = PCURVE('',#96442,#125107); +#125107 = DEFINITIONAL_REPRESENTATION('',(#125108),#125112); +#125108 = LINE('',#125109,#125110); +#125109 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#125110 = VECTOR('',#125111,1.); +#125111 = DIRECTION('',(1.,0.E+000)); +#125112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125113 = ADVANCED_FACE('',(#125114),#125060,.F.); +#125114 = FACE_BOUND('',#125115,.F.); +#125115 = EDGE_LOOP('',(#125116,#125117,#125140,#125162)); +#125116 = ORIENTED_EDGE('',*,*,#125042,.T.); +#125117 = ORIENTED_EDGE('',*,*,#125118,.F.); +#125118 = EDGE_CURVE('',#125119,#125045,#125121,.T.); +#125119 = VERTEX_POINT('',#125120); +#125120 = CARTESIAN_POINT('',(10.303662633502,8.85,0.65)); +#125121 = SURFACE_CURVE('',#125122,(#125127,#125133),.PCURVE_S1.); +#125122 = CIRCLE('',#125123,0.119270391569); +#125123 = AXIS2_PLACEMENT_3D('',#125124,#125125,#125126); +#125124 = CARTESIAN_POINT('',(10.30032442045,8.85,0.530776333563)); +#125125 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125126 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125127 = PCURVE('',#125060,#125128); +#125128 = DEFINITIONAL_REPRESENTATION('',(#125129),#125132); +#125129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125130,#125131), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#122738 = CARTESIAN_POINT('',(1.598788597134,8.85)); -#122739 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#122740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122741 = PCURVE('',#93994,#122742); -#122742 = DEFINITIONAL_REPRESENTATION('',(#122743),#122747); -#122743 = CIRCLE('',#122744,0.119270391569); -#122744 = AXIS2_PLACEMENT_2D('',#122745,#122746); -#122745 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#122746 = DIRECTION('',(0.E+000,-1.)); -#122747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122748 = ORIENTED_EDGE('',*,*,#122749,.T.); -#122749 = EDGE_CURVE('',#122727,#122750,#122752,.T.); -#122750 = VERTEX_POINT('',#122751); -#122751 = CARTESIAN_POINT('',(10.303662633502,8.65,0.65)); -#122752 = SURFACE_CURVE('',#122753,(#122757,#122763),.PCURVE_S1.); -#122753 = LINE('',#122754,#122755); -#122754 = CARTESIAN_POINT('',(10.303662633502,8.65,0.65)); -#122755 = VECTOR('',#122756,1.); -#122756 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#122757 = PCURVE('',#122668,#122758); -#122758 = DEFINITIONAL_REPRESENTATION('',(#122759),#122762); -#122759 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122760,#122761), +#125130 = CARTESIAN_POINT('',(1.598788597134,8.85)); +#125131 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#125132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125133 = PCURVE('',#96386,#125134); +#125134 = DEFINITIONAL_REPRESENTATION('',(#125135),#125139); +#125135 = CIRCLE('',#125136,0.119270391569); +#125136 = AXIS2_PLACEMENT_2D('',#125137,#125138); +#125137 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#125138 = DIRECTION('',(0.E+000,-1.)); +#125139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125140 = ORIENTED_EDGE('',*,*,#125141,.T.); +#125141 = EDGE_CURVE('',#125119,#125142,#125144,.T.); +#125142 = VERTEX_POINT('',#125143); +#125143 = CARTESIAN_POINT('',(10.303662633502,8.65,0.65)); +#125144 = SURFACE_CURVE('',#125145,(#125149,#125155),.PCURVE_S1.); +#125145 = LINE('',#125146,#125147); +#125146 = CARTESIAN_POINT('',(10.303662633502,8.65,0.65)); +#125147 = VECTOR('',#125148,1.); +#125148 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125149 = PCURVE('',#125060,#125150); +#125150 = DEFINITIONAL_REPRESENTATION('',(#125151),#125154); +#125151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125152,#125153), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#122760 = CARTESIAN_POINT('',(1.598788597134,8.85)); -#122761 = CARTESIAN_POINT('',(1.598788597134,8.65)); -#122762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122763 = PCURVE('',#94022,#122764); -#122764 = DEFINITIONAL_REPRESENTATION('',(#122765),#122769); -#122765 = LINE('',#122766,#122767); -#122766 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#122767 = VECTOR('',#122768,1.); -#122768 = DIRECTION('',(4.440892098501E-016,-1.)); -#122769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122770 = ORIENTED_EDGE('',*,*,#122771,.T.); -#122771 = EDGE_CURVE('',#122750,#122651,#122772,.T.); -#122772 = SURFACE_CURVE('',#122773,(#122778,#122784),.PCURVE_S1.); -#122773 = CIRCLE('',#122774,0.119270391569); -#122774 = AXIS2_PLACEMENT_3D('',#122775,#122776,#122777); -#122775 = CARTESIAN_POINT('',(10.30032442045,8.65,0.530776333563)); -#122776 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122777 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122778 = PCURVE('',#122668,#122779); -#122779 = DEFINITIONAL_REPRESENTATION('',(#122780),#122783); -#122780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122781,#122782), +#125152 = CARTESIAN_POINT('',(1.598788597134,8.85)); +#125153 = CARTESIAN_POINT('',(1.598788597134,8.65)); +#125154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125155 = PCURVE('',#96414,#125156); +#125156 = DEFINITIONAL_REPRESENTATION('',(#125157),#125161); +#125157 = LINE('',#125158,#125159); +#125158 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#125159 = VECTOR('',#125160,1.); +#125160 = DIRECTION('',(4.440892098501E-016,-1.)); +#125161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125162 = ORIENTED_EDGE('',*,*,#125163,.T.); +#125163 = EDGE_CURVE('',#125142,#125043,#125164,.T.); +#125164 = SURFACE_CURVE('',#125165,(#125170,#125176),.PCURVE_S1.); +#125165 = CIRCLE('',#125166,0.119270391569); +#125166 = AXIS2_PLACEMENT_3D('',#125167,#125168,#125169); +#125167 = CARTESIAN_POINT('',(10.30032442045,8.65,0.530776333563)); +#125168 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125169 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125170 = PCURVE('',#125060,#125171); +#125171 = DEFINITIONAL_REPRESENTATION('',(#125172),#125175); +#125172 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125173,#125174), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#122781 = CARTESIAN_POINT('',(1.598788597134,8.65)); -#122782 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#122783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125173 = CARTESIAN_POINT('',(1.598788597134,8.65)); +#125174 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#125175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122784 = PCURVE('',#94050,#122785); -#122785 = DEFINITIONAL_REPRESENTATION('',(#122786),#122794); -#122786 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122787,#122788,#122789, - #122790,#122791,#122792,#122793),.UNSPECIFIED.,.T.,.F.) +#125176 = PCURVE('',#96442,#125177); +#125177 = DEFINITIONAL_REPRESENTATION('',(#125178),#125186); +#125178 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125179,#125180,#125181, + #125182,#125183,#125184,#125185),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#122787 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#122788 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#122789 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#122790 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#122791 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#122792 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#122793 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#122794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122795 = ADVANCED_FACE('',(#122796),#122593,.T.); -#122796 = FACE_BOUND('',#122797,.T.); -#122797 = EDGE_LOOP('',(#122798,#122799,#122822,#122844)); -#122798 = ORIENTED_EDGE('',*,*,#122575,.F.); -#122799 = ORIENTED_EDGE('',*,*,#122800,.F.); -#122800 = EDGE_CURVE('',#122801,#122576,#122803,.T.); -#122801 = VERTEX_POINT('',#122802); -#122802 = CARTESIAN_POINT('',(10.304819755875,8.85,0.75)); -#122803 = SURFACE_CURVE('',#122804,(#122809,#122815),.PCURVE_S1.); -#122804 = CIRCLE('',#122805,0.2192697516); -#122805 = AXIS2_PLACEMENT_3D('',#122806,#122807,#122808); -#122806 = CARTESIAN_POINT('',(10.30032442045,8.85,0.530776333563)); -#122807 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122808 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122809 = PCURVE('',#122593,#122810); -#122810 = DEFINITIONAL_REPRESENTATION('',(#122811),#122814); -#122811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122812,#122813), +#125179 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#125180 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#125181 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#125182 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#125183 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#125184 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#125185 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#125186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125187 = ADVANCED_FACE('',(#125188),#124985,.T.); +#125188 = FACE_BOUND('',#125189,.T.); +#125189 = EDGE_LOOP('',(#125190,#125191,#125214,#125236)); +#125190 = ORIENTED_EDGE('',*,*,#124967,.F.); +#125191 = ORIENTED_EDGE('',*,*,#125192,.F.); +#125192 = EDGE_CURVE('',#125193,#124968,#125195,.T.); +#125193 = VERTEX_POINT('',#125194); +#125194 = CARTESIAN_POINT('',(10.304819755875,8.85,0.75)); +#125195 = SURFACE_CURVE('',#125196,(#125201,#125207),.PCURVE_S1.); +#125196 = CIRCLE('',#125197,0.2192697516); +#125197 = AXIS2_PLACEMENT_3D('',#125198,#125199,#125200); +#125198 = CARTESIAN_POINT('',(10.30032442045,8.85,0.530776333563)); +#125199 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125200 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125201 = PCURVE('',#124985,#125202); +#125202 = DEFINITIONAL_REPRESENTATION('',(#125203),#125206); +#125203 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125204,#125205), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#122812 = CARTESIAN_POINT('',(1.591299156552,8.85)); -#122813 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#122814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122815 = PCURVE('',#93994,#122816); -#122816 = DEFINITIONAL_REPRESENTATION('',(#122817),#122821); -#122817 = CIRCLE('',#122818,0.2192697516); -#122818 = AXIS2_PLACEMENT_2D('',#122819,#122820); -#122819 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#122820 = DIRECTION('',(0.E+000,-1.)); -#122821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122822 = ORIENTED_EDGE('',*,*,#122823,.F.); -#122823 = EDGE_CURVE('',#122824,#122801,#122826,.T.); -#122824 = VERTEX_POINT('',#122825); -#122825 = CARTESIAN_POINT('',(10.304819755875,8.65,0.75)); -#122826 = SURFACE_CURVE('',#122827,(#122831,#122837),.PCURVE_S1.); -#122827 = LINE('',#122828,#122829); -#122828 = CARTESIAN_POINT('',(10.304819755875,8.65,0.75)); -#122829 = VECTOR('',#122830,1.); -#122830 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122831 = PCURVE('',#122593,#122832); -#122832 = DEFINITIONAL_REPRESENTATION('',(#122833),#122836); -#122833 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122834,#122835), +#125204 = CARTESIAN_POINT('',(1.591299156552,8.85)); +#125205 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#125206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125207 = PCURVE('',#96386,#125208); +#125208 = DEFINITIONAL_REPRESENTATION('',(#125209),#125213); +#125209 = CIRCLE('',#125210,0.2192697516); +#125210 = AXIS2_PLACEMENT_2D('',#125211,#125212); +#125211 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#125212 = DIRECTION('',(0.E+000,-1.)); +#125213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125214 = ORIENTED_EDGE('',*,*,#125215,.F.); +#125215 = EDGE_CURVE('',#125216,#125193,#125218,.T.); +#125216 = VERTEX_POINT('',#125217); +#125217 = CARTESIAN_POINT('',(10.304819755875,8.65,0.75)); +#125218 = SURFACE_CURVE('',#125219,(#125223,#125229),.PCURVE_S1.); +#125219 = LINE('',#125220,#125221); +#125220 = CARTESIAN_POINT('',(10.304819755875,8.65,0.75)); +#125221 = VECTOR('',#125222,1.); +#125222 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125223 = PCURVE('',#124985,#125224); +#125224 = DEFINITIONAL_REPRESENTATION('',(#125225),#125228); +#125225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125226,#125227), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#122834 = CARTESIAN_POINT('',(1.591299156552,8.65)); -#122835 = CARTESIAN_POINT('',(1.591299156552,8.85)); -#122836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122837 = PCURVE('',#94076,#122838); -#122838 = DEFINITIONAL_REPRESENTATION('',(#122839),#122843); -#122839 = LINE('',#122840,#122841); -#122840 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#122841 = VECTOR('',#122842,1.); -#122842 = DIRECTION('',(4.440892098501E-016,1.)); -#122843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122844 = ORIENTED_EDGE('',*,*,#122845,.T.); -#122845 = EDGE_CURVE('',#122824,#122578,#122846,.T.); -#122846 = SURFACE_CURVE('',#122847,(#122852,#122858),.PCURVE_S1.); -#122847 = CIRCLE('',#122848,0.2192697516); -#122848 = AXIS2_PLACEMENT_3D('',#122849,#122850,#122851); -#122849 = CARTESIAN_POINT('',(10.30032442045,8.65,0.530776333563)); -#122850 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#122851 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#122852 = PCURVE('',#122593,#122853); -#122853 = DEFINITIONAL_REPRESENTATION('',(#122854),#122857); -#122854 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#122855,#122856), +#125226 = CARTESIAN_POINT('',(1.591299156552,8.65)); +#125227 = CARTESIAN_POINT('',(1.591299156552,8.85)); +#125228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125229 = PCURVE('',#96468,#125230); +#125230 = DEFINITIONAL_REPRESENTATION('',(#125231),#125235); +#125231 = LINE('',#125232,#125233); +#125232 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#125233 = VECTOR('',#125234,1.); +#125234 = DIRECTION('',(4.440892098501E-016,1.)); +#125235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125236 = ORIENTED_EDGE('',*,*,#125237,.T.); +#125237 = EDGE_CURVE('',#125216,#124970,#125238,.T.); +#125238 = SURFACE_CURVE('',#125239,(#125244,#125250),.PCURVE_S1.); +#125239 = CIRCLE('',#125240,0.2192697516); +#125240 = AXIS2_PLACEMENT_3D('',#125241,#125242,#125243); +#125241 = CARTESIAN_POINT('',(10.30032442045,8.65,0.530776333563)); +#125242 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125243 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125244 = PCURVE('',#124985,#125245); +#125245 = DEFINITIONAL_REPRESENTATION('',(#125246),#125249); +#125246 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125247,#125248), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#122855 = CARTESIAN_POINT('',(1.591299156552,8.65)); -#122856 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#122857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125247 = CARTESIAN_POINT('',(1.591299156552,8.65)); +#125248 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#125249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122858 = PCURVE('',#94050,#122859); -#122859 = DEFINITIONAL_REPRESENTATION('',(#122860),#122868); -#122860 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#122861,#122862,#122863, - #122864,#122865,#122866,#122867),.UNSPECIFIED.,.T.,.F.) +#125250 = PCURVE('',#96442,#125251); +#125251 = DEFINITIONAL_REPRESENTATION('',(#125252),#125260); +#125252 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125253,#125254,#125255, + #125256,#125257,#125258,#125259),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#122861 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#122862 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#122863 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#122864 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#122865 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#122866 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#122867 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#122868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122869 = ADVANCED_FACE('',(#122870),#94022,.T.); -#122870 = FACE_BOUND('',#122871,.T.); -#122871 = EDGE_LOOP('',(#122872,#122893,#122894,#122915)); -#122872 = ORIENTED_EDGE('',*,*,#122873,.F.); -#122873 = EDGE_CURVE('',#122727,#93979,#122874,.T.); -#122874 = SURFACE_CURVE('',#122875,(#122879,#122886),.PCURVE_S1.); -#122875 = LINE('',#122876,#122877); -#122876 = CARTESIAN_POINT('',(10.527847992439,8.85,0.65)); -#122877 = VECTOR('',#122878,1.); -#122878 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#122879 = PCURVE('',#94022,#122880); -#122880 = DEFINITIONAL_REPRESENTATION('',(#122881),#122885); -#122881 = LINE('',#122882,#122883); -#122882 = CARTESIAN_POINT('',(0.E+000,0.2)); -#122883 = VECTOR('',#122884,1.); -#122884 = DIRECTION('',(1.,4.800009495482E-063)); -#122885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122886 = PCURVE('',#93994,#122887); -#122887 = DEFINITIONAL_REPRESENTATION('',(#122888),#122892); -#122888 = LINE('',#122889,#122890); -#122889 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122890 = VECTOR('',#122891,1.); -#122891 = DIRECTION('',(3.563627120235E-016,-1.)); -#122892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122893 = ORIENTED_EDGE('',*,*,#122749,.T.); -#122894 = ORIENTED_EDGE('',*,*,#122895,.T.); -#122895 = EDGE_CURVE('',#122750,#94007,#122896,.T.); -#122896 = SURFACE_CURVE('',#122897,(#122901,#122908),.PCURVE_S1.); -#122897 = LINE('',#122898,#122899); -#122898 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); -#122899 = VECTOR('',#122900,1.); -#122900 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#122901 = PCURVE('',#94022,#122902); -#122902 = DEFINITIONAL_REPRESENTATION('',(#122903),#122907); -#122903 = LINE('',#122904,#122905); -#122904 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122905 = VECTOR('',#122906,1.); -#122906 = DIRECTION('',(1.,4.800009495482E-063)); -#122907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125253 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#125254 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#125255 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#125256 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#125257 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#125258 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#125259 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#125260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#122908 = PCURVE('',#94050,#122909); -#122909 = DEFINITIONAL_REPRESENTATION('',(#122910),#122914); -#122910 = LINE('',#122911,#122912); -#122911 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122912 = VECTOR('',#122913,1.); -#122913 = DIRECTION('',(-3.563627120235E-016,-1.)); -#122914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122915 = ORIENTED_EDGE('',*,*,#94006,.F.); -#122916 = ADVANCED_FACE('',(#122917),#93994,.T.); -#122917 = FACE_BOUND('',#122918,.T.); -#122918 = EDGE_LOOP('',(#122919,#122940,#122941,#122942,#122943,#122944, - #122965,#122966,#122967,#122968,#122969,#122970)); -#122919 = ORIENTED_EDGE('',*,*,#122920,.F.); -#122920 = EDGE_CURVE('',#122801,#93977,#122921,.T.); -#122921 = SURFACE_CURVE('',#122922,(#122926,#122933),.PCURVE_S1.); -#122922 = LINE('',#122923,#122924); -#122923 = CARTESIAN_POINT('',(10.527847992439,8.85,0.75)); -#122924 = VECTOR('',#122925,1.); -#122925 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#122926 = PCURVE('',#93994,#122927); -#122927 = DEFINITIONAL_REPRESENTATION('',(#122928),#122932); -#122928 = LINE('',#122929,#122930); -#122929 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#122930 = VECTOR('',#122931,1.); -#122931 = DIRECTION('',(3.563627120235E-016,-1.)); -#122932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122933 = PCURVE('',#94076,#122934); -#122934 = DEFINITIONAL_REPRESENTATION('',(#122935),#122939); -#122935 = LINE('',#122936,#122937); -#122936 = CARTESIAN_POINT('',(0.E+000,0.2)); -#122937 = VECTOR('',#122938,1.); -#122938 = DIRECTION('',(-1.,4.800009495482E-063)); -#122939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122940 = ORIENTED_EDGE('',*,*,#122800,.T.); -#122941 = ORIENTED_EDGE('',*,*,#122626,.T.); -#122942 = ORIENTED_EDGE('',*,*,#122546,.T.); -#122943 = ORIENTED_EDGE('',*,*,#122343,.T.); -#122944 = ORIENTED_EDGE('',*,*,#122945,.F.); -#122945 = EDGE_CURVE('',#122207,#122314,#122946,.T.); -#122946 = SURFACE_CURVE('',#122947,(#122951,#122958),.PCURVE_S1.); -#122947 = LINE('',#122948,#122949); -#122948 = CARTESIAN_POINT('',(11.,8.85,1.159810404338E-002)); -#122949 = VECTOR('',#122950,1.); -#122950 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#122951 = PCURVE('',#93994,#122952); -#122952 = DEFINITIONAL_REPRESENTATION('',(#122953),#122957); -#122953 = LINE('',#122954,#122955); -#122954 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#122955 = VECTOR('',#122956,1.); -#122956 = DIRECTION('',(1.,2.101748079665E-016)); -#122957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122958 = PCURVE('',#122227,#122959); -#122959 = DEFINITIONAL_REPRESENTATION('',(#122960),#122964); -#122960 = LINE('',#122961,#122962); -#122961 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#122962 = VECTOR('',#122963,1.); -#122963 = DIRECTION('',(1.194699204908E-017,1.)); -#122964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122965 = ORIENTED_EDGE('',*,*,#122289,.F.); -#122966 = ORIENTED_EDGE('',*,*,#122417,.F.); -#122967 = ORIENTED_EDGE('',*,*,#122679,.F.); -#122968 = ORIENTED_EDGE('',*,*,#122726,.F.); -#122969 = ORIENTED_EDGE('',*,*,#122873,.T.); -#122970 = ORIENTED_EDGE('',*,*,#93976,.F.); -#122971 = ADVANCED_FACE('',(#122972),#94076,.T.); -#122972 = FACE_BOUND('',#122973,.T.); -#122973 = EDGE_LOOP('',(#122974,#122995,#122996,#122997)); -#122974 = ORIENTED_EDGE('',*,*,#122975,.F.); -#122975 = EDGE_CURVE('',#122824,#94035,#122976,.T.); -#122976 = SURFACE_CURVE('',#122977,(#122981,#122988),.PCURVE_S1.); -#122977 = LINE('',#122978,#122979); -#122978 = CARTESIAN_POINT('',(10.527847992439,8.65,0.75)); -#122979 = VECTOR('',#122980,1.); -#122980 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#122981 = PCURVE('',#94076,#122982); -#122982 = DEFINITIONAL_REPRESENTATION('',(#122983),#122987); -#122983 = LINE('',#122984,#122985); -#122984 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#122985 = VECTOR('',#122986,1.); -#122986 = DIRECTION('',(-1.,4.800009495482E-063)); -#122987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122988 = PCURVE('',#94050,#122989); -#122989 = DEFINITIONAL_REPRESENTATION('',(#122990),#122994); -#122990 = LINE('',#122991,#122992); -#122991 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#122992 = VECTOR('',#122993,1.); -#122993 = DIRECTION('',(-3.563627120235E-016,-1.)); -#122994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#122995 = ORIENTED_EDGE('',*,*,#122823,.T.); -#122996 = ORIENTED_EDGE('',*,*,#122920,.T.); -#122997 = ORIENTED_EDGE('',*,*,#94062,.F.); -#122998 = ADVANCED_FACE('',(#122999),#94050,.T.); -#122999 = FACE_BOUND('',#123000,.T.); -#123000 = EDGE_LOOP('',(#123001,#123002,#123003,#123004,#123005,#123006, - #123027,#123028,#123029,#123030,#123031,#123032)); -#123001 = ORIENTED_EDGE('',*,*,#122895,.F.); -#123002 = ORIENTED_EDGE('',*,*,#122771,.T.); -#123003 = ORIENTED_EDGE('',*,*,#122701,.T.); -#123004 = ORIENTED_EDGE('',*,*,#122445,.T.); -#123005 = ORIENTED_EDGE('',*,*,#122239,.T.); -#123006 = ORIENTED_EDGE('',*,*,#123007,.F.); -#123007 = EDGE_CURVE('',#122316,#122205,#123008,.T.); -#123008 = SURFACE_CURVE('',#123009,(#123013,#123020),.PCURVE_S1.); -#123009 = LINE('',#123010,#123011); -#123010 = CARTESIAN_POINT('',(11.,8.65,1.159810404338E-002)); -#123011 = VECTOR('',#123012,1.); -#123012 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#123013 = PCURVE('',#94050,#123014); -#123014 = DEFINITIONAL_REPRESENTATION('',(#123015),#123019); -#123015 = LINE('',#123016,#123017); -#123016 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#123017 = VECTOR('',#123018,1.); -#123018 = DIRECTION('',(1.,-2.101748079665E-016)); -#123019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123020 = PCURVE('',#122227,#123021); -#123021 = DEFINITIONAL_REPRESENTATION('',(#123022),#123026); -#123022 = LINE('',#123023,#123024); -#123023 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#123024 = VECTOR('',#123025,1.); -#123025 = DIRECTION('',(-1.194699204908E-017,-1.)); -#123026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123027 = ORIENTED_EDGE('',*,*,#122393,.F.); -#123028 = ORIENTED_EDGE('',*,*,#122496,.F.); -#123029 = ORIENTED_EDGE('',*,*,#122604,.F.); -#123030 = ORIENTED_EDGE('',*,*,#122845,.F.); -#123031 = ORIENTED_EDGE('',*,*,#122975,.T.); -#123032 = ORIENTED_EDGE('',*,*,#94034,.F.); -#123033 = ADVANCED_FACE('',(#123034),#122227,.T.); -#123034 = FACE_BOUND('',#123035,.T.); -#123035 = EDGE_LOOP('',(#123036,#123037,#123038,#123039)); -#123036 = ORIENTED_EDGE('',*,*,#122945,.T.); -#123037 = ORIENTED_EDGE('',*,*,#122313,.T.); -#123038 = ORIENTED_EDGE('',*,*,#123007,.T.); -#123039 = ORIENTED_EDGE('',*,*,#122204,.T.); -#123040 = ADVANCED_FACE('',(#123041),#123055,.F.); -#123041 = FACE_BOUND('',#123042,.T.); -#123042 = EDGE_LOOP('',(#123043,#123078,#123101,#123128)); -#123043 = ORIENTED_EDGE('',*,*,#123044,.F.); -#123044 = EDGE_CURVE('',#123045,#123047,#123049,.T.); -#123045 = VERTEX_POINT('',#123046); -#123046 = CARTESIAN_POINT('',(11.,4.85,-0.208196358798)); -#123047 = VERTEX_POINT('',#123048); -#123048 = CARTESIAN_POINT('',(11.,4.65,-0.208196358798)); -#123049 = SURFACE_CURVE('',#123050,(#123054,#123066),.PCURVE_S1.); -#123050 = LINE('',#123051,#123052); -#123051 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#123052 = VECTOR('',#123053,1.); -#123053 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123054 = PCURVE('',#123055,#123060); -#123055 = PLANE('',#123056); -#123056 = AXIS2_PLACEMENT_3D('',#123057,#123058,#123059); -#123057 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#125261 = ADVANCED_FACE('',(#125262),#96414,.T.); +#125262 = FACE_BOUND('',#125263,.T.); +#125263 = EDGE_LOOP('',(#125264,#125285,#125286,#125307)); +#125264 = ORIENTED_EDGE('',*,*,#125265,.F.); +#125265 = EDGE_CURVE('',#125119,#96371,#125266,.T.); +#125266 = SURFACE_CURVE('',#125267,(#125271,#125278),.PCURVE_S1.); +#125267 = LINE('',#125268,#125269); +#125268 = CARTESIAN_POINT('',(10.527847992439,8.85,0.65)); +#125269 = VECTOR('',#125270,1.); +#125270 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#125271 = PCURVE('',#96414,#125272); +#125272 = DEFINITIONAL_REPRESENTATION('',(#125273),#125277); +#125273 = LINE('',#125274,#125275); +#125274 = CARTESIAN_POINT('',(0.E+000,0.2)); +#125275 = VECTOR('',#125276,1.); +#125276 = DIRECTION('',(1.,4.800009495482E-063)); +#125277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125278 = PCURVE('',#96386,#125279); +#125279 = DEFINITIONAL_REPRESENTATION('',(#125280),#125284); +#125280 = LINE('',#125281,#125282); +#125281 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125282 = VECTOR('',#125283,1.); +#125283 = DIRECTION('',(3.563627120235E-016,-1.)); +#125284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125285 = ORIENTED_EDGE('',*,*,#125141,.T.); +#125286 = ORIENTED_EDGE('',*,*,#125287,.T.); +#125287 = EDGE_CURVE('',#125142,#96399,#125288,.T.); +#125288 = SURFACE_CURVE('',#125289,(#125293,#125300),.PCURVE_S1.); +#125289 = LINE('',#125290,#125291); +#125290 = CARTESIAN_POINT('',(10.527847992439,8.65,0.65)); +#125291 = VECTOR('',#125292,1.); +#125292 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#125293 = PCURVE('',#96414,#125294); +#125294 = DEFINITIONAL_REPRESENTATION('',(#125295),#125299); +#125295 = LINE('',#125296,#125297); +#125296 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125297 = VECTOR('',#125298,1.); +#125298 = DIRECTION('',(1.,4.800009495482E-063)); +#125299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125300 = PCURVE('',#96442,#125301); +#125301 = DEFINITIONAL_REPRESENTATION('',(#125302),#125306); +#125302 = LINE('',#125303,#125304); +#125303 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125304 = VECTOR('',#125305,1.); +#125305 = DIRECTION('',(-3.563627120235E-016,-1.)); +#125306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125307 = ORIENTED_EDGE('',*,*,#96398,.F.); +#125308 = ADVANCED_FACE('',(#125309),#96386,.T.); +#125309 = FACE_BOUND('',#125310,.T.); +#125310 = EDGE_LOOP('',(#125311,#125332,#125333,#125334,#125335,#125336, + #125357,#125358,#125359,#125360,#125361,#125362)); +#125311 = ORIENTED_EDGE('',*,*,#125312,.F.); +#125312 = EDGE_CURVE('',#125193,#96369,#125313,.T.); +#125313 = SURFACE_CURVE('',#125314,(#125318,#125325),.PCURVE_S1.); +#125314 = LINE('',#125315,#125316); +#125315 = CARTESIAN_POINT('',(10.527847992439,8.85,0.75)); +#125316 = VECTOR('',#125317,1.); +#125317 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#125318 = PCURVE('',#96386,#125319); +#125319 = DEFINITIONAL_REPRESENTATION('',(#125320),#125324); +#125320 = LINE('',#125321,#125322); +#125321 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#125322 = VECTOR('',#125323,1.); +#125323 = DIRECTION('',(3.563627120235E-016,-1.)); +#125324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125325 = PCURVE('',#96468,#125326); +#125326 = DEFINITIONAL_REPRESENTATION('',(#125327),#125331); +#125327 = LINE('',#125328,#125329); +#125328 = CARTESIAN_POINT('',(0.E+000,0.2)); +#125329 = VECTOR('',#125330,1.); +#125330 = DIRECTION('',(-1.,4.800009495482E-063)); +#125331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125332 = ORIENTED_EDGE('',*,*,#125192,.T.); +#125333 = ORIENTED_EDGE('',*,*,#125018,.T.); +#125334 = ORIENTED_EDGE('',*,*,#124938,.T.); +#125335 = ORIENTED_EDGE('',*,*,#124735,.T.); +#125336 = ORIENTED_EDGE('',*,*,#125337,.F.); +#125337 = EDGE_CURVE('',#124599,#124706,#125338,.T.); +#125338 = SURFACE_CURVE('',#125339,(#125343,#125350),.PCURVE_S1.); +#125339 = LINE('',#125340,#125341); +#125340 = CARTESIAN_POINT('',(11.,8.85,1.159810404338E-002)); +#125341 = VECTOR('',#125342,1.); +#125342 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#125343 = PCURVE('',#96386,#125344); +#125344 = DEFINITIONAL_REPRESENTATION('',(#125345),#125349); +#125345 = LINE('',#125346,#125347); +#125346 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#125347 = VECTOR('',#125348,1.); +#125348 = DIRECTION('',(1.,2.101748079665E-016)); +#125349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125350 = PCURVE('',#124619,#125351); +#125351 = DEFINITIONAL_REPRESENTATION('',(#125352),#125356); +#125352 = LINE('',#125353,#125354); +#125353 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#125354 = VECTOR('',#125355,1.); +#125355 = DIRECTION('',(1.194699204908E-017,1.)); +#125356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125357 = ORIENTED_EDGE('',*,*,#124681,.F.); +#125358 = ORIENTED_EDGE('',*,*,#124809,.F.); +#125359 = ORIENTED_EDGE('',*,*,#125071,.F.); +#125360 = ORIENTED_EDGE('',*,*,#125118,.F.); +#125361 = ORIENTED_EDGE('',*,*,#125265,.T.); +#125362 = ORIENTED_EDGE('',*,*,#96368,.F.); +#125363 = ADVANCED_FACE('',(#125364),#96468,.T.); +#125364 = FACE_BOUND('',#125365,.T.); +#125365 = EDGE_LOOP('',(#125366,#125387,#125388,#125389)); +#125366 = ORIENTED_EDGE('',*,*,#125367,.F.); +#125367 = EDGE_CURVE('',#125216,#96427,#125368,.T.); +#125368 = SURFACE_CURVE('',#125369,(#125373,#125380),.PCURVE_S1.); +#125369 = LINE('',#125370,#125371); +#125370 = CARTESIAN_POINT('',(10.527847992439,8.65,0.75)); +#125371 = VECTOR('',#125372,1.); +#125372 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#125373 = PCURVE('',#96468,#125374); +#125374 = DEFINITIONAL_REPRESENTATION('',(#125375),#125379); +#125375 = LINE('',#125376,#125377); +#125376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125377 = VECTOR('',#125378,1.); +#125378 = DIRECTION('',(-1.,4.800009495482E-063)); +#125379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125380 = PCURVE('',#96442,#125381); +#125381 = DEFINITIONAL_REPRESENTATION('',(#125382),#125386); +#125382 = LINE('',#125383,#125384); +#125383 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#125384 = VECTOR('',#125385,1.); +#125385 = DIRECTION('',(-3.563627120235E-016,-1.)); +#125386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125387 = ORIENTED_EDGE('',*,*,#125215,.T.); +#125388 = ORIENTED_EDGE('',*,*,#125312,.T.); +#125389 = ORIENTED_EDGE('',*,*,#96454,.F.); +#125390 = ADVANCED_FACE('',(#125391),#96442,.T.); +#125391 = FACE_BOUND('',#125392,.T.); +#125392 = EDGE_LOOP('',(#125393,#125394,#125395,#125396,#125397,#125398, + #125419,#125420,#125421,#125422,#125423,#125424)); +#125393 = ORIENTED_EDGE('',*,*,#125287,.F.); +#125394 = ORIENTED_EDGE('',*,*,#125163,.T.); +#125395 = ORIENTED_EDGE('',*,*,#125093,.T.); +#125396 = ORIENTED_EDGE('',*,*,#124837,.T.); +#125397 = ORIENTED_EDGE('',*,*,#124631,.T.); +#125398 = ORIENTED_EDGE('',*,*,#125399,.F.); +#125399 = EDGE_CURVE('',#124708,#124597,#125400,.T.); +#125400 = SURFACE_CURVE('',#125401,(#125405,#125412),.PCURVE_S1.); +#125401 = LINE('',#125402,#125403); +#125402 = CARTESIAN_POINT('',(11.,8.65,1.159810404338E-002)); +#125403 = VECTOR('',#125404,1.); +#125404 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#125405 = PCURVE('',#96442,#125406); +#125406 = DEFINITIONAL_REPRESENTATION('',(#125407),#125411); +#125407 = LINE('',#125408,#125409); +#125408 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#125409 = VECTOR('',#125410,1.); +#125410 = DIRECTION('',(1.,-2.101748079665E-016)); +#125411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125412 = PCURVE('',#124619,#125413); +#125413 = DEFINITIONAL_REPRESENTATION('',(#125414),#125418); +#125414 = LINE('',#125415,#125416); +#125415 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#125416 = VECTOR('',#125417,1.); +#125417 = DIRECTION('',(-1.194699204908E-017,-1.)); +#125418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125419 = ORIENTED_EDGE('',*,*,#124785,.F.); +#125420 = ORIENTED_EDGE('',*,*,#124888,.F.); +#125421 = ORIENTED_EDGE('',*,*,#124996,.F.); +#125422 = ORIENTED_EDGE('',*,*,#125237,.F.); +#125423 = ORIENTED_EDGE('',*,*,#125367,.T.); +#125424 = ORIENTED_EDGE('',*,*,#96426,.F.); +#125425 = ADVANCED_FACE('',(#125426),#124619,.T.); +#125426 = FACE_BOUND('',#125427,.T.); +#125427 = EDGE_LOOP('',(#125428,#125429,#125430,#125431)); +#125428 = ORIENTED_EDGE('',*,*,#125337,.T.); +#125429 = ORIENTED_EDGE('',*,*,#124705,.T.); +#125430 = ORIENTED_EDGE('',*,*,#125399,.T.); +#125431 = ORIENTED_EDGE('',*,*,#124596,.T.); +#125432 = ADVANCED_FACE('',(#125433),#125447,.F.); +#125433 = FACE_BOUND('',#125434,.T.); +#125434 = EDGE_LOOP('',(#125435,#125470,#125493,#125520)); +#125435 = ORIENTED_EDGE('',*,*,#125436,.F.); +#125436 = EDGE_CURVE('',#125437,#125439,#125441,.T.); +#125437 = VERTEX_POINT('',#125438); +#125438 = CARTESIAN_POINT('',(11.,4.85,-0.208196358798)); +#125439 = VERTEX_POINT('',#125440); +#125440 = CARTESIAN_POINT('',(11.,4.65,-0.208196358798)); +#125441 = SURFACE_CURVE('',#125442,(#125446,#125458),.PCURVE_S1.); +#125442 = LINE('',#125443,#125444); +#125443 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#125444 = VECTOR('',#125445,1.); +#125445 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125446 = PCURVE('',#125447,#125452); +#125447 = PLANE('',#125448); +#125448 = AXIS2_PLACEMENT_3D('',#125449,#125450,#125451); +#125449 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#123058 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#123059 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#123060 = DEFINITIONAL_REPRESENTATION('',(#123061),#123065); -#123061 = LINE('',#123062,#123063); -#123062 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#123063 = VECTOR('',#123064,1.); -#123064 = DIRECTION('',(4.440892098501E-016,-1.)); -#123065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123066 = PCURVE('',#123067,#123072); -#123067 = PLANE('',#123068); -#123068 = AXIS2_PLACEMENT_3D('',#123069,#123070,#123071); -#123069 = CARTESIAN_POINT('',(11.,4.75,-0.258196742327)); -#123070 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#123071 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123072 = DEFINITIONAL_REPRESENTATION('',(#123073),#123077); -#123073 = LINE('',#123074,#123075); -#123074 = CARTESIAN_POINT('',(-4.75,5.000038352949E-002)); -#123075 = VECTOR('',#123076,1.); -#123076 = DIRECTION('',(-1.,0.E+000)); -#123077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123078 = ORIENTED_EDGE('',*,*,#123079,.F.); -#123079 = EDGE_CURVE('',#123080,#123045,#123082,.T.); -#123080 = VERTEX_POINT('',#123081); -#123081 = CARTESIAN_POINT('',(10.740726081328,4.85,-0.208196358798)); -#123082 = SURFACE_CURVE('',#123083,(#123087,#123094),.PCURVE_S1.); -#123083 = LINE('',#123084,#123085); -#123084 = CARTESIAN_POINT('',(10.740726081328,4.85,-0.208196358798)); -#123085 = VECTOR('',#123086,1.); -#123086 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123087 = PCURVE('',#123055,#123088); -#123088 = DEFINITIONAL_REPRESENTATION('',(#123089),#123093); -#123089 = LINE('',#123090,#123091); -#123090 = CARTESIAN_POINT('',(-1.7763568394E-015,4.85)); -#123091 = VECTOR('',#123092,1.); -#123092 = DIRECTION('',(-1.,0.E+000)); -#123093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123094 = PCURVE('',#93908,#123095); -#123095 = DEFINITIONAL_REPRESENTATION('',(#123096),#123100); -#123096 = LINE('',#123097,#123098); -#123097 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#123098 = VECTOR('',#123099,1.); -#123099 = DIRECTION('',(0.E+000,1.)); -#123100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123101 = ORIENTED_EDGE('',*,*,#123102,.F.); -#123102 = EDGE_CURVE('',#123103,#123080,#123105,.T.); -#123103 = VERTEX_POINT('',#123104); -#123104 = CARTESIAN_POINT('',(10.740726081328,4.65,-0.208196358798)); -#123105 = SURFACE_CURVE('',#123106,(#123110,#123117),.PCURVE_S1.); -#123106 = LINE('',#123107,#123108); -#123107 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#125450 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125451 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#125452 = DEFINITIONAL_REPRESENTATION('',(#125453),#125457); +#125453 = LINE('',#125454,#125455); +#125454 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#125455 = VECTOR('',#125456,1.); +#125456 = DIRECTION('',(4.440892098501E-016,-1.)); +#125457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125458 = PCURVE('',#125459,#125464); +#125459 = PLANE('',#125460); +#125460 = AXIS2_PLACEMENT_3D('',#125461,#125462,#125463); +#125461 = CARTESIAN_POINT('',(11.,4.75,-0.258196742327)); +#125462 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#125463 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125464 = DEFINITIONAL_REPRESENTATION('',(#125465),#125469); +#125465 = LINE('',#125466,#125467); +#125466 = CARTESIAN_POINT('',(-4.75,5.000038352949E-002)); +#125467 = VECTOR('',#125468,1.); +#125468 = DIRECTION('',(-1.,0.E+000)); +#125469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125470 = ORIENTED_EDGE('',*,*,#125471,.F.); +#125471 = EDGE_CURVE('',#125472,#125437,#125474,.T.); +#125472 = VERTEX_POINT('',#125473); +#125473 = CARTESIAN_POINT('',(10.740726081328,4.85,-0.208196358798)); +#125474 = SURFACE_CURVE('',#125475,(#125479,#125486),.PCURVE_S1.); +#125475 = LINE('',#125476,#125477); +#125476 = CARTESIAN_POINT('',(10.740726081328,4.85,-0.208196358798)); +#125477 = VECTOR('',#125478,1.); +#125478 = DIRECTION('',(1.,0.E+000,0.E+000)); +#125479 = PCURVE('',#125447,#125480); +#125480 = DEFINITIONAL_REPRESENTATION('',(#125481),#125485); +#125481 = LINE('',#125482,#125483); +#125482 = CARTESIAN_POINT('',(-1.7763568394E-015,4.85)); +#125483 = VECTOR('',#125484,1.); +#125484 = DIRECTION('',(-1.,0.E+000)); +#125485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125486 = PCURVE('',#96300,#125487); +#125487 = DEFINITIONAL_REPRESENTATION('',(#125488),#125492); +#125488 = LINE('',#125489,#125490); +#125489 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#125490 = VECTOR('',#125491,1.); +#125491 = DIRECTION('',(0.E+000,1.)); +#125492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125493 = ORIENTED_EDGE('',*,*,#125494,.F.); +#125494 = EDGE_CURVE('',#125495,#125472,#125497,.T.); +#125495 = VERTEX_POINT('',#125496); +#125496 = CARTESIAN_POINT('',(10.740726081328,4.65,-0.208196358798)); +#125497 = SURFACE_CURVE('',#125498,(#125502,#125509),.PCURVE_S1.); +#125498 = LINE('',#125499,#125500); +#125499 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#123108 = VECTOR('',#123109,1.); -#123109 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123110 = PCURVE('',#123055,#123111); -#123111 = DEFINITIONAL_REPRESENTATION('',(#123112),#123116); -#123112 = LINE('',#123113,#123114); -#123113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123114 = VECTOR('',#123115,1.); -#123115 = DIRECTION('',(-4.440892098501E-016,1.)); -#123116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123117 = PCURVE('',#123118,#123123); -#123118 = CYLINDRICAL_SURFACE('',#123119,0.208574704164); -#123119 = AXIS2_PLACEMENT_3D('',#123120,#123121,#123122); -#123120 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#125500 = VECTOR('',#125501,1.); +#125501 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125502 = PCURVE('',#125447,#125503); +#125503 = DEFINITIONAL_REPRESENTATION('',(#125504),#125508); +#125504 = LINE('',#125505,#125506); +#125505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125506 = VECTOR('',#125507,1.); +#125507 = DIRECTION('',(-4.440892098501E-016,1.)); +#125508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125509 = PCURVE('',#125510,#125515); +#125510 = CYLINDRICAL_SURFACE('',#125511,0.208574704164); +#125511 = AXIS2_PLACEMENT_3D('',#125512,#125513,#125514); +#125512 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#123121 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123122 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123123 = DEFINITIONAL_REPRESENTATION('',(#123124),#123127); -#123124 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123125,#123126), +#125513 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125514 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125515 = DEFINITIONAL_REPRESENTATION('',(#125516),#125519); +#125516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125517,#125518), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#123125 = CARTESIAN_POINT('',(4.772630242227,-4.65)); -#123126 = CARTESIAN_POINT('',(4.772630242227,-4.85)); -#123127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123128 = ORIENTED_EDGE('',*,*,#123129,.T.); -#123129 = EDGE_CURVE('',#123103,#123047,#123130,.T.); -#123130 = SURFACE_CURVE('',#123131,(#123135,#123142),.PCURVE_S1.); -#123131 = LINE('',#123132,#123133); -#123132 = CARTESIAN_POINT('',(10.740726081328,4.65,-0.208196358798)); -#123133 = VECTOR('',#123134,1.); -#123134 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123135 = PCURVE('',#123055,#123136); -#123136 = DEFINITIONAL_REPRESENTATION('',(#123137),#123141); -#123137 = LINE('',#123138,#123139); -#123138 = CARTESIAN_POINT('',(-1.7763568394E-015,4.65)); -#123139 = VECTOR('',#123140,1.); -#123140 = DIRECTION('',(-1.,0.E+000)); -#123141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123142 = PCURVE('',#93962,#123143); -#123143 = DEFINITIONAL_REPRESENTATION('',(#123144),#123148); -#123144 = LINE('',#123145,#123146); -#123145 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#123146 = VECTOR('',#123147,1.); -#123147 = DIRECTION('',(0.E+000,1.)); -#123148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123149 = ADVANCED_FACE('',(#123150),#123164,.F.); -#123150 = FACE_BOUND('',#123151,.T.); -#123151 = EDGE_LOOP('',(#123152,#123182,#123205,#123232)); -#123152 = ORIENTED_EDGE('',*,*,#123153,.F.); -#123153 = EDGE_CURVE('',#123154,#123156,#123158,.T.); -#123154 = VERTEX_POINT('',#123155); -#123155 = CARTESIAN_POINT('',(11.,4.65,-0.308197125857)); -#123156 = VERTEX_POINT('',#123157); -#123157 = CARTESIAN_POINT('',(11.,4.85,-0.308197125857)); -#123158 = SURFACE_CURVE('',#123159,(#123163,#123175),.PCURVE_S1.); -#123159 = LINE('',#123160,#123161); -#123160 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#123161 = VECTOR('',#123162,1.); -#123162 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123163 = PCURVE('',#123164,#123169); -#123164 = PLANE('',#123165); -#123165 = AXIS2_PLACEMENT_3D('',#123166,#123167,#123168); -#123166 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#125517 = CARTESIAN_POINT('',(4.772630242227,-4.65)); +#125518 = CARTESIAN_POINT('',(4.772630242227,-4.85)); +#125519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125520 = ORIENTED_EDGE('',*,*,#125521,.T.); +#125521 = EDGE_CURVE('',#125495,#125439,#125522,.T.); +#125522 = SURFACE_CURVE('',#125523,(#125527,#125534),.PCURVE_S1.); +#125523 = LINE('',#125524,#125525); +#125524 = CARTESIAN_POINT('',(10.740726081328,4.65,-0.208196358798)); +#125525 = VECTOR('',#125526,1.); +#125526 = DIRECTION('',(1.,0.E+000,0.E+000)); +#125527 = PCURVE('',#125447,#125528); +#125528 = DEFINITIONAL_REPRESENTATION('',(#125529),#125533); +#125529 = LINE('',#125530,#125531); +#125530 = CARTESIAN_POINT('',(-1.7763568394E-015,4.65)); +#125531 = VECTOR('',#125532,1.); +#125532 = DIRECTION('',(-1.,0.E+000)); +#125533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125534 = PCURVE('',#96354,#125535); +#125535 = DEFINITIONAL_REPRESENTATION('',(#125536),#125540); +#125536 = LINE('',#125537,#125538); +#125537 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#125538 = VECTOR('',#125539,1.); +#125539 = DIRECTION('',(0.E+000,1.)); +#125540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125541 = ADVANCED_FACE('',(#125542),#125556,.F.); +#125542 = FACE_BOUND('',#125543,.T.); +#125543 = EDGE_LOOP('',(#125544,#125574,#125597,#125624)); +#125544 = ORIENTED_EDGE('',*,*,#125545,.F.); +#125545 = EDGE_CURVE('',#125546,#125548,#125550,.T.); +#125546 = VERTEX_POINT('',#125547); +#125547 = CARTESIAN_POINT('',(11.,4.65,-0.308197125857)); +#125548 = VERTEX_POINT('',#125549); +#125549 = CARTESIAN_POINT('',(11.,4.85,-0.308197125857)); +#125550 = SURFACE_CURVE('',#125551,(#125555,#125567),.PCURVE_S1.); +#125551 = LINE('',#125552,#125553); +#125552 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#125553 = VECTOR('',#125554,1.); +#125554 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125555 = PCURVE('',#125556,#125561); +#125556 = PLANE('',#125557); +#125557 = AXIS2_PLACEMENT_3D('',#125558,#125559,#125560); +#125558 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#123167 = DIRECTION('',(0.E+000,0.E+000,1.)); -#123168 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123169 = DEFINITIONAL_REPRESENTATION('',(#123170),#123174); -#123170 = LINE('',#123171,#123172); -#123171 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#123172 = VECTOR('',#123173,1.); -#123173 = DIRECTION('',(4.440892098501E-016,1.)); -#123174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123175 = PCURVE('',#123067,#123176); -#123176 = DEFINITIONAL_REPRESENTATION('',(#123177),#123181); -#123177 = LINE('',#123178,#123179); -#123178 = CARTESIAN_POINT('',(-4.75,-5.000038352949E-002)); -#123179 = VECTOR('',#123180,1.); -#123180 = DIRECTION('',(1.,0.E+000)); -#123181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123182 = ORIENTED_EDGE('',*,*,#123183,.F.); -#123183 = EDGE_CURVE('',#123184,#123154,#123186,.T.); -#123184 = VERTEX_POINT('',#123185); -#123185 = CARTESIAN_POINT('',(10.74341632541,4.65,-0.308197125857)); -#123186 = SURFACE_CURVE('',#123187,(#123191,#123198),.PCURVE_S1.); -#123187 = LINE('',#123188,#123189); -#123188 = CARTESIAN_POINT('',(10.74341632541,4.65,-0.308197125857)); -#123189 = VECTOR('',#123190,1.); -#123190 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123191 = PCURVE('',#123164,#123192); -#123192 = DEFINITIONAL_REPRESENTATION('',(#123193),#123197); -#123193 = LINE('',#123194,#123195); -#123194 = CARTESIAN_POINT('',(1.7763568394E-015,4.65)); -#123195 = VECTOR('',#123196,1.); -#123196 = DIRECTION('',(1.,0.E+000)); -#123197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123198 = PCURVE('',#93962,#123199); -#123199 = DEFINITIONAL_REPRESENTATION('',(#123200),#123204); -#123200 = LINE('',#123201,#123202); -#123201 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#123202 = VECTOR('',#123203,1.); -#123203 = DIRECTION('',(0.E+000,1.)); -#123204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123205 = ORIENTED_EDGE('',*,*,#123206,.F.); -#123206 = EDGE_CURVE('',#123207,#123184,#123209,.T.); -#123207 = VERTEX_POINT('',#123208); -#123208 = CARTESIAN_POINT('',(10.74341632541,4.85,-0.308197125857)); -#123209 = SURFACE_CURVE('',#123210,(#123214,#123221),.PCURVE_S1.); -#123210 = LINE('',#123211,#123212); -#123211 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#125559 = DIRECTION('',(0.E+000,0.E+000,1.)); +#125560 = DIRECTION('',(1.,0.E+000,0.E+000)); +#125561 = DEFINITIONAL_REPRESENTATION('',(#125562),#125566); +#125562 = LINE('',#125563,#125564); +#125563 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#125564 = VECTOR('',#125565,1.); +#125565 = DIRECTION('',(4.440892098501E-016,1.)); +#125566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125567 = PCURVE('',#125459,#125568); +#125568 = DEFINITIONAL_REPRESENTATION('',(#125569),#125573); +#125569 = LINE('',#125570,#125571); +#125570 = CARTESIAN_POINT('',(-4.75,-5.000038352949E-002)); +#125571 = VECTOR('',#125572,1.); +#125572 = DIRECTION('',(1.,0.E+000)); +#125573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125574 = ORIENTED_EDGE('',*,*,#125575,.F.); +#125575 = EDGE_CURVE('',#125576,#125546,#125578,.T.); +#125576 = VERTEX_POINT('',#125577); +#125577 = CARTESIAN_POINT('',(10.74341632541,4.65,-0.308197125857)); +#125578 = SURFACE_CURVE('',#125579,(#125583,#125590),.PCURVE_S1.); +#125579 = LINE('',#125580,#125581); +#125580 = CARTESIAN_POINT('',(10.74341632541,4.65,-0.308197125857)); +#125581 = VECTOR('',#125582,1.); +#125582 = DIRECTION('',(1.,0.E+000,0.E+000)); +#125583 = PCURVE('',#125556,#125584); +#125584 = DEFINITIONAL_REPRESENTATION('',(#125585),#125589); +#125585 = LINE('',#125586,#125587); +#125586 = CARTESIAN_POINT('',(1.7763568394E-015,4.65)); +#125587 = VECTOR('',#125588,1.); +#125588 = DIRECTION('',(1.,0.E+000)); +#125589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125590 = PCURVE('',#96354,#125591); +#125591 = DEFINITIONAL_REPRESENTATION('',(#125592),#125596); +#125592 = LINE('',#125593,#125594); +#125593 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#125594 = VECTOR('',#125595,1.); +#125595 = DIRECTION('',(0.E+000,1.)); +#125596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125597 = ORIENTED_EDGE('',*,*,#125598,.F.); +#125598 = EDGE_CURVE('',#125599,#125576,#125601,.T.); +#125599 = VERTEX_POINT('',#125600); +#125600 = CARTESIAN_POINT('',(10.74341632541,4.85,-0.308197125857)); +#125601 = SURFACE_CURVE('',#125602,(#125606,#125613),.PCURVE_S1.); +#125602 = LINE('',#125603,#125604); +#125603 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#123212 = VECTOR('',#123213,1.); -#123213 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123214 = PCURVE('',#123164,#123215); -#123215 = DEFINITIONAL_REPRESENTATION('',(#123216),#123220); -#123216 = LINE('',#123217,#123218); -#123217 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123218 = VECTOR('',#123219,1.); -#123219 = DIRECTION('',(-4.440892098501E-016,-1.)); -#123220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123221 = PCURVE('',#123222,#123227); -#123222 = CYLINDRICAL_SURFACE('',#123223,0.308574064194); -#123223 = AXIS2_PLACEMENT_3D('',#123224,#123225,#123226); -#123224 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#125604 = VECTOR('',#125605,1.); +#125605 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125606 = PCURVE('',#125556,#125607); +#125607 = DEFINITIONAL_REPRESENTATION('',(#125608),#125612); +#125608 = LINE('',#125609,#125610); +#125609 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125610 = VECTOR('',#125611,1.); +#125611 = DIRECTION('',(-4.440892098501E-016,-1.)); +#125612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125613 = PCURVE('',#125614,#125619); +#125614 = CYLINDRICAL_SURFACE('',#125615,0.308574064194); +#125615 = AXIS2_PLACEMENT_3D('',#125616,#125617,#125618); +#125616 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#123225 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123226 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123227 = DEFINITIONAL_REPRESENTATION('',(#123228),#123231); -#123228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123229,#123230), +#125617 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125618 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125619 = DEFINITIONAL_REPRESENTATION('',(#125620),#125623); +#125620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125621,#125622), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#123229 = CARTESIAN_POINT('',(4.761821717947,-4.85)); -#123230 = CARTESIAN_POINT('',(4.761821717947,-4.65)); -#123231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123232 = ORIENTED_EDGE('',*,*,#123233,.T.); -#123233 = EDGE_CURVE('',#123207,#123156,#123234,.T.); -#123234 = SURFACE_CURVE('',#123235,(#123239,#123246),.PCURVE_S1.); -#123235 = LINE('',#123236,#123237); -#123236 = CARTESIAN_POINT('',(10.74341632541,4.85,-0.308197125857)); -#123237 = VECTOR('',#123238,1.); -#123238 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123239 = PCURVE('',#123164,#123240); -#123240 = DEFINITIONAL_REPRESENTATION('',(#123241),#123245); -#123241 = LINE('',#123242,#123243); -#123242 = CARTESIAN_POINT('',(1.7763568394E-015,4.85)); -#123243 = VECTOR('',#123244,1.); -#123244 = DIRECTION('',(1.,0.E+000)); -#123245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123246 = PCURVE('',#93908,#123247); -#123247 = DEFINITIONAL_REPRESENTATION('',(#123248),#123252); -#123248 = LINE('',#123249,#123250); -#123249 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#123250 = VECTOR('',#123251,1.); -#123251 = DIRECTION('',(0.E+000,1.)); -#123252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123253 = ADVANCED_FACE('',(#123254),#123222,.T.); -#123254 = FACE_BOUND('',#123255,.T.); -#123255 = EDGE_LOOP('',(#123256,#123283,#123284,#123307)); -#123256 = ORIENTED_EDGE('',*,*,#123257,.T.); -#123257 = EDGE_CURVE('',#123258,#123207,#123260,.T.); -#123258 = VERTEX_POINT('',#123259); -#123259 = CARTESIAN_POINT('',(10.419594812019,4.85,0.E+000)); -#123260 = SURFACE_CURVE('',#123261,(#123266,#123272),.PCURVE_S1.); -#123261 = CIRCLE('',#123262,0.308574064194); -#123262 = AXIS2_PLACEMENT_3D('',#123263,#123264,#123265); -#123263 = CARTESIAN_POINT('',(10.728168876214,4.85,2.640924866458E-017) - ); -#123264 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123265 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123266 = PCURVE('',#123222,#123267); -#123267 = DEFINITIONAL_REPRESENTATION('',(#123268),#123271); -#123268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123269,#123270), +#125621 = CARTESIAN_POINT('',(4.761821717947,-4.85)); +#125622 = CARTESIAN_POINT('',(4.761821717947,-4.65)); +#125623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125624 = ORIENTED_EDGE('',*,*,#125625,.T.); +#125625 = EDGE_CURVE('',#125599,#125548,#125626,.T.); +#125626 = SURFACE_CURVE('',#125627,(#125631,#125638),.PCURVE_S1.); +#125627 = LINE('',#125628,#125629); +#125628 = CARTESIAN_POINT('',(10.74341632541,4.85,-0.308197125857)); +#125629 = VECTOR('',#125630,1.); +#125630 = DIRECTION('',(1.,0.E+000,0.E+000)); +#125631 = PCURVE('',#125556,#125632); +#125632 = DEFINITIONAL_REPRESENTATION('',(#125633),#125637); +#125633 = LINE('',#125634,#125635); +#125634 = CARTESIAN_POINT('',(1.7763568394E-015,4.85)); +#125635 = VECTOR('',#125636,1.); +#125636 = DIRECTION('',(1.,0.E+000)); +#125637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125638 = PCURVE('',#96300,#125639); +#125639 = DEFINITIONAL_REPRESENTATION('',(#125640),#125644); +#125640 = LINE('',#125641,#125642); +#125641 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#125642 = VECTOR('',#125643,1.); +#125643 = DIRECTION('',(0.E+000,1.)); +#125644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125645 = ADVANCED_FACE('',(#125646),#125614,.T.); +#125646 = FACE_BOUND('',#125647,.T.); +#125647 = EDGE_LOOP('',(#125648,#125675,#125676,#125699)); +#125648 = ORIENTED_EDGE('',*,*,#125649,.T.); +#125649 = EDGE_CURVE('',#125650,#125599,#125652,.T.); +#125650 = VERTEX_POINT('',#125651); +#125651 = CARTESIAN_POINT('',(10.419594812019,4.85,0.E+000)); +#125652 = SURFACE_CURVE('',#125653,(#125658,#125664),.PCURVE_S1.); +#125653 = CIRCLE('',#125654,0.308574064194); +#125654 = AXIS2_PLACEMENT_3D('',#125655,#125656,#125657); +#125655 = CARTESIAN_POINT('',(10.728168876214,4.85,2.640924866458E-017) + ); +#125656 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125657 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125658 = PCURVE('',#125614,#125659); +#125659 = DEFINITIONAL_REPRESENTATION('',(#125660),#125663); +#125660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125661,#125662), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#123269 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#123270 = CARTESIAN_POINT('',(4.761821717947,-4.85)); -#123271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125661 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#125662 = CARTESIAN_POINT('',(4.761821717947,-4.85)); +#125663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123272 = PCURVE('',#93908,#123273); -#123273 = DEFINITIONAL_REPRESENTATION('',(#123274),#123282); -#123274 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123275,#123276,#123277, - #123278,#123279,#123280,#123281),.UNSPECIFIED.,.T.,.F.) +#125664 = PCURVE('',#96300,#125665); +#125665 = DEFINITIONAL_REPRESENTATION('',(#125666),#125674); +#125666 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125667,#125668,#125669, + #125670,#125671,#125672,#125673),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#123275 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#123276 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#123277 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#123278 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#123279 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#123280 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#123281 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#123282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123283 = ORIENTED_EDGE('',*,*,#123206,.T.); -#123284 = ORIENTED_EDGE('',*,*,#123285,.F.); -#123285 = EDGE_CURVE('',#123286,#123184,#123288,.T.); -#123286 = VERTEX_POINT('',#123287); -#123287 = CARTESIAN_POINT('',(10.419594812019,4.65,0.E+000)); -#123288 = SURFACE_CURVE('',#123289,(#123294,#123300),.PCURVE_S1.); -#123289 = CIRCLE('',#123290,0.308574064194); -#123290 = AXIS2_PLACEMENT_3D('',#123291,#123292,#123293); -#123291 = CARTESIAN_POINT('',(10.728168876214,4.65,2.640924866458E-017) - ); -#123292 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123293 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123294 = PCURVE('',#123222,#123295); -#123295 = DEFINITIONAL_REPRESENTATION('',(#123296),#123299); -#123296 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123297,#123298), +#125667 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#125668 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#125669 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#125670 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#125671 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#125672 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#125673 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#125674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125675 = ORIENTED_EDGE('',*,*,#125598,.T.); +#125676 = ORIENTED_EDGE('',*,*,#125677,.F.); +#125677 = EDGE_CURVE('',#125678,#125576,#125680,.T.); +#125678 = VERTEX_POINT('',#125679); +#125679 = CARTESIAN_POINT('',(10.419594812019,4.65,0.E+000)); +#125680 = SURFACE_CURVE('',#125681,(#125686,#125692),.PCURVE_S1.); +#125681 = CIRCLE('',#125682,0.308574064194); +#125682 = AXIS2_PLACEMENT_3D('',#125683,#125684,#125685); +#125683 = CARTESIAN_POINT('',(10.728168876214,4.65,2.640924866458E-017) + ); +#125684 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125685 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125686 = PCURVE('',#125614,#125687); +#125687 = DEFINITIONAL_REPRESENTATION('',(#125688),#125691); +#125688 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125689,#125690), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#123297 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#123298 = CARTESIAN_POINT('',(4.761821717947,-4.65)); -#123299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125689 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#125690 = CARTESIAN_POINT('',(4.761821717947,-4.65)); +#125691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123300 = PCURVE('',#93962,#123301); -#123301 = DEFINITIONAL_REPRESENTATION('',(#123302),#123306); -#123302 = CIRCLE('',#123303,0.308574064194); -#123303 = AXIS2_PLACEMENT_2D('',#123304,#123305); -#123304 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#123305 = DIRECTION('',(0.E+000,1.)); -#123306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125692 = PCURVE('',#96354,#125693); +#125693 = DEFINITIONAL_REPRESENTATION('',(#125694),#125698); +#125694 = CIRCLE('',#125695,0.308574064194); +#125695 = AXIS2_PLACEMENT_2D('',#125696,#125697); +#125696 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#125697 = DIRECTION('',(0.E+000,1.)); +#125698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123307 = ORIENTED_EDGE('',*,*,#123308,.T.); -#123308 = EDGE_CURVE('',#123286,#123258,#123309,.T.); -#123309 = SURFACE_CURVE('',#123310,(#123314,#123320),.PCURVE_S1.); -#123310 = LINE('',#123311,#123312); -#123311 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#125699 = ORIENTED_EDGE('',*,*,#125700,.T.); +#125700 = EDGE_CURVE('',#125678,#125650,#125701,.T.); +#125701 = SURFACE_CURVE('',#125702,(#125706,#125712),.PCURVE_S1.); +#125702 = LINE('',#125703,#125704); +#125703 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#123312 = VECTOR('',#123313,1.); -#123313 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123314 = PCURVE('',#123222,#123315); -#123315 = DEFINITIONAL_REPRESENTATION('',(#123316),#123319); -#123316 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123317,#123318), +#125704 = VECTOR('',#125705,1.); +#125705 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125706 = PCURVE('',#125614,#125707); +#125707 = DEFINITIONAL_REPRESENTATION('',(#125708),#125711); +#125708 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125709,#125710), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#123317 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#123318 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#123319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125709 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#125710 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#125711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123320 = PCURVE('',#123321,#123326); -#123321 = PLANE('',#123322); -#123322 = AXIS2_PLACEMENT_3D('',#123323,#123324,#123325); -#123323 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#125712 = PCURVE('',#125713,#125718); +#125713 = PLANE('',#125714); +#125714 = AXIS2_PLACEMENT_3D('',#125715,#125716,#125717); +#125715 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#123324 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123325 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123326 = DEFINITIONAL_REPRESENTATION('',(#123327),#123331); -#123327 = LINE('',#123328,#123329); -#123328 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#123329 = VECTOR('',#123330,1.); -#123330 = DIRECTION('',(-1.,0.E+000)); -#123331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123332 = ADVANCED_FACE('',(#123333),#123118,.F.); -#123333 = FACE_BOUND('',#123334,.F.); -#123334 = EDGE_LOOP('',(#123335,#123358,#123385,#123410)); -#123335 = ORIENTED_EDGE('',*,*,#123336,.F.); -#123336 = EDGE_CURVE('',#123337,#123103,#123339,.T.); -#123337 = VERTEX_POINT('',#123338); -#123338 = CARTESIAN_POINT('',(10.51959417205,4.65,0.E+000)); -#123339 = SURFACE_CURVE('',#123340,(#123345,#123351),.PCURVE_S1.); -#123340 = CIRCLE('',#123341,0.208574704164); -#123341 = AXIS2_PLACEMENT_3D('',#123342,#123343,#123344); -#123342 = CARTESIAN_POINT('',(10.728168876214,4.65,2.640924866458E-017) - ); -#123343 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123344 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123345 = PCURVE('',#123118,#123346); -#123346 = DEFINITIONAL_REPRESENTATION('',(#123347),#123350); -#123347 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123348,#123349), +#125716 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125717 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125718 = DEFINITIONAL_REPRESENTATION('',(#125719),#125723); +#125719 = LINE('',#125720,#125721); +#125720 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#125721 = VECTOR('',#125722,1.); +#125722 = DIRECTION('',(-1.,0.E+000)); +#125723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125724 = ADVANCED_FACE('',(#125725),#125510,.F.); +#125725 = FACE_BOUND('',#125726,.F.); +#125726 = EDGE_LOOP('',(#125727,#125750,#125777,#125802)); +#125727 = ORIENTED_EDGE('',*,*,#125728,.F.); +#125728 = EDGE_CURVE('',#125729,#125495,#125731,.T.); +#125729 = VERTEX_POINT('',#125730); +#125730 = CARTESIAN_POINT('',(10.51959417205,4.65,0.E+000)); +#125731 = SURFACE_CURVE('',#125732,(#125737,#125743),.PCURVE_S1.); +#125732 = CIRCLE('',#125733,0.208574704164); +#125733 = AXIS2_PLACEMENT_3D('',#125734,#125735,#125736); +#125734 = CARTESIAN_POINT('',(10.728168876214,4.65,2.640924866458E-017) + ); +#125735 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125736 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125737 = PCURVE('',#125510,#125738); +#125738 = DEFINITIONAL_REPRESENTATION('',(#125739),#125742); +#125739 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125740,#125741), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#123348 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#123349 = CARTESIAN_POINT('',(4.772630242227,-4.65)); -#123350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125740 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#125741 = CARTESIAN_POINT('',(4.772630242227,-4.65)); +#125742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123351 = PCURVE('',#93962,#123352); -#123352 = DEFINITIONAL_REPRESENTATION('',(#123353),#123357); -#123353 = CIRCLE('',#123354,0.208574704164); -#123354 = AXIS2_PLACEMENT_2D('',#123355,#123356); -#123355 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#123356 = DIRECTION('',(0.E+000,1.)); -#123357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125743 = PCURVE('',#96354,#125744); +#125744 = DEFINITIONAL_REPRESENTATION('',(#125745),#125749); +#125745 = CIRCLE('',#125746,0.208574704164); +#125746 = AXIS2_PLACEMENT_2D('',#125747,#125748); +#125747 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#125748 = DIRECTION('',(0.E+000,1.)); +#125749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123358 = ORIENTED_EDGE('',*,*,#123359,.F.); -#123359 = EDGE_CURVE('',#123360,#123337,#123362,.T.); -#123360 = VERTEX_POINT('',#123361); -#123361 = CARTESIAN_POINT('',(10.51959417205,4.85,0.E+000)); -#123362 = SURFACE_CURVE('',#123363,(#123367,#123373),.PCURVE_S1.); -#123363 = LINE('',#123364,#123365); -#123364 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#125750 = ORIENTED_EDGE('',*,*,#125751,.F.); +#125751 = EDGE_CURVE('',#125752,#125729,#125754,.T.); +#125752 = VERTEX_POINT('',#125753); +#125753 = CARTESIAN_POINT('',(10.51959417205,4.85,0.E+000)); +#125754 = SURFACE_CURVE('',#125755,(#125759,#125765),.PCURVE_S1.); +#125755 = LINE('',#125756,#125757); +#125756 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#123365 = VECTOR('',#123366,1.); -#123366 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123367 = PCURVE('',#123118,#123368); -#123368 = DEFINITIONAL_REPRESENTATION('',(#123369),#123372); -#123369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123370,#123371), +#125757 = VECTOR('',#125758,1.); +#125758 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125759 = PCURVE('',#125510,#125760); +#125760 = DEFINITIONAL_REPRESENTATION('',(#125761),#125764); +#125761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125762,#125763), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#123370 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#123371 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#123372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125762 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#125763 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#125764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123373 = PCURVE('',#123374,#123379); -#123374 = PLANE('',#123375); -#123375 = AXIS2_PLACEMENT_3D('',#123376,#123377,#123378); -#123376 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#125765 = PCURVE('',#125766,#125771); +#125766 = PLANE('',#125767); +#125767 = AXIS2_PLACEMENT_3D('',#125768,#125769,#125770); +#125768 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#123377 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123378 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123379 = DEFINITIONAL_REPRESENTATION('',(#123380),#123384); -#123380 = LINE('',#123381,#123382); -#123381 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#123382 = VECTOR('',#123383,1.); -#123383 = DIRECTION('',(-1.,0.E+000)); -#123384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123385 = ORIENTED_EDGE('',*,*,#123386,.T.); -#123386 = EDGE_CURVE('',#123360,#123080,#123387,.T.); -#123387 = SURFACE_CURVE('',#123388,(#123393,#123399),.PCURVE_S1.); -#123388 = CIRCLE('',#123389,0.208574704164); -#123389 = AXIS2_PLACEMENT_3D('',#123390,#123391,#123392); -#123390 = CARTESIAN_POINT('',(10.728168876214,4.85,2.640924866458E-017) - ); -#123391 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123392 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123393 = PCURVE('',#123118,#123394); -#123394 = DEFINITIONAL_REPRESENTATION('',(#123395),#123398); -#123395 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123396,#123397), +#125769 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125770 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125771 = DEFINITIONAL_REPRESENTATION('',(#125772),#125776); +#125772 = LINE('',#125773,#125774); +#125773 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#125774 = VECTOR('',#125775,1.); +#125775 = DIRECTION('',(-1.,0.E+000)); +#125776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125777 = ORIENTED_EDGE('',*,*,#125778,.T.); +#125778 = EDGE_CURVE('',#125752,#125472,#125779,.T.); +#125779 = SURFACE_CURVE('',#125780,(#125785,#125791),.PCURVE_S1.); +#125780 = CIRCLE('',#125781,0.208574704164); +#125781 = AXIS2_PLACEMENT_3D('',#125782,#125783,#125784); +#125782 = CARTESIAN_POINT('',(10.728168876214,4.85,2.640924866458E-017) + ); +#125783 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125784 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#125785 = PCURVE('',#125510,#125786); +#125786 = DEFINITIONAL_REPRESENTATION('',(#125787),#125790); +#125787 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125788,#125789), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#123396 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#123397 = CARTESIAN_POINT('',(4.772630242227,-4.85)); -#123398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#125788 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#125789 = CARTESIAN_POINT('',(4.772630242227,-4.85)); +#125790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123399 = PCURVE('',#93908,#123400); -#123400 = DEFINITIONAL_REPRESENTATION('',(#123401),#123409); -#123401 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123402,#123403,#123404, - #123405,#123406,#123407,#123408),.UNSPECIFIED.,.T.,.F.) +#125791 = PCURVE('',#96300,#125792); +#125792 = DEFINITIONAL_REPRESENTATION('',(#125793),#125801); +#125793 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125794,#125795,#125796, + #125797,#125798,#125799,#125800),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#123402 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#123403 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#123404 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#123405 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#123406 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#123407 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#123408 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#123409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123410 = ORIENTED_EDGE('',*,*,#123102,.F.); -#123411 = ADVANCED_FACE('',(#123412),#123374,.T.); -#123412 = FACE_BOUND('',#123413,.T.); -#123413 = EDGE_LOOP('',(#123414,#123443,#123464,#123465)); -#123414 = ORIENTED_EDGE('',*,*,#123415,.T.); -#123415 = EDGE_CURVE('',#123416,#123418,#123420,.T.); -#123416 = VERTEX_POINT('',#123417); -#123417 = CARTESIAN_POINT('',(10.51959417205,4.85,0.530776333563)); -#123418 = VERTEX_POINT('',#123419); -#123419 = CARTESIAN_POINT('',(10.51959417205,4.65,0.530776333563)); -#123420 = SURFACE_CURVE('',#123421,(#123425,#123432),.PCURVE_S1.); -#123421 = LINE('',#123422,#123423); -#123422 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#125794 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#125795 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#125796 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#125797 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#125798 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#125799 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#125800 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#125801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125802 = ORIENTED_EDGE('',*,*,#125494,.F.); +#125803 = ADVANCED_FACE('',(#125804),#125766,.T.); +#125804 = FACE_BOUND('',#125805,.T.); +#125805 = EDGE_LOOP('',(#125806,#125835,#125856,#125857)); +#125806 = ORIENTED_EDGE('',*,*,#125807,.T.); +#125807 = EDGE_CURVE('',#125808,#125810,#125812,.T.); +#125808 = VERTEX_POINT('',#125809); +#125809 = CARTESIAN_POINT('',(10.51959417205,4.85,0.530776333563)); +#125810 = VERTEX_POINT('',#125811); +#125811 = CARTESIAN_POINT('',(10.51959417205,4.65,0.530776333563)); +#125812 = SURFACE_CURVE('',#125813,(#125817,#125824),.PCURVE_S1.); +#125813 = LINE('',#125814,#125815); +#125814 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#123423 = VECTOR('',#123424,1.); -#123424 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123425 = PCURVE('',#123374,#123426); -#123426 = DEFINITIONAL_REPRESENTATION('',(#123427),#123431); -#123427 = LINE('',#123428,#123429); -#123428 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123429 = VECTOR('',#123430,1.); -#123430 = DIRECTION('',(-1.,0.E+000)); -#123431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123432 = PCURVE('',#123433,#123438); -#123433 = CYLINDRICAL_SURFACE('',#123434,0.2192697516); -#123434 = AXIS2_PLACEMENT_3D('',#123435,#123436,#123437); -#123435 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#125815 = VECTOR('',#125816,1.); +#125816 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125817 = PCURVE('',#125766,#125818); +#125818 = DEFINITIONAL_REPRESENTATION('',(#125819),#125823); +#125819 = LINE('',#125820,#125821); +#125820 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125821 = VECTOR('',#125822,1.); +#125822 = DIRECTION('',(-1.,0.E+000)); +#125823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125824 = PCURVE('',#125825,#125830); +#125825 = CYLINDRICAL_SURFACE('',#125826,0.2192697516); +#125826 = AXIS2_PLACEMENT_3D('',#125827,#125828,#125829); +#125827 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#123436 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123437 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123438 = DEFINITIONAL_REPRESENTATION('',(#123439),#123442); -#123439 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123440,#123441), +#125828 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125829 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125830 = DEFINITIONAL_REPRESENTATION('',(#125831),#125834); +#125831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125832,#125833), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#123440 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#123441 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#123442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123443 = ORIENTED_EDGE('',*,*,#123444,.T.); -#123444 = EDGE_CURVE('',#123418,#123337,#123445,.T.); -#123445 = SURFACE_CURVE('',#123446,(#123450,#123457),.PCURVE_S1.); -#123446 = LINE('',#123447,#123448); -#123447 = CARTESIAN_POINT('',(10.51959417205,4.65,0.530776333563)); -#123448 = VECTOR('',#123449,1.); -#123449 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#123450 = PCURVE('',#123374,#123451); -#123451 = DEFINITIONAL_REPRESENTATION('',(#123452),#123456); -#123452 = LINE('',#123453,#123454); -#123453 = CARTESIAN_POINT('',(4.65,0.E+000)); -#123454 = VECTOR('',#123455,1.); -#123455 = DIRECTION('',(0.E+000,-1.)); -#123456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123457 = PCURVE('',#93962,#123458); -#123458 = DEFINITIONAL_REPRESENTATION('',(#123459),#123463); -#123459 = LINE('',#123460,#123461); -#123460 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#123461 = VECTOR('',#123462,1.); -#123462 = DIRECTION('',(1.,0.E+000)); -#123463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123464 = ORIENTED_EDGE('',*,*,#123359,.F.); -#123465 = ORIENTED_EDGE('',*,*,#123466,.F.); -#123466 = EDGE_CURVE('',#123416,#123360,#123467,.T.); -#123467 = SURFACE_CURVE('',#123468,(#123472,#123479),.PCURVE_S1.); -#123468 = LINE('',#123469,#123470); -#123469 = CARTESIAN_POINT('',(10.51959417205,4.85,0.530776333563)); -#123470 = VECTOR('',#123471,1.); -#123471 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#123472 = PCURVE('',#123374,#123473); -#123473 = DEFINITIONAL_REPRESENTATION('',(#123474),#123478); -#123474 = LINE('',#123475,#123476); -#123475 = CARTESIAN_POINT('',(4.85,0.E+000)); -#123476 = VECTOR('',#123477,1.); -#123477 = DIRECTION('',(0.E+000,-1.)); -#123478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123479 = PCURVE('',#93908,#123480); -#123480 = DEFINITIONAL_REPRESENTATION('',(#123481),#123485); -#123481 = LINE('',#123482,#123483); -#123482 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#123483 = VECTOR('',#123484,1.); -#123484 = DIRECTION('',(-1.,0.E+000)); -#123485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123486 = ADVANCED_FACE('',(#123487),#123321,.T.); -#123487 = FACE_BOUND('',#123488,.T.); -#123488 = EDGE_LOOP('',(#123489,#123518,#123539,#123540)); -#123489 = ORIENTED_EDGE('',*,*,#123490,.T.); -#123490 = EDGE_CURVE('',#123491,#123493,#123495,.T.); -#123491 = VERTEX_POINT('',#123492); -#123492 = CARTESIAN_POINT('',(10.419594812019,4.65,0.530776333563)); -#123493 = VERTEX_POINT('',#123494); -#123494 = CARTESIAN_POINT('',(10.419594812019,4.85,0.530776333563)); -#123495 = SURFACE_CURVE('',#123496,(#123500,#123507),.PCURVE_S1.); -#123496 = LINE('',#123497,#123498); -#123497 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#125832 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#125833 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#125834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125835 = ORIENTED_EDGE('',*,*,#125836,.T.); +#125836 = EDGE_CURVE('',#125810,#125729,#125837,.T.); +#125837 = SURFACE_CURVE('',#125838,(#125842,#125849),.PCURVE_S1.); +#125838 = LINE('',#125839,#125840); +#125839 = CARTESIAN_POINT('',(10.51959417205,4.65,0.530776333563)); +#125840 = VECTOR('',#125841,1.); +#125841 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125842 = PCURVE('',#125766,#125843); +#125843 = DEFINITIONAL_REPRESENTATION('',(#125844),#125848); +#125844 = LINE('',#125845,#125846); +#125845 = CARTESIAN_POINT('',(4.65,0.E+000)); +#125846 = VECTOR('',#125847,1.); +#125847 = DIRECTION('',(0.E+000,-1.)); +#125848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125849 = PCURVE('',#96354,#125850); +#125850 = DEFINITIONAL_REPRESENTATION('',(#125851),#125855); +#125851 = LINE('',#125852,#125853); +#125852 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#125853 = VECTOR('',#125854,1.); +#125854 = DIRECTION('',(1.,0.E+000)); +#125855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125856 = ORIENTED_EDGE('',*,*,#125751,.F.); +#125857 = ORIENTED_EDGE('',*,*,#125858,.F.); +#125858 = EDGE_CURVE('',#125808,#125752,#125859,.T.); +#125859 = SURFACE_CURVE('',#125860,(#125864,#125871),.PCURVE_S1.); +#125860 = LINE('',#125861,#125862); +#125861 = CARTESIAN_POINT('',(10.51959417205,4.85,0.530776333563)); +#125862 = VECTOR('',#125863,1.); +#125863 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125864 = PCURVE('',#125766,#125865); +#125865 = DEFINITIONAL_REPRESENTATION('',(#125866),#125870); +#125866 = LINE('',#125867,#125868); +#125867 = CARTESIAN_POINT('',(4.85,0.E+000)); +#125868 = VECTOR('',#125869,1.); +#125869 = DIRECTION('',(0.E+000,-1.)); +#125870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125871 = PCURVE('',#96300,#125872); +#125872 = DEFINITIONAL_REPRESENTATION('',(#125873),#125877); +#125873 = LINE('',#125874,#125875); +#125874 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#125875 = VECTOR('',#125876,1.); +#125876 = DIRECTION('',(-1.,0.E+000)); +#125877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125878 = ADVANCED_FACE('',(#125879),#125713,.T.); +#125879 = FACE_BOUND('',#125880,.T.); +#125880 = EDGE_LOOP('',(#125881,#125910,#125931,#125932)); +#125881 = ORIENTED_EDGE('',*,*,#125882,.T.); +#125882 = EDGE_CURVE('',#125883,#125885,#125887,.T.); +#125883 = VERTEX_POINT('',#125884); +#125884 = CARTESIAN_POINT('',(10.419594812019,4.65,0.530776333563)); +#125885 = VERTEX_POINT('',#125886); +#125886 = CARTESIAN_POINT('',(10.419594812019,4.85,0.530776333563)); +#125887 = SURFACE_CURVE('',#125888,(#125892,#125899),.PCURVE_S1.); +#125888 = LINE('',#125889,#125890); +#125889 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#123498 = VECTOR('',#123499,1.); -#123499 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123500 = PCURVE('',#123321,#123501); -#123501 = DEFINITIONAL_REPRESENTATION('',(#123502),#123506); -#123502 = LINE('',#123503,#123504); -#123503 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123504 = VECTOR('',#123505,1.); -#123505 = DIRECTION('',(-1.,0.E+000)); -#123506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123507 = PCURVE('',#123508,#123513); -#123508 = CYLINDRICAL_SURFACE('',#123509,0.119270391569); -#123509 = AXIS2_PLACEMENT_3D('',#123510,#123511,#123512); -#123510 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#125890 = VECTOR('',#125891,1.); +#125891 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125892 = PCURVE('',#125713,#125893); +#125893 = DEFINITIONAL_REPRESENTATION('',(#125894),#125898); +#125894 = LINE('',#125895,#125896); +#125895 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#125896 = VECTOR('',#125897,1.); +#125897 = DIRECTION('',(-1.,0.E+000)); +#125898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125899 = PCURVE('',#125900,#125905); +#125900 = CYLINDRICAL_SURFACE('',#125901,0.119270391569); +#125901 = AXIS2_PLACEMENT_3D('',#125902,#125903,#125904); +#125902 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#123511 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123512 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123513 = DEFINITIONAL_REPRESENTATION('',(#123514),#123517); -#123514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123515,#123516), +#125903 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125904 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125905 = DEFINITIONAL_REPRESENTATION('',(#125906),#125909); +#125906 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125907,#125908), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#123515 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#123516 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#123517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123518 = ORIENTED_EDGE('',*,*,#123519,.T.); -#123519 = EDGE_CURVE('',#123493,#123258,#123520,.T.); -#123520 = SURFACE_CURVE('',#123521,(#123525,#123532),.PCURVE_S1.); -#123521 = LINE('',#123522,#123523); -#123522 = CARTESIAN_POINT('',(10.419594812019,4.85,0.530776333563)); -#123523 = VECTOR('',#123524,1.); -#123524 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#123525 = PCURVE('',#123321,#123526); -#123526 = DEFINITIONAL_REPRESENTATION('',(#123527),#123531); -#123527 = LINE('',#123528,#123529); -#123528 = CARTESIAN_POINT('',(-4.85,0.E+000)); -#123529 = VECTOR('',#123530,1.); -#123530 = DIRECTION('',(0.E+000,-1.)); -#123531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123532 = PCURVE('',#93908,#123533); -#123533 = DEFINITIONAL_REPRESENTATION('',(#123534),#123538); -#123534 = LINE('',#123535,#123536); -#123535 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#123536 = VECTOR('',#123537,1.); -#123537 = DIRECTION('',(-1.,0.E+000)); -#123538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123539 = ORIENTED_EDGE('',*,*,#123308,.F.); -#123540 = ORIENTED_EDGE('',*,*,#123541,.F.); -#123541 = EDGE_CURVE('',#123491,#123286,#123542,.T.); -#123542 = SURFACE_CURVE('',#123543,(#123547,#123554),.PCURVE_S1.); -#123543 = LINE('',#123544,#123545); -#123544 = CARTESIAN_POINT('',(10.419594812019,4.65,0.530776333563)); -#123545 = VECTOR('',#123546,1.); -#123546 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#123547 = PCURVE('',#123321,#123548); -#123548 = DEFINITIONAL_REPRESENTATION('',(#123549),#123553); -#123549 = LINE('',#123550,#123551); -#123550 = CARTESIAN_POINT('',(-4.65,0.E+000)); -#123551 = VECTOR('',#123552,1.); -#123552 = DIRECTION('',(0.E+000,-1.)); -#123553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123554 = PCURVE('',#93962,#123555); -#123555 = DEFINITIONAL_REPRESENTATION('',(#123556),#123560); -#123556 = LINE('',#123557,#123558); -#123557 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#123558 = VECTOR('',#123559,1.); -#123559 = DIRECTION('',(1.,0.E+000)); -#123560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123561 = ADVANCED_FACE('',(#123562),#123508,.F.); -#123562 = FACE_BOUND('',#123563,.F.); -#123563 = EDGE_LOOP('',(#123564,#123565,#123588,#123610)); -#123564 = ORIENTED_EDGE('',*,*,#123490,.T.); -#123565 = ORIENTED_EDGE('',*,*,#123566,.F.); -#123566 = EDGE_CURVE('',#123567,#123493,#123569,.T.); -#123567 = VERTEX_POINT('',#123568); -#123568 = CARTESIAN_POINT('',(10.303662633502,4.85,0.65)); -#123569 = SURFACE_CURVE('',#123570,(#123575,#123581),.PCURVE_S1.); -#123570 = CIRCLE('',#123571,0.119270391569); -#123571 = AXIS2_PLACEMENT_3D('',#123572,#123573,#123574); -#123572 = CARTESIAN_POINT('',(10.30032442045,4.85,0.530776333563)); -#123573 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123574 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123575 = PCURVE('',#123508,#123576); -#123576 = DEFINITIONAL_REPRESENTATION('',(#123577),#123580); -#123577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123578,#123579), +#125907 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#125908 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#125909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125910 = ORIENTED_EDGE('',*,*,#125911,.T.); +#125911 = EDGE_CURVE('',#125885,#125650,#125912,.T.); +#125912 = SURFACE_CURVE('',#125913,(#125917,#125924),.PCURVE_S1.); +#125913 = LINE('',#125914,#125915); +#125914 = CARTESIAN_POINT('',(10.419594812019,4.85,0.530776333563)); +#125915 = VECTOR('',#125916,1.); +#125916 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125917 = PCURVE('',#125713,#125918); +#125918 = DEFINITIONAL_REPRESENTATION('',(#125919),#125923); +#125919 = LINE('',#125920,#125921); +#125920 = CARTESIAN_POINT('',(-4.85,0.E+000)); +#125921 = VECTOR('',#125922,1.); +#125922 = DIRECTION('',(0.E+000,-1.)); +#125923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125924 = PCURVE('',#96300,#125925); +#125925 = DEFINITIONAL_REPRESENTATION('',(#125926),#125930); +#125926 = LINE('',#125927,#125928); +#125927 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#125928 = VECTOR('',#125929,1.); +#125929 = DIRECTION('',(-1.,0.E+000)); +#125930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125931 = ORIENTED_EDGE('',*,*,#125700,.F.); +#125932 = ORIENTED_EDGE('',*,*,#125933,.F.); +#125933 = EDGE_CURVE('',#125883,#125678,#125934,.T.); +#125934 = SURFACE_CURVE('',#125935,(#125939,#125946),.PCURVE_S1.); +#125935 = LINE('',#125936,#125937); +#125936 = CARTESIAN_POINT('',(10.419594812019,4.65,0.530776333563)); +#125937 = VECTOR('',#125938,1.); +#125938 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#125939 = PCURVE('',#125713,#125940); +#125940 = DEFINITIONAL_REPRESENTATION('',(#125941),#125945); +#125941 = LINE('',#125942,#125943); +#125942 = CARTESIAN_POINT('',(-4.65,0.E+000)); +#125943 = VECTOR('',#125944,1.); +#125944 = DIRECTION('',(0.E+000,-1.)); +#125945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125946 = PCURVE('',#96354,#125947); +#125947 = DEFINITIONAL_REPRESENTATION('',(#125948),#125952); +#125948 = LINE('',#125949,#125950); +#125949 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#125950 = VECTOR('',#125951,1.); +#125951 = DIRECTION('',(1.,0.E+000)); +#125952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125953 = ADVANCED_FACE('',(#125954),#125900,.F.); +#125954 = FACE_BOUND('',#125955,.F.); +#125955 = EDGE_LOOP('',(#125956,#125957,#125980,#126002)); +#125956 = ORIENTED_EDGE('',*,*,#125882,.T.); +#125957 = ORIENTED_EDGE('',*,*,#125958,.F.); +#125958 = EDGE_CURVE('',#125959,#125885,#125961,.T.); +#125959 = VERTEX_POINT('',#125960); +#125960 = CARTESIAN_POINT('',(10.303662633502,4.85,0.65)); +#125961 = SURFACE_CURVE('',#125962,(#125967,#125973),.PCURVE_S1.); +#125962 = CIRCLE('',#125963,0.119270391569); +#125963 = AXIS2_PLACEMENT_3D('',#125964,#125965,#125966); +#125964 = CARTESIAN_POINT('',(10.30032442045,4.85,0.530776333563)); +#125965 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#125966 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#125967 = PCURVE('',#125900,#125968); +#125968 = DEFINITIONAL_REPRESENTATION('',(#125969),#125972); +#125969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125970,#125971), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#123578 = CARTESIAN_POINT('',(1.598788597134,4.85)); -#123579 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#123580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123581 = PCURVE('',#93908,#123582); -#123582 = DEFINITIONAL_REPRESENTATION('',(#123583),#123587); -#123583 = CIRCLE('',#123584,0.119270391569); -#123584 = AXIS2_PLACEMENT_2D('',#123585,#123586); -#123585 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#123586 = DIRECTION('',(0.E+000,-1.)); -#123587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123588 = ORIENTED_EDGE('',*,*,#123589,.T.); -#123589 = EDGE_CURVE('',#123567,#123590,#123592,.T.); -#123590 = VERTEX_POINT('',#123591); -#123591 = CARTESIAN_POINT('',(10.303662633502,4.65,0.65)); -#123592 = SURFACE_CURVE('',#123593,(#123597,#123603),.PCURVE_S1.); -#123593 = LINE('',#123594,#123595); -#123594 = CARTESIAN_POINT('',(10.303662633502,4.85,0.65)); -#123595 = VECTOR('',#123596,1.); -#123596 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123597 = PCURVE('',#123508,#123598); -#123598 = DEFINITIONAL_REPRESENTATION('',(#123599),#123602); -#123599 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123600,#123601), +#125970 = CARTESIAN_POINT('',(1.598788597134,4.85)); +#125971 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#125972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125973 = PCURVE('',#96300,#125974); +#125974 = DEFINITIONAL_REPRESENTATION('',(#125975),#125979); +#125975 = CIRCLE('',#125976,0.119270391569); +#125976 = AXIS2_PLACEMENT_2D('',#125977,#125978); +#125977 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#125978 = DIRECTION('',(0.E+000,-1.)); +#125979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125980 = ORIENTED_EDGE('',*,*,#125981,.T.); +#125981 = EDGE_CURVE('',#125959,#125982,#125984,.T.); +#125982 = VERTEX_POINT('',#125983); +#125983 = CARTESIAN_POINT('',(10.303662633502,4.65,0.65)); +#125984 = SURFACE_CURVE('',#125985,(#125989,#125995),.PCURVE_S1.); +#125985 = LINE('',#125986,#125987); +#125986 = CARTESIAN_POINT('',(10.303662633502,4.85,0.65)); +#125987 = VECTOR('',#125988,1.); +#125988 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#125989 = PCURVE('',#125900,#125990); +#125990 = DEFINITIONAL_REPRESENTATION('',(#125991),#125994); +#125991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125992,#125993), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#123600 = CARTESIAN_POINT('',(1.598788597134,4.85)); -#123601 = CARTESIAN_POINT('',(1.598788597134,4.65)); -#123602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123603 = PCURVE('',#93936,#123604); -#123604 = DEFINITIONAL_REPRESENTATION('',(#123605),#123609); -#123605 = LINE('',#123606,#123607); -#123606 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#123607 = VECTOR('',#123608,1.); -#123608 = DIRECTION('',(4.440892098501E-016,-1.)); -#123609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123610 = ORIENTED_EDGE('',*,*,#123611,.T.); -#123611 = EDGE_CURVE('',#123590,#123491,#123612,.T.); -#123612 = SURFACE_CURVE('',#123613,(#123618,#123624),.PCURVE_S1.); -#123613 = CIRCLE('',#123614,0.119270391569); -#123614 = AXIS2_PLACEMENT_3D('',#123615,#123616,#123617); -#123615 = CARTESIAN_POINT('',(10.30032442045,4.65,0.530776333563)); -#123616 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123617 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123618 = PCURVE('',#123508,#123619); -#123619 = DEFINITIONAL_REPRESENTATION('',(#123620),#123623); -#123620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123621,#123622), +#125992 = CARTESIAN_POINT('',(1.598788597134,4.85)); +#125993 = CARTESIAN_POINT('',(1.598788597134,4.65)); +#125994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#125995 = PCURVE('',#96328,#125996); +#125996 = DEFINITIONAL_REPRESENTATION('',(#125997),#126001); +#125997 = LINE('',#125998,#125999); +#125998 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#125999 = VECTOR('',#126000,1.); +#126000 = DIRECTION('',(4.440892098501E-016,-1.)); +#126001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126002 = ORIENTED_EDGE('',*,*,#126003,.T.); +#126003 = EDGE_CURVE('',#125982,#125883,#126004,.T.); +#126004 = SURFACE_CURVE('',#126005,(#126010,#126016),.PCURVE_S1.); +#126005 = CIRCLE('',#126006,0.119270391569); +#126006 = AXIS2_PLACEMENT_3D('',#126007,#126008,#126009); +#126007 = CARTESIAN_POINT('',(10.30032442045,4.65,0.530776333563)); +#126008 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126009 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126010 = PCURVE('',#125900,#126011); +#126011 = DEFINITIONAL_REPRESENTATION('',(#126012),#126015); +#126012 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126013,#126014), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#123621 = CARTESIAN_POINT('',(1.598788597134,4.65)); -#123622 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#123623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126013 = CARTESIAN_POINT('',(1.598788597134,4.65)); +#126014 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#126015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123624 = PCURVE('',#93962,#123625); -#123625 = DEFINITIONAL_REPRESENTATION('',(#123626),#123634); -#123626 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123627,#123628,#123629, - #123630,#123631,#123632,#123633),.UNSPECIFIED.,.T.,.F.) +#126016 = PCURVE('',#96354,#126017); +#126017 = DEFINITIONAL_REPRESENTATION('',(#126018),#126026); +#126018 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126019,#126020,#126021, + #126022,#126023,#126024,#126025),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#123627 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#123628 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#123629 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#123630 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#123631 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#123632 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#123633 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#123634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123635 = ADVANCED_FACE('',(#123636),#123433,.T.); -#123636 = FACE_BOUND('',#123637,.T.); -#123637 = EDGE_LOOP('',(#123638,#123639,#123662,#123684)); -#123638 = ORIENTED_EDGE('',*,*,#123415,.F.); -#123639 = ORIENTED_EDGE('',*,*,#123640,.F.); -#123640 = EDGE_CURVE('',#123641,#123416,#123643,.T.); -#123641 = VERTEX_POINT('',#123642); -#123642 = CARTESIAN_POINT('',(10.304819755875,4.85,0.75)); -#123643 = SURFACE_CURVE('',#123644,(#123649,#123655),.PCURVE_S1.); -#123644 = CIRCLE('',#123645,0.2192697516); -#123645 = AXIS2_PLACEMENT_3D('',#123646,#123647,#123648); -#123646 = CARTESIAN_POINT('',(10.30032442045,4.85,0.530776333563)); -#123647 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123648 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123649 = PCURVE('',#123433,#123650); -#123650 = DEFINITIONAL_REPRESENTATION('',(#123651),#123654); -#123651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123652,#123653), +#126019 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#126020 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#126021 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#126022 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#126023 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#126024 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#126025 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#126026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126027 = ADVANCED_FACE('',(#126028),#125825,.T.); +#126028 = FACE_BOUND('',#126029,.T.); +#126029 = EDGE_LOOP('',(#126030,#126031,#126054,#126076)); +#126030 = ORIENTED_EDGE('',*,*,#125807,.F.); +#126031 = ORIENTED_EDGE('',*,*,#126032,.F.); +#126032 = EDGE_CURVE('',#126033,#125808,#126035,.T.); +#126033 = VERTEX_POINT('',#126034); +#126034 = CARTESIAN_POINT('',(10.304819755875,4.85,0.75)); +#126035 = SURFACE_CURVE('',#126036,(#126041,#126047),.PCURVE_S1.); +#126036 = CIRCLE('',#126037,0.2192697516); +#126037 = AXIS2_PLACEMENT_3D('',#126038,#126039,#126040); +#126038 = CARTESIAN_POINT('',(10.30032442045,4.85,0.530776333563)); +#126039 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126040 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126041 = PCURVE('',#125825,#126042); +#126042 = DEFINITIONAL_REPRESENTATION('',(#126043),#126046); +#126043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126044,#126045), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#123652 = CARTESIAN_POINT('',(1.591299156552,4.85)); -#123653 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#123654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123655 = PCURVE('',#93908,#123656); -#123656 = DEFINITIONAL_REPRESENTATION('',(#123657),#123661); -#123657 = CIRCLE('',#123658,0.2192697516); -#123658 = AXIS2_PLACEMENT_2D('',#123659,#123660); -#123659 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#123660 = DIRECTION('',(0.E+000,-1.)); -#123661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123662 = ORIENTED_EDGE('',*,*,#123663,.F.); -#123663 = EDGE_CURVE('',#123664,#123641,#123666,.T.); -#123664 = VERTEX_POINT('',#123665); -#123665 = CARTESIAN_POINT('',(10.304819755875,4.65,0.75)); -#123666 = SURFACE_CURVE('',#123667,(#123671,#123677),.PCURVE_S1.); -#123667 = LINE('',#123668,#123669); -#123668 = CARTESIAN_POINT('',(10.304819755875,4.85,0.75)); -#123669 = VECTOR('',#123670,1.); -#123670 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123671 = PCURVE('',#123433,#123672); -#123672 = DEFINITIONAL_REPRESENTATION('',(#123673),#123676); -#123673 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123674,#123675), +#126044 = CARTESIAN_POINT('',(1.591299156552,4.85)); +#126045 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#126046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126047 = PCURVE('',#96300,#126048); +#126048 = DEFINITIONAL_REPRESENTATION('',(#126049),#126053); +#126049 = CIRCLE('',#126050,0.2192697516); +#126050 = AXIS2_PLACEMENT_2D('',#126051,#126052); +#126051 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#126052 = DIRECTION('',(0.E+000,-1.)); +#126053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126054 = ORIENTED_EDGE('',*,*,#126055,.F.); +#126055 = EDGE_CURVE('',#126056,#126033,#126058,.T.); +#126056 = VERTEX_POINT('',#126057); +#126057 = CARTESIAN_POINT('',(10.304819755875,4.65,0.75)); +#126058 = SURFACE_CURVE('',#126059,(#126063,#126069),.PCURVE_S1.); +#126059 = LINE('',#126060,#126061); +#126060 = CARTESIAN_POINT('',(10.304819755875,4.85,0.75)); +#126061 = VECTOR('',#126062,1.); +#126062 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126063 = PCURVE('',#125825,#126064); +#126064 = DEFINITIONAL_REPRESENTATION('',(#126065),#126068); +#126065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126066,#126067), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#123674 = CARTESIAN_POINT('',(1.591299156552,4.65)); -#123675 = CARTESIAN_POINT('',(1.591299156552,4.85)); -#123676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123677 = PCURVE('',#93880,#123678); -#123678 = DEFINITIONAL_REPRESENTATION('',(#123679),#123683); -#123679 = LINE('',#123680,#123681); -#123680 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#123681 = VECTOR('',#123682,1.); -#123682 = DIRECTION('',(4.440892098501E-016,1.)); -#123683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123684 = ORIENTED_EDGE('',*,*,#123685,.T.); -#123685 = EDGE_CURVE('',#123664,#123418,#123686,.T.); -#123686 = SURFACE_CURVE('',#123687,(#123692,#123698),.PCURVE_S1.); -#123687 = CIRCLE('',#123688,0.2192697516); -#123688 = AXIS2_PLACEMENT_3D('',#123689,#123690,#123691); -#123689 = CARTESIAN_POINT('',(10.30032442045,4.65,0.530776333563)); -#123690 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123691 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#123692 = PCURVE('',#123433,#123693); -#123693 = DEFINITIONAL_REPRESENTATION('',(#123694),#123697); -#123694 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123695,#123696), +#126066 = CARTESIAN_POINT('',(1.591299156552,4.65)); +#126067 = CARTESIAN_POINT('',(1.591299156552,4.85)); +#126068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126069 = PCURVE('',#96272,#126070); +#126070 = DEFINITIONAL_REPRESENTATION('',(#126071),#126075); +#126071 = LINE('',#126072,#126073); +#126072 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#126073 = VECTOR('',#126074,1.); +#126074 = DIRECTION('',(4.440892098501E-016,1.)); +#126075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126076 = ORIENTED_EDGE('',*,*,#126077,.T.); +#126077 = EDGE_CURVE('',#126056,#125810,#126078,.T.); +#126078 = SURFACE_CURVE('',#126079,(#126084,#126090),.PCURVE_S1.); +#126079 = CIRCLE('',#126080,0.2192697516); +#126080 = AXIS2_PLACEMENT_3D('',#126081,#126082,#126083); +#126081 = CARTESIAN_POINT('',(10.30032442045,4.65,0.530776333563)); +#126082 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126083 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126084 = PCURVE('',#125825,#126085); +#126085 = DEFINITIONAL_REPRESENTATION('',(#126086),#126089); +#126086 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126087,#126088), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#123695 = CARTESIAN_POINT('',(1.591299156552,4.65)); -#123696 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#123697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126087 = CARTESIAN_POINT('',(1.591299156552,4.65)); +#126088 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#126089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123698 = PCURVE('',#93962,#123699); -#123699 = DEFINITIONAL_REPRESENTATION('',(#123700),#123708); -#123700 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#123701,#123702,#123703, - #123704,#123705,#123706,#123707),.UNSPECIFIED.,.T.,.F.) +#126090 = PCURVE('',#96354,#126091); +#126091 = DEFINITIONAL_REPRESENTATION('',(#126092),#126100); +#126092 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126093,#126094,#126095, + #126096,#126097,#126098,#126099),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#123701 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#123702 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#123703 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#123704 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#123705 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#123706 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#123707 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#123708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123709 = ADVANCED_FACE('',(#123710),#93908,.T.); -#123710 = FACE_BOUND('',#123711,.T.); -#123711 = EDGE_LOOP('',(#123712,#123733,#123734,#123735,#123736,#123737, - #123758,#123759,#123760,#123761,#123762,#123783)); -#123712 = ORIENTED_EDGE('',*,*,#123713,.F.); -#123713 = EDGE_CURVE('',#123641,#93865,#123714,.T.); -#123714 = SURFACE_CURVE('',#123715,(#123719,#123726),.PCURVE_S1.); -#123715 = LINE('',#123716,#123717); -#123716 = CARTESIAN_POINT('',(10.527847992439,4.85,0.75)); -#123717 = VECTOR('',#123718,1.); -#123718 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#123719 = PCURVE('',#93908,#123720); -#123720 = DEFINITIONAL_REPRESENTATION('',(#123721),#123725); -#123721 = LINE('',#123722,#123723); -#123722 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#123723 = VECTOR('',#123724,1.); -#123724 = DIRECTION('',(3.563627120235E-016,-1.)); -#123725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123726 = PCURVE('',#93880,#123727); -#123727 = DEFINITIONAL_REPRESENTATION('',(#123728),#123732); -#123728 = LINE('',#123729,#123730); -#123729 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123730 = VECTOR('',#123731,1.); -#123731 = DIRECTION('',(-1.,-1.082494723017E-063)); -#123732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123733 = ORIENTED_EDGE('',*,*,#123640,.T.); -#123734 = ORIENTED_EDGE('',*,*,#123466,.T.); -#123735 = ORIENTED_EDGE('',*,*,#123386,.T.); -#123736 = ORIENTED_EDGE('',*,*,#123079,.T.); -#123737 = ORIENTED_EDGE('',*,*,#123738,.F.); -#123738 = EDGE_CURVE('',#123156,#123045,#123739,.T.); -#123739 = SURFACE_CURVE('',#123740,(#123744,#123751),.PCURVE_S1.); -#123740 = LINE('',#123741,#123742); -#123741 = CARTESIAN_POINT('',(11.,4.85,1.159810404338E-002)); -#123742 = VECTOR('',#123743,1.); -#123743 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#123744 = PCURVE('',#93908,#123745); -#123745 = DEFINITIONAL_REPRESENTATION('',(#123746),#123750); -#123746 = LINE('',#123747,#123748); -#123747 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#123748 = VECTOR('',#123749,1.); -#123749 = DIRECTION('',(1.,2.101748079665E-016)); -#123750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123751 = PCURVE('',#123067,#123752); -#123752 = DEFINITIONAL_REPRESENTATION('',(#123753),#123757); -#123753 = LINE('',#123754,#123755); -#123754 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#123755 = VECTOR('',#123756,1.); -#123756 = DIRECTION('',(1.194699204908E-017,1.)); -#123757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123758 = ORIENTED_EDGE('',*,*,#123233,.F.); -#123759 = ORIENTED_EDGE('',*,*,#123257,.F.); -#123760 = ORIENTED_EDGE('',*,*,#123519,.F.); -#123761 = ORIENTED_EDGE('',*,*,#123566,.F.); -#123762 = ORIENTED_EDGE('',*,*,#123763,.T.); -#123763 = EDGE_CURVE('',#123567,#93893,#123764,.T.); -#123764 = SURFACE_CURVE('',#123765,(#123769,#123776),.PCURVE_S1.); -#123765 = LINE('',#123766,#123767); -#123766 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); -#123767 = VECTOR('',#123768,1.); -#123768 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#123769 = PCURVE('',#93908,#123770); -#123770 = DEFINITIONAL_REPRESENTATION('',(#123771),#123775); -#123771 = LINE('',#123772,#123773); -#123772 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123773 = VECTOR('',#123774,1.); -#123774 = DIRECTION('',(3.563627120235E-016,-1.)); -#123775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123776 = PCURVE('',#93936,#123777); -#123777 = DEFINITIONAL_REPRESENTATION('',(#123778),#123782); -#123778 = LINE('',#123779,#123780); -#123779 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123780 = VECTOR('',#123781,1.); -#123781 = DIRECTION('',(1.,-1.082494723017E-063)); -#123782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126093 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#126094 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#126095 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#126096 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#126097 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#126098 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#126099 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#126100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123783 = ORIENTED_EDGE('',*,*,#93892,.F.); -#123784 = ADVANCED_FACE('',(#123785),#93880,.T.); -#123785 = FACE_BOUND('',#123786,.T.); -#123786 = EDGE_LOOP('',(#123787,#123808,#123809,#123810)); -#123787 = ORIENTED_EDGE('',*,*,#123788,.F.); -#123788 = EDGE_CURVE('',#123664,#93863,#123789,.T.); -#123789 = SURFACE_CURVE('',#123790,(#123794,#123801),.PCURVE_S1.); -#123790 = LINE('',#123791,#123792); -#123791 = CARTESIAN_POINT('',(10.527847992439,4.65,0.75)); -#123792 = VECTOR('',#123793,1.); -#123793 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#123794 = PCURVE('',#93880,#123795); -#123795 = DEFINITIONAL_REPRESENTATION('',(#123796),#123800); -#123796 = LINE('',#123797,#123798); -#123797 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#123798 = VECTOR('',#123799,1.); -#123799 = DIRECTION('',(-1.,-1.082494723017E-063)); -#123800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123801 = PCURVE('',#93962,#123802); -#123802 = DEFINITIONAL_REPRESENTATION('',(#123803),#123807); -#123803 = LINE('',#123804,#123805); -#123804 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#123805 = VECTOR('',#123806,1.); -#123806 = DIRECTION('',(-3.563627120235E-016,-1.)); -#123807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126101 = ADVANCED_FACE('',(#126102),#96300,.T.); +#126102 = FACE_BOUND('',#126103,.T.); +#126103 = EDGE_LOOP('',(#126104,#126125,#126126,#126127,#126128,#126129, + #126150,#126151,#126152,#126153,#126154,#126175)); +#126104 = ORIENTED_EDGE('',*,*,#126105,.F.); +#126105 = EDGE_CURVE('',#126033,#96257,#126106,.T.); +#126106 = SURFACE_CURVE('',#126107,(#126111,#126118),.PCURVE_S1.); +#126107 = LINE('',#126108,#126109); +#126108 = CARTESIAN_POINT('',(10.527847992439,4.85,0.75)); +#126109 = VECTOR('',#126110,1.); +#126110 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126111 = PCURVE('',#96300,#126112); +#126112 = DEFINITIONAL_REPRESENTATION('',(#126113),#126117); +#126113 = LINE('',#126114,#126115); +#126114 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#126115 = VECTOR('',#126116,1.); +#126116 = DIRECTION('',(3.563627120235E-016,-1.)); +#126117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126118 = PCURVE('',#96272,#126119); +#126119 = DEFINITIONAL_REPRESENTATION('',(#126120),#126124); +#126120 = LINE('',#126121,#126122); +#126121 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126122 = VECTOR('',#126123,1.); +#126123 = DIRECTION('',(-1.,-1.082494723017E-063)); +#126124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126125 = ORIENTED_EDGE('',*,*,#126032,.T.); +#126126 = ORIENTED_EDGE('',*,*,#125858,.T.); +#126127 = ORIENTED_EDGE('',*,*,#125778,.T.); +#126128 = ORIENTED_EDGE('',*,*,#125471,.T.); +#126129 = ORIENTED_EDGE('',*,*,#126130,.F.); +#126130 = EDGE_CURVE('',#125548,#125437,#126131,.T.); +#126131 = SURFACE_CURVE('',#126132,(#126136,#126143),.PCURVE_S1.); +#126132 = LINE('',#126133,#126134); +#126133 = CARTESIAN_POINT('',(11.,4.85,1.159810404338E-002)); +#126134 = VECTOR('',#126135,1.); +#126135 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#126136 = PCURVE('',#96300,#126137); +#126137 = DEFINITIONAL_REPRESENTATION('',(#126138),#126142); +#126138 = LINE('',#126139,#126140); +#126139 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#126140 = VECTOR('',#126141,1.); +#126141 = DIRECTION('',(1.,2.101748079665E-016)); +#126142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126143 = PCURVE('',#125459,#126144); +#126144 = DEFINITIONAL_REPRESENTATION('',(#126145),#126149); +#126145 = LINE('',#126146,#126147); +#126146 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#126147 = VECTOR('',#126148,1.); +#126148 = DIRECTION('',(1.194699204908E-017,1.)); +#126149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126150 = ORIENTED_EDGE('',*,*,#125625,.F.); +#126151 = ORIENTED_EDGE('',*,*,#125649,.F.); +#126152 = ORIENTED_EDGE('',*,*,#125911,.F.); +#126153 = ORIENTED_EDGE('',*,*,#125958,.F.); +#126154 = ORIENTED_EDGE('',*,*,#126155,.T.); +#126155 = EDGE_CURVE('',#125959,#96285,#126156,.T.); +#126156 = SURFACE_CURVE('',#126157,(#126161,#126168),.PCURVE_S1.); +#126157 = LINE('',#126158,#126159); +#126158 = CARTESIAN_POINT('',(10.527847992439,4.85,0.65)); +#126159 = VECTOR('',#126160,1.); +#126160 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126161 = PCURVE('',#96300,#126162); +#126162 = DEFINITIONAL_REPRESENTATION('',(#126163),#126167); +#126163 = LINE('',#126164,#126165); +#126164 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126165 = VECTOR('',#126166,1.); +#126166 = DIRECTION('',(3.563627120235E-016,-1.)); +#126167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126168 = PCURVE('',#96328,#126169); +#126169 = DEFINITIONAL_REPRESENTATION('',(#126170),#126174); +#126170 = LINE('',#126171,#126172); +#126171 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126172 = VECTOR('',#126173,1.); +#126173 = DIRECTION('',(1.,-1.082494723017E-063)); +#126174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#123808 = ORIENTED_EDGE('',*,*,#123663,.T.); -#123809 = ORIENTED_EDGE('',*,*,#123713,.T.); -#123810 = ORIENTED_EDGE('',*,*,#93862,.F.); -#123811 = ADVANCED_FACE('',(#123812),#93962,.T.); -#123812 = FACE_BOUND('',#123813,.T.); -#123813 = EDGE_LOOP('',(#123814,#123835,#123836,#123837,#123838,#123839, - #123860,#123861,#123862,#123863,#123864,#123865)); -#123814 = ORIENTED_EDGE('',*,*,#123815,.F.); -#123815 = EDGE_CURVE('',#123590,#93921,#123816,.T.); -#123816 = SURFACE_CURVE('',#123817,(#123821,#123828),.PCURVE_S1.); -#123817 = LINE('',#123818,#123819); -#123818 = CARTESIAN_POINT('',(10.527847992439,4.65,0.65)); -#123819 = VECTOR('',#123820,1.); -#123820 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#123821 = PCURVE('',#93962,#123822); -#123822 = DEFINITIONAL_REPRESENTATION('',(#123823),#123827); -#123823 = LINE('',#123824,#123825); -#123824 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123825 = VECTOR('',#123826,1.); -#123826 = DIRECTION('',(-3.563627120235E-016,-1.)); -#123827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123828 = PCURVE('',#93936,#123829); -#123829 = DEFINITIONAL_REPRESENTATION('',(#123830),#123834); -#123830 = LINE('',#123831,#123832); -#123831 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#123832 = VECTOR('',#123833,1.); -#123833 = DIRECTION('',(1.,-1.082494723017E-063)); -#123834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123835 = ORIENTED_EDGE('',*,*,#123611,.T.); -#123836 = ORIENTED_EDGE('',*,*,#123541,.T.); -#123837 = ORIENTED_EDGE('',*,*,#123285,.T.); -#123838 = ORIENTED_EDGE('',*,*,#123183,.T.); -#123839 = ORIENTED_EDGE('',*,*,#123840,.F.); -#123840 = EDGE_CURVE('',#123047,#123154,#123841,.T.); -#123841 = SURFACE_CURVE('',#123842,(#123846,#123853),.PCURVE_S1.); -#123842 = LINE('',#123843,#123844); -#123843 = CARTESIAN_POINT('',(11.,4.65,1.159810404338E-002)); -#123844 = VECTOR('',#123845,1.); -#123845 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#123846 = PCURVE('',#93962,#123847); -#123847 = DEFINITIONAL_REPRESENTATION('',(#123848),#123852); -#123848 = LINE('',#123849,#123850); -#123849 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#123850 = VECTOR('',#123851,1.); -#123851 = DIRECTION('',(1.,-2.101748079665E-016)); -#123852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123853 = PCURVE('',#123067,#123854); -#123854 = DEFINITIONAL_REPRESENTATION('',(#123855),#123859); -#123855 = LINE('',#123856,#123857); -#123856 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#123857 = VECTOR('',#123858,1.); -#123858 = DIRECTION('',(-1.194699204908E-017,-1.)); -#123859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123860 = ORIENTED_EDGE('',*,*,#123129,.F.); -#123861 = ORIENTED_EDGE('',*,*,#123336,.F.); -#123862 = ORIENTED_EDGE('',*,*,#123444,.F.); -#123863 = ORIENTED_EDGE('',*,*,#123685,.F.); -#123864 = ORIENTED_EDGE('',*,*,#123788,.T.); -#123865 = ORIENTED_EDGE('',*,*,#93948,.F.); -#123866 = ADVANCED_FACE('',(#123867),#93936,.T.); -#123867 = FACE_BOUND('',#123868,.T.); -#123868 = EDGE_LOOP('',(#123869,#123870,#123871,#123872)); -#123869 = ORIENTED_EDGE('',*,*,#123763,.F.); -#123870 = ORIENTED_EDGE('',*,*,#123589,.T.); -#123871 = ORIENTED_EDGE('',*,*,#123815,.T.); -#123872 = ORIENTED_EDGE('',*,*,#93920,.F.); -#123873 = ADVANCED_FACE('',(#123874),#123067,.T.); -#123874 = FACE_BOUND('',#123875,.T.); -#123875 = EDGE_LOOP('',(#123876,#123877,#123878,#123879)); -#123876 = ORIENTED_EDGE('',*,*,#123044,.T.); -#123877 = ORIENTED_EDGE('',*,*,#123840,.T.); -#123878 = ORIENTED_EDGE('',*,*,#123153,.T.); -#123879 = ORIENTED_EDGE('',*,*,#123738,.T.); -#123880 = ADVANCED_FACE('',(#123881),#123895,.F.); -#123881 = FACE_BOUND('',#123882,.T.); -#123882 = EDGE_LOOP('',(#123883,#123918,#123941,#123968)); -#123883 = ORIENTED_EDGE('',*,*,#123884,.F.); -#123884 = EDGE_CURVE('',#123885,#123887,#123889,.T.); -#123885 = VERTEX_POINT('',#123886); -#123886 = CARTESIAN_POINT('',(11.,8.15,-0.308197125857)); -#123887 = VERTEX_POINT('',#123888); -#123888 = CARTESIAN_POINT('',(11.,8.35,-0.308197125857)); -#123889 = SURFACE_CURVE('',#123890,(#123894,#123906),.PCURVE_S1.); -#123890 = LINE('',#123891,#123892); -#123891 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#123892 = VECTOR('',#123893,1.); -#123893 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123894 = PCURVE('',#123895,#123900); -#123895 = PLANE('',#123896); -#123896 = AXIS2_PLACEMENT_3D('',#123897,#123898,#123899); -#123897 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#126175 = ORIENTED_EDGE('',*,*,#96284,.F.); +#126176 = ADVANCED_FACE('',(#126177),#96272,.T.); +#126177 = FACE_BOUND('',#126178,.T.); +#126178 = EDGE_LOOP('',(#126179,#126200,#126201,#126202)); +#126179 = ORIENTED_EDGE('',*,*,#126180,.F.); +#126180 = EDGE_CURVE('',#126056,#96255,#126181,.T.); +#126181 = SURFACE_CURVE('',#126182,(#126186,#126193),.PCURVE_S1.); +#126182 = LINE('',#126183,#126184); +#126183 = CARTESIAN_POINT('',(10.527847992439,4.65,0.75)); +#126184 = VECTOR('',#126185,1.); +#126185 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126186 = PCURVE('',#96272,#126187); +#126187 = DEFINITIONAL_REPRESENTATION('',(#126188),#126192); +#126188 = LINE('',#126189,#126190); +#126189 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#126190 = VECTOR('',#126191,1.); +#126191 = DIRECTION('',(-1.,-1.082494723017E-063)); +#126192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126193 = PCURVE('',#96354,#126194); +#126194 = DEFINITIONAL_REPRESENTATION('',(#126195),#126199); +#126195 = LINE('',#126196,#126197); +#126196 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#126197 = VECTOR('',#126198,1.); +#126198 = DIRECTION('',(-3.563627120235E-016,-1.)); +#126199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126200 = ORIENTED_EDGE('',*,*,#126055,.T.); +#126201 = ORIENTED_EDGE('',*,*,#126105,.T.); +#126202 = ORIENTED_EDGE('',*,*,#96254,.F.); +#126203 = ADVANCED_FACE('',(#126204),#96354,.T.); +#126204 = FACE_BOUND('',#126205,.T.); +#126205 = EDGE_LOOP('',(#126206,#126227,#126228,#126229,#126230,#126231, + #126252,#126253,#126254,#126255,#126256,#126257)); +#126206 = ORIENTED_EDGE('',*,*,#126207,.F.); +#126207 = EDGE_CURVE('',#125982,#96313,#126208,.T.); +#126208 = SURFACE_CURVE('',#126209,(#126213,#126220),.PCURVE_S1.); +#126209 = LINE('',#126210,#126211); +#126210 = CARTESIAN_POINT('',(10.527847992439,4.65,0.65)); +#126211 = VECTOR('',#126212,1.); +#126212 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126213 = PCURVE('',#96354,#126214); +#126214 = DEFINITIONAL_REPRESENTATION('',(#126215),#126219); +#126215 = LINE('',#126216,#126217); +#126216 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126217 = VECTOR('',#126218,1.); +#126218 = DIRECTION('',(-3.563627120235E-016,-1.)); +#126219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126220 = PCURVE('',#96328,#126221); +#126221 = DEFINITIONAL_REPRESENTATION('',(#126222),#126226); +#126222 = LINE('',#126223,#126224); +#126223 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#126224 = VECTOR('',#126225,1.); +#126225 = DIRECTION('',(1.,-1.082494723017E-063)); +#126226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126227 = ORIENTED_EDGE('',*,*,#126003,.T.); +#126228 = ORIENTED_EDGE('',*,*,#125933,.T.); +#126229 = ORIENTED_EDGE('',*,*,#125677,.T.); +#126230 = ORIENTED_EDGE('',*,*,#125575,.T.); +#126231 = ORIENTED_EDGE('',*,*,#126232,.F.); +#126232 = EDGE_CURVE('',#125439,#125546,#126233,.T.); +#126233 = SURFACE_CURVE('',#126234,(#126238,#126245),.PCURVE_S1.); +#126234 = LINE('',#126235,#126236); +#126235 = CARTESIAN_POINT('',(11.,4.65,1.159810404338E-002)); +#126236 = VECTOR('',#126237,1.); +#126237 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#126238 = PCURVE('',#96354,#126239); +#126239 = DEFINITIONAL_REPRESENTATION('',(#126240),#126244); +#126240 = LINE('',#126241,#126242); +#126241 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#126242 = VECTOR('',#126243,1.); +#126243 = DIRECTION('',(1.,-2.101748079665E-016)); +#126244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126245 = PCURVE('',#125459,#126246); +#126246 = DEFINITIONAL_REPRESENTATION('',(#126247),#126251); +#126247 = LINE('',#126248,#126249); +#126248 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#126249 = VECTOR('',#126250,1.); +#126250 = DIRECTION('',(-1.194699204908E-017,-1.)); +#126251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126252 = ORIENTED_EDGE('',*,*,#125521,.F.); +#126253 = ORIENTED_EDGE('',*,*,#125728,.F.); +#126254 = ORIENTED_EDGE('',*,*,#125836,.F.); +#126255 = ORIENTED_EDGE('',*,*,#126077,.F.); +#126256 = ORIENTED_EDGE('',*,*,#126180,.T.); +#126257 = ORIENTED_EDGE('',*,*,#96340,.F.); +#126258 = ADVANCED_FACE('',(#126259),#96328,.T.); +#126259 = FACE_BOUND('',#126260,.T.); +#126260 = EDGE_LOOP('',(#126261,#126262,#126263,#126264)); +#126261 = ORIENTED_EDGE('',*,*,#126155,.F.); +#126262 = ORIENTED_EDGE('',*,*,#125981,.T.); +#126263 = ORIENTED_EDGE('',*,*,#126207,.T.); +#126264 = ORIENTED_EDGE('',*,*,#96312,.F.); +#126265 = ADVANCED_FACE('',(#126266),#125459,.T.); +#126266 = FACE_BOUND('',#126267,.T.); +#126267 = EDGE_LOOP('',(#126268,#126269,#126270,#126271)); +#126268 = ORIENTED_EDGE('',*,*,#125436,.T.); +#126269 = ORIENTED_EDGE('',*,*,#126232,.T.); +#126270 = ORIENTED_EDGE('',*,*,#125545,.T.); +#126271 = ORIENTED_EDGE('',*,*,#126130,.T.); +#126272 = ADVANCED_FACE('',(#126273),#126287,.F.); +#126273 = FACE_BOUND('',#126274,.T.); +#126274 = EDGE_LOOP('',(#126275,#126310,#126333,#126360)); +#126275 = ORIENTED_EDGE('',*,*,#126276,.F.); +#126276 = EDGE_CURVE('',#126277,#126279,#126281,.T.); +#126277 = VERTEX_POINT('',#126278); +#126278 = CARTESIAN_POINT('',(11.,8.15,-0.308197125857)); +#126279 = VERTEX_POINT('',#126280); +#126280 = CARTESIAN_POINT('',(11.,8.35,-0.308197125857)); +#126281 = SURFACE_CURVE('',#126282,(#126286,#126298),.PCURVE_S1.); +#126282 = LINE('',#126283,#126284); +#126283 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#126284 = VECTOR('',#126285,1.); +#126285 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126286 = PCURVE('',#126287,#126292); +#126287 = PLANE('',#126288); +#126288 = AXIS2_PLACEMENT_3D('',#126289,#126290,#126291); +#126289 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#123898 = DIRECTION('',(0.E+000,0.E+000,1.)); -#123899 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123900 = DEFINITIONAL_REPRESENTATION('',(#123901),#123905); -#123901 = LINE('',#123902,#123903); -#123902 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#123903 = VECTOR('',#123904,1.); -#123904 = DIRECTION('',(4.440892098501E-016,1.)); -#123905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123906 = PCURVE('',#123907,#123912); -#123907 = PLANE('',#123908); -#123908 = AXIS2_PLACEMENT_3D('',#123909,#123910,#123911); -#123909 = CARTESIAN_POINT('',(11.,8.25,-0.258196742327)); -#123910 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#123911 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#123912 = DEFINITIONAL_REPRESENTATION('',(#123913),#123917); -#123913 = LINE('',#123914,#123915); -#123914 = CARTESIAN_POINT('',(-8.25,-5.000038352949E-002)); -#123915 = VECTOR('',#123916,1.); -#123916 = DIRECTION('',(1.,0.E+000)); -#123917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123918 = ORIENTED_EDGE('',*,*,#123919,.F.); -#123919 = EDGE_CURVE('',#123920,#123885,#123922,.T.); -#123920 = VERTEX_POINT('',#123921); -#123921 = CARTESIAN_POINT('',(10.74341632541,8.15,-0.308197125857)); -#123922 = SURFACE_CURVE('',#123923,(#123927,#123934),.PCURVE_S1.); -#123923 = LINE('',#123924,#123925); -#123924 = CARTESIAN_POINT('',(10.74341632541,8.15,-0.308197125857)); -#123925 = VECTOR('',#123926,1.); -#123926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123927 = PCURVE('',#123895,#123928); -#123928 = DEFINITIONAL_REPRESENTATION('',(#123929),#123933); -#123929 = LINE('',#123930,#123931); -#123930 = CARTESIAN_POINT('',(3.552713678801E-015,8.15)); -#123931 = VECTOR('',#123932,1.); -#123932 = DIRECTION('',(1.,0.E+000)); -#123933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123934 = PCURVE('',#93822,#123935); -#123935 = DEFINITIONAL_REPRESENTATION('',(#123936),#123940); -#123936 = LINE('',#123937,#123938); -#123937 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#123938 = VECTOR('',#123939,1.); -#123939 = DIRECTION('',(0.E+000,1.)); -#123940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123941 = ORIENTED_EDGE('',*,*,#123942,.F.); -#123942 = EDGE_CURVE('',#123943,#123920,#123945,.T.); -#123943 = VERTEX_POINT('',#123944); -#123944 = CARTESIAN_POINT('',(10.74341632541,8.35,-0.308197125857)); -#123945 = SURFACE_CURVE('',#123946,(#123950,#123957),.PCURVE_S1.); -#123946 = LINE('',#123947,#123948); -#123947 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#126290 = DIRECTION('',(0.E+000,0.E+000,1.)); +#126291 = DIRECTION('',(1.,0.E+000,0.E+000)); +#126292 = DEFINITIONAL_REPRESENTATION('',(#126293),#126297); +#126293 = LINE('',#126294,#126295); +#126294 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#126295 = VECTOR('',#126296,1.); +#126296 = DIRECTION('',(4.440892098501E-016,1.)); +#126297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126298 = PCURVE('',#126299,#126304); +#126299 = PLANE('',#126300); +#126300 = AXIS2_PLACEMENT_3D('',#126301,#126302,#126303); +#126301 = CARTESIAN_POINT('',(11.,8.25,-0.258196742327)); +#126302 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#126303 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126304 = DEFINITIONAL_REPRESENTATION('',(#126305),#126309); +#126305 = LINE('',#126306,#126307); +#126306 = CARTESIAN_POINT('',(-8.25,-5.000038352949E-002)); +#126307 = VECTOR('',#126308,1.); +#126308 = DIRECTION('',(1.,0.E+000)); +#126309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126310 = ORIENTED_EDGE('',*,*,#126311,.F.); +#126311 = EDGE_CURVE('',#126312,#126277,#126314,.T.); +#126312 = VERTEX_POINT('',#126313); +#126313 = CARTESIAN_POINT('',(10.74341632541,8.15,-0.308197125857)); +#126314 = SURFACE_CURVE('',#126315,(#126319,#126326),.PCURVE_S1.); +#126315 = LINE('',#126316,#126317); +#126316 = CARTESIAN_POINT('',(10.74341632541,8.15,-0.308197125857)); +#126317 = VECTOR('',#126318,1.); +#126318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#126319 = PCURVE('',#126287,#126320); +#126320 = DEFINITIONAL_REPRESENTATION('',(#126321),#126325); +#126321 = LINE('',#126322,#126323); +#126322 = CARTESIAN_POINT('',(3.552713678801E-015,8.15)); +#126323 = VECTOR('',#126324,1.); +#126324 = DIRECTION('',(1.,0.E+000)); +#126325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126326 = PCURVE('',#96214,#126327); +#126327 = DEFINITIONAL_REPRESENTATION('',(#126328),#126332); +#126328 = LINE('',#126329,#126330); +#126329 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#126330 = VECTOR('',#126331,1.); +#126331 = DIRECTION('',(0.E+000,1.)); +#126332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126333 = ORIENTED_EDGE('',*,*,#126334,.F.); +#126334 = EDGE_CURVE('',#126335,#126312,#126337,.T.); +#126335 = VERTEX_POINT('',#126336); +#126336 = CARTESIAN_POINT('',(10.74341632541,8.35,-0.308197125857)); +#126337 = SURFACE_CURVE('',#126338,(#126342,#126349),.PCURVE_S1.); +#126338 = LINE('',#126339,#126340); +#126339 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#123948 = VECTOR('',#123949,1.); -#123949 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123950 = PCURVE('',#123895,#123951); -#123951 = DEFINITIONAL_REPRESENTATION('',(#123952),#123956); -#123952 = LINE('',#123953,#123954); -#123953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#123954 = VECTOR('',#123955,1.); -#123955 = DIRECTION('',(-4.440892098501E-016,-1.)); -#123956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123957 = PCURVE('',#123958,#123963); -#123958 = CYLINDRICAL_SURFACE('',#123959,0.308574064194); -#123959 = AXIS2_PLACEMENT_3D('',#123960,#123961,#123962); -#123960 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#126340 = VECTOR('',#126341,1.); +#126341 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126342 = PCURVE('',#126287,#126343); +#126343 = DEFINITIONAL_REPRESENTATION('',(#126344),#126348); +#126344 = LINE('',#126345,#126346); +#126345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126346 = VECTOR('',#126347,1.); +#126347 = DIRECTION('',(-4.440892098501E-016,-1.)); +#126348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126349 = PCURVE('',#126350,#126355); +#126350 = CYLINDRICAL_SURFACE('',#126351,0.308574064194); +#126351 = AXIS2_PLACEMENT_3D('',#126352,#126353,#126354); +#126352 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#123961 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#123962 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#123963 = DEFINITIONAL_REPRESENTATION('',(#123964),#123967); -#123964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#123965,#123966), +#126353 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126354 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126355 = DEFINITIONAL_REPRESENTATION('',(#126356),#126359); +#126356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126357,#126358), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#123965 = CARTESIAN_POINT('',(4.761821717947,-8.35)); -#123966 = CARTESIAN_POINT('',(4.761821717947,-8.15)); -#123967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123968 = ORIENTED_EDGE('',*,*,#123969,.T.); -#123969 = EDGE_CURVE('',#123943,#123887,#123970,.T.); -#123970 = SURFACE_CURVE('',#123971,(#123975,#123982),.PCURVE_S1.); -#123971 = LINE('',#123972,#123973); -#123972 = CARTESIAN_POINT('',(10.74341632541,8.35,-0.308197125857)); -#123973 = VECTOR('',#123974,1.); -#123974 = DIRECTION('',(1.,0.E+000,0.E+000)); -#123975 = PCURVE('',#123895,#123976); -#123976 = DEFINITIONAL_REPRESENTATION('',(#123977),#123981); -#123977 = LINE('',#123978,#123979); -#123978 = CARTESIAN_POINT('',(3.552713678801E-015,8.35)); -#123979 = VECTOR('',#123980,1.); -#123980 = DIRECTION('',(1.,0.E+000)); -#123981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123982 = PCURVE('',#93766,#123983); -#123983 = DEFINITIONAL_REPRESENTATION('',(#123984),#123988); -#123984 = LINE('',#123985,#123986); -#123985 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#123986 = VECTOR('',#123987,1.); -#123987 = DIRECTION('',(0.E+000,1.)); -#123988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#123989 = ADVANCED_FACE('',(#123990),#124004,.F.); -#123990 = FACE_BOUND('',#123991,.T.); -#123991 = EDGE_LOOP('',(#123992,#124022,#124045,#124072)); -#123992 = ORIENTED_EDGE('',*,*,#123993,.F.); -#123993 = EDGE_CURVE('',#123994,#123996,#123998,.T.); -#123994 = VERTEX_POINT('',#123995); -#123995 = CARTESIAN_POINT('',(11.,8.35,-0.208196358798)); -#123996 = VERTEX_POINT('',#123997); -#123997 = CARTESIAN_POINT('',(11.,8.15,-0.208196358798)); -#123998 = SURFACE_CURVE('',#123999,(#124003,#124015),.PCURVE_S1.); -#123999 = LINE('',#124000,#124001); -#124000 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#124001 = VECTOR('',#124002,1.); -#124002 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124003 = PCURVE('',#124004,#124009); -#124004 = PLANE('',#124005); -#124005 = AXIS2_PLACEMENT_3D('',#124006,#124007,#124008); -#124006 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#126357 = CARTESIAN_POINT('',(4.761821717947,-8.35)); +#126358 = CARTESIAN_POINT('',(4.761821717947,-8.15)); +#126359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126360 = ORIENTED_EDGE('',*,*,#126361,.T.); +#126361 = EDGE_CURVE('',#126335,#126279,#126362,.T.); +#126362 = SURFACE_CURVE('',#126363,(#126367,#126374),.PCURVE_S1.); +#126363 = LINE('',#126364,#126365); +#126364 = CARTESIAN_POINT('',(10.74341632541,8.35,-0.308197125857)); +#126365 = VECTOR('',#126366,1.); +#126366 = DIRECTION('',(1.,0.E+000,0.E+000)); +#126367 = PCURVE('',#126287,#126368); +#126368 = DEFINITIONAL_REPRESENTATION('',(#126369),#126373); +#126369 = LINE('',#126370,#126371); +#126370 = CARTESIAN_POINT('',(3.552713678801E-015,8.35)); +#126371 = VECTOR('',#126372,1.); +#126372 = DIRECTION('',(1.,0.E+000)); +#126373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126374 = PCURVE('',#96158,#126375); +#126375 = DEFINITIONAL_REPRESENTATION('',(#126376),#126380); +#126376 = LINE('',#126377,#126378); +#126377 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#126378 = VECTOR('',#126379,1.); +#126379 = DIRECTION('',(0.E+000,1.)); +#126380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126381 = ADVANCED_FACE('',(#126382),#126396,.F.); +#126382 = FACE_BOUND('',#126383,.T.); +#126383 = EDGE_LOOP('',(#126384,#126414,#126437,#126464)); +#126384 = ORIENTED_EDGE('',*,*,#126385,.F.); +#126385 = EDGE_CURVE('',#126386,#126388,#126390,.T.); +#126386 = VERTEX_POINT('',#126387); +#126387 = CARTESIAN_POINT('',(11.,8.35,-0.208196358798)); +#126388 = VERTEX_POINT('',#126389); +#126389 = CARTESIAN_POINT('',(11.,8.15,-0.208196358798)); +#126390 = SURFACE_CURVE('',#126391,(#126395,#126407),.PCURVE_S1.); +#126391 = LINE('',#126392,#126393); +#126392 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#126393 = VECTOR('',#126394,1.); +#126394 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126395 = PCURVE('',#126396,#126401); +#126396 = PLANE('',#126397); +#126397 = AXIS2_PLACEMENT_3D('',#126398,#126399,#126400); +#126398 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#124007 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124008 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#124009 = DEFINITIONAL_REPRESENTATION('',(#124010),#124014); -#124010 = LINE('',#124011,#124012); -#124011 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#124012 = VECTOR('',#124013,1.); -#124013 = DIRECTION('',(4.440892098501E-016,-1.)); -#124014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124015 = PCURVE('',#123907,#124016); -#124016 = DEFINITIONAL_REPRESENTATION('',(#124017),#124021); -#124017 = LINE('',#124018,#124019); -#124018 = CARTESIAN_POINT('',(-8.25,5.000038352949E-002)); -#124019 = VECTOR('',#124020,1.); -#124020 = DIRECTION('',(-1.,0.E+000)); -#124021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124022 = ORIENTED_EDGE('',*,*,#124023,.F.); -#124023 = EDGE_CURVE('',#124024,#123994,#124026,.T.); -#124024 = VERTEX_POINT('',#124025); -#124025 = CARTESIAN_POINT('',(10.740726081328,8.35,-0.208196358798)); -#124026 = SURFACE_CURVE('',#124027,(#124031,#124038),.PCURVE_S1.); -#124027 = LINE('',#124028,#124029); -#124028 = CARTESIAN_POINT('',(10.740726081328,8.35,-0.208196358798)); -#124029 = VECTOR('',#124030,1.); -#124030 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124031 = PCURVE('',#124004,#124032); -#124032 = DEFINITIONAL_REPRESENTATION('',(#124033),#124037); -#124033 = LINE('',#124034,#124035); -#124034 = CARTESIAN_POINT('',(-3.552713678801E-015,8.35)); -#124035 = VECTOR('',#124036,1.); -#124036 = DIRECTION('',(-1.,0.E+000)); -#124037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124038 = PCURVE('',#93766,#124039); -#124039 = DEFINITIONAL_REPRESENTATION('',(#124040),#124044); -#124040 = LINE('',#124041,#124042); -#124041 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#124042 = VECTOR('',#124043,1.); -#124043 = DIRECTION('',(0.E+000,1.)); -#124044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124045 = ORIENTED_EDGE('',*,*,#124046,.F.); -#124046 = EDGE_CURVE('',#124047,#124024,#124049,.T.); -#124047 = VERTEX_POINT('',#124048); -#124048 = CARTESIAN_POINT('',(10.740726081328,8.15,-0.208196358798)); -#124049 = SURFACE_CURVE('',#124050,(#124054,#124061),.PCURVE_S1.); -#124050 = LINE('',#124051,#124052); -#124051 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#126399 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#126400 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#126401 = DEFINITIONAL_REPRESENTATION('',(#126402),#126406); +#126402 = LINE('',#126403,#126404); +#126403 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#126404 = VECTOR('',#126405,1.); +#126405 = DIRECTION('',(4.440892098501E-016,-1.)); +#126406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126407 = PCURVE('',#126299,#126408); +#126408 = DEFINITIONAL_REPRESENTATION('',(#126409),#126413); +#126409 = LINE('',#126410,#126411); +#126410 = CARTESIAN_POINT('',(-8.25,5.000038352949E-002)); +#126411 = VECTOR('',#126412,1.); +#126412 = DIRECTION('',(-1.,0.E+000)); +#126413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126414 = ORIENTED_EDGE('',*,*,#126415,.F.); +#126415 = EDGE_CURVE('',#126416,#126386,#126418,.T.); +#126416 = VERTEX_POINT('',#126417); +#126417 = CARTESIAN_POINT('',(10.740726081328,8.35,-0.208196358798)); +#126418 = SURFACE_CURVE('',#126419,(#126423,#126430),.PCURVE_S1.); +#126419 = LINE('',#126420,#126421); +#126420 = CARTESIAN_POINT('',(10.740726081328,8.35,-0.208196358798)); +#126421 = VECTOR('',#126422,1.); +#126422 = DIRECTION('',(1.,0.E+000,0.E+000)); +#126423 = PCURVE('',#126396,#126424); +#126424 = DEFINITIONAL_REPRESENTATION('',(#126425),#126429); +#126425 = LINE('',#126426,#126427); +#126426 = CARTESIAN_POINT('',(-3.552713678801E-015,8.35)); +#126427 = VECTOR('',#126428,1.); +#126428 = DIRECTION('',(-1.,0.E+000)); +#126429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126430 = PCURVE('',#96158,#126431); +#126431 = DEFINITIONAL_REPRESENTATION('',(#126432),#126436); +#126432 = LINE('',#126433,#126434); +#126433 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#126434 = VECTOR('',#126435,1.); +#126435 = DIRECTION('',(0.E+000,1.)); +#126436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126437 = ORIENTED_EDGE('',*,*,#126438,.F.); +#126438 = EDGE_CURVE('',#126439,#126416,#126441,.T.); +#126439 = VERTEX_POINT('',#126440); +#126440 = CARTESIAN_POINT('',(10.740726081328,8.15,-0.208196358798)); +#126441 = SURFACE_CURVE('',#126442,(#126446,#126453),.PCURVE_S1.); +#126442 = LINE('',#126443,#126444); +#126443 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#124052 = VECTOR('',#124053,1.); -#124053 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124054 = PCURVE('',#124004,#124055); -#124055 = DEFINITIONAL_REPRESENTATION('',(#124056),#124060); -#124056 = LINE('',#124057,#124058); -#124057 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124058 = VECTOR('',#124059,1.); -#124059 = DIRECTION('',(-4.440892098501E-016,1.)); -#124060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124061 = PCURVE('',#124062,#124067); -#124062 = CYLINDRICAL_SURFACE('',#124063,0.208574704164); -#124063 = AXIS2_PLACEMENT_3D('',#124064,#124065,#124066); -#124064 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#126444 = VECTOR('',#126445,1.); +#126445 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126446 = PCURVE('',#126396,#126447); +#126447 = DEFINITIONAL_REPRESENTATION('',(#126448),#126452); +#126448 = LINE('',#126449,#126450); +#126449 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126450 = VECTOR('',#126451,1.); +#126451 = DIRECTION('',(-4.440892098501E-016,1.)); +#126452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126453 = PCURVE('',#126454,#126459); +#126454 = CYLINDRICAL_SURFACE('',#126455,0.208574704164); +#126455 = AXIS2_PLACEMENT_3D('',#126456,#126457,#126458); +#126456 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#124065 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124066 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124067 = DEFINITIONAL_REPRESENTATION('',(#124068),#124071); -#124068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124069,#124070), +#126457 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126458 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126459 = DEFINITIONAL_REPRESENTATION('',(#126460),#126463); +#126460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126461,#126462), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#124069 = CARTESIAN_POINT('',(4.772630242227,-8.15)); -#124070 = CARTESIAN_POINT('',(4.772630242227,-8.35)); -#124071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124072 = ORIENTED_EDGE('',*,*,#124073,.T.); -#124073 = EDGE_CURVE('',#124047,#123996,#124074,.T.); -#124074 = SURFACE_CURVE('',#124075,(#124079,#124086),.PCURVE_S1.); -#124075 = LINE('',#124076,#124077); -#124076 = CARTESIAN_POINT('',(10.740726081328,8.15,-0.208196358798)); -#124077 = VECTOR('',#124078,1.); -#124078 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124079 = PCURVE('',#124004,#124080); -#124080 = DEFINITIONAL_REPRESENTATION('',(#124081),#124085); -#124081 = LINE('',#124082,#124083); -#124082 = CARTESIAN_POINT('',(-3.552713678801E-015,8.15)); -#124083 = VECTOR('',#124084,1.); -#124084 = DIRECTION('',(-1.,0.E+000)); -#124085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124086 = PCURVE('',#93822,#124087); -#124087 = DEFINITIONAL_REPRESENTATION('',(#124088),#124092); -#124088 = LINE('',#124089,#124090); -#124089 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#124090 = VECTOR('',#124091,1.); -#124091 = DIRECTION('',(0.E+000,1.)); -#124092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124093 = ADVANCED_FACE('',(#124094),#123958,.T.); -#124094 = FACE_BOUND('',#124095,.T.); -#124095 = EDGE_LOOP('',(#124096,#124123,#124124,#124147)); -#124096 = ORIENTED_EDGE('',*,*,#124097,.T.); -#124097 = EDGE_CURVE('',#124098,#123943,#124100,.T.); -#124098 = VERTEX_POINT('',#124099); -#124099 = CARTESIAN_POINT('',(10.419594812019,8.35,0.E+000)); -#124100 = SURFACE_CURVE('',#124101,(#124106,#124112),.PCURVE_S1.); -#124101 = CIRCLE('',#124102,0.308574064194); -#124102 = AXIS2_PLACEMENT_3D('',#124103,#124104,#124105); -#124103 = CARTESIAN_POINT('',(10.728168876214,8.35,2.640924866458E-017) - ); -#124104 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124105 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124106 = PCURVE('',#123958,#124107); -#124107 = DEFINITIONAL_REPRESENTATION('',(#124108),#124111); -#124108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124109,#124110), +#126461 = CARTESIAN_POINT('',(4.772630242227,-8.15)); +#126462 = CARTESIAN_POINT('',(4.772630242227,-8.35)); +#126463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126464 = ORIENTED_EDGE('',*,*,#126465,.T.); +#126465 = EDGE_CURVE('',#126439,#126388,#126466,.T.); +#126466 = SURFACE_CURVE('',#126467,(#126471,#126478),.PCURVE_S1.); +#126467 = LINE('',#126468,#126469); +#126468 = CARTESIAN_POINT('',(10.740726081328,8.15,-0.208196358798)); +#126469 = VECTOR('',#126470,1.); +#126470 = DIRECTION('',(1.,0.E+000,0.E+000)); +#126471 = PCURVE('',#126396,#126472); +#126472 = DEFINITIONAL_REPRESENTATION('',(#126473),#126477); +#126473 = LINE('',#126474,#126475); +#126474 = CARTESIAN_POINT('',(-3.552713678801E-015,8.15)); +#126475 = VECTOR('',#126476,1.); +#126476 = DIRECTION('',(-1.,0.E+000)); +#126477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126478 = PCURVE('',#96214,#126479); +#126479 = DEFINITIONAL_REPRESENTATION('',(#126480),#126484); +#126480 = LINE('',#126481,#126482); +#126481 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#126482 = VECTOR('',#126483,1.); +#126483 = DIRECTION('',(0.E+000,1.)); +#126484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126485 = ADVANCED_FACE('',(#126486),#126350,.T.); +#126486 = FACE_BOUND('',#126487,.T.); +#126487 = EDGE_LOOP('',(#126488,#126515,#126516,#126539)); +#126488 = ORIENTED_EDGE('',*,*,#126489,.T.); +#126489 = EDGE_CURVE('',#126490,#126335,#126492,.T.); +#126490 = VERTEX_POINT('',#126491); +#126491 = CARTESIAN_POINT('',(10.419594812019,8.35,0.E+000)); +#126492 = SURFACE_CURVE('',#126493,(#126498,#126504),.PCURVE_S1.); +#126493 = CIRCLE('',#126494,0.308574064194); +#126494 = AXIS2_PLACEMENT_3D('',#126495,#126496,#126497); +#126495 = CARTESIAN_POINT('',(10.728168876214,8.35,2.640924866458E-017) + ); +#126496 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126497 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126498 = PCURVE('',#126350,#126499); +#126499 = DEFINITIONAL_REPRESENTATION('',(#126500),#126503); +#126500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126501,#126502), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#124109 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#124110 = CARTESIAN_POINT('',(4.761821717947,-8.35)); -#124111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126501 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#126502 = CARTESIAN_POINT('',(4.761821717947,-8.35)); +#126503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124112 = PCURVE('',#93766,#124113); -#124113 = DEFINITIONAL_REPRESENTATION('',(#124114),#124122); -#124114 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124115,#124116,#124117, - #124118,#124119,#124120,#124121),.UNSPECIFIED.,.T.,.F.) +#126504 = PCURVE('',#96158,#126505); +#126505 = DEFINITIONAL_REPRESENTATION('',(#126506),#126514); +#126506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126507,#126508,#126509, + #126510,#126511,#126512,#126513),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#124115 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#124116 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#124117 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#124118 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#124119 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#124120 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#124121 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#124122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124123 = ORIENTED_EDGE('',*,*,#123942,.T.); -#124124 = ORIENTED_EDGE('',*,*,#124125,.F.); -#124125 = EDGE_CURVE('',#124126,#123920,#124128,.T.); -#124126 = VERTEX_POINT('',#124127); -#124127 = CARTESIAN_POINT('',(10.419594812019,8.15,0.E+000)); -#124128 = SURFACE_CURVE('',#124129,(#124134,#124140),.PCURVE_S1.); -#124129 = CIRCLE('',#124130,0.308574064194); -#124130 = AXIS2_PLACEMENT_3D('',#124131,#124132,#124133); -#124131 = CARTESIAN_POINT('',(10.728168876214,8.15,2.640924866458E-017) - ); -#124132 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124133 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124134 = PCURVE('',#123958,#124135); -#124135 = DEFINITIONAL_REPRESENTATION('',(#124136),#124139); -#124136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124137,#124138), +#126507 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#126508 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#126509 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#126510 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#126511 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#126512 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#126513 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#126514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126515 = ORIENTED_EDGE('',*,*,#126334,.T.); +#126516 = ORIENTED_EDGE('',*,*,#126517,.F.); +#126517 = EDGE_CURVE('',#126518,#126312,#126520,.T.); +#126518 = VERTEX_POINT('',#126519); +#126519 = CARTESIAN_POINT('',(10.419594812019,8.15,0.E+000)); +#126520 = SURFACE_CURVE('',#126521,(#126526,#126532),.PCURVE_S1.); +#126521 = CIRCLE('',#126522,0.308574064194); +#126522 = AXIS2_PLACEMENT_3D('',#126523,#126524,#126525); +#126523 = CARTESIAN_POINT('',(10.728168876214,8.15,2.640924866458E-017) + ); +#126524 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126525 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126526 = PCURVE('',#126350,#126527); +#126527 = DEFINITIONAL_REPRESENTATION('',(#126528),#126531); +#126528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126529,#126530), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#124137 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#124138 = CARTESIAN_POINT('',(4.761821717947,-8.15)); -#124139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126529 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#126530 = CARTESIAN_POINT('',(4.761821717947,-8.15)); +#126531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124140 = PCURVE('',#93822,#124141); -#124141 = DEFINITIONAL_REPRESENTATION('',(#124142),#124146); -#124142 = CIRCLE('',#124143,0.308574064194); -#124143 = AXIS2_PLACEMENT_2D('',#124144,#124145); -#124144 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#124145 = DIRECTION('',(0.E+000,1.)); -#124146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126532 = PCURVE('',#96214,#126533); +#126533 = DEFINITIONAL_REPRESENTATION('',(#126534),#126538); +#126534 = CIRCLE('',#126535,0.308574064194); +#126535 = AXIS2_PLACEMENT_2D('',#126536,#126537); +#126536 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#126537 = DIRECTION('',(0.E+000,1.)); +#126538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124147 = ORIENTED_EDGE('',*,*,#124148,.T.); -#124148 = EDGE_CURVE('',#124126,#124098,#124149,.T.); -#124149 = SURFACE_CURVE('',#124150,(#124154,#124160),.PCURVE_S1.); -#124150 = LINE('',#124151,#124152); -#124151 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#126539 = ORIENTED_EDGE('',*,*,#126540,.T.); +#126540 = EDGE_CURVE('',#126518,#126490,#126541,.T.); +#126541 = SURFACE_CURVE('',#126542,(#126546,#126552),.PCURVE_S1.); +#126542 = LINE('',#126543,#126544); +#126543 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#124152 = VECTOR('',#124153,1.); -#124153 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124154 = PCURVE('',#123958,#124155); -#124155 = DEFINITIONAL_REPRESENTATION('',(#124156),#124159); -#124156 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124157,#124158), +#126544 = VECTOR('',#126545,1.); +#126545 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126546 = PCURVE('',#126350,#126547); +#126547 = DEFINITIONAL_REPRESENTATION('',(#126548),#126551); +#126548 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126549,#126550), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#124157 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#124158 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#124159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126549 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#126550 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#126551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124160 = PCURVE('',#124161,#124166); -#124161 = PLANE('',#124162); -#124162 = AXIS2_PLACEMENT_3D('',#124163,#124164,#124165); -#124163 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#126552 = PCURVE('',#126553,#126558); +#126553 = PLANE('',#126554); +#126554 = AXIS2_PLACEMENT_3D('',#126555,#126556,#126557); +#126555 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#124164 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124165 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124166 = DEFINITIONAL_REPRESENTATION('',(#124167),#124171); -#124167 = LINE('',#124168,#124169); -#124168 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#124169 = VECTOR('',#124170,1.); -#124170 = DIRECTION('',(-1.,0.E+000)); -#124171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124172 = ADVANCED_FACE('',(#124173),#124062,.F.); -#124173 = FACE_BOUND('',#124174,.F.); -#124174 = EDGE_LOOP('',(#124175,#124198,#124225,#124250)); -#124175 = ORIENTED_EDGE('',*,*,#124176,.F.); -#124176 = EDGE_CURVE('',#124177,#124047,#124179,.T.); -#124177 = VERTEX_POINT('',#124178); -#124178 = CARTESIAN_POINT('',(10.51959417205,8.15,0.E+000)); -#124179 = SURFACE_CURVE('',#124180,(#124185,#124191),.PCURVE_S1.); -#124180 = CIRCLE('',#124181,0.208574704164); -#124181 = AXIS2_PLACEMENT_3D('',#124182,#124183,#124184); -#124182 = CARTESIAN_POINT('',(10.728168876214,8.15,2.640924866458E-017) - ); -#124183 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124184 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124185 = PCURVE('',#124062,#124186); -#124186 = DEFINITIONAL_REPRESENTATION('',(#124187),#124190); -#124187 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124188,#124189), +#126556 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126557 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126558 = DEFINITIONAL_REPRESENTATION('',(#126559),#126563); +#126559 = LINE('',#126560,#126561); +#126560 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#126561 = VECTOR('',#126562,1.); +#126562 = DIRECTION('',(-1.,0.E+000)); +#126563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126564 = ADVANCED_FACE('',(#126565),#126454,.F.); +#126565 = FACE_BOUND('',#126566,.F.); +#126566 = EDGE_LOOP('',(#126567,#126590,#126617,#126642)); +#126567 = ORIENTED_EDGE('',*,*,#126568,.F.); +#126568 = EDGE_CURVE('',#126569,#126439,#126571,.T.); +#126569 = VERTEX_POINT('',#126570); +#126570 = CARTESIAN_POINT('',(10.51959417205,8.15,0.E+000)); +#126571 = SURFACE_CURVE('',#126572,(#126577,#126583),.PCURVE_S1.); +#126572 = CIRCLE('',#126573,0.208574704164); +#126573 = AXIS2_PLACEMENT_3D('',#126574,#126575,#126576); +#126574 = CARTESIAN_POINT('',(10.728168876214,8.15,2.640924866458E-017) + ); +#126575 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126576 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126577 = PCURVE('',#126454,#126578); +#126578 = DEFINITIONAL_REPRESENTATION('',(#126579),#126582); +#126579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126580,#126581), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#124188 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#124189 = CARTESIAN_POINT('',(4.772630242227,-8.15)); -#124190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126580 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#126581 = CARTESIAN_POINT('',(4.772630242227,-8.15)); +#126582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124191 = PCURVE('',#93822,#124192); -#124192 = DEFINITIONAL_REPRESENTATION('',(#124193),#124197); -#124193 = CIRCLE('',#124194,0.208574704164); -#124194 = AXIS2_PLACEMENT_2D('',#124195,#124196); -#124195 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#124196 = DIRECTION('',(0.E+000,1.)); -#124197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126583 = PCURVE('',#96214,#126584); +#126584 = DEFINITIONAL_REPRESENTATION('',(#126585),#126589); +#126585 = CIRCLE('',#126586,0.208574704164); +#126586 = AXIS2_PLACEMENT_2D('',#126587,#126588); +#126587 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#126588 = DIRECTION('',(0.E+000,1.)); +#126589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124198 = ORIENTED_EDGE('',*,*,#124199,.F.); -#124199 = EDGE_CURVE('',#124200,#124177,#124202,.T.); -#124200 = VERTEX_POINT('',#124201); -#124201 = CARTESIAN_POINT('',(10.51959417205,8.35,0.E+000)); -#124202 = SURFACE_CURVE('',#124203,(#124207,#124213),.PCURVE_S1.); -#124203 = LINE('',#124204,#124205); -#124204 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#126590 = ORIENTED_EDGE('',*,*,#126591,.F.); +#126591 = EDGE_CURVE('',#126592,#126569,#126594,.T.); +#126592 = VERTEX_POINT('',#126593); +#126593 = CARTESIAN_POINT('',(10.51959417205,8.35,0.E+000)); +#126594 = SURFACE_CURVE('',#126595,(#126599,#126605),.PCURVE_S1.); +#126595 = LINE('',#126596,#126597); +#126596 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#124205 = VECTOR('',#124206,1.); -#124206 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124207 = PCURVE('',#124062,#124208); -#124208 = DEFINITIONAL_REPRESENTATION('',(#124209),#124212); -#124209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124210,#124211), +#126597 = VECTOR('',#126598,1.); +#126598 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126599 = PCURVE('',#126454,#126600); +#126600 = DEFINITIONAL_REPRESENTATION('',(#126601),#126604); +#126601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126602,#126603), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#124210 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#124211 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#124212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126602 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#126603 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#126604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124213 = PCURVE('',#124214,#124219); -#124214 = PLANE('',#124215); -#124215 = AXIS2_PLACEMENT_3D('',#124216,#124217,#124218); -#124216 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#126605 = PCURVE('',#126606,#126611); +#126606 = PLANE('',#126607); +#126607 = AXIS2_PLACEMENT_3D('',#126608,#126609,#126610); +#126608 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#124217 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124218 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124219 = DEFINITIONAL_REPRESENTATION('',(#124220),#124224); -#124220 = LINE('',#124221,#124222); -#124221 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#124222 = VECTOR('',#124223,1.); -#124223 = DIRECTION('',(-1.,0.E+000)); -#124224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124225 = ORIENTED_EDGE('',*,*,#124226,.T.); -#124226 = EDGE_CURVE('',#124200,#124024,#124227,.T.); -#124227 = SURFACE_CURVE('',#124228,(#124233,#124239),.PCURVE_S1.); -#124228 = CIRCLE('',#124229,0.208574704164); -#124229 = AXIS2_PLACEMENT_3D('',#124230,#124231,#124232); -#124230 = CARTESIAN_POINT('',(10.728168876214,8.35,2.640924866458E-017) - ); -#124231 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124232 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124233 = PCURVE('',#124062,#124234); -#124234 = DEFINITIONAL_REPRESENTATION('',(#124235),#124238); -#124235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124236,#124237), +#126609 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126610 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126611 = DEFINITIONAL_REPRESENTATION('',(#126612),#126616); +#126612 = LINE('',#126613,#126614); +#126613 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#126614 = VECTOR('',#126615,1.); +#126615 = DIRECTION('',(-1.,0.E+000)); +#126616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126617 = ORIENTED_EDGE('',*,*,#126618,.T.); +#126618 = EDGE_CURVE('',#126592,#126416,#126619,.T.); +#126619 = SURFACE_CURVE('',#126620,(#126625,#126631),.PCURVE_S1.); +#126620 = CIRCLE('',#126621,0.208574704164); +#126621 = AXIS2_PLACEMENT_3D('',#126622,#126623,#126624); +#126622 = CARTESIAN_POINT('',(10.728168876214,8.35,2.640924866458E-017) + ); +#126623 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126624 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#126625 = PCURVE('',#126454,#126626); +#126626 = DEFINITIONAL_REPRESENTATION('',(#126627),#126630); +#126627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126628,#126629), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#124236 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#124237 = CARTESIAN_POINT('',(4.772630242227,-8.35)); -#124238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126628 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#126629 = CARTESIAN_POINT('',(4.772630242227,-8.35)); +#126630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124239 = PCURVE('',#93766,#124240); -#124240 = DEFINITIONAL_REPRESENTATION('',(#124241),#124249); -#124241 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124242,#124243,#124244, - #124245,#124246,#124247,#124248),.UNSPECIFIED.,.T.,.F.) +#126631 = PCURVE('',#96158,#126632); +#126632 = DEFINITIONAL_REPRESENTATION('',(#126633),#126641); +#126633 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126634,#126635,#126636, + #126637,#126638,#126639,#126640),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#124242 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#124243 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#124244 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#124245 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#124246 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#124247 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#124248 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#124249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124250 = ORIENTED_EDGE('',*,*,#124046,.F.); -#124251 = ADVANCED_FACE('',(#124252),#124214,.T.); -#124252 = FACE_BOUND('',#124253,.T.); -#124253 = EDGE_LOOP('',(#124254,#124283,#124304,#124305)); -#124254 = ORIENTED_EDGE('',*,*,#124255,.T.); -#124255 = EDGE_CURVE('',#124256,#124258,#124260,.T.); -#124256 = VERTEX_POINT('',#124257); -#124257 = CARTESIAN_POINT('',(10.51959417205,8.35,0.530776333563)); -#124258 = VERTEX_POINT('',#124259); -#124259 = CARTESIAN_POINT('',(10.51959417205,8.15,0.530776333563)); -#124260 = SURFACE_CURVE('',#124261,(#124265,#124272),.PCURVE_S1.); -#124261 = LINE('',#124262,#124263); -#124262 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#126634 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#126635 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#126636 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#126637 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#126638 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#126639 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#126640 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#126641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126642 = ORIENTED_EDGE('',*,*,#126438,.F.); +#126643 = ADVANCED_FACE('',(#126644),#126606,.T.); +#126644 = FACE_BOUND('',#126645,.T.); +#126645 = EDGE_LOOP('',(#126646,#126675,#126696,#126697)); +#126646 = ORIENTED_EDGE('',*,*,#126647,.T.); +#126647 = EDGE_CURVE('',#126648,#126650,#126652,.T.); +#126648 = VERTEX_POINT('',#126649); +#126649 = CARTESIAN_POINT('',(10.51959417205,8.35,0.530776333563)); +#126650 = VERTEX_POINT('',#126651); +#126651 = CARTESIAN_POINT('',(10.51959417205,8.15,0.530776333563)); +#126652 = SURFACE_CURVE('',#126653,(#126657,#126664),.PCURVE_S1.); +#126653 = LINE('',#126654,#126655); +#126654 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#124263 = VECTOR('',#124264,1.); -#124264 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124265 = PCURVE('',#124214,#124266); -#124266 = DEFINITIONAL_REPRESENTATION('',(#124267),#124271); -#124267 = LINE('',#124268,#124269); -#124268 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124269 = VECTOR('',#124270,1.); -#124270 = DIRECTION('',(-1.,0.E+000)); -#124271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124272 = PCURVE('',#124273,#124278); -#124273 = CYLINDRICAL_SURFACE('',#124274,0.2192697516); -#124274 = AXIS2_PLACEMENT_3D('',#124275,#124276,#124277); -#124275 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#126655 = VECTOR('',#126656,1.); +#126656 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126657 = PCURVE('',#126606,#126658); +#126658 = DEFINITIONAL_REPRESENTATION('',(#126659),#126663); +#126659 = LINE('',#126660,#126661); +#126660 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126661 = VECTOR('',#126662,1.); +#126662 = DIRECTION('',(-1.,0.E+000)); +#126663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126664 = PCURVE('',#126665,#126670); +#126665 = CYLINDRICAL_SURFACE('',#126666,0.2192697516); +#126666 = AXIS2_PLACEMENT_3D('',#126667,#126668,#126669); +#126667 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#124276 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124277 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124278 = DEFINITIONAL_REPRESENTATION('',(#124279),#124282); -#124279 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124280,#124281), +#126668 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126669 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126670 = DEFINITIONAL_REPRESENTATION('',(#126671),#126674); +#126671 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126672,#126673), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#124280 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#124281 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#124282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124283 = ORIENTED_EDGE('',*,*,#124284,.T.); -#124284 = EDGE_CURVE('',#124258,#124177,#124285,.T.); -#124285 = SURFACE_CURVE('',#124286,(#124290,#124297),.PCURVE_S1.); -#124286 = LINE('',#124287,#124288); -#124287 = CARTESIAN_POINT('',(10.51959417205,8.15,0.530776333563)); -#124288 = VECTOR('',#124289,1.); -#124289 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124290 = PCURVE('',#124214,#124291); -#124291 = DEFINITIONAL_REPRESENTATION('',(#124292),#124296); -#124292 = LINE('',#124293,#124294); -#124293 = CARTESIAN_POINT('',(8.15,0.E+000)); -#124294 = VECTOR('',#124295,1.); -#124295 = DIRECTION('',(0.E+000,-1.)); -#124296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124297 = PCURVE('',#93822,#124298); -#124298 = DEFINITIONAL_REPRESENTATION('',(#124299),#124303); -#124299 = LINE('',#124300,#124301); -#124300 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#124301 = VECTOR('',#124302,1.); -#124302 = DIRECTION('',(1.,0.E+000)); -#124303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124304 = ORIENTED_EDGE('',*,*,#124199,.F.); -#124305 = ORIENTED_EDGE('',*,*,#124306,.F.); -#124306 = EDGE_CURVE('',#124256,#124200,#124307,.T.); -#124307 = SURFACE_CURVE('',#124308,(#124312,#124319),.PCURVE_S1.); -#124308 = LINE('',#124309,#124310); -#124309 = CARTESIAN_POINT('',(10.51959417205,8.35,0.530776333563)); -#124310 = VECTOR('',#124311,1.); -#124311 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124312 = PCURVE('',#124214,#124313); -#124313 = DEFINITIONAL_REPRESENTATION('',(#124314),#124318); -#124314 = LINE('',#124315,#124316); -#124315 = CARTESIAN_POINT('',(8.35,0.E+000)); -#124316 = VECTOR('',#124317,1.); -#124317 = DIRECTION('',(0.E+000,-1.)); -#124318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124319 = PCURVE('',#93766,#124320); -#124320 = DEFINITIONAL_REPRESENTATION('',(#124321),#124325); -#124321 = LINE('',#124322,#124323); -#124322 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#124323 = VECTOR('',#124324,1.); -#124324 = DIRECTION('',(-1.,0.E+000)); -#124325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124326 = ADVANCED_FACE('',(#124327),#124161,.T.); -#124327 = FACE_BOUND('',#124328,.T.); -#124328 = EDGE_LOOP('',(#124329,#124358,#124379,#124380)); -#124329 = ORIENTED_EDGE('',*,*,#124330,.T.); -#124330 = EDGE_CURVE('',#124331,#124333,#124335,.T.); -#124331 = VERTEX_POINT('',#124332); -#124332 = CARTESIAN_POINT('',(10.419594812019,8.15,0.530776333563)); -#124333 = VERTEX_POINT('',#124334); -#124334 = CARTESIAN_POINT('',(10.419594812019,8.35,0.530776333563)); -#124335 = SURFACE_CURVE('',#124336,(#124340,#124347),.PCURVE_S1.); -#124336 = LINE('',#124337,#124338); -#124337 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#126672 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#126673 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#126674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126675 = ORIENTED_EDGE('',*,*,#126676,.T.); +#126676 = EDGE_CURVE('',#126650,#126569,#126677,.T.); +#126677 = SURFACE_CURVE('',#126678,(#126682,#126689),.PCURVE_S1.); +#126678 = LINE('',#126679,#126680); +#126679 = CARTESIAN_POINT('',(10.51959417205,8.15,0.530776333563)); +#126680 = VECTOR('',#126681,1.); +#126681 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#126682 = PCURVE('',#126606,#126683); +#126683 = DEFINITIONAL_REPRESENTATION('',(#126684),#126688); +#126684 = LINE('',#126685,#126686); +#126685 = CARTESIAN_POINT('',(8.15,0.E+000)); +#126686 = VECTOR('',#126687,1.); +#126687 = DIRECTION('',(0.E+000,-1.)); +#126688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126689 = PCURVE('',#96214,#126690); +#126690 = DEFINITIONAL_REPRESENTATION('',(#126691),#126695); +#126691 = LINE('',#126692,#126693); +#126692 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#126693 = VECTOR('',#126694,1.); +#126694 = DIRECTION('',(1.,0.E+000)); +#126695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126696 = ORIENTED_EDGE('',*,*,#126591,.F.); +#126697 = ORIENTED_EDGE('',*,*,#126698,.F.); +#126698 = EDGE_CURVE('',#126648,#126592,#126699,.T.); +#126699 = SURFACE_CURVE('',#126700,(#126704,#126711),.PCURVE_S1.); +#126700 = LINE('',#126701,#126702); +#126701 = CARTESIAN_POINT('',(10.51959417205,8.35,0.530776333563)); +#126702 = VECTOR('',#126703,1.); +#126703 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#126704 = PCURVE('',#126606,#126705); +#126705 = DEFINITIONAL_REPRESENTATION('',(#126706),#126710); +#126706 = LINE('',#126707,#126708); +#126707 = CARTESIAN_POINT('',(8.35,0.E+000)); +#126708 = VECTOR('',#126709,1.); +#126709 = DIRECTION('',(0.E+000,-1.)); +#126710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126711 = PCURVE('',#96158,#126712); +#126712 = DEFINITIONAL_REPRESENTATION('',(#126713),#126717); +#126713 = LINE('',#126714,#126715); +#126714 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#126715 = VECTOR('',#126716,1.); +#126716 = DIRECTION('',(-1.,0.E+000)); +#126717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126718 = ADVANCED_FACE('',(#126719),#126553,.T.); +#126719 = FACE_BOUND('',#126720,.T.); +#126720 = EDGE_LOOP('',(#126721,#126750,#126771,#126772)); +#126721 = ORIENTED_EDGE('',*,*,#126722,.T.); +#126722 = EDGE_CURVE('',#126723,#126725,#126727,.T.); +#126723 = VERTEX_POINT('',#126724); +#126724 = CARTESIAN_POINT('',(10.419594812019,8.15,0.530776333563)); +#126725 = VERTEX_POINT('',#126726); +#126726 = CARTESIAN_POINT('',(10.419594812019,8.35,0.530776333563)); +#126727 = SURFACE_CURVE('',#126728,(#126732,#126739),.PCURVE_S1.); +#126728 = LINE('',#126729,#126730); +#126729 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#124338 = VECTOR('',#124339,1.); -#124339 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124340 = PCURVE('',#124161,#124341); -#124341 = DEFINITIONAL_REPRESENTATION('',(#124342),#124346); -#124342 = LINE('',#124343,#124344); -#124343 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124344 = VECTOR('',#124345,1.); -#124345 = DIRECTION('',(-1.,0.E+000)); -#124346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124347 = PCURVE('',#124348,#124353); -#124348 = CYLINDRICAL_SURFACE('',#124349,0.119270391569); -#124349 = AXIS2_PLACEMENT_3D('',#124350,#124351,#124352); -#124350 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#126730 = VECTOR('',#126731,1.); +#126731 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126732 = PCURVE('',#126553,#126733); +#126733 = DEFINITIONAL_REPRESENTATION('',(#126734),#126738); +#126734 = LINE('',#126735,#126736); +#126735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126736 = VECTOR('',#126737,1.); +#126737 = DIRECTION('',(-1.,0.E+000)); +#126738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126739 = PCURVE('',#126740,#126745); +#126740 = CYLINDRICAL_SURFACE('',#126741,0.119270391569); +#126741 = AXIS2_PLACEMENT_3D('',#126742,#126743,#126744); +#126742 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#124351 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124352 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124353 = DEFINITIONAL_REPRESENTATION('',(#124354),#124357); -#124354 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124355,#124356), +#126743 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126744 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126745 = DEFINITIONAL_REPRESENTATION('',(#126746),#126749); +#126746 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126747,#126748), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#124355 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#124356 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#124357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124358 = ORIENTED_EDGE('',*,*,#124359,.T.); -#124359 = EDGE_CURVE('',#124333,#124098,#124360,.T.); -#124360 = SURFACE_CURVE('',#124361,(#124365,#124372),.PCURVE_S1.); -#124361 = LINE('',#124362,#124363); -#124362 = CARTESIAN_POINT('',(10.419594812019,8.35,0.530776333563)); -#124363 = VECTOR('',#124364,1.); -#124364 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124365 = PCURVE('',#124161,#124366); -#124366 = DEFINITIONAL_REPRESENTATION('',(#124367),#124371); -#124367 = LINE('',#124368,#124369); -#124368 = CARTESIAN_POINT('',(-8.35,0.E+000)); -#124369 = VECTOR('',#124370,1.); -#124370 = DIRECTION('',(0.E+000,-1.)); -#124371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124372 = PCURVE('',#93766,#124373); -#124373 = DEFINITIONAL_REPRESENTATION('',(#124374),#124378); -#124374 = LINE('',#124375,#124376); -#124375 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#124376 = VECTOR('',#124377,1.); -#124377 = DIRECTION('',(-1.,0.E+000)); -#124378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124379 = ORIENTED_EDGE('',*,*,#124148,.F.); -#124380 = ORIENTED_EDGE('',*,*,#124381,.F.); -#124381 = EDGE_CURVE('',#124331,#124126,#124382,.T.); -#124382 = SURFACE_CURVE('',#124383,(#124387,#124394),.PCURVE_S1.); -#124383 = LINE('',#124384,#124385); -#124384 = CARTESIAN_POINT('',(10.419594812019,8.15,0.530776333563)); -#124385 = VECTOR('',#124386,1.); -#124386 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124387 = PCURVE('',#124161,#124388); -#124388 = DEFINITIONAL_REPRESENTATION('',(#124389),#124393); -#124389 = LINE('',#124390,#124391); -#124390 = CARTESIAN_POINT('',(-8.15,0.E+000)); -#124391 = VECTOR('',#124392,1.); -#124392 = DIRECTION('',(0.E+000,-1.)); -#124393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124394 = PCURVE('',#93822,#124395); -#124395 = DEFINITIONAL_REPRESENTATION('',(#124396),#124400); -#124396 = LINE('',#124397,#124398); -#124397 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#124398 = VECTOR('',#124399,1.); -#124399 = DIRECTION('',(1.,0.E+000)); -#124400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124401 = ADVANCED_FACE('',(#124402),#124348,.F.); -#124402 = FACE_BOUND('',#124403,.F.); -#124403 = EDGE_LOOP('',(#124404,#124405,#124428,#124450)); -#124404 = ORIENTED_EDGE('',*,*,#124330,.T.); -#124405 = ORIENTED_EDGE('',*,*,#124406,.F.); -#124406 = EDGE_CURVE('',#124407,#124333,#124409,.T.); -#124407 = VERTEX_POINT('',#124408); -#124408 = CARTESIAN_POINT('',(10.303662633502,8.35,0.65)); -#124409 = SURFACE_CURVE('',#124410,(#124415,#124421),.PCURVE_S1.); -#124410 = CIRCLE('',#124411,0.119270391569); -#124411 = AXIS2_PLACEMENT_3D('',#124412,#124413,#124414); -#124412 = CARTESIAN_POINT('',(10.30032442045,8.35,0.530776333563)); -#124413 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124414 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124415 = PCURVE('',#124348,#124416); -#124416 = DEFINITIONAL_REPRESENTATION('',(#124417),#124420); -#124417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124418,#124419), +#126747 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#126748 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#126749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126750 = ORIENTED_EDGE('',*,*,#126751,.T.); +#126751 = EDGE_CURVE('',#126725,#126490,#126752,.T.); +#126752 = SURFACE_CURVE('',#126753,(#126757,#126764),.PCURVE_S1.); +#126753 = LINE('',#126754,#126755); +#126754 = CARTESIAN_POINT('',(10.419594812019,8.35,0.530776333563)); +#126755 = VECTOR('',#126756,1.); +#126756 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#126757 = PCURVE('',#126553,#126758); +#126758 = DEFINITIONAL_REPRESENTATION('',(#126759),#126763); +#126759 = LINE('',#126760,#126761); +#126760 = CARTESIAN_POINT('',(-8.35,0.E+000)); +#126761 = VECTOR('',#126762,1.); +#126762 = DIRECTION('',(0.E+000,-1.)); +#126763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126764 = PCURVE('',#96158,#126765); +#126765 = DEFINITIONAL_REPRESENTATION('',(#126766),#126770); +#126766 = LINE('',#126767,#126768); +#126767 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#126768 = VECTOR('',#126769,1.); +#126769 = DIRECTION('',(-1.,0.E+000)); +#126770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126771 = ORIENTED_EDGE('',*,*,#126540,.F.); +#126772 = ORIENTED_EDGE('',*,*,#126773,.F.); +#126773 = EDGE_CURVE('',#126723,#126518,#126774,.T.); +#126774 = SURFACE_CURVE('',#126775,(#126779,#126786),.PCURVE_S1.); +#126775 = LINE('',#126776,#126777); +#126776 = CARTESIAN_POINT('',(10.419594812019,8.15,0.530776333563)); +#126777 = VECTOR('',#126778,1.); +#126778 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#126779 = PCURVE('',#126553,#126780); +#126780 = DEFINITIONAL_REPRESENTATION('',(#126781),#126785); +#126781 = LINE('',#126782,#126783); +#126782 = CARTESIAN_POINT('',(-8.15,0.E+000)); +#126783 = VECTOR('',#126784,1.); +#126784 = DIRECTION('',(0.E+000,-1.)); +#126785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126786 = PCURVE('',#96214,#126787); +#126787 = DEFINITIONAL_REPRESENTATION('',(#126788),#126792); +#126788 = LINE('',#126789,#126790); +#126789 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#126790 = VECTOR('',#126791,1.); +#126791 = DIRECTION('',(1.,0.E+000)); +#126792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126793 = ADVANCED_FACE('',(#126794),#126740,.F.); +#126794 = FACE_BOUND('',#126795,.F.); +#126795 = EDGE_LOOP('',(#126796,#126797,#126820,#126842)); +#126796 = ORIENTED_EDGE('',*,*,#126722,.T.); +#126797 = ORIENTED_EDGE('',*,*,#126798,.F.); +#126798 = EDGE_CURVE('',#126799,#126725,#126801,.T.); +#126799 = VERTEX_POINT('',#126800); +#126800 = CARTESIAN_POINT('',(10.303662633502,8.35,0.65)); +#126801 = SURFACE_CURVE('',#126802,(#126807,#126813),.PCURVE_S1.); +#126802 = CIRCLE('',#126803,0.119270391569); +#126803 = AXIS2_PLACEMENT_3D('',#126804,#126805,#126806); +#126804 = CARTESIAN_POINT('',(10.30032442045,8.35,0.530776333563)); +#126805 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126806 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126807 = PCURVE('',#126740,#126808); +#126808 = DEFINITIONAL_REPRESENTATION('',(#126809),#126812); +#126809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126810,#126811), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#124418 = CARTESIAN_POINT('',(1.598788597134,8.35)); -#124419 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#124420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124421 = PCURVE('',#93766,#124422); -#124422 = DEFINITIONAL_REPRESENTATION('',(#124423),#124427); -#124423 = CIRCLE('',#124424,0.119270391569); -#124424 = AXIS2_PLACEMENT_2D('',#124425,#124426); -#124425 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#124426 = DIRECTION('',(0.E+000,-1.)); -#124427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124428 = ORIENTED_EDGE('',*,*,#124429,.T.); -#124429 = EDGE_CURVE('',#124407,#124430,#124432,.T.); -#124430 = VERTEX_POINT('',#124431); -#124431 = CARTESIAN_POINT('',(10.303662633502,8.15,0.65)); -#124432 = SURFACE_CURVE('',#124433,(#124437,#124443),.PCURVE_S1.); -#124433 = LINE('',#124434,#124435); -#124434 = CARTESIAN_POINT('',(10.303662633502,8.15,0.65)); -#124435 = VECTOR('',#124436,1.); -#124436 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124437 = PCURVE('',#124348,#124438); -#124438 = DEFINITIONAL_REPRESENTATION('',(#124439),#124442); -#124439 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124440,#124441), +#126810 = CARTESIAN_POINT('',(1.598788597134,8.35)); +#126811 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#126812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126813 = PCURVE('',#96158,#126814); +#126814 = DEFINITIONAL_REPRESENTATION('',(#126815),#126819); +#126815 = CIRCLE('',#126816,0.119270391569); +#126816 = AXIS2_PLACEMENT_2D('',#126817,#126818); +#126817 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#126818 = DIRECTION('',(0.E+000,-1.)); +#126819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126820 = ORIENTED_EDGE('',*,*,#126821,.T.); +#126821 = EDGE_CURVE('',#126799,#126822,#126824,.T.); +#126822 = VERTEX_POINT('',#126823); +#126823 = CARTESIAN_POINT('',(10.303662633502,8.15,0.65)); +#126824 = SURFACE_CURVE('',#126825,(#126829,#126835),.PCURVE_S1.); +#126825 = LINE('',#126826,#126827); +#126826 = CARTESIAN_POINT('',(10.303662633502,8.15,0.65)); +#126827 = VECTOR('',#126828,1.); +#126828 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#126829 = PCURVE('',#126740,#126830); +#126830 = DEFINITIONAL_REPRESENTATION('',(#126831),#126834); +#126831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126832,#126833), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#124440 = CARTESIAN_POINT('',(1.598788597134,8.35)); -#124441 = CARTESIAN_POINT('',(1.598788597134,8.15)); -#124442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124443 = PCURVE('',#93794,#124444); -#124444 = DEFINITIONAL_REPRESENTATION('',(#124445),#124449); -#124445 = LINE('',#124446,#124447); -#124446 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#124447 = VECTOR('',#124448,1.); -#124448 = DIRECTION('',(4.440892098501E-016,-1.)); -#124449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124450 = ORIENTED_EDGE('',*,*,#124451,.T.); -#124451 = EDGE_CURVE('',#124430,#124331,#124452,.T.); -#124452 = SURFACE_CURVE('',#124453,(#124458,#124464),.PCURVE_S1.); -#124453 = CIRCLE('',#124454,0.119270391569); -#124454 = AXIS2_PLACEMENT_3D('',#124455,#124456,#124457); -#124455 = CARTESIAN_POINT('',(10.30032442045,8.15,0.530776333563)); -#124456 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124457 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124458 = PCURVE('',#124348,#124459); -#124459 = DEFINITIONAL_REPRESENTATION('',(#124460),#124463); -#124460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124461,#124462), +#126832 = CARTESIAN_POINT('',(1.598788597134,8.35)); +#126833 = CARTESIAN_POINT('',(1.598788597134,8.15)); +#126834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126835 = PCURVE('',#96186,#126836); +#126836 = DEFINITIONAL_REPRESENTATION('',(#126837),#126841); +#126837 = LINE('',#126838,#126839); +#126838 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#126839 = VECTOR('',#126840,1.); +#126840 = DIRECTION('',(4.440892098501E-016,-1.)); +#126841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126842 = ORIENTED_EDGE('',*,*,#126843,.T.); +#126843 = EDGE_CURVE('',#126822,#126723,#126844,.T.); +#126844 = SURFACE_CURVE('',#126845,(#126850,#126856),.PCURVE_S1.); +#126845 = CIRCLE('',#126846,0.119270391569); +#126846 = AXIS2_PLACEMENT_3D('',#126847,#126848,#126849); +#126847 = CARTESIAN_POINT('',(10.30032442045,8.15,0.530776333563)); +#126848 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126849 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126850 = PCURVE('',#126740,#126851); +#126851 = DEFINITIONAL_REPRESENTATION('',(#126852),#126855); +#126852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126853,#126854), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#124461 = CARTESIAN_POINT('',(1.598788597134,8.15)); -#124462 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#124463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126853 = CARTESIAN_POINT('',(1.598788597134,8.15)); +#126854 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#126855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124464 = PCURVE('',#93822,#124465); -#124465 = DEFINITIONAL_REPRESENTATION('',(#124466),#124474); -#124466 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124467,#124468,#124469, - #124470,#124471,#124472,#124473),.UNSPECIFIED.,.T.,.F.) +#126856 = PCURVE('',#96214,#126857); +#126857 = DEFINITIONAL_REPRESENTATION('',(#126858),#126866); +#126858 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126859,#126860,#126861, + #126862,#126863,#126864,#126865),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#124467 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#124468 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#124469 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#124470 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#124471 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#124472 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#124473 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#124474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124475 = ADVANCED_FACE('',(#124476),#124273,.T.); -#124476 = FACE_BOUND('',#124477,.T.); -#124477 = EDGE_LOOP('',(#124478,#124479,#124502,#124524)); -#124478 = ORIENTED_EDGE('',*,*,#124255,.F.); -#124479 = ORIENTED_EDGE('',*,*,#124480,.F.); -#124480 = EDGE_CURVE('',#124481,#124256,#124483,.T.); -#124481 = VERTEX_POINT('',#124482); -#124482 = CARTESIAN_POINT('',(10.304819755875,8.35,0.75)); -#124483 = SURFACE_CURVE('',#124484,(#124489,#124495),.PCURVE_S1.); -#124484 = CIRCLE('',#124485,0.2192697516); -#124485 = AXIS2_PLACEMENT_3D('',#124486,#124487,#124488); -#124486 = CARTESIAN_POINT('',(10.30032442045,8.35,0.530776333563)); -#124487 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124488 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124489 = PCURVE('',#124273,#124490); -#124490 = DEFINITIONAL_REPRESENTATION('',(#124491),#124494); -#124491 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124492,#124493), +#126859 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#126860 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#126861 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#126862 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#126863 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#126864 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#126865 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#126866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126867 = ADVANCED_FACE('',(#126868),#126665,.T.); +#126868 = FACE_BOUND('',#126869,.T.); +#126869 = EDGE_LOOP('',(#126870,#126871,#126894,#126916)); +#126870 = ORIENTED_EDGE('',*,*,#126647,.F.); +#126871 = ORIENTED_EDGE('',*,*,#126872,.F.); +#126872 = EDGE_CURVE('',#126873,#126648,#126875,.T.); +#126873 = VERTEX_POINT('',#126874); +#126874 = CARTESIAN_POINT('',(10.304819755875,8.35,0.75)); +#126875 = SURFACE_CURVE('',#126876,(#126881,#126887),.PCURVE_S1.); +#126876 = CIRCLE('',#126877,0.2192697516); +#126877 = AXIS2_PLACEMENT_3D('',#126878,#126879,#126880); +#126878 = CARTESIAN_POINT('',(10.30032442045,8.35,0.530776333563)); +#126879 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126880 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126881 = PCURVE('',#126665,#126882); +#126882 = DEFINITIONAL_REPRESENTATION('',(#126883),#126886); +#126883 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126884,#126885), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#124492 = CARTESIAN_POINT('',(1.591299156552,8.35)); -#124493 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#124494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124495 = PCURVE('',#93766,#124496); -#124496 = DEFINITIONAL_REPRESENTATION('',(#124497),#124501); -#124497 = CIRCLE('',#124498,0.2192697516); -#124498 = AXIS2_PLACEMENT_2D('',#124499,#124500); -#124499 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#124500 = DIRECTION('',(0.E+000,-1.)); -#124501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124502 = ORIENTED_EDGE('',*,*,#124503,.F.); -#124503 = EDGE_CURVE('',#124504,#124481,#124506,.T.); -#124504 = VERTEX_POINT('',#124505); -#124505 = CARTESIAN_POINT('',(10.304819755875,8.15,0.75)); -#124506 = SURFACE_CURVE('',#124507,(#124511,#124517),.PCURVE_S1.); -#124507 = LINE('',#124508,#124509); -#124508 = CARTESIAN_POINT('',(10.304819755875,8.15,0.75)); -#124509 = VECTOR('',#124510,1.); -#124510 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124511 = PCURVE('',#124273,#124512); -#124512 = DEFINITIONAL_REPRESENTATION('',(#124513),#124516); -#124513 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124514,#124515), +#126884 = CARTESIAN_POINT('',(1.591299156552,8.35)); +#126885 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#126886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126887 = PCURVE('',#96158,#126888); +#126888 = DEFINITIONAL_REPRESENTATION('',(#126889),#126893); +#126889 = CIRCLE('',#126890,0.2192697516); +#126890 = AXIS2_PLACEMENT_2D('',#126891,#126892); +#126891 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#126892 = DIRECTION('',(0.E+000,-1.)); +#126893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126894 = ORIENTED_EDGE('',*,*,#126895,.F.); +#126895 = EDGE_CURVE('',#126896,#126873,#126898,.T.); +#126896 = VERTEX_POINT('',#126897); +#126897 = CARTESIAN_POINT('',(10.304819755875,8.15,0.75)); +#126898 = SURFACE_CURVE('',#126899,(#126903,#126909),.PCURVE_S1.); +#126899 = LINE('',#126900,#126901); +#126900 = CARTESIAN_POINT('',(10.304819755875,8.15,0.75)); +#126901 = VECTOR('',#126902,1.); +#126902 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126903 = PCURVE('',#126665,#126904); +#126904 = DEFINITIONAL_REPRESENTATION('',(#126905),#126908); +#126905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126906,#126907), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#124514 = CARTESIAN_POINT('',(1.591299156552,8.15)); -#124515 = CARTESIAN_POINT('',(1.591299156552,8.35)); -#124516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124517 = PCURVE('',#93848,#124518); -#124518 = DEFINITIONAL_REPRESENTATION('',(#124519),#124523); -#124519 = LINE('',#124520,#124521); -#124520 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#124521 = VECTOR('',#124522,1.); -#124522 = DIRECTION('',(4.440892098501E-016,1.)); -#124523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124524 = ORIENTED_EDGE('',*,*,#124525,.T.); -#124525 = EDGE_CURVE('',#124504,#124258,#124526,.T.); -#124526 = SURFACE_CURVE('',#124527,(#124532,#124538),.PCURVE_S1.); -#124527 = CIRCLE('',#124528,0.2192697516); -#124528 = AXIS2_PLACEMENT_3D('',#124529,#124530,#124531); -#124529 = CARTESIAN_POINT('',(10.30032442045,8.15,0.530776333563)); -#124530 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124531 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#124532 = PCURVE('',#124273,#124533); -#124533 = DEFINITIONAL_REPRESENTATION('',(#124534),#124537); -#124534 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124535,#124536), +#126906 = CARTESIAN_POINT('',(1.591299156552,8.15)); +#126907 = CARTESIAN_POINT('',(1.591299156552,8.35)); +#126908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126909 = PCURVE('',#96240,#126910); +#126910 = DEFINITIONAL_REPRESENTATION('',(#126911),#126915); +#126911 = LINE('',#126912,#126913); +#126912 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#126913 = VECTOR('',#126914,1.); +#126914 = DIRECTION('',(4.440892098501E-016,1.)); +#126915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126916 = ORIENTED_EDGE('',*,*,#126917,.T.); +#126917 = EDGE_CURVE('',#126896,#126650,#126918,.T.); +#126918 = SURFACE_CURVE('',#126919,(#126924,#126930),.PCURVE_S1.); +#126919 = CIRCLE('',#126920,0.2192697516); +#126920 = AXIS2_PLACEMENT_3D('',#126921,#126922,#126923); +#126921 = CARTESIAN_POINT('',(10.30032442045,8.15,0.530776333563)); +#126922 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#126923 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#126924 = PCURVE('',#126665,#126925); +#126925 = DEFINITIONAL_REPRESENTATION('',(#126926),#126929); +#126926 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126927,#126928), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#124535 = CARTESIAN_POINT('',(1.591299156552,8.15)); -#124536 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#124537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126927 = CARTESIAN_POINT('',(1.591299156552,8.15)); +#126928 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#126929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124538 = PCURVE('',#93822,#124539); -#124539 = DEFINITIONAL_REPRESENTATION('',(#124540),#124548); -#124540 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124541,#124542,#124543, - #124544,#124545,#124546,#124547),.UNSPECIFIED.,.T.,.F.) +#126930 = PCURVE('',#96214,#126931); +#126931 = DEFINITIONAL_REPRESENTATION('',(#126932),#126940); +#126932 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126933,#126934,#126935, + #126936,#126937,#126938,#126939),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#124541 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#124542 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#124543 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#124544 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#124545 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#124546 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#124547 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#124548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#126933 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#126934 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#126935 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#126936 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#126937 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#126938 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#126939 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#126940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124549 = ADVANCED_FACE('',(#124550),#93794,.T.); -#124550 = FACE_BOUND('',#124551,.T.); -#124551 = EDGE_LOOP('',(#124552,#124573,#124574,#124595)); -#124552 = ORIENTED_EDGE('',*,*,#124553,.F.); -#124553 = EDGE_CURVE('',#124407,#93751,#124554,.T.); -#124554 = SURFACE_CURVE('',#124555,(#124559,#124566),.PCURVE_S1.); -#124555 = LINE('',#124556,#124557); -#124556 = CARTESIAN_POINT('',(10.527847992439,8.35,0.65)); -#124557 = VECTOR('',#124558,1.); -#124558 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#124559 = PCURVE('',#93794,#124560); -#124560 = DEFINITIONAL_REPRESENTATION('',(#124561),#124565); -#124561 = LINE('',#124562,#124563); -#124562 = CARTESIAN_POINT('',(0.E+000,0.2)); -#124563 = VECTOR('',#124564,1.); -#124564 = DIRECTION('',(1.,-1.082494723017E-063)); -#124565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124566 = PCURVE('',#93766,#124567); -#124567 = DEFINITIONAL_REPRESENTATION('',(#124568),#124572); -#124568 = LINE('',#124569,#124570); -#124569 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124570 = VECTOR('',#124571,1.); -#124571 = DIRECTION('',(3.563627120235E-016,-1.)); -#124572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124573 = ORIENTED_EDGE('',*,*,#124429,.T.); -#124574 = ORIENTED_EDGE('',*,*,#124575,.T.); -#124575 = EDGE_CURVE('',#124430,#93779,#124576,.T.); -#124576 = SURFACE_CURVE('',#124577,(#124581,#124588),.PCURVE_S1.); -#124577 = LINE('',#124578,#124579); -#124578 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); -#124579 = VECTOR('',#124580,1.); -#124580 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#124581 = PCURVE('',#93794,#124582); -#124582 = DEFINITIONAL_REPRESENTATION('',(#124583),#124587); -#124583 = LINE('',#124584,#124585); -#124584 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124585 = VECTOR('',#124586,1.); -#124586 = DIRECTION('',(1.,-1.082494723017E-063)); -#124587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124588 = PCURVE('',#93822,#124589); -#124589 = DEFINITIONAL_REPRESENTATION('',(#124590),#124594); -#124590 = LINE('',#124591,#124592); -#124591 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124592 = VECTOR('',#124593,1.); -#124593 = DIRECTION('',(-3.563627120235E-016,-1.)); -#124594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124595 = ORIENTED_EDGE('',*,*,#93778,.F.); -#124596 = ADVANCED_FACE('',(#124597),#93766,.T.); -#124597 = FACE_BOUND('',#124598,.T.); -#124598 = EDGE_LOOP('',(#124599,#124620,#124621,#124622,#124623,#124624, - #124645,#124646,#124647,#124648,#124649,#124650)); -#124599 = ORIENTED_EDGE('',*,*,#124600,.F.); -#124600 = EDGE_CURVE('',#124481,#93749,#124601,.T.); -#124601 = SURFACE_CURVE('',#124602,(#124606,#124613),.PCURVE_S1.); -#124602 = LINE('',#124603,#124604); -#124603 = CARTESIAN_POINT('',(10.527847992439,8.35,0.75)); -#124604 = VECTOR('',#124605,1.); -#124605 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#124606 = PCURVE('',#93766,#124607); -#124607 = DEFINITIONAL_REPRESENTATION('',(#124608),#124612); -#124608 = LINE('',#124609,#124610); -#124609 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#124610 = VECTOR('',#124611,1.); -#124611 = DIRECTION('',(3.563627120235E-016,-1.)); -#124612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124613 = PCURVE('',#93848,#124614); -#124614 = DEFINITIONAL_REPRESENTATION('',(#124615),#124619); -#124615 = LINE('',#124616,#124617); -#124616 = CARTESIAN_POINT('',(0.E+000,0.2)); -#124617 = VECTOR('',#124618,1.); -#124618 = DIRECTION('',(-1.,-1.082494723017E-063)); -#124619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124620 = ORIENTED_EDGE('',*,*,#124480,.T.); -#124621 = ORIENTED_EDGE('',*,*,#124306,.T.); -#124622 = ORIENTED_EDGE('',*,*,#124226,.T.); -#124623 = ORIENTED_EDGE('',*,*,#124023,.T.); -#124624 = ORIENTED_EDGE('',*,*,#124625,.F.); -#124625 = EDGE_CURVE('',#123887,#123994,#124626,.T.); -#124626 = SURFACE_CURVE('',#124627,(#124631,#124638),.PCURVE_S1.); -#124627 = LINE('',#124628,#124629); -#124628 = CARTESIAN_POINT('',(11.,8.35,1.159810404338E-002)); -#124629 = VECTOR('',#124630,1.); -#124630 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#124631 = PCURVE('',#93766,#124632); -#124632 = DEFINITIONAL_REPRESENTATION('',(#124633),#124637); -#124633 = LINE('',#124634,#124635); -#124634 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#124635 = VECTOR('',#124636,1.); -#124636 = DIRECTION('',(1.,2.101748079665E-016)); -#124637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124638 = PCURVE('',#123907,#124639); -#124639 = DEFINITIONAL_REPRESENTATION('',(#124640),#124644); -#124640 = LINE('',#124641,#124642); -#124641 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#124642 = VECTOR('',#124643,1.); -#124643 = DIRECTION('',(1.194699204908E-017,1.)); -#124644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124645 = ORIENTED_EDGE('',*,*,#123969,.F.); -#124646 = ORIENTED_EDGE('',*,*,#124097,.F.); -#124647 = ORIENTED_EDGE('',*,*,#124359,.F.); -#124648 = ORIENTED_EDGE('',*,*,#124406,.F.); -#124649 = ORIENTED_EDGE('',*,*,#124553,.T.); -#124650 = ORIENTED_EDGE('',*,*,#93748,.F.); -#124651 = ADVANCED_FACE('',(#124652),#93848,.T.); -#124652 = FACE_BOUND('',#124653,.T.); -#124653 = EDGE_LOOP('',(#124654,#124675,#124676,#124677)); -#124654 = ORIENTED_EDGE('',*,*,#124655,.F.); -#124655 = EDGE_CURVE('',#124504,#93807,#124656,.T.); -#124656 = SURFACE_CURVE('',#124657,(#124661,#124668),.PCURVE_S1.); -#124657 = LINE('',#124658,#124659); -#124658 = CARTESIAN_POINT('',(10.527847992439,8.15,0.75)); -#124659 = VECTOR('',#124660,1.); -#124660 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#124661 = PCURVE('',#93848,#124662); -#124662 = DEFINITIONAL_REPRESENTATION('',(#124663),#124667); -#124663 = LINE('',#124664,#124665); -#124664 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124665 = VECTOR('',#124666,1.); -#124666 = DIRECTION('',(-1.,-1.082494723017E-063)); -#124667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124668 = PCURVE('',#93822,#124669); -#124669 = DEFINITIONAL_REPRESENTATION('',(#124670),#124674); -#124670 = LINE('',#124671,#124672); -#124671 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#124672 = VECTOR('',#124673,1.); -#124673 = DIRECTION('',(-3.563627120235E-016,-1.)); -#124674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124675 = ORIENTED_EDGE('',*,*,#124503,.T.); -#124676 = ORIENTED_EDGE('',*,*,#124600,.T.); -#124677 = ORIENTED_EDGE('',*,*,#93834,.F.); -#124678 = ADVANCED_FACE('',(#124679),#93822,.T.); -#124679 = FACE_BOUND('',#124680,.T.); -#124680 = EDGE_LOOP('',(#124681,#124682,#124683,#124684,#124685,#124686, - #124707,#124708,#124709,#124710,#124711,#124712)); -#124681 = ORIENTED_EDGE('',*,*,#124575,.F.); -#124682 = ORIENTED_EDGE('',*,*,#124451,.T.); -#124683 = ORIENTED_EDGE('',*,*,#124381,.T.); -#124684 = ORIENTED_EDGE('',*,*,#124125,.T.); -#124685 = ORIENTED_EDGE('',*,*,#123919,.T.); -#124686 = ORIENTED_EDGE('',*,*,#124687,.F.); -#124687 = EDGE_CURVE('',#123996,#123885,#124688,.T.); -#124688 = SURFACE_CURVE('',#124689,(#124693,#124700),.PCURVE_S1.); -#124689 = LINE('',#124690,#124691); -#124690 = CARTESIAN_POINT('',(11.,8.15,1.159810404338E-002)); -#124691 = VECTOR('',#124692,1.); -#124692 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#124693 = PCURVE('',#93822,#124694); -#124694 = DEFINITIONAL_REPRESENTATION('',(#124695),#124699); -#124695 = LINE('',#124696,#124697); -#124696 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#124697 = VECTOR('',#124698,1.); -#124698 = DIRECTION('',(1.,-2.101748079665E-016)); -#124699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124700 = PCURVE('',#123907,#124701); -#124701 = DEFINITIONAL_REPRESENTATION('',(#124702),#124706); -#124702 = LINE('',#124703,#124704); -#124703 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#124704 = VECTOR('',#124705,1.); -#124705 = DIRECTION('',(-1.194699204908E-017,-1.)); -#124706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124707 = ORIENTED_EDGE('',*,*,#124073,.F.); -#124708 = ORIENTED_EDGE('',*,*,#124176,.F.); -#124709 = ORIENTED_EDGE('',*,*,#124284,.F.); -#124710 = ORIENTED_EDGE('',*,*,#124525,.F.); -#124711 = ORIENTED_EDGE('',*,*,#124655,.T.); -#124712 = ORIENTED_EDGE('',*,*,#93806,.F.); -#124713 = ADVANCED_FACE('',(#124714),#123907,.T.); -#124714 = FACE_BOUND('',#124715,.T.); -#124715 = EDGE_LOOP('',(#124716,#124717,#124718,#124719)); -#124716 = ORIENTED_EDGE('',*,*,#124625,.T.); -#124717 = ORIENTED_EDGE('',*,*,#123993,.T.); -#124718 = ORIENTED_EDGE('',*,*,#124687,.T.); -#124719 = ORIENTED_EDGE('',*,*,#123884,.T.); -#124720 = ADVANCED_FACE('',(#124721),#124735,.F.); -#124721 = FACE_BOUND('',#124722,.T.); -#124722 = EDGE_LOOP('',(#124723,#124758,#124781,#124808)); -#124723 = ORIENTED_EDGE('',*,*,#124724,.F.); -#124724 = EDGE_CURVE('',#124725,#124727,#124729,.T.); -#124725 = VERTEX_POINT('',#124726); -#124726 = CARTESIAN_POINT('',(11.,7.65,-0.308197125857)); -#124727 = VERTEX_POINT('',#124728); -#124728 = CARTESIAN_POINT('',(11.,7.85,-0.308197125857)); -#124729 = SURFACE_CURVE('',#124730,(#124734,#124746),.PCURVE_S1.); -#124730 = LINE('',#124731,#124732); -#124731 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#124732 = VECTOR('',#124733,1.); -#124733 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124734 = PCURVE('',#124735,#124740); -#124735 = PLANE('',#124736); -#124736 = AXIS2_PLACEMENT_3D('',#124737,#124738,#124739); -#124737 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#126941 = ADVANCED_FACE('',(#126942),#96186,.T.); +#126942 = FACE_BOUND('',#126943,.T.); +#126943 = EDGE_LOOP('',(#126944,#126965,#126966,#126987)); +#126944 = ORIENTED_EDGE('',*,*,#126945,.F.); +#126945 = EDGE_CURVE('',#126799,#96143,#126946,.T.); +#126946 = SURFACE_CURVE('',#126947,(#126951,#126958),.PCURVE_S1.); +#126947 = LINE('',#126948,#126949); +#126948 = CARTESIAN_POINT('',(10.527847992439,8.35,0.65)); +#126949 = VECTOR('',#126950,1.); +#126950 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126951 = PCURVE('',#96186,#126952); +#126952 = DEFINITIONAL_REPRESENTATION('',(#126953),#126957); +#126953 = LINE('',#126954,#126955); +#126954 = CARTESIAN_POINT('',(0.E+000,0.2)); +#126955 = VECTOR('',#126956,1.); +#126956 = DIRECTION('',(1.,-1.082494723017E-063)); +#126957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126958 = PCURVE('',#96158,#126959); +#126959 = DEFINITIONAL_REPRESENTATION('',(#126960),#126964); +#126960 = LINE('',#126961,#126962); +#126961 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126962 = VECTOR('',#126963,1.); +#126963 = DIRECTION('',(3.563627120235E-016,-1.)); +#126964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126965 = ORIENTED_EDGE('',*,*,#126821,.T.); +#126966 = ORIENTED_EDGE('',*,*,#126967,.T.); +#126967 = EDGE_CURVE('',#126822,#96171,#126968,.T.); +#126968 = SURFACE_CURVE('',#126969,(#126973,#126980),.PCURVE_S1.); +#126969 = LINE('',#126970,#126971); +#126970 = CARTESIAN_POINT('',(10.527847992439,8.15,0.65)); +#126971 = VECTOR('',#126972,1.); +#126972 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126973 = PCURVE('',#96186,#126974); +#126974 = DEFINITIONAL_REPRESENTATION('',(#126975),#126979); +#126975 = LINE('',#126976,#126977); +#126976 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126977 = VECTOR('',#126978,1.); +#126978 = DIRECTION('',(1.,-1.082494723017E-063)); +#126979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126980 = PCURVE('',#96214,#126981); +#126981 = DEFINITIONAL_REPRESENTATION('',(#126982),#126986); +#126982 = LINE('',#126983,#126984); +#126983 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#126984 = VECTOR('',#126985,1.); +#126985 = DIRECTION('',(-3.563627120235E-016,-1.)); +#126986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#126987 = ORIENTED_EDGE('',*,*,#96170,.F.); +#126988 = ADVANCED_FACE('',(#126989),#96158,.T.); +#126989 = FACE_BOUND('',#126990,.T.); +#126990 = EDGE_LOOP('',(#126991,#127012,#127013,#127014,#127015,#127016, + #127037,#127038,#127039,#127040,#127041,#127042)); +#126991 = ORIENTED_EDGE('',*,*,#126992,.F.); +#126992 = EDGE_CURVE('',#126873,#96141,#126993,.T.); +#126993 = SURFACE_CURVE('',#126994,(#126998,#127005),.PCURVE_S1.); +#126994 = LINE('',#126995,#126996); +#126995 = CARTESIAN_POINT('',(10.527847992439,8.35,0.75)); +#126996 = VECTOR('',#126997,1.); +#126997 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#126998 = PCURVE('',#96158,#126999); +#126999 = DEFINITIONAL_REPRESENTATION('',(#127000),#127004); +#127000 = LINE('',#127001,#127002); +#127001 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#127002 = VECTOR('',#127003,1.); +#127003 = DIRECTION('',(3.563627120235E-016,-1.)); +#127004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127005 = PCURVE('',#96240,#127006); +#127006 = DEFINITIONAL_REPRESENTATION('',(#127007),#127011); +#127007 = LINE('',#127008,#127009); +#127008 = CARTESIAN_POINT('',(0.E+000,0.2)); +#127009 = VECTOR('',#127010,1.); +#127010 = DIRECTION('',(-1.,-1.082494723017E-063)); +#127011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127012 = ORIENTED_EDGE('',*,*,#126872,.T.); +#127013 = ORIENTED_EDGE('',*,*,#126698,.T.); +#127014 = ORIENTED_EDGE('',*,*,#126618,.T.); +#127015 = ORIENTED_EDGE('',*,*,#126415,.T.); +#127016 = ORIENTED_EDGE('',*,*,#127017,.F.); +#127017 = EDGE_CURVE('',#126279,#126386,#127018,.T.); +#127018 = SURFACE_CURVE('',#127019,(#127023,#127030),.PCURVE_S1.); +#127019 = LINE('',#127020,#127021); +#127020 = CARTESIAN_POINT('',(11.,8.35,1.159810404338E-002)); +#127021 = VECTOR('',#127022,1.); +#127022 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#127023 = PCURVE('',#96158,#127024); +#127024 = DEFINITIONAL_REPRESENTATION('',(#127025),#127029); +#127025 = LINE('',#127026,#127027); +#127026 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#127027 = VECTOR('',#127028,1.); +#127028 = DIRECTION('',(1.,2.101748079665E-016)); +#127029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127030 = PCURVE('',#126299,#127031); +#127031 = DEFINITIONAL_REPRESENTATION('',(#127032),#127036); +#127032 = LINE('',#127033,#127034); +#127033 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#127034 = VECTOR('',#127035,1.); +#127035 = DIRECTION('',(1.194699204908E-017,1.)); +#127036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127037 = ORIENTED_EDGE('',*,*,#126361,.F.); +#127038 = ORIENTED_EDGE('',*,*,#126489,.F.); +#127039 = ORIENTED_EDGE('',*,*,#126751,.F.); +#127040 = ORIENTED_EDGE('',*,*,#126798,.F.); +#127041 = ORIENTED_EDGE('',*,*,#126945,.T.); +#127042 = ORIENTED_EDGE('',*,*,#96140,.F.); +#127043 = ADVANCED_FACE('',(#127044),#96240,.T.); +#127044 = FACE_BOUND('',#127045,.T.); +#127045 = EDGE_LOOP('',(#127046,#127067,#127068,#127069)); +#127046 = ORIENTED_EDGE('',*,*,#127047,.F.); +#127047 = EDGE_CURVE('',#126896,#96199,#127048,.T.); +#127048 = SURFACE_CURVE('',#127049,(#127053,#127060),.PCURVE_S1.); +#127049 = LINE('',#127050,#127051); +#127050 = CARTESIAN_POINT('',(10.527847992439,8.15,0.75)); +#127051 = VECTOR('',#127052,1.); +#127052 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#127053 = PCURVE('',#96240,#127054); +#127054 = DEFINITIONAL_REPRESENTATION('',(#127055),#127059); +#127055 = LINE('',#127056,#127057); +#127056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127057 = VECTOR('',#127058,1.); +#127058 = DIRECTION('',(-1.,-1.082494723017E-063)); +#127059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127060 = PCURVE('',#96214,#127061); +#127061 = DEFINITIONAL_REPRESENTATION('',(#127062),#127066); +#127062 = LINE('',#127063,#127064); +#127063 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#127064 = VECTOR('',#127065,1.); +#127065 = DIRECTION('',(-3.563627120235E-016,-1.)); +#127066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127067 = ORIENTED_EDGE('',*,*,#126895,.T.); +#127068 = ORIENTED_EDGE('',*,*,#126992,.T.); +#127069 = ORIENTED_EDGE('',*,*,#96226,.F.); +#127070 = ADVANCED_FACE('',(#127071),#96214,.T.); +#127071 = FACE_BOUND('',#127072,.T.); +#127072 = EDGE_LOOP('',(#127073,#127074,#127075,#127076,#127077,#127078, + #127099,#127100,#127101,#127102,#127103,#127104)); +#127073 = ORIENTED_EDGE('',*,*,#126967,.F.); +#127074 = ORIENTED_EDGE('',*,*,#126843,.T.); +#127075 = ORIENTED_EDGE('',*,*,#126773,.T.); +#127076 = ORIENTED_EDGE('',*,*,#126517,.T.); +#127077 = ORIENTED_EDGE('',*,*,#126311,.T.); +#127078 = ORIENTED_EDGE('',*,*,#127079,.F.); +#127079 = EDGE_CURVE('',#126388,#126277,#127080,.T.); +#127080 = SURFACE_CURVE('',#127081,(#127085,#127092),.PCURVE_S1.); +#127081 = LINE('',#127082,#127083); +#127082 = CARTESIAN_POINT('',(11.,8.15,1.159810404338E-002)); +#127083 = VECTOR('',#127084,1.); +#127084 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#127085 = PCURVE('',#96214,#127086); +#127086 = DEFINITIONAL_REPRESENTATION('',(#127087),#127091); +#127087 = LINE('',#127088,#127089); +#127088 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#127089 = VECTOR('',#127090,1.); +#127090 = DIRECTION('',(1.,-2.101748079665E-016)); +#127091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127092 = PCURVE('',#126299,#127093); +#127093 = DEFINITIONAL_REPRESENTATION('',(#127094),#127098); +#127094 = LINE('',#127095,#127096); +#127095 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#127096 = VECTOR('',#127097,1.); +#127097 = DIRECTION('',(-1.194699204908E-017,-1.)); +#127098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127099 = ORIENTED_EDGE('',*,*,#126465,.F.); +#127100 = ORIENTED_EDGE('',*,*,#126568,.F.); +#127101 = ORIENTED_EDGE('',*,*,#126676,.F.); +#127102 = ORIENTED_EDGE('',*,*,#126917,.F.); +#127103 = ORIENTED_EDGE('',*,*,#127047,.T.); +#127104 = ORIENTED_EDGE('',*,*,#96198,.F.); +#127105 = ADVANCED_FACE('',(#127106),#126299,.T.); +#127106 = FACE_BOUND('',#127107,.T.); +#127107 = EDGE_LOOP('',(#127108,#127109,#127110,#127111)); +#127108 = ORIENTED_EDGE('',*,*,#127017,.T.); +#127109 = ORIENTED_EDGE('',*,*,#126385,.T.); +#127110 = ORIENTED_EDGE('',*,*,#127079,.T.); +#127111 = ORIENTED_EDGE('',*,*,#126276,.T.); +#127112 = ADVANCED_FACE('',(#127113),#127127,.F.); +#127113 = FACE_BOUND('',#127114,.T.); +#127114 = EDGE_LOOP('',(#127115,#127150,#127173,#127200)); +#127115 = ORIENTED_EDGE('',*,*,#127116,.F.); +#127116 = EDGE_CURVE('',#127117,#127119,#127121,.T.); +#127117 = VERTEX_POINT('',#127118); +#127118 = CARTESIAN_POINT('',(11.,7.65,-0.308197125857)); +#127119 = VERTEX_POINT('',#127120); +#127120 = CARTESIAN_POINT('',(11.,7.85,-0.308197125857)); +#127121 = SURFACE_CURVE('',#127122,(#127126,#127138),.PCURVE_S1.); +#127122 = LINE('',#127123,#127124); +#127123 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#127124 = VECTOR('',#127125,1.); +#127125 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127126 = PCURVE('',#127127,#127132); +#127127 = PLANE('',#127128); +#127128 = AXIS2_PLACEMENT_3D('',#127129,#127130,#127131); +#127129 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#124738 = DIRECTION('',(0.E+000,0.E+000,1.)); -#124739 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124740 = DEFINITIONAL_REPRESENTATION('',(#124741),#124745); -#124741 = LINE('',#124742,#124743); -#124742 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#124743 = VECTOR('',#124744,1.); -#124744 = DIRECTION('',(4.440892098501E-016,1.)); -#124745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124746 = PCURVE('',#124747,#124752); -#124747 = PLANE('',#124748); -#124748 = AXIS2_PLACEMENT_3D('',#124749,#124750,#124751); -#124749 = CARTESIAN_POINT('',(11.,7.75,-0.258196742327)); -#124750 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#124751 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124752 = DEFINITIONAL_REPRESENTATION('',(#124753),#124757); -#124753 = LINE('',#124754,#124755); -#124754 = CARTESIAN_POINT('',(-7.75,-5.000038352949E-002)); -#124755 = VECTOR('',#124756,1.); -#124756 = DIRECTION('',(1.,0.E+000)); -#124757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124758 = ORIENTED_EDGE('',*,*,#124759,.F.); -#124759 = EDGE_CURVE('',#124760,#124725,#124762,.T.); -#124760 = VERTEX_POINT('',#124761); -#124761 = CARTESIAN_POINT('',(10.74341632541,7.65,-0.308197125857)); -#124762 = SURFACE_CURVE('',#124763,(#124767,#124774),.PCURVE_S1.); -#124763 = LINE('',#124764,#124765); -#124764 = CARTESIAN_POINT('',(10.74341632541,7.65,-0.308197125857)); -#124765 = VECTOR('',#124766,1.); -#124766 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124767 = PCURVE('',#124735,#124768); -#124768 = DEFINITIONAL_REPRESENTATION('',(#124769),#124773); -#124769 = LINE('',#124770,#124771); -#124770 = CARTESIAN_POINT('',(3.552713678801E-015,7.65)); -#124771 = VECTOR('',#124772,1.); -#124772 = DIRECTION('',(1.,0.E+000)); -#124773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124774 = PCURVE('',#93708,#124775); -#124775 = DEFINITIONAL_REPRESENTATION('',(#124776),#124780); -#124776 = LINE('',#124777,#124778); -#124777 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#124778 = VECTOR('',#124779,1.); -#124779 = DIRECTION('',(0.E+000,1.)); -#124780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124781 = ORIENTED_EDGE('',*,*,#124782,.F.); -#124782 = EDGE_CURVE('',#124783,#124760,#124785,.T.); -#124783 = VERTEX_POINT('',#124784); -#124784 = CARTESIAN_POINT('',(10.74341632541,7.85,-0.308197125857)); -#124785 = SURFACE_CURVE('',#124786,(#124790,#124797),.PCURVE_S1.); -#124786 = LINE('',#124787,#124788); -#124787 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#127130 = DIRECTION('',(0.E+000,0.E+000,1.)); +#127131 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127132 = DEFINITIONAL_REPRESENTATION('',(#127133),#127137); +#127133 = LINE('',#127134,#127135); +#127134 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#127135 = VECTOR('',#127136,1.); +#127136 = DIRECTION('',(4.440892098501E-016,1.)); +#127137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127138 = PCURVE('',#127139,#127144); +#127139 = PLANE('',#127140); +#127140 = AXIS2_PLACEMENT_3D('',#127141,#127142,#127143); +#127141 = CARTESIAN_POINT('',(11.,7.75,-0.258196742327)); +#127142 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#127143 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127144 = DEFINITIONAL_REPRESENTATION('',(#127145),#127149); +#127145 = LINE('',#127146,#127147); +#127146 = CARTESIAN_POINT('',(-7.75,-5.000038352949E-002)); +#127147 = VECTOR('',#127148,1.); +#127148 = DIRECTION('',(1.,0.E+000)); +#127149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127150 = ORIENTED_EDGE('',*,*,#127151,.F.); +#127151 = EDGE_CURVE('',#127152,#127117,#127154,.T.); +#127152 = VERTEX_POINT('',#127153); +#127153 = CARTESIAN_POINT('',(10.74341632541,7.65,-0.308197125857)); +#127154 = SURFACE_CURVE('',#127155,(#127159,#127166),.PCURVE_S1.); +#127155 = LINE('',#127156,#127157); +#127156 = CARTESIAN_POINT('',(10.74341632541,7.65,-0.308197125857)); +#127157 = VECTOR('',#127158,1.); +#127158 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127159 = PCURVE('',#127127,#127160); +#127160 = DEFINITIONAL_REPRESENTATION('',(#127161),#127165); +#127161 = LINE('',#127162,#127163); +#127162 = CARTESIAN_POINT('',(3.552713678801E-015,7.65)); +#127163 = VECTOR('',#127164,1.); +#127164 = DIRECTION('',(1.,0.E+000)); +#127165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127166 = PCURVE('',#96100,#127167); +#127167 = DEFINITIONAL_REPRESENTATION('',(#127168),#127172); +#127168 = LINE('',#127169,#127170); +#127169 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#127170 = VECTOR('',#127171,1.); +#127171 = DIRECTION('',(0.E+000,1.)); +#127172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127173 = ORIENTED_EDGE('',*,*,#127174,.F.); +#127174 = EDGE_CURVE('',#127175,#127152,#127177,.T.); +#127175 = VERTEX_POINT('',#127176); +#127176 = CARTESIAN_POINT('',(10.74341632541,7.85,-0.308197125857)); +#127177 = SURFACE_CURVE('',#127178,(#127182,#127189),.PCURVE_S1.); +#127178 = LINE('',#127179,#127180); +#127179 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#124788 = VECTOR('',#124789,1.); -#124789 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124790 = PCURVE('',#124735,#124791); -#124791 = DEFINITIONAL_REPRESENTATION('',(#124792),#124796); -#124792 = LINE('',#124793,#124794); -#124793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124794 = VECTOR('',#124795,1.); -#124795 = DIRECTION('',(-4.440892098501E-016,-1.)); -#124796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124797 = PCURVE('',#124798,#124803); -#124798 = CYLINDRICAL_SURFACE('',#124799,0.308574064194); -#124799 = AXIS2_PLACEMENT_3D('',#124800,#124801,#124802); -#124800 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#127180 = VECTOR('',#127181,1.); +#127181 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127182 = PCURVE('',#127127,#127183); +#127183 = DEFINITIONAL_REPRESENTATION('',(#127184),#127188); +#127184 = LINE('',#127185,#127186); +#127185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127186 = VECTOR('',#127187,1.); +#127187 = DIRECTION('',(-4.440892098501E-016,-1.)); +#127188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127189 = PCURVE('',#127190,#127195); +#127190 = CYLINDRICAL_SURFACE('',#127191,0.308574064194); +#127191 = AXIS2_PLACEMENT_3D('',#127192,#127193,#127194); +#127192 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#124801 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124802 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124803 = DEFINITIONAL_REPRESENTATION('',(#124804),#124807); -#124804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124805,#124806), +#127193 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127194 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127195 = DEFINITIONAL_REPRESENTATION('',(#127196),#127199); +#127196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127197,#127198), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#124805 = CARTESIAN_POINT('',(4.761821717947,-7.85)); -#124806 = CARTESIAN_POINT('',(4.761821717947,-7.65)); -#124807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124808 = ORIENTED_EDGE('',*,*,#124809,.T.); -#124809 = EDGE_CURVE('',#124783,#124727,#124810,.T.); -#124810 = SURFACE_CURVE('',#124811,(#124815,#124822),.PCURVE_S1.); -#124811 = LINE('',#124812,#124813); -#124812 = CARTESIAN_POINT('',(10.74341632541,7.85,-0.308197125857)); -#124813 = VECTOR('',#124814,1.); -#124814 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124815 = PCURVE('',#124735,#124816); -#124816 = DEFINITIONAL_REPRESENTATION('',(#124817),#124821); -#124817 = LINE('',#124818,#124819); -#124818 = CARTESIAN_POINT('',(3.552713678801E-015,7.85)); -#124819 = VECTOR('',#124820,1.); -#124820 = DIRECTION('',(1.,0.E+000)); -#124821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124822 = PCURVE('',#93652,#124823); -#124823 = DEFINITIONAL_REPRESENTATION('',(#124824),#124828); -#124824 = LINE('',#124825,#124826); -#124825 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#124826 = VECTOR('',#124827,1.); -#124827 = DIRECTION('',(0.E+000,1.)); -#124828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124829 = ADVANCED_FACE('',(#124830),#124844,.F.); -#124830 = FACE_BOUND('',#124831,.T.); -#124831 = EDGE_LOOP('',(#124832,#124862,#124885,#124912)); -#124832 = ORIENTED_EDGE('',*,*,#124833,.F.); -#124833 = EDGE_CURVE('',#124834,#124836,#124838,.T.); -#124834 = VERTEX_POINT('',#124835); -#124835 = CARTESIAN_POINT('',(11.,7.85,-0.208196358798)); -#124836 = VERTEX_POINT('',#124837); -#124837 = CARTESIAN_POINT('',(11.,7.65,-0.208196358798)); -#124838 = SURFACE_CURVE('',#124839,(#124843,#124855),.PCURVE_S1.); -#124839 = LINE('',#124840,#124841); -#124840 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#124841 = VECTOR('',#124842,1.); -#124842 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124843 = PCURVE('',#124844,#124849); -#124844 = PLANE('',#124845); -#124845 = AXIS2_PLACEMENT_3D('',#124846,#124847,#124848); -#124846 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#127197 = CARTESIAN_POINT('',(4.761821717947,-7.85)); +#127198 = CARTESIAN_POINT('',(4.761821717947,-7.65)); +#127199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127200 = ORIENTED_EDGE('',*,*,#127201,.T.); +#127201 = EDGE_CURVE('',#127175,#127119,#127202,.T.); +#127202 = SURFACE_CURVE('',#127203,(#127207,#127214),.PCURVE_S1.); +#127203 = LINE('',#127204,#127205); +#127204 = CARTESIAN_POINT('',(10.74341632541,7.85,-0.308197125857)); +#127205 = VECTOR('',#127206,1.); +#127206 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127207 = PCURVE('',#127127,#127208); +#127208 = DEFINITIONAL_REPRESENTATION('',(#127209),#127213); +#127209 = LINE('',#127210,#127211); +#127210 = CARTESIAN_POINT('',(3.552713678801E-015,7.85)); +#127211 = VECTOR('',#127212,1.); +#127212 = DIRECTION('',(1.,0.E+000)); +#127213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127214 = PCURVE('',#96044,#127215); +#127215 = DEFINITIONAL_REPRESENTATION('',(#127216),#127220); +#127216 = LINE('',#127217,#127218); +#127217 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#127218 = VECTOR('',#127219,1.); +#127219 = DIRECTION('',(0.E+000,1.)); +#127220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127221 = ADVANCED_FACE('',(#127222),#127236,.F.); +#127222 = FACE_BOUND('',#127223,.T.); +#127223 = EDGE_LOOP('',(#127224,#127254,#127277,#127304)); +#127224 = ORIENTED_EDGE('',*,*,#127225,.F.); +#127225 = EDGE_CURVE('',#127226,#127228,#127230,.T.); +#127226 = VERTEX_POINT('',#127227); +#127227 = CARTESIAN_POINT('',(11.,7.85,-0.208196358798)); +#127228 = VERTEX_POINT('',#127229); +#127229 = CARTESIAN_POINT('',(11.,7.65,-0.208196358798)); +#127230 = SURFACE_CURVE('',#127231,(#127235,#127247),.PCURVE_S1.); +#127231 = LINE('',#127232,#127233); +#127232 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#127233 = VECTOR('',#127234,1.); +#127234 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127235 = PCURVE('',#127236,#127241); +#127236 = PLANE('',#127237); +#127237 = AXIS2_PLACEMENT_3D('',#127238,#127239,#127240); +#127238 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#124847 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#124848 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#124849 = DEFINITIONAL_REPRESENTATION('',(#124850),#124854); -#124850 = LINE('',#124851,#124852); -#124851 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#124852 = VECTOR('',#124853,1.); -#124853 = DIRECTION('',(4.440892098501E-016,-1.)); -#124854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124855 = PCURVE('',#124747,#124856); -#124856 = DEFINITIONAL_REPRESENTATION('',(#124857),#124861); -#124857 = LINE('',#124858,#124859); -#124858 = CARTESIAN_POINT('',(-7.75,5.000038352949E-002)); -#124859 = VECTOR('',#124860,1.); -#124860 = DIRECTION('',(-1.,0.E+000)); -#124861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124862 = ORIENTED_EDGE('',*,*,#124863,.F.); -#124863 = EDGE_CURVE('',#124864,#124834,#124866,.T.); -#124864 = VERTEX_POINT('',#124865); -#124865 = CARTESIAN_POINT('',(10.740726081328,7.85,-0.208196358798)); -#124866 = SURFACE_CURVE('',#124867,(#124871,#124878),.PCURVE_S1.); -#124867 = LINE('',#124868,#124869); -#124868 = CARTESIAN_POINT('',(10.740726081328,7.85,-0.208196358798)); -#124869 = VECTOR('',#124870,1.); -#124870 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124871 = PCURVE('',#124844,#124872); -#124872 = DEFINITIONAL_REPRESENTATION('',(#124873),#124877); -#124873 = LINE('',#124874,#124875); -#124874 = CARTESIAN_POINT('',(-3.552713678801E-015,7.85)); -#124875 = VECTOR('',#124876,1.); -#124876 = DIRECTION('',(-1.,0.E+000)); -#124877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124878 = PCURVE('',#93652,#124879); -#124879 = DEFINITIONAL_REPRESENTATION('',(#124880),#124884); -#124880 = LINE('',#124881,#124882); -#124881 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#124882 = VECTOR('',#124883,1.); -#124883 = DIRECTION('',(0.E+000,1.)); -#124884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124885 = ORIENTED_EDGE('',*,*,#124886,.F.); -#124886 = EDGE_CURVE('',#124887,#124864,#124889,.T.); -#124887 = VERTEX_POINT('',#124888); -#124888 = CARTESIAN_POINT('',(10.740726081328,7.65,-0.208196358798)); -#124889 = SURFACE_CURVE('',#124890,(#124894,#124901),.PCURVE_S1.); -#124890 = LINE('',#124891,#124892); -#124891 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#127239 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#127240 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#127241 = DEFINITIONAL_REPRESENTATION('',(#127242),#127246); +#127242 = LINE('',#127243,#127244); +#127243 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#127244 = VECTOR('',#127245,1.); +#127245 = DIRECTION('',(4.440892098501E-016,-1.)); +#127246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127247 = PCURVE('',#127139,#127248); +#127248 = DEFINITIONAL_REPRESENTATION('',(#127249),#127253); +#127249 = LINE('',#127250,#127251); +#127250 = CARTESIAN_POINT('',(-7.75,5.000038352949E-002)); +#127251 = VECTOR('',#127252,1.); +#127252 = DIRECTION('',(-1.,0.E+000)); +#127253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127254 = ORIENTED_EDGE('',*,*,#127255,.F.); +#127255 = EDGE_CURVE('',#127256,#127226,#127258,.T.); +#127256 = VERTEX_POINT('',#127257); +#127257 = CARTESIAN_POINT('',(10.740726081328,7.85,-0.208196358798)); +#127258 = SURFACE_CURVE('',#127259,(#127263,#127270),.PCURVE_S1.); +#127259 = LINE('',#127260,#127261); +#127260 = CARTESIAN_POINT('',(10.740726081328,7.85,-0.208196358798)); +#127261 = VECTOR('',#127262,1.); +#127262 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127263 = PCURVE('',#127236,#127264); +#127264 = DEFINITIONAL_REPRESENTATION('',(#127265),#127269); +#127265 = LINE('',#127266,#127267); +#127266 = CARTESIAN_POINT('',(-3.552713678801E-015,7.85)); +#127267 = VECTOR('',#127268,1.); +#127268 = DIRECTION('',(-1.,0.E+000)); +#127269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127270 = PCURVE('',#96044,#127271); +#127271 = DEFINITIONAL_REPRESENTATION('',(#127272),#127276); +#127272 = LINE('',#127273,#127274); +#127273 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#127274 = VECTOR('',#127275,1.); +#127275 = DIRECTION('',(0.E+000,1.)); +#127276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127277 = ORIENTED_EDGE('',*,*,#127278,.F.); +#127278 = EDGE_CURVE('',#127279,#127256,#127281,.T.); +#127279 = VERTEX_POINT('',#127280); +#127280 = CARTESIAN_POINT('',(10.740726081328,7.65,-0.208196358798)); +#127281 = SURFACE_CURVE('',#127282,(#127286,#127293),.PCURVE_S1.); +#127282 = LINE('',#127283,#127284); +#127283 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#124892 = VECTOR('',#124893,1.); -#124893 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124894 = PCURVE('',#124844,#124895); -#124895 = DEFINITIONAL_REPRESENTATION('',(#124896),#124900); -#124896 = LINE('',#124897,#124898); -#124897 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#124898 = VECTOR('',#124899,1.); -#124899 = DIRECTION('',(-4.440892098501E-016,1.)); -#124900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124901 = PCURVE('',#124902,#124907); -#124902 = CYLINDRICAL_SURFACE('',#124903,0.208574704164); -#124903 = AXIS2_PLACEMENT_3D('',#124904,#124905,#124906); -#124904 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#127284 = VECTOR('',#127285,1.); +#127285 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127286 = PCURVE('',#127236,#127287); +#127287 = DEFINITIONAL_REPRESENTATION('',(#127288),#127292); +#127288 = LINE('',#127289,#127290); +#127289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127290 = VECTOR('',#127291,1.); +#127291 = DIRECTION('',(-4.440892098501E-016,1.)); +#127292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127293 = PCURVE('',#127294,#127299); +#127294 = CYLINDRICAL_SURFACE('',#127295,0.208574704164); +#127295 = AXIS2_PLACEMENT_3D('',#127296,#127297,#127298); +#127296 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#124905 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124906 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124907 = DEFINITIONAL_REPRESENTATION('',(#124908),#124911); -#124908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124909,#124910), +#127297 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127298 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127299 = DEFINITIONAL_REPRESENTATION('',(#127300),#127303); +#127300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127301,#127302), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#124909 = CARTESIAN_POINT('',(4.772630242227,-7.65)); -#124910 = CARTESIAN_POINT('',(4.772630242227,-7.85)); -#124911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124912 = ORIENTED_EDGE('',*,*,#124913,.T.); -#124913 = EDGE_CURVE('',#124887,#124836,#124914,.T.); -#124914 = SURFACE_CURVE('',#124915,(#124919,#124926),.PCURVE_S1.); -#124915 = LINE('',#124916,#124917); -#124916 = CARTESIAN_POINT('',(10.740726081328,7.65,-0.208196358798)); -#124917 = VECTOR('',#124918,1.); -#124918 = DIRECTION('',(1.,0.E+000,0.E+000)); -#124919 = PCURVE('',#124844,#124920); -#124920 = DEFINITIONAL_REPRESENTATION('',(#124921),#124925); -#124921 = LINE('',#124922,#124923); -#124922 = CARTESIAN_POINT('',(-3.552713678801E-015,7.65)); -#124923 = VECTOR('',#124924,1.); -#124924 = DIRECTION('',(-1.,0.E+000)); -#124925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124926 = PCURVE('',#93708,#124927); -#124927 = DEFINITIONAL_REPRESENTATION('',(#124928),#124932); -#124928 = LINE('',#124929,#124930); -#124929 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#124930 = VECTOR('',#124931,1.); -#124931 = DIRECTION('',(0.E+000,1.)); -#124932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124933 = ADVANCED_FACE('',(#124934),#124798,.T.); -#124934 = FACE_BOUND('',#124935,.T.); -#124935 = EDGE_LOOP('',(#124936,#124963,#124964,#124987)); -#124936 = ORIENTED_EDGE('',*,*,#124937,.T.); -#124937 = EDGE_CURVE('',#124938,#124783,#124940,.T.); -#124938 = VERTEX_POINT('',#124939); -#124939 = CARTESIAN_POINT('',(10.419594812019,7.85,0.E+000)); -#124940 = SURFACE_CURVE('',#124941,(#124946,#124952),.PCURVE_S1.); -#124941 = CIRCLE('',#124942,0.308574064194); -#124942 = AXIS2_PLACEMENT_3D('',#124943,#124944,#124945); -#124943 = CARTESIAN_POINT('',(10.728168876214,7.85,2.640924866458E-017) - ); -#124944 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124945 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124946 = PCURVE('',#124798,#124947); -#124947 = DEFINITIONAL_REPRESENTATION('',(#124948),#124951); -#124948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124949,#124950), +#127301 = CARTESIAN_POINT('',(4.772630242227,-7.65)); +#127302 = CARTESIAN_POINT('',(4.772630242227,-7.85)); +#127303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127304 = ORIENTED_EDGE('',*,*,#127305,.T.); +#127305 = EDGE_CURVE('',#127279,#127228,#127306,.T.); +#127306 = SURFACE_CURVE('',#127307,(#127311,#127318),.PCURVE_S1.); +#127307 = LINE('',#127308,#127309); +#127308 = CARTESIAN_POINT('',(10.740726081328,7.65,-0.208196358798)); +#127309 = VECTOR('',#127310,1.); +#127310 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127311 = PCURVE('',#127236,#127312); +#127312 = DEFINITIONAL_REPRESENTATION('',(#127313),#127317); +#127313 = LINE('',#127314,#127315); +#127314 = CARTESIAN_POINT('',(-3.552713678801E-015,7.65)); +#127315 = VECTOR('',#127316,1.); +#127316 = DIRECTION('',(-1.,0.E+000)); +#127317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127318 = PCURVE('',#96100,#127319); +#127319 = DEFINITIONAL_REPRESENTATION('',(#127320),#127324); +#127320 = LINE('',#127321,#127322); +#127321 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#127322 = VECTOR('',#127323,1.); +#127323 = DIRECTION('',(0.E+000,1.)); +#127324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127325 = ADVANCED_FACE('',(#127326),#127190,.T.); +#127326 = FACE_BOUND('',#127327,.T.); +#127327 = EDGE_LOOP('',(#127328,#127355,#127356,#127379)); +#127328 = ORIENTED_EDGE('',*,*,#127329,.T.); +#127329 = EDGE_CURVE('',#127330,#127175,#127332,.T.); +#127330 = VERTEX_POINT('',#127331); +#127331 = CARTESIAN_POINT('',(10.419594812019,7.85,0.E+000)); +#127332 = SURFACE_CURVE('',#127333,(#127338,#127344),.PCURVE_S1.); +#127333 = CIRCLE('',#127334,0.308574064194); +#127334 = AXIS2_PLACEMENT_3D('',#127335,#127336,#127337); +#127335 = CARTESIAN_POINT('',(10.728168876214,7.85,2.640924866458E-017) + ); +#127336 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127337 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127338 = PCURVE('',#127190,#127339); +#127339 = DEFINITIONAL_REPRESENTATION('',(#127340),#127343); +#127340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127341,#127342), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#124949 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#124950 = CARTESIAN_POINT('',(4.761821717947,-7.85)); -#124951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127341 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#127342 = CARTESIAN_POINT('',(4.761821717947,-7.85)); +#127343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124952 = PCURVE('',#93652,#124953); -#124953 = DEFINITIONAL_REPRESENTATION('',(#124954),#124962); -#124954 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#124955,#124956,#124957, - #124958,#124959,#124960,#124961),.UNSPECIFIED.,.T.,.F.) +#127344 = PCURVE('',#96044,#127345); +#127345 = DEFINITIONAL_REPRESENTATION('',(#127346),#127354); +#127346 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127347,#127348,#127349, + #127350,#127351,#127352,#127353),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#124955 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#124956 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#124957 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#124958 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#124959 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#124960 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#124961 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#124962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#124963 = ORIENTED_EDGE('',*,*,#124782,.T.); -#124964 = ORIENTED_EDGE('',*,*,#124965,.F.); -#124965 = EDGE_CURVE('',#124966,#124760,#124968,.T.); -#124966 = VERTEX_POINT('',#124967); -#124967 = CARTESIAN_POINT('',(10.419594812019,7.65,0.E+000)); -#124968 = SURFACE_CURVE('',#124969,(#124974,#124980),.PCURVE_S1.); -#124969 = CIRCLE('',#124970,0.308574064194); -#124970 = AXIS2_PLACEMENT_3D('',#124971,#124972,#124973); -#124971 = CARTESIAN_POINT('',(10.728168876214,7.65,2.640924866458E-017) - ); -#124972 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#124973 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#124974 = PCURVE('',#124798,#124975); -#124975 = DEFINITIONAL_REPRESENTATION('',(#124976),#124979); -#124976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124977,#124978), +#127347 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#127348 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#127349 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#127350 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#127351 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#127352 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#127353 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#127354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127355 = ORIENTED_EDGE('',*,*,#127174,.T.); +#127356 = ORIENTED_EDGE('',*,*,#127357,.F.); +#127357 = EDGE_CURVE('',#127358,#127152,#127360,.T.); +#127358 = VERTEX_POINT('',#127359); +#127359 = CARTESIAN_POINT('',(10.419594812019,7.65,0.E+000)); +#127360 = SURFACE_CURVE('',#127361,(#127366,#127372),.PCURVE_S1.); +#127361 = CIRCLE('',#127362,0.308574064194); +#127362 = AXIS2_PLACEMENT_3D('',#127363,#127364,#127365); +#127363 = CARTESIAN_POINT('',(10.728168876214,7.65,2.640924866458E-017) + ); +#127364 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127365 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127366 = PCURVE('',#127190,#127367); +#127367 = DEFINITIONAL_REPRESENTATION('',(#127368),#127371); +#127368 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127369,#127370), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#124977 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#124978 = CARTESIAN_POINT('',(4.761821717947,-7.65)); -#124979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127369 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#127370 = CARTESIAN_POINT('',(4.761821717947,-7.65)); +#127371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124980 = PCURVE('',#93708,#124981); -#124981 = DEFINITIONAL_REPRESENTATION('',(#124982),#124986); -#124982 = CIRCLE('',#124983,0.308574064194); -#124983 = AXIS2_PLACEMENT_2D('',#124984,#124985); -#124984 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#124985 = DIRECTION('',(0.E+000,1.)); -#124986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127372 = PCURVE('',#96100,#127373); +#127373 = DEFINITIONAL_REPRESENTATION('',(#127374),#127378); +#127374 = CIRCLE('',#127375,0.308574064194); +#127375 = AXIS2_PLACEMENT_2D('',#127376,#127377); +#127376 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#127377 = DIRECTION('',(0.E+000,1.)); +#127378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#124987 = ORIENTED_EDGE('',*,*,#124988,.T.); -#124988 = EDGE_CURVE('',#124966,#124938,#124989,.T.); -#124989 = SURFACE_CURVE('',#124990,(#124994,#125000),.PCURVE_S1.); -#124990 = LINE('',#124991,#124992); -#124991 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#127379 = ORIENTED_EDGE('',*,*,#127380,.T.); +#127380 = EDGE_CURVE('',#127358,#127330,#127381,.T.); +#127381 = SURFACE_CURVE('',#127382,(#127386,#127392),.PCURVE_S1.); +#127382 = LINE('',#127383,#127384); +#127383 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#124992 = VECTOR('',#124993,1.); -#124993 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#124994 = PCURVE('',#124798,#124995); -#124995 = DEFINITIONAL_REPRESENTATION('',(#124996),#124999); -#124996 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#124997,#124998), +#127384 = VECTOR('',#127385,1.); +#127385 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127386 = PCURVE('',#127190,#127387); +#127387 = DEFINITIONAL_REPRESENTATION('',(#127388),#127391); +#127388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127389,#127390), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#124997 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#124998 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#124999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127389 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#127390 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#127391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125000 = PCURVE('',#125001,#125006); -#125001 = PLANE('',#125002); -#125002 = AXIS2_PLACEMENT_3D('',#125003,#125004,#125005); -#125003 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#127392 = PCURVE('',#127393,#127398); +#127393 = PLANE('',#127394); +#127394 = AXIS2_PLACEMENT_3D('',#127395,#127396,#127397); +#127395 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#125004 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125005 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125006 = DEFINITIONAL_REPRESENTATION('',(#125007),#125011); -#125007 = LINE('',#125008,#125009); -#125008 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#125009 = VECTOR('',#125010,1.); -#125010 = DIRECTION('',(-1.,0.E+000)); -#125011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125012 = ADVANCED_FACE('',(#125013),#124902,.F.); -#125013 = FACE_BOUND('',#125014,.F.); -#125014 = EDGE_LOOP('',(#125015,#125038,#125065,#125090)); -#125015 = ORIENTED_EDGE('',*,*,#125016,.F.); -#125016 = EDGE_CURVE('',#125017,#124887,#125019,.T.); -#125017 = VERTEX_POINT('',#125018); -#125018 = CARTESIAN_POINT('',(10.51959417205,7.65,0.E+000)); -#125019 = SURFACE_CURVE('',#125020,(#125025,#125031),.PCURVE_S1.); -#125020 = CIRCLE('',#125021,0.208574704164); -#125021 = AXIS2_PLACEMENT_3D('',#125022,#125023,#125024); -#125022 = CARTESIAN_POINT('',(10.728168876214,7.65,2.640924866458E-017) - ); -#125023 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125024 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125025 = PCURVE('',#124902,#125026); -#125026 = DEFINITIONAL_REPRESENTATION('',(#125027),#125030); -#125027 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125028,#125029), +#127396 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127397 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127398 = DEFINITIONAL_REPRESENTATION('',(#127399),#127403); +#127399 = LINE('',#127400,#127401); +#127400 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#127401 = VECTOR('',#127402,1.); +#127402 = DIRECTION('',(-1.,0.E+000)); +#127403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127404 = ADVANCED_FACE('',(#127405),#127294,.F.); +#127405 = FACE_BOUND('',#127406,.F.); +#127406 = EDGE_LOOP('',(#127407,#127430,#127457,#127482)); +#127407 = ORIENTED_EDGE('',*,*,#127408,.F.); +#127408 = EDGE_CURVE('',#127409,#127279,#127411,.T.); +#127409 = VERTEX_POINT('',#127410); +#127410 = CARTESIAN_POINT('',(10.51959417205,7.65,0.E+000)); +#127411 = SURFACE_CURVE('',#127412,(#127417,#127423),.PCURVE_S1.); +#127412 = CIRCLE('',#127413,0.208574704164); +#127413 = AXIS2_PLACEMENT_3D('',#127414,#127415,#127416); +#127414 = CARTESIAN_POINT('',(10.728168876214,7.65,2.640924866458E-017) + ); +#127415 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127416 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127417 = PCURVE('',#127294,#127418); +#127418 = DEFINITIONAL_REPRESENTATION('',(#127419),#127422); +#127419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127420,#127421), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#125028 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#125029 = CARTESIAN_POINT('',(4.772630242227,-7.65)); -#125030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127420 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#127421 = CARTESIAN_POINT('',(4.772630242227,-7.65)); +#127422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125031 = PCURVE('',#93708,#125032); -#125032 = DEFINITIONAL_REPRESENTATION('',(#125033),#125037); -#125033 = CIRCLE('',#125034,0.208574704164); -#125034 = AXIS2_PLACEMENT_2D('',#125035,#125036); -#125035 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#125036 = DIRECTION('',(0.E+000,1.)); -#125037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127423 = PCURVE('',#96100,#127424); +#127424 = DEFINITIONAL_REPRESENTATION('',(#127425),#127429); +#127425 = CIRCLE('',#127426,0.208574704164); +#127426 = AXIS2_PLACEMENT_2D('',#127427,#127428); +#127427 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#127428 = DIRECTION('',(0.E+000,1.)); +#127429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125038 = ORIENTED_EDGE('',*,*,#125039,.F.); -#125039 = EDGE_CURVE('',#125040,#125017,#125042,.T.); -#125040 = VERTEX_POINT('',#125041); -#125041 = CARTESIAN_POINT('',(10.51959417205,7.85,0.E+000)); -#125042 = SURFACE_CURVE('',#125043,(#125047,#125053),.PCURVE_S1.); -#125043 = LINE('',#125044,#125045); -#125044 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#127430 = ORIENTED_EDGE('',*,*,#127431,.F.); +#127431 = EDGE_CURVE('',#127432,#127409,#127434,.T.); +#127432 = VERTEX_POINT('',#127433); +#127433 = CARTESIAN_POINT('',(10.51959417205,7.85,0.E+000)); +#127434 = SURFACE_CURVE('',#127435,(#127439,#127445),.PCURVE_S1.); +#127435 = LINE('',#127436,#127437); +#127436 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#125045 = VECTOR('',#125046,1.); -#125046 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125047 = PCURVE('',#124902,#125048); -#125048 = DEFINITIONAL_REPRESENTATION('',(#125049),#125052); -#125049 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125050,#125051), +#127437 = VECTOR('',#127438,1.); +#127438 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127439 = PCURVE('',#127294,#127440); +#127440 = DEFINITIONAL_REPRESENTATION('',(#127441),#127444); +#127441 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127442,#127443), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#125050 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#125051 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#125052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127442 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#127443 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#127444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125053 = PCURVE('',#125054,#125059); -#125054 = PLANE('',#125055); -#125055 = AXIS2_PLACEMENT_3D('',#125056,#125057,#125058); -#125056 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#127445 = PCURVE('',#127446,#127451); +#127446 = PLANE('',#127447); +#127447 = AXIS2_PLACEMENT_3D('',#127448,#127449,#127450); +#127448 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#125057 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125058 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125059 = DEFINITIONAL_REPRESENTATION('',(#125060),#125064); -#125060 = LINE('',#125061,#125062); -#125061 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#125062 = VECTOR('',#125063,1.); -#125063 = DIRECTION('',(-1.,0.E+000)); -#125064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125065 = ORIENTED_EDGE('',*,*,#125066,.T.); -#125066 = EDGE_CURVE('',#125040,#124864,#125067,.T.); -#125067 = SURFACE_CURVE('',#125068,(#125073,#125079),.PCURVE_S1.); -#125068 = CIRCLE('',#125069,0.208574704164); -#125069 = AXIS2_PLACEMENT_3D('',#125070,#125071,#125072); -#125070 = CARTESIAN_POINT('',(10.728168876214,7.85,2.640924866458E-017) - ); -#125071 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125072 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125073 = PCURVE('',#124902,#125074); -#125074 = DEFINITIONAL_REPRESENTATION('',(#125075),#125078); -#125075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125076,#125077), +#127449 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127450 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127451 = DEFINITIONAL_REPRESENTATION('',(#127452),#127456); +#127452 = LINE('',#127453,#127454); +#127453 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#127454 = VECTOR('',#127455,1.); +#127455 = DIRECTION('',(-1.,0.E+000)); +#127456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127457 = ORIENTED_EDGE('',*,*,#127458,.T.); +#127458 = EDGE_CURVE('',#127432,#127256,#127459,.T.); +#127459 = SURFACE_CURVE('',#127460,(#127465,#127471),.PCURVE_S1.); +#127460 = CIRCLE('',#127461,0.208574704164); +#127461 = AXIS2_PLACEMENT_3D('',#127462,#127463,#127464); +#127462 = CARTESIAN_POINT('',(10.728168876214,7.85,2.640924866458E-017) + ); +#127463 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127464 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#127465 = PCURVE('',#127294,#127466); +#127466 = DEFINITIONAL_REPRESENTATION('',(#127467),#127470); +#127467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127468,#127469), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#125076 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#125077 = CARTESIAN_POINT('',(4.772630242227,-7.85)); -#125078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127468 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#127469 = CARTESIAN_POINT('',(4.772630242227,-7.85)); +#127470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125079 = PCURVE('',#93652,#125080); -#125080 = DEFINITIONAL_REPRESENTATION('',(#125081),#125089); -#125081 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125082,#125083,#125084, - #125085,#125086,#125087,#125088),.UNSPECIFIED.,.T.,.F.) +#127471 = PCURVE('',#96044,#127472); +#127472 = DEFINITIONAL_REPRESENTATION('',(#127473),#127481); +#127473 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127474,#127475,#127476, + #127477,#127478,#127479,#127480),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#125082 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#125083 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#125084 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#125085 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#125086 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#125087 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#125088 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#125089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125090 = ORIENTED_EDGE('',*,*,#124886,.F.); -#125091 = ADVANCED_FACE('',(#125092),#125054,.T.); -#125092 = FACE_BOUND('',#125093,.T.); -#125093 = EDGE_LOOP('',(#125094,#125123,#125144,#125145)); -#125094 = ORIENTED_EDGE('',*,*,#125095,.T.); -#125095 = EDGE_CURVE('',#125096,#125098,#125100,.T.); -#125096 = VERTEX_POINT('',#125097); -#125097 = CARTESIAN_POINT('',(10.51959417205,7.85,0.530776333563)); -#125098 = VERTEX_POINT('',#125099); -#125099 = CARTESIAN_POINT('',(10.51959417205,7.65,0.530776333563)); -#125100 = SURFACE_CURVE('',#125101,(#125105,#125112),.PCURVE_S1.); -#125101 = LINE('',#125102,#125103); -#125102 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#127474 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#127475 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#127476 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#127477 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#127478 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#127479 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#127480 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#127481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127482 = ORIENTED_EDGE('',*,*,#127278,.F.); +#127483 = ADVANCED_FACE('',(#127484),#127446,.T.); +#127484 = FACE_BOUND('',#127485,.T.); +#127485 = EDGE_LOOP('',(#127486,#127515,#127536,#127537)); +#127486 = ORIENTED_EDGE('',*,*,#127487,.T.); +#127487 = EDGE_CURVE('',#127488,#127490,#127492,.T.); +#127488 = VERTEX_POINT('',#127489); +#127489 = CARTESIAN_POINT('',(10.51959417205,7.85,0.530776333563)); +#127490 = VERTEX_POINT('',#127491); +#127491 = CARTESIAN_POINT('',(10.51959417205,7.65,0.530776333563)); +#127492 = SURFACE_CURVE('',#127493,(#127497,#127504),.PCURVE_S1.); +#127493 = LINE('',#127494,#127495); +#127494 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#125103 = VECTOR('',#125104,1.); -#125104 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125105 = PCURVE('',#125054,#125106); -#125106 = DEFINITIONAL_REPRESENTATION('',(#125107),#125111); -#125107 = LINE('',#125108,#125109); -#125108 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125109 = VECTOR('',#125110,1.); -#125110 = DIRECTION('',(-1.,0.E+000)); -#125111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125112 = PCURVE('',#125113,#125118); -#125113 = CYLINDRICAL_SURFACE('',#125114,0.2192697516); -#125114 = AXIS2_PLACEMENT_3D('',#125115,#125116,#125117); -#125115 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#127495 = VECTOR('',#127496,1.); +#127496 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127497 = PCURVE('',#127446,#127498); +#127498 = DEFINITIONAL_REPRESENTATION('',(#127499),#127503); +#127499 = LINE('',#127500,#127501); +#127500 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127501 = VECTOR('',#127502,1.); +#127502 = DIRECTION('',(-1.,0.E+000)); +#127503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127504 = PCURVE('',#127505,#127510); +#127505 = CYLINDRICAL_SURFACE('',#127506,0.2192697516); +#127506 = AXIS2_PLACEMENT_3D('',#127507,#127508,#127509); +#127507 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#125116 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125117 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125118 = DEFINITIONAL_REPRESENTATION('',(#125119),#125122); -#125119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125120,#125121), +#127508 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127509 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127510 = DEFINITIONAL_REPRESENTATION('',(#127511),#127514); +#127511 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127512,#127513), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#125120 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#125121 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#125122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125123 = ORIENTED_EDGE('',*,*,#125124,.T.); -#125124 = EDGE_CURVE('',#125098,#125017,#125125,.T.); -#125125 = SURFACE_CURVE('',#125126,(#125130,#125137),.PCURVE_S1.); -#125126 = LINE('',#125127,#125128); -#125127 = CARTESIAN_POINT('',(10.51959417205,7.65,0.530776333563)); -#125128 = VECTOR('',#125129,1.); -#125129 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125130 = PCURVE('',#125054,#125131); -#125131 = DEFINITIONAL_REPRESENTATION('',(#125132),#125136); -#125132 = LINE('',#125133,#125134); -#125133 = CARTESIAN_POINT('',(7.65,0.E+000)); -#125134 = VECTOR('',#125135,1.); -#125135 = DIRECTION('',(0.E+000,-1.)); -#125136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125137 = PCURVE('',#93708,#125138); -#125138 = DEFINITIONAL_REPRESENTATION('',(#125139),#125143); -#125139 = LINE('',#125140,#125141); -#125140 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#125141 = VECTOR('',#125142,1.); -#125142 = DIRECTION('',(1.,0.E+000)); -#125143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125144 = ORIENTED_EDGE('',*,*,#125039,.F.); -#125145 = ORIENTED_EDGE('',*,*,#125146,.F.); -#125146 = EDGE_CURVE('',#125096,#125040,#125147,.T.); -#125147 = SURFACE_CURVE('',#125148,(#125152,#125159),.PCURVE_S1.); -#125148 = LINE('',#125149,#125150); -#125149 = CARTESIAN_POINT('',(10.51959417205,7.85,0.530776333563)); -#125150 = VECTOR('',#125151,1.); -#125151 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125152 = PCURVE('',#125054,#125153); -#125153 = DEFINITIONAL_REPRESENTATION('',(#125154),#125158); -#125154 = LINE('',#125155,#125156); -#125155 = CARTESIAN_POINT('',(7.85,0.E+000)); -#125156 = VECTOR('',#125157,1.); -#125157 = DIRECTION('',(0.E+000,-1.)); -#125158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125159 = PCURVE('',#93652,#125160); -#125160 = DEFINITIONAL_REPRESENTATION('',(#125161),#125165); -#125161 = LINE('',#125162,#125163); -#125162 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#125163 = VECTOR('',#125164,1.); -#125164 = DIRECTION('',(-1.,0.E+000)); -#125165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125166 = ADVANCED_FACE('',(#125167),#125001,.T.); -#125167 = FACE_BOUND('',#125168,.T.); -#125168 = EDGE_LOOP('',(#125169,#125198,#125219,#125220)); -#125169 = ORIENTED_EDGE('',*,*,#125170,.T.); -#125170 = EDGE_CURVE('',#125171,#125173,#125175,.T.); -#125171 = VERTEX_POINT('',#125172); -#125172 = CARTESIAN_POINT('',(10.419594812019,7.65,0.530776333563)); -#125173 = VERTEX_POINT('',#125174); -#125174 = CARTESIAN_POINT('',(10.419594812019,7.85,0.530776333563)); -#125175 = SURFACE_CURVE('',#125176,(#125180,#125187),.PCURVE_S1.); -#125176 = LINE('',#125177,#125178); -#125177 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, - 0.530776333563)); -#125178 = VECTOR('',#125179,1.); -#125179 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125180 = PCURVE('',#125001,#125181); -#125181 = DEFINITIONAL_REPRESENTATION('',(#125182),#125186); -#125182 = LINE('',#125183,#125184); -#125183 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125184 = VECTOR('',#125185,1.); -#125185 = DIRECTION('',(-1.,0.E+000)); -#125186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127512 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#127513 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#127514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127515 = ORIENTED_EDGE('',*,*,#127516,.T.); +#127516 = EDGE_CURVE('',#127490,#127409,#127517,.T.); +#127517 = SURFACE_CURVE('',#127518,(#127522,#127529),.PCURVE_S1.); +#127518 = LINE('',#127519,#127520); +#127519 = CARTESIAN_POINT('',(10.51959417205,7.65,0.530776333563)); +#127520 = VECTOR('',#127521,1.); +#127521 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#127522 = PCURVE('',#127446,#127523); +#127523 = DEFINITIONAL_REPRESENTATION('',(#127524),#127528); +#127524 = LINE('',#127525,#127526); +#127525 = CARTESIAN_POINT('',(7.65,0.E+000)); +#127526 = VECTOR('',#127527,1.); +#127527 = DIRECTION('',(0.E+000,-1.)); +#127528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127529 = PCURVE('',#96100,#127530); +#127530 = DEFINITIONAL_REPRESENTATION('',(#127531),#127535); +#127531 = LINE('',#127532,#127533); +#127532 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#127533 = VECTOR('',#127534,1.); +#127534 = DIRECTION('',(1.,0.E+000)); +#127535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127536 = ORIENTED_EDGE('',*,*,#127431,.F.); +#127537 = ORIENTED_EDGE('',*,*,#127538,.F.); +#127538 = EDGE_CURVE('',#127488,#127432,#127539,.T.); +#127539 = SURFACE_CURVE('',#127540,(#127544,#127551),.PCURVE_S1.); +#127540 = LINE('',#127541,#127542); +#127541 = CARTESIAN_POINT('',(10.51959417205,7.85,0.530776333563)); +#127542 = VECTOR('',#127543,1.); +#127543 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#127544 = PCURVE('',#127446,#127545); +#127545 = DEFINITIONAL_REPRESENTATION('',(#127546),#127550); +#127546 = LINE('',#127547,#127548); +#127547 = CARTESIAN_POINT('',(7.85,0.E+000)); +#127548 = VECTOR('',#127549,1.); +#127549 = DIRECTION('',(0.E+000,-1.)); +#127550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127551 = PCURVE('',#96044,#127552); +#127552 = DEFINITIONAL_REPRESENTATION('',(#127553),#127557); +#127553 = LINE('',#127554,#127555); +#127554 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#127555 = VECTOR('',#127556,1.); +#127556 = DIRECTION('',(-1.,0.E+000)); +#127557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125187 = PCURVE('',#125188,#125193); -#125188 = CYLINDRICAL_SURFACE('',#125189,0.119270391569); -#125189 = AXIS2_PLACEMENT_3D('',#125190,#125191,#125192); -#125190 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#127558 = ADVANCED_FACE('',(#127559),#127393,.T.); +#127559 = FACE_BOUND('',#127560,.T.); +#127560 = EDGE_LOOP('',(#127561,#127590,#127611,#127612)); +#127561 = ORIENTED_EDGE('',*,*,#127562,.T.); +#127562 = EDGE_CURVE('',#127563,#127565,#127567,.T.); +#127563 = VERTEX_POINT('',#127564); +#127564 = CARTESIAN_POINT('',(10.419594812019,7.65,0.530776333563)); +#127565 = VERTEX_POINT('',#127566); +#127566 = CARTESIAN_POINT('',(10.419594812019,7.85,0.530776333563)); +#127567 = SURFACE_CURVE('',#127568,(#127572,#127579),.PCURVE_S1.); +#127568 = LINE('',#127569,#127570); +#127569 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, + 0.530776333563)); +#127570 = VECTOR('',#127571,1.); +#127571 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127572 = PCURVE('',#127393,#127573); +#127573 = DEFINITIONAL_REPRESENTATION('',(#127574),#127578); +#127574 = LINE('',#127575,#127576); +#127575 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127576 = VECTOR('',#127577,1.); +#127577 = DIRECTION('',(-1.,0.E+000)); +#127578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127579 = PCURVE('',#127580,#127585); +#127580 = CYLINDRICAL_SURFACE('',#127581,0.119270391569); +#127581 = AXIS2_PLACEMENT_3D('',#127582,#127583,#127584); +#127582 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#125191 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125192 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125193 = DEFINITIONAL_REPRESENTATION('',(#125194),#125197); -#125194 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125195,#125196), +#127583 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127584 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127585 = DEFINITIONAL_REPRESENTATION('',(#127586),#127589); +#127586 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127587,#127588), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#125195 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#125196 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#125197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125198 = ORIENTED_EDGE('',*,*,#125199,.T.); -#125199 = EDGE_CURVE('',#125173,#124938,#125200,.T.); -#125200 = SURFACE_CURVE('',#125201,(#125205,#125212),.PCURVE_S1.); -#125201 = LINE('',#125202,#125203); -#125202 = CARTESIAN_POINT('',(10.419594812019,7.85,0.530776333563)); -#125203 = VECTOR('',#125204,1.); -#125204 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125205 = PCURVE('',#125001,#125206); -#125206 = DEFINITIONAL_REPRESENTATION('',(#125207),#125211); -#125207 = LINE('',#125208,#125209); -#125208 = CARTESIAN_POINT('',(-7.85,0.E+000)); -#125209 = VECTOR('',#125210,1.); -#125210 = DIRECTION('',(0.E+000,-1.)); -#125211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125212 = PCURVE('',#93652,#125213); -#125213 = DEFINITIONAL_REPRESENTATION('',(#125214),#125218); -#125214 = LINE('',#125215,#125216); -#125215 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#125216 = VECTOR('',#125217,1.); -#125217 = DIRECTION('',(-1.,0.E+000)); -#125218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125219 = ORIENTED_EDGE('',*,*,#124988,.F.); -#125220 = ORIENTED_EDGE('',*,*,#125221,.F.); -#125221 = EDGE_CURVE('',#125171,#124966,#125222,.T.); -#125222 = SURFACE_CURVE('',#125223,(#125227,#125234),.PCURVE_S1.); -#125223 = LINE('',#125224,#125225); -#125224 = CARTESIAN_POINT('',(10.419594812019,7.65,0.530776333563)); -#125225 = VECTOR('',#125226,1.); -#125226 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125227 = PCURVE('',#125001,#125228); -#125228 = DEFINITIONAL_REPRESENTATION('',(#125229),#125233); -#125229 = LINE('',#125230,#125231); -#125230 = CARTESIAN_POINT('',(-7.65,0.E+000)); -#125231 = VECTOR('',#125232,1.); -#125232 = DIRECTION('',(0.E+000,-1.)); -#125233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125234 = PCURVE('',#93708,#125235); -#125235 = DEFINITIONAL_REPRESENTATION('',(#125236),#125240); -#125236 = LINE('',#125237,#125238); -#125237 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#125238 = VECTOR('',#125239,1.); -#125239 = DIRECTION('',(1.,0.E+000)); -#125240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125241 = ADVANCED_FACE('',(#125242),#125188,.F.); -#125242 = FACE_BOUND('',#125243,.F.); -#125243 = EDGE_LOOP('',(#125244,#125245,#125268,#125290)); -#125244 = ORIENTED_EDGE('',*,*,#125170,.T.); -#125245 = ORIENTED_EDGE('',*,*,#125246,.F.); -#125246 = EDGE_CURVE('',#125247,#125173,#125249,.T.); -#125247 = VERTEX_POINT('',#125248); -#125248 = CARTESIAN_POINT('',(10.303662633502,7.85,0.65)); -#125249 = SURFACE_CURVE('',#125250,(#125255,#125261),.PCURVE_S1.); -#125250 = CIRCLE('',#125251,0.119270391569); -#125251 = AXIS2_PLACEMENT_3D('',#125252,#125253,#125254); -#125252 = CARTESIAN_POINT('',(10.30032442045,7.85,0.530776333563)); -#125253 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125254 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125255 = PCURVE('',#125188,#125256); -#125256 = DEFINITIONAL_REPRESENTATION('',(#125257),#125260); -#125257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125258,#125259), +#127587 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#127588 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#127589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127590 = ORIENTED_EDGE('',*,*,#127591,.T.); +#127591 = EDGE_CURVE('',#127565,#127330,#127592,.T.); +#127592 = SURFACE_CURVE('',#127593,(#127597,#127604),.PCURVE_S1.); +#127593 = LINE('',#127594,#127595); +#127594 = CARTESIAN_POINT('',(10.419594812019,7.85,0.530776333563)); +#127595 = VECTOR('',#127596,1.); +#127596 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#127597 = PCURVE('',#127393,#127598); +#127598 = DEFINITIONAL_REPRESENTATION('',(#127599),#127603); +#127599 = LINE('',#127600,#127601); +#127600 = CARTESIAN_POINT('',(-7.85,0.E+000)); +#127601 = VECTOR('',#127602,1.); +#127602 = DIRECTION('',(0.E+000,-1.)); +#127603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127604 = PCURVE('',#96044,#127605); +#127605 = DEFINITIONAL_REPRESENTATION('',(#127606),#127610); +#127606 = LINE('',#127607,#127608); +#127607 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#127608 = VECTOR('',#127609,1.); +#127609 = DIRECTION('',(-1.,0.E+000)); +#127610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127611 = ORIENTED_EDGE('',*,*,#127380,.F.); +#127612 = ORIENTED_EDGE('',*,*,#127613,.F.); +#127613 = EDGE_CURVE('',#127563,#127358,#127614,.T.); +#127614 = SURFACE_CURVE('',#127615,(#127619,#127626),.PCURVE_S1.); +#127615 = LINE('',#127616,#127617); +#127616 = CARTESIAN_POINT('',(10.419594812019,7.65,0.530776333563)); +#127617 = VECTOR('',#127618,1.); +#127618 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#127619 = PCURVE('',#127393,#127620); +#127620 = DEFINITIONAL_REPRESENTATION('',(#127621),#127625); +#127621 = LINE('',#127622,#127623); +#127622 = CARTESIAN_POINT('',(-7.65,0.E+000)); +#127623 = VECTOR('',#127624,1.); +#127624 = DIRECTION('',(0.E+000,-1.)); +#127625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127626 = PCURVE('',#96100,#127627); +#127627 = DEFINITIONAL_REPRESENTATION('',(#127628),#127632); +#127628 = LINE('',#127629,#127630); +#127629 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#127630 = VECTOR('',#127631,1.); +#127631 = DIRECTION('',(1.,0.E+000)); +#127632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127633 = ADVANCED_FACE('',(#127634),#127580,.F.); +#127634 = FACE_BOUND('',#127635,.F.); +#127635 = EDGE_LOOP('',(#127636,#127637,#127660,#127682)); +#127636 = ORIENTED_EDGE('',*,*,#127562,.T.); +#127637 = ORIENTED_EDGE('',*,*,#127638,.F.); +#127638 = EDGE_CURVE('',#127639,#127565,#127641,.T.); +#127639 = VERTEX_POINT('',#127640); +#127640 = CARTESIAN_POINT('',(10.303662633502,7.85,0.65)); +#127641 = SURFACE_CURVE('',#127642,(#127647,#127653),.PCURVE_S1.); +#127642 = CIRCLE('',#127643,0.119270391569); +#127643 = AXIS2_PLACEMENT_3D('',#127644,#127645,#127646); +#127644 = CARTESIAN_POINT('',(10.30032442045,7.85,0.530776333563)); +#127645 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127646 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127647 = PCURVE('',#127580,#127648); +#127648 = DEFINITIONAL_REPRESENTATION('',(#127649),#127652); +#127649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127650,#127651), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#125258 = CARTESIAN_POINT('',(1.598788597134,7.85)); -#125259 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#125260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125261 = PCURVE('',#93652,#125262); -#125262 = DEFINITIONAL_REPRESENTATION('',(#125263),#125267); -#125263 = CIRCLE('',#125264,0.119270391569); -#125264 = AXIS2_PLACEMENT_2D('',#125265,#125266); -#125265 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#125266 = DIRECTION('',(0.E+000,-1.)); -#125267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125268 = ORIENTED_EDGE('',*,*,#125269,.T.); -#125269 = EDGE_CURVE('',#125247,#125270,#125272,.T.); -#125270 = VERTEX_POINT('',#125271); -#125271 = CARTESIAN_POINT('',(10.303662633502,7.65,0.65)); -#125272 = SURFACE_CURVE('',#125273,(#125277,#125283),.PCURVE_S1.); -#125273 = LINE('',#125274,#125275); -#125274 = CARTESIAN_POINT('',(10.303662633502,7.65,0.65)); -#125275 = VECTOR('',#125276,1.); -#125276 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125277 = PCURVE('',#125188,#125278); -#125278 = DEFINITIONAL_REPRESENTATION('',(#125279),#125282); -#125279 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125280,#125281), +#127650 = CARTESIAN_POINT('',(1.598788597134,7.85)); +#127651 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#127652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127653 = PCURVE('',#96044,#127654); +#127654 = DEFINITIONAL_REPRESENTATION('',(#127655),#127659); +#127655 = CIRCLE('',#127656,0.119270391569); +#127656 = AXIS2_PLACEMENT_2D('',#127657,#127658); +#127657 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#127658 = DIRECTION('',(0.E+000,-1.)); +#127659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127660 = ORIENTED_EDGE('',*,*,#127661,.T.); +#127661 = EDGE_CURVE('',#127639,#127662,#127664,.T.); +#127662 = VERTEX_POINT('',#127663); +#127663 = CARTESIAN_POINT('',(10.303662633502,7.65,0.65)); +#127664 = SURFACE_CURVE('',#127665,(#127669,#127675),.PCURVE_S1.); +#127665 = LINE('',#127666,#127667); +#127666 = CARTESIAN_POINT('',(10.303662633502,7.65,0.65)); +#127667 = VECTOR('',#127668,1.); +#127668 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#127669 = PCURVE('',#127580,#127670); +#127670 = DEFINITIONAL_REPRESENTATION('',(#127671),#127674); +#127671 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127672,#127673), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#125280 = CARTESIAN_POINT('',(1.598788597134,7.85)); -#125281 = CARTESIAN_POINT('',(1.598788597134,7.65)); -#125282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125283 = PCURVE('',#93680,#125284); -#125284 = DEFINITIONAL_REPRESENTATION('',(#125285),#125289); -#125285 = LINE('',#125286,#125287); -#125286 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#125287 = VECTOR('',#125288,1.); -#125288 = DIRECTION('',(4.440892098501E-016,-1.)); -#125289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125290 = ORIENTED_EDGE('',*,*,#125291,.T.); -#125291 = EDGE_CURVE('',#125270,#125171,#125292,.T.); -#125292 = SURFACE_CURVE('',#125293,(#125298,#125304),.PCURVE_S1.); -#125293 = CIRCLE('',#125294,0.119270391569); -#125294 = AXIS2_PLACEMENT_3D('',#125295,#125296,#125297); -#125295 = CARTESIAN_POINT('',(10.30032442045,7.65,0.530776333563)); -#125296 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125297 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125298 = PCURVE('',#125188,#125299); -#125299 = DEFINITIONAL_REPRESENTATION('',(#125300),#125303); -#125300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125301,#125302), +#127672 = CARTESIAN_POINT('',(1.598788597134,7.85)); +#127673 = CARTESIAN_POINT('',(1.598788597134,7.65)); +#127674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127675 = PCURVE('',#96072,#127676); +#127676 = DEFINITIONAL_REPRESENTATION('',(#127677),#127681); +#127677 = LINE('',#127678,#127679); +#127678 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#127679 = VECTOR('',#127680,1.); +#127680 = DIRECTION('',(4.440892098501E-016,-1.)); +#127681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127682 = ORIENTED_EDGE('',*,*,#127683,.T.); +#127683 = EDGE_CURVE('',#127662,#127563,#127684,.T.); +#127684 = SURFACE_CURVE('',#127685,(#127690,#127696),.PCURVE_S1.); +#127685 = CIRCLE('',#127686,0.119270391569); +#127686 = AXIS2_PLACEMENT_3D('',#127687,#127688,#127689); +#127687 = CARTESIAN_POINT('',(10.30032442045,7.65,0.530776333563)); +#127688 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127689 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127690 = PCURVE('',#127580,#127691); +#127691 = DEFINITIONAL_REPRESENTATION('',(#127692),#127695); +#127692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127693,#127694), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#125301 = CARTESIAN_POINT('',(1.598788597134,7.65)); -#125302 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#125303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127693 = CARTESIAN_POINT('',(1.598788597134,7.65)); +#127694 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#127695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125304 = PCURVE('',#93708,#125305); -#125305 = DEFINITIONAL_REPRESENTATION('',(#125306),#125314); -#125306 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125307,#125308,#125309, - #125310,#125311,#125312,#125313),.UNSPECIFIED.,.T.,.F.) +#127696 = PCURVE('',#96100,#127697); +#127697 = DEFINITIONAL_REPRESENTATION('',(#127698),#127706); +#127698 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127699,#127700,#127701, + #127702,#127703,#127704,#127705),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#125307 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#125308 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#125309 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#125310 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#125311 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#125312 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#125313 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#125314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125315 = ADVANCED_FACE('',(#125316),#125113,.T.); -#125316 = FACE_BOUND('',#125317,.T.); -#125317 = EDGE_LOOP('',(#125318,#125319,#125342,#125364)); -#125318 = ORIENTED_EDGE('',*,*,#125095,.F.); -#125319 = ORIENTED_EDGE('',*,*,#125320,.F.); -#125320 = EDGE_CURVE('',#125321,#125096,#125323,.T.); -#125321 = VERTEX_POINT('',#125322); -#125322 = CARTESIAN_POINT('',(10.304819755875,7.85,0.75)); -#125323 = SURFACE_CURVE('',#125324,(#125329,#125335),.PCURVE_S1.); -#125324 = CIRCLE('',#125325,0.2192697516); -#125325 = AXIS2_PLACEMENT_3D('',#125326,#125327,#125328); -#125326 = CARTESIAN_POINT('',(10.30032442045,7.85,0.530776333563)); -#125327 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125328 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125329 = PCURVE('',#125113,#125330); -#125330 = DEFINITIONAL_REPRESENTATION('',(#125331),#125334); -#125331 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125332,#125333), +#127699 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#127700 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#127701 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#127702 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#127703 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#127704 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#127705 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#127706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127707 = ADVANCED_FACE('',(#127708),#127505,.T.); +#127708 = FACE_BOUND('',#127709,.T.); +#127709 = EDGE_LOOP('',(#127710,#127711,#127734,#127756)); +#127710 = ORIENTED_EDGE('',*,*,#127487,.F.); +#127711 = ORIENTED_EDGE('',*,*,#127712,.F.); +#127712 = EDGE_CURVE('',#127713,#127488,#127715,.T.); +#127713 = VERTEX_POINT('',#127714); +#127714 = CARTESIAN_POINT('',(10.304819755875,7.85,0.75)); +#127715 = SURFACE_CURVE('',#127716,(#127721,#127727),.PCURVE_S1.); +#127716 = CIRCLE('',#127717,0.2192697516); +#127717 = AXIS2_PLACEMENT_3D('',#127718,#127719,#127720); +#127718 = CARTESIAN_POINT('',(10.30032442045,7.85,0.530776333563)); +#127719 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127720 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127721 = PCURVE('',#127505,#127722); +#127722 = DEFINITIONAL_REPRESENTATION('',(#127723),#127726); +#127723 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127724,#127725), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#125332 = CARTESIAN_POINT('',(1.591299156552,7.85)); -#125333 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#125334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125335 = PCURVE('',#93652,#125336); -#125336 = DEFINITIONAL_REPRESENTATION('',(#125337),#125341); -#125337 = CIRCLE('',#125338,0.2192697516); -#125338 = AXIS2_PLACEMENT_2D('',#125339,#125340); -#125339 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#125340 = DIRECTION('',(0.E+000,-1.)); -#125341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125342 = ORIENTED_EDGE('',*,*,#125343,.F.); -#125343 = EDGE_CURVE('',#125344,#125321,#125346,.T.); -#125344 = VERTEX_POINT('',#125345); -#125345 = CARTESIAN_POINT('',(10.304819755875,7.65,0.75)); -#125346 = SURFACE_CURVE('',#125347,(#125351,#125357),.PCURVE_S1.); -#125347 = LINE('',#125348,#125349); -#125348 = CARTESIAN_POINT('',(10.304819755875,7.65,0.75)); -#125349 = VECTOR('',#125350,1.); -#125350 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125351 = PCURVE('',#125113,#125352); -#125352 = DEFINITIONAL_REPRESENTATION('',(#125353),#125356); -#125353 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125354,#125355), +#127724 = CARTESIAN_POINT('',(1.591299156552,7.85)); +#127725 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#127726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127727 = PCURVE('',#96044,#127728); +#127728 = DEFINITIONAL_REPRESENTATION('',(#127729),#127733); +#127729 = CIRCLE('',#127730,0.2192697516); +#127730 = AXIS2_PLACEMENT_2D('',#127731,#127732); +#127731 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#127732 = DIRECTION('',(0.E+000,-1.)); +#127733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127734 = ORIENTED_EDGE('',*,*,#127735,.F.); +#127735 = EDGE_CURVE('',#127736,#127713,#127738,.T.); +#127736 = VERTEX_POINT('',#127737); +#127737 = CARTESIAN_POINT('',(10.304819755875,7.65,0.75)); +#127738 = SURFACE_CURVE('',#127739,(#127743,#127749),.PCURVE_S1.); +#127739 = LINE('',#127740,#127741); +#127740 = CARTESIAN_POINT('',(10.304819755875,7.65,0.75)); +#127741 = VECTOR('',#127742,1.); +#127742 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127743 = PCURVE('',#127505,#127744); +#127744 = DEFINITIONAL_REPRESENTATION('',(#127745),#127748); +#127745 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127746,#127747), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#125354 = CARTESIAN_POINT('',(1.591299156552,7.65)); -#125355 = CARTESIAN_POINT('',(1.591299156552,7.85)); -#125356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125357 = PCURVE('',#93734,#125358); -#125358 = DEFINITIONAL_REPRESENTATION('',(#125359),#125363); -#125359 = LINE('',#125360,#125361); -#125360 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#125361 = VECTOR('',#125362,1.); -#125362 = DIRECTION('',(4.440892098501E-016,1.)); -#125363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125364 = ORIENTED_EDGE('',*,*,#125365,.T.); -#125365 = EDGE_CURVE('',#125344,#125098,#125366,.T.); -#125366 = SURFACE_CURVE('',#125367,(#125372,#125378),.PCURVE_S1.); -#125367 = CIRCLE('',#125368,0.2192697516); -#125368 = AXIS2_PLACEMENT_3D('',#125369,#125370,#125371); -#125369 = CARTESIAN_POINT('',(10.30032442045,7.65,0.530776333563)); -#125370 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125371 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125372 = PCURVE('',#125113,#125373); -#125373 = DEFINITIONAL_REPRESENTATION('',(#125374),#125377); -#125374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125375,#125376), +#127746 = CARTESIAN_POINT('',(1.591299156552,7.65)); +#127747 = CARTESIAN_POINT('',(1.591299156552,7.85)); +#127748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127749 = PCURVE('',#96126,#127750); +#127750 = DEFINITIONAL_REPRESENTATION('',(#127751),#127755); +#127751 = LINE('',#127752,#127753); +#127752 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#127753 = VECTOR('',#127754,1.); +#127754 = DIRECTION('',(4.440892098501E-016,1.)); +#127755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127756 = ORIENTED_EDGE('',*,*,#127757,.T.); +#127757 = EDGE_CURVE('',#127736,#127490,#127758,.T.); +#127758 = SURFACE_CURVE('',#127759,(#127764,#127770),.PCURVE_S1.); +#127759 = CIRCLE('',#127760,0.2192697516); +#127760 = AXIS2_PLACEMENT_3D('',#127761,#127762,#127763); +#127761 = CARTESIAN_POINT('',(10.30032442045,7.65,0.530776333563)); +#127762 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127763 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#127764 = PCURVE('',#127505,#127765); +#127765 = DEFINITIONAL_REPRESENTATION('',(#127766),#127769); +#127766 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127767,#127768), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#125375 = CARTESIAN_POINT('',(1.591299156552,7.65)); -#125376 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#125377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#127767 = CARTESIAN_POINT('',(1.591299156552,7.65)); +#127768 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#127769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125378 = PCURVE('',#93708,#125379); -#125379 = DEFINITIONAL_REPRESENTATION('',(#125380),#125388); -#125380 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125381,#125382,#125383, - #125384,#125385,#125386,#125387),.UNSPECIFIED.,.T.,.F.) +#127770 = PCURVE('',#96100,#127771); +#127771 = DEFINITIONAL_REPRESENTATION('',(#127772),#127780); +#127772 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127773,#127774,#127775, + #127776,#127777,#127778,#127779),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#125381 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#125382 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#125383 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#125384 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#125385 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#125386 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#125387 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#125388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125389 = ADVANCED_FACE('',(#125390),#93680,.T.); -#125390 = FACE_BOUND('',#125391,.T.); -#125391 = EDGE_LOOP('',(#125392,#125413,#125414,#125435)); -#125392 = ORIENTED_EDGE('',*,*,#125393,.F.); -#125393 = EDGE_CURVE('',#125247,#93637,#125394,.T.); -#125394 = SURFACE_CURVE('',#125395,(#125399,#125406),.PCURVE_S1.); -#125395 = LINE('',#125396,#125397); -#125396 = CARTESIAN_POINT('',(10.527847992439,7.85,0.65)); -#125397 = VECTOR('',#125398,1.); -#125398 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#125399 = PCURVE('',#93680,#125400); -#125400 = DEFINITIONAL_REPRESENTATION('',(#125401),#125405); -#125401 = LINE('',#125402,#125403); -#125402 = CARTESIAN_POINT('',(0.E+000,0.2)); -#125403 = VECTOR('',#125404,1.); -#125404 = DIRECTION('',(1.,-3.00059940766E-063)); -#125405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125406 = PCURVE('',#93652,#125407); -#125407 = DEFINITIONAL_REPRESENTATION('',(#125408),#125412); -#125408 = LINE('',#125409,#125410); -#125409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125410 = VECTOR('',#125411,1.); -#125411 = DIRECTION('',(3.563627120235E-016,-1.)); -#125412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125413 = ORIENTED_EDGE('',*,*,#125269,.T.); -#125414 = ORIENTED_EDGE('',*,*,#125415,.T.); -#125415 = EDGE_CURVE('',#125270,#93665,#125416,.T.); -#125416 = SURFACE_CURVE('',#125417,(#125421,#125428),.PCURVE_S1.); -#125417 = LINE('',#125418,#125419); -#125418 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); -#125419 = VECTOR('',#125420,1.); -#125420 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#125421 = PCURVE('',#93680,#125422); -#125422 = DEFINITIONAL_REPRESENTATION('',(#125423),#125427); -#125423 = LINE('',#125424,#125425); -#125424 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125425 = VECTOR('',#125426,1.); -#125426 = DIRECTION('',(1.,-3.00059940766E-063)); -#125427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125428 = PCURVE('',#93708,#125429); -#125429 = DEFINITIONAL_REPRESENTATION('',(#125430),#125434); -#125430 = LINE('',#125431,#125432); -#125431 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125432 = VECTOR('',#125433,1.); -#125433 = DIRECTION('',(-3.563627120235E-016,-1.)); -#125434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125435 = ORIENTED_EDGE('',*,*,#93664,.F.); -#125436 = ADVANCED_FACE('',(#125437),#93652,.T.); -#125437 = FACE_BOUND('',#125438,.T.); -#125438 = EDGE_LOOP('',(#125439,#125460,#125461,#125462,#125463,#125464, - #125485,#125486,#125487,#125488,#125489,#125490)); -#125439 = ORIENTED_EDGE('',*,*,#125440,.F.); -#125440 = EDGE_CURVE('',#125321,#93635,#125441,.T.); -#125441 = SURFACE_CURVE('',#125442,(#125446,#125453),.PCURVE_S1.); -#125442 = LINE('',#125443,#125444); -#125443 = CARTESIAN_POINT('',(10.527847992439,7.85,0.75)); -#125444 = VECTOR('',#125445,1.); -#125445 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#125446 = PCURVE('',#93652,#125447); -#125447 = DEFINITIONAL_REPRESENTATION('',(#125448),#125452); -#125448 = LINE('',#125449,#125450); -#125449 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#125450 = VECTOR('',#125451,1.); -#125451 = DIRECTION('',(3.563627120235E-016,-1.)); -#125452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125453 = PCURVE('',#93734,#125454); -#125454 = DEFINITIONAL_REPRESENTATION('',(#125455),#125459); -#125455 = LINE('',#125456,#125457); -#125456 = CARTESIAN_POINT('',(0.E+000,0.2)); -#125457 = VECTOR('',#125458,1.); -#125458 = DIRECTION('',(-1.,-3.00059940766E-063)); -#125459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125460 = ORIENTED_EDGE('',*,*,#125320,.T.); -#125461 = ORIENTED_EDGE('',*,*,#125146,.T.); -#125462 = ORIENTED_EDGE('',*,*,#125066,.T.); -#125463 = ORIENTED_EDGE('',*,*,#124863,.T.); -#125464 = ORIENTED_EDGE('',*,*,#125465,.F.); -#125465 = EDGE_CURVE('',#124727,#124834,#125466,.T.); -#125466 = SURFACE_CURVE('',#125467,(#125471,#125478),.PCURVE_S1.); -#125467 = LINE('',#125468,#125469); -#125468 = CARTESIAN_POINT('',(11.,7.85,1.159810404338E-002)); -#125469 = VECTOR('',#125470,1.); -#125470 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#125471 = PCURVE('',#93652,#125472); -#125472 = DEFINITIONAL_REPRESENTATION('',(#125473),#125477); -#125473 = LINE('',#125474,#125475); -#125474 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#125475 = VECTOR('',#125476,1.); -#125476 = DIRECTION('',(1.,2.101748079665E-016)); -#125477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125478 = PCURVE('',#124747,#125479); -#125479 = DEFINITIONAL_REPRESENTATION('',(#125480),#125484); -#125480 = LINE('',#125481,#125482); -#125481 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#125482 = VECTOR('',#125483,1.); -#125483 = DIRECTION('',(1.194699204908E-017,1.)); -#125484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125485 = ORIENTED_EDGE('',*,*,#124809,.F.); -#125486 = ORIENTED_EDGE('',*,*,#124937,.F.); -#125487 = ORIENTED_EDGE('',*,*,#125199,.F.); -#125488 = ORIENTED_EDGE('',*,*,#125246,.F.); -#125489 = ORIENTED_EDGE('',*,*,#125393,.T.); -#125490 = ORIENTED_EDGE('',*,*,#93634,.F.); -#125491 = ADVANCED_FACE('',(#125492),#93734,.T.); -#125492 = FACE_BOUND('',#125493,.T.); -#125493 = EDGE_LOOP('',(#125494,#125515,#125516,#125517)); -#125494 = ORIENTED_EDGE('',*,*,#125495,.F.); -#125495 = EDGE_CURVE('',#125344,#93693,#125496,.T.); -#125496 = SURFACE_CURVE('',#125497,(#125501,#125508),.PCURVE_S1.); -#125497 = LINE('',#125498,#125499); -#125498 = CARTESIAN_POINT('',(10.527847992439,7.65,0.75)); -#125499 = VECTOR('',#125500,1.); -#125500 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#125501 = PCURVE('',#93734,#125502); -#125502 = DEFINITIONAL_REPRESENTATION('',(#125503),#125507); -#125503 = LINE('',#125504,#125505); -#125504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125505 = VECTOR('',#125506,1.); -#125506 = DIRECTION('',(-1.,-3.00059940766E-063)); -#125507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125508 = PCURVE('',#93708,#125509); -#125509 = DEFINITIONAL_REPRESENTATION('',(#125510),#125514); -#125510 = LINE('',#125511,#125512); -#125511 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#125512 = VECTOR('',#125513,1.); -#125513 = DIRECTION('',(-3.563627120235E-016,-1.)); -#125514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125515 = ORIENTED_EDGE('',*,*,#125343,.T.); -#125516 = ORIENTED_EDGE('',*,*,#125440,.T.); -#125517 = ORIENTED_EDGE('',*,*,#93720,.F.); -#125518 = ADVANCED_FACE('',(#125519),#93708,.T.); -#125519 = FACE_BOUND('',#125520,.T.); -#125520 = EDGE_LOOP('',(#125521,#125522,#125523,#125524,#125525,#125526, - #125547,#125548,#125549,#125550,#125551,#125552)); -#125521 = ORIENTED_EDGE('',*,*,#125415,.F.); -#125522 = ORIENTED_EDGE('',*,*,#125291,.T.); -#125523 = ORIENTED_EDGE('',*,*,#125221,.T.); -#125524 = ORIENTED_EDGE('',*,*,#124965,.T.); -#125525 = ORIENTED_EDGE('',*,*,#124759,.T.); -#125526 = ORIENTED_EDGE('',*,*,#125527,.F.); -#125527 = EDGE_CURVE('',#124836,#124725,#125528,.T.); -#125528 = SURFACE_CURVE('',#125529,(#125533,#125540),.PCURVE_S1.); -#125529 = LINE('',#125530,#125531); -#125530 = CARTESIAN_POINT('',(11.,7.65,1.159810404338E-002)); -#125531 = VECTOR('',#125532,1.); -#125532 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#125533 = PCURVE('',#93708,#125534); -#125534 = DEFINITIONAL_REPRESENTATION('',(#125535),#125539); -#125535 = LINE('',#125536,#125537); -#125536 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#125537 = VECTOR('',#125538,1.); -#125538 = DIRECTION('',(1.,-2.101748079665E-016)); -#125539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125540 = PCURVE('',#124747,#125541); -#125541 = DEFINITIONAL_REPRESENTATION('',(#125542),#125546); -#125542 = LINE('',#125543,#125544); -#125543 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#125544 = VECTOR('',#125545,1.); -#125545 = DIRECTION('',(-1.194699204908E-017,-1.)); -#125546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125547 = ORIENTED_EDGE('',*,*,#124913,.F.); -#125548 = ORIENTED_EDGE('',*,*,#125016,.F.); -#125549 = ORIENTED_EDGE('',*,*,#125124,.F.); -#125550 = ORIENTED_EDGE('',*,*,#125365,.F.); -#125551 = ORIENTED_EDGE('',*,*,#125495,.T.); -#125552 = ORIENTED_EDGE('',*,*,#93692,.F.); -#125553 = ADVANCED_FACE('',(#125554),#124747,.T.); -#125554 = FACE_BOUND('',#125555,.T.); -#125555 = EDGE_LOOP('',(#125556,#125557,#125558,#125559)); -#125556 = ORIENTED_EDGE('',*,*,#125465,.T.); -#125557 = ORIENTED_EDGE('',*,*,#124833,.T.); -#125558 = ORIENTED_EDGE('',*,*,#125527,.T.); -#125559 = ORIENTED_EDGE('',*,*,#124724,.T.); -#125560 = ADVANCED_FACE('',(#125561),#125575,.F.); -#125561 = FACE_BOUND('',#125562,.T.); -#125562 = EDGE_LOOP('',(#125563,#125598,#125621,#125648)); -#125563 = ORIENTED_EDGE('',*,*,#125564,.F.); -#125564 = EDGE_CURVE('',#125565,#125567,#125569,.T.); -#125565 = VERTEX_POINT('',#125566); -#125566 = CARTESIAN_POINT('',(11.,7.15,-0.308197125857)); -#125567 = VERTEX_POINT('',#125568); -#125568 = CARTESIAN_POINT('',(11.,7.35,-0.308197125857)); -#125569 = SURFACE_CURVE('',#125570,(#125574,#125586),.PCURVE_S1.); -#125570 = LINE('',#125571,#125572); -#125571 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#125572 = VECTOR('',#125573,1.); -#125573 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125574 = PCURVE('',#125575,#125580); -#125575 = PLANE('',#125576); -#125576 = AXIS2_PLACEMENT_3D('',#125577,#125578,#125579); -#125577 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#127773 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#127774 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#127775 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#127776 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#127777 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#127778 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#127779 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#127780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127781 = ADVANCED_FACE('',(#127782),#96072,.T.); +#127782 = FACE_BOUND('',#127783,.T.); +#127783 = EDGE_LOOP('',(#127784,#127805,#127806,#127827)); +#127784 = ORIENTED_EDGE('',*,*,#127785,.F.); +#127785 = EDGE_CURVE('',#127639,#96029,#127786,.T.); +#127786 = SURFACE_CURVE('',#127787,(#127791,#127798),.PCURVE_S1.); +#127787 = LINE('',#127788,#127789); +#127788 = CARTESIAN_POINT('',(10.527847992439,7.85,0.65)); +#127789 = VECTOR('',#127790,1.); +#127790 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#127791 = PCURVE('',#96072,#127792); +#127792 = DEFINITIONAL_REPRESENTATION('',(#127793),#127797); +#127793 = LINE('',#127794,#127795); +#127794 = CARTESIAN_POINT('',(0.E+000,0.2)); +#127795 = VECTOR('',#127796,1.); +#127796 = DIRECTION('',(1.,-3.00059940766E-063)); +#127797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127798 = PCURVE('',#96044,#127799); +#127799 = DEFINITIONAL_REPRESENTATION('',(#127800),#127804); +#127800 = LINE('',#127801,#127802); +#127801 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127802 = VECTOR('',#127803,1.); +#127803 = DIRECTION('',(3.563627120235E-016,-1.)); +#127804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127805 = ORIENTED_EDGE('',*,*,#127661,.T.); +#127806 = ORIENTED_EDGE('',*,*,#127807,.T.); +#127807 = EDGE_CURVE('',#127662,#96057,#127808,.T.); +#127808 = SURFACE_CURVE('',#127809,(#127813,#127820),.PCURVE_S1.); +#127809 = LINE('',#127810,#127811); +#127810 = CARTESIAN_POINT('',(10.527847992439,7.65,0.65)); +#127811 = VECTOR('',#127812,1.); +#127812 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#127813 = PCURVE('',#96072,#127814); +#127814 = DEFINITIONAL_REPRESENTATION('',(#127815),#127819); +#127815 = LINE('',#127816,#127817); +#127816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127817 = VECTOR('',#127818,1.); +#127818 = DIRECTION('',(1.,-3.00059940766E-063)); +#127819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127820 = PCURVE('',#96100,#127821); +#127821 = DEFINITIONAL_REPRESENTATION('',(#127822),#127826); +#127822 = LINE('',#127823,#127824); +#127823 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127824 = VECTOR('',#127825,1.); +#127825 = DIRECTION('',(-3.563627120235E-016,-1.)); +#127826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127827 = ORIENTED_EDGE('',*,*,#96056,.F.); +#127828 = ADVANCED_FACE('',(#127829),#96044,.T.); +#127829 = FACE_BOUND('',#127830,.T.); +#127830 = EDGE_LOOP('',(#127831,#127852,#127853,#127854,#127855,#127856, + #127877,#127878,#127879,#127880,#127881,#127882)); +#127831 = ORIENTED_EDGE('',*,*,#127832,.F.); +#127832 = EDGE_CURVE('',#127713,#96027,#127833,.T.); +#127833 = SURFACE_CURVE('',#127834,(#127838,#127845),.PCURVE_S1.); +#127834 = LINE('',#127835,#127836); +#127835 = CARTESIAN_POINT('',(10.527847992439,7.85,0.75)); +#127836 = VECTOR('',#127837,1.); +#127837 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#127838 = PCURVE('',#96044,#127839); +#127839 = DEFINITIONAL_REPRESENTATION('',(#127840),#127844); +#127840 = LINE('',#127841,#127842); +#127841 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#127842 = VECTOR('',#127843,1.); +#127843 = DIRECTION('',(3.563627120235E-016,-1.)); +#127844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127845 = PCURVE('',#96126,#127846); +#127846 = DEFINITIONAL_REPRESENTATION('',(#127847),#127851); +#127847 = LINE('',#127848,#127849); +#127848 = CARTESIAN_POINT('',(0.E+000,0.2)); +#127849 = VECTOR('',#127850,1.); +#127850 = DIRECTION('',(-1.,-3.00059940766E-063)); +#127851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127852 = ORIENTED_EDGE('',*,*,#127712,.T.); +#127853 = ORIENTED_EDGE('',*,*,#127538,.T.); +#127854 = ORIENTED_EDGE('',*,*,#127458,.T.); +#127855 = ORIENTED_EDGE('',*,*,#127255,.T.); +#127856 = ORIENTED_EDGE('',*,*,#127857,.F.); +#127857 = EDGE_CURVE('',#127119,#127226,#127858,.T.); +#127858 = SURFACE_CURVE('',#127859,(#127863,#127870),.PCURVE_S1.); +#127859 = LINE('',#127860,#127861); +#127860 = CARTESIAN_POINT('',(11.,7.85,1.159810404338E-002)); +#127861 = VECTOR('',#127862,1.); +#127862 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#127863 = PCURVE('',#96044,#127864); +#127864 = DEFINITIONAL_REPRESENTATION('',(#127865),#127869); +#127865 = LINE('',#127866,#127867); +#127866 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#127867 = VECTOR('',#127868,1.); +#127868 = DIRECTION('',(1.,2.101748079665E-016)); +#127869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127870 = PCURVE('',#127139,#127871); +#127871 = DEFINITIONAL_REPRESENTATION('',(#127872),#127876); +#127872 = LINE('',#127873,#127874); +#127873 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#127874 = VECTOR('',#127875,1.); +#127875 = DIRECTION('',(1.194699204908E-017,1.)); +#127876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127877 = ORIENTED_EDGE('',*,*,#127201,.F.); +#127878 = ORIENTED_EDGE('',*,*,#127329,.F.); +#127879 = ORIENTED_EDGE('',*,*,#127591,.F.); +#127880 = ORIENTED_EDGE('',*,*,#127638,.F.); +#127881 = ORIENTED_EDGE('',*,*,#127785,.T.); +#127882 = ORIENTED_EDGE('',*,*,#96026,.F.); +#127883 = ADVANCED_FACE('',(#127884),#96126,.T.); +#127884 = FACE_BOUND('',#127885,.T.); +#127885 = EDGE_LOOP('',(#127886,#127907,#127908,#127909)); +#127886 = ORIENTED_EDGE('',*,*,#127887,.F.); +#127887 = EDGE_CURVE('',#127736,#96085,#127888,.T.); +#127888 = SURFACE_CURVE('',#127889,(#127893,#127900),.PCURVE_S1.); +#127889 = LINE('',#127890,#127891); +#127890 = CARTESIAN_POINT('',(10.527847992439,7.65,0.75)); +#127891 = VECTOR('',#127892,1.); +#127892 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#127893 = PCURVE('',#96126,#127894); +#127894 = DEFINITIONAL_REPRESENTATION('',(#127895),#127899); +#127895 = LINE('',#127896,#127897); +#127896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#127897 = VECTOR('',#127898,1.); +#127898 = DIRECTION('',(-1.,-3.00059940766E-063)); +#127899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127900 = PCURVE('',#96100,#127901); +#127901 = DEFINITIONAL_REPRESENTATION('',(#127902),#127906); +#127902 = LINE('',#127903,#127904); +#127903 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#127904 = VECTOR('',#127905,1.); +#127905 = DIRECTION('',(-3.563627120235E-016,-1.)); +#127906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127907 = ORIENTED_EDGE('',*,*,#127735,.T.); +#127908 = ORIENTED_EDGE('',*,*,#127832,.T.); +#127909 = ORIENTED_EDGE('',*,*,#96112,.F.); +#127910 = ADVANCED_FACE('',(#127911),#96100,.T.); +#127911 = FACE_BOUND('',#127912,.T.); +#127912 = EDGE_LOOP('',(#127913,#127914,#127915,#127916,#127917,#127918, + #127939,#127940,#127941,#127942,#127943,#127944)); +#127913 = ORIENTED_EDGE('',*,*,#127807,.F.); +#127914 = ORIENTED_EDGE('',*,*,#127683,.T.); +#127915 = ORIENTED_EDGE('',*,*,#127613,.T.); +#127916 = ORIENTED_EDGE('',*,*,#127357,.T.); +#127917 = ORIENTED_EDGE('',*,*,#127151,.T.); +#127918 = ORIENTED_EDGE('',*,*,#127919,.F.); +#127919 = EDGE_CURVE('',#127228,#127117,#127920,.T.); +#127920 = SURFACE_CURVE('',#127921,(#127925,#127932),.PCURVE_S1.); +#127921 = LINE('',#127922,#127923); +#127922 = CARTESIAN_POINT('',(11.,7.65,1.159810404338E-002)); +#127923 = VECTOR('',#127924,1.); +#127924 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#127925 = PCURVE('',#96100,#127926); +#127926 = DEFINITIONAL_REPRESENTATION('',(#127927),#127931); +#127927 = LINE('',#127928,#127929); +#127928 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#127929 = VECTOR('',#127930,1.); +#127930 = DIRECTION('',(1.,-2.101748079665E-016)); +#127931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127932 = PCURVE('',#127139,#127933); +#127933 = DEFINITIONAL_REPRESENTATION('',(#127934),#127938); +#127934 = LINE('',#127935,#127936); +#127935 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#127936 = VECTOR('',#127937,1.); +#127937 = DIRECTION('',(-1.194699204908E-017,-1.)); +#127938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127939 = ORIENTED_EDGE('',*,*,#127305,.F.); +#127940 = ORIENTED_EDGE('',*,*,#127408,.F.); +#127941 = ORIENTED_EDGE('',*,*,#127516,.F.); +#127942 = ORIENTED_EDGE('',*,*,#127757,.F.); +#127943 = ORIENTED_EDGE('',*,*,#127887,.T.); +#127944 = ORIENTED_EDGE('',*,*,#96084,.F.); +#127945 = ADVANCED_FACE('',(#127946),#127139,.T.); +#127946 = FACE_BOUND('',#127947,.T.); +#127947 = EDGE_LOOP('',(#127948,#127949,#127950,#127951)); +#127948 = ORIENTED_EDGE('',*,*,#127857,.T.); +#127949 = ORIENTED_EDGE('',*,*,#127225,.T.); +#127950 = ORIENTED_EDGE('',*,*,#127919,.T.); +#127951 = ORIENTED_EDGE('',*,*,#127116,.T.); +#127952 = ADVANCED_FACE('',(#127953),#127967,.F.); +#127953 = FACE_BOUND('',#127954,.T.); +#127954 = EDGE_LOOP('',(#127955,#127990,#128013,#128040)); +#127955 = ORIENTED_EDGE('',*,*,#127956,.F.); +#127956 = EDGE_CURVE('',#127957,#127959,#127961,.T.); +#127957 = VERTEX_POINT('',#127958); +#127958 = CARTESIAN_POINT('',(11.,7.15,-0.308197125857)); +#127959 = VERTEX_POINT('',#127960); +#127960 = CARTESIAN_POINT('',(11.,7.35,-0.308197125857)); +#127961 = SURFACE_CURVE('',#127962,(#127966,#127978),.PCURVE_S1.); +#127962 = LINE('',#127963,#127964); +#127963 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#127964 = VECTOR('',#127965,1.); +#127965 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127966 = PCURVE('',#127967,#127972); +#127967 = PLANE('',#127968); +#127968 = AXIS2_PLACEMENT_3D('',#127969,#127970,#127971); +#127969 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#125578 = DIRECTION('',(0.E+000,0.E+000,1.)); -#125579 = DIRECTION('',(1.,0.E+000,0.E+000)); -#125580 = DEFINITIONAL_REPRESENTATION('',(#125581),#125585); -#125581 = LINE('',#125582,#125583); -#125582 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#125583 = VECTOR('',#125584,1.); -#125584 = DIRECTION('',(4.440892098501E-016,1.)); -#125585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125586 = PCURVE('',#125587,#125592); -#125587 = PLANE('',#125588); -#125588 = AXIS2_PLACEMENT_3D('',#125589,#125590,#125591); -#125589 = CARTESIAN_POINT('',(11.,7.25,-0.258196742327)); -#125590 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#125591 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125592 = DEFINITIONAL_REPRESENTATION('',(#125593),#125597); -#125593 = LINE('',#125594,#125595); -#125594 = CARTESIAN_POINT('',(-7.25,-5.000038352949E-002)); -#125595 = VECTOR('',#125596,1.); -#125596 = DIRECTION('',(1.,0.E+000)); -#125597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125598 = ORIENTED_EDGE('',*,*,#125599,.F.); -#125599 = EDGE_CURVE('',#125600,#125565,#125602,.T.); -#125600 = VERTEX_POINT('',#125601); -#125601 = CARTESIAN_POINT('',(10.74341632541,7.15,-0.308197125857)); -#125602 = SURFACE_CURVE('',#125603,(#125607,#125614),.PCURVE_S1.); -#125603 = LINE('',#125604,#125605); -#125604 = CARTESIAN_POINT('',(10.74341632541,7.15,-0.308197125857)); -#125605 = VECTOR('',#125606,1.); -#125606 = DIRECTION('',(1.,0.E+000,0.E+000)); -#125607 = PCURVE('',#125575,#125608); -#125608 = DEFINITIONAL_REPRESENTATION('',(#125609),#125613); -#125609 = LINE('',#125610,#125611); -#125610 = CARTESIAN_POINT('',(3.552713678801E-015,7.15)); -#125611 = VECTOR('',#125612,1.); -#125612 = DIRECTION('',(1.,0.E+000)); -#125613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125614 = PCURVE('',#93594,#125615); -#125615 = DEFINITIONAL_REPRESENTATION('',(#125616),#125620); -#125616 = LINE('',#125617,#125618); -#125617 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#125618 = VECTOR('',#125619,1.); -#125619 = DIRECTION('',(0.E+000,1.)); -#125620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125621 = ORIENTED_EDGE('',*,*,#125622,.F.); -#125622 = EDGE_CURVE('',#125623,#125600,#125625,.T.); -#125623 = VERTEX_POINT('',#125624); -#125624 = CARTESIAN_POINT('',(10.74341632541,7.35,-0.308197125857)); -#125625 = SURFACE_CURVE('',#125626,(#125630,#125637),.PCURVE_S1.); -#125626 = LINE('',#125627,#125628); -#125627 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#127970 = DIRECTION('',(0.E+000,0.E+000,1.)); +#127971 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127972 = DEFINITIONAL_REPRESENTATION('',(#127973),#127977); +#127973 = LINE('',#127974,#127975); +#127974 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#127975 = VECTOR('',#127976,1.); +#127976 = DIRECTION('',(4.440892098501E-016,1.)); +#127977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127978 = PCURVE('',#127979,#127984); +#127979 = PLANE('',#127980); +#127980 = AXIS2_PLACEMENT_3D('',#127981,#127982,#127983); +#127981 = CARTESIAN_POINT('',(11.,7.25,-0.258196742327)); +#127982 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#127983 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#127984 = DEFINITIONAL_REPRESENTATION('',(#127985),#127989); +#127985 = LINE('',#127986,#127987); +#127986 = CARTESIAN_POINT('',(-7.25,-5.000038352949E-002)); +#127987 = VECTOR('',#127988,1.); +#127988 = DIRECTION('',(1.,0.E+000)); +#127989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#127990 = ORIENTED_EDGE('',*,*,#127991,.F.); +#127991 = EDGE_CURVE('',#127992,#127957,#127994,.T.); +#127992 = VERTEX_POINT('',#127993); +#127993 = CARTESIAN_POINT('',(10.74341632541,7.15,-0.308197125857)); +#127994 = SURFACE_CURVE('',#127995,(#127999,#128006),.PCURVE_S1.); +#127995 = LINE('',#127996,#127997); +#127996 = CARTESIAN_POINT('',(10.74341632541,7.15,-0.308197125857)); +#127997 = VECTOR('',#127998,1.); +#127998 = DIRECTION('',(1.,0.E+000,0.E+000)); +#127999 = PCURVE('',#127967,#128000); +#128000 = DEFINITIONAL_REPRESENTATION('',(#128001),#128005); +#128001 = LINE('',#128002,#128003); +#128002 = CARTESIAN_POINT('',(3.552713678801E-015,7.15)); +#128003 = VECTOR('',#128004,1.); +#128004 = DIRECTION('',(1.,0.E+000)); +#128005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128006 = PCURVE('',#95986,#128007); +#128007 = DEFINITIONAL_REPRESENTATION('',(#128008),#128012); +#128008 = LINE('',#128009,#128010); +#128009 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#128010 = VECTOR('',#128011,1.); +#128011 = DIRECTION('',(0.E+000,1.)); +#128012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128013 = ORIENTED_EDGE('',*,*,#128014,.F.); +#128014 = EDGE_CURVE('',#128015,#127992,#128017,.T.); +#128015 = VERTEX_POINT('',#128016); +#128016 = CARTESIAN_POINT('',(10.74341632541,7.35,-0.308197125857)); +#128017 = SURFACE_CURVE('',#128018,(#128022,#128029),.PCURVE_S1.); +#128018 = LINE('',#128019,#128020); +#128019 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#125628 = VECTOR('',#125629,1.); -#125629 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125630 = PCURVE('',#125575,#125631); -#125631 = DEFINITIONAL_REPRESENTATION('',(#125632),#125636); -#125632 = LINE('',#125633,#125634); -#125633 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125634 = VECTOR('',#125635,1.); -#125635 = DIRECTION('',(-4.440892098501E-016,-1.)); -#125636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125637 = PCURVE('',#125638,#125643); -#125638 = CYLINDRICAL_SURFACE('',#125639,0.308574064194); -#125639 = AXIS2_PLACEMENT_3D('',#125640,#125641,#125642); -#125640 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#128020 = VECTOR('',#128021,1.); +#128021 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128022 = PCURVE('',#127967,#128023); +#128023 = DEFINITIONAL_REPRESENTATION('',(#128024),#128028); +#128024 = LINE('',#128025,#128026); +#128025 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128026 = VECTOR('',#128027,1.); +#128027 = DIRECTION('',(-4.440892098501E-016,-1.)); +#128028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128029 = PCURVE('',#128030,#128035); +#128030 = CYLINDRICAL_SURFACE('',#128031,0.308574064194); +#128031 = AXIS2_PLACEMENT_3D('',#128032,#128033,#128034); +#128032 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#125641 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125642 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125643 = DEFINITIONAL_REPRESENTATION('',(#125644),#125647); -#125644 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125645,#125646), +#128033 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128034 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128035 = DEFINITIONAL_REPRESENTATION('',(#128036),#128039); +#128036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128037,#128038), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#125645 = CARTESIAN_POINT('',(4.761821717947,-7.35)); -#125646 = CARTESIAN_POINT('',(4.761821717947,-7.15)); -#125647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125648 = ORIENTED_EDGE('',*,*,#125649,.T.); -#125649 = EDGE_CURVE('',#125623,#125567,#125650,.T.); -#125650 = SURFACE_CURVE('',#125651,(#125655,#125662),.PCURVE_S1.); -#125651 = LINE('',#125652,#125653); -#125652 = CARTESIAN_POINT('',(10.74341632541,7.35,-0.308197125857)); -#125653 = VECTOR('',#125654,1.); -#125654 = DIRECTION('',(1.,0.E+000,0.E+000)); -#125655 = PCURVE('',#125575,#125656); -#125656 = DEFINITIONAL_REPRESENTATION('',(#125657),#125661); -#125657 = LINE('',#125658,#125659); -#125658 = CARTESIAN_POINT('',(3.552713678801E-015,7.35)); -#125659 = VECTOR('',#125660,1.); -#125660 = DIRECTION('',(1.,0.E+000)); -#125661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125662 = PCURVE('',#93538,#125663); -#125663 = DEFINITIONAL_REPRESENTATION('',(#125664),#125668); -#125664 = LINE('',#125665,#125666); -#125665 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#125666 = VECTOR('',#125667,1.); -#125667 = DIRECTION('',(0.E+000,1.)); -#125668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125669 = ADVANCED_FACE('',(#125670),#125684,.F.); -#125670 = FACE_BOUND('',#125671,.T.); -#125671 = EDGE_LOOP('',(#125672,#125702,#125725,#125752)); -#125672 = ORIENTED_EDGE('',*,*,#125673,.F.); -#125673 = EDGE_CURVE('',#125674,#125676,#125678,.T.); -#125674 = VERTEX_POINT('',#125675); -#125675 = CARTESIAN_POINT('',(11.,7.35,-0.208196358798)); -#125676 = VERTEX_POINT('',#125677); -#125677 = CARTESIAN_POINT('',(11.,7.15,-0.208196358798)); -#125678 = SURFACE_CURVE('',#125679,(#125683,#125695),.PCURVE_S1.); -#125679 = LINE('',#125680,#125681); -#125680 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#125681 = VECTOR('',#125682,1.); -#125682 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125683 = PCURVE('',#125684,#125689); -#125684 = PLANE('',#125685); -#125685 = AXIS2_PLACEMENT_3D('',#125686,#125687,#125688); -#125686 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#128037 = CARTESIAN_POINT('',(4.761821717947,-7.35)); +#128038 = CARTESIAN_POINT('',(4.761821717947,-7.15)); +#128039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128040 = ORIENTED_EDGE('',*,*,#128041,.T.); +#128041 = EDGE_CURVE('',#128015,#127959,#128042,.T.); +#128042 = SURFACE_CURVE('',#128043,(#128047,#128054),.PCURVE_S1.); +#128043 = LINE('',#128044,#128045); +#128044 = CARTESIAN_POINT('',(10.74341632541,7.35,-0.308197125857)); +#128045 = VECTOR('',#128046,1.); +#128046 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128047 = PCURVE('',#127967,#128048); +#128048 = DEFINITIONAL_REPRESENTATION('',(#128049),#128053); +#128049 = LINE('',#128050,#128051); +#128050 = CARTESIAN_POINT('',(3.552713678801E-015,7.35)); +#128051 = VECTOR('',#128052,1.); +#128052 = DIRECTION('',(1.,0.E+000)); +#128053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128054 = PCURVE('',#95930,#128055); +#128055 = DEFINITIONAL_REPRESENTATION('',(#128056),#128060); +#128056 = LINE('',#128057,#128058); +#128057 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#128058 = VECTOR('',#128059,1.); +#128059 = DIRECTION('',(0.E+000,1.)); +#128060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128061 = ADVANCED_FACE('',(#128062),#128076,.F.); +#128062 = FACE_BOUND('',#128063,.T.); +#128063 = EDGE_LOOP('',(#128064,#128094,#128117,#128144)); +#128064 = ORIENTED_EDGE('',*,*,#128065,.F.); +#128065 = EDGE_CURVE('',#128066,#128068,#128070,.T.); +#128066 = VERTEX_POINT('',#128067); +#128067 = CARTESIAN_POINT('',(11.,7.35,-0.208196358798)); +#128068 = VERTEX_POINT('',#128069); +#128069 = CARTESIAN_POINT('',(11.,7.15,-0.208196358798)); +#128070 = SURFACE_CURVE('',#128071,(#128075,#128087),.PCURVE_S1.); +#128071 = LINE('',#128072,#128073); +#128072 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#128073 = VECTOR('',#128074,1.); +#128074 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128075 = PCURVE('',#128076,#128081); +#128076 = PLANE('',#128077); +#128077 = AXIS2_PLACEMENT_3D('',#128078,#128079,#128080); +#128078 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#125687 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125688 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#125689 = DEFINITIONAL_REPRESENTATION('',(#125690),#125694); -#125690 = LINE('',#125691,#125692); -#125691 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#125692 = VECTOR('',#125693,1.); -#125693 = DIRECTION('',(4.440892098501E-016,-1.)); -#125694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125695 = PCURVE('',#125587,#125696); -#125696 = DEFINITIONAL_REPRESENTATION('',(#125697),#125701); -#125697 = LINE('',#125698,#125699); -#125698 = CARTESIAN_POINT('',(-7.25,5.000038352949E-002)); -#125699 = VECTOR('',#125700,1.); -#125700 = DIRECTION('',(-1.,0.E+000)); -#125701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125702 = ORIENTED_EDGE('',*,*,#125703,.F.); -#125703 = EDGE_CURVE('',#125704,#125674,#125706,.T.); -#125704 = VERTEX_POINT('',#125705); -#125705 = CARTESIAN_POINT('',(10.740726081328,7.35,-0.208196358798)); -#125706 = SURFACE_CURVE('',#125707,(#125711,#125718),.PCURVE_S1.); -#125707 = LINE('',#125708,#125709); -#125708 = CARTESIAN_POINT('',(10.740726081328,7.35,-0.208196358798)); -#125709 = VECTOR('',#125710,1.); -#125710 = DIRECTION('',(1.,0.E+000,0.E+000)); -#125711 = PCURVE('',#125684,#125712); -#125712 = DEFINITIONAL_REPRESENTATION('',(#125713),#125717); -#125713 = LINE('',#125714,#125715); -#125714 = CARTESIAN_POINT('',(-3.552713678801E-015,7.35)); -#125715 = VECTOR('',#125716,1.); -#125716 = DIRECTION('',(-1.,0.E+000)); -#125717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125718 = PCURVE('',#93538,#125719); -#125719 = DEFINITIONAL_REPRESENTATION('',(#125720),#125724); -#125720 = LINE('',#125721,#125722); -#125721 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#125722 = VECTOR('',#125723,1.); -#125723 = DIRECTION('',(0.E+000,1.)); -#125724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125725 = ORIENTED_EDGE('',*,*,#125726,.F.); -#125726 = EDGE_CURVE('',#125727,#125704,#125729,.T.); -#125727 = VERTEX_POINT('',#125728); -#125728 = CARTESIAN_POINT('',(10.740726081328,7.15,-0.208196358798)); -#125729 = SURFACE_CURVE('',#125730,(#125734,#125741),.PCURVE_S1.); -#125730 = LINE('',#125731,#125732); -#125731 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#128079 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128080 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#128081 = DEFINITIONAL_REPRESENTATION('',(#128082),#128086); +#128082 = LINE('',#128083,#128084); +#128083 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#128084 = VECTOR('',#128085,1.); +#128085 = DIRECTION('',(4.440892098501E-016,-1.)); +#128086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128087 = PCURVE('',#127979,#128088); +#128088 = DEFINITIONAL_REPRESENTATION('',(#128089),#128093); +#128089 = LINE('',#128090,#128091); +#128090 = CARTESIAN_POINT('',(-7.25,5.000038352949E-002)); +#128091 = VECTOR('',#128092,1.); +#128092 = DIRECTION('',(-1.,0.E+000)); +#128093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128094 = ORIENTED_EDGE('',*,*,#128095,.F.); +#128095 = EDGE_CURVE('',#128096,#128066,#128098,.T.); +#128096 = VERTEX_POINT('',#128097); +#128097 = CARTESIAN_POINT('',(10.740726081328,7.35,-0.208196358798)); +#128098 = SURFACE_CURVE('',#128099,(#128103,#128110),.PCURVE_S1.); +#128099 = LINE('',#128100,#128101); +#128100 = CARTESIAN_POINT('',(10.740726081328,7.35,-0.208196358798)); +#128101 = VECTOR('',#128102,1.); +#128102 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128103 = PCURVE('',#128076,#128104); +#128104 = DEFINITIONAL_REPRESENTATION('',(#128105),#128109); +#128105 = LINE('',#128106,#128107); +#128106 = CARTESIAN_POINT('',(-3.552713678801E-015,7.35)); +#128107 = VECTOR('',#128108,1.); +#128108 = DIRECTION('',(-1.,0.E+000)); +#128109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128110 = PCURVE('',#95930,#128111); +#128111 = DEFINITIONAL_REPRESENTATION('',(#128112),#128116); +#128112 = LINE('',#128113,#128114); +#128113 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#128114 = VECTOR('',#128115,1.); +#128115 = DIRECTION('',(0.E+000,1.)); +#128116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128117 = ORIENTED_EDGE('',*,*,#128118,.F.); +#128118 = EDGE_CURVE('',#128119,#128096,#128121,.T.); +#128119 = VERTEX_POINT('',#128120); +#128120 = CARTESIAN_POINT('',(10.740726081328,7.15,-0.208196358798)); +#128121 = SURFACE_CURVE('',#128122,(#128126,#128133),.PCURVE_S1.); +#128122 = LINE('',#128123,#128124); +#128123 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#125732 = VECTOR('',#125733,1.); -#125733 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125734 = PCURVE('',#125684,#125735); -#125735 = DEFINITIONAL_REPRESENTATION('',(#125736),#125740); -#125736 = LINE('',#125737,#125738); -#125737 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125738 = VECTOR('',#125739,1.); -#125739 = DIRECTION('',(-4.440892098501E-016,1.)); -#125740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125741 = PCURVE('',#125742,#125747); -#125742 = CYLINDRICAL_SURFACE('',#125743,0.208574704164); -#125743 = AXIS2_PLACEMENT_3D('',#125744,#125745,#125746); -#125744 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#128124 = VECTOR('',#128125,1.); +#128125 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128126 = PCURVE('',#128076,#128127); +#128127 = DEFINITIONAL_REPRESENTATION('',(#128128),#128132); +#128128 = LINE('',#128129,#128130); +#128129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128130 = VECTOR('',#128131,1.); +#128131 = DIRECTION('',(-4.440892098501E-016,1.)); +#128132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128133 = PCURVE('',#128134,#128139); +#128134 = CYLINDRICAL_SURFACE('',#128135,0.208574704164); +#128135 = AXIS2_PLACEMENT_3D('',#128136,#128137,#128138); +#128136 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#125745 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125746 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125747 = DEFINITIONAL_REPRESENTATION('',(#125748),#125751); -#125748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125749,#125750), +#128137 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128138 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128139 = DEFINITIONAL_REPRESENTATION('',(#128140),#128143); +#128140 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128141,#128142), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#125749 = CARTESIAN_POINT('',(4.772630242227,-7.15)); -#125750 = CARTESIAN_POINT('',(4.772630242227,-7.35)); -#125751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125752 = ORIENTED_EDGE('',*,*,#125753,.T.); -#125753 = EDGE_CURVE('',#125727,#125676,#125754,.T.); -#125754 = SURFACE_CURVE('',#125755,(#125759,#125766),.PCURVE_S1.); -#125755 = LINE('',#125756,#125757); -#125756 = CARTESIAN_POINT('',(10.740726081328,7.15,-0.208196358798)); -#125757 = VECTOR('',#125758,1.); -#125758 = DIRECTION('',(1.,0.E+000,0.E+000)); -#125759 = PCURVE('',#125684,#125760); -#125760 = DEFINITIONAL_REPRESENTATION('',(#125761),#125765); -#125761 = LINE('',#125762,#125763); -#125762 = CARTESIAN_POINT('',(-3.552713678801E-015,7.15)); -#125763 = VECTOR('',#125764,1.); -#125764 = DIRECTION('',(-1.,0.E+000)); -#125765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125766 = PCURVE('',#93594,#125767); -#125767 = DEFINITIONAL_REPRESENTATION('',(#125768),#125772); -#125768 = LINE('',#125769,#125770); -#125769 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#125770 = VECTOR('',#125771,1.); -#125771 = DIRECTION('',(0.E+000,1.)); -#125772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125773 = ADVANCED_FACE('',(#125774),#125638,.T.); -#125774 = FACE_BOUND('',#125775,.T.); -#125775 = EDGE_LOOP('',(#125776,#125803,#125804,#125827)); -#125776 = ORIENTED_EDGE('',*,*,#125777,.T.); -#125777 = EDGE_CURVE('',#125778,#125623,#125780,.T.); -#125778 = VERTEX_POINT('',#125779); -#125779 = CARTESIAN_POINT('',(10.419594812019,7.35,0.E+000)); -#125780 = SURFACE_CURVE('',#125781,(#125786,#125792),.PCURVE_S1.); -#125781 = CIRCLE('',#125782,0.308574064194); -#125782 = AXIS2_PLACEMENT_3D('',#125783,#125784,#125785); -#125783 = CARTESIAN_POINT('',(10.728168876214,7.35,2.640924866458E-017) - ); -#125784 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125785 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125786 = PCURVE('',#125638,#125787); -#125787 = DEFINITIONAL_REPRESENTATION('',(#125788),#125791); -#125788 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125789,#125790), +#128141 = CARTESIAN_POINT('',(4.772630242227,-7.15)); +#128142 = CARTESIAN_POINT('',(4.772630242227,-7.35)); +#128143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128144 = ORIENTED_EDGE('',*,*,#128145,.T.); +#128145 = EDGE_CURVE('',#128119,#128068,#128146,.T.); +#128146 = SURFACE_CURVE('',#128147,(#128151,#128158),.PCURVE_S1.); +#128147 = LINE('',#128148,#128149); +#128148 = CARTESIAN_POINT('',(10.740726081328,7.15,-0.208196358798)); +#128149 = VECTOR('',#128150,1.); +#128150 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128151 = PCURVE('',#128076,#128152); +#128152 = DEFINITIONAL_REPRESENTATION('',(#128153),#128157); +#128153 = LINE('',#128154,#128155); +#128154 = CARTESIAN_POINT('',(-3.552713678801E-015,7.15)); +#128155 = VECTOR('',#128156,1.); +#128156 = DIRECTION('',(-1.,0.E+000)); +#128157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128158 = PCURVE('',#95986,#128159); +#128159 = DEFINITIONAL_REPRESENTATION('',(#128160),#128164); +#128160 = LINE('',#128161,#128162); +#128161 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#128162 = VECTOR('',#128163,1.); +#128163 = DIRECTION('',(0.E+000,1.)); +#128164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128165 = ADVANCED_FACE('',(#128166),#128030,.T.); +#128166 = FACE_BOUND('',#128167,.T.); +#128167 = EDGE_LOOP('',(#128168,#128195,#128196,#128219)); +#128168 = ORIENTED_EDGE('',*,*,#128169,.T.); +#128169 = EDGE_CURVE('',#128170,#128015,#128172,.T.); +#128170 = VERTEX_POINT('',#128171); +#128171 = CARTESIAN_POINT('',(10.419594812019,7.35,0.E+000)); +#128172 = SURFACE_CURVE('',#128173,(#128178,#128184),.PCURVE_S1.); +#128173 = CIRCLE('',#128174,0.308574064194); +#128174 = AXIS2_PLACEMENT_3D('',#128175,#128176,#128177); +#128175 = CARTESIAN_POINT('',(10.728168876214,7.35,2.640924866458E-017) + ); +#128176 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128177 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128178 = PCURVE('',#128030,#128179); +#128179 = DEFINITIONAL_REPRESENTATION('',(#128180),#128183); +#128180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128181,#128182), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#125789 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#125790 = CARTESIAN_POINT('',(4.761821717947,-7.35)); -#125791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128181 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#128182 = CARTESIAN_POINT('',(4.761821717947,-7.35)); +#128183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125792 = PCURVE('',#93538,#125793); -#125793 = DEFINITIONAL_REPRESENTATION('',(#125794),#125802); -#125794 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125795,#125796,#125797, - #125798,#125799,#125800,#125801),.UNSPECIFIED.,.T.,.F.) +#128184 = PCURVE('',#95930,#128185); +#128185 = DEFINITIONAL_REPRESENTATION('',(#128186),#128194); +#128186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128187,#128188,#128189, + #128190,#128191,#128192,#128193),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#125795 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#125796 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#125797 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#125798 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#125799 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#125800 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#125801 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#125802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125803 = ORIENTED_EDGE('',*,*,#125622,.T.); -#125804 = ORIENTED_EDGE('',*,*,#125805,.F.); -#125805 = EDGE_CURVE('',#125806,#125600,#125808,.T.); -#125806 = VERTEX_POINT('',#125807); -#125807 = CARTESIAN_POINT('',(10.419594812019,7.15,0.E+000)); -#125808 = SURFACE_CURVE('',#125809,(#125814,#125820),.PCURVE_S1.); -#125809 = CIRCLE('',#125810,0.308574064194); -#125810 = AXIS2_PLACEMENT_3D('',#125811,#125812,#125813); -#125811 = CARTESIAN_POINT('',(10.728168876214,7.15,2.640924866458E-017) - ); -#125812 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125813 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125814 = PCURVE('',#125638,#125815); -#125815 = DEFINITIONAL_REPRESENTATION('',(#125816),#125819); -#125816 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125817,#125818), +#128187 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#128188 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#128189 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#128190 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#128191 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#128192 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#128193 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#128194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128195 = ORIENTED_EDGE('',*,*,#128014,.T.); +#128196 = ORIENTED_EDGE('',*,*,#128197,.F.); +#128197 = EDGE_CURVE('',#128198,#127992,#128200,.T.); +#128198 = VERTEX_POINT('',#128199); +#128199 = CARTESIAN_POINT('',(10.419594812019,7.15,0.E+000)); +#128200 = SURFACE_CURVE('',#128201,(#128206,#128212),.PCURVE_S1.); +#128201 = CIRCLE('',#128202,0.308574064194); +#128202 = AXIS2_PLACEMENT_3D('',#128203,#128204,#128205); +#128203 = CARTESIAN_POINT('',(10.728168876214,7.15,2.640924866458E-017) + ); +#128204 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128205 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128206 = PCURVE('',#128030,#128207); +#128207 = DEFINITIONAL_REPRESENTATION('',(#128208),#128211); +#128208 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128209,#128210), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#125817 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#125818 = CARTESIAN_POINT('',(4.761821717947,-7.15)); -#125819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128209 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#128210 = CARTESIAN_POINT('',(4.761821717947,-7.15)); +#128211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125820 = PCURVE('',#93594,#125821); -#125821 = DEFINITIONAL_REPRESENTATION('',(#125822),#125826); -#125822 = CIRCLE('',#125823,0.308574064194); -#125823 = AXIS2_PLACEMENT_2D('',#125824,#125825); -#125824 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#125825 = DIRECTION('',(0.E+000,1.)); -#125826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128212 = PCURVE('',#95986,#128213); +#128213 = DEFINITIONAL_REPRESENTATION('',(#128214),#128218); +#128214 = CIRCLE('',#128215,0.308574064194); +#128215 = AXIS2_PLACEMENT_2D('',#128216,#128217); +#128216 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#128217 = DIRECTION('',(0.E+000,1.)); +#128218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125827 = ORIENTED_EDGE('',*,*,#125828,.T.); -#125828 = EDGE_CURVE('',#125806,#125778,#125829,.T.); -#125829 = SURFACE_CURVE('',#125830,(#125834,#125840),.PCURVE_S1.); -#125830 = LINE('',#125831,#125832); -#125831 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#128219 = ORIENTED_EDGE('',*,*,#128220,.T.); +#128220 = EDGE_CURVE('',#128198,#128170,#128221,.T.); +#128221 = SURFACE_CURVE('',#128222,(#128226,#128232),.PCURVE_S1.); +#128222 = LINE('',#128223,#128224); +#128223 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#125832 = VECTOR('',#125833,1.); -#125833 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125834 = PCURVE('',#125638,#125835); -#125835 = DEFINITIONAL_REPRESENTATION('',(#125836),#125839); -#125836 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125837,#125838), +#128224 = VECTOR('',#128225,1.); +#128225 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128226 = PCURVE('',#128030,#128227); +#128227 = DEFINITIONAL_REPRESENTATION('',(#128228),#128231); +#128228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128229,#128230), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#125837 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#125838 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#125839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128229 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#128230 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#128231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125840 = PCURVE('',#125841,#125846); -#125841 = PLANE('',#125842); -#125842 = AXIS2_PLACEMENT_3D('',#125843,#125844,#125845); -#125843 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#128232 = PCURVE('',#128233,#128238); +#128233 = PLANE('',#128234); +#128234 = AXIS2_PLACEMENT_3D('',#128235,#128236,#128237); +#128235 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#125844 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125845 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125846 = DEFINITIONAL_REPRESENTATION('',(#125847),#125851); -#125847 = LINE('',#125848,#125849); -#125848 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#125849 = VECTOR('',#125850,1.); -#125850 = DIRECTION('',(-1.,0.E+000)); -#125851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125852 = ADVANCED_FACE('',(#125853),#125742,.F.); -#125853 = FACE_BOUND('',#125854,.F.); -#125854 = EDGE_LOOP('',(#125855,#125878,#125905,#125930)); -#125855 = ORIENTED_EDGE('',*,*,#125856,.F.); -#125856 = EDGE_CURVE('',#125857,#125727,#125859,.T.); -#125857 = VERTEX_POINT('',#125858); -#125858 = CARTESIAN_POINT('',(10.51959417205,7.15,0.E+000)); -#125859 = SURFACE_CURVE('',#125860,(#125865,#125871),.PCURVE_S1.); -#125860 = CIRCLE('',#125861,0.208574704164); -#125861 = AXIS2_PLACEMENT_3D('',#125862,#125863,#125864); -#125862 = CARTESIAN_POINT('',(10.728168876214,7.15,2.640924866458E-017) - ); -#125863 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125864 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125865 = PCURVE('',#125742,#125866); -#125866 = DEFINITIONAL_REPRESENTATION('',(#125867),#125870); -#125867 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125868,#125869), +#128236 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128237 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128238 = DEFINITIONAL_REPRESENTATION('',(#128239),#128243); +#128239 = LINE('',#128240,#128241); +#128240 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#128241 = VECTOR('',#128242,1.); +#128242 = DIRECTION('',(-1.,0.E+000)); +#128243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128244 = ADVANCED_FACE('',(#128245),#128134,.F.); +#128245 = FACE_BOUND('',#128246,.F.); +#128246 = EDGE_LOOP('',(#128247,#128270,#128297,#128322)); +#128247 = ORIENTED_EDGE('',*,*,#128248,.F.); +#128248 = EDGE_CURVE('',#128249,#128119,#128251,.T.); +#128249 = VERTEX_POINT('',#128250); +#128250 = CARTESIAN_POINT('',(10.51959417205,7.15,0.E+000)); +#128251 = SURFACE_CURVE('',#128252,(#128257,#128263),.PCURVE_S1.); +#128252 = CIRCLE('',#128253,0.208574704164); +#128253 = AXIS2_PLACEMENT_3D('',#128254,#128255,#128256); +#128254 = CARTESIAN_POINT('',(10.728168876214,7.15,2.640924866458E-017) + ); +#128255 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128256 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128257 = PCURVE('',#128134,#128258); +#128258 = DEFINITIONAL_REPRESENTATION('',(#128259),#128262); +#128259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128260,#128261), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#125868 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#125869 = CARTESIAN_POINT('',(4.772630242227,-7.15)); -#125870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128260 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#128261 = CARTESIAN_POINT('',(4.772630242227,-7.15)); +#128262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125871 = PCURVE('',#93594,#125872); -#125872 = DEFINITIONAL_REPRESENTATION('',(#125873),#125877); -#125873 = CIRCLE('',#125874,0.208574704164); -#125874 = AXIS2_PLACEMENT_2D('',#125875,#125876); -#125875 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#125876 = DIRECTION('',(0.E+000,1.)); -#125877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128263 = PCURVE('',#95986,#128264); +#128264 = DEFINITIONAL_REPRESENTATION('',(#128265),#128269); +#128265 = CIRCLE('',#128266,0.208574704164); +#128266 = AXIS2_PLACEMENT_2D('',#128267,#128268); +#128267 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#128268 = DIRECTION('',(0.E+000,1.)); +#128269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125878 = ORIENTED_EDGE('',*,*,#125879,.F.); -#125879 = EDGE_CURVE('',#125880,#125857,#125882,.T.); -#125880 = VERTEX_POINT('',#125881); -#125881 = CARTESIAN_POINT('',(10.51959417205,7.35,0.E+000)); -#125882 = SURFACE_CURVE('',#125883,(#125887,#125893),.PCURVE_S1.); -#125883 = LINE('',#125884,#125885); -#125884 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#128270 = ORIENTED_EDGE('',*,*,#128271,.F.); +#128271 = EDGE_CURVE('',#128272,#128249,#128274,.T.); +#128272 = VERTEX_POINT('',#128273); +#128273 = CARTESIAN_POINT('',(10.51959417205,7.35,0.E+000)); +#128274 = SURFACE_CURVE('',#128275,(#128279,#128285),.PCURVE_S1.); +#128275 = LINE('',#128276,#128277); +#128276 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#125885 = VECTOR('',#125886,1.); -#125886 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125887 = PCURVE('',#125742,#125888); -#125888 = DEFINITIONAL_REPRESENTATION('',(#125889),#125892); -#125889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125890,#125891), +#128277 = VECTOR('',#128278,1.); +#128278 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128279 = PCURVE('',#128134,#128280); +#128280 = DEFINITIONAL_REPRESENTATION('',(#128281),#128284); +#128281 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128282,#128283), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#125890 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#125891 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#125892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128282 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#128283 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#128284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125893 = PCURVE('',#125894,#125899); -#125894 = PLANE('',#125895); -#125895 = AXIS2_PLACEMENT_3D('',#125896,#125897,#125898); -#125896 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#128285 = PCURVE('',#128286,#128291); +#128286 = PLANE('',#128287); +#128287 = AXIS2_PLACEMENT_3D('',#128288,#128289,#128290); +#128288 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#125897 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125898 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125899 = DEFINITIONAL_REPRESENTATION('',(#125900),#125904); -#125900 = LINE('',#125901,#125902); -#125901 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#125902 = VECTOR('',#125903,1.); -#125903 = DIRECTION('',(-1.,0.E+000)); -#125904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125905 = ORIENTED_EDGE('',*,*,#125906,.T.); -#125906 = EDGE_CURVE('',#125880,#125704,#125907,.T.); -#125907 = SURFACE_CURVE('',#125908,(#125913,#125919),.PCURVE_S1.); -#125908 = CIRCLE('',#125909,0.208574704164); -#125909 = AXIS2_PLACEMENT_3D('',#125910,#125911,#125912); -#125910 = CARTESIAN_POINT('',(10.728168876214,7.35,2.640924866458E-017) - ); -#125911 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125912 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#125913 = PCURVE('',#125742,#125914); -#125914 = DEFINITIONAL_REPRESENTATION('',(#125915),#125918); -#125915 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125916,#125917), +#128289 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128290 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128291 = DEFINITIONAL_REPRESENTATION('',(#128292),#128296); +#128292 = LINE('',#128293,#128294); +#128293 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#128294 = VECTOR('',#128295,1.); +#128295 = DIRECTION('',(-1.,0.E+000)); +#128296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128297 = ORIENTED_EDGE('',*,*,#128298,.T.); +#128298 = EDGE_CURVE('',#128272,#128096,#128299,.T.); +#128299 = SURFACE_CURVE('',#128300,(#128305,#128311),.PCURVE_S1.); +#128300 = CIRCLE('',#128301,0.208574704164); +#128301 = AXIS2_PLACEMENT_3D('',#128302,#128303,#128304); +#128302 = CARTESIAN_POINT('',(10.728168876214,7.35,2.640924866458E-017) + ); +#128303 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128304 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128305 = PCURVE('',#128134,#128306); +#128306 = DEFINITIONAL_REPRESENTATION('',(#128307),#128310); +#128307 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128308,#128309), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#125916 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#125917 = CARTESIAN_POINT('',(4.772630242227,-7.35)); -#125918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128308 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#128309 = CARTESIAN_POINT('',(4.772630242227,-7.35)); +#128310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#125919 = PCURVE('',#93538,#125920); -#125920 = DEFINITIONAL_REPRESENTATION('',(#125921),#125929); -#125921 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#125922,#125923,#125924, - #125925,#125926,#125927,#125928),.UNSPECIFIED.,.T.,.F.) +#128311 = PCURVE('',#95930,#128312); +#128312 = DEFINITIONAL_REPRESENTATION('',(#128313),#128321); +#128313 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128314,#128315,#128316, + #128317,#128318,#128319,#128320),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#125922 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#125923 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#125924 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#125925 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#125926 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#125927 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#125928 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#125929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125930 = ORIENTED_EDGE('',*,*,#125726,.F.); -#125931 = ADVANCED_FACE('',(#125932),#125894,.T.); -#125932 = FACE_BOUND('',#125933,.T.); -#125933 = EDGE_LOOP('',(#125934,#125963,#125984,#125985)); -#125934 = ORIENTED_EDGE('',*,*,#125935,.T.); -#125935 = EDGE_CURVE('',#125936,#125938,#125940,.T.); -#125936 = VERTEX_POINT('',#125937); -#125937 = CARTESIAN_POINT('',(10.51959417205,7.35,0.530776333563)); -#125938 = VERTEX_POINT('',#125939); -#125939 = CARTESIAN_POINT('',(10.51959417205,7.15,0.530776333563)); -#125940 = SURFACE_CURVE('',#125941,(#125945,#125952),.PCURVE_S1.); -#125941 = LINE('',#125942,#125943); -#125942 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#128314 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#128315 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#128316 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#128317 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#128318 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#128319 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#128320 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#128321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128322 = ORIENTED_EDGE('',*,*,#128118,.F.); +#128323 = ADVANCED_FACE('',(#128324),#128286,.T.); +#128324 = FACE_BOUND('',#128325,.T.); +#128325 = EDGE_LOOP('',(#128326,#128355,#128376,#128377)); +#128326 = ORIENTED_EDGE('',*,*,#128327,.T.); +#128327 = EDGE_CURVE('',#128328,#128330,#128332,.T.); +#128328 = VERTEX_POINT('',#128329); +#128329 = CARTESIAN_POINT('',(10.51959417205,7.35,0.530776333563)); +#128330 = VERTEX_POINT('',#128331); +#128331 = CARTESIAN_POINT('',(10.51959417205,7.15,0.530776333563)); +#128332 = SURFACE_CURVE('',#128333,(#128337,#128344),.PCURVE_S1.); +#128333 = LINE('',#128334,#128335); +#128334 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#125943 = VECTOR('',#125944,1.); -#125944 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#125945 = PCURVE('',#125894,#125946); -#125946 = DEFINITIONAL_REPRESENTATION('',(#125947),#125951); -#125947 = LINE('',#125948,#125949); -#125948 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#125949 = VECTOR('',#125950,1.); -#125950 = DIRECTION('',(-1.,0.E+000)); -#125951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125952 = PCURVE('',#125953,#125958); -#125953 = CYLINDRICAL_SURFACE('',#125954,0.2192697516); -#125954 = AXIS2_PLACEMENT_3D('',#125955,#125956,#125957); -#125955 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#128335 = VECTOR('',#128336,1.); +#128336 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128337 = PCURVE('',#128286,#128338); +#128338 = DEFINITIONAL_REPRESENTATION('',(#128339),#128343); +#128339 = LINE('',#128340,#128341); +#128340 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128341 = VECTOR('',#128342,1.); +#128342 = DIRECTION('',(-1.,0.E+000)); +#128343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128344 = PCURVE('',#128345,#128350); +#128345 = CYLINDRICAL_SURFACE('',#128346,0.2192697516); +#128346 = AXIS2_PLACEMENT_3D('',#128347,#128348,#128349); +#128347 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#125956 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#125957 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#125958 = DEFINITIONAL_REPRESENTATION('',(#125959),#125962); -#125959 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#125960,#125961), +#128348 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128349 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128350 = DEFINITIONAL_REPRESENTATION('',(#128351),#128354); +#128351 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128352,#128353), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#125960 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#125961 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#125962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125963 = ORIENTED_EDGE('',*,*,#125964,.T.); -#125964 = EDGE_CURVE('',#125938,#125857,#125965,.T.); -#125965 = SURFACE_CURVE('',#125966,(#125970,#125977),.PCURVE_S1.); -#125966 = LINE('',#125967,#125968); -#125967 = CARTESIAN_POINT('',(10.51959417205,7.15,0.530776333563)); -#125968 = VECTOR('',#125969,1.); -#125969 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125970 = PCURVE('',#125894,#125971); -#125971 = DEFINITIONAL_REPRESENTATION('',(#125972),#125976); -#125972 = LINE('',#125973,#125974); -#125973 = CARTESIAN_POINT('',(7.15,0.E+000)); -#125974 = VECTOR('',#125975,1.); -#125975 = DIRECTION('',(0.E+000,-1.)); -#125976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125977 = PCURVE('',#93594,#125978); -#125978 = DEFINITIONAL_REPRESENTATION('',(#125979),#125983); -#125979 = LINE('',#125980,#125981); -#125980 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#125981 = VECTOR('',#125982,1.); -#125982 = DIRECTION('',(1.,0.E+000)); -#125983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125984 = ORIENTED_EDGE('',*,*,#125879,.F.); -#125985 = ORIENTED_EDGE('',*,*,#125986,.F.); -#125986 = EDGE_CURVE('',#125936,#125880,#125987,.T.); -#125987 = SURFACE_CURVE('',#125988,(#125992,#125999),.PCURVE_S1.); -#125988 = LINE('',#125989,#125990); -#125989 = CARTESIAN_POINT('',(10.51959417205,7.35,0.530776333563)); -#125990 = VECTOR('',#125991,1.); -#125991 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#125992 = PCURVE('',#125894,#125993); -#125993 = DEFINITIONAL_REPRESENTATION('',(#125994),#125998); -#125994 = LINE('',#125995,#125996); -#125995 = CARTESIAN_POINT('',(7.35,0.E+000)); -#125996 = VECTOR('',#125997,1.); -#125997 = DIRECTION('',(0.E+000,-1.)); -#125998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#125999 = PCURVE('',#93538,#126000); -#126000 = DEFINITIONAL_REPRESENTATION('',(#126001),#126005); -#126001 = LINE('',#126002,#126003); -#126002 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#126003 = VECTOR('',#126004,1.); -#126004 = DIRECTION('',(-1.,0.E+000)); -#126005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126006 = ADVANCED_FACE('',(#126007),#125841,.T.); -#126007 = FACE_BOUND('',#126008,.T.); -#126008 = EDGE_LOOP('',(#126009,#126038,#126059,#126060)); -#126009 = ORIENTED_EDGE('',*,*,#126010,.T.); -#126010 = EDGE_CURVE('',#126011,#126013,#126015,.T.); -#126011 = VERTEX_POINT('',#126012); -#126012 = CARTESIAN_POINT('',(10.419594812019,7.15,0.530776333563)); -#126013 = VERTEX_POINT('',#126014); -#126014 = CARTESIAN_POINT('',(10.419594812019,7.35,0.530776333563)); -#126015 = SURFACE_CURVE('',#126016,(#126020,#126027),.PCURVE_S1.); -#126016 = LINE('',#126017,#126018); -#126017 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, - 0.530776333563)); -#126018 = VECTOR('',#126019,1.); -#126019 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126020 = PCURVE('',#125841,#126021); -#126021 = DEFINITIONAL_REPRESENTATION('',(#126022),#126026); -#126022 = LINE('',#126023,#126024); -#126023 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126024 = VECTOR('',#126025,1.); -#126025 = DIRECTION('',(-1.,0.E+000)); -#126026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128352 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#128353 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#128354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128355 = ORIENTED_EDGE('',*,*,#128356,.T.); +#128356 = EDGE_CURVE('',#128330,#128249,#128357,.T.); +#128357 = SURFACE_CURVE('',#128358,(#128362,#128369),.PCURVE_S1.); +#128358 = LINE('',#128359,#128360); +#128359 = CARTESIAN_POINT('',(10.51959417205,7.15,0.530776333563)); +#128360 = VECTOR('',#128361,1.); +#128361 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128362 = PCURVE('',#128286,#128363); +#128363 = DEFINITIONAL_REPRESENTATION('',(#128364),#128368); +#128364 = LINE('',#128365,#128366); +#128365 = CARTESIAN_POINT('',(7.15,0.E+000)); +#128366 = VECTOR('',#128367,1.); +#128367 = DIRECTION('',(0.E+000,-1.)); +#128368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128369 = PCURVE('',#95986,#128370); +#128370 = DEFINITIONAL_REPRESENTATION('',(#128371),#128375); +#128371 = LINE('',#128372,#128373); +#128372 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#128373 = VECTOR('',#128374,1.); +#128374 = DIRECTION('',(1.,0.E+000)); +#128375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128376 = ORIENTED_EDGE('',*,*,#128271,.F.); +#128377 = ORIENTED_EDGE('',*,*,#128378,.F.); +#128378 = EDGE_CURVE('',#128328,#128272,#128379,.T.); +#128379 = SURFACE_CURVE('',#128380,(#128384,#128391),.PCURVE_S1.); +#128380 = LINE('',#128381,#128382); +#128381 = CARTESIAN_POINT('',(10.51959417205,7.35,0.530776333563)); +#128382 = VECTOR('',#128383,1.); +#128383 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128384 = PCURVE('',#128286,#128385); +#128385 = DEFINITIONAL_REPRESENTATION('',(#128386),#128390); +#128386 = LINE('',#128387,#128388); +#128387 = CARTESIAN_POINT('',(7.35,0.E+000)); +#128388 = VECTOR('',#128389,1.); +#128389 = DIRECTION('',(0.E+000,-1.)); +#128390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128391 = PCURVE('',#95930,#128392); +#128392 = DEFINITIONAL_REPRESENTATION('',(#128393),#128397); +#128393 = LINE('',#128394,#128395); +#128394 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#128395 = VECTOR('',#128396,1.); +#128396 = DIRECTION('',(-1.,0.E+000)); +#128397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126027 = PCURVE('',#126028,#126033); -#126028 = CYLINDRICAL_SURFACE('',#126029,0.119270391569); -#126029 = AXIS2_PLACEMENT_3D('',#126030,#126031,#126032); -#126030 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#128398 = ADVANCED_FACE('',(#128399),#128233,.T.); +#128399 = FACE_BOUND('',#128400,.T.); +#128400 = EDGE_LOOP('',(#128401,#128430,#128451,#128452)); +#128401 = ORIENTED_EDGE('',*,*,#128402,.T.); +#128402 = EDGE_CURVE('',#128403,#128405,#128407,.T.); +#128403 = VERTEX_POINT('',#128404); +#128404 = CARTESIAN_POINT('',(10.419594812019,7.15,0.530776333563)); +#128405 = VERTEX_POINT('',#128406); +#128406 = CARTESIAN_POINT('',(10.419594812019,7.35,0.530776333563)); +#128407 = SURFACE_CURVE('',#128408,(#128412,#128419),.PCURVE_S1.); +#128408 = LINE('',#128409,#128410); +#128409 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#126031 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126032 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126033 = DEFINITIONAL_REPRESENTATION('',(#126034),#126037); -#126034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126035,#126036), +#128410 = VECTOR('',#128411,1.); +#128411 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128412 = PCURVE('',#128233,#128413); +#128413 = DEFINITIONAL_REPRESENTATION('',(#128414),#128418); +#128414 = LINE('',#128415,#128416); +#128415 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128416 = VECTOR('',#128417,1.); +#128417 = DIRECTION('',(-1.,0.E+000)); +#128418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128419 = PCURVE('',#128420,#128425); +#128420 = CYLINDRICAL_SURFACE('',#128421,0.119270391569); +#128421 = AXIS2_PLACEMENT_3D('',#128422,#128423,#128424); +#128422 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, + 0.530776333563)); +#128423 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128424 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128425 = DEFINITIONAL_REPRESENTATION('',(#128426),#128429); +#128426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128427,#128428), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#126035 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#126036 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#126037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126038 = ORIENTED_EDGE('',*,*,#126039,.T.); -#126039 = EDGE_CURVE('',#126013,#125778,#126040,.T.); -#126040 = SURFACE_CURVE('',#126041,(#126045,#126052),.PCURVE_S1.); -#126041 = LINE('',#126042,#126043); -#126042 = CARTESIAN_POINT('',(10.419594812019,7.35,0.530776333563)); -#126043 = VECTOR('',#126044,1.); -#126044 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126045 = PCURVE('',#125841,#126046); -#126046 = DEFINITIONAL_REPRESENTATION('',(#126047),#126051); -#126047 = LINE('',#126048,#126049); -#126048 = CARTESIAN_POINT('',(-7.35,0.E+000)); -#126049 = VECTOR('',#126050,1.); -#126050 = DIRECTION('',(0.E+000,-1.)); -#126051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126052 = PCURVE('',#93538,#126053); -#126053 = DEFINITIONAL_REPRESENTATION('',(#126054),#126058); -#126054 = LINE('',#126055,#126056); -#126055 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#126056 = VECTOR('',#126057,1.); -#126057 = DIRECTION('',(-1.,0.E+000)); -#126058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126059 = ORIENTED_EDGE('',*,*,#125828,.F.); -#126060 = ORIENTED_EDGE('',*,*,#126061,.F.); -#126061 = EDGE_CURVE('',#126011,#125806,#126062,.T.); -#126062 = SURFACE_CURVE('',#126063,(#126067,#126074),.PCURVE_S1.); -#126063 = LINE('',#126064,#126065); -#126064 = CARTESIAN_POINT('',(10.419594812019,7.15,0.530776333563)); -#126065 = VECTOR('',#126066,1.); -#126066 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126067 = PCURVE('',#125841,#126068); -#126068 = DEFINITIONAL_REPRESENTATION('',(#126069),#126073); -#126069 = LINE('',#126070,#126071); -#126070 = CARTESIAN_POINT('',(-7.15,0.E+000)); -#126071 = VECTOR('',#126072,1.); -#126072 = DIRECTION('',(0.E+000,-1.)); -#126073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126074 = PCURVE('',#93594,#126075); -#126075 = DEFINITIONAL_REPRESENTATION('',(#126076),#126080); -#126076 = LINE('',#126077,#126078); -#126077 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#126078 = VECTOR('',#126079,1.); -#126079 = DIRECTION('',(1.,0.E+000)); -#126080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126081 = ADVANCED_FACE('',(#126082),#126028,.F.); -#126082 = FACE_BOUND('',#126083,.F.); -#126083 = EDGE_LOOP('',(#126084,#126085,#126108,#126130)); -#126084 = ORIENTED_EDGE('',*,*,#126010,.T.); -#126085 = ORIENTED_EDGE('',*,*,#126086,.F.); -#126086 = EDGE_CURVE('',#126087,#126013,#126089,.T.); -#126087 = VERTEX_POINT('',#126088); -#126088 = CARTESIAN_POINT('',(10.303662633502,7.35,0.65)); -#126089 = SURFACE_CURVE('',#126090,(#126095,#126101),.PCURVE_S1.); -#126090 = CIRCLE('',#126091,0.119270391569); -#126091 = AXIS2_PLACEMENT_3D('',#126092,#126093,#126094); -#126092 = CARTESIAN_POINT('',(10.30032442045,7.35,0.530776333563)); -#126093 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126094 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126095 = PCURVE('',#126028,#126096); -#126096 = DEFINITIONAL_REPRESENTATION('',(#126097),#126100); -#126097 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126098,#126099), +#128427 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#128428 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#128429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128430 = ORIENTED_EDGE('',*,*,#128431,.T.); +#128431 = EDGE_CURVE('',#128405,#128170,#128432,.T.); +#128432 = SURFACE_CURVE('',#128433,(#128437,#128444),.PCURVE_S1.); +#128433 = LINE('',#128434,#128435); +#128434 = CARTESIAN_POINT('',(10.419594812019,7.35,0.530776333563)); +#128435 = VECTOR('',#128436,1.); +#128436 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128437 = PCURVE('',#128233,#128438); +#128438 = DEFINITIONAL_REPRESENTATION('',(#128439),#128443); +#128439 = LINE('',#128440,#128441); +#128440 = CARTESIAN_POINT('',(-7.35,0.E+000)); +#128441 = VECTOR('',#128442,1.); +#128442 = DIRECTION('',(0.E+000,-1.)); +#128443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128444 = PCURVE('',#95930,#128445); +#128445 = DEFINITIONAL_REPRESENTATION('',(#128446),#128450); +#128446 = LINE('',#128447,#128448); +#128447 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#128448 = VECTOR('',#128449,1.); +#128449 = DIRECTION('',(-1.,0.E+000)); +#128450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128451 = ORIENTED_EDGE('',*,*,#128220,.F.); +#128452 = ORIENTED_EDGE('',*,*,#128453,.F.); +#128453 = EDGE_CURVE('',#128403,#128198,#128454,.T.); +#128454 = SURFACE_CURVE('',#128455,(#128459,#128466),.PCURVE_S1.); +#128455 = LINE('',#128456,#128457); +#128456 = CARTESIAN_POINT('',(10.419594812019,7.15,0.530776333563)); +#128457 = VECTOR('',#128458,1.); +#128458 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128459 = PCURVE('',#128233,#128460); +#128460 = DEFINITIONAL_REPRESENTATION('',(#128461),#128465); +#128461 = LINE('',#128462,#128463); +#128462 = CARTESIAN_POINT('',(-7.15,0.E+000)); +#128463 = VECTOR('',#128464,1.); +#128464 = DIRECTION('',(0.E+000,-1.)); +#128465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128466 = PCURVE('',#95986,#128467); +#128467 = DEFINITIONAL_REPRESENTATION('',(#128468),#128472); +#128468 = LINE('',#128469,#128470); +#128469 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#128470 = VECTOR('',#128471,1.); +#128471 = DIRECTION('',(1.,0.E+000)); +#128472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128473 = ADVANCED_FACE('',(#128474),#128420,.F.); +#128474 = FACE_BOUND('',#128475,.F.); +#128475 = EDGE_LOOP('',(#128476,#128477,#128500,#128522)); +#128476 = ORIENTED_EDGE('',*,*,#128402,.T.); +#128477 = ORIENTED_EDGE('',*,*,#128478,.F.); +#128478 = EDGE_CURVE('',#128479,#128405,#128481,.T.); +#128479 = VERTEX_POINT('',#128480); +#128480 = CARTESIAN_POINT('',(10.303662633502,7.35,0.65)); +#128481 = SURFACE_CURVE('',#128482,(#128487,#128493),.PCURVE_S1.); +#128482 = CIRCLE('',#128483,0.119270391569); +#128483 = AXIS2_PLACEMENT_3D('',#128484,#128485,#128486); +#128484 = CARTESIAN_POINT('',(10.30032442045,7.35,0.530776333563)); +#128485 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128486 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128487 = PCURVE('',#128420,#128488); +#128488 = DEFINITIONAL_REPRESENTATION('',(#128489),#128492); +#128489 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128490,#128491), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#126098 = CARTESIAN_POINT('',(1.598788597134,7.35)); -#126099 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#126100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126101 = PCURVE('',#93538,#126102); -#126102 = DEFINITIONAL_REPRESENTATION('',(#126103),#126107); -#126103 = CIRCLE('',#126104,0.119270391569); -#126104 = AXIS2_PLACEMENT_2D('',#126105,#126106); -#126105 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#126106 = DIRECTION('',(0.E+000,-1.)); -#126107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126108 = ORIENTED_EDGE('',*,*,#126109,.T.); -#126109 = EDGE_CURVE('',#126087,#126110,#126112,.T.); -#126110 = VERTEX_POINT('',#126111); -#126111 = CARTESIAN_POINT('',(10.303662633502,7.15,0.65)); -#126112 = SURFACE_CURVE('',#126113,(#126117,#126123),.PCURVE_S1.); -#126113 = LINE('',#126114,#126115); -#126114 = CARTESIAN_POINT('',(10.303662633502,7.15,0.65)); -#126115 = VECTOR('',#126116,1.); -#126116 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126117 = PCURVE('',#126028,#126118); -#126118 = DEFINITIONAL_REPRESENTATION('',(#126119),#126122); -#126119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126120,#126121), +#128490 = CARTESIAN_POINT('',(1.598788597134,7.35)); +#128491 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#128492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128493 = PCURVE('',#95930,#128494); +#128494 = DEFINITIONAL_REPRESENTATION('',(#128495),#128499); +#128495 = CIRCLE('',#128496,0.119270391569); +#128496 = AXIS2_PLACEMENT_2D('',#128497,#128498); +#128497 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#128498 = DIRECTION('',(0.E+000,-1.)); +#128499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128500 = ORIENTED_EDGE('',*,*,#128501,.T.); +#128501 = EDGE_CURVE('',#128479,#128502,#128504,.T.); +#128502 = VERTEX_POINT('',#128503); +#128503 = CARTESIAN_POINT('',(10.303662633502,7.15,0.65)); +#128504 = SURFACE_CURVE('',#128505,(#128509,#128515),.PCURVE_S1.); +#128505 = LINE('',#128506,#128507); +#128506 = CARTESIAN_POINT('',(10.303662633502,7.15,0.65)); +#128507 = VECTOR('',#128508,1.); +#128508 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128509 = PCURVE('',#128420,#128510); +#128510 = DEFINITIONAL_REPRESENTATION('',(#128511),#128514); +#128511 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128512,#128513), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#126120 = CARTESIAN_POINT('',(1.598788597134,7.35)); -#126121 = CARTESIAN_POINT('',(1.598788597134,7.15)); -#126122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126123 = PCURVE('',#93566,#126124); -#126124 = DEFINITIONAL_REPRESENTATION('',(#126125),#126129); -#126125 = LINE('',#126126,#126127); -#126126 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#126127 = VECTOR('',#126128,1.); -#126128 = DIRECTION('',(4.440892098501E-016,-1.)); -#126129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126130 = ORIENTED_EDGE('',*,*,#126131,.T.); -#126131 = EDGE_CURVE('',#126110,#126011,#126132,.T.); -#126132 = SURFACE_CURVE('',#126133,(#126138,#126144),.PCURVE_S1.); -#126133 = CIRCLE('',#126134,0.119270391569); -#126134 = AXIS2_PLACEMENT_3D('',#126135,#126136,#126137); -#126135 = CARTESIAN_POINT('',(10.30032442045,7.15,0.530776333563)); -#126136 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126137 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126138 = PCURVE('',#126028,#126139); -#126139 = DEFINITIONAL_REPRESENTATION('',(#126140),#126143); -#126140 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126141,#126142), +#128512 = CARTESIAN_POINT('',(1.598788597134,7.35)); +#128513 = CARTESIAN_POINT('',(1.598788597134,7.15)); +#128514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128515 = PCURVE('',#95958,#128516); +#128516 = DEFINITIONAL_REPRESENTATION('',(#128517),#128521); +#128517 = LINE('',#128518,#128519); +#128518 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#128519 = VECTOR('',#128520,1.); +#128520 = DIRECTION('',(4.440892098501E-016,-1.)); +#128521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128522 = ORIENTED_EDGE('',*,*,#128523,.T.); +#128523 = EDGE_CURVE('',#128502,#128403,#128524,.T.); +#128524 = SURFACE_CURVE('',#128525,(#128530,#128536),.PCURVE_S1.); +#128525 = CIRCLE('',#128526,0.119270391569); +#128526 = AXIS2_PLACEMENT_3D('',#128527,#128528,#128529); +#128527 = CARTESIAN_POINT('',(10.30032442045,7.15,0.530776333563)); +#128528 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128529 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128530 = PCURVE('',#128420,#128531); +#128531 = DEFINITIONAL_REPRESENTATION('',(#128532),#128535); +#128532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128533,#128534), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#126141 = CARTESIAN_POINT('',(1.598788597134,7.15)); -#126142 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#126143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128533 = CARTESIAN_POINT('',(1.598788597134,7.15)); +#128534 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#128535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126144 = PCURVE('',#93594,#126145); -#126145 = DEFINITIONAL_REPRESENTATION('',(#126146),#126154); -#126146 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126147,#126148,#126149, - #126150,#126151,#126152,#126153),.UNSPECIFIED.,.T.,.F.) +#128536 = PCURVE('',#95986,#128537); +#128537 = DEFINITIONAL_REPRESENTATION('',(#128538),#128546); +#128538 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128539,#128540,#128541, + #128542,#128543,#128544,#128545),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#126147 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#126148 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#126149 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#126150 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#126151 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#126152 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#126153 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#126154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126155 = ADVANCED_FACE('',(#126156),#125953,.T.); -#126156 = FACE_BOUND('',#126157,.T.); -#126157 = EDGE_LOOP('',(#126158,#126159,#126182,#126204)); -#126158 = ORIENTED_EDGE('',*,*,#125935,.F.); -#126159 = ORIENTED_EDGE('',*,*,#126160,.F.); -#126160 = EDGE_CURVE('',#126161,#125936,#126163,.T.); -#126161 = VERTEX_POINT('',#126162); -#126162 = CARTESIAN_POINT('',(10.304819755875,7.35,0.75)); -#126163 = SURFACE_CURVE('',#126164,(#126169,#126175),.PCURVE_S1.); -#126164 = CIRCLE('',#126165,0.2192697516); -#126165 = AXIS2_PLACEMENT_3D('',#126166,#126167,#126168); -#126166 = CARTESIAN_POINT('',(10.30032442045,7.35,0.530776333563)); -#126167 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126168 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126169 = PCURVE('',#125953,#126170); -#126170 = DEFINITIONAL_REPRESENTATION('',(#126171),#126174); -#126171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126172,#126173), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), - .PIECEWISE_BEZIER_KNOTS.); -#126172 = CARTESIAN_POINT('',(1.591299156552,7.35)); -#126173 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#126174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128539 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#128540 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#128541 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#128542 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#128543 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#128544 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#128545 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#128546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126175 = PCURVE('',#93538,#126176); -#126176 = DEFINITIONAL_REPRESENTATION('',(#126177),#126181); -#126177 = CIRCLE('',#126178,0.2192697516); -#126178 = AXIS2_PLACEMENT_2D('',#126179,#126180); -#126179 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#126180 = DIRECTION('',(0.E+000,-1.)); -#126181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126182 = ORIENTED_EDGE('',*,*,#126183,.F.); -#126183 = EDGE_CURVE('',#126184,#126161,#126186,.T.); -#126184 = VERTEX_POINT('',#126185); -#126185 = CARTESIAN_POINT('',(10.304819755875,7.15,0.75)); -#126186 = SURFACE_CURVE('',#126187,(#126191,#126197),.PCURVE_S1.); -#126187 = LINE('',#126188,#126189); -#126188 = CARTESIAN_POINT('',(10.304819755875,7.15,0.75)); -#126189 = VECTOR('',#126190,1.); -#126190 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126191 = PCURVE('',#125953,#126192); -#126192 = DEFINITIONAL_REPRESENTATION('',(#126193),#126196); -#126193 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126194,#126195), +#128547 = ADVANCED_FACE('',(#128548),#128345,.T.); +#128548 = FACE_BOUND('',#128549,.T.); +#128549 = EDGE_LOOP('',(#128550,#128551,#128574,#128596)); +#128550 = ORIENTED_EDGE('',*,*,#128327,.F.); +#128551 = ORIENTED_EDGE('',*,*,#128552,.F.); +#128552 = EDGE_CURVE('',#128553,#128328,#128555,.T.); +#128553 = VERTEX_POINT('',#128554); +#128554 = CARTESIAN_POINT('',(10.304819755875,7.35,0.75)); +#128555 = SURFACE_CURVE('',#128556,(#128561,#128567),.PCURVE_S1.); +#128556 = CIRCLE('',#128557,0.2192697516); +#128557 = AXIS2_PLACEMENT_3D('',#128558,#128559,#128560); +#128558 = CARTESIAN_POINT('',(10.30032442045,7.35,0.530776333563)); +#128559 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128560 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128561 = PCURVE('',#128345,#128562); +#128562 = DEFINITIONAL_REPRESENTATION('',(#128563),#128566); +#128563 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128564,#128565), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), + .PIECEWISE_BEZIER_KNOTS.); +#128564 = CARTESIAN_POINT('',(1.591299156552,7.35)); +#128565 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#128566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128567 = PCURVE('',#95930,#128568); +#128568 = DEFINITIONAL_REPRESENTATION('',(#128569),#128573); +#128569 = CIRCLE('',#128570,0.2192697516); +#128570 = AXIS2_PLACEMENT_2D('',#128571,#128572); +#128571 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#128572 = DIRECTION('',(0.E+000,-1.)); +#128573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128574 = ORIENTED_EDGE('',*,*,#128575,.F.); +#128575 = EDGE_CURVE('',#128576,#128553,#128578,.T.); +#128576 = VERTEX_POINT('',#128577); +#128577 = CARTESIAN_POINT('',(10.304819755875,7.15,0.75)); +#128578 = SURFACE_CURVE('',#128579,(#128583,#128589),.PCURVE_S1.); +#128579 = LINE('',#128580,#128581); +#128580 = CARTESIAN_POINT('',(10.304819755875,7.15,0.75)); +#128581 = VECTOR('',#128582,1.); +#128582 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128583 = PCURVE('',#128345,#128584); +#128584 = DEFINITIONAL_REPRESENTATION('',(#128585),#128588); +#128585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128586,#128587), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#126194 = CARTESIAN_POINT('',(1.591299156552,7.15)); -#126195 = CARTESIAN_POINT('',(1.591299156552,7.35)); -#126196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126197 = PCURVE('',#93620,#126198); -#126198 = DEFINITIONAL_REPRESENTATION('',(#126199),#126203); -#126199 = LINE('',#126200,#126201); -#126200 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#126201 = VECTOR('',#126202,1.); -#126202 = DIRECTION('',(4.440892098501E-016,1.)); -#126203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126204 = ORIENTED_EDGE('',*,*,#126205,.T.); -#126205 = EDGE_CURVE('',#126184,#125938,#126206,.T.); -#126206 = SURFACE_CURVE('',#126207,(#126212,#126218),.PCURVE_S1.); -#126207 = CIRCLE('',#126208,0.2192697516); -#126208 = AXIS2_PLACEMENT_3D('',#126209,#126210,#126211); -#126209 = CARTESIAN_POINT('',(10.30032442045,7.15,0.530776333563)); -#126210 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126211 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126212 = PCURVE('',#125953,#126213); -#126213 = DEFINITIONAL_REPRESENTATION('',(#126214),#126217); -#126214 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126215,#126216), +#128586 = CARTESIAN_POINT('',(1.591299156552,7.15)); +#128587 = CARTESIAN_POINT('',(1.591299156552,7.35)); +#128588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128589 = PCURVE('',#96012,#128590); +#128590 = DEFINITIONAL_REPRESENTATION('',(#128591),#128595); +#128591 = LINE('',#128592,#128593); +#128592 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#128593 = VECTOR('',#128594,1.); +#128594 = DIRECTION('',(4.440892098501E-016,1.)); +#128595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128596 = ORIENTED_EDGE('',*,*,#128597,.T.); +#128597 = EDGE_CURVE('',#128576,#128330,#128598,.T.); +#128598 = SURFACE_CURVE('',#128599,(#128604,#128610),.PCURVE_S1.); +#128599 = CIRCLE('',#128600,0.2192697516); +#128600 = AXIS2_PLACEMENT_3D('',#128601,#128602,#128603); +#128601 = CARTESIAN_POINT('',(10.30032442045,7.15,0.530776333563)); +#128602 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128603 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#128604 = PCURVE('',#128345,#128605); +#128605 = DEFINITIONAL_REPRESENTATION('',(#128606),#128609); +#128606 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128607,#128608), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#126215 = CARTESIAN_POINT('',(1.591299156552,7.15)); -#126216 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#126217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#128607 = CARTESIAN_POINT('',(1.591299156552,7.15)); +#128608 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#128609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126218 = PCURVE('',#93594,#126219); -#126219 = DEFINITIONAL_REPRESENTATION('',(#126220),#126228); -#126220 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126221,#126222,#126223, - #126224,#126225,#126226,#126227),.UNSPECIFIED.,.T.,.F.) +#128610 = PCURVE('',#95986,#128611); +#128611 = DEFINITIONAL_REPRESENTATION('',(#128612),#128620); +#128612 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128613,#128614,#128615, + #128616,#128617,#128618,#128619),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#126221 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#126222 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#126223 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#126224 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#126225 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#126226 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#126227 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#126228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126229 = ADVANCED_FACE('',(#126230),#93566,.T.); -#126230 = FACE_BOUND('',#126231,.T.); -#126231 = EDGE_LOOP('',(#126232,#126253,#126254,#126275)); -#126232 = ORIENTED_EDGE('',*,*,#126233,.F.); -#126233 = EDGE_CURVE('',#126087,#93523,#126234,.T.); -#126234 = SURFACE_CURVE('',#126235,(#126239,#126246),.PCURVE_S1.); -#126235 = LINE('',#126236,#126237); -#126236 = CARTESIAN_POINT('',(10.527847992439,7.35,0.65)); -#126237 = VECTOR('',#126238,1.); -#126238 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#126239 = PCURVE('',#93566,#126240); -#126240 = DEFINITIONAL_REPRESENTATION('',(#126241),#126245); -#126241 = LINE('',#126242,#126243); -#126242 = CARTESIAN_POINT('',(0.E+000,0.2)); -#126243 = VECTOR('',#126244,1.); -#126244 = DIRECTION('',(1.,-1.082494723017E-063)); -#126245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126246 = PCURVE('',#93538,#126247); -#126247 = DEFINITIONAL_REPRESENTATION('',(#126248),#126252); -#126248 = LINE('',#126249,#126250); -#126249 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126250 = VECTOR('',#126251,1.); -#126251 = DIRECTION('',(3.563627120235E-016,-1.)); -#126252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126253 = ORIENTED_EDGE('',*,*,#126109,.T.); -#126254 = ORIENTED_EDGE('',*,*,#126255,.T.); -#126255 = EDGE_CURVE('',#126110,#93551,#126256,.T.); -#126256 = SURFACE_CURVE('',#126257,(#126261,#126268),.PCURVE_S1.); -#126257 = LINE('',#126258,#126259); -#126258 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); -#126259 = VECTOR('',#126260,1.); -#126260 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#126261 = PCURVE('',#93566,#126262); -#126262 = DEFINITIONAL_REPRESENTATION('',(#126263),#126267); -#126263 = LINE('',#126264,#126265); -#126264 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126265 = VECTOR('',#126266,1.); -#126266 = DIRECTION('',(1.,-1.082494723017E-063)); -#126267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126268 = PCURVE('',#93594,#126269); -#126269 = DEFINITIONAL_REPRESENTATION('',(#126270),#126274); -#126270 = LINE('',#126271,#126272); -#126271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126272 = VECTOR('',#126273,1.); -#126273 = DIRECTION('',(-3.563627120235E-016,-1.)); -#126274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126275 = ORIENTED_EDGE('',*,*,#93550,.F.); -#126276 = ADVANCED_FACE('',(#126277),#93538,.T.); -#126277 = FACE_BOUND('',#126278,.T.); -#126278 = EDGE_LOOP('',(#126279,#126300,#126301,#126302,#126303,#126304, - #126325,#126326,#126327,#126328,#126329,#126330)); -#126279 = ORIENTED_EDGE('',*,*,#126280,.F.); -#126280 = EDGE_CURVE('',#126161,#93521,#126281,.T.); -#126281 = SURFACE_CURVE('',#126282,(#126286,#126293),.PCURVE_S1.); -#126282 = LINE('',#126283,#126284); -#126283 = CARTESIAN_POINT('',(10.527847992439,7.35,0.75)); -#126284 = VECTOR('',#126285,1.); -#126285 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#126286 = PCURVE('',#93538,#126287); -#126287 = DEFINITIONAL_REPRESENTATION('',(#126288),#126292); -#126288 = LINE('',#126289,#126290); -#126289 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#126290 = VECTOR('',#126291,1.); -#126291 = DIRECTION('',(3.563627120235E-016,-1.)); -#126292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126293 = PCURVE('',#93620,#126294); -#126294 = DEFINITIONAL_REPRESENTATION('',(#126295),#126299); -#126295 = LINE('',#126296,#126297); -#126296 = CARTESIAN_POINT('',(0.E+000,0.2)); -#126297 = VECTOR('',#126298,1.); -#126298 = DIRECTION('',(-1.,-1.082494723017E-063)); -#126299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126300 = ORIENTED_EDGE('',*,*,#126160,.T.); -#126301 = ORIENTED_EDGE('',*,*,#125986,.T.); -#126302 = ORIENTED_EDGE('',*,*,#125906,.T.); -#126303 = ORIENTED_EDGE('',*,*,#125703,.T.); -#126304 = ORIENTED_EDGE('',*,*,#126305,.F.); -#126305 = EDGE_CURVE('',#125567,#125674,#126306,.T.); -#126306 = SURFACE_CURVE('',#126307,(#126311,#126318),.PCURVE_S1.); -#126307 = LINE('',#126308,#126309); -#126308 = CARTESIAN_POINT('',(11.,7.35,1.159810404338E-002)); -#126309 = VECTOR('',#126310,1.); -#126310 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#126311 = PCURVE('',#93538,#126312); -#126312 = DEFINITIONAL_REPRESENTATION('',(#126313),#126317); -#126313 = LINE('',#126314,#126315); -#126314 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#126315 = VECTOR('',#126316,1.); -#126316 = DIRECTION('',(1.,2.101748079665E-016)); -#126317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126318 = PCURVE('',#125587,#126319); -#126319 = DEFINITIONAL_REPRESENTATION('',(#126320),#126324); -#126320 = LINE('',#126321,#126322); -#126321 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#126322 = VECTOR('',#126323,1.); -#126323 = DIRECTION('',(1.194699204908E-017,1.)); -#126324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126325 = ORIENTED_EDGE('',*,*,#125649,.F.); -#126326 = ORIENTED_EDGE('',*,*,#125777,.F.); -#126327 = ORIENTED_EDGE('',*,*,#126039,.F.); -#126328 = ORIENTED_EDGE('',*,*,#126086,.F.); -#126329 = ORIENTED_EDGE('',*,*,#126233,.T.); -#126330 = ORIENTED_EDGE('',*,*,#93520,.F.); -#126331 = ADVANCED_FACE('',(#126332),#93620,.T.); -#126332 = FACE_BOUND('',#126333,.T.); -#126333 = EDGE_LOOP('',(#126334,#126355,#126356,#126357)); -#126334 = ORIENTED_EDGE('',*,*,#126335,.F.); -#126335 = EDGE_CURVE('',#126184,#93579,#126336,.T.); -#126336 = SURFACE_CURVE('',#126337,(#126341,#126348),.PCURVE_S1.); -#126337 = LINE('',#126338,#126339); -#126338 = CARTESIAN_POINT('',(10.527847992439,7.15,0.75)); -#126339 = VECTOR('',#126340,1.); -#126340 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#126341 = PCURVE('',#93620,#126342); -#126342 = DEFINITIONAL_REPRESENTATION('',(#126343),#126347); -#126343 = LINE('',#126344,#126345); -#126344 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126345 = VECTOR('',#126346,1.); -#126346 = DIRECTION('',(-1.,-1.082494723017E-063)); -#126347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126348 = PCURVE('',#93594,#126349); -#126349 = DEFINITIONAL_REPRESENTATION('',(#126350),#126354); -#126350 = LINE('',#126351,#126352); -#126351 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#126352 = VECTOR('',#126353,1.); -#126353 = DIRECTION('',(-3.563627120235E-016,-1.)); -#126354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126355 = ORIENTED_EDGE('',*,*,#126183,.T.); -#126356 = ORIENTED_EDGE('',*,*,#126280,.T.); -#126357 = ORIENTED_EDGE('',*,*,#93606,.F.); -#126358 = ADVANCED_FACE('',(#126359),#93594,.T.); -#126359 = FACE_BOUND('',#126360,.T.); -#126360 = EDGE_LOOP('',(#126361,#126362,#126363,#126364,#126365,#126366, - #126387,#126388,#126389,#126390,#126391,#126392)); -#126361 = ORIENTED_EDGE('',*,*,#126255,.F.); -#126362 = ORIENTED_EDGE('',*,*,#126131,.T.); -#126363 = ORIENTED_EDGE('',*,*,#126061,.T.); -#126364 = ORIENTED_EDGE('',*,*,#125805,.T.); -#126365 = ORIENTED_EDGE('',*,*,#125599,.T.); -#126366 = ORIENTED_EDGE('',*,*,#126367,.F.); -#126367 = EDGE_CURVE('',#125676,#125565,#126368,.T.); -#126368 = SURFACE_CURVE('',#126369,(#126373,#126380),.PCURVE_S1.); -#126369 = LINE('',#126370,#126371); -#126370 = CARTESIAN_POINT('',(11.,7.15,1.159810404338E-002)); -#126371 = VECTOR('',#126372,1.); -#126372 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#126373 = PCURVE('',#93594,#126374); -#126374 = DEFINITIONAL_REPRESENTATION('',(#126375),#126379); -#126375 = LINE('',#126376,#126377); -#126376 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#126377 = VECTOR('',#126378,1.); -#126378 = DIRECTION('',(1.,-2.101748079665E-016)); -#126379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126380 = PCURVE('',#125587,#126381); -#126381 = DEFINITIONAL_REPRESENTATION('',(#126382),#126386); -#126382 = LINE('',#126383,#126384); -#126383 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#126384 = VECTOR('',#126385,1.); -#126385 = DIRECTION('',(-1.194699204908E-017,-1.)); -#126386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126387 = ORIENTED_EDGE('',*,*,#125753,.F.); -#126388 = ORIENTED_EDGE('',*,*,#125856,.F.); -#126389 = ORIENTED_EDGE('',*,*,#125964,.F.); -#126390 = ORIENTED_EDGE('',*,*,#126205,.F.); -#126391 = ORIENTED_EDGE('',*,*,#126335,.T.); -#126392 = ORIENTED_EDGE('',*,*,#93578,.F.); -#126393 = ADVANCED_FACE('',(#126394),#125587,.T.); -#126394 = FACE_BOUND('',#126395,.T.); -#126395 = EDGE_LOOP('',(#126396,#126397,#126398,#126399)); -#126396 = ORIENTED_EDGE('',*,*,#126305,.T.); -#126397 = ORIENTED_EDGE('',*,*,#125673,.T.); -#126398 = ORIENTED_EDGE('',*,*,#126367,.T.); -#126399 = ORIENTED_EDGE('',*,*,#125564,.T.); -#126400 = ADVANCED_FACE('',(#126401),#126415,.F.); -#126401 = FACE_BOUND('',#126402,.T.); -#126402 = EDGE_LOOP('',(#126403,#126438,#126461,#126488)); -#126403 = ORIENTED_EDGE('',*,*,#126404,.F.); -#126404 = EDGE_CURVE('',#126405,#126407,#126409,.T.); -#126405 = VERTEX_POINT('',#126406); -#126406 = CARTESIAN_POINT('',(11.,6.65,-0.308197125857)); -#126407 = VERTEX_POINT('',#126408); -#126408 = CARTESIAN_POINT('',(11.,6.85,-0.308197125857)); -#126409 = SURFACE_CURVE('',#126410,(#126414,#126426),.PCURVE_S1.); -#126410 = LINE('',#126411,#126412); -#126411 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#126412 = VECTOR('',#126413,1.); -#126413 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126414 = PCURVE('',#126415,#126420); -#126415 = PLANE('',#126416); -#126416 = AXIS2_PLACEMENT_3D('',#126417,#126418,#126419); -#126417 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#128613 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#128614 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#128615 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#128616 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#128617 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#128618 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#128619 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#128620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128621 = ADVANCED_FACE('',(#128622),#95958,.T.); +#128622 = FACE_BOUND('',#128623,.T.); +#128623 = EDGE_LOOP('',(#128624,#128645,#128646,#128667)); +#128624 = ORIENTED_EDGE('',*,*,#128625,.F.); +#128625 = EDGE_CURVE('',#128479,#95915,#128626,.T.); +#128626 = SURFACE_CURVE('',#128627,(#128631,#128638),.PCURVE_S1.); +#128627 = LINE('',#128628,#128629); +#128628 = CARTESIAN_POINT('',(10.527847992439,7.35,0.65)); +#128629 = VECTOR('',#128630,1.); +#128630 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#128631 = PCURVE('',#95958,#128632); +#128632 = DEFINITIONAL_REPRESENTATION('',(#128633),#128637); +#128633 = LINE('',#128634,#128635); +#128634 = CARTESIAN_POINT('',(0.E+000,0.2)); +#128635 = VECTOR('',#128636,1.); +#128636 = DIRECTION('',(1.,-1.082494723017E-063)); +#128637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128638 = PCURVE('',#95930,#128639); +#128639 = DEFINITIONAL_REPRESENTATION('',(#128640),#128644); +#128640 = LINE('',#128641,#128642); +#128641 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128642 = VECTOR('',#128643,1.); +#128643 = DIRECTION('',(3.563627120235E-016,-1.)); +#128644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128645 = ORIENTED_EDGE('',*,*,#128501,.T.); +#128646 = ORIENTED_EDGE('',*,*,#128647,.T.); +#128647 = EDGE_CURVE('',#128502,#95943,#128648,.T.); +#128648 = SURFACE_CURVE('',#128649,(#128653,#128660),.PCURVE_S1.); +#128649 = LINE('',#128650,#128651); +#128650 = CARTESIAN_POINT('',(10.527847992439,7.15,0.65)); +#128651 = VECTOR('',#128652,1.); +#128652 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#128653 = PCURVE('',#95958,#128654); +#128654 = DEFINITIONAL_REPRESENTATION('',(#128655),#128659); +#128655 = LINE('',#128656,#128657); +#128656 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128657 = VECTOR('',#128658,1.); +#128658 = DIRECTION('',(1.,-1.082494723017E-063)); +#128659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128660 = PCURVE('',#95986,#128661); +#128661 = DEFINITIONAL_REPRESENTATION('',(#128662),#128666); +#128662 = LINE('',#128663,#128664); +#128663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128664 = VECTOR('',#128665,1.); +#128665 = DIRECTION('',(-3.563627120235E-016,-1.)); +#128666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128667 = ORIENTED_EDGE('',*,*,#95942,.F.); +#128668 = ADVANCED_FACE('',(#128669),#95930,.T.); +#128669 = FACE_BOUND('',#128670,.T.); +#128670 = EDGE_LOOP('',(#128671,#128692,#128693,#128694,#128695,#128696, + #128717,#128718,#128719,#128720,#128721,#128722)); +#128671 = ORIENTED_EDGE('',*,*,#128672,.F.); +#128672 = EDGE_CURVE('',#128553,#95913,#128673,.T.); +#128673 = SURFACE_CURVE('',#128674,(#128678,#128685),.PCURVE_S1.); +#128674 = LINE('',#128675,#128676); +#128675 = CARTESIAN_POINT('',(10.527847992439,7.35,0.75)); +#128676 = VECTOR('',#128677,1.); +#128677 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#128678 = PCURVE('',#95930,#128679); +#128679 = DEFINITIONAL_REPRESENTATION('',(#128680),#128684); +#128680 = LINE('',#128681,#128682); +#128681 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#128682 = VECTOR('',#128683,1.); +#128683 = DIRECTION('',(3.563627120235E-016,-1.)); +#128684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128685 = PCURVE('',#96012,#128686); +#128686 = DEFINITIONAL_REPRESENTATION('',(#128687),#128691); +#128687 = LINE('',#128688,#128689); +#128688 = CARTESIAN_POINT('',(0.E+000,0.2)); +#128689 = VECTOR('',#128690,1.); +#128690 = DIRECTION('',(-1.,-1.082494723017E-063)); +#128691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128692 = ORIENTED_EDGE('',*,*,#128552,.T.); +#128693 = ORIENTED_EDGE('',*,*,#128378,.T.); +#128694 = ORIENTED_EDGE('',*,*,#128298,.T.); +#128695 = ORIENTED_EDGE('',*,*,#128095,.T.); +#128696 = ORIENTED_EDGE('',*,*,#128697,.F.); +#128697 = EDGE_CURVE('',#127959,#128066,#128698,.T.); +#128698 = SURFACE_CURVE('',#128699,(#128703,#128710),.PCURVE_S1.); +#128699 = LINE('',#128700,#128701); +#128700 = CARTESIAN_POINT('',(11.,7.35,1.159810404338E-002)); +#128701 = VECTOR('',#128702,1.); +#128702 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#128703 = PCURVE('',#95930,#128704); +#128704 = DEFINITIONAL_REPRESENTATION('',(#128705),#128709); +#128705 = LINE('',#128706,#128707); +#128706 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#128707 = VECTOR('',#128708,1.); +#128708 = DIRECTION('',(1.,2.101748079665E-016)); +#128709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128710 = PCURVE('',#127979,#128711); +#128711 = DEFINITIONAL_REPRESENTATION('',(#128712),#128716); +#128712 = LINE('',#128713,#128714); +#128713 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#128714 = VECTOR('',#128715,1.); +#128715 = DIRECTION('',(1.194699204908E-017,1.)); +#128716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128717 = ORIENTED_EDGE('',*,*,#128041,.F.); +#128718 = ORIENTED_EDGE('',*,*,#128169,.F.); +#128719 = ORIENTED_EDGE('',*,*,#128431,.F.); +#128720 = ORIENTED_EDGE('',*,*,#128478,.F.); +#128721 = ORIENTED_EDGE('',*,*,#128625,.T.); +#128722 = ORIENTED_EDGE('',*,*,#95912,.F.); +#128723 = ADVANCED_FACE('',(#128724),#96012,.T.); +#128724 = FACE_BOUND('',#128725,.T.); +#128725 = EDGE_LOOP('',(#128726,#128747,#128748,#128749)); +#128726 = ORIENTED_EDGE('',*,*,#128727,.F.); +#128727 = EDGE_CURVE('',#128576,#95971,#128728,.T.); +#128728 = SURFACE_CURVE('',#128729,(#128733,#128740),.PCURVE_S1.); +#128729 = LINE('',#128730,#128731); +#128730 = CARTESIAN_POINT('',(10.527847992439,7.15,0.75)); +#128731 = VECTOR('',#128732,1.); +#128732 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#128733 = PCURVE('',#96012,#128734); +#128734 = DEFINITIONAL_REPRESENTATION('',(#128735),#128739); +#128735 = LINE('',#128736,#128737); +#128736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128737 = VECTOR('',#128738,1.); +#128738 = DIRECTION('',(-1.,-1.082494723017E-063)); +#128739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128740 = PCURVE('',#95986,#128741); +#128741 = DEFINITIONAL_REPRESENTATION('',(#128742),#128746); +#128742 = LINE('',#128743,#128744); +#128743 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#128744 = VECTOR('',#128745,1.); +#128745 = DIRECTION('',(-3.563627120235E-016,-1.)); +#128746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128747 = ORIENTED_EDGE('',*,*,#128575,.T.); +#128748 = ORIENTED_EDGE('',*,*,#128672,.T.); +#128749 = ORIENTED_EDGE('',*,*,#95998,.F.); +#128750 = ADVANCED_FACE('',(#128751),#95986,.T.); +#128751 = FACE_BOUND('',#128752,.T.); +#128752 = EDGE_LOOP('',(#128753,#128754,#128755,#128756,#128757,#128758, + #128779,#128780,#128781,#128782,#128783,#128784)); +#128753 = ORIENTED_EDGE('',*,*,#128647,.F.); +#128754 = ORIENTED_EDGE('',*,*,#128523,.T.); +#128755 = ORIENTED_EDGE('',*,*,#128453,.T.); +#128756 = ORIENTED_EDGE('',*,*,#128197,.T.); +#128757 = ORIENTED_EDGE('',*,*,#127991,.T.); +#128758 = ORIENTED_EDGE('',*,*,#128759,.F.); +#128759 = EDGE_CURVE('',#128068,#127957,#128760,.T.); +#128760 = SURFACE_CURVE('',#128761,(#128765,#128772),.PCURVE_S1.); +#128761 = LINE('',#128762,#128763); +#128762 = CARTESIAN_POINT('',(11.,7.15,1.159810404338E-002)); +#128763 = VECTOR('',#128764,1.); +#128764 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#128765 = PCURVE('',#95986,#128766); +#128766 = DEFINITIONAL_REPRESENTATION('',(#128767),#128771); +#128767 = LINE('',#128768,#128769); +#128768 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#128769 = VECTOR('',#128770,1.); +#128770 = DIRECTION('',(1.,-2.101748079665E-016)); +#128771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128772 = PCURVE('',#127979,#128773); +#128773 = DEFINITIONAL_REPRESENTATION('',(#128774),#128778); +#128774 = LINE('',#128775,#128776); +#128775 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#128776 = VECTOR('',#128777,1.); +#128777 = DIRECTION('',(-1.194699204908E-017,-1.)); +#128778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128779 = ORIENTED_EDGE('',*,*,#128145,.F.); +#128780 = ORIENTED_EDGE('',*,*,#128248,.F.); +#128781 = ORIENTED_EDGE('',*,*,#128356,.F.); +#128782 = ORIENTED_EDGE('',*,*,#128597,.F.); +#128783 = ORIENTED_EDGE('',*,*,#128727,.T.); +#128784 = ORIENTED_EDGE('',*,*,#95970,.F.); +#128785 = ADVANCED_FACE('',(#128786),#127979,.T.); +#128786 = FACE_BOUND('',#128787,.T.); +#128787 = EDGE_LOOP('',(#128788,#128789,#128790,#128791)); +#128788 = ORIENTED_EDGE('',*,*,#128697,.T.); +#128789 = ORIENTED_EDGE('',*,*,#128065,.T.); +#128790 = ORIENTED_EDGE('',*,*,#128759,.T.); +#128791 = ORIENTED_EDGE('',*,*,#127956,.T.); +#128792 = ADVANCED_FACE('',(#128793),#128807,.F.); +#128793 = FACE_BOUND('',#128794,.T.); +#128794 = EDGE_LOOP('',(#128795,#128830,#128853,#128880)); +#128795 = ORIENTED_EDGE('',*,*,#128796,.F.); +#128796 = EDGE_CURVE('',#128797,#128799,#128801,.T.); +#128797 = VERTEX_POINT('',#128798); +#128798 = CARTESIAN_POINT('',(11.,6.65,-0.308197125857)); +#128799 = VERTEX_POINT('',#128800); +#128800 = CARTESIAN_POINT('',(11.,6.85,-0.308197125857)); +#128801 = SURFACE_CURVE('',#128802,(#128806,#128818),.PCURVE_S1.); +#128802 = LINE('',#128803,#128804); +#128803 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#128804 = VECTOR('',#128805,1.); +#128805 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128806 = PCURVE('',#128807,#128812); +#128807 = PLANE('',#128808); +#128808 = AXIS2_PLACEMENT_3D('',#128809,#128810,#128811); +#128809 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#126418 = DIRECTION('',(0.E+000,0.E+000,1.)); -#126419 = DIRECTION('',(1.,0.E+000,0.E+000)); -#126420 = DEFINITIONAL_REPRESENTATION('',(#126421),#126425); -#126421 = LINE('',#126422,#126423); -#126422 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#126423 = VECTOR('',#126424,1.); -#126424 = DIRECTION('',(4.440892098501E-016,1.)); -#126425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126426 = PCURVE('',#126427,#126432); -#126427 = PLANE('',#126428); -#126428 = AXIS2_PLACEMENT_3D('',#126429,#126430,#126431); -#126429 = CARTESIAN_POINT('',(11.,6.75,-0.258196742327)); -#126430 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#126431 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126432 = DEFINITIONAL_REPRESENTATION('',(#126433),#126437); -#126433 = LINE('',#126434,#126435); -#126434 = CARTESIAN_POINT('',(-6.75,-5.00003835295E-002)); -#126435 = VECTOR('',#126436,1.); -#126436 = DIRECTION('',(1.,0.E+000)); -#126437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126438 = ORIENTED_EDGE('',*,*,#126439,.F.); -#126439 = EDGE_CURVE('',#126440,#126405,#126442,.T.); -#126440 = VERTEX_POINT('',#126441); -#126441 = CARTESIAN_POINT('',(10.74341632541,6.65,-0.308197125857)); -#126442 = SURFACE_CURVE('',#126443,(#126447,#126454),.PCURVE_S1.); -#126443 = LINE('',#126444,#126445); -#126444 = CARTESIAN_POINT('',(10.74341632541,6.65,-0.308197125857)); -#126445 = VECTOR('',#126446,1.); -#126446 = DIRECTION('',(1.,0.E+000,0.E+000)); -#126447 = PCURVE('',#126415,#126448); -#126448 = DEFINITIONAL_REPRESENTATION('',(#126449),#126453); -#126449 = LINE('',#126450,#126451); -#126450 = CARTESIAN_POINT('',(3.552713678801E-015,6.65)); -#126451 = VECTOR('',#126452,1.); -#126452 = DIRECTION('',(1.,0.E+000)); -#126453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126454 = PCURVE('',#93480,#126455); -#126455 = DEFINITIONAL_REPRESENTATION('',(#126456),#126460); -#126456 = LINE('',#126457,#126458); -#126457 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#126458 = VECTOR('',#126459,1.); -#126459 = DIRECTION('',(0.E+000,1.)); -#126460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126461 = ORIENTED_EDGE('',*,*,#126462,.F.); -#126462 = EDGE_CURVE('',#126463,#126440,#126465,.T.); -#126463 = VERTEX_POINT('',#126464); -#126464 = CARTESIAN_POINT('',(10.74341632541,6.85,-0.308197125857)); -#126465 = SURFACE_CURVE('',#126466,(#126470,#126477),.PCURVE_S1.); -#126466 = LINE('',#126467,#126468); -#126467 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#128810 = DIRECTION('',(0.E+000,0.E+000,1.)); +#128811 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128812 = DEFINITIONAL_REPRESENTATION('',(#128813),#128817); +#128813 = LINE('',#128814,#128815); +#128814 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#128815 = VECTOR('',#128816,1.); +#128816 = DIRECTION('',(4.440892098501E-016,1.)); +#128817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128818 = PCURVE('',#128819,#128824); +#128819 = PLANE('',#128820); +#128820 = AXIS2_PLACEMENT_3D('',#128821,#128822,#128823); +#128821 = CARTESIAN_POINT('',(11.,6.75,-0.258196742327)); +#128822 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#128823 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128824 = DEFINITIONAL_REPRESENTATION('',(#128825),#128829); +#128825 = LINE('',#128826,#128827); +#128826 = CARTESIAN_POINT('',(-6.75,-5.00003835295E-002)); +#128827 = VECTOR('',#128828,1.); +#128828 = DIRECTION('',(1.,0.E+000)); +#128829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128830 = ORIENTED_EDGE('',*,*,#128831,.F.); +#128831 = EDGE_CURVE('',#128832,#128797,#128834,.T.); +#128832 = VERTEX_POINT('',#128833); +#128833 = CARTESIAN_POINT('',(10.74341632541,6.65,-0.308197125857)); +#128834 = SURFACE_CURVE('',#128835,(#128839,#128846),.PCURVE_S1.); +#128835 = LINE('',#128836,#128837); +#128836 = CARTESIAN_POINT('',(10.74341632541,6.65,-0.308197125857)); +#128837 = VECTOR('',#128838,1.); +#128838 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128839 = PCURVE('',#128807,#128840); +#128840 = DEFINITIONAL_REPRESENTATION('',(#128841),#128845); +#128841 = LINE('',#128842,#128843); +#128842 = CARTESIAN_POINT('',(3.552713678801E-015,6.65)); +#128843 = VECTOR('',#128844,1.); +#128844 = DIRECTION('',(1.,0.E+000)); +#128845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128846 = PCURVE('',#95872,#128847); +#128847 = DEFINITIONAL_REPRESENTATION('',(#128848),#128852); +#128848 = LINE('',#128849,#128850); +#128849 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#128850 = VECTOR('',#128851,1.); +#128851 = DIRECTION('',(0.E+000,1.)); +#128852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128853 = ORIENTED_EDGE('',*,*,#128854,.F.); +#128854 = EDGE_CURVE('',#128855,#128832,#128857,.T.); +#128855 = VERTEX_POINT('',#128856); +#128856 = CARTESIAN_POINT('',(10.74341632541,6.85,-0.308197125857)); +#128857 = SURFACE_CURVE('',#128858,(#128862,#128869),.PCURVE_S1.); +#128858 = LINE('',#128859,#128860); +#128859 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#126468 = VECTOR('',#126469,1.); -#126469 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126470 = PCURVE('',#126415,#126471); -#126471 = DEFINITIONAL_REPRESENTATION('',(#126472),#126476); -#126472 = LINE('',#126473,#126474); -#126473 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126474 = VECTOR('',#126475,1.); -#126475 = DIRECTION('',(-4.440892098501E-016,-1.)); -#126476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126477 = PCURVE('',#126478,#126483); -#126478 = CYLINDRICAL_SURFACE('',#126479,0.308574064194); -#126479 = AXIS2_PLACEMENT_3D('',#126480,#126481,#126482); -#126480 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#128860 = VECTOR('',#128861,1.); +#128861 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128862 = PCURVE('',#128807,#128863); +#128863 = DEFINITIONAL_REPRESENTATION('',(#128864),#128868); +#128864 = LINE('',#128865,#128866); +#128865 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128866 = VECTOR('',#128867,1.); +#128867 = DIRECTION('',(-4.440892098501E-016,-1.)); +#128868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128869 = PCURVE('',#128870,#128875); +#128870 = CYLINDRICAL_SURFACE('',#128871,0.308574064194); +#128871 = AXIS2_PLACEMENT_3D('',#128872,#128873,#128874); +#128872 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#126481 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126482 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126483 = DEFINITIONAL_REPRESENTATION('',(#126484),#126487); -#126484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126485,#126486), +#128873 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128874 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128875 = DEFINITIONAL_REPRESENTATION('',(#128876),#128879); +#128876 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128877,#128878), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#126485 = CARTESIAN_POINT('',(4.761821717947,-6.85)); -#126486 = CARTESIAN_POINT('',(4.761821717947,-6.65)); -#126487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126488 = ORIENTED_EDGE('',*,*,#126489,.T.); -#126489 = EDGE_CURVE('',#126463,#126407,#126490,.T.); -#126490 = SURFACE_CURVE('',#126491,(#126495,#126502),.PCURVE_S1.); -#126491 = LINE('',#126492,#126493); -#126492 = CARTESIAN_POINT('',(10.74341632541,6.85,-0.308197125857)); -#126493 = VECTOR('',#126494,1.); -#126494 = DIRECTION('',(1.,0.E+000,0.E+000)); -#126495 = PCURVE('',#126415,#126496); -#126496 = DEFINITIONAL_REPRESENTATION('',(#126497),#126501); -#126497 = LINE('',#126498,#126499); -#126498 = CARTESIAN_POINT('',(3.552713678801E-015,6.85)); -#126499 = VECTOR('',#126500,1.); -#126500 = DIRECTION('',(1.,0.E+000)); -#126501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126502 = PCURVE('',#93424,#126503); -#126503 = DEFINITIONAL_REPRESENTATION('',(#126504),#126508); -#126504 = LINE('',#126505,#126506); -#126505 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#126506 = VECTOR('',#126507,1.); -#126507 = DIRECTION('',(0.E+000,1.)); -#126508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126509 = ADVANCED_FACE('',(#126510),#126524,.F.); -#126510 = FACE_BOUND('',#126511,.T.); -#126511 = EDGE_LOOP('',(#126512,#126542,#126565,#126592)); -#126512 = ORIENTED_EDGE('',*,*,#126513,.F.); -#126513 = EDGE_CURVE('',#126514,#126516,#126518,.T.); -#126514 = VERTEX_POINT('',#126515); -#126515 = CARTESIAN_POINT('',(11.,6.85,-0.208196358798)); -#126516 = VERTEX_POINT('',#126517); -#126517 = CARTESIAN_POINT('',(11.,6.65,-0.208196358798)); -#126518 = SURFACE_CURVE('',#126519,(#126523,#126535),.PCURVE_S1.); -#126519 = LINE('',#126520,#126521); -#126520 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#126521 = VECTOR('',#126522,1.); -#126522 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126523 = PCURVE('',#126524,#126529); -#126524 = PLANE('',#126525); -#126525 = AXIS2_PLACEMENT_3D('',#126526,#126527,#126528); -#126526 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#128877 = CARTESIAN_POINT('',(4.761821717947,-6.85)); +#128878 = CARTESIAN_POINT('',(4.761821717947,-6.65)); +#128879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128880 = ORIENTED_EDGE('',*,*,#128881,.T.); +#128881 = EDGE_CURVE('',#128855,#128799,#128882,.T.); +#128882 = SURFACE_CURVE('',#128883,(#128887,#128894),.PCURVE_S1.); +#128883 = LINE('',#128884,#128885); +#128884 = CARTESIAN_POINT('',(10.74341632541,6.85,-0.308197125857)); +#128885 = VECTOR('',#128886,1.); +#128886 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128887 = PCURVE('',#128807,#128888); +#128888 = DEFINITIONAL_REPRESENTATION('',(#128889),#128893); +#128889 = LINE('',#128890,#128891); +#128890 = CARTESIAN_POINT('',(3.552713678801E-015,6.85)); +#128891 = VECTOR('',#128892,1.); +#128892 = DIRECTION('',(1.,0.E+000)); +#128893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128894 = PCURVE('',#95816,#128895); +#128895 = DEFINITIONAL_REPRESENTATION('',(#128896),#128900); +#128896 = LINE('',#128897,#128898); +#128897 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#128898 = VECTOR('',#128899,1.); +#128899 = DIRECTION('',(0.E+000,1.)); +#128900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128901 = ADVANCED_FACE('',(#128902),#128916,.F.); +#128902 = FACE_BOUND('',#128903,.T.); +#128903 = EDGE_LOOP('',(#128904,#128934,#128957,#128984)); +#128904 = ORIENTED_EDGE('',*,*,#128905,.F.); +#128905 = EDGE_CURVE('',#128906,#128908,#128910,.T.); +#128906 = VERTEX_POINT('',#128907); +#128907 = CARTESIAN_POINT('',(11.,6.85,-0.208196358798)); +#128908 = VERTEX_POINT('',#128909); +#128909 = CARTESIAN_POINT('',(11.,6.65,-0.208196358798)); +#128910 = SURFACE_CURVE('',#128911,(#128915,#128927),.PCURVE_S1.); +#128911 = LINE('',#128912,#128913); +#128912 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#128913 = VECTOR('',#128914,1.); +#128914 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128915 = PCURVE('',#128916,#128921); +#128916 = PLANE('',#128917); +#128917 = AXIS2_PLACEMENT_3D('',#128918,#128919,#128920); +#128918 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#126527 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126528 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#126529 = DEFINITIONAL_REPRESENTATION('',(#126530),#126534); -#126530 = LINE('',#126531,#126532); -#126531 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#126532 = VECTOR('',#126533,1.); -#126533 = DIRECTION('',(4.440892098501E-016,-1.)); -#126534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126535 = PCURVE('',#126427,#126536); -#126536 = DEFINITIONAL_REPRESENTATION('',(#126537),#126541); -#126537 = LINE('',#126538,#126539); -#126538 = CARTESIAN_POINT('',(-6.75,5.000038352949E-002)); -#126539 = VECTOR('',#126540,1.); -#126540 = DIRECTION('',(-1.,0.E+000)); -#126541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126542 = ORIENTED_EDGE('',*,*,#126543,.F.); -#126543 = EDGE_CURVE('',#126544,#126514,#126546,.T.); -#126544 = VERTEX_POINT('',#126545); -#126545 = CARTESIAN_POINT('',(10.740726081328,6.85,-0.208196358798)); -#126546 = SURFACE_CURVE('',#126547,(#126551,#126558),.PCURVE_S1.); -#126547 = LINE('',#126548,#126549); -#126548 = CARTESIAN_POINT('',(10.740726081328,6.85,-0.208196358798)); -#126549 = VECTOR('',#126550,1.); -#126550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#126551 = PCURVE('',#126524,#126552); -#126552 = DEFINITIONAL_REPRESENTATION('',(#126553),#126557); -#126553 = LINE('',#126554,#126555); -#126554 = CARTESIAN_POINT('',(-3.552713678801E-015,6.85)); -#126555 = VECTOR('',#126556,1.); -#126556 = DIRECTION('',(-1.,0.E+000)); -#126557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126558 = PCURVE('',#93424,#126559); -#126559 = DEFINITIONAL_REPRESENTATION('',(#126560),#126564); -#126560 = LINE('',#126561,#126562); -#126561 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#126562 = VECTOR('',#126563,1.); -#126563 = DIRECTION('',(0.E+000,1.)); -#126564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126565 = ORIENTED_EDGE('',*,*,#126566,.F.); -#126566 = EDGE_CURVE('',#126567,#126544,#126569,.T.); -#126567 = VERTEX_POINT('',#126568); -#126568 = CARTESIAN_POINT('',(10.740726081328,6.65,-0.208196358798)); -#126569 = SURFACE_CURVE('',#126570,(#126574,#126581),.PCURVE_S1.); -#126570 = LINE('',#126571,#126572); -#126571 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#128919 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#128920 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#128921 = DEFINITIONAL_REPRESENTATION('',(#128922),#128926); +#128922 = LINE('',#128923,#128924); +#128923 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#128924 = VECTOR('',#128925,1.); +#128925 = DIRECTION('',(4.440892098501E-016,-1.)); +#128926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128927 = PCURVE('',#128819,#128928); +#128928 = DEFINITIONAL_REPRESENTATION('',(#128929),#128933); +#128929 = LINE('',#128930,#128931); +#128930 = CARTESIAN_POINT('',(-6.75,5.000038352949E-002)); +#128931 = VECTOR('',#128932,1.); +#128932 = DIRECTION('',(-1.,0.E+000)); +#128933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128934 = ORIENTED_EDGE('',*,*,#128935,.F.); +#128935 = EDGE_CURVE('',#128936,#128906,#128938,.T.); +#128936 = VERTEX_POINT('',#128937); +#128937 = CARTESIAN_POINT('',(10.740726081328,6.85,-0.208196358798)); +#128938 = SURFACE_CURVE('',#128939,(#128943,#128950),.PCURVE_S1.); +#128939 = LINE('',#128940,#128941); +#128940 = CARTESIAN_POINT('',(10.740726081328,6.85,-0.208196358798)); +#128941 = VECTOR('',#128942,1.); +#128942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128943 = PCURVE('',#128916,#128944); +#128944 = DEFINITIONAL_REPRESENTATION('',(#128945),#128949); +#128945 = LINE('',#128946,#128947); +#128946 = CARTESIAN_POINT('',(-3.552713678801E-015,6.85)); +#128947 = VECTOR('',#128948,1.); +#128948 = DIRECTION('',(-1.,0.E+000)); +#128949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128950 = PCURVE('',#95816,#128951); +#128951 = DEFINITIONAL_REPRESENTATION('',(#128952),#128956); +#128952 = LINE('',#128953,#128954); +#128953 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#128954 = VECTOR('',#128955,1.); +#128955 = DIRECTION('',(0.E+000,1.)); +#128956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128957 = ORIENTED_EDGE('',*,*,#128958,.F.); +#128958 = EDGE_CURVE('',#128959,#128936,#128961,.T.); +#128959 = VERTEX_POINT('',#128960); +#128960 = CARTESIAN_POINT('',(10.740726081328,6.65,-0.208196358798)); +#128961 = SURFACE_CURVE('',#128962,(#128966,#128973),.PCURVE_S1.); +#128962 = LINE('',#128963,#128964); +#128963 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#126572 = VECTOR('',#126573,1.); -#126573 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126574 = PCURVE('',#126524,#126575); -#126575 = DEFINITIONAL_REPRESENTATION('',(#126576),#126580); -#126576 = LINE('',#126577,#126578); -#126577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126578 = VECTOR('',#126579,1.); -#126579 = DIRECTION('',(-4.440892098501E-016,1.)); -#126580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126581 = PCURVE('',#126582,#126587); -#126582 = CYLINDRICAL_SURFACE('',#126583,0.208574704164); -#126583 = AXIS2_PLACEMENT_3D('',#126584,#126585,#126586); -#126584 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#128964 = VECTOR('',#128965,1.); +#128965 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#128966 = PCURVE('',#128916,#128967); +#128967 = DEFINITIONAL_REPRESENTATION('',(#128968),#128972); +#128968 = LINE('',#128969,#128970); +#128969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#128970 = VECTOR('',#128971,1.); +#128971 = DIRECTION('',(-4.440892098501E-016,1.)); +#128972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128973 = PCURVE('',#128974,#128979); +#128974 = CYLINDRICAL_SURFACE('',#128975,0.208574704164); +#128975 = AXIS2_PLACEMENT_3D('',#128976,#128977,#128978); +#128976 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#126585 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126586 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126587 = DEFINITIONAL_REPRESENTATION('',(#126588),#126591); -#126588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126589,#126590), +#128977 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#128978 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#128979 = DEFINITIONAL_REPRESENTATION('',(#128980),#128983); +#128980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128981,#128982), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#126589 = CARTESIAN_POINT('',(4.772630242227,-6.65)); -#126590 = CARTESIAN_POINT('',(4.772630242227,-6.85)); -#126591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126592 = ORIENTED_EDGE('',*,*,#126593,.T.); -#126593 = EDGE_CURVE('',#126567,#126516,#126594,.T.); -#126594 = SURFACE_CURVE('',#126595,(#126599,#126606),.PCURVE_S1.); -#126595 = LINE('',#126596,#126597); -#126596 = CARTESIAN_POINT('',(10.740726081328,6.65,-0.208196358798)); -#126597 = VECTOR('',#126598,1.); -#126598 = DIRECTION('',(1.,0.E+000,0.E+000)); -#126599 = PCURVE('',#126524,#126600); -#126600 = DEFINITIONAL_REPRESENTATION('',(#126601),#126605); -#126601 = LINE('',#126602,#126603); -#126602 = CARTESIAN_POINT('',(-3.552713678801E-015,6.65)); -#126603 = VECTOR('',#126604,1.); -#126604 = DIRECTION('',(-1.,0.E+000)); -#126605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126606 = PCURVE('',#93480,#126607); -#126607 = DEFINITIONAL_REPRESENTATION('',(#126608),#126612); -#126608 = LINE('',#126609,#126610); -#126609 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#126610 = VECTOR('',#126611,1.); -#126611 = DIRECTION('',(0.E+000,1.)); -#126612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126613 = ADVANCED_FACE('',(#126614),#126478,.T.); -#126614 = FACE_BOUND('',#126615,.T.); -#126615 = EDGE_LOOP('',(#126616,#126643,#126644,#126667)); -#126616 = ORIENTED_EDGE('',*,*,#126617,.T.); -#126617 = EDGE_CURVE('',#126618,#126463,#126620,.T.); -#126618 = VERTEX_POINT('',#126619); -#126619 = CARTESIAN_POINT('',(10.419594812019,6.85,0.E+000)); -#126620 = SURFACE_CURVE('',#126621,(#126626,#126632),.PCURVE_S1.); -#126621 = CIRCLE('',#126622,0.308574064194); -#126622 = AXIS2_PLACEMENT_3D('',#126623,#126624,#126625); -#126623 = CARTESIAN_POINT('',(10.728168876214,6.85,2.640924866458E-017) - ); -#126624 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126625 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126626 = PCURVE('',#126478,#126627); -#126627 = DEFINITIONAL_REPRESENTATION('',(#126628),#126631); -#126628 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126629,#126630), +#128981 = CARTESIAN_POINT('',(4.772630242227,-6.65)); +#128982 = CARTESIAN_POINT('',(4.772630242227,-6.85)); +#128983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128984 = ORIENTED_EDGE('',*,*,#128985,.T.); +#128985 = EDGE_CURVE('',#128959,#128908,#128986,.T.); +#128986 = SURFACE_CURVE('',#128987,(#128991,#128998),.PCURVE_S1.); +#128987 = LINE('',#128988,#128989); +#128988 = CARTESIAN_POINT('',(10.740726081328,6.65,-0.208196358798)); +#128989 = VECTOR('',#128990,1.); +#128990 = DIRECTION('',(1.,0.E+000,0.E+000)); +#128991 = PCURVE('',#128916,#128992); +#128992 = DEFINITIONAL_REPRESENTATION('',(#128993),#128997); +#128993 = LINE('',#128994,#128995); +#128994 = CARTESIAN_POINT('',(-3.552713678801E-015,6.65)); +#128995 = VECTOR('',#128996,1.); +#128996 = DIRECTION('',(-1.,0.E+000)); +#128997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#128998 = PCURVE('',#95872,#128999); +#128999 = DEFINITIONAL_REPRESENTATION('',(#129000),#129004); +#129000 = LINE('',#129001,#129002); +#129001 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#129002 = VECTOR('',#129003,1.); +#129003 = DIRECTION('',(0.E+000,1.)); +#129004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129005 = ADVANCED_FACE('',(#129006),#128870,.T.); +#129006 = FACE_BOUND('',#129007,.T.); +#129007 = EDGE_LOOP('',(#129008,#129035,#129036,#129059)); +#129008 = ORIENTED_EDGE('',*,*,#129009,.T.); +#129009 = EDGE_CURVE('',#129010,#128855,#129012,.T.); +#129010 = VERTEX_POINT('',#129011); +#129011 = CARTESIAN_POINT('',(10.419594812019,6.85,0.E+000)); +#129012 = SURFACE_CURVE('',#129013,(#129018,#129024),.PCURVE_S1.); +#129013 = CIRCLE('',#129014,0.308574064194); +#129014 = AXIS2_PLACEMENT_3D('',#129015,#129016,#129017); +#129015 = CARTESIAN_POINT('',(10.728168876214,6.85,2.640924866458E-017) + ); +#129016 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129017 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129018 = PCURVE('',#128870,#129019); +#129019 = DEFINITIONAL_REPRESENTATION('',(#129020),#129023); +#129020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129021,#129022), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#126629 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#126630 = CARTESIAN_POINT('',(4.761821717947,-6.85)); -#126631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129021 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#129022 = CARTESIAN_POINT('',(4.761821717947,-6.85)); +#129023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126632 = PCURVE('',#93424,#126633); -#126633 = DEFINITIONAL_REPRESENTATION('',(#126634),#126642); -#126634 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126635,#126636,#126637, - #126638,#126639,#126640,#126641),.UNSPECIFIED.,.T.,.F.) +#129024 = PCURVE('',#95816,#129025); +#129025 = DEFINITIONAL_REPRESENTATION('',(#129026),#129034); +#129026 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129027,#129028,#129029, + #129030,#129031,#129032,#129033),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#126635 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#126636 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#126637 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#126638 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#126639 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#126640 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#126641 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#126642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126643 = ORIENTED_EDGE('',*,*,#126462,.T.); -#126644 = ORIENTED_EDGE('',*,*,#126645,.F.); -#126645 = EDGE_CURVE('',#126646,#126440,#126648,.T.); -#126646 = VERTEX_POINT('',#126647); -#126647 = CARTESIAN_POINT('',(10.419594812019,6.65,0.E+000)); -#126648 = SURFACE_CURVE('',#126649,(#126654,#126660),.PCURVE_S1.); -#126649 = CIRCLE('',#126650,0.308574064194); -#126650 = AXIS2_PLACEMENT_3D('',#126651,#126652,#126653); -#126651 = CARTESIAN_POINT('',(10.728168876214,6.65,2.640924866458E-017) - ); -#126652 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126653 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126654 = PCURVE('',#126478,#126655); -#126655 = DEFINITIONAL_REPRESENTATION('',(#126656),#126659); -#126656 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126657,#126658), +#129027 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#129028 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#129029 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#129030 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#129031 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#129032 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#129033 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#129034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129035 = ORIENTED_EDGE('',*,*,#128854,.T.); +#129036 = ORIENTED_EDGE('',*,*,#129037,.F.); +#129037 = EDGE_CURVE('',#129038,#128832,#129040,.T.); +#129038 = VERTEX_POINT('',#129039); +#129039 = CARTESIAN_POINT('',(10.419594812019,6.65,0.E+000)); +#129040 = SURFACE_CURVE('',#129041,(#129046,#129052),.PCURVE_S1.); +#129041 = CIRCLE('',#129042,0.308574064194); +#129042 = AXIS2_PLACEMENT_3D('',#129043,#129044,#129045); +#129043 = CARTESIAN_POINT('',(10.728168876214,6.65,2.640924866458E-017) + ); +#129044 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129045 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129046 = PCURVE('',#128870,#129047); +#129047 = DEFINITIONAL_REPRESENTATION('',(#129048),#129051); +#129048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129049,#129050), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#126657 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#126658 = CARTESIAN_POINT('',(4.761821717947,-6.65)); -#126659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129049 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#129050 = CARTESIAN_POINT('',(4.761821717947,-6.65)); +#129051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126660 = PCURVE('',#93480,#126661); -#126661 = DEFINITIONAL_REPRESENTATION('',(#126662),#126666); -#126662 = CIRCLE('',#126663,0.308574064194); -#126663 = AXIS2_PLACEMENT_2D('',#126664,#126665); -#126664 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#126665 = DIRECTION('',(0.E+000,1.)); -#126666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129052 = PCURVE('',#95872,#129053); +#129053 = DEFINITIONAL_REPRESENTATION('',(#129054),#129058); +#129054 = CIRCLE('',#129055,0.308574064194); +#129055 = AXIS2_PLACEMENT_2D('',#129056,#129057); +#129056 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#129057 = DIRECTION('',(0.E+000,1.)); +#129058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126667 = ORIENTED_EDGE('',*,*,#126668,.T.); -#126668 = EDGE_CURVE('',#126646,#126618,#126669,.T.); -#126669 = SURFACE_CURVE('',#126670,(#126674,#126680),.PCURVE_S1.); -#126670 = LINE('',#126671,#126672); -#126671 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#129059 = ORIENTED_EDGE('',*,*,#129060,.T.); +#129060 = EDGE_CURVE('',#129038,#129010,#129061,.T.); +#129061 = SURFACE_CURVE('',#129062,(#129066,#129072),.PCURVE_S1.); +#129062 = LINE('',#129063,#129064); +#129063 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#126672 = VECTOR('',#126673,1.); -#126673 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126674 = PCURVE('',#126478,#126675); -#126675 = DEFINITIONAL_REPRESENTATION('',(#126676),#126679); -#126676 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126677,#126678), +#129064 = VECTOR('',#129065,1.); +#129065 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129066 = PCURVE('',#128870,#129067); +#129067 = DEFINITIONAL_REPRESENTATION('',(#129068),#129071); +#129068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129069,#129070), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#126677 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#126678 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#126679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129069 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#129070 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#129071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126680 = PCURVE('',#126681,#126686); -#126681 = PLANE('',#126682); -#126682 = AXIS2_PLACEMENT_3D('',#126683,#126684,#126685); -#126683 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#129072 = PCURVE('',#129073,#129078); +#129073 = PLANE('',#129074); +#129074 = AXIS2_PLACEMENT_3D('',#129075,#129076,#129077); +#129075 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#126684 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126685 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126686 = DEFINITIONAL_REPRESENTATION('',(#126687),#126691); -#126687 = LINE('',#126688,#126689); -#126688 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#126689 = VECTOR('',#126690,1.); -#126690 = DIRECTION('',(-1.,0.E+000)); -#126691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126692 = ADVANCED_FACE('',(#126693),#126582,.F.); -#126693 = FACE_BOUND('',#126694,.F.); -#126694 = EDGE_LOOP('',(#126695,#126718,#126745,#126770)); -#126695 = ORIENTED_EDGE('',*,*,#126696,.F.); -#126696 = EDGE_CURVE('',#126697,#126567,#126699,.T.); -#126697 = VERTEX_POINT('',#126698); -#126698 = CARTESIAN_POINT('',(10.51959417205,6.65,0.E+000)); -#126699 = SURFACE_CURVE('',#126700,(#126705,#126711),.PCURVE_S1.); -#126700 = CIRCLE('',#126701,0.208574704164); -#126701 = AXIS2_PLACEMENT_3D('',#126702,#126703,#126704); -#126702 = CARTESIAN_POINT('',(10.728168876214,6.65,2.640924866458E-017) - ); -#126703 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126704 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126705 = PCURVE('',#126582,#126706); -#126706 = DEFINITIONAL_REPRESENTATION('',(#126707),#126710); -#126707 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126708,#126709), +#129076 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129077 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129078 = DEFINITIONAL_REPRESENTATION('',(#129079),#129083); +#129079 = LINE('',#129080,#129081); +#129080 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#129081 = VECTOR('',#129082,1.); +#129082 = DIRECTION('',(-1.,0.E+000)); +#129083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129084 = ADVANCED_FACE('',(#129085),#128974,.F.); +#129085 = FACE_BOUND('',#129086,.F.); +#129086 = EDGE_LOOP('',(#129087,#129110,#129137,#129162)); +#129087 = ORIENTED_EDGE('',*,*,#129088,.F.); +#129088 = EDGE_CURVE('',#129089,#128959,#129091,.T.); +#129089 = VERTEX_POINT('',#129090); +#129090 = CARTESIAN_POINT('',(10.51959417205,6.65,0.E+000)); +#129091 = SURFACE_CURVE('',#129092,(#129097,#129103),.PCURVE_S1.); +#129092 = CIRCLE('',#129093,0.208574704164); +#129093 = AXIS2_PLACEMENT_3D('',#129094,#129095,#129096); +#129094 = CARTESIAN_POINT('',(10.728168876214,6.65,2.640924866458E-017) + ); +#129095 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129096 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129097 = PCURVE('',#128974,#129098); +#129098 = DEFINITIONAL_REPRESENTATION('',(#129099),#129102); +#129099 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129100,#129101), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#126708 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#126709 = CARTESIAN_POINT('',(4.772630242227,-6.65)); -#126710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129100 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#129101 = CARTESIAN_POINT('',(4.772630242227,-6.65)); +#129102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126711 = PCURVE('',#93480,#126712); -#126712 = DEFINITIONAL_REPRESENTATION('',(#126713),#126717); -#126713 = CIRCLE('',#126714,0.208574704164); -#126714 = AXIS2_PLACEMENT_2D('',#126715,#126716); -#126715 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#126716 = DIRECTION('',(0.E+000,1.)); -#126717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129103 = PCURVE('',#95872,#129104); +#129104 = DEFINITIONAL_REPRESENTATION('',(#129105),#129109); +#129105 = CIRCLE('',#129106,0.208574704164); +#129106 = AXIS2_PLACEMENT_2D('',#129107,#129108); +#129107 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#129108 = DIRECTION('',(0.E+000,1.)); +#129109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126718 = ORIENTED_EDGE('',*,*,#126719,.F.); -#126719 = EDGE_CURVE('',#126720,#126697,#126722,.T.); -#126720 = VERTEX_POINT('',#126721); -#126721 = CARTESIAN_POINT('',(10.51959417205,6.85,0.E+000)); -#126722 = SURFACE_CURVE('',#126723,(#126727,#126733),.PCURVE_S1.); -#126723 = LINE('',#126724,#126725); -#126724 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129110 = ORIENTED_EDGE('',*,*,#129111,.F.); +#129111 = EDGE_CURVE('',#129112,#129089,#129114,.T.); +#129112 = VERTEX_POINT('',#129113); +#129113 = CARTESIAN_POINT('',(10.51959417205,6.85,0.E+000)); +#129114 = SURFACE_CURVE('',#129115,(#129119,#129125),.PCURVE_S1.); +#129115 = LINE('',#129116,#129117); +#129116 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#126725 = VECTOR('',#126726,1.); -#126726 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126727 = PCURVE('',#126582,#126728); -#126728 = DEFINITIONAL_REPRESENTATION('',(#126729),#126732); -#126729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126730,#126731), +#129117 = VECTOR('',#129118,1.); +#129118 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129119 = PCURVE('',#128974,#129120); +#129120 = DEFINITIONAL_REPRESENTATION('',(#129121),#129124); +#129121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129122,#129123), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#126730 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#126731 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#126732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129122 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#129123 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#129124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126733 = PCURVE('',#126734,#126739); -#126734 = PLANE('',#126735); -#126735 = AXIS2_PLACEMENT_3D('',#126736,#126737,#126738); -#126736 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129125 = PCURVE('',#129126,#129131); +#129126 = PLANE('',#129127); +#129127 = AXIS2_PLACEMENT_3D('',#129128,#129129,#129130); +#129128 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#126737 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126738 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126739 = DEFINITIONAL_REPRESENTATION('',(#126740),#126744); -#126740 = LINE('',#126741,#126742); -#126741 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#126742 = VECTOR('',#126743,1.); -#126743 = DIRECTION('',(-1.,0.E+000)); -#126744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126745 = ORIENTED_EDGE('',*,*,#126746,.T.); -#126746 = EDGE_CURVE('',#126720,#126544,#126747,.T.); -#126747 = SURFACE_CURVE('',#126748,(#126753,#126759),.PCURVE_S1.); -#126748 = CIRCLE('',#126749,0.208574704164); -#126749 = AXIS2_PLACEMENT_3D('',#126750,#126751,#126752); -#126750 = CARTESIAN_POINT('',(10.728168876214,6.85,2.640924866458E-017) - ); -#126751 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126752 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#126753 = PCURVE('',#126582,#126754); -#126754 = DEFINITIONAL_REPRESENTATION('',(#126755),#126758); -#126755 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126756,#126757), +#129129 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129130 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129131 = DEFINITIONAL_REPRESENTATION('',(#129132),#129136); +#129132 = LINE('',#129133,#129134); +#129133 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#129134 = VECTOR('',#129135,1.); +#129135 = DIRECTION('',(-1.,0.E+000)); +#129136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129137 = ORIENTED_EDGE('',*,*,#129138,.T.); +#129138 = EDGE_CURVE('',#129112,#128936,#129139,.T.); +#129139 = SURFACE_CURVE('',#129140,(#129145,#129151),.PCURVE_S1.); +#129140 = CIRCLE('',#129141,0.208574704164); +#129141 = AXIS2_PLACEMENT_3D('',#129142,#129143,#129144); +#129142 = CARTESIAN_POINT('',(10.728168876214,6.85,2.640924866458E-017) + ); +#129143 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129144 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129145 = PCURVE('',#128974,#129146); +#129146 = DEFINITIONAL_REPRESENTATION('',(#129147),#129150); +#129147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129148,#129149), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#126756 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#126757 = CARTESIAN_POINT('',(4.772630242227,-6.85)); -#126758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129148 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#129149 = CARTESIAN_POINT('',(4.772630242227,-6.85)); +#129150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126759 = PCURVE('',#93424,#126760); -#126760 = DEFINITIONAL_REPRESENTATION('',(#126761),#126769); -#126761 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126762,#126763,#126764, - #126765,#126766,#126767,#126768),.UNSPECIFIED.,.T.,.F.) +#129151 = PCURVE('',#95816,#129152); +#129152 = DEFINITIONAL_REPRESENTATION('',(#129153),#129161); +#129153 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129154,#129155,#129156, + #129157,#129158,#129159,#129160),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#126762 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#126763 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#126764 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#126765 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#126766 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#126767 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#126768 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#126769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126770 = ORIENTED_EDGE('',*,*,#126566,.F.); -#126771 = ADVANCED_FACE('',(#126772),#126734,.T.); -#126772 = FACE_BOUND('',#126773,.T.); -#126773 = EDGE_LOOP('',(#126774,#126803,#126824,#126825)); -#126774 = ORIENTED_EDGE('',*,*,#126775,.T.); -#126775 = EDGE_CURVE('',#126776,#126778,#126780,.T.); -#126776 = VERTEX_POINT('',#126777); -#126777 = CARTESIAN_POINT('',(10.51959417205,6.85,0.530776333563)); -#126778 = VERTEX_POINT('',#126779); -#126779 = CARTESIAN_POINT('',(10.51959417205,6.65,0.530776333563)); -#126780 = SURFACE_CURVE('',#126781,(#126785,#126792),.PCURVE_S1.); -#126781 = LINE('',#126782,#126783); -#126782 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129154 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#129155 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#129156 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#129157 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#129158 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#129159 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#129160 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#129161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129162 = ORIENTED_EDGE('',*,*,#128958,.F.); +#129163 = ADVANCED_FACE('',(#129164),#129126,.T.); +#129164 = FACE_BOUND('',#129165,.T.); +#129165 = EDGE_LOOP('',(#129166,#129195,#129216,#129217)); +#129166 = ORIENTED_EDGE('',*,*,#129167,.T.); +#129167 = EDGE_CURVE('',#129168,#129170,#129172,.T.); +#129168 = VERTEX_POINT('',#129169); +#129169 = CARTESIAN_POINT('',(10.51959417205,6.85,0.530776333563)); +#129170 = VERTEX_POINT('',#129171); +#129171 = CARTESIAN_POINT('',(10.51959417205,6.65,0.530776333563)); +#129172 = SURFACE_CURVE('',#129173,(#129177,#129184),.PCURVE_S1.); +#129173 = LINE('',#129174,#129175); +#129174 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#126783 = VECTOR('',#126784,1.); -#126784 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126785 = PCURVE('',#126734,#126786); -#126786 = DEFINITIONAL_REPRESENTATION('',(#126787),#126791); -#126787 = LINE('',#126788,#126789); -#126788 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126789 = VECTOR('',#126790,1.); -#126790 = DIRECTION('',(-1.,0.E+000)); -#126791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126792 = PCURVE('',#126793,#126798); -#126793 = CYLINDRICAL_SURFACE('',#126794,0.2192697516); -#126794 = AXIS2_PLACEMENT_3D('',#126795,#126796,#126797); -#126795 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#129175 = VECTOR('',#129176,1.); +#129176 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129177 = PCURVE('',#129126,#129178); +#129178 = DEFINITIONAL_REPRESENTATION('',(#129179),#129183); +#129179 = LINE('',#129180,#129181); +#129180 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129181 = VECTOR('',#129182,1.); +#129182 = DIRECTION('',(-1.,0.E+000)); +#129183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129184 = PCURVE('',#129185,#129190); +#129185 = CYLINDRICAL_SURFACE('',#129186,0.2192697516); +#129186 = AXIS2_PLACEMENT_3D('',#129187,#129188,#129189); +#129187 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#126796 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126797 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126798 = DEFINITIONAL_REPRESENTATION('',(#126799),#126802); -#126799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126800,#126801), +#129188 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129189 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129190 = DEFINITIONAL_REPRESENTATION('',(#129191),#129194); +#129191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129192,#129193), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#126800 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#126801 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#126802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126803 = ORIENTED_EDGE('',*,*,#126804,.T.); -#126804 = EDGE_CURVE('',#126778,#126697,#126805,.T.); -#126805 = SURFACE_CURVE('',#126806,(#126810,#126817),.PCURVE_S1.); -#126806 = LINE('',#126807,#126808); -#126807 = CARTESIAN_POINT('',(10.51959417205,6.65,0.530776333563)); -#126808 = VECTOR('',#126809,1.); -#126809 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126810 = PCURVE('',#126734,#126811); -#126811 = DEFINITIONAL_REPRESENTATION('',(#126812),#126816); -#126812 = LINE('',#126813,#126814); -#126813 = CARTESIAN_POINT('',(6.65,0.E+000)); -#126814 = VECTOR('',#126815,1.); -#126815 = DIRECTION('',(0.E+000,-1.)); -#126816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126817 = PCURVE('',#93480,#126818); -#126818 = DEFINITIONAL_REPRESENTATION('',(#126819),#126823); -#126819 = LINE('',#126820,#126821); -#126820 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#126821 = VECTOR('',#126822,1.); -#126822 = DIRECTION('',(1.,0.E+000)); -#126823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126824 = ORIENTED_EDGE('',*,*,#126719,.F.); -#126825 = ORIENTED_EDGE('',*,*,#126826,.F.); -#126826 = EDGE_CURVE('',#126776,#126720,#126827,.T.); -#126827 = SURFACE_CURVE('',#126828,(#126832,#126839),.PCURVE_S1.); -#126828 = LINE('',#126829,#126830); -#126829 = CARTESIAN_POINT('',(10.51959417205,6.85,0.530776333563)); -#126830 = VECTOR('',#126831,1.); -#126831 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126832 = PCURVE('',#126734,#126833); -#126833 = DEFINITIONAL_REPRESENTATION('',(#126834),#126838); -#126834 = LINE('',#126835,#126836); -#126835 = CARTESIAN_POINT('',(6.85,0.E+000)); -#126836 = VECTOR('',#126837,1.); -#126837 = DIRECTION('',(0.E+000,-1.)); -#126838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126839 = PCURVE('',#93424,#126840); -#126840 = DEFINITIONAL_REPRESENTATION('',(#126841),#126845); -#126841 = LINE('',#126842,#126843); -#126842 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#126843 = VECTOR('',#126844,1.); -#126844 = DIRECTION('',(-1.,0.E+000)); -#126845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126846 = ADVANCED_FACE('',(#126847),#126681,.T.); -#126847 = FACE_BOUND('',#126848,.T.); -#126848 = EDGE_LOOP('',(#126849,#126878,#126899,#126900)); -#126849 = ORIENTED_EDGE('',*,*,#126850,.T.); -#126850 = EDGE_CURVE('',#126851,#126853,#126855,.T.); -#126851 = VERTEX_POINT('',#126852); -#126852 = CARTESIAN_POINT('',(10.419594812019,6.65,0.530776333563)); -#126853 = VERTEX_POINT('',#126854); -#126854 = CARTESIAN_POINT('',(10.419594812019,6.85,0.530776333563)); -#126855 = SURFACE_CURVE('',#126856,(#126860,#126867),.PCURVE_S1.); -#126856 = LINE('',#126857,#126858); -#126857 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, - 0.530776333563)); -#126858 = VECTOR('',#126859,1.); -#126859 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126860 = PCURVE('',#126681,#126861); -#126861 = DEFINITIONAL_REPRESENTATION('',(#126862),#126866); -#126862 = LINE('',#126863,#126864); -#126863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#126864 = VECTOR('',#126865,1.); -#126865 = DIRECTION('',(-1.,0.E+000)); -#126866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129192 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#129193 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#129194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129195 = ORIENTED_EDGE('',*,*,#129196,.T.); +#129196 = EDGE_CURVE('',#129170,#129089,#129197,.T.); +#129197 = SURFACE_CURVE('',#129198,(#129202,#129209),.PCURVE_S1.); +#129198 = LINE('',#129199,#129200); +#129199 = CARTESIAN_POINT('',(10.51959417205,6.65,0.530776333563)); +#129200 = VECTOR('',#129201,1.); +#129201 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#129202 = PCURVE('',#129126,#129203); +#129203 = DEFINITIONAL_REPRESENTATION('',(#129204),#129208); +#129204 = LINE('',#129205,#129206); +#129205 = CARTESIAN_POINT('',(6.65,0.E+000)); +#129206 = VECTOR('',#129207,1.); +#129207 = DIRECTION('',(0.E+000,-1.)); +#129208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129209 = PCURVE('',#95872,#129210); +#129210 = DEFINITIONAL_REPRESENTATION('',(#129211),#129215); +#129211 = LINE('',#129212,#129213); +#129212 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#129213 = VECTOR('',#129214,1.); +#129214 = DIRECTION('',(1.,0.E+000)); +#129215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129216 = ORIENTED_EDGE('',*,*,#129111,.F.); +#129217 = ORIENTED_EDGE('',*,*,#129218,.F.); +#129218 = EDGE_CURVE('',#129168,#129112,#129219,.T.); +#129219 = SURFACE_CURVE('',#129220,(#129224,#129231),.PCURVE_S1.); +#129220 = LINE('',#129221,#129222); +#129221 = CARTESIAN_POINT('',(10.51959417205,6.85,0.530776333563)); +#129222 = VECTOR('',#129223,1.); +#129223 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#129224 = PCURVE('',#129126,#129225); +#129225 = DEFINITIONAL_REPRESENTATION('',(#129226),#129230); +#129226 = LINE('',#129227,#129228); +#129227 = CARTESIAN_POINT('',(6.85,0.E+000)); +#129228 = VECTOR('',#129229,1.); +#129229 = DIRECTION('',(0.E+000,-1.)); +#129230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129231 = PCURVE('',#95816,#129232); +#129232 = DEFINITIONAL_REPRESENTATION('',(#129233),#129237); +#129233 = LINE('',#129234,#129235); +#129234 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#129235 = VECTOR('',#129236,1.); +#129236 = DIRECTION('',(-1.,0.E+000)); +#129237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126867 = PCURVE('',#126868,#126873); -#126868 = CYLINDRICAL_SURFACE('',#126869,0.119270391569); -#126869 = AXIS2_PLACEMENT_3D('',#126870,#126871,#126872); -#126870 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#129238 = ADVANCED_FACE('',(#129239),#129073,.T.); +#129239 = FACE_BOUND('',#129240,.T.); +#129240 = EDGE_LOOP('',(#129241,#129270,#129291,#129292)); +#129241 = ORIENTED_EDGE('',*,*,#129242,.T.); +#129242 = EDGE_CURVE('',#129243,#129245,#129247,.T.); +#129243 = VERTEX_POINT('',#129244); +#129244 = CARTESIAN_POINT('',(10.419594812019,6.65,0.530776333563)); +#129245 = VERTEX_POINT('',#129246); +#129246 = CARTESIAN_POINT('',(10.419594812019,6.85,0.530776333563)); +#129247 = SURFACE_CURVE('',#129248,(#129252,#129259),.PCURVE_S1.); +#129248 = LINE('',#129249,#129250); +#129249 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, + 0.530776333563)); +#129250 = VECTOR('',#129251,1.); +#129251 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129252 = PCURVE('',#129073,#129253); +#129253 = DEFINITIONAL_REPRESENTATION('',(#129254),#129258); +#129254 = LINE('',#129255,#129256); +#129255 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129256 = VECTOR('',#129257,1.); +#129257 = DIRECTION('',(-1.,0.E+000)); +#129258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129259 = PCURVE('',#129260,#129265); +#129260 = CYLINDRICAL_SURFACE('',#129261,0.119270391569); +#129261 = AXIS2_PLACEMENT_3D('',#129262,#129263,#129264); +#129262 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#126871 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126872 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126873 = DEFINITIONAL_REPRESENTATION('',(#126874),#126877); -#126874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126875,#126876), +#129263 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129264 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129265 = DEFINITIONAL_REPRESENTATION('',(#129266),#129269); +#129266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129267,#129268), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#126875 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#126876 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#126877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126878 = ORIENTED_EDGE('',*,*,#126879,.T.); -#126879 = EDGE_CURVE('',#126853,#126618,#126880,.T.); -#126880 = SURFACE_CURVE('',#126881,(#126885,#126892),.PCURVE_S1.); -#126881 = LINE('',#126882,#126883); -#126882 = CARTESIAN_POINT('',(10.419594812019,6.85,0.530776333563)); -#126883 = VECTOR('',#126884,1.); -#126884 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126885 = PCURVE('',#126681,#126886); -#126886 = DEFINITIONAL_REPRESENTATION('',(#126887),#126891); -#126887 = LINE('',#126888,#126889); -#126888 = CARTESIAN_POINT('',(-6.85,0.E+000)); -#126889 = VECTOR('',#126890,1.); -#126890 = DIRECTION('',(0.E+000,-1.)); -#126891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126892 = PCURVE('',#93424,#126893); -#126893 = DEFINITIONAL_REPRESENTATION('',(#126894),#126898); -#126894 = LINE('',#126895,#126896); -#126895 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#126896 = VECTOR('',#126897,1.); -#126897 = DIRECTION('',(-1.,0.E+000)); -#126898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126899 = ORIENTED_EDGE('',*,*,#126668,.F.); -#126900 = ORIENTED_EDGE('',*,*,#126901,.F.); -#126901 = EDGE_CURVE('',#126851,#126646,#126902,.T.); -#126902 = SURFACE_CURVE('',#126903,(#126907,#126914),.PCURVE_S1.); -#126903 = LINE('',#126904,#126905); -#126904 = CARTESIAN_POINT('',(10.419594812019,6.65,0.530776333563)); -#126905 = VECTOR('',#126906,1.); -#126906 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#126907 = PCURVE('',#126681,#126908); -#126908 = DEFINITIONAL_REPRESENTATION('',(#126909),#126913); -#126909 = LINE('',#126910,#126911); -#126910 = CARTESIAN_POINT('',(-6.65,0.E+000)); -#126911 = VECTOR('',#126912,1.); -#126912 = DIRECTION('',(0.E+000,-1.)); -#126913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126914 = PCURVE('',#93480,#126915); -#126915 = DEFINITIONAL_REPRESENTATION('',(#126916),#126920); -#126916 = LINE('',#126917,#126918); -#126917 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#126918 = VECTOR('',#126919,1.); -#126919 = DIRECTION('',(1.,0.E+000)); -#126920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126921 = ADVANCED_FACE('',(#126922),#126868,.F.); -#126922 = FACE_BOUND('',#126923,.F.); -#126923 = EDGE_LOOP('',(#126924,#126925,#126948,#126970)); -#126924 = ORIENTED_EDGE('',*,*,#126850,.T.); -#126925 = ORIENTED_EDGE('',*,*,#126926,.F.); -#126926 = EDGE_CURVE('',#126927,#126853,#126929,.T.); -#126927 = VERTEX_POINT('',#126928); -#126928 = CARTESIAN_POINT('',(10.303662633502,6.85,0.65)); -#126929 = SURFACE_CURVE('',#126930,(#126935,#126941),.PCURVE_S1.); -#126930 = CIRCLE('',#126931,0.119270391569); -#126931 = AXIS2_PLACEMENT_3D('',#126932,#126933,#126934); -#126932 = CARTESIAN_POINT('',(10.30032442045,6.85,0.530776333563)); -#126933 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126934 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126935 = PCURVE('',#126868,#126936); -#126936 = DEFINITIONAL_REPRESENTATION('',(#126937),#126940); -#126937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126938,#126939), +#129267 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#129268 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#129269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129270 = ORIENTED_EDGE('',*,*,#129271,.T.); +#129271 = EDGE_CURVE('',#129245,#129010,#129272,.T.); +#129272 = SURFACE_CURVE('',#129273,(#129277,#129284),.PCURVE_S1.); +#129273 = LINE('',#129274,#129275); +#129274 = CARTESIAN_POINT('',(10.419594812019,6.85,0.530776333563)); +#129275 = VECTOR('',#129276,1.); +#129276 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#129277 = PCURVE('',#129073,#129278); +#129278 = DEFINITIONAL_REPRESENTATION('',(#129279),#129283); +#129279 = LINE('',#129280,#129281); +#129280 = CARTESIAN_POINT('',(-6.85,0.E+000)); +#129281 = VECTOR('',#129282,1.); +#129282 = DIRECTION('',(0.E+000,-1.)); +#129283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129284 = PCURVE('',#95816,#129285); +#129285 = DEFINITIONAL_REPRESENTATION('',(#129286),#129290); +#129286 = LINE('',#129287,#129288); +#129287 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#129288 = VECTOR('',#129289,1.); +#129289 = DIRECTION('',(-1.,0.E+000)); +#129290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129291 = ORIENTED_EDGE('',*,*,#129060,.F.); +#129292 = ORIENTED_EDGE('',*,*,#129293,.F.); +#129293 = EDGE_CURVE('',#129243,#129038,#129294,.T.); +#129294 = SURFACE_CURVE('',#129295,(#129299,#129306),.PCURVE_S1.); +#129295 = LINE('',#129296,#129297); +#129296 = CARTESIAN_POINT('',(10.419594812019,6.65,0.530776333563)); +#129297 = VECTOR('',#129298,1.); +#129298 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#129299 = PCURVE('',#129073,#129300); +#129300 = DEFINITIONAL_REPRESENTATION('',(#129301),#129305); +#129301 = LINE('',#129302,#129303); +#129302 = CARTESIAN_POINT('',(-6.65,0.E+000)); +#129303 = VECTOR('',#129304,1.); +#129304 = DIRECTION('',(0.E+000,-1.)); +#129305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129306 = PCURVE('',#95872,#129307); +#129307 = DEFINITIONAL_REPRESENTATION('',(#129308),#129312); +#129308 = LINE('',#129309,#129310); +#129309 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#129310 = VECTOR('',#129311,1.); +#129311 = DIRECTION('',(1.,0.E+000)); +#129312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129313 = ADVANCED_FACE('',(#129314),#129260,.F.); +#129314 = FACE_BOUND('',#129315,.F.); +#129315 = EDGE_LOOP('',(#129316,#129317,#129340,#129362)); +#129316 = ORIENTED_EDGE('',*,*,#129242,.T.); +#129317 = ORIENTED_EDGE('',*,*,#129318,.F.); +#129318 = EDGE_CURVE('',#129319,#129245,#129321,.T.); +#129319 = VERTEX_POINT('',#129320); +#129320 = CARTESIAN_POINT('',(10.303662633502,6.85,0.65)); +#129321 = SURFACE_CURVE('',#129322,(#129327,#129333),.PCURVE_S1.); +#129322 = CIRCLE('',#129323,0.119270391569); +#129323 = AXIS2_PLACEMENT_3D('',#129324,#129325,#129326); +#129324 = CARTESIAN_POINT('',(10.30032442045,6.85,0.530776333563)); +#129325 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129326 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129327 = PCURVE('',#129260,#129328); +#129328 = DEFINITIONAL_REPRESENTATION('',(#129329),#129332); +#129329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129330,#129331), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#126938 = CARTESIAN_POINT('',(1.598788597134,6.85)); -#126939 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#126940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126941 = PCURVE('',#93424,#126942); -#126942 = DEFINITIONAL_REPRESENTATION('',(#126943),#126947); -#126943 = CIRCLE('',#126944,0.119270391569); -#126944 = AXIS2_PLACEMENT_2D('',#126945,#126946); -#126945 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#126946 = DIRECTION('',(0.E+000,-1.)); -#126947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126948 = ORIENTED_EDGE('',*,*,#126949,.T.); -#126949 = EDGE_CURVE('',#126927,#126950,#126952,.T.); -#126950 = VERTEX_POINT('',#126951); -#126951 = CARTESIAN_POINT('',(10.303662633502,6.65,0.65)); -#126952 = SURFACE_CURVE('',#126953,(#126957,#126963),.PCURVE_S1.); -#126953 = LINE('',#126954,#126955); -#126954 = CARTESIAN_POINT('',(10.303662633502,6.65,0.65)); -#126955 = VECTOR('',#126956,1.); -#126956 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#126957 = PCURVE('',#126868,#126958); -#126958 = DEFINITIONAL_REPRESENTATION('',(#126959),#126962); -#126959 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126960,#126961), +#129330 = CARTESIAN_POINT('',(1.598788597134,6.85)); +#129331 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#129332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129333 = PCURVE('',#95816,#129334); +#129334 = DEFINITIONAL_REPRESENTATION('',(#129335),#129339); +#129335 = CIRCLE('',#129336,0.119270391569); +#129336 = AXIS2_PLACEMENT_2D('',#129337,#129338); +#129337 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#129338 = DIRECTION('',(0.E+000,-1.)); +#129339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129340 = ORIENTED_EDGE('',*,*,#129341,.T.); +#129341 = EDGE_CURVE('',#129319,#129342,#129344,.T.); +#129342 = VERTEX_POINT('',#129343); +#129343 = CARTESIAN_POINT('',(10.303662633502,6.65,0.65)); +#129344 = SURFACE_CURVE('',#129345,(#129349,#129355),.PCURVE_S1.); +#129345 = LINE('',#129346,#129347); +#129346 = CARTESIAN_POINT('',(10.303662633502,6.65,0.65)); +#129347 = VECTOR('',#129348,1.); +#129348 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129349 = PCURVE('',#129260,#129350); +#129350 = DEFINITIONAL_REPRESENTATION('',(#129351),#129354); +#129351 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129352,#129353), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#126960 = CARTESIAN_POINT('',(1.598788597134,6.85)); -#126961 = CARTESIAN_POINT('',(1.598788597134,6.65)); -#126962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126963 = PCURVE('',#93452,#126964); -#126964 = DEFINITIONAL_REPRESENTATION('',(#126965),#126969); -#126965 = LINE('',#126966,#126967); -#126966 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#126967 = VECTOR('',#126968,1.); -#126968 = DIRECTION('',(4.440892098501E-016,-1.)); -#126969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126970 = ORIENTED_EDGE('',*,*,#126971,.T.); -#126971 = EDGE_CURVE('',#126950,#126851,#126972,.T.); -#126972 = SURFACE_CURVE('',#126973,(#126978,#126984),.PCURVE_S1.); -#126973 = CIRCLE('',#126974,0.119270391569); -#126974 = AXIS2_PLACEMENT_3D('',#126975,#126976,#126977); -#126975 = CARTESIAN_POINT('',(10.30032442045,6.65,0.530776333563)); -#126976 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#126977 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#126978 = PCURVE('',#126868,#126979); -#126979 = DEFINITIONAL_REPRESENTATION('',(#126980),#126983); -#126980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#126981,#126982), +#129352 = CARTESIAN_POINT('',(1.598788597134,6.85)); +#129353 = CARTESIAN_POINT('',(1.598788597134,6.65)); +#129354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129355 = PCURVE('',#95844,#129356); +#129356 = DEFINITIONAL_REPRESENTATION('',(#129357),#129361); +#129357 = LINE('',#129358,#129359); +#129358 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#129359 = VECTOR('',#129360,1.); +#129360 = DIRECTION('',(4.440892098501E-016,-1.)); +#129361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129362 = ORIENTED_EDGE('',*,*,#129363,.T.); +#129363 = EDGE_CURVE('',#129342,#129243,#129364,.T.); +#129364 = SURFACE_CURVE('',#129365,(#129370,#129376),.PCURVE_S1.); +#129365 = CIRCLE('',#129366,0.119270391569); +#129366 = AXIS2_PLACEMENT_3D('',#129367,#129368,#129369); +#129367 = CARTESIAN_POINT('',(10.30032442045,6.65,0.530776333563)); +#129368 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129369 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129370 = PCURVE('',#129260,#129371); +#129371 = DEFINITIONAL_REPRESENTATION('',(#129372),#129375); +#129372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129373,#129374), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#126981 = CARTESIAN_POINT('',(1.598788597134,6.65)); -#126982 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#126983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129373 = CARTESIAN_POINT('',(1.598788597134,6.65)); +#129374 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#129375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#126984 = PCURVE('',#93480,#126985); -#126985 = DEFINITIONAL_REPRESENTATION('',(#126986),#126994); -#126986 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#126987,#126988,#126989, - #126990,#126991,#126992,#126993),.UNSPECIFIED.,.T.,.F.) +#129376 = PCURVE('',#95872,#129377); +#129377 = DEFINITIONAL_REPRESENTATION('',(#129378),#129386); +#129378 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129379,#129380,#129381, + #129382,#129383,#129384,#129385),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#126987 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#126988 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#126989 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#126990 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#126991 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#126992 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#126993 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#126994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#126995 = ADVANCED_FACE('',(#126996),#126793,.T.); -#126996 = FACE_BOUND('',#126997,.T.); -#126997 = EDGE_LOOP('',(#126998,#126999,#127022,#127044)); -#126998 = ORIENTED_EDGE('',*,*,#126775,.F.); -#126999 = ORIENTED_EDGE('',*,*,#127000,.F.); -#127000 = EDGE_CURVE('',#127001,#126776,#127003,.T.); -#127001 = VERTEX_POINT('',#127002); -#127002 = CARTESIAN_POINT('',(10.304819755875,6.85,0.75)); -#127003 = SURFACE_CURVE('',#127004,(#127009,#127015),.PCURVE_S1.); -#127004 = CIRCLE('',#127005,0.2192697516); -#127005 = AXIS2_PLACEMENT_3D('',#127006,#127007,#127008); -#127006 = CARTESIAN_POINT('',(10.30032442045,6.85,0.530776333563)); -#127007 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127008 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127009 = PCURVE('',#126793,#127010); -#127010 = DEFINITIONAL_REPRESENTATION('',(#127011),#127014); -#127011 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127012,#127013), +#129379 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#129380 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#129381 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#129382 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#129383 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#129384 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#129385 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#129386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129387 = ADVANCED_FACE('',(#129388),#129185,.T.); +#129388 = FACE_BOUND('',#129389,.T.); +#129389 = EDGE_LOOP('',(#129390,#129391,#129414,#129436)); +#129390 = ORIENTED_EDGE('',*,*,#129167,.F.); +#129391 = ORIENTED_EDGE('',*,*,#129392,.F.); +#129392 = EDGE_CURVE('',#129393,#129168,#129395,.T.); +#129393 = VERTEX_POINT('',#129394); +#129394 = CARTESIAN_POINT('',(10.304819755875,6.85,0.75)); +#129395 = SURFACE_CURVE('',#129396,(#129401,#129407),.PCURVE_S1.); +#129396 = CIRCLE('',#129397,0.2192697516); +#129397 = AXIS2_PLACEMENT_3D('',#129398,#129399,#129400); +#129398 = CARTESIAN_POINT('',(10.30032442045,6.85,0.530776333563)); +#129399 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129400 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129401 = PCURVE('',#129185,#129402); +#129402 = DEFINITIONAL_REPRESENTATION('',(#129403),#129406); +#129403 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129404,#129405), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#127012 = CARTESIAN_POINT('',(1.591299156552,6.85)); -#127013 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#127014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127015 = PCURVE('',#93424,#127016); -#127016 = DEFINITIONAL_REPRESENTATION('',(#127017),#127021); -#127017 = CIRCLE('',#127018,0.2192697516); -#127018 = AXIS2_PLACEMENT_2D('',#127019,#127020); -#127019 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#127020 = DIRECTION('',(0.E+000,-1.)); -#127021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127022 = ORIENTED_EDGE('',*,*,#127023,.F.); -#127023 = EDGE_CURVE('',#127024,#127001,#127026,.T.); -#127024 = VERTEX_POINT('',#127025); -#127025 = CARTESIAN_POINT('',(10.304819755875,6.65,0.75)); -#127026 = SURFACE_CURVE('',#127027,(#127031,#127037),.PCURVE_S1.); -#127027 = LINE('',#127028,#127029); -#127028 = CARTESIAN_POINT('',(10.304819755875,6.65,0.75)); -#127029 = VECTOR('',#127030,1.); -#127030 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127031 = PCURVE('',#126793,#127032); -#127032 = DEFINITIONAL_REPRESENTATION('',(#127033),#127036); -#127033 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127034,#127035), +#129404 = CARTESIAN_POINT('',(1.591299156552,6.85)); +#129405 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#129406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129407 = PCURVE('',#95816,#129408); +#129408 = DEFINITIONAL_REPRESENTATION('',(#129409),#129413); +#129409 = CIRCLE('',#129410,0.2192697516); +#129410 = AXIS2_PLACEMENT_2D('',#129411,#129412); +#129411 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#129412 = DIRECTION('',(0.E+000,-1.)); +#129413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129414 = ORIENTED_EDGE('',*,*,#129415,.F.); +#129415 = EDGE_CURVE('',#129416,#129393,#129418,.T.); +#129416 = VERTEX_POINT('',#129417); +#129417 = CARTESIAN_POINT('',(10.304819755875,6.65,0.75)); +#129418 = SURFACE_CURVE('',#129419,(#129423,#129429),.PCURVE_S1.); +#129419 = LINE('',#129420,#129421); +#129420 = CARTESIAN_POINT('',(10.304819755875,6.65,0.75)); +#129421 = VECTOR('',#129422,1.); +#129422 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129423 = PCURVE('',#129185,#129424); +#129424 = DEFINITIONAL_REPRESENTATION('',(#129425),#129428); +#129425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129426,#129427), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#127034 = CARTESIAN_POINT('',(1.591299156552,6.65)); -#127035 = CARTESIAN_POINT('',(1.591299156552,6.85)); -#127036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127037 = PCURVE('',#93506,#127038); -#127038 = DEFINITIONAL_REPRESENTATION('',(#127039),#127043); -#127039 = LINE('',#127040,#127041); -#127040 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#127041 = VECTOR('',#127042,1.); -#127042 = DIRECTION('',(4.440892098501E-016,1.)); -#127043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127044 = ORIENTED_EDGE('',*,*,#127045,.T.); -#127045 = EDGE_CURVE('',#127024,#126778,#127046,.T.); -#127046 = SURFACE_CURVE('',#127047,(#127052,#127058),.PCURVE_S1.); -#127047 = CIRCLE('',#127048,0.2192697516); -#127048 = AXIS2_PLACEMENT_3D('',#127049,#127050,#127051); -#127049 = CARTESIAN_POINT('',(10.30032442045,6.65,0.530776333563)); -#127050 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127051 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127052 = PCURVE('',#126793,#127053); -#127053 = DEFINITIONAL_REPRESENTATION('',(#127054),#127057); -#127054 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127055,#127056), +#129426 = CARTESIAN_POINT('',(1.591299156552,6.65)); +#129427 = CARTESIAN_POINT('',(1.591299156552,6.85)); +#129428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129429 = PCURVE('',#95898,#129430); +#129430 = DEFINITIONAL_REPRESENTATION('',(#129431),#129435); +#129431 = LINE('',#129432,#129433); +#129432 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#129433 = VECTOR('',#129434,1.); +#129434 = DIRECTION('',(4.440892098501E-016,1.)); +#129435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129436 = ORIENTED_EDGE('',*,*,#129437,.T.); +#129437 = EDGE_CURVE('',#129416,#129170,#129438,.T.); +#129438 = SURFACE_CURVE('',#129439,(#129444,#129450),.PCURVE_S1.); +#129439 = CIRCLE('',#129440,0.2192697516); +#129440 = AXIS2_PLACEMENT_3D('',#129441,#129442,#129443); +#129441 = CARTESIAN_POINT('',(10.30032442045,6.65,0.530776333563)); +#129442 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129443 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129444 = PCURVE('',#129185,#129445); +#129445 = DEFINITIONAL_REPRESENTATION('',(#129446),#129449); +#129446 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129447,#129448), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#127055 = CARTESIAN_POINT('',(1.591299156552,6.65)); -#127056 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#127057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129447 = CARTESIAN_POINT('',(1.591299156552,6.65)); +#129448 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#129449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127058 = PCURVE('',#93480,#127059); -#127059 = DEFINITIONAL_REPRESENTATION('',(#127060),#127068); -#127060 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127061,#127062,#127063, - #127064,#127065,#127066,#127067),.UNSPECIFIED.,.T.,.F.) +#129450 = PCURVE('',#95872,#129451); +#129451 = DEFINITIONAL_REPRESENTATION('',(#129452),#129460); +#129452 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129453,#129454,#129455, + #129456,#129457,#129458,#129459),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#127061 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#127062 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#127063 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#127064 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#127065 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#127066 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#127067 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#127068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127069 = ADVANCED_FACE('',(#127070),#93452,.T.); -#127070 = FACE_BOUND('',#127071,.T.); -#127071 = EDGE_LOOP('',(#127072,#127093,#127094,#127115)); -#127072 = ORIENTED_EDGE('',*,*,#127073,.F.); -#127073 = EDGE_CURVE('',#126927,#93409,#127074,.T.); -#127074 = SURFACE_CURVE('',#127075,(#127079,#127086),.PCURVE_S1.); -#127075 = LINE('',#127076,#127077); -#127076 = CARTESIAN_POINT('',(10.527847992439,6.85,0.65)); -#127077 = VECTOR('',#127078,1.); -#127078 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127079 = PCURVE('',#93452,#127080); -#127080 = DEFINITIONAL_REPRESENTATION('',(#127081),#127085); -#127081 = LINE('',#127082,#127083); -#127082 = CARTESIAN_POINT('',(0.E+000,0.2)); -#127083 = VECTOR('',#127084,1.); -#127084 = DIRECTION('',(1.,-3.00059940766E-063)); -#127085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127086 = PCURVE('',#93424,#127087); -#127087 = DEFINITIONAL_REPRESENTATION('',(#127088),#127092); -#127088 = LINE('',#127089,#127090); -#127089 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127090 = VECTOR('',#127091,1.); -#127091 = DIRECTION('',(3.563627120235E-016,-1.)); -#127092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127093 = ORIENTED_EDGE('',*,*,#126949,.T.); -#127094 = ORIENTED_EDGE('',*,*,#127095,.T.); -#127095 = EDGE_CURVE('',#126950,#93437,#127096,.T.); -#127096 = SURFACE_CURVE('',#127097,(#127101,#127108),.PCURVE_S1.); -#127097 = LINE('',#127098,#127099); -#127098 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); -#127099 = VECTOR('',#127100,1.); -#127100 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127101 = PCURVE('',#93452,#127102); -#127102 = DEFINITIONAL_REPRESENTATION('',(#127103),#127107); -#127103 = LINE('',#127104,#127105); -#127104 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127105 = VECTOR('',#127106,1.); -#127106 = DIRECTION('',(1.,-3.00059940766E-063)); -#127107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127108 = PCURVE('',#93480,#127109); -#127109 = DEFINITIONAL_REPRESENTATION('',(#127110),#127114); -#127110 = LINE('',#127111,#127112); -#127111 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127112 = VECTOR('',#127113,1.); -#127113 = DIRECTION('',(-3.563627120235E-016,-1.)); -#127114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127115 = ORIENTED_EDGE('',*,*,#93436,.F.); -#127116 = ADVANCED_FACE('',(#127117),#93424,.T.); -#127117 = FACE_BOUND('',#127118,.T.); -#127118 = EDGE_LOOP('',(#127119,#127140,#127141,#127142,#127143,#127144, - #127165,#127166,#127167,#127168,#127169,#127170)); -#127119 = ORIENTED_EDGE('',*,*,#127120,.F.); -#127120 = EDGE_CURVE('',#127001,#93407,#127121,.T.); -#127121 = SURFACE_CURVE('',#127122,(#127126,#127133),.PCURVE_S1.); -#127122 = LINE('',#127123,#127124); -#127123 = CARTESIAN_POINT('',(10.527847992439,6.85,0.75)); -#127124 = VECTOR('',#127125,1.); -#127125 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127126 = PCURVE('',#93424,#127127); -#127127 = DEFINITIONAL_REPRESENTATION('',(#127128),#127132); -#127128 = LINE('',#127129,#127130); -#127129 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#127130 = VECTOR('',#127131,1.); -#127131 = DIRECTION('',(3.563627120235E-016,-1.)); -#127132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127133 = PCURVE('',#93506,#127134); -#127134 = DEFINITIONAL_REPRESENTATION('',(#127135),#127139); -#127135 = LINE('',#127136,#127137); -#127136 = CARTESIAN_POINT('',(0.E+000,0.2)); -#127137 = VECTOR('',#127138,1.); -#127138 = DIRECTION('',(-1.,-3.00059940766E-063)); -#127139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127140 = ORIENTED_EDGE('',*,*,#127000,.T.); -#127141 = ORIENTED_EDGE('',*,*,#126826,.T.); -#127142 = ORIENTED_EDGE('',*,*,#126746,.T.); -#127143 = ORIENTED_EDGE('',*,*,#126543,.T.); -#127144 = ORIENTED_EDGE('',*,*,#127145,.F.); -#127145 = EDGE_CURVE('',#126407,#126514,#127146,.T.); -#127146 = SURFACE_CURVE('',#127147,(#127151,#127158),.PCURVE_S1.); -#127147 = LINE('',#127148,#127149); -#127148 = CARTESIAN_POINT('',(11.,6.85,1.159810404338E-002)); -#127149 = VECTOR('',#127150,1.); -#127150 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#127151 = PCURVE('',#93424,#127152); -#127152 = DEFINITIONAL_REPRESENTATION('',(#127153),#127157); -#127153 = LINE('',#127154,#127155); -#127154 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#127155 = VECTOR('',#127156,1.); -#127156 = DIRECTION('',(1.,2.101748079665E-016)); -#127157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127158 = PCURVE('',#126427,#127159); -#127159 = DEFINITIONAL_REPRESENTATION('',(#127160),#127164); -#127160 = LINE('',#127161,#127162); -#127161 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#127162 = VECTOR('',#127163,1.); -#127163 = DIRECTION('',(1.194699204908E-017,1.)); -#127164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127165 = ORIENTED_EDGE('',*,*,#126489,.F.); -#127166 = ORIENTED_EDGE('',*,*,#126617,.F.); -#127167 = ORIENTED_EDGE('',*,*,#126879,.F.); -#127168 = ORIENTED_EDGE('',*,*,#126926,.F.); -#127169 = ORIENTED_EDGE('',*,*,#127073,.T.); -#127170 = ORIENTED_EDGE('',*,*,#93406,.F.); -#127171 = ADVANCED_FACE('',(#127172),#93506,.T.); -#127172 = FACE_BOUND('',#127173,.T.); -#127173 = EDGE_LOOP('',(#127174,#127195,#127196,#127197)); -#127174 = ORIENTED_EDGE('',*,*,#127175,.F.); -#127175 = EDGE_CURVE('',#127024,#93465,#127176,.T.); -#127176 = SURFACE_CURVE('',#127177,(#127181,#127188),.PCURVE_S1.); -#127177 = LINE('',#127178,#127179); -#127178 = CARTESIAN_POINT('',(10.527847992439,6.65,0.75)); -#127179 = VECTOR('',#127180,1.); -#127180 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127181 = PCURVE('',#93506,#127182); -#127182 = DEFINITIONAL_REPRESENTATION('',(#127183),#127187); -#127183 = LINE('',#127184,#127185); -#127184 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127185 = VECTOR('',#127186,1.); -#127186 = DIRECTION('',(-1.,-3.00059940766E-063)); -#127187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127188 = PCURVE('',#93480,#127189); -#127189 = DEFINITIONAL_REPRESENTATION('',(#127190),#127194); -#127190 = LINE('',#127191,#127192); -#127191 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#127192 = VECTOR('',#127193,1.); -#127193 = DIRECTION('',(-3.563627120235E-016,-1.)); -#127194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127195 = ORIENTED_EDGE('',*,*,#127023,.T.); -#127196 = ORIENTED_EDGE('',*,*,#127120,.T.); -#127197 = ORIENTED_EDGE('',*,*,#93492,.F.); -#127198 = ADVANCED_FACE('',(#127199),#93480,.T.); -#127199 = FACE_BOUND('',#127200,.T.); -#127200 = EDGE_LOOP('',(#127201,#127202,#127203,#127204,#127205,#127206, - #127227,#127228,#127229,#127230,#127231,#127232)); -#127201 = ORIENTED_EDGE('',*,*,#127095,.F.); -#127202 = ORIENTED_EDGE('',*,*,#126971,.T.); -#127203 = ORIENTED_EDGE('',*,*,#126901,.T.); -#127204 = ORIENTED_EDGE('',*,*,#126645,.T.); -#127205 = ORIENTED_EDGE('',*,*,#126439,.T.); -#127206 = ORIENTED_EDGE('',*,*,#127207,.F.); -#127207 = EDGE_CURVE('',#126516,#126405,#127208,.T.); -#127208 = SURFACE_CURVE('',#127209,(#127213,#127220),.PCURVE_S1.); -#127209 = LINE('',#127210,#127211); -#127210 = CARTESIAN_POINT('',(11.,6.65,1.159810404338E-002)); -#127211 = VECTOR('',#127212,1.); -#127212 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#127213 = PCURVE('',#93480,#127214); -#127214 = DEFINITIONAL_REPRESENTATION('',(#127215),#127219); -#127215 = LINE('',#127216,#127217); -#127216 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#127217 = VECTOR('',#127218,1.); -#127218 = DIRECTION('',(1.,-2.101748079665E-016)); -#127219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127220 = PCURVE('',#126427,#127221); -#127221 = DEFINITIONAL_REPRESENTATION('',(#127222),#127226); -#127222 = LINE('',#127223,#127224); -#127223 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#127224 = VECTOR('',#127225,1.); -#127225 = DIRECTION('',(-1.194699204908E-017,-1.)); -#127226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127227 = ORIENTED_EDGE('',*,*,#126593,.F.); -#127228 = ORIENTED_EDGE('',*,*,#126696,.F.); -#127229 = ORIENTED_EDGE('',*,*,#126804,.F.); -#127230 = ORIENTED_EDGE('',*,*,#127045,.F.); -#127231 = ORIENTED_EDGE('',*,*,#127175,.T.); -#127232 = ORIENTED_EDGE('',*,*,#93464,.F.); -#127233 = ADVANCED_FACE('',(#127234),#126427,.T.); -#127234 = FACE_BOUND('',#127235,.T.); -#127235 = EDGE_LOOP('',(#127236,#127237,#127238,#127239)); -#127236 = ORIENTED_EDGE('',*,*,#127145,.T.); -#127237 = ORIENTED_EDGE('',*,*,#126513,.T.); -#127238 = ORIENTED_EDGE('',*,*,#127207,.T.); -#127239 = ORIENTED_EDGE('',*,*,#126404,.T.); -#127240 = ADVANCED_FACE('',(#127241),#127255,.F.); -#127241 = FACE_BOUND('',#127242,.T.); -#127242 = EDGE_LOOP('',(#127243,#127278,#127301,#127328)); -#127243 = ORIENTED_EDGE('',*,*,#127244,.F.); -#127244 = EDGE_CURVE('',#127245,#127247,#127249,.T.); -#127245 = VERTEX_POINT('',#127246); -#127246 = CARTESIAN_POINT('',(11.,6.15,-0.308197125857)); -#127247 = VERTEX_POINT('',#127248); -#127248 = CARTESIAN_POINT('',(11.,6.35,-0.308197125857)); -#127249 = SURFACE_CURVE('',#127250,(#127254,#127266),.PCURVE_S1.); -#127250 = LINE('',#127251,#127252); -#127251 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#127252 = VECTOR('',#127253,1.); -#127253 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127254 = PCURVE('',#127255,#127260); -#127255 = PLANE('',#127256); -#127256 = AXIS2_PLACEMENT_3D('',#127257,#127258,#127259); -#127257 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#129453 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#129454 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#129455 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#129456 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#129457 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#129458 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#129459 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#129460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129461 = ADVANCED_FACE('',(#129462),#95844,.T.); +#129462 = FACE_BOUND('',#129463,.T.); +#129463 = EDGE_LOOP('',(#129464,#129485,#129486,#129507)); +#129464 = ORIENTED_EDGE('',*,*,#129465,.F.); +#129465 = EDGE_CURVE('',#129319,#95801,#129466,.T.); +#129466 = SURFACE_CURVE('',#129467,(#129471,#129478),.PCURVE_S1.); +#129467 = LINE('',#129468,#129469); +#129468 = CARTESIAN_POINT('',(10.527847992439,6.85,0.65)); +#129469 = VECTOR('',#129470,1.); +#129470 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#129471 = PCURVE('',#95844,#129472); +#129472 = DEFINITIONAL_REPRESENTATION('',(#129473),#129477); +#129473 = LINE('',#129474,#129475); +#129474 = CARTESIAN_POINT('',(0.E+000,0.2)); +#129475 = VECTOR('',#129476,1.); +#129476 = DIRECTION('',(1.,-3.00059940766E-063)); +#129477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129478 = PCURVE('',#95816,#129479); +#129479 = DEFINITIONAL_REPRESENTATION('',(#129480),#129484); +#129480 = LINE('',#129481,#129482); +#129481 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129482 = VECTOR('',#129483,1.); +#129483 = DIRECTION('',(3.563627120235E-016,-1.)); +#129484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129485 = ORIENTED_EDGE('',*,*,#129341,.T.); +#129486 = ORIENTED_EDGE('',*,*,#129487,.T.); +#129487 = EDGE_CURVE('',#129342,#95829,#129488,.T.); +#129488 = SURFACE_CURVE('',#129489,(#129493,#129500),.PCURVE_S1.); +#129489 = LINE('',#129490,#129491); +#129490 = CARTESIAN_POINT('',(10.527847992439,6.65,0.65)); +#129491 = VECTOR('',#129492,1.); +#129492 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#129493 = PCURVE('',#95844,#129494); +#129494 = DEFINITIONAL_REPRESENTATION('',(#129495),#129499); +#129495 = LINE('',#129496,#129497); +#129496 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129497 = VECTOR('',#129498,1.); +#129498 = DIRECTION('',(1.,-3.00059940766E-063)); +#129499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129500 = PCURVE('',#95872,#129501); +#129501 = DEFINITIONAL_REPRESENTATION('',(#129502),#129506); +#129502 = LINE('',#129503,#129504); +#129503 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129504 = VECTOR('',#129505,1.); +#129505 = DIRECTION('',(-3.563627120235E-016,-1.)); +#129506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129507 = ORIENTED_EDGE('',*,*,#95828,.F.); +#129508 = ADVANCED_FACE('',(#129509),#95816,.T.); +#129509 = FACE_BOUND('',#129510,.T.); +#129510 = EDGE_LOOP('',(#129511,#129532,#129533,#129534,#129535,#129536, + #129557,#129558,#129559,#129560,#129561,#129562)); +#129511 = ORIENTED_EDGE('',*,*,#129512,.F.); +#129512 = EDGE_CURVE('',#129393,#95799,#129513,.T.); +#129513 = SURFACE_CURVE('',#129514,(#129518,#129525),.PCURVE_S1.); +#129514 = LINE('',#129515,#129516); +#129515 = CARTESIAN_POINT('',(10.527847992439,6.85,0.75)); +#129516 = VECTOR('',#129517,1.); +#129517 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#129518 = PCURVE('',#95816,#129519); +#129519 = DEFINITIONAL_REPRESENTATION('',(#129520),#129524); +#129520 = LINE('',#129521,#129522); +#129521 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#129522 = VECTOR('',#129523,1.); +#129523 = DIRECTION('',(3.563627120235E-016,-1.)); +#129524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129525 = PCURVE('',#95898,#129526); +#129526 = DEFINITIONAL_REPRESENTATION('',(#129527),#129531); +#129527 = LINE('',#129528,#129529); +#129528 = CARTESIAN_POINT('',(0.E+000,0.2)); +#129529 = VECTOR('',#129530,1.); +#129530 = DIRECTION('',(-1.,-3.00059940766E-063)); +#129531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129532 = ORIENTED_EDGE('',*,*,#129392,.T.); +#129533 = ORIENTED_EDGE('',*,*,#129218,.T.); +#129534 = ORIENTED_EDGE('',*,*,#129138,.T.); +#129535 = ORIENTED_EDGE('',*,*,#128935,.T.); +#129536 = ORIENTED_EDGE('',*,*,#129537,.F.); +#129537 = EDGE_CURVE('',#128799,#128906,#129538,.T.); +#129538 = SURFACE_CURVE('',#129539,(#129543,#129550),.PCURVE_S1.); +#129539 = LINE('',#129540,#129541); +#129540 = CARTESIAN_POINT('',(11.,6.85,1.159810404338E-002)); +#129541 = VECTOR('',#129542,1.); +#129542 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#129543 = PCURVE('',#95816,#129544); +#129544 = DEFINITIONAL_REPRESENTATION('',(#129545),#129549); +#129545 = LINE('',#129546,#129547); +#129546 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#129547 = VECTOR('',#129548,1.); +#129548 = DIRECTION('',(1.,2.101748079665E-016)); +#129549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129550 = PCURVE('',#128819,#129551); +#129551 = DEFINITIONAL_REPRESENTATION('',(#129552),#129556); +#129552 = LINE('',#129553,#129554); +#129553 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#129554 = VECTOR('',#129555,1.); +#129555 = DIRECTION('',(1.194699204908E-017,1.)); +#129556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129557 = ORIENTED_EDGE('',*,*,#128881,.F.); +#129558 = ORIENTED_EDGE('',*,*,#129009,.F.); +#129559 = ORIENTED_EDGE('',*,*,#129271,.F.); +#129560 = ORIENTED_EDGE('',*,*,#129318,.F.); +#129561 = ORIENTED_EDGE('',*,*,#129465,.T.); +#129562 = ORIENTED_EDGE('',*,*,#95798,.F.); +#129563 = ADVANCED_FACE('',(#129564),#95898,.T.); +#129564 = FACE_BOUND('',#129565,.T.); +#129565 = EDGE_LOOP('',(#129566,#129587,#129588,#129589)); +#129566 = ORIENTED_EDGE('',*,*,#129567,.F.); +#129567 = EDGE_CURVE('',#129416,#95857,#129568,.T.); +#129568 = SURFACE_CURVE('',#129569,(#129573,#129580),.PCURVE_S1.); +#129569 = LINE('',#129570,#129571); +#129570 = CARTESIAN_POINT('',(10.527847992439,6.65,0.75)); +#129571 = VECTOR('',#129572,1.); +#129572 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#129573 = PCURVE('',#95898,#129574); +#129574 = DEFINITIONAL_REPRESENTATION('',(#129575),#129579); +#129575 = LINE('',#129576,#129577); +#129576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129577 = VECTOR('',#129578,1.); +#129578 = DIRECTION('',(-1.,-3.00059940766E-063)); +#129579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129580 = PCURVE('',#95872,#129581); +#129581 = DEFINITIONAL_REPRESENTATION('',(#129582),#129586); +#129582 = LINE('',#129583,#129584); +#129583 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#129584 = VECTOR('',#129585,1.); +#129585 = DIRECTION('',(-3.563627120235E-016,-1.)); +#129586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129587 = ORIENTED_EDGE('',*,*,#129415,.T.); +#129588 = ORIENTED_EDGE('',*,*,#129512,.T.); +#129589 = ORIENTED_EDGE('',*,*,#95884,.F.); +#129590 = ADVANCED_FACE('',(#129591),#95872,.T.); +#129591 = FACE_BOUND('',#129592,.T.); +#129592 = EDGE_LOOP('',(#129593,#129594,#129595,#129596,#129597,#129598, + #129619,#129620,#129621,#129622,#129623,#129624)); +#129593 = ORIENTED_EDGE('',*,*,#129487,.F.); +#129594 = ORIENTED_EDGE('',*,*,#129363,.T.); +#129595 = ORIENTED_EDGE('',*,*,#129293,.T.); +#129596 = ORIENTED_EDGE('',*,*,#129037,.T.); +#129597 = ORIENTED_EDGE('',*,*,#128831,.T.); +#129598 = ORIENTED_EDGE('',*,*,#129599,.F.); +#129599 = EDGE_CURVE('',#128908,#128797,#129600,.T.); +#129600 = SURFACE_CURVE('',#129601,(#129605,#129612),.PCURVE_S1.); +#129601 = LINE('',#129602,#129603); +#129602 = CARTESIAN_POINT('',(11.,6.65,1.159810404338E-002)); +#129603 = VECTOR('',#129604,1.); +#129604 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#129605 = PCURVE('',#95872,#129606); +#129606 = DEFINITIONAL_REPRESENTATION('',(#129607),#129611); +#129607 = LINE('',#129608,#129609); +#129608 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#129609 = VECTOR('',#129610,1.); +#129610 = DIRECTION('',(1.,-2.101748079665E-016)); +#129611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129612 = PCURVE('',#128819,#129613); +#129613 = DEFINITIONAL_REPRESENTATION('',(#129614),#129618); +#129614 = LINE('',#129615,#129616); +#129615 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#129616 = VECTOR('',#129617,1.); +#129617 = DIRECTION('',(-1.194699204908E-017,-1.)); +#129618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129619 = ORIENTED_EDGE('',*,*,#128985,.F.); +#129620 = ORIENTED_EDGE('',*,*,#129088,.F.); +#129621 = ORIENTED_EDGE('',*,*,#129196,.F.); +#129622 = ORIENTED_EDGE('',*,*,#129437,.F.); +#129623 = ORIENTED_EDGE('',*,*,#129567,.T.); +#129624 = ORIENTED_EDGE('',*,*,#95856,.F.); +#129625 = ADVANCED_FACE('',(#129626),#128819,.T.); +#129626 = FACE_BOUND('',#129627,.T.); +#129627 = EDGE_LOOP('',(#129628,#129629,#129630,#129631)); +#129628 = ORIENTED_EDGE('',*,*,#129537,.T.); +#129629 = ORIENTED_EDGE('',*,*,#128905,.T.); +#129630 = ORIENTED_EDGE('',*,*,#129599,.T.); +#129631 = ORIENTED_EDGE('',*,*,#128796,.T.); +#129632 = ADVANCED_FACE('',(#129633),#129647,.F.); +#129633 = FACE_BOUND('',#129634,.T.); +#129634 = EDGE_LOOP('',(#129635,#129670,#129693,#129720)); +#129635 = ORIENTED_EDGE('',*,*,#129636,.F.); +#129636 = EDGE_CURVE('',#129637,#129639,#129641,.T.); +#129637 = VERTEX_POINT('',#129638); +#129638 = CARTESIAN_POINT('',(11.,6.15,-0.308197125857)); +#129639 = VERTEX_POINT('',#129640); +#129640 = CARTESIAN_POINT('',(11.,6.35,-0.308197125857)); +#129641 = SURFACE_CURVE('',#129642,(#129646,#129658),.PCURVE_S1.); +#129642 = LINE('',#129643,#129644); +#129643 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#129644 = VECTOR('',#129645,1.); +#129645 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129646 = PCURVE('',#129647,#129652); +#129647 = PLANE('',#129648); +#129648 = AXIS2_PLACEMENT_3D('',#129649,#129650,#129651); +#129649 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#127258 = DIRECTION('',(0.E+000,0.E+000,1.)); -#127259 = DIRECTION('',(1.,0.E+000,0.E+000)); -#127260 = DEFINITIONAL_REPRESENTATION('',(#127261),#127265); -#127261 = LINE('',#127262,#127263); -#127262 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#127263 = VECTOR('',#127264,1.); -#127264 = DIRECTION('',(4.440892098501E-016,1.)); -#127265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127266 = PCURVE('',#127267,#127272); -#127267 = PLANE('',#127268); -#127268 = AXIS2_PLACEMENT_3D('',#127269,#127270,#127271); -#127269 = CARTESIAN_POINT('',(11.,6.25,-0.258196742327)); -#127270 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#127271 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127272 = DEFINITIONAL_REPRESENTATION('',(#127273),#127277); -#127273 = LINE('',#127274,#127275); -#127274 = CARTESIAN_POINT('',(-6.25,-5.00003835295E-002)); -#127275 = VECTOR('',#127276,1.); -#127276 = DIRECTION('',(1.,0.E+000)); -#127277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127278 = ORIENTED_EDGE('',*,*,#127279,.F.); -#127279 = EDGE_CURVE('',#127280,#127245,#127282,.T.); -#127280 = VERTEX_POINT('',#127281); -#127281 = CARTESIAN_POINT('',(10.74341632541,6.15,-0.308197125857)); -#127282 = SURFACE_CURVE('',#127283,(#127287,#127294),.PCURVE_S1.); -#127283 = LINE('',#127284,#127285); -#127284 = CARTESIAN_POINT('',(10.74341632541,6.15,-0.308197125857)); -#127285 = VECTOR('',#127286,1.); -#127286 = DIRECTION('',(1.,0.E+000,0.E+000)); -#127287 = PCURVE('',#127255,#127288); -#127288 = DEFINITIONAL_REPRESENTATION('',(#127289),#127293); -#127289 = LINE('',#127290,#127291); -#127290 = CARTESIAN_POINT('',(3.552713678801E-015,6.15)); -#127291 = VECTOR('',#127292,1.); -#127292 = DIRECTION('',(1.,0.E+000)); -#127293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127294 = PCURVE('',#93366,#127295); -#127295 = DEFINITIONAL_REPRESENTATION('',(#127296),#127300); -#127296 = LINE('',#127297,#127298); -#127297 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#127298 = VECTOR('',#127299,1.); -#127299 = DIRECTION('',(0.E+000,1.)); -#127300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127301 = ORIENTED_EDGE('',*,*,#127302,.F.); -#127302 = EDGE_CURVE('',#127303,#127280,#127305,.T.); -#127303 = VERTEX_POINT('',#127304); -#127304 = CARTESIAN_POINT('',(10.74341632541,6.35,-0.308197125857)); -#127305 = SURFACE_CURVE('',#127306,(#127310,#127317),.PCURVE_S1.); -#127306 = LINE('',#127307,#127308); -#127307 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#129650 = DIRECTION('',(0.E+000,0.E+000,1.)); +#129651 = DIRECTION('',(1.,0.E+000,0.E+000)); +#129652 = DEFINITIONAL_REPRESENTATION('',(#129653),#129657); +#129653 = LINE('',#129654,#129655); +#129654 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#129655 = VECTOR('',#129656,1.); +#129656 = DIRECTION('',(4.440892098501E-016,1.)); +#129657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129658 = PCURVE('',#129659,#129664); +#129659 = PLANE('',#129660); +#129660 = AXIS2_PLACEMENT_3D('',#129661,#129662,#129663); +#129661 = CARTESIAN_POINT('',(11.,6.25,-0.258196742327)); +#129662 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#129663 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129664 = DEFINITIONAL_REPRESENTATION('',(#129665),#129669); +#129665 = LINE('',#129666,#129667); +#129666 = CARTESIAN_POINT('',(-6.25,-5.00003835295E-002)); +#129667 = VECTOR('',#129668,1.); +#129668 = DIRECTION('',(1.,0.E+000)); +#129669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129670 = ORIENTED_EDGE('',*,*,#129671,.F.); +#129671 = EDGE_CURVE('',#129672,#129637,#129674,.T.); +#129672 = VERTEX_POINT('',#129673); +#129673 = CARTESIAN_POINT('',(10.74341632541,6.15,-0.308197125857)); +#129674 = SURFACE_CURVE('',#129675,(#129679,#129686),.PCURVE_S1.); +#129675 = LINE('',#129676,#129677); +#129676 = CARTESIAN_POINT('',(10.74341632541,6.15,-0.308197125857)); +#129677 = VECTOR('',#129678,1.); +#129678 = DIRECTION('',(1.,0.E+000,0.E+000)); +#129679 = PCURVE('',#129647,#129680); +#129680 = DEFINITIONAL_REPRESENTATION('',(#129681),#129685); +#129681 = LINE('',#129682,#129683); +#129682 = CARTESIAN_POINT('',(3.552713678801E-015,6.15)); +#129683 = VECTOR('',#129684,1.); +#129684 = DIRECTION('',(1.,0.E+000)); +#129685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129686 = PCURVE('',#95758,#129687); +#129687 = DEFINITIONAL_REPRESENTATION('',(#129688),#129692); +#129688 = LINE('',#129689,#129690); +#129689 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#129690 = VECTOR('',#129691,1.); +#129691 = DIRECTION('',(0.E+000,1.)); +#129692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129693 = ORIENTED_EDGE('',*,*,#129694,.F.); +#129694 = EDGE_CURVE('',#129695,#129672,#129697,.T.); +#129695 = VERTEX_POINT('',#129696); +#129696 = CARTESIAN_POINT('',(10.74341632541,6.35,-0.308197125857)); +#129697 = SURFACE_CURVE('',#129698,(#129702,#129709),.PCURVE_S1.); +#129698 = LINE('',#129699,#129700); +#129699 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#127308 = VECTOR('',#127309,1.); -#127309 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127310 = PCURVE('',#127255,#127311); -#127311 = DEFINITIONAL_REPRESENTATION('',(#127312),#127316); -#127312 = LINE('',#127313,#127314); -#127313 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127314 = VECTOR('',#127315,1.); -#127315 = DIRECTION('',(-4.440892098501E-016,-1.)); -#127316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127317 = PCURVE('',#127318,#127323); -#127318 = CYLINDRICAL_SURFACE('',#127319,0.308574064194); -#127319 = AXIS2_PLACEMENT_3D('',#127320,#127321,#127322); -#127320 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#129700 = VECTOR('',#129701,1.); +#129701 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129702 = PCURVE('',#129647,#129703); +#129703 = DEFINITIONAL_REPRESENTATION('',(#129704),#129708); +#129704 = LINE('',#129705,#129706); +#129705 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129706 = VECTOR('',#129707,1.); +#129707 = DIRECTION('',(-4.440892098501E-016,-1.)); +#129708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129709 = PCURVE('',#129710,#129715); +#129710 = CYLINDRICAL_SURFACE('',#129711,0.308574064194); +#129711 = AXIS2_PLACEMENT_3D('',#129712,#129713,#129714); +#129712 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#127321 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127322 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127323 = DEFINITIONAL_REPRESENTATION('',(#127324),#127327); -#127324 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127325,#127326), +#129713 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129714 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129715 = DEFINITIONAL_REPRESENTATION('',(#129716),#129719); +#129716 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129717,#129718), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#127325 = CARTESIAN_POINT('',(4.761821717947,-6.35)); -#127326 = CARTESIAN_POINT('',(4.761821717947,-6.15)); -#127327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127328 = ORIENTED_EDGE('',*,*,#127329,.T.); -#127329 = EDGE_CURVE('',#127303,#127247,#127330,.T.); -#127330 = SURFACE_CURVE('',#127331,(#127335,#127342),.PCURVE_S1.); -#127331 = LINE('',#127332,#127333); -#127332 = CARTESIAN_POINT('',(10.74341632541,6.35,-0.308197125857)); -#127333 = VECTOR('',#127334,1.); -#127334 = DIRECTION('',(1.,0.E+000,0.E+000)); -#127335 = PCURVE('',#127255,#127336); -#127336 = DEFINITIONAL_REPRESENTATION('',(#127337),#127341); -#127337 = LINE('',#127338,#127339); -#127338 = CARTESIAN_POINT('',(3.552713678801E-015,6.35)); -#127339 = VECTOR('',#127340,1.); -#127340 = DIRECTION('',(1.,0.E+000)); -#127341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127342 = PCURVE('',#93310,#127343); -#127343 = DEFINITIONAL_REPRESENTATION('',(#127344),#127348); -#127344 = LINE('',#127345,#127346); -#127345 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#127346 = VECTOR('',#127347,1.); -#127347 = DIRECTION('',(0.E+000,1.)); -#127348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127349 = ADVANCED_FACE('',(#127350),#127364,.F.); -#127350 = FACE_BOUND('',#127351,.T.); -#127351 = EDGE_LOOP('',(#127352,#127382,#127405,#127432)); -#127352 = ORIENTED_EDGE('',*,*,#127353,.F.); -#127353 = EDGE_CURVE('',#127354,#127356,#127358,.T.); -#127354 = VERTEX_POINT('',#127355); -#127355 = CARTESIAN_POINT('',(11.,6.35,-0.208196358798)); -#127356 = VERTEX_POINT('',#127357); -#127357 = CARTESIAN_POINT('',(11.,6.15,-0.208196358798)); -#127358 = SURFACE_CURVE('',#127359,(#127363,#127375),.PCURVE_S1.); -#127359 = LINE('',#127360,#127361); -#127360 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#127361 = VECTOR('',#127362,1.); -#127362 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127363 = PCURVE('',#127364,#127369); -#127364 = PLANE('',#127365); -#127365 = AXIS2_PLACEMENT_3D('',#127366,#127367,#127368); -#127366 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#129717 = CARTESIAN_POINT('',(4.761821717947,-6.35)); +#129718 = CARTESIAN_POINT('',(4.761821717947,-6.15)); +#129719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129720 = ORIENTED_EDGE('',*,*,#129721,.T.); +#129721 = EDGE_CURVE('',#129695,#129639,#129722,.T.); +#129722 = SURFACE_CURVE('',#129723,(#129727,#129734),.PCURVE_S1.); +#129723 = LINE('',#129724,#129725); +#129724 = CARTESIAN_POINT('',(10.74341632541,6.35,-0.308197125857)); +#129725 = VECTOR('',#129726,1.); +#129726 = DIRECTION('',(1.,0.E+000,0.E+000)); +#129727 = PCURVE('',#129647,#129728); +#129728 = DEFINITIONAL_REPRESENTATION('',(#129729),#129733); +#129729 = LINE('',#129730,#129731); +#129730 = CARTESIAN_POINT('',(3.552713678801E-015,6.35)); +#129731 = VECTOR('',#129732,1.); +#129732 = DIRECTION('',(1.,0.E+000)); +#129733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129734 = PCURVE('',#95702,#129735); +#129735 = DEFINITIONAL_REPRESENTATION('',(#129736),#129740); +#129736 = LINE('',#129737,#129738); +#129737 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#129738 = VECTOR('',#129739,1.); +#129739 = DIRECTION('',(0.E+000,1.)); +#129740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129741 = ADVANCED_FACE('',(#129742),#129756,.F.); +#129742 = FACE_BOUND('',#129743,.T.); +#129743 = EDGE_LOOP('',(#129744,#129774,#129797,#129824)); +#129744 = ORIENTED_EDGE('',*,*,#129745,.F.); +#129745 = EDGE_CURVE('',#129746,#129748,#129750,.T.); +#129746 = VERTEX_POINT('',#129747); +#129747 = CARTESIAN_POINT('',(11.,6.35,-0.208196358798)); +#129748 = VERTEX_POINT('',#129749); +#129749 = CARTESIAN_POINT('',(11.,6.15,-0.208196358798)); +#129750 = SURFACE_CURVE('',#129751,(#129755,#129767),.PCURVE_S1.); +#129751 = LINE('',#129752,#129753); +#129752 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#129753 = VECTOR('',#129754,1.); +#129754 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129755 = PCURVE('',#129756,#129761); +#129756 = PLANE('',#129757); +#129757 = AXIS2_PLACEMENT_3D('',#129758,#129759,#129760); +#129758 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#127367 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#127368 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#127369 = DEFINITIONAL_REPRESENTATION('',(#127370),#127374); -#127370 = LINE('',#127371,#127372); -#127371 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#127372 = VECTOR('',#127373,1.); -#127373 = DIRECTION('',(4.440892098501E-016,-1.)); -#127374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127375 = PCURVE('',#127267,#127376); -#127376 = DEFINITIONAL_REPRESENTATION('',(#127377),#127381); -#127377 = LINE('',#127378,#127379); -#127378 = CARTESIAN_POINT('',(-6.25,5.000038352949E-002)); -#127379 = VECTOR('',#127380,1.); -#127380 = DIRECTION('',(-1.,0.E+000)); -#127381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127382 = ORIENTED_EDGE('',*,*,#127383,.F.); -#127383 = EDGE_CURVE('',#127384,#127354,#127386,.T.); -#127384 = VERTEX_POINT('',#127385); -#127385 = CARTESIAN_POINT('',(10.740726081328,6.35,-0.208196358798)); -#127386 = SURFACE_CURVE('',#127387,(#127391,#127398),.PCURVE_S1.); -#127387 = LINE('',#127388,#127389); -#127388 = CARTESIAN_POINT('',(10.740726081328,6.35,-0.208196358798)); -#127389 = VECTOR('',#127390,1.); -#127390 = DIRECTION('',(1.,0.E+000,0.E+000)); -#127391 = PCURVE('',#127364,#127392); -#127392 = DEFINITIONAL_REPRESENTATION('',(#127393),#127397); -#127393 = LINE('',#127394,#127395); -#127394 = CARTESIAN_POINT('',(-3.552713678801E-015,6.35)); -#127395 = VECTOR('',#127396,1.); -#127396 = DIRECTION('',(-1.,0.E+000)); -#127397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127398 = PCURVE('',#93310,#127399); -#127399 = DEFINITIONAL_REPRESENTATION('',(#127400),#127404); -#127400 = LINE('',#127401,#127402); -#127401 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#127402 = VECTOR('',#127403,1.); -#127403 = DIRECTION('',(0.E+000,1.)); -#127404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127405 = ORIENTED_EDGE('',*,*,#127406,.F.); -#127406 = EDGE_CURVE('',#127407,#127384,#127409,.T.); -#127407 = VERTEX_POINT('',#127408); -#127408 = CARTESIAN_POINT('',(10.740726081328,6.15,-0.208196358798)); -#127409 = SURFACE_CURVE('',#127410,(#127414,#127421),.PCURVE_S1.); -#127410 = LINE('',#127411,#127412); -#127411 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#129759 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#129760 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#129761 = DEFINITIONAL_REPRESENTATION('',(#129762),#129766); +#129762 = LINE('',#129763,#129764); +#129763 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#129764 = VECTOR('',#129765,1.); +#129765 = DIRECTION('',(4.440892098501E-016,-1.)); +#129766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129767 = PCURVE('',#129659,#129768); +#129768 = DEFINITIONAL_REPRESENTATION('',(#129769),#129773); +#129769 = LINE('',#129770,#129771); +#129770 = CARTESIAN_POINT('',(-6.25,5.000038352949E-002)); +#129771 = VECTOR('',#129772,1.); +#129772 = DIRECTION('',(-1.,0.E+000)); +#129773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129774 = ORIENTED_EDGE('',*,*,#129775,.F.); +#129775 = EDGE_CURVE('',#129776,#129746,#129778,.T.); +#129776 = VERTEX_POINT('',#129777); +#129777 = CARTESIAN_POINT('',(10.740726081328,6.35,-0.208196358798)); +#129778 = SURFACE_CURVE('',#129779,(#129783,#129790),.PCURVE_S1.); +#129779 = LINE('',#129780,#129781); +#129780 = CARTESIAN_POINT('',(10.740726081328,6.35,-0.208196358798)); +#129781 = VECTOR('',#129782,1.); +#129782 = DIRECTION('',(1.,0.E+000,0.E+000)); +#129783 = PCURVE('',#129756,#129784); +#129784 = DEFINITIONAL_REPRESENTATION('',(#129785),#129789); +#129785 = LINE('',#129786,#129787); +#129786 = CARTESIAN_POINT('',(-3.552713678801E-015,6.35)); +#129787 = VECTOR('',#129788,1.); +#129788 = DIRECTION('',(-1.,0.E+000)); +#129789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129790 = PCURVE('',#95702,#129791); +#129791 = DEFINITIONAL_REPRESENTATION('',(#129792),#129796); +#129792 = LINE('',#129793,#129794); +#129793 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#129794 = VECTOR('',#129795,1.); +#129795 = DIRECTION('',(0.E+000,1.)); +#129796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129797 = ORIENTED_EDGE('',*,*,#129798,.F.); +#129798 = EDGE_CURVE('',#129799,#129776,#129801,.T.); +#129799 = VERTEX_POINT('',#129800); +#129800 = CARTESIAN_POINT('',(10.740726081328,6.15,-0.208196358798)); +#129801 = SURFACE_CURVE('',#129802,(#129806,#129813),.PCURVE_S1.); +#129802 = LINE('',#129803,#129804); +#129803 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#127412 = VECTOR('',#127413,1.); -#127413 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127414 = PCURVE('',#127364,#127415); -#127415 = DEFINITIONAL_REPRESENTATION('',(#127416),#127420); -#127416 = LINE('',#127417,#127418); -#127417 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127418 = VECTOR('',#127419,1.); -#127419 = DIRECTION('',(-4.440892098501E-016,1.)); -#127420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127421 = PCURVE('',#127422,#127427); -#127422 = CYLINDRICAL_SURFACE('',#127423,0.208574704164); -#127423 = AXIS2_PLACEMENT_3D('',#127424,#127425,#127426); -#127424 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#129804 = VECTOR('',#129805,1.); +#129805 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129806 = PCURVE('',#129756,#129807); +#129807 = DEFINITIONAL_REPRESENTATION('',(#129808),#129812); +#129808 = LINE('',#129809,#129810); +#129809 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#129810 = VECTOR('',#129811,1.); +#129811 = DIRECTION('',(-4.440892098501E-016,1.)); +#129812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129813 = PCURVE('',#129814,#129819); +#129814 = CYLINDRICAL_SURFACE('',#129815,0.208574704164); +#129815 = AXIS2_PLACEMENT_3D('',#129816,#129817,#129818); +#129816 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#127425 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127426 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127427 = DEFINITIONAL_REPRESENTATION('',(#127428),#127431); -#127428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127429,#127430), +#129817 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129818 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129819 = DEFINITIONAL_REPRESENTATION('',(#129820),#129823); +#129820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129821,#129822), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#127429 = CARTESIAN_POINT('',(4.772630242227,-6.15)); -#127430 = CARTESIAN_POINT('',(4.772630242227,-6.35)); -#127431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127432 = ORIENTED_EDGE('',*,*,#127433,.T.); -#127433 = EDGE_CURVE('',#127407,#127356,#127434,.T.); -#127434 = SURFACE_CURVE('',#127435,(#127439,#127446),.PCURVE_S1.); -#127435 = LINE('',#127436,#127437); -#127436 = CARTESIAN_POINT('',(10.740726081328,6.15,-0.208196358798)); -#127437 = VECTOR('',#127438,1.); -#127438 = DIRECTION('',(1.,0.E+000,0.E+000)); -#127439 = PCURVE('',#127364,#127440); -#127440 = DEFINITIONAL_REPRESENTATION('',(#127441),#127445); -#127441 = LINE('',#127442,#127443); -#127442 = CARTESIAN_POINT('',(-3.552713678801E-015,6.15)); -#127443 = VECTOR('',#127444,1.); -#127444 = DIRECTION('',(-1.,0.E+000)); -#127445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127446 = PCURVE('',#93366,#127447); -#127447 = DEFINITIONAL_REPRESENTATION('',(#127448),#127452); -#127448 = LINE('',#127449,#127450); -#127449 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#127450 = VECTOR('',#127451,1.); -#127451 = DIRECTION('',(0.E+000,1.)); -#127452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127453 = ADVANCED_FACE('',(#127454),#127318,.T.); -#127454 = FACE_BOUND('',#127455,.T.); -#127455 = EDGE_LOOP('',(#127456,#127483,#127484,#127507)); -#127456 = ORIENTED_EDGE('',*,*,#127457,.T.); -#127457 = EDGE_CURVE('',#127458,#127303,#127460,.T.); -#127458 = VERTEX_POINT('',#127459); -#127459 = CARTESIAN_POINT('',(10.419594812019,6.35,0.E+000)); -#127460 = SURFACE_CURVE('',#127461,(#127466,#127472),.PCURVE_S1.); -#127461 = CIRCLE('',#127462,0.308574064194); -#127462 = AXIS2_PLACEMENT_3D('',#127463,#127464,#127465); -#127463 = CARTESIAN_POINT('',(10.728168876214,6.35,2.640924866458E-017) - ); -#127464 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127465 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127466 = PCURVE('',#127318,#127467); -#127467 = DEFINITIONAL_REPRESENTATION('',(#127468),#127471); -#127468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127469,#127470), +#129821 = CARTESIAN_POINT('',(4.772630242227,-6.15)); +#129822 = CARTESIAN_POINT('',(4.772630242227,-6.35)); +#129823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129824 = ORIENTED_EDGE('',*,*,#129825,.T.); +#129825 = EDGE_CURVE('',#129799,#129748,#129826,.T.); +#129826 = SURFACE_CURVE('',#129827,(#129831,#129838),.PCURVE_S1.); +#129827 = LINE('',#129828,#129829); +#129828 = CARTESIAN_POINT('',(10.740726081328,6.15,-0.208196358798)); +#129829 = VECTOR('',#129830,1.); +#129830 = DIRECTION('',(1.,0.E+000,0.E+000)); +#129831 = PCURVE('',#129756,#129832); +#129832 = DEFINITIONAL_REPRESENTATION('',(#129833),#129837); +#129833 = LINE('',#129834,#129835); +#129834 = CARTESIAN_POINT('',(-3.552713678801E-015,6.15)); +#129835 = VECTOR('',#129836,1.); +#129836 = DIRECTION('',(-1.,0.E+000)); +#129837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129838 = PCURVE('',#95758,#129839); +#129839 = DEFINITIONAL_REPRESENTATION('',(#129840),#129844); +#129840 = LINE('',#129841,#129842); +#129841 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#129842 = VECTOR('',#129843,1.); +#129843 = DIRECTION('',(0.E+000,1.)); +#129844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129845 = ADVANCED_FACE('',(#129846),#129710,.T.); +#129846 = FACE_BOUND('',#129847,.T.); +#129847 = EDGE_LOOP('',(#129848,#129875,#129876,#129899)); +#129848 = ORIENTED_EDGE('',*,*,#129849,.T.); +#129849 = EDGE_CURVE('',#129850,#129695,#129852,.T.); +#129850 = VERTEX_POINT('',#129851); +#129851 = CARTESIAN_POINT('',(10.419594812019,6.35,0.E+000)); +#129852 = SURFACE_CURVE('',#129853,(#129858,#129864),.PCURVE_S1.); +#129853 = CIRCLE('',#129854,0.308574064194); +#129854 = AXIS2_PLACEMENT_3D('',#129855,#129856,#129857); +#129855 = CARTESIAN_POINT('',(10.728168876214,6.35,2.640924866458E-017) + ); +#129856 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129857 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129858 = PCURVE('',#129710,#129859); +#129859 = DEFINITIONAL_REPRESENTATION('',(#129860),#129863); +#129860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129861,#129862), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#127469 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#127470 = CARTESIAN_POINT('',(4.761821717947,-6.35)); -#127471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129861 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#129862 = CARTESIAN_POINT('',(4.761821717947,-6.35)); +#129863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127472 = PCURVE('',#93310,#127473); -#127473 = DEFINITIONAL_REPRESENTATION('',(#127474),#127482); -#127474 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127475,#127476,#127477, - #127478,#127479,#127480,#127481),.UNSPECIFIED.,.T.,.F.) +#129864 = PCURVE('',#95702,#129865); +#129865 = DEFINITIONAL_REPRESENTATION('',(#129866),#129874); +#129866 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129867,#129868,#129869, + #129870,#129871,#129872,#129873),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#127475 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#127476 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#127477 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#127478 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#127479 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#127480 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#127481 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#127482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127483 = ORIENTED_EDGE('',*,*,#127302,.T.); -#127484 = ORIENTED_EDGE('',*,*,#127485,.F.); -#127485 = EDGE_CURVE('',#127486,#127280,#127488,.T.); -#127486 = VERTEX_POINT('',#127487); -#127487 = CARTESIAN_POINT('',(10.419594812019,6.15,0.E+000)); -#127488 = SURFACE_CURVE('',#127489,(#127494,#127500),.PCURVE_S1.); -#127489 = CIRCLE('',#127490,0.308574064194); -#127490 = AXIS2_PLACEMENT_3D('',#127491,#127492,#127493); -#127491 = CARTESIAN_POINT('',(10.728168876214,6.15,2.640924866458E-017) - ); -#127492 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127493 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127494 = PCURVE('',#127318,#127495); -#127495 = DEFINITIONAL_REPRESENTATION('',(#127496),#127499); -#127496 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127497,#127498), +#129867 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#129868 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#129869 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#129870 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#129871 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#129872 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#129873 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#129874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129875 = ORIENTED_EDGE('',*,*,#129694,.T.); +#129876 = ORIENTED_EDGE('',*,*,#129877,.F.); +#129877 = EDGE_CURVE('',#129878,#129672,#129880,.T.); +#129878 = VERTEX_POINT('',#129879); +#129879 = CARTESIAN_POINT('',(10.419594812019,6.15,0.E+000)); +#129880 = SURFACE_CURVE('',#129881,(#129886,#129892),.PCURVE_S1.); +#129881 = CIRCLE('',#129882,0.308574064194); +#129882 = AXIS2_PLACEMENT_3D('',#129883,#129884,#129885); +#129883 = CARTESIAN_POINT('',(10.728168876214,6.15,2.640924866458E-017) + ); +#129884 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129885 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129886 = PCURVE('',#129710,#129887); +#129887 = DEFINITIONAL_REPRESENTATION('',(#129888),#129891); +#129888 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129889,#129890), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#127497 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#127498 = CARTESIAN_POINT('',(4.761821717947,-6.15)); -#127499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129889 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#129890 = CARTESIAN_POINT('',(4.761821717947,-6.15)); +#129891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127500 = PCURVE('',#93366,#127501); -#127501 = DEFINITIONAL_REPRESENTATION('',(#127502),#127506); -#127502 = CIRCLE('',#127503,0.308574064194); -#127503 = AXIS2_PLACEMENT_2D('',#127504,#127505); -#127504 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#127505 = DIRECTION('',(0.E+000,1.)); -#127506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129892 = PCURVE('',#95758,#129893); +#129893 = DEFINITIONAL_REPRESENTATION('',(#129894),#129898); +#129894 = CIRCLE('',#129895,0.308574064194); +#129895 = AXIS2_PLACEMENT_2D('',#129896,#129897); +#129896 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#129897 = DIRECTION('',(0.E+000,1.)); +#129898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127507 = ORIENTED_EDGE('',*,*,#127508,.T.); -#127508 = EDGE_CURVE('',#127486,#127458,#127509,.T.); -#127509 = SURFACE_CURVE('',#127510,(#127514,#127520),.PCURVE_S1.); -#127510 = LINE('',#127511,#127512); -#127511 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#129899 = ORIENTED_EDGE('',*,*,#129900,.T.); +#129900 = EDGE_CURVE('',#129878,#129850,#129901,.T.); +#129901 = SURFACE_CURVE('',#129902,(#129906,#129912),.PCURVE_S1.); +#129902 = LINE('',#129903,#129904); +#129903 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#127512 = VECTOR('',#127513,1.); -#127513 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127514 = PCURVE('',#127318,#127515); -#127515 = DEFINITIONAL_REPRESENTATION('',(#127516),#127519); -#127516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127517,#127518), +#129904 = VECTOR('',#129905,1.); +#129905 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129906 = PCURVE('',#129710,#129907); +#129907 = DEFINITIONAL_REPRESENTATION('',(#129908),#129911); +#129908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129909,#129910), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#127517 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#127518 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#127519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129909 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#129910 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#129911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127520 = PCURVE('',#127521,#127526); -#127521 = PLANE('',#127522); -#127522 = AXIS2_PLACEMENT_3D('',#127523,#127524,#127525); -#127523 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#129912 = PCURVE('',#129913,#129918); +#129913 = PLANE('',#129914); +#129914 = AXIS2_PLACEMENT_3D('',#129915,#129916,#129917); +#129915 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#127524 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127525 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127526 = DEFINITIONAL_REPRESENTATION('',(#127527),#127531); -#127527 = LINE('',#127528,#127529); -#127528 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#127529 = VECTOR('',#127530,1.); -#127530 = DIRECTION('',(-1.,0.E+000)); -#127531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127532 = ADVANCED_FACE('',(#127533),#127422,.F.); -#127533 = FACE_BOUND('',#127534,.F.); -#127534 = EDGE_LOOP('',(#127535,#127558,#127585,#127610)); -#127535 = ORIENTED_EDGE('',*,*,#127536,.F.); -#127536 = EDGE_CURVE('',#127537,#127407,#127539,.T.); -#127537 = VERTEX_POINT('',#127538); -#127538 = CARTESIAN_POINT('',(10.51959417205,6.15,0.E+000)); -#127539 = SURFACE_CURVE('',#127540,(#127545,#127551),.PCURVE_S1.); -#127540 = CIRCLE('',#127541,0.208574704164); -#127541 = AXIS2_PLACEMENT_3D('',#127542,#127543,#127544); -#127542 = CARTESIAN_POINT('',(10.728168876214,6.15,2.640924866458E-017) - ); -#127543 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127544 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127545 = PCURVE('',#127422,#127546); -#127546 = DEFINITIONAL_REPRESENTATION('',(#127547),#127550); -#127547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127548,#127549), +#129916 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#129917 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129918 = DEFINITIONAL_REPRESENTATION('',(#129919),#129923); +#129919 = LINE('',#129920,#129921); +#129920 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#129921 = VECTOR('',#129922,1.); +#129922 = DIRECTION('',(-1.,0.E+000)); +#129923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129924 = ADVANCED_FACE('',(#129925),#129814,.F.); +#129925 = FACE_BOUND('',#129926,.F.); +#129926 = EDGE_LOOP('',(#129927,#129950,#129977,#130002)); +#129927 = ORIENTED_EDGE('',*,*,#129928,.F.); +#129928 = EDGE_CURVE('',#129929,#129799,#129931,.T.); +#129929 = VERTEX_POINT('',#129930); +#129930 = CARTESIAN_POINT('',(10.51959417205,6.15,0.E+000)); +#129931 = SURFACE_CURVE('',#129932,(#129937,#129943),.PCURVE_S1.); +#129932 = CIRCLE('',#129933,0.208574704164); +#129933 = AXIS2_PLACEMENT_3D('',#129934,#129935,#129936); +#129934 = CARTESIAN_POINT('',(10.728168876214,6.15,2.640924866458E-017) + ); +#129935 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129936 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129937 = PCURVE('',#129814,#129938); +#129938 = DEFINITIONAL_REPRESENTATION('',(#129939),#129942); +#129939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129940,#129941), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#127548 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#127549 = CARTESIAN_POINT('',(4.772630242227,-6.15)); -#127550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129940 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#129941 = CARTESIAN_POINT('',(4.772630242227,-6.15)); +#129942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127551 = PCURVE('',#93366,#127552); -#127552 = DEFINITIONAL_REPRESENTATION('',(#127553),#127557); -#127553 = CIRCLE('',#127554,0.208574704164); -#127554 = AXIS2_PLACEMENT_2D('',#127555,#127556); -#127555 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#127556 = DIRECTION('',(0.E+000,1.)); -#127557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129943 = PCURVE('',#95758,#129944); +#129944 = DEFINITIONAL_REPRESENTATION('',(#129945),#129949); +#129945 = CIRCLE('',#129946,0.208574704164); +#129946 = AXIS2_PLACEMENT_2D('',#129947,#129948); +#129947 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#129948 = DIRECTION('',(0.E+000,1.)); +#129949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127558 = ORIENTED_EDGE('',*,*,#127559,.F.); -#127559 = EDGE_CURVE('',#127560,#127537,#127562,.T.); -#127560 = VERTEX_POINT('',#127561); -#127561 = CARTESIAN_POINT('',(10.51959417205,6.35,0.E+000)); -#127562 = SURFACE_CURVE('',#127563,(#127567,#127573),.PCURVE_S1.); -#127563 = LINE('',#127564,#127565); -#127564 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129950 = ORIENTED_EDGE('',*,*,#129951,.F.); +#129951 = EDGE_CURVE('',#129952,#129929,#129954,.T.); +#129952 = VERTEX_POINT('',#129953); +#129953 = CARTESIAN_POINT('',(10.51959417205,6.35,0.E+000)); +#129954 = SURFACE_CURVE('',#129955,(#129959,#129965),.PCURVE_S1.); +#129955 = LINE('',#129956,#129957); +#129956 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#127565 = VECTOR('',#127566,1.); -#127566 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127567 = PCURVE('',#127422,#127568); -#127568 = DEFINITIONAL_REPRESENTATION('',(#127569),#127572); -#127569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127570,#127571), +#129957 = VECTOR('',#129958,1.); +#129958 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129959 = PCURVE('',#129814,#129960); +#129960 = DEFINITIONAL_REPRESENTATION('',(#129961),#129964); +#129961 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129962,#129963), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#127570 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#127571 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#127572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129962 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#129963 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#129964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127573 = PCURVE('',#127574,#127579); -#127574 = PLANE('',#127575); -#127575 = AXIS2_PLACEMENT_3D('',#127576,#127577,#127578); -#127576 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129965 = PCURVE('',#129966,#129971); +#129966 = PLANE('',#129967); +#129967 = AXIS2_PLACEMENT_3D('',#129968,#129969,#129970); +#129968 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#127577 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127578 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127579 = DEFINITIONAL_REPRESENTATION('',(#127580),#127584); -#127580 = LINE('',#127581,#127582); -#127581 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#127582 = VECTOR('',#127583,1.); -#127583 = DIRECTION('',(-1.,0.E+000)); -#127584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127585 = ORIENTED_EDGE('',*,*,#127586,.T.); -#127586 = EDGE_CURVE('',#127560,#127384,#127587,.T.); -#127587 = SURFACE_CURVE('',#127588,(#127593,#127599),.PCURVE_S1.); -#127588 = CIRCLE('',#127589,0.208574704164); -#127589 = AXIS2_PLACEMENT_3D('',#127590,#127591,#127592); -#127590 = CARTESIAN_POINT('',(10.728168876214,6.35,2.640924866458E-017) - ); -#127591 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127592 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#127593 = PCURVE('',#127422,#127594); -#127594 = DEFINITIONAL_REPRESENTATION('',(#127595),#127598); -#127595 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127596,#127597), +#129969 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129970 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#129971 = DEFINITIONAL_REPRESENTATION('',(#129972),#129976); +#129972 = LINE('',#129973,#129974); +#129973 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#129974 = VECTOR('',#129975,1.); +#129975 = DIRECTION('',(-1.,0.E+000)); +#129976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#129977 = ORIENTED_EDGE('',*,*,#129978,.T.); +#129978 = EDGE_CURVE('',#129952,#129776,#129979,.T.); +#129979 = SURFACE_CURVE('',#129980,(#129985,#129991),.PCURVE_S1.); +#129980 = CIRCLE('',#129981,0.208574704164); +#129981 = AXIS2_PLACEMENT_3D('',#129982,#129983,#129984); +#129982 = CARTESIAN_POINT('',(10.728168876214,6.35,2.640924866458E-017) + ); +#129983 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#129984 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#129985 = PCURVE('',#129814,#129986); +#129986 = DEFINITIONAL_REPRESENTATION('',(#129987),#129990); +#129987 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129988,#129989), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#127596 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#127597 = CARTESIAN_POINT('',(4.772630242227,-6.35)); -#127598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#129988 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#129989 = CARTESIAN_POINT('',(4.772630242227,-6.35)); +#129990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127599 = PCURVE('',#93310,#127600); -#127600 = DEFINITIONAL_REPRESENTATION('',(#127601),#127609); -#127601 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127602,#127603,#127604, - #127605,#127606,#127607,#127608),.UNSPECIFIED.,.T.,.F.) +#129991 = PCURVE('',#95702,#129992); +#129992 = DEFINITIONAL_REPRESENTATION('',(#129993),#130001); +#129993 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129994,#129995,#129996, + #129997,#129998,#129999,#130000),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#127602 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#127603 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#127604 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#127605 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#127606 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#127607 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#127608 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#127609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127610 = ORIENTED_EDGE('',*,*,#127406,.F.); -#127611 = ADVANCED_FACE('',(#127612),#127574,.T.); -#127612 = FACE_BOUND('',#127613,.T.); -#127613 = EDGE_LOOP('',(#127614,#127643,#127664,#127665)); -#127614 = ORIENTED_EDGE('',*,*,#127615,.T.); -#127615 = EDGE_CURVE('',#127616,#127618,#127620,.T.); -#127616 = VERTEX_POINT('',#127617); -#127617 = CARTESIAN_POINT('',(10.51959417205,6.35,0.530776333563)); -#127618 = VERTEX_POINT('',#127619); -#127619 = CARTESIAN_POINT('',(10.51959417205,6.15,0.530776333563)); -#127620 = SURFACE_CURVE('',#127621,(#127625,#127632),.PCURVE_S1.); -#127621 = LINE('',#127622,#127623); -#127622 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#129994 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#129995 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#129996 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#129997 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#129998 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#129999 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#130000 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#130001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130002 = ORIENTED_EDGE('',*,*,#129798,.F.); +#130003 = ADVANCED_FACE('',(#130004),#129966,.T.); +#130004 = FACE_BOUND('',#130005,.T.); +#130005 = EDGE_LOOP('',(#130006,#130035,#130056,#130057)); +#130006 = ORIENTED_EDGE('',*,*,#130007,.T.); +#130007 = EDGE_CURVE('',#130008,#130010,#130012,.T.); +#130008 = VERTEX_POINT('',#130009); +#130009 = CARTESIAN_POINT('',(10.51959417205,6.35,0.530776333563)); +#130010 = VERTEX_POINT('',#130011); +#130011 = CARTESIAN_POINT('',(10.51959417205,6.15,0.530776333563)); +#130012 = SURFACE_CURVE('',#130013,(#130017,#130024),.PCURVE_S1.); +#130013 = LINE('',#130014,#130015); +#130014 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#127623 = VECTOR('',#127624,1.); -#127624 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127625 = PCURVE('',#127574,#127626); -#127626 = DEFINITIONAL_REPRESENTATION('',(#127627),#127631); -#127627 = LINE('',#127628,#127629); -#127628 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127629 = VECTOR('',#127630,1.); -#127630 = DIRECTION('',(-1.,0.E+000)); -#127631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127632 = PCURVE('',#127633,#127638); -#127633 = CYLINDRICAL_SURFACE('',#127634,0.2192697516); -#127634 = AXIS2_PLACEMENT_3D('',#127635,#127636,#127637); -#127635 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#130015 = VECTOR('',#130016,1.); +#130016 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130017 = PCURVE('',#129966,#130018); +#130018 = DEFINITIONAL_REPRESENTATION('',(#130019),#130023); +#130019 = LINE('',#130020,#130021); +#130020 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130021 = VECTOR('',#130022,1.); +#130022 = DIRECTION('',(-1.,0.E+000)); +#130023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130024 = PCURVE('',#130025,#130030); +#130025 = CYLINDRICAL_SURFACE('',#130026,0.2192697516); +#130026 = AXIS2_PLACEMENT_3D('',#130027,#130028,#130029); +#130027 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#127636 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127637 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127638 = DEFINITIONAL_REPRESENTATION('',(#127639),#127642); -#127639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127640,#127641), +#130028 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130029 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130030 = DEFINITIONAL_REPRESENTATION('',(#130031),#130034); +#130031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130032,#130033), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#127640 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#127641 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#127642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127643 = ORIENTED_EDGE('',*,*,#127644,.T.); -#127644 = EDGE_CURVE('',#127618,#127537,#127645,.T.); -#127645 = SURFACE_CURVE('',#127646,(#127650,#127657),.PCURVE_S1.); -#127646 = LINE('',#127647,#127648); -#127647 = CARTESIAN_POINT('',(10.51959417205,6.15,0.530776333563)); -#127648 = VECTOR('',#127649,1.); -#127649 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#127650 = PCURVE('',#127574,#127651); -#127651 = DEFINITIONAL_REPRESENTATION('',(#127652),#127656); -#127652 = LINE('',#127653,#127654); -#127653 = CARTESIAN_POINT('',(6.15,0.E+000)); -#127654 = VECTOR('',#127655,1.); -#127655 = DIRECTION('',(0.E+000,-1.)); -#127656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127657 = PCURVE('',#93366,#127658); -#127658 = DEFINITIONAL_REPRESENTATION('',(#127659),#127663); -#127659 = LINE('',#127660,#127661); -#127660 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#127661 = VECTOR('',#127662,1.); -#127662 = DIRECTION('',(1.,0.E+000)); -#127663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127664 = ORIENTED_EDGE('',*,*,#127559,.F.); -#127665 = ORIENTED_EDGE('',*,*,#127666,.F.); -#127666 = EDGE_CURVE('',#127616,#127560,#127667,.T.); -#127667 = SURFACE_CURVE('',#127668,(#127672,#127679),.PCURVE_S1.); -#127668 = LINE('',#127669,#127670); -#127669 = CARTESIAN_POINT('',(10.51959417205,6.35,0.530776333563)); -#127670 = VECTOR('',#127671,1.); -#127671 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#127672 = PCURVE('',#127574,#127673); -#127673 = DEFINITIONAL_REPRESENTATION('',(#127674),#127678); -#127674 = LINE('',#127675,#127676); -#127675 = CARTESIAN_POINT('',(6.35,0.E+000)); -#127676 = VECTOR('',#127677,1.); -#127677 = DIRECTION('',(0.E+000,-1.)); -#127678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127679 = PCURVE('',#93310,#127680); -#127680 = DEFINITIONAL_REPRESENTATION('',(#127681),#127685); -#127681 = LINE('',#127682,#127683); -#127682 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#127683 = VECTOR('',#127684,1.); -#127684 = DIRECTION('',(-1.,0.E+000)); -#127685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127686 = ADVANCED_FACE('',(#127687),#127521,.T.); -#127687 = FACE_BOUND('',#127688,.T.); -#127688 = EDGE_LOOP('',(#127689,#127718,#127739,#127740)); -#127689 = ORIENTED_EDGE('',*,*,#127690,.T.); -#127690 = EDGE_CURVE('',#127691,#127693,#127695,.T.); -#127691 = VERTEX_POINT('',#127692); -#127692 = CARTESIAN_POINT('',(10.419594812019,6.15,0.530776333563)); -#127693 = VERTEX_POINT('',#127694); -#127694 = CARTESIAN_POINT('',(10.419594812019,6.35,0.530776333563)); -#127695 = SURFACE_CURVE('',#127696,(#127700,#127707),.PCURVE_S1.); -#127696 = LINE('',#127697,#127698); -#127697 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, - 0.530776333563)); -#127698 = VECTOR('',#127699,1.); -#127699 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127700 = PCURVE('',#127521,#127701); -#127701 = DEFINITIONAL_REPRESENTATION('',(#127702),#127706); -#127702 = LINE('',#127703,#127704); -#127703 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127704 = VECTOR('',#127705,1.); -#127705 = DIRECTION('',(-1.,0.E+000)); -#127706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130032 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#130033 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#130034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130035 = ORIENTED_EDGE('',*,*,#130036,.T.); +#130036 = EDGE_CURVE('',#130010,#129929,#130037,.T.); +#130037 = SURFACE_CURVE('',#130038,(#130042,#130049),.PCURVE_S1.); +#130038 = LINE('',#130039,#130040); +#130039 = CARTESIAN_POINT('',(10.51959417205,6.15,0.530776333563)); +#130040 = VECTOR('',#130041,1.); +#130041 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130042 = PCURVE('',#129966,#130043); +#130043 = DEFINITIONAL_REPRESENTATION('',(#130044),#130048); +#130044 = LINE('',#130045,#130046); +#130045 = CARTESIAN_POINT('',(6.15,0.E+000)); +#130046 = VECTOR('',#130047,1.); +#130047 = DIRECTION('',(0.E+000,-1.)); +#130048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130049 = PCURVE('',#95758,#130050); +#130050 = DEFINITIONAL_REPRESENTATION('',(#130051),#130055); +#130051 = LINE('',#130052,#130053); +#130052 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#130053 = VECTOR('',#130054,1.); +#130054 = DIRECTION('',(1.,0.E+000)); +#130055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130056 = ORIENTED_EDGE('',*,*,#129951,.F.); +#130057 = ORIENTED_EDGE('',*,*,#130058,.F.); +#130058 = EDGE_CURVE('',#130008,#129952,#130059,.T.); +#130059 = SURFACE_CURVE('',#130060,(#130064,#130071),.PCURVE_S1.); +#130060 = LINE('',#130061,#130062); +#130061 = CARTESIAN_POINT('',(10.51959417205,6.35,0.530776333563)); +#130062 = VECTOR('',#130063,1.); +#130063 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130064 = PCURVE('',#129966,#130065); +#130065 = DEFINITIONAL_REPRESENTATION('',(#130066),#130070); +#130066 = LINE('',#130067,#130068); +#130067 = CARTESIAN_POINT('',(6.35,0.E+000)); +#130068 = VECTOR('',#130069,1.); +#130069 = DIRECTION('',(0.E+000,-1.)); +#130070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130071 = PCURVE('',#95702,#130072); +#130072 = DEFINITIONAL_REPRESENTATION('',(#130073),#130077); +#130073 = LINE('',#130074,#130075); +#130074 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#130075 = VECTOR('',#130076,1.); +#130076 = DIRECTION('',(-1.,0.E+000)); +#130077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127707 = PCURVE('',#127708,#127713); -#127708 = CYLINDRICAL_SURFACE('',#127709,0.119270391569); -#127709 = AXIS2_PLACEMENT_3D('',#127710,#127711,#127712); -#127710 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#130078 = ADVANCED_FACE('',(#130079),#129913,.T.); +#130079 = FACE_BOUND('',#130080,.T.); +#130080 = EDGE_LOOP('',(#130081,#130110,#130131,#130132)); +#130081 = ORIENTED_EDGE('',*,*,#130082,.T.); +#130082 = EDGE_CURVE('',#130083,#130085,#130087,.T.); +#130083 = VERTEX_POINT('',#130084); +#130084 = CARTESIAN_POINT('',(10.419594812019,6.15,0.530776333563)); +#130085 = VERTEX_POINT('',#130086); +#130086 = CARTESIAN_POINT('',(10.419594812019,6.35,0.530776333563)); +#130087 = SURFACE_CURVE('',#130088,(#130092,#130099),.PCURVE_S1.); +#130088 = LINE('',#130089,#130090); +#130089 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#127711 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127712 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127713 = DEFINITIONAL_REPRESENTATION('',(#127714),#127717); -#127714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127715,#127716), - .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#127715 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#127716 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#127717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127718 = ORIENTED_EDGE('',*,*,#127719,.T.); -#127719 = EDGE_CURVE('',#127693,#127458,#127720,.T.); -#127720 = SURFACE_CURVE('',#127721,(#127725,#127732),.PCURVE_S1.); -#127721 = LINE('',#127722,#127723); -#127722 = CARTESIAN_POINT('',(10.419594812019,6.35,0.530776333563)); -#127723 = VECTOR('',#127724,1.); -#127724 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#127725 = PCURVE('',#127521,#127726); -#127726 = DEFINITIONAL_REPRESENTATION('',(#127727),#127731); -#127727 = LINE('',#127728,#127729); -#127728 = CARTESIAN_POINT('',(-6.35,0.E+000)); -#127729 = VECTOR('',#127730,1.); -#127730 = DIRECTION('',(0.E+000,-1.)); -#127731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127732 = PCURVE('',#93310,#127733); -#127733 = DEFINITIONAL_REPRESENTATION('',(#127734),#127738); -#127734 = LINE('',#127735,#127736); -#127735 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#127736 = VECTOR('',#127737,1.); -#127737 = DIRECTION('',(-1.,0.E+000)); -#127738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127739 = ORIENTED_EDGE('',*,*,#127508,.F.); -#127740 = ORIENTED_EDGE('',*,*,#127741,.F.); -#127741 = EDGE_CURVE('',#127691,#127486,#127742,.T.); -#127742 = SURFACE_CURVE('',#127743,(#127747,#127754),.PCURVE_S1.); -#127743 = LINE('',#127744,#127745); -#127744 = CARTESIAN_POINT('',(10.419594812019,6.15,0.530776333563)); -#127745 = VECTOR('',#127746,1.); -#127746 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#127747 = PCURVE('',#127521,#127748); -#127748 = DEFINITIONAL_REPRESENTATION('',(#127749),#127753); -#127749 = LINE('',#127750,#127751); -#127750 = CARTESIAN_POINT('',(-6.15,0.E+000)); -#127751 = VECTOR('',#127752,1.); -#127752 = DIRECTION('',(0.E+000,-1.)); -#127753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127754 = PCURVE('',#93366,#127755); -#127755 = DEFINITIONAL_REPRESENTATION('',(#127756),#127760); -#127756 = LINE('',#127757,#127758); -#127757 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#127758 = VECTOR('',#127759,1.); -#127759 = DIRECTION('',(1.,0.E+000)); -#127760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127761 = ADVANCED_FACE('',(#127762),#127708,.F.); -#127762 = FACE_BOUND('',#127763,.F.); -#127763 = EDGE_LOOP('',(#127764,#127765,#127788,#127810)); -#127764 = ORIENTED_EDGE('',*,*,#127690,.T.); -#127765 = ORIENTED_EDGE('',*,*,#127766,.F.); -#127766 = EDGE_CURVE('',#127767,#127693,#127769,.T.); -#127767 = VERTEX_POINT('',#127768); -#127768 = CARTESIAN_POINT('',(10.303662633502,6.35,0.65)); -#127769 = SURFACE_CURVE('',#127770,(#127775,#127781),.PCURVE_S1.); -#127770 = CIRCLE('',#127771,0.119270391569); -#127771 = AXIS2_PLACEMENT_3D('',#127772,#127773,#127774); -#127772 = CARTESIAN_POINT('',(10.30032442045,6.35,0.530776333563)); -#127773 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127774 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127775 = PCURVE('',#127708,#127776); -#127776 = DEFINITIONAL_REPRESENTATION('',(#127777),#127780); -#127777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127778,#127779), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), - .PIECEWISE_BEZIER_KNOTS.); -#127778 = CARTESIAN_POINT('',(1.598788597134,6.35)); -#127779 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#127780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130090 = VECTOR('',#130091,1.); +#130091 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130092 = PCURVE('',#129913,#130093); +#130093 = DEFINITIONAL_REPRESENTATION('',(#130094),#130098); +#130094 = LINE('',#130095,#130096); +#130095 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130096 = VECTOR('',#130097,1.); +#130097 = DIRECTION('',(-1.,0.E+000)); +#130098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127781 = PCURVE('',#93310,#127782); -#127782 = DEFINITIONAL_REPRESENTATION('',(#127783),#127787); -#127783 = CIRCLE('',#127784,0.119270391569); -#127784 = AXIS2_PLACEMENT_2D('',#127785,#127786); -#127785 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#127786 = DIRECTION('',(0.E+000,-1.)); -#127787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130099 = PCURVE('',#130100,#130105); +#130100 = CYLINDRICAL_SURFACE('',#130101,0.119270391569); +#130101 = AXIS2_PLACEMENT_3D('',#130102,#130103,#130104); +#130102 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, + 0.530776333563)); +#130103 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130104 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130105 = DEFINITIONAL_REPRESENTATION('',(#130106),#130109); +#130106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130107,#130108), + .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); +#130107 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#130108 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#130109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130110 = ORIENTED_EDGE('',*,*,#130111,.T.); +#130111 = EDGE_CURVE('',#130085,#129850,#130112,.T.); +#130112 = SURFACE_CURVE('',#130113,(#130117,#130124),.PCURVE_S1.); +#130113 = LINE('',#130114,#130115); +#130114 = CARTESIAN_POINT('',(10.419594812019,6.35,0.530776333563)); +#130115 = VECTOR('',#130116,1.); +#130116 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130117 = PCURVE('',#129913,#130118); +#130118 = DEFINITIONAL_REPRESENTATION('',(#130119),#130123); +#130119 = LINE('',#130120,#130121); +#130120 = CARTESIAN_POINT('',(-6.35,0.E+000)); +#130121 = VECTOR('',#130122,1.); +#130122 = DIRECTION('',(0.E+000,-1.)); +#130123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130124 = PCURVE('',#95702,#130125); +#130125 = DEFINITIONAL_REPRESENTATION('',(#130126),#130130); +#130126 = LINE('',#130127,#130128); +#130127 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#130128 = VECTOR('',#130129,1.); +#130129 = DIRECTION('',(-1.,0.E+000)); +#130130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127788 = ORIENTED_EDGE('',*,*,#127789,.T.); -#127789 = EDGE_CURVE('',#127767,#127790,#127792,.T.); -#127790 = VERTEX_POINT('',#127791); -#127791 = CARTESIAN_POINT('',(10.303662633502,6.15,0.65)); -#127792 = SURFACE_CURVE('',#127793,(#127797,#127803),.PCURVE_S1.); -#127793 = LINE('',#127794,#127795); -#127794 = CARTESIAN_POINT('',(10.303662633502,6.15,0.65)); -#127795 = VECTOR('',#127796,1.); -#127796 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#127797 = PCURVE('',#127708,#127798); -#127798 = DEFINITIONAL_REPRESENTATION('',(#127799),#127802); -#127799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127800,#127801), +#130131 = ORIENTED_EDGE('',*,*,#129900,.F.); +#130132 = ORIENTED_EDGE('',*,*,#130133,.F.); +#130133 = EDGE_CURVE('',#130083,#129878,#130134,.T.); +#130134 = SURFACE_CURVE('',#130135,(#130139,#130146),.PCURVE_S1.); +#130135 = LINE('',#130136,#130137); +#130136 = CARTESIAN_POINT('',(10.419594812019,6.15,0.530776333563)); +#130137 = VECTOR('',#130138,1.); +#130138 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130139 = PCURVE('',#129913,#130140); +#130140 = DEFINITIONAL_REPRESENTATION('',(#130141),#130145); +#130141 = LINE('',#130142,#130143); +#130142 = CARTESIAN_POINT('',(-6.15,0.E+000)); +#130143 = VECTOR('',#130144,1.); +#130144 = DIRECTION('',(0.E+000,-1.)); +#130145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130146 = PCURVE('',#95758,#130147); +#130147 = DEFINITIONAL_REPRESENTATION('',(#130148),#130152); +#130148 = LINE('',#130149,#130150); +#130149 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#130150 = VECTOR('',#130151,1.); +#130151 = DIRECTION('',(1.,0.E+000)); +#130152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130153 = ADVANCED_FACE('',(#130154),#130100,.F.); +#130154 = FACE_BOUND('',#130155,.F.); +#130155 = EDGE_LOOP('',(#130156,#130157,#130180,#130202)); +#130156 = ORIENTED_EDGE('',*,*,#130082,.T.); +#130157 = ORIENTED_EDGE('',*,*,#130158,.F.); +#130158 = EDGE_CURVE('',#130159,#130085,#130161,.T.); +#130159 = VERTEX_POINT('',#130160); +#130160 = CARTESIAN_POINT('',(10.303662633502,6.35,0.65)); +#130161 = SURFACE_CURVE('',#130162,(#130167,#130173),.PCURVE_S1.); +#130162 = CIRCLE('',#130163,0.119270391569); +#130163 = AXIS2_PLACEMENT_3D('',#130164,#130165,#130166); +#130164 = CARTESIAN_POINT('',(10.30032442045,6.35,0.530776333563)); +#130165 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130166 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130167 = PCURVE('',#130100,#130168); +#130168 = DEFINITIONAL_REPRESENTATION('',(#130169),#130172); +#130169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130170,#130171), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), + .PIECEWISE_BEZIER_KNOTS.); +#130170 = CARTESIAN_POINT('',(1.598788597134,6.35)); +#130171 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#130172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130173 = PCURVE('',#95702,#130174); +#130174 = DEFINITIONAL_REPRESENTATION('',(#130175),#130179); +#130175 = CIRCLE('',#130176,0.119270391569); +#130176 = AXIS2_PLACEMENT_2D('',#130177,#130178); +#130177 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#130178 = DIRECTION('',(0.E+000,-1.)); +#130179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130180 = ORIENTED_EDGE('',*,*,#130181,.T.); +#130181 = EDGE_CURVE('',#130159,#130182,#130184,.T.); +#130182 = VERTEX_POINT('',#130183); +#130183 = CARTESIAN_POINT('',(10.303662633502,6.15,0.65)); +#130184 = SURFACE_CURVE('',#130185,(#130189,#130195),.PCURVE_S1.); +#130185 = LINE('',#130186,#130187); +#130186 = CARTESIAN_POINT('',(10.303662633502,6.15,0.65)); +#130187 = VECTOR('',#130188,1.); +#130188 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130189 = PCURVE('',#130100,#130190); +#130190 = DEFINITIONAL_REPRESENTATION('',(#130191),#130194); +#130191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130192,#130193), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#127800 = CARTESIAN_POINT('',(1.598788597134,6.35)); -#127801 = CARTESIAN_POINT('',(1.598788597134,6.15)); -#127802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127803 = PCURVE('',#93338,#127804); -#127804 = DEFINITIONAL_REPRESENTATION('',(#127805),#127809); -#127805 = LINE('',#127806,#127807); -#127806 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#127807 = VECTOR('',#127808,1.); -#127808 = DIRECTION('',(4.440892098501E-016,-1.)); -#127809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127810 = ORIENTED_EDGE('',*,*,#127811,.T.); -#127811 = EDGE_CURVE('',#127790,#127691,#127812,.T.); -#127812 = SURFACE_CURVE('',#127813,(#127818,#127824),.PCURVE_S1.); -#127813 = CIRCLE('',#127814,0.119270391569); -#127814 = AXIS2_PLACEMENT_3D('',#127815,#127816,#127817); -#127815 = CARTESIAN_POINT('',(10.30032442045,6.15,0.530776333563)); -#127816 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127817 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127818 = PCURVE('',#127708,#127819); -#127819 = DEFINITIONAL_REPRESENTATION('',(#127820),#127823); -#127820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127821,#127822), +#130192 = CARTESIAN_POINT('',(1.598788597134,6.35)); +#130193 = CARTESIAN_POINT('',(1.598788597134,6.15)); +#130194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130195 = PCURVE('',#95730,#130196); +#130196 = DEFINITIONAL_REPRESENTATION('',(#130197),#130201); +#130197 = LINE('',#130198,#130199); +#130198 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#130199 = VECTOR('',#130200,1.); +#130200 = DIRECTION('',(4.440892098501E-016,-1.)); +#130201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130202 = ORIENTED_EDGE('',*,*,#130203,.T.); +#130203 = EDGE_CURVE('',#130182,#130083,#130204,.T.); +#130204 = SURFACE_CURVE('',#130205,(#130210,#130216),.PCURVE_S1.); +#130205 = CIRCLE('',#130206,0.119270391569); +#130206 = AXIS2_PLACEMENT_3D('',#130207,#130208,#130209); +#130207 = CARTESIAN_POINT('',(10.30032442045,6.15,0.530776333563)); +#130208 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130209 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130210 = PCURVE('',#130100,#130211); +#130211 = DEFINITIONAL_REPRESENTATION('',(#130212),#130215); +#130212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130213,#130214), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#127821 = CARTESIAN_POINT('',(1.598788597134,6.15)); -#127822 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#127823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130213 = CARTESIAN_POINT('',(1.598788597134,6.15)); +#130214 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#130215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127824 = PCURVE('',#93366,#127825); -#127825 = DEFINITIONAL_REPRESENTATION('',(#127826),#127834); -#127826 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127827,#127828,#127829, - #127830,#127831,#127832,#127833),.UNSPECIFIED.,.T.,.F.) +#130216 = PCURVE('',#95758,#130217); +#130217 = DEFINITIONAL_REPRESENTATION('',(#130218),#130226); +#130218 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130219,#130220,#130221, + #130222,#130223,#130224,#130225),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#127827 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#127828 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#127829 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#127830 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#127831 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#127832 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#127833 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#127834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127835 = ADVANCED_FACE('',(#127836),#127633,.T.); -#127836 = FACE_BOUND('',#127837,.T.); -#127837 = EDGE_LOOP('',(#127838,#127839,#127862,#127884)); -#127838 = ORIENTED_EDGE('',*,*,#127615,.F.); -#127839 = ORIENTED_EDGE('',*,*,#127840,.F.); -#127840 = EDGE_CURVE('',#127841,#127616,#127843,.T.); -#127841 = VERTEX_POINT('',#127842); -#127842 = CARTESIAN_POINT('',(10.304819755875,6.35,0.75)); -#127843 = SURFACE_CURVE('',#127844,(#127849,#127855),.PCURVE_S1.); -#127844 = CIRCLE('',#127845,0.2192697516); -#127845 = AXIS2_PLACEMENT_3D('',#127846,#127847,#127848); -#127846 = CARTESIAN_POINT('',(10.30032442045,6.35,0.530776333563)); -#127847 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127848 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127849 = PCURVE('',#127633,#127850); -#127850 = DEFINITIONAL_REPRESENTATION('',(#127851),#127854); -#127851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127852,#127853), +#130219 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#130220 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#130221 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#130222 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#130223 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#130224 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#130225 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#130226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130227 = ADVANCED_FACE('',(#130228),#130025,.T.); +#130228 = FACE_BOUND('',#130229,.T.); +#130229 = EDGE_LOOP('',(#130230,#130231,#130254,#130276)); +#130230 = ORIENTED_EDGE('',*,*,#130007,.F.); +#130231 = ORIENTED_EDGE('',*,*,#130232,.F.); +#130232 = EDGE_CURVE('',#130233,#130008,#130235,.T.); +#130233 = VERTEX_POINT('',#130234); +#130234 = CARTESIAN_POINT('',(10.304819755875,6.35,0.75)); +#130235 = SURFACE_CURVE('',#130236,(#130241,#130247),.PCURVE_S1.); +#130236 = CIRCLE('',#130237,0.2192697516); +#130237 = AXIS2_PLACEMENT_3D('',#130238,#130239,#130240); +#130238 = CARTESIAN_POINT('',(10.30032442045,6.35,0.530776333563)); +#130239 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130240 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130241 = PCURVE('',#130025,#130242); +#130242 = DEFINITIONAL_REPRESENTATION('',(#130243),#130246); +#130243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130244,#130245), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#127852 = CARTESIAN_POINT('',(1.591299156552,6.35)); -#127853 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#127854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127855 = PCURVE('',#93310,#127856); -#127856 = DEFINITIONAL_REPRESENTATION('',(#127857),#127861); -#127857 = CIRCLE('',#127858,0.2192697516); -#127858 = AXIS2_PLACEMENT_2D('',#127859,#127860); -#127859 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#127860 = DIRECTION('',(0.E+000,-1.)); -#127861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127862 = ORIENTED_EDGE('',*,*,#127863,.F.); -#127863 = EDGE_CURVE('',#127864,#127841,#127866,.T.); -#127864 = VERTEX_POINT('',#127865); -#127865 = CARTESIAN_POINT('',(10.304819755875,6.15,0.75)); -#127866 = SURFACE_CURVE('',#127867,(#127871,#127877),.PCURVE_S1.); -#127867 = LINE('',#127868,#127869); -#127868 = CARTESIAN_POINT('',(10.304819755875,6.15,0.75)); -#127869 = VECTOR('',#127870,1.); -#127870 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127871 = PCURVE('',#127633,#127872); -#127872 = DEFINITIONAL_REPRESENTATION('',(#127873),#127876); -#127873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127874,#127875), +#130244 = CARTESIAN_POINT('',(1.591299156552,6.35)); +#130245 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#130246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130247 = PCURVE('',#95702,#130248); +#130248 = DEFINITIONAL_REPRESENTATION('',(#130249),#130253); +#130249 = CIRCLE('',#130250,0.2192697516); +#130250 = AXIS2_PLACEMENT_2D('',#130251,#130252); +#130251 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#130252 = DIRECTION('',(0.E+000,-1.)); +#130253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130254 = ORIENTED_EDGE('',*,*,#130255,.F.); +#130255 = EDGE_CURVE('',#130256,#130233,#130258,.T.); +#130256 = VERTEX_POINT('',#130257); +#130257 = CARTESIAN_POINT('',(10.304819755875,6.15,0.75)); +#130258 = SURFACE_CURVE('',#130259,(#130263,#130269),.PCURVE_S1.); +#130259 = LINE('',#130260,#130261); +#130260 = CARTESIAN_POINT('',(10.304819755875,6.15,0.75)); +#130261 = VECTOR('',#130262,1.); +#130262 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130263 = PCURVE('',#130025,#130264); +#130264 = DEFINITIONAL_REPRESENTATION('',(#130265),#130268); +#130265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130266,#130267), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#127874 = CARTESIAN_POINT('',(1.591299156552,6.15)); -#127875 = CARTESIAN_POINT('',(1.591299156552,6.35)); -#127876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127877 = PCURVE('',#93392,#127878); -#127878 = DEFINITIONAL_REPRESENTATION('',(#127879),#127883); -#127879 = LINE('',#127880,#127881); -#127880 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#127881 = VECTOR('',#127882,1.); -#127882 = DIRECTION('',(4.440892098501E-016,1.)); -#127883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127884 = ORIENTED_EDGE('',*,*,#127885,.T.); -#127885 = EDGE_CURVE('',#127864,#127618,#127886,.T.); -#127886 = SURFACE_CURVE('',#127887,(#127892,#127898),.PCURVE_S1.); -#127887 = CIRCLE('',#127888,0.2192697516); -#127888 = AXIS2_PLACEMENT_3D('',#127889,#127890,#127891); -#127889 = CARTESIAN_POINT('',(10.30032442045,6.15,0.530776333563)); -#127890 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#127891 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#127892 = PCURVE('',#127633,#127893); -#127893 = DEFINITIONAL_REPRESENTATION('',(#127894),#127897); -#127894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#127895,#127896), +#130266 = CARTESIAN_POINT('',(1.591299156552,6.15)); +#130267 = CARTESIAN_POINT('',(1.591299156552,6.35)); +#130268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130269 = PCURVE('',#95784,#130270); +#130270 = DEFINITIONAL_REPRESENTATION('',(#130271),#130275); +#130271 = LINE('',#130272,#130273); +#130272 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#130273 = VECTOR('',#130274,1.); +#130274 = DIRECTION('',(4.440892098501E-016,1.)); +#130275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130276 = ORIENTED_EDGE('',*,*,#130277,.T.); +#130277 = EDGE_CURVE('',#130256,#130010,#130278,.T.); +#130278 = SURFACE_CURVE('',#130279,(#130284,#130290),.PCURVE_S1.); +#130279 = CIRCLE('',#130280,0.2192697516); +#130280 = AXIS2_PLACEMENT_3D('',#130281,#130282,#130283); +#130281 = CARTESIAN_POINT('',(10.30032442045,6.15,0.530776333563)); +#130282 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130283 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130284 = PCURVE('',#130025,#130285); +#130285 = DEFINITIONAL_REPRESENTATION('',(#130286),#130289); +#130286 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130287,#130288), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#127895 = CARTESIAN_POINT('',(1.591299156552,6.15)); -#127896 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#127897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130287 = CARTESIAN_POINT('',(1.591299156552,6.15)); +#130288 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#130289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#127898 = PCURVE('',#93366,#127899); -#127899 = DEFINITIONAL_REPRESENTATION('',(#127900),#127908); -#127900 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#127901,#127902,#127903, - #127904,#127905,#127906,#127907),.UNSPECIFIED.,.T.,.F.) +#130290 = PCURVE('',#95758,#130291); +#130291 = DEFINITIONAL_REPRESENTATION('',(#130292),#130300); +#130292 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130293,#130294,#130295, + #130296,#130297,#130298,#130299),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#127901 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#127902 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#127903 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#127904 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#127905 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#127906 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#127907 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#127908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127909 = ADVANCED_FACE('',(#127910),#93338,.T.); -#127910 = FACE_BOUND('',#127911,.T.); -#127911 = EDGE_LOOP('',(#127912,#127933,#127934,#127955)); -#127912 = ORIENTED_EDGE('',*,*,#127913,.F.); -#127913 = EDGE_CURVE('',#127767,#93295,#127914,.T.); -#127914 = SURFACE_CURVE('',#127915,(#127919,#127926),.PCURVE_S1.); -#127915 = LINE('',#127916,#127917); -#127916 = CARTESIAN_POINT('',(10.527847992439,6.35,0.65)); -#127917 = VECTOR('',#127918,1.); -#127918 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127919 = PCURVE('',#93338,#127920); -#127920 = DEFINITIONAL_REPRESENTATION('',(#127921),#127925); -#127921 = LINE('',#127922,#127923); -#127922 = CARTESIAN_POINT('',(0.E+000,0.2)); -#127923 = VECTOR('',#127924,1.); -#127924 = DIRECTION('',(1.,-3.00059940766E-063)); -#127925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127926 = PCURVE('',#93310,#127927); -#127927 = DEFINITIONAL_REPRESENTATION('',(#127928),#127932); -#127928 = LINE('',#127929,#127930); -#127929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127930 = VECTOR('',#127931,1.); -#127931 = DIRECTION('',(3.563627120235E-016,-1.)); -#127932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127933 = ORIENTED_EDGE('',*,*,#127789,.T.); -#127934 = ORIENTED_EDGE('',*,*,#127935,.T.); -#127935 = EDGE_CURVE('',#127790,#93323,#127936,.T.); -#127936 = SURFACE_CURVE('',#127937,(#127941,#127948),.PCURVE_S1.); -#127937 = LINE('',#127938,#127939); -#127938 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); -#127939 = VECTOR('',#127940,1.); -#127940 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127941 = PCURVE('',#93338,#127942); -#127942 = DEFINITIONAL_REPRESENTATION('',(#127943),#127947); -#127943 = LINE('',#127944,#127945); -#127944 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127945 = VECTOR('',#127946,1.); -#127946 = DIRECTION('',(1.,-3.00059940766E-063)); -#127947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127948 = PCURVE('',#93366,#127949); -#127949 = DEFINITIONAL_REPRESENTATION('',(#127950),#127954); -#127950 = LINE('',#127951,#127952); -#127951 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#127952 = VECTOR('',#127953,1.); -#127953 = DIRECTION('',(-3.563627120235E-016,-1.)); -#127954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127955 = ORIENTED_EDGE('',*,*,#93322,.F.); -#127956 = ADVANCED_FACE('',(#127957),#93310,.T.); -#127957 = FACE_BOUND('',#127958,.T.); -#127958 = EDGE_LOOP('',(#127959,#127980,#127981,#127982,#127983,#127984, - #128005,#128006,#128007,#128008,#128009,#128010)); -#127959 = ORIENTED_EDGE('',*,*,#127960,.F.); -#127960 = EDGE_CURVE('',#127841,#93293,#127961,.T.); -#127961 = SURFACE_CURVE('',#127962,(#127966,#127973),.PCURVE_S1.); -#127962 = LINE('',#127963,#127964); -#127963 = CARTESIAN_POINT('',(10.527847992439,6.35,0.75)); -#127964 = VECTOR('',#127965,1.); -#127965 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#127966 = PCURVE('',#93310,#127967); -#127967 = DEFINITIONAL_REPRESENTATION('',(#127968),#127972); -#127968 = LINE('',#127969,#127970); -#127969 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#127970 = VECTOR('',#127971,1.); -#127971 = DIRECTION('',(3.563627120235E-016,-1.)); -#127972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127973 = PCURVE('',#93392,#127974); -#127974 = DEFINITIONAL_REPRESENTATION('',(#127975),#127979); -#127975 = LINE('',#127976,#127977); -#127976 = CARTESIAN_POINT('',(0.E+000,0.2)); -#127977 = VECTOR('',#127978,1.); -#127978 = DIRECTION('',(-1.,-3.00059940766E-063)); -#127979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127980 = ORIENTED_EDGE('',*,*,#127840,.T.); -#127981 = ORIENTED_EDGE('',*,*,#127666,.T.); -#127982 = ORIENTED_EDGE('',*,*,#127586,.T.); -#127983 = ORIENTED_EDGE('',*,*,#127383,.T.); -#127984 = ORIENTED_EDGE('',*,*,#127985,.F.); -#127985 = EDGE_CURVE('',#127247,#127354,#127986,.T.); -#127986 = SURFACE_CURVE('',#127987,(#127991,#127998),.PCURVE_S1.); -#127987 = LINE('',#127988,#127989); -#127988 = CARTESIAN_POINT('',(11.,6.35,1.159810404338E-002)); -#127989 = VECTOR('',#127990,1.); -#127990 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#127991 = PCURVE('',#93310,#127992); -#127992 = DEFINITIONAL_REPRESENTATION('',(#127993),#127997); -#127993 = LINE('',#127994,#127995); -#127994 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#127995 = VECTOR('',#127996,1.); -#127996 = DIRECTION('',(1.,2.101748079665E-016)); -#127997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#127998 = PCURVE('',#127267,#127999); -#127999 = DEFINITIONAL_REPRESENTATION('',(#128000),#128004); -#128000 = LINE('',#128001,#128002); -#128001 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#128002 = VECTOR('',#128003,1.); -#128003 = DIRECTION('',(1.194699204908E-017,1.)); -#128004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128005 = ORIENTED_EDGE('',*,*,#127329,.F.); -#128006 = ORIENTED_EDGE('',*,*,#127457,.F.); -#128007 = ORIENTED_EDGE('',*,*,#127719,.F.); -#128008 = ORIENTED_EDGE('',*,*,#127766,.F.); -#128009 = ORIENTED_EDGE('',*,*,#127913,.T.); -#128010 = ORIENTED_EDGE('',*,*,#93292,.F.); -#128011 = ADVANCED_FACE('',(#128012),#93392,.T.); -#128012 = FACE_BOUND('',#128013,.T.); -#128013 = EDGE_LOOP('',(#128014,#128035,#128036,#128037)); -#128014 = ORIENTED_EDGE('',*,*,#128015,.F.); -#128015 = EDGE_CURVE('',#127864,#93351,#128016,.T.); -#128016 = SURFACE_CURVE('',#128017,(#128021,#128028),.PCURVE_S1.); -#128017 = LINE('',#128018,#128019); -#128018 = CARTESIAN_POINT('',(10.527847992439,6.15,0.75)); -#128019 = VECTOR('',#128020,1.); -#128020 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#128021 = PCURVE('',#93392,#128022); -#128022 = DEFINITIONAL_REPRESENTATION('',(#128023),#128027); -#128023 = LINE('',#128024,#128025); -#128024 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128025 = VECTOR('',#128026,1.); -#128026 = DIRECTION('',(-1.,-3.00059940766E-063)); -#128027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128028 = PCURVE('',#93366,#128029); -#128029 = DEFINITIONAL_REPRESENTATION('',(#128030),#128034); -#128030 = LINE('',#128031,#128032); -#128031 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#128032 = VECTOR('',#128033,1.); -#128033 = DIRECTION('',(-3.563627120235E-016,-1.)); -#128034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128035 = ORIENTED_EDGE('',*,*,#127863,.T.); -#128036 = ORIENTED_EDGE('',*,*,#127960,.T.); -#128037 = ORIENTED_EDGE('',*,*,#93378,.F.); -#128038 = ADVANCED_FACE('',(#128039),#93366,.T.); -#128039 = FACE_BOUND('',#128040,.T.); -#128040 = EDGE_LOOP('',(#128041,#128042,#128043,#128044,#128045,#128046, - #128067,#128068,#128069,#128070,#128071,#128072)); -#128041 = ORIENTED_EDGE('',*,*,#127935,.F.); -#128042 = ORIENTED_EDGE('',*,*,#127811,.T.); -#128043 = ORIENTED_EDGE('',*,*,#127741,.T.); -#128044 = ORIENTED_EDGE('',*,*,#127485,.T.); -#128045 = ORIENTED_EDGE('',*,*,#127279,.T.); -#128046 = ORIENTED_EDGE('',*,*,#128047,.F.); -#128047 = EDGE_CURVE('',#127356,#127245,#128048,.T.); -#128048 = SURFACE_CURVE('',#128049,(#128053,#128060),.PCURVE_S1.); -#128049 = LINE('',#128050,#128051); -#128050 = CARTESIAN_POINT('',(11.,6.15,1.159810404338E-002)); -#128051 = VECTOR('',#128052,1.); -#128052 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#128053 = PCURVE('',#93366,#128054); -#128054 = DEFINITIONAL_REPRESENTATION('',(#128055),#128059); -#128055 = LINE('',#128056,#128057); -#128056 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#128057 = VECTOR('',#128058,1.); -#128058 = DIRECTION('',(1.,-2.101748079665E-016)); -#128059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128060 = PCURVE('',#127267,#128061); -#128061 = DEFINITIONAL_REPRESENTATION('',(#128062),#128066); -#128062 = LINE('',#128063,#128064); -#128063 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#128064 = VECTOR('',#128065,1.); -#128065 = DIRECTION('',(-1.194699204908E-017,-1.)); -#128066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128067 = ORIENTED_EDGE('',*,*,#127433,.F.); -#128068 = ORIENTED_EDGE('',*,*,#127536,.F.); -#128069 = ORIENTED_EDGE('',*,*,#127644,.F.); -#128070 = ORIENTED_EDGE('',*,*,#127885,.F.); -#128071 = ORIENTED_EDGE('',*,*,#128015,.T.); -#128072 = ORIENTED_EDGE('',*,*,#93350,.F.); -#128073 = ADVANCED_FACE('',(#128074),#127267,.T.); -#128074 = FACE_BOUND('',#128075,.T.); -#128075 = EDGE_LOOP('',(#128076,#128077,#128078,#128079)); -#128076 = ORIENTED_EDGE('',*,*,#127985,.T.); -#128077 = ORIENTED_EDGE('',*,*,#127353,.T.); -#128078 = ORIENTED_EDGE('',*,*,#128047,.T.); -#128079 = ORIENTED_EDGE('',*,*,#127244,.T.); -#128080 = ADVANCED_FACE('',(#128081),#128095,.F.); -#128081 = FACE_BOUND('',#128082,.T.); -#128082 = EDGE_LOOP('',(#128083,#128118,#128141,#128168)); -#128083 = ORIENTED_EDGE('',*,*,#128084,.F.); -#128084 = EDGE_CURVE('',#128085,#128087,#128089,.T.); -#128085 = VERTEX_POINT('',#128086); -#128086 = CARTESIAN_POINT('',(11.,5.65,-0.308197125857)); -#128087 = VERTEX_POINT('',#128088); -#128088 = CARTESIAN_POINT('',(11.,5.85,-0.308197125857)); -#128089 = SURFACE_CURVE('',#128090,(#128094,#128106),.PCURVE_S1.); -#128090 = LINE('',#128091,#128092); -#128091 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#128092 = VECTOR('',#128093,1.); -#128093 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128094 = PCURVE('',#128095,#128100); -#128095 = PLANE('',#128096); -#128096 = AXIS2_PLACEMENT_3D('',#128097,#128098,#128099); -#128097 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#130293 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#130294 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#130295 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#130296 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#130297 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#130298 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#130299 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#130300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130301 = ADVANCED_FACE('',(#130302),#95730,.T.); +#130302 = FACE_BOUND('',#130303,.T.); +#130303 = EDGE_LOOP('',(#130304,#130325,#130326,#130347)); +#130304 = ORIENTED_EDGE('',*,*,#130305,.F.); +#130305 = EDGE_CURVE('',#130159,#95687,#130306,.T.); +#130306 = SURFACE_CURVE('',#130307,(#130311,#130318),.PCURVE_S1.); +#130307 = LINE('',#130308,#130309); +#130308 = CARTESIAN_POINT('',(10.527847992439,6.35,0.65)); +#130309 = VECTOR('',#130310,1.); +#130310 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#130311 = PCURVE('',#95730,#130312); +#130312 = DEFINITIONAL_REPRESENTATION('',(#130313),#130317); +#130313 = LINE('',#130314,#130315); +#130314 = CARTESIAN_POINT('',(0.E+000,0.2)); +#130315 = VECTOR('',#130316,1.); +#130316 = DIRECTION('',(1.,-3.00059940766E-063)); +#130317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130318 = PCURVE('',#95702,#130319); +#130319 = DEFINITIONAL_REPRESENTATION('',(#130320),#130324); +#130320 = LINE('',#130321,#130322); +#130321 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130322 = VECTOR('',#130323,1.); +#130323 = DIRECTION('',(3.563627120235E-016,-1.)); +#130324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130325 = ORIENTED_EDGE('',*,*,#130181,.T.); +#130326 = ORIENTED_EDGE('',*,*,#130327,.T.); +#130327 = EDGE_CURVE('',#130182,#95715,#130328,.T.); +#130328 = SURFACE_CURVE('',#130329,(#130333,#130340),.PCURVE_S1.); +#130329 = LINE('',#130330,#130331); +#130330 = CARTESIAN_POINT('',(10.527847992439,6.15,0.65)); +#130331 = VECTOR('',#130332,1.); +#130332 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#130333 = PCURVE('',#95730,#130334); +#130334 = DEFINITIONAL_REPRESENTATION('',(#130335),#130339); +#130335 = LINE('',#130336,#130337); +#130336 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130337 = VECTOR('',#130338,1.); +#130338 = DIRECTION('',(1.,-3.00059940766E-063)); +#130339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130340 = PCURVE('',#95758,#130341); +#130341 = DEFINITIONAL_REPRESENTATION('',(#130342),#130346); +#130342 = LINE('',#130343,#130344); +#130343 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130344 = VECTOR('',#130345,1.); +#130345 = DIRECTION('',(-3.563627120235E-016,-1.)); +#130346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130347 = ORIENTED_EDGE('',*,*,#95714,.F.); +#130348 = ADVANCED_FACE('',(#130349),#95702,.T.); +#130349 = FACE_BOUND('',#130350,.T.); +#130350 = EDGE_LOOP('',(#130351,#130372,#130373,#130374,#130375,#130376, + #130397,#130398,#130399,#130400,#130401,#130402)); +#130351 = ORIENTED_EDGE('',*,*,#130352,.F.); +#130352 = EDGE_CURVE('',#130233,#95685,#130353,.T.); +#130353 = SURFACE_CURVE('',#130354,(#130358,#130365),.PCURVE_S1.); +#130354 = LINE('',#130355,#130356); +#130355 = CARTESIAN_POINT('',(10.527847992439,6.35,0.75)); +#130356 = VECTOR('',#130357,1.); +#130357 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#130358 = PCURVE('',#95702,#130359); +#130359 = DEFINITIONAL_REPRESENTATION('',(#130360),#130364); +#130360 = LINE('',#130361,#130362); +#130361 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#130362 = VECTOR('',#130363,1.); +#130363 = DIRECTION('',(3.563627120235E-016,-1.)); +#130364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130365 = PCURVE('',#95784,#130366); +#130366 = DEFINITIONAL_REPRESENTATION('',(#130367),#130371); +#130367 = LINE('',#130368,#130369); +#130368 = CARTESIAN_POINT('',(0.E+000,0.2)); +#130369 = VECTOR('',#130370,1.); +#130370 = DIRECTION('',(-1.,-3.00059940766E-063)); +#130371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130372 = ORIENTED_EDGE('',*,*,#130232,.T.); +#130373 = ORIENTED_EDGE('',*,*,#130058,.T.); +#130374 = ORIENTED_EDGE('',*,*,#129978,.T.); +#130375 = ORIENTED_EDGE('',*,*,#129775,.T.); +#130376 = ORIENTED_EDGE('',*,*,#130377,.F.); +#130377 = EDGE_CURVE('',#129639,#129746,#130378,.T.); +#130378 = SURFACE_CURVE('',#130379,(#130383,#130390),.PCURVE_S1.); +#130379 = LINE('',#130380,#130381); +#130380 = CARTESIAN_POINT('',(11.,6.35,1.159810404338E-002)); +#130381 = VECTOR('',#130382,1.); +#130382 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#130383 = PCURVE('',#95702,#130384); +#130384 = DEFINITIONAL_REPRESENTATION('',(#130385),#130389); +#130385 = LINE('',#130386,#130387); +#130386 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#130387 = VECTOR('',#130388,1.); +#130388 = DIRECTION('',(1.,2.101748079665E-016)); +#130389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130390 = PCURVE('',#129659,#130391); +#130391 = DEFINITIONAL_REPRESENTATION('',(#130392),#130396); +#130392 = LINE('',#130393,#130394); +#130393 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#130394 = VECTOR('',#130395,1.); +#130395 = DIRECTION('',(1.194699204908E-017,1.)); +#130396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130397 = ORIENTED_EDGE('',*,*,#129721,.F.); +#130398 = ORIENTED_EDGE('',*,*,#129849,.F.); +#130399 = ORIENTED_EDGE('',*,*,#130111,.F.); +#130400 = ORIENTED_EDGE('',*,*,#130158,.F.); +#130401 = ORIENTED_EDGE('',*,*,#130305,.T.); +#130402 = ORIENTED_EDGE('',*,*,#95684,.F.); +#130403 = ADVANCED_FACE('',(#130404),#95784,.T.); +#130404 = FACE_BOUND('',#130405,.T.); +#130405 = EDGE_LOOP('',(#130406,#130427,#130428,#130429)); +#130406 = ORIENTED_EDGE('',*,*,#130407,.F.); +#130407 = EDGE_CURVE('',#130256,#95743,#130408,.T.); +#130408 = SURFACE_CURVE('',#130409,(#130413,#130420),.PCURVE_S1.); +#130409 = LINE('',#130410,#130411); +#130410 = CARTESIAN_POINT('',(10.527847992439,6.15,0.75)); +#130411 = VECTOR('',#130412,1.); +#130412 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#130413 = PCURVE('',#95784,#130414); +#130414 = DEFINITIONAL_REPRESENTATION('',(#130415),#130419); +#130415 = LINE('',#130416,#130417); +#130416 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130417 = VECTOR('',#130418,1.); +#130418 = DIRECTION('',(-1.,-3.00059940766E-063)); +#130419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130420 = PCURVE('',#95758,#130421); +#130421 = DEFINITIONAL_REPRESENTATION('',(#130422),#130426); +#130422 = LINE('',#130423,#130424); +#130423 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#130424 = VECTOR('',#130425,1.); +#130425 = DIRECTION('',(-3.563627120235E-016,-1.)); +#130426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130427 = ORIENTED_EDGE('',*,*,#130255,.T.); +#130428 = ORIENTED_EDGE('',*,*,#130352,.T.); +#130429 = ORIENTED_EDGE('',*,*,#95770,.F.); +#130430 = ADVANCED_FACE('',(#130431),#95758,.T.); +#130431 = FACE_BOUND('',#130432,.T.); +#130432 = EDGE_LOOP('',(#130433,#130434,#130435,#130436,#130437,#130438, + #130459,#130460,#130461,#130462,#130463,#130464)); +#130433 = ORIENTED_EDGE('',*,*,#130327,.F.); +#130434 = ORIENTED_EDGE('',*,*,#130203,.T.); +#130435 = ORIENTED_EDGE('',*,*,#130133,.T.); +#130436 = ORIENTED_EDGE('',*,*,#129877,.T.); +#130437 = ORIENTED_EDGE('',*,*,#129671,.T.); +#130438 = ORIENTED_EDGE('',*,*,#130439,.F.); +#130439 = EDGE_CURVE('',#129748,#129637,#130440,.T.); +#130440 = SURFACE_CURVE('',#130441,(#130445,#130452),.PCURVE_S1.); +#130441 = LINE('',#130442,#130443); +#130442 = CARTESIAN_POINT('',(11.,6.15,1.159810404338E-002)); +#130443 = VECTOR('',#130444,1.); +#130444 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#130445 = PCURVE('',#95758,#130446); +#130446 = DEFINITIONAL_REPRESENTATION('',(#130447),#130451); +#130447 = LINE('',#130448,#130449); +#130448 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#130449 = VECTOR('',#130450,1.); +#130450 = DIRECTION('',(1.,-2.101748079665E-016)); +#130451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130452 = PCURVE('',#129659,#130453); +#130453 = DEFINITIONAL_REPRESENTATION('',(#130454),#130458); +#130454 = LINE('',#130455,#130456); +#130455 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#130456 = VECTOR('',#130457,1.); +#130457 = DIRECTION('',(-1.194699204908E-017,-1.)); +#130458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130459 = ORIENTED_EDGE('',*,*,#129825,.F.); +#130460 = ORIENTED_EDGE('',*,*,#129928,.F.); +#130461 = ORIENTED_EDGE('',*,*,#130036,.F.); +#130462 = ORIENTED_EDGE('',*,*,#130277,.F.); +#130463 = ORIENTED_EDGE('',*,*,#130407,.T.); +#130464 = ORIENTED_EDGE('',*,*,#95742,.F.); +#130465 = ADVANCED_FACE('',(#130466),#129659,.T.); +#130466 = FACE_BOUND('',#130467,.T.); +#130467 = EDGE_LOOP('',(#130468,#130469,#130470,#130471)); +#130468 = ORIENTED_EDGE('',*,*,#130377,.T.); +#130469 = ORIENTED_EDGE('',*,*,#129745,.T.); +#130470 = ORIENTED_EDGE('',*,*,#130439,.T.); +#130471 = ORIENTED_EDGE('',*,*,#129636,.T.); +#130472 = ADVANCED_FACE('',(#130473),#130487,.F.); +#130473 = FACE_BOUND('',#130474,.T.); +#130474 = EDGE_LOOP('',(#130475,#130510,#130533,#130560)); +#130475 = ORIENTED_EDGE('',*,*,#130476,.F.); +#130476 = EDGE_CURVE('',#130477,#130479,#130481,.T.); +#130477 = VERTEX_POINT('',#130478); +#130478 = CARTESIAN_POINT('',(11.,5.65,-0.308197125857)); +#130479 = VERTEX_POINT('',#130480); +#130480 = CARTESIAN_POINT('',(11.,5.85,-0.308197125857)); +#130481 = SURFACE_CURVE('',#130482,(#130486,#130498),.PCURVE_S1.); +#130482 = LINE('',#130483,#130484); +#130483 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#130484 = VECTOR('',#130485,1.); +#130485 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130486 = PCURVE('',#130487,#130492); +#130487 = PLANE('',#130488); +#130488 = AXIS2_PLACEMENT_3D('',#130489,#130490,#130491); +#130489 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#128098 = DIRECTION('',(0.E+000,0.E+000,1.)); -#128099 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128100 = DEFINITIONAL_REPRESENTATION('',(#128101),#128105); -#128101 = LINE('',#128102,#128103); -#128102 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#128103 = VECTOR('',#128104,1.); -#128104 = DIRECTION('',(4.440892098501E-016,1.)); -#128105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128106 = PCURVE('',#128107,#128112); -#128107 = PLANE('',#128108); -#128108 = AXIS2_PLACEMENT_3D('',#128109,#128110,#128111); -#128109 = CARTESIAN_POINT('',(11.,5.75,-0.258196742327)); -#128110 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#128111 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128112 = DEFINITIONAL_REPRESENTATION('',(#128113),#128117); -#128113 = LINE('',#128114,#128115); -#128114 = CARTESIAN_POINT('',(-5.75,-5.000038352949E-002)); -#128115 = VECTOR('',#128116,1.); -#128116 = DIRECTION('',(1.,0.E+000)); -#128117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128118 = ORIENTED_EDGE('',*,*,#128119,.F.); -#128119 = EDGE_CURVE('',#128120,#128085,#128122,.T.); -#128120 = VERTEX_POINT('',#128121); -#128121 = CARTESIAN_POINT('',(10.74341632541,5.65,-0.308197125857)); -#128122 = SURFACE_CURVE('',#128123,(#128127,#128134),.PCURVE_S1.); -#128123 = LINE('',#128124,#128125); -#128124 = CARTESIAN_POINT('',(10.74341632541,5.65,-0.308197125857)); -#128125 = VECTOR('',#128126,1.); -#128126 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128127 = PCURVE('',#128095,#128128); -#128128 = DEFINITIONAL_REPRESENTATION('',(#128129),#128133); -#128129 = LINE('',#128130,#128131); -#128130 = CARTESIAN_POINT('',(3.552713678801E-015,5.65)); -#128131 = VECTOR('',#128132,1.); -#128132 = DIRECTION('',(1.,0.E+000)); -#128133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128134 = PCURVE('',#93252,#128135); -#128135 = DEFINITIONAL_REPRESENTATION('',(#128136),#128140); -#128136 = LINE('',#128137,#128138); -#128137 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#128138 = VECTOR('',#128139,1.); -#128139 = DIRECTION('',(0.E+000,1.)); -#128140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128141 = ORIENTED_EDGE('',*,*,#128142,.F.); -#128142 = EDGE_CURVE('',#128143,#128120,#128145,.T.); -#128143 = VERTEX_POINT('',#128144); -#128144 = CARTESIAN_POINT('',(10.74341632541,5.85,-0.308197125857)); -#128145 = SURFACE_CURVE('',#128146,(#128150,#128157),.PCURVE_S1.); -#128146 = LINE('',#128147,#128148); -#128147 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#130490 = DIRECTION('',(0.E+000,0.E+000,1.)); +#130491 = DIRECTION('',(1.,0.E+000,0.E+000)); +#130492 = DEFINITIONAL_REPRESENTATION('',(#130493),#130497); +#130493 = LINE('',#130494,#130495); +#130494 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#130495 = VECTOR('',#130496,1.); +#130496 = DIRECTION('',(4.440892098501E-016,1.)); +#130497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130498 = PCURVE('',#130499,#130504); +#130499 = PLANE('',#130500); +#130500 = AXIS2_PLACEMENT_3D('',#130501,#130502,#130503); +#130501 = CARTESIAN_POINT('',(11.,5.75,-0.258196742327)); +#130502 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#130503 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130504 = DEFINITIONAL_REPRESENTATION('',(#130505),#130509); +#130505 = LINE('',#130506,#130507); +#130506 = CARTESIAN_POINT('',(-5.75,-5.000038352949E-002)); +#130507 = VECTOR('',#130508,1.); +#130508 = DIRECTION('',(1.,0.E+000)); +#130509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130510 = ORIENTED_EDGE('',*,*,#130511,.F.); +#130511 = EDGE_CURVE('',#130512,#130477,#130514,.T.); +#130512 = VERTEX_POINT('',#130513); +#130513 = CARTESIAN_POINT('',(10.74341632541,5.65,-0.308197125857)); +#130514 = SURFACE_CURVE('',#130515,(#130519,#130526),.PCURVE_S1.); +#130515 = LINE('',#130516,#130517); +#130516 = CARTESIAN_POINT('',(10.74341632541,5.65,-0.308197125857)); +#130517 = VECTOR('',#130518,1.); +#130518 = DIRECTION('',(1.,0.E+000,0.E+000)); +#130519 = PCURVE('',#130487,#130520); +#130520 = DEFINITIONAL_REPRESENTATION('',(#130521),#130525); +#130521 = LINE('',#130522,#130523); +#130522 = CARTESIAN_POINT('',(3.552713678801E-015,5.65)); +#130523 = VECTOR('',#130524,1.); +#130524 = DIRECTION('',(1.,0.E+000)); +#130525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130526 = PCURVE('',#95644,#130527); +#130527 = DEFINITIONAL_REPRESENTATION('',(#130528),#130532); +#130528 = LINE('',#130529,#130530); +#130529 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#130530 = VECTOR('',#130531,1.); +#130531 = DIRECTION('',(0.E+000,1.)); +#130532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130533 = ORIENTED_EDGE('',*,*,#130534,.F.); +#130534 = EDGE_CURVE('',#130535,#130512,#130537,.T.); +#130535 = VERTEX_POINT('',#130536); +#130536 = CARTESIAN_POINT('',(10.74341632541,5.85,-0.308197125857)); +#130537 = SURFACE_CURVE('',#130538,(#130542,#130549),.PCURVE_S1.); +#130538 = LINE('',#130539,#130540); +#130539 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#128148 = VECTOR('',#128149,1.); -#128149 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128150 = PCURVE('',#128095,#128151); -#128151 = DEFINITIONAL_REPRESENTATION('',(#128152),#128156); -#128152 = LINE('',#128153,#128154); -#128153 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128154 = VECTOR('',#128155,1.); -#128155 = DIRECTION('',(-4.440892098501E-016,-1.)); -#128156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128157 = PCURVE('',#128158,#128163); -#128158 = CYLINDRICAL_SURFACE('',#128159,0.308574064194); -#128159 = AXIS2_PLACEMENT_3D('',#128160,#128161,#128162); -#128160 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#130540 = VECTOR('',#130541,1.); +#130541 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130542 = PCURVE('',#130487,#130543); +#130543 = DEFINITIONAL_REPRESENTATION('',(#130544),#130548); +#130544 = LINE('',#130545,#130546); +#130545 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130546 = VECTOR('',#130547,1.); +#130547 = DIRECTION('',(-4.440892098501E-016,-1.)); +#130548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130549 = PCURVE('',#130550,#130555); +#130550 = CYLINDRICAL_SURFACE('',#130551,0.308574064194); +#130551 = AXIS2_PLACEMENT_3D('',#130552,#130553,#130554); +#130552 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#128161 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128162 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128163 = DEFINITIONAL_REPRESENTATION('',(#128164),#128167); -#128164 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128165,#128166), +#130553 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130554 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130555 = DEFINITIONAL_REPRESENTATION('',(#130556),#130559); +#130556 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130557,#130558), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#128165 = CARTESIAN_POINT('',(4.761821717947,-5.85)); -#128166 = CARTESIAN_POINT('',(4.761821717947,-5.65)); -#128167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128168 = ORIENTED_EDGE('',*,*,#128169,.T.); -#128169 = EDGE_CURVE('',#128143,#128087,#128170,.T.); -#128170 = SURFACE_CURVE('',#128171,(#128175,#128182),.PCURVE_S1.); -#128171 = LINE('',#128172,#128173); -#128172 = CARTESIAN_POINT('',(10.74341632541,5.85,-0.308197125857)); -#128173 = VECTOR('',#128174,1.); -#128174 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128175 = PCURVE('',#128095,#128176); -#128176 = DEFINITIONAL_REPRESENTATION('',(#128177),#128181); -#128177 = LINE('',#128178,#128179); -#128178 = CARTESIAN_POINT('',(3.552713678801E-015,5.85)); -#128179 = VECTOR('',#128180,1.); -#128180 = DIRECTION('',(1.,0.E+000)); -#128181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128182 = PCURVE('',#93196,#128183); -#128183 = DEFINITIONAL_REPRESENTATION('',(#128184),#128188); -#128184 = LINE('',#128185,#128186); -#128185 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#128186 = VECTOR('',#128187,1.); -#128187 = DIRECTION('',(0.E+000,1.)); -#128188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128189 = ADVANCED_FACE('',(#128190),#128204,.F.); -#128190 = FACE_BOUND('',#128191,.T.); -#128191 = EDGE_LOOP('',(#128192,#128222,#128245,#128272)); -#128192 = ORIENTED_EDGE('',*,*,#128193,.F.); -#128193 = EDGE_CURVE('',#128194,#128196,#128198,.T.); -#128194 = VERTEX_POINT('',#128195); -#128195 = CARTESIAN_POINT('',(11.,5.85,-0.208196358798)); -#128196 = VERTEX_POINT('',#128197); -#128197 = CARTESIAN_POINT('',(11.,5.65,-0.208196358798)); -#128198 = SURFACE_CURVE('',#128199,(#128203,#128215),.PCURVE_S1.); -#128199 = LINE('',#128200,#128201); -#128200 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#128201 = VECTOR('',#128202,1.); -#128202 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128203 = PCURVE('',#128204,#128209); -#128204 = PLANE('',#128205); -#128205 = AXIS2_PLACEMENT_3D('',#128206,#128207,#128208); -#128206 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#130557 = CARTESIAN_POINT('',(4.761821717947,-5.85)); +#130558 = CARTESIAN_POINT('',(4.761821717947,-5.65)); +#130559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130560 = ORIENTED_EDGE('',*,*,#130561,.T.); +#130561 = EDGE_CURVE('',#130535,#130479,#130562,.T.); +#130562 = SURFACE_CURVE('',#130563,(#130567,#130574),.PCURVE_S1.); +#130563 = LINE('',#130564,#130565); +#130564 = CARTESIAN_POINT('',(10.74341632541,5.85,-0.308197125857)); +#130565 = VECTOR('',#130566,1.); +#130566 = DIRECTION('',(1.,0.E+000,0.E+000)); +#130567 = PCURVE('',#130487,#130568); +#130568 = DEFINITIONAL_REPRESENTATION('',(#130569),#130573); +#130569 = LINE('',#130570,#130571); +#130570 = CARTESIAN_POINT('',(3.552713678801E-015,5.85)); +#130571 = VECTOR('',#130572,1.); +#130572 = DIRECTION('',(1.,0.E+000)); +#130573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130574 = PCURVE('',#95588,#130575); +#130575 = DEFINITIONAL_REPRESENTATION('',(#130576),#130580); +#130576 = LINE('',#130577,#130578); +#130577 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#130578 = VECTOR('',#130579,1.); +#130579 = DIRECTION('',(0.E+000,1.)); +#130580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130581 = ADVANCED_FACE('',(#130582),#130596,.F.); +#130582 = FACE_BOUND('',#130583,.T.); +#130583 = EDGE_LOOP('',(#130584,#130614,#130637,#130664)); +#130584 = ORIENTED_EDGE('',*,*,#130585,.F.); +#130585 = EDGE_CURVE('',#130586,#130588,#130590,.T.); +#130586 = VERTEX_POINT('',#130587); +#130587 = CARTESIAN_POINT('',(11.,5.85,-0.208196358798)); +#130588 = VERTEX_POINT('',#130589); +#130589 = CARTESIAN_POINT('',(11.,5.65,-0.208196358798)); +#130590 = SURFACE_CURVE('',#130591,(#130595,#130607),.PCURVE_S1.); +#130591 = LINE('',#130592,#130593); +#130592 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#130593 = VECTOR('',#130594,1.); +#130594 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130595 = PCURVE('',#130596,#130601); +#130596 = PLANE('',#130597); +#130597 = AXIS2_PLACEMENT_3D('',#130598,#130599,#130600); +#130598 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#128207 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#128208 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#128209 = DEFINITIONAL_REPRESENTATION('',(#128210),#128214); -#128210 = LINE('',#128211,#128212); -#128211 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#128212 = VECTOR('',#128213,1.); -#128213 = DIRECTION('',(4.440892098501E-016,-1.)); -#128214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128215 = PCURVE('',#128107,#128216); -#128216 = DEFINITIONAL_REPRESENTATION('',(#128217),#128221); -#128217 = LINE('',#128218,#128219); -#128218 = CARTESIAN_POINT('',(-5.75,5.00003835295E-002)); -#128219 = VECTOR('',#128220,1.); -#128220 = DIRECTION('',(-1.,0.E+000)); -#128221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128222 = ORIENTED_EDGE('',*,*,#128223,.F.); -#128223 = EDGE_CURVE('',#128224,#128194,#128226,.T.); -#128224 = VERTEX_POINT('',#128225); -#128225 = CARTESIAN_POINT('',(10.740726081328,5.85,-0.208196358798)); -#128226 = SURFACE_CURVE('',#128227,(#128231,#128238),.PCURVE_S1.); -#128227 = LINE('',#128228,#128229); -#128228 = CARTESIAN_POINT('',(10.740726081328,5.85,-0.208196358798)); -#128229 = VECTOR('',#128230,1.); -#128230 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128231 = PCURVE('',#128204,#128232); -#128232 = DEFINITIONAL_REPRESENTATION('',(#128233),#128237); -#128233 = LINE('',#128234,#128235); -#128234 = CARTESIAN_POINT('',(-5.329070518201E-015,5.85)); -#128235 = VECTOR('',#128236,1.); -#128236 = DIRECTION('',(-1.,0.E+000)); -#128237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128238 = PCURVE('',#93196,#128239); -#128239 = DEFINITIONAL_REPRESENTATION('',(#128240),#128244); -#128240 = LINE('',#128241,#128242); -#128241 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#128242 = VECTOR('',#128243,1.); -#128243 = DIRECTION('',(0.E+000,1.)); -#128244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128245 = ORIENTED_EDGE('',*,*,#128246,.F.); -#128246 = EDGE_CURVE('',#128247,#128224,#128249,.T.); -#128247 = VERTEX_POINT('',#128248); -#128248 = CARTESIAN_POINT('',(10.740726081328,5.65,-0.208196358798)); -#128249 = SURFACE_CURVE('',#128250,(#128254,#128261),.PCURVE_S1.); -#128250 = LINE('',#128251,#128252); -#128251 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#130599 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130600 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#130601 = DEFINITIONAL_REPRESENTATION('',(#130602),#130606); +#130602 = LINE('',#130603,#130604); +#130603 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#130604 = VECTOR('',#130605,1.); +#130605 = DIRECTION('',(4.440892098501E-016,-1.)); +#130606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130607 = PCURVE('',#130499,#130608); +#130608 = DEFINITIONAL_REPRESENTATION('',(#130609),#130613); +#130609 = LINE('',#130610,#130611); +#130610 = CARTESIAN_POINT('',(-5.75,5.00003835295E-002)); +#130611 = VECTOR('',#130612,1.); +#130612 = DIRECTION('',(-1.,0.E+000)); +#130613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130614 = ORIENTED_EDGE('',*,*,#130615,.F.); +#130615 = EDGE_CURVE('',#130616,#130586,#130618,.T.); +#130616 = VERTEX_POINT('',#130617); +#130617 = CARTESIAN_POINT('',(10.740726081328,5.85,-0.208196358798)); +#130618 = SURFACE_CURVE('',#130619,(#130623,#130630),.PCURVE_S1.); +#130619 = LINE('',#130620,#130621); +#130620 = CARTESIAN_POINT('',(10.740726081328,5.85,-0.208196358798)); +#130621 = VECTOR('',#130622,1.); +#130622 = DIRECTION('',(1.,0.E+000,0.E+000)); +#130623 = PCURVE('',#130596,#130624); +#130624 = DEFINITIONAL_REPRESENTATION('',(#130625),#130629); +#130625 = LINE('',#130626,#130627); +#130626 = CARTESIAN_POINT('',(-5.329070518201E-015,5.85)); +#130627 = VECTOR('',#130628,1.); +#130628 = DIRECTION('',(-1.,0.E+000)); +#130629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130630 = PCURVE('',#95588,#130631); +#130631 = DEFINITIONAL_REPRESENTATION('',(#130632),#130636); +#130632 = LINE('',#130633,#130634); +#130633 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#130634 = VECTOR('',#130635,1.); +#130635 = DIRECTION('',(0.E+000,1.)); +#130636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130637 = ORIENTED_EDGE('',*,*,#130638,.F.); +#130638 = EDGE_CURVE('',#130639,#130616,#130641,.T.); +#130639 = VERTEX_POINT('',#130640); +#130640 = CARTESIAN_POINT('',(10.740726081328,5.65,-0.208196358798)); +#130641 = SURFACE_CURVE('',#130642,(#130646,#130653),.PCURVE_S1.); +#130642 = LINE('',#130643,#130644); +#130643 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#128252 = VECTOR('',#128253,1.); -#128253 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128254 = PCURVE('',#128204,#128255); -#128255 = DEFINITIONAL_REPRESENTATION('',(#128256),#128260); -#128256 = LINE('',#128257,#128258); -#128257 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128258 = VECTOR('',#128259,1.); -#128259 = DIRECTION('',(-4.440892098501E-016,1.)); -#128260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128261 = PCURVE('',#128262,#128267); -#128262 = CYLINDRICAL_SURFACE('',#128263,0.208574704164); -#128263 = AXIS2_PLACEMENT_3D('',#128264,#128265,#128266); -#128264 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#130644 = VECTOR('',#130645,1.); +#130645 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130646 = PCURVE('',#130596,#130647); +#130647 = DEFINITIONAL_REPRESENTATION('',(#130648),#130652); +#130648 = LINE('',#130649,#130650); +#130649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130650 = VECTOR('',#130651,1.); +#130651 = DIRECTION('',(-4.440892098501E-016,1.)); +#130652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130653 = PCURVE('',#130654,#130659); +#130654 = CYLINDRICAL_SURFACE('',#130655,0.208574704164); +#130655 = AXIS2_PLACEMENT_3D('',#130656,#130657,#130658); +#130656 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#128265 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128266 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128267 = DEFINITIONAL_REPRESENTATION('',(#128268),#128271); -#128268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128269,#128270), +#130657 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130658 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130659 = DEFINITIONAL_REPRESENTATION('',(#130660),#130663); +#130660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130661,#130662), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#128269 = CARTESIAN_POINT('',(4.772630242227,-5.65)); -#128270 = CARTESIAN_POINT('',(4.772630242227,-5.85)); -#128271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128272 = ORIENTED_EDGE('',*,*,#128273,.T.); -#128273 = EDGE_CURVE('',#128247,#128196,#128274,.T.); -#128274 = SURFACE_CURVE('',#128275,(#128279,#128286),.PCURVE_S1.); -#128275 = LINE('',#128276,#128277); -#128276 = CARTESIAN_POINT('',(10.740726081328,5.65,-0.208196358798)); -#128277 = VECTOR('',#128278,1.); -#128278 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128279 = PCURVE('',#128204,#128280); -#128280 = DEFINITIONAL_REPRESENTATION('',(#128281),#128285); -#128281 = LINE('',#128282,#128283); -#128282 = CARTESIAN_POINT('',(-1.7763568394E-015,5.65)); -#128283 = VECTOR('',#128284,1.); -#128284 = DIRECTION('',(-1.,0.E+000)); -#128285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128286 = PCURVE('',#93252,#128287); -#128287 = DEFINITIONAL_REPRESENTATION('',(#128288),#128292); -#128288 = LINE('',#128289,#128290); -#128289 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#128290 = VECTOR('',#128291,1.); -#128291 = DIRECTION('',(0.E+000,1.)); -#128292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128293 = ADVANCED_FACE('',(#128294),#128158,.T.); -#128294 = FACE_BOUND('',#128295,.T.); -#128295 = EDGE_LOOP('',(#128296,#128323,#128324,#128347)); -#128296 = ORIENTED_EDGE('',*,*,#128297,.T.); -#128297 = EDGE_CURVE('',#128298,#128143,#128300,.T.); -#128298 = VERTEX_POINT('',#128299); -#128299 = CARTESIAN_POINT('',(10.419594812019,5.85,0.E+000)); -#128300 = SURFACE_CURVE('',#128301,(#128306,#128312),.PCURVE_S1.); -#128301 = CIRCLE('',#128302,0.308574064194); -#128302 = AXIS2_PLACEMENT_3D('',#128303,#128304,#128305); -#128303 = CARTESIAN_POINT('',(10.728168876214,5.85,2.640924866458E-017) - ); -#128304 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128305 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128306 = PCURVE('',#128158,#128307); -#128307 = DEFINITIONAL_REPRESENTATION('',(#128308),#128311); -#128308 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128309,#128310), +#130661 = CARTESIAN_POINT('',(4.772630242227,-5.65)); +#130662 = CARTESIAN_POINT('',(4.772630242227,-5.85)); +#130663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130664 = ORIENTED_EDGE('',*,*,#130665,.T.); +#130665 = EDGE_CURVE('',#130639,#130588,#130666,.T.); +#130666 = SURFACE_CURVE('',#130667,(#130671,#130678),.PCURVE_S1.); +#130667 = LINE('',#130668,#130669); +#130668 = CARTESIAN_POINT('',(10.740726081328,5.65,-0.208196358798)); +#130669 = VECTOR('',#130670,1.); +#130670 = DIRECTION('',(1.,0.E+000,0.E+000)); +#130671 = PCURVE('',#130596,#130672); +#130672 = DEFINITIONAL_REPRESENTATION('',(#130673),#130677); +#130673 = LINE('',#130674,#130675); +#130674 = CARTESIAN_POINT('',(-1.7763568394E-015,5.65)); +#130675 = VECTOR('',#130676,1.); +#130676 = DIRECTION('',(-1.,0.E+000)); +#130677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130678 = PCURVE('',#95644,#130679); +#130679 = DEFINITIONAL_REPRESENTATION('',(#130680),#130684); +#130680 = LINE('',#130681,#130682); +#130681 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#130682 = VECTOR('',#130683,1.); +#130683 = DIRECTION('',(0.E+000,1.)); +#130684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130685 = ADVANCED_FACE('',(#130686),#130550,.T.); +#130686 = FACE_BOUND('',#130687,.T.); +#130687 = EDGE_LOOP('',(#130688,#130715,#130716,#130739)); +#130688 = ORIENTED_EDGE('',*,*,#130689,.T.); +#130689 = EDGE_CURVE('',#130690,#130535,#130692,.T.); +#130690 = VERTEX_POINT('',#130691); +#130691 = CARTESIAN_POINT('',(10.419594812019,5.85,0.E+000)); +#130692 = SURFACE_CURVE('',#130693,(#130698,#130704),.PCURVE_S1.); +#130693 = CIRCLE('',#130694,0.308574064194); +#130694 = AXIS2_PLACEMENT_3D('',#130695,#130696,#130697); +#130695 = CARTESIAN_POINT('',(10.728168876214,5.85,2.640924866458E-017) + ); +#130696 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130697 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130698 = PCURVE('',#130550,#130699); +#130699 = DEFINITIONAL_REPRESENTATION('',(#130700),#130703); +#130700 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130701,#130702), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#128309 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#128310 = CARTESIAN_POINT('',(4.761821717947,-5.85)); -#128311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130701 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#130702 = CARTESIAN_POINT('',(4.761821717947,-5.85)); +#130703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128312 = PCURVE('',#93196,#128313); -#128313 = DEFINITIONAL_REPRESENTATION('',(#128314),#128322); -#128314 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128315,#128316,#128317, - #128318,#128319,#128320,#128321),.UNSPECIFIED.,.T.,.F.) +#130704 = PCURVE('',#95588,#130705); +#130705 = DEFINITIONAL_REPRESENTATION('',(#130706),#130714); +#130706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130707,#130708,#130709, + #130710,#130711,#130712,#130713),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#128315 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#128316 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#128317 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#128318 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#128319 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#128320 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#128321 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#128322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128323 = ORIENTED_EDGE('',*,*,#128142,.T.); -#128324 = ORIENTED_EDGE('',*,*,#128325,.F.); -#128325 = EDGE_CURVE('',#128326,#128120,#128328,.T.); -#128326 = VERTEX_POINT('',#128327); -#128327 = CARTESIAN_POINT('',(10.419594812019,5.65,0.E+000)); -#128328 = SURFACE_CURVE('',#128329,(#128334,#128340),.PCURVE_S1.); -#128329 = CIRCLE('',#128330,0.308574064194); -#128330 = AXIS2_PLACEMENT_3D('',#128331,#128332,#128333); -#128331 = CARTESIAN_POINT('',(10.728168876214,5.65,2.640924866458E-017) - ); -#128332 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128333 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128334 = PCURVE('',#128158,#128335); -#128335 = DEFINITIONAL_REPRESENTATION('',(#128336),#128339); -#128336 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128337,#128338), +#130707 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#130708 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#130709 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#130710 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#130711 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#130712 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#130713 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#130714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130715 = ORIENTED_EDGE('',*,*,#130534,.T.); +#130716 = ORIENTED_EDGE('',*,*,#130717,.F.); +#130717 = EDGE_CURVE('',#130718,#130512,#130720,.T.); +#130718 = VERTEX_POINT('',#130719); +#130719 = CARTESIAN_POINT('',(10.419594812019,5.65,0.E+000)); +#130720 = SURFACE_CURVE('',#130721,(#130726,#130732),.PCURVE_S1.); +#130721 = CIRCLE('',#130722,0.308574064194); +#130722 = AXIS2_PLACEMENT_3D('',#130723,#130724,#130725); +#130723 = CARTESIAN_POINT('',(10.728168876214,5.65,2.640924866458E-017) + ); +#130724 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130725 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130726 = PCURVE('',#130550,#130727); +#130727 = DEFINITIONAL_REPRESENTATION('',(#130728),#130731); +#130728 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130729,#130730), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#128337 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#128338 = CARTESIAN_POINT('',(4.761821717947,-5.65)); -#128339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130729 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#130730 = CARTESIAN_POINT('',(4.761821717947,-5.65)); +#130731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128340 = PCURVE('',#93252,#128341); -#128341 = DEFINITIONAL_REPRESENTATION('',(#128342),#128346); -#128342 = CIRCLE('',#128343,0.308574064194); -#128343 = AXIS2_PLACEMENT_2D('',#128344,#128345); -#128344 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#128345 = DIRECTION('',(0.E+000,1.)); -#128346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130732 = PCURVE('',#95644,#130733); +#130733 = DEFINITIONAL_REPRESENTATION('',(#130734),#130738); +#130734 = CIRCLE('',#130735,0.308574064194); +#130735 = AXIS2_PLACEMENT_2D('',#130736,#130737); +#130736 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#130737 = DIRECTION('',(0.E+000,1.)); +#130738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128347 = ORIENTED_EDGE('',*,*,#128348,.T.); -#128348 = EDGE_CURVE('',#128326,#128298,#128349,.T.); -#128349 = SURFACE_CURVE('',#128350,(#128354,#128360),.PCURVE_S1.); -#128350 = LINE('',#128351,#128352); -#128351 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#130739 = ORIENTED_EDGE('',*,*,#130740,.T.); +#130740 = EDGE_CURVE('',#130718,#130690,#130741,.T.); +#130741 = SURFACE_CURVE('',#130742,(#130746,#130752),.PCURVE_S1.); +#130742 = LINE('',#130743,#130744); +#130743 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#128352 = VECTOR('',#128353,1.); -#128353 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128354 = PCURVE('',#128158,#128355); -#128355 = DEFINITIONAL_REPRESENTATION('',(#128356),#128359); -#128356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128357,#128358), +#130744 = VECTOR('',#130745,1.); +#130745 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130746 = PCURVE('',#130550,#130747); +#130747 = DEFINITIONAL_REPRESENTATION('',(#130748),#130751); +#130748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130749,#130750), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#128357 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#128358 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#128359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130749 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#130750 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#130751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128360 = PCURVE('',#128361,#128366); -#128361 = PLANE('',#128362); -#128362 = AXIS2_PLACEMENT_3D('',#128363,#128364,#128365); -#128363 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#130752 = PCURVE('',#130753,#130758); +#130753 = PLANE('',#130754); +#130754 = AXIS2_PLACEMENT_3D('',#130755,#130756,#130757); +#130755 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#128364 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128365 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128366 = DEFINITIONAL_REPRESENTATION('',(#128367),#128371); -#128367 = LINE('',#128368,#128369); -#128368 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#128369 = VECTOR('',#128370,1.); -#128370 = DIRECTION('',(-1.,0.E+000)); -#128371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128372 = ADVANCED_FACE('',(#128373),#128262,.F.); -#128373 = FACE_BOUND('',#128374,.F.); -#128374 = EDGE_LOOP('',(#128375,#128398,#128425,#128450)); -#128375 = ORIENTED_EDGE('',*,*,#128376,.F.); -#128376 = EDGE_CURVE('',#128377,#128247,#128379,.T.); -#128377 = VERTEX_POINT('',#128378); -#128378 = CARTESIAN_POINT('',(10.51959417205,5.65,0.E+000)); -#128379 = SURFACE_CURVE('',#128380,(#128385,#128391),.PCURVE_S1.); -#128380 = CIRCLE('',#128381,0.208574704164); -#128381 = AXIS2_PLACEMENT_3D('',#128382,#128383,#128384); -#128382 = CARTESIAN_POINT('',(10.728168876214,5.65,2.640924866458E-017) - ); -#128383 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128384 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128385 = PCURVE('',#128262,#128386); -#128386 = DEFINITIONAL_REPRESENTATION('',(#128387),#128390); -#128387 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128388,#128389), +#130756 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130757 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130758 = DEFINITIONAL_REPRESENTATION('',(#130759),#130763); +#130759 = LINE('',#130760,#130761); +#130760 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#130761 = VECTOR('',#130762,1.); +#130762 = DIRECTION('',(-1.,0.E+000)); +#130763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130764 = ADVANCED_FACE('',(#130765),#130654,.F.); +#130765 = FACE_BOUND('',#130766,.F.); +#130766 = EDGE_LOOP('',(#130767,#130790,#130817,#130842)); +#130767 = ORIENTED_EDGE('',*,*,#130768,.F.); +#130768 = EDGE_CURVE('',#130769,#130639,#130771,.T.); +#130769 = VERTEX_POINT('',#130770); +#130770 = CARTESIAN_POINT('',(10.51959417205,5.65,0.E+000)); +#130771 = SURFACE_CURVE('',#130772,(#130777,#130783),.PCURVE_S1.); +#130772 = CIRCLE('',#130773,0.208574704164); +#130773 = AXIS2_PLACEMENT_3D('',#130774,#130775,#130776); +#130774 = CARTESIAN_POINT('',(10.728168876214,5.65,2.640924866458E-017) + ); +#130775 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130776 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130777 = PCURVE('',#130654,#130778); +#130778 = DEFINITIONAL_REPRESENTATION('',(#130779),#130782); +#130779 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130780,#130781), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#128388 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#128389 = CARTESIAN_POINT('',(4.772630242227,-5.65)); -#128390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130780 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#130781 = CARTESIAN_POINT('',(4.772630242227,-5.65)); +#130782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128391 = PCURVE('',#93252,#128392); -#128392 = DEFINITIONAL_REPRESENTATION('',(#128393),#128397); -#128393 = CIRCLE('',#128394,0.208574704164); -#128394 = AXIS2_PLACEMENT_2D('',#128395,#128396); -#128395 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#128396 = DIRECTION('',(0.E+000,1.)); -#128397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130783 = PCURVE('',#95644,#130784); +#130784 = DEFINITIONAL_REPRESENTATION('',(#130785),#130789); +#130785 = CIRCLE('',#130786,0.208574704164); +#130786 = AXIS2_PLACEMENT_2D('',#130787,#130788); +#130787 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#130788 = DIRECTION('',(0.E+000,1.)); +#130789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128398 = ORIENTED_EDGE('',*,*,#128399,.F.); -#128399 = EDGE_CURVE('',#128400,#128377,#128402,.T.); -#128400 = VERTEX_POINT('',#128401); -#128401 = CARTESIAN_POINT('',(10.51959417205,5.85,0.E+000)); -#128402 = SURFACE_CURVE('',#128403,(#128407,#128413),.PCURVE_S1.); -#128403 = LINE('',#128404,#128405); -#128404 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#130790 = ORIENTED_EDGE('',*,*,#130791,.F.); +#130791 = EDGE_CURVE('',#130792,#130769,#130794,.T.); +#130792 = VERTEX_POINT('',#130793); +#130793 = CARTESIAN_POINT('',(10.51959417205,5.85,0.E+000)); +#130794 = SURFACE_CURVE('',#130795,(#130799,#130805),.PCURVE_S1.); +#130795 = LINE('',#130796,#130797); +#130796 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#128405 = VECTOR('',#128406,1.); -#128406 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128407 = PCURVE('',#128262,#128408); -#128408 = DEFINITIONAL_REPRESENTATION('',(#128409),#128412); -#128409 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128410,#128411), +#130797 = VECTOR('',#130798,1.); +#130798 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130799 = PCURVE('',#130654,#130800); +#130800 = DEFINITIONAL_REPRESENTATION('',(#130801),#130804); +#130801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130802,#130803), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#128410 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#128411 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#128412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130802 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#130803 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#130804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128413 = PCURVE('',#128414,#128419); -#128414 = PLANE('',#128415); -#128415 = AXIS2_PLACEMENT_3D('',#128416,#128417,#128418); -#128416 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#130805 = PCURVE('',#130806,#130811); +#130806 = PLANE('',#130807); +#130807 = AXIS2_PLACEMENT_3D('',#130808,#130809,#130810); +#130808 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#128417 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128418 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128419 = DEFINITIONAL_REPRESENTATION('',(#128420),#128424); -#128420 = LINE('',#128421,#128422); -#128421 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#128422 = VECTOR('',#128423,1.); -#128423 = DIRECTION('',(-1.,0.E+000)); -#128424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128425 = ORIENTED_EDGE('',*,*,#128426,.T.); -#128426 = EDGE_CURVE('',#128400,#128224,#128427,.T.); -#128427 = SURFACE_CURVE('',#128428,(#128433,#128439),.PCURVE_S1.); -#128428 = CIRCLE('',#128429,0.208574704164); -#128429 = AXIS2_PLACEMENT_3D('',#128430,#128431,#128432); -#128430 = CARTESIAN_POINT('',(10.728168876214,5.85,2.640924866458E-017) - ); -#128431 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128432 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#128433 = PCURVE('',#128262,#128434); -#128434 = DEFINITIONAL_REPRESENTATION('',(#128435),#128438); -#128435 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128436,#128437), +#130809 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130810 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130811 = DEFINITIONAL_REPRESENTATION('',(#130812),#130816); +#130812 = LINE('',#130813,#130814); +#130813 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#130814 = VECTOR('',#130815,1.); +#130815 = DIRECTION('',(-1.,0.E+000)); +#130816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130817 = ORIENTED_EDGE('',*,*,#130818,.T.); +#130818 = EDGE_CURVE('',#130792,#130616,#130819,.T.); +#130819 = SURFACE_CURVE('',#130820,(#130825,#130831),.PCURVE_S1.); +#130820 = CIRCLE('',#130821,0.208574704164); +#130821 = AXIS2_PLACEMENT_3D('',#130822,#130823,#130824); +#130822 = CARTESIAN_POINT('',(10.728168876214,5.85,2.640924866458E-017) + ); +#130823 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130824 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#130825 = PCURVE('',#130654,#130826); +#130826 = DEFINITIONAL_REPRESENTATION('',(#130827),#130830); +#130827 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130828,#130829), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#128436 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#128437 = CARTESIAN_POINT('',(4.772630242227,-5.85)); -#128438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#130828 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#130829 = CARTESIAN_POINT('',(4.772630242227,-5.85)); +#130830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128439 = PCURVE('',#93196,#128440); -#128440 = DEFINITIONAL_REPRESENTATION('',(#128441),#128449); -#128441 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128442,#128443,#128444, - #128445,#128446,#128447,#128448),.UNSPECIFIED.,.T.,.F.) +#130831 = PCURVE('',#95588,#130832); +#130832 = DEFINITIONAL_REPRESENTATION('',(#130833),#130841); +#130833 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130834,#130835,#130836, + #130837,#130838,#130839,#130840),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#128442 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#128443 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#128444 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#128445 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#128446 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#128447 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#128448 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#128449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128450 = ORIENTED_EDGE('',*,*,#128246,.F.); -#128451 = ADVANCED_FACE('',(#128452),#128414,.T.); -#128452 = FACE_BOUND('',#128453,.T.); -#128453 = EDGE_LOOP('',(#128454,#128483,#128504,#128505)); -#128454 = ORIENTED_EDGE('',*,*,#128455,.T.); -#128455 = EDGE_CURVE('',#128456,#128458,#128460,.T.); -#128456 = VERTEX_POINT('',#128457); -#128457 = CARTESIAN_POINT('',(10.51959417205,5.85,0.530776333563)); -#128458 = VERTEX_POINT('',#128459); -#128459 = CARTESIAN_POINT('',(10.51959417205,5.65,0.530776333563)); -#128460 = SURFACE_CURVE('',#128461,(#128465,#128472),.PCURVE_S1.); -#128461 = LINE('',#128462,#128463); -#128462 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#130834 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#130835 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#130836 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#130837 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#130838 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#130839 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#130840 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#130841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130842 = ORIENTED_EDGE('',*,*,#130638,.F.); +#130843 = ADVANCED_FACE('',(#130844),#130806,.T.); +#130844 = FACE_BOUND('',#130845,.T.); +#130845 = EDGE_LOOP('',(#130846,#130875,#130896,#130897)); +#130846 = ORIENTED_EDGE('',*,*,#130847,.T.); +#130847 = EDGE_CURVE('',#130848,#130850,#130852,.T.); +#130848 = VERTEX_POINT('',#130849); +#130849 = CARTESIAN_POINT('',(10.51959417205,5.85,0.530776333563)); +#130850 = VERTEX_POINT('',#130851); +#130851 = CARTESIAN_POINT('',(10.51959417205,5.65,0.530776333563)); +#130852 = SURFACE_CURVE('',#130853,(#130857,#130864),.PCURVE_S1.); +#130853 = LINE('',#130854,#130855); +#130854 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#128463 = VECTOR('',#128464,1.); -#128464 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128465 = PCURVE('',#128414,#128466); -#128466 = DEFINITIONAL_REPRESENTATION('',(#128467),#128471); -#128467 = LINE('',#128468,#128469); -#128468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128469 = VECTOR('',#128470,1.); -#128470 = DIRECTION('',(-1.,0.E+000)); -#128471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128472 = PCURVE('',#128473,#128478); -#128473 = CYLINDRICAL_SURFACE('',#128474,0.2192697516); -#128474 = AXIS2_PLACEMENT_3D('',#128475,#128476,#128477); -#128475 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#130855 = VECTOR('',#130856,1.); +#130856 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#130857 = PCURVE('',#130806,#130858); +#130858 = DEFINITIONAL_REPRESENTATION('',(#130859),#130863); +#130859 = LINE('',#130860,#130861); +#130860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130861 = VECTOR('',#130862,1.); +#130862 = DIRECTION('',(-1.,0.E+000)); +#130863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130864 = PCURVE('',#130865,#130870); +#130865 = CYLINDRICAL_SURFACE('',#130866,0.2192697516); +#130866 = AXIS2_PLACEMENT_3D('',#130867,#130868,#130869); +#130867 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#128476 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128477 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128478 = DEFINITIONAL_REPRESENTATION('',(#128479),#128482); -#128479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128480,#128481), +#130868 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130869 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130870 = DEFINITIONAL_REPRESENTATION('',(#130871),#130874); +#130871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130872,#130873), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#128480 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#128481 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#128482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128483 = ORIENTED_EDGE('',*,*,#128484,.T.); -#128484 = EDGE_CURVE('',#128458,#128377,#128485,.T.); -#128485 = SURFACE_CURVE('',#128486,(#128490,#128497),.PCURVE_S1.); -#128486 = LINE('',#128487,#128488); -#128487 = CARTESIAN_POINT('',(10.51959417205,5.65,0.530776333563)); -#128488 = VECTOR('',#128489,1.); -#128489 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#128490 = PCURVE('',#128414,#128491); -#128491 = DEFINITIONAL_REPRESENTATION('',(#128492),#128496); -#128492 = LINE('',#128493,#128494); -#128493 = CARTESIAN_POINT('',(5.65,0.E+000)); -#128494 = VECTOR('',#128495,1.); -#128495 = DIRECTION('',(0.E+000,-1.)); -#128496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128497 = PCURVE('',#93252,#128498); -#128498 = DEFINITIONAL_REPRESENTATION('',(#128499),#128503); -#128499 = LINE('',#128500,#128501); -#128500 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); -#128501 = VECTOR('',#128502,1.); -#128502 = DIRECTION('',(1.,0.E+000)); -#128503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128504 = ORIENTED_EDGE('',*,*,#128399,.F.); -#128505 = ORIENTED_EDGE('',*,*,#128506,.F.); -#128506 = EDGE_CURVE('',#128456,#128400,#128507,.T.); -#128507 = SURFACE_CURVE('',#128508,(#128512,#128519),.PCURVE_S1.); -#128508 = LINE('',#128509,#128510); -#128509 = CARTESIAN_POINT('',(10.51959417205,5.85,0.530776333563)); -#128510 = VECTOR('',#128511,1.); -#128511 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#128512 = PCURVE('',#128414,#128513); -#128513 = DEFINITIONAL_REPRESENTATION('',(#128514),#128518); -#128514 = LINE('',#128515,#128516); -#128515 = CARTESIAN_POINT('',(5.85,0.E+000)); -#128516 = VECTOR('',#128517,1.); -#128517 = DIRECTION('',(0.E+000,-1.)); -#128518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128519 = PCURVE('',#93196,#128520); -#128520 = DEFINITIONAL_REPRESENTATION('',(#128521),#128525); -#128521 = LINE('',#128522,#128523); -#128522 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); -#128523 = VECTOR('',#128524,1.); -#128524 = DIRECTION('',(-1.,0.E+000)); -#128525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128526 = ADVANCED_FACE('',(#128527),#128361,.T.); -#128527 = FACE_BOUND('',#128528,.T.); -#128528 = EDGE_LOOP('',(#128529,#128558,#128579,#128580)); -#128529 = ORIENTED_EDGE('',*,*,#128530,.T.); -#128530 = EDGE_CURVE('',#128531,#128533,#128535,.T.); -#128531 = VERTEX_POINT('',#128532); -#128532 = CARTESIAN_POINT('',(10.419594812019,5.65,0.530776333563)); -#128533 = VERTEX_POINT('',#128534); -#128534 = CARTESIAN_POINT('',(10.419594812019,5.85,0.530776333563)); -#128535 = SURFACE_CURVE('',#128536,(#128540,#128547),.PCURVE_S1.); -#128536 = LINE('',#128537,#128538); -#128537 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#130872 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#130873 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#130874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130875 = ORIENTED_EDGE('',*,*,#130876,.T.); +#130876 = EDGE_CURVE('',#130850,#130769,#130877,.T.); +#130877 = SURFACE_CURVE('',#130878,(#130882,#130889),.PCURVE_S1.); +#130878 = LINE('',#130879,#130880); +#130879 = CARTESIAN_POINT('',(10.51959417205,5.65,0.530776333563)); +#130880 = VECTOR('',#130881,1.); +#130881 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130882 = PCURVE('',#130806,#130883); +#130883 = DEFINITIONAL_REPRESENTATION('',(#130884),#130888); +#130884 = LINE('',#130885,#130886); +#130885 = CARTESIAN_POINT('',(5.65,0.E+000)); +#130886 = VECTOR('',#130887,1.); +#130887 = DIRECTION('',(0.E+000,-1.)); +#130888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130889 = PCURVE('',#95644,#130890); +#130890 = DEFINITIONAL_REPRESENTATION('',(#130891),#130895); +#130891 = LINE('',#130892,#130893); +#130892 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); +#130893 = VECTOR('',#130894,1.); +#130894 = DIRECTION('',(1.,0.E+000)); +#130895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130896 = ORIENTED_EDGE('',*,*,#130791,.F.); +#130897 = ORIENTED_EDGE('',*,*,#130898,.F.); +#130898 = EDGE_CURVE('',#130848,#130792,#130899,.T.); +#130899 = SURFACE_CURVE('',#130900,(#130904,#130911),.PCURVE_S1.); +#130900 = LINE('',#130901,#130902); +#130901 = CARTESIAN_POINT('',(10.51959417205,5.85,0.530776333563)); +#130902 = VECTOR('',#130903,1.); +#130903 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130904 = PCURVE('',#130806,#130905); +#130905 = DEFINITIONAL_REPRESENTATION('',(#130906),#130910); +#130906 = LINE('',#130907,#130908); +#130907 = CARTESIAN_POINT('',(5.85,0.E+000)); +#130908 = VECTOR('',#130909,1.); +#130909 = DIRECTION('',(0.E+000,-1.)); +#130910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130911 = PCURVE('',#95588,#130912); +#130912 = DEFINITIONAL_REPRESENTATION('',(#130913),#130917); +#130913 = LINE('',#130914,#130915); +#130914 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); +#130915 = VECTOR('',#130916,1.); +#130916 = DIRECTION('',(-1.,0.E+000)); +#130917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130918 = ADVANCED_FACE('',(#130919),#130753,.T.); +#130919 = FACE_BOUND('',#130920,.T.); +#130920 = EDGE_LOOP('',(#130921,#130950,#130971,#130972)); +#130921 = ORIENTED_EDGE('',*,*,#130922,.T.); +#130922 = EDGE_CURVE('',#130923,#130925,#130927,.T.); +#130923 = VERTEX_POINT('',#130924); +#130924 = CARTESIAN_POINT('',(10.419594812019,5.65,0.530776333563)); +#130925 = VERTEX_POINT('',#130926); +#130926 = CARTESIAN_POINT('',(10.419594812019,5.85,0.530776333563)); +#130927 = SURFACE_CURVE('',#130928,(#130932,#130939),.PCURVE_S1.); +#130928 = LINE('',#130929,#130930); +#130929 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#128538 = VECTOR('',#128539,1.); -#128539 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128540 = PCURVE('',#128361,#128541); -#128541 = DEFINITIONAL_REPRESENTATION('',(#128542),#128546); -#128542 = LINE('',#128543,#128544); -#128543 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128544 = VECTOR('',#128545,1.); -#128545 = DIRECTION('',(-1.,0.E+000)); -#128546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128547 = PCURVE('',#128548,#128553); -#128548 = CYLINDRICAL_SURFACE('',#128549,0.119270391569); -#128549 = AXIS2_PLACEMENT_3D('',#128550,#128551,#128552); -#128550 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#130930 = VECTOR('',#130931,1.); +#130931 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130932 = PCURVE('',#130753,#130933); +#130933 = DEFINITIONAL_REPRESENTATION('',(#130934),#130938); +#130934 = LINE('',#130935,#130936); +#130935 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#130936 = VECTOR('',#130937,1.); +#130937 = DIRECTION('',(-1.,0.E+000)); +#130938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130939 = PCURVE('',#130940,#130945); +#130940 = CYLINDRICAL_SURFACE('',#130941,0.119270391569); +#130941 = AXIS2_PLACEMENT_3D('',#130942,#130943,#130944); +#130942 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#128551 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128552 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128553 = DEFINITIONAL_REPRESENTATION('',(#128554),#128557); -#128554 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128555,#128556), +#130943 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#130944 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#130945 = DEFINITIONAL_REPRESENTATION('',(#130946),#130949); +#130946 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130947,#130948), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#128555 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#128556 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#128557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128558 = ORIENTED_EDGE('',*,*,#128559,.T.); -#128559 = EDGE_CURVE('',#128533,#128298,#128560,.T.); -#128560 = SURFACE_CURVE('',#128561,(#128565,#128572),.PCURVE_S1.); -#128561 = LINE('',#128562,#128563); -#128562 = CARTESIAN_POINT('',(10.419594812019,5.85,0.530776333563)); -#128563 = VECTOR('',#128564,1.); -#128564 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#128565 = PCURVE('',#128361,#128566); -#128566 = DEFINITIONAL_REPRESENTATION('',(#128567),#128571); -#128567 = LINE('',#128568,#128569); -#128568 = CARTESIAN_POINT('',(-5.85,0.E+000)); -#128569 = VECTOR('',#128570,1.); -#128570 = DIRECTION('',(0.E+000,-1.)); -#128571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128572 = PCURVE('',#93196,#128573); -#128573 = DEFINITIONAL_REPRESENTATION('',(#128574),#128578); -#128574 = LINE('',#128575,#128576); -#128575 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#128576 = VECTOR('',#128577,1.); -#128577 = DIRECTION('',(-1.,0.E+000)); -#128578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128579 = ORIENTED_EDGE('',*,*,#128348,.F.); -#128580 = ORIENTED_EDGE('',*,*,#128581,.F.); -#128581 = EDGE_CURVE('',#128531,#128326,#128582,.T.); -#128582 = SURFACE_CURVE('',#128583,(#128587,#128594),.PCURVE_S1.); -#128583 = LINE('',#128584,#128585); -#128584 = CARTESIAN_POINT('',(10.419594812019,5.65,0.530776333563)); -#128585 = VECTOR('',#128586,1.); -#128586 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#128587 = PCURVE('',#128361,#128588); -#128588 = DEFINITIONAL_REPRESENTATION('',(#128589),#128593); -#128589 = LINE('',#128590,#128591); -#128590 = CARTESIAN_POINT('',(-5.65,0.E+000)); -#128591 = VECTOR('',#128592,1.); -#128592 = DIRECTION('',(0.E+000,-1.)); -#128593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128594 = PCURVE('',#93252,#128595); -#128595 = DEFINITIONAL_REPRESENTATION('',(#128596),#128600); -#128596 = LINE('',#128597,#128598); -#128597 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#128598 = VECTOR('',#128599,1.); -#128599 = DIRECTION('',(1.,0.E+000)); -#128600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128601 = ADVANCED_FACE('',(#128602),#128548,.F.); -#128602 = FACE_BOUND('',#128603,.F.); -#128603 = EDGE_LOOP('',(#128604,#128605,#128628,#128650)); -#128604 = ORIENTED_EDGE('',*,*,#128530,.T.); -#128605 = ORIENTED_EDGE('',*,*,#128606,.F.); -#128606 = EDGE_CURVE('',#128607,#128533,#128609,.T.); -#128607 = VERTEX_POINT('',#128608); -#128608 = CARTESIAN_POINT('',(10.303662633502,5.85,0.65)); -#128609 = SURFACE_CURVE('',#128610,(#128615,#128621),.PCURVE_S1.); -#128610 = CIRCLE('',#128611,0.119270391569); -#128611 = AXIS2_PLACEMENT_3D('',#128612,#128613,#128614); -#128612 = CARTESIAN_POINT('',(10.30032442045,5.85,0.530776333563)); -#128613 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128614 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128615 = PCURVE('',#128548,#128616); -#128616 = DEFINITIONAL_REPRESENTATION('',(#128617),#128620); -#128617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128618,#128619), +#130947 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#130948 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#130949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130950 = ORIENTED_EDGE('',*,*,#130951,.T.); +#130951 = EDGE_CURVE('',#130925,#130690,#130952,.T.); +#130952 = SURFACE_CURVE('',#130953,(#130957,#130964),.PCURVE_S1.); +#130953 = LINE('',#130954,#130955); +#130954 = CARTESIAN_POINT('',(10.419594812019,5.85,0.530776333563)); +#130955 = VECTOR('',#130956,1.); +#130956 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130957 = PCURVE('',#130753,#130958); +#130958 = DEFINITIONAL_REPRESENTATION('',(#130959),#130963); +#130959 = LINE('',#130960,#130961); +#130960 = CARTESIAN_POINT('',(-5.85,0.E+000)); +#130961 = VECTOR('',#130962,1.); +#130962 = DIRECTION('',(0.E+000,-1.)); +#130963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130964 = PCURVE('',#95588,#130965); +#130965 = DEFINITIONAL_REPRESENTATION('',(#130966),#130970); +#130966 = LINE('',#130967,#130968); +#130967 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#130968 = VECTOR('',#130969,1.); +#130969 = DIRECTION('',(-1.,0.E+000)); +#130970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130971 = ORIENTED_EDGE('',*,*,#130740,.F.); +#130972 = ORIENTED_EDGE('',*,*,#130973,.F.); +#130973 = EDGE_CURVE('',#130923,#130718,#130974,.T.); +#130974 = SURFACE_CURVE('',#130975,(#130979,#130986),.PCURVE_S1.); +#130975 = LINE('',#130976,#130977); +#130976 = CARTESIAN_POINT('',(10.419594812019,5.65,0.530776333563)); +#130977 = VECTOR('',#130978,1.); +#130978 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#130979 = PCURVE('',#130753,#130980); +#130980 = DEFINITIONAL_REPRESENTATION('',(#130981),#130985); +#130981 = LINE('',#130982,#130983); +#130982 = CARTESIAN_POINT('',(-5.65,0.E+000)); +#130983 = VECTOR('',#130984,1.); +#130984 = DIRECTION('',(0.E+000,-1.)); +#130985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130986 = PCURVE('',#95644,#130987); +#130987 = DEFINITIONAL_REPRESENTATION('',(#130988),#130992); +#130988 = LINE('',#130989,#130990); +#130989 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#130990 = VECTOR('',#130991,1.); +#130991 = DIRECTION('',(1.,0.E+000)); +#130992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#130993 = ADVANCED_FACE('',(#130994),#130940,.F.); +#130994 = FACE_BOUND('',#130995,.F.); +#130995 = EDGE_LOOP('',(#130996,#130997,#131020,#131042)); +#130996 = ORIENTED_EDGE('',*,*,#130922,.T.); +#130997 = ORIENTED_EDGE('',*,*,#130998,.F.); +#130998 = EDGE_CURVE('',#130999,#130925,#131001,.T.); +#130999 = VERTEX_POINT('',#131000); +#131000 = CARTESIAN_POINT('',(10.303662633502,5.85,0.65)); +#131001 = SURFACE_CURVE('',#131002,(#131007,#131013),.PCURVE_S1.); +#131002 = CIRCLE('',#131003,0.119270391569); +#131003 = AXIS2_PLACEMENT_3D('',#131004,#131005,#131006); +#131004 = CARTESIAN_POINT('',(10.30032442045,5.85,0.530776333563)); +#131005 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131006 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131007 = PCURVE('',#130940,#131008); +#131008 = DEFINITIONAL_REPRESENTATION('',(#131009),#131012); +#131009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131010,#131011), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#128618 = CARTESIAN_POINT('',(1.598788597134,5.85)); -#128619 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#128620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131010 = CARTESIAN_POINT('',(1.598788597134,5.85)); +#131011 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#131012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128621 = PCURVE('',#93196,#128622); -#128622 = DEFINITIONAL_REPRESENTATION('',(#128623),#128627); -#128623 = CIRCLE('',#128624,0.119270391569); -#128624 = AXIS2_PLACEMENT_2D('',#128625,#128626); -#128625 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#128626 = DIRECTION('',(0.E+000,-1.)); -#128627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131013 = PCURVE('',#95588,#131014); +#131014 = DEFINITIONAL_REPRESENTATION('',(#131015),#131019); +#131015 = CIRCLE('',#131016,0.119270391569); +#131016 = AXIS2_PLACEMENT_2D('',#131017,#131018); +#131017 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#131018 = DIRECTION('',(0.E+000,-1.)); +#131019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128628 = ORIENTED_EDGE('',*,*,#128629,.T.); -#128629 = EDGE_CURVE('',#128607,#128630,#128632,.T.); -#128630 = VERTEX_POINT('',#128631); -#128631 = CARTESIAN_POINT('',(10.303662633502,5.65,0.65)); -#128632 = SURFACE_CURVE('',#128633,(#128637,#128643),.PCURVE_S1.); -#128633 = LINE('',#128634,#128635); -#128634 = CARTESIAN_POINT('',(10.303662633502,5.65,0.65)); -#128635 = VECTOR('',#128636,1.); -#128636 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128637 = PCURVE('',#128548,#128638); -#128638 = DEFINITIONAL_REPRESENTATION('',(#128639),#128642); -#128639 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128640,#128641), +#131020 = ORIENTED_EDGE('',*,*,#131021,.T.); +#131021 = EDGE_CURVE('',#130999,#131022,#131024,.T.); +#131022 = VERTEX_POINT('',#131023); +#131023 = CARTESIAN_POINT('',(10.303662633502,5.65,0.65)); +#131024 = SURFACE_CURVE('',#131025,(#131029,#131035),.PCURVE_S1.); +#131025 = LINE('',#131026,#131027); +#131026 = CARTESIAN_POINT('',(10.303662633502,5.65,0.65)); +#131027 = VECTOR('',#131028,1.); +#131028 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131029 = PCURVE('',#130940,#131030); +#131030 = DEFINITIONAL_REPRESENTATION('',(#131031),#131034); +#131031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131032,#131033), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#128640 = CARTESIAN_POINT('',(1.598788597134,5.85)); -#128641 = CARTESIAN_POINT('',(1.598788597134,5.65)); -#128642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128643 = PCURVE('',#93224,#128644); -#128644 = DEFINITIONAL_REPRESENTATION('',(#128645),#128649); -#128645 = LINE('',#128646,#128647); -#128646 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#128647 = VECTOR('',#128648,1.); -#128648 = DIRECTION('',(4.440892098501E-016,-1.)); -#128649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128650 = ORIENTED_EDGE('',*,*,#128651,.T.); -#128651 = EDGE_CURVE('',#128630,#128531,#128652,.T.); -#128652 = SURFACE_CURVE('',#128653,(#128658,#128664),.PCURVE_S1.); -#128653 = CIRCLE('',#128654,0.119270391569); -#128654 = AXIS2_PLACEMENT_3D('',#128655,#128656,#128657); -#128655 = CARTESIAN_POINT('',(10.30032442045,5.65,0.530776333563)); -#128656 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128657 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128658 = PCURVE('',#128548,#128659); -#128659 = DEFINITIONAL_REPRESENTATION('',(#128660),#128663); -#128660 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128661,#128662), +#131032 = CARTESIAN_POINT('',(1.598788597134,5.85)); +#131033 = CARTESIAN_POINT('',(1.598788597134,5.65)); +#131034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131035 = PCURVE('',#95616,#131036); +#131036 = DEFINITIONAL_REPRESENTATION('',(#131037),#131041); +#131037 = LINE('',#131038,#131039); +#131038 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#131039 = VECTOR('',#131040,1.); +#131040 = DIRECTION('',(4.440892098501E-016,-1.)); +#131041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131042 = ORIENTED_EDGE('',*,*,#131043,.T.); +#131043 = EDGE_CURVE('',#131022,#130923,#131044,.T.); +#131044 = SURFACE_CURVE('',#131045,(#131050,#131056),.PCURVE_S1.); +#131045 = CIRCLE('',#131046,0.119270391569); +#131046 = AXIS2_PLACEMENT_3D('',#131047,#131048,#131049); +#131047 = CARTESIAN_POINT('',(10.30032442045,5.65,0.530776333563)); +#131048 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131049 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131050 = PCURVE('',#130940,#131051); +#131051 = DEFINITIONAL_REPRESENTATION('',(#131052),#131055); +#131052 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131053,#131054), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#128661 = CARTESIAN_POINT('',(1.598788597134,5.65)); -#128662 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#128663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131053 = CARTESIAN_POINT('',(1.598788597134,5.65)); +#131054 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#131055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128664 = PCURVE('',#93252,#128665); -#128665 = DEFINITIONAL_REPRESENTATION('',(#128666),#128674); -#128666 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128667,#128668,#128669, - #128670,#128671,#128672,#128673),.UNSPECIFIED.,.T.,.F.) +#131056 = PCURVE('',#95644,#131057); +#131057 = DEFINITIONAL_REPRESENTATION('',(#131058),#131066); +#131058 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131059,#131060,#131061, + #131062,#131063,#131064,#131065),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#128667 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#128668 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#128669 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#128670 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#128671 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#128672 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#128673 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#128674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128675 = ADVANCED_FACE('',(#128676),#128473,.T.); -#128676 = FACE_BOUND('',#128677,.T.); -#128677 = EDGE_LOOP('',(#128678,#128679,#128702,#128724)); -#128678 = ORIENTED_EDGE('',*,*,#128455,.F.); -#128679 = ORIENTED_EDGE('',*,*,#128680,.F.); -#128680 = EDGE_CURVE('',#128681,#128456,#128683,.T.); -#128681 = VERTEX_POINT('',#128682); -#128682 = CARTESIAN_POINT('',(10.304819755875,5.85,0.75)); -#128683 = SURFACE_CURVE('',#128684,(#128689,#128695),.PCURVE_S1.); -#128684 = CIRCLE('',#128685,0.2192697516); -#128685 = AXIS2_PLACEMENT_3D('',#128686,#128687,#128688); -#128686 = CARTESIAN_POINT('',(10.30032442045,5.85,0.530776333563)); -#128687 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128688 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128689 = PCURVE('',#128473,#128690); -#128690 = DEFINITIONAL_REPRESENTATION('',(#128691),#128694); -#128691 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128692,#128693), +#131059 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#131060 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#131061 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#131062 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#131063 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#131064 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#131065 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#131066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131067 = ADVANCED_FACE('',(#131068),#130865,.T.); +#131068 = FACE_BOUND('',#131069,.T.); +#131069 = EDGE_LOOP('',(#131070,#131071,#131094,#131116)); +#131070 = ORIENTED_EDGE('',*,*,#130847,.F.); +#131071 = ORIENTED_EDGE('',*,*,#131072,.F.); +#131072 = EDGE_CURVE('',#131073,#130848,#131075,.T.); +#131073 = VERTEX_POINT('',#131074); +#131074 = CARTESIAN_POINT('',(10.304819755875,5.85,0.75)); +#131075 = SURFACE_CURVE('',#131076,(#131081,#131087),.PCURVE_S1.); +#131076 = CIRCLE('',#131077,0.2192697516); +#131077 = AXIS2_PLACEMENT_3D('',#131078,#131079,#131080); +#131078 = CARTESIAN_POINT('',(10.30032442045,5.85,0.530776333563)); +#131079 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131080 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131081 = PCURVE('',#130865,#131082); +#131082 = DEFINITIONAL_REPRESENTATION('',(#131083),#131086); +#131083 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131084,#131085), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#128692 = CARTESIAN_POINT('',(1.591299156552,5.85)); -#128693 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#128694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128695 = PCURVE('',#93196,#128696); -#128696 = DEFINITIONAL_REPRESENTATION('',(#128697),#128701); -#128697 = CIRCLE('',#128698,0.2192697516); -#128698 = AXIS2_PLACEMENT_2D('',#128699,#128700); -#128699 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#128700 = DIRECTION('',(0.E+000,-1.)); -#128701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128702 = ORIENTED_EDGE('',*,*,#128703,.F.); -#128703 = EDGE_CURVE('',#128704,#128681,#128706,.T.); -#128704 = VERTEX_POINT('',#128705); -#128705 = CARTESIAN_POINT('',(10.304819755875,5.65,0.75)); -#128706 = SURFACE_CURVE('',#128707,(#128711,#128717),.PCURVE_S1.); -#128707 = LINE('',#128708,#128709); -#128708 = CARTESIAN_POINT('',(10.304819755875,5.65,0.75)); -#128709 = VECTOR('',#128710,1.); -#128710 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128711 = PCURVE('',#128473,#128712); -#128712 = DEFINITIONAL_REPRESENTATION('',(#128713),#128716); -#128713 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128714,#128715), +#131084 = CARTESIAN_POINT('',(1.591299156552,5.85)); +#131085 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#131086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131087 = PCURVE('',#95588,#131088); +#131088 = DEFINITIONAL_REPRESENTATION('',(#131089),#131093); +#131089 = CIRCLE('',#131090,0.2192697516); +#131090 = AXIS2_PLACEMENT_2D('',#131091,#131092); +#131091 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#131092 = DIRECTION('',(0.E+000,-1.)); +#131093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131094 = ORIENTED_EDGE('',*,*,#131095,.F.); +#131095 = EDGE_CURVE('',#131096,#131073,#131098,.T.); +#131096 = VERTEX_POINT('',#131097); +#131097 = CARTESIAN_POINT('',(10.304819755875,5.65,0.75)); +#131098 = SURFACE_CURVE('',#131099,(#131103,#131109),.PCURVE_S1.); +#131099 = LINE('',#131100,#131101); +#131100 = CARTESIAN_POINT('',(10.304819755875,5.65,0.75)); +#131101 = VECTOR('',#131102,1.); +#131102 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131103 = PCURVE('',#130865,#131104); +#131104 = DEFINITIONAL_REPRESENTATION('',(#131105),#131108); +#131105 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131106,#131107), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#128714 = CARTESIAN_POINT('',(1.591299156552,5.65)); -#128715 = CARTESIAN_POINT('',(1.591299156552,5.85)); -#128716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128717 = PCURVE('',#93278,#128718); -#128718 = DEFINITIONAL_REPRESENTATION('',(#128719),#128723); -#128719 = LINE('',#128720,#128721); -#128720 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#128721 = VECTOR('',#128722,1.); -#128722 = DIRECTION('',(4.440892098501E-016,1.)); -#128723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128724 = ORIENTED_EDGE('',*,*,#128725,.T.); -#128725 = EDGE_CURVE('',#128704,#128458,#128726,.T.); -#128726 = SURFACE_CURVE('',#128727,(#128732,#128738),.PCURVE_S1.); -#128727 = CIRCLE('',#128728,0.2192697516); -#128728 = AXIS2_PLACEMENT_3D('',#128729,#128730,#128731); -#128729 = CARTESIAN_POINT('',(10.30032442045,5.65,0.530776333563)); -#128730 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128731 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#128732 = PCURVE('',#128473,#128733); -#128733 = DEFINITIONAL_REPRESENTATION('',(#128734),#128737); -#128734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#128735,#128736), +#131106 = CARTESIAN_POINT('',(1.591299156552,5.65)); +#131107 = CARTESIAN_POINT('',(1.591299156552,5.85)); +#131108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131109 = PCURVE('',#95670,#131110); +#131110 = DEFINITIONAL_REPRESENTATION('',(#131111),#131115); +#131111 = LINE('',#131112,#131113); +#131112 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#131113 = VECTOR('',#131114,1.); +#131114 = DIRECTION('',(4.440892098501E-016,1.)); +#131115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131116 = ORIENTED_EDGE('',*,*,#131117,.T.); +#131117 = EDGE_CURVE('',#131096,#130850,#131118,.T.); +#131118 = SURFACE_CURVE('',#131119,(#131124,#131130),.PCURVE_S1.); +#131119 = CIRCLE('',#131120,0.2192697516); +#131120 = AXIS2_PLACEMENT_3D('',#131121,#131122,#131123); +#131121 = CARTESIAN_POINT('',(10.30032442045,5.65,0.530776333563)); +#131122 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131123 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131124 = PCURVE('',#130865,#131125); +#131125 = DEFINITIONAL_REPRESENTATION('',(#131126),#131129); +#131126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131127,#131128), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#128735 = CARTESIAN_POINT('',(1.591299156552,5.65)); -#128736 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#128737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131127 = CARTESIAN_POINT('',(1.591299156552,5.65)); +#131128 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#131129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#128738 = PCURVE('',#93252,#128739); -#128739 = DEFINITIONAL_REPRESENTATION('',(#128740),#128748); -#128740 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#128741,#128742,#128743, - #128744,#128745,#128746,#128747),.UNSPECIFIED.,.T.,.F.) +#131130 = PCURVE('',#95644,#131131); +#131131 = DEFINITIONAL_REPRESENTATION('',(#131132),#131140); +#131132 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131133,#131134,#131135, + #131136,#131137,#131138,#131139),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#128741 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#128742 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#128743 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#128744 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#128745 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#128746 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#128747 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#128748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128749 = ADVANCED_FACE('',(#128750),#93224,.T.); -#128750 = FACE_BOUND('',#128751,.T.); -#128751 = EDGE_LOOP('',(#128752,#128773,#128774,#128795)); -#128752 = ORIENTED_EDGE('',*,*,#128753,.F.); -#128753 = EDGE_CURVE('',#128607,#93181,#128754,.T.); -#128754 = SURFACE_CURVE('',#128755,(#128759,#128766),.PCURVE_S1.); -#128755 = LINE('',#128756,#128757); -#128756 = CARTESIAN_POINT('',(10.527847992439,5.85,0.65)); -#128757 = VECTOR('',#128758,1.); -#128758 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#128759 = PCURVE('',#93224,#128760); -#128760 = DEFINITIONAL_REPRESENTATION('',(#128761),#128765); -#128761 = LINE('',#128762,#128763); -#128762 = CARTESIAN_POINT('',(0.E+000,0.2)); -#128763 = VECTOR('',#128764,1.); -#128764 = DIRECTION('',(1.,-3.00059940766E-063)); -#128765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128766 = PCURVE('',#93196,#128767); -#128767 = DEFINITIONAL_REPRESENTATION('',(#128768),#128772); -#128768 = LINE('',#128769,#128770); -#128769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128770 = VECTOR('',#128771,1.); -#128771 = DIRECTION('',(3.563627120235E-016,-1.)); -#128772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128773 = ORIENTED_EDGE('',*,*,#128629,.T.); -#128774 = ORIENTED_EDGE('',*,*,#128775,.T.); -#128775 = EDGE_CURVE('',#128630,#93209,#128776,.T.); -#128776 = SURFACE_CURVE('',#128777,(#128781,#128788),.PCURVE_S1.); -#128777 = LINE('',#128778,#128779); -#128778 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); -#128779 = VECTOR('',#128780,1.); -#128780 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#128781 = PCURVE('',#93224,#128782); -#128782 = DEFINITIONAL_REPRESENTATION('',(#128783),#128787); -#128783 = LINE('',#128784,#128785); -#128784 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128785 = VECTOR('',#128786,1.); -#128786 = DIRECTION('',(1.,-3.00059940766E-063)); -#128787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128788 = PCURVE('',#93252,#128789); -#128789 = DEFINITIONAL_REPRESENTATION('',(#128790),#128794); -#128790 = LINE('',#128791,#128792); -#128791 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128792 = VECTOR('',#128793,1.); -#128793 = DIRECTION('',(-3.563627120235E-016,-1.)); -#128794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128795 = ORIENTED_EDGE('',*,*,#93208,.F.); -#128796 = ADVANCED_FACE('',(#128797),#93196,.T.); -#128797 = FACE_BOUND('',#128798,.T.); -#128798 = EDGE_LOOP('',(#128799,#128820,#128821,#128822,#128823,#128824, - #128845,#128846,#128847,#128848,#128849,#128850)); -#128799 = ORIENTED_EDGE('',*,*,#128800,.F.); -#128800 = EDGE_CURVE('',#128681,#93179,#128801,.T.); -#128801 = SURFACE_CURVE('',#128802,(#128806,#128813),.PCURVE_S1.); -#128802 = LINE('',#128803,#128804); -#128803 = CARTESIAN_POINT('',(10.527847992439,5.85,0.75)); -#128804 = VECTOR('',#128805,1.); -#128805 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#128806 = PCURVE('',#93196,#128807); -#128807 = DEFINITIONAL_REPRESENTATION('',(#128808),#128812); -#128808 = LINE('',#128809,#128810); -#128809 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#128810 = VECTOR('',#128811,1.); -#128811 = DIRECTION('',(3.563627120235E-016,-1.)); -#128812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128813 = PCURVE('',#93278,#128814); -#128814 = DEFINITIONAL_REPRESENTATION('',(#128815),#128819); -#128815 = LINE('',#128816,#128817); -#128816 = CARTESIAN_POINT('',(0.E+000,0.2)); -#128817 = VECTOR('',#128818,1.); -#128818 = DIRECTION('',(-1.,-3.00059940766E-063)); -#128819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128820 = ORIENTED_EDGE('',*,*,#128680,.T.); -#128821 = ORIENTED_EDGE('',*,*,#128506,.T.); -#128822 = ORIENTED_EDGE('',*,*,#128426,.T.); -#128823 = ORIENTED_EDGE('',*,*,#128223,.T.); -#128824 = ORIENTED_EDGE('',*,*,#128825,.F.); -#128825 = EDGE_CURVE('',#128087,#128194,#128826,.T.); -#128826 = SURFACE_CURVE('',#128827,(#128831,#128838),.PCURVE_S1.); -#128827 = LINE('',#128828,#128829); -#128828 = CARTESIAN_POINT('',(11.,5.85,1.159810404338E-002)); -#128829 = VECTOR('',#128830,1.); -#128830 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#128831 = PCURVE('',#93196,#128832); -#128832 = DEFINITIONAL_REPRESENTATION('',(#128833),#128837); -#128833 = LINE('',#128834,#128835); -#128834 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#128835 = VECTOR('',#128836,1.); -#128836 = DIRECTION('',(1.,2.101748079665E-016)); -#128837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128838 = PCURVE('',#128107,#128839); -#128839 = DEFINITIONAL_REPRESENTATION('',(#128840),#128844); -#128840 = LINE('',#128841,#128842); -#128841 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#128842 = VECTOR('',#128843,1.); -#128843 = DIRECTION('',(1.194699204908E-017,1.)); -#128844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128845 = ORIENTED_EDGE('',*,*,#128169,.F.); -#128846 = ORIENTED_EDGE('',*,*,#128297,.F.); -#128847 = ORIENTED_EDGE('',*,*,#128559,.F.); -#128848 = ORIENTED_EDGE('',*,*,#128606,.F.); -#128849 = ORIENTED_EDGE('',*,*,#128753,.T.); -#128850 = ORIENTED_EDGE('',*,*,#93178,.F.); -#128851 = ADVANCED_FACE('',(#128852),#93278,.T.); -#128852 = FACE_BOUND('',#128853,.T.); -#128853 = EDGE_LOOP('',(#128854,#128875,#128876,#128877)); -#128854 = ORIENTED_EDGE('',*,*,#128855,.F.); -#128855 = EDGE_CURVE('',#128704,#93237,#128856,.T.); -#128856 = SURFACE_CURVE('',#128857,(#128861,#128868),.PCURVE_S1.); -#128857 = LINE('',#128858,#128859); -#128858 = CARTESIAN_POINT('',(10.527847992439,5.65,0.75)); -#128859 = VECTOR('',#128860,1.); -#128860 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#128861 = PCURVE('',#93278,#128862); -#128862 = DEFINITIONAL_REPRESENTATION('',(#128863),#128867); -#128863 = LINE('',#128864,#128865); -#128864 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128865 = VECTOR('',#128866,1.); -#128866 = DIRECTION('',(-1.,-3.00059940766E-063)); -#128867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128868 = PCURVE('',#93252,#128869); -#128869 = DEFINITIONAL_REPRESENTATION('',(#128870),#128874); -#128870 = LINE('',#128871,#128872); -#128871 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#128872 = VECTOR('',#128873,1.); -#128873 = DIRECTION('',(-3.563627120235E-016,-1.)); -#128874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128875 = ORIENTED_EDGE('',*,*,#128703,.T.); -#128876 = ORIENTED_EDGE('',*,*,#128800,.T.); -#128877 = ORIENTED_EDGE('',*,*,#93264,.F.); -#128878 = ADVANCED_FACE('',(#128879),#93252,.T.); -#128879 = FACE_BOUND('',#128880,.T.); -#128880 = EDGE_LOOP('',(#128881,#128882,#128883,#128884,#128885,#128886, - #128907,#128908,#128909,#128910,#128911,#128912)); -#128881 = ORIENTED_EDGE('',*,*,#128775,.F.); -#128882 = ORIENTED_EDGE('',*,*,#128651,.T.); -#128883 = ORIENTED_EDGE('',*,*,#128581,.T.); -#128884 = ORIENTED_EDGE('',*,*,#128325,.T.); -#128885 = ORIENTED_EDGE('',*,*,#128119,.T.); -#128886 = ORIENTED_EDGE('',*,*,#128887,.F.); -#128887 = EDGE_CURVE('',#128196,#128085,#128888,.T.); -#128888 = SURFACE_CURVE('',#128889,(#128893,#128900),.PCURVE_S1.); -#128889 = LINE('',#128890,#128891); -#128890 = CARTESIAN_POINT('',(11.,5.65,1.159810404338E-002)); -#128891 = VECTOR('',#128892,1.); -#128892 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#128893 = PCURVE('',#93252,#128894); -#128894 = DEFINITIONAL_REPRESENTATION('',(#128895),#128899); -#128895 = LINE('',#128896,#128897); -#128896 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#128897 = VECTOR('',#128898,1.); -#128898 = DIRECTION('',(1.,-2.101748079665E-016)); -#128899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128900 = PCURVE('',#128107,#128901); -#128901 = DEFINITIONAL_REPRESENTATION('',(#128902),#128906); -#128902 = LINE('',#128903,#128904); -#128903 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#128904 = VECTOR('',#128905,1.); -#128905 = DIRECTION('',(-1.194699204908E-017,-1.)); -#128906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128907 = ORIENTED_EDGE('',*,*,#128273,.F.); -#128908 = ORIENTED_EDGE('',*,*,#128376,.F.); -#128909 = ORIENTED_EDGE('',*,*,#128484,.F.); -#128910 = ORIENTED_EDGE('',*,*,#128725,.F.); -#128911 = ORIENTED_EDGE('',*,*,#128855,.T.); -#128912 = ORIENTED_EDGE('',*,*,#93236,.F.); -#128913 = ADVANCED_FACE('',(#128914),#128107,.T.); -#128914 = FACE_BOUND('',#128915,.T.); -#128915 = EDGE_LOOP('',(#128916,#128917,#128918,#128919)); -#128916 = ORIENTED_EDGE('',*,*,#128825,.T.); -#128917 = ORIENTED_EDGE('',*,*,#128193,.T.); -#128918 = ORIENTED_EDGE('',*,*,#128887,.T.); -#128919 = ORIENTED_EDGE('',*,*,#128084,.T.); -#128920 = ADVANCED_FACE('',(#128921),#128935,.F.); -#128921 = FACE_BOUND('',#128922,.T.); -#128922 = EDGE_LOOP('',(#128923,#128958,#128981,#129008)); -#128923 = ORIENTED_EDGE('',*,*,#128924,.F.); -#128924 = EDGE_CURVE('',#128925,#128927,#128929,.T.); -#128925 = VERTEX_POINT('',#128926); -#128926 = CARTESIAN_POINT('',(11.,5.15,-0.308197125857)); -#128927 = VERTEX_POINT('',#128928); -#128928 = CARTESIAN_POINT('',(11.,5.35,-0.308197125857)); -#128929 = SURFACE_CURVE('',#128930,(#128934,#128946),.PCURVE_S1.); -#128930 = LINE('',#128931,#128932); -#128931 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#128932 = VECTOR('',#128933,1.); -#128933 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128934 = PCURVE('',#128935,#128940); -#128935 = PLANE('',#128936); -#128936 = AXIS2_PLACEMENT_3D('',#128937,#128938,#128939); -#128937 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#131133 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#131134 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#131135 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#131136 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#131137 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#131138 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#131139 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#131140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131141 = ADVANCED_FACE('',(#131142),#95616,.T.); +#131142 = FACE_BOUND('',#131143,.T.); +#131143 = EDGE_LOOP('',(#131144,#131165,#131166,#131187)); +#131144 = ORIENTED_EDGE('',*,*,#131145,.F.); +#131145 = EDGE_CURVE('',#130999,#95573,#131146,.T.); +#131146 = SURFACE_CURVE('',#131147,(#131151,#131158),.PCURVE_S1.); +#131147 = LINE('',#131148,#131149); +#131148 = CARTESIAN_POINT('',(10.527847992439,5.85,0.65)); +#131149 = VECTOR('',#131150,1.); +#131150 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#131151 = PCURVE('',#95616,#131152); +#131152 = DEFINITIONAL_REPRESENTATION('',(#131153),#131157); +#131153 = LINE('',#131154,#131155); +#131154 = CARTESIAN_POINT('',(0.E+000,0.2)); +#131155 = VECTOR('',#131156,1.); +#131156 = DIRECTION('',(1.,-3.00059940766E-063)); +#131157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131158 = PCURVE('',#95588,#131159); +#131159 = DEFINITIONAL_REPRESENTATION('',(#131160),#131164); +#131160 = LINE('',#131161,#131162); +#131161 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131162 = VECTOR('',#131163,1.); +#131163 = DIRECTION('',(3.563627120235E-016,-1.)); +#131164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131165 = ORIENTED_EDGE('',*,*,#131021,.T.); +#131166 = ORIENTED_EDGE('',*,*,#131167,.T.); +#131167 = EDGE_CURVE('',#131022,#95601,#131168,.T.); +#131168 = SURFACE_CURVE('',#131169,(#131173,#131180),.PCURVE_S1.); +#131169 = LINE('',#131170,#131171); +#131170 = CARTESIAN_POINT('',(10.527847992439,5.65,0.65)); +#131171 = VECTOR('',#131172,1.); +#131172 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#131173 = PCURVE('',#95616,#131174); +#131174 = DEFINITIONAL_REPRESENTATION('',(#131175),#131179); +#131175 = LINE('',#131176,#131177); +#131176 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131177 = VECTOR('',#131178,1.); +#131178 = DIRECTION('',(1.,-3.00059940766E-063)); +#131179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131180 = PCURVE('',#95644,#131181); +#131181 = DEFINITIONAL_REPRESENTATION('',(#131182),#131186); +#131182 = LINE('',#131183,#131184); +#131183 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131184 = VECTOR('',#131185,1.); +#131185 = DIRECTION('',(-3.563627120235E-016,-1.)); +#131186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131187 = ORIENTED_EDGE('',*,*,#95600,.F.); +#131188 = ADVANCED_FACE('',(#131189),#95588,.T.); +#131189 = FACE_BOUND('',#131190,.T.); +#131190 = EDGE_LOOP('',(#131191,#131212,#131213,#131214,#131215,#131216, + #131237,#131238,#131239,#131240,#131241,#131242)); +#131191 = ORIENTED_EDGE('',*,*,#131192,.F.); +#131192 = EDGE_CURVE('',#131073,#95571,#131193,.T.); +#131193 = SURFACE_CURVE('',#131194,(#131198,#131205),.PCURVE_S1.); +#131194 = LINE('',#131195,#131196); +#131195 = CARTESIAN_POINT('',(10.527847992439,5.85,0.75)); +#131196 = VECTOR('',#131197,1.); +#131197 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#131198 = PCURVE('',#95588,#131199); +#131199 = DEFINITIONAL_REPRESENTATION('',(#131200),#131204); +#131200 = LINE('',#131201,#131202); +#131201 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#131202 = VECTOR('',#131203,1.); +#131203 = DIRECTION('',(3.563627120235E-016,-1.)); +#131204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131205 = PCURVE('',#95670,#131206); +#131206 = DEFINITIONAL_REPRESENTATION('',(#131207),#131211); +#131207 = LINE('',#131208,#131209); +#131208 = CARTESIAN_POINT('',(0.E+000,0.2)); +#131209 = VECTOR('',#131210,1.); +#131210 = DIRECTION('',(-1.,-3.00059940766E-063)); +#131211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131212 = ORIENTED_EDGE('',*,*,#131072,.T.); +#131213 = ORIENTED_EDGE('',*,*,#130898,.T.); +#131214 = ORIENTED_EDGE('',*,*,#130818,.T.); +#131215 = ORIENTED_EDGE('',*,*,#130615,.T.); +#131216 = ORIENTED_EDGE('',*,*,#131217,.F.); +#131217 = EDGE_CURVE('',#130479,#130586,#131218,.T.); +#131218 = SURFACE_CURVE('',#131219,(#131223,#131230),.PCURVE_S1.); +#131219 = LINE('',#131220,#131221); +#131220 = CARTESIAN_POINT('',(11.,5.85,1.159810404338E-002)); +#131221 = VECTOR('',#131222,1.); +#131222 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#131223 = PCURVE('',#95588,#131224); +#131224 = DEFINITIONAL_REPRESENTATION('',(#131225),#131229); +#131225 = LINE('',#131226,#131227); +#131226 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#131227 = VECTOR('',#131228,1.); +#131228 = DIRECTION('',(1.,2.101748079665E-016)); +#131229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131230 = PCURVE('',#130499,#131231); +#131231 = DEFINITIONAL_REPRESENTATION('',(#131232),#131236); +#131232 = LINE('',#131233,#131234); +#131233 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#131234 = VECTOR('',#131235,1.); +#131235 = DIRECTION('',(1.194699204908E-017,1.)); +#131236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131237 = ORIENTED_EDGE('',*,*,#130561,.F.); +#131238 = ORIENTED_EDGE('',*,*,#130689,.F.); +#131239 = ORIENTED_EDGE('',*,*,#130951,.F.); +#131240 = ORIENTED_EDGE('',*,*,#130998,.F.); +#131241 = ORIENTED_EDGE('',*,*,#131145,.T.); +#131242 = ORIENTED_EDGE('',*,*,#95570,.F.); +#131243 = ADVANCED_FACE('',(#131244),#95670,.T.); +#131244 = FACE_BOUND('',#131245,.T.); +#131245 = EDGE_LOOP('',(#131246,#131267,#131268,#131269)); +#131246 = ORIENTED_EDGE('',*,*,#131247,.F.); +#131247 = EDGE_CURVE('',#131096,#95629,#131248,.T.); +#131248 = SURFACE_CURVE('',#131249,(#131253,#131260),.PCURVE_S1.); +#131249 = LINE('',#131250,#131251); +#131250 = CARTESIAN_POINT('',(10.527847992439,5.65,0.75)); +#131251 = VECTOR('',#131252,1.); +#131252 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#131253 = PCURVE('',#95670,#131254); +#131254 = DEFINITIONAL_REPRESENTATION('',(#131255),#131259); +#131255 = LINE('',#131256,#131257); +#131256 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131257 = VECTOR('',#131258,1.); +#131258 = DIRECTION('',(-1.,-3.00059940766E-063)); +#131259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131260 = PCURVE('',#95644,#131261); +#131261 = DEFINITIONAL_REPRESENTATION('',(#131262),#131266); +#131262 = LINE('',#131263,#131264); +#131263 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#131264 = VECTOR('',#131265,1.); +#131265 = DIRECTION('',(-3.563627120235E-016,-1.)); +#131266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131267 = ORIENTED_EDGE('',*,*,#131095,.T.); +#131268 = ORIENTED_EDGE('',*,*,#131192,.T.); +#131269 = ORIENTED_EDGE('',*,*,#95656,.F.); +#131270 = ADVANCED_FACE('',(#131271),#95644,.T.); +#131271 = FACE_BOUND('',#131272,.T.); +#131272 = EDGE_LOOP('',(#131273,#131274,#131275,#131276,#131277,#131278, + #131299,#131300,#131301,#131302,#131303,#131304)); +#131273 = ORIENTED_EDGE('',*,*,#131167,.F.); +#131274 = ORIENTED_EDGE('',*,*,#131043,.T.); +#131275 = ORIENTED_EDGE('',*,*,#130973,.T.); +#131276 = ORIENTED_EDGE('',*,*,#130717,.T.); +#131277 = ORIENTED_EDGE('',*,*,#130511,.T.); +#131278 = ORIENTED_EDGE('',*,*,#131279,.F.); +#131279 = EDGE_CURVE('',#130588,#130477,#131280,.T.); +#131280 = SURFACE_CURVE('',#131281,(#131285,#131292),.PCURVE_S1.); +#131281 = LINE('',#131282,#131283); +#131282 = CARTESIAN_POINT('',(11.,5.65,1.159810404338E-002)); +#131283 = VECTOR('',#131284,1.); +#131284 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#131285 = PCURVE('',#95644,#131286); +#131286 = DEFINITIONAL_REPRESENTATION('',(#131287),#131291); +#131287 = LINE('',#131288,#131289); +#131288 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#131289 = VECTOR('',#131290,1.); +#131290 = DIRECTION('',(1.,-2.101748079665E-016)); +#131291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131292 = PCURVE('',#130499,#131293); +#131293 = DEFINITIONAL_REPRESENTATION('',(#131294),#131298); +#131294 = LINE('',#131295,#131296); +#131295 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#131296 = VECTOR('',#131297,1.); +#131297 = DIRECTION('',(-1.194699204908E-017,-1.)); +#131298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131299 = ORIENTED_EDGE('',*,*,#130665,.F.); +#131300 = ORIENTED_EDGE('',*,*,#130768,.F.); +#131301 = ORIENTED_EDGE('',*,*,#130876,.F.); +#131302 = ORIENTED_EDGE('',*,*,#131117,.F.); +#131303 = ORIENTED_EDGE('',*,*,#131247,.T.); +#131304 = ORIENTED_EDGE('',*,*,#95628,.F.); +#131305 = ADVANCED_FACE('',(#131306),#130499,.T.); +#131306 = FACE_BOUND('',#131307,.T.); +#131307 = EDGE_LOOP('',(#131308,#131309,#131310,#131311)); +#131308 = ORIENTED_EDGE('',*,*,#131217,.T.); +#131309 = ORIENTED_EDGE('',*,*,#130585,.T.); +#131310 = ORIENTED_EDGE('',*,*,#131279,.T.); +#131311 = ORIENTED_EDGE('',*,*,#130476,.T.); +#131312 = ADVANCED_FACE('',(#131313),#131327,.F.); +#131313 = FACE_BOUND('',#131314,.T.); +#131314 = EDGE_LOOP('',(#131315,#131350,#131373,#131400)); +#131315 = ORIENTED_EDGE('',*,*,#131316,.F.); +#131316 = EDGE_CURVE('',#131317,#131319,#131321,.T.); +#131317 = VERTEX_POINT('',#131318); +#131318 = CARTESIAN_POINT('',(11.,5.15,-0.308197125857)); +#131319 = VERTEX_POINT('',#131320); +#131320 = CARTESIAN_POINT('',(11.,5.35,-0.308197125857)); +#131321 = SURFACE_CURVE('',#131322,(#131326,#131338),.PCURVE_S1.); +#131322 = LINE('',#131323,#131324); +#131323 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#131324 = VECTOR('',#131325,1.); +#131325 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131326 = PCURVE('',#131327,#131332); +#131327 = PLANE('',#131328); +#131328 = AXIS2_PLACEMENT_3D('',#131329,#131330,#131331); +#131329 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#128938 = DIRECTION('',(0.E+000,0.E+000,1.)); -#128939 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128940 = DEFINITIONAL_REPRESENTATION('',(#128941),#128945); -#128941 = LINE('',#128942,#128943); -#128942 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#128943 = VECTOR('',#128944,1.); -#128944 = DIRECTION('',(4.440892098501E-016,1.)); -#128945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128946 = PCURVE('',#128947,#128952); -#128947 = PLANE('',#128948); -#128948 = AXIS2_PLACEMENT_3D('',#128949,#128950,#128951); -#128949 = CARTESIAN_POINT('',(11.,5.25,-0.258196742327)); -#128950 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#128951 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#128952 = DEFINITIONAL_REPRESENTATION('',(#128953),#128957); -#128953 = LINE('',#128954,#128955); -#128954 = CARTESIAN_POINT('',(-5.25,-5.000038352949E-002)); -#128955 = VECTOR('',#128956,1.); -#128956 = DIRECTION('',(1.,0.E+000)); -#128957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128958 = ORIENTED_EDGE('',*,*,#128959,.F.); -#128959 = EDGE_CURVE('',#128960,#128925,#128962,.T.); -#128960 = VERTEX_POINT('',#128961); -#128961 = CARTESIAN_POINT('',(10.74341632541,5.15,-0.308197125857)); -#128962 = SURFACE_CURVE('',#128963,(#128967,#128974),.PCURVE_S1.); -#128963 = LINE('',#128964,#128965); -#128964 = CARTESIAN_POINT('',(10.74341632541,5.15,-0.308197125857)); -#128965 = VECTOR('',#128966,1.); -#128966 = DIRECTION('',(1.,0.E+000,0.E+000)); -#128967 = PCURVE('',#128935,#128968); -#128968 = DEFINITIONAL_REPRESENTATION('',(#128969),#128973); -#128969 = LINE('',#128970,#128971); -#128970 = CARTESIAN_POINT('',(1.7763568394E-015,5.15)); -#128971 = VECTOR('',#128972,1.); -#128972 = DIRECTION('',(1.,0.E+000)); -#128973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128974 = PCURVE('',#93138,#128975); -#128975 = DEFINITIONAL_REPRESENTATION('',(#128976),#128980); -#128976 = LINE('',#128977,#128978); -#128977 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#128978 = VECTOR('',#128979,1.); -#128979 = DIRECTION('',(0.E+000,1.)); -#128980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128981 = ORIENTED_EDGE('',*,*,#128982,.F.); -#128982 = EDGE_CURVE('',#128983,#128960,#128985,.T.); -#128983 = VERTEX_POINT('',#128984); -#128984 = CARTESIAN_POINT('',(10.74341632541,5.35,-0.308197125857)); -#128985 = SURFACE_CURVE('',#128986,(#128990,#128997),.PCURVE_S1.); -#128986 = LINE('',#128987,#128988); -#128987 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#131330 = DIRECTION('',(0.E+000,0.E+000,1.)); +#131331 = DIRECTION('',(1.,0.E+000,0.E+000)); +#131332 = DEFINITIONAL_REPRESENTATION('',(#131333),#131337); +#131333 = LINE('',#131334,#131335); +#131334 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#131335 = VECTOR('',#131336,1.); +#131336 = DIRECTION('',(4.440892098501E-016,1.)); +#131337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131338 = PCURVE('',#131339,#131344); +#131339 = PLANE('',#131340); +#131340 = AXIS2_PLACEMENT_3D('',#131341,#131342,#131343); +#131341 = CARTESIAN_POINT('',(11.,5.25,-0.258196742327)); +#131342 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#131343 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131344 = DEFINITIONAL_REPRESENTATION('',(#131345),#131349); +#131345 = LINE('',#131346,#131347); +#131346 = CARTESIAN_POINT('',(-5.25,-5.000038352949E-002)); +#131347 = VECTOR('',#131348,1.); +#131348 = DIRECTION('',(1.,0.E+000)); +#131349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131350 = ORIENTED_EDGE('',*,*,#131351,.F.); +#131351 = EDGE_CURVE('',#131352,#131317,#131354,.T.); +#131352 = VERTEX_POINT('',#131353); +#131353 = CARTESIAN_POINT('',(10.74341632541,5.15,-0.308197125857)); +#131354 = SURFACE_CURVE('',#131355,(#131359,#131366),.PCURVE_S1.); +#131355 = LINE('',#131356,#131357); +#131356 = CARTESIAN_POINT('',(10.74341632541,5.15,-0.308197125857)); +#131357 = VECTOR('',#131358,1.); +#131358 = DIRECTION('',(1.,0.E+000,0.E+000)); +#131359 = PCURVE('',#131327,#131360); +#131360 = DEFINITIONAL_REPRESENTATION('',(#131361),#131365); +#131361 = LINE('',#131362,#131363); +#131362 = CARTESIAN_POINT('',(1.7763568394E-015,5.15)); +#131363 = VECTOR('',#131364,1.); +#131364 = DIRECTION('',(1.,0.E+000)); +#131365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131366 = PCURVE('',#95530,#131367); +#131367 = DEFINITIONAL_REPRESENTATION('',(#131368),#131372); +#131368 = LINE('',#131369,#131370); +#131369 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#131370 = VECTOR('',#131371,1.); +#131371 = DIRECTION('',(0.E+000,1.)); +#131372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131373 = ORIENTED_EDGE('',*,*,#131374,.F.); +#131374 = EDGE_CURVE('',#131375,#131352,#131377,.T.); +#131375 = VERTEX_POINT('',#131376); +#131376 = CARTESIAN_POINT('',(10.74341632541,5.35,-0.308197125857)); +#131377 = SURFACE_CURVE('',#131378,(#131382,#131389),.PCURVE_S1.); +#131378 = LINE('',#131379,#131380); +#131379 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#128988 = VECTOR('',#128989,1.); -#128989 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#128990 = PCURVE('',#128935,#128991); -#128991 = DEFINITIONAL_REPRESENTATION('',(#128992),#128996); -#128992 = LINE('',#128993,#128994); -#128993 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#128994 = VECTOR('',#128995,1.); -#128995 = DIRECTION('',(-4.440892098501E-016,-1.)); -#128996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#128997 = PCURVE('',#128998,#129003); -#128998 = CYLINDRICAL_SURFACE('',#128999,0.308574064194); -#128999 = AXIS2_PLACEMENT_3D('',#129000,#129001,#129002); -#129000 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#131380 = VECTOR('',#131381,1.); +#131381 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131382 = PCURVE('',#131327,#131383); +#131383 = DEFINITIONAL_REPRESENTATION('',(#131384),#131388); +#131384 = LINE('',#131385,#131386); +#131385 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131386 = VECTOR('',#131387,1.); +#131387 = DIRECTION('',(-4.440892098501E-016,-1.)); +#131388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131389 = PCURVE('',#131390,#131395); +#131390 = CYLINDRICAL_SURFACE('',#131391,0.308574064194); +#131391 = AXIS2_PLACEMENT_3D('',#131392,#131393,#131394); +#131392 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#129001 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129002 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129003 = DEFINITIONAL_REPRESENTATION('',(#129004),#129007); -#129004 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129005,#129006), +#131393 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131394 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131395 = DEFINITIONAL_REPRESENTATION('',(#131396),#131399); +#131396 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131397,#131398), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#129005 = CARTESIAN_POINT('',(4.761821717947,-5.35)); -#129006 = CARTESIAN_POINT('',(4.761821717947,-5.15)); -#129007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131397 = CARTESIAN_POINT('',(4.761821717947,-5.35)); +#131398 = CARTESIAN_POINT('',(4.761821717947,-5.15)); +#131399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129008 = ORIENTED_EDGE('',*,*,#129009,.T.); -#129009 = EDGE_CURVE('',#128983,#128927,#129010,.T.); -#129010 = SURFACE_CURVE('',#129011,(#129015,#129022),.PCURVE_S1.); -#129011 = LINE('',#129012,#129013); -#129012 = CARTESIAN_POINT('',(10.74341632541,5.35,-0.308197125857)); -#129013 = VECTOR('',#129014,1.); -#129014 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129015 = PCURVE('',#128935,#129016); -#129016 = DEFINITIONAL_REPRESENTATION('',(#129017),#129021); -#129017 = LINE('',#129018,#129019); -#129018 = CARTESIAN_POINT('',(1.7763568394E-015,5.35)); -#129019 = VECTOR('',#129020,1.); -#129020 = DIRECTION('',(1.,0.E+000)); -#129021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129022 = PCURVE('',#93082,#129023); -#129023 = DEFINITIONAL_REPRESENTATION('',(#129024),#129028); -#129024 = LINE('',#129025,#129026); -#129025 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#129026 = VECTOR('',#129027,1.); -#129027 = DIRECTION('',(0.E+000,1.)); -#129028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129029 = ADVANCED_FACE('',(#129030),#129044,.F.); -#129030 = FACE_BOUND('',#129031,.T.); -#129031 = EDGE_LOOP('',(#129032,#129062,#129085,#129112)); -#129032 = ORIENTED_EDGE('',*,*,#129033,.F.); -#129033 = EDGE_CURVE('',#129034,#129036,#129038,.T.); -#129034 = VERTEX_POINT('',#129035); -#129035 = CARTESIAN_POINT('',(11.,5.35,-0.208196358798)); -#129036 = VERTEX_POINT('',#129037); -#129037 = CARTESIAN_POINT('',(11.,5.15,-0.208196358798)); -#129038 = SURFACE_CURVE('',#129039,(#129043,#129055),.PCURVE_S1.); -#129039 = LINE('',#129040,#129041); -#129040 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#129041 = VECTOR('',#129042,1.); -#129042 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129043 = PCURVE('',#129044,#129049); -#129044 = PLANE('',#129045); -#129045 = AXIS2_PLACEMENT_3D('',#129046,#129047,#129048); -#129046 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#131400 = ORIENTED_EDGE('',*,*,#131401,.T.); +#131401 = EDGE_CURVE('',#131375,#131319,#131402,.T.); +#131402 = SURFACE_CURVE('',#131403,(#131407,#131414),.PCURVE_S1.); +#131403 = LINE('',#131404,#131405); +#131404 = CARTESIAN_POINT('',(10.74341632541,5.35,-0.308197125857)); +#131405 = VECTOR('',#131406,1.); +#131406 = DIRECTION('',(1.,0.E+000,0.E+000)); +#131407 = PCURVE('',#131327,#131408); +#131408 = DEFINITIONAL_REPRESENTATION('',(#131409),#131413); +#131409 = LINE('',#131410,#131411); +#131410 = CARTESIAN_POINT('',(1.7763568394E-015,5.35)); +#131411 = VECTOR('',#131412,1.); +#131412 = DIRECTION('',(1.,0.E+000)); +#131413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131414 = PCURVE('',#95474,#131415); +#131415 = DEFINITIONAL_REPRESENTATION('',(#131416),#131420); +#131416 = LINE('',#131417,#131418); +#131417 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#131418 = VECTOR('',#131419,1.); +#131419 = DIRECTION('',(0.E+000,1.)); +#131420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131421 = ADVANCED_FACE('',(#131422),#131436,.F.); +#131422 = FACE_BOUND('',#131423,.T.); +#131423 = EDGE_LOOP('',(#131424,#131454,#131477,#131504)); +#131424 = ORIENTED_EDGE('',*,*,#131425,.F.); +#131425 = EDGE_CURVE('',#131426,#131428,#131430,.T.); +#131426 = VERTEX_POINT('',#131427); +#131427 = CARTESIAN_POINT('',(11.,5.35,-0.208196358798)); +#131428 = VERTEX_POINT('',#131429); +#131429 = CARTESIAN_POINT('',(11.,5.15,-0.208196358798)); +#131430 = SURFACE_CURVE('',#131431,(#131435,#131447),.PCURVE_S1.); +#131431 = LINE('',#131432,#131433); +#131432 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#131433 = VECTOR('',#131434,1.); +#131434 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131435 = PCURVE('',#131436,#131441); +#131436 = PLANE('',#131437); +#131437 = AXIS2_PLACEMENT_3D('',#131438,#131439,#131440); +#131438 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#129047 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129048 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#129049 = DEFINITIONAL_REPRESENTATION('',(#129050),#129054); -#129050 = LINE('',#129051,#129052); -#129051 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#129052 = VECTOR('',#129053,1.); -#129053 = DIRECTION('',(4.440892098501E-016,-1.)); -#129054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129055 = PCURVE('',#128947,#129056); -#129056 = DEFINITIONAL_REPRESENTATION('',(#129057),#129061); -#129057 = LINE('',#129058,#129059); -#129058 = CARTESIAN_POINT('',(-5.25,5.00003835295E-002)); -#129059 = VECTOR('',#129060,1.); -#129060 = DIRECTION('',(-1.,0.E+000)); -#129061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129062 = ORIENTED_EDGE('',*,*,#129063,.F.); -#129063 = EDGE_CURVE('',#129064,#129034,#129066,.T.); -#129064 = VERTEX_POINT('',#129065); -#129065 = CARTESIAN_POINT('',(10.740726081328,5.35,-0.208196358798)); -#129066 = SURFACE_CURVE('',#129067,(#129071,#129078),.PCURVE_S1.); -#129067 = LINE('',#129068,#129069); -#129068 = CARTESIAN_POINT('',(10.740726081328,5.35,-0.208196358798)); -#129069 = VECTOR('',#129070,1.); -#129070 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129071 = PCURVE('',#129044,#129072); -#129072 = DEFINITIONAL_REPRESENTATION('',(#129073),#129077); -#129073 = LINE('',#129074,#129075); -#129074 = CARTESIAN_POINT('',(-3.552713678801E-015,5.35)); -#129075 = VECTOR('',#129076,1.); -#129076 = DIRECTION('',(-1.,0.E+000)); -#129077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129078 = PCURVE('',#93082,#129079); -#129079 = DEFINITIONAL_REPRESENTATION('',(#129080),#129084); -#129080 = LINE('',#129081,#129082); -#129081 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#129082 = VECTOR('',#129083,1.); -#129083 = DIRECTION('',(0.E+000,1.)); -#129084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129085 = ORIENTED_EDGE('',*,*,#129086,.F.); -#129086 = EDGE_CURVE('',#129087,#129064,#129089,.T.); -#129087 = VERTEX_POINT('',#129088); -#129088 = CARTESIAN_POINT('',(10.740726081328,5.15,-0.208196358798)); -#129089 = SURFACE_CURVE('',#129090,(#129094,#129101),.PCURVE_S1.); -#129090 = LINE('',#129091,#129092); -#129091 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#131439 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#131440 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#131441 = DEFINITIONAL_REPRESENTATION('',(#131442),#131446); +#131442 = LINE('',#131443,#131444); +#131443 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#131444 = VECTOR('',#131445,1.); +#131445 = DIRECTION('',(4.440892098501E-016,-1.)); +#131446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131447 = PCURVE('',#131339,#131448); +#131448 = DEFINITIONAL_REPRESENTATION('',(#131449),#131453); +#131449 = LINE('',#131450,#131451); +#131450 = CARTESIAN_POINT('',(-5.25,5.00003835295E-002)); +#131451 = VECTOR('',#131452,1.); +#131452 = DIRECTION('',(-1.,0.E+000)); +#131453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131454 = ORIENTED_EDGE('',*,*,#131455,.F.); +#131455 = EDGE_CURVE('',#131456,#131426,#131458,.T.); +#131456 = VERTEX_POINT('',#131457); +#131457 = CARTESIAN_POINT('',(10.740726081328,5.35,-0.208196358798)); +#131458 = SURFACE_CURVE('',#131459,(#131463,#131470),.PCURVE_S1.); +#131459 = LINE('',#131460,#131461); +#131460 = CARTESIAN_POINT('',(10.740726081328,5.35,-0.208196358798)); +#131461 = VECTOR('',#131462,1.); +#131462 = DIRECTION('',(1.,0.E+000,0.E+000)); +#131463 = PCURVE('',#131436,#131464); +#131464 = DEFINITIONAL_REPRESENTATION('',(#131465),#131469); +#131465 = LINE('',#131466,#131467); +#131466 = CARTESIAN_POINT('',(-3.552713678801E-015,5.35)); +#131467 = VECTOR('',#131468,1.); +#131468 = DIRECTION('',(-1.,0.E+000)); +#131469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131470 = PCURVE('',#95474,#131471); +#131471 = DEFINITIONAL_REPRESENTATION('',(#131472),#131476); +#131472 = LINE('',#131473,#131474); +#131473 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#131474 = VECTOR('',#131475,1.); +#131475 = DIRECTION('',(0.E+000,1.)); +#131476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131477 = ORIENTED_EDGE('',*,*,#131478,.F.); +#131478 = EDGE_CURVE('',#131479,#131456,#131481,.T.); +#131479 = VERTEX_POINT('',#131480); +#131480 = CARTESIAN_POINT('',(10.740726081328,5.15,-0.208196358798)); +#131481 = SURFACE_CURVE('',#131482,(#131486,#131493),.PCURVE_S1.); +#131482 = LINE('',#131483,#131484); +#131483 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#129092 = VECTOR('',#129093,1.); -#129093 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129094 = PCURVE('',#129044,#129095); -#129095 = DEFINITIONAL_REPRESENTATION('',(#129096),#129100); -#129096 = LINE('',#129097,#129098); -#129097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129098 = VECTOR('',#129099,1.); -#129099 = DIRECTION('',(-4.440892098501E-016,1.)); -#129100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129101 = PCURVE('',#129102,#129107); -#129102 = CYLINDRICAL_SURFACE('',#129103,0.208574704164); -#129103 = AXIS2_PLACEMENT_3D('',#129104,#129105,#129106); -#129104 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#131484 = VECTOR('',#131485,1.); +#131485 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131486 = PCURVE('',#131436,#131487); +#131487 = DEFINITIONAL_REPRESENTATION('',(#131488),#131492); +#131488 = LINE('',#131489,#131490); +#131489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131490 = VECTOR('',#131491,1.); +#131491 = DIRECTION('',(-4.440892098501E-016,1.)); +#131492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131493 = PCURVE('',#131494,#131499); +#131494 = CYLINDRICAL_SURFACE('',#131495,0.208574704164); +#131495 = AXIS2_PLACEMENT_3D('',#131496,#131497,#131498); +#131496 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#129105 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129106 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129107 = DEFINITIONAL_REPRESENTATION('',(#129108),#129111); -#129108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129109,#129110), +#131497 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131498 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131499 = DEFINITIONAL_REPRESENTATION('',(#131500),#131503); +#131500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131501,#131502), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#129109 = CARTESIAN_POINT('',(4.772630242227,-5.15)); -#129110 = CARTESIAN_POINT('',(4.772630242227,-5.35)); -#129111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131501 = CARTESIAN_POINT('',(4.772630242227,-5.15)); +#131502 = CARTESIAN_POINT('',(4.772630242227,-5.35)); +#131503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129112 = ORIENTED_EDGE('',*,*,#129113,.T.); -#129113 = EDGE_CURVE('',#129087,#129036,#129114,.T.); -#129114 = SURFACE_CURVE('',#129115,(#129119,#129126),.PCURVE_S1.); -#129115 = LINE('',#129116,#129117); -#129116 = CARTESIAN_POINT('',(10.740726081328,5.15,-0.208196358798)); -#129117 = VECTOR('',#129118,1.); -#129118 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129119 = PCURVE('',#129044,#129120); -#129120 = DEFINITIONAL_REPRESENTATION('',(#129121),#129125); -#129121 = LINE('',#129122,#129123); -#129122 = CARTESIAN_POINT('',(-1.7763568394E-015,5.15)); -#129123 = VECTOR('',#129124,1.); -#129124 = DIRECTION('',(-1.,0.E+000)); -#129125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129126 = PCURVE('',#93138,#129127); -#129127 = DEFINITIONAL_REPRESENTATION('',(#129128),#129132); -#129128 = LINE('',#129129,#129130); -#129129 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#129130 = VECTOR('',#129131,1.); -#129131 = DIRECTION('',(0.E+000,1.)); -#129132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129133 = ADVANCED_FACE('',(#129134),#128998,.T.); -#129134 = FACE_BOUND('',#129135,.T.); -#129135 = EDGE_LOOP('',(#129136,#129163,#129164,#129187)); -#129136 = ORIENTED_EDGE('',*,*,#129137,.T.); -#129137 = EDGE_CURVE('',#129138,#128983,#129140,.T.); -#129138 = VERTEX_POINT('',#129139); -#129139 = CARTESIAN_POINT('',(10.419594812019,5.35,0.E+000)); -#129140 = SURFACE_CURVE('',#129141,(#129146,#129152),.PCURVE_S1.); -#129141 = CIRCLE('',#129142,0.308574064194); -#129142 = AXIS2_PLACEMENT_3D('',#129143,#129144,#129145); -#129143 = CARTESIAN_POINT('',(10.728168876214,5.35,2.640924866458E-017) - ); -#129144 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129145 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129146 = PCURVE('',#128998,#129147); -#129147 = DEFINITIONAL_REPRESENTATION('',(#129148),#129151); -#129148 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129149,#129150), +#131504 = ORIENTED_EDGE('',*,*,#131505,.T.); +#131505 = EDGE_CURVE('',#131479,#131428,#131506,.T.); +#131506 = SURFACE_CURVE('',#131507,(#131511,#131518),.PCURVE_S1.); +#131507 = LINE('',#131508,#131509); +#131508 = CARTESIAN_POINT('',(10.740726081328,5.15,-0.208196358798)); +#131509 = VECTOR('',#131510,1.); +#131510 = DIRECTION('',(1.,0.E+000,0.E+000)); +#131511 = PCURVE('',#131436,#131512); +#131512 = DEFINITIONAL_REPRESENTATION('',(#131513),#131517); +#131513 = LINE('',#131514,#131515); +#131514 = CARTESIAN_POINT('',(-1.7763568394E-015,5.15)); +#131515 = VECTOR('',#131516,1.); +#131516 = DIRECTION('',(-1.,0.E+000)); +#131517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131518 = PCURVE('',#95530,#131519); +#131519 = DEFINITIONAL_REPRESENTATION('',(#131520),#131524); +#131520 = LINE('',#131521,#131522); +#131521 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#131522 = VECTOR('',#131523,1.); +#131523 = DIRECTION('',(0.E+000,1.)); +#131524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131525 = ADVANCED_FACE('',(#131526),#131390,.T.); +#131526 = FACE_BOUND('',#131527,.T.); +#131527 = EDGE_LOOP('',(#131528,#131555,#131556,#131579)); +#131528 = ORIENTED_EDGE('',*,*,#131529,.T.); +#131529 = EDGE_CURVE('',#131530,#131375,#131532,.T.); +#131530 = VERTEX_POINT('',#131531); +#131531 = CARTESIAN_POINT('',(10.419594812019,5.35,0.E+000)); +#131532 = SURFACE_CURVE('',#131533,(#131538,#131544),.PCURVE_S1.); +#131533 = CIRCLE('',#131534,0.308574064194); +#131534 = AXIS2_PLACEMENT_3D('',#131535,#131536,#131537); +#131535 = CARTESIAN_POINT('',(10.728168876214,5.35,2.640924866458E-017) + ); +#131536 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131537 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131538 = PCURVE('',#131390,#131539); +#131539 = DEFINITIONAL_REPRESENTATION('',(#131540),#131543); +#131540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131541,#131542), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#129149 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#129150 = CARTESIAN_POINT('',(4.761821717947,-5.35)); -#129151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131541 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#131542 = CARTESIAN_POINT('',(4.761821717947,-5.35)); +#131543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129152 = PCURVE('',#93082,#129153); -#129153 = DEFINITIONAL_REPRESENTATION('',(#129154),#129162); -#129154 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129155,#129156,#129157, - #129158,#129159,#129160,#129161),.UNSPECIFIED.,.T.,.F.) +#131544 = PCURVE('',#95474,#131545); +#131545 = DEFINITIONAL_REPRESENTATION('',(#131546),#131554); +#131546 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131547,#131548,#131549, + #131550,#131551,#131552,#131553),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#129155 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#129156 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#129157 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#129158 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#129159 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#129160 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#129161 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#129162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129163 = ORIENTED_EDGE('',*,*,#128982,.T.); -#129164 = ORIENTED_EDGE('',*,*,#129165,.F.); -#129165 = EDGE_CURVE('',#129166,#128960,#129168,.T.); -#129166 = VERTEX_POINT('',#129167); -#129167 = CARTESIAN_POINT('',(10.419594812019,5.15,0.E+000)); -#129168 = SURFACE_CURVE('',#129169,(#129174,#129180),.PCURVE_S1.); -#129169 = CIRCLE('',#129170,0.308574064194); -#129170 = AXIS2_PLACEMENT_3D('',#129171,#129172,#129173); -#129171 = CARTESIAN_POINT('',(10.728168876214,5.15,2.640924866458E-017) - ); -#129172 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129173 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129174 = PCURVE('',#128998,#129175); -#129175 = DEFINITIONAL_REPRESENTATION('',(#129176),#129179); -#129176 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129177,#129178), +#131547 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#131548 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#131549 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#131550 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#131551 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#131552 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#131553 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#131554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131555 = ORIENTED_EDGE('',*,*,#131374,.T.); +#131556 = ORIENTED_EDGE('',*,*,#131557,.F.); +#131557 = EDGE_CURVE('',#131558,#131352,#131560,.T.); +#131558 = VERTEX_POINT('',#131559); +#131559 = CARTESIAN_POINT('',(10.419594812019,5.15,0.E+000)); +#131560 = SURFACE_CURVE('',#131561,(#131566,#131572),.PCURVE_S1.); +#131561 = CIRCLE('',#131562,0.308574064194); +#131562 = AXIS2_PLACEMENT_3D('',#131563,#131564,#131565); +#131563 = CARTESIAN_POINT('',(10.728168876214,5.15,2.640924866458E-017) + ); +#131564 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131565 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131566 = PCURVE('',#131390,#131567); +#131567 = DEFINITIONAL_REPRESENTATION('',(#131568),#131571); +#131568 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131569,#131570), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#129177 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#129178 = CARTESIAN_POINT('',(4.761821717947,-5.15)); -#129179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131569 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#131570 = CARTESIAN_POINT('',(4.761821717947,-5.15)); +#131571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129180 = PCURVE('',#93138,#129181); -#129181 = DEFINITIONAL_REPRESENTATION('',(#129182),#129186); -#129182 = CIRCLE('',#129183,0.308574064194); -#129183 = AXIS2_PLACEMENT_2D('',#129184,#129185); -#129184 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#129185 = DIRECTION('',(0.E+000,1.)); -#129186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131572 = PCURVE('',#95530,#131573); +#131573 = DEFINITIONAL_REPRESENTATION('',(#131574),#131578); +#131574 = CIRCLE('',#131575,0.308574064194); +#131575 = AXIS2_PLACEMENT_2D('',#131576,#131577); +#131576 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#131577 = DIRECTION('',(0.E+000,1.)); +#131578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129187 = ORIENTED_EDGE('',*,*,#129188,.T.); -#129188 = EDGE_CURVE('',#129166,#129138,#129189,.T.); -#129189 = SURFACE_CURVE('',#129190,(#129194,#129200),.PCURVE_S1.); -#129190 = LINE('',#129191,#129192); -#129191 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#131579 = ORIENTED_EDGE('',*,*,#131580,.T.); +#131580 = EDGE_CURVE('',#131558,#131530,#131581,.T.); +#131581 = SURFACE_CURVE('',#131582,(#131586,#131592),.PCURVE_S1.); +#131582 = LINE('',#131583,#131584); +#131583 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#129192 = VECTOR('',#129193,1.); -#129193 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129194 = PCURVE('',#128998,#129195); -#129195 = DEFINITIONAL_REPRESENTATION('',(#129196),#129199); -#129196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129197,#129198), +#131584 = VECTOR('',#131585,1.); +#131585 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131586 = PCURVE('',#131390,#131587); +#131587 = DEFINITIONAL_REPRESENTATION('',(#131588),#131591); +#131588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131589,#131590), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#129197 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#129198 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#129199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131589 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#131590 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#131591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129200 = PCURVE('',#129201,#129206); -#129201 = PLANE('',#129202); -#129202 = AXIS2_PLACEMENT_3D('',#129203,#129204,#129205); -#129203 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#131592 = PCURVE('',#131593,#131598); +#131593 = PLANE('',#131594); +#131594 = AXIS2_PLACEMENT_3D('',#131595,#131596,#131597); +#131595 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#129204 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129205 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129206 = DEFINITIONAL_REPRESENTATION('',(#129207),#129211); -#129207 = LINE('',#129208,#129209); -#129208 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#129209 = VECTOR('',#129210,1.); -#129210 = DIRECTION('',(-1.,0.E+000)); -#129211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129212 = ADVANCED_FACE('',(#129213),#129102,.F.); -#129213 = FACE_BOUND('',#129214,.F.); -#129214 = EDGE_LOOP('',(#129215,#129238,#129265,#129290)); -#129215 = ORIENTED_EDGE('',*,*,#129216,.F.); -#129216 = EDGE_CURVE('',#129217,#129087,#129219,.T.); -#129217 = VERTEX_POINT('',#129218); -#129218 = CARTESIAN_POINT('',(10.51959417205,5.15,0.E+000)); -#129219 = SURFACE_CURVE('',#129220,(#129225,#129231),.PCURVE_S1.); -#129220 = CIRCLE('',#129221,0.208574704164); -#129221 = AXIS2_PLACEMENT_3D('',#129222,#129223,#129224); -#129222 = CARTESIAN_POINT('',(10.728168876214,5.15,2.640924866458E-017) - ); -#129223 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129224 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129225 = PCURVE('',#129102,#129226); -#129226 = DEFINITIONAL_REPRESENTATION('',(#129227),#129230); -#129227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129228,#129229), +#131596 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131597 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131598 = DEFINITIONAL_REPRESENTATION('',(#131599),#131603); +#131599 = LINE('',#131600,#131601); +#131600 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#131601 = VECTOR('',#131602,1.); +#131602 = DIRECTION('',(-1.,0.E+000)); +#131603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131604 = ADVANCED_FACE('',(#131605),#131494,.F.); +#131605 = FACE_BOUND('',#131606,.F.); +#131606 = EDGE_LOOP('',(#131607,#131630,#131657,#131682)); +#131607 = ORIENTED_EDGE('',*,*,#131608,.F.); +#131608 = EDGE_CURVE('',#131609,#131479,#131611,.T.); +#131609 = VERTEX_POINT('',#131610); +#131610 = CARTESIAN_POINT('',(10.51959417205,5.15,0.E+000)); +#131611 = SURFACE_CURVE('',#131612,(#131617,#131623),.PCURVE_S1.); +#131612 = CIRCLE('',#131613,0.208574704164); +#131613 = AXIS2_PLACEMENT_3D('',#131614,#131615,#131616); +#131614 = CARTESIAN_POINT('',(10.728168876214,5.15,2.640924866458E-017) + ); +#131615 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131616 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131617 = PCURVE('',#131494,#131618); +#131618 = DEFINITIONAL_REPRESENTATION('',(#131619),#131622); +#131619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131620,#131621), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#129228 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#129229 = CARTESIAN_POINT('',(4.772630242227,-5.15)); -#129230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131620 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#131621 = CARTESIAN_POINT('',(4.772630242227,-5.15)); +#131622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129231 = PCURVE('',#93138,#129232); -#129232 = DEFINITIONAL_REPRESENTATION('',(#129233),#129237); -#129233 = CIRCLE('',#129234,0.208574704164); -#129234 = AXIS2_PLACEMENT_2D('',#129235,#129236); -#129235 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#129236 = DIRECTION('',(0.E+000,1.)); -#129237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131623 = PCURVE('',#95530,#131624); +#131624 = DEFINITIONAL_REPRESENTATION('',(#131625),#131629); +#131625 = CIRCLE('',#131626,0.208574704164); +#131626 = AXIS2_PLACEMENT_2D('',#131627,#131628); +#131627 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#131628 = DIRECTION('',(0.E+000,1.)); +#131629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129238 = ORIENTED_EDGE('',*,*,#129239,.F.); -#129239 = EDGE_CURVE('',#129240,#129217,#129242,.T.); -#129240 = VERTEX_POINT('',#129241); -#129241 = CARTESIAN_POINT('',(10.51959417205,5.35,0.E+000)); -#129242 = SURFACE_CURVE('',#129243,(#129247,#129253),.PCURVE_S1.); -#129243 = LINE('',#129244,#129245); -#129244 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#131630 = ORIENTED_EDGE('',*,*,#131631,.F.); +#131631 = EDGE_CURVE('',#131632,#131609,#131634,.T.); +#131632 = VERTEX_POINT('',#131633); +#131633 = CARTESIAN_POINT('',(10.51959417205,5.35,0.E+000)); +#131634 = SURFACE_CURVE('',#131635,(#131639,#131645),.PCURVE_S1.); +#131635 = LINE('',#131636,#131637); +#131636 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#129245 = VECTOR('',#129246,1.); -#129246 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129247 = PCURVE('',#129102,#129248); -#129248 = DEFINITIONAL_REPRESENTATION('',(#129249),#129252); -#129249 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129250,#129251), +#131637 = VECTOR('',#131638,1.); +#131638 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131639 = PCURVE('',#131494,#131640); +#131640 = DEFINITIONAL_REPRESENTATION('',(#131641),#131644); +#131641 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131642,#131643), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#129250 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#129251 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#129252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131642 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#131643 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#131644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129253 = PCURVE('',#129254,#129259); -#129254 = PLANE('',#129255); -#129255 = AXIS2_PLACEMENT_3D('',#129256,#129257,#129258); -#129256 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#131645 = PCURVE('',#131646,#131651); +#131646 = PLANE('',#131647); +#131647 = AXIS2_PLACEMENT_3D('',#131648,#131649,#131650); +#131648 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#129257 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129258 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129259 = DEFINITIONAL_REPRESENTATION('',(#129260),#129264); -#129260 = LINE('',#129261,#129262); -#129261 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#129262 = VECTOR('',#129263,1.); -#129263 = DIRECTION('',(-1.,0.E+000)); -#129264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129265 = ORIENTED_EDGE('',*,*,#129266,.T.); -#129266 = EDGE_CURVE('',#129240,#129064,#129267,.T.); -#129267 = SURFACE_CURVE('',#129268,(#129273,#129279),.PCURVE_S1.); -#129268 = CIRCLE('',#129269,0.208574704164); -#129269 = AXIS2_PLACEMENT_3D('',#129270,#129271,#129272); -#129270 = CARTESIAN_POINT('',(10.728168876214,5.35,2.640924866458E-017) - ); -#129271 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129272 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129273 = PCURVE('',#129102,#129274); -#129274 = DEFINITIONAL_REPRESENTATION('',(#129275),#129278); -#129275 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129276,#129277), +#131649 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131650 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131651 = DEFINITIONAL_REPRESENTATION('',(#131652),#131656); +#131652 = LINE('',#131653,#131654); +#131653 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#131654 = VECTOR('',#131655,1.); +#131655 = DIRECTION('',(-1.,0.E+000)); +#131656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131657 = ORIENTED_EDGE('',*,*,#131658,.T.); +#131658 = EDGE_CURVE('',#131632,#131456,#131659,.T.); +#131659 = SURFACE_CURVE('',#131660,(#131665,#131671),.PCURVE_S1.); +#131660 = CIRCLE('',#131661,0.208574704164); +#131661 = AXIS2_PLACEMENT_3D('',#131662,#131663,#131664); +#131662 = CARTESIAN_POINT('',(10.728168876214,5.35,2.640924866458E-017) + ); +#131663 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131664 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#131665 = PCURVE('',#131494,#131666); +#131666 = DEFINITIONAL_REPRESENTATION('',(#131667),#131670); +#131667 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131668,#131669), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#129276 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#129277 = CARTESIAN_POINT('',(4.772630242227,-5.35)); -#129278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131668 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#131669 = CARTESIAN_POINT('',(4.772630242227,-5.35)); +#131670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129279 = PCURVE('',#93082,#129280); -#129280 = DEFINITIONAL_REPRESENTATION('',(#129281),#129289); -#129281 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129282,#129283,#129284, - #129285,#129286,#129287,#129288),.UNSPECIFIED.,.T.,.F.) +#131671 = PCURVE('',#95474,#131672); +#131672 = DEFINITIONAL_REPRESENTATION('',(#131673),#131681); +#131673 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131674,#131675,#131676, + #131677,#131678,#131679,#131680),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#129282 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#129283 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#129284 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#129285 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#129286 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#129287 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#129288 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#129289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129290 = ORIENTED_EDGE('',*,*,#129086,.F.); -#129291 = ADVANCED_FACE('',(#129292),#129254,.T.); -#129292 = FACE_BOUND('',#129293,.T.); -#129293 = EDGE_LOOP('',(#129294,#129323,#129344,#129345)); -#129294 = ORIENTED_EDGE('',*,*,#129295,.T.); -#129295 = EDGE_CURVE('',#129296,#129298,#129300,.T.); -#129296 = VERTEX_POINT('',#129297); -#129297 = CARTESIAN_POINT('',(10.51959417205,5.35,0.530776333563)); -#129298 = VERTEX_POINT('',#129299); -#129299 = CARTESIAN_POINT('',(10.51959417205,5.15,0.530776333563)); -#129300 = SURFACE_CURVE('',#129301,(#129305,#129312),.PCURVE_S1.); -#129301 = LINE('',#129302,#129303); -#129302 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#131674 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#131675 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#131676 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#131677 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#131678 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#131679 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#131680 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#131681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131682 = ORIENTED_EDGE('',*,*,#131478,.F.); +#131683 = ADVANCED_FACE('',(#131684),#131646,.T.); +#131684 = FACE_BOUND('',#131685,.T.); +#131685 = EDGE_LOOP('',(#131686,#131715,#131736,#131737)); +#131686 = ORIENTED_EDGE('',*,*,#131687,.T.); +#131687 = EDGE_CURVE('',#131688,#131690,#131692,.T.); +#131688 = VERTEX_POINT('',#131689); +#131689 = CARTESIAN_POINT('',(10.51959417205,5.35,0.530776333563)); +#131690 = VERTEX_POINT('',#131691); +#131691 = CARTESIAN_POINT('',(10.51959417205,5.15,0.530776333563)); +#131692 = SURFACE_CURVE('',#131693,(#131697,#131704),.PCURVE_S1.); +#131693 = LINE('',#131694,#131695); +#131694 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#129303 = VECTOR('',#129304,1.); -#129304 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129305 = PCURVE('',#129254,#129306); -#129306 = DEFINITIONAL_REPRESENTATION('',(#129307),#129311); -#129307 = LINE('',#129308,#129309); -#129308 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129309 = VECTOR('',#129310,1.); -#129310 = DIRECTION('',(-1.,0.E+000)); -#129311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129312 = PCURVE('',#129313,#129318); -#129313 = CYLINDRICAL_SURFACE('',#129314,0.2192697516); -#129314 = AXIS2_PLACEMENT_3D('',#129315,#129316,#129317); -#129315 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#131695 = VECTOR('',#131696,1.); +#131696 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131697 = PCURVE('',#131646,#131698); +#131698 = DEFINITIONAL_REPRESENTATION('',(#131699),#131703); +#131699 = LINE('',#131700,#131701); +#131700 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131701 = VECTOR('',#131702,1.); +#131702 = DIRECTION('',(-1.,0.E+000)); +#131703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131704 = PCURVE('',#131705,#131710); +#131705 = CYLINDRICAL_SURFACE('',#131706,0.2192697516); +#131706 = AXIS2_PLACEMENT_3D('',#131707,#131708,#131709); +#131707 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#129316 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129317 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129318 = DEFINITIONAL_REPRESENTATION('',(#129319),#129322); -#129319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129320,#129321), +#131708 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131709 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131710 = DEFINITIONAL_REPRESENTATION('',(#131711),#131714); +#131711 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131712,#131713), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#129320 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#129321 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#129322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129323 = ORIENTED_EDGE('',*,*,#129324,.T.); -#129324 = EDGE_CURVE('',#129298,#129217,#129325,.T.); -#129325 = SURFACE_CURVE('',#129326,(#129330,#129337),.PCURVE_S1.); -#129326 = LINE('',#129327,#129328); -#129327 = CARTESIAN_POINT('',(10.51959417205,5.15,0.530776333563)); -#129328 = VECTOR('',#129329,1.); -#129329 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129330 = PCURVE('',#129254,#129331); -#129331 = DEFINITIONAL_REPRESENTATION('',(#129332),#129336); -#129332 = LINE('',#129333,#129334); -#129333 = CARTESIAN_POINT('',(5.15,0.E+000)); -#129334 = VECTOR('',#129335,1.); -#129335 = DIRECTION('',(0.E+000,-1.)); -#129336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129337 = PCURVE('',#93138,#129338); -#129338 = DEFINITIONAL_REPRESENTATION('',(#129339),#129343); -#129339 = LINE('',#129340,#129341); -#129340 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); -#129341 = VECTOR('',#129342,1.); -#129342 = DIRECTION('',(1.,0.E+000)); -#129343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129344 = ORIENTED_EDGE('',*,*,#129239,.F.); -#129345 = ORIENTED_EDGE('',*,*,#129346,.F.); -#129346 = EDGE_CURVE('',#129296,#129240,#129347,.T.); -#129347 = SURFACE_CURVE('',#129348,(#129352,#129359),.PCURVE_S1.); -#129348 = LINE('',#129349,#129350); -#129349 = CARTESIAN_POINT('',(10.51959417205,5.35,0.530776333563)); -#129350 = VECTOR('',#129351,1.); -#129351 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129352 = PCURVE('',#129254,#129353); -#129353 = DEFINITIONAL_REPRESENTATION('',(#129354),#129358); -#129354 = LINE('',#129355,#129356); -#129355 = CARTESIAN_POINT('',(5.35,0.E+000)); -#129356 = VECTOR('',#129357,1.); -#129357 = DIRECTION('',(0.E+000,-1.)); -#129358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129359 = PCURVE('',#93082,#129360); -#129360 = DEFINITIONAL_REPRESENTATION('',(#129361),#129365); -#129361 = LINE('',#129362,#129363); -#129362 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); -#129363 = VECTOR('',#129364,1.); -#129364 = DIRECTION('',(-1.,0.E+000)); -#129365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129366 = ADVANCED_FACE('',(#129367),#129201,.T.); -#129367 = FACE_BOUND('',#129368,.T.); -#129368 = EDGE_LOOP('',(#129369,#129398,#129419,#129420)); -#129369 = ORIENTED_EDGE('',*,*,#129370,.T.); -#129370 = EDGE_CURVE('',#129371,#129373,#129375,.T.); -#129371 = VERTEX_POINT('',#129372); -#129372 = CARTESIAN_POINT('',(10.419594812019,5.15,0.530776333563)); -#129373 = VERTEX_POINT('',#129374); -#129374 = CARTESIAN_POINT('',(10.419594812019,5.35,0.530776333563)); -#129375 = SURFACE_CURVE('',#129376,(#129380,#129387),.PCURVE_S1.); -#129376 = LINE('',#129377,#129378); -#129377 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#131712 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#131713 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#131714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131715 = ORIENTED_EDGE('',*,*,#131716,.T.); +#131716 = EDGE_CURVE('',#131690,#131609,#131717,.T.); +#131717 = SURFACE_CURVE('',#131718,(#131722,#131729),.PCURVE_S1.); +#131718 = LINE('',#131719,#131720); +#131719 = CARTESIAN_POINT('',(10.51959417205,5.15,0.530776333563)); +#131720 = VECTOR('',#131721,1.); +#131721 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#131722 = PCURVE('',#131646,#131723); +#131723 = DEFINITIONAL_REPRESENTATION('',(#131724),#131728); +#131724 = LINE('',#131725,#131726); +#131725 = CARTESIAN_POINT('',(5.15,0.E+000)); +#131726 = VECTOR('',#131727,1.); +#131727 = DIRECTION('',(0.E+000,-1.)); +#131728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131729 = PCURVE('',#95530,#131730); +#131730 = DEFINITIONAL_REPRESENTATION('',(#131731),#131735); +#131731 = LINE('',#131732,#131733); +#131732 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); +#131733 = VECTOR('',#131734,1.); +#131734 = DIRECTION('',(1.,0.E+000)); +#131735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131736 = ORIENTED_EDGE('',*,*,#131631,.F.); +#131737 = ORIENTED_EDGE('',*,*,#131738,.F.); +#131738 = EDGE_CURVE('',#131688,#131632,#131739,.T.); +#131739 = SURFACE_CURVE('',#131740,(#131744,#131751),.PCURVE_S1.); +#131740 = LINE('',#131741,#131742); +#131741 = CARTESIAN_POINT('',(10.51959417205,5.35,0.530776333563)); +#131742 = VECTOR('',#131743,1.); +#131743 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#131744 = PCURVE('',#131646,#131745); +#131745 = DEFINITIONAL_REPRESENTATION('',(#131746),#131750); +#131746 = LINE('',#131747,#131748); +#131747 = CARTESIAN_POINT('',(5.35,0.E+000)); +#131748 = VECTOR('',#131749,1.); +#131749 = DIRECTION('',(0.E+000,-1.)); +#131750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131751 = PCURVE('',#95474,#131752); +#131752 = DEFINITIONAL_REPRESENTATION('',(#131753),#131757); +#131753 = LINE('',#131754,#131755); +#131754 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); +#131755 = VECTOR('',#131756,1.); +#131756 = DIRECTION('',(-1.,0.E+000)); +#131757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131758 = ADVANCED_FACE('',(#131759),#131593,.T.); +#131759 = FACE_BOUND('',#131760,.T.); +#131760 = EDGE_LOOP('',(#131761,#131790,#131811,#131812)); +#131761 = ORIENTED_EDGE('',*,*,#131762,.T.); +#131762 = EDGE_CURVE('',#131763,#131765,#131767,.T.); +#131763 = VERTEX_POINT('',#131764); +#131764 = CARTESIAN_POINT('',(10.419594812019,5.15,0.530776333563)); +#131765 = VERTEX_POINT('',#131766); +#131766 = CARTESIAN_POINT('',(10.419594812019,5.35,0.530776333563)); +#131767 = SURFACE_CURVE('',#131768,(#131772,#131779),.PCURVE_S1.); +#131768 = LINE('',#131769,#131770); +#131769 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#129378 = VECTOR('',#129379,1.); -#129379 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129380 = PCURVE('',#129201,#129381); -#129381 = DEFINITIONAL_REPRESENTATION('',(#129382),#129386); -#129382 = LINE('',#129383,#129384); -#129383 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129384 = VECTOR('',#129385,1.); -#129385 = DIRECTION('',(-1.,0.E+000)); -#129386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129387 = PCURVE('',#129388,#129393); -#129388 = CYLINDRICAL_SURFACE('',#129389,0.119270391569); -#129389 = AXIS2_PLACEMENT_3D('',#129390,#129391,#129392); -#129390 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#131770 = VECTOR('',#131771,1.); +#131771 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131772 = PCURVE('',#131593,#131773); +#131773 = DEFINITIONAL_REPRESENTATION('',(#131774),#131778); +#131774 = LINE('',#131775,#131776); +#131775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#131776 = VECTOR('',#131777,1.); +#131777 = DIRECTION('',(-1.,0.E+000)); +#131778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131779 = PCURVE('',#131780,#131785); +#131780 = CYLINDRICAL_SURFACE('',#131781,0.119270391569); +#131781 = AXIS2_PLACEMENT_3D('',#131782,#131783,#131784); +#131782 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#129391 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129392 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129393 = DEFINITIONAL_REPRESENTATION('',(#129394),#129397); -#129394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129395,#129396), +#131783 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131784 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131785 = DEFINITIONAL_REPRESENTATION('',(#131786),#131789); +#131786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131787,#131788), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#129395 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#129396 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#129397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129398 = ORIENTED_EDGE('',*,*,#129399,.T.); -#129399 = EDGE_CURVE('',#129373,#129138,#129400,.T.); -#129400 = SURFACE_CURVE('',#129401,(#129405,#129412),.PCURVE_S1.); -#129401 = LINE('',#129402,#129403); -#129402 = CARTESIAN_POINT('',(10.419594812019,5.35,0.530776333563)); -#129403 = VECTOR('',#129404,1.); -#129404 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129405 = PCURVE('',#129201,#129406); -#129406 = DEFINITIONAL_REPRESENTATION('',(#129407),#129411); -#129407 = LINE('',#129408,#129409); -#129408 = CARTESIAN_POINT('',(-5.35,0.E+000)); -#129409 = VECTOR('',#129410,1.); -#129410 = DIRECTION('',(0.E+000,-1.)); -#129411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129412 = PCURVE('',#93082,#129413); -#129413 = DEFINITIONAL_REPRESENTATION('',(#129414),#129418); -#129414 = LINE('',#129415,#129416); -#129415 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#129416 = VECTOR('',#129417,1.); -#129417 = DIRECTION('',(-1.,0.E+000)); -#129418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129419 = ORIENTED_EDGE('',*,*,#129188,.F.); -#129420 = ORIENTED_EDGE('',*,*,#129421,.F.); -#129421 = EDGE_CURVE('',#129371,#129166,#129422,.T.); -#129422 = SURFACE_CURVE('',#129423,(#129427,#129434),.PCURVE_S1.); -#129423 = LINE('',#129424,#129425); -#129424 = CARTESIAN_POINT('',(10.419594812019,5.15,0.530776333563)); -#129425 = VECTOR('',#129426,1.); -#129426 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129427 = PCURVE('',#129201,#129428); -#129428 = DEFINITIONAL_REPRESENTATION('',(#129429),#129433); -#129429 = LINE('',#129430,#129431); -#129430 = CARTESIAN_POINT('',(-5.15,0.E+000)); -#129431 = VECTOR('',#129432,1.); -#129432 = DIRECTION('',(0.E+000,-1.)); -#129433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129434 = PCURVE('',#93138,#129435); -#129435 = DEFINITIONAL_REPRESENTATION('',(#129436),#129440); -#129436 = LINE('',#129437,#129438); -#129437 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#129438 = VECTOR('',#129439,1.); -#129439 = DIRECTION('',(1.,0.E+000)); -#129440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129441 = ADVANCED_FACE('',(#129442),#129388,.F.); -#129442 = FACE_BOUND('',#129443,.F.); -#129443 = EDGE_LOOP('',(#129444,#129445,#129468,#129490)); -#129444 = ORIENTED_EDGE('',*,*,#129370,.T.); -#129445 = ORIENTED_EDGE('',*,*,#129446,.F.); -#129446 = EDGE_CURVE('',#129447,#129373,#129449,.T.); -#129447 = VERTEX_POINT('',#129448); -#129448 = CARTESIAN_POINT('',(10.303662633502,5.35,0.65)); -#129449 = SURFACE_CURVE('',#129450,(#129455,#129461),.PCURVE_S1.); -#129450 = CIRCLE('',#129451,0.119270391569); -#129451 = AXIS2_PLACEMENT_3D('',#129452,#129453,#129454); -#129452 = CARTESIAN_POINT('',(10.30032442045,5.35,0.530776333563)); -#129453 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129454 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129455 = PCURVE('',#129388,#129456); -#129456 = DEFINITIONAL_REPRESENTATION('',(#129457),#129460); -#129457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129458,#129459), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), - .PIECEWISE_BEZIER_KNOTS.); -#129458 = CARTESIAN_POINT('',(1.598788597134,5.35)); -#129459 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#129460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129461 = PCURVE('',#93082,#129462); -#129462 = DEFINITIONAL_REPRESENTATION('',(#129463),#129467); -#129463 = CIRCLE('',#129464,0.119270391569); -#129464 = AXIS2_PLACEMENT_2D('',#129465,#129466); -#129465 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#129466 = DIRECTION('',(0.E+000,-1.)); -#129467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131787 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#131788 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#131789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129468 = ORIENTED_EDGE('',*,*,#129469,.T.); -#129469 = EDGE_CURVE('',#129447,#129470,#129472,.T.); -#129470 = VERTEX_POINT('',#129471); -#129471 = CARTESIAN_POINT('',(10.303662633502,5.15,0.65)); -#129472 = SURFACE_CURVE('',#129473,(#129477,#129483),.PCURVE_S1.); -#129473 = LINE('',#129474,#129475); -#129474 = CARTESIAN_POINT('',(10.303662633502,5.15,0.65)); -#129475 = VECTOR('',#129476,1.); -#129476 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129477 = PCURVE('',#129388,#129478); -#129478 = DEFINITIONAL_REPRESENTATION('',(#129479),#129482); -#129479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129480,#129481), +#131790 = ORIENTED_EDGE('',*,*,#131791,.T.); +#131791 = EDGE_CURVE('',#131765,#131530,#131792,.T.); +#131792 = SURFACE_CURVE('',#131793,(#131797,#131804),.PCURVE_S1.); +#131793 = LINE('',#131794,#131795); +#131794 = CARTESIAN_POINT('',(10.419594812019,5.35,0.530776333563)); +#131795 = VECTOR('',#131796,1.); +#131796 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#131797 = PCURVE('',#131593,#131798); +#131798 = DEFINITIONAL_REPRESENTATION('',(#131799),#131803); +#131799 = LINE('',#131800,#131801); +#131800 = CARTESIAN_POINT('',(-5.35,0.E+000)); +#131801 = VECTOR('',#131802,1.); +#131802 = DIRECTION('',(0.E+000,-1.)); +#131803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131804 = PCURVE('',#95474,#131805); +#131805 = DEFINITIONAL_REPRESENTATION('',(#131806),#131810); +#131806 = LINE('',#131807,#131808); +#131807 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#131808 = VECTOR('',#131809,1.); +#131809 = DIRECTION('',(-1.,0.E+000)); +#131810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131811 = ORIENTED_EDGE('',*,*,#131580,.F.); +#131812 = ORIENTED_EDGE('',*,*,#131813,.F.); +#131813 = EDGE_CURVE('',#131763,#131558,#131814,.T.); +#131814 = SURFACE_CURVE('',#131815,(#131819,#131826),.PCURVE_S1.); +#131815 = LINE('',#131816,#131817); +#131816 = CARTESIAN_POINT('',(10.419594812019,5.15,0.530776333563)); +#131817 = VECTOR('',#131818,1.); +#131818 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#131819 = PCURVE('',#131593,#131820); +#131820 = DEFINITIONAL_REPRESENTATION('',(#131821),#131825); +#131821 = LINE('',#131822,#131823); +#131822 = CARTESIAN_POINT('',(-5.15,0.E+000)); +#131823 = VECTOR('',#131824,1.); +#131824 = DIRECTION('',(0.E+000,-1.)); +#131825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131826 = PCURVE('',#95530,#131827); +#131827 = DEFINITIONAL_REPRESENTATION('',(#131828),#131832); +#131828 = LINE('',#131829,#131830); +#131829 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#131830 = VECTOR('',#131831,1.); +#131831 = DIRECTION('',(1.,0.E+000)); +#131832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131833 = ADVANCED_FACE('',(#131834),#131780,.F.); +#131834 = FACE_BOUND('',#131835,.F.); +#131835 = EDGE_LOOP('',(#131836,#131837,#131860,#131882)); +#131836 = ORIENTED_EDGE('',*,*,#131762,.T.); +#131837 = ORIENTED_EDGE('',*,*,#131838,.F.); +#131838 = EDGE_CURVE('',#131839,#131765,#131841,.T.); +#131839 = VERTEX_POINT('',#131840); +#131840 = CARTESIAN_POINT('',(10.303662633502,5.35,0.65)); +#131841 = SURFACE_CURVE('',#131842,(#131847,#131853),.PCURVE_S1.); +#131842 = CIRCLE('',#131843,0.119270391569); +#131843 = AXIS2_PLACEMENT_3D('',#131844,#131845,#131846); +#131844 = CARTESIAN_POINT('',(10.30032442045,5.35,0.530776333563)); +#131845 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131846 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131847 = PCURVE('',#131780,#131848); +#131848 = DEFINITIONAL_REPRESENTATION('',(#131849),#131852); +#131849 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131850,#131851), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), + .PIECEWISE_BEZIER_KNOTS.); +#131850 = CARTESIAN_POINT('',(1.598788597134,5.35)); +#131851 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#131852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131853 = PCURVE('',#95474,#131854); +#131854 = DEFINITIONAL_REPRESENTATION('',(#131855),#131859); +#131855 = CIRCLE('',#131856,0.119270391569); +#131856 = AXIS2_PLACEMENT_2D('',#131857,#131858); +#131857 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#131858 = DIRECTION('',(0.E+000,-1.)); +#131859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131860 = ORIENTED_EDGE('',*,*,#131861,.T.); +#131861 = EDGE_CURVE('',#131839,#131862,#131864,.T.); +#131862 = VERTEX_POINT('',#131863); +#131863 = CARTESIAN_POINT('',(10.303662633502,5.15,0.65)); +#131864 = SURFACE_CURVE('',#131865,(#131869,#131875),.PCURVE_S1.); +#131865 = LINE('',#131866,#131867); +#131866 = CARTESIAN_POINT('',(10.303662633502,5.15,0.65)); +#131867 = VECTOR('',#131868,1.); +#131868 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#131869 = PCURVE('',#131780,#131870); +#131870 = DEFINITIONAL_REPRESENTATION('',(#131871),#131874); +#131871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131872,#131873), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#129480 = CARTESIAN_POINT('',(1.598788597134,5.35)); -#129481 = CARTESIAN_POINT('',(1.598788597134,5.15)); -#129482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129483 = PCURVE('',#93110,#129484); -#129484 = DEFINITIONAL_REPRESENTATION('',(#129485),#129489); -#129485 = LINE('',#129486,#129487); -#129486 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#129487 = VECTOR('',#129488,1.); -#129488 = DIRECTION('',(4.440892098501E-016,-1.)); -#129489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129490 = ORIENTED_EDGE('',*,*,#129491,.T.); -#129491 = EDGE_CURVE('',#129470,#129371,#129492,.T.); -#129492 = SURFACE_CURVE('',#129493,(#129498,#129504),.PCURVE_S1.); -#129493 = CIRCLE('',#129494,0.119270391569); -#129494 = AXIS2_PLACEMENT_3D('',#129495,#129496,#129497); -#129495 = CARTESIAN_POINT('',(10.30032442045,5.15,0.530776333563)); -#129496 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129497 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129498 = PCURVE('',#129388,#129499); -#129499 = DEFINITIONAL_REPRESENTATION('',(#129500),#129503); -#129500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129501,#129502), +#131872 = CARTESIAN_POINT('',(1.598788597134,5.35)); +#131873 = CARTESIAN_POINT('',(1.598788597134,5.15)); +#131874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131875 = PCURVE('',#95502,#131876); +#131876 = DEFINITIONAL_REPRESENTATION('',(#131877),#131881); +#131877 = LINE('',#131878,#131879); +#131878 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#131879 = VECTOR('',#131880,1.); +#131880 = DIRECTION('',(4.440892098501E-016,-1.)); +#131881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131882 = ORIENTED_EDGE('',*,*,#131883,.T.); +#131883 = EDGE_CURVE('',#131862,#131763,#131884,.T.); +#131884 = SURFACE_CURVE('',#131885,(#131890,#131896),.PCURVE_S1.); +#131885 = CIRCLE('',#131886,0.119270391569); +#131886 = AXIS2_PLACEMENT_3D('',#131887,#131888,#131889); +#131887 = CARTESIAN_POINT('',(10.30032442045,5.15,0.530776333563)); +#131888 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131889 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131890 = PCURVE('',#131780,#131891); +#131891 = DEFINITIONAL_REPRESENTATION('',(#131892),#131895); +#131892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131893,#131894), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#129501 = CARTESIAN_POINT('',(1.598788597134,5.15)); -#129502 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#129503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131893 = CARTESIAN_POINT('',(1.598788597134,5.15)); +#131894 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#131895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129504 = PCURVE('',#93138,#129505); -#129505 = DEFINITIONAL_REPRESENTATION('',(#129506),#129514); -#129506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129507,#129508,#129509, - #129510,#129511,#129512,#129513),.UNSPECIFIED.,.T.,.F.) +#131896 = PCURVE('',#95530,#131897); +#131897 = DEFINITIONAL_REPRESENTATION('',(#131898),#131906); +#131898 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131899,#131900,#131901, + #131902,#131903,#131904,#131905),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#129507 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#129508 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#129509 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#129510 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#129511 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#129512 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#129513 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#129514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129515 = ADVANCED_FACE('',(#129516),#129313,.T.); -#129516 = FACE_BOUND('',#129517,.T.); -#129517 = EDGE_LOOP('',(#129518,#129519,#129542,#129564)); -#129518 = ORIENTED_EDGE('',*,*,#129295,.F.); -#129519 = ORIENTED_EDGE('',*,*,#129520,.F.); -#129520 = EDGE_CURVE('',#129521,#129296,#129523,.T.); -#129521 = VERTEX_POINT('',#129522); -#129522 = CARTESIAN_POINT('',(10.304819755875,5.35,0.75)); -#129523 = SURFACE_CURVE('',#129524,(#129529,#129535),.PCURVE_S1.); -#129524 = CIRCLE('',#129525,0.2192697516); -#129525 = AXIS2_PLACEMENT_3D('',#129526,#129527,#129528); -#129526 = CARTESIAN_POINT('',(10.30032442045,5.35,0.530776333563)); -#129527 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129528 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129529 = PCURVE('',#129313,#129530); -#129530 = DEFINITIONAL_REPRESENTATION('',(#129531),#129534); -#129531 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129532,#129533), +#131899 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#131900 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#131901 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#131902 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#131903 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#131904 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#131905 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#131906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131907 = ADVANCED_FACE('',(#131908),#131705,.T.); +#131908 = FACE_BOUND('',#131909,.T.); +#131909 = EDGE_LOOP('',(#131910,#131911,#131934,#131956)); +#131910 = ORIENTED_EDGE('',*,*,#131687,.F.); +#131911 = ORIENTED_EDGE('',*,*,#131912,.F.); +#131912 = EDGE_CURVE('',#131913,#131688,#131915,.T.); +#131913 = VERTEX_POINT('',#131914); +#131914 = CARTESIAN_POINT('',(10.304819755875,5.35,0.75)); +#131915 = SURFACE_CURVE('',#131916,(#131921,#131927),.PCURVE_S1.); +#131916 = CIRCLE('',#131917,0.2192697516); +#131917 = AXIS2_PLACEMENT_3D('',#131918,#131919,#131920); +#131918 = CARTESIAN_POINT('',(10.30032442045,5.35,0.530776333563)); +#131919 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131920 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131921 = PCURVE('',#131705,#131922); +#131922 = DEFINITIONAL_REPRESENTATION('',(#131923),#131926); +#131923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131924,#131925), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#129532 = CARTESIAN_POINT('',(1.591299156552,5.35)); -#129533 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#129534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129535 = PCURVE('',#93082,#129536); -#129536 = DEFINITIONAL_REPRESENTATION('',(#129537),#129541); -#129537 = CIRCLE('',#129538,0.2192697516); -#129538 = AXIS2_PLACEMENT_2D('',#129539,#129540); -#129539 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#129540 = DIRECTION('',(0.E+000,-1.)); -#129541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129542 = ORIENTED_EDGE('',*,*,#129543,.F.); -#129543 = EDGE_CURVE('',#129544,#129521,#129546,.T.); -#129544 = VERTEX_POINT('',#129545); -#129545 = CARTESIAN_POINT('',(10.304819755875,5.15,0.75)); -#129546 = SURFACE_CURVE('',#129547,(#129551,#129557),.PCURVE_S1.); -#129547 = LINE('',#129548,#129549); -#129548 = CARTESIAN_POINT('',(10.304819755875,5.15,0.75)); -#129549 = VECTOR('',#129550,1.); -#129550 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129551 = PCURVE('',#129313,#129552); -#129552 = DEFINITIONAL_REPRESENTATION('',(#129553),#129556); -#129553 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129554,#129555), +#131924 = CARTESIAN_POINT('',(1.591299156552,5.35)); +#131925 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#131926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131927 = PCURVE('',#95474,#131928); +#131928 = DEFINITIONAL_REPRESENTATION('',(#131929),#131933); +#131929 = CIRCLE('',#131930,0.2192697516); +#131930 = AXIS2_PLACEMENT_2D('',#131931,#131932); +#131931 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#131932 = DIRECTION('',(0.E+000,-1.)); +#131933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131934 = ORIENTED_EDGE('',*,*,#131935,.F.); +#131935 = EDGE_CURVE('',#131936,#131913,#131938,.T.); +#131936 = VERTEX_POINT('',#131937); +#131937 = CARTESIAN_POINT('',(10.304819755875,5.15,0.75)); +#131938 = SURFACE_CURVE('',#131939,(#131943,#131949),.PCURVE_S1.); +#131939 = LINE('',#131940,#131941); +#131940 = CARTESIAN_POINT('',(10.304819755875,5.15,0.75)); +#131941 = VECTOR('',#131942,1.); +#131942 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131943 = PCURVE('',#131705,#131944); +#131944 = DEFINITIONAL_REPRESENTATION('',(#131945),#131948); +#131945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131946,#131947), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#129554 = CARTESIAN_POINT('',(1.591299156552,5.15)); -#129555 = CARTESIAN_POINT('',(1.591299156552,5.35)); -#129556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131946 = CARTESIAN_POINT('',(1.591299156552,5.15)); +#131947 = CARTESIAN_POINT('',(1.591299156552,5.35)); +#131948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129557 = PCURVE('',#93164,#129558); -#129558 = DEFINITIONAL_REPRESENTATION('',(#129559),#129563); -#129559 = LINE('',#129560,#129561); -#129560 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#129561 = VECTOR('',#129562,1.); -#129562 = DIRECTION('',(4.440892098501E-016,1.)); -#129563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129564 = ORIENTED_EDGE('',*,*,#129565,.T.); -#129565 = EDGE_CURVE('',#129544,#129298,#129566,.T.); -#129566 = SURFACE_CURVE('',#129567,(#129572,#129578),.PCURVE_S1.); -#129567 = CIRCLE('',#129568,0.2192697516); -#129568 = AXIS2_PLACEMENT_3D('',#129569,#129570,#129571); -#129569 = CARTESIAN_POINT('',(10.30032442045,5.15,0.530776333563)); -#129570 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129571 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#129572 = PCURVE('',#129313,#129573); -#129573 = DEFINITIONAL_REPRESENTATION('',(#129574),#129577); -#129574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129575,#129576), +#131949 = PCURVE('',#95556,#131950); +#131950 = DEFINITIONAL_REPRESENTATION('',(#131951),#131955); +#131951 = LINE('',#131952,#131953); +#131952 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#131953 = VECTOR('',#131954,1.); +#131954 = DIRECTION('',(4.440892098501E-016,1.)); +#131955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131956 = ORIENTED_EDGE('',*,*,#131957,.T.); +#131957 = EDGE_CURVE('',#131936,#131690,#131958,.T.); +#131958 = SURFACE_CURVE('',#131959,(#131964,#131970),.PCURVE_S1.); +#131959 = CIRCLE('',#131960,0.2192697516); +#131960 = AXIS2_PLACEMENT_3D('',#131961,#131962,#131963); +#131961 = CARTESIAN_POINT('',(10.30032442045,5.15,0.530776333563)); +#131962 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#131963 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#131964 = PCURVE('',#131705,#131965); +#131965 = DEFINITIONAL_REPRESENTATION('',(#131966),#131969); +#131966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131967,#131968), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#129575 = CARTESIAN_POINT('',(1.591299156552,5.15)); -#129576 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#129577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#131967 = CARTESIAN_POINT('',(1.591299156552,5.15)); +#131968 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#131969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129578 = PCURVE('',#93138,#129579); -#129579 = DEFINITIONAL_REPRESENTATION('',(#129580),#129588); -#129580 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#129581,#129582,#129583, - #129584,#129585,#129586,#129587),.UNSPECIFIED.,.T.,.F.) +#131970 = PCURVE('',#95530,#131971); +#131971 = DEFINITIONAL_REPRESENTATION('',(#131972),#131980); +#131972 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131973,#131974,#131975, + #131976,#131977,#131978,#131979),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#129581 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#129582 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#129583 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#129584 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#129585 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#129586 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#129587 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#129588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129589 = ADVANCED_FACE('',(#129590),#93110,.T.); -#129590 = FACE_BOUND('',#129591,.T.); -#129591 = EDGE_LOOP('',(#129592,#129613,#129614,#129635)); -#129592 = ORIENTED_EDGE('',*,*,#129593,.F.); -#129593 = EDGE_CURVE('',#129447,#93067,#129594,.T.); -#129594 = SURFACE_CURVE('',#129595,(#129599,#129606),.PCURVE_S1.); -#129595 = LINE('',#129596,#129597); -#129596 = CARTESIAN_POINT('',(10.527847992439,5.35,0.65)); -#129597 = VECTOR('',#129598,1.); -#129598 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#129599 = PCURVE('',#93110,#129600); -#129600 = DEFINITIONAL_REPRESENTATION('',(#129601),#129605); -#129601 = LINE('',#129602,#129603); -#129602 = CARTESIAN_POINT('',(0.E+000,0.2)); -#129603 = VECTOR('',#129604,1.); -#129604 = DIRECTION('',(1.,-3.00059940766E-063)); -#129605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129606 = PCURVE('',#93082,#129607); -#129607 = DEFINITIONAL_REPRESENTATION('',(#129608),#129612); -#129608 = LINE('',#129609,#129610); -#129609 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129610 = VECTOR('',#129611,1.); -#129611 = DIRECTION('',(3.563627120235E-016,-1.)); -#129612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129613 = ORIENTED_EDGE('',*,*,#129469,.T.); -#129614 = ORIENTED_EDGE('',*,*,#129615,.T.); -#129615 = EDGE_CURVE('',#129470,#93095,#129616,.T.); -#129616 = SURFACE_CURVE('',#129617,(#129621,#129628),.PCURVE_S1.); -#129617 = LINE('',#129618,#129619); -#129618 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); -#129619 = VECTOR('',#129620,1.); -#129620 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#129621 = PCURVE('',#93110,#129622); -#129622 = DEFINITIONAL_REPRESENTATION('',(#129623),#129627); -#129623 = LINE('',#129624,#129625); -#129624 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129625 = VECTOR('',#129626,1.); -#129626 = DIRECTION('',(1.,-3.00059940766E-063)); -#129627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129628 = PCURVE('',#93138,#129629); -#129629 = DEFINITIONAL_REPRESENTATION('',(#129630),#129634); -#129630 = LINE('',#129631,#129632); -#129631 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129632 = VECTOR('',#129633,1.); -#129633 = DIRECTION('',(-3.563627120235E-016,-1.)); -#129634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129635 = ORIENTED_EDGE('',*,*,#93094,.F.); -#129636 = ADVANCED_FACE('',(#129637),#93082,.T.); -#129637 = FACE_BOUND('',#129638,.T.); -#129638 = EDGE_LOOP('',(#129639,#129660,#129661,#129662,#129663,#129664, - #129685,#129686,#129687,#129688,#129689,#129690)); -#129639 = ORIENTED_EDGE('',*,*,#129640,.F.); -#129640 = EDGE_CURVE('',#129521,#93065,#129641,.T.); -#129641 = SURFACE_CURVE('',#129642,(#129646,#129653),.PCURVE_S1.); -#129642 = LINE('',#129643,#129644); -#129643 = CARTESIAN_POINT('',(10.527847992439,5.35,0.75)); -#129644 = VECTOR('',#129645,1.); -#129645 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#129646 = PCURVE('',#93082,#129647); -#129647 = DEFINITIONAL_REPRESENTATION('',(#129648),#129652); -#129648 = LINE('',#129649,#129650); -#129649 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#129650 = VECTOR('',#129651,1.); -#129651 = DIRECTION('',(3.563627120235E-016,-1.)); -#129652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129653 = PCURVE('',#93164,#129654); -#129654 = DEFINITIONAL_REPRESENTATION('',(#129655),#129659); -#129655 = LINE('',#129656,#129657); -#129656 = CARTESIAN_POINT('',(0.E+000,0.2)); -#129657 = VECTOR('',#129658,1.); -#129658 = DIRECTION('',(-1.,-3.00059940766E-063)); -#129659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129660 = ORIENTED_EDGE('',*,*,#129520,.T.); -#129661 = ORIENTED_EDGE('',*,*,#129346,.T.); -#129662 = ORIENTED_EDGE('',*,*,#129266,.T.); -#129663 = ORIENTED_EDGE('',*,*,#129063,.T.); -#129664 = ORIENTED_EDGE('',*,*,#129665,.F.); -#129665 = EDGE_CURVE('',#128927,#129034,#129666,.T.); -#129666 = SURFACE_CURVE('',#129667,(#129671,#129678),.PCURVE_S1.); -#129667 = LINE('',#129668,#129669); -#129668 = CARTESIAN_POINT('',(11.,5.35,1.159810404338E-002)); -#129669 = VECTOR('',#129670,1.); -#129670 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#129671 = PCURVE('',#93082,#129672); -#129672 = DEFINITIONAL_REPRESENTATION('',(#129673),#129677); -#129673 = LINE('',#129674,#129675); -#129674 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#129675 = VECTOR('',#129676,1.); -#129676 = DIRECTION('',(1.,2.101748079665E-016)); -#129677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129678 = PCURVE('',#128947,#129679); -#129679 = DEFINITIONAL_REPRESENTATION('',(#129680),#129684); -#129680 = LINE('',#129681,#129682); -#129681 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#129682 = VECTOR('',#129683,1.); -#129683 = DIRECTION('',(1.194699204908E-017,1.)); -#129684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129685 = ORIENTED_EDGE('',*,*,#129009,.F.); -#129686 = ORIENTED_EDGE('',*,*,#129137,.F.); -#129687 = ORIENTED_EDGE('',*,*,#129399,.F.); -#129688 = ORIENTED_EDGE('',*,*,#129446,.F.); -#129689 = ORIENTED_EDGE('',*,*,#129593,.T.); -#129690 = ORIENTED_EDGE('',*,*,#93064,.F.); -#129691 = ADVANCED_FACE('',(#129692),#93164,.T.); -#129692 = FACE_BOUND('',#129693,.T.); -#129693 = EDGE_LOOP('',(#129694,#129715,#129716,#129717)); -#129694 = ORIENTED_EDGE('',*,*,#129695,.F.); -#129695 = EDGE_CURVE('',#129544,#93123,#129696,.T.); -#129696 = SURFACE_CURVE('',#129697,(#129701,#129708),.PCURVE_S1.); -#129697 = LINE('',#129698,#129699); -#129698 = CARTESIAN_POINT('',(10.527847992439,5.15,0.75)); -#129699 = VECTOR('',#129700,1.); -#129700 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#129701 = PCURVE('',#93164,#129702); -#129702 = DEFINITIONAL_REPRESENTATION('',(#129703),#129707); -#129703 = LINE('',#129704,#129705); -#129704 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129705 = VECTOR('',#129706,1.); -#129706 = DIRECTION('',(-1.,-3.00059940766E-063)); -#129707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129708 = PCURVE('',#93138,#129709); -#129709 = DEFINITIONAL_REPRESENTATION('',(#129710),#129714); -#129710 = LINE('',#129711,#129712); -#129711 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#129712 = VECTOR('',#129713,1.); -#129713 = DIRECTION('',(-3.563627120235E-016,-1.)); -#129714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129715 = ORIENTED_EDGE('',*,*,#129543,.T.); -#129716 = ORIENTED_EDGE('',*,*,#129640,.T.); -#129717 = ORIENTED_EDGE('',*,*,#93150,.F.); -#129718 = ADVANCED_FACE('',(#129719),#93138,.T.); -#129719 = FACE_BOUND('',#129720,.T.); -#129720 = EDGE_LOOP('',(#129721,#129722,#129723,#129724,#129725,#129726, - #129747,#129748,#129749,#129750,#129751,#129752)); -#129721 = ORIENTED_EDGE('',*,*,#129615,.F.); -#129722 = ORIENTED_EDGE('',*,*,#129491,.T.); -#129723 = ORIENTED_EDGE('',*,*,#129421,.T.); -#129724 = ORIENTED_EDGE('',*,*,#129165,.T.); -#129725 = ORIENTED_EDGE('',*,*,#128959,.T.); -#129726 = ORIENTED_EDGE('',*,*,#129727,.F.); -#129727 = EDGE_CURVE('',#129036,#128925,#129728,.T.); -#129728 = SURFACE_CURVE('',#129729,(#129733,#129740),.PCURVE_S1.); -#129729 = LINE('',#129730,#129731); -#129730 = CARTESIAN_POINT('',(11.,5.15,1.159810404338E-002)); -#129731 = VECTOR('',#129732,1.); -#129732 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#129733 = PCURVE('',#93138,#129734); -#129734 = DEFINITIONAL_REPRESENTATION('',(#129735),#129739); -#129735 = LINE('',#129736,#129737); -#129736 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#129737 = VECTOR('',#129738,1.); -#129738 = DIRECTION('',(1.,-2.101748079665E-016)); -#129739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129740 = PCURVE('',#128947,#129741); -#129741 = DEFINITIONAL_REPRESENTATION('',(#129742),#129746); -#129742 = LINE('',#129743,#129744); -#129743 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#129744 = VECTOR('',#129745,1.); -#129745 = DIRECTION('',(-1.194699204908E-017,-1.)); -#129746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129747 = ORIENTED_EDGE('',*,*,#129113,.F.); -#129748 = ORIENTED_EDGE('',*,*,#129216,.F.); -#129749 = ORIENTED_EDGE('',*,*,#129324,.F.); -#129750 = ORIENTED_EDGE('',*,*,#129565,.F.); -#129751 = ORIENTED_EDGE('',*,*,#129695,.T.); -#129752 = ORIENTED_EDGE('',*,*,#93122,.F.); -#129753 = ADVANCED_FACE('',(#129754),#128947,.T.); -#129754 = FACE_BOUND('',#129755,.T.); -#129755 = EDGE_LOOP('',(#129756,#129757,#129758,#129759)); -#129756 = ORIENTED_EDGE('',*,*,#129665,.T.); -#129757 = ORIENTED_EDGE('',*,*,#129033,.T.); -#129758 = ORIENTED_EDGE('',*,*,#129727,.T.); -#129759 = ORIENTED_EDGE('',*,*,#128924,.T.); -#129760 = ADVANCED_FACE('',(#129761),#129775,.F.); -#129761 = FACE_BOUND('',#129762,.T.); -#129762 = EDGE_LOOP('',(#129763,#129798,#129821,#129848)); -#129763 = ORIENTED_EDGE('',*,*,#129764,.F.); -#129764 = EDGE_CURVE('',#129765,#129767,#129769,.T.); -#129765 = VERTEX_POINT('',#129766); -#129766 = CARTESIAN_POINT('',(11.,4.35,-0.208196358798)); -#129767 = VERTEX_POINT('',#129768); -#129768 = CARTESIAN_POINT('',(11.,4.15,-0.208196358798)); -#129769 = SURFACE_CURVE('',#129770,(#129774,#129786),.PCURVE_S1.); -#129770 = LINE('',#129771,#129772); -#129771 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#129772 = VECTOR('',#129773,1.); -#129773 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129774 = PCURVE('',#129775,#129780); -#129775 = PLANE('',#129776); -#129776 = AXIS2_PLACEMENT_3D('',#129777,#129778,#129779); -#129777 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#131973 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#131974 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#131975 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#131976 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#131977 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#131978 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#131979 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#131980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131981 = ADVANCED_FACE('',(#131982),#95502,.T.); +#131982 = FACE_BOUND('',#131983,.T.); +#131983 = EDGE_LOOP('',(#131984,#132005,#132006,#132027)); +#131984 = ORIENTED_EDGE('',*,*,#131985,.F.); +#131985 = EDGE_CURVE('',#131839,#95459,#131986,.T.); +#131986 = SURFACE_CURVE('',#131987,(#131991,#131998),.PCURVE_S1.); +#131987 = LINE('',#131988,#131989); +#131988 = CARTESIAN_POINT('',(10.527847992439,5.35,0.65)); +#131989 = VECTOR('',#131990,1.); +#131990 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#131991 = PCURVE('',#95502,#131992); +#131992 = DEFINITIONAL_REPRESENTATION('',(#131993),#131997); +#131993 = LINE('',#131994,#131995); +#131994 = CARTESIAN_POINT('',(0.E+000,0.2)); +#131995 = VECTOR('',#131996,1.); +#131996 = DIRECTION('',(1.,-3.00059940766E-063)); +#131997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#131998 = PCURVE('',#95474,#131999); +#131999 = DEFINITIONAL_REPRESENTATION('',(#132000),#132004); +#132000 = LINE('',#132001,#132002); +#132001 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132002 = VECTOR('',#132003,1.); +#132003 = DIRECTION('',(3.563627120235E-016,-1.)); +#132004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132005 = ORIENTED_EDGE('',*,*,#131861,.T.); +#132006 = ORIENTED_EDGE('',*,*,#132007,.T.); +#132007 = EDGE_CURVE('',#131862,#95487,#132008,.T.); +#132008 = SURFACE_CURVE('',#132009,(#132013,#132020),.PCURVE_S1.); +#132009 = LINE('',#132010,#132011); +#132010 = CARTESIAN_POINT('',(10.527847992439,5.15,0.65)); +#132011 = VECTOR('',#132012,1.); +#132012 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132013 = PCURVE('',#95502,#132014); +#132014 = DEFINITIONAL_REPRESENTATION('',(#132015),#132019); +#132015 = LINE('',#132016,#132017); +#132016 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132017 = VECTOR('',#132018,1.); +#132018 = DIRECTION('',(1.,-3.00059940766E-063)); +#132019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132020 = PCURVE('',#95530,#132021); +#132021 = DEFINITIONAL_REPRESENTATION('',(#132022),#132026); +#132022 = LINE('',#132023,#132024); +#132023 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132024 = VECTOR('',#132025,1.); +#132025 = DIRECTION('',(-3.563627120235E-016,-1.)); +#132026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132027 = ORIENTED_EDGE('',*,*,#95486,.F.); +#132028 = ADVANCED_FACE('',(#132029),#95474,.T.); +#132029 = FACE_BOUND('',#132030,.T.); +#132030 = EDGE_LOOP('',(#132031,#132052,#132053,#132054,#132055,#132056, + #132077,#132078,#132079,#132080,#132081,#132082)); +#132031 = ORIENTED_EDGE('',*,*,#132032,.F.); +#132032 = EDGE_CURVE('',#131913,#95457,#132033,.T.); +#132033 = SURFACE_CURVE('',#132034,(#132038,#132045),.PCURVE_S1.); +#132034 = LINE('',#132035,#132036); +#132035 = CARTESIAN_POINT('',(10.527847992439,5.35,0.75)); +#132036 = VECTOR('',#132037,1.); +#132037 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132038 = PCURVE('',#95474,#132039); +#132039 = DEFINITIONAL_REPRESENTATION('',(#132040),#132044); +#132040 = LINE('',#132041,#132042); +#132041 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#132042 = VECTOR('',#132043,1.); +#132043 = DIRECTION('',(3.563627120235E-016,-1.)); +#132044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132045 = PCURVE('',#95556,#132046); +#132046 = DEFINITIONAL_REPRESENTATION('',(#132047),#132051); +#132047 = LINE('',#132048,#132049); +#132048 = CARTESIAN_POINT('',(0.E+000,0.2)); +#132049 = VECTOR('',#132050,1.); +#132050 = DIRECTION('',(-1.,-3.00059940766E-063)); +#132051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132052 = ORIENTED_EDGE('',*,*,#131912,.T.); +#132053 = ORIENTED_EDGE('',*,*,#131738,.T.); +#132054 = ORIENTED_EDGE('',*,*,#131658,.T.); +#132055 = ORIENTED_EDGE('',*,*,#131455,.T.); +#132056 = ORIENTED_EDGE('',*,*,#132057,.F.); +#132057 = EDGE_CURVE('',#131319,#131426,#132058,.T.); +#132058 = SURFACE_CURVE('',#132059,(#132063,#132070),.PCURVE_S1.); +#132059 = LINE('',#132060,#132061); +#132060 = CARTESIAN_POINT('',(11.,5.35,1.159810404338E-002)); +#132061 = VECTOR('',#132062,1.); +#132062 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#132063 = PCURVE('',#95474,#132064); +#132064 = DEFINITIONAL_REPRESENTATION('',(#132065),#132069); +#132065 = LINE('',#132066,#132067); +#132066 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#132067 = VECTOR('',#132068,1.); +#132068 = DIRECTION('',(1.,2.101748079665E-016)); +#132069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132070 = PCURVE('',#131339,#132071); +#132071 = DEFINITIONAL_REPRESENTATION('',(#132072),#132076); +#132072 = LINE('',#132073,#132074); +#132073 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#132074 = VECTOR('',#132075,1.); +#132075 = DIRECTION('',(1.194699204908E-017,1.)); +#132076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132077 = ORIENTED_EDGE('',*,*,#131401,.F.); +#132078 = ORIENTED_EDGE('',*,*,#131529,.F.); +#132079 = ORIENTED_EDGE('',*,*,#131791,.F.); +#132080 = ORIENTED_EDGE('',*,*,#131838,.F.); +#132081 = ORIENTED_EDGE('',*,*,#131985,.T.); +#132082 = ORIENTED_EDGE('',*,*,#95456,.F.); +#132083 = ADVANCED_FACE('',(#132084),#95556,.T.); +#132084 = FACE_BOUND('',#132085,.T.); +#132085 = EDGE_LOOP('',(#132086,#132107,#132108,#132109)); +#132086 = ORIENTED_EDGE('',*,*,#132087,.F.); +#132087 = EDGE_CURVE('',#131936,#95515,#132088,.T.); +#132088 = SURFACE_CURVE('',#132089,(#132093,#132100),.PCURVE_S1.); +#132089 = LINE('',#132090,#132091); +#132090 = CARTESIAN_POINT('',(10.527847992439,5.15,0.75)); +#132091 = VECTOR('',#132092,1.); +#132092 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132093 = PCURVE('',#95556,#132094); +#132094 = DEFINITIONAL_REPRESENTATION('',(#132095),#132099); +#132095 = LINE('',#132096,#132097); +#132096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132097 = VECTOR('',#132098,1.); +#132098 = DIRECTION('',(-1.,-3.00059940766E-063)); +#132099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132100 = PCURVE('',#95530,#132101); +#132101 = DEFINITIONAL_REPRESENTATION('',(#132102),#132106); +#132102 = LINE('',#132103,#132104); +#132103 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#132104 = VECTOR('',#132105,1.); +#132105 = DIRECTION('',(-3.563627120235E-016,-1.)); +#132106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132107 = ORIENTED_EDGE('',*,*,#131935,.T.); +#132108 = ORIENTED_EDGE('',*,*,#132032,.T.); +#132109 = ORIENTED_EDGE('',*,*,#95542,.F.); +#132110 = ADVANCED_FACE('',(#132111),#95530,.T.); +#132111 = FACE_BOUND('',#132112,.T.); +#132112 = EDGE_LOOP('',(#132113,#132114,#132115,#132116,#132117,#132118, + #132139,#132140,#132141,#132142,#132143,#132144)); +#132113 = ORIENTED_EDGE('',*,*,#132007,.F.); +#132114 = ORIENTED_EDGE('',*,*,#131883,.T.); +#132115 = ORIENTED_EDGE('',*,*,#131813,.T.); +#132116 = ORIENTED_EDGE('',*,*,#131557,.T.); +#132117 = ORIENTED_EDGE('',*,*,#131351,.T.); +#132118 = ORIENTED_EDGE('',*,*,#132119,.F.); +#132119 = EDGE_CURVE('',#131428,#131317,#132120,.T.); +#132120 = SURFACE_CURVE('',#132121,(#132125,#132132),.PCURVE_S1.); +#132121 = LINE('',#132122,#132123); +#132122 = CARTESIAN_POINT('',(11.,5.15,1.159810404338E-002)); +#132123 = VECTOR('',#132124,1.); +#132124 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#132125 = PCURVE('',#95530,#132126); +#132126 = DEFINITIONAL_REPRESENTATION('',(#132127),#132131); +#132127 = LINE('',#132128,#132129); +#132128 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#132129 = VECTOR('',#132130,1.); +#132130 = DIRECTION('',(1.,-2.101748079665E-016)); +#132131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132132 = PCURVE('',#131339,#132133); +#132133 = DEFINITIONAL_REPRESENTATION('',(#132134),#132138); +#132134 = LINE('',#132135,#132136); +#132135 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#132136 = VECTOR('',#132137,1.); +#132137 = DIRECTION('',(-1.194699204908E-017,-1.)); +#132138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132139 = ORIENTED_EDGE('',*,*,#131505,.F.); +#132140 = ORIENTED_EDGE('',*,*,#131608,.F.); +#132141 = ORIENTED_EDGE('',*,*,#131716,.F.); +#132142 = ORIENTED_EDGE('',*,*,#131957,.F.); +#132143 = ORIENTED_EDGE('',*,*,#132087,.T.); +#132144 = ORIENTED_EDGE('',*,*,#95514,.F.); +#132145 = ADVANCED_FACE('',(#132146),#131339,.T.); +#132146 = FACE_BOUND('',#132147,.T.); +#132147 = EDGE_LOOP('',(#132148,#132149,#132150,#132151)); +#132148 = ORIENTED_EDGE('',*,*,#132057,.T.); +#132149 = ORIENTED_EDGE('',*,*,#131425,.T.); +#132150 = ORIENTED_EDGE('',*,*,#132119,.T.); +#132151 = ORIENTED_EDGE('',*,*,#131316,.T.); +#132152 = ADVANCED_FACE('',(#132153),#132167,.F.); +#132153 = FACE_BOUND('',#132154,.T.); +#132154 = EDGE_LOOP('',(#132155,#132190,#132213,#132240)); +#132155 = ORIENTED_EDGE('',*,*,#132156,.F.); +#132156 = EDGE_CURVE('',#132157,#132159,#132161,.T.); +#132157 = VERTEX_POINT('',#132158); +#132158 = CARTESIAN_POINT('',(11.,4.35,-0.208196358798)); +#132159 = VERTEX_POINT('',#132160); +#132160 = CARTESIAN_POINT('',(11.,4.15,-0.208196358798)); +#132161 = SURFACE_CURVE('',#132162,(#132166,#132178),.PCURVE_S1.); +#132162 = LINE('',#132163,#132164); +#132163 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#132164 = VECTOR('',#132165,1.); +#132165 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132166 = PCURVE('',#132167,#132172); +#132167 = PLANE('',#132168); +#132168 = AXIS2_PLACEMENT_3D('',#132169,#132170,#132171); +#132169 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#129778 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#129779 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#129780 = DEFINITIONAL_REPRESENTATION('',(#129781),#129785); -#129781 = LINE('',#129782,#129783); -#129782 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#129783 = VECTOR('',#129784,1.); -#129784 = DIRECTION('',(4.440892098501E-016,-1.)); -#129785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129786 = PCURVE('',#129787,#129792); -#129787 = PLANE('',#129788); -#129788 = AXIS2_PLACEMENT_3D('',#129789,#129790,#129791); -#129789 = CARTESIAN_POINT('',(11.,4.25,-0.258196742327)); -#129790 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#129791 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129792 = DEFINITIONAL_REPRESENTATION('',(#129793),#129797); -#129793 = LINE('',#129794,#129795); -#129794 = CARTESIAN_POINT('',(-4.25,5.000038352949E-002)); -#129795 = VECTOR('',#129796,1.); -#129796 = DIRECTION('',(-1.,0.E+000)); -#129797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129798 = ORIENTED_EDGE('',*,*,#129799,.F.); -#129799 = EDGE_CURVE('',#129800,#129765,#129802,.T.); -#129800 = VERTEX_POINT('',#129801); -#129801 = CARTESIAN_POINT('',(10.740726081328,4.35,-0.208196358798)); -#129802 = SURFACE_CURVE('',#129803,(#129807,#129814),.PCURVE_S1.); -#129803 = LINE('',#129804,#129805); -#129804 = CARTESIAN_POINT('',(10.740726081328,4.35,-0.208196358798)); -#129805 = VECTOR('',#129806,1.); -#129806 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129807 = PCURVE('',#129775,#129808); -#129808 = DEFINITIONAL_REPRESENTATION('',(#129809),#129813); -#129809 = LINE('',#129810,#129811); -#129810 = CARTESIAN_POINT('',(-1.7763568394E-015,4.35)); -#129811 = VECTOR('',#129812,1.); -#129812 = DIRECTION('',(-1.,0.E+000)); -#129813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129814 = PCURVE('',#92968,#129815); -#129815 = DEFINITIONAL_REPRESENTATION('',(#129816),#129820); -#129816 = LINE('',#129817,#129818); -#129817 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#129818 = VECTOR('',#129819,1.); -#129819 = DIRECTION('',(0.E+000,1.)); -#129820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129821 = ORIENTED_EDGE('',*,*,#129822,.F.); -#129822 = EDGE_CURVE('',#129823,#129800,#129825,.T.); -#129823 = VERTEX_POINT('',#129824); -#129824 = CARTESIAN_POINT('',(10.740726081328,4.15,-0.208196358798)); -#129825 = SURFACE_CURVE('',#129826,(#129830,#129837),.PCURVE_S1.); -#129826 = LINE('',#129827,#129828); -#129827 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#132170 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#132171 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#132172 = DEFINITIONAL_REPRESENTATION('',(#132173),#132177); +#132173 = LINE('',#132174,#132175); +#132174 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#132175 = VECTOR('',#132176,1.); +#132176 = DIRECTION('',(4.440892098501E-016,-1.)); +#132177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132178 = PCURVE('',#132179,#132184); +#132179 = PLANE('',#132180); +#132180 = AXIS2_PLACEMENT_3D('',#132181,#132182,#132183); +#132181 = CARTESIAN_POINT('',(11.,4.25,-0.258196742327)); +#132182 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#132183 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132184 = DEFINITIONAL_REPRESENTATION('',(#132185),#132189); +#132185 = LINE('',#132186,#132187); +#132186 = CARTESIAN_POINT('',(-4.25,5.000038352949E-002)); +#132187 = VECTOR('',#132188,1.); +#132188 = DIRECTION('',(-1.,0.E+000)); +#132189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132190 = ORIENTED_EDGE('',*,*,#132191,.F.); +#132191 = EDGE_CURVE('',#132192,#132157,#132194,.T.); +#132192 = VERTEX_POINT('',#132193); +#132193 = CARTESIAN_POINT('',(10.740726081328,4.35,-0.208196358798)); +#132194 = SURFACE_CURVE('',#132195,(#132199,#132206),.PCURVE_S1.); +#132195 = LINE('',#132196,#132197); +#132196 = CARTESIAN_POINT('',(10.740726081328,4.35,-0.208196358798)); +#132197 = VECTOR('',#132198,1.); +#132198 = DIRECTION('',(1.,0.E+000,0.E+000)); +#132199 = PCURVE('',#132167,#132200); +#132200 = DEFINITIONAL_REPRESENTATION('',(#132201),#132205); +#132201 = LINE('',#132202,#132203); +#132202 = CARTESIAN_POINT('',(-1.7763568394E-015,4.35)); +#132203 = VECTOR('',#132204,1.); +#132204 = DIRECTION('',(-1.,0.E+000)); +#132205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132206 = PCURVE('',#95360,#132207); +#132207 = DEFINITIONAL_REPRESENTATION('',(#132208),#132212); +#132208 = LINE('',#132209,#132210); +#132209 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#132210 = VECTOR('',#132211,1.); +#132211 = DIRECTION('',(0.E+000,1.)); +#132212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132213 = ORIENTED_EDGE('',*,*,#132214,.F.); +#132214 = EDGE_CURVE('',#132215,#132192,#132217,.T.); +#132215 = VERTEX_POINT('',#132216); +#132216 = CARTESIAN_POINT('',(10.740726081328,4.15,-0.208196358798)); +#132217 = SURFACE_CURVE('',#132218,(#132222,#132229),.PCURVE_S1.); +#132218 = LINE('',#132219,#132220); +#132219 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#129828 = VECTOR('',#129829,1.); -#129829 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129830 = PCURVE('',#129775,#129831); -#129831 = DEFINITIONAL_REPRESENTATION('',(#129832),#129836); -#129832 = LINE('',#129833,#129834); -#129833 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129834 = VECTOR('',#129835,1.); -#129835 = DIRECTION('',(-4.440892098501E-016,1.)); -#129836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129837 = PCURVE('',#129838,#129843); -#129838 = CYLINDRICAL_SURFACE('',#129839,0.208574704164); -#129839 = AXIS2_PLACEMENT_3D('',#129840,#129841,#129842); -#129840 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#132220 = VECTOR('',#132221,1.); +#132221 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132222 = PCURVE('',#132167,#132223); +#132223 = DEFINITIONAL_REPRESENTATION('',(#132224),#132228); +#132224 = LINE('',#132225,#132226); +#132225 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132226 = VECTOR('',#132227,1.); +#132227 = DIRECTION('',(-4.440892098501E-016,1.)); +#132228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132229 = PCURVE('',#132230,#132235); +#132230 = CYLINDRICAL_SURFACE('',#132231,0.208574704164); +#132231 = AXIS2_PLACEMENT_3D('',#132232,#132233,#132234); +#132232 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#129841 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129842 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129843 = DEFINITIONAL_REPRESENTATION('',(#129844),#129847); -#129844 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129845,#129846), +#132233 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132234 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132235 = DEFINITIONAL_REPRESENTATION('',(#132236),#132239); +#132236 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132237,#132238), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#129845 = CARTESIAN_POINT('',(4.772630242227,-4.15)); -#129846 = CARTESIAN_POINT('',(4.772630242227,-4.35)); -#129847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132237 = CARTESIAN_POINT('',(4.772630242227,-4.15)); +#132238 = CARTESIAN_POINT('',(4.772630242227,-4.35)); +#132239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132240 = ORIENTED_EDGE('',*,*,#132241,.T.); +#132241 = EDGE_CURVE('',#132215,#132159,#132242,.T.); +#132242 = SURFACE_CURVE('',#132243,(#132247,#132254),.PCURVE_S1.); +#132243 = LINE('',#132244,#132245); +#132244 = CARTESIAN_POINT('',(10.740726081328,4.15,-0.208196358798)); +#132245 = VECTOR('',#132246,1.); +#132246 = DIRECTION('',(1.,0.E+000,0.E+000)); +#132247 = PCURVE('',#132167,#132248); +#132248 = DEFINITIONAL_REPRESENTATION('',(#132249),#132253); +#132249 = LINE('',#132250,#132251); +#132250 = CARTESIAN_POINT('',(-1.7763568394E-015,4.15)); +#132251 = VECTOR('',#132252,1.); +#132252 = DIRECTION('',(-1.,0.E+000)); +#132253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132254 = PCURVE('',#95416,#132255); +#132255 = DEFINITIONAL_REPRESENTATION('',(#132256),#132260); +#132256 = LINE('',#132257,#132258); +#132257 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#132258 = VECTOR('',#132259,1.); +#132259 = DIRECTION('',(0.E+000,1.)); +#132260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129848 = ORIENTED_EDGE('',*,*,#129849,.T.); -#129849 = EDGE_CURVE('',#129823,#129767,#129850,.T.); -#129850 = SURFACE_CURVE('',#129851,(#129855,#129862),.PCURVE_S1.); -#129851 = LINE('',#129852,#129853); -#129852 = CARTESIAN_POINT('',(10.740726081328,4.15,-0.208196358798)); -#129853 = VECTOR('',#129854,1.); -#129854 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129855 = PCURVE('',#129775,#129856); -#129856 = DEFINITIONAL_REPRESENTATION('',(#129857),#129861); -#129857 = LINE('',#129858,#129859); -#129858 = CARTESIAN_POINT('',(-1.7763568394E-015,4.15)); -#129859 = VECTOR('',#129860,1.); -#129860 = DIRECTION('',(-1.,0.E+000)); -#129861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129862 = PCURVE('',#93024,#129863); -#129863 = DEFINITIONAL_REPRESENTATION('',(#129864),#129868); -#129864 = LINE('',#129865,#129866); -#129865 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#129866 = VECTOR('',#129867,1.); -#129867 = DIRECTION('',(0.E+000,1.)); -#129868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129869 = ADVANCED_FACE('',(#129870),#129884,.F.); -#129870 = FACE_BOUND('',#129871,.T.); -#129871 = EDGE_LOOP('',(#129872,#129902,#129925,#129952)); -#129872 = ORIENTED_EDGE('',*,*,#129873,.F.); -#129873 = EDGE_CURVE('',#129874,#129876,#129878,.T.); -#129874 = VERTEX_POINT('',#129875); -#129875 = CARTESIAN_POINT('',(11.,4.15,-0.308197125857)); -#129876 = VERTEX_POINT('',#129877); -#129877 = CARTESIAN_POINT('',(11.,4.35,-0.308197125857)); -#129878 = SURFACE_CURVE('',#129879,(#129883,#129895),.PCURVE_S1.); -#129879 = LINE('',#129880,#129881); -#129880 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#129881 = VECTOR('',#129882,1.); -#129882 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#129883 = PCURVE('',#129884,#129889); -#129884 = PLANE('',#129885); -#129885 = AXIS2_PLACEMENT_3D('',#129886,#129887,#129888); -#129886 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#132261 = ADVANCED_FACE('',(#132262),#132276,.F.); +#132262 = FACE_BOUND('',#132263,.T.); +#132263 = EDGE_LOOP('',(#132264,#132294,#132317,#132344)); +#132264 = ORIENTED_EDGE('',*,*,#132265,.F.); +#132265 = EDGE_CURVE('',#132266,#132268,#132270,.T.); +#132266 = VERTEX_POINT('',#132267); +#132267 = CARTESIAN_POINT('',(11.,4.15,-0.308197125857)); +#132268 = VERTEX_POINT('',#132269); +#132269 = CARTESIAN_POINT('',(11.,4.35,-0.308197125857)); +#132270 = SURFACE_CURVE('',#132271,(#132275,#132287),.PCURVE_S1.); +#132271 = LINE('',#132272,#132273); +#132272 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#132273 = VECTOR('',#132274,1.); +#132274 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132275 = PCURVE('',#132276,#132281); +#132276 = PLANE('',#132277); +#132277 = AXIS2_PLACEMENT_3D('',#132278,#132279,#132280); +#132278 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#129887 = DIRECTION('',(0.E+000,0.E+000,1.)); -#129888 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129889 = DEFINITIONAL_REPRESENTATION('',(#129890),#129894); -#129890 = LINE('',#129891,#129892); -#129891 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#129892 = VECTOR('',#129893,1.); -#129893 = DIRECTION('',(4.440892098501E-016,1.)); -#129894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129895 = PCURVE('',#129787,#129896); -#129896 = DEFINITIONAL_REPRESENTATION('',(#129897),#129901); -#129897 = LINE('',#129898,#129899); -#129898 = CARTESIAN_POINT('',(-4.25,-5.000038352949E-002)); -#129899 = VECTOR('',#129900,1.); -#129900 = DIRECTION('',(1.,0.E+000)); -#129901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129902 = ORIENTED_EDGE('',*,*,#129903,.F.); -#129903 = EDGE_CURVE('',#129904,#129874,#129906,.T.); -#129904 = VERTEX_POINT('',#129905); -#129905 = CARTESIAN_POINT('',(10.74341632541,4.15,-0.308197125857)); -#129906 = SURFACE_CURVE('',#129907,(#129911,#129918),.PCURVE_S1.); -#129907 = LINE('',#129908,#129909); -#129908 = CARTESIAN_POINT('',(10.74341632541,4.15,-0.308197125857)); -#129909 = VECTOR('',#129910,1.); -#129910 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129911 = PCURVE('',#129884,#129912); -#129912 = DEFINITIONAL_REPRESENTATION('',(#129913),#129917); -#129913 = LINE('',#129914,#129915); -#129914 = CARTESIAN_POINT('',(1.7763568394E-015,4.15)); -#129915 = VECTOR('',#129916,1.); -#129916 = DIRECTION('',(1.,0.E+000)); -#129917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129918 = PCURVE('',#93024,#129919); -#129919 = DEFINITIONAL_REPRESENTATION('',(#129920),#129924); -#129920 = LINE('',#129921,#129922); -#129921 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#129922 = VECTOR('',#129923,1.); -#129923 = DIRECTION('',(0.E+000,1.)); -#129924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129925 = ORIENTED_EDGE('',*,*,#129926,.F.); -#129926 = EDGE_CURVE('',#129927,#129904,#129929,.T.); -#129927 = VERTEX_POINT('',#129928); -#129928 = CARTESIAN_POINT('',(10.74341632541,4.35,-0.308197125857)); -#129929 = SURFACE_CURVE('',#129930,(#129934,#129941),.PCURVE_S1.); -#129930 = LINE('',#129931,#129932); -#129931 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#132279 = DIRECTION('',(0.E+000,0.E+000,1.)); +#132280 = DIRECTION('',(1.,0.E+000,0.E+000)); +#132281 = DEFINITIONAL_REPRESENTATION('',(#132282),#132286); +#132282 = LINE('',#132283,#132284); +#132283 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#132284 = VECTOR('',#132285,1.); +#132285 = DIRECTION('',(4.440892098501E-016,1.)); +#132286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132287 = PCURVE('',#132179,#132288); +#132288 = DEFINITIONAL_REPRESENTATION('',(#132289),#132293); +#132289 = LINE('',#132290,#132291); +#132290 = CARTESIAN_POINT('',(-4.25,-5.000038352949E-002)); +#132291 = VECTOR('',#132292,1.); +#132292 = DIRECTION('',(1.,0.E+000)); +#132293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132294 = ORIENTED_EDGE('',*,*,#132295,.F.); +#132295 = EDGE_CURVE('',#132296,#132266,#132298,.T.); +#132296 = VERTEX_POINT('',#132297); +#132297 = CARTESIAN_POINT('',(10.74341632541,4.15,-0.308197125857)); +#132298 = SURFACE_CURVE('',#132299,(#132303,#132310),.PCURVE_S1.); +#132299 = LINE('',#132300,#132301); +#132300 = CARTESIAN_POINT('',(10.74341632541,4.15,-0.308197125857)); +#132301 = VECTOR('',#132302,1.); +#132302 = DIRECTION('',(1.,0.E+000,0.E+000)); +#132303 = PCURVE('',#132276,#132304); +#132304 = DEFINITIONAL_REPRESENTATION('',(#132305),#132309); +#132305 = LINE('',#132306,#132307); +#132306 = CARTESIAN_POINT('',(1.7763568394E-015,4.15)); +#132307 = VECTOR('',#132308,1.); +#132308 = DIRECTION('',(1.,0.E+000)); +#132309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132310 = PCURVE('',#95416,#132311); +#132311 = DEFINITIONAL_REPRESENTATION('',(#132312),#132316); +#132312 = LINE('',#132313,#132314); +#132313 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#132314 = VECTOR('',#132315,1.); +#132315 = DIRECTION('',(0.E+000,1.)); +#132316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132317 = ORIENTED_EDGE('',*,*,#132318,.F.); +#132318 = EDGE_CURVE('',#132319,#132296,#132321,.T.); +#132319 = VERTEX_POINT('',#132320); +#132320 = CARTESIAN_POINT('',(10.74341632541,4.35,-0.308197125857)); +#132321 = SURFACE_CURVE('',#132322,(#132326,#132333),.PCURVE_S1.); +#132322 = LINE('',#132323,#132324); +#132323 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#129932 = VECTOR('',#129933,1.); -#129933 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129934 = PCURVE('',#129884,#129935); -#129935 = DEFINITIONAL_REPRESENTATION('',(#129936),#129940); -#129936 = LINE('',#129937,#129938); -#129937 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#129938 = VECTOR('',#129939,1.); -#129939 = DIRECTION('',(-4.440892098501E-016,-1.)); -#129940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129941 = PCURVE('',#129942,#129947); -#129942 = CYLINDRICAL_SURFACE('',#129943,0.308574064194); -#129943 = AXIS2_PLACEMENT_3D('',#129944,#129945,#129946); -#129944 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#132324 = VECTOR('',#132325,1.); +#132325 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132326 = PCURVE('',#132276,#132327); +#132327 = DEFINITIONAL_REPRESENTATION('',(#132328),#132332); +#132328 = LINE('',#132329,#132330); +#132329 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132330 = VECTOR('',#132331,1.); +#132331 = DIRECTION('',(-4.440892098501E-016,-1.)); +#132332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132333 = PCURVE('',#132334,#132339); +#132334 = CYLINDRICAL_SURFACE('',#132335,0.308574064194); +#132335 = AXIS2_PLACEMENT_3D('',#132336,#132337,#132338); +#132336 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#129945 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129946 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129947 = DEFINITIONAL_REPRESENTATION('',(#129948),#129951); -#129948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129949,#129950), +#132337 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132338 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132339 = DEFINITIONAL_REPRESENTATION('',(#132340),#132343); +#132340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132341,#132342), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#129949 = CARTESIAN_POINT('',(4.761821717947,-4.35)); -#129950 = CARTESIAN_POINT('',(4.761821717947,-4.15)); -#129951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129952 = ORIENTED_EDGE('',*,*,#129953,.T.); -#129953 = EDGE_CURVE('',#129927,#129876,#129954,.T.); -#129954 = SURFACE_CURVE('',#129955,(#129959,#129966),.PCURVE_S1.); -#129955 = LINE('',#129956,#129957); -#129956 = CARTESIAN_POINT('',(10.74341632541,4.35,-0.308197125857)); -#129957 = VECTOR('',#129958,1.); -#129958 = DIRECTION('',(1.,0.E+000,0.E+000)); -#129959 = PCURVE('',#129884,#129960); -#129960 = DEFINITIONAL_REPRESENTATION('',(#129961),#129965); -#129961 = LINE('',#129962,#129963); -#129962 = CARTESIAN_POINT('',(1.7763568394E-015,4.35)); -#129963 = VECTOR('',#129964,1.); -#129964 = DIRECTION('',(1.,0.E+000)); -#129965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129966 = PCURVE('',#92968,#129967); -#129967 = DEFINITIONAL_REPRESENTATION('',(#129968),#129972); -#129968 = LINE('',#129969,#129970); -#129969 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#129970 = VECTOR('',#129971,1.); -#129971 = DIRECTION('',(0.E+000,1.)); -#129972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#129973 = ADVANCED_FACE('',(#129974),#129838,.F.); -#129974 = FACE_BOUND('',#129975,.F.); -#129975 = EDGE_LOOP('',(#129976,#129999,#130026,#130051)); -#129976 = ORIENTED_EDGE('',*,*,#129977,.F.); -#129977 = EDGE_CURVE('',#129978,#129823,#129980,.T.); -#129978 = VERTEX_POINT('',#129979); -#129979 = CARTESIAN_POINT('',(10.51959417205,4.15,0.E+000)); -#129980 = SURFACE_CURVE('',#129981,(#129986,#129992),.PCURVE_S1.); -#129981 = CIRCLE('',#129982,0.208574704164); -#129982 = AXIS2_PLACEMENT_3D('',#129983,#129984,#129985); -#129983 = CARTESIAN_POINT('',(10.728168876214,4.15,2.640924866458E-017) - ); -#129984 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#129985 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#129986 = PCURVE('',#129838,#129987); -#129987 = DEFINITIONAL_REPRESENTATION('',(#129988),#129991); -#129988 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#129989,#129990), +#132341 = CARTESIAN_POINT('',(4.761821717947,-4.35)); +#132342 = CARTESIAN_POINT('',(4.761821717947,-4.15)); +#132343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132344 = ORIENTED_EDGE('',*,*,#132345,.T.); +#132345 = EDGE_CURVE('',#132319,#132268,#132346,.T.); +#132346 = SURFACE_CURVE('',#132347,(#132351,#132358),.PCURVE_S1.); +#132347 = LINE('',#132348,#132349); +#132348 = CARTESIAN_POINT('',(10.74341632541,4.35,-0.308197125857)); +#132349 = VECTOR('',#132350,1.); +#132350 = DIRECTION('',(1.,0.E+000,0.E+000)); +#132351 = PCURVE('',#132276,#132352); +#132352 = DEFINITIONAL_REPRESENTATION('',(#132353),#132357); +#132353 = LINE('',#132354,#132355); +#132354 = CARTESIAN_POINT('',(1.7763568394E-015,4.35)); +#132355 = VECTOR('',#132356,1.); +#132356 = DIRECTION('',(1.,0.E+000)); +#132357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132358 = PCURVE('',#95360,#132359); +#132359 = DEFINITIONAL_REPRESENTATION('',(#132360),#132364); +#132360 = LINE('',#132361,#132362); +#132361 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#132362 = VECTOR('',#132363,1.); +#132363 = DIRECTION('',(0.E+000,1.)); +#132364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132365 = ADVANCED_FACE('',(#132366),#132230,.F.); +#132366 = FACE_BOUND('',#132367,.F.); +#132367 = EDGE_LOOP('',(#132368,#132391,#132418,#132443)); +#132368 = ORIENTED_EDGE('',*,*,#132369,.F.); +#132369 = EDGE_CURVE('',#132370,#132215,#132372,.T.); +#132370 = VERTEX_POINT('',#132371); +#132371 = CARTESIAN_POINT('',(10.51959417205,4.15,0.E+000)); +#132372 = SURFACE_CURVE('',#132373,(#132378,#132384),.PCURVE_S1.); +#132373 = CIRCLE('',#132374,0.208574704164); +#132374 = AXIS2_PLACEMENT_3D('',#132375,#132376,#132377); +#132375 = CARTESIAN_POINT('',(10.728168876214,4.15,2.640924866458E-017) + ); +#132376 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132377 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132378 = PCURVE('',#132230,#132379); +#132379 = DEFINITIONAL_REPRESENTATION('',(#132380),#132383); +#132380 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132381,#132382), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#129989 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#129990 = CARTESIAN_POINT('',(4.772630242227,-4.15)); -#129991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132381 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#132382 = CARTESIAN_POINT('',(4.772630242227,-4.15)); +#132383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129992 = PCURVE('',#93024,#129993); -#129993 = DEFINITIONAL_REPRESENTATION('',(#129994),#129998); -#129994 = CIRCLE('',#129995,0.208574704164); -#129995 = AXIS2_PLACEMENT_2D('',#129996,#129997); -#129996 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#129997 = DIRECTION('',(0.E+000,1.)); -#129998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132384 = PCURVE('',#95416,#132385); +#132385 = DEFINITIONAL_REPRESENTATION('',(#132386),#132390); +#132386 = CIRCLE('',#132387,0.208574704164); +#132387 = AXIS2_PLACEMENT_2D('',#132388,#132389); +#132388 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#132389 = DIRECTION('',(0.E+000,1.)); +#132390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#129999 = ORIENTED_EDGE('',*,*,#130000,.F.); -#130000 = EDGE_CURVE('',#130001,#129978,#130003,.T.); -#130001 = VERTEX_POINT('',#130002); -#130002 = CARTESIAN_POINT('',(10.51959417205,4.35,0.E+000)); -#130003 = SURFACE_CURVE('',#130004,(#130008,#130014),.PCURVE_S1.); -#130004 = LINE('',#130005,#130006); -#130005 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#132391 = ORIENTED_EDGE('',*,*,#132392,.F.); +#132392 = EDGE_CURVE('',#132393,#132370,#132395,.T.); +#132393 = VERTEX_POINT('',#132394); +#132394 = CARTESIAN_POINT('',(10.51959417205,4.35,0.E+000)); +#132395 = SURFACE_CURVE('',#132396,(#132400,#132406),.PCURVE_S1.); +#132396 = LINE('',#132397,#132398); +#132397 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#130006 = VECTOR('',#130007,1.); -#130007 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130008 = PCURVE('',#129838,#130009); -#130009 = DEFINITIONAL_REPRESENTATION('',(#130010),#130013); -#130010 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130011,#130012), +#132398 = VECTOR('',#132399,1.); +#132399 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132400 = PCURVE('',#132230,#132401); +#132401 = DEFINITIONAL_REPRESENTATION('',(#132402),#132405); +#132402 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132403,#132404), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#130011 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#130012 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#130013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132403 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#132404 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#132405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130014 = PCURVE('',#130015,#130020); -#130015 = PLANE('',#130016); -#130016 = AXIS2_PLACEMENT_3D('',#130017,#130018,#130019); -#130017 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#132406 = PCURVE('',#132407,#132412); +#132407 = PLANE('',#132408); +#132408 = AXIS2_PLACEMENT_3D('',#132409,#132410,#132411); +#132409 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#130018 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130019 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130020 = DEFINITIONAL_REPRESENTATION('',(#130021),#130025); -#130021 = LINE('',#130022,#130023); -#130022 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#130023 = VECTOR('',#130024,1.); -#130024 = DIRECTION('',(-1.,0.E+000)); -#130025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130026 = ORIENTED_EDGE('',*,*,#130027,.T.); -#130027 = EDGE_CURVE('',#130001,#129800,#130028,.T.); -#130028 = SURFACE_CURVE('',#130029,(#130034,#130040),.PCURVE_S1.); -#130029 = CIRCLE('',#130030,0.208574704164); -#130030 = AXIS2_PLACEMENT_3D('',#130031,#130032,#130033); -#130031 = CARTESIAN_POINT('',(10.728168876214,4.35,2.640924866458E-017) - ); -#130032 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130033 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130034 = PCURVE('',#129838,#130035); -#130035 = DEFINITIONAL_REPRESENTATION('',(#130036),#130039); -#130036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130037,#130038), +#132410 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132411 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132412 = DEFINITIONAL_REPRESENTATION('',(#132413),#132417); +#132413 = LINE('',#132414,#132415); +#132414 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#132415 = VECTOR('',#132416,1.); +#132416 = DIRECTION('',(-1.,0.E+000)); +#132417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132418 = ORIENTED_EDGE('',*,*,#132419,.T.); +#132419 = EDGE_CURVE('',#132393,#132192,#132420,.T.); +#132420 = SURFACE_CURVE('',#132421,(#132426,#132432),.PCURVE_S1.); +#132421 = CIRCLE('',#132422,0.208574704164); +#132422 = AXIS2_PLACEMENT_3D('',#132423,#132424,#132425); +#132423 = CARTESIAN_POINT('',(10.728168876214,4.35,2.640924866458E-017) + ); +#132424 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132425 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132426 = PCURVE('',#132230,#132427); +#132427 = DEFINITIONAL_REPRESENTATION('',(#132428),#132431); +#132428 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132429,#132430), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#130037 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#130038 = CARTESIAN_POINT('',(4.772630242227,-4.35)); -#130039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132429 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#132430 = CARTESIAN_POINT('',(4.772630242227,-4.35)); +#132431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130040 = PCURVE('',#92968,#130041); -#130041 = DEFINITIONAL_REPRESENTATION('',(#130042),#130050); -#130042 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130043,#130044,#130045, - #130046,#130047,#130048,#130049),.UNSPECIFIED.,.T.,.F.) +#132432 = PCURVE('',#95360,#132433); +#132433 = DEFINITIONAL_REPRESENTATION('',(#132434),#132442); +#132434 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132435,#132436,#132437, + #132438,#132439,#132440,#132441),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130043 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#130044 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#130045 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#130046 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#130047 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#130048 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#130049 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#130050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130051 = ORIENTED_EDGE('',*,*,#129822,.F.); -#130052 = ADVANCED_FACE('',(#130053),#129942,.T.); -#130053 = FACE_BOUND('',#130054,.T.); -#130054 = EDGE_LOOP('',(#130055,#130082,#130083,#130106)); -#130055 = ORIENTED_EDGE('',*,*,#130056,.T.); -#130056 = EDGE_CURVE('',#130057,#129927,#130059,.T.); -#130057 = VERTEX_POINT('',#130058); -#130058 = CARTESIAN_POINT('',(10.419594812019,4.35,0.E+000)); -#130059 = SURFACE_CURVE('',#130060,(#130065,#130071),.PCURVE_S1.); -#130060 = CIRCLE('',#130061,0.308574064194); -#130061 = AXIS2_PLACEMENT_3D('',#130062,#130063,#130064); -#130062 = CARTESIAN_POINT('',(10.728168876214,4.35,2.640924866458E-017) - ); -#130063 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130064 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130065 = PCURVE('',#129942,#130066); -#130066 = DEFINITIONAL_REPRESENTATION('',(#130067),#130070); -#130067 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130068,#130069), +#132435 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#132436 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#132437 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#132438 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#132439 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#132440 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#132441 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#132442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132443 = ORIENTED_EDGE('',*,*,#132214,.F.); +#132444 = ADVANCED_FACE('',(#132445),#132334,.T.); +#132445 = FACE_BOUND('',#132446,.T.); +#132446 = EDGE_LOOP('',(#132447,#132474,#132475,#132498)); +#132447 = ORIENTED_EDGE('',*,*,#132448,.T.); +#132448 = EDGE_CURVE('',#132449,#132319,#132451,.T.); +#132449 = VERTEX_POINT('',#132450); +#132450 = CARTESIAN_POINT('',(10.419594812019,4.35,0.E+000)); +#132451 = SURFACE_CURVE('',#132452,(#132457,#132463),.PCURVE_S1.); +#132452 = CIRCLE('',#132453,0.308574064194); +#132453 = AXIS2_PLACEMENT_3D('',#132454,#132455,#132456); +#132454 = CARTESIAN_POINT('',(10.728168876214,4.35,2.640924866458E-017) + ); +#132455 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132456 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132457 = PCURVE('',#132334,#132458); +#132458 = DEFINITIONAL_REPRESENTATION('',(#132459),#132462); +#132459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132460,#132461), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#130068 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#130069 = CARTESIAN_POINT('',(4.761821717947,-4.35)); -#130070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132460 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#132461 = CARTESIAN_POINT('',(4.761821717947,-4.35)); +#132462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130071 = PCURVE('',#92968,#130072); -#130072 = DEFINITIONAL_REPRESENTATION('',(#130073),#130081); -#130073 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130074,#130075,#130076, - #130077,#130078,#130079,#130080),.UNSPECIFIED.,.T.,.F.) +#132463 = PCURVE('',#95360,#132464); +#132464 = DEFINITIONAL_REPRESENTATION('',(#132465),#132473); +#132465 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132466,#132467,#132468, + #132469,#132470,#132471,#132472),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130074 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#130075 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#130076 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#130077 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#130078 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#130079 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#130080 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#130081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130082 = ORIENTED_EDGE('',*,*,#129926,.T.); -#130083 = ORIENTED_EDGE('',*,*,#130084,.F.); -#130084 = EDGE_CURVE('',#130085,#129904,#130087,.T.); -#130085 = VERTEX_POINT('',#130086); -#130086 = CARTESIAN_POINT('',(10.419594812019,4.15,0.E+000)); -#130087 = SURFACE_CURVE('',#130088,(#130093,#130099),.PCURVE_S1.); -#130088 = CIRCLE('',#130089,0.308574064194); -#130089 = AXIS2_PLACEMENT_3D('',#130090,#130091,#130092); -#130090 = CARTESIAN_POINT('',(10.728168876214,4.15,2.640924866458E-017) - ); -#130091 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130092 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130093 = PCURVE('',#129942,#130094); -#130094 = DEFINITIONAL_REPRESENTATION('',(#130095),#130098); -#130095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130096,#130097), +#132466 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#132467 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#132468 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#132469 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#132470 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#132471 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#132472 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#132473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132474 = ORIENTED_EDGE('',*,*,#132318,.T.); +#132475 = ORIENTED_EDGE('',*,*,#132476,.F.); +#132476 = EDGE_CURVE('',#132477,#132296,#132479,.T.); +#132477 = VERTEX_POINT('',#132478); +#132478 = CARTESIAN_POINT('',(10.419594812019,4.15,0.E+000)); +#132479 = SURFACE_CURVE('',#132480,(#132485,#132491),.PCURVE_S1.); +#132480 = CIRCLE('',#132481,0.308574064194); +#132481 = AXIS2_PLACEMENT_3D('',#132482,#132483,#132484); +#132482 = CARTESIAN_POINT('',(10.728168876214,4.15,2.640924866458E-017) + ); +#132483 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132484 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#132485 = PCURVE('',#132334,#132486); +#132486 = DEFINITIONAL_REPRESENTATION('',(#132487),#132490); +#132487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132488,#132489), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#130096 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#130097 = CARTESIAN_POINT('',(4.761821717947,-4.15)); -#130098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132488 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#132489 = CARTESIAN_POINT('',(4.761821717947,-4.15)); +#132490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130099 = PCURVE('',#93024,#130100); -#130100 = DEFINITIONAL_REPRESENTATION('',(#130101),#130105); -#130101 = CIRCLE('',#130102,0.308574064194); -#130102 = AXIS2_PLACEMENT_2D('',#130103,#130104); -#130103 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#130104 = DIRECTION('',(0.E+000,1.)); -#130105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132491 = PCURVE('',#95416,#132492); +#132492 = DEFINITIONAL_REPRESENTATION('',(#132493),#132497); +#132493 = CIRCLE('',#132494,0.308574064194); +#132494 = AXIS2_PLACEMENT_2D('',#132495,#132496); +#132495 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#132496 = DIRECTION('',(0.E+000,1.)); +#132497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130106 = ORIENTED_EDGE('',*,*,#130107,.T.); -#130107 = EDGE_CURVE('',#130085,#130057,#130108,.T.); -#130108 = SURFACE_CURVE('',#130109,(#130113,#130119),.PCURVE_S1.); -#130109 = LINE('',#130110,#130111); -#130110 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#132498 = ORIENTED_EDGE('',*,*,#132499,.T.); +#132499 = EDGE_CURVE('',#132477,#132449,#132500,.T.); +#132500 = SURFACE_CURVE('',#132501,(#132505,#132511),.PCURVE_S1.); +#132501 = LINE('',#132502,#132503); +#132502 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#130111 = VECTOR('',#130112,1.); -#130112 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130113 = PCURVE('',#129942,#130114); -#130114 = DEFINITIONAL_REPRESENTATION('',(#130115),#130118); -#130115 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130116,#130117), +#132503 = VECTOR('',#132504,1.); +#132504 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132505 = PCURVE('',#132334,#132506); +#132506 = DEFINITIONAL_REPRESENTATION('',(#132507),#132510); +#132507 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132508,#132509), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#130116 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#130117 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#130118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132508 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#132509 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#132510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130119 = PCURVE('',#130120,#130125); -#130120 = PLANE('',#130121); -#130121 = AXIS2_PLACEMENT_3D('',#130122,#130123,#130124); -#130122 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#132511 = PCURVE('',#132512,#132517); +#132512 = PLANE('',#132513); +#132513 = AXIS2_PLACEMENT_3D('',#132514,#132515,#132516); +#132514 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#130123 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130124 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130125 = DEFINITIONAL_REPRESENTATION('',(#130126),#130130); -#130126 = LINE('',#130127,#130128); -#130127 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#130128 = VECTOR('',#130129,1.); -#130129 = DIRECTION('',(-1.,0.E+000)); -#130130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130131 = ADVANCED_FACE('',(#130132),#130120,.T.); -#130132 = FACE_BOUND('',#130133,.T.); -#130133 = EDGE_LOOP('',(#130134,#130163,#130184,#130185)); -#130134 = ORIENTED_EDGE('',*,*,#130135,.T.); -#130135 = EDGE_CURVE('',#130136,#130138,#130140,.T.); -#130136 = VERTEX_POINT('',#130137); -#130137 = CARTESIAN_POINT('',(10.419594812019,4.15,0.530776333563)); -#130138 = VERTEX_POINT('',#130139); -#130139 = CARTESIAN_POINT('',(10.419594812019,4.35,0.530776333563)); -#130140 = SURFACE_CURVE('',#130141,(#130145,#130152),.PCURVE_S1.); -#130141 = LINE('',#130142,#130143); -#130142 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#132515 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132516 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132517 = DEFINITIONAL_REPRESENTATION('',(#132518),#132522); +#132518 = LINE('',#132519,#132520); +#132519 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#132520 = VECTOR('',#132521,1.); +#132521 = DIRECTION('',(-1.,0.E+000)); +#132522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132523 = ADVANCED_FACE('',(#132524),#132512,.T.); +#132524 = FACE_BOUND('',#132525,.T.); +#132525 = EDGE_LOOP('',(#132526,#132555,#132576,#132577)); +#132526 = ORIENTED_EDGE('',*,*,#132527,.T.); +#132527 = EDGE_CURVE('',#132528,#132530,#132532,.T.); +#132528 = VERTEX_POINT('',#132529); +#132529 = CARTESIAN_POINT('',(10.419594812019,4.15,0.530776333563)); +#132530 = VERTEX_POINT('',#132531); +#132531 = CARTESIAN_POINT('',(10.419594812019,4.35,0.530776333563)); +#132532 = SURFACE_CURVE('',#132533,(#132537,#132544),.PCURVE_S1.); +#132533 = LINE('',#132534,#132535); +#132534 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#130143 = VECTOR('',#130144,1.); -#130144 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130145 = PCURVE('',#130120,#130146); -#130146 = DEFINITIONAL_REPRESENTATION('',(#130147),#130151); -#130147 = LINE('',#130148,#130149); -#130148 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130149 = VECTOR('',#130150,1.); -#130150 = DIRECTION('',(-1.,0.E+000)); -#130151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130152 = PCURVE('',#130153,#130158); -#130153 = CYLINDRICAL_SURFACE('',#130154,0.119270391569); -#130154 = AXIS2_PLACEMENT_3D('',#130155,#130156,#130157); -#130155 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#132535 = VECTOR('',#132536,1.); +#132536 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132537 = PCURVE('',#132512,#132538); +#132538 = DEFINITIONAL_REPRESENTATION('',(#132539),#132543); +#132539 = LINE('',#132540,#132541); +#132540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132541 = VECTOR('',#132542,1.); +#132542 = DIRECTION('',(-1.,0.E+000)); +#132543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132544 = PCURVE('',#132545,#132550); +#132545 = CYLINDRICAL_SURFACE('',#132546,0.119270391569); +#132546 = AXIS2_PLACEMENT_3D('',#132547,#132548,#132549); +#132547 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#130156 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130157 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130158 = DEFINITIONAL_REPRESENTATION('',(#130159),#130162); -#130159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130160,#130161), +#132548 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132549 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132550 = DEFINITIONAL_REPRESENTATION('',(#132551),#132554); +#132551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132552,#132553), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#130160 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#130161 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#130162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130163 = ORIENTED_EDGE('',*,*,#130164,.T.); -#130164 = EDGE_CURVE('',#130138,#130057,#130165,.T.); -#130165 = SURFACE_CURVE('',#130166,(#130170,#130177),.PCURVE_S1.); -#130166 = LINE('',#130167,#130168); -#130167 = CARTESIAN_POINT('',(10.419594812019,4.35,0.530776333563)); -#130168 = VECTOR('',#130169,1.); -#130169 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#130170 = PCURVE('',#130120,#130171); -#130171 = DEFINITIONAL_REPRESENTATION('',(#130172),#130176); -#130172 = LINE('',#130173,#130174); -#130173 = CARTESIAN_POINT('',(-4.35,0.E+000)); -#130174 = VECTOR('',#130175,1.); -#130175 = DIRECTION('',(0.E+000,-1.)); -#130176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130177 = PCURVE('',#92968,#130178); -#130178 = DEFINITIONAL_REPRESENTATION('',(#130179),#130183); -#130179 = LINE('',#130180,#130181); -#130180 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#130181 = VECTOR('',#130182,1.); -#130182 = DIRECTION('',(-1.,0.E+000)); -#130183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130184 = ORIENTED_EDGE('',*,*,#130107,.F.); -#130185 = ORIENTED_EDGE('',*,*,#130186,.F.); -#130186 = EDGE_CURVE('',#130136,#130085,#130187,.T.); -#130187 = SURFACE_CURVE('',#130188,(#130192,#130199),.PCURVE_S1.); -#130188 = LINE('',#130189,#130190); -#130189 = CARTESIAN_POINT('',(10.419594812019,4.15,0.530776333563)); -#130190 = VECTOR('',#130191,1.); -#130191 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#130192 = PCURVE('',#130120,#130193); -#130193 = DEFINITIONAL_REPRESENTATION('',(#130194),#130198); -#130194 = LINE('',#130195,#130196); -#130195 = CARTESIAN_POINT('',(-4.15,0.E+000)); -#130196 = VECTOR('',#130197,1.); -#130197 = DIRECTION('',(0.E+000,-1.)); -#130198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130199 = PCURVE('',#93024,#130200); -#130200 = DEFINITIONAL_REPRESENTATION('',(#130201),#130205); -#130201 = LINE('',#130202,#130203); -#130202 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#130203 = VECTOR('',#130204,1.); -#130204 = DIRECTION('',(1.,0.E+000)); -#130205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130206 = ADVANCED_FACE('',(#130207),#130015,.T.); -#130207 = FACE_BOUND('',#130208,.T.); -#130208 = EDGE_LOOP('',(#130209,#130238,#130259,#130260)); -#130209 = ORIENTED_EDGE('',*,*,#130210,.T.); -#130210 = EDGE_CURVE('',#130211,#130213,#130215,.T.); -#130211 = VERTEX_POINT('',#130212); -#130212 = CARTESIAN_POINT('',(10.51959417205,4.35,0.530776333563)); -#130213 = VERTEX_POINT('',#130214); -#130214 = CARTESIAN_POINT('',(10.51959417205,4.15,0.530776333563)); -#130215 = SURFACE_CURVE('',#130216,(#130220,#130227),.PCURVE_S1.); -#130216 = LINE('',#130217,#130218); -#130217 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#132552 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#132553 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#132554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132555 = ORIENTED_EDGE('',*,*,#132556,.T.); +#132556 = EDGE_CURVE('',#132530,#132449,#132557,.T.); +#132557 = SURFACE_CURVE('',#132558,(#132562,#132569),.PCURVE_S1.); +#132558 = LINE('',#132559,#132560); +#132559 = CARTESIAN_POINT('',(10.419594812019,4.35,0.530776333563)); +#132560 = VECTOR('',#132561,1.); +#132561 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#132562 = PCURVE('',#132512,#132563); +#132563 = DEFINITIONAL_REPRESENTATION('',(#132564),#132568); +#132564 = LINE('',#132565,#132566); +#132565 = CARTESIAN_POINT('',(-4.35,0.E+000)); +#132566 = VECTOR('',#132567,1.); +#132567 = DIRECTION('',(0.E+000,-1.)); +#132568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132569 = PCURVE('',#95360,#132570); +#132570 = DEFINITIONAL_REPRESENTATION('',(#132571),#132575); +#132571 = LINE('',#132572,#132573); +#132572 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#132573 = VECTOR('',#132574,1.); +#132574 = DIRECTION('',(-1.,0.E+000)); +#132575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132576 = ORIENTED_EDGE('',*,*,#132499,.F.); +#132577 = ORIENTED_EDGE('',*,*,#132578,.F.); +#132578 = EDGE_CURVE('',#132528,#132477,#132579,.T.); +#132579 = SURFACE_CURVE('',#132580,(#132584,#132591),.PCURVE_S1.); +#132580 = LINE('',#132581,#132582); +#132581 = CARTESIAN_POINT('',(10.419594812019,4.15,0.530776333563)); +#132582 = VECTOR('',#132583,1.); +#132583 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#132584 = PCURVE('',#132512,#132585); +#132585 = DEFINITIONAL_REPRESENTATION('',(#132586),#132590); +#132586 = LINE('',#132587,#132588); +#132587 = CARTESIAN_POINT('',(-4.15,0.E+000)); +#132588 = VECTOR('',#132589,1.); +#132589 = DIRECTION('',(0.E+000,-1.)); +#132590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132591 = PCURVE('',#95416,#132592); +#132592 = DEFINITIONAL_REPRESENTATION('',(#132593),#132597); +#132593 = LINE('',#132594,#132595); +#132594 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#132595 = VECTOR('',#132596,1.); +#132596 = DIRECTION('',(1.,0.E+000)); +#132597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132598 = ADVANCED_FACE('',(#132599),#132407,.T.); +#132599 = FACE_BOUND('',#132600,.T.); +#132600 = EDGE_LOOP('',(#132601,#132630,#132651,#132652)); +#132601 = ORIENTED_EDGE('',*,*,#132602,.T.); +#132602 = EDGE_CURVE('',#132603,#132605,#132607,.T.); +#132603 = VERTEX_POINT('',#132604); +#132604 = CARTESIAN_POINT('',(10.51959417205,4.35,0.530776333563)); +#132605 = VERTEX_POINT('',#132606); +#132606 = CARTESIAN_POINT('',(10.51959417205,4.15,0.530776333563)); +#132607 = SURFACE_CURVE('',#132608,(#132612,#132619),.PCURVE_S1.); +#132608 = LINE('',#132609,#132610); +#132609 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#130218 = VECTOR('',#130219,1.); -#130219 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130220 = PCURVE('',#130015,#130221); -#130221 = DEFINITIONAL_REPRESENTATION('',(#130222),#130226); -#130222 = LINE('',#130223,#130224); -#130223 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130224 = VECTOR('',#130225,1.); -#130225 = DIRECTION('',(-1.,0.E+000)); -#130226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130227 = PCURVE('',#130228,#130233); -#130228 = CYLINDRICAL_SURFACE('',#130229,0.2192697516); -#130229 = AXIS2_PLACEMENT_3D('',#130230,#130231,#130232); -#130230 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#132610 = VECTOR('',#132611,1.); +#132611 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132612 = PCURVE('',#132407,#132613); +#132613 = DEFINITIONAL_REPRESENTATION('',(#132614),#132618); +#132614 = LINE('',#132615,#132616); +#132615 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132616 = VECTOR('',#132617,1.); +#132617 = DIRECTION('',(-1.,0.E+000)); +#132618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132619 = PCURVE('',#132620,#132625); +#132620 = CYLINDRICAL_SURFACE('',#132621,0.2192697516); +#132621 = AXIS2_PLACEMENT_3D('',#132622,#132623,#132624); +#132622 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#130231 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130232 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130233 = DEFINITIONAL_REPRESENTATION('',(#130234),#130237); -#130234 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130235,#130236), +#132623 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132624 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132625 = DEFINITIONAL_REPRESENTATION('',(#132626),#132629); +#132626 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132627,#132628), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#130235 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#130236 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#130237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130238 = ORIENTED_EDGE('',*,*,#130239,.T.); -#130239 = EDGE_CURVE('',#130213,#129978,#130240,.T.); -#130240 = SURFACE_CURVE('',#130241,(#130245,#130252),.PCURVE_S1.); -#130241 = LINE('',#130242,#130243); -#130242 = CARTESIAN_POINT('',(10.51959417205,4.15,0.530776333563)); -#130243 = VECTOR('',#130244,1.); -#130244 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#130245 = PCURVE('',#130015,#130246); -#130246 = DEFINITIONAL_REPRESENTATION('',(#130247),#130251); -#130247 = LINE('',#130248,#130249); -#130248 = CARTESIAN_POINT('',(4.15,0.E+000)); -#130249 = VECTOR('',#130250,1.); -#130250 = DIRECTION('',(0.E+000,-1.)); -#130251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130252 = PCURVE('',#93024,#130253); -#130253 = DEFINITIONAL_REPRESENTATION('',(#130254),#130258); -#130254 = LINE('',#130255,#130256); -#130255 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#130256 = VECTOR('',#130257,1.); -#130257 = DIRECTION('',(1.,0.E+000)); -#130258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130259 = ORIENTED_EDGE('',*,*,#130000,.F.); -#130260 = ORIENTED_EDGE('',*,*,#130261,.F.); -#130261 = EDGE_CURVE('',#130211,#130001,#130262,.T.); -#130262 = SURFACE_CURVE('',#130263,(#130267,#130274),.PCURVE_S1.); -#130263 = LINE('',#130264,#130265); -#130264 = CARTESIAN_POINT('',(10.51959417205,4.35,0.530776333563)); -#130265 = VECTOR('',#130266,1.); -#130266 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#130267 = PCURVE('',#130015,#130268); -#130268 = DEFINITIONAL_REPRESENTATION('',(#130269),#130273); -#130269 = LINE('',#130270,#130271); -#130270 = CARTESIAN_POINT('',(4.35,0.E+000)); -#130271 = VECTOR('',#130272,1.); -#130272 = DIRECTION('',(0.E+000,-1.)); -#130273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130274 = PCURVE('',#92968,#130275); -#130275 = DEFINITIONAL_REPRESENTATION('',(#130276),#130280); -#130276 = LINE('',#130277,#130278); -#130277 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#130278 = VECTOR('',#130279,1.); -#130279 = DIRECTION('',(-1.,0.E+000)); -#130280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130281 = ADVANCED_FACE('',(#130282),#130228,.T.); -#130282 = FACE_BOUND('',#130283,.T.); -#130283 = EDGE_LOOP('',(#130284,#130285,#130308,#130330)); -#130284 = ORIENTED_EDGE('',*,*,#130210,.F.); -#130285 = ORIENTED_EDGE('',*,*,#130286,.F.); -#130286 = EDGE_CURVE('',#130287,#130211,#130289,.T.); -#130287 = VERTEX_POINT('',#130288); -#130288 = CARTESIAN_POINT('',(10.304819755875,4.35,0.75)); -#130289 = SURFACE_CURVE('',#130290,(#130295,#130301),.PCURVE_S1.); -#130290 = CIRCLE('',#130291,0.2192697516); -#130291 = AXIS2_PLACEMENT_3D('',#130292,#130293,#130294); -#130292 = CARTESIAN_POINT('',(10.30032442045,4.35,0.530776333563)); -#130293 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130294 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130295 = PCURVE('',#130228,#130296); -#130296 = DEFINITIONAL_REPRESENTATION('',(#130297),#130300); -#130297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130298,#130299), +#132627 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#132628 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#132629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132630 = ORIENTED_EDGE('',*,*,#132631,.T.); +#132631 = EDGE_CURVE('',#132605,#132370,#132632,.T.); +#132632 = SURFACE_CURVE('',#132633,(#132637,#132644),.PCURVE_S1.); +#132633 = LINE('',#132634,#132635); +#132634 = CARTESIAN_POINT('',(10.51959417205,4.15,0.530776333563)); +#132635 = VECTOR('',#132636,1.); +#132636 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#132637 = PCURVE('',#132407,#132638); +#132638 = DEFINITIONAL_REPRESENTATION('',(#132639),#132643); +#132639 = LINE('',#132640,#132641); +#132640 = CARTESIAN_POINT('',(4.15,0.E+000)); +#132641 = VECTOR('',#132642,1.); +#132642 = DIRECTION('',(0.E+000,-1.)); +#132643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132644 = PCURVE('',#95416,#132645); +#132645 = DEFINITIONAL_REPRESENTATION('',(#132646),#132650); +#132646 = LINE('',#132647,#132648); +#132647 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#132648 = VECTOR('',#132649,1.); +#132649 = DIRECTION('',(1.,0.E+000)); +#132650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132651 = ORIENTED_EDGE('',*,*,#132392,.F.); +#132652 = ORIENTED_EDGE('',*,*,#132653,.F.); +#132653 = EDGE_CURVE('',#132603,#132393,#132654,.T.); +#132654 = SURFACE_CURVE('',#132655,(#132659,#132666),.PCURVE_S1.); +#132655 = LINE('',#132656,#132657); +#132656 = CARTESIAN_POINT('',(10.51959417205,4.35,0.530776333563)); +#132657 = VECTOR('',#132658,1.); +#132658 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#132659 = PCURVE('',#132407,#132660); +#132660 = DEFINITIONAL_REPRESENTATION('',(#132661),#132665); +#132661 = LINE('',#132662,#132663); +#132662 = CARTESIAN_POINT('',(4.35,0.E+000)); +#132663 = VECTOR('',#132664,1.); +#132664 = DIRECTION('',(0.E+000,-1.)); +#132665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132666 = PCURVE('',#95360,#132667); +#132667 = DEFINITIONAL_REPRESENTATION('',(#132668),#132672); +#132668 = LINE('',#132669,#132670); +#132669 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#132670 = VECTOR('',#132671,1.); +#132671 = DIRECTION('',(-1.,0.E+000)); +#132672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132673 = ADVANCED_FACE('',(#132674),#132620,.T.); +#132674 = FACE_BOUND('',#132675,.T.); +#132675 = EDGE_LOOP('',(#132676,#132677,#132700,#132722)); +#132676 = ORIENTED_EDGE('',*,*,#132602,.F.); +#132677 = ORIENTED_EDGE('',*,*,#132678,.F.); +#132678 = EDGE_CURVE('',#132679,#132603,#132681,.T.); +#132679 = VERTEX_POINT('',#132680); +#132680 = CARTESIAN_POINT('',(10.304819755875,4.35,0.75)); +#132681 = SURFACE_CURVE('',#132682,(#132687,#132693),.PCURVE_S1.); +#132682 = CIRCLE('',#132683,0.2192697516); +#132683 = AXIS2_PLACEMENT_3D('',#132684,#132685,#132686); +#132684 = CARTESIAN_POINT('',(10.30032442045,4.35,0.530776333563)); +#132685 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132686 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132687 = PCURVE('',#132620,#132688); +#132688 = DEFINITIONAL_REPRESENTATION('',(#132689),#132692); +#132689 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132690,#132691), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#130298 = CARTESIAN_POINT('',(1.591299156552,4.35)); -#130299 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#130300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130301 = PCURVE('',#92968,#130302); -#130302 = DEFINITIONAL_REPRESENTATION('',(#130303),#130307); -#130303 = CIRCLE('',#130304,0.2192697516); -#130304 = AXIS2_PLACEMENT_2D('',#130305,#130306); -#130305 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#130306 = DIRECTION('',(0.E+000,-1.)); -#130307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130308 = ORIENTED_EDGE('',*,*,#130309,.F.); -#130309 = EDGE_CURVE('',#130310,#130287,#130312,.T.); -#130310 = VERTEX_POINT('',#130311); -#130311 = CARTESIAN_POINT('',(10.304819755875,4.15,0.75)); -#130312 = SURFACE_CURVE('',#130313,(#130317,#130323),.PCURVE_S1.); -#130313 = LINE('',#130314,#130315); -#130314 = CARTESIAN_POINT('',(10.304819755875,4.35,0.75)); -#130315 = VECTOR('',#130316,1.); -#130316 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130317 = PCURVE('',#130228,#130318); -#130318 = DEFINITIONAL_REPRESENTATION('',(#130319),#130322); -#130319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130320,#130321), +#132690 = CARTESIAN_POINT('',(1.591299156552,4.35)); +#132691 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#132692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132693 = PCURVE('',#95360,#132694); +#132694 = DEFINITIONAL_REPRESENTATION('',(#132695),#132699); +#132695 = CIRCLE('',#132696,0.2192697516); +#132696 = AXIS2_PLACEMENT_2D('',#132697,#132698); +#132697 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#132698 = DIRECTION('',(0.E+000,-1.)); +#132699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132700 = ORIENTED_EDGE('',*,*,#132701,.F.); +#132701 = EDGE_CURVE('',#132702,#132679,#132704,.T.); +#132702 = VERTEX_POINT('',#132703); +#132703 = CARTESIAN_POINT('',(10.304819755875,4.15,0.75)); +#132704 = SURFACE_CURVE('',#132705,(#132709,#132715),.PCURVE_S1.); +#132705 = LINE('',#132706,#132707); +#132706 = CARTESIAN_POINT('',(10.304819755875,4.35,0.75)); +#132707 = VECTOR('',#132708,1.); +#132708 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132709 = PCURVE('',#132620,#132710); +#132710 = DEFINITIONAL_REPRESENTATION('',(#132711),#132714); +#132711 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132712,#132713), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#130320 = CARTESIAN_POINT('',(1.591299156552,4.15)); -#130321 = CARTESIAN_POINT('',(1.591299156552,4.35)); -#130322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130323 = PCURVE('',#93050,#130324); -#130324 = DEFINITIONAL_REPRESENTATION('',(#130325),#130329); -#130325 = LINE('',#130326,#130327); -#130326 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#130327 = VECTOR('',#130328,1.); -#130328 = DIRECTION('',(4.440892098501E-016,1.)); -#130329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130330 = ORIENTED_EDGE('',*,*,#130331,.T.); -#130331 = EDGE_CURVE('',#130310,#130213,#130332,.T.); -#130332 = SURFACE_CURVE('',#130333,(#130338,#130344),.PCURVE_S1.); -#130333 = CIRCLE('',#130334,0.2192697516); -#130334 = AXIS2_PLACEMENT_3D('',#130335,#130336,#130337); -#130335 = CARTESIAN_POINT('',(10.30032442045,4.15,0.530776333563)); -#130336 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130337 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130338 = PCURVE('',#130228,#130339); -#130339 = DEFINITIONAL_REPRESENTATION('',(#130340),#130343); -#130340 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130341,#130342), +#132712 = CARTESIAN_POINT('',(1.591299156552,4.15)); +#132713 = CARTESIAN_POINT('',(1.591299156552,4.35)); +#132714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132715 = PCURVE('',#95442,#132716); +#132716 = DEFINITIONAL_REPRESENTATION('',(#132717),#132721); +#132717 = LINE('',#132718,#132719); +#132718 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#132719 = VECTOR('',#132720,1.); +#132720 = DIRECTION('',(4.440892098501E-016,1.)); +#132721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132722 = ORIENTED_EDGE('',*,*,#132723,.T.); +#132723 = EDGE_CURVE('',#132702,#132605,#132724,.T.); +#132724 = SURFACE_CURVE('',#132725,(#132730,#132736),.PCURVE_S1.); +#132725 = CIRCLE('',#132726,0.2192697516); +#132726 = AXIS2_PLACEMENT_3D('',#132727,#132728,#132729); +#132727 = CARTESIAN_POINT('',(10.30032442045,4.15,0.530776333563)); +#132728 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132729 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132730 = PCURVE('',#132620,#132731); +#132731 = DEFINITIONAL_REPRESENTATION('',(#132732),#132735); +#132732 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132733,#132734), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#130341 = CARTESIAN_POINT('',(1.591299156552,4.15)); -#130342 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#130343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132733 = CARTESIAN_POINT('',(1.591299156552,4.15)); +#132734 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#132735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130344 = PCURVE('',#93024,#130345); -#130345 = DEFINITIONAL_REPRESENTATION('',(#130346),#130354); -#130346 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130347,#130348,#130349, - #130350,#130351,#130352,#130353),.UNSPECIFIED.,.T.,.F.) +#132736 = PCURVE('',#95416,#132737); +#132737 = DEFINITIONAL_REPRESENTATION('',(#132738),#132746); +#132738 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132739,#132740,#132741, + #132742,#132743,#132744,#132745),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130347 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#130348 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#130349 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#130350 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#130351 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#130352 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#130353 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#130354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130355 = ADVANCED_FACE('',(#130356),#130153,.F.); -#130356 = FACE_BOUND('',#130357,.F.); -#130357 = EDGE_LOOP('',(#130358,#130359,#130382,#130404)); -#130358 = ORIENTED_EDGE('',*,*,#130135,.T.); -#130359 = ORIENTED_EDGE('',*,*,#130360,.F.); -#130360 = EDGE_CURVE('',#130361,#130138,#130363,.T.); -#130361 = VERTEX_POINT('',#130362); -#130362 = CARTESIAN_POINT('',(10.303662633502,4.35,0.65)); -#130363 = SURFACE_CURVE('',#130364,(#130369,#130375),.PCURVE_S1.); -#130364 = CIRCLE('',#130365,0.119270391569); -#130365 = AXIS2_PLACEMENT_3D('',#130366,#130367,#130368); -#130366 = CARTESIAN_POINT('',(10.30032442045,4.35,0.530776333563)); -#130367 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130368 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130369 = PCURVE('',#130153,#130370); -#130370 = DEFINITIONAL_REPRESENTATION('',(#130371),#130374); -#130371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130372,#130373), +#132739 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#132740 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#132741 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#132742 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#132743 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#132744 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#132745 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#132746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132747 = ADVANCED_FACE('',(#132748),#132545,.F.); +#132748 = FACE_BOUND('',#132749,.F.); +#132749 = EDGE_LOOP('',(#132750,#132751,#132774,#132796)); +#132750 = ORIENTED_EDGE('',*,*,#132527,.T.); +#132751 = ORIENTED_EDGE('',*,*,#132752,.F.); +#132752 = EDGE_CURVE('',#132753,#132530,#132755,.T.); +#132753 = VERTEX_POINT('',#132754); +#132754 = CARTESIAN_POINT('',(10.303662633502,4.35,0.65)); +#132755 = SURFACE_CURVE('',#132756,(#132761,#132767),.PCURVE_S1.); +#132756 = CIRCLE('',#132757,0.119270391569); +#132757 = AXIS2_PLACEMENT_3D('',#132758,#132759,#132760); +#132758 = CARTESIAN_POINT('',(10.30032442045,4.35,0.530776333563)); +#132759 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132760 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132761 = PCURVE('',#132545,#132762); +#132762 = DEFINITIONAL_REPRESENTATION('',(#132763),#132766); +#132763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132764,#132765), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#130372 = CARTESIAN_POINT('',(1.598788597134,4.35)); -#130373 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#130374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130375 = PCURVE('',#92968,#130376); -#130376 = DEFINITIONAL_REPRESENTATION('',(#130377),#130381); -#130377 = CIRCLE('',#130378,0.119270391569); -#130378 = AXIS2_PLACEMENT_2D('',#130379,#130380); -#130379 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#130380 = DIRECTION('',(0.E+000,-1.)); -#130381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130382 = ORIENTED_EDGE('',*,*,#130383,.T.); -#130383 = EDGE_CURVE('',#130361,#130384,#130386,.T.); -#130384 = VERTEX_POINT('',#130385); -#130385 = CARTESIAN_POINT('',(10.303662633502,4.15,0.65)); -#130386 = SURFACE_CURVE('',#130387,(#130391,#130397),.PCURVE_S1.); -#130387 = LINE('',#130388,#130389); -#130388 = CARTESIAN_POINT('',(10.303662633502,4.35,0.65)); -#130389 = VECTOR('',#130390,1.); -#130390 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130391 = PCURVE('',#130153,#130392); -#130392 = DEFINITIONAL_REPRESENTATION('',(#130393),#130396); -#130393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130394,#130395), +#132764 = CARTESIAN_POINT('',(1.598788597134,4.35)); +#132765 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#132766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132767 = PCURVE('',#95360,#132768); +#132768 = DEFINITIONAL_REPRESENTATION('',(#132769),#132773); +#132769 = CIRCLE('',#132770,0.119270391569); +#132770 = AXIS2_PLACEMENT_2D('',#132771,#132772); +#132771 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#132772 = DIRECTION('',(0.E+000,-1.)); +#132773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132774 = ORIENTED_EDGE('',*,*,#132775,.T.); +#132775 = EDGE_CURVE('',#132753,#132776,#132778,.T.); +#132776 = VERTEX_POINT('',#132777); +#132777 = CARTESIAN_POINT('',(10.303662633502,4.15,0.65)); +#132778 = SURFACE_CURVE('',#132779,(#132783,#132789),.PCURVE_S1.); +#132779 = LINE('',#132780,#132781); +#132780 = CARTESIAN_POINT('',(10.303662633502,4.35,0.65)); +#132781 = VECTOR('',#132782,1.); +#132782 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#132783 = PCURVE('',#132545,#132784); +#132784 = DEFINITIONAL_REPRESENTATION('',(#132785),#132788); +#132785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132786,#132787), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#130394 = CARTESIAN_POINT('',(1.598788597134,4.35)); -#130395 = CARTESIAN_POINT('',(1.598788597134,4.15)); -#130396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130397 = PCURVE('',#92996,#130398); -#130398 = DEFINITIONAL_REPRESENTATION('',(#130399),#130403); -#130399 = LINE('',#130400,#130401); -#130400 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#130401 = VECTOR('',#130402,1.); -#130402 = DIRECTION('',(4.440892098501E-016,-1.)); -#130403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130404 = ORIENTED_EDGE('',*,*,#130405,.T.); -#130405 = EDGE_CURVE('',#130384,#130136,#130406,.T.); -#130406 = SURFACE_CURVE('',#130407,(#130412,#130418),.PCURVE_S1.); -#130407 = CIRCLE('',#130408,0.119270391569); -#130408 = AXIS2_PLACEMENT_3D('',#130409,#130410,#130411); -#130409 = CARTESIAN_POINT('',(10.30032442045,4.15,0.530776333563)); -#130410 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130411 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#130412 = PCURVE('',#130153,#130413); -#130413 = DEFINITIONAL_REPRESENTATION('',(#130414),#130417); -#130414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130415,#130416), +#132786 = CARTESIAN_POINT('',(1.598788597134,4.35)); +#132787 = CARTESIAN_POINT('',(1.598788597134,4.15)); +#132788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132789 = PCURVE('',#95388,#132790); +#132790 = DEFINITIONAL_REPRESENTATION('',(#132791),#132795); +#132791 = LINE('',#132792,#132793); +#132792 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#132793 = VECTOR('',#132794,1.); +#132794 = DIRECTION('',(4.440892098501E-016,-1.)); +#132795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132796 = ORIENTED_EDGE('',*,*,#132797,.T.); +#132797 = EDGE_CURVE('',#132776,#132528,#132798,.T.); +#132798 = SURFACE_CURVE('',#132799,(#132804,#132810),.PCURVE_S1.); +#132799 = CIRCLE('',#132800,0.119270391569); +#132800 = AXIS2_PLACEMENT_3D('',#132801,#132802,#132803); +#132801 = CARTESIAN_POINT('',(10.30032442045,4.15,0.530776333563)); +#132802 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#132803 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#132804 = PCURVE('',#132545,#132805); +#132805 = DEFINITIONAL_REPRESENTATION('',(#132806),#132809); +#132806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132807,#132808), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#130415 = CARTESIAN_POINT('',(1.598788597134,4.15)); -#130416 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#130417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132807 = CARTESIAN_POINT('',(1.598788597134,4.15)); +#132808 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#132809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130418 = PCURVE('',#93024,#130419); -#130419 = DEFINITIONAL_REPRESENTATION('',(#130420),#130428); -#130420 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130421,#130422,#130423, - #130424,#130425,#130426,#130427),.UNSPECIFIED.,.T.,.F.) +#132810 = PCURVE('',#95416,#132811); +#132811 = DEFINITIONAL_REPRESENTATION('',(#132812),#132820); +#132812 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132813,#132814,#132815, + #132816,#132817,#132818,#132819),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130421 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#130422 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#130423 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#130424 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#130425 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#130426 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#130427 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#130428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130429 = ADVANCED_FACE('',(#130430),#92996,.T.); -#130430 = FACE_BOUND('',#130431,.T.); -#130431 = EDGE_LOOP('',(#130432,#130453,#130454,#130475)); -#130432 = ORIENTED_EDGE('',*,*,#130433,.F.); -#130433 = EDGE_CURVE('',#130361,#92953,#130434,.T.); -#130434 = SURFACE_CURVE('',#130435,(#130439,#130446),.PCURVE_S1.); -#130435 = LINE('',#130436,#130437); -#130436 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); -#130437 = VECTOR('',#130438,1.); -#130438 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#130439 = PCURVE('',#92996,#130440); -#130440 = DEFINITIONAL_REPRESENTATION('',(#130441),#130445); -#130441 = LINE('',#130442,#130443); -#130442 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130443 = VECTOR('',#130444,1.); -#130444 = DIRECTION('',(1.,-3.00059940766E-063)); -#130445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130446 = PCURVE('',#92968,#130447); -#130447 = DEFINITIONAL_REPRESENTATION('',(#130448),#130452); -#130448 = LINE('',#130449,#130450); -#130449 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130450 = VECTOR('',#130451,1.); -#130451 = DIRECTION('',(3.563627120235E-016,-1.)); -#130452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130453 = ORIENTED_EDGE('',*,*,#130383,.T.); -#130454 = ORIENTED_EDGE('',*,*,#130455,.T.); -#130455 = EDGE_CURVE('',#130384,#92981,#130456,.T.); -#130456 = SURFACE_CURVE('',#130457,(#130461,#130468),.PCURVE_S1.); -#130457 = LINE('',#130458,#130459); -#130458 = CARTESIAN_POINT('',(10.527847992439,4.15,0.65)); -#130459 = VECTOR('',#130460,1.); -#130460 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#130461 = PCURVE('',#92996,#130462); -#130462 = DEFINITIONAL_REPRESENTATION('',(#130463),#130467); -#130463 = LINE('',#130464,#130465); -#130464 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#130465 = VECTOR('',#130466,1.); -#130466 = DIRECTION('',(1.,-3.00059940766E-063)); -#130467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130468 = PCURVE('',#93024,#130469); -#130469 = DEFINITIONAL_REPRESENTATION('',(#130470),#130474); -#130470 = LINE('',#130471,#130472); -#130471 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130472 = VECTOR('',#130473,1.); -#130473 = DIRECTION('',(-3.563627120235E-016,-1.)); -#130474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130475 = ORIENTED_EDGE('',*,*,#92980,.F.); -#130476 = ADVANCED_FACE('',(#130477),#93024,.T.); -#130477 = FACE_BOUND('',#130478,.T.); -#130478 = EDGE_LOOP('',(#130479,#130480,#130481,#130482,#130483,#130484, - #130505,#130506,#130507,#130508,#130509,#130530)); -#130479 = ORIENTED_EDGE('',*,*,#130455,.F.); -#130480 = ORIENTED_EDGE('',*,*,#130405,.T.); -#130481 = ORIENTED_EDGE('',*,*,#130186,.T.); -#130482 = ORIENTED_EDGE('',*,*,#130084,.T.); -#130483 = ORIENTED_EDGE('',*,*,#129903,.T.); -#130484 = ORIENTED_EDGE('',*,*,#130485,.F.); -#130485 = EDGE_CURVE('',#129767,#129874,#130486,.T.); -#130486 = SURFACE_CURVE('',#130487,(#130491,#130498),.PCURVE_S1.); -#130487 = LINE('',#130488,#130489); -#130488 = CARTESIAN_POINT('',(11.,4.15,1.159810404338E-002)); -#130489 = VECTOR('',#130490,1.); -#130490 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#130491 = PCURVE('',#93024,#130492); -#130492 = DEFINITIONAL_REPRESENTATION('',(#130493),#130497); -#130493 = LINE('',#130494,#130495); -#130494 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#130495 = VECTOR('',#130496,1.); -#130496 = DIRECTION('',(1.,-2.101748079665E-016)); -#130497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#132813 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#132814 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#132815 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#132816 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#132817 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#132818 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#132819 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#132820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132821 = ADVANCED_FACE('',(#132822),#95388,.T.); +#132822 = FACE_BOUND('',#132823,.T.); +#132823 = EDGE_LOOP('',(#132824,#132845,#132846,#132867)); +#132824 = ORIENTED_EDGE('',*,*,#132825,.F.); +#132825 = EDGE_CURVE('',#132753,#95345,#132826,.T.); +#132826 = SURFACE_CURVE('',#132827,(#132831,#132838),.PCURVE_S1.); +#132827 = LINE('',#132828,#132829); +#132828 = CARTESIAN_POINT('',(10.527847992439,4.35,0.65)); +#132829 = VECTOR('',#132830,1.); +#132830 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132831 = PCURVE('',#95388,#132832); +#132832 = DEFINITIONAL_REPRESENTATION('',(#132833),#132837); +#132833 = LINE('',#132834,#132835); +#132834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132835 = VECTOR('',#132836,1.); +#132836 = DIRECTION('',(1.,-3.00059940766E-063)); +#132837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132838 = PCURVE('',#95360,#132839); +#132839 = DEFINITIONAL_REPRESENTATION('',(#132840),#132844); +#132840 = LINE('',#132841,#132842); +#132841 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132842 = VECTOR('',#132843,1.); +#132843 = DIRECTION('',(3.563627120235E-016,-1.)); +#132844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132845 = ORIENTED_EDGE('',*,*,#132775,.T.); +#132846 = ORIENTED_EDGE('',*,*,#132847,.T.); +#132847 = EDGE_CURVE('',#132776,#95373,#132848,.T.); +#132848 = SURFACE_CURVE('',#132849,(#132853,#132860),.PCURVE_S1.); +#132849 = LINE('',#132850,#132851); +#132850 = CARTESIAN_POINT('',(10.527847992439,4.15,0.65)); +#132851 = VECTOR('',#132852,1.); +#132852 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132853 = PCURVE('',#95388,#132854); +#132854 = DEFINITIONAL_REPRESENTATION('',(#132855),#132859); +#132855 = LINE('',#132856,#132857); +#132856 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#132857 = VECTOR('',#132858,1.); +#132858 = DIRECTION('',(1.,-3.00059940766E-063)); +#132859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132860 = PCURVE('',#95416,#132861); +#132861 = DEFINITIONAL_REPRESENTATION('',(#132862),#132866); +#132862 = LINE('',#132863,#132864); +#132863 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132864 = VECTOR('',#132865,1.); +#132865 = DIRECTION('',(-3.563627120235E-016,-1.)); +#132866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132867 = ORIENTED_EDGE('',*,*,#95372,.F.); +#132868 = ADVANCED_FACE('',(#132869),#95416,.T.); +#132869 = FACE_BOUND('',#132870,.T.); +#132870 = EDGE_LOOP('',(#132871,#132872,#132873,#132874,#132875,#132876, + #132897,#132898,#132899,#132900,#132901,#132922)); +#132871 = ORIENTED_EDGE('',*,*,#132847,.F.); +#132872 = ORIENTED_EDGE('',*,*,#132797,.T.); +#132873 = ORIENTED_EDGE('',*,*,#132578,.T.); +#132874 = ORIENTED_EDGE('',*,*,#132476,.T.); +#132875 = ORIENTED_EDGE('',*,*,#132295,.T.); +#132876 = ORIENTED_EDGE('',*,*,#132877,.F.); +#132877 = EDGE_CURVE('',#132159,#132266,#132878,.T.); +#132878 = SURFACE_CURVE('',#132879,(#132883,#132890),.PCURVE_S1.); +#132879 = LINE('',#132880,#132881); +#132880 = CARTESIAN_POINT('',(11.,4.15,1.159810404338E-002)); +#132881 = VECTOR('',#132882,1.); +#132882 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#132883 = PCURVE('',#95416,#132884); +#132884 = DEFINITIONAL_REPRESENTATION('',(#132885),#132889); +#132885 = LINE('',#132886,#132887); +#132886 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#132887 = VECTOR('',#132888,1.); +#132888 = DIRECTION('',(1.,-2.101748079665E-016)); +#132889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132890 = PCURVE('',#132179,#132891); +#132891 = DEFINITIONAL_REPRESENTATION('',(#132892),#132896); +#132892 = LINE('',#132893,#132894); +#132893 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#132894 = VECTOR('',#132895,1.); +#132895 = DIRECTION('',(-1.194699204908E-017,-1.)); +#132896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132897 = ORIENTED_EDGE('',*,*,#132241,.F.); +#132898 = ORIENTED_EDGE('',*,*,#132369,.F.); +#132899 = ORIENTED_EDGE('',*,*,#132631,.F.); +#132900 = ORIENTED_EDGE('',*,*,#132723,.F.); +#132901 = ORIENTED_EDGE('',*,*,#132902,.T.); +#132902 = EDGE_CURVE('',#132702,#95401,#132903,.T.); +#132903 = SURFACE_CURVE('',#132904,(#132908,#132915),.PCURVE_S1.); +#132904 = LINE('',#132905,#132906); +#132905 = CARTESIAN_POINT('',(10.527847992439,4.15,0.75)); +#132906 = VECTOR('',#132907,1.); +#132907 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132908 = PCURVE('',#95416,#132909); +#132909 = DEFINITIONAL_REPRESENTATION('',(#132910),#132914); +#132910 = LINE('',#132911,#132912); +#132911 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#132912 = VECTOR('',#132913,1.); +#132913 = DIRECTION('',(-3.563627120235E-016,-1.)); +#132914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132915 = PCURVE('',#95442,#132916); +#132916 = DEFINITIONAL_REPRESENTATION('',(#132917),#132921); +#132917 = LINE('',#132918,#132919); +#132918 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#132919 = VECTOR('',#132920,1.); +#132920 = DIRECTION('',(-1.,-3.00059940766E-063)); +#132921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132922 = ORIENTED_EDGE('',*,*,#95400,.F.); +#132923 = ADVANCED_FACE('',(#132924),#95442,.T.); +#132924 = FACE_BOUND('',#132925,.T.); +#132925 = EDGE_LOOP('',(#132926,#132927,#132928,#132949)); +#132926 = ORIENTED_EDGE('',*,*,#132902,.F.); +#132927 = ORIENTED_EDGE('',*,*,#132701,.T.); +#132928 = ORIENTED_EDGE('',*,*,#132929,.T.); +#132929 = EDGE_CURVE('',#132679,#95343,#132930,.T.); +#132930 = SURFACE_CURVE('',#132931,(#132935,#132942),.PCURVE_S1.); +#132931 = LINE('',#132932,#132933); +#132932 = CARTESIAN_POINT('',(10.527847992439,4.35,0.75)); +#132933 = VECTOR('',#132934,1.); +#132934 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#132935 = PCURVE('',#95442,#132936); +#132936 = DEFINITIONAL_REPRESENTATION('',(#132937),#132941); +#132937 = LINE('',#132938,#132939); +#132938 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#132939 = VECTOR('',#132940,1.); +#132940 = DIRECTION('',(-1.,-3.00059940766E-063)); +#132941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132942 = PCURVE('',#95360,#132943); +#132943 = DEFINITIONAL_REPRESENTATION('',(#132944),#132948); +#132944 = LINE('',#132945,#132946); +#132945 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#132946 = VECTOR('',#132947,1.); +#132947 = DIRECTION('',(3.563627120235E-016,-1.)); +#132948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130498 = PCURVE('',#129787,#130499); -#130499 = DEFINITIONAL_REPRESENTATION('',(#130500),#130504); -#130500 = LINE('',#130501,#130502); -#130501 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#130502 = VECTOR('',#130503,1.); -#130503 = DIRECTION('',(-1.194699204908E-017,-1.)); -#130504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130505 = ORIENTED_EDGE('',*,*,#129849,.F.); -#130506 = ORIENTED_EDGE('',*,*,#129977,.F.); -#130507 = ORIENTED_EDGE('',*,*,#130239,.F.); -#130508 = ORIENTED_EDGE('',*,*,#130331,.F.); -#130509 = ORIENTED_EDGE('',*,*,#130510,.T.); -#130510 = EDGE_CURVE('',#130310,#93009,#130511,.T.); -#130511 = SURFACE_CURVE('',#130512,(#130516,#130523),.PCURVE_S1.); -#130512 = LINE('',#130513,#130514); -#130513 = CARTESIAN_POINT('',(10.527847992439,4.15,0.75)); -#130514 = VECTOR('',#130515,1.); -#130515 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#130516 = PCURVE('',#93024,#130517); -#130517 = DEFINITIONAL_REPRESENTATION('',(#130518),#130522); -#130518 = LINE('',#130519,#130520); -#130519 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#130520 = VECTOR('',#130521,1.); -#130521 = DIRECTION('',(-3.563627120235E-016,-1.)); -#130522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130523 = PCURVE('',#93050,#130524); -#130524 = DEFINITIONAL_REPRESENTATION('',(#130525),#130529); -#130525 = LINE('',#130526,#130527); -#130526 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#130527 = VECTOR('',#130528,1.); -#130528 = DIRECTION('',(-1.,-3.00059940766E-063)); -#130529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130530 = ORIENTED_EDGE('',*,*,#93008,.F.); -#130531 = ADVANCED_FACE('',(#130532),#93050,.T.); -#130532 = FACE_BOUND('',#130533,.T.); -#130533 = EDGE_LOOP('',(#130534,#130535,#130536,#130557)); -#130534 = ORIENTED_EDGE('',*,*,#130510,.F.); -#130535 = ORIENTED_EDGE('',*,*,#130309,.T.); -#130536 = ORIENTED_EDGE('',*,*,#130537,.T.); -#130537 = EDGE_CURVE('',#130287,#92951,#130538,.T.); -#130538 = SURFACE_CURVE('',#130539,(#130543,#130550),.PCURVE_S1.); -#130539 = LINE('',#130540,#130541); -#130540 = CARTESIAN_POINT('',(10.527847992439,4.35,0.75)); -#130541 = VECTOR('',#130542,1.); -#130542 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#130543 = PCURVE('',#93050,#130544); -#130544 = DEFINITIONAL_REPRESENTATION('',(#130545),#130549); -#130545 = LINE('',#130546,#130547); -#130546 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130547 = VECTOR('',#130548,1.); -#130548 = DIRECTION('',(-1.,-3.00059940766E-063)); -#130549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130550 = PCURVE('',#92968,#130551); -#130551 = DEFINITIONAL_REPRESENTATION('',(#130552),#130556); -#130552 = LINE('',#130553,#130554); -#130553 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#130554 = VECTOR('',#130555,1.); -#130555 = DIRECTION('',(3.563627120235E-016,-1.)); -#130556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130557 = ORIENTED_EDGE('',*,*,#93036,.F.); -#130558 = ADVANCED_FACE('',(#130559),#92968,.T.); -#130559 = FACE_BOUND('',#130560,.T.); -#130560 = EDGE_LOOP('',(#130561,#130562,#130563,#130564,#130565,#130566, - #130587,#130588,#130589,#130590,#130591,#130592)); -#130561 = ORIENTED_EDGE('',*,*,#130537,.F.); -#130562 = ORIENTED_EDGE('',*,*,#130286,.T.); -#130563 = ORIENTED_EDGE('',*,*,#130261,.T.); -#130564 = ORIENTED_EDGE('',*,*,#130027,.T.); -#130565 = ORIENTED_EDGE('',*,*,#129799,.T.); -#130566 = ORIENTED_EDGE('',*,*,#130567,.F.); -#130567 = EDGE_CURVE('',#129876,#129765,#130568,.T.); -#130568 = SURFACE_CURVE('',#130569,(#130573,#130580),.PCURVE_S1.); -#130569 = LINE('',#130570,#130571); -#130570 = CARTESIAN_POINT('',(11.,4.35,1.159810404338E-002)); -#130571 = VECTOR('',#130572,1.); -#130572 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#130573 = PCURVE('',#92968,#130574); -#130574 = DEFINITIONAL_REPRESENTATION('',(#130575),#130579); -#130575 = LINE('',#130576,#130577); -#130576 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#130577 = VECTOR('',#130578,1.); -#130578 = DIRECTION('',(1.,2.101748079665E-016)); -#130579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130580 = PCURVE('',#129787,#130581); -#130581 = DEFINITIONAL_REPRESENTATION('',(#130582),#130586); -#130582 = LINE('',#130583,#130584); -#130583 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#130584 = VECTOR('',#130585,1.); -#130585 = DIRECTION('',(1.194699204908E-017,1.)); -#130586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130587 = ORIENTED_EDGE('',*,*,#129953,.F.); -#130588 = ORIENTED_EDGE('',*,*,#130056,.F.); -#130589 = ORIENTED_EDGE('',*,*,#130164,.F.); -#130590 = ORIENTED_EDGE('',*,*,#130360,.F.); -#130591 = ORIENTED_EDGE('',*,*,#130433,.T.); -#130592 = ORIENTED_EDGE('',*,*,#92950,.F.); -#130593 = ADVANCED_FACE('',(#130594),#129787,.T.); -#130594 = FACE_BOUND('',#130595,.T.); -#130595 = EDGE_LOOP('',(#130596,#130597,#130598,#130599)); -#130596 = ORIENTED_EDGE('',*,*,#130485,.T.); -#130597 = ORIENTED_EDGE('',*,*,#129873,.T.); -#130598 = ORIENTED_EDGE('',*,*,#130567,.T.); -#130599 = ORIENTED_EDGE('',*,*,#129764,.T.); -#130600 = ADVANCED_FACE('',(#130601),#130615,.F.); -#130601 = FACE_BOUND('',#130602,.T.); -#130602 = EDGE_LOOP('',(#130603,#130638,#130661,#130688)); -#130603 = ORIENTED_EDGE('',*,*,#130604,.F.); -#130604 = EDGE_CURVE('',#130605,#130607,#130609,.T.); -#130605 = VERTEX_POINT('',#130606); -#130606 = CARTESIAN_POINT('',(11.,3.85,-0.208196358798)); -#130607 = VERTEX_POINT('',#130608); -#130608 = CARTESIAN_POINT('',(11.,3.65,-0.208196358798)); -#130609 = SURFACE_CURVE('',#130610,(#130614,#130626),.PCURVE_S1.); -#130610 = LINE('',#130611,#130612); -#130611 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#130612 = VECTOR('',#130613,1.); -#130613 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130614 = PCURVE('',#130615,#130620); -#130615 = PLANE('',#130616); -#130616 = AXIS2_PLACEMENT_3D('',#130617,#130618,#130619); -#130617 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#132949 = ORIENTED_EDGE('',*,*,#95428,.F.); +#132950 = ADVANCED_FACE('',(#132951),#95360,.T.); +#132951 = FACE_BOUND('',#132952,.T.); +#132952 = EDGE_LOOP('',(#132953,#132954,#132955,#132956,#132957,#132958, + #132979,#132980,#132981,#132982,#132983,#132984)); +#132953 = ORIENTED_EDGE('',*,*,#132929,.F.); +#132954 = ORIENTED_EDGE('',*,*,#132678,.T.); +#132955 = ORIENTED_EDGE('',*,*,#132653,.T.); +#132956 = ORIENTED_EDGE('',*,*,#132419,.T.); +#132957 = ORIENTED_EDGE('',*,*,#132191,.T.); +#132958 = ORIENTED_EDGE('',*,*,#132959,.F.); +#132959 = EDGE_CURVE('',#132268,#132157,#132960,.T.); +#132960 = SURFACE_CURVE('',#132961,(#132965,#132972),.PCURVE_S1.); +#132961 = LINE('',#132962,#132963); +#132962 = CARTESIAN_POINT('',(11.,4.35,1.159810404338E-002)); +#132963 = VECTOR('',#132964,1.); +#132964 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#132965 = PCURVE('',#95360,#132966); +#132966 = DEFINITIONAL_REPRESENTATION('',(#132967),#132971); +#132967 = LINE('',#132968,#132969); +#132968 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#132969 = VECTOR('',#132970,1.); +#132970 = DIRECTION('',(1.,2.101748079665E-016)); +#132971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132972 = PCURVE('',#132179,#132973); +#132973 = DEFINITIONAL_REPRESENTATION('',(#132974),#132978); +#132974 = LINE('',#132975,#132976); +#132975 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#132976 = VECTOR('',#132977,1.); +#132977 = DIRECTION('',(1.194699204908E-017,1.)); +#132978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#132979 = ORIENTED_EDGE('',*,*,#132345,.F.); +#132980 = ORIENTED_EDGE('',*,*,#132448,.F.); +#132981 = ORIENTED_EDGE('',*,*,#132556,.F.); +#132982 = ORIENTED_EDGE('',*,*,#132752,.F.); +#132983 = ORIENTED_EDGE('',*,*,#132825,.T.); +#132984 = ORIENTED_EDGE('',*,*,#95342,.F.); +#132985 = ADVANCED_FACE('',(#132986),#132179,.T.); +#132986 = FACE_BOUND('',#132987,.T.); +#132987 = EDGE_LOOP('',(#132988,#132989,#132990,#132991)); +#132988 = ORIENTED_EDGE('',*,*,#132877,.T.); +#132989 = ORIENTED_EDGE('',*,*,#132265,.T.); +#132990 = ORIENTED_EDGE('',*,*,#132959,.T.); +#132991 = ORIENTED_EDGE('',*,*,#132156,.T.); +#132992 = ADVANCED_FACE('',(#132993),#133007,.F.); +#132993 = FACE_BOUND('',#132994,.T.); +#132994 = EDGE_LOOP('',(#132995,#133030,#133053,#133080)); +#132995 = ORIENTED_EDGE('',*,*,#132996,.F.); +#132996 = EDGE_CURVE('',#132997,#132999,#133001,.T.); +#132997 = VERTEX_POINT('',#132998); +#132998 = CARTESIAN_POINT('',(11.,3.85,-0.208196358798)); +#132999 = VERTEX_POINT('',#133000); +#133000 = CARTESIAN_POINT('',(11.,3.65,-0.208196358798)); +#133001 = SURFACE_CURVE('',#133002,(#133006,#133018),.PCURVE_S1.); +#133002 = LINE('',#133003,#133004); +#133003 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#133004 = VECTOR('',#133005,1.); +#133005 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133006 = PCURVE('',#133007,#133012); +#133007 = PLANE('',#133008); +#133008 = AXIS2_PLACEMENT_3D('',#133009,#133010,#133011); +#133009 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#130618 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#130619 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#130620 = DEFINITIONAL_REPRESENTATION('',(#130621),#130625); -#130621 = LINE('',#130622,#130623); -#130622 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#130623 = VECTOR('',#130624,1.); -#130624 = DIRECTION('',(4.440892098501E-016,-1.)); -#130625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130626 = PCURVE('',#130627,#130632); -#130627 = PLANE('',#130628); -#130628 = AXIS2_PLACEMENT_3D('',#130629,#130630,#130631); -#130629 = CARTESIAN_POINT('',(11.,3.75,-0.258196742327)); -#130630 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#130631 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130632 = DEFINITIONAL_REPRESENTATION('',(#130633),#130637); -#130633 = LINE('',#130634,#130635); -#130634 = CARTESIAN_POINT('',(-3.75,5.000038352949E-002)); -#130635 = VECTOR('',#130636,1.); -#130636 = DIRECTION('',(-1.,0.E+000)); -#130637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130638 = ORIENTED_EDGE('',*,*,#130639,.F.); -#130639 = EDGE_CURVE('',#130640,#130605,#130642,.T.); -#130640 = VERTEX_POINT('',#130641); -#130641 = CARTESIAN_POINT('',(10.740726081328,3.85,-0.208196358798)); -#130642 = SURFACE_CURVE('',#130643,(#130647,#130654),.PCURVE_S1.); -#130643 = LINE('',#130644,#130645); -#130644 = CARTESIAN_POINT('',(10.740726081328,3.85,-0.208196358798)); -#130645 = VECTOR('',#130646,1.); -#130646 = DIRECTION('',(1.,0.E+000,0.E+000)); -#130647 = PCURVE('',#130615,#130648); -#130648 = DEFINITIONAL_REPRESENTATION('',(#130649),#130653); -#130649 = LINE('',#130650,#130651); -#130650 = CARTESIAN_POINT('',(-1.7763568394E-015,3.85)); -#130651 = VECTOR('',#130652,1.); -#130652 = DIRECTION('',(-1.,0.E+000)); -#130653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130654 = PCURVE('',#92854,#130655); -#130655 = DEFINITIONAL_REPRESENTATION('',(#130656),#130660); -#130656 = LINE('',#130657,#130658); -#130657 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#130658 = VECTOR('',#130659,1.); -#130659 = DIRECTION('',(0.E+000,1.)); -#130660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130661 = ORIENTED_EDGE('',*,*,#130662,.F.); -#130662 = EDGE_CURVE('',#130663,#130640,#130665,.T.); -#130663 = VERTEX_POINT('',#130664); -#130664 = CARTESIAN_POINT('',(10.740726081328,3.65,-0.208196358798)); -#130665 = SURFACE_CURVE('',#130666,(#130670,#130677),.PCURVE_S1.); -#130666 = LINE('',#130667,#130668); -#130667 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#133010 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133011 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#133012 = DEFINITIONAL_REPRESENTATION('',(#133013),#133017); +#133013 = LINE('',#133014,#133015); +#133014 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#133015 = VECTOR('',#133016,1.); +#133016 = DIRECTION('',(4.440892098501E-016,-1.)); +#133017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133018 = PCURVE('',#133019,#133024); +#133019 = PLANE('',#133020); +#133020 = AXIS2_PLACEMENT_3D('',#133021,#133022,#133023); +#133021 = CARTESIAN_POINT('',(11.,3.75,-0.258196742327)); +#133022 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#133023 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133024 = DEFINITIONAL_REPRESENTATION('',(#133025),#133029); +#133025 = LINE('',#133026,#133027); +#133026 = CARTESIAN_POINT('',(-3.75,5.000038352949E-002)); +#133027 = VECTOR('',#133028,1.); +#133028 = DIRECTION('',(-1.,0.E+000)); +#133029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133030 = ORIENTED_EDGE('',*,*,#133031,.F.); +#133031 = EDGE_CURVE('',#133032,#132997,#133034,.T.); +#133032 = VERTEX_POINT('',#133033); +#133033 = CARTESIAN_POINT('',(10.740726081328,3.85,-0.208196358798)); +#133034 = SURFACE_CURVE('',#133035,(#133039,#133046),.PCURVE_S1.); +#133035 = LINE('',#133036,#133037); +#133036 = CARTESIAN_POINT('',(10.740726081328,3.85,-0.208196358798)); +#133037 = VECTOR('',#133038,1.); +#133038 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133039 = PCURVE('',#133007,#133040); +#133040 = DEFINITIONAL_REPRESENTATION('',(#133041),#133045); +#133041 = LINE('',#133042,#133043); +#133042 = CARTESIAN_POINT('',(-1.7763568394E-015,3.85)); +#133043 = VECTOR('',#133044,1.); +#133044 = DIRECTION('',(-1.,0.E+000)); +#133045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133046 = PCURVE('',#95246,#133047); +#133047 = DEFINITIONAL_REPRESENTATION('',(#133048),#133052); +#133048 = LINE('',#133049,#133050); +#133049 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#133050 = VECTOR('',#133051,1.); +#133051 = DIRECTION('',(0.E+000,1.)); +#133052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133053 = ORIENTED_EDGE('',*,*,#133054,.F.); +#133054 = EDGE_CURVE('',#133055,#133032,#133057,.T.); +#133055 = VERTEX_POINT('',#133056); +#133056 = CARTESIAN_POINT('',(10.740726081328,3.65,-0.208196358798)); +#133057 = SURFACE_CURVE('',#133058,(#133062,#133069),.PCURVE_S1.); +#133058 = LINE('',#133059,#133060); +#133059 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#130668 = VECTOR('',#130669,1.); -#130669 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130670 = PCURVE('',#130615,#130671); -#130671 = DEFINITIONAL_REPRESENTATION('',(#130672),#130676); -#130672 = LINE('',#130673,#130674); -#130673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130674 = VECTOR('',#130675,1.); -#130675 = DIRECTION('',(-4.440892098501E-016,1.)); -#130676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130677 = PCURVE('',#130678,#130683); -#130678 = CYLINDRICAL_SURFACE('',#130679,0.208574704164); -#130679 = AXIS2_PLACEMENT_3D('',#130680,#130681,#130682); -#130680 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#133060 = VECTOR('',#133061,1.); +#133061 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133062 = PCURVE('',#133007,#133063); +#133063 = DEFINITIONAL_REPRESENTATION('',(#133064),#133068); +#133064 = LINE('',#133065,#133066); +#133065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133066 = VECTOR('',#133067,1.); +#133067 = DIRECTION('',(-4.440892098501E-016,1.)); +#133068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133069 = PCURVE('',#133070,#133075); +#133070 = CYLINDRICAL_SURFACE('',#133071,0.208574704164); +#133071 = AXIS2_PLACEMENT_3D('',#133072,#133073,#133074); +#133072 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#130681 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130682 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130683 = DEFINITIONAL_REPRESENTATION('',(#130684),#130687); -#130684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130685,#130686), +#133073 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133074 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133075 = DEFINITIONAL_REPRESENTATION('',(#133076),#133079); +#133076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133077,#133078), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#130685 = CARTESIAN_POINT('',(4.772630242227,-3.65)); -#130686 = CARTESIAN_POINT('',(4.772630242227,-3.85)); -#130687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130688 = ORIENTED_EDGE('',*,*,#130689,.T.); -#130689 = EDGE_CURVE('',#130663,#130607,#130690,.T.); -#130690 = SURFACE_CURVE('',#130691,(#130695,#130702),.PCURVE_S1.); -#130691 = LINE('',#130692,#130693); -#130692 = CARTESIAN_POINT('',(10.740726081328,3.65,-0.208196358798)); -#130693 = VECTOR('',#130694,1.); -#130694 = DIRECTION('',(1.,0.E+000,0.E+000)); -#130695 = PCURVE('',#130615,#130696); -#130696 = DEFINITIONAL_REPRESENTATION('',(#130697),#130701); -#130697 = LINE('',#130698,#130699); -#130698 = CARTESIAN_POINT('',(-1.7763568394E-015,3.65)); -#130699 = VECTOR('',#130700,1.); -#130700 = DIRECTION('',(-1.,0.E+000)); -#130701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130702 = PCURVE('',#92910,#130703); -#130703 = DEFINITIONAL_REPRESENTATION('',(#130704),#130708); -#130704 = LINE('',#130705,#130706); -#130705 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#130706 = VECTOR('',#130707,1.); -#130707 = DIRECTION('',(0.E+000,1.)); -#130708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130709 = ADVANCED_FACE('',(#130710),#130724,.F.); -#130710 = FACE_BOUND('',#130711,.T.); -#130711 = EDGE_LOOP('',(#130712,#130742,#130765,#130792)); -#130712 = ORIENTED_EDGE('',*,*,#130713,.F.); -#130713 = EDGE_CURVE('',#130714,#130716,#130718,.T.); -#130714 = VERTEX_POINT('',#130715); -#130715 = CARTESIAN_POINT('',(11.,3.65,-0.308197125857)); -#130716 = VERTEX_POINT('',#130717); -#130717 = CARTESIAN_POINT('',(11.,3.85,-0.308197125857)); -#130718 = SURFACE_CURVE('',#130719,(#130723,#130735),.PCURVE_S1.); -#130719 = LINE('',#130720,#130721); -#130720 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#130721 = VECTOR('',#130722,1.); -#130722 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130723 = PCURVE('',#130724,#130729); -#130724 = PLANE('',#130725); -#130725 = AXIS2_PLACEMENT_3D('',#130726,#130727,#130728); -#130726 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#133077 = CARTESIAN_POINT('',(4.772630242227,-3.65)); +#133078 = CARTESIAN_POINT('',(4.772630242227,-3.85)); +#133079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133080 = ORIENTED_EDGE('',*,*,#133081,.T.); +#133081 = EDGE_CURVE('',#133055,#132999,#133082,.T.); +#133082 = SURFACE_CURVE('',#133083,(#133087,#133094),.PCURVE_S1.); +#133083 = LINE('',#133084,#133085); +#133084 = CARTESIAN_POINT('',(10.740726081328,3.65,-0.208196358798)); +#133085 = VECTOR('',#133086,1.); +#133086 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133087 = PCURVE('',#133007,#133088); +#133088 = DEFINITIONAL_REPRESENTATION('',(#133089),#133093); +#133089 = LINE('',#133090,#133091); +#133090 = CARTESIAN_POINT('',(-1.7763568394E-015,3.65)); +#133091 = VECTOR('',#133092,1.); +#133092 = DIRECTION('',(-1.,0.E+000)); +#133093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133094 = PCURVE('',#95302,#133095); +#133095 = DEFINITIONAL_REPRESENTATION('',(#133096),#133100); +#133096 = LINE('',#133097,#133098); +#133097 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#133098 = VECTOR('',#133099,1.); +#133099 = DIRECTION('',(0.E+000,1.)); +#133100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133101 = ADVANCED_FACE('',(#133102),#133116,.F.); +#133102 = FACE_BOUND('',#133103,.T.); +#133103 = EDGE_LOOP('',(#133104,#133134,#133157,#133184)); +#133104 = ORIENTED_EDGE('',*,*,#133105,.F.); +#133105 = EDGE_CURVE('',#133106,#133108,#133110,.T.); +#133106 = VERTEX_POINT('',#133107); +#133107 = CARTESIAN_POINT('',(11.,3.65,-0.308197125857)); +#133108 = VERTEX_POINT('',#133109); +#133109 = CARTESIAN_POINT('',(11.,3.85,-0.308197125857)); +#133110 = SURFACE_CURVE('',#133111,(#133115,#133127),.PCURVE_S1.); +#133111 = LINE('',#133112,#133113); +#133112 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#133113 = VECTOR('',#133114,1.); +#133114 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133115 = PCURVE('',#133116,#133121); +#133116 = PLANE('',#133117); +#133117 = AXIS2_PLACEMENT_3D('',#133118,#133119,#133120); +#133118 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#130727 = DIRECTION('',(0.E+000,0.E+000,1.)); -#130728 = DIRECTION('',(1.,0.E+000,0.E+000)); -#130729 = DEFINITIONAL_REPRESENTATION('',(#130730),#130734); -#130730 = LINE('',#130731,#130732); -#130731 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#130732 = VECTOR('',#130733,1.); -#130733 = DIRECTION('',(4.440892098501E-016,1.)); -#130734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130735 = PCURVE('',#130627,#130736); -#130736 = DEFINITIONAL_REPRESENTATION('',(#130737),#130741); -#130737 = LINE('',#130738,#130739); -#130738 = CARTESIAN_POINT('',(-3.75,-5.000038352949E-002)); -#130739 = VECTOR('',#130740,1.); -#130740 = DIRECTION('',(1.,0.E+000)); -#130741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130742 = ORIENTED_EDGE('',*,*,#130743,.F.); -#130743 = EDGE_CURVE('',#130744,#130714,#130746,.T.); -#130744 = VERTEX_POINT('',#130745); -#130745 = CARTESIAN_POINT('',(10.74341632541,3.65,-0.308197125857)); -#130746 = SURFACE_CURVE('',#130747,(#130751,#130758),.PCURVE_S1.); -#130747 = LINE('',#130748,#130749); -#130748 = CARTESIAN_POINT('',(10.74341632541,3.65,-0.308197125857)); -#130749 = VECTOR('',#130750,1.); -#130750 = DIRECTION('',(1.,0.E+000,0.E+000)); -#130751 = PCURVE('',#130724,#130752); -#130752 = DEFINITIONAL_REPRESENTATION('',(#130753),#130757); -#130753 = LINE('',#130754,#130755); -#130754 = CARTESIAN_POINT('',(1.7763568394E-015,3.65)); -#130755 = VECTOR('',#130756,1.); -#130756 = DIRECTION('',(1.,0.E+000)); -#130757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130758 = PCURVE('',#92910,#130759); -#130759 = DEFINITIONAL_REPRESENTATION('',(#130760),#130764); -#130760 = LINE('',#130761,#130762); -#130761 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#130762 = VECTOR('',#130763,1.); -#130763 = DIRECTION('',(0.E+000,1.)); -#130764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130765 = ORIENTED_EDGE('',*,*,#130766,.F.); -#130766 = EDGE_CURVE('',#130767,#130744,#130769,.T.); -#130767 = VERTEX_POINT('',#130768); -#130768 = CARTESIAN_POINT('',(10.74341632541,3.85,-0.308197125857)); -#130769 = SURFACE_CURVE('',#130770,(#130774,#130781),.PCURVE_S1.); -#130770 = LINE('',#130771,#130772); -#130771 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#133119 = DIRECTION('',(0.E+000,0.E+000,1.)); +#133120 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133121 = DEFINITIONAL_REPRESENTATION('',(#133122),#133126); +#133122 = LINE('',#133123,#133124); +#133123 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#133124 = VECTOR('',#133125,1.); +#133125 = DIRECTION('',(4.440892098501E-016,1.)); +#133126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133127 = PCURVE('',#133019,#133128); +#133128 = DEFINITIONAL_REPRESENTATION('',(#133129),#133133); +#133129 = LINE('',#133130,#133131); +#133130 = CARTESIAN_POINT('',(-3.75,-5.000038352949E-002)); +#133131 = VECTOR('',#133132,1.); +#133132 = DIRECTION('',(1.,0.E+000)); +#133133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133134 = ORIENTED_EDGE('',*,*,#133135,.F.); +#133135 = EDGE_CURVE('',#133136,#133106,#133138,.T.); +#133136 = VERTEX_POINT('',#133137); +#133137 = CARTESIAN_POINT('',(10.74341632541,3.65,-0.308197125857)); +#133138 = SURFACE_CURVE('',#133139,(#133143,#133150),.PCURVE_S1.); +#133139 = LINE('',#133140,#133141); +#133140 = CARTESIAN_POINT('',(10.74341632541,3.65,-0.308197125857)); +#133141 = VECTOR('',#133142,1.); +#133142 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133143 = PCURVE('',#133116,#133144); +#133144 = DEFINITIONAL_REPRESENTATION('',(#133145),#133149); +#133145 = LINE('',#133146,#133147); +#133146 = CARTESIAN_POINT('',(1.7763568394E-015,3.65)); +#133147 = VECTOR('',#133148,1.); +#133148 = DIRECTION('',(1.,0.E+000)); +#133149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133150 = PCURVE('',#95302,#133151); +#133151 = DEFINITIONAL_REPRESENTATION('',(#133152),#133156); +#133152 = LINE('',#133153,#133154); +#133153 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#133154 = VECTOR('',#133155,1.); +#133155 = DIRECTION('',(0.E+000,1.)); +#133156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133157 = ORIENTED_EDGE('',*,*,#133158,.F.); +#133158 = EDGE_CURVE('',#133159,#133136,#133161,.T.); +#133159 = VERTEX_POINT('',#133160); +#133160 = CARTESIAN_POINT('',(10.74341632541,3.85,-0.308197125857)); +#133161 = SURFACE_CURVE('',#133162,(#133166,#133173),.PCURVE_S1.); +#133162 = LINE('',#133163,#133164); +#133163 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#130772 = VECTOR('',#130773,1.); -#130773 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130774 = PCURVE('',#130724,#130775); -#130775 = DEFINITIONAL_REPRESENTATION('',(#130776),#130780); -#130776 = LINE('',#130777,#130778); -#130777 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#130778 = VECTOR('',#130779,1.); -#130779 = DIRECTION('',(-4.440892098501E-016,-1.)); -#130780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130781 = PCURVE('',#130782,#130787); -#130782 = CYLINDRICAL_SURFACE('',#130783,0.308574064194); -#130783 = AXIS2_PLACEMENT_3D('',#130784,#130785,#130786); -#130784 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#133164 = VECTOR('',#133165,1.); +#133165 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133166 = PCURVE('',#133116,#133167); +#133167 = DEFINITIONAL_REPRESENTATION('',(#133168),#133172); +#133168 = LINE('',#133169,#133170); +#133169 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133170 = VECTOR('',#133171,1.); +#133171 = DIRECTION('',(-4.440892098501E-016,-1.)); +#133172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133173 = PCURVE('',#133174,#133179); +#133174 = CYLINDRICAL_SURFACE('',#133175,0.308574064194); +#133175 = AXIS2_PLACEMENT_3D('',#133176,#133177,#133178); +#133176 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#130785 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130786 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130787 = DEFINITIONAL_REPRESENTATION('',(#130788),#130791); -#130788 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130789,#130790), +#133177 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133178 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133179 = DEFINITIONAL_REPRESENTATION('',(#133180),#133183); +#133180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133181,#133182), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#130789 = CARTESIAN_POINT('',(4.761821717947,-3.85)); -#130790 = CARTESIAN_POINT('',(4.761821717947,-3.65)); -#130791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130792 = ORIENTED_EDGE('',*,*,#130793,.T.); -#130793 = EDGE_CURVE('',#130767,#130716,#130794,.T.); -#130794 = SURFACE_CURVE('',#130795,(#130799,#130806),.PCURVE_S1.); -#130795 = LINE('',#130796,#130797); -#130796 = CARTESIAN_POINT('',(10.74341632541,3.85,-0.308197125857)); -#130797 = VECTOR('',#130798,1.); -#130798 = DIRECTION('',(1.,0.E+000,0.E+000)); -#130799 = PCURVE('',#130724,#130800); -#130800 = DEFINITIONAL_REPRESENTATION('',(#130801),#130805); -#130801 = LINE('',#130802,#130803); -#130802 = CARTESIAN_POINT('',(1.7763568394E-015,3.85)); -#130803 = VECTOR('',#130804,1.); -#130804 = DIRECTION('',(1.,0.E+000)); -#130805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130806 = PCURVE('',#92854,#130807); -#130807 = DEFINITIONAL_REPRESENTATION('',(#130808),#130812); -#130808 = LINE('',#130809,#130810); -#130809 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#130810 = VECTOR('',#130811,1.); -#130811 = DIRECTION('',(0.E+000,1.)); -#130812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130813 = ADVANCED_FACE('',(#130814),#130678,.F.); -#130814 = FACE_BOUND('',#130815,.F.); -#130815 = EDGE_LOOP('',(#130816,#130839,#130866,#130891)); -#130816 = ORIENTED_EDGE('',*,*,#130817,.F.); -#130817 = EDGE_CURVE('',#130818,#130663,#130820,.T.); -#130818 = VERTEX_POINT('',#130819); -#130819 = CARTESIAN_POINT('',(10.51959417205,3.65,0.E+000)); -#130820 = SURFACE_CURVE('',#130821,(#130826,#130832),.PCURVE_S1.); -#130821 = CIRCLE('',#130822,0.208574704164); -#130822 = AXIS2_PLACEMENT_3D('',#130823,#130824,#130825); -#130823 = CARTESIAN_POINT('',(10.728168876214,3.65,2.640924866458E-017) - ); -#130824 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130825 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130826 = PCURVE('',#130678,#130827); -#130827 = DEFINITIONAL_REPRESENTATION('',(#130828),#130831); -#130828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130829,#130830), +#133181 = CARTESIAN_POINT('',(4.761821717947,-3.85)); +#133182 = CARTESIAN_POINT('',(4.761821717947,-3.65)); +#133183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133184 = ORIENTED_EDGE('',*,*,#133185,.T.); +#133185 = EDGE_CURVE('',#133159,#133108,#133186,.T.); +#133186 = SURFACE_CURVE('',#133187,(#133191,#133198),.PCURVE_S1.); +#133187 = LINE('',#133188,#133189); +#133188 = CARTESIAN_POINT('',(10.74341632541,3.85,-0.308197125857)); +#133189 = VECTOR('',#133190,1.); +#133190 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133191 = PCURVE('',#133116,#133192); +#133192 = DEFINITIONAL_REPRESENTATION('',(#133193),#133197); +#133193 = LINE('',#133194,#133195); +#133194 = CARTESIAN_POINT('',(1.7763568394E-015,3.85)); +#133195 = VECTOR('',#133196,1.); +#133196 = DIRECTION('',(1.,0.E+000)); +#133197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133198 = PCURVE('',#95246,#133199); +#133199 = DEFINITIONAL_REPRESENTATION('',(#133200),#133204); +#133200 = LINE('',#133201,#133202); +#133201 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#133202 = VECTOR('',#133203,1.); +#133203 = DIRECTION('',(0.E+000,1.)); +#133204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133205 = ADVANCED_FACE('',(#133206),#133070,.F.); +#133206 = FACE_BOUND('',#133207,.F.); +#133207 = EDGE_LOOP('',(#133208,#133231,#133258,#133283)); +#133208 = ORIENTED_EDGE('',*,*,#133209,.F.); +#133209 = EDGE_CURVE('',#133210,#133055,#133212,.T.); +#133210 = VERTEX_POINT('',#133211); +#133211 = CARTESIAN_POINT('',(10.51959417205,3.65,0.E+000)); +#133212 = SURFACE_CURVE('',#133213,(#133218,#133224),.PCURVE_S1.); +#133213 = CIRCLE('',#133214,0.208574704164); +#133214 = AXIS2_PLACEMENT_3D('',#133215,#133216,#133217); +#133215 = CARTESIAN_POINT('',(10.728168876214,3.65,2.640924866458E-017) + ); +#133216 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133217 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133218 = PCURVE('',#133070,#133219); +#133219 = DEFINITIONAL_REPRESENTATION('',(#133220),#133223); +#133220 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133221,#133222), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#130829 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#130830 = CARTESIAN_POINT('',(4.772630242227,-3.65)); -#130831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133221 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#133222 = CARTESIAN_POINT('',(4.772630242227,-3.65)); +#133223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130832 = PCURVE('',#92910,#130833); -#130833 = DEFINITIONAL_REPRESENTATION('',(#130834),#130838); -#130834 = CIRCLE('',#130835,0.208574704164); -#130835 = AXIS2_PLACEMENT_2D('',#130836,#130837); -#130836 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#130837 = DIRECTION('',(0.E+000,1.)); -#130838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133224 = PCURVE('',#95302,#133225); +#133225 = DEFINITIONAL_REPRESENTATION('',(#133226),#133230); +#133226 = CIRCLE('',#133227,0.208574704164); +#133227 = AXIS2_PLACEMENT_2D('',#133228,#133229); +#133228 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#133229 = DIRECTION('',(0.E+000,1.)); +#133230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130839 = ORIENTED_EDGE('',*,*,#130840,.F.); -#130840 = EDGE_CURVE('',#130841,#130818,#130843,.T.); -#130841 = VERTEX_POINT('',#130842); -#130842 = CARTESIAN_POINT('',(10.51959417205,3.85,0.E+000)); -#130843 = SURFACE_CURVE('',#130844,(#130848,#130854),.PCURVE_S1.); -#130844 = LINE('',#130845,#130846); -#130845 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#133231 = ORIENTED_EDGE('',*,*,#133232,.F.); +#133232 = EDGE_CURVE('',#133233,#133210,#133235,.T.); +#133233 = VERTEX_POINT('',#133234); +#133234 = CARTESIAN_POINT('',(10.51959417205,3.85,0.E+000)); +#133235 = SURFACE_CURVE('',#133236,(#133240,#133246),.PCURVE_S1.); +#133236 = LINE('',#133237,#133238); +#133237 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#130846 = VECTOR('',#130847,1.); -#130847 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130848 = PCURVE('',#130678,#130849); -#130849 = DEFINITIONAL_REPRESENTATION('',(#130850),#130853); -#130850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130851,#130852), +#133238 = VECTOR('',#133239,1.); +#133239 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133240 = PCURVE('',#133070,#133241); +#133241 = DEFINITIONAL_REPRESENTATION('',(#133242),#133245); +#133242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133243,#133244), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#130851 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#130852 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#130853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133243 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#133244 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#133245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130854 = PCURVE('',#130855,#130860); -#130855 = PLANE('',#130856); -#130856 = AXIS2_PLACEMENT_3D('',#130857,#130858,#130859); -#130857 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#133246 = PCURVE('',#133247,#133252); +#133247 = PLANE('',#133248); +#133248 = AXIS2_PLACEMENT_3D('',#133249,#133250,#133251); +#133249 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#130858 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130859 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130860 = DEFINITIONAL_REPRESENTATION('',(#130861),#130865); -#130861 = LINE('',#130862,#130863); -#130862 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#130863 = VECTOR('',#130864,1.); -#130864 = DIRECTION('',(-1.,0.E+000)); -#130865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130866 = ORIENTED_EDGE('',*,*,#130867,.T.); -#130867 = EDGE_CURVE('',#130841,#130640,#130868,.T.); -#130868 = SURFACE_CURVE('',#130869,(#130874,#130880),.PCURVE_S1.); -#130869 = CIRCLE('',#130870,0.208574704164); -#130870 = AXIS2_PLACEMENT_3D('',#130871,#130872,#130873); -#130871 = CARTESIAN_POINT('',(10.728168876214,3.85,2.640924866458E-017) - ); -#130872 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130873 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130874 = PCURVE('',#130678,#130875); -#130875 = DEFINITIONAL_REPRESENTATION('',(#130876),#130879); -#130876 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#130877,#130878), +#133250 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133251 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133252 = DEFINITIONAL_REPRESENTATION('',(#133253),#133257); +#133253 = LINE('',#133254,#133255); +#133254 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#133255 = VECTOR('',#133256,1.); +#133256 = DIRECTION('',(-1.,0.E+000)); +#133257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133258 = ORIENTED_EDGE('',*,*,#133259,.T.); +#133259 = EDGE_CURVE('',#133233,#133032,#133260,.T.); +#133260 = SURFACE_CURVE('',#133261,(#133266,#133272),.PCURVE_S1.); +#133261 = CIRCLE('',#133262,0.208574704164); +#133262 = AXIS2_PLACEMENT_3D('',#133263,#133264,#133265); +#133263 = CARTESIAN_POINT('',(10.728168876214,3.85,2.640924866458E-017) + ); +#133264 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133265 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133266 = PCURVE('',#133070,#133267); +#133267 = DEFINITIONAL_REPRESENTATION('',(#133268),#133271); +#133268 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133269,#133270), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#130877 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#130878 = CARTESIAN_POINT('',(4.772630242227,-3.85)); -#130879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133269 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#133270 = CARTESIAN_POINT('',(4.772630242227,-3.85)); +#133271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#130880 = PCURVE('',#92854,#130881); -#130881 = DEFINITIONAL_REPRESENTATION('',(#130882),#130890); -#130882 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130883,#130884,#130885, - #130886,#130887,#130888,#130889),.UNSPECIFIED.,.T.,.F.) +#133272 = PCURVE('',#95246,#133273); +#133273 = DEFINITIONAL_REPRESENTATION('',(#133274),#133282); +#133274 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133275,#133276,#133277, + #133278,#133279,#133280,#133281),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130883 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#130884 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#130885 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#130886 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#130887 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#130888 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#130889 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#130890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130891 = ORIENTED_EDGE('',*,*,#130662,.F.); -#130892 = ADVANCED_FACE('',(#130893),#130782,.T.); -#130893 = FACE_BOUND('',#130894,.T.); -#130894 = EDGE_LOOP('',(#130895,#130945,#130946,#130992)); -#130895 = ORIENTED_EDGE('',*,*,#130896,.T.); -#130896 = EDGE_CURVE('',#130897,#130767,#130899,.T.); -#130897 = VERTEX_POINT('',#130898); -#130898 = CARTESIAN_POINT('',(10.419594812019,3.85,0.E+000)); -#130899 = SURFACE_CURVE('',#130900,(#130905,#130934),.PCURVE_S1.); -#130900 = CIRCLE('',#130901,0.308574064194); -#130901 = AXIS2_PLACEMENT_3D('',#130902,#130903,#130904); -#130902 = CARTESIAN_POINT('',(10.728168876214,3.85,2.640924866458E-017) - ); -#130903 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130904 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130905 = PCURVE('',#130782,#130906); -#130906 = DEFINITIONAL_REPRESENTATION('',(#130907),#130933); -#130907 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#130908,#130909,#130910, - #130911,#130912,#130913,#130914,#130915,#130916,#130917,#130918, - #130919,#130920,#130921,#130922,#130923,#130924,#130925,#130926, - #130927,#130928,#130929,#130930,#130931,#130932),.UNSPECIFIED.,.F., +#133275 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#133276 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#133277 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#133278 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#133279 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#133280 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#133281 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#133282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133283 = ORIENTED_EDGE('',*,*,#133054,.F.); +#133284 = ADVANCED_FACE('',(#133285),#133174,.T.); +#133285 = FACE_BOUND('',#133286,.T.); +#133286 = EDGE_LOOP('',(#133287,#133337,#133338,#133384)); +#133287 = ORIENTED_EDGE('',*,*,#133288,.T.); +#133288 = EDGE_CURVE('',#133289,#133159,#133291,.T.); +#133289 = VERTEX_POINT('',#133290); +#133290 = CARTESIAN_POINT('',(10.419594812019,3.85,0.E+000)); +#133291 = SURFACE_CURVE('',#133292,(#133297,#133326),.PCURVE_S1.); +#133292 = CIRCLE('',#133293,0.308574064194); +#133293 = AXIS2_PLACEMENT_3D('',#133294,#133295,#133296); +#133294 = CARTESIAN_POINT('',(10.728168876214,3.85,2.640924866458E-017) + ); +#133295 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133296 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133297 = PCURVE('',#133174,#133298); +#133298 = DEFINITIONAL_REPRESENTATION('',(#133299),#133325); +#133299 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133300,#133301,#133302, + #133303,#133304,#133305,#133306,#133307,#133308,#133309,#133310, + #133311,#133312,#133313,#133314,#133315,#133316,#133317,#133318, + #133319,#133320,#133321,#133322,#133323,#133324),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -161268,71 +164270,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#130908 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#130909 = CARTESIAN_POINT('',(3.166141578807,-3.85)); -#130910 = CARTESIAN_POINT('',(3.215239429242,-3.85)); -#130911 = CARTESIAN_POINT('',(3.288886204895,-3.85)); -#130912 = CARTESIAN_POINT('',(3.362532980548,-3.85)); -#130913 = CARTESIAN_POINT('',(3.4361797562,-3.85)); -#130914 = CARTESIAN_POINT('',(3.509826531853,-3.85)); -#130915 = CARTESIAN_POINT('',(3.583473307505,-3.85)); -#130916 = CARTESIAN_POINT('',(3.657120083158,-3.85)); -#130917 = CARTESIAN_POINT('',(3.730766858811,-3.85)); -#130918 = CARTESIAN_POINT('',(3.804413634463,-3.85)); -#130919 = CARTESIAN_POINT('',(3.878060410116,-3.85)); -#130920 = CARTESIAN_POINT('',(3.951707185768,-3.85)); -#130921 = CARTESIAN_POINT('',(4.025353961421,-3.85)); -#130922 = CARTESIAN_POINT('',(4.099000737074,-3.85)); -#130923 = CARTESIAN_POINT('',(4.172647512726,-3.85)); -#130924 = CARTESIAN_POINT('',(4.246294288379,-3.85)); -#130925 = CARTESIAN_POINT('',(4.319941064031,-3.85)); -#130926 = CARTESIAN_POINT('',(4.393587839684,-3.85)); -#130927 = CARTESIAN_POINT('',(4.467234615337,-3.85)); -#130928 = CARTESIAN_POINT('',(4.540881390989,-3.85)); -#130929 = CARTESIAN_POINT('',(4.614528166642,-3.85)); -#130930 = CARTESIAN_POINT('',(4.688174942294,-3.85)); -#130931 = CARTESIAN_POINT('',(4.737272792729,-3.85)); -#130932 = CARTESIAN_POINT('',(4.761821717947,-3.85)); -#130933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130934 = PCURVE('',#92854,#130935); -#130935 = DEFINITIONAL_REPRESENTATION('',(#130936),#130944); -#130936 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#130937,#130938,#130939, - #130940,#130941,#130942,#130943),.UNSPECIFIED.,.T.,.F.) +#133300 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#133301 = CARTESIAN_POINT('',(3.166141578807,-3.85)); +#133302 = CARTESIAN_POINT('',(3.215239429242,-3.85)); +#133303 = CARTESIAN_POINT('',(3.288886204895,-3.85)); +#133304 = CARTESIAN_POINT('',(3.362532980548,-3.85)); +#133305 = CARTESIAN_POINT('',(3.4361797562,-3.85)); +#133306 = CARTESIAN_POINT('',(3.509826531853,-3.85)); +#133307 = CARTESIAN_POINT('',(3.583473307505,-3.85)); +#133308 = CARTESIAN_POINT('',(3.657120083158,-3.85)); +#133309 = CARTESIAN_POINT('',(3.730766858811,-3.85)); +#133310 = CARTESIAN_POINT('',(3.804413634463,-3.85)); +#133311 = CARTESIAN_POINT('',(3.878060410116,-3.85)); +#133312 = CARTESIAN_POINT('',(3.951707185768,-3.85)); +#133313 = CARTESIAN_POINT('',(4.025353961421,-3.85)); +#133314 = CARTESIAN_POINT('',(4.099000737074,-3.85)); +#133315 = CARTESIAN_POINT('',(4.172647512726,-3.85)); +#133316 = CARTESIAN_POINT('',(4.246294288379,-3.85)); +#133317 = CARTESIAN_POINT('',(4.319941064031,-3.85)); +#133318 = CARTESIAN_POINT('',(4.393587839684,-3.85)); +#133319 = CARTESIAN_POINT('',(4.467234615337,-3.85)); +#133320 = CARTESIAN_POINT('',(4.540881390989,-3.85)); +#133321 = CARTESIAN_POINT('',(4.614528166642,-3.85)); +#133322 = CARTESIAN_POINT('',(4.688174942294,-3.85)); +#133323 = CARTESIAN_POINT('',(4.737272792729,-3.85)); +#133324 = CARTESIAN_POINT('',(4.761821717947,-3.85)); +#133325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133326 = PCURVE('',#95246,#133327); +#133327 = DEFINITIONAL_REPRESENTATION('',(#133328),#133336); +#133328 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133329,#133330,#133331, + #133332,#133333,#133334,#133335),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#130937 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#130938 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#130939 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#130940 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#130941 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#130942 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#130943 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#130944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130945 = ORIENTED_EDGE('',*,*,#130766,.T.); -#130946 = ORIENTED_EDGE('',*,*,#130947,.F.); -#130947 = EDGE_CURVE('',#130948,#130744,#130950,.T.); -#130948 = VERTEX_POINT('',#130949); -#130949 = CARTESIAN_POINT('',(10.419594812019,3.65,0.E+000)); -#130950 = SURFACE_CURVE('',#130951,(#130956,#130985),.PCURVE_S1.); -#130951 = CIRCLE('',#130952,0.308574064194); -#130952 = AXIS2_PLACEMENT_3D('',#130953,#130954,#130955); -#130953 = CARTESIAN_POINT('',(10.728168876214,3.65,2.640924866458E-017) - ); -#130954 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#130955 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#130956 = PCURVE('',#130782,#130957); -#130957 = DEFINITIONAL_REPRESENTATION('',(#130958),#130984); -#130958 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#130959,#130960,#130961, - #130962,#130963,#130964,#130965,#130966,#130967,#130968,#130969, - #130970,#130971,#130972,#130973,#130974,#130975,#130976,#130977, - #130978,#130979,#130980,#130981,#130982,#130983),.UNSPECIFIED.,.F., +#133329 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#133330 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#133331 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#133332 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#133333 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#133334 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#133335 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#133336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133337 = ORIENTED_EDGE('',*,*,#133158,.T.); +#133338 = ORIENTED_EDGE('',*,*,#133339,.F.); +#133339 = EDGE_CURVE('',#133340,#133136,#133342,.T.); +#133340 = VERTEX_POINT('',#133341); +#133341 = CARTESIAN_POINT('',(10.419594812019,3.65,0.E+000)); +#133342 = SURFACE_CURVE('',#133343,(#133348,#133377),.PCURVE_S1.); +#133343 = CIRCLE('',#133344,0.308574064194); +#133344 = AXIS2_PLACEMENT_3D('',#133345,#133346,#133347); +#133345 = CARTESIAN_POINT('',(10.728168876214,3.65,2.640924866458E-017) + ); +#133346 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133347 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#133348 = PCURVE('',#133174,#133349); +#133349 = DEFINITIONAL_REPRESENTATION('',(#133350),#133376); +#133350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133351,#133352,#133353, + #133354,#133355,#133356,#133357,#133358,#133359,#133360,#133361, + #133362,#133363,#133364,#133365,#133366,#133367,#133368,#133369, + #133370,#133371,#133372,#133373,#133374,#133375),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -161340,275 +164342,275 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#130959 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#130960 = CARTESIAN_POINT('',(3.166141578807,-3.65)); -#130961 = CARTESIAN_POINT('',(3.215239429242,-3.65)); -#130962 = CARTESIAN_POINT('',(3.288886204895,-3.65)); -#130963 = CARTESIAN_POINT('',(3.362532980548,-3.65)); -#130964 = CARTESIAN_POINT('',(3.4361797562,-3.65)); -#130965 = CARTESIAN_POINT('',(3.509826531853,-3.65)); -#130966 = CARTESIAN_POINT('',(3.583473307505,-3.65)); -#130967 = CARTESIAN_POINT('',(3.657120083158,-3.65)); -#130968 = CARTESIAN_POINT('',(3.730766858811,-3.65)); -#130969 = CARTESIAN_POINT('',(3.804413634463,-3.65)); -#130970 = CARTESIAN_POINT('',(3.878060410116,-3.65)); -#130971 = CARTESIAN_POINT('',(3.951707185768,-3.65)); -#130972 = CARTESIAN_POINT('',(4.025353961421,-3.65)); -#130973 = CARTESIAN_POINT('',(4.099000737074,-3.65)); -#130974 = CARTESIAN_POINT('',(4.172647512726,-3.65)); -#130975 = CARTESIAN_POINT('',(4.246294288379,-3.65)); -#130976 = CARTESIAN_POINT('',(4.319941064031,-3.65)); -#130977 = CARTESIAN_POINT('',(4.393587839684,-3.65)); -#130978 = CARTESIAN_POINT('',(4.467234615337,-3.65)); -#130979 = CARTESIAN_POINT('',(4.540881390989,-3.65)); -#130980 = CARTESIAN_POINT('',(4.614528166642,-3.65)); -#130981 = CARTESIAN_POINT('',(4.688174942294,-3.65)); -#130982 = CARTESIAN_POINT('',(4.737272792729,-3.65)); -#130983 = CARTESIAN_POINT('',(4.761821717947,-3.65)); -#130984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130985 = PCURVE('',#92910,#130986); -#130986 = DEFINITIONAL_REPRESENTATION('',(#130987),#130991); -#130987 = CIRCLE('',#130988,0.308574064194); -#130988 = AXIS2_PLACEMENT_2D('',#130989,#130990); -#130989 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#130990 = DIRECTION('',(0.E+000,1.)); -#130991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#130992 = ORIENTED_EDGE('',*,*,#130993,.T.); -#130993 = EDGE_CURVE('',#130948,#130897,#130994,.T.); -#130994 = SURFACE_CURVE('',#130995,(#130999,#131005),.PCURVE_S1.); -#130995 = LINE('',#130996,#130997); -#130996 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#133351 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#133352 = CARTESIAN_POINT('',(3.166141578807,-3.65)); +#133353 = CARTESIAN_POINT('',(3.215239429242,-3.65)); +#133354 = CARTESIAN_POINT('',(3.288886204895,-3.65)); +#133355 = CARTESIAN_POINT('',(3.362532980548,-3.65)); +#133356 = CARTESIAN_POINT('',(3.4361797562,-3.65)); +#133357 = CARTESIAN_POINT('',(3.509826531853,-3.65)); +#133358 = CARTESIAN_POINT('',(3.583473307505,-3.65)); +#133359 = CARTESIAN_POINT('',(3.657120083158,-3.65)); +#133360 = CARTESIAN_POINT('',(3.730766858811,-3.65)); +#133361 = CARTESIAN_POINT('',(3.804413634463,-3.65)); +#133362 = CARTESIAN_POINT('',(3.878060410116,-3.65)); +#133363 = CARTESIAN_POINT('',(3.951707185768,-3.65)); +#133364 = CARTESIAN_POINT('',(4.025353961421,-3.65)); +#133365 = CARTESIAN_POINT('',(4.099000737074,-3.65)); +#133366 = CARTESIAN_POINT('',(4.172647512726,-3.65)); +#133367 = CARTESIAN_POINT('',(4.246294288379,-3.65)); +#133368 = CARTESIAN_POINT('',(4.319941064031,-3.65)); +#133369 = CARTESIAN_POINT('',(4.393587839684,-3.65)); +#133370 = CARTESIAN_POINT('',(4.467234615337,-3.65)); +#133371 = CARTESIAN_POINT('',(4.540881390989,-3.65)); +#133372 = CARTESIAN_POINT('',(4.614528166642,-3.65)); +#133373 = CARTESIAN_POINT('',(4.688174942294,-3.65)); +#133374 = CARTESIAN_POINT('',(4.737272792729,-3.65)); +#133375 = CARTESIAN_POINT('',(4.761821717947,-3.65)); +#133376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133377 = PCURVE('',#95302,#133378); +#133378 = DEFINITIONAL_REPRESENTATION('',(#133379),#133383); +#133379 = CIRCLE('',#133380,0.308574064194); +#133380 = AXIS2_PLACEMENT_2D('',#133381,#133382); +#133381 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#133382 = DIRECTION('',(0.E+000,1.)); +#133383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133384 = ORIENTED_EDGE('',*,*,#133385,.T.); +#133385 = EDGE_CURVE('',#133340,#133289,#133386,.T.); +#133386 = SURFACE_CURVE('',#133387,(#133391,#133397),.PCURVE_S1.); +#133387 = LINE('',#133388,#133389); +#133388 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#130997 = VECTOR('',#130998,1.); -#130998 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#130999 = PCURVE('',#130782,#131000); -#131000 = DEFINITIONAL_REPRESENTATION('',(#131001),#131004); -#131001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131002,#131003), +#133389 = VECTOR('',#133390,1.); +#133390 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133391 = PCURVE('',#133174,#133392); +#133392 = DEFINITIONAL_REPRESENTATION('',(#133393),#133396); +#133393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133394,#133395), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#131002 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#131003 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#131004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133394 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#133395 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#133396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131005 = PCURVE('',#131006,#131011); -#131006 = PLANE('',#131007); -#131007 = AXIS2_PLACEMENT_3D('',#131008,#131009,#131010); -#131008 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#133397 = PCURVE('',#133398,#133403); +#133398 = PLANE('',#133399); +#133399 = AXIS2_PLACEMENT_3D('',#133400,#133401,#133402); +#133400 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#131009 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131010 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131011 = DEFINITIONAL_REPRESENTATION('',(#131012),#131016); -#131012 = LINE('',#131013,#131014); -#131013 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#131014 = VECTOR('',#131015,1.); -#131015 = DIRECTION('',(-1.,0.E+000)); -#131016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131017 = ADVANCED_FACE('',(#131018),#131006,.T.); -#131018 = FACE_BOUND('',#131019,.T.); -#131019 = EDGE_LOOP('',(#131020,#131049,#131070,#131071)); -#131020 = ORIENTED_EDGE('',*,*,#131021,.T.); -#131021 = EDGE_CURVE('',#131022,#131024,#131026,.T.); -#131022 = VERTEX_POINT('',#131023); -#131023 = CARTESIAN_POINT('',(10.419594812019,3.65,0.530776333563)); -#131024 = VERTEX_POINT('',#131025); -#131025 = CARTESIAN_POINT('',(10.419594812019,3.85,0.530776333563)); -#131026 = SURFACE_CURVE('',#131027,(#131031,#131038),.PCURVE_S1.); -#131027 = LINE('',#131028,#131029); -#131028 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#133401 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133402 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133403 = DEFINITIONAL_REPRESENTATION('',(#133404),#133408); +#133404 = LINE('',#133405,#133406); +#133405 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#133406 = VECTOR('',#133407,1.); +#133407 = DIRECTION('',(-1.,0.E+000)); +#133408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133409 = ADVANCED_FACE('',(#133410),#133398,.T.); +#133410 = FACE_BOUND('',#133411,.T.); +#133411 = EDGE_LOOP('',(#133412,#133441,#133462,#133463)); +#133412 = ORIENTED_EDGE('',*,*,#133413,.T.); +#133413 = EDGE_CURVE('',#133414,#133416,#133418,.T.); +#133414 = VERTEX_POINT('',#133415); +#133415 = CARTESIAN_POINT('',(10.419594812019,3.65,0.530776333563)); +#133416 = VERTEX_POINT('',#133417); +#133417 = CARTESIAN_POINT('',(10.419594812019,3.85,0.530776333563)); +#133418 = SURFACE_CURVE('',#133419,(#133423,#133430),.PCURVE_S1.); +#133419 = LINE('',#133420,#133421); +#133420 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#131029 = VECTOR('',#131030,1.); -#131030 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131031 = PCURVE('',#131006,#131032); -#131032 = DEFINITIONAL_REPRESENTATION('',(#131033),#131037); -#131033 = LINE('',#131034,#131035); -#131034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131035 = VECTOR('',#131036,1.); -#131036 = DIRECTION('',(-1.,0.E+000)); -#131037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131038 = PCURVE('',#131039,#131044); -#131039 = CYLINDRICAL_SURFACE('',#131040,0.119270391569); -#131040 = AXIS2_PLACEMENT_3D('',#131041,#131042,#131043); -#131041 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#133421 = VECTOR('',#133422,1.); +#133422 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133423 = PCURVE('',#133398,#133424); +#133424 = DEFINITIONAL_REPRESENTATION('',(#133425),#133429); +#133425 = LINE('',#133426,#133427); +#133426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133427 = VECTOR('',#133428,1.); +#133428 = DIRECTION('',(-1.,0.E+000)); +#133429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133430 = PCURVE('',#133431,#133436); +#133431 = CYLINDRICAL_SURFACE('',#133432,0.119270391569); +#133432 = AXIS2_PLACEMENT_3D('',#133433,#133434,#133435); +#133433 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#131042 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131043 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131044 = DEFINITIONAL_REPRESENTATION('',(#131045),#131048); -#131045 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131046,#131047), +#133434 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133435 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133436 = DEFINITIONAL_REPRESENTATION('',(#133437),#133440); +#133437 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133438,#133439), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#131046 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#131047 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#131048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131049 = ORIENTED_EDGE('',*,*,#131050,.T.); -#131050 = EDGE_CURVE('',#131024,#130897,#131051,.T.); -#131051 = SURFACE_CURVE('',#131052,(#131056,#131063),.PCURVE_S1.); -#131052 = LINE('',#131053,#131054); -#131053 = CARTESIAN_POINT('',(10.419594812019,3.85,0.530776333563)); -#131054 = VECTOR('',#131055,1.); -#131055 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131056 = PCURVE('',#131006,#131057); -#131057 = DEFINITIONAL_REPRESENTATION('',(#131058),#131062); -#131058 = LINE('',#131059,#131060); -#131059 = CARTESIAN_POINT('',(-3.85,0.E+000)); -#131060 = VECTOR('',#131061,1.); -#131061 = DIRECTION('',(0.E+000,-1.)); -#131062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131063 = PCURVE('',#92854,#131064); -#131064 = DEFINITIONAL_REPRESENTATION('',(#131065),#131069); -#131065 = LINE('',#131066,#131067); -#131066 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#131067 = VECTOR('',#131068,1.); -#131068 = DIRECTION('',(-1.,0.E+000)); -#131069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131070 = ORIENTED_EDGE('',*,*,#130993,.F.); -#131071 = ORIENTED_EDGE('',*,*,#131072,.F.); -#131072 = EDGE_CURVE('',#131022,#130948,#131073,.T.); -#131073 = SURFACE_CURVE('',#131074,(#131078,#131085),.PCURVE_S1.); -#131074 = LINE('',#131075,#131076); -#131075 = CARTESIAN_POINT('',(10.419594812019,3.65,0.530776333563)); -#131076 = VECTOR('',#131077,1.); -#131077 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131078 = PCURVE('',#131006,#131079); -#131079 = DEFINITIONAL_REPRESENTATION('',(#131080),#131084); -#131080 = LINE('',#131081,#131082); -#131081 = CARTESIAN_POINT('',(-3.65,0.E+000)); -#131082 = VECTOR('',#131083,1.); -#131083 = DIRECTION('',(0.E+000,-1.)); -#131084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131085 = PCURVE('',#92910,#131086); -#131086 = DEFINITIONAL_REPRESENTATION('',(#131087),#131091); -#131087 = LINE('',#131088,#131089); -#131088 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#131089 = VECTOR('',#131090,1.); -#131090 = DIRECTION('',(1.,0.E+000)); -#131091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131092 = ADVANCED_FACE('',(#131093),#130855,.T.); -#131093 = FACE_BOUND('',#131094,.T.); -#131094 = EDGE_LOOP('',(#131095,#131124,#131145,#131146)); -#131095 = ORIENTED_EDGE('',*,*,#131096,.T.); -#131096 = EDGE_CURVE('',#131097,#131099,#131101,.T.); -#131097 = VERTEX_POINT('',#131098); -#131098 = CARTESIAN_POINT('',(10.51959417205,3.85,0.530776333563)); -#131099 = VERTEX_POINT('',#131100); -#131100 = CARTESIAN_POINT('',(10.51959417205,3.65,0.530776333563)); -#131101 = SURFACE_CURVE('',#131102,(#131106,#131113),.PCURVE_S1.); -#131102 = LINE('',#131103,#131104); -#131103 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#133438 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#133439 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#133440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133441 = ORIENTED_EDGE('',*,*,#133442,.T.); +#133442 = EDGE_CURVE('',#133416,#133289,#133443,.T.); +#133443 = SURFACE_CURVE('',#133444,(#133448,#133455),.PCURVE_S1.); +#133444 = LINE('',#133445,#133446); +#133445 = CARTESIAN_POINT('',(10.419594812019,3.85,0.530776333563)); +#133446 = VECTOR('',#133447,1.); +#133447 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133448 = PCURVE('',#133398,#133449); +#133449 = DEFINITIONAL_REPRESENTATION('',(#133450),#133454); +#133450 = LINE('',#133451,#133452); +#133451 = CARTESIAN_POINT('',(-3.85,0.E+000)); +#133452 = VECTOR('',#133453,1.); +#133453 = DIRECTION('',(0.E+000,-1.)); +#133454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133455 = PCURVE('',#95246,#133456); +#133456 = DEFINITIONAL_REPRESENTATION('',(#133457),#133461); +#133457 = LINE('',#133458,#133459); +#133458 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#133459 = VECTOR('',#133460,1.); +#133460 = DIRECTION('',(-1.,0.E+000)); +#133461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133462 = ORIENTED_EDGE('',*,*,#133385,.F.); +#133463 = ORIENTED_EDGE('',*,*,#133464,.F.); +#133464 = EDGE_CURVE('',#133414,#133340,#133465,.T.); +#133465 = SURFACE_CURVE('',#133466,(#133470,#133477),.PCURVE_S1.); +#133466 = LINE('',#133467,#133468); +#133467 = CARTESIAN_POINT('',(10.419594812019,3.65,0.530776333563)); +#133468 = VECTOR('',#133469,1.); +#133469 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133470 = PCURVE('',#133398,#133471); +#133471 = DEFINITIONAL_REPRESENTATION('',(#133472),#133476); +#133472 = LINE('',#133473,#133474); +#133473 = CARTESIAN_POINT('',(-3.65,0.E+000)); +#133474 = VECTOR('',#133475,1.); +#133475 = DIRECTION('',(0.E+000,-1.)); +#133476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133477 = PCURVE('',#95302,#133478); +#133478 = DEFINITIONAL_REPRESENTATION('',(#133479),#133483); +#133479 = LINE('',#133480,#133481); +#133480 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#133481 = VECTOR('',#133482,1.); +#133482 = DIRECTION('',(1.,0.E+000)); +#133483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133484 = ADVANCED_FACE('',(#133485),#133247,.T.); +#133485 = FACE_BOUND('',#133486,.T.); +#133486 = EDGE_LOOP('',(#133487,#133516,#133537,#133538)); +#133487 = ORIENTED_EDGE('',*,*,#133488,.T.); +#133488 = EDGE_CURVE('',#133489,#133491,#133493,.T.); +#133489 = VERTEX_POINT('',#133490); +#133490 = CARTESIAN_POINT('',(10.51959417205,3.85,0.530776333563)); +#133491 = VERTEX_POINT('',#133492); +#133492 = CARTESIAN_POINT('',(10.51959417205,3.65,0.530776333563)); +#133493 = SURFACE_CURVE('',#133494,(#133498,#133505),.PCURVE_S1.); +#133494 = LINE('',#133495,#133496); +#133495 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#131104 = VECTOR('',#131105,1.); -#131105 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131106 = PCURVE('',#130855,#131107); -#131107 = DEFINITIONAL_REPRESENTATION('',(#131108),#131112); -#131108 = LINE('',#131109,#131110); -#131109 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131110 = VECTOR('',#131111,1.); -#131111 = DIRECTION('',(-1.,0.E+000)); -#131112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131113 = PCURVE('',#131114,#131119); -#131114 = CYLINDRICAL_SURFACE('',#131115,0.2192697516); -#131115 = AXIS2_PLACEMENT_3D('',#131116,#131117,#131118); -#131116 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#133496 = VECTOR('',#133497,1.); +#133497 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133498 = PCURVE('',#133247,#133499); +#133499 = DEFINITIONAL_REPRESENTATION('',(#133500),#133504); +#133500 = LINE('',#133501,#133502); +#133501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133502 = VECTOR('',#133503,1.); +#133503 = DIRECTION('',(-1.,0.E+000)); +#133504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133505 = PCURVE('',#133506,#133511); +#133506 = CYLINDRICAL_SURFACE('',#133507,0.2192697516); +#133507 = AXIS2_PLACEMENT_3D('',#133508,#133509,#133510); +#133508 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#131117 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131118 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131119 = DEFINITIONAL_REPRESENTATION('',(#131120),#131123); -#131120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131121,#131122), +#133509 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133510 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133511 = DEFINITIONAL_REPRESENTATION('',(#133512),#133515); +#133512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133513,#133514), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#131121 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#131122 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#131123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131124 = ORIENTED_EDGE('',*,*,#131125,.T.); -#131125 = EDGE_CURVE('',#131099,#130818,#131126,.T.); -#131126 = SURFACE_CURVE('',#131127,(#131131,#131138),.PCURVE_S1.); -#131127 = LINE('',#131128,#131129); -#131128 = CARTESIAN_POINT('',(10.51959417205,3.65,0.530776333563)); -#131129 = VECTOR('',#131130,1.); -#131130 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131131 = PCURVE('',#130855,#131132); -#131132 = DEFINITIONAL_REPRESENTATION('',(#131133),#131137); -#131133 = LINE('',#131134,#131135); -#131134 = CARTESIAN_POINT('',(3.65,0.E+000)); -#131135 = VECTOR('',#131136,1.); -#131136 = DIRECTION('',(0.E+000,-1.)); -#131137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131138 = PCURVE('',#92910,#131139); -#131139 = DEFINITIONAL_REPRESENTATION('',(#131140),#131144); -#131140 = LINE('',#131141,#131142); -#131141 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#131142 = VECTOR('',#131143,1.); -#131143 = DIRECTION('',(1.,0.E+000)); -#131144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131145 = ORIENTED_EDGE('',*,*,#130840,.F.); -#131146 = ORIENTED_EDGE('',*,*,#131147,.F.); -#131147 = EDGE_CURVE('',#131097,#130841,#131148,.T.); -#131148 = SURFACE_CURVE('',#131149,(#131153,#131160),.PCURVE_S1.); -#131149 = LINE('',#131150,#131151); -#131150 = CARTESIAN_POINT('',(10.51959417205,3.85,0.530776333563)); -#131151 = VECTOR('',#131152,1.); -#131152 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131153 = PCURVE('',#130855,#131154); -#131154 = DEFINITIONAL_REPRESENTATION('',(#131155),#131159); -#131155 = LINE('',#131156,#131157); -#131156 = CARTESIAN_POINT('',(3.85,0.E+000)); -#131157 = VECTOR('',#131158,1.); -#131158 = DIRECTION('',(0.E+000,-1.)); -#131159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131160 = PCURVE('',#92854,#131161); -#131161 = DEFINITIONAL_REPRESENTATION('',(#131162),#131166); -#131162 = LINE('',#131163,#131164); -#131163 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#131164 = VECTOR('',#131165,1.); -#131165 = DIRECTION('',(-1.,0.E+000)); -#131166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131167 = ADVANCED_FACE('',(#131168),#131114,.T.); -#131168 = FACE_BOUND('',#131169,.T.); -#131169 = EDGE_LOOP('',(#131170,#131171,#131217,#131239)); -#131170 = ORIENTED_EDGE('',*,*,#131096,.F.); -#131171 = ORIENTED_EDGE('',*,*,#131172,.F.); -#131172 = EDGE_CURVE('',#131173,#131097,#131175,.T.); -#131173 = VERTEX_POINT('',#131174); -#131174 = CARTESIAN_POINT('',(10.304819755875,3.85,0.75)); -#131175 = SURFACE_CURVE('',#131176,(#131181,#131210),.PCURVE_S1.); -#131176 = CIRCLE('',#131177,0.2192697516); -#131177 = AXIS2_PLACEMENT_3D('',#131178,#131179,#131180); -#131178 = CARTESIAN_POINT('',(10.30032442045,3.85,0.530776333563)); -#131179 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131180 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131181 = PCURVE('',#131114,#131182); -#131182 = DEFINITIONAL_REPRESENTATION('',(#131183),#131209); -#131183 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#131184,#131185,#131186, - #131187,#131188,#131189,#131190,#131191,#131192,#131193,#131194, - #131195,#131196,#131197,#131198,#131199,#131200,#131201,#131202, - #131203,#131204,#131205,#131206,#131207,#131208),.UNSPECIFIED.,.F., +#133513 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#133514 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#133515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133516 = ORIENTED_EDGE('',*,*,#133517,.T.); +#133517 = EDGE_CURVE('',#133491,#133210,#133518,.T.); +#133518 = SURFACE_CURVE('',#133519,(#133523,#133530),.PCURVE_S1.); +#133519 = LINE('',#133520,#133521); +#133520 = CARTESIAN_POINT('',(10.51959417205,3.65,0.530776333563)); +#133521 = VECTOR('',#133522,1.); +#133522 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133523 = PCURVE('',#133247,#133524); +#133524 = DEFINITIONAL_REPRESENTATION('',(#133525),#133529); +#133525 = LINE('',#133526,#133527); +#133526 = CARTESIAN_POINT('',(3.65,0.E+000)); +#133527 = VECTOR('',#133528,1.); +#133528 = DIRECTION('',(0.E+000,-1.)); +#133529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133530 = PCURVE('',#95302,#133531); +#133531 = DEFINITIONAL_REPRESENTATION('',(#133532),#133536); +#133532 = LINE('',#133533,#133534); +#133533 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#133534 = VECTOR('',#133535,1.); +#133535 = DIRECTION('',(1.,0.E+000)); +#133536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133537 = ORIENTED_EDGE('',*,*,#133232,.F.); +#133538 = ORIENTED_EDGE('',*,*,#133539,.F.); +#133539 = EDGE_CURVE('',#133489,#133233,#133540,.T.); +#133540 = SURFACE_CURVE('',#133541,(#133545,#133552),.PCURVE_S1.); +#133541 = LINE('',#133542,#133543); +#133542 = CARTESIAN_POINT('',(10.51959417205,3.85,0.530776333563)); +#133543 = VECTOR('',#133544,1.); +#133544 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133545 = PCURVE('',#133247,#133546); +#133546 = DEFINITIONAL_REPRESENTATION('',(#133547),#133551); +#133547 = LINE('',#133548,#133549); +#133548 = CARTESIAN_POINT('',(3.85,0.E+000)); +#133549 = VECTOR('',#133550,1.); +#133550 = DIRECTION('',(0.E+000,-1.)); +#133551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133552 = PCURVE('',#95246,#133553); +#133553 = DEFINITIONAL_REPRESENTATION('',(#133554),#133558); +#133554 = LINE('',#133555,#133556); +#133555 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#133556 = VECTOR('',#133557,1.); +#133557 = DIRECTION('',(-1.,0.E+000)); +#133558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133559 = ADVANCED_FACE('',(#133560),#133506,.T.); +#133560 = FACE_BOUND('',#133561,.T.); +#133561 = EDGE_LOOP('',(#133562,#133563,#133609,#133631)); +#133562 = ORIENTED_EDGE('',*,*,#133488,.F.); +#133563 = ORIENTED_EDGE('',*,*,#133564,.F.); +#133564 = EDGE_CURVE('',#133565,#133489,#133567,.T.); +#133565 = VERTEX_POINT('',#133566); +#133566 = CARTESIAN_POINT('',(10.304819755875,3.85,0.75)); +#133567 = SURFACE_CURVE('',#133568,(#133573,#133602),.PCURVE_S1.); +#133568 = CIRCLE('',#133569,0.2192697516); +#133569 = AXIS2_PLACEMENT_3D('',#133570,#133571,#133572); +#133570 = CARTESIAN_POINT('',(10.30032442045,3.85,0.530776333563)); +#133571 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133572 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133573 = PCURVE('',#133506,#133574); +#133574 = DEFINITIONAL_REPRESENTATION('',(#133575),#133601); +#133575 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133576,#133577,#133578, + #133579,#133580,#133581,#133582,#133583,#133584,#133585,#133586, + #133587,#133588,#133589,#133590,#133591,#133592,#133593,#133594, + #133595,#133596,#133597,#133598,#133599,#133600),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -161616,84 +164618,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#131184 = CARTESIAN_POINT('',(1.591299156552,3.85)); -#131185 = CARTESIAN_POINT('',(1.614788451962,3.85)); -#131186 = CARTESIAN_POINT('',(1.661767042781,3.85)); -#131187 = CARTESIAN_POINT('',(1.73223492901,3.85)); -#131188 = CARTESIAN_POINT('',(1.802702815239,3.85)); -#131189 = CARTESIAN_POINT('',(1.873170701468,3.85)); -#131190 = CARTESIAN_POINT('',(1.943638587697,3.85)); -#131191 = CARTESIAN_POINT('',(2.014106473926,3.85)); -#131192 = CARTESIAN_POINT('',(2.084574360155,3.85)); -#131193 = CARTESIAN_POINT('',(2.155042246384,3.85)); -#131194 = CARTESIAN_POINT('',(2.225510132613,3.85)); -#131195 = CARTESIAN_POINT('',(2.295978018842,3.85)); -#131196 = CARTESIAN_POINT('',(2.366445905071,3.85)); -#131197 = CARTESIAN_POINT('',(2.4369137913,3.85)); -#131198 = CARTESIAN_POINT('',(2.507381677529,3.85)); -#131199 = CARTESIAN_POINT('',(2.577849563758,3.85)); -#131200 = CARTESIAN_POINT('',(2.648317449987,3.85)); -#131201 = CARTESIAN_POINT('',(2.718785336216,3.85)); -#131202 = CARTESIAN_POINT('',(2.789253222445,3.85)); -#131203 = CARTESIAN_POINT('',(2.859721108674,3.85)); -#131204 = CARTESIAN_POINT('',(2.930188994903,3.85)); -#131205 = CARTESIAN_POINT('',(3.000656881132,3.85)); -#131206 = CARTESIAN_POINT('',(3.071124767361,3.85)); -#131207 = CARTESIAN_POINT('',(3.11810335818,3.85)); -#131208 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#131209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131210 = PCURVE('',#92854,#131211); -#131211 = DEFINITIONAL_REPRESENTATION('',(#131212),#131216); -#131212 = CIRCLE('',#131213,0.2192697516); -#131213 = AXIS2_PLACEMENT_2D('',#131214,#131215); -#131214 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#131215 = DIRECTION('',(0.E+000,-1.)); -#131216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131217 = ORIENTED_EDGE('',*,*,#131218,.F.); -#131218 = EDGE_CURVE('',#131219,#131173,#131221,.T.); -#131219 = VERTEX_POINT('',#131220); -#131220 = CARTESIAN_POINT('',(10.304819755875,3.65,0.75)); -#131221 = SURFACE_CURVE('',#131222,(#131226,#131232),.PCURVE_S1.); -#131222 = LINE('',#131223,#131224); -#131223 = CARTESIAN_POINT('',(10.304819755875,3.85,0.75)); -#131224 = VECTOR('',#131225,1.); -#131225 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131226 = PCURVE('',#131114,#131227); -#131227 = DEFINITIONAL_REPRESENTATION('',(#131228),#131231); -#131228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131229,#131230), +#133576 = CARTESIAN_POINT('',(1.591299156552,3.85)); +#133577 = CARTESIAN_POINT('',(1.614788451962,3.85)); +#133578 = CARTESIAN_POINT('',(1.661767042781,3.85)); +#133579 = CARTESIAN_POINT('',(1.73223492901,3.85)); +#133580 = CARTESIAN_POINT('',(1.802702815239,3.85)); +#133581 = CARTESIAN_POINT('',(1.873170701468,3.85)); +#133582 = CARTESIAN_POINT('',(1.943638587697,3.85)); +#133583 = CARTESIAN_POINT('',(2.014106473926,3.85)); +#133584 = CARTESIAN_POINT('',(2.084574360155,3.85)); +#133585 = CARTESIAN_POINT('',(2.155042246384,3.85)); +#133586 = CARTESIAN_POINT('',(2.225510132613,3.85)); +#133587 = CARTESIAN_POINT('',(2.295978018842,3.85)); +#133588 = CARTESIAN_POINT('',(2.366445905071,3.85)); +#133589 = CARTESIAN_POINT('',(2.4369137913,3.85)); +#133590 = CARTESIAN_POINT('',(2.507381677529,3.85)); +#133591 = CARTESIAN_POINT('',(2.577849563758,3.85)); +#133592 = CARTESIAN_POINT('',(2.648317449987,3.85)); +#133593 = CARTESIAN_POINT('',(2.718785336216,3.85)); +#133594 = CARTESIAN_POINT('',(2.789253222445,3.85)); +#133595 = CARTESIAN_POINT('',(2.859721108674,3.85)); +#133596 = CARTESIAN_POINT('',(2.930188994903,3.85)); +#133597 = CARTESIAN_POINT('',(3.000656881132,3.85)); +#133598 = CARTESIAN_POINT('',(3.071124767361,3.85)); +#133599 = CARTESIAN_POINT('',(3.11810335818,3.85)); +#133600 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#133601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133602 = PCURVE('',#95246,#133603); +#133603 = DEFINITIONAL_REPRESENTATION('',(#133604),#133608); +#133604 = CIRCLE('',#133605,0.2192697516); +#133605 = AXIS2_PLACEMENT_2D('',#133606,#133607); +#133606 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#133607 = DIRECTION('',(0.E+000,-1.)); +#133608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133609 = ORIENTED_EDGE('',*,*,#133610,.F.); +#133610 = EDGE_CURVE('',#133611,#133565,#133613,.T.); +#133611 = VERTEX_POINT('',#133612); +#133612 = CARTESIAN_POINT('',(10.304819755875,3.65,0.75)); +#133613 = SURFACE_CURVE('',#133614,(#133618,#133624),.PCURVE_S1.); +#133614 = LINE('',#133615,#133616); +#133615 = CARTESIAN_POINT('',(10.304819755875,3.85,0.75)); +#133616 = VECTOR('',#133617,1.); +#133617 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133618 = PCURVE('',#133506,#133619); +#133619 = DEFINITIONAL_REPRESENTATION('',(#133620),#133623); +#133620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133621,#133622), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#131229 = CARTESIAN_POINT('',(1.591299156552,3.65)); -#131230 = CARTESIAN_POINT('',(1.591299156552,3.85)); -#131231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131232 = PCURVE('',#92936,#131233); -#131233 = DEFINITIONAL_REPRESENTATION('',(#131234),#131238); -#131234 = LINE('',#131235,#131236); -#131235 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#131236 = VECTOR('',#131237,1.); -#131237 = DIRECTION('',(4.440892098501E-016,1.)); -#131238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131239 = ORIENTED_EDGE('',*,*,#131240,.T.); -#131240 = EDGE_CURVE('',#131219,#131099,#131241,.T.); -#131241 = SURFACE_CURVE('',#131242,(#131247,#131276),.PCURVE_S1.); -#131242 = CIRCLE('',#131243,0.2192697516); -#131243 = AXIS2_PLACEMENT_3D('',#131244,#131245,#131246); -#131244 = CARTESIAN_POINT('',(10.30032442045,3.65,0.530776333563)); -#131245 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131246 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131247 = PCURVE('',#131114,#131248); -#131248 = DEFINITIONAL_REPRESENTATION('',(#131249),#131275); -#131249 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#131250,#131251,#131252, - #131253,#131254,#131255,#131256,#131257,#131258,#131259,#131260, - #131261,#131262,#131263,#131264,#131265,#131266,#131267,#131268, - #131269,#131270,#131271,#131272,#131273,#131274),.UNSPECIFIED.,.F., +#133621 = CARTESIAN_POINT('',(1.591299156552,3.65)); +#133622 = CARTESIAN_POINT('',(1.591299156552,3.85)); +#133623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133624 = PCURVE('',#95328,#133625); +#133625 = DEFINITIONAL_REPRESENTATION('',(#133626),#133630); +#133626 = LINE('',#133627,#133628); +#133627 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#133628 = VECTOR('',#133629,1.); +#133629 = DIRECTION('',(4.440892098501E-016,1.)); +#133630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133631 = ORIENTED_EDGE('',*,*,#133632,.T.); +#133632 = EDGE_CURVE('',#133611,#133491,#133633,.T.); +#133633 = SURFACE_CURVE('',#133634,(#133639,#133668),.PCURVE_S1.); +#133634 = CIRCLE('',#133635,0.2192697516); +#133635 = AXIS2_PLACEMENT_3D('',#133636,#133637,#133638); +#133636 = CARTESIAN_POINT('',(10.30032442045,3.65,0.530776333563)); +#133637 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133638 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133639 = PCURVE('',#133506,#133640); +#133640 = DEFINITIONAL_REPRESENTATION('',(#133641),#133667); +#133641 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133642,#133643,#133644, + #133645,#133646,#133647,#133648,#133649,#133650,#133651,#133652, + #133653,#133654,#133655,#133656,#133657,#133658,#133659,#133660, + #133661,#133662,#133663,#133664,#133665,#133666),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -161701,728 +164703,728 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#131250 = CARTESIAN_POINT('',(1.591299156552,3.65)); -#131251 = CARTESIAN_POINT('',(1.614788451962,3.65)); -#131252 = CARTESIAN_POINT('',(1.661767042781,3.65)); -#131253 = CARTESIAN_POINT('',(1.73223492901,3.65)); -#131254 = CARTESIAN_POINT('',(1.802702815239,3.65)); -#131255 = CARTESIAN_POINT('',(1.873170701468,3.65)); -#131256 = CARTESIAN_POINT('',(1.943638587697,3.65)); -#131257 = CARTESIAN_POINT('',(2.014106473926,3.65)); -#131258 = CARTESIAN_POINT('',(2.084574360155,3.65)); -#131259 = CARTESIAN_POINT('',(2.155042246384,3.65)); -#131260 = CARTESIAN_POINT('',(2.225510132613,3.65)); -#131261 = CARTESIAN_POINT('',(2.295978018842,3.65)); -#131262 = CARTESIAN_POINT('',(2.366445905071,3.65)); -#131263 = CARTESIAN_POINT('',(2.4369137913,3.65)); -#131264 = CARTESIAN_POINT('',(2.507381677529,3.65)); -#131265 = CARTESIAN_POINT('',(2.577849563758,3.65)); -#131266 = CARTESIAN_POINT('',(2.648317449987,3.65)); -#131267 = CARTESIAN_POINT('',(2.718785336216,3.65)); -#131268 = CARTESIAN_POINT('',(2.789253222445,3.65)); -#131269 = CARTESIAN_POINT('',(2.859721108674,3.65)); -#131270 = CARTESIAN_POINT('',(2.930188994903,3.65)); -#131271 = CARTESIAN_POINT('',(3.000656881132,3.65)); -#131272 = CARTESIAN_POINT('',(3.071124767361,3.65)); -#131273 = CARTESIAN_POINT('',(3.11810335818,3.65)); -#131274 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#131275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131276 = PCURVE('',#92910,#131277); -#131277 = DEFINITIONAL_REPRESENTATION('',(#131278),#131286); -#131278 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131279,#131280,#131281, - #131282,#131283,#131284,#131285),.UNSPECIFIED.,.T.,.F.) +#133642 = CARTESIAN_POINT('',(1.591299156552,3.65)); +#133643 = CARTESIAN_POINT('',(1.614788451962,3.65)); +#133644 = CARTESIAN_POINT('',(1.661767042781,3.65)); +#133645 = CARTESIAN_POINT('',(1.73223492901,3.65)); +#133646 = CARTESIAN_POINT('',(1.802702815239,3.65)); +#133647 = CARTESIAN_POINT('',(1.873170701468,3.65)); +#133648 = CARTESIAN_POINT('',(1.943638587697,3.65)); +#133649 = CARTESIAN_POINT('',(2.014106473926,3.65)); +#133650 = CARTESIAN_POINT('',(2.084574360155,3.65)); +#133651 = CARTESIAN_POINT('',(2.155042246384,3.65)); +#133652 = CARTESIAN_POINT('',(2.225510132613,3.65)); +#133653 = CARTESIAN_POINT('',(2.295978018842,3.65)); +#133654 = CARTESIAN_POINT('',(2.366445905071,3.65)); +#133655 = CARTESIAN_POINT('',(2.4369137913,3.65)); +#133656 = CARTESIAN_POINT('',(2.507381677529,3.65)); +#133657 = CARTESIAN_POINT('',(2.577849563758,3.65)); +#133658 = CARTESIAN_POINT('',(2.648317449987,3.65)); +#133659 = CARTESIAN_POINT('',(2.718785336216,3.65)); +#133660 = CARTESIAN_POINT('',(2.789253222445,3.65)); +#133661 = CARTESIAN_POINT('',(2.859721108674,3.65)); +#133662 = CARTESIAN_POINT('',(2.930188994903,3.65)); +#133663 = CARTESIAN_POINT('',(3.000656881132,3.65)); +#133664 = CARTESIAN_POINT('',(3.071124767361,3.65)); +#133665 = CARTESIAN_POINT('',(3.11810335818,3.65)); +#133666 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#133667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133668 = PCURVE('',#95302,#133669); +#133669 = DEFINITIONAL_REPRESENTATION('',(#133670),#133678); +#133670 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133671,#133672,#133673, + #133674,#133675,#133676,#133677),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#131279 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#131280 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#131281 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#131282 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#131283 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#131284 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#131285 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#131286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131287 = ADVANCED_FACE('',(#131288),#131039,.F.); -#131288 = FACE_BOUND('',#131289,.F.); -#131289 = EDGE_LOOP('',(#131290,#131291,#131314,#131336)); -#131290 = ORIENTED_EDGE('',*,*,#131021,.T.); -#131291 = ORIENTED_EDGE('',*,*,#131292,.F.); -#131292 = EDGE_CURVE('',#131293,#131024,#131295,.T.); -#131293 = VERTEX_POINT('',#131294); -#131294 = CARTESIAN_POINT('',(10.303662633502,3.85,0.65)); -#131295 = SURFACE_CURVE('',#131296,(#131301,#131307),.PCURVE_S1.); -#131296 = CIRCLE('',#131297,0.119270391569); -#131297 = AXIS2_PLACEMENT_3D('',#131298,#131299,#131300); -#131298 = CARTESIAN_POINT('',(10.30032442045,3.85,0.530776333563)); -#131299 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131300 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131301 = PCURVE('',#131039,#131302); -#131302 = DEFINITIONAL_REPRESENTATION('',(#131303),#131306); -#131303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131304,#131305), +#133671 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#133672 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#133673 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#133674 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#133675 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#133676 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#133677 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#133678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133679 = ADVANCED_FACE('',(#133680),#133431,.F.); +#133680 = FACE_BOUND('',#133681,.F.); +#133681 = EDGE_LOOP('',(#133682,#133683,#133706,#133728)); +#133682 = ORIENTED_EDGE('',*,*,#133413,.T.); +#133683 = ORIENTED_EDGE('',*,*,#133684,.F.); +#133684 = EDGE_CURVE('',#133685,#133416,#133687,.T.); +#133685 = VERTEX_POINT('',#133686); +#133686 = CARTESIAN_POINT('',(10.303662633502,3.85,0.65)); +#133687 = SURFACE_CURVE('',#133688,(#133693,#133699),.PCURVE_S1.); +#133688 = CIRCLE('',#133689,0.119270391569); +#133689 = AXIS2_PLACEMENT_3D('',#133690,#133691,#133692); +#133690 = CARTESIAN_POINT('',(10.30032442045,3.85,0.530776333563)); +#133691 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133692 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133693 = PCURVE('',#133431,#133694); +#133694 = DEFINITIONAL_REPRESENTATION('',(#133695),#133698); +#133695 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133696,#133697), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#131304 = CARTESIAN_POINT('',(1.598788597134,3.85)); -#131305 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#131306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131307 = PCURVE('',#92854,#131308); -#131308 = DEFINITIONAL_REPRESENTATION('',(#131309),#131313); -#131309 = CIRCLE('',#131310,0.119270391569); -#131310 = AXIS2_PLACEMENT_2D('',#131311,#131312); -#131311 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#131312 = DIRECTION('',(0.E+000,-1.)); -#131313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131314 = ORIENTED_EDGE('',*,*,#131315,.T.); -#131315 = EDGE_CURVE('',#131293,#131316,#131318,.T.); -#131316 = VERTEX_POINT('',#131317); -#131317 = CARTESIAN_POINT('',(10.303662633502,3.65,0.65)); -#131318 = SURFACE_CURVE('',#131319,(#131323,#131329),.PCURVE_S1.); -#131319 = LINE('',#131320,#131321); -#131320 = CARTESIAN_POINT('',(10.303662633502,3.85,0.65)); -#131321 = VECTOR('',#131322,1.); -#131322 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131323 = PCURVE('',#131039,#131324); -#131324 = DEFINITIONAL_REPRESENTATION('',(#131325),#131328); -#131325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131326,#131327), +#133696 = CARTESIAN_POINT('',(1.598788597134,3.85)); +#133697 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#133698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133699 = PCURVE('',#95246,#133700); +#133700 = DEFINITIONAL_REPRESENTATION('',(#133701),#133705); +#133701 = CIRCLE('',#133702,0.119270391569); +#133702 = AXIS2_PLACEMENT_2D('',#133703,#133704); +#133703 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#133704 = DIRECTION('',(0.E+000,-1.)); +#133705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133706 = ORIENTED_EDGE('',*,*,#133707,.T.); +#133707 = EDGE_CURVE('',#133685,#133708,#133710,.T.); +#133708 = VERTEX_POINT('',#133709); +#133709 = CARTESIAN_POINT('',(10.303662633502,3.65,0.65)); +#133710 = SURFACE_CURVE('',#133711,(#133715,#133721),.PCURVE_S1.); +#133711 = LINE('',#133712,#133713); +#133712 = CARTESIAN_POINT('',(10.303662633502,3.85,0.65)); +#133713 = VECTOR('',#133714,1.); +#133714 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133715 = PCURVE('',#133431,#133716); +#133716 = DEFINITIONAL_REPRESENTATION('',(#133717),#133720); +#133717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133718,#133719), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#131326 = CARTESIAN_POINT('',(1.598788597134,3.85)); -#131327 = CARTESIAN_POINT('',(1.598788597134,3.65)); -#131328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131329 = PCURVE('',#92882,#131330); -#131330 = DEFINITIONAL_REPRESENTATION('',(#131331),#131335); -#131331 = LINE('',#131332,#131333); -#131332 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#131333 = VECTOR('',#131334,1.); -#131334 = DIRECTION('',(4.440892098501E-016,-1.)); -#131335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131336 = ORIENTED_EDGE('',*,*,#131337,.T.); -#131337 = EDGE_CURVE('',#131316,#131022,#131338,.T.); -#131338 = SURFACE_CURVE('',#131339,(#131344,#131350),.PCURVE_S1.); -#131339 = CIRCLE('',#131340,0.119270391569); -#131340 = AXIS2_PLACEMENT_3D('',#131341,#131342,#131343); -#131341 = CARTESIAN_POINT('',(10.30032442045,3.65,0.530776333563)); -#131342 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131343 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131344 = PCURVE('',#131039,#131345); -#131345 = DEFINITIONAL_REPRESENTATION('',(#131346),#131349); -#131346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131347,#131348), +#133718 = CARTESIAN_POINT('',(1.598788597134,3.85)); +#133719 = CARTESIAN_POINT('',(1.598788597134,3.65)); +#133720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133721 = PCURVE('',#95274,#133722); +#133722 = DEFINITIONAL_REPRESENTATION('',(#133723),#133727); +#133723 = LINE('',#133724,#133725); +#133724 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#133725 = VECTOR('',#133726,1.); +#133726 = DIRECTION('',(4.440892098501E-016,-1.)); +#133727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133728 = ORIENTED_EDGE('',*,*,#133729,.T.); +#133729 = EDGE_CURVE('',#133708,#133414,#133730,.T.); +#133730 = SURFACE_CURVE('',#133731,(#133736,#133742),.PCURVE_S1.); +#133731 = CIRCLE('',#133732,0.119270391569); +#133732 = AXIS2_PLACEMENT_3D('',#133733,#133734,#133735); +#133733 = CARTESIAN_POINT('',(10.30032442045,3.65,0.530776333563)); +#133734 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133735 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#133736 = PCURVE('',#133431,#133737); +#133737 = DEFINITIONAL_REPRESENTATION('',(#133738),#133741); +#133738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133739,#133740), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#131347 = CARTESIAN_POINT('',(1.598788597134,3.65)); -#131348 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#131349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133739 = CARTESIAN_POINT('',(1.598788597134,3.65)); +#133740 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#133741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131350 = PCURVE('',#92910,#131351); -#131351 = DEFINITIONAL_REPRESENTATION('',(#131352),#131360); -#131352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131353,#131354,#131355, - #131356,#131357,#131358,#131359),.UNSPECIFIED.,.T.,.F.) +#133742 = PCURVE('',#95302,#133743); +#133743 = DEFINITIONAL_REPRESENTATION('',(#133744),#133752); +#133744 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133745,#133746,#133747, + #133748,#133749,#133750,#133751),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#131353 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#131354 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#131355 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#131356 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#131357 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#131358 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#131359 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#131360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131361 = ADVANCED_FACE('',(#131362),#92882,.T.); -#131362 = FACE_BOUND('',#131363,.T.); -#131363 = EDGE_LOOP('',(#131364,#131385,#131386,#131407)); -#131364 = ORIENTED_EDGE('',*,*,#131365,.F.); -#131365 = EDGE_CURVE('',#131293,#92839,#131366,.T.); -#131366 = SURFACE_CURVE('',#131367,(#131371,#131378),.PCURVE_S1.); -#131367 = LINE('',#131368,#131369); -#131368 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); -#131369 = VECTOR('',#131370,1.); -#131370 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#131371 = PCURVE('',#92882,#131372); -#131372 = DEFINITIONAL_REPRESENTATION('',(#131373),#131377); -#131373 = LINE('',#131374,#131375); -#131374 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131375 = VECTOR('',#131376,1.); -#131376 = DIRECTION('',(1.,-3.00059940766E-063)); -#131377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131378 = PCURVE('',#92854,#131379); -#131379 = DEFINITIONAL_REPRESENTATION('',(#131380),#131384); -#131380 = LINE('',#131381,#131382); -#131381 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131382 = VECTOR('',#131383,1.); -#131383 = DIRECTION('',(3.563627120235E-016,-1.)); -#131384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131385 = ORIENTED_EDGE('',*,*,#131315,.T.); -#131386 = ORIENTED_EDGE('',*,*,#131387,.T.); -#131387 = EDGE_CURVE('',#131316,#92867,#131388,.T.); -#131388 = SURFACE_CURVE('',#131389,(#131393,#131400),.PCURVE_S1.); -#131389 = LINE('',#131390,#131391); -#131390 = CARTESIAN_POINT('',(10.527847992439,3.65,0.65)); -#131391 = VECTOR('',#131392,1.); -#131392 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#131393 = PCURVE('',#92882,#131394); -#131394 = DEFINITIONAL_REPRESENTATION('',(#131395),#131399); -#131395 = LINE('',#131396,#131397); -#131396 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#131397 = VECTOR('',#131398,1.); -#131398 = DIRECTION('',(1.,-3.00059940766E-063)); -#131399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#133745 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#133746 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#133747 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#133748 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#133749 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#133750 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#133751 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#133752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133753 = ADVANCED_FACE('',(#133754),#95274,.T.); +#133754 = FACE_BOUND('',#133755,.T.); +#133755 = EDGE_LOOP('',(#133756,#133777,#133778,#133799)); +#133756 = ORIENTED_EDGE('',*,*,#133757,.F.); +#133757 = EDGE_CURVE('',#133685,#95231,#133758,.T.); +#133758 = SURFACE_CURVE('',#133759,(#133763,#133770),.PCURVE_S1.); +#133759 = LINE('',#133760,#133761); +#133760 = CARTESIAN_POINT('',(10.527847992439,3.85,0.65)); +#133761 = VECTOR('',#133762,1.); +#133762 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#133763 = PCURVE('',#95274,#133764); +#133764 = DEFINITIONAL_REPRESENTATION('',(#133765),#133769); +#133765 = LINE('',#133766,#133767); +#133766 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133767 = VECTOR('',#133768,1.); +#133768 = DIRECTION('',(1.,-3.00059940766E-063)); +#133769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133770 = PCURVE('',#95246,#133771); +#133771 = DEFINITIONAL_REPRESENTATION('',(#133772),#133776); +#133772 = LINE('',#133773,#133774); +#133773 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133774 = VECTOR('',#133775,1.); +#133775 = DIRECTION('',(3.563627120235E-016,-1.)); +#133776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133777 = ORIENTED_EDGE('',*,*,#133707,.T.); +#133778 = ORIENTED_EDGE('',*,*,#133779,.T.); +#133779 = EDGE_CURVE('',#133708,#95259,#133780,.T.); +#133780 = SURFACE_CURVE('',#133781,(#133785,#133792),.PCURVE_S1.); +#133781 = LINE('',#133782,#133783); +#133782 = CARTESIAN_POINT('',(10.527847992439,3.65,0.65)); +#133783 = VECTOR('',#133784,1.); +#133784 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#133785 = PCURVE('',#95274,#133786); +#133786 = DEFINITIONAL_REPRESENTATION('',(#133787),#133791); +#133787 = LINE('',#133788,#133789); +#133788 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#133789 = VECTOR('',#133790,1.); +#133790 = DIRECTION('',(1.,-3.00059940766E-063)); +#133791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133792 = PCURVE('',#95302,#133793); +#133793 = DEFINITIONAL_REPRESENTATION('',(#133794),#133798); +#133794 = LINE('',#133795,#133796); +#133795 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133796 = VECTOR('',#133797,1.); +#133797 = DIRECTION('',(-3.563627120235E-016,-1.)); +#133798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133799 = ORIENTED_EDGE('',*,*,#95258,.F.); +#133800 = ADVANCED_FACE('',(#133801),#95302,.T.); +#133801 = FACE_BOUND('',#133802,.T.); +#133802 = EDGE_LOOP('',(#133803,#133804,#133805,#133806,#133807,#133808, + #133829,#133830,#133831,#133832,#133833,#133854)); +#133803 = ORIENTED_EDGE('',*,*,#133779,.F.); +#133804 = ORIENTED_EDGE('',*,*,#133729,.T.); +#133805 = ORIENTED_EDGE('',*,*,#133464,.T.); +#133806 = ORIENTED_EDGE('',*,*,#133339,.T.); +#133807 = ORIENTED_EDGE('',*,*,#133135,.T.); +#133808 = ORIENTED_EDGE('',*,*,#133809,.F.); +#133809 = EDGE_CURVE('',#132999,#133106,#133810,.T.); +#133810 = SURFACE_CURVE('',#133811,(#133815,#133822),.PCURVE_S1.); +#133811 = LINE('',#133812,#133813); +#133812 = CARTESIAN_POINT('',(11.,3.65,1.159810404338E-002)); +#133813 = VECTOR('',#133814,1.); +#133814 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#133815 = PCURVE('',#95302,#133816); +#133816 = DEFINITIONAL_REPRESENTATION('',(#133817),#133821); +#133817 = LINE('',#133818,#133819); +#133818 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#133819 = VECTOR('',#133820,1.); +#133820 = DIRECTION('',(1.,-2.101748079665E-016)); +#133821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133822 = PCURVE('',#133019,#133823); +#133823 = DEFINITIONAL_REPRESENTATION('',(#133824),#133828); +#133824 = LINE('',#133825,#133826); +#133825 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#133826 = VECTOR('',#133827,1.); +#133827 = DIRECTION('',(-1.194699204908E-017,-1.)); +#133828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133829 = ORIENTED_EDGE('',*,*,#133081,.F.); +#133830 = ORIENTED_EDGE('',*,*,#133209,.F.); +#133831 = ORIENTED_EDGE('',*,*,#133517,.F.); +#133832 = ORIENTED_EDGE('',*,*,#133632,.F.); +#133833 = ORIENTED_EDGE('',*,*,#133834,.T.); +#133834 = EDGE_CURVE('',#133611,#95287,#133835,.T.); +#133835 = SURFACE_CURVE('',#133836,(#133840,#133847),.PCURVE_S1.); +#133836 = LINE('',#133837,#133838); +#133837 = CARTESIAN_POINT('',(10.527847992439,3.65,0.75)); +#133838 = VECTOR('',#133839,1.); +#133839 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#133840 = PCURVE('',#95302,#133841); +#133841 = DEFINITIONAL_REPRESENTATION('',(#133842),#133846); +#133842 = LINE('',#133843,#133844); +#133843 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#133844 = VECTOR('',#133845,1.); +#133845 = DIRECTION('',(-3.563627120235E-016,-1.)); +#133846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133847 = PCURVE('',#95328,#133848); +#133848 = DEFINITIONAL_REPRESENTATION('',(#133849),#133853); +#133849 = LINE('',#133850,#133851); +#133850 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#133851 = VECTOR('',#133852,1.); +#133852 = DIRECTION('',(-1.,-3.00059940766E-063)); +#133853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133854 = ORIENTED_EDGE('',*,*,#95286,.F.); +#133855 = ADVANCED_FACE('',(#133856),#95328,.T.); +#133856 = FACE_BOUND('',#133857,.T.); +#133857 = EDGE_LOOP('',(#133858,#133859,#133860,#133881)); +#133858 = ORIENTED_EDGE('',*,*,#133834,.F.); +#133859 = ORIENTED_EDGE('',*,*,#133610,.T.); +#133860 = ORIENTED_EDGE('',*,*,#133861,.T.); +#133861 = EDGE_CURVE('',#133565,#95229,#133862,.T.); +#133862 = SURFACE_CURVE('',#133863,(#133867,#133874),.PCURVE_S1.); +#133863 = LINE('',#133864,#133865); +#133864 = CARTESIAN_POINT('',(10.527847992439,3.85,0.75)); +#133865 = VECTOR('',#133866,1.); +#133866 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#133867 = PCURVE('',#95328,#133868); +#133868 = DEFINITIONAL_REPRESENTATION('',(#133869),#133873); +#133869 = LINE('',#133870,#133871); +#133870 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133871 = VECTOR('',#133872,1.); +#133872 = DIRECTION('',(-1.,-3.00059940766E-063)); +#133873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133874 = PCURVE('',#95246,#133875); +#133875 = DEFINITIONAL_REPRESENTATION('',(#133876),#133880); +#133876 = LINE('',#133877,#133878); +#133877 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#133878 = VECTOR('',#133879,1.); +#133879 = DIRECTION('',(3.563627120235E-016,-1.)); +#133880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131400 = PCURVE('',#92910,#131401); -#131401 = DEFINITIONAL_REPRESENTATION('',(#131402),#131406); -#131402 = LINE('',#131403,#131404); -#131403 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131404 = VECTOR('',#131405,1.); -#131405 = DIRECTION('',(-3.563627120235E-016,-1.)); -#131406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131407 = ORIENTED_EDGE('',*,*,#92866,.F.); -#131408 = ADVANCED_FACE('',(#131409),#92910,.T.); -#131409 = FACE_BOUND('',#131410,.T.); -#131410 = EDGE_LOOP('',(#131411,#131412,#131413,#131414,#131415,#131416, - #131437,#131438,#131439,#131440,#131441,#131462)); -#131411 = ORIENTED_EDGE('',*,*,#131387,.F.); -#131412 = ORIENTED_EDGE('',*,*,#131337,.T.); -#131413 = ORIENTED_EDGE('',*,*,#131072,.T.); -#131414 = ORIENTED_EDGE('',*,*,#130947,.T.); -#131415 = ORIENTED_EDGE('',*,*,#130743,.T.); -#131416 = ORIENTED_EDGE('',*,*,#131417,.F.); -#131417 = EDGE_CURVE('',#130607,#130714,#131418,.T.); -#131418 = SURFACE_CURVE('',#131419,(#131423,#131430),.PCURVE_S1.); -#131419 = LINE('',#131420,#131421); -#131420 = CARTESIAN_POINT('',(11.,3.65,1.159810404338E-002)); -#131421 = VECTOR('',#131422,1.); -#131422 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#131423 = PCURVE('',#92910,#131424); -#131424 = DEFINITIONAL_REPRESENTATION('',(#131425),#131429); -#131425 = LINE('',#131426,#131427); -#131426 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#131427 = VECTOR('',#131428,1.); -#131428 = DIRECTION('',(1.,-2.101748079665E-016)); -#131429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131430 = PCURVE('',#130627,#131431); -#131431 = DEFINITIONAL_REPRESENTATION('',(#131432),#131436); -#131432 = LINE('',#131433,#131434); -#131433 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#131434 = VECTOR('',#131435,1.); -#131435 = DIRECTION('',(-1.194699204908E-017,-1.)); -#131436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131437 = ORIENTED_EDGE('',*,*,#130689,.F.); -#131438 = ORIENTED_EDGE('',*,*,#130817,.F.); -#131439 = ORIENTED_EDGE('',*,*,#131125,.F.); -#131440 = ORIENTED_EDGE('',*,*,#131240,.F.); -#131441 = ORIENTED_EDGE('',*,*,#131442,.T.); -#131442 = EDGE_CURVE('',#131219,#92895,#131443,.T.); -#131443 = SURFACE_CURVE('',#131444,(#131448,#131455),.PCURVE_S1.); -#131444 = LINE('',#131445,#131446); -#131445 = CARTESIAN_POINT('',(10.527847992439,3.65,0.75)); -#131446 = VECTOR('',#131447,1.); -#131447 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#131448 = PCURVE('',#92910,#131449); -#131449 = DEFINITIONAL_REPRESENTATION('',(#131450),#131454); -#131450 = LINE('',#131451,#131452); -#131451 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#131452 = VECTOR('',#131453,1.); -#131453 = DIRECTION('',(-3.563627120235E-016,-1.)); -#131454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131455 = PCURVE('',#92936,#131456); -#131456 = DEFINITIONAL_REPRESENTATION('',(#131457),#131461); -#131457 = LINE('',#131458,#131459); -#131458 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#131459 = VECTOR('',#131460,1.); -#131460 = DIRECTION('',(-1.,-3.00059940766E-063)); -#131461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131462 = ORIENTED_EDGE('',*,*,#92894,.F.); -#131463 = ADVANCED_FACE('',(#131464),#92936,.T.); -#131464 = FACE_BOUND('',#131465,.T.); -#131465 = EDGE_LOOP('',(#131466,#131467,#131468,#131489)); -#131466 = ORIENTED_EDGE('',*,*,#131442,.F.); -#131467 = ORIENTED_EDGE('',*,*,#131218,.T.); -#131468 = ORIENTED_EDGE('',*,*,#131469,.T.); -#131469 = EDGE_CURVE('',#131173,#92837,#131470,.T.); -#131470 = SURFACE_CURVE('',#131471,(#131475,#131482),.PCURVE_S1.); -#131471 = LINE('',#131472,#131473); -#131472 = CARTESIAN_POINT('',(10.527847992439,3.85,0.75)); -#131473 = VECTOR('',#131474,1.); -#131474 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#131475 = PCURVE('',#92936,#131476); -#131476 = DEFINITIONAL_REPRESENTATION('',(#131477),#131481); -#131477 = LINE('',#131478,#131479); -#131478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131479 = VECTOR('',#131480,1.); -#131480 = DIRECTION('',(-1.,-3.00059940766E-063)); -#131481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131482 = PCURVE('',#92854,#131483); -#131483 = DEFINITIONAL_REPRESENTATION('',(#131484),#131488); -#131484 = LINE('',#131485,#131486); -#131485 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#131486 = VECTOR('',#131487,1.); -#131487 = DIRECTION('',(3.563627120235E-016,-1.)); -#131488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131489 = ORIENTED_EDGE('',*,*,#92922,.F.); -#131490 = ADVANCED_FACE('',(#131491),#92854,.T.); -#131491 = FACE_BOUND('',#131492,.T.); -#131492 = EDGE_LOOP('',(#131493,#131494,#131495,#131496,#131497,#131498, - #131519,#131520,#131521,#131522,#131523,#131524)); -#131493 = ORIENTED_EDGE('',*,*,#131469,.F.); -#131494 = ORIENTED_EDGE('',*,*,#131172,.T.); -#131495 = ORIENTED_EDGE('',*,*,#131147,.T.); -#131496 = ORIENTED_EDGE('',*,*,#130867,.T.); -#131497 = ORIENTED_EDGE('',*,*,#130639,.T.); -#131498 = ORIENTED_EDGE('',*,*,#131499,.F.); -#131499 = EDGE_CURVE('',#130716,#130605,#131500,.T.); -#131500 = SURFACE_CURVE('',#131501,(#131505,#131512),.PCURVE_S1.); -#131501 = LINE('',#131502,#131503); -#131502 = CARTESIAN_POINT('',(11.,3.85,1.159810404338E-002)); -#131503 = VECTOR('',#131504,1.); -#131504 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#131505 = PCURVE('',#92854,#131506); -#131506 = DEFINITIONAL_REPRESENTATION('',(#131507),#131511); -#131507 = LINE('',#131508,#131509); -#131508 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#131509 = VECTOR('',#131510,1.); -#131510 = DIRECTION('',(1.,2.101748079665E-016)); -#131511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131512 = PCURVE('',#130627,#131513); -#131513 = DEFINITIONAL_REPRESENTATION('',(#131514),#131518); -#131514 = LINE('',#131515,#131516); -#131515 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#131516 = VECTOR('',#131517,1.); -#131517 = DIRECTION('',(1.194699204908E-017,1.)); -#131518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131519 = ORIENTED_EDGE('',*,*,#130793,.F.); -#131520 = ORIENTED_EDGE('',*,*,#130896,.F.); -#131521 = ORIENTED_EDGE('',*,*,#131050,.F.); -#131522 = ORIENTED_EDGE('',*,*,#131292,.F.); -#131523 = ORIENTED_EDGE('',*,*,#131365,.T.); -#131524 = ORIENTED_EDGE('',*,*,#92836,.F.); -#131525 = ADVANCED_FACE('',(#131526),#130627,.T.); -#131526 = FACE_BOUND('',#131527,.T.); -#131527 = EDGE_LOOP('',(#131528,#131529,#131530,#131531)); -#131528 = ORIENTED_EDGE('',*,*,#131417,.T.); -#131529 = ORIENTED_EDGE('',*,*,#130713,.T.); -#131530 = ORIENTED_EDGE('',*,*,#131499,.T.); -#131531 = ORIENTED_EDGE('',*,*,#130604,.T.); -#131532 = ADVANCED_FACE('',(#131533),#131547,.F.); -#131533 = FACE_BOUND('',#131534,.T.); -#131534 = EDGE_LOOP('',(#131535,#131570,#131593,#131620)); -#131535 = ORIENTED_EDGE('',*,*,#131536,.F.); -#131536 = EDGE_CURVE('',#131537,#131539,#131541,.T.); -#131537 = VERTEX_POINT('',#131538); -#131538 = CARTESIAN_POINT('',(11.,3.35,-0.208196358798)); -#131539 = VERTEX_POINT('',#131540); -#131540 = CARTESIAN_POINT('',(11.,3.15,-0.208196358798)); -#131541 = SURFACE_CURVE('',#131542,(#131546,#131558),.PCURVE_S1.); -#131542 = LINE('',#131543,#131544); -#131543 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#131544 = VECTOR('',#131545,1.); -#131545 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131546 = PCURVE('',#131547,#131552); -#131547 = PLANE('',#131548); -#131548 = AXIS2_PLACEMENT_3D('',#131549,#131550,#131551); -#131549 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#133881 = ORIENTED_EDGE('',*,*,#95314,.F.); +#133882 = ADVANCED_FACE('',(#133883),#95246,.T.); +#133883 = FACE_BOUND('',#133884,.T.); +#133884 = EDGE_LOOP('',(#133885,#133886,#133887,#133888,#133889,#133890, + #133911,#133912,#133913,#133914,#133915,#133916)); +#133885 = ORIENTED_EDGE('',*,*,#133861,.F.); +#133886 = ORIENTED_EDGE('',*,*,#133564,.T.); +#133887 = ORIENTED_EDGE('',*,*,#133539,.T.); +#133888 = ORIENTED_EDGE('',*,*,#133259,.T.); +#133889 = ORIENTED_EDGE('',*,*,#133031,.T.); +#133890 = ORIENTED_EDGE('',*,*,#133891,.F.); +#133891 = EDGE_CURVE('',#133108,#132997,#133892,.T.); +#133892 = SURFACE_CURVE('',#133893,(#133897,#133904),.PCURVE_S1.); +#133893 = LINE('',#133894,#133895); +#133894 = CARTESIAN_POINT('',(11.,3.85,1.159810404338E-002)); +#133895 = VECTOR('',#133896,1.); +#133896 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#133897 = PCURVE('',#95246,#133898); +#133898 = DEFINITIONAL_REPRESENTATION('',(#133899),#133903); +#133899 = LINE('',#133900,#133901); +#133900 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#133901 = VECTOR('',#133902,1.); +#133902 = DIRECTION('',(1.,2.101748079665E-016)); +#133903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133904 = PCURVE('',#133019,#133905); +#133905 = DEFINITIONAL_REPRESENTATION('',(#133906),#133910); +#133906 = LINE('',#133907,#133908); +#133907 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#133908 = VECTOR('',#133909,1.); +#133909 = DIRECTION('',(1.194699204908E-017,1.)); +#133910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133911 = ORIENTED_EDGE('',*,*,#133185,.F.); +#133912 = ORIENTED_EDGE('',*,*,#133288,.F.); +#133913 = ORIENTED_EDGE('',*,*,#133442,.F.); +#133914 = ORIENTED_EDGE('',*,*,#133684,.F.); +#133915 = ORIENTED_EDGE('',*,*,#133757,.T.); +#133916 = ORIENTED_EDGE('',*,*,#95228,.F.); +#133917 = ADVANCED_FACE('',(#133918),#133019,.T.); +#133918 = FACE_BOUND('',#133919,.T.); +#133919 = EDGE_LOOP('',(#133920,#133921,#133922,#133923)); +#133920 = ORIENTED_EDGE('',*,*,#133809,.T.); +#133921 = ORIENTED_EDGE('',*,*,#133105,.T.); +#133922 = ORIENTED_EDGE('',*,*,#133891,.T.); +#133923 = ORIENTED_EDGE('',*,*,#132996,.T.); +#133924 = ADVANCED_FACE('',(#133925),#133939,.F.); +#133925 = FACE_BOUND('',#133926,.T.); +#133926 = EDGE_LOOP('',(#133927,#133962,#133985,#134012)); +#133927 = ORIENTED_EDGE('',*,*,#133928,.F.); +#133928 = EDGE_CURVE('',#133929,#133931,#133933,.T.); +#133929 = VERTEX_POINT('',#133930); +#133930 = CARTESIAN_POINT('',(11.,3.35,-0.208196358798)); +#133931 = VERTEX_POINT('',#133932); +#133932 = CARTESIAN_POINT('',(11.,3.15,-0.208196358798)); +#133933 = SURFACE_CURVE('',#133934,(#133938,#133950),.PCURVE_S1.); +#133934 = LINE('',#133935,#133936); +#133935 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#133936 = VECTOR('',#133937,1.); +#133937 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#133938 = PCURVE('',#133939,#133944); +#133939 = PLANE('',#133940); +#133940 = AXIS2_PLACEMENT_3D('',#133941,#133942,#133943); +#133941 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#131550 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131551 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#131552 = DEFINITIONAL_REPRESENTATION('',(#131553),#131557); -#131553 = LINE('',#131554,#131555); -#131554 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#131555 = VECTOR('',#131556,1.); -#131556 = DIRECTION('',(4.440892098501E-016,-1.)); -#131557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131558 = PCURVE('',#131559,#131564); -#131559 = PLANE('',#131560); -#131560 = AXIS2_PLACEMENT_3D('',#131561,#131562,#131563); -#131561 = CARTESIAN_POINT('',(11.,3.25,-0.258196742327)); -#131562 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#131563 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131564 = DEFINITIONAL_REPRESENTATION('',(#131565),#131569); -#131565 = LINE('',#131566,#131567); -#131566 = CARTESIAN_POINT('',(-3.25,5.000038352949E-002)); -#131567 = VECTOR('',#131568,1.); -#131568 = DIRECTION('',(-1.,0.E+000)); -#131569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131570 = ORIENTED_EDGE('',*,*,#131571,.F.); -#131571 = EDGE_CURVE('',#131572,#131537,#131574,.T.); -#131572 = VERTEX_POINT('',#131573); -#131573 = CARTESIAN_POINT('',(10.740726081328,3.35,-0.208196358798)); -#131574 = SURFACE_CURVE('',#131575,(#131579,#131586),.PCURVE_S1.); -#131575 = LINE('',#131576,#131577); -#131576 = CARTESIAN_POINT('',(10.740726081328,3.35,-0.208196358798)); -#131577 = VECTOR('',#131578,1.); -#131578 = DIRECTION('',(1.,0.E+000,0.E+000)); -#131579 = PCURVE('',#131547,#131580); -#131580 = DEFINITIONAL_REPRESENTATION('',(#131581),#131585); -#131581 = LINE('',#131582,#131583); -#131582 = CARTESIAN_POINT('',(-1.7763568394E-015,3.35)); -#131583 = VECTOR('',#131584,1.); -#131584 = DIRECTION('',(-1.,0.E+000)); -#131585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131586 = PCURVE('',#92740,#131587); -#131587 = DEFINITIONAL_REPRESENTATION('',(#131588),#131592); -#131588 = LINE('',#131589,#131590); -#131589 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#131590 = VECTOR('',#131591,1.); -#131591 = DIRECTION('',(0.E+000,1.)); -#131592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131593 = ORIENTED_EDGE('',*,*,#131594,.F.); -#131594 = EDGE_CURVE('',#131595,#131572,#131597,.T.); -#131595 = VERTEX_POINT('',#131596); -#131596 = CARTESIAN_POINT('',(10.740726081328,3.15,-0.208196358798)); -#131597 = SURFACE_CURVE('',#131598,(#131602,#131609),.PCURVE_S1.); -#131598 = LINE('',#131599,#131600); -#131599 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#133942 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#133943 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#133944 = DEFINITIONAL_REPRESENTATION('',(#133945),#133949); +#133945 = LINE('',#133946,#133947); +#133946 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#133947 = VECTOR('',#133948,1.); +#133948 = DIRECTION('',(4.440892098501E-016,-1.)); +#133949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133950 = PCURVE('',#133951,#133956); +#133951 = PLANE('',#133952); +#133952 = AXIS2_PLACEMENT_3D('',#133953,#133954,#133955); +#133953 = CARTESIAN_POINT('',(11.,3.25,-0.258196742327)); +#133954 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#133955 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133956 = DEFINITIONAL_REPRESENTATION('',(#133957),#133961); +#133957 = LINE('',#133958,#133959); +#133958 = CARTESIAN_POINT('',(-3.25,5.000038352949E-002)); +#133959 = VECTOR('',#133960,1.); +#133960 = DIRECTION('',(-1.,0.E+000)); +#133961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133962 = ORIENTED_EDGE('',*,*,#133963,.F.); +#133963 = EDGE_CURVE('',#133964,#133929,#133966,.T.); +#133964 = VERTEX_POINT('',#133965); +#133965 = CARTESIAN_POINT('',(10.740726081328,3.35,-0.208196358798)); +#133966 = SURFACE_CURVE('',#133967,(#133971,#133978),.PCURVE_S1.); +#133967 = LINE('',#133968,#133969); +#133968 = CARTESIAN_POINT('',(10.740726081328,3.35,-0.208196358798)); +#133969 = VECTOR('',#133970,1.); +#133970 = DIRECTION('',(1.,0.E+000,0.E+000)); +#133971 = PCURVE('',#133939,#133972); +#133972 = DEFINITIONAL_REPRESENTATION('',(#133973),#133977); +#133973 = LINE('',#133974,#133975); +#133974 = CARTESIAN_POINT('',(-1.7763568394E-015,3.35)); +#133975 = VECTOR('',#133976,1.); +#133976 = DIRECTION('',(-1.,0.E+000)); +#133977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133978 = PCURVE('',#95132,#133979); +#133979 = DEFINITIONAL_REPRESENTATION('',(#133980),#133984); +#133980 = LINE('',#133981,#133982); +#133981 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#133982 = VECTOR('',#133983,1.); +#133983 = DIRECTION('',(0.E+000,1.)); +#133984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#133985 = ORIENTED_EDGE('',*,*,#133986,.F.); +#133986 = EDGE_CURVE('',#133987,#133964,#133989,.T.); +#133987 = VERTEX_POINT('',#133988); +#133988 = CARTESIAN_POINT('',(10.740726081328,3.15,-0.208196358798)); +#133989 = SURFACE_CURVE('',#133990,(#133994,#134001),.PCURVE_S1.); +#133990 = LINE('',#133991,#133992); +#133991 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#131600 = VECTOR('',#131601,1.); -#131601 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131602 = PCURVE('',#131547,#131603); -#131603 = DEFINITIONAL_REPRESENTATION('',(#131604),#131608); -#131604 = LINE('',#131605,#131606); -#131605 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131606 = VECTOR('',#131607,1.); -#131607 = DIRECTION('',(-4.440892098501E-016,1.)); -#131608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131609 = PCURVE('',#131610,#131615); -#131610 = CYLINDRICAL_SURFACE('',#131611,0.208574704164); -#131611 = AXIS2_PLACEMENT_3D('',#131612,#131613,#131614); -#131612 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#133992 = VECTOR('',#133993,1.); +#133993 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#133994 = PCURVE('',#133939,#133995); +#133995 = DEFINITIONAL_REPRESENTATION('',(#133996),#134000); +#133996 = LINE('',#133997,#133998); +#133997 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#133998 = VECTOR('',#133999,1.); +#133999 = DIRECTION('',(-4.440892098501E-016,1.)); +#134000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134001 = PCURVE('',#134002,#134007); +#134002 = CYLINDRICAL_SURFACE('',#134003,0.208574704164); +#134003 = AXIS2_PLACEMENT_3D('',#134004,#134005,#134006); +#134004 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#131613 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131614 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131615 = DEFINITIONAL_REPRESENTATION('',(#131616),#131619); -#131616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131617,#131618), +#134005 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134006 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134007 = DEFINITIONAL_REPRESENTATION('',(#134008),#134011); +#134008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134009,#134010), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#131617 = CARTESIAN_POINT('',(4.772630242227,-3.15)); -#131618 = CARTESIAN_POINT('',(4.772630242227,-3.35)); -#131619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131620 = ORIENTED_EDGE('',*,*,#131621,.T.); -#131621 = EDGE_CURVE('',#131595,#131539,#131622,.T.); -#131622 = SURFACE_CURVE('',#131623,(#131627,#131634),.PCURVE_S1.); -#131623 = LINE('',#131624,#131625); -#131624 = CARTESIAN_POINT('',(10.740726081328,3.15,-0.208196358798)); -#131625 = VECTOR('',#131626,1.); -#131626 = DIRECTION('',(1.,0.E+000,0.E+000)); -#131627 = PCURVE('',#131547,#131628); -#131628 = DEFINITIONAL_REPRESENTATION('',(#131629),#131633); -#131629 = LINE('',#131630,#131631); -#131630 = CARTESIAN_POINT('',(-1.7763568394E-015,3.15)); -#131631 = VECTOR('',#131632,1.); -#131632 = DIRECTION('',(-1.,0.E+000)); -#131633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131634 = PCURVE('',#92796,#131635); -#131635 = DEFINITIONAL_REPRESENTATION('',(#131636),#131640); -#131636 = LINE('',#131637,#131638); -#131637 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#131638 = VECTOR('',#131639,1.); -#131639 = DIRECTION('',(0.E+000,1.)); -#131640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131641 = ADVANCED_FACE('',(#131642),#131656,.F.); -#131642 = FACE_BOUND('',#131643,.T.); -#131643 = EDGE_LOOP('',(#131644,#131674,#131697,#131724)); -#131644 = ORIENTED_EDGE('',*,*,#131645,.F.); -#131645 = EDGE_CURVE('',#131646,#131648,#131650,.T.); -#131646 = VERTEX_POINT('',#131647); -#131647 = CARTESIAN_POINT('',(11.,3.15,-0.308197125857)); -#131648 = VERTEX_POINT('',#131649); -#131649 = CARTESIAN_POINT('',(11.,3.35,-0.308197125857)); -#131650 = SURFACE_CURVE('',#131651,(#131655,#131667),.PCURVE_S1.); -#131651 = LINE('',#131652,#131653); -#131652 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#131653 = VECTOR('',#131654,1.); -#131654 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131655 = PCURVE('',#131656,#131661); -#131656 = PLANE('',#131657); -#131657 = AXIS2_PLACEMENT_3D('',#131658,#131659,#131660); -#131658 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#134009 = CARTESIAN_POINT('',(4.772630242227,-3.15)); +#134010 = CARTESIAN_POINT('',(4.772630242227,-3.35)); +#134011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134012 = ORIENTED_EDGE('',*,*,#134013,.T.); +#134013 = EDGE_CURVE('',#133987,#133931,#134014,.T.); +#134014 = SURFACE_CURVE('',#134015,(#134019,#134026),.PCURVE_S1.); +#134015 = LINE('',#134016,#134017); +#134016 = CARTESIAN_POINT('',(10.740726081328,3.15,-0.208196358798)); +#134017 = VECTOR('',#134018,1.); +#134018 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134019 = PCURVE('',#133939,#134020); +#134020 = DEFINITIONAL_REPRESENTATION('',(#134021),#134025); +#134021 = LINE('',#134022,#134023); +#134022 = CARTESIAN_POINT('',(-1.7763568394E-015,3.15)); +#134023 = VECTOR('',#134024,1.); +#134024 = DIRECTION('',(-1.,0.E+000)); +#134025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134026 = PCURVE('',#95188,#134027); +#134027 = DEFINITIONAL_REPRESENTATION('',(#134028),#134032); +#134028 = LINE('',#134029,#134030); +#134029 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#134030 = VECTOR('',#134031,1.); +#134031 = DIRECTION('',(0.E+000,1.)); +#134032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134033 = ADVANCED_FACE('',(#134034),#134048,.F.); +#134034 = FACE_BOUND('',#134035,.T.); +#134035 = EDGE_LOOP('',(#134036,#134066,#134089,#134116)); +#134036 = ORIENTED_EDGE('',*,*,#134037,.F.); +#134037 = EDGE_CURVE('',#134038,#134040,#134042,.T.); +#134038 = VERTEX_POINT('',#134039); +#134039 = CARTESIAN_POINT('',(11.,3.15,-0.308197125857)); +#134040 = VERTEX_POINT('',#134041); +#134041 = CARTESIAN_POINT('',(11.,3.35,-0.308197125857)); +#134042 = SURFACE_CURVE('',#134043,(#134047,#134059),.PCURVE_S1.); +#134043 = LINE('',#134044,#134045); +#134044 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#134045 = VECTOR('',#134046,1.); +#134046 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134047 = PCURVE('',#134048,#134053); +#134048 = PLANE('',#134049); +#134049 = AXIS2_PLACEMENT_3D('',#134050,#134051,#134052); +#134050 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#131659 = DIRECTION('',(0.E+000,0.E+000,1.)); -#131660 = DIRECTION('',(1.,0.E+000,0.E+000)); -#131661 = DEFINITIONAL_REPRESENTATION('',(#131662),#131666); -#131662 = LINE('',#131663,#131664); -#131663 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#131664 = VECTOR('',#131665,1.); -#131665 = DIRECTION('',(4.440892098501E-016,1.)); -#131666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131667 = PCURVE('',#131559,#131668); -#131668 = DEFINITIONAL_REPRESENTATION('',(#131669),#131673); -#131669 = LINE('',#131670,#131671); -#131670 = CARTESIAN_POINT('',(-3.25,-5.000038352949E-002)); -#131671 = VECTOR('',#131672,1.); -#131672 = DIRECTION('',(1.,0.E+000)); -#131673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131674 = ORIENTED_EDGE('',*,*,#131675,.F.); -#131675 = EDGE_CURVE('',#131676,#131646,#131678,.T.); -#131676 = VERTEX_POINT('',#131677); -#131677 = CARTESIAN_POINT('',(10.74341632541,3.15,-0.308197125857)); -#131678 = SURFACE_CURVE('',#131679,(#131683,#131690),.PCURVE_S1.); -#131679 = LINE('',#131680,#131681); -#131680 = CARTESIAN_POINT('',(10.74341632541,3.15,-0.308197125857)); -#131681 = VECTOR('',#131682,1.); -#131682 = DIRECTION('',(1.,0.E+000,0.E+000)); -#131683 = PCURVE('',#131656,#131684); -#131684 = DEFINITIONAL_REPRESENTATION('',(#131685),#131689); -#131685 = LINE('',#131686,#131687); -#131686 = CARTESIAN_POINT('',(1.7763568394E-015,3.15)); -#131687 = VECTOR('',#131688,1.); -#131688 = DIRECTION('',(1.,0.E+000)); -#131689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131690 = PCURVE('',#92796,#131691); -#131691 = DEFINITIONAL_REPRESENTATION('',(#131692),#131696); -#131692 = LINE('',#131693,#131694); -#131693 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#131694 = VECTOR('',#131695,1.); -#131695 = DIRECTION('',(0.E+000,1.)); -#131696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131697 = ORIENTED_EDGE('',*,*,#131698,.F.); -#131698 = EDGE_CURVE('',#131699,#131676,#131701,.T.); -#131699 = VERTEX_POINT('',#131700); -#131700 = CARTESIAN_POINT('',(10.74341632541,3.35,-0.308197125857)); -#131701 = SURFACE_CURVE('',#131702,(#131706,#131713),.PCURVE_S1.); -#131702 = LINE('',#131703,#131704); -#131703 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#134051 = DIRECTION('',(0.E+000,0.E+000,1.)); +#134052 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134053 = DEFINITIONAL_REPRESENTATION('',(#134054),#134058); +#134054 = LINE('',#134055,#134056); +#134055 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#134056 = VECTOR('',#134057,1.); +#134057 = DIRECTION('',(4.440892098501E-016,1.)); +#134058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134059 = PCURVE('',#133951,#134060); +#134060 = DEFINITIONAL_REPRESENTATION('',(#134061),#134065); +#134061 = LINE('',#134062,#134063); +#134062 = CARTESIAN_POINT('',(-3.25,-5.000038352949E-002)); +#134063 = VECTOR('',#134064,1.); +#134064 = DIRECTION('',(1.,0.E+000)); +#134065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134066 = ORIENTED_EDGE('',*,*,#134067,.F.); +#134067 = EDGE_CURVE('',#134068,#134038,#134070,.T.); +#134068 = VERTEX_POINT('',#134069); +#134069 = CARTESIAN_POINT('',(10.74341632541,3.15,-0.308197125857)); +#134070 = SURFACE_CURVE('',#134071,(#134075,#134082),.PCURVE_S1.); +#134071 = LINE('',#134072,#134073); +#134072 = CARTESIAN_POINT('',(10.74341632541,3.15,-0.308197125857)); +#134073 = VECTOR('',#134074,1.); +#134074 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134075 = PCURVE('',#134048,#134076); +#134076 = DEFINITIONAL_REPRESENTATION('',(#134077),#134081); +#134077 = LINE('',#134078,#134079); +#134078 = CARTESIAN_POINT('',(1.7763568394E-015,3.15)); +#134079 = VECTOR('',#134080,1.); +#134080 = DIRECTION('',(1.,0.E+000)); +#134081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134082 = PCURVE('',#95188,#134083); +#134083 = DEFINITIONAL_REPRESENTATION('',(#134084),#134088); +#134084 = LINE('',#134085,#134086); +#134085 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#134086 = VECTOR('',#134087,1.); +#134087 = DIRECTION('',(0.E+000,1.)); +#134088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134089 = ORIENTED_EDGE('',*,*,#134090,.F.); +#134090 = EDGE_CURVE('',#134091,#134068,#134093,.T.); +#134091 = VERTEX_POINT('',#134092); +#134092 = CARTESIAN_POINT('',(10.74341632541,3.35,-0.308197125857)); +#134093 = SURFACE_CURVE('',#134094,(#134098,#134105),.PCURVE_S1.); +#134094 = LINE('',#134095,#134096); +#134095 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#131704 = VECTOR('',#131705,1.); -#131705 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131706 = PCURVE('',#131656,#131707); -#131707 = DEFINITIONAL_REPRESENTATION('',(#131708),#131712); -#131708 = LINE('',#131709,#131710); -#131709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131710 = VECTOR('',#131711,1.); -#131711 = DIRECTION('',(-4.440892098501E-016,-1.)); -#131712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131713 = PCURVE('',#131714,#131719); -#131714 = CYLINDRICAL_SURFACE('',#131715,0.308574064194); -#131715 = AXIS2_PLACEMENT_3D('',#131716,#131717,#131718); -#131716 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#134096 = VECTOR('',#134097,1.); +#134097 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134098 = PCURVE('',#134048,#134099); +#134099 = DEFINITIONAL_REPRESENTATION('',(#134100),#134104); +#134100 = LINE('',#134101,#134102); +#134101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134102 = VECTOR('',#134103,1.); +#134103 = DIRECTION('',(-4.440892098501E-016,-1.)); +#134104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134105 = PCURVE('',#134106,#134111); +#134106 = CYLINDRICAL_SURFACE('',#134107,0.308574064194); +#134107 = AXIS2_PLACEMENT_3D('',#134108,#134109,#134110); +#134108 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#131717 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131718 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131719 = DEFINITIONAL_REPRESENTATION('',(#131720),#131723); -#131720 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131721,#131722), +#134109 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134110 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134111 = DEFINITIONAL_REPRESENTATION('',(#134112),#134115); +#134112 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134113,#134114), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#131721 = CARTESIAN_POINT('',(4.761821717947,-3.35)); -#131722 = CARTESIAN_POINT('',(4.761821717947,-3.15)); -#131723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131724 = ORIENTED_EDGE('',*,*,#131725,.T.); -#131725 = EDGE_CURVE('',#131699,#131648,#131726,.T.); -#131726 = SURFACE_CURVE('',#131727,(#131731,#131738),.PCURVE_S1.); -#131727 = LINE('',#131728,#131729); -#131728 = CARTESIAN_POINT('',(10.74341632541,3.35,-0.308197125857)); -#131729 = VECTOR('',#131730,1.); -#131730 = DIRECTION('',(1.,0.E+000,0.E+000)); -#131731 = PCURVE('',#131656,#131732); -#131732 = DEFINITIONAL_REPRESENTATION('',(#131733),#131737); -#131733 = LINE('',#131734,#131735); -#131734 = CARTESIAN_POINT('',(1.7763568394E-015,3.35)); -#131735 = VECTOR('',#131736,1.); -#131736 = DIRECTION('',(1.,0.E+000)); -#131737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131738 = PCURVE('',#92740,#131739); -#131739 = DEFINITIONAL_REPRESENTATION('',(#131740),#131744); -#131740 = LINE('',#131741,#131742); -#131741 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#131742 = VECTOR('',#131743,1.); -#131743 = DIRECTION('',(0.E+000,1.)); -#131744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131745 = ADVANCED_FACE('',(#131746),#131610,.F.); -#131746 = FACE_BOUND('',#131747,.F.); -#131747 = EDGE_LOOP('',(#131748,#131771,#131798,#131823)); -#131748 = ORIENTED_EDGE('',*,*,#131749,.F.); -#131749 = EDGE_CURVE('',#131750,#131595,#131752,.T.); -#131750 = VERTEX_POINT('',#131751); -#131751 = CARTESIAN_POINT('',(10.51959417205,3.15,0.E+000)); -#131752 = SURFACE_CURVE('',#131753,(#131758,#131764),.PCURVE_S1.); -#131753 = CIRCLE('',#131754,0.208574704164); -#131754 = AXIS2_PLACEMENT_3D('',#131755,#131756,#131757); -#131755 = CARTESIAN_POINT('',(10.728168876214,3.15,2.640924866458E-017) - ); -#131756 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131757 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131758 = PCURVE('',#131610,#131759); -#131759 = DEFINITIONAL_REPRESENTATION('',(#131760),#131763); -#131760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131761,#131762), +#134113 = CARTESIAN_POINT('',(4.761821717947,-3.35)); +#134114 = CARTESIAN_POINT('',(4.761821717947,-3.15)); +#134115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134116 = ORIENTED_EDGE('',*,*,#134117,.T.); +#134117 = EDGE_CURVE('',#134091,#134040,#134118,.T.); +#134118 = SURFACE_CURVE('',#134119,(#134123,#134130),.PCURVE_S1.); +#134119 = LINE('',#134120,#134121); +#134120 = CARTESIAN_POINT('',(10.74341632541,3.35,-0.308197125857)); +#134121 = VECTOR('',#134122,1.); +#134122 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134123 = PCURVE('',#134048,#134124); +#134124 = DEFINITIONAL_REPRESENTATION('',(#134125),#134129); +#134125 = LINE('',#134126,#134127); +#134126 = CARTESIAN_POINT('',(1.7763568394E-015,3.35)); +#134127 = VECTOR('',#134128,1.); +#134128 = DIRECTION('',(1.,0.E+000)); +#134129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134130 = PCURVE('',#95132,#134131); +#134131 = DEFINITIONAL_REPRESENTATION('',(#134132),#134136); +#134132 = LINE('',#134133,#134134); +#134133 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#134134 = VECTOR('',#134135,1.); +#134135 = DIRECTION('',(0.E+000,1.)); +#134136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134137 = ADVANCED_FACE('',(#134138),#134002,.F.); +#134138 = FACE_BOUND('',#134139,.F.); +#134139 = EDGE_LOOP('',(#134140,#134163,#134190,#134215)); +#134140 = ORIENTED_EDGE('',*,*,#134141,.F.); +#134141 = EDGE_CURVE('',#134142,#133987,#134144,.T.); +#134142 = VERTEX_POINT('',#134143); +#134143 = CARTESIAN_POINT('',(10.51959417205,3.15,0.E+000)); +#134144 = SURFACE_CURVE('',#134145,(#134150,#134156),.PCURVE_S1.); +#134145 = CIRCLE('',#134146,0.208574704164); +#134146 = AXIS2_PLACEMENT_3D('',#134147,#134148,#134149); +#134147 = CARTESIAN_POINT('',(10.728168876214,3.15,2.640924866458E-017) + ); +#134148 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134149 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134150 = PCURVE('',#134002,#134151); +#134151 = DEFINITIONAL_REPRESENTATION('',(#134152),#134155); +#134152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134153,#134154), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#131761 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#131762 = CARTESIAN_POINT('',(4.772630242227,-3.15)); -#131763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134153 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#134154 = CARTESIAN_POINT('',(4.772630242227,-3.15)); +#134155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131764 = PCURVE('',#92796,#131765); -#131765 = DEFINITIONAL_REPRESENTATION('',(#131766),#131770); -#131766 = CIRCLE('',#131767,0.208574704164); -#131767 = AXIS2_PLACEMENT_2D('',#131768,#131769); -#131768 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#131769 = DIRECTION('',(0.E+000,1.)); -#131770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134156 = PCURVE('',#95188,#134157); +#134157 = DEFINITIONAL_REPRESENTATION('',(#134158),#134162); +#134158 = CIRCLE('',#134159,0.208574704164); +#134159 = AXIS2_PLACEMENT_2D('',#134160,#134161); +#134160 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#134161 = DIRECTION('',(0.E+000,1.)); +#134162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131771 = ORIENTED_EDGE('',*,*,#131772,.F.); -#131772 = EDGE_CURVE('',#131773,#131750,#131775,.T.); -#131773 = VERTEX_POINT('',#131774); -#131774 = CARTESIAN_POINT('',(10.51959417205,3.35,0.E+000)); -#131775 = SURFACE_CURVE('',#131776,(#131780,#131786),.PCURVE_S1.); -#131776 = LINE('',#131777,#131778); -#131777 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#134163 = ORIENTED_EDGE('',*,*,#134164,.F.); +#134164 = EDGE_CURVE('',#134165,#134142,#134167,.T.); +#134165 = VERTEX_POINT('',#134166); +#134166 = CARTESIAN_POINT('',(10.51959417205,3.35,0.E+000)); +#134167 = SURFACE_CURVE('',#134168,(#134172,#134178),.PCURVE_S1.); +#134168 = LINE('',#134169,#134170); +#134169 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#131778 = VECTOR('',#131779,1.); -#131779 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131780 = PCURVE('',#131610,#131781); -#131781 = DEFINITIONAL_REPRESENTATION('',(#131782),#131785); -#131782 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131783,#131784), +#134170 = VECTOR('',#134171,1.); +#134171 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134172 = PCURVE('',#134002,#134173); +#134173 = DEFINITIONAL_REPRESENTATION('',(#134174),#134177); +#134174 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134175,#134176), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#131783 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#131784 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#131785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134175 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#134176 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#134177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131786 = PCURVE('',#131787,#131792); -#131787 = PLANE('',#131788); -#131788 = AXIS2_PLACEMENT_3D('',#131789,#131790,#131791); -#131789 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#134178 = PCURVE('',#134179,#134184); +#134179 = PLANE('',#134180); +#134180 = AXIS2_PLACEMENT_3D('',#134181,#134182,#134183); +#134181 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#131790 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131791 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131792 = DEFINITIONAL_REPRESENTATION('',(#131793),#131797); -#131793 = LINE('',#131794,#131795); -#131794 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#131795 = VECTOR('',#131796,1.); -#131796 = DIRECTION('',(-1.,0.E+000)); -#131797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131798 = ORIENTED_EDGE('',*,*,#131799,.T.); -#131799 = EDGE_CURVE('',#131773,#131572,#131800,.T.); -#131800 = SURFACE_CURVE('',#131801,(#131806,#131812),.PCURVE_S1.); -#131801 = CIRCLE('',#131802,0.208574704164); -#131802 = AXIS2_PLACEMENT_3D('',#131803,#131804,#131805); -#131803 = CARTESIAN_POINT('',(10.728168876214,3.35,2.640924866458E-017) - ); -#131804 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131805 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131806 = PCURVE('',#131610,#131807); -#131807 = DEFINITIONAL_REPRESENTATION('',(#131808),#131811); -#131808 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131809,#131810), +#134182 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134183 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134184 = DEFINITIONAL_REPRESENTATION('',(#134185),#134189); +#134185 = LINE('',#134186,#134187); +#134186 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#134187 = VECTOR('',#134188,1.); +#134188 = DIRECTION('',(-1.,0.E+000)); +#134189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134190 = ORIENTED_EDGE('',*,*,#134191,.T.); +#134191 = EDGE_CURVE('',#134165,#133964,#134192,.T.); +#134192 = SURFACE_CURVE('',#134193,(#134198,#134204),.PCURVE_S1.); +#134193 = CIRCLE('',#134194,0.208574704164); +#134194 = AXIS2_PLACEMENT_3D('',#134195,#134196,#134197); +#134195 = CARTESIAN_POINT('',(10.728168876214,3.35,2.640924866458E-017) + ); +#134196 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134197 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134198 = PCURVE('',#134002,#134199); +#134199 = DEFINITIONAL_REPRESENTATION('',(#134200),#134203); +#134200 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134201,#134202), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#131809 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#131810 = CARTESIAN_POINT('',(4.772630242227,-3.35)); -#131811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134201 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#134202 = CARTESIAN_POINT('',(4.772630242227,-3.35)); +#134203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131812 = PCURVE('',#92740,#131813); -#131813 = DEFINITIONAL_REPRESENTATION('',(#131814),#131822); -#131814 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131815,#131816,#131817, - #131818,#131819,#131820,#131821),.UNSPECIFIED.,.T.,.F.) +#134204 = PCURVE('',#95132,#134205); +#134205 = DEFINITIONAL_REPRESENTATION('',(#134206),#134214); +#134206 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134207,#134208,#134209, + #134210,#134211,#134212,#134213),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#131815 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#131816 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#131817 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#131818 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#131819 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#131820 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#131821 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#131822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131823 = ORIENTED_EDGE('',*,*,#131594,.F.); -#131824 = ADVANCED_FACE('',(#131825),#131714,.T.); -#131825 = FACE_BOUND('',#131826,.T.); -#131826 = EDGE_LOOP('',(#131827,#131877,#131878,#131924)); -#131827 = ORIENTED_EDGE('',*,*,#131828,.T.); -#131828 = EDGE_CURVE('',#131829,#131699,#131831,.T.); -#131829 = VERTEX_POINT('',#131830); -#131830 = CARTESIAN_POINT('',(10.419594812019,3.35,0.E+000)); -#131831 = SURFACE_CURVE('',#131832,(#131837,#131866),.PCURVE_S1.); -#131832 = CIRCLE('',#131833,0.308574064194); -#131833 = AXIS2_PLACEMENT_3D('',#131834,#131835,#131836); -#131834 = CARTESIAN_POINT('',(10.728168876214,3.35,2.640924866458E-017) - ); -#131835 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131836 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131837 = PCURVE('',#131714,#131838); -#131838 = DEFINITIONAL_REPRESENTATION('',(#131839),#131865); -#131839 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#131840,#131841,#131842, - #131843,#131844,#131845,#131846,#131847,#131848,#131849,#131850, - #131851,#131852,#131853,#131854,#131855,#131856,#131857,#131858, - #131859,#131860,#131861,#131862,#131863,#131864),.UNSPECIFIED.,.F., +#134207 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#134208 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#134209 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#134210 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#134211 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#134212 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#134213 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#134214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134215 = ORIENTED_EDGE('',*,*,#133986,.F.); +#134216 = ADVANCED_FACE('',(#134217),#134106,.T.); +#134217 = FACE_BOUND('',#134218,.T.); +#134218 = EDGE_LOOP('',(#134219,#134269,#134270,#134316)); +#134219 = ORIENTED_EDGE('',*,*,#134220,.T.); +#134220 = EDGE_CURVE('',#134221,#134091,#134223,.T.); +#134221 = VERTEX_POINT('',#134222); +#134222 = CARTESIAN_POINT('',(10.419594812019,3.35,0.E+000)); +#134223 = SURFACE_CURVE('',#134224,(#134229,#134258),.PCURVE_S1.); +#134224 = CIRCLE('',#134225,0.308574064194); +#134225 = AXIS2_PLACEMENT_3D('',#134226,#134227,#134228); +#134226 = CARTESIAN_POINT('',(10.728168876214,3.35,2.640924866458E-017) + ); +#134227 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134228 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134229 = PCURVE('',#134106,#134230); +#134230 = DEFINITIONAL_REPRESENTATION('',(#134231),#134257); +#134231 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134232,#134233,#134234, + #134235,#134236,#134237,#134238,#134239,#134240,#134241,#134242, + #134243,#134244,#134245,#134246,#134247,#134248,#134249,#134250, + #134251,#134252,#134253,#134254,#134255,#134256),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -162430,71 +165432,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#131840 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#131841 = CARTESIAN_POINT('',(3.166141578807,-3.35)); -#131842 = CARTESIAN_POINT('',(3.215239429242,-3.35)); -#131843 = CARTESIAN_POINT('',(3.288886204895,-3.35)); -#131844 = CARTESIAN_POINT('',(3.362532980548,-3.35)); -#131845 = CARTESIAN_POINT('',(3.4361797562,-3.35)); -#131846 = CARTESIAN_POINT('',(3.509826531853,-3.35)); -#131847 = CARTESIAN_POINT('',(3.583473307505,-3.35)); -#131848 = CARTESIAN_POINT('',(3.657120083158,-3.35)); -#131849 = CARTESIAN_POINT('',(3.730766858811,-3.35)); -#131850 = CARTESIAN_POINT('',(3.804413634463,-3.35)); -#131851 = CARTESIAN_POINT('',(3.878060410116,-3.35)); -#131852 = CARTESIAN_POINT('',(3.951707185768,-3.35)); -#131853 = CARTESIAN_POINT('',(4.025353961421,-3.35)); -#131854 = CARTESIAN_POINT('',(4.099000737074,-3.35)); -#131855 = CARTESIAN_POINT('',(4.172647512726,-3.35)); -#131856 = CARTESIAN_POINT('',(4.246294288379,-3.35)); -#131857 = CARTESIAN_POINT('',(4.319941064031,-3.35)); -#131858 = CARTESIAN_POINT('',(4.393587839684,-3.35)); -#131859 = CARTESIAN_POINT('',(4.467234615337,-3.35)); -#131860 = CARTESIAN_POINT('',(4.540881390989,-3.35)); -#131861 = CARTESIAN_POINT('',(4.614528166642,-3.35)); -#131862 = CARTESIAN_POINT('',(4.688174942294,-3.35)); -#131863 = CARTESIAN_POINT('',(4.737272792729,-3.35)); -#131864 = CARTESIAN_POINT('',(4.761821717947,-3.35)); -#131865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131866 = PCURVE('',#92740,#131867); -#131867 = DEFINITIONAL_REPRESENTATION('',(#131868),#131876); -#131868 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#131869,#131870,#131871, - #131872,#131873,#131874,#131875),.UNSPECIFIED.,.T.,.F.) +#134232 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#134233 = CARTESIAN_POINT('',(3.166141578807,-3.35)); +#134234 = CARTESIAN_POINT('',(3.215239429242,-3.35)); +#134235 = CARTESIAN_POINT('',(3.288886204895,-3.35)); +#134236 = CARTESIAN_POINT('',(3.362532980548,-3.35)); +#134237 = CARTESIAN_POINT('',(3.4361797562,-3.35)); +#134238 = CARTESIAN_POINT('',(3.509826531853,-3.35)); +#134239 = CARTESIAN_POINT('',(3.583473307505,-3.35)); +#134240 = CARTESIAN_POINT('',(3.657120083158,-3.35)); +#134241 = CARTESIAN_POINT('',(3.730766858811,-3.35)); +#134242 = CARTESIAN_POINT('',(3.804413634463,-3.35)); +#134243 = CARTESIAN_POINT('',(3.878060410116,-3.35)); +#134244 = CARTESIAN_POINT('',(3.951707185768,-3.35)); +#134245 = CARTESIAN_POINT('',(4.025353961421,-3.35)); +#134246 = CARTESIAN_POINT('',(4.099000737074,-3.35)); +#134247 = CARTESIAN_POINT('',(4.172647512726,-3.35)); +#134248 = CARTESIAN_POINT('',(4.246294288379,-3.35)); +#134249 = CARTESIAN_POINT('',(4.319941064031,-3.35)); +#134250 = CARTESIAN_POINT('',(4.393587839684,-3.35)); +#134251 = CARTESIAN_POINT('',(4.467234615337,-3.35)); +#134252 = CARTESIAN_POINT('',(4.540881390989,-3.35)); +#134253 = CARTESIAN_POINT('',(4.614528166642,-3.35)); +#134254 = CARTESIAN_POINT('',(4.688174942294,-3.35)); +#134255 = CARTESIAN_POINT('',(4.737272792729,-3.35)); +#134256 = CARTESIAN_POINT('',(4.761821717947,-3.35)); +#134257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134258 = PCURVE('',#95132,#134259); +#134259 = DEFINITIONAL_REPRESENTATION('',(#134260),#134268); +#134260 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134261,#134262,#134263, + #134264,#134265,#134266,#134267),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#131869 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#131870 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#131871 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#131872 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#131873 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#131874 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#131875 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#131876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131877 = ORIENTED_EDGE('',*,*,#131698,.T.); -#131878 = ORIENTED_EDGE('',*,*,#131879,.F.); -#131879 = EDGE_CURVE('',#131880,#131676,#131882,.T.); -#131880 = VERTEX_POINT('',#131881); -#131881 = CARTESIAN_POINT('',(10.419594812019,3.15,0.E+000)); -#131882 = SURFACE_CURVE('',#131883,(#131888,#131917),.PCURVE_S1.); -#131883 = CIRCLE('',#131884,0.308574064194); -#131884 = AXIS2_PLACEMENT_3D('',#131885,#131886,#131887); -#131885 = CARTESIAN_POINT('',(10.728168876214,3.15,2.640924866458E-017) - ); -#131886 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131887 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#131888 = PCURVE('',#131714,#131889); -#131889 = DEFINITIONAL_REPRESENTATION('',(#131890),#131916); -#131890 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#131891,#131892,#131893, - #131894,#131895,#131896,#131897,#131898,#131899,#131900,#131901, - #131902,#131903,#131904,#131905,#131906,#131907,#131908,#131909, - #131910,#131911,#131912,#131913,#131914,#131915),.UNSPECIFIED.,.F., +#134261 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#134262 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#134263 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#134264 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#134265 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#134266 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#134267 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#134268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134269 = ORIENTED_EDGE('',*,*,#134090,.T.); +#134270 = ORIENTED_EDGE('',*,*,#134271,.F.); +#134271 = EDGE_CURVE('',#134272,#134068,#134274,.T.); +#134272 = VERTEX_POINT('',#134273); +#134273 = CARTESIAN_POINT('',(10.419594812019,3.15,0.E+000)); +#134274 = SURFACE_CURVE('',#134275,(#134280,#134309),.PCURVE_S1.); +#134275 = CIRCLE('',#134276,0.308574064194); +#134276 = AXIS2_PLACEMENT_3D('',#134277,#134278,#134279); +#134277 = CARTESIAN_POINT('',(10.728168876214,3.15,2.640924866458E-017) + ); +#134278 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134279 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134280 = PCURVE('',#134106,#134281); +#134281 = DEFINITIONAL_REPRESENTATION('',(#134282),#134308); +#134282 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134283,#134284,#134285, + #134286,#134287,#134288,#134289,#134290,#134291,#134292,#134293, + #134294,#134295,#134296,#134297,#134298,#134299,#134300,#134301, + #134302,#134303,#134304,#134305,#134306,#134307),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -162502,275 +165504,275 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#131891 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#131892 = CARTESIAN_POINT('',(3.166141578807,-3.15)); -#131893 = CARTESIAN_POINT('',(3.215239429242,-3.15)); -#131894 = CARTESIAN_POINT('',(3.288886204895,-3.15)); -#131895 = CARTESIAN_POINT('',(3.362532980548,-3.15)); -#131896 = CARTESIAN_POINT('',(3.4361797562,-3.15)); -#131897 = CARTESIAN_POINT('',(3.509826531853,-3.15)); -#131898 = CARTESIAN_POINT('',(3.583473307505,-3.15)); -#131899 = CARTESIAN_POINT('',(3.657120083158,-3.15)); -#131900 = CARTESIAN_POINT('',(3.730766858811,-3.15)); -#131901 = CARTESIAN_POINT('',(3.804413634463,-3.15)); -#131902 = CARTESIAN_POINT('',(3.878060410116,-3.15)); -#131903 = CARTESIAN_POINT('',(3.951707185768,-3.15)); -#131904 = CARTESIAN_POINT('',(4.025353961421,-3.15)); -#131905 = CARTESIAN_POINT('',(4.099000737074,-3.15)); -#131906 = CARTESIAN_POINT('',(4.172647512726,-3.15)); -#131907 = CARTESIAN_POINT('',(4.246294288379,-3.15)); -#131908 = CARTESIAN_POINT('',(4.319941064031,-3.15)); -#131909 = CARTESIAN_POINT('',(4.393587839684,-3.15)); -#131910 = CARTESIAN_POINT('',(4.467234615337,-3.15)); -#131911 = CARTESIAN_POINT('',(4.540881390989,-3.15)); -#131912 = CARTESIAN_POINT('',(4.614528166642,-3.15)); -#131913 = CARTESIAN_POINT('',(4.688174942294,-3.15)); -#131914 = CARTESIAN_POINT('',(4.737272792729,-3.15)); -#131915 = CARTESIAN_POINT('',(4.761821717947,-3.15)); -#131916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131917 = PCURVE('',#92796,#131918); -#131918 = DEFINITIONAL_REPRESENTATION('',(#131919),#131923); -#131919 = CIRCLE('',#131920,0.308574064194); -#131920 = AXIS2_PLACEMENT_2D('',#131921,#131922); -#131921 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#131922 = DIRECTION('',(0.E+000,1.)); -#131923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131924 = ORIENTED_EDGE('',*,*,#131925,.T.); -#131925 = EDGE_CURVE('',#131880,#131829,#131926,.T.); -#131926 = SURFACE_CURVE('',#131927,(#131931,#131937),.PCURVE_S1.); -#131927 = LINE('',#131928,#131929); -#131928 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#134283 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#134284 = CARTESIAN_POINT('',(3.166141578807,-3.15)); +#134285 = CARTESIAN_POINT('',(3.215239429242,-3.15)); +#134286 = CARTESIAN_POINT('',(3.288886204895,-3.15)); +#134287 = CARTESIAN_POINT('',(3.362532980548,-3.15)); +#134288 = CARTESIAN_POINT('',(3.4361797562,-3.15)); +#134289 = CARTESIAN_POINT('',(3.509826531853,-3.15)); +#134290 = CARTESIAN_POINT('',(3.583473307505,-3.15)); +#134291 = CARTESIAN_POINT('',(3.657120083158,-3.15)); +#134292 = CARTESIAN_POINT('',(3.730766858811,-3.15)); +#134293 = CARTESIAN_POINT('',(3.804413634463,-3.15)); +#134294 = CARTESIAN_POINT('',(3.878060410116,-3.15)); +#134295 = CARTESIAN_POINT('',(3.951707185768,-3.15)); +#134296 = CARTESIAN_POINT('',(4.025353961421,-3.15)); +#134297 = CARTESIAN_POINT('',(4.099000737074,-3.15)); +#134298 = CARTESIAN_POINT('',(4.172647512726,-3.15)); +#134299 = CARTESIAN_POINT('',(4.246294288379,-3.15)); +#134300 = CARTESIAN_POINT('',(4.319941064031,-3.15)); +#134301 = CARTESIAN_POINT('',(4.393587839684,-3.15)); +#134302 = CARTESIAN_POINT('',(4.467234615337,-3.15)); +#134303 = CARTESIAN_POINT('',(4.540881390989,-3.15)); +#134304 = CARTESIAN_POINT('',(4.614528166642,-3.15)); +#134305 = CARTESIAN_POINT('',(4.688174942294,-3.15)); +#134306 = CARTESIAN_POINT('',(4.737272792729,-3.15)); +#134307 = CARTESIAN_POINT('',(4.761821717947,-3.15)); +#134308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134309 = PCURVE('',#95188,#134310); +#134310 = DEFINITIONAL_REPRESENTATION('',(#134311),#134315); +#134311 = CIRCLE('',#134312,0.308574064194); +#134312 = AXIS2_PLACEMENT_2D('',#134313,#134314); +#134313 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#134314 = DIRECTION('',(0.E+000,1.)); +#134315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134316 = ORIENTED_EDGE('',*,*,#134317,.T.); +#134317 = EDGE_CURVE('',#134272,#134221,#134318,.T.); +#134318 = SURFACE_CURVE('',#134319,(#134323,#134329),.PCURVE_S1.); +#134319 = LINE('',#134320,#134321); +#134320 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#131929 = VECTOR('',#131930,1.); -#131930 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131931 = PCURVE('',#131714,#131932); -#131932 = DEFINITIONAL_REPRESENTATION('',(#131933),#131936); -#131933 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131934,#131935), +#134321 = VECTOR('',#134322,1.); +#134322 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134323 = PCURVE('',#134106,#134324); +#134324 = DEFINITIONAL_REPRESENTATION('',(#134325),#134328); +#134325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134326,#134327), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#131934 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#131935 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#131936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134326 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#134327 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#134328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131937 = PCURVE('',#131938,#131943); -#131938 = PLANE('',#131939); -#131939 = AXIS2_PLACEMENT_3D('',#131940,#131941,#131942); -#131940 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#134329 = PCURVE('',#134330,#134335); +#134330 = PLANE('',#134331); +#134331 = AXIS2_PLACEMENT_3D('',#134332,#134333,#134334); +#134332 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#131941 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131942 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#131943 = DEFINITIONAL_REPRESENTATION('',(#131944),#131948); -#131944 = LINE('',#131945,#131946); -#131945 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#131946 = VECTOR('',#131947,1.); -#131947 = DIRECTION('',(-1.,0.E+000)); -#131948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131949 = ADVANCED_FACE('',(#131950),#131938,.T.); -#131950 = FACE_BOUND('',#131951,.T.); -#131951 = EDGE_LOOP('',(#131952,#131981,#132002,#132003)); -#131952 = ORIENTED_EDGE('',*,*,#131953,.T.); -#131953 = EDGE_CURVE('',#131954,#131956,#131958,.T.); -#131954 = VERTEX_POINT('',#131955); -#131955 = CARTESIAN_POINT('',(10.419594812019,3.15,0.530776333563)); -#131956 = VERTEX_POINT('',#131957); -#131957 = CARTESIAN_POINT('',(10.419594812019,3.35,0.530776333563)); -#131958 = SURFACE_CURVE('',#131959,(#131963,#131970),.PCURVE_S1.); -#131959 = LINE('',#131960,#131961); -#131960 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#134333 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134334 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134335 = DEFINITIONAL_REPRESENTATION('',(#134336),#134340); +#134336 = LINE('',#134337,#134338); +#134337 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#134338 = VECTOR('',#134339,1.); +#134339 = DIRECTION('',(-1.,0.E+000)); +#134340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134341 = ADVANCED_FACE('',(#134342),#134330,.T.); +#134342 = FACE_BOUND('',#134343,.T.); +#134343 = EDGE_LOOP('',(#134344,#134373,#134394,#134395)); +#134344 = ORIENTED_EDGE('',*,*,#134345,.T.); +#134345 = EDGE_CURVE('',#134346,#134348,#134350,.T.); +#134346 = VERTEX_POINT('',#134347); +#134347 = CARTESIAN_POINT('',(10.419594812019,3.15,0.530776333563)); +#134348 = VERTEX_POINT('',#134349); +#134349 = CARTESIAN_POINT('',(10.419594812019,3.35,0.530776333563)); +#134350 = SURFACE_CURVE('',#134351,(#134355,#134362),.PCURVE_S1.); +#134351 = LINE('',#134352,#134353); +#134352 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#131961 = VECTOR('',#131962,1.); -#131962 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131963 = PCURVE('',#131938,#131964); -#131964 = DEFINITIONAL_REPRESENTATION('',(#131965),#131969); -#131965 = LINE('',#131966,#131967); -#131966 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#131967 = VECTOR('',#131968,1.); -#131968 = DIRECTION('',(-1.,0.E+000)); -#131969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131970 = PCURVE('',#131971,#131976); -#131971 = CYLINDRICAL_SURFACE('',#131972,0.119270391569); -#131972 = AXIS2_PLACEMENT_3D('',#131973,#131974,#131975); -#131973 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#134353 = VECTOR('',#134354,1.); +#134354 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134355 = PCURVE('',#134330,#134356); +#134356 = DEFINITIONAL_REPRESENTATION('',(#134357),#134361); +#134357 = LINE('',#134358,#134359); +#134358 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134359 = VECTOR('',#134360,1.); +#134360 = DIRECTION('',(-1.,0.E+000)); +#134361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134362 = PCURVE('',#134363,#134368); +#134363 = CYLINDRICAL_SURFACE('',#134364,0.119270391569); +#134364 = AXIS2_PLACEMENT_3D('',#134365,#134366,#134367); +#134365 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#131974 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#131975 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#131976 = DEFINITIONAL_REPRESENTATION('',(#131977),#131980); -#131977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#131978,#131979), +#134366 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134367 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134368 = DEFINITIONAL_REPRESENTATION('',(#134369),#134372); +#134369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134370,#134371), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#131978 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#131979 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#131980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134370 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#134371 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#134372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134373 = ORIENTED_EDGE('',*,*,#134374,.T.); +#134374 = EDGE_CURVE('',#134348,#134221,#134375,.T.); +#134375 = SURFACE_CURVE('',#134376,(#134380,#134387),.PCURVE_S1.); +#134376 = LINE('',#134377,#134378); +#134377 = CARTESIAN_POINT('',(10.419594812019,3.35,0.530776333563)); +#134378 = VECTOR('',#134379,1.); +#134379 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#134380 = PCURVE('',#134330,#134381); +#134381 = DEFINITIONAL_REPRESENTATION('',(#134382),#134386); +#134382 = LINE('',#134383,#134384); +#134383 = CARTESIAN_POINT('',(-3.35,0.E+000)); +#134384 = VECTOR('',#134385,1.); +#134385 = DIRECTION('',(0.E+000,-1.)); +#134386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134387 = PCURVE('',#95132,#134388); +#134388 = DEFINITIONAL_REPRESENTATION('',(#134389),#134393); +#134389 = LINE('',#134390,#134391); +#134390 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#134391 = VECTOR('',#134392,1.); +#134392 = DIRECTION('',(-1.,0.E+000)); +#134393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134394 = ORIENTED_EDGE('',*,*,#134317,.F.); +#134395 = ORIENTED_EDGE('',*,*,#134396,.F.); +#134396 = EDGE_CURVE('',#134346,#134272,#134397,.T.); +#134397 = SURFACE_CURVE('',#134398,(#134402,#134409),.PCURVE_S1.); +#134398 = LINE('',#134399,#134400); +#134399 = CARTESIAN_POINT('',(10.419594812019,3.15,0.530776333563)); +#134400 = VECTOR('',#134401,1.); +#134401 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#134402 = PCURVE('',#134330,#134403); +#134403 = DEFINITIONAL_REPRESENTATION('',(#134404),#134408); +#134404 = LINE('',#134405,#134406); +#134405 = CARTESIAN_POINT('',(-3.15,0.E+000)); +#134406 = VECTOR('',#134407,1.); +#134407 = DIRECTION('',(0.E+000,-1.)); +#134408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134409 = PCURVE('',#95188,#134410); +#134410 = DEFINITIONAL_REPRESENTATION('',(#134411),#134415); +#134411 = LINE('',#134412,#134413); +#134412 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#134413 = VECTOR('',#134414,1.); +#134414 = DIRECTION('',(1.,0.E+000)); +#134415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#131981 = ORIENTED_EDGE('',*,*,#131982,.T.); -#131982 = EDGE_CURVE('',#131956,#131829,#131983,.T.); -#131983 = SURFACE_CURVE('',#131984,(#131988,#131995),.PCURVE_S1.); -#131984 = LINE('',#131985,#131986); -#131985 = CARTESIAN_POINT('',(10.419594812019,3.35,0.530776333563)); -#131986 = VECTOR('',#131987,1.); -#131987 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#131988 = PCURVE('',#131938,#131989); -#131989 = DEFINITIONAL_REPRESENTATION('',(#131990),#131994); -#131990 = LINE('',#131991,#131992); -#131991 = CARTESIAN_POINT('',(-3.35,0.E+000)); -#131992 = VECTOR('',#131993,1.); -#131993 = DIRECTION('',(0.E+000,-1.)); -#131994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#131995 = PCURVE('',#92740,#131996); -#131996 = DEFINITIONAL_REPRESENTATION('',(#131997),#132001); -#131997 = LINE('',#131998,#131999); -#131998 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#131999 = VECTOR('',#132000,1.); -#132000 = DIRECTION('',(-1.,0.E+000)); -#132001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132002 = ORIENTED_EDGE('',*,*,#131925,.F.); -#132003 = ORIENTED_EDGE('',*,*,#132004,.F.); -#132004 = EDGE_CURVE('',#131954,#131880,#132005,.T.); -#132005 = SURFACE_CURVE('',#132006,(#132010,#132017),.PCURVE_S1.); -#132006 = LINE('',#132007,#132008); -#132007 = CARTESIAN_POINT('',(10.419594812019,3.15,0.530776333563)); -#132008 = VECTOR('',#132009,1.); -#132009 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132010 = PCURVE('',#131938,#132011); -#132011 = DEFINITIONAL_REPRESENTATION('',(#132012),#132016); -#132012 = LINE('',#132013,#132014); -#132013 = CARTESIAN_POINT('',(-3.15,0.E+000)); -#132014 = VECTOR('',#132015,1.); -#132015 = DIRECTION('',(0.E+000,-1.)); -#132016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132017 = PCURVE('',#92796,#132018); -#132018 = DEFINITIONAL_REPRESENTATION('',(#132019),#132023); -#132019 = LINE('',#132020,#132021); -#132020 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#132021 = VECTOR('',#132022,1.); -#132022 = DIRECTION('',(1.,0.E+000)); -#132023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132024 = ADVANCED_FACE('',(#132025),#131787,.T.); -#132025 = FACE_BOUND('',#132026,.T.); -#132026 = EDGE_LOOP('',(#132027,#132056,#132077,#132078)); -#132027 = ORIENTED_EDGE('',*,*,#132028,.T.); -#132028 = EDGE_CURVE('',#132029,#132031,#132033,.T.); -#132029 = VERTEX_POINT('',#132030); -#132030 = CARTESIAN_POINT('',(10.51959417205,3.35,0.530776333563)); -#132031 = VERTEX_POINT('',#132032); -#132032 = CARTESIAN_POINT('',(10.51959417205,3.15,0.530776333563)); -#132033 = SURFACE_CURVE('',#132034,(#132038,#132045),.PCURVE_S1.); -#132034 = LINE('',#132035,#132036); -#132035 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#134416 = ADVANCED_FACE('',(#134417),#134179,.T.); +#134417 = FACE_BOUND('',#134418,.T.); +#134418 = EDGE_LOOP('',(#134419,#134448,#134469,#134470)); +#134419 = ORIENTED_EDGE('',*,*,#134420,.T.); +#134420 = EDGE_CURVE('',#134421,#134423,#134425,.T.); +#134421 = VERTEX_POINT('',#134422); +#134422 = CARTESIAN_POINT('',(10.51959417205,3.35,0.530776333563)); +#134423 = VERTEX_POINT('',#134424); +#134424 = CARTESIAN_POINT('',(10.51959417205,3.15,0.530776333563)); +#134425 = SURFACE_CURVE('',#134426,(#134430,#134437),.PCURVE_S1.); +#134426 = LINE('',#134427,#134428); +#134427 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#132036 = VECTOR('',#132037,1.); -#132037 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132038 = PCURVE('',#131787,#132039); -#132039 = DEFINITIONAL_REPRESENTATION('',(#132040),#132044); -#132040 = LINE('',#132041,#132042); -#132041 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132042 = VECTOR('',#132043,1.); -#132043 = DIRECTION('',(-1.,0.E+000)); -#132044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134428 = VECTOR('',#134429,1.); +#134429 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134430 = PCURVE('',#134179,#134431); +#134431 = DEFINITIONAL_REPRESENTATION('',(#134432),#134436); +#134432 = LINE('',#134433,#134434); +#134433 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134434 = VECTOR('',#134435,1.); +#134435 = DIRECTION('',(-1.,0.E+000)); +#134436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132045 = PCURVE('',#132046,#132051); -#132046 = CYLINDRICAL_SURFACE('',#132047,0.2192697516); -#132047 = AXIS2_PLACEMENT_3D('',#132048,#132049,#132050); -#132048 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#134437 = PCURVE('',#134438,#134443); +#134438 = CYLINDRICAL_SURFACE('',#134439,0.2192697516); +#134439 = AXIS2_PLACEMENT_3D('',#134440,#134441,#134442); +#134440 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#132049 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132050 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132051 = DEFINITIONAL_REPRESENTATION('',(#132052),#132055); -#132052 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132053,#132054), +#134441 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134442 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134443 = DEFINITIONAL_REPRESENTATION('',(#134444),#134447); +#134444 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134445,#134446), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#132053 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#132054 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#132055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132056 = ORIENTED_EDGE('',*,*,#132057,.T.); -#132057 = EDGE_CURVE('',#132031,#131750,#132058,.T.); -#132058 = SURFACE_CURVE('',#132059,(#132063,#132070),.PCURVE_S1.); -#132059 = LINE('',#132060,#132061); -#132060 = CARTESIAN_POINT('',(10.51959417205,3.15,0.530776333563)); -#132061 = VECTOR('',#132062,1.); -#132062 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132063 = PCURVE('',#131787,#132064); -#132064 = DEFINITIONAL_REPRESENTATION('',(#132065),#132069); -#132065 = LINE('',#132066,#132067); -#132066 = CARTESIAN_POINT('',(3.15,0.E+000)); -#132067 = VECTOR('',#132068,1.); -#132068 = DIRECTION('',(0.E+000,-1.)); -#132069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132070 = PCURVE('',#92796,#132071); -#132071 = DEFINITIONAL_REPRESENTATION('',(#132072),#132076); -#132072 = LINE('',#132073,#132074); -#132073 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#132074 = VECTOR('',#132075,1.); -#132075 = DIRECTION('',(1.,0.E+000)); -#132076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132077 = ORIENTED_EDGE('',*,*,#131772,.F.); -#132078 = ORIENTED_EDGE('',*,*,#132079,.F.); -#132079 = EDGE_CURVE('',#132029,#131773,#132080,.T.); -#132080 = SURFACE_CURVE('',#132081,(#132085,#132092),.PCURVE_S1.); -#132081 = LINE('',#132082,#132083); -#132082 = CARTESIAN_POINT('',(10.51959417205,3.35,0.530776333563)); -#132083 = VECTOR('',#132084,1.); -#132084 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132085 = PCURVE('',#131787,#132086); -#132086 = DEFINITIONAL_REPRESENTATION('',(#132087),#132091); -#132087 = LINE('',#132088,#132089); -#132088 = CARTESIAN_POINT('',(3.35,0.E+000)); -#132089 = VECTOR('',#132090,1.); -#132090 = DIRECTION('',(0.E+000,-1.)); -#132091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132092 = PCURVE('',#92740,#132093); -#132093 = DEFINITIONAL_REPRESENTATION('',(#132094),#132098); -#132094 = LINE('',#132095,#132096); -#132095 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#132096 = VECTOR('',#132097,1.); -#132097 = DIRECTION('',(-1.,0.E+000)); -#132098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132099 = ADVANCED_FACE('',(#132100),#132046,.T.); -#132100 = FACE_BOUND('',#132101,.T.); -#132101 = EDGE_LOOP('',(#132102,#132103,#132149,#132171)); -#132102 = ORIENTED_EDGE('',*,*,#132028,.F.); -#132103 = ORIENTED_EDGE('',*,*,#132104,.F.); -#132104 = EDGE_CURVE('',#132105,#132029,#132107,.T.); -#132105 = VERTEX_POINT('',#132106); -#132106 = CARTESIAN_POINT('',(10.304819755875,3.35,0.75)); -#132107 = SURFACE_CURVE('',#132108,(#132113,#132142),.PCURVE_S1.); -#132108 = CIRCLE('',#132109,0.2192697516); -#132109 = AXIS2_PLACEMENT_3D('',#132110,#132111,#132112); -#132110 = CARTESIAN_POINT('',(10.30032442045,3.35,0.530776333563)); -#132111 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132112 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132113 = PCURVE('',#132046,#132114); -#132114 = DEFINITIONAL_REPRESENTATION('',(#132115),#132141); -#132115 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#132116,#132117,#132118, - #132119,#132120,#132121,#132122,#132123,#132124,#132125,#132126, - #132127,#132128,#132129,#132130,#132131,#132132,#132133,#132134, - #132135,#132136,#132137,#132138,#132139,#132140),.UNSPECIFIED.,.F., +#134445 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#134446 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#134447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134448 = ORIENTED_EDGE('',*,*,#134449,.T.); +#134449 = EDGE_CURVE('',#134423,#134142,#134450,.T.); +#134450 = SURFACE_CURVE('',#134451,(#134455,#134462),.PCURVE_S1.); +#134451 = LINE('',#134452,#134453); +#134452 = CARTESIAN_POINT('',(10.51959417205,3.15,0.530776333563)); +#134453 = VECTOR('',#134454,1.); +#134454 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#134455 = PCURVE('',#134179,#134456); +#134456 = DEFINITIONAL_REPRESENTATION('',(#134457),#134461); +#134457 = LINE('',#134458,#134459); +#134458 = CARTESIAN_POINT('',(3.15,0.E+000)); +#134459 = VECTOR('',#134460,1.); +#134460 = DIRECTION('',(0.E+000,-1.)); +#134461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134462 = PCURVE('',#95188,#134463); +#134463 = DEFINITIONAL_REPRESENTATION('',(#134464),#134468); +#134464 = LINE('',#134465,#134466); +#134465 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#134466 = VECTOR('',#134467,1.); +#134467 = DIRECTION('',(1.,0.E+000)); +#134468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134469 = ORIENTED_EDGE('',*,*,#134164,.F.); +#134470 = ORIENTED_EDGE('',*,*,#134471,.F.); +#134471 = EDGE_CURVE('',#134421,#134165,#134472,.T.); +#134472 = SURFACE_CURVE('',#134473,(#134477,#134484),.PCURVE_S1.); +#134473 = LINE('',#134474,#134475); +#134474 = CARTESIAN_POINT('',(10.51959417205,3.35,0.530776333563)); +#134475 = VECTOR('',#134476,1.); +#134476 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#134477 = PCURVE('',#134179,#134478); +#134478 = DEFINITIONAL_REPRESENTATION('',(#134479),#134483); +#134479 = LINE('',#134480,#134481); +#134480 = CARTESIAN_POINT('',(3.35,0.E+000)); +#134481 = VECTOR('',#134482,1.); +#134482 = DIRECTION('',(0.E+000,-1.)); +#134483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134484 = PCURVE('',#95132,#134485); +#134485 = DEFINITIONAL_REPRESENTATION('',(#134486),#134490); +#134486 = LINE('',#134487,#134488); +#134487 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#134488 = VECTOR('',#134489,1.); +#134489 = DIRECTION('',(-1.,0.E+000)); +#134490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134491 = ADVANCED_FACE('',(#134492),#134438,.T.); +#134492 = FACE_BOUND('',#134493,.T.); +#134493 = EDGE_LOOP('',(#134494,#134495,#134541,#134563)); +#134494 = ORIENTED_EDGE('',*,*,#134420,.F.); +#134495 = ORIENTED_EDGE('',*,*,#134496,.F.); +#134496 = EDGE_CURVE('',#134497,#134421,#134499,.T.); +#134497 = VERTEX_POINT('',#134498); +#134498 = CARTESIAN_POINT('',(10.304819755875,3.35,0.75)); +#134499 = SURFACE_CURVE('',#134500,(#134505,#134534),.PCURVE_S1.); +#134500 = CIRCLE('',#134501,0.2192697516); +#134501 = AXIS2_PLACEMENT_3D('',#134502,#134503,#134504); +#134502 = CARTESIAN_POINT('',(10.30032442045,3.35,0.530776333563)); +#134503 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134504 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134505 = PCURVE('',#134438,#134506); +#134506 = DEFINITIONAL_REPRESENTATION('',(#134507),#134533); +#134507 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134508,#134509,#134510, + #134511,#134512,#134513,#134514,#134515,#134516,#134517,#134518, + #134519,#134520,#134521,#134522,#134523,#134524,#134525,#134526, + #134527,#134528,#134529,#134530,#134531,#134532),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -162778,84 +165780,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#132116 = CARTESIAN_POINT('',(1.591299156552,3.35)); -#132117 = CARTESIAN_POINT('',(1.614788451962,3.35)); -#132118 = CARTESIAN_POINT('',(1.661767042781,3.35)); -#132119 = CARTESIAN_POINT('',(1.73223492901,3.35)); -#132120 = CARTESIAN_POINT('',(1.802702815239,3.35)); -#132121 = CARTESIAN_POINT('',(1.873170701468,3.35)); -#132122 = CARTESIAN_POINT('',(1.943638587697,3.35)); -#132123 = CARTESIAN_POINT('',(2.014106473926,3.35)); -#132124 = CARTESIAN_POINT('',(2.084574360155,3.35)); -#132125 = CARTESIAN_POINT('',(2.155042246384,3.35)); -#132126 = CARTESIAN_POINT('',(2.225510132613,3.35)); -#132127 = CARTESIAN_POINT('',(2.295978018842,3.35)); -#132128 = CARTESIAN_POINT('',(2.366445905071,3.35)); -#132129 = CARTESIAN_POINT('',(2.4369137913,3.35)); -#132130 = CARTESIAN_POINT('',(2.507381677529,3.35)); -#132131 = CARTESIAN_POINT('',(2.577849563758,3.35)); -#132132 = CARTESIAN_POINT('',(2.648317449987,3.35)); -#132133 = CARTESIAN_POINT('',(2.718785336216,3.35)); -#132134 = CARTESIAN_POINT('',(2.789253222445,3.35)); -#132135 = CARTESIAN_POINT('',(2.859721108674,3.35)); -#132136 = CARTESIAN_POINT('',(2.930188994903,3.35)); -#132137 = CARTESIAN_POINT('',(3.000656881132,3.35)); -#132138 = CARTESIAN_POINT('',(3.071124767361,3.35)); -#132139 = CARTESIAN_POINT('',(3.11810335818,3.35)); -#132140 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#132141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132142 = PCURVE('',#92740,#132143); -#132143 = DEFINITIONAL_REPRESENTATION('',(#132144),#132148); -#132144 = CIRCLE('',#132145,0.2192697516); -#132145 = AXIS2_PLACEMENT_2D('',#132146,#132147); -#132146 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#132147 = DIRECTION('',(0.E+000,-1.)); -#132148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132149 = ORIENTED_EDGE('',*,*,#132150,.F.); -#132150 = EDGE_CURVE('',#132151,#132105,#132153,.T.); -#132151 = VERTEX_POINT('',#132152); -#132152 = CARTESIAN_POINT('',(10.304819755875,3.15,0.75)); -#132153 = SURFACE_CURVE('',#132154,(#132158,#132164),.PCURVE_S1.); -#132154 = LINE('',#132155,#132156); -#132155 = CARTESIAN_POINT('',(10.304819755875,3.35,0.75)); -#132156 = VECTOR('',#132157,1.); -#132157 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132158 = PCURVE('',#132046,#132159); -#132159 = DEFINITIONAL_REPRESENTATION('',(#132160),#132163); -#132160 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132161,#132162), +#134508 = CARTESIAN_POINT('',(1.591299156552,3.35)); +#134509 = CARTESIAN_POINT('',(1.614788451962,3.35)); +#134510 = CARTESIAN_POINT('',(1.661767042781,3.35)); +#134511 = CARTESIAN_POINT('',(1.73223492901,3.35)); +#134512 = CARTESIAN_POINT('',(1.802702815239,3.35)); +#134513 = CARTESIAN_POINT('',(1.873170701468,3.35)); +#134514 = CARTESIAN_POINT('',(1.943638587697,3.35)); +#134515 = CARTESIAN_POINT('',(2.014106473926,3.35)); +#134516 = CARTESIAN_POINT('',(2.084574360155,3.35)); +#134517 = CARTESIAN_POINT('',(2.155042246384,3.35)); +#134518 = CARTESIAN_POINT('',(2.225510132613,3.35)); +#134519 = CARTESIAN_POINT('',(2.295978018842,3.35)); +#134520 = CARTESIAN_POINT('',(2.366445905071,3.35)); +#134521 = CARTESIAN_POINT('',(2.4369137913,3.35)); +#134522 = CARTESIAN_POINT('',(2.507381677529,3.35)); +#134523 = CARTESIAN_POINT('',(2.577849563758,3.35)); +#134524 = CARTESIAN_POINT('',(2.648317449987,3.35)); +#134525 = CARTESIAN_POINT('',(2.718785336216,3.35)); +#134526 = CARTESIAN_POINT('',(2.789253222445,3.35)); +#134527 = CARTESIAN_POINT('',(2.859721108674,3.35)); +#134528 = CARTESIAN_POINT('',(2.930188994903,3.35)); +#134529 = CARTESIAN_POINT('',(3.000656881132,3.35)); +#134530 = CARTESIAN_POINT('',(3.071124767361,3.35)); +#134531 = CARTESIAN_POINT('',(3.11810335818,3.35)); +#134532 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#134533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134534 = PCURVE('',#95132,#134535); +#134535 = DEFINITIONAL_REPRESENTATION('',(#134536),#134540); +#134536 = CIRCLE('',#134537,0.2192697516); +#134537 = AXIS2_PLACEMENT_2D('',#134538,#134539); +#134538 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#134539 = DIRECTION('',(0.E+000,-1.)); +#134540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134541 = ORIENTED_EDGE('',*,*,#134542,.F.); +#134542 = EDGE_CURVE('',#134543,#134497,#134545,.T.); +#134543 = VERTEX_POINT('',#134544); +#134544 = CARTESIAN_POINT('',(10.304819755875,3.15,0.75)); +#134545 = SURFACE_CURVE('',#134546,(#134550,#134556),.PCURVE_S1.); +#134546 = LINE('',#134547,#134548); +#134547 = CARTESIAN_POINT('',(10.304819755875,3.35,0.75)); +#134548 = VECTOR('',#134549,1.); +#134549 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134550 = PCURVE('',#134438,#134551); +#134551 = DEFINITIONAL_REPRESENTATION('',(#134552),#134555); +#134552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134553,#134554), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#132161 = CARTESIAN_POINT('',(1.591299156552,3.15)); -#132162 = CARTESIAN_POINT('',(1.591299156552,3.35)); -#132163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132164 = PCURVE('',#92822,#132165); -#132165 = DEFINITIONAL_REPRESENTATION('',(#132166),#132170); -#132166 = LINE('',#132167,#132168); -#132167 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#132168 = VECTOR('',#132169,1.); -#132169 = DIRECTION('',(4.440892098501E-016,1.)); -#132170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132171 = ORIENTED_EDGE('',*,*,#132172,.T.); -#132172 = EDGE_CURVE('',#132151,#132031,#132173,.T.); -#132173 = SURFACE_CURVE('',#132174,(#132179,#132208),.PCURVE_S1.); -#132174 = CIRCLE('',#132175,0.2192697516); -#132175 = AXIS2_PLACEMENT_3D('',#132176,#132177,#132178); -#132176 = CARTESIAN_POINT('',(10.30032442045,3.15,0.530776333563)); -#132177 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132178 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132179 = PCURVE('',#132046,#132180); -#132180 = DEFINITIONAL_REPRESENTATION('',(#132181),#132207); -#132181 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#132182,#132183,#132184, - #132185,#132186,#132187,#132188,#132189,#132190,#132191,#132192, - #132193,#132194,#132195,#132196,#132197,#132198,#132199,#132200, - #132201,#132202,#132203,#132204,#132205,#132206),.UNSPECIFIED.,.F., +#134553 = CARTESIAN_POINT('',(1.591299156552,3.15)); +#134554 = CARTESIAN_POINT('',(1.591299156552,3.35)); +#134555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134556 = PCURVE('',#95214,#134557); +#134557 = DEFINITIONAL_REPRESENTATION('',(#134558),#134562); +#134558 = LINE('',#134559,#134560); +#134559 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#134560 = VECTOR('',#134561,1.); +#134561 = DIRECTION('',(4.440892098501E-016,1.)); +#134562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134563 = ORIENTED_EDGE('',*,*,#134564,.T.); +#134564 = EDGE_CURVE('',#134543,#134423,#134565,.T.); +#134565 = SURFACE_CURVE('',#134566,(#134571,#134600),.PCURVE_S1.); +#134566 = CIRCLE('',#134567,0.2192697516); +#134567 = AXIS2_PLACEMENT_3D('',#134568,#134569,#134570); +#134568 = CARTESIAN_POINT('',(10.30032442045,3.15,0.530776333563)); +#134569 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134570 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134571 = PCURVE('',#134438,#134572); +#134572 = DEFINITIONAL_REPRESENTATION('',(#134573),#134599); +#134573 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134574,#134575,#134576, + #134577,#134578,#134579,#134580,#134581,#134582,#134583,#134584, + #134585,#134586,#134587,#134588,#134589,#134590,#134591,#134592, + #134593,#134594,#134595,#134596,#134597,#134598),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -162863,728 +165865,728 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#132182 = CARTESIAN_POINT('',(1.591299156552,3.15)); -#132183 = CARTESIAN_POINT('',(1.614788451962,3.15)); -#132184 = CARTESIAN_POINT('',(1.661767042781,3.15)); -#132185 = CARTESIAN_POINT('',(1.73223492901,3.15)); -#132186 = CARTESIAN_POINT('',(1.802702815239,3.15)); -#132187 = CARTESIAN_POINT('',(1.873170701468,3.15)); -#132188 = CARTESIAN_POINT('',(1.943638587697,3.15)); -#132189 = CARTESIAN_POINT('',(2.014106473926,3.15)); -#132190 = CARTESIAN_POINT('',(2.084574360155,3.15)); -#132191 = CARTESIAN_POINT('',(2.155042246384,3.15)); -#132192 = CARTESIAN_POINT('',(2.225510132613,3.15)); -#132193 = CARTESIAN_POINT('',(2.295978018842,3.15)); -#132194 = CARTESIAN_POINT('',(2.366445905071,3.15)); -#132195 = CARTESIAN_POINT('',(2.4369137913,3.15)); -#132196 = CARTESIAN_POINT('',(2.507381677529,3.15)); -#132197 = CARTESIAN_POINT('',(2.577849563758,3.15)); -#132198 = CARTESIAN_POINT('',(2.648317449987,3.15)); -#132199 = CARTESIAN_POINT('',(2.718785336216,3.15)); -#132200 = CARTESIAN_POINT('',(2.789253222445,3.15)); -#132201 = CARTESIAN_POINT('',(2.859721108674,3.15)); -#132202 = CARTESIAN_POINT('',(2.930188994903,3.15)); -#132203 = CARTESIAN_POINT('',(3.000656881132,3.15)); -#132204 = CARTESIAN_POINT('',(3.071124767361,3.15)); -#132205 = CARTESIAN_POINT('',(3.11810335818,3.15)); -#132206 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#132207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132208 = PCURVE('',#92796,#132209); -#132209 = DEFINITIONAL_REPRESENTATION('',(#132210),#132218); -#132210 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132211,#132212,#132213, - #132214,#132215,#132216,#132217),.UNSPECIFIED.,.T.,.F.) +#134574 = CARTESIAN_POINT('',(1.591299156552,3.15)); +#134575 = CARTESIAN_POINT('',(1.614788451962,3.15)); +#134576 = CARTESIAN_POINT('',(1.661767042781,3.15)); +#134577 = CARTESIAN_POINT('',(1.73223492901,3.15)); +#134578 = CARTESIAN_POINT('',(1.802702815239,3.15)); +#134579 = CARTESIAN_POINT('',(1.873170701468,3.15)); +#134580 = CARTESIAN_POINT('',(1.943638587697,3.15)); +#134581 = CARTESIAN_POINT('',(2.014106473926,3.15)); +#134582 = CARTESIAN_POINT('',(2.084574360155,3.15)); +#134583 = CARTESIAN_POINT('',(2.155042246384,3.15)); +#134584 = CARTESIAN_POINT('',(2.225510132613,3.15)); +#134585 = CARTESIAN_POINT('',(2.295978018842,3.15)); +#134586 = CARTESIAN_POINT('',(2.366445905071,3.15)); +#134587 = CARTESIAN_POINT('',(2.4369137913,3.15)); +#134588 = CARTESIAN_POINT('',(2.507381677529,3.15)); +#134589 = CARTESIAN_POINT('',(2.577849563758,3.15)); +#134590 = CARTESIAN_POINT('',(2.648317449987,3.15)); +#134591 = CARTESIAN_POINT('',(2.718785336216,3.15)); +#134592 = CARTESIAN_POINT('',(2.789253222445,3.15)); +#134593 = CARTESIAN_POINT('',(2.859721108674,3.15)); +#134594 = CARTESIAN_POINT('',(2.930188994903,3.15)); +#134595 = CARTESIAN_POINT('',(3.000656881132,3.15)); +#134596 = CARTESIAN_POINT('',(3.071124767361,3.15)); +#134597 = CARTESIAN_POINT('',(3.11810335818,3.15)); +#134598 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#134599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134600 = PCURVE('',#95188,#134601); +#134601 = DEFINITIONAL_REPRESENTATION('',(#134602),#134610); +#134602 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134603,#134604,#134605, + #134606,#134607,#134608,#134609),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#132211 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#132212 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#132213 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#132214 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#132215 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#132216 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#132217 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#132218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132219 = ADVANCED_FACE('',(#132220),#131971,.F.); -#132220 = FACE_BOUND('',#132221,.F.); -#132221 = EDGE_LOOP('',(#132222,#132223,#132246,#132268)); -#132222 = ORIENTED_EDGE('',*,*,#131953,.T.); -#132223 = ORIENTED_EDGE('',*,*,#132224,.F.); -#132224 = EDGE_CURVE('',#132225,#131956,#132227,.T.); -#132225 = VERTEX_POINT('',#132226); -#132226 = CARTESIAN_POINT('',(10.303662633502,3.35,0.65)); -#132227 = SURFACE_CURVE('',#132228,(#132233,#132239),.PCURVE_S1.); -#132228 = CIRCLE('',#132229,0.119270391569); -#132229 = AXIS2_PLACEMENT_3D('',#132230,#132231,#132232); -#132230 = CARTESIAN_POINT('',(10.30032442045,3.35,0.530776333563)); -#132231 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132232 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132233 = PCURVE('',#131971,#132234); -#132234 = DEFINITIONAL_REPRESENTATION('',(#132235),#132238); -#132235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132236,#132237), +#134603 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#134604 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#134605 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#134606 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#134607 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#134608 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#134609 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#134610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134611 = ADVANCED_FACE('',(#134612),#134363,.F.); +#134612 = FACE_BOUND('',#134613,.F.); +#134613 = EDGE_LOOP('',(#134614,#134615,#134638,#134660)); +#134614 = ORIENTED_EDGE('',*,*,#134345,.T.); +#134615 = ORIENTED_EDGE('',*,*,#134616,.F.); +#134616 = EDGE_CURVE('',#134617,#134348,#134619,.T.); +#134617 = VERTEX_POINT('',#134618); +#134618 = CARTESIAN_POINT('',(10.303662633502,3.35,0.65)); +#134619 = SURFACE_CURVE('',#134620,(#134625,#134631),.PCURVE_S1.); +#134620 = CIRCLE('',#134621,0.119270391569); +#134621 = AXIS2_PLACEMENT_3D('',#134622,#134623,#134624); +#134622 = CARTESIAN_POINT('',(10.30032442045,3.35,0.530776333563)); +#134623 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134624 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134625 = PCURVE('',#134363,#134626); +#134626 = DEFINITIONAL_REPRESENTATION('',(#134627),#134630); +#134627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134628,#134629), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#132236 = CARTESIAN_POINT('',(1.598788597134,3.35)); -#132237 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#132238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132239 = PCURVE('',#92740,#132240); -#132240 = DEFINITIONAL_REPRESENTATION('',(#132241),#132245); -#132241 = CIRCLE('',#132242,0.119270391569); -#132242 = AXIS2_PLACEMENT_2D('',#132243,#132244); -#132243 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#132244 = DIRECTION('',(0.E+000,-1.)); -#132245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132246 = ORIENTED_EDGE('',*,*,#132247,.T.); -#132247 = EDGE_CURVE('',#132225,#132248,#132250,.T.); -#132248 = VERTEX_POINT('',#132249); -#132249 = CARTESIAN_POINT('',(10.303662633502,3.15,0.65)); -#132250 = SURFACE_CURVE('',#132251,(#132255,#132261),.PCURVE_S1.); -#132251 = LINE('',#132252,#132253); -#132252 = CARTESIAN_POINT('',(10.303662633502,3.35,0.65)); -#132253 = VECTOR('',#132254,1.); -#132254 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132255 = PCURVE('',#131971,#132256); -#132256 = DEFINITIONAL_REPRESENTATION('',(#132257),#132260); -#132257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132258,#132259), +#134628 = CARTESIAN_POINT('',(1.598788597134,3.35)); +#134629 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#134630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134631 = PCURVE('',#95132,#134632); +#134632 = DEFINITIONAL_REPRESENTATION('',(#134633),#134637); +#134633 = CIRCLE('',#134634,0.119270391569); +#134634 = AXIS2_PLACEMENT_2D('',#134635,#134636); +#134635 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#134636 = DIRECTION('',(0.E+000,-1.)); +#134637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134638 = ORIENTED_EDGE('',*,*,#134639,.T.); +#134639 = EDGE_CURVE('',#134617,#134640,#134642,.T.); +#134640 = VERTEX_POINT('',#134641); +#134641 = CARTESIAN_POINT('',(10.303662633502,3.15,0.65)); +#134642 = SURFACE_CURVE('',#134643,(#134647,#134653),.PCURVE_S1.); +#134643 = LINE('',#134644,#134645); +#134644 = CARTESIAN_POINT('',(10.303662633502,3.35,0.65)); +#134645 = VECTOR('',#134646,1.); +#134646 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134647 = PCURVE('',#134363,#134648); +#134648 = DEFINITIONAL_REPRESENTATION('',(#134649),#134652); +#134649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134650,#134651), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#132258 = CARTESIAN_POINT('',(1.598788597134,3.35)); -#132259 = CARTESIAN_POINT('',(1.598788597134,3.15)); -#132260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132261 = PCURVE('',#92768,#132262); -#132262 = DEFINITIONAL_REPRESENTATION('',(#132263),#132267); -#132263 = LINE('',#132264,#132265); -#132264 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#132265 = VECTOR('',#132266,1.); -#132266 = DIRECTION('',(4.440892098501E-016,-1.)); -#132267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132268 = ORIENTED_EDGE('',*,*,#132269,.T.); -#132269 = EDGE_CURVE('',#132248,#131954,#132270,.T.); -#132270 = SURFACE_CURVE('',#132271,(#132276,#132282),.PCURVE_S1.); -#132271 = CIRCLE('',#132272,0.119270391569); -#132272 = AXIS2_PLACEMENT_3D('',#132273,#132274,#132275); -#132273 = CARTESIAN_POINT('',(10.30032442045,3.15,0.530776333563)); -#132274 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132275 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132276 = PCURVE('',#131971,#132277); -#132277 = DEFINITIONAL_REPRESENTATION('',(#132278),#132281); -#132278 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132279,#132280), +#134650 = CARTESIAN_POINT('',(1.598788597134,3.35)); +#134651 = CARTESIAN_POINT('',(1.598788597134,3.15)); +#134652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134653 = PCURVE('',#95160,#134654); +#134654 = DEFINITIONAL_REPRESENTATION('',(#134655),#134659); +#134655 = LINE('',#134656,#134657); +#134656 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#134657 = VECTOR('',#134658,1.); +#134658 = DIRECTION('',(4.440892098501E-016,-1.)); +#134659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134660 = ORIENTED_EDGE('',*,*,#134661,.T.); +#134661 = EDGE_CURVE('',#134640,#134346,#134662,.T.); +#134662 = SURFACE_CURVE('',#134663,(#134668,#134674),.PCURVE_S1.); +#134663 = CIRCLE('',#134664,0.119270391569); +#134664 = AXIS2_PLACEMENT_3D('',#134665,#134666,#134667); +#134665 = CARTESIAN_POINT('',(10.30032442045,3.15,0.530776333563)); +#134666 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134667 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#134668 = PCURVE('',#134363,#134669); +#134669 = DEFINITIONAL_REPRESENTATION('',(#134670),#134673); +#134670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134671,#134672), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#132279 = CARTESIAN_POINT('',(1.598788597134,3.15)); -#132280 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#132281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134671 = CARTESIAN_POINT('',(1.598788597134,3.15)); +#134672 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#134673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132282 = PCURVE('',#92796,#132283); -#132283 = DEFINITIONAL_REPRESENTATION('',(#132284),#132292); -#132284 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132285,#132286,#132287, - #132288,#132289,#132290,#132291),.UNSPECIFIED.,.T.,.F.) +#134674 = PCURVE('',#95188,#134675); +#134675 = DEFINITIONAL_REPRESENTATION('',(#134676),#134684); +#134676 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134677,#134678,#134679, + #134680,#134681,#134682,#134683),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#132285 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#132286 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#132287 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#132288 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#132289 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#132290 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#132291 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#132292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132293 = ADVANCED_FACE('',(#132294),#92768,.T.); -#132294 = FACE_BOUND('',#132295,.T.); -#132295 = EDGE_LOOP('',(#132296,#132317,#132318,#132339)); -#132296 = ORIENTED_EDGE('',*,*,#132297,.F.); -#132297 = EDGE_CURVE('',#132225,#92725,#132298,.T.); -#132298 = SURFACE_CURVE('',#132299,(#132303,#132310),.PCURVE_S1.); -#132299 = LINE('',#132300,#132301); -#132300 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); -#132301 = VECTOR('',#132302,1.); -#132302 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#132303 = PCURVE('',#92768,#132304); -#132304 = DEFINITIONAL_REPRESENTATION('',(#132305),#132309); -#132305 = LINE('',#132306,#132307); -#132306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132307 = VECTOR('',#132308,1.); -#132308 = DIRECTION('',(1.,-1.082494723017E-063)); -#132309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132310 = PCURVE('',#92740,#132311); -#132311 = DEFINITIONAL_REPRESENTATION('',(#132312),#132316); -#132312 = LINE('',#132313,#132314); -#132313 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132314 = VECTOR('',#132315,1.); -#132315 = DIRECTION('',(3.563627120235E-016,-1.)); -#132316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#134677 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#134678 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#134679 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#134680 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#134681 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#134682 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#134683 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#134684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134685 = ADVANCED_FACE('',(#134686),#95160,.T.); +#134686 = FACE_BOUND('',#134687,.T.); +#134687 = EDGE_LOOP('',(#134688,#134709,#134710,#134731)); +#134688 = ORIENTED_EDGE('',*,*,#134689,.F.); +#134689 = EDGE_CURVE('',#134617,#95117,#134690,.T.); +#134690 = SURFACE_CURVE('',#134691,(#134695,#134702),.PCURVE_S1.); +#134691 = LINE('',#134692,#134693); +#134692 = CARTESIAN_POINT('',(10.527847992439,3.35,0.65)); +#134693 = VECTOR('',#134694,1.); +#134694 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#134695 = PCURVE('',#95160,#134696); +#134696 = DEFINITIONAL_REPRESENTATION('',(#134697),#134701); +#134697 = LINE('',#134698,#134699); +#134698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134699 = VECTOR('',#134700,1.); +#134700 = DIRECTION('',(1.,-1.082494723017E-063)); +#134701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134702 = PCURVE('',#95132,#134703); +#134703 = DEFINITIONAL_REPRESENTATION('',(#134704),#134708); +#134704 = LINE('',#134705,#134706); +#134705 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134706 = VECTOR('',#134707,1.); +#134707 = DIRECTION('',(3.563627120235E-016,-1.)); +#134708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134709 = ORIENTED_EDGE('',*,*,#134639,.T.); +#134710 = ORIENTED_EDGE('',*,*,#134711,.T.); +#134711 = EDGE_CURVE('',#134640,#95145,#134712,.T.); +#134712 = SURFACE_CURVE('',#134713,(#134717,#134724),.PCURVE_S1.); +#134713 = LINE('',#134714,#134715); +#134714 = CARTESIAN_POINT('',(10.527847992439,3.15,0.65)); +#134715 = VECTOR('',#134716,1.); +#134716 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#134717 = PCURVE('',#95160,#134718); +#134718 = DEFINITIONAL_REPRESENTATION('',(#134719),#134723); +#134719 = LINE('',#134720,#134721); +#134720 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#134721 = VECTOR('',#134722,1.); +#134722 = DIRECTION('',(1.,-1.082494723017E-063)); +#134723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134724 = PCURVE('',#95188,#134725); +#134725 = DEFINITIONAL_REPRESENTATION('',(#134726),#134730); +#134726 = LINE('',#134727,#134728); +#134727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134728 = VECTOR('',#134729,1.); +#134729 = DIRECTION('',(-3.563627120235E-016,-1.)); +#134730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134731 = ORIENTED_EDGE('',*,*,#95144,.F.); +#134732 = ADVANCED_FACE('',(#134733),#95188,.T.); +#134733 = FACE_BOUND('',#134734,.T.); +#134734 = EDGE_LOOP('',(#134735,#134736,#134737,#134738,#134739,#134740, + #134761,#134762,#134763,#134764,#134765,#134786)); +#134735 = ORIENTED_EDGE('',*,*,#134711,.F.); +#134736 = ORIENTED_EDGE('',*,*,#134661,.T.); +#134737 = ORIENTED_EDGE('',*,*,#134396,.T.); +#134738 = ORIENTED_EDGE('',*,*,#134271,.T.); +#134739 = ORIENTED_EDGE('',*,*,#134067,.T.); +#134740 = ORIENTED_EDGE('',*,*,#134741,.F.); +#134741 = EDGE_CURVE('',#133931,#134038,#134742,.T.); +#134742 = SURFACE_CURVE('',#134743,(#134747,#134754),.PCURVE_S1.); +#134743 = LINE('',#134744,#134745); +#134744 = CARTESIAN_POINT('',(11.,3.15,1.159810404338E-002)); +#134745 = VECTOR('',#134746,1.); +#134746 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#134747 = PCURVE('',#95188,#134748); +#134748 = DEFINITIONAL_REPRESENTATION('',(#134749),#134753); +#134749 = LINE('',#134750,#134751); +#134750 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#134751 = VECTOR('',#134752,1.); +#134752 = DIRECTION('',(1.,-2.101748079665E-016)); +#134753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134754 = PCURVE('',#133951,#134755); +#134755 = DEFINITIONAL_REPRESENTATION('',(#134756),#134760); +#134756 = LINE('',#134757,#134758); +#134757 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#134758 = VECTOR('',#134759,1.); +#134759 = DIRECTION('',(-1.194699204908E-017,-1.)); +#134760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134761 = ORIENTED_EDGE('',*,*,#134013,.F.); +#134762 = ORIENTED_EDGE('',*,*,#134141,.F.); +#134763 = ORIENTED_EDGE('',*,*,#134449,.F.); +#134764 = ORIENTED_EDGE('',*,*,#134564,.F.); +#134765 = ORIENTED_EDGE('',*,*,#134766,.T.); +#134766 = EDGE_CURVE('',#134543,#95173,#134767,.T.); +#134767 = SURFACE_CURVE('',#134768,(#134772,#134779),.PCURVE_S1.); +#134768 = LINE('',#134769,#134770); +#134769 = CARTESIAN_POINT('',(10.527847992439,3.15,0.75)); +#134770 = VECTOR('',#134771,1.); +#134771 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#134772 = PCURVE('',#95188,#134773); +#134773 = DEFINITIONAL_REPRESENTATION('',(#134774),#134778); +#134774 = LINE('',#134775,#134776); +#134775 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#134776 = VECTOR('',#134777,1.); +#134777 = DIRECTION('',(-3.563627120235E-016,-1.)); +#134778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134779 = PCURVE('',#95214,#134780); +#134780 = DEFINITIONAL_REPRESENTATION('',(#134781),#134785); +#134781 = LINE('',#134782,#134783); +#134782 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#134783 = VECTOR('',#134784,1.); +#134784 = DIRECTION('',(-1.,-1.082494723017E-063)); +#134785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134786 = ORIENTED_EDGE('',*,*,#95172,.F.); +#134787 = ADVANCED_FACE('',(#134788),#95214,.T.); +#134788 = FACE_BOUND('',#134789,.T.); +#134789 = EDGE_LOOP('',(#134790,#134791,#134792,#134813)); +#134790 = ORIENTED_EDGE('',*,*,#134766,.F.); +#134791 = ORIENTED_EDGE('',*,*,#134542,.T.); +#134792 = ORIENTED_EDGE('',*,*,#134793,.T.); +#134793 = EDGE_CURVE('',#134497,#95115,#134794,.T.); +#134794 = SURFACE_CURVE('',#134795,(#134799,#134806),.PCURVE_S1.); +#134795 = LINE('',#134796,#134797); +#134796 = CARTESIAN_POINT('',(10.527847992439,3.35,0.75)); +#134797 = VECTOR('',#134798,1.); +#134798 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#134799 = PCURVE('',#95214,#134800); +#134800 = DEFINITIONAL_REPRESENTATION('',(#134801),#134805); +#134801 = LINE('',#134802,#134803); +#134802 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134803 = VECTOR('',#134804,1.); +#134804 = DIRECTION('',(-1.,-1.082494723017E-063)); +#134805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134806 = PCURVE('',#95132,#134807); +#134807 = DEFINITIONAL_REPRESENTATION('',(#134808),#134812); +#134808 = LINE('',#134809,#134810); +#134809 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#134810 = VECTOR('',#134811,1.); +#134811 = DIRECTION('',(3.563627120235E-016,-1.)); +#134812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132317 = ORIENTED_EDGE('',*,*,#132247,.T.); -#132318 = ORIENTED_EDGE('',*,*,#132319,.T.); -#132319 = EDGE_CURVE('',#132248,#92753,#132320,.T.); -#132320 = SURFACE_CURVE('',#132321,(#132325,#132332),.PCURVE_S1.); -#132321 = LINE('',#132322,#132323); -#132322 = CARTESIAN_POINT('',(10.527847992439,3.15,0.65)); -#132323 = VECTOR('',#132324,1.); -#132324 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#132325 = PCURVE('',#92768,#132326); -#132326 = DEFINITIONAL_REPRESENTATION('',(#132327),#132331); -#132327 = LINE('',#132328,#132329); -#132328 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#132329 = VECTOR('',#132330,1.); -#132330 = DIRECTION('',(1.,-1.082494723017E-063)); -#132331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132332 = PCURVE('',#92796,#132333); -#132333 = DEFINITIONAL_REPRESENTATION('',(#132334),#132338); -#132334 = LINE('',#132335,#132336); -#132335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132336 = VECTOR('',#132337,1.); -#132337 = DIRECTION('',(-3.563627120235E-016,-1.)); -#132338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132339 = ORIENTED_EDGE('',*,*,#92752,.F.); -#132340 = ADVANCED_FACE('',(#132341),#92796,.T.); -#132341 = FACE_BOUND('',#132342,.T.); -#132342 = EDGE_LOOP('',(#132343,#132344,#132345,#132346,#132347,#132348, - #132369,#132370,#132371,#132372,#132373,#132394)); -#132343 = ORIENTED_EDGE('',*,*,#132319,.F.); -#132344 = ORIENTED_EDGE('',*,*,#132269,.T.); -#132345 = ORIENTED_EDGE('',*,*,#132004,.T.); -#132346 = ORIENTED_EDGE('',*,*,#131879,.T.); -#132347 = ORIENTED_EDGE('',*,*,#131675,.T.); -#132348 = ORIENTED_EDGE('',*,*,#132349,.F.); -#132349 = EDGE_CURVE('',#131539,#131646,#132350,.T.); -#132350 = SURFACE_CURVE('',#132351,(#132355,#132362),.PCURVE_S1.); -#132351 = LINE('',#132352,#132353); -#132352 = CARTESIAN_POINT('',(11.,3.15,1.159810404338E-002)); -#132353 = VECTOR('',#132354,1.); -#132354 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#132355 = PCURVE('',#92796,#132356); -#132356 = DEFINITIONAL_REPRESENTATION('',(#132357),#132361); -#132357 = LINE('',#132358,#132359); -#132358 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#132359 = VECTOR('',#132360,1.); -#132360 = DIRECTION('',(1.,-2.101748079665E-016)); -#132361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132362 = PCURVE('',#131559,#132363); -#132363 = DEFINITIONAL_REPRESENTATION('',(#132364),#132368); -#132364 = LINE('',#132365,#132366); -#132365 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#132366 = VECTOR('',#132367,1.); -#132367 = DIRECTION('',(-1.194699204908E-017,-1.)); -#132368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132369 = ORIENTED_EDGE('',*,*,#131621,.F.); -#132370 = ORIENTED_EDGE('',*,*,#131749,.F.); -#132371 = ORIENTED_EDGE('',*,*,#132057,.F.); -#132372 = ORIENTED_EDGE('',*,*,#132172,.F.); -#132373 = ORIENTED_EDGE('',*,*,#132374,.T.); -#132374 = EDGE_CURVE('',#132151,#92781,#132375,.T.); -#132375 = SURFACE_CURVE('',#132376,(#132380,#132387),.PCURVE_S1.); -#132376 = LINE('',#132377,#132378); -#132377 = CARTESIAN_POINT('',(10.527847992439,3.15,0.75)); -#132378 = VECTOR('',#132379,1.); -#132379 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#132380 = PCURVE('',#92796,#132381); -#132381 = DEFINITIONAL_REPRESENTATION('',(#132382),#132386); -#132382 = LINE('',#132383,#132384); -#132383 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#132384 = VECTOR('',#132385,1.); -#132385 = DIRECTION('',(-3.563627120235E-016,-1.)); -#132386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132387 = PCURVE('',#92822,#132388); -#132388 = DEFINITIONAL_REPRESENTATION('',(#132389),#132393); -#132389 = LINE('',#132390,#132391); -#132390 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#132391 = VECTOR('',#132392,1.); -#132392 = DIRECTION('',(-1.,-1.082494723017E-063)); -#132393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132394 = ORIENTED_EDGE('',*,*,#92780,.F.); -#132395 = ADVANCED_FACE('',(#132396),#92822,.T.); -#132396 = FACE_BOUND('',#132397,.T.); -#132397 = EDGE_LOOP('',(#132398,#132399,#132400,#132421)); -#132398 = ORIENTED_EDGE('',*,*,#132374,.F.); -#132399 = ORIENTED_EDGE('',*,*,#132150,.T.); -#132400 = ORIENTED_EDGE('',*,*,#132401,.T.); -#132401 = EDGE_CURVE('',#132105,#92723,#132402,.T.); -#132402 = SURFACE_CURVE('',#132403,(#132407,#132414),.PCURVE_S1.); -#132403 = LINE('',#132404,#132405); -#132404 = CARTESIAN_POINT('',(10.527847992439,3.35,0.75)); -#132405 = VECTOR('',#132406,1.); -#132406 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#132407 = PCURVE('',#92822,#132408); -#132408 = DEFINITIONAL_REPRESENTATION('',(#132409),#132413); -#132409 = LINE('',#132410,#132411); -#132410 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132411 = VECTOR('',#132412,1.); -#132412 = DIRECTION('',(-1.,-1.082494723017E-063)); -#132413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132414 = PCURVE('',#92740,#132415); -#132415 = DEFINITIONAL_REPRESENTATION('',(#132416),#132420); -#132416 = LINE('',#132417,#132418); -#132417 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#132418 = VECTOR('',#132419,1.); -#132419 = DIRECTION('',(3.563627120235E-016,-1.)); -#132420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132421 = ORIENTED_EDGE('',*,*,#92808,.F.); -#132422 = ADVANCED_FACE('',(#132423),#92740,.T.); -#132423 = FACE_BOUND('',#132424,.T.); -#132424 = EDGE_LOOP('',(#132425,#132426,#132427,#132428,#132429,#132430, - #132451,#132452,#132453,#132454,#132455,#132456)); -#132425 = ORIENTED_EDGE('',*,*,#132401,.F.); -#132426 = ORIENTED_EDGE('',*,*,#132104,.T.); -#132427 = ORIENTED_EDGE('',*,*,#132079,.T.); -#132428 = ORIENTED_EDGE('',*,*,#131799,.T.); -#132429 = ORIENTED_EDGE('',*,*,#131571,.T.); -#132430 = ORIENTED_EDGE('',*,*,#132431,.F.); -#132431 = EDGE_CURVE('',#131648,#131537,#132432,.T.); -#132432 = SURFACE_CURVE('',#132433,(#132437,#132444),.PCURVE_S1.); -#132433 = LINE('',#132434,#132435); -#132434 = CARTESIAN_POINT('',(11.,3.35,1.159810404338E-002)); -#132435 = VECTOR('',#132436,1.); -#132436 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#132437 = PCURVE('',#92740,#132438); -#132438 = DEFINITIONAL_REPRESENTATION('',(#132439),#132443); -#132439 = LINE('',#132440,#132441); -#132440 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#132441 = VECTOR('',#132442,1.); -#132442 = DIRECTION('',(1.,2.101748079665E-016)); -#132443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132444 = PCURVE('',#131559,#132445); -#132445 = DEFINITIONAL_REPRESENTATION('',(#132446),#132450); -#132446 = LINE('',#132447,#132448); -#132447 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#132448 = VECTOR('',#132449,1.); -#132449 = DIRECTION('',(1.194699204908E-017,1.)); -#132450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132451 = ORIENTED_EDGE('',*,*,#131725,.F.); -#132452 = ORIENTED_EDGE('',*,*,#131828,.F.); -#132453 = ORIENTED_EDGE('',*,*,#131982,.F.); -#132454 = ORIENTED_EDGE('',*,*,#132224,.F.); -#132455 = ORIENTED_EDGE('',*,*,#132297,.T.); -#132456 = ORIENTED_EDGE('',*,*,#92722,.F.); -#132457 = ADVANCED_FACE('',(#132458),#131559,.T.); -#132458 = FACE_BOUND('',#132459,.T.); -#132459 = EDGE_LOOP('',(#132460,#132461,#132462,#132463)); -#132460 = ORIENTED_EDGE('',*,*,#132349,.T.); -#132461 = ORIENTED_EDGE('',*,*,#131645,.T.); -#132462 = ORIENTED_EDGE('',*,*,#132431,.T.); -#132463 = ORIENTED_EDGE('',*,*,#131536,.T.); -#132464 = ADVANCED_FACE('',(#132465),#132479,.F.); -#132465 = FACE_BOUND('',#132466,.T.); -#132466 = EDGE_LOOP('',(#132467,#132502,#132525,#132552)); -#132467 = ORIENTED_EDGE('',*,*,#132468,.F.); -#132468 = EDGE_CURVE('',#132469,#132471,#132473,.T.); -#132469 = VERTEX_POINT('',#132470); -#132470 = CARTESIAN_POINT('',(11.,2.85,-0.208196358798)); -#132471 = VERTEX_POINT('',#132472); -#132472 = CARTESIAN_POINT('',(11.,2.65,-0.208196358798)); -#132473 = SURFACE_CURVE('',#132474,(#132478,#132490),.PCURVE_S1.); -#132474 = LINE('',#132475,#132476); -#132475 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#132476 = VECTOR('',#132477,1.); -#132477 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132478 = PCURVE('',#132479,#132484); -#132479 = PLANE('',#132480); -#132480 = AXIS2_PLACEMENT_3D('',#132481,#132482,#132483); -#132481 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#134813 = ORIENTED_EDGE('',*,*,#95200,.F.); +#134814 = ADVANCED_FACE('',(#134815),#95132,.T.); +#134815 = FACE_BOUND('',#134816,.T.); +#134816 = EDGE_LOOP('',(#134817,#134818,#134819,#134820,#134821,#134822, + #134843,#134844,#134845,#134846,#134847,#134848)); +#134817 = ORIENTED_EDGE('',*,*,#134793,.F.); +#134818 = ORIENTED_EDGE('',*,*,#134496,.T.); +#134819 = ORIENTED_EDGE('',*,*,#134471,.T.); +#134820 = ORIENTED_EDGE('',*,*,#134191,.T.); +#134821 = ORIENTED_EDGE('',*,*,#133963,.T.); +#134822 = ORIENTED_EDGE('',*,*,#134823,.F.); +#134823 = EDGE_CURVE('',#134040,#133929,#134824,.T.); +#134824 = SURFACE_CURVE('',#134825,(#134829,#134836),.PCURVE_S1.); +#134825 = LINE('',#134826,#134827); +#134826 = CARTESIAN_POINT('',(11.,3.35,1.159810404338E-002)); +#134827 = VECTOR('',#134828,1.); +#134828 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#134829 = PCURVE('',#95132,#134830); +#134830 = DEFINITIONAL_REPRESENTATION('',(#134831),#134835); +#134831 = LINE('',#134832,#134833); +#134832 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#134833 = VECTOR('',#134834,1.); +#134834 = DIRECTION('',(1.,2.101748079665E-016)); +#134835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134836 = PCURVE('',#133951,#134837); +#134837 = DEFINITIONAL_REPRESENTATION('',(#134838),#134842); +#134838 = LINE('',#134839,#134840); +#134839 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#134840 = VECTOR('',#134841,1.); +#134841 = DIRECTION('',(1.194699204908E-017,1.)); +#134842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134843 = ORIENTED_EDGE('',*,*,#134117,.F.); +#134844 = ORIENTED_EDGE('',*,*,#134220,.F.); +#134845 = ORIENTED_EDGE('',*,*,#134374,.F.); +#134846 = ORIENTED_EDGE('',*,*,#134616,.F.); +#134847 = ORIENTED_EDGE('',*,*,#134689,.T.); +#134848 = ORIENTED_EDGE('',*,*,#95114,.F.); +#134849 = ADVANCED_FACE('',(#134850),#133951,.T.); +#134850 = FACE_BOUND('',#134851,.T.); +#134851 = EDGE_LOOP('',(#134852,#134853,#134854,#134855)); +#134852 = ORIENTED_EDGE('',*,*,#134741,.T.); +#134853 = ORIENTED_EDGE('',*,*,#134037,.T.); +#134854 = ORIENTED_EDGE('',*,*,#134823,.T.); +#134855 = ORIENTED_EDGE('',*,*,#133928,.T.); +#134856 = ADVANCED_FACE('',(#134857),#134871,.F.); +#134857 = FACE_BOUND('',#134858,.T.); +#134858 = EDGE_LOOP('',(#134859,#134894,#134917,#134944)); +#134859 = ORIENTED_EDGE('',*,*,#134860,.F.); +#134860 = EDGE_CURVE('',#134861,#134863,#134865,.T.); +#134861 = VERTEX_POINT('',#134862); +#134862 = CARTESIAN_POINT('',(11.,2.85,-0.208196358798)); +#134863 = VERTEX_POINT('',#134864); +#134864 = CARTESIAN_POINT('',(11.,2.65,-0.208196358798)); +#134865 = SURFACE_CURVE('',#134866,(#134870,#134882),.PCURVE_S1.); +#134866 = LINE('',#134867,#134868); +#134867 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#134868 = VECTOR('',#134869,1.); +#134869 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134870 = PCURVE('',#134871,#134876); +#134871 = PLANE('',#134872); +#134872 = AXIS2_PLACEMENT_3D('',#134873,#134874,#134875); +#134873 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#132482 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132483 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#132484 = DEFINITIONAL_REPRESENTATION('',(#132485),#132489); -#132485 = LINE('',#132486,#132487); -#132486 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#132487 = VECTOR('',#132488,1.); -#132488 = DIRECTION('',(4.440892098501E-016,-1.)); -#132489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132490 = PCURVE('',#132491,#132496); -#132491 = PLANE('',#132492); -#132492 = AXIS2_PLACEMENT_3D('',#132493,#132494,#132495); -#132493 = CARTESIAN_POINT('',(11.,2.75,-0.258196742327)); -#132494 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#132495 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132496 = DEFINITIONAL_REPRESENTATION('',(#132497),#132501); -#132497 = LINE('',#132498,#132499); -#132498 = CARTESIAN_POINT('',(-2.75,5.000038352949E-002)); -#132499 = VECTOR('',#132500,1.); -#132500 = DIRECTION('',(-1.,0.E+000)); -#132501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132502 = ORIENTED_EDGE('',*,*,#132503,.F.); -#132503 = EDGE_CURVE('',#132504,#132469,#132506,.T.); -#132504 = VERTEX_POINT('',#132505); -#132505 = CARTESIAN_POINT('',(10.740726081328,2.85,-0.208196358798)); -#132506 = SURFACE_CURVE('',#132507,(#132511,#132518),.PCURVE_S1.); -#132507 = LINE('',#132508,#132509); -#132508 = CARTESIAN_POINT('',(10.740726081328,2.85,-0.208196358798)); -#132509 = VECTOR('',#132510,1.); -#132510 = DIRECTION('',(1.,0.E+000,0.E+000)); -#132511 = PCURVE('',#132479,#132512); -#132512 = DEFINITIONAL_REPRESENTATION('',(#132513),#132517); -#132513 = LINE('',#132514,#132515); -#132514 = CARTESIAN_POINT('',(-1.7763568394E-015,2.85)); -#132515 = VECTOR('',#132516,1.); -#132516 = DIRECTION('',(-1.,0.E+000)); -#132517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132518 = PCURVE('',#92626,#132519); -#132519 = DEFINITIONAL_REPRESENTATION('',(#132520),#132524); -#132520 = LINE('',#132521,#132522); -#132521 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#132522 = VECTOR('',#132523,1.); -#132523 = DIRECTION('',(0.E+000,1.)); -#132524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132525 = ORIENTED_EDGE('',*,*,#132526,.F.); -#132526 = EDGE_CURVE('',#132527,#132504,#132529,.T.); -#132527 = VERTEX_POINT('',#132528); -#132528 = CARTESIAN_POINT('',(10.740726081328,2.65,-0.208196358798)); -#132529 = SURFACE_CURVE('',#132530,(#132534,#132541),.PCURVE_S1.); -#132530 = LINE('',#132531,#132532); -#132531 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#134874 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#134875 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#134876 = DEFINITIONAL_REPRESENTATION('',(#134877),#134881); +#134877 = LINE('',#134878,#134879); +#134878 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#134879 = VECTOR('',#134880,1.); +#134880 = DIRECTION('',(4.440892098501E-016,-1.)); +#134881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134882 = PCURVE('',#134883,#134888); +#134883 = PLANE('',#134884); +#134884 = AXIS2_PLACEMENT_3D('',#134885,#134886,#134887); +#134885 = CARTESIAN_POINT('',(11.,2.75,-0.258196742327)); +#134886 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#134887 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134888 = DEFINITIONAL_REPRESENTATION('',(#134889),#134893); +#134889 = LINE('',#134890,#134891); +#134890 = CARTESIAN_POINT('',(-2.75,5.000038352949E-002)); +#134891 = VECTOR('',#134892,1.); +#134892 = DIRECTION('',(-1.,0.E+000)); +#134893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134894 = ORIENTED_EDGE('',*,*,#134895,.F.); +#134895 = EDGE_CURVE('',#134896,#134861,#134898,.T.); +#134896 = VERTEX_POINT('',#134897); +#134897 = CARTESIAN_POINT('',(10.740726081328,2.85,-0.208196358798)); +#134898 = SURFACE_CURVE('',#134899,(#134903,#134910),.PCURVE_S1.); +#134899 = LINE('',#134900,#134901); +#134900 = CARTESIAN_POINT('',(10.740726081328,2.85,-0.208196358798)); +#134901 = VECTOR('',#134902,1.); +#134902 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134903 = PCURVE('',#134871,#134904); +#134904 = DEFINITIONAL_REPRESENTATION('',(#134905),#134909); +#134905 = LINE('',#134906,#134907); +#134906 = CARTESIAN_POINT('',(-1.7763568394E-015,2.85)); +#134907 = VECTOR('',#134908,1.); +#134908 = DIRECTION('',(-1.,0.E+000)); +#134909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134910 = PCURVE('',#95018,#134911); +#134911 = DEFINITIONAL_REPRESENTATION('',(#134912),#134916); +#134912 = LINE('',#134913,#134914); +#134913 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#134914 = VECTOR('',#134915,1.); +#134915 = DIRECTION('',(0.E+000,1.)); +#134916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134917 = ORIENTED_EDGE('',*,*,#134918,.F.); +#134918 = EDGE_CURVE('',#134919,#134896,#134921,.T.); +#134919 = VERTEX_POINT('',#134920); +#134920 = CARTESIAN_POINT('',(10.740726081328,2.65,-0.208196358798)); +#134921 = SURFACE_CURVE('',#134922,(#134926,#134933),.PCURVE_S1.); +#134922 = LINE('',#134923,#134924); +#134923 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#132532 = VECTOR('',#132533,1.); -#132533 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132534 = PCURVE('',#132479,#132535); -#132535 = DEFINITIONAL_REPRESENTATION('',(#132536),#132540); -#132536 = LINE('',#132537,#132538); -#132537 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132538 = VECTOR('',#132539,1.); -#132539 = DIRECTION('',(-4.440892098501E-016,1.)); -#132540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132541 = PCURVE('',#132542,#132547); -#132542 = CYLINDRICAL_SURFACE('',#132543,0.208574704164); -#132543 = AXIS2_PLACEMENT_3D('',#132544,#132545,#132546); -#132544 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#134924 = VECTOR('',#134925,1.); +#134925 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134926 = PCURVE('',#134871,#134927); +#134927 = DEFINITIONAL_REPRESENTATION('',(#134928),#134932); +#134928 = LINE('',#134929,#134930); +#134929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#134930 = VECTOR('',#134931,1.); +#134931 = DIRECTION('',(-4.440892098501E-016,1.)); +#134932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134933 = PCURVE('',#134934,#134939); +#134934 = CYLINDRICAL_SURFACE('',#134935,0.208574704164); +#134935 = AXIS2_PLACEMENT_3D('',#134936,#134937,#134938); +#134936 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#132545 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132546 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132547 = DEFINITIONAL_REPRESENTATION('',(#132548),#132551); -#132548 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132549,#132550), +#134937 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#134938 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#134939 = DEFINITIONAL_REPRESENTATION('',(#134940),#134943); +#134940 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134941,#134942), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#132549 = CARTESIAN_POINT('',(4.772630242227,-2.65)); -#132550 = CARTESIAN_POINT('',(4.772630242227,-2.85)); -#132551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132552 = ORIENTED_EDGE('',*,*,#132553,.T.); -#132553 = EDGE_CURVE('',#132527,#132471,#132554,.T.); -#132554 = SURFACE_CURVE('',#132555,(#132559,#132566),.PCURVE_S1.); -#132555 = LINE('',#132556,#132557); -#132556 = CARTESIAN_POINT('',(10.740726081328,2.65,-0.208196358798)); -#132557 = VECTOR('',#132558,1.); -#132558 = DIRECTION('',(1.,0.E+000,0.E+000)); -#132559 = PCURVE('',#132479,#132560); -#132560 = DEFINITIONAL_REPRESENTATION('',(#132561),#132565); -#132561 = LINE('',#132562,#132563); -#132562 = CARTESIAN_POINT('',(-1.7763568394E-015,2.65)); -#132563 = VECTOR('',#132564,1.); -#132564 = DIRECTION('',(-1.,0.E+000)); -#132565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132566 = PCURVE('',#92682,#132567); -#132567 = DEFINITIONAL_REPRESENTATION('',(#132568),#132572); -#132568 = LINE('',#132569,#132570); -#132569 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#132570 = VECTOR('',#132571,1.); -#132571 = DIRECTION('',(0.E+000,1.)); -#132572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132573 = ADVANCED_FACE('',(#132574),#132588,.F.); -#132574 = FACE_BOUND('',#132575,.T.); -#132575 = EDGE_LOOP('',(#132576,#132606,#132629,#132656)); -#132576 = ORIENTED_EDGE('',*,*,#132577,.F.); -#132577 = EDGE_CURVE('',#132578,#132580,#132582,.T.); -#132578 = VERTEX_POINT('',#132579); -#132579 = CARTESIAN_POINT('',(11.,2.65,-0.308197125857)); -#132580 = VERTEX_POINT('',#132581); -#132581 = CARTESIAN_POINT('',(11.,2.85,-0.308197125857)); -#132582 = SURFACE_CURVE('',#132583,(#132587,#132599),.PCURVE_S1.); -#132583 = LINE('',#132584,#132585); -#132584 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#132585 = VECTOR('',#132586,1.); -#132586 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132587 = PCURVE('',#132588,#132593); -#132588 = PLANE('',#132589); -#132589 = AXIS2_PLACEMENT_3D('',#132590,#132591,#132592); -#132590 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#134941 = CARTESIAN_POINT('',(4.772630242227,-2.65)); +#134942 = CARTESIAN_POINT('',(4.772630242227,-2.85)); +#134943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134944 = ORIENTED_EDGE('',*,*,#134945,.T.); +#134945 = EDGE_CURVE('',#134919,#134863,#134946,.T.); +#134946 = SURFACE_CURVE('',#134947,(#134951,#134958),.PCURVE_S1.); +#134947 = LINE('',#134948,#134949); +#134948 = CARTESIAN_POINT('',(10.740726081328,2.65,-0.208196358798)); +#134949 = VECTOR('',#134950,1.); +#134950 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134951 = PCURVE('',#134871,#134952); +#134952 = DEFINITIONAL_REPRESENTATION('',(#134953),#134957); +#134953 = LINE('',#134954,#134955); +#134954 = CARTESIAN_POINT('',(-1.7763568394E-015,2.65)); +#134955 = VECTOR('',#134956,1.); +#134956 = DIRECTION('',(-1.,0.E+000)); +#134957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134958 = PCURVE('',#95074,#134959); +#134959 = DEFINITIONAL_REPRESENTATION('',(#134960),#134964); +#134960 = LINE('',#134961,#134962); +#134961 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#134962 = VECTOR('',#134963,1.); +#134963 = DIRECTION('',(0.E+000,1.)); +#134964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134965 = ADVANCED_FACE('',(#134966),#134980,.F.); +#134966 = FACE_BOUND('',#134967,.T.); +#134967 = EDGE_LOOP('',(#134968,#134998,#135021,#135048)); +#134968 = ORIENTED_EDGE('',*,*,#134969,.F.); +#134969 = EDGE_CURVE('',#134970,#134972,#134974,.T.); +#134970 = VERTEX_POINT('',#134971); +#134971 = CARTESIAN_POINT('',(11.,2.65,-0.308197125857)); +#134972 = VERTEX_POINT('',#134973); +#134973 = CARTESIAN_POINT('',(11.,2.85,-0.308197125857)); +#134974 = SURFACE_CURVE('',#134975,(#134979,#134991),.PCURVE_S1.); +#134975 = LINE('',#134976,#134977); +#134976 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#134977 = VECTOR('',#134978,1.); +#134978 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#134979 = PCURVE('',#134980,#134985); +#134980 = PLANE('',#134981); +#134981 = AXIS2_PLACEMENT_3D('',#134982,#134983,#134984); +#134982 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#132591 = DIRECTION('',(0.E+000,0.E+000,1.)); -#132592 = DIRECTION('',(1.,0.E+000,0.E+000)); -#132593 = DEFINITIONAL_REPRESENTATION('',(#132594),#132598); -#132594 = LINE('',#132595,#132596); -#132595 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#132596 = VECTOR('',#132597,1.); -#132597 = DIRECTION('',(4.440892098501E-016,1.)); -#132598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132599 = PCURVE('',#132491,#132600); -#132600 = DEFINITIONAL_REPRESENTATION('',(#132601),#132605); -#132601 = LINE('',#132602,#132603); -#132602 = CARTESIAN_POINT('',(-2.75,-5.000038352949E-002)); -#132603 = VECTOR('',#132604,1.); -#132604 = DIRECTION('',(1.,0.E+000)); -#132605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132606 = ORIENTED_EDGE('',*,*,#132607,.F.); -#132607 = EDGE_CURVE('',#132608,#132578,#132610,.T.); -#132608 = VERTEX_POINT('',#132609); -#132609 = CARTESIAN_POINT('',(10.74341632541,2.65,-0.308197125857)); -#132610 = SURFACE_CURVE('',#132611,(#132615,#132622),.PCURVE_S1.); -#132611 = LINE('',#132612,#132613); -#132612 = CARTESIAN_POINT('',(10.74341632541,2.65,-0.308197125857)); -#132613 = VECTOR('',#132614,1.); -#132614 = DIRECTION('',(1.,0.E+000,0.E+000)); -#132615 = PCURVE('',#132588,#132616); -#132616 = DEFINITIONAL_REPRESENTATION('',(#132617),#132621); -#132617 = LINE('',#132618,#132619); -#132618 = CARTESIAN_POINT('',(1.7763568394E-015,2.65)); -#132619 = VECTOR('',#132620,1.); -#132620 = DIRECTION('',(1.,0.E+000)); -#132621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132622 = PCURVE('',#92682,#132623); -#132623 = DEFINITIONAL_REPRESENTATION('',(#132624),#132628); -#132624 = LINE('',#132625,#132626); -#132625 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#132626 = VECTOR('',#132627,1.); -#132627 = DIRECTION('',(0.E+000,1.)); -#132628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132629 = ORIENTED_EDGE('',*,*,#132630,.F.); -#132630 = EDGE_CURVE('',#132631,#132608,#132633,.T.); -#132631 = VERTEX_POINT('',#132632); -#132632 = CARTESIAN_POINT('',(10.74341632541,2.85,-0.308197125857)); -#132633 = SURFACE_CURVE('',#132634,(#132638,#132645),.PCURVE_S1.); -#132634 = LINE('',#132635,#132636); -#132635 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#134983 = DIRECTION('',(0.E+000,0.E+000,1.)); +#134984 = DIRECTION('',(1.,0.E+000,0.E+000)); +#134985 = DEFINITIONAL_REPRESENTATION('',(#134986),#134990); +#134986 = LINE('',#134987,#134988); +#134987 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#134988 = VECTOR('',#134989,1.); +#134989 = DIRECTION('',(4.440892098501E-016,1.)); +#134990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134991 = PCURVE('',#134883,#134992); +#134992 = DEFINITIONAL_REPRESENTATION('',(#134993),#134997); +#134993 = LINE('',#134994,#134995); +#134994 = CARTESIAN_POINT('',(-2.75,-5.000038352949E-002)); +#134995 = VECTOR('',#134996,1.); +#134996 = DIRECTION('',(1.,0.E+000)); +#134997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#134998 = ORIENTED_EDGE('',*,*,#134999,.F.); +#134999 = EDGE_CURVE('',#135000,#134970,#135002,.T.); +#135000 = VERTEX_POINT('',#135001); +#135001 = CARTESIAN_POINT('',(10.74341632541,2.65,-0.308197125857)); +#135002 = SURFACE_CURVE('',#135003,(#135007,#135014),.PCURVE_S1.); +#135003 = LINE('',#135004,#135005); +#135004 = CARTESIAN_POINT('',(10.74341632541,2.65,-0.308197125857)); +#135005 = VECTOR('',#135006,1.); +#135006 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135007 = PCURVE('',#134980,#135008); +#135008 = DEFINITIONAL_REPRESENTATION('',(#135009),#135013); +#135009 = LINE('',#135010,#135011); +#135010 = CARTESIAN_POINT('',(1.7763568394E-015,2.65)); +#135011 = VECTOR('',#135012,1.); +#135012 = DIRECTION('',(1.,0.E+000)); +#135013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135014 = PCURVE('',#95074,#135015); +#135015 = DEFINITIONAL_REPRESENTATION('',(#135016),#135020); +#135016 = LINE('',#135017,#135018); +#135017 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#135018 = VECTOR('',#135019,1.); +#135019 = DIRECTION('',(0.E+000,1.)); +#135020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135021 = ORIENTED_EDGE('',*,*,#135022,.F.); +#135022 = EDGE_CURVE('',#135023,#135000,#135025,.T.); +#135023 = VERTEX_POINT('',#135024); +#135024 = CARTESIAN_POINT('',(10.74341632541,2.85,-0.308197125857)); +#135025 = SURFACE_CURVE('',#135026,(#135030,#135037),.PCURVE_S1.); +#135026 = LINE('',#135027,#135028); +#135027 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#132636 = VECTOR('',#132637,1.); -#132637 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132638 = PCURVE('',#132588,#132639); -#132639 = DEFINITIONAL_REPRESENTATION('',(#132640),#132644); -#132640 = LINE('',#132641,#132642); -#132641 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132642 = VECTOR('',#132643,1.); -#132643 = DIRECTION('',(-4.440892098501E-016,-1.)); -#132644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132645 = PCURVE('',#132646,#132651); -#132646 = CYLINDRICAL_SURFACE('',#132647,0.308574064194); -#132647 = AXIS2_PLACEMENT_3D('',#132648,#132649,#132650); -#132648 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#135028 = VECTOR('',#135029,1.); +#135029 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135030 = PCURVE('',#134980,#135031); +#135031 = DEFINITIONAL_REPRESENTATION('',(#135032),#135036); +#135032 = LINE('',#135033,#135034); +#135033 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135034 = VECTOR('',#135035,1.); +#135035 = DIRECTION('',(-4.440892098501E-016,-1.)); +#135036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135037 = PCURVE('',#135038,#135043); +#135038 = CYLINDRICAL_SURFACE('',#135039,0.308574064194); +#135039 = AXIS2_PLACEMENT_3D('',#135040,#135041,#135042); +#135040 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#132649 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132650 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132651 = DEFINITIONAL_REPRESENTATION('',(#132652),#132655); -#132652 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132653,#132654), +#135041 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135042 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135043 = DEFINITIONAL_REPRESENTATION('',(#135044),#135047); +#135044 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135045,#135046), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#132653 = CARTESIAN_POINT('',(4.761821717947,-2.85)); -#132654 = CARTESIAN_POINT('',(4.761821717947,-2.65)); -#132655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132656 = ORIENTED_EDGE('',*,*,#132657,.T.); -#132657 = EDGE_CURVE('',#132631,#132580,#132658,.T.); -#132658 = SURFACE_CURVE('',#132659,(#132663,#132670),.PCURVE_S1.); -#132659 = LINE('',#132660,#132661); -#132660 = CARTESIAN_POINT('',(10.74341632541,2.85,-0.308197125857)); -#132661 = VECTOR('',#132662,1.); -#132662 = DIRECTION('',(1.,0.E+000,0.E+000)); -#132663 = PCURVE('',#132588,#132664); -#132664 = DEFINITIONAL_REPRESENTATION('',(#132665),#132669); -#132665 = LINE('',#132666,#132667); -#132666 = CARTESIAN_POINT('',(1.7763568394E-015,2.85)); -#132667 = VECTOR('',#132668,1.); -#132668 = DIRECTION('',(1.,0.E+000)); -#132669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132670 = PCURVE('',#92626,#132671); -#132671 = DEFINITIONAL_REPRESENTATION('',(#132672),#132676); -#132672 = LINE('',#132673,#132674); -#132673 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#132674 = VECTOR('',#132675,1.); -#132675 = DIRECTION('',(0.E+000,1.)); -#132676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132677 = ADVANCED_FACE('',(#132678),#132542,.F.); -#132678 = FACE_BOUND('',#132679,.F.); -#132679 = EDGE_LOOP('',(#132680,#132703,#132730,#132755)); -#132680 = ORIENTED_EDGE('',*,*,#132681,.F.); -#132681 = EDGE_CURVE('',#132682,#132527,#132684,.T.); -#132682 = VERTEX_POINT('',#132683); -#132683 = CARTESIAN_POINT('',(10.51959417205,2.65,0.E+000)); -#132684 = SURFACE_CURVE('',#132685,(#132690,#132696),.PCURVE_S1.); -#132685 = CIRCLE('',#132686,0.208574704164); -#132686 = AXIS2_PLACEMENT_3D('',#132687,#132688,#132689); -#132687 = CARTESIAN_POINT('',(10.728168876214,2.65,2.640924866458E-017) - ); -#132688 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132689 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132690 = PCURVE('',#132542,#132691); -#132691 = DEFINITIONAL_REPRESENTATION('',(#132692),#132695); -#132692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132693,#132694), +#135045 = CARTESIAN_POINT('',(4.761821717947,-2.85)); +#135046 = CARTESIAN_POINT('',(4.761821717947,-2.65)); +#135047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135048 = ORIENTED_EDGE('',*,*,#135049,.T.); +#135049 = EDGE_CURVE('',#135023,#134972,#135050,.T.); +#135050 = SURFACE_CURVE('',#135051,(#135055,#135062),.PCURVE_S1.); +#135051 = LINE('',#135052,#135053); +#135052 = CARTESIAN_POINT('',(10.74341632541,2.85,-0.308197125857)); +#135053 = VECTOR('',#135054,1.); +#135054 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135055 = PCURVE('',#134980,#135056); +#135056 = DEFINITIONAL_REPRESENTATION('',(#135057),#135061); +#135057 = LINE('',#135058,#135059); +#135058 = CARTESIAN_POINT('',(1.7763568394E-015,2.85)); +#135059 = VECTOR('',#135060,1.); +#135060 = DIRECTION('',(1.,0.E+000)); +#135061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135062 = PCURVE('',#95018,#135063); +#135063 = DEFINITIONAL_REPRESENTATION('',(#135064),#135068); +#135064 = LINE('',#135065,#135066); +#135065 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#135066 = VECTOR('',#135067,1.); +#135067 = DIRECTION('',(0.E+000,1.)); +#135068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135069 = ADVANCED_FACE('',(#135070),#134934,.F.); +#135070 = FACE_BOUND('',#135071,.F.); +#135071 = EDGE_LOOP('',(#135072,#135095,#135122,#135147)); +#135072 = ORIENTED_EDGE('',*,*,#135073,.F.); +#135073 = EDGE_CURVE('',#135074,#134919,#135076,.T.); +#135074 = VERTEX_POINT('',#135075); +#135075 = CARTESIAN_POINT('',(10.51959417205,2.65,0.E+000)); +#135076 = SURFACE_CURVE('',#135077,(#135082,#135088),.PCURVE_S1.); +#135077 = CIRCLE('',#135078,0.208574704164); +#135078 = AXIS2_PLACEMENT_3D('',#135079,#135080,#135081); +#135079 = CARTESIAN_POINT('',(10.728168876214,2.65,2.640924866458E-017) + ); +#135080 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135081 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135082 = PCURVE('',#134934,#135083); +#135083 = DEFINITIONAL_REPRESENTATION('',(#135084),#135087); +#135084 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135085,#135086), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#132693 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#132694 = CARTESIAN_POINT('',(4.772630242227,-2.65)); -#132695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135085 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#135086 = CARTESIAN_POINT('',(4.772630242227,-2.65)); +#135087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132696 = PCURVE('',#92682,#132697); -#132697 = DEFINITIONAL_REPRESENTATION('',(#132698),#132702); -#132698 = CIRCLE('',#132699,0.208574704164); -#132699 = AXIS2_PLACEMENT_2D('',#132700,#132701); -#132700 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#132701 = DIRECTION('',(0.E+000,1.)); -#132702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135088 = PCURVE('',#95074,#135089); +#135089 = DEFINITIONAL_REPRESENTATION('',(#135090),#135094); +#135090 = CIRCLE('',#135091,0.208574704164); +#135091 = AXIS2_PLACEMENT_2D('',#135092,#135093); +#135092 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#135093 = DIRECTION('',(0.E+000,1.)); +#135094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132703 = ORIENTED_EDGE('',*,*,#132704,.F.); -#132704 = EDGE_CURVE('',#132705,#132682,#132707,.T.); -#132705 = VERTEX_POINT('',#132706); -#132706 = CARTESIAN_POINT('',(10.51959417205,2.85,0.E+000)); -#132707 = SURFACE_CURVE('',#132708,(#132712,#132718),.PCURVE_S1.); -#132708 = LINE('',#132709,#132710); -#132709 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#135095 = ORIENTED_EDGE('',*,*,#135096,.F.); +#135096 = EDGE_CURVE('',#135097,#135074,#135099,.T.); +#135097 = VERTEX_POINT('',#135098); +#135098 = CARTESIAN_POINT('',(10.51959417205,2.85,0.E+000)); +#135099 = SURFACE_CURVE('',#135100,(#135104,#135110),.PCURVE_S1.); +#135100 = LINE('',#135101,#135102); +#135101 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#132710 = VECTOR('',#132711,1.); -#132711 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132712 = PCURVE('',#132542,#132713); -#132713 = DEFINITIONAL_REPRESENTATION('',(#132714),#132717); -#132714 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132715,#132716), +#135102 = VECTOR('',#135103,1.); +#135103 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135104 = PCURVE('',#134934,#135105); +#135105 = DEFINITIONAL_REPRESENTATION('',(#135106),#135109); +#135106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135107,#135108), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#132715 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#132716 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#132717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135107 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#135108 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#135109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132718 = PCURVE('',#132719,#132724); -#132719 = PLANE('',#132720); -#132720 = AXIS2_PLACEMENT_3D('',#132721,#132722,#132723); -#132721 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#135110 = PCURVE('',#135111,#135116); +#135111 = PLANE('',#135112); +#135112 = AXIS2_PLACEMENT_3D('',#135113,#135114,#135115); +#135113 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#132722 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132723 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132724 = DEFINITIONAL_REPRESENTATION('',(#132725),#132729); -#132725 = LINE('',#132726,#132727); -#132726 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#132727 = VECTOR('',#132728,1.); -#132728 = DIRECTION('',(-1.,0.E+000)); -#132729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132730 = ORIENTED_EDGE('',*,*,#132731,.T.); -#132731 = EDGE_CURVE('',#132705,#132504,#132732,.T.); -#132732 = SURFACE_CURVE('',#132733,(#132738,#132744),.PCURVE_S1.); -#132733 = CIRCLE('',#132734,0.208574704164); -#132734 = AXIS2_PLACEMENT_3D('',#132735,#132736,#132737); -#132735 = CARTESIAN_POINT('',(10.728168876214,2.85,2.640924866458E-017) - ); -#132736 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132737 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132738 = PCURVE('',#132542,#132739); -#132739 = DEFINITIONAL_REPRESENTATION('',(#132740),#132743); -#132740 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132741,#132742), +#135114 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135115 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135116 = DEFINITIONAL_REPRESENTATION('',(#135117),#135121); +#135117 = LINE('',#135118,#135119); +#135118 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#135119 = VECTOR('',#135120,1.); +#135120 = DIRECTION('',(-1.,0.E+000)); +#135121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135122 = ORIENTED_EDGE('',*,*,#135123,.T.); +#135123 = EDGE_CURVE('',#135097,#134896,#135124,.T.); +#135124 = SURFACE_CURVE('',#135125,(#135130,#135136),.PCURVE_S1.); +#135125 = CIRCLE('',#135126,0.208574704164); +#135126 = AXIS2_PLACEMENT_3D('',#135127,#135128,#135129); +#135127 = CARTESIAN_POINT('',(10.728168876214,2.85,2.640924866458E-017) + ); +#135128 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135129 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135130 = PCURVE('',#134934,#135131); +#135131 = DEFINITIONAL_REPRESENTATION('',(#135132),#135135); +#135132 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135133,#135134), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#132741 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#132742 = CARTESIAN_POINT('',(4.772630242227,-2.85)); -#132743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135133 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#135134 = CARTESIAN_POINT('',(4.772630242227,-2.85)); +#135135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132744 = PCURVE('',#92626,#132745); -#132745 = DEFINITIONAL_REPRESENTATION('',(#132746),#132754); -#132746 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132747,#132748,#132749, - #132750,#132751,#132752,#132753),.UNSPECIFIED.,.T.,.F.) +#135136 = PCURVE('',#95018,#135137); +#135137 = DEFINITIONAL_REPRESENTATION('',(#135138),#135146); +#135138 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135139,#135140,#135141, + #135142,#135143,#135144,#135145),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#132747 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#132748 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#132749 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#132750 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#132751 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#132752 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#132753 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#132754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132755 = ORIENTED_EDGE('',*,*,#132526,.F.); -#132756 = ADVANCED_FACE('',(#132757),#132646,.T.); -#132757 = FACE_BOUND('',#132758,.T.); -#132758 = EDGE_LOOP('',(#132759,#132809,#132810,#132856)); -#132759 = ORIENTED_EDGE('',*,*,#132760,.T.); -#132760 = EDGE_CURVE('',#132761,#132631,#132763,.T.); -#132761 = VERTEX_POINT('',#132762); -#132762 = CARTESIAN_POINT('',(10.419594812019,2.85,0.E+000)); -#132763 = SURFACE_CURVE('',#132764,(#132769,#132798),.PCURVE_S1.); -#132764 = CIRCLE('',#132765,0.308574064194); -#132765 = AXIS2_PLACEMENT_3D('',#132766,#132767,#132768); -#132766 = CARTESIAN_POINT('',(10.728168876214,2.85,2.640924866458E-017) - ); -#132767 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132768 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132769 = PCURVE('',#132646,#132770); -#132770 = DEFINITIONAL_REPRESENTATION('',(#132771),#132797); -#132771 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#132772,#132773,#132774, - #132775,#132776,#132777,#132778,#132779,#132780,#132781,#132782, - #132783,#132784,#132785,#132786,#132787,#132788,#132789,#132790, - #132791,#132792,#132793,#132794,#132795,#132796),.UNSPECIFIED.,.F., +#135139 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#135140 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#135141 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#135142 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#135143 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#135144 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#135145 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#135146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135147 = ORIENTED_EDGE('',*,*,#134918,.F.); +#135148 = ADVANCED_FACE('',(#135149),#135038,.T.); +#135149 = FACE_BOUND('',#135150,.T.); +#135150 = EDGE_LOOP('',(#135151,#135201,#135202,#135248)); +#135151 = ORIENTED_EDGE('',*,*,#135152,.T.); +#135152 = EDGE_CURVE('',#135153,#135023,#135155,.T.); +#135153 = VERTEX_POINT('',#135154); +#135154 = CARTESIAN_POINT('',(10.419594812019,2.85,0.E+000)); +#135155 = SURFACE_CURVE('',#135156,(#135161,#135190),.PCURVE_S1.); +#135156 = CIRCLE('',#135157,0.308574064194); +#135157 = AXIS2_PLACEMENT_3D('',#135158,#135159,#135160); +#135158 = CARTESIAN_POINT('',(10.728168876214,2.85,2.640924866458E-017) + ); +#135159 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135160 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135161 = PCURVE('',#135038,#135162); +#135162 = DEFINITIONAL_REPRESENTATION('',(#135163),#135189); +#135163 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135164,#135165,#135166, + #135167,#135168,#135169,#135170,#135171,#135172,#135173,#135174, + #135175,#135176,#135177,#135178,#135179,#135180,#135181,#135182, + #135183,#135184,#135185,#135186,#135187,#135188),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -163592,71 +166594,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#132772 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#132773 = CARTESIAN_POINT('',(3.166141578807,-2.85)); -#132774 = CARTESIAN_POINT('',(3.215239429242,-2.85)); -#132775 = CARTESIAN_POINT('',(3.288886204895,-2.85)); -#132776 = CARTESIAN_POINT('',(3.362532980548,-2.85)); -#132777 = CARTESIAN_POINT('',(3.4361797562,-2.85)); -#132778 = CARTESIAN_POINT('',(3.509826531853,-2.85)); -#132779 = CARTESIAN_POINT('',(3.583473307505,-2.85)); -#132780 = CARTESIAN_POINT('',(3.657120083158,-2.85)); -#132781 = CARTESIAN_POINT('',(3.730766858811,-2.85)); -#132782 = CARTESIAN_POINT('',(3.804413634463,-2.85)); -#132783 = CARTESIAN_POINT('',(3.878060410116,-2.85)); -#132784 = CARTESIAN_POINT('',(3.951707185768,-2.85)); -#132785 = CARTESIAN_POINT('',(4.025353961421,-2.85)); -#132786 = CARTESIAN_POINT('',(4.099000737074,-2.85)); -#132787 = CARTESIAN_POINT('',(4.172647512726,-2.85)); -#132788 = CARTESIAN_POINT('',(4.246294288379,-2.85)); -#132789 = CARTESIAN_POINT('',(4.319941064031,-2.85)); -#132790 = CARTESIAN_POINT('',(4.393587839684,-2.85)); -#132791 = CARTESIAN_POINT('',(4.467234615337,-2.85)); -#132792 = CARTESIAN_POINT('',(4.540881390989,-2.85)); -#132793 = CARTESIAN_POINT('',(4.614528166642,-2.85)); -#132794 = CARTESIAN_POINT('',(4.688174942294,-2.85)); -#132795 = CARTESIAN_POINT('',(4.737272792729,-2.85)); -#132796 = CARTESIAN_POINT('',(4.761821717947,-2.85)); -#132797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132798 = PCURVE('',#92626,#132799); -#132799 = DEFINITIONAL_REPRESENTATION('',(#132800),#132808); -#132800 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#132801,#132802,#132803, - #132804,#132805,#132806,#132807),.UNSPECIFIED.,.T.,.F.) +#135164 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#135165 = CARTESIAN_POINT('',(3.166141578807,-2.85)); +#135166 = CARTESIAN_POINT('',(3.215239429242,-2.85)); +#135167 = CARTESIAN_POINT('',(3.288886204895,-2.85)); +#135168 = CARTESIAN_POINT('',(3.362532980548,-2.85)); +#135169 = CARTESIAN_POINT('',(3.4361797562,-2.85)); +#135170 = CARTESIAN_POINT('',(3.509826531853,-2.85)); +#135171 = CARTESIAN_POINT('',(3.583473307505,-2.85)); +#135172 = CARTESIAN_POINT('',(3.657120083158,-2.85)); +#135173 = CARTESIAN_POINT('',(3.730766858811,-2.85)); +#135174 = CARTESIAN_POINT('',(3.804413634463,-2.85)); +#135175 = CARTESIAN_POINT('',(3.878060410116,-2.85)); +#135176 = CARTESIAN_POINT('',(3.951707185768,-2.85)); +#135177 = CARTESIAN_POINT('',(4.025353961421,-2.85)); +#135178 = CARTESIAN_POINT('',(4.099000737074,-2.85)); +#135179 = CARTESIAN_POINT('',(4.172647512726,-2.85)); +#135180 = CARTESIAN_POINT('',(4.246294288379,-2.85)); +#135181 = CARTESIAN_POINT('',(4.319941064031,-2.85)); +#135182 = CARTESIAN_POINT('',(4.393587839684,-2.85)); +#135183 = CARTESIAN_POINT('',(4.467234615337,-2.85)); +#135184 = CARTESIAN_POINT('',(4.540881390989,-2.85)); +#135185 = CARTESIAN_POINT('',(4.614528166642,-2.85)); +#135186 = CARTESIAN_POINT('',(4.688174942294,-2.85)); +#135187 = CARTESIAN_POINT('',(4.737272792729,-2.85)); +#135188 = CARTESIAN_POINT('',(4.761821717947,-2.85)); +#135189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135190 = PCURVE('',#95018,#135191); +#135191 = DEFINITIONAL_REPRESENTATION('',(#135192),#135200); +#135192 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135193,#135194,#135195, + #135196,#135197,#135198,#135199),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#132801 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#132802 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#132803 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#132804 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#132805 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#132806 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#132807 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#132808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132809 = ORIENTED_EDGE('',*,*,#132630,.T.); -#132810 = ORIENTED_EDGE('',*,*,#132811,.F.); -#132811 = EDGE_CURVE('',#132812,#132608,#132814,.T.); -#132812 = VERTEX_POINT('',#132813); -#132813 = CARTESIAN_POINT('',(10.419594812019,2.65,0.E+000)); -#132814 = SURFACE_CURVE('',#132815,(#132820,#132849),.PCURVE_S1.); -#132815 = CIRCLE('',#132816,0.308574064194); -#132816 = AXIS2_PLACEMENT_3D('',#132817,#132818,#132819); -#132817 = CARTESIAN_POINT('',(10.728168876214,2.65,2.640924866458E-017) - ); -#132818 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132819 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#132820 = PCURVE('',#132646,#132821); -#132821 = DEFINITIONAL_REPRESENTATION('',(#132822),#132848); -#132822 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#132823,#132824,#132825, - #132826,#132827,#132828,#132829,#132830,#132831,#132832,#132833, - #132834,#132835,#132836,#132837,#132838,#132839,#132840,#132841, - #132842,#132843,#132844,#132845,#132846,#132847),.UNSPECIFIED.,.F., +#135193 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#135194 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#135195 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#135196 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#135197 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#135198 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#135199 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#135200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135201 = ORIENTED_EDGE('',*,*,#135022,.T.); +#135202 = ORIENTED_EDGE('',*,*,#135203,.F.); +#135203 = EDGE_CURVE('',#135204,#135000,#135206,.T.); +#135204 = VERTEX_POINT('',#135205); +#135205 = CARTESIAN_POINT('',(10.419594812019,2.65,0.E+000)); +#135206 = SURFACE_CURVE('',#135207,(#135212,#135241),.PCURVE_S1.); +#135207 = CIRCLE('',#135208,0.308574064194); +#135208 = AXIS2_PLACEMENT_3D('',#135209,#135210,#135211); +#135209 = CARTESIAN_POINT('',(10.728168876214,2.65,2.640924866458E-017) + ); +#135210 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135211 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135212 = PCURVE('',#135038,#135213); +#135213 = DEFINITIONAL_REPRESENTATION('',(#135214),#135240); +#135214 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135215,#135216,#135217, + #135218,#135219,#135220,#135221,#135222,#135223,#135224,#135225, + #135226,#135227,#135228,#135229,#135230,#135231,#135232,#135233, + #135234,#135235,#135236,#135237,#135238,#135239),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -163664,275 +166666,275 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#132823 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#132824 = CARTESIAN_POINT('',(3.166141578807,-2.65)); -#132825 = CARTESIAN_POINT('',(3.215239429242,-2.65)); -#132826 = CARTESIAN_POINT('',(3.288886204895,-2.65)); -#132827 = CARTESIAN_POINT('',(3.362532980548,-2.65)); -#132828 = CARTESIAN_POINT('',(3.4361797562,-2.65)); -#132829 = CARTESIAN_POINT('',(3.509826531853,-2.65)); -#132830 = CARTESIAN_POINT('',(3.583473307505,-2.65)); -#132831 = CARTESIAN_POINT('',(3.657120083158,-2.65)); -#132832 = CARTESIAN_POINT('',(3.730766858811,-2.65)); -#132833 = CARTESIAN_POINT('',(3.804413634463,-2.65)); -#132834 = CARTESIAN_POINT('',(3.878060410116,-2.65)); -#132835 = CARTESIAN_POINT('',(3.951707185768,-2.65)); -#132836 = CARTESIAN_POINT('',(4.025353961421,-2.65)); -#132837 = CARTESIAN_POINT('',(4.099000737074,-2.65)); -#132838 = CARTESIAN_POINT('',(4.172647512726,-2.65)); -#132839 = CARTESIAN_POINT('',(4.246294288379,-2.65)); -#132840 = CARTESIAN_POINT('',(4.319941064031,-2.65)); -#132841 = CARTESIAN_POINT('',(4.393587839684,-2.65)); -#132842 = CARTESIAN_POINT('',(4.467234615337,-2.65)); -#132843 = CARTESIAN_POINT('',(4.540881390989,-2.65)); -#132844 = CARTESIAN_POINT('',(4.614528166642,-2.65)); -#132845 = CARTESIAN_POINT('',(4.688174942294,-2.65)); -#132846 = CARTESIAN_POINT('',(4.737272792729,-2.65)); -#132847 = CARTESIAN_POINT('',(4.761821717947,-2.65)); -#132848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132849 = PCURVE('',#92682,#132850); -#132850 = DEFINITIONAL_REPRESENTATION('',(#132851),#132855); -#132851 = CIRCLE('',#132852,0.308574064194); -#132852 = AXIS2_PLACEMENT_2D('',#132853,#132854); -#132853 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#132854 = DIRECTION('',(0.E+000,1.)); -#132855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132856 = ORIENTED_EDGE('',*,*,#132857,.T.); -#132857 = EDGE_CURVE('',#132812,#132761,#132858,.T.); -#132858 = SURFACE_CURVE('',#132859,(#132863,#132869),.PCURVE_S1.); -#132859 = LINE('',#132860,#132861); -#132860 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#135215 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#135216 = CARTESIAN_POINT('',(3.166141578807,-2.65)); +#135217 = CARTESIAN_POINT('',(3.215239429242,-2.65)); +#135218 = CARTESIAN_POINT('',(3.288886204895,-2.65)); +#135219 = CARTESIAN_POINT('',(3.362532980548,-2.65)); +#135220 = CARTESIAN_POINT('',(3.4361797562,-2.65)); +#135221 = CARTESIAN_POINT('',(3.509826531853,-2.65)); +#135222 = CARTESIAN_POINT('',(3.583473307505,-2.65)); +#135223 = CARTESIAN_POINT('',(3.657120083158,-2.65)); +#135224 = CARTESIAN_POINT('',(3.730766858811,-2.65)); +#135225 = CARTESIAN_POINT('',(3.804413634463,-2.65)); +#135226 = CARTESIAN_POINT('',(3.878060410116,-2.65)); +#135227 = CARTESIAN_POINT('',(3.951707185768,-2.65)); +#135228 = CARTESIAN_POINT('',(4.025353961421,-2.65)); +#135229 = CARTESIAN_POINT('',(4.099000737074,-2.65)); +#135230 = CARTESIAN_POINT('',(4.172647512726,-2.65)); +#135231 = CARTESIAN_POINT('',(4.246294288379,-2.65)); +#135232 = CARTESIAN_POINT('',(4.319941064031,-2.65)); +#135233 = CARTESIAN_POINT('',(4.393587839684,-2.65)); +#135234 = CARTESIAN_POINT('',(4.467234615337,-2.65)); +#135235 = CARTESIAN_POINT('',(4.540881390989,-2.65)); +#135236 = CARTESIAN_POINT('',(4.614528166642,-2.65)); +#135237 = CARTESIAN_POINT('',(4.688174942294,-2.65)); +#135238 = CARTESIAN_POINT('',(4.737272792729,-2.65)); +#135239 = CARTESIAN_POINT('',(4.761821717947,-2.65)); +#135240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135241 = PCURVE('',#95074,#135242); +#135242 = DEFINITIONAL_REPRESENTATION('',(#135243),#135247); +#135243 = CIRCLE('',#135244,0.308574064194); +#135244 = AXIS2_PLACEMENT_2D('',#135245,#135246); +#135245 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#135246 = DIRECTION('',(0.E+000,1.)); +#135247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135248 = ORIENTED_EDGE('',*,*,#135249,.T.); +#135249 = EDGE_CURVE('',#135204,#135153,#135250,.T.); +#135250 = SURFACE_CURVE('',#135251,(#135255,#135261),.PCURVE_S1.); +#135251 = LINE('',#135252,#135253); +#135252 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#132861 = VECTOR('',#132862,1.); -#132862 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132863 = PCURVE('',#132646,#132864); -#132864 = DEFINITIONAL_REPRESENTATION('',(#132865),#132868); -#132865 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132866,#132867), +#135253 = VECTOR('',#135254,1.); +#135254 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135255 = PCURVE('',#135038,#135256); +#135256 = DEFINITIONAL_REPRESENTATION('',(#135257),#135260); +#135257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135258,#135259), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#132866 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#132867 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#132868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135258 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#135259 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#135260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#132869 = PCURVE('',#132870,#132875); -#132870 = PLANE('',#132871); -#132871 = AXIS2_PLACEMENT_3D('',#132872,#132873,#132874); -#132872 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#135261 = PCURVE('',#135262,#135267); +#135262 = PLANE('',#135263); +#135263 = AXIS2_PLACEMENT_3D('',#135264,#135265,#135266); +#135264 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#132873 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132874 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132875 = DEFINITIONAL_REPRESENTATION('',(#132876),#132880); -#132876 = LINE('',#132877,#132878); -#132877 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#132878 = VECTOR('',#132879,1.); -#132879 = DIRECTION('',(-1.,0.E+000)); -#132880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132881 = ADVANCED_FACE('',(#132882),#132870,.T.); -#132882 = FACE_BOUND('',#132883,.T.); -#132883 = EDGE_LOOP('',(#132884,#132913,#132934,#132935)); -#132884 = ORIENTED_EDGE('',*,*,#132885,.T.); -#132885 = EDGE_CURVE('',#132886,#132888,#132890,.T.); -#132886 = VERTEX_POINT('',#132887); -#132887 = CARTESIAN_POINT('',(10.419594812019,2.65,0.530776333563)); -#132888 = VERTEX_POINT('',#132889); -#132889 = CARTESIAN_POINT('',(10.419594812019,2.85,0.530776333563)); -#132890 = SURFACE_CURVE('',#132891,(#132895,#132902),.PCURVE_S1.); -#132891 = LINE('',#132892,#132893); -#132892 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#135265 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135266 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135267 = DEFINITIONAL_REPRESENTATION('',(#135268),#135272); +#135268 = LINE('',#135269,#135270); +#135269 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#135270 = VECTOR('',#135271,1.); +#135271 = DIRECTION('',(-1.,0.E+000)); +#135272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135273 = ADVANCED_FACE('',(#135274),#135262,.T.); +#135274 = FACE_BOUND('',#135275,.T.); +#135275 = EDGE_LOOP('',(#135276,#135305,#135326,#135327)); +#135276 = ORIENTED_EDGE('',*,*,#135277,.T.); +#135277 = EDGE_CURVE('',#135278,#135280,#135282,.T.); +#135278 = VERTEX_POINT('',#135279); +#135279 = CARTESIAN_POINT('',(10.419594812019,2.65,0.530776333563)); +#135280 = VERTEX_POINT('',#135281); +#135281 = CARTESIAN_POINT('',(10.419594812019,2.85,0.530776333563)); +#135282 = SURFACE_CURVE('',#135283,(#135287,#135294),.PCURVE_S1.); +#135283 = LINE('',#135284,#135285); +#135284 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#132893 = VECTOR('',#132894,1.); -#132894 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132895 = PCURVE('',#132870,#132896); -#132896 = DEFINITIONAL_REPRESENTATION('',(#132897),#132901); -#132897 = LINE('',#132898,#132899); -#132898 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132899 = VECTOR('',#132900,1.); -#132900 = DIRECTION('',(-1.,0.E+000)); -#132901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132902 = PCURVE('',#132903,#132908); -#132903 = CYLINDRICAL_SURFACE('',#132904,0.119270391569); -#132904 = AXIS2_PLACEMENT_3D('',#132905,#132906,#132907); -#132905 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#135285 = VECTOR('',#135286,1.); +#135286 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135287 = PCURVE('',#135262,#135288); +#135288 = DEFINITIONAL_REPRESENTATION('',(#135289),#135293); +#135289 = LINE('',#135290,#135291); +#135290 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135291 = VECTOR('',#135292,1.); +#135292 = DIRECTION('',(-1.,0.E+000)); +#135293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135294 = PCURVE('',#135295,#135300); +#135295 = CYLINDRICAL_SURFACE('',#135296,0.119270391569); +#135296 = AXIS2_PLACEMENT_3D('',#135297,#135298,#135299); +#135297 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#132906 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132907 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132908 = DEFINITIONAL_REPRESENTATION('',(#132909),#132912); -#132909 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132910,#132911), +#135298 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135299 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135300 = DEFINITIONAL_REPRESENTATION('',(#135301),#135304); +#135301 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135302,#135303), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#132910 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#132911 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#132912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132913 = ORIENTED_EDGE('',*,*,#132914,.T.); -#132914 = EDGE_CURVE('',#132888,#132761,#132915,.T.); -#132915 = SURFACE_CURVE('',#132916,(#132920,#132927),.PCURVE_S1.); -#132916 = LINE('',#132917,#132918); -#132917 = CARTESIAN_POINT('',(10.419594812019,2.85,0.530776333563)); -#132918 = VECTOR('',#132919,1.); -#132919 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132920 = PCURVE('',#132870,#132921); -#132921 = DEFINITIONAL_REPRESENTATION('',(#132922),#132926); -#132922 = LINE('',#132923,#132924); -#132923 = CARTESIAN_POINT('',(-2.85,0.E+000)); -#132924 = VECTOR('',#132925,1.); -#132925 = DIRECTION('',(0.E+000,-1.)); -#132926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132927 = PCURVE('',#92626,#132928); -#132928 = DEFINITIONAL_REPRESENTATION('',(#132929),#132933); -#132929 = LINE('',#132930,#132931); -#132930 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#132931 = VECTOR('',#132932,1.); -#132932 = DIRECTION('',(-1.,0.E+000)); -#132933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132934 = ORIENTED_EDGE('',*,*,#132857,.F.); -#132935 = ORIENTED_EDGE('',*,*,#132936,.F.); -#132936 = EDGE_CURVE('',#132886,#132812,#132937,.T.); -#132937 = SURFACE_CURVE('',#132938,(#132942,#132949),.PCURVE_S1.); -#132938 = LINE('',#132939,#132940); -#132939 = CARTESIAN_POINT('',(10.419594812019,2.65,0.530776333563)); -#132940 = VECTOR('',#132941,1.); -#132941 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132942 = PCURVE('',#132870,#132943); -#132943 = DEFINITIONAL_REPRESENTATION('',(#132944),#132948); -#132944 = LINE('',#132945,#132946); -#132945 = CARTESIAN_POINT('',(-2.65,0.E+000)); -#132946 = VECTOR('',#132947,1.); -#132947 = DIRECTION('',(0.E+000,-1.)); -#132948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132949 = PCURVE('',#92682,#132950); -#132950 = DEFINITIONAL_REPRESENTATION('',(#132951),#132955); -#132951 = LINE('',#132952,#132953); -#132952 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#132953 = VECTOR('',#132954,1.); -#132954 = DIRECTION('',(1.,0.E+000)); -#132955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132956 = ADVANCED_FACE('',(#132957),#132719,.T.); -#132957 = FACE_BOUND('',#132958,.T.); -#132958 = EDGE_LOOP('',(#132959,#132988,#133009,#133010)); -#132959 = ORIENTED_EDGE('',*,*,#132960,.T.); -#132960 = EDGE_CURVE('',#132961,#132963,#132965,.T.); -#132961 = VERTEX_POINT('',#132962); -#132962 = CARTESIAN_POINT('',(10.51959417205,2.85,0.530776333563)); -#132963 = VERTEX_POINT('',#132964); -#132964 = CARTESIAN_POINT('',(10.51959417205,2.65,0.530776333563)); -#132965 = SURFACE_CURVE('',#132966,(#132970,#132977),.PCURVE_S1.); -#132966 = LINE('',#132967,#132968); -#132967 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#135302 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#135303 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#135304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135305 = ORIENTED_EDGE('',*,*,#135306,.T.); +#135306 = EDGE_CURVE('',#135280,#135153,#135307,.T.); +#135307 = SURFACE_CURVE('',#135308,(#135312,#135319),.PCURVE_S1.); +#135308 = LINE('',#135309,#135310); +#135309 = CARTESIAN_POINT('',(10.419594812019,2.85,0.530776333563)); +#135310 = VECTOR('',#135311,1.); +#135311 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#135312 = PCURVE('',#135262,#135313); +#135313 = DEFINITIONAL_REPRESENTATION('',(#135314),#135318); +#135314 = LINE('',#135315,#135316); +#135315 = CARTESIAN_POINT('',(-2.85,0.E+000)); +#135316 = VECTOR('',#135317,1.); +#135317 = DIRECTION('',(0.E+000,-1.)); +#135318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135319 = PCURVE('',#95018,#135320); +#135320 = DEFINITIONAL_REPRESENTATION('',(#135321),#135325); +#135321 = LINE('',#135322,#135323); +#135322 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#135323 = VECTOR('',#135324,1.); +#135324 = DIRECTION('',(-1.,0.E+000)); +#135325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135326 = ORIENTED_EDGE('',*,*,#135249,.F.); +#135327 = ORIENTED_EDGE('',*,*,#135328,.F.); +#135328 = EDGE_CURVE('',#135278,#135204,#135329,.T.); +#135329 = SURFACE_CURVE('',#135330,(#135334,#135341),.PCURVE_S1.); +#135330 = LINE('',#135331,#135332); +#135331 = CARTESIAN_POINT('',(10.419594812019,2.65,0.530776333563)); +#135332 = VECTOR('',#135333,1.); +#135333 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#135334 = PCURVE('',#135262,#135335); +#135335 = DEFINITIONAL_REPRESENTATION('',(#135336),#135340); +#135336 = LINE('',#135337,#135338); +#135337 = CARTESIAN_POINT('',(-2.65,0.E+000)); +#135338 = VECTOR('',#135339,1.); +#135339 = DIRECTION('',(0.E+000,-1.)); +#135340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135341 = PCURVE('',#95074,#135342); +#135342 = DEFINITIONAL_REPRESENTATION('',(#135343),#135347); +#135343 = LINE('',#135344,#135345); +#135344 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#135345 = VECTOR('',#135346,1.); +#135346 = DIRECTION('',(1.,0.E+000)); +#135347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135348 = ADVANCED_FACE('',(#135349),#135111,.T.); +#135349 = FACE_BOUND('',#135350,.T.); +#135350 = EDGE_LOOP('',(#135351,#135380,#135401,#135402)); +#135351 = ORIENTED_EDGE('',*,*,#135352,.T.); +#135352 = EDGE_CURVE('',#135353,#135355,#135357,.T.); +#135353 = VERTEX_POINT('',#135354); +#135354 = CARTESIAN_POINT('',(10.51959417205,2.85,0.530776333563)); +#135355 = VERTEX_POINT('',#135356); +#135356 = CARTESIAN_POINT('',(10.51959417205,2.65,0.530776333563)); +#135357 = SURFACE_CURVE('',#135358,(#135362,#135369),.PCURVE_S1.); +#135358 = LINE('',#135359,#135360); +#135359 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#132968 = VECTOR('',#132969,1.); -#132969 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#132970 = PCURVE('',#132719,#132971); -#132971 = DEFINITIONAL_REPRESENTATION('',(#132972),#132976); -#132972 = LINE('',#132973,#132974); -#132973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#132974 = VECTOR('',#132975,1.); -#132975 = DIRECTION('',(-1.,0.E+000)); -#132976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132977 = PCURVE('',#132978,#132983); -#132978 = CYLINDRICAL_SURFACE('',#132979,0.2192697516); -#132979 = AXIS2_PLACEMENT_3D('',#132980,#132981,#132982); -#132980 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#135360 = VECTOR('',#135361,1.); +#135361 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135362 = PCURVE('',#135111,#135363); +#135363 = DEFINITIONAL_REPRESENTATION('',(#135364),#135368); +#135364 = LINE('',#135365,#135366); +#135365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135366 = VECTOR('',#135367,1.); +#135367 = DIRECTION('',(-1.,0.E+000)); +#135368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135369 = PCURVE('',#135370,#135375); +#135370 = CYLINDRICAL_SURFACE('',#135371,0.2192697516); +#135371 = AXIS2_PLACEMENT_3D('',#135372,#135373,#135374); +#135372 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#132981 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#132982 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#132983 = DEFINITIONAL_REPRESENTATION('',(#132984),#132987); -#132984 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#132985,#132986), +#135373 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135374 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135375 = DEFINITIONAL_REPRESENTATION('',(#135376),#135379); +#135376 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135377,#135378), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#132985 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#132986 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#132987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#132988 = ORIENTED_EDGE('',*,*,#132989,.T.); -#132989 = EDGE_CURVE('',#132963,#132682,#132990,.T.); -#132990 = SURFACE_CURVE('',#132991,(#132995,#133002),.PCURVE_S1.); -#132991 = LINE('',#132992,#132993); -#132992 = CARTESIAN_POINT('',(10.51959417205,2.65,0.530776333563)); -#132993 = VECTOR('',#132994,1.); -#132994 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#132995 = PCURVE('',#132719,#132996); -#132996 = DEFINITIONAL_REPRESENTATION('',(#132997),#133001); -#132997 = LINE('',#132998,#132999); -#132998 = CARTESIAN_POINT('',(2.65,0.E+000)); -#132999 = VECTOR('',#133000,1.); -#133000 = DIRECTION('',(0.E+000,-1.)); -#133001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133002 = PCURVE('',#92682,#133003); -#133003 = DEFINITIONAL_REPRESENTATION('',(#133004),#133008); -#133004 = LINE('',#133005,#133006); -#133005 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#133006 = VECTOR('',#133007,1.); -#133007 = DIRECTION('',(1.,0.E+000)); -#133008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133009 = ORIENTED_EDGE('',*,*,#132704,.F.); -#133010 = ORIENTED_EDGE('',*,*,#133011,.F.); -#133011 = EDGE_CURVE('',#132961,#132705,#133012,.T.); -#133012 = SURFACE_CURVE('',#133013,(#133017,#133024),.PCURVE_S1.); -#133013 = LINE('',#133014,#133015); -#133014 = CARTESIAN_POINT('',(10.51959417205,2.85,0.530776333563)); -#133015 = VECTOR('',#133016,1.); -#133016 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133017 = PCURVE('',#132719,#133018); -#133018 = DEFINITIONAL_REPRESENTATION('',(#133019),#133023); -#133019 = LINE('',#133020,#133021); -#133020 = CARTESIAN_POINT('',(2.85,0.E+000)); -#133021 = VECTOR('',#133022,1.); -#133022 = DIRECTION('',(0.E+000,-1.)); -#133023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133024 = PCURVE('',#92626,#133025); -#133025 = DEFINITIONAL_REPRESENTATION('',(#133026),#133030); -#133026 = LINE('',#133027,#133028); -#133027 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#133028 = VECTOR('',#133029,1.); -#133029 = DIRECTION('',(-1.,0.E+000)); -#133030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133031 = ADVANCED_FACE('',(#133032),#132978,.T.); -#133032 = FACE_BOUND('',#133033,.T.); -#133033 = EDGE_LOOP('',(#133034,#133035,#133081,#133103)); -#133034 = ORIENTED_EDGE('',*,*,#132960,.F.); -#133035 = ORIENTED_EDGE('',*,*,#133036,.F.); -#133036 = EDGE_CURVE('',#133037,#132961,#133039,.T.); -#133037 = VERTEX_POINT('',#133038); -#133038 = CARTESIAN_POINT('',(10.304819755875,2.85,0.75)); -#133039 = SURFACE_CURVE('',#133040,(#133045,#133074),.PCURVE_S1.); -#133040 = CIRCLE('',#133041,0.2192697516); -#133041 = AXIS2_PLACEMENT_3D('',#133042,#133043,#133044); -#133042 = CARTESIAN_POINT('',(10.30032442045,2.85,0.530776333563)); -#133043 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133044 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133045 = PCURVE('',#132978,#133046); -#133046 = DEFINITIONAL_REPRESENTATION('',(#133047),#133073); -#133047 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133048,#133049,#133050, - #133051,#133052,#133053,#133054,#133055,#133056,#133057,#133058, - #133059,#133060,#133061,#133062,#133063,#133064,#133065,#133066, - #133067,#133068,#133069,#133070,#133071,#133072),.UNSPECIFIED.,.F., +#135377 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#135378 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#135379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135380 = ORIENTED_EDGE('',*,*,#135381,.T.); +#135381 = EDGE_CURVE('',#135355,#135074,#135382,.T.); +#135382 = SURFACE_CURVE('',#135383,(#135387,#135394),.PCURVE_S1.); +#135383 = LINE('',#135384,#135385); +#135384 = CARTESIAN_POINT('',(10.51959417205,2.65,0.530776333563)); +#135385 = VECTOR('',#135386,1.); +#135386 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#135387 = PCURVE('',#135111,#135388); +#135388 = DEFINITIONAL_REPRESENTATION('',(#135389),#135393); +#135389 = LINE('',#135390,#135391); +#135390 = CARTESIAN_POINT('',(2.65,0.E+000)); +#135391 = VECTOR('',#135392,1.); +#135392 = DIRECTION('',(0.E+000,-1.)); +#135393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135394 = PCURVE('',#95074,#135395); +#135395 = DEFINITIONAL_REPRESENTATION('',(#135396),#135400); +#135396 = LINE('',#135397,#135398); +#135397 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#135398 = VECTOR('',#135399,1.); +#135399 = DIRECTION('',(1.,0.E+000)); +#135400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135401 = ORIENTED_EDGE('',*,*,#135096,.F.); +#135402 = ORIENTED_EDGE('',*,*,#135403,.F.); +#135403 = EDGE_CURVE('',#135353,#135097,#135404,.T.); +#135404 = SURFACE_CURVE('',#135405,(#135409,#135416),.PCURVE_S1.); +#135405 = LINE('',#135406,#135407); +#135406 = CARTESIAN_POINT('',(10.51959417205,2.85,0.530776333563)); +#135407 = VECTOR('',#135408,1.); +#135408 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#135409 = PCURVE('',#135111,#135410); +#135410 = DEFINITIONAL_REPRESENTATION('',(#135411),#135415); +#135411 = LINE('',#135412,#135413); +#135412 = CARTESIAN_POINT('',(2.85,0.E+000)); +#135413 = VECTOR('',#135414,1.); +#135414 = DIRECTION('',(0.E+000,-1.)); +#135415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135416 = PCURVE('',#95018,#135417); +#135417 = DEFINITIONAL_REPRESENTATION('',(#135418),#135422); +#135418 = LINE('',#135419,#135420); +#135419 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#135420 = VECTOR('',#135421,1.); +#135421 = DIRECTION('',(-1.,0.E+000)); +#135422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135423 = ADVANCED_FACE('',(#135424),#135370,.T.); +#135424 = FACE_BOUND('',#135425,.T.); +#135425 = EDGE_LOOP('',(#135426,#135427,#135473,#135495)); +#135426 = ORIENTED_EDGE('',*,*,#135352,.F.); +#135427 = ORIENTED_EDGE('',*,*,#135428,.F.); +#135428 = EDGE_CURVE('',#135429,#135353,#135431,.T.); +#135429 = VERTEX_POINT('',#135430); +#135430 = CARTESIAN_POINT('',(10.304819755875,2.85,0.75)); +#135431 = SURFACE_CURVE('',#135432,(#135437,#135466),.PCURVE_S1.); +#135432 = CIRCLE('',#135433,0.2192697516); +#135433 = AXIS2_PLACEMENT_3D('',#135434,#135435,#135436); +#135434 = CARTESIAN_POINT('',(10.30032442045,2.85,0.530776333563)); +#135435 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135436 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135437 = PCURVE('',#135370,#135438); +#135438 = DEFINITIONAL_REPRESENTATION('',(#135439),#135465); +#135439 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135440,#135441,#135442, + #135443,#135444,#135445,#135446,#135447,#135448,#135449,#135450, + #135451,#135452,#135453,#135454,#135455,#135456,#135457,#135458, + #135459,#135460,#135461,#135462,#135463,#135464),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -163940,84 +166942,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#133048 = CARTESIAN_POINT('',(1.591299156552,2.85)); -#133049 = CARTESIAN_POINT('',(1.614788451962,2.85)); -#133050 = CARTESIAN_POINT('',(1.661767042781,2.85)); -#133051 = CARTESIAN_POINT('',(1.73223492901,2.85)); -#133052 = CARTESIAN_POINT('',(1.802702815239,2.85)); -#133053 = CARTESIAN_POINT('',(1.873170701468,2.85)); -#133054 = CARTESIAN_POINT('',(1.943638587697,2.85)); -#133055 = CARTESIAN_POINT('',(2.014106473926,2.85)); -#133056 = CARTESIAN_POINT('',(2.084574360155,2.85)); -#133057 = CARTESIAN_POINT('',(2.155042246384,2.85)); -#133058 = CARTESIAN_POINT('',(2.225510132613,2.85)); -#133059 = CARTESIAN_POINT('',(2.295978018842,2.85)); -#133060 = CARTESIAN_POINT('',(2.366445905071,2.85)); -#133061 = CARTESIAN_POINT('',(2.4369137913,2.85)); -#133062 = CARTESIAN_POINT('',(2.507381677529,2.85)); -#133063 = CARTESIAN_POINT('',(2.577849563758,2.85)); -#133064 = CARTESIAN_POINT('',(2.648317449987,2.85)); -#133065 = CARTESIAN_POINT('',(2.718785336216,2.85)); -#133066 = CARTESIAN_POINT('',(2.789253222445,2.85)); -#133067 = CARTESIAN_POINT('',(2.859721108674,2.85)); -#133068 = CARTESIAN_POINT('',(2.930188994903,2.85)); -#133069 = CARTESIAN_POINT('',(3.000656881132,2.85)); -#133070 = CARTESIAN_POINT('',(3.071124767361,2.85)); -#133071 = CARTESIAN_POINT('',(3.11810335818,2.85)); -#133072 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#133073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133074 = PCURVE('',#92626,#133075); -#133075 = DEFINITIONAL_REPRESENTATION('',(#133076),#133080); -#133076 = CIRCLE('',#133077,0.2192697516); -#133077 = AXIS2_PLACEMENT_2D('',#133078,#133079); -#133078 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#133079 = DIRECTION('',(0.E+000,-1.)); -#133080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133081 = ORIENTED_EDGE('',*,*,#133082,.F.); -#133082 = EDGE_CURVE('',#133083,#133037,#133085,.T.); -#133083 = VERTEX_POINT('',#133084); -#133084 = CARTESIAN_POINT('',(10.304819755875,2.65,0.75)); -#133085 = SURFACE_CURVE('',#133086,(#133090,#133096),.PCURVE_S1.); -#133086 = LINE('',#133087,#133088); -#133087 = CARTESIAN_POINT('',(10.304819755875,2.85,0.75)); -#133088 = VECTOR('',#133089,1.); -#133089 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133090 = PCURVE('',#132978,#133091); -#133091 = DEFINITIONAL_REPRESENTATION('',(#133092),#133095); -#133092 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133093,#133094), +#135440 = CARTESIAN_POINT('',(1.591299156552,2.85)); +#135441 = CARTESIAN_POINT('',(1.614788451962,2.85)); +#135442 = CARTESIAN_POINT('',(1.661767042781,2.85)); +#135443 = CARTESIAN_POINT('',(1.73223492901,2.85)); +#135444 = CARTESIAN_POINT('',(1.802702815239,2.85)); +#135445 = CARTESIAN_POINT('',(1.873170701468,2.85)); +#135446 = CARTESIAN_POINT('',(1.943638587697,2.85)); +#135447 = CARTESIAN_POINT('',(2.014106473926,2.85)); +#135448 = CARTESIAN_POINT('',(2.084574360155,2.85)); +#135449 = CARTESIAN_POINT('',(2.155042246384,2.85)); +#135450 = CARTESIAN_POINT('',(2.225510132613,2.85)); +#135451 = CARTESIAN_POINT('',(2.295978018842,2.85)); +#135452 = CARTESIAN_POINT('',(2.366445905071,2.85)); +#135453 = CARTESIAN_POINT('',(2.4369137913,2.85)); +#135454 = CARTESIAN_POINT('',(2.507381677529,2.85)); +#135455 = CARTESIAN_POINT('',(2.577849563758,2.85)); +#135456 = CARTESIAN_POINT('',(2.648317449987,2.85)); +#135457 = CARTESIAN_POINT('',(2.718785336216,2.85)); +#135458 = CARTESIAN_POINT('',(2.789253222445,2.85)); +#135459 = CARTESIAN_POINT('',(2.859721108674,2.85)); +#135460 = CARTESIAN_POINT('',(2.930188994903,2.85)); +#135461 = CARTESIAN_POINT('',(3.000656881132,2.85)); +#135462 = CARTESIAN_POINT('',(3.071124767361,2.85)); +#135463 = CARTESIAN_POINT('',(3.11810335818,2.85)); +#135464 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#135465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135466 = PCURVE('',#95018,#135467); +#135467 = DEFINITIONAL_REPRESENTATION('',(#135468),#135472); +#135468 = CIRCLE('',#135469,0.2192697516); +#135469 = AXIS2_PLACEMENT_2D('',#135470,#135471); +#135470 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#135471 = DIRECTION('',(0.E+000,-1.)); +#135472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135473 = ORIENTED_EDGE('',*,*,#135474,.F.); +#135474 = EDGE_CURVE('',#135475,#135429,#135477,.T.); +#135475 = VERTEX_POINT('',#135476); +#135476 = CARTESIAN_POINT('',(10.304819755875,2.65,0.75)); +#135477 = SURFACE_CURVE('',#135478,(#135482,#135488),.PCURVE_S1.); +#135478 = LINE('',#135479,#135480); +#135479 = CARTESIAN_POINT('',(10.304819755875,2.85,0.75)); +#135480 = VECTOR('',#135481,1.); +#135481 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135482 = PCURVE('',#135370,#135483); +#135483 = DEFINITIONAL_REPRESENTATION('',(#135484),#135487); +#135484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135485,#135486), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#133093 = CARTESIAN_POINT('',(1.591299156552,2.65)); -#133094 = CARTESIAN_POINT('',(1.591299156552,2.85)); -#133095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133096 = PCURVE('',#92708,#133097); -#133097 = DEFINITIONAL_REPRESENTATION('',(#133098),#133102); -#133098 = LINE('',#133099,#133100); -#133099 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#133100 = VECTOR('',#133101,1.); -#133101 = DIRECTION('',(4.440892098501E-016,1.)); -#133102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133103 = ORIENTED_EDGE('',*,*,#133104,.T.); -#133104 = EDGE_CURVE('',#133083,#132963,#133105,.T.); -#133105 = SURFACE_CURVE('',#133106,(#133111,#133140),.PCURVE_S1.); -#133106 = CIRCLE('',#133107,0.2192697516); -#133107 = AXIS2_PLACEMENT_3D('',#133108,#133109,#133110); -#133108 = CARTESIAN_POINT('',(10.30032442045,2.65,0.530776333563)); -#133109 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133110 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133111 = PCURVE('',#132978,#133112); -#133112 = DEFINITIONAL_REPRESENTATION('',(#133113),#133139); -#133113 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133114,#133115,#133116, - #133117,#133118,#133119,#133120,#133121,#133122,#133123,#133124, - #133125,#133126,#133127,#133128,#133129,#133130,#133131,#133132, - #133133,#133134,#133135,#133136,#133137,#133138),.UNSPECIFIED.,.F., +#135485 = CARTESIAN_POINT('',(1.591299156552,2.65)); +#135486 = CARTESIAN_POINT('',(1.591299156552,2.85)); +#135487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135488 = PCURVE('',#95100,#135489); +#135489 = DEFINITIONAL_REPRESENTATION('',(#135490),#135494); +#135490 = LINE('',#135491,#135492); +#135491 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#135492 = VECTOR('',#135493,1.); +#135493 = DIRECTION('',(4.440892098501E-016,1.)); +#135494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135495 = ORIENTED_EDGE('',*,*,#135496,.T.); +#135496 = EDGE_CURVE('',#135475,#135355,#135497,.T.); +#135497 = SURFACE_CURVE('',#135498,(#135503,#135532),.PCURVE_S1.); +#135498 = CIRCLE('',#135499,0.2192697516); +#135499 = AXIS2_PLACEMENT_3D('',#135500,#135501,#135502); +#135500 = CARTESIAN_POINT('',(10.30032442045,2.65,0.530776333563)); +#135501 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135502 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135503 = PCURVE('',#135370,#135504); +#135504 = DEFINITIONAL_REPRESENTATION('',(#135505),#135531); +#135505 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135506,#135507,#135508, + #135509,#135510,#135511,#135512,#135513,#135514,#135515,#135516, + #135517,#135518,#135519,#135520,#135521,#135522,#135523,#135524, + #135525,#135526,#135527,#135528,#135529,#135530),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -164025,728 +167027,728 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#133114 = CARTESIAN_POINT('',(1.591299156552,2.65)); -#133115 = CARTESIAN_POINT('',(1.614788451962,2.65)); -#133116 = CARTESIAN_POINT('',(1.661767042781,2.65)); -#133117 = CARTESIAN_POINT('',(1.73223492901,2.65)); -#133118 = CARTESIAN_POINT('',(1.802702815239,2.65)); -#133119 = CARTESIAN_POINT('',(1.873170701468,2.65)); -#133120 = CARTESIAN_POINT('',(1.943638587697,2.65)); -#133121 = CARTESIAN_POINT('',(2.014106473926,2.65)); -#133122 = CARTESIAN_POINT('',(2.084574360155,2.65)); -#133123 = CARTESIAN_POINT('',(2.155042246384,2.65)); -#133124 = CARTESIAN_POINT('',(2.225510132613,2.65)); -#133125 = CARTESIAN_POINT('',(2.295978018842,2.65)); -#133126 = CARTESIAN_POINT('',(2.366445905071,2.65)); -#133127 = CARTESIAN_POINT('',(2.4369137913,2.65)); -#133128 = CARTESIAN_POINT('',(2.507381677529,2.65)); -#133129 = CARTESIAN_POINT('',(2.577849563758,2.65)); -#133130 = CARTESIAN_POINT('',(2.648317449987,2.65)); -#133131 = CARTESIAN_POINT('',(2.718785336216,2.65)); -#133132 = CARTESIAN_POINT('',(2.789253222445,2.65)); -#133133 = CARTESIAN_POINT('',(2.859721108674,2.65)); -#133134 = CARTESIAN_POINT('',(2.930188994903,2.65)); -#133135 = CARTESIAN_POINT('',(3.000656881132,2.65)); -#133136 = CARTESIAN_POINT('',(3.071124767361,2.65)); -#133137 = CARTESIAN_POINT('',(3.11810335818,2.65)); -#133138 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#133139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133140 = PCURVE('',#92682,#133141); -#133141 = DEFINITIONAL_REPRESENTATION('',(#133142),#133150); -#133142 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133143,#133144,#133145, - #133146,#133147,#133148,#133149),.UNSPECIFIED.,.T.,.F.) +#135506 = CARTESIAN_POINT('',(1.591299156552,2.65)); +#135507 = CARTESIAN_POINT('',(1.614788451962,2.65)); +#135508 = CARTESIAN_POINT('',(1.661767042781,2.65)); +#135509 = CARTESIAN_POINT('',(1.73223492901,2.65)); +#135510 = CARTESIAN_POINT('',(1.802702815239,2.65)); +#135511 = CARTESIAN_POINT('',(1.873170701468,2.65)); +#135512 = CARTESIAN_POINT('',(1.943638587697,2.65)); +#135513 = CARTESIAN_POINT('',(2.014106473926,2.65)); +#135514 = CARTESIAN_POINT('',(2.084574360155,2.65)); +#135515 = CARTESIAN_POINT('',(2.155042246384,2.65)); +#135516 = CARTESIAN_POINT('',(2.225510132613,2.65)); +#135517 = CARTESIAN_POINT('',(2.295978018842,2.65)); +#135518 = CARTESIAN_POINT('',(2.366445905071,2.65)); +#135519 = CARTESIAN_POINT('',(2.4369137913,2.65)); +#135520 = CARTESIAN_POINT('',(2.507381677529,2.65)); +#135521 = CARTESIAN_POINT('',(2.577849563758,2.65)); +#135522 = CARTESIAN_POINT('',(2.648317449987,2.65)); +#135523 = CARTESIAN_POINT('',(2.718785336216,2.65)); +#135524 = CARTESIAN_POINT('',(2.789253222445,2.65)); +#135525 = CARTESIAN_POINT('',(2.859721108674,2.65)); +#135526 = CARTESIAN_POINT('',(2.930188994903,2.65)); +#135527 = CARTESIAN_POINT('',(3.000656881132,2.65)); +#135528 = CARTESIAN_POINT('',(3.071124767361,2.65)); +#135529 = CARTESIAN_POINT('',(3.11810335818,2.65)); +#135530 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#135531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135532 = PCURVE('',#95074,#135533); +#135533 = DEFINITIONAL_REPRESENTATION('',(#135534),#135542); +#135534 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135535,#135536,#135537, + #135538,#135539,#135540,#135541),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#133143 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#133144 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#133145 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#133146 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#133147 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#133148 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#133149 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#133150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133151 = ADVANCED_FACE('',(#133152),#132903,.F.); -#133152 = FACE_BOUND('',#133153,.F.); -#133153 = EDGE_LOOP('',(#133154,#133155,#133178,#133200)); -#133154 = ORIENTED_EDGE('',*,*,#132885,.T.); -#133155 = ORIENTED_EDGE('',*,*,#133156,.F.); -#133156 = EDGE_CURVE('',#133157,#132888,#133159,.T.); -#133157 = VERTEX_POINT('',#133158); -#133158 = CARTESIAN_POINT('',(10.303662633502,2.85,0.65)); -#133159 = SURFACE_CURVE('',#133160,(#133165,#133171),.PCURVE_S1.); -#133160 = CIRCLE('',#133161,0.119270391569); -#133161 = AXIS2_PLACEMENT_3D('',#133162,#133163,#133164); -#133162 = CARTESIAN_POINT('',(10.30032442045,2.85,0.530776333563)); -#133163 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133164 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133165 = PCURVE('',#132903,#133166); -#133166 = DEFINITIONAL_REPRESENTATION('',(#133167),#133170); -#133167 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133168,#133169), +#135535 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#135536 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#135537 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#135538 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#135539 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#135540 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#135541 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#135542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135543 = ADVANCED_FACE('',(#135544),#135295,.F.); +#135544 = FACE_BOUND('',#135545,.F.); +#135545 = EDGE_LOOP('',(#135546,#135547,#135570,#135592)); +#135546 = ORIENTED_EDGE('',*,*,#135277,.T.); +#135547 = ORIENTED_EDGE('',*,*,#135548,.F.); +#135548 = EDGE_CURVE('',#135549,#135280,#135551,.T.); +#135549 = VERTEX_POINT('',#135550); +#135550 = CARTESIAN_POINT('',(10.303662633502,2.85,0.65)); +#135551 = SURFACE_CURVE('',#135552,(#135557,#135563),.PCURVE_S1.); +#135552 = CIRCLE('',#135553,0.119270391569); +#135553 = AXIS2_PLACEMENT_3D('',#135554,#135555,#135556); +#135554 = CARTESIAN_POINT('',(10.30032442045,2.85,0.530776333563)); +#135555 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135556 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135557 = PCURVE('',#135295,#135558); +#135558 = DEFINITIONAL_REPRESENTATION('',(#135559),#135562); +#135559 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135560,#135561), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#133168 = CARTESIAN_POINT('',(1.598788597134,2.85)); -#133169 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#133170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133171 = PCURVE('',#92626,#133172); -#133172 = DEFINITIONAL_REPRESENTATION('',(#133173),#133177); -#133173 = CIRCLE('',#133174,0.119270391569); -#133174 = AXIS2_PLACEMENT_2D('',#133175,#133176); -#133175 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#133176 = DIRECTION('',(0.E+000,-1.)); -#133177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133178 = ORIENTED_EDGE('',*,*,#133179,.T.); -#133179 = EDGE_CURVE('',#133157,#133180,#133182,.T.); -#133180 = VERTEX_POINT('',#133181); -#133181 = CARTESIAN_POINT('',(10.303662633502,2.65,0.65)); -#133182 = SURFACE_CURVE('',#133183,(#133187,#133193),.PCURVE_S1.); -#133183 = LINE('',#133184,#133185); -#133184 = CARTESIAN_POINT('',(10.303662633502,2.85,0.65)); -#133185 = VECTOR('',#133186,1.); -#133186 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133187 = PCURVE('',#132903,#133188); -#133188 = DEFINITIONAL_REPRESENTATION('',(#133189),#133192); -#133189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133190,#133191), +#135560 = CARTESIAN_POINT('',(1.598788597134,2.85)); +#135561 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#135562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135563 = PCURVE('',#95018,#135564); +#135564 = DEFINITIONAL_REPRESENTATION('',(#135565),#135569); +#135565 = CIRCLE('',#135566,0.119270391569); +#135566 = AXIS2_PLACEMENT_2D('',#135567,#135568); +#135567 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#135568 = DIRECTION('',(0.E+000,-1.)); +#135569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135570 = ORIENTED_EDGE('',*,*,#135571,.T.); +#135571 = EDGE_CURVE('',#135549,#135572,#135574,.T.); +#135572 = VERTEX_POINT('',#135573); +#135573 = CARTESIAN_POINT('',(10.303662633502,2.65,0.65)); +#135574 = SURFACE_CURVE('',#135575,(#135579,#135585),.PCURVE_S1.); +#135575 = LINE('',#135576,#135577); +#135576 = CARTESIAN_POINT('',(10.303662633502,2.85,0.65)); +#135577 = VECTOR('',#135578,1.); +#135578 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135579 = PCURVE('',#135295,#135580); +#135580 = DEFINITIONAL_REPRESENTATION('',(#135581),#135584); +#135581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135582,#135583), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#133190 = CARTESIAN_POINT('',(1.598788597134,2.85)); -#133191 = CARTESIAN_POINT('',(1.598788597134,2.65)); -#133192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133193 = PCURVE('',#92654,#133194); -#133194 = DEFINITIONAL_REPRESENTATION('',(#133195),#133199); -#133195 = LINE('',#133196,#133197); -#133196 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#133197 = VECTOR('',#133198,1.); -#133198 = DIRECTION('',(4.440892098501E-016,-1.)); -#133199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133200 = ORIENTED_EDGE('',*,*,#133201,.T.); -#133201 = EDGE_CURVE('',#133180,#132886,#133202,.T.); -#133202 = SURFACE_CURVE('',#133203,(#133208,#133214),.PCURVE_S1.); -#133203 = CIRCLE('',#133204,0.119270391569); -#133204 = AXIS2_PLACEMENT_3D('',#133205,#133206,#133207); -#133205 = CARTESIAN_POINT('',(10.30032442045,2.65,0.530776333563)); -#133206 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133207 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133208 = PCURVE('',#132903,#133209); -#133209 = DEFINITIONAL_REPRESENTATION('',(#133210),#133213); -#133210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133211,#133212), +#135582 = CARTESIAN_POINT('',(1.598788597134,2.85)); +#135583 = CARTESIAN_POINT('',(1.598788597134,2.65)); +#135584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135585 = PCURVE('',#95046,#135586); +#135586 = DEFINITIONAL_REPRESENTATION('',(#135587),#135591); +#135587 = LINE('',#135588,#135589); +#135588 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#135589 = VECTOR('',#135590,1.); +#135590 = DIRECTION('',(4.440892098501E-016,-1.)); +#135591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135592 = ORIENTED_EDGE('',*,*,#135593,.T.); +#135593 = EDGE_CURVE('',#135572,#135278,#135594,.T.); +#135594 = SURFACE_CURVE('',#135595,(#135600,#135606),.PCURVE_S1.); +#135595 = CIRCLE('',#135596,0.119270391569); +#135596 = AXIS2_PLACEMENT_3D('',#135597,#135598,#135599); +#135597 = CARTESIAN_POINT('',(10.30032442045,2.65,0.530776333563)); +#135598 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135599 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#135600 = PCURVE('',#135295,#135601); +#135601 = DEFINITIONAL_REPRESENTATION('',(#135602),#135605); +#135602 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135603,#135604), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#133211 = CARTESIAN_POINT('',(1.598788597134,2.65)); -#133212 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#133213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135603 = CARTESIAN_POINT('',(1.598788597134,2.65)); +#135604 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#135605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133214 = PCURVE('',#92682,#133215); -#133215 = DEFINITIONAL_REPRESENTATION('',(#133216),#133224); -#133216 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133217,#133218,#133219, - #133220,#133221,#133222,#133223),.UNSPECIFIED.,.T.,.F.) +#135606 = PCURVE('',#95074,#135607); +#135607 = DEFINITIONAL_REPRESENTATION('',(#135608),#135616); +#135608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135609,#135610,#135611, + #135612,#135613,#135614,#135615),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#133217 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#133218 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#133219 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#133220 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#133221 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#133222 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#133223 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#133224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133225 = ADVANCED_FACE('',(#133226),#92654,.T.); -#133226 = FACE_BOUND('',#133227,.T.); -#133227 = EDGE_LOOP('',(#133228,#133249,#133250,#133271)); -#133228 = ORIENTED_EDGE('',*,*,#133229,.F.); -#133229 = EDGE_CURVE('',#133157,#92611,#133230,.T.); -#133230 = SURFACE_CURVE('',#133231,(#133235,#133242),.PCURVE_S1.); -#133231 = LINE('',#133232,#133233); -#133232 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); -#133233 = VECTOR('',#133234,1.); -#133234 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#133235 = PCURVE('',#92654,#133236); -#133236 = DEFINITIONAL_REPRESENTATION('',(#133237),#133241); -#133237 = LINE('',#133238,#133239); -#133238 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133239 = VECTOR('',#133240,1.); -#133240 = DIRECTION('',(1.,-3.00059940766E-063)); -#133241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133242 = PCURVE('',#92626,#133243); -#133243 = DEFINITIONAL_REPRESENTATION('',(#133244),#133248); -#133244 = LINE('',#133245,#133246); -#133245 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133246 = VECTOR('',#133247,1.); -#133247 = DIRECTION('',(3.563627120235E-016,-1.)); -#133248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133249 = ORIENTED_EDGE('',*,*,#133179,.T.); -#133250 = ORIENTED_EDGE('',*,*,#133251,.T.); -#133251 = EDGE_CURVE('',#133180,#92639,#133252,.T.); -#133252 = SURFACE_CURVE('',#133253,(#133257,#133264),.PCURVE_S1.); -#133253 = LINE('',#133254,#133255); -#133254 = CARTESIAN_POINT('',(10.527847992439,2.65,0.65)); -#133255 = VECTOR('',#133256,1.); -#133256 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#133257 = PCURVE('',#92654,#133258); -#133258 = DEFINITIONAL_REPRESENTATION('',(#133259),#133263); -#133259 = LINE('',#133260,#133261); -#133260 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#133261 = VECTOR('',#133262,1.); -#133262 = DIRECTION('',(1.,-3.00059940766E-063)); -#133263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133264 = PCURVE('',#92682,#133265); -#133265 = DEFINITIONAL_REPRESENTATION('',(#133266),#133270); -#133266 = LINE('',#133267,#133268); -#133267 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133268 = VECTOR('',#133269,1.); -#133269 = DIRECTION('',(-3.563627120235E-016,-1.)); -#133270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133271 = ORIENTED_EDGE('',*,*,#92638,.F.); -#133272 = ADVANCED_FACE('',(#133273),#92682,.T.); -#133273 = FACE_BOUND('',#133274,.T.); -#133274 = EDGE_LOOP('',(#133275,#133276,#133277,#133278,#133279,#133280, - #133301,#133302,#133303,#133304,#133305,#133326)); -#133275 = ORIENTED_EDGE('',*,*,#133251,.F.); -#133276 = ORIENTED_EDGE('',*,*,#133201,.T.); -#133277 = ORIENTED_EDGE('',*,*,#132936,.T.); -#133278 = ORIENTED_EDGE('',*,*,#132811,.T.); -#133279 = ORIENTED_EDGE('',*,*,#132607,.T.); -#133280 = ORIENTED_EDGE('',*,*,#133281,.F.); -#133281 = EDGE_CURVE('',#132471,#132578,#133282,.T.); -#133282 = SURFACE_CURVE('',#133283,(#133287,#133294),.PCURVE_S1.); -#133283 = LINE('',#133284,#133285); -#133284 = CARTESIAN_POINT('',(11.,2.65,1.159810404338E-002)); -#133285 = VECTOR('',#133286,1.); -#133286 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#133287 = PCURVE('',#92682,#133288); -#133288 = DEFINITIONAL_REPRESENTATION('',(#133289),#133293); -#133289 = LINE('',#133290,#133291); -#133290 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#133291 = VECTOR('',#133292,1.); -#133292 = DIRECTION('',(1.,-2.101748079665E-016)); -#133293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133294 = PCURVE('',#132491,#133295); -#133295 = DEFINITIONAL_REPRESENTATION('',(#133296),#133300); -#133296 = LINE('',#133297,#133298); -#133297 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#133298 = VECTOR('',#133299,1.); -#133299 = DIRECTION('',(-1.194699204908E-017,-1.)); -#133300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133301 = ORIENTED_EDGE('',*,*,#132553,.F.); -#133302 = ORIENTED_EDGE('',*,*,#132681,.F.); -#133303 = ORIENTED_EDGE('',*,*,#132989,.F.); -#133304 = ORIENTED_EDGE('',*,*,#133104,.F.); -#133305 = ORIENTED_EDGE('',*,*,#133306,.T.); -#133306 = EDGE_CURVE('',#133083,#92667,#133307,.T.); -#133307 = SURFACE_CURVE('',#133308,(#133312,#133319),.PCURVE_S1.); -#133308 = LINE('',#133309,#133310); -#133309 = CARTESIAN_POINT('',(10.527847992439,2.65,0.75)); -#133310 = VECTOR('',#133311,1.); -#133311 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#133312 = PCURVE('',#92682,#133313); -#133313 = DEFINITIONAL_REPRESENTATION('',(#133314),#133318); -#133314 = LINE('',#133315,#133316); -#133315 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#133316 = VECTOR('',#133317,1.); -#133317 = DIRECTION('',(-3.563627120235E-016,-1.)); -#133318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133319 = PCURVE('',#92708,#133320); -#133320 = DEFINITIONAL_REPRESENTATION('',(#133321),#133325); -#133321 = LINE('',#133322,#133323); -#133322 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#133323 = VECTOR('',#133324,1.); -#133324 = DIRECTION('',(-1.,-3.00059940766E-063)); -#133325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135609 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#135610 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#135611 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#135612 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#135613 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#135614 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#135615 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#135616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135617 = ADVANCED_FACE('',(#135618),#95046,.T.); +#135618 = FACE_BOUND('',#135619,.T.); +#135619 = EDGE_LOOP('',(#135620,#135641,#135642,#135663)); +#135620 = ORIENTED_EDGE('',*,*,#135621,.F.); +#135621 = EDGE_CURVE('',#135549,#95003,#135622,.T.); +#135622 = SURFACE_CURVE('',#135623,(#135627,#135634),.PCURVE_S1.); +#135623 = LINE('',#135624,#135625); +#135624 = CARTESIAN_POINT('',(10.527847992439,2.85,0.65)); +#135625 = VECTOR('',#135626,1.); +#135626 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#135627 = PCURVE('',#95046,#135628); +#135628 = DEFINITIONAL_REPRESENTATION('',(#135629),#135633); +#135629 = LINE('',#135630,#135631); +#135630 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135631 = VECTOR('',#135632,1.); +#135632 = DIRECTION('',(1.,-3.00059940766E-063)); +#135633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135634 = PCURVE('',#95018,#135635); +#135635 = DEFINITIONAL_REPRESENTATION('',(#135636),#135640); +#135636 = LINE('',#135637,#135638); +#135637 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135638 = VECTOR('',#135639,1.); +#135639 = DIRECTION('',(3.563627120235E-016,-1.)); +#135640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135641 = ORIENTED_EDGE('',*,*,#135571,.T.); +#135642 = ORIENTED_EDGE('',*,*,#135643,.T.); +#135643 = EDGE_CURVE('',#135572,#95031,#135644,.T.); +#135644 = SURFACE_CURVE('',#135645,(#135649,#135656),.PCURVE_S1.); +#135645 = LINE('',#135646,#135647); +#135646 = CARTESIAN_POINT('',(10.527847992439,2.65,0.65)); +#135647 = VECTOR('',#135648,1.); +#135648 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#135649 = PCURVE('',#95046,#135650); +#135650 = DEFINITIONAL_REPRESENTATION('',(#135651),#135655); +#135651 = LINE('',#135652,#135653); +#135652 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#135653 = VECTOR('',#135654,1.); +#135654 = DIRECTION('',(1.,-3.00059940766E-063)); +#135655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135656 = PCURVE('',#95074,#135657); +#135657 = DEFINITIONAL_REPRESENTATION('',(#135658),#135662); +#135658 = LINE('',#135659,#135660); +#135659 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135660 = VECTOR('',#135661,1.); +#135661 = DIRECTION('',(-3.563627120235E-016,-1.)); +#135662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135663 = ORIENTED_EDGE('',*,*,#95030,.F.); +#135664 = ADVANCED_FACE('',(#135665),#95074,.T.); +#135665 = FACE_BOUND('',#135666,.T.); +#135666 = EDGE_LOOP('',(#135667,#135668,#135669,#135670,#135671,#135672, + #135693,#135694,#135695,#135696,#135697,#135718)); +#135667 = ORIENTED_EDGE('',*,*,#135643,.F.); +#135668 = ORIENTED_EDGE('',*,*,#135593,.T.); +#135669 = ORIENTED_EDGE('',*,*,#135328,.T.); +#135670 = ORIENTED_EDGE('',*,*,#135203,.T.); +#135671 = ORIENTED_EDGE('',*,*,#134999,.T.); +#135672 = ORIENTED_EDGE('',*,*,#135673,.F.); +#135673 = EDGE_CURVE('',#134863,#134970,#135674,.T.); +#135674 = SURFACE_CURVE('',#135675,(#135679,#135686),.PCURVE_S1.); +#135675 = LINE('',#135676,#135677); +#135676 = CARTESIAN_POINT('',(11.,2.65,1.159810404338E-002)); +#135677 = VECTOR('',#135678,1.); +#135678 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#135679 = PCURVE('',#95074,#135680); +#135680 = DEFINITIONAL_REPRESENTATION('',(#135681),#135685); +#135681 = LINE('',#135682,#135683); +#135682 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#135683 = VECTOR('',#135684,1.); +#135684 = DIRECTION('',(1.,-2.101748079665E-016)); +#135685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135686 = PCURVE('',#134883,#135687); +#135687 = DEFINITIONAL_REPRESENTATION('',(#135688),#135692); +#135688 = LINE('',#135689,#135690); +#135689 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#135690 = VECTOR('',#135691,1.); +#135691 = DIRECTION('',(-1.194699204908E-017,-1.)); +#135692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135693 = ORIENTED_EDGE('',*,*,#134945,.F.); +#135694 = ORIENTED_EDGE('',*,*,#135073,.F.); +#135695 = ORIENTED_EDGE('',*,*,#135381,.F.); +#135696 = ORIENTED_EDGE('',*,*,#135496,.F.); +#135697 = ORIENTED_EDGE('',*,*,#135698,.T.); +#135698 = EDGE_CURVE('',#135475,#95059,#135699,.T.); +#135699 = SURFACE_CURVE('',#135700,(#135704,#135711),.PCURVE_S1.); +#135700 = LINE('',#135701,#135702); +#135701 = CARTESIAN_POINT('',(10.527847992439,2.65,0.75)); +#135702 = VECTOR('',#135703,1.); +#135703 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#135704 = PCURVE('',#95074,#135705); +#135705 = DEFINITIONAL_REPRESENTATION('',(#135706),#135710); +#135706 = LINE('',#135707,#135708); +#135707 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#135708 = VECTOR('',#135709,1.); +#135709 = DIRECTION('',(-3.563627120235E-016,-1.)); +#135710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135711 = PCURVE('',#95100,#135712); +#135712 = DEFINITIONAL_REPRESENTATION('',(#135713),#135717); +#135713 = LINE('',#135714,#135715); +#135714 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#135715 = VECTOR('',#135716,1.); +#135716 = DIRECTION('',(-1.,-3.00059940766E-063)); +#135717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135718 = ORIENTED_EDGE('',*,*,#95058,.F.); +#135719 = ADVANCED_FACE('',(#135720),#95100,.T.); +#135720 = FACE_BOUND('',#135721,.T.); +#135721 = EDGE_LOOP('',(#135722,#135723,#135724,#135745)); +#135722 = ORIENTED_EDGE('',*,*,#135698,.F.); +#135723 = ORIENTED_EDGE('',*,*,#135474,.T.); +#135724 = ORIENTED_EDGE('',*,*,#135725,.T.); +#135725 = EDGE_CURVE('',#135429,#95001,#135726,.T.); +#135726 = SURFACE_CURVE('',#135727,(#135731,#135738),.PCURVE_S1.); +#135727 = LINE('',#135728,#135729); +#135728 = CARTESIAN_POINT('',(10.527847992439,2.85,0.75)); +#135729 = VECTOR('',#135730,1.); +#135730 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#135731 = PCURVE('',#95100,#135732); +#135732 = DEFINITIONAL_REPRESENTATION('',(#135733),#135737); +#135733 = LINE('',#135734,#135735); +#135734 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135735 = VECTOR('',#135736,1.); +#135736 = DIRECTION('',(-1.,-3.00059940766E-063)); +#135737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133326 = ORIENTED_EDGE('',*,*,#92666,.F.); -#133327 = ADVANCED_FACE('',(#133328),#92708,.T.); -#133328 = FACE_BOUND('',#133329,.T.); -#133329 = EDGE_LOOP('',(#133330,#133331,#133332,#133353)); -#133330 = ORIENTED_EDGE('',*,*,#133306,.F.); -#133331 = ORIENTED_EDGE('',*,*,#133082,.T.); -#133332 = ORIENTED_EDGE('',*,*,#133333,.T.); -#133333 = EDGE_CURVE('',#133037,#92609,#133334,.T.); -#133334 = SURFACE_CURVE('',#133335,(#133339,#133346),.PCURVE_S1.); -#133335 = LINE('',#133336,#133337); -#133336 = CARTESIAN_POINT('',(10.527847992439,2.85,0.75)); -#133337 = VECTOR('',#133338,1.); -#133338 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#133339 = PCURVE('',#92708,#133340); -#133340 = DEFINITIONAL_REPRESENTATION('',(#133341),#133345); -#133341 = LINE('',#133342,#133343); -#133342 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133343 = VECTOR('',#133344,1.); -#133344 = DIRECTION('',(-1.,-3.00059940766E-063)); -#133345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133346 = PCURVE('',#92626,#133347); -#133347 = DEFINITIONAL_REPRESENTATION('',(#133348),#133352); -#133348 = LINE('',#133349,#133350); -#133349 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#133350 = VECTOR('',#133351,1.); -#133351 = DIRECTION('',(3.563627120235E-016,-1.)); -#133352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133353 = ORIENTED_EDGE('',*,*,#92694,.F.); -#133354 = ADVANCED_FACE('',(#133355),#92626,.T.); -#133355 = FACE_BOUND('',#133356,.T.); -#133356 = EDGE_LOOP('',(#133357,#133358,#133359,#133360,#133361,#133362, - #133383,#133384,#133385,#133386,#133387,#133388)); -#133357 = ORIENTED_EDGE('',*,*,#133333,.F.); -#133358 = ORIENTED_EDGE('',*,*,#133036,.T.); -#133359 = ORIENTED_EDGE('',*,*,#133011,.T.); -#133360 = ORIENTED_EDGE('',*,*,#132731,.T.); -#133361 = ORIENTED_EDGE('',*,*,#132503,.T.); -#133362 = ORIENTED_EDGE('',*,*,#133363,.F.); -#133363 = EDGE_CURVE('',#132580,#132469,#133364,.T.); -#133364 = SURFACE_CURVE('',#133365,(#133369,#133376),.PCURVE_S1.); -#133365 = LINE('',#133366,#133367); -#133366 = CARTESIAN_POINT('',(11.,2.85,1.159810404338E-002)); -#133367 = VECTOR('',#133368,1.); -#133368 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#133369 = PCURVE('',#92626,#133370); -#133370 = DEFINITIONAL_REPRESENTATION('',(#133371),#133375); -#133371 = LINE('',#133372,#133373); -#133372 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#133373 = VECTOR('',#133374,1.); -#133374 = DIRECTION('',(1.,2.101748079665E-016)); -#133375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133376 = PCURVE('',#132491,#133377); -#133377 = DEFINITIONAL_REPRESENTATION('',(#133378),#133382); -#133378 = LINE('',#133379,#133380); -#133379 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#133380 = VECTOR('',#133381,1.); -#133381 = DIRECTION('',(1.194699204908E-017,1.)); -#133382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133383 = ORIENTED_EDGE('',*,*,#132657,.F.); -#133384 = ORIENTED_EDGE('',*,*,#132760,.F.); -#133385 = ORIENTED_EDGE('',*,*,#132914,.F.); -#133386 = ORIENTED_EDGE('',*,*,#133156,.F.); -#133387 = ORIENTED_EDGE('',*,*,#133229,.T.); -#133388 = ORIENTED_EDGE('',*,*,#92608,.F.); -#133389 = ADVANCED_FACE('',(#133390),#132491,.T.); -#133390 = FACE_BOUND('',#133391,.T.); -#133391 = EDGE_LOOP('',(#133392,#133393,#133394,#133395)); -#133392 = ORIENTED_EDGE('',*,*,#133281,.T.); -#133393 = ORIENTED_EDGE('',*,*,#132577,.T.); -#133394 = ORIENTED_EDGE('',*,*,#133363,.T.); -#133395 = ORIENTED_EDGE('',*,*,#132468,.T.); -#133396 = ADVANCED_FACE('',(#133397),#133411,.F.); -#133397 = FACE_BOUND('',#133398,.T.); -#133398 = EDGE_LOOP('',(#133399,#133434,#133457,#133484)); -#133399 = ORIENTED_EDGE('',*,*,#133400,.F.); -#133400 = EDGE_CURVE('',#133401,#133403,#133405,.T.); -#133401 = VERTEX_POINT('',#133402); -#133402 = CARTESIAN_POINT('',(11.,2.35,-0.208196358798)); -#133403 = VERTEX_POINT('',#133404); -#133404 = CARTESIAN_POINT('',(11.,2.15,-0.208196358798)); -#133405 = SURFACE_CURVE('',#133406,(#133410,#133422),.PCURVE_S1.); -#133406 = LINE('',#133407,#133408); -#133407 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#133408 = VECTOR('',#133409,1.); -#133409 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133410 = PCURVE('',#133411,#133416); -#133411 = PLANE('',#133412); -#133412 = AXIS2_PLACEMENT_3D('',#133413,#133414,#133415); -#133413 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#135738 = PCURVE('',#95018,#135739); +#135739 = DEFINITIONAL_REPRESENTATION('',(#135740),#135744); +#135740 = LINE('',#135741,#135742); +#135741 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#135742 = VECTOR('',#135743,1.); +#135743 = DIRECTION('',(3.563627120235E-016,-1.)); +#135744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135745 = ORIENTED_EDGE('',*,*,#95086,.F.); +#135746 = ADVANCED_FACE('',(#135747),#95018,.T.); +#135747 = FACE_BOUND('',#135748,.T.); +#135748 = EDGE_LOOP('',(#135749,#135750,#135751,#135752,#135753,#135754, + #135775,#135776,#135777,#135778,#135779,#135780)); +#135749 = ORIENTED_EDGE('',*,*,#135725,.F.); +#135750 = ORIENTED_EDGE('',*,*,#135428,.T.); +#135751 = ORIENTED_EDGE('',*,*,#135403,.T.); +#135752 = ORIENTED_EDGE('',*,*,#135123,.T.); +#135753 = ORIENTED_EDGE('',*,*,#134895,.T.); +#135754 = ORIENTED_EDGE('',*,*,#135755,.F.); +#135755 = EDGE_CURVE('',#134972,#134861,#135756,.T.); +#135756 = SURFACE_CURVE('',#135757,(#135761,#135768),.PCURVE_S1.); +#135757 = LINE('',#135758,#135759); +#135758 = CARTESIAN_POINT('',(11.,2.85,1.159810404338E-002)); +#135759 = VECTOR('',#135760,1.); +#135760 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#135761 = PCURVE('',#95018,#135762); +#135762 = DEFINITIONAL_REPRESENTATION('',(#135763),#135767); +#135763 = LINE('',#135764,#135765); +#135764 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#135765 = VECTOR('',#135766,1.); +#135766 = DIRECTION('',(1.,2.101748079665E-016)); +#135767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135768 = PCURVE('',#134883,#135769); +#135769 = DEFINITIONAL_REPRESENTATION('',(#135770),#135774); +#135770 = LINE('',#135771,#135772); +#135771 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#135772 = VECTOR('',#135773,1.); +#135773 = DIRECTION('',(1.194699204908E-017,1.)); +#135774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135775 = ORIENTED_EDGE('',*,*,#135049,.F.); +#135776 = ORIENTED_EDGE('',*,*,#135152,.F.); +#135777 = ORIENTED_EDGE('',*,*,#135306,.F.); +#135778 = ORIENTED_EDGE('',*,*,#135548,.F.); +#135779 = ORIENTED_EDGE('',*,*,#135621,.T.); +#135780 = ORIENTED_EDGE('',*,*,#95000,.F.); +#135781 = ADVANCED_FACE('',(#135782),#134883,.T.); +#135782 = FACE_BOUND('',#135783,.T.); +#135783 = EDGE_LOOP('',(#135784,#135785,#135786,#135787)); +#135784 = ORIENTED_EDGE('',*,*,#135673,.T.); +#135785 = ORIENTED_EDGE('',*,*,#134969,.T.); +#135786 = ORIENTED_EDGE('',*,*,#135755,.T.); +#135787 = ORIENTED_EDGE('',*,*,#134860,.T.); +#135788 = ADVANCED_FACE('',(#135789),#135803,.F.); +#135789 = FACE_BOUND('',#135790,.T.); +#135790 = EDGE_LOOP('',(#135791,#135826,#135849,#135876)); +#135791 = ORIENTED_EDGE('',*,*,#135792,.F.); +#135792 = EDGE_CURVE('',#135793,#135795,#135797,.T.); +#135793 = VERTEX_POINT('',#135794); +#135794 = CARTESIAN_POINT('',(11.,2.35,-0.208196358798)); +#135795 = VERTEX_POINT('',#135796); +#135796 = CARTESIAN_POINT('',(11.,2.15,-0.208196358798)); +#135797 = SURFACE_CURVE('',#135798,(#135802,#135814),.PCURVE_S1.); +#135798 = LINE('',#135799,#135800); +#135799 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#135800 = VECTOR('',#135801,1.); +#135801 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135802 = PCURVE('',#135803,#135808); +#135803 = PLANE('',#135804); +#135804 = AXIS2_PLACEMENT_3D('',#135805,#135806,#135807); +#135805 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#133414 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133415 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#133416 = DEFINITIONAL_REPRESENTATION('',(#133417),#133421); -#133417 = LINE('',#133418,#133419); -#133418 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#133419 = VECTOR('',#133420,1.); -#133420 = DIRECTION('',(4.440892098501E-016,-1.)); -#133421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133422 = PCURVE('',#133423,#133428); -#133423 = PLANE('',#133424); -#133424 = AXIS2_PLACEMENT_3D('',#133425,#133426,#133427); -#133425 = CARTESIAN_POINT('',(11.,2.25,-0.258196742327)); -#133426 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#133427 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133428 = DEFINITIONAL_REPRESENTATION('',(#133429),#133433); -#133429 = LINE('',#133430,#133431); -#133430 = CARTESIAN_POINT('',(-2.25,5.000038352949E-002)); -#133431 = VECTOR('',#133432,1.); -#133432 = DIRECTION('',(-1.,0.E+000)); -#133433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133434 = ORIENTED_EDGE('',*,*,#133435,.F.); -#133435 = EDGE_CURVE('',#133436,#133401,#133438,.T.); -#133436 = VERTEX_POINT('',#133437); -#133437 = CARTESIAN_POINT('',(10.740726081328,2.35,-0.208196358798)); -#133438 = SURFACE_CURVE('',#133439,(#133443,#133450),.PCURVE_S1.); -#133439 = LINE('',#133440,#133441); -#133440 = CARTESIAN_POINT('',(10.740726081328,2.35,-0.208196358798)); -#133441 = VECTOR('',#133442,1.); -#133442 = DIRECTION('',(1.,0.E+000,0.E+000)); -#133443 = PCURVE('',#133411,#133444); -#133444 = DEFINITIONAL_REPRESENTATION('',(#133445),#133449); -#133445 = LINE('',#133446,#133447); -#133446 = CARTESIAN_POINT('',(-1.7763568394E-015,2.35)); -#133447 = VECTOR('',#133448,1.); -#133448 = DIRECTION('',(-1.,0.E+000)); -#133449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133450 = PCURVE('',#92512,#133451); -#133451 = DEFINITIONAL_REPRESENTATION('',(#133452),#133456); -#133452 = LINE('',#133453,#133454); -#133453 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#133454 = VECTOR('',#133455,1.); -#133455 = DIRECTION('',(0.E+000,1.)); -#133456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133457 = ORIENTED_EDGE('',*,*,#133458,.F.); -#133458 = EDGE_CURVE('',#133459,#133436,#133461,.T.); -#133459 = VERTEX_POINT('',#133460); -#133460 = CARTESIAN_POINT('',(10.740726081328,2.15,-0.208196358798)); -#133461 = SURFACE_CURVE('',#133462,(#133466,#133473),.PCURVE_S1.); -#133462 = LINE('',#133463,#133464); -#133463 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#135806 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#135807 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#135808 = DEFINITIONAL_REPRESENTATION('',(#135809),#135813); +#135809 = LINE('',#135810,#135811); +#135810 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#135811 = VECTOR('',#135812,1.); +#135812 = DIRECTION('',(4.440892098501E-016,-1.)); +#135813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135814 = PCURVE('',#135815,#135820); +#135815 = PLANE('',#135816); +#135816 = AXIS2_PLACEMENT_3D('',#135817,#135818,#135819); +#135817 = CARTESIAN_POINT('',(11.,2.25,-0.258196742327)); +#135818 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#135819 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135820 = DEFINITIONAL_REPRESENTATION('',(#135821),#135825); +#135821 = LINE('',#135822,#135823); +#135822 = CARTESIAN_POINT('',(-2.25,5.000038352949E-002)); +#135823 = VECTOR('',#135824,1.); +#135824 = DIRECTION('',(-1.,0.E+000)); +#135825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135826 = ORIENTED_EDGE('',*,*,#135827,.F.); +#135827 = EDGE_CURVE('',#135828,#135793,#135830,.T.); +#135828 = VERTEX_POINT('',#135829); +#135829 = CARTESIAN_POINT('',(10.740726081328,2.35,-0.208196358798)); +#135830 = SURFACE_CURVE('',#135831,(#135835,#135842),.PCURVE_S1.); +#135831 = LINE('',#135832,#135833); +#135832 = CARTESIAN_POINT('',(10.740726081328,2.35,-0.208196358798)); +#135833 = VECTOR('',#135834,1.); +#135834 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135835 = PCURVE('',#135803,#135836); +#135836 = DEFINITIONAL_REPRESENTATION('',(#135837),#135841); +#135837 = LINE('',#135838,#135839); +#135838 = CARTESIAN_POINT('',(-1.7763568394E-015,2.35)); +#135839 = VECTOR('',#135840,1.); +#135840 = DIRECTION('',(-1.,0.E+000)); +#135841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135842 = PCURVE('',#94904,#135843); +#135843 = DEFINITIONAL_REPRESENTATION('',(#135844),#135848); +#135844 = LINE('',#135845,#135846); +#135845 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#135846 = VECTOR('',#135847,1.); +#135847 = DIRECTION('',(0.E+000,1.)); +#135848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135849 = ORIENTED_EDGE('',*,*,#135850,.F.); +#135850 = EDGE_CURVE('',#135851,#135828,#135853,.T.); +#135851 = VERTEX_POINT('',#135852); +#135852 = CARTESIAN_POINT('',(10.740726081328,2.15,-0.208196358798)); +#135853 = SURFACE_CURVE('',#135854,(#135858,#135865),.PCURVE_S1.); +#135854 = LINE('',#135855,#135856); +#135855 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#133464 = VECTOR('',#133465,1.); -#133465 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133466 = PCURVE('',#133411,#133467); -#133467 = DEFINITIONAL_REPRESENTATION('',(#133468),#133472); -#133468 = LINE('',#133469,#133470); -#133469 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133470 = VECTOR('',#133471,1.); -#133471 = DIRECTION('',(-4.440892098501E-016,1.)); -#133472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133473 = PCURVE('',#133474,#133479); -#133474 = CYLINDRICAL_SURFACE('',#133475,0.208574704164); -#133475 = AXIS2_PLACEMENT_3D('',#133476,#133477,#133478); -#133476 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#135856 = VECTOR('',#135857,1.); +#135857 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135858 = PCURVE('',#135803,#135859); +#135859 = DEFINITIONAL_REPRESENTATION('',(#135860),#135864); +#135860 = LINE('',#135861,#135862); +#135861 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135862 = VECTOR('',#135863,1.); +#135863 = DIRECTION('',(-4.440892098501E-016,1.)); +#135864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135865 = PCURVE('',#135866,#135871); +#135866 = CYLINDRICAL_SURFACE('',#135867,0.208574704164); +#135867 = AXIS2_PLACEMENT_3D('',#135868,#135869,#135870); +#135868 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#133477 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133478 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133479 = DEFINITIONAL_REPRESENTATION('',(#133480),#133483); -#133480 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133481,#133482), +#135869 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135870 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135871 = DEFINITIONAL_REPRESENTATION('',(#135872),#135875); +#135872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135873,#135874), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#133481 = CARTESIAN_POINT('',(4.772630242227,-2.15)); -#133482 = CARTESIAN_POINT('',(4.772630242227,-2.35)); -#133483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133484 = ORIENTED_EDGE('',*,*,#133485,.T.); -#133485 = EDGE_CURVE('',#133459,#133403,#133486,.T.); -#133486 = SURFACE_CURVE('',#133487,(#133491,#133498),.PCURVE_S1.); -#133487 = LINE('',#133488,#133489); -#133488 = CARTESIAN_POINT('',(10.740726081328,2.15,-0.208196358798)); -#133489 = VECTOR('',#133490,1.); -#133490 = DIRECTION('',(1.,0.E+000,0.E+000)); -#133491 = PCURVE('',#133411,#133492); -#133492 = DEFINITIONAL_REPRESENTATION('',(#133493),#133497); -#133493 = LINE('',#133494,#133495); -#133494 = CARTESIAN_POINT('',(-1.7763568394E-015,2.15)); -#133495 = VECTOR('',#133496,1.); -#133496 = DIRECTION('',(-1.,0.E+000)); -#133497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133498 = PCURVE('',#92568,#133499); -#133499 = DEFINITIONAL_REPRESENTATION('',(#133500),#133504); -#133500 = LINE('',#133501,#133502); -#133501 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#133502 = VECTOR('',#133503,1.); -#133503 = DIRECTION('',(0.E+000,1.)); -#133504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135873 = CARTESIAN_POINT('',(4.772630242227,-2.15)); +#135874 = CARTESIAN_POINT('',(4.772630242227,-2.35)); +#135875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135876 = ORIENTED_EDGE('',*,*,#135877,.T.); +#135877 = EDGE_CURVE('',#135851,#135795,#135878,.T.); +#135878 = SURFACE_CURVE('',#135879,(#135883,#135890),.PCURVE_S1.); +#135879 = LINE('',#135880,#135881); +#135880 = CARTESIAN_POINT('',(10.740726081328,2.15,-0.208196358798)); +#135881 = VECTOR('',#135882,1.); +#135882 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135883 = PCURVE('',#135803,#135884); +#135884 = DEFINITIONAL_REPRESENTATION('',(#135885),#135889); +#135885 = LINE('',#135886,#135887); +#135886 = CARTESIAN_POINT('',(-1.7763568394E-015,2.15)); +#135887 = VECTOR('',#135888,1.); +#135888 = DIRECTION('',(-1.,0.E+000)); +#135889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135890 = PCURVE('',#94960,#135891); +#135891 = DEFINITIONAL_REPRESENTATION('',(#135892),#135896); +#135892 = LINE('',#135893,#135894); +#135893 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#135894 = VECTOR('',#135895,1.); +#135895 = DIRECTION('',(0.E+000,1.)); +#135896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133505 = ADVANCED_FACE('',(#133506),#133520,.F.); -#133506 = FACE_BOUND('',#133507,.T.); -#133507 = EDGE_LOOP('',(#133508,#133538,#133561,#133588)); -#133508 = ORIENTED_EDGE('',*,*,#133509,.F.); -#133509 = EDGE_CURVE('',#133510,#133512,#133514,.T.); -#133510 = VERTEX_POINT('',#133511); -#133511 = CARTESIAN_POINT('',(11.,2.15,-0.308197125857)); -#133512 = VERTEX_POINT('',#133513); -#133513 = CARTESIAN_POINT('',(11.,2.35,-0.308197125857)); -#133514 = SURFACE_CURVE('',#133515,(#133519,#133531),.PCURVE_S1.); -#133515 = LINE('',#133516,#133517); -#133516 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#133517 = VECTOR('',#133518,1.); -#133518 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133519 = PCURVE('',#133520,#133525); -#133520 = PLANE('',#133521); -#133521 = AXIS2_PLACEMENT_3D('',#133522,#133523,#133524); -#133522 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#135897 = ADVANCED_FACE('',(#135898),#135912,.F.); +#135898 = FACE_BOUND('',#135899,.T.); +#135899 = EDGE_LOOP('',(#135900,#135930,#135953,#135980)); +#135900 = ORIENTED_EDGE('',*,*,#135901,.F.); +#135901 = EDGE_CURVE('',#135902,#135904,#135906,.T.); +#135902 = VERTEX_POINT('',#135903); +#135903 = CARTESIAN_POINT('',(11.,2.15,-0.308197125857)); +#135904 = VERTEX_POINT('',#135905); +#135905 = CARTESIAN_POINT('',(11.,2.35,-0.308197125857)); +#135906 = SURFACE_CURVE('',#135907,(#135911,#135923),.PCURVE_S1.); +#135907 = LINE('',#135908,#135909); +#135908 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#135909 = VECTOR('',#135910,1.); +#135910 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#135911 = PCURVE('',#135912,#135917); +#135912 = PLANE('',#135913); +#135913 = AXIS2_PLACEMENT_3D('',#135914,#135915,#135916); +#135914 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#133523 = DIRECTION('',(0.E+000,0.E+000,1.)); -#133524 = DIRECTION('',(1.,0.E+000,0.E+000)); -#133525 = DEFINITIONAL_REPRESENTATION('',(#133526),#133530); -#133526 = LINE('',#133527,#133528); -#133527 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#133528 = VECTOR('',#133529,1.); -#133529 = DIRECTION('',(4.440892098501E-016,1.)); -#133530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135915 = DIRECTION('',(0.E+000,0.E+000,1.)); +#135916 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135917 = DEFINITIONAL_REPRESENTATION('',(#135918),#135922); +#135918 = LINE('',#135919,#135920); +#135919 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#135920 = VECTOR('',#135921,1.); +#135921 = DIRECTION('',(4.440892098501E-016,1.)); +#135922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135923 = PCURVE('',#135815,#135924); +#135924 = DEFINITIONAL_REPRESENTATION('',(#135925),#135929); +#135925 = LINE('',#135926,#135927); +#135926 = CARTESIAN_POINT('',(-2.25,-5.00003835295E-002)); +#135927 = VECTOR('',#135928,1.); +#135928 = DIRECTION('',(1.,0.E+000)); +#135929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135930 = ORIENTED_EDGE('',*,*,#135931,.F.); +#135931 = EDGE_CURVE('',#135932,#135902,#135934,.T.); +#135932 = VERTEX_POINT('',#135933); +#135933 = CARTESIAN_POINT('',(10.74341632541,2.15,-0.308197125857)); +#135934 = SURFACE_CURVE('',#135935,(#135939,#135946),.PCURVE_S1.); +#135935 = LINE('',#135936,#135937); +#135936 = CARTESIAN_POINT('',(10.74341632541,2.15,-0.308197125857)); +#135937 = VECTOR('',#135938,1.); +#135938 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135939 = PCURVE('',#135912,#135940); +#135940 = DEFINITIONAL_REPRESENTATION('',(#135941),#135945); +#135941 = LINE('',#135942,#135943); +#135942 = CARTESIAN_POINT('',(1.7763568394E-015,2.15)); +#135943 = VECTOR('',#135944,1.); +#135944 = DIRECTION('',(1.,0.E+000)); +#135945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133531 = PCURVE('',#133423,#133532); -#133532 = DEFINITIONAL_REPRESENTATION('',(#133533),#133537); -#133533 = LINE('',#133534,#133535); -#133534 = CARTESIAN_POINT('',(-2.25,-5.00003835295E-002)); -#133535 = VECTOR('',#133536,1.); -#133536 = DIRECTION('',(1.,0.E+000)); -#133537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#135946 = PCURVE('',#94960,#135947); +#135947 = DEFINITIONAL_REPRESENTATION('',(#135948),#135952); +#135948 = LINE('',#135949,#135950); +#135949 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#135950 = VECTOR('',#135951,1.); +#135951 = DIRECTION('',(0.E+000,1.)); +#135952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133538 = ORIENTED_EDGE('',*,*,#133539,.F.); -#133539 = EDGE_CURVE('',#133540,#133510,#133542,.T.); -#133540 = VERTEX_POINT('',#133541); -#133541 = CARTESIAN_POINT('',(10.74341632541,2.15,-0.308197125857)); -#133542 = SURFACE_CURVE('',#133543,(#133547,#133554),.PCURVE_S1.); -#133543 = LINE('',#133544,#133545); -#133544 = CARTESIAN_POINT('',(10.74341632541,2.15,-0.308197125857)); -#133545 = VECTOR('',#133546,1.); -#133546 = DIRECTION('',(1.,0.E+000,0.E+000)); -#133547 = PCURVE('',#133520,#133548); -#133548 = DEFINITIONAL_REPRESENTATION('',(#133549),#133553); -#133549 = LINE('',#133550,#133551); -#133550 = CARTESIAN_POINT('',(1.7763568394E-015,2.15)); -#133551 = VECTOR('',#133552,1.); -#133552 = DIRECTION('',(1.,0.E+000)); -#133553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133554 = PCURVE('',#92568,#133555); -#133555 = DEFINITIONAL_REPRESENTATION('',(#133556),#133560); -#133556 = LINE('',#133557,#133558); -#133557 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#133558 = VECTOR('',#133559,1.); -#133559 = DIRECTION('',(0.E+000,1.)); -#133560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133561 = ORIENTED_EDGE('',*,*,#133562,.F.); -#133562 = EDGE_CURVE('',#133563,#133540,#133565,.T.); -#133563 = VERTEX_POINT('',#133564); -#133564 = CARTESIAN_POINT('',(10.74341632541,2.35,-0.308197125857)); -#133565 = SURFACE_CURVE('',#133566,(#133570,#133577),.PCURVE_S1.); -#133566 = LINE('',#133567,#133568); -#133567 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#135953 = ORIENTED_EDGE('',*,*,#135954,.F.); +#135954 = EDGE_CURVE('',#135955,#135932,#135957,.T.); +#135955 = VERTEX_POINT('',#135956); +#135956 = CARTESIAN_POINT('',(10.74341632541,2.35,-0.308197125857)); +#135957 = SURFACE_CURVE('',#135958,(#135962,#135969),.PCURVE_S1.); +#135958 = LINE('',#135959,#135960); +#135959 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#133568 = VECTOR('',#133569,1.); -#133569 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133570 = PCURVE('',#133520,#133571); -#133571 = DEFINITIONAL_REPRESENTATION('',(#133572),#133576); -#133572 = LINE('',#133573,#133574); -#133573 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133574 = VECTOR('',#133575,1.); -#133575 = DIRECTION('',(-4.440892098501E-016,-1.)); -#133576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133577 = PCURVE('',#133578,#133583); -#133578 = CYLINDRICAL_SURFACE('',#133579,0.308574064194); -#133579 = AXIS2_PLACEMENT_3D('',#133580,#133581,#133582); -#133580 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#135960 = VECTOR('',#135961,1.); +#135961 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135962 = PCURVE('',#135912,#135963); +#135963 = DEFINITIONAL_REPRESENTATION('',(#135964),#135968); +#135964 = LINE('',#135965,#135966); +#135965 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#135966 = VECTOR('',#135967,1.); +#135967 = DIRECTION('',(-4.440892098501E-016,-1.)); +#135968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135969 = PCURVE('',#135970,#135975); +#135970 = CYLINDRICAL_SURFACE('',#135971,0.308574064194); +#135971 = AXIS2_PLACEMENT_3D('',#135972,#135973,#135974); +#135972 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#133581 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133582 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133583 = DEFINITIONAL_REPRESENTATION('',(#133584),#133587); -#133584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133585,#133586), +#135973 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#135974 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#135975 = DEFINITIONAL_REPRESENTATION('',(#135976),#135979); +#135976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135977,#135978), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#133585 = CARTESIAN_POINT('',(4.761821717947,-2.35)); -#133586 = CARTESIAN_POINT('',(4.761821717947,-2.15)); -#133587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133588 = ORIENTED_EDGE('',*,*,#133589,.T.); -#133589 = EDGE_CURVE('',#133563,#133512,#133590,.T.); -#133590 = SURFACE_CURVE('',#133591,(#133595,#133602),.PCURVE_S1.); -#133591 = LINE('',#133592,#133593); -#133592 = CARTESIAN_POINT('',(10.74341632541,2.35,-0.308197125857)); -#133593 = VECTOR('',#133594,1.); -#133594 = DIRECTION('',(1.,0.E+000,0.E+000)); -#133595 = PCURVE('',#133520,#133596); -#133596 = DEFINITIONAL_REPRESENTATION('',(#133597),#133601); -#133597 = LINE('',#133598,#133599); -#133598 = CARTESIAN_POINT('',(1.7763568394E-015,2.35)); -#133599 = VECTOR('',#133600,1.); -#133600 = DIRECTION('',(1.,0.E+000)); -#133601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133602 = PCURVE('',#92512,#133603); -#133603 = DEFINITIONAL_REPRESENTATION('',(#133604),#133608); -#133604 = LINE('',#133605,#133606); -#133605 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#133606 = VECTOR('',#133607,1.); -#133607 = DIRECTION('',(0.E+000,1.)); -#133608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133609 = ADVANCED_FACE('',(#133610),#133474,.F.); -#133610 = FACE_BOUND('',#133611,.F.); -#133611 = EDGE_LOOP('',(#133612,#133635,#133662,#133687)); -#133612 = ORIENTED_EDGE('',*,*,#133613,.F.); -#133613 = EDGE_CURVE('',#133614,#133459,#133616,.T.); -#133614 = VERTEX_POINT('',#133615); -#133615 = CARTESIAN_POINT('',(10.51959417205,2.15,0.E+000)); -#133616 = SURFACE_CURVE('',#133617,(#133622,#133628),.PCURVE_S1.); -#133617 = CIRCLE('',#133618,0.208574704164); -#133618 = AXIS2_PLACEMENT_3D('',#133619,#133620,#133621); -#133619 = CARTESIAN_POINT('',(10.728168876214,2.15,2.640924866458E-017) - ); -#133620 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133621 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133622 = PCURVE('',#133474,#133623); -#133623 = DEFINITIONAL_REPRESENTATION('',(#133624),#133627); -#133624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133625,#133626), +#135977 = CARTESIAN_POINT('',(4.761821717947,-2.35)); +#135978 = CARTESIAN_POINT('',(4.761821717947,-2.15)); +#135979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135980 = ORIENTED_EDGE('',*,*,#135981,.T.); +#135981 = EDGE_CURVE('',#135955,#135904,#135982,.T.); +#135982 = SURFACE_CURVE('',#135983,(#135987,#135994),.PCURVE_S1.); +#135983 = LINE('',#135984,#135985); +#135984 = CARTESIAN_POINT('',(10.74341632541,2.35,-0.308197125857)); +#135985 = VECTOR('',#135986,1.); +#135986 = DIRECTION('',(1.,0.E+000,0.E+000)); +#135987 = PCURVE('',#135912,#135988); +#135988 = DEFINITIONAL_REPRESENTATION('',(#135989),#135993); +#135989 = LINE('',#135990,#135991); +#135990 = CARTESIAN_POINT('',(1.7763568394E-015,2.35)); +#135991 = VECTOR('',#135992,1.); +#135992 = DIRECTION('',(1.,0.E+000)); +#135993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#135994 = PCURVE('',#94904,#135995); +#135995 = DEFINITIONAL_REPRESENTATION('',(#135996),#136000); +#135996 = LINE('',#135997,#135998); +#135997 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#135998 = VECTOR('',#135999,1.); +#135999 = DIRECTION('',(0.E+000,1.)); +#136000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136001 = ADVANCED_FACE('',(#136002),#135866,.F.); +#136002 = FACE_BOUND('',#136003,.F.); +#136003 = EDGE_LOOP('',(#136004,#136027,#136054,#136079)); +#136004 = ORIENTED_EDGE('',*,*,#136005,.F.); +#136005 = EDGE_CURVE('',#136006,#135851,#136008,.T.); +#136006 = VERTEX_POINT('',#136007); +#136007 = CARTESIAN_POINT('',(10.51959417205,2.15,0.E+000)); +#136008 = SURFACE_CURVE('',#136009,(#136014,#136020),.PCURVE_S1.); +#136009 = CIRCLE('',#136010,0.208574704164); +#136010 = AXIS2_PLACEMENT_3D('',#136011,#136012,#136013); +#136011 = CARTESIAN_POINT('',(10.728168876214,2.15,2.640924866458E-017) + ); +#136012 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136013 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136014 = PCURVE('',#135866,#136015); +#136015 = DEFINITIONAL_REPRESENTATION('',(#136016),#136019); +#136016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136017,#136018), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#133625 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#133626 = CARTESIAN_POINT('',(4.772630242227,-2.15)); -#133627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136017 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#136018 = CARTESIAN_POINT('',(4.772630242227,-2.15)); +#136019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133628 = PCURVE('',#92568,#133629); -#133629 = DEFINITIONAL_REPRESENTATION('',(#133630),#133634); -#133630 = CIRCLE('',#133631,0.208574704164); -#133631 = AXIS2_PLACEMENT_2D('',#133632,#133633); -#133632 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#133633 = DIRECTION('',(0.E+000,1.)); -#133634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136020 = PCURVE('',#94960,#136021); +#136021 = DEFINITIONAL_REPRESENTATION('',(#136022),#136026); +#136022 = CIRCLE('',#136023,0.208574704164); +#136023 = AXIS2_PLACEMENT_2D('',#136024,#136025); +#136024 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#136025 = DIRECTION('',(0.E+000,1.)); +#136026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133635 = ORIENTED_EDGE('',*,*,#133636,.F.); -#133636 = EDGE_CURVE('',#133637,#133614,#133639,.T.); -#133637 = VERTEX_POINT('',#133638); -#133638 = CARTESIAN_POINT('',(10.51959417205,2.35,0.E+000)); -#133639 = SURFACE_CURVE('',#133640,(#133644,#133650),.PCURVE_S1.); -#133640 = LINE('',#133641,#133642); -#133641 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#136027 = ORIENTED_EDGE('',*,*,#136028,.F.); +#136028 = EDGE_CURVE('',#136029,#136006,#136031,.T.); +#136029 = VERTEX_POINT('',#136030); +#136030 = CARTESIAN_POINT('',(10.51959417205,2.35,0.E+000)); +#136031 = SURFACE_CURVE('',#136032,(#136036,#136042),.PCURVE_S1.); +#136032 = LINE('',#136033,#136034); +#136033 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#133642 = VECTOR('',#133643,1.); -#133643 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133644 = PCURVE('',#133474,#133645); -#133645 = DEFINITIONAL_REPRESENTATION('',(#133646),#133649); -#133646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133647,#133648), +#136034 = VECTOR('',#136035,1.); +#136035 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136036 = PCURVE('',#135866,#136037); +#136037 = DEFINITIONAL_REPRESENTATION('',(#136038),#136041); +#136038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136039,#136040), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#133647 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#133648 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#133649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136039 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#136040 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#136041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133650 = PCURVE('',#133651,#133656); -#133651 = PLANE('',#133652); -#133652 = AXIS2_PLACEMENT_3D('',#133653,#133654,#133655); -#133653 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#136042 = PCURVE('',#136043,#136048); +#136043 = PLANE('',#136044); +#136044 = AXIS2_PLACEMENT_3D('',#136045,#136046,#136047); +#136045 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#133654 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133655 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133656 = DEFINITIONAL_REPRESENTATION('',(#133657),#133661); -#133657 = LINE('',#133658,#133659); -#133658 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#133659 = VECTOR('',#133660,1.); -#133660 = DIRECTION('',(-1.,0.E+000)); -#133661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133662 = ORIENTED_EDGE('',*,*,#133663,.T.); -#133663 = EDGE_CURVE('',#133637,#133436,#133664,.T.); -#133664 = SURFACE_CURVE('',#133665,(#133670,#133676),.PCURVE_S1.); -#133665 = CIRCLE('',#133666,0.208574704164); -#133666 = AXIS2_PLACEMENT_3D('',#133667,#133668,#133669); -#133667 = CARTESIAN_POINT('',(10.728168876214,2.35,2.640924866458E-017) - ); -#133668 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133669 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133670 = PCURVE('',#133474,#133671); -#133671 = DEFINITIONAL_REPRESENTATION('',(#133672),#133675); -#133672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133673,#133674), +#136046 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136047 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136048 = DEFINITIONAL_REPRESENTATION('',(#136049),#136053); +#136049 = LINE('',#136050,#136051); +#136050 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#136051 = VECTOR('',#136052,1.); +#136052 = DIRECTION('',(-1.,0.E+000)); +#136053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136054 = ORIENTED_EDGE('',*,*,#136055,.T.); +#136055 = EDGE_CURVE('',#136029,#135828,#136056,.T.); +#136056 = SURFACE_CURVE('',#136057,(#136062,#136068),.PCURVE_S1.); +#136057 = CIRCLE('',#136058,0.208574704164); +#136058 = AXIS2_PLACEMENT_3D('',#136059,#136060,#136061); +#136059 = CARTESIAN_POINT('',(10.728168876214,2.35,2.640924866458E-017) + ); +#136060 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136061 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136062 = PCURVE('',#135866,#136063); +#136063 = DEFINITIONAL_REPRESENTATION('',(#136064),#136067); +#136064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136065,#136066), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#133673 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#133674 = CARTESIAN_POINT('',(4.772630242227,-2.35)); -#133675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136065 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#136066 = CARTESIAN_POINT('',(4.772630242227,-2.35)); +#136067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133676 = PCURVE('',#92512,#133677); -#133677 = DEFINITIONAL_REPRESENTATION('',(#133678),#133686); -#133678 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133679,#133680,#133681, - #133682,#133683,#133684,#133685),.UNSPECIFIED.,.T.,.F.) +#136068 = PCURVE('',#94904,#136069); +#136069 = DEFINITIONAL_REPRESENTATION('',(#136070),#136078); +#136070 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136071,#136072,#136073, + #136074,#136075,#136076,#136077),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#133679 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#133680 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#133681 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#133682 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#133683 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#133684 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#133685 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#133686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133687 = ORIENTED_EDGE('',*,*,#133458,.F.); -#133688 = ADVANCED_FACE('',(#133689),#133578,.T.); -#133689 = FACE_BOUND('',#133690,.T.); -#133690 = EDGE_LOOP('',(#133691,#133741,#133742,#133788)); -#133691 = ORIENTED_EDGE('',*,*,#133692,.T.); -#133692 = EDGE_CURVE('',#133693,#133563,#133695,.T.); -#133693 = VERTEX_POINT('',#133694); -#133694 = CARTESIAN_POINT('',(10.419594812019,2.35,0.E+000)); -#133695 = SURFACE_CURVE('',#133696,(#133701,#133730),.PCURVE_S1.); -#133696 = CIRCLE('',#133697,0.308574064194); -#133697 = AXIS2_PLACEMENT_3D('',#133698,#133699,#133700); -#133698 = CARTESIAN_POINT('',(10.728168876214,2.35,2.640924866458E-017) - ); -#133699 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133700 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133701 = PCURVE('',#133578,#133702); -#133702 = DEFINITIONAL_REPRESENTATION('',(#133703),#133729); -#133703 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133704,#133705,#133706, - #133707,#133708,#133709,#133710,#133711,#133712,#133713,#133714, - #133715,#133716,#133717,#133718,#133719,#133720,#133721,#133722, - #133723,#133724,#133725,#133726,#133727,#133728),.UNSPECIFIED.,.F., +#136071 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#136072 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#136073 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#136074 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#136075 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#136076 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#136077 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#136078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136079 = ORIENTED_EDGE('',*,*,#135850,.F.); +#136080 = ADVANCED_FACE('',(#136081),#135970,.T.); +#136081 = FACE_BOUND('',#136082,.T.); +#136082 = EDGE_LOOP('',(#136083,#136133,#136134,#136180)); +#136083 = ORIENTED_EDGE('',*,*,#136084,.T.); +#136084 = EDGE_CURVE('',#136085,#135955,#136087,.T.); +#136085 = VERTEX_POINT('',#136086); +#136086 = CARTESIAN_POINT('',(10.419594812019,2.35,0.E+000)); +#136087 = SURFACE_CURVE('',#136088,(#136093,#136122),.PCURVE_S1.); +#136088 = CIRCLE('',#136089,0.308574064194); +#136089 = AXIS2_PLACEMENT_3D('',#136090,#136091,#136092); +#136090 = CARTESIAN_POINT('',(10.728168876214,2.35,2.640924866458E-017) + ); +#136091 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136092 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136093 = PCURVE('',#135970,#136094); +#136094 = DEFINITIONAL_REPRESENTATION('',(#136095),#136121); +#136095 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#136096,#136097,#136098, + #136099,#136100,#136101,#136102,#136103,#136104,#136105,#136106, + #136107,#136108,#136109,#136110,#136111,#136112,#136113,#136114, + #136115,#136116,#136117,#136118,#136119,#136120),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -164754,71 +167756,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#133704 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#133705 = CARTESIAN_POINT('',(3.166141578807,-2.35)); -#133706 = CARTESIAN_POINT('',(3.215239429242,-2.35)); -#133707 = CARTESIAN_POINT('',(3.288886204895,-2.35)); -#133708 = CARTESIAN_POINT('',(3.362532980548,-2.35)); -#133709 = CARTESIAN_POINT('',(3.4361797562,-2.35)); -#133710 = CARTESIAN_POINT('',(3.509826531853,-2.35)); -#133711 = CARTESIAN_POINT('',(3.583473307505,-2.35)); -#133712 = CARTESIAN_POINT('',(3.657120083158,-2.35)); -#133713 = CARTESIAN_POINT('',(3.730766858811,-2.35)); -#133714 = CARTESIAN_POINT('',(3.804413634463,-2.35)); -#133715 = CARTESIAN_POINT('',(3.878060410116,-2.35)); -#133716 = CARTESIAN_POINT('',(3.951707185768,-2.35)); -#133717 = CARTESIAN_POINT('',(4.025353961421,-2.35)); -#133718 = CARTESIAN_POINT('',(4.099000737074,-2.35)); -#133719 = CARTESIAN_POINT('',(4.172647512726,-2.35)); -#133720 = CARTESIAN_POINT('',(4.246294288379,-2.35)); -#133721 = CARTESIAN_POINT('',(4.319941064031,-2.35)); -#133722 = CARTESIAN_POINT('',(4.393587839684,-2.35)); -#133723 = CARTESIAN_POINT('',(4.467234615337,-2.35)); -#133724 = CARTESIAN_POINT('',(4.540881390989,-2.35)); -#133725 = CARTESIAN_POINT('',(4.614528166642,-2.35)); -#133726 = CARTESIAN_POINT('',(4.688174942294,-2.35)); -#133727 = CARTESIAN_POINT('',(4.737272792729,-2.35)); -#133728 = CARTESIAN_POINT('',(4.761821717947,-2.35)); -#133729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133730 = PCURVE('',#92512,#133731); -#133731 = DEFINITIONAL_REPRESENTATION('',(#133732),#133740); -#133732 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#133733,#133734,#133735, - #133736,#133737,#133738,#133739),.UNSPECIFIED.,.T.,.F.) +#136096 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#136097 = CARTESIAN_POINT('',(3.166141578807,-2.35)); +#136098 = CARTESIAN_POINT('',(3.215239429242,-2.35)); +#136099 = CARTESIAN_POINT('',(3.288886204895,-2.35)); +#136100 = CARTESIAN_POINT('',(3.362532980548,-2.35)); +#136101 = CARTESIAN_POINT('',(3.4361797562,-2.35)); +#136102 = CARTESIAN_POINT('',(3.509826531853,-2.35)); +#136103 = CARTESIAN_POINT('',(3.583473307505,-2.35)); +#136104 = CARTESIAN_POINT('',(3.657120083158,-2.35)); +#136105 = CARTESIAN_POINT('',(3.730766858811,-2.35)); +#136106 = CARTESIAN_POINT('',(3.804413634463,-2.35)); +#136107 = CARTESIAN_POINT('',(3.878060410116,-2.35)); +#136108 = CARTESIAN_POINT('',(3.951707185768,-2.35)); +#136109 = CARTESIAN_POINT('',(4.025353961421,-2.35)); +#136110 = CARTESIAN_POINT('',(4.099000737074,-2.35)); +#136111 = CARTESIAN_POINT('',(4.172647512726,-2.35)); +#136112 = CARTESIAN_POINT('',(4.246294288379,-2.35)); +#136113 = CARTESIAN_POINT('',(4.319941064031,-2.35)); +#136114 = CARTESIAN_POINT('',(4.393587839684,-2.35)); +#136115 = CARTESIAN_POINT('',(4.467234615337,-2.35)); +#136116 = CARTESIAN_POINT('',(4.540881390989,-2.35)); +#136117 = CARTESIAN_POINT('',(4.614528166642,-2.35)); +#136118 = CARTESIAN_POINT('',(4.688174942294,-2.35)); +#136119 = CARTESIAN_POINT('',(4.737272792729,-2.35)); +#136120 = CARTESIAN_POINT('',(4.761821717947,-2.35)); +#136121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136122 = PCURVE('',#94904,#136123); +#136123 = DEFINITIONAL_REPRESENTATION('',(#136124),#136132); +#136124 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136125,#136126,#136127, + #136128,#136129,#136130,#136131),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#133733 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#133734 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#133735 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#133736 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#133737 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#133738 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#133739 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#133740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133741 = ORIENTED_EDGE('',*,*,#133562,.T.); -#133742 = ORIENTED_EDGE('',*,*,#133743,.F.); -#133743 = EDGE_CURVE('',#133744,#133540,#133746,.T.); -#133744 = VERTEX_POINT('',#133745); -#133745 = CARTESIAN_POINT('',(10.419594812019,2.15,0.E+000)); -#133746 = SURFACE_CURVE('',#133747,(#133752,#133781),.PCURVE_S1.); -#133747 = CIRCLE('',#133748,0.308574064194); -#133748 = AXIS2_PLACEMENT_3D('',#133749,#133750,#133751); -#133749 = CARTESIAN_POINT('',(10.728168876214,2.15,2.640924866458E-017) - ); -#133750 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133751 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#133752 = PCURVE('',#133578,#133753); -#133753 = DEFINITIONAL_REPRESENTATION('',(#133754),#133780); -#133754 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133755,#133756,#133757, - #133758,#133759,#133760,#133761,#133762,#133763,#133764,#133765, - #133766,#133767,#133768,#133769,#133770,#133771,#133772,#133773, - #133774,#133775,#133776,#133777,#133778,#133779),.UNSPECIFIED.,.F., +#136125 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#136126 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#136127 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#136128 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#136129 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#136130 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#136131 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#136132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136133 = ORIENTED_EDGE('',*,*,#135954,.T.); +#136134 = ORIENTED_EDGE('',*,*,#136135,.F.); +#136135 = EDGE_CURVE('',#136136,#135932,#136138,.T.); +#136136 = VERTEX_POINT('',#136137); +#136137 = CARTESIAN_POINT('',(10.419594812019,2.15,0.E+000)); +#136138 = SURFACE_CURVE('',#136139,(#136144,#136173),.PCURVE_S1.); +#136139 = CIRCLE('',#136140,0.308574064194); +#136140 = AXIS2_PLACEMENT_3D('',#136141,#136142,#136143); +#136141 = CARTESIAN_POINT('',(10.728168876214,2.15,2.640924866458E-017) + ); +#136142 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136143 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136144 = PCURVE('',#135970,#136145); +#136145 = DEFINITIONAL_REPRESENTATION('',(#136146),#136172); +#136146 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#136147,#136148,#136149, + #136150,#136151,#136152,#136153,#136154,#136155,#136156,#136157, + #136158,#136159,#136160,#136161,#136162,#136163,#136164,#136165, + #136166,#136167,#136168,#136169,#136170,#136171),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -164826,275 +167828,275 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#133755 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#133756 = CARTESIAN_POINT('',(3.166141578807,-2.15)); -#133757 = CARTESIAN_POINT('',(3.215239429242,-2.15)); -#133758 = CARTESIAN_POINT('',(3.288886204895,-2.15)); -#133759 = CARTESIAN_POINT('',(3.362532980548,-2.15)); -#133760 = CARTESIAN_POINT('',(3.4361797562,-2.15)); -#133761 = CARTESIAN_POINT('',(3.509826531853,-2.15)); -#133762 = CARTESIAN_POINT('',(3.583473307505,-2.15)); -#133763 = CARTESIAN_POINT('',(3.657120083158,-2.15)); -#133764 = CARTESIAN_POINT('',(3.730766858811,-2.15)); -#133765 = CARTESIAN_POINT('',(3.804413634463,-2.15)); -#133766 = CARTESIAN_POINT('',(3.878060410116,-2.15)); -#133767 = CARTESIAN_POINT('',(3.951707185768,-2.15)); -#133768 = CARTESIAN_POINT('',(4.025353961421,-2.15)); -#133769 = CARTESIAN_POINT('',(4.099000737074,-2.15)); -#133770 = CARTESIAN_POINT('',(4.172647512726,-2.15)); -#133771 = CARTESIAN_POINT('',(4.246294288379,-2.15)); -#133772 = CARTESIAN_POINT('',(4.319941064031,-2.15)); -#133773 = CARTESIAN_POINT('',(4.393587839684,-2.15)); -#133774 = CARTESIAN_POINT('',(4.467234615337,-2.15)); -#133775 = CARTESIAN_POINT('',(4.540881390989,-2.15)); -#133776 = CARTESIAN_POINT('',(4.614528166642,-2.15)); -#133777 = CARTESIAN_POINT('',(4.688174942294,-2.15)); -#133778 = CARTESIAN_POINT('',(4.737272792729,-2.15)); -#133779 = CARTESIAN_POINT('',(4.761821717947,-2.15)); -#133780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133781 = PCURVE('',#92568,#133782); -#133782 = DEFINITIONAL_REPRESENTATION('',(#133783),#133787); -#133783 = CIRCLE('',#133784,0.308574064194); -#133784 = AXIS2_PLACEMENT_2D('',#133785,#133786); -#133785 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#133786 = DIRECTION('',(0.E+000,1.)); -#133787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133788 = ORIENTED_EDGE('',*,*,#133789,.T.); -#133789 = EDGE_CURVE('',#133744,#133693,#133790,.T.); -#133790 = SURFACE_CURVE('',#133791,(#133795,#133801),.PCURVE_S1.); -#133791 = LINE('',#133792,#133793); -#133792 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#136147 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#136148 = CARTESIAN_POINT('',(3.166141578807,-2.15)); +#136149 = CARTESIAN_POINT('',(3.215239429242,-2.15)); +#136150 = CARTESIAN_POINT('',(3.288886204895,-2.15)); +#136151 = CARTESIAN_POINT('',(3.362532980548,-2.15)); +#136152 = CARTESIAN_POINT('',(3.4361797562,-2.15)); +#136153 = CARTESIAN_POINT('',(3.509826531853,-2.15)); +#136154 = CARTESIAN_POINT('',(3.583473307505,-2.15)); +#136155 = CARTESIAN_POINT('',(3.657120083158,-2.15)); +#136156 = CARTESIAN_POINT('',(3.730766858811,-2.15)); +#136157 = CARTESIAN_POINT('',(3.804413634463,-2.15)); +#136158 = CARTESIAN_POINT('',(3.878060410116,-2.15)); +#136159 = CARTESIAN_POINT('',(3.951707185768,-2.15)); +#136160 = CARTESIAN_POINT('',(4.025353961421,-2.15)); +#136161 = CARTESIAN_POINT('',(4.099000737074,-2.15)); +#136162 = CARTESIAN_POINT('',(4.172647512726,-2.15)); +#136163 = CARTESIAN_POINT('',(4.246294288379,-2.15)); +#136164 = CARTESIAN_POINT('',(4.319941064031,-2.15)); +#136165 = CARTESIAN_POINT('',(4.393587839684,-2.15)); +#136166 = CARTESIAN_POINT('',(4.467234615337,-2.15)); +#136167 = CARTESIAN_POINT('',(4.540881390989,-2.15)); +#136168 = CARTESIAN_POINT('',(4.614528166642,-2.15)); +#136169 = CARTESIAN_POINT('',(4.688174942294,-2.15)); +#136170 = CARTESIAN_POINT('',(4.737272792729,-2.15)); +#136171 = CARTESIAN_POINT('',(4.761821717947,-2.15)); +#136172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136173 = PCURVE('',#94960,#136174); +#136174 = DEFINITIONAL_REPRESENTATION('',(#136175),#136179); +#136175 = CIRCLE('',#136176,0.308574064194); +#136176 = AXIS2_PLACEMENT_2D('',#136177,#136178); +#136177 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#136178 = DIRECTION('',(0.E+000,1.)); +#136179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136180 = ORIENTED_EDGE('',*,*,#136181,.T.); +#136181 = EDGE_CURVE('',#136136,#136085,#136182,.T.); +#136182 = SURFACE_CURVE('',#136183,(#136187,#136193),.PCURVE_S1.); +#136183 = LINE('',#136184,#136185); +#136184 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#133793 = VECTOR('',#133794,1.); -#133794 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133795 = PCURVE('',#133578,#133796); -#133796 = DEFINITIONAL_REPRESENTATION('',(#133797),#133800); -#133797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133798,#133799), +#136185 = VECTOR('',#136186,1.); +#136186 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136187 = PCURVE('',#135970,#136188); +#136188 = DEFINITIONAL_REPRESENTATION('',(#136189),#136192); +#136189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136190,#136191), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#133798 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#133799 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#133800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136190 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#136191 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#136192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133801 = PCURVE('',#133802,#133807); -#133802 = PLANE('',#133803); -#133803 = AXIS2_PLACEMENT_3D('',#133804,#133805,#133806); -#133804 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#136193 = PCURVE('',#136194,#136199); +#136194 = PLANE('',#136195); +#136195 = AXIS2_PLACEMENT_3D('',#136196,#136197,#136198); +#136196 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#133805 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133806 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133807 = DEFINITIONAL_REPRESENTATION('',(#133808),#133812); -#133808 = LINE('',#133809,#133810); -#133809 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#133810 = VECTOR('',#133811,1.); -#133811 = DIRECTION('',(-1.,0.E+000)); -#133812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133813 = ADVANCED_FACE('',(#133814),#133802,.T.); -#133814 = FACE_BOUND('',#133815,.T.); -#133815 = EDGE_LOOP('',(#133816,#133845,#133866,#133867)); -#133816 = ORIENTED_EDGE('',*,*,#133817,.T.); -#133817 = EDGE_CURVE('',#133818,#133820,#133822,.T.); -#133818 = VERTEX_POINT('',#133819); -#133819 = CARTESIAN_POINT('',(10.419594812019,2.15,0.530776333563)); -#133820 = VERTEX_POINT('',#133821); -#133821 = CARTESIAN_POINT('',(10.419594812019,2.35,0.530776333563)); -#133822 = SURFACE_CURVE('',#133823,(#133827,#133834),.PCURVE_S1.); -#133823 = LINE('',#133824,#133825); -#133824 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#136197 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136198 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136199 = DEFINITIONAL_REPRESENTATION('',(#136200),#136204); +#136200 = LINE('',#136201,#136202); +#136201 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#136202 = VECTOR('',#136203,1.); +#136203 = DIRECTION('',(-1.,0.E+000)); +#136204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136205 = ADVANCED_FACE('',(#136206),#136194,.T.); +#136206 = FACE_BOUND('',#136207,.T.); +#136207 = EDGE_LOOP('',(#136208,#136237,#136258,#136259)); +#136208 = ORIENTED_EDGE('',*,*,#136209,.T.); +#136209 = EDGE_CURVE('',#136210,#136212,#136214,.T.); +#136210 = VERTEX_POINT('',#136211); +#136211 = CARTESIAN_POINT('',(10.419594812019,2.15,0.530776333563)); +#136212 = VERTEX_POINT('',#136213); +#136213 = CARTESIAN_POINT('',(10.419594812019,2.35,0.530776333563)); +#136214 = SURFACE_CURVE('',#136215,(#136219,#136226),.PCURVE_S1.); +#136215 = LINE('',#136216,#136217); +#136216 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#133825 = VECTOR('',#133826,1.); -#133826 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133827 = PCURVE('',#133802,#133828); -#133828 = DEFINITIONAL_REPRESENTATION('',(#133829),#133833); -#133829 = LINE('',#133830,#133831); -#133830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133831 = VECTOR('',#133832,1.); -#133832 = DIRECTION('',(-1.,0.E+000)); -#133833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133834 = PCURVE('',#133835,#133840); -#133835 = CYLINDRICAL_SURFACE('',#133836,0.119270391569); -#133836 = AXIS2_PLACEMENT_3D('',#133837,#133838,#133839); -#133837 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#136217 = VECTOR('',#136218,1.); +#136218 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136219 = PCURVE('',#136194,#136220); +#136220 = DEFINITIONAL_REPRESENTATION('',(#136221),#136225); +#136221 = LINE('',#136222,#136223); +#136222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136223 = VECTOR('',#136224,1.); +#136224 = DIRECTION('',(-1.,0.E+000)); +#136225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136226 = PCURVE('',#136227,#136232); +#136227 = CYLINDRICAL_SURFACE('',#136228,0.119270391569); +#136228 = AXIS2_PLACEMENT_3D('',#136229,#136230,#136231); +#136229 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#133838 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133839 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133840 = DEFINITIONAL_REPRESENTATION('',(#133841),#133844); -#133841 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133842,#133843), +#136230 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136231 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136232 = DEFINITIONAL_REPRESENTATION('',(#136233),#136236); +#136233 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136234,#136235), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#133842 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#133843 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#133844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133845 = ORIENTED_EDGE('',*,*,#133846,.T.); -#133846 = EDGE_CURVE('',#133820,#133693,#133847,.T.); -#133847 = SURFACE_CURVE('',#133848,(#133852,#133859),.PCURVE_S1.); -#133848 = LINE('',#133849,#133850); -#133849 = CARTESIAN_POINT('',(10.419594812019,2.35,0.530776333563)); -#133850 = VECTOR('',#133851,1.); -#133851 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133852 = PCURVE('',#133802,#133853); -#133853 = DEFINITIONAL_REPRESENTATION('',(#133854),#133858); -#133854 = LINE('',#133855,#133856); -#133855 = CARTESIAN_POINT('',(-2.35,0.E+000)); -#133856 = VECTOR('',#133857,1.); -#133857 = DIRECTION('',(0.E+000,-1.)); -#133858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133859 = PCURVE('',#92512,#133860); -#133860 = DEFINITIONAL_REPRESENTATION('',(#133861),#133865); -#133861 = LINE('',#133862,#133863); -#133862 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#133863 = VECTOR('',#133864,1.); -#133864 = DIRECTION('',(-1.,0.E+000)); -#133865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133866 = ORIENTED_EDGE('',*,*,#133789,.F.); -#133867 = ORIENTED_EDGE('',*,*,#133868,.F.); -#133868 = EDGE_CURVE('',#133818,#133744,#133869,.T.); -#133869 = SURFACE_CURVE('',#133870,(#133874,#133881),.PCURVE_S1.); -#133870 = LINE('',#133871,#133872); -#133871 = CARTESIAN_POINT('',(10.419594812019,2.15,0.530776333563)); -#133872 = VECTOR('',#133873,1.); -#133873 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133874 = PCURVE('',#133802,#133875); -#133875 = DEFINITIONAL_REPRESENTATION('',(#133876),#133880); -#133876 = LINE('',#133877,#133878); -#133877 = CARTESIAN_POINT('',(-2.15,0.E+000)); -#133878 = VECTOR('',#133879,1.); -#133879 = DIRECTION('',(0.E+000,-1.)); -#133880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136234 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#136235 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#136236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136237 = ORIENTED_EDGE('',*,*,#136238,.T.); +#136238 = EDGE_CURVE('',#136212,#136085,#136239,.T.); +#136239 = SURFACE_CURVE('',#136240,(#136244,#136251),.PCURVE_S1.); +#136240 = LINE('',#136241,#136242); +#136241 = CARTESIAN_POINT('',(10.419594812019,2.35,0.530776333563)); +#136242 = VECTOR('',#136243,1.); +#136243 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#136244 = PCURVE('',#136194,#136245); +#136245 = DEFINITIONAL_REPRESENTATION('',(#136246),#136250); +#136246 = LINE('',#136247,#136248); +#136247 = CARTESIAN_POINT('',(-2.35,0.E+000)); +#136248 = VECTOR('',#136249,1.); +#136249 = DIRECTION('',(0.E+000,-1.)); +#136250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136251 = PCURVE('',#94904,#136252); +#136252 = DEFINITIONAL_REPRESENTATION('',(#136253),#136257); +#136253 = LINE('',#136254,#136255); +#136254 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#136255 = VECTOR('',#136256,1.); +#136256 = DIRECTION('',(-1.,0.E+000)); +#136257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#133881 = PCURVE('',#92568,#133882); -#133882 = DEFINITIONAL_REPRESENTATION('',(#133883),#133887); -#133883 = LINE('',#133884,#133885); -#133884 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#133885 = VECTOR('',#133886,1.); -#133886 = DIRECTION('',(1.,0.E+000)); -#133887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133888 = ADVANCED_FACE('',(#133889),#133651,.T.); -#133889 = FACE_BOUND('',#133890,.T.); -#133890 = EDGE_LOOP('',(#133891,#133920,#133941,#133942)); -#133891 = ORIENTED_EDGE('',*,*,#133892,.T.); -#133892 = EDGE_CURVE('',#133893,#133895,#133897,.T.); -#133893 = VERTEX_POINT('',#133894); -#133894 = CARTESIAN_POINT('',(10.51959417205,2.35,0.530776333563)); -#133895 = VERTEX_POINT('',#133896); -#133896 = CARTESIAN_POINT('',(10.51959417205,2.15,0.530776333563)); -#133897 = SURFACE_CURVE('',#133898,(#133902,#133909),.PCURVE_S1.); -#133898 = LINE('',#133899,#133900); -#133899 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#136258 = ORIENTED_EDGE('',*,*,#136181,.F.); +#136259 = ORIENTED_EDGE('',*,*,#136260,.F.); +#136260 = EDGE_CURVE('',#136210,#136136,#136261,.T.); +#136261 = SURFACE_CURVE('',#136262,(#136266,#136273),.PCURVE_S1.); +#136262 = LINE('',#136263,#136264); +#136263 = CARTESIAN_POINT('',(10.419594812019,2.15,0.530776333563)); +#136264 = VECTOR('',#136265,1.); +#136265 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#136266 = PCURVE('',#136194,#136267); +#136267 = DEFINITIONAL_REPRESENTATION('',(#136268),#136272); +#136268 = LINE('',#136269,#136270); +#136269 = CARTESIAN_POINT('',(-2.15,0.E+000)); +#136270 = VECTOR('',#136271,1.); +#136271 = DIRECTION('',(0.E+000,-1.)); +#136272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136273 = PCURVE('',#94960,#136274); +#136274 = DEFINITIONAL_REPRESENTATION('',(#136275),#136279); +#136275 = LINE('',#136276,#136277); +#136276 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#136277 = VECTOR('',#136278,1.); +#136278 = DIRECTION('',(1.,0.E+000)); +#136279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136280 = ADVANCED_FACE('',(#136281),#136043,.T.); +#136281 = FACE_BOUND('',#136282,.T.); +#136282 = EDGE_LOOP('',(#136283,#136312,#136333,#136334)); +#136283 = ORIENTED_EDGE('',*,*,#136284,.T.); +#136284 = EDGE_CURVE('',#136285,#136287,#136289,.T.); +#136285 = VERTEX_POINT('',#136286); +#136286 = CARTESIAN_POINT('',(10.51959417205,2.35,0.530776333563)); +#136287 = VERTEX_POINT('',#136288); +#136288 = CARTESIAN_POINT('',(10.51959417205,2.15,0.530776333563)); +#136289 = SURFACE_CURVE('',#136290,(#136294,#136301),.PCURVE_S1.); +#136290 = LINE('',#136291,#136292); +#136291 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#133900 = VECTOR('',#133901,1.); -#133901 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#133902 = PCURVE('',#133651,#133903); -#133903 = DEFINITIONAL_REPRESENTATION('',(#133904),#133908); -#133904 = LINE('',#133905,#133906); -#133905 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#133906 = VECTOR('',#133907,1.); -#133907 = DIRECTION('',(-1.,0.E+000)); -#133908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133909 = PCURVE('',#133910,#133915); -#133910 = CYLINDRICAL_SURFACE('',#133911,0.2192697516); -#133911 = AXIS2_PLACEMENT_3D('',#133912,#133913,#133914); -#133912 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#136292 = VECTOR('',#136293,1.); +#136293 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136294 = PCURVE('',#136043,#136295); +#136295 = DEFINITIONAL_REPRESENTATION('',(#136296),#136300); +#136296 = LINE('',#136297,#136298); +#136297 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136298 = VECTOR('',#136299,1.); +#136299 = DIRECTION('',(-1.,0.E+000)); +#136300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136301 = PCURVE('',#136302,#136307); +#136302 = CYLINDRICAL_SURFACE('',#136303,0.2192697516); +#136303 = AXIS2_PLACEMENT_3D('',#136304,#136305,#136306); +#136304 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#133913 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133914 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133915 = DEFINITIONAL_REPRESENTATION('',(#133916),#133919); -#133916 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#133917,#133918), +#136305 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136306 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136307 = DEFINITIONAL_REPRESENTATION('',(#136308),#136311); +#136308 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136309,#136310), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#133917 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#133918 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#133919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133920 = ORIENTED_EDGE('',*,*,#133921,.T.); -#133921 = EDGE_CURVE('',#133895,#133614,#133922,.T.); -#133922 = SURFACE_CURVE('',#133923,(#133927,#133934),.PCURVE_S1.); -#133923 = LINE('',#133924,#133925); -#133924 = CARTESIAN_POINT('',(10.51959417205,2.15,0.530776333563)); -#133925 = VECTOR('',#133926,1.); -#133926 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133927 = PCURVE('',#133651,#133928); -#133928 = DEFINITIONAL_REPRESENTATION('',(#133929),#133933); -#133929 = LINE('',#133930,#133931); -#133930 = CARTESIAN_POINT('',(2.15,0.E+000)); -#133931 = VECTOR('',#133932,1.); -#133932 = DIRECTION('',(0.E+000,-1.)); -#133933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133934 = PCURVE('',#92568,#133935); -#133935 = DEFINITIONAL_REPRESENTATION('',(#133936),#133940); -#133936 = LINE('',#133937,#133938); -#133937 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#133938 = VECTOR('',#133939,1.); -#133939 = DIRECTION('',(1.,0.E+000)); -#133940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133941 = ORIENTED_EDGE('',*,*,#133636,.F.); -#133942 = ORIENTED_EDGE('',*,*,#133943,.F.); -#133943 = EDGE_CURVE('',#133893,#133637,#133944,.T.); -#133944 = SURFACE_CURVE('',#133945,(#133949,#133956),.PCURVE_S1.); -#133945 = LINE('',#133946,#133947); -#133946 = CARTESIAN_POINT('',(10.51959417205,2.35,0.530776333563)); -#133947 = VECTOR('',#133948,1.); -#133948 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#133949 = PCURVE('',#133651,#133950); -#133950 = DEFINITIONAL_REPRESENTATION('',(#133951),#133955); -#133951 = LINE('',#133952,#133953); -#133952 = CARTESIAN_POINT('',(2.35,0.E+000)); -#133953 = VECTOR('',#133954,1.); -#133954 = DIRECTION('',(0.E+000,-1.)); -#133955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133956 = PCURVE('',#92512,#133957); -#133957 = DEFINITIONAL_REPRESENTATION('',(#133958),#133962); -#133958 = LINE('',#133959,#133960); -#133959 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#133960 = VECTOR('',#133961,1.); -#133961 = DIRECTION('',(-1.,0.E+000)); -#133962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#133963 = ADVANCED_FACE('',(#133964),#133910,.T.); -#133964 = FACE_BOUND('',#133965,.T.); -#133965 = EDGE_LOOP('',(#133966,#133967,#134013,#134035)); -#133966 = ORIENTED_EDGE('',*,*,#133892,.F.); -#133967 = ORIENTED_EDGE('',*,*,#133968,.F.); -#133968 = EDGE_CURVE('',#133969,#133893,#133971,.T.); -#133969 = VERTEX_POINT('',#133970); -#133970 = CARTESIAN_POINT('',(10.304819755875,2.35,0.75)); -#133971 = SURFACE_CURVE('',#133972,(#133977,#134006),.PCURVE_S1.); -#133972 = CIRCLE('',#133973,0.2192697516); -#133973 = AXIS2_PLACEMENT_3D('',#133974,#133975,#133976); -#133974 = CARTESIAN_POINT('',(10.30032442045,2.35,0.530776333563)); -#133975 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#133976 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#133977 = PCURVE('',#133910,#133978); -#133978 = DEFINITIONAL_REPRESENTATION('',(#133979),#134005); -#133979 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#133980,#133981,#133982, - #133983,#133984,#133985,#133986,#133987,#133988,#133989,#133990, - #133991,#133992,#133993,#133994,#133995,#133996,#133997,#133998, - #133999,#134000,#134001,#134002,#134003,#134004),.UNSPECIFIED.,.F., +#136309 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#136310 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#136311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136312 = ORIENTED_EDGE('',*,*,#136313,.T.); +#136313 = EDGE_CURVE('',#136287,#136006,#136314,.T.); +#136314 = SURFACE_CURVE('',#136315,(#136319,#136326),.PCURVE_S1.); +#136315 = LINE('',#136316,#136317); +#136316 = CARTESIAN_POINT('',(10.51959417205,2.15,0.530776333563)); +#136317 = VECTOR('',#136318,1.); +#136318 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#136319 = PCURVE('',#136043,#136320); +#136320 = DEFINITIONAL_REPRESENTATION('',(#136321),#136325); +#136321 = LINE('',#136322,#136323); +#136322 = CARTESIAN_POINT('',(2.15,0.E+000)); +#136323 = VECTOR('',#136324,1.); +#136324 = DIRECTION('',(0.E+000,-1.)); +#136325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136326 = PCURVE('',#94960,#136327); +#136327 = DEFINITIONAL_REPRESENTATION('',(#136328),#136332); +#136328 = LINE('',#136329,#136330); +#136329 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#136330 = VECTOR('',#136331,1.); +#136331 = DIRECTION('',(1.,0.E+000)); +#136332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136333 = ORIENTED_EDGE('',*,*,#136028,.F.); +#136334 = ORIENTED_EDGE('',*,*,#136335,.F.); +#136335 = EDGE_CURVE('',#136285,#136029,#136336,.T.); +#136336 = SURFACE_CURVE('',#136337,(#136341,#136348),.PCURVE_S1.); +#136337 = LINE('',#136338,#136339); +#136338 = CARTESIAN_POINT('',(10.51959417205,2.35,0.530776333563)); +#136339 = VECTOR('',#136340,1.); +#136340 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#136341 = PCURVE('',#136043,#136342); +#136342 = DEFINITIONAL_REPRESENTATION('',(#136343),#136347); +#136343 = LINE('',#136344,#136345); +#136344 = CARTESIAN_POINT('',(2.35,0.E+000)); +#136345 = VECTOR('',#136346,1.); +#136346 = DIRECTION('',(0.E+000,-1.)); +#136347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136348 = PCURVE('',#94904,#136349); +#136349 = DEFINITIONAL_REPRESENTATION('',(#136350),#136354); +#136350 = LINE('',#136351,#136352); +#136351 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#136352 = VECTOR('',#136353,1.); +#136353 = DIRECTION('',(-1.,0.E+000)); +#136354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136355 = ADVANCED_FACE('',(#136356),#136302,.T.); +#136356 = FACE_BOUND('',#136357,.T.); +#136357 = EDGE_LOOP('',(#136358,#136359,#136405,#136427)); +#136358 = ORIENTED_EDGE('',*,*,#136284,.F.); +#136359 = ORIENTED_EDGE('',*,*,#136360,.F.); +#136360 = EDGE_CURVE('',#136361,#136285,#136363,.T.); +#136361 = VERTEX_POINT('',#136362); +#136362 = CARTESIAN_POINT('',(10.304819755875,2.35,0.75)); +#136363 = SURFACE_CURVE('',#136364,(#136369,#136398),.PCURVE_S1.); +#136364 = CIRCLE('',#136365,0.2192697516); +#136365 = AXIS2_PLACEMENT_3D('',#136366,#136367,#136368); +#136366 = CARTESIAN_POINT('',(10.30032442045,2.35,0.530776333563)); +#136367 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136368 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136369 = PCURVE('',#136302,#136370); +#136370 = DEFINITIONAL_REPRESENTATION('',(#136371),#136397); +#136371 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#136372,#136373,#136374, + #136375,#136376,#136377,#136378,#136379,#136380,#136381,#136382, + #136383,#136384,#136385,#136386,#136387,#136388,#136389,#136390, + #136391,#136392,#136393,#136394,#136395,#136396),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -165102,84 +168104,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#133980 = CARTESIAN_POINT('',(1.591299156552,2.35)); -#133981 = CARTESIAN_POINT('',(1.614788451962,2.35)); -#133982 = CARTESIAN_POINT('',(1.661767042781,2.35)); -#133983 = CARTESIAN_POINT('',(1.73223492901,2.35)); -#133984 = CARTESIAN_POINT('',(1.802702815239,2.35)); -#133985 = CARTESIAN_POINT('',(1.873170701468,2.35)); -#133986 = CARTESIAN_POINT('',(1.943638587697,2.35)); -#133987 = CARTESIAN_POINT('',(2.014106473926,2.35)); -#133988 = CARTESIAN_POINT('',(2.084574360155,2.35)); -#133989 = CARTESIAN_POINT('',(2.155042246384,2.35)); -#133990 = CARTESIAN_POINT('',(2.225510132613,2.35)); -#133991 = CARTESIAN_POINT('',(2.295978018842,2.35)); -#133992 = CARTESIAN_POINT('',(2.366445905071,2.35)); -#133993 = CARTESIAN_POINT('',(2.4369137913,2.35)); -#133994 = CARTESIAN_POINT('',(2.507381677529,2.35)); -#133995 = CARTESIAN_POINT('',(2.577849563758,2.35)); -#133996 = CARTESIAN_POINT('',(2.648317449987,2.35)); -#133997 = CARTESIAN_POINT('',(2.718785336216,2.35)); -#133998 = CARTESIAN_POINT('',(2.789253222445,2.35)); -#133999 = CARTESIAN_POINT('',(2.859721108674,2.35)); -#134000 = CARTESIAN_POINT('',(2.930188994903,2.35)); -#134001 = CARTESIAN_POINT('',(3.000656881132,2.35)); -#134002 = CARTESIAN_POINT('',(3.071124767361,2.35)); -#134003 = CARTESIAN_POINT('',(3.11810335818,2.35)); -#134004 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#134005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134006 = PCURVE('',#92512,#134007); -#134007 = DEFINITIONAL_REPRESENTATION('',(#134008),#134012); -#134008 = CIRCLE('',#134009,0.2192697516); -#134009 = AXIS2_PLACEMENT_2D('',#134010,#134011); -#134010 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#134011 = DIRECTION('',(0.E+000,-1.)); -#134012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134013 = ORIENTED_EDGE('',*,*,#134014,.F.); -#134014 = EDGE_CURVE('',#134015,#133969,#134017,.T.); -#134015 = VERTEX_POINT('',#134016); -#134016 = CARTESIAN_POINT('',(10.304819755875,2.15,0.75)); -#134017 = SURFACE_CURVE('',#134018,(#134022,#134028),.PCURVE_S1.); -#134018 = LINE('',#134019,#134020); -#134019 = CARTESIAN_POINT('',(10.304819755875,2.35,0.75)); -#134020 = VECTOR('',#134021,1.); -#134021 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134022 = PCURVE('',#133910,#134023); -#134023 = DEFINITIONAL_REPRESENTATION('',(#134024),#134027); -#134024 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134025,#134026), +#136372 = CARTESIAN_POINT('',(1.591299156552,2.35)); +#136373 = CARTESIAN_POINT('',(1.614788451962,2.35)); +#136374 = CARTESIAN_POINT('',(1.661767042781,2.35)); +#136375 = CARTESIAN_POINT('',(1.73223492901,2.35)); +#136376 = CARTESIAN_POINT('',(1.802702815239,2.35)); +#136377 = CARTESIAN_POINT('',(1.873170701468,2.35)); +#136378 = CARTESIAN_POINT('',(1.943638587697,2.35)); +#136379 = CARTESIAN_POINT('',(2.014106473926,2.35)); +#136380 = CARTESIAN_POINT('',(2.084574360155,2.35)); +#136381 = CARTESIAN_POINT('',(2.155042246384,2.35)); +#136382 = CARTESIAN_POINT('',(2.225510132613,2.35)); +#136383 = CARTESIAN_POINT('',(2.295978018842,2.35)); +#136384 = CARTESIAN_POINT('',(2.366445905071,2.35)); +#136385 = CARTESIAN_POINT('',(2.4369137913,2.35)); +#136386 = CARTESIAN_POINT('',(2.507381677529,2.35)); +#136387 = CARTESIAN_POINT('',(2.577849563758,2.35)); +#136388 = CARTESIAN_POINT('',(2.648317449987,2.35)); +#136389 = CARTESIAN_POINT('',(2.718785336216,2.35)); +#136390 = CARTESIAN_POINT('',(2.789253222445,2.35)); +#136391 = CARTESIAN_POINT('',(2.859721108674,2.35)); +#136392 = CARTESIAN_POINT('',(2.930188994903,2.35)); +#136393 = CARTESIAN_POINT('',(3.000656881132,2.35)); +#136394 = CARTESIAN_POINT('',(3.071124767361,2.35)); +#136395 = CARTESIAN_POINT('',(3.11810335818,2.35)); +#136396 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#136397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136398 = PCURVE('',#94904,#136399); +#136399 = DEFINITIONAL_REPRESENTATION('',(#136400),#136404); +#136400 = CIRCLE('',#136401,0.2192697516); +#136401 = AXIS2_PLACEMENT_2D('',#136402,#136403); +#136402 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#136403 = DIRECTION('',(0.E+000,-1.)); +#136404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136405 = ORIENTED_EDGE('',*,*,#136406,.F.); +#136406 = EDGE_CURVE('',#136407,#136361,#136409,.T.); +#136407 = VERTEX_POINT('',#136408); +#136408 = CARTESIAN_POINT('',(10.304819755875,2.15,0.75)); +#136409 = SURFACE_CURVE('',#136410,(#136414,#136420),.PCURVE_S1.); +#136410 = LINE('',#136411,#136412); +#136411 = CARTESIAN_POINT('',(10.304819755875,2.35,0.75)); +#136412 = VECTOR('',#136413,1.); +#136413 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136414 = PCURVE('',#136302,#136415); +#136415 = DEFINITIONAL_REPRESENTATION('',(#136416),#136419); +#136416 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136417,#136418), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#134025 = CARTESIAN_POINT('',(1.591299156552,2.15)); -#134026 = CARTESIAN_POINT('',(1.591299156552,2.35)); -#134027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134028 = PCURVE('',#92594,#134029); -#134029 = DEFINITIONAL_REPRESENTATION('',(#134030),#134034); -#134030 = LINE('',#134031,#134032); -#134031 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#134032 = VECTOR('',#134033,1.); -#134033 = DIRECTION('',(4.440892098501E-016,1.)); -#134034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134035 = ORIENTED_EDGE('',*,*,#134036,.T.); -#134036 = EDGE_CURVE('',#134015,#133895,#134037,.T.); -#134037 = SURFACE_CURVE('',#134038,(#134043,#134072),.PCURVE_S1.); -#134038 = CIRCLE('',#134039,0.2192697516); -#134039 = AXIS2_PLACEMENT_3D('',#134040,#134041,#134042); -#134040 = CARTESIAN_POINT('',(10.30032442045,2.15,0.530776333563)); -#134041 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134042 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134043 = PCURVE('',#133910,#134044); -#134044 = DEFINITIONAL_REPRESENTATION('',(#134045),#134071); -#134045 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134046,#134047,#134048, - #134049,#134050,#134051,#134052,#134053,#134054,#134055,#134056, - #134057,#134058,#134059,#134060,#134061,#134062,#134063,#134064, - #134065,#134066,#134067,#134068,#134069,#134070),.UNSPECIFIED.,.F., +#136417 = CARTESIAN_POINT('',(1.591299156552,2.15)); +#136418 = CARTESIAN_POINT('',(1.591299156552,2.35)); +#136419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136420 = PCURVE('',#94986,#136421); +#136421 = DEFINITIONAL_REPRESENTATION('',(#136422),#136426); +#136422 = LINE('',#136423,#136424); +#136423 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#136424 = VECTOR('',#136425,1.); +#136425 = DIRECTION('',(4.440892098501E-016,1.)); +#136426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136427 = ORIENTED_EDGE('',*,*,#136428,.T.); +#136428 = EDGE_CURVE('',#136407,#136287,#136429,.T.); +#136429 = SURFACE_CURVE('',#136430,(#136435,#136464),.PCURVE_S1.); +#136430 = CIRCLE('',#136431,0.2192697516); +#136431 = AXIS2_PLACEMENT_3D('',#136432,#136433,#136434); +#136432 = CARTESIAN_POINT('',(10.30032442045,2.15,0.530776333563)); +#136433 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136434 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136435 = PCURVE('',#136302,#136436); +#136436 = DEFINITIONAL_REPRESENTATION('',(#136437),#136463); +#136437 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#136438,#136439,#136440, + #136441,#136442,#136443,#136444,#136445,#136446,#136447,#136448, + #136449,#136450,#136451,#136452,#136453,#136454,#136455,#136456, + #136457,#136458,#136459,#136460,#136461,#136462),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -165187,728 +168189,728 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#134046 = CARTESIAN_POINT('',(1.591299156552,2.15)); -#134047 = CARTESIAN_POINT('',(1.614788451962,2.15)); -#134048 = CARTESIAN_POINT('',(1.661767042781,2.15)); -#134049 = CARTESIAN_POINT('',(1.73223492901,2.15)); -#134050 = CARTESIAN_POINT('',(1.802702815239,2.15)); -#134051 = CARTESIAN_POINT('',(1.873170701468,2.15)); -#134052 = CARTESIAN_POINT('',(1.943638587697,2.15)); -#134053 = CARTESIAN_POINT('',(2.014106473926,2.15)); -#134054 = CARTESIAN_POINT('',(2.084574360155,2.15)); -#134055 = CARTESIAN_POINT('',(2.155042246384,2.15)); -#134056 = CARTESIAN_POINT('',(2.225510132613,2.15)); -#134057 = CARTESIAN_POINT('',(2.295978018842,2.15)); -#134058 = CARTESIAN_POINT('',(2.366445905071,2.15)); -#134059 = CARTESIAN_POINT('',(2.4369137913,2.15)); -#134060 = CARTESIAN_POINT('',(2.507381677529,2.15)); -#134061 = CARTESIAN_POINT('',(2.577849563758,2.15)); -#134062 = CARTESIAN_POINT('',(2.648317449987,2.15)); -#134063 = CARTESIAN_POINT('',(2.718785336216,2.15)); -#134064 = CARTESIAN_POINT('',(2.789253222445,2.15)); -#134065 = CARTESIAN_POINT('',(2.859721108674,2.15)); -#134066 = CARTESIAN_POINT('',(2.930188994903,2.15)); -#134067 = CARTESIAN_POINT('',(3.000656881132,2.15)); -#134068 = CARTESIAN_POINT('',(3.071124767361,2.15)); -#134069 = CARTESIAN_POINT('',(3.11810335818,2.15)); -#134070 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#134071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134072 = PCURVE('',#92568,#134073); -#134073 = DEFINITIONAL_REPRESENTATION('',(#134074),#134082); -#134074 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134075,#134076,#134077, - #134078,#134079,#134080,#134081),.UNSPECIFIED.,.T.,.F.) +#136438 = CARTESIAN_POINT('',(1.591299156552,2.15)); +#136439 = CARTESIAN_POINT('',(1.614788451962,2.15)); +#136440 = CARTESIAN_POINT('',(1.661767042781,2.15)); +#136441 = CARTESIAN_POINT('',(1.73223492901,2.15)); +#136442 = CARTESIAN_POINT('',(1.802702815239,2.15)); +#136443 = CARTESIAN_POINT('',(1.873170701468,2.15)); +#136444 = CARTESIAN_POINT('',(1.943638587697,2.15)); +#136445 = CARTESIAN_POINT('',(2.014106473926,2.15)); +#136446 = CARTESIAN_POINT('',(2.084574360155,2.15)); +#136447 = CARTESIAN_POINT('',(2.155042246384,2.15)); +#136448 = CARTESIAN_POINT('',(2.225510132613,2.15)); +#136449 = CARTESIAN_POINT('',(2.295978018842,2.15)); +#136450 = CARTESIAN_POINT('',(2.366445905071,2.15)); +#136451 = CARTESIAN_POINT('',(2.4369137913,2.15)); +#136452 = CARTESIAN_POINT('',(2.507381677529,2.15)); +#136453 = CARTESIAN_POINT('',(2.577849563758,2.15)); +#136454 = CARTESIAN_POINT('',(2.648317449987,2.15)); +#136455 = CARTESIAN_POINT('',(2.718785336216,2.15)); +#136456 = CARTESIAN_POINT('',(2.789253222445,2.15)); +#136457 = CARTESIAN_POINT('',(2.859721108674,2.15)); +#136458 = CARTESIAN_POINT('',(2.930188994903,2.15)); +#136459 = CARTESIAN_POINT('',(3.000656881132,2.15)); +#136460 = CARTESIAN_POINT('',(3.071124767361,2.15)); +#136461 = CARTESIAN_POINT('',(3.11810335818,2.15)); +#136462 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#136463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136464 = PCURVE('',#94960,#136465); +#136465 = DEFINITIONAL_REPRESENTATION('',(#136466),#136474); +#136466 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136467,#136468,#136469, + #136470,#136471,#136472,#136473),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#134075 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#134076 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#134077 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#134078 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#134079 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#134080 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#134081 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#134082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134083 = ADVANCED_FACE('',(#134084),#133835,.F.); -#134084 = FACE_BOUND('',#134085,.F.); -#134085 = EDGE_LOOP('',(#134086,#134087,#134110,#134132)); -#134086 = ORIENTED_EDGE('',*,*,#133817,.T.); -#134087 = ORIENTED_EDGE('',*,*,#134088,.F.); -#134088 = EDGE_CURVE('',#134089,#133820,#134091,.T.); -#134089 = VERTEX_POINT('',#134090); -#134090 = CARTESIAN_POINT('',(10.303662633502,2.35,0.65)); -#134091 = SURFACE_CURVE('',#134092,(#134097,#134103),.PCURVE_S1.); -#134092 = CIRCLE('',#134093,0.119270391569); -#134093 = AXIS2_PLACEMENT_3D('',#134094,#134095,#134096); -#134094 = CARTESIAN_POINT('',(10.30032442045,2.35,0.530776333563)); -#134095 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134096 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134097 = PCURVE('',#133835,#134098); -#134098 = DEFINITIONAL_REPRESENTATION('',(#134099),#134102); -#134099 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134100,#134101), +#136467 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#136468 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#136469 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#136470 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#136471 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#136472 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#136473 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#136474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136475 = ADVANCED_FACE('',(#136476),#136227,.F.); +#136476 = FACE_BOUND('',#136477,.F.); +#136477 = EDGE_LOOP('',(#136478,#136479,#136502,#136524)); +#136478 = ORIENTED_EDGE('',*,*,#136209,.T.); +#136479 = ORIENTED_EDGE('',*,*,#136480,.F.); +#136480 = EDGE_CURVE('',#136481,#136212,#136483,.T.); +#136481 = VERTEX_POINT('',#136482); +#136482 = CARTESIAN_POINT('',(10.303662633502,2.35,0.65)); +#136483 = SURFACE_CURVE('',#136484,(#136489,#136495),.PCURVE_S1.); +#136484 = CIRCLE('',#136485,0.119270391569); +#136485 = AXIS2_PLACEMENT_3D('',#136486,#136487,#136488); +#136486 = CARTESIAN_POINT('',(10.30032442045,2.35,0.530776333563)); +#136487 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136488 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136489 = PCURVE('',#136227,#136490); +#136490 = DEFINITIONAL_REPRESENTATION('',(#136491),#136494); +#136491 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136492,#136493), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#134100 = CARTESIAN_POINT('',(1.598788597134,2.35)); -#134101 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#134102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134103 = PCURVE('',#92512,#134104); -#134104 = DEFINITIONAL_REPRESENTATION('',(#134105),#134109); -#134105 = CIRCLE('',#134106,0.119270391569); -#134106 = AXIS2_PLACEMENT_2D('',#134107,#134108); -#134107 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#134108 = DIRECTION('',(0.E+000,-1.)); -#134109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134110 = ORIENTED_EDGE('',*,*,#134111,.T.); -#134111 = EDGE_CURVE('',#134089,#134112,#134114,.T.); -#134112 = VERTEX_POINT('',#134113); -#134113 = CARTESIAN_POINT('',(10.303662633502,2.15,0.65)); -#134114 = SURFACE_CURVE('',#134115,(#134119,#134125),.PCURVE_S1.); -#134115 = LINE('',#134116,#134117); -#134116 = CARTESIAN_POINT('',(10.303662633502,2.35,0.65)); -#134117 = VECTOR('',#134118,1.); -#134118 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134119 = PCURVE('',#133835,#134120); -#134120 = DEFINITIONAL_REPRESENTATION('',(#134121),#134124); -#134121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134122,#134123), +#136492 = CARTESIAN_POINT('',(1.598788597134,2.35)); +#136493 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#136494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136495 = PCURVE('',#94904,#136496); +#136496 = DEFINITIONAL_REPRESENTATION('',(#136497),#136501); +#136497 = CIRCLE('',#136498,0.119270391569); +#136498 = AXIS2_PLACEMENT_2D('',#136499,#136500); +#136499 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#136500 = DIRECTION('',(0.E+000,-1.)); +#136501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136502 = ORIENTED_EDGE('',*,*,#136503,.T.); +#136503 = EDGE_CURVE('',#136481,#136504,#136506,.T.); +#136504 = VERTEX_POINT('',#136505); +#136505 = CARTESIAN_POINT('',(10.303662633502,2.15,0.65)); +#136506 = SURFACE_CURVE('',#136507,(#136511,#136517),.PCURVE_S1.); +#136507 = LINE('',#136508,#136509); +#136508 = CARTESIAN_POINT('',(10.303662633502,2.35,0.65)); +#136509 = VECTOR('',#136510,1.); +#136510 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136511 = PCURVE('',#136227,#136512); +#136512 = DEFINITIONAL_REPRESENTATION('',(#136513),#136516); +#136513 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136514,#136515), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#134122 = CARTESIAN_POINT('',(1.598788597134,2.35)); -#134123 = CARTESIAN_POINT('',(1.598788597134,2.15)); -#134124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134125 = PCURVE('',#92540,#134126); -#134126 = DEFINITIONAL_REPRESENTATION('',(#134127),#134131); -#134127 = LINE('',#134128,#134129); -#134128 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#134129 = VECTOR('',#134130,1.); -#134130 = DIRECTION('',(4.440892098501E-016,-1.)); -#134131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134132 = ORIENTED_EDGE('',*,*,#134133,.T.); -#134133 = EDGE_CURVE('',#134112,#133818,#134134,.T.); -#134134 = SURFACE_CURVE('',#134135,(#134140,#134146),.PCURVE_S1.); -#134135 = CIRCLE('',#134136,0.119270391569); -#134136 = AXIS2_PLACEMENT_3D('',#134137,#134138,#134139); -#134137 = CARTESIAN_POINT('',(10.30032442045,2.15,0.530776333563)); -#134138 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134139 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134140 = PCURVE('',#133835,#134141); -#134141 = DEFINITIONAL_REPRESENTATION('',(#134142),#134145); -#134142 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134143,#134144), +#136514 = CARTESIAN_POINT('',(1.598788597134,2.35)); +#136515 = CARTESIAN_POINT('',(1.598788597134,2.15)); +#136516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136517 = PCURVE('',#94932,#136518); +#136518 = DEFINITIONAL_REPRESENTATION('',(#136519),#136523); +#136519 = LINE('',#136520,#136521); +#136520 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#136521 = VECTOR('',#136522,1.); +#136522 = DIRECTION('',(4.440892098501E-016,-1.)); +#136523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136524 = ORIENTED_EDGE('',*,*,#136525,.T.); +#136525 = EDGE_CURVE('',#136504,#136210,#136526,.T.); +#136526 = SURFACE_CURVE('',#136527,(#136532,#136538),.PCURVE_S1.); +#136527 = CIRCLE('',#136528,0.119270391569); +#136528 = AXIS2_PLACEMENT_3D('',#136529,#136530,#136531); +#136529 = CARTESIAN_POINT('',(10.30032442045,2.15,0.530776333563)); +#136530 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136531 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#136532 = PCURVE('',#136227,#136533); +#136533 = DEFINITIONAL_REPRESENTATION('',(#136534),#136537); +#136534 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136535,#136536), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#134143 = CARTESIAN_POINT('',(1.598788597134,2.15)); -#134144 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#134145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136535 = CARTESIAN_POINT('',(1.598788597134,2.15)); +#136536 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#136537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134146 = PCURVE('',#92568,#134147); -#134147 = DEFINITIONAL_REPRESENTATION('',(#134148),#134156); -#134148 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134149,#134150,#134151, - #134152,#134153,#134154,#134155),.UNSPECIFIED.,.T.,.F.) +#136538 = PCURVE('',#94960,#136539); +#136539 = DEFINITIONAL_REPRESENTATION('',(#136540),#136548); +#136540 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136541,#136542,#136543, + #136544,#136545,#136546,#136547),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#134149 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#134150 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#134151 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#134152 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#134153 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#134154 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#134155 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#134156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134157 = ADVANCED_FACE('',(#134158),#92540,.T.); -#134158 = FACE_BOUND('',#134159,.T.); -#134159 = EDGE_LOOP('',(#134160,#134181,#134182,#134203)); -#134160 = ORIENTED_EDGE('',*,*,#134161,.F.); -#134161 = EDGE_CURVE('',#134089,#92497,#134162,.T.); -#134162 = SURFACE_CURVE('',#134163,(#134167,#134174),.PCURVE_S1.); -#134163 = LINE('',#134164,#134165); -#134164 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); -#134165 = VECTOR('',#134166,1.); -#134166 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#134167 = PCURVE('',#92540,#134168); -#134168 = DEFINITIONAL_REPRESENTATION('',(#134169),#134173); -#134169 = LINE('',#134170,#134171); -#134170 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134171 = VECTOR('',#134172,1.); -#134172 = DIRECTION('',(1.,-3.00059940766E-063)); -#134173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134174 = PCURVE('',#92512,#134175); -#134175 = DEFINITIONAL_REPRESENTATION('',(#134176),#134180); -#134176 = LINE('',#134177,#134178); -#134177 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134178 = VECTOR('',#134179,1.); -#134179 = DIRECTION('',(3.563627120235E-016,-1.)); -#134180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134181 = ORIENTED_EDGE('',*,*,#134111,.T.); -#134182 = ORIENTED_EDGE('',*,*,#134183,.T.); -#134183 = EDGE_CURVE('',#134112,#92525,#134184,.T.); -#134184 = SURFACE_CURVE('',#134185,(#134189,#134196),.PCURVE_S1.); -#134185 = LINE('',#134186,#134187); -#134186 = CARTESIAN_POINT('',(10.527847992439,2.15,0.65)); -#134187 = VECTOR('',#134188,1.); -#134188 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#134189 = PCURVE('',#92540,#134190); -#134190 = DEFINITIONAL_REPRESENTATION('',(#134191),#134195); -#134191 = LINE('',#134192,#134193); -#134192 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#134193 = VECTOR('',#134194,1.); -#134194 = DIRECTION('',(1.,-3.00059940766E-063)); -#134195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134196 = PCURVE('',#92568,#134197); -#134197 = DEFINITIONAL_REPRESENTATION('',(#134198),#134202); -#134198 = LINE('',#134199,#134200); -#134199 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134200 = VECTOR('',#134201,1.); -#134201 = DIRECTION('',(-3.563627120235E-016,-1.)); -#134202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134203 = ORIENTED_EDGE('',*,*,#92524,.F.); -#134204 = ADVANCED_FACE('',(#134205),#92568,.T.); -#134205 = FACE_BOUND('',#134206,.T.); -#134206 = EDGE_LOOP('',(#134207,#134208,#134209,#134210,#134211,#134212, - #134233,#134234,#134235,#134236,#134237,#134258)); -#134207 = ORIENTED_EDGE('',*,*,#134183,.F.); -#134208 = ORIENTED_EDGE('',*,*,#134133,.T.); -#134209 = ORIENTED_EDGE('',*,*,#133868,.T.); -#134210 = ORIENTED_EDGE('',*,*,#133743,.T.); -#134211 = ORIENTED_EDGE('',*,*,#133539,.T.); -#134212 = ORIENTED_EDGE('',*,*,#134213,.F.); -#134213 = EDGE_CURVE('',#133403,#133510,#134214,.T.); -#134214 = SURFACE_CURVE('',#134215,(#134219,#134226),.PCURVE_S1.); -#134215 = LINE('',#134216,#134217); -#134216 = CARTESIAN_POINT('',(11.,2.15,1.159810404338E-002)); -#134217 = VECTOR('',#134218,1.); -#134218 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#134219 = PCURVE('',#92568,#134220); -#134220 = DEFINITIONAL_REPRESENTATION('',(#134221),#134225); -#134221 = LINE('',#134222,#134223); -#134222 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#134223 = VECTOR('',#134224,1.); -#134224 = DIRECTION('',(1.,-2.101748079665E-016)); -#134225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134226 = PCURVE('',#133423,#134227); -#134227 = DEFINITIONAL_REPRESENTATION('',(#134228),#134232); -#134228 = LINE('',#134229,#134230); -#134229 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#134230 = VECTOR('',#134231,1.); -#134231 = DIRECTION('',(-1.194699204908E-017,-1.)); -#134232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134233 = ORIENTED_EDGE('',*,*,#133485,.F.); -#134234 = ORIENTED_EDGE('',*,*,#133613,.F.); -#134235 = ORIENTED_EDGE('',*,*,#133921,.F.); -#134236 = ORIENTED_EDGE('',*,*,#134036,.F.); -#134237 = ORIENTED_EDGE('',*,*,#134238,.T.); -#134238 = EDGE_CURVE('',#134015,#92553,#134239,.T.); -#134239 = SURFACE_CURVE('',#134240,(#134244,#134251),.PCURVE_S1.); -#134240 = LINE('',#134241,#134242); -#134241 = CARTESIAN_POINT('',(10.527847992439,2.15,0.75)); -#134242 = VECTOR('',#134243,1.); -#134243 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#134244 = PCURVE('',#92568,#134245); -#134245 = DEFINITIONAL_REPRESENTATION('',(#134246),#134250); -#134246 = LINE('',#134247,#134248); -#134247 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#134248 = VECTOR('',#134249,1.); -#134249 = DIRECTION('',(-3.563627120235E-016,-1.)); -#134250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134251 = PCURVE('',#92594,#134252); -#134252 = DEFINITIONAL_REPRESENTATION('',(#134253),#134257); -#134253 = LINE('',#134254,#134255); -#134254 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#134255 = VECTOR('',#134256,1.); -#134256 = DIRECTION('',(-1.,-3.00059940766E-063)); -#134257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134258 = ORIENTED_EDGE('',*,*,#92552,.F.); -#134259 = ADVANCED_FACE('',(#134260),#92594,.T.); -#134260 = FACE_BOUND('',#134261,.T.); -#134261 = EDGE_LOOP('',(#134262,#134263,#134264,#134285)); -#134262 = ORIENTED_EDGE('',*,*,#134238,.F.); -#134263 = ORIENTED_EDGE('',*,*,#134014,.T.); -#134264 = ORIENTED_EDGE('',*,*,#134265,.T.); -#134265 = EDGE_CURVE('',#133969,#92495,#134266,.T.); -#134266 = SURFACE_CURVE('',#134267,(#134271,#134278),.PCURVE_S1.); -#134267 = LINE('',#134268,#134269); -#134268 = CARTESIAN_POINT('',(10.527847992439,2.35,0.75)); -#134269 = VECTOR('',#134270,1.); -#134270 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#134271 = PCURVE('',#92594,#134272); -#134272 = DEFINITIONAL_REPRESENTATION('',(#134273),#134277); -#134273 = LINE('',#134274,#134275); -#134274 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134275 = VECTOR('',#134276,1.); -#134276 = DIRECTION('',(-1.,-3.00059940766E-063)); -#134277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134278 = PCURVE('',#92512,#134279); -#134279 = DEFINITIONAL_REPRESENTATION('',(#134280),#134284); -#134280 = LINE('',#134281,#134282); -#134281 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#134282 = VECTOR('',#134283,1.); -#134283 = DIRECTION('',(3.563627120235E-016,-1.)); -#134284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134285 = ORIENTED_EDGE('',*,*,#92580,.F.); -#134286 = ADVANCED_FACE('',(#134287),#92512,.T.); -#134287 = FACE_BOUND('',#134288,.T.); -#134288 = EDGE_LOOP('',(#134289,#134290,#134291,#134292,#134293,#134294, - #134315,#134316,#134317,#134318,#134319,#134320)); -#134289 = ORIENTED_EDGE('',*,*,#134265,.F.); -#134290 = ORIENTED_EDGE('',*,*,#133968,.T.); -#134291 = ORIENTED_EDGE('',*,*,#133943,.T.); -#134292 = ORIENTED_EDGE('',*,*,#133663,.T.); -#134293 = ORIENTED_EDGE('',*,*,#133435,.T.); -#134294 = ORIENTED_EDGE('',*,*,#134295,.F.); -#134295 = EDGE_CURVE('',#133512,#133401,#134296,.T.); -#134296 = SURFACE_CURVE('',#134297,(#134301,#134308),.PCURVE_S1.); -#134297 = LINE('',#134298,#134299); -#134298 = CARTESIAN_POINT('',(11.,2.35,1.159810404338E-002)); -#134299 = VECTOR('',#134300,1.); -#134300 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#134301 = PCURVE('',#92512,#134302); -#134302 = DEFINITIONAL_REPRESENTATION('',(#134303),#134307); -#134303 = LINE('',#134304,#134305); -#134304 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#134305 = VECTOR('',#134306,1.); -#134306 = DIRECTION('',(1.,2.101748079665E-016)); -#134307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134308 = PCURVE('',#133423,#134309); -#134309 = DEFINITIONAL_REPRESENTATION('',(#134310),#134314); -#134310 = LINE('',#134311,#134312); -#134311 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#134312 = VECTOR('',#134313,1.); -#134313 = DIRECTION('',(1.194699204908E-017,1.)); -#134314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134315 = ORIENTED_EDGE('',*,*,#133589,.F.); -#134316 = ORIENTED_EDGE('',*,*,#133692,.F.); -#134317 = ORIENTED_EDGE('',*,*,#133846,.F.); -#134318 = ORIENTED_EDGE('',*,*,#134088,.F.); -#134319 = ORIENTED_EDGE('',*,*,#134161,.T.); -#134320 = ORIENTED_EDGE('',*,*,#92494,.F.); -#134321 = ADVANCED_FACE('',(#134322),#133423,.T.); -#134322 = FACE_BOUND('',#134323,.T.); -#134323 = EDGE_LOOP('',(#134324,#134325,#134326,#134327)); -#134324 = ORIENTED_EDGE('',*,*,#134213,.T.); -#134325 = ORIENTED_EDGE('',*,*,#133509,.T.); -#134326 = ORIENTED_EDGE('',*,*,#134295,.T.); -#134327 = ORIENTED_EDGE('',*,*,#133400,.T.); -#134328 = ADVANCED_FACE('',(#134329),#134343,.F.); -#134329 = FACE_BOUND('',#134330,.T.); -#134330 = EDGE_LOOP('',(#134331,#134366,#134389,#134416)); -#134331 = ORIENTED_EDGE('',*,*,#134332,.F.); -#134332 = EDGE_CURVE('',#134333,#134335,#134337,.T.); -#134333 = VERTEX_POINT('',#134334); -#134334 = CARTESIAN_POINT('',(11.,1.85,-0.208196358798)); -#134335 = VERTEX_POINT('',#134336); -#134336 = CARTESIAN_POINT('',(11.,1.65,-0.208196358798)); -#134337 = SURFACE_CURVE('',#134338,(#134342,#134354),.PCURVE_S1.); -#134338 = LINE('',#134339,#134340); -#134339 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#134340 = VECTOR('',#134341,1.); -#134341 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134342 = PCURVE('',#134343,#134348); -#134343 = PLANE('',#134344); -#134344 = AXIS2_PLACEMENT_3D('',#134345,#134346,#134347); -#134345 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#136541 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#136542 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#136543 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#136544 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#136545 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#136546 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#136547 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#136548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136549 = ADVANCED_FACE('',(#136550),#94932,.T.); +#136550 = FACE_BOUND('',#136551,.T.); +#136551 = EDGE_LOOP('',(#136552,#136573,#136574,#136595)); +#136552 = ORIENTED_EDGE('',*,*,#136553,.F.); +#136553 = EDGE_CURVE('',#136481,#94889,#136554,.T.); +#136554 = SURFACE_CURVE('',#136555,(#136559,#136566),.PCURVE_S1.); +#136555 = LINE('',#136556,#136557); +#136556 = CARTESIAN_POINT('',(10.527847992439,2.35,0.65)); +#136557 = VECTOR('',#136558,1.); +#136558 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#136559 = PCURVE('',#94932,#136560); +#136560 = DEFINITIONAL_REPRESENTATION('',(#136561),#136565); +#136561 = LINE('',#136562,#136563); +#136562 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136563 = VECTOR('',#136564,1.); +#136564 = DIRECTION('',(1.,-3.00059940766E-063)); +#136565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136566 = PCURVE('',#94904,#136567); +#136567 = DEFINITIONAL_REPRESENTATION('',(#136568),#136572); +#136568 = LINE('',#136569,#136570); +#136569 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136570 = VECTOR('',#136571,1.); +#136571 = DIRECTION('',(3.563627120235E-016,-1.)); +#136572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136573 = ORIENTED_EDGE('',*,*,#136503,.T.); +#136574 = ORIENTED_EDGE('',*,*,#136575,.T.); +#136575 = EDGE_CURVE('',#136504,#94917,#136576,.T.); +#136576 = SURFACE_CURVE('',#136577,(#136581,#136588),.PCURVE_S1.); +#136577 = LINE('',#136578,#136579); +#136578 = CARTESIAN_POINT('',(10.527847992439,2.15,0.65)); +#136579 = VECTOR('',#136580,1.); +#136580 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#136581 = PCURVE('',#94932,#136582); +#136582 = DEFINITIONAL_REPRESENTATION('',(#136583),#136587); +#136583 = LINE('',#136584,#136585); +#136584 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#136585 = VECTOR('',#136586,1.); +#136586 = DIRECTION('',(1.,-3.00059940766E-063)); +#136587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136588 = PCURVE('',#94960,#136589); +#136589 = DEFINITIONAL_REPRESENTATION('',(#136590),#136594); +#136590 = LINE('',#136591,#136592); +#136591 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136592 = VECTOR('',#136593,1.); +#136593 = DIRECTION('',(-3.563627120235E-016,-1.)); +#136594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136595 = ORIENTED_EDGE('',*,*,#94916,.F.); +#136596 = ADVANCED_FACE('',(#136597),#94960,.T.); +#136597 = FACE_BOUND('',#136598,.T.); +#136598 = EDGE_LOOP('',(#136599,#136600,#136601,#136602,#136603,#136604, + #136625,#136626,#136627,#136628,#136629,#136650)); +#136599 = ORIENTED_EDGE('',*,*,#136575,.F.); +#136600 = ORIENTED_EDGE('',*,*,#136525,.T.); +#136601 = ORIENTED_EDGE('',*,*,#136260,.T.); +#136602 = ORIENTED_EDGE('',*,*,#136135,.T.); +#136603 = ORIENTED_EDGE('',*,*,#135931,.T.); +#136604 = ORIENTED_EDGE('',*,*,#136605,.F.); +#136605 = EDGE_CURVE('',#135795,#135902,#136606,.T.); +#136606 = SURFACE_CURVE('',#136607,(#136611,#136618),.PCURVE_S1.); +#136607 = LINE('',#136608,#136609); +#136608 = CARTESIAN_POINT('',(11.,2.15,1.159810404338E-002)); +#136609 = VECTOR('',#136610,1.); +#136610 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#136611 = PCURVE('',#94960,#136612); +#136612 = DEFINITIONAL_REPRESENTATION('',(#136613),#136617); +#136613 = LINE('',#136614,#136615); +#136614 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#136615 = VECTOR('',#136616,1.); +#136616 = DIRECTION('',(1.,-2.101748079665E-016)); +#136617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136618 = PCURVE('',#135815,#136619); +#136619 = DEFINITIONAL_REPRESENTATION('',(#136620),#136624); +#136620 = LINE('',#136621,#136622); +#136621 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#136622 = VECTOR('',#136623,1.); +#136623 = DIRECTION('',(-1.194699204908E-017,-1.)); +#136624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136625 = ORIENTED_EDGE('',*,*,#135877,.F.); +#136626 = ORIENTED_EDGE('',*,*,#136005,.F.); +#136627 = ORIENTED_EDGE('',*,*,#136313,.F.); +#136628 = ORIENTED_EDGE('',*,*,#136428,.F.); +#136629 = ORIENTED_EDGE('',*,*,#136630,.T.); +#136630 = EDGE_CURVE('',#136407,#94945,#136631,.T.); +#136631 = SURFACE_CURVE('',#136632,(#136636,#136643),.PCURVE_S1.); +#136632 = LINE('',#136633,#136634); +#136633 = CARTESIAN_POINT('',(10.527847992439,2.15,0.75)); +#136634 = VECTOR('',#136635,1.); +#136635 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#136636 = PCURVE('',#94960,#136637); +#136637 = DEFINITIONAL_REPRESENTATION('',(#136638),#136642); +#136638 = LINE('',#136639,#136640); +#136639 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#136640 = VECTOR('',#136641,1.); +#136641 = DIRECTION('',(-3.563627120235E-016,-1.)); +#136642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136643 = PCURVE('',#94986,#136644); +#136644 = DEFINITIONAL_REPRESENTATION('',(#136645),#136649); +#136645 = LINE('',#136646,#136647); +#136646 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#136647 = VECTOR('',#136648,1.); +#136648 = DIRECTION('',(-1.,-3.00059940766E-063)); +#136649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136650 = ORIENTED_EDGE('',*,*,#94944,.F.); +#136651 = ADVANCED_FACE('',(#136652),#94986,.T.); +#136652 = FACE_BOUND('',#136653,.T.); +#136653 = EDGE_LOOP('',(#136654,#136655,#136656,#136677)); +#136654 = ORIENTED_EDGE('',*,*,#136630,.F.); +#136655 = ORIENTED_EDGE('',*,*,#136406,.T.); +#136656 = ORIENTED_EDGE('',*,*,#136657,.T.); +#136657 = EDGE_CURVE('',#136361,#94887,#136658,.T.); +#136658 = SURFACE_CURVE('',#136659,(#136663,#136670),.PCURVE_S1.); +#136659 = LINE('',#136660,#136661); +#136660 = CARTESIAN_POINT('',(10.527847992439,2.35,0.75)); +#136661 = VECTOR('',#136662,1.); +#136662 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#136663 = PCURVE('',#94986,#136664); +#136664 = DEFINITIONAL_REPRESENTATION('',(#136665),#136669); +#136665 = LINE('',#136666,#136667); +#136666 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136667 = VECTOR('',#136668,1.); +#136668 = DIRECTION('',(-1.,-3.00059940766E-063)); +#136669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136670 = PCURVE('',#94904,#136671); +#136671 = DEFINITIONAL_REPRESENTATION('',(#136672),#136676); +#136672 = LINE('',#136673,#136674); +#136673 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#136674 = VECTOR('',#136675,1.); +#136675 = DIRECTION('',(3.563627120235E-016,-1.)); +#136676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136677 = ORIENTED_EDGE('',*,*,#94972,.F.); +#136678 = ADVANCED_FACE('',(#136679),#94904,.T.); +#136679 = FACE_BOUND('',#136680,.T.); +#136680 = EDGE_LOOP('',(#136681,#136682,#136683,#136684,#136685,#136686, + #136707,#136708,#136709,#136710,#136711,#136712)); +#136681 = ORIENTED_EDGE('',*,*,#136657,.F.); +#136682 = ORIENTED_EDGE('',*,*,#136360,.T.); +#136683 = ORIENTED_EDGE('',*,*,#136335,.T.); +#136684 = ORIENTED_EDGE('',*,*,#136055,.T.); +#136685 = ORIENTED_EDGE('',*,*,#135827,.T.); +#136686 = ORIENTED_EDGE('',*,*,#136687,.F.); +#136687 = EDGE_CURVE('',#135904,#135793,#136688,.T.); +#136688 = SURFACE_CURVE('',#136689,(#136693,#136700),.PCURVE_S1.); +#136689 = LINE('',#136690,#136691); +#136690 = CARTESIAN_POINT('',(11.,2.35,1.159810404338E-002)); +#136691 = VECTOR('',#136692,1.); +#136692 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#136693 = PCURVE('',#94904,#136694); +#136694 = DEFINITIONAL_REPRESENTATION('',(#136695),#136699); +#136695 = LINE('',#136696,#136697); +#136696 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#136697 = VECTOR('',#136698,1.); +#136698 = DIRECTION('',(1.,2.101748079665E-016)); +#136699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136700 = PCURVE('',#135815,#136701); +#136701 = DEFINITIONAL_REPRESENTATION('',(#136702),#136706); +#136702 = LINE('',#136703,#136704); +#136703 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#136704 = VECTOR('',#136705,1.); +#136705 = DIRECTION('',(1.194699204908E-017,1.)); +#136706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136707 = ORIENTED_EDGE('',*,*,#135981,.F.); +#136708 = ORIENTED_EDGE('',*,*,#136084,.F.); +#136709 = ORIENTED_EDGE('',*,*,#136238,.F.); +#136710 = ORIENTED_EDGE('',*,*,#136480,.F.); +#136711 = ORIENTED_EDGE('',*,*,#136553,.T.); +#136712 = ORIENTED_EDGE('',*,*,#94886,.F.); +#136713 = ADVANCED_FACE('',(#136714),#135815,.T.); +#136714 = FACE_BOUND('',#136715,.T.); +#136715 = EDGE_LOOP('',(#136716,#136717,#136718,#136719)); +#136716 = ORIENTED_EDGE('',*,*,#136605,.T.); +#136717 = ORIENTED_EDGE('',*,*,#135901,.T.); +#136718 = ORIENTED_EDGE('',*,*,#136687,.T.); +#136719 = ORIENTED_EDGE('',*,*,#135792,.T.); +#136720 = ADVANCED_FACE('',(#136721),#136735,.F.); +#136721 = FACE_BOUND('',#136722,.T.); +#136722 = EDGE_LOOP('',(#136723,#136758,#136781,#136808)); +#136723 = ORIENTED_EDGE('',*,*,#136724,.F.); +#136724 = EDGE_CURVE('',#136725,#136727,#136729,.T.); +#136725 = VERTEX_POINT('',#136726); +#136726 = CARTESIAN_POINT('',(11.,1.85,-0.208196358798)); +#136727 = VERTEX_POINT('',#136728); +#136728 = CARTESIAN_POINT('',(11.,1.65,-0.208196358798)); +#136729 = SURFACE_CURVE('',#136730,(#136734,#136746),.PCURVE_S1.); +#136730 = LINE('',#136731,#136732); +#136731 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#136732 = VECTOR('',#136733,1.); +#136733 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136734 = PCURVE('',#136735,#136740); +#136735 = PLANE('',#136736); +#136736 = AXIS2_PLACEMENT_3D('',#136737,#136738,#136739); +#136737 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#134346 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#134347 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#134348 = DEFINITIONAL_REPRESENTATION('',(#134349),#134353); -#134349 = LINE('',#134350,#134351); -#134350 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#134351 = VECTOR('',#134352,1.); -#134352 = DIRECTION('',(4.440892098501E-016,-1.)); -#134353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134354 = PCURVE('',#134355,#134360); -#134355 = PLANE('',#134356); -#134356 = AXIS2_PLACEMENT_3D('',#134357,#134358,#134359); -#134357 = CARTESIAN_POINT('',(11.,1.75,-0.258196742327)); -#134358 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#134359 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134360 = DEFINITIONAL_REPRESENTATION('',(#134361),#134365); -#134361 = LINE('',#134362,#134363); -#134362 = CARTESIAN_POINT('',(-1.75,5.00003835295E-002)); -#134363 = VECTOR('',#134364,1.); -#134364 = DIRECTION('',(-1.,0.E+000)); -#134365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134366 = ORIENTED_EDGE('',*,*,#134367,.F.); -#134367 = EDGE_CURVE('',#134368,#134333,#134370,.T.); -#134368 = VERTEX_POINT('',#134369); -#134369 = CARTESIAN_POINT('',(10.740726081328,1.85,-0.208196358798)); -#134370 = SURFACE_CURVE('',#134371,(#134375,#134382),.PCURVE_S1.); -#134371 = LINE('',#134372,#134373); -#134372 = CARTESIAN_POINT('',(10.740726081328,1.85,-0.208196358798)); -#134373 = VECTOR('',#134374,1.); -#134374 = DIRECTION('',(1.,0.E+000,0.E+000)); -#134375 = PCURVE('',#134343,#134376); -#134376 = DEFINITIONAL_REPRESENTATION('',(#134377),#134381); -#134377 = LINE('',#134378,#134379); -#134378 = CARTESIAN_POINT('',(-1.7763568394E-015,1.85)); -#134379 = VECTOR('',#134380,1.); -#134380 = DIRECTION('',(-1.,0.E+000)); -#134381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134382 = PCURVE('',#92398,#134383); -#134383 = DEFINITIONAL_REPRESENTATION('',(#134384),#134388); -#134384 = LINE('',#134385,#134386); -#134385 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#134386 = VECTOR('',#134387,1.); -#134387 = DIRECTION('',(0.E+000,1.)); -#134388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134389 = ORIENTED_EDGE('',*,*,#134390,.F.); -#134390 = EDGE_CURVE('',#134391,#134368,#134393,.T.); -#134391 = VERTEX_POINT('',#134392); -#134392 = CARTESIAN_POINT('',(10.740726081328,1.65,-0.208196358798)); -#134393 = SURFACE_CURVE('',#134394,(#134398,#134405),.PCURVE_S1.); -#134394 = LINE('',#134395,#134396); -#134395 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#136738 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#136739 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#136740 = DEFINITIONAL_REPRESENTATION('',(#136741),#136745); +#136741 = LINE('',#136742,#136743); +#136742 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#136743 = VECTOR('',#136744,1.); +#136744 = DIRECTION('',(4.440892098501E-016,-1.)); +#136745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136746 = PCURVE('',#136747,#136752); +#136747 = PLANE('',#136748); +#136748 = AXIS2_PLACEMENT_3D('',#136749,#136750,#136751); +#136749 = CARTESIAN_POINT('',(11.,1.75,-0.258196742327)); +#136750 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#136751 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136752 = DEFINITIONAL_REPRESENTATION('',(#136753),#136757); +#136753 = LINE('',#136754,#136755); +#136754 = CARTESIAN_POINT('',(-1.75,5.00003835295E-002)); +#136755 = VECTOR('',#136756,1.); +#136756 = DIRECTION('',(-1.,0.E+000)); +#136757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136758 = ORIENTED_EDGE('',*,*,#136759,.F.); +#136759 = EDGE_CURVE('',#136760,#136725,#136762,.T.); +#136760 = VERTEX_POINT('',#136761); +#136761 = CARTESIAN_POINT('',(10.740726081328,1.85,-0.208196358798)); +#136762 = SURFACE_CURVE('',#136763,(#136767,#136774),.PCURVE_S1.); +#136763 = LINE('',#136764,#136765); +#136764 = CARTESIAN_POINT('',(10.740726081328,1.85,-0.208196358798)); +#136765 = VECTOR('',#136766,1.); +#136766 = DIRECTION('',(1.,0.E+000,0.E+000)); +#136767 = PCURVE('',#136735,#136768); +#136768 = DEFINITIONAL_REPRESENTATION('',(#136769),#136773); +#136769 = LINE('',#136770,#136771); +#136770 = CARTESIAN_POINT('',(-1.7763568394E-015,1.85)); +#136771 = VECTOR('',#136772,1.); +#136772 = DIRECTION('',(-1.,0.E+000)); +#136773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136774 = PCURVE('',#94790,#136775); +#136775 = DEFINITIONAL_REPRESENTATION('',(#136776),#136780); +#136776 = LINE('',#136777,#136778); +#136777 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#136778 = VECTOR('',#136779,1.); +#136779 = DIRECTION('',(0.E+000,1.)); +#136780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136781 = ORIENTED_EDGE('',*,*,#136782,.F.); +#136782 = EDGE_CURVE('',#136783,#136760,#136785,.T.); +#136783 = VERTEX_POINT('',#136784); +#136784 = CARTESIAN_POINT('',(10.740726081328,1.65,-0.208196358798)); +#136785 = SURFACE_CURVE('',#136786,(#136790,#136797),.PCURVE_S1.); +#136786 = LINE('',#136787,#136788); +#136787 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#134396 = VECTOR('',#134397,1.); -#134397 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134398 = PCURVE('',#134343,#134399); -#134399 = DEFINITIONAL_REPRESENTATION('',(#134400),#134404); -#134400 = LINE('',#134401,#134402); -#134401 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134402 = VECTOR('',#134403,1.); -#134403 = DIRECTION('',(-4.440892098501E-016,1.)); -#134404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134405 = PCURVE('',#134406,#134411); -#134406 = CYLINDRICAL_SURFACE('',#134407,0.208574704164); -#134407 = AXIS2_PLACEMENT_3D('',#134408,#134409,#134410); -#134408 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#136788 = VECTOR('',#136789,1.); +#136789 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136790 = PCURVE('',#136735,#136791); +#136791 = DEFINITIONAL_REPRESENTATION('',(#136792),#136796); +#136792 = LINE('',#136793,#136794); +#136793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136794 = VECTOR('',#136795,1.); +#136795 = DIRECTION('',(-4.440892098501E-016,1.)); +#136796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136797 = PCURVE('',#136798,#136803); +#136798 = CYLINDRICAL_SURFACE('',#136799,0.208574704164); +#136799 = AXIS2_PLACEMENT_3D('',#136800,#136801,#136802); +#136800 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#134409 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134410 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134411 = DEFINITIONAL_REPRESENTATION('',(#134412),#134415); -#134412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134413,#134414), +#136801 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136802 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136803 = DEFINITIONAL_REPRESENTATION('',(#136804),#136807); +#136804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136805,#136806), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#134413 = CARTESIAN_POINT('',(4.772630242227,-1.65)); -#134414 = CARTESIAN_POINT('',(4.772630242227,-1.85)); -#134415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134416 = ORIENTED_EDGE('',*,*,#134417,.T.); -#134417 = EDGE_CURVE('',#134391,#134335,#134418,.T.); -#134418 = SURFACE_CURVE('',#134419,(#134423,#134430),.PCURVE_S1.); -#134419 = LINE('',#134420,#134421); -#134420 = CARTESIAN_POINT('',(10.740726081328,1.65,-0.208196358798)); -#134421 = VECTOR('',#134422,1.); -#134422 = DIRECTION('',(1.,0.E+000,0.E+000)); -#134423 = PCURVE('',#134343,#134424); -#134424 = DEFINITIONAL_REPRESENTATION('',(#134425),#134429); -#134425 = LINE('',#134426,#134427); -#134426 = CARTESIAN_POINT('',(-1.7763568394E-015,1.65)); -#134427 = VECTOR('',#134428,1.); -#134428 = DIRECTION('',(-1.,0.E+000)); -#134429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134430 = PCURVE('',#92454,#134431); -#134431 = DEFINITIONAL_REPRESENTATION('',(#134432),#134436); -#134432 = LINE('',#134433,#134434); -#134433 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#134434 = VECTOR('',#134435,1.); -#134435 = DIRECTION('',(0.E+000,1.)); -#134436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134437 = ADVANCED_FACE('',(#134438),#134452,.F.); -#134438 = FACE_BOUND('',#134439,.T.); -#134439 = EDGE_LOOP('',(#134440,#134470,#134493,#134520)); -#134440 = ORIENTED_EDGE('',*,*,#134441,.F.); -#134441 = EDGE_CURVE('',#134442,#134444,#134446,.T.); -#134442 = VERTEX_POINT('',#134443); -#134443 = CARTESIAN_POINT('',(11.,1.65,-0.308197125857)); -#134444 = VERTEX_POINT('',#134445); -#134445 = CARTESIAN_POINT('',(11.,1.85,-0.308197125857)); -#134446 = SURFACE_CURVE('',#134447,(#134451,#134463),.PCURVE_S1.); -#134447 = LINE('',#134448,#134449); -#134448 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#134449 = VECTOR('',#134450,1.); -#134450 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134451 = PCURVE('',#134452,#134457); -#134452 = PLANE('',#134453); -#134453 = AXIS2_PLACEMENT_3D('',#134454,#134455,#134456); -#134454 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#136805 = CARTESIAN_POINT('',(4.772630242227,-1.65)); +#136806 = CARTESIAN_POINT('',(4.772630242227,-1.85)); +#136807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136808 = ORIENTED_EDGE('',*,*,#136809,.T.); +#136809 = EDGE_CURVE('',#136783,#136727,#136810,.T.); +#136810 = SURFACE_CURVE('',#136811,(#136815,#136822),.PCURVE_S1.); +#136811 = LINE('',#136812,#136813); +#136812 = CARTESIAN_POINT('',(10.740726081328,1.65,-0.208196358798)); +#136813 = VECTOR('',#136814,1.); +#136814 = DIRECTION('',(1.,0.E+000,0.E+000)); +#136815 = PCURVE('',#136735,#136816); +#136816 = DEFINITIONAL_REPRESENTATION('',(#136817),#136821); +#136817 = LINE('',#136818,#136819); +#136818 = CARTESIAN_POINT('',(-1.7763568394E-015,1.65)); +#136819 = VECTOR('',#136820,1.); +#136820 = DIRECTION('',(-1.,0.E+000)); +#136821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136822 = PCURVE('',#94846,#136823); +#136823 = DEFINITIONAL_REPRESENTATION('',(#136824),#136828); +#136824 = LINE('',#136825,#136826); +#136825 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#136826 = VECTOR('',#136827,1.); +#136827 = DIRECTION('',(0.E+000,1.)); +#136828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136829 = ADVANCED_FACE('',(#136830),#136844,.F.); +#136830 = FACE_BOUND('',#136831,.T.); +#136831 = EDGE_LOOP('',(#136832,#136862,#136885,#136912)); +#136832 = ORIENTED_EDGE('',*,*,#136833,.F.); +#136833 = EDGE_CURVE('',#136834,#136836,#136838,.T.); +#136834 = VERTEX_POINT('',#136835); +#136835 = CARTESIAN_POINT('',(11.,1.65,-0.308197125857)); +#136836 = VERTEX_POINT('',#136837); +#136837 = CARTESIAN_POINT('',(11.,1.85,-0.308197125857)); +#136838 = SURFACE_CURVE('',#136839,(#136843,#136855),.PCURVE_S1.); +#136839 = LINE('',#136840,#136841); +#136840 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#136841 = VECTOR('',#136842,1.); +#136842 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136843 = PCURVE('',#136844,#136849); +#136844 = PLANE('',#136845); +#136845 = AXIS2_PLACEMENT_3D('',#136846,#136847,#136848); +#136846 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#134455 = DIRECTION('',(0.E+000,0.E+000,1.)); -#134456 = DIRECTION('',(1.,0.E+000,0.E+000)); -#134457 = DEFINITIONAL_REPRESENTATION('',(#134458),#134462); -#134458 = LINE('',#134459,#134460); -#134459 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#134460 = VECTOR('',#134461,1.); -#134461 = DIRECTION('',(4.440892098501E-016,1.)); -#134462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134463 = PCURVE('',#134355,#134464); -#134464 = DEFINITIONAL_REPRESENTATION('',(#134465),#134469); -#134465 = LINE('',#134466,#134467); -#134466 = CARTESIAN_POINT('',(-1.75,-5.000038352949E-002)); -#134467 = VECTOR('',#134468,1.); -#134468 = DIRECTION('',(1.,0.E+000)); -#134469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134470 = ORIENTED_EDGE('',*,*,#134471,.F.); -#134471 = EDGE_CURVE('',#134472,#134442,#134474,.T.); -#134472 = VERTEX_POINT('',#134473); -#134473 = CARTESIAN_POINT('',(10.74341632541,1.65,-0.308197125857)); -#134474 = SURFACE_CURVE('',#134475,(#134479,#134486),.PCURVE_S1.); -#134475 = LINE('',#134476,#134477); -#134476 = CARTESIAN_POINT('',(10.74341632541,1.65,-0.308197125857)); -#134477 = VECTOR('',#134478,1.); -#134478 = DIRECTION('',(1.,0.E+000,0.E+000)); -#134479 = PCURVE('',#134452,#134480); -#134480 = DEFINITIONAL_REPRESENTATION('',(#134481),#134485); -#134481 = LINE('',#134482,#134483); -#134482 = CARTESIAN_POINT('',(0.E+000,1.65)); -#134483 = VECTOR('',#134484,1.); -#134484 = DIRECTION('',(1.,0.E+000)); -#134485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134486 = PCURVE('',#92454,#134487); -#134487 = DEFINITIONAL_REPRESENTATION('',(#134488),#134492); -#134488 = LINE('',#134489,#134490); -#134489 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#134490 = VECTOR('',#134491,1.); -#134491 = DIRECTION('',(0.E+000,1.)); -#134492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134493 = ORIENTED_EDGE('',*,*,#134494,.F.); -#134494 = EDGE_CURVE('',#134495,#134472,#134497,.T.); -#134495 = VERTEX_POINT('',#134496); -#134496 = CARTESIAN_POINT('',(10.74341632541,1.85,-0.308197125857)); -#134497 = SURFACE_CURVE('',#134498,(#134502,#134509),.PCURVE_S1.); -#134498 = LINE('',#134499,#134500); -#134499 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#136847 = DIRECTION('',(0.E+000,0.E+000,1.)); +#136848 = DIRECTION('',(1.,0.E+000,0.E+000)); +#136849 = DEFINITIONAL_REPRESENTATION('',(#136850),#136854); +#136850 = LINE('',#136851,#136852); +#136851 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#136852 = VECTOR('',#136853,1.); +#136853 = DIRECTION('',(4.440892098501E-016,1.)); +#136854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136855 = PCURVE('',#136747,#136856); +#136856 = DEFINITIONAL_REPRESENTATION('',(#136857),#136861); +#136857 = LINE('',#136858,#136859); +#136858 = CARTESIAN_POINT('',(-1.75,-5.000038352949E-002)); +#136859 = VECTOR('',#136860,1.); +#136860 = DIRECTION('',(1.,0.E+000)); +#136861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136862 = ORIENTED_EDGE('',*,*,#136863,.F.); +#136863 = EDGE_CURVE('',#136864,#136834,#136866,.T.); +#136864 = VERTEX_POINT('',#136865); +#136865 = CARTESIAN_POINT('',(10.74341632541,1.65,-0.308197125857)); +#136866 = SURFACE_CURVE('',#136867,(#136871,#136878),.PCURVE_S1.); +#136867 = LINE('',#136868,#136869); +#136868 = CARTESIAN_POINT('',(10.74341632541,1.65,-0.308197125857)); +#136869 = VECTOR('',#136870,1.); +#136870 = DIRECTION('',(1.,0.E+000,0.E+000)); +#136871 = PCURVE('',#136844,#136872); +#136872 = DEFINITIONAL_REPRESENTATION('',(#136873),#136877); +#136873 = LINE('',#136874,#136875); +#136874 = CARTESIAN_POINT('',(0.E+000,1.65)); +#136875 = VECTOR('',#136876,1.); +#136876 = DIRECTION('',(1.,0.E+000)); +#136877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136878 = PCURVE('',#94846,#136879); +#136879 = DEFINITIONAL_REPRESENTATION('',(#136880),#136884); +#136880 = LINE('',#136881,#136882); +#136881 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#136882 = VECTOR('',#136883,1.); +#136883 = DIRECTION('',(0.E+000,1.)); +#136884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136885 = ORIENTED_EDGE('',*,*,#136886,.F.); +#136886 = EDGE_CURVE('',#136887,#136864,#136889,.T.); +#136887 = VERTEX_POINT('',#136888); +#136888 = CARTESIAN_POINT('',(10.74341632541,1.85,-0.308197125857)); +#136889 = SURFACE_CURVE('',#136890,(#136894,#136901),.PCURVE_S1.); +#136890 = LINE('',#136891,#136892); +#136891 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#134500 = VECTOR('',#134501,1.); -#134501 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134502 = PCURVE('',#134452,#134503); -#134503 = DEFINITIONAL_REPRESENTATION('',(#134504),#134508); -#134504 = LINE('',#134505,#134506); -#134505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134506 = VECTOR('',#134507,1.); -#134507 = DIRECTION('',(-4.440892098501E-016,-1.)); -#134508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134509 = PCURVE('',#134510,#134515); -#134510 = CYLINDRICAL_SURFACE('',#134511,0.308574064194); -#134511 = AXIS2_PLACEMENT_3D('',#134512,#134513,#134514); -#134512 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#136892 = VECTOR('',#136893,1.); +#136893 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136894 = PCURVE('',#136844,#136895); +#136895 = DEFINITIONAL_REPRESENTATION('',(#136896),#136900); +#136896 = LINE('',#136897,#136898); +#136897 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#136898 = VECTOR('',#136899,1.); +#136899 = DIRECTION('',(-4.440892098501E-016,-1.)); +#136900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136901 = PCURVE('',#136902,#136907); +#136902 = CYLINDRICAL_SURFACE('',#136903,0.308574064194); +#136903 = AXIS2_PLACEMENT_3D('',#136904,#136905,#136906); +#136904 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#134513 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134514 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134515 = DEFINITIONAL_REPRESENTATION('',(#134516),#134519); -#134516 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134517,#134518), +#136905 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136906 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136907 = DEFINITIONAL_REPRESENTATION('',(#136908),#136911); +#136908 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136909,#136910), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#134517 = CARTESIAN_POINT('',(4.761821717947,-1.85)); -#134518 = CARTESIAN_POINT('',(4.761821717947,-1.65)); -#134519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134520 = ORIENTED_EDGE('',*,*,#134521,.T.); -#134521 = EDGE_CURVE('',#134495,#134444,#134522,.T.); -#134522 = SURFACE_CURVE('',#134523,(#134527,#134534),.PCURVE_S1.); -#134523 = LINE('',#134524,#134525); -#134524 = CARTESIAN_POINT('',(10.74341632541,1.85,-0.308197125857)); -#134525 = VECTOR('',#134526,1.); -#134526 = DIRECTION('',(1.,0.E+000,0.E+000)); -#134527 = PCURVE('',#134452,#134528); -#134528 = DEFINITIONAL_REPRESENTATION('',(#134529),#134533); -#134529 = LINE('',#134530,#134531); -#134530 = CARTESIAN_POINT('',(0.E+000,1.85)); -#134531 = VECTOR('',#134532,1.); -#134532 = DIRECTION('',(1.,0.E+000)); -#134533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136909 = CARTESIAN_POINT('',(4.761821717947,-1.85)); +#136910 = CARTESIAN_POINT('',(4.761821717947,-1.65)); +#136911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134534 = PCURVE('',#92398,#134535); -#134535 = DEFINITIONAL_REPRESENTATION('',(#134536),#134540); -#134536 = LINE('',#134537,#134538); -#134537 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#134538 = VECTOR('',#134539,1.); -#134539 = DIRECTION('',(0.E+000,1.)); -#134540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134541 = ADVANCED_FACE('',(#134542),#134406,.F.); -#134542 = FACE_BOUND('',#134543,.F.); -#134543 = EDGE_LOOP('',(#134544,#134567,#134594,#134619)); -#134544 = ORIENTED_EDGE('',*,*,#134545,.F.); -#134545 = EDGE_CURVE('',#134546,#134391,#134548,.T.); -#134546 = VERTEX_POINT('',#134547); -#134547 = CARTESIAN_POINT('',(10.51959417205,1.65,0.E+000)); -#134548 = SURFACE_CURVE('',#134549,(#134554,#134560),.PCURVE_S1.); -#134549 = CIRCLE('',#134550,0.208574704164); -#134550 = AXIS2_PLACEMENT_3D('',#134551,#134552,#134553); -#134551 = CARTESIAN_POINT('',(10.728168876214,1.65,2.640924866458E-017) - ); -#134552 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134553 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134554 = PCURVE('',#134406,#134555); -#134555 = DEFINITIONAL_REPRESENTATION('',(#134556),#134559); -#134556 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134557,#134558), +#136912 = ORIENTED_EDGE('',*,*,#136913,.T.); +#136913 = EDGE_CURVE('',#136887,#136836,#136914,.T.); +#136914 = SURFACE_CURVE('',#136915,(#136919,#136926),.PCURVE_S1.); +#136915 = LINE('',#136916,#136917); +#136916 = CARTESIAN_POINT('',(10.74341632541,1.85,-0.308197125857)); +#136917 = VECTOR('',#136918,1.); +#136918 = DIRECTION('',(1.,0.E+000,0.E+000)); +#136919 = PCURVE('',#136844,#136920); +#136920 = DEFINITIONAL_REPRESENTATION('',(#136921),#136925); +#136921 = LINE('',#136922,#136923); +#136922 = CARTESIAN_POINT('',(0.E+000,1.85)); +#136923 = VECTOR('',#136924,1.); +#136924 = DIRECTION('',(1.,0.E+000)); +#136925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136926 = PCURVE('',#94790,#136927); +#136927 = DEFINITIONAL_REPRESENTATION('',(#136928),#136932); +#136928 = LINE('',#136929,#136930); +#136929 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#136930 = VECTOR('',#136931,1.); +#136931 = DIRECTION('',(0.E+000,1.)); +#136932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136933 = ADVANCED_FACE('',(#136934),#136798,.F.); +#136934 = FACE_BOUND('',#136935,.F.); +#136935 = EDGE_LOOP('',(#136936,#136959,#136986,#137011)); +#136936 = ORIENTED_EDGE('',*,*,#136937,.F.); +#136937 = EDGE_CURVE('',#136938,#136783,#136940,.T.); +#136938 = VERTEX_POINT('',#136939); +#136939 = CARTESIAN_POINT('',(10.51959417205,1.65,0.E+000)); +#136940 = SURFACE_CURVE('',#136941,(#136946,#136952),.PCURVE_S1.); +#136941 = CIRCLE('',#136942,0.208574704164); +#136942 = AXIS2_PLACEMENT_3D('',#136943,#136944,#136945); +#136943 = CARTESIAN_POINT('',(10.728168876214,1.65,2.640924866458E-017) + ); +#136944 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136945 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136946 = PCURVE('',#136798,#136947); +#136947 = DEFINITIONAL_REPRESENTATION('',(#136948),#136951); +#136948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136949,#136950), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#134557 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#134558 = CARTESIAN_POINT('',(4.772630242227,-1.65)); -#134559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136949 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#136950 = CARTESIAN_POINT('',(4.772630242227,-1.65)); +#136951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134560 = PCURVE('',#92454,#134561); -#134561 = DEFINITIONAL_REPRESENTATION('',(#134562),#134566); -#134562 = CIRCLE('',#134563,0.208574704164); -#134563 = AXIS2_PLACEMENT_2D('',#134564,#134565); -#134564 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#134565 = DIRECTION('',(0.E+000,1.)); -#134566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136952 = PCURVE('',#94846,#136953); +#136953 = DEFINITIONAL_REPRESENTATION('',(#136954),#136958); +#136954 = CIRCLE('',#136955,0.208574704164); +#136955 = AXIS2_PLACEMENT_2D('',#136956,#136957); +#136956 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#136957 = DIRECTION('',(0.E+000,1.)); +#136958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134567 = ORIENTED_EDGE('',*,*,#134568,.F.); -#134568 = EDGE_CURVE('',#134569,#134546,#134571,.T.); -#134569 = VERTEX_POINT('',#134570); -#134570 = CARTESIAN_POINT('',(10.51959417205,1.85,0.E+000)); -#134571 = SURFACE_CURVE('',#134572,(#134576,#134582),.PCURVE_S1.); -#134572 = LINE('',#134573,#134574); -#134573 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#136959 = ORIENTED_EDGE('',*,*,#136960,.F.); +#136960 = EDGE_CURVE('',#136961,#136938,#136963,.T.); +#136961 = VERTEX_POINT('',#136962); +#136962 = CARTESIAN_POINT('',(10.51959417205,1.85,0.E+000)); +#136963 = SURFACE_CURVE('',#136964,(#136968,#136974),.PCURVE_S1.); +#136964 = LINE('',#136965,#136966); +#136965 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#134574 = VECTOR('',#134575,1.); -#134575 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134576 = PCURVE('',#134406,#134577); -#134577 = DEFINITIONAL_REPRESENTATION('',(#134578),#134581); -#134578 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134579,#134580), +#136966 = VECTOR('',#136967,1.); +#136967 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136968 = PCURVE('',#136798,#136969); +#136969 = DEFINITIONAL_REPRESENTATION('',(#136970),#136973); +#136970 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136971,#136972), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#134579 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#134580 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#134581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136971 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#136972 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#136973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134582 = PCURVE('',#134583,#134588); -#134583 = PLANE('',#134584); -#134584 = AXIS2_PLACEMENT_3D('',#134585,#134586,#134587); -#134585 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#136974 = PCURVE('',#136975,#136980); +#136975 = PLANE('',#136976); +#136976 = AXIS2_PLACEMENT_3D('',#136977,#136978,#136979); +#136977 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#134586 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134587 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134588 = DEFINITIONAL_REPRESENTATION('',(#134589),#134593); -#134589 = LINE('',#134590,#134591); -#134590 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#134591 = VECTOR('',#134592,1.); -#134592 = DIRECTION('',(-1.,0.E+000)); -#134593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134594 = ORIENTED_EDGE('',*,*,#134595,.T.); -#134595 = EDGE_CURVE('',#134569,#134368,#134596,.T.); -#134596 = SURFACE_CURVE('',#134597,(#134602,#134608),.PCURVE_S1.); -#134597 = CIRCLE('',#134598,0.208574704164); -#134598 = AXIS2_PLACEMENT_3D('',#134599,#134600,#134601); -#134599 = CARTESIAN_POINT('',(10.728168876214,1.85,2.640924866458E-017) - ); -#134600 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134601 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134602 = PCURVE('',#134406,#134603); -#134603 = DEFINITIONAL_REPRESENTATION('',(#134604),#134607); -#134604 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134605,#134606), +#136978 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136979 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#136980 = DEFINITIONAL_REPRESENTATION('',(#136981),#136985); +#136981 = LINE('',#136982,#136983); +#136982 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#136983 = VECTOR('',#136984,1.); +#136984 = DIRECTION('',(-1.,0.E+000)); +#136985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#136986 = ORIENTED_EDGE('',*,*,#136987,.T.); +#136987 = EDGE_CURVE('',#136961,#136760,#136988,.T.); +#136988 = SURFACE_CURVE('',#136989,(#136994,#137000),.PCURVE_S1.); +#136989 = CIRCLE('',#136990,0.208574704164); +#136990 = AXIS2_PLACEMENT_3D('',#136991,#136992,#136993); +#136991 = CARTESIAN_POINT('',(10.728168876214,1.85,2.640924866458E-017) + ); +#136992 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#136993 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#136994 = PCURVE('',#136798,#136995); +#136995 = DEFINITIONAL_REPRESENTATION('',(#136996),#136999); +#136996 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136997,#136998), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#134605 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#134606 = CARTESIAN_POINT('',(4.772630242227,-1.85)); -#134607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#136997 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#136998 = CARTESIAN_POINT('',(4.772630242227,-1.85)); +#136999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134608 = PCURVE('',#92398,#134609); -#134609 = DEFINITIONAL_REPRESENTATION('',(#134610),#134618); -#134610 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134611,#134612,#134613, - #134614,#134615,#134616,#134617),.UNSPECIFIED.,.T.,.F.) +#137000 = PCURVE('',#94790,#137001); +#137001 = DEFINITIONAL_REPRESENTATION('',(#137002),#137010); +#137002 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137003,#137004,#137005, + #137006,#137007,#137008,#137009),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#134611 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#134612 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#134613 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#134614 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#134615 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#134616 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#134617 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#134618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134619 = ORIENTED_EDGE('',*,*,#134390,.F.); -#134620 = ADVANCED_FACE('',(#134621),#134510,.T.); -#134621 = FACE_BOUND('',#134622,.T.); -#134622 = EDGE_LOOP('',(#134623,#134673,#134674,#134720)); -#134623 = ORIENTED_EDGE('',*,*,#134624,.T.); -#134624 = EDGE_CURVE('',#134625,#134495,#134627,.T.); -#134625 = VERTEX_POINT('',#134626); -#134626 = CARTESIAN_POINT('',(10.419594812019,1.85,0.E+000)); -#134627 = SURFACE_CURVE('',#134628,(#134633,#134662),.PCURVE_S1.); -#134628 = CIRCLE('',#134629,0.308574064194); -#134629 = AXIS2_PLACEMENT_3D('',#134630,#134631,#134632); -#134630 = CARTESIAN_POINT('',(10.728168876214,1.85,2.640924866458E-017) - ); -#134631 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134632 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134633 = PCURVE('',#134510,#134634); -#134634 = DEFINITIONAL_REPRESENTATION('',(#134635),#134661); -#134635 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134636,#134637,#134638, - #134639,#134640,#134641,#134642,#134643,#134644,#134645,#134646, - #134647,#134648,#134649,#134650,#134651,#134652,#134653,#134654, - #134655,#134656,#134657,#134658,#134659,#134660),.UNSPECIFIED.,.F., +#137003 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#137004 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#137005 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#137006 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#137007 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#137008 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#137009 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#137010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137011 = ORIENTED_EDGE('',*,*,#136782,.F.); +#137012 = ADVANCED_FACE('',(#137013),#136902,.T.); +#137013 = FACE_BOUND('',#137014,.T.); +#137014 = EDGE_LOOP('',(#137015,#137065,#137066,#137112)); +#137015 = ORIENTED_EDGE('',*,*,#137016,.T.); +#137016 = EDGE_CURVE('',#137017,#136887,#137019,.T.); +#137017 = VERTEX_POINT('',#137018); +#137018 = CARTESIAN_POINT('',(10.419594812019,1.85,0.E+000)); +#137019 = SURFACE_CURVE('',#137020,(#137025,#137054),.PCURVE_S1.); +#137020 = CIRCLE('',#137021,0.308574064194); +#137021 = AXIS2_PLACEMENT_3D('',#137022,#137023,#137024); +#137022 = CARTESIAN_POINT('',(10.728168876214,1.85,2.640924866458E-017) + ); +#137023 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137024 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137025 = PCURVE('',#136902,#137026); +#137026 = DEFINITIONAL_REPRESENTATION('',(#137027),#137053); +#137027 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137028,#137029,#137030, + #137031,#137032,#137033,#137034,#137035,#137036,#137037,#137038, + #137039,#137040,#137041,#137042,#137043,#137044,#137045,#137046, + #137047,#137048,#137049,#137050,#137051,#137052),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -165916,71 +168918,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#134636 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#134637 = CARTESIAN_POINT('',(3.166141578807,-1.85)); -#134638 = CARTESIAN_POINT('',(3.215239429242,-1.85)); -#134639 = CARTESIAN_POINT('',(3.288886204895,-1.85)); -#134640 = CARTESIAN_POINT('',(3.362532980548,-1.85)); -#134641 = CARTESIAN_POINT('',(3.4361797562,-1.85)); -#134642 = CARTESIAN_POINT('',(3.509826531853,-1.85)); -#134643 = CARTESIAN_POINT('',(3.583473307505,-1.85)); -#134644 = CARTESIAN_POINT('',(3.657120083158,-1.85)); -#134645 = CARTESIAN_POINT('',(3.730766858811,-1.85)); -#134646 = CARTESIAN_POINT('',(3.804413634463,-1.85)); -#134647 = CARTESIAN_POINT('',(3.878060410116,-1.85)); -#134648 = CARTESIAN_POINT('',(3.951707185768,-1.85)); -#134649 = CARTESIAN_POINT('',(4.025353961421,-1.85)); -#134650 = CARTESIAN_POINT('',(4.099000737074,-1.85)); -#134651 = CARTESIAN_POINT('',(4.172647512726,-1.85)); -#134652 = CARTESIAN_POINT('',(4.246294288379,-1.85)); -#134653 = CARTESIAN_POINT('',(4.319941064031,-1.85)); -#134654 = CARTESIAN_POINT('',(4.393587839684,-1.85)); -#134655 = CARTESIAN_POINT('',(4.467234615337,-1.85)); -#134656 = CARTESIAN_POINT('',(4.540881390989,-1.85)); -#134657 = CARTESIAN_POINT('',(4.614528166642,-1.85)); -#134658 = CARTESIAN_POINT('',(4.688174942294,-1.85)); -#134659 = CARTESIAN_POINT('',(4.737272792729,-1.85)); -#134660 = CARTESIAN_POINT('',(4.761821717947,-1.85)); -#134661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134662 = PCURVE('',#92398,#134663); -#134663 = DEFINITIONAL_REPRESENTATION('',(#134664),#134672); -#134664 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134665,#134666,#134667, - #134668,#134669,#134670,#134671),.UNSPECIFIED.,.T.,.F.) +#137028 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#137029 = CARTESIAN_POINT('',(3.166141578807,-1.85)); +#137030 = CARTESIAN_POINT('',(3.215239429242,-1.85)); +#137031 = CARTESIAN_POINT('',(3.288886204895,-1.85)); +#137032 = CARTESIAN_POINT('',(3.362532980548,-1.85)); +#137033 = CARTESIAN_POINT('',(3.4361797562,-1.85)); +#137034 = CARTESIAN_POINT('',(3.509826531853,-1.85)); +#137035 = CARTESIAN_POINT('',(3.583473307505,-1.85)); +#137036 = CARTESIAN_POINT('',(3.657120083158,-1.85)); +#137037 = CARTESIAN_POINT('',(3.730766858811,-1.85)); +#137038 = CARTESIAN_POINT('',(3.804413634463,-1.85)); +#137039 = CARTESIAN_POINT('',(3.878060410116,-1.85)); +#137040 = CARTESIAN_POINT('',(3.951707185768,-1.85)); +#137041 = CARTESIAN_POINT('',(4.025353961421,-1.85)); +#137042 = CARTESIAN_POINT('',(4.099000737074,-1.85)); +#137043 = CARTESIAN_POINT('',(4.172647512726,-1.85)); +#137044 = CARTESIAN_POINT('',(4.246294288379,-1.85)); +#137045 = CARTESIAN_POINT('',(4.319941064031,-1.85)); +#137046 = CARTESIAN_POINT('',(4.393587839684,-1.85)); +#137047 = CARTESIAN_POINT('',(4.467234615337,-1.85)); +#137048 = CARTESIAN_POINT('',(4.540881390989,-1.85)); +#137049 = CARTESIAN_POINT('',(4.614528166642,-1.85)); +#137050 = CARTESIAN_POINT('',(4.688174942294,-1.85)); +#137051 = CARTESIAN_POINT('',(4.737272792729,-1.85)); +#137052 = CARTESIAN_POINT('',(4.761821717947,-1.85)); +#137053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137054 = PCURVE('',#94790,#137055); +#137055 = DEFINITIONAL_REPRESENTATION('',(#137056),#137064); +#137056 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137057,#137058,#137059, + #137060,#137061,#137062,#137063),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#134665 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#134666 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#134667 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#134668 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#134669 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#134670 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#134671 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#134672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134673 = ORIENTED_EDGE('',*,*,#134494,.T.); -#134674 = ORIENTED_EDGE('',*,*,#134675,.F.); -#134675 = EDGE_CURVE('',#134676,#134472,#134678,.T.); -#134676 = VERTEX_POINT('',#134677); -#134677 = CARTESIAN_POINT('',(10.419594812019,1.65,0.E+000)); -#134678 = SURFACE_CURVE('',#134679,(#134684,#134713),.PCURVE_S1.); -#134679 = CIRCLE('',#134680,0.308574064194); -#134680 = AXIS2_PLACEMENT_3D('',#134681,#134682,#134683); -#134681 = CARTESIAN_POINT('',(10.728168876214,1.65,2.640924866458E-017) - ); -#134682 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134683 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#134684 = PCURVE('',#134510,#134685); -#134685 = DEFINITIONAL_REPRESENTATION('',(#134686),#134712); -#134686 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#134687,#134688,#134689, - #134690,#134691,#134692,#134693,#134694,#134695,#134696,#134697, - #134698,#134699,#134700,#134701,#134702,#134703,#134704,#134705, - #134706,#134707,#134708,#134709,#134710,#134711),.UNSPECIFIED.,.F., +#137057 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#137058 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#137059 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#137060 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#137061 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#137062 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#137063 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#137064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137065 = ORIENTED_EDGE('',*,*,#136886,.T.); +#137066 = ORIENTED_EDGE('',*,*,#137067,.F.); +#137067 = EDGE_CURVE('',#137068,#136864,#137070,.T.); +#137068 = VERTEX_POINT('',#137069); +#137069 = CARTESIAN_POINT('',(10.419594812019,1.65,0.E+000)); +#137070 = SURFACE_CURVE('',#137071,(#137076,#137105),.PCURVE_S1.); +#137071 = CIRCLE('',#137072,0.308574064194); +#137072 = AXIS2_PLACEMENT_3D('',#137073,#137074,#137075); +#137073 = CARTESIAN_POINT('',(10.728168876214,1.65,2.640924866458E-017) + ); +#137074 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137075 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137076 = PCURVE('',#136902,#137077); +#137077 = DEFINITIONAL_REPRESENTATION('',(#137078),#137104); +#137078 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137079,#137080,#137081, + #137082,#137083,#137084,#137085,#137086,#137087,#137088,#137089, + #137090,#137091,#137092,#137093,#137094,#137095,#137096,#137097, + #137098,#137099,#137100,#137101,#137102,#137103),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -165988,1027 +168990,1027 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#134687 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#134688 = CARTESIAN_POINT('',(3.166141578807,-1.65)); -#134689 = CARTESIAN_POINT('',(3.215239429242,-1.65)); -#134690 = CARTESIAN_POINT('',(3.288886204895,-1.65)); -#134691 = CARTESIAN_POINT('',(3.362532980548,-1.65)); -#134692 = CARTESIAN_POINT('',(3.4361797562,-1.65)); -#134693 = CARTESIAN_POINT('',(3.509826531853,-1.65)); -#134694 = CARTESIAN_POINT('',(3.583473307505,-1.65)); -#134695 = CARTESIAN_POINT('',(3.657120083158,-1.65)); -#134696 = CARTESIAN_POINT('',(3.730766858811,-1.65)); -#134697 = CARTESIAN_POINT('',(3.804413634463,-1.65)); -#134698 = CARTESIAN_POINT('',(3.878060410116,-1.65)); -#134699 = CARTESIAN_POINT('',(3.951707185768,-1.65)); -#134700 = CARTESIAN_POINT('',(4.025353961421,-1.65)); -#134701 = CARTESIAN_POINT('',(4.099000737074,-1.65)); -#134702 = CARTESIAN_POINT('',(4.172647512726,-1.65)); -#134703 = CARTESIAN_POINT('',(4.246294288379,-1.65)); -#134704 = CARTESIAN_POINT('',(4.319941064031,-1.65)); -#134705 = CARTESIAN_POINT('',(4.393587839684,-1.65)); -#134706 = CARTESIAN_POINT('',(4.467234615337,-1.65)); -#134707 = CARTESIAN_POINT('',(4.540881390989,-1.65)); -#134708 = CARTESIAN_POINT('',(4.614528166642,-1.65)); -#134709 = CARTESIAN_POINT('',(4.688174942294,-1.65)); -#134710 = CARTESIAN_POINT('',(4.737272792729,-1.65)); -#134711 = CARTESIAN_POINT('',(4.761821717947,-1.65)); -#134712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134713 = PCURVE('',#92454,#134714); -#134714 = DEFINITIONAL_REPRESENTATION('',(#134715),#134719); -#134715 = CIRCLE('',#134716,0.308574064194); -#134716 = AXIS2_PLACEMENT_2D('',#134717,#134718); -#134717 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#134718 = DIRECTION('',(0.E+000,1.)); -#134719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134720 = ORIENTED_EDGE('',*,*,#134721,.T.); -#134721 = EDGE_CURVE('',#134676,#134625,#134722,.T.); -#134722 = SURFACE_CURVE('',#134723,(#134727,#134733),.PCURVE_S1.); -#134723 = LINE('',#134724,#134725); -#134724 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#137079 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#137080 = CARTESIAN_POINT('',(3.166141578807,-1.65)); +#137081 = CARTESIAN_POINT('',(3.215239429242,-1.65)); +#137082 = CARTESIAN_POINT('',(3.288886204895,-1.65)); +#137083 = CARTESIAN_POINT('',(3.362532980548,-1.65)); +#137084 = CARTESIAN_POINT('',(3.4361797562,-1.65)); +#137085 = CARTESIAN_POINT('',(3.509826531853,-1.65)); +#137086 = CARTESIAN_POINT('',(3.583473307505,-1.65)); +#137087 = CARTESIAN_POINT('',(3.657120083158,-1.65)); +#137088 = CARTESIAN_POINT('',(3.730766858811,-1.65)); +#137089 = CARTESIAN_POINT('',(3.804413634463,-1.65)); +#137090 = CARTESIAN_POINT('',(3.878060410116,-1.65)); +#137091 = CARTESIAN_POINT('',(3.951707185768,-1.65)); +#137092 = CARTESIAN_POINT('',(4.025353961421,-1.65)); +#137093 = CARTESIAN_POINT('',(4.099000737074,-1.65)); +#137094 = CARTESIAN_POINT('',(4.172647512726,-1.65)); +#137095 = CARTESIAN_POINT('',(4.246294288379,-1.65)); +#137096 = CARTESIAN_POINT('',(4.319941064031,-1.65)); +#137097 = CARTESIAN_POINT('',(4.393587839684,-1.65)); +#137098 = CARTESIAN_POINT('',(4.467234615337,-1.65)); +#137099 = CARTESIAN_POINT('',(4.540881390989,-1.65)); +#137100 = CARTESIAN_POINT('',(4.614528166642,-1.65)); +#137101 = CARTESIAN_POINT('',(4.688174942294,-1.65)); +#137102 = CARTESIAN_POINT('',(4.737272792729,-1.65)); +#137103 = CARTESIAN_POINT('',(4.761821717947,-1.65)); +#137104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137105 = PCURVE('',#94846,#137106); +#137106 = DEFINITIONAL_REPRESENTATION('',(#137107),#137111); +#137107 = CIRCLE('',#137108,0.308574064194); +#137108 = AXIS2_PLACEMENT_2D('',#137109,#137110); +#137109 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#137110 = DIRECTION('',(0.E+000,1.)); +#137111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137112 = ORIENTED_EDGE('',*,*,#137113,.T.); +#137113 = EDGE_CURVE('',#137068,#137017,#137114,.T.); +#137114 = SURFACE_CURVE('',#137115,(#137119,#137125),.PCURVE_S1.); +#137115 = LINE('',#137116,#137117); +#137116 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#134725 = VECTOR('',#134726,1.); -#134726 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134727 = PCURVE('',#134510,#134728); -#134728 = DEFINITIONAL_REPRESENTATION('',(#134729),#134732); -#134729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134730,#134731), +#137117 = VECTOR('',#137118,1.); +#137118 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137119 = PCURVE('',#136902,#137120); +#137120 = DEFINITIONAL_REPRESENTATION('',(#137121),#137124); +#137121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137122,#137123), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#134730 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#134731 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#134732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137122 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#137123 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#137124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134733 = PCURVE('',#134734,#134739); -#134734 = PLANE('',#134735); -#134735 = AXIS2_PLACEMENT_3D('',#134736,#134737,#134738); -#134736 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#137125 = PCURVE('',#137126,#137131); +#137126 = PLANE('',#137127); +#137127 = AXIS2_PLACEMENT_3D('',#137128,#137129,#137130); +#137128 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#134737 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134738 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134739 = DEFINITIONAL_REPRESENTATION('',(#134740),#134744); -#134740 = LINE('',#134741,#134742); -#134741 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#134742 = VECTOR('',#134743,1.); -#134743 = DIRECTION('',(-1.,0.E+000)); -#134744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134745 = ADVANCED_FACE('',(#134746),#134734,.T.); -#134746 = FACE_BOUND('',#134747,.T.); -#134747 = EDGE_LOOP('',(#134748,#134777,#134798,#134799)); -#134748 = ORIENTED_EDGE('',*,*,#134749,.T.); -#134749 = EDGE_CURVE('',#134750,#134752,#134754,.T.); -#134750 = VERTEX_POINT('',#134751); -#134751 = CARTESIAN_POINT('',(10.419594812019,1.65,0.530776333563)); -#134752 = VERTEX_POINT('',#134753); -#134753 = CARTESIAN_POINT('',(10.419594812019,1.85,0.530776333563)); -#134754 = SURFACE_CURVE('',#134755,(#134759,#134766),.PCURVE_S1.); -#134755 = LINE('',#134756,#134757); -#134756 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#137129 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137130 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137131 = DEFINITIONAL_REPRESENTATION('',(#137132),#137136); +#137132 = LINE('',#137133,#137134); +#137133 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#137134 = VECTOR('',#137135,1.); +#137135 = DIRECTION('',(-1.,0.E+000)); +#137136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137137 = ADVANCED_FACE('',(#137138),#137126,.T.); +#137138 = FACE_BOUND('',#137139,.T.); +#137139 = EDGE_LOOP('',(#137140,#137169,#137190,#137191)); +#137140 = ORIENTED_EDGE('',*,*,#137141,.T.); +#137141 = EDGE_CURVE('',#137142,#137144,#137146,.T.); +#137142 = VERTEX_POINT('',#137143); +#137143 = CARTESIAN_POINT('',(10.419594812019,1.65,0.530776333563)); +#137144 = VERTEX_POINT('',#137145); +#137145 = CARTESIAN_POINT('',(10.419594812019,1.85,0.530776333563)); +#137146 = SURFACE_CURVE('',#137147,(#137151,#137158),.PCURVE_S1.); +#137147 = LINE('',#137148,#137149); +#137148 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#134757 = VECTOR('',#134758,1.); -#134758 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134759 = PCURVE('',#134734,#134760); -#134760 = DEFINITIONAL_REPRESENTATION('',(#134761),#134765); -#134761 = LINE('',#134762,#134763); -#134762 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134763 = VECTOR('',#134764,1.); -#134764 = DIRECTION('',(-1.,0.E+000)); -#134765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134766 = PCURVE('',#134767,#134772); -#134767 = CYLINDRICAL_SURFACE('',#134768,0.119270391569); -#134768 = AXIS2_PLACEMENT_3D('',#134769,#134770,#134771); -#134769 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#137149 = VECTOR('',#137150,1.); +#137150 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137151 = PCURVE('',#137126,#137152); +#137152 = DEFINITIONAL_REPRESENTATION('',(#137153),#137157); +#137153 = LINE('',#137154,#137155); +#137154 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137155 = VECTOR('',#137156,1.); +#137156 = DIRECTION('',(-1.,0.E+000)); +#137157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137158 = PCURVE('',#137159,#137164); +#137159 = CYLINDRICAL_SURFACE('',#137160,0.119270391569); +#137160 = AXIS2_PLACEMENT_3D('',#137161,#137162,#137163); +#137161 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#134770 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134771 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134772 = DEFINITIONAL_REPRESENTATION('',(#134773),#134776); -#134773 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134774,#134775), +#137162 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137163 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137164 = DEFINITIONAL_REPRESENTATION('',(#137165),#137168); +#137165 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137166,#137167), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#134774 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#134775 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#134776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134777 = ORIENTED_EDGE('',*,*,#134778,.T.); -#134778 = EDGE_CURVE('',#134752,#134625,#134779,.T.); -#134779 = SURFACE_CURVE('',#134780,(#134784,#134791),.PCURVE_S1.); -#134780 = LINE('',#134781,#134782); -#134781 = CARTESIAN_POINT('',(10.419594812019,1.85,0.530776333563)); -#134782 = VECTOR('',#134783,1.); -#134783 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#134784 = PCURVE('',#134734,#134785); -#134785 = DEFINITIONAL_REPRESENTATION('',(#134786),#134790); -#134786 = LINE('',#134787,#134788); -#134787 = CARTESIAN_POINT('',(-1.85,0.E+000)); -#134788 = VECTOR('',#134789,1.); -#134789 = DIRECTION('',(0.E+000,-1.)); -#134790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134791 = PCURVE('',#92398,#134792); -#134792 = DEFINITIONAL_REPRESENTATION('',(#134793),#134797); -#134793 = LINE('',#134794,#134795); -#134794 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#134795 = VECTOR('',#134796,1.); -#134796 = DIRECTION('',(-1.,0.E+000)); -#134797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134798 = ORIENTED_EDGE('',*,*,#134721,.F.); -#134799 = ORIENTED_EDGE('',*,*,#134800,.F.); -#134800 = EDGE_CURVE('',#134750,#134676,#134801,.T.); -#134801 = SURFACE_CURVE('',#134802,(#134806,#134813),.PCURVE_S1.); -#134802 = LINE('',#134803,#134804); -#134803 = CARTESIAN_POINT('',(10.419594812019,1.65,0.530776333563)); -#134804 = VECTOR('',#134805,1.); -#134805 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#134806 = PCURVE('',#134734,#134807); -#134807 = DEFINITIONAL_REPRESENTATION('',(#134808),#134812); -#134808 = LINE('',#134809,#134810); -#134809 = CARTESIAN_POINT('',(-1.65,0.E+000)); -#134810 = VECTOR('',#134811,1.); -#134811 = DIRECTION('',(0.E+000,-1.)); -#134812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134813 = PCURVE('',#92454,#134814); -#134814 = DEFINITIONAL_REPRESENTATION('',(#134815),#134819); -#134815 = LINE('',#134816,#134817); -#134816 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#134817 = VECTOR('',#134818,1.); -#134818 = DIRECTION('',(1.,0.E+000)); -#134819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134820 = ADVANCED_FACE('',(#134821),#134583,.T.); -#134821 = FACE_BOUND('',#134822,.T.); -#134822 = EDGE_LOOP('',(#134823,#134852,#134873,#134874)); -#134823 = ORIENTED_EDGE('',*,*,#134824,.T.); -#134824 = EDGE_CURVE('',#134825,#134827,#134829,.T.); -#134825 = VERTEX_POINT('',#134826); -#134826 = CARTESIAN_POINT('',(10.51959417205,1.85,0.530776333563)); -#134827 = VERTEX_POINT('',#134828); -#134828 = CARTESIAN_POINT('',(10.51959417205,1.65,0.530776333563)); -#134829 = SURFACE_CURVE('',#134830,(#134834,#134841),.PCURVE_S1.); -#134830 = LINE('',#134831,#134832); -#134831 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#137166 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#137167 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#137168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137169 = ORIENTED_EDGE('',*,*,#137170,.T.); +#137170 = EDGE_CURVE('',#137144,#137017,#137171,.T.); +#137171 = SURFACE_CURVE('',#137172,(#137176,#137183),.PCURVE_S1.); +#137172 = LINE('',#137173,#137174); +#137173 = CARTESIAN_POINT('',(10.419594812019,1.85,0.530776333563)); +#137174 = VECTOR('',#137175,1.); +#137175 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#137176 = PCURVE('',#137126,#137177); +#137177 = DEFINITIONAL_REPRESENTATION('',(#137178),#137182); +#137178 = LINE('',#137179,#137180); +#137179 = CARTESIAN_POINT('',(-1.85,0.E+000)); +#137180 = VECTOR('',#137181,1.); +#137181 = DIRECTION('',(0.E+000,-1.)); +#137182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137183 = PCURVE('',#94790,#137184); +#137184 = DEFINITIONAL_REPRESENTATION('',(#137185),#137189); +#137185 = LINE('',#137186,#137187); +#137186 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#137187 = VECTOR('',#137188,1.); +#137188 = DIRECTION('',(-1.,0.E+000)); +#137189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137190 = ORIENTED_EDGE('',*,*,#137113,.F.); +#137191 = ORIENTED_EDGE('',*,*,#137192,.F.); +#137192 = EDGE_CURVE('',#137142,#137068,#137193,.T.); +#137193 = SURFACE_CURVE('',#137194,(#137198,#137205),.PCURVE_S1.); +#137194 = LINE('',#137195,#137196); +#137195 = CARTESIAN_POINT('',(10.419594812019,1.65,0.530776333563)); +#137196 = VECTOR('',#137197,1.); +#137197 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#137198 = PCURVE('',#137126,#137199); +#137199 = DEFINITIONAL_REPRESENTATION('',(#137200),#137204); +#137200 = LINE('',#137201,#137202); +#137201 = CARTESIAN_POINT('',(-1.65,0.E+000)); +#137202 = VECTOR('',#137203,1.); +#137203 = DIRECTION('',(0.E+000,-1.)); +#137204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137205 = PCURVE('',#94846,#137206); +#137206 = DEFINITIONAL_REPRESENTATION('',(#137207),#137211); +#137207 = LINE('',#137208,#137209); +#137208 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#137209 = VECTOR('',#137210,1.); +#137210 = DIRECTION('',(1.,0.E+000)); +#137211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137212 = ADVANCED_FACE('',(#137213),#136975,.T.); +#137213 = FACE_BOUND('',#137214,.T.); +#137214 = EDGE_LOOP('',(#137215,#137244,#137265,#137266)); +#137215 = ORIENTED_EDGE('',*,*,#137216,.T.); +#137216 = EDGE_CURVE('',#137217,#137219,#137221,.T.); +#137217 = VERTEX_POINT('',#137218); +#137218 = CARTESIAN_POINT('',(10.51959417205,1.85,0.530776333563)); +#137219 = VERTEX_POINT('',#137220); +#137220 = CARTESIAN_POINT('',(10.51959417205,1.65,0.530776333563)); +#137221 = SURFACE_CURVE('',#137222,(#137226,#137233),.PCURVE_S1.); +#137222 = LINE('',#137223,#137224); +#137223 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#134832 = VECTOR('',#134833,1.); -#134833 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#134834 = PCURVE('',#134583,#134835); -#134835 = DEFINITIONAL_REPRESENTATION('',(#134836),#134840); -#134836 = LINE('',#134837,#134838); -#134837 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#134838 = VECTOR('',#134839,1.); -#134839 = DIRECTION('',(-1.,0.E+000)); -#134840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134841 = PCURVE('',#134842,#134847); -#134842 = CYLINDRICAL_SURFACE('',#134843,0.2192697516); -#134843 = AXIS2_PLACEMENT_3D('',#134844,#134845,#134846); -#134844 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#137224 = VECTOR('',#137225,1.); +#137225 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137226 = PCURVE('',#136975,#137227); +#137227 = DEFINITIONAL_REPRESENTATION('',(#137228),#137232); +#137228 = LINE('',#137229,#137230); +#137229 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137230 = VECTOR('',#137231,1.); +#137231 = DIRECTION('',(-1.,0.E+000)); +#137232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137233 = PCURVE('',#137234,#137239); +#137234 = CYLINDRICAL_SURFACE('',#137235,0.2192697516); +#137235 = AXIS2_PLACEMENT_3D('',#137236,#137237,#137238); +#137236 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#134845 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134846 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134847 = DEFINITIONAL_REPRESENTATION('',(#134848),#134851); -#134848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134849,#134850), +#137237 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137238 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137239 = DEFINITIONAL_REPRESENTATION('',(#137240),#137243); +#137240 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137241,#137242), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#134849 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#134850 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#134851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134852 = ORIENTED_EDGE('',*,*,#134853,.T.); -#134853 = EDGE_CURVE('',#134827,#134546,#134854,.T.); -#134854 = SURFACE_CURVE('',#134855,(#134859,#134866),.PCURVE_S1.); -#134855 = LINE('',#134856,#134857); -#134856 = CARTESIAN_POINT('',(10.51959417205,1.65,0.530776333563)); -#134857 = VECTOR('',#134858,1.); -#134858 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#134859 = PCURVE('',#134583,#134860); -#134860 = DEFINITIONAL_REPRESENTATION('',(#134861),#134865); -#134861 = LINE('',#134862,#134863); -#134862 = CARTESIAN_POINT('',(1.65,0.E+000)); -#134863 = VECTOR('',#134864,1.); -#134864 = DIRECTION('',(0.E+000,-1.)); -#134865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134866 = PCURVE('',#92454,#134867); -#134867 = DEFINITIONAL_REPRESENTATION('',(#134868),#134872); -#134868 = LINE('',#134869,#134870); -#134869 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#134870 = VECTOR('',#134871,1.); -#134871 = DIRECTION('',(1.,0.E+000)); -#134872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134873 = ORIENTED_EDGE('',*,*,#134568,.F.); -#134874 = ORIENTED_EDGE('',*,*,#134875,.F.); -#134875 = EDGE_CURVE('',#134825,#134569,#134876,.T.); -#134876 = SURFACE_CURVE('',#134877,(#134881,#134888),.PCURVE_S1.); -#134877 = LINE('',#134878,#134879); -#134878 = CARTESIAN_POINT('',(10.51959417205,1.85,0.530776333563)); -#134879 = VECTOR('',#134880,1.); -#134880 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#134881 = PCURVE('',#134583,#134882); -#134882 = DEFINITIONAL_REPRESENTATION('',(#134883),#134887); -#134883 = LINE('',#134884,#134885); -#134884 = CARTESIAN_POINT('',(1.85,0.E+000)); -#134885 = VECTOR('',#134886,1.); -#134886 = DIRECTION('',(0.E+000,-1.)); -#134887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134888 = PCURVE('',#92398,#134889); -#134889 = DEFINITIONAL_REPRESENTATION('',(#134890),#134894); -#134890 = LINE('',#134891,#134892); -#134891 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#134892 = VECTOR('',#134893,1.); -#134893 = DIRECTION('',(-1.,0.E+000)); -#134894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134895 = ADVANCED_FACE('',(#134896),#134842,.T.); -#134896 = FACE_BOUND('',#134897,.T.); -#134897 = EDGE_LOOP('',(#134898,#134899,#134922,#134944)); -#134898 = ORIENTED_EDGE('',*,*,#134824,.F.); -#134899 = ORIENTED_EDGE('',*,*,#134900,.F.); -#134900 = EDGE_CURVE('',#134901,#134825,#134903,.T.); -#134901 = VERTEX_POINT('',#134902); -#134902 = CARTESIAN_POINT('',(10.304819755875,1.85,0.75)); -#134903 = SURFACE_CURVE('',#134904,(#134909,#134915),.PCURVE_S1.); -#134904 = CIRCLE('',#134905,0.2192697516); -#134905 = AXIS2_PLACEMENT_3D('',#134906,#134907,#134908); -#134906 = CARTESIAN_POINT('',(10.30032442045,1.85,0.530776333563)); -#134907 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134908 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134909 = PCURVE('',#134842,#134910); -#134910 = DEFINITIONAL_REPRESENTATION('',(#134911),#134914); -#134911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134912,#134913), +#137241 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#137242 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#137243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137244 = ORIENTED_EDGE('',*,*,#137245,.T.); +#137245 = EDGE_CURVE('',#137219,#136938,#137246,.T.); +#137246 = SURFACE_CURVE('',#137247,(#137251,#137258),.PCURVE_S1.); +#137247 = LINE('',#137248,#137249); +#137248 = CARTESIAN_POINT('',(10.51959417205,1.65,0.530776333563)); +#137249 = VECTOR('',#137250,1.); +#137250 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#137251 = PCURVE('',#136975,#137252); +#137252 = DEFINITIONAL_REPRESENTATION('',(#137253),#137257); +#137253 = LINE('',#137254,#137255); +#137254 = CARTESIAN_POINT('',(1.65,0.E+000)); +#137255 = VECTOR('',#137256,1.); +#137256 = DIRECTION('',(0.E+000,-1.)); +#137257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137258 = PCURVE('',#94846,#137259); +#137259 = DEFINITIONAL_REPRESENTATION('',(#137260),#137264); +#137260 = LINE('',#137261,#137262); +#137261 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#137262 = VECTOR('',#137263,1.); +#137263 = DIRECTION('',(1.,0.E+000)); +#137264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137265 = ORIENTED_EDGE('',*,*,#136960,.F.); +#137266 = ORIENTED_EDGE('',*,*,#137267,.F.); +#137267 = EDGE_CURVE('',#137217,#136961,#137268,.T.); +#137268 = SURFACE_CURVE('',#137269,(#137273,#137280),.PCURVE_S1.); +#137269 = LINE('',#137270,#137271); +#137270 = CARTESIAN_POINT('',(10.51959417205,1.85,0.530776333563)); +#137271 = VECTOR('',#137272,1.); +#137272 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#137273 = PCURVE('',#136975,#137274); +#137274 = DEFINITIONAL_REPRESENTATION('',(#137275),#137279); +#137275 = LINE('',#137276,#137277); +#137276 = CARTESIAN_POINT('',(1.85,0.E+000)); +#137277 = VECTOR('',#137278,1.); +#137278 = DIRECTION('',(0.E+000,-1.)); +#137279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137280 = PCURVE('',#94790,#137281); +#137281 = DEFINITIONAL_REPRESENTATION('',(#137282),#137286); +#137282 = LINE('',#137283,#137284); +#137283 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#137284 = VECTOR('',#137285,1.); +#137285 = DIRECTION('',(-1.,0.E+000)); +#137286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137287 = ADVANCED_FACE('',(#137288),#137234,.T.); +#137288 = FACE_BOUND('',#137289,.T.); +#137289 = EDGE_LOOP('',(#137290,#137291,#137314,#137336)); +#137290 = ORIENTED_EDGE('',*,*,#137216,.F.); +#137291 = ORIENTED_EDGE('',*,*,#137292,.F.); +#137292 = EDGE_CURVE('',#137293,#137217,#137295,.T.); +#137293 = VERTEX_POINT('',#137294); +#137294 = CARTESIAN_POINT('',(10.304819755875,1.85,0.75)); +#137295 = SURFACE_CURVE('',#137296,(#137301,#137307),.PCURVE_S1.); +#137296 = CIRCLE('',#137297,0.2192697516); +#137297 = AXIS2_PLACEMENT_3D('',#137298,#137299,#137300); +#137298 = CARTESIAN_POINT('',(10.30032442045,1.85,0.530776333563)); +#137299 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137300 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137301 = PCURVE('',#137234,#137302); +#137302 = DEFINITIONAL_REPRESENTATION('',(#137303),#137306); +#137303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137304,#137305), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#134912 = CARTESIAN_POINT('',(1.591299156552,1.85)); -#134913 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#134914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134915 = PCURVE('',#92398,#134916); -#134916 = DEFINITIONAL_REPRESENTATION('',(#134917),#134921); -#134917 = CIRCLE('',#134918,0.2192697516); -#134918 = AXIS2_PLACEMENT_2D('',#134919,#134920); -#134919 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#134920 = DIRECTION('',(0.E+000,-1.)); -#134921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134922 = ORIENTED_EDGE('',*,*,#134923,.F.); -#134923 = EDGE_CURVE('',#134924,#134901,#134926,.T.); -#134924 = VERTEX_POINT('',#134925); -#134925 = CARTESIAN_POINT('',(10.304819755875,1.65,0.75)); -#134926 = SURFACE_CURVE('',#134927,(#134931,#134937),.PCURVE_S1.); -#134927 = LINE('',#134928,#134929); -#134928 = CARTESIAN_POINT('',(10.304819755875,1.85,0.75)); -#134929 = VECTOR('',#134930,1.); -#134930 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134931 = PCURVE('',#134842,#134932); -#134932 = DEFINITIONAL_REPRESENTATION('',(#134933),#134936); -#134933 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134934,#134935), +#137304 = CARTESIAN_POINT('',(1.591299156552,1.85)); +#137305 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#137306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137307 = PCURVE('',#94790,#137308); +#137308 = DEFINITIONAL_REPRESENTATION('',(#137309),#137313); +#137309 = CIRCLE('',#137310,0.2192697516); +#137310 = AXIS2_PLACEMENT_2D('',#137311,#137312); +#137311 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#137312 = DIRECTION('',(0.E+000,-1.)); +#137313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137314 = ORIENTED_EDGE('',*,*,#137315,.F.); +#137315 = EDGE_CURVE('',#137316,#137293,#137318,.T.); +#137316 = VERTEX_POINT('',#137317); +#137317 = CARTESIAN_POINT('',(10.304819755875,1.65,0.75)); +#137318 = SURFACE_CURVE('',#137319,(#137323,#137329),.PCURVE_S1.); +#137319 = LINE('',#137320,#137321); +#137320 = CARTESIAN_POINT('',(10.304819755875,1.85,0.75)); +#137321 = VECTOR('',#137322,1.); +#137322 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137323 = PCURVE('',#137234,#137324); +#137324 = DEFINITIONAL_REPRESENTATION('',(#137325),#137328); +#137325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137326,#137327), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#134934 = CARTESIAN_POINT('',(1.591299156552,1.65)); -#134935 = CARTESIAN_POINT('',(1.591299156552,1.85)); -#134936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137326 = CARTESIAN_POINT('',(1.591299156552,1.65)); +#137327 = CARTESIAN_POINT('',(1.591299156552,1.85)); +#137328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134937 = PCURVE('',#92480,#134938); -#134938 = DEFINITIONAL_REPRESENTATION('',(#134939),#134943); -#134939 = LINE('',#134940,#134941); -#134940 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#134941 = VECTOR('',#134942,1.); -#134942 = DIRECTION('',(4.440892098501E-016,1.)); -#134943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137329 = PCURVE('',#94872,#137330); +#137330 = DEFINITIONAL_REPRESENTATION('',(#137331),#137335); +#137331 = LINE('',#137332,#137333); +#137332 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#137333 = VECTOR('',#137334,1.); +#137334 = DIRECTION('',(4.440892098501E-016,1.)); +#137335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134944 = ORIENTED_EDGE('',*,*,#134945,.T.); -#134945 = EDGE_CURVE('',#134924,#134827,#134946,.T.); -#134946 = SURFACE_CURVE('',#134947,(#134952,#134958),.PCURVE_S1.); -#134947 = CIRCLE('',#134948,0.2192697516); -#134948 = AXIS2_PLACEMENT_3D('',#134949,#134950,#134951); -#134949 = CARTESIAN_POINT('',(10.30032442045,1.65,0.530776333563)); -#134950 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134951 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134952 = PCURVE('',#134842,#134953); -#134953 = DEFINITIONAL_REPRESENTATION('',(#134954),#134957); -#134954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134955,#134956), +#137336 = ORIENTED_EDGE('',*,*,#137337,.T.); +#137337 = EDGE_CURVE('',#137316,#137219,#137338,.T.); +#137338 = SURFACE_CURVE('',#137339,(#137344,#137350),.PCURVE_S1.); +#137339 = CIRCLE('',#137340,0.2192697516); +#137340 = AXIS2_PLACEMENT_3D('',#137341,#137342,#137343); +#137341 = CARTESIAN_POINT('',(10.30032442045,1.65,0.530776333563)); +#137342 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137343 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137344 = PCURVE('',#137234,#137345); +#137345 = DEFINITIONAL_REPRESENTATION('',(#137346),#137349); +#137346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137347,#137348), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#134955 = CARTESIAN_POINT('',(1.591299156552,1.65)); -#134956 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#134957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137347 = CARTESIAN_POINT('',(1.591299156552,1.65)); +#137348 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#137349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#134958 = PCURVE('',#92454,#134959); -#134959 = DEFINITIONAL_REPRESENTATION('',(#134960),#134968); -#134960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#134961,#134962,#134963, - #134964,#134965,#134966,#134967),.UNSPECIFIED.,.T.,.F.) +#137350 = PCURVE('',#94846,#137351); +#137351 = DEFINITIONAL_REPRESENTATION('',(#137352),#137360); +#137352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137353,#137354,#137355, + #137356,#137357,#137358,#137359),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#134961 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#134962 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#134963 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#134964 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#134965 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#134966 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#134967 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#134968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134969 = ADVANCED_FACE('',(#134970),#134767,.F.); -#134970 = FACE_BOUND('',#134971,.F.); -#134971 = EDGE_LOOP('',(#134972,#134973,#134996,#135018)); -#134972 = ORIENTED_EDGE('',*,*,#134749,.T.); -#134973 = ORIENTED_EDGE('',*,*,#134974,.F.); -#134974 = EDGE_CURVE('',#134975,#134752,#134977,.T.); -#134975 = VERTEX_POINT('',#134976); -#134976 = CARTESIAN_POINT('',(10.303662633502,1.85,0.65)); -#134977 = SURFACE_CURVE('',#134978,(#134983,#134989),.PCURVE_S1.); -#134978 = CIRCLE('',#134979,0.119270391569); -#134979 = AXIS2_PLACEMENT_3D('',#134980,#134981,#134982); -#134980 = CARTESIAN_POINT('',(10.30032442045,1.85,0.530776333563)); -#134981 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#134982 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#134983 = PCURVE('',#134767,#134984); -#134984 = DEFINITIONAL_REPRESENTATION('',(#134985),#134988); -#134985 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#134986,#134987), +#137353 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#137354 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#137355 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#137356 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#137357 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#137358 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#137359 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#137360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137361 = ADVANCED_FACE('',(#137362),#137159,.F.); +#137362 = FACE_BOUND('',#137363,.F.); +#137363 = EDGE_LOOP('',(#137364,#137365,#137388,#137410)); +#137364 = ORIENTED_EDGE('',*,*,#137141,.T.); +#137365 = ORIENTED_EDGE('',*,*,#137366,.F.); +#137366 = EDGE_CURVE('',#137367,#137144,#137369,.T.); +#137367 = VERTEX_POINT('',#137368); +#137368 = CARTESIAN_POINT('',(10.303662633502,1.85,0.65)); +#137369 = SURFACE_CURVE('',#137370,(#137375,#137381),.PCURVE_S1.); +#137370 = CIRCLE('',#137371,0.119270391569); +#137371 = AXIS2_PLACEMENT_3D('',#137372,#137373,#137374); +#137372 = CARTESIAN_POINT('',(10.30032442045,1.85,0.530776333563)); +#137373 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137374 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137375 = PCURVE('',#137159,#137376); +#137376 = DEFINITIONAL_REPRESENTATION('',(#137377),#137380); +#137377 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137378,#137379), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#134986 = CARTESIAN_POINT('',(1.598788597134,1.85)); -#134987 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#134988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134989 = PCURVE('',#92398,#134990); -#134990 = DEFINITIONAL_REPRESENTATION('',(#134991),#134995); -#134991 = CIRCLE('',#134992,0.119270391569); -#134992 = AXIS2_PLACEMENT_2D('',#134993,#134994); -#134993 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#134994 = DIRECTION('',(0.E+000,-1.)); -#134995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#134996 = ORIENTED_EDGE('',*,*,#134997,.T.); -#134997 = EDGE_CURVE('',#134975,#134998,#135000,.T.); -#134998 = VERTEX_POINT('',#134999); -#134999 = CARTESIAN_POINT('',(10.303662633502,1.65,0.65)); -#135000 = SURFACE_CURVE('',#135001,(#135005,#135011),.PCURVE_S1.); -#135001 = LINE('',#135002,#135003); -#135002 = CARTESIAN_POINT('',(10.303662633502,1.85,0.65)); -#135003 = VECTOR('',#135004,1.); -#135004 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135005 = PCURVE('',#134767,#135006); -#135006 = DEFINITIONAL_REPRESENTATION('',(#135007),#135010); -#135007 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135008,#135009), +#137378 = CARTESIAN_POINT('',(1.598788597134,1.85)); +#137379 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#137380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137381 = PCURVE('',#94790,#137382); +#137382 = DEFINITIONAL_REPRESENTATION('',(#137383),#137387); +#137383 = CIRCLE('',#137384,0.119270391569); +#137384 = AXIS2_PLACEMENT_2D('',#137385,#137386); +#137385 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#137386 = DIRECTION('',(0.E+000,-1.)); +#137387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137388 = ORIENTED_EDGE('',*,*,#137389,.T.); +#137389 = EDGE_CURVE('',#137367,#137390,#137392,.T.); +#137390 = VERTEX_POINT('',#137391); +#137391 = CARTESIAN_POINT('',(10.303662633502,1.65,0.65)); +#137392 = SURFACE_CURVE('',#137393,(#137397,#137403),.PCURVE_S1.); +#137393 = LINE('',#137394,#137395); +#137394 = CARTESIAN_POINT('',(10.303662633502,1.85,0.65)); +#137395 = VECTOR('',#137396,1.); +#137396 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137397 = PCURVE('',#137159,#137398); +#137398 = DEFINITIONAL_REPRESENTATION('',(#137399),#137402); +#137399 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137400,#137401), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#135008 = CARTESIAN_POINT('',(1.598788597134,1.85)); -#135009 = CARTESIAN_POINT('',(1.598788597134,1.65)); -#135010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135011 = PCURVE('',#92426,#135012); -#135012 = DEFINITIONAL_REPRESENTATION('',(#135013),#135017); -#135013 = LINE('',#135014,#135015); -#135014 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#135015 = VECTOR('',#135016,1.); -#135016 = DIRECTION('',(4.440892098501E-016,-1.)); -#135017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135018 = ORIENTED_EDGE('',*,*,#135019,.T.); -#135019 = EDGE_CURVE('',#134998,#134750,#135020,.T.); -#135020 = SURFACE_CURVE('',#135021,(#135026,#135032),.PCURVE_S1.); -#135021 = CIRCLE('',#135022,0.119270391569); -#135022 = AXIS2_PLACEMENT_3D('',#135023,#135024,#135025); -#135023 = CARTESIAN_POINT('',(10.30032442045,1.65,0.530776333563)); -#135024 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135025 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135026 = PCURVE('',#134767,#135027); -#135027 = DEFINITIONAL_REPRESENTATION('',(#135028),#135031); -#135028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135029,#135030), +#137400 = CARTESIAN_POINT('',(1.598788597134,1.85)); +#137401 = CARTESIAN_POINT('',(1.598788597134,1.65)); +#137402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137403 = PCURVE('',#94818,#137404); +#137404 = DEFINITIONAL_REPRESENTATION('',(#137405),#137409); +#137405 = LINE('',#137406,#137407); +#137406 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#137407 = VECTOR('',#137408,1.); +#137408 = DIRECTION('',(4.440892098501E-016,-1.)); +#137409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137410 = ORIENTED_EDGE('',*,*,#137411,.T.); +#137411 = EDGE_CURVE('',#137390,#137142,#137412,.T.); +#137412 = SURFACE_CURVE('',#137413,(#137418,#137424),.PCURVE_S1.); +#137413 = CIRCLE('',#137414,0.119270391569); +#137414 = AXIS2_PLACEMENT_3D('',#137415,#137416,#137417); +#137415 = CARTESIAN_POINT('',(10.30032442045,1.65,0.530776333563)); +#137416 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137417 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#137418 = PCURVE('',#137159,#137419); +#137419 = DEFINITIONAL_REPRESENTATION('',(#137420),#137423); +#137420 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137421,#137422), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#135029 = CARTESIAN_POINT('',(1.598788597134,1.65)); -#135030 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#135031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137421 = CARTESIAN_POINT('',(1.598788597134,1.65)); +#137422 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#137423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135032 = PCURVE('',#92454,#135033); -#135033 = DEFINITIONAL_REPRESENTATION('',(#135034),#135042); -#135034 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135035,#135036,#135037, - #135038,#135039,#135040,#135041),.UNSPECIFIED.,.T.,.F.) +#137424 = PCURVE('',#94846,#137425); +#137425 = DEFINITIONAL_REPRESENTATION('',(#137426),#137434); +#137426 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137427,#137428,#137429, + #137430,#137431,#137432,#137433),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#135035 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#135036 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#135037 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#135038 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#135039 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#135040 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#135041 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#135042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135043 = ADVANCED_FACE('',(#135044),#92426,.T.); -#135044 = FACE_BOUND('',#135045,.T.); -#135045 = EDGE_LOOP('',(#135046,#135067,#135068,#135089)); -#135046 = ORIENTED_EDGE('',*,*,#135047,.F.); -#135047 = EDGE_CURVE('',#134975,#92383,#135048,.T.); -#135048 = SURFACE_CURVE('',#135049,(#135053,#135060),.PCURVE_S1.); -#135049 = LINE('',#135050,#135051); -#135050 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); -#135051 = VECTOR('',#135052,1.); -#135052 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135053 = PCURVE('',#92426,#135054); -#135054 = DEFINITIONAL_REPRESENTATION('',(#135055),#135059); -#135055 = LINE('',#135056,#135057); -#135056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135057 = VECTOR('',#135058,1.); -#135058 = DIRECTION('',(1.,-1.082494723017E-063)); -#135059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135060 = PCURVE('',#92398,#135061); -#135061 = DEFINITIONAL_REPRESENTATION('',(#135062),#135066); -#135062 = LINE('',#135063,#135064); -#135063 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135064 = VECTOR('',#135065,1.); -#135065 = DIRECTION('',(3.563627120235E-016,-1.)); -#135066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135067 = ORIENTED_EDGE('',*,*,#134997,.T.); -#135068 = ORIENTED_EDGE('',*,*,#135069,.T.); -#135069 = EDGE_CURVE('',#134998,#92411,#135070,.T.); -#135070 = SURFACE_CURVE('',#135071,(#135075,#135082),.PCURVE_S1.); -#135071 = LINE('',#135072,#135073); -#135072 = CARTESIAN_POINT('',(10.527847992439,1.65,0.65)); -#135073 = VECTOR('',#135074,1.); -#135074 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135075 = PCURVE('',#92426,#135076); -#135076 = DEFINITIONAL_REPRESENTATION('',(#135077),#135081); -#135077 = LINE('',#135078,#135079); -#135078 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#135079 = VECTOR('',#135080,1.); -#135080 = DIRECTION('',(1.,-1.082494723017E-063)); -#135081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135082 = PCURVE('',#92454,#135083); -#135083 = DEFINITIONAL_REPRESENTATION('',(#135084),#135088); -#135084 = LINE('',#135085,#135086); -#135085 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135086 = VECTOR('',#135087,1.); -#135087 = DIRECTION('',(-3.563627120235E-016,-1.)); -#135088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135089 = ORIENTED_EDGE('',*,*,#92410,.F.); -#135090 = ADVANCED_FACE('',(#135091),#92454,.T.); -#135091 = FACE_BOUND('',#135092,.T.); -#135092 = EDGE_LOOP('',(#135093,#135094,#135095,#135096,#135097,#135098, - #135119,#135120,#135121,#135122,#135123,#135144)); -#135093 = ORIENTED_EDGE('',*,*,#135069,.F.); -#135094 = ORIENTED_EDGE('',*,*,#135019,.T.); -#135095 = ORIENTED_EDGE('',*,*,#134800,.T.); -#135096 = ORIENTED_EDGE('',*,*,#134675,.T.); -#135097 = ORIENTED_EDGE('',*,*,#134471,.T.); -#135098 = ORIENTED_EDGE('',*,*,#135099,.F.); -#135099 = EDGE_CURVE('',#134335,#134442,#135100,.T.); -#135100 = SURFACE_CURVE('',#135101,(#135105,#135112),.PCURVE_S1.); -#135101 = LINE('',#135102,#135103); -#135102 = CARTESIAN_POINT('',(11.,1.65,1.159810404338E-002)); -#135103 = VECTOR('',#135104,1.); -#135104 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#135105 = PCURVE('',#92454,#135106); -#135106 = DEFINITIONAL_REPRESENTATION('',(#135107),#135111); -#135107 = LINE('',#135108,#135109); -#135108 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#135109 = VECTOR('',#135110,1.); -#135110 = DIRECTION('',(1.,-2.101748079665E-016)); -#135111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135112 = PCURVE('',#134355,#135113); -#135113 = DEFINITIONAL_REPRESENTATION('',(#135114),#135118); -#135114 = LINE('',#135115,#135116); -#135115 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#135116 = VECTOR('',#135117,1.); -#135117 = DIRECTION('',(-1.194699204908E-017,-1.)); -#135118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135119 = ORIENTED_EDGE('',*,*,#134417,.F.); -#135120 = ORIENTED_EDGE('',*,*,#134545,.F.); -#135121 = ORIENTED_EDGE('',*,*,#134853,.F.); -#135122 = ORIENTED_EDGE('',*,*,#134945,.F.); -#135123 = ORIENTED_EDGE('',*,*,#135124,.T.); -#135124 = EDGE_CURVE('',#134924,#92439,#135125,.T.); -#135125 = SURFACE_CURVE('',#135126,(#135130,#135137),.PCURVE_S1.); -#135126 = LINE('',#135127,#135128); -#135127 = CARTESIAN_POINT('',(10.527847992439,1.65,0.75)); -#135128 = VECTOR('',#135129,1.); -#135129 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135130 = PCURVE('',#92454,#135131); -#135131 = DEFINITIONAL_REPRESENTATION('',(#135132),#135136); -#135132 = LINE('',#135133,#135134); -#135133 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#135134 = VECTOR('',#135135,1.); -#135135 = DIRECTION('',(-3.563627120235E-016,-1.)); -#135136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135137 = PCURVE('',#92480,#135138); -#135138 = DEFINITIONAL_REPRESENTATION('',(#135139),#135143); -#135139 = LINE('',#135140,#135141); -#135140 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#135141 = VECTOR('',#135142,1.); -#135142 = DIRECTION('',(-1.,-1.082494723017E-063)); -#135143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135144 = ORIENTED_EDGE('',*,*,#92438,.F.); -#135145 = ADVANCED_FACE('',(#135146),#92480,.T.); -#135146 = FACE_BOUND('',#135147,.T.); -#135147 = EDGE_LOOP('',(#135148,#135149,#135150,#135171)); -#135148 = ORIENTED_EDGE('',*,*,#135124,.F.); -#135149 = ORIENTED_EDGE('',*,*,#134923,.T.); -#135150 = ORIENTED_EDGE('',*,*,#135151,.T.); -#135151 = EDGE_CURVE('',#134901,#92381,#135152,.T.); -#135152 = SURFACE_CURVE('',#135153,(#135157,#135164),.PCURVE_S1.); -#135153 = LINE('',#135154,#135155); -#135154 = CARTESIAN_POINT('',(10.527847992439,1.85,0.75)); -#135155 = VECTOR('',#135156,1.); -#135156 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135157 = PCURVE('',#92480,#135158); -#135158 = DEFINITIONAL_REPRESENTATION('',(#135159),#135163); -#135159 = LINE('',#135160,#135161); -#135160 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135161 = VECTOR('',#135162,1.); -#135162 = DIRECTION('',(-1.,-1.082494723017E-063)); -#135163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135164 = PCURVE('',#92398,#135165); -#135165 = DEFINITIONAL_REPRESENTATION('',(#135166),#135170); -#135166 = LINE('',#135167,#135168); -#135167 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#135168 = VECTOR('',#135169,1.); -#135169 = DIRECTION('',(3.563627120235E-016,-1.)); -#135170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135171 = ORIENTED_EDGE('',*,*,#92466,.F.); -#135172 = ADVANCED_FACE('',(#135173),#92398,.T.); -#135173 = FACE_BOUND('',#135174,.T.); -#135174 = EDGE_LOOP('',(#135175,#135176,#135177,#135178,#135179,#135180, - #135201,#135202,#135203,#135204,#135205,#135206)); -#135175 = ORIENTED_EDGE('',*,*,#135151,.F.); -#135176 = ORIENTED_EDGE('',*,*,#134900,.T.); -#135177 = ORIENTED_EDGE('',*,*,#134875,.T.); -#135178 = ORIENTED_EDGE('',*,*,#134595,.T.); -#135179 = ORIENTED_EDGE('',*,*,#134367,.T.); -#135180 = ORIENTED_EDGE('',*,*,#135181,.F.); -#135181 = EDGE_CURVE('',#134444,#134333,#135182,.T.); -#135182 = SURFACE_CURVE('',#135183,(#135187,#135194),.PCURVE_S1.); -#135183 = LINE('',#135184,#135185); -#135184 = CARTESIAN_POINT('',(11.,1.85,1.159810404338E-002)); -#135185 = VECTOR('',#135186,1.); -#135186 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#135187 = PCURVE('',#92398,#135188); -#135188 = DEFINITIONAL_REPRESENTATION('',(#135189),#135193); -#135189 = LINE('',#135190,#135191); -#135190 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#135191 = VECTOR('',#135192,1.); -#135192 = DIRECTION('',(1.,2.101748079665E-016)); -#135193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135194 = PCURVE('',#134355,#135195); -#135195 = DEFINITIONAL_REPRESENTATION('',(#135196),#135200); -#135196 = LINE('',#135197,#135198); -#135197 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#135198 = VECTOR('',#135199,1.); -#135199 = DIRECTION('',(1.194699204908E-017,1.)); -#135200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135201 = ORIENTED_EDGE('',*,*,#134521,.F.); -#135202 = ORIENTED_EDGE('',*,*,#134624,.F.); -#135203 = ORIENTED_EDGE('',*,*,#134778,.F.); -#135204 = ORIENTED_EDGE('',*,*,#134974,.F.); -#135205 = ORIENTED_EDGE('',*,*,#135047,.T.); -#135206 = ORIENTED_EDGE('',*,*,#92380,.F.); -#135207 = ADVANCED_FACE('',(#135208),#134355,.T.); -#135208 = FACE_BOUND('',#135209,.T.); -#135209 = EDGE_LOOP('',(#135210,#135211,#135212,#135213)); -#135210 = ORIENTED_EDGE('',*,*,#135099,.T.); -#135211 = ORIENTED_EDGE('',*,*,#134441,.T.); -#135212 = ORIENTED_EDGE('',*,*,#135181,.T.); -#135213 = ORIENTED_EDGE('',*,*,#134332,.T.); -#135214 = ADVANCED_FACE('',(#135215),#135229,.F.); -#135215 = FACE_BOUND('',#135216,.T.); -#135216 = EDGE_LOOP('',(#135217,#135252,#135275,#135302)); -#135217 = ORIENTED_EDGE('',*,*,#135218,.F.); -#135218 = EDGE_CURVE('',#135219,#135221,#135223,.T.); -#135219 = VERTEX_POINT('',#135220); -#135220 = CARTESIAN_POINT('',(11.,1.35,-0.208196358798)); -#135221 = VERTEX_POINT('',#135222); -#135222 = CARTESIAN_POINT('',(11.,1.15,-0.208196358798)); -#135223 = SURFACE_CURVE('',#135224,(#135228,#135240),.PCURVE_S1.); -#135224 = LINE('',#135225,#135226); -#135225 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) - ); -#135226 = VECTOR('',#135227,1.); -#135227 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135228 = PCURVE('',#135229,#135234); -#135229 = PLANE('',#135230); -#135230 = AXIS2_PLACEMENT_3D('',#135231,#135232,#135233); -#135231 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#137427 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#137428 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#137429 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#137430 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#137431 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#137432 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#137433 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#137434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137435 = ADVANCED_FACE('',(#137436),#94818,.T.); +#137436 = FACE_BOUND('',#137437,.T.); +#137437 = EDGE_LOOP('',(#137438,#137459,#137460,#137481)); +#137438 = ORIENTED_EDGE('',*,*,#137439,.F.); +#137439 = EDGE_CURVE('',#137367,#94775,#137440,.T.); +#137440 = SURFACE_CURVE('',#137441,(#137445,#137452),.PCURVE_S1.); +#137441 = LINE('',#137442,#137443); +#137442 = CARTESIAN_POINT('',(10.527847992439,1.85,0.65)); +#137443 = VECTOR('',#137444,1.); +#137444 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#137445 = PCURVE('',#94818,#137446); +#137446 = DEFINITIONAL_REPRESENTATION('',(#137447),#137451); +#137447 = LINE('',#137448,#137449); +#137448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137449 = VECTOR('',#137450,1.); +#137450 = DIRECTION('',(1.,-1.082494723017E-063)); +#137451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137452 = PCURVE('',#94790,#137453); +#137453 = DEFINITIONAL_REPRESENTATION('',(#137454),#137458); +#137454 = LINE('',#137455,#137456); +#137455 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137456 = VECTOR('',#137457,1.); +#137457 = DIRECTION('',(3.563627120235E-016,-1.)); +#137458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137459 = ORIENTED_EDGE('',*,*,#137389,.T.); +#137460 = ORIENTED_EDGE('',*,*,#137461,.T.); +#137461 = EDGE_CURVE('',#137390,#94803,#137462,.T.); +#137462 = SURFACE_CURVE('',#137463,(#137467,#137474),.PCURVE_S1.); +#137463 = LINE('',#137464,#137465); +#137464 = CARTESIAN_POINT('',(10.527847992439,1.65,0.65)); +#137465 = VECTOR('',#137466,1.); +#137466 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#137467 = PCURVE('',#94818,#137468); +#137468 = DEFINITIONAL_REPRESENTATION('',(#137469),#137473); +#137469 = LINE('',#137470,#137471); +#137470 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#137471 = VECTOR('',#137472,1.); +#137472 = DIRECTION('',(1.,-1.082494723017E-063)); +#137473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137474 = PCURVE('',#94846,#137475); +#137475 = DEFINITIONAL_REPRESENTATION('',(#137476),#137480); +#137476 = LINE('',#137477,#137478); +#137477 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137478 = VECTOR('',#137479,1.); +#137479 = DIRECTION('',(-3.563627120235E-016,-1.)); +#137480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137481 = ORIENTED_EDGE('',*,*,#94802,.F.); +#137482 = ADVANCED_FACE('',(#137483),#94846,.T.); +#137483 = FACE_BOUND('',#137484,.T.); +#137484 = EDGE_LOOP('',(#137485,#137486,#137487,#137488,#137489,#137490, + #137511,#137512,#137513,#137514,#137515,#137536)); +#137485 = ORIENTED_EDGE('',*,*,#137461,.F.); +#137486 = ORIENTED_EDGE('',*,*,#137411,.T.); +#137487 = ORIENTED_EDGE('',*,*,#137192,.T.); +#137488 = ORIENTED_EDGE('',*,*,#137067,.T.); +#137489 = ORIENTED_EDGE('',*,*,#136863,.T.); +#137490 = ORIENTED_EDGE('',*,*,#137491,.F.); +#137491 = EDGE_CURVE('',#136727,#136834,#137492,.T.); +#137492 = SURFACE_CURVE('',#137493,(#137497,#137504),.PCURVE_S1.); +#137493 = LINE('',#137494,#137495); +#137494 = CARTESIAN_POINT('',(11.,1.65,1.159810404338E-002)); +#137495 = VECTOR('',#137496,1.); +#137496 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#137497 = PCURVE('',#94846,#137498); +#137498 = DEFINITIONAL_REPRESENTATION('',(#137499),#137503); +#137499 = LINE('',#137500,#137501); +#137500 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#137501 = VECTOR('',#137502,1.); +#137502 = DIRECTION('',(1.,-2.101748079665E-016)); +#137503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137504 = PCURVE('',#136747,#137505); +#137505 = DEFINITIONAL_REPRESENTATION('',(#137506),#137510); +#137506 = LINE('',#137507,#137508); +#137507 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#137508 = VECTOR('',#137509,1.); +#137509 = DIRECTION('',(-1.194699204908E-017,-1.)); +#137510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137511 = ORIENTED_EDGE('',*,*,#136809,.F.); +#137512 = ORIENTED_EDGE('',*,*,#136937,.F.); +#137513 = ORIENTED_EDGE('',*,*,#137245,.F.); +#137514 = ORIENTED_EDGE('',*,*,#137337,.F.); +#137515 = ORIENTED_EDGE('',*,*,#137516,.T.); +#137516 = EDGE_CURVE('',#137316,#94831,#137517,.T.); +#137517 = SURFACE_CURVE('',#137518,(#137522,#137529),.PCURVE_S1.); +#137518 = LINE('',#137519,#137520); +#137519 = CARTESIAN_POINT('',(10.527847992439,1.65,0.75)); +#137520 = VECTOR('',#137521,1.); +#137521 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#137522 = PCURVE('',#94846,#137523); +#137523 = DEFINITIONAL_REPRESENTATION('',(#137524),#137528); +#137524 = LINE('',#137525,#137526); +#137525 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#137526 = VECTOR('',#137527,1.); +#137527 = DIRECTION('',(-3.563627120235E-016,-1.)); +#137528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137529 = PCURVE('',#94872,#137530); +#137530 = DEFINITIONAL_REPRESENTATION('',(#137531),#137535); +#137531 = LINE('',#137532,#137533); +#137532 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#137533 = VECTOR('',#137534,1.); +#137534 = DIRECTION('',(-1.,-1.082494723017E-063)); +#137535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137536 = ORIENTED_EDGE('',*,*,#94830,.F.); +#137537 = ADVANCED_FACE('',(#137538),#94872,.T.); +#137538 = FACE_BOUND('',#137539,.T.); +#137539 = EDGE_LOOP('',(#137540,#137541,#137542,#137563)); +#137540 = ORIENTED_EDGE('',*,*,#137516,.F.); +#137541 = ORIENTED_EDGE('',*,*,#137315,.T.); +#137542 = ORIENTED_EDGE('',*,*,#137543,.T.); +#137543 = EDGE_CURVE('',#137293,#94773,#137544,.T.); +#137544 = SURFACE_CURVE('',#137545,(#137549,#137556),.PCURVE_S1.); +#137545 = LINE('',#137546,#137547); +#137546 = CARTESIAN_POINT('',(10.527847992439,1.85,0.75)); +#137547 = VECTOR('',#137548,1.); +#137548 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#137549 = PCURVE('',#94872,#137550); +#137550 = DEFINITIONAL_REPRESENTATION('',(#137551),#137555); +#137551 = LINE('',#137552,#137553); +#137552 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137553 = VECTOR('',#137554,1.); +#137554 = DIRECTION('',(-1.,-1.082494723017E-063)); +#137555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137556 = PCURVE('',#94790,#137557); +#137557 = DEFINITIONAL_REPRESENTATION('',(#137558),#137562); +#137558 = LINE('',#137559,#137560); +#137559 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#137560 = VECTOR('',#137561,1.); +#137561 = DIRECTION('',(3.563627120235E-016,-1.)); +#137562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137563 = ORIENTED_EDGE('',*,*,#94858,.F.); +#137564 = ADVANCED_FACE('',(#137565),#94790,.T.); +#137565 = FACE_BOUND('',#137566,.T.); +#137566 = EDGE_LOOP('',(#137567,#137568,#137569,#137570,#137571,#137572, + #137593,#137594,#137595,#137596,#137597,#137598)); +#137567 = ORIENTED_EDGE('',*,*,#137543,.F.); +#137568 = ORIENTED_EDGE('',*,*,#137292,.T.); +#137569 = ORIENTED_EDGE('',*,*,#137267,.T.); +#137570 = ORIENTED_EDGE('',*,*,#136987,.T.); +#137571 = ORIENTED_EDGE('',*,*,#136759,.T.); +#137572 = ORIENTED_EDGE('',*,*,#137573,.F.); +#137573 = EDGE_CURVE('',#136836,#136725,#137574,.T.); +#137574 = SURFACE_CURVE('',#137575,(#137579,#137586),.PCURVE_S1.); +#137575 = LINE('',#137576,#137577); +#137576 = CARTESIAN_POINT('',(11.,1.85,1.159810404338E-002)); +#137577 = VECTOR('',#137578,1.); +#137578 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#137579 = PCURVE('',#94790,#137580); +#137580 = DEFINITIONAL_REPRESENTATION('',(#137581),#137585); +#137581 = LINE('',#137582,#137583); +#137582 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#137583 = VECTOR('',#137584,1.); +#137584 = DIRECTION('',(1.,2.101748079665E-016)); +#137585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137586 = PCURVE('',#136747,#137587); +#137587 = DEFINITIONAL_REPRESENTATION('',(#137588),#137592); +#137588 = LINE('',#137589,#137590); +#137589 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#137590 = VECTOR('',#137591,1.); +#137591 = DIRECTION('',(1.194699204908E-017,1.)); +#137592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137593 = ORIENTED_EDGE('',*,*,#136913,.F.); +#137594 = ORIENTED_EDGE('',*,*,#137016,.F.); +#137595 = ORIENTED_EDGE('',*,*,#137170,.F.); +#137596 = ORIENTED_EDGE('',*,*,#137366,.F.); +#137597 = ORIENTED_EDGE('',*,*,#137439,.T.); +#137598 = ORIENTED_EDGE('',*,*,#94772,.F.); +#137599 = ADVANCED_FACE('',(#137600),#136747,.T.); +#137600 = FACE_BOUND('',#137601,.T.); +#137601 = EDGE_LOOP('',(#137602,#137603,#137604,#137605)); +#137602 = ORIENTED_EDGE('',*,*,#137491,.T.); +#137603 = ORIENTED_EDGE('',*,*,#136833,.T.); +#137604 = ORIENTED_EDGE('',*,*,#137573,.T.); +#137605 = ORIENTED_EDGE('',*,*,#136724,.T.); +#137606 = ADVANCED_FACE('',(#137607),#137621,.F.); +#137607 = FACE_BOUND('',#137608,.T.); +#137608 = EDGE_LOOP('',(#137609,#137644,#137667,#137694)); +#137609 = ORIENTED_EDGE('',*,*,#137610,.F.); +#137610 = EDGE_CURVE('',#137611,#137613,#137615,.T.); +#137611 = VERTEX_POINT('',#137612); +#137612 = CARTESIAN_POINT('',(11.,1.35,-0.208196358798)); +#137613 = VERTEX_POINT('',#137614); +#137614 = CARTESIAN_POINT('',(11.,1.15,-0.208196358798)); +#137615 = SURFACE_CURVE('',#137616,(#137620,#137632),.PCURVE_S1.); +#137616 = LINE('',#137617,#137618); +#137617 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.208196358798) + ); +#137618 = VECTOR('',#137619,1.); +#137619 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137620 = PCURVE('',#137621,#137626); +#137621 = PLANE('',#137622); +#137622 = AXIS2_PLACEMENT_3D('',#137623,#137624,#137625); +#137623 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#135232 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#135233 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#135234 = DEFINITIONAL_REPRESENTATION('',(#135235),#135239); -#135235 = LINE('',#135236,#135237); -#135236 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); -#135237 = VECTOR('',#135238,1.); -#135238 = DIRECTION('',(4.440892098501E-016,-1.)); -#135239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135240 = PCURVE('',#135241,#135246); -#135241 = PLANE('',#135242); -#135242 = AXIS2_PLACEMENT_3D('',#135243,#135244,#135245); -#135243 = CARTESIAN_POINT('',(11.,1.25,-0.258196742327)); -#135244 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); -#135245 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135246 = DEFINITIONAL_REPRESENTATION('',(#135247),#135251); -#135247 = LINE('',#135248,#135249); -#135248 = CARTESIAN_POINT('',(-1.25,5.00003835295E-002)); -#135249 = VECTOR('',#135250,1.); -#135250 = DIRECTION('',(-1.,0.E+000)); -#135251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135252 = ORIENTED_EDGE('',*,*,#135253,.F.); -#135253 = EDGE_CURVE('',#135254,#135219,#135256,.T.); -#135254 = VERTEX_POINT('',#135255); -#135255 = CARTESIAN_POINT('',(10.740726081328,1.35,-0.208196358798)); -#135256 = SURFACE_CURVE('',#135257,(#135261,#135268),.PCURVE_S1.); -#135257 = LINE('',#135258,#135259); -#135258 = CARTESIAN_POINT('',(10.740726081328,1.35,-0.208196358798)); -#135259 = VECTOR('',#135260,1.); -#135260 = DIRECTION('',(1.,0.E+000,0.E+000)); -#135261 = PCURVE('',#135229,#135262); -#135262 = DEFINITIONAL_REPRESENTATION('',(#135263),#135267); -#135263 = LINE('',#135264,#135265); -#135264 = CARTESIAN_POINT('',(-1.7763568394E-015,1.35)); -#135265 = VECTOR('',#135266,1.); -#135266 = DIRECTION('',(-1.,0.E+000)); -#135267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135268 = PCURVE('',#92284,#135269); -#135269 = DEFINITIONAL_REPRESENTATION('',(#135270),#135274); -#135270 = LINE('',#135271,#135272); -#135271 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#135272 = VECTOR('',#135273,1.); -#135273 = DIRECTION('',(0.E+000,1.)); -#135274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135275 = ORIENTED_EDGE('',*,*,#135276,.F.); -#135276 = EDGE_CURVE('',#135277,#135254,#135279,.T.); -#135277 = VERTEX_POINT('',#135278); -#135278 = CARTESIAN_POINT('',(10.740726081328,1.15,-0.208196358798)); -#135279 = SURFACE_CURVE('',#135280,(#135284,#135291),.PCURVE_S1.); -#135280 = LINE('',#135281,#135282); -#135281 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, +#137624 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#137625 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#137626 = DEFINITIONAL_REPRESENTATION('',(#137627),#137631); +#137627 = LINE('',#137628,#137629); +#137628 = CARTESIAN_POINT('',(-0.259273918672,-1.151407496779E-016)); +#137629 = VECTOR('',#137630,1.); +#137630 = DIRECTION('',(4.440892098501E-016,-1.)); +#137631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137632 = PCURVE('',#137633,#137638); +#137633 = PLANE('',#137634); +#137634 = AXIS2_PLACEMENT_3D('',#137635,#137636,#137637); +#137635 = CARTESIAN_POINT('',(11.,1.25,-0.258196742327)); +#137636 = DIRECTION('',(1.,-4.440892098501E-016,-2.101748079665E-016)); +#137637 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137638 = DEFINITIONAL_REPRESENTATION('',(#137639),#137643); +#137639 = LINE('',#137640,#137641); +#137640 = CARTESIAN_POINT('',(-1.25,5.00003835295E-002)); +#137641 = VECTOR('',#137642,1.); +#137642 = DIRECTION('',(-1.,0.E+000)); +#137643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137644 = ORIENTED_EDGE('',*,*,#137645,.F.); +#137645 = EDGE_CURVE('',#137646,#137611,#137648,.T.); +#137646 = VERTEX_POINT('',#137647); +#137647 = CARTESIAN_POINT('',(10.740726081328,1.35,-0.208196358798)); +#137648 = SURFACE_CURVE('',#137649,(#137653,#137660),.PCURVE_S1.); +#137649 = LINE('',#137650,#137651); +#137650 = CARTESIAN_POINT('',(10.740726081328,1.35,-0.208196358798)); +#137651 = VECTOR('',#137652,1.); +#137652 = DIRECTION('',(1.,0.E+000,0.E+000)); +#137653 = PCURVE('',#137621,#137654); +#137654 = DEFINITIONAL_REPRESENTATION('',(#137655),#137659); +#137655 = LINE('',#137656,#137657); +#137656 = CARTESIAN_POINT('',(-1.7763568394E-015,1.35)); +#137657 = VECTOR('',#137658,1.); +#137658 = DIRECTION('',(-1.,0.E+000)); +#137659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137660 = PCURVE('',#94676,#137661); +#137661 = DEFINITIONAL_REPRESENTATION('',(#137662),#137666); +#137662 = LINE('',#137663,#137664); +#137663 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#137664 = VECTOR('',#137665,1.); +#137665 = DIRECTION('',(0.E+000,1.)); +#137666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137667 = ORIENTED_EDGE('',*,*,#137668,.F.); +#137668 = EDGE_CURVE('',#137669,#137646,#137671,.T.); +#137669 = VERTEX_POINT('',#137670); +#137670 = CARTESIAN_POINT('',(10.740726081328,1.15,-0.208196358798)); +#137671 = SURFACE_CURVE('',#137672,(#137676,#137683),.PCURVE_S1.); +#137672 = LINE('',#137673,#137674); +#137673 = CARTESIAN_POINT('',(10.740726081328,-3.475023471251E-015, -0.208196358798)); -#135282 = VECTOR('',#135283,1.); -#135283 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135284 = PCURVE('',#135229,#135285); -#135285 = DEFINITIONAL_REPRESENTATION('',(#135286),#135290); -#135286 = LINE('',#135287,#135288); -#135287 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135288 = VECTOR('',#135289,1.); -#135289 = DIRECTION('',(-4.440892098501E-016,1.)); -#135290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135291 = PCURVE('',#135292,#135297); -#135292 = CYLINDRICAL_SURFACE('',#135293,0.208574704164); -#135293 = AXIS2_PLACEMENT_3D('',#135294,#135295,#135296); -#135294 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#137674 = VECTOR('',#137675,1.); +#137675 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137676 = PCURVE('',#137621,#137677); +#137677 = DEFINITIONAL_REPRESENTATION('',(#137678),#137682); +#137678 = LINE('',#137679,#137680); +#137679 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137680 = VECTOR('',#137681,1.); +#137681 = DIRECTION('',(-4.440892098501E-016,1.)); +#137682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137683 = PCURVE('',#137684,#137689); +#137684 = CYLINDRICAL_SURFACE('',#137685,0.208574704164); +#137685 = AXIS2_PLACEMENT_3D('',#137686,#137687,#137688); +#137686 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#135295 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135296 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135297 = DEFINITIONAL_REPRESENTATION('',(#135298),#135301); -#135298 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135299,#135300), +#137687 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137688 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137689 = DEFINITIONAL_REPRESENTATION('',(#137690),#137693); +#137690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137691,#137692), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#135299 = CARTESIAN_POINT('',(4.772630242227,-1.15)); -#135300 = CARTESIAN_POINT('',(4.772630242227,-1.35)); -#135301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135302 = ORIENTED_EDGE('',*,*,#135303,.T.); -#135303 = EDGE_CURVE('',#135277,#135221,#135304,.T.); -#135304 = SURFACE_CURVE('',#135305,(#135309,#135316),.PCURVE_S1.); -#135305 = LINE('',#135306,#135307); -#135306 = CARTESIAN_POINT('',(10.740726081328,1.15,-0.208196358798)); -#135307 = VECTOR('',#135308,1.); -#135308 = DIRECTION('',(1.,0.E+000,0.E+000)); -#135309 = PCURVE('',#135229,#135310); -#135310 = DEFINITIONAL_REPRESENTATION('',(#135311),#135315); -#135311 = LINE('',#135312,#135313); -#135312 = CARTESIAN_POINT('',(0.E+000,1.15)); -#135313 = VECTOR('',#135314,1.); -#135314 = DIRECTION('',(-1.,0.E+000)); -#135315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135316 = PCURVE('',#92340,#135317); -#135317 = DEFINITIONAL_REPRESENTATION('',(#135318),#135322); -#135318 = LINE('',#135319,#135320); -#135319 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#135320 = VECTOR('',#135321,1.); -#135321 = DIRECTION('',(0.E+000,1.)); -#135322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135323 = ADVANCED_FACE('',(#135324),#135338,.F.); -#135324 = FACE_BOUND('',#135325,.T.); -#135325 = EDGE_LOOP('',(#135326,#135356,#135379,#135406)); -#135326 = ORIENTED_EDGE('',*,*,#135327,.F.); -#135327 = EDGE_CURVE('',#135328,#135330,#135332,.T.); -#135328 = VERTEX_POINT('',#135329); -#135329 = CARTESIAN_POINT('',(11.,1.15,-0.308197125857)); -#135330 = VERTEX_POINT('',#135331); -#135331 = CARTESIAN_POINT('',(11.,1.35,-0.308197125857)); -#135332 = SURFACE_CURVE('',#135333,(#135337,#135349),.PCURVE_S1.); -#135333 = LINE('',#135334,#135335); -#135334 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) - ); -#135335 = VECTOR('',#135336,1.); -#135336 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135337 = PCURVE('',#135338,#135343); -#135338 = PLANE('',#135339); -#135339 = AXIS2_PLACEMENT_3D('',#135340,#135341,#135342); -#135340 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#137691 = CARTESIAN_POINT('',(4.772630242227,-1.15)); +#137692 = CARTESIAN_POINT('',(4.772630242227,-1.35)); +#137693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137694 = ORIENTED_EDGE('',*,*,#137695,.T.); +#137695 = EDGE_CURVE('',#137669,#137613,#137696,.T.); +#137696 = SURFACE_CURVE('',#137697,(#137701,#137708),.PCURVE_S1.); +#137697 = LINE('',#137698,#137699); +#137698 = CARTESIAN_POINT('',(10.740726081328,1.15,-0.208196358798)); +#137699 = VECTOR('',#137700,1.); +#137700 = DIRECTION('',(1.,0.E+000,0.E+000)); +#137701 = PCURVE('',#137621,#137702); +#137702 = DEFINITIONAL_REPRESENTATION('',(#137703),#137707); +#137703 = LINE('',#137704,#137705); +#137704 = CARTESIAN_POINT('',(0.E+000,1.15)); +#137705 = VECTOR('',#137706,1.); +#137706 = DIRECTION('',(-1.,0.E+000)); +#137707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137708 = PCURVE('',#94732,#137709); +#137709 = DEFINITIONAL_REPRESENTATION('',(#137710),#137714); +#137710 = LINE('',#137711,#137712); +#137711 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#137712 = VECTOR('',#137713,1.); +#137713 = DIRECTION('',(0.E+000,1.)); +#137714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137715 = ADVANCED_FACE('',(#137716),#137730,.F.); +#137716 = FACE_BOUND('',#137717,.T.); +#137717 = EDGE_LOOP('',(#137718,#137748,#137771,#137798)); +#137718 = ORIENTED_EDGE('',*,*,#137719,.F.); +#137719 = EDGE_CURVE('',#137720,#137722,#137724,.T.); +#137720 = VERTEX_POINT('',#137721); +#137721 = CARTESIAN_POINT('',(11.,1.15,-0.308197125857)); +#137722 = VERTEX_POINT('',#137723); +#137723 = CARTESIAN_POINT('',(11.,1.35,-0.308197125857)); +#137724 = SURFACE_CURVE('',#137725,(#137729,#137741),.PCURVE_S1.); +#137725 = LINE('',#137726,#137727); +#137726 = CARTESIAN_POINT('',(11.,-3.590164220928E-015,-0.308197125857) + ); +#137727 = VECTOR('',#137728,1.); +#137728 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137729 = PCURVE('',#137730,#137735); +#137730 = PLANE('',#137731); +#137731 = AXIS2_PLACEMENT_3D('',#137732,#137733,#137734); +#137732 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#135341 = DIRECTION('',(0.E+000,0.E+000,1.)); -#135342 = DIRECTION('',(1.,0.E+000,0.E+000)); -#135343 = DEFINITIONAL_REPRESENTATION('',(#135344),#135348); -#135344 = LINE('',#135345,#135346); -#135345 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); -#135346 = VECTOR('',#135347,1.); -#135347 = DIRECTION('',(4.440892098501E-016,1.)); -#135348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135349 = PCURVE('',#135241,#135350); -#135350 = DEFINITIONAL_REPRESENTATION('',(#135351),#135355); -#135351 = LINE('',#135352,#135353); -#135352 = CARTESIAN_POINT('',(-1.25,-5.000038352949E-002)); -#135353 = VECTOR('',#135354,1.); -#135354 = DIRECTION('',(1.,0.E+000)); -#135355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135356 = ORIENTED_EDGE('',*,*,#135357,.F.); -#135357 = EDGE_CURVE('',#135358,#135328,#135360,.T.); -#135358 = VERTEX_POINT('',#135359); -#135359 = CARTESIAN_POINT('',(10.74341632541,1.15,-0.308197125857)); -#135360 = SURFACE_CURVE('',#135361,(#135365,#135372),.PCURVE_S1.); -#135361 = LINE('',#135362,#135363); -#135362 = CARTESIAN_POINT('',(10.74341632541,1.15,-0.308197125857)); -#135363 = VECTOR('',#135364,1.); -#135364 = DIRECTION('',(1.,0.E+000,0.E+000)); -#135365 = PCURVE('',#135338,#135366); -#135366 = DEFINITIONAL_REPRESENTATION('',(#135367),#135371); -#135367 = LINE('',#135368,#135369); -#135368 = CARTESIAN_POINT('',(0.E+000,1.15)); -#135369 = VECTOR('',#135370,1.); -#135370 = DIRECTION('',(1.,0.E+000)); -#135371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135372 = PCURVE('',#92340,#135373); -#135373 = DEFINITIONAL_REPRESENTATION('',(#135374),#135378); -#135374 = LINE('',#135375,#135376); -#135375 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#135376 = VECTOR('',#135377,1.); -#135377 = DIRECTION('',(0.E+000,1.)); -#135378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135379 = ORIENTED_EDGE('',*,*,#135380,.F.); -#135380 = EDGE_CURVE('',#135381,#135358,#135383,.T.); -#135381 = VERTEX_POINT('',#135382); -#135382 = CARTESIAN_POINT('',(10.74341632541,1.35,-0.308197125857)); -#135383 = SURFACE_CURVE('',#135384,(#135388,#135395),.PCURVE_S1.); -#135384 = LINE('',#135385,#135386); -#135385 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, +#137733 = DIRECTION('',(0.E+000,0.E+000,1.)); +#137734 = DIRECTION('',(1.,0.E+000,0.E+000)); +#137735 = DEFINITIONAL_REPRESENTATION('',(#137736),#137740); +#137736 = LINE('',#137737,#137738); +#137737 = CARTESIAN_POINT('',(0.25658367459,-1.139460413089E-016)); +#137738 = VECTOR('',#137739,1.); +#137739 = DIRECTION('',(4.440892098501E-016,1.)); +#137740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137741 = PCURVE('',#137633,#137742); +#137742 = DEFINITIONAL_REPRESENTATION('',(#137743),#137747); +#137743 = LINE('',#137744,#137745); +#137744 = CARTESIAN_POINT('',(-1.25,-5.000038352949E-002)); +#137745 = VECTOR('',#137746,1.); +#137746 = DIRECTION('',(1.,0.E+000)); +#137747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137748 = ORIENTED_EDGE('',*,*,#137749,.F.); +#137749 = EDGE_CURVE('',#137750,#137720,#137752,.T.); +#137750 = VERTEX_POINT('',#137751); +#137751 = CARTESIAN_POINT('',(10.74341632541,1.15,-0.308197125857)); +#137752 = SURFACE_CURVE('',#137753,(#137757,#137764),.PCURVE_S1.); +#137753 = LINE('',#137754,#137755); +#137754 = CARTESIAN_POINT('',(10.74341632541,1.15,-0.308197125857)); +#137755 = VECTOR('',#137756,1.); +#137756 = DIRECTION('',(1.,0.E+000,0.E+000)); +#137757 = PCURVE('',#137730,#137758); +#137758 = DEFINITIONAL_REPRESENTATION('',(#137759),#137763); +#137759 = LINE('',#137760,#137761); +#137760 = CARTESIAN_POINT('',(0.E+000,1.15)); +#137761 = VECTOR('',#137762,1.); +#137762 = DIRECTION('',(1.,0.E+000)); +#137763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137764 = PCURVE('',#94732,#137765); +#137765 = DEFINITIONAL_REPRESENTATION('',(#137766),#137770); +#137766 = LINE('',#137767,#137768); +#137767 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#137768 = VECTOR('',#137769,1.); +#137769 = DIRECTION('',(0.E+000,1.)); +#137770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137771 = ORIENTED_EDGE('',*,*,#137772,.F.); +#137772 = EDGE_CURVE('',#137773,#137750,#137775,.T.); +#137773 = VERTEX_POINT('',#137774); +#137774 = CARTESIAN_POINT('',(10.74341632541,1.35,-0.308197125857)); +#137775 = SURFACE_CURVE('',#137776,(#137780,#137787),.PCURVE_S1.); +#137776 = LINE('',#137777,#137778); +#137777 = CARTESIAN_POINT('',(10.74341632541,-3.47621817962E-015, -0.308197125857)); -#135386 = VECTOR('',#135387,1.); -#135387 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135388 = PCURVE('',#135338,#135389); -#135389 = DEFINITIONAL_REPRESENTATION('',(#135390),#135394); -#135390 = LINE('',#135391,#135392); -#135391 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135392 = VECTOR('',#135393,1.); -#135393 = DIRECTION('',(-4.440892098501E-016,-1.)); -#135394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135395 = PCURVE('',#135396,#135401); -#135396 = CYLINDRICAL_SURFACE('',#135397,0.308574064194); -#135397 = AXIS2_PLACEMENT_3D('',#135398,#135399,#135400); -#135398 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, +#137778 = VECTOR('',#137779,1.); +#137779 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137780 = PCURVE('',#137730,#137781); +#137781 = DEFINITIONAL_REPRESENTATION('',(#137782),#137786); +#137782 = LINE('',#137783,#137784); +#137783 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#137784 = VECTOR('',#137785,1.); +#137785 = DIRECTION('',(-4.440892098501E-016,-1.)); +#137786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137787 = PCURVE('',#137788,#137793); +#137788 = CYLINDRICAL_SURFACE('',#137789,0.308574064194); +#137789 = AXIS2_PLACEMENT_3D('',#137790,#137791,#137792); +#137790 = CARTESIAN_POINT('',(10.728168876214,-3.469446951954E-015, 2.640924866458E-017)); -#135399 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135400 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135401 = DEFINITIONAL_REPRESENTATION('',(#135402),#135405); -#135402 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135403,#135404), +#137791 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137792 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137793 = DEFINITIONAL_REPRESENTATION('',(#137794),#137797); +#137794 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137795,#137796), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#135403 = CARTESIAN_POINT('',(4.761821717947,-1.35)); -#135404 = CARTESIAN_POINT('',(4.761821717947,-1.15)); -#135405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135406 = ORIENTED_EDGE('',*,*,#135407,.T.); -#135407 = EDGE_CURVE('',#135381,#135330,#135408,.T.); -#135408 = SURFACE_CURVE('',#135409,(#135413,#135420),.PCURVE_S1.); -#135409 = LINE('',#135410,#135411); -#135410 = CARTESIAN_POINT('',(10.74341632541,1.35,-0.308197125857)); -#135411 = VECTOR('',#135412,1.); -#135412 = DIRECTION('',(1.,0.E+000,0.E+000)); -#135413 = PCURVE('',#135338,#135414); -#135414 = DEFINITIONAL_REPRESENTATION('',(#135415),#135419); -#135415 = LINE('',#135416,#135417); -#135416 = CARTESIAN_POINT('',(0.E+000,1.35)); -#135417 = VECTOR('',#135418,1.); -#135418 = DIRECTION('',(1.,0.E+000)); -#135419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135420 = PCURVE('',#92284,#135421); -#135421 = DEFINITIONAL_REPRESENTATION('',(#135422),#135426); -#135422 = LINE('',#135423,#135424); -#135423 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#135424 = VECTOR('',#135425,1.); -#135425 = DIRECTION('',(0.E+000,1.)); -#135426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135427 = ADVANCED_FACE('',(#135428),#135292,.F.); -#135428 = FACE_BOUND('',#135429,.F.); -#135429 = EDGE_LOOP('',(#135430,#135453,#135480,#135505)); -#135430 = ORIENTED_EDGE('',*,*,#135431,.F.); -#135431 = EDGE_CURVE('',#135432,#135277,#135434,.T.); -#135432 = VERTEX_POINT('',#135433); -#135433 = CARTESIAN_POINT('',(10.51959417205,1.15,0.E+000)); -#135434 = SURFACE_CURVE('',#135435,(#135440,#135446),.PCURVE_S1.); -#135435 = CIRCLE('',#135436,0.208574704164); -#135436 = AXIS2_PLACEMENT_3D('',#135437,#135438,#135439); -#135437 = CARTESIAN_POINT('',(10.728168876214,1.15,2.640924866458E-017) - ); -#135438 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135439 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135440 = PCURVE('',#135292,#135441); -#135441 = DEFINITIONAL_REPRESENTATION('',(#135442),#135445); -#135442 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135443,#135444), +#137795 = CARTESIAN_POINT('',(4.761821717947,-1.35)); +#137796 = CARTESIAN_POINT('',(4.761821717947,-1.15)); +#137797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137798 = ORIENTED_EDGE('',*,*,#137799,.T.); +#137799 = EDGE_CURVE('',#137773,#137722,#137800,.T.); +#137800 = SURFACE_CURVE('',#137801,(#137805,#137812),.PCURVE_S1.); +#137801 = LINE('',#137802,#137803); +#137802 = CARTESIAN_POINT('',(10.74341632541,1.35,-0.308197125857)); +#137803 = VECTOR('',#137804,1.); +#137804 = DIRECTION('',(1.,0.E+000,0.E+000)); +#137805 = PCURVE('',#137730,#137806); +#137806 = DEFINITIONAL_REPRESENTATION('',(#137807),#137811); +#137807 = LINE('',#137808,#137809); +#137808 = CARTESIAN_POINT('',(0.E+000,1.35)); +#137809 = VECTOR('',#137810,1.); +#137810 = DIRECTION('',(1.,0.E+000)); +#137811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137812 = PCURVE('',#94676,#137813); +#137813 = DEFINITIONAL_REPRESENTATION('',(#137814),#137818); +#137814 = LINE('',#137815,#137816); +#137815 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#137816 = VECTOR('',#137817,1.); +#137817 = DIRECTION('',(0.E+000,1.)); +#137818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137819 = ADVANCED_FACE('',(#137820),#137684,.F.); +#137820 = FACE_BOUND('',#137821,.F.); +#137821 = EDGE_LOOP('',(#137822,#137845,#137872,#137897)); +#137822 = ORIENTED_EDGE('',*,*,#137823,.F.); +#137823 = EDGE_CURVE('',#137824,#137669,#137826,.T.); +#137824 = VERTEX_POINT('',#137825); +#137825 = CARTESIAN_POINT('',(10.51959417205,1.15,0.E+000)); +#137826 = SURFACE_CURVE('',#137827,(#137832,#137838),.PCURVE_S1.); +#137827 = CIRCLE('',#137828,0.208574704164); +#137828 = AXIS2_PLACEMENT_3D('',#137829,#137830,#137831); +#137829 = CARTESIAN_POINT('',(10.728168876214,1.15,2.640924866458E-017) + ); +#137830 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137831 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137832 = PCURVE('',#137684,#137833); +#137833 = DEFINITIONAL_REPRESENTATION('',(#137834),#137837); +#137834 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137835,#137836), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#135443 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#135444 = CARTESIAN_POINT('',(4.772630242227,-1.15)); -#135445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137835 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#137836 = CARTESIAN_POINT('',(4.772630242227,-1.15)); +#137837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135446 = PCURVE('',#92340,#135447); -#135447 = DEFINITIONAL_REPRESENTATION('',(#135448),#135452); -#135448 = CIRCLE('',#135449,0.208574704164); -#135449 = AXIS2_PLACEMENT_2D('',#135450,#135451); -#135450 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#135451 = DIRECTION('',(0.E+000,1.)); -#135452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137838 = PCURVE('',#94732,#137839); +#137839 = DEFINITIONAL_REPRESENTATION('',(#137840),#137844); +#137840 = CIRCLE('',#137841,0.208574704164); +#137841 = AXIS2_PLACEMENT_2D('',#137842,#137843); +#137842 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#137843 = DIRECTION('',(0.E+000,1.)); +#137844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135453 = ORIENTED_EDGE('',*,*,#135454,.F.); -#135454 = EDGE_CURVE('',#135455,#135432,#135457,.T.); -#135455 = VERTEX_POINT('',#135456); -#135456 = CARTESIAN_POINT('',(10.51959417205,1.35,0.E+000)); -#135457 = SURFACE_CURVE('',#135458,(#135462,#135468),.PCURVE_S1.); -#135458 = LINE('',#135459,#135460); -#135459 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#137845 = ORIENTED_EDGE('',*,*,#137846,.F.); +#137846 = EDGE_CURVE('',#137847,#137824,#137849,.T.); +#137847 = VERTEX_POINT('',#137848); +#137848 = CARTESIAN_POINT('',(10.51959417205,1.35,0.E+000)); +#137849 = SURFACE_CURVE('',#137850,(#137854,#137860),.PCURVE_S1.); +#137850 = LINE('',#137851,#137852); +#137851 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.E+000)); -#135460 = VECTOR('',#135461,1.); -#135461 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135462 = PCURVE('',#135292,#135463); -#135463 = DEFINITIONAL_REPRESENTATION('',(#135464),#135467); -#135464 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135465,#135466), +#137852 = VECTOR('',#137853,1.); +#137853 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137854 = PCURVE('',#137684,#137855); +#137855 = DEFINITIONAL_REPRESENTATION('',(#137856),#137859); +#137856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137857,#137858), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#135465 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#135466 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#135467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137857 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#137858 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#137859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135468 = PCURVE('',#135469,#135474); -#135469 = PLANE('',#135470); -#135470 = AXIS2_PLACEMENT_3D('',#135471,#135472,#135473); -#135471 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#137860 = PCURVE('',#137861,#137866); +#137861 = PLANE('',#137862); +#137862 = AXIS2_PLACEMENT_3D('',#137863,#137864,#137865); +#137863 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#135472 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135473 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135474 = DEFINITIONAL_REPRESENTATION('',(#135475),#135479); -#135475 = LINE('',#135476,#135477); -#135476 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#135477 = VECTOR('',#135478,1.); -#135478 = DIRECTION('',(-1.,0.E+000)); -#135479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135480 = ORIENTED_EDGE('',*,*,#135481,.T.); -#135481 = EDGE_CURVE('',#135455,#135254,#135482,.T.); -#135482 = SURFACE_CURVE('',#135483,(#135488,#135494),.PCURVE_S1.); -#135483 = CIRCLE('',#135484,0.208574704164); -#135484 = AXIS2_PLACEMENT_3D('',#135485,#135486,#135487); -#135485 = CARTESIAN_POINT('',(10.728168876214,1.35,2.640924866458E-017) - ); -#135486 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135487 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135488 = PCURVE('',#135292,#135489); -#135489 = DEFINITIONAL_REPRESENTATION('',(#135490),#135493); -#135490 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135491,#135492), +#137864 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137865 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#137866 = DEFINITIONAL_REPRESENTATION('',(#137867),#137871); +#137867 = LINE('',#137868,#137869); +#137868 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#137869 = VECTOR('',#137870,1.); +#137870 = DIRECTION('',(-1.,0.E+000)); +#137871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137872 = ORIENTED_EDGE('',*,*,#137873,.T.); +#137873 = EDGE_CURVE('',#137847,#137646,#137874,.T.); +#137874 = SURFACE_CURVE('',#137875,(#137880,#137886),.PCURVE_S1.); +#137875 = CIRCLE('',#137876,0.208574704164); +#137876 = AXIS2_PLACEMENT_3D('',#137877,#137878,#137879); +#137877 = CARTESIAN_POINT('',(10.728168876214,1.35,2.640924866458E-017) + ); +#137878 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137879 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137880 = PCURVE('',#137684,#137881); +#137881 = DEFINITIONAL_REPRESENTATION('',(#137882),#137885); +#137882 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137883,#137884), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#135491 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#135492 = CARTESIAN_POINT('',(4.772630242227,-1.35)); -#135493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#137883 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#137884 = CARTESIAN_POINT('',(4.772630242227,-1.35)); +#137885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135494 = PCURVE('',#92284,#135495); -#135495 = DEFINITIONAL_REPRESENTATION('',(#135496),#135504); -#135496 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135497,#135498,#135499, - #135500,#135501,#135502,#135503),.UNSPECIFIED.,.T.,.F.) +#137886 = PCURVE('',#94676,#137887); +#137887 = DEFINITIONAL_REPRESENTATION('',(#137888),#137896); +#137888 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137889,#137890,#137891, + #137892,#137893,#137894,#137895),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#135497 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#135498 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#135499 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#135500 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#135501 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#135502 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#135503 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#135504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135505 = ORIENTED_EDGE('',*,*,#135276,.F.); -#135506 = ADVANCED_FACE('',(#135507),#135396,.T.); -#135507 = FACE_BOUND('',#135508,.T.); -#135508 = EDGE_LOOP('',(#135509,#135559,#135560,#135606)); -#135509 = ORIENTED_EDGE('',*,*,#135510,.T.); -#135510 = EDGE_CURVE('',#135511,#135381,#135513,.T.); -#135511 = VERTEX_POINT('',#135512); -#135512 = CARTESIAN_POINT('',(10.419594812019,1.35,0.E+000)); -#135513 = SURFACE_CURVE('',#135514,(#135519,#135548),.PCURVE_S1.); -#135514 = CIRCLE('',#135515,0.308574064194); -#135515 = AXIS2_PLACEMENT_3D('',#135516,#135517,#135518); -#135516 = CARTESIAN_POINT('',(10.728168876214,1.35,2.640924866458E-017) - ); -#135517 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135518 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135519 = PCURVE('',#135396,#135520); -#135520 = DEFINITIONAL_REPRESENTATION('',(#135521),#135547); -#135521 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135522,#135523,#135524, - #135525,#135526,#135527,#135528,#135529,#135530,#135531,#135532, - #135533,#135534,#135535,#135536,#135537,#135538,#135539,#135540, - #135541,#135542,#135543,#135544,#135545,#135546),.UNSPECIFIED.,.F., +#137889 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#137890 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#137891 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#137892 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#137893 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#137894 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#137895 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#137896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137897 = ORIENTED_EDGE('',*,*,#137668,.F.); +#137898 = ADVANCED_FACE('',(#137899),#137788,.T.); +#137899 = FACE_BOUND('',#137900,.T.); +#137900 = EDGE_LOOP('',(#137901,#137951,#137952,#137998)); +#137901 = ORIENTED_EDGE('',*,*,#137902,.T.); +#137902 = EDGE_CURVE('',#137903,#137773,#137905,.T.); +#137903 = VERTEX_POINT('',#137904); +#137904 = CARTESIAN_POINT('',(10.419594812019,1.35,0.E+000)); +#137905 = SURFACE_CURVE('',#137906,(#137911,#137940),.PCURVE_S1.); +#137906 = CIRCLE('',#137907,0.308574064194); +#137907 = AXIS2_PLACEMENT_3D('',#137908,#137909,#137910); +#137908 = CARTESIAN_POINT('',(10.728168876214,1.35,2.640924866458E-017) + ); +#137909 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137910 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137911 = PCURVE('',#137788,#137912); +#137912 = DEFINITIONAL_REPRESENTATION('',(#137913),#137939); +#137913 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137914,#137915,#137916, + #137917,#137918,#137919,#137920,#137921,#137922,#137923,#137924, + #137925,#137926,#137927,#137928,#137929,#137930,#137931,#137932, + #137933,#137934,#137935,#137936,#137937,#137938),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -167016,71 +170018,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#135522 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#135523 = CARTESIAN_POINT('',(3.166141578807,-1.35)); -#135524 = CARTESIAN_POINT('',(3.215239429242,-1.35)); -#135525 = CARTESIAN_POINT('',(3.288886204895,-1.35)); -#135526 = CARTESIAN_POINT('',(3.362532980548,-1.35)); -#135527 = CARTESIAN_POINT('',(3.4361797562,-1.35)); -#135528 = CARTESIAN_POINT('',(3.509826531853,-1.35)); -#135529 = CARTESIAN_POINT('',(3.583473307505,-1.35)); -#135530 = CARTESIAN_POINT('',(3.657120083158,-1.35)); -#135531 = CARTESIAN_POINT('',(3.730766858811,-1.35)); -#135532 = CARTESIAN_POINT('',(3.804413634463,-1.35)); -#135533 = CARTESIAN_POINT('',(3.878060410116,-1.35)); -#135534 = CARTESIAN_POINT('',(3.951707185768,-1.35)); -#135535 = CARTESIAN_POINT('',(4.025353961421,-1.35)); -#135536 = CARTESIAN_POINT('',(4.099000737074,-1.35)); -#135537 = CARTESIAN_POINT('',(4.172647512726,-1.35)); -#135538 = CARTESIAN_POINT('',(4.246294288379,-1.35)); -#135539 = CARTESIAN_POINT('',(4.319941064031,-1.35)); -#135540 = CARTESIAN_POINT('',(4.393587839684,-1.35)); -#135541 = CARTESIAN_POINT('',(4.467234615337,-1.35)); -#135542 = CARTESIAN_POINT('',(4.540881390989,-1.35)); -#135543 = CARTESIAN_POINT('',(4.614528166642,-1.35)); -#135544 = CARTESIAN_POINT('',(4.688174942294,-1.35)); -#135545 = CARTESIAN_POINT('',(4.737272792729,-1.35)); -#135546 = CARTESIAN_POINT('',(4.761821717947,-1.35)); -#135547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135548 = PCURVE('',#92284,#135549); -#135549 = DEFINITIONAL_REPRESENTATION('',(#135550),#135558); -#135550 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135551,#135552,#135553, - #135554,#135555,#135556,#135557),.UNSPECIFIED.,.T.,.F.) +#137914 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#137915 = CARTESIAN_POINT('',(3.166141578807,-1.35)); +#137916 = CARTESIAN_POINT('',(3.215239429242,-1.35)); +#137917 = CARTESIAN_POINT('',(3.288886204895,-1.35)); +#137918 = CARTESIAN_POINT('',(3.362532980548,-1.35)); +#137919 = CARTESIAN_POINT('',(3.4361797562,-1.35)); +#137920 = CARTESIAN_POINT('',(3.509826531853,-1.35)); +#137921 = CARTESIAN_POINT('',(3.583473307505,-1.35)); +#137922 = CARTESIAN_POINT('',(3.657120083158,-1.35)); +#137923 = CARTESIAN_POINT('',(3.730766858811,-1.35)); +#137924 = CARTESIAN_POINT('',(3.804413634463,-1.35)); +#137925 = CARTESIAN_POINT('',(3.878060410116,-1.35)); +#137926 = CARTESIAN_POINT('',(3.951707185768,-1.35)); +#137927 = CARTESIAN_POINT('',(4.025353961421,-1.35)); +#137928 = CARTESIAN_POINT('',(4.099000737074,-1.35)); +#137929 = CARTESIAN_POINT('',(4.172647512726,-1.35)); +#137930 = CARTESIAN_POINT('',(4.246294288379,-1.35)); +#137931 = CARTESIAN_POINT('',(4.319941064031,-1.35)); +#137932 = CARTESIAN_POINT('',(4.393587839684,-1.35)); +#137933 = CARTESIAN_POINT('',(4.467234615337,-1.35)); +#137934 = CARTESIAN_POINT('',(4.540881390989,-1.35)); +#137935 = CARTESIAN_POINT('',(4.614528166642,-1.35)); +#137936 = CARTESIAN_POINT('',(4.688174942294,-1.35)); +#137937 = CARTESIAN_POINT('',(4.737272792729,-1.35)); +#137938 = CARTESIAN_POINT('',(4.761821717947,-1.35)); +#137939 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137940 = PCURVE('',#94676,#137941); +#137941 = DEFINITIONAL_REPRESENTATION('',(#137942),#137950); +#137942 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137943,#137944,#137945, + #137946,#137947,#137948,#137949),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#135551 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#135552 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#135553 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#135554 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#135555 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#135556 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#135557 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#135558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135559 = ORIENTED_EDGE('',*,*,#135380,.T.); -#135560 = ORIENTED_EDGE('',*,*,#135561,.F.); -#135561 = EDGE_CURVE('',#135562,#135358,#135564,.T.); -#135562 = VERTEX_POINT('',#135563); -#135563 = CARTESIAN_POINT('',(10.419594812019,1.15,0.E+000)); -#135564 = SURFACE_CURVE('',#135565,(#135570,#135599),.PCURVE_S1.); -#135565 = CIRCLE('',#135566,0.308574064194); -#135566 = AXIS2_PLACEMENT_3D('',#135567,#135568,#135569); -#135567 = CARTESIAN_POINT('',(10.728168876214,1.15,2.640924866458E-017) - ); -#135568 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135569 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); -#135570 = PCURVE('',#135396,#135571); -#135571 = DEFINITIONAL_REPRESENTATION('',(#135572),#135598); -#135572 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#135573,#135574,#135575, - #135576,#135577,#135578,#135579,#135580,#135581,#135582,#135583, - #135584,#135585,#135586,#135587,#135588,#135589,#135590,#135591, - #135592,#135593,#135594,#135595,#135596,#135597),.UNSPECIFIED.,.F., +#137943 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#137944 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#137945 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#137946 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#137947 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#137948 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#137949 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#137950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137951 = ORIENTED_EDGE('',*,*,#137772,.T.); +#137952 = ORIENTED_EDGE('',*,*,#137953,.F.); +#137953 = EDGE_CURVE('',#137954,#137750,#137956,.T.); +#137954 = VERTEX_POINT('',#137955); +#137955 = CARTESIAN_POINT('',(10.419594812019,1.15,0.E+000)); +#137956 = SURFACE_CURVE('',#137957,(#137962,#137991),.PCURVE_S1.); +#137957 = CIRCLE('',#137958,0.308574064194); +#137958 = AXIS2_PLACEMENT_3D('',#137959,#137960,#137961); +#137959 = CARTESIAN_POINT('',(10.728168876214,1.15,2.640924866458E-017) + ); +#137960 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#137961 = DIRECTION('',(1.,-4.440892098501E-016,0.E+000)); +#137962 = PCURVE('',#137788,#137963); +#137963 = DEFINITIONAL_REPRESENTATION('',(#137964),#137990); +#137964 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137965,#137966,#137967, + #137968,#137969,#137970,#137971,#137972,#137973,#137974,#137975, + #137976,#137977,#137978,#137979,#137980,#137981,#137982,#137983, + #137984,#137985,#137986,#137987,#137988,#137989),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -167088,1956 +170090,1956 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#135573 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#135574 = CARTESIAN_POINT('',(3.166141578807,-1.15)); -#135575 = CARTESIAN_POINT('',(3.215239429242,-1.15)); -#135576 = CARTESIAN_POINT('',(3.288886204895,-1.15)); -#135577 = CARTESIAN_POINT('',(3.362532980548,-1.15)); -#135578 = CARTESIAN_POINT('',(3.4361797562,-1.15)); -#135579 = CARTESIAN_POINT('',(3.509826531853,-1.15)); -#135580 = CARTESIAN_POINT('',(3.583473307505,-1.15)); -#135581 = CARTESIAN_POINT('',(3.657120083158,-1.15)); -#135582 = CARTESIAN_POINT('',(3.730766858811,-1.15)); -#135583 = CARTESIAN_POINT('',(3.804413634463,-1.15)); -#135584 = CARTESIAN_POINT('',(3.878060410116,-1.15)); -#135585 = CARTESIAN_POINT('',(3.951707185768,-1.15)); -#135586 = CARTESIAN_POINT('',(4.025353961421,-1.15)); -#135587 = CARTESIAN_POINT('',(4.099000737074,-1.15)); -#135588 = CARTESIAN_POINT('',(4.172647512726,-1.15)); -#135589 = CARTESIAN_POINT('',(4.246294288379,-1.15)); -#135590 = CARTESIAN_POINT('',(4.319941064031,-1.15)); -#135591 = CARTESIAN_POINT('',(4.393587839684,-1.15)); -#135592 = CARTESIAN_POINT('',(4.467234615337,-1.15)); -#135593 = CARTESIAN_POINT('',(4.540881390989,-1.15)); -#135594 = CARTESIAN_POINT('',(4.614528166642,-1.15)); -#135595 = CARTESIAN_POINT('',(4.688174942294,-1.15)); -#135596 = CARTESIAN_POINT('',(4.737272792729,-1.15)); -#135597 = CARTESIAN_POINT('',(4.761821717947,-1.15)); -#135598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135599 = PCURVE('',#92340,#135600); -#135600 = DEFINITIONAL_REPRESENTATION('',(#135601),#135605); -#135601 = CIRCLE('',#135602,0.308574064194); -#135602 = AXIS2_PLACEMENT_2D('',#135603,#135604); -#135603 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#135604 = DIRECTION('',(0.E+000,1.)); -#135605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135606 = ORIENTED_EDGE('',*,*,#135607,.T.); -#135607 = EDGE_CURVE('',#135562,#135511,#135608,.T.); -#135608 = SURFACE_CURVE('',#135609,(#135613,#135619),.PCURVE_S1.); -#135609 = LINE('',#135610,#135611); -#135610 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#137965 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#137966 = CARTESIAN_POINT('',(3.166141578807,-1.15)); +#137967 = CARTESIAN_POINT('',(3.215239429242,-1.15)); +#137968 = CARTESIAN_POINT('',(3.288886204895,-1.15)); +#137969 = CARTESIAN_POINT('',(3.362532980548,-1.15)); +#137970 = CARTESIAN_POINT('',(3.4361797562,-1.15)); +#137971 = CARTESIAN_POINT('',(3.509826531853,-1.15)); +#137972 = CARTESIAN_POINT('',(3.583473307505,-1.15)); +#137973 = CARTESIAN_POINT('',(3.657120083158,-1.15)); +#137974 = CARTESIAN_POINT('',(3.730766858811,-1.15)); +#137975 = CARTESIAN_POINT('',(3.804413634463,-1.15)); +#137976 = CARTESIAN_POINT('',(3.878060410116,-1.15)); +#137977 = CARTESIAN_POINT('',(3.951707185768,-1.15)); +#137978 = CARTESIAN_POINT('',(4.025353961421,-1.15)); +#137979 = CARTESIAN_POINT('',(4.099000737074,-1.15)); +#137980 = CARTESIAN_POINT('',(4.172647512726,-1.15)); +#137981 = CARTESIAN_POINT('',(4.246294288379,-1.15)); +#137982 = CARTESIAN_POINT('',(4.319941064031,-1.15)); +#137983 = CARTESIAN_POINT('',(4.393587839684,-1.15)); +#137984 = CARTESIAN_POINT('',(4.467234615337,-1.15)); +#137985 = CARTESIAN_POINT('',(4.540881390989,-1.15)); +#137986 = CARTESIAN_POINT('',(4.614528166642,-1.15)); +#137987 = CARTESIAN_POINT('',(4.688174942294,-1.15)); +#137988 = CARTESIAN_POINT('',(4.737272792729,-1.15)); +#137989 = CARTESIAN_POINT('',(4.761821717947,-1.15)); +#137990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137991 = PCURVE('',#94732,#137992); +#137992 = DEFINITIONAL_REPRESENTATION('',(#137993),#137997); +#137993 = CIRCLE('',#137994,0.308574064194); +#137994 = AXIS2_PLACEMENT_2D('',#137995,#137996); +#137995 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#137996 = DIRECTION('',(0.E+000,1.)); +#137997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#137998 = ORIENTED_EDGE('',*,*,#137999,.T.); +#137999 = EDGE_CURVE('',#137954,#137903,#138000,.T.); +#138000 = SURFACE_CURVE('',#138001,(#138005,#138011),.PCURVE_S1.); +#138001 = LINE('',#138002,#138003); +#138002 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.E+000)); -#135611 = VECTOR('',#135612,1.); -#135612 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135613 = PCURVE('',#135396,#135614); -#135614 = DEFINITIONAL_REPRESENTATION('',(#135615),#135618); -#135615 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135616,#135617), +#138003 = VECTOR('',#138004,1.); +#138004 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138005 = PCURVE('',#137788,#138006); +#138006 = DEFINITIONAL_REPRESENTATION('',(#138007),#138010); +#138007 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138008,#138009), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#135616 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#135617 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#135618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138008 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#138009 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#138010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135619 = PCURVE('',#135620,#135625); -#135620 = PLANE('',#135621); -#135621 = AXIS2_PLACEMENT_3D('',#135622,#135623,#135624); -#135622 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#138011 = PCURVE('',#138012,#138017); +#138012 = PLANE('',#138013); +#138013 = AXIS2_PLACEMENT_3D('',#138014,#138015,#138016); +#138014 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#135623 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135624 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135625 = DEFINITIONAL_REPRESENTATION('',(#135626),#135630); -#135626 = LINE('',#135627,#135628); -#135627 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#135628 = VECTOR('',#135629,1.); -#135629 = DIRECTION('',(-1.,0.E+000)); -#135630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135631 = ADVANCED_FACE('',(#135632),#135620,.T.); -#135632 = FACE_BOUND('',#135633,.T.); -#135633 = EDGE_LOOP('',(#135634,#135663,#135684,#135685)); -#135634 = ORIENTED_EDGE('',*,*,#135635,.T.); -#135635 = EDGE_CURVE('',#135636,#135638,#135640,.T.); -#135636 = VERTEX_POINT('',#135637); -#135637 = CARTESIAN_POINT('',(10.419594812019,1.15,0.530776333563)); -#135638 = VERTEX_POINT('',#135639); -#135639 = CARTESIAN_POINT('',(10.419594812019,1.35,0.530776333563)); -#135640 = SURFACE_CURVE('',#135641,(#135645,#135652),.PCURVE_S1.); -#135641 = LINE('',#135642,#135643); -#135642 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, +#138015 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138016 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#138017 = DEFINITIONAL_REPRESENTATION('',(#138018),#138022); +#138018 = LINE('',#138019,#138020); +#138019 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#138020 = VECTOR('',#138021,1.); +#138021 = DIRECTION('',(-1.,0.E+000)); +#138022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138023 = ADVANCED_FACE('',(#138024),#138012,.T.); +#138024 = FACE_BOUND('',#138025,.T.); +#138025 = EDGE_LOOP('',(#138026,#138055,#138076,#138077)); +#138026 = ORIENTED_EDGE('',*,*,#138027,.T.); +#138027 = EDGE_CURVE('',#138028,#138030,#138032,.T.); +#138028 = VERTEX_POINT('',#138029); +#138029 = CARTESIAN_POINT('',(10.419594812019,1.15,0.530776333563)); +#138030 = VERTEX_POINT('',#138031); +#138031 = CARTESIAN_POINT('',(10.419594812019,1.35,0.530776333563)); +#138032 = SURFACE_CURVE('',#138033,(#138037,#138044),.PCURVE_S1.); +#138033 = LINE('',#138034,#138035); +#138034 = CARTESIAN_POINT('',(10.419594812019,-3.522413645904E-015, 0.530776333563)); -#135643 = VECTOR('',#135644,1.); -#135644 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135645 = PCURVE('',#135620,#135646); -#135646 = DEFINITIONAL_REPRESENTATION('',(#135647),#135651); -#135647 = LINE('',#135648,#135649); -#135648 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135649 = VECTOR('',#135650,1.); -#135650 = DIRECTION('',(-1.,0.E+000)); -#135651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135652 = PCURVE('',#135653,#135658); -#135653 = CYLINDRICAL_SURFACE('',#135654,0.119270391569); -#135654 = AXIS2_PLACEMENT_3D('',#135655,#135656,#135657); -#135655 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#138035 = VECTOR('',#138036,1.); +#138036 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138037 = PCURVE('',#138012,#138038); +#138038 = DEFINITIONAL_REPRESENTATION('',(#138039),#138043); +#138039 = LINE('',#138040,#138041); +#138040 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138041 = VECTOR('',#138042,1.); +#138042 = DIRECTION('',(-1.,0.E+000)); +#138043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138044 = PCURVE('',#138045,#138050); +#138045 = CYLINDRICAL_SURFACE('',#138046,0.119270391569); +#138046 = AXIS2_PLACEMENT_3D('',#138047,#138048,#138049); +#138047 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#135656 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135657 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135658 = DEFINITIONAL_REPRESENTATION('',(#135659),#135662); -#135659 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135660,#135661), +#138048 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138049 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138050 = DEFINITIONAL_REPRESENTATION('',(#138051),#138054); +#138051 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138052,#138053), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#135660 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#135661 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#135662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135663 = ORIENTED_EDGE('',*,*,#135664,.T.); -#135664 = EDGE_CURVE('',#135638,#135511,#135665,.T.); -#135665 = SURFACE_CURVE('',#135666,(#135670,#135677),.PCURVE_S1.); -#135666 = LINE('',#135667,#135668); -#135667 = CARTESIAN_POINT('',(10.419594812019,1.35,0.530776333563)); -#135668 = VECTOR('',#135669,1.); -#135669 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#135670 = PCURVE('',#135620,#135671); -#135671 = DEFINITIONAL_REPRESENTATION('',(#135672),#135676); -#135672 = LINE('',#135673,#135674); -#135673 = CARTESIAN_POINT('',(-1.35,0.E+000)); -#135674 = VECTOR('',#135675,1.); -#135675 = DIRECTION('',(0.E+000,-1.)); -#135676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135677 = PCURVE('',#92284,#135678); -#135678 = DEFINITIONAL_REPRESENTATION('',(#135679),#135683); -#135679 = LINE('',#135680,#135681); -#135680 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#135681 = VECTOR('',#135682,1.); -#135682 = DIRECTION('',(-1.,0.E+000)); -#135683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135684 = ORIENTED_EDGE('',*,*,#135607,.F.); -#135685 = ORIENTED_EDGE('',*,*,#135686,.F.); -#135686 = EDGE_CURVE('',#135636,#135562,#135687,.T.); -#135687 = SURFACE_CURVE('',#135688,(#135692,#135699),.PCURVE_S1.); -#135688 = LINE('',#135689,#135690); -#135689 = CARTESIAN_POINT('',(10.419594812019,1.15,0.530776333563)); -#135690 = VECTOR('',#135691,1.); -#135691 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#135692 = PCURVE('',#135620,#135693); -#135693 = DEFINITIONAL_REPRESENTATION('',(#135694),#135698); -#135694 = LINE('',#135695,#135696); -#135695 = CARTESIAN_POINT('',(-1.15,0.E+000)); -#135696 = VECTOR('',#135697,1.); -#135697 = DIRECTION('',(0.E+000,-1.)); -#135698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135699 = PCURVE('',#92340,#135700); -#135700 = DEFINITIONAL_REPRESENTATION('',(#135701),#135705); -#135701 = LINE('',#135702,#135703); -#135702 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#135703 = VECTOR('',#135704,1.); -#135704 = DIRECTION('',(1.,0.E+000)); -#135705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135706 = ADVANCED_FACE('',(#135707),#135469,.T.); -#135707 = FACE_BOUND('',#135708,.T.); -#135708 = EDGE_LOOP('',(#135709,#135738,#135759,#135760)); -#135709 = ORIENTED_EDGE('',*,*,#135710,.T.); -#135710 = EDGE_CURVE('',#135711,#135713,#135715,.T.); -#135711 = VERTEX_POINT('',#135712); -#135712 = CARTESIAN_POINT('',(10.51959417205,1.35,0.530776333563)); -#135713 = VERTEX_POINT('',#135714); -#135714 = CARTESIAN_POINT('',(10.51959417205,1.15,0.530776333563)); -#135715 = SURFACE_CURVE('',#135716,(#135720,#135727),.PCURVE_S1.); -#135716 = LINE('',#135717,#135718); -#135717 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, +#138052 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#138053 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#138054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138055 = ORIENTED_EDGE('',*,*,#138056,.T.); +#138056 = EDGE_CURVE('',#138030,#137903,#138057,.T.); +#138057 = SURFACE_CURVE('',#138058,(#138062,#138069),.PCURVE_S1.); +#138058 = LINE('',#138059,#138060); +#138059 = CARTESIAN_POINT('',(10.419594812019,1.35,0.530776333563)); +#138060 = VECTOR('',#138061,1.); +#138061 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138062 = PCURVE('',#138012,#138063); +#138063 = DEFINITIONAL_REPRESENTATION('',(#138064),#138068); +#138064 = LINE('',#138065,#138066); +#138065 = CARTESIAN_POINT('',(-1.35,0.E+000)); +#138066 = VECTOR('',#138067,1.); +#138067 = DIRECTION('',(0.E+000,-1.)); +#138068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138069 = PCURVE('',#94676,#138070); +#138070 = DEFINITIONAL_REPRESENTATION('',(#138071),#138075); +#138071 = LINE('',#138072,#138073); +#138072 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#138073 = VECTOR('',#138074,1.); +#138074 = DIRECTION('',(-1.,0.E+000)); +#138075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138076 = ORIENTED_EDGE('',*,*,#137999,.F.); +#138077 = ORIENTED_EDGE('',*,*,#138078,.F.); +#138078 = EDGE_CURVE('',#138028,#137954,#138079,.T.); +#138079 = SURFACE_CURVE('',#138080,(#138084,#138091),.PCURVE_S1.); +#138080 = LINE('',#138081,#138082); +#138081 = CARTESIAN_POINT('',(10.419594812019,1.15,0.530776333563)); +#138082 = VECTOR('',#138083,1.); +#138083 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138084 = PCURVE('',#138012,#138085); +#138085 = DEFINITIONAL_REPRESENTATION('',(#138086),#138090); +#138086 = LINE('',#138087,#138088); +#138087 = CARTESIAN_POINT('',(-1.15,0.E+000)); +#138088 = VECTOR('',#138089,1.); +#138089 = DIRECTION('',(0.E+000,-1.)); +#138090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138091 = PCURVE('',#94732,#138092); +#138092 = DEFINITIONAL_REPRESENTATION('',(#138093),#138097); +#138093 = LINE('',#138094,#138095); +#138094 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#138095 = VECTOR('',#138096,1.); +#138096 = DIRECTION('',(1.,0.E+000)); +#138097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138098 = ADVANCED_FACE('',(#138099),#137861,.T.); +#138099 = FACE_BOUND('',#138100,.T.); +#138100 = EDGE_LOOP('',(#138101,#138130,#138151,#138152)); +#138101 = ORIENTED_EDGE('',*,*,#138102,.T.); +#138102 = EDGE_CURVE('',#138103,#138105,#138107,.T.); +#138103 = VERTEX_POINT('',#138104); +#138104 = CARTESIAN_POINT('',(10.51959417205,1.35,0.530776333563)); +#138105 = VERTEX_POINT('',#138106); +#138106 = CARTESIAN_POINT('',(10.51959417205,1.15,0.530776333563)); +#138107 = SURFACE_CURVE('',#138108,(#138112,#138119),.PCURVE_S1.); +#138108 = LINE('',#138109,#138110); +#138109 = CARTESIAN_POINT('',(10.51959417205,-3.566822282686E-015, 0.530776333563)); -#135718 = VECTOR('',#135719,1.); -#135719 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135720 = PCURVE('',#135469,#135721); -#135721 = DEFINITIONAL_REPRESENTATION('',(#135722),#135726); -#135722 = LINE('',#135723,#135724); -#135723 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135724 = VECTOR('',#135725,1.); -#135725 = DIRECTION('',(-1.,0.E+000)); -#135726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135727 = PCURVE('',#135728,#135733); -#135728 = CYLINDRICAL_SURFACE('',#135729,0.2192697516); -#135729 = AXIS2_PLACEMENT_3D('',#135730,#135731,#135732); -#135730 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, +#138110 = VECTOR('',#138111,1.); +#138111 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#138112 = PCURVE('',#137861,#138113); +#138113 = DEFINITIONAL_REPRESENTATION('',(#138114),#138118); +#138114 = LINE('',#138115,#138116); +#138115 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138116 = VECTOR('',#138117,1.); +#138117 = DIRECTION('',(-1.,0.E+000)); +#138118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138119 = PCURVE('',#138120,#138125); +#138120 = CYLINDRICAL_SURFACE('',#138121,0.2192697516); +#138121 = AXIS2_PLACEMENT_3D('',#138122,#138123,#138124); +#138122 = CARTESIAN_POINT('',(10.30032442045,-3.469446951954E-015, 0.530776333563)); -#135731 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135732 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135733 = DEFINITIONAL_REPRESENTATION('',(#135734),#135737); -#135734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135735,#135736), +#138123 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138124 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138125 = DEFINITIONAL_REPRESENTATION('',(#138126),#138129); +#138126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138127,#138128), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#135735 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#135736 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#135737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135738 = ORIENTED_EDGE('',*,*,#135739,.T.); -#135739 = EDGE_CURVE('',#135713,#135432,#135740,.T.); -#135740 = SURFACE_CURVE('',#135741,(#135745,#135752),.PCURVE_S1.); -#135741 = LINE('',#135742,#135743); -#135742 = CARTESIAN_POINT('',(10.51959417205,1.15,0.530776333563)); -#135743 = VECTOR('',#135744,1.); -#135744 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#135745 = PCURVE('',#135469,#135746); -#135746 = DEFINITIONAL_REPRESENTATION('',(#135747),#135751); -#135747 = LINE('',#135748,#135749); -#135748 = CARTESIAN_POINT('',(1.15,0.E+000)); -#135749 = VECTOR('',#135750,1.); -#135750 = DIRECTION('',(0.E+000,-1.)); -#135751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135752 = PCURVE('',#92340,#135753); -#135753 = DEFINITIONAL_REPRESENTATION('',(#135754),#135758); -#135754 = LINE('',#135755,#135756); -#135755 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#135756 = VECTOR('',#135757,1.); -#135757 = DIRECTION('',(1.,0.E+000)); -#135758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135759 = ORIENTED_EDGE('',*,*,#135454,.F.); -#135760 = ORIENTED_EDGE('',*,*,#135761,.F.); -#135761 = EDGE_CURVE('',#135711,#135455,#135762,.T.); -#135762 = SURFACE_CURVE('',#135763,(#135767,#135774),.PCURVE_S1.); -#135763 = LINE('',#135764,#135765); -#135764 = CARTESIAN_POINT('',(10.51959417205,1.35,0.530776333563)); -#135765 = VECTOR('',#135766,1.); -#135766 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#135767 = PCURVE('',#135469,#135768); -#135768 = DEFINITIONAL_REPRESENTATION('',(#135769),#135773); -#135769 = LINE('',#135770,#135771); -#135770 = CARTESIAN_POINT('',(1.35,0.E+000)); -#135771 = VECTOR('',#135772,1.); -#135772 = DIRECTION('',(0.E+000,-1.)); -#135773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135774 = PCURVE('',#92284,#135775); -#135775 = DEFINITIONAL_REPRESENTATION('',(#135776),#135780); -#135776 = LINE('',#135777,#135778); -#135777 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#135778 = VECTOR('',#135779,1.); -#135779 = DIRECTION('',(-1.,0.E+000)); -#135780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135781 = ADVANCED_FACE('',(#135782),#135728,.T.); -#135782 = FACE_BOUND('',#135783,.T.); -#135783 = EDGE_LOOP('',(#135784,#135785,#135808,#135830)); -#135784 = ORIENTED_EDGE('',*,*,#135710,.F.); -#135785 = ORIENTED_EDGE('',*,*,#135786,.F.); -#135786 = EDGE_CURVE('',#135787,#135711,#135789,.T.); -#135787 = VERTEX_POINT('',#135788); -#135788 = CARTESIAN_POINT('',(10.304819755875,1.35,0.75)); -#135789 = SURFACE_CURVE('',#135790,(#135795,#135801),.PCURVE_S1.); -#135790 = CIRCLE('',#135791,0.2192697516); -#135791 = AXIS2_PLACEMENT_3D('',#135792,#135793,#135794); -#135792 = CARTESIAN_POINT('',(10.30032442045,1.35,0.530776333563)); -#135793 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135794 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135795 = PCURVE('',#135728,#135796); -#135796 = DEFINITIONAL_REPRESENTATION('',(#135797),#135800); -#135797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135798,#135799), +#138127 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#138128 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#138129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138130 = ORIENTED_EDGE('',*,*,#138131,.T.); +#138131 = EDGE_CURVE('',#138105,#137824,#138132,.T.); +#138132 = SURFACE_CURVE('',#138133,(#138137,#138144),.PCURVE_S1.); +#138133 = LINE('',#138134,#138135); +#138134 = CARTESIAN_POINT('',(10.51959417205,1.15,0.530776333563)); +#138135 = VECTOR('',#138136,1.); +#138136 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138137 = PCURVE('',#137861,#138138); +#138138 = DEFINITIONAL_REPRESENTATION('',(#138139),#138143); +#138139 = LINE('',#138140,#138141); +#138140 = CARTESIAN_POINT('',(1.15,0.E+000)); +#138141 = VECTOR('',#138142,1.); +#138142 = DIRECTION('',(0.E+000,-1.)); +#138143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138144 = PCURVE('',#94732,#138145); +#138145 = DEFINITIONAL_REPRESENTATION('',(#138146),#138150); +#138146 = LINE('',#138147,#138148); +#138147 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#138148 = VECTOR('',#138149,1.); +#138149 = DIRECTION('',(1.,0.E+000)); +#138150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138151 = ORIENTED_EDGE('',*,*,#137846,.F.); +#138152 = ORIENTED_EDGE('',*,*,#138153,.F.); +#138153 = EDGE_CURVE('',#138103,#137847,#138154,.T.); +#138154 = SURFACE_CURVE('',#138155,(#138159,#138166),.PCURVE_S1.); +#138155 = LINE('',#138156,#138157); +#138156 = CARTESIAN_POINT('',(10.51959417205,1.35,0.530776333563)); +#138157 = VECTOR('',#138158,1.); +#138158 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138159 = PCURVE('',#137861,#138160); +#138160 = DEFINITIONAL_REPRESENTATION('',(#138161),#138165); +#138161 = LINE('',#138162,#138163); +#138162 = CARTESIAN_POINT('',(1.35,0.E+000)); +#138163 = VECTOR('',#138164,1.); +#138164 = DIRECTION('',(0.E+000,-1.)); +#138165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138166 = PCURVE('',#94676,#138167); +#138167 = DEFINITIONAL_REPRESENTATION('',(#138168),#138172); +#138168 = LINE('',#138169,#138170); +#138169 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#138170 = VECTOR('',#138171,1.); +#138171 = DIRECTION('',(-1.,0.E+000)); +#138172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138173 = ADVANCED_FACE('',(#138174),#138120,.T.); +#138174 = FACE_BOUND('',#138175,.T.); +#138175 = EDGE_LOOP('',(#138176,#138177,#138200,#138222)); +#138176 = ORIENTED_EDGE('',*,*,#138102,.F.); +#138177 = ORIENTED_EDGE('',*,*,#138178,.F.); +#138178 = EDGE_CURVE('',#138179,#138103,#138181,.T.); +#138179 = VERTEX_POINT('',#138180); +#138180 = CARTESIAN_POINT('',(10.304819755875,1.35,0.75)); +#138181 = SURFACE_CURVE('',#138182,(#138187,#138193),.PCURVE_S1.); +#138182 = CIRCLE('',#138183,0.2192697516); +#138183 = AXIS2_PLACEMENT_3D('',#138184,#138185,#138186); +#138184 = CARTESIAN_POINT('',(10.30032442045,1.35,0.530776333563)); +#138185 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138186 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138187 = PCURVE('',#138120,#138188); +#138188 = DEFINITIONAL_REPRESENTATION('',(#138189),#138192); +#138189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138190,#138191), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#135798 = CARTESIAN_POINT('',(1.591299156552,1.35)); -#135799 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#135800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135801 = PCURVE('',#92284,#135802); -#135802 = DEFINITIONAL_REPRESENTATION('',(#135803),#135807); -#135803 = CIRCLE('',#135804,0.2192697516); -#135804 = AXIS2_PLACEMENT_2D('',#135805,#135806); -#135805 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#135806 = DIRECTION('',(0.E+000,-1.)); -#135807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135808 = ORIENTED_EDGE('',*,*,#135809,.F.); -#135809 = EDGE_CURVE('',#135810,#135787,#135812,.T.); -#135810 = VERTEX_POINT('',#135811); -#135811 = CARTESIAN_POINT('',(10.304819755875,1.15,0.75)); -#135812 = SURFACE_CURVE('',#135813,(#135817,#135823),.PCURVE_S1.); -#135813 = LINE('',#135814,#135815); -#135814 = CARTESIAN_POINT('',(10.304819755875,1.35,0.75)); -#135815 = VECTOR('',#135816,1.); -#135816 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135817 = PCURVE('',#135728,#135818); -#135818 = DEFINITIONAL_REPRESENTATION('',(#135819),#135822); -#135819 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135820,#135821), +#138190 = CARTESIAN_POINT('',(1.591299156552,1.35)); +#138191 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#138192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138193 = PCURVE('',#94676,#138194); +#138194 = DEFINITIONAL_REPRESENTATION('',(#138195),#138199); +#138195 = CIRCLE('',#138196,0.2192697516); +#138196 = AXIS2_PLACEMENT_2D('',#138197,#138198); +#138197 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#138198 = DIRECTION('',(0.E+000,-1.)); +#138199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138200 = ORIENTED_EDGE('',*,*,#138201,.F.); +#138201 = EDGE_CURVE('',#138202,#138179,#138204,.T.); +#138202 = VERTEX_POINT('',#138203); +#138203 = CARTESIAN_POINT('',(10.304819755875,1.15,0.75)); +#138204 = SURFACE_CURVE('',#138205,(#138209,#138215),.PCURVE_S1.); +#138205 = LINE('',#138206,#138207); +#138206 = CARTESIAN_POINT('',(10.304819755875,1.35,0.75)); +#138207 = VECTOR('',#138208,1.); +#138208 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138209 = PCURVE('',#138120,#138210); +#138210 = DEFINITIONAL_REPRESENTATION('',(#138211),#138214); +#138211 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138212,#138213), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#135820 = CARTESIAN_POINT('',(1.591299156552,1.15)); -#135821 = CARTESIAN_POINT('',(1.591299156552,1.35)); -#135822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135823 = PCURVE('',#92366,#135824); -#135824 = DEFINITIONAL_REPRESENTATION('',(#135825),#135829); -#135825 = LINE('',#135826,#135827); -#135826 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); -#135827 = VECTOR('',#135828,1.); -#135828 = DIRECTION('',(4.440892098501E-016,1.)); -#135829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135830 = ORIENTED_EDGE('',*,*,#135831,.T.); -#135831 = EDGE_CURVE('',#135810,#135713,#135832,.T.); -#135832 = SURFACE_CURVE('',#135833,(#135838,#135844),.PCURVE_S1.); -#135833 = CIRCLE('',#135834,0.2192697516); -#135834 = AXIS2_PLACEMENT_3D('',#135835,#135836,#135837); -#135835 = CARTESIAN_POINT('',(10.30032442045,1.15,0.530776333563)); -#135836 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135837 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135838 = PCURVE('',#135728,#135839); -#135839 = DEFINITIONAL_REPRESENTATION('',(#135840),#135843); -#135840 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135841,#135842), +#138212 = CARTESIAN_POINT('',(1.591299156552,1.15)); +#138213 = CARTESIAN_POINT('',(1.591299156552,1.35)); +#138214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138215 = PCURVE('',#94758,#138216); +#138216 = DEFINITIONAL_REPRESENTATION('',(#138217),#138221); +#138217 = LINE('',#138218,#138219); +#138218 = CARTESIAN_POINT('',(-0.223028236564,4.991951569247E-048)); +#138219 = VECTOR('',#138220,1.); +#138220 = DIRECTION('',(4.440892098501E-016,1.)); +#138221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138222 = ORIENTED_EDGE('',*,*,#138223,.T.); +#138223 = EDGE_CURVE('',#138202,#138105,#138224,.T.); +#138224 = SURFACE_CURVE('',#138225,(#138230,#138236),.PCURVE_S1.); +#138225 = CIRCLE('',#138226,0.2192697516); +#138226 = AXIS2_PLACEMENT_3D('',#138227,#138228,#138229); +#138227 = CARTESIAN_POINT('',(10.30032442045,1.15,0.530776333563)); +#138228 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138229 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138230 = PCURVE('',#138120,#138231); +#138231 = DEFINITIONAL_REPRESENTATION('',(#138232),#138235); +#138232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138233,#138234), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#135841 = CARTESIAN_POINT('',(1.591299156552,1.15)); -#135842 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#135843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138233 = CARTESIAN_POINT('',(1.591299156552,1.15)); +#138234 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#138235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135844 = PCURVE('',#92340,#135845); -#135845 = DEFINITIONAL_REPRESENTATION('',(#135846),#135854); -#135846 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135847,#135848,#135849, - #135850,#135851,#135852,#135853),.UNSPECIFIED.,.T.,.F.) +#138236 = PCURVE('',#94732,#138237); +#138237 = DEFINITIONAL_REPRESENTATION('',(#138238),#138246); +#138238 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138239,#138240,#138241, + #138242,#138243,#138244,#138245),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#135847 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#135848 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#135849 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#135850 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#135851 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#135852 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#135853 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#135854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135855 = ADVANCED_FACE('',(#135856),#135653,.F.); -#135856 = FACE_BOUND('',#135857,.F.); -#135857 = EDGE_LOOP('',(#135858,#135859,#135882,#135904)); -#135858 = ORIENTED_EDGE('',*,*,#135635,.T.); -#135859 = ORIENTED_EDGE('',*,*,#135860,.F.); -#135860 = EDGE_CURVE('',#135861,#135638,#135863,.T.); -#135861 = VERTEX_POINT('',#135862); -#135862 = CARTESIAN_POINT('',(10.303662633502,1.35,0.65)); -#135863 = SURFACE_CURVE('',#135864,(#135869,#135875),.PCURVE_S1.); -#135864 = CIRCLE('',#135865,0.119270391569); -#135865 = AXIS2_PLACEMENT_3D('',#135866,#135867,#135868); -#135866 = CARTESIAN_POINT('',(10.30032442045,1.35,0.530776333563)); -#135867 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135868 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135869 = PCURVE('',#135653,#135870); -#135870 = DEFINITIONAL_REPRESENTATION('',(#135871),#135874); -#135871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135872,#135873), +#138239 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#138240 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#138241 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#138242 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#138243 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#138244 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#138245 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#138246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138247 = ADVANCED_FACE('',(#138248),#138045,.F.); +#138248 = FACE_BOUND('',#138249,.F.); +#138249 = EDGE_LOOP('',(#138250,#138251,#138274,#138296)); +#138250 = ORIENTED_EDGE('',*,*,#138027,.T.); +#138251 = ORIENTED_EDGE('',*,*,#138252,.F.); +#138252 = EDGE_CURVE('',#138253,#138030,#138255,.T.); +#138253 = VERTEX_POINT('',#138254); +#138254 = CARTESIAN_POINT('',(10.303662633502,1.35,0.65)); +#138255 = SURFACE_CURVE('',#138256,(#138261,#138267),.PCURVE_S1.); +#138256 = CIRCLE('',#138257,0.119270391569); +#138257 = AXIS2_PLACEMENT_3D('',#138258,#138259,#138260); +#138258 = CARTESIAN_POINT('',(10.30032442045,1.35,0.530776333563)); +#138259 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138260 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138261 = PCURVE('',#138045,#138262); +#138262 = DEFINITIONAL_REPRESENTATION('',(#138263),#138266); +#138263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138264,#138265), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#135872 = CARTESIAN_POINT('',(1.598788597134,1.35)); -#135873 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#135874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135875 = PCURVE('',#92284,#135876); -#135876 = DEFINITIONAL_REPRESENTATION('',(#135877),#135881); -#135877 = CIRCLE('',#135878,0.119270391569); -#135878 = AXIS2_PLACEMENT_2D('',#135879,#135880); -#135879 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#135880 = DIRECTION('',(0.E+000,-1.)); -#135881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135882 = ORIENTED_EDGE('',*,*,#135883,.T.); -#135883 = EDGE_CURVE('',#135861,#135884,#135886,.T.); -#135884 = VERTEX_POINT('',#135885); -#135885 = CARTESIAN_POINT('',(10.303662633502,1.15,0.65)); -#135886 = SURFACE_CURVE('',#135887,(#135891,#135897),.PCURVE_S1.); -#135887 = LINE('',#135888,#135889); -#135888 = CARTESIAN_POINT('',(10.303662633502,1.35,0.65)); -#135889 = VECTOR('',#135890,1.); -#135890 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); -#135891 = PCURVE('',#135653,#135892); -#135892 = DEFINITIONAL_REPRESENTATION('',(#135893),#135896); -#135893 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135894,#135895), +#138264 = CARTESIAN_POINT('',(1.598788597134,1.35)); +#138265 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#138266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138267 = PCURVE('',#94676,#138268); +#138268 = DEFINITIONAL_REPRESENTATION('',(#138269),#138273); +#138269 = CIRCLE('',#138270,0.119270391569); +#138270 = AXIS2_PLACEMENT_2D('',#138271,#138272); +#138271 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#138272 = DIRECTION('',(0.E+000,-1.)); +#138273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138274 = ORIENTED_EDGE('',*,*,#138275,.T.); +#138275 = EDGE_CURVE('',#138253,#138276,#138278,.T.); +#138276 = VERTEX_POINT('',#138277); +#138277 = CARTESIAN_POINT('',(10.303662633502,1.15,0.65)); +#138278 = SURFACE_CURVE('',#138279,(#138283,#138289),.PCURVE_S1.); +#138279 = LINE('',#138280,#138281); +#138280 = CARTESIAN_POINT('',(10.303662633502,1.35,0.65)); +#138281 = VECTOR('',#138282,1.); +#138282 = DIRECTION('',(-4.440892098501E-016,-1.,0.E+000)); +#138283 = PCURVE('',#138045,#138284); +#138284 = DEFINITIONAL_REPRESENTATION('',(#138285),#138288); +#138285 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138286,#138287), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#135894 = CARTESIAN_POINT('',(1.598788597134,1.35)); -#135895 = CARTESIAN_POINT('',(1.598788597134,1.15)); -#135896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138286 = CARTESIAN_POINT('',(1.598788597134,1.35)); +#138287 = CARTESIAN_POINT('',(1.598788597134,1.15)); +#138288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135897 = PCURVE('',#92312,#135898); -#135898 = DEFINITIONAL_REPRESENTATION('',(#135899),#135903); -#135899 = LINE('',#135900,#135901); -#135900 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); -#135901 = VECTOR('',#135902,1.); -#135902 = DIRECTION('',(4.440892098501E-016,-1.)); -#135903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138289 = PCURVE('',#94704,#138290); +#138290 = DEFINITIONAL_REPRESENTATION('',(#138291),#138295); +#138291 = LINE('',#138292,#138293); +#138292 = CARTESIAN_POINT('',(0.224185358936,4.926693529724E-048)); +#138293 = VECTOR('',#138294,1.); +#138294 = DIRECTION('',(4.440892098501E-016,-1.)); +#138295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135904 = ORIENTED_EDGE('',*,*,#135905,.T.); -#135905 = EDGE_CURVE('',#135884,#135636,#135906,.T.); -#135906 = SURFACE_CURVE('',#135907,(#135912,#135918),.PCURVE_S1.); -#135907 = CIRCLE('',#135908,0.119270391569); -#135908 = AXIS2_PLACEMENT_3D('',#135909,#135910,#135911); -#135909 = CARTESIAN_POINT('',(10.30032442045,1.15,0.530776333563)); -#135910 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); -#135911 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); -#135912 = PCURVE('',#135653,#135913); -#135913 = DEFINITIONAL_REPRESENTATION('',(#135914),#135917); -#135914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#135915,#135916), +#138296 = ORIENTED_EDGE('',*,*,#138297,.T.); +#138297 = EDGE_CURVE('',#138276,#138028,#138298,.T.); +#138298 = SURFACE_CURVE('',#138299,(#138304,#138310),.PCURVE_S1.); +#138299 = CIRCLE('',#138300,0.119270391569); +#138300 = AXIS2_PLACEMENT_3D('',#138301,#138302,#138303); +#138301 = CARTESIAN_POINT('',(10.30032442045,1.15,0.530776333563)); +#138302 = DIRECTION('',(4.440892098501E-016,1.,0.E+000)); +#138303 = DIRECTION('',(-1.,4.440892098501E-016,0.E+000)); +#138304 = PCURVE('',#138045,#138305); +#138305 = DEFINITIONAL_REPRESENTATION('',(#138306),#138309); +#138306 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138307,#138308), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#135915 = CARTESIAN_POINT('',(1.598788597134,1.15)); -#135916 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#135917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138307 = CARTESIAN_POINT('',(1.598788597134,1.15)); +#138308 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#138309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135918 = PCURVE('',#92340,#135919); -#135919 = DEFINITIONAL_REPRESENTATION('',(#135920),#135928); -#135920 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#135921,#135922,#135923, - #135924,#135925,#135926,#135927),.UNSPECIFIED.,.T.,.F.) +#138310 = PCURVE('',#94732,#138311); +#138311 = DEFINITIONAL_REPRESENTATION('',(#138312),#138320); +#138312 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138313,#138314,#138315, + #138316,#138317,#138318,#138319),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#135921 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#135922 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#135923 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#135924 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#135925 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#135926 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#135927 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#135928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135929 = ADVANCED_FACE('',(#135930),#92312,.T.); -#135930 = FACE_BOUND('',#135931,.T.); -#135931 = EDGE_LOOP('',(#135932,#135953,#135954,#135975)); -#135932 = ORIENTED_EDGE('',*,*,#135933,.F.); -#135933 = EDGE_CURVE('',#135861,#92264,#135934,.T.); -#135934 = SURFACE_CURVE('',#135935,(#135939,#135946),.PCURVE_S1.); -#135935 = LINE('',#135936,#135937); -#135936 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); -#135937 = VECTOR('',#135938,1.); -#135938 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135939 = PCURVE('',#92312,#135940); -#135940 = DEFINITIONAL_REPRESENTATION('',(#135941),#135945); -#135941 = LINE('',#135942,#135943); -#135942 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135943 = VECTOR('',#135944,1.); -#135944 = DIRECTION('',(1.,-1.082494723017E-063)); -#135945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135946 = PCURVE('',#92284,#135947); -#135947 = DEFINITIONAL_REPRESENTATION('',(#135948),#135952); -#135948 = LINE('',#135949,#135950); -#135949 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135950 = VECTOR('',#135951,1.); -#135951 = DIRECTION('',(3.563627120235E-016,-1.)); -#135952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138313 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#138314 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#138315 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#138316 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#138317 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#138318 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#138319 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#138320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138321 = ADVANCED_FACE('',(#138322),#94704,.T.); +#138322 = FACE_BOUND('',#138323,.T.); +#138323 = EDGE_LOOP('',(#138324,#138345,#138346,#138367)); +#138324 = ORIENTED_EDGE('',*,*,#138325,.F.); +#138325 = EDGE_CURVE('',#138253,#94656,#138326,.T.); +#138326 = SURFACE_CURVE('',#138327,(#138331,#138338),.PCURVE_S1.); +#138327 = LINE('',#138328,#138329); +#138328 = CARTESIAN_POINT('',(10.527847992439,1.35,0.65)); +#138329 = VECTOR('',#138330,1.); +#138330 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#138331 = PCURVE('',#94704,#138332); +#138332 = DEFINITIONAL_REPRESENTATION('',(#138333),#138337); +#138333 = LINE('',#138334,#138335); +#138334 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138335 = VECTOR('',#138336,1.); +#138336 = DIRECTION('',(1.,-1.082494723017E-063)); +#138337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138338 = PCURVE('',#94676,#138339); +#138339 = DEFINITIONAL_REPRESENTATION('',(#138340),#138344); +#138340 = LINE('',#138341,#138342); +#138341 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138342 = VECTOR('',#138343,1.); +#138343 = DIRECTION('',(3.563627120235E-016,-1.)); +#138344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138345 = ORIENTED_EDGE('',*,*,#138275,.T.); +#138346 = ORIENTED_EDGE('',*,*,#138347,.T.); +#138347 = EDGE_CURVE('',#138276,#94689,#138348,.T.); +#138348 = SURFACE_CURVE('',#138349,(#138353,#138360),.PCURVE_S1.); +#138349 = LINE('',#138350,#138351); +#138350 = CARTESIAN_POINT('',(10.527847992439,1.15,0.65)); +#138351 = VECTOR('',#138352,1.); +#138352 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#138353 = PCURVE('',#94704,#138354); +#138354 = DEFINITIONAL_REPRESENTATION('',(#138355),#138359); +#138355 = LINE('',#138356,#138357); +#138356 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#138357 = VECTOR('',#138358,1.); +#138358 = DIRECTION('',(1.,-1.082494723017E-063)); +#138359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138360 = PCURVE('',#94732,#138361); +#138361 = DEFINITIONAL_REPRESENTATION('',(#138362),#138366); +#138362 = LINE('',#138363,#138364); +#138363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138364 = VECTOR('',#138365,1.); +#138365 = DIRECTION('',(-3.563627120235E-016,-1.)); +#138366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138367 = ORIENTED_EDGE('',*,*,#94688,.F.); +#138368 = ADVANCED_FACE('',(#138369),#94732,.T.); +#138369 = FACE_BOUND('',#138370,.T.); +#138370 = EDGE_LOOP('',(#138371,#138372,#138373,#138374,#138375,#138376, + #138397,#138398,#138399,#138400,#138401,#138422)); +#138371 = ORIENTED_EDGE('',*,*,#138347,.F.); +#138372 = ORIENTED_EDGE('',*,*,#138297,.T.); +#138373 = ORIENTED_EDGE('',*,*,#138078,.T.); +#138374 = ORIENTED_EDGE('',*,*,#137953,.T.); +#138375 = ORIENTED_EDGE('',*,*,#137749,.T.); +#138376 = ORIENTED_EDGE('',*,*,#138377,.F.); +#138377 = EDGE_CURVE('',#137613,#137720,#138378,.T.); +#138378 = SURFACE_CURVE('',#138379,(#138383,#138390),.PCURVE_S1.); +#138379 = LINE('',#138380,#138381); +#138380 = CARTESIAN_POINT('',(11.,1.15,1.159810404338E-002)); +#138381 = VECTOR('',#138382,1.); +#138382 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); +#138383 = PCURVE('',#94732,#138384); +#138384 = DEFINITIONAL_REPRESENTATION('',(#138385),#138389); +#138385 = LINE('',#138386,#138387); +#138386 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#138387 = VECTOR('',#138388,1.); +#138388 = DIRECTION('',(1.,-2.101748079665E-016)); +#138389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138390 = PCURVE('',#137633,#138391); +#138391 = DEFINITIONAL_REPRESENTATION('',(#138392),#138396); +#138392 = LINE('',#138393,#138394); +#138393 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#138394 = VECTOR('',#138395,1.); +#138395 = DIRECTION('',(-1.194699204908E-017,-1.)); +#138396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138397 = ORIENTED_EDGE('',*,*,#137695,.F.); +#138398 = ORIENTED_EDGE('',*,*,#137823,.F.); +#138399 = ORIENTED_EDGE('',*,*,#138131,.F.); +#138400 = ORIENTED_EDGE('',*,*,#138223,.F.); +#138401 = ORIENTED_EDGE('',*,*,#138402,.T.); +#138402 = EDGE_CURVE('',#138202,#94717,#138403,.T.); +#138403 = SURFACE_CURVE('',#138404,(#138408,#138415),.PCURVE_S1.); +#138404 = LINE('',#138405,#138406); +#138405 = CARTESIAN_POINT('',(10.527847992439,1.15,0.75)); +#138406 = VECTOR('',#138407,1.); +#138407 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#138408 = PCURVE('',#94732,#138409); +#138409 = DEFINITIONAL_REPRESENTATION('',(#138410),#138414); +#138410 = LINE('',#138411,#138412); +#138411 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#138412 = VECTOR('',#138413,1.); +#138413 = DIRECTION('',(-3.563627120235E-016,-1.)); +#138414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138415 = PCURVE('',#94758,#138416); +#138416 = DEFINITIONAL_REPRESENTATION('',(#138417),#138421); +#138417 = LINE('',#138418,#138419); +#138418 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#138419 = VECTOR('',#138420,1.); +#138420 = DIRECTION('',(-1.,-1.082494723017E-063)); +#138421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138422 = ORIENTED_EDGE('',*,*,#94716,.F.); +#138423 = ADVANCED_FACE('',(#138424),#94758,.T.); +#138424 = FACE_BOUND('',#138425,.T.); +#138425 = EDGE_LOOP('',(#138426,#138427,#138428,#138449)); +#138426 = ORIENTED_EDGE('',*,*,#138402,.F.); +#138427 = ORIENTED_EDGE('',*,*,#138201,.T.); +#138428 = ORIENTED_EDGE('',*,*,#138429,.T.); +#138429 = EDGE_CURVE('',#138179,#94654,#138430,.T.); +#138430 = SURFACE_CURVE('',#138431,(#138435,#138442),.PCURVE_S1.); +#138431 = LINE('',#138432,#138433); +#138432 = CARTESIAN_POINT('',(10.527847992439,1.35,0.75)); +#138433 = VECTOR('',#138434,1.); +#138434 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); +#138435 = PCURVE('',#94758,#138436); +#138436 = DEFINITIONAL_REPRESENTATION('',(#138437),#138441); +#138437 = LINE('',#138438,#138439); +#138438 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138439 = VECTOR('',#138440,1.); +#138440 = DIRECTION('',(-1.,-1.082494723017E-063)); +#138441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138442 = PCURVE('',#94676,#138443); +#138443 = DEFINITIONAL_REPRESENTATION('',(#138444),#138448); +#138444 = LINE('',#138445,#138446); +#138445 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#138446 = VECTOR('',#138447,1.); +#138447 = DIRECTION('',(3.563627120235E-016,-1.)); +#138448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138449 = ORIENTED_EDGE('',*,*,#94744,.F.); +#138450 = ADVANCED_FACE('',(#138451),#94676,.T.); +#138451 = FACE_BOUND('',#138452,.T.); +#138452 = EDGE_LOOP('',(#138453,#138454,#138455,#138456,#138457,#138458, + #138479,#138480,#138481,#138482,#138483,#138484)); +#138453 = ORIENTED_EDGE('',*,*,#138429,.F.); +#138454 = ORIENTED_EDGE('',*,*,#138178,.T.); +#138455 = ORIENTED_EDGE('',*,*,#138153,.T.); +#138456 = ORIENTED_EDGE('',*,*,#137873,.T.); +#138457 = ORIENTED_EDGE('',*,*,#137645,.T.); +#138458 = ORIENTED_EDGE('',*,*,#138459,.F.); +#138459 = EDGE_CURVE('',#137722,#137611,#138460,.T.); +#138460 = SURFACE_CURVE('',#138461,(#138465,#138472),.PCURVE_S1.); +#138461 = LINE('',#138462,#138463); +#138462 = CARTESIAN_POINT('',(11.,1.35,1.159810404338E-002)); +#138463 = VECTOR('',#138464,1.); +#138464 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); +#138465 = PCURVE('',#94676,#138466); +#138466 = DEFINITIONAL_REPRESENTATION('',(#138467),#138471); +#138467 = LINE('',#138468,#138469); +#138468 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#138469 = VECTOR('',#138470,1.); +#138470 = DIRECTION('',(1.,2.101748079665E-016)); +#138471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138472 = PCURVE('',#137633,#138473); +#138473 = DEFINITIONAL_REPRESENTATION('',(#138474),#138478); +#138474 = LINE('',#138475,#138476); +#138475 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#138476 = VECTOR('',#138477,1.); +#138477 = DIRECTION('',(1.194699204908E-017,1.)); +#138478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138479 = ORIENTED_EDGE('',*,*,#137799,.F.); +#138480 = ORIENTED_EDGE('',*,*,#137902,.F.); +#138481 = ORIENTED_EDGE('',*,*,#138056,.F.); +#138482 = ORIENTED_EDGE('',*,*,#138252,.F.); +#138483 = ORIENTED_EDGE('',*,*,#138325,.T.); +#138484 = ORIENTED_EDGE('',*,*,#94653,.F.); +#138485 = ADVANCED_FACE('',(#138486),#137633,.T.); +#138486 = FACE_BOUND('',#138487,.T.); +#138487 = EDGE_LOOP('',(#138488,#138489,#138490,#138491)); +#138488 = ORIENTED_EDGE('',*,*,#138377,.T.); +#138489 = ORIENTED_EDGE('',*,*,#137719,.T.); +#138490 = ORIENTED_EDGE('',*,*,#138459,.T.); +#138491 = ORIENTED_EDGE('',*,*,#137610,.T.); +#138492 = ADVANCED_FACE('',(#138493),#138507,.T.); +#138493 = FACE_BOUND('',#138494,.T.); +#138494 = EDGE_LOOP('',(#138495,#138525,#138553,#138576)); +#138495 = ORIENTED_EDGE('',*,*,#138496,.T.); +#138496 = EDGE_CURVE('',#138497,#138499,#138501,.T.); +#138497 = VERTEX_POINT('',#138498); +#138498 = CARTESIAN_POINT('',(8.85,10.740726081328,-0.208196358798)); +#138499 = VERTEX_POINT('',#138500); +#138500 = CARTESIAN_POINT('',(8.85,11.,-0.208196358798)); +#138501 = SURFACE_CURVE('',#138502,(#138506,#138518),.PCURVE_S1.); +#138502 = LINE('',#138503,#138504); +#138503 = CARTESIAN_POINT('',(8.85,10.740726081328,-0.208196358798)); +#138504 = VECTOR('',#138505,1.); +#138505 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#138506 = PCURVE('',#138507,#138512); +#138507 = PLANE('',#138508); +#138508 = AXIS2_PLACEMENT_3D('',#138509,#138510,#138511); +#138509 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#138510 = DIRECTION('',(0.E+000,0.E+000,1.)); +#138511 = DIRECTION('',(1.,0.E+000,0.E+000)); +#138512 = DEFINITIONAL_REPRESENTATION('',(#138513),#138517); +#138513 = LINE('',#138514,#138515); +#138514 = CARTESIAN_POINT('',(8.85,-5.329070518201E-015)); +#138515 = VECTOR('',#138516,1.); +#138516 = DIRECTION('',(6.725593854929E-015,1.)); +#138517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138518 = PCURVE('',#89832,#138519); +#138519 = DEFINITIONAL_REPRESENTATION('',(#138520),#138524); +#138520 = LINE('',#138521,#138522); +#138521 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#138522 = VECTOR('',#138523,1.); +#138523 = DIRECTION('',(0.E+000,1.)); +#138524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138525 = ORIENTED_EDGE('',*,*,#138526,.T.); +#138526 = EDGE_CURVE('',#138499,#138527,#138529,.T.); +#138527 = VERTEX_POINT('',#138528); +#138528 = CARTESIAN_POINT('',(8.65,11.,-0.208196358798)); +#138529 = SURFACE_CURVE('',#138530,(#138534,#138541),.PCURVE_S1.); +#138530 = LINE('',#138531,#138532); +#138531 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#138532 = VECTOR('',#138533,1.); +#138533 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138534 = PCURVE('',#138507,#138535); +#138535 = DEFINITIONAL_REPRESENTATION('',(#138536),#138540); +#138536 = LINE('',#138537,#138538); +#138537 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#138538 = VECTOR('',#138539,1.); +#138539 = DIRECTION('',(-1.,8.881784197001E-016)); +#138540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#135953 = ORIENTED_EDGE('',*,*,#135883,.T.); -#135954 = ORIENTED_EDGE('',*,*,#135955,.T.); -#135955 = EDGE_CURVE('',#135884,#92297,#135956,.T.); -#135956 = SURFACE_CURVE('',#135957,(#135961,#135968),.PCURVE_S1.); -#135957 = LINE('',#135958,#135959); -#135958 = CARTESIAN_POINT('',(10.527847992439,1.15,0.65)); -#135959 = VECTOR('',#135960,1.); -#135960 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#135961 = PCURVE('',#92312,#135962); -#135962 = DEFINITIONAL_REPRESENTATION('',(#135963),#135967); -#135963 = LINE('',#135964,#135965); -#135964 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#135965 = VECTOR('',#135966,1.); -#135966 = DIRECTION('',(1.,-1.082494723017E-063)); -#135967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135968 = PCURVE('',#92340,#135969); -#135969 = DEFINITIONAL_REPRESENTATION('',(#135970),#135974); -#135970 = LINE('',#135971,#135972); -#135971 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#135972 = VECTOR('',#135973,1.); -#135973 = DIRECTION('',(-3.563627120235E-016,-1.)); -#135974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135975 = ORIENTED_EDGE('',*,*,#92296,.F.); -#135976 = ADVANCED_FACE('',(#135977),#92340,.T.); -#135977 = FACE_BOUND('',#135978,.T.); -#135978 = EDGE_LOOP('',(#135979,#135980,#135981,#135982,#135983,#135984, - #136005,#136006,#136007,#136008,#136009,#136030)); -#135979 = ORIENTED_EDGE('',*,*,#135955,.F.); -#135980 = ORIENTED_EDGE('',*,*,#135905,.T.); -#135981 = ORIENTED_EDGE('',*,*,#135686,.T.); -#135982 = ORIENTED_EDGE('',*,*,#135561,.T.); -#135983 = ORIENTED_EDGE('',*,*,#135357,.T.); -#135984 = ORIENTED_EDGE('',*,*,#135985,.F.); -#135985 = EDGE_CURVE('',#135221,#135328,#135986,.T.); -#135986 = SURFACE_CURVE('',#135987,(#135991,#135998),.PCURVE_S1.); -#135987 = LINE('',#135988,#135989); -#135988 = CARTESIAN_POINT('',(11.,1.15,1.159810404338E-002)); -#135989 = VECTOR('',#135990,1.); -#135990 = DIRECTION('',(-2.101748079665E-016,-1.194699204908E-017,-1.)); -#135991 = PCURVE('',#92340,#135992); -#135992 = DEFINITIONAL_REPRESENTATION('',(#135993),#135997); -#135993 = LINE('',#135994,#135995); -#135994 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#135995 = VECTOR('',#135996,1.); -#135996 = DIRECTION('',(1.,-2.101748079665E-016)); -#135997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#135998 = PCURVE('',#135241,#135999); -#135999 = DEFINITIONAL_REPRESENTATION('',(#136000),#136004); -#136000 = LINE('',#136001,#136002); -#136001 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#136002 = VECTOR('',#136003,1.); -#136003 = DIRECTION('',(-1.194699204908E-017,-1.)); -#136004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136005 = ORIENTED_EDGE('',*,*,#135303,.F.); -#136006 = ORIENTED_EDGE('',*,*,#135431,.F.); -#136007 = ORIENTED_EDGE('',*,*,#135739,.F.); -#136008 = ORIENTED_EDGE('',*,*,#135831,.F.); -#136009 = ORIENTED_EDGE('',*,*,#136010,.T.); -#136010 = EDGE_CURVE('',#135810,#92325,#136011,.T.); -#136011 = SURFACE_CURVE('',#136012,(#136016,#136023),.PCURVE_S1.); -#136012 = LINE('',#136013,#136014); -#136013 = CARTESIAN_POINT('',(10.527847992439,1.15,0.75)); -#136014 = VECTOR('',#136015,1.); -#136015 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#136016 = PCURVE('',#92340,#136017); -#136017 = DEFINITIONAL_REPRESENTATION('',(#136018),#136022); -#136018 = LINE('',#136019,#136020); -#136019 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#136020 = VECTOR('',#136021,1.); -#136021 = DIRECTION('',(-3.563627120235E-016,-1.)); -#136022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136023 = PCURVE('',#92366,#136024); -#136024 = DEFINITIONAL_REPRESENTATION('',(#136025),#136029); -#136025 = LINE('',#136026,#136027); -#136026 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#136027 = VECTOR('',#136028,1.); -#136028 = DIRECTION('',(-1.,-1.082494723017E-063)); -#136029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136030 = ORIENTED_EDGE('',*,*,#92324,.F.); -#136031 = ADVANCED_FACE('',(#136032),#92366,.T.); -#136032 = FACE_BOUND('',#136033,.T.); -#136033 = EDGE_LOOP('',(#136034,#136035,#136036,#136057)); -#136034 = ORIENTED_EDGE('',*,*,#136010,.F.); -#136035 = ORIENTED_EDGE('',*,*,#135809,.T.); -#136036 = ORIENTED_EDGE('',*,*,#136037,.T.); -#136037 = EDGE_CURVE('',#135787,#92262,#136038,.T.); -#136038 = SURFACE_CURVE('',#136039,(#136043,#136050),.PCURVE_S1.); -#136039 = LINE('',#136040,#136041); -#136040 = CARTESIAN_POINT('',(10.527847992439,1.35,0.75)); -#136041 = VECTOR('',#136042,1.); -#136042 = DIRECTION('',(-1.,0.E+000,3.563627120235E-016)); -#136043 = PCURVE('',#92366,#136044); -#136044 = DEFINITIONAL_REPRESENTATION('',(#136045),#136049); -#136045 = LINE('',#136046,#136047); -#136046 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136047 = VECTOR('',#136048,1.); -#136048 = DIRECTION('',(-1.,-1.082494723017E-063)); -#136049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136050 = PCURVE('',#92284,#136051); -#136051 = DEFINITIONAL_REPRESENTATION('',(#136052),#136056); -#136052 = LINE('',#136053,#136054); -#136053 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#136054 = VECTOR('',#136055,1.); -#136055 = DIRECTION('',(3.563627120235E-016,-1.)); -#136056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136057 = ORIENTED_EDGE('',*,*,#92352,.F.); -#136058 = ADVANCED_FACE('',(#136059),#92284,.T.); -#136059 = FACE_BOUND('',#136060,.T.); -#136060 = EDGE_LOOP('',(#136061,#136062,#136063,#136064,#136065,#136066, - #136087,#136088,#136089,#136090,#136091,#136092)); -#136061 = ORIENTED_EDGE('',*,*,#136037,.F.); -#136062 = ORIENTED_EDGE('',*,*,#135786,.T.); -#136063 = ORIENTED_EDGE('',*,*,#135761,.T.); -#136064 = ORIENTED_EDGE('',*,*,#135481,.T.); -#136065 = ORIENTED_EDGE('',*,*,#135253,.T.); -#136066 = ORIENTED_EDGE('',*,*,#136067,.F.); -#136067 = EDGE_CURVE('',#135330,#135219,#136068,.T.); -#136068 = SURFACE_CURVE('',#136069,(#136073,#136080),.PCURVE_S1.); -#136069 = LINE('',#136070,#136071); -#136070 = CARTESIAN_POINT('',(11.,1.35,1.159810404338E-002)); -#136071 = VECTOR('',#136072,1.); -#136072 = DIRECTION('',(2.101748079665E-016,1.194699204908E-017,1.)); -#136073 = PCURVE('',#92284,#136074); -#136074 = DEFINITIONAL_REPRESENTATION('',(#136075),#136079); -#136075 = LINE('',#136076,#136077); -#136076 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#136077 = VECTOR('',#136078,1.); -#136078 = DIRECTION('',(1.,2.101748079665E-016)); -#136079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136080 = PCURVE('',#135241,#136081); -#136081 = DEFINITIONAL_REPRESENTATION('',(#136082),#136086); -#136082 = LINE('',#136083,#136084); -#136083 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#136084 = VECTOR('',#136085,1.); -#136085 = DIRECTION('',(1.194699204908E-017,1.)); -#136086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136087 = ORIENTED_EDGE('',*,*,#135407,.F.); -#136088 = ORIENTED_EDGE('',*,*,#135510,.F.); -#136089 = ORIENTED_EDGE('',*,*,#135664,.F.); -#136090 = ORIENTED_EDGE('',*,*,#135860,.F.); -#136091 = ORIENTED_EDGE('',*,*,#135933,.T.); -#136092 = ORIENTED_EDGE('',*,*,#92261,.F.); -#136093 = ADVANCED_FACE('',(#136094),#135241,.T.); -#136094 = FACE_BOUND('',#136095,.T.); -#136095 = EDGE_LOOP('',(#136096,#136097,#136098,#136099)); -#136096 = ORIENTED_EDGE('',*,*,#135985,.T.); -#136097 = ORIENTED_EDGE('',*,*,#135327,.T.); -#136098 = ORIENTED_EDGE('',*,*,#136067,.T.); -#136099 = ORIENTED_EDGE('',*,*,#135218,.T.); -#136100 = ADVANCED_FACE('',(#136101),#136115,.T.); -#136101 = FACE_BOUND('',#136102,.T.); -#136102 = EDGE_LOOP('',(#136103,#136133,#136161,#136184)); -#136103 = ORIENTED_EDGE('',*,*,#136104,.T.); -#136104 = EDGE_CURVE('',#136105,#136107,#136109,.T.); -#136105 = VERTEX_POINT('',#136106); -#136106 = CARTESIAN_POINT('',(8.85,10.740726081328,-0.208196358798)); -#136107 = VERTEX_POINT('',#136108); -#136108 = CARTESIAN_POINT('',(8.85,11.,-0.208196358798)); -#136109 = SURFACE_CURVE('',#136110,(#136114,#136126),.PCURVE_S1.); -#136110 = LINE('',#136111,#136112); -#136111 = CARTESIAN_POINT('',(8.85,10.740726081328,-0.208196358798)); -#136112 = VECTOR('',#136113,1.); -#136113 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#136114 = PCURVE('',#136115,#136120); -#136115 = PLANE('',#136116); -#136116 = AXIS2_PLACEMENT_3D('',#136117,#136118,#136119); -#136117 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#138541 = PCURVE('',#138542,#138547); +#138542 = PLANE('',#138543); +#138543 = AXIS2_PLACEMENT_3D('',#138544,#138545,#138546); +#138544 = CARTESIAN_POINT('',(8.75,11.,-0.258196742327)); +#138545 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#138546 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#138547 = DEFINITIONAL_REPRESENTATION('',(#138548),#138552); +#138548 = LINE('',#138549,#138550); +#138549 = CARTESIAN_POINT('',(8.75,5.000038352949E-002)); +#138550 = VECTOR('',#138551,1.); +#138551 = DIRECTION('',(1.,1.1653254136E-048)); +#138552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138553 = ORIENTED_EDGE('',*,*,#138554,.F.); +#138554 = EDGE_CURVE('',#138555,#138527,#138557,.T.); +#138555 = VERTEX_POINT('',#138556); +#138556 = CARTESIAN_POINT('',(8.65,10.740726081328,-0.208196358798)); +#138557 = SURFACE_CURVE('',#138558,(#138562,#138569),.PCURVE_S1.); +#138558 = LINE('',#138559,#138560); +#138559 = CARTESIAN_POINT('',(8.65,10.740726081328,-0.208196358798)); +#138560 = VECTOR('',#138561,1.); +#138561 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#138562 = PCURVE('',#138507,#138563); +#138563 = DEFINITIONAL_REPRESENTATION('',(#138564),#138568); +#138564 = LINE('',#138565,#138566); +#138565 = CARTESIAN_POINT('',(8.65,-7.105427357601E-015)); +#138566 = VECTOR('',#138567,1.); +#138567 = DIRECTION('',(6.725593854929E-015,1.)); +#138568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138569 = PCURVE('',#89776,#138570); +#138570 = DEFINITIONAL_REPRESENTATION('',(#138571),#138575); +#138571 = LINE('',#138572,#138573); +#138572 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#138573 = VECTOR('',#138574,1.); +#138574 = DIRECTION('',(0.E+000,1.)); +#138575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138576 = ORIENTED_EDGE('',*,*,#138577,.T.); +#138577 = EDGE_CURVE('',#138555,#138497,#138578,.T.); +#138578 = SURFACE_CURVE('',#138579,(#138583,#138590),.PCURVE_S1.); +#138579 = LINE('',#138580,#138581); +#138580 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#136118 = DIRECTION('',(0.E+000,0.E+000,1.)); -#136119 = DIRECTION('',(1.,0.E+000,0.E+000)); -#136120 = DEFINITIONAL_REPRESENTATION('',(#136121),#136125); -#136121 = LINE('',#136122,#136123); -#136122 = CARTESIAN_POINT('',(8.85,-5.329070518201E-015)); -#136123 = VECTOR('',#136124,1.); -#136124 = DIRECTION('',(6.725593854929E-015,1.)); -#136125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136126 = PCURVE('',#87440,#136127); -#136127 = DEFINITIONAL_REPRESENTATION('',(#136128),#136132); -#136128 = LINE('',#136129,#136130); -#136129 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#136130 = VECTOR('',#136131,1.); -#136131 = DIRECTION('',(0.E+000,1.)); -#136132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138581 = VECTOR('',#138582,1.); +#138582 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138583 = PCURVE('',#138507,#138584); +#138584 = DEFINITIONAL_REPRESENTATION('',(#138585),#138589); +#138585 = LINE('',#138586,#138587); +#138586 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138587 = VECTOR('',#138588,1.); +#138588 = DIRECTION('',(1.,-8.881784197001E-016)); +#138589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136133 = ORIENTED_EDGE('',*,*,#136134,.T.); -#136134 = EDGE_CURVE('',#136107,#136135,#136137,.T.); -#136135 = VERTEX_POINT('',#136136); -#136136 = CARTESIAN_POINT('',(8.65,11.,-0.208196358798)); -#136137 = SURFACE_CURVE('',#136138,(#136142,#136149),.PCURVE_S1.); -#136138 = LINE('',#136139,#136140); -#136139 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#136140 = VECTOR('',#136141,1.); -#136141 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136142 = PCURVE('',#136115,#136143); -#136143 = DEFINITIONAL_REPRESENTATION('',(#136144),#136148); -#136144 = LINE('',#136145,#136146); -#136145 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#136146 = VECTOR('',#136147,1.); -#136147 = DIRECTION('',(-1.,8.881784197001E-016)); -#136148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136149 = PCURVE('',#136150,#136155); -#136150 = PLANE('',#136151); -#136151 = AXIS2_PLACEMENT_3D('',#136152,#136153,#136154); -#136152 = CARTESIAN_POINT('',(8.75,11.,-0.258196742327)); -#136153 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#136154 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#136155 = DEFINITIONAL_REPRESENTATION('',(#136156),#136160); -#136156 = LINE('',#136157,#136158); -#136157 = CARTESIAN_POINT('',(8.75,5.000038352949E-002)); -#136158 = VECTOR('',#136159,1.); -#136159 = DIRECTION('',(1.,1.1653254136E-048)); -#136160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136161 = ORIENTED_EDGE('',*,*,#136162,.F.); -#136162 = EDGE_CURVE('',#136163,#136135,#136165,.T.); -#136163 = VERTEX_POINT('',#136164); -#136164 = CARTESIAN_POINT('',(8.65,10.740726081328,-0.208196358798)); -#136165 = SURFACE_CURVE('',#136166,(#136170,#136177),.PCURVE_S1.); -#136166 = LINE('',#136167,#136168); -#136167 = CARTESIAN_POINT('',(8.65,10.740726081328,-0.208196358798)); -#136168 = VECTOR('',#136169,1.); -#136169 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#136170 = PCURVE('',#136115,#136171); -#136171 = DEFINITIONAL_REPRESENTATION('',(#136172),#136176); -#136172 = LINE('',#136173,#136174); -#136173 = CARTESIAN_POINT('',(8.65,-7.105427357601E-015)); -#136174 = VECTOR('',#136175,1.); -#136175 = DIRECTION('',(6.725593854929E-015,1.)); -#136176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136177 = PCURVE('',#87384,#136178); -#136178 = DEFINITIONAL_REPRESENTATION('',(#136179),#136183); -#136179 = LINE('',#136180,#136181); -#136180 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#136181 = VECTOR('',#136182,1.); -#136182 = DIRECTION('',(0.E+000,1.)); -#136183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136184 = ORIENTED_EDGE('',*,*,#136185,.T.); -#136185 = EDGE_CURVE('',#136163,#136105,#136186,.T.); -#136186 = SURFACE_CURVE('',#136187,(#136191,#136198),.PCURVE_S1.); -#136187 = LINE('',#136188,#136189); -#136188 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#136189 = VECTOR('',#136190,1.); -#136190 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136191 = PCURVE('',#136115,#136192); -#136192 = DEFINITIONAL_REPRESENTATION('',(#136193),#136197); -#136193 = LINE('',#136194,#136195); -#136194 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136195 = VECTOR('',#136196,1.); -#136196 = DIRECTION('',(1.,-8.881784197001E-016)); -#136197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136198 = PCURVE('',#136199,#136204); -#136199 = CYLINDRICAL_SURFACE('',#136200,0.208574704164); -#136200 = AXIS2_PLACEMENT_3D('',#136201,#136202,#136203); -#136201 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#138590 = PCURVE('',#138591,#138596); +#138591 = CYLINDRICAL_SURFACE('',#138592,0.208574704164); +#138592 = AXIS2_PLACEMENT_3D('',#138593,#138594,#138595); +#138593 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#136202 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136203 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136204 = DEFINITIONAL_REPRESENTATION('',(#136205),#136208); -#136205 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136206,#136207), +#138594 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138595 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138596 = DEFINITIONAL_REPRESENTATION('',(#138597),#138600); +#138597 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138598,#138599), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#136206 = CARTESIAN_POINT('',(4.772630242227,8.65)); -#136207 = CARTESIAN_POINT('',(4.772630242227,8.85)); -#136208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136209 = ADVANCED_FACE('',(#136210),#136224,.T.); -#136210 = FACE_BOUND('',#136211,.T.); -#136211 = EDGE_LOOP('',(#136212,#136242,#136265,#136288)); -#136212 = ORIENTED_EDGE('',*,*,#136213,.T.); -#136213 = EDGE_CURVE('',#136214,#136216,#136218,.T.); -#136214 = VERTEX_POINT('',#136215); -#136215 = CARTESIAN_POINT('',(8.65,10.74341632541,-0.308197125857)); -#136216 = VERTEX_POINT('',#136217); -#136217 = CARTESIAN_POINT('',(8.65,11.,-0.308197125857)); -#136218 = SURFACE_CURVE('',#136219,(#136223,#136235),.PCURVE_S1.); -#136219 = LINE('',#136220,#136221); -#136220 = CARTESIAN_POINT('',(8.65,10.74341632541,-0.308197125857)); -#136221 = VECTOR('',#136222,1.); -#136222 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#136223 = PCURVE('',#136224,#136229); -#136224 = PLANE('',#136225); -#136225 = AXIS2_PLACEMENT_3D('',#136226,#136227,#136228); -#136226 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#138598 = CARTESIAN_POINT('',(4.772630242227,8.65)); +#138599 = CARTESIAN_POINT('',(4.772630242227,8.85)); +#138600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138601 = ADVANCED_FACE('',(#138602),#138616,.T.); +#138602 = FACE_BOUND('',#138603,.T.); +#138603 = EDGE_LOOP('',(#138604,#138634,#138657,#138680)); +#138604 = ORIENTED_EDGE('',*,*,#138605,.T.); +#138605 = EDGE_CURVE('',#138606,#138608,#138610,.T.); +#138606 = VERTEX_POINT('',#138607); +#138607 = CARTESIAN_POINT('',(8.65,10.74341632541,-0.308197125857)); +#138608 = VERTEX_POINT('',#138609); +#138609 = CARTESIAN_POINT('',(8.65,11.,-0.308197125857)); +#138610 = SURFACE_CURVE('',#138611,(#138615,#138627),.PCURVE_S1.); +#138611 = LINE('',#138612,#138613); +#138612 = CARTESIAN_POINT('',(8.65,10.74341632541,-0.308197125857)); +#138613 = VECTOR('',#138614,1.); +#138614 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#138615 = PCURVE('',#138616,#138621); +#138616 = PLANE('',#138617); +#138617 = AXIS2_PLACEMENT_3D('',#138618,#138619,#138620); +#138618 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#136227 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136228 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#136229 = DEFINITIONAL_REPRESENTATION('',(#136230),#136234); -#136230 = LINE('',#136231,#136232); -#136231 = CARTESIAN_POINT('',(-8.65,-7.105427357601E-015)); -#136232 = VECTOR('',#136233,1.); -#136233 = DIRECTION('',(-6.725593854929E-015,1.)); -#136234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136235 = PCURVE('',#87384,#136236); -#136236 = DEFINITIONAL_REPRESENTATION('',(#136237),#136241); -#136237 = LINE('',#136238,#136239); -#136238 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#136239 = VECTOR('',#136240,1.); -#136240 = DIRECTION('',(0.E+000,1.)); -#136241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136242 = ORIENTED_EDGE('',*,*,#136243,.T.); -#136243 = EDGE_CURVE('',#136216,#136244,#136246,.T.); -#136244 = VERTEX_POINT('',#136245); -#136245 = CARTESIAN_POINT('',(8.85,11.,-0.308197125857)); -#136246 = SURFACE_CURVE('',#136247,(#136251,#136258),.PCURVE_S1.); -#136247 = LINE('',#136248,#136249); -#136248 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#136249 = VECTOR('',#136250,1.); -#136250 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136251 = PCURVE('',#136224,#136252); -#136252 = DEFINITIONAL_REPRESENTATION('',(#136253),#136257); -#136253 = LINE('',#136254,#136255); -#136254 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#136255 = VECTOR('',#136256,1.); -#136256 = DIRECTION('',(-1.,-8.881784197001E-016)); -#136257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136258 = PCURVE('',#136150,#136259); -#136259 = DEFINITIONAL_REPRESENTATION('',(#136260),#136264); -#136260 = LINE('',#136261,#136262); -#136261 = CARTESIAN_POINT('',(8.75,-5.000038352949E-002)); -#136262 = VECTOR('',#136263,1.); -#136263 = DIRECTION('',(-1.,-1.1653254136E-048)); -#136264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136265 = ORIENTED_EDGE('',*,*,#136266,.F.); -#136266 = EDGE_CURVE('',#136267,#136244,#136269,.T.); -#136267 = VERTEX_POINT('',#136268); -#136268 = CARTESIAN_POINT('',(8.85,10.74341632541,-0.308197125857)); -#136269 = SURFACE_CURVE('',#136270,(#136274,#136281),.PCURVE_S1.); -#136270 = LINE('',#136271,#136272); -#136271 = CARTESIAN_POINT('',(8.85,10.74341632541,-0.308197125857)); -#136272 = VECTOR('',#136273,1.); -#136273 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#136274 = PCURVE('',#136224,#136275); -#136275 = DEFINITIONAL_REPRESENTATION('',(#136276),#136280); -#136276 = LINE('',#136277,#136278); -#136277 = CARTESIAN_POINT('',(-8.85,-7.105427357601E-015)); -#136278 = VECTOR('',#136279,1.); -#136279 = DIRECTION('',(-6.725593854929E-015,1.)); -#136280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136281 = PCURVE('',#87440,#136282); -#136282 = DEFINITIONAL_REPRESENTATION('',(#136283),#136287); -#136283 = LINE('',#136284,#136285); -#136284 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#136285 = VECTOR('',#136286,1.); -#136286 = DIRECTION('',(0.E+000,1.)); -#136287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136288 = ORIENTED_EDGE('',*,*,#136289,.T.); -#136289 = EDGE_CURVE('',#136267,#136214,#136290,.T.); -#136290 = SURFACE_CURVE('',#136291,(#136295,#136302),.PCURVE_S1.); -#136291 = LINE('',#136292,#136293); -#136292 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#138619 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138620 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#138621 = DEFINITIONAL_REPRESENTATION('',(#138622),#138626); +#138622 = LINE('',#138623,#138624); +#138623 = CARTESIAN_POINT('',(-8.65,-7.105427357601E-015)); +#138624 = VECTOR('',#138625,1.); +#138625 = DIRECTION('',(-6.725593854929E-015,1.)); +#138626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138627 = PCURVE('',#89776,#138628); +#138628 = DEFINITIONAL_REPRESENTATION('',(#138629),#138633); +#138629 = LINE('',#138630,#138631); +#138630 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#138631 = VECTOR('',#138632,1.); +#138632 = DIRECTION('',(0.E+000,1.)); +#138633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138634 = ORIENTED_EDGE('',*,*,#138635,.T.); +#138635 = EDGE_CURVE('',#138608,#138636,#138638,.T.); +#138636 = VERTEX_POINT('',#138637); +#138637 = CARTESIAN_POINT('',(8.85,11.,-0.308197125857)); +#138638 = SURFACE_CURVE('',#138639,(#138643,#138650),.PCURVE_S1.); +#138639 = LINE('',#138640,#138641); +#138640 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#138641 = VECTOR('',#138642,1.); +#138642 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138643 = PCURVE('',#138616,#138644); +#138644 = DEFINITIONAL_REPRESENTATION('',(#138645),#138649); +#138645 = LINE('',#138646,#138647); +#138646 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#138647 = VECTOR('',#138648,1.); +#138648 = DIRECTION('',(-1.,-8.881784197001E-016)); +#138649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138650 = PCURVE('',#138542,#138651); +#138651 = DEFINITIONAL_REPRESENTATION('',(#138652),#138656); +#138652 = LINE('',#138653,#138654); +#138653 = CARTESIAN_POINT('',(8.75,-5.000038352949E-002)); +#138654 = VECTOR('',#138655,1.); +#138655 = DIRECTION('',(-1.,-1.1653254136E-048)); +#138656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138657 = ORIENTED_EDGE('',*,*,#138658,.F.); +#138658 = EDGE_CURVE('',#138659,#138636,#138661,.T.); +#138659 = VERTEX_POINT('',#138660); +#138660 = CARTESIAN_POINT('',(8.85,10.74341632541,-0.308197125857)); +#138661 = SURFACE_CURVE('',#138662,(#138666,#138673),.PCURVE_S1.); +#138662 = LINE('',#138663,#138664); +#138663 = CARTESIAN_POINT('',(8.85,10.74341632541,-0.308197125857)); +#138664 = VECTOR('',#138665,1.); +#138665 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#138666 = PCURVE('',#138616,#138667); +#138667 = DEFINITIONAL_REPRESENTATION('',(#138668),#138672); +#138668 = LINE('',#138669,#138670); +#138669 = CARTESIAN_POINT('',(-8.85,-7.105427357601E-015)); +#138670 = VECTOR('',#138671,1.); +#138671 = DIRECTION('',(-6.725593854929E-015,1.)); +#138672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138673 = PCURVE('',#89832,#138674); +#138674 = DEFINITIONAL_REPRESENTATION('',(#138675),#138679); +#138675 = LINE('',#138676,#138677); +#138676 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#138677 = VECTOR('',#138678,1.); +#138678 = DIRECTION('',(0.E+000,1.)); +#138679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138680 = ORIENTED_EDGE('',*,*,#138681,.T.); +#138681 = EDGE_CURVE('',#138659,#138606,#138682,.T.); +#138682 = SURFACE_CURVE('',#138683,(#138687,#138694),.PCURVE_S1.); +#138683 = LINE('',#138684,#138685); +#138684 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#136293 = VECTOR('',#136294,1.); -#136294 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136295 = PCURVE('',#136224,#136296); -#136296 = DEFINITIONAL_REPRESENTATION('',(#136297),#136301); -#136297 = LINE('',#136298,#136299); -#136298 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136299 = VECTOR('',#136300,1.); -#136300 = DIRECTION('',(1.,8.881784197001E-016)); -#136301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136302 = PCURVE('',#136303,#136308); -#136303 = CYLINDRICAL_SURFACE('',#136304,0.308574064194); -#136304 = AXIS2_PLACEMENT_3D('',#136305,#136306,#136307); -#136305 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#138685 = VECTOR('',#138686,1.); +#138686 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138687 = PCURVE('',#138616,#138688); +#138688 = DEFINITIONAL_REPRESENTATION('',(#138689),#138693); +#138689 = LINE('',#138690,#138691); +#138690 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138691 = VECTOR('',#138692,1.); +#138692 = DIRECTION('',(1.,8.881784197001E-016)); +#138693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138694 = PCURVE('',#138695,#138700); +#138695 = CYLINDRICAL_SURFACE('',#138696,0.308574064194); +#138696 = AXIS2_PLACEMENT_3D('',#138697,#138698,#138699); +#138697 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#136306 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136307 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136308 = DEFINITIONAL_REPRESENTATION('',(#136309),#136312); -#136309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136310,#136311), +#138698 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138699 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138700 = DEFINITIONAL_REPRESENTATION('',(#138701),#138704); +#138701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138702,#138703), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#136310 = CARTESIAN_POINT('',(4.761821717947,8.85)); -#136311 = CARTESIAN_POINT('',(4.761821717947,8.65)); -#136312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136313 = ADVANCED_FACE('',(#136314),#136199,.F.); -#136314 = FACE_BOUND('',#136315,.F.); -#136315 = EDGE_LOOP('',(#136316,#136317,#136344,#136371)); -#136316 = ORIENTED_EDGE('',*,*,#136185,.T.); -#136317 = ORIENTED_EDGE('',*,*,#136318,.F.); -#136318 = EDGE_CURVE('',#136319,#136105,#136321,.T.); -#136319 = VERTEX_POINT('',#136320); -#136320 = CARTESIAN_POINT('',(8.85,10.51959417205,0.E+000)); -#136321 = SURFACE_CURVE('',#136322,(#136327,#136333),.PCURVE_S1.); -#136322 = CIRCLE('',#136323,0.208574704164); -#136323 = AXIS2_PLACEMENT_3D('',#136324,#136325,#136326); -#136324 = CARTESIAN_POINT('',(8.85,10.728168876214,2.640924866458E-017) - ); -#136325 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136326 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136327 = PCURVE('',#136199,#136328); -#136328 = DEFINITIONAL_REPRESENTATION('',(#136329),#136332); -#136329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136330,#136331), +#138702 = CARTESIAN_POINT('',(4.761821717947,8.85)); +#138703 = CARTESIAN_POINT('',(4.761821717947,8.65)); +#138704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138705 = ADVANCED_FACE('',(#138706),#138591,.F.); +#138706 = FACE_BOUND('',#138707,.F.); +#138707 = EDGE_LOOP('',(#138708,#138709,#138736,#138763)); +#138708 = ORIENTED_EDGE('',*,*,#138577,.T.); +#138709 = ORIENTED_EDGE('',*,*,#138710,.F.); +#138710 = EDGE_CURVE('',#138711,#138497,#138713,.T.); +#138711 = VERTEX_POINT('',#138712); +#138712 = CARTESIAN_POINT('',(8.85,10.51959417205,0.E+000)); +#138713 = SURFACE_CURVE('',#138714,(#138719,#138725),.PCURVE_S1.); +#138714 = CIRCLE('',#138715,0.208574704164); +#138715 = AXIS2_PLACEMENT_3D('',#138716,#138717,#138718); +#138716 = CARTESIAN_POINT('',(8.85,10.728168876214,2.640924866458E-017) + ); +#138717 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138718 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138719 = PCURVE('',#138591,#138720); +#138720 = DEFINITIONAL_REPRESENTATION('',(#138721),#138724); +#138721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138722,#138723), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#136330 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#136331 = CARTESIAN_POINT('',(4.772630242227,8.85)); -#136332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138722 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#138723 = CARTESIAN_POINT('',(4.772630242227,8.85)); +#138724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136333 = PCURVE('',#87440,#136334); -#136334 = DEFINITIONAL_REPRESENTATION('',(#136335),#136343); -#136335 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136336,#136337,#136338, - #136339,#136340,#136341,#136342),.UNSPECIFIED.,.T.,.F.) +#138725 = PCURVE('',#89832,#138726); +#138726 = DEFINITIONAL_REPRESENTATION('',(#138727),#138735); +#138727 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138728,#138729,#138730, + #138731,#138732,#138733,#138734),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#136336 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#136337 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#136338 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#136339 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#136340 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#136341 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#136342 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#136343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136344 = ORIENTED_EDGE('',*,*,#136345,.T.); -#136345 = EDGE_CURVE('',#136319,#136346,#136348,.T.); -#136346 = VERTEX_POINT('',#136347); -#136347 = CARTESIAN_POINT('',(8.65,10.51959417205,0.E+000)); -#136348 = SURFACE_CURVE('',#136349,(#136353,#136359),.PCURVE_S1.); -#136349 = LINE('',#136350,#136351); -#136350 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#138728 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#138729 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#138730 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#138731 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#138732 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#138733 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#138734 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#138735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138736 = ORIENTED_EDGE('',*,*,#138737,.T.); +#138737 = EDGE_CURVE('',#138711,#138738,#138740,.T.); +#138738 = VERTEX_POINT('',#138739); +#138739 = CARTESIAN_POINT('',(8.65,10.51959417205,0.E+000)); +#138740 = SURFACE_CURVE('',#138741,(#138745,#138751),.PCURVE_S1.); +#138741 = LINE('',#138742,#138743); +#138742 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#136351 = VECTOR('',#136352,1.); -#136352 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136353 = PCURVE('',#136199,#136354); -#136354 = DEFINITIONAL_REPRESENTATION('',(#136355),#136358); -#136355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136356,#136357), +#138743 = VECTOR('',#138744,1.); +#138744 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138745 = PCURVE('',#138591,#138746); +#138746 = DEFINITIONAL_REPRESENTATION('',(#138747),#138750); +#138747 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138748,#138749), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#136356 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#136357 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#136358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138748 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#138749 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#138750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136359 = PCURVE('',#136360,#136365); -#136360 = PLANE('',#136361); -#136361 = AXIS2_PLACEMENT_3D('',#136362,#136363,#136364); -#136362 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#138751 = PCURVE('',#138752,#138757); +#138752 = PLANE('',#138753); +#138753 = AXIS2_PLACEMENT_3D('',#138754,#138755,#138756); +#138754 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#136363 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136364 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136365 = DEFINITIONAL_REPRESENTATION('',(#136366),#136370); -#136366 = LINE('',#136367,#136368); -#136367 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#136368 = VECTOR('',#136369,1.); -#136369 = DIRECTION('',(-1.,0.E+000)); -#136370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136371 = ORIENTED_EDGE('',*,*,#136372,.T.); -#136372 = EDGE_CURVE('',#136346,#136163,#136373,.T.); -#136373 = SURFACE_CURVE('',#136374,(#136379,#136385),.PCURVE_S1.); -#136374 = CIRCLE('',#136375,0.208574704164); -#136375 = AXIS2_PLACEMENT_3D('',#136376,#136377,#136378); -#136376 = CARTESIAN_POINT('',(8.65,10.728168876214,2.640924866458E-017) - ); -#136377 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136378 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136379 = PCURVE('',#136199,#136380); -#136380 = DEFINITIONAL_REPRESENTATION('',(#136381),#136384); -#136381 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136382,#136383), +#138755 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#138756 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138757 = DEFINITIONAL_REPRESENTATION('',(#138758),#138762); +#138758 = LINE('',#138759,#138760); +#138759 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#138760 = VECTOR('',#138761,1.); +#138761 = DIRECTION('',(-1.,0.E+000)); +#138762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138763 = ORIENTED_EDGE('',*,*,#138764,.T.); +#138764 = EDGE_CURVE('',#138738,#138555,#138765,.T.); +#138765 = SURFACE_CURVE('',#138766,(#138771,#138777),.PCURVE_S1.); +#138766 = CIRCLE('',#138767,0.208574704164); +#138767 = AXIS2_PLACEMENT_3D('',#138768,#138769,#138770); +#138768 = CARTESIAN_POINT('',(8.65,10.728168876214,2.640924866458E-017) + ); +#138769 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138770 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138771 = PCURVE('',#138591,#138772); +#138772 = DEFINITIONAL_REPRESENTATION('',(#138773),#138776); +#138773 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138774,#138775), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#136382 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#136383 = CARTESIAN_POINT('',(4.772630242227,8.65)); -#136384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136385 = PCURVE('',#87384,#136386); -#136386 = DEFINITIONAL_REPRESENTATION('',(#136387),#136391); -#136387 = CIRCLE('',#136388,0.208574704164); -#136388 = AXIS2_PLACEMENT_2D('',#136389,#136390); -#136389 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#136390 = DIRECTION('',(0.E+000,1.)); -#136391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136392 = ADVANCED_FACE('',(#136393),#136303,.T.); -#136393 = FACE_BOUND('',#136394,.T.); -#136394 = EDGE_LOOP('',(#136395,#136396,#136423,#136450)); -#136395 = ORIENTED_EDGE('',*,*,#136289,.F.); -#136396 = ORIENTED_EDGE('',*,*,#136397,.F.); -#136397 = EDGE_CURVE('',#136398,#136267,#136400,.T.); -#136398 = VERTEX_POINT('',#136399); -#136399 = CARTESIAN_POINT('',(8.85,10.419594812019,0.E+000)); -#136400 = SURFACE_CURVE('',#136401,(#136406,#136412),.PCURVE_S1.); -#136401 = CIRCLE('',#136402,0.308574064194); -#136402 = AXIS2_PLACEMENT_3D('',#136403,#136404,#136405); -#136403 = CARTESIAN_POINT('',(8.85,10.728168876214,2.640924866458E-017) - ); -#136404 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136405 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136406 = PCURVE('',#136303,#136407); -#136407 = DEFINITIONAL_REPRESENTATION('',(#136408),#136411); -#136408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136409,#136410), +#138774 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#138775 = CARTESIAN_POINT('',(4.772630242227,8.65)); +#138776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138777 = PCURVE('',#89776,#138778); +#138778 = DEFINITIONAL_REPRESENTATION('',(#138779),#138783); +#138779 = CIRCLE('',#138780,0.208574704164); +#138780 = AXIS2_PLACEMENT_2D('',#138781,#138782); +#138781 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#138782 = DIRECTION('',(0.E+000,1.)); +#138783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138784 = ADVANCED_FACE('',(#138785),#138695,.T.); +#138785 = FACE_BOUND('',#138786,.T.); +#138786 = EDGE_LOOP('',(#138787,#138788,#138815,#138842)); +#138787 = ORIENTED_EDGE('',*,*,#138681,.F.); +#138788 = ORIENTED_EDGE('',*,*,#138789,.F.); +#138789 = EDGE_CURVE('',#138790,#138659,#138792,.T.); +#138790 = VERTEX_POINT('',#138791); +#138791 = CARTESIAN_POINT('',(8.85,10.419594812019,0.E+000)); +#138792 = SURFACE_CURVE('',#138793,(#138798,#138804),.PCURVE_S1.); +#138793 = CIRCLE('',#138794,0.308574064194); +#138794 = AXIS2_PLACEMENT_3D('',#138795,#138796,#138797); +#138795 = CARTESIAN_POINT('',(8.85,10.728168876214,2.640924866458E-017) + ); +#138796 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138797 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138798 = PCURVE('',#138695,#138799); +#138799 = DEFINITIONAL_REPRESENTATION('',(#138800),#138803); +#138800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138801,#138802), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#136409 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#136410 = CARTESIAN_POINT('',(4.761821717947,8.85)); -#136411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138801 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#138802 = CARTESIAN_POINT('',(4.761821717947,8.85)); +#138803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136412 = PCURVE('',#87440,#136413); -#136413 = DEFINITIONAL_REPRESENTATION('',(#136414),#136422); -#136414 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136415,#136416,#136417, - #136418,#136419,#136420,#136421),.UNSPECIFIED.,.T.,.F.) +#138804 = PCURVE('',#89832,#138805); +#138805 = DEFINITIONAL_REPRESENTATION('',(#138806),#138814); +#138806 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138807,#138808,#138809, + #138810,#138811,#138812,#138813),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#136415 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#136416 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#136417 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#136418 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#136419 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#136420 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#136421 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#136422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136423 = ORIENTED_EDGE('',*,*,#136424,.F.); -#136424 = EDGE_CURVE('',#136425,#136398,#136427,.T.); -#136425 = VERTEX_POINT('',#136426); -#136426 = CARTESIAN_POINT('',(8.65,10.419594812019,0.E+000)); -#136427 = SURFACE_CURVE('',#136428,(#136432,#136438),.PCURVE_S1.); -#136428 = LINE('',#136429,#136430); -#136429 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#138807 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#138808 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#138809 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#138810 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#138811 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#138812 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#138813 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#138814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138815 = ORIENTED_EDGE('',*,*,#138816,.F.); +#138816 = EDGE_CURVE('',#138817,#138790,#138819,.T.); +#138817 = VERTEX_POINT('',#138818); +#138818 = CARTESIAN_POINT('',(8.65,10.419594812019,0.E+000)); +#138819 = SURFACE_CURVE('',#138820,(#138824,#138830),.PCURVE_S1.); +#138820 = LINE('',#138821,#138822); +#138821 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#136430 = VECTOR('',#136431,1.); -#136431 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136432 = PCURVE('',#136303,#136433); -#136433 = DEFINITIONAL_REPRESENTATION('',(#136434),#136437); -#136434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136435,#136436), +#138822 = VECTOR('',#138823,1.); +#138823 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138824 = PCURVE('',#138695,#138825); +#138825 = DEFINITIONAL_REPRESENTATION('',(#138826),#138829); +#138826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138827,#138828), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#136435 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#136436 = CARTESIAN_POINT('',(3.14159265359,8.85)); -#136437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#138827 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#138828 = CARTESIAN_POINT('',(3.14159265359,8.85)); +#138829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136438 = PCURVE('',#136439,#136444); -#136439 = PLANE('',#136440); -#136440 = AXIS2_PLACEMENT_3D('',#136441,#136442,#136443); -#136441 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#138830 = PCURVE('',#138831,#138836); +#138831 = PLANE('',#138832); +#138832 = AXIS2_PLACEMENT_3D('',#138833,#138834,#138835); +#138833 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#136442 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136443 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136444 = DEFINITIONAL_REPRESENTATION('',(#136445),#136449); -#136445 = LINE('',#136446,#136447); -#136446 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#136447 = VECTOR('',#136448,1.); -#136448 = DIRECTION('',(-1.,0.E+000)); -#136449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136450 = ORIENTED_EDGE('',*,*,#136451,.T.); -#136451 = EDGE_CURVE('',#136425,#136214,#136452,.T.); -#136452 = SURFACE_CURVE('',#136453,(#136458,#136464),.PCURVE_S1.); -#136453 = CIRCLE('',#136454,0.308574064194); -#136454 = AXIS2_PLACEMENT_3D('',#136455,#136456,#136457); -#136455 = CARTESIAN_POINT('',(8.65,10.728168876214,2.640924866458E-017) - ); -#136456 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136457 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#136458 = PCURVE('',#136303,#136459); -#136459 = DEFINITIONAL_REPRESENTATION('',(#136460),#136463); -#136460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136461,#136462), +#138834 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138835 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138836 = DEFINITIONAL_REPRESENTATION('',(#138837),#138841); +#138837 = LINE('',#138838,#138839); +#138838 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#138839 = VECTOR('',#138840,1.); +#138840 = DIRECTION('',(-1.,0.E+000)); +#138841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138842 = ORIENTED_EDGE('',*,*,#138843,.T.); +#138843 = EDGE_CURVE('',#138817,#138606,#138844,.T.); +#138844 = SURFACE_CURVE('',#138845,(#138850,#138856),.PCURVE_S1.); +#138845 = CIRCLE('',#138846,0.308574064194); +#138846 = AXIS2_PLACEMENT_3D('',#138847,#138848,#138849); +#138847 = CARTESIAN_POINT('',(8.65,10.728168876214,2.640924866458E-017) + ); +#138848 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138849 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#138850 = PCURVE('',#138695,#138851); +#138851 = DEFINITIONAL_REPRESENTATION('',(#138852),#138855); +#138852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138853,#138854), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#136461 = CARTESIAN_POINT('',(3.14159265359,8.65)); -#136462 = CARTESIAN_POINT('',(4.761821717947,8.65)); -#136463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136464 = PCURVE('',#87384,#136465); -#136465 = DEFINITIONAL_REPRESENTATION('',(#136466),#136470); -#136466 = CIRCLE('',#136467,0.308574064194); -#136467 = AXIS2_PLACEMENT_2D('',#136468,#136469); -#136468 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#136469 = DIRECTION('',(0.E+000,1.)); -#136470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136471 = ADVANCED_FACE('',(#136472),#136439,.F.); -#136472 = FACE_BOUND('',#136473,.T.); -#136473 = EDGE_LOOP('',(#136474,#136503,#136524,#136525)); -#136474 = ORIENTED_EDGE('',*,*,#136475,.F.); -#136475 = EDGE_CURVE('',#136476,#136478,#136480,.T.); -#136476 = VERTEX_POINT('',#136477); -#136477 = CARTESIAN_POINT('',(8.65,10.419594812019,0.530776333563)); -#136478 = VERTEX_POINT('',#136479); -#136479 = CARTESIAN_POINT('',(8.85,10.419594812019,0.530776333563)); -#136480 = SURFACE_CURVE('',#136481,(#136485,#136492),.PCURVE_S1.); -#136481 = LINE('',#136482,#136483); -#136482 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#138853 = CARTESIAN_POINT('',(3.14159265359,8.65)); +#138854 = CARTESIAN_POINT('',(4.761821717947,8.65)); +#138855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138856 = PCURVE('',#89776,#138857); +#138857 = DEFINITIONAL_REPRESENTATION('',(#138858),#138862); +#138858 = CIRCLE('',#138859,0.308574064194); +#138859 = AXIS2_PLACEMENT_2D('',#138860,#138861); +#138860 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#138861 = DIRECTION('',(0.E+000,1.)); +#138862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138863 = ADVANCED_FACE('',(#138864),#138831,.F.); +#138864 = FACE_BOUND('',#138865,.T.); +#138865 = EDGE_LOOP('',(#138866,#138895,#138916,#138917)); +#138866 = ORIENTED_EDGE('',*,*,#138867,.F.); +#138867 = EDGE_CURVE('',#138868,#138870,#138872,.T.); +#138868 = VERTEX_POINT('',#138869); +#138869 = CARTESIAN_POINT('',(8.65,10.419594812019,0.530776333563)); +#138870 = VERTEX_POINT('',#138871); +#138871 = CARTESIAN_POINT('',(8.85,10.419594812019,0.530776333563)); +#138872 = SURFACE_CURVE('',#138873,(#138877,#138884),.PCURVE_S1.); +#138873 = LINE('',#138874,#138875); +#138874 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#136483 = VECTOR('',#136484,1.); -#136484 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136485 = PCURVE('',#136439,#136486); -#136486 = DEFINITIONAL_REPRESENTATION('',(#136487),#136491); -#136487 = LINE('',#136488,#136489); -#136488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136489 = VECTOR('',#136490,1.); -#136490 = DIRECTION('',(-1.,0.E+000)); -#136491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136492 = PCURVE('',#136493,#136498); -#136493 = CYLINDRICAL_SURFACE('',#136494,0.119270391569); -#136494 = AXIS2_PLACEMENT_3D('',#136495,#136496,#136497); -#136495 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#138875 = VECTOR('',#138876,1.); +#138876 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#138877 = PCURVE('',#138831,#138878); +#138878 = DEFINITIONAL_REPRESENTATION('',(#138879),#138883); +#138879 = LINE('',#138880,#138881); +#138880 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138881 = VECTOR('',#138882,1.); +#138882 = DIRECTION('',(-1.,0.E+000)); +#138883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138884 = PCURVE('',#138885,#138890); +#138885 = CYLINDRICAL_SURFACE('',#138886,0.119270391569); +#138886 = AXIS2_PLACEMENT_3D('',#138887,#138888,#138889); +#138887 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#136496 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136497 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136498 = DEFINITIONAL_REPRESENTATION('',(#136499),#136502); -#136499 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136500,#136501), +#138888 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138889 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#138890 = DEFINITIONAL_REPRESENTATION('',(#138891),#138894); +#138891 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138892,#138893), .UNSPECIFIED.,.F.,.F.,(2,2),(8.65,8.85),.PIECEWISE_BEZIER_KNOTS.); -#136500 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#136501 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#136502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136503 = ORIENTED_EDGE('',*,*,#136504,.T.); -#136504 = EDGE_CURVE('',#136476,#136425,#136505,.T.); -#136505 = SURFACE_CURVE('',#136506,(#136510,#136517),.PCURVE_S1.); -#136506 = LINE('',#136507,#136508); -#136507 = CARTESIAN_POINT('',(8.65,10.419594812019,0.530776333563)); -#136508 = VECTOR('',#136509,1.); -#136509 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136510 = PCURVE('',#136439,#136511); -#136511 = DEFINITIONAL_REPRESENTATION('',(#136512),#136516); -#136512 = LINE('',#136513,#136514); -#136513 = CARTESIAN_POINT('',(-8.65,0.E+000)); -#136514 = VECTOR('',#136515,1.); -#136515 = DIRECTION('',(0.E+000,-1.)); -#136516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136517 = PCURVE('',#87384,#136518); -#136518 = DEFINITIONAL_REPRESENTATION('',(#136519),#136523); -#136519 = LINE('',#136520,#136521); -#136520 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#136521 = VECTOR('',#136522,1.); -#136522 = DIRECTION('',(1.,0.E+000)); -#136523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136524 = ORIENTED_EDGE('',*,*,#136424,.T.); -#136525 = ORIENTED_EDGE('',*,*,#136526,.F.); -#136526 = EDGE_CURVE('',#136478,#136398,#136527,.T.); -#136527 = SURFACE_CURVE('',#136528,(#136532,#136539),.PCURVE_S1.); -#136528 = LINE('',#136529,#136530); -#136529 = CARTESIAN_POINT('',(8.85,10.419594812019,0.530776333563)); -#136530 = VECTOR('',#136531,1.); -#136531 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136532 = PCURVE('',#136439,#136533); -#136533 = DEFINITIONAL_REPRESENTATION('',(#136534),#136538); -#136534 = LINE('',#136535,#136536); -#136535 = CARTESIAN_POINT('',(-8.85,0.E+000)); -#136536 = VECTOR('',#136537,1.); -#136537 = DIRECTION('',(0.E+000,-1.)); -#136538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136539 = PCURVE('',#87440,#136540); -#136540 = DEFINITIONAL_REPRESENTATION('',(#136541),#136545); -#136541 = LINE('',#136542,#136543); -#136542 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#136543 = VECTOR('',#136544,1.); -#136544 = DIRECTION('',(-1.,0.E+000)); -#136545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136546 = ADVANCED_FACE('',(#136547),#136360,.F.); -#136547 = FACE_BOUND('',#136548,.T.); -#136548 = EDGE_LOOP('',(#136549,#136578,#136599,#136600)); -#136549 = ORIENTED_EDGE('',*,*,#136550,.F.); -#136550 = EDGE_CURVE('',#136551,#136553,#136555,.T.); -#136551 = VERTEX_POINT('',#136552); -#136552 = CARTESIAN_POINT('',(8.85,10.51959417205,0.530776333563)); -#136553 = VERTEX_POINT('',#136554); -#136554 = CARTESIAN_POINT('',(8.65,10.51959417205,0.530776333563)); -#136555 = SURFACE_CURVE('',#136556,(#136560,#136567),.PCURVE_S1.); -#136556 = LINE('',#136557,#136558); -#136557 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#138892 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#138893 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#138894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138895 = ORIENTED_EDGE('',*,*,#138896,.T.); +#138896 = EDGE_CURVE('',#138868,#138817,#138897,.T.); +#138897 = SURFACE_CURVE('',#138898,(#138902,#138909),.PCURVE_S1.); +#138898 = LINE('',#138899,#138900); +#138899 = CARTESIAN_POINT('',(8.65,10.419594812019,0.530776333563)); +#138900 = VECTOR('',#138901,1.); +#138901 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138902 = PCURVE('',#138831,#138903); +#138903 = DEFINITIONAL_REPRESENTATION('',(#138904),#138908); +#138904 = LINE('',#138905,#138906); +#138905 = CARTESIAN_POINT('',(-8.65,0.E+000)); +#138906 = VECTOR('',#138907,1.); +#138907 = DIRECTION('',(0.E+000,-1.)); +#138908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138909 = PCURVE('',#89776,#138910); +#138910 = DEFINITIONAL_REPRESENTATION('',(#138911),#138915); +#138911 = LINE('',#138912,#138913); +#138912 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#138913 = VECTOR('',#138914,1.); +#138914 = DIRECTION('',(1.,0.E+000)); +#138915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138916 = ORIENTED_EDGE('',*,*,#138816,.T.); +#138917 = ORIENTED_EDGE('',*,*,#138918,.F.); +#138918 = EDGE_CURVE('',#138870,#138790,#138919,.T.); +#138919 = SURFACE_CURVE('',#138920,(#138924,#138931),.PCURVE_S1.); +#138920 = LINE('',#138921,#138922); +#138921 = CARTESIAN_POINT('',(8.85,10.419594812019,0.530776333563)); +#138922 = VECTOR('',#138923,1.); +#138923 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138924 = PCURVE('',#138831,#138925); +#138925 = DEFINITIONAL_REPRESENTATION('',(#138926),#138930); +#138926 = LINE('',#138927,#138928); +#138927 = CARTESIAN_POINT('',(-8.85,0.E+000)); +#138928 = VECTOR('',#138929,1.); +#138929 = DIRECTION('',(0.E+000,-1.)); +#138930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138931 = PCURVE('',#89832,#138932); +#138932 = DEFINITIONAL_REPRESENTATION('',(#138933),#138937); +#138933 = LINE('',#138934,#138935); +#138934 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#138935 = VECTOR('',#138936,1.); +#138936 = DIRECTION('',(-1.,0.E+000)); +#138937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138938 = ADVANCED_FACE('',(#138939),#138752,.F.); +#138939 = FACE_BOUND('',#138940,.T.); +#138940 = EDGE_LOOP('',(#138941,#138970,#138991,#138992)); +#138941 = ORIENTED_EDGE('',*,*,#138942,.F.); +#138942 = EDGE_CURVE('',#138943,#138945,#138947,.T.); +#138943 = VERTEX_POINT('',#138944); +#138944 = CARTESIAN_POINT('',(8.85,10.51959417205,0.530776333563)); +#138945 = VERTEX_POINT('',#138946); +#138946 = CARTESIAN_POINT('',(8.65,10.51959417205,0.530776333563)); +#138947 = SURFACE_CURVE('',#138948,(#138952,#138959),.PCURVE_S1.); +#138948 = LINE('',#138949,#138950); +#138949 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#136558 = VECTOR('',#136559,1.); -#136559 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136560 = PCURVE('',#136360,#136561); -#136561 = DEFINITIONAL_REPRESENTATION('',(#136562),#136566); -#136562 = LINE('',#136563,#136564); -#136563 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136564 = VECTOR('',#136565,1.); -#136565 = DIRECTION('',(-1.,0.E+000)); -#136566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136567 = PCURVE('',#136568,#136573); -#136568 = CYLINDRICAL_SURFACE('',#136569,0.2192697516); -#136569 = AXIS2_PLACEMENT_3D('',#136570,#136571,#136572); -#136570 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#138950 = VECTOR('',#138951,1.); +#138951 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138952 = PCURVE('',#138752,#138953); +#138953 = DEFINITIONAL_REPRESENTATION('',(#138954),#138958); +#138954 = LINE('',#138955,#138956); +#138955 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#138956 = VECTOR('',#138957,1.); +#138957 = DIRECTION('',(-1.,0.E+000)); +#138958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138959 = PCURVE('',#138960,#138965); +#138960 = CYLINDRICAL_SURFACE('',#138961,0.2192697516); +#138961 = AXIS2_PLACEMENT_3D('',#138962,#138963,#138964); +#138962 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#136571 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136572 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136573 = DEFINITIONAL_REPRESENTATION('',(#136574),#136577); -#136574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136575,#136576), +#138963 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#138964 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#138965 = DEFINITIONAL_REPRESENTATION('',(#138966),#138969); +#138966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138967,#138968), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.85,-8.65),.PIECEWISE_BEZIER_KNOTS.); -#136575 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#136576 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#136577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136578 = ORIENTED_EDGE('',*,*,#136579,.T.); -#136579 = EDGE_CURVE('',#136551,#136319,#136580,.T.); -#136580 = SURFACE_CURVE('',#136581,(#136585,#136592),.PCURVE_S1.); -#136581 = LINE('',#136582,#136583); -#136582 = CARTESIAN_POINT('',(8.85,10.51959417205,0.530776333563)); -#136583 = VECTOR('',#136584,1.); -#136584 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136585 = PCURVE('',#136360,#136586); -#136586 = DEFINITIONAL_REPRESENTATION('',(#136587),#136591); -#136587 = LINE('',#136588,#136589); -#136588 = CARTESIAN_POINT('',(8.85,0.E+000)); -#136589 = VECTOR('',#136590,1.); -#136590 = DIRECTION('',(0.E+000,-1.)); -#136591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136592 = PCURVE('',#87440,#136593); -#136593 = DEFINITIONAL_REPRESENTATION('',(#136594),#136598); -#136594 = LINE('',#136595,#136596); -#136595 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#136596 = VECTOR('',#136597,1.); -#136597 = DIRECTION('',(-1.,0.E+000)); -#136598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136599 = ORIENTED_EDGE('',*,*,#136345,.T.); -#136600 = ORIENTED_EDGE('',*,*,#136601,.F.); -#136601 = EDGE_CURVE('',#136553,#136346,#136602,.T.); -#136602 = SURFACE_CURVE('',#136603,(#136607,#136614),.PCURVE_S1.); -#136603 = LINE('',#136604,#136605); -#136604 = CARTESIAN_POINT('',(8.65,10.51959417205,0.530776333563)); -#136605 = VECTOR('',#136606,1.); -#136606 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136607 = PCURVE('',#136360,#136608); -#136608 = DEFINITIONAL_REPRESENTATION('',(#136609),#136613); -#136609 = LINE('',#136610,#136611); -#136610 = CARTESIAN_POINT('',(8.65,0.E+000)); -#136611 = VECTOR('',#136612,1.); -#136612 = DIRECTION('',(0.E+000,-1.)); -#136613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136614 = PCURVE('',#87384,#136615); -#136615 = DEFINITIONAL_REPRESENTATION('',(#136616),#136620); -#136616 = LINE('',#136617,#136618); -#136617 = CARTESIAN_POINT('',(0.119223666437,-8.253820388626E-003)); -#136618 = VECTOR('',#136619,1.); -#136619 = DIRECTION('',(1.,0.E+000)); -#136620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136621 = ADVANCED_FACE('',(#136622),#136493,.F.); -#136622 = FACE_BOUND('',#136623,.F.); -#136623 = EDGE_LOOP('',(#136624,#136651,#136673,#136694)); -#136624 = ORIENTED_EDGE('',*,*,#136625,.F.); -#136625 = EDGE_CURVE('',#136626,#136476,#136628,.T.); -#136626 = VERTEX_POINT('',#136627); -#136627 = CARTESIAN_POINT('',(8.65,10.303662633502,0.65)); -#136628 = SURFACE_CURVE('',#136629,(#136634,#136640),.PCURVE_S1.); -#136629 = CIRCLE('',#136630,0.119270391569); -#136630 = AXIS2_PLACEMENT_3D('',#136631,#136632,#136633); -#136631 = CARTESIAN_POINT('',(8.65,10.30032442045,0.530776333563)); -#136632 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136633 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136634 = PCURVE('',#136493,#136635); -#136635 = DEFINITIONAL_REPRESENTATION('',(#136636),#136639); -#136636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136637,#136638), +#138967 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#138968 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#138969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138970 = ORIENTED_EDGE('',*,*,#138971,.T.); +#138971 = EDGE_CURVE('',#138943,#138711,#138972,.T.); +#138972 = SURFACE_CURVE('',#138973,(#138977,#138984),.PCURVE_S1.); +#138973 = LINE('',#138974,#138975); +#138974 = CARTESIAN_POINT('',(8.85,10.51959417205,0.530776333563)); +#138975 = VECTOR('',#138976,1.); +#138976 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138977 = PCURVE('',#138752,#138978); +#138978 = DEFINITIONAL_REPRESENTATION('',(#138979),#138983); +#138979 = LINE('',#138980,#138981); +#138980 = CARTESIAN_POINT('',(8.85,0.E+000)); +#138981 = VECTOR('',#138982,1.); +#138982 = DIRECTION('',(0.E+000,-1.)); +#138983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138984 = PCURVE('',#89832,#138985); +#138985 = DEFINITIONAL_REPRESENTATION('',(#138986),#138990); +#138986 = LINE('',#138987,#138988); +#138987 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#138988 = VECTOR('',#138989,1.); +#138989 = DIRECTION('',(-1.,0.E+000)); +#138990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#138991 = ORIENTED_EDGE('',*,*,#138737,.T.); +#138992 = ORIENTED_EDGE('',*,*,#138993,.F.); +#138993 = EDGE_CURVE('',#138945,#138738,#138994,.T.); +#138994 = SURFACE_CURVE('',#138995,(#138999,#139006),.PCURVE_S1.); +#138995 = LINE('',#138996,#138997); +#138996 = CARTESIAN_POINT('',(8.65,10.51959417205,0.530776333563)); +#138997 = VECTOR('',#138998,1.); +#138998 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#138999 = PCURVE('',#138752,#139000); +#139000 = DEFINITIONAL_REPRESENTATION('',(#139001),#139005); +#139001 = LINE('',#139002,#139003); +#139002 = CARTESIAN_POINT('',(8.65,0.E+000)); +#139003 = VECTOR('',#139004,1.); +#139004 = DIRECTION('',(0.E+000,-1.)); +#139005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139006 = PCURVE('',#89776,#139007); +#139007 = DEFINITIONAL_REPRESENTATION('',(#139008),#139012); +#139008 = LINE('',#139009,#139010); +#139009 = CARTESIAN_POINT('',(0.119223666437,-8.253820388626E-003)); +#139010 = VECTOR('',#139011,1.); +#139011 = DIRECTION('',(1.,0.E+000)); +#139012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139013 = ADVANCED_FACE('',(#139014),#138885,.F.); +#139014 = FACE_BOUND('',#139015,.F.); +#139015 = EDGE_LOOP('',(#139016,#139043,#139065,#139086)); +#139016 = ORIENTED_EDGE('',*,*,#139017,.F.); +#139017 = EDGE_CURVE('',#139018,#138868,#139020,.T.); +#139018 = VERTEX_POINT('',#139019); +#139019 = CARTESIAN_POINT('',(8.65,10.303662633502,0.65)); +#139020 = SURFACE_CURVE('',#139021,(#139026,#139032),.PCURVE_S1.); +#139021 = CIRCLE('',#139022,0.119270391569); +#139022 = AXIS2_PLACEMENT_3D('',#139023,#139024,#139025); +#139023 = CARTESIAN_POINT('',(8.65,10.30032442045,0.530776333563)); +#139024 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139025 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139026 = PCURVE('',#138885,#139027); +#139027 = DEFINITIONAL_REPRESENTATION('',(#139028),#139031); +#139028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139029,#139030), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#136637 = CARTESIAN_POINT('',(1.598788597134,-8.65)); -#136638 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#136639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139029 = CARTESIAN_POINT('',(1.598788597134,-8.65)); +#139030 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#139031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136640 = PCURVE('',#87384,#136641); -#136641 = DEFINITIONAL_REPRESENTATION('',(#136642),#136650); -#136642 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136643,#136644,#136645, - #136646,#136647,#136648,#136649),.UNSPECIFIED.,.T.,.F.) +#139032 = PCURVE('',#89776,#139033); +#139033 = DEFINITIONAL_REPRESENTATION('',(#139034),#139042); +#139034 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139035,#139036,#139037, + #139038,#139039,#139040,#139041),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#136643 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#136644 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#136645 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#136646 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#136647 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#136648 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#136649 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#136650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136651 = ORIENTED_EDGE('',*,*,#136652,.F.); -#136652 = EDGE_CURVE('',#136653,#136626,#136655,.T.); -#136653 = VERTEX_POINT('',#136654); -#136654 = CARTESIAN_POINT('',(8.85,10.303662633502,0.65)); -#136655 = SURFACE_CURVE('',#136656,(#136660,#136666),.PCURVE_S1.); -#136656 = LINE('',#136657,#136658); -#136657 = CARTESIAN_POINT('',(8.65,10.303662633502,0.65)); -#136658 = VECTOR('',#136659,1.); -#136659 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136660 = PCURVE('',#136493,#136661); -#136661 = DEFINITIONAL_REPRESENTATION('',(#136662),#136665); -#136662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136663,#136664), +#139035 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#139036 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#139037 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#139038 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#139039 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#139040 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#139041 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#139042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139043 = ORIENTED_EDGE('',*,*,#139044,.F.); +#139044 = EDGE_CURVE('',#139045,#139018,#139047,.T.); +#139045 = VERTEX_POINT('',#139046); +#139046 = CARTESIAN_POINT('',(8.85,10.303662633502,0.65)); +#139047 = SURFACE_CURVE('',#139048,(#139052,#139058),.PCURVE_S1.); +#139048 = LINE('',#139049,#139050); +#139049 = CARTESIAN_POINT('',(8.65,10.303662633502,0.65)); +#139050 = VECTOR('',#139051,1.); +#139051 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139052 = PCURVE('',#138885,#139053); +#139053 = DEFINITIONAL_REPRESENTATION('',(#139054),#139057); +#139054 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139055,#139056), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#136663 = CARTESIAN_POINT('',(1.598788597134,-8.85)); -#136664 = CARTESIAN_POINT('',(1.598788597134,-8.65)); -#136665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136666 = PCURVE('',#87412,#136667); -#136667 = DEFINITIONAL_REPRESENTATION('',(#136668),#136672); -#136668 = LINE('',#136669,#136670); -#136669 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#136670 = VECTOR('',#136671,1.); -#136671 = DIRECTION('',(-8.881784197001E-016,-1.)); -#136672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136673 = ORIENTED_EDGE('',*,*,#136674,.T.); -#136674 = EDGE_CURVE('',#136653,#136478,#136675,.T.); -#136675 = SURFACE_CURVE('',#136676,(#136681,#136687),.PCURVE_S1.); -#136676 = CIRCLE('',#136677,0.119270391569); -#136677 = AXIS2_PLACEMENT_3D('',#136678,#136679,#136680); -#136678 = CARTESIAN_POINT('',(8.85,10.30032442045,0.530776333563)); -#136679 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136680 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136681 = PCURVE('',#136493,#136682); -#136682 = DEFINITIONAL_REPRESENTATION('',(#136683),#136686); -#136683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136684,#136685), +#139055 = CARTESIAN_POINT('',(1.598788597134,-8.85)); +#139056 = CARTESIAN_POINT('',(1.598788597134,-8.65)); +#139057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139058 = PCURVE('',#89804,#139059); +#139059 = DEFINITIONAL_REPRESENTATION('',(#139060),#139064); +#139060 = LINE('',#139061,#139062); +#139061 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#139062 = VECTOR('',#139063,1.); +#139063 = DIRECTION('',(-8.881784197001E-016,-1.)); +#139064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139065 = ORIENTED_EDGE('',*,*,#139066,.T.); +#139066 = EDGE_CURVE('',#139045,#138870,#139067,.T.); +#139067 = SURFACE_CURVE('',#139068,(#139073,#139079),.PCURVE_S1.); +#139068 = CIRCLE('',#139069,0.119270391569); +#139069 = AXIS2_PLACEMENT_3D('',#139070,#139071,#139072); +#139070 = CARTESIAN_POINT('',(8.85,10.30032442045,0.530776333563)); +#139071 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139072 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139073 = PCURVE('',#138885,#139074); +#139074 = DEFINITIONAL_REPRESENTATION('',(#139075),#139078); +#139075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139076,#139077), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#136684 = CARTESIAN_POINT('',(1.598788597134,-8.85)); -#136685 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#136686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136687 = PCURVE('',#87440,#136688); -#136688 = DEFINITIONAL_REPRESENTATION('',(#136689),#136693); -#136689 = CIRCLE('',#136690,0.119270391569); -#136690 = AXIS2_PLACEMENT_2D('',#136691,#136692); -#136691 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#136692 = DIRECTION('',(0.E+000,-1.)); -#136693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136694 = ORIENTED_EDGE('',*,*,#136475,.F.); -#136695 = ADVANCED_FACE('',(#136696),#136568,.T.); -#136696 = FACE_BOUND('',#136697,.T.); -#136697 = EDGE_LOOP('',(#136698,#136721,#136722,#136749)); -#136698 = ORIENTED_EDGE('',*,*,#136699,.T.); -#136699 = EDGE_CURVE('',#136700,#136551,#136702,.T.); -#136700 = VERTEX_POINT('',#136701); -#136701 = CARTESIAN_POINT('',(8.85,10.304819755875,0.75)); -#136702 = SURFACE_CURVE('',#136703,(#136708,#136714),.PCURVE_S1.); -#136703 = CIRCLE('',#136704,0.2192697516); -#136704 = AXIS2_PLACEMENT_3D('',#136705,#136706,#136707); -#136705 = CARTESIAN_POINT('',(8.85,10.30032442045,0.530776333563)); -#136706 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136707 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136708 = PCURVE('',#136568,#136709); -#136709 = DEFINITIONAL_REPRESENTATION('',(#136710),#136713); -#136710 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136711,#136712), +#139076 = CARTESIAN_POINT('',(1.598788597134,-8.85)); +#139077 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#139078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139079 = PCURVE('',#89832,#139080); +#139080 = DEFINITIONAL_REPRESENTATION('',(#139081),#139085); +#139081 = CIRCLE('',#139082,0.119270391569); +#139082 = AXIS2_PLACEMENT_2D('',#139083,#139084); +#139083 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#139084 = DIRECTION('',(0.E+000,-1.)); +#139085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139086 = ORIENTED_EDGE('',*,*,#138867,.F.); +#139087 = ADVANCED_FACE('',(#139088),#138960,.T.); +#139088 = FACE_BOUND('',#139089,.T.); +#139089 = EDGE_LOOP('',(#139090,#139113,#139114,#139141)); +#139090 = ORIENTED_EDGE('',*,*,#139091,.T.); +#139091 = EDGE_CURVE('',#139092,#138943,#139094,.T.); +#139092 = VERTEX_POINT('',#139093); +#139093 = CARTESIAN_POINT('',(8.85,10.304819755875,0.75)); +#139094 = SURFACE_CURVE('',#139095,(#139100,#139106),.PCURVE_S1.); +#139095 = CIRCLE('',#139096,0.2192697516); +#139096 = AXIS2_PLACEMENT_3D('',#139097,#139098,#139099); +#139097 = CARTESIAN_POINT('',(8.85,10.30032442045,0.530776333563)); +#139098 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139099 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139100 = PCURVE('',#138960,#139101); +#139101 = DEFINITIONAL_REPRESENTATION('',(#139102),#139105); +#139102 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139103,#139104), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#136711 = CARTESIAN_POINT('',(1.591299156552,-8.85)); -#136712 = CARTESIAN_POINT('',(3.14159265359,-8.85)); -#136713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136714 = PCURVE('',#87440,#136715); -#136715 = DEFINITIONAL_REPRESENTATION('',(#136716),#136720); -#136716 = CIRCLE('',#136717,0.2192697516); -#136717 = AXIS2_PLACEMENT_2D('',#136718,#136719); -#136718 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#136719 = DIRECTION('',(0.E+000,-1.)); -#136720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136721 = ORIENTED_EDGE('',*,*,#136550,.T.); -#136722 = ORIENTED_EDGE('',*,*,#136723,.F.); -#136723 = EDGE_CURVE('',#136724,#136553,#136726,.T.); -#136724 = VERTEX_POINT('',#136725); -#136725 = CARTESIAN_POINT('',(8.65,10.304819755875,0.75)); -#136726 = SURFACE_CURVE('',#136727,(#136732,#136738),.PCURVE_S1.); -#136727 = CIRCLE('',#136728,0.2192697516); -#136728 = AXIS2_PLACEMENT_3D('',#136729,#136730,#136731); -#136729 = CARTESIAN_POINT('',(8.65,10.30032442045,0.530776333563)); -#136730 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#136731 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#136732 = PCURVE('',#136568,#136733); -#136733 = DEFINITIONAL_REPRESENTATION('',(#136734),#136737); -#136734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136735,#136736), +#139103 = CARTESIAN_POINT('',(1.591299156552,-8.85)); +#139104 = CARTESIAN_POINT('',(3.14159265359,-8.85)); +#139105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139106 = PCURVE('',#89832,#139107); +#139107 = DEFINITIONAL_REPRESENTATION('',(#139108),#139112); +#139108 = CIRCLE('',#139109,0.2192697516); +#139109 = AXIS2_PLACEMENT_2D('',#139110,#139111); +#139110 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#139111 = DIRECTION('',(0.E+000,-1.)); +#139112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139113 = ORIENTED_EDGE('',*,*,#138942,.T.); +#139114 = ORIENTED_EDGE('',*,*,#139115,.F.); +#139115 = EDGE_CURVE('',#139116,#138945,#139118,.T.); +#139116 = VERTEX_POINT('',#139117); +#139117 = CARTESIAN_POINT('',(8.65,10.304819755875,0.75)); +#139118 = SURFACE_CURVE('',#139119,(#139124,#139130),.PCURVE_S1.); +#139119 = CIRCLE('',#139120,0.2192697516); +#139120 = AXIS2_PLACEMENT_3D('',#139121,#139122,#139123); +#139121 = CARTESIAN_POINT('',(8.65,10.30032442045,0.530776333563)); +#139122 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139123 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139124 = PCURVE('',#138960,#139125); +#139125 = DEFINITIONAL_REPRESENTATION('',(#139126),#139129); +#139126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139127,#139128), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#136735 = CARTESIAN_POINT('',(1.591299156552,-8.65)); -#136736 = CARTESIAN_POINT('',(3.14159265359,-8.65)); -#136737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139127 = CARTESIAN_POINT('',(1.591299156552,-8.65)); +#139128 = CARTESIAN_POINT('',(3.14159265359,-8.65)); +#139129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#136738 = PCURVE('',#87384,#136739); -#136739 = DEFINITIONAL_REPRESENTATION('',(#136740),#136748); -#136740 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#136741,#136742,#136743, - #136744,#136745,#136746,#136747),.UNSPECIFIED.,.T.,.F.) +#139130 = PCURVE('',#89776,#139131); +#139131 = DEFINITIONAL_REPRESENTATION('',(#139132),#139140); +#139132 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139133,#139134,#139135, + #139136,#139137,#139138,#139139),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#136741 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#136742 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#136743 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#136744 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#136745 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#136746 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#136747 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#136748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136749 = ORIENTED_EDGE('',*,*,#136750,.T.); -#136750 = EDGE_CURVE('',#136724,#136700,#136751,.T.); -#136751 = SURFACE_CURVE('',#136752,(#136756,#136762),.PCURVE_S1.); -#136752 = LINE('',#136753,#136754); -#136753 = CARTESIAN_POINT('',(8.65,10.304819755875,0.75)); -#136754 = VECTOR('',#136755,1.); -#136755 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136756 = PCURVE('',#136568,#136757); -#136757 = DEFINITIONAL_REPRESENTATION('',(#136758),#136761); -#136758 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#136759,#136760), +#139133 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#139134 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#139135 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#139136 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#139137 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#139138 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#139139 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#139140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139141 = ORIENTED_EDGE('',*,*,#139142,.T.); +#139142 = EDGE_CURVE('',#139116,#139092,#139143,.T.); +#139143 = SURFACE_CURVE('',#139144,(#139148,#139154),.PCURVE_S1.); +#139144 = LINE('',#139145,#139146); +#139145 = CARTESIAN_POINT('',(8.65,10.304819755875,0.75)); +#139146 = VECTOR('',#139147,1.); +#139147 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139148 = PCURVE('',#138960,#139149); +#139149 = DEFINITIONAL_REPRESENTATION('',(#139150),#139153); +#139150 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139151,#139152), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#136759 = CARTESIAN_POINT('',(1.591299156552,-8.65)); -#136760 = CARTESIAN_POINT('',(1.591299156552,-8.85)); -#136761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136762 = PCURVE('',#87466,#136763); -#136763 = DEFINITIONAL_REPRESENTATION('',(#136764),#136768); -#136764 = LINE('',#136765,#136766); -#136765 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#136766 = VECTOR('',#136767,1.); -#136767 = DIRECTION('',(-8.881784197001E-016,1.)); -#136768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136769 = ADVANCED_FACE('',(#136770),#87384,.F.); -#136770 = FACE_BOUND('',#136771,.T.); -#136771 = EDGE_LOOP('',(#136772,#136793,#136794,#136795,#136796,#136797, - #136818,#136819,#136820,#136821,#136822,#136843)); -#136772 = ORIENTED_EDGE('',*,*,#136773,.F.); -#136773 = EDGE_CURVE('',#136724,#87369,#136774,.T.); -#136774 = SURFACE_CURVE('',#136775,(#136779,#136786),.PCURVE_S1.); -#136775 = LINE('',#136776,#136777); -#136776 = CARTESIAN_POINT('',(8.65,10.527847992439,0.75)); -#136777 = VECTOR('',#136778,1.); -#136778 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#136779 = PCURVE('',#87384,#136780); -#136780 = DEFINITIONAL_REPRESENTATION('',(#136781),#136785); -#136781 = LINE('',#136782,#136783); -#136782 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#136783 = VECTOR('',#136784,1.); -#136784 = DIRECTION('',(-3.563627120235E-016,-1.)); -#136785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136786 = PCURVE('',#87466,#136787); -#136787 = DEFINITIONAL_REPRESENTATION('',(#136788),#136792); -#136788 = LINE('',#136789,#136790); -#136789 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136790 = VECTOR('',#136791,1.); -#136791 = DIRECTION('',(-1.,2.164989446033E-063)); -#136792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136793 = ORIENTED_EDGE('',*,*,#136723,.T.); -#136794 = ORIENTED_EDGE('',*,*,#136601,.T.); -#136795 = ORIENTED_EDGE('',*,*,#136372,.T.); -#136796 = ORIENTED_EDGE('',*,*,#136162,.T.); -#136797 = ORIENTED_EDGE('',*,*,#136798,.T.); -#136798 = EDGE_CURVE('',#136135,#136216,#136799,.T.); -#136799 = SURFACE_CURVE('',#136800,(#136804,#136811),.PCURVE_S1.); -#136800 = LINE('',#136801,#136802); -#136801 = CARTESIAN_POINT('',(8.65,11.,1.159810404338E-002)); -#136802 = VECTOR('',#136803,1.); -#136803 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#136804 = PCURVE('',#87384,#136805); -#136805 = DEFINITIONAL_REPRESENTATION('',(#136806),#136810); -#136806 = LINE('',#136807,#136808); -#136807 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#136808 = VECTOR('',#136809,1.); -#136809 = DIRECTION('',(1.,-2.101748079665E-016)); -#136810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136811 = PCURVE('',#136150,#136812); -#136812 = DEFINITIONAL_REPRESENTATION('',(#136813),#136817); -#136813 = LINE('',#136814,#136815); -#136814 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#136815 = VECTOR('',#136816,1.); -#136816 = DIRECTION('',(1.570395187386E-016,-1.)); -#136817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136818 = ORIENTED_EDGE('',*,*,#136213,.F.); -#136819 = ORIENTED_EDGE('',*,*,#136451,.F.); -#136820 = ORIENTED_EDGE('',*,*,#136504,.F.); -#136821 = ORIENTED_EDGE('',*,*,#136625,.F.); -#136822 = ORIENTED_EDGE('',*,*,#136823,.T.); -#136823 = EDGE_CURVE('',#136626,#87367,#136824,.T.); -#136824 = SURFACE_CURVE('',#136825,(#136829,#136836),.PCURVE_S1.); -#136825 = LINE('',#136826,#136827); -#136826 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); -#136827 = VECTOR('',#136828,1.); -#136828 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#136829 = PCURVE('',#87384,#136830); -#136830 = DEFINITIONAL_REPRESENTATION('',(#136831),#136835); -#136831 = LINE('',#136832,#136833); -#136832 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136833 = VECTOR('',#136834,1.); -#136834 = DIRECTION('',(-3.563627120235E-016,-1.)); -#136835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136836 = PCURVE('',#87412,#136837); -#136837 = DEFINITIONAL_REPRESENTATION('',(#136838),#136842); -#136838 = LINE('',#136839,#136840); -#136839 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136840 = VECTOR('',#136841,1.); -#136841 = DIRECTION('',(1.,2.164989446033E-063)); -#136842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136843 = ORIENTED_EDGE('',*,*,#87366,.T.); -#136844 = ADVANCED_FACE('',(#136845),#87466,.F.); -#136845 = FACE_BOUND('',#136846,.T.); -#136846 = EDGE_LOOP('',(#136847,#136848,#136849,#136850)); -#136847 = ORIENTED_EDGE('',*,*,#136750,.F.); -#136848 = ORIENTED_EDGE('',*,*,#136773,.T.); -#136849 = ORIENTED_EDGE('',*,*,#87452,.T.); -#136850 = ORIENTED_EDGE('',*,*,#136851,.F.); -#136851 = EDGE_CURVE('',#136700,#87425,#136852,.T.); -#136852 = SURFACE_CURVE('',#136853,(#136857,#136864),.PCURVE_S1.); -#136853 = LINE('',#136854,#136855); -#136854 = CARTESIAN_POINT('',(8.85,10.527847992439,0.75)); -#136855 = VECTOR('',#136856,1.); -#136856 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#136857 = PCURVE('',#87466,#136858); -#136858 = DEFINITIONAL_REPRESENTATION('',(#136859),#136863); -#136859 = LINE('',#136860,#136861); -#136860 = CARTESIAN_POINT('',(0.E+000,0.2)); -#136861 = VECTOR('',#136862,1.); -#136862 = DIRECTION('',(-1.,2.164989446033E-063)); -#136863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136864 = PCURVE('',#87440,#136865); -#136865 = DEFINITIONAL_REPRESENTATION('',(#136866),#136870); -#136866 = LINE('',#136867,#136868); -#136867 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#136868 = VECTOR('',#136869,1.); -#136869 = DIRECTION('',(3.563627120235E-016,-1.)); -#136870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136871 = ADVANCED_FACE('',(#136872),#87440,.F.); -#136872 = FACE_BOUND('',#136873,.T.); -#136873 = EDGE_LOOP('',(#136874,#136895,#136896,#136897,#136898,#136899, - #136920,#136921,#136922,#136923,#136924,#136925)); -#136874 = ORIENTED_EDGE('',*,*,#136875,.F.); -#136875 = EDGE_CURVE('',#136653,#87397,#136876,.T.); -#136876 = SURFACE_CURVE('',#136877,(#136881,#136888),.PCURVE_S1.); -#136877 = LINE('',#136878,#136879); -#136878 = CARTESIAN_POINT('',(8.85,10.527847992439,0.65)); -#136879 = VECTOR('',#136880,1.); -#136880 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#136881 = PCURVE('',#87440,#136882); -#136882 = DEFINITIONAL_REPRESENTATION('',(#136883),#136887); -#136883 = LINE('',#136884,#136885); -#136884 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#136885 = VECTOR('',#136886,1.); -#136886 = DIRECTION('',(3.563627120235E-016,-1.)); -#136887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136888 = PCURVE('',#87412,#136889); -#136889 = DEFINITIONAL_REPRESENTATION('',(#136890),#136894); -#136890 = LINE('',#136891,#136892); -#136891 = CARTESIAN_POINT('',(0.E+000,0.2)); -#136892 = VECTOR('',#136893,1.); -#136893 = DIRECTION('',(1.,2.164989446033E-063)); -#136894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136895 = ORIENTED_EDGE('',*,*,#136674,.T.); -#136896 = ORIENTED_EDGE('',*,*,#136526,.T.); -#136897 = ORIENTED_EDGE('',*,*,#136397,.T.); -#136898 = ORIENTED_EDGE('',*,*,#136266,.T.); -#136899 = ORIENTED_EDGE('',*,*,#136900,.T.); -#136900 = EDGE_CURVE('',#136244,#136107,#136901,.T.); -#136901 = SURFACE_CURVE('',#136902,(#136906,#136913),.PCURVE_S1.); -#136902 = LINE('',#136903,#136904); -#136903 = CARTESIAN_POINT('',(8.85,11.,1.159810404338E-002)); -#136904 = VECTOR('',#136905,1.); -#136905 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#136906 = PCURVE('',#87440,#136907); -#136907 = DEFINITIONAL_REPRESENTATION('',(#136908),#136912); -#136908 = LINE('',#136909,#136910); -#136909 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#136910 = VECTOR('',#136911,1.); -#136911 = DIRECTION('',(1.,2.101748079665E-016)); -#136912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136913 = PCURVE('',#136150,#136914); -#136914 = DEFINITIONAL_REPRESENTATION('',(#136915),#136919); -#136915 = LINE('',#136916,#136917); -#136916 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#136917 = VECTOR('',#136918,1.); -#136918 = DIRECTION('',(-1.570395187386E-016,1.)); -#136919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136920 = ORIENTED_EDGE('',*,*,#136104,.F.); -#136921 = ORIENTED_EDGE('',*,*,#136318,.F.); -#136922 = ORIENTED_EDGE('',*,*,#136579,.F.); -#136923 = ORIENTED_EDGE('',*,*,#136699,.F.); -#136924 = ORIENTED_EDGE('',*,*,#136851,.T.); -#136925 = ORIENTED_EDGE('',*,*,#87424,.T.); -#136926 = ADVANCED_FACE('',(#136927),#87412,.F.); -#136927 = FACE_BOUND('',#136928,.T.); -#136928 = EDGE_LOOP('',(#136929,#136930,#136931,#136932)); -#136929 = ORIENTED_EDGE('',*,*,#136652,.F.); -#136930 = ORIENTED_EDGE('',*,*,#136875,.T.); -#136931 = ORIENTED_EDGE('',*,*,#87396,.T.); -#136932 = ORIENTED_EDGE('',*,*,#136823,.F.); -#136933 = ADVANCED_FACE('',(#136934),#136150,.T.); -#136934 = FACE_BOUND('',#136935,.T.); -#136935 = EDGE_LOOP('',(#136936,#136937,#136938,#136939)); -#136936 = ORIENTED_EDGE('',*,*,#136900,.F.); -#136937 = ORIENTED_EDGE('',*,*,#136243,.F.); -#136938 = ORIENTED_EDGE('',*,*,#136798,.F.); -#136939 = ORIENTED_EDGE('',*,*,#136134,.F.); -#136940 = ADVANCED_FACE('',(#136941),#136955,.T.); -#136941 = FACE_BOUND('',#136942,.T.); -#136942 = EDGE_LOOP('',(#136943,#136973,#137001,#137024)); -#136943 = ORIENTED_EDGE('',*,*,#136944,.T.); -#136944 = EDGE_CURVE('',#136945,#136947,#136949,.T.); -#136945 = VERTEX_POINT('',#136946); -#136946 = CARTESIAN_POINT('',(4.65,10.74341632541,-0.308197125857)); -#136947 = VERTEX_POINT('',#136948); -#136948 = CARTESIAN_POINT('',(4.65,11.,-0.308197125857)); -#136949 = SURFACE_CURVE('',#136950,(#136954,#136966),.PCURVE_S1.); -#136950 = LINE('',#136951,#136952); -#136951 = CARTESIAN_POINT('',(4.65,10.74341632541,-0.308197125857)); -#136952 = VECTOR('',#136953,1.); -#136953 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#136954 = PCURVE('',#136955,#136960); -#136955 = PLANE('',#136956); -#136956 = AXIS2_PLACEMENT_3D('',#136957,#136958,#136959); -#136957 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#139151 = CARTESIAN_POINT('',(1.591299156552,-8.65)); +#139152 = CARTESIAN_POINT('',(1.591299156552,-8.85)); +#139153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139154 = PCURVE('',#89858,#139155); +#139155 = DEFINITIONAL_REPRESENTATION('',(#139156),#139160); +#139156 = LINE('',#139157,#139158); +#139157 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#139158 = VECTOR('',#139159,1.); +#139159 = DIRECTION('',(-8.881784197001E-016,1.)); +#139160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139161 = ADVANCED_FACE('',(#139162),#89776,.F.); +#139162 = FACE_BOUND('',#139163,.T.); +#139163 = EDGE_LOOP('',(#139164,#139185,#139186,#139187,#139188,#139189, + #139210,#139211,#139212,#139213,#139214,#139235)); +#139164 = ORIENTED_EDGE('',*,*,#139165,.F.); +#139165 = EDGE_CURVE('',#139116,#89761,#139166,.T.); +#139166 = SURFACE_CURVE('',#139167,(#139171,#139178),.PCURVE_S1.); +#139167 = LINE('',#139168,#139169); +#139168 = CARTESIAN_POINT('',(8.65,10.527847992439,0.75)); +#139169 = VECTOR('',#139170,1.); +#139170 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#139171 = PCURVE('',#89776,#139172); +#139172 = DEFINITIONAL_REPRESENTATION('',(#139173),#139177); +#139173 = LINE('',#139174,#139175); +#139174 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#139175 = VECTOR('',#139176,1.); +#139176 = DIRECTION('',(-3.563627120235E-016,-1.)); +#139177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139178 = PCURVE('',#89858,#139179); +#139179 = DEFINITIONAL_REPRESENTATION('',(#139180),#139184); +#139180 = LINE('',#139181,#139182); +#139181 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139182 = VECTOR('',#139183,1.); +#139183 = DIRECTION('',(-1.,2.164989446033E-063)); +#139184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139185 = ORIENTED_EDGE('',*,*,#139115,.T.); +#139186 = ORIENTED_EDGE('',*,*,#138993,.T.); +#139187 = ORIENTED_EDGE('',*,*,#138764,.T.); +#139188 = ORIENTED_EDGE('',*,*,#138554,.T.); +#139189 = ORIENTED_EDGE('',*,*,#139190,.T.); +#139190 = EDGE_CURVE('',#138527,#138608,#139191,.T.); +#139191 = SURFACE_CURVE('',#139192,(#139196,#139203),.PCURVE_S1.); +#139192 = LINE('',#139193,#139194); +#139193 = CARTESIAN_POINT('',(8.65,11.,1.159810404338E-002)); +#139194 = VECTOR('',#139195,1.); +#139195 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#139196 = PCURVE('',#89776,#139197); +#139197 = DEFINITIONAL_REPRESENTATION('',(#139198),#139202); +#139198 = LINE('',#139199,#139200); +#139199 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#139200 = VECTOR('',#139201,1.); +#139201 = DIRECTION('',(1.,-2.101748079665E-016)); +#139202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139203 = PCURVE('',#138542,#139204); +#139204 = DEFINITIONAL_REPRESENTATION('',(#139205),#139209); +#139205 = LINE('',#139206,#139207); +#139206 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#139207 = VECTOR('',#139208,1.); +#139208 = DIRECTION('',(1.570395187386E-016,-1.)); +#139209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139210 = ORIENTED_EDGE('',*,*,#138605,.F.); +#139211 = ORIENTED_EDGE('',*,*,#138843,.F.); +#139212 = ORIENTED_EDGE('',*,*,#138896,.F.); +#139213 = ORIENTED_EDGE('',*,*,#139017,.F.); +#139214 = ORIENTED_EDGE('',*,*,#139215,.T.); +#139215 = EDGE_CURVE('',#139018,#89759,#139216,.T.); +#139216 = SURFACE_CURVE('',#139217,(#139221,#139228),.PCURVE_S1.); +#139217 = LINE('',#139218,#139219); +#139218 = CARTESIAN_POINT('',(8.65,10.527847992439,0.65)); +#139219 = VECTOR('',#139220,1.); +#139220 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#139221 = PCURVE('',#89776,#139222); +#139222 = DEFINITIONAL_REPRESENTATION('',(#139223),#139227); +#139223 = LINE('',#139224,#139225); +#139224 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139225 = VECTOR('',#139226,1.); +#139226 = DIRECTION('',(-3.563627120235E-016,-1.)); +#139227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139228 = PCURVE('',#89804,#139229); +#139229 = DEFINITIONAL_REPRESENTATION('',(#139230),#139234); +#139230 = LINE('',#139231,#139232); +#139231 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139232 = VECTOR('',#139233,1.); +#139233 = DIRECTION('',(1.,2.164989446033E-063)); +#139234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139235 = ORIENTED_EDGE('',*,*,#89758,.T.); +#139236 = ADVANCED_FACE('',(#139237),#89858,.F.); +#139237 = FACE_BOUND('',#139238,.T.); +#139238 = EDGE_LOOP('',(#139239,#139240,#139241,#139242)); +#139239 = ORIENTED_EDGE('',*,*,#139142,.F.); +#139240 = ORIENTED_EDGE('',*,*,#139165,.T.); +#139241 = ORIENTED_EDGE('',*,*,#89844,.T.); +#139242 = ORIENTED_EDGE('',*,*,#139243,.F.); +#139243 = EDGE_CURVE('',#139092,#89817,#139244,.T.); +#139244 = SURFACE_CURVE('',#139245,(#139249,#139256),.PCURVE_S1.); +#139245 = LINE('',#139246,#139247); +#139246 = CARTESIAN_POINT('',(8.85,10.527847992439,0.75)); +#139247 = VECTOR('',#139248,1.); +#139248 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#139249 = PCURVE('',#89858,#139250); +#139250 = DEFINITIONAL_REPRESENTATION('',(#139251),#139255); +#139251 = LINE('',#139252,#139253); +#139252 = CARTESIAN_POINT('',(0.E+000,0.2)); +#139253 = VECTOR('',#139254,1.); +#139254 = DIRECTION('',(-1.,2.164989446033E-063)); +#139255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139256 = PCURVE('',#89832,#139257); +#139257 = DEFINITIONAL_REPRESENTATION('',(#139258),#139262); +#139258 = LINE('',#139259,#139260); +#139259 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#139260 = VECTOR('',#139261,1.); +#139261 = DIRECTION('',(3.563627120235E-016,-1.)); +#139262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139263 = ADVANCED_FACE('',(#139264),#89832,.F.); +#139264 = FACE_BOUND('',#139265,.T.); +#139265 = EDGE_LOOP('',(#139266,#139287,#139288,#139289,#139290,#139291, + #139312,#139313,#139314,#139315,#139316,#139317)); +#139266 = ORIENTED_EDGE('',*,*,#139267,.F.); +#139267 = EDGE_CURVE('',#139045,#89789,#139268,.T.); +#139268 = SURFACE_CURVE('',#139269,(#139273,#139280),.PCURVE_S1.); +#139269 = LINE('',#139270,#139271); +#139270 = CARTESIAN_POINT('',(8.85,10.527847992439,0.65)); +#139271 = VECTOR('',#139272,1.); +#139272 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#139273 = PCURVE('',#89832,#139274); +#139274 = DEFINITIONAL_REPRESENTATION('',(#139275),#139279); +#139275 = LINE('',#139276,#139277); +#139276 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139277 = VECTOR('',#139278,1.); +#139278 = DIRECTION('',(3.563627120235E-016,-1.)); +#139279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139280 = PCURVE('',#89804,#139281); +#139281 = DEFINITIONAL_REPRESENTATION('',(#139282),#139286); +#139282 = LINE('',#139283,#139284); +#139283 = CARTESIAN_POINT('',(0.E+000,0.2)); +#139284 = VECTOR('',#139285,1.); +#139285 = DIRECTION('',(1.,2.164989446033E-063)); +#139286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139287 = ORIENTED_EDGE('',*,*,#139066,.T.); +#139288 = ORIENTED_EDGE('',*,*,#138918,.T.); +#139289 = ORIENTED_EDGE('',*,*,#138789,.T.); +#139290 = ORIENTED_EDGE('',*,*,#138658,.T.); +#139291 = ORIENTED_EDGE('',*,*,#139292,.T.); +#139292 = EDGE_CURVE('',#138636,#138499,#139293,.T.); +#139293 = SURFACE_CURVE('',#139294,(#139298,#139305),.PCURVE_S1.); +#139294 = LINE('',#139295,#139296); +#139295 = CARTESIAN_POINT('',(8.85,11.,1.159810404338E-002)); +#139296 = VECTOR('',#139297,1.); +#139297 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#139298 = PCURVE('',#89832,#139299); +#139299 = DEFINITIONAL_REPRESENTATION('',(#139300),#139304); +#139300 = LINE('',#139301,#139302); +#139301 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#139302 = VECTOR('',#139303,1.); +#139303 = DIRECTION('',(1.,2.101748079665E-016)); +#139304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139305 = PCURVE('',#138542,#139306); +#139306 = DEFINITIONAL_REPRESENTATION('',(#139307),#139311); +#139307 = LINE('',#139308,#139309); +#139308 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#139309 = VECTOR('',#139310,1.); +#139310 = DIRECTION('',(-1.570395187386E-016,1.)); +#139311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139312 = ORIENTED_EDGE('',*,*,#138496,.F.); +#139313 = ORIENTED_EDGE('',*,*,#138710,.F.); +#139314 = ORIENTED_EDGE('',*,*,#138971,.F.); +#139315 = ORIENTED_EDGE('',*,*,#139091,.F.); +#139316 = ORIENTED_EDGE('',*,*,#139243,.T.); +#139317 = ORIENTED_EDGE('',*,*,#89816,.T.); +#139318 = ADVANCED_FACE('',(#139319),#89804,.F.); +#139319 = FACE_BOUND('',#139320,.T.); +#139320 = EDGE_LOOP('',(#139321,#139322,#139323,#139324)); +#139321 = ORIENTED_EDGE('',*,*,#139044,.F.); +#139322 = ORIENTED_EDGE('',*,*,#139267,.T.); +#139323 = ORIENTED_EDGE('',*,*,#89788,.T.); +#139324 = ORIENTED_EDGE('',*,*,#139215,.F.); +#139325 = ADVANCED_FACE('',(#139326),#138542,.T.); +#139326 = FACE_BOUND('',#139327,.T.); +#139327 = EDGE_LOOP('',(#139328,#139329,#139330,#139331)); +#139328 = ORIENTED_EDGE('',*,*,#139292,.F.); +#139329 = ORIENTED_EDGE('',*,*,#138635,.F.); +#139330 = ORIENTED_EDGE('',*,*,#139190,.F.); +#139331 = ORIENTED_EDGE('',*,*,#138526,.F.); +#139332 = ADVANCED_FACE('',(#139333),#139347,.T.); +#139333 = FACE_BOUND('',#139334,.T.); +#139334 = EDGE_LOOP('',(#139335,#139365,#139393,#139416)); +#139335 = ORIENTED_EDGE('',*,*,#139336,.T.); +#139336 = EDGE_CURVE('',#139337,#139339,#139341,.T.); +#139337 = VERTEX_POINT('',#139338); +#139338 = CARTESIAN_POINT('',(4.65,10.74341632541,-0.308197125857)); +#139339 = VERTEX_POINT('',#139340); +#139340 = CARTESIAN_POINT('',(4.65,11.,-0.308197125857)); +#139341 = SURFACE_CURVE('',#139342,(#139346,#139358),.PCURVE_S1.); +#139342 = LINE('',#139343,#139344); +#139343 = CARTESIAN_POINT('',(4.65,10.74341632541,-0.308197125857)); +#139344 = VECTOR('',#139345,1.); +#139345 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#139346 = PCURVE('',#139347,#139352); +#139347 = PLANE('',#139348); +#139348 = AXIS2_PLACEMENT_3D('',#139349,#139350,#139351); +#139349 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#136958 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#136959 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#136960 = DEFINITIONAL_REPRESENTATION('',(#136961),#136965); -#136961 = LINE('',#136962,#136963); -#136962 = CARTESIAN_POINT('',(-4.65,-3.552713678801E-015)); -#136963 = VECTOR('',#136964,1.); -#136964 = DIRECTION('',(-6.725593854929E-015,1.)); -#136965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136966 = PCURVE('',#87580,#136967); -#136967 = DEFINITIONAL_REPRESENTATION('',(#136968),#136972); -#136968 = LINE('',#136969,#136970); -#136969 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#136970 = VECTOR('',#136971,1.); -#136971 = DIRECTION('',(0.E+000,1.)); -#136972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136973 = ORIENTED_EDGE('',*,*,#136974,.T.); -#136974 = EDGE_CURVE('',#136947,#136975,#136977,.T.); -#136975 = VERTEX_POINT('',#136976); -#136976 = CARTESIAN_POINT('',(4.85,11.,-0.308197125857)); -#136977 = SURFACE_CURVE('',#136978,(#136982,#136989),.PCURVE_S1.); -#136978 = LINE('',#136979,#136980); -#136979 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#136980 = VECTOR('',#136981,1.); -#136981 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#136982 = PCURVE('',#136955,#136983); -#136983 = DEFINITIONAL_REPRESENTATION('',(#136984),#136988); -#136984 = LINE('',#136985,#136986); -#136985 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#136986 = VECTOR('',#136987,1.); -#136987 = DIRECTION('',(-1.,-8.881784197001E-016)); -#136988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#136989 = PCURVE('',#136990,#136995); -#136990 = PLANE('',#136991); -#136991 = AXIS2_PLACEMENT_3D('',#136992,#136993,#136994); -#136992 = CARTESIAN_POINT('',(4.75,11.,-0.258196742327)); -#136993 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#136994 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#136995 = DEFINITIONAL_REPRESENTATION('',(#136996),#137000); -#136996 = LINE('',#136997,#136998); -#136997 = CARTESIAN_POINT('',(4.75,-5.000038352949E-002)); -#136998 = VECTOR('',#136999,1.); -#136999 = DIRECTION('',(-1.,-1.1653254136E-048)); -#137000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137001 = ORIENTED_EDGE('',*,*,#137002,.F.); -#137002 = EDGE_CURVE('',#137003,#136975,#137005,.T.); -#137003 = VERTEX_POINT('',#137004); -#137004 = CARTESIAN_POINT('',(4.85,10.74341632541,-0.308197125857)); -#137005 = SURFACE_CURVE('',#137006,(#137010,#137017),.PCURVE_S1.); -#137006 = LINE('',#137007,#137008); -#137007 = CARTESIAN_POINT('',(4.85,10.74341632541,-0.308197125857)); -#137008 = VECTOR('',#137009,1.); -#137009 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137010 = PCURVE('',#136955,#137011); -#137011 = DEFINITIONAL_REPRESENTATION('',(#137012),#137016); -#137012 = LINE('',#137013,#137014); -#137013 = CARTESIAN_POINT('',(-4.85,-3.552713678801E-015)); -#137014 = VECTOR('',#137015,1.); -#137015 = DIRECTION('',(-6.725593854929E-015,1.)); -#137016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137017 = PCURVE('',#87526,#137018); -#137018 = DEFINITIONAL_REPRESENTATION('',(#137019),#137023); -#137019 = LINE('',#137020,#137021); -#137020 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#137021 = VECTOR('',#137022,1.); -#137022 = DIRECTION('',(0.E+000,1.)); -#137023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137024 = ORIENTED_EDGE('',*,*,#137025,.T.); -#137025 = EDGE_CURVE('',#137003,#136945,#137026,.T.); -#137026 = SURFACE_CURVE('',#137027,(#137031,#137038),.PCURVE_S1.); -#137027 = LINE('',#137028,#137029); -#137028 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#139350 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#139351 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#139352 = DEFINITIONAL_REPRESENTATION('',(#139353),#139357); +#139353 = LINE('',#139354,#139355); +#139354 = CARTESIAN_POINT('',(-4.65,-3.552713678801E-015)); +#139355 = VECTOR('',#139356,1.); +#139356 = DIRECTION('',(-6.725593854929E-015,1.)); +#139357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139358 = PCURVE('',#89972,#139359); +#139359 = DEFINITIONAL_REPRESENTATION('',(#139360),#139364); +#139360 = LINE('',#139361,#139362); +#139361 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#139362 = VECTOR('',#139363,1.); +#139363 = DIRECTION('',(0.E+000,1.)); +#139364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139365 = ORIENTED_EDGE('',*,*,#139366,.T.); +#139366 = EDGE_CURVE('',#139339,#139367,#139369,.T.); +#139367 = VERTEX_POINT('',#139368); +#139368 = CARTESIAN_POINT('',(4.85,11.,-0.308197125857)); +#139369 = SURFACE_CURVE('',#139370,(#139374,#139381),.PCURVE_S1.); +#139370 = LINE('',#139371,#139372); +#139371 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#139372 = VECTOR('',#139373,1.); +#139373 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139374 = PCURVE('',#139347,#139375); +#139375 = DEFINITIONAL_REPRESENTATION('',(#139376),#139380); +#139376 = LINE('',#139377,#139378); +#139377 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#139378 = VECTOR('',#139379,1.); +#139379 = DIRECTION('',(-1.,-8.881784197001E-016)); +#139380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139381 = PCURVE('',#139382,#139387); +#139382 = PLANE('',#139383); +#139383 = AXIS2_PLACEMENT_3D('',#139384,#139385,#139386); +#139384 = CARTESIAN_POINT('',(4.75,11.,-0.258196742327)); +#139385 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#139386 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#139387 = DEFINITIONAL_REPRESENTATION('',(#139388),#139392); +#139388 = LINE('',#139389,#139390); +#139389 = CARTESIAN_POINT('',(4.75,-5.000038352949E-002)); +#139390 = VECTOR('',#139391,1.); +#139391 = DIRECTION('',(-1.,-1.1653254136E-048)); +#139392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139393 = ORIENTED_EDGE('',*,*,#139394,.F.); +#139394 = EDGE_CURVE('',#139395,#139367,#139397,.T.); +#139395 = VERTEX_POINT('',#139396); +#139396 = CARTESIAN_POINT('',(4.85,10.74341632541,-0.308197125857)); +#139397 = SURFACE_CURVE('',#139398,(#139402,#139409),.PCURVE_S1.); +#139398 = LINE('',#139399,#139400); +#139399 = CARTESIAN_POINT('',(4.85,10.74341632541,-0.308197125857)); +#139400 = VECTOR('',#139401,1.); +#139401 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#139402 = PCURVE('',#139347,#139403); +#139403 = DEFINITIONAL_REPRESENTATION('',(#139404),#139408); +#139404 = LINE('',#139405,#139406); +#139405 = CARTESIAN_POINT('',(-4.85,-3.552713678801E-015)); +#139406 = VECTOR('',#139407,1.); +#139407 = DIRECTION('',(-6.725593854929E-015,1.)); +#139408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139409 = PCURVE('',#89918,#139410); +#139410 = DEFINITIONAL_REPRESENTATION('',(#139411),#139415); +#139411 = LINE('',#139412,#139413); +#139412 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#139413 = VECTOR('',#139414,1.); +#139414 = DIRECTION('',(0.E+000,1.)); +#139415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139416 = ORIENTED_EDGE('',*,*,#139417,.T.); +#139417 = EDGE_CURVE('',#139395,#139337,#139418,.T.); +#139418 = SURFACE_CURVE('',#139419,(#139423,#139430),.PCURVE_S1.); +#139419 = LINE('',#139420,#139421); +#139420 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#137029 = VECTOR('',#137030,1.); -#137030 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137031 = PCURVE('',#136955,#137032); -#137032 = DEFINITIONAL_REPRESENTATION('',(#137033),#137037); -#137033 = LINE('',#137034,#137035); -#137034 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137035 = VECTOR('',#137036,1.); -#137036 = DIRECTION('',(1.,8.881784197001E-016)); -#137037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137038 = PCURVE('',#137039,#137044); -#137039 = CYLINDRICAL_SURFACE('',#137040,0.308574064194); -#137040 = AXIS2_PLACEMENT_3D('',#137041,#137042,#137043); -#137041 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#139421 = VECTOR('',#139422,1.); +#139422 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139423 = PCURVE('',#139347,#139424); +#139424 = DEFINITIONAL_REPRESENTATION('',(#139425),#139429); +#139425 = LINE('',#139426,#139427); +#139426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139427 = VECTOR('',#139428,1.); +#139428 = DIRECTION('',(1.,8.881784197001E-016)); +#139429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139430 = PCURVE('',#139431,#139436); +#139431 = CYLINDRICAL_SURFACE('',#139432,0.308574064194); +#139432 = AXIS2_PLACEMENT_3D('',#139433,#139434,#139435); +#139433 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#137042 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137043 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137044 = DEFINITIONAL_REPRESENTATION('',(#137045),#137048); -#137045 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137046,#137047), +#139434 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139435 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139436 = DEFINITIONAL_REPRESENTATION('',(#139437),#139440); +#139437 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139438,#139439), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#137046 = CARTESIAN_POINT('',(4.761821717947,4.85)); -#137047 = CARTESIAN_POINT('',(4.761821717947,4.65)); -#137048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137049 = ADVANCED_FACE('',(#137050),#137064,.T.); -#137050 = FACE_BOUND('',#137051,.T.); -#137051 = EDGE_LOOP('',(#137052,#137082,#137105,#137128)); -#137052 = ORIENTED_EDGE('',*,*,#137053,.T.); -#137053 = EDGE_CURVE('',#137054,#137056,#137058,.T.); -#137054 = VERTEX_POINT('',#137055); -#137055 = CARTESIAN_POINT('',(4.85,10.740726081328,-0.208196358798)); -#137056 = VERTEX_POINT('',#137057); -#137057 = CARTESIAN_POINT('',(4.85,11.,-0.208196358798)); -#137058 = SURFACE_CURVE('',#137059,(#137063,#137075),.PCURVE_S1.); -#137059 = LINE('',#137060,#137061); -#137060 = CARTESIAN_POINT('',(4.85,10.740726081328,-0.208196358798)); -#137061 = VECTOR('',#137062,1.); -#137062 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137063 = PCURVE('',#137064,#137069); -#137064 = PLANE('',#137065); -#137065 = AXIS2_PLACEMENT_3D('',#137066,#137067,#137068); -#137066 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#139438 = CARTESIAN_POINT('',(4.761821717947,4.85)); +#139439 = CARTESIAN_POINT('',(4.761821717947,4.65)); +#139440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139441 = ADVANCED_FACE('',(#139442),#139456,.T.); +#139442 = FACE_BOUND('',#139443,.T.); +#139443 = EDGE_LOOP('',(#139444,#139474,#139497,#139520)); +#139444 = ORIENTED_EDGE('',*,*,#139445,.T.); +#139445 = EDGE_CURVE('',#139446,#139448,#139450,.T.); +#139446 = VERTEX_POINT('',#139447); +#139447 = CARTESIAN_POINT('',(4.85,10.740726081328,-0.208196358798)); +#139448 = VERTEX_POINT('',#139449); +#139449 = CARTESIAN_POINT('',(4.85,11.,-0.208196358798)); +#139450 = SURFACE_CURVE('',#139451,(#139455,#139467),.PCURVE_S1.); +#139451 = LINE('',#139452,#139453); +#139452 = CARTESIAN_POINT('',(4.85,10.740726081328,-0.208196358798)); +#139453 = VECTOR('',#139454,1.); +#139454 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#139455 = PCURVE('',#139456,#139461); +#139456 = PLANE('',#139457); +#139457 = AXIS2_PLACEMENT_3D('',#139458,#139459,#139460); +#139458 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#137067 = DIRECTION('',(0.E+000,0.E+000,1.)); -#137068 = DIRECTION('',(1.,0.E+000,0.E+000)); -#137069 = DEFINITIONAL_REPRESENTATION('',(#137070),#137074); -#137070 = LINE('',#137071,#137072); -#137071 = CARTESIAN_POINT('',(4.85,-3.552713678801E-015)); -#137072 = VECTOR('',#137073,1.); -#137073 = DIRECTION('',(6.725593854929E-015,1.)); -#137074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137075 = PCURVE('',#87526,#137076); -#137076 = DEFINITIONAL_REPRESENTATION('',(#137077),#137081); -#137077 = LINE('',#137078,#137079); -#137078 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#137079 = VECTOR('',#137080,1.); -#137080 = DIRECTION('',(0.E+000,1.)); -#137081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137082 = ORIENTED_EDGE('',*,*,#137083,.T.); -#137083 = EDGE_CURVE('',#137056,#137084,#137086,.T.); -#137084 = VERTEX_POINT('',#137085); -#137085 = CARTESIAN_POINT('',(4.65,11.,-0.208196358798)); -#137086 = SURFACE_CURVE('',#137087,(#137091,#137098),.PCURVE_S1.); -#137087 = LINE('',#137088,#137089); -#137088 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#137089 = VECTOR('',#137090,1.); -#137090 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137091 = PCURVE('',#137064,#137092); -#137092 = DEFINITIONAL_REPRESENTATION('',(#137093),#137097); -#137093 = LINE('',#137094,#137095); -#137094 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#137095 = VECTOR('',#137096,1.); -#137096 = DIRECTION('',(-1.,8.881784197001E-016)); -#137097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137098 = PCURVE('',#136990,#137099); -#137099 = DEFINITIONAL_REPRESENTATION('',(#137100),#137104); -#137100 = LINE('',#137101,#137102); -#137101 = CARTESIAN_POINT('',(4.75,5.000038352949E-002)); -#137102 = VECTOR('',#137103,1.); -#137103 = DIRECTION('',(1.,1.1653254136E-048)); -#137104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139459 = DIRECTION('',(0.E+000,0.E+000,1.)); +#139460 = DIRECTION('',(1.,0.E+000,0.E+000)); +#139461 = DEFINITIONAL_REPRESENTATION('',(#139462),#139466); +#139462 = LINE('',#139463,#139464); +#139463 = CARTESIAN_POINT('',(4.85,-3.552713678801E-015)); +#139464 = VECTOR('',#139465,1.); +#139465 = DIRECTION('',(6.725593854929E-015,1.)); +#139466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139467 = PCURVE('',#89918,#139468); +#139468 = DEFINITIONAL_REPRESENTATION('',(#139469),#139473); +#139469 = LINE('',#139470,#139471); +#139470 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#139471 = VECTOR('',#139472,1.); +#139472 = DIRECTION('',(0.E+000,1.)); +#139473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139474 = ORIENTED_EDGE('',*,*,#139475,.T.); +#139475 = EDGE_CURVE('',#139448,#139476,#139478,.T.); +#139476 = VERTEX_POINT('',#139477); +#139477 = CARTESIAN_POINT('',(4.65,11.,-0.208196358798)); +#139478 = SURFACE_CURVE('',#139479,(#139483,#139490),.PCURVE_S1.); +#139479 = LINE('',#139480,#139481); +#139480 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#139481 = VECTOR('',#139482,1.); +#139482 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139483 = PCURVE('',#139456,#139484); +#139484 = DEFINITIONAL_REPRESENTATION('',(#139485),#139489); +#139485 = LINE('',#139486,#139487); +#139486 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#139487 = VECTOR('',#139488,1.); +#139488 = DIRECTION('',(-1.,8.881784197001E-016)); +#139489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139490 = PCURVE('',#139382,#139491); +#139491 = DEFINITIONAL_REPRESENTATION('',(#139492),#139496); +#139492 = LINE('',#139493,#139494); +#139493 = CARTESIAN_POINT('',(4.75,5.000038352949E-002)); +#139494 = VECTOR('',#139495,1.); +#139495 = DIRECTION('',(1.,1.1653254136E-048)); +#139496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137105 = ORIENTED_EDGE('',*,*,#137106,.F.); -#137106 = EDGE_CURVE('',#137107,#137084,#137109,.T.); -#137107 = VERTEX_POINT('',#137108); -#137108 = CARTESIAN_POINT('',(4.65,10.740726081328,-0.208196358798)); -#137109 = SURFACE_CURVE('',#137110,(#137114,#137121),.PCURVE_S1.); -#137110 = LINE('',#137111,#137112); -#137111 = CARTESIAN_POINT('',(4.65,10.740726081328,-0.208196358798)); -#137112 = VECTOR('',#137113,1.); -#137113 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137114 = PCURVE('',#137064,#137115); -#137115 = DEFINITIONAL_REPRESENTATION('',(#137116),#137120); -#137116 = LINE('',#137117,#137118); -#137117 = CARTESIAN_POINT('',(4.65,-3.552713678801E-015)); -#137118 = VECTOR('',#137119,1.); -#137119 = DIRECTION('',(6.725593854929E-015,1.)); -#137120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137121 = PCURVE('',#87580,#137122); -#137122 = DEFINITIONAL_REPRESENTATION('',(#137123),#137127); -#137123 = LINE('',#137124,#137125); -#137124 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#137125 = VECTOR('',#137126,1.); -#137126 = DIRECTION('',(0.E+000,1.)); -#137127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137128 = ORIENTED_EDGE('',*,*,#137129,.T.); -#137129 = EDGE_CURVE('',#137107,#137054,#137130,.T.); -#137130 = SURFACE_CURVE('',#137131,(#137135,#137142),.PCURVE_S1.); -#137131 = LINE('',#137132,#137133); -#137132 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#139497 = ORIENTED_EDGE('',*,*,#139498,.F.); +#139498 = EDGE_CURVE('',#139499,#139476,#139501,.T.); +#139499 = VERTEX_POINT('',#139500); +#139500 = CARTESIAN_POINT('',(4.65,10.740726081328,-0.208196358798)); +#139501 = SURFACE_CURVE('',#139502,(#139506,#139513),.PCURVE_S1.); +#139502 = LINE('',#139503,#139504); +#139503 = CARTESIAN_POINT('',(4.65,10.740726081328,-0.208196358798)); +#139504 = VECTOR('',#139505,1.); +#139505 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#139506 = PCURVE('',#139456,#139507); +#139507 = DEFINITIONAL_REPRESENTATION('',(#139508),#139512); +#139508 = LINE('',#139509,#139510); +#139509 = CARTESIAN_POINT('',(4.65,-3.552713678801E-015)); +#139510 = VECTOR('',#139511,1.); +#139511 = DIRECTION('',(6.725593854929E-015,1.)); +#139512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139513 = PCURVE('',#89972,#139514); +#139514 = DEFINITIONAL_REPRESENTATION('',(#139515),#139519); +#139515 = LINE('',#139516,#139517); +#139516 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#139517 = VECTOR('',#139518,1.); +#139518 = DIRECTION('',(0.E+000,1.)); +#139519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139520 = ORIENTED_EDGE('',*,*,#139521,.T.); +#139521 = EDGE_CURVE('',#139499,#139446,#139522,.T.); +#139522 = SURFACE_CURVE('',#139523,(#139527,#139534),.PCURVE_S1.); +#139523 = LINE('',#139524,#139525); +#139524 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#137133 = VECTOR('',#137134,1.); -#137134 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137135 = PCURVE('',#137064,#137136); -#137136 = DEFINITIONAL_REPRESENTATION('',(#137137),#137141); -#137137 = LINE('',#137138,#137139); -#137138 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137139 = VECTOR('',#137140,1.); -#137140 = DIRECTION('',(1.,-8.881784197001E-016)); -#137141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137142 = PCURVE('',#137143,#137148); -#137143 = CYLINDRICAL_SURFACE('',#137144,0.208574704164); -#137144 = AXIS2_PLACEMENT_3D('',#137145,#137146,#137147); -#137145 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#139525 = VECTOR('',#139526,1.); +#139526 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139527 = PCURVE('',#139456,#139528); +#139528 = DEFINITIONAL_REPRESENTATION('',(#139529),#139533); +#139529 = LINE('',#139530,#139531); +#139530 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139531 = VECTOR('',#139532,1.); +#139532 = DIRECTION('',(1.,-8.881784197001E-016)); +#139533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139534 = PCURVE('',#139535,#139540); +#139535 = CYLINDRICAL_SURFACE('',#139536,0.208574704164); +#139536 = AXIS2_PLACEMENT_3D('',#139537,#139538,#139539); +#139537 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#137146 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137147 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137148 = DEFINITIONAL_REPRESENTATION('',(#137149),#137152); -#137149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137150,#137151), +#139538 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139539 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139540 = DEFINITIONAL_REPRESENTATION('',(#139541),#139544); +#139541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139542,#139543), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#137150 = CARTESIAN_POINT('',(4.772630242227,4.65)); -#137151 = CARTESIAN_POINT('',(4.772630242227,4.85)); -#137152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137153 = ADVANCED_FACE('',(#137154),#137039,.T.); -#137154 = FACE_BOUND('',#137155,.T.); -#137155 = EDGE_LOOP('',(#137156,#137157,#137207,#137234)); -#137156 = ORIENTED_EDGE('',*,*,#137025,.F.); -#137157 = ORIENTED_EDGE('',*,*,#137158,.F.); -#137158 = EDGE_CURVE('',#137159,#137003,#137161,.T.); -#137159 = VERTEX_POINT('',#137160); -#137160 = CARTESIAN_POINT('',(4.85,10.419594812019,0.E+000)); -#137161 = SURFACE_CURVE('',#137162,(#137167,#137196),.PCURVE_S1.); -#137162 = CIRCLE('',#137163,0.308574064194); -#137163 = AXIS2_PLACEMENT_3D('',#137164,#137165,#137166); -#137164 = CARTESIAN_POINT('',(4.85,10.728168876214,2.640924866458E-017) - ); -#137165 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137166 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137167 = PCURVE('',#137039,#137168); -#137168 = DEFINITIONAL_REPRESENTATION('',(#137169),#137195); -#137169 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137170,#137171,#137172, - #137173,#137174,#137175,#137176,#137177,#137178,#137179,#137180, - #137181,#137182,#137183,#137184,#137185,#137186,#137187,#137188, - #137189,#137190,#137191,#137192,#137193,#137194),.UNSPECIFIED.,.F., +#139542 = CARTESIAN_POINT('',(4.772630242227,4.65)); +#139543 = CARTESIAN_POINT('',(4.772630242227,4.85)); +#139544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139545 = ADVANCED_FACE('',(#139546),#139431,.T.); +#139546 = FACE_BOUND('',#139547,.T.); +#139547 = EDGE_LOOP('',(#139548,#139549,#139599,#139626)); +#139548 = ORIENTED_EDGE('',*,*,#139417,.F.); +#139549 = ORIENTED_EDGE('',*,*,#139550,.F.); +#139550 = EDGE_CURVE('',#139551,#139395,#139553,.T.); +#139551 = VERTEX_POINT('',#139552); +#139552 = CARTESIAN_POINT('',(4.85,10.419594812019,0.E+000)); +#139553 = SURFACE_CURVE('',#139554,(#139559,#139588),.PCURVE_S1.); +#139554 = CIRCLE('',#139555,0.308574064194); +#139555 = AXIS2_PLACEMENT_3D('',#139556,#139557,#139558); +#139556 = CARTESIAN_POINT('',(4.85,10.728168876214,2.640924866458E-017) + ); +#139557 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139558 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139559 = PCURVE('',#139431,#139560); +#139560 = DEFINITIONAL_REPRESENTATION('',(#139561),#139587); +#139561 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139562,#139563,#139564, + #139565,#139566,#139567,#139568,#139569,#139570,#139571,#139572, + #139573,#139574,#139575,#139576,#139577,#139578,#139579,#139580, + #139581,#139582,#139583,#139584,#139585,#139586),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -169045,102 +172047,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#137170 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#137171 = CARTESIAN_POINT('',(3.166141578807,4.85)); -#137172 = CARTESIAN_POINT('',(3.215239429242,4.85)); -#137173 = CARTESIAN_POINT('',(3.288886204895,4.85)); -#137174 = CARTESIAN_POINT('',(3.362532980548,4.85)); -#137175 = CARTESIAN_POINT('',(3.4361797562,4.85)); -#137176 = CARTESIAN_POINT('',(3.509826531853,4.85)); -#137177 = CARTESIAN_POINT('',(3.583473307505,4.85)); -#137178 = CARTESIAN_POINT('',(3.657120083158,4.85)); -#137179 = CARTESIAN_POINT('',(3.730766858811,4.85)); -#137180 = CARTESIAN_POINT('',(3.804413634463,4.85)); -#137181 = CARTESIAN_POINT('',(3.878060410116,4.85)); -#137182 = CARTESIAN_POINT('',(3.951707185768,4.85)); -#137183 = CARTESIAN_POINT('',(4.025353961421,4.85)); -#137184 = CARTESIAN_POINT('',(4.099000737074,4.85)); -#137185 = CARTESIAN_POINT('',(4.172647512726,4.85)); -#137186 = CARTESIAN_POINT('',(4.246294288379,4.85)); -#137187 = CARTESIAN_POINT('',(4.319941064031,4.85)); -#137188 = CARTESIAN_POINT('',(4.393587839684,4.85)); -#137189 = CARTESIAN_POINT('',(4.467234615337,4.85)); -#137190 = CARTESIAN_POINT('',(4.540881390989,4.85)); -#137191 = CARTESIAN_POINT('',(4.614528166642,4.85)); -#137192 = CARTESIAN_POINT('',(4.688174942294,4.85)); -#137193 = CARTESIAN_POINT('',(4.737272792729,4.85)); -#137194 = CARTESIAN_POINT('',(4.761821717947,4.85)); -#137195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137196 = PCURVE('',#87526,#137197); -#137197 = DEFINITIONAL_REPRESENTATION('',(#137198),#137206); -#137198 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137199,#137200,#137201, - #137202,#137203,#137204,#137205),.UNSPECIFIED.,.T.,.F.) +#139562 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#139563 = CARTESIAN_POINT('',(3.166141578807,4.85)); +#139564 = CARTESIAN_POINT('',(3.215239429242,4.85)); +#139565 = CARTESIAN_POINT('',(3.288886204895,4.85)); +#139566 = CARTESIAN_POINT('',(3.362532980548,4.85)); +#139567 = CARTESIAN_POINT('',(3.4361797562,4.85)); +#139568 = CARTESIAN_POINT('',(3.509826531853,4.85)); +#139569 = CARTESIAN_POINT('',(3.583473307505,4.85)); +#139570 = CARTESIAN_POINT('',(3.657120083158,4.85)); +#139571 = CARTESIAN_POINT('',(3.730766858811,4.85)); +#139572 = CARTESIAN_POINT('',(3.804413634463,4.85)); +#139573 = CARTESIAN_POINT('',(3.878060410116,4.85)); +#139574 = CARTESIAN_POINT('',(3.951707185768,4.85)); +#139575 = CARTESIAN_POINT('',(4.025353961421,4.85)); +#139576 = CARTESIAN_POINT('',(4.099000737074,4.85)); +#139577 = CARTESIAN_POINT('',(4.172647512726,4.85)); +#139578 = CARTESIAN_POINT('',(4.246294288379,4.85)); +#139579 = CARTESIAN_POINT('',(4.319941064031,4.85)); +#139580 = CARTESIAN_POINT('',(4.393587839684,4.85)); +#139581 = CARTESIAN_POINT('',(4.467234615337,4.85)); +#139582 = CARTESIAN_POINT('',(4.540881390989,4.85)); +#139583 = CARTESIAN_POINT('',(4.614528166642,4.85)); +#139584 = CARTESIAN_POINT('',(4.688174942294,4.85)); +#139585 = CARTESIAN_POINT('',(4.737272792729,4.85)); +#139586 = CARTESIAN_POINT('',(4.761821717947,4.85)); +#139587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139588 = PCURVE('',#89918,#139589); +#139589 = DEFINITIONAL_REPRESENTATION('',(#139590),#139598); +#139590 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139591,#139592,#139593, + #139594,#139595,#139596,#139597),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#137199 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#137200 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#137201 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#137202 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#137203 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#137204 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#137205 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#137206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137207 = ORIENTED_EDGE('',*,*,#137208,.F.); -#137208 = EDGE_CURVE('',#137209,#137159,#137211,.T.); -#137209 = VERTEX_POINT('',#137210); -#137210 = CARTESIAN_POINT('',(4.65,10.419594812019,0.E+000)); -#137211 = SURFACE_CURVE('',#137212,(#137216,#137222),.PCURVE_S1.); -#137212 = LINE('',#137213,#137214); -#137213 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#139591 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#139592 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#139593 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#139594 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#139595 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#139596 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#139597 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#139598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139599 = ORIENTED_EDGE('',*,*,#139600,.F.); +#139600 = EDGE_CURVE('',#139601,#139551,#139603,.T.); +#139601 = VERTEX_POINT('',#139602); +#139602 = CARTESIAN_POINT('',(4.65,10.419594812019,0.E+000)); +#139603 = SURFACE_CURVE('',#139604,(#139608,#139614),.PCURVE_S1.); +#139604 = LINE('',#139605,#139606); +#139605 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#137214 = VECTOR('',#137215,1.); -#137215 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137216 = PCURVE('',#137039,#137217); -#137217 = DEFINITIONAL_REPRESENTATION('',(#137218),#137221); -#137218 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137219,#137220), +#139606 = VECTOR('',#139607,1.); +#139607 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139608 = PCURVE('',#139431,#139609); +#139609 = DEFINITIONAL_REPRESENTATION('',(#139610),#139613); +#139610 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139611,#139612), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#137219 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#137220 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#137221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139611 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#139612 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#139613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137222 = PCURVE('',#137223,#137228); -#137223 = PLANE('',#137224); -#137224 = AXIS2_PLACEMENT_3D('',#137225,#137226,#137227); -#137225 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#139614 = PCURVE('',#139615,#139620); +#139615 = PLANE('',#139616); +#139616 = AXIS2_PLACEMENT_3D('',#139617,#139618,#139619); +#139617 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#137226 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137227 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137228 = DEFINITIONAL_REPRESENTATION('',(#137229),#137233); -#137229 = LINE('',#137230,#137231); -#137230 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#137231 = VECTOR('',#137232,1.); -#137232 = DIRECTION('',(-1.,0.E+000)); -#137233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137234 = ORIENTED_EDGE('',*,*,#137235,.T.); -#137235 = EDGE_CURVE('',#137209,#136945,#137236,.T.); -#137236 = SURFACE_CURVE('',#137237,(#137242,#137271),.PCURVE_S1.); -#137237 = CIRCLE('',#137238,0.308574064194); -#137238 = AXIS2_PLACEMENT_3D('',#137239,#137240,#137241); -#137239 = CARTESIAN_POINT('',(4.65,10.728168876214,2.640924866458E-017) - ); -#137240 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137241 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137242 = PCURVE('',#137039,#137243); -#137243 = DEFINITIONAL_REPRESENTATION('',(#137244),#137270); -#137244 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137245,#137246,#137247, - #137248,#137249,#137250,#137251,#137252,#137253,#137254,#137255, - #137256,#137257,#137258,#137259,#137260,#137261,#137262,#137263, - #137264,#137265,#137266,#137267,#137268,#137269),.UNSPECIFIED.,.F., +#139618 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139619 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139620 = DEFINITIONAL_REPRESENTATION('',(#139621),#139625); +#139621 = LINE('',#139622,#139623); +#139622 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#139623 = VECTOR('',#139624,1.); +#139624 = DIRECTION('',(-1.,0.E+000)); +#139625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139626 = ORIENTED_EDGE('',*,*,#139627,.T.); +#139627 = EDGE_CURVE('',#139601,#139337,#139628,.T.); +#139628 = SURFACE_CURVE('',#139629,(#139634,#139663),.PCURVE_S1.); +#139629 = CIRCLE('',#139630,0.308574064194); +#139630 = AXIS2_PLACEMENT_3D('',#139631,#139632,#139633); +#139631 = CARTESIAN_POINT('',(4.65,10.728168876214,2.640924866458E-017) + ); +#139632 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139633 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139634 = PCURVE('',#139431,#139635); +#139635 = DEFINITIONAL_REPRESENTATION('',(#139636),#139662); +#139636 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139637,#139638,#139639, + #139640,#139641,#139642,#139643,#139644,#139645,#139646,#139647, + #139648,#139649,#139650,#139651,#139652,#139653,#139654,#139655, + #139656,#139657,#139658,#139659,#139660,#139661),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -169148,445 +172150,445 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#137245 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#137246 = CARTESIAN_POINT('',(3.166141578807,4.65)); -#137247 = CARTESIAN_POINT('',(3.215239429242,4.65)); -#137248 = CARTESIAN_POINT('',(3.288886204895,4.65)); -#137249 = CARTESIAN_POINT('',(3.362532980548,4.65)); -#137250 = CARTESIAN_POINT('',(3.4361797562,4.65)); -#137251 = CARTESIAN_POINT('',(3.509826531853,4.65)); -#137252 = CARTESIAN_POINT('',(3.583473307505,4.65)); -#137253 = CARTESIAN_POINT('',(3.657120083158,4.65)); -#137254 = CARTESIAN_POINT('',(3.730766858811,4.65)); -#137255 = CARTESIAN_POINT('',(3.804413634463,4.65)); -#137256 = CARTESIAN_POINT('',(3.878060410116,4.65)); -#137257 = CARTESIAN_POINT('',(3.951707185768,4.65)); -#137258 = CARTESIAN_POINT('',(4.025353961421,4.65)); -#137259 = CARTESIAN_POINT('',(4.099000737074,4.65)); -#137260 = CARTESIAN_POINT('',(4.172647512726,4.65)); -#137261 = CARTESIAN_POINT('',(4.246294288379,4.65)); -#137262 = CARTESIAN_POINT('',(4.319941064031,4.65)); -#137263 = CARTESIAN_POINT('',(4.393587839684,4.65)); -#137264 = CARTESIAN_POINT('',(4.467234615337,4.65)); -#137265 = CARTESIAN_POINT('',(4.540881390989,4.65)); -#137266 = CARTESIAN_POINT('',(4.614528166642,4.65)); -#137267 = CARTESIAN_POINT('',(4.688174942294,4.65)); -#137268 = CARTESIAN_POINT('',(4.737272792729,4.65)); -#137269 = CARTESIAN_POINT('',(4.761821717947,4.65)); -#137270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137271 = PCURVE('',#87580,#137272); -#137272 = DEFINITIONAL_REPRESENTATION('',(#137273),#137277); -#137273 = CIRCLE('',#137274,0.308574064194); -#137274 = AXIS2_PLACEMENT_2D('',#137275,#137276); -#137275 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#137276 = DIRECTION('',(0.E+000,1.)); -#137277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137278 = ADVANCED_FACE('',(#137279),#137143,.F.); -#137279 = FACE_BOUND('',#137280,.F.); -#137280 = EDGE_LOOP('',(#137281,#137282,#137309,#137336)); -#137281 = ORIENTED_EDGE('',*,*,#137129,.T.); -#137282 = ORIENTED_EDGE('',*,*,#137283,.F.); -#137283 = EDGE_CURVE('',#137284,#137054,#137286,.T.); -#137284 = VERTEX_POINT('',#137285); -#137285 = CARTESIAN_POINT('',(4.85,10.51959417205,0.E+000)); -#137286 = SURFACE_CURVE('',#137287,(#137292,#137298),.PCURVE_S1.); -#137287 = CIRCLE('',#137288,0.208574704164); -#137288 = AXIS2_PLACEMENT_3D('',#137289,#137290,#137291); -#137289 = CARTESIAN_POINT('',(4.85,10.728168876214,2.640924866458E-017) - ); -#137290 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137291 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137292 = PCURVE('',#137143,#137293); -#137293 = DEFINITIONAL_REPRESENTATION('',(#137294),#137297); -#137294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137295,#137296), +#139637 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#139638 = CARTESIAN_POINT('',(3.166141578807,4.65)); +#139639 = CARTESIAN_POINT('',(3.215239429242,4.65)); +#139640 = CARTESIAN_POINT('',(3.288886204895,4.65)); +#139641 = CARTESIAN_POINT('',(3.362532980548,4.65)); +#139642 = CARTESIAN_POINT('',(3.4361797562,4.65)); +#139643 = CARTESIAN_POINT('',(3.509826531853,4.65)); +#139644 = CARTESIAN_POINT('',(3.583473307505,4.65)); +#139645 = CARTESIAN_POINT('',(3.657120083158,4.65)); +#139646 = CARTESIAN_POINT('',(3.730766858811,4.65)); +#139647 = CARTESIAN_POINT('',(3.804413634463,4.65)); +#139648 = CARTESIAN_POINT('',(3.878060410116,4.65)); +#139649 = CARTESIAN_POINT('',(3.951707185768,4.65)); +#139650 = CARTESIAN_POINT('',(4.025353961421,4.65)); +#139651 = CARTESIAN_POINT('',(4.099000737074,4.65)); +#139652 = CARTESIAN_POINT('',(4.172647512726,4.65)); +#139653 = CARTESIAN_POINT('',(4.246294288379,4.65)); +#139654 = CARTESIAN_POINT('',(4.319941064031,4.65)); +#139655 = CARTESIAN_POINT('',(4.393587839684,4.65)); +#139656 = CARTESIAN_POINT('',(4.467234615337,4.65)); +#139657 = CARTESIAN_POINT('',(4.540881390989,4.65)); +#139658 = CARTESIAN_POINT('',(4.614528166642,4.65)); +#139659 = CARTESIAN_POINT('',(4.688174942294,4.65)); +#139660 = CARTESIAN_POINT('',(4.737272792729,4.65)); +#139661 = CARTESIAN_POINT('',(4.761821717947,4.65)); +#139662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139663 = PCURVE('',#89972,#139664); +#139664 = DEFINITIONAL_REPRESENTATION('',(#139665),#139669); +#139665 = CIRCLE('',#139666,0.308574064194); +#139666 = AXIS2_PLACEMENT_2D('',#139667,#139668); +#139667 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#139668 = DIRECTION('',(0.E+000,1.)); +#139669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139670 = ADVANCED_FACE('',(#139671),#139535,.F.); +#139671 = FACE_BOUND('',#139672,.F.); +#139672 = EDGE_LOOP('',(#139673,#139674,#139701,#139728)); +#139673 = ORIENTED_EDGE('',*,*,#139521,.T.); +#139674 = ORIENTED_EDGE('',*,*,#139675,.F.); +#139675 = EDGE_CURVE('',#139676,#139446,#139678,.T.); +#139676 = VERTEX_POINT('',#139677); +#139677 = CARTESIAN_POINT('',(4.85,10.51959417205,0.E+000)); +#139678 = SURFACE_CURVE('',#139679,(#139684,#139690),.PCURVE_S1.); +#139679 = CIRCLE('',#139680,0.208574704164); +#139680 = AXIS2_PLACEMENT_3D('',#139681,#139682,#139683); +#139681 = CARTESIAN_POINT('',(4.85,10.728168876214,2.640924866458E-017) + ); +#139682 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139683 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139684 = PCURVE('',#139535,#139685); +#139685 = DEFINITIONAL_REPRESENTATION('',(#139686),#139689); +#139686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139687,#139688), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#137295 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#137296 = CARTESIAN_POINT('',(4.772630242227,4.85)); -#137297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139687 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#139688 = CARTESIAN_POINT('',(4.772630242227,4.85)); +#139689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137298 = PCURVE('',#87526,#137299); -#137299 = DEFINITIONAL_REPRESENTATION('',(#137300),#137308); -#137300 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137301,#137302,#137303, - #137304,#137305,#137306,#137307),.UNSPECIFIED.,.T.,.F.) +#139690 = PCURVE('',#89918,#139691); +#139691 = DEFINITIONAL_REPRESENTATION('',(#139692),#139700); +#139692 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139693,#139694,#139695, + #139696,#139697,#139698,#139699),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#137301 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#137302 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#137303 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#137304 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#137305 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#137306 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#137307 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#137308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137309 = ORIENTED_EDGE('',*,*,#137310,.T.); -#137310 = EDGE_CURVE('',#137284,#137311,#137313,.T.); -#137311 = VERTEX_POINT('',#137312); -#137312 = CARTESIAN_POINT('',(4.65,10.51959417205,0.E+000)); -#137313 = SURFACE_CURVE('',#137314,(#137318,#137324),.PCURVE_S1.); -#137314 = LINE('',#137315,#137316); -#137315 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#139693 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#139694 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#139695 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#139696 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#139697 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#139698 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#139699 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#139700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139701 = ORIENTED_EDGE('',*,*,#139702,.T.); +#139702 = EDGE_CURVE('',#139676,#139703,#139705,.T.); +#139703 = VERTEX_POINT('',#139704); +#139704 = CARTESIAN_POINT('',(4.65,10.51959417205,0.E+000)); +#139705 = SURFACE_CURVE('',#139706,(#139710,#139716),.PCURVE_S1.); +#139706 = LINE('',#139707,#139708); +#139707 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#137316 = VECTOR('',#137317,1.); -#137317 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137318 = PCURVE('',#137143,#137319); -#137319 = DEFINITIONAL_REPRESENTATION('',(#137320),#137323); -#137320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137321,#137322), +#139708 = VECTOR('',#139709,1.); +#139709 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139710 = PCURVE('',#139535,#139711); +#139711 = DEFINITIONAL_REPRESENTATION('',(#139712),#139715); +#139712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139713,#139714), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#137321 = CARTESIAN_POINT('',(3.14159265359,4.85)); -#137322 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#137323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139713 = CARTESIAN_POINT('',(3.14159265359,4.85)); +#139714 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#139715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137324 = PCURVE('',#137325,#137330); -#137325 = PLANE('',#137326); -#137326 = AXIS2_PLACEMENT_3D('',#137327,#137328,#137329); -#137327 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#139716 = PCURVE('',#139717,#139722); +#139717 = PLANE('',#139718); +#139718 = AXIS2_PLACEMENT_3D('',#139719,#139720,#139721); +#139719 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#137328 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137329 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137330 = DEFINITIONAL_REPRESENTATION('',(#137331),#137335); -#137331 = LINE('',#137332,#137333); -#137332 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#137333 = VECTOR('',#137334,1.); -#137334 = DIRECTION('',(-1.,0.E+000)); -#137335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139720 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139721 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139722 = DEFINITIONAL_REPRESENTATION('',(#139723),#139727); +#139723 = LINE('',#139724,#139725); +#139724 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#139725 = VECTOR('',#139726,1.); +#139726 = DIRECTION('',(-1.,0.E+000)); +#139727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137336 = ORIENTED_EDGE('',*,*,#137337,.T.); -#137337 = EDGE_CURVE('',#137311,#137107,#137338,.T.); -#137338 = SURFACE_CURVE('',#137339,(#137344,#137350),.PCURVE_S1.); -#137339 = CIRCLE('',#137340,0.208574704164); -#137340 = AXIS2_PLACEMENT_3D('',#137341,#137342,#137343); -#137341 = CARTESIAN_POINT('',(4.65,10.728168876214,2.640924866458E-017) +#139728 = ORIENTED_EDGE('',*,*,#139729,.T.); +#139729 = EDGE_CURVE('',#139703,#139499,#139730,.T.); +#139730 = SURFACE_CURVE('',#139731,(#139736,#139742),.PCURVE_S1.); +#139731 = CIRCLE('',#139732,0.208574704164); +#139732 = AXIS2_PLACEMENT_3D('',#139733,#139734,#139735); +#139733 = CARTESIAN_POINT('',(4.65,10.728168876214,2.640924866458E-017) ); -#137342 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137343 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137344 = PCURVE('',#137143,#137345); -#137345 = DEFINITIONAL_REPRESENTATION('',(#137346),#137349); -#137346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137347,#137348), +#139734 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139735 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#139736 = PCURVE('',#139535,#139737); +#139737 = DEFINITIONAL_REPRESENTATION('',(#139738),#139741); +#139738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139739,#139740), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#137347 = CARTESIAN_POINT('',(3.14159265359,4.65)); -#137348 = CARTESIAN_POINT('',(4.772630242227,4.65)); -#137349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139739 = CARTESIAN_POINT('',(3.14159265359,4.65)); +#139740 = CARTESIAN_POINT('',(4.772630242227,4.65)); +#139741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137350 = PCURVE('',#87580,#137351); -#137351 = DEFINITIONAL_REPRESENTATION('',(#137352),#137356); -#137352 = CIRCLE('',#137353,0.208574704164); -#137353 = AXIS2_PLACEMENT_2D('',#137354,#137355); -#137354 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#137355 = DIRECTION('',(0.E+000,1.)); -#137356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137357 = ADVANCED_FACE('',(#137358),#137325,.F.); -#137358 = FACE_BOUND('',#137359,.T.); -#137359 = EDGE_LOOP('',(#137360,#137389,#137410,#137411)); -#137360 = ORIENTED_EDGE('',*,*,#137361,.F.); -#137361 = EDGE_CURVE('',#137362,#137364,#137366,.T.); -#137362 = VERTEX_POINT('',#137363); -#137363 = CARTESIAN_POINT('',(4.85,10.51959417205,0.530776333563)); -#137364 = VERTEX_POINT('',#137365); -#137365 = CARTESIAN_POINT('',(4.65,10.51959417205,0.530776333563)); -#137366 = SURFACE_CURVE('',#137367,(#137371,#137378),.PCURVE_S1.); -#137367 = LINE('',#137368,#137369); -#137368 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#139742 = PCURVE('',#89972,#139743); +#139743 = DEFINITIONAL_REPRESENTATION('',(#139744),#139748); +#139744 = CIRCLE('',#139745,0.208574704164); +#139745 = AXIS2_PLACEMENT_2D('',#139746,#139747); +#139746 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#139747 = DIRECTION('',(0.E+000,1.)); +#139748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139749 = ADVANCED_FACE('',(#139750),#139717,.F.); +#139750 = FACE_BOUND('',#139751,.T.); +#139751 = EDGE_LOOP('',(#139752,#139781,#139802,#139803)); +#139752 = ORIENTED_EDGE('',*,*,#139753,.F.); +#139753 = EDGE_CURVE('',#139754,#139756,#139758,.T.); +#139754 = VERTEX_POINT('',#139755); +#139755 = CARTESIAN_POINT('',(4.85,10.51959417205,0.530776333563)); +#139756 = VERTEX_POINT('',#139757); +#139757 = CARTESIAN_POINT('',(4.65,10.51959417205,0.530776333563)); +#139758 = SURFACE_CURVE('',#139759,(#139763,#139770),.PCURVE_S1.); +#139759 = LINE('',#139760,#139761); +#139760 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#137369 = VECTOR('',#137370,1.); -#137370 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137371 = PCURVE('',#137325,#137372); -#137372 = DEFINITIONAL_REPRESENTATION('',(#137373),#137377); -#137373 = LINE('',#137374,#137375); -#137374 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137375 = VECTOR('',#137376,1.); -#137376 = DIRECTION('',(-1.,0.E+000)); -#137377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137378 = PCURVE('',#137379,#137384); -#137379 = CYLINDRICAL_SURFACE('',#137380,0.2192697516); -#137380 = AXIS2_PLACEMENT_3D('',#137381,#137382,#137383); -#137381 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#139761 = VECTOR('',#139762,1.); +#139762 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139763 = PCURVE('',#139717,#139764); +#139764 = DEFINITIONAL_REPRESENTATION('',(#139765),#139769); +#139765 = LINE('',#139766,#139767); +#139766 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139767 = VECTOR('',#139768,1.); +#139768 = DIRECTION('',(-1.,0.E+000)); +#139769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139770 = PCURVE('',#139771,#139776); +#139771 = CYLINDRICAL_SURFACE('',#139772,0.2192697516); +#139772 = AXIS2_PLACEMENT_3D('',#139773,#139774,#139775); +#139773 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#137382 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137383 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137384 = DEFINITIONAL_REPRESENTATION('',(#137385),#137388); -#137385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137386,#137387), +#139774 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139775 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139776 = DEFINITIONAL_REPRESENTATION('',(#139777),#139780); +#139777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139778,#139779), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.85,-4.65),.PIECEWISE_BEZIER_KNOTS.); -#137386 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#137387 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#137388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137389 = ORIENTED_EDGE('',*,*,#137390,.T.); -#137390 = EDGE_CURVE('',#137362,#137284,#137391,.T.); -#137391 = SURFACE_CURVE('',#137392,(#137396,#137403),.PCURVE_S1.); -#137392 = LINE('',#137393,#137394); -#137393 = CARTESIAN_POINT('',(4.85,10.51959417205,0.530776333563)); -#137394 = VECTOR('',#137395,1.); -#137395 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#137396 = PCURVE('',#137325,#137397); -#137397 = DEFINITIONAL_REPRESENTATION('',(#137398),#137402); -#137398 = LINE('',#137399,#137400); -#137399 = CARTESIAN_POINT('',(4.85,0.E+000)); -#137400 = VECTOR('',#137401,1.); -#137401 = DIRECTION('',(0.E+000,-1.)); -#137402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137403 = PCURVE('',#87526,#137404); -#137404 = DEFINITIONAL_REPRESENTATION('',(#137405),#137409); -#137405 = LINE('',#137406,#137407); -#137406 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#137407 = VECTOR('',#137408,1.); -#137408 = DIRECTION('',(-1.,0.E+000)); -#137409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139778 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#139779 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#139780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139781 = ORIENTED_EDGE('',*,*,#139782,.T.); +#139782 = EDGE_CURVE('',#139754,#139676,#139783,.T.); +#139783 = SURFACE_CURVE('',#139784,(#139788,#139795),.PCURVE_S1.); +#139784 = LINE('',#139785,#139786); +#139785 = CARTESIAN_POINT('',(4.85,10.51959417205,0.530776333563)); +#139786 = VECTOR('',#139787,1.); +#139787 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#139788 = PCURVE('',#139717,#139789); +#139789 = DEFINITIONAL_REPRESENTATION('',(#139790),#139794); +#139790 = LINE('',#139791,#139792); +#139791 = CARTESIAN_POINT('',(4.85,0.E+000)); +#139792 = VECTOR('',#139793,1.); +#139793 = DIRECTION('',(0.E+000,-1.)); +#139794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139795 = PCURVE('',#89918,#139796); +#139796 = DEFINITIONAL_REPRESENTATION('',(#139797),#139801); +#139797 = LINE('',#139798,#139799); +#139798 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#139799 = VECTOR('',#139800,1.); +#139800 = DIRECTION('',(-1.,0.E+000)); +#139801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137410 = ORIENTED_EDGE('',*,*,#137310,.T.); -#137411 = ORIENTED_EDGE('',*,*,#137412,.F.); -#137412 = EDGE_CURVE('',#137364,#137311,#137413,.T.); -#137413 = SURFACE_CURVE('',#137414,(#137418,#137425),.PCURVE_S1.); -#137414 = LINE('',#137415,#137416); -#137415 = CARTESIAN_POINT('',(4.65,10.51959417205,0.530776333563)); -#137416 = VECTOR('',#137417,1.); -#137417 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#137418 = PCURVE('',#137325,#137419); -#137419 = DEFINITIONAL_REPRESENTATION('',(#137420),#137424); -#137420 = LINE('',#137421,#137422); -#137421 = CARTESIAN_POINT('',(4.65,0.E+000)); -#137422 = VECTOR('',#137423,1.); -#137423 = DIRECTION('',(0.E+000,-1.)); -#137424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137425 = PCURVE('',#87580,#137426); -#137426 = DEFINITIONAL_REPRESENTATION('',(#137427),#137431); -#137427 = LINE('',#137428,#137429); -#137428 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#137429 = VECTOR('',#137430,1.); -#137430 = DIRECTION('',(1.,0.E+000)); -#137431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137432 = ADVANCED_FACE('',(#137433),#137223,.F.); -#137433 = FACE_BOUND('',#137434,.T.); -#137434 = EDGE_LOOP('',(#137435,#137464,#137485,#137486)); -#137435 = ORIENTED_EDGE('',*,*,#137436,.F.); -#137436 = EDGE_CURVE('',#137437,#137439,#137441,.T.); -#137437 = VERTEX_POINT('',#137438); -#137438 = CARTESIAN_POINT('',(4.65,10.419594812019,0.530776333563)); -#137439 = VERTEX_POINT('',#137440); -#137440 = CARTESIAN_POINT('',(4.85,10.419594812019,0.530776333563)); -#137441 = SURFACE_CURVE('',#137442,(#137446,#137453),.PCURVE_S1.); -#137442 = LINE('',#137443,#137444); -#137443 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#139802 = ORIENTED_EDGE('',*,*,#139702,.T.); +#139803 = ORIENTED_EDGE('',*,*,#139804,.F.); +#139804 = EDGE_CURVE('',#139756,#139703,#139805,.T.); +#139805 = SURFACE_CURVE('',#139806,(#139810,#139817),.PCURVE_S1.); +#139806 = LINE('',#139807,#139808); +#139807 = CARTESIAN_POINT('',(4.65,10.51959417205,0.530776333563)); +#139808 = VECTOR('',#139809,1.); +#139809 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#139810 = PCURVE('',#139717,#139811); +#139811 = DEFINITIONAL_REPRESENTATION('',(#139812),#139816); +#139812 = LINE('',#139813,#139814); +#139813 = CARTESIAN_POINT('',(4.65,0.E+000)); +#139814 = VECTOR('',#139815,1.); +#139815 = DIRECTION('',(0.E+000,-1.)); +#139816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139817 = PCURVE('',#89972,#139818); +#139818 = DEFINITIONAL_REPRESENTATION('',(#139819),#139823); +#139819 = LINE('',#139820,#139821); +#139820 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#139821 = VECTOR('',#139822,1.); +#139822 = DIRECTION('',(1.,0.E+000)); +#139823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139824 = ADVANCED_FACE('',(#139825),#139615,.F.); +#139825 = FACE_BOUND('',#139826,.T.); +#139826 = EDGE_LOOP('',(#139827,#139856,#139877,#139878)); +#139827 = ORIENTED_EDGE('',*,*,#139828,.F.); +#139828 = EDGE_CURVE('',#139829,#139831,#139833,.T.); +#139829 = VERTEX_POINT('',#139830); +#139830 = CARTESIAN_POINT('',(4.65,10.419594812019,0.530776333563)); +#139831 = VERTEX_POINT('',#139832); +#139832 = CARTESIAN_POINT('',(4.85,10.419594812019,0.530776333563)); +#139833 = SURFACE_CURVE('',#139834,(#139838,#139845),.PCURVE_S1.); +#139834 = LINE('',#139835,#139836); +#139835 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#137444 = VECTOR('',#137445,1.); -#137445 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137446 = PCURVE('',#137223,#137447); -#137447 = DEFINITIONAL_REPRESENTATION('',(#137448),#137452); -#137448 = LINE('',#137449,#137450); -#137449 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137450 = VECTOR('',#137451,1.); -#137451 = DIRECTION('',(-1.,0.E+000)); -#137452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137453 = PCURVE('',#137454,#137459); -#137454 = CYLINDRICAL_SURFACE('',#137455,0.119270391569); -#137455 = AXIS2_PLACEMENT_3D('',#137456,#137457,#137458); -#137456 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#139836 = VECTOR('',#139837,1.); +#139837 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#139838 = PCURVE('',#139615,#139839); +#139839 = DEFINITIONAL_REPRESENTATION('',(#139840),#139844); +#139840 = LINE('',#139841,#139842); +#139841 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#139842 = VECTOR('',#139843,1.); +#139843 = DIRECTION('',(-1.,0.E+000)); +#139844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139845 = PCURVE('',#139846,#139851); +#139846 = CYLINDRICAL_SURFACE('',#139847,0.119270391569); +#139847 = AXIS2_PLACEMENT_3D('',#139848,#139849,#139850); +#139848 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#137457 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137458 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137459 = DEFINITIONAL_REPRESENTATION('',(#137460),#137463); -#137460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137461,#137462), +#139849 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139850 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139851 = DEFINITIONAL_REPRESENTATION('',(#139852),#139855); +#139852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139853,#139854), .UNSPECIFIED.,.F.,.F.,(2,2),(4.65,4.85),.PIECEWISE_BEZIER_KNOTS.); -#137461 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#137462 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#137463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137464 = ORIENTED_EDGE('',*,*,#137465,.T.); -#137465 = EDGE_CURVE('',#137437,#137209,#137466,.T.); -#137466 = SURFACE_CURVE('',#137467,(#137471,#137478),.PCURVE_S1.); -#137467 = LINE('',#137468,#137469); -#137468 = CARTESIAN_POINT('',(4.65,10.419594812019,0.530776333563)); -#137469 = VECTOR('',#137470,1.); -#137470 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#137471 = PCURVE('',#137223,#137472); -#137472 = DEFINITIONAL_REPRESENTATION('',(#137473),#137477); -#137473 = LINE('',#137474,#137475); -#137474 = CARTESIAN_POINT('',(-4.65,0.E+000)); -#137475 = VECTOR('',#137476,1.); -#137476 = DIRECTION('',(0.E+000,-1.)); -#137477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137478 = PCURVE('',#87580,#137479); -#137479 = DEFINITIONAL_REPRESENTATION('',(#137480),#137484); -#137480 = LINE('',#137481,#137482); -#137481 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#137482 = VECTOR('',#137483,1.); -#137483 = DIRECTION('',(1.,0.E+000)); -#137484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137485 = ORIENTED_EDGE('',*,*,#137208,.T.); -#137486 = ORIENTED_EDGE('',*,*,#137487,.F.); -#137487 = EDGE_CURVE('',#137439,#137159,#137488,.T.); -#137488 = SURFACE_CURVE('',#137489,(#137493,#137500),.PCURVE_S1.); -#137489 = LINE('',#137490,#137491); -#137490 = CARTESIAN_POINT('',(4.85,10.419594812019,0.530776333563)); -#137491 = VECTOR('',#137492,1.); -#137492 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#137493 = PCURVE('',#137223,#137494); -#137494 = DEFINITIONAL_REPRESENTATION('',(#137495),#137499); -#137495 = LINE('',#137496,#137497); -#137496 = CARTESIAN_POINT('',(-4.85,0.E+000)); -#137497 = VECTOR('',#137498,1.); -#137498 = DIRECTION('',(0.E+000,-1.)); -#137499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137500 = PCURVE('',#87526,#137501); -#137501 = DEFINITIONAL_REPRESENTATION('',(#137502),#137506); -#137502 = LINE('',#137503,#137504); -#137503 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#137504 = VECTOR('',#137505,1.); -#137505 = DIRECTION('',(-1.,0.E+000)); -#137506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137507 = ADVANCED_FACE('',(#137508),#137454,.F.); -#137508 = FACE_BOUND('',#137509,.F.); -#137509 = EDGE_LOOP('',(#137510,#137537,#137559,#137580)); -#137510 = ORIENTED_EDGE('',*,*,#137511,.F.); -#137511 = EDGE_CURVE('',#137512,#137437,#137514,.T.); -#137512 = VERTEX_POINT('',#137513); -#137513 = CARTESIAN_POINT('',(4.65,10.303662633502,0.65)); -#137514 = SURFACE_CURVE('',#137515,(#137520,#137526),.PCURVE_S1.); -#137515 = CIRCLE('',#137516,0.119270391569); -#137516 = AXIS2_PLACEMENT_3D('',#137517,#137518,#137519); -#137517 = CARTESIAN_POINT('',(4.65,10.30032442045,0.530776333563)); -#137518 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137519 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137520 = PCURVE('',#137454,#137521); -#137521 = DEFINITIONAL_REPRESENTATION('',(#137522),#137525); -#137522 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137523,#137524), +#139853 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#139854 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#139855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139856 = ORIENTED_EDGE('',*,*,#139857,.T.); +#139857 = EDGE_CURVE('',#139829,#139601,#139858,.T.); +#139858 = SURFACE_CURVE('',#139859,(#139863,#139870),.PCURVE_S1.); +#139859 = LINE('',#139860,#139861); +#139860 = CARTESIAN_POINT('',(4.65,10.419594812019,0.530776333563)); +#139861 = VECTOR('',#139862,1.); +#139862 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#139863 = PCURVE('',#139615,#139864); +#139864 = DEFINITIONAL_REPRESENTATION('',(#139865),#139869); +#139865 = LINE('',#139866,#139867); +#139866 = CARTESIAN_POINT('',(-4.65,0.E+000)); +#139867 = VECTOR('',#139868,1.); +#139868 = DIRECTION('',(0.E+000,-1.)); +#139869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139870 = PCURVE('',#89972,#139871); +#139871 = DEFINITIONAL_REPRESENTATION('',(#139872),#139876); +#139872 = LINE('',#139873,#139874); +#139873 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#139874 = VECTOR('',#139875,1.); +#139875 = DIRECTION('',(1.,0.E+000)); +#139876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139877 = ORIENTED_EDGE('',*,*,#139600,.T.); +#139878 = ORIENTED_EDGE('',*,*,#139879,.F.); +#139879 = EDGE_CURVE('',#139831,#139551,#139880,.T.); +#139880 = SURFACE_CURVE('',#139881,(#139885,#139892),.PCURVE_S1.); +#139881 = LINE('',#139882,#139883); +#139882 = CARTESIAN_POINT('',(4.85,10.419594812019,0.530776333563)); +#139883 = VECTOR('',#139884,1.); +#139884 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#139885 = PCURVE('',#139615,#139886); +#139886 = DEFINITIONAL_REPRESENTATION('',(#139887),#139891); +#139887 = LINE('',#139888,#139889); +#139888 = CARTESIAN_POINT('',(-4.85,0.E+000)); +#139889 = VECTOR('',#139890,1.); +#139890 = DIRECTION('',(0.E+000,-1.)); +#139891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139892 = PCURVE('',#89918,#139893); +#139893 = DEFINITIONAL_REPRESENTATION('',(#139894),#139898); +#139894 = LINE('',#139895,#139896); +#139895 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#139896 = VECTOR('',#139897,1.); +#139897 = DIRECTION('',(-1.,0.E+000)); +#139898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139899 = ADVANCED_FACE('',(#139900),#139846,.F.); +#139900 = FACE_BOUND('',#139901,.F.); +#139901 = EDGE_LOOP('',(#139902,#139929,#139951,#139972)); +#139902 = ORIENTED_EDGE('',*,*,#139903,.F.); +#139903 = EDGE_CURVE('',#139904,#139829,#139906,.T.); +#139904 = VERTEX_POINT('',#139905); +#139905 = CARTESIAN_POINT('',(4.65,10.303662633502,0.65)); +#139906 = SURFACE_CURVE('',#139907,(#139912,#139918),.PCURVE_S1.); +#139907 = CIRCLE('',#139908,0.119270391569); +#139908 = AXIS2_PLACEMENT_3D('',#139909,#139910,#139911); +#139909 = CARTESIAN_POINT('',(4.65,10.30032442045,0.530776333563)); +#139910 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139911 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139912 = PCURVE('',#139846,#139913); +#139913 = DEFINITIONAL_REPRESENTATION('',(#139914),#139917); +#139914 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139915,#139916), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#137523 = CARTESIAN_POINT('',(1.598788597134,-4.65)); -#137524 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#137525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#139915 = CARTESIAN_POINT('',(1.598788597134,-4.65)); +#139916 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#139917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137526 = PCURVE('',#87580,#137527); -#137527 = DEFINITIONAL_REPRESENTATION('',(#137528),#137536); -#137528 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137529,#137530,#137531, - #137532,#137533,#137534,#137535),.UNSPECIFIED.,.T.,.F.) +#139918 = PCURVE('',#89972,#139919); +#139919 = DEFINITIONAL_REPRESENTATION('',(#139920),#139928); +#139920 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139921,#139922,#139923, + #139924,#139925,#139926,#139927),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#137529 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#137530 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#137531 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#137532 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#137533 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#137534 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#137535 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#137536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137537 = ORIENTED_EDGE('',*,*,#137538,.F.); -#137538 = EDGE_CURVE('',#137539,#137512,#137541,.T.); -#137539 = VERTEX_POINT('',#137540); -#137540 = CARTESIAN_POINT('',(4.85,10.303662633502,0.65)); -#137541 = SURFACE_CURVE('',#137542,(#137546,#137552),.PCURVE_S1.); -#137542 = LINE('',#137543,#137544); -#137543 = CARTESIAN_POINT('',(4.85,10.303662633502,0.65)); -#137544 = VECTOR('',#137545,1.); -#137545 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137546 = PCURVE('',#137454,#137547); -#137547 = DEFINITIONAL_REPRESENTATION('',(#137548),#137551); -#137548 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137549,#137550), +#139921 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#139922 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#139923 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#139924 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#139925 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#139926 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#139927 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#139928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139929 = ORIENTED_EDGE('',*,*,#139930,.F.); +#139930 = EDGE_CURVE('',#139931,#139904,#139933,.T.); +#139931 = VERTEX_POINT('',#139932); +#139932 = CARTESIAN_POINT('',(4.85,10.303662633502,0.65)); +#139933 = SURFACE_CURVE('',#139934,(#139938,#139944),.PCURVE_S1.); +#139934 = LINE('',#139935,#139936); +#139935 = CARTESIAN_POINT('',(4.85,10.303662633502,0.65)); +#139936 = VECTOR('',#139937,1.); +#139937 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139938 = PCURVE('',#139846,#139939); +#139939 = DEFINITIONAL_REPRESENTATION('',(#139940),#139943); +#139940 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139941,#139942), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#137549 = CARTESIAN_POINT('',(1.598788597134,-4.85)); -#137550 = CARTESIAN_POINT('',(1.598788597134,-4.65)); -#137551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137552 = PCURVE('',#87498,#137553); -#137553 = DEFINITIONAL_REPRESENTATION('',(#137554),#137558); -#137554 = LINE('',#137555,#137556); -#137555 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#137556 = VECTOR('',#137557,1.); -#137557 = DIRECTION('',(-8.881784197001E-016,-1.)); -#137558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137559 = ORIENTED_EDGE('',*,*,#137560,.T.); -#137560 = EDGE_CURVE('',#137539,#137439,#137561,.T.); -#137561 = SURFACE_CURVE('',#137562,(#137567,#137573),.PCURVE_S1.); -#137562 = CIRCLE('',#137563,0.119270391569); -#137563 = AXIS2_PLACEMENT_3D('',#137564,#137565,#137566); -#137564 = CARTESIAN_POINT('',(4.85,10.30032442045,0.530776333563)); -#137565 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137566 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137567 = PCURVE('',#137454,#137568); -#137568 = DEFINITIONAL_REPRESENTATION('',(#137569),#137572); -#137569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137570,#137571), +#139941 = CARTESIAN_POINT('',(1.598788597134,-4.85)); +#139942 = CARTESIAN_POINT('',(1.598788597134,-4.65)); +#139943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139944 = PCURVE('',#89890,#139945); +#139945 = DEFINITIONAL_REPRESENTATION('',(#139946),#139950); +#139946 = LINE('',#139947,#139948); +#139947 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#139948 = VECTOR('',#139949,1.); +#139949 = DIRECTION('',(-8.881784197001E-016,-1.)); +#139950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139951 = ORIENTED_EDGE('',*,*,#139952,.T.); +#139952 = EDGE_CURVE('',#139931,#139831,#139953,.T.); +#139953 = SURFACE_CURVE('',#139954,(#139959,#139965),.PCURVE_S1.); +#139954 = CIRCLE('',#139955,0.119270391569); +#139955 = AXIS2_PLACEMENT_3D('',#139956,#139957,#139958); +#139956 = CARTESIAN_POINT('',(4.85,10.30032442045,0.530776333563)); +#139957 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139958 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139959 = PCURVE('',#139846,#139960); +#139960 = DEFINITIONAL_REPRESENTATION('',(#139961),#139964); +#139961 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139962,#139963), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#137570 = CARTESIAN_POINT('',(1.598788597134,-4.85)); -#137571 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#137572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137573 = PCURVE('',#87526,#137574); -#137574 = DEFINITIONAL_REPRESENTATION('',(#137575),#137579); -#137575 = CIRCLE('',#137576,0.119270391569); -#137576 = AXIS2_PLACEMENT_2D('',#137577,#137578); -#137577 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#137578 = DIRECTION('',(0.E+000,-1.)); -#137579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137580 = ORIENTED_EDGE('',*,*,#137436,.F.); -#137581 = ADVANCED_FACE('',(#137582),#137379,.T.); -#137582 = FACE_BOUND('',#137583,.T.); -#137583 = EDGE_LOOP('',(#137584,#137630,#137631,#137681)); -#137584 = ORIENTED_EDGE('',*,*,#137585,.T.); -#137585 = EDGE_CURVE('',#137586,#137362,#137588,.T.); -#137586 = VERTEX_POINT('',#137587); -#137587 = CARTESIAN_POINT('',(4.85,10.304819755875,0.75)); -#137588 = SURFACE_CURVE('',#137589,(#137594,#137623),.PCURVE_S1.); -#137589 = CIRCLE('',#137590,0.2192697516); -#137590 = AXIS2_PLACEMENT_3D('',#137591,#137592,#137593); -#137591 = CARTESIAN_POINT('',(4.85,10.30032442045,0.530776333563)); -#137592 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137593 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137594 = PCURVE('',#137379,#137595); -#137595 = DEFINITIONAL_REPRESENTATION('',(#137596),#137622); -#137596 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137597,#137598,#137599, - #137600,#137601,#137602,#137603,#137604,#137605,#137606,#137607, - #137608,#137609,#137610,#137611,#137612,#137613,#137614,#137615, - #137616,#137617,#137618,#137619,#137620,#137621),.UNSPECIFIED.,.F., +#139962 = CARTESIAN_POINT('',(1.598788597134,-4.85)); +#139963 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#139964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139965 = PCURVE('',#89918,#139966); +#139966 = DEFINITIONAL_REPRESENTATION('',(#139967),#139971); +#139967 = CIRCLE('',#139968,0.119270391569); +#139968 = AXIS2_PLACEMENT_2D('',#139969,#139970); +#139969 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#139970 = DIRECTION('',(0.E+000,-1.)); +#139971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#139972 = ORIENTED_EDGE('',*,*,#139828,.F.); +#139973 = ADVANCED_FACE('',(#139974),#139771,.T.); +#139974 = FACE_BOUND('',#139975,.T.); +#139975 = EDGE_LOOP('',(#139976,#140022,#140023,#140073)); +#139976 = ORIENTED_EDGE('',*,*,#139977,.T.); +#139977 = EDGE_CURVE('',#139978,#139754,#139980,.T.); +#139978 = VERTEX_POINT('',#139979); +#139979 = CARTESIAN_POINT('',(4.85,10.304819755875,0.75)); +#139980 = SURFACE_CURVE('',#139981,(#139986,#140015),.PCURVE_S1.); +#139981 = CIRCLE('',#139982,0.2192697516); +#139982 = AXIS2_PLACEMENT_3D('',#139983,#139984,#139985); +#139983 = CARTESIAN_POINT('',(4.85,10.30032442045,0.530776333563)); +#139984 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#139985 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#139986 = PCURVE('',#139771,#139987); +#139987 = DEFINITIONAL_REPRESENTATION('',(#139988),#140014); +#139988 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139989,#139990,#139991, + #139992,#139993,#139994,#139995,#139996,#139997,#139998,#139999, + #140000,#140001,#140002,#140003,#140004,#140005,#140006,#140007, + #140008,#140009,#140010,#140011,#140012,#140013),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -169594,60 +172596,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#137597 = CARTESIAN_POINT('',(1.591299156552,-4.85)); -#137598 = CARTESIAN_POINT('',(1.614788451962,-4.85)); -#137599 = CARTESIAN_POINT('',(1.661767042781,-4.85)); -#137600 = CARTESIAN_POINT('',(1.73223492901,-4.85)); -#137601 = CARTESIAN_POINT('',(1.802702815239,-4.85)); -#137602 = CARTESIAN_POINT('',(1.873170701468,-4.85)); -#137603 = CARTESIAN_POINT('',(1.943638587697,-4.85)); -#137604 = CARTESIAN_POINT('',(2.014106473926,-4.85)); -#137605 = CARTESIAN_POINT('',(2.084574360155,-4.85)); -#137606 = CARTESIAN_POINT('',(2.155042246384,-4.85)); -#137607 = CARTESIAN_POINT('',(2.225510132613,-4.85)); -#137608 = CARTESIAN_POINT('',(2.295978018842,-4.85)); -#137609 = CARTESIAN_POINT('',(2.366445905071,-4.85)); -#137610 = CARTESIAN_POINT('',(2.4369137913,-4.85)); -#137611 = CARTESIAN_POINT('',(2.507381677529,-4.85)); -#137612 = CARTESIAN_POINT('',(2.577849563758,-4.85)); -#137613 = CARTESIAN_POINT('',(2.648317449987,-4.85)); -#137614 = CARTESIAN_POINT('',(2.718785336216,-4.85)); -#137615 = CARTESIAN_POINT('',(2.789253222445,-4.85)); -#137616 = CARTESIAN_POINT('',(2.859721108674,-4.85)); -#137617 = CARTESIAN_POINT('',(2.930188994903,-4.85)); -#137618 = CARTESIAN_POINT('',(3.000656881132,-4.85)); -#137619 = CARTESIAN_POINT('',(3.071124767361,-4.85)); -#137620 = CARTESIAN_POINT('',(3.11810335818,-4.85)); -#137621 = CARTESIAN_POINT('',(3.14159265359,-4.85)); -#137622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137623 = PCURVE('',#87526,#137624); -#137624 = DEFINITIONAL_REPRESENTATION('',(#137625),#137629); -#137625 = CIRCLE('',#137626,0.2192697516); -#137626 = AXIS2_PLACEMENT_2D('',#137627,#137628); -#137627 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#137628 = DIRECTION('',(0.E+000,-1.)); -#137629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137630 = ORIENTED_EDGE('',*,*,#137361,.T.); -#137631 = ORIENTED_EDGE('',*,*,#137632,.F.); -#137632 = EDGE_CURVE('',#137633,#137364,#137635,.T.); -#137633 = VERTEX_POINT('',#137634); -#137634 = CARTESIAN_POINT('',(4.65,10.304819755875,0.75)); -#137635 = SURFACE_CURVE('',#137636,(#137641,#137670),.PCURVE_S1.); -#137636 = CIRCLE('',#137637,0.2192697516); -#137637 = AXIS2_PLACEMENT_3D('',#137638,#137639,#137640); -#137638 = CARTESIAN_POINT('',(4.65,10.30032442045,0.530776333563)); -#137639 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137640 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#137641 = PCURVE('',#137379,#137642); -#137642 = DEFINITIONAL_REPRESENTATION('',(#137643),#137669); -#137643 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#137644,#137645,#137646, - #137647,#137648,#137649,#137650,#137651,#137652,#137653,#137654, - #137655,#137656,#137657,#137658,#137659,#137660,#137661,#137662, - #137663,#137664,#137665,#137666,#137667,#137668),.UNSPECIFIED.,.F., +#139989 = CARTESIAN_POINT('',(1.591299156552,-4.85)); +#139990 = CARTESIAN_POINT('',(1.614788451962,-4.85)); +#139991 = CARTESIAN_POINT('',(1.661767042781,-4.85)); +#139992 = CARTESIAN_POINT('',(1.73223492901,-4.85)); +#139993 = CARTESIAN_POINT('',(1.802702815239,-4.85)); +#139994 = CARTESIAN_POINT('',(1.873170701468,-4.85)); +#139995 = CARTESIAN_POINT('',(1.943638587697,-4.85)); +#139996 = CARTESIAN_POINT('',(2.014106473926,-4.85)); +#139997 = CARTESIAN_POINT('',(2.084574360155,-4.85)); +#139998 = CARTESIAN_POINT('',(2.155042246384,-4.85)); +#139999 = CARTESIAN_POINT('',(2.225510132613,-4.85)); +#140000 = CARTESIAN_POINT('',(2.295978018842,-4.85)); +#140001 = CARTESIAN_POINT('',(2.366445905071,-4.85)); +#140002 = CARTESIAN_POINT('',(2.4369137913,-4.85)); +#140003 = CARTESIAN_POINT('',(2.507381677529,-4.85)); +#140004 = CARTESIAN_POINT('',(2.577849563758,-4.85)); +#140005 = CARTESIAN_POINT('',(2.648317449987,-4.85)); +#140006 = CARTESIAN_POINT('',(2.718785336216,-4.85)); +#140007 = CARTESIAN_POINT('',(2.789253222445,-4.85)); +#140008 = CARTESIAN_POINT('',(2.859721108674,-4.85)); +#140009 = CARTESIAN_POINT('',(2.930188994903,-4.85)); +#140010 = CARTESIAN_POINT('',(3.000656881132,-4.85)); +#140011 = CARTESIAN_POINT('',(3.071124767361,-4.85)); +#140012 = CARTESIAN_POINT('',(3.11810335818,-4.85)); +#140013 = CARTESIAN_POINT('',(3.14159265359,-4.85)); +#140014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140015 = PCURVE('',#89918,#140016); +#140016 = DEFINITIONAL_REPRESENTATION('',(#140017),#140021); +#140017 = CIRCLE('',#140018,0.2192697516); +#140018 = AXIS2_PLACEMENT_2D('',#140019,#140020); +#140019 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#140020 = DIRECTION('',(0.E+000,-1.)); +#140021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140022 = ORIENTED_EDGE('',*,*,#139753,.T.); +#140023 = ORIENTED_EDGE('',*,*,#140024,.F.); +#140024 = EDGE_CURVE('',#140025,#139756,#140027,.T.); +#140025 = VERTEX_POINT('',#140026); +#140026 = CARTESIAN_POINT('',(4.65,10.304819755875,0.75)); +#140027 = SURFACE_CURVE('',#140028,(#140033,#140062),.PCURVE_S1.); +#140028 = CIRCLE('',#140029,0.2192697516); +#140029 = AXIS2_PLACEMENT_3D('',#140030,#140031,#140032); +#140030 = CARTESIAN_POINT('',(4.65,10.30032442045,0.530776333563)); +#140031 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140032 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140033 = PCURVE('',#139771,#140034); +#140034 = DEFINITIONAL_REPRESENTATION('',(#140035),#140061); +#140035 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140036,#140037,#140038, + #140039,#140040,#140041,#140042,#140043,#140044,#140045,#140046, + #140047,#140048,#140049,#140050,#140051,#140052,#140053,#140054, + #140055,#140056,#140057,#140058,#140059,#140060),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -169655,1691 +172657,1691 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#137644 = CARTESIAN_POINT('',(1.591299156552,-4.65)); -#137645 = CARTESIAN_POINT('',(1.614788451962,-4.65)); -#137646 = CARTESIAN_POINT('',(1.661767042781,-4.65)); -#137647 = CARTESIAN_POINT('',(1.73223492901,-4.65)); -#137648 = CARTESIAN_POINT('',(1.802702815239,-4.65)); -#137649 = CARTESIAN_POINT('',(1.873170701468,-4.65)); -#137650 = CARTESIAN_POINT('',(1.943638587697,-4.65)); -#137651 = CARTESIAN_POINT('',(2.014106473926,-4.65)); -#137652 = CARTESIAN_POINT('',(2.084574360155,-4.65)); -#137653 = CARTESIAN_POINT('',(2.155042246384,-4.65)); -#137654 = CARTESIAN_POINT('',(2.225510132613,-4.65)); -#137655 = CARTESIAN_POINT('',(2.295978018842,-4.65)); -#137656 = CARTESIAN_POINT('',(2.366445905071,-4.65)); -#137657 = CARTESIAN_POINT('',(2.4369137913,-4.65)); -#137658 = CARTESIAN_POINT('',(2.507381677529,-4.65)); -#137659 = CARTESIAN_POINT('',(2.577849563758,-4.65)); -#137660 = CARTESIAN_POINT('',(2.648317449987,-4.65)); -#137661 = CARTESIAN_POINT('',(2.718785336216,-4.65)); -#137662 = CARTESIAN_POINT('',(2.789253222445,-4.65)); -#137663 = CARTESIAN_POINT('',(2.859721108674,-4.65)); -#137664 = CARTESIAN_POINT('',(2.930188994903,-4.65)); -#137665 = CARTESIAN_POINT('',(3.000656881132,-4.65)); -#137666 = CARTESIAN_POINT('',(3.071124767361,-4.65)); -#137667 = CARTESIAN_POINT('',(3.11810335818,-4.65)); -#137668 = CARTESIAN_POINT('',(3.14159265359,-4.65)); -#137669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137670 = PCURVE('',#87580,#137671); -#137671 = DEFINITIONAL_REPRESENTATION('',(#137672),#137680); -#137672 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#137673,#137674,#137675, - #137676,#137677,#137678,#137679),.UNSPECIFIED.,.T.,.F.) +#140036 = CARTESIAN_POINT('',(1.591299156552,-4.65)); +#140037 = CARTESIAN_POINT('',(1.614788451962,-4.65)); +#140038 = CARTESIAN_POINT('',(1.661767042781,-4.65)); +#140039 = CARTESIAN_POINT('',(1.73223492901,-4.65)); +#140040 = CARTESIAN_POINT('',(1.802702815239,-4.65)); +#140041 = CARTESIAN_POINT('',(1.873170701468,-4.65)); +#140042 = CARTESIAN_POINT('',(1.943638587697,-4.65)); +#140043 = CARTESIAN_POINT('',(2.014106473926,-4.65)); +#140044 = CARTESIAN_POINT('',(2.084574360155,-4.65)); +#140045 = CARTESIAN_POINT('',(2.155042246384,-4.65)); +#140046 = CARTESIAN_POINT('',(2.225510132613,-4.65)); +#140047 = CARTESIAN_POINT('',(2.295978018842,-4.65)); +#140048 = CARTESIAN_POINT('',(2.366445905071,-4.65)); +#140049 = CARTESIAN_POINT('',(2.4369137913,-4.65)); +#140050 = CARTESIAN_POINT('',(2.507381677529,-4.65)); +#140051 = CARTESIAN_POINT('',(2.577849563758,-4.65)); +#140052 = CARTESIAN_POINT('',(2.648317449987,-4.65)); +#140053 = CARTESIAN_POINT('',(2.718785336216,-4.65)); +#140054 = CARTESIAN_POINT('',(2.789253222445,-4.65)); +#140055 = CARTESIAN_POINT('',(2.859721108674,-4.65)); +#140056 = CARTESIAN_POINT('',(2.930188994903,-4.65)); +#140057 = CARTESIAN_POINT('',(3.000656881132,-4.65)); +#140058 = CARTESIAN_POINT('',(3.071124767361,-4.65)); +#140059 = CARTESIAN_POINT('',(3.11810335818,-4.65)); +#140060 = CARTESIAN_POINT('',(3.14159265359,-4.65)); +#140061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140062 = PCURVE('',#89972,#140063); +#140063 = DEFINITIONAL_REPRESENTATION('',(#140064),#140072); +#140064 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140065,#140066,#140067, + #140068,#140069,#140070,#140071),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#137673 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#137674 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#137675 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#137676 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#137677 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#137678 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#137679 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#137680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137681 = ORIENTED_EDGE('',*,*,#137682,.T.); -#137682 = EDGE_CURVE('',#137633,#137586,#137683,.T.); -#137683 = SURFACE_CURVE('',#137684,(#137688,#137694),.PCURVE_S1.); -#137684 = LINE('',#137685,#137686); -#137685 = CARTESIAN_POINT('',(4.85,10.304819755875,0.75)); -#137686 = VECTOR('',#137687,1.); -#137687 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137688 = PCURVE('',#137379,#137689); -#137689 = DEFINITIONAL_REPRESENTATION('',(#137690),#137693); -#137690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137691,#137692), +#140065 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#140066 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#140067 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#140068 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#140069 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#140070 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#140071 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#140072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140073 = ORIENTED_EDGE('',*,*,#140074,.T.); +#140074 = EDGE_CURVE('',#140025,#139978,#140075,.T.); +#140075 = SURFACE_CURVE('',#140076,(#140080,#140086),.PCURVE_S1.); +#140076 = LINE('',#140077,#140078); +#140077 = CARTESIAN_POINT('',(4.85,10.304819755875,0.75)); +#140078 = VECTOR('',#140079,1.); +#140079 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140080 = PCURVE('',#139771,#140081); +#140081 = DEFINITIONAL_REPRESENTATION('',(#140082),#140085); +#140082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140083,#140084), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#137691 = CARTESIAN_POINT('',(1.591299156552,-4.65)); -#137692 = CARTESIAN_POINT('',(1.591299156552,-4.85)); -#137693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140083 = CARTESIAN_POINT('',(1.591299156552,-4.65)); +#140084 = CARTESIAN_POINT('',(1.591299156552,-4.85)); +#140085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137694 = PCURVE('',#87554,#137695); -#137695 = DEFINITIONAL_REPRESENTATION('',(#137696),#137700); -#137696 = LINE('',#137697,#137698); -#137697 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#137698 = VECTOR('',#137699,1.); -#137699 = DIRECTION('',(-8.881784197001E-016,1.)); -#137700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137701 = ADVANCED_FACE('',(#137702),#87498,.F.); -#137702 = FACE_BOUND('',#137703,.T.); -#137703 = EDGE_LOOP('',(#137704,#137705,#137726,#137727)); -#137704 = ORIENTED_EDGE('',*,*,#137538,.F.); -#137705 = ORIENTED_EDGE('',*,*,#137706,.T.); -#137706 = EDGE_CURVE('',#137539,#87481,#137707,.T.); -#137707 = SURFACE_CURVE('',#137708,(#137712,#137719),.PCURVE_S1.); -#137708 = LINE('',#137709,#137710); -#137709 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); -#137710 = VECTOR('',#137711,1.); -#137711 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#137712 = PCURVE('',#87498,#137713); -#137713 = DEFINITIONAL_REPRESENTATION('',(#137714),#137718); -#137714 = LINE('',#137715,#137716); -#137715 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137716 = VECTOR('',#137717,1.); -#137717 = DIRECTION('',(1.,6.005309793447E-063)); -#137718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137719 = PCURVE('',#87526,#137720); -#137720 = DEFINITIONAL_REPRESENTATION('',(#137721),#137725); -#137721 = LINE('',#137722,#137723); -#137722 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137723 = VECTOR('',#137724,1.); -#137724 = DIRECTION('',(3.563627120235E-016,-1.)); -#137725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137726 = ORIENTED_EDGE('',*,*,#87480,.T.); -#137727 = ORIENTED_EDGE('',*,*,#137728,.F.); -#137728 = EDGE_CURVE('',#137512,#87483,#137729,.T.); -#137729 = SURFACE_CURVE('',#137730,(#137734,#137741),.PCURVE_S1.); -#137730 = LINE('',#137731,#137732); -#137731 = CARTESIAN_POINT('',(4.65,10.527847992439,0.65)); -#137732 = VECTOR('',#137733,1.); -#137733 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#137734 = PCURVE('',#87498,#137735); -#137735 = DEFINITIONAL_REPRESENTATION('',(#137736),#137740); -#137736 = LINE('',#137737,#137738); -#137737 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#137738 = VECTOR('',#137739,1.); -#137739 = DIRECTION('',(1.,6.005309793447E-063)); -#137740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140086 = PCURVE('',#89946,#140087); +#140087 = DEFINITIONAL_REPRESENTATION('',(#140088),#140092); +#140088 = LINE('',#140089,#140090); +#140089 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#140090 = VECTOR('',#140091,1.); +#140091 = DIRECTION('',(-8.881784197001E-016,1.)); +#140092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137741 = PCURVE('',#87580,#137742); -#137742 = DEFINITIONAL_REPRESENTATION('',(#137743),#137747); -#137743 = LINE('',#137744,#137745); -#137744 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137745 = VECTOR('',#137746,1.); -#137746 = DIRECTION('',(-3.563627120235E-016,-1.)); -#137747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140093 = ADVANCED_FACE('',(#140094),#89890,.F.); +#140094 = FACE_BOUND('',#140095,.T.); +#140095 = EDGE_LOOP('',(#140096,#140097,#140118,#140119)); +#140096 = ORIENTED_EDGE('',*,*,#139930,.F.); +#140097 = ORIENTED_EDGE('',*,*,#140098,.T.); +#140098 = EDGE_CURVE('',#139931,#89873,#140099,.T.); +#140099 = SURFACE_CURVE('',#140100,(#140104,#140111),.PCURVE_S1.); +#140100 = LINE('',#140101,#140102); +#140101 = CARTESIAN_POINT('',(4.85,10.527847992439,0.65)); +#140102 = VECTOR('',#140103,1.); +#140103 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140104 = PCURVE('',#89890,#140105); +#140105 = DEFINITIONAL_REPRESENTATION('',(#140106),#140110); +#140106 = LINE('',#140107,#140108); +#140107 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140108 = VECTOR('',#140109,1.); +#140109 = DIRECTION('',(1.,6.005309793447E-063)); +#140110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140111 = PCURVE('',#89918,#140112); +#140112 = DEFINITIONAL_REPRESENTATION('',(#140113),#140117); +#140113 = LINE('',#140114,#140115); +#140114 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140115 = VECTOR('',#140116,1.); +#140116 = DIRECTION('',(3.563627120235E-016,-1.)); +#140117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140118 = ORIENTED_EDGE('',*,*,#89872,.T.); +#140119 = ORIENTED_EDGE('',*,*,#140120,.F.); +#140120 = EDGE_CURVE('',#139904,#89875,#140121,.T.); +#140121 = SURFACE_CURVE('',#140122,(#140126,#140133),.PCURVE_S1.); +#140122 = LINE('',#140123,#140124); +#140123 = CARTESIAN_POINT('',(4.65,10.527847992439,0.65)); +#140124 = VECTOR('',#140125,1.); +#140125 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140126 = PCURVE('',#89890,#140127); +#140127 = DEFINITIONAL_REPRESENTATION('',(#140128),#140132); +#140128 = LINE('',#140129,#140130); +#140129 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#140130 = VECTOR('',#140131,1.); +#140131 = DIRECTION('',(1.,6.005309793447E-063)); +#140132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140133 = PCURVE('',#89972,#140134); +#140134 = DEFINITIONAL_REPRESENTATION('',(#140135),#140139); +#140135 = LINE('',#140136,#140137); +#140136 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140137 = VECTOR('',#140138,1.); +#140138 = DIRECTION('',(-3.563627120235E-016,-1.)); +#140139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140140 = ADVANCED_FACE('',(#140141),#89972,.F.); +#140141 = FACE_BOUND('',#140142,.T.); +#140142 = EDGE_LOOP('',(#140143,#140164,#140165,#140166,#140167,#140168, + #140189,#140190,#140191,#140192,#140193,#140194)); +#140143 = ORIENTED_EDGE('',*,*,#140144,.F.); +#140144 = EDGE_CURVE('',#140025,#89931,#140145,.T.); +#140145 = SURFACE_CURVE('',#140146,(#140150,#140157),.PCURVE_S1.); +#140146 = LINE('',#140147,#140148); +#140147 = CARTESIAN_POINT('',(4.65,10.527847992439,0.75)); +#140148 = VECTOR('',#140149,1.); +#140149 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140150 = PCURVE('',#89972,#140151); +#140151 = DEFINITIONAL_REPRESENTATION('',(#140152),#140156); +#140152 = LINE('',#140153,#140154); +#140153 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#140154 = VECTOR('',#140155,1.); +#140155 = DIRECTION('',(-3.563627120235E-016,-1.)); +#140156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140157 = PCURVE('',#89946,#140158); +#140158 = DEFINITIONAL_REPRESENTATION('',(#140159),#140163); +#140159 = LINE('',#140160,#140161); +#140160 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#140161 = VECTOR('',#140162,1.); +#140162 = DIRECTION('',(-1.,6.005309793447E-063)); +#140163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140164 = ORIENTED_EDGE('',*,*,#140024,.T.); +#140165 = ORIENTED_EDGE('',*,*,#139804,.T.); +#140166 = ORIENTED_EDGE('',*,*,#139729,.T.); +#140167 = ORIENTED_EDGE('',*,*,#139498,.T.); +#140168 = ORIENTED_EDGE('',*,*,#140169,.T.); +#140169 = EDGE_CURVE('',#139476,#139339,#140170,.T.); +#140170 = SURFACE_CURVE('',#140171,(#140175,#140182),.PCURVE_S1.); +#140171 = LINE('',#140172,#140173); +#140172 = CARTESIAN_POINT('',(4.65,11.,1.159810404338E-002)); +#140173 = VECTOR('',#140174,1.); +#140174 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#140175 = PCURVE('',#89972,#140176); +#140176 = DEFINITIONAL_REPRESENTATION('',(#140177),#140181); +#140177 = LINE('',#140178,#140179); +#140178 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#140179 = VECTOR('',#140180,1.); +#140180 = DIRECTION('',(1.,-2.101748079665E-016)); +#140181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140182 = PCURVE('',#139382,#140183); +#140183 = DEFINITIONAL_REPRESENTATION('',(#140184),#140188); +#140184 = LINE('',#140185,#140186); +#140185 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#140186 = VECTOR('',#140187,1.); +#140187 = DIRECTION('',(1.570395187386E-016,-1.)); +#140188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140189 = ORIENTED_EDGE('',*,*,#139336,.F.); +#140190 = ORIENTED_EDGE('',*,*,#139627,.F.); +#140191 = ORIENTED_EDGE('',*,*,#139857,.F.); +#140192 = ORIENTED_EDGE('',*,*,#139903,.F.); +#140193 = ORIENTED_EDGE('',*,*,#140120,.T.); +#140194 = ORIENTED_EDGE('',*,*,#89958,.T.); +#140195 = ADVANCED_FACE('',(#140196),#89946,.F.); +#140196 = FACE_BOUND('',#140197,.T.); +#140197 = EDGE_LOOP('',(#140198,#140199,#140200,#140201)); +#140198 = ORIENTED_EDGE('',*,*,#140074,.F.); +#140199 = ORIENTED_EDGE('',*,*,#140144,.T.); +#140200 = ORIENTED_EDGE('',*,*,#89930,.T.); +#140201 = ORIENTED_EDGE('',*,*,#140202,.F.); +#140202 = EDGE_CURVE('',#139978,#89903,#140203,.T.); +#140203 = SURFACE_CURVE('',#140204,(#140208,#140215),.PCURVE_S1.); +#140204 = LINE('',#140205,#140206); +#140205 = CARTESIAN_POINT('',(4.85,10.527847992439,0.75)); +#140206 = VECTOR('',#140207,1.); +#140207 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140208 = PCURVE('',#89946,#140209); +#140209 = DEFINITIONAL_REPRESENTATION('',(#140210),#140214); +#140210 = LINE('',#140211,#140212); +#140211 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140212 = VECTOR('',#140213,1.); +#140213 = DIRECTION('',(-1.,6.005309793447E-063)); +#140214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140215 = PCURVE('',#89918,#140216); +#140216 = DEFINITIONAL_REPRESENTATION('',(#140217),#140221); +#140217 = LINE('',#140218,#140219); +#140218 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#140219 = VECTOR('',#140220,1.); +#140220 = DIRECTION('',(3.563627120235E-016,-1.)); +#140221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140222 = ADVANCED_FACE('',(#140223),#89918,.F.); +#140223 = FACE_BOUND('',#140224,.T.); +#140224 = EDGE_LOOP('',(#140225,#140226,#140227,#140228,#140229,#140230, + #140251,#140252,#140253,#140254,#140255,#140256)); +#140225 = ORIENTED_EDGE('',*,*,#140098,.F.); +#140226 = ORIENTED_EDGE('',*,*,#139952,.T.); +#140227 = ORIENTED_EDGE('',*,*,#139879,.T.); +#140228 = ORIENTED_EDGE('',*,*,#139550,.T.); +#140229 = ORIENTED_EDGE('',*,*,#139394,.T.); +#140230 = ORIENTED_EDGE('',*,*,#140231,.T.); +#140231 = EDGE_CURVE('',#139367,#139448,#140232,.T.); +#140232 = SURFACE_CURVE('',#140233,(#140237,#140244),.PCURVE_S1.); +#140233 = LINE('',#140234,#140235); +#140234 = CARTESIAN_POINT('',(4.85,11.,1.159810404338E-002)); +#140235 = VECTOR('',#140236,1.); +#140236 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#140237 = PCURVE('',#89918,#140238); +#140238 = DEFINITIONAL_REPRESENTATION('',(#140239),#140243); +#140239 = LINE('',#140240,#140241); +#140240 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#140241 = VECTOR('',#140242,1.); +#140242 = DIRECTION('',(1.,2.101748079665E-016)); +#140243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140244 = PCURVE('',#139382,#140245); +#140245 = DEFINITIONAL_REPRESENTATION('',(#140246),#140250); +#140246 = LINE('',#140247,#140248); +#140247 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#140248 = VECTOR('',#140249,1.); +#140249 = DIRECTION('',(-1.570395187386E-016,1.)); +#140250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140251 = ORIENTED_EDGE('',*,*,#139445,.F.); +#140252 = ORIENTED_EDGE('',*,*,#139675,.F.); +#140253 = ORIENTED_EDGE('',*,*,#139782,.F.); +#140254 = ORIENTED_EDGE('',*,*,#139977,.F.); +#140255 = ORIENTED_EDGE('',*,*,#140202,.T.); +#140256 = ORIENTED_EDGE('',*,*,#89902,.T.); +#140257 = ADVANCED_FACE('',(#140258),#139382,.T.); +#140258 = FACE_BOUND('',#140259,.T.); +#140259 = EDGE_LOOP('',(#140260,#140261,#140262,#140263)); +#140260 = ORIENTED_EDGE('',*,*,#139475,.F.); +#140261 = ORIENTED_EDGE('',*,*,#140231,.F.); +#140262 = ORIENTED_EDGE('',*,*,#139366,.F.); +#140263 = ORIENTED_EDGE('',*,*,#140169,.F.); +#140264 = ADVANCED_FACE('',(#140265),#140279,.T.); +#140265 = FACE_BOUND('',#140266,.T.); +#140266 = EDGE_LOOP('',(#140267,#140297,#140325,#140348)); +#140267 = ORIENTED_EDGE('',*,*,#140268,.T.); +#140268 = EDGE_CURVE('',#140269,#140271,#140273,.T.); +#140269 = VERTEX_POINT('',#140270); +#140270 = CARTESIAN_POINT('',(8.35,10.740726081328,-0.208196358798)); +#140271 = VERTEX_POINT('',#140272); +#140272 = CARTESIAN_POINT('',(8.35,11.,-0.208196358798)); +#140273 = SURFACE_CURVE('',#140274,(#140278,#140290),.PCURVE_S1.); +#140274 = LINE('',#140275,#140276); +#140275 = CARTESIAN_POINT('',(8.35,10.740726081328,-0.208196358798)); +#140276 = VECTOR('',#140277,1.); +#140277 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#140278 = PCURVE('',#140279,#140284); +#140279 = PLANE('',#140280); +#140280 = AXIS2_PLACEMENT_3D('',#140281,#140282,#140283); +#140281 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#140282 = DIRECTION('',(0.E+000,0.E+000,1.)); +#140283 = DIRECTION('',(1.,0.E+000,0.E+000)); +#140284 = DEFINITIONAL_REPRESENTATION('',(#140285),#140289); +#140285 = LINE('',#140286,#140287); +#140286 = CARTESIAN_POINT('',(8.35,-7.105427357601E-015)); +#140287 = VECTOR('',#140288,1.); +#140288 = DIRECTION('',(6.725593854929E-015,1.)); +#140289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140290 = PCURVE('',#89718,#140291); +#140291 = DEFINITIONAL_REPRESENTATION('',(#140292),#140296); +#140292 = LINE('',#140293,#140294); +#140293 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#140294 = VECTOR('',#140295,1.); +#140295 = DIRECTION('',(0.E+000,1.)); +#140296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140297 = ORIENTED_EDGE('',*,*,#140298,.T.); +#140298 = EDGE_CURVE('',#140271,#140299,#140301,.T.); +#140299 = VERTEX_POINT('',#140300); +#140300 = CARTESIAN_POINT('',(8.15,11.,-0.208196358798)); +#140301 = SURFACE_CURVE('',#140302,(#140306,#140313),.PCURVE_S1.); +#140302 = LINE('',#140303,#140304); +#140303 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#140304 = VECTOR('',#140305,1.); +#140305 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140306 = PCURVE('',#140279,#140307); +#140307 = DEFINITIONAL_REPRESENTATION('',(#140308),#140312); +#140308 = LINE('',#140309,#140310); +#140309 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#140310 = VECTOR('',#140311,1.); +#140311 = DIRECTION('',(-1.,8.881784197001E-016)); +#140312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140313 = PCURVE('',#140314,#140319); +#140314 = PLANE('',#140315); +#140315 = AXIS2_PLACEMENT_3D('',#140316,#140317,#140318); +#140316 = CARTESIAN_POINT('',(8.25,11.,-0.258196742327)); +#140317 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#140318 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#140319 = DEFINITIONAL_REPRESENTATION('',(#140320),#140324); +#140320 = LINE('',#140321,#140322); +#140321 = CARTESIAN_POINT('',(8.25,5.000038352949E-002)); +#140322 = VECTOR('',#140323,1.); +#140323 = DIRECTION('',(1.,1.1653254136E-048)); +#140324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140325 = ORIENTED_EDGE('',*,*,#140326,.F.); +#140326 = EDGE_CURVE('',#140327,#140299,#140329,.T.); +#140327 = VERTEX_POINT('',#140328); +#140328 = CARTESIAN_POINT('',(8.15,10.740726081328,-0.208196358798)); +#140329 = SURFACE_CURVE('',#140330,(#140334,#140341),.PCURVE_S1.); +#140330 = LINE('',#140331,#140332); +#140331 = CARTESIAN_POINT('',(8.15,10.740726081328,-0.208196358798)); +#140332 = VECTOR('',#140333,1.); +#140333 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#140334 = PCURVE('',#140279,#140335); +#140335 = DEFINITIONAL_REPRESENTATION('',(#140336),#140340); +#140336 = LINE('',#140337,#140338); +#140337 = CARTESIAN_POINT('',(8.15,-7.105427357601E-015)); +#140338 = VECTOR('',#140339,1.); +#140339 = DIRECTION('',(6.725593854929E-015,1.)); +#140340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140341 = PCURVE('',#89662,#140342); +#140342 = DEFINITIONAL_REPRESENTATION('',(#140343),#140347); +#140343 = LINE('',#140344,#140345); +#140344 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#140345 = VECTOR('',#140346,1.); +#140346 = DIRECTION('',(0.E+000,1.)); +#140347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140348 = ORIENTED_EDGE('',*,*,#140349,.T.); +#140349 = EDGE_CURVE('',#140327,#140269,#140350,.T.); +#140350 = SURFACE_CURVE('',#140351,(#140355,#140362),.PCURVE_S1.); +#140351 = LINE('',#140352,#140353); +#140352 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#140353 = VECTOR('',#140354,1.); +#140354 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140355 = PCURVE('',#140279,#140356); +#140356 = DEFINITIONAL_REPRESENTATION('',(#140357),#140361); +#140357 = LINE('',#140358,#140359); +#140358 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140359 = VECTOR('',#140360,1.); +#140360 = DIRECTION('',(1.,-8.881784197001E-016)); +#140361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140362 = PCURVE('',#140363,#140368); +#140363 = CYLINDRICAL_SURFACE('',#140364,0.208574704164); +#140364 = AXIS2_PLACEMENT_3D('',#140365,#140366,#140367); +#140365 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, + 2.640924866458E-017)); +#140366 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140367 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140368 = DEFINITIONAL_REPRESENTATION('',(#140369),#140372); +#140369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140370,#140371), + .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); +#140370 = CARTESIAN_POINT('',(4.772630242227,8.15)); +#140371 = CARTESIAN_POINT('',(4.772630242227,8.35)); +#140372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140373 = ADVANCED_FACE('',(#140374),#140388,.T.); +#140374 = FACE_BOUND('',#140375,.T.); +#140375 = EDGE_LOOP('',(#140376,#140406,#140429,#140452)); +#140376 = ORIENTED_EDGE('',*,*,#140377,.T.); +#140377 = EDGE_CURVE('',#140378,#140380,#140382,.T.); +#140378 = VERTEX_POINT('',#140379); +#140379 = CARTESIAN_POINT('',(8.15,10.74341632541,-0.308197125857)); +#140380 = VERTEX_POINT('',#140381); +#140381 = CARTESIAN_POINT('',(8.15,11.,-0.308197125857)); +#140382 = SURFACE_CURVE('',#140383,(#140387,#140399),.PCURVE_S1.); +#140383 = LINE('',#140384,#140385); +#140384 = CARTESIAN_POINT('',(8.15,10.74341632541,-0.308197125857)); +#140385 = VECTOR('',#140386,1.); +#140386 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#140387 = PCURVE('',#140388,#140393); +#140388 = PLANE('',#140389); +#140389 = AXIS2_PLACEMENT_3D('',#140390,#140391,#140392); +#140390 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#140391 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#140392 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#140393 = DEFINITIONAL_REPRESENTATION('',(#140394),#140398); +#140394 = LINE('',#140395,#140396); +#140395 = CARTESIAN_POINT('',(-8.15,-7.105427357601E-015)); +#140396 = VECTOR('',#140397,1.); +#140397 = DIRECTION('',(-6.725593854929E-015,1.)); +#140398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140399 = PCURVE('',#89662,#140400); +#140400 = DEFINITIONAL_REPRESENTATION('',(#140401),#140405); +#140401 = LINE('',#140402,#140403); +#140402 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#140403 = VECTOR('',#140404,1.); +#140404 = DIRECTION('',(0.E+000,1.)); +#140405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140406 = ORIENTED_EDGE('',*,*,#140407,.T.); +#140407 = EDGE_CURVE('',#140380,#140408,#140410,.T.); +#140408 = VERTEX_POINT('',#140409); +#140409 = CARTESIAN_POINT('',(8.35,11.,-0.308197125857)); +#140410 = SURFACE_CURVE('',#140411,(#140415,#140422),.PCURVE_S1.); +#140411 = LINE('',#140412,#140413); +#140412 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#140413 = VECTOR('',#140414,1.); +#140414 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140415 = PCURVE('',#140388,#140416); +#140416 = DEFINITIONAL_REPRESENTATION('',(#140417),#140421); +#140417 = LINE('',#140418,#140419); +#140418 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#140419 = VECTOR('',#140420,1.); +#140420 = DIRECTION('',(-1.,-8.881784197001E-016)); +#140421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140422 = PCURVE('',#140314,#140423); +#140423 = DEFINITIONAL_REPRESENTATION('',(#140424),#140428); +#140424 = LINE('',#140425,#140426); +#140425 = CARTESIAN_POINT('',(8.25,-5.000038352949E-002)); +#140426 = VECTOR('',#140427,1.); +#140427 = DIRECTION('',(-1.,-1.1653254136E-048)); +#140428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140429 = ORIENTED_EDGE('',*,*,#140430,.F.); +#140430 = EDGE_CURVE('',#140431,#140408,#140433,.T.); +#140431 = VERTEX_POINT('',#140432); +#140432 = CARTESIAN_POINT('',(8.35,10.74341632541,-0.308197125857)); +#140433 = SURFACE_CURVE('',#140434,(#140438,#140445),.PCURVE_S1.); +#140434 = LINE('',#140435,#140436); +#140435 = CARTESIAN_POINT('',(8.35,10.74341632541,-0.308197125857)); +#140436 = VECTOR('',#140437,1.); +#140437 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#140438 = PCURVE('',#140388,#140439); +#140439 = DEFINITIONAL_REPRESENTATION('',(#140440),#140444); +#140440 = LINE('',#140441,#140442); +#140441 = CARTESIAN_POINT('',(-8.35,-7.105427357601E-015)); +#140442 = VECTOR('',#140443,1.); +#140443 = DIRECTION('',(-6.725593854929E-015,1.)); +#140444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140445 = PCURVE('',#89718,#140446); +#140446 = DEFINITIONAL_REPRESENTATION('',(#140447),#140451); +#140447 = LINE('',#140448,#140449); +#140448 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#140449 = VECTOR('',#140450,1.); +#140450 = DIRECTION('',(0.E+000,1.)); +#140451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140452 = ORIENTED_EDGE('',*,*,#140453,.T.); +#140453 = EDGE_CURVE('',#140431,#140378,#140454,.T.); +#140454 = SURFACE_CURVE('',#140455,(#140459,#140466),.PCURVE_S1.); +#140455 = LINE('',#140456,#140457); +#140456 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#140457 = VECTOR('',#140458,1.); +#140458 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140459 = PCURVE('',#140388,#140460); +#140460 = DEFINITIONAL_REPRESENTATION('',(#140461),#140465); +#140461 = LINE('',#140462,#140463); +#140462 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140463 = VECTOR('',#140464,1.); +#140464 = DIRECTION('',(1.,8.881784197001E-016)); +#140465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#137748 = ADVANCED_FACE('',(#137749),#87580,.F.); -#137749 = FACE_BOUND('',#137750,.T.); -#137750 = EDGE_LOOP('',(#137751,#137772,#137773,#137774,#137775,#137776, - #137797,#137798,#137799,#137800,#137801,#137802)); -#137751 = ORIENTED_EDGE('',*,*,#137752,.F.); -#137752 = EDGE_CURVE('',#137633,#87539,#137753,.T.); -#137753 = SURFACE_CURVE('',#137754,(#137758,#137765),.PCURVE_S1.); -#137754 = LINE('',#137755,#137756); -#137755 = CARTESIAN_POINT('',(4.65,10.527847992439,0.75)); -#137756 = VECTOR('',#137757,1.); -#137757 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#137758 = PCURVE('',#87580,#137759); -#137759 = DEFINITIONAL_REPRESENTATION('',(#137760),#137764); -#137760 = LINE('',#137761,#137762); -#137761 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#137762 = VECTOR('',#137763,1.); -#137763 = DIRECTION('',(-3.563627120235E-016,-1.)); -#137764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137765 = PCURVE('',#87554,#137766); -#137766 = DEFINITIONAL_REPRESENTATION('',(#137767),#137771); -#137767 = LINE('',#137768,#137769); -#137768 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#137769 = VECTOR('',#137770,1.); -#137770 = DIRECTION('',(-1.,6.005309793447E-063)); -#137771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137772 = ORIENTED_EDGE('',*,*,#137632,.T.); -#137773 = ORIENTED_EDGE('',*,*,#137412,.T.); -#137774 = ORIENTED_EDGE('',*,*,#137337,.T.); -#137775 = ORIENTED_EDGE('',*,*,#137106,.T.); -#137776 = ORIENTED_EDGE('',*,*,#137777,.T.); -#137777 = EDGE_CURVE('',#137084,#136947,#137778,.T.); -#137778 = SURFACE_CURVE('',#137779,(#137783,#137790),.PCURVE_S1.); -#137779 = LINE('',#137780,#137781); -#137780 = CARTESIAN_POINT('',(4.65,11.,1.159810404338E-002)); -#137781 = VECTOR('',#137782,1.); -#137782 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#137783 = PCURVE('',#87580,#137784); -#137784 = DEFINITIONAL_REPRESENTATION('',(#137785),#137789); -#137785 = LINE('',#137786,#137787); -#137786 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#137787 = VECTOR('',#137788,1.); -#137788 = DIRECTION('',(1.,-2.101748079665E-016)); -#137789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137790 = PCURVE('',#136990,#137791); -#137791 = DEFINITIONAL_REPRESENTATION('',(#137792),#137796); -#137792 = LINE('',#137793,#137794); -#137793 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#137794 = VECTOR('',#137795,1.); -#137795 = DIRECTION('',(1.570395187386E-016,-1.)); -#137796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137797 = ORIENTED_EDGE('',*,*,#136944,.F.); -#137798 = ORIENTED_EDGE('',*,*,#137235,.F.); -#137799 = ORIENTED_EDGE('',*,*,#137465,.F.); -#137800 = ORIENTED_EDGE('',*,*,#137511,.F.); -#137801 = ORIENTED_EDGE('',*,*,#137728,.T.); -#137802 = ORIENTED_EDGE('',*,*,#87566,.T.); -#137803 = ADVANCED_FACE('',(#137804),#87554,.F.); -#137804 = FACE_BOUND('',#137805,.T.); -#137805 = EDGE_LOOP('',(#137806,#137807,#137808,#137809)); -#137806 = ORIENTED_EDGE('',*,*,#137682,.F.); -#137807 = ORIENTED_EDGE('',*,*,#137752,.T.); -#137808 = ORIENTED_EDGE('',*,*,#87538,.T.); -#137809 = ORIENTED_EDGE('',*,*,#137810,.F.); -#137810 = EDGE_CURVE('',#137586,#87511,#137811,.T.); -#137811 = SURFACE_CURVE('',#137812,(#137816,#137823),.PCURVE_S1.); -#137812 = LINE('',#137813,#137814); -#137813 = CARTESIAN_POINT('',(4.85,10.527847992439,0.75)); -#137814 = VECTOR('',#137815,1.); -#137815 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#137816 = PCURVE('',#87554,#137817); -#137817 = DEFINITIONAL_REPRESENTATION('',(#137818),#137822); -#137818 = LINE('',#137819,#137820); -#137819 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137820 = VECTOR('',#137821,1.); -#137821 = DIRECTION('',(-1.,6.005309793447E-063)); -#137822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137823 = PCURVE('',#87526,#137824); -#137824 = DEFINITIONAL_REPRESENTATION('',(#137825),#137829); -#137825 = LINE('',#137826,#137827); -#137826 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#137827 = VECTOR('',#137828,1.); -#137828 = DIRECTION('',(3.563627120235E-016,-1.)); -#137829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137830 = ADVANCED_FACE('',(#137831),#87526,.F.); -#137831 = FACE_BOUND('',#137832,.T.); -#137832 = EDGE_LOOP('',(#137833,#137834,#137835,#137836,#137837,#137838, - #137859,#137860,#137861,#137862,#137863,#137864)); -#137833 = ORIENTED_EDGE('',*,*,#137706,.F.); -#137834 = ORIENTED_EDGE('',*,*,#137560,.T.); -#137835 = ORIENTED_EDGE('',*,*,#137487,.T.); -#137836 = ORIENTED_EDGE('',*,*,#137158,.T.); -#137837 = ORIENTED_EDGE('',*,*,#137002,.T.); -#137838 = ORIENTED_EDGE('',*,*,#137839,.T.); -#137839 = EDGE_CURVE('',#136975,#137056,#137840,.T.); -#137840 = SURFACE_CURVE('',#137841,(#137845,#137852),.PCURVE_S1.); -#137841 = LINE('',#137842,#137843); -#137842 = CARTESIAN_POINT('',(4.85,11.,1.159810404338E-002)); -#137843 = VECTOR('',#137844,1.); -#137844 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#137845 = PCURVE('',#87526,#137846); -#137846 = DEFINITIONAL_REPRESENTATION('',(#137847),#137851); -#137847 = LINE('',#137848,#137849); -#137848 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#137849 = VECTOR('',#137850,1.); -#137850 = DIRECTION('',(1.,2.101748079665E-016)); -#137851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137852 = PCURVE('',#136990,#137853); -#137853 = DEFINITIONAL_REPRESENTATION('',(#137854),#137858); -#137854 = LINE('',#137855,#137856); -#137855 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#137856 = VECTOR('',#137857,1.); -#137857 = DIRECTION('',(-1.570395187386E-016,1.)); -#137858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137859 = ORIENTED_EDGE('',*,*,#137053,.F.); -#137860 = ORIENTED_EDGE('',*,*,#137283,.F.); -#137861 = ORIENTED_EDGE('',*,*,#137390,.F.); -#137862 = ORIENTED_EDGE('',*,*,#137585,.F.); -#137863 = ORIENTED_EDGE('',*,*,#137810,.T.); -#137864 = ORIENTED_EDGE('',*,*,#87510,.T.); -#137865 = ADVANCED_FACE('',(#137866),#136990,.T.); -#137866 = FACE_BOUND('',#137867,.T.); -#137867 = EDGE_LOOP('',(#137868,#137869,#137870,#137871)); -#137868 = ORIENTED_EDGE('',*,*,#137083,.F.); -#137869 = ORIENTED_EDGE('',*,*,#137839,.F.); -#137870 = ORIENTED_EDGE('',*,*,#136974,.F.); -#137871 = ORIENTED_EDGE('',*,*,#137777,.F.); -#137872 = ADVANCED_FACE('',(#137873),#137887,.T.); -#137873 = FACE_BOUND('',#137874,.T.); -#137874 = EDGE_LOOP('',(#137875,#137905,#137933,#137956)); -#137875 = ORIENTED_EDGE('',*,*,#137876,.T.); -#137876 = EDGE_CURVE('',#137877,#137879,#137881,.T.); -#137877 = VERTEX_POINT('',#137878); -#137878 = CARTESIAN_POINT('',(8.35,10.740726081328,-0.208196358798)); -#137879 = VERTEX_POINT('',#137880); -#137880 = CARTESIAN_POINT('',(8.35,11.,-0.208196358798)); -#137881 = SURFACE_CURVE('',#137882,(#137886,#137898),.PCURVE_S1.); -#137882 = LINE('',#137883,#137884); -#137883 = CARTESIAN_POINT('',(8.35,10.740726081328,-0.208196358798)); -#137884 = VECTOR('',#137885,1.); -#137885 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137886 = PCURVE('',#137887,#137892); -#137887 = PLANE('',#137888); -#137888 = AXIS2_PLACEMENT_3D('',#137889,#137890,#137891); -#137889 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#137890 = DIRECTION('',(0.E+000,0.E+000,1.)); -#137891 = DIRECTION('',(1.,0.E+000,0.E+000)); -#137892 = DEFINITIONAL_REPRESENTATION('',(#137893),#137897); -#137893 = LINE('',#137894,#137895); -#137894 = CARTESIAN_POINT('',(8.35,-7.105427357601E-015)); -#137895 = VECTOR('',#137896,1.); -#137896 = DIRECTION('',(6.725593854929E-015,1.)); -#137897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137898 = PCURVE('',#87326,#137899); -#137899 = DEFINITIONAL_REPRESENTATION('',(#137900),#137904); -#137900 = LINE('',#137901,#137902); -#137901 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#137902 = VECTOR('',#137903,1.); -#137903 = DIRECTION('',(0.E+000,1.)); -#137904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137905 = ORIENTED_EDGE('',*,*,#137906,.T.); -#137906 = EDGE_CURVE('',#137879,#137907,#137909,.T.); -#137907 = VERTEX_POINT('',#137908); -#137908 = CARTESIAN_POINT('',(8.15,11.,-0.208196358798)); -#137909 = SURFACE_CURVE('',#137910,(#137914,#137921),.PCURVE_S1.); -#137910 = LINE('',#137911,#137912); -#137911 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#137912 = VECTOR('',#137913,1.); -#137913 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#137914 = PCURVE('',#137887,#137915); -#137915 = DEFINITIONAL_REPRESENTATION('',(#137916),#137920); -#137916 = LINE('',#137917,#137918); -#137917 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#137918 = VECTOR('',#137919,1.); -#137919 = DIRECTION('',(-1.,8.881784197001E-016)); -#137920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137921 = PCURVE('',#137922,#137927); -#137922 = PLANE('',#137923); -#137923 = AXIS2_PLACEMENT_3D('',#137924,#137925,#137926); -#137924 = CARTESIAN_POINT('',(8.25,11.,-0.258196742327)); -#137925 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#137926 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#137927 = DEFINITIONAL_REPRESENTATION('',(#137928),#137932); -#137928 = LINE('',#137929,#137930); -#137929 = CARTESIAN_POINT('',(8.25,5.000038352949E-002)); -#137930 = VECTOR('',#137931,1.); -#137931 = DIRECTION('',(1.,1.1653254136E-048)); -#137932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137933 = ORIENTED_EDGE('',*,*,#137934,.F.); -#137934 = EDGE_CURVE('',#137935,#137907,#137937,.T.); -#137935 = VERTEX_POINT('',#137936); -#137936 = CARTESIAN_POINT('',(8.15,10.740726081328,-0.208196358798)); -#137937 = SURFACE_CURVE('',#137938,(#137942,#137949),.PCURVE_S1.); -#137938 = LINE('',#137939,#137940); -#137939 = CARTESIAN_POINT('',(8.15,10.740726081328,-0.208196358798)); -#137940 = VECTOR('',#137941,1.); -#137941 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137942 = PCURVE('',#137887,#137943); -#137943 = DEFINITIONAL_REPRESENTATION('',(#137944),#137948); -#137944 = LINE('',#137945,#137946); -#137945 = CARTESIAN_POINT('',(8.15,-7.105427357601E-015)); -#137946 = VECTOR('',#137947,1.); -#137947 = DIRECTION('',(6.725593854929E-015,1.)); -#137948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137949 = PCURVE('',#87270,#137950); -#137950 = DEFINITIONAL_REPRESENTATION('',(#137951),#137955); -#137951 = LINE('',#137952,#137953); -#137952 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#137953 = VECTOR('',#137954,1.); -#137954 = DIRECTION('',(0.E+000,1.)); -#137955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137956 = ORIENTED_EDGE('',*,*,#137957,.T.); -#137957 = EDGE_CURVE('',#137935,#137877,#137958,.T.); -#137958 = SURFACE_CURVE('',#137959,(#137963,#137970),.PCURVE_S1.); -#137959 = LINE('',#137960,#137961); -#137960 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#137961 = VECTOR('',#137962,1.); -#137962 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137963 = PCURVE('',#137887,#137964); -#137964 = DEFINITIONAL_REPRESENTATION('',(#137965),#137969); -#137965 = LINE('',#137966,#137967); -#137966 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#137967 = VECTOR('',#137968,1.); -#137968 = DIRECTION('',(1.,-8.881784197001E-016)); -#137969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137970 = PCURVE('',#137971,#137976); -#137971 = CYLINDRICAL_SURFACE('',#137972,0.208574704164); -#137972 = AXIS2_PLACEMENT_3D('',#137973,#137974,#137975); -#137973 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, - 2.640924866458E-017)); -#137974 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#137975 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#137976 = DEFINITIONAL_REPRESENTATION('',(#137977),#137980); -#137977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#137978,#137979), - .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#137978 = CARTESIAN_POINT('',(4.772630242227,8.15)); -#137979 = CARTESIAN_POINT('',(4.772630242227,8.35)); -#137980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#137981 = ADVANCED_FACE('',(#137982),#137996,.T.); -#137982 = FACE_BOUND('',#137983,.T.); -#137983 = EDGE_LOOP('',(#137984,#138014,#138037,#138060)); -#137984 = ORIENTED_EDGE('',*,*,#137985,.T.); -#137985 = EDGE_CURVE('',#137986,#137988,#137990,.T.); -#137986 = VERTEX_POINT('',#137987); -#137987 = CARTESIAN_POINT('',(8.15,10.74341632541,-0.308197125857)); -#137988 = VERTEX_POINT('',#137989); -#137989 = CARTESIAN_POINT('',(8.15,11.,-0.308197125857)); -#137990 = SURFACE_CURVE('',#137991,(#137995,#138007),.PCURVE_S1.); -#137991 = LINE('',#137992,#137993); -#137992 = CARTESIAN_POINT('',(8.15,10.74341632541,-0.308197125857)); -#137993 = VECTOR('',#137994,1.); -#137994 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#137995 = PCURVE('',#137996,#138001); -#137996 = PLANE('',#137997); -#137997 = AXIS2_PLACEMENT_3D('',#137998,#137999,#138000); -#137998 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#137999 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138000 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#138001 = DEFINITIONAL_REPRESENTATION('',(#138002),#138006); -#138002 = LINE('',#138003,#138004); -#138003 = CARTESIAN_POINT('',(-8.15,-7.105427357601E-015)); -#138004 = VECTOR('',#138005,1.); -#138005 = DIRECTION('',(-6.725593854929E-015,1.)); -#138006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138007 = PCURVE('',#87270,#138008); -#138008 = DEFINITIONAL_REPRESENTATION('',(#138009),#138013); -#138009 = LINE('',#138010,#138011); -#138010 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#138011 = VECTOR('',#138012,1.); -#138012 = DIRECTION('',(0.E+000,1.)); -#138013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138014 = ORIENTED_EDGE('',*,*,#138015,.T.); -#138015 = EDGE_CURVE('',#137988,#138016,#138018,.T.); -#138016 = VERTEX_POINT('',#138017); -#138017 = CARTESIAN_POINT('',(8.35,11.,-0.308197125857)); -#138018 = SURFACE_CURVE('',#138019,(#138023,#138030),.PCURVE_S1.); -#138019 = LINE('',#138020,#138021); -#138020 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#138021 = VECTOR('',#138022,1.); -#138022 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138023 = PCURVE('',#137996,#138024); -#138024 = DEFINITIONAL_REPRESENTATION('',(#138025),#138029); -#138025 = LINE('',#138026,#138027); -#138026 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#138027 = VECTOR('',#138028,1.); -#138028 = DIRECTION('',(-1.,-8.881784197001E-016)); -#138029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138030 = PCURVE('',#137922,#138031); -#138031 = DEFINITIONAL_REPRESENTATION('',(#138032),#138036); -#138032 = LINE('',#138033,#138034); -#138033 = CARTESIAN_POINT('',(8.25,-5.000038352949E-002)); -#138034 = VECTOR('',#138035,1.); -#138035 = DIRECTION('',(-1.,-1.1653254136E-048)); -#138036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138037 = ORIENTED_EDGE('',*,*,#138038,.F.); -#138038 = EDGE_CURVE('',#138039,#138016,#138041,.T.); -#138039 = VERTEX_POINT('',#138040); -#138040 = CARTESIAN_POINT('',(8.35,10.74341632541,-0.308197125857)); -#138041 = SURFACE_CURVE('',#138042,(#138046,#138053),.PCURVE_S1.); -#138042 = LINE('',#138043,#138044); -#138043 = CARTESIAN_POINT('',(8.35,10.74341632541,-0.308197125857)); -#138044 = VECTOR('',#138045,1.); -#138045 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#138046 = PCURVE('',#137996,#138047); -#138047 = DEFINITIONAL_REPRESENTATION('',(#138048),#138052); -#138048 = LINE('',#138049,#138050); -#138049 = CARTESIAN_POINT('',(-8.35,-7.105427357601E-015)); -#138050 = VECTOR('',#138051,1.); -#138051 = DIRECTION('',(-6.725593854929E-015,1.)); -#138052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138053 = PCURVE('',#87326,#138054); -#138054 = DEFINITIONAL_REPRESENTATION('',(#138055),#138059); -#138055 = LINE('',#138056,#138057); -#138056 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#138057 = VECTOR('',#138058,1.); -#138058 = DIRECTION('',(0.E+000,1.)); -#138059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138060 = ORIENTED_EDGE('',*,*,#138061,.T.); -#138061 = EDGE_CURVE('',#138039,#137986,#138062,.T.); -#138062 = SURFACE_CURVE('',#138063,(#138067,#138074),.PCURVE_S1.); -#138063 = LINE('',#138064,#138065); -#138064 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#138065 = VECTOR('',#138066,1.); -#138066 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138067 = PCURVE('',#137996,#138068); -#138068 = DEFINITIONAL_REPRESENTATION('',(#138069),#138073); -#138069 = LINE('',#138070,#138071); -#138070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138071 = VECTOR('',#138072,1.); -#138072 = DIRECTION('',(1.,8.881784197001E-016)); -#138073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138074 = PCURVE('',#138075,#138080); -#138075 = CYLINDRICAL_SURFACE('',#138076,0.308574064194); -#138076 = AXIS2_PLACEMENT_3D('',#138077,#138078,#138079); -#138077 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#140466 = PCURVE('',#140467,#140472); +#140467 = CYLINDRICAL_SURFACE('',#140468,0.308574064194); +#140468 = AXIS2_PLACEMENT_3D('',#140469,#140470,#140471); +#140469 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#138078 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138079 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138080 = DEFINITIONAL_REPRESENTATION('',(#138081),#138084); -#138081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138082,#138083), +#140470 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140471 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140472 = DEFINITIONAL_REPRESENTATION('',(#140473),#140476); +#140473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140474,#140475), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#138082 = CARTESIAN_POINT('',(4.761821717947,8.35)); -#138083 = CARTESIAN_POINT('',(4.761821717947,8.15)); -#138084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138085 = ADVANCED_FACE('',(#138086),#137971,.F.); -#138086 = FACE_BOUND('',#138087,.F.); -#138087 = EDGE_LOOP('',(#138088,#138089,#138116,#138143)); -#138088 = ORIENTED_EDGE('',*,*,#137957,.T.); -#138089 = ORIENTED_EDGE('',*,*,#138090,.F.); -#138090 = EDGE_CURVE('',#138091,#137877,#138093,.T.); -#138091 = VERTEX_POINT('',#138092); -#138092 = CARTESIAN_POINT('',(8.35,10.51959417205,0.E+000)); -#138093 = SURFACE_CURVE('',#138094,(#138099,#138105),.PCURVE_S1.); -#138094 = CIRCLE('',#138095,0.208574704164); -#138095 = AXIS2_PLACEMENT_3D('',#138096,#138097,#138098); -#138096 = CARTESIAN_POINT('',(8.35,10.728168876214,2.640924866458E-017) - ); -#138097 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138098 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138099 = PCURVE('',#137971,#138100); -#138100 = DEFINITIONAL_REPRESENTATION('',(#138101),#138104); -#138101 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138102,#138103), +#140474 = CARTESIAN_POINT('',(4.761821717947,8.35)); +#140475 = CARTESIAN_POINT('',(4.761821717947,8.15)); +#140476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140477 = ADVANCED_FACE('',(#140478),#140363,.F.); +#140478 = FACE_BOUND('',#140479,.F.); +#140479 = EDGE_LOOP('',(#140480,#140481,#140508,#140535)); +#140480 = ORIENTED_EDGE('',*,*,#140349,.T.); +#140481 = ORIENTED_EDGE('',*,*,#140482,.F.); +#140482 = EDGE_CURVE('',#140483,#140269,#140485,.T.); +#140483 = VERTEX_POINT('',#140484); +#140484 = CARTESIAN_POINT('',(8.35,10.51959417205,0.E+000)); +#140485 = SURFACE_CURVE('',#140486,(#140491,#140497),.PCURVE_S1.); +#140486 = CIRCLE('',#140487,0.208574704164); +#140487 = AXIS2_PLACEMENT_3D('',#140488,#140489,#140490); +#140488 = CARTESIAN_POINT('',(8.35,10.728168876214,2.640924866458E-017) + ); +#140489 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140490 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140491 = PCURVE('',#140363,#140492); +#140492 = DEFINITIONAL_REPRESENTATION('',(#140493),#140496); +#140493 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140494,#140495), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#138102 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#138103 = CARTESIAN_POINT('',(4.772630242227,8.35)); -#138104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140494 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#140495 = CARTESIAN_POINT('',(4.772630242227,8.35)); +#140496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138105 = PCURVE('',#87326,#138106); -#138106 = DEFINITIONAL_REPRESENTATION('',(#138107),#138115); -#138107 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138108,#138109,#138110, - #138111,#138112,#138113,#138114),.UNSPECIFIED.,.T.,.F.) +#140497 = PCURVE('',#89718,#140498); +#140498 = DEFINITIONAL_REPRESENTATION('',(#140499),#140507); +#140499 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140500,#140501,#140502, + #140503,#140504,#140505,#140506),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#138108 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#138109 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#138110 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#138111 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#138112 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#138113 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#138114 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#138115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138116 = ORIENTED_EDGE('',*,*,#138117,.T.); -#138117 = EDGE_CURVE('',#138091,#138118,#138120,.T.); -#138118 = VERTEX_POINT('',#138119); -#138119 = CARTESIAN_POINT('',(8.15,10.51959417205,0.E+000)); -#138120 = SURFACE_CURVE('',#138121,(#138125,#138131),.PCURVE_S1.); -#138121 = LINE('',#138122,#138123); -#138122 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#140500 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#140501 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#140502 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#140503 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#140504 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#140505 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#140506 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#140507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140508 = ORIENTED_EDGE('',*,*,#140509,.T.); +#140509 = EDGE_CURVE('',#140483,#140510,#140512,.T.); +#140510 = VERTEX_POINT('',#140511); +#140511 = CARTESIAN_POINT('',(8.15,10.51959417205,0.E+000)); +#140512 = SURFACE_CURVE('',#140513,(#140517,#140523),.PCURVE_S1.); +#140513 = LINE('',#140514,#140515); +#140514 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#138123 = VECTOR('',#138124,1.); -#138124 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138125 = PCURVE('',#137971,#138126); -#138126 = DEFINITIONAL_REPRESENTATION('',(#138127),#138130); -#138127 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138128,#138129), +#140515 = VECTOR('',#140516,1.); +#140516 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140517 = PCURVE('',#140363,#140518); +#140518 = DEFINITIONAL_REPRESENTATION('',(#140519),#140522); +#140519 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140520,#140521), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#138128 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#138129 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#138130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140520 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#140521 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#140522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138131 = PCURVE('',#138132,#138137); -#138132 = PLANE('',#138133); -#138133 = AXIS2_PLACEMENT_3D('',#138134,#138135,#138136); -#138134 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#140523 = PCURVE('',#140524,#140529); +#140524 = PLANE('',#140525); +#140525 = AXIS2_PLACEMENT_3D('',#140526,#140527,#140528); +#140526 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#138135 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138136 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138137 = DEFINITIONAL_REPRESENTATION('',(#138138),#138142); -#138138 = LINE('',#138139,#138140); -#138139 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#138140 = VECTOR('',#138141,1.); -#138141 = DIRECTION('',(-1.,0.E+000)); -#138142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138143 = ORIENTED_EDGE('',*,*,#138144,.T.); -#138144 = EDGE_CURVE('',#138118,#137935,#138145,.T.); -#138145 = SURFACE_CURVE('',#138146,(#138151,#138157),.PCURVE_S1.); -#138146 = CIRCLE('',#138147,0.208574704164); -#138147 = AXIS2_PLACEMENT_3D('',#138148,#138149,#138150); -#138148 = CARTESIAN_POINT('',(8.15,10.728168876214,2.640924866458E-017) - ); -#138149 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138150 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138151 = PCURVE('',#137971,#138152); -#138152 = DEFINITIONAL_REPRESENTATION('',(#138153),#138156); -#138153 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138154,#138155), +#140527 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140528 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140529 = DEFINITIONAL_REPRESENTATION('',(#140530),#140534); +#140530 = LINE('',#140531,#140532); +#140531 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#140532 = VECTOR('',#140533,1.); +#140533 = DIRECTION('',(-1.,0.E+000)); +#140534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140535 = ORIENTED_EDGE('',*,*,#140536,.T.); +#140536 = EDGE_CURVE('',#140510,#140327,#140537,.T.); +#140537 = SURFACE_CURVE('',#140538,(#140543,#140549),.PCURVE_S1.); +#140538 = CIRCLE('',#140539,0.208574704164); +#140539 = AXIS2_PLACEMENT_3D('',#140540,#140541,#140542); +#140540 = CARTESIAN_POINT('',(8.15,10.728168876214,2.640924866458E-017) + ); +#140541 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140542 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140543 = PCURVE('',#140363,#140544); +#140544 = DEFINITIONAL_REPRESENTATION('',(#140545),#140548); +#140545 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140546,#140547), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#138154 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#138155 = CARTESIAN_POINT('',(4.772630242227,8.15)); -#138156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138157 = PCURVE('',#87270,#138158); -#138158 = DEFINITIONAL_REPRESENTATION('',(#138159),#138163); -#138159 = CIRCLE('',#138160,0.208574704164); -#138160 = AXIS2_PLACEMENT_2D('',#138161,#138162); -#138161 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#138162 = DIRECTION('',(0.E+000,1.)); -#138163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138164 = ADVANCED_FACE('',(#138165),#138075,.T.); -#138165 = FACE_BOUND('',#138166,.T.); -#138166 = EDGE_LOOP('',(#138167,#138168,#138195,#138222)); -#138167 = ORIENTED_EDGE('',*,*,#138061,.F.); -#138168 = ORIENTED_EDGE('',*,*,#138169,.F.); -#138169 = EDGE_CURVE('',#138170,#138039,#138172,.T.); -#138170 = VERTEX_POINT('',#138171); -#138171 = CARTESIAN_POINT('',(8.35,10.419594812019,0.E+000)); -#138172 = SURFACE_CURVE('',#138173,(#138178,#138184),.PCURVE_S1.); -#138173 = CIRCLE('',#138174,0.308574064194); -#138174 = AXIS2_PLACEMENT_3D('',#138175,#138176,#138177); -#138175 = CARTESIAN_POINT('',(8.35,10.728168876214,2.640924866458E-017) - ); -#138176 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138177 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138178 = PCURVE('',#138075,#138179); -#138179 = DEFINITIONAL_REPRESENTATION('',(#138180),#138183); -#138180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138181,#138182), +#140546 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#140547 = CARTESIAN_POINT('',(4.772630242227,8.15)); +#140548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140549 = PCURVE('',#89662,#140550); +#140550 = DEFINITIONAL_REPRESENTATION('',(#140551),#140555); +#140551 = CIRCLE('',#140552,0.208574704164); +#140552 = AXIS2_PLACEMENT_2D('',#140553,#140554); +#140553 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#140554 = DIRECTION('',(0.E+000,1.)); +#140555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140556 = ADVANCED_FACE('',(#140557),#140467,.T.); +#140557 = FACE_BOUND('',#140558,.T.); +#140558 = EDGE_LOOP('',(#140559,#140560,#140587,#140614)); +#140559 = ORIENTED_EDGE('',*,*,#140453,.F.); +#140560 = ORIENTED_EDGE('',*,*,#140561,.F.); +#140561 = EDGE_CURVE('',#140562,#140431,#140564,.T.); +#140562 = VERTEX_POINT('',#140563); +#140563 = CARTESIAN_POINT('',(8.35,10.419594812019,0.E+000)); +#140564 = SURFACE_CURVE('',#140565,(#140570,#140576),.PCURVE_S1.); +#140565 = CIRCLE('',#140566,0.308574064194); +#140566 = AXIS2_PLACEMENT_3D('',#140567,#140568,#140569); +#140567 = CARTESIAN_POINT('',(8.35,10.728168876214,2.640924866458E-017) + ); +#140568 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140569 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140570 = PCURVE('',#140467,#140571); +#140571 = DEFINITIONAL_REPRESENTATION('',(#140572),#140575); +#140572 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140573,#140574), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#138181 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#138182 = CARTESIAN_POINT('',(4.761821717947,8.35)); -#138183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140573 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#140574 = CARTESIAN_POINT('',(4.761821717947,8.35)); +#140575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138184 = PCURVE('',#87326,#138185); -#138185 = DEFINITIONAL_REPRESENTATION('',(#138186),#138194); -#138186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138187,#138188,#138189, - #138190,#138191,#138192,#138193),.UNSPECIFIED.,.T.,.F.) +#140576 = PCURVE('',#89718,#140577); +#140577 = DEFINITIONAL_REPRESENTATION('',(#140578),#140586); +#140578 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140579,#140580,#140581, + #140582,#140583,#140584,#140585),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#138187 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#138188 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#138189 = CARTESIAN_POINT('',(-0.382767021459,4.603385167789E-002)); -#138190 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#138191 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#138192 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#138193 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#138194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138195 = ORIENTED_EDGE('',*,*,#138196,.F.); -#138196 = EDGE_CURVE('',#138197,#138170,#138199,.T.); -#138197 = VERTEX_POINT('',#138198); -#138198 = CARTESIAN_POINT('',(8.15,10.419594812019,0.E+000)); -#138199 = SURFACE_CURVE('',#138200,(#138204,#138210),.PCURVE_S1.); -#138200 = LINE('',#138201,#138202); -#138201 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#140579 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#140580 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#140581 = CARTESIAN_POINT('',(-0.382767021459,4.603385167789E-002)); +#140582 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#140583 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#140584 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#140585 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#140586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140587 = ORIENTED_EDGE('',*,*,#140588,.F.); +#140588 = EDGE_CURVE('',#140589,#140562,#140591,.T.); +#140589 = VERTEX_POINT('',#140590); +#140590 = CARTESIAN_POINT('',(8.15,10.419594812019,0.E+000)); +#140591 = SURFACE_CURVE('',#140592,(#140596,#140602),.PCURVE_S1.); +#140592 = LINE('',#140593,#140594); +#140593 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#138202 = VECTOR('',#138203,1.); -#138203 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138204 = PCURVE('',#138075,#138205); -#138205 = DEFINITIONAL_REPRESENTATION('',(#138206),#138209); -#138206 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138207,#138208), +#140594 = VECTOR('',#140595,1.); +#140595 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140596 = PCURVE('',#140467,#140597); +#140597 = DEFINITIONAL_REPRESENTATION('',(#140598),#140601); +#140598 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140599,#140600), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#138207 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#138208 = CARTESIAN_POINT('',(3.14159265359,8.35)); -#138209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140599 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#140600 = CARTESIAN_POINT('',(3.14159265359,8.35)); +#140601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138210 = PCURVE('',#138211,#138216); -#138211 = PLANE('',#138212); -#138212 = AXIS2_PLACEMENT_3D('',#138213,#138214,#138215); -#138213 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#140602 = PCURVE('',#140603,#140608); +#140603 = PLANE('',#140604); +#140604 = AXIS2_PLACEMENT_3D('',#140605,#140606,#140607); +#140605 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#138214 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138215 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138216 = DEFINITIONAL_REPRESENTATION('',(#138217),#138221); -#138217 = LINE('',#138218,#138219); -#138218 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#138219 = VECTOR('',#138220,1.); -#138220 = DIRECTION('',(-1.,0.E+000)); -#138221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138222 = ORIENTED_EDGE('',*,*,#138223,.T.); -#138223 = EDGE_CURVE('',#138197,#137986,#138224,.T.); -#138224 = SURFACE_CURVE('',#138225,(#138230,#138236),.PCURVE_S1.); -#138225 = CIRCLE('',#138226,0.308574064194); -#138226 = AXIS2_PLACEMENT_3D('',#138227,#138228,#138229); -#138227 = CARTESIAN_POINT('',(8.15,10.728168876214,2.640924866458E-017) - ); -#138228 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138229 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138230 = PCURVE('',#138075,#138231); -#138231 = DEFINITIONAL_REPRESENTATION('',(#138232),#138235); -#138232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138233,#138234), +#140606 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140607 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140608 = DEFINITIONAL_REPRESENTATION('',(#140609),#140613); +#140609 = LINE('',#140610,#140611); +#140610 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#140611 = VECTOR('',#140612,1.); +#140612 = DIRECTION('',(-1.,0.E+000)); +#140613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140614 = ORIENTED_EDGE('',*,*,#140615,.T.); +#140615 = EDGE_CURVE('',#140589,#140378,#140616,.T.); +#140616 = SURFACE_CURVE('',#140617,(#140622,#140628),.PCURVE_S1.); +#140617 = CIRCLE('',#140618,0.308574064194); +#140618 = AXIS2_PLACEMENT_3D('',#140619,#140620,#140621); +#140619 = CARTESIAN_POINT('',(8.15,10.728168876214,2.640924866458E-017) + ); +#140620 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140621 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#140622 = PCURVE('',#140467,#140623); +#140623 = DEFINITIONAL_REPRESENTATION('',(#140624),#140627); +#140624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140625,#140626), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.761821717947), .PIECEWISE_BEZIER_KNOTS.); -#138233 = CARTESIAN_POINT('',(3.14159265359,8.15)); -#138234 = CARTESIAN_POINT('',(4.761821717947,8.15)); -#138235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138236 = PCURVE('',#87270,#138237); -#138237 = DEFINITIONAL_REPRESENTATION('',(#138238),#138242); -#138238 = CIRCLE('',#138239,0.308574064194); -#138239 = AXIS2_PLACEMENT_2D('',#138240,#138241); -#138240 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#138241 = DIRECTION('',(0.E+000,1.)); -#138242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138243 = ADVANCED_FACE('',(#138244),#138211,.F.); -#138244 = FACE_BOUND('',#138245,.T.); -#138245 = EDGE_LOOP('',(#138246,#138275,#138296,#138297)); -#138246 = ORIENTED_EDGE('',*,*,#138247,.F.); -#138247 = EDGE_CURVE('',#138248,#138250,#138252,.T.); -#138248 = VERTEX_POINT('',#138249); -#138249 = CARTESIAN_POINT('',(8.15,10.419594812019,0.530776333563)); -#138250 = VERTEX_POINT('',#138251); -#138251 = CARTESIAN_POINT('',(8.35,10.419594812019,0.530776333563)); -#138252 = SURFACE_CURVE('',#138253,(#138257,#138264),.PCURVE_S1.); -#138253 = LINE('',#138254,#138255); -#138254 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#140625 = CARTESIAN_POINT('',(3.14159265359,8.15)); +#140626 = CARTESIAN_POINT('',(4.761821717947,8.15)); +#140627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140628 = PCURVE('',#89662,#140629); +#140629 = DEFINITIONAL_REPRESENTATION('',(#140630),#140634); +#140630 = CIRCLE('',#140631,0.308574064194); +#140631 = AXIS2_PLACEMENT_2D('',#140632,#140633); +#140632 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#140633 = DIRECTION('',(0.E+000,1.)); +#140634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140635 = ADVANCED_FACE('',(#140636),#140603,.F.); +#140636 = FACE_BOUND('',#140637,.T.); +#140637 = EDGE_LOOP('',(#140638,#140667,#140688,#140689)); +#140638 = ORIENTED_EDGE('',*,*,#140639,.F.); +#140639 = EDGE_CURVE('',#140640,#140642,#140644,.T.); +#140640 = VERTEX_POINT('',#140641); +#140641 = CARTESIAN_POINT('',(8.15,10.419594812019,0.530776333563)); +#140642 = VERTEX_POINT('',#140643); +#140643 = CARTESIAN_POINT('',(8.35,10.419594812019,0.530776333563)); +#140644 = SURFACE_CURVE('',#140645,(#140649,#140656),.PCURVE_S1.); +#140645 = LINE('',#140646,#140647); +#140646 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#138255 = VECTOR('',#138256,1.); -#138256 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138257 = PCURVE('',#138211,#138258); -#138258 = DEFINITIONAL_REPRESENTATION('',(#138259),#138263); -#138259 = LINE('',#138260,#138261); -#138260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138261 = VECTOR('',#138262,1.); -#138262 = DIRECTION('',(-1.,0.E+000)); -#138263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138264 = PCURVE('',#138265,#138270); -#138265 = CYLINDRICAL_SURFACE('',#138266,0.119270391569); -#138266 = AXIS2_PLACEMENT_3D('',#138267,#138268,#138269); -#138267 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#140647 = VECTOR('',#140648,1.); +#140648 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140649 = PCURVE('',#140603,#140650); +#140650 = DEFINITIONAL_REPRESENTATION('',(#140651),#140655); +#140651 = LINE('',#140652,#140653); +#140652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140653 = VECTOR('',#140654,1.); +#140654 = DIRECTION('',(-1.,0.E+000)); +#140655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140656 = PCURVE('',#140657,#140662); +#140657 = CYLINDRICAL_SURFACE('',#140658,0.119270391569); +#140658 = AXIS2_PLACEMENT_3D('',#140659,#140660,#140661); +#140659 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#138268 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138269 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138270 = DEFINITIONAL_REPRESENTATION('',(#138271),#138274); -#138271 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138272,#138273), +#140660 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140661 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140662 = DEFINITIONAL_REPRESENTATION('',(#140663),#140666); +#140663 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140664,#140665), .UNSPECIFIED.,.F.,.F.,(2,2),(8.15,8.35),.PIECEWISE_BEZIER_KNOTS.); -#138272 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#138273 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#138274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138275 = ORIENTED_EDGE('',*,*,#138276,.T.); -#138276 = EDGE_CURVE('',#138248,#138197,#138277,.T.); -#138277 = SURFACE_CURVE('',#138278,(#138282,#138289),.PCURVE_S1.); -#138278 = LINE('',#138279,#138280); -#138279 = CARTESIAN_POINT('',(8.15,10.419594812019,0.530776333563)); -#138280 = VECTOR('',#138281,1.); -#138281 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138282 = PCURVE('',#138211,#138283); -#138283 = DEFINITIONAL_REPRESENTATION('',(#138284),#138288); -#138284 = LINE('',#138285,#138286); -#138285 = CARTESIAN_POINT('',(-8.15,0.E+000)); -#138286 = VECTOR('',#138287,1.); -#138287 = DIRECTION('',(0.E+000,-1.)); -#138288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138289 = PCURVE('',#87270,#138290); -#138290 = DEFINITIONAL_REPRESENTATION('',(#138291),#138295); -#138291 = LINE('',#138292,#138293); -#138292 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#138293 = VECTOR('',#138294,1.); -#138294 = DIRECTION('',(1.,0.E+000)); -#138295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138296 = ORIENTED_EDGE('',*,*,#138196,.T.); -#138297 = ORIENTED_EDGE('',*,*,#138298,.F.); -#138298 = EDGE_CURVE('',#138250,#138170,#138299,.T.); -#138299 = SURFACE_CURVE('',#138300,(#138304,#138311),.PCURVE_S1.); -#138300 = LINE('',#138301,#138302); -#138301 = CARTESIAN_POINT('',(8.35,10.419594812019,0.530776333563)); -#138302 = VECTOR('',#138303,1.); -#138303 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138304 = PCURVE('',#138211,#138305); -#138305 = DEFINITIONAL_REPRESENTATION('',(#138306),#138310); -#138306 = LINE('',#138307,#138308); -#138307 = CARTESIAN_POINT('',(-8.35,0.E+000)); -#138308 = VECTOR('',#138309,1.); -#138309 = DIRECTION('',(0.E+000,-1.)); -#138310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138311 = PCURVE('',#87326,#138312); -#138312 = DEFINITIONAL_REPRESENTATION('',(#138313),#138317); -#138313 = LINE('',#138314,#138315); -#138314 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#138315 = VECTOR('',#138316,1.); -#138316 = DIRECTION('',(-1.,0.E+000)); -#138317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138318 = ADVANCED_FACE('',(#138319),#138132,.F.); -#138319 = FACE_BOUND('',#138320,.T.); -#138320 = EDGE_LOOP('',(#138321,#138350,#138371,#138372)); -#138321 = ORIENTED_EDGE('',*,*,#138322,.F.); -#138322 = EDGE_CURVE('',#138323,#138325,#138327,.T.); -#138323 = VERTEX_POINT('',#138324); -#138324 = CARTESIAN_POINT('',(8.35,10.51959417205,0.530776333563)); -#138325 = VERTEX_POINT('',#138326); -#138326 = CARTESIAN_POINT('',(8.15,10.51959417205,0.530776333563)); -#138327 = SURFACE_CURVE('',#138328,(#138332,#138339),.PCURVE_S1.); -#138328 = LINE('',#138329,#138330); -#138329 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#140664 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#140665 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#140666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140667 = ORIENTED_EDGE('',*,*,#140668,.T.); +#140668 = EDGE_CURVE('',#140640,#140589,#140669,.T.); +#140669 = SURFACE_CURVE('',#140670,(#140674,#140681),.PCURVE_S1.); +#140670 = LINE('',#140671,#140672); +#140671 = CARTESIAN_POINT('',(8.15,10.419594812019,0.530776333563)); +#140672 = VECTOR('',#140673,1.); +#140673 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#140674 = PCURVE('',#140603,#140675); +#140675 = DEFINITIONAL_REPRESENTATION('',(#140676),#140680); +#140676 = LINE('',#140677,#140678); +#140677 = CARTESIAN_POINT('',(-8.15,0.E+000)); +#140678 = VECTOR('',#140679,1.); +#140679 = DIRECTION('',(0.E+000,-1.)); +#140680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140681 = PCURVE('',#89662,#140682); +#140682 = DEFINITIONAL_REPRESENTATION('',(#140683),#140687); +#140683 = LINE('',#140684,#140685); +#140684 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#140685 = VECTOR('',#140686,1.); +#140686 = DIRECTION('',(1.,0.E+000)); +#140687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140688 = ORIENTED_EDGE('',*,*,#140588,.T.); +#140689 = ORIENTED_EDGE('',*,*,#140690,.F.); +#140690 = EDGE_CURVE('',#140642,#140562,#140691,.T.); +#140691 = SURFACE_CURVE('',#140692,(#140696,#140703),.PCURVE_S1.); +#140692 = LINE('',#140693,#140694); +#140693 = CARTESIAN_POINT('',(8.35,10.419594812019,0.530776333563)); +#140694 = VECTOR('',#140695,1.); +#140695 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#140696 = PCURVE('',#140603,#140697); +#140697 = DEFINITIONAL_REPRESENTATION('',(#140698),#140702); +#140698 = LINE('',#140699,#140700); +#140699 = CARTESIAN_POINT('',(-8.35,0.E+000)); +#140700 = VECTOR('',#140701,1.); +#140701 = DIRECTION('',(0.E+000,-1.)); +#140702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140703 = PCURVE('',#89718,#140704); +#140704 = DEFINITIONAL_REPRESENTATION('',(#140705),#140709); +#140705 = LINE('',#140706,#140707); +#140706 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#140707 = VECTOR('',#140708,1.); +#140708 = DIRECTION('',(-1.,0.E+000)); +#140709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140710 = ADVANCED_FACE('',(#140711),#140524,.F.); +#140711 = FACE_BOUND('',#140712,.T.); +#140712 = EDGE_LOOP('',(#140713,#140742,#140763,#140764)); +#140713 = ORIENTED_EDGE('',*,*,#140714,.F.); +#140714 = EDGE_CURVE('',#140715,#140717,#140719,.T.); +#140715 = VERTEX_POINT('',#140716); +#140716 = CARTESIAN_POINT('',(8.35,10.51959417205,0.530776333563)); +#140717 = VERTEX_POINT('',#140718); +#140718 = CARTESIAN_POINT('',(8.15,10.51959417205,0.530776333563)); +#140719 = SURFACE_CURVE('',#140720,(#140724,#140731),.PCURVE_S1.); +#140720 = LINE('',#140721,#140722); +#140721 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#138330 = VECTOR('',#138331,1.); -#138331 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138332 = PCURVE('',#138132,#138333); -#138333 = DEFINITIONAL_REPRESENTATION('',(#138334),#138338); -#138334 = LINE('',#138335,#138336); -#138335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138336 = VECTOR('',#138337,1.); -#138337 = DIRECTION('',(-1.,0.E+000)); -#138338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138339 = PCURVE('',#138340,#138345); -#138340 = CYLINDRICAL_SURFACE('',#138341,0.2192697516); -#138341 = AXIS2_PLACEMENT_3D('',#138342,#138343,#138344); -#138342 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#140722 = VECTOR('',#140723,1.); +#140723 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140724 = PCURVE('',#140524,#140725); +#140725 = DEFINITIONAL_REPRESENTATION('',(#140726),#140730); +#140726 = LINE('',#140727,#140728); +#140727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140728 = VECTOR('',#140729,1.); +#140729 = DIRECTION('',(-1.,0.E+000)); +#140730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140731 = PCURVE('',#140732,#140737); +#140732 = CYLINDRICAL_SURFACE('',#140733,0.2192697516); +#140733 = AXIS2_PLACEMENT_3D('',#140734,#140735,#140736); +#140734 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#138343 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138344 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138345 = DEFINITIONAL_REPRESENTATION('',(#138346),#138349); -#138346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138347,#138348), +#140735 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140736 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140737 = DEFINITIONAL_REPRESENTATION('',(#140738),#140741); +#140738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140739,#140740), .UNSPECIFIED.,.F.,.F.,(2,2),(-8.35,-8.15),.PIECEWISE_BEZIER_KNOTS.); -#138347 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#138348 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#138349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138350 = ORIENTED_EDGE('',*,*,#138351,.T.); -#138351 = EDGE_CURVE('',#138323,#138091,#138352,.T.); -#138352 = SURFACE_CURVE('',#138353,(#138357,#138364),.PCURVE_S1.); -#138353 = LINE('',#138354,#138355); -#138354 = CARTESIAN_POINT('',(8.35,10.51959417205,0.530776333563)); -#138355 = VECTOR('',#138356,1.); -#138356 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138357 = PCURVE('',#138132,#138358); -#138358 = DEFINITIONAL_REPRESENTATION('',(#138359),#138363); -#138359 = LINE('',#138360,#138361); -#138360 = CARTESIAN_POINT('',(8.35,0.E+000)); -#138361 = VECTOR('',#138362,1.); -#138362 = DIRECTION('',(0.E+000,-1.)); -#138363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138364 = PCURVE('',#87326,#138365); -#138365 = DEFINITIONAL_REPRESENTATION('',(#138366),#138370); -#138366 = LINE('',#138367,#138368); -#138367 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388626E-003)); -#138368 = VECTOR('',#138369,1.); -#138369 = DIRECTION('',(-1.,0.E+000)); -#138370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138371 = ORIENTED_EDGE('',*,*,#138117,.T.); -#138372 = ORIENTED_EDGE('',*,*,#138373,.F.); -#138373 = EDGE_CURVE('',#138325,#138118,#138374,.T.); -#138374 = SURFACE_CURVE('',#138375,(#138379,#138386),.PCURVE_S1.); -#138375 = LINE('',#138376,#138377); -#138376 = CARTESIAN_POINT('',(8.15,10.51959417205,0.530776333563)); -#138377 = VECTOR('',#138378,1.); -#138378 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138379 = PCURVE('',#138132,#138380); -#138380 = DEFINITIONAL_REPRESENTATION('',(#138381),#138385); -#138381 = LINE('',#138382,#138383); -#138382 = CARTESIAN_POINT('',(8.15,0.E+000)); -#138383 = VECTOR('',#138384,1.); -#138384 = DIRECTION('',(0.E+000,-1.)); -#138385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138386 = PCURVE('',#87270,#138387); -#138387 = DEFINITIONAL_REPRESENTATION('',(#138388),#138392); -#138388 = LINE('',#138389,#138390); -#138389 = CARTESIAN_POINT('',(0.119223666437,-8.253820388626E-003)); -#138390 = VECTOR('',#138391,1.); -#138391 = DIRECTION('',(1.,0.E+000)); -#138392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138393 = ADVANCED_FACE('',(#138394),#138265,.F.); -#138394 = FACE_BOUND('',#138395,.F.); -#138395 = EDGE_LOOP('',(#138396,#138423,#138445,#138466)); -#138396 = ORIENTED_EDGE('',*,*,#138397,.F.); -#138397 = EDGE_CURVE('',#138398,#138248,#138400,.T.); -#138398 = VERTEX_POINT('',#138399); -#138399 = CARTESIAN_POINT('',(8.15,10.303662633502,0.65)); -#138400 = SURFACE_CURVE('',#138401,(#138406,#138412),.PCURVE_S1.); -#138401 = CIRCLE('',#138402,0.119270391569); -#138402 = AXIS2_PLACEMENT_3D('',#138403,#138404,#138405); -#138403 = CARTESIAN_POINT('',(8.15,10.30032442045,0.530776333563)); -#138404 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138405 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138406 = PCURVE('',#138265,#138407); -#138407 = DEFINITIONAL_REPRESENTATION('',(#138408),#138411); -#138408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138409,#138410), +#140739 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#140740 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#140741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140742 = ORIENTED_EDGE('',*,*,#140743,.T.); +#140743 = EDGE_CURVE('',#140715,#140483,#140744,.T.); +#140744 = SURFACE_CURVE('',#140745,(#140749,#140756),.PCURVE_S1.); +#140745 = LINE('',#140746,#140747); +#140746 = CARTESIAN_POINT('',(8.35,10.51959417205,0.530776333563)); +#140747 = VECTOR('',#140748,1.); +#140748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#140749 = PCURVE('',#140524,#140750); +#140750 = DEFINITIONAL_REPRESENTATION('',(#140751),#140755); +#140751 = LINE('',#140752,#140753); +#140752 = CARTESIAN_POINT('',(8.35,0.E+000)); +#140753 = VECTOR('',#140754,1.); +#140754 = DIRECTION('',(0.E+000,-1.)); +#140755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140756 = PCURVE('',#89718,#140757); +#140757 = DEFINITIONAL_REPRESENTATION('',(#140758),#140762); +#140758 = LINE('',#140759,#140760); +#140759 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388626E-003)); +#140760 = VECTOR('',#140761,1.); +#140761 = DIRECTION('',(-1.,0.E+000)); +#140762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140763 = ORIENTED_EDGE('',*,*,#140509,.T.); +#140764 = ORIENTED_EDGE('',*,*,#140765,.F.); +#140765 = EDGE_CURVE('',#140717,#140510,#140766,.T.); +#140766 = SURFACE_CURVE('',#140767,(#140771,#140778),.PCURVE_S1.); +#140767 = LINE('',#140768,#140769); +#140768 = CARTESIAN_POINT('',(8.15,10.51959417205,0.530776333563)); +#140769 = VECTOR('',#140770,1.); +#140770 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#140771 = PCURVE('',#140524,#140772); +#140772 = DEFINITIONAL_REPRESENTATION('',(#140773),#140777); +#140773 = LINE('',#140774,#140775); +#140774 = CARTESIAN_POINT('',(8.15,0.E+000)); +#140775 = VECTOR('',#140776,1.); +#140776 = DIRECTION('',(0.E+000,-1.)); +#140777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140778 = PCURVE('',#89662,#140779); +#140779 = DEFINITIONAL_REPRESENTATION('',(#140780),#140784); +#140780 = LINE('',#140781,#140782); +#140781 = CARTESIAN_POINT('',(0.119223666437,-8.253820388626E-003)); +#140782 = VECTOR('',#140783,1.); +#140783 = DIRECTION('',(1.,0.E+000)); +#140784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140785 = ADVANCED_FACE('',(#140786),#140657,.F.); +#140786 = FACE_BOUND('',#140787,.F.); +#140787 = EDGE_LOOP('',(#140788,#140815,#140837,#140858)); +#140788 = ORIENTED_EDGE('',*,*,#140789,.F.); +#140789 = EDGE_CURVE('',#140790,#140640,#140792,.T.); +#140790 = VERTEX_POINT('',#140791); +#140791 = CARTESIAN_POINT('',(8.15,10.303662633502,0.65)); +#140792 = SURFACE_CURVE('',#140793,(#140798,#140804),.PCURVE_S1.); +#140793 = CIRCLE('',#140794,0.119270391569); +#140794 = AXIS2_PLACEMENT_3D('',#140795,#140796,#140797); +#140795 = CARTESIAN_POINT('',(8.15,10.30032442045,0.530776333563)); +#140796 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140797 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140798 = PCURVE('',#140657,#140799); +#140799 = DEFINITIONAL_REPRESENTATION('',(#140800),#140803); +#140800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140801,#140802), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#138409 = CARTESIAN_POINT('',(1.598788597134,-8.15)); -#138410 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#138411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140801 = CARTESIAN_POINT('',(1.598788597134,-8.15)); +#140802 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#140803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138412 = PCURVE('',#87270,#138413); -#138413 = DEFINITIONAL_REPRESENTATION('',(#138414),#138422); -#138414 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138415,#138416,#138417, - #138418,#138419,#138420,#138421),.UNSPECIFIED.,.T.,.F.) +#140804 = PCURVE('',#89662,#140805); +#140805 = DEFINITIONAL_REPRESENTATION('',(#140806),#140814); +#140806 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140807,#140808,#140809, + #140810,#140811,#140812,#140813),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#138415 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#138416 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#138417 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#138418 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#138419 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#138420 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#138421 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#138422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138423 = ORIENTED_EDGE('',*,*,#138424,.F.); -#138424 = EDGE_CURVE('',#138425,#138398,#138427,.T.); -#138425 = VERTEX_POINT('',#138426); -#138426 = CARTESIAN_POINT('',(8.35,10.303662633502,0.65)); -#138427 = SURFACE_CURVE('',#138428,(#138432,#138438),.PCURVE_S1.); -#138428 = LINE('',#138429,#138430); -#138429 = CARTESIAN_POINT('',(8.15,10.303662633502,0.65)); -#138430 = VECTOR('',#138431,1.); -#138431 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138432 = PCURVE('',#138265,#138433); -#138433 = DEFINITIONAL_REPRESENTATION('',(#138434),#138437); -#138434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138435,#138436), +#140807 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#140808 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#140809 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#140810 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#140811 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#140812 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#140813 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#140814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140815 = ORIENTED_EDGE('',*,*,#140816,.F.); +#140816 = EDGE_CURVE('',#140817,#140790,#140819,.T.); +#140817 = VERTEX_POINT('',#140818); +#140818 = CARTESIAN_POINT('',(8.35,10.303662633502,0.65)); +#140819 = SURFACE_CURVE('',#140820,(#140824,#140830),.PCURVE_S1.); +#140820 = LINE('',#140821,#140822); +#140821 = CARTESIAN_POINT('',(8.15,10.303662633502,0.65)); +#140822 = VECTOR('',#140823,1.); +#140823 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140824 = PCURVE('',#140657,#140825); +#140825 = DEFINITIONAL_REPRESENTATION('',(#140826),#140829); +#140826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140827,#140828), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#138435 = CARTESIAN_POINT('',(1.598788597134,-8.35)); -#138436 = CARTESIAN_POINT('',(1.598788597134,-8.15)); -#138437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138438 = PCURVE('',#87298,#138439); -#138439 = DEFINITIONAL_REPRESENTATION('',(#138440),#138444); -#138440 = LINE('',#138441,#138442); -#138441 = CARTESIAN_POINT('',(0.224185358936,-9.853387059449E-048)); -#138442 = VECTOR('',#138443,1.); -#138443 = DIRECTION('',(-8.881784197001E-016,-1.)); -#138444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138445 = ORIENTED_EDGE('',*,*,#138446,.T.); -#138446 = EDGE_CURVE('',#138425,#138250,#138447,.T.); -#138447 = SURFACE_CURVE('',#138448,(#138453,#138459),.PCURVE_S1.); -#138448 = CIRCLE('',#138449,0.119270391569); -#138449 = AXIS2_PLACEMENT_3D('',#138450,#138451,#138452); -#138450 = CARTESIAN_POINT('',(8.35,10.30032442045,0.530776333563)); -#138451 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138452 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138453 = PCURVE('',#138265,#138454); -#138454 = DEFINITIONAL_REPRESENTATION('',(#138455),#138458); -#138455 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138456,#138457), +#140827 = CARTESIAN_POINT('',(1.598788597134,-8.35)); +#140828 = CARTESIAN_POINT('',(1.598788597134,-8.15)); +#140829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140830 = PCURVE('',#89690,#140831); +#140831 = DEFINITIONAL_REPRESENTATION('',(#140832),#140836); +#140832 = LINE('',#140833,#140834); +#140833 = CARTESIAN_POINT('',(0.224185358936,-9.853387059449E-048)); +#140834 = VECTOR('',#140835,1.); +#140835 = DIRECTION('',(-8.881784197001E-016,-1.)); +#140836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140837 = ORIENTED_EDGE('',*,*,#140838,.T.); +#140838 = EDGE_CURVE('',#140817,#140642,#140839,.T.); +#140839 = SURFACE_CURVE('',#140840,(#140845,#140851),.PCURVE_S1.); +#140840 = CIRCLE('',#140841,0.119270391569); +#140841 = AXIS2_PLACEMENT_3D('',#140842,#140843,#140844); +#140842 = CARTESIAN_POINT('',(8.35,10.30032442045,0.530776333563)); +#140843 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140844 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140845 = PCURVE('',#140657,#140846); +#140846 = DEFINITIONAL_REPRESENTATION('',(#140847),#140850); +#140847 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140848,#140849), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#138456 = CARTESIAN_POINT('',(1.598788597134,-8.35)); -#138457 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#138458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138459 = PCURVE('',#87326,#138460); -#138460 = DEFINITIONAL_REPRESENTATION('',(#138461),#138465); -#138461 = CIRCLE('',#138462,0.119270391569); -#138462 = AXIS2_PLACEMENT_2D('',#138463,#138464); -#138463 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#138464 = DIRECTION('',(0.E+000,-1.)); -#138465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138466 = ORIENTED_EDGE('',*,*,#138247,.F.); -#138467 = ADVANCED_FACE('',(#138468),#138340,.T.); -#138468 = FACE_BOUND('',#138469,.T.); -#138469 = EDGE_LOOP('',(#138470,#138493,#138494,#138521)); -#138470 = ORIENTED_EDGE('',*,*,#138471,.T.); -#138471 = EDGE_CURVE('',#138472,#138323,#138474,.T.); -#138472 = VERTEX_POINT('',#138473); -#138473 = CARTESIAN_POINT('',(8.35,10.304819755875,0.75)); -#138474 = SURFACE_CURVE('',#138475,(#138480,#138486),.PCURVE_S1.); -#138475 = CIRCLE('',#138476,0.2192697516); -#138476 = AXIS2_PLACEMENT_3D('',#138477,#138478,#138479); -#138477 = CARTESIAN_POINT('',(8.35,10.30032442045,0.530776333563)); -#138478 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138479 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138480 = PCURVE('',#138340,#138481); -#138481 = DEFINITIONAL_REPRESENTATION('',(#138482),#138485); -#138482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138483,#138484), +#140848 = CARTESIAN_POINT('',(1.598788597134,-8.35)); +#140849 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#140850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140851 = PCURVE('',#89718,#140852); +#140852 = DEFINITIONAL_REPRESENTATION('',(#140853),#140857); +#140853 = CIRCLE('',#140854,0.119270391569); +#140854 = AXIS2_PLACEMENT_2D('',#140855,#140856); +#140855 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#140856 = DIRECTION('',(0.E+000,-1.)); +#140857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140858 = ORIENTED_EDGE('',*,*,#140639,.F.); +#140859 = ADVANCED_FACE('',(#140860),#140732,.T.); +#140860 = FACE_BOUND('',#140861,.T.); +#140861 = EDGE_LOOP('',(#140862,#140885,#140886,#140913)); +#140862 = ORIENTED_EDGE('',*,*,#140863,.T.); +#140863 = EDGE_CURVE('',#140864,#140715,#140866,.T.); +#140864 = VERTEX_POINT('',#140865); +#140865 = CARTESIAN_POINT('',(8.35,10.304819755875,0.75)); +#140866 = SURFACE_CURVE('',#140867,(#140872,#140878),.PCURVE_S1.); +#140867 = CIRCLE('',#140868,0.2192697516); +#140868 = AXIS2_PLACEMENT_3D('',#140869,#140870,#140871); +#140869 = CARTESIAN_POINT('',(8.35,10.30032442045,0.530776333563)); +#140870 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140871 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140872 = PCURVE('',#140732,#140873); +#140873 = DEFINITIONAL_REPRESENTATION('',(#140874),#140877); +#140874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140875,#140876), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#138483 = CARTESIAN_POINT('',(1.591299156552,-8.35)); -#138484 = CARTESIAN_POINT('',(3.14159265359,-8.35)); -#138485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138486 = PCURVE('',#87326,#138487); -#138487 = DEFINITIONAL_REPRESENTATION('',(#138488),#138492); -#138488 = CIRCLE('',#138489,0.2192697516); -#138489 = AXIS2_PLACEMENT_2D('',#138490,#138491); -#138490 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#138491 = DIRECTION('',(0.E+000,-1.)); -#138492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138493 = ORIENTED_EDGE('',*,*,#138322,.T.); -#138494 = ORIENTED_EDGE('',*,*,#138495,.F.); -#138495 = EDGE_CURVE('',#138496,#138325,#138498,.T.); -#138496 = VERTEX_POINT('',#138497); -#138497 = CARTESIAN_POINT('',(8.15,10.304819755875,0.75)); -#138498 = SURFACE_CURVE('',#138499,(#138504,#138510),.PCURVE_S1.); -#138499 = CIRCLE('',#138500,0.2192697516); -#138500 = AXIS2_PLACEMENT_3D('',#138501,#138502,#138503); -#138501 = CARTESIAN_POINT('',(8.15,10.30032442045,0.530776333563)); -#138502 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138503 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138504 = PCURVE('',#138340,#138505); -#138505 = DEFINITIONAL_REPRESENTATION('',(#138506),#138509); -#138506 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138507,#138508), +#140875 = CARTESIAN_POINT('',(1.591299156552,-8.35)); +#140876 = CARTESIAN_POINT('',(3.14159265359,-8.35)); +#140877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140878 = PCURVE('',#89718,#140879); +#140879 = DEFINITIONAL_REPRESENTATION('',(#140880),#140884); +#140880 = CIRCLE('',#140881,0.2192697516); +#140881 = AXIS2_PLACEMENT_2D('',#140882,#140883); +#140882 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#140883 = DIRECTION('',(0.E+000,-1.)); +#140884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140885 = ORIENTED_EDGE('',*,*,#140714,.T.); +#140886 = ORIENTED_EDGE('',*,*,#140887,.F.); +#140887 = EDGE_CURVE('',#140888,#140717,#140890,.T.); +#140888 = VERTEX_POINT('',#140889); +#140889 = CARTESIAN_POINT('',(8.15,10.304819755875,0.75)); +#140890 = SURFACE_CURVE('',#140891,(#140896,#140902),.PCURVE_S1.); +#140891 = CIRCLE('',#140892,0.2192697516); +#140892 = AXIS2_PLACEMENT_3D('',#140893,#140894,#140895); +#140893 = CARTESIAN_POINT('',(8.15,10.30032442045,0.530776333563)); +#140894 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#140895 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#140896 = PCURVE('',#140732,#140897); +#140897 = DEFINITIONAL_REPRESENTATION('',(#140898),#140901); +#140898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140899,#140900), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#138507 = CARTESIAN_POINT('',(1.591299156552,-8.15)); -#138508 = CARTESIAN_POINT('',(3.14159265359,-8.15)); -#138509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140899 = CARTESIAN_POINT('',(1.591299156552,-8.15)); +#140900 = CARTESIAN_POINT('',(3.14159265359,-8.15)); +#140901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138510 = PCURVE('',#87270,#138511); -#138511 = DEFINITIONAL_REPRESENTATION('',(#138512),#138520); -#138512 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138513,#138514,#138515, - #138516,#138517,#138518,#138519),.UNSPECIFIED.,.T.,.F.) +#140902 = PCURVE('',#89662,#140903); +#140903 = DEFINITIONAL_REPRESENTATION('',(#140904),#140912); +#140904 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140905,#140906,#140907, + #140908,#140909,#140910,#140911),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#138513 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#138514 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#138515 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#138516 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#138517 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#138518 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#138519 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#138520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138521 = ORIENTED_EDGE('',*,*,#138522,.T.); -#138522 = EDGE_CURVE('',#138496,#138472,#138523,.T.); -#138523 = SURFACE_CURVE('',#138524,(#138528,#138534),.PCURVE_S1.); -#138524 = LINE('',#138525,#138526); -#138525 = CARTESIAN_POINT('',(8.15,10.304819755875,0.75)); -#138526 = VECTOR('',#138527,1.); -#138527 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138528 = PCURVE('',#138340,#138529); -#138529 = DEFINITIONAL_REPRESENTATION('',(#138530),#138533); -#138530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138531,#138532), +#140905 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#140906 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#140907 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#140908 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#140909 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#140910 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#140911 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#140912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140913 = ORIENTED_EDGE('',*,*,#140914,.T.); +#140914 = EDGE_CURVE('',#140888,#140864,#140915,.T.); +#140915 = SURFACE_CURVE('',#140916,(#140920,#140926),.PCURVE_S1.); +#140916 = LINE('',#140917,#140918); +#140917 = CARTESIAN_POINT('',(8.15,10.304819755875,0.75)); +#140918 = VECTOR('',#140919,1.); +#140919 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#140920 = PCURVE('',#140732,#140921); +#140921 = DEFINITIONAL_REPRESENTATION('',(#140922),#140925); +#140922 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140923,#140924), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#138531 = CARTESIAN_POINT('',(1.591299156552,-8.15)); -#138532 = CARTESIAN_POINT('',(1.591299156552,-8.35)); -#138533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138534 = PCURVE('',#87352,#138535); -#138535 = DEFINITIONAL_REPRESENTATION('',(#138536),#138540); -#138536 = LINE('',#138537,#138538); -#138537 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#138538 = VECTOR('',#138539,1.); -#138539 = DIRECTION('',(-8.881784197001E-016,1.)); -#138540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138541 = ADVANCED_FACE('',(#138542),#87270,.F.); -#138542 = FACE_BOUND('',#138543,.T.); -#138543 = EDGE_LOOP('',(#138544,#138565,#138566,#138567,#138568,#138569, - #138590,#138591,#138592,#138593,#138594,#138615)); -#138544 = ORIENTED_EDGE('',*,*,#138545,.F.); -#138545 = EDGE_CURVE('',#138496,#87255,#138546,.T.); -#138546 = SURFACE_CURVE('',#138547,(#138551,#138558),.PCURVE_S1.); -#138547 = LINE('',#138548,#138549); -#138548 = CARTESIAN_POINT('',(8.15,10.527847992439,0.75)); -#138549 = VECTOR('',#138550,1.); -#138550 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#138551 = PCURVE('',#87270,#138552); -#138552 = DEFINITIONAL_REPRESENTATION('',(#138553),#138557); -#138553 = LINE('',#138554,#138555); -#138554 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#138555 = VECTOR('',#138556,1.); -#138556 = DIRECTION('',(-3.563627120235E-016,-1.)); -#138557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138558 = PCURVE('',#87352,#138559); -#138559 = DEFINITIONAL_REPRESENTATION('',(#138560),#138564); -#138560 = LINE('',#138561,#138562); -#138561 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138562 = VECTOR('',#138563,1.); -#138563 = DIRECTION('',(-1.,2.164989446033E-063)); -#138564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138565 = ORIENTED_EDGE('',*,*,#138495,.T.); -#138566 = ORIENTED_EDGE('',*,*,#138373,.T.); -#138567 = ORIENTED_EDGE('',*,*,#138144,.T.); -#138568 = ORIENTED_EDGE('',*,*,#137934,.T.); -#138569 = ORIENTED_EDGE('',*,*,#138570,.T.); -#138570 = EDGE_CURVE('',#137907,#137988,#138571,.T.); -#138571 = SURFACE_CURVE('',#138572,(#138576,#138583),.PCURVE_S1.); -#138572 = LINE('',#138573,#138574); -#138573 = CARTESIAN_POINT('',(8.15,11.,1.159810404338E-002)); -#138574 = VECTOR('',#138575,1.); -#138575 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#138576 = PCURVE('',#87270,#138577); -#138577 = DEFINITIONAL_REPRESENTATION('',(#138578),#138582); -#138578 = LINE('',#138579,#138580); -#138579 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#138580 = VECTOR('',#138581,1.); -#138581 = DIRECTION('',(1.,-2.101748079665E-016)); -#138582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138583 = PCURVE('',#137922,#138584); -#138584 = DEFINITIONAL_REPRESENTATION('',(#138585),#138589); -#138585 = LINE('',#138586,#138587); -#138586 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#138587 = VECTOR('',#138588,1.); -#138588 = DIRECTION('',(1.570395187386E-016,-1.)); -#138589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#140923 = CARTESIAN_POINT('',(1.591299156552,-8.15)); +#140924 = CARTESIAN_POINT('',(1.591299156552,-8.35)); +#140925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140926 = PCURVE('',#89744,#140927); +#140927 = DEFINITIONAL_REPRESENTATION('',(#140928),#140932); +#140928 = LINE('',#140929,#140930); +#140929 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#140930 = VECTOR('',#140931,1.); +#140931 = DIRECTION('',(-8.881784197001E-016,1.)); +#140932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140933 = ADVANCED_FACE('',(#140934),#89662,.F.); +#140934 = FACE_BOUND('',#140935,.T.); +#140935 = EDGE_LOOP('',(#140936,#140957,#140958,#140959,#140960,#140961, + #140982,#140983,#140984,#140985,#140986,#141007)); +#140936 = ORIENTED_EDGE('',*,*,#140937,.F.); +#140937 = EDGE_CURVE('',#140888,#89647,#140938,.T.); +#140938 = SURFACE_CURVE('',#140939,(#140943,#140950),.PCURVE_S1.); +#140939 = LINE('',#140940,#140941); +#140940 = CARTESIAN_POINT('',(8.15,10.527847992439,0.75)); +#140941 = VECTOR('',#140942,1.); +#140942 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140943 = PCURVE('',#89662,#140944); +#140944 = DEFINITIONAL_REPRESENTATION('',(#140945),#140949); +#140945 = LINE('',#140946,#140947); +#140946 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#140947 = VECTOR('',#140948,1.); +#140948 = DIRECTION('',(-3.563627120235E-016,-1.)); +#140949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140950 = PCURVE('',#89744,#140951); +#140951 = DEFINITIONAL_REPRESENTATION('',(#140952),#140956); +#140952 = LINE('',#140953,#140954); +#140953 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140954 = VECTOR('',#140955,1.); +#140955 = DIRECTION('',(-1.,2.164989446033E-063)); +#140956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140957 = ORIENTED_EDGE('',*,*,#140887,.T.); +#140958 = ORIENTED_EDGE('',*,*,#140765,.T.); +#140959 = ORIENTED_EDGE('',*,*,#140536,.T.); +#140960 = ORIENTED_EDGE('',*,*,#140326,.T.); +#140961 = ORIENTED_EDGE('',*,*,#140962,.T.); +#140962 = EDGE_CURVE('',#140299,#140380,#140963,.T.); +#140963 = SURFACE_CURVE('',#140964,(#140968,#140975),.PCURVE_S1.); +#140964 = LINE('',#140965,#140966); +#140965 = CARTESIAN_POINT('',(8.15,11.,1.159810404338E-002)); +#140966 = VECTOR('',#140967,1.); +#140967 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#140968 = PCURVE('',#89662,#140969); +#140969 = DEFINITIONAL_REPRESENTATION('',(#140970),#140974); +#140970 = LINE('',#140971,#140972); +#140971 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#140972 = VECTOR('',#140973,1.); +#140973 = DIRECTION('',(1.,-2.101748079665E-016)); +#140974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140975 = PCURVE('',#140314,#140976); +#140976 = DEFINITIONAL_REPRESENTATION('',(#140977),#140981); +#140977 = LINE('',#140978,#140979); +#140978 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#140979 = VECTOR('',#140980,1.); +#140980 = DIRECTION('',(1.570395187386E-016,-1.)); +#140981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#140982 = ORIENTED_EDGE('',*,*,#140377,.F.); +#140983 = ORIENTED_EDGE('',*,*,#140615,.F.); +#140984 = ORIENTED_EDGE('',*,*,#140668,.F.); +#140985 = ORIENTED_EDGE('',*,*,#140789,.F.); +#140986 = ORIENTED_EDGE('',*,*,#140987,.T.); +#140987 = EDGE_CURVE('',#140790,#89645,#140988,.T.); +#140988 = SURFACE_CURVE('',#140989,(#140993,#141000),.PCURVE_S1.); +#140989 = LINE('',#140990,#140991); +#140990 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); +#140991 = VECTOR('',#140992,1.); +#140992 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#140993 = PCURVE('',#89662,#140994); +#140994 = DEFINITIONAL_REPRESENTATION('',(#140995),#140999); +#140995 = LINE('',#140996,#140997); +#140996 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#140997 = VECTOR('',#140998,1.); +#140998 = DIRECTION('',(-3.563627120235E-016,-1.)); +#140999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141000 = PCURVE('',#89690,#141001); +#141001 = DEFINITIONAL_REPRESENTATION('',(#141002),#141006); +#141002 = LINE('',#141003,#141004); +#141003 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141004 = VECTOR('',#141005,1.); +#141005 = DIRECTION('',(1.,2.164989446033E-063)); +#141006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141007 = ORIENTED_EDGE('',*,*,#89644,.T.); +#141008 = ADVANCED_FACE('',(#141009),#89744,.F.); +#141009 = FACE_BOUND('',#141010,.T.); +#141010 = EDGE_LOOP('',(#141011,#141012,#141013,#141014)); +#141011 = ORIENTED_EDGE('',*,*,#140914,.F.); +#141012 = ORIENTED_EDGE('',*,*,#140937,.T.); +#141013 = ORIENTED_EDGE('',*,*,#89730,.T.); +#141014 = ORIENTED_EDGE('',*,*,#141015,.F.); +#141015 = EDGE_CURVE('',#140864,#89703,#141016,.T.); +#141016 = SURFACE_CURVE('',#141017,(#141021,#141028),.PCURVE_S1.); +#141017 = LINE('',#141018,#141019); +#141018 = CARTESIAN_POINT('',(8.35,10.527847992439,0.75)); +#141019 = VECTOR('',#141020,1.); +#141020 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141021 = PCURVE('',#89744,#141022); +#141022 = DEFINITIONAL_REPRESENTATION('',(#141023),#141027); +#141023 = LINE('',#141024,#141025); +#141024 = CARTESIAN_POINT('',(0.E+000,0.2)); +#141025 = VECTOR('',#141026,1.); +#141026 = DIRECTION('',(-1.,2.164989446033E-063)); +#141027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141028 = PCURVE('',#89718,#141029); +#141029 = DEFINITIONAL_REPRESENTATION('',(#141030),#141034); +#141030 = LINE('',#141031,#141032); +#141031 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#141032 = VECTOR('',#141033,1.); +#141033 = DIRECTION('',(3.563627120235E-016,-1.)); +#141034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141035 = ADVANCED_FACE('',(#141036),#89718,.F.); +#141036 = FACE_BOUND('',#141037,.T.); +#141037 = EDGE_LOOP('',(#141038,#141059,#141060,#141061,#141062,#141063, + #141084,#141085,#141086,#141087,#141088,#141089)); +#141038 = ORIENTED_EDGE('',*,*,#141039,.F.); +#141039 = EDGE_CURVE('',#140817,#89675,#141040,.T.); +#141040 = SURFACE_CURVE('',#141041,(#141045,#141052),.PCURVE_S1.); +#141041 = LINE('',#141042,#141043); +#141042 = CARTESIAN_POINT('',(8.35,10.527847992439,0.65)); +#141043 = VECTOR('',#141044,1.); +#141044 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141045 = PCURVE('',#89718,#141046); +#141046 = DEFINITIONAL_REPRESENTATION('',(#141047),#141051); +#141047 = LINE('',#141048,#141049); +#141048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141049 = VECTOR('',#141050,1.); +#141050 = DIRECTION('',(3.563627120235E-016,-1.)); +#141051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141052 = PCURVE('',#89690,#141053); +#141053 = DEFINITIONAL_REPRESENTATION('',(#141054),#141058); +#141054 = LINE('',#141055,#141056); +#141055 = CARTESIAN_POINT('',(0.E+000,0.2)); +#141056 = VECTOR('',#141057,1.); +#141057 = DIRECTION('',(1.,2.164989446033E-063)); +#141058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141059 = ORIENTED_EDGE('',*,*,#140838,.T.); +#141060 = ORIENTED_EDGE('',*,*,#140690,.T.); +#141061 = ORIENTED_EDGE('',*,*,#140561,.T.); +#141062 = ORIENTED_EDGE('',*,*,#140430,.T.); +#141063 = ORIENTED_EDGE('',*,*,#141064,.T.); +#141064 = EDGE_CURVE('',#140408,#140271,#141065,.T.); +#141065 = SURFACE_CURVE('',#141066,(#141070,#141077),.PCURVE_S1.); +#141066 = LINE('',#141067,#141068); +#141067 = CARTESIAN_POINT('',(8.35,11.,1.159810404338E-002)); +#141068 = VECTOR('',#141069,1.); +#141069 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#141070 = PCURVE('',#89718,#141071); +#141071 = DEFINITIONAL_REPRESENTATION('',(#141072),#141076); +#141072 = LINE('',#141073,#141074); +#141073 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#141074 = VECTOR('',#141075,1.); +#141075 = DIRECTION('',(1.,2.101748079665E-016)); +#141076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141077 = PCURVE('',#140314,#141078); +#141078 = DEFINITIONAL_REPRESENTATION('',(#141079),#141083); +#141079 = LINE('',#141080,#141081); +#141080 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#141081 = VECTOR('',#141082,1.); +#141082 = DIRECTION('',(-1.570395187386E-016,1.)); +#141083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141084 = ORIENTED_EDGE('',*,*,#140268,.F.); +#141085 = ORIENTED_EDGE('',*,*,#140482,.F.); +#141086 = ORIENTED_EDGE('',*,*,#140743,.F.); +#141087 = ORIENTED_EDGE('',*,*,#140863,.F.); +#141088 = ORIENTED_EDGE('',*,*,#141015,.T.); +#141089 = ORIENTED_EDGE('',*,*,#89702,.T.); +#141090 = ADVANCED_FACE('',(#141091),#89690,.F.); +#141091 = FACE_BOUND('',#141092,.T.); +#141092 = EDGE_LOOP('',(#141093,#141094,#141095,#141096)); +#141093 = ORIENTED_EDGE('',*,*,#140816,.F.); +#141094 = ORIENTED_EDGE('',*,*,#141039,.T.); +#141095 = ORIENTED_EDGE('',*,*,#89674,.T.); +#141096 = ORIENTED_EDGE('',*,*,#140987,.F.); +#141097 = ADVANCED_FACE('',(#141098),#140314,.T.); +#141098 = FACE_BOUND('',#141099,.T.); +#141099 = EDGE_LOOP('',(#141100,#141101,#141102,#141103)); +#141100 = ORIENTED_EDGE('',*,*,#141064,.F.); +#141101 = ORIENTED_EDGE('',*,*,#140407,.F.); +#141102 = ORIENTED_EDGE('',*,*,#140962,.F.); +#141103 = ORIENTED_EDGE('',*,*,#140298,.F.); +#141104 = ADVANCED_FACE('',(#141105),#141119,.T.); +#141105 = FACE_BOUND('',#141106,.T.); +#141106 = EDGE_LOOP('',(#141107,#141137,#141165,#141188)); +#141107 = ORIENTED_EDGE('',*,*,#141108,.T.); +#141108 = EDGE_CURVE('',#141109,#141111,#141113,.T.); +#141109 = VERTEX_POINT('',#141110); +#141110 = CARTESIAN_POINT('',(7.85,10.740726081328,-0.208196358798)); +#141111 = VERTEX_POINT('',#141112); +#141112 = CARTESIAN_POINT('',(7.85,11.,-0.208196358798)); +#141113 = SURFACE_CURVE('',#141114,(#141118,#141130),.PCURVE_S1.); +#141114 = LINE('',#141115,#141116); +#141115 = CARTESIAN_POINT('',(7.85,10.740726081328,-0.208196358798)); +#141116 = VECTOR('',#141117,1.); +#141117 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#141118 = PCURVE('',#141119,#141124); +#141119 = PLANE('',#141120); +#141120 = AXIS2_PLACEMENT_3D('',#141121,#141122,#141123); +#141121 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#141122 = DIRECTION('',(0.E+000,0.E+000,1.)); +#141123 = DIRECTION('',(1.,0.E+000,0.E+000)); +#141124 = DEFINITIONAL_REPRESENTATION('',(#141125),#141129); +#141125 = LINE('',#141126,#141127); +#141126 = CARTESIAN_POINT('',(7.85,-7.105427357601E-015)); +#141127 = VECTOR('',#141128,1.); +#141128 = DIRECTION('',(6.725593854929E-015,1.)); +#141129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141130 = PCURVE('',#90060,#141131); +#141131 = DEFINITIONAL_REPRESENTATION('',(#141132),#141136); +#141132 = LINE('',#141133,#141134); +#141133 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#141134 = VECTOR('',#141135,1.); +#141135 = DIRECTION('',(0.E+000,1.)); +#141136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141137 = ORIENTED_EDGE('',*,*,#141138,.T.); +#141138 = EDGE_CURVE('',#141111,#141139,#141141,.T.); +#141139 = VERTEX_POINT('',#141140); +#141140 = CARTESIAN_POINT('',(7.65,11.,-0.208196358798)); +#141141 = SURFACE_CURVE('',#141142,(#141146,#141153),.PCURVE_S1.); +#141142 = LINE('',#141143,#141144); +#141143 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#141144 = VECTOR('',#141145,1.); +#141145 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141146 = PCURVE('',#141119,#141147); +#141147 = DEFINITIONAL_REPRESENTATION('',(#141148),#141152); +#141148 = LINE('',#141149,#141150); +#141149 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#141150 = VECTOR('',#141151,1.); +#141151 = DIRECTION('',(-1.,8.881784197001E-016)); +#141152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141153 = PCURVE('',#141154,#141159); +#141154 = PLANE('',#141155); +#141155 = AXIS2_PLACEMENT_3D('',#141156,#141157,#141158); +#141156 = CARTESIAN_POINT('',(7.75,11.,-0.258196742327)); +#141157 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#141158 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#141159 = DEFINITIONAL_REPRESENTATION('',(#141160),#141164); +#141160 = LINE('',#141161,#141162); +#141161 = CARTESIAN_POINT('',(7.75,5.000038352949E-002)); +#141162 = VECTOR('',#141163,1.); +#141163 = DIRECTION('',(1.,1.1653254136E-048)); +#141164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141165 = ORIENTED_EDGE('',*,*,#141166,.F.); +#141166 = EDGE_CURVE('',#141167,#141139,#141169,.T.); +#141167 = VERTEX_POINT('',#141168); +#141168 = CARTESIAN_POINT('',(7.65,10.740726081328,-0.208196358798)); +#141169 = SURFACE_CURVE('',#141170,(#141174,#141181),.PCURVE_S1.); +#141170 = LINE('',#141171,#141172); +#141171 = CARTESIAN_POINT('',(7.65,10.740726081328,-0.208196358798)); +#141172 = VECTOR('',#141173,1.); +#141173 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#141174 = PCURVE('',#141119,#141175); +#141175 = DEFINITIONAL_REPRESENTATION('',(#141176),#141180); +#141176 = LINE('',#141177,#141178); +#141177 = CARTESIAN_POINT('',(7.65,-7.105427357601E-015)); +#141178 = VECTOR('',#141179,1.); +#141179 = DIRECTION('',(6.725593854929E-015,1.)); +#141180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141181 = PCURVE('',#90004,#141182); +#141182 = DEFINITIONAL_REPRESENTATION('',(#141183),#141187); +#141183 = LINE('',#141184,#141185); +#141184 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#141185 = VECTOR('',#141186,1.); +#141186 = DIRECTION('',(0.E+000,1.)); +#141187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138590 = ORIENTED_EDGE('',*,*,#137985,.F.); -#138591 = ORIENTED_EDGE('',*,*,#138223,.F.); -#138592 = ORIENTED_EDGE('',*,*,#138276,.F.); -#138593 = ORIENTED_EDGE('',*,*,#138397,.F.); -#138594 = ORIENTED_EDGE('',*,*,#138595,.T.); -#138595 = EDGE_CURVE('',#138398,#87253,#138596,.T.); -#138596 = SURFACE_CURVE('',#138597,(#138601,#138608),.PCURVE_S1.); -#138597 = LINE('',#138598,#138599); -#138598 = CARTESIAN_POINT('',(8.15,10.527847992439,0.65)); -#138599 = VECTOR('',#138600,1.); -#138600 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#138601 = PCURVE('',#87270,#138602); -#138602 = DEFINITIONAL_REPRESENTATION('',(#138603),#138607); -#138603 = LINE('',#138604,#138605); -#138604 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138605 = VECTOR('',#138606,1.); -#138606 = DIRECTION('',(-3.563627120235E-016,-1.)); -#138607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138608 = PCURVE('',#87298,#138609); -#138609 = DEFINITIONAL_REPRESENTATION('',(#138610),#138614); -#138610 = LINE('',#138611,#138612); -#138611 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138612 = VECTOR('',#138613,1.); -#138613 = DIRECTION('',(1.,2.164989446033E-063)); -#138614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138615 = ORIENTED_EDGE('',*,*,#87252,.T.); -#138616 = ADVANCED_FACE('',(#138617),#87352,.F.); -#138617 = FACE_BOUND('',#138618,.T.); -#138618 = EDGE_LOOP('',(#138619,#138620,#138621,#138622)); -#138619 = ORIENTED_EDGE('',*,*,#138522,.F.); -#138620 = ORIENTED_EDGE('',*,*,#138545,.T.); -#138621 = ORIENTED_EDGE('',*,*,#87338,.T.); -#138622 = ORIENTED_EDGE('',*,*,#138623,.F.); -#138623 = EDGE_CURVE('',#138472,#87311,#138624,.T.); -#138624 = SURFACE_CURVE('',#138625,(#138629,#138636),.PCURVE_S1.); -#138625 = LINE('',#138626,#138627); -#138626 = CARTESIAN_POINT('',(8.35,10.527847992439,0.75)); -#138627 = VECTOR('',#138628,1.); -#138628 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#138629 = PCURVE('',#87352,#138630); -#138630 = DEFINITIONAL_REPRESENTATION('',(#138631),#138635); -#138631 = LINE('',#138632,#138633); -#138632 = CARTESIAN_POINT('',(0.E+000,0.2)); -#138633 = VECTOR('',#138634,1.); -#138634 = DIRECTION('',(-1.,2.164989446033E-063)); -#138635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138636 = PCURVE('',#87326,#138637); -#138637 = DEFINITIONAL_REPRESENTATION('',(#138638),#138642); -#138638 = LINE('',#138639,#138640); -#138639 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#138640 = VECTOR('',#138641,1.); -#138641 = DIRECTION('',(3.563627120235E-016,-1.)); -#138642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138643 = ADVANCED_FACE('',(#138644),#87326,.F.); -#138644 = FACE_BOUND('',#138645,.T.); -#138645 = EDGE_LOOP('',(#138646,#138667,#138668,#138669,#138670,#138671, - #138692,#138693,#138694,#138695,#138696,#138697)); -#138646 = ORIENTED_EDGE('',*,*,#138647,.F.); -#138647 = EDGE_CURVE('',#138425,#87283,#138648,.T.); -#138648 = SURFACE_CURVE('',#138649,(#138653,#138660),.PCURVE_S1.); -#138649 = LINE('',#138650,#138651); -#138650 = CARTESIAN_POINT('',(8.35,10.527847992439,0.65)); -#138651 = VECTOR('',#138652,1.); -#138652 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#138653 = PCURVE('',#87326,#138654); -#138654 = DEFINITIONAL_REPRESENTATION('',(#138655),#138659); -#138655 = LINE('',#138656,#138657); -#138656 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138657 = VECTOR('',#138658,1.); -#138658 = DIRECTION('',(3.563627120235E-016,-1.)); -#138659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138660 = PCURVE('',#87298,#138661); -#138661 = DEFINITIONAL_REPRESENTATION('',(#138662),#138666); -#138662 = LINE('',#138663,#138664); -#138663 = CARTESIAN_POINT('',(0.E+000,0.2)); -#138664 = VECTOR('',#138665,1.); -#138665 = DIRECTION('',(1.,2.164989446033E-063)); -#138666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138667 = ORIENTED_EDGE('',*,*,#138446,.T.); -#138668 = ORIENTED_EDGE('',*,*,#138298,.T.); -#138669 = ORIENTED_EDGE('',*,*,#138169,.T.); -#138670 = ORIENTED_EDGE('',*,*,#138038,.T.); -#138671 = ORIENTED_EDGE('',*,*,#138672,.T.); -#138672 = EDGE_CURVE('',#138016,#137879,#138673,.T.); -#138673 = SURFACE_CURVE('',#138674,(#138678,#138685),.PCURVE_S1.); -#138674 = LINE('',#138675,#138676); -#138675 = CARTESIAN_POINT('',(8.35,11.,1.159810404338E-002)); -#138676 = VECTOR('',#138677,1.); -#138677 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#138678 = PCURVE('',#87326,#138679); -#138679 = DEFINITIONAL_REPRESENTATION('',(#138680),#138684); -#138680 = LINE('',#138681,#138682); -#138681 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#138682 = VECTOR('',#138683,1.); -#138683 = DIRECTION('',(1.,2.101748079665E-016)); -#138684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138685 = PCURVE('',#137922,#138686); -#138686 = DEFINITIONAL_REPRESENTATION('',(#138687),#138691); -#138687 = LINE('',#138688,#138689); -#138688 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#138689 = VECTOR('',#138690,1.); -#138690 = DIRECTION('',(-1.570395187386E-016,1.)); -#138691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138692 = ORIENTED_EDGE('',*,*,#137876,.F.); -#138693 = ORIENTED_EDGE('',*,*,#138090,.F.); -#138694 = ORIENTED_EDGE('',*,*,#138351,.F.); -#138695 = ORIENTED_EDGE('',*,*,#138471,.F.); -#138696 = ORIENTED_EDGE('',*,*,#138623,.T.); -#138697 = ORIENTED_EDGE('',*,*,#87310,.T.); -#138698 = ADVANCED_FACE('',(#138699),#87298,.F.); -#138699 = FACE_BOUND('',#138700,.T.); -#138700 = EDGE_LOOP('',(#138701,#138702,#138703,#138704)); -#138701 = ORIENTED_EDGE('',*,*,#138424,.F.); -#138702 = ORIENTED_EDGE('',*,*,#138647,.T.); -#138703 = ORIENTED_EDGE('',*,*,#87282,.T.); -#138704 = ORIENTED_EDGE('',*,*,#138595,.F.); -#138705 = ADVANCED_FACE('',(#138706),#137922,.T.); -#138706 = FACE_BOUND('',#138707,.T.); -#138707 = EDGE_LOOP('',(#138708,#138709,#138710,#138711)); -#138708 = ORIENTED_EDGE('',*,*,#138672,.F.); -#138709 = ORIENTED_EDGE('',*,*,#138015,.F.); -#138710 = ORIENTED_EDGE('',*,*,#138570,.F.); -#138711 = ORIENTED_EDGE('',*,*,#137906,.F.); -#138712 = ADVANCED_FACE('',(#138713),#138727,.T.); -#138713 = FACE_BOUND('',#138714,.T.); -#138714 = EDGE_LOOP('',(#138715,#138745,#138773,#138796)); -#138715 = ORIENTED_EDGE('',*,*,#138716,.T.); -#138716 = EDGE_CURVE('',#138717,#138719,#138721,.T.); -#138717 = VERTEX_POINT('',#138718); -#138718 = CARTESIAN_POINT('',(7.85,10.740726081328,-0.208196358798)); -#138719 = VERTEX_POINT('',#138720); -#138720 = CARTESIAN_POINT('',(7.85,11.,-0.208196358798)); -#138721 = SURFACE_CURVE('',#138722,(#138726,#138738),.PCURVE_S1.); -#138722 = LINE('',#138723,#138724); -#138723 = CARTESIAN_POINT('',(7.85,10.740726081328,-0.208196358798)); -#138724 = VECTOR('',#138725,1.); -#138725 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#138726 = PCURVE('',#138727,#138732); -#138727 = PLANE('',#138728); -#138728 = AXIS2_PLACEMENT_3D('',#138729,#138730,#138731); -#138729 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#138730 = DIRECTION('',(0.E+000,0.E+000,1.)); -#138731 = DIRECTION('',(1.,0.E+000,0.E+000)); -#138732 = DEFINITIONAL_REPRESENTATION('',(#138733),#138737); -#138733 = LINE('',#138734,#138735); -#138734 = CARTESIAN_POINT('',(7.85,-7.105427357601E-015)); -#138735 = VECTOR('',#138736,1.); -#138736 = DIRECTION('',(6.725593854929E-015,1.)); -#138737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138738 = PCURVE('',#87668,#138739); -#138739 = DEFINITIONAL_REPRESENTATION('',(#138740),#138744); -#138740 = LINE('',#138741,#138742); -#138741 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#138742 = VECTOR('',#138743,1.); -#138743 = DIRECTION('',(0.E+000,1.)); -#138744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138745 = ORIENTED_EDGE('',*,*,#138746,.T.); -#138746 = EDGE_CURVE('',#138719,#138747,#138749,.T.); -#138747 = VERTEX_POINT('',#138748); -#138748 = CARTESIAN_POINT('',(7.65,11.,-0.208196358798)); -#138749 = SURFACE_CURVE('',#138750,(#138754,#138761),.PCURVE_S1.); -#138750 = LINE('',#138751,#138752); -#138751 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#138752 = VECTOR('',#138753,1.); -#138753 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138754 = PCURVE('',#138727,#138755); -#138755 = DEFINITIONAL_REPRESENTATION('',(#138756),#138760); -#138756 = LINE('',#138757,#138758); -#138757 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#138758 = VECTOR('',#138759,1.); -#138759 = DIRECTION('',(-1.,8.881784197001E-016)); -#138760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138761 = PCURVE('',#138762,#138767); -#138762 = PLANE('',#138763); -#138763 = AXIS2_PLACEMENT_3D('',#138764,#138765,#138766); -#138764 = CARTESIAN_POINT('',(7.75,11.,-0.258196742327)); -#138765 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#138766 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#138767 = DEFINITIONAL_REPRESENTATION('',(#138768),#138772); -#138768 = LINE('',#138769,#138770); -#138769 = CARTESIAN_POINT('',(7.75,5.000038352949E-002)); -#138770 = VECTOR('',#138771,1.); -#138771 = DIRECTION('',(1.,1.1653254136E-048)); -#138772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138773 = ORIENTED_EDGE('',*,*,#138774,.F.); -#138774 = EDGE_CURVE('',#138775,#138747,#138777,.T.); -#138775 = VERTEX_POINT('',#138776); -#138776 = CARTESIAN_POINT('',(7.65,10.740726081328,-0.208196358798)); -#138777 = SURFACE_CURVE('',#138778,(#138782,#138789),.PCURVE_S1.); -#138778 = LINE('',#138779,#138780); -#138779 = CARTESIAN_POINT('',(7.65,10.740726081328,-0.208196358798)); -#138780 = VECTOR('',#138781,1.); -#138781 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#138782 = PCURVE('',#138727,#138783); -#138783 = DEFINITIONAL_REPRESENTATION('',(#138784),#138788); -#138784 = LINE('',#138785,#138786); -#138785 = CARTESIAN_POINT('',(7.65,-7.105427357601E-015)); -#138786 = VECTOR('',#138787,1.); -#138787 = DIRECTION('',(6.725593854929E-015,1.)); -#138788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138789 = PCURVE('',#87612,#138790); -#138790 = DEFINITIONAL_REPRESENTATION('',(#138791),#138795); -#138791 = LINE('',#138792,#138793); -#138792 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#138793 = VECTOR('',#138794,1.); -#138794 = DIRECTION('',(0.E+000,1.)); -#138795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138796 = ORIENTED_EDGE('',*,*,#138797,.T.); -#138797 = EDGE_CURVE('',#138775,#138717,#138798,.T.); -#138798 = SURFACE_CURVE('',#138799,(#138803,#138810),.PCURVE_S1.); -#138799 = LINE('',#138800,#138801); -#138800 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#141188 = ORIENTED_EDGE('',*,*,#141189,.T.); +#141189 = EDGE_CURVE('',#141167,#141109,#141190,.T.); +#141190 = SURFACE_CURVE('',#141191,(#141195,#141202),.PCURVE_S1.); +#141191 = LINE('',#141192,#141193); +#141192 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#138801 = VECTOR('',#138802,1.); -#138802 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138803 = PCURVE('',#138727,#138804); -#138804 = DEFINITIONAL_REPRESENTATION('',(#138805),#138809); -#138805 = LINE('',#138806,#138807); -#138806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138807 = VECTOR('',#138808,1.); -#138808 = DIRECTION('',(1.,-8.881784197001E-016)); -#138809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138810 = PCURVE('',#138811,#138816); -#138811 = CYLINDRICAL_SURFACE('',#138812,0.208574704164); -#138812 = AXIS2_PLACEMENT_3D('',#138813,#138814,#138815); -#138813 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#141193 = VECTOR('',#141194,1.); +#141194 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141195 = PCURVE('',#141119,#141196); +#141196 = DEFINITIONAL_REPRESENTATION('',(#141197),#141201); +#141197 = LINE('',#141198,#141199); +#141198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141199 = VECTOR('',#141200,1.); +#141200 = DIRECTION('',(1.,-8.881784197001E-016)); +#141201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141202 = PCURVE('',#141203,#141208); +#141203 = CYLINDRICAL_SURFACE('',#141204,0.208574704164); +#141204 = AXIS2_PLACEMENT_3D('',#141205,#141206,#141207); +#141205 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#138814 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138815 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138816 = DEFINITIONAL_REPRESENTATION('',(#138817),#138820); -#138817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138818,#138819), +#141206 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141207 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141208 = DEFINITIONAL_REPRESENTATION('',(#141209),#141212); +#141209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141210,#141211), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#138818 = CARTESIAN_POINT('',(4.772630242227,7.65)); -#138819 = CARTESIAN_POINT('',(4.772630242227,7.85)); -#138820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138821 = ADVANCED_FACE('',(#138822),#138836,.T.); -#138822 = FACE_BOUND('',#138823,.T.); -#138823 = EDGE_LOOP('',(#138824,#138854,#138877,#138900)); -#138824 = ORIENTED_EDGE('',*,*,#138825,.T.); -#138825 = EDGE_CURVE('',#138826,#138828,#138830,.T.); -#138826 = VERTEX_POINT('',#138827); -#138827 = CARTESIAN_POINT('',(7.65,10.74341632541,-0.308197125857)); -#138828 = VERTEX_POINT('',#138829); -#138829 = CARTESIAN_POINT('',(7.65,11.,-0.308197125857)); -#138830 = SURFACE_CURVE('',#138831,(#138835,#138847),.PCURVE_S1.); -#138831 = LINE('',#138832,#138833); -#138832 = CARTESIAN_POINT('',(7.65,10.74341632541,-0.308197125857)); -#138833 = VECTOR('',#138834,1.); -#138834 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#138835 = PCURVE('',#138836,#138841); -#138836 = PLANE('',#138837); -#138837 = AXIS2_PLACEMENT_3D('',#138838,#138839,#138840); -#138838 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#141210 = CARTESIAN_POINT('',(4.772630242227,7.65)); +#141211 = CARTESIAN_POINT('',(4.772630242227,7.85)); +#141212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141213 = ADVANCED_FACE('',(#141214),#141228,.T.); +#141214 = FACE_BOUND('',#141215,.T.); +#141215 = EDGE_LOOP('',(#141216,#141246,#141269,#141292)); +#141216 = ORIENTED_EDGE('',*,*,#141217,.T.); +#141217 = EDGE_CURVE('',#141218,#141220,#141222,.T.); +#141218 = VERTEX_POINT('',#141219); +#141219 = CARTESIAN_POINT('',(7.65,10.74341632541,-0.308197125857)); +#141220 = VERTEX_POINT('',#141221); +#141221 = CARTESIAN_POINT('',(7.65,11.,-0.308197125857)); +#141222 = SURFACE_CURVE('',#141223,(#141227,#141239),.PCURVE_S1.); +#141223 = LINE('',#141224,#141225); +#141224 = CARTESIAN_POINT('',(7.65,10.74341632541,-0.308197125857)); +#141225 = VECTOR('',#141226,1.); +#141226 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#141227 = PCURVE('',#141228,#141233); +#141228 = PLANE('',#141229); +#141229 = AXIS2_PLACEMENT_3D('',#141230,#141231,#141232); +#141230 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#138839 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#138840 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#138841 = DEFINITIONAL_REPRESENTATION('',(#138842),#138846); -#138842 = LINE('',#138843,#138844); -#138843 = CARTESIAN_POINT('',(-7.65,-7.105427357601E-015)); -#138844 = VECTOR('',#138845,1.); -#138845 = DIRECTION('',(-6.725593854929E-015,1.)); -#138846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138847 = PCURVE('',#87612,#138848); -#138848 = DEFINITIONAL_REPRESENTATION('',(#138849),#138853); -#138849 = LINE('',#138850,#138851); -#138850 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#138851 = VECTOR('',#138852,1.); -#138852 = DIRECTION('',(0.E+000,1.)); -#138853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138854 = ORIENTED_EDGE('',*,*,#138855,.T.); -#138855 = EDGE_CURVE('',#138828,#138856,#138858,.T.); -#138856 = VERTEX_POINT('',#138857); -#138857 = CARTESIAN_POINT('',(7.85,11.,-0.308197125857)); -#138858 = SURFACE_CURVE('',#138859,(#138863,#138870),.PCURVE_S1.); -#138859 = LINE('',#138860,#138861); -#138860 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#138861 = VECTOR('',#138862,1.); -#138862 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138863 = PCURVE('',#138836,#138864); -#138864 = DEFINITIONAL_REPRESENTATION('',(#138865),#138869); -#138865 = LINE('',#138866,#138867); -#138866 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#138867 = VECTOR('',#138868,1.); -#138868 = DIRECTION('',(-1.,-8.881784197001E-016)); -#138869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138870 = PCURVE('',#138762,#138871); -#138871 = DEFINITIONAL_REPRESENTATION('',(#138872),#138876); -#138872 = LINE('',#138873,#138874); -#138873 = CARTESIAN_POINT('',(7.75,-5.000038352949E-002)); -#138874 = VECTOR('',#138875,1.); -#138875 = DIRECTION('',(-1.,-1.1653254136E-048)); -#138876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138877 = ORIENTED_EDGE('',*,*,#138878,.F.); -#138878 = EDGE_CURVE('',#138879,#138856,#138881,.T.); -#138879 = VERTEX_POINT('',#138880); -#138880 = CARTESIAN_POINT('',(7.85,10.74341632541,-0.308197125857)); -#138881 = SURFACE_CURVE('',#138882,(#138886,#138893),.PCURVE_S1.); -#138882 = LINE('',#138883,#138884); -#138883 = CARTESIAN_POINT('',(7.85,10.74341632541,-0.308197125857)); -#138884 = VECTOR('',#138885,1.); -#138885 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#138886 = PCURVE('',#138836,#138887); -#138887 = DEFINITIONAL_REPRESENTATION('',(#138888),#138892); -#138888 = LINE('',#138889,#138890); -#138889 = CARTESIAN_POINT('',(-7.85,-7.105427357601E-015)); -#138890 = VECTOR('',#138891,1.); -#138891 = DIRECTION('',(-6.725593854929E-015,1.)); -#138892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138893 = PCURVE('',#87668,#138894); -#138894 = DEFINITIONAL_REPRESENTATION('',(#138895),#138899); -#138895 = LINE('',#138896,#138897); -#138896 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#138897 = VECTOR('',#138898,1.); -#138898 = DIRECTION('',(0.E+000,1.)); -#138899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138900 = ORIENTED_EDGE('',*,*,#138901,.T.); -#138901 = EDGE_CURVE('',#138879,#138826,#138902,.T.); -#138902 = SURFACE_CURVE('',#138903,(#138907,#138914),.PCURVE_S1.); -#138903 = LINE('',#138904,#138905); -#138904 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#141231 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#141232 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#141233 = DEFINITIONAL_REPRESENTATION('',(#141234),#141238); +#141234 = LINE('',#141235,#141236); +#141235 = CARTESIAN_POINT('',(-7.65,-7.105427357601E-015)); +#141236 = VECTOR('',#141237,1.); +#141237 = DIRECTION('',(-6.725593854929E-015,1.)); +#141238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141239 = PCURVE('',#90004,#141240); +#141240 = DEFINITIONAL_REPRESENTATION('',(#141241),#141245); +#141241 = LINE('',#141242,#141243); +#141242 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#141243 = VECTOR('',#141244,1.); +#141244 = DIRECTION('',(0.E+000,1.)); +#141245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141246 = ORIENTED_EDGE('',*,*,#141247,.T.); +#141247 = EDGE_CURVE('',#141220,#141248,#141250,.T.); +#141248 = VERTEX_POINT('',#141249); +#141249 = CARTESIAN_POINT('',(7.85,11.,-0.308197125857)); +#141250 = SURFACE_CURVE('',#141251,(#141255,#141262),.PCURVE_S1.); +#141251 = LINE('',#141252,#141253); +#141252 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#141253 = VECTOR('',#141254,1.); +#141254 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141255 = PCURVE('',#141228,#141256); +#141256 = DEFINITIONAL_REPRESENTATION('',(#141257),#141261); +#141257 = LINE('',#141258,#141259); +#141258 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#141259 = VECTOR('',#141260,1.); +#141260 = DIRECTION('',(-1.,-8.881784197001E-016)); +#141261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141262 = PCURVE('',#141154,#141263); +#141263 = DEFINITIONAL_REPRESENTATION('',(#141264),#141268); +#141264 = LINE('',#141265,#141266); +#141265 = CARTESIAN_POINT('',(7.75,-5.000038352949E-002)); +#141266 = VECTOR('',#141267,1.); +#141267 = DIRECTION('',(-1.,-1.1653254136E-048)); +#141268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141269 = ORIENTED_EDGE('',*,*,#141270,.F.); +#141270 = EDGE_CURVE('',#141271,#141248,#141273,.T.); +#141271 = VERTEX_POINT('',#141272); +#141272 = CARTESIAN_POINT('',(7.85,10.74341632541,-0.308197125857)); +#141273 = SURFACE_CURVE('',#141274,(#141278,#141285),.PCURVE_S1.); +#141274 = LINE('',#141275,#141276); +#141275 = CARTESIAN_POINT('',(7.85,10.74341632541,-0.308197125857)); +#141276 = VECTOR('',#141277,1.); +#141277 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#141278 = PCURVE('',#141228,#141279); +#141279 = DEFINITIONAL_REPRESENTATION('',(#141280),#141284); +#141280 = LINE('',#141281,#141282); +#141281 = CARTESIAN_POINT('',(-7.85,-7.105427357601E-015)); +#141282 = VECTOR('',#141283,1.); +#141283 = DIRECTION('',(-6.725593854929E-015,1.)); +#141284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141285 = PCURVE('',#90060,#141286); +#141286 = DEFINITIONAL_REPRESENTATION('',(#141287),#141291); +#141287 = LINE('',#141288,#141289); +#141288 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#141289 = VECTOR('',#141290,1.); +#141290 = DIRECTION('',(0.E+000,1.)); +#141291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141292 = ORIENTED_EDGE('',*,*,#141293,.T.); +#141293 = EDGE_CURVE('',#141271,#141218,#141294,.T.); +#141294 = SURFACE_CURVE('',#141295,(#141299,#141306),.PCURVE_S1.); +#141295 = LINE('',#141296,#141297); +#141296 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#138905 = VECTOR('',#138906,1.); -#138906 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138907 = PCURVE('',#138836,#138908); -#138908 = DEFINITIONAL_REPRESENTATION('',(#138909),#138913); -#138909 = LINE('',#138910,#138911); -#138910 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#138911 = VECTOR('',#138912,1.); -#138912 = DIRECTION('',(1.,8.881784197001E-016)); -#138913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138914 = PCURVE('',#138915,#138920); -#138915 = CYLINDRICAL_SURFACE('',#138916,0.308574064194); -#138916 = AXIS2_PLACEMENT_3D('',#138917,#138918,#138919); -#138917 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#141297 = VECTOR('',#141298,1.); +#141298 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141299 = PCURVE('',#141228,#141300); +#141300 = DEFINITIONAL_REPRESENTATION('',(#141301),#141305); +#141301 = LINE('',#141302,#141303); +#141302 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141303 = VECTOR('',#141304,1.); +#141304 = DIRECTION('',(1.,8.881784197001E-016)); +#141305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141306 = PCURVE('',#141307,#141312); +#141307 = CYLINDRICAL_SURFACE('',#141308,0.308574064194); +#141308 = AXIS2_PLACEMENT_3D('',#141309,#141310,#141311); +#141309 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#138918 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138919 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138920 = DEFINITIONAL_REPRESENTATION('',(#138921),#138924); -#138921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138922,#138923), +#141310 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141311 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141312 = DEFINITIONAL_REPRESENTATION('',(#141313),#141316); +#141313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141314,#141315), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#138922 = CARTESIAN_POINT('',(4.761821717947,7.85)); -#138923 = CARTESIAN_POINT('',(4.761821717947,7.65)); -#138924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138925 = ADVANCED_FACE('',(#138926),#138811,.F.); -#138926 = FACE_BOUND('',#138927,.F.); -#138927 = EDGE_LOOP('',(#138928,#138929,#138956,#138983)); -#138928 = ORIENTED_EDGE('',*,*,#138797,.T.); -#138929 = ORIENTED_EDGE('',*,*,#138930,.F.); -#138930 = EDGE_CURVE('',#138931,#138717,#138933,.T.); -#138931 = VERTEX_POINT('',#138932); -#138932 = CARTESIAN_POINT('',(7.85,10.51959417205,0.E+000)); -#138933 = SURFACE_CURVE('',#138934,(#138939,#138945),.PCURVE_S1.); -#138934 = CIRCLE('',#138935,0.208574704164); -#138935 = AXIS2_PLACEMENT_3D('',#138936,#138937,#138938); -#138936 = CARTESIAN_POINT('',(7.85,10.728168876214,2.640924866458E-017) - ); -#138937 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138938 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138939 = PCURVE('',#138811,#138940); -#138940 = DEFINITIONAL_REPRESENTATION('',(#138941),#138944); -#138941 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138942,#138943), +#141314 = CARTESIAN_POINT('',(4.761821717947,7.85)); +#141315 = CARTESIAN_POINT('',(4.761821717947,7.65)); +#141316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141317 = ADVANCED_FACE('',(#141318),#141203,.F.); +#141318 = FACE_BOUND('',#141319,.F.); +#141319 = EDGE_LOOP('',(#141320,#141321,#141348,#141375)); +#141320 = ORIENTED_EDGE('',*,*,#141189,.T.); +#141321 = ORIENTED_EDGE('',*,*,#141322,.F.); +#141322 = EDGE_CURVE('',#141323,#141109,#141325,.T.); +#141323 = VERTEX_POINT('',#141324); +#141324 = CARTESIAN_POINT('',(7.85,10.51959417205,0.E+000)); +#141325 = SURFACE_CURVE('',#141326,(#141331,#141337),.PCURVE_S1.); +#141326 = CIRCLE('',#141327,0.208574704164); +#141327 = AXIS2_PLACEMENT_3D('',#141328,#141329,#141330); +#141328 = CARTESIAN_POINT('',(7.85,10.728168876214,2.640924866458E-017) + ); +#141329 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141330 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141331 = PCURVE('',#141203,#141332); +#141332 = DEFINITIONAL_REPRESENTATION('',(#141333),#141336); +#141333 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141334,#141335), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#138942 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#138943 = CARTESIAN_POINT('',(4.772630242227,7.85)); -#138944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#141334 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#141335 = CARTESIAN_POINT('',(4.772630242227,7.85)); +#141336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138945 = PCURVE('',#87668,#138946); -#138946 = DEFINITIONAL_REPRESENTATION('',(#138947),#138955); -#138947 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#138948,#138949,#138950, - #138951,#138952,#138953,#138954),.UNSPECIFIED.,.T.,.F.) +#141337 = PCURVE('',#90060,#141338); +#141338 = DEFINITIONAL_REPRESENTATION('',(#141339),#141347); +#141339 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141340,#141341,#141342, + #141343,#141344,#141345,#141346),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#138948 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#138949 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#138950 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#138951 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#138952 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#138953 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#138954 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#138955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138956 = ORIENTED_EDGE('',*,*,#138957,.T.); -#138957 = EDGE_CURVE('',#138931,#138958,#138960,.T.); -#138958 = VERTEX_POINT('',#138959); -#138959 = CARTESIAN_POINT('',(7.65,10.51959417205,0.E+000)); -#138960 = SURFACE_CURVE('',#138961,(#138965,#138971),.PCURVE_S1.); -#138961 = LINE('',#138962,#138963); -#138962 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#141340 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#141341 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#141342 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#141343 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#141344 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#141345 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#141346 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#141347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141348 = ORIENTED_EDGE('',*,*,#141349,.T.); +#141349 = EDGE_CURVE('',#141323,#141350,#141352,.T.); +#141350 = VERTEX_POINT('',#141351); +#141351 = CARTESIAN_POINT('',(7.65,10.51959417205,0.E+000)); +#141352 = SURFACE_CURVE('',#141353,(#141357,#141363),.PCURVE_S1.); +#141353 = LINE('',#141354,#141355); +#141354 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#138963 = VECTOR('',#138964,1.); -#138964 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#138965 = PCURVE('',#138811,#138966); -#138966 = DEFINITIONAL_REPRESENTATION('',(#138967),#138970); -#138967 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138968,#138969), +#141355 = VECTOR('',#141356,1.); +#141356 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141357 = PCURVE('',#141203,#141358); +#141358 = DEFINITIONAL_REPRESENTATION('',(#141359),#141362); +#141359 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141360,#141361), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#138968 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#138969 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#138970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#141360 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#141361 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#141362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#138971 = PCURVE('',#138972,#138977); -#138972 = PLANE('',#138973); -#138973 = AXIS2_PLACEMENT_3D('',#138974,#138975,#138976); -#138974 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#141363 = PCURVE('',#141364,#141369); +#141364 = PLANE('',#141365); +#141365 = AXIS2_PLACEMENT_3D('',#141366,#141367,#141368); +#141366 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#138975 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#138976 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138977 = DEFINITIONAL_REPRESENTATION('',(#138978),#138982); -#138978 = LINE('',#138979,#138980); -#138979 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#138980 = VECTOR('',#138981,1.); -#138981 = DIRECTION('',(-1.,0.E+000)); -#138982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138983 = ORIENTED_EDGE('',*,*,#138984,.T.); -#138984 = EDGE_CURVE('',#138958,#138775,#138985,.T.); -#138985 = SURFACE_CURVE('',#138986,(#138991,#138997),.PCURVE_S1.); -#138986 = CIRCLE('',#138987,0.208574704164); -#138987 = AXIS2_PLACEMENT_3D('',#138988,#138989,#138990); -#138988 = CARTESIAN_POINT('',(7.65,10.728168876214,2.640924866458E-017) - ); -#138989 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#138990 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#138991 = PCURVE('',#138811,#138992); -#138992 = DEFINITIONAL_REPRESENTATION('',(#138993),#138996); -#138993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#138994,#138995), +#141367 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141368 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141369 = DEFINITIONAL_REPRESENTATION('',(#141370),#141374); +#141370 = LINE('',#141371,#141372); +#141371 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#141372 = VECTOR('',#141373,1.); +#141373 = DIRECTION('',(-1.,0.E+000)); +#141374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141375 = ORIENTED_EDGE('',*,*,#141376,.T.); +#141376 = EDGE_CURVE('',#141350,#141167,#141377,.T.); +#141377 = SURFACE_CURVE('',#141378,(#141383,#141389),.PCURVE_S1.); +#141378 = CIRCLE('',#141379,0.208574704164); +#141379 = AXIS2_PLACEMENT_3D('',#141380,#141381,#141382); +#141380 = CARTESIAN_POINT('',(7.65,10.728168876214,2.640924866458E-017) + ); +#141381 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141382 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141383 = PCURVE('',#141203,#141384); +#141384 = DEFINITIONAL_REPRESENTATION('',(#141385),#141388); +#141385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141386,#141387), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#138994 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#138995 = CARTESIAN_POINT('',(4.772630242227,7.65)); -#138996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#138997 = PCURVE('',#87612,#138998); -#138998 = DEFINITIONAL_REPRESENTATION('',(#138999),#139003); -#138999 = CIRCLE('',#139000,0.208574704164); -#139000 = AXIS2_PLACEMENT_2D('',#139001,#139002); -#139001 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#139002 = DIRECTION('',(0.E+000,1.)); -#139003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139004 = ADVANCED_FACE('',(#139005),#138915,.T.); -#139005 = FACE_BOUND('',#139006,.T.); -#139006 = EDGE_LOOP('',(#139007,#139008,#139058,#139085)); -#139007 = ORIENTED_EDGE('',*,*,#138901,.F.); -#139008 = ORIENTED_EDGE('',*,*,#139009,.F.); -#139009 = EDGE_CURVE('',#139010,#138879,#139012,.T.); -#139010 = VERTEX_POINT('',#139011); -#139011 = CARTESIAN_POINT('',(7.85,10.419594812019,0.E+000)); -#139012 = SURFACE_CURVE('',#139013,(#139018,#139047),.PCURVE_S1.); -#139013 = CIRCLE('',#139014,0.308574064194); -#139014 = AXIS2_PLACEMENT_3D('',#139015,#139016,#139017); -#139015 = CARTESIAN_POINT('',(7.85,10.728168876214,2.640924866458E-017) - ); -#139016 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139017 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139018 = PCURVE('',#138915,#139019); -#139019 = DEFINITIONAL_REPRESENTATION('',(#139020),#139046); -#139020 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139021,#139022,#139023, - #139024,#139025,#139026,#139027,#139028,#139029,#139030,#139031, - #139032,#139033,#139034,#139035,#139036,#139037,#139038,#139039, - #139040,#139041,#139042,#139043,#139044,#139045),.UNSPECIFIED.,.F., +#141386 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#141387 = CARTESIAN_POINT('',(4.772630242227,7.65)); +#141388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141389 = PCURVE('',#90004,#141390); +#141390 = DEFINITIONAL_REPRESENTATION('',(#141391),#141395); +#141391 = CIRCLE('',#141392,0.208574704164); +#141392 = AXIS2_PLACEMENT_2D('',#141393,#141394); +#141393 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#141394 = DIRECTION('',(0.E+000,1.)); +#141395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141396 = ADVANCED_FACE('',(#141397),#141307,.T.); +#141397 = FACE_BOUND('',#141398,.T.); +#141398 = EDGE_LOOP('',(#141399,#141400,#141450,#141477)); +#141399 = ORIENTED_EDGE('',*,*,#141293,.F.); +#141400 = ORIENTED_EDGE('',*,*,#141401,.F.); +#141401 = EDGE_CURVE('',#141402,#141271,#141404,.T.); +#141402 = VERTEX_POINT('',#141403); +#141403 = CARTESIAN_POINT('',(7.85,10.419594812019,0.E+000)); +#141404 = SURFACE_CURVE('',#141405,(#141410,#141439),.PCURVE_S1.); +#141405 = CIRCLE('',#141406,0.308574064194); +#141406 = AXIS2_PLACEMENT_3D('',#141407,#141408,#141409); +#141407 = CARTESIAN_POINT('',(7.85,10.728168876214,2.640924866458E-017) + ); +#141408 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141409 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141410 = PCURVE('',#141307,#141411); +#141411 = DEFINITIONAL_REPRESENTATION('',(#141412),#141438); +#141412 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141413,#141414,#141415, + #141416,#141417,#141418,#141419,#141420,#141421,#141422,#141423, + #141424,#141425,#141426,#141427,#141428,#141429,#141430,#141431, + #141432,#141433,#141434,#141435,#141436,#141437),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -171347,102 +174349,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#139021 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#139022 = CARTESIAN_POINT('',(3.166141578807,7.85)); -#139023 = CARTESIAN_POINT('',(3.215239429242,7.85)); -#139024 = CARTESIAN_POINT('',(3.288886204895,7.85)); -#139025 = CARTESIAN_POINT('',(3.362532980548,7.85)); -#139026 = CARTESIAN_POINT('',(3.4361797562,7.85)); -#139027 = CARTESIAN_POINT('',(3.509826531853,7.85)); -#139028 = CARTESIAN_POINT('',(3.583473307505,7.85)); -#139029 = CARTESIAN_POINT('',(3.657120083158,7.85)); -#139030 = CARTESIAN_POINT('',(3.730766858811,7.85)); -#139031 = CARTESIAN_POINT('',(3.804413634463,7.85)); -#139032 = CARTESIAN_POINT('',(3.878060410116,7.85)); -#139033 = CARTESIAN_POINT('',(3.951707185768,7.85)); -#139034 = CARTESIAN_POINT('',(4.025353961421,7.85)); -#139035 = CARTESIAN_POINT('',(4.099000737074,7.85)); -#139036 = CARTESIAN_POINT('',(4.172647512726,7.85)); -#139037 = CARTESIAN_POINT('',(4.246294288379,7.85)); -#139038 = CARTESIAN_POINT('',(4.319941064031,7.85)); -#139039 = CARTESIAN_POINT('',(4.393587839684,7.85)); -#139040 = CARTESIAN_POINT('',(4.467234615337,7.85)); -#139041 = CARTESIAN_POINT('',(4.540881390989,7.85)); -#139042 = CARTESIAN_POINT('',(4.614528166642,7.85)); -#139043 = CARTESIAN_POINT('',(4.688174942294,7.85)); -#139044 = CARTESIAN_POINT('',(4.737272792729,7.85)); -#139045 = CARTESIAN_POINT('',(4.761821717947,7.85)); -#139046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139047 = PCURVE('',#87668,#139048); -#139048 = DEFINITIONAL_REPRESENTATION('',(#139049),#139057); -#139049 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139050,#139051,#139052, - #139053,#139054,#139055,#139056),.UNSPECIFIED.,.T.,.F.) +#141413 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#141414 = CARTESIAN_POINT('',(3.166141578807,7.85)); +#141415 = CARTESIAN_POINT('',(3.215239429242,7.85)); +#141416 = CARTESIAN_POINT('',(3.288886204895,7.85)); +#141417 = CARTESIAN_POINT('',(3.362532980548,7.85)); +#141418 = CARTESIAN_POINT('',(3.4361797562,7.85)); +#141419 = CARTESIAN_POINT('',(3.509826531853,7.85)); +#141420 = CARTESIAN_POINT('',(3.583473307505,7.85)); +#141421 = CARTESIAN_POINT('',(3.657120083158,7.85)); +#141422 = CARTESIAN_POINT('',(3.730766858811,7.85)); +#141423 = CARTESIAN_POINT('',(3.804413634463,7.85)); +#141424 = CARTESIAN_POINT('',(3.878060410116,7.85)); +#141425 = CARTESIAN_POINT('',(3.951707185768,7.85)); +#141426 = CARTESIAN_POINT('',(4.025353961421,7.85)); +#141427 = CARTESIAN_POINT('',(4.099000737074,7.85)); +#141428 = CARTESIAN_POINT('',(4.172647512726,7.85)); +#141429 = CARTESIAN_POINT('',(4.246294288379,7.85)); +#141430 = CARTESIAN_POINT('',(4.319941064031,7.85)); +#141431 = CARTESIAN_POINT('',(4.393587839684,7.85)); +#141432 = CARTESIAN_POINT('',(4.467234615337,7.85)); +#141433 = CARTESIAN_POINT('',(4.540881390989,7.85)); +#141434 = CARTESIAN_POINT('',(4.614528166642,7.85)); +#141435 = CARTESIAN_POINT('',(4.688174942294,7.85)); +#141436 = CARTESIAN_POINT('',(4.737272792729,7.85)); +#141437 = CARTESIAN_POINT('',(4.761821717947,7.85)); +#141438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141439 = PCURVE('',#90060,#141440); +#141440 = DEFINITIONAL_REPRESENTATION('',(#141441),#141449); +#141441 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141442,#141443,#141444, + #141445,#141446,#141447,#141448),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#139050 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#139051 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#139052 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#139053 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#139054 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#139055 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#139056 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#139057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139058 = ORIENTED_EDGE('',*,*,#139059,.F.); -#139059 = EDGE_CURVE('',#139060,#139010,#139062,.T.); -#139060 = VERTEX_POINT('',#139061); -#139061 = CARTESIAN_POINT('',(7.65,10.419594812019,0.E+000)); -#139062 = SURFACE_CURVE('',#139063,(#139067,#139073),.PCURVE_S1.); -#139063 = LINE('',#139064,#139065); -#139064 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#141442 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#141443 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#141444 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#141445 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#141446 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#141447 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#141448 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#141449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141450 = ORIENTED_EDGE('',*,*,#141451,.F.); +#141451 = EDGE_CURVE('',#141452,#141402,#141454,.T.); +#141452 = VERTEX_POINT('',#141453); +#141453 = CARTESIAN_POINT('',(7.65,10.419594812019,0.E+000)); +#141454 = SURFACE_CURVE('',#141455,(#141459,#141465),.PCURVE_S1.); +#141455 = LINE('',#141456,#141457); +#141456 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#139065 = VECTOR('',#139066,1.); -#139066 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139067 = PCURVE('',#138915,#139068); -#139068 = DEFINITIONAL_REPRESENTATION('',(#139069),#139072); -#139069 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139070,#139071), +#141457 = VECTOR('',#141458,1.); +#141458 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141459 = PCURVE('',#141307,#141460); +#141460 = DEFINITIONAL_REPRESENTATION('',(#141461),#141464); +#141461 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141462,#141463), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#139070 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#139071 = CARTESIAN_POINT('',(3.14159265359,7.85)); -#139072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#141462 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#141463 = CARTESIAN_POINT('',(3.14159265359,7.85)); +#141464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139073 = PCURVE('',#139074,#139079); -#139074 = PLANE('',#139075); -#139075 = AXIS2_PLACEMENT_3D('',#139076,#139077,#139078); -#139076 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#141465 = PCURVE('',#141466,#141471); +#141466 = PLANE('',#141467); +#141467 = AXIS2_PLACEMENT_3D('',#141468,#141469,#141470); +#141468 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#139077 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139078 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139079 = DEFINITIONAL_REPRESENTATION('',(#139080),#139084); -#139080 = LINE('',#139081,#139082); -#139081 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#139082 = VECTOR('',#139083,1.); -#139083 = DIRECTION('',(-1.,0.E+000)); -#139084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139085 = ORIENTED_EDGE('',*,*,#139086,.T.); -#139086 = EDGE_CURVE('',#139060,#138826,#139087,.T.); -#139087 = SURFACE_CURVE('',#139088,(#139093,#139122),.PCURVE_S1.); -#139088 = CIRCLE('',#139089,0.308574064194); -#139089 = AXIS2_PLACEMENT_3D('',#139090,#139091,#139092); -#139090 = CARTESIAN_POINT('',(7.65,10.728168876214,2.640924866458E-017) - ); -#139091 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139092 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139093 = PCURVE('',#138915,#139094); -#139094 = DEFINITIONAL_REPRESENTATION('',(#139095),#139121); -#139095 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139096,#139097,#139098, - #139099,#139100,#139101,#139102,#139103,#139104,#139105,#139106, - #139107,#139108,#139109,#139110,#139111,#139112,#139113,#139114, - #139115,#139116,#139117,#139118,#139119,#139120),.UNSPECIFIED.,.F., +#141469 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141470 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141471 = DEFINITIONAL_REPRESENTATION('',(#141472),#141476); +#141472 = LINE('',#141473,#141474); +#141473 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#141474 = VECTOR('',#141475,1.); +#141475 = DIRECTION('',(-1.,0.E+000)); +#141476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141477 = ORIENTED_EDGE('',*,*,#141478,.T.); +#141478 = EDGE_CURVE('',#141452,#141218,#141479,.T.); +#141479 = SURFACE_CURVE('',#141480,(#141485,#141514),.PCURVE_S1.); +#141480 = CIRCLE('',#141481,0.308574064194); +#141481 = AXIS2_PLACEMENT_3D('',#141482,#141483,#141484); +#141482 = CARTESIAN_POINT('',(7.65,10.728168876214,2.640924866458E-017) + ); +#141483 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141484 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#141485 = PCURVE('',#141307,#141486); +#141486 = DEFINITIONAL_REPRESENTATION('',(#141487),#141513); +#141487 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141488,#141489,#141490, + #141491,#141492,#141493,#141494,#141495,#141496,#141497,#141498, + #141499,#141500,#141501,#141502,#141503,#141504,#141505,#141506, + #141507,#141508,#141509,#141510,#141511,#141512),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -171450,339 +174452,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#139096 = CARTESIAN_POINT('',(3.14159265359,7.65)); -#139097 = CARTESIAN_POINT('',(3.166141578807,7.65)); -#139098 = CARTESIAN_POINT('',(3.215239429242,7.65)); -#139099 = CARTESIAN_POINT('',(3.288886204895,7.65)); -#139100 = CARTESIAN_POINT('',(3.362532980548,7.65)); -#139101 = CARTESIAN_POINT('',(3.4361797562,7.65)); -#139102 = CARTESIAN_POINT('',(3.509826531853,7.65)); -#139103 = CARTESIAN_POINT('',(3.583473307505,7.65)); -#139104 = CARTESIAN_POINT('',(3.657120083158,7.65)); -#139105 = CARTESIAN_POINT('',(3.730766858811,7.65)); -#139106 = CARTESIAN_POINT('',(3.804413634463,7.65)); -#139107 = CARTESIAN_POINT('',(3.878060410116,7.65)); -#139108 = CARTESIAN_POINT('',(3.951707185768,7.65)); -#139109 = CARTESIAN_POINT('',(4.025353961421,7.65)); -#139110 = CARTESIAN_POINT('',(4.099000737074,7.65)); -#139111 = CARTESIAN_POINT('',(4.172647512726,7.65)); -#139112 = CARTESIAN_POINT('',(4.246294288379,7.65)); -#139113 = CARTESIAN_POINT('',(4.319941064031,7.65)); -#139114 = CARTESIAN_POINT('',(4.393587839684,7.65)); -#139115 = CARTESIAN_POINT('',(4.467234615337,7.65)); -#139116 = CARTESIAN_POINT('',(4.540881390989,7.65)); -#139117 = CARTESIAN_POINT('',(4.614528166642,7.65)); -#139118 = CARTESIAN_POINT('',(4.688174942294,7.65)); -#139119 = CARTESIAN_POINT('',(4.737272792729,7.65)); -#139120 = CARTESIAN_POINT('',(4.761821717947,7.65)); -#139121 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139122 = PCURVE('',#87612,#139123); -#139123 = DEFINITIONAL_REPRESENTATION('',(#139124),#139128); -#139124 = CIRCLE('',#139125,0.308574064194); -#139125 = AXIS2_PLACEMENT_2D('',#139126,#139127); -#139126 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#139127 = DIRECTION('',(0.E+000,1.)); -#139128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139129 = ADVANCED_FACE('',(#139130),#139074,.F.); -#139130 = FACE_BOUND('',#139131,.T.); -#139131 = EDGE_LOOP('',(#139132,#139161,#139182,#139183)); -#139132 = ORIENTED_EDGE('',*,*,#139133,.F.); -#139133 = EDGE_CURVE('',#139134,#139136,#139138,.T.); -#139134 = VERTEX_POINT('',#139135); -#139135 = CARTESIAN_POINT('',(7.65,10.419594812019,0.530776333563)); -#139136 = VERTEX_POINT('',#139137); -#139137 = CARTESIAN_POINT('',(7.85,10.419594812019,0.530776333563)); -#139138 = SURFACE_CURVE('',#139139,(#139143,#139150),.PCURVE_S1.); -#139139 = LINE('',#139140,#139141); -#139140 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#141488 = CARTESIAN_POINT('',(3.14159265359,7.65)); +#141489 = CARTESIAN_POINT('',(3.166141578807,7.65)); +#141490 = CARTESIAN_POINT('',(3.215239429242,7.65)); +#141491 = CARTESIAN_POINT('',(3.288886204895,7.65)); +#141492 = CARTESIAN_POINT('',(3.362532980548,7.65)); +#141493 = CARTESIAN_POINT('',(3.4361797562,7.65)); +#141494 = CARTESIAN_POINT('',(3.509826531853,7.65)); +#141495 = CARTESIAN_POINT('',(3.583473307505,7.65)); +#141496 = CARTESIAN_POINT('',(3.657120083158,7.65)); +#141497 = CARTESIAN_POINT('',(3.730766858811,7.65)); +#141498 = CARTESIAN_POINT('',(3.804413634463,7.65)); +#141499 = CARTESIAN_POINT('',(3.878060410116,7.65)); +#141500 = CARTESIAN_POINT('',(3.951707185768,7.65)); +#141501 = CARTESIAN_POINT('',(4.025353961421,7.65)); +#141502 = CARTESIAN_POINT('',(4.099000737074,7.65)); +#141503 = CARTESIAN_POINT('',(4.172647512726,7.65)); +#141504 = CARTESIAN_POINT('',(4.246294288379,7.65)); +#141505 = CARTESIAN_POINT('',(4.319941064031,7.65)); +#141506 = CARTESIAN_POINT('',(4.393587839684,7.65)); +#141507 = CARTESIAN_POINT('',(4.467234615337,7.65)); +#141508 = CARTESIAN_POINT('',(4.540881390989,7.65)); +#141509 = CARTESIAN_POINT('',(4.614528166642,7.65)); +#141510 = CARTESIAN_POINT('',(4.688174942294,7.65)); +#141511 = CARTESIAN_POINT('',(4.737272792729,7.65)); +#141512 = CARTESIAN_POINT('',(4.761821717947,7.65)); +#141513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141514 = PCURVE('',#90004,#141515); +#141515 = DEFINITIONAL_REPRESENTATION('',(#141516),#141520); +#141516 = CIRCLE('',#141517,0.308574064194); +#141517 = AXIS2_PLACEMENT_2D('',#141518,#141519); +#141518 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#141519 = DIRECTION('',(0.E+000,1.)); +#141520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141521 = ADVANCED_FACE('',(#141522),#141466,.F.); +#141522 = FACE_BOUND('',#141523,.T.); +#141523 = EDGE_LOOP('',(#141524,#141553,#141574,#141575)); +#141524 = ORIENTED_EDGE('',*,*,#141525,.F.); +#141525 = EDGE_CURVE('',#141526,#141528,#141530,.T.); +#141526 = VERTEX_POINT('',#141527); +#141527 = CARTESIAN_POINT('',(7.65,10.419594812019,0.530776333563)); +#141528 = VERTEX_POINT('',#141529); +#141529 = CARTESIAN_POINT('',(7.85,10.419594812019,0.530776333563)); +#141530 = SURFACE_CURVE('',#141531,(#141535,#141542),.PCURVE_S1.); +#141531 = LINE('',#141532,#141533); +#141532 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#139141 = VECTOR('',#139142,1.); -#139142 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139143 = PCURVE('',#139074,#139144); -#139144 = DEFINITIONAL_REPRESENTATION('',(#139145),#139149); -#139145 = LINE('',#139146,#139147); -#139146 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139147 = VECTOR('',#139148,1.); -#139148 = DIRECTION('',(-1.,0.E+000)); -#139149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139150 = PCURVE('',#139151,#139156); -#139151 = CYLINDRICAL_SURFACE('',#139152,0.119270391569); -#139152 = AXIS2_PLACEMENT_3D('',#139153,#139154,#139155); -#139153 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#141533 = VECTOR('',#141534,1.); +#141534 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141535 = PCURVE('',#141466,#141536); +#141536 = DEFINITIONAL_REPRESENTATION('',(#141537),#141541); +#141537 = LINE('',#141538,#141539); +#141538 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141539 = VECTOR('',#141540,1.); +#141540 = DIRECTION('',(-1.,0.E+000)); +#141541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141542 = PCURVE('',#141543,#141548); +#141543 = CYLINDRICAL_SURFACE('',#141544,0.119270391569); +#141544 = AXIS2_PLACEMENT_3D('',#141545,#141546,#141547); +#141545 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#139154 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139155 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139156 = DEFINITIONAL_REPRESENTATION('',(#139157),#139160); -#139157 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139158,#139159), +#141546 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141547 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141548 = DEFINITIONAL_REPRESENTATION('',(#141549),#141552); +#141549 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141550,#141551), .UNSPECIFIED.,.F.,.F.,(2,2),(7.65,7.85),.PIECEWISE_BEZIER_KNOTS.); -#139158 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#139159 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#139160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#141550 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#141551 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#141552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141553 = ORIENTED_EDGE('',*,*,#141554,.T.); +#141554 = EDGE_CURVE('',#141526,#141452,#141555,.T.); +#141555 = SURFACE_CURVE('',#141556,(#141560,#141567),.PCURVE_S1.); +#141556 = LINE('',#141557,#141558); +#141557 = CARTESIAN_POINT('',(7.65,10.419594812019,0.530776333563)); +#141558 = VECTOR('',#141559,1.); +#141559 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#141560 = PCURVE('',#141466,#141561); +#141561 = DEFINITIONAL_REPRESENTATION('',(#141562),#141566); +#141562 = LINE('',#141563,#141564); +#141563 = CARTESIAN_POINT('',(-7.65,0.E+000)); +#141564 = VECTOR('',#141565,1.); +#141565 = DIRECTION('',(0.E+000,-1.)); +#141566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141567 = PCURVE('',#90004,#141568); +#141568 = DEFINITIONAL_REPRESENTATION('',(#141569),#141573); +#141569 = LINE('',#141570,#141571); +#141570 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#141571 = VECTOR('',#141572,1.); +#141572 = DIRECTION('',(1.,0.E+000)); +#141573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141574 = ORIENTED_EDGE('',*,*,#141451,.T.); +#141575 = ORIENTED_EDGE('',*,*,#141576,.F.); +#141576 = EDGE_CURVE('',#141528,#141402,#141577,.T.); +#141577 = SURFACE_CURVE('',#141578,(#141582,#141589),.PCURVE_S1.); +#141578 = LINE('',#141579,#141580); +#141579 = CARTESIAN_POINT('',(7.85,10.419594812019,0.530776333563)); +#141580 = VECTOR('',#141581,1.); +#141581 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#141582 = PCURVE('',#141466,#141583); +#141583 = DEFINITIONAL_REPRESENTATION('',(#141584),#141588); +#141584 = LINE('',#141585,#141586); +#141585 = CARTESIAN_POINT('',(-7.85,0.E+000)); +#141586 = VECTOR('',#141587,1.); +#141587 = DIRECTION('',(0.E+000,-1.)); +#141588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141589 = PCURVE('',#90060,#141590); +#141590 = DEFINITIONAL_REPRESENTATION('',(#141591),#141595); +#141591 = LINE('',#141592,#141593); +#141592 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#141593 = VECTOR('',#141594,1.); +#141594 = DIRECTION('',(-1.,0.E+000)); +#141595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141596 = ADVANCED_FACE('',(#141597),#141364,.F.); +#141597 = FACE_BOUND('',#141598,.T.); +#141598 = EDGE_LOOP('',(#141599,#141628,#141649,#141650)); +#141599 = ORIENTED_EDGE('',*,*,#141600,.F.); +#141600 = EDGE_CURVE('',#141601,#141603,#141605,.T.); +#141601 = VERTEX_POINT('',#141602); +#141602 = CARTESIAN_POINT('',(7.85,10.51959417205,0.530776333563)); +#141603 = VERTEX_POINT('',#141604); +#141604 = CARTESIAN_POINT('',(7.65,10.51959417205,0.530776333563)); +#141605 = SURFACE_CURVE('',#141606,(#141610,#141617),.PCURVE_S1.); +#141606 = LINE('',#141607,#141608); +#141607 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, + 0.530776333563)); +#141608 = VECTOR('',#141609,1.); +#141609 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141610 = PCURVE('',#141364,#141611); +#141611 = DEFINITIONAL_REPRESENTATION('',(#141612),#141616); +#141612 = LINE('',#141613,#141614); +#141613 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141614 = VECTOR('',#141615,1.); +#141615 = DIRECTION('',(-1.,0.E+000)); +#141616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139161 = ORIENTED_EDGE('',*,*,#139162,.T.); -#139162 = EDGE_CURVE('',#139134,#139060,#139163,.T.); -#139163 = SURFACE_CURVE('',#139164,(#139168,#139175),.PCURVE_S1.); -#139164 = LINE('',#139165,#139166); -#139165 = CARTESIAN_POINT('',(7.65,10.419594812019,0.530776333563)); -#139166 = VECTOR('',#139167,1.); -#139167 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#139168 = PCURVE('',#139074,#139169); -#139169 = DEFINITIONAL_REPRESENTATION('',(#139170),#139174); -#139170 = LINE('',#139171,#139172); -#139171 = CARTESIAN_POINT('',(-7.65,0.E+000)); -#139172 = VECTOR('',#139173,1.); -#139173 = DIRECTION('',(0.E+000,-1.)); -#139174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139175 = PCURVE('',#87612,#139176); -#139176 = DEFINITIONAL_REPRESENTATION('',(#139177),#139181); -#139177 = LINE('',#139178,#139179); -#139178 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#139179 = VECTOR('',#139180,1.); -#139180 = DIRECTION('',(1.,0.E+000)); -#139181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139182 = ORIENTED_EDGE('',*,*,#139059,.T.); -#139183 = ORIENTED_EDGE('',*,*,#139184,.F.); -#139184 = EDGE_CURVE('',#139136,#139010,#139185,.T.); -#139185 = SURFACE_CURVE('',#139186,(#139190,#139197),.PCURVE_S1.); -#139186 = LINE('',#139187,#139188); -#139187 = CARTESIAN_POINT('',(7.85,10.419594812019,0.530776333563)); -#139188 = VECTOR('',#139189,1.); -#139189 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#139190 = PCURVE('',#139074,#139191); -#139191 = DEFINITIONAL_REPRESENTATION('',(#139192),#139196); -#139192 = LINE('',#139193,#139194); -#139193 = CARTESIAN_POINT('',(-7.85,0.E+000)); -#139194 = VECTOR('',#139195,1.); -#139195 = DIRECTION('',(0.E+000,-1.)); -#139196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139197 = PCURVE('',#87668,#139198); -#139198 = DEFINITIONAL_REPRESENTATION('',(#139199),#139203); -#139199 = LINE('',#139200,#139201); -#139200 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#139201 = VECTOR('',#139202,1.); -#139202 = DIRECTION('',(-1.,0.E+000)); -#139203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139204 = ADVANCED_FACE('',(#139205),#138972,.F.); -#139205 = FACE_BOUND('',#139206,.T.); -#139206 = EDGE_LOOP('',(#139207,#139236,#139257,#139258)); -#139207 = ORIENTED_EDGE('',*,*,#139208,.F.); -#139208 = EDGE_CURVE('',#139209,#139211,#139213,.T.); -#139209 = VERTEX_POINT('',#139210); -#139210 = CARTESIAN_POINT('',(7.85,10.51959417205,0.530776333563)); -#139211 = VERTEX_POINT('',#139212); -#139212 = CARTESIAN_POINT('',(7.65,10.51959417205,0.530776333563)); -#139213 = SURFACE_CURVE('',#139214,(#139218,#139225),.PCURVE_S1.); -#139214 = LINE('',#139215,#139216); -#139215 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#141617 = PCURVE('',#141618,#141623); +#141618 = CYLINDRICAL_SURFACE('',#141619,0.2192697516); +#141619 = AXIS2_PLACEMENT_3D('',#141620,#141621,#141622); +#141620 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#139216 = VECTOR('',#139217,1.); -#139217 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139218 = PCURVE('',#138972,#139219); -#139219 = DEFINITIONAL_REPRESENTATION('',(#139220),#139224); -#139220 = LINE('',#139221,#139222); -#139221 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139222 = VECTOR('',#139223,1.); -#139223 = DIRECTION('',(-1.,0.E+000)); -#139224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139225 = PCURVE('',#139226,#139231); -#139226 = CYLINDRICAL_SURFACE('',#139227,0.2192697516); -#139227 = AXIS2_PLACEMENT_3D('',#139228,#139229,#139230); -#139228 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, - 0.530776333563)); -#139229 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139230 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139231 = DEFINITIONAL_REPRESENTATION('',(#139232),#139235); -#139232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139233,#139234), +#141621 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141622 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141623 = DEFINITIONAL_REPRESENTATION('',(#141624),#141627); +#141624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141625,#141626), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.85,-7.65),.PIECEWISE_BEZIER_KNOTS.); -#139233 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#139234 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#139235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139236 = ORIENTED_EDGE('',*,*,#139237,.T.); -#139237 = EDGE_CURVE('',#139209,#138931,#139238,.T.); -#139238 = SURFACE_CURVE('',#139239,(#139243,#139250),.PCURVE_S1.); -#139239 = LINE('',#139240,#139241); -#139240 = CARTESIAN_POINT('',(7.85,10.51959417205,0.530776333563)); -#139241 = VECTOR('',#139242,1.); -#139242 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#139243 = PCURVE('',#138972,#139244); -#139244 = DEFINITIONAL_REPRESENTATION('',(#139245),#139249); -#139245 = LINE('',#139246,#139247); -#139246 = CARTESIAN_POINT('',(7.85,0.E+000)); -#139247 = VECTOR('',#139248,1.); -#139248 = DIRECTION('',(0.E+000,-1.)); -#139249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139250 = PCURVE('',#87668,#139251); -#139251 = DEFINITIONAL_REPRESENTATION('',(#139252),#139256); -#139252 = LINE('',#139253,#139254); -#139253 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#139254 = VECTOR('',#139255,1.); -#139255 = DIRECTION('',(-1.,0.E+000)); -#139256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139257 = ORIENTED_EDGE('',*,*,#138957,.T.); -#139258 = ORIENTED_EDGE('',*,*,#139259,.F.); -#139259 = EDGE_CURVE('',#139211,#138958,#139260,.T.); -#139260 = SURFACE_CURVE('',#139261,(#139265,#139272),.PCURVE_S1.); -#139261 = LINE('',#139262,#139263); -#139262 = CARTESIAN_POINT('',(7.65,10.51959417205,0.530776333563)); -#139263 = VECTOR('',#139264,1.); -#139264 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#139265 = PCURVE('',#138972,#139266); -#139266 = DEFINITIONAL_REPRESENTATION('',(#139267),#139271); -#139267 = LINE('',#139268,#139269); -#139268 = CARTESIAN_POINT('',(7.65,0.E+000)); -#139269 = VECTOR('',#139270,1.); -#139270 = DIRECTION('',(0.E+000,-1.)); -#139271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139272 = PCURVE('',#87612,#139273); -#139273 = DEFINITIONAL_REPRESENTATION('',(#139274),#139278); -#139274 = LINE('',#139275,#139276); -#139275 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#139276 = VECTOR('',#139277,1.); -#139277 = DIRECTION('',(1.,0.E+000)); -#139278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139279 = ADVANCED_FACE('',(#139280),#139151,.F.); -#139280 = FACE_BOUND('',#139281,.F.); -#139281 = EDGE_LOOP('',(#139282,#139309,#139331,#139352)); -#139282 = ORIENTED_EDGE('',*,*,#139283,.F.); -#139283 = EDGE_CURVE('',#139284,#139134,#139286,.T.); -#139284 = VERTEX_POINT('',#139285); -#139285 = CARTESIAN_POINT('',(7.65,10.303662633502,0.65)); -#139286 = SURFACE_CURVE('',#139287,(#139292,#139298),.PCURVE_S1.); -#139287 = CIRCLE('',#139288,0.119270391569); -#139288 = AXIS2_PLACEMENT_3D('',#139289,#139290,#139291); -#139289 = CARTESIAN_POINT('',(7.65,10.30032442045,0.530776333563)); -#139290 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139291 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139292 = PCURVE('',#139151,#139293); -#139293 = DEFINITIONAL_REPRESENTATION('',(#139294),#139297); -#139294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139295,#139296), +#141625 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#141626 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#141627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141628 = ORIENTED_EDGE('',*,*,#141629,.T.); +#141629 = EDGE_CURVE('',#141601,#141323,#141630,.T.); +#141630 = SURFACE_CURVE('',#141631,(#141635,#141642),.PCURVE_S1.); +#141631 = LINE('',#141632,#141633); +#141632 = CARTESIAN_POINT('',(7.85,10.51959417205,0.530776333563)); +#141633 = VECTOR('',#141634,1.); +#141634 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#141635 = PCURVE('',#141364,#141636); +#141636 = DEFINITIONAL_REPRESENTATION('',(#141637),#141641); +#141637 = LINE('',#141638,#141639); +#141638 = CARTESIAN_POINT('',(7.85,0.E+000)); +#141639 = VECTOR('',#141640,1.); +#141640 = DIRECTION('',(0.E+000,-1.)); +#141641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141642 = PCURVE('',#90060,#141643); +#141643 = DEFINITIONAL_REPRESENTATION('',(#141644),#141648); +#141644 = LINE('',#141645,#141646); +#141645 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#141646 = VECTOR('',#141647,1.); +#141647 = DIRECTION('',(-1.,0.E+000)); +#141648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141649 = ORIENTED_EDGE('',*,*,#141349,.T.); +#141650 = ORIENTED_EDGE('',*,*,#141651,.F.); +#141651 = EDGE_CURVE('',#141603,#141350,#141652,.T.); +#141652 = SURFACE_CURVE('',#141653,(#141657,#141664),.PCURVE_S1.); +#141653 = LINE('',#141654,#141655); +#141654 = CARTESIAN_POINT('',(7.65,10.51959417205,0.530776333563)); +#141655 = VECTOR('',#141656,1.); +#141656 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#141657 = PCURVE('',#141364,#141658); +#141658 = DEFINITIONAL_REPRESENTATION('',(#141659),#141663); +#141659 = LINE('',#141660,#141661); +#141660 = CARTESIAN_POINT('',(7.65,0.E+000)); +#141661 = VECTOR('',#141662,1.); +#141662 = DIRECTION('',(0.E+000,-1.)); +#141663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141664 = PCURVE('',#90004,#141665); +#141665 = DEFINITIONAL_REPRESENTATION('',(#141666),#141670); +#141666 = LINE('',#141667,#141668); +#141667 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#141668 = VECTOR('',#141669,1.); +#141669 = DIRECTION('',(1.,0.E+000)); +#141670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141671 = ADVANCED_FACE('',(#141672),#141543,.F.); +#141672 = FACE_BOUND('',#141673,.F.); +#141673 = EDGE_LOOP('',(#141674,#141701,#141723,#141744)); +#141674 = ORIENTED_EDGE('',*,*,#141675,.F.); +#141675 = EDGE_CURVE('',#141676,#141526,#141678,.T.); +#141676 = VERTEX_POINT('',#141677); +#141677 = CARTESIAN_POINT('',(7.65,10.303662633502,0.65)); +#141678 = SURFACE_CURVE('',#141679,(#141684,#141690),.PCURVE_S1.); +#141679 = CIRCLE('',#141680,0.119270391569); +#141680 = AXIS2_PLACEMENT_3D('',#141681,#141682,#141683); +#141681 = CARTESIAN_POINT('',(7.65,10.30032442045,0.530776333563)); +#141682 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141683 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141684 = PCURVE('',#141543,#141685); +#141685 = DEFINITIONAL_REPRESENTATION('',(#141686),#141689); +#141686 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141687,#141688), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#139295 = CARTESIAN_POINT('',(1.598788597134,-7.65)); -#139296 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#139297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#141687 = CARTESIAN_POINT('',(1.598788597134,-7.65)); +#141688 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#141689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139298 = PCURVE('',#87612,#139299); -#139299 = DEFINITIONAL_REPRESENTATION('',(#139300),#139308); -#139300 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139301,#139302,#139303, - #139304,#139305,#139306,#139307),.UNSPECIFIED.,.T.,.F.) +#141690 = PCURVE('',#90004,#141691); +#141691 = DEFINITIONAL_REPRESENTATION('',(#141692),#141700); +#141692 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141693,#141694,#141695, + #141696,#141697,#141698,#141699),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#139301 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#139302 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#139303 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#139304 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#139305 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#139306 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#139307 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#139308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139309 = ORIENTED_EDGE('',*,*,#139310,.F.); -#139310 = EDGE_CURVE('',#139311,#139284,#139313,.T.); -#139311 = VERTEX_POINT('',#139312); -#139312 = CARTESIAN_POINT('',(7.85,10.303662633502,0.65)); -#139313 = SURFACE_CURVE('',#139314,(#139318,#139324),.PCURVE_S1.); -#139314 = LINE('',#139315,#139316); -#139315 = CARTESIAN_POINT('',(7.65,10.303662633502,0.65)); -#139316 = VECTOR('',#139317,1.); -#139317 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139318 = PCURVE('',#139151,#139319); -#139319 = DEFINITIONAL_REPRESENTATION('',(#139320),#139323); -#139320 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139321,#139322), +#141693 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#141694 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#141695 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#141696 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#141697 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#141698 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#141699 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#141700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141701 = ORIENTED_EDGE('',*,*,#141702,.F.); +#141702 = EDGE_CURVE('',#141703,#141676,#141705,.T.); +#141703 = VERTEX_POINT('',#141704); +#141704 = CARTESIAN_POINT('',(7.85,10.303662633502,0.65)); +#141705 = SURFACE_CURVE('',#141706,(#141710,#141716),.PCURVE_S1.); +#141706 = LINE('',#141707,#141708); +#141707 = CARTESIAN_POINT('',(7.65,10.303662633502,0.65)); +#141708 = VECTOR('',#141709,1.); +#141709 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141710 = PCURVE('',#141543,#141711); +#141711 = DEFINITIONAL_REPRESENTATION('',(#141712),#141715); +#141712 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141713,#141714), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#139321 = CARTESIAN_POINT('',(1.598788597134,-7.85)); -#139322 = CARTESIAN_POINT('',(1.598788597134,-7.65)); -#139323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139324 = PCURVE('',#87640,#139325); -#139325 = DEFINITIONAL_REPRESENTATION('',(#139326),#139330); -#139326 = LINE('',#139327,#139328); -#139327 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#139328 = VECTOR('',#139329,1.); -#139329 = DIRECTION('',(-8.881784197001E-016,-1.)); -#139330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139331 = ORIENTED_EDGE('',*,*,#139332,.T.); -#139332 = EDGE_CURVE('',#139311,#139136,#139333,.T.); -#139333 = SURFACE_CURVE('',#139334,(#139339,#139345),.PCURVE_S1.); -#139334 = CIRCLE('',#139335,0.119270391569); -#139335 = AXIS2_PLACEMENT_3D('',#139336,#139337,#139338); -#139336 = CARTESIAN_POINT('',(7.85,10.30032442045,0.530776333563)); -#139337 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139338 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139339 = PCURVE('',#139151,#139340); -#139340 = DEFINITIONAL_REPRESENTATION('',(#139341),#139344); -#139341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139342,#139343), +#141713 = CARTESIAN_POINT('',(1.598788597134,-7.85)); +#141714 = CARTESIAN_POINT('',(1.598788597134,-7.65)); +#141715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141716 = PCURVE('',#90032,#141717); +#141717 = DEFINITIONAL_REPRESENTATION('',(#141718),#141722); +#141718 = LINE('',#141719,#141720); +#141719 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#141720 = VECTOR('',#141721,1.); +#141721 = DIRECTION('',(-8.881784197001E-016,-1.)); +#141722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141723 = ORIENTED_EDGE('',*,*,#141724,.T.); +#141724 = EDGE_CURVE('',#141703,#141528,#141725,.T.); +#141725 = SURFACE_CURVE('',#141726,(#141731,#141737),.PCURVE_S1.); +#141726 = CIRCLE('',#141727,0.119270391569); +#141727 = AXIS2_PLACEMENT_3D('',#141728,#141729,#141730); +#141728 = CARTESIAN_POINT('',(7.85,10.30032442045,0.530776333563)); +#141729 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141730 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141731 = PCURVE('',#141543,#141732); +#141732 = DEFINITIONAL_REPRESENTATION('',(#141733),#141736); +#141733 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141734,#141735), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#139342 = CARTESIAN_POINT('',(1.598788597134,-7.85)); -#139343 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#139344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139345 = PCURVE('',#87668,#139346); -#139346 = DEFINITIONAL_REPRESENTATION('',(#139347),#139351); -#139347 = CIRCLE('',#139348,0.119270391569); -#139348 = AXIS2_PLACEMENT_2D('',#139349,#139350); -#139349 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#139350 = DIRECTION('',(0.E+000,-1.)); -#139351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139352 = ORIENTED_EDGE('',*,*,#139133,.F.); -#139353 = ADVANCED_FACE('',(#139354),#139226,.T.); -#139354 = FACE_BOUND('',#139355,.T.); -#139355 = EDGE_LOOP('',(#139356,#139402,#139403,#139453)); -#139356 = ORIENTED_EDGE('',*,*,#139357,.T.); -#139357 = EDGE_CURVE('',#139358,#139209,#139360,.T.); -#139358 = VERTEX_POINT('',#139359); -#139359 = CARTESIAN_POINT('',(7.85,10.304819755875,0.75)); -#139360 = SURFACE_CURVE('',#139361,(#139366,#139395),.PCURVE_S1.); -#139361 = CIRCLE('',#139362,0.2192697516); -#139362 = AXIS2_PLACEMENT_3D('',#139363,#139364,#139365); -#139363 = CARTESIAN_POINT('',(7.85,10.30032442045,0.530776333563)); -#139364 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139365 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139366 = PCURVE('',#139226,#139367); -#139367 = DEFINITIONAL_REPRESENTATION('',(#139368),#139394); -#139368 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139369,#139370,#139371, - #139372,#139373,#139374,#139375,#139376,#139377,#139378,#139379, - #139380,#139381,#139382,#139383,#139384,#139385,#139386,#139387, - #139388,#139389,#139390,#139391,#139392,#139393),.UNSPECIFIED.,.F., +#141734 = CARTESIAN_POINT('',(1.598788597134,-7.85)); +#141735 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#141736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141737 = PCURVE('',#90060,#141738); +#141738 = DEFINITIONAL_REPRESENTATION('',(#141739),#141743); +#141739 = CIRCLE('',#141740,0.119270391569); +#141740 = AXIS2_PLACEMENT_2D('',#141741,#141742); +#141741 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#141742 = DIRECTION('',(0.E+000,-1.)); +#141743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141744 = ORIENTED_EDGE('',*,*,#141525,.F.); +#141745 = ADVANCED_FACE('',(#141746),#141618,.T.); +#141746 = FACE_BOUND('',#141747,.T.); +#141747 = EDGE_LOOP('',(#141748,#141794,#141795,#141845)); +#141748 = ORIENTED_EDGE('',*,*,#141749,.T.); +#141749 = EDGE_CURVE('',#141750,#141601,#141752,.T.); +#141750 = VERTEX_POINT('',#141751); +#141751 = CARTESIAN_POINT('',(7.85,10.304819755875,0.75)); +#141752 = SURFACE_CURVE('',#141753,(#141758,#141787),.PCURVE_S1.); +#141753 = CIRCLE('',#141754,0.2192697516); +#141754 = AXIS2_PLACEMENT_3D('',#141755,#141756,#141757); +#141755 = CARTESIAN_POINT('',(7.85,10.30032442045,0.530776333563)); +#141756 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141757 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141758 = PCURVE('',#141618,#141759); +#141759 = DEFINITIONAL_REPRESENTATION('',(#141760),#141786); +#141760 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141761,#141762,#141763, + #141764,#141765,#141766,#141767,#141768,#141769,#141770,#141771, + #141772,#141773,#141774,#141775,#141776,#141777,#141778,#141779, + #141780,#141781,#141782,#141783,#141784,#141785),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -171790,60 +174792,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#139369 = CARTESIAN_POINT('',(1.591299156552,-7.85)); -#139370 = CARTESIAN_POINT('',(1.614788451962,-7.85)); -#139371 = CARTESIAN_POINT('',(1.661767042781,-7.85)); -#139372 = CARTESIAN_POINT('',(1.73223492901,-7.85)); -#139373 = CARTESIAN_POINT('',(1.802702815239,-7.85)); -#139374 = CARTESIAN_POINT('',(1.873170701468,-7.85)); -#139375 = CARTESIAN_POINT('',(1.943638587697,-7.85)); -#139376 = CARTESIAN_POINT('',(2.014106473926,-7.85)); -#139377 = CARTESIAN_POINT('',(2.084574360155,-7.85)); -#139378 = CARTESIAN_POINT('',(2.155042246384,-7.85)); -#139379 = CARTESIAN_POINT('',(2.225510132613,-7.85)); -#139380 = CARTESIAN_POINT('',(2.295978018842,-7.85)); -#139381 = CARTESIAN_POINT('',(2.366445905071,-7.85)); -#139382 = CARTESIAN_POINT('',(2.4369137913,-7.85)); -#139383 = CARTESIAN_POINT('',(2.507381677529,-7.85)); -#139384 = CARTESIAN_POINT('',(2.577849563758,-7.85)); -#139385 = CARTESIAN_POINT('',(2.648317449987,-7.85)); -#139386 = CARTESIAN_POINT('',(2.718785336216,-7.85)); -#139387 = CARTESIAN_POINT('',(2.789253222445,-7.85)); -#139388 = CARTESIAN_POINT('',(2.859721108674,-7.85)); -#139389 = CARTESIAN_POINT('',(2.930188994903,-7.85)); -#139390 = CARTESIAN_POINT('',(3.000656881132,-7.85)); -#139391 = CARTESIAN_POINT('',(3.071124767361,-7.85)); -#139392 = CARTESIAN_POINT('',(3.11810335818,-7.85)); -#139393 = CARTESIAN_POINT('',(3.14159265359,-7.85)); -#139394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139395 = PCURVE('',#87668,#139396); -#139396 = DEFINITIONAL_REPRESENTATION('',(#139397),#139401); -#139397 = CIRCLE('',#139398,0.2192697516); -#139398 = AXIS2_PLACEMENT_2D('',#139399,#139400); -#139399 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#139400 = DIRECTION('',(0.E+000,-1.)); -#139401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139402 = ORIENTED_EDGE('',*,*,#139208,.T.); -#139403 = ORIENTED_EDGE('',*,*,#139404,.F.); -#139404 = EDGE_CURVE('',#139405,#139211,#139407,.T.); -#139405 = VERTEX_POINT('',#139406); -#139406 = CARTESIAN_POINT('',(7.65,10.304819755875,0.75)); -#139407 = SURFACE_CURVE('',#139408,(#139413,#139442),.PCURVE_S1.); -#139408 = CIRCLE('',#139409,0.2192697516); -#139409 = AXIS2_PLACEMENT_3D('',#139410,#139411,#139412); -#139410 = CARTESIAN_POINT('',(7.65,10.30032442045,0.530776333563)); -#139411 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139412 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139413 = PCURVE('',#139226,#139414); -#139414 = DEFINITIONAL_REPRESENTATION('',(#139415),#139441); -#139415 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139416,#139417,#139418, - #139419,#139420,#139421,#139422,#139423,#139424,#139425,#139426, - #139427,#139428,#139429,#139430,#139431,#139432,#139433,#139434, - #139435,#139436,#139437,#139438,#139439,#139440),.UNSPECIFIED.,.F., +#141761 = CARTESIAN_POINT('',(1.591299156552,-7.85)); +#141762 = CARTESIAN_POINT('',(1.614788451962,-7.85)); +#141763 = CARTESIAN_POINT('',(1.661767042781,-7.85)); +#141764 = CARTESIAN_POINT('',(1.73223492901,-7.85)); +#141765 = CARTESIAN_POINT('',(1.802702815239,-7.85)); +#141766 = CARTESIAN_POINT('',(1.873170701468,-7.85)); +#141767 = CARTESIAN_POINT('',(1.943638587697,-7.85)); +#141768 = CARTESIAN_POINT('',(2.014106473926,-7.85)); +#141769 = CARTESIAN_POINT('',(2.084574360155,-7.85)); +#141770 = CARTESIAN_POINT('',(2.155042246384,-7.85)); +#141771 = CARTESIAN_POINT('',(2.225510132613,-7.85)); +#141772 = CARTESIAN_POINT('',(2.295978018842,-7.85)); +#141773 = CARTESIAN_POINT('',(2.366445905071,-7.85)); +#141774 = CARTESIAN_POINT('',(2.4369137913,-7.85)); +#141775 = CARTESIAN_POINT('',(2.507381677529,-7.85)); +#141776 = CARTESIAN_POINT('',(2.577849563758,-7.85)); +#141777 = CARTESIAN_POINT('',(2.648317449987,-7.85)); +#141778 = CARTESIAN_POINT('',(2.718785336216,-7.85)); +#141779 = CARTESIAN_POINT('',(2.789253222445,-7.85)); +#141780 = CARTESIAN_POINT('',(2.859721108674,-7.85)); +#141781 = CARTESIAN_POINT('',(2.930188994903,-7.85)); +#141782 = CARTESIAN_POINT('',(3.000656881132,-7.85)); +#141783 = CARTESIAN_POINT('',(3.071124767361,-7.85)); +#141784 = CARTESIAN_POINT('',(3.11810335818,-7.85)); +#141785 = CARTESIAN_POINT('',(3.14159265359,-7.85)); +#141786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141787 = PCURVE('',#90060,#141788); +#141788 = DEFINITIONAL_REPRESENTATION('',(#141789),#141793); +#141789 = CIRCLE('',#141790,0.2192697516); +#141790 = AXIS2_PLACEMENT_2D('',#141791,#141792); +#141791 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#141792 = DIRECTION('',(0.E+000,-1.)); +#141793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141794 = ORIENTED_EDGE('',*,*,#141600,.T.); +#141795 = ORIENTED_EDGE('',*,*,#141796,.F.); +#141796 = EDGE_CURVE('',#141797,#141603,#141799,.T.); +#141797 = VERTEX_POINT('',#141798); +#141798 = CARTESIAN_POINT('',(7.65,10.304819755875,0.75)); +#141799 = SURFACE_CURVE('',#141800,(#141805,#141834),.PCURVE_S1.); +#141800 = CIRCLE('',#141801,0.2192697516); +#141801 = AXIS2_PLACEMENT_3D('',#141802,#141803,#141804); +#141802 = CARTESIAN_POINT('',(7.65,10.30032442045,0.530776333563)); +#141803 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#141804 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#141805 = PCURVE('',#141618,#141806); +#141806 = DEFINITIONAL_REPRESENTATION('',(#141807),#141833); +#141807 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141808,#141809,#141810, + #141811,#141812,#141813,#141814,#141815,#141816,#141817,#141818, + #141819,#141820,#141821,#141822,#141823,#141824,#141825,#141826, + #141827,#141828,#141829,#141830,#141831,#141832),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -171851,655 +174853,655 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#139416 = CARTESIAN_POINT('',(1.591299156552,-7.65)); -#139417 = CARTESIAN_POINT('',(1.614788451962,-7.65)); -#139418 = CARTESIAN_POINT('',(1.661767042781,-7.65)); -#139419 = CARTESIAN_POINT('',(1.73223492901,-7.65)); -#139420 = CARTESIAN_POINT('',(1.802702815239,-7.65)); -#139421 = CARTESIAN_POINT('',(1.873170701468,-7.65)); -#139422 = CARTESIAN_POINT('',(1.943638587697,-7.65)); -#139423 = CARTESIAN_POINT('',(2.014106473926,-7.65)); -#139424 = CARTESIAN_POINT('',(2.084574360155,-7.65)); -#139425 = CARTESIAN_POINT('',(2.155042246384,-7.65)); -#139426 = CARTESIAN_POINT('',(2.225510132613,-7.65)); -#139427 = CARTESIAN_POINT('',(2.295978018842,-7.65)); -#139428 = CARTESIAN_POINT('',(2.366445905071,-7.65)); -#139429 = CARTESIAN_POINT('',(2.4369137913,-7.65)); -#139430 = CARTESIAN_POINT('',(2.507381677529,-7.65)); -#139431 = CARTESIAN_POINT('',(2.577849563758,-7.65)); -#139432 = CARTESIAN_POINT('',(2.648317449987,-7.65)); -#139433 = CARTESIAN_POINT('',(2.718785336216,-7.65)); -#139434 = CARTESIAN_POINT('',(2.789253222445,-7.65)); -#139435 = CARTESIAN_POINT('',(2.859721108674,-7.65)); -#139436 = CARTESIAN_POINT('',(2.930188994903,-7.65)); -#139437 = CARTESIAN_POINT('',(3.000656881132,-7.65)); -#139438 = CARTESIAN_POINT('',(3.071124767361,-7.65)); -#139439 = CARTESIAN_POINT('',(3.11810335818,-7.65)); -#139440 = CARTESIAN_POINT('',(3.14159265359,-7.65)); -#139441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139442 = PCURVE('',#87612,#139443); -#139443 = DEFINITIONAL_REPRESENTATION('',(#139444),#139452); -#139444 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139445,#139446,#139447, - #139448,#139449,#139450,#139451),.UNSPECIFIED.,.T.,.F.) +#141808 = CARTESIAN_POINT('',(1.591299156552,-7.65)); +#141809 = CARTESIAN_POINT('',(1.614788451962,-7.65)); +#141810 = CARTESIAN_POINT('',(1.661767042781,-7.65)); +#141811 = CARTESIAN_POINT('',(1.73223492901,-7.65)); +#141812 = CARTESIAN_POINT('',(1.802702815239,-7.65)); +#141813 = CARTESIAN_POINT('',(1.873170701468,-7.65)); +#141814 = CARTESIAN_POINT('',(1.943638587697,-7.65)); +#141815 = CARTESIAN_POINT('',(2.014106473926,-7.65)); +#141816 = CARTESIAN_POINT('',(2.084574360155,-7.65)); +#141817 = CARTESIAN_POINT('',(2.155042246384,-7.65)); +#141818 = CARTESIAN_POINT('',(2.225510132613,-7.65)); +#141819 = CARTESIAN_POINT('',(2.295978018842,-7.65)); +#141820 = CARTESIAN_POINT('',(2.366445905071,-7.65)); +#141821 = CARTESIAN_POINT('',(2.4369137913,-7.65)); +#141822 = CARTESIAN_POINT('',(2.507381677529,-7.65)); +#141823 = CARTESIAN_POINT('',(2.577849563758,-7.65)); +#141824 = CARTESIAN_POINT('',(2.648317449987,-7.65)); +#141825 = CARTESIAN_POINT('',(2.718785336216,-7.65)); +#141826 = CARTESIAN_POINT('',(2.789253222445,-7.65)); +#141827 = CARTESIAN_POINT('',(2.859721108674,-7.65)); +#141828 = CARTESIAN_POINT('',(2.930188994903,-7.65)); +#141829 = CARTESIAN_POINT('',(3.000656881132,-7.65)); +#141830 = CARTESIAN_POINT('',(3.071124767361,-7.65)); +#141831 = CARTESIAN_POINT('',(3.11810335818,-7.65)); +#141832 = CARTESIAN_POINT('',(3.14159265359,-7.65)); +#141833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141834 = PCURVE('',#90004,#141835); +#141835 = DEFINITIONAL_REPRESENTATION('',(#141836),#141844); +#141836 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141837,#141838,#141839, + #141840,#141841,#141842,#141843),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#139445 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#139446 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#139447 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#139448 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#139449 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#139450 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#139451 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#139452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139453 = ORIENTED_EDGE('',*,*,#139454,.T.); -#139454 = EDGE_CURVE('',#139405,#139358,#139455,.T.); -#139455 = SURFACE_CURVE('',#139456,(#139460,#139466),.PCURVE_S1.); -#139456 = LINE('',#139457,#139458); -#139457 = CARTESIAN_POINT('',(7.65,10.304819755875,0.75)); -#139458 = VECTOR('',#139459,1.); -#139459 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139460 = PCURVE('',#139226,#139461); -#139461 = DEFINITIONAL_REPRESENTATION('',(#139462),#139465); -#139462 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139463,#139464), +#141837 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#141838 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#141839 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#141840 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#141841 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#141842 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#141843 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#141844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141845 = ORIENTED_EDGE('',*,*,#141846,.T.); +#141846 = EDGE_CURVE('',#141797,#141750,#141847,.T.); +#141847 = SURFACE_CURVE('',#141848,(#141852,#141858),.PCURVE_S1.); +#141848 = LINE('',#141849,#141850); +#141849 = CARTESIAN_POINT('',(7.65,10.304819755875,0.75)); +#141850 = VECTOR('',#141851,1.); +#141851 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#141852 = PCURVE('',#141618,#141853); +#141853 = DEFINITIONAL_REPRESENTATION('',(#141854),#141857); +#141854 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141855,#141856), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#139463 = CARTESIAN_POINT('',(1.591299156552,-7.65)); -#139464 = CARTESIAN_POINT('',(1.591299156552,-7.85)); -#139465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139466 = PCURVE('',#87694,#139467); -#139467 = DEFINITIONAL_REPRESENTATION('',(#139468),#139472); -#139468 = LINE('',#139469,#139470); -#139469 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#139470 = VECTOR('',#139471,1.); -#139471 = DIRECTION('',(-8.881784197001E-016,1.)); -#139472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139473 = ADVANCED_FACE('',(#139474),#87612,.F.); -#139474 = FACE_BOUND('',#139475,.T.); -#139475 = EDGE_LOOP('',(#139476,#139497,#139498,#139499,#139500,#139501, - #139522,#139523,#139524,#139525,#139526,#139547)); -#139476 = ORIENTED_EDGE('',*,*,#139477,.F.); -#139477 = EDGE_CURVE('',#139405,#87597,#139478,.T.); -#139478 = SURFACE_CURVE('',#139479,(#139483,#139490),.PCURVE_S1.); -#139479 = LINE('',#139480,#139481); -#139480 = CARTESIAN_POINT('',(7.65,10.527847992439,0.75)); -#139481 = VECTOR('',#139482,1.); -#139482 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#139483 = PCURVE('',#87612,#139484); -#139484 = DEFINITIONAL_REPRESENTATION('',(#139485),#139489); -#139485 = LINE('',#139486,#139487); -#139486 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#139487 = VECTOR('',#139488,1.); -#139488 = DIRECTION('',(-3.563627120235E-016,-1.)); -#139489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139490 = PCURVE('',#87694,#139491); -#139491 = DEFINITIONAL_REPRESENTATION('',(#139492),#139496); -#139492 = LINE('',#139493,#139494); -#139493 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139494 = VECTOR('',#139495,1.); -#139495 = DIRECTION('',(-1.,6.005309793447E-063)); -#139496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139497 = ORIENTED_EDGE('',*,*,#139404,.T.); -#139498 = ORIENTED_EDGE('',*,*,#139259,.T.); -#139499 = ORIENTED_EDGE('',*,*,#138984,.T.); -#139500 = ORIENTED_EDGE('',*,*,#138774,.T.); -#139501 = ORIENTED_EDGE('',*,*,#139502,.T.); -#139502 = EDGE_CURVE('',#138747,#138828,#139503,.T.); -#139503 = SURFACE_CURVE('',#139504,(#139508,#139515),.PCURVE_S1.); -#139504 = LINE('',#139505,#139506); -#139505 = CARTESIAN_POINT('',(7.65,11.,1.159810404338E-002)); -#139506 = VECTOR('',#139507,1.); -#139507 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#139508 = PCURVE('',#87612,#139509); -#139509 = DEFINITIONAL_REPRESENTATION('',(#139510),#139514); -#139510 = LINE('',#139511,#139512); -#139511 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#139512 = VECTOR('',#139513,1.); -#139513 = DIRECTION('',(1.,-2.101748079665E-016)); -#139514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139515 = PCURVE('',#138762,#139516); -#139516 = DEFINITIONAL_REPRESENTATION('',(#139517),#139521); -#139517 = LINE('',#139518,#139519); -#139518 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#139519 = VECTOR('',#139520,1.); -#139520 = DIRECTION('',(1.570395187386E-016,-1.)); -#139521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139522 = ORIENTED_EDGE('',*,*,#138825,.F.); -#139523 = ORIENTED_EDGE('',*,*,#139086,.F.); -#139524 = ORIENTED_EDGE('',*,*,#139162,.F.); -#139525 = ORIENTED_EDGE('',*,*,#139283,.F.); -#139526 = ORIENTED_EDGE('',*,*,#139527,.T.); -#139527 = EDGE_CURVE('',#139284,#87595,#139528,.T.); -#139528 = SURFACE_CURVE('',#139529,(#139533,#139540),.PCURVE_S1.); -#139529 = LINE('',#139530,#139531); -#139530 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); -#139531 = VECTOR('',#139532,1.); -#139532 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#139533 = PCURVE('',#87612,#139534); -#139534 = DEFINITIONAL_REPRESENTATION('',(#139535),#139539); -#139535 = LINE('',#139536,#139537); -#139536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139537 = VECTOR('',#139538,1.); -#139538 = DIRECTION('',(-3.563627120235E-016,-1.)); -#139539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139540 = PCURVE('',#87640,#139541); -#139541 = DEFINITIONAL_REPRESENTATION('',(#139542),#139546); -#139542 = LINE('',#139543,#139544); -#139543 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139544 = VECTOR('',#139545,1.); -#139545 = DIRECTION('',(1.,6.005309793447E-063)); -#139546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139547 = ORIENTED_EDGE('',*,*,#87594,.T.); -#139548 = ADVANCED_FACE('',(#139549),#87694,.F.); -#139549 = FACE_BOUND('',#139550,.T.); -#139550 = EDGE_LOOP('',(#139551,#139552,#139553,#139554)); -#139551 = ORIENTED_EDGE('',*,*,#139454,.F.); -#139552 = ORIENTED_EDGE('',*,*,#139477,.T.); -#139553 = ORIENTED_EDGE('',*,*,#87680,.T.); -#139554 = ORIENTED_EDGE('',*,*,#139555,.F.); -#139555 = EDGE_CURVE('',#139358,#87653,#139556,.T.); -#139556 = SURFACE_CURVE('',#139557,(#139561,#139568),.PCURVE_S1.); -#139557 = LINE('',#139558,#139559); -#139558 = CARTESIAN_POINT('',(7.85,10.527847992439,0.75)); -#139559 = VECTOR('',#139560,1.); -#139560 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#139561 = PCURVE('',#87694,#139562); -#139562 = DEFINITIONAL_REPRESENTATION('',(#139563),#139567); -#139563 = LINE('',#139564,#139565); -#139564 = CARTESIAN_POINT('',(0.E+000,0.2)); -#139565 = VECTOR('',#139566,1.); -#139566 = DIRECTION('',(-1.,6.005309793447E-063)); -#139567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139568 = PCURVE('',#87668,#139569); -#139569 = DEFINITIONAL_REPRESENTATION('',(#139570),#139574); -#139570 = LINE('',#139571,#139572); -#139571 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#139572 = VECTOR('',#139573,1.); -#139573 = DIRECTION('',(3.563627120235E-016,-1.)); -#139574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139575 = ADVANCED_FACE('',(#139576),#87668,.F.); -#139576 = FACE_BOUND('',#139577,.T.); -#139577 = EDGE_LOOP('',(#139578,#139599,#139600,#139601,#139602,#139603, - #139624,#139625,#139626,#139627,#139628,#139629)); -#139578 = ORIENTED_EDGE('',*,*,#139579,.F.); -#139579 = EDGE_CURVE('',#139311,#87625,#139580,.T.); -#139580 = SURFACE_CURVE('',#139581,(#139585,#139592),.PCURVE_S1.); -#139581 = LINE('',#139582,#139583); -#139582 = CARTESIAN_POINT('',(7.85,10.527847992439,0.65)); -#139583 = VECTOR('',#139584,1.); -#139584 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#139585 = PCURVE('',#87668,#139586); -#139586 = DEFINITIONAL_REPRESENTATION('',(#139587),#139591); -#139587 = LINE('',#139588,#139589); -#139588 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139589 = VECTOR('',#139590,1.); -#139590 = DIRECTION('',(3.563627120235E-016,-1.)); -#139591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139592 = PCURVE('',#87640,#139593); -#139593 = DEFINITIONAL_REPRESENTATION('',(#139594),#139598); -#139594 = LINE('',#139595,#139596); -#139595 = CARTESIAN_POINT('',(0.E+000,0.2)); -#139596 = VECTOR('',#139597,1.); -#139597 = DIRECTION('',(1.,6.005309793447E-063)); -#139598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139599 = ORIENTED_EDGE('',*,*,#139332,.T.); -#139600 = ORIENTED_EDGE('',*,*,#139184,.T.); -#139601 = ORIENTED_EDGE('',*,*,#139009,.T.); -#139602 = ORIENTED_EDGE('',*,*,#138878,.T.); -#139603 = ORIENTED_EDGE('',*,*,#139604,.T.); -#139604 = EDGE_CURVE('',#138856,#138719,#139605,.T.); -#139605 = SURFACE_CURVE('',#139606,(#139610,#139617),.PCURVE_S1.); -#139606 = LINE('',#139607,#139608); -#139607 = CARTESIAN_POINT('',(7.85,11.,1.159810404338E-002)); -#139608 = VECTOR('',#139609,1.); -#139609 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#139610 = PCURVE('',#87668,#139611); -#139611 = DEFINITIONAL_REPRESENTATION('',(#139612),#139616); -#139612 = LINE('',#139613,#139614); -#139613 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#139614 = VECTOR('',#139615,1.); -#139615 = DIRECTION('',(1.,2.101748079665E-016)); -#139616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139617 = PCURVE('',#138762,#139618); -#139618 = DEFINITIONAL_REPRESENTATION('',(#139619),#139623); -#139619 = LINE('',#139620,#139621); -#139620 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#139621 = VECTOR('',#139622,1.); -#139622 = DIRECTION('',(-1.570395187386E-016,1.)); -#139623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139624 = ORIENTED_EDGE('',*,*,#138716,.F.); -#139625 = ORIENTED_EDGE('',*,*,#138930,.F.); -#139626 = ORIENTED_EDGE('',*,*,#139237,.F.); -#139627 = ORIENTED_EDGE('',*,*,#139357,.F.); -#139628 = ORIENTED_EDGE('',*,*,#139555,.T.); -#139629 = ORIENTED_EDGE('',*,*,#87652,.T.); -#139630 = ADVANCED_FACE('',(#139631),#87640,.F.); -#139631 = FACE_BOUND('',#139632,.T.); -#139632 = EDGE_LOOP('',(#139633,#139634,#139635,#139636)); -#139633 = ORIENTED_EDGE('',*,*,#139310,.F.); -#139634 = ORIENTED_EDGE('',*,*,#139579,.T.); -#139635 = ORIENTED_EDGE('',*,*,#87624,.T.); -#139636 = ORIENTED_EDGE('',*,*,#139527,.F.); -#139637 = ADVANCED_FACE('',(#139638),#138762,.T.); -#139638 = FACE_BOUND('',#139639,.T.); -#139639 = EDGE_LOOP('',(#139640,#139641,#139642,#139643)); -#139640 = ORIENTED_EDGE('',*,*,#139604,.F.); -#139641 = ORIENTED_EDGE('',*,*,#138855,.F.); -#139642 = ORIENTED_EDGE('',*,*,#139502,.F.); -#139643 = ORIENTED_EDGE('',*,*,#138746,.F.); -#139644 = ADVANCED_FACE('',(#139645),#139659,.T.); -#139645 = FACE_BOUND('',#139646,.T.); -#139646 = EDGE_LOOP('',(#139647,#139677,#139705,#139728)); -#139647 = ORIENTED_EDGE('',*,*,#139648,.T.); -#139648 = EDGE_CURVE('',#139649,#139651,#139653,.T.); -#139649 = VERTEX_POINT('',#139650); -#139650 = CARTESIAN_POINT('',(7.35,10.740726081328,-0.208196358798)); -#139651 = VERTEX_POINT('',#139652); -#139652 = CARTESIAN_POINT('',(7.35,11.,-0.208196358798)); -#139653 = SURFACE_CURVE('',#139654,(#139658,#139670),.PCURVE_S1.); -#139654 = LINE('',#139655,#139656); -#139655 = CARTESIAN_POINT('',(7.35,10.740726081328,-0.208196358798)); -#139656 = VECTOR('',#139657,1.); -#139657 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#139658 = PCURVE('',#139659,#139664); -#139659 = PLANE('',#139660); -#139660 = AXIS2_PLACEMENT_3D('',#139661,#139662,#139663); -#139661 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#141855 = CARTESIAN_POINT('',(1.591299156552,-7.65)); +#141856 = CARTESIAN_POINT('',(1.591299156552,-7.85)); +#141857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141858 = PCURVE('',#90086,#141859); +#141859 = DEFINITIONAL_REPRESENTATION('',(#141860),#141864); +#141860 = LINE('',#141861,#141862); +#141861 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#141862 = VECTOR('',#141863,1.); +#141863 = DIRECTION('',(-8.881784197001E-016,1.)); +#141864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141865 = ADVANCED_FACE('',(#141866),#90004,.F.); +#141866 = FACE_BOUND('',#141867,.T.); +#141867 = EDGE_LOOP('',(#141868,#141889,#141890,#141891,#141892,#141893, + #141914,#141915,#141916,#141917,#141918,#141939)); +#141868 = ORIENTED_EDGE('',*,*,#141869,.F.); +#141869 = EDGE_CURVE('',#141797,#89989,#141870,.T.); +#141870 = SURFACE_CURVE('',#141871,(#141875,#141882),.PCURVE_S1.); +#141871 = LINE('',#141872,#141873); +#141872 = CARTESIAN_POINT('',(7.65,10.527847992439,0.75)); +#141873 = VECTOR('',#141874,1.); +#141874 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141875 = PCURVE('',#90004,#141876); +#141876 = DEFINITIONAL_REPRESENTATION('',(#141877),#141881); +#141877 = LINE('',#141878,#141879); +#141878 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#141879 = VECTOR('',#141880,1.); +#141880 = DIRECTION('',(-3.563627120235E-016,-1.)); +#141881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141882 = PCURVE('',#90086,#141883); +#141883 = DEFINITIONAL_REPRESENTATION('',(#141884),#141888); +#141884 = LINE('',#141885,#141886); +#141885 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141886 = VECTOR('',#141887,1.); +#141887 = DIRECTION('',(-1.,6.005309793447E-063)); +#141888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141889 = ORIENTED_EDGE('',*,*,#141796,.T.); +#141890 = ORIENTED_EDGE('',*,*,#141651,.T.); +#141891 = ORIENTED_EDGE('',*,*,#141376,.T.); +#141892 = ORIENTED_EDGE('',*,*,#141166,.T.); +#141893 = ORIENTED_EDGE('',*,*,#141894,.T.); +#141894 = EDGE_CURVE('',#141139,#141220,#141895,.T.); +#141895 = SURFACE_CURVE('',#141896,(#141900,#141907),.PCURVE_S1.); +#141896 = LINE('',#141897,#141898); +#141897 = CARTESIAN_POINT('',(7.65,11.,1.159810404338E-002)); +#141898 = VECTOR('',#141899,1.); +#141899 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#141900 = PCURVE('',#90004,#141901); +#141901 = DEFINITIONAL_REPRESENTATION('',(#141902),#141906); +#141902 = LINE('',#141903,#141904); +#141903 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#141904 = VECTOR('',#141905,1.); +#141905 = DIRECTION('',(1.,-2.101748079665E-016)); +#141906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141907 = PCURVE('',#141154,#141908); +#141908 = DEFINITIONAL_REPRESENTATION('',(#141909),#141913); +#141909 = LINE('',#141910,#141911); +#141910 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#141911 = VECTOR('',#141912,1.); +#141912 = DIRECTION('',(1.570395187386E-016,-1.)); +#141913 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141914 = ORIENTED_EDGE('',*,*,#141217,.F.); +#141915 = ORIENTED_EDGE('',*,*,#141478,.F.); +#141916 = ORIENTED_EDGE('',*,*,#141554,.F.); +#141917 = ORIENTED_EDGE('',*,*,#141675,.F.); +#141918 = ORIENTED_EDGE('',*,*,#141919,.T.); +#141919 = EDGE_CURVE('',#141676,#89987,#141920,.T.); +#141920 = SURFACE_CURVE('',#141921,(#141925,#141932),.PCURVE_S1.); +#141921 = LINE('',#141922,#141923); +#141922 = CARTESIAN_POINT('',(7.65,10.527847992439,0.65)); +#141923 = VECTOR('',#141924,1.); +#141924 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141925 = PCURVE('',#90004,#141926); +#141926 = DEFINITIONAL_REPRESENTATION('',(#141927),#141931); +#141927 = LINE('',#141928,#141929); +#141928 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141929 = VECTOR('',#141930,1.); +#141930 = DIRECTION('',(-3.563627120235E-016,-1.)); +#141931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141932 = PCURVE('',#90032,#141933); +#141933 = DEFINITIONAL_REPRESENTATION('',(#141934),#141938); +#141934 = LINE('',#141935,#141936); +#141935 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141936 = VECTOR('',#141937,1.); +#141937 = DIRECTION('',(1.,6.005309793447E-063)); +#141938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141939 = ORIENTED_EDGE('',*,*,#89986,.T.); +#141940 = ADVANCED_FACE('',(#141941),#90086,.F.); +#141941 = FACE_BOUND('',#141942,.T.); +#141942 = EDGE_LOOP('',(#141943,#141944,#141945,#141946)); +#141943 = ORIENTED_EDGE('',*,*,#141846,.F.); +#141944 = ORIENTED_EDGE('',*,*,#141869,.T.); +#141945 = ORIENTED_EDGE('',*,*,#90072,.T.); +#141946 = ORIENTED_EDGE('',*,*,#141947,.F.); +#141947 = EDGE_CURVE('',#141750,#90045,#141948,.T.); +#141948 = SURFACE_CURVE('',#141949,(#141953,#141960),.PCURVE_S1.); +#141949 = LINE('',#141950,#141951); +#141950 = CARTESIAN_POINT('',(7.85,10.527847992439,0.75)); +#141951 = VECTOR('',#141952,1.); +#141952 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141953 = PCURVE('',#90086,#141954); +#141954 = DEFINITIONAL_REPRESENTATION('',(#141955),#141959); +#141955 = LINE('',#141956,#141957); +#141956 = CARTESIAN_POINT('',(0.E+000,0.2)); +#141957 = VECTOR('',#141958,1.); +#141958 = DIRECTION('',(-1.,6.005309793447E-063)); +#141959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141960 = PCURVE('',#90060,#141961); +#141961 = DEFINITIONAL_REPRESENTATION('',(#141962),#141966); +#141962 = LINE('',#141963,#141964); +#141963 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#141964 = VECTOR('',#141965,1.); +#141965 = DIRECTION('',(3.563627120235E-016,-1.)); +#141966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141967 = ADVANCED_FACE('',(#141968),#90060,.F.); +#141968 = FACE_BOUND('',#141969,.T.); +#141969 = EDGE_LOOP('',(#141970,#141991,#141992,#141993,#141994,#141995, + #142016,#142017,#142018,#142019,#142020,#142021)); +#141970 = ORIENTED_EDGE('',*,*,#141971,.F.); +#141971 = EDGE_CURVE('',#141703,#90017,#141972,.T.); +#141972 = SURFACE_CURVE('',#141973,(#141977,#141984),.PCURVE_S1.); +#141973 = LINE('',#141974,#141975); +#141974 = CARTESIAN_POINT('',(7.85,10.527847992439,0.65)); +#141975 = VECTOR('',#141976,1.); +#141976 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#141977 = PCURVE('',#90060,#141978); +#141978 = DEFINITIONAL_REPRESENTATION('',(#141979),#141983); +#141979 = LINE('',#141980,#141981); +#141980 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#141981 = VECTOR('',#141982,1.); +#141982 = DIRECTION('',(3.563627120235E-016,-1.)); +#141983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141984 = PCURVE('',#90032,#141985); +#141985 = DEFINITIONAL_REPRESENTATION('',(#141986),#141990); +#141986 = LINE('',#141987,#141988); +#141987 = CARTESIAN_POINT('',(0.E+000,0.2)); +#141988 = VECTOR('',#141989,1.); +#141989 = DIRECTION('',(1.,6.005309793447E-063)); +#141990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#141991 = ORIENTED_EDGE('',*,*,#141724,.T.); +#141992 = ORIENTED_EDGE('',*,*,#141576,.T.); +#141993 = ORIENTED_EDGE('',*,*,#141401,.T.); +#141994 = ORIENTED_EDGE('',*,*,#141270,.T.); +#141995 = ORIENTED_EDGE('',*,*,#141996,.T.); +#141996 = EDGE_CURVE('',#141248,#141111,#141997,.T.); +#141997 = SURFACE_CURVE('',#141998,(#142002,#142009),.PCURVE_S1.); +#141998 = LINE('',#141999,#142000); +#141999 = CARTESIAN_POINT('',(7.85,11.,1.159810404338E-002)); +#142000 = VECTOR('',#142001,1.); +#142001 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#142002 = PCURVE('',#90060,#142003); +#142003 = DEFINITIONAL_REPRESENTATION('',(#142004),#142008); +#142004 = LINE('',#142005,#142006); +#142005 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#142006 = VECTOR('',#142007,1.); +#142007 = DIRECTION('',(1.,2.101748079665E-016)); +#142008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142009 = PCURVE('',#141154,#142010); +#142010 = DEFINITIONAL_REPRESENTATION('',(#142011),#142015); +#142011 = LINE('',#142012,#142013); +#142012 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#142013 = VECTOR('',#142014,1.); +#142014 = DIRECTION('',(-1.570395187386E-016,1.)); +#142015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142016 = ORIENTED_EDGE('',*,*,#141108,.F.); +#142017 = ORIENTED_EDGE('',*,*,#141322,.F.); +#142018 = ORIENTED_EDGE('',*,*,#141629,.F.); +#142019 = ORIENTED_EDGE('',*,*,#141749,.F.); +#142020 = ORIENTED_EDGE('',*,*,#141947,.T.); +#142021 = ORIENTED_EDGE('',*,*,#90044,.T.); +#142022 = ADVANCED_FACE('',(#142023),#90032,.F.); +#142023 = FACE_BOUND('',#142024,.T.); +#142024 = EDGE_LOOP('',(#142025,#142026,#142027,#142028)); +#142025 = ORIENTED_EDGE('',*,*,#141702,.F.); +#142026 = ORIENTED_EDGE('',*,*,#141971,.T.); +#142027 = ORIENTED_EDGE('',*,*,#90016,.T.); +#142028 = ORIENTED_EDGE('',*,*,#141919,.F.); +#142029 = ADVANCED_FACE('',(#142030),#141154,.T.); +#142030 = FACE_BOUND('',#142031,.T.); +#142031 = EDGE_LOOP('',(#142032,#142033,#142034,#142035)); +#142032 = ORIENTED_EDGE('',*,*,#141996,.F.); +#142033 = ORIENTED_EDGE('',*,*,#141247,.F.); +#142034 = ORIENTED_EDGE('',*,*,#141894,.F.); +#142035 = ORIENTED_EDGE('',*,*,#141138,.F.); +#142036 = ADVANCED_FACE('',(#142037),#142051,.T.); +#142037 = FACE_BOUND('',#142038,.T.); +#142038 = EDGE_LOOP('',(#142039,#142069,#142097,#142120)); +#142039 = ORIENTED_EDGE('',*,*,#142040,.T.); +#142040 = EDGE_CURVE('',#142041,#142043,#142045,.T.); +#142041 = VERTEX_POINT('',#142042); +#142042 = CARTESIAN_POINT('',(7.35,10.740726081328,-0.208196358798)); +#142043 = VERTEX_POINT('',#142044); +#142044 = CARTESIAN_POINT('',(7.35,11.,-0.208196358798)); +#142045 = SURFACE_CURVE('',#142046,(#142050,#142062),.PCURVE_S1.); +#142046 = LINE('',#142047,#142048); +#142047 = CARTESIAN_POINT('',(7.35,10.740726081328,-0.208196358798)); +#142048 = VECTOR('',#142049,1.); +#142049 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#142050 = PCURVE('',#142051,#142056); +#142051 = PLANE('',#142052); +#142052 = AXIS2_PLACEMENT_3D('',#142053,#142054,#142055); +#142053 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#139662 = DIRECTION('',(0.E+000,0.E+000,1.)); -#139663 = DIRECTION('',(1.,0.E+000,0.E+000)); -#139664 = DEFINITIONAL_REPRESENTATION('',(#139665),#139669); -#139665 = LINE('',#139666,#139667); -#139666 = CARTESIAN_POINT('',(7.35,-7.105427357601E-015)); -#139667 = VECTOR('',#139668,1.); -#139668 = DIRECTION('',(6.725593854929E-015,1.)); -#139669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139670 = PCURVE('',#87212,#139671); -#139671 = DEFINITIONAL_REPRESENTATION('',(#139672),#139676); -#139672 = LINE('',#139673,#139674); -#139673 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#139674 = VECTOR('',#139675,1.); -#139675 = DIRECTION('',(0.E+000,1.)); -#139676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139677 = ORIENTED_EDGE('',*,*,#139678,.T.); -#139678 = EDGE_CURVE('',#139651,#139679,#139681,.T.); -#139679 = VERTEX_POINT('',#139680); -#139680 = CARTESIAN_POINT('',(7.15,11.,-0.208196358798)); -#139681 = SURFACE_CURVE('',#139682,(#139686,#139693),.PCURVE_S1.); -#139682 = LINE('',#139683,#139684); -#139683 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#139684 = VECTOR('',#139685,1.); -#139685 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139686 = PCURVE('',#139659,#139687); -#139687 = DEFINITIONAL_REPRESENTATION('',(#139688),#139692); -#139688 = LINE('',#139689,#139690); -#139689 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#139690 = VECTOR('',#139691,1.); -#139691 = DIRECTION('',(-1.,8.881784197001E-016)); -#139692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139693 = PCURVE('',#139694,#139699); -#139694 = PLANE('',#139695); -#139695 = AXIS2_PLACEMENT_3D('',#139696,#139697,#139698); -#139696 = CARTESIAN_POINT('',(7.25,11.,-0.258196742327)); -#139697 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#139698 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#139699 = DEFINITIONAL_REPRESENTATION('',(#139700),#139704); -#139700 = LINE('',#139701,#139702); -#139701 = CARTESIAN_POINT('',(7.25,5.00003835295E-002)); -#139702 = VECTOR('',#139703,1.); -#139703 = DIRECTION('',(1.,1.1653254136E-048)); -#139704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139705 = ORIENTED_EDGE('',*,*,#139706,.F.); -#139706 = EDGE_CURVE('',#139707,#139679,#139709,.T.); -#139707 = VERTEX_POINT('',#139708); -#139708 = CARTESIAN_POINT('',(7.15,10.740726081328,-0.208196358798)); -#139709 = SURFACE_CURVE('',#139710,(#139714,#139721),.PCURVE_S1.); -#139710 = LINE('',#139711,#139712); -#139711 = CARTESIAN_POINT('',(7.15,10.740726081328,-0.208196358798)); -#139712 = VECTOR('',#139713,1.); -#139713 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#139714 = PCURVE('',#139659,#139715); -#139715 = DEFINITIONAL_REPRESENTATION('',(#139716),#139720); -#139716 = LINE('',#139717,#139718); -#139717 = CARTESIAN_POINT('',(7.15,-5.329070518201E-015)); -#139718 = VECTOR('',#139719,1.); -#139719 = DIRECTION('',(6.725593854929E-015,1.)); -#139720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139721 = PCURVE('',#87156,#139722); -#139722 = DEFINITIONAL_REPRESENTATION('',(#139723),#139727); -#139723 = LINE('',#139724,#139725); -#139724 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#139725 = VECTOR('',#139726,1.); -#139726 = DIRECTION('',(0.E+000,1.)); -#139727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142054 = DIRECTION('',(0.E+000,0.E+000,1.)); +#142055 = DIRECTION('',(1.,0.E+000,0.E+000)); +#142056 = DEFINITIONAL_REPRESENTATION('',(#142057),#142061); +#142057 = LINE('',#142058,#142059); +#142058 = CARTESIAN_POINT('',(7.35,-7.105427357601E-015)); +#142059 = VECTOR('',#142060,1.); +#142060 = DIRECTION('',(6.725593854929E-015,1.)); +#142061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142062 = PCURVE('',#89604,#142063); +#142063 = DEFINITIONAL_REPRESENTATION('',(#142064),#142068); +#142064 = LINE('',#142065,#142066); +#142065 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#142066 = VECTOR('',#142067,1.); +#142067 = DIRECTION('',(0.E+000,1.)); +#142068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142069 = ORIENTED_EDGE('',*,*,#142070,.T.); +#142070 = EDGE_CURVE('',#142043,#142071,#142073,.T.); +#142071 = VERTEX_POINT('',#142072); +#142072 = CARTESIAN_POINT('',(7.15,11.,-0.208196358798)); +#142073 = SURFACE_CURVE('',#142074,(#142078,#142085),.PCURVE_S1.); +#142074 = LINE('',#142075,#142076); +#142075 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#142076 = VECTOR('',#142077,1.); +#142077 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142078 = PCURVE('',#142051,#142079); +#142079 = DEFINITIONAL_REPRESENTATION('',(#142080),#142084); +#142080 = LINE('',#142081,#142082); +#142081 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#142082 = VECTOR('',#142083,1.); +#142083 = DIRECTION('',(-1.,8.881784197001E-016)); +#142084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142085 = PCURVE('',#142086,#142091); +#142086 = PLANE('',#142087); +#142087 = AXIS2_PLACEMENT_3D('',#142088,#142089,#142090); +#142088 = CARTESIAN_POINT('',(7.25,11.,-0.258196742327)); +#142089 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#142090 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#142091 = DEFINITIONAL_REPRESENTATION('',(#142092),#142096); +#142092 = LINE('',#142093,#142094); +#142093 = CARTESIAN_POINT('',(7.25,5.00003835295E-002)); +#142094 = VECTOR('',#142095,1.); +#142095 = DIRECTION('',(1.,1.1653254136E-048)); +#142096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142097 = ORIENTED_EDGE('',*,*,#142098,.F.); +#142098 = EDGE_CURVE('',#142099,#142071,#142101,.T.); +#142099 = VERTEX_POINT('',#142100); +#142100 = CARTESIAN_POINT('',(7.15,10.740726081328,-0.208196358798)); +#142101 = SURFACE_CURVE('',#142102,(#142106,#142113),.PCURVE_S1.); +#142102 = LINE('',#142103,#142104); +#142103 = CARTESIAN_POINT('',(7.15,10.740726081328,-0.208196358798)); +#142104 = VECTOR('',#142105,1.); +#142105 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#142106 = PCURVE('',#142051,#142107); +#142107 = DEFINITIONAL_REPRESENTATION('',(#142108),#142112); +#142108 = LINE('',#142109,#142110); +#142109 = CARTESIAN_POINT('',(7.15,-5.329070518201E-015)); +#142110 = VECTOR('',#142111,1.); +#142111 = DIRECTION('',(6.725593854929E-015,1.)); +#142112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142113 = PCURVE('',#89548,#142114); +#142114 = DEFINITIONAL_REPRESENTATION('',(#142115),#142119); +#142115 = LINE('',#142116,#142117); +#142116 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#142117 = VECTOR('',#142118,1.); +#142118 = DIRECTION('',(0.E+000,1.)); +#142119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139728 = ORIENTED_EDGE('',*,*,#139729,.T.); -#139729 = EDGE_CURVE('',#139707,#139649,#139730,.T.); -#139730 = SURFACE_CURVE('',#139731,(#139735,#139742),.PCURVE_S1.); -#139731 = LINE('',#139732,#139733); -#139732 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#142120 = ORIENTED_EDGE('',*,*,#142121,.T.); +#142121 = EDGE_CURVE('',#142099,#142041,#142122,.T.); +#142122 = SURFACE_CURVE('',#142123,(#142127,#142134),.PCURVE_S1.); +#142123 = LINE('',#142124,#142125); +#142124 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#139733 = VECTOR('',#139734,1.); -#139734 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139735 = PCURVE('',#139659,#139736); -#139736 = DEFINITIONAL_REPRESENTATION('',(#139737),#139741); -#139737 = LINE('',#139738,#139739); -#139738 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139739 = VECTOR('',#139740,1.); -#139740 = DIRECTION('',(1.,-8.881784197001E-016)); -#139741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139742 = PCURVE('',#139743,#139748); -#139743 = CYLINDRICAL_SURFACE('',#139744,0.208574704164); -#139744 = AXIS2_PLACEMENT_3D('',#139745,#139746,#139747); -#139745 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#142125 = VECTOR('',#142126,1.); +#142126 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142127 = PCURVE('',#142051,#142128); +#142128 = DEFINITIONAL_REPRESENTATION('',(#142129),#142133); +#142129 = LINE('',#142130,#142131); +#142130 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142131 = VECTOR('',#142132,1.); +#142132 = DIRECTION('',(1.,-8.881784197001E-016)); +#142133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142134 = PCURVE('',#142135,#142140); +#142135 = CYLINDRICAL_SURFACE('',#142136,0.208574704164); +#142136 = AXIS2_PLACEMENT_3D('',#142137,#142138,#142139); +#142137 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#139746 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139747 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139748 = DEFINITIONAL_REPRESENTATION('',(#139749),#139752); -#139749 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139750,#139751), +#142138 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142139 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142140 = DEFINITIONAL_REPRESENTATION('',(#142141),#142144); +#142141 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142142,#142143), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#139750 = CARTESIAN_POINT('',(4.772630242227,7.15)); -#139751 = CARTESIAN_POINT('',(4.772630242227,7.35)); -#139752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139753 = ADVANCED_FACE('',(#139754),#139768,.T.); -#139754 = FACE_BOUND('',#139755,.T.); -#139755 = EDGE_LOOP('',(#139756,#139786,#139809,#139832)); -#139756 = ORIENTED_EDGE('',*,*,#139757,.T.); -#139757 = EDGE_CURVE('',#139758,#139760,#139762,.T.); -#139758 = VERTEX_POINT('',#139759); -#139759 = CARTESIAN_POINT('',(7.15,10.74341632541,-0.308197125857)); -#139760 = VERTEX_POINT('',#139761); -#139761 = CARTESIAN_POINT('',(7.15,11.,-0.308197125857)); -#139762 = SURFACE_CURVE('',#139763,(#139767,#139779),.PCURVE_S1.); -#139763 = LINE('',#139764,#139765); -#139764 = CARTESIAN_POINT('',(7.15,10.74341632541,-0.308197125857)); -#139765 = VECTOR('',#139766,1.); -#139766 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#139767 = PCURVE('',#139768,#139773); -#139768 = PLANE('',#139769); -#139769 = AXIS2_PLACEMENT_3D('',#139770,#139771,#139772); -#139770 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#142142 = CARTESIAN_POINT('',(4.772630242227,7.15)); +#142143 = CARTESIAN_POINT('',(4.772630242227,7.35)); +#142144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142145 = ADVANCED_FACE('',(#142146),#142160,.T.); +#142146 = FACE_BOUND('',#142147,.T.); +#142147 = EDGE_LOOP('',(#142148,#142178,#142201,#142224)); +#142148 = ORIENTED_EDGE('',*,*,#142149,.T.); +#142149 = EDGE_CURVE('',#142150,#142152,#142154,.T.); +#142150 = VERTEX_POINT('',#142151); +#142151 = CARTESIAN_POINT('',(7.15,10.74341632541,-0.308197125857)); +#142152 = VERTEX_POINT('',#142153); +#142153 = CARTESIAN_POINT('',(7.15,11.,-0.308197125857)); +#142154 = SURFACE_CURVE('',#142155,(#142159,#142171),.PCURVE_S1.); +#142155 = LINE('',#142156,#142157); +#142156 = CARTESIAN_POINT('',(7.15,10.74341632541,-0.308197125857)); +#142157 = VECTOR('',#142158,1.); +#142158 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#142159 = PCURVE('',#142160,#142165); +#142160 = PLANE('',#142161); +#142161 = AXIS2_PLACEMENT_3D('',#142162,#142163,#142164); +#142162 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#139771 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#139772 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#139773 = DEFINITIONAL_REPRESENTATION('',(#139774),#139778); -#139774 = LINE('',#139775,#139776); -#139775 = CARTESIAN_POINT('',(-7.15,-7.105427357601E-015)); -#139776 = VECTOR('',#139777,1.); -#139777 = DIRECTION('',(-6.725593854929E-015,1.)); -#139778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139779 = PCURVE('',#87156,#139780); -#139780 = DEFINITIONAL_REPRESENTATION('',(#139781),#139785); -#139781 = LINE('',#139782,#139783); -#139782 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#139783 = VECTOR('',#139784,1.); -#139784 = DIRECTION('',(0.E+000,1.)); -#139785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139786 = ORIENTED_EDGE('',*,*,#139787,.T.); -#139787 = EDGE_CURVE('',#139760,#139788,#139790,.T.); -#139788 = VERTEX_POINT('',#139789); -#139789 = CARTESIAN_POINT('',(7.35,11.,-0.308197125857)); -#139790 = SURFACE_CURVE('',#139791,(#139795,#139802),.PCURVE_S1.); -#139791 = LINE('',#139792,#139793); -#139792 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#139793 = VECTOR('',#139794,1.); -#139794 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139795 = PCURVE('',#139768,#139796); -#139796 = DEFINITIONAL_REPRESENTATION('',(#139797),#139801); -#139797 = LINE('',#139798,#139799); -#139798 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#139799 = VECTOR('',#139800,1.); -#139800 = DIRECTION('',(-1.,-8.881784197001E-016)); -#139801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142163 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#142164 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#142165 = DEFINITIONAL_REPRESENTATION('',(#142166),#142170); +#142166 = LINE('',#142167,#142168); +#142167 = CARTESIAN_POINT('',(-7.15,-7.105427357601E-015)); +#142168 = VECTOR('',#142169,1.); +#142169 = DIRECTION('',(-6.725593854929E-015,1.)); +#142170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142171 = PCURVE('',#89548,#142172); +#142172 = DEFINITIONAL_REPRESENTATION('',(#142173),#142177); +#142173 = LINE('',#142174,#142175); +#142174 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#142175 = VECTOR('',#142176,1.); +#142176 = DIRECTION('',(0.E+000,1.)); +#142177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142178 = ORIENTED_EDGE('',*,*,#142179,.T.); +#142179 = EDGE_CURVE('',#142152,#142180,#142182,.T.); +#142180 = VERTEX_POINT('',#142181); +#142181 = CARTESIAN_POINT('',(7.35,11.,-0.308197125857)); +#142182 = SURFACE_CURVE('',#142183,(#142187,#142194),.PCURVE_S1.); +#142183 = LINE('',#142184,#142185); +#142184 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#142185 = VECTOR('',#142186,1.); +#142186 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142187 = PCURVE('',#142160,#142188); +#142188 = DEFINITIONAL_REPRESENTATION('',(#142189),#142193); +#142189 = LINE('',#142190,#142191); +#142190 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#142191 = VECTOR('',#142192,1.); +#142192 = DIRECTION('',(-1.,-8.881784197001E-016)); +#142193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142194 = PCURVE('',#142086,#142195); +#142195 = DEFINITIONAL_REPRESENTATION('',(#142196),#142200); +#142196 = LINE('',#142197,#142198); +#142197 = CARTESIAN_POINT('',(7.25,-5.000038352949E-002)); +#142198 = VECTOR('',#142199,1.); +#142199 = DIRECTION('',(-1.,-1.1653254136E-048)); +#142200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142201 = ORIENTED_EDGE('',*,*,#142202,.F.); +#142202 = EDGE_CURVE('',#142203,#142180,#142205,.T.); +#142203 = VERTEX_POINT('',#142204); +#142204 = CARTESIAN_POINT('',(7.35,10.74341632541,-0.308197125857)); +#142205 = SURFACE_CURVE('',#142206,(#142210,#142217),.PCURVE_S1.); +#142206 = LINE('',#142207,#142208); +#142207 = CARTESIAN_POINT('',(7.35,10.74341632541,-0.308197125857)); +#142208 = VECTOR('',#142209,1.); +#142209 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#142210 = PCURVE('',#142160,#142211); +#142211 = DEFINITIONAL_REPRESENTATION('',(#142212),#142216); +#142212 = LINE('',#142213,#142214); +#142213 = CARTESIAN_POINT('',(-7.35,-7.105427357601E-015)); +#142214 = VECTOR('',#142215,1.); +#142215 = DIRECTION('',(-6.725593854929E-015,1.)); +#142216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142217 = PCURVE('',#89604,#142218); +#142218 = DEFINITIONAL_REPRESENTATION('',(#142219),#142223); +#142219 = LINE('',#142220,#142221); +#142220 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#142221 = VECTOR('',#142222,1.); +#142222 = DIRECTION('',(0.E+000,1.)); +#142223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142224 = ORIENTED_EDGE('',*,*,#142225,.T.); +#142225 = EDGE_CURVE('',#142203,#142150,#142226,.T.); +#142226 = SURFACE_CURVE('',#142227,(#142231,#142238),.PCURVE_S1.); +#142227 = LINE('',#142228,#142229); +#142228 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#142229 = VECTOR('',#142230,1.); +#142230 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142231 = PCURVE('',#142160,#142232); +#142232 = DEFINITIONAL_REPRESENTATION('',(#142233),#142237); +#142233 = LINE('',#142234,#142235); +#142234 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142235 = VECTOR('',#142236,1.); +#142236 = DIRECTION('',(1.,8.881784197001E-016)); +#142237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139802 = PCURVE('',#139694,#139803); -#139803 = DEFINITIONAL_REPRESENTATION('',(#139804),#139808); -#139804 = LINE('',#139805,#139806); -#139805 = CARTESIAN_POINT('',(7.25,-5.000038352949E-002)); -#139806 = VECTOR('',#139807,1.); -#139807 = DIRECTION('',(-1.,-1.1653254136E-048)); -#139808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139809 = ORIENTED_EDGE('',*,*,#139810,.F.); -#139810 = EDGE_CURVE('',#139811,#139788,#139813,.T.); -#139811 = VERTEX_POINT('',#139812); -#139812 = CARTESIAN_POINT('',(7.35,10.74341632541,-0.308197125857)); -#139813 = SURFACE_CURVE('',#139814,(#139818,#139825),.PCURVE_S1.); -#139814 = LINE('',#139815,#139816); -#139815 = CARTESIAN_POINT('',(7.35,10.74341632541,-0.308197125857)); -#139816 = VECTOR('',#139817,1.); -#139817 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#139818 = PCURVE('',#139768,#139819); -#139819 = DEFINITIONAL_REPRESENTATION('',(#139820),#139824); -#139820 = LINE('',#139821,#139822); -#139821 = CARTESIAN_POINT('',(-7.35,-7.105427357601E-015)); -#139822 = VECTOR('',#139823,1.); -#139823 = DIRECTION('',(-6.725593854929E-015,1.)); -#139824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139825 = PCURVE('',#87212,#139826); -#139826 = DEFINITIONAL_REPRESENTATION('',(#139827),#139831); -#139827 = LINE('',#139828,#139829); -#139828 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#139829 = VECTOR('',#139830,1.); -#139830 = DIRECTION('',(0.E+000,1.)); -#139831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139832 = ORIENTED_EDGE('',*,*,#139833,.T.); -#139833 = EDGE_CURVE('',#139811,#139758,#139834,.T.); -#139834 = SURFACE_CURVE('',#139835,(#139839,#139846),.PCURVE_S1.); -#139835 = LINE('',#139836,#139837); -#139836 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#139837 = VECTOR('',#139838,1.); -#139838 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139839 = PCURVE('',#139768,#139840); -#139840 = DEFINITIONAL_REPRESENTATION('',(#139841),#139845); -#139841 = LINE('',#139842,#139843); -#139842 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#139843 = VECTOR('',#139844,1.); -#139844 = DIRECTION('',(1.,8.881784197001E-016)); -#139845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139846 = PCURVE('',#139847,#139852); -#139847 = CYLINDRICAL_SURFACE('',#139848,0.308574064194); -#139848 = AXIS2_PLACEMENT_3D('',#139849,#139850,#139851); -#139849 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#142238 = PCURVE('',#142239,#142244); +#142239 = CYLINDRICAL_SURFACE('',#142240,0.308574064194); +#142240 = AXIS2_PLACEMENT_3D('',#142241,#142242,#142243); +#142241 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#139850 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139851 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139852 = DEFINITIONAL_REPRESENTATION('',(#139853),#139856); -#139853 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139854,#139855), +#142242 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142243 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142244 = DEFINITIONAL_REPRESENTATION('',(#142245),#142248); +#142245 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142246,#142247), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#139854 = CARTESIAN_POINT('',(4.761821717947,7.35)); -#139855 = CARTESIAN_POINT('',(4.761821717947,7.15)); -#139856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139857 = ADVANCED_FACE('',(#139858),#139743,.F.); -#139858 = FACE_BOUND('',#139859,.F.); -#139859 = EDGE_LOOP('',(#139860,#139861,#139888,#139915)); -#139860 = ORIENTED_EDGE('',*,*,#139729,.T.); -#139861 = ORIENTED_EDGE('',*,*,#139862,.F.); -#139862 = EDGE_CURVE('',#139863,#139649,#139865,.T.); -#139863 = VERTEX_POINT('',#139864); -#139864 = CARTESIAN_POINT('',(7.35,10.51959417205,0.E+000)); -#139865 = SURFACE_CURVE('',#139866,(#139871,#139877),.PCURVE_S1.); -#139866 = CIRCLE('',#139867,0.208574704164); -#139867 = AXIS2_PLACEMENT_3D('',#139868,#139869,#139870); -#139868 = CARTESIAN_POINT('',(7.35,10.728168876214,2.640924866458E-017) - ); -#139869 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139870 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139871 = PCURVE('',#139743,#139872); -#139872 = DEFINITIONAL_REPRESENTATION('',(#139873),#139876); -#139873 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139874,#139875), +#142246 = CARTESIAN_POINT('',(4.761821717947,7.35)); +#142247 = CARTESIAN_POINT('',(4.761821717947,7.15)); +#142248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142249 = ADVANCED_FACE('',(#142250),#142135,.F.); +#142250 = FACE_BOUND('',#142251,.F.); +#142251 = EDGE_LOOP('',(#142252,#142253,#142280,#142307)); +#142252 = ORIENTED_EDGE('',*,*,#142121,.T.); +#142253 = ORIENTED_EDGE('',*,*,#142254,.F.); +#142254 = EDGE_CURVE('',#142255,#142041,#142257,.T.); +#142255 = VERTEX_POINT('',#142256); +#142256 = CARTESIAN_POINT('',(7.35,10.51959417205,0.E+000)); +#142257 = SURFACE_CURVE('',#142258,(#142263,#142269),.PCURVE_S1.); +#142258 = CIRCLE('',#142259,0.208574704164); +#142259 = AXIS2_PLACEMENT_3D('',#142260,#142261,#142262); +#142260 = CARTESIAN_POINT('',(7.35,10.728168876214,2.640924866458E-017) + ); +#142261 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142262 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142263 = PCURVE('',#142135,#142264); +#142264 = DEFINITIONAL_REPRESENTATION('',(#142265),#142268); +#142265 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142266,#142267), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#139874 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#139875 = CARTESIAN_POINT('',(4.772630242227,7.35)); -#139876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142266 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#142267 = CARTESIAN_POINT('',(4.772630242227,7.35)); +#142268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139877 = PCURVE('',#87212,#139878); -#139878 = DEFINITIONAL_REPRESENTATION('',(#139879),#139887); -#139879 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139880,#139881,#139882, - #139883,#139884,#139885,#139886),.UNSPECIFIED.,.T.,.F.) +#142269 = PCURVE('',#89604,#142270); +#142270 = DEFINITIONAL_REPRESENTATION('',(#142271),#142279); +#142271 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142272,#142273,#142274, + #142275,#142276,#142277,#142278),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#139880 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#139881 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#139882 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#139883 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#139884 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#139885 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#139886 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#139887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139888 = ORIENTED_EDGE('',*,*,#139889,.T.); -#139889 = EDGE_CURVE('',#139863,#139890,#139892,.T.); -#139890 = VERTEX_POINT('',#139891); -#139891 = CARTESIAN_POINT('',(7.15,10.51959417205,0.E+000)); -#139892 = SURFACE_CURVE('',#139893,(#139897,#139903),.PCURVE_S1.); -#139893 = LINE('',#139894,#139895); -#139894 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#142272 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#142273 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#142274 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#142275 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#142276 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#142277 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#142278 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#142279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142280 = ORIENTED_EDGE('',*,*,#142281,.T.); +#142281 = EDGE_CURVE('',#142255,#142282,#142284,.T.); +#142282 = VERTEX_POINT('',#142283); +#142283 = CARTESIAN_POINT('',(7.15,10.51959417205,0.E+000)); +#142284 = SURFACE_CURVE('',#142285,(#142289,#142295),.PCURVE_S1.); +#142285 = LINE('',#142286,#142287); +#142286 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#139895 = VECTOR('',#139896,1.); -#139896 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#139897 = PCURVE('',#139743,#139898); -#139898 = DEFINITIONAL_REPRESENTATION('',(#139899),#139902); -#139899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139900,#139901), +#142287 = VECTOR('',#142288,1.); +#142288 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142289 = PCURVE('',#142135,#142290); +#142290 = DEFINITIONAL_REPRESENTATION('',(#142291),#142294); +#142291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142292,#142293), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#139900 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#139901 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#139902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142292 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#142293 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#142294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#139903 = PCURVE('',#139904,#139909); -#139904 = PLANE('',#139905); -#139905 = AXIS2_PLACEMENT_3D('',#139906,#139907,#139908); -#139906 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#142295 = PCURVE('',#142296,#142301); +#142296 = PLANE('',#142297); +#142297 = AXIS2_PLACEMENT_3D('',#142298,#142299,#142300); +#142298 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#139907 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#139908 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139909 = DEFINITIONAL_REPRESENTATION('',(#139910),#139914); -#139910 = LINE('',#139911,#139912); -#139911 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#139912 = VECTOR('',#139913,1.); -#139913 = DIRECTION('',(-1.,0.E+000)); -#139914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139915 = ORIENTED_EDGE('',*,*,#139916,.T.); -#139916 = EDGE_CURVE('',#139890,#139707,#139917,.T.); -#139917 = SURFACE_CURVE('',#139918,(#139923,#139929),.PCURVE_S1.); -#139918 = CIRCLE('',#139919,0.208574704164); -#139919 = AXIS2_PLACEMENT_3D('',#139920,#139921,#139922); -#139920 = CARTESIAN_POINT('',(7.15,10.728168876214,2.640924866458E-017) - ); -#139921 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139922 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139923 = PCURVE('',#139743,#139924); -#139924 = DEFINITIONAL_REPRESENTATION('',(#139925),#139928); -#139925 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#139926,#139927), +#142299 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142300 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142301 = DEFINITIONAL_REPRESENTATION('',(#142302),#142306); +#142302 = LINE('',#142303,#142304); +#142303 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#142304 = VECTOR('',#142305,1.); +#142305 = DIRECTION('',(-1.,0.E+000)); +#142306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142307 = ORIENTED_EDGE('',*,*,#142308,.T.); +#142308 = EDGE_CURVE('',#142282,#142099,#142309,.T.); +#142309 = SURFACE_CURVE('',#142310,(#142315,#142321),.PCURVE_S1.); +#142310 = CIRCLE('',#142311,0.208574704164); +#142311 = AXIS2_PLACEMENT_3D('',#142312,#142313,#142314); +#142312 = CARTESIAN_POINT('',(7.15,10.728168876214,2.640924866458E-017) + ); +#142313 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142314 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142315 = PCURVE('',#142135,#142316); +#142316 = DEFINITIONAL_REPRESENTATION('',(#142317),#142320); +#142317 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142318,#142319), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#139926 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#139927 = CARTESIAN_POINT('',(4.772630242227,7.15)); -#139928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139929 = PCURVE('',#87156,#139930); -#139930 = DEFINITIONAL_REPRESENTATION('',(#139931),#139935); -#139931 = CIRCLE('',#139932,0.208574704164); -#139932 = AXIS2_PLACEMENT_2D('',#139933,#139934); -#139933 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#139934 = DIRECTION('',(0.E+000,1.)); -#139935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139936 = ADVANCED_FACE('',(#139937),#139847,.T.); -#139937 = FACE_BOUND('',#139938,.T.); -#139938 = EDGE_LOOP('',(#139939,#139940,#139990,#140017)); -#139939 = ORIENTED_EDGE('',*,*,#139833,.F.); -#139940 = ORIENTED_EDGE('',*,*,#139941,.F.); -#139941 = EDGE_CURVE('',#139942,#139811,#139944,.T.); -#139942 = VERTEX_POINT('',#139943); -#139943 = CARTESIAN_POINT('',(7.35,10.419594812019,0.E+000)); -#139944 = SURFACE_CURVE('',#139945,(#139950,#139979),.PCURVE_S1.); -#139945 = CIRCLE('',#139946,0.308574064194); -#139946 = AXIS2_PLACEMENT_3D('',#139947,#139948,#139949); -#139947 = CARTESIAN_POINT('',(7.35,10.728168876214,2.640924866458E-017) - ); -#139948 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139949 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#139950 = PCURVE('',#139847,#139951); -#139951 = DEFINITIONAL_REPRESENTATION('',(#139952),#139978); -#139952 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#139953,#139954,#139955, - #139956,#139957,#139958,#139959,#139960,#139961,#139962,#139963, - #139964,#139965,#139966,#139967,#139968,#139969,#139970,#139971, - #139972,#139973,#139974,#139975,#139976,#139977),.UNSPECIFIED.,.F., +#142318 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#142319 = CARTESIAN_POINT('',(4.772630242227,7.15)); +#142320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142321 = PCURVE('',#89548,#142322); +#142322 = DEFINITIONAL_REPRESENTATION('',(#142323),#142327); +#142323 = CIRCLE('',#142324,0.208574704164); +#142324 = AXIS2_PLACEMENT_2D('',#142325,#142326); +#142325 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#142326 = DIRECTION('',(0.E+000,1.)); +#142327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142328 = ADVANCED_FACE('',(#142329),#142239,.T.); +#142329 = FACE_BOUND('',#142330,.T.); +#142330 = EDGE_LOOP('',(#142331,#142332,#142382,#142409)); +#142331 = ORIENTED_EDGE('',*,*,#142225,.F.); +#142332 = ORIENTED_EDGE('',*,*,#142333,.F.); +#142333 = EDGE_CURVE('',#142334,#142203,#142336,.T.); +#142334 = VERTEX_POINT('',#142335); +#142335 = CARTESIAN_POINT('',(7.35,10.419594812019,0.E+000)); +#142336 = SURFACE_CURVE('',#142337,(#142342,#142371),.PCURVE_S1.); +#142337 = CIRCLE('',#142338,0.308574064194); +#142338 = AXIS2_PLACEMENT_3D('',#142339,#142340,#142341); +#142339 = CARTESIAN_POINT('',(7.35,10.728168876214,2.640924866458E-017) + ); +#142340 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142341 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142342 = PCURVE('',#142239,#142343); +#142343 = DEFINITIONAL_REPRESENTATION('',(#142344),#142370); +#142344 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142345,#142346,#142347, + #142348,#142349,#142350,#142351,#142352,#142353,#142354,#142355, + #142356,#142357,#142358,#142359,#142360,#142361,#142362,#142363, + #142364,#142365,#142366,#142367,#142368,#142369),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -172507,102 +175509,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#139953 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#139954 = CARTESIAN_POINT('',(3.166141578807,7.35)); -#139955 = CARTESIAN_POINT('',(3.215239429242,7.35)); -#139956 = CARTESIAN_POINT('',(3.288886204895,7.35)); -#139957 = CARTESIAN_POINT('',(3.362532980548,7.35)); -#139958 = CARTESIAN_POINT('',(3.4361797562,7.35)); -#139959 = CARTESIAN_POINT('',(3.509826531853,7.35)); -#139960 = CARTESIAN_POINT('',(3.583473307505,7.35)); -#139961 = CARTESIAN_POINT('',(3.657120083158,7.35)); -#139962 = CARTESIAN_POINT('',(3.730766858811,7.35)); -#139963 = CARTESIAN_POINT('',(3.804413634463,7.35)); -#139964 = CARTESIAN_POINT('',(3.878060410116,7.35)); -#139965 = CARTESIAN_POINT('',(3.951707185768,7.35)); -#139966 = CARTESIAN_POINT('',(4.025353961421,7.35)); -#139967 = CARTESIAN_POINT('',(4.099000737074,7.35)); -#139968 = CARTESIAN_POINT('',(4.172647512726,7.35)); -#139969 = CARTESIAN_POINT('',(4.246294288379,7.35)); -#139970 = CARTESIAN_POINT('',(4.319941064031,7.35)); -#139971 = CARTESIAN_POINT('',(4.393587839684,7.35)); -#139972 = CARTESIAN_POINT('',(4.467234615337,7.35)); -#139973 = CARTESIAN_POINT('',(4.540881390989,7.35)); -#139974 = CARTESIAN_POINT('',(4.614528166642,7.35)); -#139975 = CARTESIAN_POINT('',(4.688174942294,7.35)); -#139976 = CARTESIAN_POINT('',(4.737272792729,7.35)); -#139977 = CARTESIAN_POINT('',(4.761821717947,7.35)); -#139978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139979 = PCURVE('',#87212,#139980); -#139980 = DEFINITIONAL_REPRESENTATION('',(#139981),#139989); -#139981 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#139982,#139983,#139984, - #139985,#139986,#139987,#139988),.UNSPECIFIED.,.T.,.F.) +#142345 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#142346 = CARTESIAN_POINT('',(3.166141578807,7.35)); +#142347 = CARTESIAN_POINT('',(3.215239429242,7.35)); +#142348 = CARTESIAN_POINT('',(3.288886204895,7.35)); +#142349 = CARTESIAN_POINT('',(3.362532980548,7.35)); +#142350 = CARTESIAN_POINT('',(3.4361797562,7.35)); +#142351 = CARTESIAN_POINT('',(3.509826531853,7.35)); +#142352 = CARTESIAN_POINT('',(3.583473307505,7.35)); +#142353 = CARTESIAN_POINT('',(3.657120083158,7.35)); +#142354 = CARTESIAN_POINT('',(3.730766858811,7.35)); +#142355 = CARTESIAN_POINT('',(3.804413634463,7.35)); +#142356 = CARTESIAN_POINT('',(3.878060410116,7.35)); +#142357 = CARTESIAN_POINT('',(3.951707185768,7.35)); +#142358 = CARTESIAN_POINT('',(4.025353961421,7.35)); +#142359 = CARTESIAN_POINT('',(4.099000737074,7.35)); +#142360 = CARTESIAN_POINT('',(4.172647512726,7.35)); +#142361 = CARTESIAN_POINT('',(4.246294288379,7.35)); +#142362 = CARTESIAN_POINT('',(4.319941064031,7.35)); +#142363 = CARTESIAN_POINT('',(4.393587839684,7.35)); +#142364 = CARTESIAN_POINT('',(4.467234615337,7.35)); +#142365 = CARTESIAN_POINT('',(4.540881390989,7.35)); +#142366 = CARTESIAN_POINT('',(4.614528166642,7.35)); +#142367 = CARTESIAN_POINT('',(4.688174942294,7.35)); +#142368 = CARTESIAN_POINT('',(4.737272792729,7.35)); +#142369 = CARTESIAN_POINT('',(4.761821717947,7.35)); +#142370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142371 = PCURVE('',#89604,#142372); +#142372 = DEFINITIONAL_REPRESENTATION('',(#142373),#142381); +#142373 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142374,#142375,#142376, + #142377,#142378,#142379,#142380),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#139982 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#139983 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#139984 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#139985 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#139986 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#139987 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#139988 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#139989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#139990 = ORIENTED_EDGE('',*,*,#139991,.F.); -#139991 = EDGE_CURVE('',#139992,#139942,#139994,.T.); -#139992 = VERTEX_POINT('',#139993); -#139993 = CARTESIAN_POINT('',(7.15,10.419594812019,0.E+000)); -#139994 = SURFACE_CURVE('',#139995,(#139999,#140005),.PCURVE_S1.); -#139995 = LINE('',#139996,#139997); -#139996 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#142374 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#142375 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#142376 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#142377 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#142378 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#142379 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#142380 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#142381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142382 = ORIENTED_EDGE('',*,*,#142383,.F.); +#142383 = EDGE_CURVE('',#142384,#142334,#142386,.T.); +#142384 = VERTEX_POINT('',#142385); +#142385 = CARTESIAN_POINT('',(7.15,10.419594812019,0.E+000)); +#142386 = SURFACE_CURVE('',#142387,(#142391,#142397),.PCURVE_S1.); +#142387 = LINE('',#142388,#142389); +#142388 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#139997 = VECTOR('',#139998,1.); -#139998 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#139999 = PCURVE('',#139847,#140000); -#140000 = DEFINITIONAL_REPRESENTATION('',(#140001),#140004); -#140001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140002,#140003), +#142389 = VECTOR('',#142390,1.); +#142390 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142391 = PCURVE('',#142239,#142392); +#142392 = DEFINITIONAL_REPRESENTATION('',(#142393),#142396); +#142393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142394,#142395), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#140002 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#140003 = CARTESIAN_POINT('',(3.14159265359,7.35)); -#140004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142394 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#142395 = CARTESIAN_POINT('',(3.14159265359,7.35)); +#142396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140005 = PCURVE('',#140006,#140011); -#140006 = PLANE('',#140007); -#140007 = AXIS2_PLACEMENT_3D('',#140008,#140009,#140010); -#140008 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#142397 = PCURVE('',#142398,#142403); +#142398 = PLANE('',#142399); +#142399 = AXIS2_PLACEMENT_3D('',#142400,#142401,#142402); +#142400 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#140009 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140010 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140011 = DEFINITIONAL_REPRESENTATION('',(#140012),#140016); -#140012 = LINE('',#140013,#140014); -#140013 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#140014 = VECTOR('',#140015,1.); -#140015 = DIRECTION('',(-1.,0.E+000)); -#140016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140017 = ORIENTED_EDGE('',*,*,#140018,.T.); -#140018 = EDGE_CURVE('',#139992,#139758,#140019,.T.); -#140019 = SURFACE_CURVE('',#140020,(#140025,#140054),.PCURVE_S1.); -#140020 = CIRCLE('',#140021,0.308574064194); -#140021 = AXIS2_PLACEMENT_3D('',#140022,#140023,#140024); -#140022 = CARTESIAN_POINT('',(7.15,10.728168876214,2.640924866458E-017) - ); -#140023 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140024 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140025 = PCURVE('',#139847,#140026); -#140026 = DEFINITIONAL_REPRESENTATION('',(#140027),#140053); -#140027 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140028,#140029,#140030, - #140031,#140032,#140033,#140034,#140035,#140036,#140037,#140038, - #140039,#140040,#140041,#140042,#140043,#140044,#140045,#140046, - #140047,#140048,#140049,#140050,#140051,#140052),.UNSPECIFIED.,.F., +#142401 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142402 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142403 = DEFINITIONAL_REPRESENTATION('',(#142404),#142408); +#142404 = LINE('',#142405,#142406); +#142405 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#142406 = VECTOR('',#142407,1.); +#142407 = DIRECTION('',(-1.,0.E+000)); +#142408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142409 = ORIENTED_EDGE('',*,*,#142410,.T.); +#142410 = EDGE_CURVE('',#142384,#142150,#142411,.T.); +#142411 = SURFACE_CURVE('',#142412,(#142417,#142446),.PCURVE_S1.); +#142412 = CIRCLE('',#142413,0.308574064194); +#142413 = AXIS2_PLACEMENT_3D('',#142414,#142415,#142416); +#142414 = CARTESIAN_POINT('',(7.15,10.728168876214,2.640924866458E-017) + ); +#142415 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142416 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#142417 = PCURVE('',#142239,#142418); +#142418 = DEFINITIONAL_REPRESENTATION('',(#142419),#142445); +#142419 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142420,#142421,#142422, + #142423,#142424,#142425,#142426,#142427,#142428,#142429,#142430, + #142431,#142432,#142433,#142434,#142435,#142436,#142437,#142438, + #142439,#142440,#142441,#142442,#142443,#142444),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -172610,339 +175612,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#140028 = CARTESIAN_POINT('',(3.14159265359,7.15)); -#140029 = CARTESIAN_POINT('',(3.166141578807,7.15)); -#140030 = CARTESIAN_POINT('',(3.215239429242,7.15)); -#140031 = CARTESIAN_POINT('',(3.288886204895,7.15)); -#140032 = CARTESIAN_POINT('',(3.362532980548,7.15)); -#140033 = CARTESIAN_POINT('',(3.4361797562,7.15)); -#140034 = CARTESIAN_POINT('',(3.509826531853,7.15)); -#140035 = CARTESIAN_POINT('',(3.583473307505,7.15)); -#140036 = CARTESIAN_POINT('',(3.657120083158,7.15)); -#140037 = CARTESIAN_POINT('',(3.730766858811,7.15)); -#140038 = CARTESIAN_POINT('',(3.804413634463,7.15)); -#140039 = CARTESIAN_POINT('',(3.878060410116,7.15)); -#140040 = CARTESIAN_POINT('',(3.951707185768,7.15)); -#140041 = CARTESIAN_POINT('',(4.025353961421,7.15)); -#140042 = CARTESIAN_POINT('',(4.099000737074,7.15)); -#140043 = CARTESIAN_POINT('',(4.172647512726,7.15)); -#140044 = CARTESIAN_POINT('',(4.246294288379,7.15)); -#140045 = CARTESIAN_POINT('',(4.319941064031,7.15)); -#140046 = CARTESIAN_POINT('',(4.393587839684,7.15)); -#140047 = CARTESIAN_POINT('',(4.467234615337,7.15)); -#140048 = CARTESIAN_POINT('',(4.540881390989,7.15)); -#140049 = CARTESIAN_POINT('',(4.614528166642,7.15)); -#140050 = CARTESIAN_POINT('',(4.688174942294,7.15)); -#140051 = CARTESIAN_POINT('',(4.737272792729,7.15)); -#140052 = CARTESIAN_POINT('',(4.761821717947,7.15)); -#140053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140054 = PCURVE('',#87156,#140055); -#140055 = DEFINITIONAL_REPRESENTATION('',(#140056),#140060); -#140056 = CIRCLE('',#140057,0.308574064194); -#140057 = AXIS2_PLACEMENT_2D('',#140058,#140059); -#140058 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#140059 = DIRECTION('',(0.E+000,1.)); -#140060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140061 = ADVANCED_FACE('',(#140062),#140006,.F.); -#140062 = FACE_BOUND('',#140063,.T.); -#140063 = EDGE_LOOP('',(#140064,#140093,#140114,#140115)); -#140064 = ORIENTED_EDGE('',*,*,#140065,.F.); -#140065 = EDGE_CURVE('',#140066,#140068,#140070,.T.); -#140066 = VERTEX_POINT('',#140067); -#140067 = CARTESIAN_POINT('',(7.15,10.419594812019,0.530776333563)); -#140068 = VERTEX_POINT('',#140069); -#140069 = CARTESIAN_POINT('',(7.35,10.419594812019,0.530776333563)); -#140070 = SURFACE_CURVE('',#140071,(#140075,#140082),.PCURVE_S1.); -#140071 = LINE('',#140072,#140073); -#140072 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#142420 = CARTESIAN_POINT('',(3.14159265359,7.15)); +#142421 = CARTESIAN_POINT('',(3.166141578807,7.15)); +#142422 = CARTESIAN_POINT('',(3.215239429242,7.15)); +#142423 = CARTESIAN_POINT('',(3.288886204895,7.15)); +#142424 = CARTESIAN_POINT('',(3.362532980548,7.15)); +#142425 = CARTESIAN_POINT('',(3.4361797562,7.15)); +#142426 = CARTESIAN_POINT('',(3.509826531853,7.15)); +#142427 = CARTESIAN_POINT('',(3.583473307505,7.15)); +#142428 = CARTESIAN_POINT('',(3.657120083158,7.15)); +#142429 = CARTESIAN_POINT('',(3.730766858811,7.15)); +#142430 = CARTESIAN_POINT('',(3.804413634463,7.15)); +#142431 = CARTESIAN_POINT('',(3.878060410116,7.15)); +#142432 = CARTESIAN_POINT('',(3.951707185768,7.15)); +#142433 = CARTESIAN_POINT('',(4.025353961421,7.15)); +#142434 = CARTESIAN_POINT('',(4.099000737074,7.15)); +#142435 = CARTESIAN_POINT('',(4.172647512726,7.15)); +#142436 = CARTESIAN_POINT('',(4.246294288379,7.15)); +#142437 = CARTESIAN_POINT('',(4.319941064031,7.15)); +#142438 = CARTESIAN_POINT('',(4.393587839684,7.15)); +#142439 = CARTESIAN_POINT('',(4.467234615337,7.15)); +#142440 = CARTESIAN_POINT('',(4.540881390989,7.15)); +#142441 = CARTESIAN_POINT('',(4.614528166642,7.15)); +#142442 = CARTESIAN_POINT('',(4.688174942294,7.15)); +#142443 = CARTESIAN_POINT('',(4.737272792729,7.15)); +#142444 = CARTESIAN_POINT('',(4.761821717947,7.15)); +#142445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142446 = PCURVE('',#89548,#142447); +#142447 = DEFINITIONAL_REPRESENTATION('',(#142448),#142452); +#142448 = CIRCLE('',#142449,0.308574064194); +#142449 = AXIS2_PLACEMENT_2D('',#142450,#142451); +#142450 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#142451 = DIRECTION('',(0.E+000,1.)); +#142452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142453 = ADVANCED_FACE('',(#142454),#142398,.F.); +#142454 = FACE_BOUND('',#142455,.T.); +#142455 = EDGE_LOOP('',(#142456,#142485,#142506,#142507)); +#142456 = ORIENTED_EDGE('',*,*,#142457,.F.); +#142457 = EDGE_CURVE('',#142458,#142460,#142462,.T.); +#142458 = VERTEX_POINT('',#142459); +#142459 = CARTESIAN_POINT('',(7.15,10.419594812019,0.530776333563)); +#142460 = VERTEX_POINT('',#142461); +#142461 = CARTESIAN_POINT('',(7.35,10.419594812019,0.530776333563)); +#142462 = SURFACE_CURVE('',#142463,(#142467,#142474),.PCURVE_S1.); +#142463 = LINE('',#142464,#142465); +#142464 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#140073 = VECTOR('',#140074,1.); -#140074 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140075 = PCURVE('',#140006,#140076); -#140076 = DEFINITIONAL_REPRESENTATION('',(#140077),#140081); -#140077 = LINE('',#140078,#140079); -#140078 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140079 = VECTOR('',#140080,1.); -#140080 = DIRECTION('',(-1.,0.E+000)); -#140081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140082 = PCURVE('',#140083,#140088); -#140083 = CYLINDRICAL_SURFACE('',#140084,0.119270391569); -#140084 = AXIS2_PLACEMENT_3D('',#140085,#140086,#140087); -#140085 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#142465 = VECTOR('',#142466,1.); +#142466 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142467 = PCURVE('',#142398,#142468); +#142468 = DEFINITIONAL_REPRESENTATION('',(#142469),#142473); +#142469 = LINE('',#142470,#142471); +#142470 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142471 = VECTOR('',#142472,1.); +#142472 = DIRECTION('',(-1.,0.E+000)); +#142473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142474 = PCURVE('',#142475,#142480); +#142475 = CYLINDRICAL_SURFACE('',#142476,0.119270391569); +#142476 = AXIS2_PLACEMENT_3D('',#142477,#142478,#142479); +#142477 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#140086 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140087 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140088 = DEFINITIONAL_REPRESENTATION('',(#140089),#140092); -#140089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140090,#140091), +#142478 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142479 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142480 = DEFINITIONAL_REPRESENTATION('',(#142481),#142484); +#142481 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142482,#142483), .UNSPECIFIED.,.F.,.F.,(2,2),(7.15,7.35),.PIECEWISE_BEZIER_KNOTS.); -#140090 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#140091 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#140092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140093 = ORIENTED_EDGE('',*,*,#140094,.T.); -#140094 = EDGE_CURVE('',#140066,#139992,#140095,.T.); -#140095 = SURFACE_CURVE('',#140096,(#140100,#140107),.PCURVE_S1.); -#140096 = LINE('',#140097,#140098); -#140097 = CARTESIAN_POINT('',(7.15,10.419594812019,0.530776333563)); -#140098 = VECTOR('',#140099,1.); -#140099 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#140100 = PCURVE('',#140006,#140101); -#140101 = DEFINITIONAL_REPRESENTATION('',(#140102),#140106); -#140102 = LINE('',#140103,#140104); -#140103 = CARTESIAN_POINT('',(-7.15,0.E+000)); -#140104 = VECTOR('',#140105,1.); -#140105 = DIRECTION('',(0.E+000,-1.)); -#140106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140107 = PCURVE('',#87156,#140108); -#140108 = DEFINITIONAL_REPRESENTATION('',(#140109),#140113); -#140109 = LINE('',#140110,#140111); -#140110 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#140111 = VECTOR('',#140112,1.); -#140112 = DIRECTION('',(1.,0.E+000)); -#140113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140114 = ORIENTED_EDGE('',*,*,#139991,.T.); -#140115 = ORIENTED_EDGE('',*,*,#140116,.F.); -#140116 = EDGE_CURVE('',#140068,#139942,#140117,.T.); -#140117 = SURFACE_CURVE('',#140118,(#140122,#140129),.PCURVE_S1.); -#140118 = LINE('',#140119,#140120); -#140119 = CARTESIAN_POINT('',(7.35,10.419594812019,0.530776333563)); -#140120 = VECTOR('',#140121,1.); -#140121 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#140122 = PCURVE('',#140006,#140123); -#140123 = DEFINITIONAL_REPRESENTATION('',(#140124),#140128); -#140124 = LINE('',#140125,#140126); -#140125 = CARTESIAN_POINT('',(-7.35,0.E+000)); -#140126 = VECTOR('',#140127,1.); -#140127 = DIRECTION('',(0.E+000,-1.)); -#140128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140129 = PCURVE('',#87212,#140130); -#140130 = DEFINITIONAL_REPRESENTATION('',(#140131),#140135); -#140131 = LINE('',#140132,#140133); -#140132 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#140133 = VECTOR('',#140134,1.); -#140134 = DIRECTION('',(-1.,0.E+000)); -#140135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140136 = ADVANCED_FACE('',(#140137),#139904,.F.); -#140137 = FACE_BOUND('',#140138,.T.); -#140138 = EDGE_LOOP('',(#140139,#140168,#140189,#140190)); -#140139 = ORIENTED_EDGE('',*,*,#140140,.F.); -#140140 = EDGE_CURVE('',#140141,#140143,#140145,.T.); -#140141 = VERTEX_POINT('',#140142); -#140142 = CARTESIAN_POINT('',(7.35,10.51959417205,0.530776333563)); -#140143 = VERTEX_POINT('',#140144); -#140144 = CARTESIAN_POINT('',(7.15,10.51959417205,0.530776333563)); -#140145 = SURFACE_CURVE('',#140146,(#140150,#140157),.PCURVE_S1.); -#140146 = LINE('',#140147,#140148); -#140147 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#142482 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#142483 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#142484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142485 = ORIENTED_EDGE('',*,*,#142486,.T.); +#142486 = EDGE_CURVE('',#142458,#142384,#142487,.T.); +#142487 = SURFACE_CURVE('',#142488,(#142492,#142499),.PCURVE_S1.); +#142488 = LINE('',#142489,#142490); +#142489 = CARTESIAN_POINT('',(7.15,10.419594812019,0.530776333563)); +#142490 = VECTOR('',#142491,1.); +#142491 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#142492 = PCURVE('',#142398,#142493); +#142493 = DEFINITIONAL_REPRESENTATION('',(#142494),#142498); +#142494 = LINE('',#142495,#142496); +#142495 = CARTESIAN_POINT('',(-7.15,0.E+000)); +#142496 = VECTOR('',#142497,1.); +#142497 = DIRECTION('',(0.E+000,-1.)); +#142498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142499 = PCURVE('',#89548,#142500); +#142500 = DEFINITIONAL_REPRESENTATION('',(#142501),#142505); +#142501 = LINE('',#142502,#142503); +#142502 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#142503 = VECTOR('',#142504,1.); +#142504 = DIRECTION('',(1.,0.E+000)); +#142505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142506 = ORIENTED_EDGE('',*,*,#142383,.T.); +#142507 = ORIENTED_EDGE('',*,*,#142508,.F.); +#142508 = EDGE_CURVE('',#142460,#142334,#142509,.T.); +#142509 = SURFACE_CURVE('',#142510,(#142514,#142521),.PCURVE_S1.); +#142510 = LINE('',#142511,#142512); +#142511 = CARTESIAN_POINT('',(7.35,10.419594812019,0.530776333563)); +#142512 = VECTOR('',#142513,1.); +#142513 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#142514 = PCURVE('',#142398,#142515); +#142515 = DEFINITIONAL_REPRESENTATION('',(#142516),#142520); +#142516 = LINE('',#142517,#142518); +#142517 = CARTESIAN_POINT('',(-7.35,0.E+000)); +#142518 = VECTOR('',#142519,1.); +#142519 = DIRECTION('',(0.E+000,-1.)); +#142520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142521 = PCURVE('',#89604,#142522); +#142522 = DEFINITIONAL_REPRESENTATION('',(#142523),#142527); +#142523 = LINE('',#142524,#142525); +#142524 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#142525 = VECTOR('',#142526,1.); +#142526 = DIRECTION('',(-1.,0.E+000)); +#142527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142528 = ADVANCED_FACE('',(#142529),#142296,.F.); +#142529 = FACE_BOUND('',#142530,.T.); +#142530 = EDGE_LOOP('',(#142531,#142560,#142581,#142582)); +#142531 = ORIENTED_EDGE('',*,*,#142532,.F.); +#142532 = EDGE_CURVE('',#142533,#142535,#142537,.T.); +#142533 = VERTEX_POINT('',#142534); +#142534 = CARTESIAN_POINT('',(7.35,10.51959417205,0.530776333563)); +#142535 = VERTEX_POINT('',#142536); +#142536 = CARTESIAN_POINT('',(7.15,10.51959417205,0.530776333563)); +#142537 = SURFACE_CURVE('',#142538,(#142542,#142549),.PCURVE_S1.); +#142538 = LINE('',#142539,#142540); +#142539 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#140148 = VECTOR('',#140149,1.); -#140149 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140150 = PCURVE('',#139904,#140151); -#140151 = DEFINITIONAL_REPRESENTATION('',(#140152),#140156); -#140152 = LINE('',#140153,#140154); -#140153 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140154 = VECTOR('',#140155,1.); -#140155 = DIRECTION('',(-1.,0.E+000)); -#140156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142540 = VECTOR('',#142541,1.); +#142541 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142542 = PCURVE('',#142296,#142543); +#142543 = DEFINITIONAL_REPRESENTATION('',(#142544),#142548); +#142544 = LINE('',#142545,#142546); +#142545 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142546 = VECTOR('',#142547,1.); +#142547 = DIRECTION('',(-1.,0.E+000)); +#142548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140157 = PCURVE('',#140158,#140163); -#140158 = CYLINDRICAL_SURFACE('',#140159,0.2192697516); -#140159 = AXIS2_PLACEMENT_3D('',#140160,#140161,#140162); -#140160 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#142549 = PCURVE('',#142550,#142555); +#142550 = CYLINDRICAL_SURFACE('',#142551,0.2192697516); +#142551 = AXIS2_PLACEMENT_3D('',#142552,#142553,#142554); +#142552 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#140161 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140162 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140163 = DEFINITIONAL_REPRESENTATION('',(#140164),#140167); -#140164 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140165,#140166), +#142553 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142554 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142555 = DEFINITIONAL_REPRESENTATION('',(#142556),#142559); +#142556 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142557,#142558), .UNSPECIFIED.,.F.,.F.,(2,2),(-7.35,-7.15),.PIECEWISE_BEZIER_KNOTS.); -#140165 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#140166 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#140167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140168 = ORIENTED_EDGE('',*,*,#140169,.T.); -#140169 = EDGE_CURVE('',#140141,#139863,#140170,.T.); -#140170 = SURFACE_CURVE('',#140171,(#140175,#140182),.PCURVE_S1.); -#140171 = LINE('',#140172,#140173); -#140172 = CARTESIAN_POINT('',(7.35,10.51959417205,0.530776333563)); -#140173 = VECTOR('',#140174,1.); -#140174 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#140175 = PCURVE('',#139904,#140176); -#140176 = DEFINITIONAL_REPRESENTATION('',(#140177),#140181); -#140177 = LINE('',#140178,#140179); -#140178 = CARTESIAN_POINT('',(7.35,0.E+000)); -#140179 = VECTOR('',#140180,1.); -#140180 = DIRECTION('',(0.E+000,-1.)); -#140181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140182 = PCURVE('',#87212,#140183); -#140183 = DEFINITIONAL_REPRESENTATION('',(#140184),#140188); -#140184 = LINE('',#140185,#140186); -#140185 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#140186 = VECTOR('',#140187,1.); -#140187 = DIRECTION('',(-1.,0.E+000)); -#140188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140189 = ORIENTED_EDGE('',*,*,#139889,.T.); -#140190 = ORIENTED_EDGE('',*,*,#140191,.F.); -#140191 = EDGE_CURVE('',#140143,#139890,#140192,.T.); -#140192 = SURFACE_CURVE('',#140193,(#140197,#140204),.PCURVE_S1.); -#140193 = LINE('',#140194,#140195); -#140194 = CARTESIAN_POINT('',(7.15,10.51959417205,0.530776333563)); -#140195 = VECTOR('',#140196,1.); -#140196 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#140197 = PCURVE('',#139904,#140198); -#140198 = DEFINITIONAL_REPRESENTATION('',(#140199),#140203); -#140199 = LINE('',#140200,#140201); -#140200 = CARTESIAN_POINT('',(7.15,0.E+000)); -#140201 = VECTOR('',#140202,1.); -#140202 = DIRECTION('',(0.E+000,-1.)); -#140203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140204 = PCURVE('',#87156,#140205); -#140205 = DEFINITIONAL_REPRESENTATION('',(#140206),#140210); -#140206 = LINE('',#140207,#140208); -#140207 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#140208 = VECTOR('',#140209,1.); -#140209 = DIRECTION('',(1.,0.E+000)); -#140210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140211 = ADVANCED_FACE('',(#140212),#140083,.F.); -#140212 = FACE_BOUND('',#140213,.F.); -#140213 = EDGE_LOOP('',(#140214,#140241,#140263,#140284)); -#140214 = ORIENTED_EDGE('',*,*,#140215,.F.); -#140215 = EDGE_CURVE('',#140216,#140066,#140218,.T.); -#140216 = VERTEX_POINT('',#140217); -#140217 = CARTESIAN_POINT('',(7.15,10.303662633502,0.65)); -#140218 = SURFACE_CURVE('',#140219,(#140224,#140230),.PCURVE_S1.); -#140219 = CIRCLE('',#140220,0.119270391569); -#140220 = AXIS2_PLACEMENT_3D('',#140221,#140222,#140223); -#140221 = CARTESIAN_POINT('',(7.15,10.30032442045,0.530776333563)); -#140222 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140223 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140224 = PCURVE('',#140083,#140225); -#140225 = DEFINITIONAL_REPRESENTATION('',(#140226),#140229); -#140226 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140227,#140228), +#142557 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#142558 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#142559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142560 = ORIENTED_EDGE('',*,*,#142561,.T.); +#142561 = EDGE_CURVE('',#142533,#142255,#142562,.T.); +#142562 = SURFACE_CURVE('',#142563,(#142567,#142574),.PCURVE_S1.); +#142563 = LINE('',#142564,#142565); +#142564 = CARTESIAN_POINT('',(7.35,10.51959417205,0.530776333563)); +#142565 = VECTOR('',#142566,1.); +#142566 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#142567 = PCURVE('',#142296,#142568); +#142568 = DEFINITIONAL_REPRESENTATION('',(#142569),#142573); +#142569 = LINE('',#142570,#142571); +#142570 = CARTESIAN_POINT('',(7.35,0.E+000)); +#142571 = VECTOR('',#142572,1.); +#142572 = DIRECTION('',(0.E+000,-1.)); +#142573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142574 = PCURVE('',#89604,#142575); +#142575 = DEFINITIONAL_REPRESENTATION('',(#142576),#142580); +#142576 = LINE('',#142577,#142578); +#142577 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#142578 = VECTOR('',#142579,1.); +#142579 = DIRECTION('',(-1.,0.E+000)); +#142580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142581 = ORIENTED_EDGE('',*,*,#142281,.T.); +#142582 = ORIENTED_EDGE('',*,*,#142583,.F.); +#142583 = EDGE_CURVE('',#142535,#142282,#142584,.T.); +#142584 = SURFACE_CURVE('',#142585,(#142589,#142596),.PCURVE_S1.); +#142585 = LINE('',#142586,#142587); +#142586 = CARTESIAN_POINT('',(7.15,10.51959417205,0.530776333563)); +#142587 = VECTOR('',#142588,1.); +#142588 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#142589 = PCURVE('',#142296,#142590); +#142590 = DEFINITIONAL_REPRESENTATION('',(#142591),#142595); +#142591 = LINE('',#142592,#142593); +#142592 = CARTESIAN_POINT('',(7.15,0.E+000)); +#142593 = VECTOR('',#142594,1.); +#142594 = DIRECTION('',(0.E+000,-1.)); +#142595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142596 = PCURVE('',#89548,#142597); +#142597 = DEFINITIONAL_REPRESENTATION('',(#142598),#142602); +#142598 = LINE('',#142599,#142600); +#142599 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#142600 = VECTOR('',#142601,1.); +#142601 = DIRECTION('',(1.,0.E+000)); +#142602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142603 = ADVANCED_FACE('',(#142604),#142475,.F.); +#142604 = FACE_BOUND('',#142605,.F.); +#142605 = EDGE_LOOP('',(#142606,#142633,#142655,#142676)); +#142606 = ORIENTED_EDGE('',*,*,#142607,.F.); +#142607 = EDGE_CURVE('',#142608,#142458,#142610,.T.); +#142608 = VERTEX_POINT('',#142609); +#142609 = CARTESIAN_POINT('',(7.15,10.303662633502,0.65)); +#142610 = SURFACE_CURVE('',#142611,(#142616,#142622),.PCURVE_S1.); +#142611 = CIRCLE('',#142612,0.119270391569); +#142612 = AXIS2_PLACEMENT_3D('',#142613,#142614,#142615); +#142613 = CARTESIAN_POINT('',(7.15,10.30032442045,0.530776333563)); +#142614 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142615 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142616 = PCURVE('',#142475,#142617); +#142617 = DEFINITIONAL_REPRESENTATION('',(#142618),#142621); +#142618 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142619,#142620), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#140227 = CARTESIAN_POINT('',(1.598788597134,-7.15)); -#140228 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#140229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142619 = CARTESIAN_POINT('',(1.598788597134,-7.15)); +#142620 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#142621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140230 = PCURVE('',#87156,#140231); -#140231 = DEFINITIONAL_REPRESENTATION('',(#140232),#140240); -#140232 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140233,#140234,#140235, - #140236,#140237,#140238,#140239),.UNSPECIFIED.,.T.,.F.) +#142622 = PCURVE('',#89548,#142623); +#142623 = DEFINITIONAL_REPRESENTATION('',(#142624),#142632); +#142624 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142625,#142626,#142627, + #142628,#142629,#142630,#142631),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#140233 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#140234 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#140235 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#140236 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#140237 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#140238 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#140239 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#140240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140241 = ORIENTED_EDGE('',*,*,#140242,.F.); -#140242 = EDGE_CURVE('',#140243,#140216,#140245,.T.); -#140243 = VERTEX_POINT('',#140244); -#140244 = CARTESIAN_POINT('',(7.35,10.303662633502,0.65)); -#140245 = SURFACE_CURVE('',#140246,(#140250,#140256),.PCURVE_S1.); -#140246 = LINE('',#140247,#140248); -#140247 = CARTESIAN_POINT('',(7.15,10.303662633502,0.65)); -#140248 = VECTOR('',#140249,1.); -#140249 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140250 = PCURVE('',#140083,#140251); -#140251 = DEFINITIONAL_REPRESENTATION('',(#140252),#140255); -#140252 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140253,#140254), +#142625 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#142626 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#142627 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#142628 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#142629 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#142630 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#142631 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#142632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142633 = ORIENTED_EDGE('',*,*,#142634,.F.); +#142634 = EDGE_CURVE('',#142635,#142608,#142637,.T.); +#142635 = VERTEX_POINT('',#142636); +#142636 = CARTESIAN_POINT('',(7.35,10.303662633502,0.65)); +#142637 = SURFACE_CURVE('',#142638,(#142642,#142648),.PCURVE_S1.); +#142638 = LINE('',#142639,#142640); +#142639 = CARTESIAN_POINT('',(7.15,10.303662633502,0.65)); +#142640 = VECTOR('',#142641,1.); +#142641 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142642 = PCURVE('',#142475,#142643); +#142643 = DEFINITIONAL_REPRESENTATION('',(#142644),#142647); +#142644 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142645,#142646), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#140253 = CARTESIAN_POINT('',(1.598788597134,-7.35)); -#140254 = CARTESIAN_POINT('',(1.598788597134,-7.15)); -#140255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140256 = PCURVE('',#87184,#140257); -#140257 = DEFINITIONAL_REPRESENTATION('',(#140258),#140262); -#140258 = LINE('',#140259,#140260); -#140259 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#140260 = VECTOR('',#140261,1.); -#140261 = DIRECTION('',(-8.881784197001E-016,-1.)); -#140262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140263 = ORIENTED_EDGE('',*,*,#140264,.T.); -#140264 = EDGE_CURVE('',#140243,#140068,#140265,.T.); -#140265 = SURFACE_CURVE('',#140266,(#140271,#140277),.PCURVE_S1.); -#140266 = CIRCLE('',#140267,0.119270391569); -#140267 = AXIS2_PLACEMENT_3D('',#140268,#140269,#140270); -#140268 = CARTESIAN_POINT('',(7.35,10.30032442045,0.530776333563)); -#140269 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140270 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140271 = PCURVE('',#140083,#140272); -#140272 = DEFINITIONAL_REPRESENTATION('',(#140273),#140276); -#140273 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140274,#140275), +#142645 = CARTESIAN_POINT('',(1.598788597134,-7.35)); +#142646 = CARTESIAN_POINT('',(1.598788597134,-7.15)); +#142647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142648 = PCURVE('',#89576,#142649); +#142649 = DEFINITIONAL_REPRESENTATION('',(#142650),#142654); +#142650 = LINE('',#142651,#142652); +#142651 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#142652 = VECTOR('',#142653,1.); +#142653 = DIRECTION('',(-8.881784197001E-016,-1.)); +#142654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142655 = ORIENTED_EDGE('',*,*,#142656,.T.); +#142656 = EDGE_CURVE('',#142635,#142460,#142657,.T.); +#142657 = SURFACE_CURVE('',#142658,(#142663,#142669),.PCURVE_S1.); +#142658 = CIRCLE('',#142659,0.119270391569); +#142659 = AXIS2_PLACEMENT_3D('',#142660,#142661,#142662); +#142660 = CARTESIAN_POINT('',(7.35,10.30032442045,0.530776333563)); +#142661 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142662 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142663 = PCURVE('',#142475,#142664); +#142664 = DEFINITIONAL_REPRESENTATION('',(#142665),#142668); +#142665 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142666,#142667), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#140274 = CARTESIAN_POINT('',(1.598788597134,-7.35)); -#140275 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#140276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140277 = PCURVE('',#87212,#140278); -#140278 = DEFINITIONAL_REPRESENTATION('',(#140279),#140283); -#140279 = CIRCLE('',#140280,0.119270391569); -#140280 = AXIS2_PLACEMENT_2D('',#140281,#140282); -#140281 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#140282 = DIRECTION('',(0.E+000,-1.)); -#140283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140284 = ORIENTED_EDGE('',*,*,#140065,.F.); -#140285 = ADVANCED_FACE('',(#140286),#140158,.T.); -#140286 = FACE_BOUND('',#140287,.T.); -#140287 = EDGE_LOOP('',(#140288,#140334,#140335,#140385)); -#140288 = ORIENTED_EDGE('',*,*,#140289,.T.); -#140289 = EDGE_CURVE('',#140290,#140141,#140292,.T.); -#140290 = VERTEX_POINT('',#140291); -#140291 = CARTESIAN_POINT('',(7.35,10.304819755875,0.75)); -#140292 = SURFACE_CURVE('',#140293,(#140298,#140327),.PCURVE_S1.); -#140293 = CIRCLE('',#140294,0.2192697516); -#140294 = AXIS2_PLACEMENT_3D('',#140295,#140296,#140297); -#140295 = CARTESIAN_POINT('',(7.35,10.30032442045,0.530776333563)); -#140296 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140297 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140298 = PCURVE('',#140158,#140299); -#140299 = DEFINITIONAL_REPRESENTATION('',(#140300),#140326); -#140300 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140301,#140302,#140303, - #140304,#140305,#140306,#140307,#140308,#140309,#140310,#140311, - #140312,#140313,#140314,#140315,#140316,#140317,#140318,#140319, - #140320,#140321,#140322,#140323,#140324,#140325),.UNSPECIFIED.,.F., +#142666 = CARTESIAN_POINT('',(1.598788597134,-7.35)); +#142667 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#142668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142669 = PCURVE('',#89604,#142670); +#142670 = DEFINITIONAL_REPRESENTATION('',(#142671),#142675); +#142671 = CIRCLE('',#142672,0.119270391569); +#142672 = AXIS2_PLACEMENT_2D('',#142673,#142674); +#142673 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#142674 = DIRECTION('',(0.E+000,-1.)); +#142675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142676 = ORIENTED_EDGE('',*,*,#142457,.F.); +#142677 = ADVANCED_FACE('',(#142678),#142550,.T.); +#142678 = FACE_BOUND('',#142679,.T.); +#142679 = EDGE_LOOP('',(#142680,#142726,#142727,#142777)); +#142680 = ORIENTED_EDGE('',*,*,#142681,.T.); +#142681 = EDGE_CURVE('',#142682,#142533,#142684,.T.); +#142682 = VERTEX_POINT('',#142683); +#142683 = CARTESIAN_POINT('',(7.35,10.304819755875,0.75)); +#142684 = SURFACE_CURVE('',#142685,(#142690,#142719),.PCURVE_S1.); +#142685 = CIRCLE('',#142686,0.2192697516); +#142686 = AXIS2_PLACEMENT_3D('',#142687,#142688,#142689); +#142687 = CARTESIAN_POINT('',(7.35,10.30032442045,0.530776333563)); +#142688 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142689 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142690 = PCURVE('',#142550,#142691); +#142691 = DEFINITIONAL_REPRESENTATION('',(#142692),#142718); +#142692 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142693,#142694,#142695, + #142696,#142697,#142698,#142699,#142700,#142701,#142702,#142703, + #142704,#142705,#142706,#142707,#142708,#142709,#142710,#142711, + #142712,#142713,#142714,#142715,#142716,#142717),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -172950,60 +175952,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#140301 = CARTESIAN_POINT('',(1.591299156552,-7.35)); -#140302 = CARTESIAN_POINT('',(1.614788451962,-7.35)); -#140303 = CARTESIAN_POINT('',(1.661767042781,-7.35)); -#140304 = CARTESIAN_POINT('',(1.73223492901,-7.35)); -#140305 = CARTESIAN_POINT('',(1.802702815239,-7.35)); -#140306 = CARTESIAN_POINT('',(1.873170701468,-7.35)); -#140307 = CARTESIAN_POINT('',(1.943638587697,-7.35)); -#140308 = CARTESIAN_POINT('',(2.014106473926,-7.35)); -#140309 = CARTESIAN_POINT('',(2.084574360155,-7.35)); -#140310 = CARTESIAN_POINT('',(2.155042246384,-7.35)); -#140311 = CARTESIAN_POINT('',(2.225510132613,-7.35)); -#140312 = CARTESIAN_POINT('',(2.295978018842,-7.35)); -#140313 = CARTESIAN_POINT('',(2.366445905071,-7.35)); -#140314 = CARTESIAN_POINT('',(2.4369137913,-7.35)); -#140315 = CARTESIAN_POINT('',(2.507381677529,-7.35)); -#140316 = CARTESIAN_POINT('',(2.577849563758,-7.35)); -#140317 = CARTESIAN_POINT('',(2.648317449987,-7.35)); -#140318 = CARTESIAN_POINT('',(2.718785336216,-7.35)); -#140319 = CARTESIAN_POINT('',(2.789253222445,-7.35)); -#140320 = CARTESIAN_POINT('',(2.859721108674,-7.35)); -#140321 = CARTESIAN_POINT('',(2.930188994903,-7.35)); -#140322 = CARTESIAN_POINT('',(3.000656881132,-7.35)); -#140323 = CARTESIAN_POINT('',(3.071124767361,-7.35)); -#140324 = CARTESIAN_POINT('',(3.11810335818,-7.35)); -#140325 = CARTESIAN_POINT('',(3.14159265359,-7.35)); -#140326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140327 = PCURVE('',#87212,#140328); -#140328 = DEFINITIONAL_REPRESENTATION('',(#140329),#140333); -#140329 = CIRCLE('',#140330,0.2192697516); -#140330 = AXIS2_PLACEMENT_2D('',#140331,#140332); -#140331 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#140332 = DIRECTION('',(0.E+000,-1.)); -#140333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140334 = ORIENTED_EDGE('',*,*,#140140,.T.); -#140335 = ORIENTED_EDGE('',*,*,#140336,.F.); -#140336 = EDGE_CURVE('',#140337,#140143,#140339,.T.); -#140337 = VERTEX_POINT('',#140338); -#140338 = CARTESIAN_POINT('',(7.15,10.304819755875,0.75)); -#140339 = SURFACE_CURVE('',#140340,(#140345,#140374),.PCURVE_S1.); -#140340 = CIRCLE('',#140341,0.2192697516); -#140341 = AXIS2_PLACEMENT_3D('',#140342,#140343,#140344); -#140342 = CARTESIAN_POINT('',(7.15,10.30032442045,0.530776333563)); -#140343 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140344 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140345 = PCURVE('',#140158,#140346); -#140346 = DEFINITIONAL_REPRESENTATION('',(#140347),#140373); -#140347 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140348,#140349,#140350, - #140351,#140352,#140353,#140354,#140355,#140356,#140357,#140358, - #140359,#140360,#140361,#140362,#140363,#140364,#140365,#140366, - #140367,#140368,#140369,#140370,#140371,#140372),.UNSPECIFIED.,.F., +#142693 = CARTESIAN_POINT('',(1.591299156552,-7.35)); +#142694 = CARTESIAN_POINT('',(1.614788451962,-7.35)); +#142695 = CARTESIAN_POINT('',(1.661767042781,-7.35)); +#142696 = CARTESIAN_POINT('',(1.73223492901,-7.35)); +#142697 = CARTESIAN_POINT('',(1.802702815239,-7.35)); +#142698 = CARTESIAN_POINT('',(1.873170701468,-7.35)); +#142699 = CARTESIAN_POINT('',(1.943638587697,-7.35)); +#142700 = CARTESIAN_POINT('',(2.014106473926,-7.35)); +#142701 = CARTESIAN_POINT('',(2.084574360155,-7.35)); +#142702 = CARTESIAN_POINT('',(2.155042246384,-7.35)); +#142703 = CARTESIAN_POINT('',(2.225510132613,-7.35)); +#142704 = CARTESIAN_POINT('',(2.295978018842,-7.35)); +#142705 = CARTESIAN_POINT('',(2.366445905071,-7.35)); +#142706 = CARTESIAN_POINT('',(2.4369137913,-7.35)); +#142707 = CARTESIAN_POINT('',(2.507381677529,-7.35)); +#142708 = CARTESIAN_POINT('',(2.577849563758,-7.35)); +#142709 = CARTESIAN_POINT('',(2.648317449987,-7.35)); +#142710 = CARTESIAN_POINT('',(2.718785336216,-7.35)); +#142711 = CARTESIAN_POINT('',(2.789253222445,-7.35)); +#142712 = CARTESIAN_POINT('',(2.859721108674,-7.35)); +#142713 = CARTESIAN_POINT('',(2.930188994903,-7.35)); +#142714 = CARTESIAN_POINT('',(3.000656881132,-7.35)); +#142715 = CARTESIAN_POINT('',(3.071124767361,-7.35)); +#142716 = CARTESIAN_POINT('',(3.11810335818,-7.35)); +#142717 = CARTESIAN_POINT('',(3.14159265359,-7.35)); +#142718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142719 = PCURVE('',#89604,#142720); +#142720 = DEFINITIONAL_REPRESENTATION('',(#142721),#142725); +#142721 = CIRCLE('',#142722,0.2192697516); +#142722 = AXIS2_PLACEMENT_2D('',#142723,#142724); +#142723 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#142724 = DIRECTION('',(0.E+000,-1.)); +#142725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142726 = ORIENTED_EDGE('',*,*,#142532,.T.); +#142727 = ORIENTED_EDGE('',*,*,#142728,.F.); +#142728 = EDGE_CURVE('',#142729,#142535,#142731,.T.); +#142729 = VERTEX_POINT('',#142730); +#142730 = CARTESIAN_POINT('',(7.15,10.304819755875,0.75)); +#142731 = SURFACE_CURVE('',#142732,(#142737,#142766),.PCURVE_S1.); +#142732 = CIRCLE('',#142733,0.2192697516); +#142733 = AXIS2_PLACEMENT_3D('',#142734,#142735,#142736); +#142734 = CARTESIAN_POINT('',(7.15,10.30032442045,0.530776333563)); +#142735 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#142736 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#142737 = PCURVE('',#142550,#142738); +#142738 = DEFINITIONAL_REPRESENTATION('',(#142739),#142765); +#142739 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142740,#142741,#142742, + #142743,#142744,#142745,#142746,#142747,#142748,#142749,#142750, + #142751,#142752,#142753,#142754,#142755,#142756,#142757,#142758, + #142759,#142760,#142761,#142762,#142763,#142764),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -173011,655 +176013,655 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#140348 = CARTESIAN_POINT('',(1.591299156552,-7.15)); -#140349 = CARTESIAN_POINT('',(1.614788451962,-7.15)); -#140350 = CARTESIAN_POINT('',(1.661767042781,-7.15)); -#140351 = CARTESIAN_POINT('',(1.73223492901,-7.15)); -#140352 = CARTESIAN_POINT('',(1.802702815239,-7.15)); -#140353 = CARTESIAN_POINT('',(1.873170701468,-7.15)); -#140354 = CARTESIAN_POINT('',(1.943638587697,-7.15)); -#140355 = CARTESIAN_POINT('',(2.014106473926,-7.15)); -#140356 = CARTESIAN_POINT('',(2.084574360155,-7.15)); -#140357 = CARTESIAN_POINT('',(2.155042246384,-7.15)); -#140358 = CARTESIAN_POINT('',(2.225510132613,-7.15)); -#140359 = CARTESIAN_POINT('',(2.295978018842,-7.15)); -#140360 = CARTESIAN_POINT('',(2.366445905071,-7.15)); -#140361 = CARTESIAN_POINT('',(2.4369137913,-7.15)); -#140362 = CARTESIAN_POINT('',(2.507381677529,-7.15)); -#140363 = CARTESIAN_POINT('',(2.577849563758,-7.15)); -#140364 = CARTESIAN_POINT('',(2.648317449987,-7.15)); -#140365 = CARTESIAN_POINT('',(2.718785336216,-7.15)); -#140366 = CARTESIAN_POINT('',(2.789253222445,-7.15)); -#140367 = CARTESIAN_POINT('',(2.859721108674,-7.15)); -#140368 = CARTESIAN_POINT('',(2.930188994903,-7.15)); -#140369 = CARTESIAN_POINT('',(3.000656881132,-7.15)); -#140370 = CARTESIAN_POINT('',(3.071124767361,-7.15)); -#140371 = CARTESIAN_POINT('',(3.11810335818,-7.15)); -#140372 = CARTESIAN_POINT('',(3.14159265359,-7.15)); -#140373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140374 = PCURVE('',#87156,#140375); -#140375 = DEFINITIONAL_REPRESENTATION('',(#140376),#140384); -#140376 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140377,#140378,#140379, - #140380,#140381,#140382,#140383),.UNSPECIFIED.,.T.,.F.) +#142740 = CARTESIAN_POINT('',(1.591299156552,-7.15)); +#142741 = CARTESIAN_POINT('',(1.614788451962,-7.15)); +#142742 = CARTESIAN_POINT('',(1.661767042781,-7.15)); +#142743 = CARTESIAN_POINT('',(1.73223492901,-7.15)); +#142744 = CARTESIAN_POINT('',(1.802702815239,-7.15)); +#142745 = CARTESIAN_POINT('',(1.873170701468,-7.15)); +#142746 = CARTESIAN_POINT('',(1.943638587697,-7.15)); +#142747 = CARTESIAN_POINT('',(2.014106473926,-7.15)); +#142748 = CARTESIAN_POINT('',(2.084574360155,-7.15)); +#142749 = CARTESIAN_POINT('',(2.155042246384,-7.15)); +#142750 = CARTESIAN_POINT('',(2.225510132613,-7.15)); +#142751 = CARTESIAN_POINT('',(2.295978018842,-7.15)); +#142752 = CARTESIAN_POINT('',(2.366445905071,-7.15)); +#142753 = CARTESIAN_POINT('',(2.4369137913,-7.15)); +#142754 = CARTESIAN_POINT('',(2.507381677529,-7.15)); +#142755 = CARTESIAN_POINT('',(2.577849563758,-7.15)); +#142756 = CARTESIAN_POINT('',(2.648317449987,-7.15)); +#142757 = CARTESIAN_POINT('',(2.718785336216,-7.15)); +#142758 = CARTESIAN_POINT('',(2.789253222445,-7.15)); +#142759 = CARTESIAN_POINT('',(2.859721108674,-7.15)); +#142760 = CARTESIAN_POINT('',(2.930188994903,-7.15)); +#142761 = CARTESIAN_POINT('',(3.000656881132,-7.15)); +#142762 = CARTESIAN_POINT('',(3.071124767361,-7.15)); +#142763 = CARTESIAN_POINT('',(3.11810335818,-7.15)); +#142764 = CARTESIAN_POINT('',(3.14159265359,-7.15)); +#142765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142766 = PCURVE('',#89548,#142767); +#142767 = DEFINITIONAL_REPRESENTATION('',(#142768),#142776); +#142768 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142769,#142770,#142771, + #142772,#142773,#142774,#142775),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#140377 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#140378 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#140379 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#140380 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#140381 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#140382 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#140383 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#140384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140385 = ORIENTED_EDGE('',*,*,#140386,.T.); -#140386 = EDGE_CURVE('',#140337,#140290,#140387,.T.); -#140387 = SURFACE_CURVE('',#140388,(#140392,#140398),.PCURVE_S1.); -#140388 = LINE('',#140389,#140390); -#140389 = CARTESIAN_POINT('',(7.15,10.304819755875,0.75)); -#140390 = VECTOR('',#140391,1.); -#140391 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140392 = PCURVE('',#140158,#140393); -#140393 = DEFINITIONAL_REPRESENTATION('',(#140394),#140397); -#140394 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140395,#140396), +#142769 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#142770 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#142771 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#142772 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#142773 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#142774 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#142775 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#142776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142777 = ORIENTED_EDGE('',*,*,#142778,.T.); +#142778 = EDGE_CURVE('',#142729,#142682,#142779,.T.); +#142779 = SURFACE_CURVE('',#142780,(#142784,#142790),.PCURVE_S1.); +#142780 = LINE('',#142781,#142782); +#142781 = CARTESIAN_POINT('',(7.15,10.304819755875,0.75)); +#142782 = VECTOR('',#142783,1.); +#142783 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#142784 = PCURVE('',#142550,#142785); +#142785 = DEFINITIONAL_REPRESENTATION('',(#142786),#142789); +#142786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142787,#142788), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#140395 = CARTESIAN_POINT('',(1.591299156552,-7.15)); -#140396 = CARTESIAN_POINT('',(1.591299156552,-7.35)); -#140397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140398 = PCURVE('',#87238,#140399); -#140399 = DEFINITIONAL_REPRESENTATION('',(#140400),#140404); -#140400 = LINE('',#140401,#140402); -#140401 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#140402 = VECTOR('',#140403,1.); -#140403 = DIRECTION('',(-8.881784197001E-016,1.)); -#140404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140405 = ADVANCED_FACE('',(#140406),#87156,.F.); -#140406 = FACE_BOUND('',#140407,.T.); -#140407 = EDGE_LOOP('',(#140408,#140429,#140430,#140431,#140432,#140433, - #140454,#140455,#140456,#140457,#140458,#140479)); -#140408 = ORIENTED_EDGE('',*,*,#140409,.F.); -#140409 = EDGE_CURVE('',#140337,#87141,#140410,.T.); -#140410 = SURFACE_CURVE('',#140411,(#140415,#140422),.PCURVE_S1.); -#140411 = LINE('',#140412,#140413); -#140412 = CARTESIAN_POINT('',(7.15,10.527847992439,0.75)); -#140413 = VECTOR('',#140414,1.); -#140414 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#140415 = PCURVE('',#87156,#140416); -#140416 = DEFINITIONAL_REPRESENTATION('',(#140417),#140421); -#140417 = LINE('',#140418,#140419); -#140418 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#140419 = VECTOR('',#140420,1.); -#140420 = DIRECTION('',(-3.563627120235E-016,-1.)); -#140421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140422 = PCURVE('',#87238,#140423); -#140423 = DEFINITIONAL_REPRESENTATION('',(#140424),#140428); -#140424 = LINE('',#140425,#140426); -#140425 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140426 = VECTOR('',#140427,1.); -#140427 = DIRECTION('',(-1.,2.164989446033E-063)); -#140428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140429 = ORIENTED_EDGE('',*,*,#140336,.T.); -#140430 = ORIENTED_EDGE('',*,*,#140191,.T.); -#140431 = ORIENTED_EDGE('',*,*,#139916,.T.); -#140432 = ORIENTED_EDGE('',*,*,#139706,.T.); -#140433 = ORIENTED_EDGE('',*,*,#140434,.T.); -#140434 = EDGE_CURVE('',#139679,#139760,#140435,.T.); -#140435 = SURFACE_CURVE('',#140436,(#140440,#140447),.PCURVE_S1.); -#140436 = LINE('',#140437,#140438); -#140437 = CARTESIAN_POINT('',(7.15,11.,1.159810404338E-002)); -#140438 = VECTOR('',#140439,1.); -#140439 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#140440 = PCURVE('',#87156,#140441); -#140441 = DEFINITIONAL_REPRESENTATION('',(#140442),#140446); -#140442 = LINE('',#140443,#140444); -#140443 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#140444 = VECTOR('',#140445,1.); -#140445 = DIRECTION('',(1.,-2.101748079665E-016)); -#140446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140447 = PCURVE('',#139694,#140448); -#140448 = DEFINITIONAL_REPRESENTATION('',(#140449),#140453); -#140449 = LINE('',#140450,#140451); -#140450 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#140451 = VECTOR('',#140452,1.); -#140452 = DIRECTION('',(1.570395187386E-016,-1.)); -#140453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140454 = ORIENTED_EDGE('',*,*,#139757,.F.); -#140455 = ORIENTED_EDGE('',*,*,#140018,.F.); -#140456 = ORIENTED_EDGE('',*,*,#140094,.F.); -#140457 = ORIENTED_EDGE('',*,*,#140215,.F.); -#140458 = ORIENTED_EDGE('',*,*,#140459,.T.); -#140459 = EDGE_CURVE('',#140216,#87139,#140460,.T.); -#140460 = SURFACE_CURVE('',#140461,(#140465,#140472),.PCURVE_S1.); -#140461 = LINE('',#140462,#140463); -#140462 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); -#140463 = VECTOR('',#140464,1.); -#140464 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#140465 = PCURVE('',#87156,#140466); -#140466 = DEFINITIONAL_REPRESENTATION('',(#140467),#140471); -#140467 = LINE('',#140468,#140469); -#140468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140469 = VECTOR('',#140470,1.); -#140470 = DIRECTION('',(-3.563627120235E-016,-1.)); -#140471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140472 = PCURVE('',#87184,#140473); -#140473 = DEFINITIONAL_REPRESENTATION('',(#140474),#140478); -#140474 = LINE('',#140475,#140476); -#140475 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140476 = VECTOR('',#140477,1.); -#140477 = DIRECTION('',(1.,2.164989446033E-063)); -#140478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140479 = ORIENTED_EDGE('',*,*,#87138,.T.); -#140480 = ADVANCED_FACE('',(#140481),#87238,.F.); -#140481 = FACE_BOUND('',#140482,.T.); -#140482 = EDGE_LOOP('',(#140483,#140484,#140485,#140486)); -#140483 = ORIENTED_EDGE('',*,*,#140386,.F.); -#140484 = ORIENTED_EDGE('',*,*,#140409,.T.); -#140485 = ORIENTED_EDGE('',*,*,#87224,.T.); -#140486 = ORIENTED_EDGE('',*,*,#140487,.F.); -#140487 = EDGE_CURVE('',#140290,#87197,#140488,.T.); -#140488 = SURFACE_CURVE('',#140489,(#140493,#140500),.PCURVE_S1.); -#140489 = LINE('',#140490,#140491); -#140490 = CARTESIAN_POINT('',(7.35,10.527847992439,0.75)); -#140491 = VECTOR('',#140492,1.); -#140492 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#140493 = PCURVE('',#87238,#140494); -#140494 = DEFINITIONAL_REPRESENTATION('',(#140495),#140499); -#140495 = LINE('',#140496,#140497); -#140496 = CARTESIAN_POINT('',(0.E+000,0.2)); -#140497 = VECTOR('',#140498,1.); -#140498 = DIRECTION('',(-1.,2.164989446033E-063)); -#140499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140500 = PCURVE('',#87212,#140501); -#140501 = DEFINITIONAL_REPRESENTATION('',(#140502),#140506); -#140502 = LINE('',#140503,#140504); -#140503 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#140504 = VECTOR('',#140505,1.); -#140505 = DIRECTION('',(3.563627120235E-016,-1.)); -#140506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140507 = ADVANCED_FACE('',(#140508),#87212,.F.); -#140508 = FACE_BOUND('',#140509,.T.); -#140509 = EDGE_LOOP('',(#140510,#140531,#140532,#140533,#140534,#140535, - #140556,#140557,#140558,#140559,#140560,#140561)); -#140510 = ORIENTED_EDGE('',*,*,#140511,.F.); -#140511 = EDGE_CURVE('',#140243,#87169,#140512,.T.); -#140512 = SURFACE_CURVE('',#140513,(#140517,#140524),.PCURVE_S1.); -#140513 = LINE('',#140514,#140515); -#140514 = CARTESIAN_POINT('',(7.35,10.527847992439,0.65)); -#140515 = VECTOR('',#140516,1.); -#140516 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#140517 = PCURVE('',#87212,#140518); -#140518 = DEFINITIONAL_REPRESENTATION('',(#140519),#140523); -#140519 = LINE('',#140520,#140521); -#140520 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140521 = VECTOR('',#140522,1.); -#140522 = DIRECTION('',(3.563627120235E-016,-1.)); -#140523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140524 = PCURVE('',#87184,#140525); -#140525 = DEFINITIONAL_REPRESENTATION('',(#140526),#140530); -#140526 = LINE('',#140527,#140528); -#140527 = CARTESIAN_POINT('',(0.E+000,0.2)); -#140528 = VECTOR('',#140529,1.); -#140529 = DIRECTION('',(1.,2.164989446033E-063)); -#140530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140531 = ORIENTED_EDGE('',*,*,#140264,.T.); -#140532 = ORIENTED_EDGE('',*,*,#140116,.T.); -#140533 = ORIENTED_EDGE('',*,*,#139941,.T.); -#140534 = ORIENTED_EDGE('',*,*,#139810,.T.); -#140535 = ORIENTED_EDGE('',*,*,#140536,.T.); -#140536 = EDGE_CURVE('',#139788,#139651,#140537,.T.); -#140537 = SURFACE_CURVE('',#140538,(#140542,#140549),.PCURVE_S1.); -#140538 = LINE('',#140539,#140540); -#140539 = CARTESIAN_POINT('',(7.35,11.,1.159810404338E-002)); -#140540 = VECTOR('',#140541,1.); -#140541 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#140542 = PCURVE('',#87212,#140543); -#140543 = DEFINITIONAL_REPRESENTATION('',(#140544),#140548); -#140544 = LINE('',#140545,#140546); -#140545 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#140546 = VECTOR('',#140547,1.); -#140547 = DIRECTION('',(1.,2.101748079665E-016)); -#140548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140549 = PCURVE('',#139694,#140550); -#140550 = DEFINITIONAL_REPRESENTATION('',(#140551),#140555); -#140551 = LINE('',#140552,#140553); -#140552 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#140553 = VECTOR('',#140554,1.); -#140554 = DIRECTION('',(-1.570395187386E-016,1.)); -#140555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140556 = ORIENTED_EDGE('',*,*,#139648,.F.); -#140557 = ORIENTED_EDGE('',*,*,#139862,.F.); -#140558 = ORIENTED_EDGE('',*,*,#140169,.F.); -#140559 = ORIENTED_EDGE('',*,*,#140289,.F.); -#140560 = ORIENTED_EDGE('',*,*,#140487,.T.); -#140561 = ORIENTED_EDGE('',*,*,#87196,.T.); -#140562 = ADVANCED_FACE('',(#140563),#87184,.F.); -#140563 = FACE_BOUND('',#140564,.T.); -#140564 = EDGE_LOOP('',(#140565,#140566,#140567,#140568)); -#140565 = ORIENTED_EDGE('',*,*,#140242,.F.); -#140566 = ORIENTED_EDGE('',*,*,#140511,.T.); -#140567 = ORIENTED_EDGE('',*,*,#87168,.T.); -#140568 = ORIENTED_EDGE('',*,*,#140459,.F.); -#140569 = ADVANCED_FACE('',(#140570),#139694,.T.); -#140570 = FACE_BOUND('',#140571,.T.); -#140571 = EDGE_LOOP('',(#140572,#140573,#140574,#140575)); -#140572 = ORIENTED_EDGE('',*,*,#140536,.F.); -#140573 = ORIENTED_EDGE('',*,*,#139787,.F.); -#140574 = ORIENTED_EDGE('',*,*,#140434,.F.); -#140575 = ORIENTED_EDGE('',*,*,#139678,.F.); -#140576 = ADVANCED_FACE('',(#140577),#140591,.T.); -#140577 = FACE_BOUND('',#140578,.T.); -#140578 = EDGE_LOOP('',(#140579,#140609,#140637,#140660)); -#140579 = ORIENTED_EDGE('',*,*,#140580,.T.); -#140580 = EDGE_CURVE('',#140581,#140583,#140585,.T.); -#140581 = VERTEX_POINT('',#140582); -#140582 = CARTESIAN_POINT('',(6.85,10.740726081328,-0.208196358798)); -#140583 = VERTEX_POINT('',#140584); -#140584 = CARTESIAN_POINT('',(6.85,11.,-0.208196358798)); -#140585 = SURFACE_CURVE('',#140586,(#140590,#140602),.PCURVE_S1.); -#140586 = LINE('',#140587,#140588); -#140587 = CARTESIAN_POINT('',(6.85,10.740726081328,-0.208196358798)); -#140588 = VECTOR('',#140589,1.); -#140589 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#140590 = PCURVE('',#140591,#140596); -#140591 = PLANE('',#140592); -#140592 = AXIS2_PLACEMENT_3D('',#140593,#140594,#140595); -#140593 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#142787 = CARTESIAN_POINT('',(1.591299156552,-7.15)); +#142788 = CARTESIAN_POINT('',(1.591299156552,-7.35)); +#142789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142790 = PCURVE('',#89630,#142791); +#142791 = DEFINITIONAL_REPRESENTATION('',(#142792),#142796); +#142792 = LINE('',#142793,#142794); +#142793 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#142794 = VECTOR('',#142795,1.); +#142795 = DIRECTION('',(-8.881784197001E-016,1.)); +#142796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142797 = ADVANCED_FACE('',(#142798),#89548,.F.); +#142798 = FACE_BOUND('',#142799,.T.); +#142799 = EDGE_LOOP('',(#142800,#142821,#142822,#142823,#142824,#142825, + #142846,#142847,#142848,#142849,#142850,#142871)); +#142800 = ORIENTED_EDGE('',*,*,#142801,.F.); +#142801 = EDGE_CURVE('',#142729,#89533,#142802,.T.); +#142802 = SURFACE_CURVE('',#142803,(#142807,#142814),.PCURVE_S1.); +#142803 = LINE('',#142804,#142805); +#142804 = CARTESIAN_POINT('',(7.15,10.527847992439,0.75)); +#142805 = VECTOR('',#142806,1.); +#142806 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#142807 = PCURVE('',#89548,#142808); +#142808 = DEFINITIONAL_REPRESENTATION('',(#142809),#142813); +#142809 = LINE('',#142810,#142811); +#142810 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#142811 = VECTOR('',#142812,1.); +#142812 = DIRECTION('',(-3.563627120235E-016,-1.)); +#142813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142814 = PCURVE('',#89630,#142815); +#142815 = DEFINITIONAL_REPRESENTATION('',(#142816),#142820); +#142816 = LINE('',#142817,#142818); +#142817 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142818 = VECTOR('',#142819,1.); +#142819 = DIRECTION('',(-1.,2.164989446033E-063)); +#142820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142821 = ORIENTED_EDGE('',*,*,#142728,.T.); +#142822 = ORIENTED_EDGE('',*,*,#142583,.T.); +#142823 = ORIENTED_EDGE('',*,*,#142308,.T.); +#142824 = ORIENTED_EDGE('',*,*,#142098,.T.); +#142825 = ORIENTED_EDGE('',*,*,#142826,.T.); +#142826 = EDGE_CURVE('',#142071,#142152,#142827,.T.); +#142827 = SURFACE_CURVE('',#142828,(#142832,#142839),.PCURVE_S1.); +#142828 = LINE('',#142829,#142830); +#142829 = CARTESIAN_POINT('',(7.15,11.,1.159810404338E-002)); +#142830 = VECTOR('',#142831,1.); +#142831 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#142832 = PCURVE('',#89548,#142833); +#142833 = DEFINITIONAL_REPRESENTATION('',(#142834),#142838); +#142834 = LINE('',#142835,#142836); +#142835 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#142836 = VECTOR('',#142837,1.); +#142837 = DIRECTION('',(1.,-2.101748079665E-016)); +#142838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142839 = PCURVE('',#142086,#142840); +#142840 = DEFINITIONAL_REPRESENTATION('',(#142841),#142845); +#142841 = LINE('',#142842,#142843); +#142842 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#142843 = VECTOR('',#142844,1.); +#142844 = DIRECTION('',(1.570395187386E-016,-1.)); +#142845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142846 = ORIENTED_EDGE('',*,*,#142149,.F.); +#142847 = ORIENTED_EDGE('',*,*,#142410,.F.); +#142848 = ORIENTED_EDGE('',*,*,#142486,.F.); +#142849 = ORIENTED_EDGE('',*,*,#142607,.F.); +#142850 = ORIENTED_EDGE('',*,*,#142851,.T.); +#142851 = EDGE_CURVE('',#142608,#89531,#142852,.T.); +#142852 = SURFACE_CURVE('',#142853,(#142857,#142864),.PCURVE_S1.); +#142853 = LINE('',#142854,#142855); +#142854 = CARTESIAN_POINT('',(7.15,10.527847992439,0.65)); +#142855 = VECTOR('',#142856,1.); +#142856 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#142857 = PCURVE('',#89548,#142858); +#142858 = DEFINITIONAL_REPRESENTATION('',(#142859),#142863); +#142859 = LINE('',#142860,#142861); +#142860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142861 = VECTOR('',#142862,1.); +#142862 = DIRECTION('',(-3.563627120235E-016,-1.)); +#142863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142864 = PCURVE('',#89576,#142865); +#142865 = DEFINITIONAL_REPRESENTATION('',(#142866),#142870); +#142866 = LINE('',#142867,#142868); +#142867 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142868 = VECTOR('',#142869,1.); +#142869 = DIRECTION('',(1.,2.164989446033E-063)); +#142870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142871 = ORIENTED_EDGE('',*,*,#89530,.T.); +#142872 = ADVANCED_FACE('',(#142873),#89630,.F.); +#142873 = FACE_BOUND('',#142874,.T.); +#142874 = EDGE_LOOP('',(#142875,#142876,#142877,#142878)); +#142875 = ORIENTED_EDGE('',*,*,#142778,.F.); +#142876 = ORIENTED_EDGE('',*,*,#142801,.T.); +#142877 = ORIENTED_EDGE('',*,*,#89616,.T.); +#142878 = ORIENTED_EDGE('',*,*,#142879,.F.); +#142879 = EDGE_CURVE('',#142682,#89589,#142880,.T.); +#142880 = SURFACE_CURVE('',#142881,(#142885,#142892),.PCURVE_S1.); +#142881 = LINE('',#142882,#142883); +#142882 = CARTESIAN_POINT('',(7.35,10.527847992439,0.75)); +#142883 = VECTOR('',#142884,1.); +#142884 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#142885 = PCURVE('',#89630,#142886); +#142886 = DEFINITIONAL_REPRESENTATION('',(#142887),#142891); +#142887 = LINE('',#142888,#142889); +#142888 = CARTESIAN_POINT('',(0.E+000,0.2)); +#142889 = VECTOR('',#142890,1.); +#142890 = DIRECTION('',(-1.,2.164989446033E-063)); +#142891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142892 = PCURVE('',#89604,#142893); +#142893 = DEFINITIONAL_REPRESENTATION('',(#142894),#142898); +#142894 = LINE('',#142895,#142896); +#142895 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#142896 = VECTOR('',#142897,1.); +#142897 = DIRECTION('',(3.563627120235E-016,-1.)); +#142898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142899 = ADVANCED_FACE('',(#142900),#89604,.F.); +#142900 = FACE_BOUND('',#142901,.T.); +#142901 = EDGE_LOOP('',(#142902,#142923,#142924,#142925,#142926,#142927, + #142948,#142949,#142950,#142951,#142952,#142953)); +#142902 = ORIENTED_EDGE('',*,*,#142903,.F.); +#142903 = EDGE_CURVE('',#142635,#89561,#142904,.T.); +#142904 = SURFACE_CURVE('',#142905,(#142909,#142916),.PCURVE_S1.); +#142905 = LINE('',#142906,#142907); +#142906 = CARTESIAN_POINT('',(7.35,10.527847992439,0.65)); +#142907 = VECTOR('',#142908,1.); +#142908 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#142909 = PCURVE('',#89604,#142910); +#142910 = DEFINITIONAL_REPRESENTATION('',(#142911),#142915); +#142911 = LINE('',#142912,#142913); +#142912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#142913 = VECTOR('',#142914,1.); +#142914 = DIRECTION('',(3.563627120235E-016,-1.)); +#142915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142916 = PCURVE('',#89576,#142917); +#142917 = DEFINITIONAL_REPRESENTATION('',(#142918),#142922); +#142918 = LINE('',#142919,#142920); +#142919 = CARTESIAN_POINT('',(0.E+000,0.2)); +#142920 = VECTOR('',#142921,1.); +#142921 = DIRECTION('',(1.,2.164989446033E-063)); +#142922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142923 = ORIENTED_EDGE('',*,*,#142656,.T.); +#142924 = ORIENTED_EDGE('',*,*,#142508,.T.); +#142925 = ORIENTED_EDGE('',*,*,#142333,.T.); +#142926 = ORIENTED_EDGE('',*,*,#142202,.T.); +#142927 = ORIENTED_EDGE('',*,*,#142928,.T.); +#142928 = EDGE_CURVE('',#142180,#142043,#142929,.T.); +#142929 = SURFACE_CURVE('',#142930,(#142934,#142941),.PCURVE_S1.); +#142930 = LINE('',#142931,#142932); +#142931 = CARTESIAN_POINT('',(7.35,11.,1.159810404338E-002)); +#142932 = VECTOR('',#142933,1.); +#142933 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#142934 = PCURVE('',#89604,#142935); +#142935 = DEFINITIONAL_REPRESENTATION('',(#142936),#142940); +#142936 = LINE('',#142937,#142938); +#142937 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#142938 = VECTOR('',#142939,1.); +#142939 = DIRECTION('',(1.,2.101748079665E-016)); +#142940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142941 = PCURVE('',#142086,#142942); +#142942 = DEFINITIONAL_REPRESENTATION('',(#142943),#142947); +#142943 = LINE('',#142944,#142945); +#142944 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#142945 = VECTOR('',#142946,1.); +#142946 = DIRECTION('',(-1.570395187386E-016,1.)); +#142947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142948 = ORIENTED_EDGE('',*,*,#142040,.F.); +#142949 = ORIENTED_EDGE('',*,*,#142254,.F.); +#142950 = ORIENTED_EDGE('',*,*,#142561,.F.); +#142951 = ORIENTED_EDGE('',*,*,#142681,.F.); +#142952 = ORIENTED_EDGE('',*,*,#142879,.T.); +#142953 = ORIENTED_EDGE('',*,*,#89588,.T.); +#142954 = ADVANCED_FACE('',(#142955),#89576,.F.); +#142955 = FACE_BOUND('',#142956,.T.); +#142956 = EDGE_LOOP('',(#142957,#142958,#142959,#142960)); +#142957 = ORIENTED_EDGE('',*,*,#142634,.F.); +#142958 = ORIENTED_EDGE('',*,*,#142903,.T.); +#142959 = ORIENTED_EDGE('',*,*,#89560,.T.); +#142960 = ORIENTED_EDGE('',*,*,#142851,.F.); +#142961 = ADVANCED_FACE('',(#142962),#142086,.T.); +#142962 = FACE_BOUND('',#142963,.T.); +#142963 = EDGE_LOOP('',(#142964,#142965,#142966,#142967)); +#142964 = ORIENTED_EDGE('',*,*,#142928,.F.); +#142965 = ORIENTED_EDGE('',*,*,#142179,.F.); +#142966 = ORIENTED_EDGE('',*,*,#142826,.F.); +#142967 = ORIENTED_EDGE('',*,*,#142070,.F.); +#142968 = ADVANCED_FACE('',(#142969),#142983,.T.); +#142969 = FACE_BOUND('',#142970,.T.); +#142970 = EDGE_LOOP('',(#142971,#143001,#143029,#143052)); +#142971 = ORIENTED_EDGE('',*,*,#142972,.T.); +#142972 = EDGE_CURVE('',#142973,#142975,#142977,.T.); +#142973 = VERTEX_POINT('',#142974); +#142974 = CARTESIAN_POINT('',(6.85,10.740726081328,-0.208196358798)); +#142975 = VERTEX_POINT('',#142976); +#142976 = CARTESIAN_POINT('',(6.85,11.,-0.208196358798)); +#142977 = SURFACE_CURVE('',#142978,(#142982,#142994),.PCURVE_S1.); +#142978 = LINE('',#142979,#142980); +#142979 = CARTESIAN_POINT('',(6.85,10.740726081328,-0.208196358798)); +#142980 = VECTOR('',#142981,1.); +#142981 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#142982 = PCURVE('',#142983,#142988); +#142983 = PLANE('',#142984); +#142984 = AXIS2_PLACEMENT_3D('',#142985,#142986,#142987); +#142985 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#140594 = DIRECTION('',(0.E+000,0.E+000,1.)); -#140595 = DIRECTION('',(1.,0.E+000,0.E+000)); -#140596 = DEFINITIONAL_REPRESENTATION('',(#140597),#140601); -#140597 = LINE('',#140598,#140599); -#140598 = CARTESIAN_POINT('',(6.85,-3.552713678801E-015)); -#140599 = VECTOR('',#140600,1.); -#140600 = DIRECTION('',(6.725593854929E-015,1.)); -#140601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#142986 = DIRECTION('',(0.E+000,0.E+000,1.)); +#142987 = DIRECTION('',(1.,0.E+000,0.E+000)); +#142988 = DEFINITIONAL_REPRESENTATION('',(#142989),#142993); +#142989 = LINE('',#142990,#142991); +#142990 = CARTESIAN_POINT('',(6.85,-3.552713678801E-015)); +#142991 = VECTOR('',#142992,1.); +#142992 = DIRECTION('',(6.725593854929E-015,1.)); +#142993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#142994 = PCURVE('',#90174,#142995); +#142995 = DEFINITIONAL_REPRESENTATION('',(#142996),#143000); +#142996 = LINE('',#142997,#142998); +#142997 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#142998 = VECTOR('',#142999,1.); +#142999 = DIRECTION('',(0.E+000,1.)); +#143000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143001 = ORIENTED_EDGE('',*,*,#143002,.T.); +#143002 = EDGE_CURVE('',#142975,#143003,#143005,.T.); +#143003 = VERTEX_POINT('',#143004); +#143004 = CARTESIAN_POINT('',(6.65,11.,-0.208196358798)); +#143005 = SURFACE_CURVE('',#143006,(#143010,#143017),.PCURVE_S1.); +#143006 = LINE('',#143007,#143008); +#143007 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#143008 = VECTOR('',#143009,1.); +#143009 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143010 = PCURVE('',#142983,#143011); +#143011 = DEFINITIONAL_REPRESENTATION('',(#143012),#143016); +#143012 = LINE('',#143013,#143014); +#143013 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#143014 = VECTOR('',#143015,1.); +#143015 = DIRECTION('',(-1.,8.881784197001E-016)); +#143016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143017 = PCURVE('',#143018,#143023); +#143018 = PLANE('',#143019); +#143019 = AXIS2_PLACEMENT_3D('',#143020,#143021,#143022); +#143020 = CARTESIAN_POINT('',(6.75,11.,-0.258196742327)); +#143021 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#143022 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#143023 = DEFINITIONAL_REPRESENTATION('',(#143024),#143028); +#143024 = LINE('',#143025,#143026); +#143025 = CARTESIAN_POINT('',(6.75,5.000038352949E-002)); +#143026 = VECTOR('',#143027,1.); +#143027 = DIRECTION('',(1.,1.1653254136E-048)); +#143028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143029 = ORIENTED_EDGE('',*,*,#143030,.F.); +#143030 = EDGE_CURVE('',#143031,#143003,#143033,.T.); +#143031 = VERTEX_POINT('',#143032); +#143032 = CARTESIAN_POINT('',(6.65,10.740726081328,-0.208196358798)); +#143033 = SURFACE_CURVE('',#143034,(#143038,#143045),.PCURVE_S1.); +#143034 = LINE('',#143035,#143036); +#143035 = CARTESIAN_POINT('',(6.65,10.740726081328,-0.208196358798)); +#143036 = VECTOR('',#143037,1.); +#143037 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#143038 = PCURVE('',#142983,#143039); +#143039 = DEFINITIONAL_REPRESENTATION('',(#143040),#143044); +#143040 = LINE('',#143041,#143042); +#143041 = CARTESIAN_POINT('',(6.65,-5.329070518201E-015)); +#143042 = VECTOR('',#143043,1.); +#143043 = DIRECTION('',(6.725593854929E-015,1.)); +#143044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143045 = PCURVE('',#90118,#143046); +#143046 = DEFINITIONAL_REPRESENTATION('',(#143047),#143051); +#143047 = LINE('',#143048,#143049); +#143048 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#143049 = VECTOR('',#143050,1.); +#143050 = DIRECTION('',(0.E+000,1.)); +#143051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140602 = PCURVE('',#87782,#140603); -#140603 = DEFINITIONAL_REPRESENTATION('',(#140604),#140608); -#140604 = LINE('',#140605,#140606); -#140605 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#140606 = VECTOR('',#140607,1.); -#140607 = DIRECTION('',(0.E+000,1.)); -#140608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140609 = ORIENTED_EDGE('',*,*,#140610,.T.); -#140610 = EDGE_CURVE('',#140583,#140611,#140613,.T.); -#140611 = VERTEX_POINT('',#140612); -#140612 = CARTESIAN_POINT('',(6.65,11.,-0.208196358798)); -#140613 = SURFACE_CURVE('',#140614,(#140618,#140625),.PCURVE_S1.); -#140614 = LINE('',#140615,#140616); -#140615 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#140616 = VECTOR('',#140617,1.); -#140617 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140618 = PCURVE('',#140591,#140619); -#140619 = DEFINITIONAL_REPRESENTATION('',(#140620),#140624); -#140620 = LINE('',#140621,#140622); -#140621 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#140622 = VECTOR('',#140623,1.); -#140623 = DIRECTION('',(-1.,8.881784197001E-016)); -#140624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140625 = PCURVE('',#140626,#140631); -#140626 = PLANE('',#140627); -#140627 = AXIS2_PLACEMENT_3D('',#140628,#140629,#140630); -#140628 = CARTESIAN_POINT('',(6.75,11.,-0.258196742327)); -#140629 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#140630 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#140631 = DEFINITIONAL_REPRESENTATION('',(#140632),#140636); -#140632 = LINE('',#140633,#140634); -#140633 = CARTESIAN_POINT('',(6.75,5.000038352949E-002)); -#140634 = VECTOR('',#140635,1.); -#140635 = DIRECTION('',(1.,1.1653254136E-048)); -#140636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140637 = ORIENTED_EDGE('',*,*,#140638,.F.); -#140638 = EDGE_CURVE('',#140639,#140611,#140641,.T.); -#140639 = VERTEX_POINT('',#140640); -#140640 = CARTESIAN_POINT('',(6.65,10.740726081328,-0.208196358798)); -#140641 = SURFACE_CURVE('',#140642,(#140646,#140653),.PCURVE_S1.); -#140642 = LINE('',#140643,#140644); -#140643 = CARTESIAN_POINT('',(6.65,10.740726081328,-0.208196358798)); -#140644 = VECTOR('',#140645,1.); -#140645 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#140646 = PCURVE('',#140591,#140647); -#140647 = DEFINITIONAL_REPRESENTATION('',(#140648),#140652); -#140648 = LINE('',#140649,#140650); -#140649 = CARTESIAN_POINT('',(6.65,-5.329070518201E-015)); -#140650 = VECTOR('',#140651,1.); -#140651 = DIRECTION('',(6.725593854929E-015,1.)); -#140652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140653 = PCURVE('',#87726,#140654); -#140654 = DEFINITIONAL_REPRESENTATION('',(#140655),#140659); -#140655 = LINE('',#140656,#140657); -#140656 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#140657 = VECTOR('',#140658,1.); -#140658 = DIRECTION('',(0.E+000,1.)); -#140659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140660 = ORIENTED_EDGE('',*,*,#140661,.T.); -#140661 = EDGE_CURVE('',#140639,#140581,#140662,.T.); -#140662 = SURFACE_CURVE('',#140663,(#140667,#140674),.PCURVE_S1.); -#140663 = LINE('',#140664,#140665); -#140664 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#143052 = ORIENTED_EDGE('',*,*,#143053,.T.); +#143053 = EDGE_CURVE('',#143031,#142973,#143054,.T.); +#143054 = SURFACE_CURVE('',#143055,(#143059,#143066),.PCURVE_S1.); +#143055 = LINE('',#143056,#143057); +#143056 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#140665 = VECTOR('',#140666,1.); -#140666 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140667 = PCURVE('',#140591,#140668); -#140668 = DEFINITIONAL_REPRESENTATION('',(#140669),#140673); -#140669 = LINE('',#140670,#140671); -#140670 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140671 = VECTOR('',#140672,1.); -#140672 = DIRECTION('',(1.,-8.881784197001E-016)); -#140673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140674 = PCURVE('',#140675,#140680); -#140675 = CYLINDRICAL_SURFACE('',#140676,0.208574704164); -#140676 = AXIS2_PLACEMENT_3D('',#140677,#140678,#140679); -#140677 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#143057 = VECTOR('',#143058,1.); +#143058 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143059 = PCURVE('',#142983,#143060); +#143060 = DEFINITIONAL_REPRESENTATION('',(#143061),#143065); +#143061 = LINE('',#143062,#143063); +#143062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143063 = VECTOR('',#143064,1.); +#143064 = DIRECTION('',(1.,-8.881784197001E-016)); +#143065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143066 = PCURVE('',#143067,#143072); +#143067 = CYLINDRICAL_SURFACE('',#143068,0.208574704164); +#143068 = AXIS2_PLACEMENT_3D('',#143069,#143070,#143071); +#143069 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#140678 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140679 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140680 = DEFINITIONAL_REPRESENTATION('',(#140681),#140684); -#140681 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140682,#140683), +#143070 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143071 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143072 = DEFINITIONAL_REPRESENTATION('',(#143073),#143076); +#143073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143074,#143075), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#140682 = CARTESIAN_POINT('',(4.772630242227,6.65)); -#140683 = CARTESIAN_POINT('',(4.772630242227,6.85)); -#140684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140685 = ADVANCED_FACE('',(#140686),#140700,.T.); -#140686 = FACE_BOUND('',#140687,.T.); -#140687 = EDGE_LOOP('',(#140688,#140718,#140741,#140764)); -#140688 = ORIENTED_EDGE('',*,*,#140689,.T.); -#140689 = EDGE_CURVE('',#140690,#140692,#140694,.T.); -#140690 = VERTEX_POINT('',#140691); -#140691 = CARTESIAN_POINT('',(6.65,10.74341632541,-0.308197125857)); -#140692 = VERTEX_POINT('',#140693); -#140693 = CARTESIAN_POINT('',(6.65,11.,-0.308197125857)); -#140694 = SURFACE_CURVE('',#140695,(#140699,#140711),.PCURVE_S1.); -#140695 = LINE('',#140696,#140697); -#140696 = CARTESIAN_POINT('',(6.65,10.74341632541,-0.308197125857)); -#140697 = VECTOR('',#140698,1.); -#140698 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#140699 = PCURVE('',#140700,#140705); -#140700 = PLANE('',#140701); -#140701 = AXIS2_PLACEMENT_3D('',#140702,#140703,#140704); -#140702 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#143074 = CARTESIAN_POINT('',(4.772630242227,6.65)); +#143075 = CARTESIAN_POINT('',(4.772630242227,6.85)); +#143076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143077 = ADVANCED_FACE('',(#143078),#143092,.T.); +#143078 = FACE_BOUND('',#143079,.T.); +#143079 = EDGE_LOOP('',(#143080,#143110,#143133,#143156)); +#143080 = ORIENTED_EDGE('',*,*,#143081,.T.); +#143081 = EDGE_CURVE('',#143082,#143084,#143086,.T.); +#143082 = VERTEX_POINT('',#143083); +#143083 = CARTESIAN_POINT('',(6.65,10.74341632541,-0.308197125857)); +#143084 = VERTEX_POINT('',#143085); +#143085 = CARTESIAN_POINT('',(6.65,11.,-0.308197125857)); +#143086 = SURFACE_CURVE('',#143087,(#143091,#143103),.PCURVE_S1.); +#143087 = LINE('',#143088,#143089); +#143088 = CARTESIAN_POINT('',(6.65,10.74341632541,-0.308197125857)); +#143089 = VECTOR('',#143090,1.); +#143090 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#143091 = PCURVE('',#143092,#143097); +#143092 = PLANE('',#143093); +#143093 = AXIS2_PLACEMENT_3D('',#143094,#143095,#143096); +#143094 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#140703 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#140704 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#140705 = DEFINITIONAL_REPRESENTATION('',(#140706),#140710); -#140706 = LINE('',#140707,#140708); -#140707 = CARTESIAN_POINT('',(-6.65,-5.329070518201E-015)); -#140708 = VECTOR('',#140709,1.); -#140709 = DIRECTION('',(-6.725593854929E-015,1.)); -#140710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140711 = PCURVE('',#87726,#140712); -#140712 = DEFINITIONAL_REPRESENTATION('',(#140713),#140717); -#140713 = LINE('',#140714,#140715); -#140714 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#140715 = VECTOR('',#140716,1.); -#140716 = DIRECTION('',(0.E+000,1.)); -#140717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140718 = ORIENTED_EDGE('',*,*,#140719,.T.); -#140719 = EDGE_CURVE('',#140692,#140720,#140722,.T.); -#140720 = VERTEX_POINT('',#140721); -#140721 = CARTESIAN_POINT('',(6.85,11.,-0.308197125857)); -#140722 = SURFACE_CURVE('',#140723,(#140727,#140734),.PCURVE_S1.); -#140723 = LINE('',#140724,#140725); -#140724 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#140725 = VECTOR('',#140726,1.); -#140726 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140727 = PCURVE('',#140700,#140728); -#140728 = DEFINITIONAL_REPRESENTATION('',(#140729),#140733); -#140729 = LINE('',#140730,#140731); -#140730 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#140731 = VECTOR('',#140732,1.); -#140732 = DIRECTION('',(-1.,-8.881784197001E-016)); -#140733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140734 = PCURVE('',#140626,#140735); -#140735 = DEFINITIONAL_REPRESENTATION('',(#140736),#140740); -#140736 = LINE('',#140737,#140738); -#140737 = CARTESIAN_POINT('',(6.75,-5.000038352949E-002)); -#140738 = VECTOR('',#140739,1.); -#140739 = DIRECTION('',(-1.,-1.1653254136E-048)); -#140740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140741 = ORIENTED_EDGE('',*,*,#140742,.F.); -#140742 = EDGE_CURVE('',#140743,#140720,#140745,.T.); -#140743 = VERTEX_POINT('',#140744); -#140744 = CARTESIAN_POINT('',(6.85,10.74341632541,-0.308197125857)); -#140745 = SURFACE_CURVE('',#140746,(#140750,#140757),.PCURVE_S1.); -#140746 = LINE('',#140747,#140748); -#140747 = CARTESIAN_POINT('',(6.85,10.74341632541,-0.308197125857)); -#140748 = VECTOR('',#140749,1.); -#140749 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#140750 = PCURVE('',#140700,#140751); -#140751 = DEFINITIONAL_REPRESENTATION('',(#140752),#140756); -#140752 = LINE('',#140753,#140754); -#140753 = CARTESIAN_POINT('',(-6.85,-5.329070518201E-015)); -#140754 = VECTOR('',#140755,1.); -#140755 = DIRECTION('',(-6.725593854929E-015,1.)); -#140756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140757 = PCURVE('',#87782,#140758); -#140758 = DEFINITIONAL_REPRESENTATION('',(#140759),#140763); -#140759 = LINE('',#140760,#140761); -#140760 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#140761 = VECTOR('',#140762,1.); -#140762 = DIRECTION('',(0.E+000,1.)); -#140763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140764 = ORIENTED_EDGE('',*,*,#140765,.T.); -#140765 = EDGE_CURVE('',#140743,#140690,#140766,.T.); -#140766 = SURFACE_CURVE('',#140767,(#140771,#140778),.PCURVE_S1.); -#140767 = LINE('',#140768,#140769); -#140768 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#143095 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#143096 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#143097 = DEFINITIONAL_REPRESENTATION('',(#143098),#143102); +#143098 = LINE('',#143099,#143100); +#143099 = CARTESIAN_POINT('',(-6.65,-5.329070518201E-015)); +#143100 = VECTOR('',#143101,1.); +#143101 = DIRECTION('',(-6.725593854929E-015,1.)); +#143102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143103 = PCURVE('',#90118,#143104); +#143104 = DEFINITIONAL_REPRESENTATION('',(#143105),#143109); +#143105 = LINE('',#143106,#143107); +#143106 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#143107 = VECTOR('',#143108,1.); +#143108 = DIRECTION('',(0.E+000,1.)); +#143109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143110 = ORIENTED_EDGE('',*,*,#143111,.T.); +#143111 = EDGE_CURVE('',#143084,#143112,#143114,.T.); +#143112 = VERTEX_POINT('',#143113); +#143113 = CARTESIAN_POINT('',(6.85,11.,-0.308197125857)); +#143114 = SURFACE_CURVE('',#143115,(#143119,#143126),.PCURVE_S1.); +#143115 = LINE('',#143116,#143117); +#143116 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#143117 = VECTOR('',#143118,1.); +#143118 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143119 = PCURVE('',#143092,#143120); +#143120 = DEFINITIONAL_REPRESENTATION('',(#143121),#143125); +#143121 = LINE('',#143122,#143123); +#143122 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#143123 = VECTOR('',#143124,1.); +#143124 = DIRECTION('',(-1.,-8.881784197001E-016)); +#143125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143126 = PCURVE('',#143018,#143127); +#143127 = DEFINITIONAL_REPRESENTATION('',(#143128),#143132); +#143128 = LINE('',#143129,#143130); +#143129 = CARTESIAN_POINT('',(6.75,-5.000038352949E-002)); +#143130 = VECTOR('',#143131,1.); +#143131 = DIRECTION('',(-1.,-1.1653254136E-048)); +#143132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143133 = ORIENTED_EDGE('',*,*,#143134,.F.); +#143134 = EDGE_CURVE('',#143135,#143112,#143137,.T.); +#143135 = VERTEX_POINT('',#143136); +#143136 = CARTESIAN_POINT('',(6.85,10.74341632541,-0.308197125857)); +#143137 = SURFACE_CURVE('',#143138,(#143142,#143149),.PCURVE_S1.); +#143138 = LINE('',#143139,#143140); +#143139 = CARTESIAN_POINT('',(6.85,10.74341632541,-0.308197125857)); +#143140 = VECTOR('',#143141,1.); +#143141 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#143142 = PCURVE('',#143092,#143143); +#143143 = DEFINITIONAL_REPRESENTATION('',(#143144),#143148); +#143144 = LINE('',#143145,#143146); +#143145 = CARTESIAN_POINT('',(-6.85,-5.329070518201E-015)); +#143146 = VECTOR('',#143147,1.); +#143147 = DIRECTION('',(-6.725593854929E-015,1.)); +#143148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143149 = PCURVE('',#90174,#143150); +#143150 = DEFINITIONAL_REPRESENTATION('',(#143151),#143155); +#143151 = LINE('',#143152,#143153); +#143152 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#143153 = VECTOR('',#143154,1.); +#143154 = DIRECTION('',(0.E+000,1.)); +#143155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143156 = ORIENTED_EDGE('',*,*,#143157,.T.); +#143157 = EDGE_CURVE('',#143135,#143082,#143158,.T.); +#143158 = SURFACE_CURVE('',#143159,(#143163,#143170),.PCURVE_S1.); +#143159 = LINE('',#143160,#143161); +#143160 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#140769 = VECTOR('',#140770,1.); -#140770 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140771 = PCURVE('',#140700,#140772); -#140772 = DEFINITIONAL_REPRESENTATION('',(#140773),#140777); -#140773 = LINE('',#140774,#140775); -#140774 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#140775 = VECTOR('',#140776,1.); -#140776 = DIRECTION('',(1.,8.881784197001E-016)); -#140777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#143161 = VECTOR('',#143162,1.); +#143162 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143163 = PCURVE('',#143092,#143164); +#143164 = DEFINITIONAL_REPRESENTATION('',(#143165),#143169); +#143165 = LINE('',#143166,#143167); +#143166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143167 = VECTOR('',#143168,1.); +#143168 = DIRECTION('',(1.,8.881784197001E-016)); +#143169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140778 = PCURVE('',#140779,#140784); -#140779 = CYLINDRICAL_SURFACE('',#140780,0.308574064194); -#140780 = AXIS2_PLACEMENT_3D('',#140781,#140782,#140783); -#140781 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#143170 = PCURVE('',#143171,#143176); +#143171 = CYLINDRICAL_SURFACE('',#143172,0.308574064194); +#143172 = AXIS2_PLACEMENT_3D('',#143173,#143174,#143175); +#143173 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#140782 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140783 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140784 = DEFINITIONAL_REPRESENTATION('',(#140785),#140788); -#140785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140786,#140787), +#143174 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143175 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143176 = DEFINITIONAL_REPRESENTATION('',(#143177),#143180); +#143177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143178,#143179), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#140786 = CARTESIAN_POINT('',(4.761821717947,6.85)); -#140787 = CARTESIAN_POINT('',(4.761821717947,6.65)); -#140788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140789 = ADVANCED_FACE('',(#140790),#140675,.F.); -#140790 = FACE_BOUND('',#140791,.F.); -#140791 = EDGE_LOOP('',(#140792,#140793,#140820,#140847)); -#140792 = ORIENTED_EDGE('',*,*,#140661,.T.); -#140793 = ORIENTED_EDGE('',*,*,#140794,.F.); -#140794 = EDGE_CURVE('',#140795,#140581,#140797,.T.); -#140795 = VERTEX_POINT('',#140796); -#140796 = CARTESIAN_POINT('',(6.85,10.51959417205,0.E+000)); -#140797 = SURFACE_CURVE('',#140798,(#140803,#140809),.PCURVE_S1.); -#140798 = CIRCLE('',#140799,0.208574704164); -#140799 = AXIS2_PLACEMENT_3D('',#140800,#140801,#140802); -#140800 = CARTESIAN_POINT('',(6.85,10.728168876214,2.640924866458E-017) - ); -#140801 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140802 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140803 = PCURVE('',#140675,#140804); -#140804 = DEFINITIONAL_REPRESENTATION('',(#140805),#140808); -#140805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140806,#140807), +#143178 = CARTESIAN_POINT('',(4.761821717947,6.85)); +#143179 = CARTESIAN_POINT('',(4.761821717947,6.65)); +#143180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143181 = ADVANCED_FACE('',(#143182),#143067,.F.); +#143182 = FACE_BOUND('',#143183,.F.); +#143183 = EDGE_LOOP('',(#143184,#143185,#143212,#143239)); +#143184 = ORIENTED_EDGE('',*,*,#143053,.T.); +#143185 = ORIENTED_EDGE('',*,*,#143186,.F.); +#143186 = EDGE_CURVE('',#143187,#142973,#143189,.T.); +#143187 = VERTEX_POINT('',#143188); +#143188 = CARTESIAN_POINT('',(6.85,10.51959417205,0.E+000)); +#143189 = SURFACE_CURVE('',#143190,(#143195,#143201),.PCURVE_S1.); +#143190 = CIRCLE('',#143191,0.208574704164); +#143191 = AXIS2_PLACEMENT_3D('',#143192,#143193,#143194); +#143192 = CARTESIAN_POINT('',(6.85,10.728168876214,2.640924866458E-017) + ); +#143193 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143194 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143195 = PCURVE('',#143067,#143196); +#143196 = DEFINITIONAL_REPRESENTATION('',(#143197),#143200); +#143197 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143198,#143199), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#140806 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#140807 = CARTESIAN_POINT('',(4.772630242227,6.85)); -#140808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#143198 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#143199 = CARTESIAN_POINT('',(4.772630242227,6.85)); +#143200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140809 = PCURVE('',#87782,#140810); -#140810 = DEFINITIONAL_REPRESENTATION('',(#140811),#140819); -#140811 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140812,#140813,#140814, - #140815,#140816,#140817,#140818),.UNSPECIFIED.,.T.,.F.) +#143201 = PCURVE('',#90174,#143202); +#143202 = DEFINITIONAL_REPRESENTATION('',(#143203),#143211); +#143203 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143204,#143205,#143206, + #143207,#143208,#143209,#143210),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#140812 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#140813 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#140814 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#140815 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#140816 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#140817 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#140818 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#140819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140820 = ORIENTED_EDGE('',*,*,#140821,.T.); -#140821 = EDGE_CURVE('',#140795,#140822,#140824,.T.); -#140822 = VERTEX_POINT('',#140823); -#140823 = CARTESIAN_POINT('',(6.65,10.51959417205,0.E+000)); -#140824 = SURFACE_CURVE('',#140825,(#140829,#140835),.PCURVE_S1.); -#140825 = LINE('',#140826,#140827); -#140826 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#143204 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#143205 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#143206 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#143207 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#143208 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#143209 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#143210 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#143211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143212 = ORIENTED_EDGE('',*,*,#143213,.T.); +#143213 = EDGE_CURVE('',#143187,#143214,#143216,.T.); +#143214 = VERTEX_POINT('',#143215); +#143215 = CARTESIAN_POINT('',(6.65,10.51959417205,0.E+000)); +#143216 = SURFACE_CURVE('',#143217,(#143221,#143227),.PCURVE_S1.); +#143217 = LINE('',#143218,#143219); +#143218 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#140827 = VECTOR('',#140828,1.); -#140828 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140829 = PCURVE('',#140675,#140830); -#140830 = DEFINITIONAL_REPRESENTATION('',(#140831),#140834); -#140831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140832,#140833), +#143219 = VECTOR('',#143220,1.); +#143220 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143221 = PCURVE('',#143067,#143222); +#143222 = DEFINITIONAL_REPRESENTATION('',(#143223),#143226); +#143223 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143224,#143225), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#140832 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#140833 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#140834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#143224 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#143225 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#143226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140835 = PCURVE('',#140836,#140841); -#140836 = PLANE('',#140837); -#140837 = AXIS2_PLACEMENT_3D('',#140838,#140839,#140840); -#140838 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#143227 = PCURVE('',#143228,#143233); +#143228 = PLANE('',#143229); +#143229 = AXIS2_PLACEMENT_3D('',#143230,#143231,#143232); +#143230 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#140839 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#140840 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140841 = DEFINITIONAL_REPRESENTATION('',(#140842),#140846); -#140842 = LINE('',#140843,#140844); -#140843 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#140844 = VECTOR('',#140845,1.); -#140845 = DIRECTION('',(-1.,0.E+000)); -#140846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140847 = ORIENTED_EDGE('',*,*,#140848,.T.); -#140848 = EDGE_CURVE('',#140822,#140639,#140849,.T.); -#140849 = SURFACE_CURVE('',#140850,(#140855,#140861),.PCURVE_S1.); -#140850 = CIRCLE('',#140851,0.208574704164); -#140851 = AXIS2_PLACEMENT_3D('',#140852,#140853,#140854); -#140852 = CARTESIAN_POINT('',(6.65,10.728168876214,2.640924866458E-017) - ); -#140853 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140854 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140855 = PCURVE('',#140675,#140856); -#140856 = DEFINITIONAL_REPRESENTATION('',(#140857),#140860); -#140857 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140858,#140859), +#143231 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143232 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143233 = DEFINITIONAL_REPRESENTATION('',(#143234),#143238); +#143234 = LINE('',#143235,#143236); +#143235 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#143236 = VECTOR('',#143237,1.); +#143237 = DIRECTION('',(-1.,0.E+000)); +#143238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143239 = ORIENTED_EDGE('',*,*,#143240,.T.); +#143240 = EDGE_CURVE('',#143214,#143031,#143241,.T.); +#143241 = SURFACE_CURVE('',#143242,(#143247,#143253),.PCURVE_S1.); +#143242 = CIRCLE('',#143243,0.208574704164); +#143243 = AXIS2_PLACEMENT_3D('',#143244,#143245,#143246); +#143244 = CARTESIAN_POINT('',(6.65,10.728168876214,2.640924866458E-017) + ); +#143245 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143246 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143247 = PCURVE('',#143067,#143248); +#143248 = DEFINITIONAL_REPRESENTATION('',(#143249),#143252); +#143249 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143250,#143251), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#140858 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#140859 = CARTESIAN_POINT('',(4.772630242227,6.65)); -#140860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140861 = PCURVE('',#87726,#140862); -#140862 = DEFINITIONAL_REPRESENTATION('',(#140863),#140867); -#140863 = CIRCLE('',#140864,0.208574704164); -#140864 = AXIS2_PLACEMENT_2D('',#140865,#140866); -#140865 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#140866 = DIRECTION('',(0.E+000,1.)); -#140867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140868 = ADVANCED_FACE('',(#140869),#140779,.T.); -#140869 = FACE_BOUND('',#140870,.T.); -#140870 = EDGE_LOOP('',(#140871,#140872,#140922,#140949)); -#140871 = ORIENTED_EDGE('',*,*,#140765,.F.); -#140872 = ORIENTED_EDGE('',*,*,#140873,.F.); -#140873 = EDGE_CURVE('',#140874,#140743,#140876,.T.); -#140874 = VERTEX_POINT('',#140875); -#140875 = CARTESIAN_POINT('',(6.85,10.419594812019,0.E+000)); -#140876 = SURFACE_CURVE('',#140877,(#140882,#140911),.PCURVE_S1.); -#140877 = CIRCLE('',#140878,0.308574064194); -#140878 = AXIS2_PLACEMENT_3D('',#140879,#140880,#140881); -#140879 = CARTESIAN_POINT('',(6.85,10.728168876214,2.640924866458E-017) - ); -#140880 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140881 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140882 = PCURVE('',#140779,#140883); -#140883 = DEFINITIONAL_REPRESENTATION('',(#140884),#140910); -#140884 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140885,#140886,#140887, - #140888,#140889,#140890,#140891,#140892,#140893,#140894,#140895, - #140896,#140897,#140898,#140899,#140900,#140901,#140902,#140903, - #140904,#140905,#140906,#140907,#140908,#140909),.UNSPECIFIED.,.F., +#143250 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#143251 = CARTESIAN_POINT('',(4.772630242227,6.65)); +#143252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143253 = PCURVE('',#90118,#143254); +#143254 = DEFINITIONAL_REPRESENTATION('',(#143255),#143259); +#143255 = CIRCLE('',#143256,0.208574704164); +#143256 = AXIS2_PLACEMENT_2D('',#143257,#143258); +#143257 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#143258 = DIRECTION('',(0.E+000,1.)); +#143259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143260 = ADVANCED_FACE('',(#143261),#143171,.T.); +#143261 = FACE_BOUND('',#143262,.T.); +#143262 = EDGE_LOOP('',(#143263,#143264,#143314,#143341)); +#143263 = ORIENTED_EDGE('',*,*,#143157,.F.); +#143264 = ORIENTED_EDGE('',*,*,#143265,.F.); +#143265 = EDGE_CURVE('',#143266,#143135,#143268,.T.); +#143266 = VERTEX_POINT('',#143267); +#143267 = CARTESIAN_POINT('',(6.85,10.419594812019,0.E+000)); +#143268 = SURFACE_CURVE('',#143269,(#143274,#143303),.PCURVE_S1.); +#143269 = CIRCLE('',#143270,0.308574064194); +#143270 = AXIS2_PLACEMENT_3D('',#143271,#143272,#143273); +#143271 = CARTESIAN_POINT('',(6.85,10.728168876214,2.640924866458E-017) + ); +#143272 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143273 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143274 = PCURVE('',#143171,#143275); +#143275 = DEFINITIONAL_REPRESENTATION('',(#143276),#143302); +#143276 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143277,#143278,#143279, + #143280,#143281,#143282,#143283,#143284,#143285,#143286,#143287, + #143288,#143289,#143290,#143291,#143292,#143293,#143294,#143295, + #143296,#143297,#143298,#143299,#143300,#143301),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -173667,102 +176669,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#140885 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#140886 = CARTESIAN_POINT('',(3.166141578807,6.85)); -#140887 = CARTESIAN_POINT('',(3.215239429242,6.85)); -#140888 = CARTESIAN_POINT('',(3.288886204895,6.85)); -#140889 = CARTESIAN_POINT('',(3.362532980548,6.85)); -#140890 = CARTESIAN_POINT('',(3.4361797562,6.85)); -#140891 = CARTESIAN_POINT('',(3.509826531853,6.85)); -#140892 = CARTESIAN_POINT('',(3.583473307505,6.85)); -#140893 = CARTESIAN_POINT('',(3.657120083158,6.85)); -#140894 = CARTESIAN_POINT('',(3.730766858811,6.85)); -#140895 = CARTESIAN_POINT('',(3.804413634463,6.85)); -#140896 = CARTESIAN_POINT('',(3.878060410116,6.85)); -#140897 = CARTESIAN_POINT('',(3.951707185768,6.85)); -#140898 = CARTESIAN_POINT('',(4.025353961421,6.85)); -#140899 = CARTESIAN_POINT('',(4.099000737074,6.85)); -#140900 = CARTESIAN_POINT('',(4.172647512726,6.85)); -#140901 = CARTESIAN_POINT('',(4.246294288379,6.85)); -#140902 = CARTESIAN_POINT('',(4.319941064031,6.85)); -#140903 = CARTESIAN_POINT('',(4.393587839684,6.85)); -#140904 = CARTESIAN_POINT('',(4.467234615337,6.85)); -#140905 = CARTESIAN_POINT('',(4.540881390989,6.85)); -#140906 = CARTESIAN_POINT('',(4.614528166642,6.85)); -#140907 = CARTESIAN_POINT('',(4.688174942294,6.85)); -#140908 = CARTESIAN_POINT('',(4.737272792729,6.85)); -#140909 = CARTESIAN_POINT('',(4.761821717947,6.85)); -#140910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140911 = PCURVE('',#87782,#140912); -#140912 = DEFINITIONAL_REPRESENTATION('',(#140913),#140921); -#140913 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#140914,#140915,#140916, - #140917,#140918,#140919,#140920),.UNSPECIFIED.,.T.,.F.) +#143277 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#143278 = CARTESIAN_POINT('',(3.166141578807,6.85)); +#143279 = CARTESIAN_POINT('',(3.215239429242,6.85)); +#143280 = CARTESIAN_POINT('',(3.288886204895,6.85)); +#143281 = CARTESIAN_POINT('',(3.362532980548,6.85)); +#143282 = CARTESIAN_POINT('',(3.4361797562,6.85)); +#143283 = CARTESIAN_POINT('',(3.509826531853,6.85)); +#143284 = CARTESIAN_POINT('',(3.583473307505,6.85)); +#143285 = CARTESIAN_POINT('',(3.657120083158,6.85)); +#143286 = CARTESIAN_POINT('',(3.730766858811,6.85)); +#143287 = CARTESIAN_POINT('',(3.804413634463,6.85)); +#143288 = CARTESIAN_POINT('',(3.878060410116,6.85)); +#143289 = CARTESIAN_POINT('',(3.951707185768,6.85)); +#143290 = CARTESIAN_POINT('',(4.025353961421,6.85)); +#143291 = CARTESIAN_POINT('',(4.099000737074,6.85)); +#143292 = CARTESIAN_POINT('',(4.172647512726,6.85)); +#143293 = CARTESIAN_POINT('',(4.246294288379,6.85)); +#143294 = CARTESIAN_POINT('',(4.319941064031,6.85)); +#143295 = CARTESIAN_POINT('',(4.393587839684,6.85)); +#143296 = CARTESIAN_POINT('',(4.467234615337,6.85)); +#143297 = CARTESIAN_POINT('',(4.540881390989,6.85)); +#143298 = CARTESIAN_POINT('',(4.614528166642,6.85)); +#143299 = CARTESIAN_POINT('',(4.688174942294,6.85)); +#143300 = CARTESIAN_POINT('',(4.737272792729,6.85)); +#143301 = CARTESIAN_POINT('',(4.761821717947,6.85)); +#143302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143303 = PCURVE('',#90174,#143304); +#143304 = DEFINITIONAL_REPRESENTATION('',(#143305),#143313); +#143305 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143306,#143307,#143308, + #143309,#143310,#143311,#143312),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#140914 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#140915 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#140916 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#140917 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#140918 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#140919 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#140920 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#140921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140922 = ORIENTED_EDGE('',*,*,#140923,.F.); -#140923 = EDGE_CURVE('',#140924,#140874,#140926,.T.); -#140924 = VERTEX_POINT('',#140925); -#140925 = CARTESIAN_POINT('',(6.65,10.419594812019,0.E+000)); -#140926 = SURFACE_CURVE('',#140927,(#140931,#140937),.PCURVE_S1.); -#140927 = LINE('',#140928,#140929); -#140928 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#143306 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#143307 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#143308 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#143309 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#143310 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#143311 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#143312 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#143313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143314 = ORIENTED_EDGE('',*,*,#143315,.F.); +#143315 = EDGE_CURVE('',#143316,#143266,#143318,.T.); +#143316 = VERTEX_POINT('',#143317); +#143317 = CARTESIAN_POINT('',(6.65,10.419594812019,0.E+000)); +#143318 = SURFACE_CURVE('',#143319,(#143323,#143329),.PCURVE_S1.); +#143319 = LINE('',#143320,#143321); +#143320 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#140929 = VECTOR('',#140930,1.); -#140930 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140931 = PCURVE('',#140779,#140932); -#140932 = DEFINITIONAL_REPRESENTATION('',(#140933),#140936); -#140933 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#140934,#140935), +#143321 = VECTOR('',#143322,1.); +#143322 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143323 = PCURVE('',#143171,#143324); +#143324 = DEFINITIONAL_REPRESENTATION('',(#143325),#143328); +#143325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143326,#143327), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#140934 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#140935 = CARTESIAN_POINT('',(3.14159265359,6.85)); -#140936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#143326 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#143327 = CARTESIAN_POINT('',(3.14159265359,6.85)); +#143328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#140937 = PCURVE('',#140938,#140943); -#140938 = PLANE('',#140939); -#140939 = AXIS2_PLACEMENT_3D('',#140940,#140941,#140942); -#140940 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#143329 = PCURVE('',#143330,#143335); +#143330 = PLANE('',#143331); +#143331 = AXIS2_PLACEMENT_3D('',#143332,#143333,#143334); +#143332 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#140941 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140942 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#140943 = DEFINITIONAL_REPRESENTATION('',(#140944),#140948); -#140944 = LINE('',#140945,#140946); -#140945 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#140946 = VECTOR('',#140947,1.); -#140947 = DIRECTION('',(-1.,0.E+000)); -#140948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140949 = ORIENTED_EDGE('',*,*,#140950,.T.); -#140950 = EDGE_CURVE('',#140924,#140690,#140951,.T.); -#140951 = SURFACE_CURVE('',#140952,(#140957,#140986),.PCURVE_S1.); -#140952 = CIRCLE('',#140953,0.308574064194); -#140953 = AXIS2_PLACEMENT_3D('',#140954,#140955,#140956); -#140954 = CARTESIAN_POINT('',(6.65,10.728168876214,2.640924866458E-017) - ); -#140955 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#140956 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#140957 = PCURVE('',#140779,#140958); -#140958 = DEFINITIONAL_REPRESENTATION('',(#140959),#140985); -#140959 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#140960,#140961,#140962, - #140963,#140964,#140965,#140966,#140967,#140968,#140969,#140970, - #140971,#140972,#140973,#140974,#140975,#140976,#140977,#140978, - #140979,#140980,#140981,#140982,#140983,#140984),.UNSPECIFIED.,.F., +#143333 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143334 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143335 = DEFINITIONAL_REPRESENTATION('',(#143336),#143340); +#143336 = LINE('',#143337,#143338); +#143337 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#143338 = VECTOR('',#143339,1.); +#143339 = DIRECTION('',(-1.,0.E+000)); +#143340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143341 = ORIENTED_EDGE('',*,*,#143342,.T.); +#143342 = EDGE_CURVE('',#143316,#143082,#143343,.T.); +#143343 = SURFACE_CURVE('',#143344,(#143349,#143378),.PCURVE_S1.); +#143344 = CIRCLE('',#143345,0.308574064194); +#143345 = AXIS2_PLACEMENT_3D('',#143346,#143347,#143348); +#143346 = CARTESIAN_POINT('',(6.65,10.728168876214,2.640924866458E-017) + ); +#143347 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143348 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#143349 = PCURVE('',#143171,#143350); +#143350 = DEFINITIONAL_REPRESENTATION('',(#143351),#143377); +#143351 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143352,#143353,#143354, + #143355,#143356,#143357,#143358,#143359,#143360,#143361,#143362, + #143363,#143364,#143365,#143366,#143367,#143368,#143369,#143370, + #143371,#143372,#143373,#143374,#143375,#143376),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -173770,339 +176772,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#140960 = CARTESIAN_POINT('',(3.14159265359,6.65)); -#140961 = CARTESIAN_POINT('',(3.166141578807,6.65)); -#140962 = CARTESIAN_POINT('',(3.215239429242,6.65)); -#140963 = CARTESIAN_POINT('',(3.288886204895,6.65)); -#140964 = CARTESIAN_POINT('',(3.362532980548,6.65)); -#140965 = CARTESIAN_POINT('',(3.4361797562,6.65)); -#140966 = CARTESIAN_POINT('',(3.509826531853,6.65)); -#140967 = CARTESIAN_POINT('',(3.583473307505,6.65)); -#140968 = CARTESIAN_POINT('',(3.657120083158,6.65)); -#140969 = CARTESIAN_POINT('',(3.730766858811,6.65)); -#140970 = CARTESIAN_POINT('',(3.804413634463,6.65)); -#140971 = CARTESIAN_POINT('',(3.878060410116,6.65)); -#140972 = CARTESIAN_POINT('',(3.951707185768,6.65)); -#140973 = CARTESIAN_POINT('',(4.025353961421,6.65)); -#140974 = CARTESIAN_POINT('',(4.099000737074,6.65)); -#140975 = CARTESIAN_POINT('',(4.172647512726,6.65)); -#140976 = CARTESIAN_POINT('',(4.246294288379,6.65)); -#140977 = CARTESIAN_POINT('',(4.319941064031,6.65)); -#140978 = CARTESIAN_POINT('',(4.393587839684,6.65)); -#140979 = CARTESIAN_POINT('',(4.467234615337,6.65)); -#140980 = CARTESIAN_POINT('',(4.540881390989,6.65)); -#140981 = CARTESIAN_POINT('',(4.614528166642,6.65)); -#140982 = CARTESIAN_POINT('',(4.688174942294,6.65)); -#140983 = CARTESIAN_POINT('',(4.737272792729,6.65)); -#140984 = CARTESIAN_POINT('',(4.761821717947,6.65)); -#140985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140986 = PCURVE('',#87726,#140987); -#140987 = DEFINITIONAL_REPRESENTATION('',(#140988),#140992); -#140988 = CIRCLE('',#140989,0.308574064194); -#140989 = AXIS2_PLACEMENT_2D('',#140990,#140991); -#140990 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#140991 = DIRECTION('',(0.E+000,1.)); -#140992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#140993 = ADVANCED_FACE('',(#140994),#140938,.F.); -#140994 = FACE_BOUND('',#140995,.T.); -#140995 = EDGE_LOOP('',(#140996,#141025,#141046,#141047)); -#140996 = ORIENTED_EDGE('',*,*,#140997,.F.); -#140997 = EDGE_CURVE('',#140998,#141000,#141002,.T.); -#140998 = VERTEX_POINT('',#140999); -#140999 = CARTESIAN_POINT('',(6.65,10.419594812019,0.530776333563)); -#141000 = VERTEX_POINT('',#141001); -#141001 = CARTESIAN_POINT('',(6.85,10.419594812019,0.530776333563)); -#141002 = SURFACE_CURVE('',#141003,(#141007,#141014),.PCURVE_S1.); -#141003 = LINE('',#141004,#141005); -#141004 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#143352 = CARTESIAN_POINT('',(3.14159265359,6.65)); +#143353 = CARTESIAN_POINT('',(3.166141578807,6.65)); +#143354 = CARTESIAN_POINT('',(3.215239429242,6.65)); +#143355 = CARTESIAN_POINT('',(3.288886204895,6.65)); +#143356 = CARTESIAN_POINT('',(3.362532980548,6.65)); +#143357 = CARTESIAN_POINT('',(3.4361797562,6.65)); +#143358 = CARTESIAN_POINT('',(3.509826531853,6.65)); +#143359 = CARTESIAN_POINT('',(3.583473307505,6.65)); +#143360 = CARTESIAN_POINT('',(3.657120083158,6.65)); +#143361 = CARTESIAN_POINT('',(3.730766858811,6.65)); +#143362 = CARTESIAN_POINT('',(3.804413634463,6.65)); +#143363 = CARTESIAN_POINT('',(3.878060410116,6.65)); +#143364 = CARTESIAN_POINT('',(3.951707185768,6.65)); +#143365 = CARTESIAN_POINT('',(4.025353961421,6.65)); +#143366 = CARTESIAN_POINT('',(4.099000737074,6.65)); +#143367 = CARTESIAN_POINT('',(4.172647512726,6.65)); +#143368 = CARTESIAN_POINT('',(4.246294288379,6.65)); +#143369 = CARTESIAN_POINT('',(4.319941064031,6.65)); +#143370 = CARTESIAN_POINT('',(4.393587839684,6.65)); +#143371 = CARTESIAN_POINT('',(4.467234615337,6.65)); +#143372 = CARTESIAN_POINT('',(4.540881390989,6.65)); +#143373 = CARTESIAN_POINT('',(4.614528166642,6.65)); +#143374 = CARTESIAN_POINT('',(4.688174942294,6.65)); +#143375 = CARTESIAN_POINT('',(4.737272792729,6.65)); +#143376 = CARTESIAN_POINT('',(4.761821717947,6.65)); +#143377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143378 = PCURVE('',#90118,#143379); +#143379 = DEFINITIONAL_REPRESENTATION('',(#143380),#143384); +#143380 = CIRCLE('',#143381,0.308574064194); +#143381 = AXIS2_PLACEMENT_2D('',#143382,#143383); +#143382 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#143383 = DIRECTION('',(0.E+000,1.)); +#143384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143385 = ADVANCED_FACE('',(#143386),#143330,.F.); +#143386 = FACE_BOUND('',#143387,.T.); +#143387 = EDGE_LOOP('',(#143388,#143417,#143438,#143439)); +#143388 = ORIENTED_EDGE('',*,*,#143389,.F.); +#143389 = EDGE_CURVE('',#143390,#143392,#143394,.T.); +#143390 = VERTEX_POINT('',#143391); +#143391 = CARTESIAN_POINT('',(6.65,10.419594812019,0.530776333563)); +#143392 = VERTEX_POINT('',#143393); +#143393 = CARTESIAN_POINT('',(6.85,10.419594812019,0.530776333563)); +#143394 = SURFACE_CURVE('',#143395,(#143399,#143406),.PCURVE_S1.); +#143395 = LINE('',#143396,#143397); +#143396 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#141005 = VECTOR('',#141006,1.); -#141006 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141007 = PCURVE('',#140938,#141008); -#141008 = DEFINITIONAL_REPRESENTATION('',(#141009),#141013); -#141009 = LINE('',#141010,#141011); -#141010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141011 = VECTOR('',#141012,1.); -#141012 = DIRECTION('',(-1.,0.E+000)); -#141013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141014 = PCURVE('',#141015,#141020); -#141015 = CYLINDRICAL_SURFACE('',#141016,0.119270391569); -#141016 = AXIS2_PLACEMENT_3D('',#141017,#141018,#141019); -#141017 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#143397 = VECTOR('',#143398,1.); +#143398 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143399 = PCURVE('',#143330,#143400); +#143400 = DEFINITIONAL_REPRESENTATION('',(#143401),#143405); +#143401 = LINE('',#143402,#143403); +#143402 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143403 = VECTOR('',#143404,1.); +#143404 = DIRECTION('',(-1.,0.E+000)); +#143405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143406 = PCURVE('',#143407,#143412); +#143407 = CYLINDRICAL_SURFACE('',#143408,0.119270391569); +#143408 = AXIS2_PLACEMENT_3D('',#143409,#143410,#143411); +#143409 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#141018 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141019 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141020 = DEFINITIONAL_REPRESENTATION('',(#141021),#141024); -#141021 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141022,#141023), +#143410 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143411 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143412 = DEFINITIONAL_REPRESENTATION('',(#143413),#143416); +#143413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143414,#143415), .UNSPECIFIED.,.F.,.F.,(2,2),(6.65,6.85),.PIECEWISE_BEZIER_KNOTS.); -#141022 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#141023 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#141024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141025 = ORIENTED_EDGE('',*,*,#141026,.T.); -#141026 = EDGE_CURVE('',#140998,#140924,#141027,.T.); -#141027 = SURFACE_CURVE('',#141028,(#141032,#141039),.PCURVE_S1.); -#141028 = LINE('',#141029,#141030); -#141029 = CARTESIAN_POINT('',(6.65,10.419594812019,0.530776333563)); -#141030 = VECTOR('',#141031,1.); -#141031 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141032 = PCURVE('',#140938,#141033); -#141033 = DEFINITIONAL_REPRESENTATION('',(#141034),#141038); -#141034 = LINE('',#141035,#141036); -#141035 = CARTESIAN_POINT('',(-6.65,0.E+000)); -#141036 = VECTOR('',#141037,1.); -#141037 = DIRECTION('',(0.E+000,-1.)); -#141038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141039 = PCURVE('',#87726,#141040); -#141040 = DEFINITIONAL_REPRESENTATION('',(#141041),#141045); -#141041 = LINE('',#141042,#141043); -#141042 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#141043 = VECTOR('',#141044,1.); -#141044 = DIRECTION('',(1.,0.E+000)); -#141045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141046 = ORIENTED_EDGE('',*,*,#140923,.T.); -#141047 = ORIENTED_EDGE('',*,*,#141048,.F.); -#141048 = EDGE_CURVE('',#141000,#140874,#141049,.T.); -#141049 = SURFACE_CURVE('',#141050,(#141054,#141061),.PCURVE_S1.); -#141050 = LINE('',#141051,#141052); -#141051 = CARTESIAN_POINT('',(6.85,10.419594812019,0.530776333563)); -#141052 = VECTOR('',#141053,1.); -#141053 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141054 = PCURVE('',#140938,#141055); -#141055 = DEFINITIONAL_REPRESENTATION('',(#141056),#141060); -#141056 = LINE('',#141057,#141058); -#141057 = CARTESIAN_POINT('',(-6.85,0.E+000)); -#141058 = VECTOR('',#141059,1.); -#141059 = DIRECTION('',(0.E+000,-1.)); -#141060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141061 = PCURVE('',#87782,#141062); -#141062 = DEFINITIONAL_REPRESENTATION('',(#141063),#141067); -#141063 = LINE('',#141064,#141065); -#141064 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#141065 = VECTOR('',#141066,1.); -#141066 = DIRECTION('',(-1.,0.E+000)); -#141067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141068 = ADVANCED_FACE('',(#141069),#140836,.F.); -#141069 = FACE_BOUND('',#141070,.T.); -#141070 = EDGE_LOOP('',(#141071,#141100,#141121,#141122)); -#141071 = ORIENTED_EDGE('',*,*,#141072,.F.); -#141072 = EDGE_CURVE('',#141073,#141075,#141077,.T.); -#141073 = VERTEX_POINT('',#141074); -#141074 = CARTESIAN_POINT('',(6.85,10.51959417205,0.530776333563)); -#141075 = VERTEX_POINT('',#141076); -#141076 = CARTESIAN_POINT('',(6.65,10.51959417205,0.530776333563)); -#141077 = SURFACE_CURVE('',#141078,(#141082,#141089),.PCURVE_S1.); -#141078 = LINE('',#141079,#141080); -#141079 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#143414 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#143415 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#143416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143417 = ORIENTED_EDGE('',*,*,#143418,.T.); +#143418 = EDGE_CURVE('',#143390,#143316,#143419,.T.); +#143419 = SURFACE_CURVE('',#143420,(#143424,#143431),.PCURVE_S1.); +#143420 = LINE('',#143421,#143422); +#143421 = CARTESIAN_POINT('',(6.65,10.419594812019,0.530776333563)); +#143422 = VECTOR('',#143423,1.); +#143423 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#143424 = PCURVE('',#143330,#143425); +#143425 = DEFINITIONAL_REPRESENTATION('',(#143426),#143430); +#143426 = LINE('',#143427,#143428); +#143427 = CARTESIAN_POINT('',(-6.65,0.E+000)); +#143428 = VECTOR('',#143429,1.); +#143429 = DIRECTION('',(0.E+000,-1.)); +#143430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143431 = PCURVE('',#90118,#143432); +#143432 = DEFINITIONAL_REPRESENTATION('',(#143433),#143437); +#143433 = LINE('',#143434,#143435); +#143434 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#143435 = VECTOR('',#143436,1.); +#143436 = DIRECTION('',(1.,0.E+000)); +#143437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143438 = ORIENTED_EDGE('',*,*,#143315,.T.); +#143439 = ORIENTED_EDGE('',*,*,#143440,.F.); +#143440 = EDGE_CURVE('',#143392,#143266,#143441,.T.); +#143441 = SURFACE_CURVE('',#143442,(#143446,#143453),.PCURVE_S1.); +#143442 = LINE('',#143443,#143444); +#143443 = CARTESIAN_POINT('',(6.85,10.419594812019,0.530776333563)); +#143444 = VECTOR('',#143445,1.); +#143445 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#143446 = PCURVE('',#143330,#143447); +#143447 = DEFINITIONAL_REPRESENTATION('',(#143448),#143452); +#143448 = LINE('',#143449,#143450); +#143449 = CARTESIAN_POINT('',(-6.85,0.E+000)); +#143450 = VECTOR('',#143451,1.); +#143451 = DIRECTION('',(0.E+000,-1.)); +#143452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143453 = PCURVE('',#90174,#143454); +#143454 = DEFINITIONAL_REPRESENTATION('',(#143455),#143459); +#143455 = LINE('',#143456,#143457); +#143456 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#143457 = VECTOR('',#143458,1.); +#143458 = DIRECTION('',(-1.,0.E+000)); +#143459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143460 = ADVANCED_FACE('',(#143461),#143228,.F.); +#143461 = FACE_BOUND('',#143462,.T.); +#143462 = EDGE_LOOP('',(#143463,#143492,#143513,#143514)); +#143463 = ORIENTED_EDGE('',*,*,#143464,.F.); +#143464 = EDGE_CURVE('',#143465,#143467,#143469,.T.); +#143465 = VERTEX_POINT('',#143466); +#143466 = CARTESIAN_POINT('',(6.85,10.51959417205,0.530776333563)); +#143467 = VERTEX_POINT('',#143468); +#143468 = CARTESIAN_POINT('',(6.65,10.51959417205,0.530776333563)); +#143469 = SURFACE_CURVE('',#143470,(#143474,#143481),.PCURVE_S1.); +#143470 = LINE('',#143471,#143472); +#143471 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#141080 = VECTOR('',#141081,1.); -#141081 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141082 = PCURVE('',#140836,#141083); -#141083 = DEFINITIONAL_REPRESENTATION('',(#141084),#141088); -#141084 = LINE('',#141085,#141086); -#141085 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141086 = VECTOR('',#141087,1.); -#141087 = DIRECTION('',(-1.,0.E+000)); -#141088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141089 = PCURVE('',#141090,#141095); -#141090 = CYLINDRICAL_SURFACE('',#141091,0.2192697516); -#141091 = AXIS2_PLACEMENT_3D('',#141092,#141093,#141094); -#141092 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#143472 = VECTOR('',#143473,1.); +#143473 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143474 = PCURVE('',#143228,#143475); +#143475 = DEFINITIONAL_REPRESENTATION('',(#143476),#143480); +#143476 = LINE('',#143477,#143478); +#143477 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143478 = VECTOR('',#143479,1.); +#143479 = DIRECTION('',(-1.,0.E+000)); +#143480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143481 = PCURVE('',#143482,#143487); +#143482 = CYLINDRICAL_SURFACE('',#143483,0.2192697516); +#143483 = AXIS2_PLACEMENT_3D('',#143484,#143485,#143486); +#143484 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#141093 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141094 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141095 = DEFINITIONAL_REPRESENTATION('',(#141096),#141099); -#141096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141097,#141098), +#143485 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143486 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143487 = DEFINITIONAL_REPRESENTATION('',(#143488),#143491); +#143488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143489,#143490), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.85,-6.65),.PIECEWISE_BEZIER_KNOTS.); -#141097 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#141098 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#141099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141100 = ORIENTED_EDGE('',*,*,#141101,.T.); -#141101 = EDGE_CURVE('',#141073,#140795,#141102,.T.); -#141102 = SURFACE_CURVE('',#141103,(#141107,#141114),.PCURVE_S1.); -#141103 = LINE('',#141104,#141105); -#141104 = CARTESIAN_POINT('',(6.85,10.51959417205,0.530776333563)); -#141105 = VECTOR('',#141106,1.); -#141106 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141107 = PCURVE('',#140836,#141108); -#141108 = DEFINITIONAL_REPRESENTATION('',(#141109),#141113); -#141109 = LINE('',#141110,#141111); -#141110 = CARTESIAN_POINT('',(6.85,0.E+000)); -#141111 = VECTOR('',#141112,1.); -#141112 = DIRECTION('',(0.E+000,-1.)); -#141113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141114 = PCURVE('',#87782,#141115); -#141115 = DEFINITIONAL_REPRESENTATION('',(#141116),#141120); -#141116 = LINE('',#141117,#141118); -#141117 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); -#141118 = VECTOR('',#141119,1.); -#141119 = DIRECTION('',(-1.,0.E+000)); -#141120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141121 = ORIENTED_EDGE('',*,*,#140821,.T.); -#141122 = ORIENTED_EDGE('',*,*,#141123,.F.); -#141123 = EDGE_CURVE('',#141075,#140822,#141124,.T.); -#141124 = SURFACE_CURVE('',#141125,(#141129,#141136),.PCURVE_S1.); -#141125 = LINE('',#141126,#141127); -#141126 = CARTESIAN_POINT('',(6.65,10.51959417205,0.530776333563)); -#141127 = VECTOR('',#141128,1.); -#141128 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141129 = PCURVE('',#140836,#141130); -#141130 = DEFINITIONAL_REPRESENTATION('',(#141131),#141135); -#141131 = LINE('',#141132,#141133); -#141132 = CARTESIAN_POINT('',(6.65,0.E+000)); -#141133 = VECTOR('',#141134,1.); -#141134 = DIRECTION('',(0.E+000,-1.)); -#141135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141136 = PCURVE('',#87726,#141137); -#141137 = DEFINITIONAL_REPRESENTATION('',(#141138),#141142); -#141138 = LINE('',#141139,#141140); -#141139 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#141140 = VECTOR('',#141141,1.); -#141141 = DIRECTION('',(1.,0.E+000)); -#141142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141143 = ADVANCED_FACE('',(#141144),#141015,.F.); -#141144 = FACE_BOUND('',#141145,.F.); -#141145 = EDGE_LOOP('',(#141146,#141173,#141195,#141216)); -#141146 = ORIENTED_EDGE('',*,*,#141147,.F.); -#141147 = EDGE_CURVE('',#141148,#140998,#141150,.T.); -#141148 = VERTEX_POINT('',#141149); -#141149 = CARTESIAN_POINT('',(6.65,10.303662633502,0.65)); -#141150 = SURFACE_CURVE('',#141151,(#141156,#141162),.PCURVE_S1.); -#141151 = CIRCLE('',#141152,0.119270391569); -#141152 = AXIS2_PLACEMENT_3D('',#141153,#141154,#141155); -#141153 = CARTESIAN_POINT('',(6.65,10.30032442045,0.530776333563)); -#141154 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141155 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141156 = PCURVE('',#141015,#141157); -#141157 = DEFINITIONAL_REPRESENTATION('',(#141158),#141161); -#141158 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141159,#141160), +#143489 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#143490 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#143491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143492 = ORIENTED_EDGE('',*,*,#143493,.T.); +#143493 = EDGE_CURVE('',#143465,#143187,#143494,.T.); +#143494 = SURFACE_CURVE('',#143495,(#143499,#143506),.PCURVE_S1.); +#143495 = LINE('',#143496,#143497); +#143496 = CARTESIAN_POINT('',(6.85,10.51959417205,0.530776333563)); +#143497 = VECTOR('',#143498,1.); +#143498 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#143499 = PCURVE('',#143228,#143500); +#143500 = DEFINITIONAL_REPRESENTATION('',(#143501),#143505); +#143501 = LINE('',#143502,#143503); +#143502 = CARTESIAN_POINT('',(6.85,0.E+000)); +#143503 = VECTOR('',#143504,1.); +#143504 = DIRECTION('',(0.E+000,-1.)); +#143505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143506 = PCURVE('',#90174,#143507); +#143507 = DEFINITIONAL_REPRESENTATION('',(#143508),#143512); +#143508 = LINE('',#143509,#143510); +#143509 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); +#143510 = VECTOR('',#143511,1.); +#143511 = DIRECTION('',(-1.,0.E+000)); +#143512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143513 = ORIENTED_EDGE('',*,*,#143213,.T.); +#143514 = ORIENTED_EDGE('',*,*,#143515,.F.); +#143515 = EDGE_CURVE('',#143467,#143214,#143516,.T.); +#143516 = SURFACE_CURVE('',#143517,(#143521,#143528),.PCURVE_S1.); +#143517 = LINE('',#143518,#143519); +#143518 = CARTESIAN_POINT('',(6.65,10.51959417205,0.530776333563)); +#143519 = VECTOR('',#143520,1.); +#143520 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#143521 = PCURVE('',#143228,#143522); +#143522 = DEFINITIONAL_REPRESENTATION('',(#143523),#143527); +#143523 = LINE('',#143524,#143525); +#143524 = CARTESIAN_POINT('',(6.65,0.E+000)); +#143525 = VECTOR('',#143526,1.); +#143526 = DIRECTION('',(0.E+000,-1.)); +#143527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143528 = PCURVE('',#90118,#143529); +#143529 = DEFINITIONAL_REPRESENTATION('',(#143530),#143534); +#143530 = LINE('',#143531,#143532); +#143531 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#143532 = VECTOR('',#143533,1.); +#143533 = DIRECTION('',(1.,0.E+000)); +#143534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143535 = ADVANCED_FACE('',(#143536),#143407,.F.); +#143536 = FACE_BOUND('',#143537,.F.); +#143537 = EDGE_LOOP('',(#143538,#143565,#143587,#143608)); +#143538 = ORIENTED_EDGE('',*,*,#143539,.F.); +#143539 = EDGE_CURVE('',#143540,#143390,#143542,.T.); +#143540 = VERTEX_POINT('',#143541); +#143541 = CARTESIAN_POINT('',(6.65,10.303662633502,0.65)); +#143542 = SURFACE_CURVE('',#143543,(#143548,#143554),.PCURVE_S1.); +#143543 = CIRCLE('',#143544,0.119270391569); +#143544 = AXIS2_PLACEMENT_3D('',#143545,#143546,#143547); +#143545 = CARTESIAN_POINT('',(6.65,10.30032442045,0.530776333563)); +#143546 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143547 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143548 = PCURVE('',#143407,#143549); +#143549 = DEFINITIONAL_REPRESENTATION('',(#143550),#143553); +#143550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143551,#143552), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#141159 = CARTESIAN_POINT('',(1.598788597134,-6.65)); -#141160 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#141161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#143551 = CARTESIAN_POINT('',(1.598788597134,-6.65)); +#143552 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#143553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#141162 = PCURVE('',#87726,#141163); -#141163 = DEFINITIONAL_REPRESENTATION('',(#141164),#141172); -#141164 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141165,#141166,#141167, - #141168,#141169,#141170,#141171),.UNSPECIFIED.,.T.,.F.) +#143554 = PCURVE('',#90118,#143555); +#143555 = DEFINITIONAL_REPRESENTATION('',(#143556),#143564); +#143556 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143557,#143558,#143559, + #143560,#143561,#143562,#143563),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#141165 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#141166 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#141167 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#141168 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#141169 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#141170 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#141171 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#141172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141173 = ORIENTED_EDGE('',*,*,#141174,.F.); -#141174 = EDGE_CURVE('',#141175,#141148,#141177,.T.); -#141175 = VERTEX_POINT('',#141176); -#141176 = CARTESIAN_POINT('',(6.85,10.303662633502,0.65)); -#141177 = SURFACE_CURVE('',#141178,(#141182,#141188),.PCURVE_S1.); -#141178 = LINE('',#141179,#141180); -#141179 = CARTESIAN_POINT('',(6.65,10.303662633502,0.65)); -#141180 = VECTOR('',#141181,1.); -#141181 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141182 = PCURVE('',#141015,#141183); -#141183 = DEFINITIONAL_REPRESENTATION('',(#141184),#141187); -#141184 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141185,#141186), +#143557 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#143558 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#143559 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#143560 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#143561 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#143562 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#143563 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#143564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143565 = ORIENTED_EDGE('',*,*,#143566,.F.); +#143566 = EDGE_CURVE('',#143567,#143540,#143569,.T.); +#143567 = VERTEX_POINT('',#143568); +#143568 = CARTESIAN_POINT('',(6.85,10.303662633502,0.65)); +#143569 = SURFACE_CURVE('',#143570,(#143574,#143580),.PCURVE_S1.); +#143570 = LINE('',#143571,#143572); +#143571 = CARTESIAN_POINT('',(6.65,10.303662633502,0.65)); +#143572 = VECTOR('',#143573,1.); +#143573 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143574 = PCURVE('',#143407,#143575); +#143575 = DEFINITIONAL_REPRESENTATION('',(#143576),#143579); +#143576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143577,#143578), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#141185 = CARTESIAN_POINT('',(1.598788597134,-6.85)); -#141186 = CARTESIAN_POINT('',(1.598788597134,-6.65)); -#141187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141188 = PCURVE('',#87754,#141189); -#141189 = DEFINITIONAL_REPRESENTATION('',(#141190),#141194); -#141190 = LINE('',#141191,#141192); -#141191 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#141192 = VECTOR('',#141193,1.); -#141193 = DIRECTION('',(-8.881784197001E-016,-1.)); -#141194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141195 = ORIENTED_EDGE('',*,*,#141196,.T.); -#141196 = EDGE_CURVE('',#141175,#141000,#141197,.T.); -#141197 = SURFACE_CURVE('',#141198,(#141203,#141209),.PCURVE_S1.); -#141198 = CIRCLE('',#141199,0.119270391569); -#141199 = AXIS2_PLACEMENT_3D('',#141200,#141201,#141202); -#141200 = CARTESIAN_POINT('',(6.85,10.30032442045,0.530776333563)); -#141201 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141202 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141203 = PCURVE('',#141015,#141204); -#141204 = DEFINITIONAL_REPRESENTATION('',(#141205),#141208); -#141205 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141206,#141207), +#143577 = CARTESIAN_POINT('',(1.598788597134,-6.85)); +#143578 = CARTESIAN_POINT('',(1.598788597134,-6.65)); +#143579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143580 = PCURVE('',#90146,#143581); +#143581 = DEFINITIONAL_REPRESENTATION('',(#143582),#143586); +#143582 = LINE('',#143583,#143584); +#143583 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#143584 = VECTOR('',#143585,1.); +#143585 = DIRECTION('',(-8.881784197001E-016,-1.)); +#143586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143587 = ORIENTED_EDGE('',*,*,#143588,.T.); +#143588 = EDGE_CURVE('',#143567,#143392,#143589,.T.); +#143589 = SURFACE_CURVE('',#143590,(#143595,#143601),.PCURVE_S1.); +#143590 = CIRCLE('',#143591,0.119270391569); +#143591 = AXIS2_PLACEMENT_3D('',#143592,#143593,#143594); +#143592 = CARTESIAN_POINT('',(6.85,10.30032442045,0.530776333563)); +#143593 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143594 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143595 = PCURVE('',#143407,#143596); +#143596 = DEFINITIONAL_REPRESENTATION('',(#143597),#143600); +#143597 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143598,#143599), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#141206 = CARTESIAN_POINT('',(1.598788597134,-6.85)); -#141207 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#141208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141209 = PCURVE('',#87782,#141210); -#141210 = DEFINITIONAL_REPRESENTATION('',(#141211),#141215); -#141211 = CIRCLE('',#141212,0.119270391569); -#141212 = AXIS2_PLACEMENT_2D('',#141213,#141214); -#141213 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#141214 = DIRECTION('',(0.E+000,-1.)); -#141215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141216 = ORIENTED_EDGE('',*,*,#140997,.F.); -#141217 = ADVANCED_FACE('',(#141218),#141090,.T.); -#141218 = FACE_BOUND('',#141219,.T.); -#141219 = EDGE_LOOP('',(#141220,#141266,#141267,#141317)); -#141220 = ORIENTED_EDGE('',*,*,#141221,.T.); -#141221 = EDGE_CURVE('',#141222,#141073,#141224,.T.); -#141222 = VERTEX_POINT('',#141223); -#141223 = CARTESIAN_POINT('',(6.85,10.304819755875,0.75)); -#141224 = SURFACE_CURVE('',#141225,(#141230,#141259),.PCURVE_S1.); -#141225 = CIRCLE('',#141226,0.2192697516); -#141226 = AXIS2_PLACEMENT_3D('',#141227,#141228,#141229); -#141227 = CARTESIAN_POINT('',(6.85,10.30032442045,0.530776333563)); -#141228 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141229 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141230 = PCURVE('',#141090,#141231); -#141231 = DEFINITIONAL_REPRESENTATION('',(#141232),#141258); -#141232 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141233,#141234,#141235, - #141236,#141237,#141238,#141239,#141240,#141241,#141242,#141243, - #141244,#141245,#141246,#141247,#141248,#141249,#141250,#141251, - #141252,#141253,#141254,#141255,#141256,#141257),.UNSPECIFIED.,.F., +#143598 = CARTESIAN_POINT('',(1.598788597134,-6.85)); +#143599 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#143600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143601 = PCURVE('',#90174,#143602); +#143602 = DEFINITIONAL_REPRESENTATION('',(#143603),#143607); +#143603 = CIRCLE('',#143604,0.119270391569); +#143604 = AXIS2_PLACEMENT_2D('',#143605,#143606); +#143605 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#143606 = DIRECTION('',(0.E+000,-1.)); +#143607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143608 = ORIENTED_EDGE('',*,*,#143389,.F.); +#143609 = ADVANCED_FACE('',(#143610),#143482,.T.); +#143610 = FACE_BOUND('',#143611,.T.); +#143611 = EDGE_LOOP('',(#143612,#143658,#143659,#143709)); +#143612 = ORIENTED_EDGE('',*,*,#143613,.T.); +#143613 = EDGE_CURVE('',#143614,#143465,#143616,.T.); +#143614 = VERTEX_POINT('',#143615); +#143615 = CARTESIAN_POINT('',(6.85,10.304819755875,0.75)); +#143616 = SURFACE_CURVE('',#143617,(#143622,#143651),.PCURVE_S1.); +#143617 = CIRCLE('',#143618,0.2192697516); +#143618 = AXIS2_PLACEMENT_3D('',#143619,#143620,#143621); +#143619 = CARTESIAN_POINT('',(6.85,10.30032442045,0.530776333563)); +#143620 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143621 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143622 = PCURVE('',#143482,#143623); +#143623 = DEFINITIONAL_REPRESENTATION('',(#143624),#143650); +#143624 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143625,#143626,#143627, + #143628,#143629,#143630,#143631,#143632,#143633,#143634,#143635, + #143636,#143637,#143638,#143639,#143640,#143641,#143642,#143643, + #143644,#143645,#143646,#143647,#143648,#143649),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -174110,60 +177112,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#141233 = CARTESIAN_POINT('',(1.591299156552,-6.85)); -#141234 = CARTESIAN_POINT('',(1.614788451962,-6.85)); -#141235 = CARTESIAN_POINT('',(1.661767042781,-6.85)); -#141236 = CARTESIAN_POINT('',(1.73223492901,-6.85)); -#141237 = CARTESIAN_POINT('',(1.802702815239,-6.85)); -#141238 = CARTESIAN_POINT('',(1.873170701468,-6.85)); -#141239 = CARTESIAN_POINT('',(1.943638587697,-6.85)); -#141240 = CARTESIAN_POINT('',(2.014106473926,-6.85)); -#141241 = CARTESIAN_POINT('',(2.084574360155,-6.85)); -#141242 = CARTESIAN_POINT('',(2.155042246384,-6.85)); -#141243 = CARTESIAN_POINT('',(2.225510132613,-6.85)); -#141244 = CARTESIAN_POINT('',(2.295978018842,-6.85)); -#141245 = CARTESIAN_POINT('',(2.366445905071,-6.85)); -#141246 = CARTESIAN_POINT('',(2.4369137913,-6.85)); -#141247 = CARTESIAN_POINT('',(2.507381677529,-6.85)); -#141248 = CARTESIAN_POINT('',(2.577849563758,-6.85)); -#141249 = CARTESIAN_POINT('',(2.648317449987,-6.85)); -#141250 = CARTESIAN_POINT('',(2.718785336216,-6.85)); -#141251 = CARTESIAN_POINT('',(2.789253222445,-6.85)); -#141252 = CARTESIAN_POINT('',(2.859721108674,-6.85)); -#141253 = CARTESIAN_POINT('',(2.930188994903,-6.85)); -#141254 = CARTESIAN_POINT('',(3.000656881132,-6.85)); -#141255 = CARTESIAN_POINT('',(3.071124767361,-6.85)); -#141256 = CARTESIAN_POINT('',(3.11810335818,-6.85)); -#141257 = CARTESIAN_POINT('',(3.14159265359,-6.85)); -#141258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141259 = PCURVE('',#87782,#141260); -#141260 = DEFINITIONAL_REPRESENTATION('',(#141261),#141265); -#141261 = CIRCLE('',#141262,0.2192697516); -#141262 = AXIS2_PLACEMENT_2D('',#141263,#141264); -#141263 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#141264 = DIRECTION('',(0.E+000,-1.)); -#141265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141266 = ORIENTED_EDGE('',*,*,#141072,.T.); -#141267 = ORIENTED_EDGE('',*,*,#141268,.F.); -#141268 = EDGE_CURVE('',#141269,#141075,#141271,.T.); -#141269 = VERTEX_POINT('',#141270); -#141270 = CARTESIAN_POINT('',(6.65,10.304819755875,0.75)); -#141271 = SURFACE_CURVE('',#141272,(#141277,#141306),.PCURVE_S1.); -#141272 = CIRCLE('',#141273,0.2192697516); -#141273 = AXIS2_PLACEMENT_3D('',#141274,#141275,#141276); -#141274 = CARTESIAN_POINT('',(6.65,10.30032442045,0.530776333563)); -#141275 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141276 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141277 = PCURVE('',#141090,#141278); -#141278 = DEFINITIONAL_REPRESENTATION('',(#141279),#141305); -#141279 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141280,#141281,#141282, - #141283,#141284,#141285,#141286,#141287,#141288,#141289,#141290, - #141291,#141292,#141293,#141294,#141295,#141296,#141297,#141298, - #141299,#141300,#141301,#141302,#141303,#141304),.UNSPECIFIED.,.F., +#143625 = CARTESIAN_POINT('',(1.591299156552,-6.85)); +#143626 = CARTESIAN_POINT('',(1.614788451962,-6.85)); +#143627 = CARTESIAN_POINT('',(1.661767042781,-6.85)); +#143628 = CARTESIAN_POINT('',(1.73223492901,-6.85)); +#143629 = CARTESIAN_POINT('',(1.802702815239,-6.85)); +#143630 = CARTESIAN_POINT('',(1.873170701468,-6.85)); +#143631 = CARTESIAN_POINT('',(1.943638587697,-6.85)); +#143632 = CARTESIAN_POINT('',(2.014106473926,-6.85)); +#143633 = CARTESIAN_POINT('',(2.084574360155,-6.85)); +#143634 = CARTESIAN_POINT('',(2.155042246384,-6.85)); +#143635 = CARTESIAN_POINT('',(2.225510132613,-6.85)); +#143636 = CARTESIAN_POINT('',(2.295978018842,-6.85)); +#143637 = CARTESIAN_POINT('',(2.366445905071,-6.85)); +#143638 = CARTESIAN_POINT('',(2.4369137913,-6.85)); +#143639 = CARTESIAN_POINT('',(2.507381677529,-6.85)); +#143640 = CARTESIAN_POINT('',(2.577849563758,-6.85)); +#143641 = CARTESIAN_POINT('',(2.648317449987,-6.85)); +#143642 = CARTESIAN_POINT('',(2.718785336216,-6.85)); +#143643 = CARTESIAN_POINT('',(2.789253222445,-6.85)); +#143644 = CARTESIAN_POINT('',(2.859721108674,-6.85)); +#143645 = CARTESIAN_POINT('',(2.930188994903,-6.85)); +#143646 = CARTESIAN_POINT('',(3.000656881132,-6.85)); +#143647 = CARTESIAN_POINT('',(3.071124767361,-6.85)); +#143648 = CARTESIAN_POINT('',(3.11810335818,-6.85)); +#143649 = CARTESIAN_POINT('',(3.14159265359,-6.85)); +#143650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143651 = PCURVE('',#90174,#143652); +#143652 = DEFINITIONAL_REPRESENTATION('',(#143653),#143657); +#143653 = CIRCLE('',#143654,0.2192697516); +#143654 = AXIS2_PLACEMENT_2D('',#143655,#143656); +#143655 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#143656 = DIRECTION('',(0.E+000,-1.)); +#143657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143658 = ORIENTED_EDGE('',*,*,#143464,.T.); +#143659 = ORIENTED_EDGE('',*,*,#143660,.F.); +#143660 = EDGE_CURVE('',#143661,#143467,#143663,.T.); +#143661 = VERTEX_POINT('',#143662); +#143662 = CARTESIAN_POINT('',(6.65,10.304819755875,0.75)); +#143663 = SURFACE_CURVE('',#143664,(#143669,#143698),.PCURVE_S1.); +#143664 = CIRCLE('',#143665,0.2192697516); +#143665 = AXIS2_PLACEMENT_3D('',#143666,#143667,#143668); +#143666 = CARTESIAN_POINT('',(6.65,10.30032442045,0.530776333563)); +#143667 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143668 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#143669 = PCURVE('',#143482,#143670); +#143670 = DEFINITIONAL_REPRESENTATION('',(#143671),#143697); +#143671 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143672,#143673,#143674, + #143675,#143676,#143677,#143678,#143679,#143680,#143681,#143682, + #143683,#143684,#143685,#143686,#143687,#143688,#143689,#143690, + #143691,#143692,#143693,#143694,#143695,#143696),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -174171,655 +177173,655 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#141280 = CARTESIAN_POINT('',(1.591299156552,-6.65)); -#141281 = CARTESIAN_POINT('',(1.614788451962,-6.65)); -#141282 = CARTESIAN_POINT('',(1.661767042781,-6.65)); -#141283 = CARTESIAN_POINT('',(1.73223492901,-6.65)); -#141284 = CARTESIAN_POINT('',(1.802702815239,-6.65)); -#141285 = CARTESIAN_POINT('',(1.873170701468,-6.65)); -#141286 = CARTESIAN_POINT('',(1.943638587697,-6.65)); -#141287 = CARTESIAN_POINT('',(2.014106473926,-6.65)); -#141288 = CARTESIAN_POINT('',(2.084574360155,-6.65)); -#141289 = CARTESIAN_POINT('',(2.155042246384,-6.65)); -#141290 = CARTESIAN_POINT('',(2.225510132613,-6.65)); -#141291 = CARTESIAN_POINT('',(2.295978018842,-6.65)); -#141292 = CARTESIAN_POINT('',(2.366445905071,-6.65)); -#141293 = CARTESIAN_POINT('',(2.4369137913,-6.65)); -#141294 = CARTESIAN_POINT('',(2.507381677529,-6.65)); -#141295 = CARTESIAN_POINT('',(2.577849563758,-6.65)); -#141296 = CARTESIAN_POINT('',(2.648317449987,-6.65)); -#141297 = CARTESIAN_POINT('',(2.718785336216,-6.65)); -#141298 = CARTESIAN_POINT('',(2.789253222445,-6.65)); -#141299 = CARTESIAN_POINT('',(2.859721108674,-6.65)); -#141300 = CARTESIAN_POINT('',(2.930188994903,-6.65)); -#141301 = CARTESIAN_POINT('',(3.000656881132,-6.65)); -#141302 = CARTESIAN_POINT('',(3.071124767361,-6.65)); -#141303 = CARTESIAN_POINT('',(3.11810335818,-6.65)); -#141304 = CARTESIAN_POINT('',(3.14159265359,-6.65)); -#141305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141306 = PCURVE('',#87726,#141307); -#141307 = DEFINITIONAL_REPRESENTATION('',(#141308),#141316); -#141308 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141309,#141310,#141311, - #141312,#141313,#141314,#141315),.UNSPECIFIED.,.T.,.F.) +#143672 = CARTESIAN_POINT('',(1.591299156552,-6.65)); +#143673 = CARTESIAN_POINT('',(1.614788451962,-6.65)); +#143674 = CARTESIAN_POINT('',(1.661767042781,-6.65)); +#143675 = CARTESIAN_POINT('',(1.73223492901,-6.65)); +#143676 = CARTESIAN_POINT('',(1.802702815239,-6.65)); +#143677 = CARTESIAN_POINT('',(1.873170701468,-6.65)); +#143678 = CARTESIAN_POINT('',(1.943638587697,-6.65)); +#143679 = CARTESIAN_POINT('',(2.014106473926,-6.65)); +#143680 = CARTESIAN_POINT('',(2.084574360155,-6.65)); +#143681 = CARTESIAN_POINT('',(2.155042246384,-6.65)); +#143682 = CARTESIAN_POINT('',(2.225510132613,-6.65)); +#143683 = CARTESIAN_POINT('',(2.295978018842,-6.65)); +#143684 = CARTESIAN_POINT('',(2.366445905071,-6.65)); +#143685 = CARTESIAN_POINT('',(2.4369137913,-6.65)); +#143686 = CARTESIAN_POINT('',(2.507381677529,-6.65)); +#143687 = CARTESIAN_POINT('',(2.577849563758,-6.65)); +#143688 = CARTESIAN_POINT('',(2.648317449987,-6.65)); +#143689 = CARTESIAN_POINT('',(2.718785336216,-6.65)); +#143690 = CARTESIAN_POINT('',(2.789253222445,-6.65)); +#143691 = CARTESIAN_POINT('',(2.859721108674,-6.65)); +#143692 = CARTESIAN_POINT('',(2.930188994903,-6.65)); +#143693 = CARTESIAN_POINT('',(3.000656881132,-6.65)); +#143694 = CARTESIAN_POINT('',(3.071124767361,-6.65)); +#143695 = CARTESIAN_POINT('',(3.11810335818,-6.65)); +#143696 = CARTESIAN_POINT('',(3.14159265359,-6.65)); +#143697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143698 = PCURVE('',#90118,#143699); +#143699 = DEFINITIONAL_REPRESENTATION('',(#143700),#143708); +#143700 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143701,#143702,#143703, + #143704,#143705,#143706,#143707),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#141309 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#141310 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#141311 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#141312 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#141313 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#141314 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#141315 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#141316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141317 = ORIENTED_EDGE('',*,*,#141318,.T.); -#141318 = EDGE_CURVE('',#141269,#141222,#141319,.T.); -#141319 = SURFACE_CURVE('',#141320,(#141324,#141330),.PCURVE_S1.); -#141320 = LINE('',#141321,#141322); -#141321 = CARTESIAN_POINT('',(6.65,10.304819755875,0.75)); -#141322 = VECTOR('',#141323,1.); -#141323 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141324 = PCURVE('',#141090,#141325); -#141325 = DEFINITIONAL_REPRESENTATION('',(#141326),#141329); -#141326 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141327,#141328), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#141327 = CARTESIAN_POINT('',(1.591299156552,-6.65)); -#141328 = CARTESIAN_POINT('',(1.591299156552,-6.85)); -#141329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141330 = PCURVE('',#87808,#141331); -#141331 = DEFINITIONAL_REPRESENTATION('',(#141332),#141336); -#141332 = LINE('',#141333,#141334); -#141333 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#141334 = VECTOR('',#141335,1.); -#141335 = DIRECTION('',(-8.881784197001E-016,1.)); -#141336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141337 = ADVANCED_FACE('',(#141338),#87726,.F.); -#141338 = FACE_BOUND('',#141339,.T.); -#141339 = EDGE_LOOP('',(#141340,#141361,#141362,#141363,#141364,#141365, - #141386,#141387,#141388,#141389,#141390,#141411)); -#141340 = ORIENTED_EDGE('',*,*,#141341,.F.); -#141341 = EDGE_CURVE('',#141269,#87711,#141342,.T.); -#141342 = SURFACE_CURVE('',#141343,(#141347,#141354),.PCURVE_S1.); -#141343 = LINE('',#141344,#141345); -#141344 = CARTESIAN_POINT('',(6.65,10.527847992439,0.75)); -#141345 = VECTOR('',#141346,1.); -#141346 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#141347 = PCURVE('',#87726,#141348); -#141348 = DEFINITIONAL_REPRESENTATION('',(#141349),#141353); -#141349 = LINE('',#141350,#141351); -#141350 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#141351 = VECTOR('',#141352,1.); -#141352 = DIRECTION('',(-3.563627120235E-016,-1.)); -#141353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141354 = PCURVE('',#87808,#141355); -#141355 = DEFINITIONAL_REPRESENTATION('',(#141356),#141360); -#141356 = LINE('',#141357,#141358); -#141357 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141358 = VECTOR('',#141359,1.); -#141359 = DIRECTION('',(-1.,6.005309793447E-063)); -#141360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141361 = ORIENTED_EDGE('',*,*,#141268,.T.); -#141362 = ORIENTED_EDGE('',*,*,#141123,.T.); -#141363 = ORIENTED_EDGE('',*,*,#140848,.T.); -#141364 = ORIENTED_EDGE('',*,*,#140638,.T.); -#141365 = ORIENTED_EDGE('',*,*,#141366,.T.); -#141366 = EDGE_CURVE('',#140611,#140692,#141367,.T.); -#141367 = SURFACE_CURVE('',#141368,(#141372,#141379),.PCURVE_S1.); -#141368 = LINE('',#141369,#141370); -#141369 = CARTESIAN_POINT('',(6.65,11.,1.159810404338E-002)); -#141370 = VECTOR('',#141371,1.); -#141371 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#141372 = PCURVE('',#87726,#141373); -#141373 = DEFINITIONAL_REPRESENTATION('',(#141374),#141378); -#141374 = LINE('',#141375,#141376); -#141375 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#141376 = VECTOR('',#141377,1.); -#141377 = DIRECTION('',(1.,-2.101748079665E-016)); -#141378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141379 = PCURVE('',#140626,#141380); -#141380 = DEFINITIONAL_REPRESENTATION('',(#141381),#141385); -#141381 = LINE('',#141382,#141383); -#141382 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#141383 = VECTOR('',#141384,1.); -#141384 = DIRECTION('',(1.570395187386E-016,-1.)); -#141385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141386 = ORIENTED_EDGE('',*,*,#140689,.F.); -#141387 = ORIENTED_EDGE('',*,*,#140950,.F.); -#141388 = ORIENTED_EDGE('',*,*,#141026,.F.); -#141389 = ORIENTED_EDGE('',*,*,#141147,.F.); -#141390 = ORIENTED_EDGE('',*,*,#141391,.T.); -#141391 = EDGE_CURVE('',#141148,#87709,#141392,.T.); -#141392 = SURFACE_CURVE('',#141393,(#141397,#141404),.PCURVE_S1.); -#141393 = LINE('',#141394,#141395); -#141394 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); -#141395 = VECTOR('',#141396,1.); -#141396 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#141397 = PCURVE('',#87726,#141398); -#141398 = DEFINITIONAL_REPRESENTATION('',(#141399),#141403); -#141399 = LINE('',#141400,#141401); -#141400 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141401 = VECTOR('',#141402,1.); -#141402 = DIRECTION('',(-3.563627120235E-016,-1.)); -#141403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141404 = PCURVE('',#87754,#141405); -#141405 = DEFINITIONAL_REPRESENTATION('',(#141406),#141410); -#141406 = LINE('',#141407,#141408); -#141407 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141408 = VECTOR('',#141409,1.); -#141409 = DIRECTION('',(1.,6.005309793447E-063)); -#141410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141411 = ORIENTED_EDGE('',*,*,#87708,.T.); -#141412 = ADVANCED_FACE('',(#141413),#87808,.F.); -#141413 = FACE_BOUND('',#141414,.T.); -#141414 = EDGE_LOOP('',(#141415,#141416,#141417,#141418)); -#141415 = ORIENTED_EDGE('',*,*,#141318,.F.); -#141416 = ORIENTED_EDGE('',*,*,#141341,.T.); -#141417 = ORIENTED_EDGE('',*,*,#87794,.T.); -#141418 = ORIENTED_EDGE('',*,*,#141419,.F.); -#141419 = EDGE_CURVE('',#141222,#87767,#141420,.T.); -#141420 = SURFACE_CURVE('',#141421,(#141425,#141432),.PCURVE_S1.); -#141421 = LINE('',#141422,#141423); -#141422 = CARTESIAN_POINT('',(6.85,10.527847992439,0.75)); -#141423 = VECTOR('',#141424,1.); -#141424 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#141425 = PCURVE('',#87808,#141426); -#141426 = DEFINITIONAL_REPRESENTATION('',(#141427),#141431); -#141427 = LINE('',#141428,#141429); -#141428 = CARTESIAN_POINT('',(0.E+000,0.2)); -#141429 = VECTOR('',#141430,1.); -#141430 = DIRECTION('',(-1.,6.005309793447E-063)); -#141431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141432 = PCURVE('',#87782,#141433); -#141433 = DEFINITIONAL_REPRESENTATION('',(#141434),#141438); -#141434 = LINE('',#141435,#141436); -#141435 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#141436 = VECTOR('',#141437,1.); -#141437 = DIRECTION('',(3.563627120235E-016,-1.)); -#141438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#143701 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#143702 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#143703 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#143704 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#143705 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#143706 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#143707 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#143708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143709 = ORIENTED_EDGE('',*,*,#143710,.T.); +#143710 = EDGE_CURVE('',#143661,#143614,#143711,.T.); +#143711 = SURFACE_CURVE('',#143712,(#143716,#143722),.PCURVE_S1.); +#143712 = LINE('',#143713,#143714); +#143713 = CARTESIAN_POINT('',(6.65,10.304819755875,0.75)); +#143714 = VECTOR('',#143715,1.); +#143715 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143716 = PCURVE('',#143482,#143717); +#143717 = DEFINITIONAL_REPRESENTATION('',(#143718),#143721); +#143718 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143719,#143720), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); +#143719 = CARTESIAN_POINT('',(1.591299156552,-6.65)); +#143720 = CARTESIAN_POINT('',(1.591299156552,-6.85)); +#143721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143722 = PCURVE('',#90200,#143723); +#143723 = DEFINITIONAL_REPRESENTATION('',(#143724),#143728); +#143724 = LINE('',#143725,#143726); +#143725 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#143726 = VECTOR('',#143727,1.); +#143727 = DIRECTION('',(-8.881784197001E-016,1.)); +#143728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143729 = ADVANCED_FACE('',(#143730),#90118,.F.); +#143730 = FACE_BOUND('',#143731,.T.); +#143731 = EDGE_LOOP('',(#143732,#143753,#143754,#143755,#143756,#143757, + #143778,#143779,#143780,#143781,#143782,#143803)); +#143732 = ORIENTED_EDGE('',*,*,#143733,.F.); +#143733 = EDGE_CURVE('',#143661,#90103,#143734,.T.); +#143734 = SURFACE_CURVE('',#143735,(#143739,#143746),.PCURVE_S1.); +#143735 = LINE('',#143736,#143737); +#143736 = CARTESIAN_POINT('',(6.65,10.527847992439,0.75)); +#143737 = VECTOR('',#143738,1.); +#143738 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#143739 = PCURVE('',#90118,#143740); +#143740 = DEFINITIONAL_REPRESENTATION('',(#143741),#143745); +#143741 = LINE('',#143742,#143743); +#143742 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#143743 = VECTOR('',#143744,1.); +#143744 = DIRECTION('',(-3.563627120235E-016,-1.)); +#143745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143746 = PCURVE('',#90200,#143747); +#143747 = DEFINITIONAL_REPRESENTATION('',(#143748),#143752); +#143748 = LINE('',#143749,#143750); +#143749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143750 = VECTOR('',#143751,1.); +#143751 = DIRECTION('',(-1.,6.005309793447E-063)); +#143752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143753 = ORIENTED_EDGE('',*,*,#143660,.T.); +#143754 = ORIENTED_EDGE('',*,*,#143515,.T.); +#143755 = ORIENTED_EDGE('',*,*,#143240,.T.); +#143756 = ORIENTED_EDGE('',*,*,#143030,.T.); +#143757 = ORIENTED_EDGE('',*,*,#143758,.T.); +#143758 = EDGE_CURVE('',#143003,#143084,#143759,.T.); +#143759 = SURFACE_CURVE('',#143760,(#143764,#143771),.PCURVE_S1.); +#143760 = LINE('',#143761,#143762); +#143761 = CARTESIAN_POINT('',(6.65,11.,1.159810404338E-002)); +#143762 = VECTOR('',#143763,1.); +#143763 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#143764 = PCURVE('',#90118,#143765); +#143765 = DEFINITIONAL_REPRESENTATION('',(#143766),#143770); +#143766 = LINE('',#143767,#143768); +#143767 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#143768 = VECTOR('',#143769,1.); +#143769 = DIRECTION('',(1.,-2.101748079665E-016)); +#143770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143771 = PCURVE('',#143018,#143772); +#143772 = DEFINITIONAL_REPRESENTATION('',(#143773),#143777); +#143773 = LINE('',#143774,#143775); +#143774 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#143775 = VECTOR('',#143776,1.); +#143776 = DIRECTION('',(1.570395187386E-016,-1.)); +#143777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143778 = ORIENTED_EDGE('',*,*,#143081,.F.); +#143779 = ORIENTED_EDGE('',*,*,#143342,.F.); +#143780 = ORIENTED_EDGE('',*,*,#143418,.F.); +#143781 = ORIENTED_EDGE('',*,*,#143539,.F.); +#143782 = ORIENTED_EDGE('',*,*,#143783,.T.); +#143783 = EDGE_CURVE('',#143540,#90101,#143784,.T.); +#143784 = SURFACE_CURVE('',#143785,(#143789,#143796),.PCURVE_S1.); +#143785 = LINE('',#143786,#143787); +#143786 = CARTESIAN_POINT('',(6.65,10.527847992439,0.65)); +#143787 = VECTOR('',#143788,1.); +#143788 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#143789 = PCURVE('',#90118,#143790); +#143790 = DEFINITIONAL_REPRESENTATION('',(#143791),#143795); +#143791 = LINE('',#143792,#143793); +#143792 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143793 = VECTOR('',#143794,1.); +#143794 = DIRECTION('',(-3.563627120235E-016,-1.)); +#143795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143796 = PCURVE('',#90146,#143797); +#143797 = DEFINITIONAL_REPRESENTATION('',(#143798),#143802); +#143798 = LINE('',#143799,#143800); +#143799 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143800 = VECTOR('',#143801,1.); +#143801 = DIRECTION('',(1.,6.005309793447E-063)); +#143802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143803 = ORIENTED_EDGE('',*,*,#90100,.T.); +#143804 = ADVANCED_FACE('',(#143805),#90200,.F.); +#143805 = FACE_BOUND('',#143806,.T.); +#143806 = EDGE_LOOP('',(#143807,#143808,#143809,#143810)); +#143807 = ORIENTED_EDGE('',*,*,#143710,.F.); +#143808 = ORIENTED_EDGE('',*,*,#143733,.T.); +#143809 = ORIENTED_EDGE('',*,*,#90186,.T.); +#143810 = ORIENTED_EDGE('',*,*,#143811,.F.); +#143811 = EDGE_CURVE('',#143614,#90159,#143812,.T.); +#143812 = SURFACE_CURVE('',#143813,(#143817,#143824),.PCURVE_S1.); +#143813 = LINE('',#143814,#143815); +#143814 = CARTESIAN_POINT('',(6.85,10.527847992439,0.75)); +#143815 = VECTOR('',#143816,1.); +#143816 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#143817 = PCURVE('',#90200,#143818); +#143818 = DEFINITIONAL_REPRESENTATION('',(#143819),#143823); +#143819 = LINE('',#143820,#143821); +#143820 = CARTESIAN_POINT('',(0.E+000,0.2)); +#143821 = VECTOR('',#143822,1.); +#143822 = DIRECTION('',(-1.,6.005309793447E-063)); +#143823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143824 = PCURVE('',#90174,#143825); +#143825 = DEFINITIONAL_REPRESENTATION('',(#143826),#143830); +#143826 = LINE('',#143827,#143828); +#143827 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#143828 = VECTOR('',#143829,1.); +#143829 = DIRECTION('',(3.563627120235E-016,-1.)); +#143830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143831 = ADVANCED_FACE('',(#143832),#90174,.F.); +#143832 = FACE_BOUND('',#143833,.T.); +#143833 = EDGE_LOOP('',(#143834,#143855,#143856,#143857,#143858,#143859, + #143880,#143881,#143882,#143883,#143884,#143885)); +#143834 = ORIENTED_EDGE('',*,*,#143835,.F.); +#143835 = EDGE_CURVE('',#143567,#90131,#143836,.T.); +#143836 = SURFACE_CURVE('',#143837,(#143841,#143848),.PCURVE_S1.); +#143837 = LINE('',#143838,#143839); +#143838 = CARTESIAN_POINT('',(6.85,10.527847992439,0.65)); +#143839 = VECTOR('',#143840,1.); +#143840 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#143841 = PCURVE('',#90174,#143842); +#143842 = DEFINITIONAL_REPRESENTATION('',(#143843),#143847); +#143843 = LINE('',#143844,#143845); +#143844 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143845 = VECTOR('',#143846,1.); +#143846 = DIRECTION('',(3.563627120235E-016,-1.)); +#143847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143848 = PCURVE('',#90146,#143849); +#143849 = DEFINITIONAL_REPRESENTATION('',(#143850),#143854); +#143850 = LINE('',#143851,#143852); +#143851 = CARTESIAN_POINT('',(0.E+000,0.2)); +#143852 = VECTOR('',#143853,1.); +#143853 = DIRECTION('',(1.,6.005309793447E-063)); +#143854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143855 = ORIENTED_EDGE('',*,*,#143588,.T.); +#143856 = ORIENTED_EDGE('',*,*,#143440,.T.); +#143857 = ORIENTED_EDGE('',*,*,#143265,.T.); +#143858 = ORIENTED_EDGE('',*,*,#143134,.T.); +#143859 = ORIENTED_EDGE('',*,*,#143860,.T.); +#143860 = EDGE_CURVE('',#143112,#142975,#143861,.T.); +#143861 = SURFACE_CURVE('',#143862,(#143866,#143873),.PCURVE_S1.); +#143862 = LINE('',#143863,#143864); +#143863 = CARTESIAN_POINT('',(6.85,11.,1.159810404338E-002)); +#143864 = VECTOR('',#143865,1.); +#143865 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#143866 = PCURVE('',#90174,#143867); +#143867 = DEFINITIONAL_REPRESENTATION('',(#143868),#143872); +#143868 = LINE('',#143869,#143870); +#143869 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#143870 = VECTOR('',#143871,1.); +#143871 = DIRECTION('',(1.,2.101748079665E-016)); +#143872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143873 = PCURVE('',#143018,#143874); +#143874 = DEFINITIONAL_REPRESENTATION('',(#143875),#143879); +#143875 = LINE('',#143876,#143877); +#143876 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#143877 = VECTOR('',#143878,1.); +#143878 = DIRECTION('',(-1.570395187386E-016,1.)); +#143879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143880 = ORIENTED_EDGE('',*,*,#142972,.F.); +#143881 = ORIENTED_EDGE('',*,*,#143186,.F.); +#143882 = ORIENTED_EDGE('',*,*,#143493,.F.); +#143883 = ORIENTED_EDGE('',*,*,#143613,.F.); +#143884 = ORIENTED_EDGE('',*,*,#143811,.T.); +#143885 = ORIENTED_EDGE('',*,*,#90158,.T.); +#143886 = ADVANCED_FACE('',(#143887),#90146,.F.); +#143887 = FACE_BOUND('',#143888,.T.); +#143888 = EDGE_LOOP('',(#143889,#143890,#143891,#143892)); +#143889 = ORIENTED_EDGE('',*,*,#143566,.F.); +#143890 = ORIENTED_EDGE('',*,*,#143835,.T.); +#143891 = ORIENTED_EDGE('',*,*,#90130,.T.); +#143892 = ORIENTED_EDGE('',*,*,#143783,.F.); +#143893 = ADVANCED_FACE('',(#143894),#143018,.T.); +#143894 = FACE_BOUND('',#143895,.T.); +#143895 = EDGE_LOOP('',(#143896,#143897,#143898,#143899)); +#143896 = ORIENTED_EDGE('',*,*,#143860,.F.); +#143897 = ORIENTED_EDGE('',*,*,#143111,.F.); +#143898 = ORIENTED_EDGE('',*,*,#143758,.F.); +#143899 = ORIENTED_EDGE('',*,*,#143002,.F.); +#143900 = ADVANCED_FACE('',(#143901),#143915,.T.); +#143901 = FACE_BOUND('',#143902,.T.); +#143902 = EDGE_LOOP('',(#143903,#143933,#143961,#143984)); +#143903 = ORIENTED_EDGE('',*,*,#143904,.T.); +#143904 = EDGE_CURVE('',#143905,#143907,#143909,.T.); +#143905 = VERTEX_POINT('',#143906); +#143906 = CARTESIAN_POINT('',(6.35,10.740726081328,-0.208196358798)); +#143907 = VERTEX_POINT('',#143908); +#143908 = CARTESIAN_POINT('',(6.35,11.,-0.208196358798)); +#143909 = SURFACE_CURVE('',#143910,(#143914,#143926),.PCURVE_S1.); +#143910 = LINE('',#143911,#143912); +#143911 = CARTESIAN_POINT('',(6.35,10.740726081328,-0.208196358798)); +#143912 = VECTOR('',#143913,1.); +#143913 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#143914 = PCURVE('',#143915,#143920); +#143915 = PLANE('',#143916); +#143916 = AXIS2_PLACEMENT_3D('',#143917,#143918,#143919); +#143917 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#143918 = DIRECTION('',(0.E+000,0.E+000,1.)); +#143919 = DIRECTION('',(1.,0.E+000,0.E+000)); +#143920 = DEFINITIONAL_REPRESENTATION('',(#143921),#143925); +#143921 = LINE('',#143922,#143923); +#143922 = CARTESIAN_POINT('',(6.35,-5.329070518201E-015)); +#143923 = VECTOR('',#143924,1.); +#143924 = DIRECTION('',(6.725593854929E-015,1.)); +#143925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143926 = PCURVE('',#89490,#143927); +#143927 = DEFINITIONAL_REPRESENTATION('',(#143928),#143932); +#143928 = LINE('',#143929,#143930); +#143929 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#143930 = VECTOR('',#143931,1.); +#143931 = DIRECTION('',(0.E+000,1.)); +#143932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143933 = ORIENTED_EDGE('',*,*,#143934,.T.); +#143934 = EDGE_CURVE('',#143907,#143935,#143937,.T.); +#143935 = VERTEX_POINT('',#143936); +#143936 = CARTESIAN_POINT('',(6.15,11.,-0.208196358798)); +#143937 = SURFACE_CURVE('',#143938,(#143942,#143949),.PCURVE_S1.); +#143938 = LINE('',#143939,#143940); +#143939 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#143940 = VECTOR('',#143941,1.); +#143941 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#143942 = PCURVE('',#143915,#143943); +#143943 = DEFINITIONAL_REPRESENTATION('',(#143944),#143948); +#143944 = LINE('',#143945,#143946); +#143945 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#143946 = VECTOR('',#143947,1.); +#143947 = DIRECTION('',(-1.,8.881784197001E-016)); +#143948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143949 = PCURVE('',#143950,#143955); +#143950 = PLANE('',#143951); +#143951 = AXIS2_PLACEMENT_3D('',#143952,#143953,#143954); +#143952 = CARTESIAN_POINT('',(6.25,11.,-0.258196742327)); +#143953 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#143954 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#143955 = DEFINITIONAL_REPRESENTATION('',(#143956),#143960); +#143956 = LINE('',#143957,#143958); +#143957 = CARTESIAN_POINT('',(6.25,5.000038352949E-002)); +#143958 = VECTOR('',#143959,1.); +#143959 = DIRECTION('',(1.,1.1653254136E-048)); +#143960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143961 = ORIENTED_EDGE('',*,*,#143962,.F.); +#143962 = EDGE_CURVE('',#143963,#143935,#143965,.T.); +#143963 = VERTEX_POINT('',#143964); +#143964 = CARTESIAN_POINT('',(6.15,10.740726081328,-0.208196358798)); +#143965 = SURFACE_CURVE('',#143966,(#143970,#143977),.PCURVE_S1.); +#143966 = LINE('',#143967,#143968); +#143967 = CARTESIAN_POINT('',(6.15,10.740726081328,-0.208196358798)); +#143968 = VECTOR('',#143969,1.); +#143969 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#143970 = PCURVE('',#143915,#143971); +#143971 = DEFINITIONAL_REPRESENTATION('',(#143972),#143976); +#143972 = LINE('',#143973,#143974); +#143973 = CARTESIAN_POINT('',(6.15,-5.329070518201E-015)); +#143974 = VECTOR('',#143975,1.); +#143975 = DIRECTION('',(6.725593854929E-015,1.)); +#143976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143977 = PCURVE('',#89434,#143978); +#143978 = DEFINITIONAL_REPRESENTATION('',(#143979),#143983); +#143979 = LINE('',#143980,#143981); +#143980 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#143981 = VECTOR('',#143982,1.); +#143982 = DIRECTION('',(0.E+000,1.)); +#143983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#141439 = ADVANCED_FACE('',(#141440),#87782,.F.); -#141440 = FACE_BOUND('',#141441,.T.); -#141441 = EDGE_LOOP('',(#141442,#141463,#141464,#141465,#141466,#141467, - #141488,#141489,#141490,#141491,#141492,#141493)); -#141442 = ORIENTED_EDGE('',*,*,#141443,.F.); -#141443 = EDGE_CURVE('',#141175,#87739,#141444,.T.); -#141444 = SURFACE_CURVE('',#141445,(#141449,#141456),.PCURVE_S1.); -#141445 = LINE('',#141446,#141447); -#141446 = CARTESIAN_POINT('',(6.85,10.527847992439,0.65)); -#141447 = VECTOR('',#141448,1.); -#141448 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#141449 = PCURVE('',#87782,#141450); -#141450 = DEFINITIONAL_REPRESENTATION('',(#141451),#141455); -#141451 = LINE('',#141452,#141453); -#141452 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141453 = VECTOR('',#141454,1.); -#141454 = DIRECTION('',(3.563627120235E-016,-1.)); -#141455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141456 = PCURVE('',#87754,#141457); -#141457 = DEFINITIONAL_REPRESENTATION('',(#141458),#141462); -#141458 = LINE('',#141459,#141460); -#141459 = CARTESIAN_POINT('',(0.E+000,0.2)); -#141460 = VECTOR('',#141461,1.); -#141461 = DIRECTION('',(1.,6.005309793447E-063)); -#141462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141463 = ORIENTED_EDGE('',*,*,#141196,.T.); -#141464 = ORIENTED_EDGE('',*,*,#141048,.T.); -#141465 = ORIENTED_EDGE('',*,*,#140873,.T.); -#141466 = ORIENTED_EDGE('',*,*,#140742,.T.); -#141467 = ORIENTED_EDGE('',*,*,#141468,.T.); -#141468 = EDGE_CURVE('',#140720,#140583,#141469,.T.); -#141469 = SURFACE_CURVE('',#141470,(#141474,#141481),.PCURVE_S1.); -#141470 = LINE('',#141471,#141472); -#141471 = CARTESIAN_POINT('',(6.85,11.,1.159810404338E-002)); -#141472 = VECTOR('',#141473,1.); -#141473 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#141474 = PCURVE('',#87782,#141475); -#141475 = DEFINITIONAL_REPRESENTATION('',(#141476),#141480); -#141476 = LINE('',#141477,#141478); -#141477 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#141478 = VECTOR('',#141479,1.); -#141479 = DIRECTION('',(1.,2.101748079665E-016)); -#141480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141481 = PCURVE('',#140626,#141482); -#141482 = DEFINITIONAL_REPRESENTATION('',(#141483),#141487); -#141483 = LINE('',#141484,#141485); -#141484 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#141485 = VECTOR('',#141486,1.); -#141486 = DIRECTION('',(-1.570395187386E-016,1.)); -#141487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141488 = ORIENTED_EDGE('',*,*,#140580,.F.); -#141489 = ORIENTED_EDGE('',*,*,#140794,.F.); -#141490 = ORIENTED_EDGE('',*,*,#141101,.F.); -#141491 = ORIENTED_EDGE('',*,*,#141221,.F.); -#141492 = ORIENTED_EDGE('',*,*,#141419,.T.); -#141493 = ORIENTED_EDGE('',*,*,#87766,.T.); -#141494 = ADVANCED_FACE('',(#141495),#87754,.F.); -#141495 = FACE_BOUND('',#141496,.T.); -#141496 = EDGE_LOOP('',(#141497,#141498,#141499,#141500)); -#141497 = ORIENTED_EDGE('',*,*,#141174,.F.); -#141498 = ORIENTED_EDGE('',*,*,#141443,.T.); -#141499 = ORIENTED_EDGE('',*,*,#87738,.T.); -#141500 = ORIENTED_EDGE('',*,*,#141391,.F.); -#141501 = ADVANCED_FACE('',(#141502),#140626,.T.); -#141502 = FACE_BOUND('',#141503,.T.); -#141503 = EDGE_LOOP('',(#141504,#141505,#141506,#141507)); -#141504 = ORIENTED_EDGE('',*,*,#141468,.F.); -#141505 = ORIENTED_EDGE('',*,*,#140719,.F.); -#141506 = ORIENTED_EDGE('',*,*,#141366,.F.); -#141507 = ORIENTED_EDGE('',*,*,#140610,.F.); -#141508 = ADVANCED_FACE('',(#141509),#141523,.T.); -#141509 = FACE_BOUND('',#141510,.T.); -#141510 = EDGE_LOOP('',(#141511,#141541,#141569,#141592)); -#141511 = ORIENTED_EDGE('',*,*,#141512,.T.); -#141512 = EDGE_CURVE('',#141513,#141515,#141517,.T.); -#141513 = VERTEX_POINT('',#141514); -#141514 = CARTESIAN_POINT('',(6.35,10.740726081328,-0.208196358798)); -#141515 = VERTEX_POINT('',#141516); -#141516 = CARTESIAN_POINT('',(6.35,11.,-0.208196358798)); -#141517 = SURFACE_CURVE('',#141518,(#141522,#141534),.PCURVE_S1.); -#141518 = LINE('',#141519,#141520); -#141519 = CARTESIAN_POINT('',(6.35,10.740726081328,-0.208196358798)); -#141520 = VECTOR('',#141521,1.); -#141521 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#141522 = PCURVE('',#141523,#141528); -#141523 = PLANE('',#141524); -#141524 = AXIS2_PLACEMENT_3D('',#141525,#141526,#141527); -#141525 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#141526 = DIRECTION('',(0.E+000,0.E+000,1.)); -#141527 = DIRECTION('',(1.,0.E+000,0.E+000)); -#141528 = DEFINITIONAL_REPRESENTATION('',(#141529),#141533); -#141529 = LINE('',#141530,#141531); -#141530 = CARTESIAN_POINT('',(6.35,-5.329070518201E-015)); -#141531 = VECTOR('',#141532,1.); -#141532 = DIRECTION('',(6.725593854929E-015,1.)); -#141533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141534 = PCURVE('',#87098,#141535); -#141535 = DEFINITIONAL_REPRESENTATION('',(#141536),#141540); -#141536 = LINE('',#141537,#141538); -#141537 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#141538 = VECTOR('',#141539,1.); -#141539 = DIRECTION('',(0.E+000,1.)); -#141540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141541 = ORIENTED_EDGE('',*,*,#141542,.T.); -#141542 = EDGE_CURVE('',#141515,#141543,#141545,.T.); -#141543 = VERTEX_POINT('',#141544); -#141544 = CARTESIAN_POINT('',(6.15,11.,-0.208196358798)); -#141545 = SURFACE_CURVE('',#141546,(#141550,#141557),.PCURVE_S1.); -#141546 = LINE('',#141547,#141548); -#141547 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#141548 = VECTOR('',#141549,1.); -#141549 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141550 = PCURVE('',#141523,#141551); -#141551 = DEFINITIONAL_REPRESENTATION('',(#141552),#141556); -#141552 = LINE('',#141553,#141554); -#141553 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#141554 = VECTOR('',#141555,1.); -#141555 = DIRECTION('',(-1.,8.881784197001E-016)); -#141556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141557 = PCURVE('',#141558,#141563); -#141558 = PLANE('',#141559); -#141559 = AXIS2_PLACEMENT_3D('',#141560,#141561,#141562); -#141560 = CARTESIAN_POINT('',(6.25,11.,-0.258196742327)); -#141561 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#141562 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#141563 = DEFINITIONAL_REPRESENTATION('',(#141564),#141568); -#141564 = LINE('',#141565,#141566); -#141565 = CARTESIAN_POINT('',(6.25,5.000038352949E-002)); -#141566 = VECTOR('',#141567,1.); -#141567 = DIRECTION('',(1.,1.1653254136E-048)); -#141568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141569 = ORIENTED_EDGE('',*,*,#141570,.F.); -#141570 = EDGE_CURVE('',#141571,#141543,#141573,.T.); -#141571 = VERTEX_POINT('',#141572); -#141572 = CARTESIAN_POINT('',(6.15,10.740726081328,-0.208196358798)); -#141573 = SURFACE_CURVE('',#141574,(#141578,#141585),.PCURVE_S1.); -#141574 = LINE('',#141575,#141576); -#141575 = CARTESIAN_POINT('',(6.15,10.740726081328,-0.208196358798)); -#141576 = VECTOR('',#141577,1.); -#141577 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#141578 = PCURVE('',#141523,#141579); -#141579 = DEFINITIONAL_REPRESENTATION('',(#141580),#141584); -#141580 = LINE('',#141581,#141582); -#141581 = CARTESIAN_POINT('',(6.15,-5.329070518201E-015)); -#141582 = VECTOR('',#141583,1.); -#141583 = DIRECTION('',(6.725593854929E-015,1.)); -#141584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141585 = PCURVE('',#87042,#141586); -#141586 = DEFINITIONAL_REPRESENTATION('',(#141587),#141591); -#141587 = LINE('',#141588,#141589); -#141588 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#141589 = VECTOR('',#141590,1.); -#141590 = DIRECTION('',(0.E+000,1.)); -#141591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141592 = ORIENTED_EDGE('',*,*,#141593,.T.); -#141593 = EDGE_CURVE('',#141571,#141513,#141594,.T.); -#141594 = SURFACE_CURVE('',#141595,(#141599,#141606),.PCURVE_S1.); -#141595 = LINE('',#141596,#141597); -#141596 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#143984 = ORIENTED_EDGE('',*,*,#143985,.T.); +#143985 = EDGE_CURVE('',#143963,#143905,#143986,.T.); +#143986 = SURFACE_CURVE('',#143987,(#143991,#143998),.PCURVE_S1.); +#143987 = LINE('',#143988,#143989); +#143988 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#141597 = VECTOR('',#141598,1.); -#141598 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141599 = PCURVE('',#141523,#141600); -#141600 = DEFINITIONAL_REPRESENTATION('',(#141601),#141605); -#141601 = LINE('',#141602,#141603); -#141602 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141603 = VECTOR('',#141604,1.); -#141604 = DIRECTION('',(1.,-8.881784197001E-016)); -#141605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141606 = PCURVE('',#141607,#141612); -#141607 = CYLINDRICAL_SURFACE('',#141608,0.208574704164); -#141608 = AXIS2_PLACEMENT_3D('',#141609,#141610,#141611); -#141609 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#143989 = VECTOR('',#143990,1.); +#143990 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#143991 = PCURVE('',#143915,#143992); +#143992 = DEFINITIONAL_REPRESENTATION('',(#143993),#143997); +#143993 = LINE('',#143994,#143995); +#143994 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#143995 = VECTOR('',#143996,1.); +#143996 = DIRECTION('',(1.,-8.881784197001E-016)); +#143997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#143998 = PCURVE('',#143999,#144004); +#143999 = CYLINDRICAL_SURFACE('',#144000,0.208574704164); +#144000 = AXIS2_PLACEMENT_3D('',#144001,#144002,#144003); +#144001 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#141610 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141611 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141612 = DEFINITIONAL_REPRESENTATION('',(#141613),#141616); -#141613 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141614,#141615), +#144002 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144003 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144004 = DEFINITIONAL_REPRESENTATION('',(#144005),#144008); +#144005 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144006,#144007), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#141614 = CARTESIAN_POINT('',(4.772630242227,6.15)); -#141615 = CARTESIAN_POINT('',(4.772630242227,6.35)); -#141616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141617 = ADVANCED_FACE('',(#141618),#141632,.T.); -#141618 = FACE_BOUND('',#141619,.T.); -#141619 = EDGE_LOOP('',(#141620,#141650,#141673,#141696)); -#141620 = ORIENTED_EDGE('',*,*,#141621,.T.); -#141621 = EDGE_CURVE('',#141622,#141624,#141626,.T.); -#141622 = VERTEX_POINT('',#141623); -#141623 = CARTESIAN_POINT('',(6.15,10.74341632541,-0.308197125857)); -#141624 = VERTEX_POINT('',#141625); -#141625 = CARTESIAN_POINT('',(6.15,11.,-0.308197125857)); -#141626 = SURFACE_CURVE('',#141627,(#141631,#141643),.PCURVE_S1.); -#141627 = LINE('',#141628,#141629); -#141628 = CARTESIAN_POINT('',(6.15,10.74341632541,-0.308197125857)); -#141629 = VECTOR('',#141630,1.); -#141630 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#141631 = PCURVE('',#141632,#141637); -#141632 = PLANE('',#141633); -#141633 = AXIS2_PLACEMENT_3D('',#141634,#141635,#141636); -#141634 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#144006 = CARTESIAN_POINT('',(4.772630242227,6.15)); +#144007 = CARTESIAN_POINT('',(4.772630242227,6.35)); +#144008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144009 = ADVANCED_FACE('',(#144010),#144024,.T.); +#144010 = FACE_BOUND('',#144011,.T.); +#144011 = EDGE_LOOP('',(#144012,#144042,#144065,#144088)); +#144012 = ORIENTED_EDGE('',*,*,#144013,.T.); +#144013 = EDGE_CURVE('',#144014,#144016,#144018,.T.); +#144014 = VERTEX_POINT('',#144015); +#144015 = CARTESIAN_POINT('',(6.15,10.74341632541,-0.308197125857)); +#144016 = VERTEX_POINT('',#144017); +#144017 = CARTESIAN_POINT('',(6.15,11.,-0.308197125857)); +#144018 = SURFACE_CURVE('',#144019,(#144023,#144035),.PCURVE_S1.); +#144019 = LINE('',#144020,#144021); +#144020 = CARTESIAN_POINT('',(6.15,10.74341632541,-0.308197125857)); +#144021 = VECTOR('',#144022,1.); +#144022 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#144023 = PCURVE('',#144024,#144029); +#144024 = PLANE('',#144025); +#144025 = AXIS2_PLACEMENT_3D('',#144026,#144027,#144028); +#144026 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#141635 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141636 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#141637 = DEFINITIONAL_REPRESENTATION('',(#141638),#141642); -#141638 = LINE('',#141639,#141640); -#141639 = CARTESIAN_POINT('',(-6.15,-5.329070518201E-015)); -#141640 = VECTOR('',#141641,1.); -#141641 = DIRECTION('',(-6.725593854929E-015,1.)); -#141642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141643 = PCURVE('',#87042,#141644); -#141644 = DEFINITIONAL_REPRESENTATION('',(#141645),#141649); -#141645 = LINE('',#141646,#141647); -#141646 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#141647 = VECTOR('',#141648,1.); -#141648 = DIRECTION('',(0.E+000,1.)); -#141649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141650 = ORIENTED_EDGE('',*,*,#141651,.T.); -#141651 = EDGE_CURVE('',#141624,#141652,#141654,.T.); -#141652 = VERTEX_POINT('',#141653); -#141653 = CARTESIAN_POINT('',(6.35,11.,-0.308197125857)); -#141654 = SURFACE_CURVE('',#141655,(#141659,#141666),.PCURVE_S1.); -#141655 = LINE('',#141656,#141657); -#141656 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#141657 = VECTOR('',#141658,1.); -#141658 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141659 = PCURVE('',#141632,#141660); -#141660 = DEFINITIONAL_REPRESENTATION('',(#141661),#141665); -#141661 = LINE('',#141662,#141663); -#141662 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#141663 = VECTOR('',#141664,1.); -#141664 = DIRECTION('',(-1.,-8.881784197001E-016)); -#141665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141666 = PCURVE('',#141558,#141667); -#141667 = DEFINITIONAL_REPRESENTATION('',(#141668),#141672); -#141668 = LINE('',#141669,#141670); -#141669 = CARTESIAN_POINT('',(6.25,-5.000038352949E-002)); -#141670 = VECTOR('',#141671,1.); -#141671 = DIRECTION('',(-1.,-1.1653254136E-048)); -#141672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141673 = ORIENTED_EDGE('',*,*,#141674,.F.); -#141674 = EDGE_CURVE('',#141675,#141652,#141677,.T.); -#141675 = VERTEX_POINT('',#141676); -#141676 = CARTESIAN_POINT('',(6.35,10.74341632541,-0.308197125857)); -#141677 = SURFACE_CURVE('',#141678,(#141682,#141689),.PCURVE_S1.); -#141678 = LINE('',#141679,#141680); -#141679 = CARTESIAN_POINT('',(6.35,10.74341632541,-0.308197125857)); -#141680 = VECTOR('',#141681,1.); -#141681 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#141682 = PCURVE('',#141632,#141683); -#141683 = DEFINITIONAL_REPRESENTATION('',(#141684),#141688); -#141684 = LINE('',#141685,#141686); -#141685 = CARTESIAN_POINT('',(-6.35,-5.329070518201E-015)); -#141686 = VECTOR('',#141687,1.); -#141687 = DIRECTION('',(-6.725593854929E-015,1.)); -#141688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141689 = PCURVE('',#87098,#141690); -#141690 = DEFINITIONAL_REPRESENTATION('',(#141691),#141695); -#141691 = LINE('',#141692,#141693); -#141692 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#141693 = VECTOR('',#141694,1.); -#141694 = DIRECTION('',(0.E+000,1.)); -#141695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141696 = ORIENTED_EDGE('',*,*,#141697,.T.); -#141697 = EDGE_CURVE('',#141675,#141622,#141698,.T.); -#141698 = SURFACE_CURVE('',#141699,(#141703,#141710),.PCURVE_S1.); -#141699 = LINE('',#141700,#141701); -#141700 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#144027 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144028 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#144029 = DEFINITIONAL_REPRESENTATION('',(#144030),#144034); +#144030 = LINE('',#144031,#144032); +#144031 = CARTESIAN_POINT('',(-6.15,-5.329070518201E-015)); +#144032 = VECTOR('',#144033,1.); +#144033 = DIRECTION('',(-6.725593854929E-015,1.)); +#144034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144035 = PCURVE('',#89434,#144036); +#144036 = DEFINITIONAL_REPRESENTATION('',(#144037),#144041); +#144037 = LINE('',#144038,#144039); +#144038 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#144039 = VECTOR('',#144040,1.); +#144040 = DIRECTION('',(0.E+000,1.)); +#144041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144042 = ORIENTED_EDGE('',*,*,#144043,.T.); +#144043 = EDGE_CURVE('',#144016,#144044,#144046,.T.); +#144044 = VERTEX_POINT('',#144045); +#144045 = CARTESIAN_POINT('',(6.35,11.,-0.308197125857)); +#144046 = SURFACE_CURVE('',#144047,(#144051,#144058),.PCURVE_S1.); +#144047 = LINE('',#144048,#144049); +#144048 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#144049 = VECTOR('',#144050,1.); +#144050 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144051 = PCURVE('',#144024,#144052); +#144052 = DEFINITIONAL_REPRESENTATION('',(#144053),#144057); +#144053 = LINE('',#144054,#144055); +#144054 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#144055 = VECTOR('',#144056,1.); +#144056 = DIRECTION('',(-1.,-8.881784197001E-016)); +#144057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144058 = PCURVE('',#143950,#144059); +#144059 = DEFINITIONAL_REPRESENTATION('',(#144060),#144064); +#144060 = LINE('',#144061,#144062); +#144061 = CARTESIAN_POINT('',(6.25,-5.000038352949E-002)); +#144062 = VECTOR('',#144063,1.); +#144063 = DIRECTION('',(-1.,-1.1653254136E-048)); +#144064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144065 = ORIENTED_EDGE('',*,*,#144066,.F.); +#144066 = EDGE_CURVE('',#144067,#144044,#144069,.T.); +#144067 = VERTEX_POINT('',#144068); +#144068 = CARTESIAN_POINT('',(6.35,10.74341632541,-0.308197125857)); +#144069 = SURFACE_CURVE('',#144070,(#144074,#144081),.PCURVE_S1.); +#144070 = LINE('',#144071,#144072); +#144071 = CARTESIAN_POINT('',(6.35,10.74341632541,-0.308197125857)); +#144072 = VECTOR('',#144073,1.); +#144073 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#144074 = PCURVE('',#144024,#144075); +#144075 = DEFINITIONAL_REPRESENTATION('',(#144076),#144080); +#144076 = LINE('',#144077,#144078); +#144077 = CARTESIAN_POINT('',(-6.35,-5.329070518201E-015)); +#144078 = VECTOR('',#144079,1.); +#144079 = DIRECTION('',(-6.725593854929E-015,1.)); +#144080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144081 = PCURVE('',#89490,#144082); +#144082 = DEFINITIONAL_REPRESENTATION('',(#144083),#144087); +#144083 = LINE('',#144084,#144085); +#144084 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#144085 = VECTOR('',#144086,1.); +#144086 = DIRECTION('',(0.E+000,1.)); +#144087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144088 = ORIENTED_EDGE('',*,*,#144089,.T.); +#144089 = EDGE_CURVE('',#144067,#144014,#144090,.T.); +#144090 = SURFACE_CURVE('',#144091,(#144095,#144102),.PCURVE_S1.); +#144091 = LINE('',#144092,#144093); +#144092 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#141701 = VECTOR('',#141702,1.); -#141702 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141703 = PCURVE('',#141632,#141704); -#141704 = DEFINITIONAL_REPRESENTATION('',(#141705),#141709); -#141705 = LINE('',#141706,#141707); -#141706 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141707 = VECTOR('',#141708,1.); -#141708 = DIRECTION('',(1.,8.881784197001E-016)); -#141709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141710 = PCURVE('',#141711,#141716); -#141711 = CYLINDRICAL_SURFACE('',#141712,0.308574064194); -#141712 = AXIS2_PLACEMENT_3D('',#141713,#141714,#141715); -#141713 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#144093 = VECTOR('',#144094,1.); +#144094 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144095 = PCURVE('',#144024,#144096); +#144096 = DEFINITIONAL_REPRESENTATION('',(#144097),#144101); +#144097 = LINE('',#144098,#144099); +#144098 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144099 = VECTOR('',#144100,1.); +#144100 = DIRECTION('',(1.,8.881784197001E-016)); +#144101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144102 = PCURVE('',#144103,#144108); +#144103 = CYLINDRICAL_SURFACE('',#144104,0.308574064194); +#144104 = AXIS2_PLACEMENT_3D('',#144105,#144106,#144107); +#144105 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#141714 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141715 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141716 = DEFINITIONAL_REPRESENTATION('',(#141717),#141720); -#141717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141718,#141719), +#144106 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144107 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144108 = DEFINITIONAL_REPRESENTATION('',(#144109),#144112); +#144109 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144110,#144111), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#141718 = CARTESIAN_POINT('',(4.761821717947,6.35)); -#141719 = CARTESIAN_POINT('',(4.761821717947,6.15)); -#141720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141721 = ADVANCED_FACE('',(#141722),#141607,.F.); -#141722 = FACE_BOUND('',#141723,.F.); -#141723 = EDGE_LOOP('',(#141724,#141725,#141752,#141779)); -#141724 = ORIENTED_EDGE('',*,*,#141593,.T.); -#141725 = ORIENTED_EDGE('',*,*,#141726,.F.); -#141726 = EDGE_CURVE('',#141727,#141513,#141729,.T.); -#141727 = VERTEX_POINT('',#141728); -#141728 = CARTESIAN_POINT('',(6.35,10.51959417205,0.E+000)); -#141729 = SURFACE_CURVE('',#141730,(#141735,#141741),.PCURVE_S1.); -#141730 = CIRCLE('',#141731,0.208574704164); -#141731 = AXIS2_PLACEMENT_3D('',#141732,#141733,#141734); -#141732 = CARTESIAN_POINT('',(6.35,10.728168876214,2.640924866458E-017) - ); -#141733 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141734 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141735 = PCURVE('',#141607,#141736); -#141736 = DEFINITIONAL_REPRESENTATION('',(#141737),#141740); -#141737 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141738,#141739), +#144110 = CARTESIAN_POINT('',(4.761821717947,6.35)); +#144111 = CARTESIAN_POINT('',(4.761821717947,6.15)); +#144112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144113 = ADVANCED_FACE('',(#144114),#143999,.F.); +#144114 = FACE_BOUND('',#144115,.F.); +#144115 = EDGE_LOOP('',(#144116,#144117,#144144,#144171)); +#144116 = ORIENTED_EDGE('',*,*,#143985,.T.); +#144117 = ORIENTED_EDGE('',*,*,#144118,.F.); +#144118 = EDGE_CURVE('',#144119,#143905,#144121,.T.); +#144119 = VERTEX_POINT('',#144120); +#144120 = CARTESIAN_POINT('',(6.35,10.51959417205,0.E+000)); +#144121 = SURFACE_CURVE('',#144122,(#144127,#144133),.PCURVE_S1.); +#144122 = CIRCLE('',#144123,0.208574704164); +#144123 = AXIS2_PLACEMENT_3D('',#144124,#144125,#144126); +#144124 = CARTESIAN_POINT('',(6.35,10.728168876214,2.640924866458E-017) + ); +#144125 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144126 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144127 = PCURVE('',#143999,#144128); +#144128 = DEFINITIONAL_REPRESENTATION('',(#144129),#144132); +#144129 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144130,#144131), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#141738 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#141739 = CARTESIAN_POINT('',(4.772630242227,6.35)); -#141740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#144130 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#144131 = CARTESIAN_POINT('',(4.772630242227,6.35)); +#144132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#141741 = PCURVE('',#87098,#141742); -#141742 = DEFINITIONAL_REPRESENTATION('',(#141743),#141751); -#141743 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141744,#141745,#141746, - #141747,#141748,#141749,#141750),.UNSPECIFIED.,.T.,.F.) +#144133 = PCURVE('',#89490,#144134); +#144134 = DEFINITIONAL_REPRESENTATION('',(#144135),#144143); +#144135 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144136,#144137,#144138, + #144139,#144140,#144141,#144142),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#141744 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#141745 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#141746 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#141747 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#141748 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#141749 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#141750 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#141751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141752 = ORIENTED_EDGE('',*,*,#141753,.T.); -#141753 = EDGE_CURVE('',#141727,#141754,#141756,.T.); -#141754 = VERTEX_POINT('',#141755); -#141755 = CARTESIAN_POINT('',(6.15,10.51959417205,0.E+000)); -#141756 = SURFACE_CURVE('',#141757,(#141761,#141767),.PCURVE_S1.); -#141757 = LINE('',#141758,#141759); -#141758 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#144136 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#144137 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#144138 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#144139 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#144140 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#144141 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#144142 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#144143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144144 = ORIENTED_EDGE('',*,*,#144145,.T.); +#144145 = EDGE_CURVE('',#144119,#144146,#144148,.T.); +#144146 = VERTEX_POINT('',#144147); +#144147 = CARTESIAN_POINT('',(6.15,10.51959417205,0.E+000)); +#144148 = SURFACE_CURVE('',#144149,(#144153,#144159),.PCURVE_S1.); +#144149 = LINE('',#144150,#144151); +#144150 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#141759 = VECTOR('',#141760,1.); -#141760 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141761 = PCURVE('',#141607,#141762); -#141762 = DEFINITIONAL_REPRESENTATION('',(#141763),#141766); -#141763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141764,#141765), +#144151 = VECTOR('',#144152,1.); +#144152 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144153 = PCURVE('',#143999,#144154); +#144154 = DEFINITIONAL_REPRESENTATION('',(#144155),#144158); +#144155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144156,#144157), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#141764 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#141765 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#141766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#144156 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#144157 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#144158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#141767 = PCURVE('',#141768,#141773); -#141768 = PLANE('',#141769); -#141769 = AXIS2_PLACEMENT_3D('',#141770,#141771,#141772); -#141770 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#144159 = PCURVE('',#144160,#144165); +#144160 = PLANE('',#144161); +#144161 = AXIS2_PLACEMENT_3D('',#144162,#144163,#144164); +#144162 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#141771 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141772 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141773 = DEFINITIONAL_REPRESENTATION('',(#141774),#141778); -#141774 = LINE('',#141775,#141776); -#141775 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#141776 = VECTOR('',#141777,1.); -#141777 = DIRECTION('',(-1.,0.E+000)); -#141778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141779 = ORIENTED_EDGE('',*,*,#141780,.T.); -#141780 = EDGE_CURVE('',#141754,#141571,#141781,.T.); -#141781 = SURFACE_CURVE('',#141782,(#141787,#141793),.PCURVE_S1.); -#141782 = CIRCLE('',#141783,0.208574704164); -#141783 = AXIS2_PLACEMENT_3D('',#141784,#141785,#141786); -#141784 = CARTESIAN_POINT('',(6.15,10.728168876214,2.640924866458E-017) - ); -#141785 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141786 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141787 = PCURVE('',#141607,#141788); -#141788 = DEFINITIONAL_REPRESENTATION('',(#141789),#141792); -#141789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141790,#141791), +#144163 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144164 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144165 = DEFINITIONAL_REPRESENTATION('',(#144166),#144170); +#144166 = LINE('',#144167,#144168); +#144167 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#144168 = VECTOR('',#144169,1.); +#144169 = DIRECTION('',(-1.,0.E+000)); +#144170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144171 = ORIENTED_EDGE('',*,*,#144172,.T.); +#144172 = EDGE_CURVE('',#144146,#143963,#144173,.T.); +#144173 = SURFACE_CURVE('',#144174,(#144179,#144185),.PCURVE_S1.); +#144174 = CIRCLE('',#144175,0.208574704164); +#144175 = AXIS2_PLACEMENT_3D('',#144176,#144177,#144178); +#144176 = CARTESIAN_POINT('',(6.15,10.728168876214,2.640924866458E-017) + ); +#144177 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144178 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144179 = PCURVE('',#143999,#144180); +#144180 = DEFINITIONAL_REPRESENTATION('',(#144181),#144184); +#144181 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144182,#144183), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#141790 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#141791 = CARTESIAN_POINT('',(4.772630242227,6.15)); -#141792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141793 = PCURVE('',#87042,#141794); -#141794 = DEFINITIONAL_REPRESENTATION('',(#141795),#141799); -#141795 = CIRCLE('',#141796,0.208574704164); -#141796 = AXIS2_PLACEMENT_2D('',#141797,#141798); -#141797 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#141798 = DIRECTION('',(0.E+000,1.)); -#141799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141800 = ADVANCED_FACE('',(#141801),#141711,.T.); -#141801 = FACE_BOUND('',#141802,.T.); -#141802 = EDGE_LOOP('',(#141803,#141804,#141854,#141881)); -#141803 = ORIENTED_EDGE('',*,*,#141697,.F.); -#141804 = ORIENTED_EDGE('',*,*,#141805,.F.); -#141805 = EDGE_CURVE('',#141806,#141675,#141808,.T.); -#141806 = VERTEX_POINT('',#141807); -#141807 = CARTESIAN_POINT('',(6.35,10.419594812019,0.E+000)); -#141808 = SURFACE_CURVE('',#141809,(#141814,#141843),.PCURVE_S1.); -#141809 = CIRCLE('',#141810,0.308574064194); -#141810 = AXIS2_PLACEMENT_3D('',#141811,#141812,#141813); -#141811 = CARTESIAN_POINT('',(6.35,10.728168876214,2.640924866458E-017) - ); -#141812 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141813 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141814 = PCURVE('',#141711,#141815); -#141815 = DEFINITIONAL_REPRESENTATION('',(#141816),#141842); -#141816 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141817,#141818,#141819, - #141820,#141821,#141822,#141823,#141824,#141825,#141826,#141827, - #141828,#141829,#141830,#141831,#141832,#141833,#141834,#141835, - #141836,#141837,#141838,#141839,#141840,#141841),.UNSPECIFIED.,.F., +#144182 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#144183 = CARTESIAN_POINT('',(4.772630242227,6.15)); +#144184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144185 = PCURVE('',#89434,#144186); +#144186 = DEFINITIONAL_REPRESENTATION('',(#144187),#144191); +#144187 = CIRCLE('',#144188,0.208574704164); +#144188 = AXIS2_PLACEMENT_2D('',#144189,#144190); +#144189 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#144190 = DIRECTION('',(0.E+000,1.)); +#144191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144192 = ADVANCED_FACE('',(#144193),#144103,.T.); +#144193 = FACE_BOUND('',#144194,.T.); +#144194 = EDGE_LOOP('',(#144195,#144196,#144246,#144273)); +#144195 = ORIENTED_EDGE('',*,*,#144089,.F.); +#144196 = ORIENTED_EDGE('',*,*,#144197,.F.); +#144197 = EDGE_CURVE('',#144198,#144067,#144200,.T.); +#144198 = VERTEX_POINT('',#144199); +#144199 = CARTESIAN_POINT('',(6.35,10.419594812019,0.E+000)); +#144200 = SURFACE_CURVE('',#144201,(#144206,#144235),.PCURVE_S1.); +#144201 = CIRCLE('',#144202,0.308574064194); +#144202 = AXIS2_PLACEMENT_3D('',#144203,#144204,#144205); +#144203 = CARTESIAN_POINT('',(6.35,10.728168876214,2.640924866458E-017) + ); +#144204 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144205 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144206 = PCURVE('',#144103,#144207); +#144207 = DEFINITIONAL_REPRESENTATION('',(#144208),#144234); +#144208 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144209,#144210,#144211, + #144212,#144213,#144214,#144215,#144216,#144217,#144218,#144219, + #144220,#144221,#144222,#144223,#144224,#144225,#144226,#144227, + #144228,#144229,#144230,#144231,#144232,#144233),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -174827,102 +177829,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#141817 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#141818 = CARTESIAN_POINT('',(3.166141578807,6.35)); -#141819 = CARTESIAN_POINT('',(3.215239429242,6.35)); -#141820 = CARTESIAN_POINT('',(3.288886204895,6.35)); -#141821 = CARTESIAN_POINT('',(3.362532980548,6.35)); -#141822 = CARTESIAN_POINT('',(3.4361797562,6.35)); -#141823 = CARTESIAN_POINT('',(3.509826531853,6.35)); -#141824 = CARTESIAN_POINT('',(3.583473307505,6.35)); -#141825 = CARTESIAN_POINT('',(3.657120083158,6.35)); -#141826 = CARTESIAN_POINT('',(3.730766858811,6.35)); -#141827 = CARTESIAN_POINT('',(3.804413634463,6.35)); -#141828 = CARTESIAN_POINT('',(3.878060410116,6.35)); -#141829 = CARTESIAN_POINT('',(3.951707185768,6.35)); -#141830 = CARTESIAN_POINT('',(4.025353961421,6.35)); -#141831 = CARTESIAN_POINT('',(4.099000737074,6.35)); -#141832 = CARTESIAN_POINT('',(4.172647512726,6.35)); -#141833 = CARTESIAN_POINT('',(4.246294288379,6.35)); -#141834 = CARTESIAN_POINT('',(4.319941064031,6.35)); -#141835 = CARTESIAN_POINT('',(4.393587839684,6.35)); -#141836 = CARTESIAN_POINT('',(4.467234615337,6.35)); -#141837 = CARTESIAN_POINT('',(4.540881390989,6.35)); -#141838 = CARTESIAN_POINT('',(4.614528166642,6.35)); -#141839 = CARTESIAN_POINT('',(4.688174942294,6.35)); -#141840 = CARTESIAN_POINT('',(4.737272792729,6.35)); -#141841 = CARTESIAN_POINT('',(4.761821717947,6.35)); -#141842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141843 = PCURVE('',#87098,#141844); -#141844 = DEFINITIONAL_REPRESENTATION('',(#141845),#141853); -#141845 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#141846,#141847,#141848, - #141849,#141850,#141851,#141852),.UNSPECIFIED.,.T.,.F.) +#144209 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#144210 = CARTESIAN_POINT('',(3.166141578807,6.35)); +#144211 = CARTESIAN_POINT('',(3.215239429242,6.35)); +#144212 = CARTESIAN_POINT('',(3.288886204895,6.35)); +#144213 = CARTESIAN_POINT('',(3.362532980548,6.35)); +#144214 = CARTESIAN_POINT('',(3.4361797562,6.35)); +#144215 = CARTESIAN_POINT('',(3.509826531853,6.35)); +#144216 = CARTESIAN_POINT('',(3.583473307505,6.35)); +#144217 = CARTESIAN_POINT('',(3.657120083158,6.35)); +#144218 = CARTESIAN_POINT('',(3.730766858811,6.35)); +#144219 = CARTESIAN_POINT('',(3.804413634463,6.35)); +#144220 = CARTESIAN_POINT('',(3.878060410116,6.35)); +#144221 = CARTESIAN_POINT('',(3.951707185768,6.35)); +#144222 = CARTESIAN_POINT('',(4.025353961421,6.35)); +#144223 = CARTESIAN_POINT('',(4.099000737074,6.35)); +#144224 = CARTESIAN_POINT('',(4.172647512726,6.35)); +#144225 = CARTESIAN_POINT('',(4.246294288379,6.35)); +#144226 = CARTESIAN_POINT('',(4.319941064031,6.35)); +#144227 = CARTESIAN_POINT('',(4.393587839684,6.35)); +#144228 = CARTESIAN_POINT('',(4.467234615337,6.35)); +#144229 = CARTESIAN_POINT('',(4.540881390989,6.35)); +#144230 = CARTESIAN_POINT('',(4.614528166642,6.35)); +#144231 = CARTESIAN_POINT('',(4.688174942294,6.35)); +#144232 = CARTESIAN_POINT('',(4.737272792729,6.35)); +#144233 = CARTESIAN_POINT('',(4.761821717947,6.35)); +#144234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144235 = PCURVE('',#89490,#144236); +#144236 = DEFINITIONAL_REPRESENTATION('',(#144237),#144245); +#144237 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144238,#144239,#144240, + #144241,#144242,#144243,#144244),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#141846 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#141847 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#141848 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#141849 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#141850 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#141851 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#141852 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#141853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141854 = ORIENTED_EDGE('',*,*,#141855,.F.); -#141855 = EDGE_CURVE('',#141856,#141806,#141858,.T.); -#141856 = VERTEX_POINT('',#141857); -#141857 = CARTESIAN_POINT('',(6.15,10.419594812019,0.E+000)); -#141858 = SURFACE_CURVE('',#141859,(#141863,#141869),.PCURVE_S1.); -#141859 = LINE('',#141860,#141861); -#141860 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#144238 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#144239 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#144240 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#144241 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#144242 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#144243 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#144244 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#144245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144246 = ORIENTED_EDGE('',*,*,#144247,.F.); +#144247 = EDGE_CURVE('',#144248,#144198,#144250,.T.); +#144248 = VERTEX_POINT('',#144249); +#144249 = CARTESIAN_POINT('',(6.15,10.419594812019,0.E+000)); +#144250 = SURFACE_CURVE('',#144251,(#144255,#144261),.PCURVE_S1.); +#144251 = LINE('',#144252,#144253); +#144252 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#141861 = VECTOR('',#141862,1.); -#141862 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141863 = PCURVE('',#141711,#141864); -#141864 = DEFINITIONAL_REPRESENTATION('',(#141865),#141868); -#141865 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141866,#141867), +#144253 = VECTOR('',#144254,1.); +#144254 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144255 = PCURVE('',#144103,#144256); +#144256 = DEFINITIONAL_REPRESENTATION('',(#144257),#144260); +#144257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144258,#144259), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#141866 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#141867 = CARTESIAN_POINT('',(3.14159265359,6.35)); -#141868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#144258 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#144259 = CARTESIAN_POINT('',(3.14159265359,6.35)); +#144260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#141869 = PCURVE('',#141870,#141875); -#141870 = PLANE('',#141871); -#141871 = AXIS2_PLACEMENT_3D('',#141872,#141873,#141874); -#141872 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#144261 = PCURVE('',#144262,#144267); +#144262 = PLANE('',#144263); +#144263 = AXIS2_PLACEMENT_3D('',#144264,#144265,#144266); +#144264 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#141873 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141874 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141875 = DEFINITIONAL_REPRESENTATION('',(#141876),#141880); -#141876 = LINE('',#141877,#141878); -#141877 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#141878 = VECTOR('',#141879,1.); -#141879 = DIRECTION('',(-1.,0.E+000)); -#141880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141881 = ORIENTED_EDGE('',*,*,#141882,.T.); -#141882 = EDGE_CURVE('',#141856,#141622,#141883,.T.); -#141883 = SURFACE_CURVE('',#141884,(#141889,#141918),.PCURVE_S1.); -#141884 = CIRCLE('',#141885,0.308574064194); -#141885 = AXIS2_PLACEMENT_3D('',#141886,#141887,#141888); -#141886 = CARTESIAN_POINT('',(6.15,10.728168876214,2.640924866458E-017) - ); -#141887 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141888 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#141889 = PCURVE('',#141711,#141890); -#141890 = DEFINITIONAL_REPRESENTATION('',(#141891),#141917); -#141891 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#141892,#141893,#141894, - #141895,#141896,#141897,#141898,#141899,#141900,#141901,#141902, - #141903,#141904,#141905,#141906,#141907,#141908,#141909,#141910, - #141911,#141912,#141913,#141914,#141915,#141916),.UNSPECIFIED.,.F., +#144265 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144266 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144267 = DEFINITIONAL_REPRESENTATION('',(#144268),#144272); +#144268 = LINE('',#144269,#144270); +#144269 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#144270 = VECTOR('',#144271,1.); +#144271 = DIRECTION('',(-1.,0.E+000)); +#144272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144273 = ORIENTED_EDGE('',*,*,#144274,.T.); +#144274 = EDGE_CURVE('',#144248,#144014,#144275,.T.); +#144275 = SURFACE_CURVE('',#144276,(#144281,#144310),.PCURVE_S1.); +#144276 = CIRCLE('',#144277,0.308574064194); +#144277 = AXIS2_PLACEMENT_3D('',#144278,#144279,#144280); +#144278 = CARTESIAN_POINT('',(6.15,10.728168876214,2.640924866458E-017) + ); +#144279 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144280 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144281 = PCURVE('',#144103,#144282); +#144282 = DEFINITIONAL_REPRESENTATION('',(#144283),#144309); +#144283 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144284,#144285,#144286, + #144287,#144288,#144289,#144290,#144291,#144292,#144293,#144294, + #144295,#144296,#144297,#144298,#144299,#144300,#144301,#144302, + #144303,#144304,#144305,#144306,#144307,#144308),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -174930,339 +177932,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#141892 = CARTESIAN_POINT('',(3.14159265359,6.15)); -#141893 = CARTESIAN_POINT('',(3.166141578807,6.15)); -#141894 = CARTESIAN_POINT('',(3.215239429242,6.15)); -#141895 = CARTESIAN_POINT('',(3.288886204895,6.15)); -#141896 = CARTESIAN_POINT('',(3.362532980548,6.15)); -#141897 = CARTESIAN_POINT('',(3.4361797562,6.15)); -#141898 = CARTESIAN_POINT('',(3.509826531853,6.15)); -#141899 = CARTESIAN_POINT('',(3.583473307505,6.15)); -#141900 = CARTESIAN_POINT('',(3.657120083158,6.15)); -#141901 = CARTESIAN_POINT('',(3.730766858811,6.15)); -#141902 = CARTESIAN_POINT('',(3.804413634463,6.15)); -#141903 = CARTESIAN_POINT('',(3.878060410116,6.15)); -#141904 = CARTESIAN_POINT('',(3.951707185768,6.15)); -#141905 = CARTESIAN_POINT('',(4.025353961421,6.15)); -#141906 = CARTESIAN_POINT('',(4.099000737074,6.15)); -#141907 = CARTESIAN_POINT('',(4.172647512726,6.15)); -#141908 = CARTESIAN_POINT('',(4.246294288379,6.15)); -#141909 = CARTESIAN_POINT('',(4.319941064031,6.15)); -#141910 = CARTESIAN_POINT('',(4.393587839684,6.15)); -#141911 = CARTESIAN_POINT('',(4.467234615337,6.15)); -#141912 = CARTESIAN_POINT('',(4.540881390989,6.15)); -#141913 = CARTESIAN_POINT('',(4.614528166642,6.15)); -#141914 = CARTESIAN_POINT('',(4.688174942294,6.15)); -#141915 = CARTESIAN_POINT('',(4.737272792729,6.15)); -#141916 = CARTESIAN_POINT('',(4.761821717947,6.15)); -#141917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141918 = PCURVE('',#87042,#141919); -#141919 = DEFINITIONAL_REPRESENTATION('',(#141920),#141924); -#141920 = CIRCLE('',#141921,0.308574064194); -#141921 = AXIS2_PLACEMENT_2D('',#141922,#141923); -#141922 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#141923 = DIRECTION('',(0.E+000,1.)); -#141924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141925 = ADVANCED_FACE('',(#141926),#141870,.F.); -#141926 = FACE_BOUND('',#141927,.T.); -#141927 = EDGE_LOOP('',(#141928,#141957,#141978,#141979)); -#141928 = ORIENTED_EDGE('',*,*,#141929,.F.); -#141929 = EDGE_CURVE('',#141930,#141932,#141934,.T.); -#141930 = VERTEX_POINT('',#141931); -#141931 = CARTESIAN_POINT('',(6.15,10.419594812019,0.530776333563)); -#141932 = VERTEX_POINT('',#141933); -#141933 = CARTESIAN_POINT('',(6.35,10.419594812019,0.530776333563)); -#141934 = SURFACE_CURVE('',#141935,(#141939,#141946),.PCURVE_S1.); -#141935 = LINE('',#141936,#141937); -#141936 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#144284 = CARTESIAN_POINT('',(3.14159265359,6.15)); +#144285 = CARTESIAN_POINT('',(3.166141578807,6.15)); +#144286 = CARTESIAN_POINT('',(3.215239429242,6.15)); +#144287 = CARTESIAN_POINT('',(3.288886204895,6.15)); +#144288 = CARTESIAN_POINT('',(3.362532980548,6.15)); +#144289 = CARTESIAN_POINT('',(3.4361797562,6.15)); +#144290 = CARTESIAN_POINT('',(3.509826531853,6.15)); +#144291 = CARTESIAN_POINT('',(3.583473307505,6.15)); +#144292 = CARTESIAN_POINT('',(3.657120083158,6.15)); +#144293 = CARTESIAN_POINT('',(3.730766858811,6.15)); +#144294 = CARTESIAN_POINT('',(3.804413634463,6.15)); +#144295 = CARTESIAN_POINT('',(3.878060410116,6.15)); +#144296 = CARTESIAN_POINT('',(3.951707185768,6.15)); +#144297 = CARTESIAN_POINT('',(4.025353961421,6.15)); +#144298 = CARTESIAN_POINT('',(4.099000737074,6.15)); +#144299 = CARTESIAN_POINT('',(4.172647512726,6.15)); +#144300 = CARTESIAN_POINT('',(4.246294288379,6.15)); +#144301 = CARTESIAN_POINT('',(4.319941064031,6.15)); +#144302 = CARTESIAN_POINT('',(4.393587839684,6.15)); +#144303 = CARTESIAN_POINT('',(4.467234615337,6.15)); +#144304 = CARTESIAN_POINT('',(4.540881390989,6.15)); +#144305 = CARTESIAN_POINT('',(4.614528166642,6.15)); +#144306 = CARTESIAN_POINT('',(4.688174942294,6.15)); +#144307 = CARTESIAN_POINT('',(4.737272792729,6.15)); +#144308 = CARTESIAN_POINT('',(4.761821717947,6.15)); +#144309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144310 = PCURVE('',#89434,#144311); +#144311 = DEFINITIONAL_REPRESENTATION('',(#144312),#144316); +#144312 = CIRCLE('',#144313,0.308574064194); +#144313 = AXIS2_PLACEMENT_2D('',#144314,#144315); +#144314 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#144315 = DIRECTION('',(0.E+000,1.)); +#144316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144317 = ADVANCED_FACE('',(#144318),#144262,.F.); +#144318 = FACE_BOUND('',#144319,.T.); +#144319 = EDGE_LOOP('',(#144320,#144349,#144370,#144371)); +#144320 = ORIENTED_EDGE('',*,*,#144321,.F.); +#144321 = EDGE_CURVE('',#144322,#144324,#144326,.T.); +#144322 = VERTEX_POINT('',#144323); +#144323 = CARTESIAN_POINT('',(6.15,10.419594812019,0.530776333563)); +#144324 = VERTEX_POINT('',#144325); +#144325 = CARTESIAN_POINT('',(6.35,10.419594812019,0.530776333563)); +#144326 = SURFACE_CURVE('',#144327,(#144331,#144338),.PCURVE_S1.); +#144327 = LINE('',#144328,#144329); +#144328 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#141937 = VECTOR('',#141938,1.); -#141938 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#141939 = PCURVE('',#141870,#141940); -#141940 = DEFINITIONAL_REPRESENTATION('',(#141941),#141945); -#141941 = LINE('',#141942,#141943); -#141942 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#141943 = VECTOR('',#141944,1.); -#141944 = DIRECTION('',(-1.,0.E+000)); -#141945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141946 = PCURVE('',#141947,#141952); -#141947 = CYLINDRICAL_SURFACE('',#141948,0.119270391569); -#141948 = AXIS2_PLACEMENT_3D('',#141949,#141950,#141951); -#141949 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#144329 = VECTOR('',#144330,1.); +#144330 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144331 = PCURVE('',#144262,#144332); +#144332 = DEFINITIONAL_REPRESENTATION('',(#144333),#144337); +#144333 = LINE('',#144334,#144335); +#144334 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144335 = VECTOR('',#144336,1.); +#144336 = DIRECTION('',(-1.,0.E+000)); +#144337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144338 = PCURVE('',#144339,#144344); +#144339 = CYLINDRICAL_SURFACE('',#144340,0.119270391569); +#144340 = AXIS2_PLACEMENT_3D('',#144341,#144342,#144343); +#144341 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#141950 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#141951 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#141952 = DEFINITIONAL_REPRESENTATION('',(#141953),#141956); -#141953 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#141954,#141955), +#144342 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144343 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144344 = DEFINITIONAL_REPRESENTATION('',(#144345),#144348); +#144345 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144346,#144347), .UNSPECIFIED.,.F.,.F.,(2,2),(6.15,6.35),.PIECEWISE_BEZIER_KNOTS.); -#141954 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#141955 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#141956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141957 = ORIENTED_EDGE('',*,*,#141958,.T.); -#141958 = EDGE_CURVE('',#141930,#141856,#141959,.T.); -#141959 = SURFACE_CURVE('',#141960,(#141964,#141971),.PCURVE_S1.); -#141960 = LINE('',#141961,#141962); -#141961 = CARTESIAN_POINT('',(6.15,10.419594812019,0.530776333563)); -#141962 = VECTOR('',#141963,1.); -#141963 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141964 = PCURVE('',#141870,#141965); -#141965 = DEFINITIONAL_REPRESENTATION('',(#141966),#141970); -#141966 = LINE('',#141967,#141968); -#141967 = CARTESIAN_POINT('',(-6.15,0.E+000)); -#141968 = VECTOR('',#141969,1.); -#141969 = DIRECTION('',(0.E+000,-1.)); -#141970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141971 = PCURVE('',#87042,#141972); -#141972 = DEFINITIONAL_REPRESENTATION('',(#141973),#141977); -#141973 = LINE('',#141974,#141975); -#141974 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#141975 = VECTOR('',#141976,1.); -#141976 = DIRECTION('',(1.,0.E+000)); -#141977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141978 = ORIENTED_EDGE('',*,*,#141855,.T.); -#141979 = ORIENTED_EDGE('',*,*,#141980,.F.); -#141980 = EDGE_CURVE('',#141932,#141806,#141981,.T.); -#141981 = SURFACE_CURVE('',#141982,(#141986,#141993),.PCURVE_S1.); -#141982 = LINE('',#141983,#141984); -#141983 = CARTESIAN_POINT('',(6.35,10.419594812019,0.530776333563)); -#141984 = VECTOR('',#141985,1.); -#141985 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#141986 = PCURVE('',#141870,#141987); -#141987 = DEFINITIONAL_REPRESENTATION('',(#141988),#141992); -#141988 = LINE('',#141989,#141990); -#141989 = CARTESIAN_POINT('',(-6.35,0.E+000)); -#141990 = VECTOR('',#141991,1.); -#141991 = DIRECTION('',(0.E+000,-1.)); -#141992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#141993 = PCURVE('',#87098,#141994); -#141994 = DEFINITIONAL_REPRESENTATION('',(#141995),#141999); -#141995 = LINE('',#141996,#141997); -#141996 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#141997 = VECTOR('',#141998,1.); -#141998 = DIRECTION('',(-1.,0.E+000)); -#141999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142000 = ADVANCED_FACE('',(#142001),#141768,.F.); -#142001 = FACE_BOUND('',#142002,.T.); -#142002 = EDGE_LOOP('',(#142003,#142032,#142053,#142054)); -#142003 = ORIENTED_EDGE('',*,*,#142004,.F.); -#142004 = EDGE_CURVE('',#142005,#142007,#142009,.T.); -#142005 = VERTEX_POINT('',#142006); -#142006 = CARTESIAN_POINT('',(6.35,10.51959417205,0.530776333563)); -#142007 = VERTEX_POINT('',#142008); -#142008 = CARTESIAN_POINT('',(6.15,10.51959417205,0.530776333563)); -#142009 = SURFACE_CURVE('',#142010,(#142014,#142021),.PCURVE_S1.); -#142010 = LINE('',#142011,#142012); -#142011 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#144346 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#144347 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#144348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144349 = ORIENTED_EDGE('',*,*,#144350,.T.); +#144350 = EDGE_CURVE('',#144322,#144248,#144351,.T.); +#144351 = SURFACE_CURVE('',#144352,(#144356,#144363),.PCURVE_S1.); +#144352 = LINE('',#144353,#144354); +#144353 = CARTESIAN_POINT('',(6.15,10.419594812019,0.530776333563)); +#144354 = VECTOR('',#144355,1.); +#144355 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144356 = PCURVE('',#144262,#144357); +#144357 = DEFINITIONAL_REPRESENTATION('',(#144358),#144362); +#144358 = LINE('',#144359,#144360); +#144359 = CARTESIAN_POINT('',(-6.15,0.E+000)); +#144360 = VECTOR('',#144361,1.); +#144361 = DIRECTION('',(0.E+000,-1.)); +#144362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144363 = PCURVE('',#89434,#144364); +#144364 = DEFINITIONAL_REPRESENTATION('',(#144365),#144369); +#144365 = LINE('',#144366,#144367); +#144366 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#144367 = VECTOR('',#144368,1.); +#144368 = DIRECTION('',(1.,0.E+000)); +#144369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144370 = ORIENTED_EDGE('',*,*,#144247,.T.); +#144371 = ORIENTED_EDGE('',*,*,#144372,.F.); +#144372 = EDGE_CURVE('',#144324,#144198,#144373,.T.); +#144373 = SURFACE_CURVE('',#144374,(#144378,#144385),.PCURVE_S1.); +#144374 = LINE('',#144375,#144376); +#144375 = CARTESIAN_POINT('',(6.35,10.419594812019,0.530776333563)); +#144376 = VECTOR('',#144377,1.); +#144377 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144378 = PCURVE('',#144262,#144379); +#144379 = DEFINITIONAL_REPRESENTATION('',(#144380),#144384); +#144380 = LINE('',#144381,#144382); +#144381 = CARTESIAN_POINT('',(-6.35,0.E+000)); +#144382 = VECTOR('',#144383,1.); +#144383 = DIRECTION('',(0.E+000,-1.)); +#144384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144385 = PCURVE('',#89490,#144386); +#144386 = DEFINITIONAL_REPRESENTATION('',(#144387),#144391); +#144387 = LINE('',#144388,#144389); +#144388 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#144389 = VECTOR('',#144390,1.); +#144390 = DIRECTION('',(-1.,0.E+000)); +#144391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144392 = ADVANCED_FACE('',(#144393),#144160,.F.); +#144393 = FACE_BOUND('',#144394,.T.); +#144394 = EDGE_LOOP('',(#144395,#144424,#144445,#144446)); +#144395 = ORIENTED_EDGE('',*,*,#144396,.F.); +#144396 = EDGE_CURVE('',#144397,#144399,#144401,.T.); +#144397 = VERTEX_POINT('',#144398); +#144398 = CARTESIAN_POINT('',(6.35,10.51959417205,0.530776333563)); +#144399 = VERTEX_POINT('',#144400); +#144400 = CARTESIAN_POINT('',(6.15,10.51959417205,0.530776333563)); +#144401 = SURFACE_CURVE('',#144402,(#144406,#144413),.PCURVE_S1.); +#144402 = LINE('',#144403,#144404); +#144403 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#142012 = VECTOR('',#142013,1.); -#142013 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142014 = PCURVE('',#141768,#142015); -#142015 = DEFINITIONAL_REPRESENTATION('',(#142016),#142020); -#142016 = LINE('',#142017,#142018); -#142017 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142018 = VECTOR('',#142019,1.); -#142019 = DIRECTION('',(-1.,0.E+000)); -#142020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142021 = PCURVE('',#142022,#142027); -#142022 = CYLINDRICAL_SURFACE('',#142023,0.2192697516); -#142023 = AXIS2_PLACEMENT_3D('',#142024,#142025,#142026); -#142024 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#144404 = VECTOR('',#144405,1.); +#144405 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144406 = PCURVE('',#144160,#144407); +#144407 = DEFINITIONAL_REPRESENTATION('',(#144408),#144412); +#144408 = LINE('',#144409,#144410); +#144409 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144410 = VECTOR('',#144411,1.); +#144411 = DIRECTION('',(-1.,0.E+000)); +#144412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144413 = PCURVE('',#144414,#144419); +#144414 = CYLINDRICAL_SURFACE('',#144415,0.2192697516); +#144415 = AXIS2_PLACEMENT_3D('',#144416,#144417,#144418); +#144416 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#142025 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142026 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142027 = DEFINITIONAL_REPRESENTATION('',(#142028),#142031); -#142028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142029,#142030), +#144417 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144418 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144419 = DEFINITIONAL_REPRESENTATION('',(#144420),#144423); +#144420 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144421,#144422), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.35,-6.15),.PIECEWISE_BEZIER_KNOTS.); -#142029 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#142030 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#142031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142032 = ORIENTED_EDGE('',*,*,#142033,.T.); -#142033 = EDGE_CURVE('',#142005,#141727,#142034,.T.); -#142034 = SURFACE_CURVE('',#142035,(#142039,#142046),.PCURVE_S1.); -#142035 = LINE('',#142036,#142037); -#142036 = CARTESIAN_POINT('',(6.35,10.51959417205,0.530776333563)); -#142037 = VECTOR('',#142038,1.); -#142038 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142039 = PCURVE('',#141768,#142040); -#142040 = DEFINITIONAL_REPRESENTATION('',(#142041),#142045); -#142041 = LINE('',#142042,#142043); -#142042 = CARTESIAN_POINT('',(6.35,0.E+000)); -#142043 = VECTOR('',#142044,1.); -#142044 = DIRECTION('',(0.E+000,-1.)); -#142045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142046 = PCURVE('',#87098,#142047); -#142047 = DEFINITIONAL_REPRESENTATION('',(#142048),#142052); -#142048 = LINE('',#142049,#142050); -#142049 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#142050 = VECTOR('',#142051,1.); -#142051 = DIRECTION('',(-1.,0.E+000)); -#142052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142053 = ORIENTED_EDGE('',*,*,#141753,.T.); -#142054 = ORIENTED_EDGE('',*,*,#142055,.F.); -#142055 = EDGE_CURVE('',#142007,#141754,#142056,.T.); -#142056 = SURFACE_CURVE('',#142057,(#142061,#142068),.PCURVE_S1.); -#142057 = LINE('',#142058,#142059); -#142058 = CARTESIAN_POINT('',(6.15,10.51959417205,0.530776333563)); -#142059 = VECTOR('',#142060,1.); -#142060 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142061 = PCURVE('',#141768,#142062); -#142062 = DEFINITIONAL_REPRESENTATION('',(#142063),#142067); -#142063 = LINE('',#142064,#142065); -#142064 = CARTESIAN_POINT('',(6.15,0.E+000)); -#142065 = VECTOR('',#142066,1.); -#142066 = DIRECTION('',(0.E+000,-1.)); -#142067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142068 = PCURVE('',#87042,#142069); -#142069 = DEFINITIONAL_REPRESENTATION('',(#142070),#142074); -#142070 = LINE('',#142071,#142072); -#142071 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#142072 = VECTOR('',#142073,1.); -#142073 = DIRECTION('',(1.,0.E+000)); -#142074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142075 = ADVANCED_FACE('',(#142076),#141947,.F.); -#142076 = FACE_BOUND('',#142077,.F.); -#142077 = EDGE_LOOP('',(#142078,#142105,#142127,#142148)); -#142078 = ORIENTED_EDGE('',*,*,#142079,.F.); -#142079 = EDGE_CURVE('',#142080,#141930,#142082,.T.); -#142080 = VERTEX_POINT('',#142081); -#142081 = CARTESIAN_POINT('',(6.15,10.303662633502,0.65)); -#142082 = SURFACE_CURVE('',#142083,(#142088,#142094),.PCURVE_S1.); -#142083 = CIRCLE('',#142084,0.119270391569); -#142084 = AXIS2_PLACEMENT_3D('',#142085,#142086,#142087); -#142085 = CARTESIAN_POINT('',(6.15,10.30032442045,0.530776333563)); -#142086 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142087 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142088 = PCURVE('',#141947,#142089); -#142089 = DEFINITIONAL_REPRESENTATION('',(#142090),#142093); -#142090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142091,#142092), +#144421 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#144422 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#144423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144424 = ORIENTED_EDGE('',*,*,#144425,.T.); +#144425 = EDGE_CURVE('',#144397,#144119,#144426,.T.); +#144426 = SURFACE_CURVE('',#144427,(#144431,#144438),.PCURVE_S1.); +#144427 = LINE('',#144428,#144429); +#144428 = CARTESIAN_POINT('',(6.35,10.51959417205,0.530776333563)); +#144429 = VECTOR('',#144430,1.); +#144430 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144431 = PCURVE('',#144160,#144432); +#144432 = DEFINITIONAL_REPRESENTATION('',(#144433),#144437); +#144433 = LINE('',#144434,#144435); +#144434 = CARTESIAN_POINT('',(6.35,0.E+000)); +#144435 = VECTOR('',#144436,1.); +#144436 = DIRECTION('',(0.E+000,-1.)); +#144437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144438 = PCURVE('',#89490,#144439); +#144439 = DEFINITIONAL_REPRESENTATION('',(#144440),#144444); +#144440 = LINE('',#144441,#144442); +#144441 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#144442 = VECTOR('',#144443,1.); +#144443 = DIRECTION('',(-1.,0.E+000)); +#144444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144445 = ORIENTED_EDGE('',*,*,#144145,.T.); +#144446 = ORIENTED_EDGE('',*,*,#144447,.F.); +#144447 = EDGE_CURVE('',#144399,#144146,#144448,.T.); +#144448 = SURFACE_CURVE('',#144449,(#144453,#144460),.PCURVE_S1.); +#144449 = LINE('',#144450,#144451); +#144450 = CARTESIAN_POINT('',(6.15,10.51959417205,0.530776333563)); +#144451 = VECTOR('',#144452,1.); +#144452 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144453 = PCURVE('',#144160,#144454); +#144454 = DEFINITIONAL_REPRESENTATION('',(#144455),#144459); +#144455 = LINE('',#144456,#144457); +#144456 = CARTESIAN_POINT('',(6.15,0.E+000)); +#144457 = VECTOR('',#144458,1.); +#144458 = DIRECTION('',(0.E+000,-1.)); +#144459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144460 = PCURVE('',#89434,#144461); +#144461 = DEFINITIONAL_REPRESENTATION('',(#144462),#144466); +#144462 = LINE('',#144463,#144464); +#144463 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#144464 = VECTOR('',#144465,1.); +#144465 = DIRECTION('',(1.,0.E+000)); +#144466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144467 = ADVANCED_FACE('',(#144468),#144339,.F.); +#144468 = FACE_BOUND('',#144469,.F.); +#144469 = EDGE_LOOP('',(#144470,#144497,#144519,#144540)); +#144470 = ORIENTED_EDGE('',*,*,#144471,.F.); +#144471 = EDGE_CURVE('',#144472,#144322,#144474,.T.); +#144472 = VERTEX_POINT('',#144473); +#144473 = CARTESIAN_POINT('',(6.15,10.303662633502,0.65)); +#144474 = SURFACE_CURVE('',#144475,(#144480,#144486),.PCURVE_S1.); +#144475 = CIRCLE('',#144476,0.119270391569); +#144476 = AXIS2_PLACEMENT_3D('',#144477,#144478,#144479); +#144477 = CARTESIAN_POINT('',(6.15,10.30032442045,0.530776333563)); +#144478 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144479 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144480 = PCURVE('',#144339,#144481); +#144481 = DEFINITIONAL_REPRESENTATION('',(#144482),#144485); +#144482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144483,#144484), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#142091 = CARTESIAN_POINT('',(1.598788597134,-6.15)); -#142092 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#142093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#144483 = CARTESIAN_POINT('',(1.598788597134,-6.15)); +#144484 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#144485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#142094 = PCURVE('',#87042,#142095); -#142095 = DEFINITIONAL_REPRESENTATION('',(#142096),#142104); -#142096 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142097,#142098,#142099, - #142100,#142101,#142102,#142103),.UNSPECIFIED.,.T.,.F.) +#144486 = PCURVE('',#89434,#144487); +#144487 = DEFINITIONAL_REPRESENTATION('',(#144488),#144496); +#144488 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144489,#144490,#144491, + #144492,#144493,#144494,#144495),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#142097 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#142098 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#142099 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#142100 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#142101 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#142102 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#142103 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#142104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142105 = ORIENTED_EDGE('',*,*,#142106,.F.); -#142106 = EDGE_CURVE('',#142107,#142080,#142109,.T.); -#142107 = VERTEX_POINT('',#142108); -#142108 = CARTESIAN_POINT('',(6.35,10.303662633502,0.65)); -#142109 = SURFACE_CURVE('',#142110,(#142114,#142120),.PCURVE_S1.); -#142110 = LINE('',#142111,#142112); -#142111 = CARTESIAN_POINT('',(6.15,10.303662633502,0.65)); -#142112 = VECTOR('',#142113,1.); -#142113 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142114 = PCURVE('',#141947,#142115); -#142115 = DEFINITIONAL_REPRESENTATION('',(#142116),#142119); -#142116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142117,#142118), +#144489 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#144490 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#144491 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#144492 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#144493 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#144494 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#144495 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#144496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144497 = ORIENTED_EDGE('',*,*,#144498,.F.); +#144498 = EDGE_CURVE('',#144499,#144472,#144501,.T.); +#144499 = VERTEX_POINT('',#144500); +#144500 = CARTESIAN_POINT('',(6.35,10.303662633502,0.65)); +#144501 = SURFACE_CURVE('',#144502,(#144506,#144512),.PCURVE_S1.); +#144502 = LINE('',#144503,#144504); +#144503 = CARTESIAN_POINT('',(6.15,10.303662633502,0.65)); +#144504 = VECTOR('',#144505,1.); +#144505 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144506 = PCURVE('',#144339,#144507); +#144507 = DEFINITIONAL_REPRESENTATION('',(#144508),#144511); +#144508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144509,#144510), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#142117 = CARTESIAN_POINT('',(1.598788597134,-6.35)); -#142118 = CARTESIAN_POINT('',(1.598788597134,-6.15)); -#142119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142120 = PCURVE('',#87070,#142121); -#142121 = DEFINITIONAL_REPRESENTATION('',(#142122),#142126); -#142122 = LINE('',#142123,#142124); -#142123 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#142124 = VECTOR('',#142125,1.); -#142125 = DIRECTION('',(-8.881784197001E-016,-1.)); -#142126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142127 = ORIENTED_EDGE('',*,*,#142128,.T.); -#142128 = EDGE_CURVE('',#142107,#141932,#142129,.T.); -#142129 = SURFACE_CURVE('',#142130,(#142135,#142141),.PCURVE_S1.); -#142130 = CIRCLE('',#142131,0.119270391569); -#142131 = AXIS2_PLACEMENT_3D('',#142132,#142133,#142134); -#142132 = CARTESIAN_POINT('',(6.35,10.30032442045,0.530776333563)); -#142133 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142134 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142135 = PCURVE('',#141947,#142136); -#142136 = DEFINITIONAL_REPRESENTATION('',(#142137),#142140); -#142137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142138,#142139), +#144509 = CARTESIAN_POINT('',(1.598788597134,-6.35)); +#144510 = CARTESIAN_POINT('',(1.598788597134,-6.15)); +#144511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144512 = PCURVE('',#89462,#144513); +#144513 = DEFINITIONAL_REPRESENTATION('',(#144514),#144518); +#144514 = LINE('',#144515,#144516); +#144515 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#144516 = VECTOR('',#144517,1.); +#144517 = DIRECTION('',(-8.881784197001E-016,-1.)); +#144518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144519 = ORIENTED_EDGE('',*,*,#144520,.T.); +#144520 = EDGE_CURVE('',#144499,#144324,#144521,.T.); +#144521 = SURFACE_CURVE('',#144522,(#144527,#144533),.PCURVE_S1.); +#144522 = CIRCLE('',#144523,0.119270391569); +#144523 = AXIS2_PLACEMENT_3D('',#144524,#144525,#144526); +#144524 = CARTESIAN_POINT('',(6.35,10.30032442045,0.530776333563)); +#144525 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144526 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144527 = PCURVE('',#144339,#144528); +#144528 = DEFINITIONAL_REPRESENTATION('',(#144529),#144532); +#144529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144530,#144531), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#142138 = CARTESIAN_POINT('',(1.598788597134,-6.35)); -#142139 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#142140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142141 = PCURVE('',#87098,#142142); -#142142 = DEFINITIONAL_REPRESENTATION('',(#142143),#142147); -#142143 = CIRCLE('',#142144,0.119270391569); -#142144 = AXIS2_PLACEMENT_2D('',#142145,#142146); -#142145 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#142146 = DIRECTION('',(0.E+000,-1.)); -#142147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142148 = ORIENTED_EDGE('',*,*,#141929,.F.); -#142149 = ADVANCED_FACE('',(#142150),#142022,.T.); -#142150 = FACE_BOUND('',#142151,.T.); -#142151 = EDGE_LOOP('',(#142152,#142198,#142199,#142249)); -#142152 = ORIENTED_EDGE('',*,*,#142153,.T.); -#142153 = EDGE_CURVE('',#142154,#142005,#142156,.T.); -#142154 = VERTEX_POINT('',#142155); -#142155 = CARTESIAN_POINT('',(6.35,10.304819755875,0.75)); -#142156 = SURFACE_CURVE('',#142157,(#142162,#142191),.PCURVE_S1.); -#142157 = CIRCLE('',#142158,0.2192697516); -#142158 = AXIS2_PLACEMENT_3D('',#142159,#142160,#142161); -#142159 = CARTESIAN_POINT('',(6.35,10.30032442045,0.530776333563)); -#142160 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142161 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142162 = PCURVE('',#142022,#142163); -#142163 = DEFINITIONAL_REPRESENTATION('',(#142164),#142190); -#142164 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142165,#142166,#142167, - #142168,#142169,#142170,#142171,#142172,#142173,#142174,#142175, - #142176,#142177,#142178,#142179,#142180,#142181,#142182,#142183, - #142184,#142185,#142186,#142187,#142188,#142189),.UNSPECIFIED.,.F., +#144530 = CARTESIAN_POINT('',(1.598788597134,-6.35)); +#144531 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#144532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144533 = PCURVE('',#89490,#144534); +#144534 = DEFINITIONAL_REPRESENTATION('',(#144535),#144539); +#144535 = CIRCLE('',#144536,0.119270391569); +#144536 = AXIS2_PLACEMENT_2D('',#144537,#144538); +#144537 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#144538 = DIRECTION('',(0.E+000,-1.)); +#144539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144540 = ORIENTED_EDGE('',*,*,#144321,.F.); +#144541 = ADVANCED_FACE('',(#144542),#144414,.T.); +#144542 = FACE_BOUND('',#144543,.T.); +#144543 = EDGE_LOOP('',(#144544,#144590,#144591,#144641)); +#144544 = ORIENTED_EDGE('',*,*,#144545,.T.); +#144545 = EDGE_CURVE('',#144546,#144397,#144548,.T.); +#144546 = VERTEX_POINT('',#144547); +#144547 = CARTESIAN_POINT('',(6.35,10.304819755875,0.75)); +#144548 = SURFACE_CURVE('',#144549,(#144554,#144583),.PCURVE_S1.); +#144549 = CIRCLE('',#144550,0.2192697516); +#144550 = AXIS2_PLACEMENT_3D('',#144551,#144552,#144553); +#144551 = CARTESIAN_POINT('',(6.35,10.30032442045,0.530776333563)); +#144552 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144553 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144554 = PCURVE('',#144414,#144555); +#144555 = DEFINITIONAL_REPRESENTATION('',(#144556),#144582); +#144556 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144557,#144558,#144559, + #144560,#144561,#144562,#144563,#144564,#144565,#144566,#144567, + #144568,#144569,#144570,#144571,#144572,#144573,#144574,#144575, + #144576,#144577,#144578,#144579,#144580,#144581),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -175270,60 +178272,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#142165 = CARTESIAN_POINT('',(1.591299156552,-6.35)); -#142166 = CARTESIAN_POINT('',(1.614788451962,-6.35)); -#142167 = CARTESIAN_POINT('',(1.661767042781,-6.35)); -#142168 = CARTESIAN_POINT('',(1.73223492901,-6.35)); -#142169 = CARTESIAN_POINT('',(1.802702815239,-6.35)); -#142170 = CARTESIAN_POINT('',(1.873170701468,-6.35)); -#142171 = CARTESIAN_POINT('',(1.943638587697,-6.35)); -#142172 = CARTESIAN_POINT('',(2.014106473926,-6.35)); -#142173 = CARTESIAN_POINT('',(2.084574360155,-6.35)); -#142174 = CARTESIAN_POINT('',(2.155042246384,-6.35)); -#142175 = CARTESIAN_POINT('',(2.225510132613,-6.35)); -#142176 = CARTESIAN_POINT('',(2.295978018842,-6.35)); -#142177 = CARTESIAN_POINT('',(2.366445905071,-6.35)); -#142178 = CARTESIAN_POINT('',(2.4369137913,-6.35)); -#142179 = CARTESIAN_POINT('',(2.507381677529,-6.35)); -#142180 = CARTESIAN_POINT('',(2.577849563758,-6.35)); -#142181 = CARTESIAN_POINT('',(2.648317449987,-6.35)); -#142182 = CARTESIAN_POINT('',(2.718785336216,-6.35)); -#142183 = CARTESIAN_POINT('',(2.789253222445,-6.35)); -#142184 = CARTESIAN_POINT('',(2.859721108674,-6.35)); -#142185 = CARTESIAN_POINT('',(2.930188994903,-6.35)); -#142186 = CARTESIAN_POINT('',(3.000656881132,-6.35)); -#142187 = CARTESIAN_POINT('',(3.071124767361,-6.35)); -#142188 = CARTESIAN_POINT('',(3.11810335818,-6.35)); -#142189 = CARTESIAN_POINT('',(3.14159265359,-6.35)); -#142190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142191 = PCURVE('',#87098,#142192); -#142192 = DEFINITIONAL_REPRESENTATION('',(#142193),#142197); -#142193 = CIRCLE('',#142194,0.2192697516); -#142194 = AXIS2_PLACEMENT_2D('',#142195,#142196); -#142195 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#142196 = DIRECTION('',(0.E+000,-1.)); -#142197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142198 = ORIENTED_EDGE('',*,*,#142004,.T.); -#142199 = ORIENTED_EDGE('',*,*,#142200,.F.); -#142200 = EDGE_CURVE('',#142201,#142007,#142203,.T.); -#142201 = VERTEX_POINT('',#142202); -#142202 = CARTESIAN_POINT('',(6.15,10.304819755875,0.75)); -#142203 = SURFACE_CURVE('',#142204,(#142209,#142238),.PCURVE_S1.); -#142204 = CIRCLE('',#142205,0.2192697516); -#142205 = AXIS2_PLACEMENT_3D('',#142206,#142207,#142208); -#142206 = CARTESIAN_POINT('',(6.15,10.30032442045,0.530776333563)); -#142207 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142208 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142209 = PCURVE('',#142022,#142210); -#142210 = DEFINITIONAL_REPRESENTATION('',(#142211),#142237); -#142211 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142212,#142213,#142214, - #142215,#142216,#142217,#142218,#142219,#142220,#142221,#142222, - #142223,#142224,#142225,#142226,#142227,#142228,#142229,#142230, - #142231,#142232,#142233,#142234,#142235,#142236),.UNSPECIFIED.,.F., +#144557 = CARTESIAN_POINT('',(1.591299156552,-6.35)); +#144558 = CARTESIAN_POINT('',(1.614788451962,-6.35)); +#144559 = CARTESIAN_POINT('',(1.661767042781,-6.35)); +#144560 = CARTESIAN_POINT('',(1.73223492901,-6.35)); +#144561 = CARTESIAN_POINT('',(1.802702815239,-6.35)); +#144562 = CARTESIAN_POINT('',(1.873170701468,-6.35)); +#144563 = CARTESIAN_POINT('',(1.943638587697,-6.35)); +#144564 = CARTESIAN_POINT('',(2.014106473926,-6.35)); +#144565 = CARTESIAN_POINT('',(2.084574360155,-6.35)); +#144566 = CARTESIAN_POINT('',(2.155042246384,-6.35)); +#144567 = CARTESIAN_POINT('',(2.225510132613,-6.35)); +#144568 = CARTESIAN_POINT('',(2.295978018842,-6.35)); +#144569 = CARTESIAN_POINT('',(2.366445905071,-6.35)); +#144570 = CARTESIAN_POINT('',(2.4369137913,-6.35)); +#144571 = CARTESIAN_POINT('',(2.507381677529,-6.35)); +#144572 = CARTESIAN_POINT('',(2.577849563758,-6.35)); +#144573 = CARTESIAN_POINT('',(2.648317449987,-6.35)); +#144574 = CARTESIAN_POINT('',(2.718785336216,-6.35)); +#144575 = CARTESIAN_POINT('',(2.789253222445,-6.35)); +#144576 = CARTESIAN_POINT('',(2.859721108674,-6.35)); +#144577 = CARTESIAN_POINT('',(2.930188994903,-6.35)); +#144578 = CARTESIAN_POINT('',(3.000656881132,-6.35)); +#144579 = CARTESIAN_POINT('',(3.071124767361,-6.35)); +#144580 = CARTESIAN_POINT('',(3.11810335818,-6.35)); +#144581 = CARTESIAN_POINT('',(3.14159265359,-6.35)); +#144582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144583 = PCURVE('',#89490,#144584); +#144584 = DEFINITIONAL_REPRESENTATION('',(#144585),#144589); +#144585 = CIRCLE('',#144586,0.2192697516); +#144586 = AXIS2_PLACEMENT_2D('',#144587,#144588); +#144587 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#144588 = DIRECTION('',(0.E+000,-1.)); +#144589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144590 = ORIENTED_EDGE('',*,*,#144396,.T.); +#144591 = ORIENTED_EDGE('',*,*,#144592,.F.); +#144592 = EDGE_CURVE('',#144593,#144399,#144595,.T.); +#144593 = VERTEX_POINT('',#144594); +#144594 = CARTESIAN_POINT('',(6.15,10.304819755875,0.75)); +#144595 = SURFACE_CURVE('',#144596,(#144601,#144630),.PCURVE_S1.); +#144596 = CIRCLE('',#144597,0.2192697516); +#144597 = AXIS2_PLACEMENT_3D('',#144598,#144599,#144600); +#144598 = CARTESIAN_POINT('',(6.15,10.30032442045,0.530776333563)); +#144599 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144600 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#144601 = PCURVE('',#144414,#144602); +#144602 = DEFINITIONAL_REPRESENTATION('',(#144603),#144629); +#144603 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144604,#144605,#144606, + #144607,#144608,#144609,#144610,#144611,#144612,#144613,#144614, + #144615,#144616,#144617,#144618,#144619,#144620,#144621,#144622, + #144623,#144624,#144625,#144626,#144627,#144628),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -175331,655 +178333,655 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#142212 = CARTESIAN_POINT('',(1.591299156552,-6.15)); -#142213 = CARTESIAN_POINT('',(1.614788451962,-6.15)); -#142214 = CARTESIAN_POINT('',(1.661767042781,-6.15)); -#142215 = CARTESIAN_POINT('',(1.73223492901,-6.15)); -#142216 = CARTESIAN_POINT('',(1.802702815239,-6.15)); -#142217 = CARTESIAN_POINT('',(1.873170701468,-6.15)); -#142218 = CARTESIAN_POINT('',(1.943638587697,-6.15)); -#142219 = CARTESIAN_POINT('',(2.014106473926,-6.15)); -#142220 = CARTESIAN_POINT('',(2.084574360155,-6.15)); -#142221 = CARTESIAN_POINT('',(2.155042246384,-6.15)); -#142222 = CARTESIAN_POINT('',(2.225510132613,-6.15)); -#142223 = CARTESIAN_POINT('',(2.295978018842,-6.15)); -#142224 = CARTESIAN_POINT('',(2.366445905071,-6.15)); -#142225 = CARTESIAN_POINT('',(2.4369137913,-6.15)); -#142226 = CARTESIAN_POINT('',(2.507381677529,-6.15)); -#142227 = CARTESIAN_POINT('',(2.577849563758,-6.15)); -#142228 = CARTESIAN_POINT('',(2.648317449987,-6.15)); -#142229 = CARTESIAN_POINT('',(2.718785336216,-6.15)); -#142230 = CARTESIAN_POINT('',(2.789253222445,-6.15)); -#142231 = CARTESIAN_POINT('',(2.859721108674,-6.15)); -#142232 = CARTESIAN_POINT('',(2.930188994903,-6.15)); -#142233 = CARTESIAN_POINT('',(3.000656881132,-6.15)); -#142234 = CARTESIAN_POINT('',(3.071124767361,-6.15)); -#142235 = CARTESIAN_POINT('',(3.11810335818,-6.15)); -#142236 = CARTESIAN_POINT('',(3.14159265359,-6.15)); -#142237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142238 = PCURVE('',#87042,#142239); -#142239 = DEFINITIONAL_REPRESENTATION('',(#142240),#142248); -#142240 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142241,#142242,#142243, - #142244,#142245,#142246,#142247),.UNSPECIFIED.,.T.,.F.) +#144604 = CARTESIAN_POINT('',(1.591299156552,-6.15)); +#144605 = CARTESIAN_POINT('',(1.614788451962,-6.15)); +#144606 = CARTESIAN_POINT('',(1.661767042781,-6.15)); +#144607 = CARTESIAN_POINT('',(1.73223492901,-6.15)); +#144608 = CARTESIAN_POINT('',(1.802702815239,-6.15)); +#144609 = CARTESIAN_POINT('',(1.873170701468,-6.15)); +#144610 = CARTESIAN_POINT('',(1.943638587697,-6.15)); +#144611 = CARTESIAN_POINT('',(2.014106473926,-6.15)); +#144612 = CARTESIAN_POINT('',(2.084574360155,-6.15)); +#144613 = CARTESIAN_POINT('',(2.155042246384,-6.15)); +#144614 = CARTESIAN_POINT('',(2.225510132613,-6.15)); +#144615 = CARTESIAN_POINT('',(2.295978018842,-6.15)); +#144616 = CARTESIAN_POINT('',(2.366445905071,-6.15)); +#144617 = CARTESIAN_POINT('',(2.4369137913,-6.15)); +#144618 = CARTESIAN_POINT('',(2.507381677529,-6.15)); +#144619 = CARTESIAN_POINT('',(2.577849563758,-6.15)); +#144620 = CARTESIAN_POINT('',(2.648317449987,-6.15)); +#144621 = CARTESIAN_POINT('',(2.718785336216,-6.15)); +#144622 = CARTESIAN_POINT('',(2.789253222445,-6.15)); +#144623 = CARTESIAN_POINT('',(2.859721108674,-6.15)); +#144624 = CARTESIAN_POINT('',(2.930188994903,-6.15)); +#144625 = CARTESIAN_POINT('',(3.000656881132,-6.15)); +#144626 = CARTESIAN_POINT('',(3.071124767361,-6.15)); +#144627 = CARTESIAN_POINT('',(3.11810335818,-6.15)); +#144628 = CARTESIAN_POINT('',(3.14159265359,-6.15)); +#144629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144630 = PCURVE('',#89434,#144631); +#144631 = DEFINITIONAL_REPRESENTATION('',(#144632),#144640); +#144632 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144633,#144634,#144635, + #144636,#144637,#144638,#144639),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#142241 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#142242 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#142243 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#142244 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#142245 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#142246 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#142247 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#142248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142249 = ORIENTED_EDGE('',*,*,#142250,.T.); -#142250 = EDGE_CURVE('',#142201,#142154,#142251,.T.); -#142251 = SURFACE_CURVE('',#142252,(#142256,#142262),.PCURVE_S1.); -#142252 = LINE('',#142253,#142254); -#142253 = CARTESIAN_POINT('',(6.15,10.304819755875,0.75)); -#142254 = VECTOR('',#142255,1.); -#142255 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142256 = PCURVE('',#142022,#142257); -#142257 = DEFINITIONAL_REPRESENTATION('',(#142258),#142261); -#142258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142259,#142260), +#144633 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#144634 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#144635 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#144636 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#144637 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#144638 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#144639 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#144640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144641 = ORIENTED_EDGE('',*,*,#144642,.T.); +#144642 = EDGE_CURVE('',#144593,#144546,#144643,.T.); +#144643 = SURFACE_CURVE('',#144644,(#144648,#144654),.PCURVE_S1.); +#144644 = LINE('',#144645,#144646); +#144645 = CARTESIAN_POINT('',(6.15,10.304819755875,0.75)); +#144646 = VECTOR('',#144647,1.); +#144647 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144648 = PCURVE('',#144414,#144649); +#144649 = DEFINITIONAL_REPRESENTATION('',(#144650),#144653); +#144650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144651,#144652), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#142259 = CARTESIAN_POINT('',(1.591299156552,-6.15)); -#142260 = CARTESIAN_POINT('',(1.591299156552,-6.35)); -#142261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142262 = PCURVE('',#87124,#142263); -#142263 = DEFINITIONAL_REPRESENTATION('',(#142264),#142268); -#142264 = LINE('',#142265,#142266); -#142265 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#142266 = VECTOR('',#142267,1.); -#142267 = DIRECTION('',(-8.881784197001E-016,1.)); -#142268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142269 = ADVANCED_FACE('',(#142270),#87042,.F.); -#142270 = FACE_BOUND('',#142271,.T.); -#142271 = EDGE_LOOP('',(#142272,#142293,#142294,#142295,#142296,#142297, - #142318,#142319,#142320,#142321,#142322,#142343)); -#142272 = ORIENTED_EDGE('',*,*,#142273,.F.); -#142273 = EDGE_CURVE('',#142201,#87027,#142274,.T.); -#142274 = SURFACE_CURVE('',#142275,(#142279,#142286),.PCURVE_S1.); -#142275 = LINE('',#142276,#142277); -#142276 = CARTESIAN_POINT('',(6.15,10.527847992439,0.75)); -#142277 = VECTOR('',#142278,1.); -#142278 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#142279 = PCURVE('',#87042,#142280); -#142280 = DEFINITIONAL_REPRESENTATION('',(#142281),#142285); -#142281 = LINE('',#142282,#142283); -#142282 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#142283 = VECTOR('',#142284,1.); -#142284 = DIRECTION('',(-3.563627120235E-016,-1.)); -#142285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142286 = PCURVE('',#87124,#142287); -#142287 = DEFINITIONAL_REPRESENTATION('',(#142288),#142292); -#142288 = LINE('',#142289,#142290); -#142289 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142290 = VECTOR('',#142291,1.); -#142291 = DIRECTION('',(-1.,2.164989446033E-063)); -#142292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142293 = ORIENTED_EDGE('',*,*,#142200,.T.); -#142294 = ORIENTED_EDGE('',*,*,#142055,.T.); -#142295 = ORIENTED_EDGE('',*,*,#141780,.T.); -#142296 = ORIENTED_EDGE('',*,*,#141570,.T.); -#142297 = ORIENTED_EDGE('',*,*,#142298,.T.); -#142298 = EDGE_CURVE('',#141543,#141624,#142299,.T.); -#142299 = SURFACE_CURVE('',#142300,(#142304,#142311),.PCURVE_S1.); -#142300 = LINE('',#142301,#142302); -#142301 = CARTESIAN_POINT('',(6.15,11.,1.159810404338E-002)); -#142302 = VECTOR('',#142303,1.); -#142303 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#142304 = PCURVE('',#87042,#142305); -#142305 = DEFINITIONAL_REPRESENTATION('',(#142306),#142310); -#142306 = LINE('',#142307,#142308); -#142307 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#142308 = VECTOR('',#142309,1.); -#142309 = DIRECTION('',(1.,-2.101748079665E-016)); -#142310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142311 = PCURVE('',#141558,#142312); -#142312 = DEFINITIONAL_REPRESENTATION('',(#142313),#142317); -#142313 = LINE('',#142314,#142315); -#142314 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#142315 = VECTOR('',#142316,1.); -#142316 = DIRECTION('',(1.570395187386E-016,-1.)); -#142317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142318 = ORIENTED_EDGE('',*,*,#141621,.F.); -#142319 = ORIENTED_EDGE('',*,*,#141882,.F.); -#142320 = ORIENTED_EDGE('',*,*,#141958,.F.); -#142321 = ORIENTED_EDGE('',*,*,#142079,.F.); -#142322 = ORIENTED_EDGE('',*,*,#142323,.T.); -#142323 = EDGE_CURVE('',#142080,#87025,#142324,.T.); -#142324 = SURFACE_CURVE('',#142325,(#142329,#142336),.PCURVE_S1.); -#142325 = LINE('',#142326,#142327); -#142326 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); -#142327 = VECTOR('',#142328,1.); -#142328 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#142329 = PCURVE('',#87042,#142330); -#142330 = DEFINITIONAL_REPRESENTATION('',(#142331),#142335); -#142331 = LINE('',#142332,#142333); -#142332 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142333 = VECTOR('',#142334,1.); -#142334 = DIRECTION('',(-3.563627120235E-016,-1.)); -#142335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142336 = PCURVE('',#87070,#142337); -#142337 = DEFINITIONAL_REPRESENTATION('',(#142338),#142342); -#142338 = LINE('',#142339,#142340); -#142339 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142340 = VECTOR('',#142341,1.); -#142341 = DIRECTION('',(1.,2.164989446033E-063)); -#142342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142343 = ORIENTED_EDGE('',*,*,#87024,.T.); -#142344 = ADVANCED_FACE('',(#142345),#87124,.F.); -#142345 = FACE_BOUND('',#142346,.T.); -#142346 = EDGE_LOOP('',(#142347,#142348,#142349,#142350)); -#142347 = ORIENTED_EDGE('',*,*,#142250,.F.); -#142348 = ORIENTED_EDGE('',*,*,#142273,.T.); -#142349 = ORIENTED_EDGE('',*,*,#87110,.T.); -#142350 = ORIENTED_EDGE('',*,*,#142351,.F.); -#142351 = EDGE_CURVE('',#142154,#87083,#142352,.T.); -#142352 = SURFACE_CURVE('',#142353,(#142357,#142364),.PCURVE_S1.); -#142353 = LINE('',#142354,#142355); -#142354 = CARTESIAN_POINT('',(6.35,10.527847992439,0.75)); -#142355 = VECTOR('',#142356,1.); -#142356 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#142357 = PCURVE('',#87124,#142358); -#142358 = DEFINITIONAL_REPRESENTATION('',(#142359),#142363); -#142359 = LINE('',#142360,#142361); -#142360 = CARTESIAN_POINT('',(0.E+000,0.2)); -#142361 = VECTOR('',#142362,1.); -#142362 = DIRECTION('',(-1.,2.164989446033E-063)); -#142363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142364 = PCURVE('',#87098,#142365); -#142365 = DEFINITIONAL_REPRESENTATION('',(#142366),#142370); -#142366 = LINE('',#142367,#142368); -#142367 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#142368 = VECTOR('',#142369,1.); -#142369 = DIRECTION('',(3.563627120235E-016,-1.)); -#142370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142371 = ADVANCED_FACE('',(#142372),#87098,.F.); -#142372 = FACE_BOUND('',#142373,.T.); -#142373 = EDGE_LOOP('',(#142374,#142395,#142396,#142397,#142398,#142399, - #142420,#142421,#142422,#142423,#142424,#142425)); -#142374 = ORIENTED_EDGE('',*,*,#142375,.F.); -#142375 = EDGE_CURVE('',#142107,#87055,#142376,.T.); -#142376 = SURFACE_CURVE('',#142377,(#142381,#142388),.PCURVE_S1.); -#142377 = LINE('',#142378,#142379); -#142378 = CARTESIAN_POINT('',(6.35,10.527847992439,0.65)); -#142379 = VECTOR('',#142380,1.); -#142380 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#142381 = PCURVE('',#87098,#142382); -#142382 = DEFINITIONAL_REPRESENTATION('',(#142383),#142387); -#142383 = LINE('',#142384,#142385); -#142384 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142385 = VECTOR('',#142386,1.); -#142386 = DIRECTION('',(3.563627120235E-016,-1.)); -#142387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142388 = PCURVE('',#87070,#142389); -#142389 = DEFINITIONAL_REPRESENTATION('',(#142390),#142394); -#142390 = LINE('',#142391,#142392); -#142391 = CARTESIAN_POINT('',(0.E+000,0.2)); -#142392 = VECTOR('',#142393,1.); -#142393 = DIRECTION('',(1.,2.164989446033E-063)); -#142394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142395 = ORIENTED_EDGE('',*,*,#142128,.T.); -#142396 = ORIENTED_EDGE('',*,*,#141980,.T.); -#142397 = ORIENTED_EDGE('',*,*,#141805,.T.); -#142398 = ORIENTED_EDGE('',*,*,#141674,.T.); -#142399 = ORIENTED_EDGE('',*,*,#142400,.T.); -#142400 = EDGE_CURVE('',#141652,#141515,#142401,.T.); -#142401 = SURFACE_CURVE('',#142402,(#142406,#142413),.PCURVE_S1.); -#142402 = LINE('',#142403,#142404); -#142403 = CARTESIAN_POINT('',(6.35,11.,1.159810404338E-002)); -#142404 = VECTOR('',#142405,1.); -#142405 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#142406 = PCURVE('',#87098,#142407); -#142407 = DEFINITIONAL_REPRESENTATION('',(#142408),#142412); -#142408 = LINE('',#142409,#142410); -#142409 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#142410 = VECTOR('',#142411,1.); -#142411 = DIRECTION('',(1.,2.101748079665E-016)); -#142412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142413 = PCURVE('',#141558,#142414); -#142414 = DEFINITIONAL_REPRESENTATION('',(#142415),#142419); -#142415 = LINE('',#142416,#142417); -#142416 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#142417 = VECTOR('',#142418,1.); -#142418 = DIRECTION('',(-1.570395187386E-016,1.)); -#142419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142420 = ORIENTED_EDGE('',*,*,#141512,.F.); -#142421 = ORIENTED_EDGE('',*,*,#141726,.F.); -#142422 = ORIENTED_EDGE('',*,*,#142033,.F.); -#142423 = ORIENTED_EDGE('',*,*,#142153,.F.); -#142424 = ORIENTED_EDGE('',*,*,#142351,.T.); -#142425 = ORIENTED_EDGE('',*,*,#87082,.T.); -#142426 = ADVANCED_FACE('',(#142427),#87070,.F.); -#142427 = FACE_BOUND('',#142428,.T.); -#142428 = EDGE_LOOP('',(#142429,#142430,#142431,#142432)); -#142429 = ORIENTED_EDGE('',*,*,#142106,.F.); -#142430 = ORIENTED_EDGE('',*,*,#142375,.T.); -#142431 = ORIENTED_EDGE('',*,*,#87054,.T.); -#142432 = ORIENTED_EDGE('',*,*,#142323,.F.); -#142433 = ADVANCED_FACE('',(#142434),#141558,.T.); -#142434 = FACE_BOUND('',#142435,.T.); -#142435 = EDGE_LOOP('',(#142436,#142437,#142438,#142439)); -#142436 = ORIENTED_EDGE('',*,*,#142400,.F.); -#142437 = ORIENTED_EDGE('',*,*,#141651,.F.); -#142438 = ORIENTED_EDGE('',*,*,#142298,.F.); -#142439 = ORIENTED_EDGE('',*,*,#141542,.F.); -#142440 = ADVANCED_FACE('',(#142441),#142455,.T.); -#142441 = FACE_BOUND('',#142442,.T.); -#142442 = EDGE_LOOP('',(#142443,#142473,#142501,#142524)); -#142443 = ORIENTED_EDGE('',*,*,#142444,.T.); -#142444 = EDGE_CURVE('',#142445,#142447,#142449,.T.); -#142445 = VERTEX_POINT('',#142446); -#142446 = CARTESIAN_POINT('',(5.85,10.740726081328,-0.208196358798)); -#142447 = VERTEX_POINT('',#142448); -#142448 = CARTESIAN_POINT('',(5.85,11.,-0.208196358798)); -#142449 = SURFACE_CURVE('',#142450,(#142454,#142466),.PCURVE_S1.); -#142450 = LINE('',#142451,#142452); -#142451 = CARTESIAN_POINT('',(5.85,10.740726081328,-0.208196358798)); -#142452 = VECTOR('',#142453,1.); -#142453 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#142454 = PCURVE('',#142455,#142460); -#142455 = PLANE('',#142456); -#142456 = AXIS2_PLACEMENT_3D('',#142457,#142458,#142459); -#142457 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#144651 = CARTESIAN_POINT('',(1.591299156552,-6.15)); +#144652 = CARTESIAN_POINT('',(1.591299156552,-6.35)); +#144653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144654 = PCURVE('',#89516,#144655); +#144655 = DEFINITIONAL_REPRESENTATION('',(#144656),#144660); +#144656 = LINE('',#144657,#144658); +#144657 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#144658 = VECTOR('',#144659,1.); +#144659 = DIRECTION('',(-8.881784197001E-016,1.)); +#144660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144661 = ADVANCED_FACE('',(#144662),#89434,.F.); +#144662 = FACE_BOUND('',#144663,.T.); +#144663 = EDGE_LOOP('',(#144664,#144685,#144686,#144687,#144688,#144689, + #144710,#144711,#144712,#144713,#144714,#144735)); +#144664 = ORIENTED_EDGE('',*,*,#144665,.F.); +#144665 = EDGE_CURVE('',#144593,#89419,#144666,.T.); +#144666 = SURFACE_CURVE('',#144667,(#144671,#144678),.PCURVE_S1.); +#144667 = LINE('',#144668,#144669); +#144668 = CARTESIAN_POINT('',(6.15,10.527847992439,0.75)); +#144669 = VECTOR('',#144670,1.); +#144670 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#144671 = PCURVE('',#89434,#144672); +#144672 = DEFINITIONAL_REPRESENTATION('',(#144673),#144677); +#144673 = LINE('',#144674,#144675); +#144674 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#144675 = VECTOR('',#144676,1.); +#144676 = DIRECTION('',(-3.563627120235E-016,-1.)); +#144677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144678 = PCURVE('',#89516,#144679); +#144679 = DEFINITIONAL_REPRESENTATION('',(#144680),#144684); +#144680 = LINE('',#144681,#144682); +#144681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144682 = VECTOR('',#144683,1.); +#144683 = DIRECTION('',(-1.,2.164989446033E-063)); +#144684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144685 = ORIENTED_EDGE('',*,*,#144592,.T.); +#144686 = ORIENTED_EDGE('',*,*,#144447,.T.); +#144687 = ORIENTED_EDGE('',*,*,#144172,.T.); +#144688 = ORIENTED_EDGE('',*,*,#143962,.T.); +#144689 = ORIENTED_EDGE('',*,*,#144690,.T.); +#144690 = EDGE_CURVE('',#143935,#144016,#144691,.T.); +#144691 = SURFACE_CURVE('',#144692,(#144696,#144703),.PCURVE_S1.); +#144692 = LINE('',#144693,#144694); +#144693 = CARTESIAN_POINT('',(6.15,11.,1.159810404338E-002)); +#144694 = VECTOR('',#144695,1.); +#144695 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#144696 = PCURVE('',#89434,#144697); +#144697 = DEFINITIONAL_REPRESENTATION('',(#144698),#144702); +#144698 = LINE('',#144699,#144700); +#144699 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#144700 = VECTOR('',#144701,1.); +#144701 = DIRECTION('',(1.,-2.101748079665E-016)); +#144702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144703 = PCURVE('',#143950,#144704); +#144704 = DEFINITIONAL_REPRESENTATION('',(#144705),#144709); +#144705 = LINE('',#144706,#144707); +#144706 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#144707 = VECTOR('',#144708,1.); +#144708 = DIRECTION('',(1.570395187386E-016,-1.)); +#144709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144710 = ORIENTED_EDGE('',*,*,#144013,.F.); +#144711 = ORIENTED_EDGE('',*,*,#144274,.F.); +#144712 = ORIENTED_EDGE('',*,*,#144350,.F.); +#144713 = ORIENTED_EDGE('',*,*,#144471,.F.); +#144714 = ORIENTED_EDGE('',*,*,#144715,.T.); +#144715 = EDGE_CURVE('',#144472,#89417,#144716,.T.); +#144716 = SURFACE_CURVE('',#144717,(#144721,#144728),.PCURVE_S1.); +#144717 = LINE('',#144718,#144719); +#144718 = CARTESIAN_POINT('',(6.15,10.527847992439,0.65)); +#144719 = VECTOR('',#144720,1.); +#144720 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#144721 = PCURVE('',#89434,#144722); +#144722 = DEFINITIONAL_REPRESENTATION('',(#144723),#144727); +#144723 = LINE('',#144724,#144725); +#144724 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144725 = VECTOR('',#144726,1.); +#144726 = DIRECTION('',(-3.563627120235E-016,-1.)); +#144727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144728 = PCURVE('',#89462,#144729); +#144729 = DEFINITIONAL_REPRESENTATION('',(#144730),#144734); +#144730 = LINE('',#144731,#144732); +#144731 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144732 = VECTOR('',#144733,1.); +#144733 = DIRECTION('',(1.,2.164989446033E-063)); +#144734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144735 = ORIENTED_EDGE('',*,*,#89416,.T.); +#144736 = ADVANCED_FACE('',(#144737),#89516,.F.); +#144737 = FACE_BOUND('',#144738,.T.); +#144738 = EDGE_LOOP('',(#144739,#144740,#144741,#144742)); +#144739 = ORIENTED_EDGE('',*,*,#144642,.F.); +#144740 = ORIENTED_EDGE('',*,*,#144665,.T.); +#144741 = ORIENTED_EDGE('',*,*,#89502,.T.); +#144742 = ORIENTED_EDGE('',*,*,#144743,.F.); +#144743 = EDGE_CURVE('',#144546,#89475,#144744,.T.); +#144744 = SURFACE_CURVE('',#144745,(#144749,#144756),.PCURVE_S1.); +#144745 = LINE('',#144746,#144747); +#144746 = CARTESIAN_POINT('',(6.35,10.527847992439,0.75)); +#144747 = VECTOR('',#144748,1.); +#144748 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#144749 = PCURVE('',#89516,#144750); +#144750 = DEFINITIONAL_REPRESENTATION('',(#144751),#144755); +#144751 = LINE('',#144752,#144753); +#144752 = CARTESIAN_POINT('',(0.E+000,0.2)); +#144753 = VECTOR('',#144754,1.); +#144754 = DIRECTION('',(-1.,2.164989446033E-063)); +#144755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144756 = PCURVE('',#89490,#144757); +#144757 = DEFINITIONAL_REPRESENTATION('',(#144758),#144762); +#144758 = LINE('',#144759,#144760); +#144759 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#144760 = VECTOR('',#144761,1.); +#144761 = DIRECTION('',(3.563627120235E-016,-1.)); +#144762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144763 = ADVANCED_FACE('',(#144764),#89490,.F.); +#144764 = FACE_BOUND('',#144765,.T.); +#144765 = EDGE_LOOP('',(#144766,#144787,#144788,#144789,#144790,#144791, + #144812,#144813,#144814,#144815,#144816,#144817)); +#144766 = ORIENTED_EDGE('',*,*,#144767,.F.); +#144767 = EDGE_CURVE('',#144499,#89447,#144768,.T.); +#144768 = SURFACE_CURVE('',#144769,(#144773,#144780),.PCURVE_S1.); +#144769 = LINE('',#144770,#144771); +#144770 = CARTESIAN_POINT('',(6.35,10.527847992439,0.65)); +#144771 = VECTOR('',#144772,1.); +#144772 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#144773 = PCURVE('',#89490,#144774); +#144774 = DEFINITIONAL_REPRESENTATION('',(#144775),#144779); +#144775 = LINE('',#144776,#144777); +#144776 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144777 = VECTOR('',#144778,1.); +#144778 = DIRECTION('',(3.563627120235E-016,-1.)); +#144779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144780 = PCURVE('',#89462,#144781); +#144781 = DEFINITIONAL_REPRESENTATION('',(#144782),#144786); +#144782 = LINE('',#144783,#144784); +#144783 = CARTESIAN_POINT('',(0.E+000,0.2)); +#144784 = VECTOR('',#144785,1.); +#144785 = DIRECTION('',(1.,2.164989446033E-063)); +#144786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144787 = ORIENTED_EDGE('',*,*,#144520,.T.); +#144788 = ORIENTED_EDGE('',*,*,#144372,.T.); +#144789 = ORIENTED_EDGE('',*,*,#144197,.T.); +#144790 = ORIENTED_EDGE('',*,*,#144066,.T.); +#144791 = ORIENTED_EDGE('',*,*,#144792,.T.); +#144792 = EDGE_CURVE('',#144044,#143907,#144793,.T.); +#144793 = SURFACE_CURVE('',#144794,(#144798,#144805),.PCURVE_S1.); +#144794 = LINE('',#144795,#144796); +#144795 = CARTESIAN_POINT('',(6.35,11.,1.159810404338E-002)); +#144796 = VECTOR('',#144797,1.); +#144797 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#144798 = PCURVE('',#89490,#144799); +#144799 = DEFINITIONAL_REPRESENTATION('',(#144800),#144804); +#144800 = LINE('',#144801,#144802); +#144801 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#144802 = VECTOR('',#144803,1.); +#144803 = DIRECTION('',(1.,2.101748079665E-016)); +#144804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144805 = PCURVE('',#143950,#144806); +#144806 = DEFINITIONAL_REPRESENTATION('',(#144807),#144811); +#144807 = LINE('',#144808,#144809); +#144808 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#144809 = VECTOR('',#144810,1.); +#144810 = DIRECTION('',(-1.570395187386E-016,1.)); +#144811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144812 = ORIENTED_EDGE('',*,*,#143904,.F.); +#144813 = ORIENTED_EDGE('',*,*,#144118,.F.); +#144814 = ORIENTED_EDGE('',*,*,#144425,.F.); +#144815 = ORIENTED_EDGE('',*,*,#144545,.F.); +#144816 = ORIENTED_EDGE('',*,*,#144743,.T.); +#144817 = ORIENTED_EDGE('',*,*,#89474,.T.); +#144818 = ADVANCED_FACE('',(#144819),#89462,.F.); +#144819 = FACE_BOUND('',#144820,.T.); +#144820 = EDGE_LOOP('',(#144821,#144822,#144823,#144824)); +#144821 = ORIENTED_EDGE('',*,*,#144498,.F.); +#144822 = ORIENTED_EDGE('',*,*,#144767,.T.); +#144823 = ORIENTED_EDGE('',*,*,#89446,.T.); +#144824 = ORIENTED_EDGE('',*,*,#144715,.F.); +#144825 = ADVANCED_FACE('',(#144826),#143950,.T.); +#144826 = FACE_BOUND('',#144827,.T.); +#144827 = EDGE_LOOP('',(#144828,#144829,#144830,#144831)); +#144828 = ORIENTED_EDGE('',*,*,#144792,.F.); +#144829 = ORIENTED_EDGE('',*,*,#144043,.F.); +#144830 = ORIENTED_EDGE('',*,*,#144690,.F.); +#144831 = ORIENTED_EDGE('',*,*,#143934,.F.); +#144832 = ADVANCED_FACE('',(#144833),#144847,.T.); +#144833 = FACE_BOUND('',#144834,.T.); +#144834 = EDGE_LOOP('',(#144835,#144865,#144893,#144916)); +#144835 = ORIENTED_EDGE('',*,*,#144836,.T.); +#144836 = EDGE_CURVE('',#144837,#144839,#144841,.T.); +#144837 = VERTEX_POINT('',#144838); +#144838 = CARTESIAN_POINT('',(5.85,10.740726081328,-0.208196358798)); +#144839 = VERTEX_POINT('',#144840); +#144840 = CARTESIAN_POINT('',(5.85,11.,-0.208196358798)); +#144841 = SURFACE_CURVE('',#144842,(#144846,#144858),.PCURVE_S1.); +#144842 = LINE('',#144843,#144844); +#144843 = CARTESIAN_POINT('',(5.85,10.740726081328,-0.208196358798)); +#144844 = VECTOR('',#144845,1.); +#144845 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#144846 = PCURVE('',#144847,#144852); +#144847 = PLANE('',#144848); +#144848 = AXIS2_PLACEMENT_3D('',#144849,#144850,#144851); +#144849 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#142458 = DIRECTION('',(0.E+000,0.E+000,1.)); -#142459 = DIRECTION('',(1.,0.E+000,0.E+000)); -#142460 = DEFINITIONAL_REPRESENTATION('',(#142461),#142465); -#142461 = LINE('',#142462,#142463); -#142462 = CARTESIAN_POINT('',(5.85,-5.329070518201E-015)); -#142463 = VECTOR('',#142464,1.); -#142464 = DIRECTION('',(6.725593854929E-015,1.)); -#142465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142466 = PCURVE('',#87896,#142467); -#142467 = DEFINITIONAL_REPRESENTATION('',(#142468),#142472); -#142468 = LINE('',#142469,#142470); -#142469 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#142470 = VECTOR('',#142471,1.); -#142471 = DIRECTION('',(0.E+000,1.)); -#142472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142473 = ORIENTED_EDGE('',*,*,#142474,.T.); -#142474 = EDGE_CURVE('',#142447,#142475,#142477,.T.); -#142475 = VERTEX_POINT('',#142476); -#142476 = CARTESIAN_POINT('',(5.65,11.,-0.208196358798)); -#142477 = SURFACE_CURVE('',#142478,(#142482,#142489),.PCURVE_S1.); -#142478 = LINE('',#142479,#142480); -#142479 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#142480 = VECTOR('',#142481,1.); -#142481 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142482 = PCURVE('',#142455,#142483); -#142483 = DEFINITIONAL_REPRESENTATION('',(#142484),#142488); -#142484 = LINE('',#142485,#142486); -#142485 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#142486 = VECTOR('',#142487,1.); -#142487 = DIRECTION('',(-1.,8.881784197001E-016)); -#142488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142489 = PCURVE('',#142490,#142495); -#142490 = PLANE('',#142491); -#142491 = AXIS2_PLACEMENT_3D('',#142492,#142493,#142494); -#142492 = CARTESIAN_POINT('',(5.75,11.,-0.258196742327)); -#142493 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#142494 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#142495 = DEFINITIONAL_REPRESENTATION('',(#142496),#142500); -#142496 = LINE('',#142497,#142498); -#142497 = CARTESIAN_POINT('',(5.75,5.000038352949E-002)); -#142498 = VECTOR('',#142499,1.); -#142499 = DIRECTION('',(1.,1.1653254136E-048)); -#142500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142501 = ORIENTED_EDGE('',*,*,#142502,.F.); -#142502 = EDGE_CURVE('',#142503,#142475,#142505,.T.); -#142503 = VERTEX_POINT('',#142504); -#142504 = CARTESIAN_POINT('',(5.65,10.740726081328,-0.208196358798)); -#142505 = SURFACE_CURVE('',#142506,(#142510,#142517),.PCURVE_S1.); -#142506 = LINE('',#142507,#142508); -#142507 = CARTESIAN_POINT('',(5.65,10.740726081328,-0.208196358798)); -#142508 = VECTOR('',#142509,1.); -#142509 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#142510 = PCURVE('',#142455,#142511); -#142511 = DEFINITIONAL_REPRESENTATION('',(#142512),#142516); -#142512 = LINE('',#142513,#142514); -#142513 = CARTESIAN_POINT('',(5.65,-5.329070518201E-015)); -#142514 = VECTOR('',#142515,1.); -#142515 = DIRECTION('',(6.725593854929E-015,1.)); -#142516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142517 = PCURVE('',#87840,#142518); -#142518 = DEFINITIONAL_REPRESENTATION('',(#142519),#142523); -#142519 = LINE('',#142520,#142521); -#142520 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#142521 = VECTOR('',#142522,1.); -#142522 = DIRECTION('',(0.E+000,1.)); -#142523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142524 = ORIENTED_EDGE('',*,*,#142525,.T.); -#142525 = EDGE_CURVE('',#142503,#142445,#142526,.T.); -#142526 = SURFACE_CURVE('',#142527,(#142531,#142538),.PCURVE_S1.); -#142527 = LINE('',#142528,#142529); -#142528 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#144850 = DIRECTION('',(0.E+000,0.E+000,1.)); +#144851 = DIRECTION('',(1.,0.E+000,0.E+000)); +#144852 = DEFINITIONAL_REPRESENTATION('',(#144853),#144857); +#144853 = LINE('',#144854,#144855); +#144854 = CARTESIAN_POINT('',(5.85,-5.329070518201E-015)); +#144855 = VECTOR('',#144856,1.); +#144856 = DIRECTION('',(6.725593854929E-015,1.)); +#144857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144858 = PCURVE('',#90288,#144859); +#144859 = DEFINITIONAL_REPRESENTATION('',(#144860),#144864); +#144860 = LINE('',#144861,#144862); +#144861 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#144862 = VECTOR('',#144863,1.); +#144863 = DIRECTION('',(0.E+000,1.)); +#144864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144865 = ORIENTED_EDGE('',*,*,#144866,.T.); +#144866 = EDGE_CURVE('',#144839,#144867,#144869,.T.); +#144867 = VERTEX_POINT('',#144868); +#144868 = CARTESIAN_POINT('',(5.65,11.,-0.208196358798)); +#144869 = SURFACE_CURVE('',#144870,(#144874,#144881),.PCURVE_S1.); +#144870 = LINE('',#144871,#144872); +#144871 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#144872 = VECTOR('',#144873,1.); +#144873 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#144874 = PCURVE('',#144847,#144875); +#144875 = DEFINITIONAL_REPRESENTATION('',(#144876),#144880); +#144876 = LINE('',#144877,#144878); +#144877 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#144878 = VECTOR('',#144879,1.); +#144879 = DIRECTION('',(-1.,8.881784197001E-016)); +#144880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144881 = PCURVE('',#144882,#144887); +#144882 = PLANE('',#144883); +#144883 = AXIS2_PLACEMENT_3D('',#144884,#144885,#144886); +#144884 = CARTESIAN_POINT('',(5.75,11.,-0.258196742327)); +#144885 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#144886 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#144887 = DEFINITIONAL_REPRESENTATION('',(#144888),#144892); +#144888 = LINE('',#144889,#144890); +#144889 = CARTESIAN_POINT('',(5.75,5.000038352949E-002)); +#144890 = VECTOR('',#144891,1.); +#144891 = DIRECTION('',(1.,1.1653254136E-048)); +#144892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144893 = ORIENTED_EDGE('',*,*,#144894,.F.); +#144894 = EDGE_CURVE('',#144895,#144867,#144897,.T.); +#144895 = VERTEX_POINT('',#144896); +#144896 = CARTESIAN_POINT('',(5.65,10.740726081328,-0.208196358798)); +#144897 = SURFACE_CURVE('',#144898,(#144902,#144909),.PCURVE_S1.); +#144898 = LINE('',#144899,#144900); +#144899 = CARTESIAN_POINT('',(5.65,10.740726081328,-0.208196358798)); +#144900 = VECTOR('',#144901,1.); +#144901 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#144902 = PCURVE('',#144847,#144903); +#144903 = DEFINITIONAL_REPRESENTATION('',(#144904),#144908); +#144904 = LINE('',#144905,#144906); +#144905 = CARTESIAN_POINT('',(5.65,-5.329070518201E-015)); +#144906 = VECTOR('',#144907,1.); +#144907 = DIRECTION('',(6.725593854929E-015,1.)); +#144908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144909 = PCURVE('',#90232,#144910); +#144910 = DEFINITIONAL_REPRESENTATION('',(#144911),#144915); +#144911 = LINE('',#144912,#144913); +#144912 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#144913 = VECTOR('',#144914,1.); +#144914 = DIRECTION('',(0.E+000,1.)); +#144915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144916 = ORIENTED_EDGE('',*,*,#144917,.T.); +#144917 = EDGE_CURVE('',#144895,#144837,#144918,.T.); +#144918 = SURFACE_CURVE('',#144919,(#144923,#144930),.PCURVE_S1.); +#144919 = LINE('',#144920,#144921); +#144920 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#142529 = VECTOR('',#142530,1.); -#142530 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142531 = PCURVE('',#142455,#142532); -#142532 = DEFINITIONAL_REPRESENTATION('',(#142533),#142537); -#142533 = LINE('',#142534,#142535); -#142534 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142535 = VECTOR('',#142536,1.); -#142536 = DIRECTION('',(1.,-8.881784197001E-016)); -#142537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142538 = PCURVE('',#142539,#142544); -#142539 = CYLINDRICAL_SURFACE('',#142540,0.208574704164); -#142540 = AXIS2_PLACEMENT_3D('',#142541,#142542,#142543); -#142541 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#144921 = VECTOR('',#144922,1.); +#144922 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144923 = PCURVE('',#144847,#144924); +#144924 = DEFINITIONAL_REPRESENTATION('',(#144925),#144929); +#144925 = LINE('',#144926,#144927); +#144926 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#144927 = VECTOR('',#144928,1.); +#144928 = DIRECTION('',(1.,-8.881784197001E-016)); +#144929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144930 = PCURVE('',#144931,#144936); +#144931 = CYLINDRICAL_SURFACE('',#144932,0.208574704164); +#144932 = AXIS2_PLACEMENT_3D('',#144933,#144934,#144935); +#144933 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#142542 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142543 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142544 = DEFINITIONAL_REPRESENTATION('',(#142545),#142548); -#142545 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142546,#142547), +#144934 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144935 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#144936 = DEFINITIONAL_REPRESENTATION('',(#144937),#144940); +#144937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144938,#144939), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#142546 = CARTESIAN_POINT('',(4.772630242227,5.65)); -#142547 = CARTESIAN_POINT('',(4.772630242227,5.85)); -#142548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142549 = ADVANCED_FACE('',(#142550),#142564,.T.); -#142550 = FACE_BOUND('',#142551,.T.); -#142551 = EDGE_LOOP('',(#142552,#142582,#142605,#142628)); -#142552 = ORIENTED_EDGE('',*,*,#142553,.T.); -#142553 = EDGE_CURVE('',#142554,#142556,#142558,.T.); -#142554 = VERTEX_POINT('',#142555); -#142555 = CARTESIAN_POINT('',(5.65,10.74341632541,-0.308197125857)); -#142556 = VERTEX_POINT('',#142557); -#142557 = CARTESIAN_POINT('',(5.65,11.,-0.308197125857)); -#142558 = SURFACE_CURVE('',#142559,(#142563,#142575),.PCURVE_S1.); -#142559 = LINE('',#142560,#142561); -#142560 = CARTESIAN_POINT('',(5.65,10.74341632541,-0.308197125857)); -#142561 = VECTOR('',#142562,1.); -#142562 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#142563 = PCURVE('',#142564,#142569); -#142564 = PLANE('',#142565); -#142565 = AXIS2_PLACEMENT_3D('',#142566,#142567,#142568); -#142566 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#144938 = CARTESIAN_POINT('',(4.772630242227,5.65)); +#144939 = CARTESIAN_POINT('',(4.772630242227,5.85)); +#144940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144941 = ADVANCED_FACE('',(#144942),#144956,.T.); +#144942 = FACE_BOUND('',#144943,.T.); +#144943 = EDGE_LOOP('',(#144944,#144974,#144997,#145020)); +#144944 = ORIENTED_EDGE('',*,*,#144945,.T.); +#144945 = EDGE_CURVE('',#144946,#144948,#144950,.T.); +#144946 = VERTEX_POINT('',#144947); +#144947 = CARTESIAN_POINT('',(5.65,10.74341632541,-0.308197125857)); +#144948 = VERTEX_POINT('',#144949); +#144949 = CARTESIAN_POINT('',(5.65,11.,-0.308197125857)); +#144950 = SURFACE_CURVE('',#144951,(#144955,#144967),.PCURVE_S1.); +#144951 = LINE('',#144952,#144953); +#144952 = CARTESIAN_POINT('',(5.65,10.74341632541,-0.308197125857)); +#144953 = VECTOR('',#144954,1.); +#144954 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#144955 = PCURVE('',#144956,#144961); +#144956 = PLANE('',#144957); +#144957 = AXIS2_PLACEMENT_3D('',#144958,#144959,#144960); +#144958 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#142567 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142568 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#142569 = DEFINITIONAL_REPRESENTATION('',(#142570),#142574); -#142570 = LINE('',#142571,#142572); -#142571 = CARTESIAN_POINT('',(-5.65,-5.329070518201E-015)); -#142572 = VECTOR('',#142573,1.); -#142573 = DIRECTION('',(-6.725593854929E-015,1.)); -#142574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142575 = PCURVE('',#87840,#142576); -#142576 = DEFINITIONAL_REPRESENTATION('',(#142577),#142581); -#142577 = LINE('',#142578,#142579); -#142578 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#142579 = VECTOR('',#142580,1.); -#142580 = DIRECTION('',(0.E+000,1.)); -#142581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142582 = ORIENTED_EDGE('',*,*,#142583,.T.); -#142583 = EDGE_CURVE('',#142556,#142584,#142586,.T.); -#142584 = VERTEX_POINT('',#142585); -#142585 = CARTESIAN_POINT('',(5.85,11.,-0.308197125857)); -#142586 = SURFACE_CURVE('',#142587,(#142591,#142598),.PCURVE_S1.); -#142587 = LINE('',#142588,#142589); -#142588 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#142589 = VECTOR('',#142590,1.); -#142590 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142591 = PCURVE('',#142564,#142592); -#142592 = DEFINITIONAL_REPRESENTATION('',(#142593),#142597); -#142593 = LINE('',#142594,#142595); -#142594 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#142595 = VECTOR('',#142596,1.); -#142596 = DIRECTION('',(-1.,-8.881784197001E-016)); -#142597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142598 = PCURVE('',#142490,#142599); -#142599 = DEFINITIONAL_REPRESENTATION('',(#142600),#142604); -#142600 = LINE('',#142601,#142602); -#142601 = CARTESIAN_POINT('',(5.75,-5.000038352949E-002)); -#142602 = VECTOR('',#142603,1.); -#142603 = DIRECTION('',(-1.,-1.1653254136E-048)); -#142604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142605 = ORIENTED_EDGE('',*,*,#142606,.F.); -#142606 = EDGE_CURVE('',#142607,#142584,#142609,.T.); -#142607 = VERTEX_POINT('',#142608); -#142608 = CARTESIAN_POINT('',(5.85,10.74341632541,-0.308197125857)); -#142609 = SURFACE_CURVE('',#142610,(#142614,#142621),.PCURVE_S1.); -#142610 = LINE('',#142611,#142612); -#142611 = CARTESIAN_POINT('',(5.85,10.74341632541,-0.308197125857)); -#142612 = VECTOR('',#142613,1.); -#142613 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#142614 = PCURVE('',#142564,#142615); -#142615 = DEFINITIONAL_REPRESENTATION('',(#142616),#142620); -#142616 = LINE('',#142617,#142618); -#142617 = CARTESIAN_POINT('',(-5.85,-5.329070518201E-015)); -#142618 = VECTOR('',#142619,1.); -#142619 = DIRECTION('',(-6.725593854929E-015,1.)); -#142620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142621 = PCURVE('',#87896,#142622); -#142622 = DEFINITIONAL_REPRESENTATION('',(#142623),#142627); -#142623 = LINE('',#142624,#142625); -#142624 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#142625 = VECTOR('',#142626,1.); -#142626 = DIRECTION('',(0.E+000,1.)); -#142627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142628 = ORIENTED_EDGE('',*,*,#142629,.T.); -#142629 = EDGE_CURVE('',#142607,#142554,#142630,.T.); -#142630 = SURFACE_CURVE('',#142631,(#142635,#142642),.PCURVE_S1.); -#142631 = LINE('',#142632,#142633); -#142632 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#144959 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#144960 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#144961 = DEFINITIONAL_REPRESENTATION('',(#144962),#144966); +#144962 = LINE('',#144963,#144964); +#144963 = CARTESIAN_POINT('',(-5.65,-5.329070518201E-015)); +#144964 = VECTOR('',#144965,1.); +#144965 = DIRECTION('',(-6.725593854929E-015,1.)); +#144966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144967 = PCURVE('',#90232,#144968); +#144968 = DEFINITIONAL_REPRESENTATION('',(#144969),#144973); +#144969 = LINE('',#144970,#144971); +#144970 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#144971 = VECTOR('',#144972,1.); +#144972 = DIRECTION('',(0.E+000,1.)); +#144973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144974 = ORIENTED_EDGE('',*,*,#144975,.T.); +#144975 = EDGE_CURVE('',#144948,#144976,#144978,.T.); +#144976 = VERTEX_POINT('',#144977); +#144977 = CARTESIAN_POINT('',(5.85,11.,-0.308197125857)); +#144978 = SURFACE_CURVE('',#144979,(#144983,#144990),.PCURVE_S1.); +#144979 = LINE('',#144980,#144981); +#144980 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#144981 = VECTOR('',#144982,1.); +#144982 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#144983 = PCURVE('',#144956,#144984); +#144984 = DEFINITIONAL_REPRESENTATION('',(#144985),#144989); +#144985 = LINE('',#144986,#144987); +#144986 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#144987 = VECTOR('',#144988,1.); +#144988 = DIRECTION('',(-1.,-8.881784197001E-016)); +#144989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144990 = PCURVE('',#144882,#144991); +#144991 = DEFINITIONAL_REPRESENTATION('',(#144992),#144996); +#144992 = LINE('',#144993,#144994); +#144993 = CARTESIAN_POINT('',(5.75,-5.000038352949E-002)); +#144994 = VECTOR('',#144995,1.); +#144995 = DIRECTION('',(-1.,-1.1653254136E-048)); +#144996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#144997 = ORIENTED_EDGE('',*,*,#144998,.F.); +#144998 = EDGE_CURVE('',#144999,#144976,#145001,.T.); +#144999 = VERTEX_POINT('',#145000); +#145000 = CARTESIAN_POINT('',(5.85,10.74341632541,-0.308197125857)); +#145001 = SURFACE_CURVE('',#145002,(#145006,#145013),.PCURVE_S1.); +#145002 = LINE('',#145003,#145004); +#145003 = CARTESIAN_POINT('',(5.85,10.74341632541,-0.308197125857)); +#145004 = VECTOR('',#145005,1.); +#145005 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#145006 = PCURVE('',#144956,#145007); +#145007 = DEFINITIONAL_REPRESENTATION('',(#145008),#145012); +#145008 = LINE('',#145009,#145010); +#145009 = CARTESIAN_POINT('',(-5.85,-5.329070518201E-015)); +#145010 = VECTOR('',#145011,1.); +#145011 = DIRECTION('',(-6.725593854929E-015,1.)); +#145012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145013 = PCURVE('',#90288,#145014); +#145014 = DEFINITIONAL_REPRESENTATION('',(#145015),#145019); +#145015 = LINE('',#145016,#145017); +#145016 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#145017 = VECTOR('',#145018,1.); +#145018 = DIRECTION('',(0.E+000,1.)); +#145019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145020 = ORIENTED_EDGE('',*,*,#145021,.T.); +#145021 = EDGE_CURVE('',#144999,#144946,#145022,.T.); +#145022 = SURFACE_CURVE('',#145023,(#145027,#145034),.PCURVE_S1.); +#145023 = LINE('',#145024,#145025); +#145024 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#142633 = VECTOR('',#142634,1.); -#142634 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142635 = PCURVE('',#142564,#142636); -#142636 = DEFINITIONAL_REPRESENTATION('',(#142637),#142641); -#142637 = LINE('',#142638,#142639); -#142638 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142639 = VECTOR('',#142640,1.); -#142640 = DIRECTION('',(1.,8.881784197001E-016)); -#142641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142642 = PCURVE('',#142643,#142648); -#142643 = CYLINDRICAL_SURFACE('',#142644,0.308574064194); -#142644 = AXIS2_PLACEMENT_3D('',#142645,#142646,#142647); -#142645 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#145025 = VECTOR('',#145026,1.); +#145026 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145027 = PCURVE('',#144956,#145028); +#145028 = DEFINITIONAL_REPRESENTATION('',(#145029),#145033); +#145029 = LINE('',#145030,#145031); +#145030 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145031 = VECTOR('',#145032,1.); +#145032 = DIRECTION('',(1.,8.881784197001E-016)); +#145033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145034 = PCURVE('',#145035,#145040); +#145035 = CYLINDRICAL_SURFACE('',#145036,0.308574064194); +#145036 = AXIS2_PLACEMENT_3D('',#145037,#145038,#145039); +#145037 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#142646 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142647 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142648 = DEFINITIONAL_REPRESENTATION('',(#142649),#142652); -#142649 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142650,#142651), +#145038 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145039 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145040 = DEFINITIONAL_REPRESENTATION('',(#145041),#145044); +#145041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145042,#145043), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#142650 = CARTESIAN_POINT('',(4.761821717947,5.85)); -#142651 = CARTESIAN_POINT('',(4.761821717947,5.65)); -#142652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142653 = ADVANCED_FACE('',(#142654),#142539,.F.); -#142654 = FACE_BOUND('',#142655,.F.); -#142655 = EDGE_LOOP('',(#142656,#142657,#142684,#142711)); -#142656 = ORIENTED_EDGE('',*,*,#142525,.T.); -#142657 = ORIENTED_EDGE('',*,*,#142658,.F.); -#142658 = EDGE_CURVE('',#142659,#142445,#142661,.T.); -#142659 = VERTEX_POINT('',#142660); -#142660 = CARTESIAN_POINT('',(5.85,10.51959417205,0.E+000)); -#142661 = SURFACE_CURVE('',#142662,(#142667,#142673),.PCURVE_S1.); -#142662 = CIRCLE('',#142663,0.208574704164); -#142663 = AXIS2_PLACEMENT_3D('',#142664,#142665,#142666); -#142664 = CARTESIAN_POINT('',(5.85,10.728168876214,2.640924866458E-017) - ); -#142665 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142666 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142667 = PCURVE('',#142539,#142668); -#142668 = DEFINITIONAL_REPRESENTATION('',(#142669),#142672); -#142669 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142670,#142671), +#145042 = CARTESIAN_POINT('',(4.761821717947,5.85)); +#145043 = CARTESIAN_POINT('',(4.761821717947,5.65)); +#145044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145045 = ADVANCED_FACE('',(#145046),#144931,.F.); +#145046 = FACE_BOUND('',#145047,.F.); +#145047 = EDGE_LOOP('',(#145048,#145049,#145076,#145103)); +#145048 = ORIENTED_EDGE('',*,*,#144917,.T.); +#145049 = ORIENTED_EDGE('',*,*,#145050,.F.); +#145050 = EDGE_CURVE('',#145051,#144837,#145053,.T.); +#145051 = VERTEX_POINT('',#145052); +#145052 = CARTESIAN_POINT('',(5.85,10.51959417205,0.E+000)); +#145053 = SURFACE_CURVE('',#145054,(#145059,#145065),.PCURVE_S1.); +#145054 = CIRCLE('',#145055,0.208574704164); +#145055 = AXIS2_PLACEMENT_3D('',#145056,#145057,#145058); +#145056 = CARTESIAN_POINT('',(5.85,10.728168876214,2.640924866458E-017) + ); +#145057 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145058 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145059 = PCURVE('',#144931,#145060); +#145060 = DEFINITIONAL_REPRESENTATION('',(#145061),#145064); +#145061 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145062,#145063), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#142670 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#142671 = CARTESIAN_POINT('',(4.772630242227,5.85)); -#142672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145062 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#145063 = CARTESIAN_POINT('',(4.772630242227,5.85)); +#145064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#142673 = PCURVE('',#87896,#142674); -#142674 = DEFINITIONAL_REPRESENTATION('',(#142675),#142683); -#142675 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142676,#142677,#142678, - #142679,#142680,#142681,#142682),.UNSPECIFIED.,.T.,.F.) +#145065 = PCURVE('',#90288,#145066); +#145066 = DEFINITIONAL_REPRESENTATION('',(#145067),#145075); +#145067 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145068,#145069,#145070, + #145071,#145072,#145073,#145074),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#142676 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#142677 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#142678 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#142679 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#142680 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#142681 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#142682 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#142683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142684 = ORIENTED_EDGE('',*,*,#142685,.T.); -#142685 = EDGE_CURVE('',#142659,#142686,#142688,.T.); -#142686 = VERTEX_POINT('',#142687); -#142687 = CARTESIAN_POINT('',(5.65,10.51959417205,0.E+000)); -#142688 = SURFACE_CURVE('',#142689,(#142693,#142699),.PCURVE_S1.); -#142689 = LINE('',#142690,#142691); -#142690 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#145068 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#145069 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#145070 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#145071 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#145072 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#145073 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#145074 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#145075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145076 = ORIENTED_EDGE('',*,*,#145077,.T.); +#145077 = EDGE_CURVE('',#145051,#145078,#145080,.T.); +#145078 = VERTEX_POINT('',#145079); +#145079 = CARTESIAN_POINT('',(5.65,10.51959417205,0.E+000)); +#145080 = SURFACE_CURVE('',#145081,(#145085,#145091),.PCURVE_S1.); +#145081 = LINE('',#145082,#145083); +#145082 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#142691 = VECTOR('',#142692,1.); -#142692 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142693 = PCURVE('',#142539,#142694); -#142694 = DEFINITIONAL_REPRESENTATION('',(#142695),#142698); -#142695 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142696,#142697), +#145083 = VECTOR('',#145084,1.); +#145084 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145085 = PCURVE('',#144931,#145086); +#145086 = DEFINITIONAL_REPRESENTATION('',(#145087),#145090); +#145087 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145088,#145089), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#142696 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#142697 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#142698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145088 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#145089 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#145090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#142699 = PCURVE('',#142700,#142705); -#142700 = PLANE('',#142701); -#142701 = AXIS2_PLACEMENT_3D('',#142702,#142703,#142704); -#142702 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#145091 = PCURVE('',#145092,#145097); +#145092 = PLANE('',#145093); +#145093 = AXIS2_PLACEMENT_3D('',#145094,#145095,#145096); +#145094 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#142703 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142704 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142705 = DEFINITIONAL_REPRESENTATION('',(#142706),#142710); -#142706 = LINE('',#142707,#142708); -#142707 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#142708 = VECTOR('',#142709,1.); -#142709 = DIRECTION('',(-1.,0.E+000)); -#142710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142711 = ORIENTED_EDGE('',*,*,#142712,.T.); -#142712 = EDGE_CURVE('',#142686,#142503,#142713,.T.); -#142713 = SURFACE_CURVE('',#142714,(#142719,#142725),.PCURVE_S1.); -#142714 = CIRCLE('',#142715,0.208574704164); -#142715 = AXIS2_PLACEMENT_3D('',#142716,#142717,#142718); -#142716 = CARTESIAN_POINT('',(5.65,10.728168876214,2.640924866458E-017) - ); -#142717 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142718 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142719 = PCURVE('',#142539,#142720); -#142720 = DEFINITIONAL_REPRESENTATION('',(#142721),#142724); -#142721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142722,#142723), +#145095 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145096 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145097 = DEFINITIONAL_REPRESENTATION('',(#145098),#145102); +#145098 = LINE('',#145099,#145100); +#145099 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#145100 = VECTOR('',#145101,1.); +#145101 = DIRECTION('',(-1.,0.E+000)); +#145102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145103 = ORIENTED_EDGE('',*,*,#145104,.T.); +#145104 = EDGE_CURVE('',#145078,#144895,#145105,.T.); +#145105 = SURFACE_CURVE('',#145106,(#145111,#145117),.PCURVE_S1.); +#145106 = CIRCLE('',#145107,0.208574704164); +#145107 = AXIS2_PLACEMENT_3D('',#145108,#145109,#145110); +#145108 = CARTESIAN_POINT('',(5.65,10.728168876214,2.640924866458E-017) + ); +#145109 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145110 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145111 = PCURVE('',#144931,#145112); +#145112 = DEFINITIONAL_REPRESENTATION('',(#145113),#145116); +#145113 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145114,#145115), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#142722 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#142723 = CARTESIAN_POINT('',(4.772630242227,5.65)); -#142724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142725 = PCURVE('',#87840,#142726); -#142726 = DEFINITIONAL_REPRESENTATION('',(#142727),#142731); -#142727 = CIRCLE('',#142728,0.208574704164); -#142728 = AXIS2_PLACEMENT_2D('',#142729,#142730); -#142729 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#142730 = DIRECTION('',(0.E+000,1.)); -#142731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142732 = ADVANCED_FACE('',(#142733),#142643,.T.); -#142733 = FACE_BOUND('',#142734,.T.); -#142734 = EDGE_LOOP('',(#142735,#142736,#142786,#142813)); -#142735 = ORIENTED_EDGE('',*,*,#142629,.F.); -#142736 = ORIENTED_EDGE('',*,*,#142737,.F.); -#142737 = EDGE_CURVE('',#142738,#142607,#142740,.T.); -#142738 = VERTEX_POINT('',#142739); -#142739 = CARTESIAN_POINT('',(5.85,10.419594812019,0.E+000)); -#142740 = SURFACE_CURVE('',#142741,(#142746,#142775),.PCURVE_S1.); -#142741 = CIRCLE('',#142742,0.308574064194); -#142742 = AXIS2_PLACEMENT_3D('',#142743,#142744,#142745); -#142743 = CARTESIAN_POINT('',(5.85,10.728168876214,2.640924866458E-017) - ); -#142744 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142745 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142746 = PCURVE('',#142643,#142747); -#142747 = DEFINITIONAL_REPRESENTATION('',(#142748),#142774); -#142748 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142749,#142750,#142751, - #142752,#142753,#142754,#142755,#142756,#142757,#142758,#142759, - #142760,#142761,#142762,#142763,#142764,#142765,#142766,#142767, - #142768,#142769,#142770,#142771,#142772,#142773),.UNSPECIFIED.,.F., +#145114 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#145115 = CARTESIAN_POINT('',(4.772630242227,5.65)); +#145116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145117 = PCURVE('',#90232,#145118); +#145118 = DEFINITIONAL_REPRESENTATION('',(#145119),#145123); +#145119 = CIRCLE('',#145120,0.208574704164); +#145120 = AXIS2_PLACEMENT_2D('',#145121,#145122); +#145121 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#145122 = DIRECTION('',(0.E+000,1.)); +#145123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145124 = ADVANCED_FACE('',(#145125),#145035,.T.); +#145125 = FACE_BOUND('',#145126,.T.); +#145126 = EDGE_LOOP('',(#145127,#145128,#145178,#145205)); +#145127 = ORIENTED_EDGE('',*,*,#145021,.F.); +#145128 = ORIENTED_EDGE('',*,*,#145129,.F.); +#145129 = EDGE_CURVE('',#145130,#144999,#145132,.T.); +#145130 = VERTEX_POINT('',#145131); +#145131 = CARTESIAN_POINT('',(5.85,10.419594812019,0.E+000)); +#145132 = SURFACE_CURVE('',#145133,(#145138,#145167),.PCURVE_S1.); +#145133 = CIRCLE('',#145134,0.308574064194); +#145134 = AXIS2_PLACEMENT_3D('',#145135,#145136,#145137); +#145135 = CARTESIAN_POINT('',(5.85,10.728168876214,2.640924866458E-017) + ); +#145136 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145137 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145138 = PCURVE('',#145035,#145139); +#145139 = DEFINITIONAL_REPRESENTATION('',(#145140),#145166); +#145140 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145141,#145142,#145143, + #145144,#145145,#145146,#145147,#145148,#145149,#145150,#145151, + #145152,#145153,#145154,#145155,#145156,#145157,#145158,#145159, + #145160,#145161,#145162,#145163,#145164,#145165),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -175987,102 +178989,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#142749 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#142750 = CARTESIAN_POINT('',(3.166141578807,5.85)); -#142751 = CARTESIAN_POINT('',(3.215239429242,5.85)); -#142752 = CARTESIAN_POINT('',(3.288886204895,5.85)); -#142753 = CARTESIAN_POINT('',(3.362532980548,5.85)); -#142754 = CARTESIAN_POINT('',(3.4361797562,5.85)); -#142755 = CARTESIAN_POINT('',(3.509826531853,5.85)); -#142756 = CARTESIAN_POINT('',(3.583473307505,5.85)); -#142757 = CARTESIAN_POINT('',(3.657120083158,5.85)); -#142758 = CARTESIAN_POINT('',(3.730766858811,5.85)); -#142759 = CARTESIAN_POINT('',(3.804413634463,5.85)); -#142760 = CARTESIAN_POINT('',(3.878060410116,5.85)); -#142761 = CARTESIAN_POINT('',(3.951707185768,5.85)); -#142762 = CARTESIAN_POINT('',(4.025353961421,5.85)); -#142763 = CARTESIAN_POINT('',(4.099000737074,5.85)); -#142764 = CARTESIAN_POINT('',(4.172647512726,5.85)); -#142765 = CARTESIAN_POINT('',(4.246294288379,5.85)); -#142766 = CARTESIAN_POINT('',(4.319941064031,5.85)); -#142767 = CARTESIAN_POINT('',(4.393587839684,5.85)); -#142768 = CARTESIAN_POINT('',(4.467234615337,5.85)); -#142769 = CARTESIAN_POINT('',(4.540881390989,5.85)); -#142770 = CARTESIAN_POINT('',(4.614528166642,5.85)); -#142771 = CARTESIAN_POINT('',(4.688174942294,5.85)); -#142772 = CARTESIAN_POINT('',(4.737272792729,5.85)); -#142773 = CARTESIAN_POINT('',(4.761821717947,5.85)); -#142774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142775 = PCURVE('',#87896,#142776); -#142776 = DEFINITIONAL_REPRESENTATION('',(#142777),#142785); -#142777 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#142778,#142779,#142780, - #142781,#142782,#142783,#142784),.UNSPECIFIED.,.T.,.F.) +#145141 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#145142 = CARTESIAN_POINT('',(3.166141578807,5.85)); +#145143 = CARTESIAN_POINT('',(3.215239429242,5.85)); +#145144 = CARTESIAN_POINT('',(3.288886204895,5.85)); +#145145 = CARTESIAN_POINT('',(3.362532980548,5.85)); +#145146 = CARTESIAN_POINT('',(3.4361797562,5.85)); +#145147 = CARTESIAN_POINT('',(3.509826531853,5.85)); +#145148 = CARTESIAN_POINT('',(3.583473307505,5.85)); +#145149 = CARTESIAN_POINT('',(3.657120083158,5.85)); +#145150 = CARTESIAN_POINT('',(3.730766858811,5.85)); +#145151 = CARTESIAN_POINT('',(3.804413634463,5.85)); +#145152 = CARTESIAN_POINT('',(3.878060410116,5.85)); +#145153 = CARTESIAN_POINT('',(3.951707185768,5.85)); +#145154 = CARTESIAN_POINT('',(4.025353961421,5.85)); +#145155 = CARTESIAN_POINT('',(4.099000737074,5.85)); +#145156 = CARTESIAN_POINT('',(4.172647512726,5.85)); +#145157 = CARTESIAN_POINT('',(4.246294288379,5.85)); +#145158 = CARTESIAN_POINT('',(4.319941064031,5.85)); +#145159 = CARTESIAN_POINT('',(4.393587839684,5.85)); +#145160 = CARTESIAN_POINT('',(4.467234615337,5.85)); +#145161 = CARTESIAN_POINT('',(4.540881390989,5.85)); +#145162 = CARTESIAN_POINT('',(4.614528166642,5.85)); +#145163 = CARTESIAN_POINT('',(4.688174942294,5.85)); +#145164 = CARTESIAN_POINT('',(4.737272792729,5.85)); +#145165 = CARTESIAN_POINT('',(4.761821717947,5.85)); +#145166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145167 = PCURVE('',#90288,#145168); +#145168 = DEFINITIONAL_REPRESENTATION('',(#145169),#145177); +#145169 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145170,#145171,#145172, + #145173,#145174,#145175,#145176),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#142778 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#142779 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#142780 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#142781 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#142782 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#142783 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#142784 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#142785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142786 = ORIENTED_EDGE('',*,*,#142787,.F.); -#142787 = EDGE_CURVE('',#142788,#142738,#142790,.T.); -#142788 = VERTEX_POINT('',#142789); -#142789 = CARTESIAN_POINT('',(5.65,10.419594812019,0.E+000)); -#142790 = SURFACE_CURVE('',#142791,(#142795,#142801),.PCURVE_S1.); -#142791 = LINE('',#142792,#142793); -#142792 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#145170 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#145171 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#145172 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#145173 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#145174 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#145175 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#145176 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#145177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145178 = ORIENTED_EDGE('',*,*,#145179,.F.); +#145179 = EDGE_CURVE('',#145180,#145130,#145182,.T.); +#145180 = VERTEX_POINT('',#145181); +#145181 = CARTESIAN_POINT('',(5.65,10.419594812019,0.E+000)); +#145182 = SURFACE_CURVE('',#145183,(#145187,#145193),.PCURVE_S1.); +#145183 = LINE('',#145184,#145185); +#145184 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#142793 = VECTOR('',#142794,1.); -#142794 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142795 = PCURVE('',#142643,#142796); -#142796 = DEFINITIONAL_REPRESENTATION('',(#142797),#142800); -#142797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142798,#142799), +#145185 = VECTOR('',#145186,1.); +#145186 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145187 = PCURVE('',#145035,#145188); +#145188 = DEFINITIONAL_REPRESENTATION('',(#145189),#145192); +#145189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145190,#145191), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#142798 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#142799 = CARTESIAN_POINT('',(3.14159265359,5.85)); -#142800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145190 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#145191 = CARTESIAN_POINT('',(3.14159265359,5.85)); +#145192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#142801 = PCURVE('',#142802,#142807); -#142802 = PLANE('',#142803); -#142803 = AXIS2_PLACEMENT_3D('',#142804,#142805,#142806); -#142804 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#145193 = PCURVE('',#145194,#145199); +#145194 = PLANE('',#145195); +#145195 = AXIS2_PLACEMENT_3D('',#145196,#145197,#145198); +#145196 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#142805 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142806 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142807 = DEFINITIONAL_REPRESENTATION('',(#142808),#142812); -#142808 = LINE('',#142809,#142810); -#142809 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#142810 = VECTOR('',#142811,1.); -#142811 = DIRECTION('',(-1.,0.E+000)); -#142812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142813 = ORIENTED_EDGE('',*,*,#142814,.T.); -#142814 = EDGE_CURVE('',#142788,#142554,#142815,.T.); -#142815 = SURFACE_CURVE('',#142816,(#142821,#142850),.PCURVE_S1.); -#142816 = CIRCLE('',#142817,0.308574064194); -#142817 = AXIS2_PLACEMENT_3D('',#142818,#142819,#142820); -#142818 = CARTESIAN_POINT('',(5.65,10.728168876214,2.640924866458E-017) - ); -#142819 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142820 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#142821 = PCURVE('',#142643,#142822); -#142822 = DEFINITIONAL_REPRESENTATION('',(#142823),#142849); -#142823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#142824,#142825,#142826, - #142827,#142828,#142829,#142830,#142831,#142832,#142833,#142834, - #142835,#142836,#142837,#142838,#142839,#142840,#142841,#142842, - #142843,#142844,#142845,#142846,#142847,#142848),.UNSPECIFIED.,.F., +#145197 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145198 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145199 = DEFINITIONAL_REPRESENTATION('',(#145200),#145204); +#145200 = LINE('',#145201,#145202); +#145201 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#145202 = VECTOR('',#145203,1.); +#145203 = DIRECTION('',(-1.,0.E+000)); +#145204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145205 = ORIENTED_EDGE('',*,*,#145206,.T.); +#145206 = EDGE_CURVE('',#145180,#144946,#145207,.T.); +#145207 = SURFACE_CURVE('',#145208,(#145213,#145242),.PCURVE_S1.); +#145208 = CIRCLE('',#145209,0.308574064194); +#145209 = AXIS2_PLACEMENT_3D('',#145210,#145211,#145212); +#145210 = CARTESIAN_POINT('',(5.65,10.728168876214,2.640924866458E-017) + ); +#145211 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145212 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145213 = PCURVE('',#145035,#145214); +#145214 = DEFINITIONAL_REPRESENTATION('',(#145215),#145241); +#145215 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145216,#145217,#145218, + #145219,#145220,#145221,#145222,#145223,#145224,#145225,#145226, + #145227,#145228,#145229,#145230,#145231,#145232,#145233,#145234, + #145235,#145236,#145237,#145238,#145239,#145240),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -176090,339 +179092,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#142824 = CARTESIAN_POINT('',(3.14159265359,5.65)); -#142825 = CARTESIAN_POINT('',(3.166141578807,5.65)); -#142826 = CARTESIAN_POINT('',(3.215239429242,5.65)); -#142827 = CARTESIAN_POINT('',(3.288886204895,5.65)); -#142828 = CARTESIAN_POINT('',(3.362532980548,5.65)); -#142829 = CARTESIAN_POINT('',(3.4361797562,5.65)); -#142830 = CARTESIAN_POINT('',(3.509826531853,5.65)); -#142831 = CARTESIAN_POINT('',(3.583473307505,5.65)); -#142832 = CARTESIAN_POINT('',(3.657120083158,5.65)); -#142833 = CARTESIAN_POINT('',(3.730766858811,5.65)); -#142834 = CARTESIAN_POINT('',(3.804413634463,5.65)); -#142835 = CARTESIAN_POINT('',(3.878060410116,5.65)); -#142836 = CARTESIAN_POINT('',(3.951707185768,5.65)); -#142837 = CARTESIAN_POINT('',(4.025353961421,5.65)); -#142838 = CARTESIAN_POINT('',(4.099000737074,5.65)); -#142839 = CARTESIAN_POINT('',(4.172647512726,5.65)); -#142840 = CARTESIAN_POINT('',(4.246294288379,5.65)); -#142841 = CARTESIAN_POINT('',(4.319941064031,5.65)); -#142842 = CARTESIAN_POINT('',(4.393587839684,5.65)); -#142843 = CARTESIAN_POINT('',(4.467234615337,5.65)); -#142844 = CARTESIAN_POINT('',(4.540881390989,5.65)); -#142845 = CARTESIAN_POINT('',(4.614528166642,5.65)); -#142846 = CARTESIAN_POINT('',(4.688174942294,5.65)); -#142847 = CARTESIAN_POINT('',(4.737272792729,5.65)); -#142848 = CARTESIAN_POINT('',(4.761821717947,5.65)); -#142849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142850 = PCURVE('',#87840,#142851); -#142851 = DEFINITIONAL_REPRESENTATION('',(#142852),#142856); -#142852 = CIRCLE('',#142853,0.308574064194); -#142853 = AXIS2_PLACEMENT_2D('',#142854,#142855); -#142854 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#142855 = DIRECTION('',(0.E+000,1.)); -#142856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142857 = ADVANCED_FACE('',(#142858),#142802,.F.); -#142858 = FACE_BOUND('',#142859,.T.); -#142859 = EDGE_LOOP('',(#142860,#142889,#142910,#142911)); -#142860 = ORIENTED_EDGE('',*,*,#142861,.F.); -#142861 = EDGE_CURVE('',#142862,#142864,#142866,.T.); -#142862 = VERTEX_POINT('',#142863); -#142863 = CARTESIAN_POINT('',(5.65,10.419594812019,0.530776333563)); -#142864 = VERTEX_POINT('',#142865); -#142865 = CARTESIAN_POINT('',(5.85,10.419594812019,0.530776333563)); -#142866 = SURFACE_CURVE('',#142867,(#142871,#142878),.PCURVE_S1.); -#142867 = LINE('',#142868,#142869); -#142868 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#145216 = CARTESIAN_POINT('',(3.14159265359,5.65)); +#145217 = CARTESIAN_POINT('',(3.166141578807,5.65)); +#145218 = CARTESIAN_POINT('',(3.215239429242,5.65)); +#145219 = CARTESIAN_POINT('',(3.288886204895,5.65)); +#145220 = CARTESIAN_POINT('',(3.362532980548,5.65)); +#145221 = CARTESIAN_POINT('',(3.4361797562,5.65)); +#145222 = CARTESIAN_POINT('',(3.509826531853,5.65)); +#145223 = CARTESIAN_POINT('',(3.583473307505,5.65)); +#145224 = CARTESIAN_POINT('',(3.657120083158,5.65)); +#145225 = CARTESIAN_POINT('',(3.730766858811,5.65)); +#145226 = CARTESIAN_POINT('',(3.804413634463,5.65)); +#145227 = CARTESIAN_POINT('',(3.878060410116,5.65)); +#145228 = CARTESIAN_POINT('',(3.951707185768,5.65)); +#145229 = CARTESIAN_POINT('',(4.025353961421,5.65)); +#145230 = CARTESIAN_POINT('',(4.099000737074,5.65)); +#145231 = CARTESIAN_POINT('',(4.172647512726,5.65)); +#145232 = CARTESIAN_POINT('',(4.246294288379,5.65)); +#145233 = CARTESIAN_POINT('',(4.319941064031,5.65)); +#145234 = CARTESIAN_POINT('',(4.393587839684,5.65)); +#145235 = CARTESIAN_POINT('',(4.467234615337,5.65)); +#145236 = CARTESIAN_POINT('',(4.540881390989,5.65)); +#145237 = CARTESIAN_POINT('',(4.614528166642,5.65)); +#145238 = CARTESIAN_POINT('',(4.688174942294,5.65)); +#145239 = CARTESIAN_POINT('',(4.737272792729,5.65)); +#145240 = CARTESIAN_POINT('',(4.761821717947,5.65)); +#145241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145242 = PCURVE('',#90232,#145243); +#145243 = DEFINITIONAL_REPRESENTATION('',(#145244),#145248); +#145244 = CIRCLE('',#145245,0.308574064194); +#145245 = AXIS2_PLACEMENT_2D('',#145246,#145247); +#145246 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#145247 = DIRECTION('',(0.E+000,1.)); +#145248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145249 = ADVANCED_FACE('',(#145250),#145194,.F.); +#145250 = FACE_BOUND('',#145251,.T.); +#145251 = EDGE_LOOP('',(#145252,#145281,#145302,#145303)); +#145252 = ORIENTED_EDGE('',*,*,#145253,.F.); +#145253 = EDGE_CURVE('',#145254,#145256,#145258,.T.); +#145254 = VERTEX_POINT('',#145255); +#145255 = CARTESIAN_POINT('',(5.65,10.419594812019,0.530776333563)); +#145256 = VERTEX_POINT('',#145257); +#145257 = CARTESIAN_POINT('',(5.85,10.419594812019,0.530776333563)); +#145258 = SURFACE_CURVE('',#145259,(#145263,#145270),.PCURVE_S1.); +#145259 = LINE('',#145260,#145261); +#145260 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#142869 = VECTOR('',#142870,1.); -#142870 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#142871 = PCURVE('',#142802,#142872); -#142872 = DEFINITIONAL_REPRESENTATION('',(#142873),#142877); -#142873 = LINE('',#142874,#142875); -#142874 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142875 = VECTOR('',#142876,1.); -#142876 = DIRECTION('',(-1.,0.E+000)); -#142877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142878 = PCURVE('',#142879,#142884); -#142879 = CYLINDRICAL_SURFACE('',#142880,0.119270391569); -#142880 = AXIS2_PLACEMENT_3D('',#142881,#142882,#142883); -#142881 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#145261 = VECTOR('',#145262,1.); +#145262 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145263 = PCURVE('',#145194,#145264); +#145264 = DEFINITIONAL_REPRESENTATION('',(#145265),#145269); +#145265 = LINE('',#145266,#145267); +#145266 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145267 = VECTOR('',#145268,1.); +#145268 = DIRECTION('',(-1.,0.E+000)); +#145269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145270 = PCURVE('',#145271,#145276); +#145271 = CYLINDRICAL_SURFACE('',#145272,0.119270391569); +#145272 = AXIS2_PLACEMENT_3D('',#145273,#145274,#145275); +#145273 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#142882 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142883 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142884 = DEFINITIONAL_REPRESENTATION('',(#142885),#142888); -#142885 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142886,#142887), +#145274 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145275 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145276 = DEFINITIONAL_REPRESENTATION('',(#145277),#145280); +#145277 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145278,#145279), .UNSPECIFIED.,.F.,.F.,(2,2),(5.65,5.85),.PIECEWISE_BEZIER_KNOTS.); -#142886 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#142887 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#142888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142889 = ORIENTED_EDGE('',*,*,#142890,.T.); -#142890 = EDGE_CURVE('',#142862,#142788,#142891,.T.); -#142891 = SURFACE_CURVE('',#142892,(#142896,#142903),.PCURVE_S1.); -#142892 = LINE('',#142893,#142894); -#142893 = CARTESIAN_POINT('',(5.65,10.419594812019,0.530776333563)); -#142894 = VECTOR('',#142895,1.); -#142895 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142896 = PCURVE('',#142802,#142897); -#142897 = DEFINITIONAL_REPRESENTATION('',(#142898),#142902); -#142898 = LINE('',#142899,#142900); -#142899 = CARTESIAN_POINT('',(-5.65,0.E+000)); -#142900 = VECTOR('',#142901,1.); -#142901 = DIRECTION('',(0.E+000,-1.)); -#142902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142903 = PCURVE('',#87840,#142904); -#142904 = DEFINITIONAL_REPRESENTATION('',(#142905),#142909); -#142905 = LINE('',#142906,#142907); -#142906 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#142907 = VECTOR('',#142908,1.); -#142908 = DIRECTION('',(1.,0.E+000)); -#142909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142910 = ORIENTED_EDGE('',*,*,#142787,.T.); -#142911 = ORIENTED_EDGE('',*,*,#142912,.F.); -#142912 = EDGE_CURVE('',#142864,#142738,#142913,.T.); -#142913 = SURFACE_CURVE('',#142914,(#142918,#142925),.PCURVE_S1.); -#142914 = LINE('',#142915,#142916); -#142915 = CARTESIAN_POINT('',(5.85,10.419594812019,0.530776333563)); -#142916 = VECTOR('',#142917,1.); -#142917 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142918 = PCURVE('',#142802,#142919); -#142919 = DEFINITIONAL_REPRESENTATION('',(#142920),#142924); -#142920 = LINE('',#142921,#142922); -#142921 = CARTESIAN_POINT('',(-5.85,0.E+000)); -#142922 = VECTOR('',#142923,1.); -#142923 = DIRECTION('',(0.E+000,-1.)); -#142924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142925 = PCURVE('',#87896,#142926); -#142926 = DEFINITIONAL_REPRESENTATION('',(#142927),#142931); -#142927 = LINE('',#142928,#142929); -#142928 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#142929 = VECTOR('',#142930,1.); -#142930 = DIRECTION('',(-1.,0.E+000)); -#142931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142932 = ADVANCED_FACE('',(#142933),#142700,.F.); -#142933 = FACE_BOUND('',#142934,.T.); -#142934 = EDGE_LOOP('',(#142935,#142964,#142985,#142986)); -#142935 = ORIENTED_EDGE('',*,*,#142936,.F.); -#142936 = EDGE_CURVE('',#142937,#142939,#142941,.T.); -#142937 = VERTEX_POINT('',#142938); -#142938 = CARTESIAN_POINT('',(5.85,10.51959417205,0.530776333563)); -#142939 = VERTEX_POINT('',#142940); -#142940 = CARTESIAN_POINT('',(5.65,10.51959417205,0.530776333563)); -#142941 = SURFACE_CURVE('',#142942,(#142946,#142953),.PCURVE_S1.); -#142942 = LINE('',#142943,#142944); -#142943 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#145278 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#145279 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#145280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145281 = ORIENTED_EDGE('',*,*,#145282,.T.); +#145282 = EDGE_CURVE('',#145254,#145180,#145283,.T.); +#145283 = SURFACE_CURVE('',#145284,(#145288,#145295),.PCURVE_S1.); +#145284 = LINE('',#145285,#145286); +#145285 = CARTESIAN_POINT('',(5.65,10.419594812019,0.530776333563)); +#145286 = VECTOR('',#145287,1.); +#145287 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#145288 = PCURVE('',#145194,#145289); +#145289 = DEFINITIONAL_REPRESENTATION('',(#145290),#145294); +#145290 = LINE('',#145291,#145292); +#145291 = CARTESIAN_POINT('',(-5.65,0.E+000)); +#145292 = VECTOR('',#145293,1.); +#145293 = DIRECTION('',(0.E+000,-1.)); +#145294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145295 = PCURVE('',#90232,#145296); +#145296 = DEFINITIONAL_REPRESENTATION('',(#145297),#145301); +#145297 = LINE('',#145298,#145299); +#145298 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#145299 = VECTOR('',#145300,1.); +#145300 = DIRECTION('',(1.,0.E+000)); +#145301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145302 = ORIENTED_EDGE('',*,*,#145179,.T.); +#145303 = ORIENTED_EDGE('',*,*,#145304,.F.); +#145304 = EDGE_CURVE('',#145256,#145130,#145305,.T.); +#145305 = SURFACE_CURVE('',#145306,(#145310,#145317),.PCURVE_S1.); +#145306 = LINE('',#145307,#145308); +#145307 = CARTESIAN_POINT('',(5.85,10.419594812019,0.530776333563)); +#145308 = VECTOR('',#145309,1.); +#145309 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#145310 = PCURVE('',#145194,#145311); +#145311 = DEFINITIONAL_REPRESENTATION('',(#145312),#145316); +#145312 = LINE('',#145313,#145314); +#145313 = CARTESIAN_POINT('',(-5.85,0.E+000)); +#145314 = VECTOR('',#145315,1.); +#145315 = DIRECTION('',(0.E+000,-1.)); +#145316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145317 = PCURVE('',#90288,#145318); +#145318 = DEFINITIONAL_REPRESENTATION('',(#145319),#145323); +#145319 = LINE('',#145320,#145321); +#145320 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#145321 = VECTOR('',#145322,1.); +#145322 = DIRECTION('',(-1.,0.E+000)); +#145323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145324 = ADVANCED_FACE('',(#145325),#145092,.F.); +#145325 = FACE_BOUND('',#145326,.T.); +#145326 = EDGE_LOOP('',(#145327,#145356,#145377,#145378)); +#145327 = ORIENTED_EDGE('',*,*,#145328,.F.); +#145328 = EDGE_CURVE('',#145329,#145331,#145333,.T.); +#145329 = VERTEX_POINT('',#145330); +#145330 = CARTESIAN_POINT('',(5.85,10.51959417205,0.530776333563)); +#145331 = VERTEX_POINT('',#145332); +#145332 = CARTESIAN_POINT('',(5.65,10.51959417205,0.530776333563)); +#145333 = SURFACE_CURVE('',#145334,(#145338,#145345),.PCURVE_S1.); +#145334 = LINE('',#145335,#145336); +#145335 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#142944 = VECTOR('',#142945,1.); -#142945 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142946 = PCURVE('',#142700,#142947); -#142947 = DEFINITIONAL_REPRESENTATION('',(#142948),#142952); -#142948 = LINE('',#142949,#142950); -#142949 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#142950 = VECTOR('',#142951,1.); -#142951 = DIRECTION('',(-1.,0.E+000)); -#142952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142953 = PCURVE('',#142954,#142959); -#142954 = CYLINDRICAL_SURFACE('',#142955,0.2192697516); -#142955 = AXIS2_PLACEMENT_3D('',#142956,#142957,#142958); -#142956 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#145336 = VECTOR('',#145337,1.); +#145337 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145338 = PCURVE('',#145092,#145339); +#145339 = DEFINITIONAL_REPRESENTATION('',(#145340),#145344); +#145340 = LINE('',#145341,#145342); +#145341 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145342 = VECTOR('',#145343,1.); +#145343 = DIRECTION('',(-1.,0.E+000)); +#145344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145345 = PCURVE('',#145346,#145351); +#145346 = CYLINDRICAL_SURFACE('',#145347,0.2192697516); +#145347 = AXIS2_PLACEMENT_3D('',#145348,#145349,#145350); +#145348 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#142957 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#142958 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#142959 = DEFINITIONAL_REPRESENTATION('',(#142960),#142963); -#142960 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#142961,#142962), +#145349 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145350 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145351 = DEFINITIONAL_REPRESENTATION('',(#145352),#145355); +#145352 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145353,#145354), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.85,-5.65),.PIECEWISE_BEZIER_KNOTS.); -#142961 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#142962 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#142963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142964 = ORIENTED_EDGE('',*,*,#142965,.T.); -#142965 = EDGE_CURVE('',#142937,#142659,#142966,.T.); -#142966 = SURFACE_CURVE('',#142967,(#142971,#142978),.PCURVE_S1.); -#142967 = LINE('',#142968,#142969); -#142968 = CARTESIAN_POINT('',(5.85,10.51959417205,0.530776333563)); -#142969 = VECTOR('',#142970,1.); -#142970 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142971 = PCURVE('',#142700,#142972); -#142972 = DEFINITIONAL_REPRESENTATION('',(#142973),#142977); -#142973 = LINE('',#142974,#142975); -#142974 = CARTESIAN_POINT('',(5.85,0.E+000)); -#142975 = VECTOR('',#142976,1.); -#142976 = DIRECTION('',(0.E+000,-1.)); -#142977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142978 = PCURVE('',#87896,#142979); -#142979 = DEFINITIONAL_REPRESENTATION('',(#142980),#142984); -#142980 = LINE('',#142981,#142982); -#142981 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#142982 = VECTOR('',#142983,1.); -#142983 = DIRECTION('',(-1.,0.E+000)); -#142984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#142985 = ORIENTED_EDGE('',*,*,#142685,.T.); -#142986 = ORIENTED_EDGE('',*,*,#142987,.F.); -#142987 = EDGE_CURVE('',#142939,#142686,#142988,.T.); -#142988 = SURFACE_CURVE('',#142989,(#142993,#143000),.PCURVE_S1.); -#142989 = LINE('',#142990,#142991); -#142990 = CARTESIAN_POINT('',(5.65,10.51959417205,0.530776333563)); -#142991 = VECTOR('',#142992,1.); -#142992 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#142993 = PCURVE('',#142700,#142994); -#142994 = DEFINITIONAL_REPRESENTATION('',(#142995),#142999); -#142995 = LINE('',#142996,#142997); -#142996 = CARTESIAN_POINT('',(5.65,0.E+000)); -#142997 = VECTOR('',#142998,1.); -#142998 = DIRECTION('',(0.E+000,-1.)); -#142999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143000 = PCURVE('',#87840,#143001); -#143001 = DEFINITIONAL_REPRESENTATION('',(#143002),#143006); -#143002 = LINE('',#143003,#143004); -#143003 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#143004 = VECTOR('',#143005,1.); -#143005 = DIRECTION('',(1.,0.E+000)); -#143006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143007 = ADVANCED_FACE('',(#143008),#142879,.F.); -#143008 = FACE_BOUND('',#143009,.F.); -#143009 = EDGE_LOOP('',(#143010,#143037,#143059,#143080)); -#143010 = ORIENTED_EDGE('',*,*,#143011,.F.); -#143011 = EDGE_CURVE('',#143012,#142862,#143014,.T.); -#143012 = VERTEX_POINT('',#143013); -#143013 = CARTESIAN_POINT('',(5.65,10.303662633502,0.65)); -#143014 = SURFACE_CURVE('',#143015,(#143020,#143026),.PCURVE_S1.); -#143015 = CIRCLE('',#143016,0.119270391569); -#143016 = AXIS2_PLACEMENT_3D('',#143017,#143018,#143019); -#143017 = CARTESIAN_POINT('',(5.65,10.30032442045,0.530776333563)); -#143018 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143019 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143020 = PCURVE('',#142879,#143021); -#143021 = DEFINITIONAL_REPRESENTATION('',(#143022),#143025); -#143022 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143023,#143024), +#145353 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#145354 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#145355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145356 = ORIENTED_EDGE('',*,*,#145357,.T.); +#145357 = EDGE_CURVE('',#145329,#145051,#145358,.T.); +#145358 = SURFACE_CURVE('',#145359,(#145363,#145370),.PCURVE_S1.); +#145359 = LINE('',#145360,#145361); +#145360 = CARTESIAN_POINT('',(5.85,10.51959417205,0.530776333563)); +#145361 = VECTOR('',#145362,1.); +#145362 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#145363 = PCURVE('',#145092,#145364); +#145364 = DEFINITIONAL_REPRESENTATION('',(#145365),#145369); +#145365 = LINE('',#145366,#145367); +#145366 = CARTESIAN_POINT('',(5.85,0.E+000)); +#145367 = VECTOR('',#145368,1.); +#145368 = DIRECTION('',(0.E+000,-1.)); +#145369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145370 = PCURVE('',#90288,#145371); +#145371 = DEFINITIONAL_REPRESENTATION('',(#145372),#145376); +#145372 = LINE('',#145373,#145374); +#145373 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#145374 = VECTOR('',#145375,1.); +#145375 = DIRECTION('',(-1.,0.E+000)); +#145376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145377 = ORIENTED_EDGE('',*,*,#145077,.T.); +#145378 = ORIENTED_EDGE('',*,*,#145379,.F.); +#145379 = EDGE_CURVE('',#145331,#145078,#145380,.T.); +#145380 = SURFACE_CURVE('',#145381,(#145385,#145392),.PCURVE_S1.); +#145381 = LINE('',#145382,#145383); +#145382 = CARTESIAN_POINT('',(5.65,10.51959417205,0.530776333563)); +#145383 = VECTOR('',#145384,1.); +#145384 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#145385 = PCURVE('',#145092,#145386); +#145386 = DEFINITIONAL_REPRESENTATION('',(#145387),#145391); +#145387 = LINE('',#145388,#145389); +#145388 = CARTESIAN_POINT('',(5.65,0.E+000)); +#145389 = VECTOR('',#145390,1.); +#145390 = DIRECTION('',(0.E+000,-1.)); +#145391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145392 = PCURVE('',#90232,#145393); +#145393 = DEFINITIONAL_REPRESENTATION('',(#145394),#145398); +#145394 = LINE('',#145395,#145396); +#145395 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#145396 = VECTOR('',#145397,1.); +#145397 = DIRECTION('',(1.,0.E+000)); +#145398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145399 = ADVANCED_FACE('',(#145400),#145271,.F.); +#145400 = FACE_BOUND('',#145401,.F.); +#145401 = EDGE_LOOP('',(#145402,#145429,#145451,#145472)); +#145402 = ORIENTED_EDGE('',*,*,#145403,.F.); +#145403 = EDGE_CURVE('',#145404,#145254,#145406,.T.); +#145404 = VERTEX_POINT('',#145405); +#145405 = CARTESIAN_POINT('',(5.65,10.303662633502,0.65)); +#145406 = SURFACE_CURVE('',#145407,(#145412,#145418),.PCURVE_S1.); +#145407 = CIRCLE('',#145408,0.119270391569); +#145408 = AXIS2_PLACEMENT_3D('',#145409,#145410,#145411); +#145409 = CARTESIAN_POINT('',(5.65,10.30032442045,0.530776333563)); +#145410 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145411 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145412 = PCURVE('',#145271,#145413); +#145413 = DEFINITIONAL_REPRESENTATION('',(#145414),#145417); +#145414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145415,#145416), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#143023 = CARTESIAN_POINT('',(1.598788597134,-5.65)); -#143024 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#143025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145415 = CARTESIAN_POINT('',(1.598788597134,-5.65)); +#145416 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#145417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143026 = PCURVE('',#87840,#143027); -#143027 = DEFINITIONAL_REPRESENTATION('',(#143028),#143036); -#143028 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143029,#143030,#143031, - #143032,#143033,#143034,#143035),.UNSPECIFIED.,.T.,.F.) +#145418 = PCURVE('',#90232,#145419); +#145419 = DEFINITIONAL_REPRESENTATION('',(#145420),#145428); +#145420 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145421,#145422,#145423, + #145424,#145425,#145426,#145427),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#143029 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#143030 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#143031 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#143032 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#143033 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#143034 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#143035 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#143036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143037 = ORIENTED_EDGE('',*,*,#143038,.F.); -#143038 = EDGE_CURVE('',#143039,#143012,#143041,.T.); -#143039 = VERTEX_POINT('',#143040); -#143040 = CARTESIAN_POINT('',(5.85,10.303662633502,0.65)); -#143041 = SURFACE_CURVE('',#143042,(#143046,#143052),.PCURVE_S1.); -#143042 = LINE('',#143043,#143044); -#143043 = CARTESIAN_POINT('',(5.65,10.303662633502,0.65)); -#143044 = VECTOR('',#143045,1.); -#143045 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143046 = PCURVE('',#142879,#143047); -#143047 = DEFINITIONAL_REPRESENTATION('',(#143048),#143051); -#143048 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143049,#143050), +#145421 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#145422 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#145423 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#145424 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#145425 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#145426 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#145427 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#145428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145429 = ORIENTED_EDGE('',*,*,#145430,.F.); +#145430 = EDGE_CURVE('',#145431,#145404,#145433,.T.); +#145431 = VERTEX_POINT('',#145432); +#145432 = CARTESIAN_POINT('',(5.85,10.303662633502,0.65)); +#145433 = SURFACE_CURVE('',#145434,(#145438,#145444),.PCURVE_S1.); +#145434 = LINE('',#145435,#145436); +#145435 = CARTESIAN_POINT('',(5.65,10.303662633502,0.65)); +#145436 = VECTOR('',#145437,1.); +#145437 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145438 = PCURVE('',#145271,#145439); +#145439 = DEFINITIONAL_REPRESENTATION('',(#145440),#145443); +#145440 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145441,#145442), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#143049 = CARTESIAN_POINT('',(1.598788597134,-5.85)); -#143050 = CARTESIAN_POINT('',(1.598788597134,-5.65)); -#143051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143052 = PCURVE('',#87868,#143053); -#143053 = DEFINITIONAL_REPRESENTATION('',(#143054),#143058); -#143054 = LINE('',#143055,#143056); -#143055 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#143056 = VECTOR('',#143057,1.); -#143057 = DIRECTION('',(-8.881784197001E-016,-1.)); -#143058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143059 = ORIENTED_EDGE('',*,*,#143060,.T.); -#143060 = EDGE_CURVE('',#143039,#142864,#143061,.T.); -#143061 = SURFACE_CURVE('',#143062,(#143067,#143073),.PCURVE_S1.); -#143062 = CIRCLE('',#143063,0.119270391569); -#143063 = AXIS2_PLACEMENT_3D('',#143064,#143065,#143066); -#143064 = CARTESIAN_POINT('',(5.85,10.30032442045,0.530776333563)); -#143065 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143066 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143067 = PCURVE('',#142879,#143068); -#143068 = DEFINITIONAL_REPRESENTATION('',(#143069),#143072); -#143069 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143070,#143071), +#145441 = CARTESIAN_POINT('',(1.598788597134,-5.85)); +#145442 = CARTESIAN_POINT('',(1.598788597134,-5.65)); +#145443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145444 = PCURVE('',#90260,#145445); +#145445 = DEFINITIONAL_REPRESENTATION('',(#145446),#145450); +#145446 = LINE('',#145447,#145448); +#145447 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#145448 = VECTOR('',#145449,1.); +#145449 = DIRECTION('',(-8.881784197001E-016,-1.)); +#145450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145451 = ORIENTED_EDGE('',*,*,#145452,.T.); +#145452 = EDGE_CURVE('',#145431,#145256,#145453,.T.); +#145453 = SURFACE_CURVE('',#145454,(#145459,#145465),.PCURVE_S1.); +#145454 = CIRCLE('',#145455,0.119270391569); +#145455 = AXIS2_PLACEMENT_3D('',#145456,#145457,#145458); +#145456 = CARTESIAN_POINT('',(5.85,10.30032442045,0.530776333563)); +#145457 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145458 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145459 = PCURVE('',#145271,#145460); +#145460 = DEFINITIONAL_REPRESENTATION('',(#145461),#145464); +#145461 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145462,#145463), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#143070 = CARTESIAN_POINT('',(1.598788597134,-5.85)); -#143071 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#143072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143073 = PCURVE('',#87896,#143074); -#143074 = DEFINITIONAL_REPRESENTATION('',(#143075),#143079); -#143075 = CIRCLE('',#143076,0.119270391569); -#143076 = AXIS2_PLACEMENT_2D('',#143077,#143078); -#143077 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#143078 = DIRECTION('',(0.E+000,-1.)); -#143079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143080 = ORIENTED_EDGE('',*,*,#142861,.F.); -#143081 = ADVANCED_FACE('',(#143082),#142954,.T.); -#143082 = FACE_BOUND('',#143083,.T.); -#143083 = EDGE_LOOP('',(#143084,#143130,#143131,#143181)); -#143084 = ORIENTED_EDGE('',*,*,#143085,.T.); -#143085 = EDGE_CURVE('',#143086,#142937,#143088,.T.); -#143086 = VERTEX_POINT('',#143087); -#143087 = CARTESIAN_POINT('',(5.85,10.304819755875,0.75)); -#143088 = SURFACE_CURVE('',#143089,(#143094,#143123),.PCURVE_S1.); -#143089 = CIRCLE('',#143090,0.2192697516); -#143090 = AXIS2_PLACEMENT_3D('',#143091,#143092,#143093); -#143091 = CARTESIAN_POINT('',(5.85,10.30032442045,0.530776333563)); -#143092 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143093 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143094 = PCURVE('',#142954,#143095); -#143095 = DEFINITIONAL_REPRESENTATION('',(#143096),#143122); -#143096 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143097,#143098,#143099, - #143100,#143101,#143102,#143103,#143104,#143105,#143106,#143107, - #143108,#143109,#143110,#143111,#143112,#143113,#143114,#143115, - #143116,#143117,#143118,#143119,#143120,#143121),.UNSPECIFIED.,.F., +#145462 = CARTESIAN_POINT('',(1.598788597134,-5.85)); +#145463 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#145464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145465 = PCURVE('',#90288,#145466); +#145466 = DEFINITIONAL_REPRESENTATION('',(#145467),#145471); +#145467 = CIRCLE('',#145468,0.119270391569); +#145468 = AXIS2_PLACEMENT_2D('',#145469,#145470); +#145469 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#145470 = DIRECTION('',(0.E+000,-1.)); +#145471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145472 = ORIENTED_EDGE('',*,*,#145253,.F.); +#145473 = ADVANCED_FACE('',(#145474),#145346,.T.); +#145474 = FACE_BOUND('',#145475,.T.); +#145475 = EDGE_LOOP('',(#145476,#145522,#145523,#145573)); +#145476 = ORIENTED_EDGE('',*,*,#145477,.T.); +#145477 = EDGE_CURVE('',#145478,#145329,#145480,.T.); +#145478 = VERTEX_POINT('',#145479); +#145479 = CARTESIAN_POINT('',(5.85,10.304819755875,0.75)); +#145480 = SURFACE_CURVE('',#145481,(#145486,#145515),.PCURVE_S1.); +#145481 = CIRCLE('',#145482,0.2192697516); +#145482 = AXIS2_PLACEMENT_3D('',#145483,#145484,#145485); +#145483 = CARTESIAN_POINT('',(5.85,10.30032442045,0.530776333563)); +#145484 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145485 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145486 = PCURVE('',#145346,#145487); +#145487 = DEFINITIONAL_REPRESENTATION('',(#145488),#145514); +#145488 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145489,#145490,#145491, + #145492,#145493,#145494,#145495,#145496,#145497,#145498,#145499, + #145500,#145501,#145502,#145503,#145504,#145505,#145506,#145507, + #145508,#145509,#145510,#145511,#145512,#145513),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -176430,60 +179432,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#143097 = CARTESIAN_POINT('',(1.591299156552,-5.85)); -#143098 = CARTESIAN_POINT('',(1.614788451962,-5.85)); -#143099 = CARTESIAN_POINT('',(1.661767042781,-5.85)); -#143100 = CARTESIAN_POINT('',(1.73223492901,-5.85)); -#143101 = CARTESIAN_POINT('',(1.802702815239,-5.85)); -#143102 = CARTESIAN_POINT('',(1.873170701468,-5.85)); -#143103 = CARTESIAN_POINT('',(1.943638587697,-5.85)); -#143104 = CARTESIAN_POINT('',(2.014106473926,-5.85)); -#143105 = CARTESIAN_POINT('',(2.084574360155,-5.85)); -#143106 = CARTESIAN_POINT('',(2.155042246384,-5.85)); -#143107 = CARTESIAN_POINT('',(2.225510132613,-5.85)); -#143108 = CARTESIAN_POINT('',(2.295978018842,-5.85)); -#143109 = CARTESIAN_POINT('',(2.366445905071,-5.85)); -#143110 = CARTESIAN_POINT('',(2.4369137913,-5.85)); -#143111 = CARTESIAN_POINT('',(2.507381677529,-5.85)); -#143112 = CARTESIAN_POINT('',(2.577849563758,-5.85)); -#143113 = CARTESIAN_POINT('',(2.648317449987,-5.85)); -#143114 = CARTESIAN_POINT('',(2.718785336216,-5.85)); -#143115 = CARTESIAN_POINT('',(2.789253222445,-5.85)); -#143116 = CARTESIAN_POINT('',(2.859721108674,-5.85)); -#143117 = CARTESIAN_POINT('',(2.930188994903,-5.85)); -#143118 = CARTESIAN_POINT('',(3.000656881132,-5.85)); -#143119 = CARTESIAN_POINT('',(3.071124767361,-5.85)); -#143120 = CARTESIAN_POINT('',(3.11810335818,-5.85)); -#143121 = CARTESIAN_POINT('',(3.14159265359,-5.85)); -#143122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143123 = PCURVE('',#87896,#143124); -#143124 = DEFINITIONAL_REPRESENTATION('',(#143125),#143129); -#143125 = CIRCLE('',#143126,0.2192697516); -#143126 = AXIS2_PLACEMENT_2D('',#143127,#143128); -#143127 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#143128 = DIRECTION('',(0.E+000,-1.)); -#143129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143130 = ORIENTED_EDGE('',*,*,#142936,.T.); -#143131 = ORIENTED_EDGE('',*,*,#143132,.F.); -#143132 = EDGE_CURVE('',#143133,#142939,#143135,.T.); -#143133 = VERTEX_POINT('',#143134); -#143134 = CARTESIAN_POINT('',(5.65,10.304819755875,0.75)); -#143135 = SURFACE_CURVE('',#143136,(#143141,#143170),.PCURVE_S1.); -#143136 = CIRCLE('',#143137,0.2192697516); -#143137 = AXIS2_PLACEMENT_3D('',#143138,#143139,#143140); -#143138 = CARTESIAN_POINT('',(5.65,10.30032442045,0.530776333563)); -#143139 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143140 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143141 = PCURVE('',#142954,#143142); -#143142 = DEFINITIONAL_REPRESENTATION('',(#143143),#143169); -#143143 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143144,#143145,#143146, - #143147,#143148,#143149,#143150,#143151,#143152,#143153,#143154, - #143155,#143156,#143157,#143158,#143159,#143160,#143161,#143162, - #143163,#143164,#143165,#143166,#143167,#143168),.UNSPECIFIED.,.F., +#145489 = CARTESIAN_POINT('',(1.591299156552,-5.85)); +#145490 = CARTESIAN_POINT('',(1.614788451962,-5.85)); +#145491 = CARTESIAN_POINT('',(1.661767042781,-5.85)); +#145492 = CARTESIAN_POINT('',(1.73223492901,-5.85)); +#145493 = CARTESIAN_POINT('',(1.802702815239,-5.85)); +#145494 = CARTESIAN_POINT('',(1.873170701468,-5.85)); +#145495 = CARTESIAN_POINT('',(1.943638587697,-5.85)); +#145496 = CARTESIAN_POINT('',(2.014106473926,-5.85)); +#145497 = CARTESIAN_POINT('',(2.084574360155,-5.85)); +#145498 = CARTESIAN_POINT('',(2.155042246384,-5.85)); +#145499 = CARTESIAN_POINT('',(2.225510132613,-5.85)); +#145500 = CARTESIAN_POINT('',(2.295978018842,-5.85)); +#145501 = CARTESIAN_POINT('',(2.366445905071,-5.85)); +#145502 = CARTESIAN_POINT('',(2.4369137913,-5.85)); +#145503 = CARTESIAN_POINT('',(2.507381677529,-5.85)); +#145504 = CARTESIAN_POINT('',(2.577849563758,-5.85)); +#145505 = CARTESIAN_POINT('',(2.648317449987,-5.85)); +#145506 = CARTESIAN_POINT('',(2.718785336216,-5.85)); +#145507 = CARTESIAN_POINT('',(2.789253222445,-5.85)); +#145508 = CARTESIAN_POINT('',(2.859721108674,-5.85)); +#145509 = CARTESIAN_POINT('',(2.930188994903,-5.85)); +#145510 = CARTESIAN_POINT('',(3.000656881132,-5.85)); +#145511 = CARTESIAN_POINT('',(3.071124767361,-5.85)); +#145512 = CARTESIAN_POINT('',(3.11810335818,-5.85)); +#145513 = CARTESIAN_POINT('',(3.14159265359,-5.85)); +#145514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145515 = PCURVE('',#90288,#145516); +#145516 = DEFINITIONAL_REPRESENTATION('',(#145517),#145521); +#145517 = CIRCLE('',#145518,0.2192697516); +#145518 = AXIS2_PLACEMENT_2D('',#145519,#145520); +#145519 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#145520 = DIRECTION('',(0.E+000,-1.)); +#145521 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145522 = ORIENTED_EDGE('',*,*,#145328,.T.); +#145523 = ORIENTED_EDGE('',*,*,#145524,.F.); +#145524 = EDGE_CURVE('',#145525,#145331,#145527,.T.); +#145525 = VERTEX_POINT('',#145526); +#145526 = CARTESIAN_POINT('',(5.65,10.304819755875,0.75)); +#145527 = SURFACE_CURVE('',#145528,(#145533,#145562),.PCURVE_S1.); +#145528 = CIRCLE('',#145529,0.2192697516); +#145529 = AXIS2_PLACEMENT_3D('',#145530,#145531,#145532); +#145530 = CARTESIAN_POINT('',(5.65,10.30032442045,0.530776333563)); +#145531 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145532 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#145533 = PCURVE('',#145346,#145534); +#145534 = DEFINITIONAL_REPRESENTATION('',(#145535),#145561); +#145535 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145536,#145537,#145538, + #145539,#145540,#145541,#145542,#145543,#145544,#145545,#145546, + #145547,#145548,#145549,#145550,#145551,#145552,#145553,#145554, + #145555,#145556,#145557,#145558,#145559,#145560),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -176491,655 +179493,655 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#143144 = CARTESIAN_POINT('',(1.591299156552,-5.65)); -#143145 = CARTESIAN_POINT('',(1.614788451962,-5.65)); -#143146 = CARTESIAN_POINT('',(1.661767042781,-5.65)); -#143147 = CARTESIAN_POINT('',(1.73223492901,-5.65)); -#143148 = CARTESIAN_POINT('',(1.802702815239,-5.65)); -#143149 = CARTESIAN_POINT('',(1.873170701468,-5.65)); -#143150 = CARTESIAN_POINT('',(1.943638587697,-5.65)); -#143151 = CARTESIAN_POINT('',(2.014106473926,-5.65)); -#143152 = CARTESIAN_POINT('',(2.084574360155,-5.65)); -#143153 = CARTESIAN_POINT('',(2.155042246384,-5.65)); -#143154 = CARTESIAN_POINT('',(2.225510132613,-5.65)); -#143155 = CARTESIAN_POINT('',(2.295978018842,-5.65)); -#143156 = CARTESIAN_POINT('',(2.366445905071,-5.65)); -#143157 = CARTESIAN_POINT('',(2.4369137913,-5.65)); -#143158 = CARTESIAN_POINT('',(2.507381677529,-5.65)); -#143159 = CARTESIAN_POINT('',(2.577849563758,-5.65)); -#143160 = CARTESIAN_POINT('',(2.648317449987,-5.65)); -#143161 = CARTESIAN_POINT('',(2.718785336216,-5.65)); -#143162 = CARTESIAN_POINT('',(2.789253222445,-5.65)); -#143163 = CARTESIAN_POINT('',(2.859721108674,-5.65)); -#143164 = CARTESIAN_POINT('',(2.930188994903,-5.65)); -#143165 = CARTESIAN_POINT('',(3.000656881132,-5.65)); -#143166 = CARTESIAN_POINT('',(3.071124767361,-5.65)); -#143167 = CARTESIAN_POINT('',(3.11810335818,-5.65)); -#143168 = CARTESIAN_POINT('',(3.14159265359,-5.65)); -#143169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143170 = PCURVE('',#87840,#143171); -#143171 = DEFINITIONAL_REPRESENTATION('',(#143172),#143180); -#143172 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143173,#143174,#143175, - #143176,#143177,#143178,#143179),.UNSPECIFIED.,.T.,.F.) +#145536 = CARTESIAN_POINT('',(1.591299156552,-5.65)); +#145537 = CARTESIAN_POINT('',(1.614788451962,-5.65)); +#145538 = CARTESIAN_POINT('',(1.661767042781,-5.65)); +#145539 = CARTESIAN_POINT('',(1.73223492901,-5.65)); +#145540 = CARTESIAN_POINT('',(1.802702815239,-5.65)); +#145541 = CARTESIAN_POINT('',(1.873170701468,-5.65)); +#145542 = CARTESIAN_POINT('',(1.943638587697,-5.65)); +#145543 = CARTESIAN_POINT('',(2.014106473926,-5.65)); +#145544 = CARTESIAN_POINT('',(2.084574360155,-5.65)); +#145545 = CARTESIAN_POINT('',(2.155042246384,-5.65)); +#145546 = CARTESIAN_POINT('',(2.225510132613,-5.65)); +#145547 = CARTESIAN_POINT('',(2.295978018842,-5.65)); +#145548 = CARTESIAN_POINT('',(2.366445905071,-5.65)); +#145549 = CARTESIAN_POINT('',(2.4369137913,-5.65)); +#145550 = CARTESIAN_POINT('',(2.507381677529,-5.65)); +#145551 = CARTESIAN_POINT('',(2.577849563758,-5.65)); +#145552 = CARTESIAN_POINT('',(2.648317449987,-5.65)); +#145553 = CARTESIAN_POINT('',(2.718785336216,-5.65)); +#145554 = CARTESIAN_POINT('',(2.789253222445,-5.65)); +#145555 = CARTESIAN_POINT('',(2.859721108674,-5.65)); +#145556 = CARTESIAN_POINT('',(2.930188994903,-5.65)); +#145557 = CARTESIAN_POINT('',(3.000656881132,-5.65)); +#145558 = CARTESIAN_POINT('',(3.071124767361,-5.65)); +#145559 = CARTESIAN_POINT('',(3.11810335818,-5.65)); +#145560 = CARTESIAN_POINT('',(3.14159265359,-5.65)); +#145561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145562 = PCURVE('',#90232,#145563); +#145563 = DEFINITIONAL_REPRESENTATION('',(#145564),#145572); +#145564 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145565,#145566,#145567, + #145568,#145569,#145570,#145571),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#143173 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#143174 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#143175 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#143176 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#143177 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#143178 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#143179 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#143180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143181 = ORIENTED_EDGE('',*,*,#143182,.T.); -#143182 = EDGE_CURVE('',#143133,#143086,#143183,.T.); -#143183 = SURFACE_CURVE('',#143184,(#143188,#143194),.PCURVE_S1.); -#143184 = LINE('',#143185,#143186); -#143185 = CARTESIAN_POINT('',(5.65,10.304819755875,0.75)); -#143186 = VECTOR('',#143187,1.); -#143187 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143188 = PCURVE('',#142954,#143189); -#143189 = DEFINITIONAL_REPRESENTATION('',(#143190),#143193); -#143190 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143191,#143192), +#145565 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#145566 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#145567 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#145568 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#145569 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#145570 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#145571 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#145572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145573 = ORIENTED_EDGE('',*,*,#145574,.T.); +#145574 = EDGE_CURVE('',#145525,#145478,#145575,.T.); +#145575 = SURFACE_CURVE('',#145576,(#145580,#145586),.PCURVE_S1.); +#145576 = LINE('',#145577,#145578); +#145577 = CARTESIAN_POINT('',(5.65,10.304819755875,0.75)); +#145578 = VECTOR('',#145579,1.); +#145579 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145580 = PCURVE('',#145346,#145581); +#145581 = DEFINITIONAL_REPRESENTATION('',(#145582),#145585); +#145582 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145583,#145584), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#143191 = CARTESIAN_POINT('',(1.591299156552,-5.65)); -#143192 = CARTESIAN_POINT('',(1.591299156552,-5.85)); -#143193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143194 = PCURVE('',#87922,#143195); -#143195 = DEFINITIONAL_REPRESENTATION('',(#143196),#143200); -#143196 = LINE('',#143197,#143198); -#143197 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#143198 = VECTOR('',#143199,1.); -#143199 = DIRECTION('',(-8.881784197001E-016,1.)); -#143200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143201 = ADVANCED_FACE('',(#143202),#87840,.F.); -#143202 = FACE_BOUND('',#143203,.T.); -#143203 = EDGE_LOOP('',(#143204,#143225,#143226,#143227,#143228,#143229, - #143250,#143251,#143252,#143253,#143254,#143275)); -#143204 = ORIENTED_EDGE('',*,*,#143205,.F.); -#143205 = EDGE_CURVE('',#143133,#87825,#143206,.T.); -#143206 = SURFACE_CURVE('',#143207,(#143211,#143218),.PCURVE_S1.); -#143207 = LINE('',#143208,#143209); -#143208 = CARTESIAN_POINT('',(5.65,10.527847992439,0.75)); -#143209 = VECTOR('',#143210,1.); -#143210 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#143211 = PCURVE('',#87840,#143212); -#143212 = DEFINITIONAL_REPRESENTATION('',(#143213),#143217); -#143213 = LINE('',#143214,#143215); -#143214 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#143215 = VECTOR('',#143216,1.); -#143216 = DIRECTION('',(-3.563627120235E-016,-1.)); -#143217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143218 = PCURVE('',#87922,#143219); -#143219 = DEFINITIONAL_REPRESENTATION('',(#143220),#143224); -#143220 = LINE('',#143221,#143222); -#143221 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143222 = VECTOR('',#143223,1.); -#143223 = DIRECTION('',(-1.,2.164989446033E-063)); -#143224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143225 = ORIENTED_EDGE('',*,*,#143132,.T.); -#143226 = ORIENTED_EDGE('',*,*,#142987,.T.); -#143227 = ORIENTED_EDGE('',*,*,#142712,.T.); -#143228 = ORIENTED_EDGE('',*,*,#142502,.T.); -#143229 = ORIENTED_EDGE('',*,*,#143230,.T.); -#143230 = EDGE_CURVE('',#142475,#142556,#143231,.T.); -#143231 = SURFACE_CURVE('',#143232,(#143236,#143243),.PCURVE_S1.); -#143232 = LINE('',#143233,#143234); -#143233 = CARTESIAN_POINT('',(5.65,11.,1.159810404338E-002)); -#143234 = VECTOR('',#143235,1.); -#143235 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#143236 = PCURVE('',#87840,#143237); -#143237 = DEFINITIONAL_REPRESENTATION('',(#143238),#143242); -#143238 = LINE('',#143239,#143240); -#143239 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#143240 = VECTOR('',#143241,1.); -#143241 = DIRECTION('',(1.,-2.101748079665E-016)); -#143242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143243 = PCURVE('',#142490,#143244); -#143244 = DEFINITIONAL_REPRESENTATION('',(#143245),#143249); -#143245 = LINE('',#143246,#143247); -#143246 = CARTESIAN_POINT('',(0.1,0.269794846371)); -#143247 = VECTOR('',#143248,1.); -#143248 = DIRECTION('',(1.570395187386E-016,-1.)); -#143249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143250 = ORIENTED_EDGE('',*,*,#142553,.F.); -#143251 = ORIENTED_EDGE('',*,*,#142814,.F.); -#143252 = ORIENTED_EDGE('',*,*,#142890,.F.); -#143253 = ORIENTED_EDGE('',*,*,#143011,.F.); -#143254 = ORIENTED_EDGE('',*,*,#143255,.T.); -#143255 = EDGE_CURVE('',#143012,#87823,#143256,.T.); -#143256 = SURFACE_CURVE('',#143257,(#143261,#143268),.PCURVE_S1.); -#143257 = LINE('',#143258,#143259); -#143258 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); -#143259 = VECTOR('',#143260,1.); -#143260 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#143261 = PCURVE('',#87840,#143262); -#143262 = DEFINITIONAL_REPRESENTATION('',(#143263),#143267); -#143263 = LINE('',#143264,#143265); -#143264 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143265 = VECTOR('',#143266,1.); -#143266 = DIRECTION('',(-3.563627120235E-016,-1.)); -#143267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143268 = PCURVE('',#87868,#143269); -#143269 = DEFINITIONAL_REPRESENTATION('',(#143270),#143274); -#143270 = LINE('',#143271,#143272); -#143271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143272 = VECTOR('',#143273,1.); -#143273 = DIRECTION('',(1.,2.164989446033E-063)); -#143274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143275 = ORIENTED_EDGE('',*,*,#87822,.T.); -#143276 = ADVANCED_FACE('',(#143277),#87922,.F.); -#143277 = FACE_BOUND('',#143278,.T.); -#143278 = EDGE_LOOP('',(#143279,#143280,#143281,#143282)); -#143279 = ORIENTED_EDGE('',*,*,#143182,.F.); -#143280 = ORIENTED_EDGE('',*,*,#143205,.T.); -#143281 = ORIENTED_EDGE('',*,*,#87908,.T.); -#143282 = ORIENTED_EDGE('',*,*,#143283,.F.); -#143283 = EDGE_CURVE('',#143086,#87881,#143284,.T.); -#143284 = SURFACE_CURVE('',#143285,(#143289,#143296),.PCURVE_S1.); -#143285 = LINE('',#143286,#143287); -#143286 = CARTESIAN_POINT('',(5.85,10.527847992439,0.75)); -#143287 = VECTOR('',#143288,1.); -#143288 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#143289 = PCURVE('',#87922,#143290); -#143290 = DEFINITIONAL_REPRESENTATION('',(#143291),#143295); -#143291 = LINE('',#143292,#143293); -#143292 = CARTESIAN_POINT('',(0.E+000,0.2)); -#143293 = VECTOR('',#143294,1.); -#143294 = DIRECTION('',(-1.,2.164989446033E-063)); -#143295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143296 = PCURVE('',#87896,#143297); -#143297 = DEFINITIONAL_REPRESENTATION('',(#143298),#143302); -#143298 = LINE('',#143299,#143300); -#143299 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#143300 = VECTOR('',#143301,1.); -#143301 = DIRECTION('',(3.563627120235E-016,-1.)); -#143302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143303 = ADVANCED_FACE('',(#143304),#87896,.F.); -#143304 = FACE_BOUND('',#143305,.T.); -#143305 = EDGE_LOOP('',(#143306,#143327,#143328,#143329,#143330,#143331, - #143352,#143353,#143354,#143355,#143356,#143357)); -#143306 = ORIENTED_EDGE('',*,*,#143307,.F.); -#143307 = EDGE_CURVE('',#143039,#87853,#143308,.T.); -#143308 = SURFACE_CURVE('',#143309,(#143313,#143320),.PCURVE_S1.); -#143309 = LINE('',#143310,#143311); -#143310 = CARTESIAN_POINT('',(5.85,10.527847992439,0.65)); -#143311 = VECTOR('',#143312,1.); -#143312 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#143313 = PCURVE('',#87896,#143314); -#143314 = DEFINITIONAL_REPRESENTATION('',(#143315),#143319); -#143315 = LINE('',#143316,#143317); -#143316 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143317 = VECTOR('',#143318,1.); -#143318 = DIRECTION('',(3.563627120235E-016,-1.)); -#143319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143320 = PCURVE('',#87868,#143321); -#143321 = DEFINITIONAL_REPRESENTATION('',(#143322),#143326); -#143322 = LINE('',#143323,#143324); -#143323 = CARTESIAN_POINT('',(0.E+000,0.2)); -#143324 = VECTOR('',#143325,1.); -#143325 = DIRECTION('',(1.,2.164989446033E-063)); -#143326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143327 = ORIENTED_EDGE('',*,*,#143060,.T.); -#143328 = ORIENTED_EDGE('',*,*,#142912,.T.); -#143329 = ORIENTED_EDGE('',*,*,#142737,.T.); -#143330 = ORIENTED_EDGE('',*,*,#142606,.T.); -#143331 = ORIENTED_EDGE('',*,*,#143332,.T.); -#143332 = EDGE_CURVE('',#142584,#142447,#143333,.T.); -#143333 = SURFACE_CURVE('',#143334,(#143338,#143345),.PCURVE_S1.); -#143334 = LINE('',#143335,#143336); -#143335 = CARTESIAN_POINT('',(5.85,11.,1.159810404338E-002)); -#143336 = VECTOR('',#143337,1.); -#143337 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#143338 = PCURVE('',#87896,#143339); -#143339 = DEFINITIONAL_REPRESENTATION('',(#143340),#143344); -#143340 = LINE('',#143341,#143342); -#143341 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#143342 = VECTOR('',#143343,1.); -#143343 = DIRECTION('',(1.,2.101748079665E-016)); -#143344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143345 = PCURVE('',#142490,#143346); -#143346 = DEFINITIONAL_REPRESENTATION('',(#143347),#143351); -#143347 = LINE('',#143348,#143349); -#143348 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#143349 = VECTOR('',#143350,1.); -#143350 = DIRECTION('',(-1.570395187386E-016,1.)); -#143351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143352 = ORIENTED_EDGE('',*,*,#142444,.F.); -#143353 = ORIENTED_EDGE('',*,*,#142658,.F.); -#143354 = ORIENTED_EDGE('',*,*,#142965,.F.); -#143355 = ORIENTED_EDGE('',*,*,#143085,.F.); -#143356 = ORIENTED_EDGE('',*,*,#143283,.T.); -#143357 = ORIENTED_EDGE('',*,*,#87880,.T.); -#143358 = ADVANCED_FACE('',(#143359),#87868,.F.); -#143359 = FACE_BOUND('',#143360,.T.); -#143360 = EDGE_LOOP('',(#143361,#143362,#143363,#143364)); -#143361 = ORIENTED_EDGE('',*,*,#143038,.F.); -#143362 = ORIENTED_EDGE('',*,*,#143307,.T.); -#143363 = ORIENTED_EDGE('',*,*,#87852,.T.); -#143364 = ORIENTED_EDGE('',*,*,#143255,.F.); -#143365 = ADVANCED_FACE('',(#143366),#142490,.T.); -#143366 = FACE_BOUND('',#143367,.T.); -#143367 = EDGE_LOOP('',(#143368,#143369,#143370,#143371)); -#143368 = ORIENTED_EDGE('',*,*,#143332,.F.); -#143369 = ORIENTED_EDGE('',*,*,#142583,.F.); -#143370 = ORIENTED_EDGE('',*,*,#143230,.F.); -#143371 = ORIENTED_EDGE('',*,*,#142474,.F.); -#143372 = ADVANCED_FACE('',(#143373),#143387,.T.); -#143373 = FACE_BOUND('',#143374,.T.); -#143374 = EDGE_LOOP('',(#143375,#143405,#143433,#143456)); -#143375 = ORIENTED_EDGE('',*,*,#143376,.T.); -#143376 = EDGE_CURVE('',#143377,#143379,#143381,.T.); -#143377 = VERTEX_POINT('',#143378); -#143378 = CARTESIAN_POINT('',(5.35,10.740726081328,-0.208196358798)); -#143379 = VERTEX_POINT('',#143380); -#143380 = CARTESIAN_POINT('',(5.35,11.,-0.208196358798)); -#143381 = SURFACE_CURVE('',#143382,(#143386,#143398),.PCURVE_S1.); -#143382 = LINE('',#143383,#143384); -#143383 = CARTESIAN_POINT('',(5.35,10.740726081328,-0.208196358798)); -#143384 = VECTOR('',#143385,1.); -#143385 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#143386 = PCURVE('',#143387,#143392); -#143387 = PLANE('',#143388); -#143388 = AXIS2_PLACEMENT_3D('',#143389,#143390,#143391); -#143389 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#145583 = CARTESIAN_POINT('',(1.591299156552,-5.65)); +#145584 = CARTESIAN_POINT('',(1.591299156552,-5.85)); +#145585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145586 = PCURVE('',#90314,#145587); +#145587 = DEFINITIONAL_REPRESENTATION('',(#145588),#145592); +#145588 = LINE('',#145589,#145590); +#145589 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#145590 = VECTOR('',#145591,1.); +#145591 = DIRECTION('',(-8.881784197001E-016,1.)); +#145592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145593 = ADVANCED_FACE('',(#145594),#90232,.F.); +#145594 = FACE_BOUND('',#145595,.T.); +#145595 = EDGE_LOOP('',(#145596,#145617,#145618,#145619,#145620,#145621, + #145642,#145643,#145644,#145645,#145646,#145667)); +#145596 = ORIENTED_EDGE('',*,*,#145597,.F.); +#145597 = EDGE_CURVE('',#145525,#90217,#145598,.T.); +#145598 = SURFACE_CURVE('',#145599,(#145603,#145610),.PCURVE_S1.); +#145599 = LINE('',#145600,#145601); +#145600 = CARTESIAN_POINT('',(5.65,10.527847992439,0.75)); +#145601 = VECTOR('',#145602,1.); +#145602 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#145603 = PCURVE('',#90232,#145604); +#145604 = DEFINITIONAL_REPRESENTATION('',(#145605),#145609); +#145605 = LINE('',#145606,#145607); +#145606 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#145607 = VECTOR('',#145608,1.); +#145608 = DIRECTION('',(-3.563627120235E-016,-1.)); +#145609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145610 = PCURVE('',#90314,#145611); +#145611 = DEFINITIONAL_REPRESENTATION('',(#145612),#145616); +#145612 = LINE('',#145613,#145614); +#145613 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145614 = VECTOR('',#145615,1.); +#145615 = DIRECTION('',(-1.,2.164989446033E-063)); +#145616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145617 = ORIENTED_EDGE('',*,*,#145524,.T.); +#145618 = ORIENTED_EDGE('',*,*,#145379,.T.); +#145619 = ORIENTED_EDGE('',*,*,#145104,.T.); +#145620 = ORIENTED_EDGE('',*,*,#144894,.T.); +#145621 = ORIENTED_EDGE('',*,*,#145622,.T.); +#145622 = EDGE_CURVE('',#144867,#144948,#145623,.T.); +#145623 = SURFACE_CURVE('',#145624,(#145628,#145635),.PCURVE_S1.); +#145624 = LINE('',#145625,#145626); +#145625 = CARTESIAN_POINT('',(5.65,11.,1.159810404338E-002)); +#145626 = VECTOR('',#145627,1.); +#145627 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#145628 = PCURVE('',#90232,#145629); +#145629 = DEFINITIONAL_REPRESENTATION('',(#145630),#145634); +#145630 = LINE('',#145631,#145632); +#145631 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#145632 = VECTOR('',#145633,1.); +#145633 = DIRECTION('',(1.,-2.101748079665E-016)); +#145634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145635 = PCURVE('',#144882,#145636); +#145636 = DEFINITIONAL_REPRESENTATION('',(#145637),#145641); +#145637 = LINE('',#145638,#145639); +#145638 = CARTESIAN_POINT('',(0.1,0.269794846371)); +#145639 = VECTOR('',#145640,1.); +#145640 = DIRECTION('',(1.570395187386E-016,-1.)); +#145641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145642 = ORIENTED_EDGE('',*,*,#144945,.F.); +#145643 = ORIENTED_EDGE('',*,*,#145206,.F.); +#145644 = ORIENTED_EDGE('',*,*,#145282,.F.); +#145645 = ORIENTED_EDGE('',*,*,#145403,.F.); +#145646 = ORIENTED_EDGE('',*,*,#145647,.T.); +#145647 = EDGE_CURVE('',#145404,#90215,#145648,.T.); +#145648 = SURFACE_CURVE('',#145649,(#145653,#145660),.PCURVE_S1.); +#145649 = LINE('',#145650,#145651); +#145650 = CARTESIAN_POINT('',(5.65,10.527847992439,0.65)); +#145651 = VECTOR('',#145652,1.); +#145652 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#145653 = PCURVE('',#90232,#145654); +#145654 = DEFINITIONAL_REPRESENTATION('',(#145655),#145659); +#145655 = LINE('',#145656,#145657); +#145656 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145657 = VECTOR('',#145658,1.); +#145658 = DIRECTION('',(-3.563627120235E-016,-1.)); +#145659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145660 = PCURVE('',#90260,#145661); +#145661 = DEFINITIONAL_REPRESENTATION('',(#145662),#145666); +#145662 = LINE('',#145663,#145664); +#145663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145664 = VECTOR('',#145665,1.); +#145665 = DIRECTION('',(1.,2.164989446033E-063)); +#145666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145667 = ORIENTED_EDGE('',*,*,#90214,.T.); +#145668 = ADVANCED_FACE('',(#145669),#90314,.F.); +#145669 = FACE_BOUND('',#145670,.T.); +#145670 = EDGE_LOOP('',(#145671,#145672,#145673,#145674)); +#145671 = ORIENTED_EDGE('',*,*,#145574,.F.); +#145672 = ORIENTED_EDGE('',*,*,#145597,.T.); +#145673 = ORIENTED_EDGE('',*,*,#90300,.T.); +#145674 = ORIENTED_EDGE('',*,*,#145675,.F.); +#145675 = EDGE_CURVE('',#145478,#90273,#145676,.T.); +#145676 = SURFACE_CURVE('',#145677,(#145681,#145688),.PCURVE_S1.); +#145677 = LINE('',#145678,#145679); +#145678 = CARTESIAN_POINT('',(5.85,10.527847992439,0.75)); +#145679 = VECTOR('',#145680,1.); +#145680 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#145681 = PCURVE('',#90314,#145682); +#145682 = DEFINITIONAL_REPRESENTATION('',(#145683),#145687); +#145683 = LINE('',#145684,#145685); +#145684 = CARTESIAN_POINT('',(0.E+000,0.2)); +#145685 = VECTOR('',#145686,1.); +#145686 = DIRECTION('',(-1.,2.164989446033E-063)); +#145687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145688 = PCURVE('',#90288,#145689); +#145689 = DEFINITIONAL_REPRESENTATION('',(#145690),#145694); +#145690 = LINE('',#145691,#145692); +#145691 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#145692 = VECTOR('',#145693,1.); +#145693 = DIRECTION('',(3.563627120235E-016,-1.)); +#145694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145695 = ADVANCED_FACE('',(#145696),#90288,.F.); +#145696 = FACE_BOUND('',#145697,.T.); +#145697 = EDGE_LOOP('',(#145698,#145719,#145720,#145721,#145722,#145723, + #145744,#145745,#145746,#145747,#145748,#145749)); +#145698 = ORIENTED_EDGE('',*,*,#145699,.F.); +#145699 = EDGE_CURVE('',#145431,#90245,#145700,.T.); +#145700 = SURFACE_CURVE('',#145701,(#145705,#145712),.PCURVE_S1.); +#145701 = LINE('',#145702,#145703); +#145702 = CARTESIAN_POINT('',(5.85,10.527847992439,0.65)); +#145703 = VECTOR('',#145704,1.); +#145704 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#145705 = PCURVE('',#90288,#145706); +#145706 = DEFINITIONAL_REPRESENTATION('',(#145707),#145711); +#145707 = LINE('',#145708,#145709); +#145708 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145709 = VECTOR('',#145710,1.); +#145710 = DIRECTION('',(3.563627120235E-016,-1.)); +#145711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145712 = PCURVE('',#90260,#145713); +#145713 = DEFINITIONAL_REPRESENTATION('',(#145714),#145718); +#145714 = LINE('',#145715,#145716); +#145715 = CARTESIAN_POINT('',(0.E+000,0.2)); +#145716 = VECTOR('',#145717,1.); +#145717 = DIRECTION('',(1.,2.164989446033E-063)); +#145718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145719 = ORIENTED_EDGE('',*,*,#145452,.T.); +#145720 = ORIENTED_EDGE('',*,*,#145304,.T.); +#145721 = ORIENTED_EDGE('',*,*,#145129,.T.); +#145722 = ORIENTED_EDGE('',*,*,#144998,.T.); +#145723 = ORIENTED_EDGE('',*,*,#145724,.T.); +#145724 = EDGE_CURVE('',#144976,#144839,#145725,.T.); +#145725 = SURFACE_CURVE('',#145726,(#145730,#145737),.PCURVE_S1.); +#145726 = LINE('',#145727,#145728); +#145727 = CARTESIAN_POINT('',(5.85,11.,1.159810404338E-002)); +#145728 = VECTOR('',#145729,1.); +#145729 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#145730 = PCURVE('',#90288,#145731); +#145731 = DEFINITIONAL_REPRESENTATION('',(#145732),#145736); +#145732 = LINE('',#145733,#145734); +#145733 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#145734 = VECTOR('',#145735,1.); +#145735 = DIRECTION('',(1.,2.101748079665E-016)); +#145736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145737 = PCURVE('',#144882,#145738); +#145738 = DEFINITIONAL_REPRESENTATION('',(#145739),#145743); +#145739 = LINE('',#145740,#145741); +#145740 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#145741 = VECTOR('',#145742,1.); +#145742 = DIRECTION('',(-1.570395187386E-016,1.)); +#145743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145744 = ORIENTED_EDGE('',*,*,#144836,.F.); +#145745 = ORIENTED_EDGE('',*,*,#145050,.F.); +#145746 = ORIENTED_EDGE('',*,*,#145357,.F.); +#145747 = ORIENTED_EDGE('',*,*,#145477,.F.); +#145748 = ORIENTED_EDGE('',*,*,#145675,.T.); +#145749 = ORIENTED_EDGE('',*,*,#90272,.T.); +#145750 = ADVANCED_FACE('',(#145751),#90260,.F.); +#145751 = FACE_BOUND('',#145752,.T.); +#145752 = EDGE_LOOP('',(#145753,#145754,#145755,#145756)); +#145753 = ORIENTED_EDGE('',*,*,#145430,.F.); +#145754 = ORIENTED_EDGE('',*,*,#145699,.T.); +#145755 = ORIENTED_EDGE('',*,*,#90244,.T.); +#145756 = ORIENTED_EDGE('',*,*,#145647,.F.); +#145757 = ADVANCED_FACE('',(#145758),#144882,.T.); +#145758 = FACE_BOUND('',#145759,.T.); +#145759 = EDGE_LOOP('',(#145760,#145761,#145762,#145763)); +#145760 = ORIENTED_EDGE('',*,*,#145724,.F.); +#145761 = ORIENTED_EDGE('',*,*,#144975,.F.); +#145762 = ORIENTED_EDGE('',*,*,#145622,.F.); +#145763 = ORIENTED_EDGE('',*,*,#144866,.F.); +#145764 = ADVANCED_FACE('',(#145765),#145779,.T.); +#145765 = FACE_BOUND('',#145766,.T.); +#145766 = EDGE_LOOP('',(#145767,#145797,#145825,#145848)); +#145767 = ORIENTED_EDGE('',*,*,#145768,.T.); +#145768 = EDGE_CURVE('',#145769,#145771,#145773,.T.); +#145769 = VERTEX_POINT('',#145770); +#145770 = CARTESIAN_POINT('',(5.35,10.740726081328,-0.208196358798)); +#145771 = VERTEX_POINT('',#145772); +#145772 = CARTESIAN_POINT('',(5.35,11.,-0.208196358798)); +#145773 = SURFACE_CURVE('',#145774,(#145778,#145790),.PCURVE_S1.); +#145774 = LINE('',#145775,#145776); +#145775 = CARTESIAN_POINT('',(5.35,10.740726081328,-0.208196358798)); +#145776 = VECTOR('',#145777,1.); +#145777 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#145778 = PCURVE('',#145779,#145784); +#145779 = PLANE('',#145780); +#145780 = AXIS2_PLACEMENT_3D('',#145781,#145782,#145783); +#145781 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#143390 = DIRECTION('',(0.E+000,0.E+000,1.)); -#143391 = DIRECTION('',(1.,0.E+000,0.E+000)); -#143392 = DEFINITIONAL_REPRESENTATION('',(#143393),#143397); -#143393 = LINE('',#143394,#143395); -#143394 = CARTESIAN_POINT('',(5.35,-5.329070518201E-015)); -#143395 = VECTOR('',#143396,1.); -#143396 = DIRECTION('',(6.725593854929E-015,1.)); -#143397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143398 = PCURVE('',#86984,#143399); -#143399 = DEFINITIONAL_REPRESENTATION('',(#143400),#143404); -#143400 = LINE('',#143401,#143402); -#143401 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#143402 = VECTOR('',#143403,1.); -#143403 = DIRECTION('',(0.E+000,1.)); -#143404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143405 = ORIENTED_EDGE('',*,*,#143406,.T.); -#143406 = EDGE_CURVE('',#143379,#143407,#143409,.T.); -#143407 = VERTEX_POINT('',#143408); -#143408 = CARTESIAN_POINT('',(5.15,11.,-0.208196358798)); -#143409 = SURFACE_CURVE('',#143410,(#143414,#143421),.PCURVE_S1.); -#143410 = LINE('',#143411,#143412); -#143411 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#143412 = VECTOR('',#143413,1.); -#143413 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143414 = PCURVE('',#143387,#143415); -#143415 = DEFINITIONAL_REPRESENTATION('',(#143416),#143420); -#143416 = LINE('',#143417,#143418); -#143417 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#143418 = VECTOR('',#143419,1.); -#143419 = DIRECTION('',(-1.,8.881784197001E-016)); -#143420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143421 = PCURVE('',#143422,#143427); -#143422 = PLANE('',#143423); -#143423 = AXIS2_PLACEMENT_3D('',#143424,#143425,#143426); -#143424 = CARTESIAN_POINT('',(5.25,11.,-0.258196742327)); -#143425 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#143426 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#143427 = DEFINITIONAL_REPRESENTATION('',(#143428),#143432); -#143428 = LINE('',#143429,#143430); -#143429 = CARTESIAN_POINT('',(5.25,5.00003835295E-002)); -#143430 = VECTOR('',#143431,1.); -#143431 = DIRECTION('',(1.,1.1653254136E-048)); -#143432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143433 = ORIENTED_EDGE('',*,*,#143434,.F.); -#143434 = EDGE_CURVE('',#143435,#143407,#143437,.T.); -#143435 = VERTEX_POINT('',#143436); -#143436 = CARTESIAN_POINT('',(5.15,10.740726081328,-0.208196358798)); -#143437 = SURFACE_CURVE('',#143438,(#143442,#143449),.PCURVE_S1.); -#143438 = LINE('',#143439,#143440); -#143439 = CARTESIAN_POINT('',(5.15,10.740726081328,-0.208196358798)); -#143440 = VECTOR('',#143441,1.); -#143441 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#143442 = PCURVE('',#143387,#143443); -#143443 = DEFINITIONAL_REPRESENTATION('',(#143444),#143448); -#143444 = LINE('',#143445,#143446); -#143445 = CARTESIAN_POINT('',(5.15,-3.552713678801E-015)); -#143446 = VECTOR('',#143447,1.); -#143447 = DIRECTION('',(6.725593854929E-015,1.)); -#143448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143449 = PCURVE('',#86928,#143450); -#143450 = DEFINITIONAL_REPRESENTATION('',(#143451),#143455); -#143451 = LINE('',#143452,#143453); -#143452 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#143453 = VECTOR('',#143454,1.); -#143454 = DIRECTION('',(0.E+000,1.)); -#143455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143456 = ORIENTED_EDGE('',*,*,#143457,.T.); -#143457 = EDGE_CURVE('',#143435,#143377,#143458,.T.); -#143458 = SURFACE_CURVE('',#143459,(#143463,#143470),.PCURVE_S1.); -#143459 = LINE('',#143460,#143461); -#143460 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#145782 = DIRECTION('',(0.E+000,0.E+000,1.)); +#145783 = DIRECTION('',(1.,0.E+000,0.E+000)); +#145784 = DEFINITIONAL_REPRESENTATION('',(#145785),#145789); +#145785 = LINE('',#145786,#145787); +#145786 = CARTESIAN_POINT('',(5.35,-5.329070518201E-015)); +#145787 = VECTOR('',#145788,1.); +#145788 = DIRECTION('',(6.725593854929E-015,1.)); +#145789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145790 = PCURVE('',#89376,#145791); +#145791 = DEFINITIONAL_REPRESENTATION('',(#145792),#145796); +#145792 = LINE('',#145793,#145794); +#145793 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#145794 = VECTOR('',#145795,1.); +#145795 = DIRECTION('',(0.E+000,1.)); +#145796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145797 = ORIENTED_EDGE('',*,*,#145798,.T.); +#145798 = EDGE_CURVE('',#145771,#145799,#145801,.T.); +#145799 = VERTEX_POINT('',#145800); +#145800 = CARTESIAN_POINT('',(5.15,11.,-0.208196358798)); +#145801 = SURFACE_CURVE('',#145802,(#145806,#145813),.PCURVE_S1.); +#145802 = LINE('',#145803,#145804); +#145803 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#145804 = VECTOR('',#145805,1.); +#145805 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145806 = PCURVE('',#145779,#145807); +#145807 = DEFINITIONAL_REPRESENTATION('',(#145808),#145812); +#145808 = LINE('',#145809,#145810); +#145809 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#145810 = VECTOR('',#145811,1.); +#145811 = DIRECTION('',(-1.,8.881784197001E-016)); +#145812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145813 = PCURVE('',#145814,#145819); +#145814 = PLANE('',#145815); +#145815 = AXIS2_PLACEMENT_3D('',#145816,#145817,#145818); +#145816 = CARTESIAN_POINT('',(5.25,11.,-0.258196742327)); +#145817 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#145818 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#145819 = DEFINITIONAL_REPRESENTATION('',(#145820),#145824); +#145820 = LINE('',#145821,#145822); +#145821 = CARTESIAN_POINT('',(5.25,5.00003835295E-002)); +#145822 = VECTOR('',#145823,1.); +#145823 = DIRECTION('',(1.,1.1653254136E-048)); +#145824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145825 = ORIENTED_EDGE('',*,*,#145826,.F.); +#145826 = EDGE_CURVE('',#145827,#145799,#145829,.T.); +#145827 = VERTEX_POINT('',#145828); +#145828 = CARTESIAN_POINT('',(5.15,10.740726081328,-0.208196358798)); +#145829 = SURFACE_CURVE('',#145830,(#145834,#145841),.PCURVE_S1.); +#145830 = LINE('',#145831,#145832); +#145831 = CARTESIAN_POINT('',(5.15,10.740726081328,-0.208196358798)); +#145832 = VECTOR('',#145833,1.); +#145833 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#145834 = PCURVE('',#145779,#145835); +#145835 = DEFINITIONAL_REPRESENTATION('',(#145836),#145840); +#145836 = LINE('',#145837,#145838); +#145837 = CARTESIAN_POINT('',(5.15,-3.552713678801E-015)); +#145838 = VECTOR('',#145839,1.); +#145839 = DIRECTION('',(6.725593854929E-015,1.)); +#145840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145841 = PCURVE('',#89320,#145842); +#145842 = DEFINITIONAL_REPRESENTATION('',(#145843),#145847); +#145843 = LINE('',#145844,#145845); +#145844 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#145845 = VECTOR('',#145846,1.); +#145846 = DIRECTION('',(0.E+000,1.)); +#145847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145848 = ORIENTED_EDGE('',*,*,#145849,.T.); +#145849 = EDGE_CURVE('',#145827,#145769,#145850,.T.); +#145850 = SURFACE_CURVE('',#145851,(#145855,#145862),.PCURVE_S1.); +#145851 = LINE('',#145852,#145853); +#145852 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#143461 = VECTOR('',#143462,1.); -#143462 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143463 = PCURVE('',#143387,#143464); -#143464 = DEFINITIONAL_REPRESENTATION('',(#143465),#143469); -#143465 = LINE('',#143466,#143467); -#143466 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143467 = VECTOR('',#143468,1.); -#143468 = DIRECTION('',(1.,-8.881784197001E-016)); -#143469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143470 = PCURVE('',#143471,#143476); -#143471 = CYLINDRICAL_SURFACE('',#143472,0.208574704164); -#143472 = AXIS2_PLACEMENT_3D('',#143473,#143474,#143475); -#143473 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#145853 = VECTOR('',#145854,1.); +#145854 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145855 = PCURVE('',#145779,#145856); +#145856 = DEFINITIONAL_REPRESENTATION('',(#145857),#145861); +#145857 = LINE('',#145858,#145859); +#145858 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145859 = VECTOR('',#145860,1.); +#145860 = DIRECTION('',(1.,-8.881784197001E-016)); +#145861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145862 = PCURVE('',#145863,#145868); +#145863 = CYLINDRICAL_SURFACE('',#145864,0.208574704164); +#145864 = AXIS2_PLACEMENT_3D('',#145865,#145866,#145867); +#145865 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#143474 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143475 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143476 = DEFINITIONAL_REPRESENTATION('',(#143477),#143480); -#143477 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143478,#143479), +#145866 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145867 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145868 = DEFINITIONAL_REPRESENTATION('',(#145869),#145872); +#145869 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145870,#145871), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#143478 = CARTESIAN_POINT('',(4.772630242227,5.15)); -#143479 = CARTESIAN_POINT('',(4.772630242227,5.35)); -#143480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145870 = CARTESIAN_POINT('',(4.772630242227,5.15)); +#145871 = CARTESIAN_POINT('',(4.772630242227,5.35)); +#145872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145873 = ADVANCED_FACE('',(#145874),#145888,.T.); +#145874 = FACE_BOUND('',#145875,.T.); +#145875 = EDGE_LOOP('',(#145876,#145906,#145929,#145952)); +#145876 = ORIENTED_EDGE('',*,*,#145877,.T.); +#145877 = EDGE_CURVE('',#145878,#145880,#145882,.T.); +#145878 = VERTEX_POINT('',#145879); +#145879 = CARTESIAN_POINT('',(5.15,10.74341632541,-0.308197125857)); +#145880 = VERTEX_POINT('',#145881); +#145881 = CARTESIAN_POINT('',(5.15,11.,-0.308197125857)); +#145882 = SURFACE_CURVE('',#145883,(#145887,#145899),.PCURVE_S1.); +#145883 = LINE('',#145884,#145885); +#145884 = CARTESIAN_POINT('',(5.15,10.74341632541,-0.308197125857)); +#145885 = VECTOR('',#145886,1.); +#145886 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#145887 = PCURVE('',#145888,#145893); +#145888 = PLANE('',#145889); +#145889 = AXIS2_PLACEMENT_3D('',#145890,#145891,#145892); +#145890 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#145891 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#145892 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#145893 = DEFINITIONAL_REPRESENTATION('',(#145894),#145898); +#145894 = LINE('',#145895,#145896); +#145895 = CARTESIAN_POINT('',(-5.15,-5.329070518201E-015)); +#145896 = VECTOR('',#145897,1.); +#145897 = DIRECTION('',(-6.725593854929E-015,1.)); +#145898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145899 = PCURVE('',#89320,#145900); +#145900 = DEFINITIONAL_REPRESENTATION('',(#145901),#145905); +#145901 = LINE('',#145902,#145903); +#145902 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#145903 = VECTOR('',#145904,1.); +#145904 = DIRECTION('',(0.E+000,1.)); +#145905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145906 = ORIENTED_EDGE('',*,*,#145907,.T.); +#145907 = EDGE_CURVE('',#145880,#145908,#145910,.T.); +#145908 = VERTEX_POINT('',#145909); +#145909 = CARTESIAN_POINT('',(5.35,11.,-0.308197125857)); +#145910 = SURFACE_CURVE('',#145911,(#145915,#145922),.PCURVE_S1.); +#145911 = LINE('',#145912,#145913); +#145912 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#145913 = VECTOR('',#145914,1.); +#145914 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145915 = PCURVE('',#145888,#145916); +#145916 = DEFINITIONAL_REPRESENTATION('',(#145917),#145921); +#145917 = LINE('',#145918,#145919); +#145918 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#145919 = VECTOR('',#145920,1.); +#145920 = DIRECTION('',(-1.,-8.881784197001E-016)); +#145921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143481 = ADVANCED_FACE('',(#143482),#143496,.T.); -#143482 = FACE_BOUND('',#143483,.T.); -#143483 = EDGE_LOOP('',(#143484,#143514,#143537,#143560)); -#143484 = ORIENTED_EDGE('',*,*,#143485,.T.); -#143485 = EDGE_CURVE('',#143486,#143488,#143490,.T.); -#143486 = VERTEX_POINT('',#143487); -#143487 = CARTESIAN_POINT('',(5.15,10.74341632541,-0.308197125857)); -#143488 = VERTEX_POINT('',#143489); -#143489 = CARTESIAN_POINT('',(5.15,11.,-0.308197125857)); -#143490 = SURFACE_CURVE('',#143491,(#143495,#143507),.PCURVE_S1.); -#143491 = LINE('',#143492,#143493); -#143492 = CARTESIAN_POINT('',(5.15,10.74341632541,-0.308197125857)); -#143493 = VECTOR('',#143494,1.); -#143494 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#143495 = PCURVE('',#143496,#143501); -#143496 = PLANE('',#143497); -#143497 = AXIS2_PLACEMENT_3D('',#143498,#143499,#143500); -#143498 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#143499 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#143500 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#143501 = DEFINITIONAL_REPRESENTATION('',(#143502),#143506); -#143502 = LINE('',#143503,#143504); -#143503 = CARTESIAN_POINT('',(-5.15,-5.329070518201E-015)); -#143504 = VECTOR('',#143505,1.); -#143505 = DIRECTION('',(-6.725593854929E-015,1.)); -#143506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143507 = PCURVE('',#86928,#143508); -#143508 = DEFINITIONAL_REPRESENTATION('',(#143509),#143513); -#143509 = LINE('',#143510,#143511); -#143510 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#143511 = VECTOR('',#143512,1.); -#143512 = DIRECTION('',(0.E+000,1.)); -#143513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143514 = ORIENTED_EDGE('',*,*,#143515,.T.); -#143515 = EDGE_CURVE('',#143488,#143516,#143518,.T.); -#143516 = VERTEX_POINT('',#143517); -#143517 = CARTESIAN_POINT('',(5.35,11.,-0.308197125857)); -#143518 = SURFACE_CURVE('',#143519,(#143523,#143530),.PCURVE_S1.); -#143519 = LINE('',#143520,#143521); -#143520 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#143521 = VECTOR('',#143522,1.); -#143522 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143523 = PCURVE('',#143496,#143524); -#143524 = DEFINITIONAL_REPRESENTATION('',(#143525),#143529); -#143525 = LINE('',#143526,#143527); -#143526 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#143527 = VECTOR('',#143528,1.); -#143528 = DIRECTION('',(-1.,-8.881784197001E-016)); -#143529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143530 = PCURVE('',#143422,#143531); -#143531 = DEFINITIONAL_REPRESENTATION('',(#143532),#143536); -#143532 = LINE('',#143533,#143534); -#143533 = CARTESIAN_POINT('',(5.25,-5.000038352949E-002)); -#143534 = VECTOR('',#143535,1.); -#143535 = DIRECTION('',(-1.,-1.1653254136E-048)); -#143536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143537 = ORIENTED_EDGE('',*,*,#143538,.F.); -#143538 = EDGE_CURVE('',#143539,#143516,#143541,.T.); -#143539 = VERTEX_POINT('',#143540); -#143540 = CARTESIAN_POINT('',(5.35,10.74341632541,-0.308197125857)); -#143541 = SURFACE_CURVE('',#143542,(#143546,#143553),.PCURVE_S1.); -#143542 = LINE('',#143543,#143544); -#143543 = CARTESIAN_POINT('',(5.35,10.74341632541,-0.308197125857)); -#143544 = VECTOR('',#143545,1.); -#143545 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#143546 = PCURVE('',#143496,#143547); -#143547 = DEFINITIONAL_REPRESENTATION('',(#143548),#143552); -#143548 = LINE('',#143549,#143550); -#143549 = CARTESIAN_POINT('',(-5.35,-5.329070518201E-015)); -#143550 = VECTOR('',#143551,1.); -#143551 = DIRECTION('',(-6.725593854929E-015,1.)); -#143552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143553 = PCURVE('',#86984,#143554); -#143554 = DEFINITIONAL_REPRESENTATION('',(#143555),#143559); -#143555 = LINE('',#143556,#143557); -#143556 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#143557 = VECTOR('',#143558,1.); -#143558 = DIRECTION('',(0.E+000,1.)); -#143559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143560 = ORIENTED_EDGE('',*,*,#143561,.T.); -#143561 = EDGE_CURVE('',#143539,#143486,#143562,.T.); -#143562 = SURFACE_CURVE('',#143563,(#143567,#143574),.PCURVE_S1.); -#143563 = LINE('',#143564,#143565); -#143564 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#145922 = PCURVE('',#145814,#145923); +#145923 = DEFINITIONAL_REPRESENTATION('',(#145924),#145928); +#145924 = LINE('',#145925,#145926); +#145925 = CARTESIAN_POINT('',(5.25,-5.000038352949E-002)); +#145926 = VECTOR('',#145927,1.); +#145927 = DIRECTION('',(-1.,-1.1653254136E-048)); +#145928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145929 = ORIENTED_EDGE('',*,*,#145930,.F.); +#145930 = EDGE_CURVE('',#145931,#145908,#145933,.T.); +#145931 = VERTEX_POINT('',#145932); +#145932 = CARTESIAN_POINT('',(5.35,10.74341632541,-0.308197125857)); +#145933 = SURFACE_CURVE('',#145934,(#145938,#145945),.PCURVE_S1.); +#145934 = LINE('',#145935,#145936); +#145935 = CARTESIAN_POINT('',(5.35,10.74341632541,-0.308197125857)); +#145936 = VECTOR('',#145937,1.); +#145937 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#145938 = PCURVE('',#145888,#145939); +#145939 = DEFINITIONAL_REPRESENTATION('',(#145940),#145944); +#145940 = LINE('',#145941,#145942); +#145941 = CARTESIAN_POINT('',(-5.35,-5.329070518201E-015)); +#145942 = VECTOR('',#145943,1.); +#145943 = DIRECTION('',(-6.725593854929E-015,1.)); +#145944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145945 = PCURVE('',#89376,#145946); +#145946 = DEFINITIONAL_REPRESENTATION('',(#145947),#145951); +#145947 = LINE('',#145948,#145949); +#145948 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#145949 = VECTOR('',#145950,1.); +#145950 = DIRECTION('',(0.E+000,1.)); +#145951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145952 = ORIENTED_EDGE('',*,*,#145953,.T.); +#145953 = EDGE_CURVE('',#145931,#145878,#145954,.T.); +#145954 = SURFACE_CURVE('',#145955,(#145959,#145966),.PCURVE_S1.); +#145955 = LINE('',#145956,#145957); +#145956 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#143565 = VECTOR('',#143566,1.); -#143566 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143567 = PCURVE('',#143496,#143568); -#143568 = DEFINITIONAL_REPRESENTATION('',(#143569),#143573); -#143569 = LINE('',#143570,#143571); -#143570 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143571 = VECTOR('',#143572,1.); -#143572 = DIRECTION('',(1.,8.881784197001E-016)); -#143573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143574 = PCURVE('',#143575,#143580); -#143575 = CYLINDRICAL_SURFACE('',#143576,0.308574064194); -#143576 = AXIS2_PLACEMENT_3D('',#143577,#143578,#143579); -#143577 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#145957 = VECTOR('',#145958,1.); +#145958 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#145959 = PCURVE('',#145888,#145960); +#145960 = DEFINITIONAL_REPRESENTATION('',(#145961),#145965); +#145961 = LINE('',#145962,#145963); +#145962 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#145963 = VECTOR('',#145964,1.); +#145964 = DIRECTION('',(1.,8.881784197001E-016)); +#145965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145966 = PCURVE('',#145967,#145972); +#145967 = CYLINDRICAL_SURFACE('',#145968,0.308574064194); +#145968 = AXIS2_PLACEMENT_3D('',#145969,#145970,#145971); +#145969 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#143578 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143579 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143580 = DEFINITIONAL_REPRESENTATION('',(#143581),#143584); -#143581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143582,#143583), +#145970 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145971 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145972 = DEFINITIONAL_REPRESENTATION('',(#145973),#145976); +#145973 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145974,#145975), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#143582 = CARTESIAN_POINT('',(4.761821717947,5.35)); -#143583 = CARTESIAN_POINT('',(4.761821717947,5.15)); -#143584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143585 = ADVANCED_FACE('',(#143586),#143471,.F.); -#143586 = FACE_BOUND('',#143587,.F.); -#143587 = EDGE_LOOP('',(#143588,#143589,#143616,#143643)); -#143588 = ORIENTED_EDGE('',*,*,#143457,.T.); -#143589 = ORIENTED_EDGE('',*,*,#143590,.F.); -#143590 = EDGE_CURVE('',#143591,#143377,#143593,.T.); -#143591 = VERTEX_POINT('',#143592); -#143592 = CARTESIAN_POINT('',(5.35,10.51959417205,0.E+000)); -#143593 = SURFACE_CURVE('',#143594,(#143599,#143605),.PCURVE_S1.); -#143594 = CIRCLE('',#143595,0.208574704164); -#143595 = AXIS2_PLACEMENT_3D('',#143596,#143597,#143598); -#143596 = CARTESIAN_POINT('',(5.35,10.728168876214,2.640924866458E-017) - ); -#143597 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143598 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143599 = PCURVE('',#143471,#143600); -#143600 = DEFINITIONAL_REPRESENTATION('',(#143601),#143604); -#143601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143602,#143603), +#145974 = CARTESIAN_POINT('',(4.761821717947,5.35)); +#145975 = CARTESIAN_POINT('',(4.761821717947,5.15)); +#145976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#145977 = ADVANCED_FACE('',(#145978),#145863,.F.); +#145978 = FACE_BOUND('',#145979,.F.); +#145979 = EDGE_LOOP('',(#145980,#145981,#146008,#146035)); +#145980 = ORIENTED_EDGE('',*,*,#145849,.T.); +#145981 = ORIENTED_EDGE('',*,*,#145982,.F.); +#145982 = EDGE_CURVE('',#145983,#145769,#145985,.T.); +#145983 = VERTEX_POINT('',#145984); +#145984 = CARTESIAN_POINT('',(5.35,10.51959417205,0.E+000)); +#145985 = SURFACE_CURVE('',#145986,(#145991,#145997),.PCURVE_S1.); +#145986 = CIRCLE('',#145987,0.208574704164); +#145987 = AXIS2_PLACEMENT_3D('',#145988,#145989,#145990); +#145988 = CARTESIAN_POINT('',(5.35,10.728168876214,2.640924866458E-017) + ); +#145989 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#145990 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#145991 = PCURVE('',#145863,#145992); +#145992 = DEFINITIONAL_REPRESENTATION('',(#145993),#145996); +#145993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145994,#145995), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#143602 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#143603 = CARTESIAN_POINT('',(4.772630242227,5.35)); -#143604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#145994 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#145995 = CARTESIAN_POINT('',(4.772630242227,5.35)); +#145996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143605 = PCURVE('',#86984,#143606); -#143606 = DEFINITIONAL_REPRESENTATION('',(#143607),#143615); -#143607 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143608,#143609,#143610, - #143611,#143612,#143613,#143614),.UNSPECIFIED.,.T.,.F.) +#145997 = PCURVE('',#89376,#145998); +#145998 = DEFINITIONAL_REPRESENTATION('',(#145999),#146007); +#145999 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146000,#146001,#146002, + #146003,#146004,#146005,#146006),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#143608 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#143609 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#143610 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#143611 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#143612 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#143613 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#143614 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#143615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143616 = ORIENTED_EDGE('',*,*,#143617,.T.); -#143617 = EDGE_CURVE('',#143591,#143618,#143620,.T.); -#143618 = VERTEX_POINT('',#143619); -#143619 = CARTESIAN_POINT('',(5.15,10.51959417205,0.E+000)); -#143620 = SURFACE_CURVE('',#143621,(#143625,#143631),.PCURVE_S1.); -#143621 = LINE('',#143622,#143623); -#143622 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#146000 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#146001 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#146002 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#146003 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#146004 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#146005 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#146006 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#146007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146008 = ORIENTED_EDGE('',*,*,#146009,.T.); +#146009 = EDGE_CURVE('',#145983,#146010,#146012,.T.); +#146010 = VERTEX_POINT('',#146011); +#146011 = CARTESIAN_POINT('',(5.15,10.51959417205,0.E+000)); +#146012 = SURFACE_CURVE('',#146013,(#146017,#146023),.PCURVE_S1.); +#146013 = LINE('',#146014,#146015); +#146014 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#143623 = VECTOR('',#143624,1.); -#143624 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143625 = PCURVE('',#143471,#143626); -#143626 = DEFINITIONAL_REPRESENTATION('',(#143627),#143630); -#143627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143628,#143629), +#146015 = VECTOR('',#146016,1.); +#146016 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146017 = PCURVE('',#145863,#146018); +#146018 = DEFINITIONAL_REPRESENTATION('',(#146019),#146022); +#146019 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146020,#146021), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#143628 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#143629 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#143630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146020 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#146021 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#146022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143631 = PCURVE('',#143632,#143637); -#143632 = PLANE('',#143633); -#143633 = AXIS2_PLACEMENT_3D('',#143634,#143635,#143636); -#143634 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#146023 = PCURVE('',#146024,#146029); +#146024 = PLANE('',#146025); +#146025 = AXIS2_PLACEMENT_3D('',#146026,#146027,#146028); +#146026 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#143635 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143636 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143637 = DEFINITIONAL_REPRESENTATION('',(#143638),#143642); -#143638 = LINE('',#143639,#143640); -#143639 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#143640 = VECTOR('',#143641,1.); -#143641 = DIRECTION('',(-1.,0.E+000)); -#143642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143643 = ORIENTED_EDGE('',*,*,#143644,.T.); -#143644 = EDGE_CURVE('',#143618,#143435,#143645,.T.); -#143645 = SURFACE_CURVE('',#143646,(#143651,#143657),.PCURVE_S1.); -#143646 = CIRCLE('',#143647,0.208574704164); -#143647 = AXIS2_PLACEMENT_3D('',#143648,#143649,#143650); -#143648 = CARTESIAN_POINT('',(5.15,10.728168876214,2.640924866458E-017) - ); -#143649 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143650 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143651 = PCURVE('',#143471,#143652); -#143652 = DEFINITIONAL_REPRESENTATION('',(#143653),#143656); -#143653 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143654,#143655), +#146027 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146028 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146029 = DEFINITIONAL_REPRESENTATION('',(#146030),#146034); +#146030 = LINE('',#146031,#146032); +#146031 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#146032 = VECTOR('',#146033,1.); +#146033 = DIRECTION('',(-1.,0.E+000)); +#146034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146035 = ORIENTED_EDGE('',*,*,#146036,.T.); +#146036 = EDGE_CURVE('',#146010,#145827,#146037,.T.); +#146037 = SURFACE_CURVE('',#146038,(#146043,#146049),.PCURVE_S1.); +#146038 = CIRCLE('',#146039,0.208574704164); +#146039 = AXIS2_PLACEMENT_3D('',#146040,#146041,#146042); +#146040 = CARTESIAN_POINT('',(5.15,10.728168876214,2.640924866458E-017) + ); +#146041 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146042 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146043 = PCURVE('',#145863,#146044); +#146044 = DEFINITIONAL_REPRESENTATION('',(#146045),#146048); +#146045 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146046,#146047), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#143654 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#143655 = CARTESIAN_POINT('',(4.772630242227,5.15)); -#143656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143657 = PCURVE('',#86928,#143658); -#143658 = DEFINITIONAL_REPRESENTATION('',(#143659),#143663); -#143659 = CIRCLE('',#143660,0.208574704164); -#143660 = AXIS2_PLACEMENT_2D('',#143661,#143662); -#143661 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#143662 = DIRECTION('',(0.E+000,1.)); -#143663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143664 = ADVANCED_FACE('',(#143665),#143575,.T.); -#143665 = FACE_BOUND('',#143666,.T.); -#143666 = EDGE_LOOP('',(#143667,#143668,#143718,#143745)); -#143667 = ORIENTED_EDGE('',*,*,#143561,.F.); -#143668 = ORIENTED_EDGE('',*,*,#143669,.F.); -#143669 = EDGE_CURVE('',#143670,#143539,#143672,.T.); -#143670 = VERTEX_POINT('',#143671); -#143671 = CARTESIAN_POINT('',(5.35,10.419594812019,0.E+000)); -#143672 = SURFACE_CURVE('',#143673,(#143678,#143707),.PCURVE_S1.); -#143673 = CIRCLE('',#143674,0.308574064194); -#143674 = AXIS2_PLACEMENT_3D('',#143675,#143676,#143677); -#143675 = CARTESIAN_POINT('',(5.35,10.728168876214,2.640924866458E-017) - ); -#143676 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143677 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143678 = PCURVE('',#143575,#143679); -#143679 = DEFINITIONAL_REPRESENTATION('',(#143680),#143706); -#143680 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143681,#143682,#143683, - #143684,#143685,#143686,#143687,#143688,#143689,#143690,#143691, - #143692,#143693,#143694,#143695,#143696,#143697,#143698,#143699, - #143700,#143701,#143702,#143703,#143704,#143705),.UNSPECIFIED.,.F., +#146046 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#146047 = CARTESIAN_POINT('',(4.772630242227,5.15)); +#146048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146049 = PCURVE('',#89320,#146050); +#146050 = DEFINITIONAL_REPRESENTATION('',(#146051),#146055); +#146051 = CIRCLE('',#146052,0.208574704164); +#146052 = AXIS2_PLACEMENT_2D('',#146053,#146054); +#146053 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#146054 = DIRECTION('',(0.E+000,1.)); +#146055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146056 = ADVANCED_FACE('',(#146057),#145967,.T.); +#146057 = FACE_BOUND('',#146058,.T.); +#146058 = EDGE_LOOP('',(#146059,#146060,#146110,#146137)); +#146059 = ORIENTED_EDGE('',*,*,#145953,.F.); +#146060 = ORIENTED_EDGE('',*,*,#146061,.F.); +#146061 = EDGE_CURVE('',#146062,#145931,#146064,.T.); +#146062 = VERTEX_POINT('',#146063); +#146063 = CARTESIAN_POINT('',(5.35,10.419594812019,0.E+000)); +#146064 = SURFACE_CURVE('',#146065,(#146070,#146099),.PCURVE_S1.); +#146065 = CIRCLE('',#146066,0.308574064194); +#146066 = AXIS2_PLACEMENT_3D('',#146067,#146068,#146069); +#146067 = CARTESIAN_POINT('',(5.35,10.728168876214,2.640924866458E-017) + ); +#146068 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146069 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146070 = PCURVE('',#145967,#146071); +#146071 = DEFINITIONAL_REPRESENTATION('',(#146072),#146098); +#146072 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146073,#146074,#146075, + #146076,#146077,#146078,#146079,#146080,#146081,#146082,#146083, + #146084,#146085,#146086,#146087,#146088,#146089,#146090,#146091, + #146092,#146093,#146094,#146095,#146096,#146097),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -177147,102 +180149,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#143681 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#143682 = CARTESIAN_POINT('',(3.166141578807,5.35)); -#143683 = CARTESIAN_POINT('',(3.215239429242,5.35)); -#143684 = CARTESIAN_POINT('',(3.288886204895,5.35)); -#143685 = CARTESIAN_POINT('',(3.362532980548,5.35)); -#143686 = CARTESIAN_POINT('',(3.4361797562,5.35)); -#143687 = CARTESIAN_POINT('',(3.509826531853,5.35)); -#143688 = CARTESIAN_POINT('',(3.583473307505,5.35)); -#143689 = CARTESIAN_POINT('',(3.657120083158,5.35)); -#143690 = CARTESIAN_POINT('',(3.730766858811,5.35)); -#143691 = CARTESIAN_POINT('',(3.804413634463,5.35)); -#143692 = CARTESIAN_POINT('',(3.878060410116,5.35)); -#143693 = CARTESIAN_POINT('',(3.951707185768,5.35)); -#143694 = CARTESIAN_POINT('',(4.025353961421,5.35)); -#143695 = CARTESIAN_POINT('',(4.099000737074,5.35)); -#143696 = CARTESIAN_POINT('',(4.172647512726,5.35)); -#143697 = CARTESIAN_POINT('',(4.246294288379,5.35)); -#143698 = CARTESIAN_POINT('',(4.319941064031,5.35)); -#143699 = CARTESIAN_POINT('',(4.393587839684,5.35)); -#143700 = CARTESIAN_POINT('',(4.467234615337,5.35)); -#143701 = CARTESIAN_POINT('',(4.540881390989,5.35)); -#143702 = CARTESIAN_POINT('',(4.614528166642,5.35)); -#143703 = CARTESIAN_POINT('',(4.688174942294,5.35)); -#143704 = CARTESIAN_POINT('',(4.737272792729,5.35)); -#143705 = CARTESIAN_POINT('',(4.761821717947,5.35)); -#143706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143707 = PCURVE('',#86984,#143708); -#143708 = DEFINITIONAL_REPRESENTATION('',(#143709),#143717); -#143709 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143710,#143711,#143712, - #143713,#143714,#143715,#143716),.UNSPECIFIED.,.T.,.F.) +#146073 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#146074 = CARTESIAN_POINT('',(3.166141578807,5.35)); +#146075 = CARTESIAN_POINT('',(3.215239429242,5.35)); +#146076 = CARTESIAN_POINT('',(3.288886204895,5.35)); +#146077 = CARTESIAN_POINT('',(3.362532980548,5.35)); +#146078 = CARTESIAN_POINT('',(3.4361797562,5.35)); +#146079 = CARTESIAN_POINT('',(3.509826531853,5.35)); +#146080 = CARTESIAN_POINT('',(3.583473307505,5.35)); +#146081 = CARTESIAN_POINT('',(3.657120083158,5.35)); +#146082 = CARTESIAN_POINT('',(3.730766858811,5.35)); +#146083 = CARTESIAN_POINT('',(3.804413634463,5.35)); +#146084 = CARTESIAN_POINT('',(3.878060410116,5.35)); +#146085 = CARTESIAN_POINT('',(3.951707185768,5.35)); +#146086 = CARTESIAN_POINT('',(4.025353961421,5.35)); +#146087 = CARTESIAN_POINT('',(4.099000737074,5.35)); +#146088 = CARTESIAN_POINT('',(4.172647512726,5.35)); +#146089 = CARTESIAN_POINT('',(4.246294288379,5.35)); +#146090 = CARTESIAN_POINT('',(4.319941064031,5.35)); +#146091 = CARTESIAN_POINT('',(4.393587839684,5.35)); +#146092 = CARTESIAN_POINT('',(4.467234615337,5.35)); +#146093 = CARTESIAN_POINT('',(4.540881390989,5.35)); +#146094 = CARTESIAN_POINT('',(4.614528166642,5.35)); +#146095 = CARTESIAN_POINT('',(4.688174942294,5.35)); +#146096 = CARTESIAN_POINT('',(4.737272792729,5.35)); +#146097 = CARTESIAN_POINT('',(4.761821717947,5.35)); +#146098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146099 = PCURVE('',#89376,#146100); +#146100 = DEFINITIONAL_REPRESENTATION('',(#146101),#146109); +#146101 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146102,#146103,#146104, + #146105,#146106,#146107,#146108),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#143710 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#143711 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#143712 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#143713 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#143714 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#143715 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#143716 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#143717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143718 = ORIENTED_EDGE('',*,*,#143719,.F.); -#143719 = EDGE_CURVE('',#143720,#143670,#143722,.T.); -#143720 = VERTEX_POINT('',#143721); -#143721 = CARTESIAN_POINT('',(5.15,10.419594812019,0.E+000)); -#143722 = SURFACE_CURVE('',#143723,(#143727,#143733),.PCURVE_S1.); -#143723 = LINE('',#143724,#143725); -#143724 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#146102 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#146103 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#146104 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#146105 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#146106 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#146107 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#146108 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#146109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146110 = ORIENTED_EDGE('',*,*,#146111,.F.); +#146111 = EDGE_CURVE('',#146112,#146062,#146114,.T.); +#146112 = VERTEX_POINT('',#146113); +#146113 = CARTESIAN_POINT('',(5.15,10.419594812019,0.E+000)); +#146114 = SURFACE_CURVE('',#146115,(#146119,#146125),.PCURVE_S1.); +#146115 = LINE('',#146116,#146117); +#146116 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#143725 = VECTOR('',#143726,1.); -#143726 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143727 = PCURVE('',#143575,#143728); -#143728 = DEFINITIONAL_REPRESENTATION('',(#143729),#143732); -#143729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143730,#143731), +#146117 = VECTOR('',#146118,1.); +#146118 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146119 = PCURVE('',#145967,#146120); +#146120 = DEFINITIONAL_REPRESENTATION('',(#146121),#146124); +#146121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146122,#146123), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#143730 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#143731 = CARTESIAN_POINT('',(3.14159265359,5.35)); -#143732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146122 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#146123 = CARTESIAN_POINT('',(3.14159265359,5.35)); +#146124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143733 = PCURVE('',#143734,#143739); -#143734 = PLANE('',#143735); -#143735 = AXIS2_PLACEMENT_3D('',#143736,#143737,#143738); -#143736 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#146125 = PCURVE('',#146126,#146131); +#146126 = PLANE('',#146127); +#146127 = AXIS2_PLACEMENT_3D('',#146128,#146129,#146130); +#146128 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#143737 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143738 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143739 = DEFINITIONAL_REPRESENTATION('',(#143740),#143744); -#143740 = LINE('',#143741,#143742); -#143741 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#143742 = VECTOR('',#143743,1.); -#143743 = DIRECTION('',(-1.,0.E+000)); -#143744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143745 = ORIENTED_EDGE('',*,*,#143746,.T.); -#143746 = EDGE_CURVE('',#143720,#143486,#143747,.T.); -#143747 = SURFACE_CURVE('',#143748,(#143753,#143782),.PCURVE_S1.); -#143748 = CIRCLE('',#143749,0.308574064194); -#143749 = AXIS2_PLACEMENT_3D('',#143750,#143751,#143752); -#143750 = CARTESIAN_POINT('',(5.15,10.728168876214,2.640924866458E-017) - ); -#143751 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143752 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#143753 = PCURVE('',#143575,#143754); -#143754 = DEFINITIONAL_REPRESENTATION('',(#143755),#143781); -#143755 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#143756,#143757,#143758, - #143759,#143760,#143761,#143762,#143763,#143764,#143765,#143766, - #143767,#143768,#143769,#143770,#143771,#143772,#143773,#143774, - #143775,#143776,#143777,#143778,#143779,#143780),.UNSPECIFIED.,.F., +#146129 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146130 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146131 = DEFINITIONAL_REPRESENTATION('',(#146132),#146136); +#146132 = LINE('',#146133,#146134); +#146133 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#146134 = VECTOR('',#146135,1.); +#146135 = DIRECTION('',(-1.,0.E+000)); +#146136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146137 = ORIENTED_EDGE('',*,*,#146138,.T.); +#146138 = EDGE_CURVE('',#146112,#145878,#146139,.T.); +#146139 = SURFACE_CURVE('',#146140,(#146145,#146174),.PCURVE_S1.); +#146140 = CIRCLE('',#146141,0.308574064194); +#146141 = AXIS2_PLACEMENT_3D('',#146142,#146143,#146144); +#146142 = CARTESIAN_POINT('',(5.15,10.728168876214,2.640924866458E-017) + ); +#146143 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146144 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146145 = PCURVE('',#145967,#146146); +#146146 = DEFINITIONAL_REPRESENTATION('',(#146147),#146173); +#146147 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146148,#146149,#146150, + #146151,#146152,#146153,#146154,#146155,#146156,#146157,#146158, + #146159,#146160,#146161,#146162,#146163,#146164,#146165,#146166, + #146167,#146168,#146169,#146170,#146171,#146172),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -177250,339 +180252,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#143756 = CARTESIAN_POINT('',(3.14159265359,5.15)); -#143757 = CARTESIAN_POINT('',(3.166141578807,5.15)); -#143758 = CARTESIAN_POINT('',(3.215239429242,5.15)); -#143759 = CARTESIAN_POINT('',(3.288886204895,5.15)); -#143760 = CARTESIAN_POINT('',(3.362532980548,5.15)); -#143761 = CARTESIAN_POINT('',(3.4361797562,5.15)); -#143762 = CARTESIAN_POINT('',(3.509826531853,5.15)); -#143763 = CARTESIAN_POINT('',(3.583473307505,5.15)); -#143764 = CARTESIAN_POINT('',(3.657120083158,5.15)); -#143765 = CARTESIAN_POINT('',(3.730766858811,5.15)); -#143766 = CARTESIAN_POINT('',(3.804413634463,5.15)); -#143767 = CARTESIAN_POINT('',(3.878060410116,5.15)); -#143768 = CARTESIAN_POINT('',(3.951707185768,5.15)); -#143769 = CARTESIAN_POINT('',(4.025353961421,5.15)); -#143770 = CARTESIAN_POINT('',(4.099000737074,5.15)); -#143771 = CARTESIAN_POINT('',(4.172647512726,5.15)); -#143772 = CARTESIAN_POINT('',(4.246294288379,5.15)); -#143773 = CARTESIAN_POINT('',(4.319941064031,5.15)); -#143774 = CARTESIAN_POINT('',(4.393587839684,5.15)); -#143775 = CARTESIAN_POINT('',(4.467234615337,5.15)); -#143776 = CARTESIAN_POINT('',(4.540881390989,5.15)); -#143777 = CARTESIAN_POINT('',(4.614528166642,5.15)); -#143778 = CARTESIAN_POINT('',(4.688174942294,5.15)); -#143779 = CARTESIAN_POINT('',(4.737272792729,5.15)); -#143780 = CARTESIAN_POINT('',(4.761821717947,5.15)); -#143781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143782 = PCURVE('',#86928,#143783); -#143783 = DEFINITIONAL_REPRESENTATION('',(#143784),#143788); -#143784 = CIRCLE('',#143785,0.308574064194); -#143785 = AXIS2_PLACEMENT_2D('',#143786,#143787); -#143786 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#143787 = DIRECTION('',(0.E+000,1.)); -#143788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143789 = ADVANCED_FACE('',(#143790),#143734,.F.); -#143790 = FACE_BOUND('',#143791,.T.); -#143791 = EDGE_LOOP('',(#143792,#143821,#143842,#143843)); -#143792 = ORIENTED_EDGE('',*,*,#143793,.F.); -#143793 = EDGE_CURVE('',#143794,#143796,#143798,.T.); -#143794 = VERTEX_POINT('',#143795); -#143795 = CARTESIAN_POINT('',(5.15,10.419594812019,0.530776333563)); -#143796 = VERTEX_POINT('',#143797); -#143797 = CARTESIAN_POINT('',(5.35,10.419594812019,0.530776333563)); -#143798 = SURFACE_CURVE('',#143799,(#143803,#143810),.PCURVE_S1.); -#143799 = LINE('',#143800,#143801); -#143800 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#146148 = CARTESIAN_POINT('',(3.14159265359,5.15)); +#146149 = CARTESIAN_POINT('',(3.166141578807,5.15)); +#146150 = CARTESIAN_POINT('',(3.215239429242,5.15)); +#146151 = CARTESIAN_POINT('',(3.288886204895,5.15)); +#146152 = CARTESIAN_POINT('',(3.362532980548,5.15)); +#146153 = CARTESIAN_POINT('',(3.4361797562,5.15)); +#146154 = CARTESIAN_POINT('',(3.509826531853,5.15)); +#146155 = CARTESIAN_POINT('',(3.583473307505,5.15)); +#146156 = CARTESIAN_POINT('',(3.657120083158,5.15)); +#146157 = CARTESIAN_POINT('',(3.730766858811,5.15)); +#146158 = CARTESIAN_POINT('',(3.804413634463,5.15)); +#146159 = CARTESIAN_POINT('',(3.878060410116,5.15)); +#146160 = CARTESIAN_POINT('',(3.951707185768,5.15)); +#146161 = CARTESIAN_POINT('',(4.025353961421,5.15)); +#146162 = CARTESIAN_POINT('',(4.099000737074,5.15)); +#146163 = CARTESIAN_POINT('',(4.172647512726,5.15)); +#146164 = CARTESIAN_POINT('',(4.246294288379,5.15)); +#146165 = CARTESIAN_POINT('',(4.319941064031,5.15)); +#146166 = CARTESIAN_POINT('',(4.393587839684,5.15)); +#146167 = CARTESIAN_POINT('',(4.467234615337,5.15)); +#146168 = CARTESIAN_POINT('',(4.540881390989,5.15)); +#146169 = CARTESIAN_POINT('',(4.614528166642,5.15)); +#146170 = CARTESIAN_POINT('',(4.688174942294,5.15)); +#146171 = CARTESIAN_POINT('',(4.737272792729,5.15)); +#146172 = CARTESIAN_POINT('',(4.761821717947,5.15)); +#146173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146174 = PCURVE('',#89320,#146175); +#146175 = DEFINITIONAL_REPRESENTATION('',(#146176),#146180); +#146176 = CIRCLE('',#146177,0.308574064194); +#146177 = AXIS2_PLACEMENT_2D('',#146178,#146179); +#146178 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#146179 = DIRECTION('',(0.E+000,1.)); +#146180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146181 = ADVANCED_FACE('',(#146182),#146126,.F.); +#146182 = FACE_BOUND('',#146183,.T.); +#146183 = EDGE_LOOP('',(#146184,#146213,#146234,#146235)); +#146184 = ORIENTED_EDGE('',*,*,#146185,.F.); +#146185 = EDGE_CURVE('',#146186,#146188,#146190,.T.); +#146186 = VERTEX_POINT('',#146187); +#146187 = CARTESIAN_POINT('',(5.15,10.419594812019,0.530776333563)); +#146188 = VERTEX_POINT('',#146189); +#146189 = CARTESIAN_POINT('',(5.35,10.419594812019,0.530776333563)); +#146190 = SURFACE_CURVE('',#146191,(#146195,#146202),.PCURVE_S1.); +#146191 = LINE('',#146192,#146193); +#146192 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#143801 = VECTOR('',#143802,1.); -#143802 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#143803 = PCURVE('',#143734,#143804); -#143804 = DEFINITIONAL_REPRESENTATION('',(#143805),#143809); -#143805 = LINE('',#143806,#143807); -#143806 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143807 = VECTOR('',#143808,1.); -#143808 = DIRECTION('',(-1.,0.E+000)); -#143809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143810 = PCURVE('',#143811,#143816); -#143811 = CYLINDRICAL_SURFACE('',#143812,0.119270391569); -#143812 = AXIS2_PLACEMENT_3D('',#143813,#143814,#143815); -#143813 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#146193 = VECTOR('',#146194,1.); +#146194 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146195 = PCURVE('',#146126,#146196); +#146196 = DEFINITIONAL_REPRESENTATION('',(#146197),#146201); +#146197 = LINE('',#146198,#146199); +#146198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146199 = VECTOR('',#146200,1.); +#146200 = DIRECTION('',(-1.,0.E+000)); +#146201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146202 = PCURVE('',#146203,#146208); +#146203 = CYLINDRICAL_SURFACE('',#146204,0.119270391569); +#146204 = AXIS2_PLACEMENT_3D('',#146205,#146206,#146207); +#146205 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#143814 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143815 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143816 = DEFINITIONAL_REPRESENTATION('',(#143817),#143820); -#143817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143818,#143819), +#146206 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146207 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146208 = DEFINITIONAL_REPRESENTATION('',(#146209),#146212); +#146209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146210,#146211), .UNSPECIFIED.,.F.,.F.,(2,2),(5.15,5.35),.PIECEWISE_BEZIER_KNOTS.); -#143818 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#143819 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#143820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143821 = ORIENTED_EDGE('',*,*,#143822,.T.); -#143822 = EDGE_CURVE('',#143794,#143720,#143823,.T.); -#143823 = SURFACE_CURVE('',#143824,(#143828,#143835),.PCURVE_S1.); -#143824 = LINE('',#143825,#143826); -#143825 = CARTESIAN_POINT('',(5.15,10.419594812019,0.530776333563)); -#143826 = VECTOR('',#143827,1.); -#143827 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#143828 = PCURVE('',#143734,#143829); -#143829 = DEFINITIONAL_REPRESENTATION('',(#143830),#143834); -#143830 = LINE('',#143831,#143832); -#143831 = CARTESIAN_POINT('',(-5.15,0.E+000)); -#143832 = VECTOR('',#143833,1.); -#143833 = DIRECTION('',(0.E+000,-1.)); -#143834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143835 = PCURVE('',#86928,#143836); -#143836 = DEFINITIONAL_REPRESENTATION('',(#143837),#143841); -#143837 = LINE('',#143838,#143839); -#143838 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#143839 = VECTOR('',#143840,1.); -#143840 = DIRECTION('',(1.,0.E+000)); -#143841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143842 = ORIENTED_EDGE('',*,*,#143719,.T.); -#143843 = ORIENTED_EDGE('',*,*,#143844,.F.); -#143844 = EDGE_CURVE('',#143796,#143670,#143845,.T.); -#143845 = SURFACE_CURVE('',#143846,(#143850,#143857),.PCURVE_S1.); -#143846 = LINE('',#143847,#143848); -#143847 = CARTESIAN_POINT('',(5.35,10.419594812019,0.530776333563)); -#143848 = VECTOR('',#143849,1.); -#143849 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#143850 = PCURVE('',#143734,#143851); -#143851 = DEFINITIONAL_REPRESENTATION('',(#143852),#143856); -#143852 = LINE('',#143853,#143854); -#143853 = CARTESIAN_POINT('',(-5.35,0.E+000)); -#143854 = VECTOR('',#143855,1.); -#143855 = DIRECTION('',(0.E+000,-1.)); -#143856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143857 = PCURVE('',#86984,#143858); -#143858 = DEFINITIONAL_REPRESENTATION('',(#143859),#143863); -#143859 = LINE('',#143860,#143861); -#143860 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#143861 = VECTOR('',#143862,1.); -#143862 = DIRECTION('',(-1.,0.E+000)); -#143863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143864 = ADVANCED_FACE('',(#143865),#143632,.F.); -#143865 = FACE_BOUND('',#143866,.T.); -#143866 = EDGE_LOOP('',(#143867,#143896,#143917,#143918)); -#143867 = ORIENTED_EDGE('',*,*,#143868,.F.); -#143868 = EDGE_CURVE('',#143869,#143871,#143873,.T.); -#143869 = VERTEX_POINT('',#143870); -#143870 = CARTESIAN_POINT('',(5.35,10.51959417205,0.530776333563)); -#143871 = VERTEX_POINT('',#143872); -#143872 = CARTESIAN_POINT('',(5.15,10.51959417205,0.530776333563)); -#143873 = SURFACE_CURVE('',#143874,(#143878,#143885),.PCURVE_S1.); -#143874 = LINE('',#143875,#143876); -#143875 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#146210 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#146211 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#146212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146213 = ORIENTED_EDGE('',*,*,#146214,.T.); +#146214 = EDGE_CURVE('',#146186,#146112,#146215,.T.); +#146215 = SURFACE_CURVE('',#146216,(#146220,#146227),.PCURVE_S1.); +#146216 = LINE('',#146217,#146218); +#146217 = CARTESIAN_POINT('',(5.15,10.419594812019,0.530776333563)); +#146218 = VECTOR('',#146219,1.); +#146219 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#146220 = PCURVE('',#146126,#146221); +#146221 = DEFINITIONAL_REPRESENTATION('',(#146222),#146226); +#146222 = LINE('',#146223,#146224); +#146223 = CARTESIAN_POINT('',(-5.15,0.E+000)); +#146224 = VECTOR('',#146225,1.); +#146225 = DIRECTION('',(0.E+000,-1.)); +#146226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146227 = PCURVE('',#89320,#146228); +#146228 = DEFINITIONAL_REPRESENTATION('',(#146229),#146233); +#146229 = LINE('',#146230,#146231); +#146230 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#146231 = VECTOR('',#146232,1.); +#146232 = DIRECTION('',(1.,0.E+000)); +#146233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146234 = ORIENTED_EDGE('',*,*,#146111,.T.); +#146235 = ORIENTED_EDGE('',*,*,#146236,.F.); +#146236 = EDGE_CURVE('',#146188,#146062,#146237,.T.); +#146237 = SURFACE_CURVE('',#146238,(#146242,#146249),.PCURVE_S1.); +#146238 = LINE('',#146239,#146240); +#146239 = CARTESIAN_POINT('',(5.35,10.419594812019,0.530776333563)); +#146240 = VECTOR('',#146241,1.); +#146241 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#146242 = PCURVE('',#146126,#146243); +#146243 = DEFINITIONAL_REPRESENTATION('',(#146244),#146248); +#146244 = LINE('',#146245,#146246); +#146245 = CARTESIAN_POINT('',(-5.35,0.E+000)); +#146246 = VECTOR('',#146247,1.); +#146247 = DIRECTION('',(0.E+000,-1.)); +#146248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146249 = PCURVE('',#89376,#146250); +#146250 = DEFINITIONAL_REPRESENTATION('',(#146251),#146255); +#146251 = LINE('',#146252,#146253); +#146252 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#146253 = VECTOR('',#146254,1.); +#146254 = DIRECTION('',(-1.,0.E+000)); +#146255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146256 = ADVANCED_FACE('',(#146257),#146024,.F.); +#146257 = FACE_BOUND('',#146258,.T.); +#146258 = EDGE_LOOP('',(#146259,#146288,#146309,#146310)); +#146259 = ORIENTED_EDGE('',*,*,#146260,.F.); +#146260 = EDGE_CURVE('',#146261,#146263,#146265,.T.); +#146261 = VERTEX_POINT('',#146262); +#146262 = CARTESIAN_POINT('',(5.35,10.51959417205,0.530776333563)); +#146263 = VERTEX_POINT('',#146264); +#146264 = CARTESIAN_POINT('',(5.15,10.51959417205,0.530776333563)); +#146265 = SURFACE_CURVE('',#146266,(#146270,#146277),.PCURVE_S1.); +#146266 = LINE('',#146267,#146268); +#146267 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#143876 = VECTOR('',#143877,1.); -#143877 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143878 = PCURVE('',#143632,#143879); -#143879 = DEFINITIONAL_REPRESENTATION('',(#143880),#143884); -#143880 = LINE('',#143881,#143882); -#143881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#143882 = VECTOR('',#143883,1.); -#143883 = DIRECTION('',(-1.,0.E+000)); -#143884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143885 = PCURVE('',#143886,#143891); -#143886 = CYLINDRICAL_SURFACE('',#143887,0.2192697516); -#143887 = AXIS2_PLACEMENT_3D('',#143888,#143889,#143890); -#143888 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#146268 = VECTOR('',#146269,1.); +#146269 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146270 = PCURVE('',#146024,#146271); +#146271 = DEFINITIONAL_REPRESENTATION('',(#146272),#146276); +#146272 = LINE('',#146273,#146274); +#146273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146274 = VECTOR('',#146275,1.); +#146275 = DIRECTION('',(-1.,0.E+000)); +#146276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146277 = PCURVE('',#146278,#146283); +#146278 = CYLINDRICAL_SURFACE('',#146279,0.2192697516); +#146279 = AXIS2_PLACEMENT_3D('',#146280,#146281,#146282); +#146280 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#143889 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143890 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143891 = DEFINITIONAL_REPRESENTATION('',(#143892),#143895); -#143892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143893,#143894), +#146281 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146282 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146283 = DEFINITIONAL_REPRESENTATION('',(#146284),#146287); +#146284 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146285,#146286), .UNSPECIFIED.,.F.,.F.,(2,2),(-5.35,-5.15),.PIECEWISE_BEZIER_KNOTS.); -#143893 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#143894 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#143895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143896 = ORIENTED_EDGE('',*,*,#143897,.T.); -#143897 = EDGE_CURVE('',#143869,#143591,#143898,.T.); -#143898 = SURFACE_CURVE('',#143899,(#143903,#143910),.PCURVE_S1.); -#143899 = LINE('',#143900,#143901); -#143900 = CARTESIAN_POINT('',(5.35,10.51959417205,0.530776333563)); -#143901 = VECTOR('',#143902,1.); -#143902 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#143903 = PCURVE('',#143632,#143904); -#143904 = DEFINITIONAL_REPRESENTATION('',(#143905),#143909); -#143905 = LINE('',#143906,#143907); -#143906 = CARTESIAN_POINT('',(5.35,0.E+000)); -#143907 = VECTOR('',#143908,1.); -#143908 = DIRECTION('',(0.E+000,-1.)); -#143909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143910 = PCURVE('',#86984,#143911); -#143911 = DEFINITIONAL_REPRESENTATION('',(#143912),#143916); -#143912 = LINE('',#143913,#143914); -#143913 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#143914 = VECTOR('',#143915,1.); -#143915 = DIRECTION('',(-1.,0.E+000)); -#143916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143917 = ORIENTED_EDGE('',*,*,#143617,.T.); -#143918 = ORIENTED_EDGE('',*,*,#143919,.F.); -#143919 = EDGE_CURVE('',#143871,#143618,#143920,.T.); -#143920 = SURFACE_CURVE('',#143921,(#143925,#143932),.PCURVE_S1.); -#143921 = LINE('',#143922,#143923); -#143922 = CARTESIAN_POINT('',(5.15,10.51959417205,0.530776333563)); -#143923 = VECTOR('',#143924,1.); -#143924 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#143925 = PCURVE('',#143632,#143926); -#143926 = DEFINITIONAL_REPRESENTATION('',(#143927),#143931); -#143927 = LINE('',#143928,#143929); -#143928 = CARTESIAN_POINT('',(5.15,0.E+000)); -#143929 = VECTOR('',#143930,1.); -#143930 = DIRECTION('',(0.E+000,-1.)); -#143931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143932 = PCURVE('',#86928,#143933); -#143933 = DEFINITIONAL_REPRESENTATION('',(#143934),#143938); -#143934 = LINE('',#143935,#143936); -#143935 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#143936 = VECTOR('',#143937,1.); -#143937 = DIRECTION('',(1.,0.E+000)); -#143938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143939 = ADVANCED_FACE('',(#143940),#143811,.F.); -#143940 = FACE_BOUND('',#143941,.F.); -#143941 = EDGE_LOOP('',(#143942,#143969,#143991,#144012)); -#143942 = ORIENTED_EDGE('',*,*,#143943,.F.); -#143943 = EDGE_CURVE('',#143944,#143794,#143946,.T.); -#143944 = VERTEX_POINT('',#143945); -#143945 = CARTESIAN_POINT('',(5.15,10.303662633502,0.65)); -#143946 = SURFACE_CURVE('',#143947,(#143952,#143958),.PCURVE_S1.); -#143947 = CIRCLE('',#143948,0.119270391569); -#143948 = AXIS2_PLACEMENT_3D('',#143949,#143950,#143951); -#143949 = CARTESIAN_POINT('',(5.15,10.30032442045,0.530776333563)); -#143950 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143951 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143952 = PCURVE('',#143811,#143953); -#143953 = DEFINITIONAL_REPRESENTATION('',(#143954),#143957); -#143954 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143955,#143956), +#146285 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#146286 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#146287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146288 = ORIENTED_EDGE('',*,*,#146289,.T.); +#146289 = EDGE_CURVE('',#146261,#145983,#146290,.T.); +#146290 = SURFACE_CURVE('',#146291,(#146295,#146302),.PCURVE_S1.); +#146291 = LINE('',#146292,#146293); +#146292 = CARTESIAN_POINT('',(5.35,10.51959417205,0.530776333563)); +#146293 = VECTOR('',#146294,1.); +#146294 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#146295 = PCURVE('',#146024,#146296); +#146296 = DEFINITIONAL_REPRESENTATION('',(#146297),#146301); +#146297 = LINE('',#146298,#146299); +#146298 = CARTESIAN_POINT('',(5.35,0.E+000)); +#146299 = VECTOR('',#146300,1.); +#146300 = DIRECTION('',(0.E+000,-1.)); +#146301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146302 = PCURVE('',#89376,#146303); +#146303 = DEFINITIONAL_REPRESENTATION('',(#146304),#146308); +#146304 = LINE('',#146305,#146306); +#146305 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#146306 = VECTOR('',#146307,1.); +#146307 = DIRECTION('',(-1.,0.E+000)); +#146308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146309 = ORIENTED_EDGE('',*,*,#146009,.T.); +#146310 = ORIENTED_EDGE('',*,*,#146311,.F.); +#146311 = EDGE_CURVE('',#146263,#146010,#146312,.T.); +#146312 = SURFACE_CURVE('',#146313,(#146317,#146324),.PCURVE_S1.); +#146313 = LINE('',#146314,#146315); +#146314 = CARTESIAN_POINT('',(5.15,10.51959417205,0.530776333563)); +#146315 = VECTOR('',#146316,1.); +#146316 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#146317 = PCURVE('',#146024,#146318); +#146318 = DEFINITIONAL_REPRESENTATION('',(#146319),#146323); +#146319 = LINE('',#146320,#146321); +#146320 = CARTESIAN_POINT('',(5.15,0.E+000)); +#146321 = VECTOR('',#146322,1.); +#146322 = DIRECTION('',(0.E+000,-1.)); +#146323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146324 = PCURVE('',#89320,#146325); +#146325 = DEFINITIONAL_REPRESENTATION('',(#146326),#146330); +#146326 = LINE('',#146327,#146328); +#146327 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#146328 = VECTOR('',#146329,1.); +#146329 = DIRECTION('',(1.,0.E+000)); +#146330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146331 = ADVANCED_FACE('',(#146332),#146203,.F.); +#146332 = FACE_BOUND('',#146333,.F.); +#146333 = EDGE_LOOP('',(#146334,#146361,#146383,#146404)); +#146334 = ORIENTED_EDGE('',*,*,#146335,.F.); +#146335 = EDGE_CURVE('',#146336,#146186,#146338,.T.); +#146336 = VERTEX_POINT('',#146337); +#146337 = CARTESIAN_POINT('',(5.15,10.303662633502,0.65)); +#146338 = SURFACE_CURVE('',#146339,(#146344,#146350),.PCURVE_S1.); +#146339 = CIRCLE('',#146340,0.119270391569); +#146340 = AXIS2_PLACEMENT_3D('',#146341,#146342,#146343); +#146341 = CARTESIAN_POINT('',(5.15,10.30032442045,0.530776333563)); +#146342 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146343 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146344 = PCURVE('',#146203,#146345); +#146345 = DEFINITIONAL_REPRESENTATION('',(#146346),#146349); +#146346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146347,#146348), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#143955 = CARTESIAN_POINT('',(1.598788597134,-5.15)); -#143956 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#143957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146347 = CARTESIAN_POINT('',(1.598788597134,-5.15)); +#146348 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#146349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#143958 = PCURVE('',#86928,#143959); -#143959 = DEFINITIONAL_REPRESENTATION('',(#143960),#143968); -#143960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#143961,#143962,#143963, - #143964,#143965,#143966,#143967),.UNSPECIFIED.,.T.,.F.) +#146350 = PCURVE('',#89320,#146351); +#146351 = DEFINITIONAL_REPRESENTATION('',(#146352),#146360); +#146352 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146353,#146354,#146355, + #146356,#146357,#146358,#146359),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#143961 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#143962 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#143963 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#143964 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#143965 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#143966 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#143967 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#143968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143969 = ORIENTED_EDGE('',*,*,#143970,.F.); -#143970 = EDGE_CURVE('',#143971,#143944,#143973,.T.); -#143971 = VERTEX_POINT('',#143972); -#143972 = CARTESIAN_POINT('',(5.35,10.303662633502,0.65)); -#143973 = SURFACE_CURVE('',#143974,(#143978,#143984),.PCURVE_S1.); -#143974 = LINE('',#143975,#143976); -#143975 = CARTESIAN_POINT('',(5.15,10.303662633502,0.65)); -#143976 = VECTOR('',#143977,1.); -#143977 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143978 = PCURVE('',#143811,#143979); -#143979 = DEFINITIONAL_REPRESENTATION('',(#143980),#143983); -#143980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#143981,#143982), +#146353 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#146354 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#146355 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#146356 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#146357 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#146358 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#146359 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#146360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146361 = ORIENTED_EDGE('',*,*,#146362,.F.); +#146362 = EDGE_CURVE('',#146363,#146336,#146365,.T.); +#146363 = VERTEX_POINT('',#146364); +#146364 = CARTESIAN_POINT('',(5.35,10.303662633502,0.65)); +#146365 = SURFACE_CURVE('',#146366,(#146370,#146376),.PCURVE_S1.); +#146366 = LINE('',#146367,#146368); +#146367 = CARTESIAN_POINT('',(5.15,10.303662633502,0.65)); +#146368 = VECTOR('',#146369,1.); +#146369 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146370 = PCURVE('',#146203,#146371); +#146371 = DEFINITIONAL_REPRESENTATION('',(#146372),#146375); +#146372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146373,#146374), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#143981 = CARTESIAN_POINT('',(1.598788597134,-5.35)); -#143982 = CARTESIAN_POINT('',(1.598788597134,-5.15)); -#143983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143984 = PCURVE('',#86956,#143985); -#143985 = DEFINITIONAL_REPRESENTATION('',(#143986),#143990); -#143986 = LINE('',#143987,#143988); -#143987 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#143988 = VECTOR('',#143989,1.); -#143989 = DIRECTION('',(-8.881784197001E-016,-1.)); -#143990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#143991 = ORIENTED_EDGE('',*,*,#143992,.T.); -#143992 = EDGE_CURVE('',#143971,#143796,#143993,.T.); -#143993 = SURFACE_CURVE('',#143994,(#143999,#144005),.PCURVE_S1.); -#143994 = CIRCLE('',#143995,0.119270391569); -#143995 = AXIS2_PLACEMENT_3D('',#143996,#143997,#143998); -#143996 = CARTESIAN_POINT('',(5.35,10.30032442045,0.530776333563)); -#143997 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#143998 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#143999 = PCURVE('',#143811,#144000); -#144000 = DEFINITIONAL_REPRESENTATION('',(#144001),#144004); -#144001 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144002,#144003), +#146373 = CARTESIAN_POINT('',(1.598788597134,-5.35)); +#146374 = CARTESIAN_POINT('',(1.598788597134,-5.15)); +#146375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146376 = PCURVE('',#89348,#146377); +#146377 = DEFINITIONAL_REPRESENTATION('',(#146378),#146382); +#146378 = LINE('',#146379,#146380); +#146379 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#146380 = VECTOR('',#146381,1.); +#146381 = DIRECTION('',(-8.881784197001E-016,-1.)); +#146382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146383 = ORIENTED_EDGE('',*,*,#146384,.T.); +#146384 = EDGE_CURVE('',#146363,#146188,#146385,.T.); +#146385 = SURFACE_CURVE('',#146386,(#146391,#146397),.PCURVE_S1.); +#146386 = CIRCLE('',#146387,0.119270391569); +#146387 = AXIS2_PLACEMENT_3D('',#146388,#146389,#146390); +#146388 = CARTESIAN_POINT('',(5.35,10.30032442045,0.530776333563)); +#146389 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146390 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146391 = PCURVE('',#146203,#146392); +#146392 = DEFINITIONAL_REPRESENTATION('',(#146393),#146396); +#146393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146394,#146395), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#144002 = CARTESIAN_POINT('',(1.598788597134,-5.35)); -#144003 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#144004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144005 = PCURVE('',#86984,#144006); -#144006 = DEFINITIONAL_REPRESENTATION('',(#144007),#144011); -#144007 = CIRCLE('',#144008,0.119270391569); -#144008 = AXIS2_PLACEMENT_2D('',#144009,#144010); -#144009 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#144010 = DIRECTION('',(0.E+000,-1.)); -#144011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144012 = ORIENTED_EDGE('',*,*,#143793,.F.); -#144013 = ADVANCED_FACE('',(#144014),#143886,.T.); -#144014 = FACE_BOUND('',#144015,.T.); -#144015 = EDGE_LOOP('',(#144016,#144062,#144063,#144113)); -#144016 = ORIENTED_EDGE('',*,*,#144017,.T.); -#144017 = EDGE_CURVE('',#144018,#143869,#144020,.T.); -#144018 = VERTEX_POINT('',#144019); -#144019 = CARTESIAN_POINT('',(5.35,10.304819755875,0.75)); -#144020 = SURFACE_CURVE('',#144021,(#144026,#144055),.PCURVE_S1.); -#144021 = CIRCLE('',#144022,0.2192697516); -#144022 = AXIS2_PLACEMENT_3D('',#144023,#144024,#144025); -#144023 = CARTESIAN_POINT('',(5.35,10.30032442045,0.530776333563)); -#144024 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144025 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144026 = PCURVE('',#143886,#144027); -#144027 = DEFINITIONAL_REPRESENTATION('',(#144028),#144054); -#144028 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144029,#144030,#144031, - #144032,#144033,#144034,#144035,#144036,#144037,#144038,#144039, - #144040,#144041,#144042,#144043,#144044,#144045,#144046,#144047, - #144048,#144049,#144050,#144051,#144052,#144053),.UNSPECIFIED.,.F., +#146394 = CARTESIAN_POINT('',(1.598788597134,-5.35)); +#146395 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#146396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146397 = PCURVE('',#89376,#146398); +#146398 = DEFINITIONAL_REPRESENTATION('',(#146399),#146403); +#146399 = CIRCLE('',#146400,0.119270391569); +#146400 = AXIS2_PLACEMENT_2D('',#146401,#146402); +#146401 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#146402 = DIRECTION('',(0.E+000,-1.)); +#146403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146404 = ORIENTED_EDGE('',*,*,#146185,.F.); +#146405 = ADVANCED_FACE('',(#146406),#146278,.T.); +#146406 = FACE_BOUND('',#146407,.T.); +#146407 = EDGE_LOOP('',(#146408,#146454,#146455,#146505)); +#146408 = ORIENTED_EDGE('',*,*,#146409,.T.); +#146409 = EDGE_CURVE('',#146410,#146261,#146412,.T.); +#146410 = VERTEX_POINT('',#146411); +#146411 = CARTESIAN_POINT('',(5.35,10.304819755875,0.75)); +#146412 = SURFACE_CURVE('',#146413,(#146418,#146447),.PCURVE_S1.); +#146413 = CIRCLE('',#146414,0.2192697516); +#146414 = AXIS2_PLACEMENT_3D('',#146415,#146416,#146417); +#146415 = CARTESIAN_POINT('',(5.35,10.30032442045,0.530776333563)); +#146416 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146417 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146418 = PCURVE('',#146278,#146419); +#146419 = DEFINITIONAL_REPRESENTATION('',(#146420),#146446); +#146420 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146421,#146422,#146423, + #146424,#146425,#146426,#146427,#146428,#146429,#146430,#146431, + #146432,#146433,#146434,#146435,#146436,#146437,#146438,#146439, + #146440,#146441,#146442,#146443,#146444,#146445),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -177590,60 +180592,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#144029 = CARTESIAN_POINT('',(1.591299156552,-5.35)); -#144030 = CARTESIAN_POINT('',(1.614788451962,-5.35)); -#144031 = CARTESIAN_POINT('',(1.661767042781,-5.35)); -#144032 = CARTESIAN_POINT('',(1.73223492901,-5.35)); -#144033 = CARTESIAN_POINT('',(1.802702815239,-5.35)); -#144034 = CARTESIAN_POINT('',(1.873170701468,-5.35)); -#144035 = CARTESIAN_POINT('',(1.943638587697,-5.35)); -#144036 = CARTESIAN_POINT('',(2.014106473926,-5.35)); -#144037 = CARTESIAN_POINT('',(2.084574360155,-5.35)); -#144038 = CARTESIAN_POINT('',(2.155042246384,-5.35)); -#144039 = CARTESIAN_POINT('',(2.225510132613,-5.35)); -#144040 = CARTESIAN_POINT('',(2.295978018842,-5.35)); -#144041 = CARTESIAN_POINT('',(2.366445905071,-5.35)); -#144042 = CARTESIAN_POINT('',(2.4369137913,-5.35)); -#144043 = CARTESIAN_POINT('',(2.507381677529,-5.35)); -#144044 = CARTESIAN_POINT('',(2.577849563758,-5.35)); -#144045 = CARTESIAN_POINT('',(2.648317449987,-5.35)); -#144046 = CARTESIAN_POINT('',(2.718785336216,-5.35)); -#144047 = CARTESIAN_POINT('',(2.789253222445,-5.35)); -#144048 = CARTESIAN_POINT('',(2.859721108674,-5.35)); -#144049 = CARTESIAN_POINT('',(2.930188994903,-5.35)); -#144050 = CARTESIAN_POINT('',(3.000656881132,-5.35)); -#144051 = CARTESIAN_POINT('',(3.071124767361,-5.35)); -#144052 = CARTESIAN_POINT('',(3.11810335818,-5.35)); -#144053 = CARTESIAN_POINT('',(3.14159265359,-5.35)); -#144054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144055 = PCURVE('',#86984,#144056); -#144056 = DEFINITIONAL_REPRESENTATION('',(#144057),#144061); -#144057 = CIRCLE('',#144058,0.2192697516); -#144058 = AXIS2_PLACEMENT_2D('',#144059,#144060); -#144059 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#144060 = DIRECTION('',(0.E+000,-1.)); -#144061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144062 = ORIENTED_EDGE('',*,*,#143868,.T.); -#144063 = ORIENTED_EDGE('',*,*,#144064,.F.); -#144064 = EDGE_CURVE('',#144065,#143871,#144067,.T.); -#144065 = VERTEX_POINT('',#144066); -#144066 = CARTESIAN_POINT('',(5.15,10.304819755875,0.75)); -#144067 = SURFACE_CURVE('',#144068,(#144073,#144102),.PCURVE_S1.); -#144068 = CIRCLE('',#144069,0.2192697516); -#144069 = AXIS2_PLACEMENT_3D('',#144070,#144071,#144072); -#144070 = CARTESIAN_POINT('',(5.15,10.30032442045,0.530776333563)); -#144071 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144072 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144073 = PCURVE('',#143886,#144074); -#144074 = DEFINITIONAL_REPRESENTATION('',(#144075),#144101); -#144075 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144076,#144077,#144078, - #144079,#144080,#144081,#144082,#144083,#144084,#144085,#144086, - #144087,#144088,#144089,#144090,#144091,#144092,#144093,#144094, - #144095,#144096,#144097,#144098,#144099,#144100),.UNSPECIFIED.,.F., +#146421 = CARTESIAN_POINT('',(1.591299156552,-5.35)); +#146422 = CARTESIAN_POINT('',(1.614788451962,-5.35)); +#146423 = CARTESIAN_POINT('',(1.661767042781,-5.35)); +#146424 = CARTESIAN_POINT('',(1.73223492901,-5.35)); +#146425 = CARTESIAN_POINT('',(1.802702815239,-5.35)); +#146426 = CARTESIAN_POINT('',(1.873170701468,-5.35)); +#146427 = CARTESIAN_POINT('',(1.943638587697,-5.35)); +#146428 = CARTESIAN_POINT('',(2.014106473926,-5.35)); +#146429 = CARTESIAN_POINT('',(2.084574360155,-5.35)); +#146430 = CARTESIAN_POINT('',(2.155042246384,-5.35)); +#146431 = CARTESIAN_POINT('',(2.225510132613,-5.35)); +#146432 = CARTESIAN_POINT('',(2.295978018842,-5.35)); +#146433 = CARTESIAN_POINT('',(2.366445905071,-5.35)); +#146434 = CARTESIAN_POINT('',(2.4369137913,-5.35)); +#146435 = CARTESIAN_POINT('',(2.507381677529,-5.35)); +#146436 = CARTESIAN_POINT('',(2.577849563758,-5.35)); +#146437 = CARTESIAN_POINT('',(2.648317449987,-5.35)); +#146438 = CARTESIAN_POINT('',(2.718785336216,-5.35)); +#146439 = CARTESIAN_POINT('',(2.789253222445,-5.35)); +#146440 = CARTESIAN_POINT('',(2.859721108674,-5.35)); +#146441 = CARTESIAN_POINT('',(2.930188994903,-5.35)); +#146442 = CARTESIAN_POINT('',(3.000656881132,-5.35)); +#146443 = CARTESIAN_POINT('',(3.071124767361,-5.35)); +#146444 = CARTESIAN_POINT('',(3.11810335818,-5.35)); +#146445 = CARTESIAN_POINT('',(3.14159265359,-5.35)); +#146446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146447 = PCURVE('',#89376,#146448); +#146448 = DEFINITIONAL_REPRESENTATION('',(#146449),#146453); +#146449 = CIRCLE('',#146450,0.2192697516); +#146450 = AXIS2_PLACEMENT_2D('',#146451,#146452); +#146451 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#146452 = DIRECTION('',(0.E+000,-1.)); +#146453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146454 = ORIENTED_EDGE('',*,*,#146260,.T.); +#146455 = ORIENTED_EDGE('',*,*,#146456,.F.); +#146456 = EDGE_CURVE('',#146457,#146263,#146459,.T.); +#146457 = VERTEX_POINT('',#146458); +#146458 = CARTESIAN_POINT('',(5.15,10.304819755875,0.75)); +#146459 = SURFACE_CURVE('',#146460,(#146465,#146494),.PCURVE_S1.); +#146460 = CIRCLE('',#146461,0.2192697516); +#146461 = AXIS2_PLACEMENT_3D('',#146462,#146463,#146464); +#146462 = CARTESIAN_POINT('',(5.15,10.30032442045,0.530776333563)); +#146463 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146464 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#146465 = PCURVE('',#146278,#146466); +#146466 = DEFINITIONAL_REPRESENTATION('',(#146467),#146493); +#146467 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146468,#146469,#146470, + #146471,#146472,#146473,#146474,#146475,#146476,#146477,#146478, + #146479,#146480,#146481,#146482,#146483,#146484,#146485,#146486, + #146487,#146488,#146489,#146490,#146491,#146492),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -177651,549 +180653,549 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#144076 = CARTESIAN_POINT('',(1.591299156552,-5.15)); -#144077 = CARTESIAN_POINT('',(1.614788451962,-5.15)); -#144078 = CARTESIAN_POINT('',(1.661767042781,-5.15)); -#144079 = CARTESIAN_POINT('',(1.73223492901,-5.15)); -#144080 = CARTESIAN_POINT('',(1.802702815239,-5.15)); -#144081 = CARTESIAN_POINT('',(1.873170701468,-5.15)); -#144082 = CARTESIAN_POINT('',(1.943638587697,-5.15)); -#144083 = CARTESIAN_POINT('',(2.014106473926,-5.15)); -#144084 = CARTESIAN_POINT('',(2.084574360155,-5.15)); -#144085 = CARTESIAN_POINT('',(2.155042246384,-5.15)); -#144086 = CARTESIAN_POINT('',(2.225510132613,-5.15)); -#144087 = CARTESIAN_POINT('',(2.295978018842,-5.15)); -#144088 = CARTESIAN_POINT('',(2.366445905071,-5.15)); -#144089 = CARTESIAN_POINT('',(2.4369137913,-5.15)); -#144090 = CARTESIAN_POINT('',(2.507381677529,-5.15)); -#144091 = CARTESIAN_POINT('',(2.577849563758,-5.15)); -#144092 = CARTESIAN_POINT('',(2.648317449987,-5.15)); -#144093 = CARTESIAN_POINT('',(2.718785336216,-5.15)); -#144094 = CARTESIAN_POINT('',(2.789253222445,-5.15)); -#144095 = CARTESIAN_POINT('',(2.859721108674,-5.15)); -#144096 = CARTESIAN_POINT('',(2.930188994903,-5.15)); -#144097 = CARTESIAN_POINT('',(3.000656881132,-5.15)); -#144098 = CARTESIAN_POINT('',(3.071124767361,-5.15)); -#144099 = CARTESIAN_POINT('',(3.11810335818,-5.15)); -#144100 = CARTESIAN_POINT('',(3.14159265359,-5.15)); -#144101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144102 = PCURVE('',#86928,#144103); -#144103 = DEFINITIONAL_REPRESENTATION('',(#144104),#144112); -#144104 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144105,#144106,#144107, - #144108,#144109,#144110,#144111),.UNSPECIFIED.,.T.,.F.) +#146468 = CARTESIAN_POINT('',(1.591299156552,-5.15)); +#146469 = CARTESIAN_POINT('',(1.614788451962,-5.15)); +#146470 = CARTESIAN_POINT('',(1.661767042781,-5.15)); +#146471 = CARTESIAN_POINT('',(1.73223492901,-5.15)); +#146472 = CARTESIAN_POINT('',(1.802702815239,-5.15)); +#146473 = CARTESIAN_POINT('',(1.873170701468,-5.15)); +#146474 = CARTESIAN_POINT('',(1.943638587697,-5.15)); +#146475 = CARTESIAN_POINT('',(2.014106473926,-5.15)); +#146476 = CARTESIAN_POINT('',(2.084574360155,-5.15)); +#146477 = CARTESIAN_POINT('',(2.155042246384,-5.15)); +#146478 = CARTESIAN_POINT('',(2.225510132613,-5.15)); +#146479 = CARTESIAN_POINT('',(2.295978018842,-5.15)); +#146480 = CARTESIAN_POINT('',(2.366445905071,-5.15)); +#146481 = CARTESIAN_POINT('',(2.4369137913,-5.15)); +#146482 = CARTESIAN_POINT('',(2.507381677529,-5.15)); +#146483 = CARTESIAN_POINT('',(2.577849563758,-5.15)); +#146484 = CARTESIAN_POINT('',(2.648317449987,-5.15)); +#146485 = CARTESIAN_POINT('',(2.718785336216,-5.15)); +#146486 = CARTESIAN_POINT('',(2.789253222445,-5.15)); +#146487 = CARTESIAN_POINT('',(2.859721108674,-5.15)); +#146488 = CARTESIAN_POINT('',(2.930188994903,-5.15)); +#146489 = CARTESIAN_POINT('',(3.000656881132,-5.15)); +#146490 = CARTESIAN_POINT('',(3.071124767361,-5.15)); +#146491 = CARTESIAN_POINT('',(3.11810335818,-5.15)); +#146492 = CARTESIAN_POINT('',(3.14159265359,-5.15)); +#146493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146494 = PCURVE('',#89320,#146495); +#146495 = DEFINITIONAL_REPRESENTATION('',(#146496),#146504); +#146496 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146497,#146498,#146499, + #146500,#146501,#146502,#146503),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#144105 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#144106 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#144107 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#144108 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#144109 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#144110 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#144111 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#144112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144113 = ORIENTED_EDGE('',*,*,#144114,.T.); -#144114 = EDGE_CURVE('',#144065,#144018,#144115,.T.); -#144115 = SURFACE_CURVE('',#144116,(#144120,#144126),.PCURVE_S1.); -#144116 = LINE('',#144117,#144118); -#144117 = CARTESIAN_POINT('',(5.15,10.304819755875,0.75)); -#144118 = VECTOR('',#144119,1.); -#144119 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144120 = PCURVE('',#143886,#144121); -#144121 = DEFINITIONAL_REPRESENTATION('',(#144122),#144125); -#144122 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144123,#144124), +#146497 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#146498 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#146499 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#146500 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#146501 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#146502 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#146503 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#146504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146505 = ORIENTED_EDGE('',*,*,#146506,.T.); +#146506 = EDGE_CURVE('',#146457,#146410,#146507,.T.); +#146507 = SURFACE_CURVE('',#146508,(#146512,#146518),.PCURVE_S1.); +#146508 = LINE('',#146509,#146510); +#146509 = CARTESIAN_POINT('',(5.15,10.304819755875,0.75)); +#146510 = VECTOR('',#146511,1.); +#146511 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146512 = PCURVE('',#146278,#146513); +#146513 = DEFINITIONAL_REPRESENTATION('',(#146514),#146517); +#146514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146515,#146516), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#144123 = CARTESIAN_POINT('',(1.591299156552,-5.15)); -#144124 = CARTESIAN_POINT('',(1.591299156552,-5.35)); -#144125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144126 = PCURVE('',#87010,#144127); -#144127 = DEFINITIONAL_REPRESENTATION('',(#144128),#144132); -#144128 = LINE('',#144129,#144130); -#144129 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#144130 = VECTOR('',#144131,1.); -#144131 = DIRECTION('',(-8.881784197001E-016,1.)); -#144132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146515 = CARTESIAN_POINT('',(1.591299156552,-5.15)); +#146516 = CARTESIAN_POINT('',(1.591299156552,-5.35)); +#146517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144133 = ADVANCED_FACE('',(#144134),#86928,.F.); -#144134 = FACE_BOUND('',#144135,.T.); -#144135 = EDGE_LOOP('',(#144136,#144157,#144158,#144159,#144160,#144161, - #144182,#144183,#144184,#144185,#144186,#144207)); -#144136 = ORIENTED_EDGE('',*,*,#144137,.F.); -#144137 = EDGE_CURVE('',#144065,#86913,#144138,.T.); -#144138 = SURFACE_CURVE('',#144139,(#144143,#144150),.PCURVE_S1.); -#144139 = LINE('',#144140,#144141); -#144140 = CARTESIAN_POINT('',(5.15,10.527847992439,0.75)); -#144141 = VECTOR('',#144142,1.); -#144142 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#144143 = PCURVE('',#86928,#144144); -#144144 = DEFINITIONAL_REPRESENTATION('',(#144145),#144149); -#144145 = LINE('',#144146,#144147); -#144146 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#144147 = VECTOR('',#144148,1.); -#144148 = DIRECTION('',(-3.563627120235E-016,-1.)); -#144149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144150 = PCURVE('',#87010,#144151); -#144151 = DEFINITIONAL_REPRESENTATION('',(#144152),#144156); -#144152 = LINE('',#144153,#144154); -#144153 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144154 = VECTOR('',#144155,1.); -#144155 = DIRECTION('',(-1.,6.005309793447E-063)); -#144156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144157 = ORIENTED_EDGE('',*,*,#144064,.T.); -#144158 = ORIENTED_EDGE('',*,*,#143919,.T.); -#144159 = ORIENTED_EDGE('',*,*,#143644,.T.); -#144160 = ORIENTED_EDGE('',*,*,#143434,.T.); -#144161 = ORIENTED_EDGE('',*,*,#144162,.T.); -#144162 = EDGE_CURVE('',#143407,#143488,#144163,.T.); -#144163 = SURFACE_CURVE('',#144164,(#144168,#144175),.PCURVE_S1.); -#144164 = LINE('',#144165,#144166); -#144165 = CARTESIAN_POINT('',(5.15,11.,1.159810404338E-002)); -#144166 = VECTOR('',#144167,1.); -#144167 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#144168 = PCURVE('',#86928,#144169); -#144169 = DEFINITIONAL_REPRESENTATION('',(#144170),#144174); -#144170 = LINE('',#144171,#144172); -#144171 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#144172 = VECTOR('',#144173,1.); -#144173 = DIRECTION('',(1.,-2.101748079665E-016)); -#144174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144175 = PCURVE('',#143422,#144176); -#144176 = DEFINITIONAL_REPRESENTATION('',(#144177),#144181); -#144177 = LINE('',#144178,#144179); -#144178 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#144179 = VECTOR('',#144180,1.); -#144180 = DIRECTION('',(1.570395187386E-016,-1.)); -#144181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144182 = ORIENTED_EDGE('',*,*,#143485,.F.); -#144183 = ORIENTED_EDGE('',*,*,#143746,.F.); -#144184 = ORIENTED_EDGE('',*,*,#143822,.F.); -#144185 = ORIENTED_EDGE('',*,*,#143943,.F.); -#144186 = ORIENTED_EDGE('',*,*,#144187,.T.); -#144187 = EDGE_CURVE('',#143944,#86911,#144188,.T.); -#144188 = SURFACE_CURVE('',#144189,(#144193,#144200),.PCURVE_S1.); -#144189 = LINE('',#144190,#144191); -#144190 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); -#144191 = VECTOR('',#144192,1.); -#144192 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#144193 = PCURVE('',#86928,#144194); -#144194 = DEFINITIONAL_REPRESENTATION('',(#144195),#144199); -#144195 = LINE('',#144196,#144197); -#144196 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144197 = VECTOR('',#144198,1.); -#144198 = DIRECTION('',(-3.563627120235E-016,-1.)); -#144199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144200 = PCURVE('',#86956,#144201); -#144201 = DEFINITIONAL_REPRESENTATION('',(#144202),#144206); -#144202 = LINE('',#144203,#144204); -#144203 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144204 = VECTOR('',#144205,1.); -#144205 = DIRECTION('',(1.,6.005309793447E-063)); -#144206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144207 = ORIENTED_EDGE('',*,*,#86910,.T.); -#144208 = ADVANCED_FACE('',(#144209),#87010,.F.); -#144209 = FACE_BOUND('',#144210,.T.); -#144210 = EDGE_LOOP('',(#144211,#144212,#144213,#144214)); -#144211 = ORIENTED_EDGE('',*,*,#144114,.F.); -#144212 = ORIENTED_EDGE('',*,*,#144137,.T.); -#144213 = ORIENTED_EDGE('',*,*,#86996,.T.); -#144214 = ORIENTED_EDGE('',*,*,#144215,.F.); -#144215 = EDGE_CURVE('',#144018,#86969,#144216,.T.); -#144216 = SURFACE_CURVE('',#144217,(#144221,#144228),.PCURVE_S1.); -#144217 = LINE('',#144218,#144219); -#144218 = CARTESIAN_POINT('',(5.35,10.527847992439,0.75)); -#144219 = VECTOR('',#144220,1.); -#144220 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#144221 = PCURVE('',#87010,#144222); -#144222 = DEFINITIONAL_REPRESENTATION('',(#144223),#144227); -#144223 = LINE('',#144224,#144225); -#144224 = CARTESIAN_POINT('',(0.E+000,0.2)); -#144225 = VECTOR('',#144226,1.); -#144226 = DIRECTION('',(-1.,6.005309793447E-063)); -#144227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144228 = PCURVE('',#86984,#144229); -#144229 = DEFINITIONAL_REPRESENTATION('',(#144230),#144234); -#144230 = LINE('',#144231,#144232); -#144231 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#144232 = VECTOR('',#144233,1.); -#144233 = DIRECTION('',(3.563627120235E-016,-1.)); -#144234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146518 = PCURVE('',#89402,#146519); +#146519 = DEFINITIONAL_REPRESENTATION('',(#146520),#146524); +#146520 = LINE('',#146521,#146522); +#146521 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#146522 = VECTOR('',#146523,1.); +#146523 = DIRECTION('',(-8.881784197001E-016,1.)); +#146524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146525 = ADVANCED_FACE('',(#146526),#89320,.F.); +#146526 = FACE_BOUND('',#146527,.T.); +#146527 = EDGE_LOOP('',(#146528,#146549,#146550,#146551,#146552,#146553, + #146574,#146575,#146576,#146577,#146578,#146599)); +#146528 = ORIENTED_EDGE('',*,*,#146529,.F.); +#146529 = EDGE_CURVE('',#146457,#89305,#146530,.T.); +#146530 = SURFACE_CURVE('',#146531,(#146535,#146542),.PCURVE_S1.); +#146531 = LINE('',#146532,#146533); +#146532 = CARTESIAN_POINT('',(5.15,10.527847992439,0.75)); +#146533 = VECTOR('',#146534,1.); +#146534 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#146535 = PCURVE('',#89320,#146536); +#146536 = DEFINITIONAL_REPRESENTATION('',(#146537),#146541); +#146537 = LINE('',#146538,#146539); +#146538 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#146539 = VECTOR('',#146540,1.); +#146540 = DIRECTION('',(-3.563627120235E-016,-1.)); +#146541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146542 = PCURVE('',#89402,#146543); +#146543 = DEFINITIONAL_REPRESENTATION('',(#146544),#146548); +#146544 = LINE('',#146545,#146546); +#146545 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146546 = VECTOR('',#146547,1.); +#146547 = DIRECTION('',(-1.,6.005309793447E-063)); +#146548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146549 = ORIENTED_EDGE('',*,*,#146456,.T.); +#146550 = ORIENTED_EDGE('',*,*,#146311,.T.); +#146551 = ORIENTED_EDGE('',*,*,#146036,.T.); +#146552 = ORIENTED_EDGE('',*,*,#145826,.T.); +#146553 = ORIENTED_EDGE('',*,*,#146554,.T.); +#146554 = EDGE_CURVE('',#145799,#145880,#146555,.T.); +#146555 = SURFACE_CURVE('',#146556,(#146560,#146567),.PCURVE_S1.); +#146556 = LINE('',#146557,#146558); +#146557 = CARTESIAN_POINT('',(5.15,11.,1.159810404338E-002)); +#146558 = VECTOR('',#146559,1.); +#146559 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#146560 = PCURVE('',#89320,#146561); +#146561 = DEFINITIONAL_REPRESENTATION('',(#146562),#146566); +#146562 = LINE('',#146563,#146564); +#146563 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#146564 = VECTOR('',#146565,1.); +#146565 = DIRECTION('',(1.,-2.101748079665E-016)); +#146566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146567 = PCURVE('',#145814,#146568); +#146568 = DEFINITIONAL_REPRESENTATION('',(#146569),#146573); +#146569 = LINE('',#146570,#146571); +#146570 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#146571 = VECTOR('',#146572,1.); +#146572 = DIRECTION('',(1.570395187386E-016,-1.)); +#146573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146574 = ORIENTED_EDGE('',*,*,#145877,.F.); +#146575 = ORIENTED_EDGE('',*,*,#146138,.F.); +#146576 = ORIENTED_EDGE('',*,*,#146214,.F.); +#146577 = ORIENTED_EDGE('',*,*,#146335,.F.); +#146578 = ORIENTED_EDGE('',*,*,#146579,.T.); +#146579 = EDGE_CURVE('',#146336,#89303,#146580,.T.); +#146580 = SURFACE_CURVE('',#146581,(#146585,#146592),.PCURVE_S1.); +#146581 = LINE('',#146582,#146583); +#146582 = CARTESIAN_POINT('',(5.15,10.527847992439,0.65)); +#146583 = VECTOR('',#146584,1.); +#146584 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#146585 = PCURVE('',#89320,#146586); +#146586 = DEFINITIONAL_REPRESENTATION('',(#146587),#146591); +#146587 = LINE('',#146588,#146589); +#146588 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146589 = VECTOR('',#146590,1.); +#146590 = DIRECTION('',(-3.563627120235E-016,-1.)); +#146591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144235 = ADVANCED_FACE('',(#144236),#86984,.F.); -#144236 = FACE_BOUND('',#144237,.T.); -#144237 = EDGE_LOOP('',(#144238,#144259,#144260,#144261,#144262,#144263, - #144284,#144285,#144286,#144287,#144288,#144289)); -#144238 = ORIENTED_EDGE('',*,*,#144239,.F.); -#144239 = EDGE_CURVE('',#143971,#86941,#144240,.T.); -#144240 = SURFACE_CURVE('',#144241,(#144245,#144252),.PCURVE_S1.); -#144241 = LINE('',#144242,#144243); -#144242 = CARTESIAN_POINT('',(5.35,10.527847992439,0.65)); -#144243 = VECTOR('',#144244,1.); -#144244 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#144245 = PCURVE('',#86984,#144246); -#144246 = DEFINITIONAL_REPRESENTATION('',(#144247),#144251); -#144247 = LINE('',#144248,#144249); -#144248 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144249 = VECTOR('',#144250,1.); -#144250 = DIRECTION('',(3.563627120235E-016,-1.)); -#144251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144252 = PCURVE('',#86956,#144253); -#144253 = DEFINITIONAL_REPRESENTATION('',(#144254),#144258); -#144254 = LINE('',#144255,#144256); -#144255 = CARTESIAN_POINT('',(0.E+000,0.2)); -#144256 = VECTOR('',#144257,1.); -#144257 = DIRECTION('',(1.,6.005309793447E-063)); -#144258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144259 = ORIENTED_EDGE('',*,*,#143992,.T.); -#144260 = ORIENTED_EDGE('',*,*,#143844,.T.); -#144261 = ORIENTED_EDGE('',*,*,#143669,.T.); -#144262 = ORIENTED_EDGE('',*,*,#143538,.T.); -#144263 = ORIENTED_EDGE('',*,*,#144264,.T.); -#144264 = EDGE_CURVE('',#143516,#143379,#144265,.T.); -#144265 = SURFACE_CURVE('',#144266,(#144270,#144277),.PCURVE_S1.); -#144266 = LINE('',#144267,#144268); -#144267 = CARTESIAN_POINT('',(5.35,11.,1.159810404338E-002)); -#144268 = VECTOR('',#144269,1.); -#144269 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#144270 = PCURVE('',#86984,#144271); -#144271 = DEFINITIONAL_REPRESENTATION('',(#144272),#144276); -#144272 = LINE('',#144273,#144274); -#144273 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#144274 = VECTOR('',#144275,1.); -#144275 = DIRECTION('',(1.,2.101748079665E-016)); -#144276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144277 = PCURVE('',#143422,#144278); -#144278 = DEFINITIONAL_REPRESENTATION('',(#144279),#144283); -#144279 = LINE('',#144280,#144281); -#144280 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#144281 = VECTOR('',#144282,1.); -#144282 = DIRECTION('',(-1.570395187386E-016,1.)); -#144283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144284 = ORIENTED_EDGE('',*,*,#143376,.F.); -#144285 = ORIENTED_EDGE('',*,*,#143590,.F.); -#144286 = ORIENTED_EDGE('',*,*,#143897,.F.); -#144287 = ORIENTED_EDGE('',*,*,#144017,.F.); -#144288 = ORIENTED_EDGE('',*,*,#144215,.T.); -#144289 = ORIENTED_EDGE('',*,*,#86968,.T.); -#144290 = ADVANCED_FACE('',(#144291),#86956,.F.); -#144291 = FACE_BOUND('',#144292,.T.); -#144292 = EDGE_LOOP('',(#144293,#144294,#144295,#144296)); -#144293 = ORIENTED_EDGE('',*,*,#143970,.F.); -#144294 = ORIENTED_EDGE('',*,*,#144239,.T.); -#144295 = ORIENTED_EDGE('',*,*,#86940,.T.); -#144296 = ORIENTED_EDGE('',*,*,#144187,.F.); -#144297 = ADVANCED_FACE('',(#144298),#143422,.T.); -#144298 = FACE_BOUND('',#144299,.T.); -#144299 = EDGE_LOOP('',(#144300,#144301,#144302,#144303)); -#144300 = ORIENTED_EDGE('',*,*,#144264,.F.); -#144301 = ORIENTED_EDGE('',*,*,#143515,.F.); -#144302 = ORIENTED_EDGE('',*,*,#144162,.F.); -#144303 = ORIENTED_EDGE('',*,*,#143406,.F.); -#144304 = ADVANCED_FACE('',(#144305),#144319,.T.); -#144305 = FACE_BOUND('',#144306,.T.); -#144306 = EDGE_LOOP('',(#144307,#144337,#144365,#144388)); -#144307 = ORIENTED_EDGE('',*,*,#144308,.T.); -#144308 = EDGE_CURVE('',#144309,#144311,#144313,.T.); -#144309 = VERTEX_POINT('',#144310); -#144310 = CARTESIAN_POINT('',(4.15,10.74341632541,-0.308197125857)); -#144311 = VERTEX_POINT('',#144312); -#144312 = CARTESIAN_POINT('',(4.15,11.,-0.308197125857)); -#144313 = SURFACE_CURVE('',#144314,(#144318,#144330),.PCURVE_S1.); -#144314 = LINE('',#144315,#144316); -#144315 = CARTESIAN_POINT('',(4.15,10.74341632541,-0.308197125857)); -#144316 = VECTOR('',#144317,1.); -#144317 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#144318 = PCURVE('',#144319,#144324); -#144319 = PLANE('',#144320); -#144320 = AXIS2_PLACEMENT_3D('',#144321,#144322,#144323); -#144321 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#146592 = PCURVE('',#89348,#146593); +#146593 = DEFINITIONAL_REPRESENTATION('',(#146594),#146598); +#146594 = LINE('',#146595,#146596); +#146595 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146596 = VECTOR('',#146597,1.); +#146597 = DIRECTION('',(1.,6.005309793447E-063)); +#146598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146599 = ORIENTED_EDGE('',*,*,#89302,.T.); +#146600 = ADVANCED_FACE('',(#146601),#89402,.F.); +#146601 = FACE_BOUND('',#146602,.T.); +#146602 = EDGE_LOOP('',(#146603,#146604,#146605,#146606)); +#146603 = ORIENTED_EDGE('',*,*,#146506,.F.); +#146604 = ORIENTED_EDGE('',*,*,#146529,.T.); +#146605 = ORIENTED_EDGE('',*,*,#89388,.T.); +#146606 = ORIENTED_EDGE('',*,*,#146607,.F.); +#146607 = EDGE_CURVE('',#146410,#89361,#146608,.T.); +#146608 = SURFACE_CURVE('',#146609,(#146613,#146620),.PCURVE_S1.); +#146609 = LINE('',#146610,#146611); +#146610 = CARTESIAN_POINT('',(5.35,10.527847992439,0.75)); +#146611 = VECTOR('',#146612,1.); +#146612 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#146613 = PCURVE('',#89402,#146614); +#146614 = DEFINITIONAL_REPRESENTATION('',(#146615),#146619); +#146615 = LINE('',#146616,#146617); +#146616 = CARTESIAN_POINT('',(0.E+000,0.2)); +#146617 = VECTOR('',#146618,1.); +#146618 = DIRECTION('',(-1.,6.005309793447E-063)); +#146619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146620 = PCURVE('',#89376,#146621); +#146621 = DEFINITIONAL_REPRESENTATION('',(#146622),#146626); +#146622 = LINE('',#146623,#146624); +#146623 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#146624 = VECTOR('',#146625,1.); +#146625 = DIRECTION('',(3.563627120235E-016,-1.)); +#146626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146627 = ADVANCED_FACE('',(#146628),#89376,.F.); +#146628 = FACE_BOUND('',#146629,.T.); +#146629 = EDGE_LOOP('',(#146630,#146651,#146652,#146653,#146654,#146655, + #146676,#146677,#146678,#146679,#146680,#146681)); +#146630 = ORIENTED_EDGE('',*,*,#146631,.F.); +#146631 = EDGE_CURVE('',#146363,#89333,#146632,.T.); +#146632 = SURFACE_CURVE('',#146633,(#146637,#146644),.PCURVE_S1.); +#146633 = LINE('',#146634,#146635); +#146634 = CARTESIAN_POINT('',(5.35,10.527847992439,0.65)); +#146635 = VECTOR('',#146636,1.); +#146636 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#146637 = PCURVE('',#89376,#146638); +#146638 = DEFINITIONAL_REPRESENTATION('',(#146639),#146643); +#146639 = LINE('',#146640,#146641); +#146640 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146641 = VECTOR('',#146642,1.); +#146642 = DIRECTION('',(3.563627120235E-016,-1.)); +#146643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146644 = PCURVE('',#89348,#146645); +#146645 = DEFINITIONAL_REPRESENTATION('',(#146646),#146650); +#146646 = LINE('',#146647,#146648); +#146647 = CARTESIAN_POINT('',(0.E+000,0.2)); +#146648 = VECTOR('',#146649,1.); +#146649 = DIRECTION('',(1.,6.005309793447E-063)); +#146650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146651 = ORIENTED_EDGE('',*,*,#146384,.T.); +#146652 = ORIENTED_EDGE('',*,*,#146236,.T.); +#146653 = ORIENTED_EDGE('',*,*,#146061,.T.); +#146654 = ORIENTED_EDGE('',*,*,#145930,.T.); +#146655 = ORIENTED_EDGE('',*,*,#146656,.T.); +#146656 = EDGE_CURVE('',#145908,#145771,#146657,.T.); +#146657 = SURFACE_CURVE('',#146658,(#146662,#146669),.PCURVE_S1.); +#146658 = LINE('',#146659,#146660); +#146659 = CARTESIAN_POINT('',(5.35,11.,1.159810404338E-002)); +#146660 = VECTOR('',#146661,1.); +#146661 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#146662 = PCURVE('',#89376,#146663); +#146663 = DEFINITIONAL_REPRESENTATION('',(#146664),#146668); +#146664 = LINE('',#146665,#146666); +#146665 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#146666 = VECTOR('',#146667,1.); +#146667 = DIRECTION('',(1.,2.101748079665E-016)); +#146668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146669 = PCURVE('',#145814,#146670); +#146670 = DEFINITIONAL_REPRESENTATION('',(#146671),#146675); +#146671 = LINE('',#146672,#146673); +#146672 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#146673 = VECTOR('',#146674,1.); +#146674 = DIRECTION('',(-1.570395187386E-016,1.)); +#146675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146676 = ORIENTED_EDGE('',*,*,#145768,.F.); +#146677 = ORIENTED_EDGE('',*,*,#145982,.F.); +#146678 = ORIENTED_EDGE('',*,*,#146289,.F.); +#146679 = ORIENTED_EDGE('',*,*,#146409,.F.); +#146680 = ORIENTED_EDGE('',*,*,#146607,.T.); +#146681 = ORIENTED_EDGE('',*,*,#89360,.T.); +#146682 = ADVANCED_FACE('',(#146683),#89348,.F.); +#146683 = FACE_BOUND('',#146684,.T.); +#146684 = EDGE_LOOP('',(#146685,#146686,#146687,#146688)); +#146685 = ORIENTED_EDGE('',*,*,#146362,.F.); +#146686 = ORIENTED_EDGE('',*,*,#146631,.T.); +#146687 = ORIENTED_EDGE('',*,*,#89332,.T.); +#146688 = ORIENTED_EDGE('',*,*,#146579,.F.); +#146689 = ADVANCED_FACE('',(#146690),#145814,.T.); +#146690 = FACE_BOUND('',#146691,.T.); +#146691 = EDGE_LOOP('',(#146692,#146693,#146694,#146695)); +#146692 = ORIENTED_EDGE('',*,*,#146656,.F.); +#146693 = ORIENTED_EDGE('',*,*,#145907,.F.); +#146694 = ORIENTED_EDGE('',*,*,#146554,.F.); +#146695 = ORIENTED_EDGE('',*,*,#145798,.F.); +#146696 = ADVANCED_FACE('',(#146697),#146711,.T.); +#146697 = FACE_BOUND('',#146698,.T.); +#146698 = EDGE_LOOP('',(#146699,#146729,#146757,#146780)); +#146699 = ORIENTED_EDGE('',*,*,#146700,.T.); +#146700 = EDGE_CURVE('',#146701,#146703,#146705,.T.); +#146701 = VERTEX_POINT('',#146702); +#146702 = CARTESIAN_POINT('',(4.15,10.74341632541,-0.308197125857)); +#146703 = VERTEX_POINT('',#146704); +#146704 = CARTESIAN_POINT('',(4.15,11.,-0.308197125857)); +#146705 = SURFACE_CURVE('',#146706,(#146710,#146722),.PCURVE_S1.); +#146706 = LINE('',#146707,#146708); +#146707 = CARTESIAN_POINT('',(4.15,10.74341632541,-0.308197125857)); +#146708 = VECTOR('',#146709,1.); +#146709 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#146710 = PCURVE('',#146711,#146716); +#146711 = PLANE('',#146712); +#146712 = AXIS2_PLACEMENT_3D('',#146713,#146714,#146715); +#146713 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#144322 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#144323 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#144324 = DEFINITIONAL_REPRESENTATION('',(#144325),#144329); -#144325 = LINE('',#144326,#144327); -#144326 = CARTESIAN_POINT('',(-4.15,-3.552713678801E-015)); -#144327 = VECTOR('',#144328,1.); -#144328 = DIRECTION('',(-6.725593854929E-015,1.)); -#144329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144330 = PCURVE('',#88010,#144331); -#144331 = DEFINITIONAL_REPRESENTATION('',(#144332),#144336); -#144332 = LINE('',#144333,#144334); -#144333 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#144334 = VECTOR('',#144335,1.); -#144335 = DIRECTION('',(0.E+000,1.)); -#144336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144337 = ORIENTED_EDGE('',*,*,#144338,.T.); -#144338 = EDGE_CURVE('',#144311,#144339,#144341,.T.); -#144339 = VERTEX_POINT('',#144340); -#144340 = CARTESIAN_POINT('',(4.35,11.,-0.308197125857)); -#144341 = SURFACE_CURVE('',#144342,(#144346,#144353),.PCURVE_S1.); -#144342 = LINE('',#144343,#144344); -#144343 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#144344 = VECTOR('',#144345,1.); -#144345 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144346 = PCURVE('',#144319,#144347); -#144347 = DEFINITIONAL_REPRESENTATION('',(#144348),#144352); -#144348 = LINE('',#144349,#144350); -#144349 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#144350 = VECTOR('',#144351,1.); -#144351 = DIRECTION('',(-1.,-8.881784197001E-016)); -#144352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144353 = PCURVE('',#144354,#144359); -#144354 = PLANE('',#144355); -#144355 = AXIS2_PLACEMENT_3D('',#144356,#144357,#144358); -#144356 = CARTESIAN_POINT('',(4.25,11.,-0.258196742327)); -#144357 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#144358 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#144359 = DEFINITIONAL_REPRESENTATION('',(#144360),#144364); -#144360 = LINE('',#144361,#144362); -#144361 = CARTESIAN_POINT('',(4.25,-5.000038352949E-002)); -#144362 = VECTOR('',#144363,1.); -#144363 = DIRECTION('',(-1.,-1.1653254136E-048)); -#144364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144365 = ORIENTED_EDGE('',*,*,#144366,.F.); -#144366 = EDGE_CURVE('',#144367,#144339,#144369,.T.); -#144367 = VERTEX_POINT('',#144368); -#144368 = CARTESIAN_POINT('',(4.35,10.74341632541,-0.308197125857)); -#144369 = SURFACE_CURVE('',#144370,(#144374,#144381),.PCURVE_S1.); -#144370 = LINE('',#144371,#144372); -#144371 = CARTESIAN_POINT('',(4.35,10.74341632541,-0.308197125857)); -#144372 = VECTOR('',#144373,1.); -#144373 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#144374 = PCURVE('',#144319,#144375); -#144375 = DEFINITIONAL_REPRESENTATION('',(#144376),#144380); -#144376 = LINE('',#144377,#144378); -#144377 = CARTESIAN_POINT('',(-4.35,-3.552713678801E-015)); -#144378 = VECTOR('',#144379,1.); -#144379 = DIRECTION('',(-6.725593854929E-015,1.)); -#144380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144381 = PCURVE('',#87954,#144382); -#144382 = DEFINITIONAL_REPRESENTATION('',(#144383),#144387); -#144383 = LINE('',#144384,#144385); -#144384 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#144385 = VECTOR('',#144386,1.); -#144386 = DIRECTION('',(0.E+000,1.)); -#144387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144388 = ORIENTED_EDGE('',*,*,#144389,.T.); -#144389 = EDGE_CURVE('',#144367,#144309,#144390,.T.); -#144390 = SURFACE_CURVE('',#144391,(#144395,#144402),.PCURVE_S1.); -#144391 = LINE('',#144392,#144393); -#144392 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#146714 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#146715 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#146716 = DEFINITIONAL_REPRESENTATION('',(#146717),#146721); +#146717 = LINE('',#146718,#146719); +#146718 = CARTESIAN_POINT('',(-4.15,-3.552713678801E-015)); +#146719 = VECTOR('',#146720,1.); +#146720 = DIRECTION('',(-6.725593854929E-015,1.)); +#146721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146722 = PCURVE('',#90402,#146723); +#146723 = DEFINITIONAL_REPRESENTATION('',(#146724),#146728); +#146724 = LINE('',#146725,#146726); +#146725 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#146726 = VECTOR('',#146727,1.); +#146727 = DIRECTION('',(0.E+000,1.)); +#146728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146729 = ORIENTED_EDGE('',*,*,#146730,.T.); +#146730 = EDGE_CURVE('',#146703,#146731,#146733,.T.); +#146731 = VERTEX_POINT('',#146732); +#146732 = CARTESIAN_POINT('',(4.35,11.,-0.308197125857)); +#146733 = SURFACE_CURVE('',#146734,(#146738,#146745),.PCURVE_S1.); +#146734 = LINE('',#146735,#146736); +#146735 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#146736 = VECTOR('',#146737,1.); +#146737 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146738 = PCURVE('',#146711,#146739); +#146739 = DEFINITIONAL_REPRESENTATION('',(#146740),#146744); +#146740 = LINE('',#146741,#146742); +#146741 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#146742 = VECTOR('',#146743,1.); +#146743 = DIRECTION('',(-1.,-8.881784197001E-016)); +#146744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146745 = PCURVE('',#146746,#146751); +#146746 = PLANE('',#146747); +#146747 = AXIS2_PLACEMENT_3D('',#146748,#146749,#146750); +#146748 = CARTESIAN_POINT('',(4.25,11.,-0.258196742327)); +#146749 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#146750 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#146751 = DEFINITIONAL_REPRESENTATION('',(#146752),#146756); +#146752 = LINE('',#146753,#146754); +#146753 = CARTESIAN_POINT('',(4.25,-5.000038352949E-002)); +#146754 = VECTOR('',#146755,1.); +#146755 = DIRECTION('',(-1.,-1.1653254136E-048)); +#146756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146757 = ORIENTED_EDGE('',*,*,#146758,.F.); +#146758 = EDGE_CURVE('',#146759,#146731,#146761,.T.); +#146759 = VERTEX_POINT('',#146760); +#146760 = CARTESIAN_POINT('',(4.35,10.74341632541,-0.308197125857)); +#146761 = SURFACE_CURVE('',#146762,(#146766,#146773),.PCURVE_S1.); +#146762 = LINE('',#146763,#146764); +#146763 = CARTESIAN_POINT('',(4.35,10.74341632541,-0.308197125857)); +#146764 = VECTOR('',#146765,1.); +#146765 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#146766 = PCURVE('',#146711,#146767); +#146767 = DEFINITIONAL_REPRESENTATION('',(#146768),#146772); +#146768 = LINE('',#146769,#146770); +#146769 = CARTESIAN_POINT('',(-4.35,-3.552713678801E-015)); +#146770 = VECTOR('',#146771,1.); +#146771 = DIRECTION('',(-6.725593854929E-015,1.)); +#146772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146773 = PCURVE('',#90346,#146774); +#146774 = DEFINITIONAL_REPRESENTATION('',(#146775),#146779); +#146775 = LINE('',#146776,#146777); +#146776 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#146777 = VECTOR('',#146778,1.); +#146778 = DIRECTION('',(0.E+000,1.)); +#146779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146780 = ORIENTED_EDGE('',*,*,#146781,.T.); +#146781 = EDGE_CURVE('',#146759,#146701,#146782,.T.); +#146782 = SURFACE_CURVE('',#146783,(#146787,#146794),.PCURVE_S1.); +#146783 = LINE('',#146784,#146785); +#146784 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#144393 = VECTOR('',#144394,1.); -#144394 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144395 = PCURVE('',#144319,#144396); -#144396 = DEFINITIONAL_REPRESENTATION('',(#144397),#144401); -#144397 = LINE('',#144398,#144399); -#144398 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144399 = VECTOR('',#144400,1.); -#144400 = DIRECTION('',(1.,8.881784197001E-016)); -#144401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144402 = PCURVE('',#144403,#144408); -#144403 = CYLINDRICAL_SURFACE('',#144404,0.308574064194); -#144404 = AXIS2_PLACEMENT_3D('',#144405,#144406,#144407); -#144405 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#146785 = VECTOR('',#146786,1.); +#146786 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146787 = PCURVE('',#146711,#146788); +#146788 = DEFINITIONAL_REPRESENTATION('',(#146789),#146793); +#146789 = LINE('',#146790,#146791); +#146790 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146791 = VECTOR('',#146792,1.); +#146792 = DIRECTION('',(1.,8.881784197001E-016)); +#146793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146794 = PCURVE('',#146795,#146800); +#146795 = CYLINDRICAL_SURFACE('',#146796,0.308574064194); +#146796 = AXIS2_PLACEMENT_3D('',#146797,#146798,#146799); +#146797 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#144406 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144407 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144408 = DEFINITIONAL_REPRESENTATION('',(#144409),#144412); -#144409 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144410,#144411), +#146798 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146799 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146800 = DEFINITIONAL_REPRESENTATION('',(#146801),#146804); +#146801 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146802,#146803), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#144410 = CARTESIAN_POINT('',(4.761821717947,4.35)); -#144411 = CARTESIAN_POINT('',(4.761821717947,4.15)); -#144412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146802 = CARTESIAN_POINT('',(4.761821717947,4.35)); +#146803 = CARTESIAN_POINT('',(4.761821717947,4.15)); +#146804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146805 = ADVANCED_FACE('',(#146806),#146820,.T.); +#146806 = FACE_BOUND('',#146807,.T.); +#146807 = EDGE_LOOP('',(#146808,#146838,#146861,#146884)); +#146808 = ORIENTED_EDGE('',*,*,#146809,.T.); +#146809 = EDGE_CURVE('',#146810,#146812,#146814,.T.); +#146810 = VERTEX_POINT('',#146811); +#146811 = CARTESIAN_POINT('',(4.35,10.740726081328,-0.208196358798)); +#146812 = VERTEX_POINT('',#146813); +#146813 = CARTESIAN_POINT('',(4.35,11.,-0.208196358798)); +#146814 = SURFACE_CURVE('',#146815,(#146819,#146831),.PCURVE_S1.); +#146815 = LINE('',#146816,#146817); +#146816 = CARTESIAN_POINT('',(4.35,10.740726081328,-0.208196358798)); +#146817 = VECTOR('',#146818,1.); +#146818 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#146819 = PCURVE('',#146820,#146825); +#146820 = PLANE('',#146821); +#146821 = AXIS2_PLACEMENT_3D('',#146822,#146823,#146824); +#146822 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#146823 = DIRECTION('',(0.E+000,0.E+000,1.)); +#146824 = DIRECTION('',(1.,0.E+000,0.E+000)); +#146825 = DEFINITIONAL_REPRESENTATION('',(#146826),#146830); +#146826 = LINE('',#146827,#146828); +#146827 = CARTESIAN_POINT('',(4.35,-3.552713678801E-015)); +#146828 = VECTOR('',#146829,1.); +#146829 = DIRECTION('',(6.725593854929E-015,1.)); +#146830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146831 = PCURVE('',#90346,#146832); +#146832 = DEFINITIONAL_REPRESENTATION('',(#146833),#146837); +#146833 = LINE('',#146834,#146835); +#146834 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#146835 = VECTOR('',#146836,1.); +#146836 = DIRECTION('',(0.E+000,1.)); +#146837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146838 = ORIENTED_EDGE('',*,*,#146839,.T.); +#146839 = EDGE_CURVE('',#146812,#146840,#146842,.T.); +#146840 = VERTEX_POINT('',#146841); +#146841 = CARTESIAN_POINT('',(4.15,11.,-0.208196358798)); +#146842 = SURFACE_CURVE('',#146843,(#146847,#146854),.PCURVE_S1.); +#146843 = LINE('',#146844,#146845); +#146844 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#146845 = VECTOR('',#146846,1.); +#146846 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146847 = PCURVE('',#146820,#146848); +#146848 = DEFINITIONAL_REPRESENTATION('',(#146849),#146853); +#146849 = LINE('',#146850,#146851); +#146850 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#146851 = VECTOR('',#146852,1.); +#146852 = DIRECTION('',(-1.,8.881784197001E-016)); +#146853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144413 = ADVANCED_FACE('',(#144414),#144428,.T.); -#144414 = FACE_BOUND('',#144415,.T.); -#144415 = EDGE_LOOP('',(#144416,#144446,#144469,#144492)); -#144416 = ORIENTED_EDGE('',*,*,#144417,.T.); -#144417 = EDGE_CURVE('',#144418,#144420,#144422,.T.); -#144418 = VERTEX_POINT('',#144419); -#144419 = CARTESIAN_POINT('',(4.35,10.740726081328,-0.208196358798)); -#144420 = VERTEX_POINT('',#144421); -#144421 = CARTESIAN_POINT('',(4.35,11.,-0.208196358798)); -#144422 = SURFACE_CURVE('',#144423,(#144427,#144439),.PCURVE_S1.); -#144423 = LINE('',#144424,#144425); -#144424 = CARTESIAN_POINT('',(4.35,10.740726081328,-0.208196358798)); -#144425 = VECTOR('',#144426,1.); -#144426 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#144427 = PCURVE('',#144428,#144433); -#144428 = PLANE('',#144429); -#144429 = AXIS2_PLACEMENT_3D('',#144430,#144431,#144432); -#144430 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#144431 = DIRECTION('',(0.E+000,0.E+000,1.)); -#144432 = DIRECTION('',(1.,0.E+000,0.E+000)); -#144433 = DEFINITIONAL_REPRESENTATION('',(#144434),#144438); -#144434 = LINE('',#144435,#144436); -#144435 = CARTESIAN_POINT('',(4.35,-3.552713678801E-015)); -#144436 = VECTOR('',#144437,1.); -#144437 = DIRECTION('',(6.725593854929E-015,1.)); -#144438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144439 = PCURVE('',#87954,#144440); -#144440 = DEFINITIONAL_REPRESENTATION('',(#144441),#144445); -#144441 = LINE('',#144442,#144443); -#144442 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#144443 = VECTOR('',#144444,1.); -#144444 = DIRECTION('',(0.E+000,1.)); -#144445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144446 = ORIENTED_EDGE('',*,*,#144447,.T.); -#144447 = EDGE_CURVE('',#144420,#144448,#144450,.T.); -#144448 = VERTEX_POINT('',#144449); -#144449 = CARTESIAN_POINT('',(4.15,11.,-0.208196358798)); -#144450 = SURFACE_CURVE('',#144451,(#144455,#144462),.PCURVE_S1.); -#144451 = LINE('',#144452,#144453); -#144452 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#144453 = VECTOR('',#144454,1.); -#144454 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144455 = PCURVE('',#144428,#144456); -#144456 = DEFINITIONAL_REPRESENTATION('',(#144457),#144461); -#144457 = LINE('',#144458,#144459); -#144458 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#144459 = VECTOR('',#144460,1.); -#144460 = DIRECTION('',(-1.,8.881784197001E-016)); -#144461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144462 = PCURVE('',#144354,#144463); -#144463 = DEFINITIONAL_REPRESENTATION('',(#144464),#144468); -#144464 = LINE('',#144465,#144466); -#144465 = CARTESIAN_POINT('',(4.25,5.000038352949E-002)); -#144466 = VECTOR('',#144467,1.); -#144467 = DIRECTION('',(1.,1.1653254136E-048)); -#144468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144469 = ORIENTED_EDGE('',*,*,#144470,.F.); -#144470 = EDGE_CURVE('',#144471,#144448,#144473,.T.); -#144471 = VERTEX_POINT('',#144472); -#144472 = CARTESIAN_POINT('',(4.15,10.740726081328,-0.208196358798)); -#144473 = SURFACE_CURVE('',#144474,(#144478,#144485),.PCURVE_S1.); -#144474 = LINE('',#144475,#144476); -#144475 = CARTESIAN_POINT('',(4.15,10.740726081328,-0.208196358798)); -#144476 = VECTOR('',#144477,1.); -#144477 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#144478 = PCURVE('',#144428,#144479); -#144479 = DEFINITIONAL_REPRESENTATION('',(#144480),#144484); -#144480 = LINE('',#144481,#144482); -#144481 = CARTESIAN_POINT('',(4.15,-3.552713678801E-015)); -#144482 = VECTOR('',#144483,1.); -#144483 = DIRECTION('',(6.725593854929E-015,1.)); -#144484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144485 = PCURVE('',#88010,#144486); -#144486 = DEFINITIONAL_REPRESENTATION('',(#144487),#144491); -#144487 = LINE('',#144488,#144489); -#144488 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#144489 = VECTOR('',#144490,1.); -#144490 = DIRECTION('',(0.E+000,1.)); -#144491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144492 = ORIENTED_EDGE('',*,*,#144493,.T.); -#144493 = EDGE_CURVE('',#144471,#144418,#144494,.T.); -#144494 = SURFACE_CURVE('',#144495,(#144499,#144506),.PCURVE_S1.); -#144495 = LINE('',#144496,#144497); -#144496 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#146854 = PCURVE('',#146746,#146855); +#146855 = DEFINITIONAL_REPRESENTATION('',(#146856),#146860); +#146856 = LINE('',#146857,#146858); +#146857 = CARTESIAN_POINT('',(4.25,5.000038352949E-002)); +#146858 = VECTOR('',#146859,1.); +#146859 = DIRECTION('',(1.,1.1653254136E-048)); +#146860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146861 = ORIENTED_EDGE('',*,*,#146862,.F.); +#146862 = EDGE_CURVE('',#146863,#146840,#146865,.T.); +#146863 = VERTEX_POINT('',#146864); +#146864 = CARTESIAN_POINT('',(4.15,10.740726081328,-0.208196358798)); +#146865 = SURFACE_CURVE('',#146866,(#146870,#146877),.PCURVE_S1.); +#146866 = LINE('',#146867,#146868); +#146867 = CARTESIAN_POINT('',(4.15,10.740726081328,-0.208196358798)); +#146868 = VECTOR('',#146869,1.); +#146869 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#146870 = PCURVE('',#146820,#146871); +#146871 = DEFINITIONAL_REPRESENTATION('',(#146872),#146876); +#146872 = LINE('',#146873,#146874); +#146873 = CARTESIAN_POINT('',(4.15,-3.552713678801E-015)); +#146874 = VECTOR('',#146875,1.); +#146875 = DIRECTION('',(6.725593854929E-015,1.)); +#146876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146877 = PCURVE('',#90402,#146878); +#146878 = DEFINITIONAL_REPRESENTATION('',(#146879),#146883); +#146879 = LINE('',#146880,#146881); +#146880 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#146881 = VECTOR('',#146882,1.); +#146882 = DIRECTION('',(0.E+000,1.)); +#146883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146884 = ORIENTED_EDGE('',*,*,#146885,.T.); +#146885 = EDGE_CURVE('',#146863,#146810,#146886,.T.); +#146886 = SURFACE_CURVE('',#146887,(#146891,#146898),.PCURVE_S1.); +#146887 = LINE('',#146888,#146889); +#146888 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#144497 = VECTOR('',#144498,1.); -#144498 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144499 = PCURVE('',#144428,#144500); -#144500 = DEFINITIONAL_REPRESENTATION('',(#144501),#144505); -#144501 = LINE('',#144502,#144503); -#144502 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144503 = VECTOR('',#144504,1.); -#144504 = DIRECTION('',(1.,-8.881784197001E-016)); -#144505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144506 = PCURVE('',#144507,#144512); -#144507 = CYLINDRICAL_SURFACE('',#144508,0.208574704164); -#144508 = AXIS2_PLACEMENT_3D('',#144509,#144510,#144511); -#144509 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#146889 = VECTOR('',#146890,1.); +#146890 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146891 = PCURVE('',#146820,#146892); +#146892 = DEFINITIONAL_REPRESENTATION('',(#146893),#146897); +#146893 = LINE('',#146894,#146895); +#146894 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#146895 = VECTOR('',#146896,1.); +#146896 = DIRECTION('',(1.,-8.881784197001E-016)); +#146897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146898 = PCURVE('',#146899,#146904); +#146899 = CYLINDRICAL_SURFACE('',#146900,0.208574704164); +#146900 = AXIS2_PLACEMENT_3D('',#146901,#146902,#146903); +#146901 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#144510 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144511 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144512 = DEFINITIONAL_REPRESENTATION('',(#144513),#144516); -#144513 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144514,#144515), +#146902 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146903 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146904 = DEFINITIONAL_REPRESENTATION('',(#146905),#146908); +#146905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146906,#146907), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#144514 = CARTESIAN_POINT('',(4.772630242227,4.15)); -#144515 = CARTESIAN_POINT('',(4.772630242227,4.35)); -#144516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144517 = ADVANCED_FACE('',(#144518),#144403,.T.); -#144518 = FACE_BOUND('',#144519,.T.); -#144519 = EDGE_LOOP('',(#144520,#144521,#144571,#144598)); -#144520 = ORIENTED_EDGE('',*,*,#144389,.F.); -#144521 = ORIENTED_EDGE('',*,*,#144522,.F.); -#144522 = EDGE_CURVE('',#144523,#144367,#144525,.T.); -#144523 = VERTEX_POINT('',#144524); -#144524 = CARTESIAN_POINT('',(4.35,10.419594812019,0.E+000)); -#144525 = SURFACE_CURVE('',#144526,(#144531,#144560),.PCURVE_S1.); -#144526 = CIRCLE('',#144527,0.308574064194); -#144527 = AXIS2_PLACEMENT_3D('',#144528,#144529,#144530); -#144528 = CARTESIAN_POINT('',(4.35,10.728168876214,2.640924866458E-017) - ); -#144529 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144530 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144531 = PCURVE('',#144403,#144532); -#144532 = DEFINITIONAL_REPRESENTATION('',(#144533),#144559); -#144533 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144534,#144535,#144536, - #144537,#144538,#144539,#144540,#144541,#144542,#144543,#144544, - #144545,#144546,#144547,#144548,#144549,#144550,#144551,#144552, - #144553,#144554,#144555,#144556,#144557,#144558),.UNSPECIFIED.,.F., +#146906 = CARTESIAN_POINT('',(4.772630242227,4.15)); +#146907 = CARTESIAN_POINT('',(4.772630242227,4.35)); +#146908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146909 = ADVANCED_FACE('',(#146910),#146795,.T.); +#146910 = FACE_BOUND('',#146911,.T.); +#146911 = EDGE_LOOP('',(#146912,#146913,#146963,#146990)); +#146912 = ORIENTED_EDGE('',*,*,#146781,.F.); +#146913 = ORIENTED_EDGE('',*,*,#146914,.F.); +#146914 = EDGE_CURVE('',#146915,#146759,#146917,.T.); +#146915 = VERTEX_POINT('',#146916); +#146916 = CARTESIAN_POINT('',(4.35,10.419594812019,0.E+000)); +#146917 = SURFACE_CURVE('',#146918,(#146923,#146952),.PCURVE_S1.); +#146918 = CIRCLE('',#146919,0.308574064194); +#146919 = AXIS2_PLACEMENT_3D('',#146920,#146921,#146922); +#146920 = CARTESIAN_POINT('',(4.35,10.728168876214,2.640924866458E-017) + ); +#146921 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146922 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146923 = PCURVE('',#146795,#146924); +#146924 = DEFINITIONAL_REPRESENTATION('',(#146925),#146951); +#146925 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146926,#146927,#146928, + #146929,#146930,#146931,#146932,#146933,#146934,#146935,#146936, + #146937,#146938,#146939,#146940,#146941,#146942,#146943,#146944, + #146945,#146946,#146947,#146948,#146949,#146950),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -178201,102 +181203,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#144534 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#144535 = CARTESIAN_POINT('',(3.166141578807,4.35)); -#144536 = CARTESIAN_POINT('',(3.215239429242,4.35)); -#144537 = CARTESIAN_POINT('',(3.288886204895,4.35)); -#144538 = CARTESIAN_POINT('',(3.362532980548,4.35)); -#144539 = CARTESIAN_POINT('',(3.4361797562,4.35)); -#144540 = CARTESIAN_POINT('',(3.509826531853,4.35)); -#144541 = CARTESIAN_POINT('',(3.583473307505,4.35)); -#144542 = CARTESIAN_POINT('',(3.657120083158,4.35)); -#144543 = CARTESIAN_POINT('',(3.730766858811,4.35)); -#144544 = CARTESIAN_POINT('',(3.804413634463,4.35)); -#144545 = CARTESIAN_POINT('',(3.878060410116,4.35)); -#144546 = CARTESIAN_POINT('',(3.951707185768,4.35)); -#144547 = CARTESIAN_POINT('',(4.025353961421,4.35)); -#144548 = CARTESIAN_POINT('',(4.099000737074,4.35)); -#144549 = CARTESIAN_POINT('',(4.172647512726,4.35)); -#144550 = CARTESIAN_POINT('',(4.246294288379,4.35)); -#144551 = CARTESIAN_POINT('',(4.319941064031,4.35)); -#144552 = CARTESIAN_POINT('',(4.393587839684,4.35)); -#144553 = CARTESIAN_POINT('',(4.467234615337,4.35)); -#144554 = CARTESIAN_POINT('',(4.540881390989,4.35)); -#144555 = CARTESIAN_POINT('',(4.614528166642,4.35)); -#144556 = CARTESIAN_POINT('',(4.688174942294,4.35)); -#144557 = CARTESIAN_POINT('',(4.737272792729,4.35)); -#144558 = CARTESIAN_POINT('',(4.761821717947,4.35)); -#144559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144560 = PCURVE('',#87954,#144561); -#144561 = DEFINITIONAL_REPRESENTATION('',(#144562),#144570); -#144562 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144563,#144564,#144565, - #144566,#144567,#144568,#144569),.UNSPECIFIED.,.T.,.F.) +#146926 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#146927 = CARTESIAN_POINT('',(3.166141578807,4.35)); +#146928 = CARTESIAN_POINT('',(3.215239429242,4.35)); +#146929 = CARTESIAN_POINT('',(3.288886204895,4.35)); +#146930 = CARTESIAN_POINT('',(3.362532980548,4.35)); +#146931 = CARTESIAN_POINT('',(3.4361797562,4.35)); +#146932 = CARTESIAN_POINT('',(3.509826531853,4.35)); +#146933 = CARTESIAN_POINT('',(3.583473307505,4.35)); +#146934 = CARTESIAN_POINT('',(3.657120083158,4.35)); +#146935 = CARTESIAN_POINT('',(3.730766858811,4.35)); +#146936 = CARTESIAN_POINT('',(3.804413634463,4.35)); +#146937 = CARTESIAN_POINT('',(3.878060410116,4.35)); +#146938 = CARTESIAN_POINT('',(3.951707185768,4.35)); +#146939 = CARTESIAN_POINT('',(4.025353961421,4.35)); +#146940 = CARTESIAN_POINT('',(4.099000737074,4.35)); +#146941 = CARTESIAN_POINT('',(4.172647512726,4.35)); +#146942 = CARTESIAN_POINT('',(4.246294288379,4.35)); +#146943 = CARTESIAN_POINT('',(4.319941064031,4.35)); +#146944 = CARTESIAN_POINT('',(4.393587839684,4.35)); +#146945 = CARTESIAN_POINT('',(4.467234615337,4.35)); +#146946 = CARTESIAN_POINT('',(4.540881390989,4.35)); +#146947 = CARTESIAN_POINT('',(4.614528166642,4.35)); +#146948 = CARTESIAN_POINT('',(4.688174942294,4.35)); +#146949 = CARTESIAN_POINT('',(4.737272792729,4.35)); +#146950 = CARTESIAN_POINT('',(4.761821717947,4.35)); +#146951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146952 = PCURVE('',#90346,#146953); +#146953 = DEFINITIONAL_REPRESENTATION('',(#146954),#146962); +#146954 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146955,#146956,#146957, + #146958,#146959,#146960,#146961),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#144563 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#144564 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#144565 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#144566 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#144567 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#144568 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#144569 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#144570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144571 = ORIENTED_EDGE('',*,*,#144572,.F.); -#144572 = EDGE_CURVE('',#144573,#144523,#144575,.T.); -#144573 = VERTEX_POINT('',#144574); -#144574 = CARTESIAN_POINT('',(4.15,10.419594812019,0.E+000)); -#144575 = SURFACE_CURVE('',#144576,(#144580,#144586),.PCURVE_S1.); -#144576 = LINE('',#144577,#144578); -#144577 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#146955 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#146956 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#146957 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#146958 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#146959 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#146960 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#146961 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#146962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146963 = ORIENTED_EDGE('',*,*,#146964,.F.); +#146964 = EDGE_CURVE('',#146965,#146915,#146967,.T.); +#146965 = VERTEX_POINT('',#146966); +#146966 = CARTESIAN_POINT('',(4.15,10.419594812019,0.E+000)); +#146967 = SURFACE_CURVE('',#146968,(#146972,#146978),.PCURVE_S1.); +#146968 = LINE('',#146969,#146970); +#146969 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#144578 = VECTOR('',#144579,1.); -#144579 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144580 = PCURVE('',#144403,#144581); -#144581 = DEFINITIONAL_REPRESENTATION('',(#144582),#144585); -#144582 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144583,#144584), +#146970 = VECTOR('',#146971,1.); +#146971 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146972 = PCURVE('',#146795,#146973); +#146973 = DEFINITIONAL_REPRESENTATION('',(#146974),#146977); +#146974 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146975,#146976), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#144583 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#144584 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#144585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#146975 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#146976 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#146977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144586 = PCURVE('',#144587,#144592); -#144587 = PLANE('',#144588); -#144588 = AXIS2_PLACEMENT_3D('',#144589,#144590,#144591); -#144589 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#146978 = PCURVE('',#146979,#146984); +#146979 = PLANE('',#146980); +#146980 = AXIS2_PLACEMENT_3D('',#146981,#146982,#146983); +#146981 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#144590 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144591 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144592 = DEFINITIONAL_REPRESENTATION('',(#144593),#144597); -#144593 = LINE('',#144594,#144595); -#144594 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#144595 = VECTOR('',#144596,1.); -#144596 = DIRECTION('',(-1.,0.E+000)); -#144597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144598 = ORIENTED_EDGE('',*,*,#144599,.T.); -#144599 = EDGE_CURVE('',#144573,#144309,#144600,.T.); -#144600 = SURFACE_CURVE('',#144601,(#144606,#144635),.PCURVE_S1.); -#144601 = CIRCLE('',#144602,0.308574064194); -#144602 = AXIS2_PLACEMENT_3D('',#144603,#144604,#144605); -#144603 = CARTESIAN_POINT('',(4.15,10.728168876214,2.640924866458E-017) - ); -#144604 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144605 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144606 = PCURVE('',#144403,#144607); -#144607 = DEFINITIONAL_REPRESENTATION('',(#144608),#144634); -#144608 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144609,#144610,#144611, - #144612,#144613,#144614,#144615,#144616,#144617,#144618,#144619, - #144620,#144621,#144622,#144623,#144624,#144625,#144626,#144627, - #144628,#144629,#144630,#144631,#144632,#144633),.UNSPECIFIED.,.F., +#146982 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146983 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#146984 = DEFINITIONAL_REPRESENTATION('',(#146985),#146989); +#146985 = LINE('',#146986,#146987); +#146986 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#146987 = VECTOR('',#146988,1.); +#146988 = DIRECTION('',(-1.,0.E+000)); +#146989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#146990 = ORIENTED_EDGE('',*,*,#146991,.T.); +#146991 = EDGE_CURVE('',#146965,#146701,#146992,.T.); +#146992 = SURFACE_CURVE('',#146993,(#146998,#147027),.PCURVE_S1.); +#146993 = CIRCLE('',#146994,0.308574064194); +#146994 = AXIS2_PLACEMENT_3D('',#146995,#146996,#146997); +#146995 = CARTESIAN_POINT('',(4.15,10.728168876214,2.640924866458E-017) + ); +#146996 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#146997 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#146998 = PCURVE('',#146795,#146999); +#146999 = DEFINITIONAL_REPRESENTATION('',(#147000),#147026); +#147000 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147001,#147002,#147003, + #147004,#147005,#147006,#147007,#147008,#147009,#147010,#147011, + #147012,#147013,#147014,#147015,#147016,#147017,#147018,#147019, + #147020,#147021,#147022,#147023,#147024,#147025),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -178304,348 +181306,348 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#144609 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#144610 = CARTESIAN_POINT('',(3.166141578807,4.15)); -#144611 = CARTESIAN_POINT('',(3.215239429242,4.15)); -#144612 = CARTESIAN_POINT('',(3.288886204895,4.15)); -#144613 = CARTESIAN_POINT('',(3.362532980548,4.15)); -#144614 = CARTESIAN_POINT('',(3.4361797562,4.15)); -#144615 = CARTESIAN_POINT('',(3.509826531853,4.15)); -#144616 = CARTESIAN_POINT('',(3.583473307505,4.15)); -#144617 = CARTESIAN_POINT('',(3.657120083158,4.15)); -#144618 = CARTESIAN_POINT('',(3.730766858811,4.15)); -#144619 = CARTESIAN_POINT('',(3.804413634463,4.15)); -#144620 = CARTESIAN_POINT('',(3.878060410116,4.15)); -#144621 = CARTESIAN_POINT('',(3.951707185768,4.15)); -#144622 = CARTESIAN_POINT('',(4.025353961421,4.15)); -#144623 = CARTESIAN_POINT('',(4.099000737074,4.15)); -#144624 = CARTESIAN_POINT('',(4.172647512726,4.15)); -#144625 = CARTESIAN_POINT('',(4.246294288379,4.15)); -#144626 = CARTESIAN_POINT('',(4.319941064031,4.15)); -#144627 = CARTESIAN_POINT('',(4.393587839684,4.15)); -#144628 = CARTESIAN_POINT('',(4.467234615337,4.15)); -#144629 = CARTESIAN_POINT('',(4.540881390989,4.15)); -#144630 = CARTESIAN_POINT('',(4.614528166642,4.15)); -#144631 = CARTESIAN_POINT('',(4.688174942294,4.15)); -#144632 = CARTESIAN_POINT('',(4.737272792729,4.15)); -#144633 = CARTESIAN_POINT('',(4.761821717947,4.15)); -#144634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144635 = PCURVE('',#88010,#144636); -#144636 = DEFINITIONAL_REPRESENTATION('',(#144637),#144641); -#144637 = CIRCLE('',#144638,0.308574064194); -#144638 = AXIS2_PLACEMENT_2D('',#144639,#144640); -#144639 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#144640 = DIRECTION('',(0.E+000,1.)); -#144641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144642 = ADVANCED_FACE('',(#144643),#144507,.F.); -#144643 = FACE_BOUND('',#144644,.F.); -#144644 = EDGE_LOOP('',(#144645,#144646,#144673,#144700)); -#144645 = ORIENTED_EDGE('',*,*,#144493,.T.); -#144646 = ORIENTED_EDGE('',*,*,#144647,.F.); -#144647 = EDGE_CURVE('',#144648,#144418,#144650,.T.); -#144648 = VERTEX_POINT('',#144649); -#144649 = CARTESIAN_POINT('',(4.35,10.51959417205,0.E+000)); -#144650 = SURFACE_CURVE('',#144651,(#144656,#144662),.PCURVE_S1.); -#144651 = CIRCLE('',#144652,0.208574704164); -#144652 = AXIS2_PLACEMENT_3D('',#144653,#144654,#144655); -#144653 = CARTESIAN_POINT('',(4.35,10.728168876214,2.640924866458E-017) - ); -#144654 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144655 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144656 = PCURVE('',#144507,#144657); -#144657 = DEFINITIONAL_REPRESENTATION('',(#144658),#144661); -#144658 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144659,#144660), +#147001 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#147002 = CARTESIAN_POINT('',(3.166141578807,4.15)); +#147003 = CARTESIAN_POINT('',(3.215239429242,4.15)); +#147004 = CARTESIAN_POINT('',(3.288886204895,4.15)); +#147005 = CARTESIAN_POINT('',(3.362532980548,4.15)); +#147006 = CARTESIAN_POINT('',(3.4361797562,4.15)); +#147007 = CARTESIAN_POINT('',(3.509826531853,4.15)); +#147008 = CARTESIAN_POINT('',(3.583473307505,4.15)); +#147009 = CARTESIAN_POINT('',(3.657120083158,4.15)); +#147010 = CARTESIAN_POINT('',(3.730766858811,4.15)); +#147011 = CARTESIAN_POINT('',(3.804413634463,4.15)); +#147012 = CARTESIAN_POINT('',(3.878060410116,4.15)); +#147013 = CARTESIAN_POINT('',(3.951707185768,4.15)); +#147014 = CARTESIAN_POINT('',(4.025353961421,4.15)); +#147015 = CARTESIAN_POINT('',(4.099000737074,4.15)); +#147016 = CARTESIAN_POINT('',(4.172647512726,4.15)); +#147017 = CARTESIAN_POINT('',(4.246294288379,4.15)); +#147018 = CARTESIAN_POINT('',(4.319941064031,4.15)); +#147019 = CARTESIAN_POINT('',(4.393587839684,4.15)); +#147020 = CARTESIAN_POINT('',(4.467234615337,4.15)); +#147021 = CARTESIAN_POINT('',(4.540881390989,4.15)); +#147022 = CARTESIAN_POINT('',(4.614528166642,4.15)); +#147023 = CARTESIAN_POINT('',(4.688174942294,4.15)); +#147024 = CARTESIAN_POINT('',(4.737272792729,4.15)); +#147025 = CARTESIAN_POINT('',(4.761821717947,4.15)); +#147026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147027 = PCURVE('',#90402,#147028); +#147028 = DEFINITIONAL_REPRESENTATION('',(#147029),#147033); +#147029 = CIRCLE('',#147030,0.308574064194); +#147030 = AXIS2_PLACEMENT_2D('',#147031,#147032); +#147031 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#147032 = DIRECTION('',(0.E+000,1.)); +#147033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147034 = ADVANCED_FACE('',(#147035),#146899,.F.); +#147035 = FACE_BOUND('',#147036,.F.); +#147036 = EDGE_LOOP('',(#147037,#147038,#147065,#147092)); +#147037 = ORIENTED_EDGE('',*,*,#146885,.T.); +#147038 = ORIENTED_EDGE('',*,*,#147039,.F.); +#147039 = EDGE_CURVE('',#147040,#146810,#147042,.T.); +#147040 = VERTEX_POINT('',#147041); +#147041 = CARTESIAN_POINT('',(4.35,10.51959417205,0.E+000)); +#147042 = SURFACE_CURVE('',#147043,(#147048,#147054),.PCURVE_S1.); +#147043 = CIRCLE('',#147044,0.208574704164); +#147044 = AXIS2_PLACEMENT_3D('',#147045,#147046,#147047); +#147045 = CARTESIAN_POINT('',(4.35,10.728168876214,2.640924866458E-017) + ); +#147046 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147047 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147048 = PCURVE('',#146899,#147049); +#147049 = DEFINITIONAL_REPRESENTATION('',(#147050),#147053); +#147050 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147051,#147052), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#144659 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#144660 = CARTESIAN_POINT('',(4.772630242227,4.35)); -#144661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147051 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#147052 = CARTESIAN_POINT('',(4.772630242227,4.35)); +#147053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144662 = PCURVE('',#87954,#144663); -#144663 = DEFINITIONAL_REPRESENTATION('',(#144664),#144672); -#144664 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144665,#144666,#144667, - #144668,#144669,#144670,#144671),.UNSPECIFIED.,.T.,.F.) +#147054 = PCURVE('',#90346,#147055); +#147055 = DEFINITIONAL_REPRESENTATION('',(#147056),#147064); +#147056 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147057,#147058,#147059, + #147060,#147061,#147062,#147063),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#144665 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#144666 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#144667 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#144668 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#144669 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#144670 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#144671 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#144672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144673 = ORIENTED_EDGE('',*,*,#144674,.T.); -#144674 = EDGE_CURVE('',#144648,#144675,#144677,.T.); -#144675 = VERTEX_POINT('',#144676); -#144676 = CARTESIAN_POINT('',(4.15,10.51959417205,0.E+000)); -#144677 = SURFACE_CURVE('',#144678,(#144682,#144688),.PCURVE_S1.); -#144678 = LINE('',#144679,#144680); -#144679 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#147057 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#147058 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#147059 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#147060 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#147061 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#147062 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#147063 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#147064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147065 = ORIENTED_EDGE('',*,*,#147066,.T.); +#147066 = EDGE_CURVE('',#147040,#147067,#147069,.T.); +#147067 = VERTEX_POINT('',#147068); +#147068 = CARTESIAN_POINT('',(4.15,10.51959417205,0.E+000)); +#147069 = SURFACE_CURVE('',#147070,(#147074,#147080),.PCURVE_S1.); +#147070 = LINE('',#147071,#147072); +#147071 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#144680 = VECTOR('',#144681,1.); -#144681 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144682 = PCURVE('',#144507,#144683); -#144683 = DEFINITIONAL_REPRESENTATION('',(#144684),#144687); -#144684 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144685,#144686), +#147072 = VECTOR('',#147073,1.); +#147073 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147074 = PCURVE('',#146899,#147075); +#147075 = DEFINITIONAL_REPRESENTATION('',(#147076),#147079); +#147076 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147077,#147078), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#144685 = CARTESIAN_POINT('',(3.14159265359,4.35)); -#144686 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#144687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147077 = CARTESIAN_POINT('',(3.14159265359,4.35)); +#147078 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#147079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#144688 = PCURVE('',#144689,#144694); -#144689 = PLANE('',#144690); -#144690 = AXIS2_PLACEMENT_3D('',#144691,#144692,#144693); -#144691 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#147080 = PCURVE('',#147081,#147086); +#147081 = PLANE('',#147082); +#147082 = AXIS2_PLACEMENT_3D('',#147083,#147084,#147085); +#147083 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#144692 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144693 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144694 = DEFINITIONAL_REPRESENTATION('',(#144695),#144699); -#144695 = LINE('',#144696,#144697); -#144696 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#144697 = VECTOR('',#144698,1.); -#144698 = DIRECTION('',(-1.,0.E+000)); -#144699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144700 = ORIENTED_EDGE('',*,*,#144701,.T.); -#144701 = EDGE_CURVE('',#144675,#144471,#144702,.T.); -#144702 = SURFACE_CURVE('',#144703,(#144708,#144714),.PCURVE_S1.); -#144703 = CIRCLE('',#144704,0.208574704164); -#144704 = AXIS2_PLACEMENT_3D('',#144705,#144706,#144707); -#144705 = CARTESIAN_POINT('',(4.15,10.728168876214,2.640924866458E-017) - ); -#144706 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144707 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#144708 = PCURVE('',#144507,#144709); -#144709 = DEFINITIONAL_REPRESENTATION('',(#144710),#144713); -#144710 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144711,#144712), +#147084 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147085 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147086 = DEFINITIONAL_REPRESENTATION('',(#147087),#147091); +#147087 = LINE('',#147088,#147089); +#147088 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#147089 = VECTOR('',#147090,1.); +#147090 = DIRECTION('',(-1.,0.E+000)); +#147091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147092 = ORIENTED_EDGE('',*,*,#147093,.T.); +#147093 = EDGE_CURVE('',#147067,#146863,#147094,.T.); +#147094 = SURFACE_CURVE('',#147095,(#147100,#147106),.PCURVE_S1.); +#147095 = CIRCLE('',#147096,0.208574704164); +#147096 = AXIS2_PLACEMENT_3D('',#147097,#147098,#147099); +#147097 = CARTESIAN_POINT('',(4.15,10.728168876214,2.640924866458E-017) + ); +#147098 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147099 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147100 = PCURVE('',#146899,#147101); +#147101 = DEFINITIONAL_REPRESENTATION('',(#147102),#147105); +#147102 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147103,#147104), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#144711 = CARTESIAN_POINT('',(3.14159265359,4.15)); -#144712 = CARTESIAN_POINT('',(4.772630242227,4.15)); -#144713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144714 = PCURVE('',#88010,#144715); -#144715 = DEFINITIONAL_REPRESENTATION('',(#144716),#144720); -#144716 = CIRCLE('',#144717,0.208574704164); -#144717 = AXIS2_PLACEMENT_2D('',#144718,#144719); -#144718 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#144719 = DIRECTION('',(0.E+000,1.)); -#144720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144721 = ADVANCED_FACE('',(#144722),#144689,.F.); -#144722 = FACE_BOUND('',#144723,.T.); -#144723 = EDGE_LOOP('',(#144724,#144753,#144774,#144775)); -#144724 = ORIENTED_EDGE('',*,*,#144725,.F.); -#144725 = EDGE_CURVE('',#144726,#144728,#144730,.T.); -#144726 = VERTEX_POINT('',#144727); -#144727 = CARTESIAN_POINT('',(4.35,10.51959417205,0.530776333563)); -#144728 = VERTEX_POINT('',#144729); -#144729 = CARTESIAN_POINT('',(4.15,10.51959417205,0.530776333563)); -#144730 = SURFACE_CURVE('',#144731,(#144735,#144742),.PCURVE_S1.); -#144731 = LINE('',#144732,#144733); -#144732 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#147103 = CARTESIAN_POINT('',(3.14159265359,4.15)); +#147104 = CARTESIAN_POINT('',(4.772630242227,4.15)); +#147105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147106 = PCURVE('',#90402,#147107); +#147107 = DEFINITIONAL_REPRESENTATION('',(#147108),#147112); +#147108 = CIRCLE('',#147109,0.208574704164); +#147109 = AXIS2_PLACEMENT_2D('',#147110,#147111); +#147110 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#147111 = DIRECTION('',(0.E+000,1.)); +#147112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147113 = ADVANCED_FACE('',(#147114),#147081,.F.); +#147114 = FACE_BOUND('',#147115,.T.); +#147115 = EDGE_LOOP('',(#147116,#147145,#147166,#147167)); +#147116 = ORIENTED_EDGE('',*,*,#147117,.F.); +#147117 = EDGE_CURVE('',#147118,#147120,#147122,.T.); +#147118 = VERTEX_POINT('',#147119); +#147119 = CARTESIAN_POINT('',(4.35,10.51959417205,0.530776333563)); +#147120 = VERTEX_POINT('',#147121); +#147121 = CARTESIAN_POINT('',(4.15,10.51959417205,0.530776333563)); +#147122 = SURFACE_CURVE('',#147123,(#147127,#147134),.PCURVE_S1.); +#147123 = LINE('',#147124,#147125); +#147124 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#144733 = VECTOR('',#144734,1.); -#144734 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144735 = PCURVE('',#144689,#144736); -#144736 = DEFINITIONAL_REPRESENTATION('',(#144737),#144741); -#144737 = LINE('',#144738,#144739); -#144738 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144739 = VECTOR('',#144740,1.); -#144740 = DIRECTION('',(-1.,0.E+000)); -#144741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144742 = PCURVE('',#144743,#144748); -#144743 = CYLINDRICAL_SURFACE('',#144744,0.2192697516); -#144744 = AXIS2_PLACEMENT_3D('',#144745,#144746,#144747); -#144745 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#147125 = VECTOR('',#147126,1.); +#147126 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147127 = PCURVE('',#147081,#147128); +#147128 = DEFINITIONAL_REPRESENTATION('',(#147129),#147133); +#147129 = LINE('',#147130,#147131); +#147130 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147131 = VECTOR('',#147132,1.); +#147132 = DIRECTION('',(-1.,0.E+000)); +#147133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147134 = PCURVE('',#147135,#147140); +#147135 = CYLINDRICAL_SURFACE('',#147136,0.2192697516); +#147136 = AXIS2_PLACEMENT_3D('',#147137,#147138,#147139); +#147137 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#144746 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144747 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144748 = DEFINITIONAL_REPRESENTATION('',(#144749),#144752); -#144749 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144750,#144751), +#147138 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147139 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147140 = DEFINITIONAL_REPRESENTATION('',(#147141),#147144); +#147141 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147142,#147143), .UNSPECIFIED.,.F.,.F.,(2,2),(-4.35,-4.15),.PIECEWISE_BEZIER_KNOTS.); -#144750 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#144751 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#144752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144753 = ORIENTED_EDGE('',*,*,#144754,.T.); -#144754 = EDGE_CURVE('',#144726,#144648,#144755,.T.); -#144755 = SURFACE_CURVE('',#144756,(#144760,#144767),.PCURVE_S1.); -#144756 = LINE('',#144757,#144758); -#144757 = CARTESIAN_POINT('',(4.35,10.51959417205,0.530776333563)); -#144758 = VECTOR('',#144759,1.); -#144759 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#144760 = PCURVE('',#144689,#144761); -#144761 = DEFINITIONAL_REPRESENTATION('',(#144762),#144766); -#144762 = LINE('',#144763,#144764); -#144763 = CARTESIAN_POINT('',(4.35,0.E+000)); -#144764 = VECTOR('',#144765,1.); -#144765 = DIRECTION('',(0.E+000,-1.)); -#144766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144767 = PCURVE('',#87954,#144768); -#144768 = DEFINITIONAL_REPRESENTATION('',(#144769),#144773); -#144769 = LINE('',#144770,#144771); -#144770 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#144771 = VECTOR('',#144772,1.); -#144772 = DIRECTION('',(-1.,0.E+000)); -#144773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144774 = ORIENTED_EDGE('',*,*,#144674,.T.); -#144775 = ORIENTED_EDGE('',*,*,#144776,.F.); -#144776 = EDGE_CURVE('',#144728,#144675,#144777,.T.); -#144777 = SURFACE_CURVE('',#144778,(#144782,#144789),.PCURVE_S1.); -#144778 = LINE('',#144779,#144780); -#144779 = CARTESIAN_POINT('',(4.15,10.51959417205,0.530776333563)); -#144780 = VECTOR('',#144781,1.); -#144781 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#144782 = PCURVE('',#144689,#144783); -#144783 = DEFINITIONAL_REPRESENTATION('',(#144784),#144788); -#144784 = LINE('',#144785,#144786); -#144785 = CARTESIAN_POINT('',(4.15,0.E+000)); -#144786 = VECTOR('',#144787,1.); -#144787 = DIRECTION('',(0.E+000,-1.)); -#144788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144789 = PCURVE('',#88010,#144790); -#144790 = DEFINITIONAL_REPRESENTATION('',(#144791),#144795); -#144791 = LINE('',#144792,#144793); -#144792 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#144793 = VECTOR('',#144794,1.); -#144794 = DIRECTION('',(1.,0.E+000)); -#144795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144796 = ADVANCED_FACE('',(#144797),#144587,.F.); -#144797 = FACE_BOUND('',#144798,.T.); -#144798 = EDGE_LOOP('',(#144799,#144828,#144849,#144850)); -#144799 = ORIENTED_EDGE('',*,*,#144800,.F.); -#144800 = EDGE_CURVE('',#144801,#144803,#144805,.T.); -#144801 = VERTEX_POINT('',#144802); -#144802 = CARTESIAN_POINT('',(4.15,10.419594812019,0.530776333563)); -#144803 = VERTEX_POINT('',#144804); -#144804 = CARTESIAN_POINT('',(4.35,10.419594812019,0.530776333563)); -#144805 = SURFACE_CURVE('',#144806,(#144810,#144817),.PCURVE_S1.); -#144806 = LINE('',#144807,#144808); -#144807 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#147142 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#147143 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#147144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147145 = ORIENTED_EDGE('',*,*,#147146,.T.); +#147146 = EDGE_CURVE('',#147118,#147040,#147147,.T.); +#147147 = SURFACE_CURVE('',#147148,(#147152,#147159),.PCURVE_S1.); +#147148 = LINE('',#147149,#147150); +#147149 = CARTESIAN_POINT('',(4.35,10.51959417205,0.530776333563)); +#147150 = VECTOR('',#147151,1.); +#147151 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#147152 = PCURVE('',#147081,#147153); +#147153 = DEFINITIONAL_REPRESENTATION('',(#147154),#147158); +#147154 = LINE('',#147155,#147156); +#147155 = CARTESIAN_POINT('',(4.35,0.E+000)); +#147156 = VECTOR('',#147157,1.); +#147157 = DIRECTION('',(0.E+000,-1.)); +#147158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147159 = PCURVE('',#90346,#147160); +#147160 = DEFINITIONAL_REPRESENTATION('',(#147161),#147165); +#147161 = LINE('',#147162,#147163); +#147162 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#147163 = VECTOR('',#147164,1.); +#147164 = DIRECTION('',(-1.,0.E+000)); +#147165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147166 = ORIENTED_EDGE('',*,*,#147066,.T.); +#147167 = ORIENTED_EDGE('',*,*,#147168,.F.); +#147168 = EDGE_CURVE('',#147120,#147067,#147169,.T.); +#147169 = SURFACE_CURVE('',#147170,(#147174,#147181),.PCURVE_S1.); +#147170 = LINE('',#147171,#147172); +#147171 = CARTESIAN_POINT('',(4.15,10.51959417205,0.530776333563)); +#147172 = VECTOR('',#147173,1.); +#147173 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#147174 = PCURVE('',#147081,#147175); +#147175 = DEFINITIONAL_REPRESENTATION('',(#147176),#147180); +#147176 = LINE('',#147177,#147178); +#147177 = CARTESIAN_POINT('',(4.15,0.E+000)); +#147178 = VECTOR('',#147179,1.); +#147179 = DIRECTION('',(0.E+000,-1.)); +#147180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147181 = PCURVE('',#90402,#147182); +#147182 = DEFINITIONAL_REPRESENTATION('',(#147183),#147187); +#147183 = LINE('',#147184,#147185); +#147184 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#147185 = VECTOR('',#147186,1.); +#147186 = DIRECTION('',(1.,0.E+000)); +#147187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147188 = ADVANCED_FACE('',(#147189),#146979,.F.); +#147189 = FACE_BOUND('',#147190,.T.); +#147190 = EDGE_LOOP('',(#147191,#147220,#147241,#147242)); +#147191 = ORIENTED_EDGE('',*,*,#147192,.F.); +#147192 = EDGE_CURVE('',#147193,#147195,#147197,.T.); +#147193 = VERTEX_POINT('',#147194); +#147194 = CARTESIAN_POINT('',(4.15,10.419594812019,0.530776333563)); +#147195 = VERTEX_POINT('',#147196); +#147196 = CARTESIAN_POINT('',(4.35,10.419594812019,0.530776333563)); +#147197 = SURFACE_CURVE('',#147198,(#147202,#147209),.PCURVE_S1.); +#147198 = LINE('',#147199,#147200); +#147199 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#144808 = VECTOR('',#144809,1.); -#144809 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144810 = PCURVE('',#144587,#144811); -#144811 = DEFINITIONAL_REPRESENTATION('',(#144812),#144816); -#144812 = LINE('',#144813,#144814); -#144813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#144814 = VECTOR('',#144815,1.); -#144815 = DIRECTION('',(-1.,0.E+000)); -#144816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144817 = PCURVE('',#144818,#144823); -#144818 = CYLINDRICAL_SURFACE('',#144819,0.119270391569); -#144819 = AXIS2_PLACEMENT_3D('',#144820,#144821,#144822); -#144820 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#147200 = VECTOR('',#147201,1.); +#147201 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147202 = PCURVE('',#146979,#147203); +#147203 = DEFINITIONAL_REPRESENTATION('',(#147204),#147208); +#147204 = LINE('',#147205,#147206); +#147205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147206 = VECTOR('',#147207,1.); +#147207 = DIRECTION('',(-1.,0.E+000)); +#147208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147209 = PCURVE('',#147210,#147215); +#147210 = CYLINDRICAL_SURFACE('',#147211,0.119270391569); +#147211 = AXIS2_PLACEMENT_3D('',#147212,#147213,#147214); +#147212 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#144821 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144822 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144823 = DEFINITIONAL_REPRESENTATION('',(#144824),#144827); -#144824 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144825,#144826), +#147213 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147214 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147215 = DEFINITIONAL_REPRESENTATION('',(#147216),#147219); +#147216 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147217,#147218), .UNSPECIFIED.,.F.,.F.,(2,2),(4.15,4.35),.PIECEWISE_BEZIER_KNOTS.); -#144825 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#144826 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#144827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144828 = ORIENTED_EDGE('',*,*,#144829,.T.); -#144829 = EDGE_CURVE('',#144801,#144573,#144830,.T.); -#144830 = SURFACE_CURVE('',#144831,(#144835,#144842),.PCURVE_S1.); -#144831 = LINE('',#144832,#144833); -#144832 = CARTESIAN_POINT('',(4.15,10.419594812019,0.530776333563)); -#144833 = VECTOR('',#144834,1.); -#144834 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#144835 = PCURVE('',#144587,#144836); -#144836 = DEFINITIONAL_REPRESENTATION('',(#144837),#144841); -#144837 = LINE('',#144838,#144839); -#144838 = CARTESIAN_POINT('',(-4.15,0.E+000)); -#144839 = VECTOR('',#144840,1.); -#144840 = DIRECTION('',(0.E+000,-1.)); -#144841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144842 = PCURVE('',#88010,#144843); -#144843 = DEFINITIONAL_REPRESENTATION('',(#144844),#144848); -#144844 = LINE('',#144845,#144846); -#144845 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#144846 = VECTOR('',#144847,1.); -#144847 = DIRECTION('',(1.,0.E+000)); -#144848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144849 = ORIENTED_EDGE('',*,*,#144572,.T.); -#144850 = ORIENTED_EDGE('',*,*,#144851,.F.); -#144851 = EDGE_CURVE('',#144803,#144523,#144852,.T.); -#144852 = SURFACE_CURVE('',#144853,(#144857,#144864),.PCURVE_S1.); -#144853 = LINE('',#144854,#144855); -#144854 = CARTESIAN_POINT('',(4.35,10.419594812019,0.530776333563)); -#144855 = VECTOR('',#144856,1.); -#144856 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#144857 = PCURVE('',#144587,#144858); -#144858 = DEFINITIONAL_REPRESENTATION('',(#144859),#144863); -#144859 = LINE('',#144860,#144861); -#144860 = CARTESIAN_POINT('',(-4.35,0.E+000)); -#144861 = VECTOR('',#144862,1.); -#144862 = DIRECTION('',(0.E+000,-1.)); -#144863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144864 = PCURVE('',#87954,#144865); -#144865 = DEFINITIONAL_REPRESENTATION('',(#144866),#144870); -#144866 = LINE('',#144867,#144868); -#144867 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#144868 = VECTOR('',#144869,1.); -#144869 = DIRECTION('',(-1.,0.E+000)); -#144870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144871 = ADVANCED_FACE('',(#144872),#144743,.T.); -#144872 = FACE_BOUND('',#144873,.T.); -#144873 = EDGE_LOOP('',(#144874,#144920,#144921,#144971)); -#144874 = ORIENTED_EDGE('',*,*,#144875,.T.); -#144875 = EDGE_CURVE('',#144876,#144726,#144878,.T.); -#144876 = VERTEX_POINT('',#144877); -#144877 = CARTESIAN_POINT('',(4.35,10.304819755875,0.75)); -#144878 = SURFACE_CURVE('',#144879,(#144884,#144913),.PCURVE_S1.); -#144879 = CIRCLE('',#144880,0.2192697516); -#144880 = AXIS2_PLACEMENT_3D('',#144881,#144882,#144883); -#144881 = CARTESIAN_POINT('',(4.35,10.30032442045,0.530776333563)); -#144882 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144883 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144884 = PCURVE('',#144743,#144885); -#144885 = DEFINITIONAL_REPRESENTATION('',(#144886),#144912); -#144886 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144887,#144888,#144889, - #144890,#144891,#144892,#144893,#144894,#144895,#144896,#144897, - #144898,#144899,#144900,#144901,#144902,#144903,#144904,#144905, - #144906,#144907,#144908,#144909,#144910,#144911),.UNSPECIFIED.,.F., +#147217 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#147218 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#147219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147220 = ORIENTED_EDGE('',*,*,#147221,.T.); +#147221 = EDGE_CURVE('',#147193,#146965,#147222,.T.); +#147222 = SURFACE_CURVE('',#147223,(#147227,#147234),.PCURVE_S1.); +#147223 = LINE('',#147224,#147225); +#147224 = CARTESIAN_POINT('',(4.15,10.419594812019,0.530776333563)); +#147225 = VECTOR('',#147226,1.); +#147226 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#147227 = PCURVE('',#146979,#147228); +#147228 = DEFINITIONAL_REPRESENTATION('',(#147229),#147233); +#147229 = LINE('',#147230,#147231); +#147230 = CARTESIAN_POINT('',(-4.15,0.E+000)); +#147231 = VECTOR('',#147232,1.); +#147232 = DIRECTION('',(0.E+000,-1.)); +#147233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147234 = PCURVE('',#90402,#147235); +#147235 = DEFINITIONAL_REPRESENTATION('',(#147236),#147240); +#147236 = LINE('',#147237,#147238); +#147237 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#147238 = VECTOR('',#147239,1.); +#147239 = DIRECTION('',(1.,0.E+000)); +#147240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147241 = ORIENTED_EDGE('',*,*,#146964,.T.); +#147242 = ORIENTED_EDGE('',*,*,#147243,.F.); +#147243 = EDGE_CURVE('',#147195,#146915,#147244,.T.); +#147244 = SURFACE_CURVE('',#147245,(#147249,#147256),.PCURVE_S1.); +#147245 = LINE('',#147246,#147247); +#147246 = CARTESIAN_POINT('',(4.35,10.419594812019,0.530776333563)); +#147247 = VECTOR('',#147248,1.); +#147248 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#147249 = PCURVE('',#146979,#147250); +#147250 = DEFINITIONAL_REPRESENTATION('',(#147251),#147255); +#147251 = LINE('',#147252,#147253); +#147252 = CARTESIAN_POINT('',(-4.35,0.E+000)); +#147253 = VECTOR('',#147254,1.); +#147254 = DIRECTION('',(0.E+000,-1.)); +#147255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147256 = PCURVE('',#90346,#147257); +#147257 = DEFINITIONAL_REPRESENTATION('',(#147258),#147262); +#147258 = LINE('',#147259,#147260); +#147259 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#147260 = VECTOR('',#147261,1.); +#147261 = DIRECTION('',(-1.,0.E+000)); +#147262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147263 = ADVANCED_FACE('',(#147264),#147135,.T.); +#147264 = FACE_BOUND('',#147265,.T.); +#147265 = EDGE_LOOP('',(#147266,#147312,#147313,#147363)); +#147266 = ORIENTED_EDGE('',*,*,#147267,.T.); +#147267 = EDGE_CURVE('',#147268,#147118,#147270,.T.); +#147268 = VERTEX_POINT('',#147269); +#147269 = CARTESIAN_POINT('',(4.35,10.304819755875,0.75)); +#147270 = SURFACE_CURVE('',#147271,(#147276,#147305),.PCURVE_S1.); +#147271 = CIRCLE('',#147272,0.2192697516); +#147272 = AXIS2_PLACEMENT_3D('',#147273,#147274,#147275); +#147273 = CARTESIAN_POINT('',(4.35,10.30032442045,0.530776333563)); +#147274 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147275 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147276 = PCURVE('',#147135,#147277); +#147277 = DEFINITIONAL_REPRESENTATION('',(#147278),#147304); +#147278 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147279,#147280,#147281, + #147282,#147283,#147284,#147285,#147286,#147287,#147288,#147289, + #147290,#147291,#147292,#147293,#147294,#147295,#147296,#147297, + #147298,#147299,#147300,#147301,#147302,#147303),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -178653,60 +181655,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#144887 = CARTESIAN_POINT('',(1.591299156552,-4.35)); -#144888 = CARTESIAN_POINT('',(1.614788451962,-4.35)); -#144889 = CARTESIAN_POINT('',(1.661767042781,-4.35)); -#144890 = CARTESIAN_POINT('',(1.73223492901,-4.35)); -#144891 = CARTESIAN_POINT('',(1.802702815239,-4.35)); -#144892 = CARTESIAN_POINT('',(1.873170701468,-4.35)); -#144893 = CARTESIAN_POINT('',(1.943638587697,-4.35)); -#144894 = CARTESIAN_POINT('',(2.014106473926,-4.35)); -#144895 = CARTESIAN_POINT('',(2.084574360155,-4.35)); -#144896 = CARTESIAN_POINT('',(2.155042246384,-4.35)); -#144897 = CARTESIAN_POINT('',(2.225510132613,-4.35)); -#144898 = CARTESIAN_POINT('',(2.295978018842,-4.35)); -#144899 = CARTESIAN_POINT('',(2.366445905071,-4.35)); -#144900 = CARTESIAN_POINT('',(2.4369137913,-4.35)); -#144901 = CARTESIAN_POINT('',(2.507381677529,-4.35)); -#144902 = CARTESIAN_POINT('',(2.577849563758,-4.35)); -#144903 = CARTESIAN_POINT('',(2.648317449987,-4.35)); -#144904 = CARTESIAN_POINT('',(2.718785336216,-4.35)); -#144905 = CARTESIAN_POINT('',(2.789253222445,-4.35)); -#144906 = CARTESIAN_POINT('',(2.859721108674,-4.35)); -#144907 = CARTESIAN_POINT('',(2.930188994903,-4.35)); -#144908 = CARTESIAN_POINT('',(3.000656881132,-4.35)); -#144909 = CARTESIAN_POINT('',(3.071124767361,-4.35)); -#144910 = CARTESIAN_POINT('',(3.11810335818,-4.35)); -#144911 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#144912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144913 = PCURVE('',#87954,#144914); -#144914 = DEFINITIONAL_REPRESENTATION('',(#144915),#144919); -#144915 = CIRCLE('',#144916,0.2192697516); -#144916 = AXIS2_PLACEMENT_2D('',#144917,#144918); -#144917 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#144918 = DIRECTION('',(0.E+000,-1.)); -#144919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144920 = ORIENTED_EDGE('',*,*,#144725,.T.); -#144921 = ORIENTED_EDGE('',*,*,#144922,.F.); -#144922 = EDGE_CURVE('',#144923,#144728,#144925,.T.); -#144923 = VERTEX_POINT('',#144924); -#144924 = CARTESIAN_POINT('',(4.15,10.304819755875,0.75)); -#144925 = SURFACE_CURVE('',#144926,(#144931,#144960),.PCURVE_S1.); -#144926 = CIRCLE('',#144927,0.2192697516); -#144927 = AXIS2_PLACEMENT_3D('',#144928,#144929,#144930); -#144928 = CARTESIAN_POINT('',(4.15,10.30032442045,0.530776333563)); -#144929 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#144930 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#144931 = PCURVE('',#144743,#144932); -#144932 = DEFINITIONAL_REPRESENTATION('',(#144933),#144959); -#144933 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#144934,#144935,#144936, - #144937,#144938,#144939,#144940,#144941,#144942,#144943,#144944, - #144945,#144946,#144947,#144948,#144949,#144950,#144951,#144952, - #144953,#144954,#144955,#144956,#144957,#144958),.UNSPECIFIED.,.F., +#147279 = CARTESIAN_POINT('',(1.591299156552,-4.35)); +#147280 = CARTESIAN_POINT('',(1.614788451962,-4.35)); +#147281 = CARTESIAN_POINT('',(1.661767042781,-4.35)); +#147282 = CARTESIAN_POINT('',(1.73223492901,-4.35)); +#147283 = CARTESIAN_POINT('',(1.802702815239,-4.35)); +#147284 = CARTESIAN_POINT('',(1.873170701468,-4.35)); +#147285 = CARTESIAN_POINT('',(1.943638587697,-4.35)); +#147286 = CARTESIAN_POINT('',(2.014106473926,-4.35)); +#147287 = CARTESIAN_POINT('',(2.084574360155,-4.35)); +#147288 = CARTESIAN_POINT('',(2.155042246384,-4.35)); +#147289 = CARTESIAN_POINT('',(2.225510132613,-4.35)); +#147290 = CARTESIAN_POINT('',(2.295978018842,-4.35)); +#147291 = CARTESIAN_POINT('',(2.366445905071,-4.35)); +#147292 = CARTESIAN_POINT('',(2.4369137913,-4.35)); +#147293 = CARTESIAN_POINT('',(2.507381677529,-4.35)); +#147294 = CARTESIAN_POINT('',(2.577849563758,-4.35)); +#147295 = CARTESIAN_POINT('',(2.648317449987,-4.35)); +#147296 = CARTESIAN_POINT('',(2.718785336216,-4.35)); +#147297 = CARTESIAN_POINT('',(2.789253222445,-4.35)); +#147298 = CARTESIAN_POINT('',(2.859721108674,-4.35)); +#147299 = CARTESIAN_POINT('',(2.930188994903,-4.35)); +#147300 = CARTESIAN_POINT('',(3.000656881132,-4.35)); +#147301 = CARTESIAN_POINT('',(3.071124767361,-4.35)); +#147302 = CARTESIAN_POINT('',(3.11810335818,-4.35)); +#147303 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#147304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147305 = PCURVE('',#90346,#147306); +#147306 = DEFINITIONAL_REPRESENTATION('',(#147307),#147311); +#147307 = CIRCLE('',#147308,0.2192697516); +#147308 = AXIS2_PLACEMENT_2D('',#147309,#147310); +#147309 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#147310 = DIRECTION('',(0.E+000,-1.)); +#147311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147312 = ORIENTED_EDGE('',*,*,#147117,.T.); +#147313 = ORIENTED_EDGE('',*,*,#147314,.F.); +#147314 = EDGE_CURVE('',#147315,#147120,#147317,.T.); +#147315 = VERTEX_POINT('',#147316); +#147316 = CARTESIAN_POINT('',(4.15,10.304819755875,0.75)); +#147317 = SURFACE_CURVE('',#147318,(#147323,#147352),.PCURVE_S1.); +#147318 = CIRCLE('',#147319,0.2192697516); +#147319 = AXIS2_PLACEMENT_3D('',#147320,#147321,#147322); +#147320 = CARTESIAN_POINT('',(4.15,10.30032442045,0.530776333563)); +#147321 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147322 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147323 = PCURVE('',#147135,#147324); +#147324 = DEFINITIONAL_REPRESENTATION('',(#147325),#147351); +#147325 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147326,#147327,#147328, + #147329,#147330,#147331,#147332,#147333,#147334,#147335,#147336, + #147337,#147338,#147339,#147340,#147341,#147342,#147343,#147344, + #147345,#147346,#147347,#147348,#147349,#147350),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -178714,646 +181716,646 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#144934 = CARTESIAN_POINT('',(1.591299156552,-4.15)); -#144935 = CARTESIAN_POINT('',(1.614788451962,-4.15)); -#144936 = CARTESIAN_POINT('',(1.661767042781,-4.15)); -#144937 = CARTESIAN_POINT('',(1.73223492901,-4.15)); -#144938 = CARTESIAN_POINT('',(1.802702815239,-4.15)); -#144939 = CARTESIAN_POINT('',(1.873170701468,-4.15)); -#144940 = CARTESIAN_POINT('',(1.943638587697,-4.15)); -#144941 = CARTESIAN_POINT('',(2.014106473926,-4.15)); -#144942 = CARTESIAN_POINT('',(2.084574360155,-4.15)); -#144943 = CARTESIAN_POINT('',(2.155042246384,-4.15)); -#144944 = CARTESIAN_POINT('',(2.225510132613,-4.15)); -#144945 = CARTESIAN_POINT('',(2.295978018842,-4.15)); -#144946 = CARTESIAN_POINT('',(2.366445905071,-4.15)); -#144947 = CARTESIAN_POINT('',(2.4369137913,-4.15)); -#144948 = CARTESIAN_POINT('',(2.507381677529,-4.15)); -#144949 = CARTESIAN_POINT('',(2.577849563758,-4.15)); -#144950 = CARTESIAN_POINT('',(2.648317449987,-4.15)); -#144951 = CARTESIAN_POINT('',(2.718785336216,-4.15)); -#144952 = CARTESIAN_POINT('',(2.789253222445,-4.15)); -#144953 = CARTESIAN_POINT('',(2.859721108674,-4.15)); -#144954 = CARTESIAN_POINT('',(2.930188994903,-4.15)); -#144955 = CARTESIAN_POINT('',(3.000656881132,-4.15)); -#144956 = CARTESIAN_POINT('',(3.071124767361,-4.15)); -#144957 = CARTESIAN_POINT('',(3.11810335818,-4.15)); -#144958 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#144959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144960 = PCURVE('',#88010,#144961); -#144961 = DEFINITIONAL_REPRESENTATION('',(#144962),#144970); -#144962 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#144963,#144964,#144965, - #144966,#144967,#144968,#144969),.UNSPECIFIED.,.T.,.F.) +#147326 = CARTESIAN_POINT('',(1.591299156552,-4.15)); +#147327 = CARTESIAN_POINT('',(1.614788451962,-4.15)); +#147328 = CARTESIAN_POINT('',(1.661767042781,-4.15)); +#147329 = CARTESIAN_POINT('',(1.73223492901,-4.15)); +#147330 = CARTESIAN_POINT('',(1.802702815239,-4.15)); +#147331 = CARTESIAN_POINT('',(1.873170701468,-4.15)); +#147332 = CARTESIAN_POINT('',(1.943638587697,-4.15)); +#147333 = CARTESIAN_POINT('',(2.014106473926,-4.15)); +#147334 = CARTESIAN_POINT('',(2.084574360155,-4.15)); +#147335 = CARTESIAN_POINT('',(2.155042246384,-4.15)); +#147336 = CARTESIAN_POINT('',(2.225510132613,-4.15)); +#147337 = CARTESIAN_POINT('',(2.295978018842,-4.15)); +#147338 = CARTESIAN_POINT('',(2.366445905071,-4.15)); +#147339 = CARTESIAN_POINT('',(2.4369137913,-4.15)); +#147340 = CARTESIAN_POINT('',(2.507381677529,-4.15)); +#147341 = CARTESIAN_POINT('',(2.577849563758,-4.15)); +#147342 = CARTESIAN_POINT('',(2.648317449987,-4.15)); +#147343 = CARTESIAN_POINT('',(2.718785336216,-4.15)); +#147344 = CARTESIAN_POINT('',(2.789253222445,-4.15)); +#147345 = CARTESIAN_POINT('',(2.859721108674,-4.15)); +#147346 = CARTESIAN_POINT('',(2.930188994903,-4.15)); +#147347 = CARTESIAN_POINT('',(3.000656881132,-4.15)); +#147348 = CARTESIAN_POINT('',(3.071124767361,-4.15)); +#147349 = CARTESIAN_POINT('',(3.11810335818,-4.15)); +#147350 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#147351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147352 = PCURVE('',#90402,#147353); +#147353 = DEFINITIONAL_REPRESENTATION('',(#147354),#147362); +#147354 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147355,#147356,#147357, + #147358,#147359,#147360,#147361),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#144963 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#144964 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#144965 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#144966 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#144967 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#144968 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#144969 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#144970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144971 = ORIENTED_EDGE('',*,*,#144972,.T.); -#144972 = EDGE_CURVE('',#144923,#144876,#144973,.T.); -#144973 = SURFACE_CURVE('',#144974,(#144978,#144984),.PCURVE_S1.); -#144974 = LINE('',#144975,#144976); -#144975 = CARTESIAN_POINT('',(4.35,10.304819755875,0.75)); -#144976 = VECTOR('',#144977,1.); -#144977 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#144978 = PCURVE('',#144743,#144979); -#144979 = DEFINITIONAL_REPRESENTATION('',(#144980),#144983); -#144980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#144981,#144982), +#147355 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#147356 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#147357 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#147358 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#147359 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#147360 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#147361 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#147362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147363 = ORIENTED_EDGE('',*,*,#147364,.T.); +#147364 = EDGE_CURVE('',#147315,#147268,#147365,.T.); +#147365 = SURFACE_CURVE('',#147366,(#147370,#147376),.PCURVE_S1.); +#147366 = LINE('',#147367,#147368); +#147367 = CARTESIAN_POINT('',(4.35,10.304819755875,0.75)); +#147368 = VECTOR('',#147369,1.); +#147369 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147370 = PCURVE('',#147135,#147371); +#147371 = DEFINITIONAL_REPRESENTATION('',(#147372),#147375); +#147372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147373,#147374), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#144981 = CARTESIAN_POINT('',(1.591299156552,-4.15)); -#144982 = CARTESIAN_POINT('',(1.591299156552,-4.35)); -#144983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144984 = PCURVE('',#87982,#144985); -#144985 = DEFINITIONAL_REPRESENTATION('',(#144986),#144990); -#144986 = LINE('',#144987,#144988); -#144987 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#144988 = VECTOR('',#144989,1.); -#144989 = DIRECTION('',(-8.881784197001E-016,1.)); -#144990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#144991 = ADVANCED_FACE('',(#144992),#144818,.F.); -#144992 = FACE_BOUND('',#144993,.F.); -#144993 = EDGE_LOOP('',(#144994,#145021,#145043,#145064)); -#144994 = ORIENTED_EDGE('',*,*,#144995,.F.); -#144995 = EDGE_CURVE('',#144996,#144801,#144998,.T.); -#144996 = VERTEX_POINT('',#144997); -#144997 = CARTESIAN_POINT('',(4.15,10.303662633502,0.65)); -#144998 = SURFACE_CURVE('',#144999,(#145004,#145010),.PCURVE_S1.); -#144999 = CIRCLE('',#145000,0.119270391569); -#145000 = AXIS2_PLACEMENT_3D('',#145001,#145002,#145003); -#145001 = CARTESIAN_POINT('',(4.15,10.30032442045,0.530776333563)); -#145002 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145003 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145004 = PCURVE('',#144818,#145005); -#145005 = DEFINITIONAL_REPRESENTATION('',(#145006),#145009); -#145006 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145007,#145008), +#147373 = CARTESIAN_POINT('',(1.591299156552,-4.15)); +#147374 = CARTESIAN_POINT('',(1.591299156552,-4.35)); +#147375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147376 = PCURVE('',#90374,#147377); +#147377 = DEFINITIONAL_REPRESENTATION('',(#147378),#147382); +#147378 = LINE('',#147379,#147380); +#147379 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#147380 = VECTOR('',#147381,1.); +#147381 = DIRECTION('',(-8.881784197001E-016,1.)); +#147382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147383 = ADVANCED_FACE('',(#147384),#147210,.F.); +#147384 = FACE_BOUND('',#147385,.F.); +#147385 = EDGE_LOOP('',(#147386,#147413,#147435,#147456)); +#147386 = ORIENTED_EDGE('',*,*,#147387,.F.); +#147387 = EDGE_CURVE('',#147388,#147193,#147390,.T.); +#147388 = VERTEX_POINT('',#147389); +#147389 = CARTESIAN_POINT('',(4.15,10.303662633502,0.65)); +#147390 = SURFACE_CURVE('',#147391,(#147396,#147402),.PCURVE_S1.); +#147391 = CIRCLE('',#147392,0.119270391569); +#147392 = AXIS2_PLACEMENT_3D('',#147393,#147394,#147395); +#147393 = CARTESIAN_POINT('',(4.15,10.30032442045,0.530776333563)); +#147394 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147395 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147396 = PCURVE('',#147210,#147397); +#147397 = DEFINITIONAL_REPRESENTATION('',(#147398),#147401); +#147398 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147399,#147400), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145007 = CARTESIAN_POINT('',(1.598788597134,-4.15)); -#145008 = CARTESIAN_POINT('',(3.14159265359,-4.15)); -#145009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147399 = CARTESIAN_POINT('',(1.598788597134,-4.15)); +#147400 = CARTESIAN_POINT('',(3.14159265359,-4.15)); +#147401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145010 = PCURVE('',#88010,#145011); -#145011 = DEFINITIONAL_REPRESENTATION('',(#145012),#145020); -#145012 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145013,#145014,#145015, - #145016,#145017,#145018,#145019),.UNSPECIFIED.,.T.,.F.) +#147402 = PCURVE('',#90402,#147403); +#147403 = DEFINITIONAL_REPRESENTATION('',(#147404),#147412); +#147404 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147405,#147406,#147407, + #147408,#147409,#147410,#147411),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#145013 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#145014 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#145015 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#145016 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#145017 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#145018 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#145019 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#145020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145021 = ORIENTED_EDGE('',*,*,#145022,.F.); -#145022 = EDGE_CURVE('',#145023,#144996,#145025,.T.); -#145023 = VERTEX_POINT('',#145024); -#145024 = CARTESIAN_POINT('',(4.35,10.303662633502,0.65)); -#145025 = SURFACE_CURVE('',#145026,(#145030,#145036),.PCURVE_S1.); -#145026 = LINE('',#145027,#145028); -#145027 = CARTESIAN_POINT('',(4.35,10.303662633502,0.65)); -#145028 = VECTOR('',#145029,1.); -#145029 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145030 = PCURVE('',#144818,#145031); -#145031 = DEFINITIONAL_REPRESENTATION('',(#145032),#145035); -#145032 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145033,#145034), +#147405 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#147406 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#147407 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#147408 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#147409 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#147410 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#147411 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#147412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147413 = ORIENTED_EDGE('',*,*,#147414,.F.); +#147414 = EDGE_CURVE('',#147415,#147388,#147417,.T.); +#147415 = VERTEX_POINT('',#147416); +#147416 = CARTESIAN_POINT('',(4.35,10.303662633502,0.65)); +#147417 = SURFACE_CURVE('',#147418,(#147422,#147428),.PCURVE_S1.); +#147418 = LINE('',#147419,#147420); +#147419 = CARTESIAN_POINT('',(4.35,10.303662633502,0.65)); +#147420 = VECTOR('',#147421,1.); +#147421 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147422 = PCURVE('',#147210,#147423); +#147423 = DEFINITIONAL_REPRESENTATION('',(#147424),#147427); +#147424 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147425,#147426), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#145033 = CARTESIAN_POINT('',(1.598788597134,-4.35)); -#145034 = CARTESIAN_POINT('',(1.598788597134,-4.15)); -#145035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145036 = PCURVE('',#88036,#145037); -#145037 = DEFINITIONAL_REPRESENTATION('',(#145038),#145042); -#145038 = LINE('',#145039,#145040); -#145039 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#145040 = VECTOR('',#145041,1.); -#145041 = DIRECTION('',(-8.881784197001E-016,-1.)); -#145042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145043 = ORIENTED_EDGE('',*,*,#145044,.T.); -#145044 = EDGE_CURVE('',#145023,#144803,#145045,.T.); -#145045 = SURFACE_CURVE('',#145046,(#145051,#145057),.PCURVE_S1.); -#145046 = CIRCLE('',#145047,0.119270391569); -#145047 = AXIS2_PLACEMENT_3D('',#145048,#145049,#145050); -#145048 = CARTESIAN_POINT('',(4.35,10.30032442045,0.530776333563)); -#145049 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145050 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145051 = PCURVE('',#144818,#145052); -#145052 = DEFINITIONAL_REPRESENTATION('',(#145053),#145056); -#145053 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145054,#145055), +#147425 = CARTESIAN_POINT('',(1.598788597134,-4.35)); +#147426 = CARTESIAN_POINT('',(1.598788597134,-4.15)); +#147427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147428 = PCURVE('',#90428,#147429); +#147429 = DEFINITIONAL_REPRESENTATION('',(#147430),#147434); +#147430 = LINE('',#147431,#147432); +#147431 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#147432 = VECTOR('',#147433,1.); +#147433 = DIRECTION('',(-8.881784197001E-016,-1.)); +#147434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147435 = ORIENTED_EDGE('',*,*,#147436,.T.); +#147436 = EDGE_CURVE('',#147415,#147195,#147437,.T.); +#147437 = SURFACE_CURVE('',#147438,(#147443,#147449),.PCURVE_S1.); +#147438 = CIRCLE('',#147439,0.119270391569); +#147439 = AXIS2_PLACEMENT_3D('',#147440,#147441,#147442); +#147440 = CARTESIAN_POINT('',(4.35,10.30032442045,0.530776333563)); +#147441 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147442 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#147443 = PCURVE('',#147210,#147444); +#147444 = DEFINITIONAL_REPRESENTATION('',(#147445),#147448); +#147445 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147446,#147447), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145054 = CARTESIAN_POINT('',(1.598788597134,-4.35)); -#145055 = CARTESIAN_POINT('',(3.14159265359,-4.35)); -#145056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145057 = PCURVE('',#87954,#145058); -#145058 = DEFINITIONAL_REPRESENTATION('',(#145059),#145063); -#145059 = CIRCLE('',#145060,0.119270391569); -#145060 = AXIS2_PLACEMENT_2D('',#145061,#145062); -#145061 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#145062 = DIRECTION('',(0.E+000,-1.)); -#145063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145064 = ORIENTED_EDGE('',*,*,#144800,.F.); -#145065 = ADVANCED_FACE('',(#145066),#87954,.F.); -#145066 = FACE_BOUND('',#145067,.T.); -#145067 = EDGE_LOOP('',(#145068,#145089,#145090,#145091,#145092,#145093, - #145114,#145115,#145116,#145117,#145118,#145139)); -#145068 = ORIENTED_EDGE('',*,*,#145069,.F.); -#145069 = EDGE_CURVE('',#145023,#87939,#145070,.T.); -#145070 = SURFACE_CURVE('',#145071,(#145075,#145082),.PCURVE_S1.); -#145071 = LINE('',#145072,#145073); -#145072 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); -#145073 = VECTOR('',#145074,1.); -#145074 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#145075 = PCURVE('',#87954,#145076); -#145076 = DEFINITIONAL_REPRESENTATION('',(#145077),#145081); -#145077 = LINE('',#145078,#145079); -#145078 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145079 = VECTOR('',#145080,1.); -#145080 = DIRECTION('',(3.563627120235E-016,-1.)); -#145081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145082 = PCURVE('',#88036,#145083); -#145083 = DEFINITIONAL_REPRESENTATION('',(#145084),#145088); -#145084 = LINE('',#145085,#145086); -#145085 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145086 = VECTOR('',#145087,1.); -#145087 = DIRECTION('',(1.,2.164989446033E-063)); -#145088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145089 = ORIENTED_EDGE('',*,*,#145044,.T.); -#145090 = ORIENTED_EDGE('',*,*,#144851,.T.); -#145091 = ORIENTED_EDGE('',*,*,#144522,.T.); -#145092 = ORIENTED_EDGE('',*,*,#144366,.T.); -#145093 = ORIENTED_EDGE('',*,*,#145094,.T.); -#145094 = EDGE_CURVE('',#144339,#144420,#145095,.T.); -#145095 = SURFACE_CURVE('',#145096,(#145100,#145107),.PCURVE_S1.); -#145096 = LINE('',#145097,#145098); -#145097 = CARTESIAN_POINT('',(4.35,11.,1.159810404338E-002)); -#145098 = VECTOR('',#145099,1.); -#145099 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#145100 = PCURVE('',#87954,#145101); -#145101 = DEFINITIONAL_REPRESENTATION('',(#145102),#145106); -#145102 = LINE('',#145103,#145104); -#145103 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#145104 = VECTOR('',#145105,1.); -#145105 = DIRECTION('',(1.,2.101748079665E-016)); -#145106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145107 = PCURVE('',#144354,#145108); -#145108 = DEFINITIONAL_REPRESENTATION('',(#145109),#145113); -#145109 = LINE('',#145110,#145111); -#145110 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#145111 = VECTOR('',#145112,1.); -#145112 = DIRECTION('',(-1.570395187386E-016,1.)); -#145113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145114 = ORIENTED_EDGE('',*,*,#144417,.F.); -#145115 = ORIENTED_EDGE('',*,*,#144647,.F.); -#145116 = ORIENTED_EDGE('',*,*,#144754,.F.); -#145117 = ORIENTED_EDGE('',*,*,#144875,.F.); -#145118 = ORIENTED_EDGE('',*,*,#145119,.T.); -#145119 = EDGE_CURVE('',#144876,#87937,#145120,.T.); -#145120 = SURFACE_CURVE('',#145121,(#145125,#145132),.PCURVE_S1.); -#145121 = LINE('',#145122,#145123); -#145122 = CARTESIAN_POINT('',(4.35,10.527847992439,0.75)); -#145123 = VECTOR('',#145124,1.); -#145124 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#145125 = PCURVE('',#87954,#145126); -#145126 = DEFINITIONAL_REPRESENTATION('',(#145127),#145131); -#145127 = LINE('',#145128,#145129); -#145128 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#145129 = VECTOR('',#145130,1.); -#145130 = DIRECTION('',(3.563627120235E-016,-1.)); -#145131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145132 = PCURVE('',#87982,#145133); -#145133 = DEFINITIONAL_REPRESENTATION('',(#145134),#145138); -#145134 = LINE('',#145135,#145136); -#145135 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145136 = VECTOR('',#145137,1.); -#145137 = DIRECTION('',(-1.,2.164989446033E-063)); -#145138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145139 = ORIENTED_EDGE('',*,*,#87936,.T.); -#145140 = ADVANCED_FACE('',(#145141),#87982,.F.); -#145141 = FACE_BOUND('',#145142,.T.); -#145142 = EDGE_LOOP('',(#145143,#145144,#145165,#145166)); -#145143 = ORIENTED_EDGE('',*,*,#144972,.F.); -#145144 = ORIENTED_EDGE('',*,*,#145145,.T.); -#145145 = EDGE_CURVE('',#144923,#87967,#145146,.T.); -#145146 = SURFACE_CURVE('',#145147,(#145151,#145158),.PCURVE_S1.); -#145147 = LINE('',#145148,#145149); -#145148 = CARTESIAN_POINT('',(4.15,10.527847992439,0.75)); -#145149 = VECTOR('',#145150,1.); -#145150 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#145151 = PCURVE('',#87982,#145152); -#145152 = DEFINITIONAL_REPRESENTATION('',(#145153),#145157); -#145153 = LINE('',#145154,#145155); -#145154 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#145155 = VECTOR('',#145156,1.); -#145156 = DIRECTION('',(-1.,2.164989446033E-063)); -#145157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145158 = PCURVE('',#88010,#145159); -#145159 = DEFINITIONAL_REPRESENTATION('',(#145160),#145164); -#145160 = LINE('',#145161,#145162); -#145161 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#145162 = VECTOR('',#145163,1.); -#145163 = DIRECTION('',(-3.563627120235E-016,-1.)); -#145164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145165 = ORIENTED_EDGE('',*,*,#87966,.T.); -#145166 = ORIENTED_EDGE('',*,*,#145119,.F.); -#145167 = ADVANCED_FACE('',(#145168),#88010,.F.); -#145168 = FACE_BOUND('',#145169,.T.); -#145169 = EDGE_LOOP('',(#145170,#145171,#145172,#145173,#145174,#145175, - #145196,#145197,#145198,#145199,#145200,#145221)); -#145170 = ORIENTED_EDGE('',*,*,#145145,.F.); -#145171 = ORIENTED_EDGE('',*,*,#144922,.T.); -#145172 = ORIENTED_EDGE('',*,*,#144776,.T.); -#145173 = ORIENTED_EDGE('',*,*,#144701,.T.); -#145174 = ORIENTED_EDGE('',*,*,#144470,.T.); -#145175 = ORIENTED_EDGE('',*,*,#145176,.T.); -#145176 = EDGE_CURVE('',#144448,#144311,#145177,.T.); -#145177 = SURFACE_CURVE('',#145178,(#145182,#145189),.PCURVE_S1.); -#145178 = LINE('',#145179,#145180); -#145179 = CARTESIAN_POINT('',(4.15,11.,1.159810404338E-002)); -#145180 = VECTOR('',#145181,1.); -#145181 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#145182 = PCURVE('',#88010,#145183); -#145183 = DEFINITIONAL_REPRESENTATION('',(#145184),#145188); -#145184 = LINE('',#145185,#145186); -#145185 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#145186 = VECTOR('',#145187,1.); -#145187 = DIRECTION('',(1.,-2.101748079665E-016)); -#145188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145189 = PCURVE('',#144354,#145190); -#145190 = DEFINITIONAL_REPRESENTATION('',(#145191),#145195); -#145191 = LINE('',#145192,#145193); -#145192 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#145193 = VECTOR('',#145194,1.); -#145194 = DIRECTION('',(1.570395187386E-016,-1.)); -#145195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145196 = ORIENTED_EDGE('',*,*,#144308,.F.); -#145197 = ORIENTED_EDGE('',*,*,#144599,.F.); -#145198 = ORIENTED_EDGE('',*,*,#144829,.F.); -#145199 = ORIENTED_EDGE('',*,*,#144995,.F.); -#145200 = ORIENTED_EDGE('',*,*,#145201,.T.); -#145201 = EDGE_CURVE('',#144996,#87995,#145202,.T.); -#145202 = SURFACE_CURVE('',#145203,(#145207,#145214),.PCURVE_S1.); -#145203 = LINE('',#145204,#145205); -#145204 = CARTESIAN_POINT('',(4.15,10.527847992439,0.65)); -#145205 = VECTOR('',#145206,1.); -#145206 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#145207 = PCURVE('',#88010,#145208); -#145208 = DEFINITIONAL_REPRESENTATION('',(#145209),#145213); -#145209 = LINE('',#145210,#145211); -#145210 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145211 = VECTOR('',#145212,1.); -#145212 = DIRECTION('',(-3.563627120235E-016,-1.)); -#145213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145214 = PCURVE('',#88036,#145215); -#145215 = DEFINITIONAL_REPRESENTATION('',(#145216),#145220); -#145216 = LINE('',#145217,#145218); -#145217 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#145218 = VECTOR('',#145219,1.); -#145219 = DIRECTION('',(1.,2.164989446033E-063)); -#145220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145221 = ORIENTED_EDGE('',*,*,#87994,.T.); -#145222 = ADVANCED_FACE('',(#145223),#88036,.F.); -#145223 = FACE_BOUND('',#145224,.T.); -#145224 = EDGE_LOOP('',(#145225,#145226,#145227,#145228)); -#145225 = ORIENTED_EDGE('',*,*,#145022,.F.); -#145226 = ORIENTED_EDGE('',*,*,#145069,.T.); -#145227 = ORIENTED_EDGE('',*,*,#88022,.T.); -#145228 = ORIENTED_EDGE('',*,*,#145201,.F.); -#145229 = ADVANCED_FACE('',(#145230),#144354,.T.); -#145230 = FACE_BOUND('',#145231,.T.); -#145231 = EDGE_LOOP('',(#145232,#145233,#145234,#145235)); -#145232 = ORIENTED_EDGE('',*,*,#145176,.F.); -#145233 = ORIENTED_EDGE('',*,*,#144447,.F.); -#145234 = ORIENTED_EDGE('',*,*,#145094,.F.); -#145235 = ORIENTED_EDGE('',*,*,#144338,.F.); -#145236 = ADVANCED_FACE('',(#145237),#145251,.T.); -#145237 = FACE_BOUND('',#145238,.T.); -#145238 = EDGE_LOOP('',(#145239,#145269,#145297,#145320)); -#145239 = ORIENTED_EDGE('',*,*,#145240,.T.); -#145240 = EDGE_CURVE('',#145241,#145243,#145245,.T.); -#145241 = VERTEX_POINT('',#145242); -#145242 = CARTESIAN_POINT('',(3.65,10.74341632541,-0.308197125857)); -#145243 = VERTEX_POINT('',#145244); -#145244 = CARTESIAN_POINT('',(3.65,11.,-0.308197125857)); -#145245 = SURFACE_CURVE('',#145246,(#145250,#145262),.PCURVE_S1.); -#145246 = LINE('',#145247,#145248); -#145247 = CARTESIAN_POINT('',(3.65,10.74341632541,-0.308197125857)); -#145248 = VECTOR('',#145249,1.); -#145249 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#145250 = PCURVE('',#145251,#145256); -#145251 = PLANE('',#145252); -#145252 = AXIS2_PLACEMENT_3D('',#145253,#145254,#145255); -#145253 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#147446 = CARTESIAN_POINT('',(1.598788597134,-4.35)); +#147447 = CARTESIAN_POINT('',(3.14159265359,-4.35)); +#147448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147449 = PCURVE('',#90346,#147450); +#147450 = DEFINITIONAL_REPRESENTATION('',(#147451),#147455); +#147451 = CIRCLE('',#147452,0.119270391569); +#147452 = AXIS2_PLACEMENT_2D('',#147453,#147454); +#147453 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#147454 = DIRECTION('',(0.E+000,-1.)); +#147455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147456 = ORIENTED_EDGE('',*,*,#147192,.F.); +#147457 = ADVANCED_FACE('',(#147458),#90346,.F.); +#147458 = FACE_BOUND('',#147459,.T.); +#147459 = EDGE_LOOP('',(#147460,#147481,#147482,#147483,#147484,#147485, + #147506,#147507,#147508,#147509,#147510,#147531)); +#147460 = ORIENTED_EDGE('',*,*,#147461,.F.); +#147461 = EDGE_CURVE('',#147415,#90331,#147462,.T.); +#147462 = SURFACE_CURVE('',#147463,(#147467,#147474),.PCURVE_S1.); +#147463 = LINE('',#147464,#147465); +#147464 = CARTESIAN_POINT('',(4.35,10.527847992439,0.65)); +#147465 = VECTOR('',#147466,1.); +#147466 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#147467 = PCURVE('',#90346,#147468); +#147468 = DEFINITIONAL_REPRESENTATION('',(#147469),#147473); +#147469 = LINE('',#147470,#147471); +#147470 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147471 = VECTOR('',#147472,1.); +#147472 = DIRECTION('',(3.563627120235E-016,-1.)); +#147473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147474 = PCURVE('',#90428,#147475); +#147475 = DEFINITIONAL_REPRESENTATION('',(#147476),#147480); +#147476 = LINE('',#147477,#147478); +#147477 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147478 = VECTOR('',#147479,1.); +#147479 = DIRECTION('',(1.,2.164989446033E-063)); +#147480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147481 = ORIENTED_EDGE('',*,*,#147436,.T.); +#147482 = ORIENTED_EDGE('',*,*,#147243,.T.); +#147483 = ORIENTED_EDGE('',*,*,#146914,.T.); +#147484 = ORIENTED_EDGE('',*,*,#146758,.T.); +#147485 = ORIENTED_EDGE('',*,*,#147486,.T.); +#147486 = EDGE_CURVE('',#146731,#146812,#147487,.T.); +#147487 = SURFACE_CURVE('',#147488,(#147492,#147499),.PCURVE_S1.); +#147488 = LINE('',#147489,#147490); +#147489 = CARTESIAN_POINT('',(4.35,11.,1.159810404338E-002)); +#147490 = VECTOR('',#147491,1.); +#147491 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#147492 = PCURVE('',#90346,#147493); +#147493 = DEFINITIONAL_REPRESENTATION('',(#147494),#147498); +#147494 = LINE('',#147495,#147496); +#147495 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#147496 = VECTOR('',#147497,1.); +#147497 = DIRECTION('',(1.,2.101748079665E-016)); +#147498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147499 = PCURVE('',#146746,#147500); +#147500 = DEFINITIONAL_REPRESENTATION('',(#147501),#147505); +#147501 = LINE('',#147502,#147503); +#147502 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#147503 = VECTOR('',#147504,1.); +#147504 = DIRECTION('',(-1.570395187386E-016,1.)); +#147505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147506 = ORIENTED_EDGE('',*,*,#146809,.F.); +#147507 = ORIENTED_EDGE('',*,*,#147039,.F.); +#147508 = ORIENTED_EDGE('',*,*,#147146,.F.); +#147509 = ORIENTED_EDGE('',*,*,#147267,.F.); +#147510 = ORIENTED_EDGE('',*,*,#147511,.T.); +#147511 = EDGE_CURVE('',#147268,#90329,#147512,.T.); +#147512 = SURFACE_CURVE('',#147513,(#147517,#147524),.PCURVE_S1.); +#147513 = LINE('',#147514,#147515); +#147514 = CARTESIAN_POINT('',(4.35,10.527847992439,0.75)); +#147515 = VECTOR('',#147516,1.); +#147516 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#147517 = PCURVE('',#90346,#147518); +#147518 = DEFINITIONAL_REPRESENTATION('',(#147519),#147523); +#147519 = LINE('',#147520,#147521); +#147520 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#147521 = VECTOR('',#147522,1.); +#147522 = DIRECTION('',(3.563627120235E-016,-1.)); +#147523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147524 = PCURVE('',#90374,#147525); +#147525 = DEFINITIONAL_REPRESENTATION('',(#147526),#147530); +#147526 = LINE('',#147527,#147528); +#147527 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147528 = VECTOR('',#147529,1.); +#147529 = DIRECTION('',(-1.,2.164989446033E-063)); +#147530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147531 = ORIENTED_EDGE('',*,*,#90328,.T.); +#147532 = ADVANCED_FACE('',(#147533),#90374,.F.); +#147533 = FACE_BOUND('',#147534,.T.); +#147534 = EDGE_LOOP('',(#147535,#147536,#147557,#147558)); +#147535 = ORIENTED_EDGE('',*,*,#147364,.F.); +#147536 = ORIENTED_EDGE('',*,*,#147537,.T.); +#147537 = EDGE_CURVE('',#147315,#90359,#147538,.T.); +#147538 = SURFACE_CURVE('',#147539,(#147543,#147550),.PCURVE_S1.); +#147539 = LINE('',#147540,#147541); +#147540 = CARTESIAN_POINT('',(4.15,10.527847992439,0.75)); +#147541 = VECTOR('',#147542,1.); +#147542 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#147543 = PCURVE('',#90374,#147544); +#147544 = DEFINITIONAL_REPRESENTATION('',(#147545),#147549); +#147545 = LINE('',#147546,#147547); +#147546 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#147547 = VECTOR('',#147548,1.); +#147548 = DIRECTION('',(-1.,2.164989446033E-063)); +#147549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147550 = PCURVE('',#90402,#147551); +#147551 = DEFINITIONAL_REPRESENTATION('',(#147552),#147556); +#147552 = LINE('',#147553,#147554); +#147553 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#147554 = VECTOR('',#147555,1.); +#147555 = DIRECTION('',(-3.563627120235E-016,-1.)); +#147556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147557 = ORIENTED_EDGE('',*,*,#90358,.T.); +#147558 = ORIENTED_EDGE('',*,*,#147511,.F.); +#147559 = ADVANCED_FACE('',(#147560),#90402,.F.); +#147560 = FACE_BOUND('',#147561,.T.); +#147561 = EDGE_LOOP('',(#147562,#147563,#147564,#147565,#147566,#147567, + #147588,#147589,#147590,#147591,#147592,#147613)); +#147562 = ORIENTED_EDGE('',*,*,#147537,.F.); +#147563 = ORIENTED_EDGE('',*,*,#147314,.T.); +#147564 = ORIENTED_EDGE('',*,*,#147168,.T.); +#147565 = ORIENTED_EDGE('',*,*,#147093,.T.); +#147566 = ORIENTED_EDGE('',*,*,#146862,.T.); +#147567 = ORIENTED_EDGE('',*,*,#147568,.T.); +#147568 = EDGE_CURVE('',#146840,#146703,#147569,.T.); +#147569 = SURFACE_CURVE('',#147570,(#147574,#147581),.PCURVE_S1.); +#147570 = LINE('',#147571,#147572); +#147571 = CARTESIAN_POINT('',(4.15,11.,1.159810404338E-002)); +#147572 = VECTOR('',#147573,1.); +#147573 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#147574 = PCURVE('',#90402,#147575); +#147575 = DEFINITIONAL_REPRESENTATION('',(#147576),#147580); +#147576 = LINE('',#147577,#147578); +#147577 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#147578 = VECTOR('',#147579,1.); +#147579 = DIRECTION('',(1.,-2.101748079665E-016)); +#147580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147581 = PCURVE('',#146746,#147582); +#147582 = DEFINITIONAL_REPRESENTATION('',(#147583),#147587); +#147583 = LINE('',#147584,#147585); +#147584 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#147585 = VECTOR('',#147586,1.); +#147586 = DIRECTION('',(1.570395187386E-016,-1.)); +#147587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147588 = ORIENTED_EDGE('',*,*,#146700,.F.); +#147589 = ORIENTED_EDGE('',*,*,#146991,.F.); +#147590 = ORIENTED_EDGE('',*,*,#147221,.F.); +#147591 = ORIENTED_EDGE('',*,*,#147387,.F.); +#147592 = ORIENTED_EDGE('',*,*,#147593,.T.); +#147593 = EDGE_CURVE('',#147388,#90387,#147594,.T.); +#147594 = SURFACE_CURVE('',#147595,(#147599,#147606),.PCURVE_S1.); +#147595 = LINE('',#147596,#147597); +#147596 = CARTESIAN_POINT('',(4.15,10.527847992439,0.65)); +#147597 = VECTOR('',#147598,1.); +#147598 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#147599 = PCURVE('',#90402,#147600); +#147600 = DEFINITIONAL_REPRESENTATION('',(#147601),#147605); +#147601 = LINE('',#147602,#147603); +#147602 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147603 = VECTOR('',#147604,1.); +#147604 = DIRECTION('',(-3.563627120235E-016,-1.)); +#147605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147606 = PCURVE('',#90428,#147607); +#147607 = DEFINITIONAL_REPRESENTATION('',(#147608),#147612); +#147608 = LINE('',#147609,#147610); +#147609 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#147610 = VECTOR('',#147611,1.); +#147611 = DIRECTION('',(1.,2.164989446033E-063)); +#147612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147613 = ORIENTED_EDGE('',*,*,#90386,.T.); +#147614 = ADVANCED_FACE('',(#147615),#90428,.F.); +#147615 = FACE_BOUND('',#147616,.T.); +#147616 = EDGE_LOOP('',(#147617,#147618,#147619,#147620)); +#147617 = ORIENTED_EDGE('',*,*,#147414,.F.); +#147618 = ORIENTED_EDGE('',*,*,#147461,.T.); +#147619 = ORIENTED_EDGE('',*,*,#90414,.T.); +#147620 = ORIENTED_EDGE('',*,*,#147593,.F.); +#147621 = ADVANCED_FACE('',(#147622),#146746,.T.); +#147622 = FACE_BOUND('',#147623,.T.); +#147623 = EDGE_LOOP('',(#147624,#147625,#147626,#147627)); +#147624 = ORIENTED_EDGE('',*,*,#147568,.F.); +#147625 = ORIENTED_EDGE('',*,*,#146839,.F.); +#147626 = ORIENTED_EDGE('',*,*,#147486,.F.); +#147627 = ORIENTED_EDGE('',*,*,#146730,.F.); +#147628 = ADVANCED_FACE('',(#147629),#147643,.T.); +#147629 = FACE_BOUND('',#147630,.T.); +#147630 = EDGE_LOOP('',(#147631,#147661,#147689,#147712)); +#147631 = ORIENTED_EDGE('',*,*,#147632,.T.); +#147632 = EDGE_CURVE('',#147633,#147635,#147637,.T.); +#147633 = VERTEX_POINT('',#147634); +#147634 = CARTESIAN_POINT('',(3.65,10.74341632541,-0.308197125857)); +#147635 = VERTEX_POINT('',#147636); +#147636 = CARTESIAN_POINT('',(3.65,11.,-0.308197125857)); +#147637 = SURFACE_CURVE('',#147638,(#147642,#147654),.PCURVE_S1.); +#147638 = LINE('',#147639,#147640); +#147639 = CARTESIAN_POINT('',(3.65,10.74341632541,-0.308197125857)); +#147640 = VECTOR('',#147641,1.); +#147641 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#147642 = PCURVE('',#147643,#147648); +#147643 = PLANE('',#147644); +#147644 = AXIS2_PLACEMENT_3D('',#147645,#147646,#147647); +#147645 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#145254 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#145255 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#145256 = DEFINITIONAL_REPRESENTATION('',(#145257),#145261); -#145257 = LINE('',#145258,#145259); -#145258 = CARTESIAN_POINT('',(-3.65,-3.552713678801E-015)); -#145259 = VECTOR('',#145260,1.); -#145260 = DIRECTION('',(-6.725593854929E-015,1.)); -#145261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145262 = PCURVE('',#86870,#145263); -#145263 = DEFINITIONAL_REPRESENTATION('',(#145264),#145268); -#145264 = LINE('',#145265,#145266); -#145265 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#145266 = VECTOR('',#145267,1.); -#145267 = DIRECTION('',(0.E+000,1.)); -#145268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145269 = ORIENTED_EDGE('',*,*,#145270,.T.); -#145270 = EDGE_CURVE('',#145243,#145271,#145273,.T.); -#145271 = VERTEX_POINT('',#145272); -#145272 = CARTESIAN_POINT('',(3.85,11.,-0.308197125857)); -#145273 = SURFACE_CURVE('',#145274,(#145278,#145285),.PCURVE_S1.); -#145274 = LINE('',#145275,#145276); -#145275 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#145276 = VECTOR('',#145277,1.); -#145277 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145278 = PCURVE('',#145251,#145279); -#145279 = DEFINITIONAL_REPRESENTATION('',(#145280),#145284); -#145280 = LINE('',#145281,#145282); -#145281 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#145282 = VECTOR('',#145283,1.); -#145283 = DIRECTION('',(-1.,-8.881784197001E-016)); -#145284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145285 = PCURVE('',#145286,#145291); -#145286 = PLANE('',#145287); -#145287 = AXIS2_PLACEMENT_3D('',#145288,#145289,#145290); -#145288 = CARTESIAN_POINT('',(3.75,11.,-0.258196742327)); -#145289 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#145290 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#145291 = DEFINITIONAL_REPRESENTATION('',(#145292),#145296); -#145292 = LINE('',#145293,#145294); -#145293 = CARTESIAN_POINT('',(3.75,-5.000038352949E-002)); -#145294 = VECTOR('',#145295,1.); -#145295 = DIRECTION('',(-1.,-1.1653254136E-048)); -#145296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145297 = ORIENTED_EDGE('',*,*,#145298,.F.); -#145298 = EDGE_CURVE('',#145299,#145271,#145301,.T.); -#145299 = VERTEX_POINT('',#145300); -#145300 = CARTESIAN_POINT('',(3.85,10.74341632541,-0.308197125857)); -#145301 = SURFACE_CURVE('',#145302,(#145306,#145313),.PCURVE_S1.); -#145302 = LINE('',#145303,#145304); -#145303 = CARTESIAN_POINT('',(3.85,10.74341632541,-0.308197125857)); -#145304 = VECTOR('',#145305,1.); -#145305 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#145306 = PCURVE('',#145251,#145307); -#145307 = DEFINITIONAL_REPRESENTATION('',(#145308),#145312); -#145308 = LINE('',#145309,#145310); -#145309 = CARTESIAN_POINT('',(-3.85,-3.552713678801E-015)); -#145310 = VECTOR('',#145311,1.); -#145311 = DIRECTION('',(-6.725593854929E-015,1.)); -#145312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145313 = PCURVE('',#86814,#145314); -#145314 = DEFINITIONAL_REPRESENTATION('',(#145315),#145319); -#145315 = LINE('',#145316,#145317); -#145316 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#145317 = VECTOR('',#145318,1.); -#145318 = DIRECTION('',(0.E+000,1.)); -#145319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145320 = ORIENTED_EDGE('',*,*,#145321,.T.); -#145321 = EDGE_CURVE('',#145299,#145241,#145322,.T.); -#145322 = SURFACE_CURVE('',#145323,(#145327,#145334),.PCURVE_S1.); -#145323 = LINE('',#145324,#145325); -#145324 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#147646 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#147647 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#147648 = DEFINITIONAL_REPRESENTATION('',(#147649),#147653); +#147649 = LINE('',#147650,#147651); +#147650 = CARTESIAN_POINT('',(-3.65,-3.552713678801E-015)); +#147651 = VECTOR('',#147652,1.); +#147652 = DIRECTION('',(-6.725593854929E-015,1.)); +#147653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147654 = PCURVE('',#89262,#147655); +#147655 = DEFINITIONAL_REPRESENTATION('',(#147656),#147660); +#147656 = LINE('',#147657,#147658); +#147657 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#147658 = VECTOR('',#147659,1.); +#147659 = DIRECTION('',(0.E+000,1.)); +#147660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147661 = ORIENTED_EDGE('',*,*,#147662,.T.); +#147662 = EDGE_CURVE('',#147635,#147663,#147665,.T.); +#147663 = VERTEX_POINT('',#147664); +#147664 = CARTESIAN_POINT('',(3.85,11.,-0.308197125857)); +#147665 = SURFACE_CURVE('',#147666,(#147670,#147677),.PCURVE_S1.); +#147666 = LINE('',#147667,#147668); +#147667 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#147668 = VECTOR('',#147669,1.); +#147669 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147670 = PCURVE('',#147643,#147671); +#147671 = DEFINITIONAL_REPRESENTATION('',(#147672),#147676); +#147672 = LINE('',#147673,#147674); +#147673 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#147674 = VECTOR('',#147675,1.); +#147675 = DIRECTION('',(-1.,-8.881784197001E-016)); +#147676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147677 = PCURVE('',#147678,#147683); +#147678 = PLANE('',#147679); +#147679 = AXIS2_PLACEMENT_3D('',#147680,#147681,#147682); +#147680 = CARTESIAN_POINT('',(3.75,11.,-0.258196742327)); +#147681 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#147682 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#147683 = DEFINITIONAL_REPRESENTATION('',(#147684),#147688); +#147684 = LINE('',#147685,#147686); +#147685 = CARTESIAN_POINT('',(3.75,-5.000038352949E-002)); +#147686 = VECTOR('',#147687,1.); +#147687 = DIRECTION('',(-1.,-1.1653254136E-048)); +#147688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147689 = ORIENTED_EDGE('',*,*,#147690,.F.); +#147690 = EDGE_CURVE('',#147691,#147663,#147693,.T.); +#147691 = VERTEX_POINT('',#147692); +#147692 = CARTESIAN_POINT('',(3.85,10.74341632541,-0.308197125857)); +#147693 = SURFACE_CURVE('',#147694,(#147698,#147705),.PCURVE_S1.); +#147694 = LINE('',#147695,#147696); +#147695 = CARTESIAN_POINT('',(3.85,10.74341632541,-0.308197125857)); +#147696 = VECTOR('',#147697,1.); +#147697 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#147698 = PCURVE('',#147643,#147699); +#147699 = DEFINITIONAL_REPRESENTATION('',(#147700),#147704); +#147700 = LINE('',#147701,#147702); +#147701 = CARTESIAN_POINT('',(-3.85,-3.552713678801E-015)); +#147702 = VECTOR('',#147703,1.); +#147703 = DIRECTION('',(-6.725593854929E-015,1.)); +#147704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147705 = PCURVE('',#89206,#147706); +#147706 = DEFINITIONAL_REPRESENTATION('',(#147707),#147711); +#147707 = LINE('',#147708,#147709); +#147708 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#147709 = VECTOR('',#147710,1.); +#147710 = DIRECTION('',(0.E+000,1.)); +#147711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147712 = ORIENTED_EDGE('',*,*,#147713,.T.); +#147713 = EDGE_CURVE('',#147691,#147633,#147714,.T.); +#147714 = SURFACE_CURVE('',#147715,(#147719,#147726),.PCURVE_S1.); +#147715 = LINE('',#147716,#147717); +#147716 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#145325 = VECTOR('',#145326,1.); -#145326 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145327 = PCURVE('',#145251,#145328); -#145328 = DEFINITIONAL_REPRESENTATION('',(#145329),#145333); -#145329 = LINE('',#145330,#145331); -#145330 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145331 = VECTOR('',#145332,1.); -#145332 = DIRECTION('',(1.,8.881784197001E-016)); -#145333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145334 = PCURVE('',#145335,#145340); -#145335 = CYLINDRICAL_SURFACE('',#145336,0.308574064194); -#145336 = AXIS2_PLACEMENT_3D('',#145337,#145338,#145339); -#145337 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#147717 = VECTOR('',#147718,1.); +#147718 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147719 = PCURVE('',#147643,#147720); +#147720 = DEFINITIONAL_REPRESENTATION('',(#147721),#147725); +#147721 = LINE('',#147722,#147723); +#147722 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147723 = VECTOR('',#147724,1.); +#147724 = DIRECTION('',(1.,8.881784197001E-016)); +#147725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147726 = PCURVE('',#147727,#147732); +#147727 = CYLINDRICAL_SURFACE('',#147728,0.308574064194); +#147728 = AXIS2_PLACEMENT_3D('',#147729,#147730,#147731); +#147729 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#145338 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145339 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145340 = DEFINITIONAL_REPRESENTATION('',(#145341),#145344); -#145341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145342,#145343), +#147730 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147731 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147732 = DEFINITIONAL_REPRESENTATION('',(#147733),#147736); +#147733 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147734,#147735), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#145342 = CARTESIAN_POINT('',(4.761821717947,3.85)); -#145343 = CARTESIAN_POINT('',(4.761821717947,3.65)); -#145344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147734 = CARTESIAN_POINT('',(4.761821717947,3.85)); +#147735 = CARTESIAN_POINT('',(4.761821717947,3.65)); +#147736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147737 = ADVANCED_FACE('',(#147738),#147752,.T.); +#147738 = FACE_BOUND('',#147739,.T.); +#147739 = EDGE_LOOP('',(#147740,#147770,#147793,#147816)); +#147740 = ORIENTED_EDGE('',*,*,#147741,.T.); +#147741 = EDGE_CURVE('',#147742,#147744,#147746,.T.); +#147742 = VERTEX_POINT('',#147743); +#147743 = CARTESIAN_POINT('',(3.85,10.740726081328,-0.208196358798)); +#147744 = VERTEX_POINT('',#147745); +#147745 = CARTESIAN_POINT('',(3.85,11.,-0.208196358798)); +#147746 = SURFACE_CURVE('',#147747,(#147751,#147763),.PCURVE_S1.); +#147747 = LINE('',#147748,#147749); +#147748 = CARTESIAN_POINT('',(3.85,10.740726081328,-0.208196358798)); +#147749 = VECTOR('',#147750,1.); +#147750 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#147751 = PCURVE('',#147752,#147757); +#147752 = PLANE('',#147753); +#147753 = AXIS2_PLACEMENT_3D('',#147754,#147755,#147756); +#147754 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#147755 = DIRECTION('',(0.E+000,0.E+000,1.)); +#147756 = DIRECTION('',(1.,0.E+000,0.E+000)); +#147757 = DEFINITIONAL_REPRESENTATION('',(#147758),#147762); +#147758 = LINE('',#147759,#147760); +#147759 = CARTESIAN_POINT('',(3.85,-3.552713678801E-015)); +#147760 = VECTOR('',#147761,1.); +#147761 = DIRECTION('',(6.725593854929E-015,1.)); +#147762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147763 = PCURVE('',#89206,#147764); +#147764 = DEFINITIONAL_REPRESENTATION('',(#147765),#147769); +#147765 = LINE('',#147766,#147767); +#147766 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#147767 = VECTOR('',#147768,1.); +#147768 = DIRECTION('',(0.E+000,1.)); +#147769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147770 = ORIENTED_EDGE('',*,*,#147771,.T.); +#147771 = EDGE_CURVE('',#147744,#147772,#147774,.T.); +#147772 = VERTEX_POINT('',#147773); +#147773 = CARTESIAN_POINT('',(3.65,11.,-0.208196358798)); +#147774 = SURFACE_CURVE('',#147775,(#147779,#147786),.PCURVE_S1.); +#147775 = LINE('',#147776,#147777); +#147776 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#147777 = VECTOR('',#147778,1.); +#147778 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147779 = PCURVE('',#147752,#147780); +#147780 = DEFINITIONAL_REPRESENTATION('',(#147781),#147785); +#147781 = LINE('',#147782,#147783); +#147782 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#147783 = VECTOR('',#147784,1.); +#147784 = DIRECTION('',(-1.,8.881784197001E-016)); +#147785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147786 = PCURVE('',#147678,#147787); +#147787 = DEFINITIONAL_REPRESENTATION('',(#147788),#147792); +#147788 = LINE('',#147789,#147790); +#147789 = CARTESIAN_POINT('',(3.75,5.000038352949E-002)); +#147790 = VECTOR('',#147791,1.); +#147791 = DIRECTION('',(1.,1.1653254136E-048)); +#147792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147793 = ORIENTED_EDGE('',*,*,#147794,.F.); +#147794 = EDGE_CURVE('',#147795,#147772,#147797,.T.); +#147795 = VERTEX_POINT('',#147796); +#147796 = CARTESIAN_POINT('',(3.65,10.740726081328,-0.208196358798)); +#147797 = SURFACE_CURVE('',#147798,(#147802,#147809),.PCURVE_S1.); +#147798 = LINE('',#147799,#147800); +#147799 = CARTESIAN_POINT('',(3.65,10.740726081328,-0.208196358798)); +#147800 = VECTOR('',#147801,1.); +#147801 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#147802 = PCURVE('',#147752,#147803); +#147803 = DEFINITIONAL_REPRESENTATION('',(#147804),#147808); +#147804 = LINE('',#147805,#147806); +#147805 = CARTESIAN_POINT('',(3.65,-3.552713678801E-015)); +#147806 = VECTOR('',#147807,1.); +#147807 = DIRECTION('',(6.725593854929E-015,1.)); +#147808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147809 = PCURVE('',#89262,#147810); +#147810 = DEFINITIONAL_REPRESENTATION('',(#147811),#147815); +#147811 = LINE('',#147812,#147813); +#147812 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#147813 = VECTOR('',#147814,1.); +#147814 = DIRECTION('',(0.E+000,1.)); +#147815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145345 = ADVANCED_FACE('',(#145346),#145360,.T.); -#145346 = FACE_BOUND('',#145347,.T.); -#145347 = EDGE_LOOP('',(#145348,#145378,#145401,#145424)); -#145348 = ORIENTED_EDGE('',*,*,#145349,.T.); -#145349 = EDGE_CURVE('',#145350,#145352,#145354,.T.); -#145350 = VERTEX_POINT('',#145351); -#145351 = CARTESIAN_POINT('',(3.85,10.740726081328,-0.208196358798)); -#145352 = VERTEX_POINT('',#145353); -#145353 = CARTESIAN_POINT('',(3.85,11.,-0.208196358798)); -#145354 = SURFACE_CURVE('',#145355,(#145359,#145371),.PCURVE_S1.); -#145355 = LINE('',#145356,#145357); -#145356 = CARTESIAN_POINT('',(3.85,10.740726081328,-0.208196358798)); -#145357 = VECTOR('',#145358,1.); -#145358 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#145359 = PCURVE('',#145360,#145365); -#145360 = PLANE('',#145361); -#145361 = AXIS2_PLACEMENT_3D('',#145362,#145363,#145364); -#145362 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#147816 = ORIENTED_EDGE('',*,*,#147817,.T.); +#147817 = EDGE_CURVE('',#147795,#147742,#147818,.T.); +#147818 = SURFACE_CURVE('',#147819,(#147823,#147830),.PCURVE_S1.); +#147819 = LINE('',#147820,#147821); +#147820 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#145363 = DIRECTION('',(0.E+000,0.E+000,1.)); -#145364 = DIRECTION('',(1.,0.E+000,0.E+000)); -#145365 = DEFINITIONAL_REPRESENTATION('',(#145366),#145370); -#145366 = LINE('',#145367,#145368); -#145367 = CARTESIAN_POINT('',(3.85,-3.552713678801E-015)); -#145368 = VECTOR('',#145369,1.); -#145369 = DIRECTION('',(6.725593854929E-015,1.)); -#145370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145371 = PCURVE('',#86814,#145372); -#145372 = DEFINITIONAL_REPRESENTATION('',(#145373),#145377); -#145373 = LINE('',#145374,#145375); -#145374 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#145375 = VECTOR('',#145376,1.); -#145376 = DIRECTION('',(0.E+000,1.)); -#145377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145378 = ORIENTED_EDGE('',*,*,#145379,.T.); -#145379 = EDGE_CURVE('',#145352,#145380,#145382,.T.); -#145380 = VERTEX_POINT('',#145381); -#145381 = CARTESIAN_POINT('',(3.65,11.,-0.208196358798)); -#145382 = SURFACE_CURVE('',#145383,(#145387,#145394),.PCURVE_S1.); -#145383 = LINE('',#145384,#145385); -#145384 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#145385 = VECTOR('',#145386,1.); -#145386 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145387 = PCURVE('',#145360,#145388); -#145388 = DEFINITIONAL_REPRESENTATION('',(#145389),#145393); -#145389 = LINE('',#145390,#145391); -#145390 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#145391 = VECTOR('',#145392,1.); -#145392 = DIRECTION('',(-1.,8.881784197001E-016)); -#145393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145394 = PCURVE('',#145286,#145395); -#145395 = DEFINITIONAL_REPRESENTATION('',(#145396),#145400); -#145396 = LINE('',#145397,#145398); -#145397 = CARTESIAN_POINT('',(3.75,5.000038352949E-002)); -#145398 = VECTOR('',#145399,1.); -#145399 = DIRECTION('',(1.,1.1653254136E-048)); -#145400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145401 = ORIENTED_EDGE('',*,*,#145402,.F.); -#145402 = EDGE_CURVE('',#145403,#145380,#145405,.T.); -#145403 = VERTEX_POINT('',#145404); -#145404 = CARTESIAN_POINT('',(3.65,10.740726081328,-0.208196358798)); -#145405 = SURFACE_CURVE('',#145406,(#145410,#145417),.PCURVE_S1.); -#145406 = LINE('',#145407,#145408); -#145407 = CARTESIAN_POINT('',(3.65,10.740726081328,-0.208196358798)); -#145408 = VECTOR('',#145409,1.); -#145409 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#145410 = PCURVE('',#145360,#145411); -#145411 = DEFINITIONAL_REPRESENTATION('',(#145412),#145416); -#145412 = LINE('',#145413,#145414); -#145413 = CARTESIAN_POINT('',(3.65,-3.552713678801E-015)); -#145414 = VECTOR('',#145415,1.); -#145415 = DIRECTION('',(6.725593854929E-015,1.)); -#145416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145417 = PCURVE('',#86870,#145418); -#145418 = DEFINITIONAL_REPRESENTATION('',(#145419),#145423); -#145419 = LINE('',#145420,#145421); -#145420 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#145421 = VECTOR('',#145422,1.); -#145422 = DIRECTION('',(0.E+000,1.)); -#145423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145424 = ORIENTED_EDGE('',*,*,#145425,.T.); -#145425 = EDGE_CURVE('',#145403,#145350,#145426,.T.); -#145426 = SURFACE_CURVE('',#145427,(#145431,#145438),.PCURVE_S1.); -#145427 = LINE('',#145428,#145429); -#145428 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#145429 = VECTOR('',#145430,1.); -#145430 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145431 = PCURVE('',#145360,#145432); -#145432 = DEFINITIONAL_REPRESENTATION('',(#145433),#145437); -#145433 = LINE('',#145434,#145435); -#145434 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145435 = VECTOR('',#145436,1.); -#145436 = DIRECTION('',(1.,-8.881784197001E-016)); -#145437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145438 = PCURVE('',#145439,#145444); -#145439 = CYLINDRICAL_SURFACE('',#145440,0.208574704164); -#145440 = AXIS2_PLACEMENT_3D('',#145441,#145442,#145443); -#145441 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#147821 = VECTOR('',#147822,1.); +#147822 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147823 = PCURVE('',#147752,#147824); +#147824 = DEFINITIONAL_REPRESENTATION('',(#147825),#147829); +#147825 = LINE('',#147826,#147827); +#147826 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#147827 = VECTOR('',#147828,1.); +#147828 = DIRECTION('',(1.,-8.881784197001E-016)); +#147829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147830 = PCURVE('',#147831,#147836); +#147831 = CYLINDRICAL_SURFACE('',#147832,0.208574704164); +#147832 = AXIS2_PLACEMENT_3D('',#147833,#147834,#147835); +#147833 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#145442 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145443 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145444 = DEFINITIONAL_REPRESENTATION('',(#145445),#145448); -#145445 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145446,#145447), +#147834 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147835 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147836 = DEFINITIONAL_REPRESENTATION('',(#147837),#147840); +#147837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147838,#147839), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#145446 = CARTESIAN_POINT('',(4.772630242227,3.65)); -#145447 = CARTESIAN_POINT('',(4.772630242227,3.85)); -#145448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145449 = ADVANCED_FACE('',(#145450),#145335,.T.); -#145450 = FACE_BOUND('',#145451,.T.); -#145451 = EDGE_LOOP('',(#145452,#145453,#145503,#145530)); -#145452 = ORIENTED_EDGE('',*,*,#145321,.F.); -#145453 = ORIENTED_EDGE('',*,*,#145454,.F.); -#145454 = EDGE_CURVE('',#145455,#145299,#145457,.T.); -#145455 = VERTEX_POINT('',#145456); -#145456 = CARTESIAN_POINT('',(3.85,10.419594812019,0.E+000)); -#145457 = SURFACE_CURVE('',#145458,(#145463,#145492),.PCURVE_S1.); -#145458 = CIRCLE('',#145459,0.308574064194); -#145459 = AXIS2_PLACEMENT_3D('',#145460,#145461,#145462); -#145460 = CARTESIAN_POINT('',(3.85,10.728168876214,2.640924866458E-017) - ); -#145461 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145462 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145463 = PCURVE('',#145335,#145464); -#145464 = DEFINITIONAL_REPRESENTATION('',(#145465),#145491); -#145465 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145466,#145467,#145468, - #145469,#145470,#145471,#145472,#145473,#145474,#145475,#145476, - #145477,#145478,#145479,#145480,#145481,#145482,#145483,#145484, - #145485,#145486,#145487,#145488,#145489,#145490),.UNSPECIFIED.,.F., +#147838 = CARTESIAN_POINT('',(4.772630242227,3.65)); +#147839 = CARTESIAN_POINT('',(4.772630242227,3.85)); +#147840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147841 = ADVANCED_FACE('',(#147842),#147727,.T.); +#147842 = FACE_BOUND('',#147843,.T.); +#147843 = EDGE_LOOP('',(#147844,#147845,#147895,#147922)); +#147844 = ORIENTED_EDGE('',*,*,#147713,.F.); +#147845 = ORIENTED_EDGE('',*,*,#147846,.F.); +#147846 = EDGE_CURVE('',#147847,#147691,#147849,.T.); +#147847 = VERTEX_POINT('',#147848); +#147848 = CARTESIAN_POINT('',(3.85,10.419594812019,0.E+000)); +#147849 = SURFACE_CURVE('',#147850,(#147855,#147884),.PCURVE_S1.); +#147850 = CIRCLE('',#147851,0.308574064194); +#147851 = AXIS2_PLACEMENT_3D('',#147852,#147853,#147854); +#147852 = CARTESIAN_POINT('',(3.85,10.728168876214,2.640924866458E-017) + ); +#147853 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147854 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147855 = PCURVE('',#147727,#147856); +#147856 = DEFINITIONAL_REPRESENTATION('',(#147857),#147883); +#147857 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147858,#147859,#147860, + #147861,#147862,#147863,#147864,#147865,#147866,#147867,#147868, + #147869,#147870,#147871,#147872,#147873,#147874,#147875,#147876, + #147877,#147878,#147879,#147880,#147881,#147882),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -179361,102 +182363,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#145466 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#145467 = CARTESIAN_POINT('',(3.166141578807,3.85)); -#145468 = CARTESIAN_POINT('',(3.215239429242,3.85)); -#145469 = CARTESIAN_POINT('',(3.288886204895,3.85)); -#145470 = CARTESIAN_POINT('',(3.362532980548,3.85)); -#145471 = CARTESIAN_POINT('',(3.4361797562,3.85)); -#145472 = CARTESIAN_POINT('',(3.509826531853,3.85)); -#145473 = CARTESIAN_POINT('',(3.583473307505,3.85)); -#145474 = CARTESIAN_POINT('',(3.657120083158,3.85)); -#145475 = CARTESIAN_POINT('',(3.730766858811,3.85)); -#145476 = CARTESIAN_POINT('',(3.804413634463,3.85)); -#145477 = CARTESIAN_POINT('',(3.878060410116,3.85)); -#145478 = CARTESIAN_POINT('',(3.951707185768,3.85)); -#145479 = CARTESIAN_POINT('',(4.025353961421,3.85)); -#145480 = CARTESIAN_POINT('',(4.099000737074,3.85)); -#145481 = CARTESIAN_POINT('',(4.172647512726,3.85)); -#145482 = CARTESIAN_POINT('',(4.246294288379,3.85)); -#145483 = CARTESIAN_POINT('',(4.319941064031,3.85)); -#145484 = CARTESIAN_POINT('',(4.393587839684,3.85)); -#145485 = CARTESIAN_POINT('',(4.467234615337,3.85)); -#145486 = CARTESIAN_POINT('',(4.540881390989,3.85)); -#145487 = CARTESIAN_POINT('',(4.614528166642,3.85)); -#145488 = CARTESIAN_POINT('',(4.688174942294,3.85)); -#145489 = CARTESIAN_POINT('',(4.737272792729,3.85)); -#145490 = CARTESIAN_POINT('',(4.761821717947,3.85)); -#145491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145492 = PCURVE('',#86814,#145493); -#145493 = DEFINITIONAL_REPRESENTATION('',(#145494),#145502); -#145494 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145495,#145496,#145497, - #145498,#145499,#145500,#145501),.UNSPECIFIED.,.T.,.F.) +#147858 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#147859 = CARTESIAN_POINT('',(3.166141578807,3.85)); +#147860 = CARTESIAN_POINT('',(3.215239429242,3.85)); +#147861 = CARTESIAN_POINT('',(3.288886204895,3.85)); +#147862 = CARTESIAN_POINT('',(3.362532980548,3.85)); +#147863 = CARTESIAN_POINT('',(3.4361797562,3.85)); +#147864 = CARTESIAN_POINT('',(3.509826531853,3.85)); +#147865 = CARTESIAN_POINT('',(3.583473307505,3.85)); +#147866 = CARTESIAN_POINT('',(3.657120083158,3.85)); +#147867 = CARTESIAN_POINT('',(3.730766858811,3.85)); +#147868 = CARTESIAN_POINT('',(3.804413634463,3.85)); +#147869 = CARTESIAN_POINT('',(3.878060410116,3.85)); +#147870 = CARTESIAN_POINT('',(3.951707185768,3.85)); +#147871 = CARTESIAN_POINT('',(4.025353961421,3.85)); +#147872 = CARTESIAN_POINT('',(4.099000737074,3.85)); +#147873 = CARTESIAN_POINT('',(4.172647512726,3.85)); +#147874 = CARTESIAN_POINT('',(4.246294288379,3.85)); +#147875 = CARTESIAN_POINT('',(4.319941064031,3.85)); +#147876 = CARTESIAN_POINT('',(4.393587839684,3.85)); +#147877 = CARTESIAN_POINT('',(4.467234615337,3.85)); +#147878 = CARTESIAN_POINT('',(4.540881390989,3.85)); +#147879 = CARTESIAN_POINT('',(4.614528166642,3.85)); +#147880 = CARTESIAN_POINT('',(4.688174942294,3.85)); +#147881 = CARTESIAN_POINT('',(4.737272792729,3.85)); +#147882 = CARTESIAN_POINT('',(4.761821717947,3.85)); +#147883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147884 = PCURVE('',#89206,#147885); +#147885 = DEFINITIONAL_REPRESENTATION('',(#147886),#147894); +#147886 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147887,#147888,#147889, + #147890,#147891,#147892,#147893),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#145495 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#145496 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#145497 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#145498 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#145499 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#145500 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#145501 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#145502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145503 = ORIENTED_EDGE('',*,*,#145504,.F.); -#145504 = EDGE_CURVE('',#145505,#145455,#145507,.T.); -#145505 = VERTEX_POINT('',#145506); -#145506 = CARTESIAN_POINT('',(3.65,10.419594812019,0.E+000)); -#145507 = SURFACE_CURVE('',#145508,(#145512,#145518),.PCURVE_S1.); -#145508 = LINE('',#145509,#145510); -#145509 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#147887 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#147888 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#147889 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#147890 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#147891 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#147892 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#147893 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#147894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147895 = ORIENTED_EDGE('',*,*,#147896,.F.); +#147896 = EDGE_CURVE('',#147897,#147847,#147899,.T.); +#147897 = VERTEX_POINT('',#147898); +#147898 = CARTESIAN_POINT('',(3.65,10.419594812019,0.E+000)); +#147899 = SURFACE_CURVE('',#147900,(#147904,#147910),.PCURVE_S1.); +#147900 = LINE('',#147901,#147902); +#147901 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#145510 = VECTOR('',#145511,1.); -#145511 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145512 = PCURVE('',#145335,#145513); -#145513 = DEFINITIONAL_REPRESENTATION('',(#145514),#145517); -#145514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145515,#145516), +#147902 = VECTOR('',#147903,1.); +#147903 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147904 = PCURVE('',#147727,#147905); +#147905 = DEFINITIONAL_REPRESENTATION('',(#147906),#147909); +#147906 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147907,#147908), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#145515 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#145516 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#145517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147907 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#147908 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#147909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145518 = PCURVE('',#145519,#145524); -#145519 = PLANE('',#145520); -#145520 = AXIS2_PLACEMENT_3D('',#145521,#145522,#145523); -#145521 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#147910 = PCURVE('',#147911,#147916); +#147911 = PLANE('',#147912); +#147912 = AXIS2_PLACEMENT_3D('',#147913,#147914,#147915); +#147913 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#145522 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145523 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145524 = DEFINITIONAL_REPRESENTATION('',(#145525),#145529); -#145525 = LINE('',#145526,#145527); -#145526 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#145527 = VECTOR('',#145528,1.); -#145528 = DIRECTION('',(-1.,0.E+000)); -#145529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145530 = ORIENTED_EDGE('',*,*,#145531,.T.); -#145531 = EDGE_CURVE('',#145505,#145241,#145532,.T.); -#145532 = SURFACE_CURVE('',#145533,(#145538,#145567),.PCURVE_S1.); -#145533 = CIRCLE('',#145534,0.308574064194); -#145534 = AXIS2_PLACEMENT_3D('',#145535,#145536,#145537); -#145535 = CARTESIAN_POINT('',(3.65,10.728168876214,2.640924866458E-017) - ); -#145536 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145537 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145538 = PCURVE('',#145335,#145539); -#145539 = DEFINITIONAL_REPRESENTATION('',(#145540),#145566); -#145540 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#145541,#145542,#145543, - #145544,#145545,#145546,#145547,#145548,#145549,#145550,#145551, - #145552,#145553,#145554,#145555,#145556,#145557,#145558,#145559, - #145560,#145561,#145562,#145563,#145564,#145565),.UNSPECIFIED.,.F., +#147914 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147915 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#147916 = DEFINITIONAL_REPRESENTATION('',(#147917),#147921); +#147917 = LINE('',#147918,#147919); +#147918 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#147919 = VECTOR('',#147920,1.); +#147920 = DIRECTION('',(-1.,0.E+000)); +#147921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147922 = ORIENTED_EDGE('',*,*,#147923,.T.); +#147923 = EDGE_CURVE('',#147897,#147633,#147924,.T.); +#147924 = SURFACE_CURVE('',#147925,(#147930,#147959),.PCURVE_S1.); +#147925 = CIRCLE('',#147926,0.308574064194); +#147926 = AXIS2_PLACEMENT_3D('',#147927,#147928,#147929); +#147927 = CARTESIAN_POINT('',(3.65,10.728168876214,2.640924866458E-017) + ); +#147928 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147929 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147930 = PCURVE('',#147727,#147931); +#147931 = DEFINITIONAL_REPRESENTATION('',(#147932),#147958); +#147932 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147933,#147934,#147935, + #147936,#147937,#147938,#147939,#147940,#147941,#147942,#147943, + #147944,#147945,#147946,#147947,#147948,#147949,#147950,#147951, + #147952,#147953,#147954,#147955,#147956,#147957),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -179464,994 +182466,994 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#145541 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#145542 = CARTESIAN_POINT('',(3.166141578807,3.65)); -#145543 = CARTESIAN_POINT('',(3.215239429242,3.65)); -#145544 = CARTESIAN_POINT('',(3.288886204895,3.65)); -#145545 = CARTESIAN_POINT('',(3.362532980548,3.65)); -#145546 = CARTESIAN_POINT('',(3.4361797562,3.65)); -#145547 = CARTESIAN_POINT('',(3.509826531853,3.65)); -#145548 = CARTESIAN_POINT('',(3.583473307505,3.65)); -#145549 = CARTESIAN_POINT('',(3.657120083158,3.65)); -#145550 = CARTESIAN_POINT('',(3.730766858811,3.65)); -#145551 = CARTESIAN_POINT('',(3.804413634463,3.65)); -#145552 = CARTESIAN_POINT('',(3.878060410116,3.65)); -#145553 = CARTESIAN_POINT('',(3.951707185768,3.65)); -#145554 = CARTESIAN_POINT('',(4.025353961421,3.65)); -#145555 = CARTESIAN_POINT('',(4.099000737074,3.65)); -#145556 = CARTESIAN_POINT('',(4.172647512726,3.65)); -#145557 = CARTESIAN_POINT('',(4.246294288379,3.65)); -#145558 = CARTESIAN_POINT('',(4.319941064031,3.65)); -#145559 = CARTESIAN_POINT('',(4.393587839684,3.65)); -#145560 = CARTESIAN_POINT('',(4.467234615337,3.65)); -#145561 = CARTESIAN_POINT('',(4.540881390989,3.65)); -#145562 = CARTESIAN_POINT('',(4.614528166642,3.65)); -#145563 = CARTESIAN_POINT('',(4.688174942294,3.65)); -#145564 = CARTESIAN_POINT('',(4.737272792729,3.65)); -#145565 = CARTESIAN_POINT('',(4.761821717947,3.65)); -#145566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145567 = PCURVE('',#86870,#145568); -#145568 = DEFINITIONAL_REPRESENTATION('',(#145569),#145573); -#145569 = CIRCLE('',#145570,0.308574064194); -#145570 = AXIS2_PLACEMENT_2D('',#145571,#145572); -#145571 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#145572 = DIRECTION('',(0.E+000,1.)); -#145573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145574 = ADVANCED_FACE('',(#145575),#145439,.F.); -#145575 = FACE_BOUND('',#145576,.F.); -#145576 = EDGE_LOOP('',(#145577,#145578,#145605,#145632)); -#145577 = ORIENTED_EDGE('',*,*,#145425,.T.); -#145578 = ORIENTED_EDGE('',*,*,#145579,.F.); -#145579 = EDGE_CURVE('',#145580,#145350,#145582,.T.); -#145580 = VERTEX_POINT('',#145581); -#145581 = CARTESIAN_POINT('',(3.85,10.51959417205,0.E+000)); -#145582 = SURFACE_CURVE('',#145583,(#145588,#145594),.PCURVE_S1.); -#145583 = CIRCLE('',#145584,0.208574704164); -#145584 = AXIS2_PLACEMENT_3D('',#145585,#145586,#145587); -#145585 = CARTESIAN_POINT('',(3.85,10.728168876214,2.640924866458E-017) - ); -#145586 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145587 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145588 = PCURVE('',#145439,#145589); -#145589 = DEFINITIONAL_REPRESENTATION('',(#145590),#145593); -#145590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145591,#145592), +#147933 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#147934 = CARTESIAN_POINT('',(3.166141578807,3.65)); +#147935 = CARTESIAN_POINT('',(3.215239429242,3.65)); +#147936 = CARTESIAN_POINT('',(3.288886204895,3.65)); +#147937 = CARTESIAN_POINT('',(3.362532980548,3.65)); +#147938 = CARTESIAN_POINT('',(3.4361797562,3.65)); +#147939 = CARTESIAN_POINT('',(3.509826531853,3.65)); +#147940 = CARTESIAN_POINT('',(3.583473307505,3.65)); +#147941 = CARTESIAN_POINT('',(3.657120083158,3.65)); +#147942 = CARTESIAN_POINT('',(3.730766858811,3.65)); +#147943 = CARTESIAN_POINT('',(3.804413634463,3.65)); +#147944 = CARTESIAN_POINT('',(3.878060410116,3.65)); +#147945 = CARTESIAN_POINT('',(3.951707185768,3.65)); +#147946 = CARTESIAN_POINT('',(4.025353961421,3.65)); +#147947 = CARTESIAN_POINT('',(4.099000737074,3.65)); +#147948 = CARTESIAN_POINT('',(4.172647512726,3.65)); +#147949 = CARTESIAN_POINT('',(4.246294288379,3.65)); +#147950 = CARTESIAN_POINT('',(4.319941064031,3.65)); +#147951 = CARTESIAN_POINT('',(4.393587839684,3.65)); +#147952 = CARTESIAN_POINT('',(4.467234615337,3.65)); +#147953 = CARTESIAN_POINT('',(4.540881390989,3.65)); +#147954 = CARTESIAN_POINT('',(4.614528166642,3.65)); +#147955 = CARTESIAN_POINT('',(4.688174942294,3.65)); +#147956 = CARTESIAN_POINT('',(4.737272792729,3.65)); +#147957 = CARTESIAN_POINT('',(4.761821717947,3.65)); +#147958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147959 = PCURVE('',#89262,#147960); +#147960 = DEFINITIONAL_REPRESENTATION('',(#147961),#147965); +#147961 = CIRCLE('',#147962,0.308574064194); +#147962 = AXIS2_PLACEMENT_2D('',#147963,#147964); +#147963 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#147964 = DIRECTION('',(0.E+000,1.)); +#147965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147966 = ADVANCED_FACE('',(#147967),#147831,.F.); +#147967 = FACE_BOUND('',#147968,.F.); +#147968 = EDGE_LOOP('',(#147969,#147970,#147997,#148024)); +#147969 = ORIENTED_EDGE('',*,*,#147817,.T.); +#147970 = ORIENTED_EDGE('',*,*,#147971,.F.); +#147971 = EDGE_CURVE('',#147972,#147742,#147974,.T.); +#147972 = VERTEX_POINT('',#147973); +#147973 = CARTESIAN_POINT('',(3.85,10.51959417205,0.E+000)); +#147974 = SURFACE_CURVE('',#147975,(#147980,#147986),.PCURVE_S1.); +#147975 = CIRCLE('',#147976,0.208574704164); +#147976 = AXIS2_PLACEMENT_3D('',#147977,#147978,#147979); +#147977 = CARTESIAN_POINT('',(3.85,10.728168876214,2.640924866458E-017) + ); +#147978 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#147979 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#147980 = PCURVE('',#147831,#147981); +#147981 = DEFINITIONAL_REPRESENTATION('',(#147982),#147985); +#147982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147983,#147984), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#145591 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#145592 = CARTESIAN_POINT('',(4.772630242227,3.85)); -#145593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#147983 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#147984 = CARTESIAN_POINT('',(4.772630242227,3.85)); +#147985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145594 = PCURVE('',#86814,#145595); -#145595 = DEFINITIONAL_REPRESENTATION('',(#145596),#145604); -#145596 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145597,#145598,#145599, - #145600,#145601,#145602,#145603),.UNSPECIFIED.,.T.,.F.) +#147986 = PCURVE('',#89206,#147987); +#147987 = DEFINITIONAL_REPRESENTATION('',(#147988),#147996); +#147988 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147989,#147990,#147991, + #147992,#147993,#147994,#147995),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#145597 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#145598 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#145599 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#145600 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#145601 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#145602 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#145603 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#145604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145605 = ORIENTED_EDGE('',*,*,#145606,.T.); -#145606 = EDGE_CURVE('',#145580,#145607,#145609,.T.); -#145607 = VERTEX_POINT('',#145608); -#145608 = CARTESIAN_POINT('',(3.65,10.51959417205,0.E+000)); -#145609 = SURFACE_CURVE('',#145610,(#145614,#145620),.PCURVE_S1.); -#145610 = LINE('',#145611,#145612); -#145611 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#147989 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#147990 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#147991 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#147992 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#147993 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#147994 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#147995 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#147996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#147997 = ORIENTED_EDGE('',*,*,#147998,.T.); +#147998 = EDGE_CURVE('',#147972,#147999,#148001,.T.); +#147999 = VERTEX_POINT('',#148000); +#148000 = CARTESIAN_POINT('',(3.65,10.51959417205,0.E+000)); +#148001 = SURFACE_CURVE('',#148002,(#148006,#148012),.PCURVE_S1.); +#148002 = LINE('',#148003,#148004); +#148003 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#145612 = VECTOR('',#145613,1.); -#145613 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145614 = PCURVE('',#145439,#145615); -#145615 = DEFINITIONAL_REPRESENTATION('',(#145616),#145619); -#145616 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145617,#145618), +#148004 = VECTOR('',#148005,1.); +#148005 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148006 = PCURVE('',#147831,#148007); +#148007 = DEFINITIONAL_REPRESENTATION('',(#148008),#148011); +#148008 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148009,#148010), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#145617 = CARTESIAN_POINT('',(3.14159265359,3.85)); -#145618 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#145619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148009 = CARTESIAN_POINT('',(3.14159265359,3.85)); +#148010 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#148011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145620 = PCURVE('',#145621,#145626); -#145621 = PLANE('',#145622); -#145622 = AXIS2_PLACEMENT_3D('',#145623,#145624,#145625); -#145623 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#148012 = PCURVE('',#148013,#148018); +#148013 = PLANE('',#148014); +#148014 = AXIS2_PLACEMENT_3D('',#148015,#148016,#148017); +#148015 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#145624 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145625 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145626 = DEFINITIONAL_REPRESENTATION('',(#145627),#145631); -#145627 = LINE('',#145628,#145629); -#145628 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#145629 = VECTOR('',#145630,1.); -#145630 = DIRECTION('',(-1.,0.E+000)); -#145631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145632 = ORIENTED_EDGE('',*,*,#145633,.T.); -#145633 = EDGE_CURVE('',#145607,#145403,#145634,.T.); -#145634 = SURFACE_CURVE('',#145635,(#145640,#145646),.PCURVE_S1.); -#145635 = CIRCLE('',#145636,0.208574704164); -#145636 = AXIS2_PLACEMENT_3D('',#145637,#145638,#145639); -#145637 = CARTESIAN_POINT('',(3.65,10.728168876214,2.640924866458E-017) - ); -#145638 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145639 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#145640 = PCURVE('',#145439,#145641); -#145641 = DEFINITIONAL_REPRESENTATION('',(#145642),#145645); -#145642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145643,#145644), +#148016 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148017 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148018 = DEFINITIONAL_REPRESENTATION('',(#148019),#148023); +#148019 = LINE('',#148020,#148021); +#148020 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#148021 = VECTOR('',#148022,1.); +#148022 = DIRECTION('',(-1.,0.E+000)); +#148023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148024 = ORIENTED_EDGE('',*,*,#148025,.T.); +#148025 = EDGE_CURVE('',#147999,#147795,#148026,.T.); +#148026 = SURFACE_CURVE('',#148027,(#148032,#148038),.PCURVE_S1.); +#148027 = CIRCLE('',#148028,0.208574704164); +#148028 = AXIS2_PLACEMENT_3D('',#148029,#148030,#148031); +#148029 = CARTESIAN_POINT('',(3.65,10.728168876214,2.640924866458E-017) + ); +#148030 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148031 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148032 = PCURVE('',#147831,#148033); +#148033 = DEFINITIONAL_REPRESENTATION('',(#148034),#148037); +#148034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148035,#148036), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#145643 = CARTESIAN_POINT('',(3.14159265359,3.65)); -#145644 = CARTESIAN_POINT('',(4.772630242227,3.65)); -#145645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145646 = PCURVE('',#86870,#145647); -#145647 = DEFINITIONAL_REPRESENTATION('',(#145648),#145652); -#145648 = CIRCLE('',#145649,0.208574704164); -#145649 = AXIS2_PLACEMENT_2D('',#145650,#145651); -#145650 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#145651 = DIRECTION('',(0.E+000,1.)); -#145652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145653 = ADVANCED_FACE('',(#145654),#145621,.F.); -#145654 = FACE_BOUND('',#145655,.T.); -#145655 = EDGE_LOOP('',(#145656,#145685,#145706,#145707)); -#145656 = ORIENTED_EDGE('',*,*,#145657,.F.); -#145657 = EDGE_CURVE('',#145658,#145660,#145662,.T.); -#145658 = VERTEX_POINT('',#145659); -#145659 = CARTESIAN_POINT('',(3.85,10.51959417205,0.530776333563)); -#145660 = VERTEX_POINT('',#145661); -#145661 = CARTESIAN_POINT('',(3.65,10.51959417205,0.530776333563)); -#145662 = SURFACE_CURVE('',#145663,(#145667,#145674),.PCURVE_S1.); -#145663 = LINE('',#145664,#145665); -#145664 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#148035 = CARTESIAN_POINT('',(3.14159265359,3.65)); +#148036 = CARTESIAN_POINT('',(4.772630242227,3.65)); +#148037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148038 = PCURVE('',#89262,#148039); +#148039 = DEFINITIONAL_REPRESENTATION('',(#148040),#148044); +#148040 = CIRCLE('',#148041,0.208574704164); +#148041 = AXIS2_PLACEMENT_2D('',#148042,#148043); +#148042 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#148043 = DIRECTION('',(0.E+000,1.)); +#148044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148045 = ADVANCED_FACE('',(#148046),#148013,.F.); +#148046 = FACE_BOUND('',#148047,.T.); +#148047 = EDGE_LOOP('',(#148048,#148077,#148098,#148099)); +#148048 = ORIENTED_EDGE('',*,*,#148049,.F.); +#148049 = EDGE_CURVE('',#148050,#148052,#148054,.T.); +#148050 = VERTEX_POINT('',#148051); +#148051 = CARTESIAN_POINT('',(3.85,10.51959417205,0.530776333563)); +#148052 = VERTEX_POINT('',#148053); +#148053 = CARTESIAN_POINT('',(3.65,10.51959417205,0.530776333563)); +#148054 = SURFACE_CURVE('',#148055,(#148059,#148066),.PCURVE_S1.); +#148055 = LINE('',#148056,#148057); +#148056 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#145665 = VECTOR('',#145666,1.); -#145666 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145667 = PCURVE('',#145621,#145668); -#145668 = DEFINITIONAL_REPRESENTATION('',(#145669),#145673); -#145669 = LINE('',#145670,#145671); -#145670 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145671 = VECTOR('',#145672,1.); -#145672 = DIRECTION('',(-1.,0.E+000)); -#145673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145674 = PCURVE('',#145675,#145680); -#145675 = CYLINDRICAL_SURFACE('',#145676,0.2192697516); -#145676 = AXIS2_PLACEMENT_3D('',#145677,#145678,#145679); -#145677 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#148057 = VECTOR('',#148058,1.); +#148058 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148059 = PCURVE('',#148013,#148060); +#148060 = DEFINITIONAL_REPRESENTATION('',(#148061),#148065); +#148061 = LINE('',#148062,#148063); +#148062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148063 = VECTOR('',#148064,1.); +#148064 = DIRECTION('',(-1.,0.E+000)); +#148065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148066 = PCURVE('',#148067,#148072); +#148067 = CYLINDRICAL_SURFACE('',#148068,0.2192697516); +#148068 = AXIS2_PLACEMENT_3D('',#148069,#148070,#148071); +#148069 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#145678 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145679 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145680 = DEFINITIONAL_REPRESENTATION('',(#145681),#145684); -#145681 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145682,#145683), +#148070 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148071 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148072 = DEFINITIONAL_REPRESENTATION('',(#148073),#148076); +#148073 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148074,#148075), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.85,-3.65),.PIECEWISE_BEZIER_KNOTS.); -#145682 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#145683 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#145684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145685 = ORIENTED_EDGE('',*,*,#145686,.T.); -#145686 = EDGE_CURVE('',#145658,#145580,#145687,.T.); -#145687 = SURFACE_CURVE('',#145688,(#145692,#145699),.PCURVE_S1.); -#145688 = LINE('',#145689,#145690); -#145689 = CARTESIAN_POINT('',(3.85,10.51959417205,0.530776333563)); -#145690 = VECTOR('',#145691,1.); -#145691 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#145692 = PCURVE('',#145621,#145693); -#145693 = DEFINITIONAL_REPRESENTATION('',(#145694),#145698); -#145694 = LINE('',#145695,#145696); -#145695 = CARTESIAN_POINT('',(3.85,0.E+000)); -#145696 = VECTOR('',#145697,1.); -#145697 = DIRECTION('',(0.E+000,-1.)); -#145698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145699 = PCURVE('',#86814,#145700); -#145700 = DEFINITIONAL_REPRESENTATION('',(#145701),#145705); -#145701 = LINE('',#145702,#145703); -#145702 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#145703 = VECTOR('',#145704,1.); -#145704 = DIRECTION('',(-1.,0.E+000)); -#145705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145706 = ORIENTED_EDGE('',*,*,#145606,.T.); -#145707 = ORIENTED_EDGE('',*,*,#145708,.F.); -#145708 = EDGE_CURVE('',#145660,#145607,#145709,.T.); -#145709 = SURFACE_CURVE('',#145710,(#145714,#145721),.PCURVE_S1.); -#145710 = LINE('',#145711,#145712); -#145711 = CARTESIAN_POINT('',(3.65,10.51959417205,0.530776333563)); -#145712 = VECTOR('',#145713,1.); -#145713 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#145714 = PCURVE('',#145621,#145715); -#145715 = DEFINITIONAL_REPRESENTATION('',(#145716),#145720); -#145716 = LINE('',#145717,#145718); -#145717 = CARTESIAN_POINT('',(3.65,0.E+000)); -#145718 = VECTOR('',#145719,1.); -#145719 = DIRECTION('',(0.E+000,-1.)); -#145720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145721 = PCURVE('',#86870,#145722); -#145722 = DEFINITIONAL_REPRESENTATION('',(#145723),#145727); -#145723 = LINE('',#145724,#145725); -#145724 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#145725 = VECTOR('',#145726,1.); -#145726 = DIRECTION('',(1.,0.E+000)); -#145727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145728 = ADVANCED_FACE('',(#145729),#145519,.F.); -#145729 = FACE_BOUND('',#145730,.T.); -#145730 = EDGE_LOOP('',(#145731,#145760,#145781,#145782)); -#145731 = ORIENTED_EDGE('',*,*,#145732,.F.); -#145732 = EDGE_CURVE('',#145733,#145735,#145737,.T.); -#145733 = VERTEX_POINT('',#145734); -#145734 = CARTESIAN_POINT('',(3.65,10.419594812019,0.530776333563)); -#145735 = VERTEX_POINT('',#145736); -#145736 = CARTESIAN_POINT('',(3.85,10.419594812019,0.530776333563)); -#145737 = SURFACE_CURVE('',#145738,(#145742,#145749),.PCURVE_S1.); -#145738 = LINE('',#145739,#145740); -#145739 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#148074 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#148075 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#148076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148077 = ORIENTED_EDGE('',*,*,#148078,.T.); +#148078 = EDGE_CURVE('',#148050,#147972,#148079,.T.); +#148079 = SURFACE_CURVE('',#148080,(#148084,#148091),.PCURVE_S1.); +#148080 = LINE('',#148081,#148082); +#148081 = CARTESIAN_POINT('',(3.85,10.51959417205,0.530776333563)); +#148082 = VECTOR('',#148083,1.); +#148083 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148084 = PCURVE('',#148013,#148085); +#148085 = DEFINITIONAL_REPRESENTATION('',(#148086),#148090); +#148086 = LINE('',#148087,#148088); +#148087 = CARTESIAN_POINT('',(3.85,0.E+000)); +#148088 = VECTOR('',#148089,1.); +#148089 = DIRECTION('',(0.E+000,-1.)); +#148090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148091 = PCURVE('',#89206,#148092); +#148092 = DEFINITIONAL_REPRESENTATION('',(#148093),#148097); +#148093 = LINE('',#148094,#148095); +#148094 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#148095 = VECTOR('',#148096,1.); +#148096 = DIRECTION('',(-1.,0.E+000)); +#148097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148098 = ORIENTED_EDGE('',*,*,#147998,.T.); +#148099 = ORIENTED_EDGE('',*,*,#148100,.F.); +#148100 = EDGE_CURVE('',#148052,#147999,#148101,.T.); +#148101 = SURFACE_CURVE('',#148102,(#148106,#148113),.PCURVE_S1.); +#148102 = LINE('',#148103,#148104); +#148103 = CARTESIAN_POINT('',(3.65,10.51959417205,0.530776333563)); +#148104 = VECTOR('',#148105,1.); +#148105 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148106 = PCURVE('',#148013,#148107); +#148107 = DEFINITIONAL_REPRESENTATION('',(#148108),#148112); +#148108 = LINE('',#148109,#148110); +#148109 = CARTESIAN_POINT('',(3.65,0.E+000)); +#148110 = VECTOR('',#148111,1.); +#148111 = DIRECTION('',(0.E+000,-1.)); +#148112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148113 = PCURVE('',#89262,#148114); +#148114 = DEFINITIONAL_REPRESENTATION('',(#148115),#148119); +#148115 = LINE('',#148116,#148117); +#148116 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#148117 = VECTOR('',#148118,1.); +#148118 = DIRECTION('',(1.,0.E+000)); +#148119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148120 = ADVANCED_FACE('',(#148121),#147911,.F.); +#148121 = FACE_BOUND('',#148122,.T.); +#148122 = EDGE_LOOP('',(#148123,#148152,#148173,#148174)); +#148123 = ORIENTED_EDGE('',*,*,#148124,.F.); +#148124 = EDGE_CURVE('',#148125,#148127,#148129,.T.); +#148125 = VERTEX_POINT('',#148126); +#148126 = CARTESIAN_POINT('',(3.65,10.419594812019,0.530776333563)); +#148127 = VERTEX_POINT('',#148128); +#148128 = CARTESIAN_POINT('',(3.85,10.419594812019,0.530776333563)); +#148129 = SURFACE_CURVE('',#148130,(#148134,#148141),.PCURVE_S1.); +#148130 = LINE('',#148131,#148132); +#148131 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#145740 = VECTOR('',#145741,1.); -#145741 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145742 = PCURVE('',#145519,#145743); -#145743 = DEFINITIONAL_REPRESENTATION('',(#145744),#145748); -#145744 = LINE('',#145745,#145746); -#145745 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145746 = VECTOR('',#145747,1.); -#145747 = DIRECTION('',(-1.,0.E+000)); -#145748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145749 = PCURVE('',#145750,#145755); -#145750 = CYLINDRICAL_SURFACE('',#145751,0.119270391569); -#145751 = AXIS2_PLACEMENT_3D('',#145752,#145753,#145754); -#145752 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#148132 = VECTOR('',#148133,1.); +#148133 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148134 = PCURVE('',#147911,#148135); +#148135 = DEFINITIONAL_REPRESENTATION('',(#148136),#148140); +#148136 = LINE('',#148137,#148138); +#148137 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148138 = VECTOR('',#148139,1.); +#148139 = DIRECTION('',(-1.,0.E+000)); +#148140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148141 = PCURVE('',#148142,#148147); +#148142 = CYLINDRICAL_SURFACE('',#148143,0.119270391569); +#148143 = AXIS2_PLACEMENT_3D('',#148144,#148145,#148146); +#148144 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#145753 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145754 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145755 = DEFINITIONAL_REPRESENTATION('',(#145756),#145759); -#145756 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145757,#145758), +#148145 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148146 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148147 = DEFINITIONAL_REPRESENTATION('',(#148148),#148151); +#148148 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148149,#148150), .UNSPECIFIED.,.F.,.F.,(2,2),(3.65,3.85),.PIECEWISE_BEZIER_KNOTS.); -#145757 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#145758 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#145759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145760 = ORIENTED_EDGE('',*,*,#145761,.T.); -#145761 = EDGE_CURVE('',#145733,#145505,#145762,.T.); -#145762 = SURFACE_CURVE('',#145763,(#145767,#145774),.PCURVE_S1.); -#145763 = LINE('',#145764,#145765); -#145764 = CARTESIAN_POINT('',(3.65,10.419594812019,0.530776333563)); -#145765 = VECTOR('',#145766,1.); -#145766 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#145767 = PCURVE('',#145519,#145768); -#145768 = DEFINITIONAL_REPRESENTATION('',(#145769),#145773); -#145769 = LINE('',#145770,#145771); -#145770 = CARTESIAN_POINT('',(-3.65,0.E+000)); -#145771 = VECTOR('',#145772,1.); -#145772 = DIRECTION('',(0.E+000,-1.)); -#145773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145774 = PCURVE('',#86870,#145775); -#145775 = DEFINITIONAL_REPRESENTATION('',(#145776),#145780); -#145776 = LINE('',#145777,#145778); -#145777 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#145778 = VECTOR('',#145779,1.); -#145779 = DIRECTION('',(1.,0.E+000)); -#145780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145781 = ORIENTED_EDGE('',*,*,#145504,.T.); -#145782 = ORIENTED_EDGE('',*,*,#145783,.F.); -#145783 = EDGE_CURVE('',#145735,#145455,#145784,.T.); -#145784 = SURFACE_CURVE('',#145785,(#145789,#145796),.PCURVE_S1.); -#145785 = LINE('',#145786,#145787); -#145786 = CARTESIAN_POINT('',(3.85,10.419594812019,0.530776333563)); -#145787 = VECTOR('',#145788,1.); -#145788 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#145789 = PCURVE('',#145519,#145790); -#145790 = DEFINITIONAL_REPRESENTATION('',(#145791),#145795); -#145791 = LINE('',#145792,#145793); -#145792 = CARTESIAN_POINT('',(-3.85,0.E+000)); -#145793 = VECTOR('',#145794,1.); -#145794 = DIRECTION('',(0.E+000,-1.)); -#145795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145796 = PCURVE('',#86814,#145797); -#145797 = DEFINITIONAL_REPRESENTATION('',(#145798),#145802); -#145798 = LINE('',#145799,#145800); -#145799 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#145800 = VECTOR('',#145801,1.); -#145801 = DIRECTION('',(-1.,0.E+000)); -#145802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145803 = ADVANCED_FACE('',(#145804),#145675,.T.); -#145804 = FACE_BOUND('',#145805,.T.); -#145805 = EDGE_LOOP('',(#145806,#145829,#145830,#145857)); -#145806 = ORIENTED_EDGE('',*,*,#145807,.T.); -#145807 = EDGE_CURVE('',#145808,#145658,#145810,.T.); -#145808 = VERTEX_POINT('',#145809); -#145809 = CARTESIAN_POINT('',(3.85,10.304819755875,0.75)); -#145810 = SURFACE_CURVE('',#145811,(#145816,#145822),.PCURVE_S1.); -#145811 = CIRCLE('',#145812,0.2192697516); -#145812 = AXIS2_PLACEMENT_3D('',#145813,#145814,#145815); -#145813 = CARTESIAN_POINT('',(3.85,10.30032442045,0.530776333563)); -#145814 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145815 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145816 = PCURVE('',#145675,#145817); -#145817 = DEFINITIONAL_REPRESENTATION('',(#145818),#145821); -#145818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145819,#145820), +#148149 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#148150 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#148151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148152 = ORIENTED_EDGE('',*,*,#148153,.T.); +#148153 = EDGE_CURVE('',#148125,#147897,#148154,.T.); +#148154 = SURFACE_CURVE('',#148155,(#148159,#148166),.PCURVE_S1.); +#148155 = LINE('',#148156,#148157); +#148156 = CARTESIAN_POINT('',(3.65,10.419594812019,0.530776333563)); +#148157 = VECTOR('',#148158,1.); +#148158 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148159 = PCURVE('',#147911,#148160); +#148160 = DEFINITIONAL_REPRESENTATION('',(#148161),#148165); +#148161 = LINE('',#148162,#148163); +#148162 = CARTESIAN_POINT('',(-3.65,0.E+000)); +#148163 = VECTOR('',#148164,1.); +#148164 = DIRECTION('',(0.E+000,-1.)); +#148165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148166 = PCURVE('',#89262,#148167); +#148167 = DEFINITIONAL_REPRESENTATION('',(#148168),#148172); +#148168 = LINE('',#148169,#148170); +#148169 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#148170 = VECTOR('',#148171,1.); +#148171 = DIRECTION('',(1.,0.E+000)); +#148172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148173 = ORIENTED_EDGE('',*,*,#147896,.T.); +#148174 = ORIENTED_EDGE('',*,*,#148175,.F.); +#148175 = EDGE_CURVE('',#148127,#147847,#148176,.T.); +#148176 = SURFACE_CURVE('',#148177,(#148181,#148188),.PCURVE_S1.); +#148177 = LINE('',#148178,#148179); +#148178 = CARTESIAN_POINT('',(3.85,10.419594812019,0.530776333563)); +#148179 = VECTOR('',#148180,1.); +#148180 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148181 = PCURVE('',#147911,#148182); +#148182 = DEFINITIONAL_REPRESENTATION('',(#148183),#148187); +#148183 = LINE('',#148184,#148185); +#148184 = CARTESIAN_POINT('',(-3.85,0.E+000)); +#148185 = VECTOR('',#148186,1.); +#148186 = DIRECTION('',(0.E+000,-1.)); +#148187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148188 = PCURVE('',#89206,#148189); +#148189 = DEFINITIONAL_REPRESENTATION('',(#148190),#148194); +#148190 = LINE('',#148191,#148192); +#148191 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#148192 = VECTOR('',#148193,1.); +#148193 = DIRECTION('',(-1.,0.E+000)); +#148194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148195 = ADVANCED_FACE('',(#148196),#148067,.T.); +#148196 = FACE_BOUND('',#148197,.T.); +#148197 = EDGE_LOOP('',(#148198,#148221,#148222,#148249)); +#148198 = ORIENTED_EDGE('',*,*,#148199,.T.); +#148199 = EDGE_CURVE('',#148200,#148050,#148202,.T.); +#148200 = VERTEX_POINT('',#148201); +#148201 = CARTESIAN_POINT('',(3.85,10.304819755875,0.75)); +#148202 = SURFACE_CURVE('',#148203,(#148208,#148214),.PCURVE_S1.); +#148203 = CIRCLE('',#148204,0.2192697516); +#148204 = AXIS2_PLACEMENT_3D('',#148205,#148206,#148207); +#148205 = CARTESIAN_POINT('',(3.85,10.30032442045,0.530776333563)); +#148206 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148207 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148208 = PCURVE('',#148067,#148209); +#148209 = DEFINITIONAL_REPRESENTATION('',(#148210),#148213); +#148210 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148211,#148212), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145819 = CARTESIAN_POINT('',(1.591299156552,-3.85)); -#145820 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#145821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145822 = PCURVE('',#86814,#145823); -#145823 = DEFINITIONAL_REPRESENTATION('',(#145824),#145828); -#145824 = CIRCLE('',#145825,0.2192697516); -#145825 = AXIS2_PLACEMENT_2D('',#145826,#145827); -#145826 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#145827 = DIRECTION('',(0.E+000,-1.)); -#145828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145829 = ORIENTED_EDGE('',*,*,#145657,.T.); -#145830 = ORIENTED_EDGE('',*,*,#145831,.F.); -#145831 = EDGE_CURVE('',#145832,#145660,#145834,.T.); -#145832 = VERTEX_POINT('',#145833); -#145833 = CARTESIAN_POINT('',(3.65,10.304819755875,0.75)); -#145834 = SURFACE_CURVE('',#145835,(#145840,#145846),.PCURVE_S1.); -#145835 = CIRCLE('',#145836,0.2192697516); -#145836 = AXIS2_PLACEMENT_3D('',#145837,#145838,#145839); -#145837 = CARTESIAN_POINT('',(3.65,10.30032442045,0.530776333563)); -#145838 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145839 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145840 = PCURVE('',#145675,#145841); -#145841 = DEFINITIONAL_REPRESENTATION('',(#145842),#145845); -#145842 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145843,#145844), +#148211 = CARTESIAN_POINT('',(1.591299156552,-3.85)); +#148212 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#148213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148214 = PCURVE('',#89206,#148215); +#148215 = DEFINITIONAL_REPRESENTATION('',(#148216),#148220); +#148216 = CIRCLE('',#148217,0.2192697516); +#148217 = AXIS2_PLACEMENT_2D('',#148218,#148219); +#148218 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#148219 = DIRECTION('',(0.E+000,-1.)); +#148220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148221 = ORIENTED_EDGE('',*,*,#148049,.T.); +#148222 = ORIENTED_EDGE('',*,*,#148223,.F.); +#148223 = EDGE_CURVE('',#148224,#148052,#148226,.T.); +#148224 = VERTEX_POINT('',#148225); +#148225 = CARTESIAN_POINT('',(3.65,10.304819755875,0.75)); +#148226 = SURFACE_CURVE('',#148227,(#148232,#148238),.PCURVE_S1.); +#148227 = CIRCLE('',#148228,0.2192697516); +#148228 = AXIS2_PLACEMENT_3D('',#148229,#148230,#148231); +#148229 = CARTESIAN_POINT('',(3.65,10.30032442045,0.530776333563)); +#148230 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148231 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148232 = PCURVE('',#148067,#148233); +#148233 = DEFINITIONAL_REPRESENTATION('',(#148234),#148237); +#148234 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148235,#148236), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145843 = CARTESIAN_POINT('',(1.591299156552,-3.65)); -#145844 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#145845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148235 = CARTESIAN_POINT('',(1.591299156552,-3.65)); +#148236 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#148237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145846 = PCURVE('',#86870,#145847); -#145847 = DEFINITIONAL_REPRESENTATION('',(#145848),#145856); -#145848 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145849,#145850,#145851, - #145852,#145853,#145854,#145855),.UNSPECIFIED.,.T.,.F.) +#148238 = PCURVE('',#89262,#148239); +#148239 = DEFINITIONAL_REPRESENTATION('',(#148240),#148248); +#148240 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148241,#148242,#148243, + #148244,#148245,#148246,#148247),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#145849 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#145850 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#145851 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#145852 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#145853 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#145854 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#145855 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#145856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145857 = ORIENTED_EDGE('',*,*,#145858,.T.); -#145858 = EDGE_CURVE('',#145832,#145808,#145859,.T.); -#145859 = SURFACE_CURVE('',#145860,(#145864,#145870),.PCURVE_S1.); -#145860 = LINE('',#145861,#145862); -#145861 = CARTESIAN_POINT('',(3.85,10.304819755875,0.75)); -#145862 = VECTOR('',#145863,1.); -#145863 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#145864 = PCURVE('',#145675,#145865); -#145865 = DEFINITIONAL_REPRESENTATION('',(#145866),#145869); -#145866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145867,#145868), +#148241 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#148242 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#148243 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#148244 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#148245 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#148246 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#148247 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#148248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148249 = ORIENTED_EDGE('',*,*,#148250,.T.); +#148250 = EDGE_CURVE('',#148224,#148200,#148251,.T.); +#148251 = SURFACE_CURVE('',#148252,(#148256,#148262),.PCURVE_S1.); +#148252 = LINE('',#148253,#148254); +#148253 = CARTESIAN_POINT('',(3.85,10.304819755875,0.75)); +#148254 = VECTOR('',#148255,1.); +#148255 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148256 = PCURVE('',#148067,#148257); +#148257 = DEFINITIONAL_REPRESENTATION('',(#148258),#148261); +#148258 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148259,#148260), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#145867 = CARTESIAN_POINT('',(1.591299156552,-3.65)); -#145868 = CARTESIAN_POINT('',(1.591299156552,-3.85)); -#145869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145870 = PCURVE('',#86842,#145871); -#145871 = DEFINITIONAL_REPRESENTATION('',(#145872),#145876); -#145872 = LINE('',#145873,#145874); -#145873 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#145874 = VECTOR('',#145875,1.); -#145875 = DIRECTION('',(-8.881784197001E-016,1.)); -#145876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145877 = ADVANCED_FACE('',(#145878),#145750,.F.); -#145878 = FACE_BOUND('',#145879,.F.); -#145879 = EDGE_LOOP('',(#145880,#145907,#145929,#145950)); -#145880 = ORIENTED_EDGE('',*,*,#145881,.F.); -#145881 = EDGE_CURVE('',#145882,#145733,#145884,.T.); -#145882 = VERTEX_POINT('',#145883); -#145883 = CARTESIAN_POINT('',(3.65,10.303662633502,0.65)); -#145884 = SURFACE_CURVE('',#145885,(#145890,#145896),.PCURVE_S1.); -#145885 = CIRCLE('',#145886,0.119270391569); -#145886 = AXIS2_PLACEMENT_3D('',#145887,#145888,#145889); -#145887 = CARTESIAN_POINT('',(3.65,10.30032442045,0.530776333563)); -#145888 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145889 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145890 = PCURVE('',#145750,#145891); -#145891 = DEFINITIONAL_REPRESENTATION('',(#145892),#145895); -#145892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145893,#145894), +#148259 = CARTESIAN_POINT('',(1.591299156552,-3.65)); +#148260 = CARTESIAN_POINT('',(1.591299156552,-3.85)); +#148261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148262 = PCURVE('',#89234,#148263); +#148263 = DEFINITIONAL_REPRESENTATION('',(#148264),#148268); +#148264 = LINE('',#148265,#148266); +#148265 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#148266 = VECTOR('',#148267,1.); +#148267 = DIRECTION('',(-8.881784197001E-016,1.)); +#148268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148269 = ADVANCED_FACE('',(#148270),#148142,.F.); +#148270 = FACE_BOUND('',#148271,.F.); +#148271 = EDGE_LOOP('',(#148272,#148299,#148321,#148342)); +#148272 = ORIENTED_EDGE('',*,*,#148273,.F.); +#148273 = EDGE_CURVE('',#148274,#148125,#148276,.T.); +#148274 = VERTEX_POINT('',#148275); +#148275 = CARTESIAN_POINT('',(3.65,10.303662633502,0.65)); +#148276 = SURFACE_CURVE('',#148277,(#148282,#148288),.PCURVE_S1.); +#148277 = CIRCLE('',#148278,0.119270391569); +#148278 = AXIS2_PLACEMENT_3D('',#148279,#148280,#148281); +#148279 = CARTESIAN_POINT('',(3.65,10.30032442045,0.530776333563)); +#148280 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148281 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148282 = PCURVE('',#148142,#148283); +#148283 = DEFINITIONAL_REPRESENTATION('',(#148284),#148287); +#148284 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148285,#148286), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145893 = CARTESIAN_POINT('',(1.598788597134,-3.65)); -#145894 = CARTESIAN_POINT('',(3.14159265359,-3.65)); -#145895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148285 = CARTESIAN_POINT('',(1.598788597134,-3.65)); +#148286 = CARTESIAN_POINT('',(3.14159265359,-3.65)); +#148287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#145896 = PCURVE('',#86870,#145897); -#145897 = DEFINITIONAL_REPRESENTATION('',(#145898),#145906); -#145898 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#145899,#145900,#145901, - #145902,#145903,#145904,#145905),.UNSPECIFIED.,.T.,.F.) +#148288 = PCURVE('',#89262,#148289); +#148289 = DEFINITIONAL_REPRESENTATION('',(#148290),#148298); +#148290 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148291,#148292,#148293, + #148294,#148295,#148296,#148297),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#145899 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#145900 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#145901 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#145902 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#145903 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#145904 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#145905 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#145906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145907 = ORIENTED_EDGE('',*,*,#145908,.F.); -#145908 = EDGE_CURVE('',#145909,#145882,#145911,.T.); -#145909 = VERTEX_POINT('',#145910); -#145910 = CARTESIAN_POINT('',(3.85,10.303662633502,0.65)); -#145911 = SURFACE_CURVE('',#145912,(#145916,#145922),.PCURVE_S1.); -#145912 = LINE('',#145913,#145914); -#145913 = CARTESIAN_POINT('',(3.85,10.303662633502,0.65)); -#145914 = VECTOR('',#145915,1.); -#145915 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145916 = PCURVE('',#145750,#145917); -#145917 = DEFINITIONAL_REPRESENTATION('',(#145918),#145921); -#145918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145919,#145920), +#148291 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#148292 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#148293 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#148294 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#148295 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#148296 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#148297 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#148298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148299 = ORIENTED_EDGE('',*,*,#148300,.F.); +#148300 = EDGE_CURVE('',#148301,#148274,#148303,.T.); +#148301 = VERTEX_POINT('',#148302); +#148302 = CARTESIAN_POINT('',(3.85,10.303662633502,0.65)); +#148303 = SURFACE_CURVE('',#148304,(#148308,#148314),.PCURVE_S1.); +#148304 = LINE('',#148305,#148306); +#148305 = CARTESIAN_POINT('',(3.85,10.303662633502,0.65)); +#148306 = VECTOR('',#148307,1.); +#148307 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148308 = PCURVE('',#148142,#148309); +#148309 = DEFINITIONAL_REPRESENTATION('',(#148310),#148313); +#148310 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148311,#148312), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#145919 = CARTESIAN_POINT('',(1.598788597134,-3.85)); -#145920 = CARTESIAN_POINT('',(1.598788597134,-3.65)); -#145921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145922 = PCURVE('',#86896,#145923); -#145923 = DEFINITIONAL_REPRESENTATION('',(#145924),#145928); -#145924 = LINE('',#145925,#145926); -#145925 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#145926 = VECTOR('',#145927,1.); -#145927 = DIRECTION('',(-8.881784197001E-016,-1.)); -#145928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145929 = ORIENTED_EDGE('',*,*,#145930,.T.); -#145930 = EDGE_CURVE('',#145909,#145735,#145931,.T.); -#145931 = SURFACE_CURVE('',#145932,(#145937,#145943),.PCURVE_S1.); -#145932 = CIRCLE('',#145933,0.119270391569); -#145933 = AXIS2_PLACEMENT_3D('',#145934,#145935,#145936); -#145934 = CARTESIAN_POINT('',(3.85,10.30032442045,0.530776333563)); -#145935 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#145936 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#145937 = PCURVE('',#145750,#145938); -#145938 = DEFINITIONAL_REPRESENTATION('',(#145939),#145942); -#145939 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#145940,#145941), +#148311 = CARTESIAN_POINT('',(1.598788597134,-3.85)); +#148312 = CARTESIAN_POINT('',(1.598788597134,-3.65)); +#148313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148314 = PCURVE('',#89288,#148315); +#148315 = DEFINITIONAL_REPRESENTATION('',(#148316),#148320); +#148316 = LINE('',#148317,#148318); +#148317 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#148318 = VECTOR('',#148319,1.); +#148319 = DIRECTION('',(-8.881784197001E-016,-1.)); +#148320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148321 = ORIENTED_EDGE('',*,*,#148322,.T.); +#148322 = EDGE_CURVE('',#148301,#148127,#148323,.T.); +#148323 = SURFACE_CURVE('',#148324,(#148329,#148335),.PCURVE_S1.); +#148324 = CIRCLE('',#148325,0.119270391569); +#148325 = AXIS2_PLACEMENT_3D('',#148326,#148327,#148328); +#148326 = CARTESIAN_POINT('',(3.85,10.30032442045,0.530776333563)); +#148327 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148328 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148329 = PCURVE('',#148142,#148330); +#148330 = DEFINITIONAL_REPRESENTATION('',(#148331),#148334); +#148331 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148332,#148333), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#145940 = CARTESIAN_POINT('',(1.598788597134,-3.85)); -#145941 = CARTESIAN_POINT('',(3.14159265359,-3.85)); -#145942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145943 = PCURVE('',#86814,#145944); -#145944 = DEFINITIONAL_REPRESENTATION('',(#145945),#145949); -#145945 = CIRCLE('',#145946,0.119270391569); -#145946 = AXIS2_PLACEMENT_2D('',#145947,#145948); -#145947 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#145948 = DIRECTION('',(0.E+000,-1.)); -#145949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145950 = ORIENTED_EDGE('',*,*,#145732,.F.); -#145951 = ADVANCED_FACE('',(#145952),#86814,.F.); -#145952 = FACE_BOUND('',#145953,.T.); -#145953 = EDGE_LOOP('',(#145954,#145975,#145976,#145977,#145978,#145979, - #146000,#146001,#146002,#146003,#146004,#146025)); -#145954 = ORIENTED_EDGE('',*,*,#145955,.F.); -#145955 = EDGE_CURVE('',#145909,#86799,#145956,.T.); -#145956 = SURFACE_CURVE('',#145957,(#145961,#145968),.PCURVE_S1.); -#145957 = LINE('',#145958,#145959); -#145958 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); -#145959 = VECTOR('',#145960,1.); -#145960 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#145961 = PCURVE('',#86814,#145962); -#145962 = DEFINITIONAL_REPRESENTATION('',(#145963),#145967); -#145963 = LINE('',#145964,#145965); -#145964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145965 = VECTOR('',#145966,1.); -#145966 = DIRECTION('',(3.563627120235E-016,-1.)); -#145967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145968 = PCURVE('',#86896,#145969); -#145969 = DEFINITIONAL_REPRESENTATION('',(#145970),#145974); -#145970 = LINE('',#145971,#145972); -#145971 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#145972 = VECTOR('',#145973,1.); -#145973 = DIRECTION('',(1.,2.164989446033E-063)); -#145974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145975 = ORIENTED_EDGE('',*,*,#145930,.T.); -#145976 = ORIENTED_EDGE('',*,*,#145783,.T.); -#145977 = ORIENTED_EDGE('',*,*,#145454,.T.); -#145978 = ORIENTED_EDGE('',*,*,#145298,.T.); -#145979 = ORIENTED_EDGE('',*,*,#145980,.T.); -#145980 = EDGE_CURVE('',#145271,#145352,#145981,.T.); -#145981 = SURFACE_CURVE('',#145982,(#145986,#145993),.PCURVE_S1.); -#145982 = LINE('',#145983,#145984); -#145983 = CARTESIAN_POINT('',(3.85,11.,1.159810404338E-002)); -#145984 = VECTOR('',#145985,1.); -#145985 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#145986 = PCURVE('',#86814,#145987); -#145987 = DEFINITIONAL_REPRESENTATION('',(#145988),#145992); -#145988 = LINE('',#145989,#145990); -#145989 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#145990 = VECTOR('',#145991,1.); -#145991 = DIRECTION('',(1.,2.101748079665E-016)); -#145992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#145993 = PCURVE('',#145286,#145994); -#145994 = DEFINITIONAL_REPRESENTATION('',(#145995),#145999); -#145995 = LINE('',#145996,#145997); -#145996 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#145997 = VECTOR('',#145998,1.); -#145998 = DIRECTION('',(-1.570395187386E-016,1.)); -#145999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146000 = ORIENTED_EDGE('',*,*,#145349,.F.); -#146001 = ORIENTED_EDGE('',*,*,#145579,.F.); -#146002 = ORIENTED_EDGE('',*,*,#145686,.F.); -#146003 = ORIENTED_EDGE('',*,*,#145807,.F.); -#146004 = ORIENTED_EDGE('',*,*,#146005,.T.); -#146005 = EDGE_CURVE('',#145808,#86797,#146006,.T.); -#146006 = SURFACE_CURVE('',#146007,(#146011,#146018),.PCURVE_S1.); -#146007 = LINE('',#146008,#146009); -#146008 = CARTESIAN_POINT('',(3.85,10.527847992439,0.75)); -#146009 = VECTOR('',#146010,1.); -#146010 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146011 = PCURVE('',#86814,#146012); -#146012 = DEFINITIONAL_REPRESENTATION('',(#146013),#146017); -#146013 = LINE('',#146014,#146015); -#146014 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#146015 = VECTOR('',#146016,1.); -#146016 = DIRECTION('',(3.563627120235E-016,-1.)); -#146017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146018 = PCURVE('',#86842,#146019); -#146019 = DEFINITIONAL_REPRESENTATION('',(#146020),#146024); -#146020 = LINE('',#146021,#146022); -#146021 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146022 = VECTOR('',#146023,1.); -#146023 = DIRECTION('',(-1.,2.164989446033E-063)); -#146024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146025 = ORIENTED_EDGE('',*,*,#86796,.T.); -#146026 = ADVANCED_FACE('',(#146027),#86842,.F.); -#146027 = FACE_BOUND('',#146028,.T.); -#146028 = EDGE_LOOP('',(#146029,#146030,#146051,#146052)); -#146029 = ORIENTED_EDGE('',*,*,#145858,.F.); -#146030 = ORIENTED_EDGE('',*,*,#146031,.T.); -#146031 = EDGE_CURVE('',#145832,#86827,#146032,.T.); -#146032 = SURFACE_CURVE('',#146033,(#146037,#146044),.PCURVE_S1.); -#146033 = LINE('',#146034,#146035); -#146034 = CARTESIAN_POINT('',(3.65,10.527847992439,0.75)); -#146035 = VECTOR('',#146036,1.); -#146036 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146037 = PCURVE('',#86842,#146038); -#146038 = DEFINITIONAL_REPRESENTATION('',(#146039),#146043); -#146039 = LINE('',#146040,#146041); -#146040 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#146041 = VECTOR('',#146042,1.); -#146042 = DIRECTION('',(-1.,2.164989446033E-063)); -#146043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146044 = PCURVE('',#86870,#146045); -#146045 = DEFINITIONAL_REPRESENTATION('',(#146046),#146050); -#146046 = LINE('',#146047,#146048); -#146047 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#146048 = VECTOR('',#146049,1.); -#146049 = DIRECTION('',(-3.563627120235E-016,-1.)); -#146050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146051 = ORIENTED_EDGE('',*,*,#86826,.T.); -#146052 = ORIENTED_EDGE('',*,*,#146005,.F.); -#146053 = ADVANCED_FACE('',(#146054),#86870,.F.); -#146054 = FACE_BOUND('',#146055,.T.); -#146055 = EDGE_LOOP('',(#146056,#146057,#146058,#146059,#146060,#146061, - #146082,#146083,#146084,#146085,#146086,#146107)); -#146056 = ORIENTED_EDGE('',*,*,#146031,.F.); -#146057 = ORIENTED_EDGE('',*,*,#145831,.T.); -#146058 = ORIENTED_EDGE('',*,*,#145708,.T.); -#146059 = ORIENTED_EDGE('',*,*,#145633,.T.); -#146060 = ORIENTED_EDGE('',*,*,#145402,.T.); -#146061 = ORIENTED_EDGE('',*,*,#146062,.T.); -#146062 = EDGE_CURVE('',#145380,#145243,#146063,.T.); -#146063 = SURFACE_CURVE('',#146064,(#146068,#146075),.PCURVE_S1.); -#146064 = LINE('',#146065,#146066); -#146065 = CARTESIAN_POINT('',(3.65,11.,1.159810404338E-002)); -#146066 = VECTOR('',#146067,1.); -#146067 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#146068 = PCURVE('',#86870,#146069); -#146069 = DEFINITIONAL_REPRESENTATION('',(#146070),#146074); -#146070 = LINE('',#146071,#146072); -#146071 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#146072 = VECTOR('',#146073,1.); -#146073 = DIRECTION('',(1.,-2.101748079665E-016)); -#146074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146075 = PCURVE('',#145286,#146076); -#146076 = DEFINITIONAL_REPRESENTATION('',(#146077),#146081); -#146077 = LINE('',#146078,#146079); -#146078 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#146079 = VECTOR('',#146080,1.); -#146080 = DIRECTION('',(1.570395187386E-016,-1.)); -#146081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146082 = ORIENTED_EDGE('',*,*,#145240,.F.); -#146083 = ORIENTED_EDGE('',*,*,#145531,.F.); -#146084 = ORIENTED_EDGE('',*,*,#145761,.F.); -#146085 = ORIENTED_EDGE('',*,*,#145881,.F.); -#146086 = ORIENTED_EDGE('',*,*,#146087,.T.); -#146087 = EDGE_CURVE('',#145882,#86855,#146088,.T.); -#146088 = SURFACE_CURVE('',#146089,(#146093,#146100),.PCURVE_S1.); -#146089 = LINE('',#146090,#146091); -#146090 = CARTESIAN_POINT('',(3.65,10.527847992439,0.65)); -#146091 = VECTOR('',#146092,1.); -#146092 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146093 = PCURVE('',#86870,#146094); -#146094 = DEFINITIONAL_REPRESENTATION('',(#146095),#146099); -#146095 = LINE('',#146096,#146097); -#146096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146097 = VECTOR('',#146098,1.); -#146098 = DIRECTION('',(-3.563627120235E-016,-1.)); -#146099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146100 = PCURVE('',#86896,#146101); -#146101 = DEFINITIONAL_REPRESENTATION('',(#146102),#146106); -#146102 = LINE('',#146103,#146104); -#146103 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#146104 = VECTOR('',#146105,1.); -#146105 = DIRECTION('',(1.,2.164989446033E-063)); -#146106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146107 = ORIENTED_EDGE('',*,*,#86854,.T.); -#146108 = ADVANCED_FACE('',(#146109),#86896,.F.); -#146109 = FACE_BOUND('',#146110,.T.); -#146110 = EDGE_LOOP('',(#146111,#146112,#146113,#146114)); -#146111 = ORIENTED_EDGE('',*,*,#145908,.F.); -#146112 = ORIENTED_EDGE('',*,*,#145955,.T.); -#146113 = ORIENTED_EDGE('',*,*,#86882,.T.); -#146114 = ORIENTED_EDGE('',*,*,#146087,.F.); -#146115 = ADVANCED_FACE('',(#146116),#145286,.T.); -#146116 = FACE_BOUND('',#146117,.T.); -#146117 = EDGE_LOOP('',(#146118,#146119,#146120,#146121)); -#146118 = ORIENTED_EDGE('',*,*,#146062,.F.); -#146119 = ORIENTED_EDGE('',*,*,#145379,.F.); -#146120 = ORIENTED_EDGE('',*,*,#145980,.F.); -#146121 = ORIENTED_EDGE('',*,*,#145270,.F.); -#146122 = ADVANCED_FACE('',(#146123),#146137,.T.); -#146123 = FACE_BOUND('',#146124,.T.); -#146124 = EDGE_LOOP('',(#146125,#146155,#146183,#146206)); -#146125 = ORIENTED_EDGE('',*,*,#146126,.T.); -#146126 = EDGE_CURVE('',#146127,#146129,#146131,.T.); -#146127 = VERTEX_POINT('',#146128); -#146128 = CARTESIAN_POINT('',(3.15,10.74341632541,-0.308197125857)); -#146129 = VERTEX_POINT('',#146130); -#146130 = CARTESIAN_POINT('',(3.15,11.,-0.308197125857)); -#146131 = SURFACE_CURVE('',#146132,(#146136,#146148),.PCURVE_S1.); -#146132 = LINE('',#146133,#146134); -#146133 = CARTESIAN_POINT('',(3.15,10.74341632541,-0.308197125857)); -#146134 = VECTOR('',#146135,1.); -#146135 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#146136 = PCURVE('',#146137,#146142); -#146137 = PLANE('',#146138); -#146138 = AXIS2_PLACEMENT_3D('',#146139,#146140,#146141); -#146139 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#148332 = CARTESIAN_POINT('',(1.598788597134,-3.85)); +#148333 = CARTESIAN_POINT('',(3.14159265359,-3.85)); +#148334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148335 = PCURVE('',#89206,#148336); +#148336 = DEFINITIONAL_REPRESENTATION('',(#148337),#148341); +#148337 = CIRCLE('',#148338,0.119270391569); +#148338 = AXIS2_PLACEMENT_2D('',#148339,#148340); +#148339 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#148340 = DIRECTION('',(0.E+000,-1.)); +#148341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148342 = ORIENTED_EDGE('',*,*,#148124,.F.); +#148343 = ADVANCED_FACE('',(#148344),#89206,.F.); +#148344 = FACE_BOUND('',#148345,.T.); +#148345 = EDGE_LOOP('',(#148346,#148367,#148368,#148369,#148370,#148371, + #148392,#148393,#148394,#148395,#148396,#148417)); +#148346 = ORIENTED_EDGE('',*,*,#148347,.F.); +#148347 = EDGE_CURVE('',#148301,#89191,#148348,.T.); +#148348 = SURFACE_CURVE('',#148349,(#148353,#148360),.PCURVE_S1.); +#148349 = LINE('',#148350,#148351); +#148350 = CARTESIAN_POINT('',(3.85,10.527847992439,0.65)); +#148351 = VECTOR('',#148352,1.); +#148352 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#148353 = PCURVE('',#89206,#148354); +#148354 = DEFINITIONAL_REPRESENTATION('',(#148355),#148359); +#148355 = LINE('',#148356,#148357); +#148356 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148357 = VECTOR('',#148358,1.); +#148358 = DIRECTION('',(3.563627120235E-016,-1.)); +#148359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148360 = PCURVE('',#89288,#148361); +#148361 = DEFINITIONAL_REPRESENTATION('',(#148362),#148366); +#148362 = LINE('',#148363,#148364); +#148363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148364 = VECTOR('',#148365,1.); +#148365 = DIRECTION('',(1.,2.164989446033E-063)); +#148366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148367 = ORIENTED_EDGE('',*,*,#148322,.T.); +#148368 = ORIENTED_EDGE('',*,*,#148175,.T.); +#148369 = ORIENTED_EDGE('',*,*,#147846,.T.); +#148370 = ORIENTED_EDGE('',*,*,#147690,.T.); +#148371 = ORIENTED_EDGE('',*,*,#148372,.T.); +#148372 = EDGE_CURVE('',#147663,#147744,#148373,.T.); +#148373 = SURFACE_CURVE('',#148374,(#148378,#148385),.PCURVE_S1.); +#148374 = LINE('',#148375,#148376); +#148375 = CARTESIAN_POINT('',(3.85,11.,1.159810404338E-002)); +#148376 = VECTOR('',#148377,1.); +#148377 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#148378 = PCURVE('',#89206,#148379); +#148379 = DEFINITIONAL_REPRESENTATION('',(#148380),#148384); +#148380 = LINE('',#148381,#148382); +#148381 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#148382 = VECTOR('',#148383,1.); +#148383 = DIRECTION('',(1.,2.101748079665E-016)); +#148384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148385 = PCURVE('',#147678,#148386); +#148386 = DEFINITIONAL_REPRESENTATION('',(#148387),#148391); +#148387 = LINE('',#148388,#148389); +#148388 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#148389 = VECTOR('',#148390,1.); +#148390 = DIRECTION('',(-1.570395187386E-016,1.)); +#148391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148392 = ORIENTED_EDGE('',*,*,#147741,.F.); +#148393 = ORIENTED_EDGE('',*,*,#147971,.F.); +#148394 = ORIENTED_EDGE('',*,*,#148078,.F.); +#148395 = ORIENTED_EDGE('',*,*,#148199,.F.); +#148396 = ORIENTED_EDGE('',*,*,#148397,.T.); +#148397 = EDGE_CURVE('',#148200,#89189,#148398,.T.); +#148398 = SURFACE_CURVE('',#148399,(#148403,#148410),.PCURVE_S1.); +#148399 = LINE('',#148400,#148401); +#148400 = CARTESIAN_POINT('',(3.85,10.527847992439,0.75)); +#148401 = VECTOR('',#148402,1.); +#148402 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#148403 = PCURVE('',#89206,#148404); +#148404 = DEFINITIONAL_REPRESENTATION('',(#148405),#148409); +#148405 = LINE('',#148406,#148407); +#148406 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#148407 = VECTOR('',#148408,1.); +#148408 = DIRECTION('',(3.563627120235E-016,-1.)); +#148409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148410 = PCURVE('',#89234,#148411); +#148411 = DEFINITIONAL_REPRESENTATION('',(#148412),#148416); +#148412 = LINE('',#148413,#148414); +#148413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148414 = VECTOR('',#148415,1.); +#148415 = DIRECTION('',(-1.,2.164989446033E-063)); +#148416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148417 = ORIENTED_EDGE('',*,*,#89188,.T.); +#148418 = ADVANCED_FACE('',(#148419),#89234,.F.); +#148419 = FACE_BOUND('',#148420,.T.); +#148420 = EDGE_LOOP('',(#148421,#148422,#148443,#148444)); +#148421 = ORIENTED_EDGE('',*,*,#148250,.F.); +#148422 = ORIENTED_EDGE('',*,*,#148423,.T.); +#148423 = EDGE_CURVE('',#148224,#89219,#148424,.T.); +#148424 = SURFACE_CURVE('',#148425,(#148429,#148436),.PCURVE_S1.); +#148425 = LINE('',#148426,#148427); +#148426 = CARTESIAN_POINT('',(3.65,10.527847992439,0.75)); +#148427 = VECTOR('',#148428,1.); +#148428 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#148429 = PCURVE('',#89234,#148430); +#148430 = DEFINITIONAL_REPRESENTATION('',(#148431),#148435); +#148431 = LINE('',#148432,#148433); +#148432 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#148433 = VECTOR('',#148434,1.); +#148434 = DIRECTION('',(-1.,2.164989446033E-063)); +#148435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148436 = PCURVE('',#89262,#148437); +#148437 = DEFINITIONAL_REPRESENTATION('',(#148438),#148442); +#148438 = LINE('',#148439,#148440); +#148439 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#148440 = VECTOR('',#148441,1.); +#148441 = DIRECTION('',(-3.563627120235E-016,-1.)); +#148442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148443 = ORIENTED_EDGE('',*,*,#89218,.T.); +#148444 = ORIENTED_EDGE('',*,*,#148397,.F.); +#148445 = ADVANCED_FACE('',(#148446),#89262,.F.); +#148446 = FACE_BOUND('',#148447,.T.); +#148447 = EDGE_LOOP('',(#148448,#148449,#148450,#148451,#148452,#148453, + #148474,#148475,#148476,#148477,#148478,#148499)); +#148448 = ORIENTED_EDGE('',*,*,#148423,.F.); +#148449 = ORIENTED_EDGE('',*,*,#148223,.T.); +#148450 = ORIENTED_EDGE('',*,*,#148100,.T.); +#148451 = ORIENTED_EDGE('',*,*,#148025,.T.); +#148452 = ORIENTED_EDGE('',*,*,#147794,.T.); +#148453 = ORIENTED_EDGE('',*,*,#148454,.T.); +#148454 = EDGE_CURVE('',#147772,#147635,#148455,.T.); +#148455 = SURFACE_CURVE('',#148456,(#148460,#148467),.PCURVE_S1.); +#148456 = LINE('',#148457,#148458); +#148457 = CARTESIAN_POINT('',(3.65,11.,1.159810404338E-002)); +#148458 = VECTOR('',#148459,1.); +#148459 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#148460 = PCURVE('',#89262,#148461); +#148461 = DEFINITIONAL_REPRESENTATION('',(#148462),#148466); +#148462 = LINE('',#148463,#148464); +#148463 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#148464 = VECTOR('',#148465,1.); +#148465 = DIRECTION('',(1.,-2.101748079665E-016)); +#148466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148467 = PCURVE('',#147678,#148468); +#148468 = DEFINITIONAL_REPRESENTATION('',(#148469),#148473); +#148469 = LINE('',#148470,#148471); +#148470 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#148471 = VECTOR('',#148472,1.); +#148472 = DIRECTION('',(1.570395187386E-016,-1.)); +#148473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148474 = ORIENTED_EDGE('',*,*,#147632,.F.); +#148475 = ORIENTED_EDGE('',*,*,#147923,.F.); +#148476 = ORIENTED_EDGE('',*,*,#148153,.F.); +#148477 = ORIENTED_EDGE('',*,*,#148273,.F.); +#148478 = ORIENTED_EDGE('',*,*,#148479,.T.); +#148479 = EDGE_CURVE('',#148274,#89247,#148480,.T.); +#148480 = SURFACE_CURVE('',#148481,(#148485,#148492),.PCURVE_S1.); +#148481 = LINE('',#148482,#148483); +#148482 = CARTESIAN_POINT('',(3.65,10.527847992439,0.65)); +#148483 = VECTOR('',#148484,1.); +#148484 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#148485 = PCURVE('',#89262,#148486); +#148486 = DEFINITIONAL_REPRESENTATION('',(#148487),#148491); +#148487 = LINE('',#148488,#148489); +#148488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148489 = VECTOR('',#148490,1.); +#148490 = DIRECTION('',(-3.563627120235E-016,-1.)); +#148491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148492 = PCURVE('',#89288,#148493); +#148493 = DEFINITIONAL_REPRESENTATION('',(#148494),#148498); +#148494 = LINE('',#148495,#148496); +#148495 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#148496 = VECTOR('',#148497,1.); +#148497 = DIRECTION('',(1.,2.164989446033E-063)); +#148498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148499 = ORIENTED_EDGE('',*,*,#89246,.T.); +#148500 = ADVANCED_FACE('',(#148501),#89288,.F.); +#148501 = FACE_BOUND('',#148502,.T.); +#148502 = EDGE_LOOP('',(#148503,#148504,#148505,#148506)); +#148503 = ORIENTED_EDGE('',*,*,#148300,.F.); +#148504 = ORIENTED_EDGE('',*,*,#148347,.T.); +#148505 = ORIENTED_EDGE('',*,*,#89274,.T.); +#148506 = ORIENTED_EDGE('',*,*,#148479,.F.); +#148507 = ADVANCED_FACE('',(#148508),#147678,.T.); +#148508 = FACE_BOUND('',#148509,.T.); +#148509 = EDGE_LOOP('',(#148510,#148511,#148512,#148513)); +#148510 = ORIENTED_EDGE('',*,*,#148454,.F.); +#148511 = ORIENTED_EDGE('',*,*,#147771,.F.); +#148512 = ORIENTED_EDGE('',*,*,#148372,.F.); +#148513 = ORIENTED_EDGE('',*,*,#147662,.F.); +#148514 = ADVANCED_FACE('',(#148515),#148529,.T.); +#148515 = FACE_BOUND('',#148516,.T.); +#148516 = EDGE_LOOP('',(#148517,#148547,#148575,#148598)); +#148517 = ORIENTED_EDGE('',*,*,#148518,.T.); +#148518 = EDGE_CURVE('',#148519,#148521,#148523,.T.); +#148519 = VERTEX_POINT('',#148520); +#148520 = CARTESIAN_POINT('',(3.15,10.74341632541,-0.308197125857)); +#148521 = VERTEX_POINT('',#148522); +#148522 = CARTESIAN_POINT('',(3.15,11.,-0.308197125857)); +#148523 = SURFACE_CURVE('',#148524,(#148528,#148540),.PCURVE_S1.); +#148524 = LINE('',#148525,#148526); +#148525 = CARTESIAN_POINT('',(3.15,10.74341632541,-0.308197125857)); +#148526 = VECTOR('',#148527,1.); +#148527 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#148528 = PCURVE('',#148529,#148534); +#148529 = PLANE('',#148530); +#148530 = AXIS2_PLACEMENT_3D('',#148531,#148532,#148533); +#148531 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#146140 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#146141 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#146142 = DEFINITIONAL_REPRESENTATION('',(#146143),#146147); -#146143 = LINE('',#146144,#146145); -#146144 = CARTESIAN_POINT('',(-3.15,-3.552713678801E-015)); -#146145 = VECTOR('',#146146,1.); -#146146 = DIRECTION('',(-6.725593854929E-015,1.)); -#146147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146148 = PCURVE('',#88124,#146149); -#146149 = DEFINITIONAL_REPRESENTATION('',(#146150),#146154); -#146150 = LINE('',#146151,#146152); -#146151 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#146152 = VECTOR('',#146153,1.); -#146153 = DIRECTION('',(0.E+000,1.)); -#146154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146155 = ORIENTED_EDGE('',*,*,#146156,.T.); -#146156 = EDGE_CURVE('',#146129,#146157,#146159,.T.); -#146157 = VERTEX_POINT('',#146158); -#146158 = CARTESIAN_POINT('',(3.35,11.,-0.308197125857)); -#146159 = SURFACE_CURVE('',#146160,(#146164,#146171),.PCURVE_S1.); -#146160 = LINE('',#146161,#146162); -#146161 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#146162 = VECTOR('',#146163,1.); -#146163 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146164 = PCURVE('',#146137,#146165); -#146165 = DEFINITIONAL_REPRESENTATION('',(#146166),#146170); -#146166 = LINE('',#146167,#146168); -#146167 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#146168 = VECTOR('',#146169,1.); -#146169 = DIRECTION('',(-1.,-8.881784197001E-016)); -#146170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146171 = PCURVE('',#146172,#146177); -#146172 = PLANE('',#146173); -#146173 = AXIS2_PLACEMENT_3D('',#146174,#146175,#146176); -#146174 = CARTESIAN_POINT('',(3.25,11.,-0.258196742327)); -#146175 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#146176 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#146177 = DEFINITIONAL_REPRESENTATION('',(#146178),#146182); -#146178 = LINE('',#146179,#146180); -#146179 = CARTESIAN_POINT('',(3.25,-5.000038352949E-002)); -#146180 = VECTOR('',#146181,1.); -#146181 = DIRECTION('',(-1.,-1.1653254136E-048)); -#146182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146183 = ORIENTED_EDGE('',*,*,#146184,.F.); -#146184 = EDGE_CURVE('',#146185,#146157,#146187,.T.); -#146185 = VERTEX_POINT('',#146186); -#146186 = CARTESIAN_POINT('',(3.35,10.74341632541,-0.308197125857)); -#146187 = SURFACE_CURVE('',#146188,(#146192,#146199),.PCURVE_S1.); -#146188 = LINE('',#146189,#146190); -#146189 = CARTESIAN_POINT('',(3.35,10.74341632541,-0.308197125857)); -#146190 = VECTOR('',#146191,1.); -#146191 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#146192 = PCURVE('',#146137,#146193); -#146193 = DEFINITIONAL_REPRESENTATION('',(#146194),#146198); -#146194 = LINE('',#146195,#146196); -#146195 = CARTESIAN_POINT('',(-3.35,-3.552713678801E-015)); -#146196 = VECTOR('',#146197,1.); -#146197 = DIRECTION('',(-6.725593854929E-015,1.)); -#146198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146199 = PCURVE('',#88068,#146200); -#146200 = DEFINITIONAL_REPRESENTATION('',(#146201),#146205); -#146201 = LINE('',#146202,#146203); -#146202 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#146203 = VECTOR('',#146204,1.); -#146204 = DIRECTION('',(0.E+000,1.)); -#146205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146206 = ORIENTED_EDGE('',*,*,#146207,.T.); -#146207 = EDGE_CURVE('',#146185,#146127,#146208,.T.); -#146208 = SURFACE_CURVE('',#146209,(#146213,#146220),.PCURVE_S1.); -#146209 = LINE('',#146210,#146211); -#146210 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#148532 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148533 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#148534 = DEFINITIONAL_REPRESENTATION('',(#148535),#148539); +#148535 = LINE('',#148536,#148537); +#148536 = CARTESIAN_POINT('',(-3.15,-3.552713678801E-015)); +#148537 = VECTOR('',#148538,1.); +#148538 = DIRECTION('',(-6.725593854929E-015,1.)); +#148539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148540 = PCURVE('',#90516,#148541); +#148541 = DEFINITIONAL_REPRESENTATION('',(#148542),#148546); +#148542 = LINE('',#148543,#148544); +#148543 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#148544 = VECTOR('',#148545,1.); +#148545 = DIRECTION('',(0.E+000,1.)); +#148546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148547 = ORIENTED_EDGE('',*,*,#148548,.T.); +#148548 = EDGE_CURVE('',#148521,#148549,#148551,.T.); +#148549 = VERTEX_POINT('',#148550); +#148550 = CARTESIAN_POINT('',(3.35,11.,-0.308197125857)); +#148551 = SURFACE_CURVE('',#148552,(#148556,#148563),.PCURVE_S1.); +#148552 = LINE('',#148553,#148554); +#148553 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#148554 = VECTOR('',#148555,1.); +#148555 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148556 = PCURVE('',#148529,#148557); +#148557 = DEFINITIONAL_REPRESENTATION('',(#148558),#148562); +#148558 = LINE('',#148559,#148560); +#148559 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#148560 = VECTOR('',#148561,1.); +#148561 = DIRECTION('',(-1.,-8.881784197001E-016)); +#148562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148563 = PCURVE('',#148564,#148569); +#148564 = PLANE('',#148565); +#148565 = AXIS2_PLACEMENT_3D('',#148566,#148567,#148568); +#148566 = CARTESIAN_POINT('',(3.25,11.,-0.258196742327)); +#148567 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#148568 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#148569 = DEFINITIONAL_REPRESENTATION('',(#148570),#148574); +#148570 = LINE('',#148571,#148572); +#148571 = CARTESIAN_POINT('',(3.25,-5.000038352949E-002)); +#148572 = VECTOR('',#148573,1.); +#148573 = DIRECTION('',(-1.,-1.1653254136E-048)); +#148574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148575 = ORIENTED_EDGE('',*,*,#148576,.F.); +#148576 = EDGE_CURVE('',#148577,#148549,#148579,.T.); +#148577 = VERTEX_POINT('',#148578); +#148578 = CARTESIAN_POINT('',(3.35,10.74341632541,-0.308197125857)); +#148579 = SURFACE_CURVE('',#148580,(#148584,#148591),.PCURVE_S1.); +#148580 = LINE('',#148581,#148582); +#148581 = CARTESIAN_POINT('',(3.35,10.74341632541,-0.308197125857)); +#148582 = VECTOR('',#148583,1.); +#148583 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#148584 = PCURVE('',#148529,#148585); +#148585 = DEFINITIONAL_REPRESENTATION('',(#148586),#148590); +#148586 = LINE('',#148587,#148588); +#148587 = CARTESIAN_POINT('',(-3.35,-3.552713678801E-015)); +#148588 = VECTOR('',#148589,1.); +#148589 = DIRECTION('',(-6.725593854929E-015,1.)); +#148590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148591 = PCURVE('',#90460,#148592); +#148592 = DEFINITIONAL_REPRESENTATION('',(#148593),#148597); +#148593 = LINE('',#148594,#148595); +#148594 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#148595 = VECTOR('',#148596,1.); +#148596 = DIRECTION('',(0.E+000,1.)); +#148597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148598 = ORIENTED_EDGE('',*,*,#148599,.T.); +#148599 = EDGE_CURVE('',#148577,#148519,#148600,.T.); +#148600 = SURFACE_CURVE('',#148601,(#148605,#148612),.PCURVE_S1.); +#148601 = LINE('',#148602,#148603); +#148602 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#146211 = VECTOR('',#146212,1.); -#146212 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146213 = PCURVE('',#146137,#146214); -#146214 = DEFINITIONAL_REPRESENTATION('',(#146215),#146219); -#146215 = LINE('',#146216,#146217); -#146216 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146217 = VECTOR('',#146218,1.); -#146218 = DIRECTION('',(1.,8.881784197001E-016)); -#146219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146220 = PCURVE('',#146221,#146226); -#146221 = CYLINDRICAL_SURFACE('',#146222,0.308574064194); -#146222 = AXIS2_PLACEMENT_3D('',#146223,#146224,#146225); -#146223 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#148603 = VECTOR('',#148604,1.); +#148604 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148605 = PCURVE('',#148529,#148606); +#148606 = DEFINITIONAL_REPRESENTATION('',(#148607),#148611); +#148607 = LINE('',#148608,#148609); +#148608 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148609 = VECTOR('',#148610,1.); +#148610 = DIRECTION('',(1.,8.881784197001E-016)); +#148611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148612 = PCURVE('',#148613,#148618); +#148613 = CYLINDRICAL_SURFACE('',#148614,0.308574064194); +#148614 = AXIS2_PLACEMENT_3D('',#148615,#148616,#148617); +#148615 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#146224 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146225 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146226 = DEFINITIONAL_REPRESENTATION('',(#146227),#146230); -#146227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146228,#146229), +#148616 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148617 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148618 = DEFINITIONAL_REPRESENTATION('',(#148619),#148622); +#148619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148620,#148621), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#146228 = CARTESIAN_POINT('',(4.761821717947,3.35)); -#146229 = CARTESIAN_POINT('',(4.761821717947,3.15)); -#146230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146231 = ADVANCED_FACE('',(#146232),#146246,.T.); -#146232 = FACE_BOUND('',#146233,.T.); -#146233 = EDGE_LOOP('',(#146234,#146264,#146287,#146310)); -#146234 = ORIENTED_EDGE('',*,*,#146235,.T.); -#146235 = EDGE_CURVE('',#146236,#146238,#146240,.T.); -#146236 = VERTEX_POINT('',#146237); -#146237 = CARTESIAN_POINT('',(3.35,10.740726081328,-0.208196358798)); -#146238 = VERTEX_POINT('',#146239); -#146239 = CARTESIAN_POINT('',(3.35,11.,-0.208196358798)); -#146240 = SURFACE_CURVE('',#146241,(#146245,#146257),.PCURVE_S1.); -#146241 = LINE('',#146242,#146243); -#146242 = CARTESIAN_POINT('',(3.35,10.740726081328,-0.208196358798)); -#146243 = VECTOR('',#146244,1.); -#146244 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#146245 = PCURVE('',#146246,#146251); -#146246 = PLANE('',#146247); -#146247 = AXIS2_PLACEMENT_3D('',#146248,#146249,#146250); -#146248 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#148620 = CARTESIAN_POINT('',(4.761821717947,3.35)); +#148621 = CARTESIAN_POINT('',(4.761821717947,3.15)); +#148622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148623 = ADVANCED_FACE('',(#148624),#148638,.T.); +#148624 = FACE_BOUND('',#148625,.T.); +#148625 = EDGE_LOOP('',(#148626,#148656,#148679,#148702)); +#148626 = ORIENTED_EDGE('',*,*,#148627,.T.); +#148627 = EDGE_CURVE('',#148628,#148630,#148632,.T.); +#148628 = VERTEX_POINT('',#148629); +#148629 = CARTESIAN_POINT('',(3.35,10.740726081328,-0.208196358798)); +#148630 = VERTEX_POINT('',#148631); +#148631 = CARTESIAN_POINT('',(3.35,11.,-0.208196358798)); +#148632 = SURFACE_CURVE('',#148633,(#148637,#148649),.PCURVE_S1.); +#148633 = LINE('',#148634,#148635); +#148634 = CARTESIAN_POINT('',(3.35,10.740726081328,-0.208196358798)); +#148635 = VECTOR('',#148636,1.); +#148636 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#148637 = PCURVE('',#148638,#148643); +#148638 = PLANE('',#148639); +#148639 = AXIS2_PLACEMENT_3D('',#148640,#148641,#148642); +#148640 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#146249 = DIRECTION('',(0.E+000,0.E+000,1.)); -#146250 = DIRECTION('',(1.,0.E+000,0.E+000)); -#146251 = DEFINITIONAL_REPRESENTATION('',(#146252),#146256); -#146252 = LINE('',#146253,#146254); -#146253 = CARTESIAN_POINT('',(3.35,-3.552713678801E-015)); -#146254 = VECTOR('',#146255,1.); -#146255 = DIRECTION('',(6.725593854929E-015,1.)); -#146256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146257 = PCURVE('',#88068,#146258); -#146258 = DEFINITIONAL_REPRESENTATION('',(#146259),#146263); -#146259 = LINE('',#146260,#146261); -#146260 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#146261 = VECTOR('',#146262,1.); -#146262 = DIRECTION('',(0.E+000,1.)); -#146263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146264 = ORIENTED_EDGE('',*,*,#146265,.T.); -#146265 = EDGE_CURVE('',#146238,#146266,#146268,.T.); -#146266 = VERTEX_POINT('',#146267); -#146267 = CARTESIAN_POINT('',(3.15,11.,-0.208196358798)); -#146268 = SURFACE_CURVE('',#146269,(#146273,#146280),.PCURVE_S1.); -#146269 = LINE('',#146270,#146271); -#146270 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#146271 = VECTOR('',#146272,1.); -#146272 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146273 = PCURVE('',#146246,#146274); -#146274 = DEFINITIONAL_REPRESENTATION('',(#146275),#146279); -#146275 = LINE('',#146276,#146277); -#146276 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#146277 = VECTOR('',#146278,1.); -#146278 = DIRECTION('',(-1.,8.881784197001E-016)); -#146279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146280 = PCURVE('',#146172,#146281); -#146281 = DEFINITIONAL_REPRESENTATION('',(#146282),#146286); -#146282 = LINE('',#146283,#146284); -#146283 = CARTESIAN_POINT('',(3.25,5.00003835295E-002)); -#146284 = VECTOR('',#146285,1.); -#146285 = DIRECTION('',(1.,1.1653254136E-048)); -#146286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146287 = ORIENTED_EDGE('',*,*,#146288,.F.); -#146288 = EDGE_CURVE('',#146289,#146266,#146291,.T.); -#146289 = VERTEX_POINT('',#146290); -#146290 = CARTESIAN_POINT('',(3.15,10.740726081328,-0.208196358798)); -#146291 = SURFACE_CURVE('',#146292,(#146296,#146303),.PCURVE_S1.); -#146292 = LINE('',#146293,#146294); -#146293 = CARTESIAN_POINT('',(3.15,10.740726081328,-0.208196358798)); -#146294 = VECTOR('',#146295,1.); -#146295 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#146296 = PCURVE('',#146246,#146297); -#146297 = DEFINITIONAL_REPRESENTATION('',(#146298),#146302); -#146298 = LINE('',#146299,#146300); -#146299 = CARTESIAN_POINT('',(3.15,-1.7763568394E-015)); -#146300 = VECTOR('',#146301,1.); -#146301 = DIRECTION('',(6.725593854929E-015,1.)); -#146302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146303 = PCURVE('',#88124,#146304); -#146304 = DEFINITIONAL_REPRESENTATION('',(#146305),#146309); -#146305 = LINE('',#146306,#146307); -#146306 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#146307 = VECTOR('',#146308,1.); -#146308 = DIRECTION('',(0.E+000,1.)); -#146309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146310 = ORIENTED_EDGE('',*,*,#146311,.T.); -#146311 = EDGE_CURVE('',#146289,#146236,#146312,.T.); -#146312 = SURFACE_CURVE('',#146313,(#146317,#146324),.PCURVE_S1.); -#146313 = LINE('',#146314,#146315); -#146314 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, - -0.208196358798)); -#146315 = VECTOR('',#146316,1.); -#146316 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146317 = PCURVE('',#146246,#146318); -#146318 = DEFINITIONAL_REPRESENTATION('',(#146319),#146323); -#146319 = LINE('',#146320,#146321); -#146320 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146321 = VECTOR('',#146322,1.); -#146322 = DIRECTION('',(1.,-8.881784197001E-016)); -#146323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148641 = DIRECTION('',(0.E+000,0.E+000,1.)); +#148642 = DIRECTION('',(1.,0.E+000,0.E+000)); +#148643 = DEFINITIONAL_REPRESENTATION('',(#148644),#148648); +#148644 = LINE('',#148645,#148646); +#148645 = CARTESIAN_POINT('',(3.35,-3.552713678801E-015)); +#148646 = VECTOR('',#148647,1.); +#148647 = DIRECTION('',(6.725593854929E-015,1.)); +#148648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148649 = PCURVE('',#90460,#148650); +#148650 = DEFINITIONAL_REPRESENTATION('',(#148651),#148655); +#148651 = LINE('',#148652,#148653); +#148652 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#148653 = VECTOR('',#148654,1.); +#148654 = DIRECTION('',(0.E+000,1.)); +#148655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148656 = ORIENTED_EDGE('',*,*,#148657,.T.); +#148657 = EDGE_CURVE('',#148630,#148658,#148660,.T.); +#148658 = VERTEX_POINT('',#148659); +#148659 = CARTESIAN_POINT('',(3.15,11.,-0.208196358798)); +#148660 = SURFACE_CURVE('',#148661,(#148665,#148672),.PCURVE_S1.); +#148661 = LINE('',#148662,#148663); +#148662 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#148663 = VECTOR('',#148664,1.); +#148664 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148665 = PCURVE('',#148638,#148666); +#148666 = DEFINITIONAL_REPRESENTATION('',(#148667),#148671); +#148667 = LINE('',#148668,#148669); +#148668 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#148669 = VECTOR('',#148670,1.); +#148670 = DIRECTION('',(-1.,8.881784197001E-016)); +#148671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148672 = PCURVE('',#148564,#148673); +#148673 = DEFINITIONAL_REPRESENTATION('',(#148674),#148678); +#148674 = LINE('',#148675,#148676); +#148675 = CARTESIAN_POINT('',(3.25,5.00003835295E-002)); +#148676 = VECTOR('',#148677,1.); +#148677 = DIRECTION('',(1.,1.1653254136E-048)); +#148678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148679 = ORIENTED_EDGE('',*,*,#148680,.F.); +#148680 = EDGE_CURVE('',#148681,#148658,#148683,.T.); +#148681 = VERTEX_POINT('',#148682); +#148682 = CARTESIAN_POINT('',(3.15,10.740726081328,-0.208196358798)); +#148683 = SURFACE_CURVE('',#148684,(#148688,#148695),.PCURVE_S1.); +#148684 = LINE('',#148685,#148686); +#148685 = CARTESIAN_POINT('',(3.15,10.740726081328,-0.208196358798)); +#148686 = VECTOR('',#148687,1.); +#148687 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#148688 = PCURVE('',#148638,#148689); +#148689 = DEFINITIONAL_REPRESENTATION('',(#148690),#148694); +#148690 = LINE('',#148691,#148692); +#148691 = CARTESIAN_POINT('',(3.15,-1.7763568394E-015)); +#148692 = VECTOR('',#148693,1.); +#148693 = DIRECTION('',(6.725593854929E-015,1.)); +#148694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148695 = PCURVE('',#90516,#148696); +#148696 = DEFINITIONAL_REPRESENTATION('',(#148697),#148701); +#148697 = LINE('',#148698,#148699); +#148698 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#148699 = VECTOR('',#148700,1.); +#148700 = DIRECTION('',(0.E+000,1.)); +#148701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146324 = PCURVE('',#146325,#146330); -#146325 = CYLINDRICAL_SURFACE('',#146326,0.208574704164); -#146326 = AXIS2_PLACEMENT_3D('',#146327,#146328,#146329); -#146327 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#148702 = ORIENTED_EDGE('',*,*,#148703,.T.); +#148703 = EDGE_CURVE('',#148681,#148628,#148704,.T.); +#148704 = SURFACE_CURVE('',#148705,(#148709,#148716),.PCURVE_S1.); +#148705 = LINE('',#148706,#148707); +#148706 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, + -0.208196358798)); +#148707 = VECTOR('',#148708,1.); +#148708 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148709 = PCURVE('',#148638,#148710); +#148710 = DEFINITIONAL_REPRESENTATION('',(#148711),#148715); +#148711 = LINE('',#148712,#148713); +#148712 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148713 = VECTOR('',#148714,1.); +#148714 = DIRECTION('',(1.,-8.881784197001E-016)); +#148715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148716 = PCURVE('',#148717,#148722); +#148717 = CYLINDRICAL_SURFACE('',#148718,0.208574704164); +#148718 = AXIS2_PLACEMENT_3D('',#148719,#148720,#148721); +#148719 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#146328 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146329 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146330 = DEFINITIONAL_REPRESENTATION('',(#146331),#146334); -#146331 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146332,#146333), +#148720 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148721 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148722 = DEFINITIONAL_REPRESENTATION('',(#148723),#148726); +#148723 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148724,#148725), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#146332 = CARTESIAN_POINT('',(4.772630242227,3.15)); -#146333 = CARTESIAN_POINT('',(4.772630242227,3.35)); -#146334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146335 = ADVANCED_FACE('',(#146336),#146221,.T.); -#146336 = FACE_BOUND('',#146337,.T.); -#146337 = EDGE_LOOP('',(#146338,#146339,#146389,#146416)); -#146338 = ORIENTED_EDGE('',*,*,#146207,.F.); -#146339 = ORIENTED_EDGE('',*,*,#146340,.F.); -#146340 = EDGE_CURVE('',#146341,#146185,#146343,.T.); -#146341 = VERTEX_POINT('',#146342); -#146342 = CARTESIAN_POINT('',(3.35,10.419594812019,0.E+000)); -#146343 = SURFACE_CURVE('',#146344,(#146349,#146378),.PCURVE_S1.); -#146344 = CIRCLE('',#146345,0.308574064194); -#146345 = AXIS2_PLACEMENT_3D('',#146346,#146347,#146348); -#146346 = CARTESIAN_POINT('',(3.35,10.728168876214,2.640924866458E-017) - ); -#146347 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146348 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146349 = PCURVE('',#146221,#146350); -#146350 = DEFINITIONAL_REPRESENTATION('',(#146351),#146377); -#146351 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146352,#146353,#146354, - #146355,#146356,#146357,#146358,#146359,#146360,#146361,#146362, - #146363,#146364,#146365,#146366,#146367,#146368,#146369,#146370, - #146371,#146372,#146373,#146374,#146375,#146376),.UNSPECIFIED.,.F., +#148724 = CARTESIAN_POINT('',(4.772630242227,3.15)); +#148725 = CARTESIAN_POINT('',(4.772630242227,3.35)); +#148726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148727 = ADVANCED_FACE('',(#148728),#148613,.T.); +#148728 = FACE_BOUND('',#148729,.T.); +#148729 = EDGE_LOOP('',(#148730,#148731,#148781,#148808)); +#148730 = ORIENTED_EDGE('',*,*,#148599,.F.); +#148731 = ORIENTED_EDGE('',*,*,#148732,.F.); +#148732 = EDGE_CURVE('',#148733,#148577,#148735,.T.); +#148733 = VERTEX_POINT('',#148734); +#148734 = CARTESIAN_POINT('',(3.35,10.419594812019,0.E+000)); +#148735 = SURFACE_CURVE('',#148736,(#148741,#148770),.PCURVE_S1.); +#148736 = CIRCLE('',#148737,0.308574064194); +#148737 = AXIS2_PLACEMENT_3D('',#148738,#148739,#148740); +#148738 = CARTESIAN_POINT('',(3.35,10.728168876214,2.640924866458E-017) + ); +#148739 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148740 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148741 = PCURVE('',#148613,#148742); +#148742 = DEFINITIONAL_REPRESENTATION('',(#148743),#148769); +#148743 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#148744,#148745,#148746, + #148747,#148748,#148749,#148750,#148751,#148752,#148753,#148754, + #148755,#148756,#148757,#148758,#148759,#148760,#148761,#148762, + #148763,#148764,#148765,#148766,#148767,#148768),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -180459,102 +183461,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#146352 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#146353 = CARTESIAN_POINT('',(3.166141578807,3.35)); -#146354 = CARTESIAN_POINT('',(3.215239429242,3.35)); -#146355 = CARTESIAN_POINT('',(3.288886204895,3.35)); -#146356 = CARTESIAN_POINT('',(3.362532980548,3.35)); -#146357 = CARTESIAN_POINT('',(3.4361797562,3.35)); -#146358 = CARTESIAN_POINT('',(3.509826531853,3.35)); -#146359 = CARTESIAN_POINT('',(3.583473307505,3.35)); -#146360 = CARTESIAN_POINT('',(3.657120083158,3.35)); -#146361 = CARTESIAN_POINT('',(3.730766858811,3.35)); -#146362 = CARTESIAN_POINT('',(3.804413634463,3.35)); -#146363 = CARTESIAN_POINT('',(3.878060410116,3.35)); -#146364 = CARTESIAN_POINT('',(3.951707185768,3.35)); -#146365 = CARTESIAN_POINT('',(4.025353961421,3.35)); -#146366 = CARTESIAN_POINT('',(4.099000737074,3.35)); -#146367 = CARTESIAN_POINT('',(4.172647512726,3.35)); -#146368 = CARTESIAN_POINT('',(4.246294288379,3.35)); -#146369 = CARTESIAN_POINT('',(4.319941064031,3.35)); -#146370 = CARTESIAN_POINT('',(4.393587839684,3.35)); -#146371 = CARTESIAN_POINT('',(4.467234615337,3.35)); -#146372 = CARTESIAN_POINT('',(4.540881390989,3.35)); -#146373 = CARTESIAN_POINT('',(4.614528166642,3.35)); -#146374 = CARTESIAN_POINT('',(4.688174942294,3.35)); -#146375 = CARTESIAN_POINT('',(4.737272792729,3.35)); -#146376 = CARTESIAN_POINT('',(4.761821717947,3.35)); -#146377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146378 = PCURVE('',#88068,#146379); -#146379 = DEFINITIONAL_REPRESENTATION('',(#146380),#146388); -#146380 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146381,#146382,#146383, - #146384,#146385,#146386,#146387),.UNSPECIFIED.,.T.,.F.) +#148744 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#148745 = CARTESIAN_POINT('',(3.166141578807,3.35)); +#148746 = CARTESIAN_POINT('',(3.215239429242,3.35)); +#148747 = CARTESIAN_POINT('',(3.288886204895,3.35)); +#148748 = CARTESIAN_POINT('',(3.362532980548,3.35)); +#148749 = CARTESIAN_POINT('',(3.4361797562,3.35)); +#148750 = CARTESIAN_POINT('',(3.509826531853,3.35)); +#148751 = CARTESIAN_POINT('',(3.583473307505,3.35)); +#148752 = CARTESIAN_POINT('',(3.657120083158,3.35)); +#148753 = CARTESIAN_POINT('',(3.730766858811,3.35)); +#148754 = CARTESIAN_POINT('',(3.804413634463,3.35)); +#148755 = CARTESIAN_POINT('',(3.878060410116,3.35)); +#148756 = CARTESIAN_POINT('',(3.951707185768,3.35)); +#148757 = CARTESIAN_POINT('',(4.025353961421,3.35)); +#148758 = CARTESIAN_POINT('',(4.099000737074,3.35)); +#148759 = CARTESIAN_POINT('',(4.172647512726,3.35)); +#148760 = CARTESIAN_POINT('',(4.246294288379,3.35)); +#148761 = CARTESIAN_POINT('',(4.319941064031,3.35)); +#148762 = CARTESIAN_POINT('',(4.393587839684,3.35)); +#148763 = CARTESIAN_POINT('',(4.467234615337,3.35)); +#148764 = CARTESIAN_POINT('',(4.540881390989,3.35)); +#148765 = CARTESIAN_POINT('',(4.614528166642,3.35)); +#148766 = CARTESIAN_POINT('',(4.688174942294,3.35)); +#148767 = CARTESIAN_POINT('',(4.737272792729,3.35)); +#148768 = CARTESIAN_POINT('',(4.761821717947,3.35)); +#148769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148770 = PCURVE('',#90460,#148771); +#148771 = DEFINITIONAL_REPRESENTATION('',(#148772),#148780); +#148772 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148773,#148774,#148775, + #148776,#148777,#148778,#148779),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#146381 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#146382 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#146383 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#146384 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#146385 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#146386 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#146387 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#146388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146389 = ORIENTED_EDGE('',*,*,#146390,.F.); -#146390 = EDGE_CURVE('',#146391,#146341,#146393,.T.); -#146391 = VERTEX_POINT('',#146392); -#146392 = CARTESIAN_POINT('',(3.15,10.419594812019,0.E+000)); -#146393 = SURFACE_CURVE('',#146394,(#146398,#146404),.PCURVE_S1.); -#146394 = LINE('',#146395,#146396); -#146395 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#148773 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#148774 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#148775 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#148776 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#148777 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#148778 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#148779 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#148780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148781 = ORIENTED_EDGE('',*,*,#148782,.F.); +#148782 = EDGE_CURVE('',#148783,#148733,#148785,.T.); +#148783 = VERTEX_POINT('',#148784); +#148784 = CARTESIAN_POINT('',(3.15,10.419594812019,0.E+000)); +#148785 = SURFACE_CURVE('',#148786,(#148790,#148796),.PCURVE_S1.); +#148786 = LINE('',#148787,#148788); +#148787 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#146396 = VECTOR('',#146397,1.); -#146397 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146398 = PCURVE('',#146221,#146399); -#146399 = DEFINITIONAL_REPRESENTATION('',(#146400),#146403); -#146400 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146401,#146402), +#148788 = VECTOR('',#148789,1.); +#148789 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148790 = PCURVE('',#148613,#148791); +#148791 = DEFINITIONAL_REPRESENTATION('',(#148792),#148795); +#148792 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148793,#148794), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#146401 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#146402 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#146403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148793 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#148794 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#148795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146404 = PCURVE('',#146405,#146410); -#146405 = PLANE('',#146406); -#146406 = AXIS2_PLACEMENT_3D('',#146407,#146408,#146409); -#146407 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#148796 = PCURVE('',#148797,#148802); +#148797 = PLANE('',#148798); +#148798 = AXIS2_PLACEMENT_3D('',#148799,#148800,#148801); +#148799 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#146408 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146409 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146410 = DEFINITIONAL_REPRESENTATION('',(#146411),#146415); -#146411 = LINE('',#146412,#146413); -#146412 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#146413 = VECTOR('',#146414,1.); -#146414 = DIRECTION('',(-1.,0.E+000)); -#146415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146416 = ORIENTED_EDGE('',*,*,#146417,.T.); -#146417 = EDGE_CURVE('',#146391,#146127,#146418,.T.); -#146418 = SURFACE_CURVE('',#146419,(#146424,#146453),.PCURVE_S1.); -#146419 = CIRCLE('',#146420,0.308574064194); -#146420 = AXIS2_PLACEMENT_3D('',#146421,#146422,#146423); -#146421 = CARTESIAN_POINT('',(3.15,10.728168876214,2.640924866458E-017) - ); -#146422 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146423 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146424 = PCURVE('',#146221,#146425); -#146425 = DEFINITIONAL_REPRESENTATION('',(#146426),#146452); -#146426 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#146427,#146428,#146429, - #146430,#146431,#146432,#146433,#146434,#146435,#146436,#146437, - #146438,#146439,#146440,#146441,#146442,#146443,#146444,#146445, - #146446,#146447,#146448,#146449,#146450,#146451),.UNSPECIFIED.,.F., +#148800 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148801 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148802 = DEFINITIONAL_REPRESENTATION('',(#148803),#148807); +#148803 = LINE('',#148804,#148805); +#148804 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#148805 = VECTOR('',#148806,1.); +#148806 = DIRECTION('',(-1.,0.E+000)); +#148807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148808 = ORIENTED_EDGE('',*,*,#148809,.T.); +#148809 = EDGE_CURVE('',#148783,#148519,#148810,.T.); +#148810 = SURFACE_CURVE('',#148811,(#148816,#148845),.PCURVE_S1.); +#148811 = CIRCLE('',#148812,0.308574064194); +#148812 = AXIS2_PLACEMENT_3D('',#148813,#148814,#148815); +#148813 = CARTESIAN_POINT('',(3.15,10.728168876214,2.640924866458E-017) + ); +#148814 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148815 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148816 = PCURVE('',#148613,#148817); +#148817 = DEFINITIONAL_REPRESENTATION('',(#148818),#148844); +#148818 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#148819,#148820,#148821, + #148822,#148823,#148824,#148825,#148826,#148827,#148828,#148829, + #148830,#148831,#148832,#148833,#148834,#148835,#148836,#148837, + #148838,#148839,#148840,#148841,#148842,#148843),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -180562,994 +183564,994 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#146427 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#146428 = CARTESIAN_POINT('',(3.166141578807,3.15)); -#146429 = CARTESIAN_POINT('',(3.215239429242,3.15)); -#146430 = CARTESIAN_POINT('',(3.288886204895,3.15)); -#146431 = CARTESIAN_POINT('',(3.362532980548,3.15)); -#146432 = CARTESIAN_POINT('',(3.4361797562,3.15)); -#146433 = CARTESIAN_POINT('',(3.509826531853,3.15)); -#146434 = CARTESIAN_POINT('',(3.583473307505,3.15)); -#146435 = CARTESIAN_POINT('',(3.657120083158,3.15)); -#146436 = CARTESIAN_POINT('',(3.730766858811,3.15)); -#146437 = CARTESIAN_POINT('',(3.804413634463,3.15)); -#146438 = CARTESIAN_POINT('',(3.878060410116,3.15)); -#146439 = CARTESIAN_POINT('',(3.951707185768,3.15)); -#146440 = CARTESIAN_POINT('',(4.025353961421,3.15)); -#146441 = CARTESIAN_POINT('',(4.099000737074,3.15)); -#146442 = CARTESIAN_POINT('',(4.172647512726,3.15)); -#146443 = CARTESIAN_POINT('',(4.246294288379,3.15)); -#146444 = CARTESIAN_POINT('',(4.319941064031,3.15)); -#146445 = CARTESIAN_POINT('',(4.393587839684,3.15)); -#146446 = CARTESIAN_POINT('',(4.467234615337,3.15)); -#146447 = CARTESIAN_POINT('',(4.540881390989,3.15)); -#146448 = CARTESIAN_POINT('',(4.614528166642,3.15)); -#146449 = CARTESIAN_POINT('',(4.688174942294,3.15)); -#146450 = CARTESIAN_POINT('',(4.737272792729,3.15)); -#146451 = CARTESIAN_POINT('',(4.761821717947,3.15)); -#146452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146453 = PCURVE('',#88124,#146454); -#146454 = DEFINITIONAL_REPRESENTATION('',(#146455),#146459); -#146455 = CIRCLE('',#146456,0.308574064194); -#146456 = AXIS2_PLACEMENT_2D('',#146457,#146458); -#146457 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#146458 = DIRECTION('',(0.E+000,1.)); -#146459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146460 = ADVANCED_FACE('',(#146461),#146325,.F.); -#146461 = FACE_BOUND('',#146462,.F.); -#146462 = EDGE_LOOP('',(#146463,#146464,#146491,#146518)); -#146463 = ORIENTED_EDGE('',*,*,#146311,.T.); -#146464 = ORIENTED_EDGE('',*,*,#146465,.F.); -#146465 = EDGE_CURVE('',#146466,#146236,#146468,.T.); -#146466 = VERTEX_POINT('',#146467); -#146467 = CARTESIAN_POINT('',(3.35,10.51959417205,0.E+000)); -#146468 = SURFACE_CURVE('',#146469,(#146474,#146480),.PCURVE_S1.); -#146469 = CIRCLE('',#146470,0.208574704164); -#146470 = AXIS2_PLACEMENT_3D('',#146471,#146472,#146473); -#146471 = CARTESIAN_POINT('',(3.35,10.728168876214,2.640924866458E-017) - ); -#146472 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146473 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146474 = PCURVE('',#146325,#146475); -#146475 = DEFINITIONAL_REPRESENTATION('',(#146476),#146479); -#146476 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146477,#146478), +#148819 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#148820 = CARTESIAN_POINT('',(3.166141578807,3.15)); +#148821 = CARTESIAN_POINT('',(3.215239429242,3.15)); +#148822 = CARTESIAN_POINT('',(3.288886204895,3.15)); +#148823 = CARTESIAN_POINT('',(3.362532980548,3.15)); +#148824 = CARTESIAN_POINT('',(3.4361797562,3.15)); +#148825 = CARTESIAN_POINT('',(3.509826531853,3.15)); +#148826 = CARTESIAN_POINT('',(3.583473307505,3.15)); +#148827 = CARTESIAN_POINT('',(3.657120083158,3.15)); +#148828 = CARTESIAN_POINT('',(3.730766858811,3.15)); +#148829 = CARTESIAN_POINT('',(3.804413634463,3.15)); +#148830 = CARTESIAN_POINT('',(3.878060410116,3.15)); +#148831 = CARTESIAN_POINT('',(3.951707185768,3.15)); +#148832 = CARTESIAN_POINT('',(4.025353961421,3.15)); +#148833 = CARTESIAN_POINT('',(4.099000737074,3.15)); +#148834 = CARTESIAN_POINT('',(4.172647512726,3.15)); +#148835 = CARTESIAN_POINT('',(4.246294288379,3.15)); +#148836 = CARTESIAN_POINT('',(4.319941064031,3.15)); +#148837 = CARTESIAN_POINT('',(4.393587839684,3.15)); +#148838 = CARTESIAN_POINT('',(4.467234615337,3.15)); +#148839 = CARTESIAN_POINT('',(4.540881390989,3.15)); +#148840 = CARTESIAN_POINT('',(4.614528166642,3.15)); +#148841 = CARTESIAN_POINT('',(4.688174942294,3.15)); +#148842 = CARTESIAN_POINT('',(4.737272792729,3.15)); +#148843 = CARTESIAN_POINT('',(4.761821717947,3.15)); +#148844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148845 = PCURVE('',#90516,#148846); +#148846 = DEFINITIONAL_REPRESENTATION('',(#148847),#148851); +#148847 = CIRCLE('',#148848,0.308574064194); +#148848 = AXIS2_PLACEMENT_2D('',#148849,#148850); +#148849 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#148850 = DIRECTION('',(0.E+000,1.)); +#148851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148852 = ADVANCED_FACE('',(#148853),#148717,.F.); +#148853 = FACE_BOUND('',#148854,.F.); +#148854 = EDGE_LOOP('',(#148855,#148856,#148883,#148910)); +#148855 = ORIENTED_EDGE('',*,*,#148703,.T.); +#148856 = ORIENTED_EDGE('',*,*,#148857,.F.); +#148857 = EDGE_CURVE('',#148858,#148628,#148860,.T.); +#148858 = VERTEX_POINT('',#148859); +#148859 = CARTESIAN_POINT('',(3.35,10.51959417205,0.E+000)); +#148860 = SURFACE_CURVE('',#148861,(#148866,#148872),.PCURVE_S1.); +#148861 = CIRCLE('',#148862,0.208574704164); +#148862 = AXIS2_PLACEMENT_3D('',#148863,#148864,#148865); +#148863 = CARTESIAN_POINT('',(3.35,10.728168876214,2.640924866458E-017) + ); +#148864 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148865 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148866 = PCURVE('',#148717,#148867); +#148867 = DEFINITIONAL_REPRESENTATION('',(#148868),#148871); +#148868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148869,#148870), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#146477 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#146478 = CARTESIAN_POINT('',(4.772630242227,3.35)); -#146479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148869 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#148870 = CARTESIAN_POINT('',(4.772630242227,3.35)); +#148871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146480 = PCURVE('',#88068,#146481); -#146481 = DEFINITIONAL_REPRESENTATION('',(#146482),#146490); -#146482 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146483,#146484,#146485, - #146486,#146487,#146488,#146489),.UNSPECIFIED.,.T.,.F.) +#148872 = PCURVE('',#90460,#148873); +#148873 = DEFINITIONAL_REPRESENTATION('',(#148874),#148882); +#148874 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148875,#148876,#148877, + #148878,#148879,#148880,#148881),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#146483 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#146484 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#146485 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#146486 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#146487 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#146488 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#146489 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#146490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146491 = ORIENTED_EDGE('',*,*,#146492,.T.); -#146492 = EDGE_CURVE('',#146466,#146493,#146495,.T.); -#146493 = VERTEX_POINT('',#146494); -#146494 = CARTESIAN_POINT('',(3.15,10.51959417205,0.E+000)); -#146495 = SURFACE_CURVE('',#146496,(#146500,#146506),.PCURVE_S1.); -#146496 = LINE('',#146497,#146498); -#146497 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#148875 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#148876 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#148877 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#148878 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#148879 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#148880 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#148881 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#148882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148883 = ORIENTED_EDGE('',*,*,#148884,.T.); +#148884 = EDGE_CURVE('',#148858,#148885,#148887,.T.); +#148885 = VERTEX_POINT('',#148886); +#148886 = CARTESIAN_POINT('',(3.15,10.51959417205,0.E+000)); +#148887 = SURFACE_CURVE('',#148888,(#148892,#148898),.PCURVE_S1.); +#148888 = LINE('',#148889,#148890); +#148889 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#146498 = VECTOR('',#146499,1.); -#146499 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146500 = PCURVE('',#146325,#146501); -#146501 = DEFINITIONAL_REPRESENTATION('',(#146502),#146505); -#146502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146503,#146504), +#148890 = VECTOR('',#148891,1.); +#148891 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148892 = PCURVE('',#148717,#148893); +#148893 = DEFINITIONAL_REPRESENTATION('',(#148894),#148897); +#148894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148895,#148896), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#146503 = CARTESIAN_POINT('',(3.14159265359,3.35)); -#146504 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#146505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#148895 = CARTESIAN_POINT('',(3.14159265359,3.35)); +#148896 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#148897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146506 = PCURVE('',#146507,#146512); -#146507 = PLANE('',#146508); -#146508 = AXIS2_PLACEMENT_3D('',#146509,#146510,#146511); -#146509 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#148898 = PCURVE('',#148899,#148904); +#148899 = PLANE('',#148900); +#148900 = AXIS2_PLACEMENT_3D('',#148901,#148902,#148903); +#148901 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#146510 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146511 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146512 = DEFINITIONAL_REPRESENTATION('',(#146513),#146517); -#146513 = LINE('',#146514,#146515); -#146514 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#146515 = VECTOR('',#146516,1.); -#146516 = DIRECTION('',(-1.,0.E+000)); -#146517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146518 = ORIENTED_EDGE('',*,*,#146519,.T.); -#146519 = EDGE_CURVE('',#146493,#146289,#146520,.T.); -#146520 = SURFACE_CURVE('',#146521,(#146526,#146532),.PCURVE_S1.); -#146521 = CIRCLE('',#146522,0.208574704164); -#146522 = AXIS2_PLACEMENT_3D('',#146523,#146524,#146525); -#146523 = CARTESIAN_POINT('',(3.15,10.728168876214,2.640924866458E-017) - ); -#146524 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146525 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#146526 = PCURVE('',#146325,#146527); -#146527 = DEFINITIONAL_REPRESENTATION('',(#146528),#146531); -#146528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146529,#146530), +#148902 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148903 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148904 = DEFINITIONAL_REPRESENTATION('',(#148905),#148909); +#148905 = LINE('',#148906,#148907); +#148906 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#148907 = VECTOR('',#148908,1.); +#148908 = DIRECTION('',(-1.,0.E+000)); +#148909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148910 = ORIENTED_EDGE('',*,*,#148911,.T.); +#148911 = EDGE_CURVE('',#148885,#148681,#148912,.T.); +#148912 = SURFACE_CURVE('',#148913,(#148918,#148924),.PCURVE_S1.); +#148913 = CIRCLE('',#148914,0.208574704164); +#148914 = AXIS2_PLACEMENT_3D('',#148915,#148916,#148917); +#148915 = CARTESIAN_POINT('',(3.15,10.728168876214,2.640924866458E-017) + ); +#148916 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#148917 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#148918 = PCURVE('',#148717,#148919); +#148919 = DEFINITIONAL_REPRESENTATION('',(#148920),#148923); +#148920 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148921,#148922), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#146529 = CARTESIAN_POINT('',(3.14159265359,3.15)); -#146530 = CARTESIAN_POINT('',(4.772630242227,3.15)); -#146531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146532 = PCURVE('',#88124,#146533); -#146533 = DEFINITIONAL_REPRESENTATION('',(#146534),#146538); -#146534 = CIRCLE('',#146535,0.208574704164); -#146535 = AXIS2_PLACEMENT_2D('',#146536,#146537); -#146536 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#146537 = DIRECTION('',(0.E+000,1.)); -#146538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146539 = ADVANCED_FACE('',(#146540),#146507,.F.); -#146540 = FACE_BOUND('',#146541,.T.); -#146541 = EDGE_LOOP('',(#146542,#146571,#146592,#146593)); -#146542 = ORIENTED_EDGE('',*,*,#146543,.F.); -#146543 = EDGE_CURVE('',#146544,#146546,#146548,.T.); -#146544 = VERTEX_POINT('',#146545); -#146545 = CARTESIAN_POINT('',(3.35,10.51959417205,0.530776333563)); -#146546 = VERTEX_POINT('',#146547); -#146547 = CARTESIAN_POINT('',(3.15,10.51959417205,0.530776333563)); -#146548 = SURFACE_CURVE('',#146549,(#146553,#146560),.PCURVE_S1.); -#146549 = LINE('',#146550,#146551); -#146550 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#148921 = CARTESIAN_POINT('',(3.14159265359,3.15)); +#148922 = CARTESIAN_POINT('',(4.772630242227,3.15)); +#148923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148924 = PCURVE('',#90516,#148925); +#148925 = DEFINITIONAL_REPRESENTATION('',(#148926),#148930); +#148926 = CIRCLE('',#148927,0.208574704164); +#148927 = AXIS2_PLACEMENT_2D('',#148928,#148929); +#148928 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#148929 = DIRECTION('',(0.E+000,1.)); +#148930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148931 = ADVANCED_FACE('',(#148932),#148899,.F.); +#148932 = FACE_BOUND('',#148933,.T.); +#148933 = EDGE_LOOP('',(#148934,#148963,#148984,#148985)); +#148934 = ORIENTED_EDGE('',*,*,#148935,.F.); +#148935 = EDGE_CURVE('',#148936,#148938,#148940,.T.); +#148936 = VERTEX_POINT('',#148937); +#148937 = CARTESIAN_POINT('',(3.35,10.51959417205,0.530776333563)); +#148938 = VERTEX_POINT('',#148939); +#148939 = CARTESIAN_POINT('',(3.15,10.51959417205,0.530776333563)); +#148940 = SURFACE_CURVE('',#148941,(#148945,#148952),.PCURVE_S1.); +#148941 = LINE('',#148942,#148943); +#148942 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#146551 = VECTOR('',#146552,1.); -#146552 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146553 = PCURVE('',#146507,#146554); -#146554 = DEFINITIONAL_REPRESENTATION('',(#146555),#146559); -#146555 = LINE('',#146556,#146557); -#146556 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146557 = VECTOR('',#146558,1.); -#146558 = DIRECTION('',(-1.,0.E+000)); -#146559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146560 = PCURVE('',#146561,#146566); -#146561 = CYLINDRICAL_SURFACE('',#146562,0.2192697516); -#146562 = AXIS2_PLACEMENT_3D('',#146563,#146564,#146565); -#146563 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#148943 = VECTOR('',#148944,1.); +#148944 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148945 = PCURVE('',#148899,#148946); +#148946 = DEFINITIONAL_REPRESENTATION('',(#148947),#148951); +#148947 = LINE('',#148948,#148949); +#148948 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#148949 = VECTOR('',#148950,1.); +#148950 = DIRECTION('',(-1.,0.E+000)); +#148951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148952 = PCURVE('',#148953,#148958); +#148953 = CYLINDRICAL_SURFACE('',#148954,0.2192697516); +#148954 = AXIS2_PLACEMENT_3D('',#148955,#148956,#148957); +#148955 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#146564 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146565 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146566 = DEFINITIONAL_REPRESENTATION('',(#146567),#146570); -#146567 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146568,#146569), +#148956 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#148957 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#148958 = DEFINITIONAL_REPRESENTATION('',(#148959),#148962); +#148959 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148960,#148961), .UNSPECIFIED.,.F.,.F.,(2,2),(-3.35,-3.15),.PIECEWISE_BEZIER_KNOTS.); -#146568 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#146569 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#146570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146571 = ORIENTED_EDGE('',*,*,#146572,.T.); -#146572 = EDGE_CURVE('',#146544,#146466,#146573,.T.); -#146573 = SURFACE_CURVE('',#146574,(#146578,#146585),.PCURVE_S1.); -#146574 = LINE('',#146575,#146576); -#146575 = CARTESIAN_POINT('',(3.35,10.51959417205,0.530776333563)); -#146576 = VECTOR('',#146577,1.); -#146577 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#146578 = PCURVE('',#146507,#146579); -#146579 = DEFINITIONAL_REPRESENTATION('',(#146580),#146584); -#146580 = LINE('',#146581,#146582); -#146581 = CARTESIAN_POINT('',(3.35,0.E+000)); -#146582 = VECTOR('',#146583,1.); -#146583 = DIRECTION('',(0.E+000,-1.)); -#146584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146585 = PCURVE('',#88068,#146586); -#146586 = DEFINITIONAL_REPRESENTATION('',(#146587),#146591); -#146587 = LINE('',#146588,#146589); -#146588 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); -#146589 = VECTOR('',#146590,1.); -#146590 = DIRECTION('',(-1.,0.E+000)); -#146591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146592 = ORIENTED_EDGE('',*,*,#146492,.T.); -#146593 = ORIENTED_EDGE('',*,*,#146594,.F.); -#146594 = EDGE_CURVE('',#146546,#146493,#146595,.T.); -#146595 = SURFACE_CURVE('',#146596,(#146600,#146607),.PCURVE_S1.); -#146596 = LINE('',#146597,#146598); -#146597 = CARTESIAN_POINT('',(3.15,10.51959417205,0.530776333563)); -#146598 = VECTOR('',#146599,1.); -#146599 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#146600 = PCURVE('',#146507,#146601); -#146601 = DEFINITIONAL_REPRESENTATION('',(#146602),#146606); -#146602 = LINE('',#146603,#146604); -#146603 = CARTESIAN_POINT('',(3.15,0.E+000)); -#146604 = VECTOR('',#146605,1.); -#146605 = DIRECTION('',(0.E+000,-1.)); -#146606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146607 = PCURVE('',#88124,#146608); -#146608 = DEFINITIONAL_REPRESENTATION('',(#146609),#146613); -#146609 = LINE('',#146610,#146611); -#146610 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); -#146611 = VECTOR('',#146612,1.); -#146612 = DIRECTION('',(1.,0.E+000)); -#146613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146614 = ADVANCED_FACE('',(#146615),#146405,.F.); -#146615 = FACE_BOUND('',#146616,.T.); -#146616 = EDGE_LOOP('',(#146617,#146646,#146667,#146668)); -#146617 = ORIENTED_EDGE('',*,*,#146618,.F.); -#146618 = EDGE_CURVE('',#146619,#146621,#146623,.T.); -#146619 = VERTEX_POINT('',#146620); -#146620 = CARTESIAN_POINT('',(3.15,10.419594812019,0.530776333563)); -#146621 = VERTEX_POINT('',#146622); -#146622 = CARTESIAN_POINT('',(3.35,10.419594812019,0.530776333563)); -#146623 = SURFACE_CURVE('',#146624,(#146628,#146635),.PCURVE_S1.); -#146624 = LINE('',#146625,#146626); -#146625 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#148960 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#148961 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#148962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148963 = ORIENTED_EDGE('',*,*,#148964,.T.); +#148964 = EDGE_CURVE('',#148936,#148858,#148965,.T.); +#148965 = SURFACE_CURVE('',#148966,(#148970,#148977),.PCURVE_S1.); +#148966 = LINE('',#148967,#148968); +#148967 = CARTESIAN_POINT('',(3.35,10.51959417205,0.530776333563)); +#148968 = VECTOR('',#148969,1.); +#148969 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148970 = PCURVE('',#148899,#148971); +#148971 = DEFINITIONAL_REPRESENTATION('',(#148972),#148976); +#148972 = LINE('',#148973,#148974); +#148973 = CARTESIAN_POINT('',(3.35,0.E+000)); +#148974 = VECTOR('',#148975,1.); +#148975 = DIRECTION('',(0.E+000,-1.)); +#148976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148977 = PCURVE('',#90460,#148978); +#148978 = DEFINITIONAL_REPRESENTATION('',(#148979),#148983); +#148979 = LINE('',#148980,#148981); +#148980 = CARTESIAN_POINT('',(-0.119223666437,-8.25382038863E-003)); +#148981 = VECTOR('',#148982,1.); +#148982 = DIRECTION('',(-1.,0.E+000)); +#148983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148984 = ORIENTED_EDGE('',*,*,#148884,.T.); +#148985 = ORIENTED_EDGE('',*,*,#148986,.F.); +#148986 = EDGE_CURVE('',#148938,#148885,#148987,.T.); +#148987 = SURFACE_CURVE('',#148988,(#148992,#148999),.PCURVE_S1.); +#148988 = LINE('',#148989,#148990); +#148989 = CARTESIAN_POINT('',(3.15,10.51959417205,0.530776333563)); +#148990 = VECTOR('',#148991,1.); +#148991 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#148992 = PCURVE('',#148899,#148993); +#148993 = DEFINITIONAL_REPRESENTATION('',(#148994),#148998); +#148994 = LINE('',#148995,#148996); +#148995 = CARTESIAN_POINT('',(3.15,0.E+000)); +#148996 = VECTOR('',#148997,1.); +#148997 = DIRECTION('',(0.E+000,-1.)); +#148998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#148999 = PCURVE('',#90516,#149000); +#149000 = DEFINITIONAL_REPRESENTATION('',(#149001),#149005); +#149001 = LINE('',#149002,#149003); +#149002 = CARTESIAN_POINT('',(0.119223666437,-8.25382038863E-003)); +#149003 = VECTOR('',#149004,1.); +#149004 = DIRECTION('',(1.,0.E+000)); +#149005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149006 = ADVANCED_FACE('',(#149007),#148797,.F.); +#149007 = FACE_BOUND('',#149008,.T.); +#149008 = EDGE_LOOP('',(#149009,#149038,#149059,#149060)); +#149009 = ORIENTED_EDGE('',*,*,#149010,.F.); +#149010 = EDGE_CURVE('',#149011,#149013,#149015,.T.); +#149011 = VERTEX_POINT('',#149012); +#149012 = CARTESIAN_POINT('',(3.15,10.419594812019,0.530776333563)); +#149013 = VERTEX_POINT('',#149014); +#149014 = CARTESIAN_POINT('',(3.35,10.419594812019,0.530776333563)); +#149015 = SURFACE_CURVE('',#149016,(#149020,#149027),.PCURVE_S1.); +#149016 = LINE('',#149017,#149018); +#149017 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#146626 = VECTOR('',#146627,1.); -#146627 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146628 = PCURVE('',#146405,#146629); -#146629 = DEFINITIONAL_REPRESENTATION('',(#146630),#146634); -#146630 = LINE('',#146631,#146632); -#146631 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146632 = VECTOR('',#146633,1.); -#146633 = DIRECTION('',(-1.,0.E+000)); -#146634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146635 = PCURVE('',#146636,#146641); -#146636 = CYLINDRICAL_SURFACE('',#146637,0.119270391569); -#146637 = AXIS2_PLACEMENT_3D('',#146638,#146639,#146640); -#146638 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#149018 = VECTOR('',#149019,1.); +#149019 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149020 = PCURVE('',#148797,#149021); +#149021 = DEFINITIONAL_REPRESENTATION('',(#149022),#149026); +#149022 = LINE('',#149023,#149024); +#149023 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149024 = VECTOR('',#149025,1.); +#149025 = DIRECTION('',(-1.,0.E+000)); +#149026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149027 = PCURVE('',#149028,#149033); +#149028 = CYLINDRICAL_SURFACE('',#149029,0.119270391569); +#149029 = AXIS2_PLACEMENT_3D('',#149030,#149031,#149032); +#149030 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#146639 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146640 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146641 = DEFINITIONAL_REPRESENTATION('',(#146642),#146645); -#146642 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146643,#146644), +#149031 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149032 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149033 = DEFINITIONAL_REPRESENTATION('',(#149034),#149037); +#149034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149035,#149036), .UNSPECIFIED.,.F.,.F.,(2,2),(3.15,3.35),.PIECEWISE_BEZIER_KNOTS.); -#146643 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#146644 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#146645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146646 = ORIENTED_EDGE('',*,*,#146647,.T.); -#146647 = EDGE_CURVE('',#146619,#146391,#146648,.T.); -#146648 = SURFACE_CURVE('',#146649,(#146653,#146660),.PCURVE_S1.); -#146649 = LINE('',#146650,#146651); -#146650 = CARTESIAN_POINT('',(3.15,10.419594812019,0.530776333563)); -#146651 = VECTOR('',#146652,1.); -#146652 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#146653 = PCURVE('',#146405,#146654); -#146654 = DEFINITIONAL_REPRESENTATION('',(#146655),#146659); -#146655 = LINE('',#146656,#146657); -#146656 = CARTESIAN_POINT('',(-3.15,0.E+000)); -#146657 = VECTOR('',#146658,1.); -#146658 = DIRECTION('',(0.E+000,-1.)); -#146659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146660 = PCURVE('',#88124,#146661); -#146661 = DEFINITIONAL_REPRESENTATION('',(#146662),#146666); -#146662 = LINE('',#146663,#146664); -#146663 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#146664 = VECTOR('',#146665,1.); -#146665 = DIRECTION('',(1.,0.E+000)); -#146666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146667 = ORIENTED_EDGE('',*,*,#146390,.T.); -#146668 = ORIENTED_EDGE('',*,*,#146669,.F.); -#146669 = EDGE_CURVE('',#146621,#146341,#146670,.T.); -#146670 = SURFACE_CURVE('',#146671,(#146675,#146682),.PCURVE_S1.); -#146671 = LINE('',#146672,#146673); -#146672 = CARTESIAN_POINT('',(3.35,10.419594812019,0.530776333563)); -#146673 = VECTOR('',#146674,1.); -#146674 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#146675 = PCURVE('',#146405,#146676); -#146676 = DEFINITIONAL_REPRESENTATION('',(#146677),#146681); -#146677 = LINE('',#146678,#146679); -#146678 = CARTESIAN_POINT('',(-3.35,0.E+000)); -#146679 = VECTOR('',#146680,1.); -#146680 = DIRECTION('',(0.E+000,-1.)); -#146681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146682 = PCURVE('',#88068,#146683); -#146683 = DEFINITIONAL_REPRESENTATION('',(#146684),#146688); -#146684 = LINE('',#146685,#146686); -#146685 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#146686 = VECTOR('',#146687,1.); -#146687 = DIRECTION('',(-1.,0.E+000)); -#146688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146689 = ADVANCED_FACE('',(#146690),#146561,.T.); -#146690 = FACE_BOUND('',#146691,.T.); -#146691 = EDGE_LOOP('',(#146692,#146715,#146716,#146743)); -#146692 = ORIENTED_EDGE('',*,*,#146693,.T.); -#146693 = EDGE_CURVE('',#146694,#146544,#146696,.T.); -#146694 = VERTEX_POINT('',#146695); -#146695 = CARTESIAN_POINT('',(3.35,10.304819755875,0.75)); -#146696 = SURFACE_CURVE('',#146697,(#146702,#146708),.PCURVE_S1.); -#146697 = CIRCLE('',#146698,0.2192697516); -#146698 = AXIS2_PLACEMENT_3D('',#146699,#146700,#146701); -#146699 = CARTESIAN_POINT('',(3.35,10.30032442045,0.530776333563)); -#146700 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146701 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146702 = PCURVE('',#146561,#146703); -#146703 = DEFINITIONAL_REPRESENTATION('',(#146704),#146707); -#146704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146705,#146706), +#149035 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#149036 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#149037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149038 = ORIENTED_EDGE('',*,*,#149039,.T.); +#149039 = EDGE_CURVE('',#149011,#148783,#149040,.T.); +#149040 = SURFACE_CURVE('',#149041,(#149045,#149052),.PCURVE_S1.); +#149041 = LINE('',#149042,#149043); +#149042 = CARTESIAN_POINT('',(3.15,10.419594812019,0.530776333563)); +#149043 = VECTOR('',#149044,1.); +#149044 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149045 = PCURVE('',#148797,#149046); +#149046 = DEFINITIONAL_REPRESENTATION('',(#149047),#149051); +#149047 = LINE('',#149048,#149049); +#149048 = CARTESIAN_POINT('',(-3.15,0.E+000)); +#149049 = VECTOR('',#149050,1.); +#149050 = DIRECTION('',(0.E+000,-1.)); +#149051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149052 = PCURVE('',#90516,#149053); +#149053 = DEFINITIONAL_REPRESENTATION('',(#149054),#149058); +#149054 = LINE('',#149055,#149056); +#149055 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#149056 = VECTOR('',#149057,1.); +#149057 = DIRECTION('',(1.,0.E+000)); +#149058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149059 = ORIENTED_EDGE('',*,*,#148782,.T.); +#149060 = ORIENTED_EDGE('',*,*,#149061,.F.); +#149061 = EDGE_CURVE('',#149013,#148733,#149062,.T.); +#149062 = SURFACE_CURVE('',#149063,(#149067,#149074),.PCURVE_S1.); +#149063 = LINE('',#149064,#149065); +#149064 = CARTESIAN_POINT('',(3.35,10.419594812019,0.530776333563)); +#149065 = VECTOR('',#149066,1.); +#149066 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149067 = PCURVE('',#148797,#149068); +#149068 = DEFINITIONAL_REPRESENTATION('',(#149069),#149073); +#149069 = LINE('',#149070,#149071); +#149070 = CARTESIAN_POINT('',(-3.35,0.E+000)); +#149071 = VECTOR('',#149072,1.); +#149072 = DIRECTION('',(0.E+000,-1.)); +#149073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149074 = PCURVE('',#90460,#149075); +#149075 = DEFINITIONAL_REPRESENTATION('',(#149076),#149080); +#149076 = LINE('',#149077,#149078); +#149077 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#149078 = VECTOR('',#149079,1.); +#149079 = DIRECTION('',(-1.,0.E+000)); +#149080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149081 = ADVANCED_FACE('',(#149082),#148953,.T.); +#149082 = FACE_BOUND('',#149083,.T.); +#149083 = EDGE_LOOP('',(#149084,#149107,#149108,#149135)); +#149084 = ORIENTED_EDGE('',*,*,#149085,.T.); +#149085 = EDGE_CURVE('',#149086,#148936,#149088,.T.); +#149086 = VERTEX_POINT('',#149087); +#149087 = CARTESIAN_POINT('',(3.35,10.304819755875,0.75)); +#149088 = SURFACE_CURVE('',#149089,(#149094,#149100),.PCURVE_S1.); +#149089 = CIRCLE('',#149090,0.2192697516); +#149090 = AXIS2_PLACEMENT_3D('',#149091,#149092,#149093); +#149091 = CARTESIAN_POINT('',(3.35,10.30032442045,0.530776333563)); +#149092 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149093 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149094 = PCURVE('',#148953,#149095); +#149095 = DEFINITIONAL_REPRESENTATION('',(#149096),#149099); +#149096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149097,#149098), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#146705 = CARTESIAN_POINT('',(1.591299156552,-3.35)); -#146706 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#146707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146708 = PCURVE('',#88068,#146709); -#146709 = DEFINITIONAL_REPRESENTATION('',(#146710),#146714); -#146710 = CIRCLE('',#146711,0.2192697516); -#146711 = AXIS2_PLACEMENT_2D('',#146712,#146713); -#146712 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#146713 = DIRECTION('',(0.E+000,-1.)); -#146714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146715 = ORIENTED_EDGE('',*,*,#146543,.T.); -#146716 = ORIENTED_EDGE('',*,*,#146717,.F.); -#146717 = EDGE_CURVE('',#146718,#146546,#146720,.T.); -#146718 = VERTEX_POINT('',#146719); -#146719 = CARTESIAN_POINT('',(3.15,10.304819755875,0.75)); -#146720 = SURFACE_CURVE('',#146721,(#146726,#146732),.PCURVE_S1.); -#146721 = CIRCLE('',#146722,0.2192697516); -#146722 = AXIS2_PLACEMENT_3D('',#146723,#146724,#146725); -#146723 = CARTESIAN_POINT('',(3.15,10.30032442045,0.530776333563)); -#146724 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146725 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146726 = PCURVE('',#146561,#146727); -#146727 = DEFINITIONAL_REPRESENTATION('',(#146728),#146731); -#146728 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146729,#146730), +#149097 = CARTESIAN_POINT('',(1.591299156552,-3.35)); +#149098 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#149099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149100 = PCURVE('',#90460,#149101); +#149101 = DEFINITIONAL_REPRESENTATION('',(#149102),#149106); +#149102 = CIRCLE('',#149103,0.2192697516); +#149103 = AXIS2_PLACEMENT_2D('',#149104,#149105); +#149104 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#149105 = DIRECTION('',(0.E+000,-1.)); +#149106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149107 = ORIENTED_EDGE('',*,*,#148935,.T.); +#149108 = ORIENTED_EDGE('',*,*,#149109,.F.); +#149109 = EDGE_CURVE('',#149110,#148938,#149112,.T.); +#149110 = VERTEX_POINT('',#149111); +#149111 = CARTESIAN_POINT('',(3.15,10.304819755875,0.75)); +#149112 = SURFACE_CURVE('',#149113,(#149118,#149124),.PCURVE_S1.); +#149113 = CIRCLE('',#149114,0.2192697516); +#149114 = AXIS2_PLACEMENT_3D('',#149115,#149116,#149117); +#149115 = CARTESIAN_POINT('',(3.15,10.30032442045,0.530776333563)); +#149116 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149117 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149118 = PCURVE('',#148953,#149119); +#149119 = DEFINITIONAL_REPRESENTATION('',(#149120),#149123); +#149120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149121,#149122), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#146729 = CARTESIAN_POINT('',(1.591299156552,-3.15)); -#146730 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#146731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149121 = CARTESIAN_POINT('',(1.591299156552,-3.15)); +#149122 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#149123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146732 = PCURVE('',#88124,#146733); -#146733 = DEFINITIONAL_REPRESENTATION('',(#146734),#146742); -#146734 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146735,#146736,#146737, - #146738,#146739,#146740,#146741),.UNSPECIFIED.,.T.,.F.) +#149124 = PCURVE('',#90516,#149125); +#149125 = DEFINITIONAL_REPRESENTATION('',(#149126),#149134); +#149126 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149127,#149128,#149129, + #149130,#149131,#149132,#149133),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#146735 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#146736 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#146737 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#146738 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#146739 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#146740 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#146741 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#146742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146743 = ORIENTED_EDGE('',*,*,#146744,.T.); -#146744 = EDGE_CURVE('',#146718,#146694,#146745,.T.); -#146745 = SURFACE_CURVE('',#146746,(#146750,#146756),.PCURVE_S1.); -#146746 = LINE('',#146747,#146748); -#146747 = CARTESIAN_POINT('',(3.35,10.304819755875,0.75)); -#146748 = VECTOR('',#146749,1.); -#146749 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#146750 = PCURVE('',#146561,#146751); -#146751 = DEFINITIONAL_REPRESENTATION('',(#146752),#146755); -#146752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146753,#146754), +#149127 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#149128 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#149129 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#149130 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#149131 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#149132 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#149133 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#149134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149135 = ORIENTED_EDGE('',*,*,#149136,.T.); +#149136 = EDGE_CURVE('',#149110,#149086,#149137,.T.); +#149137 = SURFACE_CURVE('',#149138,(#149142,#149148),.PCURVE_S1.); +#149138 = LINE('',#149139,#149140); +#149139 = CARTESIAN_POINT('',(3.35,10.304819755875,0.75)); +#149140 = VECTOR('',#149141,1.); +#149141 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149142 = PCURVE('',#148953,#149143); +#149143 = DEFINITIONAL_REPRESENTATION('',(#149144),#149147); +#149144 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149145,#149146), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#146753 = CARTESIAN_POINT('',(1.591299156552,-3.15)); -#146754 = CARTESIAN_POINT('',(1.591299156552,-3.35)); -#146755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146756 = PCURVE('',#88096,#146757); -#146757 = DEFINITIONAL_REPRESENTATION('',(#146758),#146762); -#146758 = LINE('',#146759,#146760); -#146759 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#146760 = VECTOR('',#146761,1.); -#146761 = DIRECTION('',(-8.881784197001E-016,1.)); -#146762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146763 = ADVANCED_FACE('',(#146764),#146636,.F.); -#146764 = FACE_BOUND('',#146765,.F.); -#146765 = EDGE_LOOP('',(#146766,#146793,#146815,#146836)); -#146766 = ORIENTED_EDGE('',*,*,#146767,.F.); -#146767 = EDGE_CURVE('',#146768,#146619,#146770,.T.); -#146768 = VERTEX_POINT('',#146769); -#146769 = CARTESIAN_POINT('',(3.15,10.303662633502,0.65)); -#146770 = SURFACE_CURVE('',#146771,(#146776,#146782),.PCURVE_S1.); -#146771 = CIRCLE('',#146772,0.119270391569); -#146772 = AXIS2_PLACEMENT_3D('',#146773,#146774,#146775); -#146773 = CARTESIAN_POINT('',(3.15,10.30032442045,0.530776333563)); -#146774 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146775 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146776 = PCURVE('',#146636,#146777); -#146777 = DEFINITIONAL_REPRESENTATION('',(#146778),#146781); -#146778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146779,#146780), +#149145 = CARTESIAN_POINT('',(1.591299156552,-3.15)); +#149146 = CARTESIAN_POINT('',(1.591299156552,-3.35)); +#149147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149148 = PCURVE('',#90488,#149149); +#149149 = DEFINITIONAL_REPRESENTATION('',(#149150),#149154); +#149150 = LINE('',#149151,#149152); +#149151 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#149152 = VECTOR('',#149153,1.); +#149153 = DIRECTION('',(-8.881784197001E-016,1.)); +#149154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149155 = ADVANCED_FACE('',(#149156),#149028,.F.); +#149156 = FACE_BOUND('',#149157,.F.); +#149157 = EDGE_LOOP('',(#149158,#149185,#149207,#149228)); +#149158 = ORIENTED_EDGE('',*,*,#149159,.F.); +#149159 = EDGE_CURVE('',#149160,#149011,#149162,.T.); +#149160 = VERTEX_POINT('',#149161); +#149161 = CARTESIAN_POINT('',(3.15,10.303662633502,0.65)); +#149162 = SURFACE_CURVE('',#149163,(#149168,#149174),.PCURVE_S1.); +#149163 = CIRCLE('',#149164,0.119270391569); +#149164 = AXIS2_PLACEMENT_3D('',#149165,#149166,#149167); +#149165 = CARTESIAN_POINT('',(3.15,10.30032442045,0.530776333563)); +#149166 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149167 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149168 = PCURVE('',#149028,#149169); +#149169 = DEFINITIONAL_REPRESENTATION('',(#149170),#149173); +#149170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149171,#149172), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#146779 = CARTESIAN_POINT('',(1.598788597134,-3.15)); -#146780 = CARTESIAN_POINT('',(3.14159265359,-3.15)); -#146781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149171 = CARTESIAN_POINT('',(1.598788597134,-3.15)); +#149172 = CARTESIAN_POINT('',(3.14159265359,-3.15)); +#149173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146782 = PCURVE('',#88124,#146783); -#146783 = DEFINITIONAL_REPRESENTATION('',(#146784),#146792); -#146784 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#146785,#146786,#146787, - #146788,#146789,#146790,#146791),.UNSPECIFIED.,.T.,.F.) +#149174 = PCURVE('',#90516,#149175); +#149175 = DEFINITIONAL_REPRESENTATION('',(#149176),#149184); +#149176 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149177,#149178,#149179, + #149180,#149181,#149182,#149183),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#146785 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#146786 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#146787 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#146788 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#146789 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#146790 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#146791 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#146792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146793 = ORIENTED_EDGE('',*,*,#146794,.F.); -#146794 = EDGE_CURVE('',#146795,#146768,#146797,.T.); -#146795 = VERTEX_POINT('',#146796); -#146796 = CARTESIAN_POINT('',(3.35,10.303662633502,0.65)); -#146797 = SURFACE_CURVE('',#146798,(#146802,#146808),.PCURVE_S1.); -#146798 = LINE('',#146799,#146800); -#146799 = CARTESIAN_POINT('',(3.35,10.303662633502,0.65)); -#146800 = VECTOR('',#146801,1.); -#146801 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146802 = PCURVE('',#146636,#146803); -#146803 = DEFINITIONAL_REPRESENTATION('',(#146804),#146807); -#146804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146805,#146806), +#149177 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#149178 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#149179 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#149180 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#149181 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#149182 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#149183 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#149184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149185 = ORIENTED_EDGE('',*,*,#149186,.F.); +#149186 = EDGE_CURVE('',#149187,#149160,#149189,.T.); +#149187 = VERTEX_POINT('',#149188); +#149188 = CARTESIAN_POINT('',(3.35,10.303662633502,0.65)); +#149189 = SURFACE_CURVE('',#149190,(#149194,#149200),.PCURVE_S1.); +#149190 = LINE('',#149191,#149192); +#149191 = CARTESIAN_POINT('',(3.35,10.303662633502,0.65)); +#149192 = VECTOR('',#149193,1.); +#149193 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149194 = PCURVE('',#149028,#149195); +#149195 = DEFINITIONAL_REPRESENTATION('',(#149196),#149199); +#149196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149197,#149198), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#146805 = CARTESIAN_POINT('',(1.598788597134,-3.35)); -#146806 = CARTESIAN_POINT('',(1.598788597134,-3.15)); -#146807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146808 = PCURVE('',#88150,#146809); -#146809 = DEFINITIONAL_REPRESENTATION('',(#146810),#146814); -#146810 = LINE('',#146811,#146812); -#146811 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#146812 = VECTOR('',#146813,1.); -#146813 = DIRECTION('',(-8.881784197001E-016,-1.)); -#146814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146815 = ORIENTED_EDGE('',*,*,#146816,.T.); -#146816 = EDGE_CURVE('',#146795,#146621,#146817,.T.); -#146817 = SURFACE_CURVE('',#146818,(#146823,#146829),.PCURVE_S1.); -#146818 = CIRCLE('',#146819,0.119270391569); -#146819 = AXIS2_PLACEMENT_3D('',#146820,#146821,#146822); -#146820 = CARTESIAN_POINT('',(3.35,10.30032442045,0.530776333563)); -#146821 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#146822 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#146823 = PCURVE('',#146636,#146824); -#146824 = DEFINITIONAL_REPRESENTATION('',(#146825),#146828); -#146825 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#146826,#146827), +#149197 = CARTESIAN_POINT('',(1.598788597134,-3.35)); +#149198 = CARTESIAN_POINT('',(1.598788597134,-3.15)); +#149199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149200 = PCURVE('',#90542,#149201); +#149201 = DEFINITIONAL_REPRESENTATION('',(#149202),#149206); +#149202 = LINE('',#149203,#149204); +#149203 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#149204 = VECTOR('',#149205,1.); +#149205 = DIRECTION('',(-8.881784197001E-016,-1.)); +#149206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149207 = ORIENTED_EDGE('',*,*,#149208,.T.); +#149208 = EDGE_CURVE('',#149187,#149013,#149209,.T.); +#149209 = SURFACE_CURVE('',#149210,(#149215,#149221),.PCURVE_S1.); +#149210 = CIRCLE('',#149211,0.119270391569); +#149211 = AXIS2_PLACEMENT_3D('',#149212,#149213,#149214); +#149212 = CARTESIAN_POINT('',(3.35,10.30032442045,0.530776333563)); +#149213 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149214 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149215 = PCURVE('',#149028,#149216); +#149216 = DEFINITIONAL_REPRESENTATION('',(#149217),#149220); +#149217 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149218,#149219), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#146826 = CARTESIAN_POINT('',(1.598788597134,-3.35)); -#146827 = CARTESIAN_POINT('',(3.14159265359,-3.35)); -#146828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146829 = PCURVE('',#88068,#146830); -#146830 = DEFINITIONAL_REPRESENTATION('',(#146831),#146835); -#146831 = CIRCLE('',#146832,0.119270391569); -#146832 = AXIS2_PLACEMENT_2D('',#146833,#146834); -#146833 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#146834 = DIRECTION('',(0.E+000,-1.)); -#146835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146836 = ORIENTED_EDGE('',*,*,#146618,.F.); -#146837 = ADVANCED_FACE('',(#146838),#88068,.F.); -#146838 = FACE_BOUND('',#146839,.T.); -#146839 = EDGE_LOOP('',(#146840,#146861,#146862,#146863,#146864,#146865, - #146886,#146887,#146888,#146889,#146890,#146911)); -#146840 = ORIENTED_EDGE('',*,*,#146841,.F.); -#146841 = EDGE_CURVE('',#146795,#88053,#146842,.T.); -#146842 = SURFACE_CURVE('',#146843,(#146847,#146854),.PCURVE_S1.); -#146843 = LINE('',#146844,#146845); -#146844 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); -#146845 = VECTOR('',#146846,1.); -#146846 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146847 = PCURVE('',#88068,#146848); -#146848 = DEFINITIONAL_REPRESENTATION('',(#146849),#146853); -#146849 = LINE('',#146850,#146851); -#146850 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146851 = VECTOR('',#146852,1.); -#146852 = DIRECTION('',(3.563627120235E-016,-1.)); -#146853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146854 = PCURVE('',#88150,#146855); -#146855 = DEFINITIONAL_REPRESENTATION('',(#146856),#146860); -#146856 = LINE('',#146857,#146858); -#146857 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146858 = VECTOR('',#146859,1.); -#146859 = DIRECTION('',(1.,6.005309793447E-063)); -#146860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149218 = CARTESIAN_POINT('',(1.598788597134,-3.35)); +#149219 = CARTESIAN_POINT('',(3.14159265359,-3.35)); +#149220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149221 = PCURVE('',#90460,#149222); +#149222 = DEFINITIONAL_REPRESENTATION('',(#149223),#149227); +#149223 = CIRCLE('',#149224,0.119270391569); +#149224 = AXIS2_PLACEMENT_2D('',#149225,#149226); +#149225 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#149226 = DIRECTION('',(0.E+000,-1.)); +#149227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149228 = ORIENTED_EDGE('',*,*,#149010,.F.); +#149229 = ADVANCED_FACE('',(#149230),#90460,.F.); +#149230 = FACE_BOUND('',#149231,.T.); +#149231 = EDGE_LOOP('',(#149232,#149253,#149254,#149255,#149256,#149257, + #149278,#149279,#149280,#149281,#149282,#149303)); +#149232 = ORIENTED_EDGE('',*,*,#149233,.F.); +#149233 = EDGE_CURVE('',#149187,#90445,#149234,.T.); +#149234 = SURFACE_CURVE('',#149235,(#149239,#149246),.PCURVE_S1.); +#149235 = LINE('',#149236,#149237); +#149236 = CARTESIAN_POINT('',(3.35,10.527847992439,0.65)); +#149237 = VECTOR('',#149238,1.); +#149238 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#149239 = PCURVE('',#90460,#149240); +#149240 = DEFINITIONAL_REPRESENTATION('',(#149241),#149245); +#149241 = LINE('',#149242,#149243); +#149242 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149243 = VECTOR('',#149244,1.); +#149244 = DIRECTION('',(3.563627120235E-016,-1.)); +#149245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149246 = PCURVE('',#90542,#149247); +#149247 = DEFINITIONAL_REPRESENTATION('',(#149248),#149252); +#149248 = LINE('',#149249,#149250); +#149249 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149250 = VECTOR('',#149251,1.); +#149251 = DIRECTION('',(1.,6.005309793447E-063)); +#149252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149253 = ORIENTED_EDGE('',*,*,#149208,.T.); +#149254 = ORIENTED_EDGE('',*,*,#149061,.T.); +#149255 = ORIENTED_EDGE('',*,*,#148732,.T.); +#149256 = ORIENTED_EDGE('',*,*,#148576,.T.); +#149257 = ORIENTED_EDGE('',*,*,#149258,.T.); +#149258 = EDGE_CURVE('',#148549,#148630,#149259,.T.); +#149259 = SURFACE_CURVE('',#149260,(#149264,#149271),.PCURVE_S1.); +#149260 = LINE('',#149261,#149262); +#149261 = CARTESIAN_POINT('',(3.35,11.,1.159810404338E-002)); +#149262 = VECTOR('',#149263,1.); +#149263 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#149264 = PCURVE('',#90460,#149265); +#149265 = DEFINITIONAL_REPRESENTATION('',(#149266),#149270); +#149266 = LINE('',#149267,#149268); +#149267 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#149268 = VECTOR('',#149269,1.); +#149269 = DIRECTION('',(1.,2.101748079665E-016)); +#149270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149271 = PCURVE('',#148564,#149272); +#149272 = DEFINITIONAL_REPRESENTATION('',(#149273),#149277); +#149273 = LINE('',#149274,#149275); +#149274 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#149275 = VECTOR('',#149276,1.); +#149276 = DIRECTION('',(-1.570395187386E-016,1.)); +#149277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149278 = ORIENTED_EDGE('',*,*,#148627,.F.); +#149279 = ORIENTED_EDGE('',*,*,#148857,.F.); +#149280 = ORIENTED_EDGE('',*,*,#148964,.F.); +#149281 = ORIENTED_EDGE('',*,*,#149085,.F.); +#149282 = ORIENTED_EDGE('',*,*,#149283,.T.); +#149283 = EDGE_CURVE('',#149086,#90443,#149284,.T.); +#149284 = SURFACE_CURVE('',#149285,(#149289,#149296),.PCURVE_S1.); +#149285 = LINE('',#149286,#149287); +#149286 = CARTESIAN_POINT('',(3.35,10.527847992439,0.75)); +#149287 = VECTOR('',#149288,1.); +#149288 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#149289 = PCURVE('',#90460,#149290); +#149290 = DEFINITIONAL_REPRESENTATION('',(#149291),#149295); +#149291 = LINE('',#149292,#149293); +#149292 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#149293 = VECTOR('',#149294,1.); +#149294 = DIRECTION('',(3.563627120235E-016,-1.)); +#149295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#146861 = ORIENTED_EDGE('',*,*,#146816,.T.); -#146862 = ORIENTED_EDGE('',*,*,#146669,.T.); -#146863 = ORIENTED_EDGE('',*,*,#146340,.T.); -#146864 = ORIENTED_EDGE('',*,*,#146184,.T.); -#146865 = ORIENTED_EDGE('',*,*,#146866,.T.); -#146866 = EDGE_CURVE('',#146157,#146238,#146867,.T.); -#146867 = SURFACE_CURVE('',#146868,(#146872,#146879),.PCURVE_S1.); -#146868 = LINE('',#146869,#146870); -#146869 = CARTESIAN_POINT('',(3.35,11.,1.159810404338E-002)); -#146870 = VECTOR('',#146871,1.); -#146871 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#146872 = PCURVE('',#88068,#146873); -#146873 = DEFINITIONAL_REPRESENTATION('',(#146874),#146878); -#146874 = LINE('',#146875,#146876); -#146875 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#146876 = VECTOR('',#146877,1.); -#146877 = DIRECTION('',(1.,2.101748079665E-016)); -#146878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146879 = PCURVE('',#146172,#146880); -#146880 = DEFINITIONAL_REPRESENTATION('',(#146881),#146885); -#146881 = LINE('',#146882,#146883); -#146882 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#146883 = VECTOR('',#146884,1.); -#146884 = DIRECTION('',(-1.570395187386E-016,1.)); -#146885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146886 = ORIENTED_EDGE('',*,*,#146235,.F.); -#146887 = ORIENTED_EDGE('',*,*,#146465,.F.); -#146888 = ORIENTED_EDGE('',*,*,#146572,.F.); -#146889 = ORIENTED_EDGE('',*,*,#146693,.F.); -#146890 = ORIENTED_EDGE('',*,*,#146891,.T.); -#146891 = EDGE_CURVE('',#146694,#88051,#146892,.T.); -#146892 = SURFACE_CURVE('',#146893,(#146897,#146904),.PCURVE_S1.); -#146893 = LINE('',#146894,#146895); -#146894 = CARTESIAN_POINT('',(3.35,10.527847992439,0.75)); -#146895 = VECTOR('',#146896,1.); -#146896 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146897 = PCURVE('',#88068,#146898); -#146898 = DEFINITIONAL_REPRESENTATION('',(#146899),#146903); -#146899 = LINE('',#146900,#146901); -#146900 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#146901 = VECTOR('',#146902,1.); -#146902 = DIRECTION('',(3.563627120235E-016,-1.)); -#146903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146904 = PCURVE('',#88096,#146905); -#146905 = DEFINITIONAL_REPRESENTATION('',(#146906),#146910); -#146906 = LINE('',#146907,#146908); -#146907 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146908 = VECTOR('',#146909,1.); -#146909 = DIRECTION('',(-1.,6.005309793447E-063)); -#146910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146911 = ORIENTED_EDGE('',*,*,#88050,.T.); -#146912 = ADVANCED_FACE('',(#146913),#88096,.F.); -#146913 = FACE_BOUND('',#146914,.T.); -#146914 = EDGE_LOOP('',(#146915,#146916,#146937,#146938)); -#146915 = ORIENTED_EDGE('',*,*,#146744,.F.); -#146916 = ORIENTED_EDGE('',*,*,#146917,.T.); -#146917 = EDGE_CURVE('',#146718,#88081,#146918,.T.); -#146918 = SURFACE_CURVE('',#146919,(#146923,#146930),.PCURVE_S1.); -#146919 = LINE('',#146920,#146921); -#146920 = CARTESIAN_POINT('',(3.15,10.527847992439,0.75)); -#146921 = VECTOR('',#146922,1.); -#146922 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146923 = PCURVE('',#88096,#146924); -#146924 = DEFINITIONAL_REPRESENTATION('',(#146925),#146929); -#146925 = LINE('',#146926,#146927); -#146926 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#146927 = VECTOR('',#146928,1.); -#146928 = DIRECTION('',(-1.,6.005309793447E-063)); -#146929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146930 = PCURVE('',#88124,#146931); -#146931 = DEFINITIONAL_REPRESENTATION('',(#146932),#146936); -#146932 = LINE('',#146933,#146934); -#146933 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#146934 = VECTOR('',#146935,1.); -#146935 = DIRECTION('',(-3.563627120235E-016,-1.)); -#146936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146937 = ORIENTED_EDGE('',*,*,#88080,.T.); -#146938 = ORIENTED_EDGE('',*,*,#146891,.F.); -#146939 = ADVANCED_FACE('',(#146940),#88124,.F.); -#146940 = FACE_BOUND('',#146941,.T.); -#146941 = EDGE_LOOP('',(#146942,#146943,#146944,#146945,#146946,#146947, - #146968,#146969,#146970,#146971,#146972,#146993)); -#146942 = ORIENTED_EDGE('',*,*,#146917,.F.); -#146943 = ORIENTED_EDGE('',*,*,#146717,.T.); -#146944 = ORIENTED_EDGE('',*,*,#146594,.T.); -#146945 = ORIENTED_EDGE('',*,*,#146519,.T.); -#146946 = ORIENTED_EDGE('',*,*,#146288,.T.); -#146947 = ORIENTED_EDGE('',*,*,#146948,.T.); -#146948 = EDGE_CURVE('',#146266,#146129,#146949,.T.); -#146949 = SURFACE_CURVE('',#146950,(#146954,#146961),.PCURVE_S1.); -#146950 = LINE('',#146951,#146952); -#146951 = CARTESIAN_POINT('',(3.15,11.,1.159810404338E-002)); -#146952 = VECTOR('',#146953,1.); -#146953 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#146954 = PCURVE('',#88124,#146955); -#146955 = DEFINITIONAL_REPRESENTATION('',(#146956),#146960); -#146956 = LINE('',#146957,#146958); -#146957 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#146958 = VECTOR('',#146959,1.); -#146959 = DIRECTION('',(1.,-2.101748079665E-016)); -#146960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146961 = PCURVE('',#146172,#146962); -#146962 = DEFINITIONAL_REPRESENTATION('',(#146963),#146967); -#146963 = LINE('',#146964,#146965); -#146964 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#146965 = VECTOR('',#146966,1.); -#146966 = DIRECTION('',(1.570395187386E-016,-1.)); -#146967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146968 = ORIENTED_EDGE('',*,*,#146126,.F.); -#146969 = ORIENTED_EDGE('',*,*,#146417,.F.); -#146970 = ORIENTED_EDGE('',*,*,#146647,.F.); -#146971 = ORIENTED_EDGE('',*,*,#146767,.F.); -#146972 = ORIENTED_EDGE('',*,*,#146973,.T.); -#146973 = EDGE_CURVE('',#146768,#88109,#146974,.T.); -#146974 = SURFACE_CURVE('',#146975,(#146979,#146986),.PCURVE_S1.); -#146975 = LINE('',#146976,#146977); -#146976 = CARTESIAN_POINT('',(3.15,10.527847992439,0.65)); -#146977 = VECTOR('',#146978,1.); -#146978 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#146979 = PCURVE('',#88124,#146980); -#146980 = DEFINITIONAL_REPRESENTATION('',(#146981),#146985); -#146981 = LINE('',#146982,#146983); -#146982 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#146983 = VECTOR('',#146984,1.); -#146984 = DIRECTION('',(-3.563627120235E-016,-1.)); -#146985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146986 = PCURVE('',#88150,#146987); -#146987 = DEFINITIONAL_REPRESENTATION('',(#146988),#146992); -#146988 = LINE('',#146989,#146990); -#146989 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#146990 = VECTOR('',#146991,1.); -#146991 = DIRECTION('',(1.,6.005309793447E-063)); -#146992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#146993 = ORIENTED_EDGE('',*,*,#88108,.T.); -#146994 = ADVANCED_FACE('',(#146995),#88150,.F.); -#146995 = FACE_BOUND('',#146996,.T.); -#146996 = EDGE_LOOP('',(#146997,#146998,#146999,#147000)); -#146997 = ORIENTED_EDGE('',*,*,#146794,.F.); -#146998 = ORIENTED_EDGE('',*,*,#146841,.T.); -#146999 = ORIENTED_EDGE('',*,*,#88136,.T.); -#147000 = ORIENTED_EDGE('',*,*,#146973,.F.); -#147001 = ADVANCED_FACE('',(#147002),#146172,.T.); -#147002 = FACE_BOUND('',#147003,.T.); -#147003 = EDGE_LOOP('',(#147004,#147005,#147006,#147007)); -#147004 = ORIENTED_EDGE('',*,*,#146948,.F.); -#147005 = ORIENTED_EDGE('',*,*,#146265,.F.); -#147006 = ORIENTED_EDGE('',*,*,#146866,.F.); -#147007 = ORIENTED_EDGE('',*,*,#146156,.F.); -#147008 = ADVANCED_FACE('',(#147009),#147023,.T.); -#147009 = FACE_BOUND('',#147010,.T.); -#147010 = EDGE_LOOP('',(#147011,#147041,#147069,#147092)); -#147011 = ORIENTED_EDGE('',*,*,#147012,.T.); -#147012 = EDGE_CURVE('',#147013,#147015,#147017,.T.); -#147013 = VERTEX_POINT('',#147014); -#147014 = CARTESIAN_POINT('',(2.65,10.74341632541,-0.308197125857)); -#147015 = VERTEX_POINT('',#147016); -#147016 = CARTESIAN_POINT('',(2.65,11.,-0.308197125857)); -#147017 = SURFACE_CURVE('',#147018,(#147022,#147034),.PCURVE_S1.); -#147018 = LINE('',#147019,#147020); -#147019 = CARTESIAN_POINT('',(2.65,10.74341632541,-0.308197125857)); -#147020 = VECTOR('',#147021,1.); -#147021 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147022 = PCURVE('',#147023,#147028); -#147023 = PLANE('',#147024); -#147024 = AXIS2_PLACEMENT_3D('',#147025,#147026,#147027); -#147025 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#149296 = PCURVE('',#90488,#149297); +#149297 = DEFINITIONAL_REPRESENTATION('',(#149298),#149302); +#149298 = LINE('',#149299,#149300); +#149299 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149300 = VECTOR('',#149301,1.); +#149301 = DIRECTION('',(-1.,6.005309793447E-063)); +#149302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149303 = ORIENTED_EDGE('',*,*,#90442,.T.); +#149304 = ADVANCED_FACE('',(#149305),#90488,.F.); +#149305 = FACE_BOUND('',#149306,.T.); +#149306 = EDGE_LOOP('',(#149307,#149308,#149329,#149330)); +#149307 = ORIENTED_EDGE('',*,*,#149136,.F.); +#149308 = ORIENTED_EDGE('',*,*,#149309,.T.); +#149309 = EDGE_CURVE('',#149110,#90473,#149310,.T.); +#149310 = SURFACE_CURVE('',#149311,(#149315,#149322),.PCURVE_S1.); +#149311 = LINE('',#149312,#149313); +#149312 = CARTESIAN_POINT('',(3.15,10.527847992439,0.75)); +#149313 = VECTOR('',#149314,1.); +#149314 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#149315 = PCURVE('',#90488,#149316); +#149316 = DEFINITIONAL_REPRESENTATION('',(#149317),#149321); +#149317 = LINE('',#149318,#149319); +#149318 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#149319 = VECTOR('',#149320,1.); +#149320 = DIRECTION('',(-1.,6.005309793447E-063)); +#149321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149322 = PCURVE('',#90516,#149323); +#149323 = DEFINITIONAL_REPRESENTATION('',(#149324),#149328); +#149324 = LINE('',#149325,#149326); +#149325 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#149326 = VECTOR('',#149327,1.); +#149327 = DIRECTION('',(-3.563627120235E-016,-1.)); +#149328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149329 = ORIENTED_EDGE('',*,*,#90472,.T.); +#149330 = ORIENTED_EDGE('',*,*,#149283,.F.); +#149331 = ADVANCED_FACE('',(#149332),#90516,.F.); +#149332 = FACE_BOUND('',#149333,.T.); +#149333 = EDGE_LOOP('',(#149334,#149335,#149336,#149337,#149338,#149339, + #149360,#149361,#149362,#149363,#149364,#149385)); +#149334 = ORIENTED_EDGE('',*,*,#149309,.F.); +#149335 = ORIENTED_EDGE('',*,*,#149109,.T.); +#149336 = ORIENTED_EDGE('',*,*,#148986,.T.); +#149337 = ORIENTED_EDGE('',*,*,#148911,.T.); +#149338 = ORIENTED_EDGE('',*,*,#148680,.T.); +#149339 = ORIENTED_EDGE('',*,*,#149340,.T.); +#149340 = EDGE_CURVE('',#148658,#148521,#149341,.T.); +#149341 = SURFACE_CURVE('',#149342,(#149346,#149353),.PCURVE_S1.); +#149342 = LINE('',#149343,#149344); +#149343 = CARTESIAN_POINT('',(3.15,11.,1.159810404338E-002)); +#149344 = VECTOR('',#149345,1.); +#149345 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#149346 = PCURVE('',#90516,#149347); +#149347 = DEFINITIONAL_REPRESENTATION('',(#149348),#149352); +#149348 = LINE('',#149349,#149350); +#149349 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#149350 = VECTOR('',#149351,1.); +#149351 = DIRECTION('',(1.,-2.101748079665E-016)); +#149352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149353 = PCURVE('',#148564,#149354); +#149354 = DEFINITIONAL_REPRESENTATION('',(#149355),#149359); +#149355 = LINE('',#149356,#149357); +#149356 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#149357 = VECTOR('',#149358,1.); +#149358 = DIRECTION('',(1.570395187386E-016,-1.)); +#149359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149360 = ORIENTED_EDGE('',*,*,#148518,.F.); +#149361 = ORIENTED_EDGE('',*,*,#148809,.F.); +#149362 = ORIENTED_EDGE('',*,*,#149039,.F.); +#149363 = ORIENTED_EDGE('',*,*,#149159,.F.); +#149364 = ORIENTED_EDGE('',*,*,#149365,.T.); +#149365 = EDGE_CURVE('',#149160,#90501,#149366,.T.); +#149366 = SURFACE_CURVE('',#149367,(#149371,#149378),.PCURVE_S1.); +#149367 = LINE('',#149368,#149369); +#149368 = CARTESIAN_POINT('',(3.15,10.527847992439,0.65)); +#149369 = VECTOR('',#149370,1.); +#149370 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#149371 = PCURVE('',#90516,#149372); +#149372 = DEFINITIONAL_REPRESENTATION('',(#149373),#149377); +#149373 = LINE('',#149374,#149375); +#149374 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149375 = VECTOR('',#149376,1.); +#149376 = DIRECTION('',(-3.563627120235E-016,-1.)); +#149377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149378 = PCURVE('',#90542,#149379); +#149379 = DEFINITIONAL_REPRESENTATION('',(#149380),#149384); +#149380 = LINE('',#149381,#149382); +#149381 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#149382 = VECTOR('',#149383,1.); +#149383 = DIRECTION('',(1.,6.005309793447E-063)); +#149384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149385 = ORIENTED_EDGE('',*,*,#90500,.T.); +#149386 = ADVANCED_FACE('',(#149387),#90542,.F.); +#149387 = FACE_BOUND('',#149388,.T.); +#149388 = EDGE_LOOP('',(#149389,#149390,#149391,#149392)); +#149389 = ORIENTED_EDGE('',*,*,#149186,.F.); +#149390 = ORIENTED_EDGE('',*,*,#149233,.T.); +#149391 = ORIENTED_EDGE('',*,*,#90528,.T.); +#149392 = ORIENTED_EDGE('',*,*,#149365,.F.); +#149393 = ADVANCED_FACE('',(#149394),#148564,.T.); +#149394 = FACE_BOUND('',#149395,.T.); +#149395 = EDGE_LOOP('',(#149396,#149397,#149398,#149399)); +#149396 = ORIENTED_EDGE('',*,*,#149340,.F.); +#149397 = ORIENTED_EDGE('',*,*,#148657,.F.); +#149398 = ORIENTED_EDGE('',*,*,#149258,.F.); +#149399 = ORIENTED_EDGE('',*,*,#148548,.F.); +#149400 = ADVANCED_FACE('',(#149401),#149415,.T.); +#149401 = FACE_BOUND('',#149402,.T.); +#149402 = EDGE_LOOP('',(#149403,#149433,#149461,#149484)); +#149403 = ORIENTED_EDGE('',*,*,#149404,.T.); +#149404 = EDGE_CURVE('',#149405,#149407,#149409,.T.); +#149405 = VERTEX_POINT('',#149406); +#149406 = CARTESIAN_POINT('',(2.65,10.74341632541,-0.308197125857)); +#149407 = VERTEX_POINT('',#149408); +#149408 = CARTESIAN_POINT('',(2.65,11.,-0.308197125857)); +#149409 = SURFACE_CURVE('',#149410,(#149414,#149426),.PCURVE_S1.); +#149410 = LINE('',#149411,#149412); +#149411 = CARTESIAN_POINT('',(2.65,10.74341632541,-0.308197125857)); +#149412 = VECTOR('',#149413,1.); +#149413 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#149414 = PCURVE('',#149415,#149420); +#149415 = PLANE('',#149416); +#149416 = AXIS2_PLACEMENT_3D('',#149417,#149418,#149419); +#149417 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#147026 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147027 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#147028 = DEFINITIONAL_REPRESENTATION('',(#147029),#147033); -#147029 = LINE('',#147030,#147031); -#147030 = CARTESIAN_POINT('',(-2.65,-1.7763568394E-015)); -#147031 = VECTOR('',#147032,1.); -#147032 = DIRECTION('',(-6.725593854929E-015,1.)); -#147033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147034 = PCURVE('',#86756,#147035); -#147035 = DEFINITIONAL_REPRESENTATION('',(#147036),#147040); -#147036 = LINE('',#147037,#147038); -#147037 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#147038 = VECTOR('',#147039,1.); -#147039 = DIRECTION('',(0.E+000,1.)); -#147040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147041 = ORIENTED_EDGE('',*,*,#147042,.T.); -#147042 = EDGE_CURVE('',#147015,#147043,#147045,.T.); -#147043 = VERTEX_POINT('',#147044); -#147044 = CARTESIAN_POINT('',(2.85,11.,-0.308197125857)); -#147045 = SURFACE_CURVE('',#147046,(#147050,#147057),.PCURVE_S1.); -#147046 = LINE('',#147047,#147048); -#147047 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#147048 = VECTOR('',#147049,1.); -#147049 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147050 = PCURVE('',#147023,#147051); -#147051 = DEFINITIONAL_REPRESENTATION('',(#147052),#147056); -#147052 = LINE('',#147053,#147054); -#147053 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#147054 = VECTOR('',#147055,1.); -#147055 = DIRECTION('',(-1.,-8.881784197001E-016)); -#147056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147057 = PCURVE('',#147058,#147063); -#147058 = PLANE('',#147059); -#147059 = AXIS2_PLACEMENT_3D('',#147060,#147061,#147062); -#147060 = CARTESIAN_POINT('',(2.75,11.,-0.258196742327)); -#147061 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#147062 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#147063 = DEFINITIONAL_REPRESENTATION('',(#147064),#147068); -#147064 = LINE('',#147065,#147066); -#147065 = CARTESIAN_POINT('',(2.75,-5.00003835295E-002)); -#147066 = VECTOR('',#147067,1.); -#147067 = DIRECTION('',(-1.,-1.1653254136E-048)); -#147068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147069 = ORIENTED_EDGE('',*,*,#147070,.F.); -#147070 = EDGE_CURVE('',#147071,#147043,#147073,.T.); -#147071 = VERTEX_POINT('',#147072); -#147072 = CARTESIAN_POINT('',(2.85,10.74341632541,-0.308197125857)); -#147073 = SURFACE_CURVE('',#147074,(#147078,#147085),.PCURVE_S1.); -#147074 = LINE('',#147075,#147076); -#147075 = CARTESIAN_POINT('',(2.85,10.74341632541,-0.308197125857)); -#147076 = VECTOR('',#147077,1.); -#147077 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147078 = PCURVE('',#147023,#147079); -#147079 = DEFINITIONAL_REPRESENTATION('',(#147080),#147084); -#147080 = LINE('',#147081,#147082); -#147081 = CARTESIAN_POINT('',(-2.85,-1.7763568394E-015)); -#147082 = VECTOR('',#147083,1.); -#147083 = DIRECTION('',(-6.725593854929E-015,1.)); -#147084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147085 = PCURVE('',#86700,#147086); -#147086 = DEFINITIONAL_REPRESENTATION('',(#147087),#147091); -#147087 = LINE('',#147088,#147089); -#147088 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#147089 = VECTOR('',#147090,1.); -#147090 = DIRECTION('',(0.E+000,1.)); -#147091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147092 = ORIENTED_EDGE('',*,*,#147093,.T.); -#147093 = EDGE_CURVE('',#147071,#147013,#147094,.T.); -#147094 = SURFACE_CURVE('',#147095,(#147099,#147106),.PCURVE_S1.); -#147095 = LINE('',#147096,#147097); -#147096 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#149418 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149419 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#149420 = DEFINITIONAL_REPRESENTATION('',(#149421),#149425); +#149421 = LINE('',#149422,#149423); +#149422 = CARTESIAN_POINT('',(-2.65,-1.7763568394E-015)); +#149423 = VECTOR('',#149424,1.); +#149424 = DIRECTION('',(-6.725593854929E-015,1.)); +#149425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149426 = PCURVE('',#89148,#149427); +#149427 = DEFINITIONAL_REPRESENTATION('',(#149428),#149432); +#149428 = LINE('',#149429,#149430); +#149429 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#149430 = VECTOR('',#149431,1.); +#149431 = DIRECTION('',(0.E+000,1.)); +#149432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149433 = ORIENTED_EDGE('',*,*,#149434,.T.); +#149434 = EDGE_CURVE('',#149407,#149435,#149437,.T.); +#149435 = VERTEX_POINT('',#149436); +#149436 = CARTESIAN_POINT('',(2.85,11.,-0.308197125857)); +#149437 = SURFACE_CURVE('',#149438,(#149442,#149449),.PCURVE_S1.); +#149438 = LINE('',#149439,#149440); +#149439 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#149440 = VECTOR('',#149441,1.); +#149441 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149442 = PCURVE('',#149415,#149443); +#149443 = DEFINITIONAL_REPRESENTATION('',(#149444),#149448); +#149444 = LINE('',#149445,#149446); +#149445 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#149446 = VECTOR('',#149447,1.); +#149447 = DIRECTION('',(-1.,-8.881784197001E-016)); +#149448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149449 = PCURVE('',#149450,#149455); +#149450 = PLANE('',#149451); +#149451 = AXIS2_PLACEMENT_3D('',#149452,#149453,#149454); +#149452 = CARTESIAN_POINT('',(2.75,11.,-0.258196742327)); +#149453 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#149454 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#149455 = DEFINITIONAL_REPRESENTATION('',(#149456),#149460); +#149456 = LINE('',#149457,#149458); +#149457 = CARTESIAN_POINT('',(2.75,-5.00003835295E-002)); +#149458 = VECTOR('',#149459,1.); +#149459 = DIRECTION('',(-1.,-1.1653254136E-048)); +#149460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149461 = ORIENTED_EDGE('',*,*,#149462,.F.); +#149462 = EDGE_CURVE('',#149463,#149435,#149465,.T.); +#149463 = VERTEX_POINT('',#149464); +#149464 = CARTESIAN_POINT('',(2.85,10.74341632541,-0.308197125857)); +#149465 = SURFACE_CURVE('',#149466,(#149470,#149477),.PCURVE_S1.); +#149466 = LINE('',#149467,#149468); +#149467 = CARTESIAN_POINT('',(2.85,10.74341632541,-0.308197125857)); +#149468 = VECTOR('',#149469,1.); +#149469 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#149470 = PCURVE('',#149415,#149471); +#149471 = DEFINITIONAL_REPRESENTATION('',(#149472),#149476); +#149472 = LINE('',#149473,#149474); +#149473 = CARTESIAN_POINT('',(-2.85,-1.7763568394E-015)); +#149474 = VECTOR('',#149475,1.); +#149475 = DIRECTION('',(-6.725593854929E-015,1.)); +#149476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149477 = PCURVE('',#89092,#149478); +#149478 = DEFINITIONAL_REPRESENTATION('',(#149479),#149483); +#149479 = LINE('',#149480,#149481); +#149480 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#149481 = VECTOR('',#149482,1.); +#149482 = DIRECTION('',(0.E+000,1.)); +#149483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149484 = ORIENTED_EDGE('',*,*,#149485,.T.); +#149485 = EDGE_CURVE('',#149463,#149405,#149486,.T.); +#149486 = SURFACE_CURVE('',#149487,(#149491,#149498),.PCURVE_S1.); +#149487 = LINE('',#149488,#149489); +#149488 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#147097 = VECTOR('',#147098,1.); -#147098 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147099 = PCURVE('',#147023,#147100); -#147100 = DEFINITIONAL_REPRESENTATION('',(#147101),#147105); -#147101 = LINE('',#147102,#147103); -#147102 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147103 = VECTOR('',#147104,1.); -#147104 = DIRECTION('',(1.,8.881784197001E-016)); -#147105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147106 = PCURVE('',#147107,#147112); -#147107 = CYLINDRICAL_SURFACE('',#147108,0.308574064194); -#147108 = AXIS2_PLACEMENT_3D('',#147109,#147110,#147111); -#147109 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#149489 = VECTOR('',#149490,1.); +#149490 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149491 = PCURVE('',#149415,#149492); +#149492 = DEFINITIONAL_REPRESENTATION('',(#149493),#149497); +#149493 = LINE('',#149494,#149495); +#149494 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149495 = VECTOR('',#149496,1.); +#149496 = DIRECTION('',(1.,8.881784197001E-016)); +#149497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149498 = PCURVE('',#149499,#149504); +#149499 = CYLINDRICAL_SURFACE('',#149500,0.308574064194); +#149500 = AXIS2_PLACEMENT_3D('',#149501,#149502,#149503); +#149501 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#147110 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147111 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147112 = DEFINITIONAL_REPRESENTATION('',(#147113),#147116); -#147113 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147114,#147115), +#149502 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149503 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149504 = DEFINITIONAL_REPRESENTATION('',(#149505),#149508); +#149505 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149506,#149507), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#147114 = CARTESIAN_POINT('',(4.761821717947,2.85)); -#147115 = CARTESIAN_POINT('',(4.761821717947,2.65)); -#147116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147117 = ADVANCED_FACE('',(#147118),#147132,.T.); -#147118 = FACE_BOUND('',#147119,.T.); -#147119 = EDGE_LOOP('',(#147120,#147150,#147173,#147196)); -#147120 = ORIENTED_EDGE('',*,*,#147121,.T.); -#147121 = EDGE_CURVE('',#147122,#147124,#147126,.T.); -#147122 = VERTEX_POINT('',#147123); -#147123 = CARTESIAN_POINT('',(2.85,10.740726081328,-0.208196358798)); -#147124 = VERTEX_POINT('',#147125); -#147125 = CARTESIAN_POINT('',(2.85,11.,-0.208196358798)); -#147126 = SURFACE_CURVE('',#147127,(#147131,#147143),.PCURVE_S1.); -#147127 = LINE('',#147128,#147129); -#147128 = CARTESIAN_POINT('',(2.85,10.740726081328,-0.208196358798)); -#147129 = VECTOR('',#147130,1.); -#147130 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147131 = PCURVE('',#147132,#147137); -#147132 = PLANE('',#147133); -#147133 = AXIS2_PLACEMENT_3D('',#147134,#147135,#147136); -#147134 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#149506 = CARTESIAN_POINT('',(4.761821717947,2.85)); +#149507 = CARTESIAN_POINT('',(4.761821717947,2.65)); +#149508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149509 = ADVANCED_FACE('',(#149510),#149524,.T.); +#149510 = FACE_BOUND('',#149511,.T.); +#149511 = EDGE_LOOP('',(#149512,#149542,#149565,#149588)); +#149512 = ORIENTED_EDGE('',*,*,#149513,.T.); +#149513 = EDGE_CURVE('',#149514,#149516,#149518,.T.); +#149514 = VERTEX_POINT('',#149515); +#149515 = CARTESIAN_POINT('',(2.85,10.740726081328,-0.208196358798)); +#149516 = VERTEX_POINT('',#149517); +#149517 = CARTESIAN_POINT('',(2.85,11.,-0.208196358798)); +#149518 = SURFACE_CURVE('',#149519,(#149523,#149535),.PCURVE_S1.); +#149519 = LINE('',#149520,#149521); +#149520 = CARTESIAN_POINT('',(2.85,10.740726081328,-0.208196358798)); +#149521 = VECTOR('',#149522,1.); +#149522 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#149523 = PCURVE('',#149524,#149529); +#149524 = PLANE('',#149525); +#149525 = AXIS2_PLACEMENT_3D('',#149526,#149527,#149528); +#149526 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#147135 = DIRECTION('',(0.E+000,0.E+000,1.)); -#147136 = DIRECTION('',(1.,0.E+000,0.E+000)); -#147137 = DEFINITIONAL_REPRESENTATION('',(#147138),#147142); -#147138 = LINE('',#147139,#147140); -#147139 = CARTESIAN_POINT('',(2.85,-1.7763568394E-015)); -#147140 = VECTOR('',#147141,1.); -#147141 = DIRECTION('',(6.725593854929E-015,1.)); -#147142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147143 = PCURVE('',#86700,#147144); -#147144 = DEFINITIONAL_REPRESENTATION('',(#147145),#147149); -#147145 = LINE('',#147146,#147147); -#147146 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#147147 = VECTOR('',#147148,1.); -#147148 = DIRECTION('',(0.E+000,1.)); -#147149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147150 = ORIENTED_EDGE('',*,*,#147151,.T.); -#147151 = EDGE_CURVE('',#147124,#147152,#147154,.T.); -#147152 = VERTEX_POINT('',#147153); -#147153 = CARTESIAN_POINT('',(2.65,11.,-0.208196358798)); -#147154 = SURFACE_CURVE('',#147155,(#147159,#147166),.PCURVE_S1.); -#147155 = LINE('',#147156,#147157); -#147156 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#147157 = VECTOR('',#147158,1.); -#147158 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147159 = PCURVE('',#147132,#147160); -#147160 = DEFINITIONAL_REPRESENTATION('',(#147161),#147165); -#147161 = LINE('',#147162,#147163); -#147162 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#147163 = VECTOR('',#147164,1.); -#147164 = DIRECTION('',(-1.,8.881784197001E-016)); -#147165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149527 = DIRECTION('',(0.E+000,0.E+000,1.)); +#149528 = DIRECTION('',(1.,0.E+000,0.E+000)); +#149529 = DEFINITIONAL_REPRESENTATION('',(#149530),#149534); +#149530 = LINE('',#149531,#149532); +#149531 = CARTESIAN_POINT('',(2.85,-1.7763568394E-015)); +#149532 = VECTOR('',#149533,1.); +#149533 = DIRECTION('',(6.725593854929E-015,1.)); +#149534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149535 = PCURVE('',#89092,#149536); +#149536 = DEFINITIONAL_REPRESENTATION('',(#149537),#149541); +#149537 = LINE('',#149538,#149539); +#149538 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#149539 = VECTOR('',#149540,1.); +#149540 = DIRECTION('',(0.E+000,1.)); +#149541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149542 = ORIENTED_EDGE('',*,*,#149543,.T.); +#149543 = EDGE_CURVE('',#149516,#149544,#149546,.T.); +#149544 = VERTEX_POINT('',#149545); +#149545 = CARTESIAN_POINT('',(2.65,11.,-0.208196358798)); +#149546 = SURFACE_CURVE('',#149547,(#149551,#149558),.PCURVE_S1.); +#149547 = LINE('',#149548,#149549); +#149548 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#149549 = VECTOR('',#149550,1.); +#149550 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149551 = PCURVE('',#149524,#149552); +#149552 = DEFINITIONAL_REPRESENTATION('',(#149553),#149557); +#149553 = LINE('',#149554,#149555); +#149554 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#149555 = VECTOR('',#149556,1.); +#149556 = DIRECTION('',(-1.,8.881784197001E-016)); +#149557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149558 = PCURVE('',#149450,#149559); +#149559 = DEFINITIONAL_REPRESENTATION('',(#149560),#149564); +#149560 = LINE('',#149561,#149562); +#149561 = CARTESIAN_POINT('',(2.75,5.000038352949E-002)); +#149562 = VECTOR('',#149563,1.); +#149563 = DIRECTION('',(1.,1.1653254136E-048)); +#149564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149565 = ORIENTED_EDGE('',*,*,#149566,.F.); +#149566 = EDGE_CURVE('',#149567,#149544,#149569,.T.); +#149567 = VERTEX_POINT('',#149568); +#149568 = CARTESIAN_POINT('',(2.65,10.740726081328,-0.208196358798)); +#149569 = SURFACE_CURVE('',#149570,(#149574,#149581),.PCURVE_S1.); +#149570 = LINE('',#149571,#149572); +#149571 = CARTESIAN_POINT('',(2.65,10.740726081328,-0.208196358798)); +#149572 = VECTOR('',#149573,1.); +#149573 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#149574 = PCURVE('',#149524,#149575); +#149575 = DEFINITIONAL_REPRESENTATION('',(#149576),#149580); +#149576 = LINE('',#149577,#149578); +#149577 = CARTESIAN_POINT('',(2.65,-1.7763568394E-015)); +#149578 = VECTOR('',#149579,1.); +#149579 = DIRECTION('',(6.725593854929E-015,1.)); +#149580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149581 = PCURVE('',#89148,#149582); +#149582 = DEFINITIONAL_REPRESENTATION('',(#149583),#149587); +#149583 = LINE('',#149584,#149585); +#149584 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#149585 = VECTOR('',#149586,1.); +#149586 = DIRECTION('',(0.E+000,1.)); +#149587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147166 = PCURVE('',#147058,#147167); -#147167 = DEFINITIONAL_REPRESENTATION('',(#147168),#147172); -#147168 = LINE('',#147169,#147170); -#147169 = CARTESIAN_POINT('',(2.75,5.000038352949E-002)); -#147170 = VECTOR('',#147171,1.); -#147171 = DIRECTION('',(1.,1.1653254136E-048)); -#147172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147173 = ORIENTED_EDGE('',*,*,#147174,.F.); -#147174 = EDGE_CURVE('',#147175,#147152,#147177,.T.); -#147175 = VERTEX_POINT('',#147176); -#147176 = CARTESIAN_POINT('',(2.65,10.740726081328,-0.208196358798)); -#147177 = SURFACE_CURVE('',#147178,(#147182,#147189),.PCURVE_S1.); -#147178 = LINE('',#147179,#147180); -#147179 = CARTESIAN_POINT('',(2.65,10.740726081328,-0.208196358798)); -#147180 = VECTOR('',#147181,1.); -#147181 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147182 = PCURVE('',#147132,#147183); -#147183 = DEFINITIONAL_REPRESENTATION('',(#147184),#147188); -#147184 = LINE('',#147185,#147186); -#147185 = CARTESIAN_POINT('',(2.65,-1.7763568394E-015)); -#147186 = VECTOR('',#147187,1.); -#147187 = DIRECTION('',(6.725593854929E-015,1.)); -#147188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147189 = PCURVE('',#86756,#147190); -#147190 = DEFINITIONAL_REPRESENTATION('',(#147191),#147195); -#147191 = LINE('',#147192,#147193); -#147192 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#147193 = VECTOR('',#147194,1.); -#147194 = DIRECTION('',(0.E+000,1.)); -#147195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147196 = ORIENTED_EDGE('',*,*,#147197,.T.); -#147197 = EDGE_CURVE('',#147175,#147122,#147198,.T.); -#147198 = SURFACE_CURVE('',#147199,(#147203,#147210),.PCURVE_S1.); -#147199 = LINE('',#147200,#147201); -#147200 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#149588 = ORIENTED_EDGE('',*,*,#149589,.T.); +#149589 = EDGE_CURVE('',#149567,#149514,#149590,.T.); +#149590 = SURFACE_CURVE('',#149591,(#149595,#149602),.PCURVE_S1.); +#149591 = LINE('',#149592,#149593); +#149592 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#147201 = VECTOR('',#147202,1.); -#147202 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147203 = PCURVE('',#147132,#147204); -#147204 = DEFINITIONAL_REPRESENTATION('',(#147205),#147209); -#147205 = LINE('',#147206,#147207); -#147206 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147207 = VECTOR('',#147208,1.); -#147208 = DIRECTION('',(1.,-8.881784197001E-016)); -#147209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147210 = PCURVE('',#147211,#147216); -#147211 = CYLINDRICAL_SURFACE('',#147212,0.208574704164); -#147212 = AXIS2_PLACEMENT_3D('',#147213,#147214,#147215); -#147213 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#149593 = VECTOR('',#149594,1.); +#149594 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149595 = PCURVE('',#149524,#149596); +#149596 = DEFINITIONAL_REPRESENTATION('',(#149597),#149601); +#149597 = LINE('',#149598,#149599); +#149598 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149599 = VECTOR('',#149600,1.); +#149600 = DIRECTION('',(1.,-8.881784197001E-016)); +#149601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149602 = PCURVE('',#149603,#149608); +#149603 = CYLINDRICAL_SURFACE('',#149604,0.208574704164); +#149604 = AXIS2_PLACEMENT_3D('',#149605,#149606,#149607); +#149605 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#147214 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147215 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147216 = DEFINITIONAL_REPRESENTATION('',(#147217),#147220); -#147217 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147218,#147219), +#149606 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149607 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149608 = DEFINITIONAL_REPRESENTATION('',(#149609),#149612); +#149609 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149610,#149611), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#147218 = CARTESIAN_POINT('',(4.772630242227,2.65)); -#147219 = CARTESIAN_POINT('',(4.772630242227,2.85)); -#147220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147221 = ADVANCED_FACE('',(#147222),#147107,.T.); -#147222 = FACE_BOUND('',#147223,.T.); -#147223 = EDGE_LOOP('',(#147224,#147225,#147275,#147302)); -#147224 = ORIENTED_EDGE('',*,*,#147093,.F.); -#147225 = ORIENTED_EDGE('',*,*,#147226,.F.); -#147226 = EDGE_CURVE('',#147227,#147071,#147229,.T.); -#147227 = VERTEX_POINT('',#147228); -#147228 = CARTESIAN_POINT('',(2.85,10.419594812019,0.E+000)); -#147229 = SURFACE_CURVE('',#147230,(#147235,#147264),.PCURVE_S1.); -#147230 = CIRCLE('',#147231,0.308574064194); -#147231 = AXIS2_PLACEMENT_3D('',#147232,#147233,#147234); -#147232 = CARTESIAN_POINT('',(2.85,10.728168876214,2.640924866458E-017) - ); -#147233 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147234 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147235 = PCURVE('',#147107,#147236); -#147236 = DEFINITIONAL_REPRESENTATION('',(#147237),#147263); -#147237 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147238,#147239,#147240, - #147241,#147242,#147243,#147244,#147245,#147246,#147247,#147248, - #147249,#147250,#147251,#147252,#147253,#147254,#147255,#147256, - #147257,#147258,#147259,#147260,#147261,#147262),.UNSPECIFIED.,.F., +#149610 = CARTESIAN_POINT('',(4.772630242227,2.65)); +#149611 = CARTESIAN_POINT('',(4.772630242227,2.85)); +#149612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149613 = ADVANCED_FACE('',(#149614),#149499,.T.); +#149614 = FACE_BOUND('',#149615,.T.); +#149615 = EDGE_LOOP('',(#149616,#149617,#149667,#149694)); +#149616 = ORIENTED_EDGE('',*,*,#149485,.F.); +#149617 = ORIENTED_EDGE('',*,*,#149618,.F.); +#149618 = EDGE_CURVE('',#149619,#149463,#149621,.T.); +#149619 = VERTEX_POINT('',#149620); +#149620 = CARTESIAN_POINT('',(2.85,10.419594812019,0.E+000)); +#149621 = SURFACE_CURVE('',#149622,(#149627,#149656),.PCURVE_S1.); +#149622 = CIRCLE('',#149623,0.308574064194); +#149623 = AXIS2_PLACEMENT_3D('',#149624,#149625,#149626); +#149624 = CARTESIAN_POINT('',(2.85,10.728168876214,2.640924866458E-017) + ); +#149625 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149626 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149627 = PCURVE('',#149499,#149628); +#149628 = DEFINITIONAL_REPRESENTATION('',(#149629),#149655); +#149629 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149630,#149631,#149632, + #149633,#149634,#149635,#149636,#149637,#149638,#149639,#149640, + #149641,#149642,#149643,#149644,#149645,#149646,#149647,#149648, + #149649,#149650,#149651,#149652,#149653,#149654),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -181557,102 +184559,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#147238 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#147239 = CARTESIAN_POINT('',(3.166141578807,2.85)); -#147240 = CARTESIAN_POINT('',(3.215239429242,2.85)); -#147241 = CARTESIAN_POINT('',(3.288886204895,2.85)); -#147242 = CARTESIAN_POINT('',(3.362532980548,2.85)); -#147243 = CARTESIAN_POINT('',(3.4361797562,2.85)); -#147244 = CARTESIAN_POINT('',(3.509826531853,2.85)); -#147245 = CARTESIAN_POINT('',(3.583473307505,2.85)); -#147246 = CARTESIAN_POINT('',(3.657120083158,2.85)); -#147247 = CARTESIAN_POINT('',(3.730766858811,2.85)); -#147248 = CARTESIAN_POINT('',(3.804413634463,2.85)); -#147249 = CARTESIAN_POINT('',(3.878060410116,2.85)); -#147250 = CARTESIAN_POINT('',(3.951707185768,2.85)); -#147251 = CARTESIAN_POINT('',(4.025353961421,2.85)); -#147252 = CARTESIAN_POINT('',(4.099000737074,2.85)); -#147253 = CARTESIAN_POINT('',(4.172647512726,2.85)); -#147254 = CARTESIAN_POINT('',(4.246294288379,2.85)); -#147255 = CARTESIAN_POINT('',(4.319941064031,2.85)); -#147256 = CARTESIAN_POINT('',(4.393587839684,2.85)); -#147257 = CARTESIAN_POINT('',(4.467234615337,2.85)); -#147258 = CARTESIAN_POINT('',(4.540881390989,2.85)); -#147259 = CARTESIAN_POINT('',(4.614528166642,2.85)); -#147260 = CARTESIAN_POINT('',(4.688174942294,2.85)); -#147261 = CARTESIAN_POINT('',(4.737272792729,2.85)); -#147262 = CARTESIAN_POINT('',(4.761821717947,2.85)); -#147263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147264 = PCURVE('',#86700,#147265); -#147265 = DEFINITIONAL_REPRESENTATION('',(#147266),#147274); -#147266 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147267,#147268,#147269, - #147270,#147271,#147272,#147273),.UNSPECIFIED.,.T.,.F.) +#149630 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#149631 = CARTESIAN_POINT('',(3.166141578807,2.85)); +#149632 = CARTESIAN_POINT('',(3.215239429242,2.85)); +#149633 = CARTESIAN_POINT('',(3.288886204895,2.85)); +#149634 = CARTESIAN_POINT('',(3.362532980548,2.85)); +#149635 = CARTESIAN_POINT('',(3.4361797562,2.85)); +#149636 = CARTESIAN_POINT('',(3.509826531853,2.85)); +#149637 = CARTESIAN_POINT('',(3.583473307505,2.85)); +#149638 = CARTESIAN_POINT('',(3.657120083158,2.85)); +#149639 = CARTESIAN_POINT('',(3.730766858811,2.85)); +#149640 = CARTESIAN_POINT('',(3.804413634463,2.85)); +#149641 = CARTESIAN_POINT('',(3.878060410116,2.85)); +#149642 = CARTESIAN_POINT('',(3.951707185768,2.85)); +#149643 = CARTESIAN_POINT('',(4.025353961421,2.85)); +#149644 = CARTESIAN_POINT('',(4.099000737074,2.85)); +#149645 = CARTESIAN_POINT('',(4.172647512726,2.85)); +#149646 = CARTESIAN_POINT('',(4.246294288379,2.85)); +#149647 = CARTESIAN_POINT('',(4.319941064031,2.85)); +#149648 = CARTESIAN_POINT('',(4.393587839684,2.85)); +#149649 = CARTESIAN_POINT('',(4.467234615337,2.85)); +#149650 = CARTESIAN_POINT('',(4.540881390989,2.85)); +#149651 = CARTESIAN_POINT('',(4.614528166642,2.85)); +#149652 = CARTESIAN_POINT('',(4.688174942294,2.85)); +#149653 = CARTESIAN_POINT('',(4.737272792729,2.85)); +#149654 = CARTESIAN_POINT('',(4.761821717947,2.85)); +#149655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149656 = PCURVE('',#89092,#149657); +#149657 = DEFINITIONAL_REPRESENTATION('',(#149658),#149666); +#149658 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149659,#149660,#149661, + #149662,#149663,#149664,#149665),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#147267 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#147268 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#147269 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#147270 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#147271 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#147272 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#147273 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#147274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147275 = ORIENTED_EDGE('',*,*,#147276,.F.); -#147276 = EDGE_CURVE('',#147277,#147227,#147279,.T.); -#147277 = VERTEX_POINT('',#147278); -#147278 = CARTESIAN_POINT('',(2.65,10.419594812019,0.E+000)); -#147279 = SURFACE_CURVE('',#147280,(#147284,#147290),.PCURVE_S1.); -#147280 = LINE('',#147281,#147282); -#147281 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#149659 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#149660 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#149661 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#149662 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#149663 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#149664 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#149665 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#149666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149667 = ORIENTED_EDGE('',*,*,#149668,.F.); +#149668 = EDGE_CURVE('',#149669,#149619,#149671,.T.); +#149669 = VERTEX_POINT('',#149670); +#149670 = CARTESIAN_POINT('',(2.65,10.419594812019,0.E+000)); +#149671 = SURFACE_CURVE('',#149672,(#149676,#149682),.PCURVE_S1.); +#149672 = LINE('',#149673,#149674); +#149673 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#147282 = VECTOR('',#147283,1.); -#147283 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147284 = PCURVE('',#147107,#147285); -#147285 = DEFINITIONAL_REPRESENTATION('',(#147286),#147289); -#147286 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147287,#147288), +#149674 = VECTOR('',#149675,1.); +#149675 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149676 = PCURVE('',#149499,#149677); +#149677 = DEFINITIONAL_REPRESENTATION('',(#149678),#149681); +#149678 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149679,#149680), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#147287 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#147288 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#147289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149679 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#149680 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#149681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147290 = PCURVE('',#147291,#147296); -#147291 = PLANE('',#147292); -#147292 = AXIS2_PLACEMENT_3D('',#147293,#147294,#147295); -#147293 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#149682 = PCURVE('',#149683,#149688); +#149683 = PLANE('',#149684); +#149684 = AXIS2_PLACEMENT_3D('',#149685,#149686,#149687); +#149685 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#147294 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147295 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147296 = DEFINITIONAL_REPRESENTATION('',(#147297),#147301); -#147297 = LINE('',#147298,#147299); -#147298 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#147299 = VECTOR('',#147300,1.); -#147300 = DIRECTION('',(-1.,0.E+000)); -#147301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147302 = ORIENTED_EDGE('',*,*,#147303,.T.); -#147303 = EDGE_CURVE('',#147277,#147013,#147304,.T.); -#147304 = SURFACE_CURVE('',#147305,(#147310,#147339),.PCURVE_S1.); -#147305 = CIRCLE('',#147306,0.308574064194); -#147306 = AXIS2_PLACEMENT_3D('',#147307,#147308,#147309); -#147307 = CARTESIAN_POINT('',(2.65,10.728168876214,2.640924866458E-017) - ); -#147308 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147309 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147310 = PCURVE('',#147107,#147311); -#147311 = DEFINITIONAL_REPRESENTATION('',(#147312),#147338); -#147312 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#147313,#147314,#147315, - #147316,#147317,#147318,#147319,#147320,#147321,#147322,#147323, - #147324,#147325,#147326,#147327,#147328,#147329,#147330,#147331, - #147332,#147333,#147334,#147335,#147336,#147337),.UNSPECIFIED.,.F., +#149686 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149687 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149688 = DEFINITIONAL_REPRESENTATION('',(#149689),#149693); +#149689 = LINE('',#149690,#149691); +#149690 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#149691 = VECTOR('',#149692,1.); +#149692 = DIRECTION('',(-1.,0.E+000)); +#149693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149694 = ORIENTED_EDGE('',*,*,#149695,.T.); +#149695 = EDGE_CURVE('',#149669,#149405,#149696,.T.); +#149696 = SURFACE_CURVE('',#149697,(#149702,#149731),.PCURVE_S1.); +#149697 = CIRCLE('',#149698,0.308574064194); +#149698 = AXIS2_PLACEMENT_3D('',#149699,#149700,#149701); +#149699 = CARTESIAN_POINT('',(2.65,10.728168876214,2.640924866458E-017) + ); +#149700 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149701 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149702 = PCURVE('',#149499,#149703); +#149703 = DEFINITIONAL_REPRESENTATION('',(#149704),#149730); +#149704 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149705,#149706,#149707, + #149708,#149709,#149710,#149711,#149712,#149713,#149714,#149715, + #149716,#149717,#149718,#149719,#149720,#149721,#149722,#149723, + #149724,#149725,#149726,#149727,#149728,#149729),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -181660,994 +184662,994 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#147313 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#147314 = CARTESIAN_POINT('',(3.166141578807,2.65)); -#147315 = CARTESIAN_POINT('',(3.215239429242,2.65)); -#147316 = CARTESIAN_POINT('',(3.288886204895,2.65)); -#147317 = CARTESIAN_POINT('',(3.362532980548,2.65)); -#147318 = CARTESIAN_POINT('',(3.4361797562,2.65)); -#147319 = CARTESIAN_POINT('',(3.509826531853,2.65)); -#147320 = CARTESIAN_POINT('',(3.583473307505,2.65)); -#147321 = CARTESIAN_POINT('',(3.657120083158,2.65)); -#147322 = CARTESIAN_POINT('',(3.730766858811,2.65)); -#147323 = CARTESIAN_POINT('',(3.804413634463,2.65)); -#147324 = CARTESIAN_POINT('',(3.878060410116,2.65)); -#147325 = CARTESIAN_POINT('',(3.951707185768,2.65)); -#147326 = CARTESIAN_POINT('',(4.025353961421,2.65)); -#147327 = CARTESIAN_POINT('',(4.099000737074,2.65)); -#147328 = CARTESIAN_POINT('',(4.172647512726,2.65)); -#147329 = CARTESIAN_POINT('',(4.246294288379,2.65)); -#147330 = CARTESIAN_POINT('',(4.319941064031,2.65)); -#147331 = CARTESIAN_POINT('',(4.393587839684,2.65)); -#147332 = CARTESIAN_POINT('',(4.467234615337,2.65)); -#147333 = CARTESIAN_POINT('',(4.540881390989,2.65)); -#147334 = CARTESIAN_POINT('',(4.614528166642,2.65)); -#147335 = CARTESIAN_POINT('',(4.688174942294,2.65)); -#147336 = CARTESIAN_POINT('',(4.737272792729,2.65)); -#147337 = CARTESIAN_POINT('',(4.761821717947,2.65)); -#147338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147339 = PCURVE('',#86756,#147340); -#147340 = DEFINITIONAL_REPRESENTATION('',(#147341),#147345); -#147341 = CIRCLE('',#147342,0.308574064194); -#147342 = AXIS2_PLACEMENT_2D('',#147343,#147344); -#147343 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#147344 = DIRECTION('',(0.E+000,1.)); -#147345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147346 = ADVANCED_FACE('',(#147347),#147211,.F.); -#147347 = FACE_BOUND('',#147348,.F.); -#147348 = EDGE_LOOP('',(#147349,#147350,#147377,#147404)); -#147349 = ORIENTED_EDGE('',*,*,#147197,.T.); -#147350 = ORIENTED_EDGE('',*,*,#147351,.F.); -#147351 = EDGE_CURVE('',#147352,#147122,#147354,.T.); -#147352 = VERTEX_POINT('',#147353); -#147353 = CARTESIAN_POINT('',(2.85,10.51959417205,0.E+000)); -#147354 = SURFACE_CURVE('',#147355,(#147360,#147366),.PCURVE_S1.); -#147355 = CIRCLE('',#147356,0.208574704164); -#147356 = AXIS2_PLACEMENT_3D('',#147357,#147358,#147359); -#147357 = CARTESIAN_POINT('',(2.85,10.728168876214,2.640924866458E-017) - ); -#147358 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147359 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147360 = PCURVE('',#147211,#147361); -#147361 = DEFINITIONAL_REPRESENTATION('',(#147362),#147365); -#147362 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147363,#147364), +#149705 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#149706 = CARTESIAN_POINT('',(3.166141578807,2.65)); +#149707 = CARTESIAN_POINT('',(3.215239429242,2.65)); +#149708 = CARTESIAN_POINT('',(3.288886204895,2.65)); +#149709 = CARTESIAN_POINT('',(3.362532980548,2.65)); +#149710 = CARTESIAN_POINT('',(3.4361797562,2.65)); +#149711 = CARTESIAN_POINT('',(3.509826531853,2.65)); +#149712 = CARTESIAN_POINT('',(3.583473307505,2.65)); +#149713 = CARTESIAN_POINT('',(3.657120083158,2.65)); +#149714 = CARTESIAN_POINT('',(3.730766858811,2.65)); +#149715 = CARTESIAN_POINT('',(3.804413634463,2.65)); +#149716 = CARTESIAN_POINT('',(3.878060410116,2.65)); +#149717 = CARTESIAN_POINT('',(3.951707185768,2.65)); +#149718 = CARTESIAN_POINT('',(4.025353961421,2.65)); +#149719 = CARTESIAN_POINT('',(4.099000737074,2.65)); +#149720 = CARTESIAN_POINT('',(4.172647512726,2.65)); +#149721 = CARTESIAN_POINT('',(4.246294288379,2.65)); +#149722 = CARTESIAN_POINT('',(4.319941064031,2.65)); +#149723 = CARTESIAN_POINT('',(4.393587839684,2.65)); +#149724 = CARTESIAN_POINT('',(4.467234615337,2.65)); +#149725 = CARTESIAN_POINT('',(4.540881390989,2.65)); +#149726 = CARTESIAN_POINT('',(4.614528166642,2.65)); +#149727 = CARTESIAN_POINT('',(4.688174942294,2.65)); +#149728 = CARTESIAN_POINT('',(4.737272792729,2.65)); +#149729 = CARTESIAN_POINT('',(4.761821717947,2.65)); +#149730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149731 = PCURVE('',#89148,#149732); +#149732 = DEFINITIONAL_REPRESENTATION('',(#149733),#149737); +#149733 = CIRCLE('',#149734,0.308574064194); +#149734 = AXIS2_PLACEMENT_2D('',#149735,#149736); +#149735 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#149736 = DIRECTION('',(0.E+000,1.)); +#149737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149738 = ADVANCED_FACE('',(#149739),#149603,.F.); +#149739 = FACE_BOUND('',#149740,.F.); +#149740 = EDGE_LOOP('',(#149741,#149742,#149769,#149796)); +#149741 = ORIENTED_EDGE('',*,*,#149589,.T.); +#149742 = ORIENTED_EDGE('',*,*,#149743,.F.); +#149743 = EDGE_CURVE('',#149744,#149514,#149746,.T.); +#149744 = VERTEX_POINT('',#149745); +#149745 = CARTESIAN_POINT('',(2.85,10.51959417205,0.E+000)); +#149746 = SURFACE_CURVE('',#149747,(#149752,#149758),.PCURVE_S1.); +#149747 = CIRCLE('',#149748,0.208574704164); +#149748 = AXIS2_PLACEMENT_3D('',#149749,#149750,#149751); +#149749 = CARTESIAN_POINT('',(2.85,10.728168876214,2.640924866458E-017) + ); +#149750 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149751 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149752 = PCURVE('',#149603,#149753); +#149753 = DEFINITIONAL_REPRESENTATION('',(#149754),#149757); +#149754 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149755,#149756), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#147363 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#147364 = CARTESIAN_POINT('',(4.772630242227,2.85)); -#147365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149755 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#149756 = CARTESIAN_POINT('',(4.772630242227,2.85)); +#149757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147366 = PCURVE('',#86700,#147367); -#147367 = DEFINITIONAL_REPRESENTATION('',(#147368),#147376); -#147368 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147369,#147370,#147371, - #147372,#147373,#147374,#147375),.UNSPECIFIED.,.T.,.F.) +#149758 = PCURVE('',#89092,#149759); +#149759 = DEFINITIONAL_REPRESENTATION('',(#149760),#149768); +#149760 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149761,#149762,#149763, + #149764,#149765,#149766,#149767),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#147369 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#147370 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#147371 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#147372 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#147373 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#147374 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#147375 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#147376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147377 = ORIENTED_EDGE('',*,*,#147378,.T.); -#147378 = EDGE_CURVE('',#147352,#147379,#147381,.T.); -#147379 = VERTEX_POINT('',#147380); -#147380 = CARTESIAN_POINT('',(2.65,10.51959417205,0.E+000)); -#147381 = SURFACE_CURVE('',#147382,(#147386,#147392),.PCURVE_S1.); -#147382 = LINE('',#147383,#147384); -#147383 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#149761 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#149762 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#149763 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#149764 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#149765 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#149766 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#149767 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#149768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149769 = ORIENTED_EDGE('',*,*,#149770,.T.); +#149770 = EDGE_CURVE('',#149744,#149771,#149773,.T.); +#149771 = VERTEX_POINT('',#149772); +#149772 = CARTESIAN_POINT('',(2.65,10.51959417205,0.E+000)); +#149773 = SURFACE_CURVE('',#149774,(#149778,#149784),.PCURVE_S1.); +#149774 = LINE('',#149775,#149776); +#149775 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#147384 = VECTOR('',#147385,1.); -#147385 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147386 = PCURVE('',#147211,#147387); -#147387 = DEFINITIONAL_REPRESENTATION('',(#147388),#147391); -#147388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147389,#147390), +#149776 = VECTOR('',#149777,1.); +#149777 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149778 = PCURVE('',#149603,#149779); +#149779 = DEFINITIONAL_REPRESENTATION('',(#149780),#149783); +#149780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149781,#149782), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#147389 = CARTESIAN_POINT('',(3.14159265359,2.85)); -#147390 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#147391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#149781 = CARTESIAN_POINT('',(3.14159265359,2.85)); +#149782 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#149783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147392 = PCURVE('',#147393,#147398); -#147393 = PLANE('',#147394); -#147394 = AXIS2_PLACEMENT_3D('',#147395,#147396,#147397); -#147395 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#149784 = PCURVE('',#149785,#149790); +#149785 = PLANE('',#149786); +#149786 = AXIS2_PLACEMENT_3D('',#149787,#149788,#149789); +#149787 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#147396 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147397 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147398 = DEFINITIONAL_REPRESENTATION('',(#147399),#147403); -#147399 = LINE('',#147400,#147401); -#147400 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#147401 = VECTOR('',#147402,1.); -#147402 = DIRECTION('',(-1.,0.E+000)); -#147403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147404 = ORIENTED_EDGE('',*,*,#147405,.T.); -#147405 = EDGE_CURVE('',#147379,#147175,#147406,.T.); -#147406 = SURFACE_CURVE('',#147407,(#147412,#147418),.PCURVE_S1.); -#147407 = CIRCLE('',#147408,0.208574704164); -#147408 = AXIS2_PLACEMENT_3D('',#147409,#147410,#147411); -#147409 = CARTESIAN_POINT('',(2.65,10.728168876214,2.640924866458E-017) - ); -#147410 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147411 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147412 = PCURVE('',#147211,#147413); -#147413 = DEFINITIONAL_REPRESENTATION('',(#147414),#147417); -#147414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147415,#147416), +#149788 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149789 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149790 = DEFINITIONAL_REPRESENTATION('',(#149791),#149795); +#149791 = LINE('',#149792,#149793); +#149792 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#149793 = VECTOR('',#149794,1.); +#149794 = DIRECTION('',(-1.,0.E+000)); +#149795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149796 = ORIENTED_EDGE('',*,*,#149797,.T.); +#149797 = EDGE_CURVE('',#149771,#149567,#149798,.T.); +#149798 = SURFACE_CURVE('',#149799,(#149804,#149810),.PCURVE_S1.); +#149799 = CIRCLE('',#149800,0.208574704164); +#149800 = AXIS2_PLACEMENT_3D('',#149801,#149802,#149803); +#149801 = CARTESIAN_POINT('',(2.65,10.728168876214,2.640924866458E-017) + ); +#149802 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149803 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#149804 = PCURVE('',#149603,#149805); +#149805 = DEFINITIONAL_REPRESENTATION('',(#149806),#149809); +#149806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149807,#149808), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#147415 = CARTESIAN_POINT('',(3.14159265359,2.65)); -#147416 = CARTESIAN_POINT('',(4.772630242227,2.65)); -#147417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147418 = PCURVE('',#86756,#147419); -#147419 = DEFINITIONAL_REPRESENTATION('',(#147420),#147424); -#147420 = CIRCLE('',#147421,0.208574704164); -#147421 = AXIS2_PLACEMENT_2D('',#147422,#147423); -#147422 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#147423 = DIRECTION('',(0.E+000,1.)); -#147424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147425 = ADVANCED_FACE('',(#147426),#147393,.F.); -#147426 = FACE_BOUND('',#147427,.T.); -#147427 = EDGE_LOOP('',(#147428,#147457,#147478,#147479)); -#147428 = ORIENTED_EDGE('',*,*,#147429,.F.); -#147429 = EDGE_CURVE('',#147430,#147432,#147434,.T.); -#147430 = VERTEX_POINT('',#147431); -#147431 = CARTESIAN_POINT('',(2.85,10.51959417205,0.530776333563)); -#147432 = VERTEX_POINT('',#147433); -#147433 = CARTESIAN_POINT('',(2.65,10.51959417205,0.530776333563)); -#147434 = SURFACE_CURVE('',#147435,(#147439,#147446),.PCURVE_S1.); -#147435 = LINE('',#147436,#147437); -#147436 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#149807 = CARTESIAN_POINT('',(3.14159265359,2.65)); +#149808 = CARTESIAN_POINT('',(4.772630242227,2.65)); +#149809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149810 = PCURVE('',#89148,#149811); +#149811 = DEFINITIONAL_REPRESENTATION('',(#149812),#149816); +#149812 = CIRCLE('',#149813,0.208574704164); +#149813 = AXIS2_PLACEMENT_2D('',#149814,#149815); +#149814 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#149815 = DIRECTION('',(0.E+000,1.)); +#149816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149817 = ADVANCED_FACE('',(#149818),#149785,.F.); +#149818 = FACE_BOUND('',#149819,.T.); +#149819 = EDGE_LOOP('',(#149820,#149849,#149870,#149871)); +#149820 = ORIENTED_EDGE('',*,*,#149821,.F.); +#149821 = EDGE_CURVE('',#149822,#149824,#149826,.T.); +#149822 = VERTEX_POINT('',#149823); +#149823 = CARTESIAN_POINT('',(2.85,10.51959417205,0.530776333563)); +#149824 = VERTEX_POINT('',#149825); +#149825 = CARTESIAN_POINT('',(2.65,10.51959417205,0.530776333563)); +#149826 = SURFACE_CURVE('',#149827,(#149831,#149838),.PCURVE_S1.); +#149827 = LINE('',#149828,#149829); +#149828 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#147437 = VECTOR('',#147438,1.); -#147438 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147439 = PCURVE('',#147393,#147440); -#147440 = DEFINITIONAL_REPRESENTATION('',(#147441),#147445); -#147441 = LINE('',#147442,#147443); -#147442 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147443 = VECTOR('',#147444,1.); -#147444 = DIRECTION('',(-1.,0.E+000)); -#147445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147446 = PCURVE('',#147447,#147452); -#147447 = CYLINDRICAL_SURFACE('',#147448,0.2192697516); -#147448 = AXIS2_PLACEMENT_3D('',#147449,#147450,#147451); -#147449 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#149829 = VECTOR('',#149830,1.); +#149830 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149831 = PCURVE('',#149785,#149832); +#149832 = DEFINITIONAL_REPRESENTATION('',(#149833),#149837); +#149833 = LINE('',#149834,#149835); +#149834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149835 = VECTOR('',#149836,1.); +#149836 = DIRECTION('',(-1.,0.E+000)); +#149837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149838 = PCURVE('',#149839,#149844); +#149839 = CYLINDRICAL_SURFACE('',#149840,0.2192697516); +#149840 = AXIS2_PLACEMENT_3D('',#149841,#149842,#149843); +#149841 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#147450 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147451 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147452 = DEFINITIONAL_REPRESENTATION('',(#147453),#147456); -#147453 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147454,#147455), +#149842 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149843 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149844 = DEFINITIONAL_REPRESENTATION('',(#149845),#149848); +#149845 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149846,#149847), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.85,-2.65),.PIECEWISE_BEZIER_KNOTS.); -#147454 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#147455 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#147456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147457 = ORIENTED_EDGE('',*,*,#147458,.T.); -#147458 = EDGE_CURVE('',#147430,#147352,#147459,.T.); -#147459 = SURFACE_CURVE('',#147460,(#147464,#147471),.PCURVE_S1.); -#147460 = LINE('',#147461,#147462); -#147461 = CARTESIAN_POINT('',(2.85,10.51959417205,0.530776333563)); -#147462 = VECTOR('',#147463,1.); -#147463 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147464 = PCURVE('',#147393,#147465); -#147465 = DEFINITIONAL_REPRESENTATION('',(#147466),#147470); -#147466 = LINE('',#147467,#147468); -#147467 = CARTESIAN_POINT('',(2.85,0.E+000)); -#147468 = VECTOR('',#147469,1.); -#147469 = DIRECTION('',(0.E+000,-1.)); -#147470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147471 = PCURVE('',#86700,#147472); -#147472 = DEFINITIONAL_REPRESENTATION('',(#147473),#147477); -#147473 = LINE('',#147474,#147475); -#147474 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#147475 = VECTOR('',#147476,1.); -#147476 = DIRECTION('',(-1.,0.E+000)); -#147477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147478 = ORIENTED_EDGE('',*,*,#147378,.T.); -#147479 = ORIENTED_EDGE('',*,*,#147480,.F.); -#147480 = EDGE_CURVE('',#147432,#147379,#147481,.T.); -#147481 = SURFACE_CURVE('',#147482,(#147486,#147493),.PCURVE_S1.); -#147482 = LINE('',#147483,#147484); -#147483 = CARTESIAN_POINT('',(2.65,10.51959417205,0.530776333563)); -#147484 = VECTOR('',#147485,1.); -#147485 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147486 = PCURVE('',#147393,#147487); -#147487 = DEFINITIONAL_REPRESENTATION('',(#147488),#147492); -#147488 = LINE('',#147489,#147490); -#147489 = CARTESIAN_POINT('',(2.65,0.E+000)); -#147490 = VECTOR('',#147491,1.); -#147491 = DIRECTION('',(0.E+000,-1.)); -#147492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147493 = PCURVE('',#86756,#147494); -#147494 = DEFINITIONAL_REPRESENTATION('',(#147495),#147499); -#147495 = LINE('',#147496,#147497); -#147496 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#147497 = VECTOR('',#147498,1.); -#147498 = DIRECTION('',(1.,0.E+000)); -#147499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147500 = ADVANCED_FACE('',(#147501),#147291,.F.); -#147501 = FACE_BOUND('',#147502,.T.); -#147502 = EDGE_LOOP('',(#147503,#147532,#147553,#147554)); -#147503 = ORIENTED_EDGE('',*,*,#147504,.F.); -#147504 = EDGE_CURVE('',#147505,#147507,#147509,.T.); -#147505 = VERTEX_POINT('',#147506); -#147506 = CARTESIAN_POINT('',(2.65,10.419594812019,0.530776333563)); -#147507 = VERTEX_POINT('',#147508); -#147508 = CARTESIAN_POINT('',(2.85,10.419594812019,0.530776333563)); -#147509 = SURFACE_CURVE('',#147510,(#147514,#147521),.PCURVE_S1.); -#147510 = LINE('',#147511,#147512); -#147511 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#149846 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#149847 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#149848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149849 = ORIENTED_EDGE('',*,*,#149850,.T.); +#149850 = EDGE_CURVE('',#149822,#149744,#149851,.T.); +#149851 = SURFACE_CURVE('',#149852,(#149856,#149863),.PCURVE_S1.); +#149852 = LINE('',#149853,#149854); +#149853 = CARTESIAN_POINT('',(2.85,10.51959417205,0.530776333563)); +#149854 = VECTOR('',#149855,1.); +#149855 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149856 = PCURVE('',#149785,#149857); +#149857 = DEFINITIONAL_REPRESENTATION('',(#149858),#149862); +#149858 = LINE('',#149859,#149860); +#149859 = CARTESIAN_POINT('',(2.85,0.E+000)); +#149860 = VECTOR('',#149861,1.); +#149861 = DIRECTION('',(0.E+000,-1.)); +#149862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149863 = PCURVE('',#89092,#149864); +#149864 = DEFINITIONAL_REPRESENTATION('',(#149865),#149869); +#149865 = LINE('',#149866,#149867); +#149866 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#149867 = VECTOR('',#149868,1.); +#149868 = DIRECTION('',(-1.,0.E+000)); +#149869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149870 = ORIENTED_EDGE('',*,*,#149770,.T.); +#149871 = ORIENTED_EDGE('',*,*,#149872,.F.); +#149872 = EDGE_CURVE('',#149824,#149771,#149873,.T.); +#149873 = SURFACE_CURVE('',#149874,(#149878,#149885),.PCURVE_S1.); +#149874 = LINE('',#149875,#149876); +#149875 = CARTESIAN_POINT('',(2.65,10.51959417205,0.530776333563)); +#149876 = VECTOR('',#149877,1.); +#149877 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149878 = PCURVE('',#149785,#149879); +#149879 = DEFINITIONAL_REPRESENTATION('',(#149880),#149884); +#149880 = LINE('',#149881,#149882); +#149881 = CARTESIAN_POINT('',(2.65,0.E+000)); +#149882 = VECTOR('',#149883,1.); +#149883 = DIRECTION('',(0.E+000,-1.)); +#149884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149885 = PCURVE('',#89148,#149886); +#149886 = DEFINITIONAL_REPRESENTATION('',(#149887),#149891); +#149887 = LINE('',#149888,#149889); +#149888 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#149889 = VECTOR('',#149890,1.); +#149890 = DIRECTION('',(1.,0.E+000)); +#149891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149892 = ADVANCED_FACE('',(#149893),#149683,.F.); +#149893 = FACE_BOUND('',#149894,.T.); +#149894 = EDGE_LOOP('',(#149895,#149924,#149945,#149946)); +#149895 = ORIENTED_EDGE('',*,*,#149896,.F.); +#149896 = EDGE_CURVE('',#149897,#149899,#149901,.T.); +#149897 = VERTEX_POINT('',#149898); +#149898 = CARTESIAN_POINT('',(2.65,10.419594812019,0.530776333563)); +#149899 = VERTEX_POINT('',#149900); +#149900 = CARTESIAN_POINT('',(2.85,10.419594812019,0.530776333563)); +#149901 = SURFACE_CURVE('',#149902,(#149906,#149913),.PCURVE_S1.); +#149902 = LINE('',#149903,#149904); +#149903 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#147512 = VECTOR('',#147513,1.); -#147513 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147514 = PCURVE('',#147291,#147515); -#147515 = DEFINITIONAL_REPRESENTATION('',(#147516),#147520); -#147516 = LINE('',#147517,#147518); -#147517 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147518 = VECTOR('',#147519,1.); -#147519 = DIRECTION('',(-1.,0.E+000)); -#147520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147521 = PCURVE('',#147522,#147527); -#147522 = CYLINDRICAL_SURFACE('',#147523,0.119270391569); -#147523 = AXIS2_PLACEMENT_3D('',#147524,#147525,#147526); -#147524 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#149904 = VECTOR('',#149905,1.); +#149905 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#149906 = PCURVE('',#149683,#149907); +#149907 = DEFINITIONAL_REPRESENTATION('',(#149908),#149912); +#149908 = LINE('',#149909,#149910); +#149909 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#149910 = VECTOR('',#149911,1.); +#149911 = DIRECTION('',(-1.,0.E+000)); +#149912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149913 = PCURVE('',#149914,#149919); +#149914 = CYLINDRICAL_SURFACE('',#149915,0.119270391569); +#149915 = AXIS2_PLACEMENT_3D('',#149916,#149917,#149918); +#149916 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#147525 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147526 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147527 = DEFINITIONAL_REPRESENTATION('',(#147528),#147531); -#147528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147529,#147530), +#149917 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149918 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149919 = DEFINITIONAL_REPRESENTATION('',(#149920),#149923); +#149920 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149921,#149922), .UNSPECIFIED.,.F.,.F.,(2,2),(2.65,2.85),.PIECEWISE_BEZIER_KNOTS.); -#147529 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#147530 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#147531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147532 = ORIENTED_EDGE('',*,*,#147533,.T.); -#147533 = EDGE_CURVE('',#147505,#147277,#147534,.T.); -#147534 = SURFACE_CURVE('',#147535,(#147539,#147546),.PCURVE_S1.); -#147535 = LINE('',#147536,#147537); -#147536 = CARTESIAN_POINT('',(2.65,10.419594812019,0.530776333563)); -#147537 = VECTOR('',#147538,1.); -#147538 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147539 = PCURVE('',#147291,#147540); -#147540 = DEFINITIONAL_REPRESENTATION('',(#147541),#147545); -#147541 = LINE('',#147542,#147543); -#147542 = CARTESIAN_POINT('',(-2.65,0.E+000)); -#147543 = VECTOR('',#147544,1.); -#147544 = DIRECTION('',(0.E+000,-1.)); -#147545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147546 = PCURVE('',#86756,#147547); -#147547 = DEFINITIONAL_REPRESENTATION('',(#147548),#147552); -#147548 = LINE('',#147549,#147550); -#147549 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#147550 = VECTOR('',#147551,1.); -#147551 = DIRECTION('',(1.,0.E+000)); -#147552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147553 = ORIENTED_EDGE('',*,*,#147276,.T.); -#147554 = ORIENTED_EDGE('',*,*,#147555,.F.); -#147555 = EDGE_CURVE('',#147507,#147227,#147556,.T.); -#147556 = SURFACE_CURVE('',#147557,(#147561,#147568),.PCURVE_S1.); -#147557 = LINE('',#147558,#147559); -#147558 = CARTESIAN_POINT('',(2.85,10.419594812019,0.530776333563)); -#147559 = VECTOR('',#147560,1.); -#147560 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147561 = PCURVE('',#147291,#147562); -#147562 = DEFINITIONAL_REPRESENTATION('',(#147563),#147567); -#147563 = LINE('',#147564,#147565); -#147564 = CARTESIAN_POINT('',(-2.85,0.E+000)); -#147565 = VECTOR('',#147566,1.); -#147566 = DIRECTION('',(0.E+000,-1.)); -#147567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147568 = PCURVE('',#86700,#147569); -#147569 = DEFINITIONAL_REPRESENTATION('',(#147570),#147574); -#147570 = LINE('',#147571,#147572); -#147571 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#147572 = VECTOR('',#147573,1.); -#147573 = DIRECTION('',(-1.,0.E+000)); -#147574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147575 = ADVANCED_FACE('',(#147576),#147447,.T.); -#147576 = FACE_BOUND('',#147577,.T.); -#147577 = EDGE_LOOP('',(#147578,#147601,#147602,#147629)); -#147578 = ORIENTED_EDGE('',*,*,#147579,.T.); -#147579 = EDGE_CURVE('',#147580,#147430,#147582,.T.); -#147580 = VERTEX_POINT('',#147581); -#147581 = CARTESIAN_POINT('',(2.85,10.304819755875,0.75)); -#147582 = SURFACE_CURVE('',#147583,(#147588,#147594),.PCURVE_S1.); -#147583 = CIRCLE('',#147584,0.2192697516); -#147584 = AXIS2_PLACEMENT_3D('',#147585,#147586,#147587); -#147585 = CARTESIAN_POINT('',(2.85,10.30032442045,0.530776333563)); -#147586 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147587 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147588 = PCURVE('',#147447,#147589); -#147589 = DEFINITIONAL_REPRESENTATION('',(#147590),#147593); -#147590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147591,#147592), +#149921 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#149922 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#149923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149924 = ORIENTED_EDGE('',*,*,#149925,.T.); +#149925 = EDGE_CURVE('',#149897,#149669,#149926,.T.); +#149926 = SURFACE_CURVE('',#149927,(#149931,#149938),.PCURVE_S1.); +#149927 = LINE('',#149928,#149929); +#149928 = CARTESIAN_POINT('',(2.65,10.419594812019,0.530776333563)); +#149929 = VECTOR('',#149930,1.); +#149930 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149931 = PCURVE('',#149683,#149932); +#149932 = DEFINITIONAL_REPRESENTATION('',(#149933),#149937); +#149933 = LINE('',#149934,#149935); +#149934 = CARTESIAN_POINT('',(-2.65,0.E+000)); +#149935 = VECTOR('',#149936,1.); +#149936 = DIRECTION('',(0.E+000,-1.)); +#149937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149938 = PCURVE('',#89148,#149939); +#149939 = DEFINITIONAL_REPRESENTATION('',(#149940),#149944); +#149940 = LINE('',#149941,#149942); +#149941 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#149942 = VECTOR('',#149943,1.); +#149943 = DIRECTION('',(1.,0.E+000)); +#149944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149945 = ORIENTED_EDGE('',*,*,#149668,.T.); +#149946 = ORIENTED_EDGE('',*,*,#149947,.F.); +#149947 = EDGE_CURVE('',#149899,#149619,#149948,.T.); +#149948 = SURFACE_CURVE('',#149949,(#149953,#149960),.PCURVE_S1.); +#149949 = LINE('',#149950,#149951); +#149950 = CARTESIAN_POINT('',(2.85,10.419594812019,0.530776333563)); +#149951 = VECTOR('',#149952,1.); +#149952 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#149953 = PCURVE('',#149683,#149954); +#149954 = DEFINITIONAL_REPRESENTATION('',(#149955),#149959); +#149955 = LINE('',#149956,#149957); +#149956 = CARTESIAN_POINT('',(-2.85,0.E+000)); +#149957 = VECTOR('',#149958,1.); +#149958 = DIRECTION('',(0.E+000,-1.)); +#149959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149960 = PCURVE('',#89092,#149961); +#149961 = DEFINITIONAL_REPRESENTATION('',(#149962),#149966); +#149962 = LINE('',#149963,#149964); +#149963 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#149964 = VECTOR('',#149965,1.); +#149965 = DIRECTION('',(-1.,0.E+000)); +#149966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149967 = ADVANCED_FACE('',(#149968),#149839,.T.); +#149968 = FACE_BOUND('',#149969,.T.); +#149969 = EDGE_LOOP('',(#149970,#149993,#149994,#150021)); +#149970 = ORIENTED_EDGE('',*,*,#149971,.T.); +#149971 = EDGE_CURVE('',#149972,#149822,#149974,.T.); +#149972 = VERTEX_POINT('',#149973); +#149973 = CARTESIAN_POINT('',(2.85,10.304819755875,0.75)); +#149974 = SURFACE_CURVE('',#149975,(#149980,#149986),.PCURVE_S1.); +#149975 = CIRCLE('',#149976,0.2192697516); +#149976 = AXIS2_PLACEMENT_3D('',#149977,#149978,#149979); +#149977 = CARTESIAN_POINT('',(2.85,10.30032442045,0.530776333563)); +#149978 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#149979 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#149980 = PCURVE('',#149839,#149981); +#149981 = DEFINITIONAL_REPRESENTATION('',(#149982),#149985); +#149982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149983,#149984), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#147591 = CARTESIAN_POINT('',(1.591299156552,-2.85)); -#147592 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#147593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147594 = PCURVE('',#86700,#147595); -#147595 = DEFINITIONAL_REPRESENTATION('',(#147596),#147600); -#147596 = CIRCLE('',#147597,0.2192697516); -#147597 = AXIS2_PLACEMENT_2D('',#147598,#147599); -#147598 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#147599 = DIRECTION('',(0.E+000,-1.)); -#147600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147601 = ORIENTED_EDGE('',*,*,#147429,.T.); -#147602 = ORIENTED_EDGE('',*,*,#147603,.F.); -#147603 = EDGE_CURVE('',#147604,#147432,#147606,.T.); -#147604 = VERTEX_POINT('',#147605); -#147605 = CARTESIAN_POINT('',(2.65,10.304819755875,0.75)); -#147606 = SURFACE_CURVE('',#147607,(#147612,#147618),.PCURVE_S1.); -#147607 = CIRCLE('',#147608,0.2192697516); -#147608 = AXIS2_PLACEMENT_3D('',#147609,#147610,#147611); -#147609 = CARTESIAN_POINT('',(2.65,10.30032442045,0.530776333563)); -#147610 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147611 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147612 = PCURVE('',#147447,#147613); -#147613 = DEFINITIONAL_REPRESENTATION('',(#147614),#147617); -#147614 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147615,#147616), +#149983 = CARTESIAN_POINT('',(1.591299156552,-2.85)); +#149984 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#149985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149986 = PCURVE('',#89092,#149987); +#149987 = DEFINITIONAL_REPRESENTATION('',(#149988),#149992); +#149988 = CIRCLE('',#149989,0.2192697516); +#149989 = AXIS2_PLACEMENT_2D('',#149990,#149991); +#149990 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#149991 = DIRECTION('',(0.E+000,-1.)); +#149992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#149993 = ORIENTED_EDGE('',*,*,#149821,.T.); +#149994 = ORIENTED_EDGE('',*,*,#149995,.F.); +#149995 = EDGE_CURVE('',#149996,#149824,#149998,.T.); +#149996 = VERTEX_POINT('',#149997); +#149997 = CARTESIAN_POINT('',(2.65,10.304819755875,0.75)); +#149998 = SURFACE_CURVE('',#149999,(#150004,#150010),.PCURVE_S1.); +#149999 = CIRCLE('',#150000,0.2192697516); +#150000 = AXIS2_PLACEMENT_3D('',#150001,#150002,#150003); +#150001 = CARTESIAN_POINT('',(2.65,10.30032442045,0.530776333563)); +#150002 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150003 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150004 = PCURVE('',#149839,#150005); +#150005 = DEFINITIONAL_REPRESENTATION('',(#150006),#150009); +#150006 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150007,#150008), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#147615 = CARTESIAN_POINT('',(1.591299156552,-2.65)); -#147616 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#147617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150007 = CARTESIAN_POINT('',(1.591299156552,-2.65)); +#150008 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#150009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147618 = PCURVE('',#86756,#147619); -#147619 = DEFINITIONAL_REPRESENTATION('',(#147620),#147628); -#147620 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147621,#147622,#147623, - #147624,#147625,#147626,#147627),.UNSPECIFIED.,.T.,.F.) +#150010 = PCURVE('',#89148,#150011); +#150011 = DEFINITIONAL_REPRESENTATION('',(#150012),#150020); +#150012 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150013,#150014,#150015, + #150016,#150017,#150018,#150019),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#147621 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#147622 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#147623 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#147624 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#147625 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#147626 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#147627 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#147628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147629 = ORIENTED_EDGE('',*,*,#147630,.T.); -#147630 = EDGE_CURVE('',#147604,#147580,#147631,.T.); -#147631 = SURFACE_CURVE('',#147632,(#147636,#147642),.PCURVE_S1.); -#147632 = LINE('',#147633,#147634); -#147633 = CARTESIAN_POINT('',(2.85,10.304819755875,0.75)); -#147634 = VECTOR('',#147635,1.); -#147635 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147636 = PCURVE('',#147447,#147637); -#147637 = DEFINITIONAL_REPRESENTATION('',(#147638),#147641); -#147638 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147639,#147640), +#150013 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#150014 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#150015 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#150016 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#150017 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#150018 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#150019 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#150020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150021 = ORIENTED_EDGE('',*,*,#150022,.T.); +#150022 = EDGE_CURVE('',#149996,#149972,#150023,.T.); +#150023 = SURFACE_CURVE('',#150024,(#150028,#150034),.PCURVE_S1.); +#150024 = LINE('',#150025,#150026); +#150025 = CARTESIAN_POINT('',(2.85,10.304819755875,0.75)); +#150026 = VECTOR('',#150027,1.); +#150027 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150028 = PCURVE('',#149839,#150029); +#150029 = DEFINITIONAL_REPRESENTATION('',(#150030),#150033); +#150030 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150031,#150032), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#147639 = CARTESIAN_POINT('',(1.591299156552,-2.65)); -#147640 = CARTESIAN_POINT('',(1.591299156552,-2.85)); -#147641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147642 = PCURVE('',#86728,#147643); -#147643 = DEFINITIONAL_REPRESENTATION('',(#147644),#147648); -#147644 = LINE('',#147645,#147646); -#147645 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#147646 = VECTOR('',#147647,1.); -#147647 = DIRECTION('',(-8.881784197001E-016,1.)); -#147648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147649 = ADVANCED_FACE('',(#147650),#147522,.F.); -#147650 = FACE_BOUND('',#147651,.F.); -#147651 = EDGE_LOOP('',(#147652,#147679,#147701,#147722)); -#147652 = ORIENTED_EDGE('',*,*,#147653,.F.); -#147653 = EDGE_CURVE('',#147654,#147505,#147656,.T.); -#147654 = VERTEX_POINT('',#147655); -#147655 = CARTESIAN_POINT('',(2.65,10.303662633502,0.65)); -#147656 = SURFACE_CURVE('',#147657,(#147662,#147668),.PCURVE_S1.); -#147657 = CIRCLE('',#147658,0.119270391569); -#147658 = AXIS2_PLACEMENT_3D('',#147659,#147660,#147661); -#147659 = CARTESIAN_POINT('',(2.65,10.30032442045,0.530776333563)); -#147660 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147661 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147662 = PCURVE('',#147522,#147663); -#147663 = DEFINITIONAL_REPRESENTATION('',(#147664),#147667); -#147664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147665,#147666), +#150031 = CARTESIAN_POINT('',(1.591299156552,-2.65)); +#150032 = CARTESIAN_POINT('',(1.591299156552,-2.85)); +#150033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150034 = PCURVE('',#89120,#150035); +#150035 = DEFINITIONAL_REPRESENTATION('',(#150036),#150040); +#150036 = LINE('',#150037,#150038); +#150037 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#150038 = VECTOR('',#150039,1.); +#150039 = DIRECTION('',(-8.881784197001E-016,1.)); +#150040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150041 = ADVANCED_FACE('',(#150042),#149914,.F.); +#150042 = FACE_BOUND('',#150043,.F.); +#150043 = EDGE_LOOP('',(#150044,#150071,#150093,#150114)); +#150044 = ORIENTED_EDGE('',*,*,#150045,.F.); +#150045 = EDGE_CURVE('',#150046,#149897,#150048,.T.); +#150046 = VERTEX_POINT('',#150047); +#150047 = CARTESIAN_POINT('',(2.65,10.303662633502,0.65)); +#150048 = SURFACE_CURVE('',#150049,(#150054,#150060),.PCURVE_S1.); +#150049 = CIRCLE('',#150050,0.119270391569); +#150050 = AXIS2_PLACEMENT_3D('',#150051,#150052,#150053); +#150051 = CARTESIAN_POINT('',(2.65,10.30032442045,0.530776333563)); +#150052 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150053 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150054 = PCURVE('',#149914,#150055); +#150055 = DEFINITIONAL_REPRESENTATION('',(#150056),#150059); +#150056 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150057,#150058), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#147665 = CARTESIAN_POINT('',(1.598788597134,-2.65)); -#147666 = CARTESIAN_POINT('',(3.14159265359,-2.65)); -#147667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150057 = CARTESIAN_POINT('',(1.598788597134,-2.65)); +#150058 = CARTESIAN_POINT('',(3.14159265359,-2.65)); +#150059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147668 = PCURVE('',#86756,#147669); -#147669 = DEFINITIONAL_REPRESENTATION('',(#147670),#147678); -#147670 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#147671,#147672,#147673, - #147674,#147675,#147676,#147677),.UNSPECIFIED.,.T.,.F.) +#150060 = PCURVE('',#89148,#150061); +#150061 = DEFINITIONAL_REPRESENTATION('',(#150062),#150070); +#150062 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150063,#150064,#150065, + #150066,#150067,#150068,#150069),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#147671 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#147672 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#147673 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#147674 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#147675 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#147676 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#147677 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#147678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147679 = ORIENTED_EDGE('',*,*,#147680,.F.); -#147680 = EDGE_CURVE('',#147681,#147654,#147683,.T.); -#147681 = VERTEX_POINT('',#147682); -#147682 = CARTESIAN_POINT('',(2.85,10.303662633502,0.65)); -#147683 = SURFACE_CURVE('',#147684,(#147688,#147694),.PCURVE_S1.); -#147684 = LINE('',#147685,#147686); -#147685 = CARTESIAN_POINT('',(2.85,10.303662633502,0.65)); -#147686 = VECTOR('',#147687,1.); -#147687 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147688 = PCURVE('',#147522,#147689); -#147689 = DEFINITIONAL_REPRESENTATION('',(#147690),#147693); -#147690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147691,#147692), +#150063 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#150064 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#150065 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#150066 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#150067 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#150068 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#150069 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#150070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150071 = ORIENTED_EDGE('',*,*,#150072,.F.); +#150072 = EDGE_CURVE('',#150073,#150046,#150075,.T.); +#150073 = VERTEX_POINT('',#150074); +#150074 = CARTESIAN_POINT('',(2.85,10.303662633502,0.65)); +#150075 = SURFACE_CURVE('',#150076,(#150080,#150086),.PCURVE_S1.); +#150076 = LINE('',#150077,#150078); +#150077 = CARTESIAN_POINT('',(2.85,10.303662633502,0.65)); +#150078 = VECTOR('',#150079,1.); +#150079 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150080 = PCURVE('',#149914,#150081); +#150081 = DEFINITIONAL_REPRESENTATION('',(#150082),#150085); +#150082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150083,#150084), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#147691 = CARTESIAN_POINT('',(1.598788597134,-2.85)); -#147692 = CARTESIAN_POINT('',(1.598788597134,-2.65)); -#147693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147694 = PCURVE('',#86782,#147695); -#147695 = DEFINITIONAL_REPRESENTATION('',(#147696),#147700); -#147696 = LINE('',#147697,#147698); -#147697 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#147698 = VECTOR('',#147699,1.); -#147699 = DIRECTION('',(-8.881784197001E-016,-1.)); -#147700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147701 = ORIENTED_EDGE('',*,*,#147702,.T.); -#147702 = EDGE_CURVE('',#147681,#147507,#147703,.T.); -#147703 = SURFACE_CURVE('',#147704,(#147709,#147715),.PCURVE_S1.); -#147704 = CIRCLE('',#147705,0.119270391569); -#147705 = AXIS2_PLACEMENT_3D('',#147706,#147707,#147708); -#147706 = CARTESIAN_POINT('',(2.85,10.30032442045,0.530776333563)); -#147707 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147708 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#147709 = PCURVE('',#147522,#147710); -#147710 = DEFINITIONAL_REPRESENTATION('',(#147711),#147714); -#147711 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#147712,#147713), +#150083 = CARTESIAN_POINT('',(1.598788597134,-2.85)); +#150084 = CARTESIAN_POINT('',(1.598788597134,-2.65)); +#150085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150086 = PCURVE('',#89174,#150087); +#150087 = DEFINITIONAL_REPRESENTATION('',(#150088),#150092); +#150088 = LINE('',#150089,#150090); +#150089 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#150090 = VECTOR('',#150091,1.); +#150091 = DIRECTION('',(-8.881784197001E-016,-1.)); +#150092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150093 = ORIENTED_EDGE('',*,*,#150094,.T.); +#150094 = EDGE_CURVE('',#150073,#149899,#150095,.T.); +#150095 = SURFACE_CURVE('',#150096,(#150101,#150107),.PCURVE_S1.); +#150096 = CIRCLE('',#150097,0.119270391569); +#150097 = AXIS2_PLACEMENT_3D('',#150098,#150099,#150100); +#150098 = CARTESIAN_POINT('',(2.85,10.30032442045,0.530776333563)); +#150099 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150100 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150101 = PCURVE('',#149914,#150102); +#150102 = DEFINITIONAL_REPRESENTATION('',(#150103),#150106); +#150103 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150104,#150105), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#147712 = CARTESIAN_POINT('',(1.598788597134,-2.85)); -#147713 = CARTESIAN_POINT('',(3.14159265359,-2.85)); -#147714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147715 = PCURVE('',#86700,#147716); -#147716 = DEFINITIONAL_REPRESENTATION('',(#147717),#147721); -#147717 = CIRCLE('',#147718,0.119270391569); -#147718 = AXIS2_PLACEMENT_2D('',#147719,#147720); -#147719 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#147720 = DIRECTION('',(0.E+000,-1.)); -#147721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147722 = ORIENTED_EDGE('',*,*,#147504,.F.); -#147723 = ADVANCED_FACE('',(#147724),#86700,.F.); -#147724 = FACE_BOUND('',#147725,.T.); -#147725 = EDGE_LOOP('',(#147726,#147747,#147748,#147749,#147750,#147751, - #147772,#147773,#147774,#147775,#147776,#147797)); -#147726 = ORIENTED_EDGE('',*,*,#147727,.F.); -#147727 = EDGE_CURVE('',#147681,#86685,#147728,.T.); -#147728 = SURFACE_CURVE('',#147729,(#147733,#147740),.PCURVE_S1.); -#147729 = LINE('',#147730,#147731); -#147730 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); -#147731 = VECTOR('',#147732,1.); -#147732 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#147733 = PCURVE('',#86700,#147734); -#147734 = DEFINITIONAL_REPRESENTATION('',(#147735),#147739); -#147735 = LINE('',#147736,#147737); -#147736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147737 = VECTOR('',#147738,1.); -#147738 = DIRECTION('',(3.563627120235E-016,-1.)); -#147739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147740 = PCURVE('',#86782,#147741); -#147741 = DEFINITIONAL_REPRESENTATION('',(#147742),#147746); -#147742 = LINE('',#147743,#147744); -#147743 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147744 = VECTOR('',#147745,1.); -#147745 = DIRECTION('',(1.,6.005309793447E-063)); -#147746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147747 = ORIENTED_EDGE('',*,*,#147702,.T.); -#147748 = ORIENTED_EDGE('',*,*,#147555,.T.); -#147749 = ORIENTED_EDGE('',*,*,#147226,.T.); -#147750 = ORIENTED_EDGE('',*,*,#147070,.T.); -#147751 = ORIENTED_EDGE('',*,*,#147752,.T.); -#147752 = EDGE_CURVE('',#147043,#147124,#147753,.T.); -#147753 = SURFACE_CURVE('',#147754,(#147758,#147765),.PCURVE_S1.); -#147754 = LINE('',#147755,#147756); -#147755 = CARTESIAN_POINT('',(2.85,11.,1.159810404338E-002)); -#147756 = VECTOR('',#147757,1.); -#147757 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#147758 = PCURVE('',#86700,#147759); -#147759 = DEFINITIONAL_REPRESENTATION('',(#147760),#147764); -#147760 = LINE('',#147761,#147762); -#147761 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#147762 = VECTOR('',#147763,1.); -#147763 = DIRECTION('',(1.,2.101748079665E-016)); -#147764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147765 = PCURVE('',#147058,#147766); -#147766 = DEFINITIONAL_REPRESENTATION('',(#147767),#147771); -#147767 = LINE('',#147768,#147769); -#147768 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#147769 = VECTOR('',#147770,1.); -#147770 = DIRECTION('',(-1.570395187386E-016,1.)); -#147771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147772 = ORIENTED_EDGE('',*,*,#147121,.F.); -#147773 = ORIENTED_EDGE('',*,*,#147351,.F.); -#147774 = ORIENTED_EDGE('',*,*,#147458,.F.); -#147775 = ORIENTED_EDGE('',*,*,#147579,.F.); -#147776 = ORIENTED_EDGE('',*,*,#147777,.T.); -#147777 = EDGE_CURVE('',#147580,#86683,#147778,.T.); -#147778 = SURFACE_CURVE('',#147779,(#147783,#147790),.PCURVE_S1.); -#147779 = LINE('',#147780,#147781); -#147780 = CARTESIAN_POINT('',(2.85,10.527847992439,0.75)); -#147781 = VECTOR('',#147782,1.); -#147782 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#147783 = PCURVE('',#86700,#147784); -#147784 = DEFINITIONAL_REPRESENTATION('',(#147785),#147789); -#147785 = LINE('',#147786,#147787); -#147786 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#147787 = VECTOR('',#147788,1.); -#147788 = DIRECTION('',(3.563627120235E-016,-1.)); -#147789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147790 = PCURVE('',#86728,#147791); -#147791 = DEFINITIONAL_REPRESENTATION('',(#147792),#147796); -#147792 = LINE('',#147793,#147794); -#147793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147794 = VECTOR('',#147795,1.); -#147795 = DIRECTION('',(-1.,6.005309793447E-063)); -#147796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147797 = ORIENTED_EDGE('',*,*,#86682,.T.); -#147798 = ADVANCED_FACE('',(#147799),#86728,.F.); -#147799 = FACE_BOUND('',#147800,.T.); -#147800 = EDGE_LOOP('',(#147801,#147802,#147823,#147824)); -#147801 = ORIENTED_EDGE('',*,*,#147630,.F.); -#147802 = ORIENTED_EDGE('',*,*,#147803,.T.); -#147803 = EDGE_CURVE('',#147604,#86713,#147804,.T.); -#147804 = SURFACE_CURVE('',#147805,(#147809,#147816),.PCURVE_S1.); -#147805 = LINE('',#147806,#147807); -#147806 = CARTESIAN_POINT('',(2.65,10.527847992439,0.75)); -#147807 = VECTOR('',#147808,1.); -#147808 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#147809 = PCURVE('',#86728,#147810); -#147810 = DEFINITIONAL_REPRESENTATION('',(#147811),#147815); -#147811 = LINE('',#147812,#147813); -#147812 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#147813 = VECTOR('',#147814,1.); -#147814 = DIRECTION('',(-1.,6.005309793447E-063)); -#147815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150104 = CARTESIAN_POINT('',(1.598788597134,-2.85)); +#150105 = CARTESIAN_POINT('',(3.14159265359,-2.85)); +#150106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150107 = PCURVE('',#89092,#150108); +#150108 = DEFINITIONAL_REPRESENTATION('',(#150109),#150113); +#150109 = CIRCLE('',#150110,0.119270391569); +#150110 = AXIS2_PLACEMENT_2D('',#150111,#150112); +#150111 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#150112 = DIRECTION('',(0.E+000,-1.)); +#150113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150114 = ORIENTED_EDGE('',*,*,#149896,.F.); +#150115 = ADVANCED_FACE('',(#150116),#89092,.F.); +#150116 = FACE_BOUND('',#150117,.T.); +#150117 = EDGE_LOOP('',(#150118,#150139,#150140,#150141,#150142,#150143, + #150164,#150165,#150166,#150167,#150168,#150189)); +#150118 = ORIENTED_EDGE('',*,*,#150119,.F.); +#150119 = EDGE_CURVE('',#150073,#89077,#150120,.T.); +#150120 = SURFACE_CURVE('',#150121,(#150125,#150132),.PCURVE_S1.); +#150121 = LINE('',#150122,#150123); +#150122 = CARTESIAN_POINT('',(2.85,10.527847992439,0.65)); +#150123 = VECTOR('',#150124,1.); +#150124 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#150125 = PCURVE('',#89092,#150126); +#150126 = DEFINITIONAL_REPRESENTATION('',(#150127),#150131); +#150127 = LINE('',#150128,#150129); +#150128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150129 = VECTOR('',#150130,1.); +#150130 = DIRECTION('',(3.563627120235E-016,-1.)); +#150131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150132 = PCURVE('',#89174,#150133); +#150133 = DEFINITIONAL_REPRESENTATION('',(#150134),#150138); +#150134 = LINE('',#150135,#150136); +#150135 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150136 = VECTOR('',#150137,1.); +#150137 = DIRECTION('',(1.,6.005309793447E-063)); +#150138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150139 = ORIENTED_EDGE('',*,*,#150094,.T.); +#150140 = ORIENTED_EDGE('',*,*,#149947,.T.); +#150141 = ORIENTED_EDGE('',*,*,#149618,.T.); +#150142 = ORIENTED_EDGE('',*,*,#149462,.T.); +#150143 = ORIENTED_EDGE('',*,*,#150144,.T.); +#150144 = EDGE_CURVE('',#149435,#149516,#150145,.T.); +#150145 = SURFACE_CURVE('',#150146,(#150150,#150157),.PCURVE_S1.); +#150146 = LINE('',#150147,#150148); +#150147 = CARTESIAN_POINT('',(2.85,11.,1.159810404338E-002)); +#150148 = VECTOR('',#150149,1.); +#150149 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#150150 = PCURVE('',#89092,#150151); +#150151 = DEFINITIONAL_REPRESENTATION('',(#150152),#150156); +#150152 = LINE('',#150153,#150154); +#150153 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#150154 = VECTOR('',#150155,1.); +#150155 = DIRECTION('',(1.,2.101748079665E-016)); +#150156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150157 = PCURVE('',#149450,#150158); +#150158 = DEFINITIONAL_REPRESENTATION('',(#150159),#150163); +#150159 = LINE('',#150160,#150161); +#150160 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#150161 = VECTOR('',#150162,1.); +#150162 = DIRECTION('',(-1.570395187386E-016,1.)); +#150163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150164 = ORIENTED_EDGE('',*,*,#149513,.F.); +#150165 = ORIENTED_EDGE('',*,*,#149743,.F.); +#150166 = ORIENTED_EDGE('',*,*,#149850,.F.); +#150167 = ORIENTED_EDGE('',*,*,#149971,.F.); +#150168 = ORIENTED_EDGE('',*,*,#150169,.T.); +#150169 = EDGE_CURVE('',#149972,#89075,#150170,.T.); +#150170 = SURFACE_CURVE('',#150171,(#150175,#150182),.PCURVE_S1.); +#150171 = LINE('',#150172,#150173); +#150172 = CARTESIAN_POINT('',(2.85,10.527847992439,0.75)); +#150173 = VECTOR('',#150174,1.); +#150174 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#150175 = PCURVE('',#89092,#150176); +#150176 = DEFINITIONAL_REPRESENTATION('',(#150177),#150181); +#150177 = LINE('',#150178,#150179); +#150178 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#150179 = VECTOR('',#150180,1.); +#150180 = DIRECTION('',(3.563627120235E-016,-1.)); +#150181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150182 = PCURVE('',#89120,#150183); +#150183 = DEFINITIONAL_REPRESENTATION('',(#150184),#150188); +#150184 = LINE('',#150185,#150186); +#150185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150186 = VECTOR('',#150187,1.); +#150187 = DIRECTION('',(-1.,6.005309793447E-063)); +#150188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150189 = ORIENTED_EDGE('',*,*,#89074,.T.); +#150190 = ADVANCED_FACE('',(#150191),#89120,.F.); +#150191 = FACE_BOUND('',#150192,.T.); +#150192 = EDGE_LOOP('',(#150193,#150194,#150215,#150216)); +#150193 = ORIENTED_EDGE('',*,*,#150022,.F.); +#150194 = ORIENTED_EDGE('',*,*,#150195,.T.); +#150195 = EDGE_CURVE('',#149996,#89105,#150196,.T.); +#150196 = SURFACE_CURVE('',#150197,(#150201,#150208),.PCURVE_S1.); +#150197 = LINE('',#150198,#150199); +#150198 = CARTESIAN_POINT('',(2.65,10.527847992439,0.75)); +#150199 = VECTOR('',#150200,1.); +#150200 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#150201 = PCURVE('',#89120,#150202); +#150202 = DEFINITIONAL_REPRESENTATION('',(#150203),#150207); +#150203 = LINE('',#150204,#150205); +#150204 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#150205 = VECTOR('',#150206,1.); +#150206 = DIRECTION('',(-1.,6.005309793447E-063)); +#150207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150208 = PCURVE('',#89148,#150209); +#150209 = DEFINITIONAL_REPRESENTATION('',(#150210),#150214); +#150210 = LINE('',#150211,#150212); +#150211 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#150212 = VECTOR('',#150213,1.); +#150213 = DIRECTION('',(-3.563627120235E-016,-1.)); +#150214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150215 = ORIENTED_EDGE('',*,*,#89104,.T.); +#150216 = ORIENTED_EDGE('',*,*,#150169,.F.); +#150217 = ADVANCED_FACE('',(#150218),#89148,.F.); +#150218 = FACE_BOUND('',#150219,.T.); +#150219 = EDGE_LOOP('',(#150220,#150221,#150222,#150223,#150224,#150225, + #150246,#150247,#150248,#150249,#150250,#150271)); +#150220 = ORIENTED_EDGE('',*,*,#150195,.F.); +#150221 = ORIENTED_EDGE('',*,*,#149995,.T.); +#150222 = ORIENTED_EDGE('',*,*,#149872,.T.); +#150223 = ORIENTED_EDGE('',*,*,#149797,.T.); +#150224 = ORIENTED_EDGE('',*,*,#149566,.T.); +#150225 = ORIENTED_EDGE('',*,*,#150226,.T.); +#150226 = EDGE_CURVE('',#149544,#149407,#150227,.T.); +#150227 = SURFACE_CURVE('',#150228,(#150232,#150239),.PCURVE_S1.); +#150228 = LINE('',#150229,#150230); +#150229 = CARTESIAN_POINT('',(2.65,11.,1.159810404338E-002)); +#150230 = VECTOR('',#150231,1.); +#150231 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#150232 = PCURVE('',#89148,#150233); +#150233 = DEFINITIONAL_REPRESENTATION('',(#150234),#150238); +#150234 = LINE('',#150235,#150236); +#150235 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#150236 = VECTOR('',#150237,1.); +#150237 = DIRECTION('',(1.,-2.101748079665E-016)); +#150238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150239 = PCURVE('',#149450,#150240); +#150240 = DEFINITIONAL_REPRESENTATION('',(#150241),#150245); +#150241 = LINE('',#150242,#150243); +#150242 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#150243 = VECTOR('',#150244,1.); +#150244 = DIRECTION('',(1.570395187386E-016,-1.)); +#150245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150246 = ORIENTED_EDGE('',*,*,#149404,.F.); +#150247 = ORIENTED_EDGE('',*,*,#149695,.F.); +#150248 = ORIENTED_EDGE('',*,*,#149925,.F.); +#150249 = ORIENTED_EDGE('',*,*,#150045,.F.); +#150250 = ORIENTED_EDGE('',*,*,#150251,.T.); +#150251 = EDGE_CURVE('',#150046,#89133,#150252,.T.); +#150252 = SURFACE_CURVE('',#150253,(#150257,#150264),.PCURVE_S1.); +#150253 = LINE('',#150254,#150255); +#150254 = CARTESIAN_POINT('',(2.65,10.527847992439,0.65)); +#150255 = VECTOR('',#150256,1.); +#150256 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#150257 = PCURVE('',#89148,#150258); +#150258 = DEFINITIONAL_REPRESENTATION('',(#150259),#150263); +#150259 = LINE('',#150260,#150261); +#150260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150261 = VECTOR('',#150262,1.); +#150262 = DIRECTION('',(-3.563627120235E-016,-1.)); +#150263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150264 = PCURVE('',#89174,#150265); +#150265 = DEFINITIONAL_REPRESENTATION('',(#150266),#150270); +#150266 = LINE('',#150267,#150268); +#150267 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#150268 = VECTOR('',#150269,1.); +#150269 = DIRECTION('',(1.,6.005309793447E-063)); +#150270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150271 = ORIENTED_EDGE('',*,*,#89132,.T.); +#150272 = ADVANCED_FACE('',(#150273),#89174,.F.); +#150273 = FACE_BOUND('',#150274,.T.); +#150274 = EDGE_LOOP('',(#150275,#150276,#150277,#150278)); +#150275 = ORIENTED_EDGE('',*,*,#150072,.F.); +#150276 = ORIENTED_EDGE('',*,*,#150119,.T.); +#150277 = ORIENTED_EDGE('',*,*,#89160,.T.); +#150278 = ORIENTED_EDGE('',*,*,#150251,.F.); +#150279 = ADVANCED_FACE('',(#150280),#149450,.T.); +#150280 = FACE_BOUND('',#150281,.T.); +#150281 = EDGE_LOOP('',(#150282,#150283,#150284,#150285)); +#150282 = ORIENTED_EDGE('',*,*,#150226,.F.); +#150283 = ORIENTED_EDGE('',*,*,#149543,.F.); +#150284 = ORIENTED_EDGE('',*,*,#150144,.F.); +#150285 = ORIENTED_EDGE('',*,*,#149434,.F.); +#150286 = ADVANCED_FACE('',(#150287),#150301,.T.); +#150287 = FACE_BOUND('',#150288,.T.); +#150288 = EDGE_LOOP('',(#150289,#150319,#150347,#150370)); +#150289 = ORIENTED_EDGE('',*,*,#150290,.T.); +#150290 = EDGE_CURVE('',#150291,#150293,#150295,.T.); +#150291 = VERTEX_POINT('',#150292); +#150292 = CARTESIAN_POINT('',(2.15,10.74341632541,-0.308197125857)); +#150293 = VERTEX_POINT('',#150294); +#150294 = CARTESIAN_POINT('',(2.15,11.,-0.308197125857)); +#150295 = SURFACE_CURVE('',#150296,(#150300,#150312),.PCURVE_S1.); +#150296 = LINE('',#150297,#150298); +#150297 = CARTESIAN_POINT('',(2.15,10.74341632541,-0.308197125857)); +#150298 = VECTOR('',#150299,1.); +#150299 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#150300 = PCURVE('',#150301,#150306); +#150301 = PLANE('',#150302); +#150302 = AXIS2_PLACEMENT_3D('',#150303,#150304,#150305); +#150303 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#150304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#150305 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#150306 = DEFINITIONAL_REPRESENTATION('',(#150307),#150311); +#150307 = LINE('',#150308,#150309); +#150308 = CARTESIAN_POINT('',(-2.15,-1.7763568394E-015)); +#150309 = VECTOR('',#150310,1.); +#150310 = DIRECTION('',(-6.725593854929E-015,1.)); +#150311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150312 = PCURVE('',#90630,#150313); +#150313 = DEFINITIONAL_REPRESENTATION('',(#150314),#150318); +#150314 = LINE('',#150315,#150316); +#150315 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#150316 = VECTOR('',#150317,1.); +#150317 = DIRECTION('',(0.E+000,1.)); +#150318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150319 = ORIENTED_EDGE('',*,*,#150320,.T.); +#150320 = EDGE_CURVE('',#150293,#150321,#150323,.T.); +#150321 = VERTEX_POINT('',#150322); +#150322 = CARTESIAN_POINT('',(2.35,11.,-0.308197125857)); +#150323 = SURFACE_CURVE('',#150324,(#150328,#150335),.PCURVE_S1.); +#150324 = LINE('',#150325,#150326); +#150325 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#150326 = VECTOR('',#150327,1.); +#150327 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150328 = PCURVE('',#150301,#150329); +#150329 = DEFINITIONAL_REPRESENTATION('',(#150330),#150334); +#150330 = LINE('',#150331,#150332); +#150331 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#150332 = VECTOR('',#150333,1.); +#150333 = DIRECTION('',(-1.,-8.881784197001E-016)); +#150334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#147816 = PCURVE('',#86756,#147817); -#147817 = DEFINITIONAL_REPRESENTATION('',(#147818),#147822); -#147818 = LINE('',#147819,#147820); -#147819 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#147820 = VECTOR('',#147821,1.); -#147821 = DIRECTION('',(-3.563627120235E-016,-1.)); -#147822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147823 = ORIENTED_EDGE('',*,*,#86712,.T.); -#147824 = ORIENTED_EDGE('',*,*,#147777,.F.); -#147825 = ADVANCED_FACE('',(#147826),#86756,.F.); -#147826 = FACE_BOUND('',#147827,.T.); -#147827 = EDGE_LOOP('',(#147828,#147829,#147830,#147831,#147832,#147833, - #147854,#147855,#147856,#147857,#147858,#147879)); -#147828 = ORIENTED_EDGE('',*,*,#147803,.F.); -#147829 = ORIENTED_EDGE('',*,*,#147603,.T.); -#147830 = ORIENTED_EDGE('',*,*,#147480,.T.); -#147831 = ORIENTED_EDGE('',*,*,#147405,.T.); -#147832 = ORIENTED_EDGE('',*,*,#147174,.T.); -#147833 = ORIENTED_EDGE('',*,*,#147834,.T.); -#147834 = EDGE_CURVE('',#147152,#147015,#147835,.T.); -#147835 = SURFACE_CURVE('',#147836,(#147840,#147847),.PCURVE_S1.); -#147836 = LINE('',#147837,#147838); -#147837 = CARTESIAN_POINT('',(2.65,11.,1.159810404338E-002)); -#147838 = VECTOR('',#147839,1.); -#147839 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#147840 = PCURVE('',#86756,#147841); -#147841 = DEFINITIONAL_REPRESENTATION('',(#147842),#147846); -#147842 = LINE('',#147843,#147844); -#147843 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#147844 = VECTOR('',#147845,1.); -#147845 = DIRECTION('',(1.,-2.101748079665E-016)); -#147846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147847 = PCURVE('',#147058,#147848); -#147848 = DEFINITIONAL_REPRESENTATION('',(#147849),#147853); -#147849 = LINE('',#147850,#147851); -#147850 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#147851 = VECTOR('',#147852,1.); -#147852 = DIRECTION('',(1.570395187386E-016,-1.)); -#147853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147854 = ORIENTED_EDGE('',*,*,#147012,.F.); -#147855 = ORIENTED_EDGE('',*,*,#147303,.F.); -#147856 = ORIENTED_EDGE('',*,*,#147533,.F.); -#147857 = ORIENTED_EDGE('',*,*,#147653,.F.); -#147858 = ORIENTED_EDGE('',*,*,#147859,.T.); -#147859 = EDGE_CURVE('',#147654,#86741,#147860,.T.); -#147860 = SURFACE_CURVE('',#147861,(#147865,#147872),.PCURVE_S1.); -#147861 = LINE('',#147862,#147863); -#147862 = CARTESIAN_POINT('',(2.65,10.527847992439,0.65)); -#147863 = VECTOR('',#147864,1.); -#147864 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#147865 = PCURVE('',#86756,#147866); -#147866 = DEFINITIONAL_REPRESENTATION('',(#147867),#147871); -#147867 = LINE('',#147868,#147869); -#147868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147869 = VECTOR('',#147870,1.); -#147870 = DIRECTION('',(-3.563627120235E-016,-1.)); -#147871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147872 = PCURVE('',#86782,#147873); -#147873 = DEFINITIONAL_REPRESENTATION('',(#147874),#147878); -#147874 = LINE('',#147875,#147876); -#147875 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#147876 = VECTOR('',#147877,1.); -#147877 = DIRECTION('',(1.,6.005309793447E-063)); -#147878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147879 = ORIENTED_EDGE('',*,*,#86740,.T.); -#147880 = ADVANCED_FACE('',(#147881),#86782,.F.); -#147881 = FACE_BOUND('',#147882,.T.); -#147882 = EDGE_LOOP('',(#147883,#147884,#147885,#147886)); -#147883 = ORIENTED_EDGE('',*,*,#147680,.F.); -#147884 = ORIENTED_EDGE('',*,*,#147727,.T.); -#147885 = ORIENTED_EDGE('',*,*,#86768,.T.); -#147886 = ORIENTED_EDGE('',*,*,#147859,.F.); -#147887 = ADVANCED_FACE('',(#147888),#147058,.T.); -#147888 = FACE_BOUND('',#147889,.T.); -#147889 = EDGE_LOOP('',(#147890,#147891,#147892,#147893)); -#147890 = ORIENTED_EDGE('',*,*,#147834,.F.); -#147891 = ORIENTED_EDGE('',*,*,#147151,.F.); -#147892 = ORIENTED_EDGE('',*,*,#147752,.F.); -#147893 = ORIENTED_EDGE('',*,*,#147042,.F.); -#147894 = ADVANCED_FACE('',(#147895),#147909,.T.); -#147895 = FACE_BOUND('',#147896,.T.); -#147896 = EDGE_LOOP('',(#147897,#147927,#147955,#147978)); -#147897 = ORIENTED_EDGE('',*,*,#147898,.T.); -#147898 = EDGE_CURVE('',#147899,#147901,#147903,.T.); -#147899 = VERTEX_POINT('',#147900); -#147900 = CARTESIAN_POINT('',(2.15,10.74341632541,-0.308197125857)); -#147901 = VERTEX_POINT('',#147902); -#147902 = CARTESIAN_POINT('',(2.15,11.,-0.308197125857)); -#147903 = SURFACE_CURVE('',#147904,(#147908,#147920),.PCURVE_S1.); -#147904 = LINE('',#147905,#147906); -#147905 = CARTESIAN_POINT('',(2.15,10.74341632541,-0.308197125857)); -#147906 = VECTOR('',#147907,1.); -#147907 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147908 = PCURVE('',#147909,#147914); -#147909 = PLANE('',#147910); -#147910 = AXIS2_PLACEMENT_3D('',#147911,#147912,#147913); -#147911 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#147912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#147913 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#147914 = DEFINITIONAL_REPRESENTATION('',(#147915),#147919); -#147915 = LINE('',#147916,#147917); -#147916 = CARTESIAN_POINT('',(-2.15,-1.7763568394E-015)); -#147917 = VECTOR('',#147918,1.); -#147918 = DIRECTION('',(-6.725593854929E-015,1.)); -#147919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147920 = PCURVE('',#88238,#147921); -#147921 = DEFINITIONAL_REPRESENTATION('',(#147922),#147926); -#147922 = LINE('',#147923,#147924); -#147923 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#147924 = VECTOR('',#147925,1.); -#147925 = DIRECTION('',(0.E+000,1.)); -#147926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147927 = ORIENTED_EDGE('',*,*,#147928,.T.); -#147928 = EDGE_CURVE('',#147901,#147929,#147931,.T.); -#147929 = VERTEX_POINT('',#147930); -#147930 = CARTESIAN_POINT('',(2.35,11.,-0.308197125857)); -#147931 = SURFACE_CURVE('',#147932,(#147936,#147943),.PCURVE_S1.); -#147932 = LINE('',#147933,#147934); -#147933 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#147934 = VECTOR('',#147935,1.); -#147935 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147936 = PCURVE('',#147909,#147937); -#147937 = DEFINITIONAL_REPRESENTATION('',(#147938),#147942); -#147938 = LINE('',#147939,#147940); -#147939 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#147940 = VECTOR('',#147941,1.); -#147941 = DIRECTION('',(-1.,-8.881784197001E-016)); -#147942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147943 = PCURVE('',#147944,#147949); -#147944 = PLANE('',#147945); -#147945 = AXIS2_PLACEMENT_3D('',#147946,#147947,#147948); -#147946 = CARTESIAN_POINT('',(2.25,11.,-0.258196742327)); -#147947 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#147948 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#147949 = DEFINITIONAL_REPRESENTATION('',(#147950),#147954); -#147950 = LINE('',#147951,#147952); -#147951 = CARTESIAN_POINT('',(2.25,-5.000038352949E-002)); -#147952 = VECTOR('',#147953,1.); -#147953 = DIRECTION('',(-1.,-1.1653254136E-048)); -#147954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147955 = ORIENTED_EDGE('',*,*,#147956,.F.); -#147956 = EDGE_CURVE('',#147957,#147929,#147959,.T.); -#147957 = VERTEX_POINT('',#147958); -#147958 = CARTESIAN_POINT('',(2.35,10.74341632541,-0.308197125857)); -#147959 = SURFACE_CURVE('',#147960,(#147964,#147971),.PCURVE_S1.); -#147960 = LINE('',#147961,#147962); -#147961 = CARTESIAN_POINT('',(2.35,10.74341632541,-0.308197125857)); -#147962 = VECTOR('',#147963,1.); -#147963 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#147964 = PCURVE('',#147909,#147965); -#147965 = DEFINITIONAL_REPRESENTATION('',(#147966),#147970); -#147966 = LINE('',#147967,#147968); -#147967 = CARTESIAN_POINT('',(-2.35,-1.7763568394E-015)); -#147968 = VECTOR('',#147969,1.); -#147969 = DIRECTION('',(-6.725593854929E-015,1.)); -#147970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147971 = PCURVE('',#88182,#147972); -#147972 = DEFINITIONAL_REPRESENTATION('',(#147973),#147977); -#147973 = LINE('',#147974,#147975); -#147974 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#147975 = VECTOR('',#147976,1.); -#147976 = DIRECTION('',(0.E+000,1.)); -#147977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147978 = ORIENTED_EDGE('',*,*,#147979,.T.); -#147979 = EDGE_CURVE('',#147957,#147899,#147980,.T.); -#147980 = SURFACE_CURVE('',#147981,(#147985,#147992),.PCURVE_S1.); -#147981 = LINE('',#147982,#147983); -#147982 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#150335 = PCURVE('',#150336,#150341); +#150336 = PLANE('',#150337); +#150337 = AXIS2_PLACEMENT_3D('',#150338,#150339,#150340); +#150338 = CARTESIAN_POINT('',(2.25,11.,-0.258196742327)); +#150339 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#150340 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#150341 = DEFINITIONAL_REPRESENTATION('',(#150342),#150346); +#150342 = LINE('',#150343,#150344); +#150343 = CARTESIAN_POINT('',(2.25,-5.000038352949E-002)); +#150344 = VECTOR('',#150345,1.); +#150345 = DIRECTION('',(-1.,-1.1653254136E-048)); +#150346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150347 = ORIENTED_EDGE('',*,*,#150348,.F.); +#150348 = EDGE_CURVE('',#150349,#150321,#150351,.T.); +#150349 = VERTEX_POINT('',#150350); +#150350 = CARTESIAN_POINT('',(2.35,10.74341632541,-0.308197125857)); +#150351 = SURFACE_CURVE('',#150352,(#150356,#150363),.PCURVE_S1.); +#150352 = LINE('',#150353,#150354); +#150353 = CARTESIAN_POINT('',(2.35,10.74341632541,-0.308197125857)); +#150354 = VECTOR('',#150355,1.); +#150355 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#150356 = PCURVE('',#150301,#150357); +#150357 = DEFINITIONAL_REPRESENTATION('',(#150358),#150362); +#150358 = LINE('',#150359,#150360); +#150359 = CARTESIAN_POINT('',(-2.35,-1.7763568394E-015)); +#150360 = VECTOR('',#150361,1.); +#150361 = DIRECTION('',(-6.725593854929E-015,1.)); +#150362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150363 = PCURVE('',#90574,#150364); +#150364 = DEFINITIONAL_REPRESENTATION('',(#150365),#150369); +#150365 = LINE('',#150366,#150367); +#150366 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#150367 = VECTOR('',#150368,1.); +#150368 = DIRECTION('',(0.E+000,1.)); +#150369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150370 = ORIENTED_EDGE('',*,*,#150371,.T.); +#150371 = EDGE_CURVE('',#150349,#150291,#150372,.T.); +#150372 = SURFACE_CURVE('',#150373,(#150377,#150384),.PCURVE_S1.); +#150373 = LINE('',#150374,#150375); +#150374 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#147983 = VECTOR('',#147984,1.); -#147984 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#147985 = PCURVE('',#147909,#147986); -#147986 = DEFINITIONAL_REPRESENTATION('',(#147987),#147991); -#147987 = LINE('',#147988,#147989); -#147988 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#147989 = VECTOR('',#147990,1.); -#147990 = DIRECTION('',(1.,8.881784197001E-016)); -#147991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#147992 = PCURVE('',#147993,#147998); -#147993 = CYLINDRICAL_SURFACE('',#147994,0.308574064194); -#147994 = AXIS2_PLACEMENT_3D('',#147995,#147996,#147997); -#147995 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#150375 = VECTOR('',#150376,1.); +#150376 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150377 = PCURVE('',#150301,#150378); +#150378 = DEFINITIONAL_REPRESENTATION('',(#150379),#150383); +#150379 = LINE('',#150380,#150381); +#150380 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150381 = VECTOR('',#150382,1.); +#150382 = DIRECTION('',(1.,8.881784197001E-016)); +#150383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150384 = PCURVE('',#150385,#150390); +#150385 = CYLINDRICAL_SURFACE('',#150386,0.308574064194); +#150386 = AXIS2_PLACEMENT_3D('',#150387,#150388,#150389); +#150387 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#147996 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#147997 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#147998 = DEFINITIONAL_REPRESENTATION('',(#147999),#148002); -#147999 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148000,#148001), +#150388 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150389 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150390 = DEFINITIONAL_REPRESENTATION('',(#150391),#150394); +#150391 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150392,#150393), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#148000 = CARTESIAN_POINT('',(4.761821717947,2.35)); -#148001 = CARTESIAN_POINT('',(4.761821717947,2.15)); -#148002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148003 = ADVANCED_FACE('',(#148004),#148018,.T.); -#148004 = FACE_BOUND('',#148005,.T.); -#148005 = EDGE_LOOP('',(#148006,#148036,#148059,#148082)); -#148006 = ORIENTED_EDGE('',*,*,#148007,.T.); -#148007 = EDGE_CURVE('',#148008,#148010,#148012,.T.); -#148008 = VERTEX_POINT('',#148009); -#148009 = CARTESIAN_POINT('',(2.35,10.740726081328,-0.208196358798)); -#148010 = VERTEX_POINT('',#148011); -#148011 = CARTESIAN_POINT('',(2.35,11.,-0.208196358798)); -#148012 = SURFACE_CURVE('',#148013,(#148017,#148029),.PCURVE_S1.); -#148013 = LINE('',#148014,#148015); -#148014 = CARTESIAN_POINT('',(2.35,10.740726081328,-0.208196358798)); -#148015 = VECTOR('',#148016,1.); -#148016 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148017 = PCURVE('',#148018,#148023); -#148018 = PLANE('',#148019); -#148019 = AXIS2_PLACEMENT_3D('',#148020,#148021,#148022); -#148020 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#150392 = CARTESIAN_POINT('',(4.761821717947,2.35)); +#150393 = CARTESIAN_POINT('',(4.761821717947,2.15)); +#150394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150395 = ADVANCED_FACE('',(#150396),#150410,.T.); +#150396 = FACE_BOUND('',#150397,.T.); +#150397 = EDGE_LOOP('',(#150398,#150428,#150451,#150474)); +#150398 = ORIENTED_EDGE('',*,*,#150399,.T.); +#150399 = EDGE_CURVE('',#150400,#150402,#150404,.T.); +#150400 = VERTEX_POINT('',#150401); +#150401 = CARTESIAN_POINT('',(2.35,10.740726081328,-0.208196358798)); +#150402 = VERTEX_POINT('',#150403); +#150403 = CARTESIAN_POINT('',(2.35,11.,-0.208196358798)); +#150404 = SURFACE_CURVE('',#150405,(#150409,#150421),.PCURVE_S1.); +#150405 = LINE('',#150406,#150407); +#150406 = CARTESIAN_POINT('',(2.35,10.740726081328,-0.208196358798)); +#150407 = VECTOR('',#150408,1.); +#150408 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#150409 = PCURVE('',#150410,#150415); +#150410 = PLANE('',#150411); +#150411 = AXIS2_PLACEMENT_3D('',#150412,#150413,#150414); +#150412 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#148021 = DIRECTION('',(0.E+000,0.E+000,1.)); -#148022 = DIRECTION('',(1.,0.E+000,0.E+000)); -#148023 = DEFINITIONAL_REPRESENTATION('',(#148024),#148028); -#148024 = LINE('',#148025,#148026); -#148025 = CARTESIAN_POINT('',(2.35,-1.7763568394E-015)); -#148026 = VECTOR('',#148027,1.); -#148027 = DIRECTION('',(6.725593854929E-015,1.)); -#148028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148029 = PCURVE('',#88182,#148030); -#148030 = DEFINITIONAL_REPRESENTATION('',(#148031),#148035); -#148031 = LINE('',#148032,#148033); -#148032 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#148033 = VECTOR('',#148034,1.); -#148034 = DIRECTION('',(0.E+000,1.)); -#148035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148036 = ORIENTED_EDGE('',*,*,#148037,.T.); -#148037 = EDGE_CURVE('',#148010,#148038,#148040,.T.); -#148038 = VERTEX_POINT('',#148039); -#148039 = CARTESIAN_POINT('',(2.15,11.,-0.208196358798)); -#148040 = SURFACE_CURVE('',#148041,(#148045,#148052),.PCURVE_S1.); -#148041 = LINE('',#148042,#148043); -#148042 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#148043 = VECTOR('',#148044,1.); -#148044 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148045 = PCURVE('',#148018,#148046); -#148046 = DEFINITIONAL_REPRESENTATION('',(#148047),#148051); -#148047 = LINE('',#148048,#148049); -#148048 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#148049 = VECTOR('',#148050,1.); -#148050 = DIRECTION('',(-1.,8.881784197001E-016)); -#148051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148052 = PCURVE('',#147944,#148053); -#148053 = DEFINITIONAL_REPRESENTATION('',(#148054),#148058); -#148054 = LINE('',#148055,#148056); -#148055 = CARTESIAN_POINT('',(2.25,5.000038352949E-002)); -#148056 = VECTOR('',#148057,1.); -#148057 = DIRECTION('',(1.,1.1653254136E-048)); -#148058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148059 = ORIENTED_EDGE('',*,*,#148060,.F.); -#148060 = EDGE_CURVE('',#148061,#148038,#148063,.T.); -#148061 = VERTEX_POINT('',#148062); -#148062 = CARTESIAN_POINT('',(2.15,10.740726081328,-0.208196358798)); -#148063 = SURFACE_CURVE('',#148064,(#148068,#148075),.PCURVE_S1.); -#148064 = LINE('',#148065,#148066); -#148065 = CARTESIAN_POINT('',(2.15,10.740726081328,-0.208196358798)); -#148066 = VECTOR('',#148067,1.); -#148067 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148068 = PCURVE('',#148018,#148069); -#148069 = DEFINITIONAL_REPRESENTATION('',(#148070),#148074); -#148070 = LINE('',#148071,#148072); -#148071 = CARTESIAN_POINT('',(2.15,-1.7763568394E-015)); -#148072 = VECTOR('',#148073,1.); -#148073 = DIRECTION('',(6.725593854929E-015,1.)); -#148074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148075 = PCURVE('',#88238,#148076); -#148076 = DEFINITIONAL_REPRESENTATION('',(#148077),#148081); -#148077 = LINE('',#148078,#148079); -#148078 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#148079 = VECTOR('',#148080,1.); -#148080 = DIRECTION('',(0.E+000,1.)); -#148081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148082 = ORIENTED_EDGE('',*,*,#148083,.T.); -#148083 = EDGE_CURVE('',#148061,#148008,#148084,.T.); -#148084 = SURFACE_CURVE('',#148085,(#148089,#148096),.PCURVE_S1.); -#148085 = LINE('',#148086,#148087); -#148086 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#150413 = DIRECTION('',(0.E+000,0.E+000,1.)); +#150414 = DIRECTION('',(1.,0.E+000,0.E+000)); +#150415 = DEFINITIONAL_REPRESENTATION('',(#150416),#150420); +#150416 = LINE('',#150417,#150418); +#150417 = CARTESIAN_POINT('',(2.35,-1.7763568394E-015)); +#150418 = VECTOR('',#150419,1.); +#150419 = DIRECTION('',(6.725593854929E-015,1.)); +#150420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150421 = PCURVE('',#90574,#150422); +#150422 = DEFINITIONAL_REPRESENTATION('',(#150423),#150427); +#150423 = LINE('',#150424,#150425); +#150424 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#150425 = VECTOR('',#150426,1.); +#150426 = DIRECTION('',(0.E+000,1.)); +#150427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150428 = ORIENTED_EDGE('',*,*,#150429,.T.); +#150429 = EDGE_CURVE('',#150402,#150430,#150432,.T.); +#150430 = VERTEX_POINT('',#150431); +#150431 = CARTESIAN_POINT('',(2.15,11.,-0.208196358798)); +#150432 = SURFACE_CURVE('',#150433,(#150437,#150444),.PCURVE_S1.); +#150433 = LINE('',#150434,#150435); +#150434 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#150435 = VECTOR('',#150436,1.); +#150436 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150437 = PCURVE('',#150410,#150438); +#150438 = DEFINITIONAL_REPRESENTATION('',(#150439),#150443); +#150439 = LINE('',#150440,#150441); +#150440 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#150441 = VECTOR('',#150442,1.); +#150442 = DIRECTION('',(-1.,8.881784197001E-016)); +#150443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150444 = PCURVE('',#150336,#150445); +#150445 = DEFINITIONAL_REPRESENTATION('',(#150446),#150450); +#150446 = LINE('',#150447,#150448); +#150447 = CARTESIAN_POINT('',(2.25,5.000038352949E-002)); +#150448 = VECTOR('',#150449,1.); +#150449 = DIRECTION('',(1.,1.1653254136E-048)); +#150450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150451 = ORIENTED_EDGE('',*,*,#150452,.F.); +#150452 = EDGE_CURVE('',#150453,#150430,#150455,.T.); +#150453 = VERTEX_POINT('',#150454); +#150454 = CARTESIAN_POINT('',(2.15,10.740726081328,-0.208196358798)); +#150455 = SURFACE_CURVE('',#150456,(#150460,#150467),.PCURVE_S1.); +#150456 = LINE('',#150457,#150458); +#150457 = CARTESIAN_POINT('',(2.15,10.740726081328,-0.208196358798)); +#150458 = VECTOR('',#150459,1.); +#150459 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#150460 = PCURVE('',#150410,#150461); +#150461 = DEFINITIONAL_REPRESENTATION('',(#150462),#150466); +#150462 = LINE('',#150463,#150464); +#150463 = CARTESIAN_POINT('',(2.15,-1.7763568394E-015)); +#150464 = VECTOR('',#150465,1.); +#150465 = DIRECTION('',(6.725593854929E-015,1.)); +#150466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150467 = PCURVE('',#90630,#150468); +#150468 = DEFINITIONAL_REPRESENTATION('',(#150469),#150473); +#150469 = LINE('',#150470,#150471); +#150470 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#150471 = VECTOR('',#150472,1.); +#150472 = DIRECTION('',(0.E+000,1.)); +#150473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150474 = ORIENTED_EDGE('',*,*,#150475,.T.); +#150475 = EDGE_CURVE('',#150453,#150400,#150476,.T.); +#150476 = SURFACE_CURVE('',#150477,(#150481,#150488),.PCURVE_S1.); +#150477 = LINE('',#150478,#150479); +#150478 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#148087 = VECTOR('',#148088,1.); -#148088 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148089 = PCURVE('',#148018,#148090); -#148090 = DEFINITIONAL_REPRESENTATION('',(#148091),#148095); -#148091 = LINE('',#148092,#148093); -#148092 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148093 = VECTOR('',#148094,1.); -#148094 = DIRECTION('',(1.,-8.881784197001E-016)); -#148095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148096 = PCURVE('',#148097,#148102); -#148097 = CYLINDRICAL_SURFACE('',#148098,0.208574704164); -#148098 = AXIS2_PLACEMENT_3D('',#148099,#148100,#148101); -#148099 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#150479 = VECTOR('',#150480,1.); +#150480 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150481 = PCURVE('',#150410,#150482); +#150482 = DEFINITIONAL_REPRESENTATION('',(#150483),#150487); +#150483 = LINE('',#150484,#150485); +#150484 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150485 = VECTOR('',#150486,1.); +#150486 = DIRECTION('',(1.,-8.881784197001E-016)); +#150487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150488 = PCURVE('',#150489,#150494); +#150489 = CYLINDRICAL_SURFACE('',#150490,0.208574704164); +#150490 = AXIS2_PLACEMENT_3D('',#150491,#150492,#150493); +#150491 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#148100 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148101 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148102 = DEFINITIONAL_REPRESENTATION('',(#148103),#148106); -#148103 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148104,#148105), +#150492 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150493 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150494 = DEFINITIONAL_REPRESENTATION('',(#150495),#150498); +#150495 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150496,#150497), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#148104 = CARTESIAN_POINT('',(4.772630242227,2.15)); -#148105 = CARTESIAN_POINT('',(4.772630242227,2.35)); -#148106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148107 = ADVANCED_FACE('',(#148108),#147993,.T.); -#148108 = FACE_BOUND('',#148109,.T.); -#148109 = EDGE_LOOP('',(#148110,#148111,#148161,#148188)); -#148110 = ORIENTED_EDGE('',*,*,#147979,.F.); -#148111 = ORIENTED_EDGE('',*,*,#148112,.F.); -#148112 = EDGE_CURVE('',#148113,#147957,#148115,.T.); -#148113 = VERTEX_POINT('',#148114); -#148114 = CARTESIAN_POINT('',(2.35,10.419594812019,0.E+000)); -#148115 = SURFACE_CURVE('',#148116,(#148121,#148150),.PCURVE_S1.); -#148116 = CIRCLE('',#148117,0.308574064194); -#148117 = AXIS2_PLACEMENT_3D('',#148118,#148119,#148120); -#148118 = CARTESIAN_POINT('',(2.35,10.728168876214,2.640924866458E-017) - ); -#148119 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148120 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148121 = PCURVE('',#147993,#148122); -#148122 = DEFINITIONAL_REPRESENTATION('',(#148123),#148149); -#148123 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#148124,#148125,#148126, - #148127,#148128,#148129,#148130,#148131,#148132,#148133,#148134, - #148135,#148136,#148137,#148138,#148139,#148140,#148141,#148142, - #148143,#148144,#148145,#148146,#148147,#148148),.UNSPECIFIED.,.F., +#150496 = CARTESIAN_POINT('',(4.772630242227,2.15)); +#150497 = CARTESIAN_POINT('',(4.772630242227,2.35)); +#150498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150499 = ADVANCED_FACE('',(#150500),#150385,.T.); +#150500 = FACE_BOUND('',#150501,.T.); +#150501 = EDGE_LOOP('',(#150502,#150503,#150553,#150580)); +#150502 = ORIENTED_EDGE('',*,*,#150371,.F.); +#150503 = ORIENTED_EDGE('',*,*,#150504,.F.); +#150504 = EDGE_CURVE('',#150505,#150349,#150507,.T.); +#150505 = VERTEX_POINT('',#150506); +#150506 = CARTESIAN_POINT('',(2.35,10.419594812019,0.E+000)); +#150507 = SURFACE_CURVE('',#150508,(#150513,#150542),.PCURVE_S1.); +#150508 = CIRCLE('',#150509,0.308574064194); +#150509 = AXIS2_PLACEMENT_3D('',#150510,#150511,#150512); +#150510 = CARTESIAN_POINT('',(2.35,10.728168876214,2.640924866458E-017) + ); +#150511 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150512 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150513 = PCURVE('',#150385,#150514); +#150514 = DEFINITIONAL_REPRESENTATION('',(#150515),#150541); +#150515 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150516,#150517,#150518, + #150519,#150520,#150521,#150522,#150523,#150524,#150525,#150526, + #150527,#150528,#150529,#150530,#150531,#150532,#150533,#150534, + #150535,#150536,#150537,#150538,#150539,#150540),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -182655,102 +185657,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#148124 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#148125 = CARTESIAN_POINT('',(3.166141578807,2.35)); -#148126 = CARTESIAN_POINT('',(3.215239429242,2.35)); -#148127 = CARTESIAN_POINT('',(3.288886204895,2.35)); -#148128 = CARTESIAN_POINT('',(3.362532980548,2.35)); -#148129 = CARTESIAN_POINT('',(3.4361797562,2.35)); -#148130 = CARTESIAN_POINT('',(3.509826531853,2.35)); -#148131 = CARTESIAN_POINT('',(3.583473307505,2.35)); -#148132 = CARTESIAN_POINT('',(3.657120083158,2.35)); -#148133 = CARTESIAN_POINT('',(3.730766858811,2.35)); -#148134 = CARTESIAN_POINT('',(3.804413634463,2.35)); -#148135 = CARTESIAN_POINT('',(3.878060410116,2.35)); -#148136 = CARTESIAN_POINT('',(3.951707185768,2.35)); -#148137 = CARTESIAN_POINT('',(4.025353961421,2.35)); -#148138 = CARTESIAN_POINT('',(4.099000737074,2.35)); -#148139 = CARTESIAN_POINT('',(4.172647512726,2.35)); -#148140 = CARTESIAN_POINT('',(4.246294288379,2.35)); -#148141 = CARTESIAN_POINT('',(4.319941064031,2.35)); -#148142 = CARTESIAN_POINT('',(4.393587839684,2.35)); -#148143 = CARTESIAN_POINT('',(4.467234615337,2.35)); -#148144 = CARTESIAN_POINT('',(4.540881390989,2.35)); -#148145 = CARTESIAN_POINT('',(4.614528166642,2.35)); -#148146 = CARTESIAN_POINT('',(4.688174942294,2.35)); -#148147 = CARTESIAN_POINT('',(4.737272792729,2.35)); -#148148 = CARTESIAN_POINT('',(4.761821717947,2.35)); -#148149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148150 = PCURVE('',#88182,#148151); -#148151 = DEFINITIONAL_REPRESENTATION('',(#148152),#148160); -#148152 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148153,#148154,#148155, - #148156,#148157,#148158,#148159),.UNSPECIFIED.,.T.,.F.) +#150516 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#150517 = CARTESIAN_POINT('',(3.166141578807,2.35)); +#150518 = CARTESIAN_POINT('',(3.215239429242,2.35)); +#150519 = CARTESIAN_POINT('',(3.288886204895,2.35)); +#150520 = CARTESIAN_POINT('',(3.362532980548,2.35)); +#150521 = CARTESIAN_POINT('',(3.4361797562,2.35)); +#150522 = CARTESIAN_POINT('',(3.509826531853,2.35)); +#150523 = CARTESIAN_POINT('',(3.583473307505,2.35)); +#150524 = CARTESIAN_POINT('',(3.657120083158,2.35)); +#150525 = CARTESIAN_POINT('',(3.730766858811,2.35)); +#150526 = CARTESIAN_POINT('',(3.804413634463,2.35)); +#150527 = CARTESIAN_POINT('',(3.878060410116,2.35)); +#150528 = CARTESIAN_POINT('',(3.951707185768,2.35)); +#150529 = CARTESIAN_POINT('',(4.025353961421,2.35)); +#150530 = CARTESIAN_POINT('',(4.099000737074,2.35)); +#150531 = CARTESIAN_POINT('',(4.172647512726,2.35)); +#150532 = CARTESIAN_POINT('',(4.246294288379,2.35)); +#150533 = CARTESIAN_POINT('',(4.319941064031,2.35)); +#150534 = CARTESIAN_POINT('',(4.393587839684,2.35)); +#150535 = CARTESIAN_POINT('',(4.467234615337,2.35)); +#150536 = CARTESIAN_POINT('',(4.540881390989,2.35)); +#150537 = CARTESIAN_POINT('',(4.614528166642,2.35)); +#150538 = CARTESIAN_POINT('',(4.688174942294,2.35)); +#150539 = CARTESIAN_POINT('',(4.737272792729,2.35)); +#150540 = CARTESIAN_POINT('',(4.761821717947,2.35)); +#150541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150542 = PCURVE('',#90574,#150543); +#150543 = DEFINITIONAL_REPRESENTATION('',(#150544),#150552); +#150544 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150545,#150546,#150547, + #150548,#150549,#150550,#150551),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#148153 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#148154 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#148155 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#148156 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#148157 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#148158 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#148159 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#148160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148161 = ORIENTED_EDGE('',*,*,#148162,.F.); -#148162 = EDGE_CURVE('',#148163,#148113,#148165,.T.); -#148163 = VERTEX_POINT('',#148164); -#148164 = CARTESIAN_POINT('',(2.15,10.419594812019,0.E+000)); -#148165 = SURFACE_CURVE('',#148166,(#148170,#148176),.PCURVE_S1.); -#148166 = LINE('',#148167,#148168); -#148167 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#150545 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#150546 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#150547 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#150548 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#150549 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#150550 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#150551 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#150552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150553 = ORIENTED_EDGE('',*,*,#150554,.F.); +#150554 = EDGE_CURVE('',#150555,#150505,#150557,.T.); +#150555 = VERTEX_POINT('',#150556); +#150556 = CARTESIAN_POINT('',(2.15,10.419594812019,0.E+000)); +#150557 = SURFACE_CURVE('',#150558,(#150562,#150568),.PCURVE_S1.); +#150558 = LINE('',#150559,#150560); +#150559 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#148168 = VECTOR('',#148169,1.); -#148169 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148170 = PCURVE('',#147993,#148171); -#148171 = DEFINITIONAL_REPRESENTATION('',(#148172),#148175); -#148172 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148173,#148174), +#150560 = VECTOR('',#150561,1.); +#150561 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150562 = PCURVE('',#150385,#150563); +#150563 = DEFINITIONAL_REPRESENTATION('',(#150564),#150567); +#150564 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150565,#150566), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#148173 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#148174 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#148175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150565 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#150566 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#150567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148176 = PCURVE('',#148177,#148182); -#148177 = PLANE('',#148178); -#148178 = AXIS2_PLACEMENT_3D('',#148179,#148180,#148181); -#148179 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#150568 = PCURVE('',#150569,#150574); +#150569 = PLANE('',#150570); +#150570 = AXIS2_PLACEMENT_3D('',#150571,#150572,#150573); +#150571 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#148180 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148181 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148182 = DEFINITIONAL_REPRESENTATION('',(#148183),#148187); -#148183 = LINE('',#148184,#148185); -#148184 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#148185 = VECTOR('',#148186,1.); -#148186 = DIRECTION('',(-1.,0.E+000)); -#148187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148188 = ORIENTED_EDGE('',*,*,#148189,.T.); -#148189 = EDGE_CURVE('',#148163,#147899,#148190,.T.); -#148190 = SURFACE_CURVE('',#148191,(#148196,#148225),.PCURVE_S1.); -#148191 = CIRCLE('',#148192,0.308574064194); -#148192 = AXIS2_PLACEMENT_3D('',#148193,#148194,#148195); -#148193 = CARTESIAN_POINT('',(2.15,10.728168876214,2.640924866458E-017) - ); -#148194 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148195 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148196 = PCURVE('',#147993,#148197); -#148197 = DEFINITIONAL_REPRESENTATION('',(#148198),#148224); -#148198 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#148199,#148200,#148201, - #148202,#148203,#148204,#148205,#148206,#148207,#148208,#148209, - #148210,#148211,#148212,#148213,#148214,#148215,#148216,#148217, - #148218,#148219,#148220,#148221,#148222,#148223),.UNSPECIFIED.,.F., +#150572 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150573 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150574 = DEFINITIONAL_REPRESENTATION('',(#150575),#150579); +#150575 = LINE('',#150576,#150577); +#150576 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#150577 = VECTOR('',#150578,1.); +#150578 = DIRECTION('',(-1.,0.E+000)); +#150579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150580 = ORIENTED_EDGE('',*,*,#150581,.T.); +#150581 = EDGE_CURVE('',#150555,#150291,#150582,.T.); +#150582 = SURFACE_CURVE('',#150583,(#150588,#150617),.PCURVE_S1.); +#150583 = CIRCLE('',#150584,0.308574064194); +#150584 = AXIS2_PLACEMENT_3D('',#150585,#150586,#150587); +#150585 = CARTESIAN_POINT('',(2.15,10.728168876214,2.640924866458E-017) + ); +#150586 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150587 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150588 = PCURVE('',#150385,#150589); +#150589 = DEFINITIONAL_REPRESENTATION('',(#150590),#150616); +#150590 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150591,#150592,#150593, + #150594,#150595,#150596,#150597,#150598,#150599,#150600,#150601, + #150602,#150603,#150604,#150605,#150606,#150607,#150608,#150609, + #150610,#150611,#150612,#150613,#150614,#150615),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -182758,994 +185760,994 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#148199 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#148200 = CARTESIAN_POINT('',(3.166141578807,2.15)); -#148201 = CARTESIAN_POINT('',(3.215239429242,2.15)); -#148202 = CARTESIAN_POINT('',(3.288886204895,2.15)); -#148203 = CARTESIAN_POINT('',(3.362532980548,2.15)); -#148204 = CARTESIAN_POINT('',(3.4361797562,2.15)); -#148205 = CARTESIAN_POINT('',(3.509826531853,2.15)); -#148206 = CARTESIAN_POINT('',(3.583473307505,2.15)); -#148207 = CARTESIAN_POINT('',(3.657120083158,2.15)); -#148208 = CARTESIAN_POINT('',(3.730766858811,2.15)); -#148209 = CARTESIAN_POINT('',(3.804413634463,2.15)); -#148210 = CARTESIAN_POINT('',(3.878060410116,2.15)); -#148211 = CARTESIAN_POINT('',(3.951707185768,2.15)); -#148212 = CARTESIAN_POINT('',(4.025353961421,2.15)); -#148213 = CARTESIAN_POINT('',(4.099000737074,2.15)); -#148214 = CARTESIAN_POINT('',(4.172647512726,2.15)); -#148215 = CARTESIAN_POINT('',(4.246294288379,2.15)); -#148216 = CARTESIAN_POINT('',(4.319941064031,2.15)); -#148217 = CARTESIAN_POINT('',(4.393587839684,2.15)); -#148218 = CARTESIAN_POINT('',(4.467234615337,2.15)); -#148219 = CARTESIAN_POINT('',(4.540881390989,2.15)); -#148220 = CARTESIAN_POINT('',(4.614528166642,2.15)); -#148221 = CARTESIAN_POINT('',(4.688174942294,2.15)); -#148222 = CARTESIAN_POINT('',(4.737272792729,2.15)); -#148223 = CARTESIAN_POINT('',(4.761821717947,2.15)); -#148224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148225 = PCURVE('',#88238,#148226); -#148226 = DEFINITIONAL_REPRESENTATION('',(#148227),#148231); -#148227 = CIRCLE('',#148228,0.308574064194); -#148228 = AXIS2_PLACEMENT_2D('',#148229,#148230); -#148229 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#148230 = DIRECTION('',(0.E+000,1.)); -#148231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148232 = ADVANCED_FACE('',(#148233),#148097,.F.); -#148233 = FACE_BOUND('',#148234,.F.); -#148234 = EDGE_LOOP('',(#148235,#148236,#148263,#148290)); -#148235 = ORIENTED_EDGE('',*,*,#148083,.T.); -#148236 = ORIENTED_EDGE('',*,*,#148237,.F.); -#148237 = EDGE_CURVE('',#148238,#148008,#148240,.T.); -#148238 = VERTEX_POINT('',#148239); -#148239 = CARTESIAN_POINT('',(2.35,10.51959417205,0.E+000)); -#148240 = SURFACE_CURVE('',#148241,(#148246,#148252),.PCURVE_S1.); -#148241 = CIRCLE('',#148242,0.208574704164); -#148242 = AXIS2_PLACEMENT_3D('',#148243,#148244,#148245); -#148243 = CARTESIAN_POINT('',(2.35,10.728168876214,2.640924866458E-017) - ); -#148244 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148245 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148246 = PCURVE('',#148097,#148247); -#148247 = DEFINITIONAL_REPRESENTATION('',(#148248),#148251); -#148248 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148249,#148250), +#150591 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#150592 = CARTESIAN_POINT('',(3.166141578807,2.15)); +#150593 = CARTESIAN_POINT('',(3.215239429242,2.15)); +#150594 = CARTESIAN_POINT('',(3.288886204895,2.15)); +#150595 = CARTESIAN_POINT('',(3.362532980548,2.15)); +#150596 = CARTESIAN_POINT('',(3.4361797562,2.15)); +#150597 = CARTESIAN_POINT('',(3.509826531853,2.15)); +#150598 = CARTESIAN_POINT('',(3.583473307505,2.15)); +#150599 = CARTESIAN_POINT('',(3.657120083158,2.15)); +#150600 = CARTESIAN_POINT('',(3.730766858811,2.15)); +#150601 = CARTESIAN_POINT('',(3.804413634463,2.15)); +#150602 = CARTESIAN_POINT('',(3.878060410116,2.15)); +#150603 = CARTESIAN_POINT('',(3.951707185768,2.15)); +#150604 = CARTESIAN_POINT('',(4.025353961421,2.15)); +#150605 = CARTESIAN_POINT('',(4.099000737074,2.15)); +#150606 = CARTESIAN_POINT('',(4.172647512726,2.15)); +#150607 = CARTESIAN_POINT('',(4.246294288379,2.15)); +#150608 = CARTESIAN_POINT('',(4.319941064031,2.15)); +#150609 = CARTESIAN_POINT('',(4.393587839684,2.15)); +#150610 = CARTESIAN_POINT('',(4.467234615337,2.15)); +#150611 = CARTESIAN_POINT('',(4.540881390989,2.15)); +#150612 = CARTESIAN_POINT('',(4.614528166642,2.15)); +#150613 = CARTESIAN_POINT('',(4.688174942294,2.15)); +#150614 = CARTESIAN_POINT('',(4.737272792729,2.15)); +#150615 = CARTESIAN_POINT('',(4.761821717947,2.15)); +#150616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150617 = PCURVE('',#90630,#150618); +#150618 = DEFINITIONAL_REPRESENTATION('',(#150619),#150623); +#150619 = CIRCLE('',#150620,0.308574064194); +#150620 = AXIS2_PLACEMENT_2D('',#150621,#150622); +#150621 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#150622 = DIRECTION('',(0.E+000,1.)); +#150623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150624 = ADVANCED_FACE('',(#150625),#150489,.F.); +#150625 = FACE_BOUND('',#150626,.F.); +#150626 = EDGE_LOOP('',(#150627,#150628,#150655,#150682)); +#150627 = ORIENTED_EDGE('',*,*,#150475,.T.); +#150628 = ORIENTED_EDGE('',*,*,#150629,.F.); +#150629 = EDGE_CURVE('',#150630,#150400,#150632,.T.); +#150630 = VERTEX_POINT('',#150631); +#150631 = CARTESIAN_POINT('',(2.35,10.51959417205,0.E+000)); +#150632 = SURFACE_CURVE('',#150633,(#150638,#150644),.PCURVE_S1.); +#150633 = CIRCLE('',#150634,0.208574704164); +#150634 = AXIS2_PLACEMENT_3D('',#150635,#150636,#150637); +#150635 = CARTESIAN_POINT('',(2.35,10.728168876214,2.640924866458E-017) + ); +#150636 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150637 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150638 = PCURVE('',#150489,#150639); +#150639 = DEFINITIONAL_REPRESENTATION('',(#150640),#150643); +#150640 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150641,#150642), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#148249 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#148250 = CARTESIAN_POINT('',(4.772630242227,2.35)); -#148251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150641 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#150642 = CARTESIAN_POINT('',(4.772630242227,2.35)); +#150643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148252 = PCURVE('',#88182,#148253); -#148253 = DEFINITIONAL_REPRESENTATION('',(#148254),#148262); -#148254 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148255,#148256,#148257, - #148258,#148259,#148260,#148261),.UNSPECIFIED.,.T.,.F.) +#150644 = PCURVE('',#90574,#150645); +#150645 = DEFINITIONAL_REPRESENTATION('',(#150646),#150654); +#150646 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150647,#150648,#150649, + #150650,#150651,#150652,#150653),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#148255 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#148256 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#148257 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#148258 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#148259 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#148260 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#148261 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#148262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148263 = ORIENTED_EDGE('',*,*,#148264,.T.); -#148264 = EDGE_CURVE('',#148238,#148265,#148267,.T.); -#148265 = VERTEX_POINT('',#148266); -#148266 = CARTESIAN_POINT('',(2.15,10.51959417205,0.E+000)); -#148267 = SURFACE_CURVE('',#148268,(#148272,#148278),.PCURVE_S1.); -#148268 = LINE('',#148269,#148270); -#148269 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#150647 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#150648 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#150649 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#150650 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#150651 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#150652 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#150653 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#150654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150655 = ORIENTED_EDGE('',*,*,#150656,.T.); +#150656 = EDGE_CURVE('',#150630,#150657,#150659,.T.); +#150657 = VERTEX_POINT('',#150658); +#150658 = CARTESIAN_POINT('',(2.15,10.51959417205,0.E+000)); +#150659 = SURFACE_CURVE('',#150660,(#150664,#150670),.PCURVE_S1.); +#150660 = LINE('',#150661,#150662); +#150661 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#148270 = VECTOR('',#148271,1.); -#148271 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148272 = PCURVE('',#148097,#148273); -#148273 = DEFINITIONAL_REPRESENTATION('',(#148274),#148277); -#148274 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148275,#148276), +#150662 = VECTOR('',#150663,1.); +#150663 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150664 = PCURVE('',#150489,#150665); +#150665 = DEFINITIONAL_REPRESENTATION('',(#150666),#150669); +#150666 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150667,#150668), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#148275 = CARTESIAN_POINT('',(3.14159265359,2.35)); -#148276 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#148277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150667 = CARTESIAN_POINT('',(3.14159265359,2.35)); +#150668 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#150669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148278 = PCURVE('',#148279,#148284); -#148279 = PLANE('',#148280); -#148280 = AXIS2_PLACEMENT_3D('',#148281,#148282,#148283); -#148281 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#150670 = PCURVE('',#150671,#150676); +#150671 = PLANE('',#150672); +#150672 = AXIS2_PLACEMENT_3D('',#150673,#150674,#150675); +#150673 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#148282 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148283 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148284 = DEFINITIONAL_REPRESENTATION('',(#148285),#148289); -#148285 = LINE('',#148286,#148287); -#148286 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#148287 = VECTOR('',#148288,1.); -#148288 = DIRECTION('',(-1.,0.E+000)); -#148289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148290 = ORIENTED_EDGE('',*,*,#148291,.T.); -#148291 = EDGE_CURVE('',#148265,#148061,#148292,.T.); -#148292 = SURFACE_CURVE('',#148293,(#148298,#148304),.PCURVE_S1.); -#148293 = CIRCLE('',#148294,0.208574704164); -#148294 = AXIS2_PLACEMENT_3D('',#148295,#148296,#148297); -#148295 = CARTESIAN_POINT('',(2.15,10.728168876214,2.640924866458E-017) - ); -#148296 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148297 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148298 = PCURVE('',#148097,#148299); -#148299 = DEFINITIONAL_REPRESENTATION('',(#148300),#148303); -#148300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148301,#148302), +#150674 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150675 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150676 = DEFINITIONAL_REPRESENTATION('',(#150677),#150681); +#150677 = LINE('',#150678,#150679); +#150678 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#150679 = VECTOR('',#150680,1.); +#150680 = DIRECTION('',(-1.,0.E+000)); +#150681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150682 = ORIENTED_EDGE('',*,*,#150683,.T.); +#150683 = EDGE_CURVE('',#150657,#150453,#150684,.T.); +#150684 = SURFACE_CURVE('',#150685,(#150690,#150696),.PCURVE_S1.); +#150685 = CIRCLE('',#150686,0.208574704164); +#150686 = AXIS2_PLACEMENT_3D('',#150687,#150688,#150689); +#150687 = CARTESIAN_POINT('',(2.15,10.728168876214,2.640924866458E-017) + ); +#150688 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150689 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#150690 = PCURVE('',#150489,#150691); +#150691 = DEFINITIONAL_REPRESENTATION('',(#150692),#150695); +#150692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150693,#150694), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.772630242227), .PIECEWISE_BEZIER_KNOTS.); -#148301 = CARTESIAN_POINT('',(3.14159265359,2.15)); -#148302 = CARTESIAN_POINT('',(4.772630242227,2.15)); -#148303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148304 = PCURVE('',#88238,#148305); -#148305 = DEFINITIONAL_REPRESENTATION('',(#148306),#148310); -#148306 = CIRCLE('',#148307,0.208574704164); -#148307 = AXIS2_PLACEMENT_2D('',#148308,#148309); -#148308 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#148309 = DIRECTION('',(0.E+000,1.)); -#148310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148311 = ADVANCED_FACE('',(#148312),#148279,.F.); -#148312 = FACE_BOUND('',#148313,.T.); -#148313 = EDGE_LOOP('',(#148314,#148343,#148364,#148365)); -#148314 = ORIENTED_EDGE('',*,*,#148315,.F.); -#148315 = EDGE_CURVE('',#148316,#148318,#148320,.T.); -#148316 = VERTEX_POINT('',#148317); -#148317 = CARTESIAN_POINT('',(2.35,10.51959417205,0.530776333563)); -#148318 = VERTEX_POINT('',#148319); -#148319 = CARTESIAN_POINT('',(2.15,10.51959417205,0.530776333563)); -#148320 = SURFACE_CURVE('',#148321,(#148325,#148332),.PCURVE_S1.); -#148321 = LINE('',#148322,#148323); -#148322 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#150693 = CARTESIAN_POINT('',(3.14159265359,2.15)); +#150694 = CARTESIAN_POINT('',(4.772630242227,2.15)); +#150695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150696 = PCURVE('',#90630,#150697); +#150697 = DEFINITIONAL_REPRESENTATION('',(#150698),#150702); +#150698 = CIRCLE('',#150699,0.208574704164); +#150699 = AXIS2_PLACEMENT_2D('',#150700,#150701); +#150700 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#150701 = DIRECTION('',(0.E+000,1.)); +#150702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150703 = ADVANCED_FACE('',(#150704),#150671,.F.); +#150704 = FACE_BOUND('',#150705,.T.); +#150705 = EDGE_LOOP('',(#150706,#150735,#150756,#150757)); +#150706 = ORIENTED_EDGE('',*,*,#150707,.F.); +#150707 = EDGE_CURVE('',#150708,#150710,#150712,.T.); +#150708 = VERTEX_POINT('',#150709); +#150709 = CARTESIAN_POINT('',(2.35,10.51959417205,0.530776333563)); +#150710 = VERTEX_POINT('',#150711); +#150711 = CARTESIAN_POINT('',(2.15,10.51959417205,0.530776333563)); +#150712 = SURFACE_CURVE('',#150713,(#150717,#150724),.PCURVE_S1.); +#150713 = LINE('',#150714,#150715); +#150714 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#148323 = VECTOR('',#148324,1.); -#148324 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148325 = PCURVE('',#148279,#148326); -#148326 = DEFINITIONAL_REPRESENTATION('',(#148327),#148331); -#148327 = LINE('',#148328,#148329); -#148328 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148329 = VECTOR('',#148330,1.); -#148330 = DIRECTION('',(-1.,0.E+000)); -#148331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148332 = PCURVE('',#148333,#148338); -#148333 = CYLINDRICAL_SURFACE('',#148334,0.2192697516); -#148334 = AXIS2_PLACEMENT_3D('',#148335,#148336,#148337); -#148335 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#150715 = VECTOR('',#150716,1.); +#150716 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150717 = PCURVE('',#150671,#150718); +#150718 = DEFINITIONAL_REPRESENTATION('',(#150719),#150723); +#150719 = LINE('',#150720,#150721); +#150720 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150721 = VECTOR('',#150722,1.); +#150722 = DIRECTION('',(-1.,0.E+000)); +#150723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150724 = PCURVE('',#150725,#150730); +#150725 = CYLINDRICAL_SURFACE('',#150726,0.2192697516); +#150726 = AXIS2_PLACEMENT_3D('',#150727,#150728,#150729); +#150727 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#148336 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148337 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148338 = DEFINITIONAL_REPRESENTATION('',(#148339),#148342); -#148339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148340,#148341), +#150728 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150729 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150730 = DEFINITIONAL_REPRESENTATION('',(#150731),#150734); +#150731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150732,#150733), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.35,-2.15),.PIECEWISE_BEZIER_KNOTS.); -#148340 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#148341 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#148342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148343 = ORIENTED_EDGE('',*,*,#148344,.T.); -#148344 = EDGE_CURVE('',#148316,#148238,#148345,.T.); -#148345 = SURFACE_CURVE('',#148346,(#148350,#148357),.PCURVE_S1.); -#148346 = LINE('',#148347,#148348); -#148347 = CARTESIAN_POINT('',(2.35,10.51959417205,0.530776333563)); -#148348 = VECTOR('',#148349,1.); -#148349 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#148350 = PCURVE('',#148279,#148351); -#148351 = DEFINITIONAL_REPRESENTATION('',(#148352),#148356); -#148352 = LINE('',#148353,#148354); -#148353 = CARTESIAN_POINT('',(2.35,0.E+000)); -#148354 = VECTOR('',#148355,1.); -#148355 = DIRECTION('',(0.E+000,-1.)); -#148356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148357 = PCURVE('',#88182,#148358); -#148358 = DEFINITIONAL_REPRESENTATION('',(#148359),#148363); -#148359 = LINE('',#148360,#148361); -#148360 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#148361 = VECTOR('',#148362,1.); -#148362 = DIRECTION('',(-1.,0.E+000)); -#148363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148364 = ORIENTED_EDGE('',*,*,#148264,.T.); -#148365 = ORIENTED_EDGE('',*,*,#148366,.F.); -#148366 = EDGE_CURVE('',#148318,#148265,#148367,.T.); -#148367 = SURFACE_CURVE('',#148368,(#148372,#148379),.PCURVE_S1.); -#148368 = LINE('',#148369,#148370); -#148369 = CARTESIAN_POINT('',(2.15,10.51959417205,0.530776333563)); -#148370 = VECTOR('',#148371,1.); -#148371 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#148372 = PCURVE('',#148279,#148373); -#148373 = DEFINITIONAL_REPRESENTATION('',(#148374),#148378); -#148374 = LINE('',#148375,#148376); -#148375 = CARTESIAN_POINT('',(2.15,0.E+000)); -#148376 = VECTOR('',#148377,1.); -#148377 = DIRECTION('',(0.E+000,-1.)); -#148378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148379 = PCURVE('',#88238,#148380); -#148380 = DEFINITIONAL_REPRESENTATION('',(#148381),#148385); -#148381 = LINE('',#148382,#148383); -#148382 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#148383 = VECTOR('',#148384,1.); -#148384 = DIRECTION('',(1.,0.E+000)); -#148385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148386 = ADVANCED_FACE('',(#148387),#148177,.F.); -#148387 = FACE_BOUND('',#148388,.T.); -#148388 = EDGE_LOOP('',(#148389,#148418,#148439,#148440)); -#148389 = ORIENTED_EDGE('',*,*,#148390,.F.); -#148390 = EDGE_CURVE('',#148391,#148393,#148395,.T.); -#148391 = VERTEX_POINT('',#148392); -#148392 = CARTESIAN_POINT('',(2.15,10.419594812019,0.530776333563)); -#148393 = VERTEX_POINT('',#148394); -#148394 = CARTESIAN_POINT('',(2.35,10.419594812019,0.530776333563)); -#148395 = SURFACE_CURVE('',#148396,(#148400,#148407),.PCURVE_S1.); -#148396 = LINE('',#148397,#148398); -#148397 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#150732 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#150733 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#150734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150735 = ORIENTED_EDGE('',*,*,#150736,.T.); +#150736 = EDGE_CURVE('',#150708,#150630,#150737,.T.); +#150737 = SURFACE_CURVE('',#150738,(#150742,#150749),.PCURVE_S1.); +#150738 = LINE('',#150739,#150740); +#150739 = CARTESIAN_POINT('',(2.35,10.51959417205,0.530776333563)); +#150740 = VECTOR('',#150741,1.); +#150741 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#150742 = PCURVE('',#150671,#150743); +#150743 = DEFINITIONAL_REPRESENTATION('',(#150744),#150748); +#150744 = LINE('',#150745,#150746); +#150745 = CARTESIAN_POINT('',(2.35,0.E+000)); +#150746 = VECTOR('',#150747,1.); +#150747 = DIRECTION('',(0.E+000,-1.)); +#150748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150749 = PCURVE('',#90574,#150750); +#150750 = DEFINITIONAL_REPRESENTATION('',(#150751),#150755); +#150751 = LINE('',#150752,#150753); +#150752 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#150753 = VECTOR('',#150754,1.); +#150754 = DIRECTION('',(-1.,0.E+000)); +#150755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150756 = ORIENTED_EDGE('',*,*,#150656,.T.); +#150757 = ORIENTED_EDGE('',*,*,#150758,.F.); +#150758 = EDGE_CURVE('',#150710,#150657,#150759,.T.); +#150759 = SURFACE_CURVE('',#150760,(#150764,#150771),.PCURVE_S1.); +#150760 = LINE('',#150761,#150762); +#150761 = CARTESIAN_POINT('',(2.15,10.51959417205,0.530776333563)); +#150762 = VECTOR('',#150763,1.); +#150763 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#150764 = PCURVE('',#150671,#150765); +#150765 = DEFINITIONAL_REPRESENTATION('',(#150766),#150770); +#150766 = LINE('',#150767,#150768); +#150767 = CARTESIAN_POINT('',(2.15,0.E+000)); +#150768 = VECTOR('',#150769,1.); +#150769 = DIRECTION('',(0.E+000,-1.)); +#150770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150771 = PCURVE('',#90630,#150772); +#150772 = DEFINITIONAL_REPRESENTATION('',(#150773),#150777); +#150773 = LINE('',#150774,#150775); +#150774 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#150775 = VECTOR('',#150776,1.); +#150776 = DIRECTION('',(1.,0.E+000)); +#150777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150778 = ADVANCED_FACE('',(#150779),#150569,.F.); +#150779 = FACE_BOUND('',#150780,.T.); +#150780 = EDGE_LOOP('',(#150781,#150810,#150831,#150832)); +#150781 = ORIENTED_EDGE('',*,*,#150782,.F.); +#150782 = EDGE_CURVE('',#150783,#150785,#150787,.T.); +#150783 = VERTEX_POINT('',#150784); +#150784 = CARTESIAN_POINT('',(2.15,10.419594812019,0.530776333563)); +#150785 = VERTEX_POINT('',#150786); +#150786 = CARTESIAN_POINT('',(2.35,10.419594812019,0.530776333563)); +#150787 = SURFACE_CURVE('',#150788,(#150792,#150799),.PCURVE_S1.); +#150788 = LINE('',#150789,#150790); +#150789 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#148398 = VECTOR('',#148399,1.); -#148399 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148400 = PCURVE('',#148177,#148401); -#148401 = DEFINITIONAL_REPRESENTATION('',(#148402),#148406); -#148402 = LINE('',#148403,#148404); -#148403 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148404 = VECTOR('',#148405,1.); -#148405 = DIRECTION('',(-1.,0.E+000)); -#148406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148407 = PCURVE('',#148408,#148413); -#148408 = CYLINDRICAL_SURFACE('',#148409,0.119270391569); -#148409 = AXIS2_PLACEMENT_3D('',#148410,#148411,#148412); -#148410 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#150790 = VECTOR('',#150791,1.); +#150791 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150792 = PCURVE('',#150569,#150793); +#150793 = DEFINITIONAL_REPRESENTATION('',(#150794),#150798); +#150794 = LINE('',#150795,#150796); +#150795 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#150796 = VECTOR('',#150797,1.); +#150797 = DIRECTION('',(-1.,0.E+000)); +#150798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150799 = PCURVE('',#150800,#150805); +#150800 = CYLINDRICAL_SURFACE('',#150801,0.119270391569); +#150801 = AXIS2_PLACEMENT_3D('',#150802,#150803,#150804); +#150802 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#148411 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148412 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148413 = DEFINITIONAL_REPRESENTATION('',(#148414),#148417); -#148414 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148415,#148416), +#150803 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150804 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150805 = DEFINITIONAL_REPRESENTATION('',(#150806),#150809); +#150806 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150807,#150808), .UNSPECIFIED.,.F.,.F.,(2,2),(2.15,2.35),.PIECEWISE_BEZIER_KNOTS.); -#148415 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#148416 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#148417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148418 = ORIENTED_EDGE('',*,*,#148419,.T.); -#148419 = EDGE_CURVE('',#148391,#148163,#148420,.T.); -#148420 = SURFACE_CURVE('',#148421,(#148425,#148432),.PCURVE_S1.); -#148421 = LINE('',#148422,#148423); -#148422 = CARTESIAN_POINT('',(2.15,10.419594812019,0.530776333563)); -#148423 = VECTOR('',#148424,1.); -#148424 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#148425 = PCURVE('',#148177,#148426); -#148426 = DEFINITIONAL_REPRESENTATION('',(#148427),#148431); -#148427 = LINE('',#148428,#148429); -#148428 = CARTESIAN_POINT('',(-2.15,0.E+000)); -#148429 = VECTOR('',#148430,1.); -#148430 = DIRECTION('',(0.E+000,-1.)); -#148431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148432 = PCURVE('',#88238,#148433); -#148433 = DEFINITIONAL_REPRESENTATION('',(#148434),#148438); -#148434 = LINE('',#148435,#148436); -#148435 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#148436 = VECTOR('',#148437,1.); -#148437 = DIRECTION('',(1.,0.E+000)); -#148438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148439 = ORIENTED_EDGE('',*,*,#148162,.T.); -#148440 = ORIENTED_EDGE('',*,*,#148441,.F.); -#148441 = EDGE_CURVE('',#148393,#148113,#148442,.T.); -#148442 = SURFACE_CURVE('',#148443,(#148447,#148454),.PCURVE_S1.); -#148443 = LINE('',#148444,#148445); -#148444 = CARTESIAN_POINT('',(2.35,10.419594812019,0.530776333563)); -#148445 = VECTOR('',#148446,1.); -#148446 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#148447 = PCURVE('',#148177,#148448); -#148448 = DEFINITIONAL_REPRESENTATION('',(#148449),#148453); -#148449 = LINE('',#148450,#148451); -#148450 = CARTESIAN_POINT('',(-2.35,0.E+000)); -#148451 = VECTOR('',#148452,1.); -#148452 = DIRECTION('',(0.E+000,-1.)); -#148453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148454 = PCURVE('',#88182,#148455); -#148455 = DEFINITIONAL_REPRESENTATION('',(#148456),#148460); -#148456 = LINE('',#148457,#148458); -#148457 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#148458 = VECTOR('',#148459,1.); -#148459 = DIRECTION('',(-1.,0.E+000)); -#148460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148461 = ADVANCED_FACE('',(#148462),#148333,.T.); -#148462 = FACE_BOUND('',#148463,.T.); -#148463 = EDGE_LOOP('',(#148464,#148487,#148488,#148515)); -#148464 = ORIENTED_EDGE('',*,*,#148465,.T.); -#148465 = EDGE_CURVE('',#148466,#148316,#148468,.T.); -#148466 = VERTEX_POINT('',#148467); -#148467 = CARTESIAN_POINT('',(2.35,10.304819755875,0.75)); -#148468 = SURFACE_CURVE('',#148469,(#148474,#148480),.PCURVE_S1.); -#148469 = CIRCLE('',#148470,0.2192697516); -#148470 = AXIS2_PLACEMENT_3D('',#148471,#148472,#148473); -#148471 = CARTESIAN_POINT('',(2.35,10.30032442045,0.530776333563)); -#148472 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148473 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148474 = PCURVE('',#148333,#148475); -#148475 = DEFINITIONAL_REPRESENTATION('',(#148476),#148479); -#148476 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148477,#148478), +#150807 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#150808 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#150809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150810 = ORIENTED_EDGE('',*,*,#150811,.T.); +#150811 = EDGE_CURVE('',#150783,#150555,#150812,.T.); +#150812 = SURFACE_CURVE('',#150813,(#150817,#150824),.PCURVE_S1.); +#150813 = LINE('',#150814,#150815); +#150814 = CARTESIAN_POINT('',(2.15,10.419594812019,0.530776333563)); +#150815 = VECTOR('',#150816,1.); +#150816 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#150817 = PCURVE('',#150569,#150818); +#150818 = DEFINITIONAL_REPRESENTATION('',(#150819),#150823); +#150819 = LINE('',#150820,#150821); +#150820 = CARTESIAN_POINT('',(-2.15,0.E+000)); +#150821 = VECTOR('',#150822,1.); +#150822 = DIRECTION('',(0.E+000,-1.)); +#150823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150824 = PCURVE('',#90630,#150825); +#150825 = DEFINITIONAL_REPRESENTATION('',(#150826),#150830); +#150826 = LINE('',#150827,#150828); +#150827 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#150828 = VECTOR('',#150829,1.); +#150829 = DIRECTION('',(1.,0.E+000)); +#150830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150831 = ORIENTED_EDGE('',*,*,#150554,.T.); +#150832 = ORIENTED_EDGE('',*,*,#150833,.F.); +#150833 = EDGE_CURVE('',#150785,#150505,#150834,.T.); +#150834 = SURFACE_CURVE('',#150835,(#150839,#150846),.PCURVE_S1.); +#150835 = LINE('',#150836,#150837); +#150836 = CARTESIAN_POINT('',(2.35,10.419594812019,0.530776333563)); +#150837 = VECTOR('',#150838,1.); +#150838 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#150839 = PCURVE('',#150569,#150840); +#150840 = DEFINITIONAL_REPRESENTATION('',(#150841),#150845); +#150841 = LINE('',#150842,#150843); +#150842 = CARTESIAN_POINT('',(-2.35,0.E+000)); +#150843 = VECTOR('',#150844,1.); +#150844 = DIRECTION('',(0.E+000,-1.)); +#150845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150846 = PCURVE('',#90574,#150847); +#150847 = DEFINITIONAL_REPRESENTATION('',(#150848),#150852); +#150848 = LINE('',#150849,#150850); +#150849 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#150850 = VECTOR('',#150851,1.); +#150851 = DIRECTION('',(-1.,0.E+000)); +#150852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150853 = ADVANCED_FACE('',(#150854),#150725,.T.); +#150854 = FACE_BOUND('',#150855,.T.); +#150855 = EDGE_LOOP('',(#150856,#150879,#150880,#150907)); +#150856 = ORIENTED_EDGE('',*,*,#150857,.T.); +#150857 = EDGE_CURVE('',#150858,#150708,#150860,.T.); +#150858 = VERTEX_POINT('',#150859); +#150859 = CARTESIAN_POINT('',(2.35,10.304819755875,0.75)); +#150860 = SURFACE_CURVE('',#150861,(#150866,#150872),.PCURVE_S1.); +#150861 = CIRCLE('',#150862,0.2192697516); +#150862 = AXIS2_PLACEMENT_3D('',#150863,#150864,#150865); +#150863 = CARTESIAN_POINT('',(2.35,10.30032442045,0.530776333563)); +#150864 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150865 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150866 = PCURVE('',#150725,#150867); +#150867 = DEFINITIONAL_REPRESENTATION('',(#150868),#150871); +#150868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150869,#150870), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#148477 = CARTESIAN_POINT('',(1.591299156552,-2.35)); -#148478 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#148479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148480 = PCURVE('',#88182,#148481); -#148481 = DEFINITIONAL_REPRESENTATION('',(#148482),#148486); -#148482 = CIRCLE('',#148483,0.2192697516); -#148483 = AXIS2_PLACEMENT_2D('',#148484,#148485); -#148484 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#148485 = DIRECTION('',(0.E+000,-1.)); -#148486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148487 = ORIENTED_EDGE('',*,*,#148315,.T.); -#148488 = ORIENTED_EDGE('',*,*,#148489,.F.); -#148489 = EDGE_CURVE('',#148490,#148318,#148492,.T.); -#148490 = VERTEX_POINT('',#148491); -#148491 = CARTESIAN_POINT('',(2.15,10.304819755875,0.75)); -#148492 = SURFACE_CURVE('',#148493,(#148498,#148504),.PCURVE_S1.); -#148493 = CIRCLE('',#148494,0.2192697516); -#148494 = AXIS2_PLACEMENT_3D('',#148495,#148496,#148497); -#148495 = CARTESIAN_POINT('',(2.15,10.30032442045,0.530776333563)); -#148496 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148497 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148498 = PCURVE('',#148333,#148499); -#148499 = DEFINITIONAL_REPRESENTATION('',(#148500),#148503); -#148500 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148501,#148502), +#150869 = CARTESIAN_POINT('',(1.591299156552,-2.35)); +#150870 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#150871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150872 = PCURVE('',#90574,#150873); +#150873 = DEFINITIONAL_REPRESENTATION('',(#150874),#150878); +#150874 = CIRCLE('',#150875,0.2192697516); +#150875 = AXIS2_PLACEMENT_2D('',#150876,#150877); +#150876 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#150877 = DIRECTION('',(0.E+000,-1.)); +#150878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150879 = ORIENTED_EDGE('',*,*,#150707,.T.); +#150880 = ORIENTED_EDGE('',*,*,#150881,.F.); +#150881 = EDGE_CURVE('',#150882,#150710,#150884,.T.); +#150882 = VERTEX_POINT('',#150883); +#150883 = CARTESIAN_POINT('',(2.15,10.304819755875,0.75)); +#150884 = SURFACE_CURVE('',#150885,(#150890,#150896),.PCURVE_S1.); +#150885 = CIRCLE('',#150886,0.2192697516); +#150886 = AXIS2_PLACEMENT_3D('',#150887,#150888,#150889); +#150887 = CARTESIAN_POINT('',(2.15,10.30032442045,0.530776333563)); +#150888 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150889 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150890 = PCURVE('',#150725,#150891); +#150891 = DEFINITIONAL_REPRESENTATION('',(#150892),#150895); +#150892 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150893,#150894), .UNSPECIFIED.,.F.,.F.,(2,2),(1.591299156552,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#148501 = CARTESIAN_POINT('',(1.591299156552,-2.15)); -#148502 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#148503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150893 = CARTESIAN_POINT('',(1.591299156552,-2.15)); +#150894 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#150895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148504 = PCURVE('',#88238,#148505); -#148505 = DEFINITIONAL_REPRESENTATION('',(#148506),#148514); -#148506 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148507,#148508,#148509, - #148510,#148511,#148512,#148513),.UNSPECIFIED.,.T.,.F.) +#150896 = PCURVE('',#90630,#150897); +#150897 = DEFINITIONAL_REPRESENTATION('',(#150898),#150906); +#150898 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150899,#150900,#150901, + #150902,#150903,#150904,#150905),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#148507 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#148508 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#148509 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#148510 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#148511 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#148512 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#148513 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#148514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148515 = ORIENTED_EDGE('',*,*,#148516,.T.); -#148516 = EDGE_CURVE('',#148490,#148466,#148517,.T.); -#148517 = SURFACE_CURVE('',#148518,(#148522,#148528),.PCURVE_S1.); -#148518 = LINE('',#148519,#148520); -#148519 = CARTESIAN_POINT('',(2.35,10.304819755875,0.75)); -#148520 = VECTOR('',#148521,1.); -#148521 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148522 = PCURVE('',#148333,#148523); -#148523 = DEFINITIONAL_REPRESENTATION('',(#148524),#148527); -#148524 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148525,#148526), +#150899 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#150900 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#150901 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#150902 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#150903 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#150904 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#150905 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#150906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150907 = ORIENTED_EDGE('',*,*,#150908,.T.); +#150908 = EDGE_CURVE('',#150882,#150858,#150909,.T.); +#150909 = SURFACE_CURVE('',#150910,(#150914,#150920),.PCURVE_S1.); +#150910 = LINE('',#150911,#150912); +#150911 = CARTESIAN_POINT('',(2.35,10.304819755875,0.75)); +#150912 = VECTOR('',#150913,1.); +#150913 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#150914 = PCURVE('',#150725,#150915); +#150915 = DEFINITIONAL_REPRESENTATION('',(#150916),#150919); +#150916 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150917,#150918), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,0.E+000),.PIECEWISE_BEZIER_KNOTS.); -#148525 = CARTESIAN_POINT('',(1.591299156552,-2.15)); -#148526 = CARTESIAN_POINT('',(1.591299156552,-2.35)); -#148527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148528 = PCURVE('',#88210,#148529); -#148529 = DEFINITIONAL_REPRESENTATION('',(#148530),#148534); -#148530 = LINE('',#148531,#148532); -#148531 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); -#148532 = VECTOR('',#148533,1.); -#148533 = DIRECTION('',(-8.881784197001E-016,1.)); -#148534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148535 = ADVANCED_FACE('',(#148536),#148408,.F.); -#148536 = FACE_BOUND('',#148537,.F.); -#148537 = EDGE_LOOP('',(#148538,#148565,#148587,#148608)); -#148538 = ORIENTED_EDGE('',*,*,#148539,.F.); -#148539 = EDGE_CURVE('',#148540,#148391,#148542,.T.); -#148540 = VERTEX_POINT('',#148541); -#148541 = CARTESIAN_POINT('',(2.15,10.303662633502,0.65)); -#148542 = SURFACE_CURVE('',#148543,(#148548,#148554),.PCURVE_S1.); -#148543 = CIRCLE('',#148544,0.119270391569); -#148544 = AXIS2_PLACEMENT_3D('',#148545,#148546,#148547); -#148545 = CARTESIAN_POINT('',(2.15,10.30032442045,0.530776333563)); -#148546 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148547 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148548 = PCURVE('',#148408,#148549); -#148549 = DEFINITIONAL_REPRESENTATION('',(#148550),#148553); -#148550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148551,#148552), +#150917 = CARTESIAN_POINT('',(1.591299156552,-2.15)); +#150918 = CARTESIAN_POINT('',(1.591299156552,-2.35)); +#150919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150920 = PCURVE('',#90602,#150921); +#150921 = DEFINITIONAL_REPRESENTATION('',(#150922),#150926); +#150922 = LINE('',#150923,#150924); +#150923 = CARTESIAN_POINT('',(-0.223028236564,-9.983903138494E-048)); +#150924 = VECTOR('',#150925,1.); +#150925 = DIRECTION('',(-8.881784197001E-016,1.)); +#150926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150927 = ADVANCED_FACE('',(#150928),#150800,.F.); +#150928 = FACE_BOUND('',#150929,.F.); +#150929 = EDGE_LOOP('',(#150930,#150957,#150979,#151000)); +#150930 = ORIENTED_EDGE('',*,*,#150931,.F.); +#150931 = EDGE_CURVE('',#150932,#150783,#150934,.T.); +#150932 = VERTEX_POINT('',#150933); +#150933 = CARTESIAN_POINT('',(2.15,10.303662633502,0.65)); +#150934 = SURFACE_CURVE('',#150935,(#150940,#150946),.PCURVE_S1.); +#150935 = CIRCLE('',#150936,0.119270391569); +#150936 = AXIS2_PLACEMENT_3D('',#150937,#150938,#150939); +#150937 = CARTESIAN_POINT('',(2.15,10.30032442045,0.530776333563)); +#150938 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150939 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150940 = PCURVE('',#150800,#150941); +#150941 = DEFINITIONAL_REPRESENTATION('',(#150942),#150945); +#150942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150943,#150944), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#148551 = CARTESIAN_POINT('',(1.598788597134,-2.15)); -#148552 = CARTESIAN_POINT('',(3.14159265359,-2.15)); -#148553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150943 = CARTESIAN_POINT('',(1.598788597134,-2.15)); +#150944 = CARTESIAN_POINT('',(3.14159265359,-2.15)); +#150945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148554 = PCURVE('',#88238,#148555); -#148555 = DEFINITIONAL_REPRESENTATION('',(#148556),#148564); -#148556 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#148557,#148558,#148559, - #148560,#148561,#148562,#148563),.UNSPECIFIED.,.T.,.F.) +#150946 = PCURVE('',#90630,#150947); +#150947 = DEFINITIONAL_REPRESENTATION('',(#150948),#150956); +#150948 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150949,#150950,#150951, + #150952,#150953,#150954,#150955),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#148557 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#148558 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#148559 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#148560 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#148561 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#148562 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#148563 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#148564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148565 = ORIENTED_EDGE('',*,*,#148566,.F.); -#148566 = EDGE_CURVE('',#148567,#148540,#148569,.T.); -#148567 = VERTEX_POINT('',#148568); -#148568 = CARTESIAN_POINT('',(2.35,10.303662633502,0.65)); -#148569 = SURFACE_CURVE('',#148570,(#148574,#148580),.PCURVE_S1.); -#148570 = LINE('',#148571,#148572); -#148571 = CARTESIAN_POINT('',(2.35,10.303662633502,0.65)); -#148572 = VECTOR('',#148573,1.); -#148573 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148574 = PCURVE('',#148408,#148575); -#148575 = DEFINITIONAL_REPRESENTATION('',(#148576),#148579); -#148576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148577,#148578), +#150949 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#150950 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#150951 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#150952 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#150953 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#150954 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#150955 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#150956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150957 = ORIENTED_EDGE('',*,*,#150958,.F.); +#150958 = EDGE_CURVE('',#150959,#150932,#150961,.T.); +#150959 = VERTEX_POINT('',#150960); +#150960 = CARTESIAN_POINT('',(2.35,10.303662633502,0.65)); +#150961 = SURFACE_CURVE('',#150962,(#150966,#150972),.PCURVE_S1.); +#150962 = LINE('',#150963,#150964); +#150963 = CARTESIAN_POINT('',(2.35,10.303662633502,0.65)); +#150964 = VECTOR('',#150965,1.); +#150965 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150966 = PCURVE('',#150800,#150967); +#150967 = DEFINITIONAL_REPRESENTATION('',(#150968),#150971); +#150968 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150969,#150970), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#148577 = CARTESIAN_POINT('',(1.598788597134,-2.35)); -#148578 = CARTESIAN_POINT('',(1.598788597134,-2.15)); -#148579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148580 = PCURVE('',#88264,#148581); -#148581 = DEFINITIONAL_REPRESENTATION('',(#148582),#148586); -#148582 = LINE('',#148583,#148584); -#148583 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); -#148584 = VECTOR('',#148585,1.); -#148585 = DIRECTION('',(-8.881784197001E-016,-1.)); -#148586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148587 = ORIENTED_EDGE('',*,*,#148588,.T.); -#148588 = EDGE_CURVE('',#148567,#148393,#148589,.T.); -#148589 = SURFACE_CURVE('',#148590,(#148595,#148601),.PCURVE_S1.); -#148590 = CIRCLE('',#148591,0.119270391569); -#148591 = AXIS2_PLACEMENT_3D('',#148592,#148593,#148594); -#148592 = CARTESIAN_POINT('',(2.35,10.30032442045,0.530776333563)); -#148593 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148594 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#148595 = PCURVE('',#148408,#148596); -#148596 = DEFINITIONAL_REPRESENTATION('',(#148597),#148600); -#148597 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148598,#148599), +#150969 = CARTESIAN_POINT('',(1.598788597134,-2.35)); +#150970 = CARTESIAN_POINT('',(1.598788597134,-2.15)); +#150971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150972 = PCURVE('',#90656,#150973); +#150973 = DEFINITIONAL_REPRESENTATION('',(#150974),#150978); +#150974 = LINE('',#150975,#150976); +#150975 = CARTESIAN_POINT('',(0.224185358936,-9.853387059448E-048)); +#150976 = VECTOR('',#150977,1.); +#150977 = DIRECTION('',(-8.881784197001E-016,-1.)); +#150978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150979 = ORIENTED_EDGE('',*,*,#150980,.T.); +#150980 = EDGE_CURVE('',#150959,#150785,#150981,.T.); +#150981 = SURFACE_CURVE('',#150982,(#150987,#150993),.PCURVE_S1.); +#150982 = CIRCLE('',#150983,0.119270391569); +#150983 = AXIS2_PLACEMENT_3D('',#150984,#150985,#150986); +#150984 = CARTESIAN_POINT('',(2.35,10.30032442045,0.530776333563)); +#150985 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#150986 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#150987 = PCURVE('',#150800,#150988); +#150988 = DEFINITIONAL_REPRESENTATION('',(#150989),#150992); +#150989 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150990,#150991), .UNSPECIFIED.,.F.,.F.,(2,2),(1.598788597134,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#148598 = CARTESIAN_POINT('',(1.598788597134,-2.35)); -#148599 = CARTESIAN_POINT('',(3.14159265359,-2.35)); -#148600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148601 = PCURVE('',#88182,#148602); -#148602 = DEFINITIONAL_REPRESENTATION('',(#148603),#148607); -#148603 = CIRCLE('',#148604,0.119270391569); -#148604 = AXIS2_PLACEMENT_2D('',#148605,#148606); -#148605 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#148606 = DIRECTION('',(0.E+000,-1.)); -#148607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148608 = ORIENTED_EDGE('',*,*,#148390,.F.); -#148609 = ADVANCED_FACE('',(#148610),#88182,.F.); -#148610 = FACE_BOUND('',#148611,.T.); -#148611 = EDGE_LOOP('',(#148612,#148633,#148634,#148635,#148636,#148637, - #148658,#148659,#148660,#148661,#148662,#148683)); -#148612 = ORIENTED_EDGE('',*,*,#148613,.F.); -#148613 = EDGE_CURVE('',#148567,#88167,#148614,.T.); -#148614 = SURFACE_CURVE('',#148615,(#148619,#148626),.PCURVE_S1.); -#148615 = LINE('',#148616,#148617); -#148616 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); -#148617 = VECTOR('',#148618,1.); -#148618 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#148619 = PCURVE('',#88182,#148620); -#148620 = DEFINITIONAL_REPRESENTATION('',(#148621),#148625); -#148621 = LINE('',#148622,#148623); -#148622 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148623 = VECTOR('',#148624,1.); -#148624 = DIRECTION('',(3.563627120235E-016,-1.)); -#148625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148626 = PCURVE('',#88264,#148627); -#148627 = DEFINITIONAL_REPRESENTATION('',(#148628),#148632); -#148628 = LINE('',#148629,#148630); -#148629 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148630 = VECTOR('',#148631,1.); -#148631 = DIRECTION('',(1.,2.164989446033E-063)); -#148632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148633 = ORIENTED_EDGE('',*,*,#148588,.T.); -#148634 = ORIENTED_EDGE('',*,*,#148441,.T.); -#148635 = ORIENTED_EDGE('',*,*,#148112,.T.); -#148636 = ORIENTED_EDGE('',*,*,#147956,.T.); -#148637 = ORIENTED_EDGE('',*,*,#148638,.T.); -#148638 = EDGE_CURVE('',#147929,#148010,#148639,.T.); -#148639 = SURFACE_CURVE('',#148640,(#148644,#148651),.PCURVE_S1.); -#148640 = LINE('',#148641,#148642); -#148641 = CARTESIAN_POINT('',(2.35,11.,1.159810404338E-002)); -#148642 = VECTOR('',#148643,1.); -#148643 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#148644 = PCURVE('',#88182,#148645); -#148645 = DEFINITIONAL_REPRESENTATION('',(#148646),#148650); -#148646 = LINE('',#148647,#148648); -#148647 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#148648 = VECTOR('',#148649,1.); -#148649 = DIRECTION('',(1.,2.101748079665E-016)); -#148650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148651 = PCURVE('',#147944,#148652); -#148652 = DEFINITIONAL_REPRESENTATION('',(#148653),#148657); -#148653 = LINE('',#148654,#148655); -#148654 = CARTESIAN_POINT('',(-0.1,0.269794846371)); -#148655 = VECTOR('',#148656,1.); -#148656 = DIRECTION('',(-1.570395187386E-016,1.)); -#148657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148658 = ORIENTED_EDGE('',*,*,#148007,.F.); -#148659 = ORIENTED_EDGE('',*,*,#148237,.F.); -#148660 = ORIENTED_EDGE('',*,*,#148344,.F.); -#148661 = ORIENTED_EDGE('',*,*,#148465,.F.); -#148662 = ORIENTED_EDGE('',*,*,#148663,.T.); -#148663 = EDGE_CURVE('',#148466,#88165,#148664,.T.); -#148664 = SURFACE_CURVE('',#148665,(#148669,#148676),.PCURVE_S1.); -#148665 = LINE('',#148666,#148667); -#148666 = CARTESIAN_POINT('',(2.35,10.527847992439,0.75)); -#148667 = VECTOR('',#148668,1.); -#148668 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#148669 = PCURVE('',#88182,#148670); -#148670 = DEFINITIONAL_REPRESENTATION('',(#148671),#148675); -#148671 = LINE('',#148672,#148673); -#148672 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#148673 = VECTOR('',#148674,1.); -#148674 = DIRECTION('',(3.563627120235E-016,-1.)); -#148675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148676 = PCURVE('',#88210,#148677); -#148677 = DEFINITIONAL_REPRESENTATION('',(#148678),#148682); -#148678 = LINE('',#148679,#148680); -#148679 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148680 = VECTOR('',#148681,1.); -#148681 = DIRECTION('',(-1.,2.164989446033E-063)); -#148682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148683 = ORIENTED_EDGE('',*,*,#88164,.T.); -#148684 = ADVANCED_FACE('',(#148685),#88210,.F.); -#148685 = FACE_BOUND('',#148686,.T.); -#148686 = EDGE_LOOP('',(#148687,#148688,#148709,#148710)); -#148687 = ORIENTED_EDGE('',*,*,#148516,.F.); -#148688 = ORIENTED_EDGE('',*,*,#148689,.T.); -#148689 = EDGE_CURVE('',#148490,#88195,#148690,.T.); -#148690 = SURFACE_CURVE('',#148691,(#148695,#148702),.PCURVE_S1.); -#148691 = LINE('',#148692,#148693); -#148692 = CARTESIAN_POINT('',(2.15,10.527847992439,0.75)); -#148693 = VECTOR('',#148694,1.); -#148694 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#148695 = PCURVE('',#88210,#148696); -#148696 = DEFINITIONAL_REPRESENTATION('',(#148697),#148701); -#148697 = LINE('',#148698,#148699); -#148698 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#148699 = VECTOR('',#148700,1.); -#148700 = DIRECTION('',(-1.,2.164989446033E-063)); -#148701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#150990 = CARTESIAN_POINT('',(1.598788597134,-2.35)); +#150991 = CARTESIAN_POINT('',(3.14159265359,-2.35)); +#150992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#150993 = PCURVE('',#90574,#150994); +#150994 = DEFINITIONAL_REPRESENTATION('',(#150995),#150999); +#150995 = CIRCLE('',#150996,0.119270391569); +#150996 = AXIS2_PLACEMENT_2D('',#150997,#150998); +#150997 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#150998 = DIRECTION('',(0.E+000,-1.)); +#150999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151000 = ORIENTED_EDGE('',*,*,#150782,.F.); +#151001 = ADVANCED_FACE('',(#151002),#90574,.F.); +#151002 = FACE_BOUND('',#151003,.T.); +#151003 = EDGE_LOOP('',(#151004,#151025,#151026,#151027,#151028,#151029, + #151050,#151051,#151052,#151053,#151054,#151075)); +#151004 = ORIENTED_EDGE('',*,*,#151005,.F.); +#151005 = EDGE_CURVE('',#150959,#90559,#151006,.T.); +#151006 = SURFACE_CURVE('',#151007,(#151011,#151018),.PCURVE_S1.); +#151007 = LINE('',#151008,#151009); +#151008 = CARTESIAN_POINT('',(2.35,10.527847992439,0.65)); +#151009 = VECTOR('',#151010,1.); +#151010 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#151011 = PCURVE('',#90574,#151012); +#151012 = DEFINITIONAL_REPRESENTATION('',(#151013),#151017); +#151013 = LINE('',#151014,#151015); +#151014 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151015 = VECTOR('',#151016,1.); +#151016 = DIRECTION('',(3.563627120235E-016,-1.)); +#151017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151018 = PCURVE('',#90656,#151019); +#151019 = DEFINITIONAL_REPRESENTATION('',(#151020),#151024); +#151020 = LINE('',#151021,#151022); +#151021 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151022 = VECTOR('',#151023,1.); +#151023 = DIRECTION('',(1.,2.164989446033E-063)); +#151024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151025 = ORIENTED_EDGE('',*,*,#150980,.T.); +#151026 = ORIENTED_EDGE('',*,*,#150833,.T.); +#151027 = ORIENTED_EDGE('',*,*,#150504,.T.); +#151028 = ORIENTED_EDGE('',*,*,#150348,.T.); +#151029 = ORIENTED_EDGE('',*,*,#151030,.T.); +#151030 = EDGE_CURVE('',#150321,#150402,#151031,.T.); +#151031 = SURFACE_CURVE('',#151032,(#151036,#151043),.PCURVE_S1.); +#151032 = LINE('',#151033,#151034); +#151033 = CARTESIAN_POINT('',(2.35,11.,1.159810404338E-002)); +#151034 = VECTOR('',#151035,1.); +#151035 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#151036 = PCURVE('',#90574,#151037); +#151037 = DEFINITIONAL_REPRESENTATION('',(#151038),#151042); +#151038 = LINE('',#151039,#151040); +#151039 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#151040 = VECTOR('',#151041,1.); +#151041 = DIRECTION('',(1.,2.101748079665E-016)); +#151042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151043 = PCURVE('',#150336,#151044); +#151044 = DEFINITIONAL_REPRESENTATION('',(#151045),#151049); +#151045 = LINE('',#151046,#151047); +#151046 = CARTESIAN_POINT('',(-0.1,0.269794846371)); +#151047 = VECTOR('',#151048,1.); +#151048 = DIRECTION('',(-1.570395187386E-016,1.)); +#151049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#148702 = PCURVE('',#88238,#148703); -#148703 = DEFINITIONAL_REPRESENTATION('',(#148704),#148708); -#148704 = LINE('',#148705,#148706); -#148705 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#148706 = VECTOR('',#148707,1.); -#148707 = DIRECTION('',(-3.563627120235E-016,-1.)); -#148708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148709 = ORIENTED_EDGE('',*,*,#88194,.T.); -#148710 = ORIENTED_EDGE('',*,*,#148663,.F.); -#148711 = ADVANCED_FACE('',(#148712),#88238,.F.); -#148712 = FACE_BOUND('',#148713,.T.); -#148713 = EDGE_LOOP('',(#148714,#148715,#148716,#148717,#148718,#148719, - #148740,#148741,#148742,#148743,#148744,#148765)); -#148714 = ORIENTED_EDGE('',*,*,#148689,.F.); -#148715 = ORIENTED_EDGE('',*,*,#148489,.T.); -#148716 = ORIENTED_EDGE('',*,*,#148366,.T.); -#148717 = ORIENTED_EDGE('',*,*,#148291,.T.); -#148718 = ORIENTED_EDGE('',*,*,#148060,.T.); -#148719 = ORIENTED_EDGE('',*,*,#148720,.T.); -#148720 = EDGE_CURVE('',#148038,#147901,#148721,.T.); -#148721 = SURFACE_CURVE('',#148722,(#148726,#148733),.PCURVE_S1.); -#148722 = LINE('',#148723,#148724); -#148723 = CARTESIAN_POINT('',(2.15,11.,1.159810404338E-002)); -#148724 = VECTOR('',#148725,1.); -#148725 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#148726 = PCURVE('',#88238,#148727); -#148727 = DEFINITIONAL_REPRESENTATION('',(#148728),#148732); -#148728 = LINE('',#148729,#148730); -#148729 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#148730 = VECTOR('',#148731,1.); -#148731 = DIRECTION('',(1.,-2.101748079665E-016)); -#148732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148733 = PCURVE('',#147944,#148734); -#148734 = DEFINITIONAL_REPRESENTATION('',(#148735),#148739); -#148735 = LINE('',#148736,#148737); -#148736 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#148737 = VECTOR('',#148738,1.); -#148738 = DIRECTION('',(1.570395187386E-016,-1.)); -#148739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148740 = ORIENTED_EDGE('',*,*,#147898,.F.); -#148741 = ORIENTED_EDGE('',*,*,#148189,.F.); -#148742 = ORIENTED_EDGE('',*,*,#148419,.F.); -#148743 = ORIENTED_EDGE('',*,*,#148539,.F.); -#148744 = ORIENTED_EDGE('',*,*,#148745,.T.); -#148745 = EDGE_CURVE('',#148540,#88223,#148746,.T.); -#148746 = SURFACE_CURVE('',#148747,(#148751,#148758),.PCURVE_S1.); -#148747 = LINE('',#148748,#148749); -#148748 = CARTESIAN_POINT('',(2.15,10.527847992439,0.65)); -#148749 = VECTOR('',#148750,1.); -#148750 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#148751 = PCURVE('',#88238,#148752); -#148752 = DEFINITIONAL_REPRESENTATION('',(#148753),#148757); -#148753 = LINE('',#148754,#148755); -#148754 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148755 = VECTOR('',#148756,1.); -#148756 = DIRECTION('',(-3.563627120235E-016,-1.)); -#148757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148758 = PCURVE('',#88264,#148759); -#148759 = DEFINITIONAL_REPRESENTATION('',(#148760),#148764); -#148760 = LINE('',#148761,#148762); -#148761 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#148762 = VECTOR('',#148763,1.); -#148763 = DIRECTION('',(1.,2.164989446033E-063)); -#148764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148765 = ORIENTED_EDGE('',*,*,#88222,.T.); -#148766 = ADVANCED_FACE('',(#148767),#88264,.F.); -#148767 = FACE_BOUND('',#148768,.T.); -#148768 = EDGE_LOOP('',(#148769,#148770,#148771,#148772)); -#148769 = ORIENTED_EDGE('',*,*,#148566,.F.); -#148770 = ORIENTED_EDGE('',*,*,#148613,.T.); -#148771 = ORIENTED_EDGE('',*,*,#88250,.T.); -#148772 = ORIENTED_EDGE('',*,*,#148745,.F.); -#148773 = ADVANCED_FACE('',(#148774),#147944,.T.); -#148774 = FACE_BOUND('',#148775,.T.); -#148775 = EDGE_LOOP('',(#148776,#148777,#148778,#148779)); -#148776 = ORIENTED_EDGE('',*,*,#148720,.F.); -#148777 = ORIENTED_EDGE('',*,*,#148037,.F.); -#148778 = ORIENTED_EDGE('',*,*,#148638,.F.); -#148779 = ORIENTED_EDGE('',*,*,#147928,.F.); -#148780 = ADVANCED_FACE('',(#148781),#148795,.T.); -#148781 = FACE_BOUND('',#148782,.T.); -#148782 = EDGE_LOOP('',(#148783,#148813,#148841,#148864)); -#148783 = ORIENTED_EDGE('',*,*,#148784,.T.); -#148784 = EDGE_CURVE('',#148785,#148787,#148789,.T.); -#148785 = VERTEX_POINT('',#148786); -#148786 = CARTESIAN_POINT('',(1.65,10.74341632541,-0.308197125857)); -#148787 = VERTEX_POINT('',#148788); -#148788 = CARTESIAN_POINT('',(1.65,11.,-0.308197125857)); -#148789 = SURFACE_CURVE('',#148790,(#148794,#148806),.PCURVE_S1.); -#148790 = LINE('',#148791,#148792); -#148791 = CARTESIAN_POINT('',(1.65,10.74341632541,-0.308197125857)); -#148792 = VECTOR('',#148793,1.); -#148793 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148794 = PCURVE('',#148795,#148800); -#148795 = PLANE('',#148796); -#148796 = AXIS2_PLACEMENT_3D('',#148797,#148798,#148799); -#148797 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#151050 = ORIENTED_EDGE('',*,*,#150399,.F.); +#151051 = ORIENTED_EDGE('',*,*,#150629,.F.); +#151052 = ORIENTED_EDGE('',*,*,#150736,.F.); +#151053 = ORIENTED_EDGE('',*,*,#150857,.F.); +#151054 = ORIENTED_EDGE('',*,*,#151055,.T.); +#151055 = EDGE_CURVE('',#150858,#90557,#151056,.T.); +#151056 = SURFACE_CURVE('',#151057,(#151061,#151068),.PCURVE_S1.); +#151057 = LINE('',#151058,#151059); +#151058 = CARTESIAN_POINT('',(2.35,10.527847992439,0.75)); +#151059 = VECTOR('',#151060,1.); +#151060 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#151061 = PCURVE('',#90574,#151062); +#151062 = DEFINITIONAL_REPRESENTATION('',(#151063),#151067); +#151063 = LINE('',#151064,#151065); +#151064 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#151065 = VECTOR('',#151066,1.); +#151066 = DIRECTION('',(3.563627120235E-016,-1.)); +#151067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151068 = PCURVE('',#90602,#151069); +#151069 = DEFINITIONAL_REPRESENTATION('',(#151070),#151074); +#151070 = LINE('',#151071,#151072); +#151071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151072 = VECTOR('',#151073,1.); +#151073 = DIRECTION('',(-1.,2.164989446033E-063)); +#151074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151075 = ORIENTED_EDGE('',*,*,#90556,.T.); +#151076 = ADVANCED_FACE('',(#151077),#90602,.F.); +#151077 = FACE_BOUND('',#151078,.T.); +#151078 = EDGE_LOOP('',(#151079,#151080,#151101,#151102)); +#151079 = ORIENTED_EDGE('',*,*,#150908,.F.); +#151080 = ORIENTED_EDGE('',*,*,#151081,.T.); +#151081 = EDGE_CURVE('',#150882,#90587,#151082,.T.); +#151082 = SURFACE_CURVE('',#151083,(#151087,#151094),.PCURVE_S1.); +#151083 = LINE('',#151084,#151085); +#151084 = CARTESIAN_POINT('',(2.15,10.527847992439,0.75)); +#151085 = VECTOR('',#151086,1.); +#151086 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#151087 = PCURVE('',#90602,#151088); +#151088 = DEFINITIONAL_REPRESENTATION('',(#151089),#151093); +#151089 = LINE('',#151090,#151091); +#151090 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#151091 = VECTOR('',#151092,1.); +#151092 = DIRECTION('',(-1.,2.164989446033E-063)); +#151093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151094 = PCURVE('',#90630,#151095); +#151095 = DEFINITIONAL_REPRESENTATION('',(#151096),#151100); +#151096 = LINE('',#151097,#151098); +#151097 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#151098 = VECTOR('',#151099,1.); +#151099 = DIRECTION('',(-3.563627120235E-016,-1.)); +#151100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151101 = ORIENTED_EDGE('',*,*,#90586,.T.); +#151102 = ORIENTED_EDGE('',*,*,#151055,.F.); +#151103 = ADVANCED_FACE('',(#151104),#90630,.F.); +#151104 = FACE_BOUND('',#151105,.T.); +#151105 = EDGE_LOOP('',(#151106,#151107,#151108,#151109,#151110,#151111, + #151132,#151133,#151134,#151135,#151136,#151157)); +#151106 = ORIENTED_EDGE('',*,*,#151081,.F.); +#151107 = ORIENTED_EDGE('',*,*,#150881,.T.); +#151108 = ORIENTED_EDGE('',*,*,#150758,.T.); +#151109 = ORIENTED_EDGE('',*,*,#150683,.T.); +#151110 = ORIENTED_EDGE('',*,*,#150452,.T.); +#151111 = ORIENTED_EDGE('',*,*,#151112,.T.); +#151112 = EDGE_CURVE('',#150430,#150293,#151113,.T.); +#151113 = SURFACE_CURVE('',#151114,(#151118,#151125),.PCURVE_S1.); +#151114 = LINE('',#151115,#151116); +#151115 = CARTESIAN_POINT('',(2.15,11.,1.159810404338E-002)); +#151116 = VECTOR('',#151117,1.); +#151117 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#151118 = PCURVE('',#90630,#151119); +#151119 = DEFINITIONAL_REPRESENTATION('',(#151120),#151124); +#151120 = LINE('',#151121,#151122); +#151121 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#151122 = VECTOR('',#151123,1.); +#151123 = DIRECTION('',(1.,-2.101748079665E-016)); +#151124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151125 = PCURVE('',#150336,#151126); +#151126 = DEFINITIONAL_REPRESENTATION('',(#151127),#151131); +#151127 = LINE('',#151128,#151129); +#151128 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#151129 = VECTOR('',#151130,1.); +#151130 = DIRECTION('',(1.570395187386E-016,-1.)); +#151131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151132 = ORIENTED_EDGE('',*,*,#150290,.F.); +#151133 = ORIENTED_EDGE('',*,*,#150581,.F.); +#151134 = ORIENTED_EDGE('',*,*,#150811,.F.); +#151135 = ORIENTED_EDGE('',*,*,#150931,.F.); +#151136 = ORIENTED_EDGE('',*,*,#151137,.T.); +#151137 = EDGE_CURVE('',#150932,#90615,#151138,.T.); +#151138 = SURFACE_CURVE('',#151139,(#151143,#151150),.PCURVE_S1.); +#151139 = LINE('',#151140,#151141); +#151140 = CARTESIAN_POINT('',(2.15,10.527847992439,0.65)); +#151141 = VECTOR('',#151142,1.); +#151142 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#151143 = PCURVE('',#90630,#151144); +#151144 = DEFINITIONAL_REPRESENTATION('',(#151145),#151149); +#151145 = LINE('',#151146,#151147); +#151146 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151147 = VECTOR('',#151148,1.); +#151148 = DIRECTION('',(-3.563627120235E-016,-1.)); +#151149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151150 = PCURVE('',#90656,#151151); +#151151 = DEFINITIONAL_REPRESENTATION('',(#151152),#151156); +#151152 = LINE('',#151153,#151154); +#151153 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#151154 = VECTOR('',#151155,1.); +#151155 = DIRECTION('',(1.,2.164989446033E-063)); +#151156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151157 = ORIENTED_EDGE('',*,*,#90614,.T.); +#151158 = ADVANCED_FACE('',(#151159),#90656,.F.); +#151159 = FACE_BOUND('',#151160,.T.); +#151160 = EDGE_LOOP('',(#151161,#151162,#151163,#151164)); +#151161 = ORIENTED_EDGE('',*,*,#150958,.F.); +#151162 = ORIENTED_EDGE('',*,*,#151005,.T.); +#151163 = ORIENTED_EDGE('',*,*,#90642,.T.); +#151164 = ORIENTED_EDGE('',*,*,#151137,.F.); +#151165 = ADVANCED_FACE('',(#151166),#150336,.T.); +#151166 = FACE_BOUND('',#151167,.T.); +#151167 = EDGE_LOOP('',(#151168,#151169,#151170,#151171)); +#151168 = ORIENTED_EDGE('',*,*,#151112,.F.); +#151169 = ORIENTED_EDGE('',*,*,#150429,.F.); +#151170 = ORIENTED_EDGE('',*,*,#151030,.F.); +#151171 = ORIENTED_EDGE('',*,*,#150320,.F.); +#151172 = ADVANCED_FACE('',(#151173),#151187,.T.); +#151173 = FACE_BOUND('',#151174,.T.); +#151174 = EDGE_LOOP('',(#151175,#151205,#151233,#151256)); +#151175 = ORIENTED_EDGE('',*,*,#151176,.T.); +#151176 = EDGE_CURVE('',#151177,#151179,#151181,.T.); +#151177 = VERTEX_POINT('',#151178); +#151178 = CARTESIAN_POINT('',(1.65,10.74341632541,-0.308197125857)); +#151179 = VERTEX_POINT('',#151180); +#151180 = CARTESIAN_POINT('',(1.65,11.,-0.308197125857)); +#151181 = SURFACE_CURVE('',#151182,(#151186,#151198),.PCURVE_S1.); +#151182 = LINE('',#151183,#151184); +#151183 = CARTESIAN_POINT('',(1.65,10.74341632541,-0.308197125857)); +#151184 = VECTOR('',#151185,1.); +#151185 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#151186 = PCURVE('',#151187,#151192); +#151187 = PLANE('',#151188); +#151188 = AXIS2_PLACEMENT_3D('',#151189,#151190,#151191); +#151189 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#148798 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#148799 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#148800 = DEFINITIONAL_REPRESENTATION('',(#148801),#148805); -#148801 = LINE('',#148802,#148803); -#148802 = CARTESIAN_POINT('',(-1.65,-1.7763568394E-015)); -#148803 = VECTOR('',#148804,1.); -#148804 = DIRECTION('',(-6.725593854929E-015,1.)); -#148805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148806 = PCURVE('',#86642,#148807); -#148807 = DEFINITIONAL_REPRESENTATION('',(#148808),#148812); -#148808 = LINE('',#148809,#148810); -#148809 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#148810 = VECTOR('',#148811,1.); -#148811 = DIRECTION('',(0.E+000,1.)); -#148812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148813 = ORIENTED_EDGE('',*,*,#148814,.T.); -#148814 = EDGE_CURVE('',#148787,#148815,#148817,.T.); -#148815 = VERTEX_POINT('',#148816); -#148816 = CARTESIAN_POINT('',(1.85,11.,-0.308197125857)); -#148817 = SURFACE_CURVE('',#148818,(#148822,#148829),.PCURVE_S1.); -#148818 = LINE('',#148819,#148820); -#148819 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#148820 = VECTOR('',#148821,1.); -#148821 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148822 = PCURVE('',#148795,#148823); -#148823 = DEFINITIONAL_REPRESENTATION('',(#148824),#148828); -#148824 = LINE('',#148825,#148826); -#148825 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#148826 = VECTOR('',#148827,1.); -#148827 = DIRECTION('',(-1.,-8.881784197001E-016)); -#148828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148829 = PCURVE('',#148830,#148835); -#148830 = PLANE('',#148831); -#148831 = AXIS2_PLACEMENT_3D('',#148832,#148833,#148834); -#148832 = CARTESIAN_POINT('',(1.75,11.,-0.258196742327)); -#148833 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#148834 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#148835 = DEFINITIONAL_REPRESENTATION('',(#148836),#148840); -#148836 = LINE('',#148837,#148838); -#148837 = CARTESIAN_POINT('',(1.75,-5.000038352949E-002)); -#148838 = VECTOR('',#148839,1.); -#148839 = DIRECTION('',(-1.,-1.1653254136E-048)); -#148840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148841 = ORIENTED_EDGE('',*,*,#148842,.F.); -#148842 = EDGE_CURVE('',#148843,#148815,#148845,.T.); -#148843 = VERTEX_POINT('',#148844); -#148844 = CARTESIAN_POINT('',(1.85,10.74341632541,-0.308197125857)); -#148845 = SURFACE_CURVE('',#148846,(#148850,#148857),.PCURVE_S1.); -#148846 = LINE('',#148847,#148848); -#148847 = CARTESIAN_POINT('',(1.85,10.74341632541,-0.308197125857)); -#148848 = VECTOR('',#148849,1.); -#148849 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148850 = PCURVE('',#148795,#148851); -#148851 = DEFINITIONAL_REPRESENTATION('',(#148852),#148856); -#148852 = LINE('',#148853,#148854); -#148853 = CARTESIAN_POINT('',(-1.85,-1.7763568394E-015)); -#148854 = VECTOR('',#148855,1.); -#148855 = DIRECTION('',(-6.725593854929E-015,1.)); -#148856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148857 = PCURVE('',#86586,#148858); -#148858 = DEFINITIONAL_REPRESENTATION('',(#148859),#148863); -#148859 = LINE('',#148860,#148861); -#148860 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#148861 = VECTOR('',#148862,1.); -#148862 = DIRECTION('',(0.E+000,1.)); -#148863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148864 = ORIENTED_EDGE('',*,*,#148865,.T.); -#148865 = EDGE_CURVE('',#148843,#148785,#148866,.T.); -#148866 = SURFACE_CURVE('',#148867,(#148871,#148878),.PCURVE_S1.); -#148867 = LINE('',#148868,#148869); -#148868 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#151190 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#151191 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#151192 = DEFINITIONAL_REPRESENTATION('',(#151193),#151197); +#151193 = LINE('',#151194,#151195); +#151194 = CARTESIAN_POINT('',(-1.65,-1.7763568394E-015)); +#151195 = VECTOR('',#151196,1.); +#151196 = DIRECTION('',(-6.725593854929E-015,1.)); +#151197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151198 = PCURVE('',#89034,#151199); +#151199 = DEFINITIONAL_REPRESENTATION('',(#151200),#151204); +#151200 = LINE('',#151201,#151202); +#151201 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#151202 = VECTOR('',#151203,1.); +#151203 = DIRECTION('',(0.E+000,1.)); +#151204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151205 = ORIENTED_EDGE('',*,*,#151206,.T.); +#151206 = EDGE_CURVE('',#151179,#151207,#151209,.T.); +#151207 = VERTEX_POINT('',#151208); +#151208 = CARTESIAN_POINT('',(1.85,11.,-0.308197125857)); +#151209 = SURFACE_CURVE('',#151210,(#151214,#151221),.PCURVE_S1.); +#151210 = LINE('',#151211,#151212); +#151211 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#151212 = VECTOR('',#151213,1.); +#151213 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151214 = PCURVE('',#151187,#151215); +#151215 = DEFINITIONAL_REPRESENTATION('',(#151216),#151220); +#151216 = LINE('',#151217,#151218); +#151217 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#151218 = VECTOR('',#151219,1.); +#151219 = DIRECTION('',(-1.,-8.881784197001E-016)); +#151220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151221 = PCURVE('',#151222,#151227); +#151222 = PLANE('',#151223); +#151223 = AXIS2_PLACEMENT_3D('',#151224,#151225,#151226); +#151224 = CARTESIAN_POINT('',(1.75,11.,-0.258196742327)); +#151225 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#151226 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#151227 = DEFINITIONAL_REPRESENTATION('',(#151228),#151232); +#151228 = LINE('',#151229,#151230); +#151229 = CARTESIAN_POINT('',(1.75,-5.000038352949E-002)); +#151230 = VECTOR('',#151231,1.); +#151231 = DIRECTION('',(-1.,-1.1653254136E-048)); +#151232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151233 = ORIENTED_EDGE('',*,*,#151234,.F.); +#151234 = EDGE_CURVE('',#151235,#151207,#151237,.T.); +#151235 = VERTEX_POINT('',#151236); +#151236 = CARTESIAN_POINT('',(1.85,10.74341632541,-0.308197125857)); +#151237 = SURFACE_CURVE('',#151238,(#151242,#151249),.PCURVE_S1.); +#151238 = LINE('',#151239,#151240); +#151239 = CARTESIAN_POINT('',(1.85,10.74341632541,-0.308197125857)); +#151240 = VECTOR('',#151241,1.); +#151241 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#151242 = PCURVE('',#151187,#151243); +#151243 = DEFINITIONAL_REPRESENTATION('',(#151244),#151248); +#151244 = LINE('',#151245,#151246); +#151245 = CARTESIAN_POINT('',(-1.85,-1.7763568394E-015)); +#151246 = VECTOR('',#151247,1.); +#151247 = DIRECTION('',(-6.725593854929E-015,1.)); +#151248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151249 = PCURVE('',#88978,#151250); +#151250 = DEFINITIONAL_REPRESENTATION('',(#151251),#151255); +#151251 = LINE('',#151252,#151253); +#151252 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#151253 = VECTOR('',#151254,1.); +#151254 = DIRECTION('',(0.E+000,1.)); +#151255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151256 = ORIENTED_EDGE('',*,*,#151257,.T.); +#151257 = EDGE_CURVE('',#151235,#151177,#151258,.T.); +#151258 = SURFACE_CURVE('',#151259,(#151263,#151270),.PCURVE_S1.); +#151259 = LINE('',#151260,#151261); +#151260 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#148869 = VECTOR('',#148870,1.); -#148870 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148871 = PCURVE('',#148795,#148872); -#148872 = DEFINITIONAL_REPRESENTATION('',(#148873),#148877); -#148873 = LINE('',#148874,#148875); -#148874 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148875 = VECTOR('',#148876,1.); -#148876 = DIRECTION('',(1.,8.881784197001E-016)); -#148877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148878 = PCURVE('',#148879,#148884); -#148879 = CYLINDRICAL_SURFACE('',#148880,0.308574064194); -#148880 = AXIS2_PLACEMENT_3D('',#148881,#148882,#148883); -#148881 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#151261 = VECTOR('',#151262,1.); +#151262 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151263 = PCURVE('',#151187,#151264); +#151264 = DEFINITIONAL_REPRESENTATION('',(#151265),#151269); +#151265 = LINE('',#151266,#151267); +#151266 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151267 = VECTOR('',#151268,1.); +#151268 = DIRECTION('',(1.,8.881784197001E-016)); +#151269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151270 = PCURVE('',#151271,#151276); +#151271 = CYLINDRICAL_SURFACE('',#151272,0.308574064194); +#151272 = AXIS2_PLACEMENT_3D('',#151273,#151274,#151275); +#151273 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#148882 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148883 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148884 = DEFINITIONAL_REPRESENTATION('',(#148885),#148888); -#148885 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148886,#148887), +#151274 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151275 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151276 = DEFINITIONAL_REPRESENTATION('',(#151277),#151280); +#151277 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151278,#151279), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#148886 = CARTESIAN_POINT('',(4.761821717947,1.85)); -#148887 = CARTESIAN_POINT('',(4.761821717947,1.65)); -#148888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148889 = ADVANCED_FACE('',(#148890),#148904,.T.); -#148890 = FACE_BOUND('',#148891,.T.); -#148891 = EDGE_LOOP('',(#148892,#148922,#148945,#148968)); -#148892 = ORIENTED_EDGE('',*,*,#148893,.T.); -#148893 = EDGE_CURVE('',#148894,#148896,#148898,.T.); -#148894 = VERTEX_POINT('',#148895); -#148895 = CARTESIAN_POINT('',(1.85,10.740726081328,-0.208196358798)); -#148896 = VERTEX_POINT('',#148897); -#148897 = CARTESIAN_POINT('',(1.85,11.,-0.208196358798)); -#148898 = SURFACE_CURVE('',#148899,(#148903,#148915),.PCURVE_S1.); -#148899 = LINE('',#148900,#148901); -#148900 = CARTESIAN_POINT('',(1.85,10.740726081328,-0.208196358798)); -#148901 = VECTOR('',#148902,1.); -#148902 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148903 = PCURVE('',#148904,#148909); -#148904 = PLANE('',#148905); -#148905 = AXIS2_PLACEMENT_3D('',#148906,#148907,#148908); -#148906 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#151278 = CARTESIAN_POINT('',(4.761821717947,1.85)); +#151279 = CARTESIAN_POINT('',(4.761821717947,1.65)); +#151280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151281 = ADVANCED_FACE('',(#151282),#151296,.T.); +#151282 = FACE_BOUND('',#151283,.T.); +#151283 = EDGE_LOOP('',(#151284,#151314,#151337,#151360)); +#151284 = ORIENTED_EDGE('',*,*,#151285,.T.); +#151285 = EDGE_CURVE('',#151286,#151288,#151290,.T.); +#151286 = VERTEX_POINT('',#151287); +#151287 = CARTESIAN_POINT('',(1.85,10.740726081328,-0.208196358798)); +#151288 = VERTEX_POINT('',#151289); +#151289 = CARTESIAN_POINT('',(1.85,11.,-0.208196358798)); +#151290 = SURFACE_CURVE('',#151291,(#151295,#151307),.PCURVE_S1.); +#151291 = LINE('',#151292,#151293); +#151292 = CARTESIAN_POINT('',(1.85,10.740726081328,-0.208196358798)); +#151293 = VECTOR('',#151294,1.); +#151294 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#151295 = PCURVE('',#151296,#151301); +#151296 = PLANE('',#151297); +#151297 = AXIS2_PLACEMENT_3D('',#151298,#151299,#151300); +#151298 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#148907 = DIRECTION('',(0.E+000,0.E+000,1.)); -#148908 = DIRECTION('',(1.,0.E+000,0.E+000)); -#148909 = DEFINITIONAL_REPRESENTATION('',(#148910),#148914); -#148910 = LINE('',#148911,#148912); -#148911 = CARTESIAN_POINT('',(1.85,-1.7763568394E-015)); -#148912 = VECTOR('',#148913,1.); -#148913 = DIRECTION('',(6.725593854929E-015,1.)); -#148914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148915 = PCURVE('',#86586,#148916); -#148916 = DEFINITIONAL_REPRESENTATION('',(#148917),#148921); -#148917 = LINE('',#148918,#148919); -#148918 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#148919 = VECTOR('',#148920,1.); -#148920 = DIRECTION('',(0.E+000,1.)); -#148921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148922 = ORIENTED_EDGE('',*,*,#148923,.T.); -#148923 = EDGE_CURVE('',#148896,#148924,#148926,.T.); -#148924 = VERTEX_POINT('',#148925); -#148925 = CARTESIAN_POINT('',(1.65,11.,-0.208196358798)); -#148926 = SURFACE_CURVE('',#148927,(#148931,#148938),.PCURVE_S1.); -#148927 = LINE('',#148928,#148929); -#148928 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#148929 = VECTOR('',#148930,1.); -#148930 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#148931 = PCURVE('',#148904,#148932); -#148932 = DEFINITIONAL_REPRESENTATION('',(#148933),#148937); -#148933 = LINE('',#148934,#148935); -#148934 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#148935 = VECTOR('',#148936,1.); -#148936 = DIRECTION('',(-1.,8.881784197001E-016)); -#148937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148938 = PCURVE('',#148830,#148939); -#148939 = DEFINITIONAL_REPRESENTATION('',(#148940),#148944); -#148940 = LINE('',#148941,#148942); -#148941 = CARTESIAN_POINT('',(1.75,5.000038352949E-002)); -#148942 = VECTOR('',#148943,1.); -#148943 = DIRECTION('',(1.,1.1653254136E-048)); -#148944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148945 = ORIENTED_EDGE('',*,*,#148946,.F.); -#148946 = EDGE_CURVE('',#148947,#148924,#148949,.T.); -#148947 = VERTEX_POINT('',#148948); -#148948 = CARTESIAN_POINT('',(1.65,10.740726081328,-0.208196358798)); -#148949 = SURFACE_CURVE('',#148950,(#148954,#148961),.PCURVE_S1.); -#148950 = LINE('',#148951,#148952); -#148951 = CARTESIAN_POINT('',(1.65,10.740726081328,-0.208196358798)); -#148952 = VECTOR('',#148953,1.); -#148953 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#148954 = PCURVE('',#148904,#148955); -#148955 = DEFINITIONAL_REPRESENTATION('',(#148956),#148960); -#148956 = LINE('',#148957,#148958); -#148957 = CARTESIAN_POINT('',(1.65,-1.7763568394E-015)); -#148958 = VECTOR('',#148959,1.); -#148959 = DIRECTION('',(6.725593854929E-015,1.)); -#148960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148961 = PCURVE('',#86642,#148962); -#148962 = DEFINITIONAL_REPRESENTATION('',(#148963),#148967); -#148963 = LINE('',#148964,#148965); -#148964 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#148965 = VECTOR('',#148966,1.); -#148966 = DIRECTION('',(0.E+000,1.)); -#148967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148968 = ORIENTED_EDGE('',*,*,#148969,.T.); -#148969 = EDGE_CURVE('',#148947,#148894,#148970,.T.); -#148970 = SURFACE_CURVE('',#148971,(#148975,#148982),.PCURVE_S1.); -#148971 = LINE('',#148972,#148973); -#148972 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#151299 = DIRECTION('',(0.E+000,0.E+000,1.)); +#151300 = DIRECTION('',(1.,0.E+000,0.E+000)); +#151301 = DEFINITIONAL_REPRESENTATION('',(#151302),#151306); +#151302 = LINE('',#151303,#151304); +#151303 = CARTESIAN_POINT('',(1.85,-1.7763568394E-015)); +#151304 = VECTOR('',#151305,1.); +#151305 = DIRECTION('',(6.725593854929E-015,1.)); +#151306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151307 = PCURVE('',#88978,#151308); +#151308 = DEFINITIONAL_REPRESENTATION('',(#151309),#151313); +#151309 = LINE('',#151310,#151311); +#151310 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#151311 = VECTOR('',#151312,1.); +#151312 = DIRECTION('',(0.E+000,1.)); +#151313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151314 = ORIENTED_EDGE('',*,*,#151315,.T.); +#151315 = EDGE_CURVE('',#151288,#151316,#151318,.T.); +#151316 = VERTEX_POINT('',#151317); +#151317 = CARTESIAN_POINT('',(1.65,11.,-0.208196358798)); +#151318 = SURFACE_CURVE('',#151319,(#151323,#151330),.PCURVE_S1.); +#151319 = LINE('',#151320,#151321); +#151320 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#151321 = VECTOR('',#151322,1.); +#151322 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151323 = PCURVE('',#151296,#151324); +#151324 = DEFINITIONAL_REPRESENTATION('',(#151325),#151329); +#151325 = LINE('',#151326,#151327); +#151326 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#151327 = VECTOR('',#151328,1.); +#151328 = DIRECTION('',(-1.,8.881784197001E-016)); +#151329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151330 = PCURVE('',#151222,#151331); +#151331 = DEFINITIONAL_REPRESENTATION('',(#151332),#151336); +#151332 = LINE('',#151333,#151334); +#151333 = CARTESIAN_POINT('',(1.75,5.000038352949E-002)); +#151334 = VECTOR('',#151335,1.); +#151335 = DIRECTION('',(1.,1.1653254136E-048)); +#151336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151337 = ORIENTED_EDGE('',*,*,#151338,.F.); +#151338 = EDGE_CURVE('',#151339,#151316,#151341,.T.); +#151339 = VERTEX_POINT('',#151340); +#151340 = CARTESIAN_POINT('',(1.65,10.740726081328,-0.208196358798)); +#151341 = SURFACE_CURVE('',#151342,(#151346,#151353),.PCURVE_S1.); +#151342 = LINE('',#151343,#151344); +#151343 = CARTESIAN_POINT('',(1.65,10.740726081328,-0.208196358798)); +#151344 = VECTOR('',#151345,1.); +#151345 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#151346 = PCURVE('',#151296,#151347); +#151347 = DEFINITIONAL_REPRESENTATION('',(#151348),#151352); +#151348 = LINE('',#151349,#151350); +#151349 = CARTESIAN_POINT('',(1.65,-1.7763568394E-015)); +#151350 = VECTOR('',#151351,1.); +#151351 = DIRECTION('',(6.725593854929E-015,1.)); +#151352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151353 = PCURVE('',#89034,#151354); +#151354 = DEFINITIONAL_REPRESENTATION('',(#151355),#151359); +#151355 = LINE('',#151356,#151357); +#151356 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#151357 = VECTOR('',#151358,1.); +#151358 = DIRECTION('',(0.E+000,1.)); +#151359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151360 = ORIENTED_EDGE('',*,*,#151361,.T.); +#151361 = EDGE_CURVE('',#151339,#151286,#151362,.T.); +#151362 = SURFACE_CURVE('',#151363,(#151367,#151374),.PCURVE_S1.); +#151363 = LINE('',#151364,#151365); +#151364 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#148973 = VECTOR('',#148974,1.); -#148974 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148975 = PCURVE('',#148904,#148976); -#148976 = DEFINITIONAL_REPRESENTATION('',(#148977),#148981); -#148977 = LINE('',#148978,#148979); -#148978 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#148979 = VECTOR('',#148980,1.); -#148980 = DIRECTION('',(1.,-8.881784197001E-016)); -#148981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148982 = PCURVE('',#148983,#148988); -#148983 = CYLINDRICAL_SURFACE('',#148984,0.208574704164); -#148984 = AXIS2_PLACEMENT_3D('',#148985,#148986,#148987); -#148985 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#151365 = VECTOR('',#151366,1.); +#151366 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151367 = PCURVE('',#151296,#151368); +#151368 = DEFINITIONAL_REPRESENTATION('',(#151369),#151373); +#151369 = LINE('',#151370,#151371); +#151370 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151371 = VECTOR('',#151372,1.); +#151372 = DIRECTION('',(1.,-8.881784197001E-016)); +#151373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151374 = PCURVE('',#151375,#151380); +#151375 = CYLINDRICAL_SURFACE('',#151376,0.208574704164); +#151376 = AXIS2_PLACEMENT_3D('',#151377,#151378,#151379); +#151377 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#148986 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#148987 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#148988 = DEFINITIONAL_REPRESENTATION('',(#148989),#148992); -#148989 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#148990,#148991), +#151378 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151379 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151380 = DEFINITIONAL_REPRESENTATION('',(#151381),#151384); +#151381 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151382,#151383), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#148990 = CARTESIAN_POINT('',(4.772630242227,1.65)); -#148991 = CARTESIAN_POINT('',(4.772630242227,1.85)); -#148992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#148993 = ADVANCED_FACE('',(#148994),#148879,.T.); -#148994 = FACE_BOUND('',#148995,.T.); -#148995 = EDGE_LOOP('',(#148996,#148997,#149047,#149074)); -#148996 = ORIENTED_EDGE('',*,*,#148865,.F.); -#148997 = ORIENTED_EDGE('',*,*,#148998,.F.); -#148998 = EDGE_CURVE('',#148999,#148843,#149001,.T.); -#148999 = VERTEX_POINT('',#149000); -#149000 = CARTESIAN_POINT('',(1.85,10.419594812019,0.E+000)); -#149001 = SURFACE_CURVE('',#149002,(#149007,#149036),.PCURVE_S1.); -#149002 = CIRCLE('',#149003,0.308574064194); -#149003 = AXIS2_PLACEMENT_3D('',#149004,#149005,#149006); -#149004 = CARTESIAN_POINT('',(1.85,10.728168876214,2.640924866458E-017) - ); -#149005 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149006 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149007 = PCURVE('',#148879,#149008); -#149008 = DEFINITIONAL_REPRESENTATION('',(#149009),#149035); -#149009 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149010,#149011,#149012, - #149013,#149014,#149015,#149016,#149017,#149018,#149019,#149020, - #149021,#149022,#149023,#149024,#149025,#149026,#149027,#149028, - #149029,#149030,#149031,#149032,#149033,#149034),.UNSPECIFIED.,.F., +#151382 = CARTESIAN_POINT('',(4.772630242227,1.65)); +#151383 = CARTESIAN_POINT('',(4.772630242227,1.85)); +#151384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151385 = ADVANCED_FACE('',(#151386),#151271,.T.); +#151386 = FACE_BOUND('',#151387,.T.); +#151387 = EDGE_LOOP('',(#151388,#151389,#151439,#151466)); +#151388 = ORIENTED_EDGE('',*,*,#151257,.F.); +#151389 = ORIENTED_EDGE('',*,*,#151390,.F.); +#151390 = EDGE_CURVE('',#151391,#151235,#151393,.T.); +#151391 = VERTEX_POINT('',#151392); +#151392 = CARTESIAN_POINT('',(1.85,10.419594812019,0.E+000)); +#151393 = SURFACE_CURVE('',#151394,(#151399,#151428),.PCURVE_S1.); +#151394 = CIRCLE('',#151395,0.308574064194); +#151395 = AXIS2_PLACEMENT_3D('',#151396,#151397,#151398); +#151396 = CARTESIAN_POINT('',(1.85,10.728168876214,2.640924866458E-017) + ); +#151397 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151398 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151399 = PCURVE('',#151271,#151400); +#151400 = DEFINITIONAL_REPRESENTATION('',(#151401),#151427); +#151401 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151402,#151403,#151404, + #151405,#151406,#151407,#151408,#151409,#151410,#151411,#151412, + #151413,#151414,#151415,#151416,#151417,#151418,#151419,#151420, + #151421,#151422,#151423,#151424,#151425,#151426),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -183753,102 +186755,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#149010 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#149011 = CARTESIAN_POINT('',(3.166141578807,1.85)); -#149012 = CARTESIAN_POINT('',(3.215239429242,1.85)); -#149013 = CARTESIAN_POINT('',(3.288886204895,1.85)); -#149014 = CARTESIAN_POINT('',(3.362532980548,1.85)); -#149015 = CARTESIAN_POINT('',(3.4361797562,1.85)); -#149016 = CARTESIAN_POINT('',(3.509826531853,1.85)); -#149017 = CARTESIAN_POINT('',(3.583473307505,1.85)); -#149018 = CARTESIAN_POINT('',(3.657120083158,1.85)); -#149019 = CARTESIAN_POINT('',(3.730766858811,1.85)); -#149020 = CARTESIAN_POINT('',(3.804413634463,1.85)); -#149021 = CARTESIAN_POINT('',(3.878060410116,1.85)); -#149022 = CARTESIAN_POINT('',(3.951707185768,1.85)); -#149023 = CARTESIAN_POINT('',(4.025353961421,1.85)); -#149024 = CARTESIAN_POINT('',(4.099000737074,1.85)); -#149025 = CARTESIAN_POINT('',(4.172647512726,1.85)); -#149026 = CARTESIAN_POINT('',(4.246294288379,1.85)); -#149027 = CARTESIAN_POINT('',(4.319941064031,1.85)); -#149028 = CARTESIAN_POINT('',(4.393587839684,1.85)); -#149029 = CARTESIAN_POINT('',(4.467234615337,1.85)); -#149030 = CARTESIAN_POINT('',(4.540881390989,1.85)); -#149031 = CARTESIAN_POINT('',(4.614528166642,1.85)); -#149032 = CARTESIAN_POINT('',(4.688174942294,1.85)); -#149033 = CARTESIAN_POINT('',(4.737272792729,1.85)); -#149034 = CARTESIAN_POINT('',(4.761821717947,1.85)); -#149035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149036 = PCURVE('',#86586,#149037); -#149037 = DEFINITIONAL_REPRESENTATION('',(#149038),#149046); -#149038 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149039,#149040,#149041, - #149042,#149043,#149044,#149045),.UNSPECIFIED.,.T.,.F.) +#151402 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#151403 = CARTESIAN_POINT('',(3.166141578807,1.85)); +#151404 = CARTESIAN_POINT('',(3.215239429242,1.85)); +#151405 = CARTESIAN_POINT('',(3.288886204895,1.85)); +#151406 = CARTESIAN_POINT('',(3.362532980548,1.85)); +#151407 = CARTESIAN_POINT('',(3.4361797562,1.85)); +#151408 = CARTESIAN_POINT('',(3.509826531853,1.85)); +#151409 = CARTESIAN_POINT('',(3.583473307505,1.85)); +#151410 = CARTESIAN_POINT('',(3.657120083158,1.85)); +#151411 = CARTESIAN_POINT('',(3.730766858811,1.85)); +#151412 = CARTESIAN_POINT('',(3.804413634463,1.85)); +#151413 = CARTESIAN_POINT('',(3.878060410116,1.85)); +#151414 = CARTESIAN_POINT('',(3.951707185768,1.85)); +#151415 = CARTESIAN_POINT('',(4.025353961421,1.85)); +#151416 = CARTESIAN_POINT('',(4.099000737074,1.85)); +#151417 = CARTESIAN_POINT('',(4.172647512726,1.85)); +#151418 = CARTESIAN_POINT('',(4.246294288379,1.85)); +#151419 = CARTESIAN_POINT('',(4.319941064031,1.85)); +#151420 = CARTESIAN_POINT('',(4.393587839684,1.85)); +#151421 = CARTESIAN_POINT('',(4.467234615337,1.85)); +#151422 = CARTESIAN_POINT('',(4.540881390989,1.85)); +#151423 = CARTESIAN_POINT('',(4.614528166642,1.85)); +#151424 = CARTESIAN_POINT('',(4.688174942294,1.85)); +#151425 = CARTESIAN_POINT('',(4.737272792729,1.85)); +#151426 = CARTESIAN_POINT('',(4.761821717947,1.85)); +#151427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151428 = PCURVE('',#88978,#151429); +#151429 = DEFINITIONAL_REPRESENTATION('',(#151430),#151438); +#151430 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#151431,#151432,#151433, + #151434,#151435,#151436,#151437),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#149039 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#149040 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#149041 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); -#149042 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#149043 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#149044 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#149045 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#149046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149047 = ORIENTED_EDGE('',*,*,#149048,.F.); -#149048 = EDGE_CURVE('',#149049,#148999,#149051,.T.); -#149049 = VERTEX_POINT('',#149050); -#149050 = CARTESIAN_POINT('',(1.65,10.419594812019,0.E+000)); -#149051 = SURFACE_CURVE('',#149052,(#149056,#149062),.PCURVE_S1.); -#149052 = LINE('',#149053,#149054); -#149053 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#151431 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#151432 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#151433 = CARTESIAN_POINT('',(-0.382767021459,4.603385167788E-002)); +#151434 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#151435 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#151436 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#151437 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#151438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151439 = ORIENTED_EDGE('',*,*,#151440,.F.); +#151440 = EDGE_CURVE('',#151441,#151391,#151443,.T.); +#151441 = VERTEX_POINT('',#151442); +#151442 = CARTESIAN_POINT('',(1.65,10.419594812019,0.E+000)); +#151443 = SURFACE_CURVE('',#151444,(#151448,#151454),.PCURVE_S1.); +#151444 = LINE('',#151445,#151446); +#151445 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#149054 = VECTOR('',#149055,1.); -#149055 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149056 = PCURVE('',#148879,#149057); -#149057 = DEFINITIONAL_REPRESENTATION('',(#149058),#149061); -#149058 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149059,#149060), +#151446 = VECTOR('',#151447,1.); +#151447 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151448 = PCURVE('',#151271,#151449); +#151449 = DEFINITIONAL_REPRESENTATION('',(#151450),#151453); +#151450 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151451,#151452), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#149059 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#149060 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#149061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#151451 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#151452 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#151453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#149062 = PCURVE('',#149063,#149068); -#149063 = PLANE('',#149064); -#149064 = AXIS2_PLACEMENT_3D('',#149065,#149066,#149067); -#149065 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#151454 = PCURVE('',#151455,#151460); +#151455 = PLANE('',#151456); +#151456 = AXIS2_PLACEMENT_3D('',#151457,#151458,#151459); +#151457 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#149066 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149067 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149068 = DEFINITIONAL_REPRESENTATION('',(#149069),#149073); -#149069 = LINE('',#149070,#149071); -#149070 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#149071 = VECTOR('',#149072,1.); -#149072 = DIRECTION('',(-1.,0.E+000)); -#149073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#151458 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151459 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151460 = DEFINITIONAL_REPRESENTATION('',(#151461),#151465); +#151461 = LINE('',#151462,#151463); +#151462 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#151463 = VECTOR('',#151464,1.); +#151464 = DIRECTION('',(-1.,0.E+000)); +#151465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#149074 = ORIENTED_EDGE('',*,*,#149075,.T.); -#149075 = EDGE_CURVE('',#149049,#148785,#149076,.T.); -#149076 = SURFACE_CURVE('',#149077,(#149082,#149111),.PCURVE_S1.); -#149077 = CIRCLE('',#149078,0.308574064194); -#149078 = AXIS2_PLACEMENT_3D('',#149079,#149080,#149081); -#149079 = CARTESIAN_POINT('',(1.65,10.728168876214,2.640924866458E-017) - ); -#149080 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149081 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149082 = PCURVE('',#148879,#149083); -#149083 = DEFINITIONAL_REPRESENTATION('',(#149084),#149110); -#149084 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149085,#149086,#149087, - #149088,#149089,#149090,#149091,#149092,#149093,#149094,#149095, - #149096,#149097,#149098,#149099,#149100,#149101,#149102,#149103, - #149104,#149105,#149106,#149107,#149108,#149109),.UNSPECIFIED.,.F., +#151466 = ORIENTED_EDGE('',*,*,#151467,.T.); +#151467 = EDGE_CURVE('',#151441,#151177,#151468,.T.); +#151468 = SURFACE_CURVE('',#151469,(#151474,#151503),.PCURVE_S1.); +#151469 = CIRCLE('',#151470,0.308574064194); +#151470 = AXIS2_PLACEMENT_3D('',#151471,#151472,#151473); +#151471 = CARTESIAN_POINT('',(1.65,10.728168876214,2.640924866458E-017) + ); +#151472 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151473 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151474 = PCURVE('',#151271,#151475); +#151475 = DEFINITIONAL_REPRESENTATION('',(#151476),#151502); +#151476 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151477,#151478,#151479, + #151480,#151481,#151482,#151483,#151484,#151485,#151486,#151487, + #151488,#151489,#151490,#151491,#151492,#151493,#151494,#151495, + #151496,#151497,#151498,#151499,#151500,#151501),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -183856,64 +186858,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#149085 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#149086 = CARTESIAN_POINT('',(3.166141578807,1.65)); -#149087 = CARTESIAN_POINT('',(3.215239429242,1.65)); -#149088 = CARTESIAN_POINT('',(3.288886204895,1.65)); -#149089 = CARTESIAN_POINT('',(3.362532980548,1.65)); -#149090 = CARTESIAN_POINT('',(3.4361797562,1.65)); -#149091 = CARTESIAN_POINT('',(3.509826531853,1.65)); -#149092 = CARTESIAN_POINT('',(3.583473307505,1.65)); -#149093 = CARTESIAN_POINT('',(3.657120083158,1.65)); -#149094 = CARTESIAN_POINT('',(3.730766858811,1.65)); -#149095 = CARTESIAN_POINT('',(3.804413634463,1.65)); -#149096 = CARTESIAN_POINT('',(3.878060410116,1.65)); -#149097 = CARTESIAN_POINT('',(3.951707185768,1.65)); -#149098 = CARTESIAN_POINT('',(4.025353961421,1.65)); -#149099 = CARTESIAN_POINT('',(4.099000737074,1.65)); -#149100 = CARTESIAN_POINT('',(4.172647512726,1.65)); -#149101 = CARTESIAN_POINT('',(4.246294288379,1.65)); -#149102 = CARTESIAN_POINT('',(4.319941064031,1.65)); -#149103 = CARTESIAN_POINT('',(4.393587839684,1.65)); -#149104 = CARTESIAN_POINT('',(4.467234615337,1.65)); -#149105 = CARTESIAN_POINT('',(4.540881390989,1.65)); -#149106 = CARTESIAN_POINT('',(4.614528166642,1.65)); -#149107 = CARTESIAN_POINT('',(4.688174942294,1.65)); -#149108 = CARTESIAN_POINT('',(4.737272792729,1.65)); -#149109 = CARTESIAN_POINT('',(4.761821717947,1.65)); -#149110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149111 = PCURVE('',#86642,#149112); -#149112 = DEFINITIONAL_REPRESENTATION('',(#149113),#149117); -#149113 = CIRCLE('',#149114,0.308574064194); -#149114 = AXIS2_PLACEMENT_2D('',#149115,#149116); -#149115 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#149116 = DIRECTION('',(0.E+000,1.)); -#149117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149118 = ADVANCED_FACE('',(#149119),#148983,.F.); -#149119 = FACE_BOUND('',#149120,.F.); -#149120 = EDGE_LOOP('',(#149121,#149122,#149172,#149199)); -#149121 = ORIENTED_EDGE('',*,*,#148969,.T.); -#149122 = ORIENTED_EDGE('',*,*,#149123,.F.); -#149123 = EDGE_CURVE('',#149124,#148894,#149126,.T.); -#149124 = VERTEX_POINT('',#149125); -#149125 = CARTESIAN_POINT('',(1.85,10.51959417205,0.E+000)); -#149126 = SURFACE_CURVE('',#149127,(#149132,#149161),.PCURVE_S1.); -#149127 = CIRCLE('',#149128,0.208574704164); -#149128 = AXIS2_PLACEMENT_3D('',#149129,#149130,#149131); -#149129 = CARTESIAN_POINT('',(1.85,10.728168876214,2.640924866458E-017) - ); -#149130 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149131 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149132 = PCURVE('',#148983,#149133); -#149133 = DEFINITIONAL_REPRESENTATION('',(#149134),#149160); -#149134 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149135,#149136,#149137, - #149138,#149139,#149140,#149141,#149142,#149143,#149144,#149145, - #149146,#149147,#149148,#149149,#149150,#149151,#149152,#149153, - #149154,#149155,#149156,#149157,#149158,#149159),.UNSPECIFIED.,.F., +#151477 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#151478 = CARTESIAN_POINT('',(3.166141578807,1.65)); +#151479 = CARTESIAN_POINT('',(3.215239429242,1.65)); +#151480 = CARTESIAN_POINT('',(3.288886204895,1.65)); +#151481 = CARTESIAN_POINT('',(3.362532980548,1.65)); +#151482 = CARTESIAN_POINT('',(3.4361797562,1.65)); +#151483 = CARTESIAN_POINT('',(3.509826531853,1.65)); +#151484 = CARTESIAN_POINT('',(3.583473307505,1.65)); +#151485 = CARTESIAN_POINT('',(3.657120083158,1.65)); +#151486 = CARTESIAN_POINT('',(3.730766858811,1.65)); +#151487 = CARTESIAN_POINT('',(3.804413634463,1.65)); +#151488 = CARTESIAN_POINT('',(3.878060410116,1.65)); +#151489 = CARTESIAN_POINT('',(3.951707185768,1.65)); +#151490 = CARTESIAN_POINT('',(4.025353961421,1.65)); +#151491 = CARTESIAN_POINT('',(4.099000737074,1.65)); +#151492 = CARTESIAN_POINT('',(4.172647512726,1.65)); +#151493 = CARTESIAN_POINT('',(4.246294288379,1.65)); +#151494 = CARTESIAN_POINT('',(4.319941064031,1.65)); +#151495 = CARTESIAN_POINT('',(4.393587839684,1.65)); +#151496 = CARTESIAN_POINT('',(4.467234615337,1.65)); +#151497 = CARTESIAN_POINT('',(4.540881390989,1.65)); +#151498 = CARTESIAN_POINT('',(4.614528166642,1.65)); +#151499 = CARTESIAN_POINT('',(4.688174942294,1.65)); +#151500 = CARTESIAN_POINT('',(4.737272792729,1.65)); +#151501 = CARTESIAN_POINT('',(4.761821717947,1.65)); +#151502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151503 = PCURVE('',#89034,#151504); +#151504 = DEFINITIONAL_REPRESENTATION('',(#151505),#151509); +#151505 = CIRCLE('',#151506,0.308574064194); +#151506 = AXIS2_PLACEMENT_2D('',#151507,#151508); +#151507 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#151508 = DIRECTION('',(0.E+000,1.)); +#151509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151510 = ADVANCED_FACE('',(#151511),#151375,.F.); +#151511 = FACE_BOUND('',#151512,.F.); +#151512 = EDGE_LOOP('',(#151513,#151514,#151564,#151591)); +#151513 = ORIENTED_EDGE('',*,*,#151361,.T.); +#151514 = ORIENTED_EDGE('',*,*,#151515,.F.); +#151515 = EDGE_CURVE('',#151516,#151286,#151518,.T.); +#151516 = VERTEX_POINT('',#151517); +#151517 = CARTESIAN_POINT('',(1.85,10.51959417205,0.E+000)); +#151518 = SURFACE_CURVE('',#151519,(#151524,#151553),.PCURVE_S1.); +#151519 = CIRCLE('',#151520,0.208574704164); +#151520 = AXIS2_PLACEMENT_3D('',#151521,#151522,#151523); +#151521 = CARTESIAN_POINT('',(1.85,10.728168876214,2.640924866458E-017) + ); +#151522 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151523 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151524 = PCURVE('',#151375,#151525); +#151525 = DEFINITIONAL_REPRESENTATION('',(#151526),#151552); +#151526 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151527,#151528,#151529, + #151530,#151531,#151532,#151533,#151534,#151535,#151536,#151537, + #151538,#151539,#151540,#151541,#151542,#151543,#151544,#151545, + #151546,#151547,#151548,#151549,#151550,#151551),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215730725801,3.289868798011,3.364006870222,3.438144942433, 3.512283014644,3.586421086854,3.660559159065,3.734697231276, @@ -183921,102 +186923,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.10538759233,4.179525664541,4.253663736751,4.327801808962, 4.401939881173,4.476077953384,4.550216025595,4.624354097805, 4.698492170016,4.772630242227),.QUASI_UNIFORM_KNOTS.); -#149135 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#149136 = CARTESIAN_POINT('',(3.166305344327,1.85)); -#149137 = CARTESIAN_POINT('',(3.215730725801,1.85)); -#149138 = CARTESIAN_POINT('',(3.289868798011,1.85)); -#149139 = CARTESIAN_POINT('',(3.364006870222,1.85)); -#149140 = CARTESIAN_POINT('',(3.438144942433,1.85)); -#149141 = CARTESIAN_POINT('',(3.512283014644,1.85)); -#149142 = CARTESIAN_POINT('',(3.586421086854,1.85)); -#149143 = CARTESIAN_POINT('',(3.660559159065,1.85)); -#149144 = CARTESIAN_POINT('',(3.734697231276,1.85)); -#149145 = CARTESIAN_POINT('',(3.808835303487,1.85)); -#149146 = CARTESIAN_POINT('',(3.882973375698,1.85)); -#149147 = CARTESIAN_POINT('',(3.957111447908,1.85)); -#149148 = CARTESIAN_POINT('',(4.031249520119,1.85)); -#149149 = CARTESIAN_POINT('',(4.10538759233,1.85)); -#149150 = CARTESIAN_POINT('',(4.179525664541,1.85)); -#149151 = CARTESIAN_POINT('',(4.253663736751,1.85)); -#149152 = CARTESIAN_POINT('',(4.327801808962,1.85)); -#149153 = CARTESIAN_POINT('',(4.401939881173,1.85)); -#149154 = CARTESIAN_POINT('',(4.476077953384,1.85)); -#149155 = CARTESIAN_POINT('',(4.550216025595,1.85)); -#149156 = CARTESIAN_POINT('',(4.624354097805,1.85)); -#149157 = CARTESIAN_POINT('',(4.698492170016,1.85)); -#149158 = CARTESIAN_POINT('',(4.74791755149,1.85)); -#149159 = CARTESIAN_POINT('',(4.772630242227,1.85)); -#149160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149161 = PCURVE('',#86586,#149162); -#149162 = DEFINITIONAL_REPRESENTATION('',(#149163),#149171); -#149163 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149164,#149165,#149166, - #149167,#149168,#149169,#149170),.UNSPECIFIED.,.T.,.F.) +#151527 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#151528 = CARTESIAN_POINT('',(3.166305344327,1.85)); +#151529 = CARTESIAN_POINT('',(3.215730725801,1.85)); +#151530 = CARTESIAN_POINT('',(3.289868798011,1.85)); +#151531 = CARTESIAN_POINT('',(3.364006870222,1.85)); +#151532 = CARTESIAN_POINT('',(3.438144942433,1.85)); +#151533 = CARTESIAN_POINT('',(3.512283014644,1.85)); +#151534 = CARTESIAN_POINT('',(3.586421086854,1.85)); +#151535 = CARTESIAN_POINT('',(3.660559159065,1.85)); +#151536 = CARTESIAN_POINT('',(3.734697231276,1.85)); +#151537 = CARTESIAN_POINT('',(3.808835303487,1.85)); +#151538 = CARTESIAN_POINT('',(3.882973375698,1.85)); +#151539 = CARTESIAN_POINT('',(3.957111447908,1.85)); +#151540 = CARTESIAN_POINT('',(4.031249520119,1.85)); +#151541 = CARTESIAN_POINT('',(4.10538759233,1.85)); +#151542 = CARTESIAN_POINT('',(4.179525664541,1.85)); +#151543 = CARTESIAN_POINT('',(4.253663736751,1.85)); +#151544 = CARTESIAN_POINT('',(4.327801808962,1.85)); +#151545 = CARTESIAN_POINT('',(4.401939881173,1.85)); +#151546 = CARTESIAN_POINT('',(4.476077953384,1.85)); +#151547 = CARTESIAN_POINT('',(4.550216025595,1.85)); +#151548 = CARTESIAN_POINT('',(4.624354097805,1.85)); +#151549 = CARTESIAN_POINT('',(4.698492170016,1.85)); +#151550 = CARTESIAN_POINT('',(4.74791755149,1.85)); +#151551 = CARTESIAN_POINT('',(4.772630242227,1.85)); +#151552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151553 = PCURVE('',#88978,#151554); +#151554 = DEFINITIONAL_REPRESENTATION('',(#151555),#151563); +#151555 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#151556,#151557,#151558, + #151559,#151560,#151561,#151562),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#149164 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#149165 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#149166 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#149167 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#149168 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#149169 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#149170 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#149171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149172 = ORIENTED_EDGE('',*,*,#149173,.T.); -#149173 = EDGE_CURVE('',#149124,#149174,#149176,.T.); -#149174 = VERTEX_POINT('',#149175); -#149175 = CARTESIAN_POINT('',(1.65,10.51959417205,0.E+000)); -#149176 = SURFACE_CURVE('',#149177,(#149181,#149187),.PCURVE_S1.); -#149177 = LINE('',#149178,#149179); -#149178 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 +#151556 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#151557 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#151558 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#151559 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#151560 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#151561 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#151562 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#151563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151564 = ORIENTED_EDGE('',*,*,#151565,.T.); +#151565 = EDGE_CURVE('',#151516,#151566,#151568,.T.); +#151566 = VERTEX_POINT('',#151567); +#151567 = CARTESIAN_POINT('',(1.65,10.51959417205,0.E+000)); +#151568 = SURFACE_CURVE('',#151569,(#151573,#151579),.PCURVE_S1.); +#151569 = LINE('',#151570,#151571); +#151570 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 )); -#149179 = VECTOR('',#149180,1.); -#149180 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149181 = PCURVE('',#148983,#149182); -#149182 = DEFINITIONAL_REPRESENTATION('',(#149183),#149186); -#149183 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149184,#149185), +#151571 = VECTOR('',#151572,1.); +#151572 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151573 = PCURVE('',#151375,#151574); +#151574 = DEFINITIONAL_REPRESENTATION('',(#151575),#151578); +#151575 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151576,#151577), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#149184 = CARTESIAN_POINT('',(3.14159265359,1.85)); -#149185 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#149186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#151576 = CARTESIAN_POINT('',(3.14159265359,1.85)); +#151577 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#151578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#149187 = PCURVE('',#149188,#149193); -#149188 = PLANE('',#149189); -#149189 = AXIS2_PLACEMENT_3D('',#149190,#149191,#149192); -#149190 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#151579 = PCURVE('',#151580,#151585); +#151580 = PLANE('',#151581); +#151581 = AXIS2_PLACEMENT_3D('',#151582,#151583,#151584); +#151582 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#149191 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149192 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149193 = DEFINITIONAL_REPRESENTATION('',(#149194),#149198); -#149194 = LINE('',#149195,#149196); -#149195 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#149196 = VECTOR('',#149197,1.); -#149197 = DIRECTION('',(-1.,0.E+000)); -#149198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149199 = ORIENTED_EDGE('',*,*,#149200,.T.); -#149200 = EDGE_CURVE('',#149174,#148947,#149201,.T.); -#149201 = SURFACE_CURVE('',#149202,(#149207,#149236),.PCURVE_S1.); -#149202 = CIRCLE('',#149203,0.208574704164); -#149203 = AXIS2_PLACEMENT_3D('',#149204,#149205,#149206); -#149204 = CARTESIAN_POINT('',(1.65,10.728168876214,2.640924866458E-017) - ); -#149205 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149206 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149207 = PCURVE('',#148983,#149208); -#149208 = DEFINITIONAL_REPRESENTATION('',(#149209),#149235); -#149209 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149210,#149211,#149212, - #149213,#149214,#149215,#149216,#149217,#149218,#149219,#149220, - #149221,#149222,#149223,#149224,#149225,#149226,#149227,#149228, - #149229,#149230,#149231,#149232,#149233,#149234),.UNSPECIFIED.,.F., +#151583 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151584 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151585 = DEFINITIONAL_REPRESENTATION('',(#151586),#151590); +#151586 = LINE('',#151587,#151588); +#151587 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#151588 = VECTOR('',#151589,1.); +#151589 = DIRECTION('',(-1.,0.E+000)); +#151590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151591 = ORIENTED_EDGE('',*,*,#151592,.T.); +#151592 = EDGE_CURVE('',#151566,#151339,#151593,.T.); +#151593 = SURFACE_CURVE('',#151594,(#151599,#151628),.PCURVE_S1.); +#151594 = CIRCLE('',#151595,0.208574704164); +#151595 = AXIS2_PLACEMENT_3D('',#151596,#151597,#151598); +#151596 = CARTESIAN_POINT('',(1.65,10.728168876214,2.640924866458E-017) + ); +#151597 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151598 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#151599 = PCURVE('',#151375,#151600); +#151600 = DEFINITIONAL_REPRESENTATION('',(#151601),#151627); +#151601 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151602,#151603,#151604, + #151605,#151606,#151607,#151608,#151609,#151610,#151611,#151612, + #151613,#151614,#151615,#151616,#151617,#151618,#151619,#151620, + #151621,#151622,#151623,#151624,#151625,#151626),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215730725801,3.289868798011,3.364006870222,3.438144942433, 3.512283014644,3.586421086854,3.660559159065,3.734697231276, @@ -184024,242 +187026,242 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.10538759233,4.179525664541,4.253663736751,4.327801808962, 4.401939881173,4.476077953384,4.550216025595,4.624354097805, 4.698492170016,4.772630242227),.QUASI_UNIFORM_KNOTS.); -#149210 = CARTESIAN_POINT('',(3.14159265359,1.65)); -#149211 = CARTESIAN_POINT('',(3.166305344327,1.65)); -#149212 = CARTESIAN_POINT('',(3.215730725801,1.65)); -#149213 = CARTESIAN_POINT('',(3.289868798011,1.65)); -#149214 = CARTESIAN_POINT('',(3.364006870222,1.65)); -#149215 = CARTESIAN_POINT('',(3.438144942433,1.65)); -#149216 = CARTESIAN_POINT('',(3.512283014644,1.65)); -#149217 = CARTESIAN_POINT('',(3.586421086854,1.65)); -#149218 = CARTESIAN_POINT('',(3.660559159065,1.65)); -#149219 = CARTESIAN_POINT('',(3.734697231276,1.65)); -#149220 = CARTESIAN_POINT('',(3.808835303487,1.65)); -#149221 = CARTESIAN_POINT('',(3.882973375698,1.65)); -#149222 = CARTESIAN_POINT('',(3.957111447908,1.65)); -#149223 = CARTESIAN_POINT('',(4.031249520119,1.65)); -#149224 = CARTESIAN_POINT('',(4.10538759233,1.65)); -#149225 = CARTESIAN_POINT('',(4.179525664541,1.65)); -#149226 = CARTESIAN_POINT('',(4.253663736751,1.65)); -#149227 = CARTESIAN_POINT('',(4.327801808962,1.65)); -#149228 = CARTESIAN_POINT('',(4.401939881173,1.65)); -#149229 = CARTESIAN_POINT('',(4.476077953384,1.65)); -#149230 = CARTESIAN_POINT('',(4.550216025595,1.65)); -#149231 = CARTESIAN_POINT('',(4.624354097805,1.65)); -#149232 = CARTESIAN_POINT('',(4.698492170016,1.65)); -#149233 = CARTESIAN_POINT('',(4.74791755149,1.65)); -#149234 = CARTESIAN_POINT('',(4.772630242227,1.65)); -#149235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149236 = PCURVE('',#86642,#149237); -#149237 = DEFINITIONAL_REPRESENTATION('',(#149238),#149242); -#149238 = CIRCLE('',#149239,0.208574704164); -#149239 = AXIS2_PLACEMENT_2D('',#149240,#149241); -#149240 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#149241 = DIRECTION('',(0.E+000,1.)); -#149242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149243 = ADVANCED_FACE('',(#149244),#149188,.F.); -#149244 = FACE_BOUND('',#149245,.T.); -#149245 = EDGE_LOOP('',(#149246,#149275,#149296,#149297)); -#149246 = ORIENTED_EDGE('',*,*,#149247,.F.); -#149247 = EDGE_CURVE('',#149248,#149250,#149252,.T.); -#149248 = VERTEX_POINT('',#149249); -#149249 = CARTESIAN_POINT('',(1.85,10.51959417205,0.530776333563)); -#149250 = VERTEX_POINT('',#149251); -#149251 = CARTESIAN_POINT('',(1.65,10.51959417205,0.530776333563)); -#149252 = SURFACE_CURVE('',#149253,(#149257,#149264),.PCURVE_S1.); -#149253 = LINE('',#149254,#149255); -#149254 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, +#151602 = CARTESIAN_POINT('',(3.14159265359,1.65)); +#151603 = CARTESIAN_POINT('',(3.166305344327,1.65)); +#151604 = CARTESIAN_POINT('',(3.215730725801,1.65)); +#151605 = CARTESIAN_POINT('',(3.289868798011,1.65)); +#151606 = CARTESIAN_POINT('',(3.364006870222,1.65)); +#151607 = CARTESIAN_POINT('',(3.438144942433,1.65)); +#151608 = CARTESIAN_POINT('',(3.512283014644,1.65)); +#151609 = CARTESIAN_POINT('',(3.586421086854,1.65)); +#151610 = CARTESIAN_POINT('',(3.660559159065,1.65)); +#151611 = CARTESIAN_POINT('',(3.734697231276,1.65)); +#151612 = CARTESIAN_POINT('',(3.808835303487,1.65)); +#151613 = CARTESIAN_POINT('',(3.882973375698,1.65)); +#151614 = CARTESIAN_POINT('',(3.957111447908,1.65)); +#151615 = CARTESIAN_POINT('',(4.031249520119,1.65)); +#151616 = CARTESIAN_POINT('',(4.10538759233,1.65)); +#151617 = CARTESIAN_POINT('',(4.179525664541,1.65)); +#151618 = CARTESIAN_POINT('',(4.253663736751,1.65)); +#151619 = CARTESIAN_POINT('',(4.327801808962,1.65)); +#151620 = CARTESIAN_POINT('',(4.401939881173,1.65)); +#151621 = CARTESIAN_POINT('',(4.476077953384,1.65)); +#151622 = CARTESIAN_POINT('',(4.550216025595,1.65)); +#151623 = CARTESIAN_POINT('',(4.624354097805,1.65)); +#151624 = CARTESIAN_POINT('',(4.698492170016,1.65)); +#151625 = CARTESIAN_POINT('',(4.74791755149,1.65)); +#151626 = CARTESIAN_POINT('',(4.772630242227,1.65)); +#151627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151628 = PCURVE('',#89034,#151629); +#151629 = DEFINITIONAL_REPRESENTATION('',(#151630),#151634); +#151630 = CIRCLE('',#151631,0.208574704164); +#151631 = AXIS2_PLACEMENT_2D('',#151632,#151633); +#151632 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#151633 = DIRECTION('',(0.E+000,1.)); +#151634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151635 = ADVANCED_FACE('',(#151636),#151580,.F.); +#151636 = FACE_BOUND('',#151637,.T.); +#151637 = EDGE_LOOP('',(#151638,#151667,#151688,#151689)); +#151638 = ORIENTED_EDGE('',*,*,#151639,.F.); +#151639 = EDGE_CURVE('',#151640,#151642,#151644,.T.); +#151640 = VERTEX_POINT('',#151641); +#151641 = CARTESIAN_POINT('',(1.85,10.51959417205,0.530776333563)); +#151642 = VERTEX_POINT('',#151643); +#151643 = CARTESIAN_POINT('',(1.65,10.51959417205,0.530776333563)); +#151644 = SURFACE_CURVE('',#151645,(#151649,#151656),.PCURVE_S1.); +#151645 = LINE('',#151646,#151647); +#151646 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, 0.530776333563)); -#149255 = VECTOR('',#149256,1.); -#149256 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149257 = PCURVE('',#149188,#149258); -#149258 = DEFINITIONAL_REPRESENTATION('',(#149259),#149263); -#149259 = LINE('',#149260,#149261); -#149260 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149261 = VECTOR('',#149262,1.); -#149262 = DIRECTION('',(-1.,0.E+000)); -#149263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149264 = PCURVE('',#149265,#149270); -#149265 = CYLINDRICAL_SURFACE('',#149266,0.2192697516); -#149266 = AXIS2_PLACEMENT_3D('',#149267,#149268,#149269); -#149267 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#151647 = VECTOR('',#151648,1.); +#151648 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151649 = PCURVE('',#151580,#151650); +#151650 = DEFINITIONAL_REPRESENTATION('',(#151651),#151655); +#151651 = LINE('',#151652,#151653); +#151652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151653 = VECTOR('',#151654,1.); +#151654 = DIRECTION('',(-1.,0.E+000)); +#151655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151656 = PCURVE('',#151657,#151662); +#151657 = CYLINDRICAL_SURFACE('',#151658,0.2192697516); +#151658 = AXIS2_PLACEMENT_3D('',#151659,#151660,#151661); +#151659 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#149268 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149269 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149270 = DEFINITIONAL_REPRESENTATION('',(#149271),#149274); -#149271 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149272,#149273), +#151660 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151661 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151662 = DEFINITIONAL_REPRESENTATION('',(#151663),#151666); +#151663 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151664,#151665), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.85,-1.65),.PIECEWISE_BEZIER_KNOTS.); -#149272 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#149273 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#149274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149275 = ORIENTED_EDGE('',*,*,#149276,.T.); -#149276 = EDGE_CURVE('',#149248,#149124,#149277,.T.); -#149277 = SURFACE_CURVE('',#149278,(#149282,#149289),.PCURVE_S1.); -#149278 = LINE('',#149279,#149280); -#149279 = CARTESIAN_POINT('',(1.85,10.51959417205,0.530776333563)); -#149280 = VECTOR('',#149281,1.); -#149281 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#149282 = PCURVE('',#149188,#149283); -#149283 = DEFINITIONAL_REPRESENTATION('',(#149284),#149288); -#149284 = LINE('',#149285,#149286); -#149285 = CARTESIAN_POINT('',(1.85,0.E+000)); -#149286 = VECTOR('',#149287,1.); -#149287 = DIRECTION('',(0.E+000,-1.)); -#149288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149289 = PCURVE('',#86586,#149290); -#149290 = DEFINITIONAL_REPRESENTATION('',(#149291),#149295); -#149291 = LINE('',#149292,#149293); -#149292 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); -#149293 = VECTOR('',#149294,1.); -#149294 = DIRECTION('',(-1.,0.E+000)); -#149295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149296 = ORIENTED_EDGE('',*,*,#149173,.T.); -#149297 = ORIENTED_EDGE('',*,*,#149298,.F.); -#149298 = EDGE_CURVE('',#149250,#149174,#149299,.T.); -#149299 = SURFACE_CURVE('',#149300,(#149304,#149311),.PCURVE_S1.); -#149300 = LINE('',#149301,#149302); -#149301 = CARTESIAN_POINT('',(1.65,10.51959417205,0.530776333563)); -#149302 = VECTOR('',#149303,1.); -#149303 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#149304 = PCURVE('',#149188,#149305); -#149305 = DEFINITIONAL_REPRESENTATION('',(#149306),#149310); -#149306 = LINE('',#149307,#149308); -#149307 = CARTESIAN_POINT('',(1.65,0.E+000)); -#149308 = VECTOR('',#149309,1.); -#149309 = DIRECTION('',(0.E+000,-1.)); -#149310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149311 = PCURVE('',#86642,#149312); -#149312 = DEFINITIONAL_REPRESENTATION('',(#149313),#149317); -#149313 = LINE('',#149314,#149315); -#149314 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#149315 = VECTOR('',#149316,1.); -#149316 = DIRECTION('',(1.,0.E+000)); -#149317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149318 = ADVANCED_FACE('',(#149319),#149063,.F.); -#149319 = FACE_BOUND('',#149320,.T.); -#149320 = EDGE_LOOP('',(#149321,#149350,#149371,#149372)); -#149321 = ORIENTED_EDGE('',*,*,#149322,.F.); -#149322 = EDGE_CURVE('',#149323,#149325,#149327,.T.); -#149323 = VERTEX_POINT('',#149324); -#149324 = CARTESIAN_POINT('',(1.65,10.419594812019,0.530776333563)); -#149325 = VERTEX_POINT('',#149326); -#149326 = CARTESIAN_POINT('',(1.85,10.419594812019,0.530776333563)); -#149327 = SURFACE_CURVE('',#149328,(#149332,#149339),.PCURVE_S1.); -#149328 = LINE('',#149329,#149330); -#149329 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#151664 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#151665 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#151666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151667 = ORIENTED_EDGE('',*,*,#151668,.T.); +#151668 = EDGE_CURVE('',#151640,#151516,#151669,.T.); +#151669 = SURFACE_CURVE('',#151670,(#151674,#151681),.PCURVE_S1.); +#151670 = LINE('',#151671,#151672); +#151671 = CARTESIAN_POINT('',(1.85,10.51959417205,0.530776333563)); +#151672 = VECTOR('',#151673,1.); +#151673 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#151674 = PCURVE('',#151580,#151675); +#151675 = DEFINITIONAL_REPRESENTATION('',(#151676),#151680); +#151676 = LINE('',#151677,#151678); +#151677 = CARTESIAN_POINT('',(1.85,0.E+000)); +#151678 = VECTOR('',#151679,1.); +#151679 = DIRECTION('',(0.E+000,-1.)); +#151680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151681 = PCURVE('',#88978,#151682); +#151682 = DEFINITIONAL_REPRESENTATION('',(#151683),#151687); +#151683 = LINE('',#151684,#151685); +#151684 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388628E-003)); +#151685 = VECTOR('',#151686,1.); +#151686 = DIRECTION('',(-1.,0.E+000)); +#151687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151688 = ORIENTED_EDGE('',*,*,#151565,.T.); +#151689 = ORIENTED_EDGE('',*,*,#151690,.F.); +#151690 = EDGE_CURVE('',#151642,#151566,#151691,.T.); +#151691 = SURFACE_CURVE('',#151692,(#151696,#151703),.PCURVE_S1.); +#151692 = LINE('',#151693,#151694); +#151693 = CARTESIAN_POINT('',(1.65,10.51959417205,0.530776333563)); +#151694 = VECTOR('',#151695,1.); +#151695 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#151696 = PCURVE('',#151580,#151697); +#151697 = DEFINITIONAL_REPRESENTATION('',(#151698),#151702); +#151698 = LINE('',#151699,#151700); +#151699 = CARTESIAN_POINT('',(1.65,0.E+000)); +#151700 = VECTOR('',#151701,1.); +#151701 = DIRECTION('',(0.E+000,-1.)); +#151702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151703 = PCURVE('',#89034,#151704); +#151704 = DEFINITIONAL_REPRESENTATION('',(#151705),#151709); +#151705 = LINE('',#151706,#151707); +#151706 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#151707 = VECTOR('',#151708,1.); +#151708 = DIRECTION('',(1.,0.E+000)); +#151709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151710 = ADVANCED_FACE('',(#151711),#151455,.F.); +#151711 = FACE_BOUND('',#151712,.T.); +#151712 = EDGE_LOOP('',(#151713,#151742,#151763,#151764)); +#151713 = ORIENTED_EDGE('',*,*,#151714,.F.); +#151714 = EDGE_CURVE('',#151715,#151717,#151719,.T.); +#151715 = VERTEX_POINT('',#151716); +#151716 = CARTESIAN_POINT('',(1.65,10.419594812019,0.530776333563)); +#151717 = VERTEX_POINT('',#151718); +#151718 = CARTESIAN_POINT('',(1.85,10.419594812019,0.530776333563)); +#151719 = SURFACE_CURVE('',#151720,(#151724,#151731),.PCURVE_S1.); +#151720 = LINE('',#151721,#151722); +#151721 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#149330 = VECTOR('',#149331,1.); -#149331 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149332 = PCURVE('',#149063,#149333); -#149333 = DEFINITIONAL_REPRESENTATION('',(#149334),#149338); -#149334 = LINE('',#149335,#149336); -#149335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149336 = VECTOR('',#149337,1.); -#149337 = DIRECTION('',(-1.,0.E+000)); -#149338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149339 = PCURVE('',#149340,#149345); -#149340 = CYLINDRICAL_SURFACE('',#149341,0.119270391569); -#149341 = AXIS2_PLACEMENT_3D('',#149342,#149343,#149344); -#149342 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#151722 = VECTOR('',#151723,1.); +#151723 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151724 = PCURVE('',#151455,#151725); +#151725 = DEFINITIONAL_REPRESENTATION('',(#151726),#151730); +#151726 = LINE('',#151727,#151728); +#151727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#151728 = VECTOR('',#151729,1.); +#151729 = DIRECTION('',(-1.,0.E+000)); +#151730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151731 = PCURVE('',#151732,#151737); +#151732 = CYLINDRICAL_SURFACE('',#151733,0.119270391569); +#151733 = AXIS2_PLACEMENT_3D('',#151734,#151735,#151736); +#151734 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#149343 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149344 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149345 = DEFINITIONAL_REPRESENTATION('',(#149346),#149349); -#149346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149347,#149348), +#151735 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151736 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151737 = DEFINITIONAL_REPRESENTATION('',(#151738),#151741); +#151738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151739,#151740), .UNSPECIFIED.,.F.,.F.,(2,2),(1.65,1.85),.PIECEWISE_BEZIER_KNOTS.); -#149347 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#149348 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#149349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149350 = ORIENTED_EDGE('',*,*,#149351,.T.); -#149351 = EDGE_CURVE('',#149323,#149049,#149352,.T.); -#149352 = SURFACE_CURVE('',#149353,(#149357,#149364),.PCURVE_S1.); -#149353 = LINE('',#149354,#149355); -#149354 = CARTESIAN_POINT('',(1.65,10.419594812019,0.530776333563)); -#149355 = VECTOR('',#149356,1.); -#149356 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#149357 = PCURVE('',#149063,#149358); -#149358 = DEFINITIONAL_REPRESENTATION('',(#149359),#149363); -#149359 = LINE('',#149360,#149361); -#149360 = CARTESIAN_POINT('',(-1.65,0.E+000)); -#149361 = VECTOR('',#149362,1.); -#149362 = DIRECTION('',(0.E+000,-1.)); -#149363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149364 = PCURVE('',#86642,#149365); -#149365 = DEFINITIONAL_REPRESENTATION('',(#149366),#149370); -#149366 = LINE('',#149367,#149368); -#149367 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#149368 = VECTOR('',#149369,1.); -#149369 = DIRECTION('',(1.,0.E+000)); -#149370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149371 = ORIENTED_EDGE('',*,*,#149048,.T.); -#149372 = ORIENTED_EDGE('',*,*,#149373,.F.); -#149373 = EDGE_CURVE('',#149325,#148999,#149374,.T.); -#149374 = SURFACE_CURVE('',#149375,(#149379,#149386),.PCURVE_S1.); -#149375 = LINE('',#149376,#149377); -#149376 = CARTESIAN_POINT('',(1.85,10.419594812019,0.530776333563)); -#149377 = VECTOR('',#149378,1.); -#149378 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#149379 = PCURVE('',#149063,#149380); -#149380 = DEFINITIONAL_REPRESENTATION('',(#149381),#149385); -#149381 = LINE('',#149382,#149383); -#149382 = CARTESIAN_POINT('',(-1.85,0.E+000)); -#149383 = VECTOR('',#149384,1.); -#149384 = DIRECTION('',(0.E+000,-1.)); -#149385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149386 = PCURVE('',#86586,#149387); -#149387 = DEFINITIONAL_REPRESENTATION('',(#149388),#149392); -#149388 = LINE('',#149389,#149390); -#149389 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#149390 = VECTOR('',#149391,1.); -#149391 = DIRECTION('',(-1.,0.E+000)); -#149392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149393 = ADVANCED_FACE('',(#149394),#149265,.T.); -#149394 = FACE_BOUND('',#149395,.T.); -#149395 = EDGE_LOOP('',(#149396,#149442,#149443,#149493)); -#149396 = ORIENTED_EDGE('',*,*,#149397,.T.); -#149397 = EDGE_CURVE('',#149398,#149248,#149400,.T.); -#149398 = VERTEX_POINT('',#149399); -#149399 = CARTESIAN_POINT('',(1.85,10.304819755875,0.75)); -#149400 = SURFACE_CURVE('',#149401,(#149406,#149435),.PCURVE_S1.); -#149401 = CIRCLE('',#149402,0.2192697516); -#149402 = AXIS2_PLACEMENT_3D('',#149403,#149404,#149405); -#149403 = CARTESIAN_POINT('',(1.85,10.30032442045,0.530776333563)); -#149404 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149405 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149406 = PCURVE('',#149265,#149407); -#149407 = DEFINITIONAL_REPRESENTATION('',(#149408),#149434); -#149408 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149409,#149410,#149411, - #149412,#149413,#149414,#149415,#149416,#149417,#149418,#149419, - #149420,#149421,#149422,#149423,#149424,#149425,#149426,#149427, - #149428,#149429,#149430,#149431,#149432,#149433),.UNSPECIFIED.,.F., +#151739 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#151740 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#151741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151742 = ORIENTED_EDGE('',*,*,#151743,.T.); +#151743 = EDGE_CURVE('',#151715,#151441,#151744,.T.); +#151744 = SURFACE_CURVE('',#151745,(#151749,#151756),.PCURVE_S1.); +#151745 = LINE('',#151746,#151747); +#151746 = CARTESIAN_POINT('',(1.65,10.419594812019,0.530776333563)); +#151747 = VECTOR('',#151748,1.); +#151748 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#151749 = PCURVE('',#151455,#151750); +#151750 = DEFINITIONAL_REPRESENTATION('',(#151751),#151755); +#151751 = LINE('',#151752,#151753); +#151752 = CARTESIAN_POINT('',(-1.65,0.E+000)); +#151753 = VECTOR('',#151754,1.); +#151754 = DIRECTION('',(0.E+000,-1.)); +#151755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151756 = PCURVE('',#89034,#151757); +#151757 = DEFINITIONAL_REPRESENTATION('',(#151758),#151762); +#151758 = LINE('',#151759,#151760); +#151759 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#151760 = VECTOR('',#151761,1.); +#151761 = DIRECTION('',(1.,0.E+000)); +#151762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151763 = ORIENTED_EDGE('',*,*,#151440,.T.); +#151764 = ORIENTED_EDGE('',*,*,#151765,.F.); +#151765 = EDGE_CURVE('',#151717,#151391,#151766,.T.); +#151766 = SURFACE_CURVE('',#151767,(#151771,#151778),.PCURVE_S1.); +#151767 = LINE('',#151768,#151769); +#151768 = CARTESIAN_POINT('',(1.85,10.419594812019,0.530776333563)); +#151769 = VECTOR('',#151770,1.); +#151770 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#151771 = PCURVE('',#151455,#151772); +#151772 = DEFINITIONAL_REPRESENTATION('',(#151773),#151777); +#151773 = LINE('',#151774,#151775); +#151774 = CARTESIAN_POINT('',(-1.85,0.E+000)); +#151775 = VECTOR('',#151776,1.); +#151776 = DIRECTION('',(0.E+000,-1.)); +#151777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151778 = PCURVE('',#88978,#151779); +#151779 = DEFINITIONAL_REPRESENTATION('',(#151780),#151784); +#151780 = LINE('',#151781,#151782); +#151781 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#151782 = VECTOR('',#151783,1.); +#151783 = DIRECTION('',(-1.,0.E+000)); +#151784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151785 = ADVANCED_FACE('',(#151786),#151657,.T.); +#151786 = FACE_BOUND('',#151787,.T.); +#151787 = EDGE_LOOP('',(#151788,#151834,#151835,#151885)); +#151788 = ORIENTED_EDGE('',*,*,#151789,.T.); +#151789 = EDGE_CURVE('',#151790,#151640,#151792,.T.); +#151790 = VERTEX_POINT('',#151791); +#151791 = CARTESIAN_POINT('',(1.85,10.304819755875,0.75)); +#151792 = SURFACE_CURVE('',#151793,(#151798,#151827),.PCURVE_S1.); +#151793 = CIRCLE('',#151794,0.2192697516); +#151794 = AXIS2_PLACEMENT_3D('',#151795,#151796,#151797); +#151795 = CARTESIAN_POINT('',(1.85,10.30032442045,0.530776333563)); +#151796 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151797 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151798 = PCURVE('',#151657,#151799); +#151799 = DEFINITIONAL_REPRESENTATION('',(#151800),#151826); +#151800 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151801,#151802,#151803, + #151804,#151805,#151806,#151807,#151808,#151809,#151810,#151811, + #151812,#151813,#151814,#151815,#151816,#151817,#151818,#151819, + #151820,#151821,#151822,#151823,#151824,#151825),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -184267,60 +187269,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#149409 = CARTESIAN_POINT('',(1.591299156552,-1.85)); -#149410 = CARTESIAN_POINT('',(1.614788451962,-1.85)); -#149411 = CARTESIAN_POINT('',(1.661767042781,-1.85)); -#149412 = CARTESIAN_POINT('',(1.73223492901,-1.85)); -#149413 = CARTESIAN_POINT('',(1.802702815239,-1.85)); -#149414 = CARTESIAN_POINT('',(1.873170701468,-1.85)); -#149415 = CARTESIAN_POINT('',(1.943638587697,-1.85)); -#149416 = CARTESIAN_POINT('',(2.014106473926,-1.85)); -#149417 = CARTESIAN_POINT('',(2.084574360155,-1.85)); -#149418 = CARTESIAN_POINT('',(2.155042246384,-1.85)); -#149419 = CARTESIAN_POINT('',(2.225510132613,-1.85)); -#149420 = CARTESIAN_POINT('',(2.295978018842,-1.85)); -#149421 = CARTESIAN_POINT('',(2.366445905071,-1.85)); -#149422 = CARTESIAN_POINT('',(2.4369137913,-1.85)); -#149423 = CARTESIAN_POINT('',(2.507381677529,-1.85)); -#149424 = CARTESIAN_POINT('',(2.577849563758,-1.85)); -#149425 = CARTESIAN_POINT('',(2.648317449987,-1.85)); -#149426 = CARTESIAN_POINT('',(2.718785336216,-1.85)); -#149427 = CARTESIAN_POINT('',(2.789253222445,-1.85)); -#149428 = CARTESIAN_POINT('',(2.859721108674,-1.85)); -#149429 = CARTESIAN_POINT('',(2.930188994903,-1.85)); -#149430 = CARTESIAN_POINT('',(3.000656881132,-1.85)); -#149431 = CARTESIAN_POINT('',(3.071124767361,-1.85)); -#149432 = CARTESIAN_POINT('',(3.11810335818,-1.85)); -#149433 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#149434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149435 = PCURVE('',#86586,#149436); -#149436 = DEFINITIONAL_REPRESENTATION('',(#149437),#149441); -#149437 = CIRCLE('',#149438,0.2192697516); -#149438 = AXIS2_PLACEMENT_2D('',#149439,#149440); -#149439 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#149440 = DIRECTION('',(0.E+000,-1.)); -#149441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149442 = ORIENTED_EDGE('',*,*,#149247,.T.); -#149443 = ORIENTED_EDGE('',*,*,#149444,.F.); -#149444 = EDGE_CURVE('',#149445,#149250,#149447,.T.); -#149445 = VERTEX_POINT('',#149446); -#149446 = CARTESIAN_POINT('',(1.65,10.304819755875,0.75)); -#149447 = SURFACE_CURVE('',#149448,(#149453,#149482),.PCURVE_S1.); -#149448 = CIRCLE('',#149449,0.2192697516); -#149449 = AXIS2_PLACEMENT_3D('',#149450,#149451,#149452); -#149450 = CARTESIAN_POINT('',(1.65,10.30032442045,0.530776333563)); -#149451 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149452 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149453 = PCURVE('',#149265,#149454); -#149454 = DEFINITIONAL_REPRESENTATION('',(#149455),#149481); -#149455 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149456,#149457,#149458, - #149459,#149460,#149461,#149462,#149463,#149464,#149465,#149466, - #149467,#149468,#149469,#149470,#149471,#149472,#149473,#149474, - #149475,#149476,#149477,#149478,#149479,#149480),.UNSPECIFIED.,.F., +#151801 = CARTESIAN_POINT('',(1.591299156552,-1.85)); +#151802 = CARTESIAN_POINT('',(1.614788451962,-1.85)); +#151803 = CARTESIAN_POINT('',(1.661767042781,-1.85)); +#151804 = CARTESIAN_POINT('',(1.73223492901,-1.85)); +#151805 = CARTESIAN_POINT('',(1.802702815239,-1.85)); +#151806 = CARTESIAN_POINT('',(1.873170701468,-1.85)); +#151807 = CARTESIAN_POINT('',(1.943638587697,-1.85)); +#151808 = CARTESIAN_POINT('',(2.014106473926,-1.85)); +#151809 = CARTESIAN_POINT('',(2.084574360155,-1.85)); +#151810 = CARTESIAN_POINT('',(2.155042246384,-1.85)); +#151811 = CARTESIAN_POINT('',(2.225510132613,-1.85)); +#151812 = CARTESIAN_POINT('',(2.295978018842,-1.85)); +#151813 = CARTESIAN_POINT('',(2.366445905071,-1.85)); +#151814 = CARTESIAN_POINT('',(2.4369137913,-1.85)); +#151815 = CARTESIAN_POINT('',(2.507381677529,-1.85)); +#151816 = CARTESIAN_POINT('',(2.577849563758,-1.85)); +#151817 = CARTESIAN_POINT('',(2.648317449987,-1.85)); +#151818 = CARTESIAN_POINT('',(2.718785336216,-1.85)); +#151819 = CARTESIAN_POINT('',(2.789253222445,-1.85)); +#151820 = CARTESIAN_POINT('',(2.859721108674,-1.85)); +#151821 = CARTESIAN_POINT('',(2.930188994903,-1.85)); +#151822 = CARTESIAN_POINT('',(3.000656881132,-1.85)); +#151823 = CARTESIAN_POINT('',(3.071124767361,-1.85)); +#151824 = CARTESIAN_POINT('',(3.11810335818,-1.85)); +#151825 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#151826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151827 = PCURVE('',#88978,#151828); +#151828 = DEFINITIONAL_REPRESENTATION('',(#151829),#151833); +#151829 = CIRCLE('',#151830,0.2192697516); +#151830 = AXIS2_PLACEMENT_2D('',#151831,#151832); +#151831 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#151832 = DIRECTION('',(0.E+000,-1.)); +#151833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151834 = ORIENTED_EDGE('',*,*,#151639,.T.); +#151835 = ORIENTED_EDGE('',*,*,#151836,.F.); +#151836 = EDGE_CURVE('',#151837,#151642,#151839,.T.); +#151837 = VERTEX_POINT('',#151838); +#151838 = CARTESIAN_POINT('',(1.65,10.304819755875,0.75)); +#151839 = SURFACE_CURVE('',#151840,(#151845,#151874),.PCURVE_S1.); +#151840 = CIRCLE('',#151841,0.2192697516); +#151841 = AXIS2_PLACEMENT_3D('',#151842,#151843,#151844); +#151842 = CARTESIAN_POINT('',(1.65,10.30032442045,0.530776333563)); +#151843 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151844 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151845 = PCURVE('',#151657,#151846); +#151846 = DEFINITIONAL_REPRESENTATION('',(#151847),#151873); +#151847 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151848,#151849,#151850, + #151851,#151852,#151853,#151854,#151855,#151856,#151857,#151858, + #151859,#151860,#151861,#151862,#151863,#151864,#151865,#151866, + #151867,#151868,#151869,#151870,#151871,#151872),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -184328,98 +187330,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#149456 = CARTESIAN_POINT('',(1.591299156552,-1.65)); -#149457 = CARTESIAN_POINT('',(1.614788451962,-1.65)); -#149458 = CARTESIAN_POINT('',(1.661767042781,-1.65)); -#149459 = CARTESIAN_POINT('',(1.73223492901,-1.65)); -#149460 = CARTESIAN_POINT('',(1.802702815239,-1.65)); -#149461 = CARTESIAN_POINT('',(1.873170701468,-1.65)); -#149462 = CARTESIAN_POINT('',(1.943638587697,-1.65)); -#149463 = CARTESIAN_POINT('',(2.014106473926,-1.65)); -#149464 = CARTESIAN_POINT('',(2.084574360155,-1.65)); -#149465 = CARTESIAN_POINT('',(2.155042246384,-1.65)); -#149466 = CARTESIAN_POINT('',(2.225510132613,-1.65)); -#149467 = CARTESIAN_POINT('',(2.295978018842,-1.65)); -#149468 = CARTESIAN_POINT('',(2.366445905071,-1.65)); -#149469 = CARTESIAN_POINT('',(2.4369137913,-1.65)); -#149470 = CARTESIAN_POINT('',(2.507381677529,-1.65)); -#149471 = CARTESIAN_POINT('',(2.577849563758,-1.65)); -#149472 = CARTESIAN_POINT('',(2.648317449987,-1.65)); -#149473 = CARTESIAN_POINT('',(2.718785336216,-1.65)); -#149474 = CARTESIAN_POINT('',(2.789253222445,-1.65)); -#149475 = CARTESIAN_POINT('',(2.859721108674,-1.65)); -#149476 = CARTESIAN_POINT('',(2.930188994903,-1.65)); -#149477 = CARTESIAN_POINT('',(3.000656881132,-1.65)); -#149478 = CARTESIAN_POINT('',(3.071124767361,-1.65)); -#149479 = CARTESIAN_POINT('',(3.11810335818,-1.65)); -#149480 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#149481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149482 = PCURVE('',#86642,#149483); -#149483 = DEFINITIONAL_REPRESENTATION('',(#149484),#149492); -#149484 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149485,#149486,#149487, - #149488,#149489,#149490,#149491),.UNSPECIFIED.,.T.,.F.) +#151848 = CARTESIAN_POINT('',(1.591299156552,-1.65)); +#151849 = CARTESIAN_POINT('',(1.614788451962,-1.65)); +#151850 = CARTESIAN_POINT('',(1.661767042781,-1.65)); +#151851 = CARTESIAN_POINT('',(1.73223492901,-1.65)); +#151852 = CARTESIAN_POINT('',(1.802702815239,-1.65)); +#151853 = CARTESIAN_POINT('',(1.873170701468,-1.65)); +#151854 = CARTESIAN_POINT('',(1.943638587697,-1.65)); +#151855 = CARTESIAN_POINT('',(2.014106473926,-1.65)); +#151856 = CARTESIAN_POINT('',(2.084574360155,-1.65)); +#151857 = CARTESIAN_POINT('',(2.155042246384,-1.65)); +#151858 = CARTESIAN_POINT('',(2.225510132613,-1.65)); +#151859 = CARTESIAN_POINT('',(2.295978018842,-1.65)); +#151860 = CARTESIAN_POINT('',(2.366445905071,-1.65)); +#151861 = CARTESIAN_POINT('',(2.4369137913,-1.65)); +#151862 = CARTESIAN_POINT('',(2.507381677529,-1.65)); +#151863 = CARTESIAN_POINT('',(2.577849563758,-1.65)); +#151864 = CARTESIAN_POINT('',(2.648317449987,-1.65)); +#151865 = CARTESIAN_POINT('',(2.718785336216,-1.65)); +#151866 = CARTESIAN_POINT('',(2.789253222445,-1.65)); +#151867 = CARTESIAN_POINT('',(2.859721108674,-1.65)); +#151868 = CARTESIAN_POINT('',(2.930188994903,-1.65)); +#151869 = CARTESIAN_POINT('',(3.000656881132,-1.65)); +#151870 = CARTESIAN_POINT('',(3.071124767361,-1.65)); +#151871 = CARTESIAN_POINT('',(3.11810335818,-1.65)); +#151872 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#151873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151874 = PCURVE('',#89034,#151875); +#151875 = DEFINITIONAL_REPRESENTATION('',(#151876),#151884); +#151876 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#151877,#151878,#151879, + #151880,#151881,#151882,#151883),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#149485 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#149486 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#149487 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#149488 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#149489 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#149490 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#149491 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#149492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149493 = ORIENTED_EDGE('',*,*,#149494,.T.); -#149494 = EDGE_CURVE('',#149445,#149398,#149495,.T.); -#149495 = SURFACE_CURVE('',#149496,(#149500,#149506),.PCURVE_S1.); -#149496 = LINE('',#149497,#149498); -#149497 = CARTESIAN_POINT('',(1.85,10.304819755875,0.75)); -#149498 = VECTOR('',#149499,1.); -#149499 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149500 = PCURVE('',#149265,#149501); -#149501 = DEFINITIONAL_REPRESENTATION('',(#149502),#149505); -#149502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149503,#149504), +#151877 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#151878 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#151879 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#151880 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#151881 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#151882 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#151883 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#151884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151885 = ORIENTED_EDGE('',*,*,#151886,.T.); +#151886 = EDGE_CURVE('',#151837,#151790,#151887,.T.); +#151887 = SURFACE_CURVE('',#151888,(#151892,#151898),.PCURVE_S1.); +#151888 = LINE('',#151889,#151890); +#151889 = CARTESIAN_POINT('',(1.85,10.304819755875,0.75)); +#151890 = VECTOR('',#151891,1.); +#151891 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#151892 = PCURVE('',#151657,#151893); +#151893 = DEFINITIONAL_REPRESENTATION('',(#151894),#151897); +#151894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151895,#151896), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,2.22044604925E-016), .PIECEWISE_BEZIER_KNOTS.); -#149503 = CARTESIAN_POINT('',(1.591299156552,-1.65)); -#149504 = CARTESIAN_POINT('',(1.591299156552,-1.85)); -#149505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149506 = PCURVE('',#86614,#149507); -#149507 = DEFINITIONAL_REPRESENTATION('',(#149508),#149512); -#149508 = LINE('',#149509,#149510); -#149509 = CARTESIAN_POINT('',(-0.223028236564,-2.22044604925E-016)); -#149510 = VECTOR('',#149511,1.); -#149511 = DIRECTION('',(-8.881784197001E-016,1.)); -#149512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149513 = ADVANCED_FACE('',(#149514),#149340,.F.); -#149514 = FACE_BOUND('',#149515,.F.); -#149515 = EDGE_LOOP('',(#149516,#149566,#149588,#149632)); -#149516 = ORIENTED_EDGE('',*,*,#149517,.F.); -#149517 = EDGE_CURVE('',#149518,#149323,#149520,.T.); -#149518 = VERTEX_POINT('',#149519); -#149519 = CARTESIAN_POINT('',(1.65,10.303662633502,0.65)); -#149520 = SURFACE_CURVE('',#149521,(#149526,#149555),.PCURVE_S1.); -#149521 = CIRCLE('',#149522,0.119270391569); -#149522 = AXIS2_PLACEMENT_3D('',#149523,#149524,#149525); -#149523 = CARTESIAN_POINT('',(1.65,10.30032442045,0.530776333563)); -#149524 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149525 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149526 = PCURVE('',#149340,#149527); -#149527 = DEFINITIONAL_REPRESENTATION('',(#149528),#149554); -#149528 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149529,#149530,#149531, - #149532,#149533,#149534,#149535,#149536,#149537,#149538,#149539, - #149540,#149541,#149542,#149543,#149544,#149545,#149546,#149547, - #149548,#149549,#149550,#149551,#149552,#149553),.UNSPECIFIED.,.F., +#151895 = CARTESIAN_POINT('',(1.591299156552,-1.65)); +#151896 = CARTESIAN_POINT('',(1.591299156552,-1.85)); +#151897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151898 = PCURVE('',#89006,#151899); +#151899 = DEFINITIONAL_REPRESENTATION('',(#151900),#151904); +#151900 = LINE('',#151901,#151902); +#151901 = CARTESIAN_POINT('',(-0.223028236564,-2.22044604925E-016)); +#151902 = VECTOR('',#151903,1.); +#151903 = DIRECTION('',(-8.881784197001E-016,1.)); +#151904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151905 = ADVANCED_FACE('',(#151906),#151732,.F.); +#151906 = FACE_BOUND('',#151907,.F.); +#151907 = EDGE_LOOP('',(#151908,#151958,#151980,#152024)); +#151908 = ORIENTED_EDGE('',*,*,#151909,.F.); +#151909 = EDGE_CURVE('',#151910,#151715,#151912,.T.); +#151910 = VERTEX_POINT('',#151911); +#151911 = CARTESIAN_POINT('',(1.65,10.303662633502,0.65)); +#151912 = SURFACE_CURVE('',#151913,(#151918,#151947),.PCURVE_S1.); +#151913 = CIRCLE('',#151914,0.119270391569); +#151914 = AXIS2_PLACEMENT_3D('',#151915,#151916,#151917); +#151915 = CARTESIAN_POINT('',(1.65,10.30032442045,0.530776333563)); +#151916 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151917 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151918 = PCURVE('',#151732,#151919); +#151919 = DEFINITIONAL_REPRESENTATION('',(#151920),#151946); +#151920 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151921,#151922,#151923, + #151924,#151925,#151926,#151927,#151928,#151929,#151930,#151931, + #151932,#151933,#151934,#151935,#151936,#151937,#151938,#151939, + #151940,#151941,#151942,#151943,#151944,#151945),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.598788597134, 1.668916054246,1.739043511357,1.809170968469,1.879298425581, 1.949425882692,2.019553339804,2.089680796916,2.159808254027, @@ -184427,94 +187429,94 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.510445539585,2.580572996697,2.650700453808,2.72082791092, 2.790955368032,2.861082825143,2.931210282255,3.001337739367, 3.071465196478,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#149529 = CARTESIAN_POINT('',(1.598788597134,-1.65)); -#149530 = CARTESIAN_POINT('',(1.622164416171,-1.65)); -#149531 = CARTESIAN_POINT('',(1.668916054246,-1.65)); -#149532 = CARTESIAN_POINT('',(1.739043511357,-1.65)); -#149533 = CARTESIAN_POINT('',(1.809170968469,-1.65)); -#149534 = CARTESIAN_POINT('',(1.879298425581,-1.65)); -#149535 = CARTESIAN_POINT('',(1.949425882692,-1.65)); -#149536 = CARTESIAN_POINT('',(2.019553339804,-1.65)); -#149537 = CARTESIAN_POINT('',(2.089680796916,-1.65)); -#149538 = CARTESIAN_POINT('',(2.159808254027,-1.65)); -#149539 = CARTESIAN_POINT('',(2.229935711139,-1.65)); -#149540 = CARTESIAN_POINT('',(2.30006316825,-1.65)); -#149541 = CARTESIAN_POINT('',(2.370190625362,-1.65)); -#149542 = CARTESIAN_POINT('',(2.440318082474,-1.65)); -#149543 = CARTESIAN_POINT('',(2.510445539585,-1.65)); -#149544 = CARTESIAN_POINT('',(2.580572996697,-1.65)); -#149545 = CARTESIAN_POINT('',(2.650700453808,-1.65)); -#149546 = CARTESIAN_POINT('',(2.72082791092,-1.65)); -#149547 = CARTESIAN_POINT('',(2.790955368032,-1.65)); -#149548 = CARTESIAN_POINT('',(2.861082825143,-1.65)); -#149549 = CARTESIAN_POINT('',(2.931210282255,-1.65)); -#149550 = CARTESIAN_POINT('',(3.001337739367,-1.65)); -#149551 = CARTESIAN_POINT('',(3.071465196478,-1.65)); -#149552 = CARTESIAN_POINT('',(3.118216834553,-1.65)); -#149553 = CARTESIAN_POINT('',(3.14159265359,-1.65)); -#149554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149555 = PCURVE('',#86642,#149556); -#149556 = DEFINITIONAL_REPRESENTATION('',(#149557),#149565); -#149557 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#149558,#149559,#149560, - #149561,#149562,#149563,#149564),.UNSPECIFIED.,.T.,.F.) +#151921 = CARTESIAN_POINT('',(1.598788597134,-1.65)); +#151922 = CARTESIAN_POINT('',(1.622164416171,-1.65)); +#151923 = CARTESIAN_POINT('',(1.668916054246,-1.65)); +#151924 = CARTESIAN_POINT('',(1.739043511357,-1.65)); +#151925 = CARTESIAN_POINT('',(1.809170968469,-1.65)); +#151926 = CARTESIAN_POINT('',(1.879298425581,-1.65)); +#151927 = CARTESIAN_POINT('',(1.949425882692,-1.65)); +#151928 = CARTESIAN_POINT('',(2.019553339804,-1.65)); +#151929 = CARTESIAN_POINT('',(2.089680796916,-1.65)); +#151930 = CARTESIAN_POINT('',(2.159808254027,-1.65)); +#151931 = CARTESIAN_POINT('',(2.229935711139,-1.65)); +#151932 = CARTESIAN_POINT('',(2.30006316825,-1.65)); +#151933 = CARTESIAN_POINT('',(2.370190625362,-1.65)); +#151934 = CARTESIAN_POINT('',(2.440318082474,-1.65)); +#151935 = CARTESIAN_POINT('',(2.510445539585,-1.65)); +#151936 = CARTESIAN_POINT('',(2.580572996697,-1.65)); +#151937 = CARTESIAN_POINT('',(2.650700453808,-1.65)); +#151938 = CARTESIAN_POINT('',(2.72082791092,-1.65)); +#151939 = CARTESIAN_POINT('',(2.790955368032,-1.65)); +#151940 = CARTESIAN_POINT('',(2.861082825143,-1.65)); +#151941 = CARTESIAN_POINT('',(2.931210282255,-1.65)); +#151942 = CARTESIAN_POINT('',(3.001337739367,-1.65)); +#151943 = CARTESIAN_POINT('',(3.071465196478,-1.65)); +#151944 = CARTESIAN_POINT('',(3.118216834553,-1.65)); +#151945 = CARTESIAN_POINT('',(3.14159265359,-1.65)); +#151946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151947 = PCURVE('',#89034,#151948); +#151948 = DEFINITIONAL_REPRESENTATION('',(#151949),#151957); +#151949 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#151950,#151951,#151952, + #151953,#151954,#151955,#151956),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#149558 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#149559 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#149560 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#149561 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#149562 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#149563 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#149564 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#149565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149566 = ORIENTED_EDGE('',*,*,#149567,.F.); -#149567 = EDGE_CURVE('',#149568,#149518,#149570,.T.); -#149568 = VERTEX_POINT('',#149569); -#149569 = CARTESIAN_POINT('',(1.85,10.303662633502,0.65)); -#149570 = SURFACE_CURVE('',#149571,(#149575,#149581),.PCURVE_S1.); -#149571 = LINE('',#149572,#149573); -#149572 = CARTESIAN_POINT('',(1.85,10.303662633502,0.65)); -#149573 = VECTOR('',#149574,1.); -#149574 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149575 = PCURVE('',#149340,#149576); -#149576 = DEFINITIONAL_REPRESENTATION('',(#149577),#149580); -#149577 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149578,#149579), +#151950 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#151951 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#151952 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#151953 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#151954 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#151955 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#151956 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#151957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151958 = ORIENTED_EDGE('',*,*,#151959,.F.); +#151959 = EDGE_CURVE('',#151960,#151910,#151962,.T.); +#151960 = VERTEX_POINT('',#151961); +#151961 = CARTESIAN_POINT('',(1.85,10.303662633502,0.65)); +#151962 = SURFACE_CURVE('',#151963,(#151967,#151973),.PCURVE_S1.); +#151963 = LINE('',#151964,#151965); +#151964 = CARTESIAN_POINT('',(1.85,10.303662633502,0.65)); +#151965 = VECTOR('',#151966,1.); +#151966 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151967 = PCURVE('',#151732,#151968); +#151968 = DEFINITIONAL_REPRESENTATION('',(#151969),#151972); +#151969 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151970,#151971), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#149578 = CARTESIAN_POINT('',(1.598788597134,-1.85)); -#149579 = CARTESIAN_POINT('',(1.598788597134,-1.65)); -#149580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149581 = PCURVE('',#86668,#149582); -#149582 = DEFINITIONAL_REPRESENTATION('',(#149583),#149587); -#149583 = LINE('',#149584,#149585); -#149584 = CARTESIAN_POINT('',(0.224185358936,-2.22044604925E-016)); -#149585 = VECTOR('',#149586,1.); -#149586 = DIRECTION('',(-8.881784197001E-016,-1.)); -#149587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149588 = ORIENTED_EDGE('',*,*,#149589,.T.); -#149589 = EDGE_CURVE('',#149568,#149325,#149590,.T.); -#149590 = SURFACE_CURVE('',#149591,(#149596,#149625),.PCURVE_S1.); -#149591 = CIRCLE('',#149592,0.119270391569); -#149592 = AXIS2_PLACEMENT_3D('',#149593,#149594,#149595); -#149593 = CARTESIAN_POINT('',(1.85,10.30032442045,0.530776333563)); -#149594 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149595 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#149596 = PCURVE('',#149340,#149597); -#149597 = DEFINITIONAL_REPRESENTATION('',(#149598),#149624); -#149598 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#149599,#149600,#149601, - #149602,#149603,#149604,#149605,#149606,#149607,#149608,#149609, - #149610,#149611,#149612,#149613,#149614,#149615,#149616,#149617, - #149618,#149619,#149620,#149621,#149622,#149623),.UNSPECIFIED.,.F., +#151970 = CARTESIAN_POINT('',(1.598788597134,-1.85)); +#151971 = CARTESIAN_POINT('',(1.598788597134,-1.65)); +#151972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151973 = PCURVE('',#89060,#151974); +#151974 = DEFINITIONAL_REPRESENTATION('',(#151975),#151979); +#151975 = LINE('',#151976,#151977); +#151976 = CARTESIAN_POINT('',(0.224185358936,-2.22044604925E-016)); +#151977 = VECTOR('',#151978,1.); +#151978 = DIRECTION('',(-8.881784197001E-016,-1.)); +#151979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#151980 = ORIENTED_EDGE('',*,*,#151981,.T.); +#151981 = EDGE_CURVE('',#151960,#151717,#151982,.T.); +#151982 = SURFACE_CURVE('',#151983,(#151988,#152017),.PCURVE_S1.); +#151983 = CIRCLE('',#151984,0.119270391569); +#151984 = AXIS2_PLACEMENT_3D('',#151985,#151986,#151987); +#151985 = CARTESIAN_POINT('',(1.85,10.30032442045,0.530776333563)); +#151986 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#151987 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#151988 = PCURVE('',#151732,#151989); +#151989 = DEFINITIONAL_REPRESENTATION('',(#151990),#152016); +#151990 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#151991,#151992,#151993, + #151994,#151995,#151996,#151997,#151998,#151999,#152000,#152001, + #152002,#152003,#152004,#152005,#152006,#152007,#152008,#152009, + #152010,#152011,#152012,#152013,#152014,#152015),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.598788597134, 1.668916054246,1.739043511357,1.809170968469,1.879298425581, 1.949425882692,2.019553339804,2.089680796916,2.159808254027, @@ -184522,515 +187524,515 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.510445539585,2.580572996697,2.650700453808,2.72082791092, 2.790955368032,2.861082825143,2.931210282255,3.001337739367, 3.071465196478,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#149599 = CARTESIAN_POINT('',(1.598788597134,-1.85)); -#149600 = CARTESIAN_POINT('',(1.622164416171,-1.85)); -#149601 = CARTESIAN_POINT('',(1.668916054246,-1.85)); -#149602 = CARTESIAN_POINT('',(1.739043511357,-1.85)); -#149603 = CARTESIAN_POINT('',(1.809170968469,-1.85)); -#149604 = CARTESIAN_POINT('',(1.879298425581,-1.85)); -#149605 = CARTESIAN_POINT('',(1.949425882692,-1.85)); -#149606 = CARTESIAN_POINT('',(2.019553339804,-1.85)); -#149607 = CARTESIAN_POINT('',(2.089680796916,-1.85)); -#149608 = CARTESIAN_POINT('',(2.159808254027,-1.85)); -#149609 = CARTESIAN_POINT('',(2.229935711139,-1.85)); -#149610 = CARTESIAN_POINT('',(2.30006316825,-1.85)); -#149611 = CARTESIAN_POINT('',(2.370190625362,-1.85)); -#149612 = CARTESIAN_POINT('',(2.440318082474,-1.85)); -#149613 = CARTESIAN_POINT('',(2.510445539585,-1.85)); -#149614 = CARTESIAN_POINT('',(2.580572996697,-1.85)); -#149615 = CARTESIAN_POINT('',(2.650700453808,-1.85)); -#149616 = CARTESIAN_POINT('',(2.72082791092,-1.85)); -#149617 = CARTESIAN_POINT('',(2.790955368032,-1.85)); -#149618 = CARTESIAN_POINT('',(2.861082825143,-1.85)); -#149619 = CARTESIAN_POINT('',(2.931210282255,-1.85)); -#149620 = CARTESIAN_POINT('',(3.001337739367,-1.85)); -#149621 = CARTESIAN_POINT('',(3.071465196478,-1.85)); -#149622 = CARTESIAN_POINT('',(3.118216834553,-1.85)); -#149623 = CARTESIAN_POINT('',(3.14159265359,-1.85)); -#149624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149625 = PCURVE('',#86586,#149626); -#149626 = DEFINITIONAL_REPRESENTATION('',(#149627),#149631); -#149627 = CIRCLE('',#149628,0.119270391569); -#149628 = AXIS2_PLACEMENT_2D('',#149629,#149630); -#149629 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#149630 = DIRECTION('',(0.E+000,-1.)); -#149631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149632 = ORIENTED_EDGE('',*,*,#149322,.F.); -#149633 = ADVANCED_FACE('',(#149634),#86586,.F.); -#149634 = FACE_BOUND('',#149635,.T.); -#149635 = EDGE_LOOP('',(#149636,#149657,#149658,#149659,#149660,#149661, - #149682,#149683,#149684,#149685,#149686,#149707)); -#149636 = ORIENTED_EDGE('',*,*,#149637,.F.); -#149637 = EDGE_CURVE('',#149568,#86571,#149638,.T.); -#149638 = SURFACE_CURVE('',#149639,(#149643,#149650),.PCURVE_S1.); -#149639 = LINE('',#149640,#149641); -#149640 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); -#149641 = VECTOR('',#149642,1.); -#149642 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#149643 = PCURVE('',#86586,#149644); -#149644 = DEFINITIONAL_REPRESENTATION('',(#149645),#149649); -#149645 = LINE('',#149646,#149647); -#149646 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149647 = VECTOR('',#149648,1.); -#149648 = DIRECTION('',(3.563627120235E-016,-1.)); -#149649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149650 = PCURVE('',#86668,#149651); -#149651 = DEFINITIONAL_REPRESENTATION('',(#149652),#149656); -#149652 = LINE('',#149653,#149654); -#149653 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149654 = VECTOR('',#149655,1.); -#149655 = DIRECTION('',(1.,2.164989446033E-063)); -#149656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149657 = ORIENTED_EDGE('',*,*,#149589,.T.); -#149658 = ORIENTED_EDGE('',*,*,#149373,.T.); -#149659 = ORIENTED_EDGE('',*,*,#148998,.T.); -#149660 = ORIENTED_EDGE('',*,*,#148842,.T.); -#149661 = ORIENTED_EDGE('',*,*,#149662,.T.); -#149662 = EDGE_CURVE('',#148815,#148896,#149663,.T.); -#149663 = SURFACE_CURVE('',#149664,(#149668,#149675),.PCURVE_S1.); -#149664 = LINE('',#149665,#149666); -#149665 = CARTESIAN_POINT('',(1.85,11.,1.159810404338E-002)); -#149666 = VECTOR('',#149667,1.); -#149667 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#149668 = PCURVE('',#86586,#149669); -#149669 = DEFINITIONAL_REPRESENTATION('',(#149670),#149674); -#149670 = LINE('',#149671,#149672); -#149671 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#149672 = VECTOR('',#149673,1.); -#149673 = DIRECTION('',(1.,2.101748079665E-016)); -#149674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149675 = PCURVE('',#148830,#149676); -#149676 = DEFINITIONAL_REPRESENTATION('',(#149677),#149681); -#149677 = LINE('',#149678,#149679); -#149678 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#149679 = VECTOR('',#149680,1.); -#149680 = DIRECTION('',(-1.570395187386E-016,1.)); -#149681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#151991 = CARTESIAN_POINT('',(1.598788597134,-1.85)); +#151992 = CARTESIAN_POINT('',(1.622164416171,-1.85)); +#151993 = CARTESIAN_POINT('',(1.668916054246,-1.85)); +#151994 = CARTESIAN_POINT('',(1.739043511357,-1.85)); +#151995 = CARTESIAN_POINT('',(1.809170968469,-1.85)); +#151996 = CARTESIAN_POINT('',(1.879298425581,-1.85)); +#151997 = CARTESIAN_POINT('',(1.949425882692,-1.85)); +#151998 = CARTESIAN_POINT('',(2.019553339804,-1.85)); +#151999 = CARTESIAN_POINT('',(2.089680796916,-1.85)); +#152000 = CARTESIAN_POINT('',(2.159808254027,-1.85)); +#152001 = CARTESIAN_POINT('',(2.229935711139,-1.85)); +#152002 = CARTESIAN_POINT('',(2.30006316825,-1.85)); +#152003 = CARTESIAN_POINT('',(2.370190625362,-1.85)); +#152004 = CARTESIAN_POINT('',(2.440318082474,-1.85)); +#152005 = CARTESIAN_POINT('',(2.510445539585,-1.85)); +#152006 = CARTESIAN_POINT('',(2.580572996697,-1.85)); +#152007 = CARTESIAN_POINT('',(2.650700453808,-1.85)); +#152008 = CARTESIAN_POINT('',(2.72082791092,-1.85)); +#152009 = CARTESIAN_POINT('',(2.790955368032,-1.85)); +#152010 = CARTESIAN_POINT('',(2.861082825143,-1.85)); +#152011 = CARTESIAN_POINT('',(2.931210282255,-1.85)); +#152012 = CARTESIAN_POINT('',(3.001337739367,-1.85)); +#152013 = CARTESIAN_POINT('',(3.071465196478,-1.85)); +#152014 = CARTESIAN_POINT('',(3.118216834553,-1.85)); +#152015 = CARTESIAN_POINT('',(3.14159265359,-1.85)); +#152016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152017 = PCURVE('',#88978,#152018); +#152018 = DEFINITIONAL_REPRESENTATION('',(#152019),#152023); +#152019 = CIRCLE('',#152020,0.119270391569); +#152020 = AXIS2_PLACEMENT_2D('',#152021,#152022); +#152021 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#152022 = DIRECTION('',(0.E+000,-1.)); +#152023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152024 = ORIENTED_EDGE('',*,*,#151714,.F.); +#152025 = ADVANCED_FACE('',(#152026),#88978,.F.); +#152026 = FACE_BOUND('',#152027,.T.); +#152027 = EDGE_LOOP('',(#152028,#152049,#152050,#152051,#152052,#152053, + #152074,#152075,#152076,#152077,#152078,#152099)); +#152028 = ORIENTED_EDGE('',*,*,#152029,.F.); +#152029 = EDGE_CURVE('',#151960,#88963,#152030,.T.); +#152030 = SURFACE_CURVE('',#152031,(#152035,#152042),.PCURVE_S1.); +#152031 = LINE('',#152032,#152033); +#152032 = CARTESIAN_POINT('',(1.85,10.527847992439,0.65)); +#152033 = VECTOR('',#152034,1.); +#152034 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#152035 = PCURVE('',#88978,#152036); +#152036 = DEFINITIONAL_REPRESENTATION('',(#152037),#152041); +#152037 = LINE('',#152038,#152039); +#152038 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152039 = VECTOR('',#152040,1.); +#152040 = DIRECTION('',(3.563627120235E-016,-1.)); +#152041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152042 = PCURVE('',#89060,#152043); +#152043 = DEFINITIONAL_REPRESENTATION('',(#152044),#152048); +#152044 = LINE('',#152045,#152046); +#152045 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152046 = VECTOR('',#152047,1.); +#152047 = DIRECTION('',(1.,2.164989446033E-063)); +#152048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152049 = ORIENTED_EDGE('',*,*,#151981,.T.); +#152050 = ORIENTED_EDGE('',*,*,#151765,.T.); +#152051 = ORIENTED_EDGE('',*,*,#151390,.T.); +#152052 = ORIENTED_EDGE('',*,*,#151234,.T.); +#152053 = ORIENTED_EDGE('',*,*,#152054,.T.); +#152054 = EDGE_CURVE('',#151207,#151288,#152055,.T.); +#152055 = SURFACE_CURVE('',#152056,(#152060,#152067),.PCURVE_S1.); +#152056 = LINE('',#152057,#152058); +#152057 = CARTESIAN_POINT('',(1.85,11.,1.159810404338E-002)); +#152058 = VECTOR('',#152059,1.); +#152059 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#152060 = PCURVE('',#88978,#152061); +#152061 = DEFINITIONAL_REPRESENTATION('',(#152062),#152066); +#152062 = LINE('',#152063,#152064); +#152063 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#152064 = VECTOR('',#152065,1.); +#152065 = DIRECTION('',(1.,2.101748079665E-016)); +#152066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152067 = PCURVE('',#151222,#152068); +#152068 = DEFINITIONAL_REPRESENTATION('',(#152069),#152073); +#152069 = LINE('',#152070,#152071); +#152070 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#152071 = VECTOR('',#152072,1.); +#152072 = DIRECTION('',(-1.570395187386E-016,1.)); +#152073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152074 = ORIENTED_EDGE('',*,*,#151285,.F.); +#152075 = ORIENTED_EDGE('',*,*,#151515,.F.); +#152076 = ORIENTED_EDGE('',*,*,#151668,.F.); +#152077 = ORIENTED_EDGE('',*,*,#151789,.F.); +#152078 = ORIENTED_EDGE('',*,*,#152079,.T.); +#152079 = EDGE_CURVE('',#151790,#88961,#152080,.T.); +#152080 = SURFACE_CURVE('',#152081,(#152085,#152092),.PCURVE_S1.); +#152081 = LINE('',#152082,#152083); +#152082 = CARTESIAN_POINT('',(1.85,10.527847992439,0.75)); +#152083 = VECTOR('',#152084,1.); +#152084 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#152085 = PCURVE('',#88978,#152086); +#152086 = DEFINITIONAL_REPRESENTATION('',(#152087),#152091); +#152087 = LINE('',#152088,#152089); +#152088 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#152089 = VECTOR('',#152090,1.); +#152090 = DIRECTION('',(3.563627120235E-016,-1.)); +#152091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152092 = PCURVE('',#89006,#152093); +#152093 = DEFINITIONAL_REPRESENTATION('',(#152094),#152098); +#152094 = LINE('',#152095,#152096); +#152095 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152096 = VECTOR('',#152097,1.); +#152097 = DIRECTION('',(-1.,2.164989446033E-063)); +#152098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152099 = ORIENTED_EDGE('',*,*,#88960,.T.); +#152100 = ADVANCED_FACE('',(#152101),#89006,.F.); +#152101 = FACE_BOUND('',#152102,.T.); +#152102 = EDGE_LOOP('',(#152103,#152104,#152125,#152126)); +#152103 = ORIENTED_EDGE('',*,*,#151886,.F.); +#152104 = ORIENTED_EDGE('',*,*,#152105,.T.); +#152105 = EDGE_CURVE('',#151837,#88991,#152106,.T.); +#152106 = SURFACE_CURVE('',#152107,(#152111,#152118),.PCURVE_S1.); +#152107 = LINE('',#152108,#152109); +#152108 = CARTESIAN_POINT('',(1.65,10.527847992439,0.75)); +#152109 = VECTOR('',#152110,1.); +#152110 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#152111 = PCURVE('',#89006,#152112); +#152112 = DEFINITIONAL_REPRESENTATION('',(#152113),#152117); +#152113 = LINE('',#152114,#152115); +#152114 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#152115 = VECTOR('',#152116,1.); +#152116 = DIRECTION('',(-1.,2.164989446033E-063)); +#152117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152118 = PCURVE('',#89034,#152119); +#152119 = DEFINITIONAL_REPRESENTATION('',(#152120),#152124); +#152120 = LINE('',#152121,#152122); +#152121 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#152122 = VECTOR('',#152123,1.); +#152123 = DIRECTION('',(-3.563627120235E-016,-1.)); +#152124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152125 = ORIENTED_EDGE('',*,*,#88990,.T.); +#152126 = ORIENTED_EDGE('',*,*,#152079,.F.); +#152127 = ADVANCED_FACE('',(#152128),#89034,.F.); +#152128 = FACE_BOUND('',#152129,.T.); +#152129 = EDGE_LOOP('',(#152130,#152131,#152132,#152133,#152134,#152135, + #152156,#152157,#152158,#152159,#152160,#152181)); +#152130 = ORIENTED_EDGE('',*,*,#152105,.F.); +#152131 = ORIENTED_EDGE('',*,*,#151836,.T.); +#152132 = ORIENTED_EDGE('',*,*,#151690,.T.); +#152133 = ORIENTED_EDGE('',*,*,#151592,.T.); +#152134 = ORIENTED_EDGE('',*,*,#151338,.T.); +#152135 = ORIENTED_EDGE('',*,*,#152136,.T.); +#152136 = EDGE_CURVE('',#151316,#151179,#152137,.T.); +#152137 = SURFACE_CURVE('',#152138,(#152142,#152149),.PCURVE_S1.); +#152138 = LINE('',#152139,#152140); +#152139 = CARTESIAN_POINT('',(1.65,11.,1.159810404338E-002)); +#152140 = VECTOR('',#152141,1.); +#152141 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#152142 = PCURVE('',#89034,#152143); +#152143 = DEFINITIONAL_REPRESENTATION('',(#152144),#152148); +#152144 = LINE('',#152145,#152146); +#152145 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#152146 = VECTOR('',#152147,1.); +#152147 = DIRECTION('',(1.,-2.101748079665E-016)); +#152148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152149 = PCURVE('',#151222,#152150); +#152150 = DEFINITIONAL_REPRESENTATION('',(#152151),#152155); +#152151 = LINE('',#152152,#152153); +#152152 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#152153 = VECTOR('',#152154,1.); +#152154 = DIRECTION('',(1.570395187386E-016,-1.)); +#152155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152156 = ORIENTED_EDGE('',*,*,#151176,.F.); +#152157 = ORIENTED_EDGE('',*,*,#151467,.F.); +#152158 = ORIENTED_EDGE('',*,*,#151743,.F.); +#152159 = ORIENTED_EDGE('',*,*,#151909,.F.); +#152160 = ORIENTED_EDGE('',*,*,#152161,.T.); +#152161 = EDGE_CURVE('',#151910,#89019,#152162,.T.); +#152162 = SURFACE_CURVE('',#152163,(#152167,#152174),.PCURVE_S1.); +#152163 = LINE('',#152164,#152165); +#152164 = CARTESIAN_POINT('',(1.65,10.527847992439,0.65)); +#152165 = VECTOR('',#152166,1.); +#152166 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#152167 = PCURVE('',#89034,#152168); +#152168 = DEFINITIONAL_REPRESENTATION('',(#152169),#152173); +#152169 = LINE('',#152170,#152171); +#152170 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152171 = VECTOR('',#152172,1.); +#152172 = DIRECTION('',(-3.563627120235E-016,-1.)); +#152173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152174 = PCURVE('',#89060,#152175); +#152175 = DEFINITIONAL_REPRESENTATION('',(#152176),#152180); +#152176 = LINE('',#152177,#152178); +#152177 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#152178 = VECTOR('',#152179,1.); +#152179 = DIRECTION('',(1.,2.164989446033E-063)); +#152180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152181 = ORIENTED_EDGE('',*,*,#89018,.T.); +#152182 = ADVANCED_FACE('',(#152183),#89060,.F.); +#152183 = FACE_BOUND('',#152184,.T.); +#152184 = EDGE_LOOP('',(#152185,#152186,#152187,#152188)); +#152185 = ORIENTED_EDGE('',*,*,#151959,.F.); +#152186 = ORIENTED_EDGE('',*,*,#152029,.T.); +#152187 = ORIENTED_EDGE('',*,*,#89046,.T.); +#152188 = ORIENTED_EDGE('',*,*,#152161,.F.); +#152189 = ADVANCED_FACE('',(#152190),#151222,.T.); +#152190 = FACE_BOUND('',#152191,.T.); +#152191 = EDGE_LOOP('',(#152192,#152193,#152194,#152195)); +#152192 = ORIENTED_EDGE('',*,*,#152136,.F.); +#152193 = ORIENTED_EDGE('',*,*,#151315,.F.); +#152194 = ORIENTED_EDGE('',*,*,#152054,.F.); +#152195 = ORIENTED_EDGE('',*,*,#151206,.F.); +#152196 = ADVANCED_FACE('',(#152197),#152211,.T.); +#152197 = FACE_BOUND('',#152198,.T.); +#152198 = EDGE_LOOP('',(#152199,#152229,#152257,#152280)); +#152199 = ORIENTED_EDGE('',*,*,#152200,.T.); +#152200 = EDGE_CURVE('',#152201,#152203,#152205,.T.); +#152201 = VERTEX_POINT('',#152202); +#152202 = CARTESIAN_POINT('',(1.15,10.74341632541,-0.308197125857)); +#152203 = VERTEX_POINT('',#152204); +#152204 = CARTESIAN_POINT('',(1.15,11.,-0.308197125857)); +#152205 = SURFACE_CURVE('',#152206,(#152210,#152222),.PCURVE_S1.); +#152206 = LINE('',#152207,#152208); +#152207 = CARTESIAN_POINT('',(1.15,10.74341632541,-0.308197125857)); +#152208 = VECTOR('',#152209,1.); +#152209 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#152210 = PCURVE('',#152211,#152216); +#152211 = PLANE('',#152212); +#152212 = AXIS2_PLACEMENT_3D('',#152213,#152214,#152215); +#152213 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, + -0.308197125857)); +#152214 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#152215 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#152216 = DEFINITIONAL_REPRESENTATION('',(#152217),#152221); +#152217 = LINE('',#152218,#152219); +#152218 = CARTESIAN_POINT('',(-1.15,-1.7763568394E-015)); +#152219 = VECTOR('',#152220,1.); +#152220 = DIRECTION('',(-6.725593854929E-015,1.)); +#152221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152222 = PCURVE('',#90744,#152223); +#152223 = DEFINITIONAL_REPRESENTATION('',(#152224),#152228); +#152224 = LINE('',#152225,#152226); +#152225 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); +#152226 = VECTOR('',#152227,1.); +#152227 = DIRECTION('',(0.E+000,1.)); +#152228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152229 = ORIENTED_EDGE('',*,*,#152230,.T.); +#152230 = EDGE_CURVE('',#152203,#152231,#152233,.T.); +#152231 = VERTEX_POINT('',#152232); +#152232 = CARTESIAN_POINT('',(1.35,11.,-0.308197125857)); +#152233 = SURFACE_CURVE('',#152234,(#152238,#152245),.PCURVE_S1.); +#152234 = LINE('',#152235,#152236); +#152235 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); +#152236 = VECTOR('',#152237,1.); +#152237 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152238 = PCURVE('',#152211,#152239); +#152239 = DEFINITIONAL_REPRESENTATION('',(#152240),#152244); +#152240 = LINE('',#152241,#152242); +#152241 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); +#152242 = VECTOR('',#152243,1.); +#152243 = DIRECTION('',(-1.,-8.881784197001E-016)); +#152244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152245 = PCURVE('',#152246,#152251); +#152246 = PLANE('',#152247); +#152247 = AXIS2_PLACEMENT_3D('',#152248,#152249,#152250); +#152248 = CARTESIAN_POINT('',(1.25,11.,-0.258196742327)); +#152249 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); +#152250 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); +#152251 = DEFINITIONAL_REPRESENTATION('',(#152252),#152256); +#152252 = LINE('',#152253,#152254); +#152253 = CARTESIAN_POINT('',(1.25,-5.000038352949E-002)); +#152254 = VECTOR('',#152255,1.); +#152255 = DIRECTION('',(-1.,-1.1653254136E-048)); +#152256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#149682 = ORIENTED_EDGE('',*,*,#148893,.F.); -#149683 = ORIENTED_EDGE('',*,*,#149123,.F.); -#149684 = ORIENTED_EDGE('',*,*,#149276,.F.); -#149685 = ORIENTED_EDGE('',*,*,#149397,.F.); -#149686 = ORIENTED_EDGE('',*,*,#149687,.T.); -#149687 = EDGE_CURVE('',#149398,#86569,#149688,.T.); -#149688 = SURFACE_CURVE('',#149689,(#149693,#149700),.PCURVE_S1.); -#149689 = LINE('',#149690,#149691); -#149690 = CARTESIAN_POINT('',(1.85,10.527847992439,0.75)); -#149691 = VECTOR('',#149692,1.); -#149692 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#149693 = PCURVE('',#86586,#149694); -#149694 = DEFINITIONAL_REPRESENTATION('',(#149695),#149699); -#149695 = LINE('',#149696,#149697); -#149696 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#149697 = VECTOR('',#149698,1.); -#149698 = DIRECTION('',(3.563627120235E-016,-1.)); -#149699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149700 = PCURVE('',#86614,#149701); -#149701 = DEFINITIONAL_REPRESENTATION('',(#149702),#149706); -#149702 = LINE('',#149703,#149704); -#149703 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149704 = VECTOR('',#149705,1.); -#149705 = DIRECTION('',(-1.,2.164989446033E-063)); -#149706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149707 = ORIENTED_EDGE('',*,*,#86568,.T.); -#149708 = ADVANCED_FACE('',(#149709),#86614,.F.); -#149709 = FACE_BOUND('',#149710,.T.); -#149710 = EDGE_LOOP('',(#149711,#149712,#149733,#149734)); -#149711 = ORIENTED_EDGE('',*,*,#149494,.F.); -#149712 = ORIENTED_EDGE('',*,*,#149713,.T.); -#149713 = EDGE_CURVE('',#149445,#86599,#149714,.T.); -#149714 = SURFACE_CURVE('',#149715,(#149719,#149726),.PCURVE_S1.); -#149715 = LINE('',#149716,#149717); -#149716 = CARTESIAN_POINT('',(1.65,10.527847992439,0.75)); -#149717 = VECTOR('',#149718,1.); -#149718 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#149719 = PCURVE('',#86614,#149720); -#149720 = DEFINITIONAL_REPRESENTATION('',(#149721),#149725); -#149721 = LINE('',#149722,#149723); -#149722 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#149723 = VECTOR('',#149724,1.); -#149724 = DIRECTION('',(-1.,2.164989446033E-063)); -#149725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149726 = PCURVE('',#86642,#149727); -#149727 = DEFINITIONAL_REPRESENTATION('',(#149728),#149732); -#149728 = LINE('',#149729,#149730); -#149729 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#149730 = VECTOR('',#149731,1.); -#149731 = DIRECTION('',(-3.563627120235E-016,-1.)); -#149732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149733 = ORIENTED_EDGE('',*,*,#86598,.T.); -#149734 = ORIENTED_EDGE('',*,*,#149687,.F.); -#149735 = ADVANCED_FACE('',(#149736),#86642,.F.); -#149736 = FACE_BOUND('',#149737,.T.); -#149737 = EDGE_LOOP('',(#149738,#149739,#149740,#149741,#149742,#149743, - #149764,#149765,#149766,#149767,#149768,#149789)); -#149738 = ORIENTED_EDGE('',*,*,#149713,.F.); -#149739 = ORIENTED_EDGE('',*,*,#149444,.T.); -#149740 = ORIENTED_EDGE('',*,*,#149298,.T.); -#149741 = ORIENTED_EDGE('',*,*,#149200,.T.); -#149742 = ORIENTED_EDGE('',*,*,#148946,.T.); -#149743 = ORIENTED_EDGE('',*,*,#149744,.T.); -#149744 = EDGE_CURVE('',#148924,#148787,#149745,.T.); -#149745 = SURFACE_CURVE('',#149746,(#149750,#149757),.PCURVE_S1.); -#149746 = LINE('',#149747,#149748); -#149747 = CARTESIAN_POINT('',(1.65,11.,1.159810404338E-002)); -#149748 = VECTOR('',#149749,1.); -#149749 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#149750 = PCURVE('',#86642,#149751); -#149751 = DEFINITIONAL_REPRESENTATION('',(#149752),#149756); -#149752 = LINE('',#149753,#149754); -#149753 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#149754 = VECTOR('',#149755,1.); -#149755 = DIRECTION('',(1.,-2.101748079665E-016)); -#149756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149757 = PCURVE('',#148830,#149758); -#149758 = DEFINITIONAL_REPRESENTATION('',(#149759),#149763); -#149759 = LINE('',#149760,#149761); -#149760 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#149761 = VECTOR('',#149762,1.); -#149762 = DIRECTION('',(1.570395187386E-016,-1.)); -#149763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149764 = ORIENTED_EDGE('',*,*,#148784,.F.); -#149765 = ORIENTED_EDGE('',*,*,#149075,.F.); -#149766 = ORIENTED_EDGE('',*,*,#149351,.F.); -#149767 = ORIENTED_EDGE('',*,*,#149517,.F.); -#149768 = ORIENTED_EDGE('',*,*,#149769,.T.); -#149769 = EDGE_CURVE('',#149518,#86627,#149770,.T.); -#149770 = SURFACE_CURVE('',#149771,(#149775,#149782),.PCURVE_S1.); -#149771 = LINE('',#149772,#149773); -#149772 = CARTESIAN_POINT('',(1.65,10.527847992439,0.65)); -#149773 = VECTOR('',#149774,1.); -#149774 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#149775 = PCURVE('',#86642,#149776); -#149776 = DEFINITIONAL_REPRESENTATION('',(#149777),#149781); -#149777 = LINE('',#149778,#149779); -#149778 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149779 = VECTOR('',#149780,1.); -#149780 = DIRECTION('',(-3.563627120235E-016,-1.)); -#149781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149782 = PCURVE('',#86668,#149783); -#149783 = DEFINITIONAL_REPRESENTATION('',(#149784),#149788); -#149784 = LINE('',#149785,#149786); -#149785 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#149786 = VECTOR('',#149787,1.); -#149787 = DIRECTION('',(1.,2.164989446033E-063)); -#149788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149789 = ORIENTED_EDGE('',*,*,#86626,.T.); -#149790 = ADVANCED_FACE('',(#149791),#86668,.F.); -#149791 = FACE_BOUND('',#149792,.T.); -#149792 = EDGE_LOOP('',(#149793,#149794,#149795,#149796)); -#149793 = ORIENTED_EDGE('',*,*,#149567,.F.); -#149794 = ORIENTED_EDGE('',*,*,#149637,.T.); -#149795 = ORIENTED_EDGE('',*,*,#86654,.T.); -#149796 = ORIENTED_EDGE('',*,*,#149769,.F.); -#149797 = ADVANCED_FACE('',(#149798),#148830,.T.); -#149798 = FACE_BOUND('',#149799,.T.); -#149799 = EDGE_LOOP('',(#149800,#149801,#149802,#149803)); -#149800 = ORIENTED_EDGE('',*,*,#149744,.F.); -#149801 = ORIENTED_EDGE('',*,*,#148923,.F.); -#149802 = ORIENTED_EDGE('',*,*,#149662,.F.); -#149803 = ORIENTED_EDGE('',*,*,#148814,.F.); -#149804 = ADVANCED_FACE('',(#149805),#149819,.T.); -#149805 = FACE_BOUND('',#149806,.T.); -#149806 = EDGE_LOOP('',(#149807,#149837,#149865,#149888)); -#149807 = ORIENTED_EDGE('',*,*,#149808,.T.); -#149808 = EDGE_CURVE('',#149809,#149811,#149813,.T.); -#149809 = VERTEX_POINT('',#149810); -#149810 = CARTESIAN_POINT('',(1.15,10.74341632541,-0.308197125857)); -#149811 = VERTEX_POINT('',#149812); -#149812 = CARTESIAN_POINT('',(1.15,11.,-0.308197125857)); -#149813 = SURFACE_CURVE('',#149814,(#149818,#149830),.PCURVE_S1.); -#149814 = LINE('',#149815,#149816); -#149815 = CARTESIAN_POINT('',(1.15,10.74341632541,-0.308197125857)); -#149816 = VECTOR('',#149817,1.); -#149817 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#149818 = PCURVE('',#149819,#149824); -#149819 = PLANE('',#149820); -#149820 = AXIS2_PLACEMENT_3D('',#149821,#149822,#149823); -#149821 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, - -0.308197125857)); -#149822 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#149823 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#149824 = DEFINITIONAL_REPRESENTATION('',(#149825),#149829); -#149825 = LINE('',#149826,#149827); -#149826 = CARTESIAN_POINT('',(-1.15,-1.7763568394E-015)); -#149827 = VECTOR('',#149828,1.); -#149828 = DIRECTION('',(-6.725593854929E-015,1.)); -#149829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149830 = PCURVE('',#88352,#149831); -#149831 = DEFINITIONAL_REPRESENTATION('',(#149832),#149836); -#149832 = LINE('',#149833,#149834); -#149833 = CARTESIAN_POINT('',(0.958197125857,0.215568332972)); -#149834 = VECTOR('',#149835,1.); -#149835 = DIRECTION('',(0.E+000,1.)); -#149836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149837 = ORIENTED_EDGE('',*,*,#149838,.T.); -#149838 = EDGE_CURVE('',#149811,#149839,#149841,.T.); -#149839 = VERTEX_POINT('',#149840); -#149840 = CARTESIAN_POINT('',(1.35,11.,-0.308197125857)); -#149841 = SURFACE_CURVE('',#149842,(#149846,#149853),.PCURVE_S1.); -#149842 = LINE('',#149843,#149844); -#149843 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.308197125857)); -#149844 = VECTOR('',#149845,1.); -#149845 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149846 = PCURVE('',#149819,#149847); -#149847 = DEFINITIONAL_REPRESENTATION('',(#149848),#149852); -#149848 = LINE('',#149849,#149850); -#149849 = CARTESIAN_POINT('',(-2.278920826178E-016,0.25658367459)); -#149850 = VECTOR('',#149851,1.); -#149851 = DIRECTION('',(-1.,-8.881784197001E-016)); -#149852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149853 = PCURVE('',#149854,#149859); -#149854 = PLANE('',#149855); -#149855 = AXIS2_PLACEMENT_3D('',#149856,#149857,#149858); -#149856 = CARTESIAN_POINT('',(1.25,11.,-0.258196742327)); -#149857 = DIRECTION('',(8.881784197001E-016,1.,-2.101748079665E-016)); -#149858 = DIRECTION('',(-1.,8.881784197001E-016,-1.1653254136E-048)); -#149859 = DEFINITIONAL_REPRESENTATION('',(#149860),#149864); -#149860 = LINE('',#149861,#149862); -#149861 = CARTESIAN_POINT('',(1.25,-5.000038352949E-002)); -#149862 = VECTOR('',#149863,1.); -#149863 = DIRECTION('',(-1.,-1.1653254136E-048)); -#149864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149865 = ORIENTED_EDGE('',*,*,#149866,.F.); -#149866 = EDGE_CURVE('',#149867,#149839,#149869,.T.); -#149867 = VERTEX_POINT('',#149868); -#149868 = CARTESIAN_POINT('',(1.35,10.74341632541,-0.308197125857)); -#149869 = SURFACE_CURVE('',#149870,(#149874,#149881),.PCURVE_S1.); -#149870 = LINE('',#149871,#149872); -#149871 = CARTESIAN_POINT('',(1.35,10.74341632541,-0.308197125857)); -#149872 = VECTOR('',#149873,1.); -#149873 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#149874 = PCURVE('',#149819,#149875); -#149875 = DEFINITIONAL_REPRESENTATION('',(#149876),#149880); -#149876 = LINE('',#149877,#149878); -#149877 = CARTESIAN_POINT('',(-1.35,-1.7763568394E-015)); -#149878 = VECTOR('',#149879,1.); -#149879 = DIRECTION('',(-6.725593854929E-015,1.)); -#149880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149881 = PCURVE('',#88296,#149882); -#149882 = DEFINITIONAL_REPRESENTATION('',(#149883),#149887); -#149883 = LINE('',#149884,#149885); -#149884 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); -#149885 = VECTOR('',#149886,1.); -#149886 = DIRECTION('',(0.E+000,1.)); -#149887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149888 = ORIENTED_EDGE('',*,*,#149889,.T.); -#149889 = EDGE_CURVE('',#149867,#149809,#149890,.T.); -#149890 = SURFACE_CURVE('',#149891,(#149895,#149902),.PCURVE_S1.); -#149891 = LINE('',#149892,#149893); -#149892 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, +#152257 = ORIENTED_EDGE('',*,*,#152258,.F.); +#152258 = EDGE_CURVE('',#152259,#152231,#152261,.T.); +#152259 = VERTEX_POINT('',#152260); +#152260 = CARTESIAN_POINT('',(1.35,10.74341632541,-0.308197125857)); +#152261 = SURFACE_CURVE('',#152262,(#152266,#152273),.PCURVE_S1.); +#152262 = LINE('',#152263,#152264); +#152263 = CARTESIAN_POINT('',(1.35,10.74341632541,-0.308197125857)); +#152264 = VECTOR('',#152265,1.); +#152265 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#152266 = PCURVE('',#152211,#152267); +#152267 = DEFINITIONAL_REPRESENTATION('',(#152268),#152272); +#152268 = LINE('',#152269,#152270); +#152269 = CARTESIAN_POINT('',(-1.35,-1.7763568394E-015)); +#152270 = VECTOR('',#152271,1.); +#152271 = DIRECTION('',(-6.725593854929E-015,1.)); +#152272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152273 = PCURVE('',#90688,#152274); +#152274 = DEFINITIONAL_REPRESENTATION('',(#152275),#152279); +#152275 = LINE('',#152276,#152277); +#152276 = CARTESIAN_POINT('',(-0.958197125857,0.215568332972)); +#152277 = VECTOR('',#152278,1.); +#152278 = DIRECTION('',(0.E+000,1.)); +#152279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152280 = ORIENTED_EDGE('',*,*,#152281,.T.); +#152281 = EDGE_CURVE('',#152259,#152201,#152282,.T.); +#152282 = SURFACE_CURVE('',#152283,(#152287,#152294),.PCURVE_S1.); +#152283 = LINE('',#152284,#152285); +#152284 = CARTESIAN_POINT('',(1.748265931309E-015,10.74341632541, -0.308197125857)); -#149893 = VECTOR('',#149894,1.); -#149894 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149895 = PCURVE('',#149819,#149896); -#149896 = DEFINITIONAL_REPRESENTATION('',(#149897),#149901); -#149897 = LINE('',#149898,#149899); -#149898 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#149899 = VECTOR('',#149900,1.); -#149900 = DIRECTION('',(1.,8.881784197001E-016)); -#149901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149902 = PCURVE('',#149903,#149908); -#149903 = CYLINDRICAL_SURFACE('',#149904,0.308574064194); -#149904 = AXIS2_PLACEMENT_3D('',#149905,#149906,#149907); -#149905 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#152285 = VECTOR('',#152286,1.); +#152286 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152287 = PCURVE('',#152211,#152288); +#152288 = DEFINITIONAL_REPRESENTATION('',(#152289),#152293); +#152289 = LINE('',#152290,#152291); +#152290 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152291 = VECTOR('',#152292,1.); +#152292 = DIRECTION('',(1.,8.881784197001E-016)); +#152293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152294 = PCURVE('',#152295,#152300); +#152295 = CYLINDRICAL_SURFACE('',#152296,0.308574064194); +#152296 = AXIS2_PLACEMENT_3D('',#152297,#152298,#152299); +#152297 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#149906 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149907 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#149908 = DEFINITIONAL_REPRESENTATION('',(#149909),#149912); -#149909 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#149910,#149911), +#152298 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152299 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152300 = DEFINITIONAL_REPRESENTATION('',(#152301),#152304); +#152301 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152302,#152303), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#149910 = CARTESIAN_POINT('',(4.761821717947,1.35)); -#149911 = CARTESIAN_POINT('',(4.761821717947,1.15)); -#149912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149913 = ADVANCED_FACE('',(#149914),#149928,.T.); -#149914 = FACE_BOUND('',#149915,.T.); -#149915 = EDGE_LOOP('',(#149916,#149946,#149969,#149992)); -#149916 = ORIENTED_EDGE('',*,*,#149917,.T.); -#149917 = EDGE_CURVE('',#149918,#149920,#149922,.T.); -#149918 = VERTEX_POINT('',#149919); -#149919 = CARTESIAN_POINT('',(1.35,10.740726081328,-0.208196358798)); -#149920 = VERTEX_POINT('',#149921); -#149921 = CARTESIAN_POINT('',(1.35,11.,-0.208196358798)); -#149922 = SURFACE_CURVE('',#149923,(#149927,#149939),.PCURVE_S1.); -#149923 = LINE('',#149924,#149925); -#149924 = CARTESIAN_POINT('',(1.35,10.740726081328,-0.208196358798)); -#149925 = VECTOR('',#149926,1.); -#149926 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#149927 = PCURVE('',#149928,#149933); -#149928 = PLANE('',#149929); -#149929 = AXIS2_PLACEMENT_3D('',#149930,#149931,#149932); -#149930 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#152302 = CARTESIAN_POINT('',(4.761821717947,1.35)); +#152303 = CARTESIAN_POINT('',(4.761821717947,1.15)); +#152304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152305 = ADVANCED_FACE('',(#152306),#152320,.T.); +#152306 = FACE_BOUND('',#152307,.T.); +#152307 = EDGE_LOOP('',(#152308,#152338,#152361,#152384)); +#152308 = ORIENTED_EDGE('',*,*,#152309,.T.); +#152309 = EDGE_CURVE('',#152310,#152312,#152314,.T.); +#152310 = VERTEX_POINT('',#152311); +#152311 = CARTESIAN_POINT('',(1.35,10.740726081328,-0.208196358798)); +#152312 = VERTEX_POINT('',#152313); +#152313 = CARTESIAN_POINT('',(1.35,11.,-0.208196358798)); +#152314 = SURFACE_CURVE('',#152315,(#152319,#152331),.PCURVE_S1.); +#152315 = LINE('',#152316,#152317); +#152316 = CARTESIAN_POINT('',(1.35,10.740726081328,-0.208196358798)); +#152317 = VECTOR('',#152318,1.); +#152318 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#152319 = PCURVE('',#152320,#152325); +#152320 = PLANE('',#152321); +#152321 = AXIS2_PLACEMENT_3D('',#152322,#152323,#152324); +#152322 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#149931 = DIRECTION('',(0.E+000,0.E+000,1.)); -#149932 = DIRECTION('',(1.,0.E+000,0.E+000)); -#149933 = DEFINITIONAL_REPRESENTATION('',(#149934),#149938); -#149934 = LINE('',#149935,#149936); -#149935 = CARTESIAN_POINT('',(1.35,-1.7763568394E-015)); -#149936 = VECTOR('',#149937,1.); -#149937 = DIRECTION('',(6.725593854929E-015,1.)); -#149938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149939 = PCURVE('',#88296,#149940); -#149940 = DEFINITIONAL_REPRESENTATION('',(#149941),#149945); -#149941 = LINE('',#149942,#149943); -#149942 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); -#149943 = VECTOR('',#149944,1.); -#149944 = DIRECTION('',(0.E+000,1.)); -#149945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149946 = ORIENTED_EDGE('',*,*,#149947,.T.); -#149947 = EDGE_CURVE('',#149920,#149948,#149950,.T.); -#149948 = VERTEX_POINT('',#149949); -#149949 = CARTESIAN_POINT('',(1.15,11.,-0.208196358798)); -#149950 = SURFACE_CURVE('',#149951,(#149955,#149962),.PCURVE_S1.); -#149951 = LINE('',#149952,#149953); -#149952 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); -#149953 = VECTOR('',#149954,1.); -#149954 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#149955 = PCURVE('',#149928,#149956); -#149956 = DEFINITIONAL_REPRESENTATION('',(#149957),#149961); -#149957 = LINE('',#149958,#149959); -#149958 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); -#149959 = VECTOR('',#149960,1.); -#149960 = DIRECTION('',(-1.,8.881784197001E-016)); -#149961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149962 = PCURVE('',#149854,#149963); -#149963 = DEFINITIONAL_REPRESENTATION('',(#149964),#149968); -#149964 = LINE('',#149965,#149966); -#149965 = CARTESIAN_POINT('',(1.25,5.00003835295E-002)); -#149966 = VECTOR('',#149967,1.); -#149967 = DIRECTION('',(1.,1.1653254136E-048)); -#149968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149969 = ORIENTED_EDGE('',*,*,#149970,.F.); -#149970 = EDGE_CURVE('',#149971,#149948,#149973,.T.); -#149971 = VERTEX_POINT('',#149972); -#149972 = CARTESIAN_POINT('',(1.15,10.740726081328,-0.208196358798)); -#149973 = SURFACE_CURVE('',#149974,(#149978,#149985),.PCURVE_S1.); -#149974 = LINE('',#149975,#149976); -#149975 = CARTESIAN_POINT('',(1.15,10.740726081328,-0.208196358798)); -#149976 = VECTOR('',#149977,1.); -#149977 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); -#149978 = PCURVE('',#149928,#149979); -#149979 = DEFINITIONAL_REPRESENTATION('',(#149980),#149984); -#149980 = LINE('',#149981,#149982); -#149981 = CARTESIAN_POINT('',(1.15,0.E+000)); -#149982 = VECTOR('',#149983,1.); -#149983 = DIRECTION('',(6.725593854929E-015,1.)); -#149984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149985 = PCURVE('',#88352,#149986); -#149986 = DEFINITIONAL_REPRESENTATION('',(#149987),#149991); -#149987 = LINE('',#149988,#149989); -#149988 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); -#149989 = VECTOR('',#149990,1.); -#149990 = DIRECTION('',(0.E+000,1.)); -#149991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#149992 = ORIENTED_EDGE('',*,*,#149993,.T.); -#149993 = EDGE_CURVE('',#149971,#149918,#149994,.T.); -#149994 = SURFACE_CURVE('',#149995,(#149999,#150006),.PCURVE_S1.); -#149995 = LINE('',#149996,#149997); -#149996 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, +#152323 = DIRECTION('',(0.E+000,0.E+000,1.)); +#152324 = DIRECTION('',(1.,0.E+000,0.E+000)); +#152325 = DEFINITIONAL_REPRESENTATION('',(#152326),#152330); +#152326 = LINE('',#152327,#152328); +#152327 = CARTESIAN_POINT('',(1.35,-1.7763568394E-015)); +#152328 = VECTOR('',#152329,1.); +#152329 = DIRECTION('',(6.725593854929E-015,1.)); +#152330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152331 = PCURVE('',#90688,#152332); +#152332 = DEFINITIONAL_REPRESENTATION('',(#152333),#152337); +#152333 = LINE('',#152334,#152335); +#152334 = CARTESIAN_POINT('',(-0.858196358798,0.212878088889)); +#152335 = VECTOR('',#152336,1.); +#152336 = DIRECTION('',(0.E+000,1.)); +#152337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152338 = ORIENTED_EDGE('',*,*,#152339,.T.); +#152339 = EDGE_CURVE('',#152312,#152340,#152342,.T.); +#152340 = VERTEX_POINT('',#152341); +#152341 = CARTESIAN_POINT('',(1.15,11.,-0.208196358798)); +#152342 = SURFACE_CURVE('',#152343,(#152347,#152354),.PCURVE_S1.); +#152343 = LINE('',#152344,#152345); +#152344 = CARTESIAN_POINT('',(1.976158013927E-015,11.,-0.208196358798)); +#152345 = VECTOR('',#152346,1.); +#152346 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152347 = PCURVE('',#152320,#152348); +#152348 = DEFINITIONAL_REPRESENTATION('',(#152349),#152353); +#152349 = LINE('',#152350,#152351); +#152350 = CARTESIAN_POINT('',(2.302814993557E-016,0.259273918672)); +#152351 = VECTOR('',#152352,1.); +#152352 = DIRECTION('',(-1.,8.881784197001E-016)); +#152353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152354 = PCURVE('',#152246,#152355); +#152355 = DEFINITIONAL_REPRESENTATION('',(#152356),#152360); +#152356 = LINE('',#152357,#152358); +#152357 = CARTESIAN_POINT('',(1.25,5.00003835295E-002)); +#152358 = VECTOR('',#152359,1.); +#152359 = DIRECTION('',(1.,1.1653254136E-048)); +#152360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152361 = ORIENTED_EDGE('',*,*,#152362,.F.); +#152362 = EDGE_CURVE('',#152363,#152340,#152365,.T.); +#152363 = VERTEX_POINT('',#152364); +#152364 = CARTESIAN_POINT('',(1.15,10.740726081328,-0.208196358798)); +#152365 = SURFACE_CURVE('',#152366,(#152370,#152377),.PCURVE_S1.); +#152366 = LINE('',#152367,#152368); +#152367 = CARTESIAN_POINT('',(1.15,10.740726081328,-0.208196358798)); +#152368 = VECTOR('',#152369,1.); +#152369 = DIRECTION('',(6.725593854929E-015,1.,0.E+000)); +#152370 = PCURVE('',#152320,#152371); +#152371 = DEFINITIONAL_REPRESENTATION('',(#152372),#152376); +#152372 = LINE('',#152373,#152374); +#152373 = CARTESIAN_POINT('',(1.15,0.E+000)); +#152374 = VECTOR('',#152375,1.); +#152375 = DIRECTION('',(6.725593854929E-015,1.)); +#152376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152377 = PCURVE('',#90744,#152378); +#152378 = DEFINITIONAL_REPRESENTATION('',(#152379),#152383); +#152379 = LINE('',#152380,#152381); +#152380 = CARTESIAN_POINT('',(0.858196358798,0.212878088889)); +#152381 = VECTOR('',#152382,1.); +#152382 = DIRECTION('',(0.E+000,1.)); +#152383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152384 = ORIENTED_EDGE('',*,*,#152385,.T.); +#152385 = EDGE_CURVE('',#152363,#152310,#152386,.T.); +#152386 = SURFACE_CURVE('',#152387,(#152391,#152398),.PCURVE_S1.); +#152387 = LINE('',#152388,#152389); +#152388 = CARTESIAN_POINT('',(1.745876514571E-015,10.740726081328, -0.208196358798)); -#149997 = VECTOR('',#149998,1.); -#149998 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#149999 = PCURVE('',#149928,#150000); -#150000 = DEFINITIONAL_REPRESENTATION('',(#150001),#150005); -#150001 = LINE('',#150002,#150003); -#150002 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150003 = VECTOR('',#150004,1.); -#150004 = DIRECTION('',(1.,-8.881784197001E-016)); -#150005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150006 = PCURVE('',#150007,#150012); -#150007 = CYLINDRICAL_SURFACE('',#150008,0.208574704164); -#150008 = AXIS2_PLACEMENT_3D('',#150009,#150010,#150011); -#150009 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, +#152389 = VECTOR('',#152390,1.); +#152390 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152391 = PCURVE('',#152320,#152392); +#152392 = DEFINITIONAL_REPRESENTATION('',(#152393),#152397); +#152393 = LINE('',#152394,#152395); +#152394 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152395 = VECTOR('',#152396,1.); +#152396 = DIRECTION('',(1.,-8.881784197001E-016)); +#152397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152398 = PCURVE('',#152399,#152404); +#152399 = CYLINDRICAL_SURFACE('',#152400,0.208574704164); +#152400 = AXIS2_PLACEMENT_3D('',#152401,#152402,#152403); +#152401 = CARTESIAN_POINT('',(1.734723475977E-015,10.728168876214, 2.640924866458E-017)); -#150010 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150011 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150012 = DEFINITIONAL_REPRESENTATION('',(#150013),#150016); -#150013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150014,#150015), +#152402 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152403 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152404 = DEFINITIONAL_REPRESENTATION('',(#152405),#152408); +#152405 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152406,#152407), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#150014 = CARTESIAN_POINT('',(4.772630242227,1.15)); -#150015 = CARTESIAN_POINT('',(4.772630242227,1.35)); -#150016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150017 = ADVANCED_FACE('',(#150018),#149903,.T.); -#150018 = FACE_BOUND('',#150019,.T.); -#150019 = EDGE_LOOP('',(#150020,#150021,#150071,#150098)); -#150020 = ORIENTED_EDGE('',*,*,#149889,.F.); -#150021 = ORIENTED_EDGE('',*,*,#150022,.F.); -#150022 = EDGE_CURVE('',#150023,#149867,#150025,.T.); -#150023 = VERTEX_POINT('',#150024); -#150024 = CARTESIAN_POINT('',(1.35,10.419594812019,0.E+000)); -#150025 = SURFACE_CURVE('',#150026,(#150031,#150060),.PCURVE_S1.); -#150026 = CIRCLE('',#150027,0.308574064194); -#150027 = AXIS2_PLACEMENT_3D('',#150028,#150029,#150030); -#150028 = CARTESIAN_POINT('',(1.35,10.728168876214,2.640924866458E-017) - ); -#150029 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150030 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150031 = PCURVE('',#149903,#150032); -#150032 = DEFINITIONAL_REPRESENTATION('',(#150033),#150059); -#150033 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150034,#150035,#150036, - #150037,#150038,#150039,#150040,#150041,#150042,#150043,#150044, - #150045,#150046,#150047,#150048,#150049,#150050,#150051,#150052, - #150053,#150054,#150055,#150056,#150057,#150058),.UNSPECIFIED.,.F., +#152406 = CARTESIAN_POINT('',(4.772630242227,1.15)); +#152407 = CARTESIAN_POINT('',(4.772630242227,1.35)); +#152408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152409 = ADVANCED_FACE('',(#152410),#152295,.T.); +#152410 = FACE_BOUND('',#152411,.T.); +#152411 = EDGE_LOOP('',(#152412,#152413,#152463,#152490)); +#152412 = ORIENTED_EDGE('',*,*,#152281,.F.); +#152413 = ORIENTED_EDGE('',*,*,#152414,.F.); +#152414 = EDGE_CURVE('',#152415,#152259,#152417,.T.); +#152415 = VERTEX_POINT('',#152416); +#152416 = CARTESIAN_POINT('',(1.35,10.419594812019,0.E+000)); +#152417 = SURFACE_CURVE('',#152418,(#152423,#152452),.PCURVE_S1.); +#152418 = CIRCLE('',#152419,0.308574064194); +#152419 = AXIS2_PLACEMENT_3D('',#152420,#152421,#152422); +#152420 = CARTESIAN_POINT('',(1.35,10.728168876214,2.640924866458E-017) + ); +#152421 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152422 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152423 = PCURVE('',#152295,#152424); +#152424 = DEFINITIONAL_REPRESENTATION('',(#152425),#152451); +#152425 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152426,#152427,#152428, + #152429,#152430,#152431,#152432,#152433,#152434,#152435,#152436, + #152437,#152438,#152439,#152440,#152441,#152442,#152443,#152444, + #152445,#152446,#152447,#152448,#152449,#152450),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -185038,102 +188040,102 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#150034 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#150035 = CARTESIAN_POINT('',(3.166141578807,1.35)); -#150036 = CARTESIAN_POINT('',(3.215239429242,1.35)); -#150037 = CARTESIAN_POINT('',(3.288886204895,1.35)); -#150038 = CARTESIAN_POINT('',(3.362532980548,1.35)); -#150039 = CARTESIAN_POINT('',(3.4361797562,1.35)); -#150040 = CARTESIAN_POINT('',(3.509826531853,1.35)); -#150041 = CARTESIAN_POINT('',(3.583473307505,1.35)); -#150042 = CARTESIAN_POINT('',(3.657120083158,1.35)); -#150043 = CARTESIAN_POINT('',(3.730766858811,1.35)); -#150044 = CARTESIAN_POINT('',(3.804413634463,1.35)); -#150045 = CARTESIAN_POINT('',(3.878060410116,1.35)); -#150046 = CARTESIAN_POINT('',(3.951707185768,1.35)); -#150047 = CARTESIAN_POINT('',(4.025353961421,1.35)); -#150048 = CARTESIAN_POINT('',(4.099000737074,1.35)); -#150049 = CARTESIAN_POINT('',(4.172647512726,1.35)); -#150050 = CARTESIAN_POINT('',(4.246294288379,1.35)); -#150051 = CARTESIAN_POINT('',(4.319941064031,1.35)); -#150052 = CARTESIAN_POINT('',(4.393587839684,1.35)); -#150053 = CARTESIAN_POINT('',(4.467234615337,1.35)); -#150054 = CARTESIAN_POINT('',(4.540881390989,1.35)); -#150055 = CARTESIAN_POINT('',(4.614528166642,1.35)); -#150056 = CARTESIAN_POINT('',(4.688174942294,1.35)); -#150057 = CARTESIAN_POINT('',(4.737272792729,1.35)); -#150058 = CARTESIAN_POINT('',(4.761821717947,1.35)); -#150059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150060 = PCURVE('',#88296,#150061); -#150061 = DEFINITIONAL_REPRESENTATION('',(#150062),#150070); -#150062 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150063,#150064,#150065, - #150066,#150067,#150068,#150069),.UNSPECIFIED.,.T.,.F.) +#152426 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#152427 = CARTESIAN_POINT('',(3.166141578807,1.35)); +#152428 = CARTESIAN_POINT('',(3.215239429242,1.35)); +#152429 = CARTESIAN_POINT('',(3.288886204895,1.35)); +#152430 = CARTESIAN_POINT('',(3.362532980548,1.35)); +#152431 = CARTESIAN_POINT('',(3.4361797562,1.35)); +#152432 = CARTESIAN_POINT('',(3.509826531853,1.35)); +#152433 = CARTESIAN_POINT('',(3.583473307505,1.35)); +#152434 = CARTESIAN_POINT('',(3.657120083158,1.35)); +#152435 = CARTESIAN_POINT('',(3.730766858811,1.35)); +#152436 = CARTESIAN_POINT('',(3.804413634463,1.35)); +#152437 = CARTESIAN_POINT('',(3.878060410116,1.35)); +#152438 = CARTESIAN_POINT('',(3.951707185768,1.35)); +#152439 = CARTESIAN_POINT('',(4.025353961421,1.35)); +#152440 = CARTESIAN_POINT('',(4.099000737074,1.35)); +#152441 = CARTESIAN_POINT('',(4.172647512726,1.35)); +#152442 = CARTESIAN_POINT('',(4.246294288379,1.35)); +#152443 = CARTESIAN_POINT('',(4.319941064031,1.35)); +#152444 = CARTESIAN_POINT('',(4.393587839684,1.35)); +#152445 = CARTESIAN_POINT('',(4.467234615337,1.35)); +#152446 = CARTESIAN_POINT('',(4.540881390989,1.35)); +#152447 = CARTESIAN_POINT('',(4.614528166642,1.35)); +#152448 = CARTESIAN_POINT('',(4.688174942294,1.35)); +#152449 = CARTESIAN_POINT('',(4.737272792729,1.35)); +#152450 = CARTESIAN_POINT('',(4.761821717947,1.35)); +#152451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152452 = PCURVE('',#90688,#152453); +#152453 = DEFINITIONAL_REPRESENTATION('',(#152454),#152462); +#152454 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152455,#152456,#152457, + #152458,#152459,#152460,#152461),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#150063 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#150064 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); -#150065 = CARTESIAN_POINT('',(-0.382767021459,4.603385167789E-002)); -#150066 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); -#150067 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); -#150068 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); -#150069 = CARTESIAN_POINT('',(-0.65,0.508894947969)); -#150070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150071 = ORIENTED_EDGE('',*,*,#150072,.F.); -#150072 = EDGE_CURVE('',#150073,#150023,#150075,.T.); -#150073 = VERTEX_POINT('',#150074); -#150074 = CARTESIAN_POINT('',(1.15,10.419594812019,0.E+000)); -#150075 = SURFACE_CURVE('',#150076,(#150080,#150086),.PCURVE_S1.); -#150076 = LINE('',#150077,#150078); -#150077 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#152455 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#152456 = CARTESIAN_POINT('',(-0.115534042917,0.508894947969)); +#152457 = CARTESIAN_POINT('',(-0.382767021459,4.603385167789E-002)); +#152458 = CARTESIAN_POINT('',(-0.65,-0.416827244614)); +#152459 = CARTESIAN_POINT('',(-0.917232978541,4.603385167788E-002)); +#152460 = CARTESIAN_POINT('',(-1.184465957083,0.508894947969)); +#152461 = CARTESIAN_POINT('',(-0.65,0.508894947969)); +#152462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152463 = ORIENTED_EDGE('',*,*,#152464,.F.); +#152464 = EDGE_CURVE('',#152465,#152415,#152467,.T.); +#152465 = VERTEX_POINT('',#152466); +#152466 = CARTESIAN_POINT('',(1.15,10.419594812019,0.E+000)); +#152467 = SURFACE_CURVE('',#152468,(#152472,#152478),.PCURVE_S1.); +#152468 = LINE('',#152469,#152470); +#152469 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.E+000)); -#150078 = VECTOR('',#150079,1.); -#150079 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150080 = PCURVE('',#149903,#150081); -#150081 = DEFINITIONAL_REPRESENTATION('',(#150082),#150085); -#150082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150083,#150084), +#152470 = VECTOR('',#152471,1.); +#152471 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152472 = PCURVE('',#152295,#152473); +#152473 = DEFINITIONAL_REPRESENTATION('',(#152474),#152477); +#152474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152475,#152476), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#150083 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#150084 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#150085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#152475 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#152476 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#152477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#150086 = PCURVE('',#150087,#150092); -#150087 = PLANE('',#150088); -#150088 = AXIS2_PLACEMENT_3D('',#150089,#150090,#150091); -#150089 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, +#152478 = PCURVE('',#152479,#152484); +#152479 = PLANE('',#152480); +#152480 = AXIS2_PLACEMENT_3D('',#152481,#152482,#152483); +#152481 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, 0.530776333563)); -#150090 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150091 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150092 = DEFINITIONAL_REPRESENTATION('',(#150093),#150097); -#150093 = LINE('',#150094,#150095); -#150094 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#150095 = VECTOR('',#150096,1.); -#150096 = DIRECTION('',(-1.,0.E+000)); -#150097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150098 = ORIENTED_EDGE('',*,*,#150099,.T.); -#150099 = EDGE_CURVE('',#150073,#149809,#150100,.T.); -#150100 = SURFACE_CURVE('',#150101,(#150106,#150135),.PCURVE_S1.); -#150101 = CIRCLE('',#150102,0.308574064194); -#150102 = AXIS2_PLACEMENT_3D('',#150103,#150104,#150105); -#150103 = CARTESIAN_POINT('',(1.15,10.728168876214,2.640924866458E-017) - ); -#150104 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150105 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150106 = PCURVE('',#149903,#150107); -#150107 = DEFINITIONAL_REPRESENTATION('',(#150108),#150134); -#150108 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150109,#150110,#150111, - #150112,#150113,#150114,#150115,#150116,#150117,#150118,#150119, - #150120,#150121,#150122,#150123,#150124,#150125,#150126,#150127, - #150128,#150129,#150130,#150131,#150132,#150133),.UNSPECIFIED.,.F., +#152482 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152483 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152484 = DEFINITIONAL_REPRESENTATION('',(#152485),#152489); +#152485 = LINE('',#152486,#152487); +#152486 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#152487 = VECTOR('',#152488,1.); +#152488 = DIRECTION('',(-1.,0.E+000)); +#152489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152490 = ORIENTED_EDGE('',*,*,#152491,.T.); +#152491 = EDGE_CURVE('',#152465,#152201,#152492,.T.); +#152492 = SURFACE_CURVE('',#152493,(#152498,#152527),.PCURVE_S1.); +#152493 = CIRCLE('',#152494,0.308574064194); +#152494 = AXIS2_PLACEMENT_3D('',#152495,#152496,#152497); +#152495 = CARTESIAN_POINT('',(1.15,10.728168876214,2.640924866458E-017) + ); +#152496 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152497 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152498 = PCURVE('',#152295,#152499); +#152499 = DEFINITIONAL_REPRESENTATION('',(#152500),#152526); +#152500 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152501,#152502,#152503, + #152504,#152505,#152506,#152507,#152508,#152509,#152510,#152511, + #152512,#152513,#152514,#152515,#152516,#152517,#152518,#152519, + #152520,#152521,#152522,#152523,#152524,#152525),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215239429242,3.288886204895,3.362532980548,3.4361797562, 3.509826531853,3.583473307505,3.657120083158,3.730766858811, @@ -185141,64 +188143,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.099000737074,4.172647512726,4.246294288379,4.319941064031, 4.393587839684,4.467234615337,4.540881390989,4.614528166642, 4.688174942294,4.761821717947),.QUASI_UNIFORM_KNOTS.); -#150109 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#150110 = CARTESIAN_POINT('',(3.166141578807,1.15)); -#150111 = CARTESIAN_POINT('',(3.215239429242,1.15)); -#150112 = CARTESIAN_POINT('',(3.288886204895,1.15)); -#150113 = CARTESIAN_POINT('',(3.362532980548,1.15)); -#150114 = CARTESIAN_POINT('',(3.4361797562,1.15)); -#150115 = CARTESIAN_POINT('',(3.509826531853,1.15)); -#150116 = CARTESIAN_POINT('',(3.583473307505,1.15)); -#150117 = CARTESIAN_POINT('',(3.657120083158,1.15)); -#150118 = CARTESIAN_POINT('',(3.730766858811,1.15)); -#150119 = CARTESIAN_POINT('',(3.804413634463,1.15)); -#150120 = CARTESIAN_POINT('',(3.878060410116,1.15)); -#150121 = CARTESIAN_POINT('',(3.951707185768,1.15)); -#150122 = CARTESIAN_POINT('',(4.025353961421,1.15)); -#150123 = CARTESIAN_POINT('',(4.099000737074,1.15)); -#150124 = CARTESIAN_POINT('',(4.172647512726,1.15)); -#150125 = CARTESIAN_POINT('',(4.246294288379,1.15)); -#150126 = CARTESIAN_POINT('',(4.319941064031,1.15)); -#150127 = CARTESIAN_POINT('',(4.393587839684,1.15)); -#150128 = CARTESIAN_POINT('',(4.467234615337,1.15)); -#150129 = CARTESIAN_POINT('',(4.540881390989,1.15)); -#150130 = CARTESIAN_POINT('',(4.614528166642,1.15)); -#150131 = CARTESIAN_POINT('',(4.688174942294,1.15)); -#150132 = CARTESIAN_POINT('',(4.737272792729,1.15)); -#150133 = CARTESIAN_POINT('',(4.761821717947,1.15)); -#150134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150135 = PCURVE('',#88352,#150136); -#150136 = DEFINITIONAL_REPRESENTATION('',(#150137),#150141); -#150137 = CIRCLE('',#150138,0.308574064194); -#150138 = AXIS2_PLACEMENT_2D('',#150139,#150140); -#150139 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#150140 = DIRECTION('',(0.E+000,1.)); -#150141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150142 = ADVANCED_FACE('',(#150143),#150007,.F.); -#150143 = FACE_BOUND('',#150144,.F.); -#150144 = EDGE_LOOP('',(#150145,#150146,#150196,#150223)); -#150145 = ORIENTED_EDGE('',*,*,#149993,.T.); -#150146 = ORIENTED_EDGE('',*,*,#150147,.F.); -#150147 = EDGE_CURVE('',#150148,#149918,#150150,.T.); -#150148 = VERTEX_POINT('',#150149); -#150149 = CARTESIAN_POINT('',(1.35,10.51959417205,0.E+000)); -#150150 = SURFACE_CURVE('',#150151,(#150156,#150185),.PCURVE_S1.); -#150151 = CIRCLE('',#150152,0.208574704164); -#150152 = AXIS2_PLACEMENT_3D('',#150153,#150154,#150155); -#150153 = CARTESIAN_POINT('',(1.35,10.728168876214,2.640924866458E-017) - ); -#150154 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150155 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150156 = PCURVE('',#150007,#150157); -#150157 = DEFINITIONAL_REPRESENTATION('',(#150158),#150184); -#150158 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150159,#150160,#150161, - #150162,#150163,#150164,#150165,#150166,#150167,#150168,#150169, - #150170,#150171,#150172,#150173,#150174,#150175,#150176,#150177, - #150178,#150179,#150180,#150181,#150182,#150183),.UNSPECIFIED.,.F., +#152501 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#152502 = CARTESIAN_POINT('',(3.166141578807,1.15)); +#152503 = CARTESIAN_POINT('',(3.215239429242,1.15)); +#152504 = CARTESIAN_POINT('',(3.288886204895,1.15)); +#152505 = CARTESIAN_POINT('',(3.362532980548,1.15)); +#152506 = CARTESIAN_POINT('',(3.4361797562,1.15)); +#152507 = CARTESIAN_POINT('',(3.509826531853,1.15)); +#152508 = CARTESIAN_POINT('',(3.583473307505,1.15)); +#152509 = CARTESIAN_POINT('',(3.657120083158,1.15)); +#152510 = CARTESIAN_POINT('',(3.730766858811,1.15)); +#152511 = CARTESIAN_POINT('',(3.804413634463,1.15)); +#152512 = CARTESIAN_POINT('',(3.878060410116,1.15)); +#152513 = CARTESIAN_POINT('',(3.951707185768,1.15)); +#152514 = CARTESIAN_POINT('',(4.025353961421,1.15)); +#152515 = CARTESIAN_POINT('',(4.099000737074,1.15)); +#152516 = CARTESIAN_POINT('',(4.172647512726,1.15)); +#152517 = CARTESIAN_POINT('',(4.246294288379,1.15)); +#152518 = CARTESIAN_POINT('',(4.319941064031,1.15)); +#152519 = CARTESIAN_POINT('',(4.393587839684,1.15)); +#152520 = CARTESIAN_POINT('',(4.467234615337,1.15)); +#152521 = CARTESIAN_POINT('',(4.540881390989,1.15)); +#152522 = CARTESIAN_POINT('',(4.614528166642,1.15)); +#152523 = CARTESIAN_POINT('',(4.688174942294,1.15)); +#152524 = CARTESIAN_POINT('',(4.737272792729,1.15)); +#152525 = CARTESIAN_POINT('',(4.761821717947,1.15)); +#152526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152527 = PCURVE('',#90744,#152528); +#152528 = DEFINITIONAL_REPRESENTATION('',(#152529),#152533); +#152529 = CIRCLE('',#152530,0.308574064194); +#152530 = AXIS2_PLACEMENT_2D('',#152531,#152532); +#152531 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#152532 = DIRECTION('',(0.E+000,1.)); +#152533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152534 = ADVANCED_FACE('',(#152535),#152399,.F.); +#152535 = FACE_BOUND('',#152536,.F.); +#152536 = EDGE_LOOP('',(#152537,#152538,#152588,#152615)); +#152537 = ORIENTED_EDGE('',*,*,#152385,.T.); +#152538 = ORIENTED_EDGE('',*,*,#152539,.F.); +#152539 = EDGE_CURVE('',#152540,#152310,#152542,.T.); +#152540 = VERTEX_POINT('',#152541); +#152541 = CARTESIAN_POINT('',(1.35,10.51959417205,0.E+000)); +#152542 = SURFACE_CURVE('',#152543,(#152548,#152577),.PCURVE_S1.); +#152543 = CIRCLE('',#152544,0.208574704164); +#152544 = AXIS2_PLACEMENT_3D('',#152545,#152546,#152547); +#152545 = CARTESIAN_POINT('',(1.35,10.728168876214,2.640924866458E-017) + ); +#152546 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152547 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152548 = PCURVE('',#152399,#152549); +#152549 = DEFINITIONAL_REPRESENTATION('',(#152550),#152576); +#152550 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152551,#152552,#152553, + #152554,#152555,#152556,#152557,#152558,#152559,#152560,#152561, + #152562,#152563,#152564,#152565,#152566,#152567,#152568,#152569, + #152570,#152571,#152572,#152573,#152574,#152575),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.215730725801,3.289868798011,3.364006870222,3.438144942433, 3.512283014644,3.586421086854,3.660559159065,3.734697231276, @@ -185206,345 +188208,345 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.10538759233,4.179525664541,4.253663736751,4.327801808962, 4.401939881173,4.476077953384,4.550216025595,4.624354097805, 4.698492170016,4.772630242227),.QUASI_UNIFORM_KNOTS.); -#150159 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#150160 = CARTESIAN_POINT('',(3.166305344327,1.35)); -#150161 = CARTESIAN_POINT('',(3.215730725801,1.35)); -#150162 = CARTESIAN_POINT('',(3.289868798011,1.35)); -#150163 = CARTESIAN_POINT('',(3.364006870222,1.35)); -#150164 = CARTESIAN_POINT('',(3.438144942433,1.35)); -#150165 = CARTESIAN_POINT('',(3.512283014644,1.35)); -#150166 = CARTESIAN_POINT('',(3.586421086854,1.35)); -#150167 = CARTESIAN_POINT('',(3.660559159065,1.35)); -#150168 = CARTESIAN_POINT('',(3.734697231276,1.35)); -#150169 = CARTESIAN_POINT('',(3.808835303487,1.35)); -#150170 = CARTESIAN_POINT('',(3.882973375698,1.35)); -#150171 = CARTESIAN_POINT('',(3.957111447908,1.35)); -#150172 = CARTESIAN_POINT('',(4.031249520119,1.35)); -#150173 = CARTESIAN_POINT('',(4.10538759233,1.35)); -#150174 = CARTESIAN_POINT('',(4.179525664541,1.35)); -#150175 = CARTESIAN_POINT('',(4.253663736751,1.35)); -#150176 = CARTESIAN_POINT('',(4.327801808962,1.35)); -#150177 = CARTESIAN_POINT('',(4.401939881173,1.35)); -#150178 = CARTESIAN_POINT('',(4.476077953384,1.35)); -#150179 = CARTESIAN_POINT('',(4.550216025595,1.35)); -#150180 = CARTESIAN_POINT('',(4.624354097805,1.35)); -#150181 = CARTESIAN_POINT('',(4.698492170016,1.35)); -#150182 = CARTESIAN_POINT('',(4.74791755149,1.35)); -#150183 = CARTESIAN_POINT('',(4.772630242227,1.35)); -#150184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150185 = PCURVE('',#88296,#150186); -#150186 = DEFINITIONAL_REPRESENTATION('',(#150187),#150195); -#150187 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150188,#150189,#150190, - #150191,#150192,#150193,#150194),.UNSPECIFIED.,.T.,.F.) +#152551 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#152552 = CARTESIAN_POINT('',(3.166305344327,1.35)); +#152553 = CARTESIAN_POINT('',(3.215730725801,1.35)); +#152554 = CARTESIAN_POINT('',(3.289868798011,1.35)); +#152555 = CARTESIAN_POINT('',(3.364006870222,1.35)); +#152556 = CARTESIAN_POINT('',(3.438144942433,1.35)); +#152557 = CARTESIAN_POINT('',(3.512283014644,1.35)); +#152558 = CARTESIAN_POINT('',(3.586421086854,1.35)); +#152559 = CARTESIAN_POINT('',(3.660559159065,1.35)); +#152560 = CARTESIAN_POINT('',(3.734697231276,1.35)); +#152561 = CARTESIAN_POINT('',(3.808835303487,1.35)); +#152562 = CARTESIAN_POINT('',(3.882973375698,1.35)); +#152563 = CARTESIAN_POINT('',(3.957111447908,1.35)); +#152564 = CARTESIAN_POINT('',(4.031249520119,1.35)); +#152565 = CARTESIAN_POINT('',(4.10538759233,1.35)); +#152566 = CARTESIAN_POINT('',(4.179525664541,1.35)); +#152567 = CARTESIAN_POINT('',(4.253663736751,1.35)); +#152568 = CARTESIAN_POINT('',(4.327801808962,1.35)); +#152569 = CARTESIAN_POINT('',(4.401939881173,1.35)); +#152570 = CARTESIAN_POINT('',(4.476077953384,1.35)); +#152571 = CARTESIAN_POINT('',(4.550216025595,1.35)); +#152572 = CARTESIAN_POINT('',(4.624354097805,1.35)); +#152573 = CARTESIAN_POINT('',(4.698492170016,1.35)); +#152574 = CARTESIAN_POINT('',(4.74791755149,1.35)); +#152575 = CARTESIAN_POINT('',(4.772630242227,1.35)); +#152576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152577 = PCURVE('',#90688,#152578); +#152578 = DEFINITIONAL_REPRESENTATION('',(#152579),#152587); +#152579 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152580,#152581,#152582, + #152583,#152584,#152585,#152586),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#150188 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#150189 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); -#150190 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); -#150191 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); -#150192 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); -#150193 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); -#150194 = CARTESIAN_POINT('',(-0.65,0.408895587939)); -#150195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150196 = ORIENTED_EDGE('',*,*,#150197,.T.); -#150197 = EDGE_CURVE('',#150148,#150198,#150200,.T.); -#150198 = VERTEX_POINT('',#150199); -#150199 = CARTESIAN_POINT('',(1.15,10.51959417205,0.E+000)); -#150200 = SURFACE_CURVE('',#150201,(#150205,#150211),.PCURVE_S1.); -#150201 = LINE('',#150202,#150203); -#150202 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 - )); -#150203 = VECTOR('',#150204,1.); -#150204 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150205 = PCURVE('',#150007,#150206); -#150206 = DEFINITIONAL_REPRESENTATION('',(#150207),#150210); -#150207 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150208,#150209), - .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#150208 = CARTESIAN_POINT('',(3.14159265359,1.35)); -#150209 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#150210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150211 = PCURVE('',#150212,#150217); -#150212 = PLANE('',#150213); -#150213 = AXIS2_PLACEMENT_3D('',#150214,#150215,#150216); -#150214 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, - 0.530776333563)); -#150215 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150216 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150217 = DEFINITIONAL_REPRESENTATION('',(#150218),#150222); -#150218 = LINE('',#150219,#150220); -#150219 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); -#150220 = VECTOR('',#150221,1.); -#150221 = DIRECTION('',(-1.,0.E+000)); -#150222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150223 = ORIENTED_EDGE('',*,*,#150224,.T.); -#150224 = EDGE_CURVE('',#150198,#149971,#150225,.T.); -#150225 = SURFACE_CURVE('',#150226,(#150231,#150260),.PCURVE_S1.); -#150226 = CIRCLE('',#150227,0.208574704164); -#150227 = AXIS2_PLACEMENT_3D('',#150228,#150229,#150230); -#150228 = CARTESIAN_POINT('',(1.15,10.728168876214,2.640924866458E-017) - ); -#150229 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150230 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); -#150231 = PCURVE('',#150007,#150232); -#150232 = DEFINITIONAL_REPRESENTATION('',(#150233),#150259); -#150233 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150234,#150235,#150236, - #150237,#150238,#150239,#150240,#150241,#150242,#150243,#150244, - #150245,#150246,#150247,#150248,#150249,#150250,#150251,#150252, - #150253,#150254,#150255,#150256,#150257,#150258),.UNSPECIFIED.,.F., - .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, - 3.215730725801,3.289868798011,3.364006870222,3.438144942433, - 3.512283014644,3.586421086854,3.660559159065,3.734697231276, - 3.808835303487,3.882973375698,3.957111447908,4.031249520119, - 4.10538759233,4.179525664541,4.253663736751,4.327801808962, - 4.401939881173,4.476077953384,4.550216025595,4.624354097805, - 4.698492170016,4.772630242227),.QUASI_UNIFORM_KNOTS.); -#150234 = CARTESIAN_POINT('',(3.14159265359,1.15)); -#150235 = CARTESIAN_POINT('',(3.166305344327,1.15)); -#150236 = CARTESIAN_POINT('',(3.215730725801,1.15)); -#150237 = CARTESIAN_POINT('',(3.289868798011,1.15)); -#150238 = CARTESIAN_POINT('',(3.364006870222,1.15)); -#150239 = CARTESIAN_POINT('',(3.438144942433,1.15)); -#150240 = CARTESIAN_POINT('',(3.512283014644,1.15)); -#150241 = CARTESIAN_POINT('',(3.586421086854,1.15)); -#150242 = CARTESIAN_POINT('',(3.660559159065,1.15)); -#150243 = CARTESIAN_POINT('',(3.734697231276,1.15)); -#150244 = CARTESIAN_POINT('',(3.808835303487,1.15)); -#150245 = CARTESIAN_POINT('',(3.882973375698,1.15)); -#150246 = CARTESIAN_POINT('',(3.957111447908,1.15)); -#150247 = CARTESIAN_POINT('',(4.031249520119,1.15)); -#150248 = CARTESIAN_POINT('',(4.10538759233,1.15)); -#150249 = CARTESIAN_POINT('',(4.179525664541,1.15)); -#150250 = CARTESIAN_POINT('',(4.253663736751,1.15)); -#150251 = CARTESIAN_POINT('',(4.327801808962,1.15)); -#150252 = CARTESIAN_POINT('',(4.401939881173,1.15)); -#150253 = CARTESIAN_POINT('',(4.476077953384,1.15)); -#150254 = CARTESIAN_POINT('',(4.550216025595,1.15)); -#150255 = CARTESIAN_POINT('',(4.624354097805,1.15)); -#150256 = CARTESIAN_POINT('',(4.698492170016,1.15)); -#150257 = CARTESIAN_POINT('',(4.74791755149,1.15)); -#150258 = CARTESIAN_POINT('',(4.772630242227,1.15)); -#150259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150260 = PCURVE('',#88352,#150261); -#150261 = DEFINITIONAL_REPRESENTATION('',(#150262),#150266); -#150262 = CIRCLE('',#150263,0.208574704164); -#150263 = AXIS2_PLACEMENT_2D('',#150264,#150265); -#150264 = CARTESIAN_POINT('',(0.65,0.200320883775)); -#150265 = DIRECTION('',(0.E+000,1.)); -#150266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150267 = ADVANCED_FACE('',(#150268),#150212,.F.); -#150268 = FACE_BOUND('',#150269,.T.); -#150269 = EDGE_LOOP('',(#150270,#150299,#150320,#150321)); -#150270 = ORIENTED_EDGE('',*,*,#150271,.F.); -#150271 = EDGE_CURVE('',#150272,#150274,#150276,.T.); -#150272 = VERTEX_POINT('',#150273); -#150273 = CARTESIAN_POINT('',(1.35,10.51959417205,0.530776333563)); -#150274 = VERTEX_POINT('',#150275); -#150275 = CARTESIAN_POINT('',(1.15,10.51959417205,0.530776333563)); -#150276 = SURFACE_CURVE('',#150277,(#150281,#150288),.PCURVE_S1.); -#150277 = LINE('',#150278,#150279); -#150278 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, - 0.530776333563)); -#150279 = VECTOR('',#150280,1.); -#150280 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150281 = PCURVE('',#150212,#150282); -#150282 = DEFINITIONAL_REPRESENTATION('',(#150283),#150287); -#150283 = LINE('',#150284,#150285); -#150284 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150285 = VECTOR('',#150286,1.); -#150286 = DIRECTION('',(-1.,0.E+000)); -#150287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150288 = PCURVE('',#150289,#150294); -#150289 = CYLINDRICAL_SURFACE('',#150290,0.2192697516); -#150290 = AXIS2_PLACEMENT_3D('',#150291,#150292,#150293); -#150291 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, - 0.530776333563)); -#150292 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150293 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150294 = DEFINITIONAL_REPRESENTATION('',(#150295),#150298); -#150295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150296,#150297), - .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); -#150296 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#150297 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#150298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150299 = ORIENTED_EDGE('',*,*,#150300,.T.); -#150300 = EDGE_CURVE('',#150272,#150148,#150301,.T.); -#150301 = SURFACE_CURVE('',#150302,(#150306,#150313),.PCURVE_S1.); -#150302 = LINE('',#150303,#150304); -#150303 = CARTESIAN_POINT('',(1.35,10.51959417205,0.530776333563)); -#150304 = VECTOR('',#150305,1.); -#150305 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#150306 = PCURVE('',#150212,#150307); -#150307 = DEFINITIONAL_REPRESENTATION('',(#150308),#150312); -#150308 = LINE('',#150309,#150310); -#150309 = CARTESIAN_POINT('',(1.35,0.E+000)); -#150310 = VECTOR('',#150311,1.); -#150311 = DIRECTION('',(0.E+000,-1.)); -#150312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150313 = PCURVE('',#88296,#150314); -#150314 = DEFINITIONAL_REPRESENTATION('',(#150315),#150319); -#150315 = LINE('',#150316,#150317); -#150316 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388626E-003)); -#150317 = VECTOR('',#150318,1.); -#150318 = DIRECTION('',(-1.,0.E+000)); -#150319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150320 = ORIENTED_EDGE('',*,*,#150197,.T.); -#150321 = ORIENTED_EDGE('',*,*,#150322,.F.); -#150322 = EDGE_CURVE('',#150274,#150198,#150323,.T.); -#150323 = SURFACE_CURVE('',#150324,(#150328,#150335),.PCURVE_S1.); -#150324 = LINE('',#150325,#150326); -#150325 = CARTESIAN_POINT('',(1.15,10.51959417205,0.530776333563)); -#150326 = VECTOR('',#150327,1.); -#150327 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#150328 = PCURVE('',#150212,#150329); -#150329 = DEFINITIONAL_REPRESENTATION('',(#150330),#150334); -#150330 = LINE('',#150331,#150332); -#150331 = CARTESIAN_POINT('',(1.15,0.E+000)); -#150332 = VECTOR('',#150333,1.); -#150333 = DIRECTION('',(0.E+000,-1.)); -#150334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150335 = PCURVE('',#88352,#150336); -#150336 = DEFINITIONAL_REPRESENTATION('',(#150337),#150341); -#150337 = LINE('',#150338,#150339); -#150338 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); -#150339 = VECTOR('',#150340,1.); -#150340 = DIRECTION('',(1.,0.E+000)); -#150341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#152580 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#152581 = CARTESIAN_POINT('',(-0.288738015215,0.408895587939)); +#152582 = CARTESIAN_POINT('',(-0.469369007607,9.603353169323E-002)); +#152583 = CARTESIAN_POINT('',(-0.65,-0.216828524552)); +#152584 = CARTESIAN_POINT('',(-0.830630992393,9.603353169323E-002)); +#152585 = CARTESIAN_POINT('',(-1.011261984785,0.408895587939)); +#152586 = CARTESIAN_POINT('',(-0.65,0.408895587939)); +#152587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150342 = ADVANCED_FACE('',(#150343),#150087,.F.); -#150343 = FACE_BOUND('',#150344,.T.); -#150344 = EDGE_LOOP('',(#150345,#150374,#150395,#150396)); -#150345 = ORIENTED_EDGE('',*,*,#150346,.F.); -#150346 = EDGE_CURVE('',#150347,#150349,#150351,.T.); -#150347 = VERTEX_POINT('',#150348); -#150348 = CARTESIAN_POINT('',(1.15,10.419594812019,0.530776333563)); -#150349 = VERTEX_POINT('',#150350); -#150350 = CARTESIAN_POINT('',(1.35,10.419594812019,0.530776333563)); -#150351 = SURFACE_CURVE('',#150352,(#150356,#150363),.PCURVE_S1.); -#150352 = LINE('',#150353,#150354); -#150353 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, - 0.530776333563)); -#150354 = VECTOR('',#150355,1.); -#150355 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150356 = PCURVE('',#150087,#150357); -#150357 = DEFINITIONAL_REPRESENTATION('',(#150358),#150362); -#150358 = LINE('',#150359,#150360); -#150359 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150360 = VECTOR('',#150361,1.); -#150361 = DIRECTION('',(-1.,0.E+000)); -#150362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) + ) ); +#152588 = ORIENTED_EDGE('',*,*,#152589,.T.); +#152589 = EDGE_CURVE('',#152540,#152590,#152592,.T.); +#152590 = VERTEX_POINT('',#152591); +#152591 = CARTESIAN_POINT('',(1.15,10.51959417205,0.E+000)); +#152592 = SURFACE_CURVE('',#152593,(#152597,#152603),.PCURVE_S1.); +#152593 = LINE('',#152594,#152595); +#152594 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205,0.E+000 + )); +#152595 = VECTOR('',#152596,1.); +#152596 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152597 = PCURVE('',#152399,#152598); +#152598 = DEFINITIONAL_REPRESENTATION('',(#152599),#152602); +#152599 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152600,#152601), + .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); +#152600 = CARTESIAN_POINT('',(3.14159265359,1.35)); +#152601 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#152602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#150363 = PCURVE('',#150364,#150369); -#150364 = CYLINDRICAL_SURFACE('',#150365,0.119270391569); -#150365 = AXIS2_PLACEMENT_3D('',#150366,#150367,#150368); -#150366 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, +#152603 = PCURVE('',#152604,#152609); +#152604 = PLANE('',#152605); +#152605 = AXIS2_PLACEMENT_3D('',#152606,#152607,#152608); +#152606 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, + 0.530776333563)); +#152607 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152608 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152609 = DEFINITIONAL_REPRESENTATION('',(#152610),#152614); +#152610 = LINE('',#152611,#152612); +#152611 = CARTESIAN_POINT('',(0.E+000,-0.530776333563)); +#152612 = VECTOR('',#152613,1.); +#152613 = DIRECTION('',(-1.,0.E+000)); +#152614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152615 = ORIENTED_EDGE('',*,*,#152616,.T.); +#152616 = EDGE_CURVE('',#152590,#152363,#152617,.T.); +#152617 = SURFACE_CURVE('',#152618,(#152623,#152652),.PCURVE_S1.); +#152618 = CIRCLE('',#152619,0.208574704164); +#152619 = AXIS2_PLACEMENT_3D('',#152620,#152621,#152622); +#152620 = CARTESIAN_POINT('',(1.15,10.728168876214,2.640924866458E-017) + ); +#152621 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152622 = DIRECTION('',(8.881784197001E-016,1.,0.E+000)); +#152623 = PCURVE('',#152399,#152624); +#152624 = DEFINITIONAL_REPRESENTATION('',(#152625),#152651); +#152625 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152626,#152627,#152628, + #152629,#152630,#152631,#152632,#152633,#152634,#152635,#152636, + #152637,#152638,#152639,#152640,#152641,#152642,#152643,#152644, + #152645,#152646,#152647,#152648,#152649,#152650),.UNSPECIFIED.,.F., + .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, + 3.215730725801,3.289868798011,3.364006870222,3.438144942433, + 3.512283014644,3.586421086854,3.660559159065,3.734697231276, + 3.808835303487,3.882973375698,3.957111447908,4.031249520119, + 4.10538759233,4.179525664541,4.253663736751,4.327801808962, + 4.401939881173,4.476077953384,4.550216025595,4.624354097805, + 4.698492170016,4.772630242227),.QUASI_UNIFORM_KNOTS.); +#152626 = CARTESIAN_POINT('',(3.14159265359,1.15)); +#152627 = CARTESIAN_POINT('',(3.166305344327,1.15)); +#152628 = CARTESIAN_POINT('',(3.215730725801,1.15)); +#152629 = CARTESIAN_POINT('',(3.289868798011,1.15)); +#152630 = CARTESIAN_POINT('',(3.364006870222,1.15)); +#152631 = CARTESIAN_POINT('',(3.438144942433,1.15)); +#152632 = CARTESIAN_POINT('',(3.512283014644,1.15)); +#152633 = CARTESIAN_POINT('',(3.586421086854,1.15)); +#152634 = CARTESIAN_POINT('',(3.660559159065,1.15)); +#152635 = CARTESIAN_POINT('',(3.734697231276,1.15)); +#152636 = CARTESIAN_POINT('',(3.808835303487,1.15)); +#152637 = CARTESIAN_POINT('',(3.882973375698,1.15)); +#152638 = CARTESIAN_POINT('',(3.957111447908,1.15)); +#152639 = CARTESIAN_POINT('',(4.031249520119,1.15)); +#152640 = CARTESIAN_POINT('',(4.10538759233,1.15)); +#152641 = CARTESIAN_POINT('',(4.179525664541,1.15)); +#152642 = CARTESIAN_POINT('',(4.253663736751,1.15)); +#152643 = CARTESIAN_POINT('',(4.327801808962,1.15)); +#152644 = CARTESIAN_POINT('',(4.401939881173,1.15)); +#152645 = CARTESIAN_POINT('',(4.476077953384,1.15)); +#152646 = CARTESIAN_POINT('',(4.550216025595,1.15)); +#152647 = CARTESIAN_POINT('',(4.624354097805,1.15)); +#152648 = CARTESIAN_POINT('',(4.698492170016,1.15)); +#152649 = CARTESIAN_POINT('',(4.74791755149,1.15)); +#152650 = CARTESIAN_POINT('',(4.772630242227,1.15)); +#152651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152652 = PCURVE('',#90744,#152653); +#152653 = DEFINITIONAL_REPRESENTATION('',(#152654),#152658); +#152654 = CIRCLE('',#152655,0.208574704164); +#152655 = AXIS2_PLACEMENT_2D('',#152656,#152657); +#152656 = CARTESIAN_POINT('',(0.65,0.200320883775)); +#152657 = DIRECTION('',(0.E+000,1.)); +#152658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152659 = ADVANCED_FACE('',(#152660),#152604,.F.); +#152660 = FACE_BOUND('',#152661,.T.); +#152661 = EDGE_LOOP('',(#152662,#152691,#152712,#152713)); +#152662 = ORIENTED_EDGE('',*,*,#152663,.F.); +#152663 = EDGE_CURVE('',#152664,#152666,#152668,.T.); +#152664 = VERTEX_POINT('',#152665); +#152665 = CARTESIAN_POINT('',(1.35,10.51959417205,0.530776333563)); +#152666 = VERTEX_POINT('',#152667); +#152667 = CARTESIAN_POINT('',(1.15,10.51959417205,0.530776333563)); +#152668 = SURFACE_CURVE('',#152669,(#152673,#152680),.PCURVE_S1.); +#152669 = LINE('',#152670,#152671); +#152670 = CARTESIAN_POINT('',(1.929474137441E-015,10.51959417205, + 0.530776333563)); +#152671 = VECTOR('',#152672,1.); +#152672 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152673 = PCURVE('',#152604,#152674); +#152674 = DEFINITIONAL_REPRESENTATION('',(#152675),#152679); +#152675 = LINE('',#152676,#152677); +#152676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152677 = VECTOR('',#152678,1.); +#152678 = DIRECTION('',(-1.,0.E+000)); +#152679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152680 = PCURVE('',#152681,#152686); +#152681 = CYLINDRICAL_SURFACE('',#152682,0.2192697516); +#152682 = AXIS2_PLACEMENT_3D('',#152683,#152684,#152685); +#152683 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, 0.530776333563)); -#150367 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150368 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150369 = DEFINITIONAL_REPRESENTATION('',(#150370),#150373); -#150370 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150371,#150372), +#152684 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152685 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152686 = DEFINITIONAL_REPRESENTATION('',(#152687),#152690); +#152687 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152688,#152689), + .UNSPECIFIED.,.F.,.F.,(2,2),(-1.35,-1.15),.PIECEWISE_BEZIER_KNOTS.); +#152688 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#152689 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#152690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152691 = ORIENTED_EDGE('',*,*,#152692,.T.); +#152692 = EDGE_CURVE('',#152664,#152540,#152693,.T.); +#152693 = SURFACE_CURVE('',#152694,(#152698,#152705),.PCURVE_S1.); +#152694 = LINE('',#152695,#152696); +#152695 = CARTESIAN_POINT('',(1.35,10.51959417205,0.530776333563)); +#152696 = VECTOR('',#152697,1.); +#152697 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#152698 = PCURVE('',#152604,#152699); +#152699 = DEFINITIONAL_REPRESENTATION('',(#152700),#152704); +#152700 = LINE('',#152701,#152702); +#152701 = CARTESIAN_POINT('',(1.35,0.E+000)); +#152702 = VECTOR('',#152703,1.); +#152703 = DIRECTION('',(0.E+000,-1.)); +#152704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152705 = PCURVE('',#90688,#152706); +#152706 = DEFINITIONAL_REPRESENTATION('',(#152707),#152711); +#152707 = LINE('',#152708,#152709); +#152708 = CARTESIAN_POINT('',(-0.119223666437,-8.253820388626E-003)); +#152709 = VECTOR('',#152710,1.); +#152710 = DIRECTION('',(-1.,0.E+000)); +#152711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152712 = ORIENTED_EDGE('',*,*,#152589,.T.); +#152713 = ORIENTED_EDGE('',*,*,#152714,.F.); +#152714 = EDGE_CURVE('',#152666,#152590,#152715,.T.); +#152715 = SURFACE_CURVE('',#152716,(#152720,#152727),.PCURVE_S1.); +#152716 = LINE('',#152717,#152718); +#152717 = CARTESIAN_POINT('',(1.15,10.51959417205,0.530776333563)); +#152718 = VECTOR('',#152719,1.); +#152719 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#152720 = PCURVE('',#152604,#152721); +#152721 = DEFINITIONAL_REPRESENTATION('',(#152722),#152726); +#152722 = LINE('',#152723,#152724); +#152723 = CARTESIAN_POINT('',(1.15,0.E+000)); +#152724 = VECTOR('',#152725,1.); +#152725 = DIRECTION('',(0.E+000,-1.)); +#152726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152727 = PCURVE('',#90744,#152728); +#152728 = DEFINITIONAL_REPRESENTATION('',(#152729),#152733); +#152729 = LINE('',#152730,#152731); +#152730 = CARTESIAN_POINT('',(0.119223666437,-8.253820388628E-003)); +#152731 = VECTOR('',#152732,1.); +#152732 = DIRECTION('',(1.,0.E+000)); +#152733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152734 = ADVANCED_FACE('',(#152735),#152479,.F.); +#152735 = FACE_BOUND('',#152736,.T.); +#152736 = EDGE_LOOP('',(#152737,#152766,#152787,#152788)); +#152737 = ORIENTED_EDGE('',*,*,#152738,.F.); +#152738 = EDGE_CURVE('',#152739,#152741,#152743,.T.); +#152739 = VERTEX_POINT('',#152740); +#152740 = CARTESIAN_POINT('',(1.15,10.419594812019,0.530776333563)); +#152741 = VERTEX_POINT('',#152742); +#152742 = CARTESIAN_POINT('',(1.35,10.419594812019,0.530776333563)); +#152743 = SURFACE_CURVE('',#152744,(#152748,#152755),.PCURVE_S1.); +#152744 = LINE('',#152745,#152746); +#152745 = CARTESIAN_POINT('',(1.840656863878E-015,10.419594812019, + 0.530776333563)); +#152746 = VECTOR('',#152747,1.); +#152747 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152748 = PCURVE('',#152479,#152749); +#152749 = DEFINITIONAL_REPRESENTATION('',(#152750),#152754); +#152750 = LINE('',#152751,#152752); +#152751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#152752 = VECTOR('',#152753,1.); +#152753 = DIRECTION('',(-1.,0.E+000)); +#152754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152755 = PCURVE('',#152756,#152761); +#152756 = CYLINDRICAL_SURFACE('',#152757,0.119270391569); +#152757 = AXIS2_PLACEMENT_3D('',#152758,#152759,#152760); +#152758 = CARTESIAN_POINT('',(1.734723475977E-015,10.30032442045, + 0.530776333563)); +#152759 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152760 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152761 = DEFINITIONAL_REPRESENTATION('',(#152762),#152765); +#152762 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152763,#152764), .UNSPECIFIED.,.F.,.F.,(2,2),(1.15,1.35),.PIECEWISE_BEZIER_KNOTS.); -#150371 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#150372 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#150373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150374 = ORIENTED_EDGE('',*,*,#150375,.T.); -#150375 = EDGE_CURVE('',#150347,#150073,#150376,.T.); -#150376 = SURFACE_CURVE('',#150377,(#150381,#150388),.PCURVE_S1.); -#150377 = LINE('',#150378,#150379); -#150378 = CARTESIAN_POINT('',(1.15,10.419594812019,0.530776333563)); -#150379 = VECTOR('',#150380,1.); -#150380 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#150381 = PCURVE('',#150087,#150382); -#150382 = DEFINITIONAL_REPRESENTATION('',(#150383),#150387); -#150383 = LINE('',#150384,#150385); -#150384 = CARTESIAN_POINT('',(-1.15,0.E+000)); -#150385 = VECTOR('',#150386,1.); -#150386 = DIRECTION('',(0.E+000,-1.)); -#150387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150388 = PCURVE('',#88352,#150389); -#150389 = DEFINITIONAL_REPRESENTATION('',(#150390),#150394); -#150390 = LINE('',#150391,#150392); -#150391 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); -#150392 = VECTOR('',#150393,1.); -#150393 = DIRECTION('',(1.,0.E+000)); -#150394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#152763 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#152764 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#152765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152766 = ORIENTED_EDGE('',*,*,#152767,.T.); +#152767 = EDGE_CURVE('',#152739,#152465,#152768,.T.); +#152768 = SURFACE_CURVE('',#152769,(#152773,#152780),.PCURVE_S1.); +#152769 = LINE('',#152770,#152771); +#152770 = CARTESIAN_POINT('',(1.15,10.419594812019,0.530776333563)); +#152771 = VECTOR('',#152772,1.); +#152772 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#152773 = PCURVE('',#152479,#152774); +#152774 = DEFINITIONAL_REPRESENTATION('',(#152775),#152779); +#152775 = LINE('',#152776,#152777); +#152776 = CARTESIAN_POINT('',(-1.15,0.E+000)); +#152777 = VECTOR('',#152778,1.); +#152778 = DIRECTION('',(0.E+000,-1.)); +#152779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#150395 = ORIENTED_EDGE('',*,*,#150072,.T.); -#150396 = ORIENTED_EDGE('',*,*,#150397,.F.); -#150397 = EDGE_CURVE('',#150349,#150023,#150398,.T.); -#150398 = SURFACE_CURVE('',#150399,(#150403,#150410),.PCURVE_S1.); -#150399 = LINE('',#150400,#150401); -#150400 = CARTESIAN_POINT('',(1.35,10.419594812019,0.530776333563)); -#150401 = VECTOR('',#150402,1.); -#150402 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#150403 = PCURVE('',#150087,#150404); -#150404 = DEFINITIONAL_REPRESENTATION('',(#150405),#150409); -#150405 = LINE('',#150406,#150407); -#150406 = CARTESIAN_POINT('',(-1.35,0.E+000)); -#150407 = VECTOR('',#150408,1.); -#150408 = DIRECTION('',(0.E+000,-1.)); -#150409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150410 = PCURVE('',#88296,#150411); -#150411 = DEFINITIONAL_REPRESENTATION('',(#150412),#150416); -#150412 = LINE('',#150413,#150414); -#150413 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); -#150414 = VECTOR('',#150415,1.); -#150415 = DIRECTION('',(-1.,0.E+000)); -#150416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150417 = ADVANCED_FACE('',(#150418),#150289,.T.); -#150418 = FACE_BOUND('',#150419,.T.); -#150419 = EDGE_LOOP('',(#150420,#150466,#150467,#150517)); -#150420 = ORIENTED_EDGE('',*,*,#150421,.T.); -#150421 = EDGE_CURVE('',#150422,#150272,#150424,.T.); -#150422 = VERTEX_POINT('',#150423); -#150423 = CARTESIAN_POINT('',(1.35,10.304819755875,0.75)); -#150424 = SURFACE_CURVE('',#150425,(#150430,#150459),.PCURVE_S1.); -#150425 = CIRCLE('',#150426,0.2192697516); -#150426 = AXIS2_PLACEMENT_3D('',#150427,#150428,#150429); -#150427 = CARTESIAN_POINT('',(1.35,10.30032442045,0.530776333563)); -#150428 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150429 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150430 = PCURVE('',#150289,#150431); -#150431 = DEFINITIONAL_REPRESENTATION('',(#150432),#150458); -#150432 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150433,#150434,#150435, - #150436,#150437,#150438,#150439,#150440,#150441,#150442,#150443, - #150444,#150445,#150446,#150447,#150448,#150449,#150450,#150451, - #150452,#150453,#150454,#150455,#150456,#150457),.UNSPECIFIED.,.F., +#152780 = PCURVE('',#90744,#152781); +#152781 = DEFINITIONAL_REPRESENTATION('',(#152782),#152786); +#152782 = LINE('',#152783,#152784); +#152783 = CARTESIAN_POINT('',(0.119223666437,-0.108253180419)); +#152784 = VECTOR('',#152785,1.); +#152785 = DIRECTION('',(1.,0.E+000)); +#152786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152787 = ORIENTED_EDGE('',*,*,#152464,.T.); +#152788 = ORIENTED_EDGE('',*,*,#152789,.F.); +#152789 = EDGE_CURVE('',#152741,#152415,#152790,.T.); +#152790 = SURFACE_CURVE('',#152791,(#152795,#152802),.PCURVE_S1.); +#152791 = LINE('',#152792,#152793); +#152792 = CARTESIAN_POINT('',(1.35,10.419594812019,0.530776333563)); +#152793 = VECTOR('',#152794,1.); +#152794 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#152795 = PCURVE('',#152479,#152796); +#152796 = DEFINITIONAL_REPRESENTATION('',(#152797),#152801); +#152797 = LINE('',#152798,#152799); +#152798 = CARTESIAN_POINT('',(-1.35,0.E+000)); +#152799 = VECTOR('',#152800,1.); +#152800 = DIRECTION('',(0.E+000,-1.)); +#152801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152802 = PCURVE('',#90688,#152803); +#152803 = DEFINITIONAL_REPRESENTATION('',(#152804),#152808); +#152804 = LINE('',#152805,#152806); +#152805 = CARTESIAN_POINT('',(-0.119223666437,-0.108253180419)); +#152806 = VECTOR('',#152807,1.); +#152807 = DIRECTION('',(-1.,0.E+000)); +#152808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152809 = ADVANCED_FACE('',(#152810),#152681,.T.); +#152810 = FACE_BOUND('',#152811,.T.); +#152811 = EDGE_LOOP('',(#152812,#152858,#152859,#152909)); +#152812 = ORIENTED_EDGE('',*,*,#152813,.T.); +#152813 = EDGE_CURVE('',#152814,#152664,#152816,.T.); +#152814 = VERTEX_POINT('',#152815); +#152815 = CARTESIAN_POINT('',(1.35,10.304819755875,0.75)); +#152816 = SURFACE_CURVE('',#152817,(#152822,#152851),.PCURVE_S1.); +#152817 = CIRCLE('',#152818,0.2192697516); +#152818 = AXIS2_PLACEMENT_3D('',#152819,#152820,#152821); +#152819 = CARTESIAN_POINT('',(1.35,10.30032442045,0.530776333563)); +#152820 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152821 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152822 = PCURVE('',#152681,#152823); +#152823 = DEFINITIONAL_REPRESENTATION('',(#152824),#152850); +#152824 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152825,#152826,#152827, + #152828,#152829,#152830,#152831,#152832,#152833,#152834,#152835, + #152836,#152837,#152838,#152839,#152840,#152841,#152842,#152843, + #152844,#152845,#152846,#152847,#152848,#152849),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -185552,60 +188554,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#150433 = CARTESIAN_POINT('',(1.591299156552,-1.35)); -#150434 = CARTESIAN_POINT('',(1.614788451962,-1.35)); -#150435 = CARTESIAN_POINT('',(1.661767042781,-1.35)); -#150436 = CARTESIAN_POINT('',(1.73223492901,-1.35)); -#150437 = CARTESIAN_POINT('',(1.802702815239,-1.35)); -#150438 = CARTESIAN_POINT('',(1.873170701468,-1.35)); -#150439 = CARTESIAN_POINT('',(1.943638587697,-1.35)); -#150440 = CARTESIAN_POINT('',(2.014106473926,-1.35)); -#150441 = CARTESIAN_POINT('',(2.084574360155,-1.35)); -#150442 = CARTESIAN_POINT('',(2.155042246384,-1.35)); -#150443 = CARTESIAN_POINT('',(2.225510132613,-1.35)); -#150444 = CARTESIAN_POINT('',(2.295978018842,-1.35)); -#150445 = CARTESIAN_POINT('',(2.366445905071,-1.35)); -#150446 = CARTESIAN_POINT('',(2.4369137913,-1.35)); -#150447 = CARTESIAN_POINT('',(2.507381677529,-1.35)); -#150448 = CARTESIAN_POINT('',(2.577849563758,-1.35)); -#150449 = CARTESIAN_POINT('',(2.648317449987,-1.35)); -#150450 = CARTESIAN_POINT('',(2.718785336216,-1.35)); -#150451 = CARTESIAN_POINT('',(2.789253222445,-1.35)); -#150452 = CARTESIAN_POINT('',(2.859721108674,-1.35)); -#150453 = CARTESIAN_POINT('',(2.930188994903,-1.35)); -#150454 = CARTESIAN_POINT('',(3.000656881132,-1.35)); -#150455 = CARTESIAN_POINT('',(3.071124767361,-1.35)); -#150456 = CARTESIAN_POINT('',(3.11810335818,-1.35)); -#150457 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#150458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150459 = PCURVE('',#88296,#150460); -#150460 = DEFINITIONAL_REPRESENTATION('',(#150461),#150465); -#150461 = CIRCLE('',#150462,0.2192697516); -#150462 = AXIS2_PLACEMENT_2D('',#150463,#150464); -#150463 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#150464 = DIRECTION('',(0.E+000,-1.)); -#150465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150466 = ORIENTED_EDGE('',*,*,#150271,.T.); -#150467 = ORIENTED_EDGE('',*,*,#150468,.F.); -#150468 = EDGE_CURVE('',#150469,#150274,#150471,.T.); -#150469 = VERTEX_POINT('',#150470); -#150470 = CARTESIAN_POINT('',(1.15,10.304819755875,0.75)); -#150471 = SURFACE_CURVE('',#150472,(#150477,#150506),.PCURVE_S1.); -#150472 = CIRCLE('',#150473,0.2192697516); -#150473 = AXIS2_PLACEMENT_3D('',#150474,#150475,#150476); -#150474 = CARTESIAN_POINT('',(1.15,10.30032442045,0.530776333563)); -#150475 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150476 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150477 = PCURVE('',#150289,#150478); -#150478 = DEFINITIONAL_REPRESENTATION('',(#150479),#150505); -#150479 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150480,#150481,#150482, - #150483,#150484,#150485,#150486,#150487,#150488,#150489,#150490, - #150491,#150492,#150493,#150494,#150495,#150496,#150497,#150498, - #150499,#150500,#150501,#150502,#150503,#150504),.UNSPECIFIED.,.F., +#152825 = CARTESIAN_POINT('',(1.591299156552,-1.35)); +#152826 = CARTESIAN_POINT('',(1.614788451962,-1.35)); +#152827 = CARTESIAN_POINT('',(1.661767042781,-1.35)); +#152828 = CARTESIAN_POINT('',(1.73223492901,-1.35)); +#152829 = CARTESIAN_POINT('',(1.802702815239,-1.35)); +#152830 = CARTESIAN_POINT('',(1.873170701468,-1.35)); +#152831 = CARTESIAN_POINT('',(1.943638587697,-1.35)); +#152832 = CARTESIAN_POINT('',(2.014106473926,-1.35)); +#152833 = CARTESIAN_POINT('',(2.084574360155,-1.35)); +#152834 = CARTESIAN_POINT('',(2.155042246384,-1.35)); +#152835 = CARTESIAN_POINT('',(2.225510132613,-1.35)); +#152836 = CARTESIAN_POINT('',(2.295978018842,-1.35)); +#152837 = CARTESIAN_POINT('',(2.366445905071,-1.35)); +#152838 = CARTESIAN_POINT('',(2.4369137913,-1.35)); +#152839 = CARTESIAN_POINT('',(2.507381677529,-1.35)); +#152840 = CARTESIAN_POINT('',(2.577849563758,-1.35)); +#152841 = CARTESIAN_POINT('',(2.648317449987,-1.35)); +#152842 = CARTESIAN_POINT('',(2.718785336216,-1.35)); +#152843 = CARTESIAN_POINT('',(2.789253222445,-1.35)); +#152844 = CARTESIAN_POINT('',(2.859721108674,-1.35)); +#152845 = CARTESIAN_POINT('',(2.930188994903,-1.35)); +#152846 = CARTESIAN_POINT('',(3.000656881132,-1.35)); +#152847 = CARTESIAN_POINT('',(3.071124767361,-1.35)); +#152848 = CARTESIAN_POINT('',(3.11810335818,-1.35)); +#152849 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#152850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152851 = PCURVE('',#90688,#152852); +#152852 = DEFINITIONAL_REPRESENTATION('',(#152853),#152857); +#152853 = CIRCLE('',#152854,0.2192697516); +#152854 = AXIS2_PLACEMENT_2D('',#152855,#152856); +#152855 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#152856 = DIRECTION('',(0.E+000,-1.)); +#152857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152858 = ORIENTED_EDGE('',*,*,#152663,.T.); +#152859 = ORIENTED_EDGE('',*,*,#152860,.F.); +#152860 = EDGE_CURVE('',#152861,#152666,#152863,.T.); +#152861 = VERTEX_POINT('',#152862); +#152862 = CARTESIAN_POINT('',(1.15,10.304819755875,0.75)); +#152863 = SURFACE_CURVE('',#152864,(#152869,#152898),.PCURVE_S1.); +#152864 = CIRCLE('',#152865,0.2192697516); +#152865 = AXIS2_PLACEMENT_3D('',#152866,#152867,#152868); +#152866 = CARTESIAN_POINT('',(1.15,10.30032442045,0.530776333563)); +#152867 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152868 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152869 = PCURVE('',#152681,#152870); +#152870 = DEFINITIONAL_REPRESENTATION('',(#152871),#152897); +#152871 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152872,#152873,#152874, + #152875,#152876,#152877,#152878,#152879,#152880,#152881,#152882, + #152883,#152884,#152885,#152886,#152887,#152888,#152889,#152890, + #152891,#152892,#152893,#152894,#152895,#152896),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.591299156552, 1.661767042781,1.73223492901,1.802702815239,1.873170701468, 1.943638587697,2.014106473926,2.084574360155,2.155042246384, @@ -185613,98 +188615,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.507381677529,2.577849563758,2.648317449987,2.718785336216, 2.789253222445,2.859721108674,2.930188994903,3.000656881132, 3.071124767361,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#150480 = CARTESIAN_POINT('',(1.591299156552,-1.15)); -#150481 = CARTESIAN_POINT('',(1.614788451962,-1.15)); -#150482 = CARTESIAN_POINT('',(1.661767042781,-1.15)); -#150483 = CARTESIAN_POINT('',(1.73223492901,-1.15)); -#150484 = CARTESIAN_POINT('',(1.802702815239,-1.15)); -#150485 = CARTESIAN_POINT('',(1.873170701468,-1.15)); -#150486 = CARTESIAN_POINT('',(1.943638587697,-1.15)); -#150487 = CARTESIAN_POINT('',(2.014106473926,-1.15)); -#150488 = CARTESIAN_POINT('',(2.084574360155,-1.15)); -#150489 = CARTESIAN_POINT('',(2.155042246384,-1.15)); -#150490 = CARTESIAN_POINT('',(2.225510132613,-1.15)); -#150491 = CARTESIAN_POINT('',(2.295978018842,-1.15)); -#150492 = CARTESIAN_POINT('',(2.366445905071,-1.15)); -#150493 = CARTESIAN_POINT('',(2.4369137913,-1.15)); -#150494 = CARTESIAN_POINT('',(2.507381677529,-1.15)); -#150495 = CARTESIAN_POINT('',(2.577849563758,-1.15)); -#150496 = CARTESIAN_POINT('',(2.648317449987,-1.15)); -#150497 = CARTESIAN_POINT('',(2.718785336216,-1.15)); -#150498 = CARTESIAN_POINT('',(2.789253222445,-1.15)); -#150499 = CARTESIAN_POINT('',(2.859721108674,-1.15)); -#150500 = CARTESIAN_POINT('',(2.930188994903,-1.15)); -#150501 = CARTESIAN_POINT('',(3.000656881132,-1.15)); -#150502 = CARTESIAN_POINT('',(3.071124767361,-1.15)); -#150503 = CARTESIAN_POINT('',(3.11810335818,-1.15)); -#150504 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#150505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150506 = PCURVE('',#88352,#150507); -#150507 = DEFINITIONAL_REPRESENTATION('',(#150508),#150516); -#150508 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150509,#150510,#150511, - #150512,#150513,#150514,#150515),.UNSPECIFIED.,.T.,.F.) +#152872 = CARTESIAN_POINT('',(1.591299156552,-1.15)); +#152873 = CARTESIAN_POINT('',(1.614788451962,-1.15)); +#152874 = CARTESIAN_POINT('',(1.661767042781,-1.15)); +#152875 = CARTESIAN_POINT('',(1.73223492901,-1.15)); +#152876 = CARTESIAN_POINT('',(1.802702815239,-1.15)); +#152877 = CARTESIAN_POINT('',(1.873170701468,-1.15)); +#152878 = CARTESIAN_POINT('',(1.943638587697,-1.15)); +#152879 = CARTESIAN_POINT('',(2.014106473926,-1.15)); +#152880 = CARTESIAN_POINT('',(2.084574360155,-1.15)); +#152881 = CARTESIAN_POINT('',(2.155042246384,-1.15)); +#152882 = CARTESIAN_POINT('',(2.225510132613,-1.15)); +#152883 = CARTESIAN_POINT('',(2.295978018842,-1.15)); +#152884 = CARTESIAN_POINT('',(2.366445905071,-1.15)); +#152885 = CARTESIAN_POINT('',(2.4369137913,-1.15)); +#152886 = CARTESIAN_POINT('',(2.507381677529,-1.15)); +#152887 = CARTESIAN_POINT('',(2.577849563758,-1.15)); +#152888 = CARTESIAN_POINT('',(2.648317449987,-1.15)); +#152889 = CARTESIAN_POINT('',(2.718785336216,-1.15)); +#152890 = CARTESIAN_POINT('',(2.789253222445,-1.15)); +#152891 = CARTESIAN_POINT('',(2.859721108674,-1.15)); +#152892 = CARTESIAN_POINT('',(2.930188994903,-1.15)); +#152893 = CARTESIAN_POINT('',(3.000656881132,-1.15)); +#152894 = CARTESIAN_POINT('',(3.071124767361,-1.15)); +#152895 = CARTESIAN_POINT('',(3.11810335818,-1.15)); +#152896 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#152897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152898 = PCURVE('',#90744,#152899); +#152899 = DEFINITIONAL_REPRESENTATION('',(#152900),#152908); +#152900 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152901,#152902,#152903, + #152904,#152905,#152906,#152907),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#150509 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#150510 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); -#150511 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); -#150512 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); -#150513 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); -#150514 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); -#150515 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); -#150516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150517 = ORIENTED_EDGE('',*,*,#150518,.T.); -#150518 = EDGE_CURVE('',#150469,#150422,#150519,.T.); -#150519 = SURFACE_CURVE('',#150520,(#150524,#150530),.PCURVE_S1.); -#150520 = LINE('',#150521,#150522); -#150521 = CARTESIAN_POINT('',(1.35,10.304819755875,0.75)); -#150522 = VECTOR('',#150523,1.); -#150523 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); -#150524 = PCURVE('',#150289,#150525); -#150525 = DEFINITIONAL_REPRESENTATION('',(#150526),#150529); -#150526 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150527,#150528), +#152901 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#152902 = CARTESIAN_POINT('',(-0.260562683897,-0.446793323588)); +#152903 = CARTESIAN_POINT('',(-7.066950872999E-002,-0.117888696189)); +#152904 = CARTESIAN_POINT('',(0.119223666437,0.211015931211)); +#152905 = CARTESIAN_POINT('',(0.309116841604,-0.117888696189)); +#152906 = CARTESIAN_POINT('',(0.499010016771,-0.446793323588)); +#152907 = CARTESIAN_POINT('',(0.119223666437,-0.446793323588)); +#152908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152909 = ORIENTED_EDGE('',*,*,#152910,.T.); +#152910 = EDGE_CURVE('',#152861,#152814,#152911,.T.); +#152911 = SURFACE_CURVE('',#152912,(#152916,#152922),.PCURVE_S1.); +#152912 = LINE('',#152913,#152914); +#152913 = CARTESIAN_POINT('',(1.35,10.304819755875,0.75)); +#152914 = VECTOR('',#152915,1.); +#152915 = DIRECTION('',(1.,-8.881784197001E-016,0.E+000)); +#152916 = PCURVE('',#152681,#152917); +#152917 = DEFINITIONAL_REPRESENTATION('',(#152918),#152921); +#152918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152919,#152920), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.2,2.22044604925E-016), .PIECEWISE_BEZIER_KNOTS.); -#150527 = CARTESIAN_POINT('',(1.591299156552,-1.15)); -#150528 = CARTESIAN_POINT('',(1.591299156552,-1.35)); -#150529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150530 = PCURVE('',#88324,#150531); -#150531 = DEFINITIONAL_REPRESENTATION('',(#150532),#150536); -#150532 = LINE('',#150533,#150534); -#150533 = CARTESIAN_POINT('',(-0.223028236564,-2.22044604925E-016)); -#150534 = VECTOR('',#150535,1.); -#150535 = DIRECTION('',(-8.881784197001E-016,1.)); -#150536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150537 = ADVANCED_FACE('',(#150538),#150364,.F.); -#150538 = FACE_BOUND('',#150539,.F.); -#150539 = EDGE_LOOP('',(#150540,#150590,#150612,#150656)); -#150540 = ORIENTED_EDGE('',*,*,#150541,.F.); -#150541 = EDGE_CURVE('',#150542,#150347,#150544,.T.); -#150542 = VERTEX_POINT('',#150543); -#150543 = CARTESIAN_POINT('',(1.15,10.303662633502,0.65)); -#150544 = SURFACE_CURVE('',#150545,(#150550,#150579),.PCURVE_S1.); -#150545 = CIRCLE('',#150546,0.119270391569); -#150546 = AXIS2_PLACEMENT_3D('',#150547,#150548,#150549); -#150547 = CARTESIAN_POINT('',(1.15,10.30032442045,0.530776333563)); -#150548 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150549 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150550 = PCURVE('',#150364,#150551); -#150551 = DEFINITIONAL_REPRESENTATION('',(#150552),#150578); -#150552 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150553,#150554,#150555, - #150556,#150557,#150558,#150559,#150560,#150561,#150562,#150563, - #150564,#150565,#150566,#150567,#150568,#150569,#150570,#150571, - #150572,#150573,#150574,#150575,#150576,#150577),.UNSPECIFIED.,.F., +#152919 = CARTESIAN_POINT('',(1.591299156552,-1.15)); +#152920 = CARTESIAN_POINT('',(1.591299156552,-1.35)); +#152921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152922 = PCURVE('',#90716,#152923); +#152923 = DEFINITIONAL_REPRESENTATION('',(#152924),#152928); +#152924 = LINE('',#152925,#152926); +#152925 = CARTESIAN_POINT('',(-0.223028236564,-2.22044604925E-016)); +#152926 = VECTOR('',#152927,1.); +#152927 = DIRECTION('',(-8.881784197001E-016,1.)); +#152928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152929 = ADVANCED_FACE('',(#152930),#152756,.F.); +#152930 = FACE_BOUND('',#152931,.F.); +#152931 = EDGE_LOOP('',(#152932,#152982,#153004,#153048)); +#152932 = ORIENTED_EDGE('',*,*,#152933,.F.); +#152933 = EDGE_CURVE('',#152934,#152739,#152936,.T.); +#152934 = VERTEX_POINT('',#152935); +#152935 = CARTESIAN_POINT('',(1.15,10.303662633502,0.65)); +#152936 = SURFACE_CURVE('',#152937,(#152942,#152971),.PCURVE_S1.); +#152937 = CIRCLE('',#152938,0.119270391569); +#152938 = AXIS2_PLACEMENT_3D('',#152939,#152940,#152941); +#152939 = CARTESIAN_POINT('',(1.15,10.30032442045,0.530776333563)); +#152940 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152941 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#152942 = PCURVE('',#152756,#152943); +#152943 = DEFINITIONAL_REPRESENTATION('',(#152944),#152970); +#152944 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#152945,#152946,#152947, + #152948,#152949,#152950,#152951,#152952,#152953,#152954,#152955, + #152956,#152957,#152958,#152959,#152960,#152961,#152962,#152963, + #152964,#152965,#152966,#152967,#152968,#152969),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.598788597134, 1.668916054246,1.739043511357,1.809170968469,1.879298425581, 1.949425882692,2.019553339804,2.089680796916,2.159808254027, @@ -185712,94 +188714,94 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.510445539585,2.580572996697,2.650700453808,2.72082791092, 2.790955368032,2.861082825143,2.931210282255,3.001337739367, 3.071465196478,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#150553 = CARTESIAN_POINT('',(1.598788597134,-1.15)); -#150554 = CARTESIAN_POINT('',(1.622164416171,-1.15)); -#150555 = CARTESIAN_POINT('',(1.668916054246,-1.15)); -#150556 = CARTESIAN_POINT('',(1.739043511357,-1.15)); -#150557 = CARTESIAN_POINT('',(1.809170968469,-1.15)); -#150558 = CARTESIAN_POINT('',(1.879298425581,-1.15)); -#150559 = CARTESIAN_POINT('',(1.949425882692,-1.15)); -#150560 = CARTESIAN_POINT('',(2.019553339804,-1.15)); -#150561 = CARTESIAN_POINT('',(2.089680796916,-1.15)); -#150562 = CARTESIAN_POINT('',(2.159808254027,-1.15)); -#150563 = CARTESIAN_POINT('',(2.229935711139,-1.15)); -#150564 = CARTESIAN_POINT('',(2.30006316825,-1.15)); -#150565 = CARTESIAN_POINT('',(2.370190625362,-1.15)); -#150566 = CARTESIAN_POINT('',(2.440318082474,-1.15)); -#150567 = CARTESIAN_POINT('',(2.510445539585,-1.15)); -#150568 = CARTESIAN_POINT('',(2.580572996697,-1.15)); -#150569 = CARTESIAN_POINT('',(2.650700453808,-1.15)); -#150570 = CARTESIAN_POINT('',(2.72082791092,-1.15)); -#150571 = CARTESIAN_POINT('',(2.790955368032,-1.15)); -#150572 = CARTESIAN_POINT('',(2.861082825143,-1.15)); -#150573 = CARTESIAN_POINT('',(2.931210282255,-1.15)); -#150574 = CARTESIAN_POINT('',(3.001337739367,-1.15)); -#150575 = CARTESIAN_POINT('',(3.071465196478,-1.15)); -#150576 = CARTESIAN_POINT('',(3.118216834553,-1.15)); -#150577 = CARTESIAN_POINT('',(3.14159265359,-1.15)); -#150578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150579 = PCURVE('',#88352,#150580); -#150580 = DEFINITIONAL_REPRESENTATION('',(#150581),#150589); -#150581 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#150582,#150583,#150584, - #150585,#150586,#150587,#150588),.UNSPECIFIED.,.T.,.F.) +#152945 = CARTESIAN_POINT('',(1.598788597134,-1.15)); +#152946 = CARTESIAN_POINT('',(1.622164416171,-1.15)); +#152947 = CARTESIAN_POINT('',(1.668916054246,-1.15)); +#152948 = CARTESIAN_POINT('',(1.739043511357,-1.15)); +#152949 = CARTESIAN_POINT('',(1.809170968469,-1.15)); +#152950 = CARTESIAN_POINT('',(1.879298425581,-1.15)); +#152951 = CARTESIAN_POINT('',(1.949425882692,-1.15)); +#152952 = CARTESIAN_POINT('',(2.019553339804,-1.15)); +#152953 = CARTESIAN_POINT('',(2.089680796916,-1.15)); +#152954 = CARTESIAN_POINT('',(2.159808254027,-1.15)); +#152955 = CARTESIAN_POINT('',(2.229935711139,-1.15)); +#152956 = CARTESIAN_POINT('',(2.30006316825,-1.15)); +#152957 = CARTESIAN_POINT('',(2.370190625362,-1.15)); +#152958 = CARTESIAN_POINT('',(2.440318082474,-1.15)); +#152959 = CARTESIAN_POINT('',(2.510445539585,-1.15)); +#152960 = CARTESIAN_POINT('',(2.580572996697,-1.15)); +#152961 = CARTESIAN_POINT('',(2.650700453808,-1.15)); +#152962 = CARTESIAN_POINT('',(2.72082791092,-1.15)); +#152963 = CARTESIAN_POINT('',(2.790955368032,-1.15)); +#152964 = CARTESIAN_POINT('',(2.861082825143,-1.15)); +#152965 = CARTESIAN_POINT('',(2.931210282255,-1.15)); +#152966 = CARTESIAN_POINT('',(3.001337739367,-1.15)); +#152967 = CARTESIAN_POINT('',(3.071465196478,-1.15)); +#152968 = CARTESIAN_POINT('',(3.118216834553,-1.15)); +#152969 = CARTESIAN_POINT('',(3.14159265359,-1.15)); +#152970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152971 = PCURVE('',#90744,#152972); +#152972 = DEFINITIONAL_REPRESENTATION('',(#152973),#152981); +#152973 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152974,#152975,#152976, + #152977,#152978,#152979,#152980),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#150582 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#150583 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); -#150584 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); -#150585 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); -#150586 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); -#150587 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); -#150588 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); -#150589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150590 = ORIENTED_EDGE('',*,*,#150591,.F.); -#150591 = EDGE_CURVE('',#150592,#150542,#150594,.T.); -#150592 = VERTEX_POINT('',#150593); -#150593 = CARTESIAN_POINT('',(1.35,10.303662633502,0.65)); -#150594 = SURFACE_CURVE('',#150595,(#150599,#150605),.PCURVE_S1.); -#150595 = LINE('',#150596,#150597); -#150596 = CARTESIAN_POINT('',(1.35,10.303662633502,0.65)); -#150597 = VECTOR('',#150598,1.); -#150598 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150599 = PCURVE('',#150364,#150600); -#150600 = DEFINITIONAL_REPRESENTATION('',(#150601),#150604); -#150601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#150602,#150603), +#152974 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#152975 = CARTESIAN_POINT('',(-8.735871159939E-002,-0.346793963558)); +#152976 = CARTESIAN_POINT('',(1.593247741878E-002,-0.167888376204)); +#152977 = CARTESIAN_POINT('',(0.119223666437,1.10172111498E-002)); +#152978 = CARTESIAN_POINT('',(0.222514855455,-0.167888376204)); +#152979 = CARTESIAN_POINT('',(0.325806044473,-0.346793963558)); +#152980 = CARTESIAN_POINT('',(0.119223666437,-0.346793963558)); +#152981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152982 = ORIENTED_EDGE('',*,*,#152983,.F.); +#152983 = EDGE_CURVE('',#152984,#152934,#152986,.T.); +#152984 = VERTEX_POINT('',#152985); +#152985 = CARTESIAN_POINT('',(1.35,10.303662633502,0.65)); +#152986 = SURFACE_CURVE('',#152987,(#152991,#152997),.PCURVE_S1.); +#152987 = LINE('',#152988,#152989); +#152988 = CARTESIAN_POINT('',(1.35,10.303662633502,0.65)); +#152989 = VECTOR('',#152990,1.); +#152990 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#152991 = PCURVE('',#152756,#152992); +#152992 = DEFINITIONAL_REPRESENTATION('',(#152993),#152996); +#152993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152994,#152995), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.2),.PIECEWISE_BEZIER_KNOTS.); -#150602 = CARTESIAN_POINT('',(1.598788597134,-1.35)); -#150603 = CARTESIAN_POINT('',(1.598788597134,-1.15)); -#150604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150605 = PCURVE('',#88378,#150606); -#150606 = DEFINITIONAL_REPRESENTATION('',(#150607),#150611); -#150607 = LINE('',#150608,#150609); -#150608 = CARTESIAN_POINT('',(0.224185358936,-2.22044604925E-016)); -#150609 = VECTOR('',#150610,1.); -#150610 = DIRECTION('',(-8.881784197001E-016,-1.)); -#150611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150612 = ORIENTED_EDGE('',*,*,#150613,.T.); -#150613 = EDGE_CURVE('',#150592,#150349,#150614,.T.); -#150614 = SURFACE_CURVE('',#150615,(#150620,#150649),.PCURVE_S1.); -#150615 = CIRCLE('',#150616,0.119270391569); -#150616 = AXIS2_PLACEMENT_3D('',#150617,#150618,#150619); -#150617 = CARTESIAN_POINT('',(1.35,10.30032442045,0.530776333563)); -#150618 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); -#150619 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); -#150620 = PCURVE('',#150364,#150621); -#150621 = DEFINITIONAL_REPRESENTATION('',(#150622),#150648); -#150622 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#150623,#150624,#150625, - #150626,#150627,#150628,#150629,#150630,#150631,#150632,#150633, - #150634,#150635,#150636,#150637,#150638,#150639,#150640,#150641, - #150642,#150643,#150644,#150645,#150646,#150647),.UNSPECIFIED.,.F., +#152994 = CARTESIAN_POINT('',(1.598788597134,-1.35)); +#152995 = CARTESIAN_POINT('',(1.598788597134,-1.15)); +#152996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#152997 = PCURVE('',#90770,#152998); +#152998 = DEFINITIONAL_REPRESENTATION('',(#152999),#153003); +#152999 = LINE('',#153000,#153001); +#153000 = CARTESIAN_POINT('',(0.224185358936,-2.22044604925E-016)); +#153001 = VECTOR('',#153002,1.); +#153002 = DIRECTION('',(-8.881784197001E-016,-1.)); +#153003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153004 = ORIENTED_EDGE('',*,*,#153005,.T.); +#153005 = EDGE_CURVE('',#152984,#152741,#153006,.T.); +#153006 = SURFACE_CURVE('',#153007,(#153012,#153041),.PCURVE_S1.); +#153007 = CIRCLE('',#153008,0.119270391569); +#153008 = AXIS2_PLACEMENT_3D('',#153009,#153010,#153011); +#153009 = CARTESIAN_POINT('',(1.35,10.30032442045,0.530776333563)); +#153010 = DIRECTION('',(-1.,8.881784197001E-016,0.E+000)); +#153011 = DIRECTION('',(-8.881784197001E-016,-1.,0.E+000)); +#153012 = PCURVE('',#152756,#153013); +#153013 = DEFINITIONAL_REPRESENTATION('',(#153014),#153040); +#153014 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#153015,#153016,#153017, + #153018,#153019,#153020,#153021,#153022,#153023,#153024,#153025, + #153026,#153027,#153028,#153029,#153030,#153031,#153032,#153033, + #153034,#153035,#153036,#153037,#153038,#153039),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.598788597134, 1.668916054246,1.739043511357,1.809170968469,1.879298425581, 1.949425882692,2.019553339804,2.089680796916,2.159808254027, @@ -185807,3945 +188809,3945 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.510445539585,2.580572996697,2.650700453808,2.72082791092, 2.790955368032,2.861082825143,2.931210282255,3.001337739367, 3.071465196478,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#150623 = CARTESIAN_POINT('',(1.598788597134,-1.35)); -#150624 = CARTESIAN_POINT('',(1.622164416171,-1.35)); -#150625 = CARTESIAN_POINT('',(1.668916054246,-1.35)); -#150626 = CARTESIAN_POINT('',(1.739043511357,-1.35)); -#150627 = CARTESIAN_POINT('',(1.809170968469,-1.35)); -#150628 = CARTESIAN_POINT('',(1.879298425581,-1.35)); -#150629 = CARTESIAN_POINT('',(1.949425882692,-1.35)); -#150630 = CARTESIAN_POINT('',(2.019553339804,-1.35)); -#150631 = CARTESIAN_POINT('',(2.089680796916,-1.35)); -#150632 = CARTESIAN_POINT('',(2.159808254027,-1.35)); -#150633 = CARTESIAN_POINT('',(2.229935711139,-1.35)); -#150634 = CARTESIAN_POINT('',(2.30006316825,-1.35)); -#150635 = CARTESIAN_POINT('',(2.370190625362,-1.35)); -#150636 = CARTESIAN_POINT('',(2.440318082474,-1.35)); -#150637 = CARTESIAN_POINT('',(2.510445539585,-1.35)); -#150638 = CARTESIAN_POINT('',(2.580572996697,-1.35)); -#150639 = CARTESIAN_POINT('',(2.650700453808,-1.35)); -#150640 = CARTESIAN_POINT('',(2.72082791092,-1.35)); -#150641 = CARTESIAN_POINT('',(2.790955368032,-1.35)); -#150642 = CARTESIAN_POINT('',(2.861082825143,-1.35)); -#150643 = CARTESIAN_POINT('',(2.931210282255,-1.35)); -#150644 = CARTESIAN_POINT('',(3.001337739367,-1.35)); -#150645 = CARTESIAN_POINT('',(3.071465196478,-1.35)); -#150646 = CARTESIAN_POINT('',(3.118216834553,-1.35)); -#150647 = CARTESIAN_POINT('',(3.14159265359,-1.35)); -#150648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150649 = PCURVE('',#88296,#150650); -#150650 = DEFINITIONAL_REPRESENTATION('',(#150651),#150655); -#150651 = CIRCLE('',#150652,0.119270391569); -#150652 = AXIS2_PLACEMENT_2D('',#150653,#150654); -#150653 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); -#150654 = DIRECTION('',(0.E+000,-1.)); -#150655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150656 = ORIENTED_EDGE('',*,*,#150346,.F.); -#150657 = ADVANCED_FACE('',(#150658),#88296,.F.); -#150658 = FACE_BOUND('',#150659,.T.); -#150659 = EDGE_LOOP('',(#150660,#150681,#150682,#150683,#150684,#150685, - #150706,#150707,#150708,#150709,#150710,#150731)); -#150660 = ORIENTED_EDGE('',*,*,#150661,.F.); -#150661 = EDGE_CURVE('',#150592,#88281,#150662,.T.); -#150662 = SURFACE_CURVE('',#150663,(#150667,#150674),.PCURVE_S1.); -#150663 = LINE('',#150664,#150665); -#150664 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); -#150665 = VECTOR('',#150666,1.); -#150666 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#150667 = PCURVE('',#88296,#150668); -#150668 = DEFINITIONAL_REPRESENTATION('',(#150669),#150673); -#150669 = LINE('',#150670,#150671); -#150670 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150671 = VECTOR('',#150672,1.); -#150672 = DIRECTION('',(3.563627120235E-016,-1.)); -#150673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150674 = PCURVE('',#88378,#150675); -#150675 = DEFINITIONAL_REPRESENTATION('',(#150676),#150680); -#150676 = LINE('',#150677,#150678); -#150677 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150678 = VECTOR('',#150679,1.); -#150679 = DIRECTION('',(1.,2.164989446033E-063)); -#150680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150681 = ORIENTED_EDGE('',*,*,#150613,.T.); -#150682 = ORIENTED_EDGE('',*,*,#150397,.T.); -#150683 = ORIENTED_EDGE('',*,*,#150022,.T.); -#150684 = ORIENTED_EDGE('',*,*,#149866,.T.); -#150685 = ORIENTED_EDGE('',*,*,#150686,.T.); -#150686 = EDGE_CURVE('',#149839,#149920,#150687,.T.); -#150687 = SURFACE_CURVE('',#150688,(#150692,#150699),.PCURVE_S1.); -#150688 = LINE('',#150689,#150690); -#150689 = CARTESIAN_POINT('',(1.35,11.,1.159810404338E-002)); -#150690 = VECTOR('',#150691,1.); -#150691 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); -#150692 = PCURVE('',#88296,#150693); -#150693 = DEFINITIONAL_REPRESENTATION('',(#150694),#150698); -#150694 = LINE('',#150695,#150696); -#150695 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); -#150696 = VECTOR('',#150697,1.); -#150697 = DIRECTION('',(1.,2.101748079665E-016)); -#150698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150699 = PCURVE('',#149854,#150700); -#150700 = DEFINITIONAL_REPRESENTATION('',(#150701),#150705); -#150701 = LINE('',#150702,#150703); -#150702 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); -#150703 = VECTOR('',#150704,1.); -#150704 = DIRECTION('',(-1.570395187386E-016,1.)); -#150705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150706 = ORIENTED_EDGE('',*,*,#149917,.F.); -#150707 = ORIENTED_EDGE('',*,*,#150147,.F.); -#150708 = ORIENTED_EDGE('',*,*,#150300,.F.); -#150709 = ORIENTED_EDGE('',*,*,#150421,.F.); -#150710 = ORIENTED_EDGE('',*,*,#150711,.T.); -#150711 = EDGE_CURVE('',#150422,#88279,#150712,.T.); -#150712 = SURFACE_CURVE('',#150713,(#150717,#150724),.PCURVE_S1.); -#150713 = LINE('',#150714,#150715); -#150714 = CARTESIAN_POINT('',(1.35,10.527847992439,0.75)); -#150715 = VECTOR('',#150716,1.); -#150716 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#150717 = PCURVE('',#88296,#150718); -#150718 = DEFINITIONAL_REPRESENTATION('',(#150719),#150723); -#150719 = LINE('',#150720,#150721); -#150720 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#150721 = VECTOR('',#150722,1.); -#150722 = DIRECTION('',(3.563627120235E-016,-1.)); -#150723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150724 = PCURVE('',#88324,#150725); -#150725 = DEFINITIONAL_REPRESENTATION('',(#150726),#150730); -#150726 = LINE('',#150727,#150728); -#150727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150728 = VECTOR('',#150729,1.); -#150729 = DIRECTION('',(-1.,2.164989446033E-063)); -#150730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150731 = ORIENTED_EDGE('',*,*,#88278,.T.); -#150732 = ADVANCED_FACE('',(#150733),#88324,.F.); -#150733 = FACE_BOUND('',#150734,.T.); -#150734 = EDGE_LOOP('',(#150735,#150736,#150757,#150758)); -#150735 = ORIENTED_EDGE('',*,*,#150518,.F.); -#150736 = ORIENTED_EDGE('',*,*,#150737,.T.); -#150737 = EDGE_CURVE('',#150469,#88309,#150738,.T.); -#150738 = SURFACE_CURVE('',#150739,(#150743,#150750),.PCURVE_S1.); -#150739 = LINE('',#150740,#150741); -#150740 = CARTESIAN_POINT('',(1.15,10.527847992439,0.75)); -#150741 = VECTOR('',#150742,1.); -#150742 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#150743 = PCURVE('',#88324,#150744); -#150744 = DEFINITIONAL_REPRESENTATION('',(#150745),#150749); -#150745 = LINE('',#150746,#150747); -#150746 = CARTESIAN_POINT('',(1.7763568394E-015,-0.2)); -#150747 = VECTOR('',#150748,1.); -#150748 = DIRECTION('',(-1.,2.164989446033E-063)); -#150749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150750 = PCURVE('',#88352,#150751); -#150751 = DEFINITIONAL_REPRESENTATION('',(#150752),#150756); -#150752 = LINE('',#150753,#150754); -#150753 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#150754 = VECTOR('',#150755,1.); -#150755 = DIRECTION('',(-3.563627120235E-016,-1.)); -#150756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150757 = ORIENTED_EDGE('',*,*,#88308,.T.); -#150758 = ORIENTED_EDGE('',*,*,#150711,.F.); -#150759 = ADVANCED_FACE('',(#150760),#88352,.F.); -#150760 = FACE_BOUND('',#150761,.T.); -#150761 = EDGE_LOOP('',(#150762,#150763,#150764,#150765,#150766,#150767, - #150788,#150789,#150790,#150791,#150792,#150813)); -#150762 = ORIENTED_EDGE('',*,*,#150737,.F.); -#150763 = ORIENTED_EDGE('',*,*,#150468,.T.); -#150764 = ORIENTED_EDGE('',*,*,#150322,.T.); -#150765 = ORIENTED_EDGE('',*,*,#150224,.T.); -#150766 = ORIENTED_EDGE('',*,*,#149970,.T.); -#150767 = ORIENTED_EDGE('',*,*,#150768,.T.); -#150768 = EDGE_CURVE('',#149948,#149811,#150769,.T.); -#150769 = SURFACE_CURVE('',#150770,(#150774,#150781),.PCURVE_S1.); -#150770 = LINE('',#150771,#150772); -#150771 = CARTESIAN_POINT('',(1.15,11.,1.159810404338E-002)); -#150772 = VECTOR('',#150773,1.); -#150773 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); -#150774 = PCURVE('',#88352,#150775); -#150775 = DEFINITIONAL_REPRESENTATION('',(#150776),#150780); -#150776 = LINE('',#150777,#150778); -#150777 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); -#150778 = VECTOR('',#150779,1.); -#150779 = DIRECTION('',(1.,-2.101748079665E-016)); -#150780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150781 = PCURVE('',#149854,#150782); -#150782 = DEFINITIONAL_REPRESENTATION('',(#150783),#150787); -#150783 = LINE('',#150784,#150785); -#150784 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); -#150785 = VECTOR('',#150786,1.); -#150786 = DIRECTION('',(1.570395187386E-016,-1.)); -#150787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150788 = ORIENTED_EDGE('',*,*,#149808,.F.); -#150789 = ORIENTED_EDGE('',*,*,#150099,.F.); -#150790 = ORIENTED_EDGE('',*,*,#150375,.F.); -#150791 = ORIENTED_EDGE('',*,*,#150541,.F.); -#150792 = ORIENTED_EDGE('',*,*,#150793,.T.); -#150793 = EDGE_CURVE('',#150542,#88337,#150794,.T.); -#150794 = SURFACE_CURVE('',#150795,(#150799,#150806),.PCURVE_S1.); -#150795 = LINE('',#150796,#150797); -#150796 = CARTESIAN_POINT('',(1.15,10.527847992439,0.65)); -#150797 = VECTOR('',#150798,1.); -#150798 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); -#150799 = PCURVE('',#88352,#150800); -#150800 = DEFINITIONAL_REPRESENTATION('',(#150801),#150805); -#150801 = LINE('',#150802,#150803); -#150802 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150803 = VECTOR('',#150804,1.); -#150804 = DIRECTION('',(-3.563627120235E-016,-1.)); -#150805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150806 = PCURVE('',#88378,#150807); -#150807 = DEFINITIONAL_REPRESENTATION('',(#150808),#150812); -#150808 = LINE('',#150809,#150810); -#150809 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.2)); -#150810 = VECTOR('',#150811,1.); -#150811 = DIRECTION('',(1.,2.164989446033E-063)); -#150812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150813 = ORIENTED_EDGE('',*,*,#88336,.T.); -#150814 = ADVANCED_FACE('',(#150815),#88378,.F.); -#150815 = FACE_BOUND('',#150816,.T.); -#150816 = EDGE_LOOP('',(#150817,#150818,#150819,#150820)); -#150817 = ORIENTED_EDGE('',*,*,#150591,.F.); -#150818 = ORIENTED_EDGE('',*,*,#150661,.T.); -#150819 = ORIENTED_EDGE('',*,*,#88364,.T.); -#150820 = ORIENTED_EDGE('',*,*,#150793,.F.); -#150821 = ADVANCED_FACE('',(#150822),#149854,.T.); -#150822 = FACE_BOUND('',#150823,.T.); -#150823 = EDGE_LOOP('',(#150824,#150825,#150826,#150827)); -#150824 = ORIENTED_EDGE('',*,*,#150768,.F.); -#150825 = ORIENTED_EDGE('',*,*,#149947,.F.); -#150826 = ORIENTED_EDGE('',*,*,#150686,.F.); -#150827 = ORIENTED_EDGE('',*,*,#149838,.F.); -#150828 = ADVANCED_FACE('',(#150829),#86554,.F.); -#150829 = FACE_BOUND('',#150830,.T.); -#150830 = EDGE_LOOP('',(#150831,#150857,#150858,#150859)); -#150831 = ORIENTED_EDGE('',*,*,#150832,.F.); -#150832 = EDGE_CURVE('',#94091,#86513,#150833,.T.); -#150833 = SURFACE_CURVE('',#150834,(#150838,#150845),.PCURVE_S1.); -#150834 = LINE('',#150835,#150836); -#150835 = CARTESIAN_POINT('',(10.,9.8,1.2)); -#150836 = VECTOR('',#150837,1.); -#150837 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#150838 = PCURVE('',#86554,#150839); -#150839 = DEFINITIONAL_REPRESENTATION('',(#150840),#150844); -#150840 = LINE('',#150841,#150842); -#150841 = CARTESIAN_POINT('',(0.282842712475,-0.2)); -#150842 = VECTOR('',#150843,1.); -#150843 = DIRECTION('',(-1.,0.E+000)); -#150844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150845 = PCURVE('',#150846,#150851); -#150846 = PLANE('',#150847); -#150847 = AXIS2_PLACEMENT_3D('',#150848,#150849,#150850); -#150848 = CARTESIAN_POINT('',(10.,9.8,1.2)); -#150849 = DIRECTION('',(0.57735026919,0.57735026919,0.57735026919)); -#150850 = DIRECTION('',(0.707106781187,3.016792544941E-017, +#153015 = CARTESIAN_POINT('',(1.598788597134,-1.35)); +#153016 = CARTESIAN_POINT('',(1.622164416171,-1.35)); +#153017 = CARTESIAN_POINT('',(1.668916054246,-1.35)); +#153018 = CARTESIAN_POINT('',(1.739043511357,-1.35)); +#153019 = CARTESIAN_POINT('',(1.809170968469,-1.35)); +#153020 = CARTESIAN_POINT('',(1.879298425581,-1.35)); +#153021 = CARTESIAN_POINT('',(1.949425882692,-1.35)); +#153022 = CARTESIAN_POINT('',(2.019553339804,-1.35)); +#153023 = CARTESIAN_POINT('',(2.089680796916,-1.35)); +#153024 = CARTESIAN_POINT('',(2.159808254027,-1.35)); +#153025 = CARTESIAN_POINT('',(2.229935711139,-1.35)); +#153026 = CARTESIAN_POINT('',(2.30006316825,-1.35)); +#153027 = CARTESIAN_POINT('',(2.370190625362,-1.35)); +#153028 = CARTESIAN_POINT('',(2.440318082474,-1.35)); +#153029 = CARTESIAN_POINT('',(2.510445539585,-1.35)); +#153030 = CARTESIAN_POINT('',(2.580572996697,-1.35)); +#153031 = CARTESIAN_POINT('',(2.650700453808,-1.35)); +#153032 = CARTESIAN_POINT('',(2.72082791092,-1.35)); +#153033 = CARTESIAN_POINT('',(2.790955368032,-1.35)); +#153034 = CARTESIAN_POINT('',(2.861082825143,-1.35)); +#153035 = CARTESIAN_POINT('',(2.931210282255,-1.35)); +#153036 = CARTESIAN_POINT('',(3.001337739367,-1.35)); +#153037 = CARTESIAN_POINT('',(3.071465196478,-1.35)); +#153038 = CARTESIAN_POINT('',(3.118216834553,-1.35)); +#153039 = CARTESIAN_POINT('',(3.14159265359,-1.35)); +#153040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153041 = PCURVE('',#90688,#153042); +#153042 = DEFINITIONAL_REPRESENTATION('',(#153043),#153047); +#153043 = CIRCLE('',#153044,0.119270391569); +#153044 = AXIS2_PLACEMENT_2D('',#153045,#153046); +#153045 = CARTESIAN_POINT('',(-0.119223666437,-0.227523571988)); +#153046 = DIRECTION('',(0.E+000,-1.)); +#153047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153048 = ORIENTED_EDGE('',*,*,#152738,.F.); +#153049 = ADVANCED_FACE('',(#153050),#90688,.F.); +#153050 = FACE_BOUND('',#153051,.T.); +#153051 = EDGE_LOOP('',(#153052,#153073,#153074,#153075,#153076,#153077, + #153098,#153099,#153100,#153101,#153102,#153123)); +#153052 = ORIENTED_EDGE('',*,*,#153053,.F.); +#153053 = EDGE_CURVE('',#152984,#90673,#153054,.T.); +#153054 = SURFACE_CURVE('',#153055,(#153059,#153066),.PCURVE_S1.); +#153055 = LINE('',#153056,#153057); +#153056 = CARTESIAN_POINT('',(1.35,10.527847992439,0.65)); +#153057 = VECTOR('',#153058,1.); +#153058 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#153059 = PCURVE('',#90688,#153060); +#153060 = DEFINITIONAL_REPRESENTATION('',(#153061),#153065); +#153061 = LINE('',#153062,#153063); +#153062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153063 = VECTOR('',#153064,1.); +#153064 = DIRECTION('',(3.563627120235E-016,-1.)); +#153065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153066 = PCURVE('',#90770,#153067); +#153067 = DEFINITIONAL_REPRESENTATION('',(#153068),#153072); +#153068 = LINE('',#153069,#153070); +#153069 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153070 = VECTOR('',#153071,1.); +#153071 = DIRECTION('',(1.,2.164989446033E-063)); +#153072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153073 = ORIENTED_EDGE('',*,*,#153005,.T.); +#153074 = ORIENTED_EDGE('',*,*,#152789,.T.); +#153075 = ORIENTED_EDGE('',*,*,#152414,.T.); +#153076 = ORIENTED_EDGE('',*,*,#152258,.T.); +#153077 = ORIENTED_EDGE('',*,*,#153078,.T.); +#153078 = EDGE_CURVE('',#152231,#152312,#153079,.T.); +#153079 = SURFACE_CURVE('',#153080,(#153084,#153091),.PCURVE_S1.); +#153080 = LINE('',#153081,#153082); +#153081 = CARTESIAN_POINT('',(1.35,11.,1.159810404338E-002)); +#153082 = VECTOR('',#153083,1.); +#153083 = DIRECTION('',(1.570395187386E-016,2.101748079665E-016,1.)); +#153084 = PCURVE('',#90688,#153085); +#153085 = DEFINITIONAL_REPRESENTATION('',(#153086),#153090); +#153086 = LINE('',#153087,#153088); +#153087 = CARTESIAN_POINT('',(-0.638401895957,0.472152007561)); +#153088 = VECTOR('',#153089,1.); +#153089 = DIRECTION('',(1.,2.101748079665E-016)); +#153090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153091 = PCURVE('',#152246,#153092); +#153092 = DEFINITIONAL_REPRESENTATION('',(#153093),#153097); +#153093 = LINE('',#153094,#153095); +#153094 = CARTESIAN_POINT('',(-1.E-001,0.269794846371)); +#153095 = VECTOR('',#153096,1.); +#153096 = DIRECTION('',(-1.570395187386E-016,1.)); +#153097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153098 = ORIENTED_EDGE('',*,*,#152309,.F.); +#153099 = ORIENTED_EDGE('',*,*,#152539,.F.); +#153100 = ORIENTED_EDGE('',*,*,#152692,.F.); +#153101 = ORIENTED_EDGE('',*,*,#152813,.F.); +#153102 = ORIENTED_EDGE('',*,*,#153103,.T.); +#153103 = EDGE_CURVE('',#152814,#90671,#153104,.T.); +#153104 = SURFACE_CURVE('',#153105,(#153109,#153116),.PCURVE_S1.); +#153105 = LINE('',#153106,#153107); +#153106 = CARTESIAN_POINT('',(1.35,10.527847992439,0.75)); +#153107 = VECTOR('',#153108,1.); +#153108 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#153109 = PCURVE('',#90688,#153110); +#153110 = DEFINITIONAL_REPRESENTATION('',(#153111),#153115); +#153111 = LINE('',#153112,#153113); +#153112 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#153113 = VECTOR('',#153114,1.); +#153114 = DIRECTION('',(3.563627120235E-016,-1.)); +#153115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153116 = PCURVE('',#90716,#153117); +#153117 = DEFINITIONAL_REPRESENTATION('',(#153118),#153122); +#153118 = LINE('',#153119,#153120); +#153119 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153120 = VECTOR('',#153121,1.); +#153121 = DIRECTION('',(-1.,2.164989446033E-063)); +#153122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153123 = ORIENTED_EDGE('',*,*,#90670,.T.); +#153124 = ADVANCED_FACE('',(#153125),#90716,.F.); +#153125 = FACE_BOUND('',#153126,.T.); +#153126 = EDGE_LOOP('',(#153127,#153128,#153149,#153150)); +#153127 = ORIENTED_EDGE('',*,*,#152910,.F.); +#153128 = ORIENTED_EDGE('',*,*,#153129,.T.); +#153129 = EDGE_CURVE('',#152861,#90701,#153130,.T.); +#153130 = SURFACE_CURVE('',#153131,(#153135,#153142),.PCURVE_S1.); +#153131 = LINE('',#153132,#153133); +#153132 = CARTESIAN_POINT('',(1.15,10.527847992439,0.75)); +#153133 = VECTOR('',#153134,1.); +#153134 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#153135 = PCURVE('',#90716,#153136); +#153136 = DEFINITIONAL_REPRESENTATION('',(#153137),#153141); +#153137 = LINE('',#153138,#153139); +#153138 = CARTESIAN_POINT('',(1.7763568394E-015,-0.2)); +#153139 = VECTOR('',#153140,1.); +#153140 = DIRECTION('',(-1.,2.164989446033E-063)); +#153141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153142 = PCURVE('',#90744,#153143); +#153143 = DEFINITIONAL_REPRESENTATION('',(#153144),#153148); +#153144 = LINE('',#153145,#153146); +#153145 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#153146 = VECTOR('',#153147,1.); +#153147 = DIRECTION('',(-3.563627120235E-016,-1.)); +#153148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153149 = ORIENTED_EDGE('',*,*,#90700,.T.); +#153150 = ORIENTED_EDGE('',*,*,#153103,.F.); +#153151 = ADVANCED_FACE('',(#153152),#90744,.F.); +#153152 = FACE_BOUND('',#153153,.T.); +#153153 = EDGE_LOOP('',(#153154,#153155,#153156,#153157,#153158,#153159, + #153180,#153181,#153182,#153183,#153184,#153205)); +#153154 = ORIENTED_EDGE('',*,*,#153129,.F.); +#153155 = ORIENTED_EDGE('',*,*,#152860,.T.); +#153156 = ORIENTED_EDGE('',*,*,#152714,.T.); +#153157 = ORIENTED_EDGE('',*,*,#152616,.T.); +#153158 = ORIENTED_EDGE('',*,*,#152362,.T.); +#153159 = ORIENTED_EDGE('',*,*,#153160,.T.); +#153160 = EDGE_CURVE('',#152340,#152203,#153161,.T.); +#153161 = SURFACE_CURVE('',#153162,(#153166,#153173),.PCURVE_S1.); +#153162 = LINE('',#153163,#153164); +#153163 = CARTESIAN_POINT('',(1.15,11.,1.159810404338E-002)); +#153164 = VECTOR('',#153165,1.); +#153165 = DIRECTION('',(-1.570395187386E-016,-2.101748079665E-016,-1.)); +#153166 = PCURVE('',#90744,#153167); +#153167 = DEFINITIONAL_REPRESENTATION('',(#153168),#153172); +#153168 = LINE('',#153169,#153170); +#153169 = CARTESIAN_POINT('',(0.638401895957,0.472152007561)); +#153170 = VECTOR('',#153171,1.); +#153171 = DIRECTION('',(1.,-2.101748079665E-016)); +#153172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153173 = PCURVE('',#152246,#153174); +#153174 = DEFINITIONAL_REPRESENTATION('',(#153175),#153179); +#153175 = LINE('',#153176,#153177); +#153176 = CARTESIAN_POINT('',(1.E-001,0.269794846371)); +#153177 = VECTOR('',#153178,1.); +#153178 = DIRECTION('',(1.570395187386E-016,-1.)); +#153179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153180 = ORIENTED_EDGE('',*,*,#152200,.F.); +#153181 = ORIENTED_EDGE('',*,*,#152491,.F.); +#153182 = ORIENTED_EDGE('',*,*,#152767,.F.); +#153183 = ORIENTED_EDGE('',*,*,#152933,.F.); +#153184 = ORIENTED_EDGE('',*,*,#153185,.T.); +#153185 = EDGE_CURVE('',#152934,#90729,#153186,.T.); +#153186 = SURFACE_CURVE('',#153187,(#153191,#153198),.PCURVE_S1.); +#153187 = LINE('',#153188,#153189); +#153188 = CARTESIAN_POINT('',(1.15,10.527847992439,0.65)); +#153189 = VECTOR('',#153190,1.); +#153190 = DIRECTION('',(0.E+000,-1.,3.563627120235E-016)); +#153191 = PCURVE('',#90744,#153192); +#153192 = DEFINITIONAL_REPRESENTATION('',(#153193),#153197); +#153193 = LINE('',#153194,#153195); +#153194 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153195 = VECTOR('',#153196,1.); +#153196 = DIRECTION('',(-3.563627120235E-016,-1.)); +#153197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153198 = PCURVE('',#90770,#153199); +#153199 = DEFINITIONAL_REPRESENTATION('',(#153200),#153204); +#153200 = LINE('',#153201,#153202); +#153201 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.2)); +#153202 = VECTOR('',#153203,1.); +#153203 = DIRECTION('',(1.,2.164989446033E-063)); +#153204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153205 = ORIENTED_EDGE('',*,*,#90728,.T.); +#153206 = ADVANCED_FACE('',(#153207),#90770,.F.); +#153207 = FACE_BOUND('',#153208,.T.); +#153208 = EDGE_LOOP('',(#153209,#153210,#153211,#153212)); +#153209 = ORIENTED_EDGE('',*,*,#152983,.F.); +#153210 = ORIENTED_EDGE('',*,*,#153053,.T.); +#153211 = ORIENTED_EDGE('',*,*,#90756,.T.); +#153212 = ORIENTED_EDGE('',*,*,#153185,.F.); +#153213 = ADVANCED_FACE('',(#153214),#152246,.T.); +#153214 = FACE_BOUND('',#153215,.T.); +#153215 = EDGE_LOOP('',(#153216,#153217,#153218,#153219)); +#153216 = ORIENTED_EDGE('',*,*,#153160,.F.); +#153217 = ORIENTED_EDGE('',*,*,#152339,.F.); +#153218 = ORIENTED_EDGE('',*,*,#153078,.F.); +#153219 = ORIENTED_EDGE('',*,*,#152230,.F.); +#153220 = ADVANCED_FACE('',(#153221),#88946,.F.); +#153221 = FACE_BOUND('',#153222,.T.); +#153222 = EDGE_LOOP('',(#153223,#153249,#153250,#153251)); +#153223 = ORIENTED_EDGE('',*,*,#153224,.F.); +#153224 = EDGE_CURVE('',#96483,#88905,#153225,.T.); +#153225 = SURFACE_CURVE('',#153226,(#153230,#153237),.PCURVE_S1.); +#153226 = LINE('',#153227,#153228); +#153227 = CARTESIAN_POINT('',(10.,9.8,1.2)); +#153228 = VECTOR('',#153229,1.); +#153229 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#153230 = PCURVE('',#88946,#153231); +#153231 = DEFINITIONAL_REPRESENTATION('',(#153232),#153236); +#153232 = LINE('',#153233,#153234); +#153233 = CARTESIAN_POINT('',(0.282842712475,-0.2)); +#153234 = VECTOR('',#153235,1.); +#153235 = DIRECTION('',(-1.,0.E+000)); +#153236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153237 = PCURVE('',#153238,#153243); +#153238 = PLANE('',#153239); +#153239 = AXIS2_PLACEMENT_3D('',#153240,#153241,#153242); +#153240 = CARTESIAN_POINT('',(10.,9.8,1.2)); +#153241 = DIRECTION('',(0.57735026919,0.57735026919,0.57735026919)); +#153242 = DIRECTION('',(0.707106781187,3.016792544941E-017, -0.707106781187)); -#150851 = DEFINITIONAL_REPRESENTATION('',(#150852),#150856); -#150852 = LINE('',#150853,#150854); -#150853 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150854 = VECTOR('',#150855,1.); -#150855 = DIRECTION('',(-0.5,0.866025403784)); -#150856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150857 = ORIENTED_EDGE('',*,*,#94166,.F.); -#150858 = ORIENTED_EDGE('',*,*,#94358,.F.); -#150859 = ORIENTED_EDGE('',*,*,#86540,.F.); -#150860 = ADVANCED_FACE('',(#150861),#150846,.T.); -#150861 = FACE_BOUND('',#150862,.T.); -#150862 = EDGE_LOOP('',(#150863,#150884,#150885)); -#150863 = ORIENTED_EDGE('',*,*,#150864,.F.); -#150864 = EDGE_CURVE('',#94091,#94267,#150865,.T.); -#150865 = SURFACE_CURVE('',#150866,(#150870,#150877),.PCURVE_S1.); -#150866 = LINE('',#150867,#150868); -#150867 = CARTESIAN_POINT('',(10.,9.8,1.2)); -#150868 = VECTOR('',#150869,1.); -#150869 = DIRECTION('',(-0.707106781187,-9.614813431918E-017, +#153243 = DEFINITIONAL_REPRESENTATION('',(#153244),#153248); +#153244 = LINE('',#153245,#153246); +#153245 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153246 = VECTOR('',#153247,1.); +#153247 = DIRECTION('',(-0.5,0.866025403784)); +#153248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153249 = ORIENTED_EDGE('',*,*,#96558,.F.); +#153250 = ORIENTED_EDGE('',*,*,#96750,.F.); +#153251 = ORIENTED_EDGE('',*,*,#88932,.F.); +#153252 = ADVANCED_FACE('',(#153253),#153238,.T.); +#153253 = FACE_BOUND('',#153254,.T.); +#153254 = EDGE_LOOP('',(#153255,#153276,#153277)); +#153255 = ORIENTED_EDGE('',*,*,#153256,.F.); +#153256 = EDGE_CURVE('',#96483,#96659,#153257,.T.); +#153257 = SURFACE_CURVE('',#153258,(#153262,#153269),.PCURVE_S1.); +#153258 = LINE('',#153259,#153260); +#153259 = CARTESIAN_POINT('',(10.,9.8,1.2)); +#153260 = VECTOR('',#153261,1.); +#153261 = DIRECTION('',(-0.707106781187,-9.614813431918E-017, 0.707106781187)); -#150870 = PCURVE('',#150846,#150871); -#150871 = DEFINITIONAL_REPRESENTATION('',(#150872),#150876); -#150872 = LINE('',#150873,#150874); -#150873 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150874 = VECTOR('',#150875,1.); -#150875 = DIRECTION('',(-1.,1.767249541151E-017)); -#150876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150877 = PCURVE('',#94108,#150878); -#150878 = DEFINITIONAL_REPRESENTATION('',(#150879),#150883); -#150879 = LINE('',#150880,#150881); -#150880 = CARTESIAN_POINT('',(-0.282842712475,-0.2)); -#150881 = VECTOR('',#150882,1.); -#150882 = DIRECTION('',(1.,-9.614813431918E-017)); -#150883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150884 = ORIENTED_EDGE('',*,*,#150832,.T.); -#150885 = ORIENTED_EDGE('',*,*,#150886,.F.); -#150886 = EDGE_CURVE('',#94267,#86513,#150887,.T.); -#150887 = SURFACE_CURVE('',#150888,(#150892,#150899),.PCURVE_S1.); -#150888 = LINE('',#150889,#150890); -#150889 = CARTESIAN_POINT('',(9.8,9.9,1.3)); -#150890 = VECTOR('',#150891,1.); -#150891 = DIRECTION('',(9.614813431918E-017,0.707106781187, +#153262 = PCURVE('',#153238,#153263); +#153263 = DEFINITIONAL_REPRESENTATION('',(#153264),#153268); +#153264 = LINE('',#153265,#153266); +#153265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153266 = VECTOR('',#153267,1.); +#153267 = DIRECTION('',(-1.,1.767249541151E-017)); +#153268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153269 = PCURVE('',#96500,#153270); +#153270 = DEFINITIONAL_REPRESENTATION('',(#153271),#153275); +#153271 = LINE('',#153272,#153273); +#153272 = CARTESIAN_POINT('',(-0.282842712475,-0.2)); +#153273 = VECTOR('',#153274,1.); +#153274 = DIRECTION('',(1.,-9.614813431918E-017)); +#153275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153276 = ORIENTED_EDGE('',*,*,#153224,.T.); +#153277 = ORIENTED_EDGE('',*,*,#153278,.F.); +#153278 = EDGE_CURVE('',#96659,#88905,#153279,.T.); +#153279 = SURFACE_CURVE('',#153280,(#153284,#153291),.PCURVE_S1.); +#153280 = LINE('',#153281,#153282); +#153281 = CARTESIAN_POINT('',(9.8,9.9,1.3)); +#153282 = VECTOR('',#153283,1.); +#153283 = DIRECTION('',(9.614813431918E-017,0.707106781187, -0.707106781187)); -#150892 = PCURVE('',#150846,#150893); -#150893 = DEFINITIONAL_REPRESENTATION('',(#150894),#150898); -#150894 = LINE('',#150895,#150896); -#150895 = CARTESIAN_POINT('',(-0.212132034356,0.122474487139)); -#150896 = VECTOR('',#150897,1.); -#150897 = DIRECTION('',(0.5,0.866025403784)); -#150898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150899 = PCURVE('',#86528,#150900); -#150900 = DEFINITIONAL_REPRESENTATION('',(#150901),#150905); -#150901 = LINE('',#150902,#150903); -#150902 = CARTESIAN_POINT('',(0.141421356237,9.8)); -#150903 = VECTOR('',#150904,1.); -#150904 = DIRECTION('',(1.,9.614813431918E-017)); -#150905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150906 = ADVANCED_FACE('',(#150907),#86500,.F.); -#150907 = FACE_BOUND('',#150908,.T.); -#150908 = EDGE_LOOP('',(#150909,#150910,#150911,#150937)); -#150909 = ORIENTED_EDGE('',*,*,#94336,.F.); -#150910 = ORIENTED_EDGE('',*,*,#92237,.F.); -#150911 = ORIENTED_EDGE('',*,*,#150912,.F.); -#150912 = EDGE_CURVE('',#86485,#92210,#150913,.T.); -#150913 = SURFACE_CURVE('',#150914,(#150918,#150925),.PCURVE_S1.); -#150914 = LINE('',#150915,#150916); -#150915 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); -#150916 = VECTOR('',#150917,1.); -#150917 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#150918 = PCURVE('',#86500,#150919); -#150919 = DEFINITIONAL_REPRESENTATION('',(#150920),#150924); -#150920 = LINE('',#150921,#150922); -#150921 = CARTESIAN_POINT('',(0.E+000,-0.2)); -#150922 = VECTOR('',#150923,1.); -#150923 = DIRECTION('',(-1.,0.E+000)); -#150924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150925 = PCURVE('',#150926,#150931); -#150926 = PLANE('',#150927); -#150927 = AXIS2_PLACEMENT_3D('',#150928,#150929,#150930); -#150928 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); -#150929 = DIRECTION('',(-0.57735026919,0.57735026919,0.57735026919)); -#150930 = DIRECTION('',(0.707106781187,3.256672275603E-017, +#153284 = PCURVE('',#153238,#153285); +#153285 = DEFINITIONAL_REPRESENTATION('',(#153286),#153290); +#153286 = LINE('',#153287,#153288); +#153287 = CARTESIAN_POINT('',(-0.212132034356,0.122474487139)); +#153288 = VECTOR('',#153289,1.); +#153289 = DIRECTION('',(0.5,0.866025403784)); +#153290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153291 = PCURVE('',#88920,#153292); +#153292 = DEFINITIONAL_REPRESENTATION('',(#153293),#153297); +#153293 = LINE('',#153294,#153295); +#153294 = CARTESIAN_POINT('',(0.141421356237,9.8)); +#153295 = VECTOR('',#153296,1.); +#153296 = DIRECTION('',(1.,9.614813431918E-017)); +#153297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153298 = ADVANCED_FACE('',(#153299),#88892,.F.); +#153299 = FACE_BOUND('',#153300,.T.); +#153300 = EDGE_LOOP('',(#153301,#153302,#153303,#153329)); +#153301 = ORIENTED_EDGE('',*,*,#96728,.F.); +#153302 = ORIENTED_EDGE('',*,*,#94629,.F.); +#153303 = ORIENTED_EDGE('',*,*,#153304,.F.); +#153304 = EDGE_CURVE('',#88877,#94602,#153305,.T.); +#153305 = SURFACE_CURVE('',#153306,(#153310,#153317),.PCURVE_S1.); +#153306 = LINE('',#153307,#153308); +#153307 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); +#153308 = VECTOR('',#153309,1.); +#153309 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#153310 = PCURVE('',#88892,#153311); +#153311 = DEFINITIONAL_REPRESENTATION('',(#153312),#153316); +#153312 = LINE('',#153313,#153314); +#153313 = CARTESIAN_POINT('',(0.E+000,-0.2)); +#153314 = VECTOR('',#153315,1.); +#153315 = DIRECTION('',(-1.,0.E+000)); +#153316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153317 = PCURVE('',#153318,#153323); +#153318 = PLANE('',#153319); +#153319 = AXIS2_PLACEMENT_3D('',#153320,#153321,#153322); +#153320 = CARTESIAN_POINT('',(0.E+000,9.8,1.2)); +#153321 = DIRECTION('',(-0.57735026919,0.57735026919,0.57735026919)); +#153322 = DIRECTION('',(0.707106781187,3.256672275603E-017, 0.707106781187)); -#150931 = DEFINITIONAL_REPRESENTATION('',(#150932),#150936); -#150932 = LINE('',#150933,#150934); -#150933 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150934 = VECTOR('',#150935,1.); -#150935 = DIRECTION('',(-0.5,-0.866025403784)); -#150936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150937 = ORIENTED_EDGE('',*,*,#86484,.F.); -#150938 = ADVANCED_FACE('',(#150939),#86528,.F.); -#150939 = FACE_BOUND('',#150940,.T.); -#150940 = EDGE_LOOP('',(#150941,#150942,#150943,#150964)); -#150941 = ORIENTED_EDGE('',*,*,#150886,.T.); -#150942 = ORIENTED_EDGE('',*,*,#86512,.F.); -#150943 = ORIENTED_EDGE('',*,*,#150944,.F.); -#150944 = EDGE_CURVE('',#94219,#86485,#150945,.T.); -#150945 = SURFACE_CURVE('',#150946,(#150950,#150957),.PCURVE_S1.); -#150946 = LINE('',#150947,#150948); -#150947 = CARTESIAN_POINT('',(0.2,9.9,1.3)); -#150948 = VECTOR('',#150949,1.); -#150949 = DIRECTION('',(-1.60676270781E-015,0.707106781187, +#153323 = DEFINITIONAL_REPRESENTATION('',(#153324),#153328); +#153324 = LINE('',#153325,#153326); +#153325 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153326 = VECTOR('',#153327,1.); +#153327 = DIRECTION('',(-0.5,-0.866025403784)); +#153328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153329 = ORIENTED_EDGE('',*,*,#88876,.F.); +#153330 = ADVANCED_FACE('',(#153331),#88920,.F.); +#153331 = FACE_BOUND('',#153332,.T.); +#153332 = EDGE_LOOP('',(#153333,#153334,#153335,#153356)); +#153333 = ORIENTED_EDGE('',*,*,#153278,.T.); +#153334 = ORIENTED_EDGE('',*,*,#88904,.F.); +#153335 = ORIENTED_EDGE('',*,*,#153336,.F.); +#153336 = EDGE_CURVE('',#96611,#88877,#153337,.T.); +#153337 = SURFACE_CURVE('',#153338,(#153342,#153349),.PCURVE_S1.); +#153338 = LINE('',#153339,#153340); +#153339 = CARTESIAN_POINT('',(0.2,9.9,1.3)); +#153340 = VECTOR('',#153341,1.); +#153341 = DIRECTION('',(-1.60676270781E-015,0.707106781187, -0.707106781187)); -#150950 = PCURVE('',#86528,#150951); -#150951 = DEFINITIONAL_REPRESENTATION('',(#150952),#150956); -#150952 = LINE('',#150953,#150954); -#150953 = CARTESIAN_POINT('',(0.141421356237,0.2)); -#150954 = VECTOR('',#150955,1.); -#150955 = DIRECTION('',(1.,-1.60676270781E-015)); -#150956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150957 = PCURVE('',#150926,#150958); -#150958 = DEFINITIONAL_REPRESENTATION('',(#150959),#150963); -#150959 = LINE('',#150960,#150961); -#150960 = CARTESIAN_POINT('',(0.212132034356,0.122474487139)); -#150961 = VECTOR('',#150962,1.); -#150962 = DIRECTION('',(-0.5,0.866025403784)); -#150963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150964 = ORIENTED_EDGE('',*,*,#94289,.F.); -#150965 = ADVANCED_FACE('',(#150966),#94108,.F.); -#150966 = FACE_BOUND('',#150967,.T.); -#150967 = EDGE_LOOP('',(#150968,#150969,#150970,#150996)); -#150968 = ORIENTED_EDGE('',*,*,#150864,.T.); -#150969 = ORIENTED_EDGE('',*,*,#94266,.F.); -#150970 = ORIENTED_EDGE('',*,*,#150971,.F.); -#150971 = EDGE_CURVE('',#94093,#94244,#150972,.T.); -#150972 = SURFACE_CURVE('',#150973,(#150977,#150984),.PCURVE_S1.); -#150973 = LINE('',#150974,#150975); -#150974 = CARTESIAN_POINT('',(9.8,0.2,1.4)); -#150975 = VECTOR('',#150976,1.); -#150976 = DIRECTION('',(-0.707106781187,1.60676270781E-015, +#153342 = PCURVE('',#88920,#153343); +#153343 = DEFINITIONAL_REPRESENTATION('',(#153344),#153348); +#153344 = LINE('',#153345,#153346); +#153345 = CARTESIAN_POINT('',(0.141421356237,0.2)); +#153346 = VECTOR('',#153347,1.); +#153347 = DIRECTION('',(1.,-1.60676270781E-015)); +#153348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153349 = PCURVE('',#153318,#153350); +#153350 = DEFINITIONAL_REPRESENTATION('',(#153351),#153355); +#153351 = LINE('',#153352,#153353); +#153352 = CARTESIAN_POINT('',(0.212132034356,0.122474487139)); +#153353 = VECTOR('',#153354,1.); +#153354 = DIRECTION('',(-0.5,0.866025403784)); +#153355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153356 = ORIENTED_EDGE('',*,*,#96681,.F.); +#153357 = ADVANCED_FACE('',(#153358),#96500,.F.); +#153358 = FACE_BOUND('',#153359,.T.); +#153359 = EDGE_LOOP('',(#153360,#153361,#153362,#153388)); +#153360 = ORIENTED_EDGE('',*,*,#153256,.T.); +#153361 = ORIENTED_EDGE('',*,*,#96658,.F.); +#153362 = ORIENTED_EDGE('',*,*,#153363,.F.); +#153363 = EDGE_CURVE('',#96485,#96636,#153364,.T.); +#153364 = SURFACE_CURVE('',#153365,(#153369,#153376),.PCURVE_S1.); +#153365 = LINE('',#153366,#153367); +#153366 = CARTESIAN_POINT('',(9.8,0.2,1.4)); +#153367 = VECTOR('',#153368,1.); +#153368 = DIRECTION('',(-0.707106781187,1.60676270781E-015, 0.707106781187)); -#150977 = PCURVE('',#94108,#150978); -#150978 = DEFINITIONAL_REPRESENTATION('',(#150979),#150983); -#150979 = LINE('',#150980,#150981); -#150980 = CARTESIAN_POINT('',(0.E+000,-9.8)); -#150981 = VECTOR('',#150982,1.); -#150982 = DIRECTION('',(1.,1.60676270781E-015)); -#150983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150984 = PCURVE('',#150985,#150990); -#150985 = PLANE('',#150986); -#150986 = AXIS2_PLACEMENT_3D('',#150987,#150988,#150989); -#150987 = CARTESIAN_POINT('',(9.8,0.2,1.4)); -#150988 = DIRECTION('',(0.57735026919,-0.57735026919,0.57735026919)); -#150989 = DIRECTION('',(-3.256672275603E-017,-0.707106781187, +#153369 = PCURVE('',#96500,#153370); +#153370 = DEFINITIONAL_REPRESENTATION('',(#153371),#153375); +#153371 = LINE('',#153372,#153373); +#153372 = CARTESIAN_POINT('',(0.E+000,-9.8)); +#153373 = VECTOR('',#153374,1.); +#153374 = DIRECTION('',(1.,1.60676270781E-015)); +#153375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153376 = PCURVE('',#153377,#153382); +#153377 = PLANE('',#153378); +#153378 = AXIS2_PLACEMENT_3D('',#153379,#153380,#153381); +#153379 = CARTESIAN_POINT('',(9.8,0.2,1.4)); +#153380 = DIRECTION('',(0.57735026919,-0.57735026919,0.57735026919)); +#153381 = DIRECTION('',(-3.256672275603E-017,-0.707106781187, -0.707106781187)); -#150990 = DEFINITIONAL_REPRESENTATION('',(#150991),#150995); -#150991 = LINE('',#150992,#150993); -#150992 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#150993 = VECTOR('',#150994,1.); -#150994 = DIRECTION('',(-0.5,-0.866025403784)); -#150995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#150996 = ORIENTED_EDGE('',*,*,#94090,.F.); -#150997 = ADVANCED_FACE('',(#150998),#89405,.F.); -#150998 = FACE_BOUND('',#150999,.T.); -#150999 = EDGE_LOOP('',(#151000,#151001,#151002,#151023)); -#151000 = ORIENTED_EDGE('',*,*,#94380,.F.); -#151001 = ORIENTED_EDGE('',*,*,#94120,.F.); -#151002 = ORIENTED_EDGE('',*,*,#151003,.F.); -#151003 = EDGE_CURVE('',#89311,#94093,#151004,.T.); -#151004 = SURFACE_CURVE('',#151005,(#151009,#151016),.PCURVE_S1.); -#151005 = LINE('',#151006,#151007); -#151006 = CARTESIAN_POINT('',(9.9,0.1,1.2)); -#151007 = VECTOR('',#151008,1.); -#151008 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#151009 = PCURVE('',#89405,#151010); -#151010 = DEFINITIONAL_REPRESENTATION('',(#151011),#151015); -#151011 = LINE('',#151012,#151013); -#151012 = CARTESIAN_POINT('',(0.141421356237,-0.2)); -#151013 = VECTOR('',#151014,1.); -#151014 = DIRECTION('',(-1.,0.E+000)); -#151015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151016 = PCURVE('',#150985,#151017); -#151017 = DEFINITIONAL_REPRESENTATION('',(#151018),#151022); -#151018 = LINE('',#151019,#151020); -#151019 = CARTESIAN_POINT('',(0.212132034356,0.122474487139)); -#151020 = VECTOR('',#151021,1.); -#151021 = DIRECTION('',(-0.5,0.866025403784)); -#151022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151023 = ORIENTED_EDGE('',*,*,#89391,.F.); -#151024 = ADVANCED_FACE('',(#151025),#150926,.T.); -#151025 = FACE_BOUND('',#151026,.T.); -#151026 = EDGE_LOOP('',(#151027,#151028,#151029)); -#151027 = ORIENTED_EDGE('',*,*,#150944,.T.); -#151028 = ORIENTED_EDGE('',*,*,#150912,.T.); -#151029 = ORIENTED_EDGE('',*,*,#151030,.F.); -#151030 = EDGE_CURVE('',#94219,#92210,#151031,.T.); -#151031 = SURFACE_CURVE('',#151032,(#151036,#151043),.PCURVE_S1.); -#151032 = LINE('',#151033,#151034); -#151033 = CARTESIAN_POINT('',(-1.916616770854E-017,9.8,1.2)); -#151034 = VECTOR('',#151035,1.); -#151035 = DIRECTION('',(-0.707106781187,9.614813431918E-017, +#153382 = DEFINITIONAL_REPRESENTATION('',(#153383),#153387); +#153383 = LINE('',#153384,#153385); +#153384 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153385 = VECTOR('',#153386,1.); +#153386 = DIRECTION('',(-0.5,-0.866025403784)); +#153387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153388 = ORIENTED_EDGE('',*,*,#96482,.F.); +#153389 = ADVANCED_FACE('',(#153390),#91797,.F.); +#153390 = FACE_BOUND('',#153391,.T.); +#153391 = EDGE_LOOP('',(#153392,#153393,#153394,#153415)); +#153392 = ORIENTED_EDGE('',*,*,#96772,.F.); +#153393 = ORIENTED_EDGE('',*,*,#96512,.F.); +#153394 = ORIENTED_EDGE('',*,*,#153395,.F.); +#153395 = EDGE_CURVE('',#91703,#96485,#153396,.T.); +#153396 = SURFACE_CURVE('',#153397,(#153401,#153408),.PCURVE_S1.); +#153397 = LINE('',#153398,#153399); +#153398 = CARTESIAN_POINT('',(9.9,0.1,1.2)); +#153399 = VECTOR('',#153400,1.); +#153400 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#153401 = PCURVE('',#91797,#153402); +#153402 = DEFINITIONAL_REPRESENTATION('',(#153403),#153407); +#153403 = LINE('',#153404,#153405); +#153404 = CARTESIAN_POINT('',(0.141421356237,-0.2)); +#153405 = VECTOR('',#153406,1.); +#153406 = DIRECTION('',(-1.,0.E+000)); +#153407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153408 = PCURVE('',#153377,#153409); +#153409 = DEFINITIONAL_REPRESENTATION('',(#153410),#153414); +#153410 = LINE('',#153411,#153412); +#153411 = CARTESIAN_POINT('',(0.212132034356,0.122474487139)); +#153412 = VECTOR('',#153413,1.); +#153413 = DIRECTION('',(-0.5,0.866025403784)); +#153414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153415 = ORIENTED_EDGE('',*,*,#91783,.F.); +#153416 = ADVANCED_FACE('',(#153417),#153318,.T.); +#153417 = FACE_BOUND('',#153418,.T.); +#153418 = EDGE_LOOP('',(#153419,#153420,#153421)); +#153419 = ORIENTED_EDGE('',*,*,#153336,.T.); +#153420 = ORIENTED_EDGE('',*,*,#153304,.T.); +#153421 = ORIENTED_EDGE('',*,*,#153422,.F.); +#153422 = EDGE_CURVE('',#96611,#94602,#153423,.T.); +#153423 = SURFACE_CURVE('',#153424,(#153428,#153435),.PCURVE_S1.); +#153424 = LINE('',#153425,#153426); +#153425 = CARTESIAN_POINT('',(-1.916616770854E-017,9.8,1.2)); +#153426 = VECTOR('',#153427,1.); +#153427 = DIRECTION('',(-0.707106781187,9.614813431918E-017, -0.707106781187)); -#151036 = PCURVE('',#150926,#151037); -#151037 = DEFINITIONAL_REPRESENTATION('',(#151038),#151042); -#151038 = LINE('',#151039,#151040); -#151039 = CARTESIAN_POINT('',(-9.035018104046E-018,-5.216370134504E-018) - ); -#151040 = VECTOR('',#151041,1.); -#151041 = DIRECTION('',(-1.,1.000718605204E-016)); -#151042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151043 = PCURVE('',#92225,#151044); -#151044 = DEFINITIONAL_REPRESENTATION('',(#151045),#151049); -#151045 = LINE('',#151046,#151047); -#151046 = CARTESIAN_POINT('',(0.282842712475,-0.2)); -#151047 = VECTOR('',#151048,1.); -#151048 = DIRECTION('',(1.,9.614813431918E-017)); -#151049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151050 = ADVANCED_FACE('',(#151051),#150985,.T.); -#151051 = FACE_BOUND('',#151052,.T.); -#151052 = EDGE_LOOP('',(#151053,#151054,#151055)); -#151053 = ORIENTED_EDGE('',*,*,#151003,.T.); -#151054 = ORIENTED_EDGE('',*,*,#150971,.T.); -#151055 = ORIENTED_EDGE('',*,*,#151056,.F.); -#151056 = EDGE_CURVE('',#89311,#94244,#151057,.T.); -#151057 = SURFACE_CURVE('',#151058,(#151062,#151069),.PCURVE_S1.); -#151058 = LINE('',#151059,#151060); -#151059 = CARTESIAN_POINT('',(9.8,0.2,1.4)); -#151060 = VECTOR('',#151061,1.); -#151061 = DIRECTION('',(-9.614813431918E-017,0.707106781187, +#153428 = PCURVE('',#153318,#153429); +#153429 = DEFINITIONAL_REPRESENTATION('',(#153430),#153434); +#153430 = LINE('',#153431,#153432); +#153431 = CARTESIAN_POINT('',(-9.035018104046E-018,-5.216370134504E-018) + ); +#153432 = VECTOR('',#153433,1.); +#153433 = DIRECTION('',(-1.,1.000718605204E-016)); +#153434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153435 = PCURVE('',#94617,#153436); +#153436 = DEFINITIONAL_REPRESENTATION('',(#153437),#153441); +#153437 = LINE('',#153438,#153439); +#153438 = CARTESIAN_POINT('',(0.282842712475,-0.2)); +#153439 = VECTOR('',#153440,1.); +#153440 = DIRECTION('',(1.,9.614813431918E-017)); +#153441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153442 = ADVANCED_FACE('',(#153443),#153377,.T.); +#153443 = FACE_BOUND('',#153444,.T.); +#153444 = EDGE_LOOP('',(#153445,#153446,#153447)); +#153445 = ORIENTED_EDGE('',*,*,#153395,.T.); +#153446 = ORIENTED_EDGE('',*,*,#153363,.T.); +#153447 = ORIENTED_EDGE('',*,*,#153448,.F.); +#153448 = EDGE_CURVE('',#91703,#96636,#153449,.T.); +#153449 = SURFACE_CURVE('',#153450,(#153454,#153461),.PCURVE_S1.); +#153450 = LINE('',#153451,#153452); +#153451 = CARTESIAN_POINT('',(9.8,0.2,1.4)); +#153452 = VECTOR('',#153453,1.); +#153453 = DIRECTION('',(-9.614813431918E-017,0.707106781187, 0.707106781187)); -#151062 = PCURVE('',#150985,#151063); -#151063 = DEFINITIONAL_REPRESENTATION('',(#151064),#151068); -#151064 = LINE('',#151065,#151066); -#151065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151066 = VECTOR('',#151067,1.); -#151067 = DIRECTION('',(-1.,-1.000650183217E-016)); -#151068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153454 = PCURVE('',#153377,#153455); +#153455 = DEFINITIONAL_REPRESENTATION('',(#153456),#153460); +#153456 = LINE('',#153457,#153458); +#153457 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153458 = VECTOR('',#153459,1.); +#153459 = DIRECTION('',(-1.,-1.000650183217E-016)); +#153460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151069 = PCURVE('',#89328,#151070); -#151070 = DEFINITIONAL_REPRESENTATION('',(#151071),#151075); -#151071 = LINE('',#151072,#151073); -#151072 = CARTESIAN_POINT('',(0.E+000,9.8)); -#151073 = VECTOR('',#151074,1.); -#151074 = DIRECTION('',(1.,-9.614813431918E-017)); -#151075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153461 = PCURVE('',#91720,#153462); +#153462 = DEFINITIONAL_REPRESENTATION('',(#153463),#153467); +#153463 = LINE('',#153464,#153465); +#153464 = CARTESIAN_POINT('',(0.E+000,9.8)); +#153465 = VECTOR('',#153466,1.); +#153466 = DIRECTION('',(1.,-9.614813431918E-017)); +#153467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151076 = ADVANCED_FACE('',(#151077),#92225,.F.); -#151077 = FACE_BOUND('',#151078,.T.); -#151078 = EDGE_LOOP('',(#151079,#151080,#151081,#151107)); -#151079 = ORIENTED_EDGE('',*,*,#151030,.T.); -#151080 = ORIENTED_EDGE('',*,*,#92209,.F.); -#151081 = ORIENTED_EDGE('',*,*,#151082,.F.); -#151082 = EDGE_CURVE('',#94221,#92187,#151083,.T.); -#151083 = SURFACE_CURVE('',#151084,(#151088,#151095),.PCURVE_S1.); -#151084 = LINE('',#151085,#151086); -#151085 = CARTESIAN_POINT('',(-1.916616770854E-017,0.2,1.2)); -#151086 = VECTOR('',#151087,1.); -#151087 = DIRECTION('',(-0.707106781187,-1.60676270781E-015, +#153468 = ADVANCED_FACE('',(#153469),#94617,.F.); +#153469 = FACE_BOUND('',#153470,.T.); +#153470 = EDGE_LOOP('',(#153471,#153472,#153473,#153499)); +#153471 = ORIENTED_EDGE('',*,*,#153422,.T.); +#153472 = ORIENTED_EDGE('',*,*,#94601,.F.); +#153473 = ORIENTED_EDGE('',*,*,#153474,.F.); +#153474 = EDGE_CURVE('',#96613,#94579,#153475,.T.); +#153475 = SURFACE_CURVE('',#153476,(#153480,#153487),.PCURVE_S1.); +#153476 = LINE('',#153477,#153478); +#153477 = CARTESIAN_POINT('',(-1.916616770854E-017,0.2,1.2)); +#153478 = VECTOR('',#153479,1.); +#153479 = DIRECTION('',(-0.707106781187,-1.60676270781E-015, -0.707106781187)); -#151088 = PCURVE('',#92225,#151089); -#151089 = DEFINITIONAL_REPRESENTATION('',(#151090),#151094); -#151090 = LINE('',#151091,#151092); -#151091 = CARTESIAN_POINT('',(0.282842712475,-9.8)); -#151092 = VECTOR('',#151093,1.); -#151093 = DIRECTION('',(1.,-1.60676270781E-015)); -#151094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151095 = PCURVE('',#151096,#151101); -#151096 = PLANE('',#151097); -#151097 = AXIS2_PLACEMENT_3D('',#151098,#151099,#151100); -#151098 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); -#151099 = DIRECTION('',(-0.57735026919,-0.57735026919,0.57735026919)); -#151100 = DIRECTION('',(3.256672275603E-017,-0.707106781187, +#153480 = PCURVE('',#94617,#153481); +#153481 = DEFINITIONAL_REPRESENTATION('',(#153482),#153486); +#153482 = LINE('',#153483,#153484); +#153483 = CARTESIAN_POINT('',(0.282842712475,-9.8)); +#153484 = VECTOR('',#153485,1.); +#153485 = DIRECTION('',(1.,-1.60676270781E-015)); +#153486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153487 = PCURVE('',#153488,#153493); +#153488 = PLANE('',#153489); +#153489 = AXIS2_PLACEMENT_3D('',#153490,#153491,#153492); +#153490 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); +#153491 = DIRECTION('',(-0.57735026919,-0.57735026919,0.57735026919)); +#153492 = DIRECTION('',(3.256672275603E-017,-0.707106781187, -0.707106781187)); -#151101 = DEFINITIONAL_REPRESENTATION('',(#151102),#151106); -#151102 = LINE('',#151103,#151104); -#151103 = CARTESIAN_POINT('',(-1.962615573355E-017,-2.931801742888E-017) - ); -#151104 = VECTOR('',#151105,1.); -#151105 = DIRECTION('',(0.5,-0.866025403784)); -#151106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151107 = ORIENTED_EDGE('',*,*,#94218,.F.); -#151108 = ADVANCED_FACE('',(#151109),#89328,.F.); -#151109 = FACE_BOUND('',#151110,.T.); -#151110 = EDGE_LOOP('',(#151111,#151112,#151113,#151134)); -#151111 = ORIENTED_EDGE('',*,*,#151056,.T.); -#151112 = ORIENTED_EDGE('',*,*,#94243,.F.); -#151113 = ORIENTED_EDGE('',*,*,#151114,.F.); -#151114 = EDGE_CURVE('',#89313,#94221,#151115,.T.); -#151115 = SURFACE_CURVE('',#151116,(#151120,#151127),.PCURVE_S1.); -#151116 = LINE('',#151117,#151118); -#151117 = CARTESIAN_POINT('',(0.2,0.1,1.3)); -#151118 = VECTOR('',#151119,1.); -#151119 = DIRECTION('',(9.614813431918E-017,0.707106781187, +#153493 = DEFINITIONAL_REPRESENTATION('',(#153494),#153498); +#153494 = LINE('',#153495,#153496); +#153495 = CARTESIAN_POINT('',(-1.962615573355E-017,-2.931801742888E-017) + ); +#153496 = VECTOR('',#153497,1.); +#153497 = DIRECTION('',(0.5,-0.866025403784)); +#153498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153499 = ORIENTED_EDGE('',*,*,#96610,.F.); +#153500 = ADVANCED_FACE('',(#153501),#91720,.F.); +#153501 = FACE_BOUND('',#153502,.T.); +#153502 = EDGE_LOOP('',(#153503,#153504,#153505,#153526)); +#153503 = ORIENTED_EDGE('',*,*,#153448,.T.); +#153504 = ORIENTED_EDGE('',*,*,#96635,.F.); +#153505 = ORIENTED_EDGE('',*,*,#153506,.F.); +#153506 = EDGE_CURVE('',#91705,#96613,#153507,.T.); +#153507 = SURFACE_CURVE('',#153508,(#153512,#153519),.PCURVE_S1.); +#153508 = LINE('',#153509,#153510); +#153509 = CARTESIAN_POINT('',(0.2,0.1,1.3)); +#153510 = VECTOR('',#153511,1.); +#153511 = DIRECTION('',(9.614813431918E-017,0.707106781187, 0.707106781187)); -#151120 = PCURVE('',#89328,#151121); -#151121 = DEFINITIONAL_REPRESENTATION('',(#151122),#151126); -#151122 = LINE('',#151123,#151124); -#151123 = CARTESIAN_POINT('',(-0.141421356237,0.2)); -#151124 = VECTOR('',#151125,1.); -#151125 = DIRECTION('',(1.,9.614813431918E-017)); -#151126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151127 = PCURVE('',#151096,#151128); -#151128 = DEFINITIONAL_REPRESENTATION('',(#151129),#151133); -#151129 = LINE('',#151130,#151131); -#151130 = CARTESIAN_POINT('',(-2.321412376563E-017,0.244948974278)); -#151131 = VECTOR('',#151132,1.); -#151132 = DIRECTION('',(-1.,1.000650183217E-016)); -#151133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151134 = ORIENTED_EDGE('',*,*,#89310,.F.); -#151135 = ADVANCED_FACE('',(#151136),#151096,.T.); -#151136 = FACE_BOUND('',#151137,.T.); -#151137 = EDGE_LOOP('',(#151138,#151139,#151140)); -#151138 = ORIENTED_EDGE('',*,*,#151114,.T.); -#151139 = ORIENTED_EDGE('',*,*,#151082,.T.); -#151140 = ORIENTED_EDGE('',*,*,#151141,.F.); -#151141 = EDGE_CURVE('',#89313,#92187,#151142,.T.); -#151142 = SURFACE_CURVE('',#151143,(#151147,#151154),.PCURVE_S1.); -#151143 = LINE('',#151144,#151145); -#151144 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); -#151145 = VECTOR('',#151146,1.); -#151146 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#151147 = PCURVE('',#151096,#151148); -#151148 = DEFINITIONAL_REPRESENTATION('',(#151149),#151153); -#151149 = LINE('',#151150,#151151); -#151150 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151151 = VECTOR('',#151152,1.); -#151152 = DIRECTION('',(-0.5,-0.866025403784)); -#151153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151154 = PCURVE('',#89356,#151155); -#151155 = DEFINITIONAL_REPRESENTATION('',(#151156),#151160); -#151156 = LINE('',#151157,#151158); -#151157 = CARTESIAN_POINT('',(0.282842712475,-0.2)); -#151158 = VECTOR('',#151159,1.); -#151159 = DIRECTION('',(1.,0.E+000)); -#151160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151161 = ADVANCED_FACE('',(#151162),#89356,.F.); -#151162 = FACE_BOUND('',#151163,.T.); -#151163 = EDGE_LOOP('',(#151164,#151165,#151166,#151167)); -#151164 = ORIENTED_EDGE('',*,*,#151141,.T.); -#151165 = ORIENTED_EDGE('',*,*,#92186,.F.); -#151166 = ORIENTED_EDGE('',*,*,#94314,.F.); -#151167 = ORIENTED_EDGE('',*,*,#89340,.F.); -#151168 = ADVANCED_FACE('',(#151169),#86384,.F.); -#151169 = FACE_BOUND('',#151170,.F.); -#151170 = EDGE_LOOP('',(#151171,#151172,#151173,#151174)); -#151171 = ORIENTED_EDGE('',*,*,#86427,.T.); -#151172 = ORIENTED_EDGE('',*,*,#94190,.F.); -#151173 = ORIENTED_EDGE('',*,*,#86369,.F.); -#151174 = ORIENTED_EDGE('',*,*,#151175,.T.); -#151175 = EDGE_CURVE('',#86337,#86335,#151176,.T.); -#151176 = SURFACE_CURVE('',#151177,(#151182,#151188),.PCURVE_S1.); -#151177 = CIRCLE('',#151178,0.345974717232); -#151178 = AXIS2_PLACEMENT_3D('',#151179,#151180,#151181); -#151179 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); -#151180 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151181 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151182 = PCURVE('',#86384,#151183); -#151183 = DEFINITIONAL_REPRESENTATION('',(#151184),#151187); -#151184 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#151185,#151186), +#153512 = PCURVE('',#91720,#153513); +#153513 = DEFINITIONAL_REPRESENTATION('',(#153514),#153518); +#153514 = LINE('',#153515,#153516); +#153515 = CARTESIAN_POINT('',(-0.141421356237,0.2)); +#153516 = VECTOR('',#153517,1.); +#153517 = DIRECTION('',(1.,9.614813431918E-017)); +#153518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153519 = PCURVE('',#153488,#153520); +#153520 = DEFINITIONAL_REPRESENTATION('',(#153521),#153525); +#153521 = LINE('',#153522,#153523); +#153522 = CARTESIAN_POINT('',(-2.321412376563E-017,0.244948974278)); +#153523 = VECTOR('',#153524,1.); +#153524 = DIRECTION('',(-1.,1.000650183217E-016)); +#153525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153526 = ORIENTED_EDGE('',*,*,#91702,.F.); +#153527 = ADVANCED_FACE('',(#153528),#153488,.T.); +#153528 = FACE_BOUND('',#153529,.T.); +#153529 = EDGE_LOOP('',(#153530,#153531,#153532)); +#153530 = ORIENTED_EDGE('',*,*,#153506,.T.); +#153531 = ORIENTED_EDGE('',*,*,#153474,.T.); +#153532 = ORIENTED_EDGE('',*,*,#153533,.F.); +#153533 = EDGE_CURVE('',#91705,#94579,#153534,.T.); +#153534 = SURFACE_CURVE('',#153535,(#153539,#153546),.PCURVE_S1.); +#153535 = LINE('',#153536,#153537); +#153536 = CARTESIAN_POINT('',(0.E+000,0.2,1.2)); +#153537 = VECTOR('',#153538,1.); +#153538 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#153539 = PCURVE('',#153488,#153540); +#153540 = DEFINITIONAL_REPRESENTATION('',(#153541),#153545); +#153541 = LINE('',#153542,#153543); +#153542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153543 = VECTOR('',#153544,1.); +#153544 = DIRECTION('',(-0.5,-0.866025403784)); +#153545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153546 = PCURVE('',#91748,#153547); +#153547 = DEFINITIONAL_REPRESENTATION('',(#153548),#153552); +#153548 = LINE('',#153549,#153550); +#153549 = CARTESIAN_POINT('',(0.282842712475,-0.2)); +#153550 = VECTOR('',#153551,1.); +#153551 = DIRECTION('',(1.,0.E+000)); +#153552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153553 = ADVANCED_FACE('',(#153554),#91748,.F.); +#153554 = FACE_BOUND('',#153555,.T.); +#153555 = EDGE_LOOP('',(#153556,#153557,#153558,#153559)); +#153556 = ORIENTED_EDGE('',*,*,#153533,.T.); +#153557 = ORIENTED_EDGE('',*,*,#94578,.F.); +#153558 = ORIENTED_EDGE('',*,*,#96706,.F.); +#153559 = ORIENTED_EDGE('',*,*,#91732,.F.); +#153560 = ADVANCED_FACE('',(#153561),#88776,.F.); +#153561 = FACE_BOUND('',#153562,.F.); +#153562 = EDGE_LOOP('',(#153563,#153564,#153565,#153566)); +#153563 = ORIENTED_EDGE('',*,*,#88819,.T.); +#153564 = ORIENTED_EDGE('',*,*,#96582,.F.); +#153565 = ORIENTED_EDGE('',*,*,#88761,.F.); +#153566 = ORIENTED_EDGE('',*,*,#153567,.T.); +#153567 = EDGE_CURVE('',#88729,#88727,#153568,.T.); +#153568 = SURFACE_CURVE('',#153569,(#153574,#153580),.PCURVE_S1.); +#153569 = CIRCLE('',#153570,0.345974717232); +#153570 = AXIS2_PLACEMENT_3D('',#153571,#153572,#153573); +#153571 = CARTESIAN_POINT('',(0.878908848969,0.95874916833,1.1)); +#153572 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153573 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153574 = PCURVE('',#88776,#153575); +#153575 = DEFINITIONAL_REPRESENTATION('',(#153576),#153579); +#153576 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153577,#153578), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#151185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151186 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#151187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153578 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#153579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151188 = PCURVE('',#86357,#151189); -#151189 = DEFINITIONAL_REPRESENTATION('',(#151190),#151194); -#151190 = CIRCLE('',#151191,0.345974717232); -#151191 = AXIS2_PLACEMENT_2D('',#151192,#151193); -#151192 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151193 = DIRECTION('',(1.,0.E+000)); -#151194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153580 = PCURVE('',#88749,#153581); +#153581 = DEFINITIONAL_REPRESENTATION('',(#153582),#153586); +#153582 = CIRCLE('',#153583,0.345974717232); +#153583 = AXIS2_PLACEMENT_2D('',#153584,#153585); +#153584 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153585 = DIRECTION('',(1.,0.E+000)); +#153586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151195 = ADVANCED_FACE('',(#151196),#86357,.T.); -#151196 = FACE_BOUND('',#151197,.T.); -#151197 = EDGE_LOOP('',(#151198,#151199)); -#151198 = ORIENTED_EDGE('',*,*,#151175,.T.); -#151199 = ORIENTED_EDGE('',*,*,#86334,.T.); -#151200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#151204)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#151201,#151202,#151203)) +#153587 = ADVANCED_FACE('',(#153588),#88749,.T.); +#153588 = FACE_BOUND('',#153589,.T.); +#153589 = EDGE_LOOP('',(#153590,#153591)); +#153590 = ORIENTED_EDGE('',*,*,#153567,.T.); +#153591 = ORIENTED_EDGE('',*,*,#88726,.T.); +#153592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#153596)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#153593,#153594,#153595)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#151201 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#151202 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#151203 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#151204 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#151201, +#153593 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#153594 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#153595 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#153596 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#153593, 'distance_accuracy_value','confusion accuracy'); -#151205 = SHAPE_DEFINITION_REPRESENTATION(#151206,#86327); -#151206 = PRODUCT_DEFINITION_SHAPE('','',#151207); -#151207 = PRODUCT_DEFINITION('design','',#151208,#151211); -#151208 = PRODUCT_DEFINITION_FORMATION('','',#151209); -#151209 = PRODUCT('LQFP-64','LQFP-64','',(#151210)); -#151210 = PRODUCT_CONTEXT('',#2,'mechanical'); -#151211 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#151212 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#151213,#151215); -#151213 = ( REPRESENTATION_RELATIONSHIP('','',#86327,#86317) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#151214) +#153597 = SHAPE_DEFINITION_REPRESENTATION(#153598,#88719); +#153598 = PRODUCT_DEFINITION_SHAPE('','',#153599); +#153599 = PRODUCT_DEFINITION('design','',#153600,#153603); +#153600 = PRODUCT_DEFINITION_FORMATION('','',#153601); +#153601 = PRODUCT('LQFP-64','LQFP-64','',(#153602)); +#153602 = PRODUCT_CONTEXT('',#2,'mechanical'); +#153603 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#153604 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#153605,#153607); +#153605 = ( REPRESENTATION_RELATIONSHIP('','',#88719,#88709) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#153606) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#151214 = ITEM_DEFINED_TRANSFORMATION('','',#11,#86318); -#151215 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #151216); -#151216 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('267','=>[0:1:1:78]','',#86312, - #151207,$); -#151217 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#151209)); -#151218 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#151219,#151221); -#151219 = ( REPRESENTATION_RELATIONSHIP('','',#86317,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#151220) +#153606 = ITEM_DEFINED_TRANSFORMATION('','',#11,#88710); +#153607 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #153608); +#153608 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('368','=>[0:1:1:78]','',#88704, + #153599,$); +#153609 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#153601)); +#153610 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#153611,#153613); +#153611 = ( REPRESENTATION_RELATIONSHIP('','',#88709,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#153612) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#151220 = ITEM_DEFINED_TRANSFORMATION('','',#11,#223); -#151221 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #151222); -#151222 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('268','=>[0:1:1:77]','',#5, - #86312,$); -#151223 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#86314)); -#151224 = SHAPE_DEFINITION_REPRESENTATION(#151225,#151231); -#151225 = PRODUCT_DEFINITION_SHAPE('','',#151226); -#151226 = PRODUCT_DEFINITION('design','',#151227,#151230); -#151227 = PRODUCT_DEFINITION_FORMATION('','',#151228); -#151228 = PRODUCT('U6','U6','',(#151229)); -#151229 = PRODUCT_CONTEXT('',#2,'mechanical'); -#151230 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#151231 = SHAPE_REPRESENTATION('',(#11,#151232),#151236); -#151232 = AXIS2_PLACEMENT_3D('',#151233,#151234,#151235); -#151233 = CARTESIAN_POINT('',(9.14404318,18.92312192,1.27E-002)); -#151234 = DIRECTION('',(-2.449212707645E-016,-1.,1.110223024625E-016)); -#151235 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#151236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#151240)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#151237,#151238,#151239)) +#153612 = ITEM_DEFINED_TRANSFORMATION('','',#11,#223); +#153613 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #153614); +#153614 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('369','=>[0:1:1:77]','',#5, + #88704,$); +#153615 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#88706)); +#153616 = SHAPE_DEFINITION_REPRESENTATION(#153617,#153623); +#153617 = PRODUCT_DEFINITION_SHAPE('','',#153618); +#153618 = PRODUCT_DEFINITION('design','',#153619,#153622); +#153619 = PRODUCT_DEFINITION_FORMATION('','',#153620); +#153620 = PRODUCT('U6','U6','',(#153621)); +#153621 = PRODUCT_CONTEXT('',#2,'mechanical'); +#153622 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#153623 = SHAPE_REPRESENTATION('',(#11,#153624),#153628); +#153624 = AXIS2_PLACEMENT_3D('',#153625,#153626,#153627); +#153625 = CARTESIAN_POINT('',(9.14404318,18.92312192,1.27E-002)); +#153626 = DIRECTION('',(-2.449212707645E-016,-1.,1.110223024625E-016)); +#153627 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#153628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#153632)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#153629,#153630,#153631)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#151237 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#151238 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#151239 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#151240 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#151237, +#153629 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#153630 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#153631 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#153632 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#153629, 'distance_accuracy_value','confusion accuracy'); -#151241 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#151242),#156644); -#151242 = MANIFOLD_SOLID_BREP('',#151243); -#151243 = CLOSED_SHELL('',(#151244,#151685,#152004,#152161,#152232, - #152333,#152380,#152389,#152398,#152473,#152754,#152995,#153021, - #153047,#153073,#153099,#153126,#153153,#153179,#153205,#153231, - #153238,#153313,#153594,#153835,#153861,#153910,#153936,#153963, - #153990,#154016,#154042,#154068,#154094,#154101,#154176,#154457, - #154698,#154724,#154750,#154776,#154802,#154828,#154855,#154882, - #154908,#154934,#154941,#155016,#155297,#155538,#155564,#155590, - #155616,#155642,#155668,#155695,#155722,#155748,#155774,#155781, - #155856,#156137,#156378,#156404,#156453,#156479,#156506,#156533, - #156559,#156585,#156611,#156637)); -#151244 = ADVANCED_FACE('',(#151245),#151259,.F.); -#151245 = FACE_BOUND('',#151246,.T.); -#151246 = EDGE_LOOP('',(#151247,#151282,#151310,#151338,#151366,#151394, - #151422,#151450,#151473,#151501,#151529,#151557,#151580,#151608, - #151636,#151664)); -#151247 = ORIENTED_EDGE('',*,*,#151248,.F.); -#151248 = EDGE_CURVE('',#151249,#151251,#151253,.T.); -#151249 = VERTEX_POINT('',#151250); -#151250 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); -#151251 = VERTEX_POINT('',#151252); -#151252 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.825)); -#151253 = SURFACE_CURVE('',#151254,(#151258,#151270),.PCURVE_S1.); -#151254 = LINE('',#151255,#151256); -#151255 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.825)); -#151256 = VECTOR('',#151257,1.); -#151257 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151258 = PCURVE('',#151259,#151264); -#151259 = PLANE('',#151260); -#151260 = AXIS2_PLACEMENT_3D('',#151261,#151262,#151263); -#151261 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#151262 = DIRECTION('',(0.994521895368,-0.104528463268,0.E+000)); -#151263 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); -#151264 = DEFINITIONAL_REPRESENTATION('',(#151265),#151269); -#151265 = LINE('',#151266,#151267); -#151266 = CARTESIAN_POINT('',(0.E+000,-1.875)); -#151267 = VECTOR('',#151268,1.); -#151268 = DIRECTION('',(-1.,0.E+000)); -#151269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153633 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#153634),#159036); +#153634 = MANIFOLD_SOLID_BREP('',#153635); +#153635 = CLOSED_SHELL('',(#153636,#154077,#154396,#154553,#154624, + #154725,#154772,#154781,#154790,#154865,#155146,#155387,#155413, + #155439,#155465,#155491,#155518,#155545,#155571,#155597,#155623, + #155630,#155705,#155986,#156227,#156253,#156302,#156328,#156355, + #156382,#156408,#156434,#156460,#156486,#156493,#156568,#156849, + #157090,#157116,#157142,#157168,#157194,#157220,#157247,#157274, + #157300,#157326,#157333,#157408,#157689,#157930,#157956,#157982, + #158008,#158034,#158060,#158087,#158114,#158140,#158166,#158173, + #158248,#158529,#158770,#158796,#158845,#158871,#158898,#158925, + #158951,#158977,#159003,#159029)); +#153636 = ADVANCED_FACE('',(#153637),#153651,.F.); +#153637 = FACE_BOUND('',#153638,.T.); +#153638 = EDGE_LOOP('',(#153639,#153674,#153702,#153730,#153758,#153786, + #153814,#153842,#153865,#153893,#153921,#153949,#153972,#154000, + #154028,#154056)); +#153639 = ORIENTED_EDGE('',*,*,#153640,.F.); +#153640 = EDGE_CURVE('',#153641,#153643,#153645,.T.); +#153641 = VERTEX_POINT('',#153642); +#153642 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); +#153643 = VERTEX_POINT('',#153644); +#153644 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.825)); +#153645 = SURFACE_CURVE('',#153646,(#153650,#153662),.PCURVE_S1.); +#153646 = LINE('',#153647,#153648); +#153647 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.825)); +#153648 = VECTOR('',#153649,1.); +#153649 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#153650 = PCURVE('',#153651,#153656); +#153651 = PLANE('',#153652); +#153652 = AXIS2_PLACEMENT_3D('',#153653,#153654,#153655); +#153653 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#153654 = DIRECTION('',(0.994521895368,-0.104528463268,0.E+000)); +#153655 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); +#153656 = DEFINITIONAL_REPRESENTATION('',(#153657),#153661); +#153657 = LINE('',#153658,#153659); +#153658 = CARTESIAN_POINT('',(0.E+000,-1.875)); +#153659 = VECTOR('',#153660,1.); +#153660 = DIRECTION('',(-1.,0.E+000)); +#153661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153662 = PCURVE('',#153663,#153668); +#153663 = PLANE('',#153664); +#153664 = AXIS2_PLACEMENT_3D('',#153665,#153666,#153667); +#153665 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); +#153666 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153667 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153668 = DEFINITIONAL_REPRESENTATION('',(#153669),#153673); +#153669 = LINE('',#153670,#153671); +#153670 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); +#153671 = VECTOR('',#153672,1.); +#153672 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#153673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153674 = ORIENTED_EDGE('',*,*,#153675,.T.); +#153675 = EDGE_CURVE('',#153641,#153676,#153678,.T.); +#153676 = VERTEX_POINT('',#153677); +#153677 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.475)); +#153678 = SURFACE_CURVE('',#153679,(#153683,#153690),.PCURVE_S1.); +#153679 = LINE('',#153680,#153681); +#153680 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); +#153681 = VECTOR('',#153682,1.); +#153682 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153683 = PCURVE('',#153651,#153684); +#153684 = DEFINITIONAL_REPRESENTATION('',(#153685),#153689); +#153685 = LINE('',#153686,#153687); +#153686 = CARTESIAN_POINT('',(-0.302322816019,-1.875)); +#153687 = VECTOR('',#153688,1.); +#153688 = DIRECTION('',(0.E+000,1.)); +#153689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153690 = PCURVE('',#153691,#153696); +#153691 = PLANE('',#153692); +#153692 = AXIS2_PLACEMENT_3D('',#153693,#153694,#153695); +#153693 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); +#153694 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#153695 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153696 = DEFINITIONAL_REPRESENTATION('',(#153697),#153701); +#153697 = LINE('',#153698,#153699); +#153698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153699 = VECTOR('',#153700,1.); +#153700 = DIRECTION('',(-1.,0.E+000)); +#153701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153702 = ORIENTED_EDGE('',*,*,#153703,.T.); +#153703 = EDGE_CURVE('',#153676,#153704,#153706,.T.); +#153704 = VERTEX_POINT('',#153705); +#153705 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.475)); +#153706 = SURFACE_CURVE('',#153707,(#153711,#153718),.PCURVE_S1.); +#153707 = LINE('',#153708,#153709); +#153708 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.475)); +#153709 = VECTOR('',#153710,1.); +#153710 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#153711 = PCURVE('',#153651,#153712); +#153712 = DEFINITIONAL_REPRESENTATION('',(#153713),#153717); +#153713 = LINE('',#153714,#153715); +#153714 = CARTESIAN_POINT('',(0.E+000,-1.525)); +#153715 = VECTOR('',#153716,1.); +#153716 = DIRECTION('',(-1.,0.E+000)); +#153717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153718 = PCURVE('',#153719,#153724); +#153719 = PLANE('',#153720); +#153720 = AXIS2_PLACEMENT_3D('',#153721,#153722,#153723); +#153721 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); +#153722 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153723 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153724 = DEFINITIONAL_REPRESENTATION('',(#153725),#153729); +#153725 = LINE('',#153726,#153727); +#153726 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); +#153727 = VECTOR('',#153728,1.); +#153728 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#153729 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153730 = ORIENTED_EDGE('',*,*,#153731,.F.); +#153731 = EDGE_CURVE('',#153732,#153704,#153734,.T.); +#153732 = VERTEX_POINT('',#153733); +#153733 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.1125)); +#153734 = SURFACE_CURVE('',#153735,(#153739,#153746),.PCURVE_S1.); +#153735 = LINE('',#153736,#153737); +#153736 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#153737 = VECTOR('',#153738,1.); +#153738 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153739 = PCURVE('',#153651,#153740); +#153740 = DEFINITIONAL_REPRESENTATION('',(#153741),#153745); +#153741 = LINE('',#153742,#153743); +#153742 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); +#153743 = VECTOR('',#153744,1.); +#153744 = DIRECTION('',(0.E+000,-1.)); +#153745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153746 = PCURVE('',#153747,#153752); +#153747 = PLANE('',#153748); +#153748 = AXIS2_PLACEMENT_3D('',#153749,#153750,#153751); +#153749 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#153750 = DIRECTION('',(0.998629534755,5.233595624294E-002,0.E+000)); +#153751 = DIRECTION('',(-5.233595624294E-002,0.998629534755,0.E+000)); +#153752 = DEFINITIONAL_REPRESENTATION('',(#153753),#153757); +#153753 = LINE('',#153754,#153755); +#153754 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153755 = VECTOR('',#153756,1.); +#153756 = DIRECTION('',(0.E+000,-1.)); +#153757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153758 = ORIENTED_EDGE('',*,*,#153759,.F.); +#153759 = EDGE_CURVE('',#153760,#153732,#153762,.T.); +#153760 = VERTEX_POINT('',#153761); +#153761 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.1125)); +#153762 = SURFACE_CURVE('',#153763,(#153767,#153774),.PCURVE_S1.); +#153763 = LINE('',#153764,#153765); +#153764 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.1125)); +#153765 = VECTOR('',#153766,1.); +#153766 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#153767 = PCURVE('',#153651,#153768); +#153768 = DEFINITIONAL_REPRESENTATION('',(#153769),#153773); +#153769 = LINE('',#153770,#153771); +#153770 = CARTESIAN_POINT('',(0.E+000,-1.1625)); +#153771 = VECTOR('',#153772,1.); +#153772 = DIRECTION('',(-1.,0.E+000)); +#153773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153774 = PCURVE('',#153775,#153780); +#153775 = PLANE('',#153776); +#153776 = AXIS2_PLACEMENT_3D('',#153777,#153778,#153779); +#153777 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); +#153778 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153779 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153780 = DEFINITIONAL_REPRESENTATION('',(#153781),#153785); +#153781 = LINE('',#153782,#153783); +#153782 = CARTESIAN_POINT('',(0.131166903554,0.33266666)); +#153783 = VECTOR('',#153784,1.); +#153784 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#153785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153786 = ORIENTED_EDGE('',*,*,#153787,.F.); +#153787 = EDGE_CURVE('',#153788,#153760,#153790,.T.); +#153788 = VERTEX_POINT('',#153789); +#153789 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); +#153790 = SURFACE_CURVE('',#153791,(#153795,#153802),.PCURVE_S1.); +#153791 = LINE('',#153792,#153793); +#153792 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); +#153793 = VECTOR('',#153794,1.); +#153794 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153795 = PCURVE('',#153651,#153796); +#153796 = DEFINITIONAL_REPRESENTATION('',(#153797),#153801); +#153797 = LINE('',#153798,#153799); +#153798 = CARTESIAN_POINT('',(-0.302322816019,-0.9375)); +#153799 = VECTOR('',#153800,1.); +#153800 = DIRECTION('',(0.E+000,-1.)); +#153801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153802 = PCURVE('',#153803,#153808); +#153803 = PLANE('',#153804); +#153804 = AXIS2_PLACEMENT_3D('',#153805,#153806,#153807); +#153805 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); +#153806 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#153807 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153808 = DEFINITIONAL_REPRESENTATION('',(#153809),#153813); +#153809 = LINE('',#153810,#153811); +#153810 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153811 = VECTOR('',#153812,1.); +#153812 = DIRECTION('',(1.,0.E+000)); +#153813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153814 = ORIENTED_EDGE('',*,*,#153815,.T.); +#153815 = EDGE_CURVE('',#153788,#153816,#153818,.T.); +#153816 = VERTEX_POINT('',#153817); +#153817 = CARTESIAN_POINT('',(-0.575,0.68333334,0.1125)); +#153818 = SURFACE_CURVE('',#153819,(#153823,#153830),.PCURVE_S1.); +#153819 = LINE('',#153820,#153821); +#153820 = CARTESIAN_POINT('',(-0.541716992867,1.,0.1125)); +#153821 = VECTOR('',#153822,1.); +#153822 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#153823 = PCURVE('',#153651,#153824); +#153824 = DEFINITIONAL_REPRESENTATION('',(#153825),#153829); +#153825 = LINE('',#153826,#153827); +#153826 = CARTESIAN_POINT('',(0.E+000,-0.9375)); +#153827 = VECTOR('',#153828,1.); +#153828 = DIRECTION('',(-1.,0.E+000)); +#153829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153830 = PCURVE('',#153831,#153836); +#153831 = PLANE('',#153832); +#153832 = AXIS2_PLACEMENT_3D('',#153833,#153834,#153835); +#153833 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); +#153834 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153835 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153836 = DEFINITIONAL_REPRESENTATION('',(#153837),#153841); +#153837 = LINE('',#153838,#153839); +#153838 = CARTESIAN_POINT('',(0.131166903554,0.33266666)); +#153839 = VECTOR('',#153840,1.); +#153840 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#153841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153842 = ORIENTED_EDGE('',*,*,#153843,.F.); +#153843 = EDGE_CURVE('',#153844,#153816,#153846,.T.); +#153844 = VERTEX_POINT('',#153845); +#153845 = CARTESIAN_POINT('',(-0.575,0.68333334,0.475)); +#153846 = SURFACE_CURVE('',#153847,(#153851,#153858),.PCURVE_S1.); +#153847 = LINE('',#153848,#153849); +#153848 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#153849 = VECTOR('',#153850,1.); +#153850 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153851 = PCURVE('',#153651,#153852); +#153852 = DEFINITIONAL_REPRESENTATION('',(#153853),#153857); +#153853 = LINE('',#153854,#153855); +#153854 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); +#153855 = VECTOR('',#153856,1.); +#153856 = DIRECTION('',(0.E+000,-1.)); +#153857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153858 = PCURVE('',#153747,#153859); +#153859 = DEFINITIONAL_REPRESENTATION('',(#153860),#153864); +#153860 = LINE('',#153861,#153862); +#153861 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153862 = VECTOR('',#153863,1.); +#153863 = DIRECTION('',(0.E+000,-1.)); +#153864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153865 = ORIENTED_EDGE('',*,*,#153866,.T.); +#153866 = EDGE_CURVE('',#153844,#153867,#153869,.T.); +#153867 = VERTEX_POINT('',#153868); +#153868 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.475)); +#153869 = SURFACE_CURVE('',#153870,(#153874,#153881),.PCURVE_S1.); +#153870 = LINE('',#153871,#153872); +#153871 = CARTESIAN_POINT('',(-0.541716992867,1.,0.475)); +#153872 = VECTOR('',#153873,1.); +#153873 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); +#153874 = PCURVE('',#153651,#153875); +#153875 = DEFINITIONAL_REPRESENTATION('',(#153876),#153880); +#153876 = LINE('',#153877,#153878); +#153877 = CARTESIAN_POINT('',(0.E+000,-0.575)); +#153878 = VECTOR('',#153879,1.); +#153879 = DIRECTION('',(1.,0.E+000)); +#153880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153881 = PCURVE('',#153882,#153887); +#153882 = PLANE('',#153883); +#153883 = AXIS2_PLACEMENT_3D('',#153884,#153885,#153886); +#153884 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); +#153885 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153886 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153887 = DEFINITIONAL_REPRESENTATION('',(#153888),#153892); +#153888 = LINE('',#153889,#153890); +#153889 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); +#153890 = VECTOR('',#153891,1.); +#153891 = DIRECTION('',(0.104528463268,-0.994521895368)); +#153892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153893 = ORIENTED_EDGE('',*,*,#153894,.F.); +#153894 = EDGE_CURVE('',#153895,#153867,#153897,.T.); +#153895 = VERTEX_POINT('',#153896); +#153896 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); +#153897 = SURFACE_CURVE('',#153898,(#153902,#153909),.PCURVE_S1.); +#153898 = LINE('',#153899,#153900); +#153899 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); +#153900 = VECTOR('',#153901,1.); +#153901 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153902 = PCURVE('',#153651,#153903); +#153903 = DEFINITIONAL_REPRESENTATION('',(#153904),#153908); +#153904 = LINE('',#153905,#153906); +#153905 = CARTESIAN_POINT('',(-0.302322816019,-0.225)); +#153906 = VECTOR('',#153907,1.); +#153907 = DIRECTION('',(0.E+000,-1.)); +#153908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153909 = PCURVE('',#153910,#153915); +#153910 = PLANE('',#153911); +#153911 = AXIS2_PLACEMENT_3D('',#153912,#153913,#153914); +#153912 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); +#153913 = DIRECTION('',(0.E+000,1.,0.E+000)); +#153914 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153915 = DEFINITIONAL_REPRESENTATION('',(#153916),#153920); +#153916 = LINE('',#153917,#153918); +#153917 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153918 = VECTOR('',#153919,1.); +#153919 = DIRECTION('',(-1.,0.E+000)); +#153920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153921 = ORIENTED_EDGE('',*,*,#153922,.F.); +#153922 = EDGE_CURVE('',#153923,#153895,#153925,.T.); +#153923 = VERTEX_POINT('',#153924); +#153924 = CARTESIAN_POINT('',(-0.575,0.68333334,0.825)); +#153925 = SURFACE_CURVE('',#153926,(#153930,#153937),.PCURVE_S1.); +#153926 = LINE('',#153927,#153928); +#153927 = CARTESIAN_POINT('',(-0.541716992867,1.,0.825)); +#153928 = VECTOR('',#153929,1.); +#153929 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); +#153930 = PCURVE('',#153651,#153931); +#153931 = DEFINITIONAL_REPRESENTATION('',(#153932),#153936); +#153932 = LINE('',#153933,#153934); +#153933 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#153934 = VECTOR('',#153935,1.); +#153935 = DIRECTION('',(1.,0.E+000)); +#153936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153937 = PCURVE('',#153938,#153943); +#153938 = PLANE('',#153939); +#153939 = AXIS2_PLACEMENT_3D('',#153940,#153941,#153942); +#153940 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); +#153941 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153943 = DEFINITIONAL_REPRESENTATION('',(#153944),#153948); +#153944 = LINE('',#153945,#153946); +#153945 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); +#153946 = VECTOR('',#153947,1.); +#153947 = DIRECTION('',(0.104528463268,-0.994521895368)); +#153948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153949 = ORIENTED_EDGE('',*,*,#153950,.F.); +#153950 = EDGE_CURVE('',#153951,#153923,#153953,.T.); +#153951 = VERTEX_POINT('',#153952); +#153952 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#153953 = SURFACE_CURVE('',#153954,(#153958,#153965),.PCURVE_S1.); +#153954 = LINE('',#153955,#153956); +#153955 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#153956 = VECTOR('',#153957,1.); +#153957 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#153958 = PCURVE('',#153651,#153959); +#153959 = DEFINITIONAL_REPRESENTATION('',(#153960),#153964); +#153960 = LINE('',#153961,#153962); +#153961 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); +#153962 = VECTOR('',#153963,1.); +#153963 = DIRECTION('',(0.E+000,-1.)); +#153964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153965 = PCURVE('',#153747,#153966); +#153966 = DEFINITIONAL_REPRESENTATION('',(#153967),#153971); +#153967 = LINE('',#153968,#153969); +#153968 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153969 = VECTOR('',#153970,1.); +#153970 = DIRECTION('',(0.E+000,-1.)); +#153971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#153972 = ORIENTED_EDGE('',*,*,#153973,.F.); +#153973 = EDGE_CURVE('',#153974,#153951,#153976,.T.); +#153974 = VERTEX_POINT('',#153975); +#153975 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#153976 = SURFACE_CURVE('',#153977,(#153981,#153988),.PCURVE_S1.); +#153977 = LINE('',#153978,#153979); +#153978 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#153979 = VECTOR('',#153980,1.); +#153980 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#153981 = PCURVE('',#153651,#153982); +#153982 = DEFINITIONAL_REPRESENTATION('',(#153983),#153987); +#153983 = LINE('',#153984,#153985); +#153984 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#153985 = VECTOR('',#153986,1.); +#153986 = DIRECTION('',(-1.,0.E+000)); +#153987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151270 = PCURVE('',#151271,#151276); -#151271 = PLANE('',#151272); -#151272 = AXIS2_PLACEMENT_3D('',#151273,#151274,#151275); -#151273 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); -#151274 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151275 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151276 = DEFINITIONAL_REPRESENTATION('',(#151277),#151281); -#151277 = LINE('',#151278,#151279); -#151278 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); -#151279 = VECTOR('',#151280,1.); -#151280 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151282 = ORIENTED_EDGE('',*,*,#151283,.T.); -#151283 = EDGE_CURVE('',#151249,#151284,#151286,.T.); -#151284 = VERTEX_POINT('',#151285); -#151285 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.475)); -#151286 = SURFACE_CURVE('',#151287,(#151291,#151298),.PCURVE_S1.); -#151287 = LINE('',#151288,#151289); -#151288 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); -#151289 = VECTOR('',#151290,1.); -#151290 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151291 = PCURVE('',#151259,#151292); -#151292 = DEFINITIONAL_REPRESENTATION('',(#151293),#151297); -#151293 = LINE('',#151294,#151295); -#151294 = CARTESIAN_POINT('',(-0.302322816019,-1.875)); -#151295 = VECTOR('',#151296,1.); -#151296 = DIRECTION('',(0.E+000,1.)); -#151297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151298 = PCURVE('',#151299,#151304); -#151299 = PLANE('',#151300); -#151300 = AXIS2_PLACEMENT_3D('',#151301,#151302,#151303); -#151301 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); -#151302 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#151303 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151304 = DEFINITIONAL_REPRESENTATION('',(#151305),#151309); -#151305 = LINE('',#151306,#151307); -#151306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151307 = VECTOR('',#151308,1.); -#151308 = DIRECTION('',(-1.,0.E+000)); -#151309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151310 = ORIENTED_EDGE('',*,*,#151311,.T.); -#151311 = EDGE_CURVE('',#151284,#151312,#151314,.T.); -#151312 = VERTEX_POINT('',#151313); -#151313 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.475)); -#151314 = SURFACE_CURVE('',#151315,(#151319,#151326),.PCURVE_S1.); -#151315 = LINE('',#151316,#151317); -#151316 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.475)); -#151317 = VECTOR('',#151318,1.); -#151318 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151319 = PCURVE('',#151259,#151320); -#151320 = DEFINITIONAL_REPRESENTATION('',(#151321),#151325); -#151321 = LINE('',#151322,#151323); -#151322 = CARTESIAN_POINT('',(0.E+000,-1.525)); -#151323 = VECTOR('',#151324,1.); -#151324 = DIRECTION('',(-1.,0.E+000)); -#151325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151326 = PCURVE('',#151327,#151332); -#151327 = PLANE('',#151328); -#151328 = AXIS2_PLACEMENT_3D('',#151329,#151330,#151331); -#151329 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); -#151330 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151331 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151332 = DEFINITIONAL_REPRESENTATION('',(#151333),#151337); -#151333 = LINE('',#151334,#151335); -#151334 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); -#151335 = VECTOR('',#151336,1.); -#151336 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151338 = ORIENTED_EDGE('',*,*,#151339,.F.); -#151339 = EDGE_CURVE('',#151340,#151312,#151342,.T.); -#151340 = VERTEX_POINT('',#151341); -#151341 = CARTESIAN_POINT('',(-0.575,0.68333334,-0.1125)); -#151342 = SURFACE_CURVE('',#151343,(#151347,#151354),.PCURVE_S1.); -#151343 = LINE('',#151344,#151345); -#151344 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151345 = VECTOR('',#151346,1.); -#151346 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151347 = PCURVE('',#151259,#151348); -#151348 = DEFINITIONAL_REPRESENTATION('',(#151349),#151353); -#151349 = LINE('',#151350,#151351); -#151350 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); -#151351 = VECTOR('',#151352,1.); -#151352 = DIRECTION('',(0.E+000,-1.)); -#151353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151354 = PCURVE('',#151355,#151360); -#151355 = PLANE('',#151356); -#151356 = AXIS2_PLACEMENT_3D('',#151357,#151358,#151359); -#151357 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151358 = DIRECTION('',(0.998629534755,5.233595624294E-002,0.E+000)); -#151359 = DIRECTION('',(-5.233595624294E-002,0.998629534755,0.E+000)); -#151360 = DEFINITIONAL_REPRESENTATION('',(#151361),#151365); -#151361 = LINE('',#151362,#151363); -#151362 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151363 = VECTOR('',#151364,1.); -#151364 = DIRECTION('',(0.E+000,-1.)); -#151365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151366 = ORIENTED_EDGE('',*,*,#151367,.F.); -#151367 = EDGE_CURVE('',#151368,#151340,#151370,.T.); -#151368 = VERTEX_POINT('',#151369); -#151369 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.1125)); -#151370 = SURFACE_CURVE('',#151371,(#151375,#151382),.PCURVE_S1.); -#151371 = LINE('',#151372,#151373); -#151372 = CARTESIAN_POINT('',(-0.541716992867,1.,-0.1125)); -#151373 = VECTOR('',#151374,1.); -#151374 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151375 = PCURVE('',#151259,#151376); -#151376 = DEFINITIONAL_REPRESENTATION('',(#151377),#151381); -#151377 = LINE('',#151378,#151379); -#151378 = CARTESIAN_POINT('',(0.E+000,-1.1625)); -#151379 = VECTOR('',#151380,1.); -#151380 = DIRECTION('',(-1.,0.E+000)); -#151381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151382 = PCURVE('',#151383,#151388); -#151383 = PLANE('',#151384); -#151384 = AXIS2_PLACEMENT_3D('',#151385,#151386,#151387); -#151385 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); -#151386 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151387 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151388 = DEFINITIONAL_REPRESENTATION('',(#151389),#151393); -#151389 = LINE('',#151390,#151391); -#151390 = CARTESIAN_POINT('',(0.131166903554,0.33266666)); -#151391 = VECTOR('',#151392,1.); -#151392 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151394 = ORIENTED_EDGE('',*,*,#151395,.F.); -#151395 = EDGE_CURVE('',#151396,#151368,#151398,.T.); -#151396 = VERTEX_POINT('',#151397); -#151397 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); -#151398 = SURFACE_CURVE('',#151399,(#151403,#151410),.PCURVE_S1.); -#151399 = LINE('',#151400,#151401); -#151400 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); -#151401 = VECTOR('',#151402,1.); -#151402 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151403 = PCURVE('',#151259,#151404); -#151404 = DEFINITIONAL_REPRESENTATION('',(#151405),#151409); -#151405 = LINE('',#151406,#151407); -#151406 = CARTESIAN_POINT('',(-0.302322816019,-0.9375)); -#151407 = VECTOR('',#151408,1.); -#151408 = DIRECTION('',(0.E+000,-1.)); -#151409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151410 = PCURVE('',#151411,#151416); -#151411 = PLANE('',#151412); -#151412 = AXIS2_PLACEMENT_3D('',#151413,#151414,#151415); -#151413 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); -#151414 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#151415 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151416 = DEFINITIONAL_REPRESENTATION('',(#151417),#151421); -#151417 = LINE('',#151418,#151419); -#151418 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151419 = VECTOR('',#151420,1.); -#151420 = DIRECTION('',(1.,0.E+000)); -#151421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151422 = ORIENTED_EDGE('',*,*,#151423,.T.); -#151423 = EDGE_CURVE('',#151396,#151424,#151426,.T.); -#151424 = VERTEX_POINT('',#151425); -#151425 = CARTESIAN_POINT('',(-0.575,0.68333334,0.1125)); -#151426 = SURFACE_CURVE('',#151427,(#151431,#151438),.PCURVE_S1.); -#151427 = LINE('',#151428,#151429); -#151428 = CARTESIAN_POINT('',(-0.541716992867,1.,0.1125)); -#151429 = VECTOR('',#151430,1.); -#151430 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151431 = PCURVE('',#151259,#151432); -#151432 = DEFINITIONAL_REPRESENTATION('',(#151433),#151437); -#151433 = LINE('',#151434,#151435); -#151434 = CARTESIAN_POINT('',(0.E+000,-0.9375)); -#151435 = VECTOR('',#151436,1.); -#151436 = DIRECTION('',(-1.,0.E+000)); -#151437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151438 = PCURVE('',#151439,#151444); -#151439 = PLANE('',#151440); -#151440 = AXIS2_PLACEMENT_3D('',#151441,#151442,#151443); -#151441 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); -#151442 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151443 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151444 = DEFINITIONAL_REPRESENTATION('',(#151445),#151449); -#151445 = LINE('',#151446,#151447); -#151446 = CARTESIAN_POINT('',(0.131166903554,0.33266666)); -#151447 = VECTOR('',#151448,1.); -#151448 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151450 = ORIENTED_EDGE('',*,*,#151451,.F.); -#151451 = EDGE_CURVE('',#151452,#151424,#151454,.T.); -#151452 = VERTEX_POINT('',#151453); -#151453 = CARTESIAN_POINT('',(-0.575,0.68333334,0.475)); -#151454 = SURFACE_CURVE('',#151455,(#151459,#151466),.PCURVE_S1.); -#151455 = LINE('',#151456,#151457); -#151456 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151457 = VECTOR('',#151458,1.); -#151458 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151459 = PCURVE('',#151259,#151460); -#151460 = DEFINITIONAL_REPRESENTATION('',(#151461),#151465); -#151461 = LINE('',#151462,#151463); -#151462 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); -#151463 = VECTOR('',#151464,1.); -#151464 = DIRECTION('',(0.E+000,-1.)); -#151465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#153988 = PCURVE('',#153989,#153994); +#153989 = PLANE('',#153990); +#153990 = AXIS2_PLACEMENT_3D('',#153991,#153992,#153993); +#153991 = CARTESIAN_POINT('',(-0.641566016369,5.E-002,1.05)); +#153992 = DIRECTION('',(0.E+000,0.E+000,1.)); +#153993 = DIRECTION('',(1.,0.E+000,0.E+000)); +#153994 = DEFINITIONAL_REPRESENTATION('',(#153995),#153999); +#153995 = LINE('',#153996,#153997); +#153996 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); +#153997 = VECTOR('',#153998,1.); +#153998 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#153999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154000 = ORIENTED_EDGE('',*,*,#154001,.T.); +#154001 = EDGE_CURVE('',#153974,#154002,#154004,.T.); +#154002 = VERTEX_POINT('',#154003); +#154003 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); +#154004 = SURFACE_CURVE('',#154005,(#154009,#154016),.PCURVE_S1.); +#154005 = LINE('',#154006,#154007); +#154006 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#154007 = VECTOR('',#154008,1.); +#154008 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154009 = PCURVE('',#153651,#154010); +#154010 = DEFINITIONAL_REPRESENTATION('',(#154011),#154015); +#154011 = LINE('',#154012,#154013); +#154012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154013 = VECTOR('',#154014,1.); +#154014 = DIRECTION('',(0.E+000,-1.)); +#154015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154016 = PCURVE('',#154017,#154022); +#154017 = PLANE('',#154018); +#154018 = AXIS2_PLACEMENT_3D('',#154019,#154020,#154021); +#154019 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#154020 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#154021 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154022 = DEFINITIONAL_REPRESENTATION('',(#154023),#154027); +#154023 = LINE('',#154024,#154025); +#154024 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154025 = VECTOR('',#154026,1.); +#154026 = DIRECTION('',(1.,0.E+000)); +#154027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154028 = ORIENTED_EDGE('',*,*,#154029,.T.); +#154029 = EDGE_CURVE('',#154002,#154030,#154032,.T.); +#154030 = VERTEX_POINT('',#154031); +#154031 = CARTESIAN_POINT('',(-0.575,0.68333334,-1.05)); +#154032 = SURFACE_CURVE('',#154033,(#154037,#154044),.PCURVE_S1.); +#154033 = LINE('',#154034,#154035); +#154034 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); +#154035 = VECTOR('',#154036,1.); +#154036 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); +#154037 = PCURVE('',#153651,#154038); +#154038 = DEFINITIONAL_REPRESENTATION('',(#154039),#154043); +#154039 = LINE('',#154040,#154041); +#154040 = CARTESIAN_POINT('',(0.E+000,-2.1)); +#154041 = VECTOR('',#154042,1.); +#154042 = DIRECTION('',(-1.,0.E+000)); +#154043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154044 = PCURVE('',#154045,#154050); +#154045 = PLANE('',#154046); +#154046 = AXIS2_PLACEMENT_3D('',#154047,#154048,#154049); +#154047 = CARTESIAN_POINT('',(-0.641566016369,5.E-002,-1.05)); +#154048 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154049 = DIRECTION('',(1.,0.E+000,0.E+000)); +#154050 = DEFINITIONAL_REPRESENTATION('',(#154051),#154055); +#154051 = LINE('',#154052,#154053); +#154052 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); +#154053 = VECTOR('',#154054,1.); +#154054 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#154055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154056 = ORIENTED_EDGE('',*,*,#154057,.F.); +#154057 = EDGE_CURVE('',#153643,#154030,#154058,.T.); +#154058 = SURFACE_CURVE('',#154059,(#154063,#154070),.PCURVE_S1.); +#154059 = LINE('',#154060,#154061); +#154060 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#154061 = VECTOR('',#154062,1.); +#154062 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154063 = PCURVE('',#153651,#154064); +#154064 = DEFINITIONAL_REPRESENTATION('',(#154065),#154069); +#154065 = LINE('',#154066,#154067); +#154066 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); +#154067 = VECTOR('',#154068,1.); +#154068 = DIRECTION('',(0.E+000,-1.)); +#154069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154070 = PCURVE('',#153747,#154071); +#154071 = DEFINITIONAL_REPRESENTATION('',(#154072),#154076); +#154072 = LINE('',#154073,#154074); +#154073 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154074 = VECTOR('',#154075,1.); +#154075 = DIRECTION('',(0.E+000,-1.)); +#154076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154077 = ADVANCED_FACE('',(#154078),#154092,.F.); +#154078 = FACE_BOUND('',#154079,.T.); +#154079 = EDGE_LOOP('',(#154080,#154115,#154143,#154166,#154189,#154212, + #154235,#154263,#154291,#154319,#154342,#154370)); +#154080 = ORIENTED_EDGE('',*,*,#154081,.F.); +#154081 = EDGE_CURVE('',#154082,#154084,#154086,.T.); +#154082 = VERTEX_POINT('',#154083); +#154083 = CARTESIAN_POINT('',(0.575,0.68333334,-0.825)); +#154084 = VERTEX_POINT('',#154085); +#154085 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); +#154086 = SURFACE_CURVE('',#154087,(#154091,#154103),.PCURVE_S1.); +#154087 = LINE('',#154088,#154089); +#154088 = CARTESIAN_POINT('',(0.541716992867,1.,-0.825)); +#154089 = VECTOR('',#154090,1.); +#154090 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); +#154091 = PCURVE('',#154092,#154097); +#154092 = PLANE('',#154093); +#154093 = AXIS2_PLACEMENT_3D('',#154094,#154095,#154096); +#154094 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); +#154095 = DIRECTION('',(-0.994521895368,-0.104528463268,0.E+000)); +#154096 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); +#154097 = DEFINITIONAL_REPRESENTATION('',(#154098),#154102); +#154098 = LINE('',#154099,#154100); +#154099 = CARTESIAN_POINT('',(0.E+000,-1.875)); +#154100 = VECTOR('',#154101,1.); +#154101 = DIRECTION('',(-1.,0.E+000)); +#154102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154103 = PCURVE('',#154104,#154109); +#154104 = PLANE('',#154105); +#154105 = AXIS2_PLACEMENT_3D('',#154106,#154107,#154108); +#154106 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); +#154107 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154108 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154109 = DEFINITIONAL_REPRESENTATION('',(#154110),#154114); +#154110 = LINE('',#154111,#154112); +#154111 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); +#154112 = VECTOR('',#154113,1.); +#154113 = DIRECTION('',(0.104528463268,-0.994521895368)); +#154114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154115 = ORIENTED_EDGE('',*,*,#154116,.T.); +#154116 = EDGE_CURVE('',#154082,#154117,#154119,.T.); +#154117 = VERTEX_POINT('',#154118); +#154118 = CARTESIAN_POINT('',(0.575,0.68333334,-1.05)); +#154119 = SURFACE_CURVE('',#154120,(#154124,#154131),.PCURVE_S1.); +#154120 = LINE('',#154121,#154122); +#154121 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154122 = VECTOR('',#154123,1.); +#154123 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154124 = PCURVE('',#154092,#154125); +#154125 = DEFINITIONAL_REPRESENTATION('',(#154126),#154130); +#154126 = LINE('',#154127,#154128); +#154127 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); +#154128 = VECTOR('',#154129,1.); +#154129 = DIRECTION('',(0.E+000,-1.)); +#154130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154131 = PCURVE('',#154132,#154137); +#154132 = PLANE('',#154133); +#154133 = AXIS2_PLACEMENT_3D('',#154134,#154135,#154136); +#154134 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154135 = DIRECTION('',(-0.998629534755,5.233595624294E-002,0.E+000)); +#154136 = DIRECTION('',(-5.233595624294E-002,-0.998629534755,0.E+000)); +#154137 = DEFINITIONAL_REPRESENTATION('',(#154138),#154142); +#154138 = LINE('',#154139,#154140); +#154139 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154140 = VECTOR('',#154141,1.); +#154141 = DIRECTION('',(0.E+000,-1.)); +#154142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154143 = ORIENTED_EDGE('',*,*,#154144,.T.); +#154144 = EDGE_CURVE('',#154117,#154145,#154147,.T.); +#154145 = VERTEX_POINT('',#154146); +#154146 = CARTESIAN_POINT('',(0.541716992867,1.,-1.05)); +#154147 = SURFACE_CURVE('',#154148,(#154152,#154159),.PCURVE_S1.); +#154148 = LINE('',#154149,#154150); +#154149 = CARTESIAN_POINT('',(0.541716992867,1.,-1.05)); +#154150 = VECTOR('',#154151,1.); +#154151 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); +#154152 = PCURVE('',#154092,#154153); +#154153 = DEFINITIONAL_REPRESENTATION('',(#154154),#154158); +#154154 = LINE('',#154155,#154156); +#154155 = CARTESIAN_POINT('',(0.E+000,-2.1)); +#154156 = VECTOR('',#154157,1.); +#154157 = DIRECTION('',(-1.,0.E+000)); +#154158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154159 = PCURVE('',#154045,#154160); +#154160 = DEFINITIONAL_REPRESENTATION('',(#154161),#154165); +#154161 = LINE('',#154162,#154163); +#154162 = CARTESIAN_POINT('',(1.183283009236,0.95)); +#154163 = VECTOR('',#154164,1.); +#154164 = DIRECTION('',(-0.104528463268,0.994521895368)); +#154165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154166 = ORIENTED_EDGE('',*,*,#154167,.F.); +#154167 = EDGE_CURVE('',#154168,#154145,#154170,.T.); +#154168 = VERTEX_POINT('',#154169); +#154169 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); +#154170 = SURFACE_CURVE('',#154171,(#154175,#154182),.PCURVE_S1.); +#154171 = LINE('',#154172,#154173); +#154172 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); +#154173 = VECTOR('',#154174,1.); +#154174 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154175 = PCURVE('',#154092,#154176); +#154176 = DEFINITIONAL_REPRESENTATION('',(#154177),#154181); +#154177 = LINE('',#154178,#154179); +#154178 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154179 = VECTOR('',#154180,1.); +#154180 = DIRECTION('',(0.E+000,-1.)); +#154181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154182 = PCURVE('',#154017,#154183); +#154183 = DEFINITIONAL_REPRESENTATION('',(#154184),#154188); +#154184 = LINE('',#154185,#154186); +#154185 = CARTESIAN_POINT('',(0.E+000,1.083433985733)); +#154186 = VECTOR('',#154187,1.); +#154187 = DIRECTION('',(1.,0.E+000)); +#154188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154189 = ORIENTED_EDGE('',*,*,#154190,.F.); +#154190 = EDGE_CURVE('',#154191,#154168,#154193,.T.); +#154191 = VERTEX_POINT('',#154192); +#154192 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154193 = SURFACE_CURVE('',#154194,(#154198,#154205),.PCURVE_S1.); +#154194 = LINE('',#154195,#154196); +#154195 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); +#154196 = VECTOR('',#154197,1.); +#154197 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); +#154198 = PCURVE('',#154092,#154199); +#154199 = DEFINITIONAL_REPRESENTATION('',(#154200),#154204); +#154200 = LINE('',#154201,#154202); +#154201 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154202 = VECTOR('',#154203,1.); +#154203 = DIRECTION('',(-1.,0.E+000)); +#154204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154205 = PCURVE('',#153989,#154206); +#154206 = DEFINITIONAL_REPRESENTATION('',(#154207),#154211); +#154207 = LINE('',#154208,#154209); +#154208 = CARTESIAN_POINT('',(1.183283009236,0.95)); +#154209 = VECTOR('',#154210,1.); +#154210 = DIRECTION('',(-0.104528463268,0.994521895368)); +#154211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154212 = ORIENTED_EDGE('',*,*,#154213,.T.); +#154213 = EDGE_CURVE('',#154191,#154214,#154216,.T.); +#154214 = VERTEX_POINT('',#154215); +#154215 = CARTESIAN_POINT('',(0.575,0.68333334,0.825)); +#154216 = SURFACE_CURVE('',#154217,(#154221,#154228),.PCURVE_S1.); +#154217 = LINE('',#154218,#154219); +#154218 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154219 = VECTOR('',#154220,1.); +#154220 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154221 = PCURVE('',#154092,#154222); +#154222 = DEFINITIONAL_REPRESENTATION('',(#154223),#154227); +#154223 = LINE('',#154224,#154225); +#154224 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); +#154225 = VECTOR('',#154226,1.); +#154226 = DIRECTION('',(0.E+000,-1.)); +#154227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154228 = PCURVE('',#154132,#154229); +#154229 = DEFINITIONAL_REPRESENTATION('',(#154230),#154234); +#154230 = LINE('',#154231,#154232); +#154231 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154232 = VECTOR('',#154233,1.); +#154233 = DIRECTION('',(0.E+000,-1.)); +#154234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154235 = ORIENTED_EDGE('',*,*,#154236,.F.); +#154236 = EDGE_CURVE('',#154237,#154214,#154239,.T.); +#154237 = VERTEX_POINT('',#154238); +#154238 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); +#154239 = SURFACE_CURVE('',#154240,(#154244,#154251),.PCURVE_S1.); +#154240 = LINE('',#154241,#154242); +#154241 = CARTESIAN_POINT('',(0.541716992867,1.,0.825)); +#154242 = VECTOR('',#154243,1.); +#154243 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); +#154244 = PCURVE('',#154092,#154245); +#154245 = DEFINITIONAL_REPRESENTATION('',(#154246),#154250); +#154246 = LINE('',#154247,#154248); +#154247 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#154248 = VECTOR('',#154249,1.); +#154249 = DIRECTION('',(1.,0.E+000)); +#154250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154251 = PCURVE('',#154252,#154257); +#154252 = PLANE('',#154253); +#154253 = AXIS2_PLACEMENT_3D('',#154254,#154255,#154256); +#154254 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); +#154255 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154256 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154257 = DEFINITIONAL_REPRESENTATION('',(#154258),#154262); +#154258 = LINE('',#154259,#154260); +#154259 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); +#154260 = VECTOR('',#154261,1.); +#154261 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#154262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154263 = ORIENTED_EDGE('',*,*,#154264,.T.); +#154264 = EDGE_CURVE('',#154237,#154265,#154267,.T.); +#154265 = VERTEX_POINT('',#154266); +#154266 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.475)); +#154267 = SURFACE_CURVE('',#154268,(#154272,#154279),.PCURVE_S1.); +#154268 = LINE('',#154269,#154270); +#154269 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); +#154270 = VECTOR('',#154271,1.); +#154271 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154272 = PCURVE('',#154092,#154273); +#154273 = DEFINITIONAL_REPRESENTATION('',(#154274),#154278); +#154274 = LINE('',#154275,#154276); +#154275 = CARTESIAN_POINT('',(0.302322816019,-0.225)); +#154276 = VECTOR('',#154277,1.); +#154277 = DIRECTION('',(0.E+000,-1.)); +#154278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154279 = PCURVE('',#154280,#154285); +#154280 = PLANE('',#154281); +#154281 = AXIS2_PLACEMENT_3D('',#154282,#154283,#154284); +#154282 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); +#154283 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#154284 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154285 = DEFINITIONAL_REPRESENTATION('',(#154286),#154290); +#154286 = LINE('',#154287,#154288); +#154287 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154288 = VECTOR('',#154289,1.); +#154289 = DIRECTION('',(1.,0.E+000)); +#154290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154291 = ORIENTED_EDGE('',*,*,#154292,.T.); +#154292 = EDGE_CURVE('',#154265,#154293,#154295,.T.); +#154293 = VERTEX_POINT('',#154294); +#154294 = CARTESIAN_POINT('',(0.575,0.68333334,0.475)); +#154295 = SURFACE_CURVE('',#154296,(#154300,#154307),.PCURVE_S1.); +#154296 = LINE('',#154297,#154298); +#154297 = CARTESIAN_POINT('',(0.541716992867,1.,0.475)); +#154298 = VECTOR('',#154299,1.); +#154299 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); +#154300 = PCURVE('',#154092,#154301); +#154301 = DEFINITIONAL_REPRESENTATION('',(#154302),#154306); +#154302 = LINE('',#154303,#154304); +#154303 = CARTESIAN_POINT('',(0.E+000,-0.575)); +#154304 = VECTOR('',#154305,1.); +#154305 = DIRECTION('',(1.,0.E+000)); +#154306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154307 = PCURVE('',#154308,#154313); +#154308 = PLANE('',#154309); +#154309 = AXIS2_PLACEMENT_3D('',#154310,#154311,#154312); +#154310 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); +#154311 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154312 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154313 = DEFINITIONAL_REPRESENTATION('',(#154314),#154318); +#154314 = LINE('',#154315,#154316); +#154315 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); +#154316 = VECTOR('',#154317,1.); +#154317 = DIRECTION('',(-0.104528463268,-0.994521895368)); +#154318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154319 = ORIENTED_EDGE('',*,*,#154320,.T.); +#154320 = EDGE_CURVE('',#154293,#154321,#154323,.T.); +#154321 = VERTEX_POINT('',#154322); +#154322 = CARTESIAN_POINT('',(0.575,0.68333334,-0.475)); +#154323 = SURFACE_CURVE('',#154324,(#154328,#154335),.PCURVE_S1.); +#154324 = LINE('',#154325,#154326); +#154325 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154326 = VECTOR('',#154327,1.); +#154327 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154328 = PCURVE('',#154092,#154329); +#154329 = DEFINITIONAL_REPRESENTATION('',(#154330),#154334); +#154330 = LINE('',#154331,#154332); +#154331 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); +#154332 = VECTOR('',#154333,1.); +#154333 = DIRECTION('',(0.E+000,-1.)); +#154334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154335 = PCURVE('',#154132,#154336); +#154336 = DEFINITIONAL_REPRESENTATION('',(#154337),#154341); +#154337 = LINE('',#154338,#154339); +#154338 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154339 = VECTOR('',#154340,1.); +#154340 = DIRECTION('',(0.E+000,-1.)); +#154341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154342 = ORIENTED_EDGE('',*,*,#154343,.T.); +#154343 = EDGE_CURVE('',#154321,#154344,#154346,.T.); +#154344 = VERTEX_POINT('',#154345); +#154345 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.475)); +#154346 = SURFACE_CURVE('',#154347,(#154351,#154358),.PCURVE_S1.); +#154347 = LINE('',#154348,#154349); +#154348 = CARTESIAN_POINT('',(0.541716992867,1.,-0.475)); +#154349 = VECTOR('',#154350,1.); +#154350 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); +#154351 = PCURVE('',#154092,#154352); +#154352 = DEFINITIONAL_REPRESENTATION('',(#154353),#154357); +#154353 = LINE('',#154354,#154355); +#154354 = CARTESIAN_POINT('',(0.E+000,-1.525)); +#154355 = VECTOR('',#154356,1.); +#154356 = DIRECTION('',(-1.,0.E+000)); +#154357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154358 = PCURVE('',#154359,#154364); +#154359 = PLANE('',#154360); +#154360 = AXIS2_PLACEMENT_3D('',#154361,#154362,#154363); +#154361 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); +#154362 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154363 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154364 = DEFINITIONAL_REPRESENTATION('',(#154365),#154369); +#154365 = LINE('',#154366,#154367); +#154366 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); +#154367 = VECTOR('',#154368,1.); +#154368 = DIRECTION('',(0.104528463268,-0.994521895368)); +#154369 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154370 = ORIENTED_EDGE('',*,*,#154371,.F.); +#154371 = EDGE_CURVE('',#154084,#154344,#154372,.T.); +#154372 = SURFACE_CURVE('',#154373,(#154377,#154384),.PCURVE_S1.); +#154373 = LINE('',#154374,#154375); +#154374 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); +#154375 = VECTOR('',#154376,1.); +#154376 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154377 = PCURVE('',#154092,#154378); +#154378 = DEFINITIONAL_REPRESENTATION('',(#154379),#154383); +#154379 = LINE('',#154380,#154381); +#154380 = CARTESIAN_POINT('',(0.302322816019,-1.875)); +#154381 = VECTOR('',#154382,1.); +#154382 = DIRECTION('',(0.E+000,1.)); +#154383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154384 = PCURVE('',#154385,#154390); +#154385 = PLANE('',#154386); +#154386 = AXIS2_PLACEMENT_3D('',#154387,#154388,#154389); +#154387 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); +#154388 = DIRECTION('',(0.E+000,1.,0.E+000)); +#154389 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154390 = DEFINITIONAL_REPRESENTATION('',(#154391),#154395); +#154391 = LINE('',#154392,#154393); +#154392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154393 = VECTOR('',#154394,1.); +#154394 = DIRECTION('',(1.,0.E+000)); +#154395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154396 = ADVANCED_FACE('',(#154397),#153747,.F.); +#154397 = FACE_BOUND('',#154398,.T.); +#154398 = EDGE_LOOP('',(#154399,#154422,#154450,#154471,#154472,#154498, + #154499,#154525,#154526,#154552)); +#154399 = ORIENTED_EDGE('',*,*,#154400,.T.); +#154400 = EDGE_CURVE('',#154030,#154401,#154403,.T.); +#154401 = VERTEX_POINT('',#154402); +#154402 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,-1.05)); +#154403 = SURFACE_CURVE('',#154404,(#154408,#154415),.PCURVE_S1.); +#154404 = LINE('',#154405,#154406); +#154405 = CARTESIAN_POINT('',(-0.575,0.68333334,-1.05)); +#154406 = VECTOR('',#154407,1.); +#154407 = DIRECTION('',(5.233595624294E-002,-0.998629534755,0.E+000)); +#154408 = PCURVE('',#153747,#154409); +#154409 = DEFINITIONAL_REPRESENTATION('',(#154410),#154414); +#154410 = LINE('',#154411,#154412); +#154411 = CARTESIAN_POINT('',(0.E+000,-2.1)); +#154412 = VECTOR('',#154413,1.); +#154413 = DIRECTION('',(-1.,0.E+000)); +#154414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154415 = PCURVE('',#154045,#154416); +#154416 = DEFINITIONAL_REPRESENTATION('',(#154417),#154421); +#154417 = LINE('',#154418,#154419); +#154418 = CARTESIAN_POINT('',(6.656601636895E-002,0.63333334)); +#154419 = VECTOR('',#154420,1.); +#154420 = DIRECTION('',(5.233595624294E-002,-0.998629534755)); +#154421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154422 = ORIENTED_EDGE('',*,*,#154423,.F.); +#154423 = EDGE_CURVE('',#154424,#154401,#154426,.T.); +#154424 = VERTEX_POINT('',#154425); +#154425 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); +#154426 = SURFACE_CURVE('',#154427,(#154431,#154438),.PCURVE_S1.); +#154427 = LINE('',#154428,#154429); +#154428 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); +#154429 = VECTOR('',#154430,1.); +#154430 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154431 = PCURVE('',#153747,#154432); +#154432 = DEFINITIONAL_REPRESENTATION('',(#154433),#154437); +#154433 = LINE('',#154434,#154435); +#154434 = CARTESIAN_POINT('',(-0.634202492474,0.E+000)); +#154435 = VECTOR('',#154436,1.); +#154436 = DIRECTION('',(0.E+000,-1.)); +#154437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154438 = PCURVE('',#154439,#154444); +#154439 = PLANE('',#154440); +#154440 = AXIS2_PLACEMENT_3D('',#154441,#154442,#154443); +#154441 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); +#154442 = DIRECTION('',(0.E+000,1.,0.E+000)); +#154443 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154444 = DEFINITIONAL_REPRESENTATION('',(#154445),#154449); +#154445 = LINE('',#154446,#154447); +#154446 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154447 = VECTOR('',#154448,1.); +#154448 = DIRECTION('',(-1.,0.E+000)); +#154449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154450 = ORIENTED_EDGE('',*,*,#154451,.F.); +#154451 = EDGE_CURVE('',#153951,#154424,#154452,.T.); +#154452 = SURFACE_CURVE('',#154453,(#154457,#154464),.PCURVE_S1.); +#154453 = LINE('',#154454,#154455); +#154454 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#154455 = VECTOR('',#154456,1.); +#154456 = DIRECTION('',(5.233595624294E-002,-0.998629534755,0.E+000)); +#154457 = PCURVE('',#153747,#154458); +#154458 = DEFINITIONAL_REPRESENTATION('',(#154459),#154463); +#154459 = LINE('',#154460,#154461); +#154460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154461 = VECTOR('',#154462,1.); +#154462 = DIRECTION('',(-1.,0.E+000)); +#154463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154464 = PCURVE('',#153989,#154465); +#154465 = DEFINITIONAL_REPRESENTATION('',(#154466),#154470); +#154466 = LINE('',#154467,#154468); +#154467 = CARTESIAN_POINT('',(6.656601636895E-002,0.63333334)); +#154468 = VECTOR('',#154469,1.); +#154469 = DIRECTION('',(5.233595624294E-002,-0.998629534755)); +#154470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154471 = ORIENTED_EDGE('',*,*,#153950,.T.); +#154472 = ORIENTED_EDGE('',*,*,#154473,.T.); +#154473 = EDGE_CURVE('',#153923,#153844,#154474,.T.); +#154474 = SURFACE_CURVE('',#154475,(#154479,#154486),.PCURVE_S1.); +#154475 = LINE('',#154476,#154477); +#154476 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#154477 = VECTOR('',#154478,1.); +#154478 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154479 = PCURVE('',#153747,#154480); +#154480 = DEFINITIONAL_REPRESENTATION('',(#154481),#154485); +#154481 = LINE('',#154482,#154483); +#154482 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154483 = VECTOR('',#154484,1.); +#154484 = DIRECTION('',(0.E+000,-1.)); +#154485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154486 = PCURVE('',#154487,#154492); +#154487 = PLANE('',#154488); +#154488 = AXIS2_PLACEMENT_3D('',#154489,#154490,#154491); +#154489 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.825)); +#154490 = DIRECTION('',(1.07686155438E-015,-1.,0.E+000)); +#154491 = DIRECTION('',(1.,1.07686155438E-015,0.E+000)); +#154492 = DEFINITIONAL_REPRESENTATION('',(#154493),#154497); +#154493 = LINE('',#154494,#154495); +#154494 = CARTESIAN_POINT('',(-1.681667764292E-003,0.225)); +#154495 = VECTOR('',#154496,1.); +#154496 = DIRECTION('',(0.E+000,-1.)); +#154497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154498 = ORIENTED_EDGE('',*,*,#153843,.T.); +#154499 = ORIENTED_EDGE('',*,*,#154500,.T.); +#154500 = EDGE_CURVE('',#153816,#153732,#154501,.T.); +#154501 = SURFACE_CURVE('',#154502,(#154506,#154513),.PCURVE_S1.); +#154502 = LINE('',#154503,#154504); +#154503 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#154504 = VECTOR('',#154505,1.); +#154505 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154506 = PCURVE('',#153747,#154507); +#154507 = DEFINITIONAL_REPRESENTATION('',(#154508),#154512); +#154508 = LINE('',#154509,#154510); +#154509 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154510 = VECTOR('',#154511,1.); +#154511 = DIRECTION('',(0.E+000,-1.)); +#154512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154513 = PCURVE('',#154514,#154519); +#154514 = PLANE('',#154515); +#154515 = AXIS2_PLACEMENT_3D('',#154516,#154517,#154518); +#154516 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.1125)); +#154517 = DIRECTION('',(1.088932886955E-015,1.,0.E+000)); +#154518 = DIRECTION('',(-1.,1.088932886955E-015,0.E+000)); +#154519 = DEFINITIONAL_REPRESENTATION('',(#154520),#154524); +#154520 = LINE('',#154521,#154522); +#154521 = CARTESIAN_POINT('',(1.681667764251E-003,0.9375)); +#154522 = VECTOR('',#154523,1.); +#154523 = DIRECTION('',(0.E+000,-1.)); +#154524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154525 = ORIENTED_EDGE('',*,*,#153731,.T.); +#154526 = ORIENTED_EDGE('',*,*,#154527,.T.); +#154527 = EDGE_CURVE('',#153704,#153643,#154528,.T.); +#154528 = SURFACE_CURVE('',#154529,(#154533,#154540),.PCURVE_S1.); +#154529 = LINE('',#154530,#154531); +#154530 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); +#154531 = VECTOR('',#154532,1.); +#154532 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154533 = PCURVE('',#153747,#154534); +#154534 = DEFINITIONAL_REPRESENTATION('',(#154535),#154539); +#154535 = LINE('',#154536,#154537); +#154536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154537 = VECTOR('',#154538,1.); +#154538 = DIRECTION('',(0.E+000,-1.)); +#154539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154540 = PCURVE('',#154541,#154546); +#154541 = PLANE('',#154542); +#154542 = AXIS2_PLACEMENT_3D('',#154543,#154544,#154545); +#154543 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.825)); +#154544 = DIRECTION('',(-1.07686155438E-015,1.,0.E+000)); +#154545 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); +#154546 = DEFINITIONAL_REPRESENTATION('',(#154547),#154551); +#154547 = LINE('',#154548,#154549); +#154548 = CARTESIAN_POINT('',(1.681667764292E-003,1.875)); +#154549 = VECTOR('',#154550,1.); +#154550 = DIRECTION('',(0.E+000,-1.)); +#154551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154552 = ORIENTED_EDGE('',*,*,#154057,.T.); +#154553 = ADVANCED_FACE('',(#154554),#154439,.F.); +#154554 = FACE_BOUND('',#154555,.T.); +#154555 = EDGE_LOOP('',(#154556,#154579,#154602,#154623)); +#154556 = ORIENTED_EDGE('',*,*,#154557,.T.); +#154557 = EDGE_CURVE('',#154401,#154558,#154560,.T.); +#154558 = VERTEX_POINT('',#154559); +#154559 = CARTESIAN_POINT('',(0.541808406105,5.E-002,-1.05)); +#154560 = SURFACE_CURVE('',#154561,(#154565,#154572),.PCURVE_S1.); +#154561 = LINE('',#154562,#154563); +#154562 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,-1.05)); +#154563 = VECTOR('',#154564,1.); +#154564 = DIRECTION('',(1.,0.E+000,0.E+000)); +#154565 = PCURVE('',#154439,#154566); +#154566 = DEFINITIONAL_REPRESENTATION('',(#154567),#154571); +#154567 = LINE('',#154568,#154569); +#154568 = CARTESIAN_POINT('',(-2.1,0.E+000)); +#154569 = VECTOR('',#154570,1.); +#154570 = DIRECTION('',(0.E+000,1.)); +#154571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154572 = PCURVE('',#154045,#154573); +#154573 = DEFINITIONAL_REPRESENTATION('',(#154574),#154578); +#154574 = LINE('',#154575,#154576); +#154575 = CARTESIAN_POINT('',(9.975761026426E-002,0.E+000)); +#154576 = VECTOR('',#154577,1.); +#154577 = DIRECTION('',(1.,0.E+000)); +#154578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154579 = ORIENTED_EDGE('',*,*,#154580,.F.); +#154580 = EDGE_CURVE('',#154581,#154558,#154583,.T.); +#154581 = VERTEX_POINT('',#154582); +#154582 = CARTESIAN_POINT('',(0.541808406105,5.E-002,1.05)); +#154583 = SURFACE_CURVE('',#154584,(#154588,#154595),.PCURVE_S1.); +#154584 = LINE('',#154585,#154586); +#154585 = CARTESIAN_POINT('',(0.541808406105,5.E-002,1.05)); +#154586 = VECTOR('',#154587,1.); +#154587 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154588 = PCURVE('',#154439,#154589); +#154589 = DEFINITIONAL_REPRESENTATION('',(#154590),#154594); +#154590 = LINE('',#154591,#154592); +#154591 = CARTESIAN_POINT('',(0.E+000,1.083616812209)); +#154592 = VECTOR('',#154593,1.); +#154593 = DIRECTION('',(-1.,0.E+000)); +#154594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154595 = PCURVE('',#154132,#154596); +#154596 = DEFINITIONAL_REPRESENTATION('',(#154597),#154601); +#154597 = LINE('',#154598,#154599); +#154598 = CARTESIAN_POINT('',(0.634202492474,0.E+000)); +#154599 = VECTOR('',#154600,1.); +#154600 = DIRECTION('',(0.E+000,-1.)); +#154601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154602 = ORIENTED_EDGE('',*,*,#154603,.F.); +#154603 = EDGE_CURVE('',#154424,#154581,#154604,.T.); +#154604 = SURFACE_CURVE('',#154605,(#154609,#154616),.PCURVE_S1.); +#154605 = LINE('',#154606,#154607); +#154606 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); +#154607 = VECTOR('',#154608,1.); +#154608 = DIRECTION('',(1.,0.E+000,0.E+000)); +#154609 = PCURVE('',#154439,#154610); +#154610 = DEFINITIONAL_REPRESENTATION('',(#154611),#154615); +#154611 = LINE('',#154612,#154613); +#154612 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154613 = VECTOR('',#154614,1.); +#154614 = DIRECTION('',(0.E+000,1.)); +#154615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154616 = PCURVE('',#153989,#154617); +#154617 = DEFINITIONAL_REPRESENTATION('',(#154618),#154622); +#154618 = LINE('',#154619,#154620); +#154619 = CARTESIAN_POINT('',(9.975761026426E-002,0.E+000)); +#154620 = VECTOR('',#154621,1.); +#154621 = DIRECTION('',(1.,0.E+000)); +#154622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154623 = ORIENTED_EDGE('',*,*,#154423,.T.); +#154624 = ADVANCED_FACE('',(#154625),#154132,.F.); +#154625 = FACE_BOUND('',#154626,.T.); +#154626 = EDGE_LOOP('',(#154627,#154648,#154649,#154675,#154676,#154702, + #154703,#154724)); +#154627 = ORIENTED_EDGE('',*,*,#154628,.T.); +#154628 = EDGE_CURVE('',#154558,#154117,#154629,.T.); +#154629 = SURFACE_CURVE('',#154630,(#154634,#154641),.PCURVE_S1.); +#154630 = LINE('',#154631,#154632); +#154631 = CARTESIAN_POINT('',(0.575,0.68333334,-1.05)); +#154632 = VECTOR('',#154633,1.); +#154633 = DIRECTION('',(5.233595624294E-002,0.998629534755,0.E+000)); +#154634 = PCURVE('',#154132,#154635); +#154635 = DEFINITIONAL_REPRESENTATION('',(#154636),#154640); +#154636 = LINE('',#154637,#154638); +#154637 = CARTESIAN_POINT('',(0.E+000,-2.1)); +#154638 = VECTOR('',#154639,1.); +#154639 = DIRECTION('',(-1.,0.E+000)); +#154640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154641 = PCURVE('',#154045,#154642); +#154642 = DEFINITIONAL_REPRESENTATION('',(#154643),#154647); +#154643 = LINE('',#154644,#154645); +#154644 = CARTESIAN_POINT('',(1.216566016369,0.63333334)); +#154645 = VECTOR('',#154646,1.); +#154646 = DIRECTION('',(5.233595624294E-002,0.998629534755)); +#154647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154648 = ORIENTED_EDGE('',*,*,#154116,.F.); +#154649 = ORIENTED_EDGE('',*,*,#154650,.F.); +#154650 = EDGE_CURVE('',#154321,#154082,#154651,.T.); +#154651 = SURFACE_CURVE('',#154652,(#154656,#154663),.PCURVE_S1.); +#154652 = LINE('',#154653,#154654); +#154653 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154654 = VECTOR('',#154655,1.); +#154655 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154656 = PCURVE('',#154132,#154657); +#154657 = DEFINITIONAL_REPRESENTATION('',(#154658),#154662); +#154658 = LINE('',#154659,#154660); +#154659 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154660 = VECTOR('',#154661,1.); +#154661 = DIRECTION('',(0.E+000,-1.)); +#154662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154663 = PCURVE('',#154664,#154669); +#154664 = PLANE('',#154665); +#154665 = AXIS2_PLACEMENT_3D('',#154666,#154667,#154668); +#154666 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.825)); +#154667 = DIRECTION('',(-1.07686155438E-015,-1.,0.E+000)); +#154668 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); +#154669 = DEFINITIONAL_REPRESENTATION('',(#154670),#154674); +#154670 = LINE('',#154671,#154672); +#154671 = CARTESIAN_POINT('',(1.681667764292E-003,1.875)); +#154672 = VECTOR('',#154673,1.); +#154673 = DIRECTION('',(0.E+000,-1.)); +#154674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154675 = ORIENTED_EDGE('',*,*,#154320,.F.); +#154676 = ORIENTED_EDGE('',*,*,#154677,.F.); +#154677 = EDGE_CURVE('',#154214,#154293,#154678,.T.); +#154678 = SURFACE_CURVE('',#154679,(#154683,#154690),.PCURVE_S1.); +#154679 = LINE('',#154680,#154681); +#154680 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154681 = VECTOR('',#154682,1.); +#154682 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154683 = PCURVE('',#154132,#154684); +#154684 = DEFINITIONAL_REPRESENTATION('',(#154685),#154689); +#154685 = LINE('',#154686,#154687); +#154686 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154687 = VECTOR('',#154688,1.); +#154688 = DIRECTION('',(0.E+000,-1.)); +#154689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154690 = PCURVE('',#154691,#154696); +#154691 = PLANE('',#154692); +#154692 = AXIS2_PLACEMENT_3D('',#154693,#154694,#154695); +#154693 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.825)); +#154694 = DIRECTION('',(1.07686155438E-015,1.,0.E+000)); +#154695 = DIRECTION('',(-1.,1.07686155438E-015,0.E+000)); +#154696 = DEFINITIONAL_REPRESENTATION('',(#154697),#154701); +#154697 = LINE('',#154698,#154699); +#154698 = CARTESIAN_POINT('',(-1.681667764292E-003,0.225)); +#154699 = VECTOR('',#154700,1.); +#154700 = DIRECTION('',(0.E+000,-1.)); +#154701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154702 = ORIENTED_EDGE('',*,*,#154213,.F.); +#154703 = ORIENTED_EDGE('',*,*,#154704,.F.); +#154704 = EDGE_CURVE('',#154581,#154191,#154705,.T.); +#154705 = SURFACE_CURVE('',#154706,(#154710,#154717),.PCURVE_S1.); +#154706 = LINE('',#154707,#154708); +#154707 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); +#154708 = VECTOR('',#154709,1.); +#154709 = DIRECTION('',(5.233595624294E-002,0.998629534755,0.E+000)); +#154710 = PCURVE('',#154132,#154711); +#154711 = DEFINITIONAL_REPRESENTATION('',(#154712),#154716); +#154712 = LINE('',#154713,#154714); +#154713 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154714 = VECTOR('',#154715,1.); +#154715 = DIRECTION('',(-1.,0.E+000)); +#154716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154717 = PCURVE('',#153989,#154718); +#154718 = DEFINITIONAL_REPRESENTATION('',(#154719),#154723); +#154719 = LINE('',#154720,#154721); +#154720 = CARTESIAN_POINT('',(1.216566016369,0.63333334)); +#154721 = VECTOR('',#154722,1.); +#154722 = DIRECTION('',(5.233595624294E-002,0.998629534755)); +#154723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154724 = ORIENTED_EDGE('',*,*,#154580,.T.); +#154725 = ADVANCED_FACE('',(#154726),#154017,.F.); +#154726 = FACE_BOUND('',#154727,.T.); +#154727 = EDGE_LOOP('',(#154728,#154749,#154750,#154771)); +#154728 = ORIENTED_EDGE('',*,*,#154729,.T.); +#154729 = EDGE_CURVE('',#154145,#154002,#154730,.T.); +#154730 = SURFACE_CURVE('',#154731,(#154735,#154742),.PCURVE_S1.); +#154731 = LINE('',#154732,#154733); +#154732 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); +#154733 = VECTOR('',#154734,1.); +#154734 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154735 = PCURVE('',#154017,#154736); +#154736 = DEFINITIONAL_REPRESENTATION('',(#154737),#154741); +#154737 = LINE('',#154738,#154739); +#154738 = CARTESIAN_POINT('',(2.1,0.E+000)); +#154739 = VECTOR('',#154740,1.); +#154740 = DIRECTION('',(0.E+000,-1.)); +#154741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#151466 = PCURVE('',#151355,#151467); -#151467 = DEFINITIONAL_REPRESENTATION('',(#151468),#151472); -#151468 = LINE('',#151469,#151470); -#151469 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151470 = VECTOR('',#151471,1.); -#151471 = DIRECTION('',(0.E+000,-1.)); -#151472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151473 = ORIENTED_EDGE('',*,*,#151474,.T.); -#151474 = EDGE_CURVE('',#151452,#151475,#151477,.T.); -#151475 = VERTEX_POINT('',#151476); -#151476 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.475)); -#151477 = SURFACE_CURVE('',#151478,(#151482,#151489),.PCURVE_S1.); -#151478 = LINE('',#151479,#151480); -#151479 = CARTESIAN_POINT('',(-0.541716992867,1.,0.475)); -#151480 = VECTOR('',#151481,1.); -#151481 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); -#151482 = PCURVE('',#151259,#151483); -#151483 = DEFINITIONAL_REPRESENTATION('',(#151484),#151488); -#151484 = LINE('',#151485,#151486); -#151485 = CARTESIAN_POINT('',(0.E+000,-0.575)); -#151486 = VECTOR('',#151487,1.); -#151487 = DIRECTION('',(1.,0.E+000)); -#151488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151489 = PCURVE('',#151490,#151495); -#151490 = PLANE('',#151491); -#151491 = AXIS2_PLACEMENT_3D('',#151492,#151493,#151494); -#151492 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); -#151493 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151494 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151495 = DEFINITIONAL_REPRESENTATION('',(#151496),#151500); -#151496 = LINE('',#151497,#151498); -#151497 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); -#151498 = VECTOR('',#151499,1.); -#151499 = DIRECTION('',(0.104528463268,-0.994521895368)); -#151500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151501 = ORIENTED_EDGE('',*,*,#151502,.F.); -#151502 = EDGE_CURVE('',#151503,#151475,#151505,.T.); -#151503 = VERTEX_POINT('',#151504); -#151504 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); -#151505 = SURFACE_CURVE('',#151506,(#151510,#151517),.PCURVE_S1.); -#151506 = LINE('',#151507,#151508); -#151507 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); -#151508 = VECTOR('',#151509,1.); -#151509 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151510 = PCURVE('',#151259,#151511); -#151511 = DEFINITIONAL_REPRESENTATION('',(#151512),#151516); -#151512 = LINE('',#151513,#151514); -#151513 = CARTESIAN_POINT('',(-0.302322816019,-0.225)); -#151514 = VECTOR('',#151515,1.); -#151515 = DIRECTION('',(0.E+000,-1.)); -#151516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151517 = PCURVE('',#151518,#151523); -#151518 = PLANE('',#151519); -#151519 = AXIS2_PLACEMENT_3D('',#151520,#151521,#151522); -#151520 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); -#151521 = DIRECTION('',(0.E+000,1.,0.E+000)); -#151522 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151523 = DEFINITIONAL_REPRESENTATION('',(#151524),#151528); -#151524 = LINE('',#151525,#151526); -#151525 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151526 = VECTOR('',#151527,1.); -#151527 = DIRECTION('',(-1.,0.E+000)); -#151528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151529 = ORIENTED_EDGE('',*,*,#151530,.F.); -#151530 = EDGE_CURVE('',#151531,#151503,#151533,.T.); -#151531 = VERTEX_POINT('',#151532); -#151532 = CARTESIAN_POINT('',(-0.575,0.68333334,0.825)); -#151533 = SURFACE_CURVE('',#151534,(#151538,#151545),.PCURVE_S1.); -#151534 = LINE('',#151535,#151536); -#151535 = CARTESIAN_POINT('',(-0.541716992867,1.,0.825)); -#151536 = VECTOR('',#151537,1.); -#151537 = DIRECTION('',(0.104528463268,0.994521895368,0.E+000)); -#151538 = PCURVE('',#151259,#151539); -#151539 = DEFINITIONAL_REPRESENTATION('',(#151540),#151544); -#151540 = LINE('',#151541,#151542); -#151541 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#151542 = VECTOR('',#151543,1.); -#151543 = DIRECTION('',(1.,0.E+000)); -#151544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151545 = PCURVE('',#151546,#151551); -#151546 = PLANE('',#151547); -#151547 = AXIS2_PLACEMENT_3D('',#151548,#151549,#151550); -#151548 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); -#151549 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151551 = DEFINITIONAL_REPRESENTATION('',(#151552),#151556); -#151552 = LINE('',#151553,#151554); -#151553 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); -#151554 = VECTOR('',#151555,1.); -#151555 = DIRECTION('',(0.104528463268,-0.994521895368)); -#151556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151557 = ORIENTED_EDGE('',*,*,#151558,.F.); -#151558 = EDGE_CURVE('',#151559,#151531,#151561,.T.); -#151559 = VERTEX_POINT('',#151560); -#151560 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151561 = SURFACE_CURVE('',#151562,(#151566,#151573),.PCURVE_S1.); -#151562 = LINE('',#151563,#151564); -#151563 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151564 = VECTOR('',#151565,1.); -#151565 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151566 = PCURVE('',#151259,#151567); -#151567 = DEFINITIONAL_REPRESENTATION('',(#151568),#151572); -#151568 = LINE('',#151569,#151570); -#151569 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); -#151570 = VECTOR('',#151571,1.); -#151571 = DIRECTION('',(0.E+000,-1.)); -#151572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151573 = PCURVE('',#151355,#151574); -#151574 = DEFINITIONAL_REPRESENTATION('',(#151575),#151579); -#151575 = LINE('',#151576,#151577); -#151576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151577 = VECTOR('',#151578,1.); -#151578 = DIRECTION('',(0.E+000,-1.)); -#151579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151580 = ORIENTED_EDGE('',*,*,#151581,.F.); -#151581 = EDGE_CURVE('',#151582,#151559,#151584,.T.); -#151582 = VERTEX_POINT('',#151583); -#151583 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#151584 = SURFACE_CURVE('',#151585,(#151589,#151596),.PCURVE_S1.); -#151585 = LINE('',#151586,#151587); -#151586 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#151587 = VECTOR('',#151588,1.); -#151588 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151589 = PCURVE('',#151259,#151590); -#151590 = DEFINITIONAL_REPRESENTATION('',(#151591),#151595); -#151591 = LINE('',#151592,#151593); -#151592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151593 = VECTOR('',#151594,1.); -#151594 = DIRECTION('',(-1.,0.E+000)); -#151595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151596 = PCURVE('',#151597,#151602); -#151597 = PLANE('',#151598); -#151598 = AXIS2_PLACEMENT_3D('',#151599,#151600,#151601); -#151599 = CARTESIAN_POINT('',(-0.641566016369,5.E-002,1.05)); -#151600 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151601 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151602 = DEFINITIONAL_REPRESENTATION('',(#151603),#151607); -#151603 = LINE('',#151604,#151605); -#151604 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); -#151605 = VECTOR('',#151606,1.); -#151606 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151608 = ORIENTED_EDGE('',*,*,#151609,.T.); -#151609 = EDGE_CURVE('',#151582,#151610,#151612,.T.); -#151610 = VERTEX_POINT('',#151611); -#151611 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); -#151612 = SURFACE_CURVE('',#151613,(#151617,#151624),.PCURVE_S1.); -#151613 = LINE('',#151614,#151615); -#151614 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#151615 = VECTOR('',#151616,1.); -#151616 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151617 = PCURVE('',#151259,#151618); -#151618 = DEFINITIONAL_REPRESENTATION('',(#151619),#151623); -#151619 = LINE('',#151620,#151621); -#151620 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151621 = VECTOR('',#151622,1.); -#151622 = DIRECTION('',(0.E+000,-1.)); -#151623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151624 = PCURVE('',#151625,#151630); -#151625 = PLANE('',#151626); -#151626 = AXIS2_PLACEMENT_3D('',#151627,#151628,#151629); -#151627 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#151628 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#151629 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151630 = DEFINITIONAL_REPRESENTATION('',(#151631),#151635); -#151631 = LINE('',#151632,#151633); -#151632 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151633 = VECTOR('',#151634,1.); -#151634 = DIRECTION('',(1.,0.E+000)); -#151635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151636 = ORIENTED_EDGE('',*,*,#151637,.T.); -#151637 = EDGE_CURVE('',#151610,#151638,#151640,.T.); -#151638 = VERTEX_POINT('',#151639); -#151639 = CARTESIAN_POINT('',(-0.575,0.68333334,-1.05)); -#151640 = SURFACE_CURVE('',#151641,(#151645,#151652),.PCURVE_S1.); -#151641 = LINE('',#151642,#151643); -#151642 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); -#151643 = VECTOR('',#151644,1.); -#151644 = DIRECTION('',(-0.104528463268,-0.994521895368,0.E+000)); -#151645 = PCURVE('',#151259,#151646); -#151646 = DEFINITIONAL_REPRESENTATION('',(#151647),#151651); -#151647 = LINE('',#151648,#151649); -#151648 = CARTESIAN_POINT('',(0.E+000,-2.1)); -#151649 = VECTOR('',#151650,1.); -#151650 = DIRECTION('',(-1.,0.E+000)); -#151651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151652 = PCURVE('',#151653,#151658); -#151653 = PLANE('',#151654); -#151654 = AXIS2_PLACEMENT_3D('',#151655,#151656,#151657); -#151655 = CARTESIAN_POINT('',(-0.641566016369,5.E-002,-1.05)); -#151656 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151657 = DIRECTION('',(1.,0.E+000,0.E+000)); -#151658 = DEFINITIONAL_REPRESENTATION('',(#151659),#151663); -#151659 = LINE('',#151660,#151661); -#151660 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); -#151661 = VECTOR('',#151662,1.); -#151662 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151664 = ORIENTED_EDGE('',*,*,#151665,.F.); -#151665 = EDGE_CURVE('',#151251,#151638,#151666,.T.); -#151666 = SURFACE_CURVE('',#151667,(#151671,#151678),.PCURVE_S1.); -#151667 = LINE('',#151668,#151669); -#151668 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#151669 = VECTOR('',#151670,1.); -#151670 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151671 = PCURVE('',#151259,#151672); -#151672 = DEFINITIONAL_REPRESENTATION('',(#151673),#151677); -#151673 = LINE('',#151674,#151675); -#151674 = CARTESIAN_POINT('',(-0.318410948492,0.E+000)); -#151675 = VECTOR('',#151676,1.); -#151676 = DIRECTION('',(0.E+000,-1.)); -#151677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151678 = PCURVE('',#151355,#151679); -#151679 = DEFINITIONAL_REPRESENTATION('',(#151680),#151684); -#151680 = LINE('',#151681,#151682); -#151681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151682 = VECTOR('',#151683,1.); -#151683 = DIRECTION('',(0.E+000,-1.)); -#151684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151685 = ADVANCED_FACE('',(#151686),#151700,.F.); -#151686 = FACE_BOUND('',#151687,.T.); -#151687 = EDGE_LOOP('',(#151688,#151723,#151751,#151774,#151797,#151820, - #151843,#151871,#151899,#151927,#151950,#151978)); -#151688 = ORIENTED_EDGE('',*,*,#151689,.F.); -#151689 = EDGE_CURVE('',#151690,#151692,#151694,.T.); -#151690 = VERTEX_POINT('',#151691); -#151691 = CARTESIAN_POINT('',(0.575,0.68333334,-0.825)); -#151692 = VERTEX_POINT('',#151693); -#151693 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); -#151694 = SURFACE_CURVE('',#151695,(#151699,#151711),.PCURVE_S1.); -#151695 = LINE('',#151696,#151697); -#151696 = CARTESIAN_POINT('',(0.541716992867,1.,-0.825)); -#151697 = VECTOR('',#151698,1.); -#151698 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); -#151699 = PCURVE('',#151700,#151705); -#151700 = PLANE('',#151701); -#151701 = AXIS2_PLACEMENT_3D('',#151702,#151703,#151704); -#151702 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); -#151703 = DIRECTION('',(-0.994521895368,-0.104528463268,0.E+000)); -#151704 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); -#151705 = DEFINITIONAL_REPRESENTATION('',(#151706),#151710); -#151706 = LINE('',#151707,#151708); -#151707 = CARTESIAN_POINT('',(0.E+000,-1.875)); -#151708 = VECTOR('',#151709,1.); -#151709 = DIRECTION('',(-1.,0.E+000)); -#151710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151711 = PCURVE('',#151712,#151717); -#151712 = PLANE('',#151713); -#151713 = AXIS2_PLACEMENT_3D('',#151714,#151715,#151716); -#151714 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); -#151715 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151716 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#151717 = DEFINITIONAL_REPRESENTATION('',(#151718),#151722); -#151718 = LINE('',#151719,#151720); -#151719 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); -#151720 = VECTOR('',#151721,1.); -#151721 = DIRECTION('',(0.104528463268,-0.994521895368)); -#151722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151723 = ORIENTED_EDGE('',*,*,#151724,.T.); -#151724 = EDGE_CURVE('',#151690,#151725,#151727,.T.); -#151725 = VERTEX_POINT('',#151726); -#151726 = CARTESIAN_POINT('',(0.575,0.68333334,-1.05)); -#151727 = SURFACE_CURVE('',#151728,(#151732,#151739),.PCURVE_S1.); -#151728 = LINE('',#151729,#151730); -#151729 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#151730 = VECTOR('',#151731,1.); -#151731 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151732 = PCURVE('',#151700,#151733); -#151733 = DEFINITIONAL_REPRESENTATION('',(#151734),#151738); -#151734 = LINE('',#151735,#151736); -#151735 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); -#151736 = VECTOR('',#151737,1.); -#151737 = DIRECTION('',(0.E+000,-1.)); -#151738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151739 = PCURVE('',#151740,#151745); -#151740 = PLANE('',#151741); -#151741 = AXIS2_PLACEMENT_3D('',#151742,#151743,#151744); -#151742 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#151743 = DIRECTION('',(-0.998629534755,5.233595624294E-002,0.E+000)); -#151744 = DIRECTION('',(-5.233595624294E-002,-0.998629534755,0.E+000)); -#151745 = DEFINITIONAL_REPRESENTATION('',(#151746),#151750); -#151746 = LINE('',#151747,#151748); -#151747 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151748 = VECTOR('',#151749,1.); -#151749 = DIRECTION('',(0.E+000,-1.)); -#151750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151751 = ORIENTED_EDGE('',*,*,#151752,.T.); -#151752 = EDGE_CURVE('',#151725,#151753,#151755,.T.); -#151753 = VERTEX_POINT('',#151754); -#151754 = CARTESIAN_POINT('',(0.541716992867,1.,-1.05)); -#151755 = SURFACE_CURVE('',#151756,(#151760,#151767),.PCURVE_S1.); -#151756 = LINE('',#151757,#151758); -#151757 = CARTESIAN_POINT('',(0.541716992867,1.,-1.05)); -#151758 = VECTOR('',#151759,1.); -#151759 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); -#151760 = PCURVE('',#151700,#151761); -#151761 = DEFINITIONAL_REPRESENTATION('',(#151762),#151766); -#151762 = LINE('',#151763,#151764); -#151763 = CARTESIAN_POINT('',(0.E+000,-2.1)); -#151764 = VECTOR('',#151765,1.); -#151765 = DIRECTION('',(-1.,0.E+000)); -#151766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151767 = PCURVE('',#151653,#151768); -#151768 = DEFINITIONAL_REPRESENTATION('',(#151769),#151773); -#151769 = LINE('',#151770,#151771); -#151770 = CARTESIAN_POINT('',(1.183283009236,0.95)); -#151771 = VECTOR('',#151772,1.); -#151772 = DIRECTION('',(-0.104528463268,0.994521895368)); -#151773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151774 = ORIENTED_EDGE('',*,*,#151775,.F.); -#151775 = EDGE_CURVE('',#151776,#151753,#151778,.T.); -#151776 = VERTEX_POINT('',#151777); -#151777 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); -#151778 = SURFACE_CURVE('',#151779,(#151783,#151790),.PCURVE_S1.); -#151779 = LINE('',#151780,#151781); -#151780 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); -#151781 = VECTOR('',#151782,1.); -#151782 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151783 = PCURVE('',#151700,#151784); -#151784 = DEFINITIONAL_REPRESENTATION('',(#151785),#151789); -#151785 = LINE('',#151786,#151787); -#151786 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151787 = VECTOR('',#151788,1.); -#151788 = DIRECTION('',(0.E+000,-1.)); -#151789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151790 = PCURVE('',#151625,#151791); -#151791 = DEFINITIONAL_REPRESENTATION('',(#151792),#151796); -#151792 = LINE('',#151793,#151794); -#151793 = CARTESIAN_POINT('',(0.E+000,1.083433985733)); -#151794 = VECTOR('',#151795,1.); -#151795 = DIRECTION('',(1.,0.E+000)); -#151796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151797 = ORIENTED_EDGE('',*,*,#151798,.F.); -#151798 = EDGE_CURVE('',#151799,#151776,#151801,.T.); -#151799 = VERTEX_POINT('',#151800); -#151800 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#151801 = SURFACE_CURVE('',#151802,(#151806,#151813),.PCURVE_S1.); -#151802 = LINE('',#151803,#151804); -#151803 = CARTESIAN_POINT('',(0.541716992867,1.,1.05)); -#151804 = VECTOR('',#151805,1.); -#151805 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); -#151806 = PCURVE('',#151700,#151807); -#151807 = DEFINITIONAL_REPRESENTATION('',(#151808),#151812); -#151808 = LINE('',#151809,#151810); -#151809 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151810 = VECTOR('',#151811,1.); -#151811 = DIRECTION('',(-1.,0.E+000)); -#151812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151813 = PCURVE('',#151597,#151814); -#151814 = DEFINITIONAL_REPRESENTATION('',(#151815),#151819); -#151815 = LINE('',#151816,#151817); -#151816 = CARTESIAN_POINT('',(1.183283009236,0.95)); -#151817 = VECTOR('',#151818,1.); -#151818 = DIRECTION('',(-0.104528463268,0.994521895368)); -#151819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151820 = ORIENTED_EDGE('',*,*,#151821,.T.); -#151821 = EDGE_CURVE('',#151799,#151822,#151824,.T.); -#151822 = VERTEX_POINT('',#151823); -#151823 = CARTESIAN_POINT('',(0.575,0.68333334,0.825)); -#151824 = SURFACE_CURVE('',#151825,(#151829,#151836),.PCURVE_S1.); -#151825 = LINE('',#151826,#151827); -#151826 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#151827 = VECTOR('',#151828,1.); -#151828 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151829 = PCURVE('',#151700,#151830); -#151830 = DEFINITIONAL_REPRESENTATION('',(#151831),#151835); -#151831 = LINE('',#151832,#151833); -#151832 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); -#151833 = VECTOR('',#151834,1.); -#151834 = DIRECTION('',(0.E+000,-1.)); -#151835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151836 = PCURVE('',#151740,#151837); -#151837 = DEFINITIONAL_REPRESENTATION('',(#151838),#151842); -#151838 = LINE('',#151839,#151840); -#151839 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151840 = VECTOR('',#151841,1.); -#151841 = DIRECTION('',(0.E+000,-1.)); -#151842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151843 = ORIENTED_EDGE('',*,*,#151844,.F.); -#151844 = EDGE_CURVE('',#151845,#151822,#151847,.T.); -#151845 = VERTEX_POINT('',#151846); -#151846 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); -#151847 = SURFACE_CURVE('',#151848,(#151852,#151859),.PCURVE_S1.); -#151848 = LINE('',#151849,#151850); -#151849 = CARTESIAN_POINT('',(0.541716992867,1.,0.825)); -#151850 = VECTOR('',#151851,1.); -#151851 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); -#151852 = PCURVE('',#151700,#151853); -#151853 = DEFINITIONAL_REPRESENTATION('',(#151854),#151858); -#151854 = LINE('',#151855,#151856); -#151855 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#151856 = VECTOR('',#151857,1.); -#151857 = DIRECTION('',(1.,0.E+000)); -#151858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151859 = PCURVE('',#151860,#151865); -#151860 = PLANE('',#151861); -#151861 = AXIS2_PLACEMENT_3D('',#151862,#151863,#151864); -#151862 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); -#151863 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151864 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#151865 = DEFINITIONAL_REPRESENTATION('',(#151866),#151870); -#151866 = LINE('',#151867,#151868); -#151867 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); -#151868 = VECTOR('',#151869,1.); -#151869 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151871 = ORIENTED_EDGE('',*,*,#151872,.T.); -#151872 = EDGE_CURVE('',#151845,#151873,#151875,.T.); -#151873 = VERTEX_POINT('',#151874); -#151874 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.475)); -#151875 = SURFACE_CURVE('',#151876,(#151880,#151887),.PCURVE_S1.); -#151876 = LINE('',#151877,#151878); -#151877 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); -#151878 = VECTOR('',#151879,1.); -#151879 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151880 = PCURVE('',#151700,#151881); -#151881 = DEFINITIONAL_REPRESENTATION('',(#151882),#151886); -#151882 = LINE('',#151883,#151884); -#151883 = CARTESIAN_POINT('',(0.302322816019,-0.225)); -#151884 = VECTOR('',#151885,1.); -#151885 = DIRECTION('',(0.E+000,-1.)); -#151886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151887 = PCURVE('',#151888,#151893); -#151888 = PLANE('',#151889); -#151889 = AXIS2_PLACEMENT_3D('',#151890,#151891,#151892); -#151890 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); -#151891 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#151892 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151893 = DEFINITIONAL_REPRESENTATION('',(#151894),#151898); -#151894 = LINE('',#151895,#151896); -#151895 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151896 = VECTOR('',#151897,1.); -#151897 = DIRECTION('',(1.,0.E+000)); -#151898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151899 = ORIENTED_EDGE('',*,*,#151900,.T.); -#151900 = EDGE_CURVE('',#151873,#151901,#151903,.T.); -#151901 = VERTEX_POINT('',#151902); -#151902 = CARTESIAN_POINT('',(0.575,0.68333334,0.475)); -#151903 = SURFACE_CURVE('',#151904,(#151908,#151915),.PCURVE_S1.); -#151904 = LINE('',#151905,#151906); -#151905 = CARTESIAN_POINT('',(0.541716992867,1.,0.475)); -#151906 = VECTOR('',#151907,1.); -#151907 = DIRECTION('',(0.104528463268,-0.994521895368,0.E+000)); -#151908 = PCURVE('',#151700,#151909); -#151909 = DEFINITIONAL_REPRESENTATION('',(#151910),#151914); -#151910 = LINE('',#151911,#151912); -#151911 = CARTESIAN_POINT('',(0.E+000,-0.575)); -#151912 = VECTOR('',#151913,1.); -#151913 = DIRECTION('',(1.,0.E+000)); -#151914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151915 = PCURVE('',#151916,#151921); -#151916 = PLANE('',#151917); -#151917 = AXIS2_PLACEMENT_3D('',#151918,#151919,#151920); -#151918 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); -#151919 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151920 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#151921 = DEFINITIONAL_REPRESENTATION('',(#151922),#151926); -#151922 = LINE('',#151923,#151924); -#151923 = CARTESIAN_POINT('',(0.132283007136,0.33266666)); -#151924 = VECTOR('',#151925,1.); -#151925 = DIRECTION('',(-0.104528463268,-0.994521895368)); -#151926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151927 = ORIENTED_EDGE('',*,*,#151928,.T.); -#151928 = EDGE_CURVE('',#151901,#151929,#151931,.T.); -#151929 = VERTEX_POINT('',#151930); -#151930 = CARTESIAN_POINT('',(0.575,0.68333334,-0.475)); -#151931 = SURFACE_CURVE('',#151932,(#151936,#151943),.PCURVE_S1.); -#151932 = LINE('',#151933,#151934); -#151933 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#151934 = VECTOR('',#151935,1.); -#151935 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#151936 = PCURVE('',#151700,#151937); -#151937 = DEFINITIONAL_REPRESENTATION('',(#151938),#151942); -#151938 = LINE('',#151939,#151940); -#151939 = CARTESIAN_POINT('',(0.318410948492,0.E+000)); -#151940 = VECTOR('',#151941,1.); -#151941 = DIRECTION('',(0.E+000,-1.)); -#151942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151943 = PCURVE('',#151740,#151944); -#151944 = DEFINITIONAL_REPRESENTATION('',(#151945),#151949); -#151945 = LINE('',#151946,#151947); -#151946 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#151947 = VECTOR('',#151948,1.); -#151948 = DIRECTION('',(0.E+000,-1.)); -#151949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151950 = ORIENTED_EDGE('',*,*,#151951,.T.); -#151951 = EDGE_CURVE('',#151929,#151952,#151954,.T.); -#151952 = VERTEX_POINT('',#151953); -#151953 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.475)); -#151954 = SURFACE_CURVE('',#151955,(#151959,#151966),.PCURVE_S1.); -#151955 = LINE('',#151956,#151957); -#151956 = CARTESIAN_POINT('',(0.541716992867,1.,-0.475)); -#151957 = VECTOR('',#151958,1.); -#151958 = DIRECTION('',(-0.104528463268,0.994521895368,0.E+000)); -#151959 = PCURVE('',#151700,#151960); -#151960 = DEFINITIONAL_REPRESENTATION('',(#151961),#151965); -#151961 = LINE('',#151962,#151963); -#151962 = CARTESIAN_POINT('',(0.E+000,-1.525)); -#151963 = VECTOR('',#151964,1.); -#151964 = DIRECTION('',(-1.,0.E+000)); -#151965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151966 = PCURVE('',#151967,#151972); -#151967 = PLANE('',#151968); -#151968 = AXIS2_PLACEMENT_3D('',#151969,#151970,#151971); -#151969 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); -#151970 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151971 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#151972 = DEFINITIONAL_REPRESENTATION('',(#151973),#151977); -#151973 = LINE('',#151974,#151975); -#151974 = CARTESIAN_POINT('',(0.132283007136,-0.33266666)); -#151975 = VECTOR('',#151976,1.); -#151976 = DIRECTION('',(0.104528463268,-0.994521895368)); -#151977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151978 = ORIENTED_EDGE('',*,*,#151979,.F.); -#151979 = EDGE_CURVE('',#151692,#151952,#151980,.T.); -#151980 = SURFACE_CURVE('',#151981,(#151985,#151992),.PCURVE_S1.); -#151981 = LINE('',#151982,#151983); -#151982 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); -#151983 = VECTOR('',#151984,1.); -#151984 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151985 = PCURVE('',#151700,#151986); -#151986 = DEFINITIONAL_REPRESENTATION('',(#151987),#151991); -#151987 = LINE('',#151988,#151989); -#151988 = CARTESIAN_POINT('',(0.302322816019,-1.875)); -#151989 = VECTOR('',#151990,1.); -#151990 = DIRECTION('',(0.E+000,1.)); -#151991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#151992 = PCURVE('',#151993,#151998); -#151993 = PLANE('',#151994); -#151994 = AXIS2_PLACEMENT_3D('',#151995,#151996,#151997); -#151995 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); -#151996 = DIRECTION('',(0.E+000,1.,0.E+000)); -#151997 = DIRECTION('',(0.E+000,0.E+000,1.)); -#151998 = DEFINITIONAL_REPRESENTATION('',(#151999),#152003); -#151999 = LINE('',#152000,#152001); -#152000 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152001 = VECTOR('',#152002,1.); -#152002 = DIRECTION('',(1.,0.E+000)); -#152003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152004 = ADVANCED_FACE('',(#152005),#151355,.F.); -#152005 = FACE_BOUND('',#152006,.T.); -#152006 = EDGE_LOOP('',(#152007,#152030,#152058,#152079,#152080,#152106, - #152107,#152133,#152134,#152160)); -#152007 = ORIENTED_EDGE('',*,*,#152008,.T.); -#152008 = EDGE_CURVE('',#151638,#152009,#152011,.T.); -#152009 = VERTEX_POINT('',#152010); -#152010 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,-1.05)); -#152011 = SURFACE_CURVE('',#152012,(#152016,#152023),.PCURVE_S1.); -#152012 = LINE('',#152013,#152014); -#152013 = CARTESIAN_POINT('',(-0.575,0.68333334,-1.05)); -#152014 = VECTOR('',#152015,1.); -#152015 = DIRECTION('',(5.233595624294E-002,-0.998629534755,0.E+000)); -#152016 = PCURVE('',#151355,#152017); -#152017 = DEFINITIONAL_REPRESENTATION('',(#152018),#152022); -#152018 = LINE('',#152019,#152020); -#152019 = CARTESIAN_POINT('',(0.E+000,-2.1)); -#152020 = VECTOR('',#152021,1.); -#152021 = DIRECTION('',(-1.,0.E+000)); -#152022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152023 = PCURVE('',#151653,#152024); -#152024 = DEFINITIONAL_REPRESENTATION('',(#152025),#152029); -#152025 = LINE('',#152026,#152027); -#152026 = CARTESIAN_POINT('',(6.656601636895E-002,0.63333334)); -#152027 = VECTOR('',#152028,1.); -#152028 = DIRECTION('',(5.233595624294E-002,-0.998629534755)); -#152029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152030 = ORIENTED_EDGE('',*,*,#152031,.F.); -#152031 = EDGE_CURVE('',#152032,#152009,#152034,.T.); -#152032 = VERTEX_POINT('',#152033); -#152033 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); -#152034 = SURFACE_CURVE('',#152035,(#152039,#152046),.PCURVE_S1.); -#152035 = LINE('',#152036,#152037); -#152036 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); -#152037 = VECTOR('',#152038,1.); -#152038 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152039 = PCURVE('',#151355,#152040); -#152040 = DEFINITIONAL_REPRESENTATION('',(#152041),#152045); -#152041 = LINE('',#152042,#152043); -#152042 = CARTESIAN_POINT('',(-0.634202492474,0.E+000)); -#152043 = VECTOR('',#152044,1.); -#152044 = DIRECTION('',(0.E+000,-1.)); -#152045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152046 = PCURVE('',#152047,#152052); -#152047 = PLANE('',#152048); -#152048 = AXIS2_PLACEMENT_3D('',#152049,#152050,#152051); -#152049 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); -#152050 = DIRECTION('',(0.E+000,1.,0.E+000)); -#152051 = DIRECTION('',(0.E+000,0.E+000,1.)); -#152052 = DEFINITIONAL_REPRESENTATION('',(#152053),#152057); -#152053 = LINE('',#152054,#152055); -#152054 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152055 = VECTOR('',#152056,1.); -#152056 = DIRECTION('',(-1.,0.E+000)); -#152057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152058 = ORIENTED_EDGE('',*,*,#152059,.F.); -#152059 = EDGE_CURVE('',#151559,#152032,#152060,.T.); -#152060 = SURFACE_CURVE('',#152061,(#152065,#152072),.PCURVE_S1.); -#152061 = LINE('',#152062,#152063); -#152062 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#152063 = VECTOR('',#152064,1.); -#152064 = DIRECTION('',(5.233595624294E-002,-0.998629534755,0.E+000)); -#152065 = PCURVE('',#151355,#152066); -#152066 = DEFINITIONAL_REPRESENTATION('',(#152067),#152071); -#152067 = LINE('',#152068,#152069); -#152068 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152069 = VECTOR('',#152070,1.); -#152070 = DIRECTION('',(-1.,0.E+000)); -#152071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152072 = PCURVE('',#151597,#152073); -#152073 = DEFINITIONAL_REPRESENTATION('',(#152074),#152078); -#152074 = LINE('',#152075,#152076); -#152075 = CARTESIAN_POINT('',(6.656601636895E-002,0.63333334)); -#152076 = VECTOR('',#152077,1.); -#152077 = DIRECTION('',(5.233595624294E-002,-0.998629534755)); -#152078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152079 = ORIENTED_EDGE('',*,*,#151558,.T.); -#152080 = ORIENTED_EDGE('',*,*,#152081,.T.); -#152081 = EDGE_CURVE('',#151531,#151452,#152082,.T.); -#152082 = SURFACE_CURVE('',#152083,(#152087,#152094),.PCURVE_S1.); -#152083 = LINE('',#152084,#152085); -#152084 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#152085 = VECTOR('',#152086,1.); -#152086 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152087 = PCURVE('',#151355,#152088); -#152088 = DEFINITIONAL_REPRESENTATION('',(#152089),#152093); -#152089 = LINE('',#152090,#152091); -#152090 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152091 = VECTOR('',#152092,1.); -#152092 = DIRECTION('',(0.E+000,-1.)); -#152093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152094 = PCURVE('',#152095,#152100); -#152095 = PLANE('',#152096); -#152096 = AXIS2_PLACEMENT_3D('',#152097,#152098,#152099); -#152097 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.825)); -#152098 = DIRECTION('',(1.07686155438E-015,-1.,0.E+000)); -#152099 = DIRECTION('',(1.,1.07686155438E-015,0.E+000)); -#152100 = DEFINITIONAL_REPRESENTATION('',(#152101),#152105); -#152101 = LINE('',#152102,#152103); -#152102 = CARTESIAN_POINT('',(-1.681667764292E-003,0.225)); -#152103 = VECTOR('',#152104,1.); -#152104 = DIRECTION('',(0.E+000,-1.)); -#152105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152106 = ORIENTED_EDGE('',*,*,#151451,.T.); -#152107 = ORIENTED_EDGE('',*,*,#152108,.T.); -#152108 = EDGE_CURVE('',#151424,#151340,#152109,.T.); -#152109 = SURFACE_CURVE('',#152110,(#152114,#152121),.PCURVE_S1.); -#152110 = LINE('',#152111,#152112); -#152111 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#152112 = VECTOR('',#152113,1.); -#152113 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152114 = PCURVE('',#151355,#152115); -#152115 = DEFINITIONAL_REPRESENTATION('',(#152116),#152120); -#152116 = LINE('',#152117,#152118); -#152117 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152118 = VECTOR('',#152119,1.); -#152119 = DIRECTION('',(0.E+000,-1.)); -#152120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152121 = PCURVE('',#152122,#152127); -#152122 = PLANE('',#152123); -#152123 = AXIS2_PLACEMENT_3D('',#152124,#152125,#152126); -#152124 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.1125)); -#152125 = DIRECTION('',(1.088932886955E-015,1.,0.E+000)); -#152126 = DIRECTION('',(-1.,1.088932886955E-015,0.E+000)); -#152127 = DEFINITIONAL_REPRESENTATION('',(#152128),#152132); -#152128 = LINE('',#152129,#152130); -#152129 = CARTESIAN_POINT('',(1.681667764251E-003,0.9375)); -#152130 = VECTOR('',#152131,1.); -#152131 = DIRECTION('',(0.E+000,-1.)); -#152132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152133 = ORIENTED_EDGE('',*,*,#151339,.T.); -#152134 = ORIENTED_EDGE('',*,*,#152135,.T.); -#152135 = EDGE_CURVE('',#151312,#151251,#152136,.T.); -#152136 = SURFACE_CURVE('',#152137,(#152141,#152148),.PCURVE_S1.); -#152137 = LINE('',#152138,#152139); -#152138 = CARTESIAN_POINT('',(-0.575,0.68333334,1.05)); -#152139 = VECTOR('',#152140,1.); -#152140 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152141 = PCURVE('',#151355,#152142); -#152142 = DEFINITIONAL_REPRESENTATION('',(#152143),#152147); -#152143 = LINE('',#152144,#152145); -#152144 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152145 = VECTOR('',#152146,1.); -#152146 = DIRECTION('',(0.E+000,-1.)); -#152147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152148 = PCURVE('',#152149,#152154); -#152149 = PLANE('',#152150); -#152150 = AXIS2_PLACEMENT_3D('',#152151,#152152,#152153); -#152151 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.825)); -#152152 = DIRECTION('',(-1.07686155438E-015,1.,0.E+000)); -#152153 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); -#152154 = DEFINITIONAL_REPRESENTATION('',(#152155),#152159); -#152155 = LINE('',#152156,#152157); -#152156 = CARTESIAN_POINT('',(1.681667764292E-003,1.875)); -#152157 = VECTOR('',#152158,1.); -#152158 = DIRECTION('',(0.E+000,-1.)); -#152159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152160 = ORIENTED_EDGE('',*,*,#151665,.T.); -#152161 = ADVANCED_FACE('',(#152162),#152047,.F.); -#152162 = FACE_BOUND('',#152163,.T.); -#152163 = EDGE_LOOP('',(#152164,#152187,#152210,#152231)); -#152164 = ORIENTED_EDGE('',*,*,#152165,.T.); -#152165 = EDGE_CURVE('',#152009,#152166,#152168,.T.); -#152166 = VERTEX_POINT('',#152167); -#152167 = CARTESIAN_POINT('',(0.541808406105,5.E-002,-1.05)); -#152168 = SURFACE_CURVE('',#152169,(#152173,#152180),.PCURVE_S1.); -#152169 = LINE('',#152170,#152171); -#152170 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,-1.05)); -#152171 = VECTOR('',#152172,1.); -#152172 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152173 = PCURVE('',#152047,#152174); -#152174 = DEFINITIONAL_REPRESENTATION('',(#152175),#152179); -#152175 = LINE('',#152176,#152177); -#152176 = CARTESIAN_POINT('',(-2.1,0.E+000)); -#152177 = VECTOR('',#152178,1.); -#152178 = DIRECTION('',(0.E+000,1.)); -#152179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152180 = PCURVE('',#151653,#152181); -#152181 = DEFINITIONAL_REPRESENTATION('',(#152182),#152186); -#152182 = LINE('',#152183,#152184); -#152183 = CARTESIAN_POINT('',(9.975761026426E-002,0.E+000)); -#152184 = VECTOR('',#152185,1.); -#152185 = DIRECTION('',(1.,0.E+000)); -#152186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152187 = ORIENTED_EDGE('',*,*,#152188,.F.); -#152188 = EDGE_CURVE('',#152189,#152166,#152191,.T.); -#152189 = VERTEX_POINT('',#152190); -#152190 = CARTESIAN_POINT('',(0.541808406105,5.E-002,1.05)); -#152191 = SURFACE_CURVE('',#152192,(#152196,#152203),.PCURVE_S1.); -#152192 = LINE('',#152193,#152194); -#152193 = CARTESIAN_POINT('',(0.541808406105,5.E-002,1.05)); -#152194 = VECTOR('',#152195,1.); -#152195 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152196 = PCURVE('',#152047,#152197); -#152197 = DEFINITIONAL_REPRESENTATION('',(#152198),#152202); -#152198 = LINE('',#152199,#152200); -#152199 = CARTESIAN_POINT('',(0.E+000,1.083616812209)); -#152200 = VECTOR('',#152201,1.); -#152201 = DIRECTION('',(-1.,0.E+000)); -#152202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152203 = PCURVE('',#151740,#152204); -#152204 = DEFINITIONAL_REPRESENTATION('',(#152205),#152209); -#152205 = LINE('',#152206,#152207); -#152206 = CARTESIAN_POINT('',(0.634202492474,0.E+000)); -#152207 = VECTOR('',#152208,1.); -#152208 = DIRECTION('',(0.E+000,-1.)); -#152209 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152210 = ORIENTED_EDGE('',*,*,#152211,.F.); -#152211 = EDGE_CURVE('',#152032,#152189,#152212,.T.); -#152212 = SURFACE_CURVE('',#152213,(#152217,#152224),.PCURVE_S1.); -#152213 = LINE('',#152214,#152215); -#152214 = CARTESIAN_POINT('',(-0.541808406105,5.E-002,1.05)); -#152215 = VECTOR('',#152216,1.); -#152216 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152217 = PCURVE('',#152047,#152218); -#152218 = DEFINITIONAL_REPRESENTATION('',(#152219),#152223); -#152219 = LINE('',#152220,#152221); -#152220 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152221 = VECTOR('',#152222,1.); -#152222 = DIRECTION('',(0.E+000,1.)); -#152223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152224 = PCURVE('',#151597,#152225); -#152225 = DEFINITIONAL_REPRESENTATION('',(#152226),#152230); -#152226 = LINE('',#152227,#152228); -#152227 = CARTESIAN_POINT('',(9.975761026426E-002,0.E+000)); -#152228 = VECTOR('',#152229,1.); -#152229 = DIRECTION('',(1.,0.E+000)); -#152230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152231 = ORIENTED_EDGE('',*,*,#152031,.T.); -#152232 = ADVANCED_FACE('',(#152233),#151740,.F.); -#152233 = FACE_BOUND('',#152234,.T.); -#152234 = EDGE_LOOP('',(#152235,#152256,#152257,#152283,#152284,#152310, - #152311,#152332)); -#152235 = ORIENTED_EDGE('',*,*,#152236,.T.); -#152236 = EDGE_CURVE('',#152166,#151725,#152237,.T.); -#152237 = SURFACE_CURVE('',#152238,(#152242,#152249),.PCURVE_S1.); -#152238 = LINE('',#152239,#152240); -#152239 = CARTESIAN_POINT('',(0.575,0.68333334,-1.05)); -#152240 = VECTOR('',#152241,1.); -#152241 = DIRECTION('',(5.233595624294E-002,0.998629534755,0.E+000)); -#152242 = PCURVE('',#151740,#152243); -#152243 = DEFINITIONAL_REPRESENTATION('',(#152244),#152248); -#152244 = LINE('',#152245,#152246); -#152245 = CARTESIAN_POINT('',(0.E+000,-2.1)); -#152246 = VECTOR('',#152247,1.); -#152247 = DIRECTION('',(-1.,0.E+000)); -#152248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152249 = PCURVE('',#151653,#152250); -#152250 = DEFINITIONAL_REPRESENTATION('',(#152251),#152255); -#152251 = LINE('',#152252,#152253); -#152252 = CARTESIAN_POINT('',(1.216566016369,0.63333334)); -#152253 = VECTOR('',#152254,1.); -#152254 = DIRECTION('',(5.233595624294E-002,0.998629534755)); -#152255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152256 = ORIENTED_EDGE('',*,*,#151724,.F.); -#152257 = ORIENTED_EDGE('',*,*,#152258,.F.); -#152258 = EDGE_CURVE('',#151929,#151690,#152259,.T.); -#152259 = SURFACE_CURVE('',#152260,(#152264,#152271),.PCURVE_S1.); -#152260 = LINE('',#152261,#152262); -#152261 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#152262 = VECTOR('',#152263,1.); -#152263 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152264 = PCURVE('',#151740,#152265); -#152265 = DEFINITIONAL_REPRESENTATION('',(#152266),#152270); -#152266 = LINE('',#152267,#152268); -#152267 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152268 = VECTOR('',#152269,1.); -#152269 = DIRECTION('',(0.E+000,-1.)); -#152270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152271 = PCURVE('',#152272,#152277); -#152272 = PLANE('',#152273); -#152273 = AXIS2_PLACEMENT_3D('',#152274,#152275,#152276); -#152274 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.825)); -#152275 = DIRECTION('',(-1.07686155438E-015,-1.,0.E+000)); -#152276 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); -#152277 = DEFINITIONAL_REPRESENTATION('',(#152278),#152282); -#152278 = LINE('',#152279,#152280); -#152279 = CARTESIAN_POINT('',(1.681667764292E-003,1.875)); -#152280 = VECTOR('',#152281,1.); -#152281 = DIRECTION('',(0.E+000,-1.)); -#152282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152283 = ORIENTED_EDGE('',*,*,#151928,.F.); -#152284 = ORIENTED_EDGE('',*,*,#152285,.F.); -#152285 = EDGE_CURVE('',#151822,#151901,#152286,.T.); -#152286 = SURFACE_CURVE('',#152287,(#152291,#152298),.PCURVE_S1.); -#152287 = LINE('',#152288,#152289); -#152288 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#152289 = VECTOR('',#152290,1.); -#152290 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152291 = PCURVE('',#151740,#152292); -#152292 = DEFINITIONAL_REPRESENTATION('',(#152293),#152297); -#152293 = LINE('',#152294,#152295); -#152294 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152295 = VECTOR('',#152296,1.); -#152296 = DIRECTION('',(0.E+000,-1.)); -#152297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152298 = PCURVE('',#152299,#152304); -#152299 = PLANE('',#152300); -#152300 = AXIS2_PLACEMENT_3D('',#152301,#152302,#152303); -#152301 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.825)); -#152302 = DIRECTION('',(1.07686155438E-015,1.,0.E+000)); -#152303 = DIRECTION('',(-1.,1.07686155438E-015,0.E+000)); -#152304 = DEFINITIONAL_REPRESENTATION('',(#152305),#152309); -#152305 = LINE('',#152306,#152307); -#152306 = CARTESIAN_POINT('',(-1.681667764292E-003,0.225)); -#152307 = VECTOR('',#152308,1.); -#152308 = DIRECTION('',(0.E+000,-1.)); -#152309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152310 = ORIENTED_EDGE('',*,*,#151821,.F.); -#152311 = ORIENTED_EDGE('',*,*,#152312,.F.); -#152312 = EDGE_CURVE('',#152189,#151799,#152313,.T.); -#152313 = SURFACE_CURVE('',#152314,(#152318,#152325),.PCURVE_S1.); -#152314 = LINE('',#152315,#152316); -#152315 = CARTESIAN_POINT('',(0.575,0.68333334,1.05)); -#152316 = VECTOR('',#152317,1.); -#152317 = DIRECTION('',(5.233595624294E-002,0.998629534755,0.E+000)); -#152318 = PCURVE('',#151740,#152319); -#152319 = DEFINITIONAL_REPRESENTATION('',(#152320),#152324); -#152320 = LINE('',#152321,#152322); -#152321 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152322 = VECTOR('',#152323,1.); -#152323 = DIRECTION('',(-1.,0.E+000)); -#152324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152325 = PCURVE('',#151597,#152326); -#152326 = DEFINITIONAL_REPRESENTATION('',(#152327),#152331); -#152327 = LINE('',#152328,#152329); -#152328 = CARTESIAN_POINT('',(1.216566016369,0.63333334)); -#152329 = VECTOR('',#152330,1.); -#152330 = DIRECTION('',(5.233595624294E-002,0.998629534755)); -#152331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152332 = ORIENTED_EDGE('',*,*,#152188,.T.); -#152333 = ADVANCED_FACE('',(#152334),#151625,.F.); -#152334 = FACE_BOUND('',#152335,.T.); -#152335 = EDGE_LOOP('',(#152336,#152357,#152358,#152379)); -#152336 = ORIENTED_EDGE('',*,*,#152337,.T.); -#152337 = EDGE_CURVE('',#151753,#151610,#152338,.T.); -#152338 = SURFACE_CURVE('',#152339,(#152343,#152350),.PCURVE_S1.); -#152339 = LINE('',#152340,#152341); -#152340 = CARTESIAN_POINT('',(-0.541716992867,1.,-1.05)); -#152341 = VECTOR('',#152342,1.); -#152342 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152343 = PCURVE('',#151625,#152344); -#152344 = DEFINITIONAL_REPRESENTATION('',(#152345),#152349); -#152345 = LINE('',#152346,#152347); -#152346 = CARTESIAN_POINT('',(2.1,0.E+000)); -#152347 = VECTOR('',#152348,1.); -#152348 = DIRECTION('',(0.E+000,-1.)); -#152349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152350 = PCURVE('',#151653,#152351); -#152351 = DEFINITIONAL_REPRESENTATION('',(#152352),#152356); -#152352 = LINE('',#152353,#152354); -#152353 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); -#152354 = VECTOR('',#152355,1.); -#152355 = DIRECTION('',(-1.,0.E+000)); -#152356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152357 = ORIENTED_EDGE('',*,*,#151609,.F.); -#152358 = ORIENTED_EDGE('',*,*,#152359,.F.); -#152359 = EDGE_CURVE('',#151776,#151582,#152360,.T.); -#152360 = SURFACE_CURVE('',#152361,(#152365,#152372),.PCURVE_S1.); -#152361 = LINE('',#152362,#152363); -#152362 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); -#152363 = VECTOR('',#152364,1.); -#152364 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152365 = PCURVE('',#151625,#152366); -#152366 = DEFINITIONAL_REPRESENTATION('',(#152367),#152371); -#152367 = LINE('',#152368,#152369); -#152368 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152369 = VECTOR('',#152370,1.); -#152370 = DIRECTION('',(0.E+000,-1.)); -#152371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152372 = PCURVE('',#151597,#152373); -#152373 = DEFINITIONAL_REPRESENTATION('',(#152374),#152378); -#152374 = LINE('',#152375,#152376); -#152375 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); -#152376 = VECTOR('',#152377,1.); -#152377 = DIRECTION('',(-1.,0.E+000)); -#152378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152379 = ORIENTED_EDGE('',*,*,#151775,.T.); -#152380 = ADVANCED_FACE('',(#152381),#151597,.T.); -#152381 = FACE_BOUND('',#152382,.T.); -#152382 = EDGE_LOOP('',(#152383,#152384,#152385,#152386,#152387,#152388) - ); -#152383 = ORIENTED_EDGE('',*,*,#151581,.T.); -#152384 = ORIENTED_EDGE('',*,*,#152059,.T.); -#152385 = ORIENTED_EDGE('',*,*,#152211,.T.); -#152386 = ORIENTED_EDGE('',*,*,#152312,.T.); -#152387 = ORIENTED_EDGE('',*,*,#151798,.T.); -#152388 = ORIENTED_EDGE('',*,*,#152359,.T.); -#152389 = ADVANCED_FACE('',(#152390),#151653,.F.); -#152390 = FACE_BOUND('',#152391,.T.); -#152391 = EDGE_LOOP('',(#152392,#152393,#152394,#152395,#152396,#152397) - ); -#152392 = ORIENTED_EDGE('',*,*,#151637,.F.); -#152393 = ORIENTED_EDGE('',*,*,#152337,.F.); -#152394 = ORIENTED_EDGE('',*,*,#151752,.F.); -#152395 = ORIENTED_EDGE('',*,*,#152236,.F.); -#152396 = ORIENTED_EDGE('',*,*,#152165,.F.); -#152397 = ORIENTED_EDGE('',*,*,#152008,.F.); -#152398 = ADVANCED_FACE('',(#152399),#152122,.F.); -#152399 = FACE_BOUND('',#152400,.T.); -#152400 = EDGE_LOOP('',(#152401,#152424,#152425,#152448)); -#152401 = ORIENTED_EDGE('',*,*,#152402,.T.); -#152402 = EDGE_CURVE('',#152403,#151340,#152405,.T.); -#152403 = VERTEX_POINT('',#152404); -#152404 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,-0.1125)); -#152405 = SURFACE_CURVE('',#152406,(#152410,#152417),.PCURVE_S1.); -#152406 = LINE('',#152407,#152408); -#152407 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.1125)); -#152408 = VECTOR('',#152409,1.); -#152409 = DIRECTION('',(1.,-1.088932886955E-015,0.E+000)); -#152410 = PCURVE('',#152122,#152411); -#152411 = DEFINITIONAL_REPRESENTATION('',(#152412),#152416); -#152412 = LINE('',#152413,#152414); -#152413 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152414 = VECTOR('',#152415,1.); -#152415 = DIRECTION('',(-1.,0.E+000)); -#152416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152417 = PCURVE('',#151383,#152418); -#152418 = DEFINITIONAL_REPRESENTATION('',(#152419),#152423); -#152419 = LINE('',#152420,#152421); -#152420 = CARTESIAN_POINT('',(9.956556418434E-002,1.6E-002)); -#152421 = VECTOR('',#152422,1.); -#152422 = DIRECTION('',(1.,-1.088932886955E-015)); -#152423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152424 = ORIENTED_EDGE('',*,*,#152108,.F.); -#152425 = ORIENTED_EDGE('',*,*,#152426,.F.); -#152426 = EDGE_CURVE('',#152427,#151424,#152429,.T.); -#152427 = VERTEX_POINT('',#152428); -#152428 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,0.1125)); -#152429 = SURFACE_CURVE('',#152430,(#152434,#152441),.PCURVE_S1.); -#152430 = LINE('',#152431,#152432); -#152431 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.1125)); -#152432 = VECTOR('',#152433,1.); -#152433 = DIRECTION('',(1.,-1.088932886955E-015,0.E+000)); -#152434 = PCURVE('',#152122,#152435); -#152435 = DEFINITIONAL_REPRESENTATION('',(#152436),#152440); -#152436 = LINE('',#152437,#152438); -#152437 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152438 = VECTOR('',#152439,1.); -#152439 = DIRECTION('',(-1.,0.E+000)); -#152440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152441 = PCURVE('',#151439,#152442); -#152442 = DEFINITIONAL_REPRESENTATION('',(#152443),#152447); -#152443 = LINE('',#152444,#152445); -#152444 = CARTESIAN_POINT('',(9.956556418434E-002,1.6E-002)); -#152445 = VECTOR('',#152446,1.); -#152446 = DIRECTION('',(1.,-1.088932886955E-015)); -#152447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152448 = ORIENTED_EDGE('',*,*,#152449,.T.); -#152449 = EDGE_CURVE('',#152427,#152403,#152450,.T.); -#152450 = SURFACE_CURVE('',#152451,(#152455,#152462),.PCURVE_S1.); -#152451 = LINE('',#152452,#152453); -#152452 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,0.1125)); -#152453 = VECTOR('',#152454,1.); -#152454 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152455 = PCURVE('',#152122,#152456); -#152456 = DEFINITIONAL_REPRESENTATION('',(#152457),#152461); -#152457 = LINE('',#152458,#152459); -#152458 = CARTESIAN_POINT('',(9.956556418434E-002,0.E+000)); -#152459 = VECTOR('',#152460,1.); -#152460 = DIRECTION('',(0.E+000,-1.)); -#152461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152462 = PCURVE('',#152463,#152468); -#152463 = CYLINDRICAL_SURFACE('',#152464,1.6E-002); -#152464 = AXIS2_PLACEMENT_3D('',#152465,#152466,#152467); -#152465 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); -#152466 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152467 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152468 = DEFINITIONAL_REPRESENTATION('',(#152469),#152472); -#152469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152470,#152471), +#154742 = PCURVE('',#154045,#154743); +#154743 = DEFINITIONAL_REPRESENTATION('',(#154744),#154748); +#154744 = LINE('',#154745,#154746); +#154745 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); +#154746 = VECTOR('',#154747,1.); +#154747 = DIRECTION('',(-1.,0.E+000)); +#154748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154749 = ORIENTED_EDGE('',*,*,#154001,.F.); +#154750 = ORIENTED_EDGE('',*,*,#154751,.F.); +#154751 = EDGE_CURVE('',#154168,#153974,#154752,.T.); +#154752 = SURFACE_CURVE('',#154753,(#154757,#154764),.PCURVE_S1.); +#154753 = LINE('',#154754,#154755); +#154754 = CARTESIAN_POINT('',(-0.541716992867,1.,1.05)); +#154755 = VECTOR('',#154756,1.); +#154756 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154757 = PCURVE('',#154017,#154758); +#154758 = DEFINITIONAL_REPRESENTATION('',(#154759),#154763); +#154759 = LINE('',#154760,#154761); +#154760 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154761 = VECTOR('',#154762,1.); +#154762 = DIRECTION('',(0.E+000,-1.)); +#154763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154764 = PCURVE('',#153989,#154765); +#154765 = DEFINITIONAL_REPRESENTATION('',(#154766),#154770); +#154766 = LINE('',#154767,#154768); +#154767 = CARTESIAN_POINT('',(9.984902350239E-002,0.95)); +#154768 = VECTOR('',#154769,1.); +#154769 = DIRECTION('',(-1.,0.E+000)); +#154770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154771 = ORIENTED_EDGE('',*,*,#154167,.T.); +#154772 = ADVANCED_FACE('',(#154773),#153989,.T.); +#154773 = FACE_BOUND('',#154774,.T.); +#154774 = EDGE_LOOP('',(#154775,#154776,#154777,#154778,#154779,#154780) + ); +#154775 = ORIENTED_EDGE('',*,*,#153973,.T.); +#154776 = ORIENTED_EDGE('',*,*,#154451,.T.); +#154777 = ORIENTED_EDGE('',*,*,#154603,.T.); +#154778 = ORIENTED_EDGE('',*,*,#154704,.T.); +#154779 = ORIENTED_EDGE('',*,*,#154190,.T.); +#154780 = ORIENTED_EDGE('',*,*,#154751,.T.); +#154781 = ADVANCED_FACE('',(#154782),#154045,.F.); +#154782 = FACE_BOUND('',#154783,.T.); +#154783 = EDGE_LOOP('',(#154784,#154785,#154786,#154787,#154788,#154789) + ); +#154784 = ORIENTED_EDGE('',*,*,#154029,.F.); +#154785 = ORIENTED_EDGE('',*,*,#154729,.F.); +#154786 = ORIENTED_EDGE('',*,*,#154144,.F.); +#154787 = ORIENTED_EDGE('',*,*,#154628,.F.); +#154788 = ORIENTED_EDGE('',*,*,#154557,.F.); +#154789 = ORIENTED_EDGE('',*,*,#154400,.F.); +#154790 = ADVANCED_FACE('',(#154791),#154514,.F.); +#154791 = FACE_BOUND('',#154792,.T.); +#154792 = EDGE_LOOP('',(#154793,#154816,#154817,#154840)); +#154793 = ORIENTED_EDGE('',*,*,#154794,.T.); +#154794 = EDGE_CURVE('',#154795,#153732,#154797,.T.); +#154795 = VERTEX_POINT('',#154796); +#154796 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,-0.1125)); +#154797 = SURFACE_CURVE('',#154798,(#154802,#154809),.PCURVE_S1.); +#154798 = LINE('',#154799,#154800); +#154799 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.1125)); +#154800 = VECTOR('',#154801,1.); +#154801 = DIRECTION('',(1.,-1.088932886955E-015,0.E+000)); +#154802 = PCURVE('',#154514,#154803); +#154803 = DEFINITIONAL_REPRESENTATION('',(#154804),#154808); +#154804 = LINE('',#154805,#154806); +#154805 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#154806 = VECTOR('',#154807,1.); +#154807 = DIRECTION('',(-1.,0.E+000)); +#154808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154809 = PCURVE('',#153775,#154810); +#154810 = DEFINITIONAL_REPRESENTATION('',(#154811),#154815); +#154811 = LINE('',#154812,#154813); +#154812 = CARTESIAN_POINT('',(9.956556418434E-002,1.6E-002)); +#154813 = VECTOR('',#154814,1.); +#154814 = DIRECTION('',(1.,-1.088932886955E-015)); +#154815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154816 = ORIENTED_EDGE('',*,*,#154500,.F.); +#154817 = ORIENTED_EDGE('',*,*,#154818,.F.); +#154818 = EDGE_CURVE('',#154819,#153816,#154821,.T.); +#154819 = VERTEX_POINT('',#154820); +#154820 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,0.1125)); +#154821 = SURFACE_CURVE('',#154822,(#154826,#154833),.PCURVE_S1.); +#154822 = LINE('',#154823,#154824); +#154823 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.1125)); +#154824 = VECTOR('',#154825,1.); +#154825 = DIRECTION('',(1.,-1.088932886955E-015,0.E+000)); +#154826 = PCURVE('',#154514,#154827); +#154827 = DEFINITIONAL_REPRESENTATION('',(#154828),#154832); +#154828 = LINE('',#154829,#154830); +#154829 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154830 = VECTOR('',#154831,1.); +#154831 = DIRECTION('',(-1.,0.E+000)); +#154832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154833 = PCURVE('',#153831,#154834); +#154834 = DEFINITIONAL_REPRESENTATION('',(#154835),#154839); +#154835 = LINE('',#154836,#154837); +#154836 = CARTESIAN_POINT('',(9.956556418434E-002,1.6E-002)); +#154837 = VECTOR('',#154838,1.); +#154838 = DIRECTION('',(1.,-1.088932886955E-015)); +#154839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154840 = ORIENTED_EDGE('',*,*,#154841,.T.); +#154841 = EDGE_CURVE('',#154819,#154795,#154842,.T.); +#154842 = SURFACE_CURVE('',#154843,(#154847,#154854),.PCURVE_S1.); +#154843 = LINE('',#154844,#154845); +#154844 = CARTESIAN_POINT('',(-0.67288389642,0.68333334,0.1125)); +#154845 = VECTOR('',#154846,1.); +#154846 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154847 = PCURVE('',#154514,#154848); +#154848 = DEFINITIONAL_REPRESENTATION('',(#154849),#154853); +#154849 = LINE('',#154850,#154851); +#154850 = CARTESIAN_POINT('',(9.956556418434E-002,0.E+000)); +#154851 = VECTOR('',#154852,1.); +#154852 = DIRECTION('',(0.E+000,-1.)); +#154853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154854 = PCURVE('',#154855,#154860); +#154855 = CYLINDRICAL_SURFACE('',#154856,1.6E-002); +#154856 = AXIS2_PLACEMENT_3D('',#154857,#154858,#154859); +#154857 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); +#154858 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154859 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154860 = DEFINITIONAL_REPRESENTATION('',(#154861),#154864); +#154861 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154862,#154863), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#152470 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#152471 = CARTESIAN_POINT('',(1.570796326795,0.225)); -#152472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152473 = ADVANCED_FACE('',(#152474),#151439,.T.); -#152474 = FACE_BOUND('',#152475,.T.); -#152475 = EDGE_LOOP('',(#152476,#152477,#152500,#152528,#152556,#152588, - #152616,#152644,#152672,#152700,#152728,#152753)); -#152476 = ORIENTED_EDGE('',*,*,#151423,.F.); -#152477 = ORIENTED_EDGE('',*,*,#152478,.T.); -#152478 = EDGE_CURVE('',#151396,#152479,#152481,.T.); -#152479 = VERTEX_POINT('',#152480); -#152480 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,0.1125)); -#152481 = SURFACE_CURVE('',#152482,(#152486,#152493),.PCURVE_S1.); -#152482 = LINE('',#152483,#152484); -#152483 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); -#152484 = VECTOR('',#152485,1.); -#152485 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152486 = PCURVE('',#151439,#152487); -#152487 = DEFINITIONAL_REPRESENTATION('',(#152488),#152492); -#152488 = LINE('',#152489,#152490); -#152489 = CARTESIAN_POINT('',(9.956556418434E-002,3.2E-002)); -#152490 = VECTOR('',#152491,1.); -#152491 = DIRECTION('',(-1.,0.E+000)); -#152492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152493 = PCURVE('',#151411,#152494); -#152494 = DEFINITIONAL_REPRESENTATION('',(#152495),#152499); -#152495 = LINE('',#152496,#152497); -#152496 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152497 = VECTOR('',#152498,1.); -#152498 = DIRECTION('',(0.E+000,-1.)); -#152499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152500 = ORIENTED_EDGE('',*,*,#152501,.T.); -#152501 = EDGE_CURVE('',#152479,#152502,#152504,.T.); -#152502 = VERTEX_POINT('',#152503); -#152503 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); -#152504 = SURFACE_CURVE('',#152505,(#152510,#152517),.PCURVE_S1.); -#152505 = CIRCLE('',#152506,3.2E-002); -#152506 = AXIS2_PLACEMENT_3D('',#152507,#152508,#152509); -#152507 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); -#152508 = DIRECTION('',(0.E+000,0.E+000,1.)); -#152509 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152510 = PCURVE('',#151439,#152511); -#152511 = DEFINITIONAL_REPRESENTATION('',(#152512),#152516); -#152512 = CIRCLE('',#152513,3.2E-002); -#152513 = AXIS2_PLACEMENT_2D('',#152514,#152515); -#152514 = CARTESIAN_POINT('',(1.110223024625E-016,-1.110223024625E-016) - ); -#152515 = DIRECTION('',(1.,0.E+000)); -#152516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152517 = PCURVE('',#152518,#152523); -#152518 = CYLINDRICAL_SURFACE('',#152519,3.2E-002); -#152519 = AXIS2_PLACEMENT_3D('',#152520,#152521,#152522); -#152520 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); -#152521 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152522 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152523 = DEFINITIONAL_REPRESENTATION('',(#152524),#152527); -#152524 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152525,#152526), +#154862 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#154863 = CARTESIAN_POINT('',(1.570796326795,0.225)); +#154864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154865 = ADVANCED_FACE('',(#154866),#153831,.T.); +#154866 = FACE_BOUND('',#154867,.T.); +#154867 = EDGE_LOOP('',(#154868,#154869,#154892,#154920,#154948,#154980, + #155008,#155036,#155064,#155092,#155120,#155145)); +#154868 = ORIENTED_EDGE('',*,*,#153815,.F.); +#154869 = ORIENTED_EDGE('',*,*,#154870,.T.); +#154870 = EDGE_CURVE('',#153788,#154871,#154873,.T.); +#154871 = VERTEX_POINT('',#154872); +#154872 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,0.1125)); +#154873 = SURFACE_CURVE('',#154874,(#154878,#154885),.PCURVE_S1.); +#154874 = LINE('',#154875,#154876); +#154875 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.1125)); +#154876 = VECTOR('',#154877,1.); +#154877 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154878 = PCURVE('',#153831,#154879); +#154879 = DEFINITIONAL_REPRESENTATION('',(#154880),#154884); +#154880 = LINE('',#154881,#154882); +#154881 = CARTESIAN_POINT('',(9.956556418434E-002,3.2E-002)); +#154882 = VECTOR('',#154883,1.); +#154883 = DIRECTION('',(-1.,0.E+000)); +#154884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154885 = PCURVE('',#153803,#154886); +#154886 = DEFINITIONAL_REPRESENTATION('',(#154887),#154891); +#154887 = LINE('',#154888,#154889); +#154888 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154889 = VECTOR('',#154890,1.); +#154890 = DIRECTION('',(0.E+000,-1.)); +#154891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154892 = ORIENTED_EDGE('',*,*,#154893,.T.); +#154893 = EDGE_CURVE('',#154871,#154894,#154896,.T.); +#154894 = VERTEX_POINT('',#154895); +#154895 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); +#154896 = SURFACE_CURVE('',#154897,(#154902,#154909),.PCURVE_S1.); +#154897 = CIRCLE('',#154898,3.2E-002); +#154898 = AXIS2_PLACEMENT_3D('',#154899,#154900,#154901); +#154899 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); +#154900 = DIRECTION('',(0.E+000,0.E+000,1.)); +#154901 = DIRECTION('',(1.,0.E+000,0.E+000)); +#154902 = PCURVE('',#153831,#154903); +#154903 = DEFINITIONAL_REPRESENTATION('',(#154904),#154908); +#154904 = CIRCLE('',#154905,3.2E-002); +#154905 = AXIS2_PLACEMENT_2D('',#154906,#154907); +#154906 = CARTESIAN_POINT('',(1.110223024625E-016,-1.110223024625E-016) + ); +#154907 = DIRECTION('',(1.,0.E+000)); +#154908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154909 = PCURVE('',#154910,#154915); +#154910 = CYLINDRICAL_SURFACE('',#154911,3.2E-002); +#154911 = AXIS2_PLACEMENT_3D('',#154912,#154913,#154914); +#154912 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); +#154913 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154914 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154915 = DEFINITIONAL_REPRESENTATION('',(#154916),#154919); +#154916 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154917,#154918), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#152525 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#152526 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152528 = ORIENTED_EDGE('',*,*,#152529,.T.); -#152529 = EDGE_CURVE('',#152502,#152530,#152532,.T.); -#152530 = VERTEX_POINT('',#152531); -#152531 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,0.1125) - ); -#152532 = SURFACE_CURVE('',#152533,(#152537,#152544),.PCURVE_S1.); -#152533 = LINE('',#152534,#152535); -#152534 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); -#152535 = VECTOR('',#152536,1.); -#152536 = DIRECTION('',(1.770648648175E-016,-1.,0.E+000)); -#152537 = PCURVE('',#151439,#152538); -#152538 = DEFINITIONAL_REPRESENTATION('',(#152539),#152543); -#152539 = LINE('',#152540,#152541); -#152540 = CARTESIAN_POINT('',(-3.2E-002,-1.110223024625E-016)); -#152541 = VECTOR('',#152542,1.); -#152542 = DIRECTION('',(1.770648648175E-016,-1.)); -#152543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152544 = PCURVE('',#152545,#152550); -#152545 = PLANE('',#152546); -#152546 = AXIS2_PLACEMENT_3D('',#152547,#152548,#152549); -#152547 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); -#152548 = DIRECTION('',(1.,1.770648648175E-016,0.E+000)); -#152549 = DIRECTION('',(-1.770648648175E-016,1.,0.E+000)); -#152550 = DEFINITIONAL_REPRESENTATION('',(#152551),#152555); -#152551 = LINE('',#152552,#152553); -#152552 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152553 = VECTOR('',#152554,1.); -#152554 = DIRECTION('',(-1.,0.E+000)); -#152555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152556 = ORIENTED_EDGE('',*,*,#152557,.T.); -#152557 = EDGE_CURVE('',#152530,#152558,#152560,.T.); -#152558 = VERTEX_POINT('',#152559); -#152559 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) - ); -#152560 = SURFACE_CURVE('',#152561,(#152566,#152577),.PCURVE_S1.); -#152561 = CIRCLE('',#152562,1.6E-002); -#152562 = AXIS2_PLACEMENT_3D('',#152563,#152564,#152565); -#152563 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) - ); -#152564 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152565 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152566 = PCURVE('',#151439,#152567); -#152567 = DEFINITIONAL_REPRESENTATION('',(#152568),#152576); -#152568 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152569,#152570,#152571, - #152572,#152573,#152574,#152575),.UNSPECIFIED.,.T.,.F.) +#154917 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#154918 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154920 = ORIENTED_EDGE('',*,*,#154921,.T.); +#154921 = EDGE_CURVE('',#154894,#154922,#154924,.T.); +#154922 = VERTEX_POINT('',#154923); +#154923 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,0.1125) + ); +#154924 = SURFACE_CURVE('',#154925,(#154929,#154936),.PCURVE_S1.); +#154925 = LINE('',#154926,#154927); +#154926 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); +#154927 = VECTOR('',#154928,1.); +#154928 = DIRECTION('',(1.770648648175E-016,-1.,0.E+000)); +#154929 = PCURVE('',#153831,#154930); +#154930 = DEFINITIONAL_REPRESENTATION('',(#154931),#154935); +#154931 = LINE('',#154932,#154933); +#154932 = CARTESIAN_POINT('',(-3.2E-002,-1.110223024625E-016)); +#154933 = VECTOR('',#154934,1.); +#154934 = DIRECTION('',(1.770648648175E-016,-1.)); +#154935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154936 = PCURVE('',#154937,#154942); +#154937 = PLANE('',#154938); +#154938 = AXIS2_PLACEMENT_3D('',#154939,#154940,#154941); +#154939 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); +#154940 = DIRECTION('',(1.,1.770648648175E-016,0.E+000)); +#154941 = DIRECTION('',(-1.770648648175E-016,1.,0.E+000)); +#154942 = DEFINITIONAL_REPRESENTATION('',(#154943),#154947); +#154943 = LINE('',#154944,#154945); +#154944 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#154945 = VECTOR('',#154946,1.); +#154946 = DIRECTION('',(-1.,0.E+000)); +#154947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154948 = ORIENTED_EDGE('',*,*,#154949,.T.); +#154949 = EDGE_CURVE('',#154922,#154950,#154952,.T.); +#154950 = VERTEX_POINT('',#154951); +#154951 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) + ); +#154952 = SURFACE_CURVE('',#154953,(#154958,#154969),.PCURVE_S1.); +#154953 = CIRCLE('',#154954,1.6E-002); +#154954 = AXIS2_PLACEMENT_3D('',#154955,#154956,#154957); +#154955 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) + ); +#154956 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154957 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154958 = PCURVE('',#153831,#154959); +#154959 = DEFINITIONAL_REPRESENTATION('',(#154960),#154968); +#154960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#154961,#154962,#154963, + #154964,#154965,#154966,#154967),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#152569 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); -#152570 = CARTESIAN_POINT('',(-6.4E-002,-0.584606392023)); -#152571 = CARTESIAN_POINT('',(-4.E-002,-0.598462798483)); -#152572 = CARTESIAN_POINT('',(-1.6E-002,-0.612319204944)); -#152573 = CARTESIAN_POINT('',(-4.E-002,-0.626175611404)); -#152574 = CARTESIAN_POINT('',(-6.4E-002,-0.640032017865)); -#152575 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); -#152576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152577 = PCURVE('',#152578,#152583); -#152578 = CYLINDRICAL_SURFACE('',#152579,1.6E-002); -#152579 = AXIS2_PLACEMENT_3D('',#152580,#152581,#152582); -#152580 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) - ); -#152581 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152582 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152583 = DEFINITIONAL_REPRESENTATION('',(#152584),#152587); -#152584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152585,#152586), +#154961 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); +#154962 = CARTESIAN_POINT('',(-6.4E-002,-0.584606392023)); +#154963 = CARTESIAN_POINT('',(-4.E-002,-0.598462798483)); +#154964 = CARTESIAN_POINT('',(-1.6E-002,-0.612319204944)); +#154965 = CARTESIAN_POINT('',(-4.E-002,-0.626175611404)); +#154966 = CARTESIAN_POINT('',(-6.4E-002,-0.640032017865)); +#154967 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); +#154968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154969 = PCURVE('',#154970,#154975); +#154970 = CYLINDRICAL_SURFACE('',#154971,1.6E-002); +#154971 = AXIS2_PLACEMENT_3D('',#154972,#154973,#154974); +#154972 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) + ); +#154973 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#154974 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#154975 = DEFINITIONAL_REPRESENTATION('',(#154976),#154979); +#154976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154977,#154978), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#152585 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#152586 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#152587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152588 = ORIENTED_EDGE('',*,*,#152589,.T.); -#152589 = EDGE_CURVE('',#152558,#152590,#152592,.T.); -#152590 = VERTEX_POINT('',#152591); -#152591 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,0.1125)); -#152592 = SURFACE_CURVE('',#152593,(#152597,#152604),.PCURVE_S1.); -#152593 = LINE('',#152594,#152595); -#152594 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) - ); -#152595 = VECTOR('',#152596,1.); -#152596 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); -#152597 = PCURVE('',#151439,#152598); -#152598 = DEFINITIONAL_REPRESENTATION('',(#152599),#152603); -#152599 = LINE('',#152600,#152601); -#152600 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#152601 = VECTOR('',#152602,1.); -#152602 = DIRECTION('',(-0.99756405026,-6.975647374412E-002)); -#152603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152604 = PCURVE('',#152605,#152610); -#152605 = PLANE('',#152606); -#152606 = AXIS2_PLACEMENT_3D('',#152607,#152608,#152609); -#152607 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) - ); -#152608 = DIRECTION('',(6.975647374412E-002,-0.99756405026,0.E+000)); -#152609 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); -#152610 = DEFINITIONAL_REPRESENTATION('',(#152611),#152615); -#152611 = LINE('',#152612,#152613); -#152612 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152613 = VECTOR('',#152614,1.); -#152614 = DIRECTION('',(-1.,0.E+000)); -#152615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152616 = ORIENTED_EDGE('',*,*,#152617,.T.); -#152617 = EDGE_CURVE('',#152590,#152618,#152620,.T.); -#152618 = VERTEX_POINT('',#152619); -#152619 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) - ); -#152620 = SURFACE_CURVE('',#152621,(#152625,#152632),.PCURVE_S1.); -#152621 = LINE('',#152622,#152623); -#152622 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) - ); -#152623 = VECTOR('',#152624,1.); -#152624 = DIRECTION('',(6.975647374411E-002,-0.99756405026,0.E+000)); -#152625 = PCURVE('',#151439,#152626); -#152626 = DEFINITIONAL_REPRESENTATION('',(#152627),#152631); -#152627 = LINE('',#152628,#152629); -#152628 = CARTESIAN_POINT('',(-0.376,-0.66733334)); -#152629 = VECTOR('',#152630,1.); -#152630 = DIRECTION('',(6.975647374411E-002,-0.99756405026)); -#152631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152632 = PCURVE('',#152633,#152638); -#152633 = PLANE('',#152634); -#152634 = AXIS2_PLACEMENT_3D('',#152635,#152636,#152637); -#152635 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) - ); -#152636 = DIRECTION('',(0.99756405026,6.975647374411E-002,0.E+000)); -#152637 = DIRECTION('',(-6.975647374411E-002,0.99756405026,0.E+000)); -#152638 = DEFINITIONAL_REPRESENTATION('',(#152639),#152643); -#152639 = LINE('',#152640,#152641); -#152640 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152641 = VECTOR('',#152642,1.); -#152642 = DIRECTION('',(-1.,0.E+000)); -#152643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152644 = ORIENTED_EDGE('',*,*,#152645,.T.); -#152645 = EDGE_CURVE('',#152618,#152646,#152648,.T.); -#152646 = VERTEX_POINT('',#152647); -#152647 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) - ); -#152648 = SURFACE_CURVE('',#152649,(#152653,#152660),.PCURVE_S1.); -#152649 = LINE('',#152650,#152651); -#152650 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) - ); -#152651 = VECTOR('',#152652,1.); -#152652 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); -#152653 = PCURVE('',#151439,#152654); -#152654 = DEFINITIONAL_REPRESENTATION('',(#152655),#152659); -#152655 = LINE('',#152656,#152657); -#152656 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#152657 = VECTOR('',#152658,1.); -#152658 = DIRECTION('',(0.99756405026,6.975647374412E-002)); -#152659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152660 = PCURVE('',#152661,#152666); -#152661 = PLANE('',#152662); -#152662 = AXIS2_PLACEMENT_3D('',#152663,#152664,#152665); -#152663 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) - ); -#152664 = DIRECTION('',(-6.975647374412E-002,0.99756405026,0.E+000)); -#152665 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); -#152666 = DEFINITIONAL_REPRESENTATION('',(#152667),#152671); -#152667 = LINE('',#152668,#152669); -#152668 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152669 = VECTOR('',#152670,1.); -#152670 = DIRECTION('',(-1.,0.E+000)); -#152671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152672 = ORIENTED_EDGE('',*,*,#152673,.T.); -#152673 = EDGE_CURVE('',#152646,#152674,#152676,.T.); -#152674 = VERTEX_POINT('',#152675); -#152675 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,0.1125) - ); -#152676 = SURFACE_CURVE('',#152677,(#152682,#152689),.PCURVE_S1.); -#152677 = CIRCLE('',#152678,3.2E-002); -#152678 = AXIS2_PLACEMENT_3D('',#152679,#152680,#152681); -#152679 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) - ); -#152680 = DIRECTION('',(0.E+000,0.E+000,1.)); -#152681 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152682 = PCURVE('',#151439,#152683); -#152683 = DEFINITIONAL_REPRESENTATION('',(#152684),#152688); -#152684 = CIRCLE('',#152685,3.2E-002); -#152685 = AXIS2_PLACEMENT_2D('',#152686,#152687); -#152686 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#152687 = DIRECTION('',(-1.,0.E+000)); -#152688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152689 = PCURVE('',#152690,#152695); -#152690 = CYLINDRICAL_SURFACE('',#152691,3.2E-002); -#152691 = AXIS2_PLACEMENT_3D('',#152692,#152693,#152694); -#152692 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) - ); -#152693 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152694 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152695 = DEFINITIONAL_REPRESENTATION('',(#152696),#152699); -#152696 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152697,#152698), +#154977 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#154978 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#154979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154980 = ORIENTED_EDGE('',*,*,#154981,.T.); +#154981 = EDGE_CURVE('',#154950,#154982,#154984,.T.); +#154982 = VERTEX_POINT('',#154983); +#154983 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,0.1125)); +#154984 = SURFACE_CURVE('',#154985,(#154989,#154996),.PCURVE_S1.); +#154985 = LINE('',#154986,#154987); +#154986 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) + ); +#154987 = VECTOR('',#154988,1.); +#154988 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); +#154989 = PCURVE('',#153831,#154990); +#154990 = DEFINITIONAL_REPRESENTATION('',(#154991),#154995); +#154991 = LINE('',#154992,#154993); +#154992 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#154993 = VECTOR('',#154994,1.); +#154994 = DIRECTION('',(-0.99756405026,-6.975647374412E-002)); +#154995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#154996 = PCURVE('',#154997,#155002); +#154997 = PLANE('',#154998); +#154998 = AXIS2_PLACEMENT_3D('',#154999,#155000,#155001); +#154999 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) + ); +#155000 = DIRECTION('',(6.975647374412E-002,-0.99756405026,0.E+000)); +#155001 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); +#155002 = DEFINITIONAL_REPRESENTATION('',(#155003),#155007); +#155003 = LINE('',#155004,#155005); +#155004 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155005 = VECTOR('',#155006,1.); +#155006 = DIRECTION('',(-1.,0.E+000)); +#155007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155008 = ORIENTED_EDGE('',*,*,#155009,.T.); +#155009 = EDGE_CURVE('',#154982,#155010,#155012,.T.); +#155010 = VERTEX_POINT('',#155011); +#155011 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) + ); +#155012 = SURFACE_CURVE('',#155013,(#155017,#155024),.PCURVE_S1.); +#155013 = LINE('',#155014,#155015); +#155014 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) + ); +#155015 = VECTOR('',#155016,1.); +#155016 = DIRECTION('',(6.975647374411E-002,-0.99756405026,0.E+000)); +#155017 = PCURVE('',#153831,#155018); +#155018 = DEFINITIONAL_REPRESENTATION('',(#155019),#155023); +#155019 = LINE('',#155020,#155021); +#155020 = CARTESIAN_POINT('',(-0.376,-0.66733334)); +#155021 = VECTOR('',#155022,1.); +#155022 = DIRECTION('',(6.975647374411E-002,-0.99756405026)); +#155023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155024 = PCURVE('',#155025,#155030); +#155025 = PLANE('',#155026); +#155026 = AXIS2_PLACEMENT_3D('',#155027,#155028,#155029); +#155027 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) + ); +#155028 = DIRECTION('',(0.99756405026,6.975647374411E-002,0.E+000)); +#155029 = DIRECTION('',(-6.975647374411E-002,0.99756405026,0.E+000)); +#155030 = DEFINITIONAL_REPRESENTATION('',(#155031),#155035); +#155031 = LINE('',#155032,#155033); +#155032 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155033 = VECTOR('',#155034,1.); +#155034 = DIRECTION('',(-1.,0.E+000)); +#155035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155036 = ORIENTED_EDGE('',*,*,#155037,.T.); +#155037 = EDGE_CURVE('',#155010,#155038,#155040,.T.); +#155038 = VERTEX_POINT('',#155039); +#155039 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) + ); +#155040 = SURFACE_CURVE('',#155041,(#155045,#155052),.PCURVE_S1.); +#155041 = LINE('',#155042,#155043); +#155042 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) + ); +#155043 = VECTOR('',#155044,1.); +#155044 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); +#155045 = PCURVE('',#153831,#155046); +#155046 = DEFINITIONAL_REPRESENTATION('',(#155047),#155051); +#155047 = LINE('',#155048,#155049); +#155048 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#155049 = VECTOR('',#155050,1.); +#155050 = DIRECTION('',(0.99756405026,6.975647374412E-002)); +#155051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155052 = PCURVE('',#155053,#155058); +#155053 = PLANE('',#155054); +#155054 = AXIS2_PLACEMENT_3D('',#155055,#155056,#155057); +#155055 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) + ); +#155056 = DIRECTION('',(-6.975647374412E-002,0.99756405026,0.E+000)); +#155057 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); +#155058 = DEFINITIONAL_REPRESENTATION('',(#155059),#155063); +#155059 = LINE('',#155060,#155061); +#155060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155061 = VECTOR('',#155062,1.); +#155062 = DIRECTION('',(-1.,0.E+000)); +#155063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155064 = ORIENTED_EDGE('',*,*,#155065,.T.); +#155065 = EDGE_CURVE('',#155038,#155066,#155068,.T.); +#155066 = VERTEX_POINT('',#155067); +#155067 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,0.1125) + ); +#155068 = SURFACE_CURVE('',#155069,(#155074,#155081),.PCURVE_S1.); +#155069 = CIRCLE('',#155070,3.2E-002); +#155070 = AXIS2_PLACEMENT_3D('',#155071,#155072,#155073); +#155071 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) + ); +#155072 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155073 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155074 = PCURVE('',#153831,#155075); +#155075 = DEFINITIONAL_REPRESENTATION('',(#155076),#155080); +#155076 = CIRCLE('',#155077,3.2E-002); +#155077 = AXIS2_PLACEMENT_2D('',#155078,#155079); +#155078 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#155079 = DIRECTION('',(-1.,0.E+000)); +#155080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155081 = PCURVE('',#155082,#155087); +#155082 = CYLINDRICAL_SURFACE('',#155083,3.2E-002); +#155083 = AXIS2_PLACEMENT_3D('',#155084,#155085,#155086); +#155084 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,0.1125) + ); +#155085 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155086 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155087 = DEFINITIONAL_REPRESENTATION('',(#155088),#155091); +#155088 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155089,#155090), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#152697 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#152698 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#152699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152700 = ORIENTED_EDGE('',*,*,#152701,.T.); -#152701 = EDGE_CURVE('',#152674,#152702,#152704,.T.); -#152702 = VERTEX_POINT('',#152703); -#152703 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); -#152704 = SURFACE_CURVE('',#152705,(#152709,#152716),.PCURVE_S1.); -#152705 = LINE('',#152706,#152707); -#152706 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); -#152707 = VECTOR('',#152708,1.); -#152708 = DIRECTION('',(-3.54129729635E-016,1.,0.E+000)); -#152709 = PCURVE('',#151439,#152710); -#152710 = DEFINITIONAL_REPRESENTATION('',(#152711),#152715); -#152711 = LINE('',#152712,#152713); -#152712 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#152713 = VECTOR('',#152714,1.); -#152714 = DIRECTION('',(-3.54129729635E-016,1.)); -#152715 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152716 = PCURVE('',#152717,#152722); -#152717 = PLANE('',#152718); -#152718 = AXIS2_PLACEMENT_3D('',#152719,#152720,#152721); -#152719 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); -#152720 = DIRECTION('',(-1.,-3.54129729635E-016,0.E+000)); -#152721 = DIRECTION('',(3.54129729635E-016,-1.,0.E+000)); -#152722 = DEFINITIONAL_REPRESENTATION('',(#152723),#152727); -#152723 = LINE('',#152724,#152725); -#152724 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152725 = VECTOR('',#152726,1.); -#152726 = DIRECTION('',(-1.,0.E+000)); -#152727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152728 = ORIENTED_EDGE('',*,*,#152729,.T.); -#152729 = EDGE_CURVE('',#152702,#152427,#152730,.T.); -#152730 = SURFACE_CURVE('',#152731,(#152736,#152747),.PCURVE_S1.); -#152731 = CIRCLE('',#152732,1.6E-002); -#152732 = AXIS2_PLACEMENT_3D('',#152733,#152734,#152735); -#152733 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); -#152734 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152735 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152736 = PCURVE('',#151439,#152737); -#152737 = DEFINITIONAL_REPRESENTATION('',(#152738),#152746); -#152738 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152739,#152740,#152741, - #152742,#152743,#152744,#152745),.UNSPECIFIED.,.F.,.F.) +#155089 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#155090 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#155091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155092 = ORIENTED_EDGE('',*,*,#155093,.T.); +#155093 = EDGE_CURVE('',#155066,#155094,#155096,.T.); +#155094 = VERTEX_POINT('',#155095); +#155095 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); +#155096 = SURFACE_CURVE('',#155097,(#155101,#155108),.PCURVE_S1.); +#155097 = LINE('',#155098,#155099); +#155098 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); +#155099 = VECTOR('',#155100,1.); +#155100 = DIRECTION('',(-3.54129729635E-016,1.,0.E+000)); +#155101 = PCURVE('',#153831,#155102); +#155102 = DEFINITIONAL_REPRESENTATION('',(#155103),#155107); +#155103 = LINE('',#155104,#155105); +#155104 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#155105 = VECTOR('',#155106,1.); +#155106 = DIRECTION('',(-3.54129729635E-016,1.)); +#155107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155108 = PCURVE('',#155109,#155114); +#155109 = PLANE('',#155110); +#155110 = AXIS2_PLACEMENT_3D('',#155111,#155112,#155113); +#155111 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); +#155112 = DIRECTION('',(-1.,-3.54129729635E-016,0.E+000)); +#155113 = DIRECTION('',(3.54129729635E-016,-1.,0.E+000)); +#155114 = DEFINITIONAL_REPRESENTATION('',(#155115),#155119); +#155115 = LINE('',#155116,#155117); +#155116 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155117 = VECTOR('',#155118,1.); +#155118 = DIRECTION('',(-1.,0.E+000)); +#155119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155120 = ORIENTED_EDGE('',*,*,#155121,.T.); +#155121 = EDGE_CURVE('',#155094,#154819,#155122,.T.); +#155122 = SURFACE_CURVE('',#155123,(#155128,#155139),.PCURVE_S1.); +#155123 = CIRCLE('',#155124,1.6E-002); +#155124 = AXIS2_PLACEMENT_3D('',#155125,#155126,#155127); +#155125 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,0.1125)); +#155126 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155127 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155128 = PCURVE('',#153831,#155129); +#155129 = DEFINITIONAL_REPRESENTATION('',(#155130),#155138); +#155130 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155131,#155132,#155133, + #155134,#155135,#155136,#155137),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#152739 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#152740 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#152741 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#152742 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#152743 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#152744 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#152745 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#152746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152747 = PCURVE('',#152463,#152748); -#152748 = DEFINITIONAL_REPRESENTATION('',(#152749),#152752); -#152749 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152750,#152751), +#155131 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#155132 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#155133 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#155134 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#155135 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#155136 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#155137 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#155138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155139 = PCURVE('',#154855,#155140); +#155140 = DEFINITIONAL_REPRESENTATION('',(#155141),#155144); +#155141 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155142,#155143), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#152750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#152751 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#152752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152753 = ORIENTED_EDGE('',*,*,#152426,.T.); -#152754 = ADVANCED_FACE('',(#152755),#151383,.F.); -#152755 = FACE_BOUND('',#152756,.T.); -#152756 = EDGE_LOOP('',(#152757,#152780,#152781,#152782,#152809,#152832, - #152855,#152878,#152901,#152924,#152951,#152974)); -#152757 = ORIENTED_EDGE('',*,*,#152758,.F.); -#152758 = EDGE_CURVE('',#151368,#152759,#152761,.T.); -#152759 = VERTEX_POINT('',#152760); -#152760 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,-0.1125)); -#152761 = SURFACE_CURVE('',#152762,(#152766,#152773),.PCURVE_S1.); -#152762 = LINE('',#152763,#152764); -#152763 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.1125)); -#152764 = VECTOR('',#152765,1.); -#152765 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152766 = PCURVE('',#151383,#152767); -#152767 = DEFINITIONAL_REPRESENTATION('',(#152768),#152772); -#152768 = LINE('',#152769,#152770); -#152769 = CARTESIAN_POINT('',(9.956556418434E-002,3.2E-002)); -#152770 = VECTOR('',#152771,1.); -#152771 = DIRECTION('',(-1.,0.E+000)); -#152772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152773 = PCURVE('',#151411,#152774); -#152774 = DEFINITIONAL_REPRESENTATION('',(#152775),#152779); -#152775 = LINE('',#152776,#152777); -#152776 = CARTESIAN_POINT('',(0.225,0.E+000)); -#152777 = VECTOR('',#152778,1.); -#152778 = DIRECTION('',(0.E+000,-1.)); -#152779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152780 = ORIENTED_EDGE('',*,*,#151367,.T.); -#152781 = ORIENTED_EDGE('',*,*,#152402,.F.); -#152782 = ORIENTED_EDGE('',*,*,#152783,.F.); -#152783 = EDGE_CURVE('',#152784,#152403,#152786,.T.); -#152784 = VERTEX_POINT('',#152785); -#152785 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,-0.1125)); -#152786 = SURFACE_CURVE('',#152787,(#152792,#152803),.PCURVE_S1.); -#152787 = CIRCLE('',#152788,1.6E-002); -#152788 = AXIS2_PLACEMENT_3D('',#152789,#152790,#152791); -#152789 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); -#152790 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152791 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152792 = PCURVE('',#151383,#152793); -#152793 = DEFINITIONAL_REPRESENTATION('',(#152794),#152802); -#152794 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152795,#152796,#152797, - #152798,#152799,#152800,#152801),.UNSPECIFIED.,.F.,.F.) +#155142 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155143 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#155144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155145 = ORIENTED_EDGE('',*,*,#154818,.T.); +#155146 = ADVANCED_FACE('',(#155147),#153775,.F.); +#155147 = FACE_BOUND('',#155148,.T.); +#155148 = EDGE_LOOP('',(#155149,#155172,#155173,#155174,#155201,#155224, + #155247,#155270,#155293,#155316,#155343,#155366)); +#155149 = ORIENTED_EDGE('',*,*,#155150,.F.); +#155150 = EDGE_CURVE('',#153760,#155151,#155153,.T.); +#155151 = VERTEX_POINT('',#155152); +#155152 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,-0.1125)); +#155153 = SURFACE_CURVE('',#155154,(#155158,#155165),.PCURVE_S1.); +#155154 = LINE('',#155155,#155156); +#155155 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.1125)); +#155156 = VECTOR('',#155157,1.); +#155157 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155158 = PCURVE('',#153775,#155159); +#155159 = DEFINITIONAL_REPRESENTATION('',(#155160),#155164); +#155160 = LINE('',#155161,#155162); +#155161 = CARTESIAN_POINT('',(9.956556418434E-002,3.2E-002)); +#155162 = VECTOR('',#155163,1.); +#155163 = DIRECTION('',(-1.,0.E+000)); +#155164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155165 = PCURVE('',#153803,#155166); +#155166 = DEFINITIONAL_REPRESENTATION('',(#155167),#155171); +#155167 = LINE('',#155168,#155169); +#155168 = CARTESIAN_POINT('',(0.225,0.E+000)); +#155169 = VECTOR('',#155170,1.); +#155170 = DIRECTION('',(0.E+000,-1.)); +#155171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155172 = ORIENTED_EDGE('',*,*,#153759,.T.); +#155173 = ORIENTED_EDGE('',*,*,#154794,.F.); +#155174 = ORIENTED_EDGE('',*,*,#155175,.F.); +#155175 = EDGE_CURVE('',#155176,#154795,#155178,.T.); +#155176 = VERTEX_POINT('',#155177); +#155177 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,-0.1125)); +#155178 = SURFACE_CURVE('',#155179,(#155184,#155195),.PCURVE_S1.); +#155179 = CIRCLE('',#155180,1.6E-002); +#155180 = AXIS2_PLACEMENT_3D('',#155181,#155182,#155183); +#155181 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); +#155182 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155183 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155184 = PCURVE('',#153775,#155185); +#155185 = DEFINITIONAL_REPRESENTATION('',(#155186),#155194); +#155186 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155187,#155188,#155189, + #155190,#155191,#155192,#155193),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#152795 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#152796 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#152797 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#152798 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#152799 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#152800 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#152801 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#152802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152803 = PCURVE('',#152463,#152804); -#152804 = DEFINITIONAL_REPRESENTATION('',(#152805),#152808); -#152805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152806,#152807), +#155187 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#155188 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#155189 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#155190 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#155191 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#155192 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#155193 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#155194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155195 = PCURVE('',#154855,#155196); +#155196 = DEFINITIONAL_REPRESENTATION('',(#155197),#155200); +#155197 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155198,#155199), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#152806 = CARTESIAN_POINT('',(0.E+000,0.225)); -#152807 = CARTESIAN_POINT('',(1.570796326795,0.225)); -#152808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#155198 = CARTESIAN_POINT('',(0.E+000,0.225)); +#155199 = CARTESIAN_POINT('',(1.570796326795,0.225)); +#155200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#152809 = ORIENTED_EDGE('',*,*,#152810,.F.); -#152810 = EDGE_CURVE('',#152811,#152784,#152813,.T.); -#152811 = VERTEX_POINT('',#152812); -#152812 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,-0.1125 +#155201 = ORIENTED_EDGE('',*,*,#155202,.F.); +#155202 = EDGE_CURVE('',#155203,#155176,#155205,.T.); +#155203 = VERTEX_POINT('',#155204); +#155204 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,-0.1125 )); -#152813 = SURFACE_CURVE('',#152814,(#152818,#152825),.PCURVE_S1.); -#152814 = LINE('',#152815,#152816); -#152815 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,-0.1125)); -#152816 = VECTOR('',#152817,1.); -#152817 = DIRECTION('',(-3.54129729635E-016,1.,0.E+000)); -#152818 = PCURVE('',#151383,#152819); -#152819 = DEFINITIONAL_REPRESENTATION('',(#152820),#152824); -#152820 = LINE('',#152821,#152822); -#152821 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#152822 = VECTOR('',#152823,1.); -#152823 = DIRECTION('',(-3.54129729635E-016,1.)); -#152824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152825 = PCURVE('',#152717,#152826); -#152826 = DEFINITIONAL_REPRESENTATION('',(#152827),#152831); -#152827 = LINE('',#152828,#152829); -#152828 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152829 = VECTOR('',#152830,1.); -#152830 = DIRECTION('',(-1.,0.E+000)); -#152831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152832 = ORIENTED_EDGE('',*,*,#152833,.F.); -#152833 = EDGE_CURVE('',#152834,#152811,#152836,.T.); -#152834 = VERTEX_POINT('',#152835); -#152835 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,-0.1125 +#155205 = SURFACE_CURVE('',#155206,(#155210,#155217),.PCURVE_S1.); +#155206 = LINE('',#155207,#155208); +#155207 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,-0.1125)); +#155208 = VECTOR('',#155209,1.); +#155209 = DIRECTION('',(-3.54129729635E-016,1.,0.E+000)); +#155210 = PCURVE('',#153775,#155211); +#155211 = DEFINITIONAL_REPRESENTATION('',(#155212),#155216); +#155212 = LINE('',#155213,#155214); +#155213 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#155214 = VECTOR('',#155215,1.); +#155215 = DIRECTION('',(-3.54129729635E-016,1.)); +#155216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155217 = PCURVE('',#155109,#155218); +#155218 = DEFINITIONAL_REPRESENTATION('',(#155219),#155223); +#155219 = LINE('',#155220,#155221); +#155220 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#155221 = VECTOR('',#155222,1.); +#155222 = DIRECTION('',(-1.,0.E+000)); +#155223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155224 = ORIENTED_EDGE('',*,*,#155225,.F.); +#155225 = EDGE_CURVE('',#155226,#155203,#155228,.T.); +#155226 = VERTEX_POINT('',#155227); +#155227 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,-0.1125 )); -#152836 = SURFACE_CURVE('',#152837,(#152842,#152849),.PCURVE_S1.); -#152837 = CIRCLE('',#152838,3.2E-002); -#152838 = AXIS2_PLACEMENT_3D('',#152839,#152840,#152841); -#152839 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,-0.1125 +#155228 = SURFACE_CURVE('',#155229,(#155234,#155241),.PCURVE_S1.); +#155229 = CIRCLE('',#155230,3.2E-002); +#155230 = AXIS2_PLACEMENT_3D('',#155231,#155232,#155233); +#155231 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,-0.1125 )); -#152840 = DIRECTION('',(0.E+000,0.E+000,1.)); -#152841 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152842 = PCURVE('',#151383,#152843); -#152843 = DEFINITIONAL_REPRESENTATION('',(#152844),#152848); -#152844 = CIRCLE('',#152845,3.2E-002); -#152845 = AXIS2_PLACEMENT_2D('',#152846,#152847); -#152846 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#152847 = DIRECTION('',(-1.,0.E+000)); -#152848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152849 = PCURVE('',#152690,#152850); -#152850 = DEFINITIONAL_REPRESENTATION('',(#152851),#152854); -#152851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152852,#152853), +#155232 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155233 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155234 = PCURVE('',#153775,#155235); +#155235 = DEFINITIONAL_REPRESENTATION('',(#155236),#155240); +#155236 = CIRCLE('',#155237,3.2E-002); +#155237 = AXIS2_PLACEMENT_2D('',#155238,#155239); +#155238 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#155239 = DIRECTION('',(-1.,0.E+000)); +#155240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155241 = PCURVE('',#155082,#155242); +#155242 = DEFINITIONAL_REPRESENTATION('',(#155243),#155246); +#155243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155244,#155245), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#152852 = CARTESIAN_POINT('',(4.642575810305,0.225)); -#152853 = CARTESIAN_POINT('',(3.14159265359,0.225)); -#152854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#155244 = CARTESIAN_POINT('',(4.642575810305,0.225)); +#155245 = CARTESIAN_POINT('',(3.14159265359,0.225)); +#155246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#152855 = ORIENTED_EDGE('',*,*,#152856,.F.); -#152856 = EDGE_CURVE('',#152857,#152834,#152859,.T.); -#152857 = VERTEX_POINT('',#152858); -#152858 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,-0.1125 +#155247 = ORIENTED_EDGE('',*,*,#155248,.F.); +#155248 = EDGE_CURVE('',#155249,#155226,#155251,.T.); +#155249 = VERTEX_POINT('',#155250); +#155250 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,-0.1125 )); -#152859 = SURFACE_CURVE('',#152860,(#152864,#152871),.PCURVE_S1.); -#152860 = LINE('',#152861,#152862); -#152861 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,-0.1125 +#155251 = SURFACE_CURVE('',#155252,(#155256,#155263),.PCURVE_S1.); +#155252 = LINE('',#155253,#155254); +#155253 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,-0.1125 )); -#152862 = VECTOR('',#152863,1.); -#152863 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); -#152864 = PCURVE('',#151383,#152865); -#152865 = DEFINITIONAL_REPRESENTATION('',(#152866),#152870); -#152866 = LINE('',#152867,#152868); -#152867 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#152868 = VECTOR('',#152869,1.); -#152869 = DIRECTION('',(0.99756405026,6.975647374412E-002)); -#152870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152871 = PCURVE('',#152661,#152872); -#152872 = DEFINITIONAL_REPRESENTATION('',(#152873),#152877); -#152873 = LINE('',#152874,#152875); -#152874 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152875 = VECTOR('',#152876,1.); -#152876 = DIRECTION('',(-1.,0.E+000)); -#152877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152878 = ORIENTED_EDGE('',*,*,#152879,.F.); -#152879 = EDGE_CURVE('',#152880,#152857,#152882,.T.); -#152880 = VERTEX_POINT('',#152881); -#152881 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,-0.1125)); -#152882 = SURFACE_CURVE('',#152883,(#152887,#152894),.PCURVE_S1.); -#152883 = LINE('',#152884,#152885); -#152884 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,-0.1125 +#155254 = VECTOR('',#155255,1.); +#155255 = DIRECTION('',(0.99756405026,6.975647374412E-002,0.E+000)); +#155256 = PCURVE('',#153775,#155257); +#155257 = DEFINITIONAL_REPRESENTATION('',(#155258),#155262); +#155258 = LINE('',#155259,#155260); +#155259 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#155260 = VECTOR('',#155261,1.); +#155261 = DIRECTION('',(0.99756405026,6.975647374412E-002)); +#155262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155263 = PCURVE('',#155053,#155264); +#155264 = DEFINITIONAL_REPRESENTATION('',(#155265),#155269); +#155265 = LINE('',#155266,#155267); +#155266 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#155267 = VECTOR('',#155268,1.); +#155268 = DIRECTION('',(-1.,0.E+000)); +#155269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155270 = ORIENTED_EDGE('',*,*,#155271,.F.); +#155271 = EDGE_CURVE('',#155272,#155249,#155274,.T.); +#155272 = VERTEX_POINT('',#155273); +#155273 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,-0.1125)); +#155274 = SURFACE_CURVE('',#155275,(#155279,#155286),.PCURVE_S1.); +#155275 = LINE('',#155276,#155277); +#155276 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,-0.1125 )); -#152885 = VECTOR('',#152886,1.); -#152886 = DIRECTION('',(6.975647374411E-002,-0.99756405026,0.E+000)); -#152887 = PCURVE('',#151383,#152888); -#152888 = DEFINITIONAL_REPRESENTATION('',(#152889),#152893); -#152889 = LINE('',#152890,#152891); -#152890 = CARTESIAN_POINT('',(-0.376,-0.66733334)); -#152891 = VECTOR('',#152892,1.); -#152892 = DIRECTION('',(6.975647374411E-002,-0.99756405026)); -#152893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152894 = PCURVE('',#152633,#152895); -#152895 = DEFINITIONAL_REPRESENTATION('',(#152896),#152900); -#152896 = LINE('',#152897,#152898); -#152897 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152898 = VECTOR('',#152899,1.); -#152899 = DIRECTION('',(-1.,0.E+000)); -#152900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152901 = ORIENTED_EDGE('',*,*,#152902,.F.); -#152902 = EDGE_CURVE('',#152903,#152880,#152905,.T.); -#152903 = VERTEX_POINT('',#152904); -#152904 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,-0.1125 +#155277 = VECTOR('',#155278,1.); +#155278 = DIRECTION('',(6.975647374411E-002,-0.99756405026,0.E+000)); +#155279 = PCURVE('',#153775,#155280); +#155280 = DEFINITIONAL_REPRESENTATION('',(#155281),#155285); +#155281 = LINE('',#155282,#155283); +#155282 = CARTESIAN_POINT('',(-0.376,-0.66733334)); +#155283 = VECTOR('',#155284,1.); +#155284 = DIRECTION('',(6.975647374411E-002,-0.99756405026)); +#155285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155286 = PCURVE('',#155025,#155287); +#155287 = DEFINITIONAL_REPRESENTATION('',(#155288),#155292); +#155288 = LINE('',#155289,#155290); +#155289 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#155290 = VECTOR('',#155291,1.); +#155291 = DIRECTION('',(-1.,0.E+000)); +#155292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155293 = ORIENTED_EDGE('',*,*,#155294,.F.); +#155294 = EDGE_CURVE('',#155295,#155272,#155297,.T.); +#155295 = VERTEX_POINT('',#155296); +#155296 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,-0.1125 )); -#152905 = SURFACE_CURVE('',#152906,(#152910,#152917),.PCURVE_S1.); -#152906 = LINE('',#152907,#152908); -#152907 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,-0.1125 +#155297 = SURFACE_CURVE('',#155298,(#155302,#155309),.PCURVE_S1.); +#155298 = LINE('',#155299,#155300); +#155299 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,-0.1125 )); -#152908 = VECTOR('',#152909,1.); -#152909 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); -#152910 = PCURVE('',#151383,#152911); -#152911 = DEFINITIONAL_REPRESENTATION('',(#152912),#152916); -#152912 = LINE('',#152913,#152914); -#152913 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#152914 = VECTOR('',#152915,1.); -#152915 = DIRECTION('',(-0.99756405026,-6.975647374412E-002)); -#152916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152917 = PCURVE('',#152605,#152918); -#152918 = DEFINITIONAL_REPRESENTATION('',(#152919),#152923); -#152919 = LINE('',#152920,#152921); -#152920 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152921 = VECTOR('',#152922,1.); -#152922 = DIRECTION('',(-1.,0.E+000)); -#152923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152924 = ORIENTED_EDGE('',*,*,#152925,.F.); -#152925 = EDGE_CURVE('',#152926,#152903,#152928,.T.); -#152926 = VERTEX_POINT('',#152927); -#152927 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,-0.1125 +#155300 = VECTOR('',#155301,1.); +#155301 = DIRECTION('',(-0.99756405026,-6.975647374412E-002,0.E+000)); +#155302 = PCURVE('',#153775,#155303); +#155303 = DEFINITIONAL_REPRESENTATION('',(#155304),#155308); +#155304 = LINE('',#155305,#155306); +#155305 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#155306 = VECTOR('',#155307,1.); +#155307 = DIRECTION('',(-0.99756405026,-6.975647374412E-002)); +#155308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155309 = PCURVE('',#154997,#155310); +#155310 = DEFINITIONAL_REPRESENTATION('',(#155311),#155315); +#155311 = LINE('',#155312,#155313); +#155312 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#155313 = VECTOR('',#155314,1.); +#155314 = DIRECTION('',(-1.,0.E+000)); +#155315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155316 = ORIENTED_EDGE('',*,*,#155317,.F.); +#155317 = EDGE_CURVE('',#155318,#155295,#155320,.T.); +#155318 = VERTEX_POINT('',#155319); +#155319 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,-0.1125 )); -#152928 = SURFACE_CURVE('',#152929,(#152934,#152945),.PCURVE_S1.); -#152929 = CIRCLE('',#152930,1.6E-002); -#152930 = AXIS2_PLACEMENT_3D('',#152931,#152932,#152933); -#152931 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,-0.1125 +#155320 = SURFACE_CURVE('',#155321,(#155326,#155337),.PCURVE_S1.); +#155321 = CIRCLE('',#155322,1.6E-002); +#155322 = AXIS2_PLACEMENT_3D('',#155323,#155324,#155325); +#155323 = CARTESIAN_POINT('',(-0.72088389642,5.501413505607E-002,-0.1125 )); -#152932 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#152933 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#152934 = PCURVE('',#151383,#152935); -#152935 = DEFINITIONAL_REPRESENTATION('',(#152936),#152944); -#152936 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#152937,#152938,#152939, - #152940,#152941,#152942,#152943),.UNSPECIFIED.,.T.,.F.) +#155324 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155325 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155326 = PCURVE('',#153775,#155327); +#155327 = DEFINITIONAL_REPRESENTATION('',(#155328),#155336); +#155328 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155329,#155330,#155331, + #155332,#155333,#155334,#155335),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#152937 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); -#152938 = CARTESIAN_POINT('',(-6.4E-002,-0.584606392023)); -#152939 = CARTESIAN_POINT('',(-4.E-002,-0.598462798483)); -#152940 = CARTESIAN_POINT('',(-1.6E-002,-0.612319204944)); -#152941 = CARTESIAN_POINT('',(-4.E-002,-0.626175611404)); -#152942 = CARTESIAN_POINT('',(-6.4E-002,-0.640032017865)); -#152943 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); -#152944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152945 = PCURVE('',#152578,#152946); -#152946 = DEFINITIONAL_REPRESENTATION('',(#152947),#152950); -#152947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152948,#152949), +#155329 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); +#155330 = CARTESIAN_POINT('',(-6.4E-002,-0.584606392023)); +#155331 = CARTESIAN_POINT('',(-4.E-002,-0.598462798483)); +#155332 = CARTESIAN_POINT('',(-1.6E-002,-0.612319204944)); +#155333 = CARTESIAN_POINT('',(-4.E-002,-0.626175611404)); +#155334 = CARTESIAN_POINT('',(-6.4E-002,-0.640032017865)); +#155335 = CARTESIAN_POINT('',(-6.4E-002,-0.612319204944)); +#155336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155337 = PCURVE('',#154970,#155338); +#155338 = DEFINITIONAL_REPRESENTATION('',(#155339),#155342); +#155339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155340,#155341), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#152948 = CARTESIAN_POINT('',(3.14159265359,0.225)); -#152949 = CARTESIAN_POINT('',(4.642575810305,0.225)); -#152950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152951 = ORIENTED_EDGE('',*,*,#152952,.F.); -#152952 = EDGE_CURVE('',#152953,#152926,#152955,.T.); -#152953 = VERTEX_POINT('',#152954); -#152954 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,-0.1125)); -#152955 = SURFACE_CURVE('',#152956,(#152960,#152967),.PCURVE_S1.); -#152956 = LINE('',#152957,#152958); -#152957 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,-0.1125)); -#152958 = VECTOR('',#152959,1.); -#152959 = DIRECTION('',(1.770648648175E-016,-1.,0.E+000)); -#152960 = PCURVE('',#151383,#152961); -#152961 = DEFINITIONAL_REPRESENTATION('',(#152962),#152966); -#152962 = LINE('',#152963,#152964); -#152963 = CARTESIAN_POINT('',(-3.2E-002,-1.110223024625E-016)); -#152964 = VECTOR('',#152965,1.); -#152965 = DIRECTION('',(1.770648648175E-016,-1.)); -#152966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152967 = PCURVE('',#152545,#152968); -#152968 = DEFINITIONAL_REPRESENTATION('',(#152969),#152973); -#152969 = LINE('',#152970,#152971); -#152970 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#152971 = VECTOR('',#152972,1.); -#152972 = DIRECTION('',(-1.,0.E+000)); -#152973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152974 = ORIENTED_EDGE('',*,*,#152975,.F.); -#152975 = EDGE_CURVE('',#152759,#152953,#152976,.T.); -#152976 = SURFACE_CURVE('',#152977,(#152982,#152989),.PCURVE_S1.); -#152977 = CIRCLE('',#152978,3.2E-002); -#152978 = AXIS2_PLACEMENT_3D('',#152979,#152980,#152981); -#152979 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); -#152980 = DIRECTION('',(0.E+000,0.E+000,1.)); -#152981 = DIRECTION('',(1.,0.E+000,0.E+000)); -#152982 = PCURVE('',#151383,#152983); -#152983 = DEFINITIONAL_REPRESENTATION('',(#152984),#152988); -#152984 = CIRCLE('',#152985,3.2E-002); -#152985 = AXIS2_PLACEMENT_2D('',#152986,#152987); -#152986 = CARTESIAN_POINT('',(1.110223024625E-016,-1.110223024625E-016) - ); -#152987 = DIRECTION('',(1.,0.E+000)); -#152988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152989 = PCURVE('',#152518,#152990); -#152990 = DEFINITIONAL_REPRESENTATION('',(#152991),#152994); -#152991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#152992,#152993), +#155340 = CARTESIAN_POINT('',(3.14159265359,0.225)); +#155341 = CARTESIAN_POINT('',(4.642575810305,0.225)); +#155342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155343 = ORIENTED_EDGE('',*,*,#155344,.F.); +#155344 = EDGE_CURVE('',#155345,#155318,#155347,.T.); +#155345 = VERTEX_POINT('',#155346); +#155346 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,-0.1125)); +#155347 = SURFACE_CURVE('',#155348,(#155352,#155359),.PCURVE_S1.); +#155348 = LINE('',#155349,#155350); +#155349 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,-0.1125)); +#155350 = VECTOR('',#155351,1.); +#155351 = DIRECTION('',(1.770648648175E-016,-1.,0.E+000)); +#155352 = PCURVE('',#153775,#155353); +#155353 = DEFINITIONAL_REPRESENTATION('',(#155354),#155358); +#155354 = LINE('',#155355,#155356); +#155355 = CARTESIAN_POINT('',(-3.2E-002,-1.110223024625E-016)); +#155356 = VECTOR('',#155357,1.); +#155357 = DIRECTION('',(1.770648648175E-016,-1.)); +#155358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155359 = PCURVE('',#154937,#155360); +#155360 = DEFINITIONAL_REPRESENTATION('',(#155361),#155365); +#155361 = LINE('',#155362,#155363); +#155362 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#155363 = VECTOR('',#155364,1.); +#155364 = DIRECTION('',(-1.,0.E+000)); +#155365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155366 = ORIENTED_EDGE('',*,*,#155367,.F.); +#155367 = EDGE_CURVE('',#155151,#155345,#155368,.T.); +#155368 = SURFACE_CURVE('',#155369,(#155374,#155381),.PCURVE_S1.); +#155369 = CIRCLE('',#155370,3.2E-002); +#155370 = AXIS2_PLACEMENT_3D('',#155371,#155372,#155373); +#155371 = CARTESIAN_POINT('',(-0.67288389642,0.66733334,-0.1125)); +#155372 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155373 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155374 = PCURVE('',#153775,#155375); +#155375 = DEFINITIONAL_REPRESENTATION('',(#155376),#155380); +#155376 = CIRCLE('',#155377,3.2E-002); +#155377 = AXIS2_PLACEMENT_2D('',#155378,#155379); +#155378 = CARTESIAN_POINT('',(1.110223024625E-016,-1.110223024625E-016) + ); +#155379 = DIRECTION('',(1.,0.E+000)); +#155380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155381 = PCURVE('',#154910,#155382); +#155382 = DEFINITIONAL_REPRESENTATION('',(#155383),#155386); +#155383 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155384,#155385), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#152992 = CARTESIAN_POINT('',(1.570796326795,0.225)); -#152993 = CARTESIAN_POINT('',(0.E+000,0.225)); -#152994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#152995 = ADVANCED_FACE('',(#152996),#151411,.F.); -#152996 = FACE_BOUND('',#152997,.T.); -#152997 = EDGE_LOOP('',(#152998,#152999,#153019,#153020)); -#152998 = ORIENTED_EDGE('',*,*,#152758,.T.); -#152999 = ORIENTED_EDGE('',*,*,#153000,.F.); -#153000 = EDGE_CURVE('',#152479,#152759,#153001,.T.); -#153001 = SURFACE_CURVE('',#153002,(#153006,#153013),.PCURVE_S1.); -#153002 = LINE('',#153003,#153004); -#153003 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,0.1125)); -#153004 = VECTOR('',#153005,1.); -#153005 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153006 = PCURVE('',#151411,#153007); -#153007 = DEFINITIONAL_REPRESENTATION('',(#153008),#153012); -#153008 = LINE('',#153009,#153010); -#153009 = CARTESIAN_POINT('',(0.E+000,-9.956556418434E-002)); -#153010 = VECTOR('',#153011,1.); -#153011 = DIRECTION('',(1.,0.E+000)); -#153012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153013 = PCURVE('',#152518,#153014); -#153014 = DEFINITIONAL_REPRESENTATION('',(#153015),#153018); -#153015 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153016,#153017), +#155384 = CARTESIAN_POINT('',(1.570796326795,0.225)); +#155385 = CARTESIAN_POINT('',(0.E+000,0.225)); +#155386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155387 = ADVANCED_FACE('',(#155388),#153803,.F.); +#155388 = FACE_BOUND('',#155389,.T.); +#155389 = EDGE_LOOP('',(#155390,#155391,#155411,#155412)); +#155390 = ORIENTED_EDGE('',*,*,#155150,.T.); +#155391 = ORIENTED_EDGE('',*,*,#155392,.F.); +#155392 = EDGE_CURVE('',#154871,#155151,#155393,.T.); +#155393 = SURFACE_CURVE('',#155394,(#155398,#155405),.PCURVE_S1.); +#155394 = LINE('',#155395,#155396); +#155395 = CARTESIAN_POINT('',(-0.67288389642,0.69933334,0.1125)); +#155396 = VECTOR('',#155397,1.); +#155397 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155398 = PCURVE('',#153803,#155399); +#155399 = DEFINITIONAL_REPRESENTATION('',(#155400),#155404); +#155400 = LINE('',#155401,#155402); +#155401 = CARTESIAN_POINT('',(0.E+000,-9.956556418434E-002)); +#155402 = VECTOR('',#155403,1.); +#155403 = DIRECTION('',(1.,0.E+000)); +#155404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155405 = PCURVE('',#154910,#155406); +#155406 = DEFINITIONAL_REPRESENTATION('',(#155407),#155410); +#155407 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155408,#155409), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153016 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#153017 = CARTESIAN_POINT('',(1.570796326795,0.225)); -#153018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153019 = ORIENTED_EDGE('',*,*,#152478,.F.); -#153020 = ORIENTED_EDGE('',*,*,#151395,.T.); -#153021 = ADVANCED_FACE('',(#153022),#152518,.T.); -#153022 = FACE_BOUND('',#153023,.T.); -#153023 = EDGE_LOOP('',(#153024,#153025,#153045,#153046)); -#153024 = ORIENTED_EDGE('',*,*,#152975,.T.); -#153025 = ORIENTED_EDGE('',*,*,#153026,.F.); -#153026 = EDGE_CURVE('',#152502,#152953,#153027,.T.); -#153027 = SURFACE_CURVE('',#153028,(#153032,#153038),.PCURVE_S1.); -#153028 = LINE('',#153029,#153030); -#153029 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); -#153030 = VECTOR('',#153031,1.); -#153031 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153032 = PCURVE('',#152518,#153033); -#153033 = DEFINITIONAL_REPRESENTATION('',(#153034),#153037); -#153034 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153035,#153036), +#155408 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#155409 = CARTESIAN_POINT('',(1.570796326795,0.225)); +#155410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155411 = ORIENTED_EDGE('',*,*,#154870,.F.); +#155412 = ORIENTED_EDGE('',*,*,#153787,.T.); +#155413 = ADVANCED_FACE('',(#155414),#154910,.T.); +#155414 = FACE_BOUND('',#155415,.T.); +#155415 = EDGE_LOOP('',(#155416,#155417,#155437,#155438)); +#155416 = ORIENTED_EDGE('',*,*,#155367,.T.); +#155417 = ORIENTED_EDGE('',*,*,#155418,.F.); +#155418 = EDGE_CURVE('',#154894,#155345,#155419,.T.); +#155419 = SURFACE_CURVE('',#155420,(#155424,#155430),.PCURVE_S1.); +#155420 = LINE('',#155421,#155422); +#155421 = CARTESIAN_POINT('',(-0.70488389642,0.66733334,0.1125)); +#155422 = VECTOR('',#155423,1.); +#155423 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155424 = PCURVE('',#154910,#155425); +#155425 = DEFINITIONAL_REPRESENTATION('',(#155426),#155429); +#155426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155427,#155428), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153035 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153036 = CARTESIAN_POINT('',(0.E+000,0.225)); -#153037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153038 = PCURVE('',#152545,#153039); -#153039 = DEFINITIONAL_REPRESENTATION('',(#153040),#153044); -#153040 = LINE('',#153041,#153042); -#153041 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153042 = VECTOR('',#153043,1.); -#153043 = DIRECTION('',(0.E+000,-1.)); -#153044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153045 = ORIENTED_EDGE('',*,*,#152501,.F.); -#153046 = ORIENTED_EDGE('',*,*,#153000,.T.); -#153047 = ADVANCED_FACE('',(#153048),#152545,.F.); -#153048 = FACE_BOUND('',#153049,.T.); -#153049 = EDGE_LOOP('',(#153050,#153051,#153071,#153072)); -#153050 = ORIENTED_EDGE('',*,*,#152952,.T.); -#153051 = ORIENTED_EDGE('',*,*,#153052,.F.); -#153052 = EDGE_CURVE('',#152530,#152926,#153053,.T.); -#153053 = SURFACE_CURVE('',#153054,(#153058,#153065),.PCURVE_S1.); -#153054 = LINE('',#153055,#153056); -#153055 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,0.1125) - ); -#153056 = VECTOR('',#153057,1.); -#153057 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153058 = PCURVE('',#152545,#153059); -#153059 = DEFINITIONAL_REPRESENTATION('',(#153060),#153064); -#153060 = LINE('',#153061,#153062); -#153061 = CARTESIAN_POINT('',(-0.612319204944,0.E+000)); -#153062 = VECTOR('',#153063,1.); -#153063 = DIRECTION('',(0.E+000,-1.)); -#153064 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153065 = PCURVE('',#152578,#153066); -#153066 = DEFINITIONAL_REPRESENTATION('',(#153067),#153070); -#153067 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153068,#153069), +#155427 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155428 = CARTESIAN_POINT('',(0.E+000,0.225)); +#155429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155430 = PCURVE('',#154937,#155431); +#155431 = DEFINITIONAL_REPRESENTATION('',(#155432),#155436); +#155432 = LINE('',#155433,#155434); +#155433 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155434 = VECTOR('',#155435,1.); +#155435 = DIRECTION('',(0.E+000,-1.)); +#155436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155437 = ORIENTED_EDGE('',*,*,#154893,.F.); +#155438 = ORIENTED_EDGE('',*,*,#155392,.T.); +#155439 = ADVANCED_FACE('',(#155440),#154937,.F.); +#155440 = FACE_BOUND('',#155441,.T.); +#155441 = EDGE_LOOP('',(#155442,#155443,#155463,#155464)); +#155442 = ORIENTED_EDGE('',*,*,#155344,.T.); +#155443 = ORIENTED_EDGE('',*,*,#155444,.F.); +#155444 = EDGE_CURVE('',#154922,#155318,#155445,.T.); +#155445 = SURFACE_CURVE('',#155446,(#155450,#155457),.PCURVE_S1.); +#155446 = LINE('',#155447,#155448); +#155447 = CARTESIAN_POINT('',(-0.70488389642,5.501413505607E-002,0.1125) + ); +#155448 = VECTOR('',#155449,1.); +#155449 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155450 = PCURVE('',#154937,#155451); +#155451 = DEFINITIONAL_REPRESENTATION('',(#155452),#155456); +#155452 = LINE('',#155453,#155454); +#155453 = CARTESIAN_POINT('',(-0.612319204944,0.E+000)); +#155454 = VECTOR('',#155455,1.); +#155455 = DIRECTION('',(0.E+000,-1.)); +#155456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155457 = PCURVE('',#154970,#155458); +#155458 = DEFINITIONAL_REPRESENTATION('',(#155459),#155462); +#155459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155460,#155461), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153068 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#153069 = CARTESIAN_POINT('',(3.14159265359,0.225)); -#153070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153071 = ORIENTED_EDGE('',*,*,#152529,.F.); -#153072 = ORIENTED_EDGE('',*,*,#153026,.T.); -#153073 = ADVANCED_FACE('',(#153074),#152578,.F.); -#153074 = FACE_BOUND('',#153075,.F.); -#153075 = EDGE_LOOP('',(#153076,#153077,#153078,#153079)); -#153076 = ORIENTED_EDGE('',*,*,#152925,.F.); -#153077 = ORIENTED_EDGE('',*,*,#153052,.F.); -#153078 = ORIENTED_EDGE('',*,*,#152557,.T.); -#153079 = ORIENTED_EDGE('',*,*,#153080,.T.); -#153080 = EDGE_CURVE('',#152558,#152903,#153081,.T.); -#153081 = SURFACE_CURVE('',#153082,(#153086,#153092),.PCURVE_S1.); -#153082 = LINE('',#153083,#153084); -#153083 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) - ); -#153084 = VECTOR('',#153085,1.); -#153085 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153086 = PCURVE('',#152578,#153087); -#153087 = DEFINITIONAL_REPRESENTATION('',(#153088),#153091); -#153088 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153089,#153090), +#155460 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#155461 = CARTESIAN_POINT('',(3.14159265359,0.225)); +#155462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155463 = ORIENTED_EDGE('',*,*,#154921,.F.); +#155464 = ORIENTED_EDGE('',*,*,#155418,.T.); +#155465 = ADVANCED_FACE('',(#155466),#154970,.F.); +#155466 = FACE_BOUND('',#155467,.F.); +#155467 = EDGE_LOOP('',(#155468,#155469,#155470,#155471)); +#155468 = ORIENTED_EDGE('',*,*,#155317,.F.); +#155469 = ORIENTED_EDGE('',*,*,#155444,.F.); +#155470 = ORIENTED_EDGE('',*,*,#154949,.T.); +#155471 = ORIENTED_EDGE('',*,*,#155472,.T.); +#155472 = EDGE_CURVE('',#154950,#155295,#155473,.T.); +#155473 = SURFACE_CURVE('',#155474,(#155478,#155484),.PCURVE_S1.); +#155474 = LINE('',#155475,#155476); +#155475 = CARTESIAN_POINT('',(-0.71976779284,3.905311025191E-002,0.1125) + ); +#155476 = VECTOR('',#155477,1.); +#155477 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155478 = PCURVE('',#154970,#155479); +#155479 = DEFINITIONAL_REPRESENTATION('',(#155480),#155483); +#155480 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155481,#155482), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153089 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#153090 = CARTESIAN_POINT('',(4.642575810305,0.225)); -#153091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153092 = PCURVE('',#152605,#153093); -#153093 = DEFINITIONAL_REPRESENTATION('',(#153094),#153098); -#153094 = LINE('',#153095,#153096); -#153095 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153096 = VECTOR('',#153097,1.); -#153097 = DIRECTION('',(0.E+000,-1.)); -#153098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153099 = ADVANCED_FACE('',(#153100),#152605,.F.); -#153100 = FACE_BOUND('',#153101,.T.); -#153101 = EDGE_LOOP('',(#153102,#153103,#153124,#153125)); -#153102 = ORIENTED_EDGE('',*,*,#152902,.T.); -#153103 = ORIENTED_EDGE('',*,*,#153104,.F.); -#153104 = EDGE_CURVE('',#152590,#152880,#153105,.T.); -#153105 = SURFACE_CURVE('',#153106,(#153110,#153117),.PCURVE_S1.); -#153106 = LINE('',#153107,#153108); -#153107 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,0.1125)); -#153108 = VECTOR('',#153109,1.); -#153109 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153110 = PCURVE('',#152605,#153111); -#153111 = DEFINITIONAL_REPRESENTATION('',(#153112),#153116); -#153112 = LINE('',#153113,#153114); -#153113 = CARTESIAN_POINT('',(-0.331038600553,0.E+000)); -#153114 = VECTOR('',#153115,1.); -#153115 = DIRECTION('',(0.E+000,-1.)); -#153116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153117 = PCURVE('',#152633,#153118); -#153118 = DEFINITIONAL_REPRESENTATION('',(#153119),#153123); -#153119 = LINE('',#153120,#153121); -#153120 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#153121 = VECTOR('',#153122,1.); -#153122 = DIRECTION('',(0.E+000,-1.)); -#153123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153124 = ORIENTED_EDGE('',*,*,#152589,.F.); -#153125 = ORIENTED_EDGE('',*,*,#153080,.T.); -#153126 = ADVANCED_FACE('',(#153127),#152633,.F.); -#153127 = FACE_BOUND('',#153128,.T.); -#153128 = EDGE_LOOP('',(#153129,#153130,#153151,#153152)); -#153129 = ORIENTED_EDGE('',*,*,#152879,.T.); -#153130 = ORIENTED_EDGE('',*,*,#153131,.F.); -#153131 = EDGE_CURVE('',#152618,#152857,#153132,.T.); -#153132 = SURFACE_CURVE('',#153133,(#153137,#153144),.PCURVE_S1.); -#153133 = LINE('',#153134,#153135); -#153134 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) - ); -#153135 = VECTOR('',#153136,1.); -#153136 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153137 = PCURVE('',#152633,#153138); -#153138 = DEFINITIONAL_REPRESENTATION('',(#153139),#153143); -#153139 = LINE('',#153140,#153141); -#153140 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153141 = VECTOR('',#153142,1.); -#153142 = DIRECTION('',(0.E+000,-1.)); -#153143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153144 = PCURVE('',#152661,#153145); -#153145 = DEFINITIONAL_REPRESENTATION('',(#153146),#153150); -#153146 = LINE('',#153147,#153148); -#153147 = CARTESIAN_POINT('',(0.331038600553,0.E+000)); -#153148 = VECTOR('',#153149,1.); -#153149 = DIRECTION('',(0.E+000,-1.)); -#153150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153151 = ORIENTED_EDGE('',*,*,#152617,.F.); -#153152 = ORIENTED_EDGE('',*,*,#153104,.T.); -#153153 = ADVANCED_FACE('',(#153154),#152661,.F.); -#153154 = FACE_BOUND('',#153155,.T.); -#153155 = EDGE_LOOP('',(#153156,#153157,#153177,#153178)); -#153156 = ORIENTED_EDGE('',*,*,#152856,.T.); -#153157 = ORIENTED_EDGE('',*,*,#153158,.F.); -#153158 = EDGE_CURVE('',#152646,#152834,#153159,.T.); -#153159 = SURFACE_CURVE('',#153160,(#153164,#153171),.PCURVE_S1.); -#153160 = LINE('',#153161,#153162); -#153161 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) - ); -#153162 = VECTOR('',#153163,1.); -#153163 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153164 = PCURVE('',#152661,#153165); -#153165 = DEFINITIONAL_REPRESENTATION('',(#153166),#153170); -#153166 = LINE('',#153167,#153168); -#153167 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153168 = VECTOR('',#153169,1.); -#153169 = DIRECTION('',(0.E+000,-1.)); -#153170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153171 = PCURVE('',#152690,#153172); -#153172 = DEFINITIONAL_REPRESENTATION('',(#153173),#153176); -#153173 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153174,#153175), +#155481 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#155482 = CARTESIAN_POINT('',(4.642575810305,0.225)); +#155483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155484 = PCURVE('',#154997,#155485); +#155485 = DEFINITIONAL_REPRESENTATION('',(#155486),#155490); +#155486 = LINE('',#155487,#155488); +#155487 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155488 = VECTOR('',#155489,1.); +#155489 = DIRECTION('',(0.E+000,-1.)); +#155490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155491 = ADVANCED_FACE('',(#155492),#154997,.F.); +#155492 = FACE_BOUND('',#155493,.T.); +#155493 = EDGE_LOOP('',(#155494,#155495,#155516,#155517)); +#155494 = ORIENTED_EDGE('',*,*,#155294,.T.); +#155495 = ORIENTED_EDGE('',*,*,#155496,.F.); +#155496 = EDGE_CURVE('',#154982,#155272,#155497,.T.); +#155497 = SURFACE_CURVE('',#155498,(#155502,#155509),.PCURVE_S1.); +#155498 = LINE('',#155499,#155500); +#155499 = CARTESIAN_POINT('',(-1.05,1.596102480416E-002,0.1125)); +#155500 = VECTOR('',#155501,1.); +#155501 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155502 = PCURVE('',#154997,#155503); +#155503 = DEFINITIONAL_REPRESENTATION('',(#155504),#155508); +#155504 = LINE('',#155505,#155506); +#155505 = CARTESIAN_POINT('',(-0.331038600553,0.E+000)); +#155506 = VECTOR('',#155507,1.); +#155507 = DIRECTION('',(0.E+000,-1.)); +#155508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155509 = PCURVE('',#155025,#155510); +#155510 = DEFINITIONAL_REPRESENTATION('',(#155511),#155515); +#155511 = LINE('',#155512,#155513); +#155512 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#155513 = VECTOR('',#155514,1.); +#155514 = DIRECTION('',(0.E+000,-1.)); +#155515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155516 = ORIENTED_EDGE('',*,*,#154981,.F.); +#155517 = ORIENTED_EDGE('',*,*,#155472,.T.); +#155518 = ADVANCED_FACE('',(#155519),#155025,.F.); +#155519 = FACE_BOUND('',#155520,.T.); +#155520 = EDGE_LOOP('',(#155521,#155522,#155543,#155544)); +#155521 = ORIENTED_EDGE('',*,*,#155271,.T.); +#155522 = ORIENTED_EDGE('',*,*,#155523,.F.); +#155523 = EDGE_CURVE('',#155010,#155249,#155524,.T.); +#155524 = SURFACE_CURVE('',#155525,(#155529,#155536),.PCURVE_S1.); +#155525 = LINE('',#155526,#155527); +#155526 = CARTESIAN_POINT('',(-1.04888389642,5.862420758285E-020,0.1125) + ); +#155527 = VECTOR('',#155528,1.); +#155528 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155529 = PCURVE('',#155025,#155530); +#155530 = DEFINITIONAL_REPRESENTATION('',(#155531),#155535); +#155531 = LINE('',#155532,#155533); +#155532 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155533 = VECTOR('',#155534,1.); +#155534 = DIRECTION('',(0.E+000,-1.)); +#155535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155536 = PCURVE('',#155053,#155537); +#155537 = DEFINITIONAL_REPRESENTATION('',(#155538),#155542); +#155538 = LINE('',#155539,#155540); +#155539 = CARTESIAN_POINT('',(0.331038600553,0.E+000)); +#155540 = VECTOR('',#155541,1.); +#155541 = DIRECTION('',(0.E+000,-1.)); +#155542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155543 = ORIENTED_EDGE('',*,*,#155009,.F.); +#155544 = ORIENTED_EDGE('',*,*,#155496,.T.); +#155545 = ADVANCED_FACE('',(#155546),#155053,.F.); +#155546 = FACE_BOUND('',#155547,.T.); +#155547 = EDGE_LOOP('',(#155548,#155549,#155569,#155570)); +#155548 = ORIENTED_EDGE('',*,*,#155248,.T.); +#155549 = ORIENTED_EDGE('',*,*,#155550,.F.); +#155550 = EDGE_CURVE('',#155038,#155226,#155551,.T.); +#155551 = SURFACE_CURVE('',#155552,(#155556,#155563),.PCURVE_S1.); +#155552 = LINE('',#155553,#155554); +#155553 = CARTESIAN_POINT('',(-0.71865168926,2.309208544775E-002,0.1125) + ); +#155554 = VECTOR('',#155555,1.); +#155555 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155556 = PCURVE('',#155053,#155557); +#155557 = DEFINITIONAL_REPRESENTATION('',(#155558),#155562); +#155558 = LINE('',#155559,#155560); +#155559 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155560 = VECTOR('',#155561,1.); +#155561 = DIRECTION('',(0.E+000,-1.)); +#155562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155563 = PCURVE('',#155082,#155564); +#155564 = DEFINITIONAL_REPRESENTATION('',(#155565),#155568); +#155565 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155566,#155567), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153174 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#153175 = CARTESIAN_POINT('',(4.642575810305,0.225)); -#153176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153177 = ORIENTED_EDGE('',*,*,#152645,.F.); -#153178 = ORIENTED_EDGE('',*,*,#153131,.T.); -#153179 = ADVANCED_FACE('',(#153180),#152690,.T.); -#153180 = FACE_BOUND('',#153181,.T.); -#153181 = EDGE_LOOP('',(#153182,#153183,#153203,#153204)); -#153182 = ORIENTED_EDGE('',*,*,#152833,.T.); -#153183 = ORIENTED_EDGE('',*,*,#153184,.F.); -#153184 = EDGE_CURVE('',#152674,#152811,#153185,.T.); -#153185 = SURFACE_CURVE('',#153186,(#153190,#153196),.PCURVE_S1.); -#153186 = LINE('',#153187,#153188); -#153187 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,0.1125) - ); -#153188 = VECTOR('',#153189,1.); -#153189 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153190 = PCURVE('',#152690,#153191); -#153191 = DEFINITIONAL_REPRESENTATION('',(#153192),#153195); -#153192 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153193,#153194), +#155566 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#155567 = CARTESIAN_POINT('',(4.642575810305,0.225)); +#155568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155569 = ORIENTED_EDGE('',*,*,#155037,.F.); +#155570 = ORIENTED_EDGE('',*,*,#155523,.T.); +#155571 = ADVANCED_FACE('',(#155572),#155082,.T.); +#155572 = FACE_BOUND('',#155573,.T.); +#155573 = EDGE_LOOP('',(#155574,#155575,#155595,#155596)); +#155574 = ORIENTED_EDGE('',*,*,#155225,.T.); +#155575 = ORIENTED_EDGE('',*,*,#155576,.F.); +#155576 = EDGE_CURVE('',#155066,#155203,#155577,.T.); +#155577 = SURFACE_CURVE('',#155578,(#155582,#155588),.PCURVE_S1.); +#155578 = LINE('',#155579,#155580); +#155579 = CARTESIAN_POINT('',(-0.68888389642,5.501413505607E-002,0.1125) + ); +#155580 = VECTOR('',#155581,1.); +#155581 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155582 = PCURVE('',#155082,#155583); +#155583 = DEFINITIONAL_REPRESENTATION('',(#155584),#155587); +#155584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155585,#155586), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153193 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#153194 = CARTESIAN_POINT('',(3.14159265359,0.225)); -#153195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153196 = PCURVE('',#152717,#153197); -#153197 = DEFINITIONAL_REPRESENTATION('',(#153198),#153202); -#153198 = LINE('',#153199,#153200); -#153199 = CARTESIAN_POINT('',(0.612319204944,0.E+000)); -#153200 = VECTOR('',#153201,1.); -#153201 = DIRECTION('',(0.E+000,-1.)); -#153202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153203 = ORIENTED_EDGE('',*,*,#152673,.F.); -#153204 = ORIENTED_EDGE('',*,*,#153158,.T.); -#153205 = ADVANCED_FACE('',(#153206),#152717,.F.); -#153206 = FACE_BOUND('',#153207,.T.); -#153207 = EDGE_LOOP('',(#153208,#153209,#153229,#153230)); -#153208 = ORIENTED_EDGE('',*,*,#152810,.T.); -#153209 = ORIENTED_EDGE('',*,*,#153210,.F.); -#153210 = EDGE_CURVE('',#152702,#152784,#153211,.T.); -#153211 = SURFACE_CURVE('',#153212,(#153216,#153223),.PCURVE_S1.); -#153212 = LINE('',#153213,#153214); -#153213 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); -#153214 = VECTOR('',#153215,1.); -#153215 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153216 = PCURVE('',#152717,#153217); -#153217 = DEFINITIONAL_REPRESENTATION('',(#153218),#153222); -#153218 = LINE('',#153219,#153220); -#153219 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153220 = VECTOR('',#153221,1.); -#153221 = DIRECTION('',(0.E+000,-1.)); -#153222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153223 = PCURVE('',#152463,#153224); -#153224 = DEFINITIONAL_REPRESENTATION('',(#153225),#153228); -#153225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153226,#153227), +#155585 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#155586 = CARTESIAN_POINT('',(3.14159265359,0.225)); +#155587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155588 = PCURVE('',#155109,#155589); +#155589 = DEFINITIONAL_REPRESENTATION('',(#155590),#155594); +#155590 = LINE('',#155591,#155592); +#155591 = CARTESIAN_POINT('',(0.612319204944,0.E+000)); +#155592 = VECTOR('',#155593,1.); +#155593 = DIRECTION('',(0.E+000,-1.)); +#155594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155595 = ORIENTED_EDGE('',*,*,#155065,.F.); +#155596 = ORIENTED_EDGE('',*,*,#155550,.T.); +#155597 = ADVANCED_FACE('',(#155598),#155109,.F.); +#155598 = FACE_BOUND('',#155599,.T.); +#155599 = EDGE_LOOP('',(#155600,#155601,#155621,#155622)); +#155600 = ORIENTED_EDGE('',*,*,#155202,.T.); +#155601 = ORIENTED_EDGE('',*,*,#155602,.F.); +#155602 = EDGE_CURVE('',#155094,#155176,#155603,.T.); +#155603 = SURFACE_CURVE('',#155604,(#155608,#155615),.PCURVE_S1.); +#155604 = LINE('',#155605,#155606); +#155605 = CARTESIAN_POINT('',(-0.68888389642,0.66733334,0.1125)); +#155606 = VECTOR('',#155607,1.); +#155607 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155608 = PCURVE('',#155109,#155609); +#155609 = DEFINITIONAL_REPRESENTATION('',(#155610),#155614); +#155610 = LINE('',#155611,#155612); +#155611 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155612 = VECTOR('',#155613,1.); +#155613 = DIRECTION('',(0.E+000,-1.)); +#155614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155615 = PCURVE('',#154855,#155616); +#155616 = DEFINITIONAL_REPRESENTATION('',(#155617),#155620); +#155617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155618,#155619), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.225),.PIECEWISE_BEZIER_KNOTS.); -#153226 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153227 = CARTESIAN_POINT('',(0.E+000,0.225)); -#153228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153229 = ORIENTED_EDGE('',*,*,#152701,.F.); -#153230 = ORIENTED_EDGE('',*,*,#153184,.T.); -#153231 = ADVANCED_FACE('',(#153232),#152463,.F.); -#153232 = FACE_BOUND('',#153233,.F.); -#153233 = EDGE_LOOP('',(#153234,#153235,#153236,#153237)); -#153234 = ORIENTED_EDGE('',*,*,#152783,.F.); -#153235 = ORIENTED_EDGE('',*,*,#153210,.F.); -#153236 = ORIENTED_EDGE('',*,*,#152729,.T.); -#153237 = ORIENTED_EDGE('',*,*,#152449,.T.); -#153238 = ADVANCED_FACE('',(#153239),#152299,.F.); -#153239 = FACE_BOUND('',#153240,.T.); -#153240 = EDGE_LOOP('',(#153241,#153264,#153265,#153288)); -#153241 = ORIENTED_EDGE('',*,*,#153242,.F.); -#153242 = EDGE_CURVE('',#151822,#153243,#153245,.T.); -#153243 = VERTEX_POINT('',#153244); -#153244 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.825)); -#153245 = SURFACE_CURVE('',#153246,(#153250,#153257),.PCURVE_S1.); -#153246 = LINE('',#153247,#153248); -#153247 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.825)); -#153248 = VECTOR('',#153249,1.); -#153249 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); -#153250 = PCURVE('',#152299,#153251); -#153251 = DEFINITIONAL_REPRESENTATION('',(#153252),#153256); -#153252 = LINE('',#153253,#153254); -#153253 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153254 = VECTOR('',#153255,1.); -#153255 = DIRECTION('',(-1.,0.E+000)); -#153256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153257 = PCURVE('',#151860,#153258); -#153258 = DEFINITIONAL_REPRESENTATION('',(#153259),#153263); -#153259 = LINE('',#153260,#153261); -#153260 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); -#153261 = VECTOR('',#153262,1.); -#153262 = DIRECTION('',(-1.,-1.07686155438E-015)); -#153263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153264 = ORIENTED_EDGE('',*,*,#152285,.T.); -#153265 = ORIENTED_EDGE('',*,*,#153266,.T.); -#153266 = EDGE_CURVE('',#151901,#153267,#153269,.T.); -#153267 = VERTEX_POINT('',#153268); -#153268 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.475)); -#153269 = SURFACE_CURVE('',#153270,(#153274,#153281),.PCURVE_S1.); -#153270 = LINE('',#153271,#153272); -#153271 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.475)); -#153272 = VECTOR('',#153273,1.); -#153273 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); -#153274 = PCURVE('',#152299,#153275); -#153275 = DEFINITIONAL_REPRESENTATION('',(#153276),#153280); -#153276 = LINE('',#153277,#153278); -#153277 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#153278 = VECTOR('',#153279,1.); -#153279 = DIRECTION('',(-1.,0.E+000)); -#153280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153281 = PCURVE('',#151916,#153282); -#153282 = DEFINITIONAL_REPRESENTATION('',(#153283),#153287); -#153283 = LINE('',#153284,#153285); -#153284 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); -#153285 = VECTOR('',#153286,1.); -#153286 = DIRECTION('',(-1.,-1.07686155438E-015)); -#153287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153288 = ORIENTED_EDGE('',*,*,#153289,.F.); -#153289 = EDGE_CURVE('',#153243,#153267,#153290,.T.); -#153290 = SURFACE_CURVE('',#153291,(#153295,#153302),.PCURVE_S1.); -#153291 = LINE('',#153292,#153293); -#153292 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.825)); -#153293 = VECTOR('',#153294,1.); -#153294 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153295 = PCURVE('',#152299,#153296); -#153296 = DEFINITIONAL_REPRESENTATION('',(#153297),#153301); -#153297 = LINE('',#153298,#153299); -#153298 = CARTESIAN_POINT('',(-0.100681667766,0.E+000)); -#153299 = VECTOR('',#153300,1.); -#153300 = DIRECTION('',(0.E+000,-1.)); -#153301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153302 = PCURVE('',#153303,#153308); -#153303 = CYLINDRICAL_SURFACE('',#153304,1.6E-002); -#153304 = AXIS2_PLACEMENT_3D('',#153305,#153306,#153307); -#153305 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); -#153306 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153307 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153308 = DEFINITIONAL_REPRESENTATION('',(#153309),#153312); -#153309 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153310,#153311), +#155618 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155619 = CARTESIAN_POINT('',(0.E+000,0.225)); +#155620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155621 = ORIENTED_EDGE('',*,*,#155093,.F.); +#155622 = ORIENTED_EDGE('',*,*,#155576,.T.); +#155623 = ADVANCED_FACE('',(#155624),#154855,.F.); +#155624 = FACE_BOUND('',#155625,.F.); +#155625 = EDGE_LOOP('',(#155626,#155627,#155628,#155629)); +#155626 = ORIENTED_EDGE('',*,*,#155175,.F.); +#155627 = ORIENTED_EDGE('',*,*,#155602,.F.); +#155628 = ORIENTED_EDGE('',*,*,#155121,.T.); +#155629 = ORIENTED_EDGE('',*,*,#154841,.T.); +#155630 = ADVANCED_FACE('',(#155631),#154691,.F.); +#155631 = FACE_BOUND('',#155632,.T.); +#155632 = EDGE_LOOP('',(#155633,#155656,#155657,#155680)); +#155633 = ORIENTED_EDGE('',*,*,#155634,.F.); +#155634 = EDGE_CURVE('',#154214,#155635,#155637,.T.); +#155635 = VERTEX_POINT('',#155636); +#155636 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.825)); +#155637 = SURFACE_CURVE('',#155638,(#155642,#155649),.PCURVE_S1.); +#155638 = LINE('',#155639,#155640); +#155639 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.825)); +#155640 = VECTOR('',#155641,1.); +#155641 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); +#155642 = PCURVE('',#154691,#155643); +#155643 = DEFINITIONAL_REPRESENTATION('',(#155644),#155648); +#155644 = LINE('',#155645,#155646); +#155645 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155646 = VECTOR('',#155647,1.); +#155647 = DIRECTION('',(-1.,0.E+000)); +#155648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155649 = PCURVE('',#154252,#155650); +#155650 = DEFINITIONAL_REPRESENTATION('',(#155651),#155655); +#155651 = LINE('',#155652,#155653); +#155652 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); +#155653 = VECTOR('',#155654,1.); +#155654 = DIRECTION('',(-1.,-1.07686155438E-015)); +#155655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155656 = ORIENTED_EDGE('',*,*,#154677,.T.); +#155657 = ORIENTED_EDGE('',*,*,#155658,.T.); +#155658 = EDGE_CURVE('',#154293,#155659,#155661,.T.); +#155659 = VERTEX_POINT('',#155660); +#155660 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.475)); +#155661 = SURFACE_CURVE('',#155662,(#155666,#155673),.PCURVE_S1.); +#155662 = LINE('',#155663,#155664); +#155663 = CARTESIAN_POINT('',(0.573318332236,0.68333334,0.475)); +#155664 = VECTOR('',#155665,1.); +#155665 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); +#155666 = PCURVE('',#154691,#155667); +#155667 = DEFINITIONAL_REPRESENTATION('',(#155668),#155672); +#155668 = LINE('',#155669,#155670); +#155669 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#155670 = VECTOR('',#155671,1.); +#155671 = DIRECTION('',(-1.,0.E+000)); +#155672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155673 = PCURVE('',#154308,#155674); +#155674 = DEFINITIONAL_REPRESENTATION('',(#155675),#155679); +#155675 = LINE('',#155676,#155677); +#155676 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); +#155677 = VECTOR('',#155678,1.); +#155678 = DIRECTION('',(-1.,-1.07686155438E-015)); +#155679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155680 = ORIENTED_EDGE('',*,*,#155681,.F.); +#155681 = EDGE_CURVE('',#155635,#155659,#155682,.T.); +#155682 = SURFACE_CURVE('',#155683,(#155687,#155694),.PCURVE_S1.); +#155683 = LINE('',#155684,#155685); +#155684 = CARTESIAN_POINT('',(0.674000000002,0.68333334,0.825)); +#155685 = VECTOR('',#155686,1.); +#155686 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155687 = PCURVE('',#154691,#155688); +#155688 = DEFINITIONAL_REPRESENTATION('',(#155689),#155693); +#155689 = LINE('',#155690,#155691); +#155690 = CARTESIAN_POINT('',(-0.100681667766,0.E+000)); +#155691 = VECTOR('',#155692,1.); +#155692 = DIRECTION('',(0.E+000,-1.)); +#155693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155694 = PCURVE('',#155695,#155700); +#155695 = CYLINDRICAL_SURFACE('',#155696,1.6E-002); +#155696 = AXIS2_PLACEMENT_3D('',#155697,#155698,#155699); +#155697 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); +#155698 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155699 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155700 = DEFINITIONAL_REPRESENTATION('',(#155701),#155704); +#155701 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155702,#155703), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#153310 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#153311 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#153312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153313 = ADVANCED_FACE('',(#153314),#151860,.F.); -#153314 = FACE_BOUND('',#153315,.T.); -#153315 = EDGE_LOOP('',(#153316,#153339,#153340,#153341,#153364,#153392, - #153424,#153452,#153480,#153508,#153536,#153564)); -#153316 = ORIENTED_EDGE('',*,*,#153317,.T.); -#153317 = EDGE_CURVE('',#153318,#151845,#153320,.T.); -#153318 = VERTEX_POINT('',#153319); -#153319 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.825)); -#153320 = SURFACE_CURVE('',#153321,(#153325,#153332),.PCURVE_S1.); -#153321 = LINE('',#153322,#153323); -#153322 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); -#153323 = VECTOR('',#153324,1.); -#153324 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153325 = PCURVE('',#151860,#153326); -#153326 = DEFINITIONAL_REPRESENTATION('',(#153327),#153331); -#153327 = LINE('',#153328,#153329); -#153328 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); -#153329 = VECTOR('',#153330,1.); -#153330 = DIRECTION('',(1.,0.E+000)); -#153331 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153332 = PCURVE('',#151888,#153333); -#153333 = DEFINITIONAL_REPRESENTATION('',(#153334),#153338); -#153334 = LINE('',#153335,#153336); -#153335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153336 = VECTOR('',#153337,1.); -#153337 = DIRECTION('',(0.E+000,-1.)); -#153338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153339 = ORIENTED_EDGE('',*,*,#151844,.T.); -#153340 = ORIENTED_EDGE('',*,*,#153242,.T.); -#153341 = ORIENTED_EDGE('',*,*,#153342,.T.); -#153342 = EDGE_CURVE('',#153243,#153343,#153345,.T.); -#153343 = VERTEX_POINT('',#153344); -#153344 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); -#153345 = SURFACE_CURVE('',#153346,(#153351,#153358),.PCURVE_S1.); -#153346 = CIRCLE('',#153347,1.6E-002); -#153347 = AXIS2_PLACEMENT_3D('',#153348,#153349,#153350); -#153348 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); -#153349 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153350 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153351 = PCURVE('',#151860,#153352); -#153352 = DEFINITIONAL_REPRESENTATION('',(#153353),#153357); -#153353 = CIRCLE('',#153354,1.6E-002); -#153354 = AXIS2_PLACEMENT_2D('',#153355,#153356); -#153355 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153356 = DIRECTION('',(1.,0.E+000)); -#153357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153358 = PCURVE('',#153303,#153359); -#153359 = DEFINITIONAL_REPRESENTATION('',(#153360),#153363); -#153360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153361,#153362), +#155702 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#155703 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#155704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155705 = ADVANCED_FACE('',(#155706),#154252,.F.); +#155706 = FACE_BOUND('',#155707,.T.); +#155707 = EDGE_LOOP('',(#155708,#155731,#155732,#155733,#155756,#155784, + #155816,#155844,#155872,#155900,#155928,#155956)); +#155708 = ORIENTED_EDGE('',*,*,#155709,.T.); +#155709 = EDGE_CURVE('',#155710,#154237,#155712,.T.); +#155710 = VERTEX_POINT('',#155711); +#155711 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.825)); +#155712 = SURFACE_CURVE('',#155713,(#155717,#155724),.PCURVE_S1.); +#155713 = LINE('',#155714,#155715); +#155714 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.825)); +#155715 = VECTOR('',#155716,1.); +#155716 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155717 = PCURVE('',#154252,#155718); +#155718 = DEFINITIONAL_REPRESENTATION('',(#155719),#155723); +#155719 = LINE('',#155720,#155721); +#155720 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); +#155721 = VECTOR('',#155722,1.); +#155722 = DIRECTION('',(1.,0.E+000)); +#155723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155724 = PCURVE('',#154280,#155725); +#155725 = DEFINITIONAL_REPRESENTATION('',(#155726),#155730); +#155726 = LINE('',#155727,#155728); +#155727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155728 = VECTOR('',#155729,1.); +#155729 = DIRECTION('',(0.E+000,-1.)); +#155730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155731 = ORIENTED_EDGE('',*,*,#154236,.T.); +#155732 = ORIENTED_EDGE('',*,*,#155634,.T.); +#155733 = ORIENTED_EDGE('',*,*,#155734,.T.); +#155734 = EDGE_CURVE('',#155635,#155735,#155737,.T.); +#155735 = VERTEX_POINT('',#155736); +#155736 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); +#155737 = SURFACE_CURVE('',#155738,(#155743,#155750),.PCURVE_S1.); +#155738 = CIRCLE('',#155739,1.6E-002); +#155739 = AXIS2_PLACEMENT_3D('',#155740,#155741,#155742); +#155740 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); +#155741 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155742 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155743 = PCURVE('',#154252,#155744); +#155744 = DEFINITIONAL_REPRESENTATION('',(#155745),#155749); +#155745 = CIRCLE('',#155746,1.6E-002); +#155746 = AXIS2_PLACEMENT_2D('',#155747,#155748); +#155747 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155748 = DIRECTION('',(1.,0.E+000)); +#155749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155750 = PCURVE('',#155695,#155751); +#155751 = DEFINITIONAL_REPRESENTATION('',(#155752),#155755); +#155752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155753,#155754), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#153361 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#153362 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#153363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153364 = ORIENTED_EDGE('',*,*,#153365,.T.); -#153365 = EDGE_CURVE('',#153343,#153366,#153368,.T.); -#153366 = VERTEX_POINT('',#153367); -#153367 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.825) - ); -#153368 = SURFACE_CURVE('',#153369,(#153373,#153380),.PCURVE_S1.); -#153369 = LINE('',#153370,#153371); -#153370 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); -#153371 = VECTOR('',#153372,1.); -#153372 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#153373 = PCURVE('',#151860,#153374); -#153374 = DEFINITIONAL_REPRESENTATION('',(#153375),#153379); -#153375 = LINE('',#153376,#153377); -#153376 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#153377 = VECTOR('',#153378,1.); -#153378 = DIRECTION('',(0.E+000,-1.)); -#153379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153380 = PCURVE('',#153381,#153386); -#153381 = PLANE('',#153382); -#153382 = AXIS2_PLACEMENT_3D('',#153383,#153384,#153385); -#153383 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); -#153384 = DIRECTION('',(1.,0.E+000,0.E+000)); -#153385 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153386 = DEFINITIONAL_REPRESENTATION('',(#153387),#153391); -#153387 = LINE('',#153388,#153389); -#153388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153389 = VECTOR('',#153390,1.); -#153390 = DIRECTION('',(0.E+000,-1.)); -#153391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153392 = ORIENTED_EDGE('',*,*,#153393,.T.); -#153393 = EDGE_CURVE('',#153366,#153394,#153396,.T.); -#153394 = VERTEX_POINT('',#153395); -#153395 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) - ); -#153396 = SURFACE_CURVE('',#153397,(#153402,#153413),.PCURVE_S1.); -#153397 = CIRCLE('',#153398,3.199999999999E-002); -#153398 = AXIS2_PLACEMENT_3D('',#153399,#153400,#153401); -#153399 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) - ); -#153400 = DIRECTION('',(0.E+000,0.E+000,1.)); -#153401 = DIRECTION('',(1.,0.E+000,0.E+000)); -#153402 = PCURVE('',#151860,#153403); -#153403 = DEFINITIONAL_REPRESENTATION('',(#153404),#153412); -#153404 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#153405,#153406,#153407, - #153408,#153409,#153410,#153411),.UNSPECIFIED.,.T.,.F.) +#155753 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#155754 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#155755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155756 = ORIENTED_EDGE('',*,*,#155757,.T.); +#155757 = EDGE_CURVE('',#155735,#155758,#155760,.T.); +#155758 = VERTEX_POINT('',#155759); +#155759 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.825) + ); +#155760 = SURFACE_CURVE('',#155761,(#155765,#155772),.PCURVE_S1.); +#155761 = LINE('',#155762,#155763); +#155762 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); +#155763 = VECTOR('',#155764,1.); +#155764 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#155765 = PCURVE('',#154252,#155766); +#155766 = DEFINITIONAL_REPRESENTATION('',(#155767),#155771); +#155767 = LINE('',#155768,#155769); +#155768 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#155769 = VECTOR('',#155770,1.); +#155770 = DIRECTION('',(0.E+000,-1.)); +#155771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155772 = PCURVE('',#155773,#155778); +#155773 = PLANE('',#155774); +#155774 = AXIS2_PLACEMENT_3D('',#155775,#155776,#155777); +#155775 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); +#155776 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155777 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155778 = DEFINITIONAL_REPRESENTATION('',(#155779),#155783); +#155779 = LINE('',#155780,#155781); +#155780 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155781 = VECTOR('',#155782,1.); +#155782 = DIRECTION('',(0.E+000,-1.)); +#155783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155784 = ORIENTED_EDGE('',*,*,#155785,.T.); +#155785 = EDGE_CURVE('',#155758,#155786,#155788,.T.); +#155786 = VERTEX_POINT('',#155787); +#155787 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) + ); +#155788 = SURFACE_CURVE('',#155789,(#155794,#155805),.PCURVE_S1.); +#155789 = CIRCLE('',#155790,3.199999999999E-002); +#155790 = AXIS2_PLACEMENT_3D('',#155791,#155792,#155793); +#155791 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) + ); +#155792 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155793 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155794 = PCURVE('',#154252,#155795); +#155795 = DEFINITIONAL_REPRESENTATION('',(#155796),#155804); +#155796 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155797,#155798,#155799, + #155800,#155801,#155802,#155803),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#153405 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#153406 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); -#153407 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); -#153408 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); -#153409 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); -#153410 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); -#153411 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#153412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153413 = PCURVE('',#153414,#153419); -#153414 = CYLINDRICAL_SURFACE('',#153415,3.199999999999E-002); -#153415 = AXIS2_PLACEMENT_3D('',#153416,#153417,#153418); -#153416 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) - ); -#153417 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153418 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153419 = DEFINITIONAL_REPRESENTATION('',(#153420),#153423); -#153420 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153421,#153422), +#155797 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#155798 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); +#155799 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); +#155800 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); +#155801 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); +#155802 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); +#155803 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#155804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155805 = PCURVE('',#155806,#155811); +#155806 = CYLINDRICAL_SURFACE('',#155807,3.199999999999E-002); +#155807 = AXIS2_PLACEMENT_3D('',#155808,#155809,#155810); +#155808 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) + ); +#155809 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155810 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155811 = DEFINITIONAL_REPRESENTATION('',(#155812),#155815); +#155812 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155813,#155814), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#153421 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#153422 = CARTESIAN_POINT('',(4.782202150464,0.E+000)); -#153423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153424 = ORIENTED_EDGE('',*,*,#153425,.T.); -#153425 = EDGE_CURVE('',#153394,#153426,#153428,.T.); -#153426 = VERTEX_POINT('',#153427); -#153427 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); -#153428 = SURFACE_CURVE('',#153429,(#153433,#153440),.PCURVE_S1.); -#153429 = LINE('',#153430,#153431); -#153430 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) - ); -#153431 = VECTOR('',#153432,1.); -#153432 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#153433 = PCURVE('',#151860,#153434); -#153434 = DEFINITIONAL_REPRESENTATION('',(#153435),#153439); -#153435 = LINE('',#153436,#153437); -#153436 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#153437 = VECTOR('',#153438,1.); -#153438 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); -#153439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153440 = PCURVE('',#153441,#153446); -#153441 = PLANE('',#153442); -#153442 = AXIS2_PLACEMENT_3D('',#153443,#153444,#153445); -#153443 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) - ); -#153444 = DIRECTION('',(6.975647374417E-002,0.99756405026,0.E+000)); -#153445 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#153446 = DEFINITIONAL_REPRESENTATION('',(#153447),#153451); -#153447 = LINE('',#153448,#153449); -#153448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153449 = VECTOR('',#153450,1.); -#153450 = DIRECTION('',(-1.,0.E+000)); -#153451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153452 = ORIENTED_EDGE('',*,*,#153453,.T.); -#153453 = EDGE_CURVE('',#153426,#153454,#153456,.T.); -#153454 = VERTEX_POINT('',#153455); -#153455 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.825)); -#153456 = SURFACE_CURVE('',#153457,(#153461,#153468),.PCURVE_S1.); -#153457 = LINE('',#153458,#153459); -#153458 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); -#153459 = VECTOR('',#153460,1.); -#153460 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); -#153461 = PCURVE('',#151860,#153462); -#153462 = DEFINITIONAL_REPRESENTATION('',(#153463),#153467); -#153463 = LINE('',#153464,#153465); -#153464 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); -#153465 = VECTOR('',#153466,1.); -#153466 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); -#153467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153468 = PCURVE('',#153469,#153474); -#153469 = PLANE('',#153470); -#153470 = AXIS2_PLACEMENT_3D('',#153471,#153472,#153473); -#153471 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); -#153472 = DIRECTION('',(-0.99756405026,6.975647374418E-002,0.E+000)); -#153473 = DIRECTION('',(-6.975647374418E-002,-0.99756405026,0.E+000)); -#153474 = DEFINITIONAL_REPRESENTATION('',(#153475),#153479); -#153475 = LINE('',#153476,#153477); -#153476 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153477 = VECTOR('',#153478,1.); -#153478 = DIRECTION('',(-1.,0.E+000)); -#153479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153480 = ORIENTED_EDGE('',*,*,#153481,.T.); -#153481 = EDGE_CURVE('',#153454,#153482,#153484,.T.); -#153482 = VERTEX_POINT('',#153483); -#153483 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.825) - ); -#153484 = SURFACE_CURVE('',#153485,(#153489,#153496),.PCURVE_S1.); -#153485 = LINE('',#153486,#153487); -#153486 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.825) - ); -#153487 = VECTOR('',#153488,1.); -#153488 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#153489 = PCURVE('',#151860,#153490); -#153490 = DEFINITIONAL_REPRESENTATION('',(#153491),#153495); -#153491 = LINE('',#153492,#153493); -#153492 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#153493 = VECTOR('',#153494,1.); -#153494 = DIRECTION('',(0.99756405026,6.975647374417E-002)); -#153495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153496 = PCURVE('',#153497,#153502); -#153497 = PLANE('',#153498); -#153498 = AXIS2_PLACEMENT_3D('',#153499,#153500,#153501); -#153499 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.825) - ); -#153500 = DIRECTION('',(-6.975647374417E-002,-0.99756405026,0.E+000)); -#153501 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#153502 = DEFINITIONAL_REPRESENTATION('',(#153503),#153507); -#153503 = LINE('',#153504,#153505); -#153504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153505 = VECTOR('',#153506,1.); -#153506 = DIRECTION('',(-1.,0.E+000)); -#153507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153508 = ORIENTED_EDGE('',*,*,#153509,.T.); -#153509 = EDGE_CURVE('',#153482,#153510,#153512,.T.); -#153510 = VERTEX_POINT('',#153511); -#153511 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.825) - ); -#153512 = SURFACE_CURVE('',#153513,(#153518,#153525),.PCURVE_S1.); -#153513 = CIRCLE('',#153514,1.599999999999E-002); -#153514 = AXIS2_PLACEMENT_3D('',#153515,#153516,#153517); -#153515 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) - ); -#153516 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153517 = DIRECTION('',(1.,0.E+000,0.E+000)); -#153518 = PCURVE('',#151860,#153519); -#153519 = DEFINITIONAL_REPRESENTATION('',(#153520),#153524); -#153520 = CIRCLE('',#153521,1.599999999999E-002); -#153521 = AXIS2_PLACEMENT_2D('',#153522,#153523); -#153522 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#153523 = DIRECTION('',(-1.,0.E+000)); -#153524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153525 = PCURVE('',#153526,#153531); -#153526 = CYLINDRICAL_SURFACE('',#153527,1.599999999999E-002); -#153527 = AXIS2_PLACEMENT_3D('',#153528,#153529,#153530); -#153528 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) - ); -#153529 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153530 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153531 = DEFINITIONAL_REPRESENTATION('',(#153532),#153535); -#153532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153533,#153534), +#155813 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#155814 = CARTESIAN_POINT('',(4.782202150464,0.E+000)); +#155815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155816 = ORIENTED_EDGE('',*,*,#155817,.T.); +#155817 = EDGE_CURVE('',#155786,#155818,#155820,.T.); +#155818 = VERTEX_POINT('',#155819); +#155819 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); +#155820 = SURFACE_CURVE('',#155821,(#155825,#155832),.PCURVE_S1.); +#155821 = LINE('',#155822,#155823); +#155822 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) + ); +#155823 = VECTOR('',#155824,1.); +#155824 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#155825 = PCURVE('',#154252,#155826); +#155826 = DEFINITIONAL_REPRESENTATION('',(#155827),#155831); +#155827 = LINE('',#155828,#155829); +#155828 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#155829 = VECTOR('',#155830,1.); +#155830 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); +#155831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155832 = PCURVE('',#155833,#155838); +#155833 = PLANE('',#155834); +#155834 = AXIS2_PLACEMENT_3D('',#155835,#155836,#155837); +#155835 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) + ); +#155836 = DIRECTION('',(6.975647374417E-002,0.99756405026,0.E+000)); +#155837 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#155838 = DEFINITIONAL_REPRESENTATION('',(#155839),#155843); +#155839 = LINE('',#155840,#155841); +#155840 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155841 = VECTOR('',#155842,1.); +#155842 = DIRECTION('',(-1.,0.E+000)); +#155843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155844 = ORIENTED_EDGE('',*,*,#155845,.T.); +#155845 = EDGE_CURVE('',#155818,#155846,#155848,.T.); +#155846 = VERTEX_POINT('',#155847); +#155847 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.825)); +#155848 = SURFACE_CURVE('',#155849,(#155853,#155860),.PCURVE_S1.); +#155849 = LINE('',#155850,#155851); +#155850 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); +#155851 = VECTOR('',#155852,1.); +#155852 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); +#155853 = PCURVE('',#154252,#155854); +#155854 = DEFINITIONAL_REPRESENTATION('',(#155855),#155859); +#155855 = LINE('',#155856,#155857); +#155856 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); +#155857 = VECTOR('',#155858,1.); +#155858 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); +#155859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155860 = PCURVE('',#155861,#155866); +#155861 = PLANE('',#155862); +#155862 = AXIS2_PLACEMENT_3D('',#155863,#155864,#155865); +#155863 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); +#155864 = DIRECTION('',(-0.99756405026,6.975647374418E-002,0.E+000)); +#155865 = DIRECTION('',(-6.975647374418E-002,-0.99756405026,0.E+000)); +#155866 = DEFINITIONAL_REPRESENTATION('',(#155867),#155871); +#155867 = LINE('',#155868,#155869); +#155868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155869 = VECTOR('',#155870,1.); +#155870 = DIRECTION('',(-1.,0.E+000)); +#155871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155872 = ORIENTED_EDGE('',*,*,#155873,.T.); +#155873 = EDGE_CURVE('',#155846,#155874,#155876,.T.); +#155874 = VERTEX_POINT('',#155875); +#155875 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.825) + ); +#155876 = SURFACE_CURVE('',#155877,(#155881,#155888),.PCURVE_S1.); +#155877 = LINE('',#155878,#155879); +#155878 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.825) + ); +#155879 = VECTOR('',#155880,1.); +#155880 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#155881 = PCURVE('',#154252,#155882); +#155882 = DEFINITIONAL_REPRESENTATION('',(#155883),#155887); +#155883 = LINE('',#155884,#155885); +#155884 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#155885 = VECTOR('',#155886,1.); +#155886 = DIRECTION('',(0.99756405026,6.975647374417E-002)); +#155887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155888 = PCURVE('',#155889,#155894); +#155889 = PLANE('',#155890); +#155890 = AXIS2_PLACEMENT_3D('',#155891,#155892,#155893); +#155891 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.825) + ); +#155892 = DIRECTION('',(-6.975647374417E-002,-0.99756405026,0.E+000)); +#155893 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#155894 = DEFINITIONAL_REPRESENTATION('',(#155895),#155899); +#155895 = LINE('',#155896,#155897); +#155896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155897 = VECTOR('',#155898,1.); +#155898 = DIRECTION('',(-1.,0.E+000)); +#155899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155900 = ORIENTED_EDGE('',*,*,#155901,.T.); +#155901 = EDGE_CURVE('',#155874,#155902,#155904,.T.); +#155902 = VERTEX_POINT('',#155903); +#155903 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.825) + ); +#155904 = SURFACE_CURVE('',#155905,(#155910,#155917),.PCURVE_S1.); +#155905 = CIRCLE('',#155906,1.599999999999E-002); +#155906 = AXIS2_PLACEMENT_3D('',#155907,#155908,#155909); +#155907 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) + ); +#155908 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155909 = DIRECTION('',(1.,0.E+000,0.E+000)); +#155910 = PCURVE('',#154252,#155911); +#155911 = DEFINITIONAL_REPRESENTATION('',(#155912),#155916); +#155912 = CIRCLE('',#155913,1.599999999999E-002); +#155913 = AXIS2_PLACEMENT_2D('',#155914,#155915); +#155914 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#155915 = DIRECTION('',(-1.,0.E+000)); +#155916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155917 = PCURVE('',#155918,#155923); +#155918 = CYLINDRICAL_SURFACE('',#155919,1.599999999999E-002); +#155919 = AXIS2_PLACEMENT_3D('',#155920,#155921,#155922); +#155920 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.825) + ); +#155921 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155922 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155923 = DEFINITIONAL_REPRESENTATION('',(#155924),#155927); +#155924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155925,#155926), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#153533 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#153534 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#153535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#155925 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#155926 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#155927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155928 = ORIENTED_EDGE('',*,*,#155929,.T.); +#155929 = EDGE_CURVE('',#155902,#155930,#155932,.T.); +#155930 = VERTEX_POINT('',#155931); +#155931 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); +#155932 = SURFACE_CURVE('',#155933,(#155937,#155944),.PCURVE_S1.); +#155933 = LINE('',#155934,#155935); +#155934 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); +#155935 = VECTOR('',#155936,1.); +#155936 = DIRECTION('',(0.E+000,1.,0.E+000)); +#155937 = PCURVE('',#154252,#155938); +#155938 = DEFINITIONAL_REPRESENTATION('',(#155939),#155943); +#155939 = LINE('',#155940,#155941); +#155940 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#155941 = VECTOR('',#155942,1.); +#155942 = DIRECTION('',(0.E+000,1.)); +#155943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155944 = PCURVE('',#155945,#155950); +#155945 = PLANE('',#155946); +#155946 = AXIS2_PLACEMENT_3D('',#155947,#155948,#155949); +#155947 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); +#155948 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155949 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155950 = DEFINITIONAL_REPRESENTATION('',(#155951),#155955); +#155951 = LINE('',#155952,#155953); +#155952 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#155953 = VECTOR('',#155954,1.); +#155954 = DIRECTION('',(0.E+000,1.)); +#155955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#153536 = ORIENTED_EDGE('',*,*,#153537,.T.); -#153537 = EDGE_CURVE('',#153510,#153538,#153540,.T.); -#153538 = VERTEX_POINT('',#153539); -#153539 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); -#153540 = SURFACE_CURVE('',#153541,(#153545,#153552),.PCURVE_S1.); -#153541 = LINE('',#153542,#153543); -#153542 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); -#153543 = VECTOR('',#153544,1.); -#153544 = DIRECTION('',(0.E+000,1.,0.E+000)); -#153545 = PCURVE('',#151860,#153546); -#153546 = DEFINITIONAL_REPRESENTATION('',(#153547),#153551); -#153547 = LINE('',#153548,#153549); -#153548 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#153549 = VECTOR('',#153550,1.); -#153550 = DIRECTION('',(0.E+000,1.)); -#153551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153552 = PCURVE('',#153553,#153558); -#153553 = PLANE('',#153554); -#153554 = AXIS2_PLACEMENT_3D('',#153555,#153556,#153557); -#153555 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); -#153556 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153557 = DIRECTION('',(0.E+000,0.E+000,1.)); -#153558 = DEFINITIONAL_REPRESENTATION('',(#153559),#153563); -#153559 = LINE('',#153560,#153561); -#153560 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153561 = VECTOR('',#153562,1.); -#153562 = DIRECTION('',(0.E+000,1.)); -#153563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153564 = ORIENTED_EDGE('',*,*,#153565,.T.); -#153565 = EDGE_CURVE('',#153538,#153318,#153566,.T.); -#153566 = SURFACE_CURVE('',#153567,(#153572,#153583),.PCURVE_S1.); -#153567 = CIRCLE('',#153568,3.2E-002); -#153568 = AXIS2_PLACEMENT_3D('',#153569,#153570,#153571); -#153569 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); -#153570 = DIRECTION('',(0.E+000,0.E+000,1.)); -#153571 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153572 = PCURVE('',#151860,#153573); -#153573 = DEFINITIONAL_REPRESENTATION('',(#153574),#153582); -#153574 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#153575,#153576,#153577, - #153578,#153579,#153580,#153581),.UNSPECIFIED.,.F.,.F.) +#155956 = ORIENTED_EDGE('',*,*,#155957,.T.); +#155957 = EDGE_CURVE('',#155930,#155710,#155958,.T.); +#155958 = SURFACE_CURVE('',#155959,(#155964,#155975),.PCURVE_S1.); +#155959 = CIRCLE('',#155960,3.2E-002); +#155960 = AXIS2_PLACEMENT_3D('',#155961,#155962,#155963); +#155961 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); +#155962 = DIRECTION('',(0.E+000,0.E+000,1.)); +#155963 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155964 = PCURVE('',#154252,#155965); +#155965 = DEFINITIONAL_REPRESENTATION('',(#155966),#155974); +#155966 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155967,#155968,#155969, + #155970,#155971,#155972,#155973),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#153575 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#153576 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); -#153577 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); -#153578 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); -#153579 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); -#153580 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); -#153581 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#153582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153583 = PCURVE('',#153584,#153589); -#153584 = CYLINDRICAL_SURFACE('',#153585,3.2E-002); -#153585 = AXIS2_PLACEMENT_3D('',#153586,#153587,#153588); -#153586 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); -#153587 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153588 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153589 = DEFINITIONAL_REPRESENTATION('',(#153590),#153593); -#153590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153591,#153592), +#155967 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#155968 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); +#155969 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); +#155970 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); +#155971 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); +#155972 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); +#155973 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#155974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155975 = PCURVE('',#155976,#155981); +#155976 = CYLINDRICAL_SURFACE('',#155977,3.2E-002); +#155977 = AXIS2_PLACEMENT_3D('',#155978,#155979,#155980); +#155978 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.825)); +#155979 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#155980 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155981 = DEFINITIONAL_REPRESENTATION('',(#155982),#155985); +#155982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155983,#155984), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#153591 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#153592 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#153593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153594 = ADVANCED_FACE('',(#153595),#151916,.T.); -#153595 = FACE_BOUND('',#153596,.T.); -#153596 = EDGE_LOOP('',(#153597,#153598,#153621,#153648,#153671,#153694, - #153717,#153740,#153763,#153790,#153813,#153834)); -#153597 = ORIENTED_EDGE('',*,*,#151900,.F.); -#153598 = ORIENTED_EDGE('',*,*,#153599,.F.); -#153599 = EDGE_CURVE('',#153600,#151873,#153602,.T.); -#153600 = VERTEX_POINT('',#153601); -#153601 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.475)); -#153602 = SURFACE_CURVE('',#153603,(#153607,#153614),.PCURVE_S1.); -#153603 = LINE('',#153604,#153605); -#153604 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.475)); -#153605 = VECTOR('',#153606,1.); -#153606 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153607 = PCURVE('',#151916,#153608); -#153608 = DEFINITIONAL_REPRESENTATION('',(#153609),#153613); -#153609 = LINE('',#153610,#153611); -#153610 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); -#153611 = VECTOR('',#153612,1.); -#153612 = DIRECTION('',(1.,0.E+000)); -#153613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153614 = PCURVE('',#151888,#153615); -#153615 = DEFINITIONAL_REPRESENTATION('',(#153616),#153620); -#153616 = LINE('',#153617,#153618); -#153617 = CARTESIAN_POINT('',(0.35,0.E+000)); -#153618 = VECTOR('',#153619,1.); -#153619 = DIRECTION('',(0.E+000,-1.)); -#153620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153621 = ORIENTED_EDGE('',*,*,#153622,.F.); -#153622 = EDGE_CURVE('',#153623,#153600,#153625,.T.); -#153623 = VERTEX_POINT('',#153624); -#153624 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.475)); -#153625 = SURFACE_CURVE('',#153626,(#153631,#153642),.PCURVE_S1.); -#153626 = CIRCLE('',#153627,3.2E-002); -#153627 = AXIS2_PLACEMENT_3D('',#153628,#153629,#153630); -#153628 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); -#153629 = DIRECTION('',(0.E+000,0.E+000,1.)); -#153630 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153631 = PCURVE('',#151916,#153632); -#153632 = DEFINITIONAL_REPRESENTATION('',(#153633),#153641); -#153633 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#153634,#153635,#153636, - #153637,#153638,#153639,#153640),.UNSPECIFIED.,.F.,.F.) +#155983 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#155984 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#155985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#155986 = ADVANCED_FACE('',(#155987),#154308,.T.); +#155987 = FACE_BOUND('',#155988,.T.); +#155988 = EDGE_LOOP('',(#155989,#155990,#156013,#156040,#156063,#156086, + #156109,#156132,#156155,#156182,#156205,#156226)); +#155989 = ORIENTED_EDGE('',*,*,#154292,.F.); +#155990 = ORIENTED_EDGE('',*,*,#155991,.F.); +#155991 = EDGE_CURVE('',#155992,#154265,#155994,.T.); +#155992 = VERTEX_POINT('',#155993); +#155993 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.475)); +#155994 = SURFACE_CURVE('',#155995,(#155999,#156006),.PCURVE_S1.); +#155995 = LINE('',#155996,#155997); +#155996 = CARTESIAN_POINT('',(0.573318332236,0.69933334,0.475)); +#155997 = VECTOR('',#155998,1.); +#155998 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#155999 = PCURVE('',#154308,#156000); +#156000 = DEFINITIONAL_REPRESENTATION('',(#156001),#156005); +#156001 = LINE('',#156002,#156003); +#156002 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); +#156003 = VECTOR('',#156004,1.); +#156004 = DIRECTION('',(1.,0.E+000)); +#156005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156006 = PCURVE('',#154280,#156007); +#156007 = DEFINITIONAL_REPRESENTATION('',(#156008),#156012); +#156008 = LINE('',#156009,#156010); +#156009 = CARTESIAN_POINT('',(0.35,0.E+000)); +#156010 = VECTOR('',#156011,1.); +#156011 = DIRECTION('',(0.E+000,-1.)); +#156012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156013 = ORIENTED_EDGE('',*,*,#156014,.F.); +#156014 = EDGE_CURVE('',#156015,#155992,#156017,.T.); +#156015 = VERTEX_POINT('',#156016); +#156016 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.475)); +#156017 = SURFACE_CURVE('',#156018,(#156023,#156034),.PCURVE_S1.); +#156018 = CIRCLE('',#156019,3.2E-002); +#156019 = AXIS2_PLACEMENT_3D('',#156020,#156021,#156022); +#156020 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); +#156021 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156022 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156023 = PCURVE('',#154308,#156024); +#156024 = DEFINITIONAL_REPRESENTATION('',(#156025),#156033); +#156025 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156026,#156027,#156028, + #156029,#156030,#156031,#156032),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#153634 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#153635 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); -#153636 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); -#153637 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); -#153638 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); -#153639 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); -#153640 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#153641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153642 = PCURVE('',#153584,#153643); -#153643 = DEFINITIONAL_REPRESENTATION('',(#153644),#153647); -#153644 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153645,#153646), +#156026 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#156027 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); +#156028 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); +#156029 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); +#156030 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); +#156031 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); +#156032 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#156033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156034 = PCURVE('',#155976,#156035); +#156035 = DEFINITIONAL_REPRESENTATION('',(#156036),#156039); +#156036 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156037,#156038), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#153645 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#153646 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#153647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153648 = ORIENTED_EDGE('',*,*,#153649,.F.); -#153649 = EDGE_CURVE('',#153650,#153623,#153652,.T.); -#153650 = VERTEX_POINT('',#153651); -#153651 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.475) - ); -#153652 = SURFACE_CURVE('',#153653,(#153657,#153664),.PCURVE_S1.); -#153653 = LINE('',#153654,#153655); -#153654 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.475)); -#153655 = VECTOR('',#153656,1.); -#153656 = DIRECTION('',(0.E+000,1.,0.E+000)); -#153657 = PCURVE('',#151916,#153658); -#153658 = DEFINITIONAL_REPRESENTATION('',(#153659),#153663); -#153659 = LINE('',#153660,#153661); -#153660 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#153661 = VECTOR('',#153662,1.); -#153662 = DIRECTION('',(0.E+000,1.)); -#153663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153664 = PCURVE('',#153553,#153665); -#153665 = DEFINITIONAL_REPRESENTATION('',(#153666),#153670); -#153666 = LINE('',#153667,#153668); -#153667 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#153668 = VECTOR('',#153669,1.); -#153669 = DIRECTION('',(0.E+000,1.)); -#153670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153671 = ORIENTED_EDGE('',*,*,#153672,.F.); -#153672 = EDGE_CURVE('',#153673,#153650,#153675,.T.); -#153673 = VERTEX_POINT('',#153674); -#153674 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.475) - ); -#153675 = SURFACE_CURVE('',#153676,(#153681,#153688),.PCURVE_S1.); -#153676 = CIRCLE('',#153677,1.599999999999E-002); -#153677 = AXIS2_PLACEMENT_3D('',#153678,#153679,#153680); -#153678 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.475) - ); -#153679 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153680 = DIRECTION('',(1.,0.E+000,0.E+000)); -#153681 = PCURVE('',#151916,#153682); -#153682 = DEFINITIONAL_REPRESENTATION('',(#153683),#153687); -#153683 = CIRCLE('',#153684,1.599999999999E-002); -#153684 = AXIS2_PLACEMENT_2D('',#153685,#153686); -#153685 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#153686 = DIRECTION('',(-1.,0.E+000)); -#153687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153688 = PCURVE('',#153526,#153689); -#153689 = DEFINITIONAL_REPRESENTATION('',(#153690),#153693); -#153690 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153691,#153692), +#156037 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#156038 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#156039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156040 = ORIENTED_EDGE('',*,*,#156041,.F.); +#156041 = EDGE_CURVE('',#156042,#156015,#156044,.T.); +#156042 = VERTEX_POINT('',#156043); +#156043 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.475) + ); +#156044 = SURFACE_CURVE('',#156045,(#156049,#156056),.PCURVE_S1.); +#156045 = LINE('',#156046,#156047); +#156046 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.475)); +#156047 = VECTOR('',#156048,1.); +#156048 = DIRECTION('',(0.E+000,1.,0.E+000)); +#156049 = PCURVE('',#154308,#156050); +#156050 = DEFINITIONAL_REPRESENTATION('',(#156051),#156055); +#156051 = LINE('',#156052,#156053); +#156052 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#156053 = VECTOR('',#156054,1.); +#156054 = DIRECTION('',(0.E+000,1.)); +#156055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156056 = PCURVE('',#155945,#156057); +#156057 = DEFINITIONAL_REPRESENTATION('',(#156058),#156062); +#156058 = LINE('',#156059,#156060); +#156059 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#156060 = VECTOR('',#156061,1.); +#156061 = DIRECTION('',(0.E+000,1.)); +#156062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156063 = ORIENTED_EDGE('',*,*,#156064,.F.); +#156064 = EDGE_CURVE('',#156065,#156042,#156067,.T.); +#156065 = VERTEX_POINT('',#156066); +#156066 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.475) + ); +#156067 = SURFACE_CURVE('',#156068,(#156073,#156080),.PCURVE_S1.); +#156068 = CIRCLE('',#156069,1.599999999999E-002); +#156069 = AXIS2_PLACEMENT_3D('',#156070,#156071,#156072); +#156070 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.475) + ); +#156071 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156072 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156073 = PCURVE('',#154308,#156074); +#156074 = DEFINITIONAL_REPRESENTATION('',(#156075),#156079); +#156075 = CIRCLE('',#156076,1.599999999999E-002); +#156076 = AXIS2_PLACEMENT_2D('',#156077,#156078); +#156077 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#156078 = DIRECTION('',(-1.,0.E+000)); +#156079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156080 = PCURVE('',#155918,#156081); +#156081 = DEFINITIONAL_REPRESENTATION('',(#156082),#156085); +#156082 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156083,#156084), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#153691 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#153692 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#153693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153694 = ORIENTED_EDGE('',*,*,#153695,.F.); -#153695 = EDGE_CURVE('',#153696,#153673,#153698,.T.); -#153696 = VERTEX_POINT('',#153697); -#153697 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.475)); -#153698 = SURFACE_CURVE('',#153699,(#153703,#153710),.PCURVE_S1.); -#153699 = LINE('',#153700,#153701); -#153700 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.475) - ); -#153701 = VECTOR('',#153702,1.); -#153702 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#153703 = PCURVE('',#151916,#153704); -#153704 = DEFINITIONAL_REPRESENTATION('',(#153705),#153709); -#153705 = LINE('',#153706,#153707); -#153706 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#153707 = VECTOR('',#153708,1.); -#153708 = DIRECTION('',(0.99756405026,6.975647374417E-002)); -#153709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153710 = PCURVE('',#153497,#153711); -#153711 = DEFINITIONAL_REPRESENTATION('',(#153712),#153716); -#153712 = LINE('',#153713,#153714); -#153713 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#153714 = VECTOR('',#153715,1.); -#153715 = DIRECTION('',(-1.,0.E+000)); -#153716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153717 = ORIENTED_EDGE('',*,*,#153718,.F.); -#153718 = EDGE_CURVE('',#153719,#153696,#153721,.T.); -#153719 = VERTEX_POINT('',#153720); -#153720 = CARTESIAN_POINT('',(1.05,0.E+000,0.475)); -#153721 = SURFACE_CURVE('',#153722,(#153726,#153733),.PCURVE_S1.); -#153722 = LINE('',#153723,#153724); -#153723 = CARTESIAN_POINT('',(1.05,0.E+000,0.475)); -#153724 = VECTOR('',#153725,1.); -#153725 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); -#153726 = PCURVE('',#151916,#153727); -#153727 = DEFINITIONAL_REPRESENTATION('',(#153728),#153732); -#153728 = LINE('',#153729,#153730); -#153729 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); -#153730 = VECTOR('',#153731,1.); -#153731 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); -#153732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153733 = PCURVE('',#153469,#153734); -#153734 = DEFINITIONAL_REPRESENTATION('',(#153735),#153739); -#153735 = LINE('',#153736,#153737); -#153736 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#153737 = VECTOR('',#153738,1.); -#153738 = DIRECTION('',(-1.,0.E+000)); -#153739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153740 = ORIENTED_EDGE('',*,*,#153741,.F.); -#153741 = EDGE_CURVE('',#153742,#153719,#153744,.T.); -#153742 = VERTEX_POINT('',#153743); -#153743 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.475) - ); -#153744 = SURFACE_CURVE('',#153745,(#153749,#153756),.PCURVE_S1.); -#153745 = LINE('',#153746,#153747); -#153746 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.475) - ); -#153747 = VECTOR('',#153748,1.); -#153748 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#153749 = PCURVE('',#151916,#153750); -#153750 = DEFINITIONAL_REPRESENTATION('',(#153751),#153755); -#153751 = LINE('',#153752,#153753); -#153752 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#153753 = VECTOR('',#153754,1.); -#153754 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); -#153755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153756 = PCURVE('',#153441,#153757); -#153757 = DEFINITIONAL_REPRESENTATION('',(#153758),#153762); -#153758 = LINE('',#153759,#153760); -#153759 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#153760 = VECTOR('',#153761,1.); -#153761 = DIRECTION('',(-1.,0.E+000)); -#153762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153763 = ORIENTED_EDGE('',*,*,#153764,.F.); -#153764 = EDGE_CURVE('',#153765,#153742,#153767,.T.); -#153765 = VERTEX_POINT('',#153766); -#153766 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.475) - ); -#153767 = SURFACE_CURVE('',#153768,(#153773,#153784),.PCURVE_S1.); -#153768 = CIRCLE('',#153769,3.199999999999E-002); -#153769 = AXIS2_PLACEMENT_3D('',#153770,#153771,#153772); -#153770 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.475) - ); -#153771 = DIRECTION('',(0.E+000,0.E+000,1.)); -#153772 = DIRECTION('',(1.,0.E+000,0.E+000)); -#153773 = PCURVE('',#151916,#153774); -#153774 = DEFINITIONAL_REPRESENTATION('',(#153775),#153783); -#153775 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#153776,#153777,#153778, - #153779,#153780,#153781,#153782),.UNSPECIFIED.,.T.,.F.) +#156083 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#156084 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#156085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156086 = ORIENTED_EDGE('',*,*,#156087,.F.); +#156087 = EDGE_CURVE('',#156088,#156065,#156090,.T.); +#156088 = VERTEX_POINT('',#156089); +#156089 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.475)); +#156090 = SURFACE_CURVE('',#156091,(#156095,#156102),.PCURVE_S1.); +#156091 = LINE('',#156092,#156093); +#156092 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,0.475) + ); +#156093 = VECTOR('',#156094,1.); +#156094 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#156095 = PCURVE('',#154308,#156096); +#156096 = DEFINITIONAL_REPRESENTATION('',(#156097),#156101); +#156097 = LINE('',#156098,#156099); +#156098 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#156099 = VECTOR('',#156100,1.); +#156100 = DIRECTION('',(0.99756405026,6.975647374417E-002)); +#156101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156102 = PCURVE('',#155889,#156103); +#156103 = DEFINITIONAL_REPRESENTATION('',(#156104),#156108); +#156104 = LINE('',#156105,#156106); +#156105 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#156106 = VECTOR('',#156107,1.); +#156107 = DIRECTION('',(-1.,0.E+000)); +#156108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156109 = ORIENTED_EDGE('',*,*,#156110,.F.); +#156110 = EDGE_CURVE('',#156111,#156088,#156113,.T.); +#156111 = VERTEX_POINT('',#156112); +#156112 = CARTESIAN_POINT('',(1.05,0.E+000,0.475)); +#156113 = SURFACE_CURVE('',#156114,(#156118,#156125),.PCURVE_S1.); +#156114 = LINE('',#156115,#156116); +#156115 = CARTESIAN_POINT('',(1.05,0.E+000,0.475)); +#156116 = VECTOR('',#156117,1.); +#156117 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); +#156118 = PCURVE('',#154308,#156119); +#156119 = DEFINITIONAL_REPRESENTATION('',(#156120),#156124); +#156120 = LINE('',#156121,#156122); +#156121 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); +#156122 = VECTOR('',#156123,1.); +#156123 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); +#156124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156125 = PCURVE('',#155861,#156126); +#156126 = DEFINITIONAL_REPRESENTATION('',(#156127),#156131); +#156127 = LINE('',#156128,#156129); +#156128 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#156129 = VECTOR('',#156130,1.); +#156130 = DIRECTION('',(-1.,0.E+000)); +#156131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156132 = ORIENTED_EDGE('',*,*,#156133,.F.); +#156133 = EDGE_CURVE('',#156134,#156111,#156136,.T.); +#156134 = VERTEX_POINT('',#156135); +#156135 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.475) + ); +#156136 = SURFACE_CURVE('',#156137,(#156141,#156148),.PCURVE_S1.); +#156137 = LINE('',#156138,#156139); +#156138 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.475) + ); +#156139 = VECTOR('',#156140,1.); +#156140 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#156141 = PCURVE('',#154308,#156142); +#156142 = DEFINITIONAL_REPRESENTATION('',(#156143),#156147); +#156143 = LINE('',#156144,#156145); +#156144 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#156145 = VECTOR('',#156146,1.); +#156146 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); +#156147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156148 = PCURVE('',#155833,#156149); +#156149 = DEFINITIONAL_REPRESENTATION('',(#156150),#156154); +#156150 = LINE('',#156151,#156152); +#156151 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#156152 = VECTOR('',#156153,1.); +#156153 = DIRECTION('',(-1.,0.E+000)); +#156154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156155 = ORIENTED_EDGE('',*,*,#156156,.F.); +#156156 = EDGE_CURVE('',#156157,#156134,#156159,.T.); +#156157 = VERTEX_POINT('',#156158); +#156158 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.475) + ); +#156159 = SURFACE_CURVE('',#156160,(#156165,#156176),.PCURVE_S1.); +#156160 = CIRCLE('',#156161,3.199999999999E-002); +#156161 = AXIS2_PLACEMENT_3D('',#156162,#156163,#156164); +#156162 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,0.475) + ); +#156163 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156164 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156165 = PCURVE('',#154308,#156166); +#156166 = DEFINITIONAL_REPRESENTATION('',(#156167),#156175); +#156167 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156168,#156169,#156170, + #156171,#156172,#156173,#156174),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#153776 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#153777 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); -#153778 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); -#153779 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); -#153780 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); -#153781 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); -#153782 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#153783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153784 = PCURVE('',#153414,#153785); -#153785 = DEFINITIONAL_REPRESENTATION('',(#153786),#153789); -#153786 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153787,#153788), +#156168 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#156169 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); +#156170 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); +#156171 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); +#156172 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); +#156173 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); +#156174 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#156175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156176 = PCURVE('',#155806,#156177); +#156177 = DEFINITIONAL_REPRESENTATION('',(#156178),#156181); +#156178 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156179,#156180), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#153787 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#153788 = CARTESIAN_POINT('',(4.782202150464,0.35)); -#153789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153790 = ORIENTED_EDGE('',*,*,#153791,.F.); -#153791 = EDGE_CURVE('',#153792,#153765,#153794,.T.); -#153792 = VERTEX_POINT('',#153793); -#153793 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.475)); -#153794 = SURFACE_CURVE('',#153795,(#153799,#153806),.PCURVE_S1.); -#153795 = LINE('',#153796,#153797); -#153796 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.475)); -#153797 = VECTOR('',#153798,1.); -#153798 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#153799 = PCURVE('',#151916,#153800); -#153800 = DEFINITIONAL_REPRESENTATION('',(#153801),#153805); -#153801 = LINE('',#153802,#153803); -#153802 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#153803 = VECTOR('',#153804,1.); -#153804 = DIRECTION('',(0.E+000,-1.)); -#153805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153806 = PCURVE('',#153381,#153807); -#153807 = DEFINITIONAL_REPRESENTATION('',(#153808),#153812); -#153808 = LINE('',#153809,#153810); -#153809 = CARTESIAN_POINT('',(0.35,0.E+000)); -#153810 = VECTOR('',#153811,1.); -#153811 = DIRECTION('',(0.E+000,-1.)); -#153812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153813 = ORIENTED_EDGE('',*,*,#153814,.F.); -#153814 = EDGE_CURVE('',#153267,#153792,#153815,.T.); -#153815 = SURFACE_CURVE('',#153816,(#153821,#153828),.PCURVE_S1.); -#153816 = CIRCLE('',#153817,1.6E-002); -#153817 = AXIS2_PLACEMENT_3D('',#153818,#153819,#153820); -#153818 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); -#153819 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153820 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#153821 = PCURVE('',#151916,#153822); -#153822 = DEFINITIONAL_REPRESENTATION('',(#153823),#153827); -#153823 = CIRCLE('',#153824,1.6E-002); -#153824 = AXIS2_PLACEMENT_2D('',#153825,#153826); -#153825 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153826 = DIRECTION('',(1.,0.E+000)); -#153827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153828 = PCURVE('',#153303,#153829); -#153829 = DEFINITIONAL_REPRESENTATION('',(#153830),#153833); -#153830 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153831,#153832), +#156179 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#156180 = CARTESIAN_POINT('',(4.782202150464,0.35)); +#156181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156182 = ORIENTED_EDGE('',*,*,#156183,.F.); +#156183 = EDGE_CURVE('',#156184,#156157,#156186,.T.); +#156184 = VERTEX_POINT('',#156185); +#156185 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.475)); +#156186 = SURFACE_CURVE('',#156187,(#156191,#156198),.PCURVE_S1.); +#156187 = LINE('',#156188,#156189); +#156188 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.475)); +#156189 = VECTOR('',#156190,1.); +#156190 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#156191 = PCURVE('',#154308,#156192); +#156192 = DEFINITIONAL_REPRESENTATION('',(#156193),#156197); +#156193 = LINE('',#156194,#156195); +#156194 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#156195 = VECTOR('',#156196,1.); +#156196 = DIRECTION('',(0.E+000,-1.)); +#156197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156198 = PCURVE('',#155773,#156199); +#156199 = DEFINITIONAL_REPRESENTATION('',(#156200),#156204); +#156200 = LINE('',#156201,#156202); +#156201 = CARTESIAN_POINT('',(0.35,0.E+000)); +#156202 = VECTOR('',#156203,1.); +#156203 = DIRECTION('',(0.E+000,-1.)); +#156204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156205 = ORIENTED_EDGE('',*,*,#156206,.F.); +#156206 = EDGE_CURVE('',#155659,#156184,#156207,.T.); +#156207 = SURFACE_CURVE('',#156208,(#156213,#156220),.PCURVE_S1.); +#156208 = CIRCLE('',#156209,1.6E-002); +#156209 = AXIS2_PLACEMENT_3D('',#156210,#156211,#156212); +#156210 = CARTESIAN_POINT('',(0.674000000002,0.66733334,0.475)); +#156211 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156212 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156213 = PCURVE('',#154308,#156214); +#156214 = DEFINITIONAL_REPRESENTATION('',(#156215),#156219); +#156215 = CIRCLE('',#156216,1.6E-002); +#156216 = AXIS2_PLACEMENT_2D('',#156217,#156218); +#156217 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156218 = DIRECTION('',(1.,0.E+000)); +#156219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156220 = PCURVE('',#155695,#156221); +#156221 = DEFINITIONAL_REPRESENTATION('',(#156222),#156225); +#156222 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156223,#156224), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#153831 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#153832 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#153833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153834 = ORIENTED_EDGE('',*,*,#153266,.F.); -#153835 = ADVANCED_FACE('',(#153836),#153303,.F.); -#153836 = FACE_BOUND('',#153837,.F.); -#153837 = EDGE_LOOP('',(#153838,#153839,#153840,#153841)); -#153838 = ORIENTED_EDGE('',*,*,#153814,.F.); -#153839 = ORIENTED_EDGE('',*,*,#153289,.F.); -#153840 = ORIENTED_EDGE('',*,*,#153342,.T.); -#153841 = ORIENTED_EDGE('',*,*,#153842,.T.); -#153842 = EDGE_CURVE('',#153343,#153792,#153843,.T.); -#153843 = SURFACE_CURVE('',#153844,(#153848,#153854),.PCURVE_S1.); -#153844 = LINE('',#153845,#153846); -#153845 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); -#153846 = VECTOR('',#153847,1.); -#153847 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153848 = PCURVE('',#153303,#153849); -#153849 = DEFINITIONAL_REPRESENTATION('',(#153850),#153853); -#153850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153851,#153852), +#156223 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#156224 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#156225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156226 = ORIENTED_EDGE('',*,*,#155658,.F.); +#156227 = ADVANCED_FACE('',(#156228),#155695,.F.); +#156228 = FACE_BOUND('',#156229,.F.); +#156229 = EDGE_LOOP('',(#156230,#156231,#156232,#156233)); +#156230 = ORIENTED_EDGE('',*,*,#156206,.F.); +#156231 = ORIENTED_EDGE('',*,*,#155681,.F.); +#156232 = ORIENTED_EDGE('',*,*,#155734,.T.); +#156233 = ORIENTED_EDGE('',*,*,#156234,.T.); +#156234 = EDGE_CURVE('',#155735,#156184,#156235,.T.); +#156235 = SURFACE_CURVE('',#156236,(#156240,#156246),.PCURVE_S1.); +#156236 = LINE('',#156237,#156238); +#156237 = CARTESIAN_POINT('',(0.690000000002,0.66733334,0.825)); +#156238 = VECTOR('',#156239,1.); +#156239 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156240 = PCURVE('',#155695,#156241); +#156241 = DEFINITIONAL_REPRESENTATION('',(#156242),#156245); +#156242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156243,#156244), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#153851 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#153852 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#153853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153854 = PCURVE('',#153381,#153855); -#153855 = DEFINITIONAL_REPRESENTATION('',(#153856),#153860); -#153856 = LINE('',#153857,#153858); -#153857 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153858 = VECTOR('',#153859,1.); -#153859 = DIRECTION('',(1.,0.E+000)); -#153860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153861 = ADVANCED_FACE('',(#153862),#153381,.F.); -#153862 = FACE_BOUND('',#153863,.T.); -#153863 = EDGE_LOOP('',(#153864,#153865,#153908,#153909)); -#153864 = ORIENTED_EDGE('',*,*,#153791,.T.); -#153865 = ORIENTED_EDGE('',*,*,#153866,.F.); -#153866 = EDGE_CURVE('',#153366,#153765,#153867,.T.); -#153867 = SURFACE_CURVE('',#153868,(#153872,#153879),.PCURVE_S1.); -#153868 = LINE('',#153869,#153870); -#153869 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.825) - ); -#153870 = VECTOR('',#153871,1.); -#153871 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153872 = PCURVE('',#153381,#153873); -#153873 = DEFINITIONAL_REPRESENTATION('',(#153874),#153878); -#153874 = LINE('',#153875,#153876); -#153875 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#153876 = VECTOR('',#153877,1.); -#153877 = DIRECTION('',(1.,0.E+000)); -#153878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153879 = PCURVE('',#153414,#153880); -#153880 = DEFINITIONAL_REPRESENTATION('',(#153881),#153907); -#153881 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#153882,#153883,#153884, - #153885,#153886,#153887,#153888,#153889,#153890,#153891,#153892, - #153893,#153894,#153895,#153896,#153897,#153898,#153899,#153900, - #153901,#153902,#153903,#153904,#153905,#153906),.UNSPECIFIED.,.F., +#156243 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#156244 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#156245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156246 = PCURVE('',#155773,#156247); +#156247 = DEFINITIONAL_REPRESENTATION('',(#156248),#156252); +#156248 = LINE('',#156249,#156250); +#156249 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156250 = VECTOR('',#156251,1.); +#156251 = DIRECTION('',(1.,0.E+000)); +#156252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156253 = ADVANCED_FACE('',(#156254),#155773,.F.); +#156254 = FACE_BOUND('',#156255,.T.); +#156255 = EDGE_LOOP('',(#156256,#156257,#156300,#156301)); +#156256 = ORIENTED_EDGE('',*,*,#156183,.T.); +#156257 = ORIENTED_EDGE('',*,*,#156258,.F.); +#156258 = EDGE_CURVE('',#155758,#156157,#156259,.T.); +#156259 = SURFACE_CURVE('',#156260,(#156264,#156271),.PCURVE_S1.); +#156260 = LINE('',#156261,#156262); +#156261 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,0.825) + ); +#156262 = VECTOR('',#156263,1.); +#156263 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156264 = PCURVE('',#155773,#156265); +#156265 = DEFINITIONAL_REPRESENTATION('',(#156266),#156270); +#156266 = LINE('',#156267,#156268); +#156267 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#156268 = VECTOR('',#156269,1.); +#156269 = DIRECTION('',(1.,0.E+000)); +#156270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156271 = PCURVE('',#155806,#156272); +#156272 = DEFINITIONAL_REPRESENTATION('',(#156273),#156299); +#156273 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156274,#156275,#156276, + #156277,#156278,#156279,#156280,#156281,#156282,#156283,#156284, + #156285,#156286,#156287,#156288,#156289,#156290,#156291,#156292, + #156293,#156294,#156295,#156296,#156297,#156298),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.590909090909E-002,3.181818181818E-002,4.772727272727E-002, 6.363636363636E-002,7.954545454545E-002,9.545454545455E-002, @@ -189753,3165 +192755,3165 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.190909090909,0.206818181818,0.222727272727,0.238636363636, 0.254545454545,0.270454545455,0.286363636364,0.302272727273, 0.318181818182,0.334090909091,0.35),.QUASI_UNIFORM_KNOTS.); -#153882 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#153883 = CARTESIAN_POINT('',(6.28318530718,5.30303030303E-003)); -#153884 = CARTESIAN_POINT('',(6.28318530718,1.590909090909E-002)); -#153885 = CARTESIAN_POINT('',(6.28318530718,3.181818181818E-002)); -#153886 = CARTESIAN_POINT('',(6.28318530718,4.772727272727E-002)); -#153887 = CARTESIAN_POINT('',(6.28318530718,6.363636363636E-002)); -#153888 = CARTESIAN_POINT('',(6.28318530718,7.954545454545E-002)); -#153889 = CARTESIAN_POINT('',(6.28318530718,9.545454545455E-002)); -#153890 = CARTESIAN_POINT('',(6.28318530718,0.111363636364)); -#153891 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#153892 = CARTESIAN_POINT('',(6.28318530718,0.143181818182)); -#153893 = CARTESIAN_POINT('',(6.28318530718,0.159090909091)); -#153894 = CARTESIAN_POINT('',(6.28318530718,0.175)); -#153895 = CARTESIAN_POINT('',(6.28318530718,0.190909090909)); -#153896 = CARTESIAN_POINT('',(6.28318530718,0.206818181818)); -#153897 = CARTESIAN_POINT('',(6.28318530718,0.222727272727)); -#153898 = CARTESIAN_POINT('',(6.28318530718,0.238636363636)); -#153899 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#153900 = CARTESIAN_POINT('',(6.28318530718,0.270454545455)); -#153901 = CARTESIAN_POINT('',(6.28318530718,0.286363636364)); -#153902 = CARTESIAN_POINT('',(6.28318530718,0.302272727273)); -#153903 = CARTESIAN_POINT('',(6.28318530718,0.318181818182)); -#153904 = CARTESIAN_POINT('',(6.28318530718,0.334090909091)); -#153905 = CARTESIAN_POINT('',(6.28318530718,0.344696969697)); -#153906 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#153907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153908 = ORIENTED_EDGE('',*,*,#153365,.F.); -#153909 = ORIENTED_EDGE('',*,*,#153842,.T.); -#153910 = ADVANCED_FACE('',(#153911),#153414,.T.); -#153911 = FACE_BOUND('',#153912,.T.); -#153912 = EDGE_LOOP('',(#153913,#153914,#153934,#153935)); -#153913 = ORIENTED_EDGE('',*,*,#153764,.T.); -#153914 = ORIENTED_EDGE('',*,*,#153915,.F.); -#153915 = EDGE_CURVE('',#153394,#153742,#153916,.T.); -#153916 = SURFACE_CURVE('',#153917,(#153921,#153927),.PCURVE_S1.); -#153917 = LINE('',#153918,#153919); -#153918 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) - ); -#153919 = VECTOR('',#153920,1.); -#153920 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153921 = PCURVE('',#153414,#153922); -#153922 = DEFINITIONAL_REPRESENTATION('',(#153923),#153926); -#153923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#153924,#153925), +#156274 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#156275 = CARTESIAN_POINT('',(6.28318530718,5.30303030303E-003)); +#156276 = CARTESIAN_POINT('',(6.28318530718,1.590909090909E-002)); +#156277 = CARTESIAN_POINT('',(6.28318530718,3.181818181818E-002)); +#156278 = CARTESIAN_POINT('',(6.28318530718,4.772727272727E-002)); +#156279 = CARTESIAN_POINT('',(6.28318530718,6.363636363636E-002)); +#156280 = CARTESIAN_POINT('',(6.28318530718,7.954545454545E-002)); +#156281 = CARTESIAN_POINT('',(6.28318530718,9.545454545455E-002)); +#156282 = CARTESIAN_POINT('',(6.28318530718,0.111363636364)); +#156283 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#156284 = CARTESIAN_POINT('',(6.28318530718,0.143181818182)); +#156285 = CARTESIAN_POINT('',(6.28318530718,0.159090909091)); +#156286 = CARTESIAN_POINT('',(6.28318530718,0.175)); +#156287 = CARTESIAN_POINT('',(6.28318530718,0.190909090909)); +#156288 = CARTESIAN_POINT('',(6.28318530718,0.206818181818)); +#156289 = CARTESIAN_POINT('',(6.28318530718,0.222727272727)); +#156290 = CARTESIAN_POINT('',(6.28318530718,0.238636363636)); +#156291 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#156292 = CARTESIAN_POINT('',(6.28318530718,0.270454545455)); +#156293 = CARTESIAN_POINT('',(6.28318530718,0.286363636364)); +#156294 = CARTESIAN_POINT('',(6.28318530718,0.302272727273)); +#156295 = CARTESIAN_POINT('',(6.28318530718,0.318181818182)); +#156296 = CARTESIAN_POINT('',(6.28318530718,0.334090909091)); +#156297 = CARTESIAN_POINT('',(6.28318530718,0.344696969697)); +#156298 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#156299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156300 = ORIENTED_EDGE('',*,*,#155757,.F.); +#156301 = ORIENTED_EDGE('',*,*,#156234,.T.); +#156302 = ADVANCED_FACE('',(#156303),#155806,.T.); +#156303 = FACE_BOUND('',#156304,.T.); +#156304 = EDGE_LOOP('',(#156305,#156306,#156326,#156327)); +#156305 = ORIENTED_EDGE('',*,*,#156156,.T.); +#156306 = ORIENTED_EDGE('',*,*,#156307,.F.); +#156307 = EDGE_CURVE('',#155786,#156134,#156308,.T.); +#156308 = SURFACE_CURVE('',#156309,(#156313,#156319),.PCURVE_S1.); +#156309 = LINE('',#156310,#156311); +#156310 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,0.825) + ); +#156311 = VECTOR('',#156312,1.); +#156312 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156313 = PCURVE('',#155806,#156314); +#156314 = DEFINITIONAL_REPRESENTATION('',(#156315),#156318); +#156315 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156316,#156317), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#153924 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#153925 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#153926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153927 = PCURVE('',#153441,#153928); -#153928 = DEFINITIONAL_REPRESENTATION('',(#153929),#153933); -#153929 = LINE('',#153930,#153931); -#153930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153931 = VECTOR('',#153932,1.); -#153932 = DIRECTION('',(0.E+000,-1.)); -#153933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153934 = ORIENTED_EDGE('',*,*,#153393,.F.); -#153935 = ORIENTED_EDGE('',*,*,#153866,.T.); -#153936 = ADVANCED_FACE('',(#153937),#153441,.F.); -#153937 = FACE_BOUND('',#153938,.T.); -#153938 = EDGE_LOOP('',(#153939,#153940,#153961,#153962)); -#153939 = ORIENTED_EDGE('',*,*,#153741,.T.); -#153940 = ORIENTED_EDGE('',*,*,#153941,.F.); -#153941 = EDGE_CURVE('',#153426,#153719,#153942,.T.); -#153942 = SURFACE_CURVE('',#153943,(#153947,#153954),.PCURVE_S1.); -#153943 = LINE('',#153944,#153945); -#153944 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); -#153945 = VECTOR('',#153946,1.); -#153946 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153947 = PCURVE('',#153441,#153948); -#153948 = DEFINITIONAL_REPRESENTATION('',(#153949),#153953); -#153949 = LINE('',#153950,#153951); -#153950 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); -#153951 = VECTOR('',#153952,1.); -#153952 = DIRECTION('',(0.E+000,-1.)); -#153953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153954 = PCURVE('',#153469,#153955); -#153955 = DEFINITIONAL_REPRESENTATION('',(#153956),#153960); -#153956 = LINE('',#153957,#153958); -#153957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#153958 = VECTOR('',#153959,1.); -#153959 = DIRECTION('',(0.E+000,-1.)); -#153960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153961 = ORIENTED_EDGE('',*,*,#153425,.F.); -#153962 = ORIENTED_EDGE('',*,*,#153915,.T.); -#153963 = ADVANCED_FACE('',(#153964),#153469,.F.); -#153964 = FACE_BOUND('',#153965,.T.); -#153965 = EDGE_LOOP('',(#153966,#153967,#153988,#153989)); -#153966 = ORIENTED_EDGE('',*,*,#153718,.T.); -#153967 = ORIENTED_EDGE('',*,*,#153968,.F.); -#153968 = EDGE_CURVE('',#153454,#153696,#153969,.T.); -#153969 = SURFACE_CURVE('',#153970,(#153974,#153981),.PCURVE_S1.); -#153970 = LINE('',#153971,#153972); -#153971 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.825)); -#153972 = VECTOR('',#153973,1.); -#153973 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#153974 = PCURVE('',#153469,#153975); -#153975 = DEFINITIONAL_REPRESENTATION('',(#153976),#153980); -#153976 = LINE('',#153977,#153978); -#153977 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#153978 = VECTOR('',#153979,1.); -#153979 = DIRECTION('',(0.E+000,-1.)); -#153980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153981 = PCURVE('',#153497,#153982); -#153982 = DEFINITIONAL_REPRESENTATION('',(#153983),#153987); -#153983 = LINE('',#153984,#153985); -#153984 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); -#153985 = VECTOR('',#153986,1.); -#153986 = DIRECTION('',(0.E+000,-1.)); -#153987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#153988 = ORIENTED_EDGE('',*,*,#153453,.F.); -#153989 = ORIENTED_EDGE('',*,*,#153941,.T.); -#153990 = ADVANCED_FACE('',(#153991),#153497,.F.); -#153991 = FACE_BOUND('',#153992,.T.); -#153992 = EDGE_LOOP('',(#153993,#153994,#154014,#154015)); -#153993 = ORIENTED_EDGE('',*,*,#153695,.T.); -#153994 = ORIENTED_EDGE('',*,*,#153995,.F.); -#153995 = EDGE_CURVE('',#153482,#153673,#153996,.T.); -#153996 = SURFACE_CURVE('',#153997,(#154001,#154008),.PCURVE_S1.); -#153997 = LINE('',#153998,#153999); -#153998 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.825) - ); -#153999 = VECTOR('',#154000,1.); -#154000 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154001 = PCURVE('',#153497,#154002); -#154002 = DEFINITIONAL_REPRESENTATION('',(#154003),#154007); -#154003 = LINE('',#154004,#154005); -#154004 = CARTESIAN_POINT('',(-1.112358904841E-016,0.E+000)); -#154005 = VECTOR('',#154006,1.); -#154006 = DIRECTION('',(0.E+000,-1.)); -#154007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154008 = PCURVE('',#153526,#154009); -#154009 = DEFINITIONAL_REPRESENTATION('',(#154010),#154013); -#154010 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154011,#154012), +#156316 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#156317 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#156318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156319 = PCURVE('',#155833,#156320); +#156320 = DEFINITIONAL_REPRESENTATION('',(#156321),#156325); +#156321 = LINE('',#156322,#156323); +#156322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156323 = VECTOR('',#156324,1.); +#156324 = DIRECTION('',(0.E+000,-1.)); +#156325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156326 = ORIENTED_EDGE('',*,*,#155785,.F.); +#156327 = ORIENTED_EDGE('',*,*,#156258,.T.); +#156328 = ADVANCED_FACE('',(#156329),#155833,.F.); +#156329 = FACE_BOUND('',#156330,.T.); +#156330 = EDGE_LOOP('',(#156331,#156332,#156353,#156354)); +#156331 = ORIENTED_EDGE('',*,*,#156133,.T.); +#156332 = ORIENTED_EDGE('',*,*,#156333,.F.); +#156333 = EDGE_CURVE('',#155818,#156111,#156334,.T.); +#156334 = SURFACE_CURVE('',#156335,(#156339,#156346),.PCURVE_S1.); +#156335 = LINE('',#156336,#156337); +#156336 = CARTESIAN_POINT('',(1.05,0.E+000,0.825)); +#156337 = VECTOR('',#156338,1.); +#156338 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156339 = PCURVE('',#155833,#156340); +#156340 = DEFINITIONAL_REPRESENTATION('',(#156341),#156345); +#156341 = LINE('',#156342,#156343); +#156342 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); +#156343 = VECTOR('',#156344,1.); +#156344 = DIRECTION('',(0.E+000,-1.)); +#156345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156346 = PCURVE('',#155861,#156347); +#156347 = DEFINITIONAL_REPRESENTATION('',(#156348),#156352); +#156348 = LINE('',#156349,#156350); +#156349 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156350 = VECTOR('',#156351,1.); +#156351 = DIRECTION('',(0.E+000,-1.)); +#156352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156353 = ORIENTED_EDGE('',*,*,#155817,.F.); +#156354 = ORIENTED_EDGE('',*,*,#156307,.T.); +#156355 = ADVANCED_FACE('',(#156356),#155861,.F.); +#156356 = FACE_BOUND('',#156357,.T.); +#156357 = EDGE_LOOP('',(#156358,#156359,#156380,#156381)); +#156358 = ORIENTED_EDGE('',*,*,#156110,.T.); +#156359 = ORIENTED_EDGE('',*,*,#156360,.F.); +#156360 = EDGE_CURVE('',#155846,#156088,#156361,.T.); +#156361 = SURFACE_CURVE('',#156362,(#156366,#156373),.PCURVE_S1.); +#156362 = LINE('',#156363,#156364); +#156363 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,0.825)); +#156364 = VECTOR('',#156365,1.); +#156365 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156366 = PCURVE('',#155861,#156367); +#156367 = DEFINITIONAL_REPRESENTATION('',(#156368),#156372); +#156368 = LINE('',#156369,#156370); +#156369 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#156370 = VECTOR('',#156371,1.); +#156371 = DIRECTION('',(0.E+000,-1.)); +#156372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156373 = PCURVE('',#155889,#156374); +#156374 = DEFINITIONAL_REPRESENTATION('',(#156375),#156379); +#156375 = LINE('',#156376,#156377); +#156376 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); +#156377 = VECTOR('',#156378,1.); +#156378 = DIRECTION('',(0.E+000,-1.)); +#156379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156380 = ORIENTED_EDGE('',*,*,#155845,.F.); +#156381 = ORIENTED_EDGE('',*,*,#156333,.T.); +#156382 = ADVANCED_FACE('',(#156383),#155889,.F.); +#156383 = FACE_BOUND('',#156384,.T.); +#156384 = EDGE_LOOP('',(#156385,#156386,#156406,#156407)); +#156385 = ORIENTED_EDGE('',*,*,#156087,.T.); +#156386 = ORIENTED_EDGE('',*,*,#156387,.F.); +#156387 = EDGE_CURVE('',#155874,#156065,#156388,.T.); +#156388 = SURFACE_CURVE('',#156389,(#156393,#156400),.PCURVE_S1.); +#156389 = LINE('',#156390,#156391); +#156390 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,0.825) + ); +#156391 = VECTOR('',#156392,1.); +#156392 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156393 = PCURVE('',#155889,#156394); +#156394 = DEFINITIONAL_REPRESENTATION('',(#156395),#156399); +#156395 = LINE('',#156396,#156397); +#156396 = CARTESIAN_POINT('',(-1.112358904841E-016,0.E+000)); +#156397 = VECTOR('',#156398,1.); +#156398 = DIRECTION('',(0.E+000,-1.)); +#156399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156400 = PCURVE('',#155918,#156401); +#156401 = DEFINITIONAL_REPRESENTATION('',(#156402),#156405); +#156402 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156403,#156404), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154011 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#154012 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#154013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154014 = ORIENTED_EDGE('',*,*,#153481,.F.); -#154015 = ORIENTED_EDGE('',*,*,#153968,.T.); -#154016 = ADVANCED_FACE('',(#154017),#153526,.F.); -#154017 = FACE_BOUND('',#154018,.F.); -#154018 = EDGE_LOOP('',(#154019,#154020,#154021,#154022)); -#154019 = ORIENTED_EDGE('',*,*,#153672,.F.); -#154020 = ORIENTED_EDGE('',*,*,#153995,.F.); -#154021 = ORIENTED_EDGE('',*,*,#153509,.T.); -#154022 = ORIENTED_EDGE('',*,*,#154023,.T.); -#154023 = EDGE_CURVE('',#153510,#153650,#154024,.T.); -#154024 = SURFACE_CURVE('',#154025,(#154029,#154035),.PCURVE_S1.); -#154025 = LINE('',#154026,#154027); -#154026 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.825) - ); -#154027 = VECTOR('',#154028,1.); -#154028 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154029 = PCURVE('',#153526,#154030); -#154030 = DEFINITIONAL_REPRESENTATION('',(#154031),#154034); -#154031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154032,#154033), +#156403 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#156404 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#156405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156406 = ORIENTED_EDGE('',*,*,#155873,.F.); +#156407 = ORIENTED_EDGE('',*,*,#156360,.T.); +#156408 = ADVANCED_FACE('',(#156409),#155918,.F.); +#156409 = FACE_BOUND('',#156410,.F.); +#156410 = EDGE_LOOP('',(#156411,#156412,#156413,#156414)); +#156411 = ORIENTED_EDGE('',*,*,#156064,.F.); +#156412 = ORIENTED_EDGE('',*,*,#156387,.F.); +#156413 = ORIENTED_EDGE('',*,*,#155901,.T.); +#156414 = ORIENTED_EDGE('',*,*,#156415,.T.); +#156415 = EDGE_CURVE('',#155902,#156042,#156416,.T.); +#156416 = SURFACE_CURVE('',#156417,(#156421,#156427),.PCURVE_S1.); +#156417 = LINE('',#156418,#156419); +#156418 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,0.825) + ); +#156419 = VECTOR('',#156420,1.); +#156420 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156421 = PCURVE('',#155918,#156422); +#156422 = DEFINITIONAL_REPRESENTATION('',(#156423),#156426); +#156423 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156424,#156425), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154032 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#154033 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#154034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154035 = PCURVE('',#153553,#154036); -#154036 = DEFINITIONAL_REPRESENTATION('',(#154037),#154041); -#154037 = LINE('',#154038,#154039); -#154038 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#154039 = VECTOR('',#154040,1.); -#154040 = DIRECTION('',(-1.,0.E+000)); -#154041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154042 = ADVANCED_FACE('',(#154043),#153553,.F.); -#154043 = FACE_BOUND('',#154044,.T.); -#154044 = EDGE_LOOP('',(#154045,#154046,#154066,#154067)); -#154045 = ORIENTED_EDGE('',*,*,#153649,.T.); -#154046 = ORIENTED_EDGE('',*,*,#154047,.F.); -#154047 = EDGE_CURVE('',#153538,#153623,#154048,.T.); -#154048 = SURFACE_CURVE('',#154049,(#154053,#154060),.PCURVE_S1.); -#154049 = LINE('',#154050,#154051); -#154050 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); -#154051 = VECTOR('',#154052,1.); -#154052 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154053 = PCURVE('',#153553,#154054); -#154054 = DEFINITIONAL_REPRESENTATION('',(#154055),#154059); -#154055 = LINE('',#154056,#154057); -#154056 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154057 = VECTOR('',#154058,1.); -#154058 = DIRECTION('',(-1.,0.E+000)); -#154059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154060 = PCURVE('',#153584,#154061); -#154061 = DEFINITIONAL_REPRESENTATION('',(#154062),#154065); -#154062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154063,#154064), +#156424 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#156425 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#156426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156427 = PCURVE('',#155945,#156428); +#156428 = DEFINITIONAL_REPRESENTATION('',(#156429),#156433); +#156429 = LINE('',#156430,#156431); +#156430 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#156431 = VECTOR('',#156432,1.); +#156432 = DIRECTION('',(-1.,0.E+000)); +#156433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156434 = ADVANCED_FACE('',(#156435),#155945,.F.); +#156435 = FACE_BOUND('',#156436,.T.); +#156436 = EDGE_LOOP('',(#156437,#156438,#156458,#156459)); +#156437 = ORIENTED_EDGE('',*,*,#156041,.T.); +#156438 = ORIENTED_EDGE('',*,*,#156439,.F.); +#156439 = EDGE_CURVE('',#155930,#156015,#156440,.T.); +#156440 = SURFACE_CURVE('',#156441,(#156445,#156452),.PCURVE_S1.); +#156441 = LINE('',#156442,#156443); +#156442 = CARTESIAN_POINT('',(0.706000000002,0.66733334,0.825)); +#156443 = VECTOR('',#156444,1.); +#156444 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156445 = PCURVE('',#155945,#156446); +#156446 = DEFINITIONAL_REPRESENTATION('',(#156447),#156451); +#156447 = LINE('',#156448,#156449); +#156448 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156449 = VECTOR('',#156450,1.); +#156450 = DIRECTION('',(-1.,0.E+000)); +#156451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156452 = PCURVE('',#155976,#156453); +#156453 = DEFINITIONAL_REPRESENTATION('',(#156454),#156457); +#156454 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156455,#156456), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154063 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#154064 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#154065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154066 = ORIENTED_EDGE('',*,*,#153537,.F.); -#154067 = ORIENTED_EDGE('',*,*,#154023,.T.); -#154068 = ADVANCED_FACE('',(#154069),#153584,.T.); -#154069 = FACE_BOUND('',#154070,.T.); -#154070 = EDGE_LOOP('',(#154071,#154072,#154092,#154093)); -#154071 = ORIENTED_EDGE('',*,*,#153622,.T.); -#154072 = ORIENTED_EDGE('',*,*,#154073,.F.); -#154073 = EDGE_CURVE('',#153318,#153600,#154074,.T.); -#154074 = SURFACE_CURVE('',#154075,(#154079,#154085),.PCURVE_S1.); -#154075 = LINE('',#154076,#154077); -#154076 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.825)); -#154077 = VECTOR('',#154078,1.); -#154078 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154079 = PCURVE('',#153584,#154080); -#154080 = DEFINITIONAL_REPRESENTATION('',(#154081),#154084); -#154081 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154082,#154083), +#156455 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#156456 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#156457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156458 = ORIENTED_EDGE('',*,*,#155929,.F.); +#156459 = ORIENTED_EDGE('',*,*,#156415,.T.); +#156460 = ADVANCED_FACE('',(#156461),#155976,.T.); +#156461 = FACE_BOUND('',#156462,.T.); +#156462 = EDGE_LOOP('',(#156463,#156464,#156484,#156485)); +#156463 = ORIENTED_EDGE('',*,*,#156014,.T.); +#156464 = ORIENTED_EDGE('',*,*,#156465,.F.); +#156465 = EDGE_CURVE('',#155710,#155992,#156466,.T.); +#156466 = SURFACE_CURVE('',#156467,(#156471,#156477),.PCURVE_S1.); +#156467 = LINE('',#156468,#156469); +#156468 = CARTESIAN_POINT('',(0.674000000002,0.69933334,0.825)); +#156469 = VECTOR('',#156470,1.); +#156470 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156471 = PCURVE('',#155976,#156472); +#156472 = DEFINITIONAL_REPRESENTATION('',(#156473),#156476); +#156473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156474,#156475), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154082 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154083 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#156474 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#156475 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#156476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#154085 = PCURVE('',#151888,#154086); -#154086 = DEFINITIONAL_REPRESENTATION('',(#154087),#154091); -#154087 = LINE('',#154088,#154089); -#154088 = CARTESIAN_POINT('',(0.E+000,0.100681667766)); -#154089 = VECTOR('',#154090,1.); -#154090 = DIRECTION('',(1.,0.E+000)); -#154091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154092 = ORIENTED_EDGE('',*,*,#153565,.F.); -#154093 = ORIENTED_EDGE('',*,*,#154047,.T.); -#154094 = ADVANCED_FACE('',(#154095),#151888,.F.); -#154095 = FACE_BOUND('',#154096,.T.); -#154096 = EDGE_LOOP('',(#154097,#154098,#154099,#154100)); -#154097 = ORIENTED_EDGE('',*,*,#153599,.T.); -#154098 = ORIENTED_EDGE('',*,*,#151872,.F.); -#154099 = ORIENTED_EDGE('',*,*,#153317,.F.); -#154100 = ORIENTED_EDGE('',*,*,#154073,.T.); -#154101 = ADVANCED_FACE('',(#154102),#152272,.T.); -#154102 = FACE_BOUND('',#154103,.T.); -#154103 = EDGE_LOOP('',(#154104,#154105,#154128,#154155)); -#154104 = ORIENTED_EDGE('',*,*,#152258,.T.); -#154105 = ORIENTED_EDGE('',*,*,#154106,.T.); -#154106 = EDGE_CURVE('',#151690,#154107,#154109,.T.); -#154107 = VERTEX_POINT('',#154108); -#154108 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.825)); -#154109 = SURFACE_CURVE('',#154110,(#154114,#154121),.PCURVE_S1.); -#154110 = LINE('',#154111,#154112); -#154111 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.825)); -#154112 = VECTOR('',#154113,1.); -#154113 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); -#154114 = PCURVE('',#152272,#154115); -#154115 = DEFINITIONAL_REPRESENTATION('',(#154116),#154120); -#154116 = LINE('',#154117,#154118); -#154117 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154118 = VECTOR('',#154119,1.); -#154119 = DIRECTION('',(1.,0.E+000)); -#154120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154121 = PCURVE('',#151712,#154122); -#154122 = DEFINITIONAL_REPRESENTATION('',(#154123),#154127); -#154123 = LINE('',#154124,#154125); -#154124 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); -#154125 = VECTOR('',#154126,1.); -#154126 = DIRECTION('',(-1.,1.07686155438E-015)); -#154127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154128 = ORIENTED_EDGE('',*,*,#154129,.T.); -#154129 = EDGE_CURVE('',#154107,#154130,#154132,.T.); -#154130 = VERTEX_POINT('',#154131); -#154131 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.475)); -#154132 = SURFACE_CURVE('',#154133,(#154137,#154144),.PCURVE_S1.); -#154133 = LINE('',#154134,#154135); -#154134 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.825)); -#154135 = VECTOR('',#154136,1.); -#154136 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154137 = PCURVE('',#152272,#154138); -#154138 = DEFINITIONAL_REPRESENTATION('',(#154139),#154143); -#154139 = LINE('',#154140,#154141); -#154140 = CARTESIAN_POINT('',(0.100681667766,0.E+000)); -#154141 = VECTOR('',#154142,1.); -#154142 = DIRECTION('',(0.E+000,1.)); -#154143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154144 = PCURVE('',#154145,#154150); -#154145 = CYLINDRICAL_SURFACE('',#154146,1.6E-002); -#154146 = AXIS2_PLACEMENT_3D('',#154147,#154148,#154149); -#154147 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); -#154148 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154149 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154150 = DEFINITIONAL_REPRESENTATION('',(#154151),#154154); -#154151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154152,#154153), +#156477 = PCURVE('',#154280,#156478); +#156478 = DEFINITIONAL_REPRESENTATION('',(#156479),#156483); +#156479 = LINE('',#156480,#156481); +#156480 = CARTESIAN_POINT('',(0.E+000,0.100681667766)); +#156481 = VECTOR('',#156482,1.); +#156482 = DIRECTION('',(1.,0.E+000)); +#156483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156484 = ORIENTED_EDGE('',*,*,#155957,.F.); +#156485 = ORIENTED_EDGE('',*,*,#156439,.T.); +#156486 = ADVANCED_FACE('',(#156487),#154280,.F.); +#156487 = FACE_BOUND('',#156488,.T.); +#156488 = EDGE_LOOP('',(#156489,#156490,#156491,#156492)); +#156489 = ORIENTED_EDGE('',*,*,#155991,.T.); +#156490 = ORIENTED_EDGE('',*,*,#154264,.F.); +#156491 = ORIENTED_EDGE('',*,*,#155709,.F.); +#156492 = ORIENTED_EDGE('',*,*,#156465,.T.); +#156493 = ADVANCED_FACE('',(#156494),#154664,.T.); +#156494 = FACE_BOUND('',#156495,.T.); +#156495 = EDGE_LOOP('',(#156496,#156497,#156520,#156547)); +#156496 = ORIENTED_EDGE('',*,*,#154650,.T.); +#156497 = ORIENTED_EDGE('',*,*,#156498,.T.); +#156498 = EDGE_CURVE('',#154082,#156499,#156501,.T.); +#156499 = VERTEX_POINT('',#156500); +#156500 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.825)); +#156501 = SURFACE_CURVE('',#156502,(#156506,#156513),.PCURVE_S1.); +#156502 = LINE('',#156503,#156504); +#156503 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.825)); +#156504 = VECTOR('',#156505,1.); +#156505 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); +#156506 = PCURVE('',#154664,#156507); +#156507 = DEFINITIONAL_REPRESENTATION('',(#156508),#156512); +#156508 = LINE('',#156509,#156510); +#156509 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156510 = VECTOR('',#156511,1.); +#156511 = DIRECTION('',(1.,0.E+000)); +#156512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156513 = PCURVE('',#154104,#156514); +#156514 = DEFINITIONAL_REPRESENTATION('',(#156515),#156519); +#156515 = LINE('',#156516,#156517); +#156516 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); +#156517 = VECTOR('',#156518,1.); +#156518 = DIRECTION('',(-1.,1.07686155438E-015)); +#156519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156520 = ORIENTED_EDGE('',*,*,#156521,.T.); +#156521 = EDGE_CURVE('',#156499,#156522,#156524,.T.); +#156522 = VERTEX_POINT('',#156523); +#156523 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.475)); +#156524 = SURFACE_CURVE('',#156525,(#156529,#156536),.PCURVE_S1.); +#156525 = LINE('',#156526,#156527); +#156526 = CARTESIAN_POINT('',(0.674000000002,0.68333334,-0.825)); +#156527 = VECTOR('',#156528,1.); +#156528 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156529 = PCURVE('',#154664,#156530); +#156530 = DEFINITIONAL_REPRESENTATION('',(#156531),#156535); +#156531 = LINE('',#156532,#156533); +#156532 = CARTESIAN_POINT('',(0.100681667766,0.E+000)); +#156533 = VECTOR('',#156534,1.); +#156534 = DIRECTION('',(0.E+000,1.)); +#156535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156536 = PCURVE('',#156537,#156542); +#156537 = CYLINDRICAL_SURFACE('',#156538,1.6E-002); +#156538 = AXIS2_PLACEMENT_3D('',#156539,#156540,#156541); +#156539 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); +#156540 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156541 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156542 = DEFINITIONAL_REPRESENTATION('',(#156543),#156546); +#156543 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156544,#156545), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154152 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154153 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154155 = ORIENTED_EDGE('',*,*,#154156,.F.); -#154156 = EDGE_CURVE('',#151929,#154130,#154157,.T.); -#154157 = SURFACE_CURVE('',#154158,(#154162,#154169),.PCURVE_S1.); -#154158 = LINE('',#154159,#154160); -#154159 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.475)); -#154160 = VECTOR('',#154161,1.); -#154161 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); -#154162 = PCURVE('',#152272,#154163); -#154163 = DEFINITIONAL_REPRESENTATION('',(#154164),#154168); -#154164 = LINE('',#154165,#154166); -#154165 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154166 = VECTOR('',#154167,1.); -#154167 = DIRECTION('',(1.,0.E+000)); -#154168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154169 = PCURVE('',#151967,#154170); -#154170 = DEFINITIONAL_REPRESENTATION('',(#154171),#154175); -#154171 = LINE('',#154172,#154173); -#154172 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); -#154173 = VECTOR('',#154174,1.); -#154174 = DIRECTION('',(-1.,1.07686155438E-015)); -#154175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154176 = ADVANCED_FACE('',(#154177),#151712,.F.); -#154177 = FACE_BOUND('',#154178,.T.); -#154178 = EDGE_LOOP('',(#154179,#154180,#154181,#154204,#154232,#154260, - #154292,#154320,#154348,#154376,#154404,#154432)); -#154179 = ORIENTED_EDGE('',*,*,#154106,.F.); -#154180 = ORIENTED_EDGE('',*,*,#151689,.T.); -#154181 = ORIENTED_EDGE('',*,*,#154182,.F.); -#154182 = EDGE_CURVE('',#154183,#151692,#154185,.T.); -#154183 = VERTEX_POINT('',#154184); -#154184 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.825)); -#154185 = SURFACE_CURVE('',#154186,(#154190,#154197),.PCURVE_S1.); -#154186 = LINE('',#154187,#154188); -#154187 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); -#154188 = VECTOR('',#154189,1.); -#154189 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154190 = PCURVE('',#151712,#154191); -#154191 = DEFINITIONAL_REPRESENTATION('',(#154192),#154196); -#154192 = LINE('',#154193,#154194); -#154193 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); -#154194 = VECTOR('',#154195,1.); -#154195 = DIRECTION('',(1.,0.E+000)); -#154196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154197 = PCURVE('',#151993,#154198); -#154198 = DEFINITIONAL_REPRESENTATION('',(#154199),#154203); -#154199 = LINE('',#154200,#154201); -#154200 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154201 = VECTOR('',#154202,1.); -#154202 = DIRECTION('',(0.E+000,-1.)); -#154203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154204 = ORIENTED_EDGE('',*,*,#154205,.F.); -#154205 = EDGE_CURVE('',#154206,#154183,#154208,.T.); -#154206 = VERTEX_POINT('',#154207); -#154207 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); -#154208 = SURFACE_CURVE('',#154209,(#154214,#154221),.PCURVE_S1.); -#154209 = CIRCLE('',#154210,3.2E-002); -#154210 = AXIS2_PLACEMENT_3D('',#154211,#154212,#154213); -#154211 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); -#154212 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154213 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154214 = PCURVE('',#151712,#154215); -#154215 = DEFINITIONAL_REPRESENTATION('',(#154216),#154220); -#154216 = CIRCLE('',#154217,3.2E-002); -#154217 = AXIS2_PLACEMENT_2D('',#154218,#154219); -#154218 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154219 = DIRECTION('',(1.,0.E+000)); -#154220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154221 = PCURVE('',#154222,#154227); -#154222 = CYLINDRICAL_SURFACE('',#154223,3.2E-002); -#154223 = AXIS2_PLACEMENT_3D('',#154224,#154225,#154226); -#154224 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); -#154225 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154226 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154227 = DEFINITIONAL_REPRESENTATION('',(#154228),#154231); -#154228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154229,#154230), +#156544 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#156545 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#156546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156547 = ORIENTED_EDGE('',*,*,#156548,.F.); +#156548 = EDGE_CURVE('',#154321,#156522,#156549,.T.); +#156549 = SURFACE_CURVE('',#156550,(#156554,#156561),.PCURVE_S1.); +#156550 = LINE('',#156551,#156552); +#156551 = CARTESIAN_POINT('',(0.573318332236,0.68333334,-0.475)); +#156552 = VECTOR('',#156553,1.); +#156553 = DIRECTION('',(1.,-1.07686155438E-015,0.E+000)); +#156554 = PCURVE('',#154664,#156555); +#156555 = DEFINITIONAL_REPRESENTATION('',(#156556),#156560); +#156556 = LINE('',#156557,#156558); +#156557 = CARTESIAN_POINT('',(0.E+000,0.35)); +#156558 = VECTOR('',#156559,1.); +#156559 = DIRECTION('',(1.,0.E+000)); +#156560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156561 = PCURVE('',#154359,#156562); +#156562 = DEFINITIONAL_REPRESENTATION('',(#156563),#156567); +#156563 = LINE('',#156564,#156565); +#156564 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); +#156565 = VECTOR('',#156566,1.); +#156566 = DIRECTION('',(-1.,1.07686155438E-015)); +#156567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156568 = ADVANCED_FACE('',(#156569),#154104,.F.); +#156569 = FACE_BOUND('',#156570,.T.); +#156570 = EDGE_LOOP('',(#156571,#156572,#156573,#156596,#156624,#156652, + #156684,#156712,#156740,#156768,#156796,#156824)); +#156571 = ORIENTED_EDGE('',*,*,#156498,.F.); +#156572 = ORIENTED_EDGE('',*,*,#154081,.T.); +#156573 = ORIENTED_EDGE('',*,*,#156574,.F.); +#156574 = EDGE_CURVE('',#156575,#154084,#156577,.T.); +#156575 = VERTEX_POINT('',#156576); +#156576 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.825)); +#156577 = SURFACE_CURVE('',#156578,(#156582,#156589),.PCURVE_S1.); +#156578 = LINE('',#156579,#156580); +#156579 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.825)); +#156580 = VECTOR('',#156581,1.); +#156581 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156582 = PCURVE('',#154104,#156583); +#156583 = DEFINITIONAL_REPRESENTATION('',(#156584),#156588); +#156584 = LINE('',#156585,#156586); +#156585 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); +#156586 = VECTOR('',#156587,1.); +#156587 = DIRECTION('',(1.,0.E+000)); +#156588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156589 = PCURVE('',#154385,#156590); +#156590 = DEFINITIONAL_REPRESENTATION('',(#156591),#156595); +#156591 = LINE('',#156592,#156593); +#156592 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156593 = VECTOR('',#156594,1.); +#156594 = DIRECTION('',(0.E+000,-1.)); +#156595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156596 = ORIENTED_EDGE('',*,*,#156597,.F.); +#156597 = EDGE_CURVE('',#156598,#156575,#156600,.T.); +#156598 = VERTEX_POINT('',#156599); +#156599 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); +#156600 = SURFACE_CURVE('',#156601,(#156606,#156613),.PCURVE_S1.); +#156601 = CIRCLE('',#156602,3.2E-002); +#156602 = AXIS2_PLACEMENT_3D('',#156603,#156604,#156605); +#156603 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); +#156604 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156605 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156606 = PCURVE('',#154104,#156607); +#156607 = DEFINITIONAL_REPRESENTATION('',(#156608),#156612); +#156608 = CIRCLE('',#156609,3.2E-002); +#156609 = AXIS2_PLACEMENT_2D('',#156610,#156611); +#156610 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156611 = DIRECTION('',(1.,0.E+000)); +#156612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156613 = PCURVE('',#156614,#156619); +#156614 = CYLINDRICAL_SURFACE('',#156615,3.2E-002); +#156615 = AXIS2_PLACEMENT_3D('',#156616,#156617,#156618); +#156616 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); +#156617 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156618 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156619 = DEFINITIONAL_REPRESENTATION('',(#156620),#156623); +#156620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156621,#156622), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#154229 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154230 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154232 = ORIENTED_EDGE('',*,*,#154233,.F.); -#154233 = EDGE_CURVE('',#154234,#154206,#154236,.T.); -#154234 = VERTEX_POINT('',#154235); -#154235 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.825) - ); -#154236 = SURFACE_CURVE('',#154237,(#154241,#154248),.PCURVE_S1.); -#154237 = LINE('',#154238,#154239); -#154238 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); -#154239 = VECTOR('',#154240,1.); -#154240 = DIRECTION('',(0.E+000,1.,0.E+000)); -#154241 = PCURVE('',#151712,#154242); -#154242 = DEFINITIONAL_REPRESENTATION('',(#154243),#154247); -#154243 = LINE('',#154244,#154245); -#154244 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#154245 = VECTOR('',#154246,1.); -#154246 = DIRECTION('',(0.E+000,-1.)); -#154247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154248 = PCURVE('',#154249,#154254); -#154249 = PLANE('',#154250); -#154250 = AXIS2_PLACEMENT_3D('',#154251,#154252,#154253); -#154251 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); -#154252 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154253 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154254 = DEFINITIONAL_REPRESENTATION('',(#154255),#154259); -#154255 = LINE('',#154256,#154257); -#154256 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154257 = VECTOR('',#154258,1.); -#154258 = DIRECTION('',(0.E+000,1.)); -#154259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154260 = ORIENTED_EDGE('',*,*,#154261,.F.); -#154261 = EDGE_CURVE('',#154262,#154234,#154264,.T.); -#154262 = VERTEX_POINT('',#154263); -#154263 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.825) - ); -#154264 = SURFACE_CURVE('',#154265,(#154270,#154281),.PCURVE_S1.); -#154265 = CIRCLE('',#154266,1.599999999999E-002); -#154266 = AXIS2_PLACEMENT_3D('',#154267,#154268,#154269); -#154267 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) - ); -#154268 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154269 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154270 = PCURVE('',#151712,#154271); -#154271 = DEFINITIONAL_REPRESENTATION('',(#154272),#154280); -#154272 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#154273,#154274,#154275, - #154276,#154277,#154278,#154279),.UNSPECIFIED.,.T.,.F.) +#156621 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156622 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#156623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156624 = ORIENTED_EDGE('',*,*,#156625,.F.); +#156625 = EDGE_CURVE('',#156626,#156598,#156628,.T.); +#156626 = VERTEX_POINT('',#156627); +#156627 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.825) + ); +#156628 = SURFACE_CURVE('',#156629,(#156633,#156640),.PCURVE_S1.); +#156629 = LINE('',#156630,#156631); +#156630 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); +#156631 = VECTOR('',#156632,1.); +#156632 = DIRECTION('',(0.E+000,1.,0.E+000)); +#156633 = PCURVE('',#154104,#156634); +#156634 = DEFINITIONAL_REPRESENTATION('',(#156635),#156639); +#156635 = LINE('',#156636,#156637); +#156636 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#156637 = VECTOR('',#156638,1.); +#156638 = DIRECTION('',(0.E+000,-1.)); +#156639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156640 = PCURVE('',#156641,#156646); +#156641 = PLANE('',#156642); +#156642 = AXIS2_PLACEMENT_3D('',#156643,#156644,#156645); +#156643 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); +#156644 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156645 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156646 = DEFINITIONAL_REPRESENTATION('',(#156647),#156651); +#156647 = LINE('',#156648,#156649); +#156648 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156649 = VECTOR('',#156650,1.); +#156650 = DIRECTION('',(0.E+000,1.)); +#156651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156652 = ORIENTED_EDGE('',*,*,#156653,.F.); +#156653 = EDGE_CURVE('',#156654,#156626,#156656,.T.); +#156654 = VERTEX_POINT('',#156655); +#156655 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.825) + ); +#156656 = SURFACE_CURVE('',#156657,(#156662,#156673),.PCURVE_S1.); +#156657 = CIRCLE('',#156658,1.599999999999E-002); +#156658 = AXIS2_PLACEMENT_3D('',#156659,#156660,#156661); +#156659 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) + ); +#156660 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156661 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156662 = PCURVE('',#154104,#156663); +#156663 = DEFINITIONAL_REPRESENTATION('',(#156664),#156672); +#156664 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156665,#156666,#156667, + #156668,#156669,#156670,#156671),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#154273 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#154274 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); -#154275 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); -#154276 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); -#154277 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); -#154278 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); -#154279 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#154280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154281 = PCURVE('',#154282,#154287); -#154282 = CYLINDRICAL_SURFACE('',#154283,1.599999999999E-002); -#154283 = AXIS2_PLACEMENT_3D('',#154284,#154285,#154286); -#154284 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) - ); -#154285 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154286 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154287 = DEFINITIONAL_REPRESENTATION('',(#154288),#154291); -#154288 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154289,#154290), +#156665 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#156666 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); +#156667 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); +#156668 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); +#156669 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); +#156670 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); +#156671 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#156672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156673 = PCURVE('',#156674,#156679); +#156674 = CYLINDRICAL_SURFACE('',#156675,1.599999999999E-002); +#156675 = AXIS2_PLACEMENT_3D('',#156676,#156677,#156678); +#156676 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) + ); +#156677 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156678 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156679 = DEFINITIONAL_REPRESENTATION('',(#156680),#156683); +#156680 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156681,#156682), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#154289 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#154290 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#154291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154292 = ORIENTED_EDGE('',*,*,#154293,.F.); -#154293 = EDGE_CURVE('',#154294,#154262,#154296,.T.); -#154294 = VERTEX_POINT('',#154295); -#154295 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.825) - ); -#154296 = SURFACE_CURVE('',#154297,(#154301,#154308),.PCURVE_S1.); -#154297 = LINE('',#154298,#154299); -#154298 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.825) - ); -#154299 = VECTOR('',#154300,1.); -#154300 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#154301 = PCURVE('',#151712,#154302); -#154302 = DEFINITIONAL_REPRESENTATION('',(#154303),#154307); -#154303 = LINE('',#154304,#154305); -#154304 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); -#154305 = VECTOR('',#154306,1.); -#154306 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); -#154307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154308 = PCURVE('',#154309,#154314); -#154309 = PLANE('',#154310); -#154310 = AXIS2_PLACEMENT_3D('',#154311,#154312,#154313); -#154311 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.825) - ); -#154312 = DIRECTION('',(6.975647374417E-002,0.99756405026,0.E+000)); -#154313 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#154314 = DEFINITIONAL_REPRESENTATION('',(#154315),#154319); -#154315 = LINE('',#154316,#154317); -#154316 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154317 = VECTOR('',#154318,1.); -#154318 = DIRECTION('',(1.,0.E+000)); -#154319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154320 = ORIENTED_EDGE('',*,*,#154321,.F.); -#154321 = EDGE_CURVE('',#154322,#154294,#154324,.T.); -#154322 = VERTEX_POINT('',#154323); -#154323 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); -#154324 = SURFACE_CURVE('',#154325,(#154329,#154336),.PCURVE_S1.); -#154325 = LINE('',#154326,#154327); -#154326 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); -#154327 = VECTOR('',#154328,1.); -#154328 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); -#154329 = PCURVE('',#151712,#154330); -#154330 = DEFINITIONAL_REPRESENTATION('',(#154331),#154335); -#154331 = LINE('',#154332,#154333); -#154332 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); -#154333 = VECTOR('',#154334,1.); -#154334 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); -#154335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154336 = PCURVE('',#154337,#154342); -#154337 = PLANE('',#154338); -#154338 = AXIS2_PLACEMENT_3D('',#154339,#154340,#154341); -#154339 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); -#154340 = DIRECTION('',(0.99756405026,-6.975647374418E-002,0.E+000)); -#154341 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); -#154342 = DEFINITIONAL_REPRESENTATION('',(#154343),#154347); -#154343 = LINE('',#154344,#154345); -#154344 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154345 = VECTOR('',#154346,1.); -#154346 = DIRECTION('',(1.,0.E+000)); -#154347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154348 = ORIENTED_EDGE('',*,*,#154349,.F.); -#154349 = EDGE_CURVE('',#154350,#154322,#154352,.T.); -#154350 = VERTEX_POINT('',#154351); -#154351 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) - ); -#154352 = SURFACE_CURVE('',#154353,(#154357,#154364),.PCURVE_S1.); -#154353 = LINE('',#154354,#154355); -#154354 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) +#156681 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#156682 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#156683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156684 = ORIENTED_EDGE('',*,*,#156685,.F.); +#156685 = EDGE_CURVE('',#156686,#156654,#156688,.T.); +#156686 = VERTEX_POINT('',#156687); +#156687 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.825) ); -#154355 = VECTOR('',#154356,1.); -#154356 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#154357 = PCURVE('',#151712,#154358); -#154358 = DEFINITIONAL_REPRESENTATION('',(#154359),#154363); -#154359 = LINE('',#154360,#154361); -#154360 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); -#154361 = VECTOR('',#154362,1.); -#154362 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); -#154363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154364 = PCURVE('',#154365,#154370); -#154365 = PLANE('',#154366); -#154366 = AXIS2_PLACEMENT_3D('',#154367,#154368,#154369); -#154367 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) - ); -#154368 = DIRECTION('',(-6.975647374417E-002,-0.99756405026,0.E+000)); -#154369 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#154370 = DEFINITIONAL_REPRESENTATION('',(#154371),#154375); -#154371 = LINE('',#154372,#154373); -#154372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154373 = VECTOR('',#154374,1.); -#154374 = DIRECTION('',(1.,0.E+000)); -#154375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154376 = ORIENTED_EDGE('',*,*,#154377,.F.); -#154377 = EDGE_CURVE('',#154378,#154350,#154380,.T.); -#154378 = VERTEX_POINT('',#154379); -#154379 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.825) - ); -#154380 = SURFACE_CURVE('',#154381,(#154386,#154393),.PCURVE_S1.); -#154381 = CIRCLE('',#154382,3.199999999999E-002); -#154382 = AXIS2_PLACEMENT_3D('',#154383,#154384,#154385); -#154383 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) - ); -#154384 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154385 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154386 = PCURVE('',#151712,#154387); -#154387 = DEFINITIONAL_REPRESENTATION('',(#154388),#154392); -#154388 = CIRCLE('',#154389,3.199999999999E-002); -#154389 = AXIS2_PLACEMENT_2D('',#154390,#154391); -#154390 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); -#154391 = DIRECTION('',(-1.,0.E+000)); -#154392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154393 = PCURVE('',#154394,#154399); -#154394 = CYLINDRICAL_SURFACE('',#154395,3.199999999999E-002); -#154395 = AXIS2_PLACEMENT_3D('',#154396,#154397,#154398); -#154396 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) - ); -#154397 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154398 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154399 = DEFINITIONAL_REPRESENTATION('',(#154400),#154403); -#154400 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154401,#154402), +#156688 = SURFACE_CURVE('',#156689,(#156693,#156700),.PCURVE_S1.); +#156689 = LINE('',#156690,#156691); +#156690 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.825) + ); +#156691 = VECTOR('',#156692,1.); +#156692 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#156693 = PCURVE('',#154104,#156694); +#156694 = DEFINITIONAL_REPRESENTATION('',(#156695),#156699); +#156695 = LINE('',#156696,#156697); +#156696 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); +#156697 = VECTOR('',#156698,1.); +#156698 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); +#156699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156700 = PCURVE('',#156701,#156706); +#156701 = PLANE('',#156702); +#156702 = AXIS2_PLACEMENT_3D('',#156703,#156704,#156705); +#156703 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.825) + ); +#156704 = DIRECTION('',(6.975647374417E-002,0.99756405026,0.E+000)); +#156705 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#156706 = DEFINITIONAL_REPRESENTATION('',(#156707),#156711); +#156707 = LINE('',#156708,#156709); +#156708 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156709 = VECTOR('',#156710,1.); +#156710 = DIRECTION('',(1.,0.E+000)); +#156711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156712 = ORIENTED_EDGE('',*,*,#156713,.F.); +#156713 = EDGE_CURVE('',#156714,#156686,#156716,.T.); +#156714 = VERTEX_POINT('',#156715); +#156715 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); +#156716 = SURFACE_CURVE('',#156717,(#156721,#156728),.PCURVE_S1.); +#156717 = LINE('',#156718,#156719); +#156718 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); +#156719 = VECTOR('',#156720,1.); +#156720 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); +#156721 = PCURVE('',#154104,#156722); +#156722 = DEFINITIONAL_REPRESENTATION('',(#156723),#156727); +#156723 = LINE('',#156724,#156725); +#156724 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); +#156725 = VECTOR('',#156726,1.); +#156726 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); +#156727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156728 = PCURVE('',#156729,#156734); +#156729 = PLANE('',#156730); +#156730 = AXIS2_PLACEMENT_3D('',#156731,#156732,#156733); +#156731 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); +#156732 = DIRECTION('',(0.99756405026,-6.975647374418E-002,0.E+000)); +#156733 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); +#156734 = DEFINITIONAL_REPRESENTATION('',(#156735),#156739); +#156735 = LINE('',#156736,#156737); +#156736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156737 = VECTOR('',#156738,1.); +#156738 = DIRECTION('',(1.,0.E+000)); +#156739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156740 = ORIENTED_EDGE('',*,*,#156741,.F.); +#156741 = EDGE_CURVE('',#156742,#156714,#156744,.T.); +#156742 = VERTEX_POINT('',#156743); +#156743 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) + ); +#156744 = SURFACE_CURVE('',#156745,(#156749,#156756),.PCURVE_S1.); +#156745 = LINE('',#156746,#156747); +#156746 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) + ); +#156747 = VECTOR('',#156748,1.); +#156748 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#156749 = PCURVE('',#154104,#156750); +#156750 = DEFINITIONAL_REPRESENTATION('',(#156751),#156755); +#156751 = LINE('',#156752,#156753); +#156752 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); +#156753 = VECTOR('',#156754,1.); +#156754 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); +#156755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156756 = PCURVE('',#156757,#156762); +#156757 = PLANE('',#156758); +#156758 = AXIS2_PLACEMENT_3D('',#156759,#156760,#156761); +#156759 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) + ); +#156760 = DIRECTION('',(-6.975647374417E-002,-0.99756405026,0.E+000)); +#156761 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#156762 = DEFINITIONAL_REPRESENTATION('',(#156763),#156767); +#156763 = LINE('',#156764,#156765); +#156764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156765 = VECTOR('',#156766,1.); +#156766 = DIRECTION('',(1.,0.E+000)); +#156767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156768 = ORIENTED_EDGE('',*,*,#156769,.F.); +#156769 = EDGE_CURVE('',#156770,#156742,#156772,.T.); +#156770 = VERTEX_POINT('',#156771); +#156771 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.825) + ); +#156772 = SURFACE_CURVE('',#156773,(#156778,#156785),.PCURVE_S1.); +#156773 = CIRCLE('',#156774,3.199999999999E-002); +#156774 = AXIS2_PLACEMENT_3D('',#156775,#156776,#156777); +#156775 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) + ); +#156776 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156777 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156778 = PCURVE('',#154104,#156779); +#156779 = DEFINITIONAL_REPRESENTATION('',(#156780),#156784); +#156780 = CIRCLE('',#156781,3.199999999999E-002); +#156781 = AXIS2_PLACEMENT_2D('',#156782,#156783); +#156782 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); +#156783 = DIRECTION('',(-1.,0.E+000)); +#156784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156785 = PCURVE('',#156786,#156791); +#156786 = CYLINDRICAL_SURFACE('',#156787,3.199999999999E-002); +#156787 = AXIS2_PLACEMENT_3D('',#156788,#156789,#156790); +#156788 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.825) + ); +#156789 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156790 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156791 = DEFINITIONAL_REPRESENTATION('',(#156792),#156795); +#156792 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156793,#156794), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#154401 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); -#154402 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#154403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154404 = ORIENTED_EDGE('',*,*,#154405,.F.); -#154405 = EDGE_CURVE('',#154406,#154378,#154408,.T.); -#154406 = VERTEX_POINT('',#154407); -#154407 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); -#154408 = SURFACE_CURVE('',#154409,(#154413,#154420),.PCURVE_S1.); -#154409 = LINE('',#154410,#154411); -#154410 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); -#154411 = VECTOR('',#154412,1.); -#154412 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#154413 = PCURVE('',#151712,#154414); -#154414 = DEFINITIONAL_REPRESENTATION('',(#154415),#154419); -#154415 = LINE('',#154416,#154417); -#154416 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#154417 = VECTOR('',#154418,1.); -#154418 = DIRECTION('',(0.E+000,1.)); -#154419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154420 = PCURVE('',#154421,#154426); -#154421 = PLANE('',#154422); -#154422 = AXIS2_PLACEMENT_3D('',#154423,#154424,#154425); -#154423 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); -#154424 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154425 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154426 = DEFINITIONAL_REPRESENTATION('',(#154427),#154431); -#154427 = LINE('',#154428,#154429); -#154428 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154429 = VECTOR('',#154430,1.); -#154430 = DIRECTION('',(0.E+000,-1.)); -#154431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154432 = ORIENTED_EDGE('',*,*,#154433,.F.); -#154433 = EDGE_CURVE('',#154107,#154406,#154434,.T.); -#154434 = SURFACE_CURVE('',#154435,(#154440,#154451),.PCURVE_S1.); -#154435 = CIRCLE('',#154436,1.6E-002); -#154436 = AXIS2_PLACEMENT_3D('',#154437,#154438,#154439); -#154437 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); -#154438 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154439 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154440 = PCURVE('',#151712,#154441); -#154441 = DEFINITIONAL_REPRESENTATION('',(#154442),#154450); -#154442 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#154443,#154444,#154445, - #154446,#154447,#154448,#154449),.UNSPECIFIED.,.F.,.F.) +#156793 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); +#156794 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#156795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156796 = ORIENTED_EDGE('',*,*,#156797,.F.); +#156797 = EDGE_CURVE('',#156798,#156770,#156800,.T.); +#156798 = VERTEX_POINT('',#156799); +#156799 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); +#156800 = SURFACE_CURVE('',#156801,(#156805,#156812),.PCURVE_S1.); +#156801 = LINE('',#156802,#156803); +#156802 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); +#156803 = VECTOR('',#156804,1.); +#156804 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#156805 = PCURVE('',#154104,#156806); +#156806 = DEFINITIONAL_REPRESENTATION('',(#156807),#156811); +#156807 = LINE('',#156808,#156809); +#156808 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#156809 = VECTOR('',#156810,1.); +#156810 = DIRECTION('',(0.E+000,1.)); +#156811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156812 = PCURVE('',#156813,#156818); +#156813 = PLANE('',#156814); +#156814 = AXIS2_PLACEMENT_3D('',#156815,#156816,#156817); +#156815 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); +#156816 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156817 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156818 = DEFINITIONAL_REPRESENTATION('',(#156819),#156823); +#156819 = LINE('',#156820,#156821); +#156820 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156821 = VECTOR('',#156822,1.); +#156822 = DIRECTION('',(0.E+000,-1.)); +#156823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156824 = ORIENTED_EDGE('',*,*,#156825,.F.); +#156825 = EDGE_CURVE('',#156499,#156798,#156826,.T.); +#156826 = SURFACE_CURVE('',#156827,(#156832,#156843),.PCURVE_S1.); +#156827 = CIRCLE('',#156828,1.6E-002); +#156828 = AXIS2_PLACEMENT_3D('',#156829,#156830,#156831); +#156829 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.825)); +#156830 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156831 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156832 = PCURVE('',#154104,#156833); +#156833 = DEFINITIONAL_REPRESENTATION('',(#156834),#156842); +#156834 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156835,#156836,#156837, + #156838,#156839,#156840,#156841),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#154443 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#154444 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#154445 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#154446 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#154447 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#154448 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#154449 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#154450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154451 = PCURVE('',#154145,#154452); -#154452 = DEFINITIONAL_REPRESENTATION('',(#154453),#154456); -#154453 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154454,#154455), +#156835 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#156836 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#156837 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#156838 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#156839 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#156840 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#156841 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#156842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156843 = PCURVE('',#156537,#156844); +#156844 = DEFINITIONAL_REPRESENTATION('',(#156845),#156848); +#156845 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156846,#156847), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#154454 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154455 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154457 = ADVANCED_FACE('',(#154458),#151967,.T.); -#154458 = FACE_BOUND('',#154459,.T.); -#154459 = EDGE_LOOP('',(#154460,#154461,#154462,#154489,#154512,#154535, - #154558,#154581,#154604,#154631,#154654,#154677)); -#154460 = ORIENTED_EDGE('',*,*,#151951,.F.); -#154461 = ORIENTED_EDGE('',*,*,#154156,.T.); -#154462 = ORIENTED_EDGE('',*,*,#154463,.T.); -#154463 = EDGE_CURVE('',#154130,#154464,#154466,.T.); -#154464 = VERTEX_POINT('',#154465); -#154465 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.475)); -#154466 = SURFACE_CURVE('',#154467,(#154472,#154483),.PCURVE_S1.); -#154467 = CIRCLE('',#154468,1.6E-002); -#154468 = AXIS2_PLACEMENT_3D('',#154469,#154470,#154471); -#154469 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); -#154470 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154471 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154472 = PCURVE('',#151967,#154473); -#154473 = DEFINITIONAL_REPRESENTATION('',(#154474),#154482); -#154474 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#154475,#154476,#154477, - #154478,#154479,#154480,#154481),.UNSPECIFIED.,.F.,.F.) +#156846 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#156847 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#156848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156849 = ADVANCED_FACE('',(#156850),#154359,.T.); +#156850 = FACE_BOUND('',#156851,.T.); +#156851 = EDGE_LOOP('',(#156852,#156853,#156854,#156881,#156904,#156927, + #156950,#156973,#156996,#157023,#157046,#157069)); +#156852 = ORIENTED_EDGE('',*,*,#154343,.F.); +#156853 = ORIENTED_EDGE('',*,*,#156548,.T.); +#156854 = ORIENTED_EDGE('',*,*,#156855,.T.); +#156855 = EDGE_CURVE('',#156522,#156856,#156858,.T.); +#156856 = VERTEX_POINT('',#156857); +#156857 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.475)); +#156858 = SURFACE_CURVE('',#156859,(#156864,#156875),.PCURVE_S1.); +#156859 = CIRCLE('',#156860,1.6E-002); +#156860 = AXIS2_PLACEMENT_3D('',#156861,#156862,#156863); +#156861 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); +#156862 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#156863 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#156864 = PCURVE('',#154359,#156865); +#156865 = DEFINITIONAL_REPRESENTATION('',(#156866),#156874); +#156866 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156867,#156868,#156869, + #156870,#156871,#156872,#156873),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#154475 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#154476 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#154477 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#154478 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#154479 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#154480 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#154481 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#154482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154483 = PCURVE('',#154145,#154484); -#154484 = DEFINITIONAL_REPRESENTATION('',(#154485),#154488); -#154485 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154486,#154487), +#156867 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#156868 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#156869 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#156870 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#156871 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#156872 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#156873 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#156874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156875 = PCURVE('',#156537,#156876); +#156876 = DEFINITIONAL_REPRESENTATION('',(#156877),#156880); +#156877 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156878,#156879), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#154486 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154487 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154489 = ORIENTED_EDGE('',*,*,#154490,.T.); -#154490 = EDGE_CURVE('',#154464,#154491,#154493,.T.); -#154491 = VERTEX_POINT('',#154492); -#154492 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.475) - ); -#154493 = SURFACE_CURVE('',#154494,(#154498,#154505),.PCURVE_S1.); -#154494 = LINE('',#154495,#154496); -#154495 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.475)); -#154496 = VECTOR('',#154497,1.); -#154497 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#154498 = PCURVE('',#151967,#154499); -#154499 = DEFINITIONAL_REPRESENTATION('',(#154500),#154504); -#154500 = LINE('',#154501,#154502); -#154501 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#154502 = VECTOR('',#154503,1.); -#154503 = DIRECTION('',(0.E+000,1.)); -#154504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154505 = PCURVE('',#154421,#154506); -#154506 = DEFINITIONAL_REPRESENTATION('',(#154507),#154511); -#154507 = LINE('',#154508,#154509); -#154508 = CARTESIAN_POINT('',(0.35,0.E+000)); -#154509 = VECTOR('',#154510,1.); -#154510 = DIRECTION('',(0.E+000,-1.)); -#154511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154512 = ORIENTED_EDGE('',*,*,#154513,.T.); -#154513 = EDGE_CURVE('',#154491,#154514,#154516,.T.); -#154514 = VERTEX_POINT('',#154515); -#154515 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.475) - ); -#154516 = SURFACE_CURVE('',#154517,(#154522,#154529),.PCURVE_S1.); -#154517 = CIRCLE('',#154518,3.199999999999E-002); -#154518 = AXIS2_PLACEMENT_3D('',#154519,#154520,#154521); -#154519 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.475) - ); -#154520 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154521 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154522 = PCURVE('',#151967,#154523); -#154523 = DEFINITIONAL_REPRESENTATION('',(#154524),#154528); -#154524 = CIRCLE('',#154525,3.199999999999E-002); -#154525 = AXIS2_PLACEMENT_2D('',#154526,#154527); -#154526 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); -#154527 = DIRECTION('',(-1.,0.E+000)); -#154528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154529 = PCURVE('',#154394,#154530); -#154530 = DEFINITIONAL_REPRESENTATION('',(#154531),#154534); -#154531 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154532,#154533), +#156878 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#156879 = CARTESIAN_POINT('',(0.E+000,0.35)); +#156880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156881 = ORIENTED_EDGE('',*,*,#156882,.T.); +#156882 = EDGE_CURVE('',#156856,#156883,#156885,.T.); +#156883 = VERTEX_POINT('',#156884); +#156884 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.475) + ); +#156885 = SURFACE_CURVE('',#156886,(#156890,#156897),.PCURVE_S1.); +#156886 = LINE('',#156887,#156888); +#156887 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.475)); +#156888 = VECTOR('',#156889,1.); +#156889 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#156890 = PCURVE('',#154359,#156891); +#156891 = DEFINITIONAL_REPRESENTATION('',(#156892),#156896); +#156892 = LINE('',#156893,#156894); +#156893 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#156894 = VECTOR('',#156895,1.); +#156895 = DIRECTION('',(0.E+000,1.)); +#156896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156897 = PCURVE('',#156813,#156898); +#156898 = DEFINITIONAL_REPRESENTATION('',(#156899),#156903); +#156899 = LINE('',#156900,#156901); +#156900 = CARTESIAN_POINT('',(0.35,0.E+000)); +#156901 = VECTOR('',#156902,1.); +#156902 = DIRECTION('',(0.E+000,-1.)); +#156903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156904 = ORIENTED_EDGE('',*,*,#156905,.T.); +#156905 = EDGE_CURVE('',#156883,#156906,#156908,.T.); +#156906 = VERTEX_POINT('',#156907); +#156907 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.475) + ); +#156908 = SURFACE_CURVE('',#156909,(#156914,#156921),.PCURVE_S1.); +#156909 = CIRCLE('',#156910,3.199999999999E-002); +#156910 = AXIS2_PLACEMENT_3D('',#156911,#156912,#156913); +#156911 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.475) + ); +#156912 = DIRECTION('',(0.E+000,0.E+000,1.)); +#156913 = DIRECTION('',(1.,0.E+000,0.E+000)); +#156914 = PCURVE('',#154359,#156915); +#156915 = DEFINITIONAL_REPRESENTATION('',(#156916),#156920); +#156916 = CIRCLE('',#156917,3.199999999999E-002); +#156917 = AXIS2_PLACEMENT_2D('',#156918,#156919); +#156918 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); +#156919 = DIRECTION('',(-1.,0.E+000)); +#156920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156921 = PCURVE('',#156786,#156922); +#156922 = DEFINITIONAL_REPRESENTATION('',(#156923),#156926); +#156923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156924,#156925), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#154532 = CARTESIAN_POINT('',(3.141592653589,0.35)); -#154533 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#154534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154535 = ORIENTED_EDGE('',*,*,#154536,.T.); -#154536 = EDGE_CURVE('',#154514,#154537,#154539,.T.); -#154537 = VERTEX_POINT('',#154538); -#154538 = CARTESIAN_POINT('',(1.05,0.E+000,-0.475)); -#154539 = SURFACE_CURVE('',#154540,(#154544,#154551),.PCURVE_S1.); -#154540 = LINE('',#154541,#154542); -#154541 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.475) - ); -#154542 = VECTOR('',#154543,1.); -#154543 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); -#154544 = PCURVE('',#151967,#154545); -#154545 = DEFINITIONAL_REPRESENTATION('',(#154546),#154550); -#154546 = LINE('',#154547,#154548); -#154547 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); -#154548 = VECTOR('',#154549,1.); -#154549 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); -#154550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154551 = PCURVE('',#154365,#154552); -#154552 = DEFINITIONAL_REPRESENTATION('',(#154553),#154557); -#154553 = LINE('',#154554,#154555); -#154554 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154555 = VECTOR('',#154556,1.); -#154556 = DIRECTION('',(1.,0.E+000)); -#154557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154558 = ORIENTED_EDGE('',*,*,#154559,.T.); -#154559 = EDGE_CURVE('',#154537,#154560,#154562,.T.); -#154560 = VERTEX_POINT('',#154561); -#154561 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.475) - ); -#154562 = SURFACE_CURVE('',#154563,(#154567,#154574),.PCURVE_S1.); -#154563 = LINE('',#154564,#154565); -#154564 = CARTESIAN_POINT('',(1.05,0.E+000,-0.475)); -#154565 = VECTOR('',#154566,1.); -#154566 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); -#154567 = PCURVE('',#151967,#154568); -#154568 = DEFINITIONAL_REPRESENTATION('',(#154569),#154573); -#154569 = LINE('',#154570,#154571); -#154570 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); -#154571 = VECTOR('',#154572,1.); -#154572 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); -#154573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154574 = PCURVE('',#154337,#154575); -#154575 = DEFINITIONAL_REPRESENTATION('',(#154576),#154580); -#154576 = LINE('',#154577,#154578); -#154577 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154578 = VECTOR('',#154579,1.); -#154579 = DIRECTION('',(1.,0.E+000)); -#154580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154581 = ORIENTED_EDGE('',*,*,#154582,.T.); -#154582 = EDGE_CURVE('',#154560,#154583,#154585,.T.); -#154583 = VERTEX_POINT('',#154584); -#154584 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.475) - ); -#154585 = SURFACE_CURVE('',#154586,(#154590,#154597),.PCURVE_S1.); -#154586 = LINE('',#154587,#154588); -#154587 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.475) - ); -#154588 = VECTOR('',#154589,1.); -#154589 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); -#154590 = PCURVE('',#151967,#154591); -#154591 = DEFINITIONAL_REPRESENTATION('',(#154592),#154596); -#154592 = LINE('',#154593,#154594); -#154593 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); -#154594 = VECTOR('',#154595,1.); -#154595 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); -#154596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154597 = PCURVE('',#154309,#154598); -#154598 = DEFINITIONAL_REPRESENTATION('',(#154599),#154603); -#154599 = LINE('',#154600,#154601); -#154600 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154601 = VECTOR('',#154602,1.); -#154602 = DIRECTION('',(1.,0.E+000)); -#154603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154604 = ORIENTED_EDGE('',*,*,#154605,.T.); -#154605 = EDGE_CURVE('',#154583,#154606,#154608,.T.); -#154606 = VERTEX_POINT('',#154607); -#154607 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.475) - ); -#154608 = SURFACE_CURVE('',#154609,(#154614,#154625),.PCURVE_S1.); -#154609 = CIRCLE('',#154610,1.599999999999E-002); -#154610 = AXIS2_PLACEMENT_3D('',#154611,#154612,#154613); -#154611 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.475) - ); -#154612 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154613 = DIRECTION('',(1.,0.E+000,0.E+000)); -#154614 = PCURVE('',#151967,#154615); -#154615 = DEFINITIONAL_REPRESENTATION('',(#154616),#154624); -#154616 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#154617,#154618,#154619, - #154620,#154621,#154622,#154623),.UNSPECIFIED.,.T.,.F.) +#156924 = CARTESIAN_POINT('',(3.141592653589,0.35)); +#156925 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#156926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156927 = ORIENTED_EDGE('',*,*,#156928,.T.); +#156928 = EDGE_CURVE('',#156906,#156929,#156931,.T.); +#156929 = VERTEX_POINT('',#156930); +#156930 = CARTESIAN_POINT('',(1.05,0.E+000,-0.475)); +#156931 = SURFACE_CURVE('',#156932,(#156936,#156943),.PCURVE_S1.); +#156932 = LINE('',#156933,#156934); +#156933 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.475) + ); +#156934 = VECTOR('',#156935,1.); +#156935 = DIRECTION('',(0.99756405026,-6.975647374417E-002,0.E+000)); +#156936 = PCURVE('',#154359,#156937); +#156937 = DEFINITIONAL_REPRESENTATION('',(#156938),#156942); +#156938 = LINE('',#156939,#156940); +#156939 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); +#156940 = VECTOR('',#156941,1.); +#156941 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); +#156942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156943 = PCURVE('',#156757,#156944); +#156944 = DEFINITIONAL_REPRESENTATION('',(#156945),#156949); +#156945 = LINE('',#156946,#156947); +#156946 = CARTESIAN_POINT('',(0.E+000,0.35)); +#156947 = VECTOR('',#156948,1.); +#156948 = DIRECTION('',(1.,0.E+000)); +#156949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156950 = ORIENTED_EDGE('',*,*,#156951,.T.); +#156951 = EDGE_CURVE('',#156929,#156952,#156954,.T.); +#156952 = VERTEX_POINT('',#156953); +#156953 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.475) + ); +#156954 = SURFACE_CURVE('',#156955,(#156959,#156966),.PCURVE_S1.); +#156955 = LINE('',#156956,#156957); +#156956 = CARTESIAN_POINT('',(1.05,0.E+000,-0.475)); +#156957 = VECTOR('',#156958,1.); +#156958 = DIRECTION('',(6.975647374418E-002,0.99756405026,0.E+000)); +#156959 = PCURVE('',#154359,#156960); +#156960 = DEFINITIONAL_REPRESENTATION('',(#156961),#156965); +#156961 = LINE('',#156962,#156963); +#156962 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); +#156963 = VECTOR('',#156964,1.); +#156964 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); +#156965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156966 = PCURVE('',#156729,#156967); +#156967 = DEFINITIONAL_REPRESENTATION('',(#156968),#156972); +#156968 = LINE('',#156969,#156970); +#156969 = CARTESIAN_POINT('',(0.E+000,0.35)); +#156970 = VECTOR('',#156971,1.); +#156971 = DIRECTION('',(1.,0.E+000)); +#156972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156973 = ORIENTED_EDGE('',*,*,#156974,.T.); +#156974 = EDGE_CURVE('',#156952,#156975,#156977,.T.); +#156975 = VERTEX_POINT('',#156976); +#156976 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.475) + ); +#156977 = SURFACE_CURVE('',#156978,(#156982,#156989),.PCURVE_S1.); +#156978 = LINE('',#156979,#156980); +#156979 = CARTESIAN_POINT('',(0.720883896422,3.905311025178E-002,-0.475) + ); +#156980 = VECTOR('',#156981,1.); +#156981 = DIRECTION('',(-0.99756405026,6.975647374417E-002,0.E+000)); +#156982 = PCURVE('',#154359,#156983); +#156983 = DEFINITIONAL_REPRESENTATION('',(#156984),#156988); +#156984 = LINE('',#156985,#156986); +#156985 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); +#156986 = VECTOR('',#156987,1.); +#156987 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); +#156988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156989 = PCURVE('',#156701,#156990); +#156990 = DEFINITIONAL_REPRESENTATION('',(#156991),#156995); +#156991 = LINE('',#156992,#156993); +#156992 = CARTESIAN_POINT('',(0.E+000,0.35)); +#156993 = VECTOR('',#156994,1.); +#156994 = DIRECTION('',(1.,0.E+000)); +#156995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#156996 = ORIENTED_EDGE('',*,*,#156997,.T.); +#156997 = EDGE_CURVE('',#156975,#156998,#157000,.T.); +#156998 = VERTEX_POINT('',#156999); +#156999 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.475) + ); +#157000 = SURFACE_CURVE('',#157001,(#157006,#157017),.PCURVE_S1.); +#157001 = CIRCLE('',#157002,1.599999999999E-002); +#157002 = AXIS2_PLACEMENT_3D('',#157003,#157004,#157005); +#157003 = CARTESIAN_POINT('',(0.722000000002,5.501413505592E-002,-0.475) + ); +#157004 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157005 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157006 = PCURVE('',#154359,#157007); +#157007 = DEFINITIONAL_REPRESENTATION('',(#157008),#157016); +#157008 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157009,#157010,#157011, + #157012,#157013,#157014,#157015),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#154617 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#154618 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); -#154619 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); -#154620 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); -#154621 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); -#154622 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); -#154623 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#154624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154625 = PCURVE('',#154282,#154626); -#154626 = DEFINITIONAL_REPRESENTATION('',(#154627),#154630); -#154627 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154628,#154629), +#157009 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157010 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); +#157011 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); +#157012 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); +#157013 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); +#157014 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); +#157015 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157017 = PCURVE('',#156674,#157018); +#157018 = DEFINITIONAL_REPRESENTATION('',(#157019),#157022); +#157019 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157020,#157021), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#154628 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#154629 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#154630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154631 = ORIENTED_EDGE('',*,*,#154632,.T.); -#154632 = EDGE_CURVE('',#154606,#154633,#154635,.T.); -#154633 = VERTEX_POINT('',#154634); -#154634 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.475)); -#154635 = SURFACE_CURVE('',#154636,(#154640,#154647),.PCURVE_S1.); -#154636 = LINE('',#154637,#154638); -#154637 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.475)); -#154638 = VECTOR('',#154639,1.); -#154639 = DIRECTION('',(0.E+000,1.,0.E+000)); -#154640 = PCURVE('',#151967,#154641); -#154641 = DEFINITIONAL_REPRESENTATION('',(#154642),#154646); -#154642 = LINE('',#154643,#154644); -#154643 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#154644 = VECTOR('',#154645,1.); -#154645 = DIRECTION('',(0.E+000,-1.)); -#154646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154647 = PCURVE('',#154249,#154648); -#154648 = DEFINITIONAL_REPRESENTATION('',(#154649),#154653); -#154649 = LINE('',#154650,#154651); -#154650 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#154651 = VECTOR('',#154652,1.); -#154652 = DIRECTION('',(0.E+000,1.)); -#154653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154654 = ORIENTED_EDGE('',*,*,#154655,.T.); -#154655 = EDGE_CURVE('',#154633,#154656,#154658,.T.); -#154656 = VERTEX_POINT('',#154657); -#154657 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.475)); -#154658 = SURFACE_CURVE('',#154659,(#154664,#154671),.PCURVE_S1.); -#154659 = CIRCLE('',#154660,3.2E-002); -#154660 = AXIS2_PLACEMENT_3D('',#154661,#154662,#154663); -#154661 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); -#154662 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154663 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154664 = PCURVE('',#151967,#154665); -#154665 = DEFINITIONAL_REPRESENTATION('',(#154666),#154670); -#154666 = CIRCLE('',#154667,3.2E-002); -#154667 = AXIS2_PLACEMENT_2D('',#154668,#154669); -#154668 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154669 = DIRECTION('',(1.,0.E+000)); -#154670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154671 = PCURVE('',#154222,#154672); -#154672 = DEFINITIONAL_REPRESENTATION('',(#154673),#154676); -#154673 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154674,#154675), +#157020 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#157021 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#157022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157023 = ORIENTED_EDGE('',*,*,#157024,.T.); +#157024 = EDGE_CURVE('',#156998,#157025,#157027,.T.); +#157025 = VERTEX_POINT('',#157026); +#157026 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.475)); +#157027 = SURFACE_CURVE('',#157028,(#157032,#157039),.PCURVE_S1.); +#157028 = LINE('',#157029,#157030); +#157029 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.475)); +#157030 = VECTOR('',#157031,1.); +#157031 = DIRECTION('',(0.E+000,1.,0.E+000)); +#157032 = PCURVE('',#154359,#157033); +#157033 = DEFINITIONAL_REPRESENTATION('',(#157034),#157038); +#157034 = LINE('',#157035,#157036); +#157035 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#157036 = VECTOR('',#157037,1.); +#157037 = DIRECTION('',(0.E+000,-1.)); +#157038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157039 = PCURVE('',#156641,#157040); +#157040 = DEFINITIONAL_REPRESENTATION('',(#157041),#157045); +#157041 = LINE('',#157042,#157043); +#157042 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#157043 = VECTOR('',#157044,1.); +#157044 = DIRECTION('',(0.E+000,1.)); +#157045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157046 = ORIENTED_EDGE('',*,*,#157047,.T.); +#157047 = EDGE_CURVE('',#157025,#157048,#157050,.T.); +#157048 = VERTEX_POINT('',#157049); +#157049 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.475)); +#157050 = SURFACE_CURVE('',#157051,(#157056,#157063),.PCURVE_S1.); +#157051 = CIRCLE('',#157052,3.2E-002); +#157052 = AXIS2_PLACEMENT_3D('',#157053,#157054,#157055); +#157053 = CARTESIAN_POINT('',(0.674000000002,0.66733334,-0.475)); +#157054 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157055 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157056 = PCURVE('',#154359,#157057); +#157057 = DEFINITIONAL_REPRESENTATION('',(#157058),#157062); +#157058 = CIRCLE('',#157059,3.2E-002); +#157059 = AXIS2_PLACEMENT_2D('',#157060,#157061); +#157060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157061 = DIRECTION('',(1.,0.E+000)); +#157062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157063 = PCURVE('',#156614,#157064); +#157064 = DEFINITIONAL_REPRESENTATION('',(#157065),#157068); +#157065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157066,#157067), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#154674 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154675 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154677 = ORIENTED_EDGE('',*,*,#154678,.T.); -#154678 = EDGE_CURVE('',#154656,#151952,#154679,.T.); -#154679 = SURFACE_CURVE('',#154680,(#154684,#154691),.PCURVE_S1.); -#154680 = LINE('',#154681,#154682); -#154681 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.475)); -#154682 = VECTOR('',#154683,1.); -#154683 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154684 = PCURVE('',#151967,#154685); -#154685 = DEFINITIONAL_REPRESENTATION('',(#154686),#154690); -#154686 = LINE('',#154687,#154688); -#154687 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); -#154688 = VECTOR('',#154689,1.); -#154689 = DIRECTION('',(1.,0.E+000)); -#154690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154691 = PCURVE('',#151993,#154692); -#154692 = DEFINITIONAL_REPRESENTATION('',(#154693),#154697); -#154693 = LINE('',#154694,#154695); -#154694 = CARTESIAN_POINT('',(0.35,0.E+000)); -#154695 = VECTOR('',#154696,1.); -#154696 = DIRECTION('',(0.E+000,-1.)); -#154697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154698 = ADVANCED_FACE('',(#154699),#154145,.F.); -#154699 = FACE_BOUND('',#154700,.F.); -#154700 = EDGE_LOOP('',(#154701,#154702,#154722,#154723)); -#154701 = ORIENTED_EDGE('',*,*,#154463,.T.); -#154702 = ORIENTED_EDGE('',*,*,#154703,.F.); -#154703 = EDGE_CURVE('',#154406,#154464,#154704,.T.); -#154704 = SURFACE_CURVE('',#154705,(#154709,#154715),.PCURVE_S1.); -#154705 = LINE('',#154706,#154707); -#154706 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); -#154707 = VECTOR('',#154708,1.); -#154708 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154709 = PCURVE('',#154145,#154710); -#154710 = DEFINITIONAL_REPRESENTATION('',(#154711),#154714); -#154711 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154712,#154713), +#157066 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157067 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157069 = ORIENTED_EDGE('',*,*,#157070,.T.); +#157070 = EDGE_CURVE('',#157048,#154344,#157071,.T.); +#157071 = SURFACE_CURVE('',#157072,(#157076,#157083),.PCURVE_S1.); +#157072 = LINE('',#157073,#157074); +#157073 = CARTESIAN_POINT('',(0.573318332236,0.69933334,-0.475)); +#157074 = VECTOR('',#157075,1.); +#157075 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157076 = PCURVE('',#154359,#157077); +#157077 = DEFINITIONAL_REPRESENTATION('',(#157078),#157082); +#157078 = LINE('',#157079,#157080); +#157079 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); +#157080 = VECTOR('',#157081,1.); +#157081 = DIRECTION('',(1.,0.E+000)); +#157082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157083 = PCURVE('',#154385,#157084); +#157084 = DEFINITIONAL_REPRESENTATION('',(#157085),#157089); +#157085 = LINE('',#157086,#157087); +#157086 = CARTESIAN_POINT('',(0.35,0.E+000)); +#157087 = VECTOR('',#157088,1.); +#157088 = DIRECTION('',(0.E+000,-1.)); +#157089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157090 = ADVANCED_FACE('',(#157091),#156537,.F.); +#157091 = FACE_BOUND('',#157092,.F.); +#157092 = EDGE_LOOP('',(#157093,#157094,#157114,#157115)); +#157093 = ORIENTED_EDGE('',*,*,#156855,.T.); +#157094 = ORIENTED_EDGE('',*,*,#157095,.F.); +#157095 = EDGE_CURVE('',#156798,#156856,#157096,.T.); +#157096 = SURFACE_CURVE('',#157097,(#157101,#157107),.PCURVE_S1.); +#157097 = LINE('',#157098,#157099); +#157098 = CARTESIAN_POINT('',(0.690000000002,0.66733334,-0.825)); +#157099 = VECTOR('',#157100,1.); +#157100 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157101 = PCURVE('',#156537,#157102); +#157102 = DEFINITIONAL_REPRESENTATION('',(#157103),#157106); +#157103 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157104,#157105), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154712 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154713 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154715 = PCURVE('',#154421,#154716); -#154716 = DEFINITIONAL_REPRESENTATION('',(#154717),#154721); -#154717 = LINE('',#154718,#154719); -#154718 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154719 = VECTOR('',#154720,1.); -#154720 = DIRECTION('',(1.,0.E+000)); -#154721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154722 = ORIENTED_EDGE('',*,*,#154433,.F.); -#154723 = ORIENTED_EDGE('',*,*,#154129,.T.); -#154724 = ADVANCED_FACE('',(#154725),#151993,.T.); -#154725 = FACE_BOUND('',#154726,.T.); -#154726 = EDGE_LOOP('',(#154727,#154728,#154748,#154749)); -#154727 = ORIENTED_EDGE('',*,*,#154678,.F.); -#154728 = ORIENTED_EDGE('',*,*,#154729,.F.); -#154729 = EDGE_CURVE('',#154183,#154656,#154730,.T.); -#154730 = SURFACE_CURVE('',#154731,(#154735,#154742),.PCURVE_S1.); -#154731 = LINE('',#154732,#154733); -#154732 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.825)); -#154733 = VECTOR('',#154734,1.); -#154734 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154735 = PCURVE('',#151993,#154736); -#154736 = DEFINITIONAL_REPRESENTATION('',(#154737),#154741); -#154737 = LINE('',#154738,#154739); -#154738 = CARTESIAN_POINT('',(0.E+000,0.100681667766)); -#154739 = VECTOR('',#154740,1.); -#154740 = DIRECTION('',(1.,0.E+000)); -#154741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154742 = PCURVE('',#154222,#154743); -#154743 = DEFINITIONAL_REPRESENTATION('',(#154744),#154747); -#154744 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154745,#154746), +#157104 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157105 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157107 = PCURVE('',#156813,#157108); +#157108 = DEFINITIONAL_REPRESENTATION('',(#157109),#157113); +#157109 = LINE('',#157110,#157111); +#157110 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157111 = VECTOR('',#157112,1.); +#157112 = DIRECTION('',(1.,0.E+000)); +#157113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157114 = ORIENTED_EDGE('',*,*,#156825,.F.); +#157115 = ORIENTED_EDGE('',*,*,#156521,.T.); +#157116 = ADVANCED_FACE('',(#157117),#154385,.T.); +#157117 = FACE_BOUND('',#157118,.T.); +#157118 = EDGE_LOOP('',(#157119,#157120,#157140,#157141)); +#157119 = ORIENTED_EDGE('',*,*,#157070,.F.); +#157120 = ORIENTED_EDGE('',*,*,#157121,.F.); +#157121 = EDGE_CURVE('',#156575,#157048,#157122,.T.); +#157122 = SURFACE_CURVE('',#157123,(#157127,#157134),.PCURVE_S1.); +#157123 = LINE('',#157124,#157125); +#157124 = CARTESIAN_POINT('',(0.674000000002,0.69933334,-0.825)); +#157125 = VECTOR('',#157126,1.); +#157126 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157127 = PCURVE('',#154385,#157128); +#157128 = DEFINITIONAL_REPRESENTATION('',(#157129),#157133); +#157129 = LINE('',#157130,#157131); +#157130 = CARTESIAN_POINT('',(0.E+000,0.100681667766)); +#157131 = VECTOR('',#157132,1.); +#157132 = DIRECTION('',(1.,0.E+000)); +#157133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157134 = PCURVE('',#156614,#157135); +#157135 = DEFINITIONAL_REPRESENTATION('',(#157136),#157139); +#157136 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157137,#157138), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154745 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154746 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154748 = ORIENTED_EDGE('',*,*,#154182,.T.); -#154749 = ORIENTED_EDGE('',*,*,#151979,.T.); -#154750 = ADVANCED_FACE('',(#154751),#154222,.T.); -#154751 = FACE_BOUND('',#154752,.T.); -#154752 = EDGE_LOOP('',(#154753,#154754,#154774,#154775)); -#154753 = ORIENTED_EDGE('',*,*,#154655,.F.); -#154754 = ORIENTED_EDGE('',*,*,#154755,.F.); -#154755 = EDGE_CURVE('',#154206,#154633,#154756,.T.); -#154756 = SURFACE_CURVE('',#154757,(#154761,#154767),.PCURVE_S1.); -#154757 = LINE('',#154758,#154759); -#154758 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); -#154759 = VECTOR('',#154760,1.); -#154760 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154761 = PCURVE('',#154222,#154762); -#154762 = DEFINITIONAL_REPRESENTATION('',(#154763),#154766); -#154763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154764,#154765), +#157137 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#157138 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157140 = ORIENTED_EDGE('',*,*,#156574,.T.); +#157141 = ORIENTED_EDGE('',*,*,#154371,.T.); +#157142 = ADVANCED_FACE('',(#157143),#156614,.T.); +#157143 = FACE_BOUND('',#157144,.T.); +#157144 = EDGE_LOOP('',(#157145,#157146,#157166,#157167)); +#157145 = ORIENTED_EDGE('',*,*,#157047,.F.); +#157146 = ORIENTED_EDGE('',*,*,#157147,.F.); +#157147 = EDGE_CURVE('',#156598,#157025,#157148,.T.); +#157148 = SURFACE_CURVE('',#157149,(#157153,#157159),.PCURVE_S1.); +#157149 = LINE('',#157150,#157151); +#157150 = CARTESIAN_POINT('',(0.706000000002,0.66733334,-0.825)); +#157151 = VECTOR('',#157152,1.); +#157152 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157153 = PCURVE('',#156614,#157154); +#157154 = DEFINITIONAL_REPRESENTATION('',(#157155),#157158); +#157155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157156,#157157), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154765 = CARTESIAN_POINT('',(0.E+000,0.35)); -#154766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154767 = PCURVE('',#154249,#154768); -#154768 = DEFINITIONAL_REPRESENTATION('',(#154769),#154773); -#154769 = LINE('',#154770,#154771); -#154770 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154771 = VECTOR('',#154772,1.); -#154772 = DIRECTION('',(-1.,0.E+000)); -#154773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154774 = ORIENTED_EDGE('',*,*,#154205,.T.); -#154775 = ORIENTED_EDGE('',*,*,#154729,.T.); -#154776 = ADVANCED_FACE('',(#154777),#154249,.T.); -#154777 = FACE_BOUND('',#154778,.T.); -#154778 = EDGE_LOOP('',(#154779,#154780,#154800,#154801)); -#154779 = ORIENTED_EDGE('',*,*,#154632,.F.); -#154780 = ORIENTED_EDGE('',*,*,#154781,.F.); -#154781 = EDGE_CURVE('',#154234,#154606,#154782,.T.); -#154782 = SURFACE_CURVE('',#154783,(#154787,#154794),.PCURVE_S1.); -#154783 = LINE('',#154784,#154785); -#154784 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.825) - ); -#154785 = VECTOR('',#154786,1.); -#154786 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154787 = PCURVE('',#154249,#154788); -#154788 = DEFINITIONAL_REPRESENTATION('',(#154789),#154793); -#154789 = LINE('',#154790,#154791); -#154790 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#154791 = VECTOR('',#154792,1.); -#154792 = DIRECTION('',(-1.,0.E+000)); -#154793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154794 = PCURVE('',#154282,#154795); -#154795 = DEFINITIONAL_REPRESENTATION('',(#154796),#154799); -#154796 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154797,#154798), +#157156 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157157 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157159 = PCURVE('',#156641,#157160); +#157160 = DEFINITIONAL_REPRESENTATION('',(#157161),#157165); +#157161 = LINE('',#157162,#157163); +#157162 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157163 = VECTOR('',#157164,1.); +#157164 = DIRECTION('',(-1.,0.E+000)); +#157165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157166 = ORIENTED_EDGE('',*,*,#156597,.T.); +#157167 = ORIENTED_EDGE('',*,*,#157121,.T.); +#157168 = ADVANCED_FACE('',(#157169),#156641,.T.); +#157169 = FACE_BOUND('',#157170,.T.); +#157170 = EDGE_LOOP('',(#157171,#157172,#157192,#157193)); +#157171 = ORIENTED_EDGE('',*,*,#157024,.F.); +#157172 = ORIENTED_EDGE('',*,*,#157173,.F.); +#157173 = EDGE_CURVE('',#156626,#156998,#157174,.T.); +#157174 = SURFACE_CURVE('',#157175,(#157179,#157186),.PCURVE_S1.); +#157175 = LINE('',#157176,#157177); +#157176 = CARTESIAN_POINT('',(0.706000000002,5.501413505592E-002,-0.825) + ); +#157177 = VECTOR('',#157178,1.); +#157178 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157179 = PCURVE('',#156641,#157180); +#157180 = DEFINITIONAL_REPRESENTATION('',(#157181),#157185); +#157181 = LINE('',#157182,#157183); +#157182 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#157183 = VECTOR('',#157184,1.); +#157184 = DIRECTION('',(-1.,0.E+000)); +#157185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157186 = PCURVE('',#156674,#157187); +#157187 = DEFINITIONAL_REPRESENTATION('',(#157188),#157191); +#157188 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157189,#157190), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154797 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#154798 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#154799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154800 = ORIENTED_EDGE('',*,*,#154233,.T.); -#154801 = ORIENTED_EDGE('',*,*,#154755,.T.); -#154802 = ADVANCED_FACE('',(#154803),#154282,.F.); -#154803 = FACE_BOUND('',#154804,.F.); -#154804 = EDGE_LOOP('',(#154805,#154806,#154807,#154808)); -#154805 = ORIENTED_EDGE('',*,*,#154605,.T.); -#154806 = ORIENTED_EDGE('',*,*,#154781,.F.); -#154807 = ORIENTED_EDGE('',*,*,#154261,.F.); -#154808 = ORIENTED_EDGE('',*,*,#154809,.T.); -#154809 = EDGE_CURVE('',#154262,#154583,#154810,.T.); -#154810 = SURFACE_CURVE('',#154811,(#154815,#154821),.PCURVE_S1.); -#154811 = LINE('',#154812,#154813); -#154812 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.825) - ); -#154813 = VECTOR('',#154814,1.); -#154814 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154815 = PCURVE('',#154282,#154816); -#154816 = DEFINITIONAL_REPRESENTATION('',(#154817),#154820); -#154817 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154818,#154819), +#157189 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#157190 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#157191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157192 = ORIENTED_EDGE('',*,*,#156625,.T.); +#157193 = ORIENTED_EDGE('',*,*,#157147,.T.); +#157194 = ADVANCED_FACE('',(#157195),#156674,.F.); +#157195 = FACE_BOUND('',#157196,.F.); +#157196 = EDGE_LOOP('',(#157197,#157198,#157199,#157200)); +#157197 = ORIENTED_EDGE('',*,*,#156997,.T.); +#157198 = ORIENTED_EDGE('',*,*,#157173,.F.); +#157199 = ORIENTED_EDGE('',*,*,#156653,.F.); +#157200 = ORIENTED_EDGE('',*,*,#157201,.T.); +#157201 = EDGE_CURVE('',#156654,#156975,#157202,.T.); +#157202 = SURFACE_CURVE('',#157203,(#157207,#157213),.PCURVE_S1.); +#157203 = LINE('',#157204,#157205); +#157204 = CARTESIAN_POINT('',(0.720883896422,3.905311025177E-002,-0.825) + ); +#157205 = VECTOR('',#157206,1.); +#157206 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157207 = PCURVE('',#156674,#157208); +#157208 = DEFINITIONAL_REPRESENTATION('',(#157209),#157212); +#157209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157210,#157211), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154818 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#154819 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#154820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154821 = PCURVE('',#154309,#154822); -#154822 = DEFINITIONAL_REPRESENTATION('',(#154823),#154827); -#154823 = LINE('',#154824,#154825); -#154824 = CARTESIAN_POINT('',(1.112358904841E-016,0.E+000)); -#154825 = VECTOR('',#154826,1.); -#154826 = DIRECTION('',(0.E+000,1.)); -#154827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154828 = ADVANCED_FACE('',(#154829),#154309,.T.); -#154829 = FACE_BOUND('',#154830,.T.); -#154830 = EDGE_LOOP('',(#154831,#154832,#154853,#154854)); -#154831 = ORIENTED_EDGE('',*,*,#154582,.F.); -#154832 = ORIENTED_EDGE('',*,*,#154833,.F.); -#154833 = EDGE_CURVE('',#154294,#154560,#154834,.T.); -#154834 = SURFACE_CURVE('',#154835,(#154839,#154846),.PCURVE_S1.); -#154835 = LINE('',#154836,#154837); -#154836 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.825) - ); -#154837 = VECTOR('',#154838,1.); -#154838 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154839 = PCURVE('',#154309,#154840); -#154840 = DEFINITIONAL_REPRESENTATION('',(#154841),#154845); -#154841 = LINE('',#154842,#154843); -#154842 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); -#154843 = VECTOR('',#154844,1.); -#154844 = DIRECTION('',(0.E+000,1.)); -#154845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154846 = PCURVE('',#154337,#154847); -#154847 = DEFINITIONAL_REPRESENTATION('',(#154848),#154852); -#154848 = LINE('',#154849,#154850); -#154849 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#154850 = VECTOR('',#154851,1.); -#154851 = DIRECTION('',(0.E+000,1.)); -#154852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154853 = ORIENTED_EDGE('',*,*,#154293,.T.); -#154854 = ORIENTED_EDGE('',*,*,#154809,.T.); -#154855 = ADVANCED_FACE('',(#154856),#154337,.T.); -#154856 = FACE_BOUND('',#154857,.T.); -#154857 = EDGE_LOOP('',(#154858,#154859,#154880,#154881)); -#154858 = ORIENTED_EDGE('',*,*,#154559,.F.); -#154859 = ORIENTED_EDGE('',*,*,#154860,.F.); -#154860 = EDGE_CURVE('',#154322,#154537,#154861,.T.); -#154861 = SURFACE_CURVE('',#154862,(#154866,#154873),.PCURVE_S1.); -#154862 = LINE('',#154863,#154864); -#154863 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); -#154864 = VECTOR('',#154865,1.); -#154865 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154866 = PCURVE('',#154337,#154867); -#154867 = DEFINITIONAL_REPRESENTATION('',(#154868),#154872); -#154868 = LINE('',#154869,#154870); -#154869 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154870 = VECTOR('',#154871,1.); -#154871 = DIRECTION('',(0.E+000,1.)); -#154872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154873 = PCURVE('',#154365,#154874); -#154874 = DEFINITIONAL_REPRESENTATION('',(#154875),#154879); -#154875 = LINE('',#154876,#154877); -#154876 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); -#154877 = VECTOR('',#154878,1.); -#154878 = DIRECTION('',(0.E+000,1.)); -#154879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154880 = ORIENTED_EDGE('',*,*,#154321,.T.); -#154881 = ORIENTED_EDGE('',*,*,#154833,.T.); -#154882 = ADVANCED_FACE('',(#154883),#154365,.T.); -#154883 = FACE_BOUND('',#154884,.T.); -#154884 = EDGE_LOOP('',(#154885,#154886,#154906,#154907)); -#154885 = ORIENTED_EDGE('',*,*,#154536,.F.); -#154886 = ORIENTED_EDGE('',*,*,#154887,.F.); -#154887 = EDGE_CURVE('',#154350,#154514,#154888,.T.); -#154888 = SURFACE_CURVE('',#154889,(#154893,#154900),.PCURVE_S1.); -#154889 = LINE('',#154890,#154891); -#154890 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) - ); -#154891 = VECTOR('',#154892,1.); -#154892 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154893 = PCURVE('',#154365,#154894); -#154894 = DEFINITIONAL_REPRESENTATION('',(#154895),#154899); -#154895 = LINE('',#154896,#154897); -#154896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154897 = VECTOR('',#154898,1.); -#154898 = DIRECTION('',(0.E+000,1.)); -#154899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154900 = PCURVE('',#154394,#154901); -#154901 = DEFINITIONAL_REPRESENTATION('',(#154902),#154905); -#154902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154903,#154904), +#157210 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#157211 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#157212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157213 = PCURVE('',#156701,#157214); +#157214 = DEFINITIONAL_REPRESENTATION('',(#157215),#157219); +#157215 = LINE('',#157216,#157217); +#157216 = CARTESIAN_POINT('',(1.112358904841E-016,0.E+000)); +#157217 = VECTOR('',#157218,1.); +#157218 = DIRECTION('',(0.E+000,1.)); +#157219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157220 = ADVANCED_FACE('',(#157221),#156701,.T.); +#157221 = FACE_BOUND('',#157222,.T.); +#157222 = EDGE_LOOP('',(#157223,#157224,#157245,#157246)); +#157223 = ORIENTED_EDGE('',*,*,#156974,.F.); +#157224 = ORIENTED_EDGE('',*,*,#157225,.F.); +#157225 = EDGE_CURVE('',#156686,#156952,#157226,.T.); +#157226 = SURFACE_CURVE('',#157227,(#157231,#157238),.PCURVE_S1.); +#157227 = LINE('',#157228,#157229); +#157228 = CARTESIAN_POINT('',(1.05111610358,1.596102480416E-002,-0.825) + ); +#157229 = VECTOR('',#157230,1.); +#157230 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157231 = PCURVE('',#156701,#157232); +#157232 = DEFINITIONAL_REPRESENTATION('',(#157233),#157237); +#157233 = LINE('',#157234,#157235); +#157234 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); +#157235 = VECTOR('',#157236,1.); +#157236 = DIRECTION('',(0.E+000,1.)); +#157237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157238 = PCURVE('',#156729,#157239); +#157239 = DEFINITIONAL_REPRESENTATION('',(#157240),#157244); +#157240 = LINE('',#157241,#157242); +#157241 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#157242 = VECTOR('',#157243,1.); +#157243 = DIRECTION('',(0.E+000,1.)); +#157244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157245 = ORIENTED_EDGE('',*,*,#156685,.T.); +#157246 = ORIENTED_EDGE('',*,*,#157201,.T.); +#157247 = ADVANCED_FACE('',(#157248),#156729,.T.); +#157248 = FACE_BOUND('',#157249,.T.); +#157249 = EDGE_LOOP('',(#157250,#157251,#157272,#157273)); +#157250 = ORIENTED_EDGE('',*,*,#156951,.F.); +#157251 = ORIENTED_EDGE('',*,*,#157252,.F.); +#157252 = EDGE_CURVE('',#156714,#156929,#157253,.T.); +#157253 = SURFACE_CURVE('',#157254,(#157258,#157265),.PCURVE_S1.); +#157254 = LINE('',#157255,#157256); +#157255 = CARTESIAN_POINT('',(1.05,0.E+000,-0.825)); +#157256 = VECTOR('',#157257,1.); +#157257 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157258 = PCURVE('',#156729,#157259); +#157259 = DEFINITIONAL_REPRESENTATION('',(#157260),#157264); +#157260 = LINE('',#157261,#157262); +#157261 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157262 = VECTOR('',#157263,1.); +#157263 = DIRECTION('',(0.E+000,1.)); +#157264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157265 = PCURVE('',#156757,#157266); +#157266 = DEFINITIONAL_REPRESENTATION('',(#157267),#157271); +#157267 = LINE('',#157268,#157269); +#157268 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); +#157269 = VECTOR('',#157270,1.); +#157270 = DIRECTION('',(0.E+000,1.)); +#157271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157272 = ORIENTED_EDGE('',*,*,#156713,.T.); +#157273 = ORIENTED_EDGE('',*,*,#157225,.T.); +#157274 = ADVANCED_FACE('',(#157275),#156757,.T.); +#157275 = FACE_BOUND('',#157276,.T.); +#157276 = EDGE_LOOP('',(#157277,#157278,#157298,#157299)); +#157277 = ORIENTED_EDGE('',*,*,#156928,.F.); +#157278 = ORIENTED_EDGE('',*,*,#157279,.F.); +#157279 = EDGE_CURVE('',#156742,#156906,#157280,.T.); +#157280 = SURFACE_CURVE('',#157281,(#157285,#157292),.PCURVE_S1.); +#157281 = LINE('',#157282,#157283); +#157282 = CARTESIAN_POINT('',(0.719767792842,2.309208544762E-002,-0.825) + ); +#157283 = VECTOR('',#157284,1.); +#157284 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157285 = PCURVE('',#156757,#157286); +#157286 = DEFINITIONAL_REPRESENTATION('',(#157287),#157291); +#157287 = LINE('',#157288,#157289); +#157288 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157289 = VECTOR('',#157290,1.); +#157290 = DIRECTION('',(0.E+000,1.)); +#157291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157292 = PCURVE('',#156786,#157293); +#157293 = DEFINITIONAL_REPRESENTATION('',(#157294),#157297); +#157294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157295,#157296), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154903 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#154904 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#154905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154906 = ORIENTED_EDGE('',*,*,#154349,.T.); -#154907 = ORIENTED_EDGE('',*,*,#154860,.T.); -#154908 = ADVANCED_FACE('',(#154909),#154394,.T.); -#154909 = FACE_BOUND('',#154910,.T.); -#154910 = EDGE_LOOP('',(#154911,#154912,#154932,#154933)); -#154911 = ORIENTED_EDGE('',*,*,#154513,.F.); -#154912 = ORIENTED_EDGE('',*,*,#154913,.F.); -#154913 = EDGE_CURVE('',#154378,#154491,#154914,.T.); -#154914 = SURFACE_CURVE('',#154915,(#154919,#154925),.PCURVE_S1.); -#154915 = LINE('',#154916,#154917); -#154916 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.825) - ); -#154917 = VECTOR('',#154918,1.); -#154918 = DIRECTION('',(0.E+000,0.E+000,1.)); -#154919 = PCURVE('',#154394,#154920); -#154920 = DEFINITIONAL_REPRESENTATION('',(#154921),#154924); -#154921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154922,#154923), +#157295 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#157296 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#157297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157298 = ORIENTED_EDGE('',*,*,#156741,.T.); +#157299 = ORIENTED_EDGE('',*,*,#157252,.T.); +#157300 = ADVANCED_FACE('',(#157301),#156786,.T.); +#157301 = FACE_BOUND('',#157302,.T.); +#157302 = EDGE_LOOP('',(#157303,#157304,#157324,#157325)); +#157303 = ORIENTED_EDGE('',*,*,#156905,.F.); +#157304 = ORIENTED_EDGE('',*,*,#157305,.F.); +#157305 = EDGE_CURVE('',#156770,#156883,#157306,.T.); +#157306 = SURFACE_CURVE('',#157307,(#157311,#157317),.PCURVE_S1.); +#157307 = LINE('',#157308,#157309); +#157308 = CARTESIAN_POINT('',(0.690000000002,5.501413505593E-002,-0.825) + ); +#157309 = VECTOR('',#157310,1.); +#157310 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157311 = PCURVE('',#156786,#157312); +#157312 = DEFINITIONAL_REPRESENTATION('',(#157313),#157316); +#157313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157314,#157315), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154922 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); -#154923 = CARTESIAN_POINT('',(3.141592653589,0.35)); -#154924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154925 = PCURVE('',#154421,#154926); -#154926 = DEFINITIONAL_REPRESENTATION('',(#154927),#154931); -#154927 = LINE('',#154928,#154929); -#154928 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#154929 = VECTOR('',#154930,1.); -#154930 = DIRECTION('',(1.,0.E+000)); -#154931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154932 = ORIENTED_EDGE('',*,*,#154377,.T.); -#154933 = ORIENTED_EDGE('',*,*,#154887,.T.); -#154934 = ADVANCED_FACE('',(#154935),#154421,.T.); -#154935 = FACE_BOUND('',#154936,.T.); -#154936 = EDGE_LOOP('',(#154937,#154938,#154939,#154940)); -#154937 = ORIENTED_EDGE('',*,*,#154490,.F.); -#154938 = ORIENTED_EDGE('',*,*,#154703,.F.); -#154939 = ORIENTED_EDGE('',*,*,#154405,.T.); -#154940 = ORIENTED_EDGE('',*,*,#154913,.T.); -#154941 = ADVANCED_FACE('',(#154942),#152095,.T.); -#154942 = FACE_BOUND('',#154943,.T.); -#154943 = EDGE_LOOP('',(#154944,#154945,#154968,#154995)); -#154944 = ORIENTED_EDGE('',*,*,#152081,.F.); -#154945 = ORIENTED_EDGE('',*,*,#154946,.T.); -#154946 = EDGE_CURVE('',#151531,#154947,#154949,.T.); -#154947 = VERTEX_POINT('',#154948); -#154948 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.825)); -#154949 = SURFACE_CURVE('',#154950,(#154954,#154961),.PCURVE_S1.); -#154950 = LINE('',#154951,#154952); -#154951 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.825)); -#154952 = VECTOR('',#154953,1.); -#154953 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); -#154954 = PCURVE('',#152095,#154955); -#154955 = DEFINITIONAL_REPRESENTATION('',(#154956),#154960); -#154956 = LINE('',#154957,#154958); -#154957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#154958 = VECTOR('',#154959,1.); -#154959 = DIRECTION('',(-1.,0.E+000)); -#154960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154961 = PCURVE('',#151546,#154962); -#154962 = DEFINITIONAL_REPRESENTATION('',(#154963),#154967); -#154963 = LINE('',#154964,#154965); -#154964 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); -#154965 = VECTOR('',#154966,1.); -#154966 = DIRECTION('',(-1.,1.07686155438E-015)); -#154967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154968 = ORIENTED_EDGE('',*,*,#154969,.T.); -#154969 = EDGE_CURVE('',#154947,#154970,#154972,.T.); -#154970 = VERTEX_POINT('',#154971); -#154971 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.475)); -#154972 = SURFACE_CURVE('',#154973,(#154977,#154984),.PCURVE_S1.); -#154973 = LINE('',#154974,#154975); -#154974 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.825)); -#154975 = VECTOR('',#154976,1.); -#154976 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154977 = PCURVE('',#152095,#154978); -#154978 = DEFINITIONAL_REPRESENTATION('',(#154979),#154983); -#154979 = LINE('',#154980,#154981); -#154980 = CARTESIAN_POINT('',(-0.100681667766,0.E+000)); -#154981 = VECTOR('',#154982,1.); -#154982 = DIRECTION('',(0.E+000,-1.)); -#154983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154984 = PCURVE('',#154985,#154990); -#154985 = CYLINDRICAL_SURFACE('',#154986,1.6E-002); -#154986 = AXIS2_PLACEMENT_3D('',#154987,#154988,#154989); -#154987 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); -#154988 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#154989 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#154990 = DEFINITIONAL_REPRESENTATION('',(#154991),#154994); -#154991 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#154992,#154993), +#157314 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); +#157315 = CARTESIAN_POINT('',(3.141592653589,0.35)); +#157316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157317 = PCURVE('',#156813,#157318); +#157318 = DEFINITIONAL_REPRESENTATION('',(#157319),#157323); +#157319 = LINE('',#157320,#157321); +#157320 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#157321 = VECTOR('',#157322,1.); +#157322 = DIRECTION('',(1.,0.E+000)); +#157323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157324 = ORIENTED_EDGE('',*,*,#156769,.T.); +#157325 = ORIENTED_EDGE('',*,*,#157279,.T.); +#157326 = ADVANCED_FACE('',(#157327),#156813,.T.); +#157327 = FACE_BOUND('',#157328,.T.); +#157328 = EDGE_LOOP('',(#157329,#157330,#157331,#157332)); +#157329 = ORIENTED_EDGE('',*,*,#156882,.F.); +#157330 = ORIENTED_EDGE('',*,*,#157095,.F.); +#157331 = ORIENTED_EDGE('',*,*,#156797,.T.); +#157332 = ORIENTED_EDGE('',*,*,#157305,.T.); +#157333 = ADVANCED_FACE('',(#157334),#154487,.T.); +#157334 = FACE_BOUND('',#157335,.T.); +#157335 = EDGE_LOOP('',(#157336,#157337,#157360,#157387)); +#157336 = ORIENTED_EDGE('',*,*,#154473,.F.); +#157337 = ORIENTED_EDGE('',*,*,#157338,.T.); +#157338 = EDGE_CURVE('',#153923,#157339,#157341,.T.); +#157339 = VERTEX_POINT('',#157340); +#157340 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.825)); +#157341 = SURFACE_CURVE('',#157342,(#157346,#157353),.PCURVE_S1.); +#157342 = LINE('',#157343,#157344); +#157343 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.825)); +#157344 = VECTOR('',#157345,1.); +#157345 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); +#157346 = PCURVE('',#154487,#157347); +#157347 = DEFINITIONAL_REPRESENTATION('',(#157348),#157352); +#157348 = LINE('',#157349,#157350); +#157349 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157350 = VECTOR('',#157351,1.); +#157351 = DIRECTION('',(-1.,0.E+000)); +#157352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157353 = PCURVE('',#153938,#157354); +#157354 = DEFINITIONAL_REPRESENTATION('',(#157355),#157359); +#157355 = LINE('',#157356,#157357); +#157356 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); +#157357 = VECTOR('',#157358,1.); +#157358 = DIRECTION('',(-1.,1.07686155438E-015)); +#157359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157360 = ORIENTED_EDGE('',*,*,#157361,.T.); +#157361 = EDGE_CURVE('',#157339,#157362,#157364,.T.); +#157362 = VERTEX_POINT('',#157363); +#157363 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.475)); +#157364 = SURFACE_CURVE('',#157365,(#157369,#157376),.PCURVE_S1.); +#157365 = LINE('',#157366,#157367); +#157366 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,0.825)); +#157367 = VECTOR('',#157368,1.); +#157368 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157369 = PCURVE('',#154487,#157370); +#157370 = DEFINITIONAL_REPRESENTATION('',(#157371),#157375); +#157371 = LINE('',#157372,#157373); +#157372 = CARTESIAN_POINT('',(-0.100681667766,0.E+000)); +#157373 = VECTOR('',#157374,1.); +#157374 = DIRECTION('',(0.E+000,-1.)); +#157375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157376 = PCURVE('',#157377,#157382); +#157377 = CYLINDRICAL_SURFACE('',#157378,1.6E-002); +#157378 = AXIS2_PLACEMENT_3D('',#157379,#157380,#157381); +#157379 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); +#157380 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157381 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157382 = DEFINITIONAL_REPRESENTATION('',(#157383),#157386); +#157383 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157384,#157385), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#154992 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#154993 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#154994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#154995 = ORIENTED_EDGE('',*,*,#154996,.F.); -#154996 = EDGE_CURVE('',#151452,#154970,#154997,.T.); -#154997 = SURFACE_CURVE('',#154998,(#155002,#155009),.PCURVE_S1.); -#154998 = LINE('',#154999,#155000); -#154999 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.475)); -#155000 = VECTOR('',#155001,1.); -#155001 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); -#155002 = PCURVE('',#152095,#155003); -#155003 = DEFINITIONAL_REPRESENTATION('',(#155004),#155008); -#155004 = LINE('',#155005,#155006); -#155005 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#155006 = VECTOR('',#155007,1.); -#155007 = DIRECTION('',(-1.,0.E+000)); -#155008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155009 = PCURVE('',#151490,#155010); -#155010 = DEFINITIONAL_REPRESENTATION('',(#155011),#155015); -#155011 = LINE('',#155012,#155013); -#155012 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); -#155013 = VECTOR('',#155014,1.); -#155014 = DIRECTION('',(-1.,1.07686155438E-015)); -#155015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155016 = ADVANCED_FACE('',(#155017),#151546,.F.); -#155017 = FACE_BOUND('',#155018,.T.); -#155018 = EDGE_LOOP('',(#155019,#155020,#155021,#155044,#155072,#155100, - #155132,#155160,#155188,#155216,#155244,#155272)); -#155019 = ORIENTED_EDGE('',*,*,#154946,.F.); -#155020 = ORIENTED_EDGE('',*,*,#151530,.T.); -#155021 = ORIENTED_EDGE('',*,*,#155022,.F.); -#155022 = EDGE_CURVE('',#155023,#151503,#155025,.T.); -#155023 = VERTEX_POINT('',#155024); -#155024 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.825)); -#155025 = SURFACE_CURVE('',#155026,(#155030,#155037),.PCURVE_S1.); -#155026 = LINE('',#155027,#155028); -#155027 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); -#155028 = VECTOR('',#155029,1.); -#155029 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155030 = PCURVE('',#151546,#155031); -#155031 = DEFINITIONAL_REPRESENTATION('',(#155032),#155036); -#155032 = LINE('',#155033,#155034); -#155033 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); -#155034 = VECTOR('',#155035,1.); -#155035 = DIRECTION('',(1.,0.E+000)); -#155036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155037 = PCURVE('',#151518,#155038); -#155038 = DEFINITIONAL_REPRESENTATION('',(#155039),#155043); -#155039 = LINE('',#155040,#155041); -#155040 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155041 = VECTOR('',#155042,1.); -#155042 = DIRECTION('',(0.E+000,1.)); -#155043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155044 = ORIENTED_EDGE('',*,*,#155045,.F.); -#155045 = EDGE_CURVE('',#155046,#155023,#155048,.T.); -#155046 = VERTEX_POINT('',#155047); -#155047 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); -#155048 = SURFACE_CURVE('',#155049,(#155054,#155061),.PCURVE_S1.); -#155049 = CIRCLE('',#155050,3.2E-002); -#155050 = AXIS2_PLACEMENT_3D('',#155051,#155052,#155053); -#155051 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); -#155052 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155053 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155054 = PCURVE('',#151546,#155055); -#155055 = DEFINITIONAL_REPRESENTATION('',(#155056),#155060); -#155056 = CIRCLE('',#155057,3.2E-002); -#155057 = AXIS2_PLACEMENT_2D('',#155058,#155059); -#155058 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155059 = DIRECTION('',(1.,0.E+000)); -#155060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155061 = PCURVE('',#155062,#155067); -#155062 = CYLINDRICAL_SURFACE('',#155063,3.2E-002); -#155063 = AXIS2_PLACEMENT_3D('',#155064,#155065,#155066); -#155064 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); -#155065 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155066 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155067 = DEFINITIONAL_REPRESENTATION('',(#155068),#155071); -#155068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155069,#155070), +#157384 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#157385 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157387 = ORIENTED_EDGE('',*,*,#157388,.F.); +#157388 = EDGE_CURVE('',#153844,#157362,#157389,.T.); +#157389 = SURFACE_CURVE('',#157390,(#157394,#157401),.PCURVE_S1.); +#157390 = LINE('',#157391,#157392); +#157391 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,0.475)); +#157392 = VECTOR('',#157393,1.); +#157393 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); +#157394 = PCURVE('',#154487,#157395); +#157395 = DEFINITIONAL_REPRESENTATION('',(#157396),#157400); +#157396 = LINE('',#157397,#157398); +#157397 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#157398 = VECTOR('',#157399,1.); +#157399 = DIRECTION('',(-1.,0.E+000)); +#157400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157401 = PCURVE('',#153882,#157402); +#157402 = DEFINITIONAL_REPRESENTATION('',(#157403),#157407); +#157403 = LINE('',#157404,#157405); +#157404 = CARTESIAN_POINT('',(0.100681667766,-1.6E-002)); +#157405 = VECTOR('',#157406,1.); +#157406 = DIRECTION('',(-1.,1.07686155438E-015)); +#157407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157408 = ADVANCED_FACE('',(#157409),#153938,.F.); +#157409 = FACE_BOUND('',#157410,.T.); +#157410 = EDGE_LOOP('',(#157411,#157412,#157413,#157436,#157464,#157492, + #157524,#157552,#157580,#157608,#157636,#157664)); +#157411 = ORIENTED_EDGE('',*,*,#157338,.F.); +#157412 = ORIENTED_EDGE('',*,*,#153922,.T.); +#157413 = ORIENTED_EDGE('',*,*,#157414,.F.); +#157414 = EDGE_CURVE('',#157415,#153895,#157417,.T.); +#157415 = VERTEX_POINT('',#157416); +#157416 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.825)); +#157417 = SURFACE_CURVE('',#157418,(#157422,#157429),.PCURVE_S1.); +#157418 = LINE('',#157419,#157420); +#157419 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.825)); +#157420 = VECTOR('',#157421,1.); +#157421 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157422 = PCURVE('',#153938,#157423); +#157423 = DEFINITIONAL_REPRESENTATION('',(#157424),#157428); +#157424 = LINE('',#157425,#157426); +#157425 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); +#157426 = VECTOR('',#157427,1.); +#157427 = DIRECTION('',(1.,0.E+000)); +#157428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157429 = PCURVE('',#153910,#157430); +#157430 = DEFINITIONAL_REPRESENTATION('',(#157431),#157435); +#157431 = LINE('',#157432,#157433); +#157432 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157433 = VECTOR('',#157434,1.); +#157434 = DIRECTION('',(0.E+000,1.)); +#157435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157436 = ORIENTED_EDGE('',*,*,#157437,.F.); +#157437 = EDGE_CURVE('',#157438,#157415,#157440,.T.); +#157438 = VERTEX_POINT('',#157439); +#157439 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); +#157440 = SURFACE_CURVE('',#157441,(#157446,#157453),.PCURVE_S1.); +#157441 = CIRCLE('',#157442,3.2E-002); +#157442 = AXIS2_PLACEMENT_3D('',#157443,#157444,#157445); +#157443 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); +#157444 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157445 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157446 = PCURVE('',#153938,#157447); +#157447 = DEFINITIONAL_REPRESENTATION('',(#157448),#157452); +#157448 = CIRCLE('',#157449,3.2E-002); +#157449 = AXIS2_PLACEMENT_2D('',#157450,#157451); +#157450 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157451 = DIRECTION('',(1.,0.E+000)); +#157452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157453 = PCURVE('',#157454,#157459); +#157454 = CYLINDRICAL_SURFACE('',#157455,3.2E-002); +#157455 = AXIS2_PLACEMENT_3D('',#157456,#157457,#157458); +#157456 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); +#157457 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157458 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157459 = DEFINITIONAL_REPRESENTATION('',(#157460),#157463); +#157460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157461,#157462), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#155069 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155070 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#155071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155072 = ORIENTED_EDGE('',*,*,#155073,.F.); -#155073 = EDGE_CURVE('',#155074,#155046,#155076,.T.); -#155074 = VERTEX_POINT('',#155075); -#155075 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.825) - ); -#155076 = SURFACE_CURVE('',#155077,(#155081,#155088),.PCURVE_S1.); -#155077 = LINE('',#155078,#155079); -#155078 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); -#155079 = VECTOR('',#155080,1.); -#155080 = DIRECTION('',(0.E+000,1.,0.E+000)); -#155081 = PCURVE('',#151546,#155082); -#155082 = DEFINITIONAL_REPRESENTATION('',(#155083),#155087); -#155083 = LINE('',#155084,#155085); -#155084 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#155085 = VECTOR('',#155086,1.); -#155086 = DIRECTION('',(0.E+000,-1.)); -#155087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155088 = PCURVE('',#155089,#155094); -#155089 = PLANE('',#155090); -#155090 = AXIS2_PLACEMENT_3D('',#155091,#155092,#155093); -#155091 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); -#155092 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155093 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155094 = DEFINITIONAL_REPRESENTATION('',(#155095),#155099); -#155095 = LINE('',#155096,#155097); -#155096 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155097 = VECTOR('',#155098,1.); -#155098 = DIRECTION('',(0.E+000,1.)); -#155099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155100 = ORIENTED_EDGE('',*,*,#155101,.F.); -#155101 = EDGE_CURVE('',#155102,#155074,#155104,.T.); -#155102 = VERTEX_POINT('',#155103); -#155103 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.825) - ); -#155104 = SURFACE_CURVE('',#155105,(#155110,#155121),.PCURVE_S1.); -#155105 = CIRCLE('',#155106,1.599999999999E-002); -#155106 = AXIS2_PLACEMENT_3D('',#155107,#155108,#155109); -#155107 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) - ); -#155108 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155109 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155110 = PCURVE('',#151546,#155111); -#155111 = DEFINITIONAL_REPRESENTATION('',(#155112),#155120); -#155112 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155113,#155114,#155115, - #155116,#155117,#155118,#155119),.UNSPECIFIED.,.T.,.F.) +#157461 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157462 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#157463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157464 = ORIENTED_EDGE('',*,*,#157465,.F.); +#157465 = EDGE_CURVE('',#157466,#157438,#157468,.T.); +#157466 = VERTEX_POINT('',#157467); +#157467 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.825) + ); +#157468 = SURFACE_CURVE('',#157469,(#157473,#157480),.PCURVE_S1.); +#157469 = LINE('',#157470,#157471); +#157470 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); +#157471 = VECTOR('',#157472,1.); +#157472 = DIRECTION('',(0.E+000,1.,0.E+000)); +#157473 = PCURVE('',#153938,#157474); +#157474 = DEFINITIONAL_REPRESENTATION('',(#157475),#157479); +#157475 = LINE('',#157476,#157477); +#157476 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#157477 = VECTOR('',#157478,1.); +#157478 = DIRECTION('',(0.E+000,-1.)); +#157479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157480 = PCURVE('',#157481,#157486); +#157481 = PLANE('',#157482); +#157482 = AXIS2_PLACEMENT_3D('',#157483,#157484,#157485); +#157483 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); +#157484 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157485 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157486 = DEFINITIONAL_REPRESENTATION('',(#157487),#157491); +#157487 = LINE('',#157488,#157489); +#157488 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157489 = VECTOR('',#157490,1.); +#157490 = DIRECTION('',(0.E+000,1.)); +#157491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157492 = ORIENTED_EDGE('',*,*,#157493,.F.); +#157493 = EDGE_CURVE('',#157494,#157466,#157496,.T.); +#157494 = VERTEX_POINT('',#157495); +#157495 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.825) + ); +#157496 = SURFACE_CURVE('',#157497,(#157502,#157513),.PCURVE_S1.); +#157497 = CIRCLE('',#157498,1.599999999999E-002); +#157498 = AXIS2_PLACEMENT_3D('',#157499,#157500,#157501); +#157499 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) + ); +#157500 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157501 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157502 = PCURVE('',#153938,#157503); +#157503 = DEFINITIONAL_REPRESENTATION('',(#157504),#157512); +#157504 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157505,#157506,#157507, + #157508,#157509,#157510,#157511),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#155113 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#155114 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); -#155115 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); -#155116 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); -#155117 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); -#155118 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); -#155119 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#155120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155121 = PCURVE('',#155122,#155127); -#155122 = CYLINDRICAL_SURFACE('',#155123,1.599999999999E-002); -#155123 = AXIS2_PLACEMENT_3D('',#155124,#155125,#155126); -#155124 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) - ); -#155125 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155126 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155127 = DEFINITIONAL_REPRESENTATION('',(#155128),#155131); -#155128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155129,#155130), +#157505 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157506 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); +#157507 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); +#157508 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); +#157509 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); +#157510 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); +#157511 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157513 = PCURVE('',#157514,#157519); +#157514 = CYLINDRICAL_SURFACE('',#157515,1.599999999999E-002); +#157515 = AXIS2_PLACEMENT_3D('',#157516,#157517,#157518); +#157516 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) + ); +#157517 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157518 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157519 = DEFINITIONAL_REPRESENTATION('',(#157520),#157523); +#157520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157521,#157522), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#155129 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#155130 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#155131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155132 = ORIENTED_EDGE('',*,*,#155133,.F.); -#155133 = EDGE_CURVE('',#155134,#155102,#155136,.T.); -#155134 = VERTEX_POINT('',#155135); -#155135 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.825) - ); -#155136 = SURFACE_CURVE('',#155137,(#155141,#155148),.PCURVE_S1.); -#155137 = LINE('',#155138,#155139); -#155138 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.825) - ); -#155139 = VECTOR('',#155140,1.); -#155140 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#155141 = PCURVE('',#151546,#155142); -#155142 = DEFINITIONAL_REPRESENTATION('',(#155143),#155147); -#155143 = LINE('',#155144,#155145); -#155144 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); -#155145 = VECTOR('',#155146,1.); -#155146 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); -#155147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155148 = PCURVE('',#155149,#155154); -#155149 = PLANE('',#155150); -#155150 = AXIS2_PLACEMENT_3D('',#155151,#155152,#155153); -#155151 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.825) - ); -#155152 = DIRECTION('',(-6.975647374417E-002,0.99756405026,0.E+000)); -#155153 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#155154 = DEFINITIONAL_REPRESENTATION('',(#155155),#155159); -#155155 = LINE('',#155156,#155157); -#155156 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155157 = VECTOR('',#155158,1.); -#155158 = DIRECTION('',(-1.,0.E+000)); -#155159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155160 = ORIENTED_EDGE('',*,*,#155161,.F.); -#155161 = EDGE_CURVE('',#155162,#155134,#155164,.T.); -#155162 = VERTEX_POINT('',#155163); -#155163 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); -#155164 = SURFACE_CURVE('',#155165,(#155169,#155176),.PCURVE_S1.); -#155165 = LINE('',#155166,#155167); -#155166 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); -#155167 = VECTOR('',#155168,1.); -#155168 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); -#155169 = PCURVE('',#151546,#155170); -#155170 = DEFINITIONAL_REPRESENTATION('',(#155171),#155175); -#155171 = LINE('',#155172,#155173); -#155172 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); -#155173 = VECTOR('',#155174,1.); -#155174 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); -#155175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155176 = PCURVE('',#155177,#155182); -#155177 = PLANE('',#155178); -#155178 = AXIS2_PLACEMENT_3D('',#155179,#155180,#155181); -#155179 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); -#155180 = DIRECTION('',(-0.99756405026,-6.975647374418E-002,0.E+000)); -#155181 = DIRECTION('',(6.975647374418E-002,-0.99756405026,0.E+000)); -#155182 = DEFINITIONAL_REPRESENTATION('',(#155183),#155187); -#155183 = LINE('',#155184,#155185); -#155184 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155185 = VECTOR('',#155186,1.); -#155186 = DIRECTION('',(-1.,0.E+000)); -#155187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155188 = ORIENTED_EDGE('',*,*,#155189,.F.); -#155189 = EDGE_CURVE('',#155190,#155162,#155192,.T.); -#155190 = VERTEX_POINT('',#155191); -#155191 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) - ); -#155192 = SURFACE_CURVE('',#155193,(#155197,#155204),.PCURVE_S1.); -#155193 = LINE('',#155194,#155195); -#155194 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) - ); -#155195 = VECTOR('',#155196,1.); -#155196 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#155197 = PCURVE('',#151546,#155198); -#155198 = DEFINITIONAL_REPRESENTATION('',(#155199),#155203); -#155199 = LINE('',#155200,#155201); -#155200 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); -#155201 = VECTOR('',#155202,1.); -#155202 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); -#155203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155204 = PCURVE('',#155205,#155210); -#155205 = PLANE('',#155206); -#155206 = AXIS2_PLACEMENT_3D('',#155207,#155208,#155209); -#155207 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) - ); -#155208 = DIRECTION('',(6.975647374417E-002,-0.99756405026,0.E+000)); -#155209 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#155210 = DEFINITIONAL_REPRESENTATION('',(#155211),#155215); -#155211 = LINE('',#155212,#155213); -#155212 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155213 = VECTOR('',#155214,1.); -#155214 = DIRECTION('',(-1.,0.E+000)); -#155215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155216 = ORIENTED_EDGE('',*,*,#155217,.F.); -#155217 = EDGE_CURVE('',#155218,#155190,#155220,.T.); -#155218 = VERTEX_POINT('',#155219); -#155219 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.825) - ); -#155220 = SURFACE_CURVE('',#155221,(#155226,#155233),.PCURVE_S1.); -#155221 = CIRCLE('',#155222,3.199999999999E-002); -#155222 = AXIS2_PLACEMENT_3D('',#155223,#155224,#155225); -#155223 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) - ); -#155224 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155225 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155226 = PCURVE('',#151546,#155227); -#155227 = DEFINITIONAL_REPRESENTATION('',(#155228),#155232); -#155228 = CIRCLE('',#155229,3.199999999999E-002); -#155229 = AXIS2_PLACEMENT_2D('',#155230,#155231); -#155230 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); -#155231 = DIRECTION('',(-1.,0.E+000)); -#155232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155233 = PCURVE('',#155234,#155239); -#155234 = CYLINDRICAL_SURFACE('',#155235,3.199999999999E-002); -#155235 = AXIS2_PLACEMENT_3D('',#155236,#155237,#155238); -#155236 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) - ); -#155237 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155238 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155239 = DEFINITIONAL_REPRESENTATION('',(#155240),#155243); -#155240 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155241,#155242), +#157521 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#157522 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#157523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157524 = ORIENTED_EDGE('',*,*,#157525,.F.); +#157525 = EDGE_CURVE('',#157526,#157494,#157528,.T.); +#157526 = VERTEX_POINT('',#157527); +#157527 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.825) + ); +#157528 = SURFACE_CURVE('',#157529,(#157533,#157540),.PCURVE_S1.); +#157529 = LINE('',#157530,#157531); +#157530 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.825) + ); +#157531 = VECTOR('',#157532,1.); +#157532 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#157533 = PCURVE('',#153938,#157534); +#157534 = DEFINITIONAL_REPRESENTATION('',(#157535),#157539); +#157535 = LINE('',#157536,#157537); +#157536 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); +#157537 = VECTOR('',#157538,1.); +#157538 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); +#157539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157540 = PCURVE('',#157541,#157546); +#157541 = PLANE('',#157542); +#157542 = AXIS2_PLACEMENT_3D('',#157543,#157544,#157545); +#157543 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.825) + ); +#157544 = DIRECTION('',(-6.975647374417E-002,0.99756405026,0.E+000)); +#157545 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#157546 = DEFINITIONAL_REPRESENTATION('',(#157547),#157551); +#157547 = LINE('',#157548,#157549); +#157548 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157549 = VECTOR('',#157550,1.); +#157550 = DIRECTION('',(-1.,0.E+000)); +#157551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157552 = ORIENTED_EDGE('',*,*,#157553,.F.); +#157553 = EDGE_CURVE('',#157554,#157526,#157556,.T.); +#157554 = VERTEX_POINT('',#157555); +#157555 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); +#157556 = SURFACE_CURVE('',#157557,(#157561,#157568),.PCURVE_S1.); +#157557 = LINE('',#157558,#157559); +#157558 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); +#157559 = VECTOR('',#157560,1.); +#157560 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); +#157561 = PCURVE('',#153938,#157562); +#157562 = DEFINITIONAL_REPRESENTATION('',(#157563),#157567); +#157563 = LINE('',#157564,#157565); +#157564 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); +#157565 = VECTOR('',#157566,1.); +#157566 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); +#157567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157568 = PCURVE('',#157569,#157574); +#157569 = PLANE('',#157570); +#157570 = AXIS2_PLACEMENT_3D('',#157571,#157572,#157573); +#157571 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); +#157572 = DIRECTION('',(-0.99756405026,-6.975647374418E-002,0.E+000)); +#157573 = DIRECTION('',(6.975647374418E-002,-0.99756405026,0.E+000)); +#157574 = DEFINITIONAL_REPRESENTATION('',(#157575),#157579); +#157575 = LINE('',#157576,#157577); +#157576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157577 = VECTOR('',#157578,1.); +#157578 = DIRECTION('',(-1.,0.E+000)); +#157579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157580 = ORIENTED_EDGE('',*,*,#157581,.F.); +#157581 = EDGE_CURVE('',#157582,#157554,#157584,.T.); +#157582 = VERTEX_POINT('',#157583); +#157583 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) + ); +#157584 = SURFACE_CURVE('',#157585,(#157589,#157596),.PCURVE_S1.); +#157585 = LINE('',#157586,#157587); +#157586 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) + ); +#157587 = VECTOR('',#157588,1.); +#157588 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#157589 = PCURVE('',#153938,#157590); +#157590 = DEFINITIONAL_REPRESENTATION('',(#157591),#157595); +#157591 = LINE('',#157592,#157593); +#157592 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); +#157593 = VECTOR('',#157594,1.); +#157594 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); +#157595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157596 = PCURVE('',#157597,#157602); +#157597 = PLANE('',#157598); +#157598 = AXIS2_PLACEMENT_3D('',#157599,#157600,#157601); +#157599 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) + ); +#157600 = DIRECTION('',(6.975647374417E-002,-0.99756405026,0.E+000)); +#157601 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#157602 = DEFINITIONAL_REPRESENTATION('',(#157603),#157607); +#157603 = LINE('',#157604,#157605); +#157604 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157605 = VECTOR('',#157606,1.); +#157606 = DIRECTION('',(-1.,0.E+000)); +#157607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157608 = ORIENTED_EDGE('',*,*,#157609,.F.); +#157609 = EDGE_CURVE('',#157610,#157582,#157612,.T.); +#157610 = VERTEX_POINT('',#157611); +#157611 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.825) + ); +#157612 = SURFACE_CURVE('',#157613,(#157618,#157625),.PCURVE_S1.); +#157613 = CIRCLE('',#157614,3.199999999999E-002); +#157614 = AXIS2_PLACEMENT_3D('',#157615,#157616,#157617); +#157615 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) + ); +#157616 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157617 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157618 = PCURVE('',#153938,#157619); +#157619 = DEFINITIONAL_REPRESENTATION('',(#157620),#157624); +#157620 = CIRCLE('',#157621,3.199999999999E-002); +#157621 = AXIS2_PLACEMENT_2D('',#157622,#157623); +#157622 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); +#157623 = DIRECTION('',(-1.,0.E+000)); +#157624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157625 = PCURVE('',#157626,#157631); +#157626 = CYLINDRICAL_SURFACE('',#157627,3.199999999999E-002); +#157627 = AXIS2_PLACEMENT_3D('',#157628,#157629,#157630); +#157628 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.825) + ); +#157629 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157630 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157631 = DEFINITIONAL_REPRESENTATION('',(#157632),#157635); +#157632 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157633,#157634), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#155241 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); -#155242 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#155243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155244 = ORIENTED_EDGE('',*,*,#155245,.F.); -#155245 = EDGE_CURVE('',#155246,#155218,#155248,.T.); -#155246 = VERTEX_POINT('',#155247); -#155247 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); -#155248 = SURFACE_CURVE('',#155249,(#155253,#155260),.PCURVE_S1.); -#155249 = LINE('',#155250,#155251); -#155250 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); -#155251 = VECTOR('',#155252,1.); -#155252 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#155253 = PCURVE('',#151546,#155254); -#155254 = DEFINITIONAL_REPRESENTATION('',(#155255),#155259); -#155255 = LINE('',#155256,#155257); -#155256 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#155257 = VECTOR('',#155258,1.); -#155258 = DIRECTION('',(0.E+000,1.)); -#155259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155260 = PCURVE('',#155261,#155266); -#155261 = PLANE('',#155262); -#155262 = AXIS2_PLACEMENT_3D('',#155263,#155264,#155265); -#155263 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); -#155264 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155265 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155266 = DEFINITIONAL_REPRESENTATION('',(#155267),#155271); -#155267 = LINE('',#155268,#155269); -#155268 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155269 = VECTOR('',#155270,1.); -#155270 = DIRECTION('',(0.E+000,-1.)); -#155271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155272 = ORIENTED_EDGE('',*,*,#155273,.F.); -#155273 = EDGE_CURVE('',#154947,#155246,#155274,.T.); -#155274 = SURFACE_CURVE('',#155275,(#155280,#155291),.PCURVE_S1.); -#155275 = CIRCLE('',#155276,1.6E-002); -#155276 = AXIS2_PLACEMENT_3D('',#155277,#155278,#155279); -#155277 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); -#155278 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155279 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155280 = PCURVE('',#151546,#155281); -#155281 = DEFINITIONAL_REPRESENTATION('',(#155282),#155290); -#155282 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155283,#155284,#155285, - #155286,#155287,#155288,#155289),.UNSPECIFIED.,.F.,.F.) +#157633 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); +#157634 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#157635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157636 = ORIENTED_EDGE('',*,*,#157637,.F.); +#157637 = EDGE_CURVE('',#157638,#157610,#157640,.T.); +#157638 = VERTEX_POINT('',#157639); +#157639 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); +#157640 = SURFACE_CURVE('',#157641,(#157645,#157652),.PCURVE_S1.); +#157641 = LINE('',#157642,#157643); +#157642 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); +#157643 = VECTOR('',#157644,1.); +#157644 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#157645 = PCURVE('',#153938,#157646); +#157646 = DEFINITIONAL_REPRESENTATION('',(#157647),#157651); +#157647 = LINE('',#157648,#157649); +#157648 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#157649 = VECTOR('',#157650,1.); +#157650 = DIRECTION('',(0.E+000,1.)); +#157651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157652 = PCURVE('',#157653,#157658); +#157653 = PLANE('',#157654); +#157654 = AXIS2_PLACEMENT_3D('',#157655,#157656,#157657); +#157655 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); +#157656 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157657 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157658 = DEFINITIONAL_REPRESENTATION('',(#157659),#157663); +#157659 = LINE('',#157660,#157661); +#157660 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157661 = VECTOR('',#157662,1.); +#157662 = DIRECTION('',(0.E+000,-1.)); +#157663 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157664 = ORIENTED_EDGE('',*,*,#157665,.F.); +#157665 = EDGE_CURVE('',#157339,#157638,#157666,.T.); +#157666 = SURFACE_CURVE('',#157667,(#157672,#157683),.PCURVE_S1.); +#157667 = CIRCLE('',#157668,1.6E-002); +#157668 = AXIS2_PLACEMENT_3D('',#157669,#157670,#157671); +#157669 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.825)); +#157670 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157671 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157672 = PCURVE('',#153938,#157673); +#157673 = DEFINITIONAL_REPRESENTATION('',(#157674),#157682); +#157674 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157675,#157676,#157677, + #157678,#157679,#157680,#157681),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#155283 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#155284 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#155285 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#155286 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#155287 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#155288 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#155289 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#155290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155291 = PCURVE('',#154985,#155292); -#155292 = DEFINITIONAL_REPRESENTATION('',(#155293),#155296); -#155293 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155294,#155295), +#157675 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#157676 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#157677 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#157678 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#157679 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#157680 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#157681 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#157682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157683 = PCURVE('',#157377,#157684); +#157684 = DEFINITIONAL_REPRESENTATION('',(#157685),#157688); +#157685 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157686,#157687), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#155294 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#155295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155297 = ADVANCED_FACE('',(#155298),#151490,.T.); -#155298 = FACE_BOUND('',#155299,.T.); -#155299 = EDGE_LOOP('',(#155300,#155301,#155302,#155329,#155352,#155375, - #155398,#155421,#155444,#155471,#155494,#155517)); -#155300 = ORIENTED_EDGE('',*,*,#151474,.F.); -#155301 = ORIENTED_EDGE('',*,*,#154996,.T.); -#155302 = ORIENTED_EDGE('',*,*,#155303,.T.); -#155303 = EDGE_CURVE('',#154970,#155304,#155306,.T.); -#155304 = VERTEX_POINT('',#155305); -#155305 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.475)); -#155306 = SURFACE_CURVE('',#155307,(#155312,#155323),.PCURVE_S1.); -#155307 = CIRCLE('',#155308,1.6E-002); -#155308 = AXIS2_PLACEMENT_3D('',#155309,#155310,#155311); -#155309 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); -#155310 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155311 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155312 = PCURVE('',#151490,#155313); -#155313 = DEFINITIONAL_REPRESENTATION('',(#155314),#155322); -#155314 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155315,#155316,#155317, - #155318,#155319,#155320,#155321),.UNSPECIFIED.,.F.,.F.) +#157686 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#157687 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157689 = ADVANCED_FACE('',(#157690),#153882,.T.); +#157690 = FACE_BOUND('',#157691,.T.); +#157691 = EDGE_LOOP('',(#157692,#157693,#157694,#157721,#157744,#157767, + #157790,#157813,#157836,#157863,#157886,#157909)); +#157692 = ORIENTED_EDGE('',*,*,#153866,.F.); +#157693 = ORIENTED_EDGE('',*,*,#157388,.T.); +#157694 = ORIENTED_EDGE('',*,*,#157695,.T.); +#157695 = EDGE_CURVE('',#157362,#157696,#157698,.T.); +#157696 = VERTEX_POINT('',#157697); +#157697 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.475)); +#157698 = SURFACE_CURVE('',#157699,(#157704,#157715),.PCURVE_S1.); +#157699 = CIRCLE('',#157700,1.6E-002); +#157700 = AXIS2_PLACEMENT_3D('',#157701,#157702,#157703); +#157701 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); +#157702 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157703 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157704 = PCURVE('',#153882,#157705); +#157705 = DEFINITIONAL_REPRESENTATION('',(#157706),#157714); +#157706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157707,#157708,#157709, + #157710,#157711,#157712,#157713),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#155315 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#155316 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); -#155317 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); -#155318 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); -#155319 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); -#155320 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); -#155321 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#155322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155323 = PCURVE('',#154985,#155324); -#155324 = DEFINITIONAL_REPRESENTATION('',(#155325),#155328); -#155325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155326,#155327), +#157707 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#157708 = CARTESIAN_POINT('',(1.6E-002,-2.77128129211E-002)); +#157709 = CARTESIAN_POINT('',(-8.E-003,-1.385640646055E-002)); +#157710 = CARTESIAN_POINT('',(-3.2E-002,-1.102416768983E-017)); +#157711 = CARTESIAN_POINT('',(-8.E-003,1.385640646055E-002)); +#157712 = CARTESIAN_POINT('',(1.6E-002,2.77128129211E-002)); +#157713 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#157714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157715 = PCURVE('',#157377,#157716); +#157716 = DEFINITIONAL_REPRESENTATION('',(#157717),#157720); +#157717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157718,#157719), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#155326 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#155327 = CARTESIAN_POINT('',(0.E+000,0.35)); -#155328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155329 = ORIENTED_EDGE('',*,*,#155330,.T.); -#155330 = EDGE_CURVE('',#155304,#155331,#155333,.T.); -#155331 = VERTEX_POINT('',#155332); -#155332 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.475) - ); -#155333 = SURFACE_CURVE('',#155334,(#155338,#155345),.PCURVE_S1.); -#155334 = LINE('',#155335,#155336); -#155335 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.475)); -#155336 = VECTOR('',#155337,1.); -#155337 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#155338 = PCURVE('',#151490,#155339); -#155339 = DEFINITIONAL_REPRESENTATION('',(#155340),#155344); -#155340 = LINE('',#155341,#155342); -#155341 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#155342 = VECTOR('',#155343,1.); -#155343 = DIRECTION('',(0.E+000,1.)); -#155344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155345 = PCURVE('',#155261,#155346); -#155346 = DEFINITIONAL_REPRESENTATION('',(#155347),#155351); -#155347 = LINE('',#155348,#155349); -#155348 = CARTESIAN_POINT('',(0.35,0.E+000)); -#155349 = VECTOR('',#155350,1.); -#155350 = DIRECTION('',(0.E+000,-1.)); -#155351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155352 = ORIENTED_EDGE('',*,*,#155353,.T.); -#155353 = EDGE_CURVE('',#155331,#155354,#155356,.T.); -#155354 = VERTEX_POINT('',#155355); -#155355 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.475) - ); -#155356 = SURFACE_CURVE('',#155357,(#155362,#155369),.PCURVE_S1.); -#155357 = CIRCLE('',#155358,3.199999999999E-002); -#155358 = AXIS2_PLACEMENT_3D('',#155359,#155360,#155361); -#155359 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.475) - ); -#155360 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155361 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155362 = PCURVE('',#151490,#155363); -#155363 = DEFINITIONAL_REPRESENTATION('',(#155364),#155368); -#155364 = CIRCLE('',#155365,3.199999999999E-002); -#155365 = AXIS2_PLACEMENT_2D('',#155366,#155367); -#155366 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); -#155367 = DIRECTION('',(-1.,0.E+000)); -#155368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155369 = PCURVE('',#155234,#155370); -#155370 = DEFINITIONAL_REPRESENTATION('',(#155371),#155374); -#155371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155372,#155373), +#157718 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157719 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157721 = ORIENTED_EDGE('',*,*,#157722,.T.); +#157722 = EDGE_CURVE('',#157696,#157723,#157725,.T.); +#157723 = VERTEX_POINT('',#157724); +#157724 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.475) + ); +#157725 = SURFACE_CURVE('',#157726,(#157730,#157737),.PCURVE_S1.); +#157726 = LINE('',#157727,#157728); +#157727 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.475)); +#157728 = VECTOR('',#157729,1.); +#157729 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#157730 = PCURVE('',#153882,#157731); +#157731 = DEFINITIONAL_REPRESENTATION('',(#157732),#157736); +#157732 = LINE('',#157733,#157734); +#157733 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#157734 = VECTOR('',#157735,1.); +#157735 = DIRECTION('',(0.E+000,1.)); +#157736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157737 = PCURVE('',#157653,#157738); +#157738 = DEFINITIONAL_REPRESENTATION('',(#157739),#157743); +#157739 = LINE('',#157740,#157741); +#157740 = CARTESIAN_POINT('',(0.35,0.E+000)); +#157741 = VECTOR('',#157742,1.); +#157742 = DIRECTION('',(0.E+000,-1.)); +#157743 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157744 = ORIENTED_EDGE('',*,*,#157745,.T.); +#157745 = EDGE_CURVE('',#157723,#157746,#157748,.T.); +#157746 = VERTEX_POINT('',#157747); +#157747 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.475) + ); +#157748 = SURFACE_CURVE('',#157749,(#157754,#157761),.PCURVE_S1.); +#157749 = CIRCLE('',#157750,3.199999999999E-002); +#157750 = AXIS2_PLACEMENT_3D('',#157751,#157752,#157753); +#157751 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.475) + ); +#157752 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157753 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157754 = PCURVE('',#153882,#157755); +#157755 = DEFINITIONAL_REPRESENTATION('',(#157756),#157760); +#157756 = CIRCLE('',#157757,3.199999999999E-002); +#157757 = AXIS2_PLACEMENT_2D('',#157758,#157759); +#157758 = CARTESIAN_POINT('',(-4.8E-002,0.612319204944)); +#157759 = DIRECTION('',(-1.,0.E+000)); +#157760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157761 = PCURVE('',#157626,#157762); +#157762 = DEFINITIONAL_REPRESENTATION('',(#157763),#157766); +#157763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157764,#157765), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#155372 = CARTESIAN_POINT('',(3.141592653589,0.35)); -#155373 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#155374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155375 = ORIENTED_EDGE('',*,*,#155376,.T.); -#155376 = EDGE_CURVE('',#155354,#155377,#155379,.T.); -#155377 = VERTEX_POINT('',#155378); -#155378 = CARTESIAN_POINT('',(-1.05,0.E+000,0.475)); -#155379 = SURFACE_CURVE('',#155380,(#155384,#155391),.PCURVE_S1.); -#155380 = LINE('',#155381,#155382); -#155381 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.475) - ); -#155382 = VECTOR('',#155383,1.); -#155383 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#155384 = PCURVE('',#151490,#155385); -#155385 = DEFINITIONAL_REPRESENTATION('',(#155386),#155390); -#155386 = LINE('',#155387,#155388); -#155387 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); -#155388 = VECTOR('',#155389,1.); -#155389 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); -#155390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155391 = PCURVE('',#155205,#155392); -#155392 = DEFINITIONAL_REPRESENTATION('',(#155393),#155397); -#155393 = LINE('',#155394,#155395); -#155394 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#155395 = VECTOR('',#155396,1.); -#155396 = DIRECTION('',(-1.,0.E+000)); -#155397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155398 = ORIENTED_EDGE('',*,*,#155399,.T.); -#155399 = EDGE_CURVE('',#155377,#155400,#155402,.T.); -#155400 = VERTEX_POINT('',#155401); -#155401 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.475) - ); -#155402 = SURFACE_CURVE('',#155403,(#155407,#155414),.PCURVE_S1.); -#155403 = LINE('',#155404,#155405); -#155404 = CARTESIAN_POINT('',(-1.05,0.E+000,0.475)); -#155405 = VECTOR('',#155406,1.); -#155406 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); -#155407 = PCURVE('',#151490,#155408); -#155408 = DEFINITIONAL_REPRESENTATION('',(#155409),#155413); -#155409 = LINE('',#155410,#155411); -#155410 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); -#155411 = VECTOR('',#155412,1.); -#155412 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); -#155413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155414 = PCURVE('',#155177,#155415); -#155415 = DEFINITIONAL_REPRESENTATION('',(#155416),#155420); -#155416 = LINE('',#155417,#155418); -#155417 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#155418 = VECTOR('',#155419,1.); -#155419 = DIRECTION('',(-1.,0.E+000)); -#155420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155421 = ORIENTED_EDGE('',*,*,#155422,.T.); -#155422 = EDGE_CURVE('',#155400,#155423,#155425,.T.); -#155423 = VERTEX_POINT('',#155424); -#155424 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.475) - ); -#155425 = SURFACE_CURVE('',#155426,(#155430,#155437),.PCURVE_S1.); -#155426 = LINE('',#155427,#155428); -#155427 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.475) - ); -#155428 = VECTOR('',#155429,1.); -#155429 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#155430 = PCURVE('',#151490,#155431); -#155431 = DEFINITIONAL_REPRESENTATION('',(#155432),#155436); -#155432 = LINE('',#155433,#155434); -#155433 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); -#155434 = VECTOR('',#155435,1.); -#155435 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); -#155436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155437 = PCURVE('',#155149,#155438); -#155438 = DEFINITIONAL_REPRESENTATION('',(#155439),#155443); -#155439 = LINE('',#155440,#155441); -#155440 = CARTESIAN_POINT('',(0.E+000,-0.35)); -#155441 = VECTOR('',#155442,1.); -#155442 = DIRECTION('',(-1.,0.E+000)); -#155443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155444 = ORIENTED_EDGE('',*,*,#155445,.T.); -#155445 = EDGE_CURVE('',#155423,#155446,#155448,.T.); -#155446 = VERTEX_POINT('',#155447); -#155447 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.475) - ); -#155448 = SURFACE_CURVE('',#155449,(#155454,#155465),.PCURVE_S1.); -#155449 = CIRCLE('',#155450,1.599999999999E-002); -#155450 = AXIS2_PLACEMENT_3D('',#155451,#155452,#155453); -#155451 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.475) - ); -#155452 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155453 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155454 = PCURVE('',#151490,#155455); -#155455 = DEFINITIONAL_REPRESENTATION('',(#155456),#155464); -#155456 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155457,#155458,#155459, - #155460,#155461,#155462,#155463),.UNSPECIFIED.,.T.,.F.) +#157764 = CARTESIAN_POINT('',(3.141592653589,0.35)); +#157765 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#157766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157767 = ORIENTED_EDGE('',*,*,#157768,.T.); +#157768 = EDGE_CURVE('',#157746,#157769,#157771,.T.); +#157769 = VERTEX_POINT('',#157770); +#157770 = CARTESIAN_POINT('',(-1.05,0.E+000,0.475)); +#157771 = SURFACE_CURVE('',#157772,(#157776,#157783),.PCURVE_S1.); +#157772 = LINE('',#157773,#157774); +#157773 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.475) + ); +#157774 = VECTOR('',#157775,1.); +#157775 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#157776 = PCURVE('',#153882,#157777); +#157777 = DEFINITIONAL_REPRESENTATION('',(#157778),#157782); +#157778 = LINE('',#157779,#157780); +#157779 = CARTESIAN_POINT('',(-4.576779284019E-002,0.644241254552)); +#157780 = VECTOR('',#157781,1.); +#157781 = DIRECTION('',(-0.99756405026,6.975647374417E-002)); +#157782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157783 = PCURVE('',#157597,#157784); +#157784 = DEFINITIONAL_REPRESENTATION('',(#157785),#157789); +#157785 = LINE('',#157786,#157787); +#157786 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#157787 = VECTOR('',#157788,1.); +#157788 = DIRECTION('',(-1.,0.E+000)); +#157789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157790 = ORIENTED_EDGE('',*,*,#157791,.T.); +#157791 = EDGE_CURVE('',#157769,#157792,#157794,.T.); +#157792 = VERTEX_POINT('',#157793); +#157793 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.475) + ); +#157794 = SURFACE_CURVE('',#157795,(#157799,#157806),.PCURVE_S1.); +#157795 = LINE('',#157796,#157797); +#157796 = CARTESIAN_POINT('',(-1.05,0.E+000,0.475)); +#157797 = VECTOR('',#157798,1.); +#157798 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); +#157799 = PCURVE('',#153882,#157800); +#157800 = DEFINITIONAL_REPRESENTATION('',(#157801),#157805); +#157801 = LINE('',#157802,#157803); +#157802 = CARTESIAN_POINT('',(-0.375999999998,0.66733334)); +#157803 = VECTOR('',#157804,1.); +#157804 = DIRECTION('',(-6.975647374418E-002,-0.99756405026)); +#157805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157806 = PCURVE('',#157569,#157807); +#157807 = DEFINITIONAL_REPRESENTATION('',(#157808),#157812); +#157808 = LINE('',#157809,#157810); +#157809 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#157810 = VECTOR('',#157811,1.); +#157811 = DIRECTION('',(-1.,0.E+000)); +#157812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157813 = ORIENTED_EDGE('',*,*,#157814,.T.); +#157814 = EDGE_CURVE('',#157792,#157815,#157817,.T.); +#157815 = VERTEX_POINT('',#157816); +#157816 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.475) + ); +#157817 = SURFACE_CURVE('',#157818,(#157822,#157829),.PCURVE_S1.); +#157818 = LINE('',#157819,#157820); +#157819 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,0.475) + ); +#157820 = VECTOR('',#157821,1.); +#157821 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#157822 = PCURVE('',#153882,#157823); +#157823 = DEFINITIONAL_REPRESENTATION('',(#157824),#157828); +#157824 = LINE('',#157825,#157826); +#157825 = CARTESIAN_POINT('',(-4.688389642009E-002,0.628280229748)); +#157826 = VECTOR('',#157827,1.); +#157827 = DIRECTION('',(0.99756405026,-6.975647374417E-002)); +#157828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157829 = PCURVE('',#157541,#157830); +#157830 = DEFINITIONAL_REPRESENTATION('',(#157831),#157835); +#157831 = LINE('',#157832,#157833); +#157832 = CARTESIAN_POINT('',(0.E+000,-0.35)); +#157833 = VECTOR('',#157834,1.); +#157834 = DIRECTION('',(-1.,0.E+000)); +#157835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157836 = ORIENTED_EDGE('',*,*,#157837,.T.); +#157837 = EDGE_CURVE('',#157815,#157838,#157840,.T.); +#157838 = VERTEX_POINT('',#157839); +#157839 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.475) + ); +#157840 = SURFACE_CURVE('',#157841,(#157846,#157857),.PCURVE_S1.); +#157841 = CIRCLE('',#157842,1.599999999999E-002); +#157842 = AXIS2_PLACEMENT_3D('',#157843,#157844,#157845); +#157843 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,0.475) + ); +#157844 = DIRECTION('',(0.E+000,0.E+000,1.)); +#157845 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#157846 = PCURVE('',#153882,#157847); +#157847 = DEFINITIONAL_REPRESENTATION('',(#157848),#157856); +#157848 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157849,#157850,#157851, + #157852,#157853,#157854,#157855),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#155457 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#155458 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); -#155459 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); -#155460 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); -#155461 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); -#155462 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); -#155463 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); -#155464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155465 = PCURVE('',#155122,#155466); -#155466 = DEFINITIONAL_REPRESENTATION('',(#155467),#155470); -#155467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155468,#155469), +#157849 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157850 = CARTESIAN_POINT('',(-6.399999999999E-002,0.640032017865)); +#157851 = CARTESIAN_POINT('',(-4.E-002,0.626175611405)); +#157852 = CARTESIAN_POINT('',(-1.600000000001E-002,0.612319204944)); +#157853 = CARTESIAN_POINT('',(-4.E-002,0.598462798484)); +#157854 = CARTESIAN_POINT('',(-6.399999999999E-002,0.584606392023)); +#157855 = CARTESIAN_POINT('',(-6.399999999999E-002,0.612319204944)); +#157856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157857 = PCURVE('',#157514,#157858); +#157858 = DEFINITIONAL_REPRESENTATION('',(#157859),#157862); +#157859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157860,#157861), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#155468 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#155469 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#155470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155471 = ORIENTED_EDGE('',*,*,#155472,.T.); -#155472 = EDGE_CURVE('',#155446,#155473,#155475,.T.); -#155473 = VERTEX_POINT('',#155474); -#155474 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.475)); -#155475 = SURFACE_CURVE('',#155476,(#155480,#155487),.PCURVE_S1.); -#155476 = LINE('',#155477,#155478); -#155477 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.475)); -#155478 = VECTOR('',#155479,1.); -#155479 = DIRECTION('',(0.E+000,1.,0.E+000)); -#155480 = PCURVE('',#151490,#155481); -#155481 = DEFINITIONAL_REPRESENTATION('',(#155482),#155486); -#155482 = LINE('',#155483,#155484); -#155483 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#155484 = VECTOR('',#155485,1.); -#155485 = DIRECTION('',(0.E+000,-1.)); -#155486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155487 = PCURVE('',#155089,#155488); -#155488 = DEFINITIONAL_REPRESENTATION('',(#155489),#155493); -#155489 = LINE('',#155490,#155491); -#155490 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#155491 = VECTOR('',#155492,1.); -#155492 = DIRECTION('',(0.E+000,1.)); -#155493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155494 = ORIENTED_EDGE('',*,*,#155495,.T.); -#155495 = EDGE_CURVE('',#155473,#155496,#155498,.T.); -#155496 = VERTEX_POINT('',#155497); -#155497 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.475)); -#155498 = SURFACE_CURVE('',#155499,(#155504,#155511),.PCURVE_S1.); -#155499 = CIRCLE('',#155500,3.2E-002); -#155500 = AXIS2_PLACEMENT_3D('',#155501,#155502,#155503); -#155501 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); -#155502 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155503 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155504 = PCURVE('',#151490,#155505); -#155505 = DEFINITIONAL_REPRESENTATION('',(#155506),#155510); -#155506 = CIRCLE('',#155507,3.2E-002); -#155507 = AXIS2_PLACEMENT_2D('',#155508,#155509); -#155508 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155509 = DIRECTION('',(1.,0.E+000)); -#155510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155511 = PCURVE('',#155062,#155512); -#155512 = DEFINITIONAL_REPRESENTATION('',(#155513),#155516); -#155513 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155514,#155515), +#157860 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#157861 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#157862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157863 = ORIENTED_EDGE('',*,*,#157864,.T.); +#157864 = EDGE_CURVE('',#157838,#157865,#157867,.T.); +#157865 = VERTEX_POINT('',#157866); +#157866 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.475)); +#157867 = SURFACE_CURVE('',#157868,(#157872,#157879),.PCURVE_S1.); +#157868 = LINE('',#157869,#157870); +#157869 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.475)); +#157870 = VECTOR('',#157871,1.); +#157871 = DIRECTION('',(0.E+000,1.,0.E+000)); +#157872 = PCURVE('',#153882,#157873); +#157873 = DEFINITIONAL_REPRESENTATION('',(#157874),#157878); +#157874 = LINE('',#157875,#157876); +#157875 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#157876 = VECTOR('',#157877,1.); +#157877 = DIRECTION('',(0.E+000,-1.)); +#157878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157879 = PCURVE('',#157481,#157880); +#157880 = DEFINITIONAL_REPRESENTATION('',(#157881),#157885); +#157881 = LINE('',#157882,#157883); +#157882 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#157883 = VECTOR('',#157884,1.); +#157884 = DIRECTION('',(0.E+000,1.)); +#157885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157886 = ORIENTED_EDGE('',*,*,#157887,.T.); +#157887 = EDGE_CURVE('',#157865,#157888,#157890,.T.); +#157888 = VERTEX_POINT('',#157889); +#157889 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.475)); +#157890 = SURFACE_CURVE('',#157891,(#157896,#157903),.PCURVE_S1.); +#157891 = CIRCLE('',#157892,3.2E-002); +#157892 = AXIS2_PLACEMENT_3D('',#157893,#157894,#157895); +#157893 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,0.475)); +#157894 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157895 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157896 = PCURVE('',#153882,#157897); +#157897 = DEFINITIONAL_REPRESENTATION('',(#157898),#157902); +#157898 = CIRCLE('',#157899,3.2E-002); +#157899 = AXIS2_PLACEMENT_2D('',#157900,#157901); +#157900 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157901 = DIRECTION('',(1.,0.E+000)); +#157902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157903 = PCURVE('',#157454,#157904); +#157904 = DEFINITIONAL_REPRESENTATION('',(#157905),#157908); +#157905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157906,#157907), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#155514 = CARTESIAN_POINT('',(0.E+000,0.35)); -#155515 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#155516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155517 = ORIENTED_EDGE('',*,*,#155518,.T.); -#155518 = EDGE_CURVE('',#155496,#151475,#155519,.T.); -#155519 = SURFACE_CURVE('',#155520,(#155524,#155531),.PCURVE_S1.); -#155520 = LINE('',#155521,#155522); -#155521 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.475)); -#155522 = VECTOR('',#155523,1.); -#155523 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155524 = PCURVE('',#151490,#155525); -#155525 = DEFINITIONAL_REPRESENTATION('',(#155526),#155530); -#155526 = LINE('',#155527,#155528); -#155527 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); -#155528 = VECTOR('',#155529,1.); -#155529 = DIRECTION('',(1.,0.E+000)); -#155530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155531 = PCURVE('',#151518,#155532); -#155532 = DEFINITIONAL_REPRESENTATION('',(#155533),#155537); -#155533 = LINE('',#155534,#155535); -#155534 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#155535 = VECTOR('',#155536,1.); -#155536 = DIRECTION('',(0.E+000,1.)); -#155537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155538 = ADVANCED_FACE('',(#155539),#154985,.F.); -#155539 = FACE_BOUND('',#155540,.F.); -#155540 = EDGE_LOOP('',(#155541,#155542,#155562,#155563)); -#155541 = ORIENTED_EDGE('',*,*,#155303,.T.); -#155542 = ORIENTED_EDGE('',*,*,#155543,.F.); -#155543 = EDGE_CURVE('',#155246,#155304,#155544,.T.); -#155544 = SURFACE_CURVE('',#155545,(#155549,#155555),.PCURVE_S1.); -#155545 = LINE('',#155546,#155547); -#155546 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); -#155547 = VECTOR('',#155548,1.); -#155548 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155549 = PCURVE('',#154985,#155550); -#155550 = DEFINITIONAL_REPRESENTATION('',(#155551),#155554); -#155551 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155552,#155553), +#157906 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157907 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157909 = ORIENTED_EDGE('',*,*,#157910,.T.); +#157910 = EDGE_CURVE('',#157888,#153867,#157911,.T.); +#157911 = SURFACE_CURVE('',#157912,(#157916,#157923),.PCURVE_S1.); +#157912 = LINE('',#157913,#157914); +#157913 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,0.475)); +#157914 = VECTOR('',#157915,1.); +#157915 = DIRECTION('',(1.,0.E+000,0.E+000)); +#157916 = PCURVE('',#153882,#157917); +#157917 = DEFINITIONAL_REPRESENTATION('',(#157918),#157922); +#157918 = LINE('',#157919,#157920); +#157919 = CARTESIAN_POINT('',(0.100681667766,-3.2E-002)); +#157920 = VECTOR('',#157921,1.); +#157921 = DIRECTION('',(1.,0.E+000)); +#157922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157923 = PCURVE('',#153910,#157924); +#157924 = DEFINITIONAL_REPRESENTATION('',(#157925),#157929); +#157925 = LINE('',#157926,#157927); +#157926 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#157927 = VECTOR('',#157928,1.); +#157928 = DIRECTION('',(0.E+000,1.)); +#157929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157930 = ADVANCED_FACE('',(#157931),#157377,.F.); +#157931 = FACE_BOUND('',#157932,.F.); +#157932 = EDGE_LOOP('',(#157933,#157934,#157954,#157955)); +#157933 = ORIENTED_EDGE('',*,*,#157695,.T.); +#157934 = ORIENTED_EDGE('',*,*,#157935,.F.); +#157935 = EDGE_CURVE('',#157638,#157696,#157936,.T.); +#157936 = SURFACE_CURVE('',#157937,(#157941,#157947),.PCURVE_S1.); +#157937 = LINE('',#157938,#157939); +#157938 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,0.825)); +#157939 = VECTOR('',#157940,1.); +#157940 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157941 = PCURVE('',#157377,#157942); +#157942 = DEFINITIONAL_REPRESENTATION('',(#157943),#157946); +#157943 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157944,#157945), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155552 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155553 = CARTESIAN_POINT('',(0.E+000,0.35)); -#155554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155555 = PCURVE('',#155261,#155556); -#155556 = DEFINITIONAL_REPRESENTATION('',(#155557),#155561); -#155557 = LINE('',#155558,#155559); -#155558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155559 = VECTOR('',#155560,1.); -#155560 = DIRECTION('',(1.,0.E+000)); -#155561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155562 = ORIENTED_EDGE('',*,*,#155273,.F.); -#155563 = ORIENTED_EDGE('',*,*,#154969,.T.); -#155564 = ADVANCED_FACE('',(#155565),#151518,.T.); -#155565 = FACE_BOUND('',#155566,.T.); -#155566 = EDGE_LOOP('',(#155567,#155568,#155588,#155589)); -#155567 = ORIENTED_EDGE('',*,*,#155518,.F.); -#155568 = ORIENTED_EDGE('',*,*,#155569,.F.); -#155569 = EDGE_CURVE('',#155023,#155496,#155570,.T.); -#155570 = SURFACE_CURVE('',#155571,(#155575,#155582),.PCURVE_S1.); -#155571 = LINE('',#155572,#155573); -#155572 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.825)); -#155573 = VECTOR('',#155574,1.); -#155574 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155575 = PCURVE('',#151518,#155576); -#155576 = DEFINITIONAL_REPRESENTATION('',(#155577),#155581); -#155577 = LINE('',#155578,#155579); -#155578 = CARTESIAN_POINT('',(0.E+000,-0.100681667766)); -#155579 = VECTOR('',#155580,1.); -#155580 = DIRECTION('',(-1.,0.E+000)); -#155581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155582 = PCURVE('',#155062,#155583); -#155583 = DEFINITIONAL_REPRESENTATION('',(#155584),#155587); -#155584 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155585,#155586), +#157944 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157945 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157947 = PCURVE('',#157653,#157948); +#157948 = DEFINITIONAL_REPRESENTATION('',(#157949),#157953); +#157949 = LINE('',#157950,#157951); +#157950 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157951 = VECTOR('',#157952,1.); +#157952 = DIRECTION('',(1.,0.E+000)); +#157953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157954 = ORIENTED_EDGE('',*,*,#157665,.F.); +#157955 = ORIENTED_EDGE('',*,*,#157361,.T.); +#157956 = ADVANCED_FACE('',(#157957),#153910,.T.); +#157957 = FACE_BOUND('',#157958,.T.); +#157958 = EDGE_LOOP('',(#157959,#157960,#157980,#157981)); +#157959 = ORIENTED_EDGE('',*,*,#157910,.F.); +#157960 = ORIENTED_EDGE('',*,*,#157961,.F.); +#157961 = EDGE_CURVE('',#157415,#157888,#157962,.T.); +#157962 = SURFACE_CURVE('',#157963,(#157967,#157974),.PCURVE_S1.); +#157963 = LINE('',#157964,#157965); +#157964 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,0.825)); +#157965 = VECTOR('',#157966,1.); +#157966 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157967 = PCURVE('',#153910,#157968); +#157968 = DEFINITIONAL_REPRESENTATION('',(#157969),#157973); +#157969 = LINE('',#157970,#157971); +#157970 = CARTESIAN_POINT('',(0.E+000,-0.100681667766)); +#157971 = VECTOR('',#157972,1.); +#157972 = DIRECTION('',(-1.,0.E+000)); +#157973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157974 = PCURVE('',#157454,#157975); +#157975 = DEFINITIONAL_REPRESENTATION('',(#157976),#157979); +#157976 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157977,#157978), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155585 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#155586 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#155587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#157977 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#157978 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#157979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155588 = ORIENTED_EDGE('',*,*,#155022,.T.); -#155589 = ORIENTED_EDGE('',*,*,#151502,.T.); -#155590 = ADVANCED_FACE('',(#155591),#155062,.T.); -#155591 = FACE_BOUND('',#155592,.T.); -#155592 = EDGE_LOOP('',(#155593,#155594,#155614,#155615)); -#155593 = ORIENTED_EDGE('',*,*,#155495,.F.); -#155594 = ORIENTED_EDGE('',*,*,#155595,.F.); -#155595 = EDGE_CURVE('',#155046,#155473,#155596,.T.); -#155596 = SURFACE_CURVE('',#155597,(#155601,#155607),.PCURVE_S1.); -#155597 = LINE('',#155598,#155599); -#155598 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); -#155599 = VECTOR('',#155600,1.); -#155600 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155601 = PCURVE('',#155062,#155602); -#155602 = DEFINITIONAL_REPRESENTATION('',(#155603),#155606); -#155603 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155604,#155605), +#157980 = ORIENTED_EDGE('',*,*,#157414,.T.); +#157981 = ORIENTED_EDGE('',*,*,#153894,.T.); +#157982 = ADVANCED_FACE('',(#157983),#157454,.T.); +#157983 = FACE_BOUND('',#157984,.T.); +#157984 = EDGE_LOOP('',(#157985,#157986,#158006,#158007)); +#157985 = ORIENTED_EDGE('',*,*,#157887,.F.); +#157986 = ORIENTED_EDGE('',*,*,#157987,.F.); +#157987 = EDGE_CURVE('',#157438,#157865,#157988,.T.); +#157988 = SURFACE_CURVE('',#157989,(#157993,#157999),.PCURVE_S1.); +#157989 = LINE('',#157990,#157991); +#157990 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,0.825)); +#157991 = VECTOR('',#157992,1.); +#157992 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#157993 = PCURVE('',#157454,#157994); +#157994 = DEFINITIONAL_REPRESENTATION('',(#157995),#157998); +#157995 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157996,#157997), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155604 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155605 = CARTESIAN_POINT('',(0.E+000,0.35)); -#155606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155607 = PCURVE('',#155089,#155608); -#155608 = DEFINITIONAL_REPRESENTATION('',(#155609),#155613); -#155609 = LINE('',#155610,#155611); -#155610 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155611 = VECTOR('',#155612,1.); -#155612 = DIRECTION('',(-1.,0.E+000)); -#155613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155614 = ORIENTED_EDGE('',*,*,#155045,.T.); -#155615 = ORIENTED_EDGE('',*,*,#155569,.T.); -#155616 = ADVANCED_FACE('',(#155617),#155089,.T.); -#155617 = FACE_BOUND('',#155618,.T.); -#155618 = EDGE_LOOP('',(#155619,#155620,#155640,#155641)); -#155619 = ORIENTED_EDGE('',*,*,#155472,.F.); -#155620 = ORIENTED_EDGE('',*,*,#155621,.F.); -#155621 = EDGE_CURVE('',#155074,#155446,#155622,.T.); -#155622 = SURFACE_CURVE('',#155623,(#155627,#155634),.PCURVE_S1.); -#155623 = LINE('',#155624,#155625); -#155624 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.825) - ); -#155625 = VECTOR('',#155626,1.); -#155626 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155627 = PCURVE('',#155089,#155628); -#155628 = DEFINITIONAL_REPRESENTATION('',(#155629),#155633); -#155629 = LINE('',#155630,#155631); -#155630 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#155631 = VECTOR('',#155632,1.); -#155632 = DIRECTION('',(-1.,0.E+000)); -#155633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155634 = PCURVE('',#155122,#155635); -#155635 = DEFINITIONAL_REPRESENTATION('',(#155636),#155639); -#155636 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155637,#155638), +#157996 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#157997 = CARTESIAN_POINT('',(0.E+000,0.35)); +#157998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#157999 = PCURVE('',#157481,#158000); +#158000 = DEFINITIONAL_REPRESENTATION('',(#158001),#158005); +#158001 = LINE('',#158002,#158003); +#158002 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158003 = VECTOR('',#158004,1.); +#158004 = DIRECTION('',(-1.,0.E+000)); +#158005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158006 = ORIENTED_EDGE('',*,*,#157437,.T.); +#158007 = ORIENTED_EDGE('',*,*,#157961,.T.); +#158008 = ADVANCED_FACE('',(#158009),#157481,.T.); +#158009 = FACE_BOUND('',#158010,.T.); +#158010 = EDGE_LOOP('',(#158011,#158012,#158032,#158033)); +#158011 = ORIENTED_EDGE('',*,*,#157864,.F.); +#158012 = ORIENTED_EDGE('',*,*,#158013,.F.); +#158013 = EDGE_CURVE('',#157466,#157838,#158014,.T.); +#158014 = SURFACE_CURVE('',#158015,(#158019,#158026),.PCURVE_S1.); +#158015 = LINE('',#158016,#158017); +#158016 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,0.825) + ); +#158017 = VECTOR('',#158018,1.); +#158018 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158019 = PCURVE('',#157481,#158020); +#158020 = DEFINITIONAL_REPRESENTATION('',(#158021),#158025); +#158021 = LINE('',#158022,#158023); +#158022 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#158023 = VECTOR('',#158024,1.); +#158024 = DIRECTION('',(-1.,0.E+000)); +#158025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158026 = PCURVE('',#157514,#158027); +#158027 = DEFINITIONAL_REPRESENTATION('',(#158028),#158031); +#158028 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158029,#158030), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155637 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#155638 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#155639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155640 = ORIENTED_EDGE('',*,*,#155073,.T.); -#155641 = ORIENTED_EDGE('',*,*,#155595,.T.); -#155642 = ADVANCED_FACE('',(#155643),#155122,.F.); -#155643 = FACE_BOUND('',#155644,.F.); -#155644 = EDGE_LOOP('',(#155645,#155646,#155647,#155648)); -#155645 = ORIENTED_EDGE('',*,*,#155445,.T.); -#155646 = ORIENTED_EDGE('',*,*,#155621,.F.); -#155647 = ORIENTED_EDGE('',*,*,#155101,.F.); -#155648 = ORIENTED_EDGE('',*,*,#155649,.T.); -#155649 = EDGE_CURVE('',#155102,#155423,#155650,.T.); -#155650 = SURFACE_CURVE('',#155651,(#155655,#155661),.PCURVE_S1.); -#155651 = LINE('',#155652,#155653); -#155652 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.825) +#158029 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#158030 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#158031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158032 = ORIENTED_EDGE('',*,*,#157465,.T.); +#158033 = ORIENTED_EDGE('',*,*,#157987,.T.); +#158034 = ADVANCED_FACE('',(#158035),#157514,.F.); +#158035 = FACE_BOUND('',#158036,.F.); +#158036 = EDGE_LOOP('',(#158037,#158038,#158039,#158040)); +#158037 = ORIENTED_EDGE('',*,*,#157837,.T.); +#158038 = ORIENTED_EDGE('',*,*,#158013,.F.); +#158039 = ORIENTED_EDGE('',*,*,#157493,.F.); +#158040 = ORIENTED_EDGE('',*,*,#158041,.T.); +#158041 = EDGE_CURVE('',#157494,#157815,#158042,.T.); +#158042 = SURFACE_CURVE('',#158043,(#158047,#158053),.PCURVE_S1.); +#158043 = LINE('',#158044,#158045); +#158044 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,0.825) ); -#155653 = VECTOR('',#155654,1.); -#155654 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155655 = PCURVE('',#155122,#155656); -#155656 = DEFINITIONAL_REPRESENTATION('',(#155657),#155660); -#155657 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155658,#155659), +#158045 = VECTOR('',#158046,1.); +#158046 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158047 = PCURVE('',#157514,#158048); +#158048 = DEFINITIONAL_REPRESENTATION('',(#158049),#158052); +#158049 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158050,#158051), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155658 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#155659 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#155660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155661 = PCURVE('',#155149,#155662); -#155662 = DEFINITIONAL_REPRESENTATION('',(#155663),#155667); -#155663 = LINE('',#155664,#155665); -#155664 = CARTESIAN_POINT('',(-1.112358904841E-016,0.E+000)); -#155665 = VECTOR('',#155666,1.); -#155666 = DIRECTION('',(0.E+000,-1.)); -#155667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155668 = ADVANCED_FACE('',(#155669),#155149,.T.); -#155669 = FACE_BOUND('',#155670,.T.); -#155670 = EDGE_LOOP('',(#155671,#155672,#155693,#155694)); -#155671 = ORIENTED_EDGE('',*,*,#155422,.F.); -#155672 = ORIENTED_EDGE('',*,*,#155673,.F.); -#155673 = EDGE_CURVE('',#155134,#155400,#155674,.T.); -#155674 = SURFACE_CURVE('',#155675,(#155679,#155686),.PCURVE_S1.); -#155675 = LINE('',#155676,#155677); -#155676 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.825) - ); -#155677 = VECTOR('',#155678,1.); -#155678 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155679 = PCURVE('',#155149,#155680); -#155680 = DEFINITIONAL_REPRESENTATION('',(#155681),#155685); -#155681 = LINE('',#155682,#155683); -#155682 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); -#155683 = VECTOR('',#155684,1.); -#155684 = DIRECTION('',(0.E+000,-1.)); -#155685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155686 = PCURVE('',#155177,#155687); -#155687 = DEFINITIONAL_REPRESENTATION('',(#155688),#155692); -#155688 = LINE('',#155689,#155690); -#155689 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#155690 = VECTOR('',#155691,1.); -#155691 = DIRECTION('',(0.E+000,-1.)); -#155692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155693 = ORIENTED_EDGE('',*,*,#155133,.T.); -#155694 = ORIENTED_EDGE('',*,*,#155649,.T.); -#155695 = ADVANCED_FACE('',(#155696),#155177,.T.); -#155696 = FACE_BOUND('',#155697,.T.); -#155697 = EDGE_LOOP('',(#155698,#155699,#155720,#155721)); -#155698 = ORIENTED_EDGE('',*,*,#155399,.F.); -#155699 = ORIENTED_EDGE('',*,*,#155700,.F.); -#155700 = EDGE_CURVE('',#155162,#155377,#155701,.T.); -#155701 = SURFACE_CURVE('',#155702,(#155706,#155713),.PCURVE_S1.); -#155702 = LINE('',#155703,#155704); -#155703 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); -#155704 = VECTOR('',#155705,1.); -#155705 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155706 = PCURVE('',#155177,#155707); -#155707 = DEFINITIONAL_REPRESENTATION('',(#155708),#155712); -#155708 = LINE('',#155709,#155710); -#155709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155710 = VECTOR('',#155711,1.); -#155711 = DIRECTION('',(0.E+000,-1.)); -#155712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155713 = PCURVE('',#155205,#155714); -#155714 = DEFINITIONAL_REPRESENTATION('',(#155715),#155719); -#155715 = LINE('',#155716,#155717); -#155716 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); -#155717 = VECTOR('',#155718,1.); -#155718 = DIRECTION('',(0.E+000,-1.)); -#155719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155720 = ORIENTED_EDGE('',*,*,#155161,.T.); -#155721 = ORIENTED_EDGE('',*,*,#155673,.T.); -#155722 = ADVANCED_FACE('',(#155723),#155205,.T.); -#155723 = FACE_BOUND('',#155724,.T.); -#155724 = EDGE_LOOP('',(#155725,#155726,#155746,#155747)); -#155725 = ORIENTED_EDGE('',*,*,#155376,.F.); -#155726 = ORIENTED_EDGE('',*,*,#155727,.F.); -#155727 = EDGE_CURVE('',#155190,#155354,#155728,.T.); -#155728 = SURFACE_CURVE('',#155729,(#155733,#155740),.PCURVE_S1.); -#155729 = LINE('',#155730,#155731); -#155730 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) - ); -#155731 = VECTOR('',#155732,1.); -#155732 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155733 = PCURVE('',#155205,#155734); -#155734 = DEFINITIONAL_REPRESENTATION('',(#155735),#155739); -#155735 = LINE('',#155736,#155737); -#155736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155737 = VECTOR('',#155738,1.); -#155738 = DIRECTION('',(0.E+000,-1.)); -#155739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155740 = PCURVE('',#155234,#155741); -#155741 = DEFINITIONAL_REPRESENTATION('',(#155742),#155745); -#155742 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155743,#155744), +#158050 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#158051 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#158052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158053 = PCURVE('',#157541,#158054); +#158054 = DEFINITIONAL_REPRESENTATION('',(#158055),#158059); +#158055 = LINE('',#158056,#158057); +#158056 = CARTESIAN_POINT('',(-1.112358904841E-016,0.E+000)); +#158057 = VECTOR('',#158058,1.); +#158058 = DIRECTION('',(0.E+000,-1.)); +#158059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158060 = ADVANCED_FACE('',(#158061),#157541,.T.); +#158061 = FACE_BOUND('',#158062,.T.); +#158062 = EDGE_LOOP('',(#158063,#158064,#158085,#158086)); +#158063 = ORIENTED_EDGE('',*,*,#157814,.F.); +#158064 = ORIENTED_EDGE('',*,*,#158065,.F.); +#158065 = EDGE_CURVE('',#157526,#157792,#158066,.T.); +#158066 = SURFACE_CURVE('',#158067,(#158071,#158078),.PCURVE_S1.); +#158067 = LINE('',#158068,#158069); +#158068 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,0.825) + ); +#158069 = VECTOR('',#158070,1.); +#158070 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158071 = PCURVE('',#157541,#158072); +#158072 = DEFINITIONAL_REPRESENTATION('',(#158073),#158077); +#158073 = LINE('',#158074,#158075); +#158074 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); +#158075 = VECTOR('',#158076,1.); +#158076 = DIRECTION('',(0.E+000,-1.)); +#158077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158078 = PCURVE('',#157569,#158079); +#158079 = DEFINITIONAL_REPRESENTATION('',(#158080),#158084); +#158080 = LINE('',#158081,#158082); +#158081 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#158082 = VECTOR('',#158083,1.); +#158083 = DIRECTION('',(0.E+000,-1.)); +#158084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158085 = ORIENTED_EDGE('',*,*,#157525,.T.); +#158086 = ORIENTED_EDGE('',*,*,#158041,.T.); +#158087 = ADVANCED_FACE('',(#158088),#157569,.T.); +#158088 = FACE_BOUND('',#158089,.T.); +#158089 = EDGE_LOOP('',(#158090,#158091,#158112,#158113)); +#158090 = ORIENTED_EDGE('',*,*,#157791,.F.); +#158091 = ORIENTED_EDGE('',*,*,#158092,.F.); +#158092 = EDGE_CURVE('',#157554,#157769,#158093,.T.); +#158093 = SURFACE_CURVE('',#158094,(#158098,#158105),.PCURVE_S1.); +#158094 = LINE('',#158095,#158096); +#158095 = CARTESIAN_POINT('',(-1.05,0.E+000,0.825)); +#158096 = VECTOR('',#158097,1.); +#158097 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158098 = PCURVE('',#157569,#158099); +#158099 = DEFINITIONAL_REPRESENTATION('',(#158100),#158104); +#158100 = LINE('',#158101,#158102); +#158101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158102 = VECTOR('',#158103,1.); +#158103 = DIRECTION('',(0.E+000,-1.)); +#158104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158105 = PCURVE('',#157597,#158106); +#158106 = DEFINITIONAL_REPRESENTATION('',(#158107),#158111); +#158107 = LINE('',#158108,#158109); +#158108 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); +#158109 = VECTOR('',#158110,1.); +#158110 = DIRECTION('',(0.E+000,-1.)); +#158111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158112 = ORIENTED_EDGE('',*,*,#157553,.T.); +#158113 = ORIENTED_EDGE('',*,*,#158065,.T.); +#158114 = ADVANCED_FACE('',(#158115),#157597,.T.); +#158115 = FACE_BOUND('',#158116,.T.); +#158116 = EDGE_LOOP('',(#158117,#158118,#158138,#158139)); +#158117 = ORIENTED_EDGE('',*,*,#157768,.F.); +#158118 = ORIENTED_EDGE('',*,*,#158119,.F.); +#158119 = EDGE_CURVE('',#157582,#157746,#158120,.T.); +#158120 = SURFACE_CURVE('',#158121,(#158125,#158132),.PCURVE_S1.); +#158121 = LINE('',#158122,#158123); +#158122 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,0.825) + ); +#158123 = VECTOR('',#158124,1.); +#158124 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158125 = PCURVE('',#157597,#158126); +#158126 = DEFINITIONAL_REPRESENTATION('',(#158127),#158131); +#158127 = LINE('',#158128,#158129); +#158128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158129 = VECTOR('',#158130,1.); +#158130 = DIRECTION('',(0.E+000,-1.)); +#158131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158132 = PCURVE('',#157626,#158133); +#158133 = DEFINITIONAL_REPRESENTATION('',(#158134),#158137); +#158134 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158135,#158136), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); +#158135 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); +#158136 = CARTESIAN_POINT('',(4.642575810305,0.35)); +#158137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158138 = ORIENTED_EDGE('',*,*,#157581,.T.); +#158139 = ORIENTED_EDGE('',*,*,#158092,.T.); +#158140 = ADVANCED_FACE('',(#158141),#157626,.T.); +#158141 = FACE_BOUND('',#158142,.T.); +#158142 = EDGE_LOOP('',(#158143,#158144,#158164,#158165)); +#158143 = ORIENTED_EDGE('',*,*,#157745,.F.); +#158144 = ORIENTED_EDGE('',*,*,#158145,.F.); +#158145 = EDGE_CURVE('',#157610,#157723,#158146,.T.); +#158146 = SURFACE_CURVE('',#158147,(#158151,#158157),.PCURVE_S1.); +#158147 = LINE('',#158148,#158149); +#158148 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.825) + ); +#158149 = VECTOR('',#158150,1.); +#158150 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158151 = PCURVE('',#157626,#158152); +#158152 = DEFINITIONAL_REPRESENTATION('',(#158153),#158156); +#158153 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158154,#158155), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155743 = CARTESIAN_POINT('',(4.642575810305,0.E+000)); -#155744 = CARTESIAN_POINT('',(4.642575810305,0.35)); -#155745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155746 = ORIENTED_EDGE('',*,*,#155189,.T.); -#155747 = ORIENTED_EDGE('',*,*,#155700,.T.); -#155748 = ADVANCED_FACE('',(#155749),#155234,.T.); -#155749 = FACE_BOUND('',#155750,.T.); -#155750 = EDGE_LOOP('',(#155751,#155752,#155772,#155773)); -#155751 = ORIENTED_EDGE('',*,*,#155353,.F.); -#155752 = ORIENTED_EDGE('',*,*,#155753,.F.); -#155753 = EDGE_CURVE('',#155218,#155331,#155754,.T.); -#155754 = SURFACE_CURVE('',#155755,(#155759,#155765),.PCURVE_S1.); -#155755 = LINE('',#155756,#155757); -#155756 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,0.825) - ); -#155757 = VECTOR('',#155758,1.); -#155758 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155759 = PCURVE('',#155234,#155760); -#155760 = DEFINITIONAL_REPRESENTATION('',(#155761),#155764); -#155761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155762,#155763), +#158154 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); +#158155 = CARTESIAN_POINT('',(3.141592653589,0.35)); +#158156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158157 = PCURVE('',#157653,#158158); +#158158 = DEFINITIONAL_REPRESENTATION('',(#158159),#158163); +#158159 = LINE('',#158160,#158161); +#158160 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#158161 = VECTOR('',#158162,1.); +#158162 = DIRECTION('',(1.,0.E+000)); +#158163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158164 = ORIENTED_EDGE('',*,*,#157609,.T.); +#158165 = ORIENTED_EDGE('',*,*,#158119,.T.); +#158166 = ADVANCED_FACE('',(#158167),#157653,.T.); +#158167 = FACE_BOUND('',#158168,.T.); +#158168 = EDGE_LOOP('',(#158169,#158170,#158171,#158172)); +#158169 = ORIENTED_EDGE('',*,*,#157722,.F.); +#158170 = ORIENTED_EDGE('',*,*,#157935,.F.); +#158171 = ORIENTED_EDGE('',*,*,#157637,.T.); +#158172 = ORIENTED_EDGE('',*,*,#158145,.T.); +#158173 = ADVANCED_FACE('',(#158174),#154541,.F.); +#158174 = FACE_BOUND('',#158175,.T.); +#158175 = EDGE_LOOP('',(#158176,#158199,#158200,#158223)); +#158176 = ORIENTED_EDGE('',*,*,#158177,.F.); +#158177 = EDGE_CURVE('',#153643,#158178,#158180,.T.); +#158178 = VERTEX_POINT('',#158179); +#158179 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.825)); +#158180 = SURFACE_CURVE('',#158181,(#158185,#158192),.PCURVE_S1.); +#158181 = LINE('',#158182,#158183); +#158182 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.825)); +#158183 = VECTOR('',#158184,1.); +#158184 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); +#158185 = PCURVE('',#154541,#158186); +#158186 = DEFINITIONAL_REPRESENTATION('',(#158187),#158191); +#158187 = LINE('',#158188,#158189); +#158188 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158189 = VECTOR('',#158190,1.); +#158190 = DIRECTION('',(1.,0.E+000)); +#158191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158192 = PCURVE('',#153663,#158193); +#158193 = DEFINITIONAL_REPRESENTATION('',(#158194),#158198); +#158194 = LINE('',#158195,#158196); +#158195 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); +#158196 = VECTOR('',#158197,1.); +#158197 = DIRECTION('',(-1.,-1.07686155438E-015)); +#158198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158199 = ORIENTED_EDGE('',*,*,#154527,.F.); +#158200 = ORIENTED_EDGE('',*,*,#158201,.T.); +#158201 = EDGE_CURVE('',#153704,#158202,#158204,.T.); +#158202 = VERTEX_POINT('',#158203); +#158203 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.475)); +#158204 = SURFACE_CURVE('',#158205,(#158209,#158216),.PCURVE_S1.); +#158205 = LINE('',#158206,#158207); +#158206 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.475)); +#158207 = VECTOR('',#158208,1.); +#158208 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); +#158209 = PCURVE('',#154541,#158210); +#158210 = DEFINITIONAL_REPRESENTATION('',(#158211),#158215); +#158211 = LINE('',#158212,#158213); +#158212 = CARTESIAN_POINT('',(0.E+000,0.35)); +#158213 = VECTOR('',#158214,1.); +#158214 = DIRECTION('',(1.,0.E+000)); +#158215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158216 = PCURVE('',#153719,#158217); +#158217 = DEFINITIONAL_REPRESENTATION('',(#158218),#158222); +#158218 = LINE('',#158219,#158220); +#158219 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); +#158220 = VECTOR('',#158221,1.); +#158221 = DIRECTION('',(-1.,-1.07686155438E-015)); +#158222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158223 = ORIENTED_EDGE('',*,*,#158224,.F.); +#158224 = EDGE_CURVE('',#158178,#158202,#158225,.T.); +#158225 = SURFACE_CURVE('',#158226,(#158230,#158237),.PCURVE_S1.); +#158226 = LINE('',#158227,#158228); +#158227 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.825)); +#158228 = VECTOR('',#158229,1.); +#158229 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158230 = PCURVE('',#154541,#158231); +#158231 = DEFINITIONAL_REPRESENTATION('',(#158232),#158236); +#158232 = LINE('',#158233,#158234); +#158233 = CARTESIAN_POINT('',(0.100681667766,0.E+000)); +#158234 = VECTOR('',#158235,1.); +#158235 = DIRECTION('',(0.E+000,1.)); +#158236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158237 = PCURVE('',#158238,#158243); +#158238 = CYLINDRICAL_SURFACE('',#158239,1.6E-002); +#158239 = AXIS2_PLACEMENT_3D('',#158240,#158241,#158242); +#158240 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); +#158241 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158242 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158243 = DEFINITIONAL_REPRESENTATION('',(#158244),#158247); +#158244 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158245,#158246), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155762 = CARTESIAN_POINT('',(3.141592653589,0.E+000)); -#155763 = CARTESIAN_POINT('',(3.141592653589,0.35)); -#155764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158245 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#158246 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#158247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158248 = ADVANCED_FACE('',(#158249),#153663,.F.); +#158249 = FACE_BOUND('',#158250,.T.); +#158250 = EDGE_LOOP('',(#158251,#158274,#158275,#158276,#158299,#158327, + #158359,#158387,#158415,#158443,#158471,#158499)); +#158251 = ORIENTED_EDGE('',*,*,#158252,.T.); +#158252 = EDGE_CURVE('',#158253,#153641,#158255,.T.); +#158253 = VERTEX_POINT('',#158254); +#158254 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.825)); +#158255 = SURFACE_CURVE('',#158256,(#158260,#158267),.PCURVE_S1.); +#158256 = LINE('',#158257,#158258); +#158257 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); +#158258 = VECTOR('',#158259,1.); +#158259 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158260 = PCURVE('',#153663,#158261); +#158261 = DEFINITIONAL_REPRESENTATION('',(#158262),#158266); +#158262 = LINE('',#158263,#158264); +#158263 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); +#158264 = VECTOR('',#158265,1.); +#158265 = DIRECTION('',(1.,0.E+000)); +#158266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155765 = PCURVE('',#155261,#155766); -#155766 = DEFINITIONAL_REPRESENTATION('',(#155767),#155771); -#155767 = LINE('',#155768,#155769); -#155768 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#155769 = VECTOR('',#155770,1.); -#155770 = DIRECTION('',(1.,0.E+000)); -#155771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158267 = PCURVE('',#153691,#158268); +#158268 = DEFINITIONAL_REPRESENTATION('',(#158269),#158273); +#158269 = LINE('',#158270,#158271); +#158270 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158271 = VECTOR('',#158272,1.); +#158272 = DIRECTION('',(0.E+000,1.)); +#158273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155772 = ORIENTED_EDGE('',*,*,#155217,.T.); -#155773 = ORIENTED_EDGE('',*,*,#155727,.T.); -#155774 = ADVANCED_FACE('',(#155775),#155261,.T.); -#155775 = FACE_BOUND('',#155776,.T.); -#155776 = EDGE_LOOP('',(#155777,#155778,#155779,#155780)); -#155777 = ORIENTED_EDGE('',*,*,#155330,.F.); -#155778 = ORIENTED_EDGE('',*,*,#155543,.F.); -#155779 = ORIENTED_EDGE('',*,*,#155245,.T.); -#155780 = ORIENTED_EDGE('',*,*,#155753,.T.); -#155781 = ADVANCED_FACE('',(#155782),#152149,.F.); -#155782 = FACE_BOUND('',#155783,.T.); -#155783 = EDGE_LOOP('',(#155784,#155807,#155808,#155831)); -#155784 = ORIENTED_EDGE('',*,*,#155785,.F.); -#155785 = EDGE_CURVE('',#151251,#155786,#155788,.T.); -#155786 = VERTEX_POINT('',#155787); -#155787 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.825)); -#155788 = SURFACE_CURVE('',#155789,(#155793,#155800),.PCURVE_S1.); -#155789 = LINE('',#155790,#155791); -#155790 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.825)); -#155791 = VECTOR('',#155792,1.); -#155792 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); -#155793 = PCURVE('',#152149,#155794); -#155794 = DEFINITIONAL_REPRESENTATION('',(#155795),#155799); -#155795 = LINE('',#155796,#155797); -#155796 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155797 = VECTOR('',#155798,1.); -#155798 = DIRECTION('',(1.,0.E+000)); -#155799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155800 = PCURVE('',#151271,#155801); -#155801 = DEFINITIONAL_REPRESENTATION('',(#155802),#155806); -#155802 = LINE('',#155803,#155804); -#155803 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); -#155804 = VECTOR('',#155805,1.); -#155805 = DIRECTION('',(-1.,-1.07686155438E-015)); -#155806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155807 = ORIENTED_EDGE('',*,*,#152135,.F.); -#155808 = ORIENTED_EDGE('',*,*,#155809,.T.); -#155809 = EDGE_CURVE('',#151312,#155810,#155812,.T.); -#155810 = VERTEX_POINT('',#155811); -#155811 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.475)); -#155812 = SURFACE_CURVE('',#155813,(#155817,#155824),.PCURVE_S1.); -#155813 = LINE('',#155814,#155815); -#155814 = CARTESIAN_POINT('',(-0.573318332236,0.68333334,-0.475)); -#155815 = VECTOR('',#155816,1.); -#155816 = DIRECTION('',(-1.,-1.07686155438E-015,0.E+000)); -#155817 = PCURVE('',#152149,#155818); -#155818 = DEFINITIONAL_REPRESENTATION('',(#155819),#155823); -#155819 = LINE('',#155820,#155821); -#155820 = CARTESIAN_POINT('',(0.E+000,0.35)); -#155821 = VECTOR('',#155822,1.); -#155822 = DIRECTION('',(1.,0.E+000)); -#155823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155824 = PCURVE('',#151327,#155825); -#155825 = DEFINITIONAL_REPRESENTATION('',(#155826),#155830); -#155826 = LINE('',#155827,#155828); -#155827 = CARTESIAN_POINT('',(0.100681667766,1.6E-002)); -#155828 = VECTOR('',#155829,1.); -#155829 = DIRECTION('',(-1.,-1.07686155438E-015)); -#155830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155831 = ORIENTED_EDGE('',*,*,#155832,.F.); -#155832 = EDGE_CURVE('',#155786,#155810,#155833,.T.); -#155833 = SURFACE_CURVE('',#155834,(#155838,#155845),.PCURVE_S1.); -#155834 = LINE('',#155835,#155836); -#155835 = CARTESIAN_POINT('',(-0.674000000002,0.68333334,-0.825)); -#155836 = VECTOR('',#155837,1.); -#155837 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155838 = PCURVE('',#152149,#155839); -#155839 = DEFINITIONAL_REPRESENTATION('',(#155840),#155844); -#155840 = LINE('',#155841,#155842); -#155841 = CARTESIAN_POINT('',(0.100681667766,0.E+000)); -#155842 = VECTOR('',#155843,1.); -#155843 = DIRECTION('',(0.E+000,1.)); -#155844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155845 = PCURVE('',#155846,#155851); -#155846 = CYLINDRICAL_SURFACE('',#155847,1.6E-002); -#155847 = AXIS2_PLACEMENT_3D('',#155848,#155849,#155850); -#155848 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); -#155849 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155850 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155851 = DEFINITIONAL_REPRESENTATION('',(#155852),#155855); -#155852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155853,#155854), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#155853 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#155854 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#155855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155856 = ADVANCED_FACE('',(#155857),#151271,.F.); -#155857 = FACE_BOUND('',#155858,.T.); -#155858 = EDGE_LOOP('',(#155859,#155882,#155883,#155884,#155907,#155935, - #155967,#155995,#156023,#156051,#156079,#156107)); -#155859 = ORIENTED_EDGE('',*,*,#155860,.T.); -#155860 = EDGE_CURVE('',#155861,#151249,#155863,.T.); -#155861 = VERTEX_POINT('',#155862); -#155862 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.825)); -#155863 = SURFACE_CURVE('',#155864,(#155868,#155875),.PCURVE_S1.); -#155864 = LINE('',#155865,#155866); -#155865 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.825)); -#155866 = VECTOR('',#155867,1.); -#155867 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155868 = PCURVE('',#151271,#155869); -#155869 = DEFINITIONAL_REPRESENTATION('',(#155870),#155874); -#155870 = LINE('',#155871,#155872); -#155871 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); -#155872 = VECTOR('',#155873,1.); -#155873 = DIRECTION('',(1.,0.E+000)); -#155874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155875 = PCURVE('',#151299,#155876); -#155876 = DEFINITIONAL_REPRESENTATION('',(#155877),#155881); -#155877 = LINE('',#155878,#155879); -#155878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155879 = VECTOR('',#155880,1.); -#155880 = DIRECTION('',(0.E+000,1.)); -#155881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155882 = ORIENTED_EDGE('',*,*,#151248,.T.); -#155883 = ORIENTED_EDGE('',*,*,#155785,.T.); -#155884 = ORIENTED_EDGE('',*,*,#155885,.T.); -#155885 = EDGE_CURVE('',#155786,#155886,#155888,.T.); -#155886 = VERTEX_POINT('',#155887); -#155887 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); -#155888 = SURFACE_CURVE('',#155889,(#155894,#155901),.PCURVE_S1.); -#155889 = CIRCLE('',#155890,1.6E-002); -#155890 = AXIS2_PLACEMENT_3D('',#155891,#155892,#155893); -#155891 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); -#155892 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155893 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155894 = PCURVE('',#151271,#155895); -#155895 = DEFINITIONAL_REPRESENTATION('',(#155896),#155900); -#155896 = CIRCLE('',#155897,1.6E-002); -#155897 = AXIS2_PLACEMENT_2D('',#155898,#155899); -#155898 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155899 = DIRECTION('',(1.,0.E+000)); -#155900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155901 = PCURVE('',#155846,#155902); -#155902 = DEFINITIONAL_REPRESENTATION('',(#155903),#155906); -#155903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155904,#155905), +#158274 = ORIENTED_EDGE('',*,*,#153640,.T.); +#158275 = ORIENTED_EDGE('',*,*,#158177,.T.); +#158276 = ORIENTED_EDGE('',*,*,#158277,.T.); +#158277 = EDGE_CURVE('',#158178,#158278,#158280,.T.); +#158278 = VERTEX_POINT('',#158279); +#158279 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); +#158280 = SURFACE_CURVE('',#158281,(#158286,#158293),.PCURVE_S1.); +#158281 = CIRCLE('',#158282,1.6E-002); +#158282 = AXIS2_PLACEMENT_3D('',#158283,#158284,#158285); +#158283 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); +#158284 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158285 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158286 = PCURVE('',#153663,#158287); +#158287 = DEFINITIONAL_REPRESENTATION('',(#158288),#158292); +#158288 = CIRCLE('',#158289,1.6E-002); +#158289 = AXIS2_PLACEMENT_2D('',#158290,#158291); +#158290 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158291 = DIRECTION('',(1.,0.E+000)); +#158292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158293 = PCURVE('',#158238,#158294); +#158294 = DEFINITIONAL_REPRESENTATION('',(#158295),#158298); +#158295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158296,#158297), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#155904 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#155905 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#155906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158296 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#158297 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#158298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155907 = ORIENTED_EDGE('',*,*,#155908,.T.); -#155908 = EDGE_CURVE('',#155886,#155909,#155911,.T.); -#155909 = VERTEX_POINT('',#155910); -#155910 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.825 +#158299 = ORIENTED_EDGE('',*,*,#158300,.T.); +#158300 = EDGE_CURVE('',#158278,#158301,#158303,.T.); +#158301 = VERTEX_POINT('',#158302); +#158302 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.825 )); -#155911 = SURFACE_CURVE('',#155912,(#155916,#155923),.PCURVE_S1.); -#155912 = LINE('',#155913,#155914); -#155913 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); -#155914 = VECTOR('',#155915,1.); -#155915 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#155916 = PCURVE('',#151271,#155917); -#155917 = DEFINITIONAL_REPRESENTATION('',(#155918),#155922); -#155918 = LINE('',#155919,#155920); -#155919 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#155920 = VECTOR('',#155921,1.); -#155921 = DIRECTION('',(0.E+000,-1.)); -#155922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155923 = PCURVE('',#155924,#155929); -#155924 = PLANE('',#155925); -#155925 = AXIS2_PLACEMENT_3D('',#155926,#155927,#155928); -#155926 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); -#155927 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155928 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155929 = DEFINITIONAL_REPRESENTATION('',(#155930),#155934); -#155930 = LINE('',#155931,#155932); -#155931 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155932 = VECTOR('',#155933,1.); -#155933 = DIRECTION('',(0.E+000,-1.)); -#155934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155935 = ORIENTED_EDGE('',*,*,#155936,.T.); -#155936 = EDGE_CURVE('',#155909,#155937,#155939,.T.); -#155937 = VERTEX_POINT('',#155938); -#155938 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 +#158303 = SURFACE_CURVE('',#158304,(#158308,#158315),.PCURVE_S1.); +#158304 = LINE('',#158305,#158306); +#158305 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); +#158306 = VECTOR('',#158307,1.); +#158307 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#158308 = PCURVE('',#153663,#158309); +#158309 = DEFINITIONAL_REPRESENTATION('',(#158310),#158314); +#158310 = LINE('',#158311,#158312); +#158311 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#158312 = VECTOR('',#158313,1.); +#158313 = DIRECTION('',(0.E+000,-1.)); +#158314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158315 = PCURVE('',#158316,#158321); +#158316 = PLANE('',#158317); +#158317 = AXIS2_PLACEMENT_3D('',#158318,#158319,#158320); +#158318 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); +#158319 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#158320 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158321 = DEFINITIONAL_REPRESENTATION('',(#158322),#158326); +#158322 = LINE('',#158323,#158324); +#158323 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158324 = VECTOR('',#158325,1.); +#158325 = DIRECTION('',(0.E+000,-1.)); +#158326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158327 = ORIENTED_EDGE('',*,*,#158328,.T.); +#158328 = EDGE_CURVE('',#158301,#158329,#158331,.T.); +#158329 = VERTEX_POINT('',#158330); +#158330 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 )); -#155939 = SURFACE_CURVE('',#155940,(#155945,#155956),.PCURVE_S1.); -#155940 = CIRCLE('',#155941,3.199999999999E-002); -#155941 = AXIS2_PLACEMENT_3D('',#155942,#155943,#155944); -#155942 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 +#158331 = SURFACE_CURVE('',#158332,(#158337,#158348),.PCURVE_S1.); +#158332 = CIRCLE('',#158333,3.199999999999E-002); +#158333 = AXIS2_PLACEMENT_3D('',#158334,#158335,#158336); +#158334 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 )); -#155943 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#155944 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#155945 = PCURVE('',#151271,#155946); -#155946 = DEFINITIONAL_REPRESENTATION('',(#155947),#155955); -#155947 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#155948,#155949,#155950, - #155951,#155952,#155953,#155954),.UNSPECIFIED.,.T.,.F.) +#158335 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158336 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#158337 = PCURVE('',#153663,#158338); +#158338 = DEFINITIONAL_REPRESENTATION('',(#158339),#158347); +#158339 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158340,#158341,#158342, + #158343,#158344,#158345,#158346),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#155948 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#155949 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); -#155950 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); -#155951 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); -#155952 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); -#155953 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); -#155954 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#155955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158340 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#158341 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); +#158342 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); +#158343 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); +#158344 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); +#158345 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); +#158346 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#158347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155956 = PCURVE('',#155957,#155962); -#155957 = CYLINDRICAL_SURFACE('',#155958,3.199999999999E-002); -#155958 = AXIS2_PLACEMENT_3D('',#155959,#155960,#155961); -#155959 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 +#158348 = PCURVE('',#158349,#158354); +#158349 = CYLINDRICAL_SURFACE('',#158350,3.199999999999E-002); +#158350 = AXIS2_PLACEMENT_3D('',#158351,#158352,#158353); +#158351 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 )); -#155960 = DIRECTION('',(0.E+000,0.E+000,1.)); -#155961 = DIRECTION('',(1.,0.E+000,0.E+000)); -#155962 = DEFINITIONAL_REPRESENTATION('',(#155963),#155966); -#155963 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#155964,#155965), +#158352 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158353 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158354 = DEFINITIONAL_REPRESENTATION('',(#158355),#158358); +#158355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158356,#158357), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#155964 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#155965 = CARTESIAN_POINT('',(4.782202150464,0.E+000)); -#155966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158356 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#158357 = CARTESIAN_POINT('',(4.782202150464,0.E+000)); +#158358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#155967 = ORIENTED_EDGE('',*,*,#155968,.T.); -#155968 = EDGE_CURVE('',#155937,#155969,#155971,.T.); -#155969 = VERTEX_POINT('',#155970); -#155970 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); -#155971 = SURFACE_CURVE('',#155972,(#155976,#155983),.PCURVE_S1.); -#155972 = LINE('',#155973,#155974); -#155973 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 +#158359 = ORIENTED_EDGE('',*,*,#158360,.T.); +#158360 = EDGE_CURVE('',#158329,#158361,#158363,.T.); +#158361 = VERTEX_POINT('',#158362); +#158362 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); +#158363 = SURFACE_CURVE('',#158364,(#158368,#158375),.PCURVE_S1.); +#158364 = LINE('',#158365,#158366); +#158365 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 )); -#155974 = VECTOR('',#155975,1.); -#155975 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#155976 = PCURVE('',#151271,#155977); -#155977 = DEFINITIONAL_REPRESENTATION('',(#155978),#155982); -#155978 = LINE('',#155979,#155980); -#155979 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#155980 = VECTOR('',#155981,1.); -#155981 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); -#155982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155983 = PCURVE('',#155984,#155989); -#155984 = PLANE('',#155985); -#155985 = AXIS2_PLACEMENT_3D('',#155986,#155987,#155988); -#155986 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 +#158366 = VECTOR('',#158367,1.); +#158367 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#158368 = PCURVE('',#153663,#158369); +#158369 = DEFINITIONAL_REPRESENTATION('',(#158370),#158374); +#158370 = LINE('',#158371,#158372); +#158371 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#158372 = VECTOR('',#158373,1.); +#158373 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); +#158374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158375 = PCURVE('',#158376,#158381); +#158376 = PLANE('',#158377); +#158377 = AXIS2_PLACEMENT_3D('',#158378,#158379,#158380); +#158378 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 )); -#155987 = DIRECTION('',(-6.975647374417E-002,0.99756405026,0.E+000)); -#155988 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#155989 = DEFINITIONAL_REPRESENTATION('',(#155990),#155994); -#155990 = LINE('',#155991,#155992); -#155991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#155992 = VECTOR('',#155993,1.); -#155993 = DIRECTION('',(1.,0.E+000)); -#155994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#155995 = ORIENTED_EDGE('',*,*,#155996,.T.); -#155996 = EDGE_CURVE('',#155969,#155997,#155999,.T.); -#155997 = VERTEX_POINT('',#155998); -#155998 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.825) - ); -#155999 = SURFACE_CURVE('',#156000,(#156004,#156011),.PCURVE_S1.); -#156000 = LINE('',#156001,#156002); -#156001 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); -#156002 = VECTOR('',#156003,1.); -#156003 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); -#156004 = PCURVE('',#151271,#156005); -#156005 = DEFINITIONAL_REPRESENTATION('',(#156006),#156010); -#156006 = LINE('',#156007,#156008); -#156007 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); -#156008 = VECTOR('',#156009,1.); -#156009 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); -#156010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156011 = PCURVE('',#156012,#156017); -#156012 = PLANE('',#156013); -#156013 = AXIS2_PLACEMENT_3D('',#156014,#156015,#156016); -#156014 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); -#156015 = DIRECTION('',(0.99756405026,6.975647374418E-002,0.E+000)); -#156016 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); -#156017 = DEFINITIONAL_REPRESENTATION('',(#156018),#156022); -#156018 = LINE('',#156019,#156020); -#156019 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156020 = VECTOR('',#156021,1.); -#156021 = DIRECTION('',(1.,0.E+000)); -#156022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156023 = ORIENTED_EDGE('',*,*,#156024,.T.); -#156024 = EDGE_CURVE('',#155997,#156025,#156027,.T.); -#156025 = VERTEX_POINT('',#156026); -#156026 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.825 +#158379 = DIRECTION('',(-6.975647374417E-002,0.99756405026,0.E+000)); +#158380 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#158381 = DEFINITIONAL_REPRESENTATION('',(#158382),#158386); +#158382 = LINE('',#158383,#158384); +#158383 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158384 = VECTOR('',#158385,1.); +#158385 = DIRECTION('',(1.,0.E+000)); +#158386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158387 = ORIENTED_EDGE('',*,*,#158388,.T.); +#158388 = EDGE_CURVE('',#158361,#158389,#158391,.T.); +#158389 = VERTEX_POINT('',#158390); +#158390 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.825) + ); +#158391 = SURFACE_CURVE('',#158392,(#158396,#158403),.PCURVE_S1.); +#158392 = LINE('',#158393,#158394); +#158393 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); +#158394 = VECTOR('',#158395,1.); +#158395 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); +#158396 = PCURVE('',#153663,#158397); +#158397 = DEFINITIONAL_REPRESENTATION('',(#158398),#158402); +#158398 = LINE('',#158399,#158400); +#158399 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); +#158400 = VECTOR('',#158401,1.); +#158401 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); +#158402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158403 = PCURVE('',#158404,#158409); +#158404 = PLANE('',#158405); +#158405 = AXIS2_PLACEMENT_3D('',#158406,#158407,#158408); +#158406 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); +#158407 = DIRECTION('',(0.99756405026,6.975647374418E-002,0.E+000)); +#158408 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); +#158409 = DEFINITIONAL_REPRESENTATION('',(#158410),#158414); +#158410 = LINE('',#158411,#158412); +#158411 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158412 = VECTOR('',#158413,1.); +#158413 = DIRECTION('',(1.,0.E+000)); +#158414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158415 = ORIENTED_EDGE('',*,*,#158416,.T.); +#158416 = EDGE_CURVE('',#158389,#158417,#158419,.T.); +#158417 = VERTEX_POINT('',#158418); +#158418 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.825 )); -#156027 = SURFACE_CURVE('',#156028,(#156032,#156039),.PCURVE_S1.); -#156028 = LINE('',#156029,#156030); -#156029 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.825 +#158419 = SURFACE_CURVE('',#158420,(#158424,#158431),.PCURVE_S1.); +#158420 = LINE('',#158421,#158422); +#158421 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.825 )); -#156030 = VECTOR('',#156031,1.); -#156031 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#156032 = PCURVE('',#151271,#156033); -#156033 = DEFINITIONAL_REPRESENTATION('',(#156034),#156038); -#156034 = LINE('',#156035,#156036); -#156035 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#156036 = VECTOR('',#156037,1.); -#156037 = DIRECTION('',(0.99756405026,6.975647374417E-002)); -#156038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156039 = PCURVE('',#156040,#156045); -#156040 = PLANE('',#156041); -#156041 = AXIS2_PLACEMENT_3D('',#156042,#156043,#156044); -#156042 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.825 +#158422 = VECTOR('',#158423,1.); +#158423 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#158424 = PCURVE('',#153663,#158425); +#158425 = DEFINITIONAL_REPRESENTATION('',(#158426),#158430); +#158426 = LINE('',#158427,#158428); +#158427 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#158428 = VECTOR('',#158429,1.); +#158429 = DIRECTION('',(0.99756405026,6.975647374417E-002)); +#158430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158431 = PCURVE('',#158432,#158437); +#158432 = PLANE('',#158433); +#158433 = AXIS2_PLACEMENT_3D('',#158434,#158435,#158436); +#158434 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.825 )); -#156043 = DIRECTION('',(6.975647374417E-002,-0.99756405026,0.E+000)); -#156044 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#156045 = DEFINITIONAL_REPRESENTATION('',(#156046),#156050); -#156046 = LINE('',#156047,#156048); -#156047 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156048 = VECTOR('',#156049,1.); -#156049 = DIRECTION('',(1.,0.E+000)); -#156050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156051 = ORIENTED_EDGE('',*,*,#156052,.T.); -#156052 = EDGE_CURVE('',#156025,#156053,#156055,.T.); -#156053 = VERTEX_POINT('',#156054); -#156054 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.825 +#158435 = DIRECTION('',(6.975647374417E-002,-0.99756405026,0.E+000)); +#158436 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#158437 = DEFINITIONAL_REPRESENTATION('',(#158438),#158442); +#158438 = LINE('',#158439,#158440); +#158439 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158440 = VECTOR('',#158441,1.); +#158441 = DIRECTION('',(1.,0.E+000)); +#158442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158443 = ORIENTED_EDGE('',*,*,#158444,.T.); +#158444 = EDGE_CURVE('',#158417,#158445,#158447,.T.); +#158445 = VERTEX_POINT('',#158446); +#158446 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.825 )); -#156055 = SURFACE_CURVE('',#156056,(#156061,#156068),.PCURVE_S1.); -#156056 = CIRCLE('',#156057,1.599999999999E-002); -#156057 = AXIS2_PLACEMENT_3D('',#156058,#156059,#156060); -#156058 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 +#158447 = SURFACE_CURVE('',#158448,(#158453,#158460),.PCURVE_S1.); +#158448 = CIRCLE('',#158449,1.599999999999E-002); +#158449 = AXIS2_PLACEMENT_3D('',#158450,#158451,#158452); +#158450 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 )); -#156059 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156060 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#156061 = PCURVE('',#151271,#156062); -#156062 = DEFINITIONAL_REPRESENTATION('',(#156063),#156067); -#156063 = CIRCLE('',#156064,1.599999999999E-002); -#156064 = AXIS2_PLACEMENT_2D('',#156065,#156066); -#156065 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#156066 = DIRECTION('',(-1.,0.E+000)); -#156067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156068 = PCURVE('',#156069,#156074); -#156069 = CYLINDRICAL_SURFACE('',#156070,1.599999999999E-002); -#156070 = AXIS2_PLACEMENT_3D('',#156071,#156072,#156073); -#156071 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 +#158451 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158452 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#158453 = PCURVE('',#153663,#158454); +#158454 = DEFINITIONAL_REPRESENTATION('',(#158455),#158459); +#158455 = CIRCLE('',#158456,1.599999999999E-002); +#158456 = AXIS2_PLACEMENT_2D('',#158457,#158458); +#158457 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#158458 = DIRECTION('',(-1.,0.E+000)); +#158459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158460 = PCURVE('',#158461,#158466); +#158461 = CYLINDRICAL_SURFACE('',#158462,1.599999999999E-002); +#158462 = AXIS2_PLACEMENT_3D('',#158463,#158464,#158465); +#158463 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.825 )); -#156072 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156073 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156074 = DEFINITIONAL_REPRESENTATION('',(#156075),#156078); -#156075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156076,#156077), +#158464 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158465 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158466 = DEFINITIONAL_REPRESENTATION('',(#158467),#158470); +#158467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158468,#158469), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#156076 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#156077 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#156078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156079 = ORIENTED_EDGE('',*,*,#156080,.T.); -#156080 = EDGE_CURVE('',#156053,#156081,#156083,.T.); -#156081 = VERTEX_POINT('',#156082); -#156082 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); -#156083 = SURFACE_CURVE('',#156084,(#156088,#156095),.PCURVE_S1.); -#156084 = LINE('',#156085,#156086); -#156085 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); -#156086 = VECTOR('',#156087,1.); -#156087 = DIRECTION('',(0.E+000,1.,0.E+000)); -#156088 = PCURVE('',#151271,#156089); -#156089 = DEFINITIONAL_REPRESENTATION('',(#156090),#156094); -#156090 = LINE('',#156091,#156092); -#156091 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#156092 = VECTOR('',#156093,1.); -#156093 = DIRECTION('',(0.E+000,1.)); -#156094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156095 = PCURVE('',#156096,#156101); -#156096 = PLANE('',#156097); -#156097 = AXIS2_PLACEMENT_3D('',#156098,#156099,#156100); -#156098 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); -#156099 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156100 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#156101 = DEFINITIONAL_REPRESENTATION('',(#156102),#156106); -#156102 = LINE('',#156103,#156104); -#156103 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156104 = VECTOR('',#156105,1.); -#156105 = DIRECTION('',(0.E+000,1.)); -#156106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156107 = ORIENTED_EDGE('',*,*,#156108,.T.); -#156108 = EDGE_CURVE('',#156081,#155861,#156109,.T.); -#156109 = SURFACE_CURVE('',#156110,(#156115,#156126),.PCURVE_S1.); -#156110 = CIRCLE('',#156111,3.2E-002); -#156111 = AXIS2_PLACEMENT_3D('',#156112,#156113,#156114); -#156112 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); -#156113 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#156114 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156115 = PCURVE('',#151271,#156116); -#156116 = DEFINITIONAL_REPRESENTATION('',(#156117),#156125); -#156117 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156118,#156119,#156120, - #156121,#156122,#156123,#156124),.UNSPECIFIED.,.F.,.F.) +#158468 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#158469 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#158470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158471 = ORIENTED_EDGE('',*,*,#158472,.T.); +#158472 = EDGE_CURVE('',#158445,#158473,#158475,.T.); +#158473 = VERTEX_POINT('',#158474); +#158474 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); +#158475 = SURFACE_CURVE('',#158476,(#158480,#158487),.PCURVE_S1.); +#158476 = LINE('',#158477,#158478); +#158477 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); +#158478 = VECTOR('',#158479,1.); +#158479 = DIRECTION('',(0.E+000,1.,0.E+000)); +#158480 = PCURVE('',#153663,#158481); +#158481 = DEFINITIONAL_REPRESENTATION('',(#158482),#158486); +#158482 = LINE('',#158483,#158484); +#158483 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#158484 = VECTOR('',#158485,1.); +#158485 = DIRECTION('',(0.E+000,1.)); +#158486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158487 = PCURVE('',#158488,#158493); +#158488 = PLANE('',#158489); +#158489 = AXIS2_PLACEMENT_3D('',#158490,#158491,#158492); +#158490 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); +#158491 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158492 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158493 = DEFINITIONAL_REPRESENTATION('',(#158494),#158498); +#158494 = LINE('',#158495,#158496); +#158495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158496 = VECTOR('',#158497,1.); +#158497 = DIRECTION('',(0.E+000,1.)); +#158498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158499 = ORIENTED_EDGE('',*,*,#158500,.T.); +#158500 = EDGE_CURVE('',#158473,#158253,#158501,.T.); +#158501 = SURFACE_CURVE('',#158502,(#158507,#158518),.PCURVE_S1.); +#158502 = CIRCLE('',#158503,3.2E-002); +#158503 = AXIS2_PLACEMENT_3D('',#158504,#158505,#158506); +#158504 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); +#158505 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158506 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158507 = PCURVE('',#153663,#158508); +#158508 = DEFINITIONAL_REPRESENTATION('',(#158509),#158517); +#158509 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158510,#158511,#158512, + #158513,#158514,#158515,#158516),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#156118 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#156119 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); -#156120 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); -#156121 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); -#156122 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); -#156123 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); -#156124 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#156125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156126 = PCURVE('',#156127,#156132); -#156127 = CYLINDRICAL_SURFACE('',#156128,3.2E-002); -#156128 = AXIS2_PLACEMENT_3D('',#156129,#156130,#156131); -#156129 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); -#156130 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156131 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156132 = DEFINITIONAL_REPRESENTATION('',(#156133),#156136); -#156133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156134,#156135), +#158510 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#158511 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); +#158512 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); +#158513 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); +#158514 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); +#158515 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); +#158516 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#158517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158518 = PCURVE('',#158519,#158524); +#158519 = CYLINDRICAL_SURFACE('',#158520,3.2E-002); +#158520 = AXIS2_PLACEMENT_3D('',#158521,#158522,#158523); +#158521 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.825)); +#158522 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158523 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158524 = DEFINITIONAL_REPRESENTATION('',(#158525),#158528); +#158525 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158526,#158527), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#156134 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#156135 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#156136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156137 = ADVANCED_FACE('',(#156138),#151327,.T.); -#156138 = FACE_BOUND('',#156139,.T.); -#156139 = EDGE_LOOP('',(#156140,#156141,#156164,#156191,#156214,#156237, - #156260,#156283,#156306,#156333,#156356,#156377)); -#156140 = ORIENTED_EDGE('',*,*,#151311,.F.); -#156141 = ORIENTED_EDGE('',*,*,#156142,.F.); -#156142 = EDGE_CURVE('',#156143,#151284,#156145,.T.); -#156143 = VERTEX_POINT('',#156144); -#156144 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.475)); -#156145 = SURFACE_CURVE('',#156146,(#156150,#156157),.PCURVE_S1.); -#156146 = LINE('',#156147,#156148); -#156147 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.475)); -#156148 = VECTOR('',#156149,1.); -#156149 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156150 = PCURVE('',#151327,#156151); -#156151 = DEFINITIONAL_REPRESENTATION('',(#156152),#156156); -#156152 = LINE('',#156153,#156154); -#156153 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); -#156154 = VECTOR('',#156155,1.); -#156155 = DIRECTION('',(1.,0.E+000)); -#156156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156157 = PCURVE('',#151299,#156158); -#156158 = DEFINITIONAL_REPRESENTATION('',(#156159),#156163); -#156159 = LINE('',#156160,#156161); -#156160 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#156161 = VECTOR('',#156162,1.); -#156162 = DIRECTION('',(0.E+000,1.)); -#156163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156164 = ORIENTED_EDGE('',*,*,#156165,.F.); -#156165 = EDGE_CURVE('',#156166,#156143,#156168,.T.); -#156166 = VERTEX_POINT('',#156167); -#156167 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.475)); -#156168 = SURFACE_CURVE('',#156169,(#156174,#156185),.PCURVE_S1.); -#156169 = CIRCLE('',#156170,3.2E-002); -#156170 = AXIS2_PLACEMENT_3D('',#156171,#156172,#156173); -#156171 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); -#156172 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#156173 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156174 = PCURVE('',#151327,#156175); -#156175 = DEFINITIONAL_REPRESENTATION('',(#156176),#156184); -#156176 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156177,#156178,#156179, - #156180,#156181,#156182,#156183),.UNSPECIFIED.,.F.,.F.) +#158526 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#158527 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#158528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158529 = ADVANCED_FACE('',(#158530),#153719,.T.); +#158530 = FACE_BOUND('',#158531,.T.); +#158531 = EDGE_LOOP('',(#158532,#158533,#158556,#158583,#158606,#158629, + #158652,#158675,#158698,#158725,#158748,#158769)); +#158532 = ORIENTED_EDGE('',*,*,#153703,.F.); +#158533 = ORIENTED_EDGE('',*,*,#158534,.F.); +#158534 = EDGE_CURVE('',#158535,#153676,#158537,.T.); +#158535 = VERTEX_POINT('',#158536); +#158536 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.475)); +#158537 = SURFACE_CURVE('',#158538,(#158542,#158549),.PCURVE_S1.); +#158538 = LINE('',#158539,#158540); +#158539 = CARTESIAN_POINT('',(-0.573318332236,0.69933334,-0.475)); +#158540 = VECTOR('',#158541,1.); +#158541 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158542 = PCURVE('',#153719,#158543); +#158543 = DEFINITIONAL_REPRESENTATION('',(#158544),#158548); +#158544 = LINE('',#158545,#158546); +#158545 = CARTESIAN_POINT('',(0.100681667766,3.2E-002)); +#158546 = VECTOR('',#158547,1.); +#158547 = DIRECTION('',(1.,0.E+000)); +#158548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158549 = PCURVE('',#153691,#158550); +#158550 = DEFINITIONAL_REPRESENTATION('',(#158551),#158555); +#158551 = LINE('',#158552,#158553); +#158552 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#158553 = VECTOR('',#158554,1.); +#158554 = DIRECTION('',(0.E+000,1.)); +#158555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158556 = ORIENTED_EDGE('',*,*,#158557,.F.); +#158557 = EDGE_CURVE('',#158558,#158535,#158560,.T.); +#158558 = VERTEX_POINT('',#158559); +#158559 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.475)); +#158560 = SURFACE_CURVE('',#158561,(#158566,#158577),.PCURVE_S1.); +#158561 = CIRCLE('',#158562,3.2E-002); +#158562 = AXIS2_PLACEMENT_3D('',#158563,#158564,#158565); +#158563 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); +#158564 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158565 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158566 = PCURVE('',#153719,#158567); +#158567 = DEFINITIONAL_REPRESENTATION('',(#158568),#158576); +#158568 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158569,#158570,#158571, + #158572,#158573,#158574,#158575),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#156177 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#156178 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); -#156179 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); -#156180 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); -#156181 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); -#156182 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); -#156183 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); -#156184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156185 = PCURVE('',#156127,#156186); -#156186 = DEFINITIONAL_REPRESENTATION('',(#156187),#156190); -#156187 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156188,#156189), +#158569 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#158570 = CARTESIAN_POINT('',(3.2E-002,-5.54256258422E-002)); +#158571 = CARTESIAN_POINT('',(-1.6E-002,-2.77128129211E-002)); +#158572 = CARTESIAN_POINT('',(-6.4E-002,-2.204833537967E-017)); +#158573 = CARTESIAN_POINT('',(-1.6E-002,2.77128129211E-002)); +#158574 = CARTESIAN_POINT('',(3.2E-002,5.54256258422E-002)); +#158575 = CARTESIAN_POINT('',(3.2E-002,0.E+000)); +#158576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158577 = PCURVE('',#158519,#158578); +#158578 = DEFINITIONAL_REPRESENTATION('',(#158579),#158582); +#158579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158580,#158581), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#156188 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#156189 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#156190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158580 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#158581 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#158582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#156191 = ORIENTED_EDGE('',*,*,#156192,.F.); -#156192 = EDGE_CURVE('',#156193,#156166,#156195,.T.); -#156193 = VERTEX_POINT('',#156194); -#156194 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.475 +#158583 = ORIENTED_EDGE('',*,*,#158584,.F.); +#158584 = EDGE_CURVE('',#158585,#158558,#158587,.T.); +#158585 = VERTEX_POINT('',#158586); +#158586 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.475 )); -#156195 = SURFACE_CURVE('',#156196,(#156200,#156207),.PCURVE_S1.); -#156196 = LINE('',#156197,#156198); -#156197 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.475)); -#156198 = VECTOR('',#156199,1.); -#156199 = DIRECTION('',(0.E+000,1.,0.E+000)); -#156200 = PCURVE('',#151327,#156201); -#156201 = DEFINITIONAL_REPRESENTATION('',(#156202),#156206); -#156202 = LINE('',#156203,#156204); -#156203 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); -#156204 = VECTOR('',#156205,1.); -#156205 = DIRECTION('',(0.E+000,1.)); -#156206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156207 = PCURVE('',#156096,#156208); -#156208 = DEFINITIONAL_REPRESENTATION('',(#156209),#156213); -#156209 = LINE('',#156210,#156211); -#156210 = CARTESIAN_POINT('',(-0.35,0.E+000)); -#156211 = VECTOR('',#156212,1.); -#156212 = DIRECTION('',(0.E+000,1.)); -#156213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156214 = ORIENTED_EDGE('',*,*,#156215,.F.); -#156215 = EDGE_CURVE('',#156216,#156193,#156218,.T.); -#156216 = VERTEX_POINT('',#156217); -#156217 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.475 +#158587 = SURFACE_CURVE('',#158588,(#158592,#158599),.PCURVE_S1.); +#158588 = LINE('',#158589,#158590); +#158589 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.475)); +#158590 = VECTOR('',#158591,1.); +#158591 = DIRECTION('',(0.E+000,1.,0.E+000)); +#158592 = PCURVE('',#153719,#158593); +#158593 = DEFINITIONAL_REPRESENTATION('',(#158594),#158598); +#158594 = LINE('',#158595,#158596); +#158595 = CARTESIAN_POINT('',(-3.2E-002,0.E+000)); +#158596 = VECTOR('',#158597,1.); +#158597 = DIRECTION('',(0.E+000,1.)); +#158598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158599 = PCURVE('',#158488,#158600); +#158600 = DEFINITIONAL_REPRESENTATION('',(#158601),#158605); +#158601 = LINE('',#158602,#158603); +#158602 = CARTESIAN_POINT('',(-0.35,0.E+000)); +#158603 = VECTOR('',#158604,1.); +#158604 = DIRECTION('',(0.E+000,1.)); +#158605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158606 = ORIENTED_EDGE('',*,*,#158607,.F.); +#158607 = EDGE_CURVE('',#158608,#158585,#158610,.T.); +#158608 = VERTEX_POINT('',#158609); +#158609 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.475 )); -#156218 = SURFACE_CURVE('',#156219,(#156224,#156231),.PCURVE_S1.); -#156219 = CIRCLE('',#156220,1.599999999999E-002); -#156220 = AXIS2_PLACEMENT_3D('',#156221,#156222,#156223); -#156221 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.475 +#158610 = SURFACE_CURVE('',#158611,(#158616,#158623),.PCURVE_S1.); +#158611 = CIRCLE('',#158612,1.599999999999E-002); +#158612 = AXIS2_PLACEMENT_3D('',#158613,#158614,#158615); +#158613 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.475 )); -#156222 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156223 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#156224 = PCURVE('',#151327,#156225); -#156225 = DEFINITIONAL_REPRESENTATION('',(#156226),#156230); -#156226 = CIRCLE('',#156227,1.599999999999E-002); -#156227 = AXIS2_PLACEMENT_2D('',#156228,#156229); -#156228 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); -#156229 = DIRECTION('',(-1.,0.E+000)); -#156230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156231 = PCURVE('',#156069,#156232); -#156232 = DEFINITIONAL_REPRESENTATION('',(#156233),#156236); -#156233 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156234,#156235), +#158614 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158615 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#158616 = PCURVE('',#153719,#158617); +#158617 = DEFINITIONAL_REPRESENTATION('',(#158618),#158622); +#158618 = CIRCLE('',#158619,1.599999999999E-002); +#158619 = AXIS2_PLACEMENT_2D('',#158620,#158621); +#158620 = CARTESIAN_POINT('',(-4.8E-002,-0.612319204944)); +#158621 = DIRECTION('',(-1.,0.E+000)); +#158622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158623 = PCURVE('',#158461,#158624); +#158624 = DEFINITIONAL_REPRESENTATION('',(#158625),#158628); +#158625 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158626,#158627), .UNSPECIFIED.,.F.,.F.,(2,2),(1.640609496875,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#156234 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#156235 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#156236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#158626 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#158627 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#158628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#156237 = ORIENTED_EDGE('',*,*,#156238,.F.); -#156238 = EDGE_CURVE('',#156239,#156216,#156241,.T.); -#156239 = VERTEX_POINT('',#156240); -#156240 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.475) +#158629 = ORIENTED_EDGE('',*,*,#158630,.F.); +#158630 = EDGE_CURVE('',#158631,#158608,#158633,.T.); +#158631 = VERTEX_POINT('',#158632); +#158632 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.475) ); -#156241 = SURFACE_CURVE('',#156242,(#156246,#156253),.PCURVE_S1.); -#156242 = LINE('',#156243,#156244); -#156243 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.475 +#158633 = SURFACE_CURVE('',#158634,(#158638,#158645),.PCURVE_S1.); +#158634 = LINE('',#158635,#158636); +#158635 = CARTESIAN_POINT('',(-0.720883896422,3.905311025178E-002,-0.475 )); -#156244 = VECTOR('',#156245,1.); -#156245 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); -#156246 = PCURVE('',#151327,#156247); -#156247 = DEFINITIONAL_REPRESENTATION('',(#156248),#156252); -#156248 = LINE('',#156249,#156250); -#156249 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); -#156250 = VECTOR('',#156251,1.); -#156251 = DIRECTION('',(0.99756405026,6.975647374417E-002)); -#156252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156253 = PCURVE('',#156040,#156254); -#156254 = DEFINITIONAL_REPRESENTATION('',(#156255),#156259); -#156255 = LINE('',#156256,#156257); -#156256 = CARTESIAN_POINT('',(0.E+000,0.35)); -#156257 = VECTOR('',#156258,1.); -#156258 = DIRECTION('',(1.,0.E+000)); -#156259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156260 = ORIENTED_EDGE('',*,*,#156261,.F.); -#156261 = EDGE_CURVE('',#156262,#156239,#156264,.T.); -#156262 = VERTEX_POINT('',#156263); -#156263 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.475)); -#156264 = SURFACE_CURVE('',#156265,(#156269,#156276),.PCURVE_S1.); -#156265 = LINE('',#156266,#156267); -#156266 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.475)); -#156267 = VECTOR('',#156268,1.); -#156268 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); -#156269 = PCURVE('',#151327,#156270); -#156270 = DEFINITIONAL_REPRESENTATION('',(#156271),#156275); -#156271 = LINE('',#156272,#156273); -#156272 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); -#156273 = VECTOR('',#156274,1.); -#156274 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); -#156275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156276 = PCURVE('',#156012,#156277); -#156277 = DEFINITIONAL_REPRESENTATION('',(#156278),#156282); -#156278 = LINE('',#156279,#156280); -#156279 = CARTESIAN_POINT('',(0.E+000,0.35)); -#156280 = VECTOR('',#156281,1.); -#156281 = DIRECTION('',(1.,0.E+000)); -#156282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156283 = ORIENTED_EDGE('',*,*,#156284,.F.); -#156284 = EDGE_CURVE('',#156285,#156262,#156287,.T.); -#156285 = VERTEX_POINT('',#156286); -#156286 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.475 +#158636 = VECTOR('',#158637,1.); +#158637 = DIRECTION('',(0.99756405026,6.975647374417E-002,0.E+000)); +#158638 = PCURVE('',#153719,#158639); +#158639 = DEFINITIONAL_REPRESENTATION('',(#158640),#158644); +#158640 = LINE('',#158641,#158642); +#158641 = CARTESIAN_POINT('',(-4.688389642009E-002,-0.628280229748)); +#158642 = VECTOR('',#158643,1.); +#158643 = DIRECTION('',(0.99756405026,6.975647374417E-002)); +#158644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158645 = PCURVE('',#158432,#158646); +#158646 = DEFINITIONAL_REPRESENTATION('',(#158647),#158651); +#158647 = LINE('',#158648,#158649); +#158648 = CARTESIAN_POINT('',(0.E+000,0.35)); +#158649 = VECTOR('',#158650,1.); +#158650 = DIRECTION('',(1.,0.E+000)); +#158651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158652 = ORIENTED_EDGE('',*,*,#158653,.F.); +#158653 = EDGE_CURVE('',#158654,#158631,#158656,.T.); +#158654 = VERTEX_POINT('',#158655); +#158655 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.475)); +#158656 = SURFACE_CURVE('',#158657,(#158661,#158668),.PCURVE_S1.); +#158657 = LINE('',#158658,#158659); +#158658 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.475)); +#158659 = VECTOR('',#158660,1.); +#158660 = DIRECTION('',(-6.975647374418E-002,0.99756405026,0.E+000)); +#158661 = PCURVE('',#153719,#158662); +#158662 = DEFINITIONAL_REPRESENTATION('',(#158663),#158667); +#158663 = LINE('',#158664,#158665); +#158664 = CARTESIAN_POINT('',(-0.375999999998,-0.66733334)); +#158665 = VECTOR('',#158666,1.); +#158666 = DIRECTION('',(-6.975647374418E-002,0.99756405026)); +#158667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158668 = PCURVE('',#158404,#158669); +#158669 = DEFINITIONAL_REPRESENTATION('',(#158670),#158674); +#158670 = LINE('',#158671,#158672); +#158671 = CARTESIAN_POINT('',(0.E+000,0.35)); +#158672 = VECTOR('',#158673,1.); +#158673 = DIRECTION('',(1.,0.E+000)); +#158674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158675 = ORIENTED_EDGE('',*,*,#158676,.F.); +#158676 = EDGE_CURVE('',#158677,#158654,#158679,.T.); +#158677 = VERTEX_POINT('',#158678); +#158678 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.475 )); -#156287 = SURFACE_CURVE('',#156288,(#156292,#156299),.PCURVE_S1.); -#156288 = LINE('',#156289,#156290); -#156289 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.475 +#158679 = SURFACE_CURVE('',#158680,(#158684,#158691),.PCURVE_S1.); +#158680 = LINE('',#158681,#158682); +#158681 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.475 )); -#156290 = VECTOR('',#156291,1.); -#156291 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); -#156292 = PCURVE('',#151327,#156293); -#156293 = DEFINITIONAL_REPRESENTATION('',(#156294),#156298); -#156294 = LINE('',#156295,#156296); -#156295 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); -#156296 = VECTOR('',#156297,1.); -#156297 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); -#156298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156299 = PCURVE('',#155984,#156300); -#156300 = DEFINITIONAL_REPRESENTATION('',(#156301),#156305); -#156301 = LINE('',#156302,#156303); -#156302 = CARTESIAN_POINT('',(0.E+000,0.35)); -#156303 = VECTOR('',#156304,1.); -#156304 = DIRECTION('',(1.,0.E+000)); -#156305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156306 = ORIENTED_EDGE('',*,*,#156307,.F.); -#156307 = EDGE_CURVE('',#156308,#156285,#156310,.T.); -#156308 = VERTEX_POINT('',#156309); -#156309 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.475 +#158682 = VECTOR('',#158683,1.); +#158683 = DIRECTION('',(-0.99756405026,-6.975647374417E-002,0.E+000)); +#158684 = PCURVE('',#153719,#158685); +#158685 = DEFINITIONAL_REPRESENTATION('',(#158686),#158690); +#158686 = LINE('',#158687,#158688); +#158687 = CARTESIAN_POINT('',(-4.576779284019E-002,-0.644241254552)); +#158688 = VECTOR('',#158689,1.); +#158689 = DIRECTION('',(-0.99756405026,-6.975647374417E-002)); +#158690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158691 = PCURVE('',#158376,#158692); +#158692 = DEFINITIONAL_REPRESENTATION('',(#158693),#158697); +#158693 = LINE('',#158694,#158695); +#158694 = CARTESIAN_POINT('',(0.E+000,0.35)); +#158695 = VECTOR('',#158696,1.); +#158696 = DIRECTION('',(1.,0.E+000)); +#158697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158698 = ORIENTED_EDGE('',*,*,#158699,.F.); +#158699 = EDGE_CURVE('',#158700,#158677,#158702,.T.); +#158700 = VERTEX_POINT('',#158701); +#158701 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.475 )); -#156310 = SURFACE_CURVE('',#156311,(#156316,#156327),.PCURVE_S1.); -#156311 = CIRCLE('',#156312,3.199999999999E-002); -#156312 = AXIS2_PLACEMENT_3D('',#156313,#156314,#156315); -#156313 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.475 +#158702 = SURFACE_CURVE('',#158703,(#158708,#158719),.PCURVE_S1.); +#158703 = CIRCLE('',#158704,3.199999999999E-002); +#158704 = AXIS2_PLACEMENT_3D('',#158705,#158706,#158707); +#158705 = CARTESIAN_POINT('',(-0.722000000002,5.501413505592E-002,-0.475 )); -#156314 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#156315 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#156316 = PCURVE('',#151327,#156317); -#156317 = DEFINITIONAL_REPRESENTATION('',(#156318),#156326); -#156318 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156319,#156320,#156321, - #156322,#156323,#156324,#156325),.UNSPECIFIED.,.T.,.F.) +#158706 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#158707 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#158708 = PCURVE('',#153719,#158709); +#158709 = DEFINITIONAL_REPRESENTATION('',(#158710),#158718); +#158710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158711,#158712,#158713, + #158714,#158715,#158716,#158717),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#156319 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#156320 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); -#156321 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); -#156322 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); -#156323 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); -#156324 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); -#156325 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); -#156326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156327 = PCURVE('',#155957,#156328); -#156328 = DEFINITIONAL_REPRESENTATION('',(#156329),#156332); -#156329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156330,#156331), +#158711 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#158712 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.556893579102)); +#158713 = CARTESIAN_POINT('',(-3.2E-002,-0.584606392023)); +#158714 = CARTESIAN_POINT('',(1.599999999999E-002,-0.612319204944)); +#158715 = CARTESIAN_POINT('',(-3.2E-002,-0.640032017865)); +#158716 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.667744830786)); +#158717 = CARTESIAN_POINT('',(-7.999999999999E-002,-0.612319204944)); +#158718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158719 = PCURVE('',#158349,#158720); +#158720 = DEFINITIONAL_REPRESENTATION('',(#158721),#158724); +#158721 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158722,#158723), .UNSPECIFIED.,.F.,.F.,(2,2),(3.141592653589,4.642575810305), .PIECEWISE_BEZIER_KNOTS.); -#156330 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#156331 = CARTESIAN_POINT('',(4.782202150464,0.35)); -#156332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156333 = ORIENTED_EDGE('',*,*,#156334,.F.); -#156334 = EDGE_CURVE('',#156335,#156308,#156337,.T.); -#156335 = VERTEX_POINT('',#156336); -#156336 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.475)); -#156337 = SURFACE_CURVE('',#156338,(#156342,#156349),.PCURVE_S1.); -#156338 = LINE('',#156339,#156340); -#156339 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.475)); -#156340 = VECTOR('',#156341,1.); -#156341 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#156342 = PCURVE('',#151327,#156343); -#156343 = DEFINITIONAL_REPRESENTATION('',(#156344),#156348); -#156344 = LINE('',#156345,#156346); -#156345 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); -#156346 = VECTOR('',#156347,1.); -#156347 = DIRECTION('',(0.E+000,-1.)); -#156348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156349 = PCURVE('',#155924,#156350); -#156350 = DEFINITIONAL_REPRESENTATION('',(#156351),#156355); -#156351 = LINE('',#156352,#156353); -#156352 = CARTESIAN_POINT('',(0.35,0.E+000)); -#156353 = VECTOR('',#156354,1.); -#156354 = DIRECTION('',(0.E+000,-1.)); -#156355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156356 = ORIENTED_EDGE('',*,*,#156357,.F.); -#156357 = EDGE_CURVE('',#155810,#156335,#156358,.T.); -#156358 = SURFACE_CURVE('',#156359,(#156364,#156371),.PCURVE_S1.); -#156359 = CIRCLE('',#156360,1.6E-002); -#156360 = AXIS2_PLACEMENT_3D('',#156361,#156362,#156363); -#156361 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); -#156362 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156363 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156364 = PCURVE('',#151327,#156365); -#156365 = DEFINITIONAL_REPRESENTATION('',(#156366),#156370); -#156366 = CIRCLE('',#156367,1.6E-002); -#156367 = AXIS2_PLACEMENT_2D('',#156368,#156369); -#156368 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156369 = DIRECTION('',(1.,0.E+000)); -#156370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156371 = PCURVE('',#155846,#156372); -#156372 = DEFINITIONAL_REPRESENTATION('',(#156373),#156376); -#156373 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156374,#156375), +#158722 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#158723 = CARTESIAN_POINT('',(4.782202150464,0.35)); +#158724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158725 = ORIENTED_EDGE('',*,*,#158726,.F.); +#158726 = EDGE_CURVE('',#158727,#158700,#158729,.T.); +#158727 = VERTEX_POINT('',#158728); +#158728 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.475)); +#158729 = SURFACE_CURVE('',#158730,(#158734,#158741),.PCURVE_S1.); +#158730 = LINE('',#158731,#158732); +#158731 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.475)); +#158732 = VECTOR('',#158733,1.); +#158733 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#158734 = PCURVE('',#153719,#158735); +#158735 = DEFINITIONAL_REPRESENTATION('',(#158736),#158740); +#158736 = LINE('',#158737,#158738); +#158737 = CARTESIAN_POINT('',(-1.6E-002,0.E+000)); +#158738 = VECTOR('',#158739,1.); +#158739 = DIRECTION('',(0.E+000,-1.)); +#158740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158741 = PCURVE('',#158316,#158742); +#158742 = DEFINITIONAL_REPRESENTATION('',(#158743),#158747); +#158743 = LINE('',#158744,#158745); +#158744 = CARTESIAN_POINT('',(0.35,0.E+000)); +#158745 = VECTOR('',#158746,1.); +#158746 = DIRECTION('',(0.E+000,-1.)); +#158747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158748 = ORIENTED_EDGE('',*,*,#158749,.F.); +#158749 = EDGE_CURVE('',#158202,#158727,#158750,.T.); +#158750 = SURFACE_CURVE('',#158751,(#158756,#158763),.PCURVE_S1.); +#158751 = CIRCLE('',#158752,1.6E-002); +#158752 = AXIS2_PLACEMENT_3D('',#158753,#158754,#158755); +#158753 = CARTESIAN_POINT('',(-0.674000000002,0.66733334,-0.475)); +#158754 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158755 = DIRECTION('',(1.,0.E+000,0.E+000)); +#158756 = PCURVE('',#153719,#158757); +#158757 = DEFINITIONAL_REPRESENTATION('',(#158758),#158762); +#158758 = CIRCLE('',#158759,1.6E-002); +#158759 = AXIS2_PLACEMENT_2D('',#158760,#158761); +#158760 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158761 = DIRECTION('',(1.,0.E+000)); +#158762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158763 = PCURVE('',#158238,#158764); +#158764 = DEFINITIONAL_REPRESENTATION('',(#158765),#158768); +#158765 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158766,#158767), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#156374 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#156375 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#156376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156377 = ORIENTED_EDGE('',*,*,#155809,.F.); -#156378 = ADVANCED_FACE('',(#156379),#155846,.F.); -#156379 = FACE_BOUND('',#156380,.F.); -#156380 = EDGE_LOOP('',(#156381,#156382,#156383,#156384)); -#156381 = ORIENTED_EDGE('',*,*,#156357,.F.); -#156382 = ORIENTED_EDGE('',*,*,#155832,.F.); -#156383 = ORIENTED_EDGE('',*,*,#155885,.T.); -#156384 = ORIENTED_EDGE('',*,*,#156385,.T.); -#156385 = EDGE_CURVE('',#155886,#156335,#156386,.T.); -#156386 = SURFACE_CURVE('',#156387,(#156391,#156397),.PCURVE_S1.); -#156387 = LINE('',#156388,#156389); -#156388 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); -#156389 = VECTOR('',#156390,1.); -#156390 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156391 = PCURVE('',#155846,#156392); -#156392 = DEFINITIONAL_REPRESENTATION('',(#156393),#156396); -#156393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156394,#156395), +#158766 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#158767 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#158768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158769 = ORIENTED_EDGE('',*,*,#158201,.F.); +#158770 = ADVANCED_FACE('',(#158771),#158238,.F.); +#158771 = FACE_BOUND('',#158772,.F.); +#158772 = EDGE_LOOP('',(#158773,#158774,#158775,#158776)); +#158773 = ORIENTED_EDGE('',*,*,#158749,.F.); +#158774 = ORIENTED_EDGE('',*,*,#158224,.F.); +#158775 = ORIENTED_EDGE('',*,*,#158277,.T.); +#158776 = ORIENTED_EDGE('',*,*,#158777,.T.); +#158777 = EDGE_CURVE('',#158278,#158727,#158778,.T.); +#158778 = SURFACE_CURVE('',#158779,(#158783,#158789),.PCURVE_S1.); +#158779 = LINE('',#158780,#158781); +#158780 = CARTESIAN_POINT('',(-0.690000000002,0.66733334,-0.825)); +#158781 = VECTOR('',#158782,1.); +#158782 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158783 = PCURVE('',#158238,#158784); +#158784 = DEFINITIONAL_REPRESENTATION('',(#158785),#158788); +#158785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158786,#158787), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156394 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#156395 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#156396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156397 = PCURVE('',#155924,#156398); -#156398 = DEFINITIONAL_REPRESENTATION('',(#156399),#156403); -#156399 = LINE('',#156400,#156401); -#156400 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156401 = VECTOR('',#156402,1.); -#156402 = DIRECTION('',(1.,0.E+000)); -#156403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156404 = ADVANCED_FACE('',(#156405),#155924,.F.); -#156405 = FACE_BOUND('',#156406,.T.); -#156406 = EDGE_LOOP('',(#156407,#156408,#156451,#156452)); -#156407 = ORIENTED_EDGE('',*,*,#156334,.T.); -#156408 = ORIENTED_EDGE('',*,*,#156409,.F.); -#156409 = EDGE_CURVE('',#155909,#156308,#156410,.T.); -#156410 = SURFACE_CURVE('',#156411,(#156415,#156422),.PCURVE_S1.); -#156411 = LINE('',#156412,#156413); -#156412 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.825 +#158786 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#158787 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#158788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158789 = PCURVE('',#158316,#158790); +#158790 = DEFINITIONAL_REPRESENTATION('',(#158791),#158795); +#158791 = LINE('',#158792,#158793); +#158792 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158793 = VECTOR('',#158794,1.); +#158794 = DIRECTION('',(1.,0.E+000)); +#158795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158796 = ADVANCED_FACE('',(#158797),#158316,.F.); +#158797 = FACE_BOUND('',#158798,.T.); +#158798 = EDGE_LOOP('',(#158799,#158800,#158843,#158844)); +#158799 = ORIENTED_EDGE('',*,*,#158726,.T.); +#158800 = ORIENTED_EDGE('',*,*,#158801,.F.); +#158801 = EDGE_CURVE('',#158301,#158700,#158802,.T.); +#158802 = SURFACE_CURVE('',#158803,(#158807,#158814),.PCURVE_S1.); +#158803 = LINE('',#158804,#158805); +#158804 = CARTESIAN_POINT('',(-0.690000000002,5.501413505593E-002,-0.825 )); -#156413 = VECTOR('',#156414,1.); -#156414 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156415 = PCURVE('',#155924,#156416); -#156416 = DEFINITIONAL_REPRESENTATION('',(#156417),#156421); -#156417 = LINE('',#156418,#156419); -#156418 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#156419 = VECTOR('',#156420,1.); -#156420 = DIRECTION('',(1.,0.E+000)); -#156421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156422 = PCURVE('',#155957,#156423); -#156423 = DEFINITIONAL_REPRESENTATION('',(#156424),#156450); -#156424 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156425,#156426,#156427, - #156428,#156429,#156430,#156431,#156432,#156433,#156434,#156435, - #156436,#156437,#156438,#156439,#156440,#156441,#156442,#156443, - #156444,#156445,#156446,#156447,#156448,#156449),.UNSPECIFIED.,.F., +#158805 = VECTOR('',#158806,1.); +#158806 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158807 = PCURVE('',#158316,#158808); +#158808 = DEFINITIONAL_REPRESENTATION('',(#158809),#158813); +#158809 = LINE('',#158810,#158811); +#158810 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#158811 = VECTOR('',#158812,1.); +#158812 = DIRECTION('',(1.,0.E+000)); +#158813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158814 = PCURVE('',#158349,#158815); +#158815 = DEFINITIONAL_REPRESENTATION('',(#158816),#158842); +#158816 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158817,#158818,#158819, + #158820,#158821,#158822,#158823,#158824,#158825,#158826,#158827, + #158828,#158829,#158830,#158831,#158832,#158833,#158834,#158835, + #158836,#158837,#158838,#158839,#158840,#158841),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.590909090909E-002,3.181818181818E-002,4.772727272727E-002, 6.363636363636E-002,7.954545454545E-002,9.545454545455E-002, @@ -192919,377 +195921,377 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.190909090909,0.206818181818,0.222727272727,0.238636363636, 0.254545454545,0.270454545455,0.286363636364,0.302272727273, 0.318181818182,0.334090909091,0.35),.QUASI_UNIFORM_KNOTS.); -#156425 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#156426 = CARTESIAN_POINT('',(6.28318530718,5.30303030303E-003)); -#156427 = CARTESIAN_POINT('',(6.28318530718,1.590909090909E-002)); -#156428 = CARTESIAN_POINT('',(6.28318530718,3.181818181818E-002)); -#156429 = CARTESIAN_POINT('',(6.28318530718,4.772727272727E-002)); -#156430 = CARTESIAN_POINT('',(6.28318530718,6.363636363636E-002)); -#156431 = CARTESIAN_POINT('',(6.28318530718,7.954545454545E-002)); -#156432 = CARTESIAN_POINT('',(6.28318530718,9.545454545455E-002)); -#156433 = CARTESIAN_POINT('',(6.28318530718,0.111363636364)); -#156434 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#156435 = CARTESIAN_POINT('',(6.28318530718,0.143181818182)); -#156436 = CARTESIAN_POINT('',(6.28318530718,0.159090909091)); -#156437 = CARTESIAN_POINT('',(6.28318530718,0.175)); -#156438 = CARTESIAN_POINT('',(6.28318530718,0.190909090909)); -#156439 = CARTESIAN_POINT('',(6.28318530718,0.206818181818)); -#156440 = CARTESIAN_POINT('',(6.28318530718,0.222727272727)); -#156441 = CARTESIAN_POINT('',(6.28318530718,0.238636363636)); -#156442 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#156443 = CARTESIAN_POINT('',(6.28318530718,0.270454545455)); -#156444 = CARTESIAN_POINT('',(6.28318530718,0.286363636364)); -#156445 = CARTESIAN_POINT('',(6.28318530718,0.302272727273)); -#156446 = CARTESIAN_POINT('',(6.28318530718,0.318181818182)); -#156447 = CARTESIAN_POINT('',(6.28318530718,0.334090909091)); -#156448 = CARTESIAN_POINT('',(6.28318530718,0.344696969697)); -#156449 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#156450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156451 = ORIENTED_EDGE('',*,*,#155908,.F.); -#156452 = ORIENTED_EDGE('',*,*,#156385,.T.); -#156453 = ADVANCED_FACE('',(#156454),#155957,.T.); -#156454 = FACE_BOUND('',#156455,.T.); -#156455 = EDGE_LOOP('',(#156456,#156457,#156477,#156478)); -#156456 = ORIENTED_EDGE('',*,*,#156307,.T.); -#156457 = ORIENTED_EDGE('',*,*,#156458,.F.); -#156458 = EDGE_CURVE('',#155937,#156285,#156459,.T.); -#156459 = SURFACE_CURVE('',#156460,(#156464,#156470),.PCURVE_S1.); -#156460 = LINE('',#156461,#156462); -#156461 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 +#158817 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#158818 = CARTESIAN_POINT('',(6.28318530718,5.30303030303E-003)); +#158819 = CARTESIAN_POINT('',(6.28318530718,1.590909090909E-002)); +#158820 = CARTESIAN_POINT('',(6.28318530718,3.181818181818E-002)); +#158821 = CARTESIAN_POINT('',(6.28318530718,4.772727272727E-002)); +#158822 = CARTESIAN_POINT('',(6.28318530718,6.363636363636E-002)); +#158823 = CARTESIAN_POINT('',(6.28318530718,7.954545454545E-002)); +#158824 = CARTESIAN_POINT('',(6.28318530718,9.545454545455E-002)); +#158825 = CARTESIAN_POINT('',(6.28318530718,0.111363636364)); +#158826 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#158827 = CARTESIAN_POINT('',(6.28318530718,0.143181818182)); +#158828 = CARTESIAN_POINT('',(6.28318530718,0.159090909091)); +#158829 = CARTESIAN_POINT('',(6.28318530718,0.175)); +#158830 = CARTESIAN_POINT('',(6.28318530718,0.190909090909)); +#158831 = CARTESIAN_POINT('',(6.28318530718,0.206818181818)); +#158832 = CARTESIAN_POINT('',(6.28318530718,0.222727272727)); +#158833 = CARTESIAN_POINT('',(6.28318530718,0.238636363636)); +#158834 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#158835 = CARTESIAN_POINT('',(6.28318530718,0.270454545455)); +#158836 = CARTESIAN_POINT('',(6.28318530718,0.286363636364)); +#158837 = CARTESIAN_POINT('',(6.28318530718,0.302272727273)); +#158838 = CARTESIAN_POINT('',(6.28318530718,0.318181818182)); +#158839 = CARTESIAN_POINT('',(6.28318530718,0.334090909091)); +#158840 = CARTESIAN_POINT('',(6.28318530718,0.344696969697)); +#158841 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#158842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158843 = ORIENTED_EDGE('',*,*,#158300,.F.); +#158844 = ORIENTED_EDGE('',*,*,#158777,.T.); +#158845 = ADVANCED_FACE('',(#158846),#158349,.T.); +#158846 = FACE_BOUND('',#158847,.T.); +#158847 = EDGE_LOOP('',(#158848,#158849,#158869,#158870)); +#158848 = ORIENTED_EDGE('',*,*,#158699,.T.); +#158849 = ORIENTED_EDGE('',*,*,#158850,.F.); +#158850 = EDGE_CURVE('',#158329,#158677,#158851,.T.); +#158851 = SURFACE_CURVE('',#158852,(#158856,#158862),.PCURVE_S1.); +#158852 = LINE('',#158853,#158854); +#158853 = CARTESIAN_POINT('',(-0.719767792842,2.309208544762E-002,-0.825 )); -#156462 = VECTOR('',#156463,1.); -#156463 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156464 = PCURVE('',#155957,#156465); -#156465 = DEFINITIONAL_REPRESENTATION('',(#156466),#156469); -#156466 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156467,#156468), +#158854 = VECTOR('',#158855,1.); +#158855 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158856 = PCURVE('',#158349,#158857); +#158857 = DEFINITIONAL_REPRESENTATION('',(#158858),#158861); +#158858 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158859,#158860), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156467 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#156468 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#156469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156470 = PCURVE('',#155984,#156471); -#156471 = DEFINITIONAL_REPRESENTATION('',(#156472),#156476); -#156472 = LINE('',#156473,#156474); -#156473 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156474 = VECTOR('',#156475,1.); -#156475 = DIRECTION('',(0.E+000,1.)); -#156476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156477 = ORIENTED_EDGE('',*,*,#155936,.F.); -#156478 = ORIENTED_EDGE('',*,*,#156409,.T.); -#156479 = ADVANCED_FACE('',(#156480),#155984,.F.); -#156480 = FACE_BOUND('',#156481,.T.); -#156481 = EDGE_LOOP('',(#156482,#156483,#156504,#156505)); -#156482 = ORIENTED_EDGE('',*,*,#156284,.T.); -#156483 = ORIENTED_EDGE('',*,*,#156484,.F.); -#156484 = EDGE_CURVE('',#155969,#156262,#156485,.T.); -#156485 = SURFACE_CURVE('',#156486,(#156490,#156497),.PCURVE_S1.); -#156486 = LINE('',#156487,#156488); -#156487 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); -#156488 = VECTOR('',#156489,1.); -#156489 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156490 = PCURVE('',#155984,#156491); -#156491 = DEFINITIONAL_REPRESENTATION('',(#156492),#156496); -#156492 = LINE('',#156493,#156494); -#156493 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); -#156494 = VECTOR('',#156495,1.); -#156495 = DIRECTION('',(0.E+000,1.)); -#156496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156497 = PCURVE('',#156012,#156498); -#156498 = DEFINITIONAL_REPRESENTATION('',(#156499),#156503); -#156499 = LINE('',#156500,#156501); -#156500 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156501 = VECTOR('',#156502,1.); -#156502 = DIRECTION('',(0.E+000,1.)); -#156503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156504 = ORIENTED_EDGE('',*,*,#155968,.F.); -#156505 = ORIENTED_EDGE('',*,*,#156458,.T.); -#156506 = ADVANCED_FACE('',(#156507),#156012,.F.); -#156507 = FACE_BOUND('',#156508,.T.); -#156508 = EDGE_LOOP('',(#156509,#156510,#156531,#156532)); -#156509 = ORIENTED_EDGE('',*,*,#156261,.T.); -#156510 = ORIENTED_EDGE('',*,*,#156511,.F.); -#156511 = EDGE_CURVE('',#155997,#156239,#156512,.T.); -#156512 = SURFACE_CURVE('',#156513,(#156517,#156524),.PCURVE_S1.); -#156513 = LINE('',#156514,#156515); -#156514 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.825) - ); -#156515 = VECTOR('',#156516,1.); -#156516 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156517 = PCURVE('',#156012,#156518); -#156518 = DEFINITIONAL_REPRESENTATION('',(#156519),#156523); -#156519 = LINE('',#156520,#156521); -#156520 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); -#156521 = VECTOR('',#156522,1.); -#156522 = DIRECTION('',(0.E+000,1.)); -#156523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156524 = PCURVE('',#156040,#156525); -#156525 = DEFINITIONAL_REPRESENTATION('',(#156526),#156530); -#156526 = LINE('',#156527,#156528); -#156527 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); -#156528 = VECTOR('',#156529,1.); -#156529 = DIRECTION('',(0.E+000,1.)); -#156530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156531 = ORIENTED_EDGE('',*,*,#155996,.F.); -#156532 = ORIENTED_EDGE('',*,*,#156484,.T.); -#156533 = ADVANCED_FACE('',(#156534),#156040,.F.); -#156534 = FACE_BOUND('',#156535,.T.); -#156535 = EDGE_LOOP('',(#156536,#156537,#156557,#156558)); -#156536 = ORIENTED_EDGE('',*,*,#156238,.T.); -#156537 = ORIENTED_EDGE('',*,*,#156538,.F.); -#156538 = EDGE_CURVE('',#156025,#156216,#156539,.T.); -#156539 = SURFACE_CURVE('',#156540,(#156544,#156551),.PCURVE_S1.); -#156540 = LINE('',#156541,#156542); -#156541 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.825 +#158859 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#158860 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#158861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158862 = PCURVE('',#158376,#158863); +#158863 = DEFINITIONAL_REPRESENTATION('',(#158864),#158868); +#158864 = LINE('',#158865,#158866); +#158865 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158866 = VECTOR('',#158867,1.); +#158867 = DIRECTION('',(0.E+000,1.)); +#158868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158869 = ORIENTED_EDGE('',*,*,#158328,.F.); +#158870 = ORIENTED_EDGE('',*,*,#158801,.T.); +#158871 = ADVANCED_FACE('',(#158872),#158376,.F.); +#158872 = FACE_BOUND('',#158873,.T.); +#158873 = EDGE_LOOP('',(#158874,#158875,#158896,#158897)); +#158874 = ORIENTED_EDGE('',*,*,#158676,.T.); +#158875 = ORIENTED_EDGE('',*,*,#158876,.F.); +#158876 = EDGE_CURVE('',#158361,#158654,#158877,.T.); +#158877 = SURFACE_CURVE('',#158878,(#158882,#158889),.PCURVE_S1.); +#158878 = LINE('',#158879,#158880); +#158879 = CARTESIAN_POINT('',(-1.05,0.E+000,-0.825)); +#158880 = VECTOR('',#158881,1.); +#158881 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158882 = PCURVE('',#158376,#158883); +#158883 = DEFINITIONAL_REPRESENTATION('',(#158884),#158888); +#158884 = LINE('',#158885,#158886); +#158885 = CARTESIAN_POINT('',(0.331038600551,0.E+000)); +#158886 = VECTOR('',#158887,1.); +#158887 = DIRECTION('',(0.E+000,1.)); +#158888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158889 = PCURVE('',#158404,#158890); +#158890 = DEFINITIONAL_REPRESENTATION('',(#158891),#158895); +#158891 = LINE('',#158892,#158893); +#158892 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158893 = VECTOR('',#158894,1.); +#158894 = DIRECTION('',(0.E+000,1.)); +#158895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158896 = ORIENTED_EDGE('',*,*,#158360,.F.); +#158897 = ORIENTED_EDGE('',*,*,#158850,.T.); +#158898 = ADVANCED_FACE('',(#158899),#158404,.F.); +#158899 = FACE_BOUND('',#158900,.T.); +#158900 = EDGE_LOOP('',(#158901,#158902,#158923,#158924)); +#158901 = ORIENTED_EDGE('',*,*,#158653,.T.); +#158902 = ORIENTED_EDGE('',*,*,#158903,.F.); +#158903 = EDGE_CURVE('',#158389,#158631,#158904,.T.); +#158904 = SURFACE_CURVE('',#158905,(#158909,#158916),.PCURVE_S1.); +#158905 = LINE('',#158906,#158907); +#158906 = CARTESIAN_POINT('',(-1.05111610358,1.596102480416E-002,-0.825) + ); +#158907 = VECTOR('',#158908,1.); +#158908 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158909 = PCURVE('',#158404,#158910); +#158910 = DEFINITIONAL_REPRESENTATION('',(#158911),#158915); +#158911 = LINE('',#158912,#158913); +#158912 = CARTESIAN_POINT('',(1.6E-002,0.E+000)); +#158913 = VECTOR('',#158914,1.); +#158914 = DIRECTION('',(0.E+000,1.)); +#158915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158916 = PCURVE('',#158432,#158917); +#158917 = DEFINITIONAL_REPRESENTATION('',(#158918),#158922); +#158918 = LINE('',#158919,#158920); +#158919 = CARTESIAN_POINT('',(-0.331038600551,0.E+000)); +#158920 = VECTOR('',#158921,1.); +#158921 = DIRECTION('',(0.E+000,1.)); +#158922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158923 = ORIENTED_EDGE('',*,*,#158388,.F.); +#158924 = ORIENTED_EDGE('',*,*,#158876,.T.); +#158925 = ADVANCED_FACE('',(#158926),#158432,.F.); +#158926 = FACE_BOUND('',#158927,.T.); +#158927 = EDGE_LOOP('',(#158928,#158929,#158949,#158950)); +#158928 = ORIENTED_EDGE('',*,*,#158630,.T.); +#158929 = ORIENTED_EDGE('',*,*,#158930,.F.); +#158930 = EDGE_CURVE('',#158417,#158608,#158931,.T.); +#158931 = SURFACE_CURVE('',#158932,(#158936,#158943),.PCURVE_S1.); +#158932 = LINE('',#158933,#158934); +#158933 = CARTESIAN_POINT('',(-0.720883896422,3.905311025177E-002,-0.825 )); -#156542 = VECTOR('',#156543,1.); -#156543 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156544 = PCURVE('',#156040,#156545); -#156545 = DEFINITIONAL_REPRESENTATION('',(#156546),#156550); -#156546 = LINE('',#156547,#156548); -#156547 = CARTESIAN_POINT('',(1.112358904841E-016,0.E+000)); -#156548 = VECTOR('',#156549,1.); -#156549 = DIRECTION('',(0.E+000,1.)); -#156550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156551 = PCURVE('',#156069,#156552); -#156552 = DEFINITIONAL_REPRESENTATION('',(#156553),#156556); -#156553 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156554,#156555), +#158934 = VECTOR('',#158935,1.); +#158935 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158936 = PCURVE('',#158432,#158937); +#158937 = DEFINITIONAL_REPRESENTATION('',(#158938),#158942); +#158938 = LINE('',#158939,#158940); +#158939 = CARTESIAN_POINT('',(1.112358904841E-016,0.E+000)); +#158940 = VECTOR('',#158941,1.); +#158941 = DIRECTION('',(0.E+000,1.)); +#158942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158943 = PCURVE('',#158461,#158944); +#158944 = DEFINITIONAL_REPRESENTATION('',(#158945),#158948); +#158945 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158946,#158947), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156554 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); -#156555 = CARTESIAN_POINT('',(4.782202150465,0.35)); -#156556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156557 = ORIENTED_EDGE('',*,*,#156024,.F.); -#156558 = ORIENTED_EDGE('',*,*,#156511,.T.); -#156559 = ADVANCED_FACE('',(#156560),#156069,.F.); -#156560 = FACE_BOUND('',#156561,.F.); -#156561 = EDGE_LOOP('',(#156562,#156563,#156564,#156565)); -#156562 = ORIENTED_EDGE('',*,*,#156215,.F.); -#156563 = ORIENTED_EDGE('',*,*,#156538,.F.); -#156564 = ORIENTED_EDGE('',*,*,#156052,.T.); -#156565 = ORIENTED_EDGE('',*,*,#156566,.T.); -#156566 = EDGE_CURVE('',#156053,#156193,#156567,.T.); -#156567 = SURFACE_CURVE('',#156568,(#156572,#156578),.PCURVE_S1.); -#156568 = LINE('',#156569,#156570); -#156569 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.825 +#158946 = CARTESIAN_POINT('',(4.782202150465,0.E+000)); +#158947 = CARTESIAN_POINT('',(4.782202150465,0.35)); +#158948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158949 = ORIENTED_EDGE('',*,*,#158416,.F.); +#158950 = ORIENTED_EDGE('',*,*,#158903,.T.); +#158951 = ADVANCED_FACE('',(#158952),#158461,.F.); +#158952 = FACE_BOUND('',#158953,.F.); +#158953 = EDGE_LOOP('',(#158954,#158955,#158956,#158957)); +#158954 = ORIENTED_EDGE('',*,*,#158607,.F.); +#158955 = ORIENTED_EDGE('',*,*,#158930,.F.); +#158956 = ORIENTED_EDGE('',*,*,#158444,.T.); +#158957 = ORIENTED_EDGE('',*,*,#158958,.T.); +#158958 = EDGE_CURVE('',#158445,#158585,#158959,.T.); +#158959 = SURFACE_CURVE('',#158960,(#158964,#158970),.PCURVE_S1.); +#158960 = LINE('',#158961,#158962); +#158961 = CARTESIAN_POINT('',(-0.706000000002,5.501413505592E-002,-0.825 )); -#156570 = VECTOR('',#156571,1.); -#156571 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156572 = PCURVE('',#156069,#156573); -#156573 = DEFINITIONAL_REPRESENTATION('',(#156574),#156577); -#156574 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156575,#156576), +#158962 = VECTOR('',#158963,1.); +#158963 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158964 = PCURVE('',#158461,#158965); +#158965 = DEFINITIONAL_REPRESENTATION('',(#158966),#158969); +#158966 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158967,#158968), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156575 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#156576 = CARTESIAN_POINT('',(6.28318530718,0.35)); -#156577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156578 = PCURVE('',#156096,#156579); -#156579 = DEFINITIONAL_REPRESENTATION('',(#156580),#156584); -#156580 = LINE('',#156581,#156582); -#156581 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); -#156582 = VECTOR('',#156583,1.); -#156583 = DIRECTION('',(-1.,0.E+000)); -#156584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156585 = ADVANCED_FACE('',(#156586),#156096,.F.); -#156586 = FACE_BOUND('',#156587,.T.); -#156587 = EDGE_LOOP('',(#156588,#156589,#156609,#156610)); -#156588 = ORIENTED_EDGE('',*,*,#156192,.T.); -#156589 = ORIENTED_EDGE('',*,*,#156590,.F.); -#156590 = EDGE_CURVE('',#156081,#156166,#156591,.T.); -#156591 = SURFACE_CURVE('',#156592,(#156596,#156603),.PCURVE_S1.); -#156592 = LINE('',#156593,#156594); -#156593 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); -#156594 = VECTOR('',#156595,1.); -#156595 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156596 = PCURVE('',#156096,#156597); -#156597 = DEFINITIONAL_REPRESENTATION('',(#156598),#156602); -#156598 = LINE('',#156599,#156600); -#156599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156600 = VECTOR('',#156601,1.); -#156601 = DIRECTION('',(-1.,0.E+000)); -#156602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156603 = PCURVE('',#156127,#156604); -#156604 = DEFINITIONAL_REPRESENTATION('',(#156605),#156608); -#156605 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156606,#156607), +#158967 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#158968 = CARTESIAN_POINT('',(6.28318530718,0.35)); +#158969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158970 = PCURVE('',#158488,#158971); +#158971 = DEFINITIONAL_REPRESENTATION('',(#158972),#158976); +#158972 = LINE('',#158973,#158974); +#158973 = CARTESIAN_POINT('',(0.E+000,-0.612319204944)); +#158974 = VECTOR('',#158975,1.); +#158975 = DIRECTION('',(-1.,0.E+000)); +#158976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158977 = ADVANCED_FACE('',(#158978),#158488,.F.); +#158978 = FACE_BOUND('',#158979,.T.); +#158979 = EDGE_LOOP('',(#158980,#158981,#159001,#159002)); +#158980 = ORIENTED_EDGE('',*,*,#158584,.T.); +#158981 = ORIENTED_EDGE('',*,*,#158982,.F.); +#158982 = EDGE_CURVE('',#158473,#158558,#158983,.T.); +#158983 = SURFACE_CURVE('',#158984,(#158988,#158995),.PCURVE_S1.); +#158984 = LINE('',#158985,#158986); +#158985 = CARTESIAN_POINT('',(-0.706000000002,0.66733334,-0.825)); +#158986 = VECTOR('',#158987,1.); +#158987 = DIRECTION('',(0.E+000,0.E+000,1.)); +#158988 = PCURVE('',#158488,#158989); +#158989 = DEFINITIONAL_REPRESENTATION('',(#158990),#158994); +#158990 = LINE('',#158991,#158992); +#158991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#158992 = VECTOR('',#158993,1.); +#158993 = DIRECTION('',(-1.,0.E+000)); +#158994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#158995 = PCURVE('',#158519,#158996); +#158996 = DEFINITIONAL_REPRESENTATION('',(#158997),#159000); +#158997 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158998,#158999), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156606 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#156607 = CARTESIAN_POINT('',(3.14159265359,0.35)); -#156608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156609 = ORIENTED_EDGE('',*,*,#156080,.F.); -#156610 = ORIENTED_EDGE('',*,*,#156566,.T.); -#156611 = ADVANCED_FACE('',(#156612),#156127,.T.); -#156612 = FACE_BOUND('',#156613,.T.); -#156613 = EDGE_LOOP('',(#156614,#156615,#156635,#156636)); -#156614 = ORIENTED_EDGE('',*,*,#156165,.T.); -#156615 = ORIENTED_EDGE('',*,*,#156616,.F.); -#156616 = EDGE_CURVE('',#155861,#156143,#156617,.T.); -#156617 = SURFACE_CURVE('',#156618,(#156622,#156628),.PCURVE_S1.); -#156618 = LINE('',#156619,#156620); -#156619 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.825)); -#156620 = VECTOR('',#156621,1.); -#156621 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156622 = PCURVE('',#156127,#156623); -#156623 = DEFINITIONAL_REPRESENTATION('',(#156624),#156627); -#156624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#156625,#156626), +#158998 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#158999 = CARTESIAN_POINT('',(3.14159265359,0.35)); +#159000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159001 = ORIENTED_EDGE('',*,*,#158472,.F.); +#159002 = ORIENTED_EDGE('',*,*,#158958,.T.); +#159003 = ADVANCED_FACE('',(#159004),#158519,.T.); +#159004 = FACE_BOUND('',#159005,.T.); +#159005 = EDGE_LOOP('',(#159006,#159007,#159027,#159028)); +#159006 = ORIENTED_EDGE('',*,*,#158557,.T.); +#159007 = ORIENTED_EDGE('',*,*,#159008,.F.); +#159008 = EDGE_CURVE('',#158253,#158535,#159009,.T.); +#159009 = SURFACE_CURVE('',#159010,(#159014,#159020),.PCURVE_S1.); +#159010 = LINE('',#159011,#159012); +#159011 = CARTESIAN_POINT('',(-0.674000000002,0.69933334,-0.825)); +#159012 = VECTOR('',#159013,1.); +#159013 = DIRECTION('',(0.E+000,0.E+000,1.)); +#159014 = PCURVE('',#158519,#159015); +#159015 = DEFINITIONAL_REPRESENTATION('',(#159016),#159019); +#159016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159017,#159018), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.35),.PIECEWISE_BEZIER_KNOTS.); -#156625 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); -#156626 = CARTESIAN_POINT('',(1.570796326795,0.35)); -#156627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156628 = PCURVE('',#151299,#156629); -#156629 = DEFINITIONAL_REPRESENTATION('',(#156630),#156634); -#156630 = LINE('',#156631,#156632); -#156631 = CARTESIAN_POINT('',(0.E+000,-0.100681667766)); -#156632 = VECTOR('',#156633,1.); -#156633 = DIRECTION('',(-1.,0.E+000)); -#156634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156635 = ORIENTED_EDGE('',*,*,#156108,.F.); -#156636 = ORIENTED_EDGE('',*,*,#156590,.T.); -#156637 = ADVANCED_FACE('',(#156638),#151299,.F.); -#156638 = FACE_BOUND('',#156639,.T.); -#156639 = EDGE_LOOP('',(#156640,#156641,#156642,#156643)); -#156640 = ORIENTED_EDGE('',*,*,#156142,.T.); -#156641 = ORIENTED_EDGE('',*,*,#151283,.F.); -#156642 = ORIENTED_EDGE('',*,*,#155860,.F.); -#156643 = ORIENTED_EDGE('',*,*,#156616,.T.); -#156644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#156648)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#156645,#156646,#156647)) +#159017 = CARTESIAN_POINT('',(1.570796326795,0.E+000)); +#159018 = CARTESIAN_POINT('',(1.570796326795,0.35)); +#159019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159020 = PCURVE('',#153691,#159021); +#159021 = DEFINITIONAL_REPRESENTATION('',(#159022),#159026); +#159022 = LINE('',#159023,#159024); +#159023 = CARTESIAN_POINT('',(0.E+000,-0.100681667766)); +#159024 = VECTOR('',#159025,1.); +#159025 = DIRECTION('',(-1.,0.E+000)); +#159026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159027 = ORIENTED_EDGE('',*,*,#158500,.F.); +#159028 = ORIENTED_EDGE('',*,*,#158982,.T.); +#159029 = ADVANCED_FACE('',(#159030),#153691,.F.); +#159030 = FACE_BOUND('',#159031,.T.); +#159031 = EDGE_LOOP('',(#159032,#159033,#159034,#159035)); +#159032 = ORIENTED_EDGE('',*,*,#158534,.T.); +#159033 = ORIENTED_EDGE('',*,*,#153675,.F.); +#159034 = ORIENTED_EDGE('',*,*,#158252,.F.); +#159035 = ORIENTED_EDGE('',*,*,#159008,.T.); +#159036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#159040)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#159037,#159038,#159039)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#156645 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#156646 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#156647 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#156648 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#156645, +#159037 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#159038 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#159039 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#159040 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#159037, 'distance_accuracy_value','confusion accuracy'); -#156649 = SHAPE_DEFINITION_REPRESENTATION(#156650,#151241); -#156650 = PRODUCT_DEFINITION_SHAPE('','',#156651); -#156651 = PRODUCT_DEFINITION('design','',#156652,#156655); -#156652 = PRODUCT_DEFINITION_FORMATION('','',#156653); -#156653 = PRODUCT('User_Library-SOT-323-5L','User_Library-SOT-323-5L','' - ,(#156654)); -#156654 = PRODUCT_CONTEXT('',#2,'mechanical'); -#156655 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#156656 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#156657,#156659); -#156657 = ( REPRESENTATION_RELATIONSHIP('','',#151241,#151231) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#156658) +#159041 = SHAPE_DEFINITION_REPRESENTATION(#159042,#153633); +#159042 = PRODUCT_DEFINITION_SHAPE('','',#159043); +#159043 = PRODUCT_DEFINITION('design','',#159044,#159047); +#159044 = PRODUCT_DEFINITION_FORMATION('','',#159045); +#159045 = PRODUCT('User_Library-SOT-323-5L','User_Library-SOT-323-5L','' + ,(#159046)); +#159046 = PRODUCT_CONTEXT('',#2,'mechanical'); +#159047 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#159048 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#159049,#159051); +#159049 = ( REPRESENTATION_RELATIONSHIP('','',#153633,#153623) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#159050) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#156658 = ITEM_DEFINED_TRANSFORMATION('','',#11,#151232); -#156659 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #156660); -#156660 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('269','=>[0:1:1:80]','',#151226 - ,#156651,$); -#156661 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#156653)); -#156662 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#156663,#156665); -#156663 = ( REPRESENTATION_RELATIONSHIP('','',#151231,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#156664) +#159050 = ITEM_DEFINED_TRANSFORMATION('','',#11,#153624); +#159051 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #159052); +#159052 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('370','=>[0:1:1:80]','',#153618 + ,#159043,$); +#159053 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#159045)); +#159054 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#159055,#159057); +#159055 = ( REPRESENTATION_RELATIONSHIP('','',#153623,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#159056) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#156664 = ITEM_DEFINED_TRANSFORMATION('','',#11,#227); -#156665 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #156666); -#156666 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('270','=>[0:1:1:79]','',#5, - #151226,$); -#156667 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#151228)); -#156668 = SHAPE_DEFINITION_REPRESENTATION(#156669,#156675); -#156669 = PRODUCT_DEFINITION_SHAPE('','',#156670); -#156670 = PRODUCT_DEFINITION('design','',#156671,#156674); -#156671 = PRODUCT_DEFINITION_FORMATION('','',#156672); -#156672 = PRODUCT('U9','U9','',(#156673)); -#156673 = PRODUCT_CONTEXT('',#2,'mechanical'); -#156674 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#156675 = SHAPE_REPRESENTATION('',(#11,#156676),#156680); -#156676 = AXIS2_PLACEMENT_3D('',#156677,#156678,#156679); -#156677 = CARTESIAN_POINT('',(10.03311176,5.5879111,1.27E-002)); -#156678 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); -#156679 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#156680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#156684)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#156681,#156682,#156683)) +#159056 = ITEM_DEFINED_TRANSFORMATION('','',#11,#227); +#159057 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #159058); +#159058 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('371','=>[0:1:1:79]','',#5, + #153618,$); +#159059 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#153620)); +#159060 = SHAPE_DEFINITION_REPRESENTATION(#159061,#159067); +#159061 = PRODUCT_DEFINITION_SHAPE('','',#159062); +#159062 = PRODUCT_DEFINITION('design','',#159063,#159066); +#159063 = PRODUCT_DEFINITION_FORMATION('','',#159064); +#159064 = PRODUCT('U9','U9','',(#159065)); +#159065 = PRODUCT_CONTEXT('',#2,'mechanical'); +#159066 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#159067 = SHAPE_REPRESENTATION('',(#11,#159068),#159072); +#159068 = AXIS2_PLACEMENT_3D('',#159069,#159070,#159071); +#159069 = CARTESIAN_POINT('',(10.03311176,5.5879111,1.27E-002)); +#159070 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); +#159071 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#159072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#159076)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#159073,#159074,#159075)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#156681 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#156682 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#156683 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#156684 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(2.E-007),#156681, +#159073 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#159074 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#159075 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#159076 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(2.E-007),#159073, 'distance_accuracy_value','confusion accuracy'); -#156685 = SHAPE_DEFINITION_REPRESENTATION(#156686,#156692); -#156686 = PRODUCT_DEFINITION_SHAPE('','',#156687); -#156687 = PRODUCT_DEFINITION('design','',#156688,#156691); -#156688 = PRODUCT_DEFINITION_FORMATION('','',#156689); -#156689 = PRODUCT('SOIC-8','SOIC-8','',(#156690)); -#156690 = PRODUCT_CONTEXT('',#2,'mechanical'); -#156691 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#156692 = SHAPE_REPRESENTATION('',(#11,#156693,#156697),#156701); -#156693 = AXIS2_PLACEMENT_3D('',#156694,#156695,#156696); -#156694 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#156695 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156696 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156697 = AXIS2_PLACEMENT_3D('',#156698,#156699,#156700); -#156698 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#156699 = DIRECTION('',(0.E+000,0.E+000,1.)); -#156700 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#156705)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#156702,#156703,#156704)) +#159077 = SHAPE_DEFINITION_REPRESENTATION(#159078,#159084); +#159078 = PRODUCT_DEFINITION_SHAPE('','',#159079); +#159079 = PRODUCT_DEFINITION('design','',#159080,#159083); +#159080 = PRODUCT_DEFINITION_FORMATION('','',#159081); +#159081 = PRODUCT('SOIC-8','SOIC-8','',(#159082)); +#159082 = PRODUCT_CONTEXT('',#2,'mechanical'); +#159083 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#159084 = SHAPE_REPRESENTATION('',(#11,#159085,#159089),#159093); +#159085 = AXIS2_PLACEMENT_3D('',#159086,#159087,#159088); +#159086 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#159087 = DIRECTION('',(0.E+000,0.E+000,1.)); +#159088 = DIRECTION('',(1.,0.E+000,0.E+000)); +#159089 = AXIS2_PLACEMENT_3D('',#159090,#159091,#159092); +#159090 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#159091 = DIRECTION('',(0.E+000,0.E+000,1.)); +#159092 = DIRECTION('',(1.,0.E+000,0.E+000)); +#159093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#159097)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#159094,#159095,#159096)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#156702 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#156703 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#156704 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#156705 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(2.E-007),#156702, +#159094 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#159095 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#159096 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#159097 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(2.E-007),#159094, 'distance_accuracy_value','confusion accuracy'); -#156706 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#156707),#158689); -#156707 = MANIFOLD_SOLID_BREP('',#156708); -#156708 = CLOSED_SHELL('',(#156709,#157001,#157092,#157146,#157262, - #157442,#157535,#157633,#157659,#157735,#157790,#157844,#157877, - #157953,#158007,#158061,#158093,#158168,#158221,#158274,#158305, - #158470,#158563,#158656,#158682)); -#156709 = ADVANCED_FACE('',(#156710),#156725,.F.); -#156710 = FACE_BOUND('',#156711,.F.); -#156711 = EDGE_LOOP('',(#156712,#156786,#156871,#156935)); -#156712 = ORIENTED_EDGE('',*,*,#156713,.T.); -#156713 = EDGE_CURVE('',#156714,#156716,#156718,.T.); -#156714 = VERTEX_POINT('',#156715); -#156715 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); -#156716 = VERTEX_POINT('',#156717); -#156717 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); -#156718 = SURFACE_CURVE('',#156719,(#156724,#156770),.PCURVE_S1.); -#156719 = CIRCLE('',#156720,0.325); -#156720 = AXIS2_PLACEMENT_3D('',#156721,#156722,#156723); -#156721 = CARTESIAN_POINT('',(-1.7,1.75,0.8)); -#156722 = DIRECTION('',(6.898853532133E-034,-1.,-1.437261152528E-033)); -#156723 = DIRECTION('',(6.672013369142E-016,-1.437261152528E-033,1.)); -#156724 = PCURVE('',#156725,#156742); -#156725 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#156726,#156727,#156728,#156729) - ,(#156730,#156731,#156732,#156733) - ,(#156734,#156735,#156736,#156737) - ,(#156738,#156739,#156740,#156741 +#159098 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#159099),#161081); +#159099 = MANIFOLD_SOLID_BREP('',#159100); +#159100 = CLOSED_SHELL('',(#159101,#159393,#159484,#159538,#159654, + #159834,#159927,#160025,#160051,#160127,#160182,#160236,#160269, + #160345,#160399,#160453,#160485,#160560,#160613,#160666,#160697, + #160862,#160955,#161048,#161074)); +#159101 = ADVANCED_FACE('',(#159102),#159117,.F.); +#159102 = FACE_BOUND('',#159103,.F.); +#159103 = EDGE_LOOP('',(#159104,#159178,#159263,#159327)); +#159104 = ORIENTED_EDGE('',*,*,#159105,.T.); +#159105 = EDGE_CURVE('',#159106,#159108,#159110,.T.); +#159106 = VERTEX_POINT('',#159107); +#159107 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); +#159108 = VERTEX_POINT('',#159109); +#159109 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); +#159110 = SURFACE_CURVE('',#159111,(#159116,#159162),.PCURVE_S1.); +#159111 = CIRCLE('',#159112,0.325); +#159112 = AXIS2_PLACEMENT_3D('',#159113,#159114,#159115); +#159113 = CARTESIAN_POINT('',(-1.7,1.75,0.8)); +#159114 = DIRECTION('',(6.898853532133E-034,-1.,-1.437261152528E-033)); +#159115 = DIRECTION('',(6.672013369142E-016,-1.437261152528E-033,1.)); +#159116 = PCURVE('',#159117,#159134); +#159117 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#159118,#159119,#159120,#159121) + ,(#159122,#159123,#159124,#159125) + ,(#159126,#159127,#159128,#159129) + ,(#159130,#159131,#159132,#159133 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -193298,27 +196300,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.268245951375,0.268245951375,0.804737854124) ,(1.,0.333333333333,0.333333333333,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#156726 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); -#156727 = CARTESIAN_POINT('',(-1.375,1.75,0.15)); -#156728 = CARTESIAN_POINT('',(-2.025,1.75,0.15)); -#156729 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); -#156730 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.8)); -#156731 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.15)); -#156732 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.15)); -#156733 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.8)); -#156734 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.8)); -#156735 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.232842712475)); -#156736 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.232842712475)); -#156737 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.8)); -#156738 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); -#156739 = CARTESIAN_POINT('',(-1.475,1.65,0.35)); -#156740 = CARTESIAN_POINT('',(-1.925,1.65,0.35)); -#156741 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); -#156742 = DEFINITIONAL_REPRESENTATION('',(#156743),#156769); -#156743 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156744,#156745,#156746, - #156747,#156748,#156749,#156750,#156751,#156752,#156753,#156754, - #156755,#156756,#156757,#156758,#156759,#156760,#156761,#156762, - #156763,#156764,#156765,#156766,#156767,#156768),.UNSPECIFIED.,.F., +#159118 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); +#159119 = CARTESIAN_POINT('',(-1.375,1.75,0.15)); +#159120 = CARTESIAN_POINT('',(-2.025,1.75,0.15)); +#159121 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); +#159122 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.8)); +#159123 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.15)); +#159124 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.15)); +#159125 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.8)); +#159126 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.8)); +#159127 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.232842712475)); +#159128 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.232842712475)); +#159129 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.8)); +#159130 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); +#159131 = CARTESIAN_POINT('',(-1.475,1.65,0.35)); +#159132 = CARTESIAN_POINT('',(-1.925,1.65,0.35)); +#159133 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); +#159134 = DEFINITIONAL_REPRESENTATION('',(#159135),#159161); +#159135 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159136,#159137,#159138, + #159139,#159140,#159141,#159142,#159143,#159144,#159145,#159146, + #159147,#159148,#159149,#159150,#159151,#159152,#159153,#159154, + #159155,#159156,#159157,#159158,#159159,#159160),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795, 1.713595992867,1.856395658939,1.999195325012,2.141994991084, 2.284794657156,2.427594323228,2.570393989301,2.713193655373, @@ -193326,74 +196328,74 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 3.427191985734,3.569991651807,3.712791317879,3.855590983951, 3.998390650023,4.141190316096,4.283989982168,4.42678964824, 4.569589314312,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#156744 = CARTESIAN_POINT('',(0.E+000,1.)); -#156745 = CARTESIAN_POINT('',(0.E+000,0.976252642514)); -#156746 = CARTESIAN_POINT('',(0.E+000,0.931948683956)); -#156747 = CARTESIAN_POINT('',(0.E+000,0.873315440011)); -#156748 = CARTESIAN_POINT('',(0.E+000,0.820561425866)); -#156749 = CARTESIAN_POINT('',(0.E+000,0.772421788032)); -#156750 = CARTESIAN_POINT('',(0.E+000,0.727875357125)); -#156751 = CARTESIAN_POINT('',(0.E+000,0.68613087718)); -#156752 = CARTESIAN_POINT('',(0.E+000,0.646543283156)); -#156753 = CARTESIAN_POINT('',(0.E+000,0.608575469012)); -#156754 = CARTESIAN_POINT('',(0.E+000,0.571764894481)); -#156755 = CARTESIAN_POINT('',(0.E+000,0.535699835049)); -#156756 = CARTESIAN_POINT('',(0.E+000,0.5)); -#156757 = CARTESIAN_POINT('',(0.E+000,0.464300164951)); -#156758 = CARTESIAN_POINT('',(0.E+000,0.428235105519)); -#156759 = CARTESIAN_POINT('',(0.E+000,0.391424530988)); -#156760 = CARTESIAN_POINT('',(0.E+000,0.353456716844)); -#156761 = CARTESIAN_POINT('',(0.E+000,0.31386912282)); -#156762 = CARTESIAN_POINT('',(0.E+000,0.272124642875)); -#156763 = CARTESIAN_POINT('',(0.E+000,0.227578211968)); -#156764 = CARTESIAN_POINT('',(0.E+000,0.179438574134)); -#156765 = CARTESIAN_POINT('',(0.E+000,0.126684559989)); -#156766 = CARTESIAN_POINT('',(0.E+000,6.805131604372E-002)); -#156767 = CARTESIAN_POINT('',(0.E+000,2.374735748557E-002)); -#156768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156770 = PCURVE('',#156771,#156776); -#156771 = PLANE('',#156772); -#156772 = AXIS2_PLACEMENT_3D('',#156773,#156774,#156775); -#156773 = CARTESIAN_POINT('',(2.733503659115E-017,1.75,0.E+000)); -#156774 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); -#156775 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); -#156776 = DEFINITIONAL_REPRESENTATION('',(#156777),#156785); -#156777 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#156778,#156779,#156780, - #156781,#156782,#156783,#156784),.UNSPECIFIED.,.T.,.F.) +#159136 = CARTESIAN_POINT('',(0.E+000,1.)); +#159137 = CARTESIAN_POINT('',(0.E+000,0.976252642514)); +#159138 = CARTESIAN_POINT('',(0.E+000,0.931948683956)); +#159139 = CARTESIAN_POINT('',(0.E+000,0.873315440011)); +#159140 = CARTESIAN_POINT('',(0.E+000,0.820561425866)); +#159141 = CARTESIAN_POINT('',(0.E+000,0.772421788032)); +#159142 = CARTESIAN_POINT('',(0.E+000,0.727875357125)); +#159143 = CARTESIAN_POINT('',(0.E+000,0.68613087718)); +#159144 = CARTESIAN_POINT('',(0.E+000,0.646543283156)); +#159145 = CARTESIAN_POINT('',(0.E+000,0.608575469012)); +#159146 = CARTESIAN_POINT('',(0.E+000,0.571764894481)); +#159147 = CARTESIAN_POINT('',(0.E+000,0.535699835049)); +#159148 = CARTESIAN_POINT('',(0.E+000,0.5)); +#159149 = CARTESIAN_POINT('',(0.E+000,0.464300164951)); +#159150 = CARTESIAN_POINT('',(0.E+000,0.428235105519)); +#159151 = CARTESIAN_POINT('',(0.E+000,0.391424530988)); +#159152 = CARTESIAN_POINT('',(0.E+000,0.353456716844)); +#159153 = CARTESIAN_POINT('',(0.E+000,0.31386912282)); +#159154 = CARTESIAN_POINT('',(0.E+000,0.272124642875)); +#159155 = CARTESIAN_POINT('',(0.E+000,0.227578211968)); +#159156 = CARTESIAN_POINT('',(0.E+000,0.179438574134)); +#159157 = CARTESIAN_POINT('',(0.E+000,0.126684559989)); +#159158 = CARTESIAN_POINT('',(0.E+000,6.805131604372E-002)); +#159159 = CARTESIAN_POINT('',(0.E+000,2.374735748557E-002)); +#159160 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#159161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159162 = PCURVE('',#159163,#159168); +#159163 = PLANE('',#159164); +#159164 = AXIS2_PLACEMENT_3D('',#159165,#159166,#159167); +#159165 = CARTESIAN_POINT('',(2.733503659115E-017,1.75,0.E+000)); +#159166 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); +#159167 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); +#159168 = DEFINITIONAL_REPRESENTATION('',(#159169),#159177); +#159169 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159170,#159171,#159172, + #159173,#159174,#159175,#159176),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#156778 = CARTESIAN_POINT('',(1.125,-1.7)); -#156779 = CARTESIAN_POINT('',(1.125,-2.26291651246)); -#156780 = CARTESIAN_POINT('',(0.6375,-1.98145825623)); -#156781 = CARTESIAN_POINT('',(0.15,-1.7)); -#156782 = CARTESIAN_POINT('',(0.6375,-1.41854174377)); -#156783 = CARTESIAN_POINT('',(1.125,-1.13708348754)); -#156784 = CARTESIAN_POINT('',(1.125,-1.7)); -#156785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156786 = ORIENTED_EDGE('',*,*,#156787,.T.); -#156787 = EDGE_CURVE('',#156716,#156788,#156790,.T.); -#156788 = VERTEX_POINT('',#156789); -#156789 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); -#156790 = SURFACE_CURVE('',#156791,(#156796,#156825),.PCURVE_S1.); -#156791 = CIRCLE('',#156792,0.1); -#156792 = AXIS2_PLACEMENT_3D('',#156793,#156794,#156795); -#156793 = CARTESIAN_POINT('',(-1.475,1.75,0.8)); -#156794 = DIRECTION('',(0.E+000,1.437261152528E-033,-1.)); -#156795 = DIRECTION('',(1.,0.E+000,0.E+000)); -#156796 = PCURVE('',#156725,#156797); -#156797 = DEFINITIONAL_REPRESENTATION('',(#156798),#156824); -#156798 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156799,#156800,#156801, - #156802,#156803,#156804,#156805,#156806,#156807,#156808,#156809, - #156810,#156811,#156812,#156813,#156814,#156815,#156816,#156817, - #156818,#156819,#156820,#156821,#156822,#156823),.UNSPECIFIED.,.F., +#159170 = CARTESIAN_POINT('',(1.125,-1.7)); +#159171 = CARTESIAN_POINT('',(1.125,-2.26291651246)); +#159172 = CARTESIAN_POINT('',(0.6375,-1.98145825623)); +#159173 = CARTESIAN_POINT('',(0.15,-1.7)); +#159174 = CARTESIAN_POINT('',(0.6375,-1.41854174377)); +#159175 = CARTESIAN_POINT('',(1.125,-1.13708348754)); +#159176 = CARTESIAN_POINT('',(1.125,-1.7)); +#159177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159178 = ORIENTED_EDGE('',*,*,#159179,.T.); +#159179 = EDGE_CURVE('',#159108,#159180,#159182,.T.); +#159180 = VERTEX_POINT('',#159181); +#159181 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); +#159182 = SURFACE_CURVE('',#159183,(#159188,#159217),.PCURVE_S1.); +#159183 = CIRCLE('',#159184,0.1); +#159184 = AXIS2_PLACEMENT_3D('',#159185,#159186,#159187); +#159185 = CARTESIAN_POINT('',(-1.475,1.75,0.8)); +#159186 = DIRECTION('',(0.E+000,1.437261152528E-033,-1.)); +#159187 = DIRECTION('',(1.,0.E+000,0.E+000)); +#159188 = PCURVE('',#159117,#159189); +#159189 = DEFINITIONAL_REPRESENTATION('',(#159190),#159216); +#159190 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159191,#159192,#159193, + #159194,#159195,#159196,#159197,#159198,#159199,#159200,#159201, + #159202,#159203,#159204,#159205,#159206,#159207,#159208,#159209, + #159210,#159211,#159212,#159213,#159214,#159215),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 7.139983303613E-002,0.142799666072,0.214199499108,0.285599332145, 0.356999165181,0.428398998217,0.499798831253,0.571198664289, @@ -193401,40 +196403,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.92819782947,0.999597662506,1.070997495542,1.142397328578, 1.213797161614,1.28519699465,1.356596827686,1.427996660723, 1.499396493759,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#156799 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156800 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#156801 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#156802 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#156803 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#156804 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#156805 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#156806 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#156807 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#156808 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#156809 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#156810 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#156811 = CARTESIAN_POINT('',(0.5,0.E+000)); -#156812 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#156813 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#156814 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#156815 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#156816 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#156817 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#156818 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#156819 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#156820 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#156821 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#156822 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#156823 = CARTESIAN_POINT('',(1.,0.E+000)); -#156824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156825 = PCURVE('',#156826,#156843); -#156826 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( - (#156827,#156828,#156829,#156830) - ,(#156831,#156832,#156833,#156834) - ,(#156835,#156836,#156837,#156838) - ,(#156839,#156840,#156841,#156842 +#159191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#159192 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#159193 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#159194 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#159195 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#159196 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#159197 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#159198 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#159199 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#159200 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#159201 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#159202 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#159203 = CARTESIAN_POINT('',(0.5,0.E+000)); +#159204 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#159205 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#159206 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#159207 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#159208 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#159209 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#159210 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#159211 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#159212 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#159213 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#159214 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#159215 = CARTESIAN_POINT('',(1.,0.E+000)); +#159216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159217 = PCURVE('',#159218,#159235); +#159218 = ( BOUNDED_SURFACE() B_SPLINE_SURFACE(3,3,( + (#159219,#159220,#159221,#159222) + ,(#159223,#159224,#159225,#159226) + ,(#159227,#159228,#159229,#159230) + ,(#159231,#159232,#159233,#159234 )),.UNSPECIFIED.,.F.,.F.,.F.) B_SPLINE_SURFACE_WITH_KNOTS((4,4),(4,4),( 0.E+000,1.),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.) GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( @@ -193443,27 +196445,27 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( ,(0.804737854124,0.268245951375,0.268245951375,0.804737854124) ,(1.,0.333333333333,0.333333333333,1. ))) REPRESENTATION_ITEM('') SURFACE() ); -#156827 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); -#156828 = CARTESIAN_POINT('',(-2.025,1.75,1.45)); -#156829 = CARTESIAN_POINT('',(-1.375,1.75,1.45)); -#156830 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); -#156831 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.8)); -#156832 = CARTESIAN_POINT('',(-2.025,1.691421356237,1.45)); -#156833 = CARTESIAN_POINT('',(-1.375,1.691421356237,1.45)); -#156834 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.8)); -#156835 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.8)); -#156836 = CARTESIAN_POINT('',(-1.983578643763,1.65,1.367157287525)); -#156837 = CARTESIAN_POINT('',(-1.416421356237,1.65,1.367157287525)); -#156838 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.8)); -#156839 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); -#156840 = CARTESIAN_POINT('',(-1.925,1.65,1.25)); -#156841 = CARTESIAN_POINT('',(-1.475,1.65,1.25)); -#156842 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); -#156843 = DEFINITIONAL_REPRESENTATION('',(#156844),#156870); -#156844 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156845,#156846,#156847, - #156848,#156849,#156850,#156851,#156852,#156853,#156854,#156855, - #156856,#156857,#156858,#156859,#156860,#156861,#156862,#156863, - #156864,#156865,#156866,#156867,#156868,#156869),.UNSPECIFIED.,.F., +#159219 = CARTESIAN_POINT('',(-2.025,1.75,0.8)); +#159220 = CARTESIAN_POINT('',(-2.025,1.75,1.45)); +#159221 = CARTESIAN_POINT('',(-1.375,1.75,1.45)); +#159222 = CARTESIAN_POINT('',(-1.375,1.75,0.8)); +#159223 = CARTESIAN_POINT('',(-2.025,1.691421356237,0.8)); +#159224 = CARTESIAN_POINT('',(-2.025,1.691421356237,1.45)); +#159225 = CARTESIAN_POINT('',(-1.375,1.691421356237,1.45)); +#159226 = CARTESIAN_POINT('',(-1.375,1.691421356237,0.8)); +#159227 = CARTESIAN_POINT('',(-1.983578643763,1.65,0.8)); +#159228 = CARTESIAN_POINT('',(-1.983578643763,1.65,1.367157287525)); +#159229 = CARTESIAN_POINT('',(-1.416421356237,1.65,1.367157287525)); +#159230 = CARTESIAN_POINT('',(-1.416421356237,1.65,0.8)); +#159231 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); +#159232 = CARTESIAN_POINT('',(-1.925,1.65,1.25)); +#159233 = CARTESIAN_POINT('',(-1.475,1.65,1.25)); +#159234 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); +#159235 = DEFINITIONAL_REPRESENTATION('',(#159236),#159262); +#159236 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159237,#159238,#159239, + #159240,#159241,#159242,#159243,#159244,#159245,#159246,#159247, + #159248,#159249,#159250,#159251,#159252,#159253,#159254,#159255, + #159256,#159257,#159258,#159259,#159260,#159261),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 7.139983303613E-002,0.142799666072,0.214199499108,0.285599332145, 0.356999165181,0.428398998217,0.499798831253,0.571198664289, @@ -193471,59 +196473,59 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_SURFACE(( 0.92819782947,0.999597662506,1.070997495542,1.142397328578, 1.213797161614,1.28519699465,1.356596827686,1.427996660723, 1.499396493759,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#156845 = CARTESIAN_POINT('',(0.E+000,1.)); -#156846 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#156847 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#156848 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#156849 = CARTESIAN_POINT('',(0.145724913075,1.)); -#156850 = CARTESIAN_POINT('',(0.192043637223,1.)); -#156851 = CARTESIAN_POINT('',(0.237526724423,1.)); -#156852 = CARTESIAN_POINT('',(0.282309422539,1.)); -#156853 = CARTESIAN_POINT('',(0.326519436214,1.)); -#156854 = CARTESIAN_POINT('',(0.370278310591,1.)); -#156855 = CARTESIAN_POINT('',(0.413702852292,1.)); -#156856 = CARTESIAN_POINT('',(0.456906394885,1.)); -#156857 = CARTESIAN_POINT('',(0.5,1.)); -#156858 = CARTESIAN_POINT('',(0.543093605115,1.)); -#156859 = CARTESIAN_POINT('',(0.586297147708,1.)); -#156860 = CARTESIAN_POINT('',(0.629721689409,1.)); -#156861 = CARTESIAN_POINT('',(0.673480563786,1.)); -#156862 = CARTESIAN_POINT('',(0.717690577461,1.)); -#156863 = CARTESIAN_POINT('',(0.762473275577,1.)); -#156864 = CARTESIAN_POINT('',(0.807956362777,1.)); -#156865 = CARTESIAN_POINT('',(0.854275086925,1.)); -#156866 = CARTESIAN_POINT('',(0.901574474096,1.)); -#156867 = CARTESIAN_POINT('',(0.950009297011,1.)); -#156868 = CARTESIAN_POINT('',(0.983172198663,1.)); -#156869 = CARTESIAN_POINT('',(1.,1.)); -#156870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156871 = ORIENTED_EDGE('',*,*,#156872,.T.); -#156872 = EDGE_CURVE('',#156788,#156873,#156875,.T.); -#156873 = VERTEX_POINT('',#156874); -#156874 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); -#156875 = SURFACE_CURVE('',#156876,(#156887,#156916),.PCURVE_S1.); -#156876 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156877,#156878,#156879, - #156880,#156881,#156882,#156883,#156884,#156885,#156886), +#159237 = CARTESIAN_POINT('',(0.E+000,1.)); +#159238 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#159239 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#159240 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#159241 = CARTESIAN_POINT('',(0.145724913075,1.)); +#159242 = CARTESIAN_POINT('',(0.192043637223,1.)); +#159243 = CARTESIAN_POINT('',(0.237526724423,1.)); +#159244 = CARTESIAN_POINT('',(0.282309422539,1.)); +#159245 = CARTESIAN_POINT('',(0.326519436214,1.)); +#159246 = CARTESIAN_POINT('',(0.370278310591,1.)); +#159247 = CARTESIAN_POINT('',(0.413702852292,1.)); +#159248 = CARTESIAN_POINT('',(0.456906394885,1.)); +#159249 = CARTESIAN_POINT('',(0.5,1.)); +#159250 = CARTESIAN_POINT('',(0.543093605115,1.)); +#159251 = CARTESIAN_POINT('',(0.586297147708,1.)); +#159252 = CARTESIAN_POINT('',(0.629721689409,1.)); +#159253 = CARTESIAN_POINT('',(0.673480563786,1.)); +#159254 = CARTESIAN_POINT('',(0.717690577461,1.)); +#159255 = CARTESIAN_POINT('',(0.762473275577,1.)); +#159256 = CARTESIAN_POINT('',(0.807956362777,1.)); +#159257 = CARTESIAN_POINT('',(0.854275086925,1.)); +#159258 = CARTESIAN_POINT('',(0.901574474096,1.)); +#159259 = CARTESIAN_POINT('',(0.950009297011,1.)); +#159260 = CARTESIAN_POINT('',(0.983172198663,1.)); +#159261 = CARTESIAN_POINT('',(1.,1.)); +#159262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159263 = ORIENTED_EDGE('',*,*,#159264,.T.); +#159264 = EDGE_CURVE('',#159180,#159265,#159267,.T.); +#159265 = VERTEX_POINT('',#159266); +#159266 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); +#159267 = SURFACE_CURVE('',#159268,(#159279,#159308),.PCURVE_S1.); +#159268 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159269,#159270,#159271, + #159272,#159273,#159274,#159275,#159276,#159277,#159278), .UNSPECIFIED.,.F.,.F.,(4,2,2,2,4),(0.E+000,0.125,0.25,0.375,0.5), .UNSPECIFIED.); -#156877 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); -#156878 = CARTESIAN_POINT('',(-1.475293578369,1.65,0.737783771773)); -#156879 = CARTESIAN_POINT('',(-1.497323504808,1.65,0.684687526197)); -#156880 = CARTESIAN_POINT('',(-1.584478443658,1.65,0.597114422269)); -#156881 = CARTESIAN_POINT('',(-1.638225204886,1.65,0.575145746883)); -#156882 = CARTESIAN_POINT('',(-1.761774795114,1.65,0.574854253117)); -#156883 = CARTESIAN_POINT('',(-1.815312473803,1.65,0.597323504808)); -#156884 = CARTESIAN_POINT('',(-1.902885577731,1.65,0.684478443658)); -#156885 = CARTESIAN_POINT('',(-1.924854253117,1.65,0.738225204886)); -#156886 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); -#156887 = PCURVE('',#156725,#156888); -#156888 = DEFINITIONAL_REPRESENTATION('',(#156889),#156915); -#156889 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156890,#156891,#156892, - #156893,#156894,#156895,#156896,#156897,#156898,#156899,#156900, - #156901,#156902,#156903,#156904,#156905,#156906,#156907,#156908, - #156909,#156910,#156911,#156912,#156913,#156914),.UNSPECIFIED.,.F., +#159269 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); +#159270 = CARTESIAN_POINT('',(-1.475293578369,1.65,0.737783771773)); +#159271 = CARTESIAN_POINT('',(-1.497323504808,1.65,0.684687526197)); +#159272 = CARTESIAN_POINT('',(-1.584478443658,1.65,0.597114422269)); +#159273 = CARTESIAN_POINT('',(-1.638225204886,1.65,0.575145746883)); +#159274 = CARTESIAN_POINT('',(-1.761774795114,1.65,0.574854253117)); +#159275 = CARTESIAN_POINT('',(-1.815312473803,1.65,0.597323504808)); +#159276 = CARTESIAN_POINT('',(-1.902885577731,1.65,0.684478443658)); +#159277 = CARTESIAN_POINT('',(-1.924854253117,1.65,0.738225204886)); +#159278 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); +#159279 = PCURVE('',#159117,#159280); +#159280 = DEFINITIONAL_REPRESENTATION('',(#159281),#159307); +#159281 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159282,#159283,#159284, + #159285,#159286,#159287,#159288,#159289,#159290,#159291,#159292, + #159293,#159294,#159295,#159296,#159297,#159298,#159299,#159300, + #159301,#159302,#159303,#159304,#159305,#159306),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 2.272727272727E-002,4.545454545455E-002,6.818181818182E-002, 9.090909090909E-002,0.113636363636,0.136363636364,0.159090909091, @@ -193531,72 +196533,72 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.295454545455,0.318181818182,0.340909090909,0.363636363636, 0.386363636364,0.409090909091,0.431818181818,0.454545454545, 0.477272727273,0.5),.QUASI_UNIFORM_KNOTS.); -#156890 = CARTESIAN_POINT('',(1.,0.E+000)); -#156891 = CARTESIAN_POINT('',(1.000207368824,2.502001636976E-002)); -#156892 = CARTESIAN_POINT('',(0.999364919946,7.043068548041E-002)); -#156893 = CARTESIAN_POINT('',(0.996750492632,0.128124947454)); -#156894 = CARTESIAN_POINT('',(0.996031422489,0.179283063054)); -#156895 = CARTESIAN_POINT('',(0.997565251137,0.226323266161)); -#156896 = CARTESIAN_POINT('',(1.000319498085,0.270985448075)); -#156897 = CARTESIAN_POINT('',(0.999703466885,0.314998118453)); -#156898 = CARTESIAN_POINT('',(0.996762769025,0.354525147402)); -#156899 = CARTESIAN_POINT('',(0.995339906537,0.391628103613)); -#156900 = CARTESIAN_POINT('',(0.996259056724,0.427473741296)); -#156901 = CARTESIAN_POINT('',(0.998942822373,0.4630654096)); -#156902 = CARTESIAN_POINT('',(1.000727887034,0.500007956506)); -#156903 = CARTESIAN_POINT('',(0.998145629491,0.536902764376)); -#156904 = CARTESIAN_POINT('',(0.995800907999,0.572437801804)); -#156905 = CARTESIAN_POINT('',(0.995520027312,0.60826722991)); -#156906 = CARTESIAN_POINT('',(0.997460259595,0.645404907802)); -#156907 = CARTESIAN_POINT('',(1.000336158947,0.685003012716)); -#156908 = CARTESIAN_POINT('',(0.999699204294,0.729010055999)); -#156909 = CARTESIAN_POINT('',(0.996763158527,0.77373217402)); -#156910 = CARTESIAN_POINT('',(0.995342611118,0.820895076465)); -#156911 = CARTESIAN_POINT('',(0.996247848897,0.872183814472)); -#156912 = CARTESIAN_POINT('',(0.998984949101,0.929916627287)); -#156913 = CARTESIAN_POINT('',(1.000042041667,0.975149705105)); -#156914 = CARTESIAN_POINT('',(1.,1.)); -#156915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156916 = PCURVE('',#156917,#156922); -#156917 = PLANE('',#156918); -#156918 = AXIS2_PLACEMENT_3D('',#156919,#156920,#156921); -#156919 = CARTESIAN_POINT('',(-1.7,1.65,0.8)); -#156920 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); -#156921 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); -#156922 = DEFINITIONAL_REPRESENTATION('',(#156923),#156934); -#156923 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156924,#156925,#156926, - #156927,#156928,#156929,#156930,#156931,#156932,#156933), +#159282 = CARTESIAN_POINT('',(1.,0.E+000)); +#159283 = CARTESIAN_POINT('',(1.000207368824,2.502001636976E-002)); +#159284 = CARTESIAN_POINT('',(0.999364919946,7.043068548041E-002)); +#159285 = CARTESIAN_POINT('',(0.996750492632,0.128124947454)); +#159286 = CARTESIAN_POINT('',(0.996031422489,0.179283063054)); +#159287 = CARTESIAN_POINT('',(0.997565251137,0.226323266161)); +#159288 = CARTESIAN_POINT('',(1.000319498085,0.270985448075)); +#159289 = CARTESIAN_POINT('',(0.999703466885,0.314998118453)); +#159290 = CARTESIAN_POINT('',(0.996762769025,0.354525147402)); +#159291 = CARTESIAN_POINT('',(0.995339906537,0.391628103613)); +#159292 = CARTESIAN_POINT('',(0.996259056724,0.427473741296)); +#159293 = CARTESIAN_POINT('',(0.998942822373,0.4630654096)); +#159294 = CARTESIAN_POINT('',(1.000727887034,0.500007956506)); +#159295 = CARTESIAN_POINT('',(0.998145629491,0.536902764376)); +#159296 = CARTESIAN_POINT('',(0.995800907999,0.572437801804)); +#159297 = CARTESIAN_POINT('',(0.995520027312,0.60826722991)); +#159298 = CARTESIAN_POINT('',(0.997460259595,0.645404907802)); +#159299 = CARTESIAN_POINT('',(1.000336158947,0.685003012716)); +#159300 = CARTESIAN_POINT('',(0.999699204294,0.729010055999)); +#159301 = CARTESIAN_POINT('',(0.996763158527,0.77373217402)); +#159302 = CARTESIAN_POINT('',(0.995342611118,0.820895076465)); +#159303 = CARTESIAN_POINT('',(0.996247848897,0.872183814472)); +#159304 = CARTESIAN_POINT('',(0.998984949101,0.929916627287)); +#159305 = CARTESIAN_POINT('',(1.000042041667,0.975149705105)); +#159306 = CARTESIAN_POINT('',(1.,1.)); +#159307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159308 = PCURVE('',#159309,#159314); +#159309 = PLANE('',#159310); +#159310 = AXIS2_PLACEMENT_3D('',#159311,#159312,#159313); +#159311 = CARTESIAN_POINT('',(-1.7,1.65,0.8)); +#159312 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); +#159313 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); +#159314 = DEFINITIONAL_REPRESENTATION('',(#159315),#159326); +#159315 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159316,#159317,#159318, + #159319,#159320,#159321,#159322,#159323,#159324,#159325), .UNSPECIFIED.,.F.,.F.,(4,2,2,2,4),(0.E+000,0.125,0.25,0.375,0.5), .UNSPECIFIED.); -#156924 = CARTESIAN_POINT('',(0.E+000,0.225)); -#156925 = CARTESIAN_POINT('',(-6.221622822663E-002,0.224706421631)); -#156926 = CARTESIAN_POINT('',(-0.115312473803,0.202676495192)); -#156927 = CARTESIAN_POINT('',(-0.202885577731,0.115521556342)); -#156928 = CARTESIAN_POINT('',(-0.224854253117,6.177479511431E-002)); -#156929 = CARTESIAN_POINT('',(-0.225145746883,-6.177479511431E-002)); -#156930 = CARTESIAN_POINT('',(-0.202676495192,-0.115312473803)); -#156931 = CARTESIAN_POINT('',(-0.115521556342,-0.202885577731)); -#156932 = CARTESIAN_POINT('',(-6.177479511434E-002,-0.224854253117)); -#156933 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#156934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156935 = ORIENTED_EDGE('',*,*,#156936,.F.); -#156936 = EDGE_CURVE('',#156714,#156873,#156937,.T.); -#156937 = SURFACE_CURVE('',#156938,(#156943,#156972),.PCURVE_S1.); -#156938 = CIRCLE('',#156939,1.E-001); -#156939 = AXIS2_PLACEMENT_3D('',#156940,#156941,#156942); -#156940 = CARTESIAN_POINT('',(-1.925,1.75,0.8)); -#156941 = DIRECTION('',(-1.224646799147E-016,-1.437261152528E-033,1.)); -#156942 = DIRECTION('',(-1.,1.760137269982E-049,-1.224646799147E-016)); -#156943 = PCURVE('',#156725,#156944); -#156944 = DEFINITIONAL_REPRESENTATION('',(#156945),#156971); -#156945 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156946,#156947,#156948, - #156949,#156950,#156951,#156952,#156953,#156954,#156955,#156956, - #156957,#156958,#156959,#156960,#156961,#156962,#156963,#156964, - #156965,#156966,#156967,#156968,#156969,#156970),.UNSPECIFIED.,.F., +#159316 = CARTESIAN_POINT('',(0.E+000,0.225)); +#159317 = CARTESIAN_POINT('',(-6.221622822663E-002,0.224706421631)); +#159318 = CARTESIAN_POINT('',(-0.115312473803,0.202676495192)); +#159319 = CARTESIAN_POINT('',(-0.202885577731,0.115521556342)); +#159320 = CARTESIAN_POINT('',(-0.224854253117,6.177479511431E-002)); +#159321 = CARTESIAN_POINT('',(-0.225145746883,-6.177479511431E-002)); +#159322 = CARTESIAN_POINT('',(-0.202676495192,-0.115312473803)); +#159323 = CARTESIAN_POINT('',(-0.115521556342,-0.202885577731)); +#159324 = CARTESIAN_POINT('',(-6.177479511434E-002,-0.224854253117)); +#159325 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#159326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159327 = ORIENTED_EDGE('',*,*,#159328,.F.); +#159328 = EDGE_CURVE('',#159106,#159265,#159329,.T.); +#159329 = SURFACE_CURVE('',#159330,(#159335,#159364),.PCURVE_S1.); +#159330 = CIRCLE('',#159331,1.E-001); +#159331 = AXIS2_PLACEMENT_3D('',#159332,#159333,#159334); +#159332 = CARTESIAN_POINT('',(-1.925,1.75,0.8)); +#159333 = DIRECTION('',(-1.224646799147E-016,-1.437261152528E-033,1.)); +#159334 = DIRECTION('',(-1.,1.760137269982E-049,-1.224646799147E-016)); +#159335 = PCURVE('',#159117,#159336); +#159336 = DEFINITIONAL_REPRESENTATION('',(#159337),#159363); +#159337 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159338,#159339,#159340, + #159341,#159342,#159343,#159344,#159345,#159346,#159347,#159348, + #159349,#159350,#159351,#159352,#159353,#159354,#159355,#159356, + #159357,#159358,#159359,#159360,#159361,#159362),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 7.139983303613E-002,0.142799666072,0.214199499108,0.285599332145, 0.356999165181,0.428398998217,0.499798831253,0.571198664289, @@ -193604,40 +196606,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.92819782947,0.999597662506,1.070997495542,1.142397328578, 1.213797161614,1.28519699465,1.356596827687,1.427996660723, 1.499396493759,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#156946 = CARTESIAN_POINT('',(0.E+000,1.)); -#156947 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); -#156948 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); -#156949 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); -#156950 = CARTESIAN_POINT('',(0.145724913075,1.)); -#156951 = CARTESIAN_POINT('',(0.192043637223,1.)); -#156952 = CARTESIAN_POINT('',(0.237526724423,1.)); -#156953 = CARTESIAN_POINT('',(0.282309422539,1.)); -#156954 = CARTESIAN_POINT('',(0.326519436214,1.)); -#156955 = CARTESIAN_POINT('',(0.370278310591,1.)); -#156956 = CARTESIAN_POINT('',(0.413702852292,1.)); -#156957 = CARTESIAN_POINT('',(0.456906394885,1.)); -#156958 = CARTESIAN_POINT('',(0.5,1.)); -#156959 = CARTESIAN_POINT('',(0.543093605115,1.)); -#156960 = CARTESIAN_POINT('',(0.586297147708,1.)); -#156961 = CARTESIAN_POINT('',(0.629721689409,1.)); -#156962 = CARTESIAN_POINT('',(0.673480563786,1.)); -#156963 = CARTESIAN_POINT('',(0.717690577461,1.)); -#156964 = CARTESIAN_POINT('',(0.762473275577,1.)); -#156965 = CARTESIAN_POINT('',(0.807956362777,1.)); -#156966 = CARTESIAN_POINT('',(0.854275086925,1.)); -#156967 = CARTESIAN_POINT('',(0.901574474096,1.)); -#156968 = CARTESIAN_POINT('',(0.950009297011,1.)); -#156969 = CARTESIAN_POINT('',(0.983172198663,1.)); -#156970 = CARTESIAN_POINT('',(1.,1.)); -#156971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#156972 = PCURVE('',#156826,#156973); -#156973 = DEFINITIONAL_REPRESENTATION('',(#156974),#157000); -#156974 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#156975,#156976,#156977, - #156978,#156979,#156980,#156981,#156982,#156983,#156984,#156985, - #156986,#156987,#156988,#156989,#156990,#156991,#156992,#156993, - #156994,#156995,#156996,#156997,#156998,#156999),.UNSPECIFIED.,.F., +#159338 = CARTESIAN_POINT('',(0.E+000,1.)); +#159339 = CARTESIAN_POINT('',(1.682780133706E-002,1.)); +#159340 = CARTESIAN_POINT('',(4.999070298881E-002,1.)); +#159341 = CARTESIAN_POINT('',(9.842552590405E-002,1.)); +#159342 = CARTESIAN_POINT('',(0.145724913075,1.)); +#159343 = CARTESIAN_POINT('',(0.192043637223,1.)); +#159344 = CARTESIAN_POINT('',(0.237526724423,1.)); +#159345 = CARTESIAN_POINT('',(0.282309422539,1.)); +#159346 = CARTESIAN_POINT('',(0.326519436214,1.)); +#159347 = CARTESIAN_POINT('',(0.370278310591,1.)); +#159348 = CARTESIAN_POINT('',(0.413702852292,1.)); +#159349 = CARTESIAN_POINT('',(0.456906394885,1.)); +#159350 = CARTESIAN_POINT('',(0.5,1.)); +#159351 = CARTESIAN_POINT('',(0.543093605115,1.)); +#159352 = CARTESIAN_POINT('',(0.586297147708,1.)); +#159353 = CARTESIAN_POINT('',(0.629721689409,1.)); +#159354 = CARTESIAN_POINT('',(0.673480563786,1.)); +#159355 = CARTESIAN_POINT('',(0.717690577461,1.)); +#159356 = CARTESIAN_POINT('',(0.762473275577,1.)); +#159357 = CARTESIAN_POINT('',(0.807956362777,1.)); +#159358 = CARTESIAN_POINT('',(0.854275086925,1.)); +#159359 = CARTESIAN_POINT('',(0.901574474096,1.)); +#159360 = CARTESIAN_POINT('',(0.950009297011,1.)); +#159361 = CARTESIAN_POINT('',(0.983172198663,1.)); +#159362 = CARTESIAN_POINT('',(1.,1.)); +#159363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159364 = PCURVE('',#159218,#159365); +#159365 = DEFINITIONAL_REPRESENTATION('',(#159366),#159392); +#159366 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159367,#159368,#159369, + #159370,#159371,#159372,#159373,#159374,#159375,#159376,#159377, + #159378,#159379,#159380,#159381,#159382,#159383,#159384,#159385, + #159386,#159387,#159388,#159389,#159390,#159391),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 7.139983303613E-002,0.142799666072,0.214199499108,0.285599332145, 0.356999165181,0.428398998217,0.499798831253,0.571198664289, @@ -193645,91 +196647,91 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.92819782947,0.999597662506,1.070997495542,1.142397328578, 1.213797161614,1.28519699465,1.356596827687,1.427996660723, 1.499396493759,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#156975 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#156976 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); -#156977 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); -#156978 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); -#156979 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); -#156980 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); -#156981 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); -#156982 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); -#156983 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); -#156984 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); -#156985 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); -#156986 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); -#156987 = CARTESIAN_POINT('',(0.5,0.E+000)); -#156988 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); -#156989 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); -#156990 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); -#156991 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); -#156992 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); -#156993 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); -#156994 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); -#156995 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); -#156996 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); -#156997 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); -#156998 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); -#156999 = CARTESIAN_POINT('',(1.,0.E+000)); -#157000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157001 = ADVANCED_FACE('',(#157002),#156917,.T.); -#157002 = FACE_BOUND('',#157003,.T.); -#157003 = EDGE_LOOP('',(#157004,#157005)); -#157004 = ORIENTED_EDGE('',*,*,#156872,.T.); -#157005 = ORIENTED_EDGE('',*,*,#157006,.T.); -#157006 = EDGE_CURVE('',#156873,#156788,#157007,.T.); -#157007 = SURFACE_CURVE('',#157008,(#157023,#157041),.PCURVE_S1.); -#157008 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157009,#157010,#157011, - #157012,#157013,#157014,#157015,#157016,#157017,#157018,#157019, - #157020,#157021,#157022),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,4),(0.5, +#159367 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#159368 = CARTESIAN_POINT('',(1.682780133706E-002,0.E+000)); +#159369 = CARTESIAN_POINT('',(4.999070298881E-002,0.E+000)); +#159370 = CARTESIAN_POINT('',(9.842552590405E-002,0.E+000)); +#159371 = CARTESIAN_POINT('',(0.145724913075,0.E+000)); +#159372 = CARTESIAN_POINT('',(0.192043637223,0.E+000)); +#159373 = CARTESIAN_POINT('',(0.237526724423,0.E+000)); +#159374 = CARTESIAN_POINT('',(0.282309422539,0.E+000)); +#159375 = CARTESIAN_POINT('',(0.326519436214,0.E+000)); +#159376 = CARTESIAN_POINT('',(0.370278310591,0.E+000)); +#159377 = CARTESIAN_POINT('',(0.413702852292,0.E+000)); +#159378 = CARTESIAN_POINT('',(0.456906394885,0.E+000)); +#159379 = CARTESIAN_POINT('',(0.5,0.E+000)); +#159380 = CARTESIAN_POINT('',(0.543093605115,0.E+000)); +#159381 = CARTESIAN_POINT('',(0.586297147708,0.E+000)); +#159382 = CARTESIAN_POINT('',(0.629721689409,0.E+000)); +#159383 = CARTESIAN_POINT('',(0.673480563786,0.E+000)); +#159384 = CARTESIAN_POINT('',(0.717690577461,0.E+000)); +#159385 = CARTESIAN_POINT('',(0.762473275577,0.E+000)); +#159386 = CARTESIAN_POINT('',(0.807956362777,0.E+000)); +#159387 = CARTESIAN_POINT('',(0.854275086925,0.E+000)); +#159388 = CARTESIAN_POINT('',(0.901574474096,0.E+000)); +#159389 = CARTESIAN_POINT('',(0.950009297011,0.E+000)); +#159390 = CARTESIAN_POINT('',(0.983172198663,0.E+000)); +#159391 = CARTESIAN_POINT('',(1.,0.E+000)); +#159392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159393 = ADVANCED_FACE('',(#159394),#159309,.T.); +#159394 = FACE_BOUND('',#159395,.T.); +#159395 = EDGE_LOOP('',(#159396,#159397)); +#159396 = ORIENTED_EDGE('',*,*,#159264,.T.); +#159397 = ORIENTED_EDGE('',*,*,#159398,.T.); +#159398 = EDGE_CURVE('',#159265,#159180,#159399,.T.); +#159399 = SURFACE_CURVE('',#159400,(#159415,#159433),.PCURVE_S1.); +#159400 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159401,#159402,#159403, + #159404,#159405,#159406,#159407,#159408,#159409,#159410,#159411, + #159412,#159413,#159414),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,4),(0.5, 0.625,0.75,0.875,0.90625,0.9375,1.),.UNSPECIFIED.); -#157009 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); -#157010 = CARTESIAN_POINT('',(-1.925145746883,1.65,0.861774795114)); -#157011 = CARTESIAN_POINT('',(-1.902676495192,1.65,0.915312473803)); -#157012 = CARTESIAN_POINT('',(-1.815521556342,1.65,1.002885577731)); -#157013 = CARTESIAN_POINT('',(-1.761774795114,1.65,1.024854253117)); -#157014 = CARTESIAN_POINT('',(-1.638225204886,1.65,1.025145746883)); -#157015 = CARTESIAN_POINT('',(-1.584441870712,1.65,1.002432012722)); -#157016 = CARTESIAN_POINT('',(-1.530015750113,1.65,0.948265779028)); -#157017 = CARTESIAN_POINT('',(-1.520397859556,1.65,0.936492679316)); -#157018 = CARTESIAN_POINT('',(-1.503696745565,1.65,0.911066773944)); -#157019 = CARTESIAN_POINT('',(-1.496130637837,1.65,0.896202362523)); -#157020 = CARTESIAN_POINT('',(-1.480131621109,1.65,0.856059203908)); -#157021 = CARTESIAN_POINT('',(-1.474865743689,1.65,0.828452100691)); -#157022 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); -#157023 = PCURVE('',#156917,#157024); -#157024 = DEFINITIONAL_REPRESENTATION('',(#157025),#157040); -#157025 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157026,#157027,#157028, - #157029,#157030,#157031,#157032,#157033,#157034,#157035,#157036, - #157037,#157038,#157039),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,4),(0.5, +#159401 = CARTESIAN_POINT('',(-1.925,1.65,0.8)); +#159402 = CARTESIAN_POINT('',(-1.925145746883,1.65,0.861774795114)); +#159403 = CARTESIAN_POINT('',(-1.902676495192,1.65,0.915312473803)); +#159404 = CARTESIAN_POINT('',(-1.815521556342,1.65,1.002885577731)); +#159405 = CARTESIAN_POINT('',(-1.761774795114,1.65,1.024854253117)); +#159406 = CARTESIAN_POINT('',(-1.638225204886,1.65,1.025145746883)); +#159407 = CARTESIAN_POINT('',(-1.584441870712,1.65,1.002432012722)); +#159408 = CARTESIAN_POINT('',(-1.530015750113,1.65,0.948265779028)); +#159409 = CARTESIAN_POINT('',(-1.520397859556,1.65,0.936492679316)); +#159410 = CARTESIAN_POINT('',(-1.503696745565,1.65,0.911066773944)); +#159411 = CARTESIAN_POINT('',(-1.496130637837,1.65,0.896202362523)); +#159412 = CARTESIAN_POINT('',(-1.480131621109,1.65,0.856059203908)); +#159413 = CARTESIAN_POINT('',(-1.474865743689,1.65,0.828452100691)); +#159414 = CARTESIAN_POINT('',(-1.475,1.65,0.8)); +#159415 = PCURVE('',#159309,#159416); +#159416 = DEFINITIONAL_REPRESENTATION('',(#159417),#159432); +#159417 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159418,#159419,#159420, + #159421,#159422,#159423,#159424,#159425,#159426,#159427,#159428, + #159429,#159430,#159431),.UNSPECIFIED.,.F.,.F.,(4,2,2,2,2,2,4),(0.5, 0.625,0.75,0.875,0.90625,0.9375,1.),.UNSPECIFIED.); -#157026 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#157027 = CARTESIAN_POINT('',(6.177479511434E-002,-0.225145746883)); -#157028 = CARTESIAN_POINT('',(0.115312473803,-0.202676495192)); -#157029 = CARTESIAN_POINT('',(0.202885577731,-0.115521556342)); -#157030 = CARTESIAN_POINT('',(0.224854253117,-6.177479511434E-002)); -#157031 = CARTESIAN_POINT('',(0.225145746883,6.177479511434E-002)); -#157032 = CARTESIAN_POINT('',(0.202432012722,0.115558129288)); -#157033 = CARTESIAN_POINT('',(0.148265779028,0.169984249887)); -#157034 = CARTESIAN_POINT('',(0.136492679316,0.179602140444)); -#157035 = CARTESIAN_POINT('',(0.111066773944,0.196303254435)); -#157036 = CARTESIAN_POINT('',(9.620236252317E-002,0.203869362163)); -#157037 = CARTESIAN_POINT('',(5.605920390792E-002,0.219868378891)); -#157038 = CARTESIAN_POINT('',(2.845210069078E-002,0.225134256311)); -#157039 = CARTESIAN_POINT('',(0.E+000,0.225)); -#157040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157041 = PCURVE('',#156826,#157042); -#157042 = DEFINITIONAL_REPRESENTATION('',(#157043),#157091); -#157043 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157044,#157045,#157046, - #157047,#157048,#157049,#157050,#157051,#157052,#157053,#157054, - #157055,#157056,#157057,#157058,#157059,#157060,#157061,#157062, - #157063,#157064,#157065,#157066,#157067,#157068,#157069,#157070, - #157071,#157072,#157073,#157074,#157075,#157076,#157077,#157078, - #157079,#157080,#157081,#157082,#157083,#157084,#157085,#157086, - #157087,#157088,#157089,#157090),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1, +#159418 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#159419 = CARTESIAN_POINT('',(6.177479511434E-002,-0.225145746883)); +#159420 = CARTESIAN_POINT('',(0.115312473803,-0.202676495192)); +#159421 = CARTESIAN_POINT('',(0.202885577731,-0.115521556342)); +#159422 = CARTESIAN_POINT('',(0.224854253117,-6.177479511434E-002)); +#159423 = CARTESIAN_POINT('',(0.225145746883,6.177479511434E-002)); +#159424 = CARTESIAN_POINT('',(0.202432012722,0.115558129288)); +#159425 = CARTESIAN_POINT('',(0.148265779028,0.169984249887)); +#159426 = CARTESIAN_POINT('',(0.136492679316,0.179602140444)); +#159427 = CARTESIAN_POINT('',(0.111066773944,0.196303254435)); +#159428 = CARTESIAN_POINT('',(9.620236252317E-002,0.203869362163)); +#159429 = CARTESIAN_POINT('',(5.605920390792E-002,0.219868378891)); +#159430 = CARTESIAN_POINT('',(2.845210069078E-002,0.225134256311)); +#159431 = CARTESIAN_POINT('',(0.E+000,0.225)); +#159432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159433 = PCURVE('',#159218,#159434); +#159434 = DEFINITIONAL_REPRESENTATION('',(#159435),#159483); +#159435 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159436,#159437,#159438, + #159439,#159440,#159441,#159442,#159443,#159444,#159445,#159446, + #159447,#159448,#159449,#159450,#159451,#159452,#159453,#159454, + #159455,#159456,#159457,#159458,#159459,#159460,#159461,#159462, + #159463,#159464,#159465,#159466,#159467,#159468,#159469,#159470, + #159471,#159472,#159473,#159474,#159475,#159476,#159477,#159478, + #159479,#159480,#159481,#159482),.UNSPECIFIED.,.F.,.F.,(4,1,1,1,1,1, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,4),(0.5,0.511363636364,0.522727272727,0.534090909091, 0.545454545455,0.556818181818,0.568181818182,0.579545454545, @@ -193742,76 +196744,76 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.897727272727,0.909090909091,0.920454545455,0.931818181818, 0.943181818182,0.954545454545,0.965909090909,0.977272727273, 0.988636363636,1.),.QUASI_UNIFORM_KNOTS.); -#157044 = CARTESIAN_POINT('',(1.,0.E+000)); -#157045 = CARTESIAN_POINT('',(0.999896349723,1.24701123946E-002)); -#157046 = CARTESIAN_POINT('',(0.999396586177,3.620632975718E-002)); -#157047 = CARTESIAN_POINT('',(0.998185138844,6.875079066305E-002)); -#157048 = CARTESIAN_POINT('',(0.996974171448,9.88270288121E-002)); -#157049 = CARTESIAN_POINT('',(0.996062533492,0.126888488248)); -#157050 = CARTESIAN_POINT('',(0.995644983385,0.153324133957)); -#157051 = CARTESIAN_POINT('',(0.99580007431,0.178458279629)); -#157052 = CARTESIAN_POINT('',(0.99649599622,0.2025672909)); -#157053 = CARTESIAN_POINT('',(0.997591999648,0.225881603859)); -#157054 = CARTESIAN_POINT('',(0.998833229826,0.248612985706)); -#157055 = CARTESIAN_POINT('',(0.999871028538,0.270882134449)); -#157056 = CARTESIAN_POINT('',(1.0001867557,0.293008725647)); -#157057 = CARTESIAN_POINT('',(0.99938194866,0.314442275844)); -#157058 = CARTESIAN_POINT('',(0.99818158431,0.334725240266)); -#157059 = CARTESIAN_POINT('',(0.996964952481,0.354229154568)); -#157060 = CARTESIAN_POINT('',(0.99605305529,0.373084953135)); -#157061 = CARTESIAN_POINT('',(0.995634639382,0.391471546073)); -#157062 = CARTESIAN_POINT('',(0.99578983908,0.409540165723)); -#157063 = CARTESIAN_POINT('',(0.996486334236,0.427437673934)); -#157064 = CARTESIAN_POINT('',(0.997583779781,0.445297616935)); -#157065 = CARTESIAN_POINT('',(0.998826319641,0.463259900197)); -#157066 = CARTESIAN_POINT('',(0.999869174903,0.481406118477)); -#157067 = CARTESIAN_POINT('',(1.000179643218,0.500000906502)); -#157068 = CARTESIAN_POINT('',(0.999412252224,0.518590255514)); -#157069 = CARTESIAN_POINT('',(0.998304758515,0.536730890316)); -#157070 = CARTESIAN_POINT('',(0.997188482095,0.554694411519)); -#157071 = CARTESIAN_POINT('',(0.996361668749,0.572565964233)); -#157072 = CARTESIAN_POINT('',(0.995993211047,0.59048580884)); -#157073 = CARTESIAN_POINT('',(0.996153127512,0.60858490815)); -#157074 = CARTESIAN_POINT('',(0.996806528451,0.627004173087)); -#157075 = CARTESIAN_POINT('',(0.997823040403,0.645886994834)); -#157076 = CARTESIAN_POINT('',(0.998955310087,0.665396236537)); -#157077 = CARTESIAN_POINT('',(0.999921125769,0.685660690895)); -#157078 = CARTESIAN_POINT('',(1.000100945844,0.706979101639)); -#157079 = CARTESIAN_POINT('',(0.999675090853,0.72906358967)); -#157080 = CARTESIAN_POINT('',(0.999560605215,0.75173018814)); -#157081 = CARTESIAN_POINT('',(0.999668068186,0.775073964241)); -#157082 = CARTESIAN_POINT('',(1.000105996611,0.800528055436)); -#157083 = CARTESIAN_POINT('',(1.000029370934,0.827065114291)); -#157084 = CARTESIAN_POINT('',(0.999897945216,0.852516791708)); -#157085 = CARTESIAN_POINT('',(0.999444903797,0.878948252316)); -#157086 = CARTESIAN_POINT('',(0.999187342355,0.90652820184)); -#157087 = CARTESIAN_POINT('',(0.9991853042,0.935574672207)); -#157088 = CARTESIAN_POINT('',(0.999491359909,0.966430706084)); -#157089 = CARTESIAN_POINT('',(0.999818160903,0.988511502173)); -#157090 = CARTESIAN_POINT('',(1.,1.)); -#157091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157092 = ADVANCED_FACE('',(#157093),#156826,.F.); -#157093 = FACE_BOUND('',#157094,.F.); -#157094 = EDGE_LOOP('',(#157095,#157096,#157097,#157098)); -#157095 = ORIENTED_EDGE('',*,*,#156936,.T.); -#157096 = ORIENTED_EDGE('',*,*,#157006,.T.); -#157097 = ORIENTED_EDGE('',*,*,#156787,.F.); -#157098 = ORIENTED_EDGE('',*,*,#157099,.T.); -#157099 = EDGE_CURVE('',#156716,#156714,#157100,.T.); -#157100 = SURFACE_CURVE('',#157101,(#157106,#157135),.PCURVE_S1.); -#157101 = CIRCLE('',#157102,0.325); -#157102 = AXIS2_PLACEMENT_3D('',#157103,#157104,#157105); -#157103 = CARTESIAN_POINT('',(-1.7,1.75,0.8)); -#157104 = DIRECTION('',(6.898853532133E-034,-1.,-1.437261152528E-033)); -#157105 = DIRECTION('',(9.915454178714E-067,-1.437261152528E-033,1.)); -#157106 = PCURVE('',#156826,#157107); -#157107 = DEFINITIONAL_REPRESENTATION('',(#157108),#157134); -#157108 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157109,#157110,#157111, - #157112,#157113,#157114,#157115,#157116,#157117,#157118,#157119, - #157120,#157121,#157122,#157123,#157124,#157125,#157126,#157127, - #157128,#157129,#157130,#157131,#157132,#157133),.UNSPECIFIED.,.F., +#159436 = CARTESIAN_POINT('',(1.,0.E+000)); +#159437 = CARTESIAN_POINT('',(0.999896349723,1.24701123946E-002)); +#159438 = CARTESIAN_POINT('',(0.999396586177,3.620632975718E-002)); +#159439 = CARTESIAN_POINT('',(0.998185138844,6.875079066305E-002)); +#159440 = CARTESIAN_POINT('',(0.996974171448,9.88270288121E-002)); +#159441 = CARTESIAN_POINT('',(0.996062533492,0.126888488248)); +#159442 = CARTESIAN_POINT('',(0.995644983385,0.153324133957)); +#159443 = CARTESIAN_POINT('',(0.99580007431,0.178458279629)); +#159444 = CARTESIAN_POINT('',(0.99649599622,0.2025672909)); +#159445 = CARTESIAN_POINT('',(0.997591999648,0.225881603859)); +#159446 = CARTESIAN_POINT('',(0.998833229826,0.248612985706)); +#159447 = CARTESIAN_POINT('',(0.999871028538,0.270882134449)); +#159448 = CARTESIAN_POINT('',(1.0001867557,0.293008725647)); +#159449 = CARTESIAN_POINT('',(0.99938194866,0.314442275844)); +#159450 = CARTESIAN_POINT('',(0.99818158431,0.334725240266)); +#159451 = CARTESIAN_POINT('',(0.996964952481,0.354229154568)); +#159452 = CARTESIAN_POINT('',(0.99605305529,0.373084953135)); +#159453 = CARTESIAN_POINT('',(0.995634639382,0.391471546073)); +#159454 = CARTESIAN_POINT('',(0.99578983908,0.409540165723)); +#159455 = CARTESIAN_POINT('',(0.996486334236,0.427437673934)); +#159456 = CARTESIAN_POINT('',(0.997583779781,0.445297616935)); +#159457 = CARTESIAN_POINT('',(0.998826319641,0.463259900197)); +#159458 = CARTESIAN_POINT('',(0.999869174903,0.481406118477)); +#159459 = CARTESIAN_POINT('',(1.000179643218,0.500000906502)); +#159460 = CARTESIAN_POINT('',(0.999412252224,0.518590255514)); +#159461 = CARTESIAN_POINT('',(0.998304758515,0.536730890316)); +#159462 = CARTESIAN_POINT('',(0.997188482095,0.554694411519)); +#159463 = CARTESIAN_POINT('',(0.996361668749,0.572565964233)); +#159464 = CARTESIAN_POINT('',(0.995993211047,0.59048580884)); +#159465 = CARTESIAN_POINT('',(0.996153127512,0.60858490815)); +#159466 = CARTESIAN_POINT('',(0.996806528451,0.627004173087)); +#159467 = CARTESIAN_POINT('',(0.997823040403,0.645886994834)); +#159468 = CARTESIAN_POINT('',(0.998955310087,0.665396236537)); +#159469 = CARTESIAN_POINT('',(0.999921125769,0.685660690895)); +#159470 = CARTESIAN_POINT('',(1.000100945844,0.706979101639)); +#159471 = CARTESIAN_POINT('',(0.999675090853,0.72906358967)); +#159472 = CARTESIAN_POINT('',(0.999560605215,0.75173018814)); +#159473 = CARTESIAN_POINT('',(0.999668068186,0.775073964241)); +#159474 = CARTESIAN_POINT('',(1.000105996611,0.800528055436)); +#159475 = CARTESIAN_POINT('',(1.000029370934,0.827065114291)); +#159476 = CARTESIAN_POINT('',(0.999897945216,0.852516791708)); +#159477 = CARTESIAN_POINT('',(0.999444903797,0.878948252316)); +#159478 = CARTESIAN_POINT('',(0.999187342355,0.90652820184)); +#159479 = CARTESIAN_POINT('',(0.9991853042,0.935574672207)); +#159480 = CARTESIAN_POINT('',(0.999491359909,0.966430706084)); +#159481 = CARTESIAN_POINT('',(0.999818160903,0.988511502173)); +#159482 = CARTESIAN_POINT('',(1.,1.)); +#159483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159484 = ADVANCED_FACE('',(#159485),#159218,.F.); +#159485 = FACE_BOUND('',#159486,.F.); +#159486 = EDGE_LOOP('',(#159487,#159488,#159489,#159490)); +#159487 = ORIENTED_EDGE('',*,*,#159328,.T.); +#159488 = ORIENTED_EDGE('',*,*,#159398,.T.); +#159489 = ORIENTED_EDGE('',*,*,#159179,.F.); +#159490 = ORIENTED_EDGE('',*,*,#159491,.T.); +#159491 = EDGE_CURVE('',#159108,#159106,#159492,.T.); +#159492 = SURFACE_CURVE('',#159493,(#159498,#159527),.PCURVE_S1.); +#159493 = CIRCLE('',#159494,0.325); +#159494 = AXIS2_PLACEMENT_3D('',#159495,#159496,#159497); +#159495 = CARTESIAN_POINT('',(-1.7,1.75,0.8)); +#159496 = DIRECTION('',(6.898853532133E-034,-1.,-1.437261152528E-033)); +#159497 = DIRECTION('',(9.915454178714E-067,-1.437261152528E-033,1.)); +#159498 = PCURVE('',#159218,#159499); +#159499 = DEFINITIONAL_REPRESENTATION('',(#159500),#159526); +#159500 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159501,#159502,#159503, + #159504,#159505,#159506,#159507,#159508,#159509,#159510,#159511, + #159512,#159513,#159514,#159515,#159516,#159517,#159518,#159519, + #159520,#159521,#159522,#159523,#159524,#159525),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.855188646457,4.997988312529,5.140787978601,5.283587644674, 5.426387310746,5.569186976818,5.711986642891,5.854786308963, @@ -193819,239 +196821,239 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.568784639324,6.711584305396,6.854383971469,6.997183637541, 7.139983303613,7.282782969685,7.425582635758,7.56838230183, 7.711181967902,7.853981633974),.QUASI_UNIFORM_KNOTS.); -#157109 = CARTESIAN_POINT('',(0.E+000,1.)); -#157110 = CARTESIAN_POINT('',(0.E+000,0.976252642514)); -#157111 = CARTESIAN_POINT('',(0.E+000,0.931948683956)); -#157112 = CARTESIAN_POINT('',(0.E+000,0.873315440011)); -#157113 = CARTESIAN_POINT('',(0.E+000,0.820561425866)); -#157114 = CARTESIAN_POINT('',(0.E+000,0.772421788032)); -#157115 = CARTESIAN_POINT('',(0.E+000,0.727875357125)); -#157116 = CARTESIAN_POINT('',(0.E+000,0.68613087718)); -#157117 = CARTESIAN_POINT('',(0.E+000,0.646543283156)); -#157118 = CARTESIAN_POINT('',(0.E+000,0.608575469012)); -#157119 = CARTESIAN_POINT('',(0.E+000,0.571764894481)); -#157120 = CARTESIAN_POINT('',(0.E+000,0.535699835049)); -#157121 = CARTESIAN_POINT('',(0.E+000,0.5)); -#157122 = CARTESIAN_POINT('',(0.E+000,0.464300164951)); -#157123 = CARTESIAN_POINT('',(0.E+000,0.428235105519)); -#157124 = CARTESIAN_POINT('',(0.E+000,0.391424530988)); -#157125 = CARTESIAN_POINT('',(0.E+000,0.353456716844)); -#157126 = CARTESIAN_POINT('',(0.E+000,0.31386912282)); -#157127 = CARTESIAN_POINT('',(0.E+000,0.272124642875)); -#157128 = CARTESIAN_POINT('',(0.E+000,0.227578211968)); -#157129 = CARTESIAN_POINT('',(0.E+000,0.179438574134)); -#157130 = CARTESIAN_POINT('',(0.E+000,0.126684559989)); -#157131 = CARTESIAN_POINT('',(0.E+000,6.805131604372E-002)); -#157132 = CARTESIAN_POINT('',(0.E+000,2.374735748557E-002)); -#157133 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#157134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157135 = PCURVE('',#156771,#157136); -#157136 = DEFINITIONAL_REPRESENTATION('',(#157137),#157145); -#157137 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#157138,#157139,#157140, - #157141,#157142,#157143,#157144),.UNSPECIFIED.,.T.,.F.) +#159501 = CARTESIAN_POINT('',(0.E+000,1.)); +#159502 = CARTESIAN_POINT('',(0.E+000,0.976252642514)); +#159503 = CARTESIAN_POINT('',(0.E+000,0.931948683956)); +#159504 = CARTESIAN_POINT('',(0.E+000,0.873315440011)); +#159505 = CARTESIAN_POINT('',(0.E+000,0.820561425866)); +#159506 = CARTESIAN_POINT('',(0.E+000,0.772421788032)); +#159507 = CARTESIAN_POINT('',(0.E+000,0.727875357125)); +#159508 = CARTESIAN_POINT('',(0.E+000,0.68613087718)); +#159509 = CARTESIAN_POINT('',(0.E+000,0.646543283156)); +#159510 = CARTESIAN_POINT('',(0.E+000,0.608575469012)); +#159511 = CARTESIAN_POINT('',(0.E+000,0.571764894481)); +#159512 = CARTESIAN_POINT('',(0.E+000,0.535699835049)); +#159513 = CARTESIAN_POINT('',(0.E+000,0.5)); +#159514 = CARTESIAN_POINT('',(0.E+000,0.464300164951)); +#159515 = CARTESIAN_POINT('',(0.E+000,0.428235105519)); +#159516 = CARTESIAN_POINT('',(0.E+000,0.391424530988)); +#159517 = CARTESIAN_POINT('',(0.E+000,0.353456716844)); +#159518 = CARTESIAN_POINT('',(0.E+000,0.31386912282)); +#159519 = CARTESIAN_POINT('',(0.E+000,0.272124642875)); +#159520 = CARTESIAN_POINT('',(0.E+000,0.227578211968)); +#159521 = CARTESIAN_POINT('',(0.E+000,0.179438574134)); +#159522 = CARTESIAN_POINT('',(0.E+000,0.126684559989)); +#159523 = CARTESIAN_POINT('',(0.E+000,6.805131604372E-002)); +#159524 = CARTESIAN_POINT('',(0.E+000,2.374735748557E-002)); +#159525 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#159526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159527 = PCURVE('',#159163,#159528); +#159528 = DEFINITIONAL_REPRESENTATION('',(#159529),#159537); +#159529 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159530,#159531,#159532, + #159533,#159534,#159535,#159536),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#157138 = CARTESIAN_POINT('',(1.125,-1.7)); -#157139 = CARTESIAN_POINT('',(1.125,-2.26291651246)); -#157140 = CARTESIAN_POINT('',(0.6375,-1.98145825623)); -#157141 = CARTESIAN_POINT('',(0.15,-1.7)); -#157142 = CARTESIAN_POINT('',(0.6375,-1.41854174377)); -#157143 = CARTESIAN_POINT('',(1.125,-1.13708348754)); -#157144 = CARTESIAN_POINT('',(1.125,-1.7)); -#157145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157146 = ADVANCED_FACE('',(#157147,#157258),#156771,.T.); -#157147 = FACE_BOUND('',#157148,.T.); -#157148 = EDGE_LOOP('',(#157149,#157178,#157205,#157232)); -#157149 = ORIENTED_EDGE('',*,*,#157150,.F.); -#157150 = EDGE_CURVE('',#157151,#157153,#157155,.T.); -#157151 = VERTEX_POINT('',#157152); -#157152 = CARTESIAN_POINT('',(2.317597284454,1.75,-1.817597284454)); -#157153 = VERTEX_POINT('',#157154); -#157154 = CARTESIAN_POINT('',(2.317597284454,1.75,1.506069810909)); -#157155 = SURFACE_CURVE('',#157156,(#157160,#157167),.PCURVE_S1.); -#157156 = LINE('',#157157,#157158); -#157157 = CARTESIAN_POINT('',(2.317597284454,1.75,5.749044610111E-034)); -#157158 = VECTOR('',#157159,1.); -#157159 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); -#157160 = PCURVE('',#156771,#157161); -#157161 = DEFINITIONAL_REPRESENTATION('',(#157162),#157166); -#157162 = LINE('',#157163,#157164); -#157163 = CARTESIAN_POINT('',(5.749044610111E-034,2.317597284454)); -#157164 = VECTOR('',#157165,1.); -#157165 = DIRECTION('',(1.,2.154269365246E-050)); -#157166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157167 = PCURVE('',#157168,#157173); -#157168 = CYLINDRICAL_SURFACE('',#157169,0.1); -#157169 = AXIS2_PLACEMENT_3D('',#157170,#157171,#157172); -#157170 = CARTESIAN_POINT('',(2.317597284454,1.65,4.311783457583E-034)); -#157171 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); -#157172 = DIRECTION('',(-7.368696838173E-099,-1.,-1.437261152528E-033)); -#157173 = DEFINITIONAL_REPRESENTATION('',(#157174),#157177); -#157174 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157175,#157176), +#159530 = CARTESIAN_POINT('',(1.125,-1.7)); +#159531 = CARTESIAN_POINT('',(1.125,-2.26291651246)); +#159532 = CARTESIAN_POINT('',(0.6375,-1.98145825623)); +#159533 = CARTESIAN_POINT('',(0.15,-1.7)); +#159534 = CARTESIAN_POINT('',(0.6375,-1.41854174377)); +#159535 = CARTESIAN_POINT('',(1.125,-1.13708348754)); +#159536 = CARTESIAN_POINT('',(1.125,-1.7)); +#159537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159538 = ADVANCED_FACE('',(#159539,#159650),#159163,.T.); +#159539 = FACE_BOUND('',#159540,.T.); +#159540 = EDGE_LOOP('',(#159541,#159570,#159597,#159624)); +#159541 = ORIENTED_EDGE('',*,*,#159542,.F.); +#159542 = EDGE_CURVE('',#159543,#159545,#159547,.T.); +#159543 = VERTEX_POINT('',#159544); +#159544 = CARTESIAN_POINT('',(2.317597284454,1.75,-1.817597284454)); +#159545 = VERTEX_POINT('',#159546); +#159546 = CARTESIAN_POINT('',(2.317597284454,1.75,1.506069810909)); +#159547 = SURFACE_CURVE('',#159548,(#159552,#159559),.PCURVE_S1.); +#159548 = LINE('',#159549,#159550); +#159549 = CARTESIAN_POINT('',(2.317597284454,1.75,5.749044610111E-034)); +#159550 = VECTOR('',#159551,1.); +#159551 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); +#159552 = PCURVE('',#159163,#159553); +#159553 = DEFINITIONAL_REPRESENTATION('',(#159554),#159558); +#159554 = LINE('',#159555,#159556); +#159555 = CARTESIAN_POINT('',(5.749044610111E-034,2.317597284454)); +#159556 = VECTOR('',#159557,1.); +#159557 = DIRECTION('',(1.,2.154269365246E-050)); +#159558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159559 = PCURVE('',#159560,#159565); +#159560 = CYLINDRICAL_SURFACE('',#159561,0.1); +#159561 = AXIS2_PLACEMENT_3D('',#159562,#159563,#159564); +#159562 = CARTESIAN_POINT('',(2.317597284454,1.65,4.311783457583E-034)); +#159563 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); +#159564 = DIRECTION('',(-7.368696838173E-099,-1.,-1.437261152528E-033)); +#159565 = DEFINITIONAL_REPRESENTATION('',(#159566),#159569); +#159566 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159567,#159568), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.817597284454,1.506069810909), .PIECEWISE_BEZIER_KNOTS.); -#157175 = CARTESIAN_POINT('',(3.14159265359,-1.817597284454)); -#157176 = CARTESIAN_POINT('',(3.14159265359,1.506069810909)); -#157177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157178 = ORIENTED_EDGE('',*,*,#157179,.F.); -#157179 = EDGE_CURVE('',#157180,#157151,#157182,.T.); -#157180 = VERTEX_POINT('',#157181); -#157181 = CARTESIAN_POINT('',(-2.317597284454,1.75,-1.817597284454)); -#157182 = SURFACE_CURVE('',#157183,(#157187,#157194),.PCURVE_S1.); -#157183 = LINE('',#157184,#157185); -#157184 = CARTESIAN_POINT('',(2.050127744336E-017,1.75,-1.817597284454) - ); -#157185 = VECTOR('',#157186,1.); -#157186 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); -#157187 = PCURVE('',#156771,#157188); -#157188 = DEFINITIONAL_REPRESENTATION('',(#157189),#157193); -#157189 = LINE('',#157190,#157191); -#157190 = CARTESIAN_POINT('',(-1.817597284454,-6.833759147787E-018)); -#157191 = VECTOR('',#157192,1.); -#157192 = DIRECTION('',(-9.915454178714E-067,1.)); -#157193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157194 = PCURVE('',#157195,#157200); -#157195 = CYLINDRICAL_SURFACE('',#157196,0.1); -#157196 = AXIS2_PLACEMENT_3D('',#157197,#157198,#157199); -#157197 = CARTESIAN_POINT('',(2.050127744336E-017,1.65,-1.817597284454) - ); -#157198 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); -#157199 = DIRECTION('',(-6.898853532133E-034,1.,0.E+000)); -#157200 = DEFINITIONAL_REPRESENTATION('',(#157201),#157204); -#157201 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157202,#157203), +#159567 = CARTESIAN_POINT('',(3.14159265359,-1.817597284454)); +#159568 = CARTESIAN_POINT('',(3.14159265359,1.506069810909)); +#159569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159570 = ORIENTED_EDGE('',*,*,#159571,.F.); +#159571 = EDGE_CURVE('',#159572,#159543,#159574,.T.); +#159572 = VERTEX_POINT('',#159573); +#159573 = CARTESIAN_POINT('',(-2.317597284454,1.75,-1.817597284454)); +#159574 = SURFACE_CURVE('',#159575,(#159579,#159586),.PCURVE_S1.); +#159575 = LINE('',#159576,#159577); +#159576 = CARTESIAN_POINT('',(2.050127744336E-017,1.75,-1.817597284454) + ); +#159577 = VECTOR('',#159578,1.); +#159578 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); +#159579 = PCURVE('',#159163,#159580); +#159580 = DEFINITIONAL_REPRESENTATION('',(#159581),#159585); +#159581 = LINE('',#159582,#159583); +#159582 = CARTESIAN_POINT('',(-1.817597284454,-6.833759147787E-018)); +#159583 = VECTOR('',#159584,1.); +#159584 = DIRECTION('',(-9.915454178714E-067,1.)); +#159585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159586 = PCURVE('',#159587,#159592); +#159587 = CYLINDRICAL_SURFACE('',#159588,0.1); +#159588 = AXIS2_PLACEMENT_3D('',#159589,#159590,#159591); +#159589 = CARTESIAN_POINT('',(2.050127744336E-017,1.65,-1.817597284454) + ); +#159590 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); +#159591 = DIRECTION('',(-6.898853532133E-034,1.,0.E+000)); +#159592 = DEFINITIONAL_REPRESENTATION('',(#159593),#159596); +#159593 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159594,#159595), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.317597284454,2.317597284454), .PIECEWISE_BEZIER_KNOTS.); -#157202 = CARTESIAN_POINT('',(6.28318530718,-2.317597284454)); -#157203 = CARTESIAN_POINT('',(6.28318530718,2.317597284454)); -#157204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157205 = ORIENTED_EDGE('',*,*,#157206,.F.); -#157206 = EDGE_CURVE('',#157207,#157180,#157209,.T.); -#157207 = VERTEX_POINT('',#157208); -#157208 = CARTESIAN_POINT('',(-2.317597284454,1.75,1.506069810909)); -#157209 = SURFACE_CURVE('',#157210,(#157214,#157221),.PCURVE_S1.); -#157210 = LINE('',#157211,#157212); -#157211 = CARTESIAN_POINT('',(-2.317597284454,1.75,5.749044610111E-034) - ); -#157212 = VECTOR('',#157213,1.); -#157213 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); -#157214 = PCURVE('',#156771,#157215); -#157215 = DEFINITIONAL_REPRESENTATION('',(#157216),#157220); -#157216 = LINE('',#157217,#157218); -#157217 = CARTESIAN_POINT('',(5.749044610111E-034,-2.317597284454)); -#157218 = VECTOR('',#157219,1.); -#157219 = DIRECTION('',(-1.,2.154269365246E-050)); -#157220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157221 = PCURVE('',#157222,#157227); -#157222 = CYLINDRICAL_SURFACE('',#157223,0.1); -#157223 = AXIS2_PLACEMENT_3D('',#157224,#157225,#157226); -#157224 = CARTESIAN_POINT('',(-2.317597284454,1.65,4.311783457583E-034) - ); -#157225 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); -#157226 = DIRECTION('',(-7.368696838173E-099,1.,1.437261152528E-033)); -#157227 = DEFINITIONAL_REPRESENTATION('',(#157228),#157231); -#157228 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157229,#157230), +#159594 = CARTESIAN_POINT('',(6.28318530718,-2.317597284454)); +#159595 = CARTESIAN_POINT('',(6.28318530718,2.317597284454)); +#159596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159597 = ORIENTED_EDGE('',*,*,#159598,.F.); +#159598 = EDGE_CURVE('',#159599,#159572,#159601,.T.); +#159599 = VERTEX_POINT('',#159600); +#159600 = CARTESIAN_POINT('',(-2.317597284454,1.75,1.506069810909)); +#159601 = SURFACE_CURVE('',#159602,(#159606,#159613),.PCURVE_S1.); +#159602 = LINE('',#159603,#159604); +#159603 = CARTESIAN_POINT('',(-2.317597284454,1.75,5.749044610111E-034) + ); +#159604 = VECTOR('',#159605,1.); +#159605 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); +#159606 = PCURVE('',#159163,#159607); +#159607 = DEFINITIONAL_REPRESENTATION('',(#159608),#159612); +#159608 = LINE('',#159609,#159610); +#159609 = CARTESIAN_POINT('',(5.749044610111E-034,-2.317597284454)); +#159610 = VECTOR('',#159611,1.); +#159611 = DIRECTION('',(-1.,2.154269365246E-050)); +#159612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159613 = PCURVE('',#159614,#159619); +#159614 = CYLINDRICAL_SURFACE('',#159615,0.1); +#159615 = AXIS2_PLACEMENT_3D('',#159616,#159617,#159618); +#159616 = CARTESIAN_POINT('',(-2.317597284454,1.65,4.311783457583E-034) + ); +#159617 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); +#159618 = DIRECTION('',(-7.368696838173E-099,1.,1.437261152528E-033)); +#159619 = DEFINITIONAL_REPRESENTATION('',(#159620),#159623); +#159620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159621,#159622), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.506069810909,1.817597284454), .PIECEWISE_BEZIER_KNOTS.); -#157229 = CARTESIAN_POINT('',(6.28318530718,-1.506069810909)); -#157230 = CARTESIAN_POINT('',(6.28318530718,1.817597284454)); -#157231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157232 = ORIENTED_EDGE('',*,*,#157233,.F.); -#157233 = EDGE_CURVE('',#157153,#157207,#157234,.T.); -#157234 = SURFACE_CURVE('',#157235,(#157239,#157246),.PCURVE_S1.); -#157235 = LINE('',#157236,#157237); -#157236 = CARTESIAN_POINT('',(2.050127744336E-017,1.75,1.506069810909)); -#157237 = VECTOR('',#157238,1.); -#157238 = DIRECTION('',(-1.,-3.869806141171E-034,-3.423715262028E-034)); -#157239 = PCURVE('',#156771,#157240); -#157240 = DEFINITIONAL_REPRESENTATION('',(#157241),#157245); -#157241 = LINE('',#157242,#157243); -#157242 = CARTESIAN_POINT('',(1.506069810909,-6.833759147787E-018)); -#157243 = VECTOR('',#157244,1.); -#157244 = DIRECTION('',(-3.423715262028E-034,-1.)); -#157245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157246 = PCURVE('',#157247,#157252); -#157247 = PLANE('',#157248); -#157248 = AXIS2_PLACEMENT_3D('',#157249,#157250,#157251); -#157249 = CARTESIAN_POINT('',(2.050127744336E-017,1.551490769672, +#159621 = CARTESIAN_POINT('',(6.28318530718,-1.506069810909)); +#159622 = CARTESIAN_POINT('',(6.28318530718,1.817597284454)); +#159623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159624 = ORIENTED_EDGE('',*,*,#159625,.F.); +#159625 = EDGE_CURVE('',#159545,#159599,#159626,.T.); +#159626 = SURFACE_CURVE('',#159627,(#159631,#159638),.PCURVE_S1.); +#159627 = LINE('',#159628,#159629); +#159628 = CARTESIAN_POINT('',(2.050127744336E-017,1.75,1.506069810909)); +#159629 = VECTOR('',#159630,1.); +#159630 = DIRECTION('',(-1.,-3.869806141171E-034,-3.423715262028E-034)); +#159631 = PCURVE('',#159163,#159632); +#159632 = DEFINITIONAL_REPRESENTATION('',(#159633),#159637); +#159633 = LINE('',#159634,#159635); +#159634 = CARTESIAN_POINT('',(1.506069810909,-6.833759147787E-018)); +#159635 = VECTOR('',#159636,1.); +#159636 = DIRECTION('',(-3.423715262028E-034,-1.)); +#159637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159638 = PCURVE('',#159639,#159644); +#159639 = PLANE('',#159640); +#159640 = AXIS2_PLACEMENT_3D('',#159641,#159642,#159643); +#159641 = CARTESIAN_POINT('',(2.050127744336E-017,1.551490769672, 1.73044367959)); -#157250 = DIRECTION('',(-5.166935819777E-034,0.748955720789, +#159642 = DIRECTION('',(-5.166935819777E-034,0.748955720789, 0.662620048216)); -#157251 = DIRECTION('',(4.907028959935E-051,-0.662620048216, +#159643 = DIRECTION('',(4.907028959935E-051,-0.662620048216, 0.748955720789)); -#157252 = DEFINITIONAL_REPRESENTATION('',(#157253),#157257); -#157253 = LINE('',#157254,#157255); -#157254 = CARTESIAN_POINT('',(-0.299582288316,5.714600640894E-050)); -#157255 = VECTOR('',#157256,1.); -#157256 = DIRECTION('',(3.82330639389E-050,-1.)); -#157257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157258 = FACE_BOUND('',#157259,.T.); -#157259 = EDGE_LOOP('',(#157260,#157261)); -#157260 = ORIENTED_EDGE('',*,*,#157099,.T.); -#157261 = ORIENTED_EDGE('',*,*,#156713,.T.); -#157262 = ADVANCED_FACE('',(#157263),#157247,.T.); -#157263 = FACE_BOUND('',#157264,.T.); -#157264 = EDGE_LOOP('',(#157265,#157312,#157313,#157360,#157388,#157416) - ); -#157265 = ORIENTED_EDGE('',*,*,#157266,.F.); -#157266 = EDGE_CURVE('',#157153,#157267,#157269,.T.); -#157267 = VERTEX_POINT('',#157268); -#157268 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#159644 = DEFINITIONAL_REPRESENTATION('',(#159645),#159649); +#159645 = LINE('',#159646,#159647); +#159646 = CARTESIAN_POINT('',(-0.299582288316,5.714600640894E-050)); +#159647 = VECTOR('',#159648,1.); +#159648 = DIRECTION('',(3.82330639389E-050,-1.)); +#159649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159650 = FACE_BOUND('',#159651,.T.); +#159651 = EDGE_LOOP('',(#159652,#159653)); +#159652 = ORIENTED_EDGE('',*,*,#159491,.T.); +#159653 = ORIENTED_EDGE('',*,*,#159105,.T.); +#159654 = ADVANCED_FACE('',(#159655),#159639,.T.); +#159655 = FACE_BOUND('',#159656,.T.); +#159656 = EDGE_LOOP('',(#159657,#159704,#159705,#159752,#159780,#159808) + ); +#159657 = ORIENTED_EDGE('',*,*,#159658,.F.); +#159658 = EDGE_CURVE('',#159545,#159659,#159661,.T.); +#159659 = VERTEX_POINT('',#159660); +#159660 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, 1.605324426073)); -#157269 = SURFACE_CURVE('',#157270,(#157275,#157283),.PCURVE_S1.); -#157270 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157271,#157272,#157273, -#157274),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159661 = SURFACE_CURVE('',#159662,(#159667,#159675),.PCURVE_S1.); +#159662 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159663,#159664,#159665, +#159666),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.14159265359,4.590215932745),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157271 = CARTESIAN_POINT('',(2.317597284454,1.75,1.506069810909)); -#157272 = CARTESIAN_POINT('',(2.370651210801,1.75,1.506069810909)); -#157273 = CARTESIAN_POINT('',(2.410386252449,1.714845404766, +#159663 = CARTESIAN_POINT('',(2.317597284454,1.75,1.506069810909)); +#159664 = CARTESIAN_POINT('',(2.370651210801,1.75,1.506069810909)); +#159665 = CARTESIAN_POINT('',(2.410386252449,1.714845404766, 1.545804852557)); -#157274 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#159666 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, 1.605324426073)); -#157275 = PCURVE('',#157247,#157276); -#157276 = DEFINITIONAL_REPRESENTATION('',(#157277),#157282); -#157277 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157278,#157279,#157280, -#157281),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159667 = PCURVE('',#159639,#159668); +#159668 = DEFINITIONAL_REPRESENTATION('',(#159669),#159674); +#159669 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159670,#159671,#159672, +#159673),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.14159265359,4.590215932745),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157278 = CARTESIAN_POINT('',(-0.299582288316,2.317597284454)); -#157279 = CARTESIAN_POINT('',(-0.299582288316,2.370651210801)); -#157280 = CARTESIAN_POINT('',(-0.246528361968,2.410386252449)); -#157281 = CARTESIAN_POINT('',(-0.167058278672,2.416851899618)); -#157282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157283 = PCURVE('',#157168,#157284); -#157284 = DEFINITIONAL_REPRESENTATION('',(#157285),#157311); -#157285 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157286,#157287,#157288, - #157289,#157290,#157291,#157292,#157293,#157294,#157295,#157296, - #157297,#157298,#157299,#157300,#157301,#157302,#157303,#157304, - #157305,#157306,#157307,#157308,#157309,#157310),.UNSPECIFIED.,.F., +#159670 = CARTESIAN_POINT('',(-0.299582288316,2.317597284454)); +#159671 = CARTESIAN_POINT('',(-0.299582288316,2.370651210801)); +#159672 = CARTESIAN_POINT('',(-0.246528361968,2.410386252449)); +#159673 = CARTESIAN_POINT('',(-0.167058278672,2.416851899618)); +#159674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159675 = PCURVE('',#159560,#159676); +#159676 = DEFINITIONAL_REPRESENTATION('',(#159677),#159703); +#159677 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159678,#159679,#159680, + #159681,#159682,#159683,#159684,#159685,#159686,#159687,#159688, + #159689,#159690,#159691,#159692,#159693,#159694,#159695,#159696, + #159697,#159698,#159699,#159700,#159701,#159702),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.207439166279,3.273285678968,3.339132191656,3.404978704345, 3.470825217034,3.536671729723,3.602518242412,3.668364755101, @@ -194059,72 +197061,72 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 3.997597318545,4.063443831234,4.129290343923,4.195136856612, 4.260983369301,4.32682988199,4.392676394678,4.458522907367, 4.524369420056,4.590215932745),.QUASI_UNIFORM_KNOTS.); -#157286 = CARTESIAN_POINT('',(3.14159265359,1.506069810909)); -#157287 = CARTESIAN_POINT('',(3.12151434906,1.506069510231)); -#157288 = CARTESIAN_POINT('',(3.080895346177,1.506206741002)); -#157289 = CARTESIAN_POINT('',(3.018662714711,1.50684883735)); -#157290 = CARTESIAN_POINT('',(2.955203867684,1.507951558968)); -#157291 = CARTESIAN_POINT('',(2.890614716316,1.509533606481)); -#157292 = CARTESIAN_POINT('',(2.825002696965,1.511608868195)); -#157293 = CARTESIAN_POINT('',(2.75848783298,1.514185191034)); -#157294 = CARTESIAN_POINT('',(2.691201358285,1.517263867251)); -#157295 = CARTESIAN_POINT('',(2.623284574238,1.520839143563)); -#157296 = CARTESIAN_POINT('',(2.554887243423,1.524897989991)); -#157297 = CARTESIAN_POINT('',(2.486165748071,1.529420103758)); -#157298 = CARTESIAN_POINT('',(2.417281014012,1.534378176579)); -#157299 = CARTESIAN_POINT('',(2.348396279953,1.539738419096)); -#157300 = CARTESIAN_POINT('',(2.279674784602,1.545461323746)); -#157301 = CARTESIAN_POINT('',(2.211277453786,1.551502630008)); -#157302 = CARTESIAN_POINT('',(2.143360669739,1.557814442667)); -#157303 = CARTESIAN_POINT('',(2.076074195044,1.56434644606)); -#157304 = CARTESIAN_POINT('',(2.009559331059,1.571047147888)); -#157305 = CARTESIAN_POINT('',(1.943947311708,1.577865107761)); -#157306 = CARTESIAN_POINT('',(1.87935816034,1.584750036023)); -#157307 = CARTESIAN_POINT('',(1.815899313313,1.59165394064)); -#157308 = CARTESIAN_POINT('',(1.753666681847,1.598531458208)); -#157309 = CARTESIAN_POINT('',(1.713047678964,1.603072120587)); -#157310 = CARTESIAN_POINT('',(1.692969374434,1.605324426073)); -#157311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157312 = ORIENTED_EDGE('',*,*,#157233,.T.); -#157313 = ORIENTED_EDGE('',*,*,#157314,.F.); -#157314 = EDGE_CURVE('',#157315,#157207,#157317,.T.); -#157315 = VERTEX_POINT('',#157316); -#157316 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159678 = CARTESIAN_POINT('',(3.14159265359,1.506069810909)); +#159679 = CARTESIAN_POINT('',(3.12151434906,1.506069510231)); +#159680 = CARTESIAN_POINT('',(3.080895346177,1.506206741002)); +#159681 = CARTESIAN_POINT('',(3.018662714711,1.50684883735)); +#159682 = CARTESIAN_POINT('',(2.955203867684,1.507951558968)); +#159683 = CARTESIAN_POINT('',(2.890614716316,1.509533606481)); +#159684 = CARTESIAN_POINT('',(2.825002696965,1.511608868195)); +#159685 = CARTESIAN_POINT('',(2.75848783298,1.514185191034)); +#159686 = CARTESIAN_POINT('',(2.691201358285,1.517263867251)); +#159687 = CARTESIAN_POINT('',(2.623284574238,1.520839143563)); +#159688 = CARTESIAN_POINT('',(2.554887243423,1.524897989991)); +#159689 = CARTESIAN_POINT('',(2.486165748071,1.529420103758)); +#159690 = CARTESIAN_POINT('',(2.417281014012,1.534378176579)); +#159691 = CARTESIAN_POINT('',(2.348396279953,1.539738419096)); +#159692 = CARTESIAN_POINT('',(2.279674784602,1.545461323746)); +#159693 = CARTESIAN_POINT('',(2.211277453786,1.551502630008)); +#159694 = CARTESIAN_POINT('',(2.143360669739,1.557814442667)); +#159695 = CARTESIAN_POINT('',(2.076074195044,1.56434644606)); +#159696 = CARTESIAN_POINT('',(2.009559331059,1.571047147888)); +#159697 = CARTESIAN_POINT('',(1.943947311708,1.577865107761)); +#159698 = CARTESIAN_POINT('',(1.87935816034,1.584750036023)); +#159699 = CARTESIAN_POINT('',(1.815899313313,1.59165394064)); +#159700 = CARTESIAN_POINT('',(1.753666681847,1.598531458208)); +#159701 = CARTESIAN_POINT('',(1.713047678964,1.603072120587)); +#159702 = CARTESIAN_POINT('',(1.692969374434,1.605324426073)); +#159703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159704 = ORIENTED_EDGE('',*,*,#159625,.T.); +#159705 = ORIENTED_EDGE('',*,*,#159706,.F.); +#159706 = EDGE_CURVE('',#159707,#159599,#159709,.T.); +#159707 = VERTEX_POINT('',#159708); +#159708 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, 1.605324426073)); -#157317 = SURFACE_CURVE('',#157318,(#157323,#157331),.PCURVE_S1.); -#157318 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157319,#157320,#157321, -#157322),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159709 = SURFACE_CURVE('',#159710,(#159715,#159723),.PCURVE_S1.); +#159710 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159711,#159712,#159713, +#159714),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 4.834562028024,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157319 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159711 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, 1.605324426073)); -#157320 = CARTESIAN_POINT('',(-2.410386252449,1.714845404766, +#159712 = CARTESIAN_POINT('',(-2.410386252449,1.714845404766, 1.545804852557)); -#157321 = CARTESIAN_POINT('',(-2.370651210801,1.75,1.506069810909)); -#157322 = CARTESIAN_POINT('',(-2.317597284454,1.75,1.506069810909)); -#157323 = PCURVE('',#157247,#157324); -#157324 = DEFINITIONAL_REPRESENTATION('',(#157325),#157330); -#157325 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157326,#157327,#157328, -#157329),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159713 = CARTESIAN_POINT('',(-2.370651210801,1.75,1.506069810909)); +#159714 = CARTESIAN_POINT('',(-2.317597284454,1.75,1.506069810909)); +#159715 = PCURVE('',#159639,#159716); +#159716 = DEFINITIONAL_REPRESENTATION('',(#159717),#159722); +#159717 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159718,#159719,#159720, +#159721),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 4.834562028024,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157326 = CARTESIAN_POINT('',(-0.167058278672,-2.416851899618)); -#157327 = CARTESIAN_POINT('',(-0.246528361968,-2.410386252449)); -#157328 = CARTESIAN_POINT('',(-0.299582288316,-2.370651210801)); -#157329 = CARTESIAN_POINT('',(-0.299582288316,-2.317597284454)); -#157330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157331 = PCURVE('',#157222,#157332); -#157332 = DEFINITIONAL_REPRESENTATION('',(#157333),#157359); -#157333 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157334,#157335,#157336, - #157337,#157338,#157339,#157340,#157341,#157342,#157343,#157344, - #157345,#157346,#157347,#157348,#157349,#157350,#157351,#157352, - #157353,#157354,#157355,#157356,#157357,#157358),.UNSPECIFIED.,.F., +#159718 = CARTESIAN_POINT('',(-0.167058278672,-2.416851899618)); +#159719 = CARTESIAN_POINT('',(-0.246528361968,-2.410386252449)); +#159720 = CARTESIAN_POINT('',(-0.299582288316,-2.370651210801)); +#159721 = CARTESIAN_POINT('',(-0.299582288316,-2.317597284454)); +#159722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159723 = PCURVE('',#159614,#159724); +#159724 = DEFINITIONAL_REPRESENTATION('',(#159725),#159751); +#159725 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159726,#159727,#159728, + #159729,#159730,#159731,#159732,#159733,#159734,#159735,#159736, + #159737,#159738,#159739,#159740,#159741,#159742,#159743,#159744, + #159745,#159746,#159747,#159748,#159749,#159750),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.834562028024, 4.900408540713,4.966255053402,5.032101566091,5.09794807878, 5.163794591469,5.229641104158,5.295487616846,5.361334129535, @@ -194132,170 +197134,170 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.69056669298,5.756413205669,5.822259718357,5.888106231046, 5.953952743735,6.019799256424,6.085645769113,6.151492281802, 6.217338794491,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#157334 = CARTESIAN_POINT('',(4.834562028024,-1.605324426073)); -#157335 = CARTESIAN_POINT('',(4.854640332554,-1.603072120587)); -#157336 = CARTESIAN_POINT('',(4.895259335437,-1.598531458208)); -#157337 = CARTESIAN_POINT('',(4.957491966903,-1.59165394064)); -#157338 = CARTESIAN_POINT('',(5.02095081393,-1.584750036023)); -#157339 = CARTESIAN_POINT('',(5.085539965298,-1.577865107761)); -#157340 = CARTESIAN_POINT('',(5.151151984649,-1.571047147888)); -#157341 = CARTESIAN_POINT('',(5.217666848634,-1.56434644606)); -#157342 = CARTESIAN_POINT('',(5.284953323329,-1.557814442667)); -#157343 = CARTESIAN_POINT('',(5.352870107376,-1.551502630008)); -#157344 = CARTESIAN_POINT('',(5.421267438192,-1.545461323746)); -#157345 = CARTESIAN_POINT('',(5.489988933543,-1.539738419096)); -#157346 = CARTESIAN_POINT('',(5.558873667602,-1.534378176579)); -#157347 = CARTESIAN_POINT('',(5.627758401661,-1.529420103758)); -#157348 = CARTESIAN_POINT('',(5.696479897012,-1.524897989991)); -#157349 = CARTESIAN_POINT('',(5.764877227828,-1.520839143563)); -#157350 = CARTESIAN_POINT('',(5.832794011875,-1.517263867251)); -#157351 = CARTESIAN_POINT('',(5.90008048657,-1.514185191034)); -#157352 = CARTESIAN_POINT('',(5.966595350555,-1.511608868195)); -#157353 = CARTESIAN_POINT('',(6.032207369906,-1.509533606481)); -#157354 = CARTESIAN_POINT('',(6.096796521274,-1.507951558968)); -#157355 = CARTESIAN_POINT('',(6.160255368301,-1.50684883735)); -#157356 = CARTESIAN_POINT('',(6.222487999767,-1.506206741002)); -#157357 = CARTESIAN_POINT('',(6.26310700265,-1.506069510231)); -#157358 = CARTESIAN_POINT('',(6.28318530718,-1.506069810909)); -#157359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157360 = ORIENTED_EDGE('',*,*,#157361,.T.); -#157361 = EDGE_CURVE('',#157315,#157362,#157364,.T.); -#157362 = VERTEX_POINT('',#157363); -#157363 = CARTESIAN_POINT('',(-2.454817548271,1.352981539343, +#159726 = CARTESIAN_POINT('',(4.834562028024,-1.605324426073)); +#159727 = CARTESIAN_POINT('',(4.854640332554,-1.603072120587)); +#159728 = CARTESIAN_POINT('',(4.895259335437,-1.598531458208)); +#159729 = CARTESIAN_POINT('',(4.957491966903,-1.59165394064)); +#159730 = CARTESIAN_POINT('',(5.02095081393,-1.584750036023)); +#159731 = CARTESIAN_POINT('',(5.085539965298,-1.577865107761)); +#159732 = CARTESIAN_POINT('',(5.151151984649,-1.571047147888)); +#159733 = CARTESIAN_POINT('',(5.217666848634,-1.56434644606)); +#159734 = CARTESIAN_POINT('',(5.284953323329,-1.557814442667)); +#159735 = CARTESIAN_POINT('',(5.352870107376,-1.551502630008)); +#159736 = CARTESIAN_POINT('',(5.421267438192,-1.545461323746)); +#159737 = CARTESIAN_POINT('',(5.489988933543,-1.539738419096)); +#159738 = CARTESIAN_POINT('',(5.558873667602,-1.534378176579)); +#159739 = CARTESIAN_POINT('',(5.627758401661,-1.529420103758)); +#159740 = CARTESIAN_POINT('',(5.696479897012,-1.524897989991)); +#159741 = CARTESIAN_POINT('',(5.764877227828,-1.520839143563)); +#159742 = CARTESIAN_POINT('',(5.832794011875,-1.517263867251)); +#159743 = CARTESIAN_POINT('',(5.90008048657,-1.514185191034)); +#159744 = CARTESIAN_POINT('',(5.966595350555,-1.511608868195)); +#159745 = CARTESIAN_POINT('',(6.032207369906,-1.509533606481)); +#159746 = CARTESIAN_POINT('',(6.096796521274,-1.507951558968)); +#159747 = CARTESIAN_POINT('',(6.160255368301,-1.50684883735)); +#159748 = CARTESIAN_POINT('',(6.222487999767,-1.506206741002)); +#159749 = CARTESIAN_POINT('',(6.26310700265,-1.506069510231)); +#159750 = CARTESIAN_POINT('',(6.28318530718,-1.506069810909)); +#159751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159752 = ORIENTED_EDGE('',*,*,#159753,.T.); +#159753 = EDGE_CURVE('',#159707,#159754,#159756,.T.); +#159754 = VERTEX_POINT('',#159755); +#159755 = CARTESIAN_POINT('',(-2.454817548271,1.352981539343, 1.954817548271)); -#157364 = SURFACE_CURVE('',#157365,(#157369,#157376),.PCURVE_S1.); -#157365 = LINE('',#157366,#157367); -#157366 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159756 = SURFACE_CURVE('',#159757,(#159761,#159768),.PCURVE_S1.); +#159757 = LINE('',#159758,#159759); +#159758 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, 1.605324426073)); -#157367 = VECTOR('',#157368,1.); -#157368 = DIRECTION('',(-8.109156679299E-002,-0.660437812349, +#159759 = VECTOR('',#159760,1.); +#159760 = DIRECTION('',(-8.109156679299E-002,-0.660437812349, 0.74648915184)); -#157369 = PCURVE('',#157247,#157370); -#157370 = DEFINITIONAL_REPRESENTATION('',(#157371),#157375); -#157371 = LINE('',#157372,#157373); -#157372 = CARTESIAN_POINT('',(-0.167058278672,-2.416851899618)); -#157373 = VECTOR('',#157374,1.); -#157374 = DIRECTION('',(0.99670665584,-8.109156679299E-002)); -#157375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157376 = PCURVE('',#157377,#157382); -#157377 = PLANE('',#157378); -#157378 = AXIS2_PLACEMENT_3D('',#157379,#157380,#157381); -#157379 = CARTESIAN_POINT('',(-2.453034905455,1.3675,6.000565311804E-034 +#159761 = PCURVE('',#159639,#159762); +#159762 = DEFINITIONAL_REPRESENTATION('',(#159763),#159767); +#159763 = LINE('',#159764,#159765); +#159764 = CARTESIAN_POINT('',(-0.167058278672,-2.416851899618)); +#159765 = VECTOR('',#159766,1.); +#159766 = DIRECTION('',(0.99670665584,-8.109156679299E-002)); +#159767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159768 = PCURVE('',#159769,#159774); +#159769 = PLANE('',#159770); +#159770 = AXIS2_PLACEMENT_3D('',#159771,#159772,#159773); +#159771 = CARTESIAN_POINT('',(-2.453034905455,1.3675,6.000565311804E-034 )); -#157380 = DIRECTION('',(-0.992546151641,0.121869343405, +#159772 = DIRECTION('',(-0.992546151641,0.121869343405, 1.751580729603E-034)); -#157381 = DIRECTION('',(-0.121869343405,-0.992546151641, +#159773 = DIRECTION('',(-0.121869343405,-0.992546151641, -1.256773640537E-051)); -#157382 = DEFINITIONAL_REPRESENTATION('',(#157383),#157387); -#157383 = LINE('',#157384,#157385); -#157384 = CARTESIAN_POINT('',(-0.296899981782,1.605324426073)); -#157385 = VECTOR('',#157386,1.); -#157386 = DIRECTION('',(0.665397585047,0.74648915184)); -#157387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157388 = ORIENTED_EDGE('',*,*,#157389,.F.); -#157389 = EDGE_CURVE('',#157390,#157362,#157392,.T.); -#157390 = VERTEX_POINT('',#157391); -#157391 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, +#159774 = DEFINITIONAL_REPRESENTATION('',(#159775),#159779); +#159775 = LINE('',#159776,#159777); +#159776 = CARTESIAN_POINT('',(-0.296899981782,1.605324426073)); +#159777 = VECTOR('',#159778,1.); +#159778 = DIRECTION('',(0.665397585047,0.74648915184)); +#159779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159780 = ORIENTED_EDGE('',*,*,#159781,.F.); +#159781 = EDGE_CURVE('',#159782,#159754,#159784,.T.); +#159782 = VERTEX_POINT('',#159783); +#159783 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, 1.954817548271)); -#157392 = SURFACE_CURVE('',#157393,(#157397,#157404),.PCURVE_S1.); -#157393 = LINE('',#157394,#157395); -#157394 = CARTESIAN_POINT('',(1.366751829557E-017,1.352981539343, +#159784 = SURFACE_CURVE('',#159785,(#159789,#159796),.PCURVE_S1.); +#159785 = LINE('',#159786,#159787); +#159786 = CARTESIAN_POINT('',(1.366751829557E-017,1.352981539343, 1.954817548271)); -#157395 = VECTOR('',#157396,1.); -#157396 = DIRECTION('',(-1.,-1.024627168501E-035,-8.344918619791E-035)); -#157397 = PCURVE('',#157247,#157398); -#157398 = DEFINITIONAL_REPRESENTATION('',(#157399),#157403); -#157399 = LINE('',#157400,#157401); -#157400 = CARTESIAN_POINT('',(0.299582288316,-6.833759147787E-018)); -#157401 = VECTOR('',#157402,1.); -#157402 = DIRECTION('',(-5.571036036015E-035,-1.)); -#157403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157404 = PCURVE('',#157405,#157410); -#157405 = PLANE('',#157406); -#157406 = AXIS2_PLACEMENT_3D('',#157407,#157408,#157409); -#157407 = CARTESIAN_POINT('',(1.366751829557E-017,1.3675,1.953034905455) - ); -#157408 = DIRECTION('',(-8.407587502094E-035,0.121869343405, +#159787 = VECTOR('',#159788,1.); +#159788 = DIRECTION('',(-1.,-1.024627168501E-035,-8.344918619791E-035)); +#159789 = PCURVE('',#159639,#159790); +#159790 = DEFINITIONAL_REPRESENTATION('',(#159791),#159795); +#159791 = LINE('',#159792,#159793); +#159792 = CARTESIAN_POINT('',(0.299582288316,-6.833759147787E-018)); +#159793 = VECTOR('',#159794,1.); +#159794 = DIRECTION('',(-5.571036036015E-035,-1.)); +#159795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159796 = PCURVE('',#159797,#159802); +#159797 = PLANE('',#159798); +#159798 = AXIS2_PLACEMENT_3D('',#159799,#159800,#159801); +#159799 = CARTESIAN_POINT('',(1.366751829557E-017,1.3675,1.953034905455) + ); +#159800 = DIRECTION('',(-8.407587502094E-035,0.121869343405, 0.992546151641)); -#157409 = DIRECTION('',(-1.350738024876E-052,-0.992546151641, +#159801 = DIRECTION('',(-1.350738024876E-052,-0.992546151641, 0.121869343405)); -#157410 = DEFINITIONAL_REPRESENTATION('',(#157411),#157415); -#157411 = LINE('',#157412,#157413); -#157412 = CARTESIAN_POINT('',(1.462749176199E-002,6.520553230683E-051)); -#157413 = VECTOR('',#157414,1.); -#157414 = DIRECTION('',(-1.218274344175E-051,-1.)); -#157415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157416 = ORIENTED_EDGE('',*,*,#157417,.T.); -#157417 = EDGE_CURVE('',#157390,#157267,#157418,.T.); -#157418 = SURFACE_CURVE('',#157419,(#157423,#157430),.PCURVE_S1.); -#157419 = LINE('',#157420,#157421); -#157420 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, +#159802 = DEFINITIONAL_REPRESENTATION('',(#159803),#159807); +#159803 = LINE('',#159804,#159805); +#159804 = CARTESIAN_POINT('',(1.462749176199E-002,6.520553230683E-051)); +#159805 = VECTOR('',#159806,1.); +#159806 = DIRECTION('',(-1.218274344175E-051,-1.)); +#159807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159808 = ORIENTED_EDGE('',*,*,#159809,.T.); +#159809 = EDGE_CURVE('',#159782,#159659,#159810,.T.); +#159810 = SURFACE_CURVE('',#159811,(#159815,#159822),.PCURVE_S1.); +#159811 = LINE('',#159812,#159813); +#159812 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, 1.954817548271)); -#157421 = VECTOR('',#157422,1.); -#157422 = DIRECTION('',(-8.109156679299E-002,0.660437812349, +#159813 = VECTOR('',#159814,1.); +#159814 = DIRECTION('',(-8.109156679299E-002,0.660437812349, -0.74648915184)); -#157423 = PCURVE('',#157247,#157424); -#157424 = DEFINITIONAL_REPRESENTATION('',(#157425),#157429); -#157425 = LINE('',#157426,#157427); -#157426 = CARTESIAN_POINT('',(0.299582288316,2.454817548271)); -#157427 = VECTOR('',#157428,1.); -#157428 = DIRECTION('',(-0.99670665584,-8.109156679299E-002)); -#157429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#159815 = PCURVE('',#159639,#159816); +#159816 = DEFINITIONAL_REPRESENTATION('',(#159817),#159821); +#159817 = LINE('',#159818,#159819); +#159818 = CARTESIAN_POINT('',(0.299582288316,2.454817548271)); +#159819 = VECTOR('',#159820,1.); +#159820 = DIRECTION('',(-0.99670665584,-8.109156679299E-002)); +#159821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157430 = PCURVE('',#157431,#157436); -#157431 = PLANE('',#157432); -#157432 = AXIS2_PLACEMENT_3D('',#157433,#157434,#157435); -#157433 = CARTESIAN_POINT('',(2.453034905455,1.3675,6.000565311804E-034) +#159822 = PCURVE('',#159823,#159828); +#159823 = PLANE('',#159824); +#159824 = AXIS2_PLACEMENT_3D('',#159825,#159826,#159827); +#159825 = CARTESIAN_POINT('',(2.453034905455,1.3675,6.000565311804E-034) ); -#157434 = DIRECTION('',(0.992546151641,0.121869343405, +#159826 = DIRECTION('',(0.992546151641,0.121869343405, 1.751580729603E-034)); -#157435 = DIRECTION('',(-0.121869343405,0.992546151641, +#159827 = DIRECTION('',(-0.121869343405,0.992546151641, 1.256773640537E-051)); -#157436 = DEFINITIONAL_REPRESENTATION('',(#157437),#157441); -#157437 = LINE('',#157438,#157439); -#157438 = CARTESIAN_POINT('',(-1.462749176199E-002,1.954817548271)); -#157439 = VECTOR('',#157440,1.); -#157440 = DIRECTION('',(0.665397585047,-0.74648915184)); -#157441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157442 = ADVANCED_FACE('',(#157443),#157168,.T.); -#157443 = FACE_BOUND('',#157444,.T.); -#157444 = EDGE_LOOP('',(#157445,#157513,#157514,#157515)); -#157445 = ORIENTED_EDGE('',*,*,#157446,.F.); -#157446 = EDGE_CURVE('',#157151,#157447,#157449,.T.); -#157447 = VERTEX_POINT('',#157448); -#157448 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#159828 = DEFINITIONAL_REPRESENTATION('',(#159829),#159833); +#159829 = LINE('',#159830,#159831); +#159830 = CARTESIAN_POINT('',(-1.462749176199E-002,1.954817548271)); +#159831 = VECTOR('',#159832,1.); +#159832 = DIRECTION('',(0.665397585047,-0.74648915184)); +#159833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159834 = ADVANCED_FACE('',(#159835),#159560,.T.); +#159835 = FACE_BOUND('',#159836,.T.); +#159836 = EDGE_LOOP('',(#159837,#159905,#159906,#159907)); +#159837 = ORIENTED_EDGE('',*,*,#159838,.F.); +#159838 = EDGE_CURVE('',#159543,#159839,#159841,.T.); +#159839 = VERTEX_POINT('',#159840); +#159840 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, -1.916851899618)); -#157449 = SURFACE_CURVE('',#157450,(#157455,#157484),.PCURVE_S1.); -#157450 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157451,#157452,#157453, -#157454),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159841 = SURFACE_CURVE('',#159842,(#159847,#159876),.PCURVE_S1.); +#159842 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159843,#159844,#159845, +#159846),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 4.712388980385,6.16101225954),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157451 = CARTESIAN_POINT('',(2.317597284454,1.75,-1.817597284454)); -#157452 = CARTESIAN_POINT('',(2.370651210801,1.75,-1.870651210801)); -#157453 = CARTESIAN_POINT('',(2.410386252449,1.714845404766, +#159843 = CARTESIAN_POINT('',(2.317597284454,1.75,-1.817597284454)); +#159844 = CARTESIAN_POINT('',(2.370651210801,1.75,-1.870651210801)); +#159845 = CARTESIAN_POINT('',(2.410386252449,1.714845404766, -1.910386252449)); -#157454 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#159846 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, -1.916851899618)); -#157455 = PCURVE('',#157168,#157456); -#157456 = DEFINITIONAL_REPRESENTATION('',(#157457),#157483); -#157457 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157458,#157459,#157460, - #157461,#157462,#157463,#157464,#157465,#157466,#157467,#157468, - #157469,#157470,#157471,#157472,#157473,#157474,#157475,#157476, - #157477,#157478,#157479,#157480,#157481,#157482),.UNSPECIFIED.,.F., +#159847 = PCURVE('',#159560,#159848); +#159848 = DEFINITIONAL_REPRESENTATION('',(#159849),#159875); +#159849 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159850,#159851,#159852, + #159853,#159854,#159855,#159856,#159857,#159858,#159859,#159860, + #159861,#159862,#159863,#159864,#159865,#159866,#159867,#159868, + #159869,#159870,#159871,#159872,#159873,#159874),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -194303,40 +197305,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208785,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#157458 = CARTESIAN_POINT('',(3.14159265359,-1.817597284454)); -#157459 = CARTESIAN_POINT('',(3.12151434906,-1.819604887973)); -#157460 = CARTESIAN_POINT('',(3.080895346177,-1.823667202921)); -#157461 = CARTESIAN_POINT('',(3.018662714711,-1.829867362922)); -#157462 = CARTESIAN_POINT('',(2.955203867684,-1.836141081531)); -#157463 = CARTESIAN_POINT('',(2.890614716316,-1.842449954658)); -#157464 = CARTESIAN_POINT('',(2.825002696965,-1.84875271237)); -#157465 = CARTESIAN_POINT('',(2.75848783298,-1.855005380421)); -#157466 = CARTESIAN_POINT('',(2.691201358285,-1.8611622468)); -#157467 = CARTESIAN_POINT('',(2.623284574238,-1.867176787865)); -#157468 = CARTESIAN_POINT('',(2.554887243423,-1.87300273832)); -#157469 = CARTESIAN_POINT('',(2.486165748071,-1.878595200332)); -#157470 = CARTESIAN_POINT('',(2.417281014012,-1.883911754912)); -#157471 = CARTESIAN_POINT('',(2.348396279953,-1.88891351567)); -#157472 = CARTESIAN_POINT('',(2.279674784602,-1.893566072075)); -#157473 = CARTESIAN_POINT('',(2.211277453786,-1.89784027431)); -#157474 = CARTESIAN_POINT('',(2.143360669739,-1.901712822216)); -#157475 = CARTESIAN_POINT('',(2.076074195044,-1.905166635447)); -#157476 = CARTESIAN_POINT('',(2.009559331059,-1.908190992063)); -#157477 = CARTESIAN_POINT('',(1.943947311708,-1.910781455939)); -#157478 = CARTESIAN_POINT('',(1.87935816034,-1.912939558585)); -#157479 = CARTESIAN_POINT('',(1.815899313313,-1.914672466212)); -#157480 = CARTESIAN_POINT('',(1.753666681847,-1.915991920127)); -#157481 = CARTESIAN_POINT('',(1.713047678964,-1.91660749833)); -#157482 = CARTESIAN_POINT('',(1.692969374434,-1.916851899618)); -#157483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157484 = PCURVE('',#157195,#157485); -#157485 = DEFINITIONAL_REPRESENTATION('',(#157486),#157512); -#157486 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157487,#157488,#157489, - #157490,#157491,#157492,#157493,#157494,#157495,#157496,#157497, - #157498,#157499,#157500,#157501,#157502,#157503,#157504,#157505, - #157506,#157507,#157508,#157509,#157510,#157511),.UNSPECIFIED.,.F., +#159850 = CARTESIAN_POINT('',(3.14159265359,-1.817597284454)); +#159851 = CARTESIAN_POINT('',(3.12151434906,-1.819604887973)); +#159852 = CARTESIAN_POINT('',(3.080895346177,-1.823667202921)); +#159853 = CARTESIAN_POINT('',(3.018662714711,-1.829867362922)); +#159854 = CARTESIAN_POINT('',(2.955203867684,-1.836141081531)); +#159855 = CARTESIAN_POINT('',(2.890614716316,-1.842449954658)); +#159856 = CARTESIAN_POINT('',(2.825002696965,-1.84875271237)); +#159857 = CARTESIAN_POINT('',(2.75848783298,-1.855005380421)); +#159858 = CARTESIAN_POINT('',(2.691201358285,-1.8611622468)); +#159859 = CARTESIAN_POINT('',(2.623284574238,-1.867176787865)); +#159860 = CARTESIAN_POINT('',(2.554887243423,-1.87300273832)); +#159861 = CARTESIAN_POINT('',(2.486165748071,-1.878595200332)); +#159862 = CARTESIAN_POINT('',(2.417281014012,-1.883911754912)); +#159863 = CARTESIAN_POINT('',(2.348396279953,-1.88891351567)); +#159864 = CARTESIAN_POINT('',(2.279674784602,-1.893566072075)); +#159865 = CARTESIAN_POINT('',(2.211277453786,-1.89784027431)); +#159866 = CARTESIAN_POINT('',(2.143360669739,-1.901712822216)); +#159867 = CARTESIAN_POINT('',(2.076074195044,-1.905166635447)); +#159868 = CARTESIAN_POINT('',(2.009559331059,-1.908190992063)); +#159869 = CARTESIAN_POINT('',(1.943947311708,-1.910781455939)); +#159870 = CARTESIAN_POINT('',(1.87935816034,-1.912939558585)); +#159871 = CARTESIAN_POINT('',(1.815899313313,-1.914672466212)); +#159872 = CARTESIAN_POINT('',(1.753666681847,-1.915991920127)); +#159873 = CARTESIAN_POINT('',(1.713047678964,-1.91660749833)); +#159874 = CARTESIAN_POINT('',(1.692969374434,-1.916851899618)); +#159875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159876 = PCURVE('',#159587,#159877); +#159877 = DEFINITIONAL_REPRESENTATION('',(#159878),#159904); +#159878 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159879,#159880,#159881, + #159882,#159883,#159884,#159885,#159886,#159887,#159888,#159889, + #159890,#159891,#159892,#159893,#159894,#159895,#159896,#159897, + #159898,#159899,#159900,#159901,#159902,#159903),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -194344,124 +197346,124 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208785,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#157487 = CARTESIAN_POINT('',(6.28318530718,2.317597284454)); -#157488 = CARTESIAN_POINT('',(6.26310700265,2.319604887973)); -#157489 = CARTESIAN_POINT('',(6.222487999767,2.323667202921)); -#157490 = CARTESIAN_POINT('',(6.160255368301,2.329867362922)); -#157491 = CARTESIAN_POINT('',(6.096796521274,2.336141081531)); -#157492 = CARTESIAN_POINT('',(6.032207369906,2.342449954658)); -#157493 = CARTESIAN_POINT('',(5.966595350555,2.34875271237)); -#157494 = CARTESIAN_POINT('',(5.90008048657,2.355005380421)); -#157495 = CARTESIAN_POINT('',(5.832794011875,2.3611622468)); -#157496 = CARTESIAN_POINT('',(5.764877227828,2.367176787865)); -#157497 = CARTESIAN_POINT('',(5.696479897012,2.37300273832)); -#157498 = CARTESIAN_POINT('',(5.627758401661,2.378595200332)); -#157499 = CARTESIAN_POINT('',(5.558873667602,2.383911754912)); -#157500 = CARTESIAN_POINT('',(5.489988933543,2.38891351567)); -#157501 = CARTESIAN_POINT('',(5.421267438192,2.393566072075)); -#157502 = CARTESIAN_POINT('',(5.352870107376,2.39784027431)); -#157503 = CARTESIAN_POINT('',(5.284953323329,2.401712822216)); -#157504 = CARTESIAN_POINT('',(5.217666848634,2.405166635447)); -#157505 = CARTESIAN_POINT('',(5.151151984649,2.408190992063)); -#157506 = CARTESIAN_POINT('',(5.085539965298,2.410781455939)); -#157507 = CARTESIAN_POINT('',(5.02095081393,2.412939558585)); -#157508 = CARTESIAN_POINT('',(4.957491966903,2.414672466212)); -#157509 = CARTESIAN_POINT('',(4.895259335437,2.415991920127)); -#157510 = CARTESIAN_POINT('',(4.854640332554,2.41660749833)); -#157511 = CARTESIAN_POINT('',(4.834562028024,2.416851899618)); -#157512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157513 = ORIENTED_EDGE('',*,*,#157150,.T.); -#157514 = ORIENTED_EDGE('',*,*,#157266,.T.); -#157515 = ORIENTED_EDGE('',*,*,#157516,.F.); -#157516 = EDGE_CURVE('',#157447,#157267,#157517,.T.); -#157517 = SURFACE_CURVE('',#157518,(#157522,#157528),.PCURVE_S1.); -#157518 = LINE('',#157519,#157520); -#157519 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#159879 = CARTESIAN_POINT('',(6.28318530718,2.317597284454)); +#159880 = CARTESIAN_POINT('',(6.26310700265,2.319604887973)); +#159881 = CARTESIAN_POINT('',(6.222487999767,2.323667202921)); +#159882 = CARTESIAN_POINT('',(6.160255368301,2.329867362922)); +#159883 = CARTESIAN_POINT('',(6.096796521274,2.336141081531)); +#159884 = CARTESIAN_POINT('',(6.032207369906,2.342449954658)); +#159885 = CARTESIAN_POINT('',(5.966595350555,2.34875271237)); +#159886 = CARTESIAN_POINT('',(5.90008048657,2.355005380421)); +#159887 = CARTESIAN_POINT('',(5.832794011875,2.3611622468)); +#159888 = CARTESIAN_POINT('',(5.764877227828,2.367176787865)); +#159889 = CARTESIAN_POINT('',(5.696479897012,2.37300273832)); +#159890 = CARTESIAN_POINT('',(5.627758401661,2.378595200332)); +#159891 = CARTESIAN_POINT('',(5.558873667602,2.383911754912)); +#159892 = CARTESIAN_POINT('',(5.489988933543,2.38891351567)); +#159893 = CARTESIAN_POINT('',(5.421267438192,2.393566072075)); +#159894 = CARTESIAN_POINT('',(5.352870107376,2.39784027431)); +#159895 = CARTESIAN_POINT('',(5.284953323329,2.401712822216)); +#159896 = CARTESIAN_POINT('',(5.217666848634,2.405166635447)); +#159897 = CARTESIAN_POINT('',(5.151151984649,2.408190992063)); +#159898 = CARTESIAN_POINT('',(5.085539965298,2.410781455939)); +#159899 = CARTESIAN_POINT('',(5.02095081393,2.412939558585)); +#159900 = CARTESIAN_POINT('',(4.957491966903,2.414672466212)); +#159901 = CARTESIAN_POINT('',(4.895259335437,2.415991920127)); +#159902 = CARTESIAN_POINT('',(4.854640332554,2.41660749833)); +#159903 = CARTESIAN_POINT('',(4.834562028024,2.416851899618)); +#159904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159905 = ORIENTED_EDGE('',*,*,#159542,.T.); +#159906 = ORIENTED_EDGE('',*,*,#159658,.T.); +#159907 = ORIENTED_EDGE('',*,*,#159908,.F.); +#159908 = EDGE_CURVE('',#159839,#159659,#159909,.T.); +#159909 = SURFACE_CURVE('',#159910,(#159914,#159920),.PCURVE_S1.); +#159910 = LINE('',#159911,#159912); +#159911 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, 6.000565311804E-034)); -#157520 = VECTOR('',#157521,1.); -#157521 = DIRECTION('',(-1.738524712456E-034,-2.134639934378E-035,1.)); -#157522 = PCURVE('',#157168,#157523); -#157523 = DEFINITIONAL_REPRESENTATION('',(#157524),#157527); -#157524 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157525,#157526), +#159912 = VECTOR('',#159913,1.); +#159913 = DIRECTION('',(-1.738524712456E-034,-2.134639934378E-035,1.)); +#159914 = PCURVE('',#159560,#159915); +#159915 = DEFINITIONAL_REPRESENTATION('',(#159916),#159919); +#159916 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159917,#159918), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.916851899618,1.605324426073), .PIECEWISE_BEZIER_KNOTS.); -#157525 = CARTESIAN_POINT('',(1.692969374434,-1.916851899618)); -#157526 = CARTESIAN_POINT('',(1.692969374434,1.605324426073)); -#157527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#159917 = CARTESIAN_POINT('',(1.692969374434,-1.916851899618)); +#159918 = CARTESIAN_POINT('',(1.692969374434,1.605324426073)); +#159919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157528 = PCURVE('',#157431,#157529); -#157529 = DEFINITIONAL_REPRESENTATION('',(#157530),#157534); -#157530 = LINE('',#157531,#157532); -#157531 = CARTESIAN_POINT('',(0.296899981782,3.161901533013E-050)); -#157532 = VECTOR('',#157533,1.); -#157533 = DIRECTION('',(3.832963844502E-051,1.)); -#157534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#159920 = PCURVE('',#159823,#159921); +#159921 = DEFINITIONAL_REPRESENTATION('',(#159922),#159926); +#159922 = LINE('',#159923,#159924); +#159923 = CARTESIAN_POINT('',(0.296899981782,3.161901533013E-050)); +#159924 = VECTOR('',#159925,1.); +#159925 = DIRECTION('',(3.832963844502E-051,1.)); +#159926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157535 = ADVANCED_FACE('',(#157536),#157195,.T.); -#157536 = FACE_BOUND('',#157537,.T.); -#157537 = EDGE_LOOP('',(#157538,#157565,#157631,#157632)); -#157538 = ORIENTED_EDGE('',*,*,#157539,.F.); -#157539 = EDGE_CURVE('',#157540,#157447,#157542,.T.); -#157540 = VERTEX_POINT('',#157541); -#157541 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159927 = ADVANCED_FACE('',(#159928),#159587,.T.); +#159928 = FACE_BOUND('',#159929,.T.); +#159929 = EDGE_LOOP('',(#159930,#159957,#160023,#160024)); +#159930 = ORIENTED_EDGE('',*,*,#159931,.F.); +#159931 = EDGE_CURVE('',#159932,#159839,#159934,.T.); +#159932 = VERTEX_POINT('',#159933); +#159933 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, -1.916851899618)); -#157542 = SURFACE_CURVE('',#157543,(#157547,#157553),.PCURVE_S1.); -#157543 = LINE('',#157544,#157545); -#157544 = CARTESIAN_POINT('',(1.366751829557E-017,1.662186934341, +#159934 = SURFACE_CURVE('',#159935,(#159939,#159945),.PCURVE_S1.); +#159935 = LINE('',#159936,#159937); +#159936 = CARTESIAN_POINT('',(1.366751829557E-017,1.662186934341, -1.916851899618)); -#157545 = VECTOR('',#157546,1.); -#157546 = DIRECTION('',(1.,1.024627168501E-035,-8.344918619791E-035)); -#157547 = PCURVE('',#157195,#157548); -#157548 = DEFINITIONAL_REPRESENTATION('',(#157549),#157552); -#157549 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157550,#157551), +#159937 = VECTOR('',#159938,1.); +#159938 = DIRECTION('',(1.,1.024627168501E-035,-8.344918619791E-035)); +#159939 = PCURVE('',#159587,#159940); +#159940 = DEFINITIONAL_REPRESENTATION('',(#159941),#159944); +#159941 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159942,#159943), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.416851899618,2.416851899618), .PIECEWISE_BEZIER_KNOTS.); -#157550 = CARTESIAN_POINT('',(4.834562028024,-2.416851899618)); -#157551 = CARTESIAN_POINT('',(4.834562028024,2.416851899618)); -#157552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#159942 = CARTESIAN_POINT('',(4.834562028024,-2.416851899618)); +#159943 = CARTESIAN_POINT('',(4.834562028024,2.416851899618)); +#159944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157553 = PCURVE('',#157554,#157559); -#157554 = PLANE('',#157555); -#157555 = AXIS2_PLACEMENT_3D('',#157556,#157557,#157558); -#157556 = CARTESIAN_POINT('',(1.366751829557E-017,1.3675,-1.953034905455 +#159945 = PCURVE('',#159946,#159951); +#159946 = PLANE('',#159947); +#159947 = AXIS2_PLACEMENT_3D('',#159948,#159949,#159950); +#159948 = CARTESIAN_POINT('',(1.366751829557E-017,1.3675,-1.953034905455 )); -#157557 = DIRECTION('',(-8.407587502094E-035,0.121869343405, +#159949 = DIRECTION('',(-8.407587502094E-035,0.121869343405, -0.992546151641)); -#157558 = DIRECTION('',(1.350738024876E-052,0.992546151641, +#159950 = DIRECTION('',(1.350738024876E-052,0.992546151641, 0.121869343405)); -#157559 = DEFINITIONAL_REPRESENTATION('',(#157560),#157564); -#157560 = LINE('',#157561,#157562); -#157561 = CARTESIAN_POINT('',(0.296899981782,-4.227418499593E-051)); -#157562 = VECTOR('',#157563,1.); -#157563 = DIRECTION('',(-1.218274344175E-051,1.)); -#157564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157565 = ORIENTED_EDGE('',*,*,#157566,.F.); -#157566 = EDGE_CURVE('',#157180,#157540,#157567,.T.); -#157567 = SURFACE_CURVE('',#157568,(#157573,#157602),.PCURVE_S1.); -#157568 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#157569,#157570,#157571, -#157572),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#159951 = DEFINITIONAL_REPRESENTATION('',(#159952),#159956); +#159952 = LINE('',#159953,#159954); +#159953 = CARTESIAN_POINT('',(0.296899981782,-4.227418499593E-051)); +#159954 = VECTOR('',#159955,1.); +#159955 = DIRECTION('',(-1.218274344175E-051,1.)); +#159956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159957 = ORIENTED_EDGE('',*,*,#159958,.F.); +#159958 = EDGE_CURVE('',#159572,#159932,#159959,.T.); +#159959 = SURFACE_CURVE('',#159960,(#159965,#159994),.PCURVE_S1.); +#159960 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#159961,#159962,#159963, +#159964),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 4.712388980385,6.16101225954),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#157569 = CARTESIAN_POINT('',(-2.317597284454,1.75,-1.817597284454)); -#157570 = CARTESIAN_POINT('',(-2.370651210801,1.75,-1.870651210801)); -#157571 = CARTESIAN_POINT('',(-2.410386252449,1.714845404766, +#159961 = CARTESIAN_POINT('',(-2.317597284454,1.75,-1.817597284454)); +#159962 = CARTESIAN_POINT('',(-2.370651210801,1.75,-1.870651210801)); +#159963 = CARTESIAN_POINT('',(-2.410386252449,1.714845404766, -1.910386252449)); -#157572 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159964 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, -1.916851899618)); -#157573 = PCURVE('',#157195,#157574); -#157574 = DEFINITIONAL_REPRESENTATION('',(#157575),#157601); -#157575 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157576,#157577,#157578, - #157579,#157580,#157581,#157582,#157583,#157584,#157585,#157586, - #157587,#157588,#157589,#157590,#157591,#157592,#157593,#157594, - #157595,#157596,#157597,#157598,#157599,#157600),.UNSPECIFIED.,.F., +#159965 = PCURVE('',#159587,#159966); +#159966 = DEFINITIONAL_REPRESENTATION('',(#159967),#159993); +#159967 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159968,#159969,#159970, + #159971,#159972,#159973,#159974,#159975,#159976,#159977,#159978, + #159979,#159980,#159981,#159982,#159983,#159984,#159985,#159986, + #159987,#159988,#159989,#159990,#159991,#159992),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -194469,40 +197471,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208785,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#157576 = CARTESIAN_POINT('',(6.28318530718,-2.317597284454)); -#157577 = CARTESIAN_POINT('',(6.26310700265,-2.319604887973)); -#157578 = CARTESIAN_POINT('',(6.222487999767,-2.323667202921)); -#157579 = CARTESIAN_POINT('',(6.160255368301,-2.329867362922)); -#157580 = CARTESIAN_POINT('',(6.096796521274,-2.336141081531)); -#157581 = CARTESIAN_POINT('',(6.032207369906,-2.342449954658)); -#157582 = CARTESIAN_POINT('',(5.966595350555,-2.34875271237)); -#157583 = CARTESIAN_POINT('',(5.90008048657,-2.355005380421)); -#157584 = CARTESIAN_POINT('',(5.832794011875,-2.3611622468)); -#157585 = CARTESIAN_POINT('',(5.764877227828,-2.367176787865)); -#157586 = CARTESIAN_POINT('',(5.696479897012,-2.37300273832)); -#157587 = CARTESIAN_POINT('',(5.627758401661,-2.378595200332)); -#157588 = CARTESIAN_POINT('',(5.558873667602,-2.383911754912)); -#157589 = CARTESIAN_POINT('',(5.489988933543,-2.38891351567)); -#157590 = CARTESIAN_POINT('',(5.421267438192,-2.393566072075)); -#157591 = CARTESIAN_POINT('',(5.352870107376,-2.39784027431)); -#157592 = CARTESIAN_POINT('',(5.284953323329,-2.401712822216)); -#157593 = CARTESIAN_POINT('',(5.217666848634,-2.405166635447)); -#157594 = CARTESIAN_POINT('',(5.151151984649,-2.408190992063)); -#157595 = CARTESIAN_POINT('',(5.085539965298,-2.410781455939)); -#157596 = CARTESIAN_POINT('',(5.02095081393,-2.412939558585)); -#157597 = CARTESIAN_POINT('',(4.957491966903,-2.414672466212)); -#157598 = CARTESIAN_POINT('',(4.895259335437,-2.415991920127)); -#157599 = CARTESIAN_POINT('',(4.854640332554,-2.41660749833)); -#157600 = CARTESIAN_POINT('',(4.834562028024,-2.416851899618)); -#157601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157602 = PCURVE('',#157222,#157603); -#157603 = DEFINITIONAL_REPRESENTATION('',(#157604),#157630); -#157604 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#157605,#157606,#157607, - #157608,#157609,#157610,#157611,#157612,#157613,#157614,#157615, - #157616,#157617,#157618,#157619,#157620,#157621,#157622,#157623, - #157624,#157625,#157626,#157627,#157628,#157629),.UNSPECIFIED.,.F., +#159968 = CARTESIAN_POINT('',(6.28318530718,-2.317597284454)); +#159969 = CARTESIAN_POINT('',(6.26310700265,-2.319604887973)); +#159970 = CARTESIAN_POINT('',(6.222487999767,-2.323667202921)); +#159971 = CARTESIAN_POINT('',(6.160255368301,-2.329867362922)); +#159972 = CARTESIAN_POINT('',(6.096796521274,-2.336141081531)); +#159973 = CARTESIAN_POINT('',(6.032207369906,-2.342449954658)); +#159974 = CARTESIAN_POINT('',(5.966595350555,-2.34875271237)); +#159975 = CARTESIAN_POINT('',(5.90008048657,-2.355005380421)); +#159976 = CARTESIAN_POINT('',(5.832794011875,-2.3611622468)); +#159977 = CARTESIAN_POINT('',(5.764877227828,-2.367176787865)); +#159978 = CARTESIAN_POINT('',(5.696479897012,-2.37300273832)); +#159979 = CARTESIAN_POINT('',(5.627758401661,-2.378595200332)); +#159980 = CARTESIAN_POINT('',(5.558873667602,-2.383911754912)); +#159981 = CARTESIAN_POINT('',(5.489988933543,-2.38891351567)); +#159982 = CARTESIAN_POINT('',(5.421267438192,-2.393566072075)); +#159983 = CARTESIAN_POINT('',(5.352870107376,-2.39784027431)); +#159984 = CARTESIAN_POINT('',(5.284953323329,-2.401712822216)); +#159985 = CARTESIAN_POINT('',(5.217666848634,-2.405166635447)); +#159986 = CARTESIAN_POINT('',(5.151151984649,-2.408190992063)); +#159987 = CARTESIAN_POINT('',(5.085539965298,-2.410781455939)); +#159988 = CARTESIAN_POINT('',(5.02095081393,-2.412939558585)); +#159989 = CARTESIAN_POINT('',(4.957491966903,-2.414672466212)); +#159990 = CARTESIAN_POINT('',(4.895259335437,-2.415991920127)); +#159991 = CARTESIAN_POINT('',(4.854640332554,-2.41660749833)); +#159992 = CARTESIAN_POINT('',(4.834562028024,-2.416851899618)); +#159993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#159994 = PCURVE('',#159614,#159995); +#159995 = DEFINITIONAL_REPRESENTATION('',(#159996),#160022); +#159996 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#159997,#159998,#159999, + #160000,#160001,#160002,#160003,#160004,#160005,#160006,#160007, + #160008,#160009,#160010,#160011,#160012,#160013,#160014,#160015, + #160016,#160017,#160018,#160019,#160020,#160021),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -194510,875 +197512,875 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208785,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#157605 = CARTESIAN_POINT('',(6.28318530718,1.817597284454)); -#157606 = CARTESIAN_POINT('',(6.26310700265,1.819604887973)); -#157607 = CARTESIAN_POINT('',(6.222487999767,1.823667202921)); -#157608 = CARTESIAN_POINT('',(6.160255368301,1.829867362922)); -#157609 = CARTESIAN_POINT('',(6.096796521274,1.836141081531)); -#157610 = CARTESIAN_POINT('',(6.032207369906,1.842449954658)); -#157611 = CARTESIAN_POINT('',(5.966595350555,1.84875271237)); -#157612 = CARTESIAN_POINT('',(5.90008048657,1.855005380421)); -#157613 = CARTESIAN_POINT('',(5.832794011875,1.8611622468)); -#157614 = CARTESIAN_POINT('',(5.764877227828,1.867176787865)); -#157615 = CARTESIAN_POINT('',(5.696479897012,1.87300273832)); -#157616 = CARTESIAN_POINT('',(5.627758401661,1.878595200332)); -#157617 = CARTESIAN_POINT('',(5.558873667602,1.883911754912)); -#157618 = CARTESIAN_POINT('',(5.489988933543,1.88891351567)); -#157619 = CARTESIAN_POINT('',(5.421267438192,1.893566072075)); -#157620 = CARTESIAN_POINT('',(5.352870107376,1.89784027431)); -#157621 = CARTESIAN_POINT('',(5.284953323329,1.901712822216)); -#157622 = CARTESIAN_POINT('',(5.217666848634,1.905166635447)); -#157623 = CARTESIAN_POINT('',(5.151151984649,1.908190992063)); -#157624 = CARTESIAN_POINT('',(5.085539965298,1.910781455939)); -#157625 = CARTESIAN_POINT('',(5.02095081393,1.912939558585)); -#157626 = CARTESIAN_POINT('',(4.957491966903,1.914672466212)); -#157627 = CARTESIAN_POINT('',(4.895259335437,1.915991920127)); -#157628 = CARTESIAN_POINT('',(4.854640332554,1.91660749833)); -#157629 = CARTESIAN_POINT('',(4.834562028024,1.916851899618)); -#157630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157631 = ORIENTED_EDGE('',*,*,#157179,.T.); -#157632 = ORIENTED_EDGE('',*,*,#157446,.T.); -#157633 = ADVANCED_FACE('',(#157634),#157222,.T.); -#157634 = FACE_BOUND('',#157635,.T.); -#157635 = EDGE_LOOP('',(#157636,#157637,#157657,#157658)); -#157636 = ORIENTED_EDGE('',*,*,#157566,.T.); -#157637 = ORIENTED_EDGE('',*,*,#157638,.F.); -#157638 = EDGE_CURVE('',#157315,#157540,#157639,.T.); -#157639 = SURFACE_CURVE('',#157640,(#157644,#157650),.PCURVE_S1.); -#157640 = LINE('',#157641,#157642); -#157641 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#159997 = CARTESIAN_POINT('',(6.28318530718,1.817597284454)); +#159998 = CARTESIAN_POINT('',(6.26310700265,1.819604887973)); +#159999 = CARTESIAN_POINT('',(6.222487999767,1.823667202921)); +#160000 = CARTESIAN_POINT('',(6.160255368301,1.829867362922)); +#160001 = CARTESIAN_POINT('',(6.096796521274,1.836141081531)); +#160002 = CARTESIAN_POINT('',(6.032207369906,1.842449954658)); +#160003 = CARTESIAN_POINT('',(5.966595350555,1.84875271237)); +#160004 = CARTESIAN_POINT('',(5.90008048657,1.855005380421)); +#160005 = CARTESIAN_POINT('',(5.832794011875,1.8611622468)); +#160006 = CARTESIAN_POINT('',(5.764877227828,1.867176787865)); +#160007 = CARTESIAN_POINT('',(5.696479897012,1.87300273832)); +#160008 = CARTESIAN_POINT('',(5.627758401661,1.878595200332)); +#160009 = CARTESIAN_POINT('',(5.558873667602,1.883911754912)); +#160010 = CARTESIAN_POINT('',(5.489988933543,1.88891351567)); +#160011 = CARTESIAN_POINT('',(5.421267438192,1.893566072075)); +#160012 = CARTESIAN_POINT('',(5.352870107376,1.89784027431)); +#160013 = CARTESIAN_POINT('',(5.284953323329,1.901712822216)); +#160014 = CARTESIAN_POINT('',(5.217666848634,1.905166635447)); +#160015 = CARTESIAN_POINT('',(5.151151984649,1.908190992063)); +#160016 = CARTESIAN_POINT('',(5.085539965298,1.910781455939)); +#160017 = CARTESIAN_POINT('',(5.02095081393,1.912939558585)); +#160018 = CARTESIAN_POINT('',(4.957491966903,1.914672466212)); +#160019 = CARTESIAN_POINT('',(4.895259335437,1.915991920127)); +#160020 = CARTESIAN_POINT('',(4.854640332554,1.91660749833)); +#160021 = CARTESIAN_POINT('',(4.834562028024,1.916851899618)); +#160022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160023 = ORIENTED_EDGE('',*,*,#159571,.T.); +#160024 = ORIENTED_EDGE('',*,*,#159838,.T.); +#160025 = ADVANCED_FACE('',(#160026),#159614,.T.); +#160026 = FACE_BOUND('',#160027,.T.); +#160027 = EDGE_LOOP('',(#160028,#160029,#160049,#160050)); +#160028 = ORIENTED_EDGE('',*,*,#159958,.T.); +#160029 = ORIENTED_EDGE('',*,*,#160030,.F.); +#160030 = EDGE_CURVE('',#159707,#159932,#160031,.T.); +#160031 = SURFACE_CURVE('',#160032,(#160036,#160042),.PCURVE_S1.); +#160032 = LINE('',#160033,#160034); +#160033 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, 6.000565311804E-034)); -#157642 = VECTOR('',#157643,1.); -#157643 = DIRECTION('',(-1.738524712456E-034,2.134639934378E-035,-1.)); -#157644 = PCURVE('',#157222,#157645); -#157645 = DEFINITIONAL_REPRESENTATION('',(#157646),#157649); -#157646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#157647,#157648), +#160034 = VECTOR('',#160035,1.); +#160035 = DIRECTION('',(-1.738524712456E-034,2.134639934378E-035,-1.)); +#160036 = PCURVE('',#159614,#160037); +#160037 = DEFINITIONAL_REPRESENTATION('',(#160038),#160041); +#160038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160039,#160040), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.605324426073,1.916851899618), .PIECEWISE_BEZIER_KNOTS.); -#157647 = CARTESIAN_POINT('',(4.834562028024,-1.605324426073)); -#157648 = CARTESIAN_POINT('',(4.834562028024,1.916851899618)); -#157649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157650 = PCURVE('',#157377,#157651); -#157651 = DEFINITIONAL_REPRESENTATION('',(#157652),#157656); -#157652 = LINE('',#157653,#157654); -#157653 = CARTESIAN_POINT('',(-0.296899981782,3.161901533013E-050)); -#157654 = VECTOR('',#157655,1.); -#157655 = DIRECTION('',(3.832963844502E-051,-1.)); -#157656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157657 = ORIENTED_EDGE('',*,*,#157314,.T.); -#157658 = ORIENTED_EDGE('',*,*,#157206,.T.); -#157659 = ADVANCED_FACE('',(#157660),#157405,.T.); -#157660 = FACE_BOUND('',#157661,.T.); -#157661 = EDGE_LOOP('',(#157662,#157692,#157713,#157714)); -#157662 = ORIENTED_EDGE('',*,*,#157663,.F.); -#157663 = EDGE_CURVE('',#157664,#157666,#157668,.T.); -#157664 = VERTEX_POINT('',#157665); -#157665 = CARTESIAN_POINT('',(2.5,0.985,2.)); -#157666 = VERTEX_POINT('',#157667); -#157667 = CARTESIAN_POINT('',(-2.5,0.985,2.)); -#157668 = SURFACE_CURVE('',#157669,(#157673,#157680),.PCURVE_S1.); -#157669 = LINE('',#157670,#157671); -#157670 = CARTESIAN_POINT('',(0.E+000,0.985,2.)); -#157671 = VECTOR('',#157672,1.); -#157672 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#157673 = PCURVE('',#157405,#157674); -#157674 = DEFINITIONAL_REPRESENTATION('',(#157675),#157679); -#157675 = LINE('',#157676,#157677); -#157676 = CARTESIAN_POINT('',(0.385372508238,-1.366751829557E-017)); -#157677 = VECTOR('',#157678,1.); -#157678 = DIRECTION('',(1.083200541688E-052,-1.)); -#157679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157680 = PCURVE('',#157681,#157686); -#157681 = PLANE('',#157682); -#157682 = AXIS2_PLACEMENT_3D('',#157683,#157684,#157685); -#157683 = CARTESIAN_POINT('',(0.E+000,0.15,2.)); -#157684 = DIRECTION('',(0.E+000,0.E+000,1.)); -#157685 = DIRECTION('',(1.,0.E+000,0.E+000)); -#157686 = DEFINITIONAL_REPRESENTATION('',(#157687),#157691); -#157687 = LINE('',#157688,#157689); -#157688 = CARTESIAN_POINT('',(0.E+000,0.835)); -#157689 = VECTOR('',#157690,1.); -#157690 = DIRECTION('',(-1.,0.E+000)); -#157691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157692 = ORIENTED_EDGE('',*,*,#157693,.F.); -#157693 = EDGE_CURVE('',#157390,#157664,#157694,.T.); -#157694 = SURFACE_CURVE('',#157695,(#157699,#157706),.PCURVE_S1.); -#157695 = LINE('',#157696,#157697); -#157696 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, +#160039 = CARTESIAN_POINT('',(4.834562028024,-1.605324426073)); +#160040 = CARTESIAN_POINT('',(4.834562028024,1.916851899618)); +#160041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160042 = PCURVE('',#159769,#160043); +#160043 = DEFINITIONAL_REPRESENTATION('',(#160044),#160048); +#160044 = LINE('',#160045,#160046); +#160045 = CARTESIAN_POINT('',(-0.296899981782,3.161901533013E-050)); +#160046 = VECTOR('',#160047,1.); +#160047 = DIRECTION('',(3.832963844502E-051,-1.)); +#160048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160049 = ORIENTED_EDGE('',*,*,#159706,.T.); +#160050 = ORIENTED_EDGE('',*,*,#159598,.T.); +#160051 = ADVANCED_FACE('',(#160052),#159797,.T.); +#160052 = FACE_BOUND('',#160053,.T.); +#160053 = EDGE_LOOP('',(#160054,#160084,#160105,#160106)); +#160054 = ORIENTED_EDGE('',*,*,#160055,.F.); +#160055 = EDGE_CURVE('',#160056,#160058,#160060,.T.); +#160056 = VERTEX_POINT('',#160057); +#160057 = CARTESIAN_POINT('',(2.5,0.985,2.)); +#160058 = VERTEX_POINT('',#160059); +#160059 = CARTESIAN_POINT('',(-2.5,0.985,2.)); +#160060 = SURFACE_CURVE('',#160061,(#160065,#160072),.PCURVE_S1.); +#160061 = LINE('',#160062,#160063); +#160062 = CARTESIAN_POINT('',(0.E+000,0.985,2.)); +#160063 = VECTOR('',#160064,1.); +#160064 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#160065 = PCURVE('',#159797,#160066); +#160066 = DEFINITIONAL_REPRESENTATION('',(#160067),#160071); +#160067 = LINE('',#160068,#160069); +#160068 = CARTESIAN_POINT('',(0.385372508238,-1.366751829557E-017)); +#160069 = VECTOR('',#160070,1.); +#160070 = DIRECTION('',(1.083200541688E-052,-1.)); +#160071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160072 = PCURVE('',#160073,#160078); +#160073 = PLANE('',#160074); +#160074 = AXIS2_PLACEMENT_3D('',#160075,#160076,#160077); +#160075 = CARTESIAN_POINT('',(0.E+000,0.15,2.)); +#160076 = DIRECTION('',(0.E+000,0.E+000,1.)); +#160077 = DIRECTION('',(1.,0.E+000,0.E+000)); +#160078 = DEFINITIONAL_REPRESENTATION('',(#160079),#160083); +#160079 = LINE('',#160080,#160081); +#160080 = CARTESIAN_POINT('',(0.E+000,0.835)); +#160081 = VECTOR('',#160082,1.); +#160082 = DIRECTION('',(-1.,0.E+000)); +#160083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160084 = ORIENTED_EDGE('',*,*,#160085,.F.); +#160085 = EDGE_CURVE('',#159782,#160056,#160086,.T.); +#160086 = SURFACE_CURVE('',#160087,(#160091,#160098),.PCURVE_S1.); +#160087 = LINE('',#160088,#160089); +#160088 = CARTESIAN_POINT('',(2.454817548271,1.352981539343, 1.954817548271)); -#157697 = VECTOR('',#157698,1.); -#157698 = DIRECTION('',(0.120974291151,-0.985256536015,0.120974291151)); -#157699 = PCURVE('',#157405,#157700); -#157700 = DEFINITIONAL_REPRESENTATION('',(#157701),#157705); -#157701 = LINE('',#157702,#157703); -#157702 = CARTESIAN_POINT('',(1.462749176199E-002,2.454817548271)); -#157703 = VECTOR('',#157704,1.); -#157704 = DIRECTION('',(0.992655640633,0.120974291151)); -#157705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157706 = PCURVE('',#157431,#157707); -#157707 = DEFINITIONAL_REPRESENTATION('',(#157708),#157712); -#157708 = LINE('',#157709,#157710); -#157709 = CARTESIAN_POINT('',(-1.462749176199E-002,1.954817548271)); -#157710 = VECTOR('',#157711,1.); -#157711 = DIRECTION('',(-0.992655640633,0.120974291151)); -#157712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157713 = ORIENTED_EDGE('',*,*,#157389,.T.); -#157714 = ORIENTED_EDGE('',*,*,#157715,.F.); -#157715 = EDGE_CURVE('',#157666,#157362,#157716,.T.); -#157716 = SURFACE_CURVE('',#157717,(#157721,#157728),.PCURVE_S1.); -#157717 = LINE('',#157718,#157719); -#157718 = CARTESIAN_POINT('',(-2.5,0.985,2.)); -#157719 = VECTOR('',#157720,1.); -#157720 = DIRECTION('',(0.120974291151,0.985256536015,-0.120974291151)); -#157721 = PCURVE('',#157405,#157722); -#157722 = DEFINITIONAL_REPRESENTATION('',(#157723),#157727); -#157723 = LINE('',#157724,#157725); -#157724 = CARTESIAN_POINT('',(0.385372508238,-2.5)); -#157725 = VECTOR('',#157726,1.); -#157726 = DIRECTION('',(-0.992655640633,0.120974291151)); -#157727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157728 = PCURVE('',#157377,#157729); -#157729 = DEFINITIONAL_REPRESENTATION('',(#157730),#157734); -#157730 = LINE('',#157731,#157732); -#157731 = CARTESIAN_POINT('',(0.385372508238,2.)); -#157732 = VECTOR('',#157733,1.); -#157733 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#157734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157735 = ADVANCED_FACE('',(#157736),#157431,.T.); -#157736 = FACE_BOUND('',#157737,.T.); -#157737 = EDGE_LOOP('',(#157738,#157766,#157787,#157788,#157789)); -#157738 = ORIENTED_EDGE('',*,*,#157739,.F.); -#157739 = EDGE_CURVE('',#157740,#157664,#157742,.T.); -#157740 = VERTEX_POINT('',#157741); -#157741 = CARTESIAN_POINT('',(2.5,0.985,-2.)); -#157742 = SURFACE_CURVE('',#157743,(#157747,#157754),.PCURVE_S1.); -#157743 = LINE('',#157744,#157745); -#157744 = CARTESIAN_POINT('',(2.5,0.985,0.E+000)); -#157745 = VECTOR('',#157746,1.); -#157746 = DIRECTION('',(0.E+000,0.E+000,1.)); -#157747 = PCURVE('',#157431,#157748); -#157748 = DEFINITIONAL_REPRESENTATION('',(#157749),#157753); -#157749 = LINE('',#157750,#157751); -#157750 = CARTESIAN_POINT('',(-0.385372508238,-6.000565311804E-034)); -#157751 = VECTOR('',#157752,1.); -#157752 = DIRECTION('',(1.226757239984E-051,1.)); -#157753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157754 = PCURVE('',#157755,#157760); -#157755 = PLANE('',#157756); -#157756 = AXIS2_PLACEMENT_3D('',#157757,#157758,#157759); -#157757 = CARTESIAN_POINT('',(2.5,0.15,0.E+000)); -#157758 = DIRECTION('',(1.,0.E+000,0.E+000)); -#157759 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#157760 = DEFINITIONAL_REPRESENTATION('',(#157761),#157765); -#157761 = LINE('',#157762,#157763); -#157762 = CARTESIAN_POINT('',(0.E+000,0.835)); -#157763 = VECTOR('',#157764,1.); -#157764 = DIRECTION('',(-1.,0.E+000)); -#157765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157766 = ORIENTED_EDGE('',*,*,#157767,.F.); -#157767 = EDGE_CURVE('',#157447,#157740,#157768,.T.); -#157768 = SURFACE_CURVE('',#157769,(#157773,#157780),.PCURVE_S1.); -#157769 = LINE('',#157770,#157771); -#157770 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, +#160089 = VECTOR('',#160090,1.); +#160090 = DIRECTION('',(0.120974291151,-0.985256536015,0.120974291151)); +#160091 = PCURVE('',#159797,#160092); +#160092 = DEFINITIONAL_REPRESENTATION('',(#160093),#160097); +#160093 = LINE('',#160094,#160095); +#160094 = CARTESIAN_POINT('',(1.462749176199E-002,2.454817548271)); +#160095 = VECTOR('',#160096,1.); +#160096 = DIRECTION('',(0.992655640633,0.120974291151)); +#160097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160098 = PCURVE('',#159823,#160099); +#160099 = DEFINITIONAL_REPRESENTATION('',(#160100),#160104); +#160100 = LINE('',#160101,#160102); +#160101 = CARTESIAN_POINT('',(-1.462749176199E-002,1.954817548271)); +#160102 = VECTOR('',#160103,1.); +#160103 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160105 = ORIENTED_EDGE('',*,*,#159781,.T.); +#160106 = ORIENTED_EDGE('',*,*,#160107,.F.); +#160107 = EDGE_CURVE('',#160058,#159754,#160108,.T.); +#160108 = SURFACE_CURVE('',#160109,(#160113,#160120),.PCURVE_S1.); +#160109 = LINE('',#160110,#160111); +#160110 = CARTESIAN_POINT('',(-2.5,0.985,2.)); +#160111 = VECTOR('',#160112,1.); +#160112 = DIRECTION('',(0.120974291151,0.985256536015,-0.120974291151)); +#160113 = PCURVE('',#159797,#160114); +#160114 = DEFINITIONAL_REPRESENTATION('',(#160115),#160119); +#160115 = LINE('',#160116,#160117); +#160116 = CARTESIAN_POINT('',(0.385372508238,-2.5)); +#160117 = VECTOR('',#160118,1.); +#160118 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160120 = PCURVE('',#159769,#160121); +#160121 = DEFINITIONAL_REPRESENTATION('',(#160122),#160126); +#160122 = LINE('',#160123,#160124); +#160123 = CARTESIAN_POINT('',(0.385372508238,2.)); +#160124 = VECTOR('',#160125,1.); +#160125 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160127 = ADVANCED_FACE('',(#160128),#159823,.T.); +#160128 = FACE_BOUND('',#160129,.T.); +#160129 = EDGE_LOOP('',(#160130,#160158,#160179,#160180,#160181)); +#160130 = ORIENTED_EDGE('',*,*,#160131,.F.); +#160131 = EDGE_CURVE('',#160132,#160056,#160134,.T.); +#160132 = VERTEX_POINT('',#160133); +#160133 = CARTESIAN_POINT('',(2.5,0.985,-2.)); +#160134 = SURFACE_CURVE('',#160135,(#160139,#160146),.PCURVE_S1.); +#160135 = LINE('',#160136,#160137); +#160136 = CARTESIAN_POINT('',(2.5,0.985,0.E+000)); +#160137 = VECTOR('',#160138,1.); +#160138 = DIRECTION('',(0.E+000,0.E+000,1.)); +#160139 = PCURVE('',#159823,#160140); +#160140 = DEFINITIONAL_REPRESENTATION('',(#160141),#160145); +#160141 = LINE('',#160142,#160143); +#160142 = CARTESIAN_POINT('',(-0.385372508238,-6.000565311804E-034)); +#160143 = VECTOR('',#160144,1.); +#160144 = DIRECTION('',(1.226757239984E-051,1.)); +#160145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160146 = PCURVE('',#160147,#160152); +#160147 = PLANE('',#160148); +#160148 = AXIS2_PLACEMENT_3D('',#160149,#160150,#160151); +#160149 = CARTESIAN_POINT('',(2.5,0.15,0.E+000)); +#160150 = DIRECTION('',(1.,0.E+000,0.E+000)); +#160151 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#160152 = DEFINITIONAL_REPRESENTATION('',(#160153),#160157); +#160153 = LINE('',#160154,#160155); +#160154 = CARTESIAN_POINT('',(0.E+000,0.835)); +#160155 = VECTOR('',#160156,1.); +#160156 = DIRECTION('',(-1.,0.E+000)); +#160157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160158 = ORIENTED_EDGE('',*,*,#160159,.F.); +#160159 = EDGE_CURVE('',#159839,#160132,#160160,.T.); +#160160 = SURFACE_CURVE('',#160161,(#160165,#160172),.PCURVE_S1.); +#160161 = LINE('',#160162,#160163); +#160162 = CARTESIAN_POINT('',(2.416851899618,1.662186934341, -1.916851899618)); -#157771 = VECTOR('',#157772,1.); -#157772 = DIRECTION('',(0.120974291151,-0.985256536015,-0.120974291151) - ); -#157773 = PCURVE('',#157431,#157774); -#157774 = DEFINITIONAL_REPRESENTATION('',(#157775),#157779); -#157775 = LINE('',#157776,#157777); -#157776 = CARTESIAN_POINT('',(0.296899981782,-1.916851899618)); -#157777 = VECTOR('',#157778,1.); -#157778 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#157779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157780 = PCURVE('',#157554,#157781); -#157781 = DEFINITIONAL_REPRESENTATION('',(#157782),#157786); -#157782 = LINE('',#157783,#157784); -#157783 = CARTESIAN_POINT('',(0.296899981782,2.416851899618)); -#157784 = VECTOR('',#157785,1.); -#157785 = DIRECTION('',(-0.992655640633,0.120974291151)); -#157786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157787 = ORIENTED_EDGE('',*,*,#157516,.T.); -#157788 = ORIENTED_EDGE('',*,*,#157417,.F.); -#157789 = ORIENTED_EDGE('',*,*,#157693,.T.); -#157790 = ADVANCED_FACE('',(#157791),#157554,.T.); -#157791 = FACE_BOUND('',#157792,.T.); -#157792 = EDGE_LOOP('',(#157793,#157821,#157842,#157843)); -#157793 = ORIENTED_EDGE('',*,*,#157794,.F.); -#157794 = EDGE_CURVE('',#157795,#157740,#157797,.T.); -#157795 = VERTEX_POINT('',#157796); -#157796 = CARTESIAN_POINT('',(-2.5,0.985,-2.)); -#157797 = SURFACE_CURVE('',#157798,(#157802,#157809),.PCURVE_S1.); -#157798 = LINE('',#157799,#157800); -#157799 = CARTESIAN_POINT('',(0.E+000,0.985,-2.)); -#157800 = VECTOR('',#157801,1.); -#157801 = DIRECTION('',(1.,0.E+000,0.E+000)); -#157802 = PCURVE('',#157554,#157803); -#157803 = DEFINITIONAL_REPRESENTATION('',(#157804),#157808); -#157804 = LINE('',#157805,#157806); -#157805 = CARTESIAN_POINT('',(-0.385372508238,-1.366751829557E-017)); -#157806 = VECTOR('',#157807,1.); -#157807 = DIRECTION('',(1.083200541688E-052,1.)); -#157808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157809 = PCURVE('',#157810,#157815); -#157810 = PLANE('',#157811); -#157811 = AXIS2_PLACEMENT_3D('',#157812,#157813,#157814); -#157812 = CARTESIAN_POINT('',(0.E+000,0.15,-2.)); -#157813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#157814 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#157815 = DEFINITIONAL_REPRESENTATION('',(#157816),#157820); -#157816 = LINE('',#157817,#157818); -#157817 = CARTESIAN_POINT('',(0.E+000,0.835)); -#157818 = VECTOR('',#157819,1.); -#157819 = DIRECTION('',(-1.,0.E+000)); -#157820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157821 = ORIENTED_EDGE('',*,*,#157822,.F.); -#157822 = EDGE_CURVE('',#157540,#157795,#157823,.T.); -#157823 = SURFACE_CURVE('',#157824,(#157828,#157835),.PCURVE_S1.); -#157824 = LINE('',#157825,#157826); -#157825 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, +#160163 = VECTOR('',#160164,1.); +#160164 = DIRECTION('',(0.120974291151,-0.985256536015,-0.120974291151) + ); +#160165 = PCURVE('',#159823,#160166); +#160166 = DEFINITIONAL_REPRESENTATION('',(#160167),#160171); +#160167 = LINE('',#160168,#160169); +#160168 = CARTESIAN_POINT('',(0.296899981782,-1.916851899618)); +#160169 = VECTOR('',#160170,1.); +#160170 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160172 = PCURVE('',#159946,#160173); +#160173 = DEFINITIONAL_REPRESENTATION('',(#160174),#160178); +#160174 = LINE('',#160175,#160176); +#160175 = CARTESIAN_POINT('',(0.296899981782,2.416851899618)); +#160176 = VECTOR('',#160177,1.); +#160177 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160179 = ORIENTED_EDGE('',*,*,#159908,.T.); +#160180 = ORIENTED_EDGE('',*,*,#159809,.F.); +#160181 = ORIENTED_EDGE('',*,*,#160085,.T.); +#160182 = ADVANCED_FACE('',(#160183),#159946,.T.); +#160183 = FACE_BOUND('',#160184,.T.); +#160184 = EDGE_LOOP('',(#160185,#160213,#160234,#160235)); +#160185 = ORIENTED_EDGE('',*,*,#160186,.F.); +#160186 = EDGE_CURVE('',#160187,#160132,#160189,.T.); +#160187 = VERTEX_POINT('',#160188); +#160188 = CARTESIAN_POINT('',(-2.5,0.985,-2.)); +#160189 = SURFACE_CURVE('',#160190,(#160194,#160201),.PCURVE_S1.); +#160190 = LINE('',#160191,#160192); +#160191 = CARTESIAN_POINT('',(0.E+000,0.985,-2.)); +#160192 = VECTOR('',#160193,1.); +#160193 = DIRECTION('',(1.,0.E+000,0.E+000)); +#160194 = PCURVE('',#159946,#160195); +#160195 = DEFINITIONAL_REPRESENTATION('',(#160196),#160200); +#160196 = LINE('',#160197,#160198); +#160197 = CARTESIAN_POINT('',(-0.385372508238,-1.366751829557E-017)); +#160198 = VECTOR('',#160199,1.); +#160199 = DIRECTION('',(1.083200541688E-052,1.)); +#160200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160201 = PCURVE('',#160202,#160207); +#160202 = PLANE('',#160203); +#160203 = AXIS2_PLACEMENT_3D('',#160204,#160205,#160206); +#160204 = CARTESIAN_POINT('',(0.E+000,0.15,-2.)); +#160205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#160206 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#160207 = DEFINITIONAL_REPRESENTATION('',(#160208),#160212); +#160208 = LINE('',#160209,#160210); +#160209 = CARTESIAN_POINT('',(0.E+000,0.835)); +#160210 = VECTOR('',#160211,1.); +#160211 = DIRECTION('',(-1.,0.E+000)); +#160212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160213 = ORIENTED_EDGE('',*,*,#160214,.F.); +#160214 = EDGE_CURVE('',#159932,#160187,#160215,.T.); +#160215 = SURFACE_CURVE('',#160216,(#160220,#160227),.PCURVE_S1.); +#160216 = LINE('',#160217,#160218); +#160217 = CARTESIAN_POINT('',(-2.416851899618,1.662186934341, -1.916851899618)); -#157826 = VECTOR('',#157827,1.); -#157827 = DIRECTION('',(-0.120974291151,-0.985256536015,-0.120974291151) - ); -#157828 = PCURVE('',#157554,#157829); -#157829 = DEFINITIONAL_REPRESENTATION('',(#157830),#157834); -#157830 = LINE('',#157831,#157832); -#157831 = CARTESIAN_POINT('',(0.296899981782,-2.416851899618)); -#157832 = VECTOR('',#157833,1.); -#157833 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#157834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157835 = PCURVE('',#157377,#157836); -#157836 = DEFINITIONAL_REPRESENTATION('',(#157837),#157841); -#157837 = LINE('',#157838,#157839); -#157838 = CARTESIAN_POINT('',(-0.296899981782,-1.916851899618)); -#157839 = VECTOR('',#157840,1.); -#157840 = DIRECTION('',(0.992655640633,-0.120974291151)); -#157841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157842 = ORIENTED_EDGE('',*,*,#157539,.T.); -#157843 = ORIENTED_EDGE('',*,*,#157767,.T.); -#157844 = ADVANCED_FACE('',(#157845),#157377,.T.); -#157845 = FACE_BOUND('',#157846,.T.); -#157846 = EDGE_LOOP('',(#157847,#157848,#157849,#157850,#157851)); -#157847 = ORIENTED_EDGE('',*,*,#157715,.T.); -#157848 = ORIENTED_EDGE('',*,*,#157361,.F.); -#157849 = ORIENTED_EDGE('',*,*,#157638,.T.); -#157850 = ORIENTED_EDGE('',*,*,#157822,.T.); -#157851 = ORIENTED_EDGE('',*,*,#157852,.F.); -#157852 = EDGE_CURVE('',#157666,#157795,#157853,.T.); -#157853 = SURFACE_CURVE('',#157854,(#157858,#157865),.PCURVE_S1.); -#157854 = LINE('',#157855,#157856); -#157855 = CARTESIAN_POINT('',(-2.5,0.985,0.E+000)); -#157856 = VECTOR('',#157857,1.); -#157857 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#157858 = PCURVE('',#157377,#157859); -#157859 = DEFINITIONAL_REPRESENTATION('',(#157860),#157864); -#157860 = LINE('',#157861,#157862); -#157861 = CARTESIAN_POINT('',(0.385372508238,-6.000565311804E-034)); -#157862 = VECTOR('',#157863,1.); -#157863 = DIRECTION('',(1.226757239984E-051,-1.)); -#157864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157865 = PCURVE('',#157866,#157871); -#157866 = PLANE('',#157867); -#157867 = AXIS2_PLACEMENT_3D('',#157868,#157869,#157870); -#157868 = CARTESIAN_POINT('',(-2.5,0.15,0.E+000)); -#157869 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#157870 = DIRECTION('',(0.E+000,0.E+000,1.)); -#157871 = DEFINITIONAL_REPRESENTATION('',(#157872),#157876); -#157872 = LINE('',#157873,#157874); -#157873 = CARTESIAN_POINT('',(0.E+000,0.835)); -#157874 = VECTOR('',#157875,1.); -#157875 = DIRECTION('',(-1.,0.E+000)); -#157876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157877 = ADVANCED_FACE('',(#157878),#157681,.T.); -#157878 = FACE_BOUND('',#157879,.T.); -#157879 = EDGE_LOOP('',(#157880,#157881,#157904,#157932)); -#157880 = ORIENTED_EDGE('',*,*,#157663,.T.); -#157881 = ORIENTED_EDGE('',*,*,#157882,.F.); -#157882 = EDGE_CURVE('',#157883,#157666,#157885,.T.); -#157883 = VERTEX_POINT('',#157884); -#157884 = CARTESIAN_POINT('',(-2.5,0.765,2.)); -#157885 = SURFACE_CURVE('',#157886,(#157890,#157897),.PCURVE_S1.); -#157886 = LINE('',#157887,#157888); -#157887 = CARTESIAN_POINT('',(-2.5,0.15,2.)); -#157888 = VECTOR('',#157889,1.); -#157889 = DIRECTION('',(0.E+000,1.,0.E+000)); -#157890 = PCURVE('',#157681,#157891); -#157891 = DEFINITIONAL_REPRESENTATION('',(#157892),#157896); -#157892 = LINE('',#157893,#157894); -#157893 = CARTESIAN_POINT('',(-2.5,0.E+000)); -#157894 = VECTOR('',#157895,1.); -#157895 = DIRECTION('',(0.E+000,1.)); -#157896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157897 = PCURVE('',#157866,#157898); -#157898 = DEFINITIONAL_REPRESENTATION('',(#157899),#157903); -#157899 = LINE('',#157900,#157901); -#157900 = CARTESIAN_POINT('',(2.,0.E+000)); -#157901 = VECTOR('',#157902,1.); -#157902 = DIRECTION('',(0.E+000,1.)); -#157903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157904 = ORIENTED_EDGE('',*,*,#157905,.F.); -#157905 = EDGE_CURVE('',#157906,#157883,#157908,.T.); -#157906 = VERTEX_POINT('',#157907); -#157907 = CARTESIAN_POINT('',(2.5,0.765,2.)); -#157908 = SURFACE_CURVE('',#157909,(#157913,#157920),.PCURVE_S1.); -#157909 = LINE('',#157910,#157911); -#157910 = CARTESIAN_POINT('',(1.366751829557E-017,0.765,2.)); -#157911 = VECTOR('',#157912,1.); -#157912 = DIRECTION('',(-1.,-1.024627168501E-035,8.344918619791E-035)); -#157913 = PCURVE('',#157681,#157914); -#157914 = DEFINITIONAL_REPRESENTATION('',(#157915),#157919); -#157915 = LINE('',#157916,#157917); -#157916 = CARTESIAN_POINT('',(1.366751829557E-017,0.615)); -#157917 = VECTOR('',#157918,1.); -#157918 = DIRECTION('',(-1.,-1.024627168501E-035)); -#157919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157920 = PCURVE('',#157921,#157926); -#157921 = PLANE('',#157922); -#157922 = AXIS2_PLACEMENT_3D('',#157923,#157924,#157925); -#157923 = CARTESIAN_POINT('',(1.366751829557E-017,0.4575,1.962243747522) - ); -#157924 = DIRECTION('',(8.407587502094E-035,-0.121869343405, - 0.992546151641)); -#157925 = DIRECTION('',(-4.815674697383E-052,-0.992546151641, - -0.121869343405)); -#157926 = DEFINITIONAL_REPRESENTATION('',(#157927),#157931); -#157927 = LINE('',#157928,#157929); -#157928 = CARTESIAN_POINT('',(-0.309809271329,-1.50082002764E-050)); -#157929 = VECTOR('',#157930,1.); -#157930 = DIRECTION('',(8.776534509458E-052,-1.)); -#157931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157932 = ORIENTED_EDGE('',*,*,#157933,.F.); -#157933 = EDGE_CURVE('',#157664,#157906,#157934,.T.); -#157934 = SURFACE_CURVE('',#157935,(#157939,#157946),.PCURVE_S1.); -#157935 = LINE('',#157936,#157937); -#157936 = CARTESIAN_POINT('',(2.5,0.15,2.)); -#157937 = VECTOR('',#157938,1.); -#157938 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#157939 = PCURVE('',#157681,#157940); -#157940 = DEFINITIONAL_REPRESENTATION('',(#157941),#157945); -#157941 = LINE('',#157942,#157943); -#157942 = CARTESIAN_POINT('',(2.5,0.E+000)); -#157943 = VECTOR('',#157944,1.); -#157944 = DIRECTION('',(0.E+000,-1.)); -#157945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157946 = PCURVE('',#157755,#157947); -#157947 = DEFINITIONAL_REPRESENTATION('',(#157948),#157952); -#157948 = LINE('',#157949,#157950); -#157949 = CARTESIAN_POINT('',(-2.,0.E+000)); -#157950 = VECTOR('',#157951,1.); -#157951 = DIRECTION('',(0.E+000,-1.)); -#157952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#157953 = ADVANCED_FACE('',(#157954),#157755,.T.); -#157954 = FACE_BOUND('',#157955,.T.); -#157955 = EDGE_LOOP('',(#157956,#157957,#157958,#157986)); -#157956 = ORIENTED_EDGE('',*,*,#157739,.T.); -#157957 = ORIENTED_EDGE('',*,*,#157933,.T.); -#157958 = ORIENTED_EDGE('',*,*,#157959,.F.); -#157959 = EDGE_CURVE('',#157960,#157906,#157962,.T.); -#157960 = VERTEX_POINT('',#157961); -#157961 = CARTESIAN_POINT('',(2.5,0.765,-2.)); -#157962 = SURFACE_CURVE('',#157963,(#157967,#157974),.PCURVE_S1.); -#157963 = LINE('',#157964,#157965); -#157964 = CARTESIAN_POINT('',(2.5,0.765,4.419578044023E-034)); -#157965 = VECTOR('',#157966,1.); -#157966 = DIRECTION('',(1.738524712456E-034,-2.134639934378E-035,1.)); -#157967 = PCURVE('',#157755,#157968); -#157968 = DEFINITIONAL_REPRESENTATION('',(#157969),#157973); -#157969 = LINE('',#157970,#157971); -#157970 = CARTESIAN_POINT('',(-4.419578044023E-034,0.615)); -#157971 = VECTOR('',#157972,1.); -#157972 = DIRECTION('',(-1.,-2.134639934378E-035)); -#157973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160218 = VECTOR('',#160219,1.); +#160219 = DIRECTION('',(-0.120974291151,-0.985256536015,-0.120974291151) + ); +#160220 = PCURVE('',#159946,#160221); +#160221 = DEFINITIONAL_REPRESENTATION('',(#160222),#160226); +#160222 = LINE('',#160223,#160224); +#160223 = CARTESIAN_POINT('',(0.296899981782,-2.416851899618)); +#160224 = VECTOR('',#160225,1.); +#160225 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157974 = PCURVE('',#157975,#157980); -#157975 = PLANE('',#157976); -#157976 = AXIS2_PLACEMENT_3D('',#157977,#157978,#157979); -#157977 = CARTESIAN_POINT('',(2.462243747522,0.4575,4.419578044023E-034) - ); -#157978 = DIRECTION('',(0.992546151641,-0.121869343405, +#160227 = PCURVE('',#159769,#160228); +#160228 = DEFINITIONAL_REPRESENTATION('',(#160229),#160233); +#160229 = LINE('',#160230,#160231); +#160230 = CARTESIAN_POINT('',(-0.296899981782,-1.916851899618)); +#160231 = VECTOR('',#160232,1.); +#160232 = DIRECTION('',(0.992655640633,-0.120974291151)); +#160233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160234 = ORIENTED_EDGE('',*,*,#159931,.T.); +#160235 = ORIENTED_EDGE('',*,*,#160159,.T.); +#160236 = ADVANCED_FACE('',(#160237),#159769,.T.); +#160237 = FACE_BOUND('',#160238,.T.); +#160238 = EDGE_LOOP('',(#160239,#160240,#160241,#160242,#160243)); +#160239 = ORIENTED_EDGE('',*,*,#160107,.T.); +#160240 = ORIENTED_EDGE('',*,*,#159753,.F.); +#160241 = ORIENTED_EDGE('',*,*,#160030,.T.); +#160242 = ORIENTED_EDGE('',*,*,#160214,.T.); +#160243 = ORIENTED_EDGE('',*,*,#160244,.F.); +#160244 = EDGE_CURVE('',#160058,#160187,#160245,.T.); +#160245 = SURFACE_CURVE('',#160246,(#160250,#160257),.PCURVE_S1.); +#160246 = LINE('',#160247,#160248); +#160247 = CARTESIAN_POINT('',(-2.5,0.985,0.E+000)); +#160248 = VECTOR('',#160249,1.); +#160249 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#160250 = PCURVE('',#159769,#160251); +#160251 = DEFINITIONAL_REPRESENTATION('',(#160252),#160256); +#160252 = LINE('',#160253,#160254); +#160253 = CARTESIAN_POINT('',(0.385372508238,-6.000565311804E-034)); +#160254 = VECTOR('',#160255,1.); +#160255 = DIRECTION('',(1.226757239984E-051,-1.)); +#160256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160257 = PCURVE('',#160258,#160263); +#160258 = PLANE('',#160259); +#160259 = AXIS2_PLACEMENT_3D('',#160260,#160261,#160262); +#160260 = CARTESIAN_POINT('',(-2.5,0.15,0.E+000)); +#160261 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#160262 = DIRECTION('',(0.E+000,0.E+000,1.)); +#160263 = DEFINITIONAL_REPRESENTATION('',(#160264),#160268); +#160264 = LINE('',#160265,#160266); +#160265 = CARTESIAN_POINT('',(0.E+000,0.835)); +#160266 = VECTOR('',#160267,1.); +#160267 = DIRECTION('',(-1.,0.E+000)); +#160268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160269 = ADVANCED_FACE('',(#160270),#160073,.T.); +#160270 = FACE_BOUND('',#160271,.T.); +#160271 = EDGE_LOOP('',(#160272,#160273,#160296,#160324)); +#160272 = ORIENTED_EDGE('',*,*,#160055,.T.); +#160273 = ORIENTED_EDGE('',*,*,#160274,.F.); +#160274 = EDGE_CURVE('',#160275,#160058,#160277,.T.); +#160275 = VERTEX_POINT('',#160276); +#160276 = CARTESIAN_POINT('',(-2.5,0.765,2.)); +#160277 = SURFACE_CURVE('',#160278,(#160282,#160289),.PCURVE_S1.); +#160278 = LINE('',#160279,#160280); +#160279 = CARTESIAN_POINT('',(-2.5,0.15,2.)); +#160280 = VECTOR('',#160281,1.); +#160281 = DIRECTION('',(0.E+000,1.,0.E+000)); +#160282 = PCURVE('',#160073,#160283); +#160283 = DEFINITIONAL_REPRESENTATION('',(#160284),#160288); +#160284 = LINE('',#160285,#160286); +#160285 = CARTESIAN_POINT('',(-2.5,0.E+000)); +#160286 = VECTOR('',#160287,1.); +#160287 = DIRECTION('',(0.E+000,1.)); +#160288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160289 = PCURVE('',#160258,#160290); +#160290 = DEFINITIONAL_REPRESENTATION('',(#160291),#160295); +#160291 = LINE('',#160292,#160293); +#160292 = CARTESIAN_POINT('',(2.,0.E+000)); +#160293 = VECTOR('',#160294,1.); +#160294 = DIRECTION('',(0.E+000,1.)); +#160295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160296 = ORIENTED_EDGE('',*,*,#160297,.F.); +#160297 = EDGE_CURVE('',#160298,#160275,#160300,.T.); +#160298 = VERTEX_POINT('',#160299); +#160299 = CARTESIAN_POINT('',(2.5,0.765,2.)); +#160300 = SURFACE_CURVE('',#160301,(#160305,#160312),.PCURVE_S1.); +#160301 = LINE('',#160302,#160303); +#160302 = CARTESIAN_POINT('',(1.366751829557E-017,0.765,2.)); +#160303 = VECTOR('',#160304,1.); +#160304 = DIRECTION('',(-1.,-1.024627168501E-035,8.344918619791E-035)); +#160305 = PCURVE('',#160073,#160306); +#160306 = DEFINITIONAL_REPRESENTATION('',(#160307),#160311); +#160307 = LINE('',#160308,#160309); +#160308 = CARTESIAN_POINT('',(1.366751829557E-017,0.615)); +#160309 = VECTOR('',#160310,1.); +#160310 = DIRECTION('',(-1.,-1.024627168501E-035)); +#160311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160312 = PCURVE('',#160313,#160318); +#160313 = PLANE('',#160314); +#160314 = AXIS2_PLACEMENT_3D('',#160315,#160316,#160317); +#160315 = CARTESIAN_POINT('',(1.366751829557E-017,0.4575,1.962243747522) + ); +#160316 = DIRECTION('',(8.407587502094E-035,-0.121869343405, + 0.992546151641)); +#160317 = DIRECTION('',(-4.815674697383E-052,-0.992546151641, + -0.121869343405)); +#160318 = DEFINITIONAL_REPRESENTATION('',(#160319),#160323); +#160319 = LINE('',#160320,#160321); +#160320 = CARTESIAN_POINT('',(-0.309809271329,-1.50082002764E-050)); +#160321 = VECTOR('',#160322,1.); +#160322 = DIRECTION('',(8.776534509458E-052,-1.)); +#160323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160324 = ORIENTED_EDGE('',*,*,#160325,.F.); +#160325 = EDGE_CURVE('',#160056,#160298,#160326,.T.); +#160326 = SURFACE_CURVE('',#160327,(#160331,#160338),.PCURVE_S1.); +#160327 = LINE('',#160328,#160329); +#160328 = CARTESIAN_POINT('',(2.5,0.15,2.)); +#160329 = VECTOR('',#160330,1.); +#160330 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#160331 = PCURVE('',#160073,#160332); +#160332 = DEFINITIONAL_REPRESENTATION('',(#160333),#160337); +#160333 = LINE('',#160334,#160335); +#160334 = CARTESIAN_POINT('',(2.5,0.E+000)); +#160335 = VECTOR('',#160336,1.); +#160336 = DIRECTION('',(0.E+000,-1.)); +#160337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160338 = PCURVE('',#160147,#160339); +#160339 = DEFINITIONAL_REPRESENTATION('',(#160340),#160344); +#160340 = LINE('',#160341,#160342); +#160341 = CARTESIAN_POINT('',(-2.,0.E+000)); +#160342 = VECTOR('',#160343,1.); +#160343 = DIRECTION('',(0.E+000,-1.)); +#160344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160345 = ADVANCED_FACE('',(#160346),#160147,.T.); +#160346 = FACE_BOUND('',#160347,.T.); +#160347 = EDGE_LOOP('',(#160348,#160349,#160350,#160378)); +#160348 = ORIENTED_EDGE('',*,*,#160131,.T.); +#160349 = ORIENTED_EDGE('',*,*,#160325,.T.); +#160350 = ORIENTED_EDGE('',*,*,#160351,.F.); +#160351 = EDGE_CURVE('',#160352,#160298,#160354,.T.); +#160352 = VERTEX_POINT('',#160353); +#160353 = CARTESIAN_POINT('',(2.5,0.765,-2.)); +#160354 = SURFACE_CURVE('',#160355,(#160359,#160366),.PCURVE_S1.); +#160355 = LINE('',#160356,#160357); +#160356 = CARTESIAN_POINT('',(2.5,0.765,4.419578044023E-034)); +#160357 = VECTOR('',#160358,1.); +#160358 = DIRECTION('',(1.738524712456E-034,-2.134639934378E-035,1.)); +#160359 = PCURVE('',#160147,#160360); +#160360 = DEFINITIONAL_REPRESENTATION('',(#160361),#160365); +#160361 = LINE('',#160362,#160363); +#160362 = CARTESIAN_POINT('',(-4.419578044023E-034,0.615)); +#160363 = VECTOR('',#160364,1.); +#160364 = DIRECTION('',(-1.,-2.134639934378E-035)); +#160365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160366 = PCURVE('',#160367,#160372); +#160367 = PLANE('',#160368); +#160368 = AXIS2_PLACEMENT_3D('',#160369,#160370,#160371); +#160369 = CARTESIAN_POINT('',(2.462243747522,0.4575,4.419578044023E-034) + ); +#160370 = DIRECTION('',(0.992546151641,-0.121869343405, -1.751580729603E-034)); -#157979 = DIRECTION('',(0.121869343405,0.992546151641, +#160371 = DIRECTION('',(0.121869343405,0.992546151641, 1.256773640537E-051)); -#157980 = DEFINITIONAL_REPRESENTATION('',(#157981),#157985); -#157981 = LINE('',#157982,#157983); -#157982 = CARTESIAN_POINT('',(0.309809271329,-2.508783808811E-050)); -#157983 = VECTOR('',#157984,1.); -#157984 = DIRECTION('',(3.832963844502E-051,1.)); -#157985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160372 = DEFINITIONAL_REPRESENTATION('',(#160373),#160377); +#160373 = LINE('',#160374,#160375); +#160374 = CARTESIAN_POINT('',(0.309809271329,-2.508783808811E-050)); +#160375 = VECTOR('',#160376,1.); +#160376 = DIRECTION('',(3.832963844502E-051,1.)); +#160377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160378 = ORIENTED_EDGE('',*,*,#160379,.F.); +#160379 = EDGE_CURVE('',#160132,#160352,#160380,.T.); +#160380 = SURFACE_CURVE('',#160381,(#160385,#160392),.PCURVE_S1.); +#160381 = LINE('',#160382,#160383); +#160382 = CARTESIAN_POINT('',(2.5,0.15,-2.)); +#160383 = VECTOR('',#160384,1.); +#160384 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#160385 = PCURVE('',#160147,#160386); +#160386 = DEFINITIONAL_REPRESENTATION('',(#160387),#160391); +#160387 = LINE('',#160388,#160389); +#160388 = CARTESIAN_POINT('',(2.,0.E+000)); +#160389 = VECTOR('',#160390,1.); +#160390 = DIRECTION('',(0.E+000,-1.)); +#160391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160392 = PCURVE('',#160202,#160393); +#160393 = DEFINITIONAL_REPRESENTATION('',(#160394),#160398); +#160394 = LINE('',#160395,#160396); +#160395 = CARTESIAN_POINT('',(-2.5,0.E+000)); +#160396 = VECTOR('',#160397,1.); +#160397 = DIRECTION('',(0.E+000,-1.)); +#160398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160399 = ADVANCED_FACE('',(#160400),#160202,.T.); +#160400 = FACE_BOUND('',#160401,.T.); +#160401 = EDGE_LOOP('',(#160402,#160403,#160404,#160432)); +#160402 = ORIENTED_EDGE('',*,*,#160186,.T.); +#160403 = ORIENTED_EDGE('',*,*,#160379,.T.); +#160404 = ORIENTED_EDGE('',*,*,#160405,.F.); +#160405 = EDGE_CURVE('',#160406,#160352,#160408,.T.); +#160406 = VERTEX_POINT('',#160407); +#160407 = CARTESIAN_POINT('',(-2.5,0.765,-2.)); +#160408 = SURFACE_CURVE('',#160409,(#160413,#160420),.PCURVE_S1.); +#160409 = LINE('',#160410,#160411); +#160410 = CARTESIAN_POINT('',(1.366751829557E-017,0.765,-2.)); +#160411 = VECTOR('',#160412,1.); +#160412 = DIRECTION('',(1.,1.024627168501E-035,8.344918619791E-035)); +#160413 = PCURVE('',#160202,#160414); +#160414 = DEFINITIONAL_REPRESENTATION('',(#160415),#160419); +#160415 = LINE('',#160416,#160417); +#160416 = CARTESIAN_POINT('',(-1.366751829557E-017,0.615)); +#160417 = VECTOR('',#160418,1.); +#160418 = DIRECTION('',(-1.,1.024627168501E-035)); +#160419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#157986 = ORIENTED_EDGE('',*,*,#157987,.F.); -#157987 = EDGE_CURVE('',#157740,#157960,#157988,.T.); -#157988 = SURFACE_CURVE('',#157989,(#157993,#158000),.PCURVE_S1.); -#157989 = LINE('',#157990,#157991); -#157990 = CARTESIAN_POINT('',(2.5,0.15,-2.)); -#157991 = VECTOR('',#157992,1.); -#157992 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#157993 = PCURVE('',#157755,#157994); -#157994 = DEFINITIONAL_REPRESENTATION('',(#157995),#157999); -#157995 = LINE('',#157996,#157997); -#157996 = CARTESIAN_POINT('',(2.,0.E+000)); -#157997 = VECTOR('',#157998,1.); -#157998 = DIRECTION('',(0.E+000,-1.)); -#157999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158000 = PCURVE('',#157810,#158001); -#158001 = DEFINITIONAL_REPRESENTATION('',(#158002),#158006); -#158002 = LINE('',#158003,#158004); -#158003 = CARTESIAN_POINT('',(-2.5,0.E+000)); -#158004 = VECTOR('',#158005,1.); -#158005 = DIRECTION('',(0.E+000,-1.)); -#158006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158007 = ADVANCED_FACE('',(#158008),#157810,.T.); -#158008 = FACE_BOUND('',#158009,.T.); -#158009 = EDGE_LOOP('',(#158010,#158011,#158012,#158040)); -#158010 = ORIENTED_EDGE('',*,*,#157794,.T.); -#158011 = ORIENTED_EDGE('',*,*,#157987,.T.); -#158012 = ORIENTED_EDGE('',*,*,#158013,.F.); -#158013 = EDGE_CURVE('',#158014,#157960,#158016,.T.); -#158014 = VERTEX_POINT('',#158015); -#158015 = CARTESIAN_POINT('',(-2.5,0.765,-2.)); -#158016 = SURFACE_CURVE('',#158017,(#158021,#158028),.PCURVE_S1.); -#158017 = LINE('',#158018,#158019); -#158018 = CARTESIAN_POINT('',(1.366751829557E-017,0.765,-2.)); -#158019 = VECTOR('',#158020,1.); -#158020 = DIRECTION('',(1.,1.024627168501E-035,8.344918619791E-035)); -#158021 = PCURVE('',#157810,#158022); -#158022 = DEFINITIONAL_REPRESENTATION('',(#158023),#158027); -#158023 = LINE('',#158024,#158025); -#158024 = CARTESIAN_POINT('',(-1.366751829557E-017,0.615)); -#158025 = VECTOR('',#158026,1.); -#158026 = DIRECTION('',(-1.,1.024627168501E-035)); -#158027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158028 = PCURVE('',#158029,#158034); -#158029 = PLANE('',#158030); -#158030 = AXIS2_PLACEMENT_3D('',#158031,#158032,#158033); -#158031 = CARTESIAN_POINT('',(1.366751829557E-017,0.4575,-1.962243747522 +#160420 = PCURVE('',#160421,#160426); +#160421 = PLANE('',#160422); +#160422 = AXIS2_PLACEMENT_3D('',#160423,#160424,#160425); +#160423 = CARTESIAN_POINT('',(1.366751829557E-017,0.4575,-1.962243747522 )); -#158032 = DIRECTION('',(8.407587502094E-035,-0.121869343405, +#160424 = DIRECTION('',(8.407587502094E-035,-0.121869343405, -0.992546151641)); -#158033 = DIRECTION('',(4.815674697383E-052,0.992546151641, +#160425 = DIRECTION('',(4.815674697383E-052,0.992546151641, -0.121869343405)); -#158034 = DEFINITIONAL_REPRESENTATION('',(#158035),#158039); -#158035 = LINE('',#158036,#158037); -#158036 = CARTESIAN_POINT('',(0.309809271329,-1.50082002764E-050)); -#158037 = VECTOR('',#158038,1.); -#158038 = DIRECTION('',(8.776534509458E-052,1.)); -#158039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158040 = ORIENTED_EDGE('',*,*,#158041,.F.); -#158041 = EDGE_CURVE('',#157795,#158014,#158042,.T.); -#158042 = SURFACE_CURVE('',#158043,(#158047,#158054),.PCURVE_S1.); -#158043 = LINE('',#158044,#158045); -#158044 = CARTESIAN_POINT('',(-2.5,0.15,-2.)); -#158045 = VECTOR('',#158046,1.); -#158046 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#158047 = PCURVE('',#157810,#158048); -#158048 = DEFINITIONAL_REPRESENTATION('',(#158049),#158053); -#158049 = LINE('',#158050,#158051); -#158050 = CARTESIAN_POINT('',(2.5,0.E+000)); -#158051 = VECTOR('',#158052,1.); -#158052 = DIRECTION('',(0.E+000,-1.)); -#158053 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158054 = PCURVE('',#157866,#158055); -#158055 = DEFINITIONAL_REPRESENTATION('',(#158056),#158060); -#158056 = LINE('',#158057,#158058); -#158057 = CARTESIAN_POINT('',(-2.,0.E+000)); -#158058 = VECTOR('',#158059,1.); -#158059 = DIRECTION('',(0.E+000,-1.)); -#158060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158061 = ADVANCED_FACE('',(#158062),#157866,.T.); -#158062 = FACE_BOUND('',#158063,.T.); -#158063 = EDGE_LOOP('',(#158064,#158065,#158066,#158092)); -#158064 = ORIENTED_EDGE('',*,*,#157852,.T.); -#158065 = ORIENTED_EDGE('',*,*,#158041,.T.); -#158066 = ORIENTED_EDGE('',*,*,#158067,.F.); -#158067 = EDGE_CURVE('',#157883,#158014,#158068,.T.); -#158068 = SURFACE_CURVE('',#158069,(#158073,#158080),.PCURVE_S1.); -#158069 = LINE('',#158070,#158071); -#158070 = CARTESIAN_POINT('',(-2.5,0.765,4.419578044023E-034)); -#158071 = VECTOR('',#158072,1.); -#158072 = DIRECTION('',(1.738524712456E-034,2.134639934378E-035,-1.)); -#158073 = PCURVE('',#157866,#158074); -#158074 = DEFINITIONAL_REPRESENTATION('',(#158075),#158079); -#158075 = LINE('',#158076,#158077); -#158076 = CARTESIAN_POINT('',(4.419578044023E-034,0.615)); -#158077 = VECTOR('',#158078,1.); -#158078 = DIRECTION('',(-1.,2.134639934378E-035)); -#158079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158080 = PCURVE('',#158081,#158086); -#158081 = PLANE('',#158082); -#158082 = AXIS2_PLACEMENT_3D('',#158083,#158084,#158085); -#158083 = CARTESIAN_POINT('',(-2.462243747522,0.4575,4.419578044023E-034 +#160426 = DEFINITIONAL_REPRESENTATION('',(#160427),#160431); +#160427 = LINE('',#160428,#160429); +#160428 = CARTESIAN_POINT('',(0.309809271329,-1.50082002764E-050)); +#160429 = VECTOR('',#160430,1.); +#160430 = DIRECTION('',(8.776534509458E-052,1.)); +#160431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160432 = ORIENTED_EDGE('',*,*,#160433,.F.); +#160433 = EDGE_CURVE('',#160187,#160406,#160434,.T.); +#160434 = SURFACE_CURVE('',#160435,(#160439,#160446),.PCURVE_S1.); +#160435 = LINE('',#160436,#160437); +#160436 = CARTESIAN_POINT('',(-2.5,0.15,-2.)); +#160437 = VECTOR('',#160438,1.); +#160438 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#160439 = PCURVE('',#160202,#160440); +#160440 = DEFINITIONAL_REPRESENTATION('',(#160441),#160445); +#160441 = LINE('',#160442,#160443); +#160442 = CARTESIAN_POINT('',(2.5,0.E+000)); +#160443 = VECTOR('',#160444,1.); +#160444 = DIRECTION('',(0.E+000,-1.)); +#160445 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160446 = PCURVE('',#160258,#160447); +#160447 = DEFINITIONAL_REPRESENTATION('',(#160448),#160452); +#160448 = LINE('',#160449,#160450); +#160449 = CARTESIAN_POINT('',(-2.,0.E+000)); +#160450 = VECTOR('',#160451,1.); +#160451 = DIRECTION('',(0.E+000,-1.)); +#160452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160453 = ADVANCED_FACE('',(#160454),#160258,.T.); +#160454 = FACE_BOUND('',#160455,.T.); +#160455 = EDGE_LOOP('',(#160456,#160457,#160458,#160484)); +#160456 = ORIENTED_EDGE('',*,*,#160244,.T.); +#160457 = ORIENTED_EDGE('',*,*,#160433,.T.); +#160458 = ORIENTED_EDGE('',*,*,#160459,.F.); +#160459 = EDGE_CURVE('',#160275,#160406,#160460,.T.); +#160460 = SURFACE_CURVE('',#160461,(#160465,#160472),.PCURVE_S1.); +#160461 = LINE('',#160462,#160463); +#160462 = CARTESIAN_POINT('',(-2.5,0.765,4.419578044023E-034)); +#160463 = VECTOR('',#160464,1.); +#160464 = DIRECTION('',(1.738524712456E-034,2.134639934378E-035,-1.)); +#160465 = PCURVE('',#160258,#160466); +#160466 = DEFINITIONAL_REPRESENTATION('',(#160467),#160471); +#160467 = LINE('',#160468,#160469); +#160468 = CARTESIAN_POINT('',(4.419578044023E-034,0.615)); +#160469 = VECTOR('',#160470,1.); +#160470 = DIRECTION('',(-1.,2.134639934378E-035)); +#160471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160472 = PCURVE('',#160473,#160478); +#160473 = PLANE('',#160474); +#160474 = AXIS2_PLACEMENT_3D('',#160475,#160476,#160477); +#160475 = CARTESIAN_POINT('',(-2.462243747522,0.4575,4.419578044023E-034 )); -#158084 = DIRECTION('',(-0.992546151641,-0.121869343405, +#160476 = DIRECTION('',(-0.992546151641,-0.121869343405, -1.751580729603E-034)); -#158085 = DIRECTION('',(0.121869343405,-0.992546151641, +#160477 = DIRECTION('',(0.121869343405,-0.992546151641, -1.256773640537E-051)); -#158086 = DEFINITIONAL_REPRESENTATION('',(#158087),#158091); -#158087 = LINE('',#158088,#158089); -#158088 = CARTESIAN_POINT('',(-0.309809271329,-2.508783808811E-050)); -#158089 = VECTOR('',#158090,1.); -#158090 = DIRECTION('',(3.832963844502E-051,-1.)); -#158091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158092 = ORIENTED_EDGE('',*,*,#157882,.T.); -#158093 = ADVANCED_FACE('',(#158094),#157921,.T.); -#158094 = FACE_BOUND('',#158095,.T.); -#158095 = EDGE_LOOP('',(#158096,#158097,#158120,#158147)); -#158096 = ORIENTED_EDGE('',*,*,#157905,.T.); -#158097 = ORIENTED_EDGE('',*,*,#158098,.F.); -#158098 = EDGE_CURVE('',#158099,#157883,#158101,.T.); -#158099 = VERTEX_POINT('',#158100); -#158100 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160478 = DEFINITIONAL_REPRESENTATION('',(#160479),#160483); +#160479 = LINE('',#160480,#160481); +#160480 = CARTESIAN_POINT('',(-0.309809271329,-2.508783808811E-050)); +#160481 = VECTOR('',#160482,1.); +#160482 = DIRECTION('',(3.832963844502E-051,-1.)); +#160483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160484 = ORIENTED_EDGE('',*,*,#160274,.T.); +#160485 = ADVANCED_FACE('',(#160486),#160313,.T.); +#160486 = FACE_BOUND('',#160487,.T.); +#160487 = EDGE_LOOP('',(#160488,#160489,#160512,#160539)); +#160488 = ORIENTED_EDGE('',*,*,#160297,.T.); +#160489 = ORIENTED_EDGE('',*,*,#160490,.F.); +#160490 = EDGE_CURVE('',#160491,#160275,#160493,.T.); +#160491 = VERTEX_POINT('',#160492); +#160492 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, 1.935269583753)); -#158101 = SURFACE_CURVE('',#158102,(#158106,#158113),.PCURVE_S1.); -#158102 = LINE('',#158103,#158104); -#158103 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160493 = SURFACE_CURVE('',#160494,(#160498,#160505),.PCURVE_S1.); +#160494 = LINE('',#160495,#160496); +#160495 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, 1.935269583753)); -#158104 = VECTOR('',#158105,1.); -#158105 = DIRECTION('',(-0.120974291151,0.985256536015,0.120974291151)); -#158106 = PCURVE('',#157921,#158107); -#158107 = DEFINITIONAL_REPRESENTATION('',(#158108),#158112); -#158108 = LINE('',#158109,#158110); -#158109 = CARTESIAN_POINT('',(0.221336744873,-2.435269583753)); -#158110 = VECTOR('',#158111,1.); -#158111 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#158112 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158113 = PCURVE('',#158081,#158114); -#158114 = DEFINITIONAL_REPRESENTATION('',(#158115),#158119); -#158115 = LINE('',#158116,#158117); -#158116 = CARTESIAN_POINT('',(0.221336744873,1.935269583753)); -#158117 = VECTOR('',#158118,1.); -#158118 = DIRECTION('',(-0.992655640633,0.120974291151)); -#158119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158120 = ORIENTED_EDGE('',*,*,#158121,.F.); -#158121 = EDGE_CURVE('',#158122,#158099,#158124,.T.); -#158122 = VERTEX_POINT('',#158123); -#158123 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, +#160496 = VECTOR('',#160497,1.); +#160497 = DIRECTION('',(-0.120974291151,0.985256536015,0.120974291151)); +#160498 = PCURVE('',#160313,#160499); +#160499 = DEFINITIONAL_REPRESENTATION('',(#160500),#160504); +#160500 = LINE('',#160501,#160502); +#160501 = CARTESIAN_POINT('',(0.221336744873,-2.435269583753)); +#160502 = VECTOR('',#160503,1.); +#160503 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160505 = PCURVE('',#160473,#160506); +#160506 = DEFINITIONAL_REPRESENTATION('',(#160507),#160511); +#160507 = LINE('',#160508,#160509); +#160508 = CARTESIAN_POINT('',(0.221336744873,1.935269583753)); +#160509 = VECTOR('',#160510,1.); +#160510 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160512 = ORIENTED_EDGE('',*,*,#160513,.F.); +#160513 = EDGE_CURVE('',#160514,#160491,#160516,.T.); +#160514 = VERTEX_POINT('',#160515); +#160515 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, 1.935269583753)); -#158124 = SURFACE_CURVE('',#158125,(#158129,#158136),.PCURVE_S1.); -#158125 = LINE('',#158126,#158127); -#158126 = CARTESIAN_POINT('',(2.050127744336E-017,0.237813065659, +#160516 = SURFACE_CURVE('',#160517,(#160521,#160528),.PCURVE_S1.); +#160517 = LINE('',#160518,#160519); +#160518 = CARTESIAN_POINT('',(2.050127744336E-017,0.237813065659, 1.935269583753)); -#158127 = VECTOR('',#158128,1.); -#158128 = DIRECTION('',(-1.,-6.898853532133E-034,0.E+000)); -#158129 = PCURVE('',#157921,#158130); -#158130 = DEFINITIONAL_REPRESENTATION('',(#158131),#158135); -#158131 = LINE('',#158132,#158133); -#158132 = CARTESIAN_POINT('',(0.221336744873,6.833759147787E-018)); -#158133 = VECTOR('',#158134,1.); -#158134 = DIRECTION('',(6.847430524056E-034,-1.)); -#158135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158136 = PCURVE('',#158137,#158142); -#158137 = CYLINDRICAL_SURFACE('',#158138,0.1); -#158138 = AXIS2_PLACEMENT_3D('',#158139,#158140,#158141); -#158139 = CARTESIAN_POINT('',(2.050127744336E-017,0.25,1.836014968589)); -#158140 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); -#158141 = DIRECTION('',(-6.898853532133E-034,1.,0.E+000)); -#158142 = DEFINITIONAL_REPRESENTATION('',(#158143),#158146); -#158143 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158144,#158145), +#160519 = VECTOR('',#160520,1.); +#160520 = DIRECTION('',(-1.,-6.898853532133E-034,0.E+000)); +#160521 = PCURVE('',#160313,#160522); +#160522 = DEFINITIONAL_REPRESENTATION('',(#160523),#160527); +#160523 = LINE('',#160524,#160525); +#160524 = CARTESIAN_POINT('',(0.221336744873,6.833759147787E-018)); +#160525 = VECTOR('',#160526,1.); +#160526 = DIRECTION('',(6.847430524056E-034,-1.)); +#160527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160528 = PCURVE('',#160529,#160534); +#160529 = CYLINDRICAL_SURFACE('',#160530,0.1); +#160530 = AXIS2_PLACEMENT_3D('',#160531,#160532,#160533); +#160531 = CARTESIAN_POINT('',(2.050127744336E-017,0.25,1.836014968589)); +#160532 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); +#160533 = DIRECTION('',(-6.898853532133E-034,1.,0.E+000)); +#160534 = DEFINITIONAL_REPRESENTATION('',(#160535),#160538); +#160535 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160536,#160537), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.435269583753,2.435269583753), .PIECEWISE_BEZIER_KNOTS.); -#158144 = CARTESIAN_POINT('',(1.692969374435,2.435269583753)); -#158145 = CARTESIAN_POINT('',(1.692969374435,-2.435269583753)); -#158146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158147 = ORIENTED_EDGE('',*,*,#158148,.F.); -#158148 = EDGE_CURVE('',#157906,#158122,#158149,.T.); -#158149 = SURFACE_CURVE('',#158150,(#158154,#158161),.PCURVE_S1.); -#158150 = LINE('',#158151,#158152); -#158151 = CARTESIAN_POINT('',(2.5,0.765,2.)); -#158152 = VECTOR('',#158153,1.); -#158153 = DIRECTION('',(-0.120974291151,-0.985256536015,-0.120974291151) - ); -#158154 = PCURVE('',#157921,#158155); -#158155 = DEFINITIONAL_REPRESENTATION('',(#158156),#158160); -#158156 = LINE('',#158157,#158158); -#158157 = CARTESIAN_POINT('',(-0.309809271329,2.5)); -#158158 = VECTOR('',#158159,1.); -#158159 = DIRECTION('',(0.992655640633,-0.120974291151)); -#158160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158161 = PCURVE('',#157975,#158162); -#158162 = DEFINITIONAL_REPRESENTATION('',(#158163),#158167); -#158163 = LINE('',#158164,#158165); -#158164 = CARTESIAN_POINT('',(0.309809271329,2.)); -#158165 = VECTOR('',#158166,1.); -#158166 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#158167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158168 = ADVANCED_FACE('',(#158169),#157975,.T.); -#158169 = FACE_BOUND('',#158170,.T.); -#158170 = EDGE_LOOP('',(#158171,#158172,#158173,#158200)); -#158171 = ORIENTED_EDGE('',*,*,#157959,.T.); -#158172 = ORIENTED_EDGE('',*,*,#158148,.T.); -#158173 = ORIENTED_EDGE('',*,*,#158174,.F.); -#158174 = EDGE_CURVE('',#158175,#158122,#158177,.T.); -#158175 = VERTEX_POINT('',#158176); -#158176 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, +#160536 = CARTESIAN_POINT('',(1.692969374435,2.435269583753)); +#160537 = CARTESIAN_POINT('',(1.692969374435,-2.435269583753)); +#160538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160539 = ORIENTED_EDGE('',*,*,#160540,.F.); +#160540 = EDGE_CURVE('',#160298,#160514,#160541,.T.); +#160541 = SURFACE_CURVE('',#160542,(#160546,#160553),.PCURVE_S1.); +#160542 = LINE('',#160543,#160544); +#160543 = CARTESIAN_POINT('',(2.5,0.765,2.)); +#160544 = VECTOR('',#160545,1.); +#160545 = DIRECTION('',(-0.120974291151,-0.985256536015,-0.120974291151) + ); +#160546 = PCURVE('',#160313,#160547); +#160547 = DEFINITIONAL_REPRESENTATION('',(#160548),#160552); +#160548 = LINE('',#160549,#160550); +#160549 = CARTESIAN_POINT('',(-0.309809271329,2.5)); +#160550 = VECTOR('',#160551,1.); +#160551 = DIRECTION('',(0.992655640633,-0.120974291151)); +#160552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160553 = PCURVE('',#160367,#160554); +#160554 = DEFINITIONAL_REPRESENTATION('',(#160555),#160559); +#160555 = LINE('',#160556,#160557); +#160556 = CARTESIAN_POINT('',(0.309809271329,2.)); +#160557 = VECTOR('',#160558,1.); +#160558 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160560 = ADVANCED_FACE('',(#160561),#160367,.T.); +#160561 = FACE_BOUND('',#160562,.T.); +#160562 = EDGE_LOOP('',(#160563,#160564,#160565,#160592)); +#160563 = ORIENTED_EDGE('',*,*,#160351,.T.); +#160564 = ORIENTED_EDGE('',*,*,#160540,.T.); +#160565 = ORIENTED_EDGE('',*,*,#160566,.F.); +#160566 = EDGE_CURVE('',#160567,#160514,#160569,.T.); +#160567 = VERTEX_POINT('',#160568); +#160568 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, -1.935269583753)); -#158177 = SURFACE_CURVE('',#158178,(#158182,#158189),.PCURVE_S1.); -#158178 = LINE('',#158179,#158180); -#158179 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, +#160569 = SURFACE_CURVE('',#160570,(#160574,#160581),.PCURVE_S1.); +#160570 = LINE('',#160571,#160572); +#160571 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, 1.262103079567E-034)); -#158180 = VECTOR('',#158181,1.); -#158181 = DIRECTION('',(-2.154269365246E-050,-1.437261152528E-033,1.)); -#158182 = PCURVE('',#157975,#158183); -#158183 = DEFINITIONAL_REPRESENTATION('',(#158184),#158188); -#158184 = LINE('',#158185,#158186); -#158185 = CARTESIAN_POINT('',(-0.221336744873,-3.157474964455E-034)); -#158186 = VECTOR('',#158187,1.); -#158187 = DIRECTION('',(-1.426548025845E-033,1.)); -#158188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158189 = PCURVE('',#158190,#158195); -#158190 = CYLINDRICAL_SURFACE('',#158191,0.1); -#158191 = AXIS2_PLACEMENT_3D('',#158192,#158193,#158194); -#158192 = CARTESIAN_POINT('',(2.336014968589,0.25,1.437261152528E-034)); -#158193 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); -#158194 = DIRECTION('',(-3.684348419086E-099,1.,1.437261152528E-033)); -#158195 = DEFINITIONAL_REPRESENTATION('',(#158196),#158199); -#158196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158197,#158198), +#160572 = VECTOR('',#160573,1.); +#160573 = DIRECTION('',(-2.154269365246E-050,-1.437261152528E-033,1.)); +#160574 = PCURVE('',#160367,#160575); +#160575 = DEFINITIONAL_REPRESENTATION('',(#160576),#160580); +#160576 = LINE('',#160577,#160578); +#160577 = CARTESIAN_POINT('',(-0.221336744873,-3.157474964455E-034)); +#160578 = VECTOR('',#160579,1.); +#160579 = DIRECTION('',(-1.426548025845E-033,1.)); +#160580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160581 = PCURVE('',#160582,#160587); +#160582 = CYLINDRICAL_SURFACE('',#160583,0.1); +#160583 = AXIS2_PLACEMENT_3D('',#160584,#160585,#160586); +#160584 = CARTESIAN_POINT('',(2.336014968589,0.25,1.437261152528E-034)); +#160585 = DIRECTION('',(2.154269365246E-050,1.437261152528E-033,-1.)); +#160586 = DIRECTION('',(-3.684348419086E-099,1.,1.437261152528E-033)); +#160587 = DEFINITIONAL_REPRESENTATION('',(#160588),#160591); +#160588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160589,#160590), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.935269583753,1.935269583753), .PIECEWISE_BEZIER_KNOTS.); -#158197 = CARTESIAN_POINT('',(1.692969374435,1.935269583753)); -#158198 = CARTESIAN_POINT('',(1.692969374435,-1.935269583753)); -#158199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158200 = ORIENTED_EDGE('',*,*,#158201,.F.); -#158201 = EDGE_CURVE('',#157960,#158175,#158202,.T.); -#158202 = SURFACE_CURVE('',#158203,(#158207,#158214),.PCURVE_S1.); -#158203 = LINE('',#158204,#158205); -#158204 = CARTESIAN_POINT('',(2.5,0.765,-2.)); -#158205 = VECTOR('',#158206,1.); -#158206 = DIRECTION('',(-0.120974291151,-0.985256536015,0.120974291151) - ); -#158207 = PCURVE('',#157975,#158208); -#158208 = DEFINITIONAL_REPRESENTATION('',(#158209),#158213); -#158209 = LINE('',#158210,#158211); -#158210 = CARTESIAN_POINT('',(0.309809271329,-2.)); -#158211 = VECTOR('',#158212,1.); -#158212 = DIRECTION('',(-0.992655640633,0.120974291151)); -#158213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158214 = PCURVE('',#158029,#158215); -#158215 = DEFINITIONAL_REPRESENTATION('',(#158216),#158220); -#158216 = LINE('',#158217,#158218); -#158217 = CARTESIAN_POINT('',(0.309809271329,2.5)); -#158218 = VECTOR('',#158219,1.); -#158219 = DIRECTION('',(-0.992655640633,-0.120974291151)); -#158220 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158221 = ADVANCED_FACE('',(#158222),#158029,.T.); -#158222 = FACE_BOUND('',#158223,.T.); -#158223 = EDGE_LOOP('',(#158224,#158225,#158226,#158253)); -#158224 = ORIENTED_EDGE('',*,*,#158013,.T.); -#158225 = ORIENTED_EDGE('',*,*,#158201,.T.); -#158226 = ORIENTED_EDGE('',*,*,#158227,.F.); -#158227 = EDGE_CURVE('',#158228,#158175,#158230,.T.); -#158228 = VERTEX_POINT('',#158229); -#158229 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160589 = CARTESIAN_POINT('',(1.692969374435,1.935269583753)); +#160590 = CARTESIAN_POINT('',(1.692969374435,-1.935269583753)); +#160591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160592 = ORIENTED_EDGE('',*,*,#160593,.F.); +#160593 = EDGE_CURVE('',#160352,#160567,#160594,.T.); +#160594 = SURFACE_CURVE('',#160595,(#160599,#160606),.PCURVE_S1.); +#160595 = LINE('',#160596,#160597); +#160596 = CARTESIAN_POINT('',(2.5,0.765,-2.)); +#160597 = VECTOR('',#160598,1.); +#160598 = DIRECTION('',(-0.120974291151,-0.985256536015,0.120974291151) + ); +#160599 = PCURVE('',#160367,#160600); +#160600 = DEFINITIONAL_REPRESENTATION('',(#160601),#160605); +#160601 = LINE('',#160602,#160603); +#160602 = CARTESIAN_POINT('',(0.309809271329,-2.)); +#160603 = VECTOR('',#160604,1.); +#160604 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160606 = PCURVE('',#160421,#160607); +#160607 = DEFINITIONAL_REPRESENTATION('',(#160608),#160612); +#160608 = LINE('',#160609,#160610); +#160609 = CARTESIAN_POINT('',(0.309809271329,2.5)); +#160610 = VECTOR('',#160611,1.); +#160611 = DIRECTION('',(-0.992655640633,-0.120974291151)); +#160612 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160613 = ADVANCED_FACE('',(#160614),#160421,.T.); +#160614 = FACE_BOUND('',#160615,.T.); +#160615 = EDGE_LOOP('',(#160616,#160617,#160618,#160645)); +#160616 = ORIENTED_EDGE('',*,*,#160405,.T.); +#160617 = ORIENTED_EDGE('',*,*,#160593,.T.); +#160618 = ORIENTED_EDGE('',*,*,#160619,.F.); +#160619 = EDGE_CURVE('',#160620,#160567,#160622,.T.); +#160620 = VERTEX_POINT('',#160621); +#160621 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, -1.935269583753)); -#158230 = SURFACE_CURVE('',#158231,(#158235,#158242),.PCURVE_S1.); -#158231 = LINE('',#158232,#158233); -#158232 = CARTESIAN_POINT('',(2.050127744336E-017,0.237813065659, +#160622 = SURFACE_CURVE('',#160623,(#160627,#160634),.PCURVE_S1.); +#160623 = LINE('',#160624,#160625); +#160624 = CARTESIAN_POINT('',(2.050127744336E-017,0.237813065659, -1.935269583753)); -#158233 = VECTOR('',#158234,1.); -#158234 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); -#158235 = PCURVE('',#158029,#158236); -#158236 = DEFINITIONAL_REPRESENTATION('',(#158237),#158241); -#158237 = LINE('',#158238,#158239); -#158238 = CARTESIAN_POINT('',(-0.221336744873,6.833759147787E-018)); -#158239 = VECTOR('',#158240,1.); -#158240 = DIRECTION('',(6.847430524056E-034,1.)); -#158241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158242 = PCURVE('',#158243,#158248); -#158243 = CYLINDRICAL_SURFACE('',#158244,0.1); -#158244 = AXIS2_PLACEMENT_3D('',#158245,#158246,#158247); -#158245 = CARTESIAN_POINT('',(2.050127744336E-017,0.25,-1.836014968589) - ); -#158246 = DIRECTION('',(-1.,-6.898853532133E-034,0.E+000)); -#158247 = DIRECTION('',(6.898853532133E-034,-1.,0.E+000)); -#158248 = DEFINITIONAL_REPRESENTATION('',(#158249),#158252); -#158249 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158250,#158251), +#160625 = VECTOR('',#160626,1.); +#160626 = DIRECTION('',(1.,6.898853532133E-034,0.E+000)); +#160627 = PCURVE('',#160421,#160628); +#160628 = DEFINITIONAL_REPRESENTATION('',(#160629),#160633); +#160629 = LINE('',#160630,#160631); +#160630 = CARTESIAN_POINT('',(-0.221336744873,6.833759147787E-018)); +#160631 = VECTOR('',#160632,1.); +#160632 = DIRECTION('',(6.847430524056E-034,1.)); +#160633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160634 = PCURVE('',#160635,#160640); +#160635 = CYLINDRICAL_SURFACE('',#160636,0.1); +#160636 = AXIS2_PLACEMENT_3D('',#160637,#160638,#160639); +#160637 = CARTESIAN_POINT('',(2.050127744336E-017,0.25,-1.836014968589) + ); +#160638 = DIRECTION('',(-1.,-6.898853532133E-034,0.E+000)); +#160639 = DIRECTION('',(6.898853532133E-034,-1.,0.E+000)); +#160640 = DEFINITIONAL_REPRESENTATION('',(#160641),#160644); +#160641 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160642,#160643), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.435269583753,2.435269583753), .PIECEWISE_BEZIER_KNOTS.); -#158250 = CARTESIAN_POINT('',(4.834562028024,2.435269583753)); -#158251 = CARTESIAN_POINT('',(4.834562028024,-2.435269583753)); -#158252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158253 = ORIENTED_EDGE('',*,*,#158254,.F.); -#158254 = EDGE_CURVE('',#158014,#158228,#158255,.T.); -#158255 = SURFACE_CURVE('',#158256,(#158260,#158267),.PCURVE_S1.); -#158256 = LINE('',#158257,#158258); -#158257 = CARTESIAN_POINT('',(-2.5,0.765,-2.)); -#158258 = VECTOR('',#158259,1.); -#158259 = DIRECTION('',(0.120974291151,-0.985256536015,0.120974291151)); -#158260 = PCURVE('',#158029,#158261); -#158261 = DEFINITIONAL_REPRESENTATION('',(#158262),#158266); -#158262 = LINE('',#158263,#158264); -#158263 = CARTESIAN_POINT('',(0.309809271329,-2.5)); -#158264 = VECTOR('',#158265,1.); -#158265 = DIRECTION('',(-0.992655640633,0.120974291151)); -#158266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158267 = PCURVE('',#158081,#158268); -#158268 = DEFINITIONAL_REPRESENTATION('',(#158269),#158273); -#158269 = LINE('',#158270,#158271); -#158270 = CARTESIAN_POINT('',(-0.309809271329,-2.)); -#158271 = VECTOR('',#158272,1.); -#158272 = DIRECTION('',(0.992655640633,0.120974291151)); -#158273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158274 = ADVANCED_FACE('',(#158275),#158081,.T.); -#158275 = FACE_BOUND('',#158276,.T.); -#158276 = EDGE_LOOP('',(#158277,#158278,#158279,#158304)); -#158277 = ORIENTED_EDGE('',*,*,#158067,.T.); -#158278 = ORIENTED_EDGE('',*,*,#158254,.T.); -#158279 = ORIENTED_EDGE('',*,*,#158280,.F.); -#158280 = EDGE_CURVE('',#158099,#158228,#158281,.T.); -#158281 = SURFACE_CURVE('',#158282,(#158286,#158293),.PCURVE_S1.); -#158282 = LINE('',#158283,#158284); -#158283 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160642 = CARTESIAN_POINT('',(4.834562028024,2.435269583753)); +#160643 = CARTESIAN_POINT('',(4.834562028024,-2.435269583753)); +#160644 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160645 = ORIENTED_EDGE('',*,*,#160646,.F.); +#160646 = EDGE_CURVE('',#160406,#160620,#160647,.T.); +#160647 = SURFACE_CURVE('',#160648,(#160652,#160659),.PCURVE_S1.); +#160648 = LINE('',#160649,#160650); +#160649 = CARTESIAN_POINT('',(-2.5,0.765,-2.)); +#160650 = VECTOR('',#160651,1.); +#160651 = DIRECTION('',(0.120974291151,-0.985256536015,0.120974291151)); +#160652 = PCURVE('',#160421,#160653); +#160653 = DEFINITIONAL_REPRESENTATION('',(#160654),#160658); +#160654 = LINE('',#160655,#160656); +#160655 = CARTESIAN_POINT('',(0.309809271329,-2.5)); +#160656 = VECTOR('',#160657,1.); +#160657 = DIRECTION('',(-0.992655640633,0.120974291151)); +#160658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160659 = PCURVE('',#160473,#160660); +#160660 = DEFINITIONAL_REPRESENTATION('',(#160661),#160665); +#160661 = LINE('',#160662,#160663); +#160662 = CARTESIAN_POINT('',(-0.309809271329,-2.)); +#160663 = VECTOR('',#160664,1.); +#160664 = DIRECTION('',(0.992655640633,0.120974291151)); +#160665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160666 = ADVANCED_FACE('',(#160667),#160473,.T.); +#160667 = FACE_BOUND('',#160668,.T.); +#160668 = EDGE_LOOP('',(#160669,#160670,#160671,#160696)); +#160669 = ORIENTED_EDGE('',*,*,#160459,.T.); +#160670 = ORIENTED_EDGE('',*,*,#160646,.T.); +#160671 = ORIENTED_EDGE('',*,*,#160672,.F.); +#160672 = EDGE_CURVE('',#160491,#160620,#160673,.T.); +#160673 = SURFACE_CURVE('',#160674,(#160678,#160685),.PCURVE_S1.); +#160674 = LINE('',#160675,#160676); +#160675 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, 1.262103079567E-034)); -#158284 = VECTOR('',#158285,1.); -#158285 = DIRECTION('',(-2.154269365246E-050,1.437261152528E-033,-1.)); -#158286 = PCURVE('',#158081,#158287); -#158287 = DEFINITIONAL_REPRESENTATION('',(#158288),#158292); -#158288 = LINE('',#158289,#158290); -#158289 = CARTESIAN_POINT('',(0.221336744873,-3.157474964455E-034)); -#158290 = VECTOR('',#158291,1.); -#158291 = DIRECTION('',(-1.426548025845E-033,-1.)); -#158292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158293 = PCURVE('',#158294,#158299); -#158294 = CYLINDRICAL_SURFACE('',#158295,0.1); -#158295 = AXIS2_PLACEMENT_3D('',#158296,#158297,#158298); -#158296 = CARTESIAN_POINT('',(-2.336014968589,0.25,1.437261152528E-034) - ); -#158297 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); -#158298 = DIRECTION('',(-3.684348419086E-099,-1.,-1.437261152528E-033)); -#158299 = DEFINITIONAL_REPRESENTATION('',(#158300),#158303); -#158300 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158301,#158302), +#160676 = VECTOR('',#160677,1.); +#160677 = DIRECTION('',(-2.154269365246E-050,1.437261152528E-033,-1.)); +#160678 = PCURVE('',#160473,#160679); +#160679 = DEFINITIONAL_REPRESENTATION('',(#160680),#160684); +#160680 = LINE('',#160681,#160682); +#160681 = CARTESIAN_POINT('',(0.221336744873,-3.157474964455E-034)); +#160682 = VECTOR('',#160683,1.); +#160683 = DIRECTION('',(-1.426548025845E-033,-1.)); +#160684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160685 = PCURVE('',#160686,#160691); +#160686 = CYLINDRICAL_SURFACE('',#160687,0.1); +#160687 = AXIS2_PLACEMENT_3D('',#160688,#160689,#160690); +#160688 = CARTESIAN_POINT('',(-2.336014968589,0.25,1.437261152528E-034) + ); +#160689 = DIRECTION('',(2.154269365246E-050,-1.437261152528E-033,1.)); +#160690 = DIRECTION('',(-3.684348419086E-099,-1.,-1.437261152528E-033)); +#160691 = DEFINITIONAL_REPRESENTATION('',(#160692),#160695); +#160692 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160693,#160694), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.935269583753,1.935269583753), .PIECEWISE_BEZIER_KNOTS.); -#158301 = CARTESIAN_POINT('',(4.834562028024,1.935269583753)); -#158302 = CARTESIAN_POINT('',(4.834562028024,-1.935269583753)); -#158303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158304 = ORIENTED_EDGE('',*,*,#158098,.T.); -#158305 = ADVANCED_FACE('',(#158306),#158137,.T.); -#158306 = FACE_BOUND('',#158307,.T.); -#158307 = EDGE_LOOP('',(#158308,#158309,#158377,#158404)); -#158308 = ORIENTED_EDGE('',*,*,#158121,.T.); -#158309 = ORIENTED_EDGE('',*,*,#158310,.F.); -#158310 = EDGE_CURVE('',#158311,#158099,#158313,.T.); -#158311 = VERTEX_POINT('',#158312); -#158312 = CARTESIAN_POINT('',(-2.336014968589,0.15,1.836014968589)); -#158313 = SURFACE_CURVE('',#158314,(#158319,#158348),.PCURVE_S1.); -#158314 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#158315,#158316,#158317, -#158318),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#160693 = CARTESIAN_POINT('',(4.834562028024,1.935269583753)); +#160694 = CARTESIAN_POINT('',(4.834562028024,-1.935269583753)); +#160695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160696 = ORIENTED_EDGE('',*,*,#160490,.T.); +#160697 = ADVANCED_FACE('',(#160698),#160529,.T.); +#160698 = FACE_BOUND('',#160699,.T.); +#160699 = EDGE_LOOP('',(#160700,#160701,#160769,#160796)); +#160700 = ORIENTED_EDGE('',*,*,#160513,.T.); +#160701 = ORIENTED_EDGE('',*,*,#160702,.F.); +#160702 = EDGE_CURVE('',#160703,#160491,#160705,.T.); +#160703 = VERTEX_POINT('',#160704); +#160704 = CARTESIAN_POINT('',(-2.336014968589,0.15,1.836014968589)); +#160705 = SURFACE_CURVE('',#160706,(#160711,#160740),.PCURVE_S1.); +#160706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#160707,#160708,#160709, +#160710),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 4.712388980385,6.16101225954),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#158315 = CARTESIAN_POINT('',(-2.336014968589,0.15,1.836014968589)); -#158316 = CARTESIAN_POINT('',(-2.389068894936,0.15,1.889068894936)); -#158317 = CARTESIAN_POINT('',(-2.428803936584,0.185154595234, +#160707 = CARTESIAN_POINT('',(-2.336014968589,0.15,1.836014968589)); +#160708 = CARTESIAN_POINT('',(-2.389068894936,0.15,1.889068894936)); +#160709 = CARTESIAN_POINT('',(-2.428803936584,0.185154595234, 1.928803936584)); -#158318 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160710 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, 1.935269583753)); -#158319 = PCURVE('',#158137,#158320); -#158320 = DEFINITIONAL_REPRESENTATION('',(#158321),#158347); -#158321 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158322,#158323,#158324, - #158325,#158326,#158327,#158328,#158329,#158330,#158331,#158332, - #158333,#158334,#158335,#158336,#158337,#158338,#158339,#158340, - #158341,#158342,#158343,#158344,#158345,#158346),.UNSPECIFIED.,.F., +#160711 = PCURVE('',#160529,#160712); +#160712 = DEFINITIONAL_REPRESENTATION('',(#160713),#160739); +#160713 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160714,#160715,#160716, + #160717,#160718,#160719,#160720,#160721,#160722,#160723,#160724, + #160725,#160726,#160727,#160728,#160729,#160730,#160731,#160732, + #160733,#160734,#160735,#160736,#160737,#160738),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -195386,40 +198388,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208784,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#158322 = CARTESIAN_POINT('',(3.14159265359,-2.336014968589)); -#158323 = CARTESIAN_POINT('',(3.12151434906,-2.338022572109)); -#158324 = CARTESIAN_POINT('',(3.080895346177,-2.342084887057)); -#158325 = CARTESIAN_POINT('',(3.018662714711,-2.348285047057)); -#158326 = CARTESIAN_POINT('',(2.955203867684,-2.354558765666)); -#158327 = CARTESIAN_POINT('',(2.890614716316,-2.360867638794)); -#158328 = CARTESIAN_POINT('',(2.825002696965,-2.367170396506)); -#158329 = CARTESIAN_POINT('',(2.75848783298,-2.373423064557)); -#158330 = CARTESIAN_POINT('',(2.691201358285,-2.379579930936)); -#158331 = CARTESIAN_POINT('',(2.623284574238,-2.385594472001)); -#158332 = CARTESIAN_POINT('',(2.554887243423,-2.391420422455)); -#158333 = CARTESIAN_POINT('',(2.486165748071,-2.397012884468)); -#158334 = CARTESIAN_POINT('',(2.417281014012,-2.402329439048)); -#158335 = CARTESIAN_POINT('',(2.348396279953,-2.407331199805)); -#158336 = CARTESIAN_POINT('',(2.279674784602,-2.41198375621)); -#158337 = CARTESIAN_POINT('',(2.211277453786,-2.416257958446)); -#158338 = CARTESIAN_POINT('',(2.143360669739,-2.420130506351)); -#158339 = CARTESIAN_POINT('',(2.076074195044,-2.423584319582)); -#158340 = CARTESIAN_POINT('',(2.009559331059,-2.426608676199)); -#158341 = CARTESIAN_POINT('',(1.943947311708,-2.429199140074)); -#158342 = CARTESIAN_POINT('',(1.87935816034,-2.431357242721)); -#158343 = CARTESIAN_POINT('',(1.815899313313,-2.433090150347)); -#158344 = CARTESIAN_POINT('',(1.753666681847,-2.434409604263)); -#158345 = CARTESIAN_POINT('',(1.713047678964,-2.435025182465)); -#158346 = CARTESIAN_POINT('',(1.692969374435,-2.435269583753)); -#158347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158348 = PCURVE('',#158294,#158349); -#158349 = DEFINITIONAL_REPRESENTATION('',(#158350),#158376); -#158350 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158351,#158352,#158353, - #158354,#158355,#158356,#158357,#158358,#158359,#158360,#158361, - #158362,#158363,#158364,#158365,#158366,#158367,#158368,#158369, - #158370,#158371,#158372,#158373,#158374,#158375),.UNSPECIFIED.,.F., +#160714 = CARTESIAN_POINT('',(3.14159265359,-2.336014968589)); +#160715 = CARTESIAN_POINT('',(3.12151434906,-2.338022572109)); +#160716 = CARTESIAN_POINT('',(3.080895346177,-2.342084887057)); +#160717 = CARTESIAN_POINT('',(3.018662714711,-2.348285047057)); +#160718 = CARTESIAN_POINT('',(2.955203867684,-2.354558765666)); +#160719 = CARTESIAN_POINT('',(2.890614716316,-2.360867638794)); +#160720 = CARTESIAN_POINT('',(2.825002696965,-2.367170396506)); +#160721 = CARTESIAN_POINT('',(2.75848783298,-2.373423064557)); +#160722 = CARTESIAN_POINT('',(2.691201358285,-2.379579930936)); +#160723 = CARTESIAN_POINT('',(2.623284574238,-2.385594472001)); +#160724 = CARTESIAN_POINT('',(2.554887243423,-2.391420422455)); +#160725 = CARTESIAN_POINT('',(2.486165748071,-2.397012884468)); +#160726 = CARTESIAN_POINT('',(2.417281014012,-2.402329439048)); +#160727 = CARTESIAN_POINT('',(2.348396279953,-2.407331199805)); +#160728 = CARTESIAN_POINT('',(2.279674784602,-2.41198375621)); +#160729 = CARTESIAN_POINT('',(2.211277453786,-2.416257958446)); +#160730 = CARTESIAN_POINT('',(2.143360669739,-2.420130506351)); +#160731 = CARTESIAN_POINT('',(2.076074195044,-2.423584319582)); +#160732 = CARTESIAN_POINT('',(2.009559331059,-2.426608676199)); +#160733 = CARTESIAN_POINT('',(1.943947311708,-2.429199140074)); +#160734 = CARTESIAN_POINT('',(1.87935816034,-2.431357242721)); +#160735 = CARTESIAN_POINT('',(1.815899313313,-2.433090150347)); +#160736 = CARTESIAN_POINT('',(1.753666681847,-2.434409604263)); +#160737 = CARTESIAN_POINT('',(1.713047678964,-2.435025182465)); +#160738 = CARTESIAN_POINT('',(1.692969374435,-2.435269583753)); +#160739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160740 = PCURVE('',#160686,#160741); +#160741 = DEFINITIONAL_REPRESENTATION('',(#160742),#160768); +#160742 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160743,#160744,#160745, + #160746,#160747,#160748,#160749,#160750,#160751,#160752,#160753, + #160754,#160755,#160756,#160757,#160758,#160759,#160760,#160761, + #160762,#160763,#160764,#160765,#160766,#160767),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.778235493074,4.844082005762,4.909928518451,4.97577503114, 5.041621543829,5.107468056518,5.173314569207,5.239161081896, @@ -195427,87 +198429,87 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.56839364534,5.634240158029,5.700086670718,5.765933183407, 5.831779696096,5.897626208784,5.963472721473,6.029319234162, 6.095165746851,6.16101225954),.QUASI_UNIFORM_KNOTS.); -#158351 = CARTESIAN_POINT('',(6.28318530718,1.836014968589)); -#158352 = CARTESIAN_POINT('',(6.26310700265,1.838022572109)); -#158353 = CARTESIAN_POINT('',(6.222487999767,1.842084887057)); -#158354 = CARTESIAN_POINT('',(6.160255368301,1.848285047057)); -#158355 = CARTESIAN_POINT('',(6.096796521274,1.854558765666)); -#158356 = CARTESIAN_POINT('',(6.032207369906,1.860867638794)); -#158357 = CARTESIAN_POINT('',(5.966595350555,1.867170396506)); -#158358 = CARTESIAN_POINT('',(5.90008048657,1.873423064557)); -#158359 = CARTESIAN_POINT('',(5.832794011875,1.879579930936)); -#158360 = CARTESIAN_POINT('',(5.764877227828,1.885594472001)); -#158361 = CARTESIAN_POINT('',(5.696479897012,1.891420422455)); -#158362 = CARTESIAN_POINT('',(5.627758401661,1.897012884468)); -#158363 = CARTESIAN_POINT('',(5.558873667602,1.902329439048)); -#158364 = CARTESIAN_POINT('',(5.489988933543,1.907331199805)); -#158365 = CARTESIAN_POINT('',(5.421267438192,1.91198375621)); -#158366 = CARTESIAN_POINT('',(5.352870107376,1.916257958446)); -#158367 = CARTESIAN_POINT('',(5.284953323329,1.920130506351)); -#158368 = CARTESIAN_POINT('',(5.217666848634,1.923584319582)); -#158369 = CARTESIAN_POINT('',(5.151151984649,1.926608676199)); -#158370 = CARTESIAN_POINT('',(5.085539965298,1.929199140074)); -#158371 = CARTESIAN_POINT('',(5.02095081393,1.931357242721)); -#158372 = CARTESIAN_POINT('',(4.957491966903,1.933090150347)); -#158373 = CARTESIAN_POINT('',(4.895259335437,1.934409604263)); -#158374 = CARTESIAN_POINT('',(4.854640332554,1.935025182465)); -#158375 = CARTESIAN_POINT('',(4.834562028024,1.935269583753)); -#158376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158377 = ORIENTED_EDGE('',*,*,#158378,.T.); -#158378 = EDGE_CURVE('',#158311,#158379,#158381,.T.); -#158379 = VERTEX_POINT('',#158380); -#158380 = CARTESIAN_POINT('',(2.336014968589,0.15,1.836014968589)); -#158381 = SURFACE_CURVE('',#158382,(#158386,#158392),.PCURVE_S1.); -#158382 = LINE('',#158383,#158384); -#158383 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,1.836014968589)); -#158384 = VECTOR('',#158385,1.); -#158385 = DIRECTION('',(1.,6.898853532133E-034,9.915454178714E-067)); -#158386 = PCURVE('',#158137,#158387); -#158387 = DEFINITIONAL_REPRESENTATION('',(#158388),#158391); -#158388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158389,#158390), +#160743 = CARTESIAN_POINT('',(6.28318530718,1.836014968589)); +#160744 = CARTESIAN_POINT('',(6.26310700265,1.838022572109)); +#160745 = CARTESIAN_POINT('',(6.222487999767,1.842084887057)); +#160746 = CARTESIAN_POINT('',(6.160255368301,1.848285047057)); +#160747 = CARTESIAN_POINT('',(6.096796521274,1.854558765666)); +#160748 = CARTESIAN_POINT('',(6.032207369906,1.860867638794)); +#160749 = CARTESIAN_POINT('',(5.966595350555,1.867170396506)); +#160750 = CARTESIAN_POINT('',(5.90008048657,1.873423064557)); +#160751 = CARTESIAN_POINT('',(5.832794011875,1.879579930936)); +#160752 = CARTESIAN_POINT('',(5.764877227828,1.885594472001)); +#160753 = CARTESIAN_POINT('',(5.696479897012,1.891420422455)); +#160754 = CARTESIAN_POINT('',(5.627758401661,1.897012884468)); +#160755 = CARTESIAN_POINT('',(5.558873667602,1.902329439048)); +#160756 = CARTESIAN_POINT('',(5.489988933543,1.907331199805)); +#160757 = CARTESIAN_POINT('',(5.421267438192,1.91198375621)); +#160758 = CARTESIAN_POINT('',(5.352870107376,1.916257958446)); +#160759 = CARTESIAN_POINT('',(5.284953323329,1.920130506351)); +#160760 = CARTESIAN_POINT('',(5.217666848634,1.923584319582)); +#160761 = CARTESIAN_POINT('',(5.151151984649,1.926608676199)); +#160762 = CARTESIAN_POINT('',(5.085539965298,1.929199140074)); +#160763 = CARTESIAN_POINT('',(5.02095081393,1.931357242721)); +#160764 = CARTESIAN_POINT('',(4.957491966903,1.933090150347)); +#160765 = CARTESIAN_POINT('',(4.895259335437,1.934409604263)); +#160766 = CARTESIAN_POINT('',(4.854640332554,1.935025182465)); +#160767 = CARTESIAN_POINT('',(4.834562028024,1.935269583753)); +#160768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160769 = ORIENTED_EDGE('',*,*,#160770,.T.); +#160770 = EDGE_CURVE('',#160703,#160771,#160773,.T.); +#160771 = VERTEX_POINT('',#160772); +#160772 = CARTESIAN_POINT('',(2.336014968589,0.15,1.836014968589)); +#160773 = SURFACE_CURVE('',#160774,(#160778,#160784),.PCURVE_S1.); +#160774 = LINE('',#160775,#160776); +#160775 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,1.836014968589)); +#160776 = VECTOR('',#160777,1.); +#160777 = DIRECTION('',(1.,6.898853532133E-034,9.915454178714E-067)); +#160778 = PCURVE('',#160529,#160779); +#160779 = DEFINITIONAL_REPRESENTATION('',(#160780),#160783); +#160780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160781,#160782), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.336014968589,2.336014968589), .PIECEWISE_BEZIER_KNOTS.); -#158389 = CARTESIAN_POINT('',(3.14159265359,-2.336014968589)); -#158390 = CARTESIAN_POINT('',(3.14159265359,2.336014968589)); -#158391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158392 = PCURVE('',#158393,#158398); -#158393 = PLANE('',#158394); -#158394 = AXIS2_PLACEMENT_3D('',#158395,#158396,#158397); -#158395 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,0.E+000)); -#158396 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); -#158397 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); -#158398 = DEFINITIONAL_REPRESENTATION('',(#158399),#158403); -#158399 = LINE('',#158400,#158401); -#158400 = CARTESIAN_POINT('',(1.836014968589,1.820492229248E-066)); -#158401 = VECTOR('',#158402,1.); -#158402 = DIRECTION('',(0.E+000,1.)); -#158403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158404 = ORIENTED_EDGE('',*,*,#158405,.F.); -#158405 = EDGE_CURVE('',#158122,#158379,#158406,.T.); -#158406 = SURFACE_CURVE('',#158407,(#158412,#158441),.PCURVE_S1.); -#158407 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#158408,#158409,#158410, -#158411),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#160781 = CARTESIAN_POINT('',(3.14159265359,-2.336014968589)); +#160782 = CARTESIAN_POINT('',(3.14159265359,2.336014968589)); +#160783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160784 = PCURVE('',#160785,#160790); +#160785 = PLANE('',#160786); +#160786 = AXIS2_PLACEMENT_3D('',#160787,#160788,#160789); +#160787 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,0.E+000)); +#160788 = DIRECTION('',(-6.898853532133E-034,1.,1.437261152528E-033)); +#160789 = DIRECTION('',(-2.219884210458E-083,-1.437261152528E-033,1.)); +#160790 = DEFINITIONAL_REPRESENTATION('',(#160791),#160795); +#160791 = LINE('',#160792,#160793); +#160792 = CARTESIAN_POINT('',(1.836014968589,1.820492229248E-066)); +#160793 = VECTOR('',#160794,1.); +#160794 = DIRECTION('',(0.E+000,1.)); +#160795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160796 = ORIENTED_EDGE('',*,*,#160797,.F.); +#160797 = EDGE_CURVE('',#160514,#160771,#160798,.T.); +#160798 = SURFACE_CURVE('',#160799,(#160804,#160833),.PCURVE_S1.); +#160799 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#160800,#160801,#160802, +#160803),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.263765701229,4.712388980385),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#158408 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, +#160800 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, 1.935269583753)); -#158409 = CARTESIAN_POINT('',(2.428803936584,0.185154595234, +#160801 = CARTESIAN_POINT('',(2.428803936584,0.185154595234, 1.928803936584)); -#158410 = CARTESIAN_POINT('',(2.389068894936,0.15,1.889068894936)); -#158411 = CARTESIAN_POINT('',(2.336014968589,0.15,1.836014968589)); -#158412 = PCURVE('',#158137,#158413); -#158413 = DEFINITIONAL_REPRESENTATION('',(#158414),#158440); -#158414 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158415,#158416,#158417, - #158418,#158419,#158420,#158421,#158422,#158423,#158424,#158425, - #158426,#158427,#158428,#158429,#158430,#158431,#158432,#158433, - #158434,#158435,#158436,#158437,#158438,#158439),.UNSPECIFIED.,.F., +#160802 = CARTESIAN_POINT('',(2.389068894936,0.15,1.889068894936)); +#160803 = CARTESIAN_POINT('',(2.336014968589,0.15,1.836014968589)); +#160804 = PCURVE('',#160529,#160805); +#160805 = DEFINITIONAL_REPRESENTATION('',(#160806),#160832); +#160806 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160807,#160808,#160809, + #160810,#160811,#160812,#160813,#160814,#160815,#160816,#160817, + #160818,#160819,#160820,#160821,#160822,#160823,#160824,#160825, + #160826,#160827,#160828,#160829,#160830,#160831),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195515,40 +198517,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158415 = CARTESIAN_POINT('',(1.692969374435,2.435269583753)); -#158416 = CARTESIAN_POINT('',(1.713047678964,2.435025182465)); -#158417 = CARTESIAN_POINT('',(1.753666681847,2.434409604263)); -#158418 = CARTESIAN_POINT('',(1.815899313313,2.433090150347)); -#158419 = CARTESIAN_POINT('',(1.87935816034,2.431357242721)); -#158420 = CARTESIAN_POINT('',(1.943947311708,2.429199140074)); -#158421 = CARTESIAN_POINT('',(2.009559331059,2.426608676199)); -#158422 = CARTESIAN_POINT('',(2.076074195044,2.423584319582)); -#158423 = CARTESIAN_POINT('',(2.143360669739,2.420130506351)); -#158424 = CARTESIAN_POINT('',(2.211277453786,2.416257958446)); -#158425 = CARTESIAN_POINT('',(2.279674784602,2.41198375621)); -#158426 = CARTESIAN_POINT('',(2.348396279953,2.407331199805)); -#158427 = CARTESIAN_POINT('',(2.417281014012,2.402329439048)); -#158428 = CARTESIAN_POINT('',(2.486165748071,2.397012884468)); -#158429 = CARTESIAN_POINT('',(2.554887243423,2.391420422455)); -#158430 = CARTESIAN_POINT('',(2.623284574238,2.385594472001)); -#158431 = CARTESIAN_POINT('',(2.691201358285,2.379579930936)); -#158432 = CARTESIAN_POINT('',(2.75848783298,2.373423064557)); -#158433 = CARTESIAN_POINT('',(2.825002696965,2.367170396506)); -#158434 = CARTESIAN_POINT('',(2.890614716316,2.360867638794)); -#158435 = CARTESIAN_POINT('',(2.955203867684,2.354558765666)); -#158436 = CARTESIAN_POINT('',(3.018662714711,2.348285047057)); -#158437 = CARTESIAN_POINT('',(3.080895346177,2.342084887057)); -#158438 = CARTESIAN_POINT('',(3.12151434906,2.338022572109)); -#158439 = CARTESIAN_POINT('',(3.14159265359,2.336014968589)); -#158440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158441 = PCURVE('',#158190,#158442); -#158442 = DEFINITIONAL_REPRESENTATION('',(#158443),#158469); -#158443 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158444,#158445,#158446, - #158447,#158448,#158449,#158450,#158451,#158452,#158453,#158454, - #158455,#158456,#158457,#158458,#158459,#158460,#158461,#158462, - #158463,#158464,#158465,#158466,#158467,#158468),.UNSPECIFIED.,.F., +#160807 = CARTESIAN_POINT('',(1.692969374435,2.435269583753)); +#160808 = CARTESIAN_POINT('',(1.713047678964,2.435025182465)); +#160809 = CARTESIAN_POINT('',(1.753666681847,2.434409604263)); +#160810 = CARTESIAN_POINT('',(1.815899313313,2.433090150347)); +#160811 = CARTESIAN_POINT('',(1.87935816034,2.431357242721)); +#160812 = CARTESIAN_POINT('',(1.943947311708,2.429199140074)); +#160813 = CARTESIAN_POINT('',(2.009559331059,2.426608676199)); +#160814 = CARTESIAN_POINT('',(2.076074195044,2.423584319582)); +#160815 = CARTESIAN_POINT('',(2.143360669739,2.420130506351)); +#160816 = CARTESIAN_POINT('',(2.211277453786,2.416257958446)); +#160817 = CARTESIAN_POINT('',(2.279674784602,2.41198375621)); +#160818 = CARTESIAN_POINT('',(2.348396279953,2.407331199805)); +#160819 = CARTESIAN_POINT('',(2.417281014012,2.402329439048)); +#160820 = CARTESIAN_POINT('',(2.486165748071,2.397012884468)); +#160821 = CARTESIAN_POINT('',(2.554887243423,2.391420422455)); +#160822 = CARTESIAN_POINT('',(2.623284574238,2.385594472001)); +#160823 = CARTESIAN_POINT('',(2.691201358285,2.379579930936)); +#160824 = CARTESIAN_POINT('',(2.75848783298,2.373423064557)); +#160825 = CARTESIAN_POINT('',(2.825002696965,2.367170396506)); +#160826 = CARTESIAN_POINT('',(2.890614716316,2.360867638794)); +#160827 = CARTESIAN_POINT('',(2.955203867684,2.354558765666)); +#160828 = CARTESIAN_POINT('',(3.018662714711,2.348285047057)); +#160829 = CARTESIAN_POINT('',(3.080895346177,2.342084887057)); +#160830 = CARTESIAN_POINT('',(3.12151434906,2.338022572109)); +#160831 = CARTESIAN_POINT('',(3.14159265359,2.336014968589)); +#160832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160833 = PCURVE('',#160582,#160834); +#160834 = DEFINITIONAL_REPRESENTATION('',(#160835),#160861); +#160835 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160836,#160837,#160838, + #160839,#160840,#160841,#160842,#160843,#160844,#160845,#160846, + #160847,#160848,#160849,#160850,#160851,#160852,#160853,#160854, + #160855,#160856,#160857,#160858,#160859,#160860),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195556,87 +198558,87 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158444 = CARTESIAN_POINT('',(1.692969374435,-1.935269583753)); -#158445 = CARTESIAN_POINT('',(1.713047678964,-1.935025182465)); -#158446 = CARTESIAN_POINT('',(1.753666681847,-1.934409604263)); -#158447 = CARTESIAN_POINT('',(1.815899313313,-1.933090150347)); -#158448 = CARTESIAN_POINT('',(1.87935816034,-1.931357242721)); -#158449 = CARTESIAN_POINT('',(1.943947311708,-1.929199140074)); -#158450 = CARTESIAN_POINT('',(2.009559331059,-1.926608676199)); -#158451 = CARTESIAN_POINT('',(2.076074195044,-1.923584319582)); -#158452 = CARTESIAN_POINT('',(2.143360669739,-1.920130506351)); -#158453 = CARTESIAN_POINT('',(2.211277453786,-1.916257958446)); -#158454 = CARTESIAN_POINT('',(2.279674784602,-1.91198375621)); -#158455 = CARTESIAN_POINT('',(2.348396279953,-1.907331199805)); -#158456 = CARTESIAN_POINT('',(2.417281014012,-1.902329439048)); -#158457 = CARTESIAN_POINT('',(2.486165748071,-1.897012884468)); -#158458 = CARTESIAN_POINT('',(2.554887243423,-1.891420422455)); -#158459 = CARTESIAN_POINT('',(2.623284574238,-1.885594472001)); -#158460 = CARTESIAN_POINT('',(2.691201358285,-1.879579930936)); -#158461 = CARTESIAN_POINT('',(2.75848783298,-1.873423064557)); -#158462 = CARTESIAN_POINT('',(2.825002696965,-1.867170396506)); -#158463 = CARTESIAN_POINT('',(2.890614716316,-1.860867638794)); -#158464 = CARTESIAN_POINT('',(2.955203867684,-1.854558765666)); -#158465 = CARTESIAN_POINT('',(3.018662714711,-1.848285047057)); -#158466 = CARTESIAN_POINT('',(3.080895346177,-1.842084887057)); -#158467 = CARTESIAN_POINT('',(3.12151434906,-1.838022572109)); -#158468 = CARTESIAN_POINT('',(3.14159265359,-1.836014968589)); -#158469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158470 = ADVANCED_FACE('',(#158471),#158190,.T.); -#158471 = FACE_BOUND('',#158472,.T.); -#158472 = EDGE_LOOP('',(#158473,#158474,#158475,#158497)); -#158473 = ORIENTED_EDGE('',*,*,#158174,.T.); -#158474 = ORIENTED_EDGE('',*,*,#158405,.T.); -#158475 = ORIENTED_EDGE('',*,*,#158476,.T.); -#158476 = EDGE_CURVE('',#158379,#158477,#158479,.T.); -#158477 = VERTEX_POINT('',#158478); -#158478 = CARTESIAN_POINT('',(2.336014968589,0.15,-1.836014968589)); -#158479 = SURFACE_CURVE('',#158480,(#158484,#158490),.PCURVE_S1.); -#158480 = LINE('',#158481,#158482); -#158481 = CARTESIAN_POINT('',(2.336014968589,0.15,2.316264938184E-066)); -#158482 = VECTOR('',#158483,1.); -#158483 = DIRECTION('',(0.E+000,1.437261152528E-033,-1.)); -#158484 = PCURVE('',#158190,#158485); -#158485 = DEFINITIONAL_REPRESENTATION('',(#158486),#158489); -#158486 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158487,#158488), +#160836 = CARTESIAN_POINT('',(1.692969374435,-1.935269583753)); +#160837 = CARTESIAN_POINT('',(1.713047678964,-1.935025182465)); +#160838 = CARTESIAN_POINT('',(1.753666681847,-1.934409604263)); +#160839 = CARTESIAN_POINT('',(1.815899313313,-1.933090150347)); +#160840 = CARTESIAN_POINT('',(1.87935816034,-1.931357242721)); +#160841 = CARTESIAN_POINT('',(1.943947311708,-1.929199140074)); +#160842 = CARTESIAN_POINT('',(2.009559331059,-1.926608676199)); +#160843 = CARTESIAN_POINT('',(2.076074195044,-1.923584319582)); +#160844 = CARTESIAN_POINT('',(2.143360669739,-1.920130506351)); +#160845 = CARTESIAN_POINT('',(2.211277453786,-1.916257958446)); +#160846 = CARTESIAN_POINT('',(2.279674784602,-1.91198375621)); +#160847 = CARTESIAN_POINT('',(2.348396279953,-1.907331199805)); +#160848 = CARTESIAN_POINT('',(2.417281014012,-1.902329439048)); +#160849 = CARTESIAN_POINT('',(2.486165748071,-1.897012884468)); +#160850 = CARTESIAN_POINT('',(2.554887243423,-1.891420422455)); +#160851 = CARTESIAN_POINT('',(2.623284574238,-1.885594472001)); +#160852 = CARTESIAN_POINT('',(2.691201358285,-1.879579930936)); +#160853 = CARTESIAN_POINT('',(2.75848783298,-1.873423064557)); +#160854 = CARTESIAN_POINT('',(2.825002696965,-1.867170396506)); +#160855 = CARTESIAN_POINT('',(2.890614716316,-1.860867638794)); +#160856 = CARTESIAN_POINT('',(2.955203867684,-1.854558765666)); +#160857 = CARTESIAN_POINT('',(3.018662714711,-1.848285047057)); +#160858 = CARTESIAN_POINT('',(3.080895346177,-1.842084887057)); +#160859 = CARTESIAN_POINT('',(3.12151434906,-1.838022572109)); +#160860 = CARTESIAN_POINT('',(3.14159265359,-1.836014968589)); +#160861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160862 = ADVANCED_FACE('',(#160863),#160582,.T.); +#160863 = FACE_BOUND('',#160864,.T.); +#160864 = EDGE_LOOP('',(#160865,#160866,#160867,#160889)); +#160865 = ORIENTED_EDGE('',*,*,#160566,.T.); +#160866 = ORIENTED_EDGE('',*,*,#160797,.T.); +#160867 = ORIENTED_EDGE('',*,*,#160868,.T.); +#160868 = EDGE_CURVE('',#160771,#160869,#160871,.T.); +#160869 = VERTEX_POINT('',#160870); +#160870 = CARTESIAN_POINT('',(2.336014968589,0.15,-1.836014968589)); +#160871 = SURFACE_CURVE('',#160872,(#160876,#160882),.PCURVE_S1.); +#160872 = LINE('',#160873,#160874); +#160873 = CARTESIAN_POINT('',(2.336014968589,0.15,2.316264938184E-066)); +#160874 = VECTOR('',#160875,1.); +#160875 = DIRECTION('',(0.E+000,1.437261152528E-033,-1.)); +#160876 = PCURVE('',#160582,#160877); +#160877 = DEFINITIONAL_REPRESENTATION('',(#160878),#160881); +#160878 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160879,#160880), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.836014968589,1.836014968589), .PIECEWISE_BEZIER_KNOTS.); -#158487 = CARTESIAN_POINT('',(3.14159265359,-1.836014968589)); -#158488 = CARTESIAN_POINT('',(3.14159265359,1.836014968589)); -#158489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160879 = CARTESIAN_POINT('',(3.14159265359,-1.836014968589)); +#160880 = CARTESIAN_POINT('',(3.14159265359,1.836014968589)); +#160881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158490 = PCURVE('',#158393,#158491); -#158491 = DEFINITIONAL_REPRESENTATION('',(#158492),#158496); -#158492 = LINE('',#158493,#158494); -#158493 = CARTESIAN_POINT('',(4.632529876367E-066,2.336014968589)); -#158494 = VECTOR('',#158495,1.); -#158495 = DIRECTION('',(-1.,-2.219884210458E-083)); -#158496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160882 = PCURVE('',#160785,#160883); +#160883 = DEFINITIONAL_REPRESENTATION('',(#160884),#160888); +#160884 = LINE('',#160885,#160886); +#160885 = CARTESIAN_POINT('',(4.632529876367E-066,2.336014968589)); +#160886 = VECTOR('',#160887,1.); +#160887 = DIRECTION('',(-1.,-2.219884210458E-083)); +#160888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158497 = ORIENTED_EDGE('',*,*,#158498,.F.); -#158498 = EDGE_CURVE('',#158175,#158477,#158499,.T.); -#158499 = SURFACE_CURVE('',#158500,(#158505,#158534),.PCURVE_S1.); -#158500 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#158501,#158502,#158503, -#158504),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#160889 = ORIENTED_EDGE('',*,*,#160890,.F.); +#160890 = EDGE_CURVE('',#160567,#160869,#160891,.T.); +#160891 = SURFACE_CURVE('',#160892,(#160897,#160926),.PCURVE_S1.); +#160892 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#160893,#160894,#160895, +#160896),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.263765701229,4.712388980385),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#158501 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, +#160893 = CARTESIAN_POINT('',(2.435269583753,0.237813065659, -1.935269583753)); -#158502 = CARTESIAN_POINT('',(2.428803936584,0.185154595234, +#160894 = CARTESIAN_POINT('',(2.428803936584,0.185154595234, -1.928803936584)); -#158503 = CARTESIAN_POINT('',(2.389068894936,0.15,-1.889068894936)); -#158504 = CARTESIAN_POINT('',(2.336014968589,0.15,-1.836014968589)); -#158505 = PCURVE('',#158190,#158506); -#158506 = DEFINITIONAL_REPRESENTATION('',(#158507),#158533); -#158507 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158508,#158509,#158510, - #158511,#158512,#158513,#158514,#158515,#158516,#158517,#158518, - #158519,#158520,#158521,#158522,#158523,#158524,#158525,#158526, - #158527,#158528,#158529,#158530,#158531,#158532),.UNSPECIFIED.,.F., +#160895 = CARTESIAN_POINT('',(2.389068894936,0.15,-1.889068894936)); +#160896 = CARTESIAN_POINT('',(2.336014968589,0.15,-1.836014968589)); +#160897 = PCURVE('',#160582,#160898); +#160898 = DEFINITIONAL_REPRESENTATION('',(#160899),#160925); +#160899 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160900,#160901,#160902, + #160903,#160904,#160905,#160906,#160907,#160908,#160909,#160910, + #160911,#160912,#160913,#160914,#160915,#160916,#160917,#160918, + #160919,#160920,#160921,#160922,#160923,#160924),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195644,40 +198646,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158508 = CARTESIAN_POINT('',(1.692969374435,1.935269583753)); -#158509 = CARTESIAN_POINT('',(1.713047678964,1.935025182465)); -#158510 = CARTESIAN_POINT('',(1.753666681847,1.934409604263)); -#158511 = CARTESIAN_POINT('',(1.815899313313,1.933090150347)); -#158512 = CARTESIAN_POINT('',(1.87935816034,1.931357242721)); -#158513 = CARTESIAN_POINT('',(1.943947311708,1.929199140074)); -#158514 = CARTESIAN_POINT('',(2.009559331059,1.926608676199)); -#158515 = CARTESIAN_POINT('',(2.076074195044,1.923584319582)); -#158516 = CARTESIAN_POINT('',(2.143360669739,1.920130506351)); -#158517 = CARTESIAN_POINT('',(2.211277453786,1.916257958446)); -#158518 = CARTESIAN_POINT('',(2.279674784602,1.91198375621)); -#158519 = CARTESIAN_POINT('',(2.348396279953,1.907331199805)); -#158520 = CARTESIAN_POINT('',(2.417281014012,1.902329439048)); -#158521 = CARTESIAN_POINT('',(2.486165748071,1.897012884468)); -#158522 = CARTESIAN_POINT('',(2.554887243423,1.891420422455)); -#158523 = CARTESIAN_POINT('',(2.623284574238,1.885594472001)); -#158524 = CARTESIAN_POINT('',(2.691201358285,1.879579930936)); -#158525 = CARTESIAN_POINT('',(2.75848783298,1.873423064557)); -#158526 = CARTESIAN_POINT('',(2.825002696965,1.867170396506)); -#158527 = CARTESIAN_POINT('',(2.890614716316,1.860867638794)); -#158528 = CARTESIAN_POINT('',(2.955203867684,1.854558765666)); -#158529 = CARTESIAN_POINT('',(3.018662714711,1.848285047057)); -#158530 = CARTESIAN_POINT('',(3.080895346177,1.842084887057)); -#158531 = CARTESIAN_POINT('',(3.12151434906,1.838022572109)); -#158532 = CARTESIAN_POINT('',(3.14159265359,1.836014968589)); -#158533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158534 = PCURVE('',#158243,#158535); -#158535 = DEFINITIONAL_REPRESENTATION('',(#158536),#158562); -#158536 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158537,#158538,#158539, - #158540,#158541,#158542,#158543,#158544,#158545,#158546,#158547, - #158548,#158549,#158550,#158551,#158552,#158553,#158554,#158555, - #158556,#158557,#158558,#158559,#158560,#158561),.UNSPECIFIED.,.F., +#160900 = CARTESIAN_POINT('',(1.692969374435,1.935269583753)); +#160901 = CARTESIAN_POINT('',(1.713047678964,1.935025182465)); +#160902 = CARTESIAN_POINT('',(1.753666681847,1.934409604263)); +#160903 = CARTESIAN_POINT('',(1.815899313313,1.933090150347)); +#160904 = CARTESIAN_POINT('',(1.87935816034,1.931357242721)); +#160905 = CARTESIAN_POINT('',(1.943947311708,1.929199140074)); +#160906 = CARTESIAN_POINT('',(2.009559331059,1.926608676199)); +#160907 = CARTESIAN_POINT('',(2.076074195044,1.923584319582)); +#160908 = CARTESIAN_POINT('',(2.143360669739,1.920130506351)); +#160909 = CARTESIAN_POINT('',(2.211277453786,1.916257958446)); +#160910 = CARTESIAN_POINT('',(2.279674784602,1.91198375621)); +#160911 = CARTESIAN_POINT('',(2.348396279953,1.907331199805)); +#160912 = CARTESIAN_POINT('',(2.417281014012,1.902329439048)); +#160913 = CARTESIAN_POINT('',(2.486165748071,1.897012884468)); +#160914 = CARTESIAN_POINT('',(2.554887243423,1.891420422455)); +#160915 = CARTESIAN_POINT('',(2.623284574238,1.885594472001)); +#160916 = CARTESIAN_POINT('',(2.691201358285,1.879579930936)); +#160917 = CARTESIAN_POINT('',(2.75848783298,1.873423064557)); +#160918 = CARTESIAN_POINT('',(2.825002696965,1.867170396506)); +#160919 = CARTESIAN_POINT('',(2.890614716316,1.860867638794)); +#160920 = CARTESIAN_POINT('',(2.955203867684,1.854558765666)); +#160921 = CARTESIAN_POINT('',(3.018662714711,1.848285047057)); +#160922 = CARTESIAN_POINT('',(3.080895346177,1.842084887057)); +#160923 = CARTESIAN_POINT('',(3.12151434906,1.838022572109)); +#160924 = CARTESIAN_POINT('',(3.14159265359,1.836014968589)); +#160925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160926 = PCURVE('',#160635,#160927); +#160927 = DEFINITIONAL_REPRESENTATION('',(#160928),#160954); +#160928 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160929,#160930,#160931, + #160932,#160933,#160934,#160935,#160936,#160937,#160938,#160939, + #160940,#160941,#160942,#160943,#160944,#160945,#160946,#160947, + #160948,#160949,#160950,#160951,#160952,#160953),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195685,88 +198687,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158537 = CARTESIAN_POINT('',(4.834562028024,-2.435269583753)); -#158538 = CARTESIAN_POINT('',(4.854640332554,-2.435025182465)); -#158539 = CARTESIAN_POINT('',(4.895259335437,-2.434409604263)); -#158540 = CARTESIAN_POINT('',(4.957491966903,-2.433090150347)); -#158541 = CARTESIAN_POINT('',(5.02095081393,-2.431357242721)); -#158542 = CARTESIAN_POINT('',(5.085539965298,-2.429199140074)); -#158543 = CARTESIAN_POINT('',(5.151151984649,-2.426608676199)); -#158544 = CARTESIAN_POINT('',(5.217666848634,-2.423584319582)); -#158545 = CARTESIAN_POINT('',(5.284953323329,-2.420130506351)); -#158546 = CARTESIAN_POINT('',(5.352870107376,-2.416257958446)); -#158547 = CARTESIAN_POINT('',(5.421267438192,-2.41198375621)); -#158548 = CARTESIAN_POINT('',(5.489988933543,-2.407331199805)); -#158549 = CARTESIAN_POINT('',(5.558873667602,-2.402329439048)); -#158550 = CARTESIAN_POINT('',(5.627758401661,-2.397012884468)); -#158551 = CARTESIAN_POINT('',(5.696479897012,-2.391420422455)); -#158552 = CARTESIAN_POINT('',(5.764877227828,-2.385594472001)); -#158553 = CARTESIAN_POINT('',(5.832794011875,-2.379579930936)); -#158554 = CARTESIAN_POINT('',(5.90008048657,-2.373423064557)); -#158555 = CARTESIAN_POINT('',(5.966595350555,-2.367170396506)); -#158556 = CARTESIAN_POINT('',(6.032207369906,-2.360867638794)); -#158557 = CARTESIAN_POINT('',(6.096796521274,-2.354558765666)); -#158558 = CARTESIAN_POINT('',(6.160255368301,-2.348285047057)); -#158559 = CARTESIAN_POINT('',(6.222487999767,-2.342084887057)); -#158560 = CARTESIAN_POINT('',(6.26310700265,-2.338022572109)); -#158561 = CARTESIAN_POINT('',(6.28318530718,-2.336014968589)); -#158562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158563 = ADVANCED_FACE('',(#158564),#158243,.T.); -#158564 = FACE_BOUND('',#158565,.T.); -#158565 = EDGE_LOOP('',(#158566,#158567,#158568,#158590)); -#158566 = ORIENTED_EDGE('',*,*,#158227,.T.); -#158567 = ORIENTED_EDGE('',*,*,#158498,.T.); -#158568 = ORIENTED_EDGE('',*,*,#158569,.T.); -#158569 = EDGE_CURVE('',#158477,#158570,#158572,.T.); -#158570 = VERTEX_POINT('',#158571); -#158571 = CARTESIAN_POINT('',(-2.336014968589,0.15,-1.836014968589)); -#158572 = SURFACE_CURVE('',#158573,(#158577,#158583),.PCURVE_S1.); -#158573 = LINE('',#158574,#158575); -#158574 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,-1.836014968589) - ); -#158575 = VECTOR('',#158576,1.); -#158576 = DIRECTION('',(-1.,-6.898853532133E-034,-9.915454178714E-067)); -#158577 = PCURVE('',#158243,#158578); -#158578 = DEFINITIONAL_REPRESENTATION('',(#158579),#158582); -#158579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158580,#158581), +#160929 = CARTESIAN_POINT('',(4.834562028024,-2.435269583753)); +#160930 = CARTESIAN_POINT('',(4.854640332554,-2.435025182465)); +#160931 = CARTESIAN_POINT('',(4.895259335437,-2.434409604263)); +#160932 = CARTESIAN_POINT('',(4.957491966903,-2.433090150347)); +#160933 = CARTESIAN_POINT('',(5.02095081393,-2.431357242721)); +#160934 = CARTESIAN_POINT('',(5.085539965298,-2.429199140074)); +#160935 = CARTESIAN_POINT('',(5.151151984649,-2.426608676199)); +#160936 = CARTESIAN_POINT('',(5.217666848634,-2.423584319582)); +#160937 = CARTESIAN_POINT('',(5.284953323329,-2.420130506351)); +#160938 = CARTESIAN_POINT('',(5.352870107376,-2.416257958446)); +#160939 = CARTESIAN_POINT('',(5.421267438192,-2.41198375621)); +#160940 = CARTESIAN_POINT('',(5.489988933543,-2.407331199805)); +#160941 = CARTESIAN_POINT('',(5.558873667602,-2.402329439048)); +#160942 = CARTESIAN_POINT('',(5.627758401661,-2.397012884468)); +#160943 = CARTESIAN_POINT('',(5.696479897012,-2.391420422455)); +#160944 = CARTESIAN_POINT('',(5.764877227828,-2.385594472001)); +#160945 = CARTESIAN_POINT('',(5.832794011875,-2.379579930936)); +#160946 = CARTESIAN_POINT('',(5.90008048657,-2.373423064557)); +#160947 = CARTESIAN_POINT('',(5.966595350555,-2.367170396506)); +#160948 = CARTESIAN_POINT('',(6.032207369906,-2.360867638794)); +#160949 = CARTESIAN_POINT('',(6.096796521274,-2.354558765666)); +#160950 = CARTESIAN_POINT('',(6.160255368301,-2.348285047057)); +#160951 = CARTESIAN_POINT('',(6.222487999767,-2.342084887057)); +#160952 = CARTESIAN_POINT('',(6.26310700265,-2.338022572109)); +#160953 = CARTESIAN_POINT('',(6.28318530718,-2.336014968589)); +#160954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#160955 = ADVANCED_FACE('',(#160956),#160635,.T.); +#160956 = FACE_BOUND('',#160957,.T.); +#160957 = EDGE_LOOP('',(#160958,#160959,#160960,#160982)); +#160958 = ORIENTED_EDGE('',*,*,#160619,.T.); +#160959 = ORIENTED_EDGE('',*,*,#160890,.T.); +#160960 = ORIENTED_EDGE('',*,*,#160961,.T.); +#160961 = EDGE_CURVE('',#160869,#160962,#160964,.T.); +#160962 = VERTEX_POINT('',#160963); +#160963 = CARTESIAN_POINT('',(-2.336014968589,0.15,-1.836014968589)); +#160964 = SURFACE_CURVE('',#160965,(#160969,#160975),.PCURVE_S1.); +#160965 = LINE('',#160966,#160967); +#160966 = CARTESIAN_POINT('',(2.733503659115E-017,0.15,-1.836014968589) + ); +#160967 = VECTOR('',#160968,1.); +#160968 = DIRECTION('',(-1.,-6.898853532133E-034,-9.915454178714E-067)); +#160969 = PCURVE('',#160635,#160970); +#160970 = DEFINITIONAL_REPRESENTATION('',(#160971),#160974); +#160971 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160972,#160973), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.336014968589,2.336014968589), .PIECEWISE_BEZIER_KNOTS.); -#158580 = CARTESIAN_POINT('',(6.28318530718,-2.336014968589)); -#158581 = CARTESIAN_POINT('',(6.28318530718,2.336014968589)); -#158582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160972 = CARTESIAN_POINT('',(6.28318530718,-2.336014968589)); +#160973 = CARTESIAN_POINT('',(6.28318530718,2.336014968589)); +#160974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158583 = PCURVE('',#158393,#158584); -#158584 = DEFINITIONAL_REPRESENTATION('',(#158585),#158589); -#158585 = LINE('',#158586,#158587); -#158586 = CARTESIAN_POINT('',(-1.836014968589,-1.820492229248E-066)); -#158587 = VECTOR('',#158588,1.); -#158588 = DIRECTION('',(0.E+000,-1.)); -#158589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#160975 = PCURVE('',#160785,#160976); +#160976 = DEFINITIONAL_REPRESENTATION('',(#160977),#160981); +#160977 = LINE('',#160978,#160979); +#160978 = CARTESIAN_POINT('',(-1.836014968589,-1.820492229248E-066)); +#160979 = VECTOR('',#160980,1.); +#160980 = DIRECTION('',(0.E+000,-1.)); +#160981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158590 = ORIENTED_EDGE('',*,*,#158591,.F.); -#158591 = EDGE_CURVE('',#158228,#158570,#158592,.T.); -#158592 = SURFACE_CURVE('',#158593,(#158598,#158627),.PCURVE_S1.); -#158593 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#158594,#158595,#158596, -#158597),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#160982 = ORIENTED_EDGE('',*,*,#160983,.F.); +#160983 = EDGE_CURVE('',#160620,#160962,#160984,.T.); +#160984 = SURFACE_CURVE('',#160985,(#160990,#161019),.PCURVE_S1.); +#160985 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#160986,#160987,#160988, +#160989),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.263765701229,4.712388980385),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.832637147193,0.832637147193,1.)) REPRESENTATION_ITEM('') ); -#158594 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, +#160986 = CARTESIAN_POINT('',(-2.435269583753,0.237813065659, -1.935269583753)); -#158595 = CARTESIAN_POINT('',(-2.428803936584,0.185154595234, +#160987 = CARTESIAN_POINT('',(-2.428803936584,0.185154595234, -1.928803936584)); -#158596 = CARTESIAN_POINT('',(-2.389068894936,0.15,-1.889068894936)); -#158597 = CARTESIAN_POINT('',(-2.336014968589,0.15,-1.836014968589)); -#158598 = PCURVE('',#158243,#158599); -#158599 = DEFINITIONAL_REPRESENTATION('',(#158600),#158626); -#158600 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158601,#158602,#158603, - #158604,#158605,#158606,#158607,#158608,#158609,#158610,#158611, - #158612,#158613,#158614,#158615,#158616,#158617,#158618,#158619, - #158620,#158621,#158622,#158623,#158624,#158625),.UNSPECIFIED.,.F., +#160988 = CARTESIAN_POINT('',(-2.389068894936,0.15,-1.889068894936)); +#160989 = CARTESIAN_POINT('',(-2.336014968589,0.15,-1.836014968589)); +#160990 = PCURVE('',#160635,#160991); +#160991 = DEFINITIONAL_REPRESENTATION('',(#160992),#161018); +#160992 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#160993,#160994,#160995, + #160996,#160997,#160998,#160999,#161000,#161001,#161002,#161003, + #161004,#161005,#161006,#161007,#161008,#161009,#161010,#161011, + #161012,#161013,#161014,#161015,#161016,#161017),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195774,40 +198776,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158601 = CARTESIAN_POINT('',(4.834562028024,2.435269583753)); -#158602 = CARTESIAN_POINT('',(4.854640332554,2.435025182465)); -#158603 = CARTESIAN_POINT('',(4.895259335437,2.434409604263)); -#158604 = CARTESIAN_POINT('',(4.957491966903,2.433090150347)); -#158605 = CARTESIAN_POINT('',(5.02095081393,2.431357242721)); -#158606 = CARTESIAN_POINT('',(5.085539965298,2.429199140074)); -#158607 = CARTESIAN_POINT('',(5.151151984649,2.426608676199)); -#158608 = CARTESIAN_POINT('',(5.217666848634,2.423584319582)); -#158609 = CARTESIAN_POINT('',(5.284953323329,2.420130506351)); -#158610 = CARTESIAN_POINT('',(5.352870107376,2.416257958446)); -#158611 = CARTESIAN_POINT('',(5.421267438192,2.41198375621)); -#158612 = CARTESIAN_POINT('',(5.489988933543,2.407331199805)); -#158613 = CARTESIAN_POINT('',(5.558873667602,2.402329439048)); -#158614 = CARTESIAN_POINT('',(5.627758401661,2.397012884468)); -#158615 = CARTESIAN_POINT('',(5.696479897012,2.391420422455)); -#158616 = CARTESIAN_POINT('',(5.764877227828,2.385594472001)); -#158617 = CARTESIAN_POINT('',(5.832794011875,2.379579930936)); -#158618 = CARTESIAN_POINT('',(5.90008048657,2.373423064557)); -#158619 = CARTESIAN_POINT('',(5.966595350555,2.367170396506)); -#158620 = CARTESIAN_POINT('',(6.032207369906,2.360867638794)); -#158621 = CARTESIAN_POINT('',(6.096796521274,2.354558765666)); -#158622 = CARTESIAN_POINT('',(6.160255368301,2.348285047057)); -#158623 = CARTESIAN_POINT('',(6.222487999767,2.342084887057)); -#158624 = CARTESIAN_POINT('',(6.26310700265,2.338022572109)); -#158625 = CARTESIAN_POINT('',(6.28318530718,2.336014968589)); -#158626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158627 = PCURVE('',#158294,#158628); -#158628 = DEFINITIONAL_REPRESENTATION('',(#158629),#158655); -#158629 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#158630,#158631,#158632, - #158633,#158634,#158635,#158636,#158637,#158638,#158639,#158640, - #158641,#158642,#158643,#158644,#158645,#158646,#158647,#158648, - #158649,#158650,#158651,#158652,#158653,#158654),.UNSPECIFIED.,.F., +#160993 = CARTESIAN_POINT('',(4.834562028024,2.435269583753)); +#160994 = CARTESIAN_POINT('',(4.854640332554,2.435025182465)); +#160995 = CARTESIAN_POINT('',(4.895259335437,2.434409604263)); +#160996 = CARTESIAN_POINT('',(4.957491966903,2.433090150347)); +#160997 = CARTESIAN_POINT('',(5.02095081393,2.431357242721)); +#160998 = CARTESIAN_POINT('',(5.085539965298,2.429199140074)); +#160999 = CARTESIAN_POINT('',(5.151151984649,2.426608676199)); +#161000 = CARTESIAN_POINT('',(5.217666848634,2.423584319582)); +#161001 = CARTESIAN_POINT('',(5.284953323329,2.420130506351)); +#161002 = CARTESIAN_POINT('',(5.352870107376,2.416257958446)); +#161003 = CARTESIAN_POINT('',(5.421267438192,2.41198375621)); +#161004 = CARTESIAN_POINT('',(5.489988933543,2.407331199805)); +#161005 = CARTESIAN_POINT('',(5.558873667602,2.402329439048)); +#161006 = CARTESIAN_POINT('',(5.627758401661,2.397012884468)); +#161007 = CARTESIAN_POINT('',(5.696479897012,2.391420422455)); +#161008 = CARTESIAN_POINT('',(5.764877227828,2.385594472001)); +#161009 = CARTESIAN_POINT('',(5.832794011875,2.379579930936)); +#161010 = CARTESIAN_POINT('',(5.90008048657,2.373423064557)); +#161011 = CARTESIAN_POINT('',(5.966595350555,2.367170396506)); +#161012 = CARTESIAN_POINT('',(6.032207369906,2.360867638794)); +#161013 = CARTESIAN_POINT('',(6.096796521274,2.354558765666)); +#161014 = CARTESIAN_POINT('',(6.160255368301,2.348285047057)); +#161015 = CARTESIAN_POINT('',(6.222487999767,2.342084887057)); +#161016 = CARTESIAN_POINT('',(6.26310700265,2.338022572109)); +#161017 = CARTESIAN_POINT('',(6.28318530718,2.336014968589)); +#161018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161019 = PCURVE('',#160686,#161020); +#161020 = DEFINITIONAL_REPRESENTATION('',(#161021),#161047); +#161021 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#161022,#161023,#161024, + #161025,#161026,#161027,#161028,#161029,#161030,#161031,#161032, + #161033,#161034,#161035,#161036,#161037,#161038,#161039,#161040, + #161041,#161042,#161043,#161044,#161045,#161046),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.263765701229, 3.329612213918,3.395458726607,3.461305239296,3.527151751985, 3.592998264674,3.658844777363,3.724691290052,3.79053780274, @@ -195815,12344 +198817,12344 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.119770366185,4.185616878874,4.251463391563,4.317309904251, 4.38315641694,4.449002929629,4.514849442318,4.580695955007, 4.646542467696,4.712388980385),.QUASI_UNIFORM_KNOTS.); -#158630 = CARTESIAN_POINT('',(4.834562028024,-1.935269583753)); -#158631 = CARTESIAN_POINT('',(4.854640332554,-1.935025182465)); -#158632 = CARTESIAN_POINT('',(4.895259335437,-1.934409604263)); -#158633 = CARTESIAN_POINT('',(4.957491966903,-1.933090150347)); -#158634 = CARTESIAN_POINT('',(5.02095081393,-1.931357242721)); -#158635 = CARTESIAN_POINT('',(5.085539965298,-1.929199140074)); -#158636 = CARTESIAN_POINT('',(5.151151984649,-1.926608676199)); -#158637 = CARTESIAN_POINT('',(5.217666848634,-1.923584319582)); -#158638 = CARTESIAN_POINT('',(5.284953323329,-1.920130506351)); -#158639 = CARTESIAN_POINT('',(5.352870107376,-1.916257958446)); -#158640 = CARTESIAN_POINT('',(5.421267438192,-1.91198375621)); -#158641 = CARTESIAN_POINT('',(5.489988933543,-1.907331199805)); -#158642 = CARTESIAN_POINT('',(5.558873667602,-1.902329439048)); -#158643 = CARTESIAN_POINT('',(5.627758401661,-1.897012884468)); -#158644 = CARTESIAN_POINT('',(5.696479897012,-1.891420422455)); -#158645 = CARTESIAN_POINT('',(5.764877227828,-1.885594472001)); -#158646 = CARTESIAN_POINT('',(5.832794011875,-1.879579930936)); -#158647 = CARTESIAN_POINT('',(5.90008048657,-1.873423064557)); -#158648 = CARTESIAN_POINT('',(5.966595350555,-1.867170396506)); -#158649 = CARTESIAN_POINT('',(6.032207369906,-1.860867638794)); -#158650 = CARTESIAN_POINT('',(6.096796521274,-1.854558765666)); -#158651 = CARTESIAN_POINT('',(6.160255368301,-1.848285047057)); -#158652 = CARTESIAN_POINT('',(6.222487999767,-1.842084887057)); -#158653 = CARTESIAN_POINT('',(6.26310700265,-1.838022572109)); -#158654 = CARTESIAN_POINT('',(6.28318530718,-1.836014968589)); -#158655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158656 = ADVANCED_FACE('',(#158657),#158294,.T.); -#158657 = FACE_BOUND('',#158658,.T.); -#158658 = EDGE_LOOP('',(#158659,#158660,#158661,#158681)); -#158659 = ORIENTED_EDGE('',*,*,#158280,.T.); -#158660 = ORIENTED_EDGE('',*,*,#158591,.T.); -#158661 = ORIENTED_EDGE('',*,*,#158662,.T.); -#158662 = EDGE_CURVE('',#158570,#158311,#158663,.T.); -#158663 = SURFACE_CURVE('',#158664,(#158668,#158674),.PCURVE_S1.); -#158664 = LINE('',#158665,#158666); -#158665 = CARTESIAN_POINT('',(-2.336014968589,0.15,-2.316264938184E-066) - ); -#158666 = VECTOR('',#158667,1.); -#158667 = DIRECTION('',(0.E+000,-1.437261152528E-033,1.)); -#158668 = PCURVE('',#158294,#158669); -#158669 = DEFINITIONAL_REPRESENTATION('',(#158670),#158673); -#158670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158671,#158672), +#161022 = CARTESIAN_POINT('',(4.834562028024,-1.935269583753)); +#161023 = CARTESIAN_POINT('',(4.854640332554,-1.935025182465)); +#161024 = CARTESIAN_POINT('',(4.895259335437,-1.934409604263)); +#161025 = CARTESIAN_POINT('',(4.957491966903,-1.933090150347)); +#161026 = CARTESIAN_POINT('',(5.02095081393,-1.931357242721)); +#161027 = CARTESIAN_POINT('',(5.085539965298,-1.929199140074)); +#161028 = CARTESIAN_POINT('',(5.151151984649,-1.926608676199)); +#161029 = CARTESIAN_POINT('',(5.217666848634,-1.923584319582)); +#161030 = CARTESIAN_POINT('',(5.284953323329,-1.920130506351)); +#161031 = CARTESIAN_POINT('',(5.352870107376,-1.916257958446)); +#161032 = CARTESIAN_POINT('',(5.421267438192,-1.91198375621)); +#161033 = CARTESIAN_POINT('',(5.489988933543,-1.907331199805)); +#161034 = CARTESIAN_POINT('',(5.558873667602,-1.902329439048)); +#161035 = CARTESIAN_POINT('',(5.627758401661,-1.897012884468)); +#161036 = CARTESIAN_POINT('',(5.696479897012,-1.891420422455)); +#161037 = CARTESIAN_POINT('',(5.764877227828,-1.885594472001)); +#161038 = CARTESIAN_POINT('',(5.832794011875,-1.879579930936)); +#161039 = CARTESIAN_POINT('',(5.90008048657,-1.873423064557)); +#161040 = CARTESIAN_POINT('',(5.966595350555,-1.867170396506)); +#161041 = CARTESIAN_POINT('',(6.032207369906,-1.860867638794)); +#161042 = CARTESIAN_POINT('',(6.096796521274,-1.854558765666)); +#161043 = CARTESIAN_POINT('',(6.160255368301,-1.848285047057)); +#161044 = CARTESIAN_POINT('',(6.222487999767,-1.842084887057)); +#161045 = CARTESIAN_POINT('',(6.26310700265,-1.838022572109)); +#161046 = CARTESIAN_POINT('',(6.28318530718,-1.836014968589)); +#161047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161048 = ADVANCED_FACE('',(#161049),#160686,.T.); +#161049 = FACE_BOUND('',#161050,.T.); +#161050 = EDGE_LOOP('',(#161051,#161052,#161053,#161073)); +#161051 = ORIENTED_EDGE('',*,*,#160672,.T.); +#161052 = ORIENTED_EDGE('',*,*,#160983,.T.); +#161053 = ORIENTED_EDGE('',*,*,#161054,.T.); +#161054 = EDGE_CURVE('',#160962,#160703,#161055,.T.); +#161055 = SURFACE_CURVE('',#161056,(#161060,#161066),.PCURVE_S1.); +#161056 = LINE('',#161057,#161058); +#161057 = CARTESIAN_POINT('',(-2.336014968589,0.15,-2.316264938184E-066) + ); +#161058 = VECTOR('',#161059,1.); +#161059 = DIRECTION('',(0.E+000,-1.437261152528E-033,1.)); +#161060 = PCURVE('',#160686,#161061); +#161061 = DEFINITIONAL_REPRESENTATION('',(#161062),#161065); +#161062 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161063,#161064), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.836014968589,1.836014968589), .PIECEWISE_BEZIER_KNOTS.); -#158671 = CARTESIAN_POINT('',(6.28318530718,-1.836014968589)); -#158672 = CARTESIAN_POINT('',(6.28318530718,1.836014968589)); -#158673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158674 = PCURVE('',#158393,#158675); -#158675 = DEFINITIONAL_REPRESENTATION('',(#158676),#158680); -#158676 = LINE('',#158677,#158678); -#158677 = CARTESIAN_POINT('',(-4.632529876367E-066,-2.336014968589)); -#158678 = VECTOR('',#158679,1.); -#158679 = DIRECTION('',(1.,2.219884210458E-083)); -#158680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158681 = ORIENTED_EDGE('',*,*,#158310,.T.); -#158682 = ADVANCED_FACE('',(#158683),#158393,.F.); -#158683 = FACE_BOUND('',#158684,.T.); -#158684 = EDGE_LOOP('',(#158685,#158686,#158687,#158688)); -#158685 = ORIENTED_EDGE('',*,*,#158569,.F.); -#158686 = ORIENTED_EDGE('',*,*,#158476,.F.); -#158687 = ORIENTED_EDGE('',*,*,#158378,.F.); -#158688 = ORIENTED_EDGE('',*,*,#158662,.F.); -#158689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#158693)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#158690,#158691,#158692)) +#161063 = CARTESIAN_POINT('',(6.28318530718,-1.836014968589)); +#161064 = CARTESIAN_POINT('',(6.28318530718,1.836014968589)); +#161065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161066 = PCURVE('',#160785,#161067); +#161067 = DEFINITIONAL_REPRESENTATION('',(#161068),#161072); +#161068 = LINE('',#161069,#161070); +#161069 = CARTESIAN_POINT('',(-4.632529876367E-066,-2.336014968589)); +#161070 = VECTOR('',#161071,1.); +#161071 = DIRECTION('',(1.,2.219884210458E-083)); +#161072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161073 = ORIENTED_EDGE('',*,*,#160702,.T.); +#161074 = ADVANCED_FACE('',(#161075),#160785,.F.); +#161075 = FACE_BOUND('',#161076,.T.); +#161076 = EDGE_LOOP('',(#161077,#161078,#161079,#161080)); +#161077 = ORIENTED_EDGE('',*,*,#160961,.F.); +#161078 = ORIENTED_EDGE('',*,*,#160868,.F.); +#161079 = ORIENTED_EDGE('',*,*,#160770,.F.); +#161080 = ORIENTED_EDGE('',*,*,#161054,.F.); +#161081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#161085)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#161082,#161083,#161084)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#158690 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#158691 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#158692 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#158693 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-006),#158690, +#161082 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#161083 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#161084 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#161085 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-006),#161082, 'distance_accuracy_value','confusion accuracy'); -#158694 = SHAPE_DEFINITION_REPRESENTATION(#158695,#156706); -#158695 = PRODUCT_DEFINITION_SHAPE('','',#158696); -#158696 = PRODUCT_DEFINITION('design','',#158697,#158700); -#158697 = PRODUCT_DEFINITION_FORMATION('','',#158698); -#158698 = PRODUCT('User_Library-SOIC-8_SOIC-8_Body_1', - 'User_Library-SOIC-8_SOIC-8_Body_1','',(#158699)); -#158699 = PRODUCT_CONTEXT('',#2,'mechanical'); -#158700 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#158701 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#158702,#158704); -#158702 = ( REPRESENTATION_RELATIONSHIP('','',#156706,#156692) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#158703) +#161086 = SHAPE_DEFINITION_REPRESENTATION(#161087,#159098); +#161087 = PRODUCT_DEFINITION_SHAPE('','',#161088); +#161088 = PRODUCT_DEFINITION('design','',#161089,#161092); +#161089 = PRODUCT_DEFINITION_FORMATION('','',#161090); +#161090 = PRODUCT('User_Library-SOIC-8_SOIC-8_Body_1', + 'User_Library-SOIC-8_SOIC-8_Body_1','',(#161091)); +#161091 = PRODUCT_CONTEXT('',#2,'mechanical'); +#161092 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#161093 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#161094,#161096); +#161094 = ( REPRESENTATION_RELATIONSHIP('','',#159098,#159084) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#161095) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#158703 = ITEM_DEFINED_TRANSFORMATION('','',#11,#156693); -#158704 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #158705); -#158705 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('271','','',#156687,#158696,$); -#158706 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#158698)); -#158707 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#158708),#165998); -#158708 = MANIFOLD_SOLID_BREP('',#158709); -#158709 = CLOSED_SHELL('',(#158710,#158828,#158911,#158987,#159063, - #159138,#159213,#159288,#159371,#159489,#159572,#159648,#159724, - #159799,#159874,#159949,#160027,#160145,#160228,#160304,#160380, - #160455,#160530,#160605,#160683,#160796,#160879,#160955,#161031, - #161106,#161181,#161256,#161334,#161452,#161535,#161611,#161687, - #161762,#161837,#161912,#161990,#162108,#162191,#162267,#162343, - #162418,#162493,#162568,#162646,#162764,#162847,#162923,#162999, - #163074,#163149,#163224,#163302,#163415,#163498,#163574,#163650, - #163725,#163800,#163875,#163953,#164438,#164526,#164574,#164631, - #164680,#164741,#164789,#164846,#164895,#164956,#165004,#165073, - #165121,#165178,#165227,#165288,#165336,#165393,#165442,#165503, - #165551,#165608,#165657,#165718,#165766,#165835,#165883,#165940, - #165967)); -#158710 = ADVANCED_FACE('',(#158711),#158725,.T.); -#158711 = FACE_BOUND('',#158712,.T.); -#158712 = EDGE_LOOP('',(#158713,#158747,#158775,#158802)); -#158713 = ORIENTED_EDGE('',*,*,#158714,.F.); -#158714 = EDGE_CURVE('',#158715,#158717,#158719,.T.); -#158715 = VERTEX_POINT('',#158716); -#158716 = CARTESIAN_POINT('',(0.845,0.706843139085,-2.459055548476)); -#158717 = VERTEX_POINT('',#158718); -#158718 = CARTESIAN_POINT('',(0.425,0.706843139085,-2.459055548476)); -#158719 = SURFACE_CURVE('',#158720,(#158724,#158736),.PCURVE_S1.); -#158720 = LINE('',#158721,#158722); -#158721 = CARTESIAN_POINT('',(0.635,0.706843139085,-2.459055548476)); -#158722 = VECTOR('',#158723,1.); -#158723 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158724 = PCURVE('',#158725,#158730); -#158725 = PLANE('',#158726); -#158726 = AXIS2_PLACEMENT_3D('',#158727,#158728,#158729); -#158727 = CARTESIAN_POINT('',(0.635,0.706843139085,-2.459055548476)); -#158728 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); -#158729 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#158730 = DEFINITIONAL_REPRESENTATION('',(#158731),#158735); -#158731 = LINE('',#158732,#158733); -#158732 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#158733 = VECTOR('',#158734,1.); -#158734 = DIRECTION('',(0.E+000,-1.)); -#158735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158736 = PCURVE('',#158737,#158742); -#158737 = CYLINDRICAL_SURFACE('',#158738,0.32); -#158738 = AXIS2_PLACEMENT_3D('',#158739,#158740,#158741); -#158739 = CARTESIAN_POINT('',(0.635,0.665,-2.141803043818)); -#158740 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158741 = DIRECTION('',(0.E+000,0.E+000,1.)); -#158742 = DEFINITIONAL_REPRESENTATION('',(#158743),#158746); -#158743 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158744,#158745), +#161095 = ITEM_DEFINED_TRANSFORMATION('','',#11,#159085); +#161096 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #161097); +#161097 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('372','','',#159079,#161088,$); +#161098 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#161090)); +#161099 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#161100),#168390); +#161100 = MANIFOLD_SOLID_BREP('',#161101); +#161101 = CLOSED_SHELL('',(#161102,#161220,#161303,#161379,#161455, + #161530,#161605,#161680,#161763,#161881,#161964,#162040,#162116, + #162191,#162266,#162341,#162419,#162537,#162620,#162696,#162772, + #162847,#162922,#162997,#163075,#163188,#163271,#163347,#163423, + #163498,#163573,#163648,#163726,#163844,#163927,#164003,#164079, + #164154,#164229,#164304,#164382,#164500,#164583,#164659,#164735, + #164810,#164885,#164960,#165038,#165156,#165239,#165315,#165391, + #165466,#165541,#165616,#165694,#165807,#165890,#165966,#166042, + #166117,#166192,#166267,#166345,#166830,#166918,#166966,#167023, + #167072,#167133,#167181,#167238,#167287,#167348,#167396,#167465, + #167513,#167570,#167619,#167680,#167728,#167785,#167834,#167895, + #167943,#168000,#168049,#168110,#168158,#168227,#168275,#168332, + #168359)); +#161102 = ADVANCED_FACE('',(#161103),#161117,.T.); +#161103 = FACE_BOUND('',#161104,.T.); +#161104 = EDGE_LOOP('',(#161105,#161139,#161167,#161194)); +#161105 = ORIENTED_EDGE('',*,*,#161106,.F.); +#161106 = EDGE_CURVE('',#161107,#161109,#161111,.T.); +#161107 = VERTEX_POINT('',#161108); +#161108 = CARTESIAN_POINT('',(0.845,0.706843139085,-2.459055548476)); +#161109 = VERTEX_POINT('',#161110); +#161110 = CARTESIAN_POINT('',(0.425,0.706843139085,-2.459055548476)); +#161111 = SURFACE_CURVE('',#161112,(#161116,#161128),.PCURVE_S1.); +#161112 = LINE('',#161113,#161114); +#161113 = CARTESIAN_POINT('',(0.635,0.706843139085,-2.459055548476)); +#161114 = VECTOR('',#161115,1.); +#161115 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161116 = PCURVE('',#161117,#161122); +#161117 = PLANE('',#161118); +#161118 = AXIS2_PLACEMENT_3D('',#161119,#161120,#161121); +#161119 = CARTESIAN_POINT('',(0.635,0.706843139085,-2.459055548476)); +#161120 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); +#161121 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#161122 = DEFINITIONAL_REPRESENTATION('',(#161123),#161127); +#161123 = LINE('',#161124,#161125); +#161124 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#161125 = VECTOR('',#161126,1.); +#161126 = DIRECTION('',(0.E+000,-1.)); +#161127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161128 = PCURVE('',#161129,#161134); +#161129 = CYLINDRICAL_SURFACE('',#161130,0.32); +#161130 = AXIS2_PLACEMENT_3D('',#161131,#161132,#161133); +#161131 = CARTESIAN_POINT('',(0.635,0.665,-2.141803043818)); +#161132 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161133 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161134 = DEFINITIONAL_REPRESENTATION('',(#161135),#161138); +#161135 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161136,#161137), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#158744 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#158745 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#158746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158747 = ORIENTED_EDGE('',*,*,#158748,.F.); -#158748 = EDGE_CURVE('',#158749,#158715,#158751,.T.); -#158749 = VERTEX_POINT('',#158750); -#158750 = CARTESIAN_POINT('',(0.845,0.327745739138,-2.509055548476)); -#158751 = SURFACE_CURVE('',#158752,(#158756,#158763),.PCURVE_S1.); -#158752 = LINE('',#158753,#158754); -#158753 = CARTESIAN_POINT('',(0.845,0.327745739138,-2.509055548476)); -#158754 = VECTOR('',#158755,1.); -#158755 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#158756 = PCURVE('',#158725,#158757); -#158757 = DEFINITIONAL_REPRESENTATION('',(#158758),#158762); -#158758 = LINE('',#158759,#158760); -#158759 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#158760 = VECTOR('',#158761,1.); -#158761 = DIRECTION('',(1.,0.E+000)); -#158762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161136 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#161137 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#161138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161139 = ORIENTED_EDGE('',*,*,#161140,.F.); +#161140 = EDGE_CURVE('',#161141,#161107,#161143,.T.); +#161141 = VERTEX_POINT('',#161142); +#161142 = CARTESIAN_POINT('',(0.845,0.327745739138,-2.509055548476)); +#161143 = SURFACE_CURVE('',#161144,(#161148,#161155),.PCURVE_S1.); +#161144 = LINE('',#161145,#161146); +#161145 = CARTESIAN_POINT('',(0.845,0.327745739138,-2.509055548476)); +#161146 = VECTOR('',#161147,1.); +#161147 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#161148 = PCURVE('',#161117,#161149); +#161149 = DEFINITIONAL_REPRESENTATION('',(#161150),#161154); +#161150 = LINE('',#161151,#161152); +#161151 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#161152 = VECTOR('',#161153,1.); +#161153 = DIRECTION('',(1.,0.E+000)); +#161154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161155 = PCURVE('',#161156,#161161); +#161156 = PLANE('',#161157); +#161157 = AXIS2_PLACEMENT_3D('',#161158,#161159,#161160); +#161158 = CARTESIAN_POINT('',(0.845,0.875,0.E+000)); +#161159 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161160 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161161 = DEFINITIONAL_REPRESENTATION('',(#161162),#161166); +#161162 = LINE('',#161163,#161164); +#161163 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#161164 = VECTOR('',#161165,1.); +#161165 = DIRECTION('',(-0.130759809642,0.991414077055)); +#161166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161167 = ORIENTED_EDGE('',*,*,#161168,.T.); +#161168 = EDGE_CURVE('',#161141,#161169,#161171,.T.); +#161169 = VERTEX_POINT('',#161170); +#161170 = CARTESIAN_POINT('',(0.425,0.327745739138,-2.509055548476)); +#161171 = SURFACE_CURVE('',#161172,(#161176,#161183),.PCURVE_S1.); +#161172 = LINE('',#161173,#161174); +#161173 = CARTESIAN_POINT('',(0.635,0.327745739138,-2.509055548476)); +#161174 = VECTOR('',#161175,1.); +#161175 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161176 = PCURVE('',#161117,#161177); +#161177 = DEFINITIONAL_REPRESENTATION('',(#161178),#161182); +#161178 = LINE('',#161179,#161180); +#161179 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#161180 = VECTOR('',#161181,1.); +#161181 = DIRECTION('',(0.E+000,-1.)); +#161182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161183 = PCURVE('',#161184,#161189); +#161184 = CYLINDRICAL_SURFACE('',#161185,9.999999999999E-002); +#161185 = AXIS2_PLACEMENT_3D('',#161186,#161187,#161188); +#161186 = CARTESIAN_POINT('',(0.635,0.340821720102,-2.608196956182)); +#161187 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161188 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161189 = DEFINITIONAL_REPRESENTATION('',(#161190),#161193); +#161190 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161191,#161192), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#161191 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161192 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158763 = PCURVE('',#158764,#158769); -#158764 = PLANE('',#158765); -#158765 = AXIS2_PLACEMENT_3D('',#158766,#158767,#158768); -#158766 = CARTESIAN_POINT('',(0.845,0.875,0.E+000)); -#158767 = DIRECTION('',(1.,0.E+000,0.E+000)); -#158768 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#158769 = DEFINITIONAL_REPRESENTATION('',(#158770),#158774); -#158770 = LINE('',#158771,#158772); -#158771 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#158772 = VECTOR('',#158773,1.); -#158773 = DIRECTION('',(-0.130759809642,0.991414077055)); -#158774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158775 = ORIENTED_EDGE('',*,*,#158776,.T.); -#158776 = EDGE_CURVE('',#158749,#158777,#158779,.T.); -#158777 = VERTEX_POINT('',#158778); -#158778 = CARTESIAN_POINT('',(0.425,0.327745739138,-2.509055548476)); -#158779 = SURFACE_CURVE('',#158780,(#158784,#158791),.PCURVE_S1.); -#158780 = LINE('',#158781,#158782); -#158781 = CARTESIAN_POINT('',(0.635,0.327745739138,-2.509055548476)); -#158782 = VECTOR('',#158783,1.); -#158783 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158784 = PCURVE('',#158725,#158785); -#158785 = DEFINITIONAL_REPRESENTATION('',(#158786),#158790); -#158786 = LINE('',#158787,#158788); -#158787 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#158788 = VECTOR('',#158789,1.); -#158789 = DIRECTION('',(0.E+000,-1.)); -#158790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158791 = PCURVE('',#158792,#158797); -#158792 = CYLINDRICAL_SURFACE('',#158793,9.999999999999E-002); -#158793 = AXIS2_PLACEMENT_3D('',#158794,#158795,#158796); -#158794 = CARTESIAN_POINT('',(0.635,0.340821720102,-2.608196956182)); -#158795 = DIRECTION('',(1.,0.E+000,0.E+000)); -#158796 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#158797 = DEFINITIONAL_REPRESENTATION('',(#158798),#158801); -#158798 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158799,#158800), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#158799 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#158800 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#158801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158802 = ORIENTED_EDGE('',*,*,#158803,.F.); -#158803 = EDGE_CURVE('',#158717,#158777,#158804,.T.); -#158804 = SURFACE_CURVE('',#158805,(#158809,#158816),.PCURVE_S1.); -#158805 = LINE('',#158806,#158807); -#158806 = CARTESIAN_POINT('',(0.425,0.706843139085,-2.459055548476)); -#158807 = VECTOR('',#158808,1.); -#158808 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#158809 = PCURVE('',#158725,#158810); -#158810 = DEFINITIONAL_REPRESENTATION('',(#158811),#158815); -#158811 = LINE('',#158812,#158813); -#158812 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#158813 = VECTOR('',#158814,1.); -#158814 = DIRECTION('',(-1.,0.E+000)); -#158815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158816 = PCURVE('',#158817,#158822); -#158817 = PLANE('',#158818); -#158818 = AXIS2_PLACEMENT_3D('',#158819,#158820,#158821); -#158819 = CARTESIAN_POINT('',(0.425,0.875,0.E+000)); -#158820 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158821 = DIRECTION('',(0.E+000,0.E+000,1.)); -#158822 = DEFINITIONAL_REPRESENTATION('',(#158823),#158827); -#158823 = LINE('',#158824,#158825); -#158824 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#158825 = VECTOR('',#158826,1.); -#158826 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#158827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158828 = ADVANCED_FACE('',(#158829),#158792,.F.); -#158829 = FACE_BOUND('',#158830,.F.); -#158830 = EDGE_LOOP('',(#158831,#158858,#158885,#158910)); -#158831 = ORIENTED_EDGE('',*,*,#158832,.T.); -#158832 = EDGE_CURVE('',#158777,#158833,#158835,.T.); -#158833 = VERTEX_POINT('',#158834); -#158834 = CARTESIAN_POINT('',(0.425,0.240958766627,-2.602963360557)); -#158835 = SURFACE_CURVE('',#158836,(#158841,#158847),.PCURVE_S1.); -#158836 = CIRCLE('',#158837,9.999999999999E-002); -#158837 = AXIS2_PLACEMENT_3D('',#158838,#158839,#158840); -#158838 = CARTESIAN_POINT('',(0.425,0.340821720102,-2.608196956182)); -#158839 = DIRECTION('',(1.,0.E+000,0.E+000)); -#158840 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#158841 = PCURVE('',#158792,#158842); -#158842 = DEFINITIONAL_REPRESENTATION('',(#158843),#158846); -#158843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158844,#158845), +#161194 = ORIENTED_EDGE('',*,*,#161195,.F.); +#161195 = EDGE_CURVE('',#161109,#161169,#161196,.T.); +#161196 = SURFACE_CURVE('',#161197,(#161201,#161208),.PCURVE_S1.); +#161197 = LINE('',#161198,#161199); +#161198 = CARTESIAN_POINT('',(0.425,0.706843139085,-2.459055548476)); +#161199 = VECTOR('',#161200,1.); +#161200 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#161201 = PCURVE('',#161117,#161202); +#161202 = DEFINITIONAL_REPRESENTATION('',(#161203),#161207); +#161203 = LINE('',#161204,#161205); +#161204 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#161205 = VECTOR('',#161206,1.); +#161206 = DIRECTION('',(-1.,0.E+000)); +#161207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161208 = PCURVE('',#161209,#161214); +#161209 = PLANE('',#161210); +#161210 = AXIS2_PLACEMENT_3D('',#161211,#161212,#161213); +#161211 = CARTESIAN_POINT('',(0.425,0.875,0.E+000)); +#161212 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161213 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161214 = DEFINITIONAL_REPRESENTATION('',(#161215),#161219); +#161215 = LINE('',#161216,#161217); +#161216 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#161217 = VECTOR('',#161218,1.); +#161218 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#161219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161220 = ADVANCED_FACE('',(#161221),#161184,.F.); +#161221 = FACE_BOUND('',#161222,.F.); +#161222 = EDGE_LOOP('',(#161223,#161250,#161277,#161302)); +#161223 = ORIENTED_EDGE('',*,*,#161224,.T.); +#161224 = EDGE_CURVE('',#161169,#161225,#161227,.T.); +#161225 = VERTEX_POINT('',#161226); +#161226 = CARTESIAN_POINT('',(0.425,0.240958766627,-2.602963360557)); +#161227 = SURFACE_CURVE('',#161228,(#161233,#161239),.PCURVE_S1.); +#161228 = CIRCLE('',#161229,9.999999999999E-002); +#161229 = AXIS2_PLACEMENT_3D('',#161230,#161231,#161232); +#161230 = CARTESIAN_POINT('',(0.425,0.340821720102,-2.608196956182)); +#161231 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161232 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161233 = PCURVE('',#161184,#161234); +#161234 = DEFINITIONAL_REPRESENTATION('',(#161235),#161238); +#161235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161236,#161237), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#158844 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#158845 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#158846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161236 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161237 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158847 = PCURVE('',#158817,#158848); -#158848 = DEFINITIONAL_REPRESENTATION('',(#158849),#158857); -#158849 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158850,#158851,#158852, - #158853,#158854,#158855,#158856),.UNSPECIFIED.,.T.,.F.) +#161239 = PCURVE('',#161209,#161240); +#161240 = DEFINITIONAL_REPRESENTATION('',(#161241),#161249); +#161241 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161242,#161243,#161244, + #161245,#161246,#161247,#161248),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#158850 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#158851 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#158852 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#158853 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#158854 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#158855 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#158856 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#158857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158858 = ORIENTED_EDGE('',*,*,#158859,.T.); -#158859 = EDGE_CURVE('',#158833,#158860,#158862,.T.); -#158860 = VERTEX_POINT('',#158861); -#158861 = CARTESIAN_POINT('',(0.845,0.240958766627,-2.602963360557)); -#158862 = SURFACE_CURVE('',#158863,(#158867,#158873),.PCURVE_S1.); -#158863 = LINE('',#158864,#158865); -#158864 = CARTESIAN_POINT('',(0.635,0.240958766627,-2.602963360557)); -#158865 = VECTOR('',#158866,1.); -#158866 = DIRECTION('',(1.,0.E+000,0.E+000)); -#158867 = PCURVE('',#158792,#158868); -#158868 = DEFINITIONAL_REPRESENTATION('',(#158869),#158872); -#158869 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158870,#158871), +#161242 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#161243 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#161244 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#161245 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#161246 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#161247 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#161248 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#161249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161250 = ORIENTED_EDGE('',*,*,#161251,.T.); +#161251 = EDGE_CURVE('',#161225,#161252,#161254,.T.); +#161252 = VERTEX_POINT('',#161253); +#161253 = CARTESIAN_POINT('',(0.845,0.240958766627,-2.602963360557)); +#161254 = SURFACE_CURVE('',#161255,(#161259,#161265),.PCURVE_S1.); +#161255 = LINE('',#161256,#161257); +#161256 = CARTESIAN_POINT('',(0.635,0.240958766627,-2.602963360557)); +#161257 = VECTOR('',#161258,1.); +#161258 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161259 = PCURVE('',#161184,#161260); +#161260 = DEFINITIONAL_REPRESENTATION('',(#161261),#161264); +#161261 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161262,#161263), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#158870 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#158871 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#158872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158873 = PCURVE('',#158874,#158879); -#158874 = PLANE('',#158875); -#158875 = AXIS2_PLACEMENT_3D('',#158876,#158877,#158878); -#158876 = CARTESIAN_POINT('',(0.635,0.240958766627,-2.602963360557)); -#158877 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); -#158878 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#158879 = DEFINITIONAL_REPRESENTATION('',(#158880),#158884); -#158880 = LINE('',#158881,#158882); -#158881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#158882 = VECTOR('',#158883,1.); -#158883 = DIRECTION('',(0.E+000,1.)); -#158884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158885 = ORIENTED_EDGE('',*,*,#158886,.T.); -#158886 = EDGE_CURVE('',#158860,#158749,#158887,.T.); -#158887 = SURFACE_CURVE('',#158888,(#158893,#158899),.PCURVE_S1.); -#158888 = CIRCLE('',#158889,9.999999999999E-002); -#158889 = AXIS2_PLACEMENT_3D('',#158890,#158891,#158892); -#158890 = CARTESIAN_POINT('',(0.845,0.340821720102,-2.608196956182)); -#158891 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158892 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); -#158893 = PCURVE('',#158792,#158894); -#158894 = DEFINITIONAL_REPRESENTATION('',(#158895),#158898); -#158895 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#158896,#158897), +#161262 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161263 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161265 = PCURVE('',#161266,#161271); +#161266 = PLANE('',#161267); +#161267 = AXIS2_PLACEMENT_3D('',#161268,#161269,#161270); +#161268 = CARTESIAN_POINT('',(0.635,0.240958766627,-2.602963360557)); +#161269 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); +#161270 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#161271 = DEFINITIONAL_REPRESENTATION('',(#161272),#161276); +#161272 = LINE('',#161273,#161274); +#161273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#161274 = VECTOR('',#161275,1.); +#161275 = DIRECTION('',(0.E+000,1.)); +#161276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161277 = ORIENTED_EDGE('',*,*,#161278,.T.); +#161278 = EDGE_CURVE('',#161252,#161141,#161279,.T.); +#161279 = SURFACE_CURVE('',#161280,(#161285,#161291),.PCURVE_S1.); +#161280 = CIRCLE('',#161281,9.999999999999E-002); +#161281 = AXIS2_PLACEMENT_3D('',#161282,#161283,#161284); +#161282 = CARTESIAN_POINT('',(0.845,0.340821720102,-2.608196956182)); +#161283 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161284 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); +#161285 = PCURVE('',#161184,#161286); +#161286 = DEFINITIONAL_REPRESENTATION('',(#161287),#161290); +#161287 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161288,#161289), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#158896 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#158897 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#158898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161288 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161289 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#158899 = PCURVE('',#158764,#158900); -#158900 = DEFINITIONAL_REPRESENTATION('',(#158901),#158909); -#158901 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#158902,#158903,#158904, - #158905,#158906,#158907,#158908),.UNSPECIFIED.,.T.,.F.) +#161291 = PCURVE('',#161156,#161292); +#161292 = DEFINITIONAL_REPRESENTATION('',(#161293),#161301); +#161293 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161294,#161295,#161296, + #161297,#161298,#161299,#161300),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#158902 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#158903 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#158904 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#158905 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#158906 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#158907 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#158908 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#158909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158910 = ORIENTED_EDGE('',*,*,#158776,.T.); -#158911 = ADVANCED_FACE('',(#158912),#158874,.T.); -#158912 = FACE_BOUND('',#158913,.T.); -#158913 = EDGE_LOOP('',(#158914,#158915,#158938,#158966)); -#158914 = ORIENTED_EDGE('',*,*,#158859,.T.); -#158915 = ORIENTED_EDGE('',*,*,#158916,.F.); -#158916 = EDGE_CURVE('',#158917,#158860,#158919,.T.); -#158917 = VERTEX_POINT('',#158918); -#158918 = CARTESIAN_POINT('',(0.845,0.219849248823,-3.005756955187)); -#158919 = SURFACE_CURVE('',#158920,(#158924,#158931),.PCURVE_S1.); -#158920 = LINE('',#158921,#158922); -#158921 = CARTESIAN_POINT('',(0.845,0.219849248823,-3.005756955187)); -#158922 = VECTOR('',#158923,1.); -#158923 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#158924 = PCURVE('',#158874,#158925); -#158925 = DEFINITIONAL_REPRESENTATION('',(#158926),#158930); -#158926 = LINE('',#158927,#158928); -#158927 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#158928 = VECTOR('',#158929,1.); -#158929 = DIRECTION('',(1.,0.E+000)); -#158930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158931 = PCURVE('',#158764,#158932); -#158932 = DEFINITIONAL_REPRESENTATION('',(#158933),#158937); -#158933 = LINE('',#158934,#158935); -#158934 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#158935 = VECTOR('',#158936,1.); -#158936 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#158937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158938 = ORIENTED_EDGE('',*,*,#158939,.T.); -#158939 = EDGE_CURVE('',#158917,#158940,#158942,.T.); -#158940 = VERTEX_POINT('',#158941); -#158941 = CARTESIAN_POINT('',(0.425,0.219849248823,-3.005756955187)); -#158942 = SURFACE_CURVE('',#158943,(#158947,#158954),.PCURVE_S1.); -#158943 = LINE('',#158944,#158945); -#158944 = CARTESIAN_POINT('',(0.635,0.219849248823,-3.005756955187)); -#158945 = VECTOR('',#158946,1.); -#158946 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#158947 = PCURVE('',#158874,#158948); -#158948 = DEFINITIONAL_REPRESENTATION('',(#158949),#158953); -#158949 = LINE('',#158950,#158951); -#158950 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#158951 = VECTOR('',#158952,1.); -#158952 = DIRECTION('',(0.E+000,-1.)); -#158953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158954 = PCURVE('',#158955,#158960); -#158955 = PLANE('',#158956); -#158956 = AXIS2_PLACEMENT_3D('',#158957,#158958,#158959); -#158957 = CARTESIAN_POINT('',(0.635,0.11,-3.)); -#158958 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); -#158959 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#158960 = DEFINITIONAL_REPRESENTATION('',(#158961),#158965); -#158961 = LINE('',#158962,#158963); -#158962 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#158963 = VECTOR('',#158964,1.); -#158964 = DIRECTION('',(0.E+000,-1.)); -#158965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158966 = ORIENTED_EDGE('',*,*,#158967,.F.); -#158967 = EDGE_CURVE('',#158833,#158940,#158968,.T.); -#158968 = SURFACE_CURVE('',#158969,(#158973,#158980),.PCURVE_S1.); -#158969 = LINE('',#158970,#158971); -#158970 = CARTESIAN_POINT('',(0.425,0.240958766627,-2.602963360557)); -#158971 = VECTOR('',#158972,1.); -#158972 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#158973 = PCURVE('',#158874,#158974); -#158974 = DEFINITIONAL_REPRESENTATION('',(#158975),#158979); -#158975 = LINE('',#158976,#158977); -#158976 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#158977 = VECTOR('',#158978,1.); -#158978 = DIRECTION('',(-1.,0.E+000)); -#158979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158980 = PCURVE('',#158817,#158981); -#158981 = DEFINITIONAL_REPRESENTATION('',(#158982),#158986); -#158982 = LINE('',#158983,#158984); -#158983 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#158984 = VECTOR('',#158985,1.); -#158985 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#158986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#158987 = ADVANCED_FACE('',(#158988),#158955,.F.); -#158988 = FACE_BOUND('',#158989,.T.); -#158989 = EDGE_LOOP('',(#158990,#159013,#159014,#159037)); -#158990 = ORIENTED_EDGE('',*,*,#158991,.F.); -#158991 = EDGE_CURVE('',#158940,#158992,#158994,.T.); -#158992 = VERTEX_POINT('',#158993); -#158993 = CARTESIAN_POINT('',(0.425,1.507511769881E-004,-2.994243044813) - ); -#158994 = SURFACE_CURVE('',#158995,(#158999,#159006),.PCURVE_S1.); -#158995 = LINE('',#158996,#158997); -#158996 = CARTESIAN_POINT('',(0.425,0.219849248823,-3.005756955187)); -#158997 = VECTOR('',#158998,1.); -#158998 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#158999 = PCURVE('',#158955,#159000); -#159000 = DEFINITIONAL_REPRESENTATION('',(#159001),#159005); -#159001 = LINE('',#159002,#159003); -#159002 = CARTESIAN_POINT('',(-0.11,-0.21)); -#159003 = VECTOR('',#159004,1.); -#159004 = DIRECTION('',(1.,0.E+000)); -#159005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159006 = PCURVE('',#158817,#159007); -#159007 = DEFINITIONAL_REPRESENTATION('',(#159008),#159012); -#159008 = LINE('',#159009,#159010); -#159009 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#159010 = VECTOR('',#159011,1.); -#159011 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#159012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159013 = ORIENTED_EDGE('',*,*,#158939,.F.); -#159014 = ORIENTED_EDGE('',*,*,#159015,.F.); -#159015 = EDGE_CURVE('',#159016,#158917,#159018,.T.); -#159016 = VERTEX_POINT('',#159017); -#159017 = CARTESIAN_POINT('',(0.845,1.507511769881E-004,-2.994243044813) - ); -#159018 = SURFACE_CURVE('',#159019,(#159023,#159030),.PCURVE_S1.); -#159019 = LINE('',#159020,#159021); -#159020 = CARTESIAN_POINT('',(0.845,1.507511769892E-004,-2.994243044813) - ); -#159021 = VECTOR('',#159022,1.); -#159022 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); -#159023 = PCURVE('',#158955,#159024); -#159024 = DEFINITIONAL_REPRESENTATION('',(#159025),#159029); -#159025 = LINE('',#159026,#159027); -#159026 = CARTESIAN_POINT('',(0.11,0.21)); -#159027 = VECTOR('',#159028,1.); -#159028 = DIRECTION('',(-1.,0.E+000)); -#159029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159030 = PCURVE('',#158764,#159031); -#159031 = DEFINITIONAL_REPRESENTATION('',(#159032),#159036); -#159032 = LINE('',#159033,#159034); -#159033 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#159034 = VECTOR('',#159035,1.); -#159035 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#159036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159037 = ORIENTED_EDGE('',*,*,#159038,.F.); -#159038 = EDGE_CURVE('',#158992,#159016,#159039,.T.); -#159039 = SURFACE_CURVE('',#159040,(#159044,#159051),.PCURVE_S1.); -#159040 = LINE('',#159041,#159042); -#159041 = CARTESIAN_POINT('',(0.635,1.507511769861E-004,-2.994243044813) - ); -#159042 = VECTOR('',#159043,1.); -#159043 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159044 = PCURVE('',#158955,#159045); -#159045 = DEFINITIONAL_REPRESENTATION('',(#159046),#159050); -#159046 = LINE('',#159047,#159048); -#159047 = CARTESIAN_POINT('',(0.11,0.E+000)); -#159048 = VECTOR('',#159049,1.); -#159049 = DIRECTION('',(0.E+000,1.)); -#159050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159051 = PCURVE('',#159052,#159057); -#159052 = PLANE('',#159053); -#159053 = AXIS2_PLACEMENT_3D('',#159054,#159055,#159056); -#159054 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,-2.591449450184) - ); -#159055 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); -#159056 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#159057 = DEFINITIONAL_REPRESENTATION('',(#159058),#159062); -#159058 = LINE('',#159059,#159060); -#159059 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#159060 = VECTOR('',#159061,1.); -#159061 = DIRECTION('',(0.E+000,1.)); -#159062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159063 = ADVANCED_FACE('',(#159064),#159052,.T.); -#159064 = FACE_BOUND('',#159065,.T.); -#159065 = EDGE_LOOP('',(#159066,#159095,#159116,#159117)); -#159066 = ORIENTED_EDGE('',*,*,#159067,.F.); -#159067 = EDGE_CURVE('',#159068,#159070,#159072,.T.); -#159068 = VERTEX_POINT('',#159069); -#159069 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,-2.591449450184) - ); -#159070 = VERTEX_POINT('',#159071); -#159071 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,-2.591449450184) - ); -#159072 = SURFACE_CURVE('',#159073,(#159077,#159084),.PCURVE_S1.); -#159073 = LINE('',#159074,#159075); -#159074 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,-2.591449450184) - ); -#159075 = VECTOR('',#159076,1.); -#159076 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159077 = PCURVE('',#159052,#159078); -#159078 = DEFINITIONAL_REPRESENTATION('',(#159079),#159083); -#159079 = LINE('',#159080,#159081); -#159080 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); -#159081 = VECTOR('',#159082,1.); -#159082 = DIRECTION('',(0.E+000,1.)); -#159083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159084 = PCURVE('',#159085,#159090); -#159085 = CYLINDRICAL_SURFACE('',#159086,0.32); -#159086 = AXIS2_PLACEMENT_3D('',#159087,#159088,#159089); -#159087 = CARTESIAN_POINT('',(0.635,0.340821720102,-2.608196956182)); -#159088 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159089 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159090 = DEFINITIONAL_REPRESENTATION('',(#159091),#159094); -#159091 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159092,#159093), +#161294 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#161295 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#161296 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#161297 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#161298 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#161299 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#161300 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#161301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161302 = ORIENTED_EDGE('',*,*,#161168,.T.); +#161303 = ADVANCED_FACE('',(#161304),#161266,.T.); +#161304 = FACE_BOUND('',#161305,.T.); +#161305 = EDGE_LOOP('',(#161306,#161307,#161330,#161358)); +#161306 = ORIENTED_EDGE('',*,*,#161251,.T.); +#161307 = ORIENTED_EDGE('',*,*,#161308,.F.); +#161308 = EDGE_CURVE('',#161309,#161252,#161311,.T.); +#161309 = VERTEX_POINT('',#161310); +#161310 = CARTESIAN_POINT('',(0.845,0.219849248823,-3.005756955187)); +#161311 = SURFACE_CURVE('',#161312,(#161316,#161323),.PCURVE_S1.); +#161312 = LINE('',#161313,#161314); +#161313 = CARTESIAN_POINT('',(0.845,0.219849248823,-3.005756955187)); +#161314 = VECTOR('',#161315,1.); +#161315 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#161316 = PCURVE('',#161266,#161317); +#161317 = DEFINITIONAL_REPRESENTATION('',(#161318),#161322); +#161318 = LINE('',#161319,#161320); +#161319 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#161320 = VECTOR('',#161321,1.); +#161321 = DIRECTION('',(1.,0.E+000)); +#161322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161323 = PCURVE('',#161156,#161324); +#161324 = DEFINITIONAL_REPRESENTATION('',(#161325),#161329); +#161325 = LINE('',#161326,#161327); +#161326 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#161327 = VECTOR('',#161328,1.); +#161328 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#161329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161330 = ORIENTED_EDGE('',*,*,#161331,.T.); +#161331 = EDGE_CURVE('',#161309,#161332,#161334,.T.); +#161332 = VERTEX_POINT('',#161333); +#161333 = CARTESIAN_POINT('',(0.425,0.219849248823,-3.005756955187)); +#161334 = SURFACE_CURVE('',#161335,(#161339,#161346),.PCURVE_S1.); +#161335 = LINE('',#161336,#161337); +#161336 = CARTESIAN_POINT('',(0.635,0.219849248823,-3.005756955187)); +#161337 = VECTOR('',#161338,1.); +#161338 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161339 = PCURVE('',#161266,#161340); +#161340 = DEFINITIONAL_REPRESENTATION('',(#161341),#161345); +#161341 = LINE('',#161342,#161343); +#161342 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#161343 = VECTOR('',#161344,1.); +#161344 = DIRECTION('',(0.E+000,-1.)); +#161345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161346 = PCURVE('',#161347,#161352); +#161347 = PLANE('',#161348); +#161348 = AXIS2_PLACEMENT_3D('',#161349,#161350,#161351); +#161349 = CARTESIAN_POINT('',(0.635,0.11,-3.)); +#161350 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); +#161351 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#161352 = DEFINITIONAL_REPRESENTATION('',(#161353),#161357); +#161353 = LINE('',#161354,#161355); +#161354 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#161355 = VECTOR('',#161356,1.); +#161356 = DIRECTION('',(0.E+000,-1.)); +#161357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161358 = ORIENTED_EDGE('',*,*,#161359,.F.); +#161359 = EDGE_CURVE('',#161225,#161332,#161360,.T.); +#161360 = SURFACE_CURVE('',#161361,(#161365,#161372),.PCURVE_S1.); +#161361 = LINE('',#161362,#161363); +#161362 = CARTESIAN_POINT('',(0.425,0.240958766627,-2.602963360557)); +#161363 = VECTOR('',#161364,1.); +#161364 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#161365 = PCURVE('',#161266,#161366); +#161366 = DEFINITIONAL_REPRESENTATION('',(#161367),#161371); +#161367 = LINE('',#161368,#161369); +#161368 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#161369 = VECTOR('',#161370,1.); +#161370 = DIRECTION('',(-1.,0.E+000)); +#161371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161372 = PCURVE('',#161209,#161373); +#161373 = DEFINITIONAL_REPRESENTATION('',(#161374),#161378); +#161374 = LINE('',#161375,#161376); +#161375 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#161376 = VECTOR('',#161377,1.); +#161377 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#161378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161379 = ADVANCED_FACE('',(#161380),#161347,.F.); +#161380 = FACE_BOUND('',#161381,.T.); +#161381 = EDGE_LOOP('',(#161382,#161405,#161406,#161429)); +#161382 = ORIENTED_EDGE('',*,*,#161383,.F.); +#161383 = EDGE_CURVE('',#161332,#161384,#161386,.T.); +#161384 = VERTEX_POINT('',#161385); +#161385 = CARTESIAN_POINT('',(0.425,1.507511769881E-004,-2.994243044813) + ); +#161386 = SURFACE_CURVE('',#161387,(#161391,#161398),.PCURVE_S1.); +#161387 = LINE('',#161388,#161389); +#161388 = CARTESIAN_POINT('',(0.425,0.219849248823,-3.005756955187)); +#161389 = VECTOR('',#161390,1.); +#161390 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#161391 = PCURVE('',#161347,#161392); +#161392 = DEFINITIONAL_REPRESENTATION('',(#161393),#161397); +#161393 = LINE('',#161394,#161395); +#161394 = CARTESIAN_POINT('',(-0.11,-0.21)); +#161395 = VECTOR('',#161396,1.); +#161396 = DIRECTION('',(1.,0.E+000)); +#161397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161398 = PCURVE('',#161209,#161399); +#161399 = DEFINITIONAL_REPRESENTATION('',(#161400),#161404); +#161400 = LINE('',#161401,#161402); +#161401 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#161402 = VECTOR('',#161403,1.); +#161403 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#161404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161405 = ORIENTED_EDGE('',*,*,#161331,.F.); +#161406 = ORIENTED_EDGE('',*,*,#161407,.F.); +#161407 = EDGE_CURVE('',#161408,#161309,#161410,.T.); +#161408 = VERTEX_POINT('',#161409); +#161409 = CARTESIAN_POINT('',(0.845,1.507511769881E-004,-2.994243044813) + ); +#161410 = SURFACE_CURVE('',#161411,(#161415,#161422),.PCURVE_S1.); +#161411 = LINE('',#161412,#161413); +#161412 = CARTESIAN_POINT('',(0.845,1.507511769892E-004,-2.994243044813) + ); +#161413 = VECTOR('',#161414,1.); +#161414 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); +#161415 = PCURVE('',#161347,#161416); +#161416 = DEFINITIONAL_REPRESENTATION('',(#161417),#161421); +#161417 = LINE('',#161418,#161419); +#161418 = CARTESIAN_POINT('',(0.11,0.21)); +#161419 = VECTOR('',#161420,1.); +#161420 = DIRECTION('',(-1.,0.E+000)); +#161421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161422 = PCURVE('',#161156,#161423); +#161423 = DEFINITIONAL_REPRESENTATION('',(#161424),#161428); +#161424 = LINE('',#161425,#161426); +#161425 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#161426 = VECTOR('',#161427,1.); +#161427 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#161428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161429 = ORIENTED_EDGE('',*,*,#161430,.F.); +#161430 = EDGE_CURVE('',#161384,#161408,#161431,.T.); +#161431 = SURFACE_CURVE('',#161432,(#161436,#161443),.PCURVE_S1.); +#161432 = LINE('',#161433,#161434); +#161433 = CARTESIAN_POINT('',(0.635,1.507511769861E-004,-2.994243044813) + ); +#161434 = VECTOR('',#161435,1.); +#161435 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161436 = PCURVE('',#161347,#161437); +#161437 = DEFINITIONAL_REPRESENTATION('',(#161438),#161442); +#161438 = LINE('',#161439,#161440); +#161439 = CARTESIAN_POINT('',(0.11,0.E+000)); +#161440 = VECTOR('',#161441,1.); +#161441 = DIRECTION('',(0.E+000,1.)); +#161442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161443 = PCURVE('',#161444,#161449); +#161444 = PLANE('',#161445); +#161445 = AXIS2_PLACEMENT_3D('',#161446,#161447,#161448); +#161446 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,-2.591449450184) + ); +#161447 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); +#161448 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#161449 = DEFINITIONAL_REPRESENTATION('',(#161450),#161454); +#161450 = LINE('',#161451,#161452); +#161451 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#161452 = VECTOR('',#161453,1.); +#161453 = DIRECTION('',(0.E+000,1.)); +#161454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161455 = ADVANCED_FACE('',(#161456),#161444,.T.); +#161456 = FACE_BOUND('',#161457,.T.); +#161457 = EDGE_LOOP('',(#161458,#161487,#161508,#161509)); +#161458 = ORIENTED_EDGE('',*,*,#161459,.F.); +#161459 = EDGE_CURVE('',#161460,#161462,#161464,.T.); +#161460 = VERTEX_POINT('',#161461); +#161461 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,-2.591449450184) + ); +#161462 = VERTEX_POINT('',#161463); +#161463 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,-2.591449450184) + ); +#161464 = SURFACE_CURVE('',#161465,(#161469,#161476),.PCURVE_S1.); +#161465 = LINE('',#161466,#161467); +#161466 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,-2.591449450184) + ); +#161467 = VECTOR('',#161468,1.); +#161468 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161469 = PCURVE('',#161444,#161470); +#161470 = DEFINITIONAL_REPRESENTATION('',(#161471),#161475); +#161471 = LINE('',#161472,#161473); +#161472 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); +#161473 = VECTOR('',#161474,1.); +#161474 = DIRECTION('',(0.E+000,1.)); +#161475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161476 = PCURVE('',#161477,#161482); +#161477 = CYLINDRICAL_SURFACE('',#161478,0.32); +#161478 = AXIS2_PLACEMENT_3D('',#161479,#161480,#161481); +#161479 = CARTESIAN_POINT('',(0.635,0.340821720102,-2.608196956182)); +#161480 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161481 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161482 = DEFINITIONAL_REPRESENTATION('',(#161483),#161486); +#161483 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161484,#161485), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159092 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159093 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159095 = ORIENTED_EDGE('',*,*,#159096,.F.); -#159096 = EDGE_CURVE('',#158992,#159068,#159097,.T.); -#159097 = SURFACE_CURVE('',#159098,(#159102,#159109),.PCURVE_S1.); -#159098 = LINE('',#159099,#159100); -#159099 = CARTESIAN_POINT('',(0.425,1.507511769892E-004,-2.994243044813) - ); -#159100 = VECTOR('',#159101,1.); -#159101 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#159102 = PCURVE('',#159052,#159103); -#159103 = DEFINITIONAL_REPRESENTATION('',(#159104),#159108); -#159104 = LINE('',#159105,#159106); -#159105 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#159106 = VECTOR('',#159107,1.); -#159107 = DIRECTION('',(-1.,0.E+000)); -#159108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159109 = PCURVE('',#158817,#159110); -#159110 = DEFINITIONAL_REPRESENTATION('',(#159111),#159115); -#159111 = LINE('',#159112,#159113); -#159112 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#159113 = VECTOR('',#159114,1.); -#159114 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#159115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159116 = ORIENTED_EDGE('',*,*,#159038,.T.); -#159117 = ORIENTED_EDGE('',*,*,#159118,.F.); -#159118 = EDGE_CURVE('',#159070,#159016,#159119,.T.); -#159119 = SURFACE_CURVE('',#159120,(#159124,#159131),.PCURVE_S1.); -#159120 = LINE('',#159121,#159122); -#159121 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,-2.591449450184) - ); -#159122 = VECTOR('',#159123,1.); -#159123 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#159124 = PCURVE('',#159052,#159125); -#159125 = DEFINITIONAL_REPRESENTATION('',(#159126),#159130); -#159126 = LINE('',#159127,#159128); -#159127 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); -#159128 = VECTOR('',#159129,1.); -#159129 = DIRECTION('',(1.,0.E+000)); -#159130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159131 = PCURVE('',#158764,#159132); -#159132 = DEFINITIONAL_REPRESENTATION('',(#159133),#159137); -#159133 = LINE('',#159134,#159135); -#159134 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#159135 = VECTOR('',#159136,1.); -#159136 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#159137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159138 = ADVANCED_FACE('',(#159139),#159085,.T.); -#159139 = FACE_BOUND('',#159140,.T.); -#159140 = EDGE_LOOP('',(#159141,#159170,#159191,#159192)); -#159141 = ORIENTED_EDGE('',*,*,#159142,.F.); -#159142 = EDGE_CURVE('',#159143,#159145,#159147,.T.); -#159143 = VERTEX_POINT('',#159144); -#159144 = CARTESIAN_POINT('',(0.425,0.298978581017,-2.290944451524)); -#159145 = VERTEX_POINT('',#159146); -#159146 = CARTESIAN_POINT('',(0.845,0.298978581017,-2.290944451524)); -#159147 = SURFACE_CURVE('',#159148,(#159152,#159158),.PCURVE_S1.); -#159148 = LINE('',#159149,#159150); -#159149 = CARTESIAN_POINT('',(0.635,0.298978581017,-2.290944451524)); -#159150 = VECTOR('',#159151,1.); -#159151 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159152 = PCURVE('',#159085,#159153); -#159153 = DEFINITIONAL_REPRESENTATION('',(#159154),#159157); -#159154 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159155,#159156), +#161484 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161485 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161487 = ORIENTED_EDGE('',*,*,#161488,.F.); +#161488 = EDGE_CURVE('',#161384,#161460,#161489,.T.); +#161489 = SURFACE_CURVE('',#161490,(#161494,#161501),.PCURVE_S1.); +#161490 = LINE('',#161491,#161492); +#161491 = CARTESIAN_POINT('',(0.425,1.507511769892E-004,-2.994243044813) + ); +#161492 = VECTOR('',#161493,1.); +#161493 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#161494 = PCURVE('',#161444,#161495); +#161495 = DEFINITIONAL_REPRESENTATION('',(#161496),#161500); +#161496 = LINE('',#161497,#161498); +#161497 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#161498 = VECTOR('',#161499,1.); +#161499 = DIRECTION('',(-1.,0.E+000)); +#161500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161501 = PCURVE('',#161209,#161502); +#161502 = DEFINITIONAL_REPRESENTATION('',(#161503),#161507); +#161503 = LINE('',#161504,#161505); +#161504 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#161505 = VECTOR('',#161506,1.); +#161506 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#161507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161508 = ORIENTED_EDGE('',*,*,#161430,.T.); +#161509 = ORIENTED_EDGE('',*,*,#161510,.F.); +#161510 = EDGE_CURVE('',#161462,#161408,#161511,.T.); +#161511 = SURFACE_CURVE('',#161512,(#161516,#161523),.PCURVE_S1.); +#161512 = LINE('',#161513,#161514); +#161513 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,-2.591449450184) + ); +#161514 = VECTOR('',#161515,1.); +#161515 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#161516 = PCURVE('',#161444,#161517); +#161517 = DEFINITIONAL_REPRESENTATION('',(#161518),#161522); +#161518 = LINE('',#161519,#161520); +#161519 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); +#161520 = VECTOR('',#161521,1.); +#161521 = DIRECTION('',(1.,0.E+000)); +#161522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161523 = PCURVE('',#161156,#161524); +#161524 = DEFINITIONAL_REPRESENTATION('',(#161525),#161529); +#161525 = LINE('',#161526,#161527); +#161526 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#161527 = VECTOR('',#161528,1.); +#161528 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#161529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161530 = ADVANCED_FACE('',(#161531),#161477,.T.); +#161531 = FACE_BOUND('',#161532,.T.); +#161532 = EDGE_LOOP('',(#161533,#161562,#161583,#161584)); +#161533 = ORIENTED_EDGE('',*,*,#161534,.F.); +#161534 = EDGE_CURVE('',#161535,#161537,#161539,.T.); +#161535 = VERTEX_POINT('',#161536); +#161536 = CARTESIAN_POINT('',(0.425,0.298978581017,-2.290944451524)); +#161537 = VERTEX_POINT('',#161538); +#161538 = CARTESIAN_POINT('',(0.845,0.298978581017,-2.290944451524)); +#161539 = SURFACE_CURVE('',#161540,(#161544,#161550),.PCURVE_S1.); +#161540 = LINE('',#161541,#161542); +#161541 = CARTESIAN_POINT('',(0.635,0.298978581017,-2.290944451524)); +#161542 = VECTOR('',#161543,1.); +#161543 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161544 = PCURVE('',#161477,#161545); +#161545 = DEFINITIONAL_REPRESENTATION('',(#161546),#161549); +#161546 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161547,#161548), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159155 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159156 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159158 = PCURVE('',#159159,#159164); -#159159 = PLANE('',#159160); -#159160 = AXIS2_PLACEMENT_3D('',#159161,#159162,#159163); -#159161 = CARTESIAN_POINT('',(0.635,0.678075980964,-2.240944451524)); -#159162 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); -#159163 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#159164 = DEFINITIONAL_REPRESENTATION('',(#159165),#159169); -#159165 = LINE('',#159166,#159167); -#159166 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#159167 = VECTOR('',#159168,1.); -#159168 = DIRECTION('',(0.E+000,1.)); -#159169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159170 = ORIENTED_EDGE('',*,*,#159171,.F.); -#159171 = EDGE_CURVE('',#159068,#159143,#159172,.T.); -#159172 = SURFACE_CURVE('',#159173,(#159178,#159184),.PCURVE_S1.); -#159173 = CIRCLE('',#159174,0.32); -#159174 = AXIS2_PLACEMENT_3D('',#159175,#159176,#159177); -#159175 = CARTESIAN_POINT('',(0.425,0.340821720102,-2.608196956182)); -#159176 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159177 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); -#159178 = PCURVE('',#159085,#159179); -#159179 = DEFINITIONAL_REPRESENTATION('',(#159180),#159183); -#159180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159181,#159182), +#161547 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161548 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161550 = PCURVE('',#161551,#161556); +#161551 = PLANE('',#161552); +#161552 = AXIS2_PLACEMENT_3D('',#161553,#161554,#161555); +#161553 = CARTESIAN_POINT('',(0.635,0.678075980964,-2.240944451524)); +#161554 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); +#161555 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#161556 = DEFINITIONAL_REPRESENTATION('',(#161557),#161561); +#161557 = LINE('',#161558,#161559); +#161558 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#161559 = VECTOR('',#161560,1.); +#161560 = DIRECTION('',(0.E+000,1.)); +#161561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161562 = ORIENTED_EDGE('',*,*,#161563,.F.); +#161563 = EDGE_CURVE('',#161460,#161535,#161564,.T.); +#161564 = SURFACE_CURVE('',#161565,(#161570,#161576),.PCURVE_S1.); +#161565 = CIRCLE('',#161566,0.32); +#161566 = AXIS2_PLACEMENT_3D('',#161567,#161568,#161569); +#161567 = CARTESIAN_POINT('',(0.425,0.340821720102,-2.608196956182)); +#161568 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161569 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); +#161570 = PCURVE('',#161477,#161571); +#161571 = DEFINITIONAL_REPRESENTATION('',(#161572),#161575); +#161572 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161573,#161574), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#159181 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159182 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159184 = PCURVE('',#158817,#159185); -#159185 = DEFINITIONAL_REPRESENTATION('',(#159186),#159190); -#159186 = CIRCLE('',#159187,0.32); -#159187 = AXIS2_PLACEMENT_2D('',#159188,#159189); -#159188 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#159189 = DIRECTION('',(-1.,1.694065894509E-015)); -#159190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159191 = ORIENTED_EDGE('',*,*,#159067,.T.); -#159192 = ORIENTED_EDGE('',*,*,#159193,.F.); -#159193 = EDGE_CURVE('',#159145,#159070,#159194,.T.); -#159194 = SURFACE_CURVE('',#159195,(#159200,#159206),.PCURVE_S1.); -#159195 = CIRCLE('',#159196,0.32); -#159196 = AXIS2_PLACEMENT_3D('',#159197,#159198,#159199); -#159197 = CARTESIAN_POINT('',(0.845,0.340821720102,-2.608196956182)); -#159198 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159199 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159200 = PCURVE('',#159085,#159201); -#159201 = DEFINITIONAL_REPRESENTATION('',(#159202),#159205); -#159202 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159203,#159204), +#161573 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161574 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161576 = PCURVE('',#161209,#161577); +#161577 = DEFINITIONAL_REPRESENTATION('',(#161578),#161582); +#161578 = CIRCLE('',#161579,0.32); +#161579 = AXIS2_PLACEMENT_2D('',#161580,#161581); +#161580 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#161581 = DIRECTION('',(-1.,1.694065894509E-015)); +#161582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161583 = ORIENTED_EDGE('',*,*,#161459,.T.); +#161584 = ORIENTED_EDGE('',*,*,#161585,.F.); +#161585 = EDGE_CURVE('',#161537,#161462,#161586,.T.); +#161586 = SURFACE_CURVE('',#161587,(#161592,#161598),.PCURVE_S1.); +#161587 = CIRCLE('',#161588,0.32); +#161588 = AXIS2_PLACEMENT_3D('',#161589,#161590,#161591); +#161589 = CARTESIAN_POINT('',(0.845,0.340821720102,-2.608196956182)); +#161590 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161591 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161592 = PCURVE('',#161477,#161593); +#161593 = DEFINITIONAL_REPRESENTATION('',(#161594),#161597); +#161594 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161595,#161596), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#159203 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159204 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159206 = PCURVE('',#158764,#159207); -#159207 = DEFINITIONAL_REPRESENTATION('',(#159208),#159212); -#159208 = CIRCLE('',#159209,0.32); -#159209 = AXIS2_PLACEMENT_2D('',#159210,#159211); -#159210 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#159211 = DIRECTION('',(1.,0.E+000)); -#159212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159213 = ADVANCED_FACE('',(#159214),#159159,.T.); -#159214 = FACE_BOUND('',#159215,.T.); -#159215 = EDGE_LOOP('',(#159216,#159245,#159266,#159267)); -#159216 = ORIENTED_EDGE('',*,*,#159217,.T.); -#159217 = EDGE_CURVE('',#159218,#159220,#159222,.T.); -#159218 = VERTEX_POINT('',#159219); -#159219 = CARTESIAN_POINT('',(0.845,0.678075980964,-2.240944451524)); -#159220 = VERTEX_POINT('',#159221); -#159221 = CARTESIAN_POINT('',(0.425,0.678075980964,-2.240944451524)); -#159222 = SURFACE_CURVE('',#159223,(#159227,#159234),.PCURVE_S1.); -#159223 = LINE('',#159224,#159225); -#159224 = CARTESIAN_POINT('',(0.635,0.678075980964,-2.240944451524)); -#159225 = VECTOR('',#159226,1.); -#159226 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159227 = PCURVE('',#159159,#159228); -#159228 = DEFINITIONAL_REPRESENTATION('',(#159229),#159233); -#159229 = LINE('',#159230,#159231); -#159230 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#159231 = VECTOR('',#159232,1.); -#159232 = DIRECTION('',(0.E+000,-1.)); -#159233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159234 = PCURVE('',#159235,#159240); -#159235 = CYLINDRICAL_SURFACE('',#159236,1.E-001); -#159236 = AXIS2_PLACEMENT_3D('',#159237,#159238,#159239); -#159237 = CARTESIAN_POINT('',(0.635,0.665,-2.141803043818)); -#159238 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159239 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159240 = DEFINITIONAL_REPRESENTATION('',(#159241),#159244); -#159241 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159242,#159243), +#161595 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161596 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161598 = PCURVE('',#161156,#161599); +#161599 = DEFINITIONAL_REPRESENTATION('',(#161600),#161604); +#161600 = CIRCLE('',#161601,0.32); +#161601 = AXIS2_PLACEMENT_2D('',#161602,#161603); +#161602 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#161603 = DIRECTION('',(1.,0.E+000)); +#161604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161605 = ADVANCED_FACE('',(#161606),#161551,.T.); +#161606 = FACE_BOUND('',#161607,.T.); +#161607 = EDGE_LOOP('',(#161608,#161637,#161658,#161659)); +#161608 = ORIENTED_EDGE('',*,*,#161609,.T.); +#161609 = EDGE_CURVE('',#161610,#161612,#161614,.T.); +#161610 = VERTEX_POINT('',#161611); +#161611 = CARTESIAN_POINT('',(0.845,0.678075980964,-2.240944451524)); +#161612 = VERTEX_POINT('',#161613); +#161613 = CARTESIAN_POINT('',(0.425,0.678075980964,-2.240944451524)); +#161614 = SURFACE_CURVE('',#161615,(#161619,#161626),.PCURVE_S1.); +#161615 = LINE('',#161616,#161617); +#161616 = CARTESIAN_POINT('',(0.635,0.678075980964,-2.240944451524)); +#161617 = VECTOR('',#161618,1.); +#161618 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161619 = PCURVE('',#161551,#161620); +#161620 = DEFINITIONAL_REPRESENTATION('',(#161621),#161625); +#161621 = LINE('',#161622,#161623); +#161622 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#161623 = VECTOR('',#161624,1.); +#161624 = DIRECTION('',(0.E+000,-1.)); +#161625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161626 = PCURVE('',#161627,#161632); +#161627 = CYLINDRICAL_SURFACE('',#161628,1.E-001); +#161628 = AXIS2_PLACEMENT_3D('',#161629,#161630,#161631); +#161629 = CARTESIAN_POINT('',(0.635,0.665,-2.141803043818)); +#161630 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161631 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161632 = DEFINITIONAL_REPRESENTATION('',(#161633),#161636); +#161633 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161634,#161635), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159242 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#159243 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#159244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159245 = ORIENTED_EDGE('',*,*,#159246,.F.); -#159246 = EDGE_CURVE('',#159143,#159220,#159247,.T.); -#159247 = SURFACE_CURVE('',#159248,(#159252,#159259),.PCURVE_S1.); -#159248 = LINE('',#159249,#159250); -#159249 = CARTESIAN_POINT('',(0.425,0.298978581017,-2.290944451524)); -#159250 = VECTOR('',#159251,1.); -#159251 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#159252 = PCURVE('',#159159,#159253); -#159253 = DEFINITIONAL_REPRESENTATION('',(#159254),#159258); -#159254 = LINE('',#159255,#159256); -#159255 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#159256 = VECTOR('',#159257,1.); -#159257 = DIRECTION('',(-1.,0.E+000)); -#159258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159259 = PCURVE('',#158817,#159260); -#159260 = DEFINITIONAL_REPRESENTATION('',(#159261),#159265); -#159261 = LINE('',#159262,#159263); -#159262 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#159263 = VECTOR('',#159264,1.); -#159264 = DIRECTION('',(0.130759809642,0.991414077055)); -#159265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159266 = ORIENTED_EDGE('',*,*,#159142,.T.); -#159267 = ORIENTED_EDGE('',*,*,#159268,.F.); -#159268 = EDGE_CURVE('',#159218,#159145,#159269,.T.); -#159269 = SURFACE_CURVE('',#159270,(#159274,#159281),.PCURVE_S1.); -#159270 = LINE('',#159271,#159272); -#159271 = CARTESIAN_POINT('',(0.845,0.678075980964,-2.240944451524)); -#159272 = VECTOR('',#159273,1.); -#159273 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#159274 = PCURVE('',#159159,#159275); -#159275 = DEFINITIONAL_REPRESENTATION('',(#159276),#159280); -#159276 = LINE('',#159277,#159278); -#159277 = CARTESIAN_POINT('',(0.E+000,0.21)); -#159278 = VECTOR('',#159279,1.); -#159279 = DIRECTION('',(1.,0.E+000)); -#159280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159281 = PCURVE('',#158764,#159282); -#159282 = DEFINITIONAL_REPRESENTATION('',(#159283),#159287); -#159283 = LINE('',#159284,#159285); -#159284 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#159285 = VECTOR('',#159286,1.); -#159286 = DIRECTION('',(0.130759809642,-0.991414077055)); -#159287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159288 = ADVANCED_FACE('',(#159289),#159235,.F.); -#159289 = FACE_BOUND('',#159290,.F.); -#159290 = EDGE_LOOP('',(#159291,#159318,#159319,#159346)); -#159291 = ORIENTED_EDGE('',*,*,#159292,.T.); -#159292 = EDGE_CURVE('',#159293,#159218,#159295,.T.); -#159293 = VERTEX_POINT('',#159294); -#159294 = CARTESIAN_POINT('',(0.845,0.765,-2.141803043818)); -#159295 = SURFACE_CURVE('',#159296,(#159301,#159307),.PCURVE_S1.); -#159296 = CIRCLE('',#159297,1.E-001); -#159297 = AXIS2_PLACEMENT_3D('',#159298,#159299,#159300); -#159298 = CARTESIAN_POINT('',(0.845,0.665,-2.141803043818)); -#159299 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159300 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159301 = PCURVE('',#159235,#159302); -#159302 = DEFINITIONAL_REPRESENTATION('',(#159303),#159306); -#159303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159304,#159305), +#161634 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#161635 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#161636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161637 = ORIENTED_EDGE('',*,*,#161638,.F.); +#161638 = EDGE_CURVE('',#161535,#161612,#161639,.T.); +#161639 = SURFACE_CURVE('',#161640,(#161644,#161651),.PCURVE_S1.); +#161640 = LINE('',#161641,#161642); +#161641 = CARTESIAN_POINT('',(0.425,0.298978581017,-2.290944451524)); +#161642 = VECTOR('',#161643,1.); +#161643 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#161644 = PCURVE('',#161551,#161645); +#161645 = DEFINITIONAL_REPRESENTATION('',(#161646),#161650); +#161646 = LINE('',#161647,#161648); +#161647 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#161648 = VECTOR('',#161649,1.); +#161649 = DIRECTION('',(-1.,0.E+000)); +#161650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161651 = PCURVE('',#161209,#161652); +#161652 = DEFINITIONAL_REPRESENTATION('',(#161653),#161657); +#161653 = LINE('',#161654,#161655); +#161654 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#161655 = VECTOR('',#161656,1.); +#161656 = DIRECTION('',(0.130759809642,0.991414077055)); +#161657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161658 = ORIENTED_EDGE('',*,*,#161534,.T.); +#161659 = ORIENTED_EDGE('',*,*,#161660,.F.); +#161660 = EDGE_CURVE('',#161610,#161537,#161661,.T.); +#161661 = SURFACE_CURVE('',#161662,(#161666,#161673),.PCURVE_S1.); +#161662 = LINE('',#161663,#161664); +#161663 = CARTESIAN_POINT('',(0.845,0.678075980964,-2.240944451524)); +#161664 = VECTOR('',#161665,1.); +#161665 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#161666 = PCURVE('',#161551,#161667); +#161667 = DEFINITIONAL_REPRESENTATION('',(#161668),#161672); +#161668 = LINE('',#161669,#161670); +#161669 = CARTESIAN_POINT('',(0.E+000,0.21)); +#161670 = VECTOR('',#161671,1.); +#161671 = DIRECTION('',(1.,0.E+000)); +#161672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161673 = PCURVE('',#161156,#161674); +#161674 = DEFINITIONAL_REPRESENTATION('',(#161675),#161679); +#161675 = LINE('',#161676,#161677); +#161676 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#161677 = VECTOR('',#161678,1.); +#161678 = DIRECTION('',(0.130759809642,-0.991414077055)); +#161679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161680 = ADVANCED_FACE('',(#161681),#161627,.F.); +#161681 = FACE_BOUND('',#161682,.F.); +#161682 = EDGE_LOOP('',(#161683,#161710,#161711,#161738)); +#161683 = ORIENTED_EDGE('',*,*,#161684,.T.); +#161684 = EDGE_CURVE('',#161685,#161610,#161687,.T.); +#161685 = VERTEX_POINT('',#161686); +#161686 = CARTESIAN_POINT('',(0.845,0.765,-2.141803043818)); +#161687 = SURFACE_CURVE('',#161688,(#161693,#161699),.PCURVE_S1.); +#161688 = CIRCLE('',#161689,1.E-001); +#161689 = AXIS2_PLACEMENT_3D('',#161690,#161691,#161692); +#161690 = CARTESIAN_POINT('',(0.845,0.665,-2.141803043818)); +#161691 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161692 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161693 = PCURVE('',#161627,#161694); +#161694 = DEFINITIONAL_REPRESENTATION('',(#161695),#161698); +#161695 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161696,#161697), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#159304 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#159305 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#159306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161696 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#161697 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#161698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159307 = PCURVE('',#158764,#159308); -#159308 = DEFINITIONAL_REPRESENTATION('',(#159309),#159317); -#159309 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159310,#159311,#159312, - #159313,#159314,#159315,#159316),.UNSPECIFIED.,.T.,.F.) +#161699 = PCURVE('',#161156,#161700); +#161700 = DEFINITIONAL_REPRESENTATION('',(#161701),#161709); +#161701 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161702,#161703,#161704, + #161705,#161706,#161707,#161708),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159310 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#159311 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#159312 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#159313 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#159314 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#159315 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#159316 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#159317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159318 = ORIENTED_EDGE('',*,*,#159217,.T.); -#159319 = ORIENTED_EDGE('',*,*,#159320,.T.); -#159320 = EDGE_CURVE('',#159220,#159321,#159323,.T.); -#159321 = VERTEX_POINT('',#159322); -#159322 = CARTESIAN_POINT('',(0.425,0.765,-2.141803043818)); -#159323 = SURFACE_CURVE('',#159324,(#159329,#159335),.PCURVE_S1.); -#159324 = CIRCLE('',#159325,1.E-001); -#159325 = AXIS2_PLACEMENT_3D('',#159326,#159327,#159328); -#159326 = CARTESIAN_POINT('',(0.425,0.665,-2.141803043818)); -#159327 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159328 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); -#159329 = PCURVE('',#159235,#159330); -#159330 = DEFINITIONAL_REPRESENTATION('',(#159331),#159334); -#159331 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159332,#159333), +#161702 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#161703 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#161704 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#161705 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#161706 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#161707 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#161708 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#161709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161710 = ORIENTED_EDGE('',*,*,#161609,.T.); +#161711 = ORIENTED_EDGE('',*,*,#161712,.T.); +#161712 = EDGE_CURVE('',#161612,#161713,#161715,.T.); +#161713 = VERTEX_POINT('',#161714); +#161714 = CARTESIAN_POINT('',(0.425,0.765,-2.141803043818)); +#161715 = SURFACE_CURVE('',#161716,(#161721,#161727),.PCURVE_S1.); +#161716 = CIRCLE('',#161717,1.E-001); +#161717 = AXIS2_PLACEMENT_3D('',#161718,#161719,#161720); +#161718 = CARTESIAN_POINT('',(0.425,0.665,-2.141803043818)); +#161719 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161720 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); +#161721 = PCURVE('',#161627,#161722); +#161722 = DEFINITIONAL_REPRESENTATION('',(#161723),#161726); +#161723 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161724,#161725), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#159332 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#159333 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#159334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161724 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#161725 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#161726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159335 = PCURVE('',#158817,#159336); -#159336 = DEFINITIONAL_REPRESENTATION('',(#159337),#159345); -#159337 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159338,#159339,#159340, - #159341,#159342,#159343,#159344),.UNSPECIFIED.,.T.,.F.) +#161727 = PCURVE('',#161209,#161728); +#161728 = DEFINITIONAL_REPRESENTATION('',(#161729),#161737); +#161729 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161730,#161731,#161732, + #161733,#161734,#161735,#161736),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159338 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#159339 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#159340 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#159341 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#159342 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#159343 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#159344 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#159345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159346 = ORIENTED_EDGE('',*,*,#159347,.T.); -#159347 = EDGE_CURVE('',#159321,#159293,#159348,.T.); -#159348 = SURFACE_CURVE('',#159349,(#159353,#159359),.PCURVE_S1.); -#159349 = LINE('',#159350,#159351); -#159350 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); -#159351 = VECTOR('',#159352,1.); -#159352 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159353 = PCURVE('',#159235,#159354); -#159354 = DEFINITIONAL_REPRESENTATION('',(#159355),#159358); -#159355 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159356,#159357), +#161730 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#161731 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#161732 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#161733 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#161734 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#161735 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#161736 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#161737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161738 = ORIENTED_EDGE('',*,*,#161739,.T.); +#161739 = EDGE_CURVE('',#161713,#161685,#161740,.T.); +#161740 = SURFACE_CURVE('',#161741,(#161745,#161751),.PCURVE_S1.); +#161741 = LINE('',#161742,#161743); +#161742 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); +#161743 = VECTOR('',#161744,1.); +#161744 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161745 = PCURVE('',#161627,#161746); +#161746 = DEFINITIONAL_REPRESENTATION('',(#161747),#161750); +#161747 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161748,#161749), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159356 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#159357 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#159358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159359 = PCURVE('',#159360,#159365); -#159360 = PLANE('',#159361); -#159361 = AXIS2_PLACEMENT_3D('',#159362,#159363,#159364); -#159362 = CARTESIAN_POINT('',(0.635,0.765,0.E+000)); -#159363 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#159364 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159365 = DEFINITIONAL_REPRESENTATION('',(#159366),#159370); -#159366 = LINE('',#159367,#159368); -#159367 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#159368 = VECTOR('',#159369,1.); -#159369 = DIRECTION('',(0.E+000,1.)); -#159370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159371 = ADVANCED_FACE('',(#159372),#159386,.T.); -#159372 = FACE_BOUND('',#159373,.T.); -#159373 = EDGE_LOOP('',(#159374,#159408,#159436,#159463)); -#159374 = ORIENTED_EDGE('',*,*,#159375,.F.); -#159375 = EDGE_CURVE('',#159376,#159378,#159380,.T.); -#159376 = VERTEX_POINT('',#159377); -#159377 = CARTESIAN_POINT('',(-0.425,0.706843139085,-2.459055548476)); -#159378 = VERTEX_POINT('',#159379); -#159379 = CARTESIAN_POINT('',(-0.845,0.706843139085,-2.459055548476)); -#159380 = SURFACE_CURVE('',#159381,(#159385,#159397),.PCURVE_S1.); -#159381 = LINE('',#159382,#159383); -#159382 = CARTESIAN_POINT('',(-0.635,0.706843139085,-2.459055548476)); -#159383 = VECTOR('',#159384,1.); -#159384 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159385 = PCURVE('',#159386,#159391); -#159386 = PLANE('',#159387); -#159387 = AXIS2_PLACEMENT_3D('',#159388,#159389,#159390); -#159388 = CARTESIAN_POINT('',(-0.635,0.706843139085,-2.459055548476)); -#159389 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); -#159390 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#159391 = DEFINITIONAL_REPRESENTATION('',(#159392),#159396); -#159392 = LINE('',#159393,#159394); -#159393 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#159394 = VECTOR('',#159395,1.); -#159395 = DIRECTION('',(0.E+000,-1.)); -#159396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159397 = PCURVE('',#159398,#159403); -#159398 = CYLINDRICAL_SURFACE('',#159399,0.32); -#159399 = AXIS2_PLACEMENT_3D('',#159400,#159401,#159402); -#159400 = CARTESIAN_POINT('',(-0.635,0.665,-2.141803043818)); -#159401 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159402 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159403 = DEFINITIONAL_REPRESENTATION('',(#159404),#159407); -#159404 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159405,#159406), +#161748 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#161749 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#161750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161751 = PCURVE('',#161752,#161757); +#161752 = PLANE('',#161753); +#161753 = AXIS2_PLACEMENT_3D('',#161754,#161755,#161756); +#161754 = CARTESIAN_POINT('',(0.635,0.765,0.E+000)); +#161755 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#161756 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161757 = DEFINITIONAL_REPRESENTATION('',(#161758),#161762); +#161758 = LINE('',#161759,#161760); +#161759 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#161760 = VECTOR('',#161761,1.); +#161761 = DIRECTION('',(0.E+000,1.)); +#161762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161763 = ADVANCED_FACE('',(#161764),#161778,.T.); +#161764 = FACE_BOUND('',#161765,.T.); +#161765 = EDGE_LOOP('',(#161766,#161800,#161828,#161855)); +#161766 = ORIENTED_EDGE('',*,*,#161767,.F.); +#161767 = EDGE_CURVE('',#161768,#161770,#161772,.T.); +#161768 = VERTEX_POINT('',#161769); +#161769 = CARTESIAN_POINT('',(-0.425,0.706843139085,-2.459055548476)); +#161770 = VERTEX_POINT('',#161771); +#161771 = CARTESIAN_POINT('',(-0.845,0.706843139085,-2.459055548476)); +#161772 = SURFACE_CURVE('',#161773,(#161777,#161789),.PCURVE_S1.); +#161773 = LINE('',#161774,#161775); +#161774 = CARTESIAN_POINT('',(-0.635,0.706843139085,-2.459055548476)); +#161775 = VECTOR('',#161776,1.); +#161776 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161777 = PCURVE('',#161778,#161783); +#161778 = PLANE('',#161779); +#161779 = AXIS2_PLACEMENT_3D('',#161780,#161781,#161782); +#161780 = CARTESIAN_POINT('',(-0.635,0.706843139085,-2.459055548476)); +#161781 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); +#161782 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#161783 = DEFINITIONAL_REPRESENTATION('',(#161784),#161788); +#161784 = LINE('',#161785,#161786); +#161785 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#161786 = VECTOR('',#161787,1.); +#161787 = DIRECTION('',(0.E+000,-1.)); +#161788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161789 = PCURVE('',#161790,#161795); +#161790 = CYLINDRICAL_SURFACE('',#161791,0.32); +#161791 = AXIS2_PLACEMENT_3D('',#161792,#161793,#161794); +#161792 = CARTESIAN_POINT('',(-0.635,0.665,-2.141803043818)); +#161793 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161794 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161795 = DEFINITIONAL_REPRESENTATION('',(#161796),#161799); +#161796 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161797,#161798), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159405 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#159406 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#159407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159408 = ORIENTED_EDGE('',*,*,#159409,.F.); -#159409 = EDGE_CURVE('',#159410,#159376,#159412,.T.); -#159410 = VERTEX_POINT('',#159411); -#159411 = CARTESIAN_POINT('',(-0.425,0.327745739138,-2.509055548476)); -#159412 = SURFACE_CURVE('',#159413,(#159417,#159424),.PCURVE_S1.); -#159413 = LINE('',#159414,#159415); -#159414 = CARTESIAN_POINT('',(-0.425,0.327745739138,-2.509055548476)); -#159415 = VECTOR('',#159416,1.); -#159416 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#159417 = PCURVE('',#159386,#159418); -#159418 = DEFINITIONAL_REPRESENTATION('',(#159419),#159423); -#159419 = LINE('',#159420,#159421); -#159420 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#159421 = VECTOR('',#159422,1.); -#159422 = DIRECTION('',(1.,0.E+000)); -#159423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159424 = PCURVE('',#159425,#159430); -#159425 = PLANE('',#159426); -#159426 = AXIS2_PLACEMENT_3D('',#159427,#159428,#159429); -#159427 = CARTESIAN_POINT('',(-0.425,0.875,0.E+000)); -#159428 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159429 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159430 = DEFINITIONAL_REPRESENTATION('',(#159431),#159435); -#159431 = LINE('',#159432,#159433); -#159432 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#159433 = VECTOR('',#159434,1.); -#159434 = DIRECTION('',(-0.130759809642,0.991414077055)); -#159435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159436 = ORIENTED_EDGE('',*,*,#159437,.T.); -#159437 = EDGE_CURVE('',#159410,#159438,#159440,.T.); -#159438 = VERTEX_POINT('',#159439); -#159439 = CARTESIAN_POINT('',(-0.845,0.327745739138,-2.509055548476)); -#159440 = SURFACE_CURVE('',#159441,(#159445,#159452),.PCURVE_S1.); -#159441 = LINE('',#159442,#159443); -#159442 = CARTESIAN_POINT('',(-0.635,0.327745739138,-2.509055548476)); -#159443 = VECTOR('',#159444,1.); -#159444 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159445 = PCURVE('',#159386,#159446); -#159446 = DEFINITIONAL_REPRESENTATION('',(#159447),#159451); -#159447 = LINE('',#159448,#159449); -#159448 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#159449 = VECTOR('',#159450,1.); -#159450 = DIRECTION('',(0.E+000,-1.)); -#159451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159452 = PCURVE('',#159453,#159458); -#159453 = CYLINDRICAL_SURFACE('',#159454,9.999999999999E-002); -#159454 = AXIS2_PLACEMENT_3D('',#159455,#159456,#159457); -#159455 = CARTESIAN_POINT('',(-0.635,0.340821720102,-2.608196956182)); -#159456 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159457 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159458 = DEFINITIONAL_REPRESENTATION('',(#159459),#159462); -#159459 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159460,#159461), +#161797 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#161798 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#161799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161800 = ORIENTED_EDGE('',*,*,#161801,.F.); +#161801 = EDGE_CURVE('',#161802,#161768,#161804,.T.); +#161802 = VERTEX_POINT('',#161803); +#161803 = CARTESIAN_POINT('',(-0.425,0.327745739138,-2.509055548476)); +#161804 = SURFACE_CURVE('',#161805,(#161809,#161816),.PCURVE_S1.); +#161805 = LINE('',#161806,#161807); +#161806 = CARTESIAN_POINT('',(-0.425,0.327745739138,-2.509055548476)); +#161807 = VECTOR('',#161808,1.); +#161808 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#161809 = PCURVE('',#161778,#161810); +#161810 = DEFINITIONAL_REPRESENTATION('',(#161811),#161815); +#161811 = LINE('',#161812,#161813); +#161812 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#161813 = VECTOR('',#161814,1.); +#161814 = DIRECTION('',(1.,0.E+000)); +#161815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161816 = PCURVE('',#161817,#161822); +#161817 = PLANE('',#161818); +#161818 = AXIS2_PLACEMENT_3D('',#161819,#161820,#161821); +#161819 = CARTESIAN_POINT('',(-0.425,0.875,0.E+000)); +#161820 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161821 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161822 = DEFINITIONAL_REPRESENTATION('',(#161823),#161827); +#161823 = LINE('',#161824,#161825); +#161824 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#161825 = VECTOR('',#161826,1.); +#161826 = DIRECTION('',(-0.130759809642,0.991414077055)); +#161827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161828 = ORIENTED_EDGE('',*,*,#161829,.T.); +#161829 = EDGE_CURVE('',#161802,#161830,#161832,.T.); +#161830 = VERTEX_POINT('',#161831); +#161831 = CARTESIAN_POINT('',(-0.845,0.327745739138,-2.509055548476)); +#161832 = SURFACE_CURVE('',#161833,(#161837,#161844),.PCURVE_S1.); +#161833 = LINE('',#161834,#161835); +#161834 = CARTESIAN_POINT('',(-0.635,0.327745739138,-2.509055548476)); +#161835 = VECTOR('',#161836,1.); +#161836 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161837 = PCURVE('',#161778,#161838); +#161838 = DEFINITIONAL_REPRESENTATION('',(#161839),#161843); +#161839 = LINE('',#161840,#161841); +#161840 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#161841 = VECTOR('',#161842,1.); +#161842 = DIRECTION('',(0.E+000,-1.)); +#161843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161844 = PCURVE('',#161845,#161850); +#161845 = CYLINDRICAL_SURFACE('',#161846,9.999999999999E-002); +#161846 = AXIS2_PLACEMENT_3D('',#161847,#161848,#161849); +#161847 = CARTESIAN_POINT('',(-0.635,0.340821720102,-2.608196956182)); +#161848 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161849 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161850 = DEFINITIONAL_REPRESENTATION('',(#161851),#161854); +#161851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161852,#161853), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159460 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159461 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159463 = ORIENTED_EDGE('',*,*,#159464,.F.); -#159464 = EDGE_CURVE('',#159378,#159438,#159465,.T.); -#159465 = SURFACE_CURVE('',#159466,(#159470,#159477),.PCURVE_S1.); -#159466 = LINE('',#159467,#159468); -#159467 = CARTESIAN_POINT('',(-0.845,0.706843139085,-2.459055548476)); -#159468 = VECTOR('',#159469,1.); -#159469 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#159470 = PCURVE('',#159386,#159471); -#159471 = DEFINITIONAL_REPRESENTATION('',(#159472),#159476); -#159472 = LINE('',#159473,#159474); -#159473 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#159474 = VECTOR('',#159475,1.); -#159475 = DIRECTION('',(-1.,0.E+000)); -#159476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159477 = PCURVE('',#159478,#159483); -#159478 = PLANE('',#159479); -#159479 = AXIS2_PLACEMENT_3D('',#159480,#159481,#159482); -#159480 = CARTESIAN_POINT('',(-0.845,0.875,0.E+000)); -#159481 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159482 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159483 = DEFINITIONAL_REPRESENTATION('',(#159484),#159488); -#159484 = LINE('',#159485,#159486); -#159485 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#159486 = VECTOR('',#159487,1.); -#159487 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#159488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159489 = ADVANCED_FACE('',(#159490),#159453,.F.); -#159490 = FACE_BOUND('',#159491,.F.); -#159491 = EDGE_LOOP('',(#159492,#159519,#159546,#159571)); -#159492 = ORIENTED_EDGE('',*,*,#159493,.T.); -#159493 = EDGE_CURVE('',#159438,#159494,#159496,.T.); -#159494 = VERTEX_POINT('',#159495); -#159495 = CARTESIAN_POINT('',(-0.845,0.240958766627,-2.602963360557)); -#159496 = SURFACE_CURVE('',#159497,(#159502,#159508),.PCURVE_S1.); -#159497 = CIRCLE('',#159498,9.999999999999E-002); -#159498 = AXIS2_PLACEMENT_3D('',#159499,#159500,#159501); -#159499 = CARTESIAN_POINT('',(-0.845,0.340821720102,-2.608196956182)); -#159500 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159501 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159502 = PCURVE('',#159453,#159503); -#159503 = DEFINITIONAL_REPRESENTATION('',(#159504),#159507); -#159504 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159505,#159506), +#161852 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161853 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161855 = ORIENTED_EDGE('',*,*,#161856,.F.); +#161856 = EDGE_CURVE('',#161770,#161830,#161857,.T.); +#161857 = SURFACE_CURVE('',#161858,(#161862,#161869),.PCURVE_S1.); +#161858 = LINE('',#161859,#161860); +#161859 = CARTESIAN_POINT('',(-0.845,0.706843139085,-2.459055548476)); +#161860 = VECTOR('',#161861,1.); +#161861 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#161862 = PCURVE('',#161778,#161863); +#161863 = DEFINITIONAL_REPRESENTATION('',(#161864),#161868); +#161864 = LINE('',#161865,#161866); +#161865 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#161866 = VECTOR('',#161867,1.); +#161867 = DIRECTION('',(-1.,0.E+000)); +#161868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161869 = PCURVE('',#161870,#161875); +#161870 = PLANE('',#161871); +#161871 = AXIS2_PLACEMENT_3D('',#161872,#161873,#161874); +#161872 = CARTESIAN_POINT('',(-0.845,0.875,0.E+000)); +#161873 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161874 = DIRECTION('',(0.E+000,0.E+000,1.)); +#161875 = DEFINITIONAL_REPRESENTATION('',(#161876),#161880); +#161876 = LINE('',#161877,#161878); +#161877 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#161878 = VECTOR('',#161879,1.); +#161879 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#161880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161881 = ADVANCED_FACE('',(#161882),#161845,.F.); +#161882 = FACE_BOUND('',#161883,.F.); +#161883 = EDGE_LOOP('',(#161884,#161911,#161938,#161963)); +#161884 = ORIENTED_EDGE('',*,*,#161885,.T.); +#161885 = EDGE_CURVE('',#161830,#161886,#161888,.T.); +#161886 = VERTEX_POINT('',#161887); +#161887 = CARTESIAN_POINT('',(-0.845,0.240958766627,-2.602963360557)); +#161888 = SURFACE_CURVE('',#161889,(#161894,#161900),.PCURVE_S1.); +#161889 = CIRCLE('',#161890,9.999999999999E-002); +#161890 = AXIS2_PLACEMENT_3D('',#161891,#161892,#161893); +#161891 = CARTESIAN_POINT('',(-0.845,0.340821720102,-2.608196956182)); +#161892 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161893 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#161894 = PCURVE('',#161845,#161895); +#161895 = DEFINITIONAL_REPRESENTATION('',(#161896),#161899); +#161896 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161897,#161898), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#159505 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159506 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161897 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#161898 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159508 = PCURVE('',#159478,#159509); -#159509 = DEFINITIONAL_REPRESENTATION('',(#159510),#159518); -#159510 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159511,#159512,#159513, - #159514,#159515,#159516,#159517),.UNSPECIFIED.,.T.,.F.) +#161900 = PCURVE('',#161870,#161901); +#161901 = DEFINITIONAL_REPRESENTATION('',(#161902),#161910); +#161902 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161903,#161904,#161905, + #161906,#161907,#161908,#161909),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159511 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#159512 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#159513 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#159514 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#159515 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#159516 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#159517 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#159518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159519 = ORIENTED_EDGE('',*,*,#159520,.T.); -#159520 = EDGE_CURVE('',#159494,#159521,#159523,.T.); -#159521 = VERTEX_POINT('',#159522); -#159522 = CARTESIAN_POINT('',(-0.425,0.240958766627,-2.602963360557)); -#159523 = SURFACE_CURVE('',#159524,(#159528,#159534),.PCURVE_S1.); -#159524 = LINE('',#159525,#159526); -#159525 = CARTESIAN_POINT('',(-0.635,0.240958766627,-2.602963360557)); -#159526 = VECTOR('',#159527,1.); -#159527 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159528 = PCURVE('',#159453,#159529); -#159529 = DEFINITIONAL_REPRESENTATION('',(#159530),#159533); -#159530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159531,#159532), +#161903 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#161904 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#161905 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#161906 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#161907 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#161908 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#161909 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#161910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161911 = ORIENTED_EDGE('',*,*,#161912,.T.); +#161912 = EDGE_CURVE('',#161886,#161913,#161915,.T.); +#161913 = VERTEX_POINT('',#161914); +#161914 = CARTESIAN_POINT('',(-0.425,0.240958766627,-2.602963360557)); +#161915 = SURFACE_CURVE('',#161916,(#161920,#161926),.PCURVE_S1.); +#161916 = LINE('',#161917,#161918); +#161917 = CARTESIAN_POINT('',(-0.635,0.240958766627,-2.602963360557)); +#161918 = VECTOR('',#161919,1.); +#161919 = DIRECTION('',(1.,0.E+000,0.E+000)); +#161920 = PCURVE('',#161845,#161921); +#161921 = DEFINITIONAL_REPRESENTATION('',(#161922),#161925); +#161922 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161923,#161924), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159531 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159532 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159534 = PCURVE('',#159535,#159540); -#159535 = PLANE('',#159536); -#159536 = AXIS2_PLACEMENT_3D('',#159537,#159538,#159539); -#159537 = CARTESIAN_POINT('',(-0.635,0.240958766627,-2.602963360557)); -#159538 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); -#159539 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#159540 = DEFINITIONAL_REPRESENTATION('',(#159541),#159545); -#159541 = LINE('',#159542,#159543); -#159542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#159543 = VECTOR('',#159544,1.); -#159544 = DIRECTION('',(0.E+000,1.)); -#159545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159546 = ORIENTED_EDGE('',*,*,#159547,.T.); -#159547 = EDGE_CURVE('',#159521,#159410,#159548,.T.); -#159548 = SURFACE_CURVE('',#159549,(#159554,#159560),.PCURVE_S1.); -#159549 = CIRCLE('',#159550,9.999999999999E-002); -#159550 = AXIS2_PLACEMENT_3D('',#159551,#159552,#159553); -#159551 = CARTESIAN_POINT('',(-0.425,0.340821720102,-2.608196956182)); -#159552 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159553 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); -#159554 = PCURVE('',#159453,#159555); -#159555 = DEFINITIONAL_REPRESENTATION('',(#159556),#159559); -#159556 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159557,#159558), +#161923 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#161924 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161926 = PCURVE('',#161927,#161932); +#161927 = PLANE('',#161928); +#161928 = AXIS2_PLACEMENT_3D('',#161929,#161930,#161931); +#161929 = CARTESIAN_POINT('',(-0.635,0.240958766627,-2.602963360557)); +#161930 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); +#161931 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#161932 = DEFINITIONAL_REPRESENTATION('',(#161933),#161937); +#161933 = LINE('',#161934,#161935); +#161934 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#161935 = VECTOR('',#161936,1.); +#161936 = DIRECTION('',(0.E+000,1.)); +#161937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161938 = ORIENTED_EDGE('',*,*,#161939,.T.); +#161939 = EDGE_CURVE('',#161913,#161802,#161940,.T.); +#161940 = SURFACE_CURVE('',#161941,(#161946,#161952),.PCURVE_S1.); +#161941 = CIRCLE('',#161942,9.999999999999E-002); +#161942 = AXIS2_PLACEMENT_3D('',#161943,#161944,#161945); +#161943 = CARTESIAN_POINT('',(-0.425,0.340821720102,-2.608196956182)); +#161944 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#161945 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); +#161946 = PCURVE('',#161845,#161947); +#161947 = DEFINITIONAL_REPRESENTATION('',(#161948),#161951); +#161948 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161949,#161950), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#159557 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159558 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#161949 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#161950 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#161951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159560 = PCURVE('',#159425,#159561); -#159561 = DEFINITIONAL_REPRESENTATION('',(#159562),#159570); -#159562 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159563,#159564,#159565, - #159566,#159567,#159568,#159569),.UNSPECIFIED.,.T.,.F.) +#161952 = PCURVE('',#161817,#161953); +#161953 = DEFINITIONAL_REPRESENTATION('',(#161954),#161962); +#161954 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161955,#161956,#161957, + #161958,#161959,#161960,#161961),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159563 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#159564 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#159565 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#159566 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#159567 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#159568 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#159569 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#159570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159571 = ORIENTED_EDGE('',*,*,#159437,.T.); -#159572 = ADVANCED_FACE('',(#159573),#159535,.T.); -#159573 = FACE_BOUND('',#159574,.T.); -#159574 = EDGE_LOOP('',(#159575,#159576,#159599,#159627)); -#159575 = ORIENTED_EDGE('',*,*,#159520,.T.); -#159576 = ORIENTED_EDGE('',*,*,#159577,.F.); -#159577 = EDGE_CURVE('',#159578,#159521,#159580,.T.); -#159578 = VERTEX_POINT('',#159579); -#159579 = CARTESIAN_POINT('',(-0.425,0.219849248823,-3.005756955187)); -#159580 = SURFACE_CURVE('',#159581,(#159585,#159592),.PCURVE_S1.); -#159581 = LINE('',#159582,#159583); -#159582 = CARTESIAN_POINT('',(-0.425,0.219849248823,-3.005756955187)); -#159583 = VECTOR('',#159584,1.); -#159584 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#159585 = PCURVE('',#159535,#159586); -#159586 = DEFINITIONAL_REPRESENTATION('',(#159587),#159591); -#159587 = LINE('',#159588,#159589); -#159588 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#159589 = VECTOR('',#159590,1.); -#159590 = DIRECTION('',(1.,0.E+000)); -#159591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159592 = PCURVE('',#159425,#159593); -#159593 = DEFINITIONAL_REPRESENTATION('',(#159594),#159598); -#159594 = LINE('',#159595,#159596); -#159595 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#159596 = VECTOR('',#159597,1.); -#159597 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#159598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159599 = ORIENTED_EDGE('',*,*,#159600,.T.); -#159600 = EDGE_CURVE('',#159578,#159601,#159603,.T.); -#159601 = VERTEX_POINT('',#159602); -#159602 = CARTESIAN_POINT('',(-0.845,0.219849248823,-3.005756955187)); -#159603 = SURFACE_CURVE('',#159604,(#159608,#159615),.PCURVE_S1.); -#159604 = LINE('',#159605,#159606); -#159605 = CARTESIAN_POINT('',(-0.635,0.219849248823,-3.005756955187)); -#159606 = VECTOR('',#159607,1.); -#159607 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159608 = PCURVE('',#159535,#159609); -#159609 = DEFINITIONAL_REPRESENTATION('',(#159610),#159614); -#159610 = LINE('',#159611,#159612); -#159611 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#159612 = VECTOR('',#159613,1.); -#159613 = DIRECTION('',(0.E+000,-1.)); -#159614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159615 = PCURVE('',#159616,#159621); -#159616 = PLANE('',#159617); -#159617 = AXIS2_PLACEMENT_3D('',#159618,#159619,#159620); -#159618 = CARTESIAN_POINT('',(-0.635,0.11,-3.)); -#159619 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); -#159620 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#159621 = DEFINITIONAL_REPRESENTATION('',(#159622),#159626); -#159622 = LINE('',#159623,#159624); -#159623 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#159624 = VECTOR('',#159625,1.); -#159625 = DIRECTION('',(0.E+000,-1.)); -#159626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159627 = ORIENTED_EDGE('',*,*,#159628,.F.); -#159628 = EDGE_CURVE('',#159494,#159601,#159629,.T.); -#159629 = SURFACE_CURVE('',#159630,(#159634,#159641),.PCURVE_S1.); -#159630 = LINE('',#159631,#159632); -#159631 = CARTESIAN_POINT('',(-0.845,0.240958766627,-2.602963360557)); -#159632 = VECTOR('',#159633,1.); -#159633 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#159634 = PCURVE('',#159535,#159635); -#159635 = DEFINITIONAL_REPRESENTATION('',(#159636),#159640); -#159636 = LINE('',#159637,#159638); -#159637 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#159638 = VECTOR('',#159639,1.); -#159639 = DIRECTION('',(-1.,0.E+000)); -#159640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159641 = PCURVE('',#159478,#159642); -#159642 = DEFINITIONAL_REPRESENTATION('',(#159643),#159647); -#159643 = LINE('',#159644,#159645); -#159644 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#159645 = VECTOR('',#159646,1.); -#159646 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#159647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159648 = ADVANCED_FACE('',(#159649),#159616,.F.); -#159649 = FACE_BOUND('',#159650,.T.); -#159650 = EDGE_LOOP('',(#159651,#159674,#159675,#159698)); -#159651 = ORIENTED_EDGE('',*,*,#159652,.F.); -#159652 = EDGE_CURVE('',#159601,#159653,#159655,.T.); -#159653 = VERTEX_POINT('',#159654); -#159654 = CARTESIAN_POINT('',(-0.845,1.507511769881E-004,-2.994243044813 +#161955 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#161956 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#161957 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#161958 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#161959 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#161960 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#161961 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#161962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161963 = ORIENTED_EDGE('',*,*,#161829,.T.); +#161964 = ADVANCED_FACE('',(#161965),#161927,.T.); +#161965 = FACE_BOUND('',#161966,.T.); +#161966 = EDGE_LOOP('',(#161967,#161968,#161991,#162019)); +#161967 = ORIENTED_EDGE('',*,*,#161912,.T.); +#161968 = ORIENTED_EDGE('',*,*,#161969,.F.); +#161969 = EDGE_CURVE('',#161970,#161913,#161972,.T.); +#161970 = VERTEX_POINT('',#161971); +#161971 = CARTESIAN_POINT('',(-0.425,0.219849248823,-3.005756955187)); +#161972 = SURFACE_CURVE('',#161973,(#161977,#161984),.PCURVE_S1.); +#161973 = LINE('',#161974,#161975); +#161974 = CARTESIAN_POINT('',(-0.425,0.219849248823,-3.005756955187)); +#161975 = VECTOR('',#161976,1.); +#161976 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#161977 = PCURVE('',#161927,#161978); +#161978 = DEFINITIONAL_REPRESENTATION('',(#161979),#161983); +#161979 = LINE('',#161980,#161981); +#161980 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#161981 = VECTOR('',#161982,1.); +#161982 = DIRECTION('',(1.,0.E+000)); +#161983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161984 = PCURVE('',#161817,#161985); +#161985 = DEFINITIONAL_REPRESENTATION('',(#161986),#161990); +#161986 = LINE('',#161987,#161988); +#161987 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#161988 = VECTOR('',#161989,1.); +#161989 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#161990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#161991 = ORIENTED_EDGE('',*,*,#161992,.T.); +#161992 = EDGE_CURVE('',#161970,#161993,#161995,.T.); +#161993 = VERTEX_POINT('',#161994); +#161994 = CARTESIAN_POINT('',(-0.845,0.219849248823,-3.005756955187)); +#161995 = SURFACE_CURVE('',#161996,(#162000,#162007),.PCURVE_S1.); +#161996 = LINE('',#161997,#161998); +#161997 = CARTESIAN_POINT('',(-0.635,0.219849248823,-3.005756955187)); +#161998 = VECTOR('',#161999,1.); +#161999 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162000 = PCURVE('',#161927,#162001); +#162001 = DEFINITIONAL_REPRESENTATION('',(#162002),#162006); +#162002 = LINE('',#162003,#162004); +#162003 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#162004 = VECTOR('',#162005,1.); +#162005 = DIRECTION('',(0.E+000,-1.)); +#162006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162007 = PCURVE('',#162008,#162013); +#162008 = PLANE('',#162009); +#162009 = AXIS2_PLACEMENT_3D('',#162010,#162011,#162012); +#162010 = CARTESIAN_POINT('',(-0.635,0.11,-3.)); +#162011 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); +#162012 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#162013 = DEFINITIONAL_REPRESENTATION('',(#162014),#162018); +#162014 = LINE('',#162015,#162016); +#162015 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#162016 = VECTOR('',#162017,1.); +#162017 = DIRECTION('',(0.E+000,-1.)); +#162018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162019 = ORIENTED_EDGE('',*,*,#162020,.F.); +#162020 = EDGE_CURVE('',#161886,#161993,#162021,.T.); +#162021 = SURFACE_CURVE('',#162022,(#162026,#162033),.PCURVE_S1.); +#162022 = LINE('',#162023,#162024); +#162023 = CARTESIAN_POINT('',(-0.845,0.240958766627,-2.602963360557)); +#162024 = VECTOR('',#162025,1.); +#162025 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162026 = PCURVE('',#161927,#162027); +#162027 = DEFINITIONAL_REPRESENTATION('',(#162028),#162032); +#162028 = LINE('',#162029,#162030); +#162029 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#162030 = VECTOR('',#162031,1.); +#162031 = DIRECTION('',(-1.,0.E+000)); +#162032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162033 = PCURVE('',#161870,#162034); +#162034 = DEFINITIONAL_REPRESENTATION('',(#162035),#162039); +#162035 = LINE('',#162036,#162037); +#162036 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#162037 = VECTOR('',#162038,1.); +#162038 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#162039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162040 = ADVANCED_FACE('',(#162041),#162008,.F.); +#162041 = FACE_BOUND('',#162042,.T.); +#162042 = EDGE_LOOP('',(#162043,#162066,#162067,#162090)); +#162043 = ORIENTED_EDGE('',*,*,#162044,.F.); +#162044 = EDGE_CURVE('',#161993,#162045,#162047,.T.); +#162045 = VERTEX_POINT('',#162046); +#162046 = CARTESIAN_POINT('',(-0.845,1.507511769881E-004,-2.994243044813 )); -#159655 = SURFACE_CURVE('',#159656,(#159660,#159667),.PCURVE_S1.); -#159656 = LINE('',#159657,#159658); -#159657 = CARTESIAN_POINT('',(-0.845,0.219849248823,-3.005756955187)); -#159658 = VECTOR('',#159659,1.); -#159659 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#159660 = PCURVE('',#159616,#159661); -#159661 = DEFINITIONAL_REPRESENTATION('',(#159662),#159666); -#159662 = LINE('',#159663,#159664); -#159663 = CARTESIAN_POINT('',(-0.11,-0.21)); -#159664 = VECTOR('',#159665,1.); -#159665 = DIRECTION('',(1.,0.E+000)); -#159666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159667 = PCURVE('',#159478,#159668); -#159668 = DEFINITIONAL_REPRESENTATION('',(#159669),#159673); -#159669 = LINE('',#159670,#159671); -#159670 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#159671 = VECTOR('',#159672,1.); -#159672 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#159673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159674 = ORIENTED_EDGE('',*,*,#159600,.F.); -#159675 = ORIENTED_EDGE('',*,*,#159676,.F.); -#159676 = EDGE_CURVE('',#159677,#159578,#159679,.T.); -#159677 = VERTEX_POINT('',#159678); -#159678 = CARTESIAN_POINT('',(-0.425,1.507511769881E-004,-2.994243044813 +#162047 = SURFACE_CURVE('',#162048,(#162052,#162059),.PCURVE_S1.); +#162048 = LINE('',#162049,#162050); +#162049 = CARTESIAN_POINT('',(-0.845,0.219849248823,-3.005756955187)); +#162050 = VECTOR('',#162051,1.); +#162051 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#162052 = PCURVE('',#162008,#162053); +#162053 = DEFINITIONAL_REPRESENTATION('',(#162054),#162058); +#162054 = LINE('',#162055,#162056); +#162055 = CARTESIAN_POINT('',(-0.11,-0.21)); +#162056 = VECTOR('',#162057,1.); +#162057 = DIRECTION('',(1.,0.E+000)); +#162058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162059 = PCURVE('',#161870,#162060); +#162060 = DEFINITIONAL_REPRESENTATION('',(#162061),#162065); +#162061 = LINE('',#162062,#162063); +#162062 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#162063 = VECTOR('',#162064,1.); +#162064 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#162065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162066 = ORIENTED_EDGE('',*,*,#161992,.F.); +#162067 = ORIENTED_EDGE('',*,*,#162068,.F.); +#162068 = EDGE_CURVE('',#162069,#161970,#162071,.T.); +#162069 = VERTEX_POINT('',#162070); +#162070 = CARTESIAN_POINT('',(-0.425,1.507511769881E-004,-2.994243044813 )); -#159679 = SURFACE_CURVE('',#159680,(#159684,#159691),.PCURVE_S1.); -#159680 = LINE('',#159681,#159682); -#159681 = CARTESIAN_POINT('',(-0.425,1.507511769892E-004,-2.994243044813 +#162071 = SURFACE_CURVE('',#162072,(#162076,#162083),.PCURVE_S1.); +#162072 = LINE('',#162073,#162074); +#162073 = CARTESIAN_POINT('',(-0.425,1.507511769892E-004,-2.994243044813 )); -#159682 = VECTOR('',#159683,1.); -#159683 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); -#159684 = PCURVE('',#159616,#159685); -#159685 = DEFINITIONAL_REPRESENTATION('',(#159686),#159690); -#159686 = LINE('',#159687,#159688); -#159687 = CARTESIAN_POINT('',(0.11,0.21)); -#159688 = VECTOR('',#159689,1.); -#159689 = DIRECTION('',(-1.,0.E+000)); -#159690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159691 = PCURVE('',#159425,#159692); -#159692 = DEFINITIONAL_REPRESENTATION('',(#159693),#159697); -#159693 = LINE('',#159694,#159695); -#159694 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#159695 = VECTOR('',#159696,1.); -#159696 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#159697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159698 = ORIENTED_EDGE('',*,*,#159699,.F.); -#159699 = EDGE_CURVE('',#159653,#159677,#159700,.T.); -#159700 = SURFACE_CURVE('',#159701,(#159705,#159712),.PCURVE_S1.); -#159701 = LINE('',#159702,#159703); -#159702 = CARTESIAN_POINT('',(-0.635,1.507511769861E-004,-2.994243044813 +#162074 = VECTOR('',#162075,1.); +#162075 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); +#162076 = PCURVE('',#162008,#162077); +#162077 = DEFINITIONAL_REPRESENTATION('',(#162078),#162082); +#162078 = LINE('',#162079,#162080); +#162079 = CARTESIAN_POINT('',(0.11,0.21)); +#162080 = VECTOR('',#162081,1.); +#162081 = DIRECTION('',(-1.,0.E+000)); +#162082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162083 = PCURVE('',#161817,#162084); +#162084 = DEFINITIONAL_REPRESENTATION('',(#162085),#162089); +#162085 = LINE('',#162086,#162087); +#162086 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#162087 = VECTOR('',#162088,1.); +#162088 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#162089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162090 = ORIENTED_EDGE('',*,*,#162091,.F.); +#162091 = EDGE_CURVE('',#162045,#162069,#162092,.T.); +#162092 = SURFACE_CURVE('',#162093,(#162097,#162104),.PCURVE_S1.); +#162093 = LINE('',#162094,#162095); +#162094 = CARTESIAN_POINT('',(-0.635,1.507511769861E-004,-2.994243044813 )); -#159703 = VECTOR('',#159704,1.); -#159704 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159705 = PCURVE('',#159616,#159706); -#159706 = DEFINITIONAL_REPRESENTATION('',(#159707),#159711); -#159707 = LINE('',#159708,#159709); -#159708 = CARTESIAN_POINT('',(0.11,0.E+000)); -#159709 = VECTOR('',#159710,1.); -#159710 = DIRECTION('',(0.E+000,1.)); -#159711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159712 = PCURVE('',#159713,#159718); -#159713 = PLANE('',#159714); -#159714 = AXIS2_PLACEMENT_3D('',#159715,#159716,#159717); -#159715 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,-2.591449450184 +#162095 = VECTOR('',#162096,1.); +#162096 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162097 = PCURVE('',#162008,#162098); +#162098 = DEFINITIONAL_REPRESENTATION('',(#162099),#162103); +#162099 = LINE('',#162100,#162101); +#162100 = CARTESIAN_POINT('',(0.11,0.E+000)); +#162101 = VECTOR('',#162102,1.); +#162102 = DIRECTION('',(0.E+000,1.)); +#162103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162104 = PCURVE('',#162105,#162110); +#162105 = PLANE('',#162106); +#162106 = AXIS2_PLACEMENT_3D('',#162107,#162108,#162109); +#162107 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,-2.591449450184 )); -#159716 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); -#159717 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#159718 = DEFINITIONAL_REPRESENTATION('',(#159719),#159723); -#159719 = LINE('',#159720,#159721); -#159720 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#159721 = VECTOR('',#159722,1.); -#159722 = DIRECTION('',(0.E+000,1.)); -#159723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159724 = ADVANCED_FACE('',(#159725),#159713,.T.); -#159725 = FACE_BOUND('',#159726,.T.); -#159726 = EDGE_LOOP('',(#159727,#159756,#159777,#159778)); -#159727 = ORIENTED_EDGE('',*,*,#159728,.F.); -#159728 = EDGE_CURVE('',#159729,#159731,#159733,.T.); -#159729 = VERTEX_POINT('',#159730); -#159730 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,-2.591449450184 +#162108 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); +#162109 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162110 = DEFINITIONAL_REPRESENTATION('',(#162111),#162115); +#162111 = LINE('',#162112,#162113); +#162112 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#162113 = VECTOR('',#162114,1.); +#162114 = DIRECTION('',(0.E+000,1.)); +#162115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162116 = ADVANCED_FACE('',(#162117),#162105,.T.); +#162117 = FACE_BOUND('',#162118,.T.); +#162118 = EDGE_LOOP('',(#162119,#162148,#162169,#162170)); +#162119 = ORIENTED_EDGE('',*,*,#162120,.F.); +#162120 = EDGE_CURVE('',#162121,#162123,#162125,.T.); +#162121 = VERTEX_POINT('',#162122); +#162122 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,-2.591449450184 )); -#159731 = VERTEX_POINT('',#159732); -#159732 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,-2.591449450184 +#162123 = VERTEX_POINT('',#162124); +#162124 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,-2.591449450184 )); -#159733 = SURFACE_CURVE('',#159734,(#159738,#159745),.PCURVE_S1.); -#159734 = LINE('',#159735,#159736); -#159735 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,-2.591449450184 +#162125 = SURFACE_CURVE('',#162126,(#162130,#162137),.PCURVE_S1.); +#162126 = LINE('',#162127,#162128); +#162127 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,-2.591449450184 )); -#159736 = VECTOR('',#159737,1.); -#159737 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159738 = PCURVE('',#159713,#159739); -#159739 = DEFINITIONAL_REPRESENTATION('',(#159740),#159744); -#159740 = LINE('',#159741,#159742); -#159741 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); -#159742 = VECTOR('',#159743,1.); -#159743 = DIRECTION('',(0.E+000,1.)); -#159744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159745 = PCURVE('',#159746,#159751); -#159746 = CYLINDRICAL_SURFACE('',#159747,0.32); -#159747 = AXIS2_PLACEMENT_3D('',#159748,#159749,#159750); -#159748 = CARTESIAN_POINT('',(-0.635,0.340821720102,-2.608196956182)); -#159749 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159750 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159751 = DEFINITIONAL_REPRESENTATION('',(#159752),#159755); -#159752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159753,#159754), +#162128 = VECTOR('',#162129,1.); +#162129 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162130 = PCURVE('',#162105,#162131); +#162131 = DEFINITIONAL_REPRESENTATION('',(#162132),#162136); +#162132 = LINE('',#162133,#162134); +#162133 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); +#162134 = VECTOR('',#162135,1.); +#162135 = DIRECTION('',(0.E+000,1.)); +#162136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162137 = PCURVE('',#162138,#162143); +#162138 = CYLINDRICAL_SURFACE('',#162139,0.32); +#162139 = AXIS2_PLACEMENT_3D('',#162140,#162141,#162142); +#162140 = CARTESIAN_POINT('',(-0.635,0.340821720102,-2.608196956182)); +#162141 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162142 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162143 = DEFINITIONAL_REPRESENTATION('',(#162144),#162147); +#162144 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162145,#162146), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159753 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159754 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162145 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162146 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159756 = ORIENTED_EDGE('',*,*,#159757,.F.); -#159757 = EDGE_CURVE('',#159653,#159729,#159758,.T.); -#159758 = SURFACE_CURVE('',#159759,(#159763,#159770),.PCURVE_S1.); -#159759 = LINE('',#159760,#159761); -#159760 = CARTESIAN_POINT('',(-0.845,1.507511769892E-004,-2.994243044813 +#162148 = ORIENTED_EDGE('',*,*,#162149,.F.); +#162149 = EDGE_CURVE('',#162045,#162121,#162150,.T.); +#162150 = SURFACE_CURVE('',#162151,(#162155,#162162),.PCURVE_S1.); +#162151 = LINE('',#162152,#162153); +#162152 = CARTESIAN_POINT('',(-0.845,1.507511769892E-004,-2.994243044813 )); -#159761 = VECTOR('',#159762,1.); -#159762 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#159763 = PCURVE('',#159713,#159764); -#159764 = DEFINITIONAL_REPRESENTATION('',(#159765),#159769); -#159765 = LINE('',#159766,#159767); -#159766 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#159767 = VECTOR('',#159768,1.); -#159768 = DIRECTION('',(-1.,0.E+000)); -#159769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159770 = PCURVE('',#159478,#159771); -#159771 = DEFINITIONAL_REPRESENTATION('',(#159772),#159776); -#159772 = LINE('',#159773,#159774); -#159773 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#159774 = VECTOR('',#159775,1.); -#159775 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#159776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159777 = ORIENTED_EDGE('',*,*,#159699,.T.); -#159778 = ORIENTED_EDGE('',*,*,#159779,.F.); -#159779 = EDGE_CURVE('',#159731,#159677,#159780,.T.); -#159780 = SURFACE_CURVE('',#159781,(#159785,#159792),.PCURVE_S1.); -#159781 = LINE('',#159782,#159783); -#159782 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,-2.591449450184 +#162153 = VECTOR('',#162154,1.); +#162154 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#162155 = PCURVE('',#162105,#162156); +#162156 = DEFINITIONAL_REPRESENTATION('',(#162157),#162161); +#162157 = LINE('',#162158,#162159); +#162158 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#162159 = VECTOR('',#162160,1.); +#162160 = DIRECTION('',(-1.,0.E+000)); +#162161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162162 = PCURVE('',#161870,#162163); +#162163 = DEFINITIONAL_REPRESENTATION('',(#162164),#162168); +#162164 = LINE('',#162165,#162166); +#162165 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#162166 = VECTOR('',#162167,1.); +#162167 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#162168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162169 = ORIENTED_EDGE('',*,*,#162091,.T.); +#162170 = ORIENTED_EDGE('',*,*,#162171,.F.); +#162171 = EDGE_CURVE('',#162123,#162069,#162172,.T.); +#162172 = SURFACE_CURVE('',#162173,(#162177,#162184),.PCURVE_S1.); +#162173 = LINE('',#162174,#162175); +#162174 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,-2.591449450184 )); -#159783 = VECTOR('',#159784,1.); -#159784 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#159785 = PCURVE('',#159713,#159786); -#159786 = DEFINITIONAL_REPRESENTATION('',(#159787),#159791); -#159787 = LINE('',#159788,#159789); -#159788 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); -#159789 = VECTOR('',#159790,1.); -#159790 = DIRECTION('',(1.,0.E+000)); -#159791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159792 = PCURVE('',#159425,#159793); -#159793 = DEFINITIONAL_REPRESENTATION('',(#159794),#159798); -#159794 = LINE('',#159795,#159796); -#159795 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#159796 = VECTOR('',#159797,1.); -#159797 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#159798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159799 = ADVANCED_FACE('',(#159800),#159746,.T.); -#159800 = FACE_BOUND('',#159801,.T.); -#159801 = EDGE_LOOP('',(#159802,#159831,#159852,#159853)); -#159802 = ORIENTED_EDGE('',*,*,#159803,.F.); -#159803 = EDGE_CURVE('',#159804,#159806,#159808,.T.); -#159804 = VERTEX_POINT('',#159805); -#159805 = CARTESIAN_POINT('',(-0.845,0.298978581017,-2.290944451524)); -#159806 = VERTEX_POINT('',#159807); -#159807 = CARTESIAN_POINT('',(-0.425,0.298978581017,-2.290944451524)); -#159808 = SURFACE_CURVE('',#159809,(#159813,#159819),.PCURVE_S1.); -#159809 = LINE('',#159810,#159811); -#159810 = CARTESIAN_POINT('',(-0.635,0.298978581017,-2.290944451524)); -#159811 = VECTOR('',#159812,1.); -#159812 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159813 = PCURVE('',#159746,#159814); -#159814 = DEFINITIONAL_REPRESENTATION('',(#159815),#159818); -#159815 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159816,#159817), +#162175 = VECTOR('',#162176,1.); +#162176 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162177 = PCURVE('',#162105,#162178); +#162178 = DEFINITIONAL_REPRESENTATION('',(#162179),#162183); +#162179 = LINE('',#162180,#162181); +#162180 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); +#162181 = VECTOR('',#162182,1.); +#162182 = DIRECTION('',(1.,0.E+000)); +#162183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162184 = PCURVE('',#161817,#162185); +#162185 = DEFINITIONAL_REPRESENTATION('',(#162186),#162190); +#162186 = LINE('',#162187,#162188); +#162187 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#162188 = VECTOR('',#162189,1.); +#162189 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#162190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162191 = ADVANCED_FACE('',(#162192),#162138,.T.); +#162192 = FACE_BOUND('',#162193,.T.); +#162193 = EDGE_LOOP('',(#162194,#162223,#162244,#162245)); +#162194 = ORIENTED_EDGE('',*,*,#162195,.F.); +#162195 = EDGE_CURVE('',#162196,#162198,#162200,.T.); +#162196 = VERTEX_POINT('',#162197); +#162197 = CARTESIAN_POINT('',(-0.845,0.298978581017,-2.290944451524)); +#162198 = VERTEX_POINT('',#162199); +#162199 = CARTESIAN_POINT('',(-0.425,0.298978581017,-2.290944451524)); +#162200 = SURFACE_CURVE('',#162201,(#162205,#162211),.PCURVE_S1.); +#162201 = LINE('',#162202,#162203); +#162202 = CARTESIAN_POINT('',(-0.635,0.298978581017,-2.290944451524)); +#162203 = VECTOR('',#162204,1.); +#162204 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162205 = PCURVE('',#162138,#162206); +#162206 = DEFINITIONAL_REPRESENTATION('',(#162207),#162210); +#162207 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162208,#162209), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159816 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159817 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159819 = PCURVE('',#159820,#159825); -#159820 = PLANE('',#159821); -#159821 = AXIS2_PLACEMENT_3D('',#159822,#159823,#159824); -#159822 = CARTESIAN_POINT('',(-0.635,0.678075980964,-2.240944451524)); -#159823 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); -#159824 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#159825 = DEFINITIONAL_REPRESENTATION('',(#159826),#159830); -#159826 = LINE('',#159827,#159828); -#159827 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#159828 = VECTOR('',#159829,1.); -#159829 = DIRECTION('',(0.E+000,1.)); -#159830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159831 = ORIENTED_EDGE('',*,*,#159832,.F.); -#159832 = EDGE_CURVE('',#159729,#159804,#159833,.T.); -#159833 = SURFACE_CURVE('',#159834,(#159839,#159845),.PCURVE_S1.); -#159834 = CIRCLE('',#159835,0.32); -#159835 = AXIS2_PLACEMENT_3D('',#159836,#159837,#159838); -#159836 = CARTESIAN_POINT('',(-0.845,0.340821720102,-2.608196956182)); -#159837 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159838 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); -#159839 = PCURVE('',#159746,#159840); -#159840 = DEFINITIONAL_REPRESENTATION('',(#159841),#159844); -#159841 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159842,#159843), +#162208 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162209 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162211 = PCURVE('',#162212,#162217); +#162212 = PLANE('',#162213); +#162213 = AXIS2_PLACEMENT_3D('',#162214,#162215,#162216); +#162214 = CARTESIAN_POINT('',(-0.635,0.678075980964,-2.240944451524)); +#162215 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); +#162216 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#162217 = DEFINITIONAL_REPRESENTATION('',(#162218),#162222); +#162218 = LINE('',#162219,#162220); +#162219 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#162220 = VECTOR('',#162221,1.); +#162221 = DIRECTION('',(0.E+000,1.)); +#162222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162223 = ORIENTED_EDGE('',*,*,#162224,.F.); +#162224 = EDGE_CURVE('',#162121,#162196,#162225,.T.); +#162225 = SURFACE_CURVE('',#162226,(#162231,#162237),.PCURVE_S1.); +#162226 = CIRCLE('',#162227,0.32); +#162227 = AXIS2_PLACEMENT_3D('',#162228,#162229,#162230); +#162228 = CARTESIAN_POINT('',(-0.845,0.340821720102,-2.608196956182)); +#162229 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162230 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); +#162231 = PCURVE('',#162138,#162232); +#162232 = DEFINITIONAL_REPRESENTATION('',(#162233),#162236); +#162233 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162234,#162235), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#159842 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#159843 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#159844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159845 = PCURVE('',#159478,#159846); -#159846 = DEFINITIONAL_REPRESENTATION('',(#159847),#159851); -#159847 = CIRCLE('',#159848,0.32); -#159848 = AXIS2_PLACEMENT_2D('',#159849,#159850); -#159849 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#159850 = DIRECTION('',(-1.,1.694065894509E-015)); -#159851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159852 = ORIENTED_EDGE('',*,*,#159728,.T.); -#159853 = ORIENTED_EDGE('',*,*,#159854,.F.); -#159854 = EDGE_CURVE('',#159806,#159731,#159855,.T.); -#159855 = SURFACE_CURVE('',#159856,(#159861,#159867),.PCURVE_S1.); -#159856 = CIRCLE('',#159857,0.32); -#159857 = AXIS2_PLACEMENT_3D('',#159858,#159859,#159860); -#159858 = CARTESIAN_POINT('',(-0.425,0.340821720102,-2.608196956182)); -#159859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159860 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#159861 = PCURVE('',#159746,#159862); -#159862 = DEFINITIONAL_REPRESENTATION('',(#159863),#159866); -#159863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159864,#159865), +#162234 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162235 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162236 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162237 = PCURVE('',#161870,#162238); +#162238 = DEFINITIONAL_REPRESENTATION('',(#162239),#162243); +#162239 = CIRCLE('',#162240,0.32); +#162240 = AXIS2_PLACEMENT_2D('',#162241,#162242); +#162241 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#162242 = DIRECTION('',(-1.,1.694065894509E-015)); +#162243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162244 = ORIENTED_EDGE('',*,*,#162120,.T.); +#162245 = ORIENTED_EDGE('',*,*,#162246,.F.); +#162246 = EDGE_CURVE('',#162198,#162123,#162247,.T.); +#162247 = SURFACE_CURVE('',#162248,(#162253,#162259),.PCURVE_S1.); +#162248 = CIRCLE('',#162249,0.32); +#162249 = AXIS2_PLACEMENT_3D('',#162250,#162251,#162252); +#162250 = CARTESIAN_POINT('',(-0.425,0.340821720102,-2.608196956182)); +#162251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162252 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162253 = PCURVE('',#162138,#162254); +#162254 = DEFINITIONAL_REPRESENTATION('',(#162255),#162258); +#162255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162256,#162257), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#159864 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#159865 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#159866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159867 = PCURVE('',#159425,#159868); -#159868 = DEFINITIONAL_REPRESENTATION('',(#159869),#159873); -#159869 = CIRCLE('',#159870,0.32); -#159870 = AXIS2_PLACEMENT_2D('',#159871,#159872); -#159871 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#159872 = DIRECTION('',(1.,0.E+000)); -#159873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159874 = ADVANCED_FACE('',(#159875),#159820,.T.); -#159875 = FACE_BOUND('',#159876,.T.); -#159876 = EDGE_LOOP('',(#159877,#159906,#159927,#159928)); -#159877 = ORIENTED_EDGE('',*,*,#159878,.T.); -#159878 = EDGE_CURVE('',#159879,#159881,#159883,.T.); -#159879 = VERTEX_POINT('',#159880); -#159880 = CARTESIAN_POINT('',(-0.425,0.678075980964,-2.240944451524)); -#159881 = VERTEX_POINT('',#159882); -#159882 = CARTESIAN_POINT('',(-0.845,0.678075980964,-2.240944451524)); -#159883 = SURFACE_CURVE('',#159884,(#159888,#159895),.PCURVE_S1.); -#159884 = LINE('',#159885,#159886); -#159885 = CARTESIAN_POINT('',(-0.635,0.678075980964,-2.240944451524)); -#159886 = VECTOR('',#159887,1.); -#159887 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159888 = PCURVE('',#159820,#159889); -#159889 = DEFINITIONAL_REPRESENTATION('',(#159890),#159894); -#159890 = LINE('',#159891,#159892); -#159891 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#159892 = VECTOR('',#159893,1.); -#159893 = DIRECTION('',(0.E+000,-1.)); -#159894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159895 = PCURVE('',#159896,#159901); -#159896 = CYLINDRICAL_SURFACE('',#159897,1.E-001); -#159897 = AXIS2_PLACEMENT_3D('',#159898,#159899,#159900); -#159898 = CARTESIAN_POINT('',(-0.635,0.665,-2.141803043818)); -#159899 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159900 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159901 = DEFINITIONAL_REPRESENTATION('',(#159902),#159905); -#159902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159903,#159904), +#162256 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162257 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162259 = PCURVE('',#161817,#162260); +#162260 = DEFINITIONAL_REPRESENTATION('',(#162261),#162265); +#162261 = CIRCLE('',#162262,0.32); +#162262 = AXIS2_PLACEMENT_2D('',#162263,#162264); +#162263 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#162264 = DIRECTION('',(1.,0.E+000)); +#162265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162266 = ADVANCED_FACE('',(#162267),#162212,.T.); +#162267 = FACE_BOUND('',#162268,.T.); +#162268 = EDGE_LOOP('',(#162269,#162298,#162319,#162320)); +#162269 = ORIENTED_EDGE('',*,*,#162270,.T.); +#162270 = EDGE_CURVE('',#162271,#162273,#162275,.T.); +#162271 = VERTEX_POINT('',#162272); +#162272 = CARTESIAN_POINT('',(-0.425,0.678075980964,-2.240944451524)); +#162273 = VERTEX_POINT('',#162274); +#162274 = CARTESIAN_POINT('',(-0.845,0.678075980964,-2.240944451524)); +#162275 = SURFACE_CURVE('',#162276,(#162280,#162287),.PCURVE_S1.); +#162276 = LINE('',#162277,#162278); +#162277 = CARTESIAN_POINT('',(-0.635,0.678075980964,-2.240944451524)); +#162278 = VECTOR('',#162279,1.); +#162279 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162280 = PCURVE('',#162212,#162281); +#162281 = DEFINITIONAL_REPRESENTATION('',(#162282),#162286); +#162282 = LINE('',#162283,#162284); +#162283 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#162284 = VECTOR('',#162285,1.); +#162285 = DIRECTION('',(0.E+000,-1.)); +#162286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162287 = PCURVE('',#162288,#162293); +#162288 = CYLINDRICAL_SURFACE('',#162289,1.E-001); +#162289 = AXIS2_PLACEMENT_3D('',#162290,#162291,#162292); +#162290 = CARTESIAN_POINT('',(-0.635,0.665,-2.141803043818)); +#162291 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162292 = DIRECTION('',(0.E+000,0.E+000,1.)); +#162293 = DEFINITIONAL_REPRESENTATION('',(#162294),#162297); +#162294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162295,#162296), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#159903 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#159904 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#159905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159906 = ORIENTED_EDGE('',*,*,#159907,.F.); -#159907 = EDGE_CURVE('',#159804,#159881,#159908,.T.); -#159908 = SURFACE_CURVE('',#159909,(#159913,#159920),.PCURVE_S1.); -#159909 = LINE('',#159910,#159911); -#159910 = CARTESIAN_POINT('',(-0.845,0.298978581017,-2.290944451524)); -#159911 = VECTOR('',#159912,1.); -#159912 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#159913 = PCURVE('',#159820,#159914); -#159914 = DEFINITIONAL_REPRESENTATION('',(#159915),#159919); -#159915 = LINE('',#159916,#159917); -#159916 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#159917 = VECTOR('',#159918,1.); -#159918 = DIRECTION('',(-1.,0.E+000)); -#159919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159920 = PCURVE('',#159478,#159921); -#159921 = DEFINITIONAL_REPRESENTATION('',(#159922),#159926); -#159922 = LINE('',#159923,#159924); -#159923 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#159924 = VECTOR('',#159925,1.); -#159925 = DIRECTION('',(0.130759809642,0.991414077055)); -#159926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159927 = ORIENTED_EDGE('',*,*,#159803,.T.); -#159928 = ORIENTED_EDGE('',*,*,#159929,.F.); -#159929 = EDGE_CURVE('',#159879,#159806,#159930,.T.); -#159930 = SURFACE_CURVE('',#159931,(#159935,#159942),.PCURVE_S1.); -#159931 = LINE('',#159932,#159933); -#159932 = CARTESIAN_POINT('',(-0.425,0.678075980964,-2.240944451524)); -#159933 = VECTOR('',#159934,1.); -#159934 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#159935 = PCURVE('',#159820,#159936); -#159936 = DEFINITIONAL_REPRESENTATION('',(#159937),#159941); -#159937 = LINE('',#159938,#159939); -#159938 = CARTESIAN_POINT('',(0.E+000,0.21)); -#159939 = VECTOR('',#159940,1.); -#159940 = DIRECTION('',(1.,0.E+000)); -#159941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159942 = PCURVE('',#159425,#159943); -#159943 = DEFINITIONAL_REPRESENTATION('',(#159944),#159948); -#159944 = LINE('',#159945,#159946); -#159945 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#159946 = VECTOR('',#159947,1.); -#159947 = DIRECTION('',(0.130759809642,-0.991414077055)); -#159948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159949 = ADVANCED_FACE('',(#159950),#159896,.F.); -#159950 = FACE_BOUND('',#159951,.F.); -#159951 = EDGE_LOOP('',(#159952,#159979,#159980,#160007)); -#159952 = ORIENTED_EDGE('',*,*,#159953,.T.); -#159953 = EDGE_CURVE('',#159954,#159879,#159956,.T.); -#159954 = VERTEX_POINT('',#159955); -#159955 = CARTESIAN_POINT('',(-0.425,0.765,-2.141803043818)); -#159956 = SURFACE_CURVE('',#159957,(#159962,#159968),.PCURVE_S1.); -#159957 = CIRCLE('',#159958,1.E-001); -#159958 = AXIS2_PLACEMENT_3D('',#159959,#159960,#159961); -#159959 = CARTESIAN_POINT('',(-0.425,0.665,-2.141803043818)); -#159960 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#159961 = DIRECTION('',(0.E+000,0.E+000,1.)); -#159962 = PCURVE('',#159896,#159963); -#159963 = DEFINITIONAL_REPRESENTATION('',(#159964),#159967); -#159964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159965,#159966), +#162295 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#162296 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#162297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162298 = ORIENTED_EDGE('',*,*,#162299,.F.); +#162299 = EDGE_CURVE('',#162196,#162273,#162300,.T.); +#162300 = SURFACE_CURVE('',#162301,(#162305,#162312),.PCURVE_S1.); +#162301 = LINE('',#162302,#162303); +#162302 = CARTESIAN_POINT('',(-0.845,0.298978581017,-2.290944451524)); +#162303 = VECTOR('',#162304,1.); +#162304 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#162305 = PCURVE('',#162212,#162306); +#162306 = DEFINITIONAL_REPRESENTATION('',(#162307),#162311); +#162307 = LINE('',#162308,#162309); +#162308 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#162309 = VECTOR('',#162310,1.); +#162310 = DIRECTION('',(-1.,0.E+000)); +#162311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162312 = PCURVE('',#161870,#162313); +#162313 = DEFINITIONAL_REPRESENTATION('',(#162314),#162318); +#162314 = LINE('',#162315,#162316); +#162315 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#162316 = VECTOR('',#162317,1.); +#162317 = DIRECTION('',(0.130759809642,0.991414077055)); +#162318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162319 = ORIENTED_EDGE('',*,*,#162195,.T.); +#162320 = ORIENTED_EDGE('',*,*,#162321,.F.); +#162321 = EDGE_CURVE('',#162271,#162198,#162322,.T.); +#162322 = SURFACE_CURVE('',#162323,(#162327,#162334),.PCURVE_S1.); +#162323 = LINE('',#162324,#162325); +#162324 = CARTESIAN_POINT('',(-0.425,0.678075980964,-2.240944451524)); +#162325 = VECTOR('',#162326,1.); +#162326 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#162327 = PCURVE('',#162212,#162328); +#162328 = DEFINITIONAL_REPRESENTATION('',(#162329),#162333); +#162329 = LINE('',#162330,#162331); +#162330 = CARTESIAN_POINT('',(0.E+000,0.21)); +#162331 = VECTOR('',#162332,1.); +#162332 = DIRECTION('',(1.,0.E+000)); +#162333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162334 = PCURVE('',#161817,#162335); +#162335 = DEFINITIONAL_REPRESENTATION('',(#162336),#162340); +#162336 = LINE('',#162337,#162338); +#162337 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#162338 = VECTOR('',#162339,1.); +#162339 = DIRECTION('',(0.130759809642,-0.991414077055)); +#162340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162341 = ADVANCED_FACE('',(#162342),#162288,.F.); +#162342 = FACE_BOUND('',#162343,.F.); +#162343 = EDGE_LOOP('',(#162344,#162371,#162372,#162399)); +#162344 = ORIENTED_EDGE('',*,*,#162345,.T.); +#162345 = EDGE_CURVE('',#162346,#162271,#162348,.T.); +#162346 = VERTEX_POINT('',#162347); +#162347 = CARTESIAN_POINT('',(-0.425,0.765,-2.141803043818)); +#162348 = SURFACE_CURVE('',#162349,(#162354,#162360),.PCURVE_S1.); +#162349 = CIRCLE('',#162350,1.E-001); +#162350 = AXIS2_PLACEMENT_3D('',#162351,#162352,#162353); +#162351 = CARTESIAN_POINT('',(-0.425,0.665,-2.141803043818)); +#162352 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162353 = DIRECTION('',(0.E+000,0.E+000,1.)); +#162354 = PCURVE('',#162288,#162355); +#162355 = DEFINITIONAL_REPRESENTATION('',(#162356),#162359); +#162356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162357,#162358), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#159965 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#159966 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#159967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162357 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#162358 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#162359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159968 = PCURVE('',#159425,#159969); -#159969 = DEFINITIONAL_REPRESENTATION('',(#159970),#159978); -#159970 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159971,#159972,#159973, - #159974,#159975,#159976,#159977),.UNSPECIFIED.,.T.,.F.) +#162360 = PCURVE('',#161817,#162361); +#162361 = DEFINITIONAL_REPRESENTATION('',(#162362),#162370); +#162362 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162363,#162364,#162365, + #162366,#162367,#162368,#162369),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159971 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#159972 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#159973 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#159974 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#159975 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#159976 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#159977 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#159978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#159979 = ORIENTED_EDGE('',*,*,#159878,.T.); -#159980 = ORIENTED_EDGE('',*,*,#159981,.T.); -#159981 = EDGE_CURVE('',#159881,#159982,#159984,.T.); -#159982 = VERTEX_POINT('',#159983); -#159983 = CARTESIAN_POINT('',(-0.845,0.765,-2.141803043818)); -#159984 = SURFACE_CURVE('',#159985,(#159990,#159996),.PCURVE_S1.); -#159985 = CIRCLE('',#159986,1.E-001); -#159986 = AXIS2_PLACEMENT_3D('',#159987,#159988,#159989); -#159987 = CARTESIAN_POINT('',(-0.845,0.665,-2.141803043818)); -#159988 = DIRECTION('',(1.,0.E+000,0.E+000)); -#159989 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); -#159990 = PCURVE('',#159896,#159991); -#159991 = DEFINITIONAL_REPRESENTATION('',(#159992),#159995); -#159992 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#159993,#159994), +#162363 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#162364 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#162365 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#162366 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#162367 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#162368 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#162369 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#162370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162371 = ORIENTED_EDGE('',*,*,#162270,.T.); +#162372 = ORIENTED_EDGE('',*,*,#162373,.T.); +#162373 = EDGE_CURVE('',#162273,#162374,#162376,.T.); +#162374 = VERTEX_POINT('',#162375); +#162375 = CARTESIAN_POINT('',(-0.845,0.765,-2.141803043818)); +#162376 = SURFACE_CURVE('',#162377,(#162382,#162388),.PCURVE_S1.); +#162377 = CIRCLE('',#162378,1.E-001); +#162378 = AXIS2_PLACEMENT_3D('',#162379,#162380,#162381); +#162379 = CARTESIAN_POINT('',(-0.845,0.665,-2.141803043818)); +#162380 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162381 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); +#162382 = PCURVE('',#162288,#162383); +#162383 = DEFINITIONAL_REPRESENTATION('',(#162384),#162387); +#162384 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162385,#162386), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#159993 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#159994 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#159995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162385 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#162386 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#162387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#159996 = PCURVE('',#159478,#159997); -#159997 = DEFINITIONAL_REPRESENTATION('',(#159998),#160006); -#159998 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#159999,#160000,#160001, - #160002,#160003,#160004,#160005),.UNSPECIFIED.,.T.,.F.) +#162388 = PCURVE('',#161870,#162389); +#162389 = DEFINITIONAL_REPRESENTATION('',(#162390),#162398); +#162390 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162391,#162392,#162393, + #162394,#162395,#162396,#162397),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#159999 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#160000 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#160001 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#160002 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#160003 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#160004 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#160005 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#160006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160007 = ORIENTED_EDGE('',*,*,#160008,.T.); -#160008 = EDGE_CURVE('',#159982,#159954,#160009,.T.); -#160009 = SURFACE_CURVE('',#160010,(#160014,#160020),.PCURVE_S1.); -#160010 = LINE('',#160011,#160012); -#160011 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); -#160012 = VECTOR('',#160013,1.); -#160013 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160014 = PCURVE('',#159896,#160015); -#160015 = DEFINITIONAL_REPRESENTATION('',(#160016),#160019); -#160016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160017,#160018), +#162391 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#162392 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#162393 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#162394 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#162395 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#162396 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#162397 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#162398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162399 = ORIENTED_EDGE('',*,*,#162400,.T.); +#162400 = EDGE_CURVE('',#162374,#162346,#162401,.T.); +#162401 = SURFACE_CURVE('',#162402,(#162406,#162412),.PCURVE_S1.); +#162402 = LINE('',#162403,#162404); +#162403 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); +#162404 = VECTOR('',#162405,1.); +#162405 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162406 = PCURVE('',#162288,#162407); +#162407 = DEFINITIONAL_REPRESENTATION('',(#162408),#162411); +#162408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162409,#162410), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.48,-1.06),.PIECEWISE_BEZIER_KNOTS.); -#160017 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#160018 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#160019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160020 = PCURVE('',#159360,#160021); -#160021 = DEFINITIONAL_REPRESENTATION('',(#160022),#160026); -#160022 = LINE('',#160023,#160024); -#160023 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#160024 = VECTOR('',#160025,1.); -#160025 = DIRECTION('',(0.E+000,1.)); -#160026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160027 = ADVANCED_FACE('',(#160028),#160042,.T.); -#160028 = FACE_BOUND('',#160029,.T.); -#160029 = EDGE_LOOP('',(#160030,#160064,#160092,#160119)); -#160030 = ORIENTED_EDGE('',*,*,#160031,.F.); -#160031 = EDGE_CURVE('',#160032,#160034,#160036,.T.); -#160032 = VERTEX_POINT('',#160033); -#160033 = CARTESIAN_POINT('',(-1.695,0.706843139085,-2.459055548476)); -#160034 = VERTEX_POINT('',#160035); -#160035 = CARTESIAN_POINT('',(-2.115,0.706843139085,-2.459055548476)); -#160036 = SURFACE_CURVE('',#160037,(#160041,#160053),.PCURVE_S1.); -#160037 = LINE('',#160038,#160039); -#160038 = CARTESIAN_POINT('',(-1.905,0.706843139085,-2.459055548476)); -#160039 = VECTOR('',#160040,1.); -#160040 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160041 = PCURVE('',#160042,#160047); -#160042 = PLANE('',#160043); -#160043 = AXIS2_PLACEMENT_3D('',#160044,#160045,#160046); -#160044 = CARTESIAN_POINT('',(-1.905,0.706843139085,-2.459055548476)); -#160045 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); -#160046 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#160047 = DEFINITIONAL_REPRESENTATION('',(#160048),#160052); -#160048 = LINE('',#160049,#160050); -#160049 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#160050 = VECTOR('',#160051,1.); -#160051 = DIRECTION('',(0.E+000,-1.)); -#160052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160053 = PCURVE('',#160054,#160059); -#160054 = CYLINDRICAL_SURFACE('',#160055,0.32); -#160055 = AXIS2_PLACEMENT_3D('',#160056,#160057,#160058); -#160056 = CARTESIAN_POINT('',(-1.905,0.665,-2.141803043818)); -#160057 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160058 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160059 = DEFINITIONAL_REPRESENTATION('',(#160060),#160063); -#160060 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160061,#160062), +#162409 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#162410 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#162411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162412 = PCURVE('',#161752,#162413); +#162413 = DEFINITIONAL_REPRESENTATION('',(#162414),#162418); +#162414 = LINE('',#162415,#162416); +#162415 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#162416 = VECTOR('',#162417,1.); +#162417 = DIRECTION('',(0.E+000,1.)); +#162418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162419 = ADVANCED_FACE('',(#162420),#162434,.T.); +#162420 = FACE_BOUND('',#162421,.T.); +#162421 = EDGE_LOOP('',(#162422,#162456,#162484,#162511)); +#162422 = ORIENTED_EDGE('',*,*,#162423,.F.); +#162423 = EDGE_CURVE('',#162424,#162426,#162428,.T.); +#162424 = VERTEX_POINT('',#162425); +#162425 = CARTESIAN_POINT('',(-1.695,0.706843139085,-2.459055548476)); +#162426 = VERTEX_POINT('',#162427); +#162427 = CARTESIAN_POINT('',(-2.115,0.706843139085,-2.459055548476)); +#162428 = SURFACE_CURVE('',#162429,(#162433,#162445),.PCURVE_S1.); +#162429 = LINE('',#162430,#162431); +#162430 = CARTESIAN_POINT('',(-1.905,0.706843139085,-2.459055548476)); +#162431 = VECTOR('',#162432,1.); +#162432 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162433 = PCURVE('',#162434,#162439); +#162434 = PLANE('',#162435); +#162435 = AXIS2_PLACEMENT_3D('',#162436,#162437,#162438); +#162436 = CARTESIAN_POINT('',(-1.905,0.706843139085,-2.459055548476)); +#162437 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); +#162438 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#162439 = DEFINITIONAL_REPRESENTATION('',(#162440),#162444); +#162440 = LINE('',#162441,#162442); +#162441 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#162442 = VECTOR('',#162443,1.); +#162443 = DIRECTION('',(0.E+000,-1.)); +#162444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162445 = PCURVE('',#162446,#162451); +#162446 = CYLINDRICAL_SURFACE('',#162447,0.32); +#162447 = AXIS2_PLACEMENT_3D('',#162448,#162449,#162450); +#162448 = CARTESIAN_POINT('',(-1.905,0.665,-2.141803043818)); +#162449 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162450 = DIRECTION('',(0.E+000,0.E+000,1.)); +#162451 = DEFINITIONAL_REPRESENTATION('',(#162452),#162455); +#162452 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162453,#162454), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160061 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#160062 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#160063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160064 = ORIENTED_EDGE('',*,*,#160065,.F.); -#160065 = EDGE_CURVE('',#160066,#160032,#160068,.T.); -#160066 = VERTEX_POINT('',#160067); -#160067 = CARTESIAN_POINT('',(-1.695,0.327745739138,-2.509055548476)); -#160068 = SURFACE_CURVE('',#160069,(#160073,#160080),.PCURVE_S1.); -#160069 = LINE('',#160070,#160071); -#160070 = CARTESIAN_POINT('',(-1.695,0.327745739138,-2.509055548476)); -#160071 = VECTOR('',#160072,1.); -#160072 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#160073 = PCURVE('',#160042,#160074); -#160074 = DEFINITIONAL_REPRESENTATION('',(#160075),#160079); -#160075 = LINE('',#160076,#160077); -#160076 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#160077 = VECTOR('',#160078,1.); -#160078 = DIRECTION('',(1.,0.E+000)); -#160079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160080 = PCURVE('',#160081,#160086); -#160081 = PLANE('',#160082); -#160082 = AXIS2_PLACEMENT_3D('',#160083,#160084,#160085); -#160083 = CARTESIAN_POINT('',(-1.695,0.875,0.E+000)); -#160084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160085 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160086 = DEFINITIONAL_REPRESENTATION('',(#160087),#160091); -#160087 = LINE('',#160088,#160089); -#160088 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#160089 = VECTOR('',#160090,1.); -#160090 = DIRECTION('',(-0.130759809642,0.991414077055)); -#160091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160092 = ORIENTED_EDGE('',*,*,#160093,.T.); -#160093 = EDGE_CURVE('',#160066,#160094,#160096,.T.); -#160094 = VERTEX_POINT('',#160095); -#160095 = CARTESIAN_POINT('',(-2.115,0.327745739138,-2.509055548476)); -#160096 = SURFACE_CURVE('',#160097,(#160101,#160108),.PCURVE_S1.); -#160097 = LINE('',#160098,#160099); -#160098 = CARTESIAN_POINT('',(-1.905,0.327745739138,-2.509055548476)); -#160099 = VECTOR('',#160100,1.); -#160100 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160101 = PCURVE('',#160042,#160102); -#160102 = DEFINITIONAL_REPRESENTATION('',(#160103),#160107); -#160103 = LINE('',#160104,#160105); -#160104 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#160105 = VECTOR('',#160106,1.); -#160106 = DIRECTION('',(0.E+000,-1.)); -#160107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160108 = PCURVE('',#160109,#160114); -#160109 = CYLINDRICAL_SURFACE('',#160110,9.999999999999E-002); -#160110 = AXIS2_PLACEMENT_3D('',#160111,#160112,#160113); -#160111 = CARTESIAN_POINT('',(-1.905,0.340821720102,-2.608196956182)); -#160112 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160113 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160114 = DEFINITIONAL_REPRESENTATION('',(#160115),#160118); -#160115 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160116,#160117), +#162453 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#162454 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#162455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162456 = ORIENTED_EDGE('',*,*,#162457,.F.); +#162457 = EDGE_CURVE('',#162458,#162424,#162460,.T.); +#162458 = VERTEX_POINT('',#162459); +#162459 = CARTESIAN_POINT('',(-1.695,0.327745739138,-2.509055548476)); +#162460 = SURFACE_CURVE('',#162461,(#162465,#162472),.PCURVE_S1.); +#162461 = LINE('',#162462,#162463); +#162462 = CARTESIAN_POINT('',(-1.695,0.327745739138,-2.509055548476)); +#162463 = VECTOR('',#162464,1.); +#162464 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#162465 = PCURVE('',#162434,#162466); +#162466 = DEFINITIONAL_REPRESENTATION('',(#162467),#162471); +#162467 = LINE('',#162468,#162469); +#162468 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#162469 = VECTOR('',#162470,1.); +#162470 = DIRECTION('',(1.,0.E+000)); +#162471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162472 = PCURVE('',#162473,#162478); +#162473 = PLANE('',#162474); +#162474 = AXIS2_PLACEMENT_3D('',#162475,#162476,#162477); +#162475 = CARTESIAN_POINT('',(-1.695,0.875,0.E+000)); +#162476 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162477 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162478 = DEFINITIONAL_REPRESENTATION('',(#162479),#162483); +#162479 = LINE('',#162480,#162481); +#162480 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#162481 = VECTOR('',#162482,1.); +#162482 = DIRECTION('',(-0.130759809642,0.991414077055)); +#162483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162484 = ORIENTED_EDGE('',*,*,#162485,.T.); +#162485 = EDGE_CURVE('',#162458,#162486,#162488,.T.); +#162486 = VERTEX_POINT('',#162487); +#162487 = CARTESIAN_POINT('',(-2.115,0.327745739138,-2.509055548476)); +#162488 = SURFACE_CURVE('',#162489,(#162493,#162500),.PCURVE_S1.); +#162489 = LINE('',#162490,#162491); +#162490 = CARTESIAN_POINT('',(-1.905,0.327745739138,-2.509055548476)); +#162491 = VECTOR('',#162492,1.); +#162492 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162493 = PCURVE('',#162434,#162494); +#162494 = DEFINITIONAL_REPRESENTATION('',(#162495),#162499); +#162495 = LINE('',#162496,#162497); +#162496 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#162497 = VECTOR('',#162498,1.); +#162498 = DIRECTION('',(0.E+000,-1.)); +#162499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162500 = PCURVE('',#162501,#162506); +#162501 = CYLINDRICAL_SURFACE('',#162502,9.999999999999E-002); +#162502 = AXIS2_PLACEMENT_3D('',#162503,#162504,#162505); +#162503 = CARTESIAN_POINT('',(-1.905,0.340821720102,-2.608196956182)); +#162504 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162505 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162506 = DEFINITIONAL_REPRESENTATION('',(#162507),#162510); +#162507 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162508,#162509), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160116 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160117 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162508 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162509 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162511 = ORIENTED_EDGE('',*,*,#162512,.F.); +#162512 = EDGE_CURVE('',#162426,#162486,#162513,.T.); +#162513 = SURFACE_CURVE('',#162514,(#162518,#162525),.PCURVE_S1.); +#162514 = LINE('',#162515,#162516); +#162515 = CARTESIAN_POINT('',(-2.115,0.706843139085,-2.459055548476)); +#162516 = VECTOR('',#162517,1.); +#162517 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#162518 = PCURVE('',#162434,#162519); +#162519 = DEFINITIONAL_REPRESENTATION('',(#162520),#162524); +#162520 = LINE('',#162521,#162522); +#162521 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#162522 = VECTOR('',#162523,1.); +#162523 = DIRECTION('',(-1.,0.E+000)); +#162524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160119 = ORIENTED_EDGE('',*,*,#160120,.F.); -#160120 = EDGE_CURVE('',#160034,#160094,#160121,.T.); -#160121 = SURFACE_CURVE('',#160122,(#160126,#160133),.PCURVE_S1.); -#160122 = LINE('',#160123,#160124); -#160123 = CARTESIAN_POINT('',(-2.115,0.706843139085,-2.459055548476)); -#160124 = VECTOR('',#160125,1.); -#160125 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#160126 = PCURVE('',#160042,#160127); -#160127 = DEFINITIONAL_REPRESENTATION('',(#160128),#160132); -#160128 = LINE('',#160129,#160130); -#160129 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#160130 = VECTOR('',#160131,1.); -#160131 = DIRECTION('',(-1.,0.E+000)); -#160132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160133 = PCURVE('',#160134,#160139); -#160134 = PLANE('',#160135); -#160135 = AXIS2_PLACEMENT_3D('',#160136,#160137,#160138); -#160136 = CARTESIAN_POINT('',(-2.115,0.875,0.E+000)); -#160137 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160138 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160139 = DEFINITIONAL_REPRESENTATION('',(#160140),#160144); -#160140 = LINE('',#160141,#160142); -#160141 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#160142 = VECTOR('',#160143,1.); -#160143 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#160144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160145 = ADVANCED_FACE('',(#160146),#160109,.F.); -#160146 = FACE_BOUND('',#160147,.F.); -#160147 = EDGE_LOOP('',(#160148,#160175,#160202,#160227)); -#160148 = ORIENTED_EDGE('',*,*,#160149,.T.); -#160149 = EDGE_CURVE('',#160094,#160150,#160152,.T.); -#160150 = VERTEX_POINT('',#160151); -#160151 = CARTESIAN_POINT('',(-2.115,0.240958766627,-2.602963360557)); -#160152 = SURFACE_CURVE('',#160153,(#160158,#160164),.PCURVE_S1.); -#160153 = CIRCLE('',#160154,9.999999999999E-002); -#160154 = AXIS2_PLACEMENT_3D('',#160155,#160156,#160157); -#160155 = CARTESIAN_POINT('',(-2.115,0.340821720102,-2.608196956182)); -#160156 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160157 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160158 = PCURVE('',#160109,#160159); -#160159 = DEFINITIONAL_REPRESENTATION('',(#160160),#160163); -#160160 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160161,#160162), +#162525 = PCURVE('',#162526,#162531); +#162526 = PLANE('',#162527); +#162527 = AXIS2_PLACEMENT_3D('',#162528,#162529,#162530); +#162528 = CARTESIAN_POINT('',(-2.115,0.875,0.E+000)); +#162529 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162530 = DIRECTION('',(0.E+000,0.E+000,1.)); +#162531 = DEFINITIONAL_REPRESENTATION('',(#162532),#162536); +#162532 = LINE('',#162533,#162534); +#162533 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#162534 = VECTOR('',#162535,1.); +#162535 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#162536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162537 = ADVANCED_FACE('',(#162538),#162501,.F.); +#162538 = FACE_BOUND('',#162539,.F.); +#162539 = EDGE_LOOP('',(#162540,#162567,#162594,#162619)); +#162540 = ORIENTED_EDGE('',*,*,#162541,.T.); +#162541 = EDGE_CURVE('',#162486,#162542,#162544,.T.); +#162542 = VERTEX_POINT('',#162543); +#162543 = CARTESIAN_POINT('',(-2.115,0.240958766627,-2.602963360557)); +#162544 = SURFACE_CURVE('',#162545,(#162550,#162556),.PCURVE_S1.); +#162545 = CIRCLE('',#162546,9.999999999999E-002); +#162546 = AXIS2_PLACEMENT_3D('',#162547,#162548,#162549); +#162547 = CARTESIAN_POINT('',(-2.115,0.340821720102,-2.608196956182)); +#162548 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162549 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162550 = PCURVE('',#162501,#162551); +#162551 = DEFINITIONAL_REPRESENTATION('',(#162552),#162555); +#162552 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162553,#162554), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#160161 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160162 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160163 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162553 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162554 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160164 = PCURVE('',#160134,#160165); -#160165 = DEFINITIONAL_REPRESENTATION('',(#160166),#160174); -#160166 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160167,#160168,#160169, - #160170,#160171,#160172,#160173),.UNSPECIFIED.,.T.,.F.) +#162556 = PCURVE('',#162526,#162557); +#162557 = DEFINITIONAL_REPRESENTATION('',(#162558),#162566); +#162558 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162559,#162560,#162561, + #162562,#162563,#162564,#162565),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160167 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#160168 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#160169 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#160170 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#160171 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#160172 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#160173 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#160174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160175 = ORIENTED_EDGE('',*,*,#160176,.T.); -#160176 = EDGE_CURVE('',#160150,#160177,#160179,.T.); -#160177 = VERTEX_POINT('',#160178); -#160178 = CARTESIAN_POINT('',(-1.695,0.240958766627,-2.602963360557)); -#160179 = SURFACE_CURVE('',#160180,(#160184,#160190),.PCURVE_S1.); -#160180 = LINE('',#160181,#160182); -#160181 = CARTESIAN_POINT('',(-1.905,0.240958766627,-2.602963360557)); -#160182 = VECTOR('',#160183,1.); -#160183 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160184 = PCURVE('',#160109,#160185); -#160185 = DEFINITIONAL_REPRESENTATION('',(#160186),#160189); -#160186 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160187,#160188), +#162559 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#162560 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#162561 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#162562 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#162563 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#162564 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#162565 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#162566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162567 = ORIENTED_EDGE('',*,*,#162568,.T.); +#162568 = EDGE_CURVE('',#162542,#162569,#162571,.T.); +#162569 = VERTEX_POINT('',#162570); +#162570 = CARTESIAN_POINT('',(-1.695,0.240958766627,-2.602963360557)); +#162571 = SURFACE_CURVE('',#162572,(#162576,#162582),.PCURVE_S1.); +#162572 = LINE('',#162573,#162574); +#162573 = CARTESIAN_POINT('',(-1.905,0.240958766627,-2.602963360557)); +#162574 = VECTOR('',#162575,1.); +#162575 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162576 = PCURVE('',#162501,#162577); +#162577 = DEFINITIONAL_REPRESENTATION('',(#162578),#162581); +#162578 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162579,#162580), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160187 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160188 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160190 = PCURVE('',#160191,#160196); -#160191 = PLANE('',#160192); -#160192 = AXIS2_PLACEMENT_3D('',#160193,#160194,#160195); -#160193 = CARTESIAN_POINT('',(-1.905,0.240958766627,-2.602963360557)); -#160194 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); -#160195 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#160196 = DEFINITIONAL_REPRESENTATION('',(#160197),#160201); -#160197 = LINE('',#160198,#160199); -#160198 = CARTESIAN_POINT('',(-4.44933215613E-016,0.E+000)); -#160199 = VECTOR('',#160200,1.); -#160200 = DIRECTION('',(0.E+000,1.)); -#160201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160202 = ORIENTED_EDGE('',*,*,#160203,.T.); -#160203 = EDGE_CURVE('',#160177,#160066,#160204,.T.); -#160204 = SURFACE_CURVE('',#160205,(#160210,#160216),.PCURVE_S1.); -#160205 = CIRCLE('',#160206,9.999999999999E-002); -#160206 = AXIS2_PLACEMENT_3D('',#160207,#160208,#160209); -#160207 = CARTESIAN_POINT('',(-1.695,0.340821720102,-2.608196956182)); -#160208 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160209 = DIRECTION('',(0.E+000,-4.336808689942E-015,-1.)); -#160210 = PCURVE('',#160109,#160211); -#160211 = DEFINITIONAL_REPRESENTATION('',(#160212),#160215); -#160212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160213,#160214), +#162579 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162580 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162582 = PCURVE('',#162583,#162588); +#162583 = PLANE('',#162584); +#162584 = AXIS2_PLACEMENT_3D('',#162585,#162586,#162587); +#162585 = CARTESIAN_POINT('',(-1.905,0.240958766627,-2.602963360557)); +#162586 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); +#162587 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#162588 = DEFINITIONAL_REPRESENTATION('',(#162589),#162593); +#162589 = LINE('',#162590,#162591); +#162590 = CARTESIAN_POINT('',(-4.44933215613E-016,0.E+000)); +#162591 = VECTOR('',#162592,1.); +#162592 = DIRECTION('',(0.E+000,1.)); +#162593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162594 = ORIENTED_EDGE('',*,*,#162595,.T.); +#162595 = EDGE_CURVE('',#162569,#162458,#162596,.T.); +#162596 = SURFACE_CURVE('',#162597,(#162602,#162608),.PCURVE_S1.); +#162597 = CIRCLE('',#162598,9.999999999999E-002); +#162598 = AXIS2_PLACEMENT_3D('',#162599,#162600,#162601); +#162599 = CARTESIAN_POINT('',(-1.695,0.340821720102,-2.608196956182)); +#162600 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162601 = DIRECTION('',(0.E+000,-4.336808689942E-015,-1.)); +#162602 = PCURVE('',#162501,#162603); +#162603 = DEFINITIONAL_REPRESENTATION('',(#162604),#162607); +#162604 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162605,#162606), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#160213 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160214 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162605 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162606 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160216 = PCURVE('',#160081,#160217); -#160217 = DEFINITIONAL_REPRESENTATION('',(#160218),#160226); -#160218 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160219,#160220,#160221, - #160222,#160223,#160224,#160225),.UNSPECIFIED.,.F.,.F.) +#162608 = PCURVE('',#162473,#162609); +#162609 = DEFINITIONAL_REPRESENTATION('',(#162610),#162618); +#162610 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162611,#162612,#162613, + #162614,#162615,#162616,#162617),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160219 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#160220 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#160221 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#160222 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#160223 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#160224 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#160225 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#160226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160227 = ORIENTED_EDGE('',*,*,#160093,.T.); -#160228 = ADVANCED_FACE('',(#160229),#160191,.T.); -#160229 = FACE_BOUND('',#160230,.T.); -#160230 = EDGE_LOOP('',(#160231,#160232,#160255,#160283)); -#160231 = ORIENTED_EDGE('',*,*,#160176,.T.); -#160232 = ORIENTED_EDGE('',*,*,#160233,.F.); -#160233 = EDGE_CURVE('',#160234,#160177,#160236,.T.); -#160234 = VERTEX_POINT('',#160235); -#160235 = CARTESIAN_POINT('',(-1.695,0.219849248823,-3.005756955187)); -#160236 = SURFACE_CURVE('',#160237,(#160241,#160248),.PCURVE_S1.); -#160237 = LINE('',#160238,#160239); -#160238 = CARTESIAN_POINT('',(-1.695,0.219849248823,-3.005756955187)); -#160239 = VECTOR('',#160240,1.); -#160240 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#160241 = PCURVE('',#160191,#160242); -#160242 = DEFINITIONAL_REPRESENTATION('',(#160243),#160247); -#160243 = LINE('',#160244,#160245); -#160244 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#160245 = VECTOR('',#160246,1.); -#160246 = DIRECTION('',(1.,0.E+000)); -#160247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160248 = PCURVE('',#160081,#160249); -#160249 = DEFINITIONAL_REPRESENTATION('',(#160250),#160254); -#160250 = LINE('',#160251,#160252); -#160251 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#160252 = VECTOR('',#160253,1.); -#160253 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#160254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160255 = ORIENTED_EDGE('',*,*,#160256,.T.); -#160256 = EDGE_CURVE('',#160234,#160257,#160259,.T.); -#160257 = VERTEX_POINT('',#160258); -#160258 = CARTESIAN_POINT('',(-2.115,0.219849248823,-3.005756955187)); -#160259 = SURFACE_CURVE('',#160260,(#160264,#160271),.PCURVE_S1.); -#160260 = LINE('',#160261,#160262); -#160261 = CARTESIAN_POINT('',(-1.905,0.219849248823,-3.005756955187)); -#160262 = VECTOR('',#160263,1.); -#160263 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160264 = PCURVE('',#160191,#160265); -#160265 = DEFINITIONAL_REPRESENTATION('',(#160266),#160270); -#160266 = LINE('',#160267,#160268); -#160267 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#160268 = VECTOR('',#160269,1.); -#160269 = DIRECTION('',(0.E+000,-1.)); -#160270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160271 = PCURVE('',#160272,#160277); -#160272 = PLANE('',#160273); -#160273 = AXIS2_PLACEMENT_3D('',#160274,#160275,#160276); -#160274 = CARTESIAN_POINT('',(-1.905,0.11,-3.)); -#160275 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); -#160276 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#160277 = DEFINITIONAL_REPRESENTATION('',(#160278),#160282); -#160278 = LINE('',#160279,#160280); -#160279 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#160280 = VECTOR('',#160281,1.); -#160281 = DIRECTION('',(0.E+000,-1.)); -#160282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160283 = ORIENTED_EDGE('',*,*,#160284,.F.); -#160284 = EDGE_CURVE('',#160150,#160257,#160285,.T.); -#160285 = SURFACE_CURVE('',#160286,(#160290,#160297),.PCURVE_S1.); -#160286 = LINE('',#160287,#160288); -#160287 = CARTESIAN_POINT('',(-2.115,0.240958766627,-2.602963360557)); -#160288 = VECTOR('',#160289,1.); -#160289 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#160290 = PCURVE('',#160191,#160291); -#160291 = DEFINITIONAL_REPRESENTATION('',(#160292),#160296); -#160292 = LINE('',#160293,#160294); -#160293 = CARTESIAN_POINT('',(-4.44933215613E-016,-0.21)); -#160294 = VECTOR('',#160295,1.); -#160295 = DIRECTION('',(-1.,0.E+000)); -#160296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160297 = PCURVE('',#160134,#160298); -#160298 = DEFINITIONAL_REPRESENTATION('',(#160299),#160303); -#160299 = LINE('',#160300,#160301); -#160300 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#160301 = VECTOR('',#160302,1.); -#160302 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#160303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160304 = ADVANCED_FACE('',(#160305),#160272,.F.); -#160305 = FACE_BOUND('',#160306,.T.); -#160306 = EDGE_LOOP('',(#160307,#160330,#160331,#160354)); -#160307 = ORIENTED_EDGE('',*,*,#160308,.F.); -#160308 = EDGE_CURVE('',#160257,#160309,#160311,.T.); -#160309 = VERTEX_POINT('',#160310); -#160310 = CARTESIAN_POINT('',(-2.115,1.507511769915E-004,-2.994243044813 +#162611 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#162612 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#162613 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#162614 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#162615 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#162616 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#162617 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#162618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162619 = ORIENTED_EDGE('',*,*,#162485,.T.); +#162620 = ADVANCED_FACE('',(#162621),#162583,.T.); +#162621 = FACE_BOUND('',#162622,.T.); +#162622 = EDGE_LOOP('',(#162623,#162624,#162647,#162675)); +#162623 = ORIENTED_EDGE('',*,*,#162568,.T.); +#162624 = ORIENTED_EDGE('',*,*,#162625,.F.); +#162625 = EDGE_CURVE('',#162626,#162569,#162628,.T.); +#162626 = VERTEX_POINT('',#162627); +#162627 = CARTESIAN_POINT('',(-1.695,0.219849248823,-3.005756955187)); +#162628 = SURFACE_CURVE('',#162629,(#162633,#162640),.PCURVE_S1.); +#162629 = LINE('',#162630,#162631); +#162630 = CARTESIAN_POINT('',(-1.695,0.219849248823,-3.005756955187)); +#162631 = VECTOR('',#162632,1.); +#162632 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#162633 = PCURVE('',#162583,#162634); +#162634 = DEFINITIONAL_REPRESENTATION('',(#162635),#162639); +#162635 = LINE('',#162636,#162637); +#162636 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#162637 = VECTOR('',#162638,1.); +#162638 = DIRECTION('',(1.,0.E+000)); +#162639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162640 = PCURVE('',#162473,#162641); +#162641 = DEFINITIONAL_REPRESENTATION('',(#162642),#162646); +#162642 = LINE('',#162643,#162644); +#162643 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#162644 = VECTOR('',#162645,1.); +#162645 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#162646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162647 = ORIENTED_EDGE('',*,*,#162648,.T.); +#162648 = EDGE_CURVE('',#162626,#162649,#162651,.T.); +#162649 = VERTEX_POINT('',#162650); +#162650 = CARTESIAN_POINT('',(-2.115,0.219849248823,-3.005756955187)); +#162651 = SURFACE_CURVE('',#162652,(#162656,#162663),.PCURVE_S1.); +#162652 = LINE('',#162653,#162654); +#162653 = CARTESIAN_POINT('',(-1.905,0.219849248823,-3.005756955187)); +#162654 = VECTOR('',#162655,1.); +#162655 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162656 = PCURVE('',#162583,#162657); +#162657 = DEFINITIONAL_REPRESENTATION('',(#162658),#162662); +#162658 = LINE('',#162659,#162660); +#162659 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#162660 = VECTOR('',#162661,1.); +#162661 = DIRECTION('',(0.E+000,-1.)); +#162662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162663 = PCURVE('',#162664,#162669); +#162664 = PLANE('',#162665); +#162665 = AXIS2_PLACEMENT_3D('',#162666,#162667,#162668); +#162666 = CARTESIAN_POINT('',(-1.905,0.11,-3.)); +#162667 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); +#162668 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#162669 = DEFINITIONAL_REPRESENTATION('',(#162670),#162674); +#162670 = LINE('',#162671,#162672); +#162671 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#162672 = VECTOR('',#162673,1.); +#162673 = DIRECTION('',(0.E+000,-1.)); +#162674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162675 = ORIENTED_EDGE('',*,*,#162676,.F.); +#162676 = EDGE_CURVE('',#162542,#162649,#162677,.T.); +#162677 = SURFACE_CURVE('',#162678,(#162682,#162689),.PCURVE_S1.); +#162678 = LINE('',#162679,#162680); +#162679 = CARTESIAN_POINT('',(-2.115,0.240958766627,-2.602963360557)); +#162680 = VECTOR('',#162681,1.); +#162681 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162682 = PCURVE('',#162583,#162683); +#162683 = DEFINITIONAL_REPRESENTATION('',(#162684),#162688); +#162684 = LINE('',#162685,#162686); +#162685 = CARTESIAN_POINT('',(-4.44933215613E-016,-0.21)); +#162686 = VECTOR('',#162687,1.); +#162687 = DIRECTION('',(-1.,0.E+000)); +#162688 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162689 = PCURVE('',#162526,#162690); +#162690 = DEFINITIONAL_REPRESENTATION('',(#162691),#162695); +#162691 = LINE('',#162692,#162693); +#162692 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#162693 = VECTOR('',#162694,1.); +#162694 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#162695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162696 = ADVANCED_FACE('',(#162697),#162664,.F.); +#162697 = FACE_BOUND('',#162698,.T.); +#162698 = EDGE_LOOP('',(#162699,#162722,#162723,#162746)); +#162699 = ORIENTED_EDGE('',*,*,#162700,.F.); +#162700 = EDGE_CURVE('',#162649,#162701,#162703,.T.); +#162701 = VERTEX_POINT('',#162702); +#162702 = CARTESIAN_POINT('',(-2.115,1.507511769915E-004,-2.994243044813 )); -#160311 = SURFACE_CURVE('',#160312,(#160316,#160323),.PCURVE_S1.); -#160312 = LINE('',#160313,#160314); -#160313 = CARTESIAN_POINT('',(-2.115,0.219849248823,-3.005756955187)); -#160314 = VECTOR('',#160315,1.); -#160315 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#160316 = PCURVE('',#160272,#160317); -#160317 = DEFINITIONAL_REPRESENTATION('',(#160318),#160322); -#160318 = LINE('',#160319,#160320); -#160319 = CARTESIAN_POINT('',(-0.11,-0.21)); -#160320 = VECTOR('',#160321,1.); -#160321 = DIRECTION('',(1.,0.E+000)); -#160322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160323 = PCURVE('',#160134,#160324); -#160324 = DEFINITIONAL_REPRESENTATION('',(#160325),#160329); -#160325 = LINE('',#160326,#160327); -#160326 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#160327 = VECTOR('',#160328,1.); -#160328 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#160329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160330 = ORIENTED_EDGE('',*,*,#160256,.F.); -#160331 = ORIENTED_EDGE('',*,*,#160332,.F.); -#160332 = EDGE_CURVE('',#160333,#160234,#160335,.T.); -#160333 = VERTEX_POINT('',#160334); -#160334 = CARTESIAN_POINT('',(-1.695,1.507511769916E-004,-2.994243044813 +#162703 = SURFACE_CURVE('',#162704,(#162708,#162715),.PCURVE_S1.); +#162704 = LINE('',#162705,#162706); +#162705 = CARTESIAN_POINT('',(-2.115,0.219849248823,-3.005756955187)); +#162706 = VECTOR('',#162707,1.); +#162707 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#162708 = PCURVE('',#162664,#162709); +#162709 = DEFINITIONAL_REPRESENTATION('',(#162710),#162714); +#162710 = LINE('',#162711,#162712); +#162711 = CARTESIAN_POINT('',(-0.11,-0.21)); +#162712 = VECTOR('',#162713,1.); +#162713 = DIRECTION('',(1.,0.E+000)); +#162714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162715 = PCURVE('',#162526,#162716); +#162716 = DEFINITIONAL_REPRESENTATION('',(#162717),#162721); +#162717 = LINE('',#162718,#162719); +#162718 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#162719 = VECTOR('',#162720,1.); +#162720 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#162721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162722 = ORIENTED_EDGE('',*,*,#162648,.F.); +#162723 = ORIENTED_EDGE('',*,*,#162724,.F.); +#162724 = EDGE_CURVE('',#162725,#162626,#162727,.T.); +#162725 = VERTEX_POINT('',#162726); +#162726 = CARTESIAN_POINT('',(-1.695,1.507511769916E-004,-2.994243044813 )); -#160335 = SURFACE_CURVE('',#160336,(#160340,#160347),.PCURVE_S1.); -#160336 = LINE('',#160337,#160338); -#160337 = CARTESIAN_POINT('',(-1.695,1.507511769892E-004,-2.994243044813 +#162727 = SURFACE_CURVE('',#162728,(#162732,#162739),.PCURVE_S1.); +#162728 = LINE('',#162729,#162730); +#162729 = CARTESIAN_POINT('',(-1.695,1.507511769892E-004,-2.994243044813 )); -#160338 = VECTOR('',#160339,1.); -#160339 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); -#160340 = PCURVE('',#160272,#160341); -#160341 = DEFINITIONAL_REPRESENTATION('',(#160342),#160346); -#160342 = LINE('',#160343,#160344); -#160343 = CARTESIAN_POINT('',(0.11,0.21)); -#160344 = VECTOR('',#160345,1.); -#160345 = DIRECTION('',(-1.,0.E+000)); -#160346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160347 = PCURVE('',#160081,#160348); -#160348 = DEFINITIONAL_REPRESENTATION('',(#160349),#160353); -#160349 = LINE('',#160350,#160351); -#160350 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#160351 = VECTOR('',#160352,1.); -#160352 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#160353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160354 = ORIENTED_EDGE('',*,*,#160355,.F.); -#160355 = EDGE_CURVE('',#160309,#160333,#160356,.T.); -#160356 = SURFACE_CURVE('',#160357,(#160361,#160368),.PCURVE_S1.); -#160357 = LINE('',#160358,#160359); -#160358 = CARTESIAN_POINT('',(-1.905,1.507511769963E-004,-2.994243044813 +#162730 = VECTOR('',#162731,1.); +#162731 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); +#162732 = PCURVE('',#162664,#162733); +#162733 = DEFINITIONAL_REPRESENTATION('',(#162734),#162738); +#162734 = LINE('',#162735,#162736); +#162735 = CARTESIAN_POINT('',(0.11,0.21)); +#162736 = VECTOR('',#162737,1.); +#162737 = DIRECTION('',(-1.,0.E+000)); +#162738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162739 = PCURVE('',#162473,#162740); +#162740 = DEFINITIONAL_REPRESENTATION('',(#162741),#162745); +#162741 = LINE('',#162742,#162743); +#162742 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#162743 = VECTOR('',#162744,1.); +#162744 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#162745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162746 = ORIENTED_EDGE('',*,*,#162747,.F.); +#162747 = EDGE_CURVE('',#162701,#162725,#162748,.T.); +#162748 = SURFACE_CURVE('',#162749,(#162753,#162760),.PCURVE_S1.); +#162749 = LINE('',#162750,#162751); +#162750 = CARTESIAN_POINT('',(-1.905,1.507511769963E-004,-2.994243044813 )); -#160359 = VECTOR('',#160360,1.); -#160360 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160361 = PCURVE('',#160272,#160362); -#160362 = DEFINITIONAL_REPRESENTATION('',(#160363),#160367); -#160363 = LINE('',#160364,#160365); -#160364 = CARTESIAN_POINT('',(0.11,0.E+000)); -#160365 = VECTOR('',#160366,1.); -#160366 = DIRECTION('',(0.E+000,1.)); -#160367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160368 = PCURVE('',#160369,#160374); -#160369 = PLANE('',#160370); -#160370 = AXIS2_PLACEMENT_3D('',#160371,#160372,#160373); -#160371 = CARTESIAN_POINT('',(-1.905,2.126026898096E-002,-2.591449450184 +#162751 = VECTOR('',#162752,1.); +#162752 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162753 = PCURVE('',#162664,#162754); +#162754 = DEFINITIONAL_REPRESENTATION('',(#162755),#162759); +#162755 = LINE('',#162756,#162757); +#162756 = CARTESIAN_POINT('',(0.11,0.E+000)); +#162757 = VECTOR('',#162758,1.); +#162758 = DIRECTION('',(0.E+000,1.)); +#162759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162760 = PCURVE('',#162761,#162766); +#162761 = PLANE('',#162762); +#162762 = AXIS2_PLACEMENT_3D('',#162763,#162764,#162765); +#162763 = CARTESIAN_POINT('',(-1.905,2.126026898096E-002,-2.591449450184 )); -#160372 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); -#160373 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#160374 = DEFINITIONAL_REPRESENTATION('',(#160375),#160379); -#160375 = LINE('',#160376,#160377); -#160376 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#160377 = VECTOR('',#160378,1.); -#160378 = DIRECTION('',(0.E+000,1.)); -#160379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160380 = ADVANCED_FACE('',(#160381),#160369,.T.); -#160381 = FACE_BOUND('',#160382,.T.); -#160382 = EDGE_LOOP('',(#160383,#160412,#160433,#160434)); -#160383 = ORIENTED_EDGE('',*,*,#160384,.F.); -#160384 = EDGE_CURVE('',#160385,#160387,#160389,.T.); -#160385 = VERTEX_POINT('',#160386); -#160386 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,-2.591449450184 +#162764 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); +#162765 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162766 = DEFINITIONAL_REPRESENTATION('',(#162767),#162771); +#162767 = LINE('',#162768,#162769); +#162768 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#162769 = VECTOR('',#162770,1.); +#162770 = DIRECTION('',(0.E+000,1.)); +#162771 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162772 = ADVANCED_FACE('',(#162773),#162761,.T.); +#162773 = FACE_BOUND('',#162774,.T.); +#162774 = EDGE_LOOP('',(#162775,#162804,#162825,#162826)); +#162775 = ORIENTED_EDGE('',*,*,#162776,.F.); +#162776 = EDGE_CURVE('',#162777,#162779,#162781,.T.); +#162777 = VERTEX_POINT('',#162778); +#162778 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,-2.591449450184 )); -#160387 = VERTEX_POINT('',#160388); -#160388 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,-2.591449450184 +#162779 = VERTEX_POINT('',#162780); +#162780 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,-2.591449450184 )); -#160389 = SURFACE_CURVE('',#160390,(#160394,#160401),.PCURVE_S1.); -#160390 = LINE('',#160391,#160392); -#160391 = CARTESIAN_POINT('',(-1.905,2.126026898095E-002,-2.591449450184 +#162781 = SURFACE_CURVE('',#162782,(#162786,#162793),.PCURVE_S1.); +#162782 = LINE('',#162783,#162784); +#162783 = CARTESIAN_POINT('',(-1.905,2.126026898095E-002,-2.591449450184 )); -#160392 = VECTOR('',#160393,1.); -#160393 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160394 = PCURVE('',#160369,#160395); -#160395 = DEFINITIONAL_REPRESENTATION('',(#160396),#160400); -#160396 = LINE('',#160397,#160398); -#160397 = CARTESIAN_POINT('',(4.445700619653E-016,0.E+000)); -#160398 = VECTOR('',#160399,1.); -#160399 = DIRECTION('',(0.E+000,1.)); -#160400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160401 = PCURVE('',#160402,#160407); -#160402 = CYLINDRICAL_SURFACE('',#160403,0.32); -#160403 = AXIS2_PLACEMENT_3D('',#160404,#160405,#160406); -#160404 = CARTESIAN_POINT('',(-1.905,0.340821720102,-2.608196956182)); -#160405 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160406 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160407 = DEFINITIONAL_REPRESENTATION('',(#160408),#160411); -#160408 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160409,#160410), +#162784 = VECTOR('',#162785,1.); +#162785 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162786 = PCURVE('',#162761,#162787); +#162787 = DEFINITIONAL_REPRESENTATION('',(#162788),#162792); +#162788 = LINE('',#162789,#162790); +#162789 = CARTESIAN_POINT('',(4.445700619653E-016,0.E+000)); +#162790 = VECTOR('',#162791,1.); +#162791 = DIRECTION('',(0.E+000,1.)); +#162792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162793 = PCURVE('',#162794,#162799); +#162794 = CYLINDRICAL_SURFACE('',#162795,0.32); +#162795 = AXIS2_PLACEMENT_3D('',#162796,#162797,#162798); +#162796 = CARTESIAN_POINT('',(-1.905,0.340821720102,-2.608196956182)); +#162797 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162798 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162799 = DEFINITIONAL_REPRESENTATION('',(#162800),#162803); +#162800 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162801,#162802), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160409 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160410 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#162801 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162802 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160412 = ORIENTED_EDGE('',*,*,#160413,.F.); -#160413 = EDGE_CURVE('',#160309,#160385,#160414,.T.); -#160414 = SURFACE_CURVE('',#160415,(#160419,#160426),.PCURVE_S1.); -#160415 = LINE('',#160416,#160417); -#160416 = CARTESIAN_POINT('',(-2.115,1.507511769892E-004,-2.994243044813 +#162804 = ORIENTED_EDGE('',*,*,#162805,.F.); +#162805 = EDGE_CURVE('',#162701,#162777,#162806,.T.); +#162806 = SURFACE_CURVE('',#162807,(#162811,#162818),.PCURVE_S1.); +#162807 = LINE('',#162808,#162809); +#162808 = CARTESIAN_POINT('',(-2.115,1.507511769892E-004,-2.994243044813 )); -#160417 = VECTOR('',#160418,1.); -#160418 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#160419 = PCURVE('',#160369,#160420); -#160420 = DEFINITIONAL_REPRESENTATION('',(#160421),#160425); -#160421 = LINE('',#160422,#160423); -#160422 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#160423 = VECTOR('',#160424,1.); -#160424 = DIRECTION('',(-1.,0.E+000)); -#160425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160426 = PCURVE('',#160134,#160427); -#160427 = DEFINITIONAL_REPRESENTATION('',(#160428),#160432); -#160428 = LINE('',#160429,#160430); -#160429 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#160430 = VECTOR('',#160431,1.); -#160431 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#160432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160433 = ORIENTED_EDGE('',*,*,#160355,.T.); -#160434 = ORIENTED_EDGE('',*,*,#160435,.F.); -#160435 = EDGE_CURVE('',#160387,#160333,#160436,.T.); -#160436 = SURFACE_CURVE('',#160437,(#160441,#160448),.PCURVE_S1.); -#160437 = LINE('',#160438,#160439); -#160438 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,-2.591449450184 +#162809 = VECTOR('',#162810,1.); +#162810 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#162811 = PCURVE('',#162761,#162812); +#162812 = DEFINITIONAL_REPRESENTATION('',(#162813),#162817); +#162813 = LINE('',#162814,#162815); +#162814 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#162815 = VECTOR('',#162816,1.); +#162816 = DIRECTION('',(-1.,0.E+000)); +#162817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162818 = PCURVE('',#162526,#162819); +#162819 = DEFINITIONAL_REPRESENTATION('',(#162820),#162824); +#162820 = LINE('',#162821,#162822); +#162821 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#162822 = VECTOR('',#162823,1.); +#162823 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#162824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162825 = ORIENTED_EDGE('',*,*,#162747,.T.); +#162826 = ORIENTED_EDGE('',*,*,#162827,.F.); +#162827 = EDGE_CURVE('',#162779,#162725,#162828,.T.); +#162828 = SURFACE_CURVE('',#162829,(#162833,#162840),.PCURVE_S1.); +#162829 = LINE('',#162830,#162831); +#162830 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,-2.591449450184 )); -#160439 = VECTOR('',#160440,1.); -#160440 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#160441 = PCURVE('',#160369,#160442); -#160442 = DEFINITIONAL_REPRESENTATION('',(#160443),#160447); -#160443 = LINE('',#160444,#160445); -#160444 = CARTESIAN_POINT('',(4.445700619653E-016,0.21)); -#160445 = VECTOR('',#160446,1.); -#160446 = DIRECTION('',(1.,0.E+000)); -#160447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160448 = PCURVE('',#160081,#160449); -#160449 = DEFINITIONAL_REPRESENTATION('',(#160450),#160454); -#160450 = LINE('',#160451,#160452); -#160451 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#160452 = VECTOR('',#160453,1.); -#160453 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#160454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160455 = ADVANCED_FACE('',(#160456),#160402,.T.); -#160456 = FACE_BOUND('',#160457,.T.); -#160457 = EDGE_LOOP('',(#160458,#160487,#160508,#160509)); -#160458 = ORIENTED_EDGE('',*,*,#160459,.F.); -#160459 = EDGE_CURVE('',#160460,#160462,#160464,.T.); -#160460 = VERTEX_POINT('',#160461); -#160461 = CARTESIAN_POINT('',(-2.115,0.298978581017,-2.290944451524)); -#160462 = VERTEX_POINT('',#160463); -#160463 = CARTESIAN_POINT('',(-1.695,0.298978581017,-2.290944451524)); -#160464 = SURFACE_CURVE('',#160465,(#160469,#160475),.PCURVE_S1.); -#160465 = LINE('',#160466,#160467); -#160466 = CARTESIAN_POINT('',(-1.905,0.298978581017,-2.290944451524)); -#160467 = VECTOR('',#160468,1.); -#160468 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160469 = PCURVE('',#160402,#160470); -#160470 = DEFINITIONAL_REPRESENTATION('',(#160471),#160474); -#160471 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160472,#160473), +#162831 = VECTOR('',#162832,1.); +#162832 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#162833 = PCURVE('',#162761,#162834); +#162834 = DEFINITIONAL_REPRESENTATION('',(#162835),#162839); +#162835 = LINE('',#162836,#162837); +#162836 = CARTESIAN_POINT('',(4.445700619653E-016,0.21)); +#162837 = VECTOR('',#162838,1.); +#162838 = DIRECTION('',(1.,0.E+000)); +#162839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162840 = PCURVE('',#162473,#162841); +#162841 = DEFINITIONAL_REPRESENTATION('',(#162842),#162846); +#162842 = LINE('',#162843,#162844); +#162843 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#162844 = VECTOR('',#162845,1.); +#162845 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#162846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162847 = ADVANCED_FACE('',(#162848),#162794,.T.); +#162848 = FACE_BOUND('',#162849,.T.); +#162849 = EDGE_LOOP('',(#162850,#162879,#162900,#162901)); +#162850 = ORIENTED_EDGE('',*,*,#162851,.F.); +#162851 = EDGE_CURVE('',#162852,#162854,#162856,.T.); +#162852 = VERTEX_POINT('',#162853); +#162853 = CARTESIAN_POINT('',(-2.115,0.298978581017,-2.290944451524)); +#162854 = VERTEX_POINT('',#162855); +#162855 = CARTESIAN_POINT('',(-1.695,0.298978581017,-2.290944451524)); +#162856 = SURFACE_CURVE('',#162857,(#162861,#162867),.PCURVE_S1.); +#162857 = LINE('',#162858,#162859); +#162858 = CARTESIAN_POINT('',(-1.905,0.298978581017,-2.290944451524)); +#162859 = VECTOR('',#162860,1.); +#162860 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162861 = PCURVE('',#162794,#162862); +#162862 = DEFINITIONAL_REPRESENTATION('',(#162863),#162866); +#162863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162864,#162865), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160472 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160473 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160475 = PCURVE('',#160476,#160481); -#160476 = PLANE('',#160477); -#160477 = AXIS2_PLACEMENT_3D('',#160478,#160479,#160480); -#160478 = CARTESIAN_POINT('',(-1.905,0.678075980964,-2.240944451524)); -#160479 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); -#160480 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#160481 = DEFINITIONAL_REPRESENTATION('',(#160482),#160486); -#160482 = LINE('',#160483,#160484); -#160483 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#160484 = VECTOR('',#160485,1.); -#160485 = DIRECTION('',(0.E+000,1.)); -#160486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160487 = ORIENTED_EDGE('',*,*,#160488,.F.); -#160488 = EDGE_CURVE('',#160385,#160460,#160489,.T.); -#160489 = SURFACE_CURVE('',#160490,(#160495,#160501),.PCURVE_S1.); -#160490 = CIRCLE('',#160491,0.32); -#160491 = AXIS2_PLACEMENT_3D('',#160492,#160493,#160494); -#160492 = CARTESIAN_POINT('',(-2.115,0.340821720102,-2.608196956182)); -#160493 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160494 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); -#160495 = PCURVE('',#160402,#160496); -#160496 = DEFINITIONAL_REPRESENTATION('',(#160497),#160500); -#160497 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160498,#160499), +#162864 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162865 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162867 = PCURVE('',#162868,#162873); +#162868 = PLANE('',#162869); +#162869 = AXIS2_PLACEMENT_3D('',#162870,#162871,#162872); +#162870 = CARTESIAN_POINT('',(-1.905,0.678075980964,-2.240944451524)); +#162871 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); +#162872 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#162873 = DEFINITIONAL_REPRESENTATION('',(#162874),#162878); +#162874 = LINE('',#162875,#162876); +#162875 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#162876 = VECTOR('',#162877,1.); +#162877 = DIRECTION('',(0.E+000,1.)); +#162878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162879 = ORIENTED_EDGE('',*,*,#162880,.F.); +#162880 = EDGE_CURVE('',#162777,#162852,#162881,.T.); +#162881 = SURFACE_CURVE('',#162882,(#162887,#162893),.PCURVE_S1.); +#162882 = CIRCLE('',#162883,0.32); +#162883 = AXIS2_PLACEMENT_3D('',#162884,#162885,#162886); +#162884 = CARTESIAN_POINT('',(-2.115,0.340821720102,-2.608196956182)); +#162885 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162886 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); +#162887 = PCURVE('',#162794,#162888); +#162888 = DEFINITIONAL_REPRESENTATION('',(#162889),#162892); +#162889 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162890,#162891), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#160498 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160499 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160501 = PCURVE('',#160134,#160502); -#160502 = DEFINITIONAL_REPRESENTATION('',(#160503),#160507); -#160503 = CIRCLE('',#160504,0.32); -#160504 = AXIS2_PLACEMENT_2D('',#160505,#160506); -#160505 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#160506 = DIRECTION('',(-1.,1.694065894509E-015)); -#160507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160508 = ORIENTED_EDGE('',*,*,#160384,.T.); -#160509 = ORIENTED_EDGE('',*,*,#160510,.F.); -#160510 = EDGE_CURVE('',#160462,#160387,#160511,.T.); -#160511 = SURFACE_CURVE('',#160512,(#160517,#160523),.PCURVE_S1.); -#160512 = CIRCLE('',#160513,0.32); -#160513 = AXIS2_PLACEMENT_3D('',#160514,#160515,#160516); -#160514 = CARTESIAN_POINT('',(-1.695,0.340821720102,-2.608196956182)); -#160515 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160516 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160517 = PCURVE('',#160402,#160518); -#160518 = DEFINITIONAL_REPRESENTATION('',(#160519),#160522); -#160519 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160520,#160521), +#162890 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#162891 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#162892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162893 = PCURVE('',#162526,#162894); +#162894 = DEFINITIONAL_REPRESENTATION('',(#162895),#162899); +#162895 = CIRCLE('',#162896,0.32); +#162896 = AXIS2_PLACEMENT_2D('',#162897,#162898); +#162897 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#162898 = DIRECTION('',(-1.,1.694065894509E-015)); +#162899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162900 = ORIENTED_EDGE('',*,*,#162776,.T.); +#162901 = ORIENTED_EDGE('',*,*,#162902,.F.); +#162902 = EDGE_CURVE('',#162854,#162779,#162903,.T.); +#162903 = SURFACE_CURVE('',#162904,(#162909,#162915),.PCURVE_S1.); +#162904 = CIRCLE('',#162905,0.32); +#162905 = AXIS2_PLACEMENT_3D('',#162906,#162907,#162908); +#162906 = CARTESIAN_POINT('',(-1.695,0.340821720102,-2.608196956182)); +#162907 = DIRECTION('',(1.,0.E+000,0.E+000)); +#162908 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#162909 = PCURVE('',#162794,#162910); +#162910 = DEFINITIONAL_REPRESENTATION('',(#162911),#162914); +#162911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162912,#162913), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#160520 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160521 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160523 = PCURVE('',#160081,#160524); -#160524 = DEFINITIONAL_REPRESENTATION('',(#160525),#160529); -#160525 = CIRCLE('',#160526,0.32); -#160526 = AXIS2_PLACEMENT_2D('',#160527,#160528); -#160527 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#160528 = DIRECTION('',(1.,0.E+000)); -#160529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160530 = ADVANCED_FACE('',(#160531),#160476,.T.); -#160531 = FACE_BOUND('',#160532,.T.); -#160532 = EDGE_LOOP('',(#160533,#160562,#160583,#160584)); -#160533 = ORIENTED_EDGE('',*,*,#160534,.T.); -#160534 = EDGE_CURVE('',#160535,#160537,#160539,.T.); -#160535 = VERTEX_POINT('',#160536); -#160536 = CARTESIAN_POINT('',(-1.695,0.678075980964,-2.240944451524)); -#160537 = VERTEX_POINT('',#160538); -#160538 = CARTESIAN_POINT('',(-2.115,0.678075980964,-2.240944451524)); -#160539 = SURFACE_CURVE('',#160540,(#160544,#160551),.PCURVE_S1.); -#160540 = LINE('',#160541,#160542); -#160541 = CARTESIAN_POINT('',(-1.905,0.678075980964,-2.240944451524)); -#160542 = VECTOR('',#160543,1.); -#160543 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160544 = PCURVE('',#160476,#160545); -#160545 = DEFINITIONAL_REPRESENTATION('',(#160546),#160550); -#160546 = LINE('',#160547,#160548); -#160547 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#160548 = VECTOR('',#160549,1.); -#160549 = DIRECTION('',(0.E+000,-1.)); -#160550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160551 = PCURVE('',#160552,#160557); -#160552 = CYLINDRICAL_SURFACE('',#160553,1.E-001); -#160553 = AXIS2_PLACEMENT_3D('',#160554,#160555,#160556); -#160554 = CARTESIAN_POINT('',(-1.905,0.665,-2.141803043818)); -#160555 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160556 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160557 = DEFINITIONAL_REPRESENTATION('',(#160558),#160561); -#160558 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160559,#160560), +#162912 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#162913 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#162914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162915 = PCURVE('',#162473,#162916); +#162916 = DEFINITIONAL_REPRESENTATION('',(#162917),#162921); +#162917 = CIRCLE('',#162918,0.32); +#162918 = AXIS2_PLACEMENT_2D('',#162919,#162920); +#162919 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#162920 = DIRECTION('',(1.,0.E+000)); +#162921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162922 = ADVANCED_FACE('',(#162923),#162868,.T.); +#162923 = FACE_BOUND('',#162924,.T.); +#162924 = EDGE_LOOP('',(#162925,#162954,#162975,#162976)); +#162925 = ORIENTED_EDGE('',*,*,#162926,.T.); +#162926 = EDGE_CURVE('',#162927,#162929,#162931,.T.); +#162927 = VERTEX_POINT('',#162928); +#162928 = CARTESIAN_POINT('',(-1.695,0.678075980964,-2.240944451524)); +#162929 = VERTEX_POINT('',#162930); +#162930 = CARTESIAN_POINT('',(-2.115,0.678075980964,-2.240944451524)); +#162931 = SURFACE_CURVE('',#162932,(#162936,#162943),.PCURVE_S1.); +#162932 = LINE('',#162933,#162934); +#162933 = CARTESIAN_POINT('',(-1.905,0.678075980964,-2.240944451524)); +#162934 = VECTOR('',#162935,1.); +#162935 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162936 = PCURVE('',#162868,#162937); +#162937 = DEFINITIONAL_REPRESENTATION('',(#162938),#162942); +#162938 = LINE('',#162939,#162940); +#162939 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#162940 = VECTOR('',#162941,1.); +#162941 = DIRECTION('',(0.E+000,-1.)); +#162942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162943 = PCURVE('',#162944,#162949); +#162944 = CYLINDRICAL_SURFACE('',#162945,1.E-001); +#162945 = AXIS2_PLACEMENT_3D('',#162946,#162947,#162948); +#162946 = CARTESIAN_POINT('',(-1.905,0.665,-2.141803043818)); +#162947 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#162948 = DIRECTION('',(0.E+000,0.E+000,1.)); +#162949 = DEFINITIONAL_REPRESENTATION('',(#162950),#162953); +#162950 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162951,#162952), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160559 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#160560 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#160561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160562 = ORIENTED_EDGE('',*,*,#160563,.F.); -#160563 = EDGE_CURVE('',#160460,#160537,#160564,.T.); -#160564 = SURFACE_CURVE('',#160565,(#160569,#160576),.PCURVE_S1.); -#160565 = LINE('',#160566,#160567); -#160566 = CARTESIAN_POINT('',(-2.115,0.298978581017,-2.290944451524)); -#160567 = VECTOR('',#160568,1.); -#160568 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#160569 = PCURVE('',#160476,#160570); -#160570 = DEFINITIONAL_REPRESENTATION('',(#160571),#160575); -#160571 = LINE('',#160572,#160573); -#160572 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#160573 = VECTOR('',#160574,1.); -#160574 = DIRECTION('',(-1.,0.E+000)); -#160575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160576 = PCURVE('',#160134,#160577); -#160577 = DEFINITIONAL_REPRESENTATION('',(#160578),#160582); -#160578 = LINE('',#160579,#160580); -#160579 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#160580 = VECTOR('',#160581,1.); -#160581 = DIRECTION('',(0.130759809642,0.991414077055)); -#160582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160583 = ORIENTED_EDGE('',*,*,#160459,.T.); -#160584 = ORIENTED_EDGE('',*,*,#160585,.F.); -#160585 = EDGE_CURVE('',#160535,#160462,#160586,.T.); -#160586 = SURFACE_CURVE('',#160587,(#160591,#160598),.PCURVE_S1.); -#160587 = LINE('',#160588,#160589); -#160588 = CARTESIAN_POINT('',(-1.695,0.678075980964,-2.240944451524)); -#160589 = VECTOR('',#160590,1.); -#160590 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#160591 = PCURVE('',#160476,#160592); -#160592 = DEFINITIONAL_REPRESENTATION('',(#160593),#160597); -#160593 = LINE('',#160594,#160595); -#160594 = CARTESIAN_POINT('',(0.E+000,0.21)); -#160595 = VECTOR('',#160596,1.); -#160596 = DIRECTION('',(1.,0.E+000)); -#160597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160598 = PCURVE('',#160081,#160599); -#160599 = DEFINITIONAL_REPRESENTATION('',(#160600),#160604); -#160600 = LINE('',#160601,#160602); -#160601 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#160602 = VECTOR('',#160603,1.); -#160603 = DIRECTION('',(0.130759809642,-0.991414077055)); -#160604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160605 = ADVANCED_FACE('',(#160606),#160552,.F.); -#160606 = FACE_BOUND('',#160607,.F.); -#160607 = EDGE_LOOP('',(#160608,#160635,#160636,#160663)); -#160608 = ORIENTED_EDGE('',*,*,#160609,.T.); -#160609 = EDGE_CURVE('',#160610,#160535,#160612,.T.); -#160610 = VERTEX_POINT('',#160611); -#160611 = CARTESIAN_POINT('',(-1.695,0.765,-2.141803043818)); -#160612 = SURFACE_CURVE('',#160613,(#160618,#160624),.PCURVE_S1.); -#160613 = CIRCLE('',#160614,1.E-001); -#160614 = AXIS2_PLACEMENT_3D('',#160615,#160616,#160617); -#160615 = CARTESIAN_POINT('',(-1.695,0.665,-2.141803043818)); -#160616 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160617 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160618 = PCURVE('',#160552,#160619); -#160619 = DEFINITIONAL_REPRESENTATION('',(#160620),#160623); -#160620 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160621,#160622), +#162951 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#162952 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#162953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162954 = ORIENTED_EDGE('',*,*,#162955,.F.); +#162955 = EDGE_CURVE('',#162852,#162929,#162956,.T.); +#162956 = SURFACE_CURVE('',#162957,(#162961,#162968),.PCURVE_S1.); +#162957 = LINE('',#162958,#162959); +#162958 = CARTESIAN_POINT('',(-2.115,0.298978581017,-2.290944451524)); +#162959 = VECTOR('',#162960,1.); +#162960 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#162961 = PCURVE('',#162868,#162962); +#162962 = DEFINITIONAL_REPRESENTATION('',(#162963),#162967); +#162963 = LINE('',#162964,#162965); +#162964 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#162965 = VECTOR('',#162966,1.); +#162966 = DIRECTION('',(-1.,0.E+000)); +#162967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162968 = PCURVE('',#162526,#162969); +#162969 = DEFINITIONAL_REPRESENTATION('',(#162970),#162974); +#162970 = LINE('',#162971,#162972); +#162971 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#162972 = VECTOR('',#162973,1.); +#162973 = DIRECTION('',(0.130759809642,0.991414077055)); +#162974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162975 = ORIENTED_EDGE('',*,*,#162851,.T.); +#162976 = ORIENTED_EDGE('',*,*,#162977,.F.); +#162977 = EDGE_CURVE('',#162927,#162854,#162978,.T.); +#162978 = SURFACE_CURVE('',#162979,(#162983,#162990),.PCURVE_S1.); +#162979 = LINE('',#162980,#162981); +#162980 = CARTESIAN_POINT('',(-1.695,0.678075980964,-2.240944451524)); +#162981 = VECTOR('',#162982,1.); +#162982 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#162983 = PCURVE('',#162868,#162984); +#162984 = DEFINITIONAL_REPRESENTATION('',(#162985),#162989); +#162985 = LINE('',#162986,#162987); +#162986 = CARTESIAN_POINT('',(0.E+000,0.21)); +#162987 = VECTOR('',#162988,1.); +#162988 = DIRECTION('',(1.,0.E+000)); +#162989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162990 = PCURVE('',#162473,#162991); +#162991 = DEFINITIONAL_REPRESENTATION('',(#162992),#162996); +#162992 = LINE('',#162993,#162994); +#162993 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#162994 = VECTOR('',#162995,1.); +#162995 = DIRECTION('',(0.130759809642,-0.991414077055)); +#162996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#162997 = ADVANCED_FACE('',(#162998),#162944,.F.); +#162998 = FACE_BOUND('',#162999,.F.); +#162999 = EDGE_LOOP('',(#163000,#163027,#163028,#163055)); +#163000 = ORIENTED_EDGE('',*,*,#163001,.T.); +#163001 = EDGE_CURVE('',#163002,#162927,#163004,.T.); +#163002 = VERTEX_POINT('',#163003); +#163003 = CARTESIAN_POINT('',(-1.695,0.765,-2.141803043818)); +#163004 = SURFACE_CURVE('',#163005,(#163010,#163016),.PCURVE_S1.); +#163005 = CIRCLE('',#163006,1.E-001); +#163006 = AXIS2_PLACEMENT_3D('',#163007,#163008,#163009); +#163007 = CARTESIAN_POINT('',(-1.695,0.665,-2.141803043818)); +#163008 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163009 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163010 = PCURVE('',#162944,#163011); +#163011 = DEFINITIONAL_REPRESENTATION('',(#163012),#163015); +#163012 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163013,#163014), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#160621 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#160622 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#160623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163013 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#163014 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#163015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160624 = PCURVE('',#160081,#160625); -#160625 = DEFINITIONAL_REPRESENTATION('',(#160626),#160634); -#160626 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160627,#160628,#160629, - #160630,#160631,#160632,#160633),.UNSPECIFIED.,.T.,.F.) +#163016 = PCURVE('',#162473,#163017); +#163017 = DEFINITIONAL_REPRESENTATION('',(#163018),#163026); +#163018 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163019,#163020,#163021, + #163022,#163023,#163024,#163025),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160627 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#160628 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#160629 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#160630 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#160631 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#160632 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#160633 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#160634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160635 = ORIENTED_EDGE('',*,*,#160534,.T.); -#160636 = ORIENTED_EDGE('',*,*,#160637,.T.); -#160637 = EDGE_CURVE('',#160537,#160638,#160640,.T.); -#160638 = VERTEX_POINT('',#160639); -#160639 = CARTESIAN_POINT('',(-2.115,0.765,-2.141803043818)); -#160640 = SURFACE_CURVE('',#160641,(#160646,#160652),.PCURVE_S1.); -#160641 = CIRCLE('',#160642,1.E-001); -#160642 = AXIS2_PLACEMENT_3D('',#160643,#160644,#160645); -#160643 = CARTESIAN_POINT('',(-2.115,0.665,-2.141803043818)); -#160644 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160645 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); -#160646 = PCURVE('',#160552,#160647); -#160647 = DEFINITIONAL_REPRESENTATION('',(#160648),#160651); -#160648 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160649,#160650), +#163019 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#163020 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#163021 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#163022 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#163023 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#163024 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#163025 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#163026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163027 = ORIENTED_EDGE('',*,*,#162926,.T.); +#163028 = ORIENTED_EDGE('',*,*,#163029,.T.); +#163029 = EDGE_CURVE('',#162929,#163030,#163032,.T.); +#163030 = VERTEX_POINT('',#163031); +#163031 = CARTESIAN_POINT('',(-2.115,0.765,-2.141803043818)); +#163032 = SURFACE_CURVE('',#163033,(#163038,#163044),.PCURVE_S1.); +#163033 = CIRCLE('',#163034,1.E-001); +#163034 = AXIS2_PLACEMENT_3D('',#163035,#163036,#163037); +#163035 = CARTESIAN_POINT('',(-2.115,0.665,-2.141803043818)); +#163036 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163037 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); +#163038 = PCURVE('',#162944,#163039); +#163039 = DEFINITIONAL_REPRESENTATION('',(#163040),#163043); +#163040 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163041,#163042), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#160649 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#160650 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#160651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163041 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#163042 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#163043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160652 = PCURVE('',#160134,#160653); -#160653 = DEFINITIONAL_REPRESENTATION('',(#160654),#160662); -#160654 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160655,#160656,#160657, - #160658,#160659,#160660,#160661),.UNSPECIFIED.,.T.,.F.) +#163044 = PCURVE('',#162526,#163045); +#163045 = DEFINITIONAL_REPRESENTATION('',(#163046),#163054); +#163046 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163047,#163048,#163049, + #163050,#163051,#163052,#163053),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160655 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#160656 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#160657 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#160658 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#160659 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#160660 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#160661 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#160662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160663 = ORIENTED_EDGE('',*,*,#160664,.T.); -#160664 = EDGE_CURVE('',#160638,#160610,#160665,.T.); -#160665 = SURFACE_CURVE('',#160666,(#160670,#160676),.PCURVE_S1.); -#160666 = LINE('',#160667,#160668); -#160667 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); -#160668 = VECTOR('',#160669,1.); -#160669 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160670 = PCURVE('',#160552,#160671); -#160671 = DEFINITIONAL_REPRESENTATION('',(#160672),#160675); -#160672 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160673,#160674), +#163047 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#163048 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#163049 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#163050 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#163051 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#163052 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#163053 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#163054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163055 = ORIENTED_EDGE('',*,*,#163056,.T.); +#163056 = EDGE_CURVE('',#163030,#163002,#163057,.T.); +#163057 = SURFACE_CURVE('',#163058,(#163062,#163068),.PCURVE_S1.); +#163058 = LINE('',#163059,#163060); +#163059 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); +#163060 = VECTOR('',#163061,1.); +#163061 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163062 = PCURVE('',#162944,#163063); +#163063 = DEFINITIONAL_REPRESENTATION('',(#163064),#163067); +#163064 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163065,#163066), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.75,-2.33),.PIECEWISE_BEZIER_KNOTS.); -#160673 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#160674 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#160675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160676 = PCURVE('',#159360,#160677); -#160677 = DEFINITIONAL_REPRESENTATION('',(#160678),#160682); -#160678 = LINE('',#160679,#160680); -#160679 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#160680 = VECTOR('',#160681,1.); -#160681 = DIRECTION('',(0.E+000,1.)); -#160682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160683 = ADVANCED_FACE('',(#160684),#160698,.T.); -#160684 = FACE_BOUND('',#160685,.T.); -#160685 = EDGE_LOOP('',(#160686,#160720,#160743,#160770)); -#160686 = ORIENTED_EDGE('',*,*,#160687,.F.); -#160687 = EDGE_CURVE('',#160688,#160690,#160692,.T.); -#160688 = VERTEX_POINT('',#160689); -#160689 = CARTESIAN_POINT('',(-2.115,0.706843139085,2.459055548476)); -#160690 = VERTEX_POINT('',#160691); -#160691 = CARTESIAN_POINT('',(-1.695,0.706843139085,2.459055548476)); -#160692 = SURFACE_CURVE('',#160693,(#160697,#160709),.PCURVE_S1.); -#160693 = LINE('',#160694,#160695); -#160694 = CARTESIAN_POINT('',(-1.905,0.706843139085,2.459055548476)); -#160695 = VECTOR('',#160696,1.); -#160696 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160697 = PCURVE('',#160698,#160703); -#160698 = PLANE('',#160699); -#160699 = AXIS2_PLACEMENT_3D('',#160700,#160701,#160702); -#160700 = CARTESIAN_POINT('',(-1.905,0.706843139085,2.459055548476)); -#160701 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); -#160702 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#160703 = DEFINITIONAL_REPRESENTATION('',(#160704),#160708); -#160704 = LINE('',#160705,#160706); -#160705 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#160706 = VECTOR('',#160707,1.); -#160707 = DIRECTION('',(0.E+000,1.)); -#160708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160709 = PCURVE('',#160710,#160715); -#160710 = CYLINDRICAL_SURFACE('',#160711,0.32); -#160711 = AXIS2_PLACEMENT_3D('',#160712,#160713,#160714); -#160712 = CARTESIAN_POINT('',(-1.905,0.665,2.141803043818)); -#160713 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160714 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160715 = DEFINITIONAL_REPRESENTATION('',(#160716),#160719); -#160716 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160717,#160718), +#163065 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#163066 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#163067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163068 = PCURVE('',#161752,#163069); +#163069 = DEFINITIONAL_REPRESENTATION('',(#163070),#163074); +#163070 = LINE('',#163071,#163072); +#163071 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#163072 = VECTOR('',#163073,1.); +#163073 = DIRECTION('',(0.E+000,1.)); +#163074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163075 = ADVANCED_FACE('',(#163076),#163090,.T.); +#163076 = FACE_BOUND('',#163077,.T.); +#163077 = EDGE_LOOP('',(#163078,#163112,#163135,#163162)); +#163078 = ORIENTED_EDGE('',*,*,#163079,.F.); +#163079 = EDGE_CURVE('',#163080,#163082,#163084,.T.); +#163080 = VERTEX_POINT('',#163081); +#163081 = CARTESIAN_POINT('',(-2.115,0.706843139085,2.459055548476)); +#163082 = VERTEX_POINT('',#163083); +#163083 = CARTESIAN_POINT('',(-1.695,0.706843139085,2.459055548476)); +#163084 = SURFACE_CURVE('',#163085,(#163089,#163101),.PCURVE_S1.); +#163085 = LINE('',#163086,#163087); +#163086 = CARTESIAN_POINT('',(-1.905,0.706843139085,2.459055548476)); +#163087 = VECTOR('',#163088,1.); +#163088 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163089 = PCURVE('',#163090,#163095); +#163090 = PLANE('',#163091); +#163091 = AXIS2_PLACEMENT_3D('',#163092,#163093,#163094); +#163092 = CARTESIAN_POINT('',(-1.905,0.706843139085,2.459055548476)); +#163093 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); +#163094 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#163095 = DEFINITIONAL_REPRESENTATION('',(#163096),#163100); +#163096 = LINE('',#163097,#163098); +#163097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#163098 = VECTOR('',#163099,1.); +#163099 = DIRECTION('',(0.E+000,1.)); +#163100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163101 = PCURVE('',#163102,#163107); +#163102 = CYLINDRICAL_SURFACE('',#163103,0.32); +#163103 = AXIS2_PLACEMENT_3D('',#163104,#163105,#163106); +#163104 = CARTESIAN_POINT('',(-1.905,0.665,2.141803043818)); +#163105 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163106 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163107 = DEFINITIONAL_REPRESENTATION('',(#163108),#163111); +#163108 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163109,#163110), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160717 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#160718 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#160719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160720 = ORIENTED_EDGE('',*,*,#160721,.F.); -#160721 = EDGE_CURVE('',#160722,#160688,#160724,.T.); -#160722 = VERTEX_POINT('',#160723); -#160723 = CARTESIAN_POINT('',(-2.115,0.327745739138,2.509055548476)); -#160724 = SURFACE_CURVE('',#160725,(#160729,#160736),.PCURVE_S1.); -#160725 = LINE('',#160726,#160727); -#160726 = CARTESIAN_POINT('',(-2.115,0.327745739138,2.509055548476)); -#160727 = VECTOR('',#160728,1.); -#160728 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#160729 = PCURVE('',#160698,#160730); -#160730 = DEFINITIONAL_REPRESENTATION('',(#160731),#160735); -#160731 = LINE('',#160732,#160733); -#160732 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#160733 = VECTOR('',#160734,1.); -#160734 = DIRECTION('',(-1.,0.E+000)); -#160735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160736 = PCURVE('',#160134,#160737); -#160737 = DEFINITIONAL_REPRESENTATION('',(#160738),#160742); -#160738 = LINE('',#160739,#160740); -#160739 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#160740 = VECTOR('',#160741,1.); -#160741 = DIRECTION('',(-0.130759809642,0.991414077055)); -#160742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160743 = ORIENTED_EDGE('',*,*,#160744,.T.); -#160744 = EDGE_CURVE('',#160722,#160745,#160747,.T.); -#160745 = VERTEX_POINT('',#160746); -#160746 = CARTESIAN_POINT('',(-1.695,0.327745739138,2.509055548476)); -#160747 = SURFACE_CURVE('',#160748,(#160752,#160759),.PCURVE_S1.); -#160748 = LINE('',#160749,#160750); -#160749 = CARTESIAN_POINT('',(-1.905,0.327745739138,2.509055548476)); -#160750 = VECTOR('',#160751,1.); -#160751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160752 = PCURVE('',#160698,#160753); -#160753 = DEFINITIONAL_REPRESENTATION('',(#160754),#160758); -#160754 = LINE('',#160755,#160756); -#160755 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#160756 = VECTOR('',#160757,1.); -#160757 = DIRECTION('',(0.E+000,1.)); -#160758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160759 = PCURVE('',#160760,#160765); -#160760 = CYLINDRICAL_SURFACE('',#160761,9.999999999999E-002); -#160761 = AXIS2_PLACEMENT_3D('',#160762,#160763,#160764); -#160762 = CARTESIAN_POINT('',(-1.905,0.340821720102,2.608196956182)); -#160763 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160764 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160765 = DEFINITIONAL_REPRESENTATION('',(#160766),#160769); -#160766 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160767,#160768), +#163109 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#163110 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#163111 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163112 = ORIENTED_EDGE('',*,*,#163113,.F.); +#163113 = EDGE_CURVE('',#163114,#163080,#163116,.T.); +#163114 = VERTEX_POINT('',#163115); +#163115 = CARTESIAN_POINT('',(-2.115,0.327745739138,2.509055548476)); +#163116 = SURFACE_CURVE('',#163117,(#163121,#163128),.PCURVE_S1.); +#163117 = LINE('',#163118,#163119); +#163118 = CARTESIAN_POINT('',(-2.115,0.327745739138,2.509055548476)); +#163119 = VECTOR('',#163120,1.); +#163120 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#163121 = PCURVE('',#163090,#163122); +#163122 = DEFINITIONAL_REPRESENTATION('',(#163123),#163127); +#163123 = LINE('',#163124,#163125); +#163124 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#163125 = VECTOR('',#163126,1.); +#163126 = DIRECTION('',(-1.,0.E+000)); +#163127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163128 = PCURVE('',#162526,#163129); +#163129 = DEFINITIONAL_REPRESENTATION('',(#163130),#163134); +#163130 = LINE('',#163131,#163132); +#163131 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#163132 = VECTOR('',#163133,1.); +#163133 = DIRECTION('',(-0.130759809642,0.991414077055)); +#163134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163135 = ORIENTED_EDGE('',*,*,#163136,.T.); +#163136 = EDGE_CURVE('',#163114,#163137,#163139,.T.); +#163137 = VERTEX_POINT('',#163138); +#163138 = CARTESIAN_POINT('',(-1.695,0.327745739138,2.509055548476)); +#163139 = SURFACE_CURVE('',#163140,(#163144,#163151),.PCURVE_S1.); +#163140 = LINE('',#163141,#163142); +#163141 = CARTESIAN_POINT('',(-1.905,0.327745739138,2.509055548476)); +#163142 = VECTOR('',#163143,1.); +#163143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163144 = PCURVE('',#163090,#163145); +#163145 = DEFINITIONAL_REPRESENTATION('',(#163146),#163150); +#163146 = LINE('',#163147,#163148); +#163147 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#163148 = VECTOR('',#163149,1.); +#163149 = DIRECTION('',(0.E+000,1.)); +#163150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163151 = PCURVE('',#163152,#163157); +#163152 = CYLINDRICAL_SURFACE('',#163153,9.999999999999E-002); +#163153 = AXIS2_PLACEMENT_3D('',#163154,#163155,#163156); +#163154 = CARTESIAN_POINT('',(-1.905,0.340821720102,2.608196956182)); +#163155 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163156 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163157 = DEFINITIONAL_REPRESENTATION('',(#163158),#163161); +#163158 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163159,#163160), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160767 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160768 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160770 = ORIENTED_EDGE('',*,*,#160771,.F.); -#160771 = EDGE_CURVE('',#160690,#160745,#160772,.T.); -#160772 = SURFACE_CURVE('',#160773,(#160777,#160784),.PCURVE_S1.); -#160773 = LINE('',#160774,#160775); -#160774 = CARTESIAN_POINT('',(-1.695,0.706843139085,2.459055548476)); -#160775 = VECTOR('',#160776,1.); -#160776 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#160777 = PCURVE('',#160698,#160778); -#160778 = DEFINITIONAL_REPRESENTATION('',(#160779),#160783); -#160779 = LINE('',#160780,#160781); -#160780 = CARTESIAN_POINT('',(0.E+000,0.21)); -#160781 = VECTOR('',#160782,1.); -#160782 = DIRECTION('',(1.,0.E+000)); -#160783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160784 = PCURVE('',#160785,#160790); -#160785 = PLANE('',#160786); -#160786 = AXIS2_PLACEMENT_3D('',#160787,#160788,#160789); -#160787 = CARTESIAN_POINT('',(-1.695,0.875,0.E+000)); -#160788 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160789 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#160790 = DEFINITIONAL_REPRESENTATION('',(#160791),#160795); -#160791 = LINE('',#160792,#160793); -#160792 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#160793 = VECTOR('',#160794,1.); -#160794 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#160795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163159 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163160 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160796 = ADVANCED_FACE('',(#160797),#160760,.F.); -#160797 = FACE_BOUND('',#160798,.F.); -#160798 = EDGE_LOOP('',(#160799,#160826,#160853,#160878)); -#160799 = ORIENTED_EDGE('',*,*,#160800,.T.); -#160800 = EDGE_CURVE('',#160745,#160801,#160803,.T.); -#160801 = VERTEX_POINT('',#160802); -#160802 = CARTESIAN_POINT('',(-1.695,0.240958766627,2.602963360557)); -#160803 = SURFACE_CURVE('',#160804,(#160809,#160815),.PCURVE_S1.); -#160804 = CIRCLE('',#160805,9.999999999999E-002); -#160805 = AXIS2_PLACEMENT_3D('',#160806,#160807,#160808); -#160806 = CARTESIAN_POINT('',(-1.695,0.340821720102,2.608196956182)); -#160807 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160808 = DIRECTION('',(0.E+000,0.E+000,1.)); -#160809 = PCURVE('',#160760,#160810); -#160810 = DEFINITIONAL_REPRESENTATION('',(#160811),#160814); -#160811 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160812,#160813), +#163162 = ORIENTED_EDGE('',*,*,#163163,.F.); +#163163 = EDGE_CURVE('',#163082,#163137,#163164,.T.); +#163164 = SURFACE_CURVE('',#163165,(#163169,#163176),.PCURVE_S1.); +#163165 = LINE('',#163166,#163167); +#163166 = CARTESIAN_POINT('',(-1.695,0.706843139085,2.459055548476)); +#163167 = VECTOR('',#163168,1.); +#163168 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#163169 = PCURVE('',#163090,#163170); +#163170 = DEFINITIONAL_REPRESENTATION('',(#163171),#163175); +#163171 = LINE('',#163172,#163173); +#163172 = CARTESIAN_POINT('',(0.E+000,0.21)); +#163173 = VECTOR('',#163174,1.); +#163174 = DIRECTION('',(1.,0.E+000)); +#163175 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163176 = PCURVE('',#163177,#163182); +#163177 = PLANE('',#163178); +#163178 = AXIS2_PLACEMENT_3D('',#163179,#163180,#163181); +#163179 = CARTESIAN_POINT('',(-1.695,0.875,0.E+000)); +#163180 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163181 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163182 = DEFINITIONAL_REPRESENTATION('',(#163183),#163187); +#163183 = LINE('',#163184,#163185); +#163184 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#163185 = VECTOR('',#163186,1.); +#163186 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#163187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163188 = ADVANCED_FACE('',(#163189),#163152,.F.); +#163189 = FACE_BOUND('',#163190,.F.); +#163190 = EDGE_LOOP('',(#163191,#163218,#163245,#163270)); +#163191 = ORIENTED_EDGE('',*,*,#163192,.T.); +#163192 = EDGE_CURVE('',#163137,#163193,#163195,.T.); +#163193 = VERTEX_POINT('',#163194); +#163194 = CARTESIAN_POINT('',(-1.695,0.240958766627,2.602963360557)); +#163195 = SURFACE_CURVE('',#163196,(#163201,#163207),.PCURVE_S1.); +#163196 = CIRCLE('',#163197,9.999999999999E-002); +#163197 = AXIS2_PLACEMENT_3D('',#163198,#163199,#163200); +#163198 = CARTESIAN_POINT('',(-1.695,0.340821720102,2.608196956182)); +#163199 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163200 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163201 = PCURVE('',#163152,#163202); +#163202 = DEFINITIONAL_REPRESENTATION('',(#163203),#163206); +#163203 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163204,#163205), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#160812 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#160813 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163204 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163205 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160815 = PCURVE('',#160785,#160816); -#160816 = DEFINITIONAL_REPRESENTATION('',(#160817),#160825); -#160817 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160818,#160819,#160820, - #160821,#160822,#160823,#160824),.UNSPECIFIED.,.T.,.F.) +#163207 = PCURVE('',#163177,#163208); +#163208 = DEFINITIONAL_REPRESENTATION('',(#163209),#163217); +#163209 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163210,#163211,#163212, + #163213,#163214,#163215,#163216),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160818 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#160819 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#160820 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#160821 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#160822 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#160823 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#160824 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#160825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160826 = ORIENTED_EDGE('',*,*,#160827,.T.); -#160827 = EDGE_CURVE('',#160801,#160828,#160830,.T.); -#160828 = VERTEX_POINT('',#160829); -#160829 = CARTESIAN_POINT('',(-2.115,0.240958766627,2.602963360557)); -#160830 = SURFACE_CURVE('',#160831,(#160835,#160841),.PCURVE_S1.); -#160831 = LINE('',#160832,#160833); -#160832 = CARTESIAN_POINT('',(-1.905,0.240958766627,2.602963360557)); -#160833 = VECTOR('',#160834,1.); -#160834 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160835 = PCURVE('',#160760,#160836); -#160836 = DEFINITIONAL_REPRESENTATION('',(#160837),#160840); -#160837 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160838,#160839), +#163210 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#163211 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#163212 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#163213 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#163214 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#163215 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#163216 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#163217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163218 = ORIENTED_EDGE('',*,*,#163219,.T.); +#163219 = EDGE_CURVE('',#163193,#163220,#163222,.T.); +#163220 = VERTEX_POINT('',#163221); +#163221 = CARTESIAN_POINT('',(-2.115,0.240958766627,2.602963360557)); +#163222 = SURFACE_CURVE('',#163223,(#163227,#163233),.PCURVE_S1.); +#163223 = LINE('',#163224,#163225); +#163224 = CARTESIAN_POINT('',(-1.905,0.240958766627,2.602963360557)); +#163225 = VECTOR('',#163226,1.); +#163226 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163227 = PCURVE('',#163152,#163228); +#163228 = DEFINITIONAL_REPRESENTATION('',(#163229),#163232); +#163229 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163230,#163231), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#160838 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#160839 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160841 = PCURVE('',#160842,#160847); -#160842 = PLANE('',#160843); -#160843 = AXIS2_PLACEMENT_3D('',#160844,#160845,#160846); -#160844 = CARTESIAN_POINT('',(-1.905,0.240958766627,2.602963360557)); -#160845 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); -#160846 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#160847 = DEFINITIONAL_REPRESENTATION('',(#160848),#160852); -#160848 = LINE('',#160849,#160850); -#160849 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); -#160850 = VECTOR('',#160851,1.); -#160851 = DIRECTION('',(0.E+000,-1.)); -#160852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160853 = ORIENTED_EDGE('',*,*,#160854,.T.); -#160854 = EDGE_CURVE('',#160828,#160722,#160855,.T.); -#160855 = SURFACE_CURVE('',#160856,(#160861,#160867),.PCURVE_S1.); -#160856 = CIRCLE('',#160857,9.999999999999E-002); -#160857 = AXIS2_PLACEMENT_3D('',#160858,#160859,#160860); -#160858 = CARTESIAN_POINT('',(-2.115,0.340821720102,2.608196956182)); -#160859 = DIRECTION('',(1.,0.E+000,0.E+000)); -#160860 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); -#160861 = PCURVE('',#160760,#160862); -#160862 = DEFINITIONAL_REPRESENTATION('',(#160863),#160866); -#160863 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#160864,#160865), +#163230 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163231 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163233 = PCURVE('',#163234,#163239); +#163234 = PLANE('',#163235); +#163235 = AXIS2_PLACEMENT_3D('',#163236,#163237,#163238); +#163236 = CARTESIAN_POINT('',(-1.905,0.240958766627,2.602963360557)); +#163237 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); +#163238 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#163239 = DEFINITIONAL_REPRESENTATION('',(#163240),#163244); +#163240 = LINE('',#163241,#163242); +#163241 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); +#163242 = VECTOR('',#163243,1.); +#163243 = DIRECTION('',(0.E+000,-1.)); +#163244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163245 = ORIENTED_EDGE('',*,*,#163246,.T.); +#163246 = EDGE_CURVE('',#163220,#163114,#163247,.T.); +#163247 = SURFACE_CURVE('',#163248,(#163253,#163259),.PCURVE_S1.); +#163248 = CIRCLE('',#163249,9.999999999999E-002); +#163249 = AXIS2_PLACEMENT_3D('',#163250,#163251,#163252); +#163250 = CARTESIAN_POINT('',(-2.115,0.340821720102,2.608196956182)); +#163251 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163252 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); +#163253 = PCURVE('',#163152,#163254); +#163254 = DEFINITIONAL_REPRESENTATION('',(#163255),#163258); +#163255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163256,#163257), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#160864 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#160865 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#160866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163256 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163257 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#160867 = PCURVE('',#160134,#160868); -#160868 = DEFINITIONAL_REPRESENTATION('',(#160869),#160877); -#160869 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#160870,#160871,#160872, - #160873,#160874,#160875,#160876),.UNSPECIFIED.,.F.,.F.) +#163259 = PCURVE('',#162526,#163260); +#163260 = DEFINITIONAL_REPRESENTATION('',(#163261),#163269); +#163261 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163262,#163263,#163264, + #163265,#163266,#163267,#163268),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#160870 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#160871 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#160872 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#160873 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#160874 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#160875 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#160876 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#160877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160878 = ORIENTED_EDGE('',*,*,#160744,.T.); -#160879 = ADVANCED_FACE('',(#160880),#160842,.T.); -#160880 = FACE_BOUND('',#160881,.T.); -#160881 = EDGE_LOOP('',(#160882,#160883,#160906,#160934)); -#160882 = ORIENTED_EDGE('',*,*,#160827,.T.); -#160883 = ORIENTED_EDGE('',*,*,#160884,.F.); -#160884 = EDGE_CURVE('',#160885,#160828,#160887,.T.); -#160885 = VERTEX_POINT('',#160886); -#160886 = CARTESIAN_POINT('',(-2.115,0.219849248823,3.005756955187)); -#160887 = SURFACE_CURVE('',#160888,(#160892,#160899),.PCURVE_S1.); -#160888 = LINE('',#160889,#160890); -#160889 = CARTESIAN_POINT('',(-2.115,0.219849248823,3.005756955187)); -#160890 = VECTOR('',#160891,1.); -#160891 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#160892 = PCURVE('',#160842,#160893); -#160893 = DEFINITIONAL_REPRESENTATION('',(#160894),#160898); -#160894 = LINE('',#160895,#160896); -#160895 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#160896 = VECTOR('',#160897,1.); -#160897 = DIRECTION('',(-1.,0.E+000)); -#160898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160899 = PCURVE('',#160134,#160900); -#160900 = DEFINITIONAL_REPRESENTATION('',(#160901),#160905); -#160901 = LINE('',#160902,#160903); -#160902 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#160903 = VECTOR('',#160904,1.); -#160904 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#160905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160906 = ORIENTED_EDGE('',*,*,#160907,.F.); -#160907 = EDGE_CURVE('',#160908,#160885,#160910,.T.); -#160908 = VERTEX_POINT('',#160909); -#160909 = CARTESIAN_POINT('',(-1.695,0.219849248823,3.005756955187)); -#160910 = SURFACE_CURVE('',#160911,(#160915,#160922),.PCURVE_S1.); -#160911 = LINE('',#160912,#160913); -#160912 = CARTESIAN_POINT('',(-1.905,0.219849248823,3.005756955187)); -#160913 = VECTOR('',#160914,1.); -#160914 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160915 = PCURVE('',#160842,#160916); -#160916 = DEFINITIONAL_REPRESENTATION('',(#160917),#160921); -#160917 = LINE('',#160918,#160919); -#160918 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#160919 = VECTOR('',#160920,1.); -#160920 = DIRECTION('',(0.E+000,-1.)); -#160921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160922 = PCURVE('',#160923,#160928); -#160923 = PLANE('',#160924); -#160924 = AXIS2_PLACEMENT_3D('',#160925,#160926,#160927); -#160925 = CARTESIAN_POINT('',(-1.905,0.11,3.)); -#160926 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); -#160927 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#160928 = DEFINITIONAL_REPRESENTATION('',(#160929),#160933); -#160929 = LINE('',#160930,#160931); -#160930 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#160931 = VECTOR('',#160932,1.); -#160932 = DIRECTION('',(0.E+000,-1.)); -#160933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160934 = ORIENTED_EDGE('',*,*,#160935,.F.); -#160935 = EDGE_CURVE('',#160801,#160908,#160936,.T.); -#160936 = SURFACE_CURVE('',#160937,(#160941,#160948),.PCURVE_S1.); -#160937 = LINE('',#160938,#160939); -#160938 = CARTESIAN_POINT('',(-1.695,0.240958766627,2.602963360557)); -#160939 = VECTOR('',#160940,1.); -#160940 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#160941 = PCURVE('',#160842,#160942); -#160942 = DEFINITIONAL_REPRESENTATION('',(#160943),#160947); -#160943 = LINE('',#160944,#160945); -#160944 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); -#160945 = VECTOR('',#160946,1.); -#160946 = DIRECTION('',(1.,0.E+000)); -#160947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160948 = PCURVE('',#160785,#160949); -#160949 = DEFINITIONAL_REPRESENTATION('',(#160950),#160954); -#160950 = LINE('',#160951,#160952); -#160951 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#160952 = VECTOR('',#160953,1.); -#160953 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#160954 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160955 = ADVANCED_FACE('',(#160956),#160923,.T.); -#160956 = FACE_BOUND('',#160957,.T.); -#160957 = EDGE_LOOP('',(#160958,#160988,#161009,#161010)); -#160958 = ORIENTED_EDGE('',*,*,#160959,.F.); -#160959 = EDGE_CURVE('',#160960,#160962,#160964,.T.); -#160960 = VERTEX_POINT('',#160961); -#160961 = CARTESIAN_POINT('',(-1.695,1.507511769915E-004,2.994243044813) - ); -#160962 = VERTEX_POINT('',#160963); -#160963 = CARTESIAN_POINT('',(-2.115,1.507511769916E-004,2.994243044813) - ); -#160964 = SURFACE_CURVE('',#160965,(#160969,#160976),.PCURVE_S1.); -#160965 = LINE('',#160966,#160967); -#160966 = CARTESIAN_POINT('',(-1.905,1.507511769963E-004,2.994243044813) +#163262 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#163263 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#163264 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#163265 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#163266 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#163267 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#163268 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#163269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163270 = ORIENTED_EDGE('',*,*,#163136,.T.); +#163271 = ADVANCED_FACE('',(#163272),#163234,.T.); +#163272 = FACE_BOUND('',#163273,.T.); +#163273 = EDGE_LOOP('',(#163274,#163275,#163298,#163326)); +#163274 = ORIENTED_EDGE('',*,*,#163219,.T.); +#163275 = ORIENTED_EDGE('',*,*,#163276,.F.); +#163276 = EDGE_CURVE('',#163277,#163220,#163279,.T.); +#163277 = VERTEX_POINT('',#163278); +#163278 = CARTESIAN_POINT('',(-2.115,0.219849248823,3.005756955187)); +#163279 = SURFACE_CURVE('',#163280,(#163284,#163291),.PCURVE_S1.); +#163280 = LINE('',#163281,#163282); +#163281 = CARTESIAN_POINT('',(-2.115,0.219849248823,3.005756955187)); +#163282 = VECTOR('',#163283,1.); +#163283 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#163284 = PCURVE('',#163234,#163285); +#163285 = DEFINITIONAL_REPRESENTATION('',(#163286),#163290); +#163286 = LINE('',#163287,#163288); +#163287 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#163288 = VECTOR('',#163289,1.); +#163289 = DIRECTION('',(-1.,0.E+000)); +#163290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163291 = PCURVE('',#162526,#163292); +#163292 = DEFINITIONAL_REPRESENTATION('',(#163293),#163297); +#163293 = LINE('',#163294,#163295); +#163294 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#163295 = VECTOR('',#163296,1.); +#163296 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#163297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163298 = ORIENTED_EDGE('',*,*,#163299,.F.); +#163299 = EDGE_CURVE('',#163300,#163277,#163302,.T.); +#163300 = VERTEX_POINT('',#163301); +#163301 = CARTESIAN_POINT('',(-1.695,0.219849248823,3.005756955187)); +#163302 = SURFACE_CURVE('',#163303,(#163307,#163314),.PCURVE_S1.); +#163303 = LINE('',#163304,#163305); +#163304 = CARTESIAN_POINT('',(-1.905,0.219849248823,3.005756955187)); +#163305 = VECTOR('',#163306,1.); +#163306 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163307 = PCURVE('',#163234,#163308); +#163308 = DEFINITIONAL_REPRESENTATION('',(#163309),#163313); +#163309 = LINE('',#163310,#163311); +#163310 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#163311 = VECTOR('',#163312,1.); +#163312 = DIRECTION('',(0.E+000,-1.)); +#163313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163314 = PCURVE('',#163315,#163320); +#163315 = PLANE('',#163316); +#163316 = AXIS2_PLACEMENT_3D('',#163317,#163318,#163319); +#163317 = CARTESIAN_POINT('',(-1.905,0.11,3.)); +#163318 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); +#163319 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#163320 = DEFINITIONAL_REPRESENTATION('',(#163321),#163325); +#163321 = LINE('',#163322,#163323); +#163322 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#163323 = VECTOR('',#163324,1.); +#163324 = DIRECTION('',(0.E+000,-1.)); +#163325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163326 = ORIENTED_EDGE('',*,*,#163327,.F.); +#163327 = EDGE_CURVE('',#163193,#163300,#163328,.T.); +#163328 = SURFACE_CURVE('',#163329,(#163333,#163340),.PCURVE_S1.); +#163329 = LINE('',#163330,#163331); +#163330 = CARTESIAN_POINT('',(-1.695,0.240958766627,2.602963360557)); +#163331 = VECTOR('',#163332,1.); +#163332 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#163333 = PCURVE('',#163234,#163334); +#163334 = DEFINITIONAL_REPRESENTATION('',(#163335),#163339); +#163335 = LINE('',#163336,#163337); +#163336 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); +#163337 = VECTOR('',#163338,1.); +#163338 = DIRECTION('',(1.,0.E+000)); +#163339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163340 = PCURVE('',#163177,#163341); +#163341 = DEFINITIONAL_REPRESENTATION('',(#163342),#163346); +#163342 = LINE('',#163343,#163344); +#163343 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#163344 = VECTOR('',#163345,1.); +#163345 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#163346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163347 = ADVANCED_FACE('',(#163348),#163315,.T.); +#163348 = FACE_BOUND('',#163349,.T.); +#163349 = EDGE_LOOP('',(#163350,#163380,#163401,#163402)); +#163350 = ORIENTED_EDGE('',*,*,#163351,.F.); +#163351 = EDGE_CURVE('',#163352,#163354,#163356,.T.); +#163352 = VERTEX_POINT('',#163353); +#163353 = CARTESIAN_POINT('',(-1.695,1.507511769915E-004,2.994243044813) + ); +#163354 = VERTEX_POINT('',#163355); +#163355 = CARTESIAN_POINT('',(-2.115,1.507511769916E-004,2.994243044813) + ); +#163356 = SURFACE_CURVE('',#163357,(#163361,#163368),.PCURVE_S1.); +#163357 = LINE('',#163358,#163359); +#163358 = CARTESIAN_POINT('',(-1.905,1.507511769963E-004,2.994243044813) ); -#160967 = VECTOR('',#160968,1.); -#160968 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#160969 = PCURVE('',#160923,#160970); -#160970 = DEFINITIONAL_REPRESENTATION('',(#160971),#160975); -#160971 = LINE('',#160972,#160973); -#160972 = CARTESIAN_POINT('',(0.11,0.E+000)); -#160973 = VECTOR('',#160974,1.); -#160974 = DIRECTION('',(0.E+000,-1.)); -#160975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160976 = PCURVE('',#160977,#160982); -#160977 = PLANE('',#160978); -#160978 = AXIS2_PLACEMENT_3D('',#160979,#160980,#160981); -#160979 = CARTESIAN_POINT('',(-1.905,2.126026898096E-002,2.591449450184) - ); -#160980 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); -#160981 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#160982 = DEFINITIONAL_REPRESENTATION('',(#160983),#160987); -#160983 = LINE('',#160984,#160985); -#160984 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#160985 = VECTOR('',#160986,1.); -#160986 = DIRECTION('',(0.E+000,-1.)); -#160987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#160988 = ORIENTED_EDGE('',*,*,#160989,.F.); -#160989 = EDGE_CURVE('',#160908,#160960,#160990,.T.); -#160990 = SURFACE_CURVE('',#160991,(#160995,#161002),.PCURVE_S1.); -#160991 = LINE('',#160992,#160993); -#160992 = CARTESIAN_POINT('',(-1.695,0.219849248823,3.005756955187)); -#160993 = VECTOR('',#160994,1.); -#160994 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#160995 = PCURVE('',#160923,#160996); -#160996 = DEFINITIONAL_REPRESENTATION('',(#160997),#161001); -#160997 = LINE('',#160998,#160999); -#160998 = CARTESIAN_POINT('',(-0.11,0.21)); -#160999 = VECTOR('',#161000,1.); -#161000 = DIRECTION('',(1.,0.E+000)); -#161001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161002 = PCURVE('',#160785,#161003); -#161003 = DEFINITIONAL_REPRESENTATION('',(#161004),#161008); -#161004 = LINE('',#161005,#161006); -#161005 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#161006 = VECTOR('',#161007,1.); -#161007 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#161008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161009 = ORIENTED_EDGE('',*,*,#160907,.T.); -#161010 = ORIENTED_EDGE('',*,*,#161011,.F.); -#161011 = EDGE_CURVE('',#160962,#160885,#161012,.T.); -#161012 = SURFACE_CURVE('',#161013,(#161017,#161024),.PCURVE_S1.); -#161013 = LINE('',#161014,#161015); -#161014 = CARTESIAN_POINT('',(-2.115,1.507511769892E-004,2.994243044813) - ); -#161015 = VECTOR('',#161016,1.); -#161016 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); -#161017 = PCURVE('',#160923,#161018); -#161018 = DEFINITIONAL_REPRESENTATION('',(#161019),#161023); -#161019 = LINE('',#161020,#161021); -#161020 = CARTESIAN_POINT('',(0.11,-0.21)); -#161021 = VECTOR('',#161022,1.); -#161022 = DIRECTION('',(-1.,0.E+000)); -#161023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161024 = PCURVE('',#160134,#161025); -#161025 = DEFINITIONAL_REPRESENTATION('',(#161026),#161030); -#161026 = LINE('',#161027,#161028); -#161027 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#161028 = VECTOR('',#161029,1.); -#161029 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#161030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161031 = ADVANCED_FACE('',(#161032),#160977,.T.); -#161032 = FACE_BOUND('',#161033,.T.); -#161033 = EDGE_LOOP('',(#161034,#161063,#161084,#161085)); -#161034 = ORIENTED_EDGE('',*,*,#161035,.F.); -#161035 = EDGE_CURVE('',#161036,#161038,#161040,.T.); -#161036 = VERTEX_POINT('',#161037); -#161037 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,2.591449450184) - ); -#161038 = VERTEX_POINT('',#161039); -#161039 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,2.591449450184) - ); -#161040 = SURFACE_CURVE('',#161041,(#161045,#161052),.PCURVE_S1.); -#161041 = LINE('',#161042,#161043); -#161042 = CARTESIAN_POINT('',(-1.905,2.126026898095E-002,2.591449450184) - ); -#161043 = VECTOR('',#161044,1.); -#161044 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161045 = PCURVE('',#160977,#161046); -#161046 = DEFINITIONAL_REPRESENTATION('',(#161047),#161051); -#161047 = LINE('',#161048,#161049); -#161048 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); -#161049 = VECTOR('',#161050,1.); -#161050 = DIRECTION('',(0.E+000,-1.)); -#161051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161052 = PCURVE('',#161053,#161058); -#161053 = CYLINDRICAL_SURFACE('',#161054,0.32); -#161054 = AXIS2_PLACEMENT_3D('',#161055,#161056,#161057); -#161055 = CARTESIAN_POINT('',(-1.905,0.340821720102,2.608196956182)); -#161056 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161057 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161058 = DEFINITIONAL_REPRESENTATION('',(#161059),#161062); -#161059 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161060,#161061), +#163359 = VECTOR('',#163360,1.); +#163360 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163361 = PCURVE('',#163315,#163362); +#163362 = DEFINITIONAL_REPRESENTATION('',(#163363),#163367); +#163363 = LINE('',#163364,#163365); +#163364 = CARTESIAN_POINT('',(0.11,0.E+000)); +#163365 = VECTOR('',#163366,1.); +#163366 = DIRECTION('',(0.E+000,-1.)); +#163367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163368 = PCURVE('',#163369,#163374); +#163369 = PLANE('',#163370); +#163370 = AXIS2_PLACEMENT_3D('',#163371,#163372,#163373); +#163371 = CARTESIAN_POINT('',(-1.905,2.126026898096E-002,2.591449450184) + ); +#163372 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); +#163373 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#163374 = DEFINITIONAL_REPRESENTATION('',(#163375),#163379); +#163375 = LINE('',#163376,#163377); +#163376 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#163377 = VECTOR('',#163378,1.); +#163378 = DIRECTION('',(0.E+000,-1.)); +#163379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163380 = ORIENTED_EDGE('',*,*,#163381,.F.); +#163381 = EDGE_CURVE('',#163300,#163352,#163382,.T.); +#163382 = SURFACE_CURVE('',#163383,(#163387,#163394),.PCURVE_S1.); +#163383 = LINE('',#163384,#163385); +#163384 = CARTESIAN_POINT('',(-1.695,0.219849248823,3.005756955187)); +#163385 = VECTOR('',#163386,1.); +#163386 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#163387 = PCURVE('',#163315,#163388); +#163388 = DEFINITIONAL_REPRESENTATION('',(#163389),#163393); +#163389 = LINE('',#163390,#163391); +#163390 = CARTESIAN_POINT('',(-0.11,0.21)); +#163391 = VECTOR('',#163392,1.); +#163392 = DIRECTION('',(1.,0.E+000)); +#163393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163394 = PCURVE('',#163177,#163395); +#163395 = DEFINITIONAL_REPRESENTATION('',(#163396),#163400); +#163396 = LINE('',#163397,#163398); +#163397 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#163398 = VECTOR('',#163399,1.); +#163399 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#163400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163401 = ORIENTED_EDGE('',*,*,#163299,.T.); +#163402 = ORIENTED_EDGE('',*,*,#163403,.F.); +#163403 = EDGE_CURVE('',#163354,#163277,#163404,.T.); +#163404 = SURFACE_CURVE('',#163405,(#163409,#163416),.PCURVE_S1.); +#163405 = LINE('',#163406,#163407); +#163406 = CARTESIAN_POINT('',(-2.115,1.507511769892E-004,2.994243044813) + ); +#163407 = VECTOR('',#163408,1.); +#163408 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); +#163409 = PCURVE('',#163315,#163410); +#163410 = DEFINITIONAL_REPRESENTATION('',(#163411),#163415); +#163411 = LINE('',#163412,#163413); +#163412 = CARTESIAN_POINT('',(0.11,-0.21)); +#163413 = VECTOR('',#163414,1.); +#163414 = DIRECTION('',(-1.,0.E+000)); +#163415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163416 = PCURVE('',#162526,#163417); +#163417 = DEFINITIONAL_REPRESENTATION('',(#163418),#163422); +#163418 = LINE('',#163419,#163420); +#163419 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#163420 = VECTOR('',#163421,1.); +#163421 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#163422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163423 = ADVANCED_FACE('',(#163424),#163369,.T.); +#163424 = FACE_BOUND('',#163425,.T.); +#163425 = EDGE_LOOP('',(#163426,#163455,#163476,#163477)); +#163426 = ORIENTED_EDGE('',*,*,#163427,.F.); +#163427 = EDGE_CURVE('',#163428,#163430,#163432,.T.); +#163428 = VERTEX_POINT('',#163429); +#163429 = CARTESIAN_POINT('',(-1.695,2.126026898096E-002,2.591449450184) + ); +#163430 = VERTEX_POINT('',#163431); +#163431 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,2.591449450184) + ); +#163432 = SURFACE_CURVE('',#163433,(#163437,#163444),.PCURVE_S1.); +#163433 = LINE('',#163434,#163435); +#163434 = CARTESIAN_POINT('',(-1.905,2.126026898095E-002,2.591449450184) + ); +#163435 = VECTOR('',#163436,1.); +#163436 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163437 = PCURVE('',#163369,#163438); +#163438 = DEFINITIONAL_REPRESENTATION('',(#163439),#163443); +#163439 = LINE('',#163440,#163441); +#163440 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); +#163441 = VECTOR('',#163442,1.); +#163442 = DIRECTION('',(0.E+000,-1.)); +#163443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163444 = PCURVE('',#163445,#163450); +#163445 = CYLINDRICAL_SURFACE('',#163446,0.32); +#163446 = AXIS2_PLACEMENT_3D('',#163447,#163448,#163449); +#163447 = CARTESIAN_POINT('',(-1.905,0.340821720102,2.608196956182)); +#163448 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163449 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163450 = DEFINITIONAL_REPRESENTATION('',(#163451),#163454); +#163451 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163452,#163453), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161060 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161061 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161063 = ORIENTED_EDGE('',*,*,#161064,.F.); -#161064 = EDGE_CURVE('',#160960,#161036,#161065,.T.); -#161065 = SURFACE_CURVE('',#161066,(#161070,#161077),.PCURVE_S1.); -#161066 = LINE('',#161067,#161068); -#161067 = CARTESIAN_POINT('',(-1.695,1.507511769892E-004,2.994243044813) - ); -#161068 = VECTOR('',#161069,1.); -#161069 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#161070 = PCURVE('',#160977,#161071); -#161071 = DEFINITIONAL_REPRESENTATION('',(#161072),#161076); -#161072 = LINE('',#161073,#161074); -#161073 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#161074 = VECTOR('',#161075,1.); -#161075 = DIRECTION('',(1.,0.E+000)); -#161076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161077 = PCURVE('',#160785,#161078); -#161078 = DEFINITIONAL_REPRESENTATION('',(#161079),#161083); -#161079 = LINE('',#161080,#161081); -#161080 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#161081 = VECTOR('',#161082,1.); -#161082 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#161083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161084 = ORIENTED_EDGE('',*,*,#160959,.T.); -#161085 = ORIENTED_EDGE('',*,*,#161086,.F.); -#161086 = EDGE_CURVE('',#161038,#160962,#161087,.T.); -#161087 = SURFACE_CURVE('',#161088,(#161092,#161099),.PCURVE_S1.); -#161088 = LINE('',#161089,#161090); -#161089 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,2.591449450184) - ); -#161090 = VECTOR('',#161091,1.); -#161091 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#161092 = PCURVE('',#160977,#161093); -#161093 = DEFINITIONAL_REPRESENTATION('',(#161094),#161098); -#161094 = LINE('',#161095,#161096); -#161095 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); -#161096 = VECTOR('',#161097,1.); -#161097 = DIRECTION('',(-1.,0.E+000)); -#161098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161099 = PCURVE('',#160134,#161100); -#161100 = DEFINITIONAL_REPRESENTATION('',(#161101),#161105); -#161101 = LINE('',#161102,#161103); -#161102 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#161103 = VECTOR('',#161104,1.); -#161104 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#161105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161106 = ADVANCED_FACE('',(#161107),#161053,.T.); -#161107 = FACE_BOUND('',#161108,.T.); -#161108 = EDGE_LOOP('',(#161109,#161138,#161159,#161160)); -#161109 = ORIENTED_EDGE('',*,*,#161110,.F.); -#161110 = EDGE_CURVE('',#161111,#161113,#161115,.T.); -#161111 = VERTEX_POINT('',#161112); -#161112 = CARTESIAN_POINT('',(-1.695,0.298978581017,2.290944451524)); -#161113 = VERTEX_POINT('',#161114); -#161114 = CARTESIAN_POINT('',(-2.115,0.298978581017,2.290944451524)); -#161115 = SURFACE_CURVE('',#161116,(#161120,#161126),.PCURVE_S1.); -#161116 = LINE('',#161117,#161118); -#161117 = CARTESIAN_POINT('',(-1.905,0.298978581017,2.290944451524)); -#161118 = VECTOR('',#161119,1.); -#161119 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161120 = PCURVE('',#161053,#161121); -#161121 = DEFINITIONAL_REPRESENTATION('',(#161122),#161125); -#161122 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161123,#161124), +#163452 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163453 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163455 = ORIENTED_EDGE('',*,*,#163456,.F.); +#163456 = EDGE_CURVE('',#163352,#163428,#163457,.T.); +#163457 = SURFACE_CURVE('',#163458,(#163462,#163469),.PCURVE_S1.); +#163458 = LINE('',#163459,#163460); +#163459 = CARTESIAN_POINT('',(-1.695,1.507511769892E-004,2.994243044813) + ); +#163460 = VECTOR('',#163461,1.); +#163461 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#163462 = PCURVE('',#163369,#163463); +#163463 = DEFINITIONAL_REPRESENTATION('',(#163464),#163468); +#163464 = LINE('',#163465,#163466); +#163465 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#163466 = VECTOR('',#163467,1.); +#163467 = DIRECTION('',(1.,0.E+000)); +#163468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163469 = PCURVE('',#163177,#163470); +#163470 = DEFINITIONAL_REPRESENTATION('',(#163471),#163475); +#163471 = LINE('',#163472,#163473); +#163472 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#163473 = VECTOR('',#163474,1.); +#163474 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#163475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163476 = ORIENTED_EDGE('',*,*,#163351,.T.); +#163477 = ORIENTED_EDGE('',*,*,#163478,.F.); +#163478 = EDGE_CURVE('',#163430,#163354,#163479,.T.); +#163479 = SURFACE_CURVE('',#163480,(#163484,#163491),.PCURVE_S1.); +#163480 = LINE('',#163481,#163482); +#163481 = CARTESIAN_POINT('',(-2.115,2.126026898096E-002,2.591449450184) + ); +#163482 = VECTOR('',#163483,1.); +#163483 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#163484 = PCURVE('',#163369,#163485); +#163485 = DEFINITIONAL_REPRESENTATION('',(#163486),#163490); +#163486 = LINE('',#163487,#163488); +#163487 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); +#163488 = VECTOR('',#163489,1.); +#163489 = DIRECTION('',(-1.,0.E+000)); +#163490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163491 = PCURVE('',#162526,#163492); +#163492 = DEFINITIONAL_REPRESENTATION('',(#163493),#163497); +#163493 = LINE('',#163494,#163495); +#163494 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#163495 = VECTOR('',#163496,1.); +#163496 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#163497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163498 = ADVANCED_FACE('',(#163499),#163445,.T.); +#163499 = FACE_BOUND('',#163500,.T.); +#163500 = EDGE_LOOP('',(#163501,#163530,#163551,#163552)); +#163501 = ORIENTED_EDGE('',*,*,#163502,.F.); +#163502 = EDGE_CURVE('',#163503,#163505,#163507,.T.); +#163503 = VERTEX_POINT('',#163504); +#163504 = CARTESIAN_POINT('',(-1.695,0.298978581017,2.290944451524)); +#163505 = VERTEX_POINT('',#163506); +#163506 = CARTESIAN_POINT('',(-2.115,0.298978581017,2.290944451524)); +#163507 = SURFACE_CURVE('',#163508,(#163512,#163518),.PCURVE_S1.); +#163508 = LINE('',#163509,#163510); +#163509 = CARTESIAN_POINT('',(-1.905,0.298978581017,2.290944451524)); +#163510 = VECTOR('',#163511,1.); +#163511 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163512 = PCURVE('',#163445,#163513); +#163513 = DEFINITIONAL_REPRESENTATION('',(#163514),#163517); +#163514 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163515,#163516), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161123 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161124 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161126 = PCURVE('',#161127,#161132); -#161127 = PLANE('',#161128); -#161128 = AXIS2_PLACEMENT_3D('',#161129,#161130,#161131); -#161129 = CARTESIAN_POINT('',(-1.905,0.678075980964,2.240944451524)); -#161130 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); -#161131 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#161132 = DEFINITIONAL_REPRESENTATION('',(#161133),#161137); -#161133 = LINE('',#161134,#161135); -#161134 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#161135 = VECTOR('',#161136,1.); -#161136 = DIRECTION('',(0.E+000,-1.)); -#161137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161138 = ORIENTED_EDGE('',*,*,#161139,.F.); -#161139 = EDGE_CURVE('',#161036,#161111,#161140,.T.); -#161140 = SURFACE_CURVE('',#161141,(#161146,#161152),.PCURVE_S1.); -#161141 = CIRCLE('',#161142,0.32); -#161142 = AXIS2_PLACEMENT_3D('',#161143,#161144,#161145); -#161143 = CARTESIAN_POINT('',(-1.695,0.340821720102,2.608196956182)); -#161144 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161145 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); -#161146 = PCURVE('',#161053,#161147); -#161147 = DEFINITIONAL_REPRESENTATION('',(#161148),#161151); -#161148 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161149,#161150), +#163515 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163516 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163518 = PCURVE('',#163519,#163524); +#163519 = PLANE('',#163520); +#163520 = AXIS2_PLACEMENT_3D('',#163521,#163522,#163523); +#163521 = CARTESIAN_POINT('',(-1.905,0.678075980964,2.240944451524)); +#163522 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); +#163523 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#163524 = DEFINITIONAL_REPRESENTATION('',(#163525),#163529); +#163525 = LINE('',#163526,#163527); +#163526 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#163527 = VECTOR('',#163528,1.); +#163528 = DIRECTION('',(0.E+000,-1.)); +#163529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163530 = ORIENTED_EDGE('',*,*,#163531,.F.); +#163531 = EDGE_CURVE('',#163428,#163503,#163532,.T.); +#163532 = SURFACE_CURVE('',#163533,(#163538,#163544),.PCURVE_S1.); +#163533 = CIRCLE('',#163534,0.32); +#163534 = AXIS2_PLACEMENT_3D('',#163535,#163536,#163537); +#163535 = CARTESIAN_POINT('',(-1.695,0.340821720102,2.608196956182)); +#163536 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163537 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); +#163538 = PCURVE('',#163445,#163539); +#163539 = DEFINITIONAL_REPRESENTATION('',(#163540),#163543); +#163540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163541,#163542), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#161149 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161150 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161151 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161152 = PCURVE('',#160785,#161153); -#161153 = DEFINITIONAL_REPRESENTATION('',(#161154),#161158); -#161154 = CIRCLE('',#161155,0.32); -#161155 = AXIS2_PLACEMENT_2D('',#161156,#161157); -#161156 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#161157 = DIRECTION('',(-1.,1.694065894509E-015)); -#161158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161159 = ORIENTED_EDGE('',*,*,#161035,.T.); -#161160 = ORIENTED_EDGE('',*,*,#161161,.F.); -#161161 = EDGE_CURVE('',#161113,#161038,#161162,.T.); -#161162 = SURFACE_CURVE('',#161163,(#161168,#161174),.PCURVE_S1.); -#161163 = CIRCLE('',#161164,0.32); -#161164 = AXIS2_PLACEMENT_3D('',#161165,#161166,#161167); -#161165 = CARTESIAN_POINT('',(-2.115,0.340821720102,2.608196956182)); -#161166 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161167 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161168 = PCURVE('',#161053,#161169); -#161169 = DEFINITIONAL_REPRESENTATION('',(#161170),#161173); -#161170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161171,#161172), +#163541 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163542 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163544 = PCURVE('',#163177,#163545); +#163545 = DEFINITIONAL_REPRESENTATION('',(#163546),#163550); +#163546 = CIRCLE('',#163547,0.32); +#163547 = AXIS2_PLACEMENT_2D('',#163548,#163549); +#163548 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#163549 = DIRECTION('',(-1.,1.694065894509E-015)); +#163550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163551 = ORIENTED_EDGE('',*,*,#163427,.T.); +#163552 = ORIENTED_EDGE('',*,*,#163553,.F.); +#163553 = EDGE_CURVE('',#163505,#163430,#163554,.T.); +#163554 = SURFACE_CURVE('',#163555,(#163560,#163566),.PCURVE_S1.); +#163555 = CIRCLE('',#163556,0.32); +#163556 = AXIS2_PLACEMENT_3D('',#163557,#163558,#163559); +#163557 = CARTESIAN_POINT('',(-2.115,0.340821720102,2.608196956182)); +#163558 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163559 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163560 = PCURVE('',#163445,#163561); +#163561 = DEFINITIONAL_REPRESENTATION('',(#163562),#163565); +#163562 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163563,#163564), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#161171 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161172 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161174 = PCURVE('',#160134,#161175); -#161175 = DEFINITIONAL_REPRESENTATION('',(#161176),#161180); -#161176 = CIRCLE('',#161177,0.32); -#161177 = AXIS2_PLACEMENT_2D('',#161178,#161179); -#161178 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#161179 = DIRECTION('',(1.,0.E+000)); -#161180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161181 = ADVANCED_FACE('',(#161182),#161127,.T.); -#161182 = FACE_BOUND('',#161183,.T.); -#161183 = EDGE_LOOP('',(#161184,#161213,#161234,#161235)); -#161184 = ORIENTED_EDGE('',*,*,#161185,.T.); -#161185 = EDGE_CURVE('',#161186,#161188,#161190,.T.); -#161186 = VERTEX_POINT('',#161187); -#161187 = CARTESIAN_POINT('',(-2.115,0.678075980964,2.240944451524)); -#161188 = VERTEX_POINT('',#161189); -#161189 = CARTESIAN_POINT('',(-1.695,0.678075980964,2.240944451524)); -#161190 = SURFACE_CURVE('',#161191,(#161195,#161202),.PCURVE_S1.); -#161191 = LINE('',#161192,#161193); -#161192 = CARTESIAN_POINT('',(-1.905,0.678075980964,2.240944451524)); -#161193 = VECTOR('',#161194,1.); -#161194 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161195 = PCURVE('',#161127,#161196); -#161196 = DEFINITIONAL_REPRESENTATION('',(#161197),#161201); -#161197 = LINE('',#161198,#161199); -#161198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#161199 = VECTOR('',#161200,1.); -#161200 = DIRECTION('',(0.E+000,1.)); -#161201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161202 = PCURVE('',#161203,#161208); -#161203 = CYLINDRICAL_SURFACE('',#161204,1.E-001); -#161204 = AXIS2_PLACEMENT_3D('',#161205,#161206,#161207); -#161205 = CARTESIAN_POINT('',(-1.905,0.665,2.141803043818)); -#161206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161207 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161208 = DEFINITIONAL_REPRESENTATION('',(#161209),#161212); -#161209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161210,#161211), +#163563 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163564 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163566 = PCURVE('',#162526,#163567); +#163567 = DEFINITIONAL_REPRESENTATION('',(#163568),#163572); +#163568 = CIRCLE('',#163569,0.32); +#163569 = AXIS2_PLACEMENT_2D('',#163570,#163571); +#163570 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#163571 = DIRECTION('',(1.,0.E+000)); +#163572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163573 = ADVANCED_FACE('',(#163574),#163519,.T.); +#163574 = FACE_BOUND('',#163575,.T.); +#163575 = EDGE_LOOP('',(#163576,#163605,#163626,#163627)); +#163576 = ORIENTED_EDGE('',*,*,#163577,.T.); +#163577 = EDGE_CURVE('',#163578,#163580,#163582,.T.); +#163578 = VERTEX_POINT('',#163579); +#163579 = CARTESIAN_POINT('',(-2.115,0.678075980964,2.240944451524)); +#163580 = VERTEX_POINT('',#163581); +#163581 = CARTESIAN_POINT('',(-1.695,0.678075980964,2.240944451524)); +#163582 = SURFACE_CURVE('',#163583,(#163587,#163594),.PCURVE_S1.); +#163583 = LINE('',#163584,#163585); +#163584 = CARTESIAN_POINT('',(-1.905,0.678075980964,2.240944451524)); +#163585 = VECTOR('',#163586,1.); +#163586 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163587 = PCURVE('',#163519,#163588); +#163588 = DEFINITIONAL_REPRESENTATION('',(#163589),#163593); +#163589 = LINE('',#163590,#163591); +#163590 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#163591 = VECTOR('',#163592,1.); +#163592 = DIRECTION('',(0.E+000,1.)); +#163593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163594 = PCURVE('',#163595,#163600); +#163595 = CYLINDRICAL_SURFACE('',#163596,1.E-001); +#163596 = AXIS2_PLACEMENT_3D('',#163597,#163598,#163599); +#163597 = CARTESIAN_POINT('',(-1.905,0.665,2.141803043818)); +#163598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163599 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163600 = DEFINITIONAL_REPRESENTATION('',(#163601),#163604); +#163601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163602,#163603), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161210 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#161211 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#161212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161213 = ORIENTED_EDGE('',*,*,#161214,.F.); -#161214 = EDGE_CURVE('',#161111,#161188,#161215,.T.); -#161215 = SURFACE_CURVE('',#161216,(#161220,#161227),.PCURVE_S1.); -#161216 = LINE('',#161217,#161218); -#161217 = CARTESIAN_POINT('',(-1.695,0.298978581017,2.290944451524)); -#161218 = VECTOR('',#161219,1.); -#161219 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#161220 = PCURVE('',#161127,#161221); -#161221 = DEFINITIONAL_REPRESENTATION('',(#161222),#161226); -#161222 = LINE('',#161223,#161224); -#161223 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#161224 = VECTOR('',#161225,1.); -#161225 = DIRECTION('',(1.,0.E+000)); -#161226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161227 = PCURVE('',#160785,#161228); -#161228 = DEFINITIONAL_REPRESENTATION('',(#161229),#161233); -#161229 = LINE('',#161230,#161231); -#161230 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#161231 = VECTOR('',#161232,1.); -#161232 = DIRECTION('',(0.130759809642,0.991414077055)); -#161233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161234 = ORIENTED_EDGE('',*,*,#161110,.T.); -#161235 = ORIENTED_EDGE('',*,*,#161236,.F.); -#161236 = EDGE_CURVE('',#161186,#161113,#161237,.T.); -#161237 = SURFACE_CURVE('',#161238,(#161242,#161249),.PCURVE_S1.); -#161238 = LINE('',#161239,#161240); -#161239 = CARTESIAN_POINT('',(-2.115,0.678075980964,2.240944451524)); -#161240 = VECTOR('',#161241,1.); -#161241 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#161242 = PCURVE('',#161127,#161243); -#161243 = DEFINITIONAL_REPRESENTATION('',(#161244),#161248); -#161244 = LINE('',#161245,#161246); -#161245 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#161246 = VECTOR('',#161247,1.); -#161247 = DIRECTION('',(-1.,0.E+000)); -#161248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161249 = PCURVE('',#160134,#161250); -#161250 = DEFINITIONAL_REPRESENTATION('',(#161251),#161255); -#161251 = LINE('',#161252,#161253); -#161252 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#161253 = VECTOR('',#161254,1.); -#161254 = DIRECTION('',(0.130759809642,-0.991414077055)); -#161255 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161256 = ADVANCED_FACE('',(#161257),#161203,.F.); -#161257 = FACE_BOUND('',#161258,.F.); -#161258 = EDGE_LOOP('',(#161259,#161286,#161287,#161314)); -#161259 = ORIENTED_EDGE('',*,*,#161260,.T.); -#161260 = EDGE_CURVE('',#161261,#161186,#161263,.T.); -#161261 = VERTEX_POINT('',#161262); -#161262 = CARTESIAN_POINT('',(-2.115,0.765,2.141803043818)); -#161263 = SURFACE_CURVE('',#161264,(#161269,#161275),.PCURVE_S1.); -#161264 = CIRCLE('',#161265,1.E-001); -#161265 = AXIS2_PLACEMENT_3D('',#161266,#161267,#161268); -#161266 = CARTESIAN_POINT('',(-2.115,0.665,2.141803043818)); -#161267 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161268 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161269 = PCURVE('',#161203,#161270); -#161270 = DEFINITIONAL_REPRESENTATION('',(#161271),#161274); -#161271 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161272,#161273), +#163602 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#163603 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#163604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163605 = ORIENTED_EDGE('',*,*,#163606,.F.); +#163606 = EDGE_CURVE('',#163503,#163580,#163607,.T.); +#163607 = SURFACE_CURVE('',#163608,(#163612,#163619),.PCURVE_S1.); +#163608 = LINE('',#163609,#163610); +#163609 = CARTESIAN_POINT('',(-1.695,0.298978581017,2.290944451524)); +#163610 = VECTOR('',#163611,1.); +#163611 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#163612 = PCURVE('',#163519,#163613); +#163613 = DEFINITIONAL_REPRESENTATION('',(#163614),#163618); +#163614 = LINE('',#163615,#163616); +#163615 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#163616 = VECTOR('',#163617,1.); +#163617 = DIRECTION('',(1.,0.E+000)); +#163618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163619 = PCURVE('',#163177,#163620); +#163620 = DEFINITIONAL_REPRESENTATION('',(#163621),#163625); +#163621 = LINE('',#163622,#163623); +#163622 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#163623 = VECTOR('',#163624,1.); +#163624 = DIRECTION('',(0.130759809642,0.991414077055)); +#163625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163626 = ORIENTED_EDGE('',*,*,#163502,.T.); +#163627 = ORIENTED_EDGE('',*,*,#163628,.F.); +#163628 = EDGE_CURVE('',#163578,#163505,#163629,.T.); +#163629 = SURFACE_CURVE('',#163630,(#163634,#163641),.PCURVE_S1.); +#163630 = LINE('',#163631,#163632); +#163631 = CARTESIAN_POINT('',(-2.115,0.678075980964,2.240944451524)); +#163632 = VECTOR('',#163633,1.); +#163633 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#163634 = PCURVE('',#163519,#163635); +#163635 = DEFINITIONAL_REPRESENTATION('',(#163636),#163640); +#163636 = LINE('',#163637,#163638); +#163637 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#163638 = VECTOR('',#163639,1.); +#163639 = DIRECTION('',(-1.,0.E+000)); +#163640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163641 = PCURVE('',#162526,#163642); +#163642 = DEFINITIONAL_REPRESENTATION('',(#163643),#163647); +#163643 = LINE('',#163644,#163645); +#163644 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#163645 = VECTOR('',#163646,1.); +#163646 = DIRECTION('',(0.130759809642,-0.991414077055)); +#163647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163648 = ADVANCED_FACE('',(#163649),#163595,.F.); +#163649 = FACE_BOUND('',#163650,.F.); +#163650 = EDGE_LOOP('',(#163651,#163678,#163679,#163706)); +#163651 = ORIENTED_EDGE('',*,*,#163652,.T.); +#163652 = EDGE_CURVE('',#163653,#163578,#163655,.T.); +#163653 = VERTEX_POINT('',#163654); +#163654 = CARTESIAN_POINT('',(-2.115,0.765,2.141803043818)); +#163655 = SURFACE_CURVE('',#163656,(#163661,#163667),.PCURVE_S1.); +#163656 = CIRCLE('',#163657,1.E-001); +#163657 = AXIS2_PLACEMENT_3D('',#163658,#163659,#163660); +#163658 = CARTESIAN_POINT('',(-2.115,0.665,2.141803043818)); +#163659 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163660 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163661 = PCURVE('',#163595,#163662); +#163662 = DEFINITIONAL_REPRESENTATION('',(#163663),#163666); +#163663 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163664,#163665), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#161272 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#161273 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#161274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163664 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#163665 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#163666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161275 = PCURVE('',#160134,#161276); -#161276 = DEFINITIONAL_REPRESENTATION('',(#161277),#161285); -#161277 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161278,#161279,#161280, - #161281,#161282,#161283,#161284),.UNSPECIFIED.,.T.,.F.) +#163667 = PCURVE('',#162526,#163668); +#163668 = DEFINITIONAL_REPRESENTATION('',(#163669),#163677); +#163669 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163670,#163671,#163672, + #163673,#163674,#163675,#163676),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161278 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#161279 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#161280 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#161281 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#161282 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#161283 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#161284 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#161285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161286 = ORIENTED_EDGE('',*,*,#161185,.T.); -#161287 = ORIENTED_EDGE('',*,*,#161288,.T.); -#161288 = EDGE_CURVE('',#161188,#161289,#161291,.T.); -#161289 = VERTEX_POINT('',#161290); -#161290 = CARTESIAN_POINT('',(-1.695,0.765,2.141803043818)); -#161291 = SURFACE_CURVE('',#161292,(#161297,#161303),.PCURVE_S1.); -#161292 = CIRCLE('',#161293,1.E-001); -#161293 = AXIS2_PLACEMENT_3D('',#161294,#161295,#161296); -#161294 = CARTESIAN_POINT('',(-1.695,0.665,2.141803043818)); -#161295 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161296 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); -#161297 = PCURVE('',#161203,#161298); -#161298 = DEFINITIONAL_REPRESENTATION('',(#161299),#161302); -#161299 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161300,#161301), +#163670 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#163671 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#163672 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#163673 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#163674 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#163675 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#163676 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#163677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163678 = ORIENTED_EDGE('',*,*,#163577,.T.); +#163679 = ORIENTED_EDGE('',*,*,#163680,.T.); +#163680 = EDGE_CURVE('',#163580,#163681,#163683,.T.); +#163681 = VERTEX_POINT('',#163682); +#163682 = CARTESIAN_POINT('',(-1.695,0.765,2.141803043818)); +#163683 = SURFACE_CURVE('',#163684,(#163689,#163695),.PCURVE_S1.); +#163684 = CIRCLE('',#163685,1.E-001); +#163685 = AXIS2_PLACEMENT_3D('',#163686,#163687,#163688); +#163686 = CARTESIAN_POINT('',(-1.695,0.665,2.141803043818)); +#163687 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163688 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); +#163689 = PCURVE('',#163595,#163690); +#163690 = DEFINITIONAL_REPRESENTATION('',(#163691),#163694); +#163691 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163692,#163693), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#161300 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#161301 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#161302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163692 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#163693 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#163694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161303 = PCURVE('',#160785,#161304); -#161304 = DEFINITIONAL_REPRESENTATION('',(#161305),#161313); -#161305 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161306,#161307,#161308, - #161309,#161310,#161311,#161312),.UNSPECIFIED.,.T.,.F.) +#163695 = PCURVE('',#163177,#163696); +#163696 = DEFINITIONAL_REPRESENTATION('',(#163697),#163705); +#163697 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163698,#163699,#163700, + #163701,#163702,#163703,#163704),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161306 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#161307 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#161308 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#161309 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#161310 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#161311 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#161312 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#161313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161314 = ORIENTED_EDGE('',*,*,#161315,.T.); -#161315 = EDGE_CURVE('',#161289,#161261,#161316,.T.); -#161316 = SURFACE_CURVE('',#161317,(#161321,#161327),.PCURVE_S1.); -#161317 = LINE('',#161318,#161319); -#161318 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); -#161319 = VECTOR('',#161320,1.); -#161320 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161321 = PCURVE('',#161203,#161322); -#161322 = DEFINITIONAL_REPRESENTATION('',(#161323),#161326); -#161323 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161324,#161325), +#163698 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#163699 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#163700 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#163701 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#163702 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#163703 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#163704 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#163705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163706 = ORIENTED_EDGE('',*,*,#163707,.T.); +#163707 = EDGE_CURVE('',#163681,#163653,#163708,.T.); +#163708 = SURFACE_CURVE('',#163709,(#163713,#163719),.PCURVE_S1.); +#163709 = LINE('',#163710,#163711); +#163710 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); +#163711 = VECTOR('',#163712,1.); +#163712 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163713 = PCURVE('',#163595,#163714); +#163714 = DEFINITIONAL_REPRESENTATION('',(#163715),#163718); +#163715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163716,#163717), .UNSPECIFIED.,.F.,.F.,(2,2),(2.33,2.75),.PIECEWISE_BEZIER_KNOTS.); -#161324 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#161325 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#161326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161327 = PCURVE('',#159360,#161328); -#161328 = DEFINITIONAL_REPRESENTATION('',(#161329),#161333); -#161329 = LINE('',#161330,#161331); -#161330 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#161331 = VECTOR('',#161332,1.); -#161332 = DIRECTION('',(0.E+000,-1.)); -#161333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161334 = ADVANCED_FACE('',(#161335),#161349,.T.); -#161335 = FACE_BOUND('',#161336,.T.); -#161336 = EDGE_LOOP('',(#161337,#161371,#161399,#161426)); -#161337 = ORIENTED_EDGE('',*,*,#161338,.F.); -#161338 = EDGE_CURVE('',#161339,#161341,#161343,.T.); -#161339 = VERTEX_POINT('',#161340); -#161340 = CARTESIAN_POINT('',(-0.845,0.706843139085,2.459055548476)); -#161341 = VERTEX_POINT('',#161342); -#161342 = CARTESIAN_POINT('',(-0.425,0.706843139085,2.459055548476)); -#161343 = SURFACE_CURVE('',#161344,(#161348,#161360),.PCURVE_S1.); -#161344 = LINE('',#161345,#161346); -#161345 = CARTESIAN_POINT('',(-0.635,0.706843139085,2.459055548476)); -#161346 = VECTOR('',#161347,1.); -#161347 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161348 = PCURVE('',#161349,#161354); -#161349 = PLANE('',#161350); -#161350 = AXIS2_PLACEMENT_3D('',#161351,#161352,#161353); -#161351 = CARTESIAN_POINT('',(-0.635,0.706843139085,2.459055548476)); -#161352 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); -#161353 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#161354 = DEFINITIONAL_REPRESENTATION('',(#161355),#161359); -#161355 = LINE('',#161356,#161357); -#161356 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#161357 = VECTOR('',#161358,1.); -#161358 = DIRECTION('',(0.E+000,1.)); -#161359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161360 = PCURVE('',#161361,#161366); -#161361 = CYLINDRICAL_SURFACE('',#161362,0.32); -#161362 = AXIS2_PLACEMENT_3D('',#161363,#161364,#161365); -#161363 = CARTESIAN_POINT('',(-0.635,0.665,2.141803043818)); -#161364 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161365 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161366 = DEFINITIONAL_REPRESENTATION('',(#161367),#161370); -#161367 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161368,#161369), +#163716 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#163717 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#163718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163719 = PCURVE('',#161752,#163720); +#163720 = DEFINITIONAL_REPRESENTATION('',(#163721),#163725); +#163721 = LINE('',#163722,#163723); +#163722 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#163723 = VECTOR('',#163724,1.); +#163724 = DIRECTION('',(0.E+000,-1.)); +#163725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163726 = ADVANCED_FACE('',(#163727),#163741,.T.); +#163727 = FACE_BOUND('',#163728,.T.); +#163728 = EDGE_LOOP('',(#163729,#163763,#163791,#163818)); +#163729 = ORIENTED_EDGE('',*,*,#163730,.F.); +#163730 = EDGE_CURVE('',#163731,#163733,#163735,.T.); +#163731 = VERTEX_POINT('',#163732); +#163732 = CARTESIAN_POINT('',(-0.845,0.706843139085,2.459055548476)); +#163733 = VERTEX_POINT('',#163734); +#163734 = CARTESIAN_POINT('',(-0.425,0.706843139085,2.459055548476)); +#163735 = SURFACE_CURVE('',#163736,(#163740,#163752),.PCURVE_S1.); +#163736 = LINE('',#163737,#163738); +#163737 = CARTESIAN_POINT('',(-0.635,0.706843139085,2.459055548476)); +#163738 = VECTOR('',#163739,1.); +#163739 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163740 = PCURVE('',#163741,#163746); +#163741 = PLANE('',#163742); +#163742 = AXIS2_PLACEMENT_3D('',#163743,#163744,#163745); +#163743 = CARTESIAN_POINT('',(-0.635,0.706843139085,2.459055548476)); +#163744 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); +#163745 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#163746 = DEFINITIONAL_REPRESENTATION('',(#163747),#163751); +#163747 = LINE('',#163748,#163749); +#163748 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#163749 = VECTOR('',#163750,1.); +#163750 = DIRECTION('',(0.E+000,1.)); +#163751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163752 = PCURVE('',#163753,#163758); +#163753 = CYLINDRICAL_SURFACE('',#163754,0.32); +#163754 = AXIS2_PLACEMENT_3D('',#163755,#163756,#163757); +#163755 = CARTESIAN_POINT('',(-0.635,0.665,2.141803043818)); +#163756 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163757 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163758 = DEFINITIONAL_REPRESENTATION('',(#163759),#163762); +#163759 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163760,#163761), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161368 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#161369 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#161370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161371 = ORIENTED_EDGE('',*,*,#161372,.F.); -#161372 = EDGE_CURVE('',#161373,#161339,#161375,.T.); -#161373 = VERTEX_POINT('',#161374); -#161374 = CARTESIAN_POINT('',(-0.845,0.327745739138,2.509055548476)); -#161375 = SURFACE_CURVE('',#161376,(#161380,#161387),.PCURVE_S1.); -#161376 = LINE('',#161377,#161378); -#161377 = CARTESIAN_POINT('',(-0.845,0.327745739138,2.509055548476)); -#161378 = VECTOR('',#161379,1.); -#161379 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#161380 = PCURVE('',#161349,#161381); -#161381 = DEFINITIONAL_REPRESENTATION('',(#161382),#161386); -#161382 = LINE('',#161383,#161384); -#161383 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#161384 = VECTOR('',#161385,1.); -#161385 = DIRECTION('',(-1.,0.E+000)); -#161386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161387 = PCURVE('',#161388,#161393); -#161388 = PLANE('',#161389); -#161389 = AXIS2_PLACEMENT_3D('',#161390,#161391,#161392); -#161390 = CARTESIAN_POINT('',(-0.845,0.875,0.E+000)); -#161391 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161392 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161393 = DEFINITIONAL_REPRESENTATION('',(#161394),#161398); -#161394 = LINE('',#161395,#161396); -#161395 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#161396 = VECTOR('',#161397,1.); -#161397 = DIRECTION('',(-0.130759809642,0.991414077055)); -#161398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161399 = ORIENTED_EDGE('',*,*,#161400,.T.); -#161400 = EDGE_CURVE('',#161373,#161401,#161403,.T.); -#161401 = VERTEX_POINT('',#161402); -#161402 = CARTESIAN_POINT('',(-0.425,0.327745739138,2.509055548476)); -#161403 = SURFACE_CURVE('',#161404,(#161408,#161415),.PCURVE_S1.); -#161404 = LINE('',#161405,#161406); -#161405 = CARTESIAN_POINT('',(-0.635,0.327745739138,2.509055548476)); -#161406 = VECTOR('',#161407,1.); -#161407 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161408 = PCURVE('',#161349,#161409); -#161409 = DEFINITIONAL_REPRESENTATION('',(#161410),#161414); -#161410 = LINE('',#161411,#161412); -#161411 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#161412 = VECTOR('',#161413,1.); -#161413 = DIRECTION('',(0.E+000,1.)); -#161414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161415 = PCURVE('',#161416,#161421); -#161416 = CYLINDRICAL_SURFACE('',#161417,9.999999999999E-002); -#161417 = AXIS2_PLACEMENT_3D('',#161418,#161419,#161420); -#161418 = CARTESIAN_POINT('',(-0.635,0.340821720102,2.608196956182)); -#161419 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161420 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161421 = DEFINITIONAL_REPRESENTATION('',(#161422),#161425); -#161422 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161423,#161424), +#163760 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#163761 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#163762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163763 = ORIENTED_EDGE('',*,*,#163764,.F.); +#163764 = EDGE_CURVE('',#163765,#163731,#163767,.T.); +#163765 = VERTEX_POINT('',#163766); +#163766 = CARTESIAN_POINT('',(-0.845,0.327745739138,2.509055548476)); +#163767 = SURFACE_CURVE('',#163768,(#163772,#163779),.PCURVE_S1.); +#163768 = LINE('',#163769,#163770); +#163769 = CARTESIAN_POINT('',(-0.845,0.327745739138,2.509055548476)); +#163770 = VECTOR('',#163771,1.); +#163771 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#163772 = PCURVE('',#163741,#163773); +#163773 = DEFINITIONAL_REPRESENTATION('',(#163774),#163778); +#163774 = LINE('',#163775,#163776); +#163775 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#163776 = VECTOR('',#163777,1.); +#163777 = DIRECTION('',(-1.,0.E+000)); +#163778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163779 = PCURVE('',#163780,#163785); +#163780 = PLANE('',#163781); +#163781 = AXIS2_PLACEMENT_3D('',#163782,#163783,#163784); +#163782 = CARTESIAN_POINT('',(-0.845,0.875,0.E+000)); +#163783 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163784 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163785 = DEFINITIONAL_REPRESENTATION('',(#163786),#163790); +#163786 = LINE('',#163787,#163788); +#163787 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#163788 = VECTOR('',#163789,1.); +#163789 = DIRECTION('',(-0.130759809642,0.991414077055)); +#163790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163791 = ORIENTED_EDGE('',*,*,#163792,.T.); +#163792 = EDGE_CURVE('',#163765,#163793,#163795,.T.); +#163793 = VERTEX_POINT('',#163794); +#163794 = CARTESIAN_POINT('',(-0.425,0.327745739138,2.509055548476)); +#163795 = SURFACE_CURVE('',#163796,(#163800,#163807),.PCURVE_S1.); +#163796 = LINE('',#163797,#163798); +#163797 = CARTESIAN_POINT('',(-0.635,0.327745739138,2.509055548476)); +#163798 = VECTOR('',#163799,1.); +#163799 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163800 = PCURVE('',#163741,#163801); +#163801 = DEFINITIONAL_REPRESENTATION('',(#163802),#163806); +#163802 = LINE('',#163803,#163804); +#163803 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#163804 = VECTOR('',#163805,1.); +#163805 = DIRECTION('',(0.E+000,1.)); +#163806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163807 = PCURVE('',#163808,#163813); +#163808 = CYLINDRICAL_SURFACE('',#163809,9.999999999999E-002); +#163809 = AXIS2_PLACEMENT_3D('',#163810,#163811,#163812); +#163810 = CARTESIAN_POINT('',(-0.635,0.340821720102,2.608196956182)); +#163811 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163812 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163813 = DEFINITIONAL_REPRESENTATION('',(#163814),#163817); +#163814 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163815,#163816), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161423 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161424 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161426 = ORIENTED_EDGE('',*,*,#161427,.F.); -#161427 = EDGE_CURVE('',#161341,#161401,#161428,.T.); -#161428 = SURFACE_CURVE('',#161429,(#161433,#161440),.PCURVE_S1.); -#161429 = LINE('',#161430,#161431); -#161430 = CARTESIAN_POINT('',(-0.425,0.706843139085,2.459055548476)); -#161431 = VECTOR('',#161432,1.); -#161432 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#161433 = PCURVE('',#161349,#161434); -#161434 = DEFINITIONAL_REPRESENTATION('',(#161435),#161439); -#161435 = LINE('',#161436,#161437); -#161436 = CARTESIAN_POINT('',(0.E+000,0.21)); -#161437 = VECTOR('',#161438,1.); -#161438 = DIRECTION('',(1.,0.E+000)); -#161439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161440 = PCURVE('',#161441,#161446); -#161441 = PLANE('',#161442); -#161442 = AXIS2_PLACEMENT_3D('',#161443,#161444,#161445); -#161443 = CARTESIAN_POINT('',(-0.425,0.875,0.E+000)); -#161444 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161445 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161446 = DEFINITIONAL_REPRESENTATION('',(#161447),#161451); -#161447 = LINE('',#161448,#161449); -#161448 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#161449 = VECTOR('',#161450,1.); -#161450 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#161451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161452 = ADVANCED_FACE('',(#161453),#161416,.F.); -#161453 = FACE_BOUND('',#161454,.F.); -#161454 = EDGE_LOOP('',(#161455,#161482,#161509,#161534)); -#161455 = ORIENTED_EDGE('',*,*,#161456,.T.); -#161456 = EDGE_CURVE('',#161401,#161457,#161459,.T.); -#161457 = VERTEX_POINT('',#161458); -#161458 = CARTESIAN_POINT('',(-0.425,0.240958766627,2.602963360557)); -#161459 = SURFACE_CURVE('',#161460,(#161465,#161471),.PCURVE_S1.); -#161460 = CIRCLE('',#161461,9.999999999999E-002); -#161461 = AXIS2_PLACEMENT_3D('',#161462,#161463,#161464); -#161462 = CARTESIAN_POINT('',(-0.425,0.340821720102,2.608196956182)); -#161463 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161464 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161465 = PCURVE('',#161416,#161466); -#161466 = DEFINITIONAL_REPRESENTATION('',(#161467),#161470); -#161467 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161468,#161469), +#163815 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163816 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163817 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163818 = ORIENTED_EDGE('',*,*,#163819,.F.); +#163819 = EDGE_CURVE('',#163733,#163793,#163820,.T.); +#163820 = SURFACE_CURVE('',#163821,(#163825,#163832),.PCURVE_S1.); +#163821 = LINE('',#163822,#163823); +#163822 = CARTESIAN_POINT('',(-0.425,0.706843139085,2.459055548476)); +#163823 = VECTOR('',#163824,1.); +#163824 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#163825 = PCURVE('',#163741,#163826); +#163826 = DEFINITIONAL_REPRESENTATION('',(#163827),#163831); +#163827 = LINE('',#163828,#163829); +#163828 = CARTESIAN_POINT('',(0.E+000,0.21)); +#163829 = VECTOR('',#163830,1.); +#163830 = DIRECTION('',(1.,0.E+000)); +#163831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163832 = PCURVE('',#163833,#163838); +#163833 = PLANE('',#163834); +#163834 = AXIS2_PLACEMENT_3D('',#163835,#163836,#163837); +#163835 = CARTESIAN_POINT('',(-0.425,0.875,0.E+000)); +#163836 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163837 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#163838 = DEFINITIONAL_REPRESENTATION('',(#163839),#163843); +#163839 = LINE('',#163840,#163841); +#163840 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#163841 = VECTOR('',#163842,1.); +#163842 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#163843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163844 = ADVANCED_FACE('',(#163845),#163808,.F.); +#163845 = FACE_BOUND('',#163846,.F.); +#163846 = EDGE_LOOP('',(#163847,#163874,#163901,#163926)); +#163847 = ORIENTED_EDGE('',*,*,#163848,.T.); +#163848 = EDGE_CURVE('',#163793,#163849,#163851,.T.); +#163849 = VERTEX_POINT('',#163850); +#163850 = CARTESIAN_POINT('',(-0.425,0.240958766627,2.602963360557)); +#163851 = SURFACE_CURVE('',#163852,(#163857,#163863),.PCURVE_S1.); +#163852 = CIRCLE('',#163853,9.999999999999E-002); +#163853 = AXIS2_PLACEMENT_3D('',#163854,#163855,#163856); +#163854 = CARTESIAN_POINT('',(-0.425,0.340821720102,2.608196956182)); +#163855 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163856 = DIRECTION('',(0.E+000,0.E+000,1.)); +#163857 = PCURVE('',#163808,#163858); +#163858 = DEFINITIONAL_REPRESENTATION('',(#163859),#163862); +#163859 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163860,#163861), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#161468 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161469 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163860 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#163861 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161471 = PCURVE('',#161441,#161472); -#161472 = DEFINITIONAL_REPRESENTATION('',(#161473),#161481); -#161473 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161474,#161475,#161476, - #161477,#161478,#161479,#161480),.UNSPECIFIED.,.T.,.F.) +#163863 = PCURVE('',#163833,#163864); +#163864 = DEFINITIONAL_REPRESENTATION('',(#163865),#163873); +#163865 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163866,#163867,#163868, + #163869,#163870,#163871,#163872),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161474 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#161475 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#161476 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#161477 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#161478 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#161479 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#161480 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#161481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161482 = ORIENTED_EDGE('',*,*,#161483,.T.); -#161483 = EDGE_CURVE('',#161457,#161484,#161486,.T.); -#161484 = VERTEX_POINT('',#161485); -#161485 = CARTESIAN_POINT('',(-0.845,0.240958766627,2.602963360557)); -#161486 = SURFACE_CURVE('',#161487,(#161491,#161497),.PCURVE_S1.); -#161487 = LINE('',#161488,#161489); -#161488 = CARTESIAN_POINT('',(-0.635,0.240958766627,2.602963360557)); -#161489 = VECTOR('',#161490,1.); -#161490 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161491 = PCURVE('',#161416,#161492); -#161492 = DEFINITIONAL_REPRESENTATION('',(#161493),#161496); -#161493 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161494,#161495), +#163866 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#163867 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#163868 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#163869 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#163870 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#163871 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#163872 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#163873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163874 = ORIENTED_EDGE('',*,*,#163875,.T.); +#163875 = EDGE_CURVE('',#163849,#163876,#163878,.T.); +#163876 = VERTEX_POINT('',#163877); +#163877 = CARTESIAN_POINT('',(-0.845,0.240958766627,2.602963360557)); +#163878 = SURFACE_CURVE('',#163879,(#163883,#163889),.PCURVE_S1.); +#163879 = LINE('',#163880,#163881); +#163880 = CARTESIAN_POINT('',(-0.635,0.240958766627,2.602963360557)); +#163881 = VECTOR('',#163882,1.); +#163882 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163883 = PCURVE('',#163808,#163884); +#163884 = DEFINITIONAL_REPRESENTATION('',(#163885),#163888); +#163885 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163886,#163887), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161494 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161495 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161497 = PCURVE('',#161498,#161503); -#161498 = PLANE('',#161499); -#161499 = AXIS2_PLACEMENT_3D('',#161500,#161501,#161502); -#161500 = CARTESIAN_POINT('',(-0.635,0.240958766627,2.602963360557)); -#161501 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); -#161502 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#161503 = DEFINITIONAL_REPRESENTATION('',(#161504),#161508); -#161504 = LINE('',#161505,#161506); -#161505 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); -#161506 = VECTOR('',#161507,1.); -#161507 = DIRECTION('',(0.E+000,-1.)); -#161508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161509 = ORIENTED_EDGE('',*,*,#161510,.T.); -#161510 = EDGE_CURVE('',#161484,#161373,#161511,.T.); -#161511 = SURFACE_CURVE('',#161512,(#161517,#161523),.PCURVE_S1.); -#161512 = CIRCLE('',#161513,9.999999999999E-002); -#161513 = AXIS2_PLACEMENT_3D('',#161514,#161515,#161516); -#161514 = CARTESIAN_POINT('',(-0.845,0.340821720102,2.608196956182)); -#161515 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161516 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); -#161517 = PCURVE('',#161416,#161518); -#161518 = DEFINITIONAL_REPRESENTATION('',(#161519),#161522); -#161519 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161520,#161521), +#163886 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#163887 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163889 = PCURVE('',#163890,#163895); +#163890 = PLANE('',#163891); +#163891 = AXIS2_PLACEMENT_3D('',#163892,#163893,#163894); +#163892 = CARTESIAN_POINT('',(-0.635,0.240958766627,2.602963360557)); +#163893 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); +#163894 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#163895 = DEFINITIONAL_REPRESENTATION('',(#163896),#163900); +#163896 = LINE('',#163897,#163898); +#163897 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); +#163898 = VECTOR('',#163899,1.); +#163899 = DIRECTION('',(0.E+000,-1.)); +#163900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163901 = ORIENTED_EDGE('',*,*,#163902,.T.); +#163902 = EDGE_CURVE('',#163876,#163765,#163903,.T.); +#163903 = SURFACE_CURVE('',#163904,(#163909,#163915),.PCURVE_S1.); +#163904 = CIRCLE('',#163905,9.999999999999E-002); +#163905 = AXIS2_PLACEMENT_3D('',#163906,#163907,#163908); +#163906 = CARTESIAN_POINT('',(-0.845,0.340821720102,2.608196956182)); +#163907 = DIRECTION('',(1.,0.E+000,0.E+000)); +#163908 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); +#163909 = PCURVE('',#163808,#163910); +#163910 = DEFINITIONAL_REPRESENTATION('',(#163911),#163914); +#163911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163912,#163913), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#161520 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161521 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163912 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#163913 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#163914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161523 = PCURVE('',#161388,#161524); -#161524 = DEFINITIONAL_REPRESENTATION('',(#161525),#161533); -#161525 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161526,#161527,#161528, - #161529,#161530,#161531,#161532),.UNSPECIFIED.,.F.,.F.) +#163915 = PCURVE('',#163780,#163916); +#163916 = DEFINITIONAL_REPRESENTATION('',(#163917),#163925); +#163917 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163918,#163919,#163920, + #163921,#163922,#163923,#163924),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161526 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#161527 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#161528 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#161529 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#161530 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#161531 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#161532 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#161533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161534 = ORIENTED_EDGE('',*,*,#161400,.T.); -#161535 = ADVANCED_FACE('',(#161536),#161498,.T.); -#161536 = FACE_BOUND('',#161537,.T.); -#161537 = EDGE_LOOP('',(#161538,#161539,#161562,#161590)); -#161538 = ORIENTED_EDGE('',*,*,#161483,.T.); -#161539 = ORIENTED_EDGE('',*,*,#161540,.F.); -#161540 = EDGE_CURVE('',#161541,#161484,#161543,.T.); -#161541 = VERTEX_POINT('',#161542); -#161542 = CARTESIAN_POINT('',(-0.845,0.219849248823,3.005756955187)); -#161543 = SURFACE_CURVE('',#161544,(#161548,#161555),.PCURVE_S1.); -#161544 = LINE('',#161545,#161546); -#161545 = CARTESIAN_POINT('',(-0.845,0.219849248823,3.005756955187)); -#161546 = VECTOR('',#161547,1.); -#161547 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#161548 = PCURVE('',#161498,#161549); -#161549 = DEFINITIONAL_REPRESENTATION('',(#161550),#161554); -#161550 = LINE('',#161551,#161552); -#161551 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#161552 = VECTOR('',#161553,1.); -#161553 = DIRECTION('',(-1.,0.E+000)); -#161554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161555 = PCURVE('',#161388,#161556); -#161556 = DEFINITIONAL_REPRESENTATION('',(#161557),#161561); -#161557 = LINE('',#161558,#161559); -#161558 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#161559 = VECTOR('',#161560,1.); -#161560 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#161561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#163918 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#163919 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#163920 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#163921 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#163922 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#163923 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#163924 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#163925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163926 = ORIENTED_EDGE('',*,*,#163792,.T.); +#163927 = ADVANCED_FACE('',(#163928),#163890,.T.); +#163928 = FACE_BOUND('',#163929,.T.); +#163929 = EDGE_LOOP('',(#163930,#163931,#163954,#163982)); +#163930 = ORIENTED_EDGE('',*,*,#163875,.T.); +#163931 = ORIENTED_EDGE('',*,*,#163932,.F.); +#163932 = EDGE_CURVE('',#163933,#163876,#163935,.T.); +#163933 = VERTEX_POINT('',#163934); +#163934 = CARTESIAN_POINT('',(-0.845,0.219849248823,3.005756955187)); +#163935 = SURFACE_CURVE('',#163936,(#163940,#163947),.PCURVE_S1.); +#163936 = LINE('',#163937,#163938); +#163937 = CARTESIAN_POINT('',(-0.845,0.219849248823,3.005756955187)); +#163938 = VECTOR('',#163939,1.); +#163939 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#163940 = PCURVE('',#163890,#163941); +#163941 = DEFINITIONAL_REPRESENTATION('',(#163942),#163946); +#163942 = LINE('',#163943,#163944); +#163943 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#163944 = VECTOR('',#163945,1.); +#163945 = DIRECTION('',(-1.,0.E+000)); +#163946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163947 = PCURVE('',#163780,#163948); +#163948 = DEFINITIONAL_REPRESENTATION('',(#163949),#163953); +#163949 = LINE('',#163950,#163951); +#163950 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#163951 = VECTOR('',#163952,1.); +#163952 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#163953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163954 = ORIENTED_EDGE('',*,*,#163955,.F.); +#163955 = EDGE_CURVE('',#163956,#163933,#163958,.T.); +#163956 = VERTEX_POINT('',#163957); +#163957 = CARTESIAN_POINT('',(-0.425,0.219849248823,3.005756955187)); +#163958 = SURFACE_CURVE('',#163959,(#163963,#163970),.PCURVE_S1.); +#163959 = LINE('',#163960,#163961); +#163960 = CARTESIAN_POINT('',(-0.635,0.219849248823,3.005756955187)); +#163961 = VECTOR('',#163962,1.); +#163962 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#163963 = PCURVE('',#163890,#163964); +#163964 = DEFINITIONAL_REPRESENTATION('',(#163965),#163969); +#163965 = LINE('',#163966,#163967); +#163966 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#163967 = VECTOR('',#163968,1.); +#163968 = DIRECTION('',(0.E+000,-1.)); +#163969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163970 = PCURVE('',#163971,#163976); +#163971 = PLANE('',#163972); +#163972 = AXIS2_PLACEMENT_3D('',#163973,#163974,#163975); +#163973 = CARTESIAN_POINT('',(-0.635,0.11,3.)); +#163974 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); +#163975 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#163976 = DEFINITIONAL_REPRESENTATION('',(#163977),#163981); +#163977 = LINE('',#163978,#163979); +#163978 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#163979 = VECTOR('',#163980,1.); +#163980 = DIRECTION('',(0.E+000,-1.)); +#163981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163982 = ORIENTED_EDGE('',*,*,#163983,.F.); +#163983 = EDGE_CURVE('',#163849,#163956,#163984,.T.); +#163984 = SURFACE_CURVE('',#163985,(#163989,#163996),.PCURVE_S1.); +#163985 = LINE('',#163986,#163987); +#163986 = CARTESIAN_POINT('',(-0.425,0.240958766627,2.602963360557)); +#163987 = VECTOR('',#163988,1.); +#163988 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#163989 = PCURVE('',#163890,#163990); +#163990 = DEFINITIONAL_REPRESENTATION('',(#163991),#163995); +#163991 = LINE('',#163992,#163993); +#163992 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); +#163993 = VECTOR('',#163994,1.); +#163994 = DIRECTION('',(1.,0.E+000)); +#163995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#163996 = PCURVE('',#163833,#163997); +#163997 = DEFINITIONAL_REPRESENTATION('',(#163998),#164002); +#163998 = LINE('',#163999,#164000); +#163999 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#164000 = VECTOR('',#164001,1.); +#164001 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#164002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164003 = ADVANCED_FACE('',(#164004),#163971,.T.); +#164004 = FACE_BOUND('',#164005,.T.); +#164005 = EDGE_LOOP('',(#164006,#164036,#164057,#164058)); +#164006 = ORIENTED_EDGE('',*,*,#164007,.F.); +#164007 = EDGE_CURVE('',#164008,#164010,#164012,.T.); +#164008 = VERTEX_POINT('',#164009); +#164009 = CARTESIAN_POINT('',(-0.425,1.507511769915E-004,2.994243044813) + ); +#164010 = VERTEX_POINT('',#164011); +#164011 = CARTESIAN_POINT('',(-0.845,1.507511769916E-004,2.994243044813) + ); +#164012 = SURFACE_CURVE('',#164013,(#164017,#164024),.PCURVE_S1.); +#164013 = LINE('',#164014,#164015); +#164014 = CARTESIAN_POINT('',(-0.635,1.507511769963E-004,2.994243044813) + ); +#164015 = VECTOR('',#164016,1.); +#164016 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164017 = PCURVE('',#163971,#164018); +#164018 = DEFINITIONAL_REPRESENTATION('',(#164019),#164023); +#164019 = LINE('',#164020,#164021); +#164020 = CARTESIAN_POINT('',(0.11,0.E+000)); +#164021 = VECTOR('',#164022,1.); +#164022 = DIRECTION('',(0.E+000,-1.)); +#164023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164024 = PCURVE('',#164025,#164030); +#164025 = PLANE('',#164026); +#164026 = AXIS2_PLACEMENT_3D('',#164027,#164028,#164029); +#164027 = CARTESIAN_POINT('',(-0.635,2.126026898096E-002,2.591449450184) + ); +#164028 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); +#164029 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#164030 = DEFINITIONAL_REPRESENTATION('',(#164031),#164035); +#164031 = LINE('',#164032,#164033); +#164032 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#164033 = VECTOR('',#164034,1.); +#164034 = DIRECTION('',(0.E+000,-1.)); +#164035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164036 = ORIENTED_EDGE('',*,*,#164037,.F.); +#164037 = EDGE_CURVE('',#163956,#164008,#164038,.T.); +#164038 = SURFACE_CURVE('',#164039,(#164043,#164050),.PCURVE_S1.); +#164039 = LINE('',#164040,#164041); +#164040 = CARTESIAN_POINT('',(-0.425,0.219849248823,3.005756955187)); +#164041 = VECTOR('',#164042,1.); +#164042 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#164043 = PCURVE('',#163971,#164044); +#164044 = DEFINITIONAL_REPRESENTATION('',(#164045),#164049); +#164045 = LINE('',#164046,#164047); +#164046 = CARTESIAN_POINT('',(-0.11,0.21)); +#164047 = VECTOR('',#164048,1.); +#164048 = DIRECTION('',(1.,0.E+000)); +#164049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164050 = PCURVE('',#163833,#164051); +#164051 = DEFINITIONAL_REPRESENTATION('',(#164052),#164056); +#164052 = LINE('',#164053,#164054); +#164053 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#164054 = VECTOR('',#164055,1.); +#164055 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#164056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164057 = ORIENTED_EDGE('',*,*,#163955,.T.); +#164058 = ORIENTED_EDGE('',*,*,#164059,.F.); +#164059 = EDGE_CURVE('',#164010,#163933,#164060,.T.); +#164060 = SURFACE_CURVE('',#164061,(#164065,#164072),.PCURVE_S1.); +#164061 = LINE('',#164062,#164063); +#164062 = CARTESIAN_POINT('',(-0.845,1.507511769892E-004,2.994243044813) + ); +#164063 = VECTOR('',#164064,1.); +#164064 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); +#164065 = PCURVE('',#163971,#164066); +#164066 = DEFINITIONAL_REPRESENTATION('',(#164067),#164071); +#164067 = LINE('',#164068,#164069); +#164068 = CARTESIAN_POINT('',(0.11,-0.21)); +#164069 = VECTOR('',#164070,1.); +#164070 = DIRECTION('',(-1.,0.E+000)); +#164071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164072 = PCURVE('',#163780,#164073); +#164073 = DEFINITIONAL_REPRESENTATION('',(#164074),#164078); +#164074 = LINE('',#164075,#164076); +#164075 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#164076 = VECTOR('',#164077,1.); +#164077 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#164078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164079 = ADVANCED_FACE('',(#164080),#164025,.T.); +#164080 = FACE_BOUND('',#164081,.T.); +#164081 = EDGE_LOOP('',(#164082,#164111,#164132,#164133)); +#164082 = ORIENTED_EDGE('',*,*,#164083,.F.); +#164083 = EDGE_CURVE('',#164084,#164086,#164088,.T.); +#164084 = VERTEX_POINT('',#164085); +#164085 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,2.591449450184) + ); +#164086 = VERTEX_POINT('',#164087); +#164087 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,2.591449450184) + ); +#164088 = SURFACE_CURVE('',#164089,(#164093,#164100),.PCURVE_S1.); +#164089 = LINE('',#164090,#164091); +#164090 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,2.591449450184) + ); +#164091 = VECTOR('',#164092,1.); +#164092 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164093 = PCURVE('',#164025,#164094); +#164094 = DEFINITIONAL_REPRESENTATION('',(#164095),#164099); +#164095 = LINE('',#164096,#164097); +#164096 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); +#164097 = VECTOR('',#164098,1.); +#164098 = DIRECTION('',(0.E+000,-1.)); +#164099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164100 = PCURVE('',#164101,#164106); +#164101 = CYLINDRICAL_SURFACE('',#164102,0.32); +#164102 = AXIS2_PLACEMENT_3D('',#164103,#164104,#164105); +#164103 = CARTESIAN_POINT('',(-0.635,0.340821720102,2.608196956182)); +#164104 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164105 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164106 = DEFINITIONAL_REPRESENTATION('',(#164107),#164110); +#164107 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164108,#164109), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#164108 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164109 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161562 = ORIENTED_EDGE('',*,*,#161563,.F.); -#161563 = EDGE_CURVE('',#161564,#161541,#161566,.T.); -#161564 = VERTEX_POINT('',#161565); -#161565 = CARTESIAN_POINT('',(-0.425,0.219849248823,3.005756955187)); -#161566 = SURFACE_CURVE('',#161567,(#161571,#161578),.PCURVE_S1.); -#161567 = LINE('',#161568,#161569); -#161568 = CARTESIAN_POINT('',(-0.635,0.219849248823,3.005756955187)); -#161569 = VECTOR('',#161570,1.); -#161570 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161571 = PCURVE('',#161498,#161572); -#161572 = DEFINITIONAL_REPRESENTATION('',(#161573),#161577); -#161573 = LINE('',#161574,#161575); -#161574 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#161575 = VECTOR('',#161576,1.); -#161576 = DIRECTION('',(0.E+000,-1.)); -#161577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161578 = PCURVE('',#161579,#161584); -#161579 = PLANE('',#161580); -#161580 = AXIS2_PLACEMENT_3D('',#161581,#161582,#161583); -#161581 = CARTESIAN_POINT('',(-0.635,0.11,3.)); -#161582 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); -#161583 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#161584 = DEFINITIONAL_REPRESENTATION('',(#161585),#161589); -#161585 = LINE('',#161586,#161587); -#161586 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#161587 = VECTOR('',#161588,1.); -#161588 = DIRECTION('',(0.E+000,-1.)); -#161589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161590 = ORIENTED_EDGE('',*,*,#161591,.F.); -#161591 = EDGE_CURVE('',#161457,#161564,#161592,.T.); -#161592 = SURFACE_CURVE('',#161593,(#161597,#161604),.PCURVE_S1.); -#161593 = LINE('',#161594,#161595); -#161594 = CARTESIAN_POINT('',(-0.425,0.240958766627,2.602963360557)); -#161595 = VECTOR('',#161596,1.); -#161596 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#161597 = PCURVE('',#161498,#161598); -#161598 = DEFINITIONAL_REPRESENTATION('',(#161599),#161603); -#161599 = LINE('',#161600,#161601); -#161600 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); -#161601 = VECTOR('',#161602,1.); -#161602 = DIRECTION('',(1.,0.E+000)); -#161603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161604 = PCURVE('',#161441,#161605); -#161605 = DEFINITIONAL_REPRESENTATION('',(#161606),#161610); -#161606 = LINE('',#161607,#161608); -#161607 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#161608 = VECTOR('',#161609,1.); -#161609 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#161610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161611 = ADVANCED_FACE('',(#161612),#161579,.T.); -#161612 = FACE_BOUND('',#161613,.T.); -#161613 = EDGE_LOOP('',(#161614,#161644,#161665,#161666)); -#161614 = ORIENTED_EDGE('',*,*,#161615,.F.); -#161615 = EDGE_CURVE('',#161616,#161618,#161620,.T.); -#161616 = VERTEX_POINT('',#161617); -#161617 = CARTESIAN_POINT('',(-0.425,1.507511769915E-004,2.994243044813) - ); -#161618 = VERTEX_POINT('',#161619); -#161619 = CARTESIAN_POINT('',(-0.845,1.507511769916E-004,2.994243044813) - ); -#161620 = SURFACE_CURVE('',#161621,(#161625,#161632),.PCURVE_S1.); -#161621 = LINE('',#161622,#161623); -#161622 = CARTESIAN_POINT('',(-0.635,1.507511769963E-004,2.994243044813) +#164111 = ORIENTED_EDGE('',*,*,#164112,.F.); +#164112 = EDGE_CURVE('',#164008,#164084,#164113,.T.); +#164113 = SURFACE_CURVE('',#164114,(#164118,#164125),.PCURVE_S1.); +#164114 = LINE('',#164115,#164116); +#164115 = CARTESIAN_POINT('',(-0.425,1.507511769892E-004,2.994243044813) ); -#161623 = VECTOR('',#161624,1.); -#161624 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161625 = PCURVE('',#161579,#161626); -#161626 = DEFINITIONAL_REPRESENTATION('',(#161627),#161631); -#161627 = LINE('',#161628,#161629); -#161628 = CARTESIAN_POINT('',(0.11,0.E+000)); -#161629 = VECTOR('',#161630,1.); -#161630 = DIRECTION('',(0.E+000,-1.)); -#161631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161632 = PCURVE('',#161633,#161638); -#161633 = PLANE('',#161634); -#161634 = AXIS2_PLACEMENT_3D('',#161635,#161636,#161637); -#161635 = CARTESIAN_POINT('',(-0.635,2.126026898096E-002,2.591449450184) - ); -#161636 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); -#161637 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#161638 = DEFINITIONAL_REPRESENTATION('',(#161639),#161643); -#161639 = LINE('',#161640,#161641); -#161640 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#161641 = VECTOR('',#161642,1.); -#161642 = DIRECTION('',(0.E+000,-1.)); -#161643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161644 = ORIENTED_EDGE('',*,*,#161645,.F.); -#161645 = EDGE_CURVE('',#161564,#161616,#161646,.T.); -#161646 = SURFACE_CURVE('',#161647,(#161651,#161658),.PCURVE_S1.); -#161647 = LINE('',#161648,#161649); -#161648 = CARTESIAN_POINT('',(-0.425,0.219849248823,3.005756955187)); -#161649 = VECTOR('',#161650,1.); -#161650 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#161651 = PCURVE('',#161579,#161652); -#161652 = DEFINITIONAL_REPRESENTATION('',(#161653),#161657); -#161653 = LINE('',#161654,#161655); -#161654 = CARTESIAN_POINT('',(-0.11,0.21)); -#161655 = VECTOR('',#161656,1.); -#161656 = DIRECTION('',(1.,0.E+000)); -#161657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164116 = VECTOR('',#164117,1.); +#164117 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#164118 = PCURVE('',#164025,#164119); +#164119 = DEFINITIONAL_REPRESENTATION('',(#164120),#164124); +#164120 = LINE('',#164121,#164122); +#164121 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#164122 = VECTOR('',#164123,1.); +#164123 = DIRECTION('',(1.,0.E+000)); +#164124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161658 = PCURVE('',#161441,#161659); -#161659 = DEFINITIONAL_REPRESENTATION('',(#161660),#161664); -#161660 = LINE('',#161661,#161662); -#161661 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#161662 = VECTOR('',#161663,1.); -#161663 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#161664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164125 = PCURVE('',#163833,#164126); +#164126 = DEFINITIONAL_REPRESENTATION('',(#164127),#164131); +#164127 = LINE('',#164128,#164129); +#164128 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#164129 = VECTOR('',#164130,1.); +#164130 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#164131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161665 = ORIENTED_EDGE('',*,*,#161563,.T.); -#161666 = ORIENTED_EDGE('',*,*,#161667,.F.); -#161667 = EDGE_CURVE('',#161618,#161541,#161668,.T.); -#161668 = SURFACE_CURVE('',#161669,(#161673,#161680),.PCURVE_S1.); -#161669 = LINE('',#161670,#161671); -#161670 = CARTESIAN_POINT('',(-0.845,1.507511769892E-004,2.994243044813) +#164132 = ORIENTED_EDGE('',*,*,#164007,.T.); +#164133 = ORIENTED_EDGE('',*,*,#164134,.F.); +#164134 = EDGE_CURVE('',#164086,#164010,#164135,.T.); +#164135 = SURFACE_CURVE('',#164136,(#164140,#164147),.PCURVE_S1.); +#164136 = LINE('',#164137,#164138); +#164137 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,2.591449450184) ); -#161671 = VECTOR('',#161672,1.); -#161672 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); -#161673 = PCURVE('',#161579,#161674); -#161674 = DEFINITIONAL_REPRESENTATION('',(#161675),#161679); -#161675 = LINE('',#161676,#161677); -#161676 = CARTESIAN_POINT('',(0.11,-0.21)); -#161677 = VECTOR('',#161678,1.); -#161678 = DIRECTION('',(-1.,0.E+000)); -#161679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164138 = VECTOR('',#164139,1.); +#164139 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#164140 = PCURVE('',#164025,#164141); +#164141 = DEFINITIONAL_REPRESENTATION('',(#164142),#164146); +#164142 = LINE('',#164143,#164144); +#164143 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); +#164144 = VECTOR('',#164145,1.); +#164145 = DIRECTION('',(-1.,0.E+000)); +#164146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164147 = PCURVE('',#163780,#164148); +#164148 = DEFINITIONAL_REPRESENTATION('',(#164149),#164153); +#164149 = LINE('',#164150,#164151); +#164150 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#164151 = VECTOR('',#164152,1.); +#164152 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#164153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164154 = ADVANCED_FACE('',(#164155),#164101,.T.); +#164155 = FACE_BOUND('',#164156,.T.); +#164156 = EDGE_LOOP('',(#164157,#164186,#164207,#164208)); +#164157 = ORIENTED_EDGE('',*,*,#164158,.F.); +#164158 = EDGE_CURVE('',#164159,#164161,#164163,.T.); +#164159 = VERTEX_POINT('',#164160); +#164160 = CARTESIAN_POINT('',(-0.425,0.298978581017,2.290944451524)); +#164161 = VERTEX_POINT('',#164162); +#164162 = CARTESIAN_POINT('',(-0.845,0.298978581017,2.290944451524)); +#164163 = SURFACE_CURVE('',#164164,(#164168,#164174),.PCURVE_S1.); +#164164 = LINE('',#164165,#164166); +#164165 = CARTESIAN_POINT('',(-0.635,0.298978581017,2.290944451524)); +#164166 = VECTOR('',#164167,1.); +#164167 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164168 = PCURVE('',#164101,#164169); +#164169 = DEFINITIONAL_REPRESENTATION('',(#164170),#164173); +#164170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164171,#164172), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#164171 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164172 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161680 = PCURVE('',#161388,#161681); -#161681 = DEFINITIONAL_REPRESENTATION('',(#161682),#161686); -#161682 = LINE('',#161683,#161684); -#161683 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#161684 = VECTOR('',#161685,1.); -#161685 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#161686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161687 = ADVANCED_FACE('',(#161688),#161633,.T.); -#161688 = FACE_BOUND('',#161689,.T.); -#161689 = EDGE_LOOP('',(#161690,#161719,#161740,#161741)); -#161690 = ORIENTED_EDGE('',*,*,#161691,.F.); -#161691 = EDGE_CURVE('',#161692,#161694,#161696,.T.); -#161692 = VERTEX_POINT('',#161693); -#161693 = CARTESIAN_POINT('',(-0.425,2.126026898096E-002,2.591449450184) - ); -#161694 = VERTEX_POINT('',#161695); -#161695 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,2.591449450184) - ); -#161696 = SURFACE_CURVE('',#161697,(#161701,#161708),.PCURVE_S1.); -#161697 = LINE('',#161698,#161699); -#161698 = CARTESIAN_POINT('',(-0.635,2.126026898095E-002,2.591449450184) - ); -#161699 = VECTOR('',#161700,1.); -#161700 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161701 = PCURVE('',#161633,#161702); -#161702 = DEFINITIONAL_REPRESENTATION('',(#161703),#161707); -#161703 = LINE('',#161704,#161705); -#161704 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); -#161705 = VECTOR('',#161706,1.); -#161706 = DIRECTION('',(0.E+000,-1.)); -#161707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161708 = PCURVE('',#161709,#161714); -#161709 = CYLINDRICAL_SURFACE('',#161710,0.32); -#161710 = AXIS2_PLACEMENT_3D('',#161711,#161712,#161713); -#161711 = CARTESIAN_POINT('',(-0.635,0.340821720102,2.608196956182)); -#161712 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161713 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161714 = DEFINITIONAL_REPRESENTATION('',(#161715),#161718); -#161715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161716,#161717), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161716 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161717 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161719 = ORIENTED_EDGE('',*,*,#161720,.F.); -#161720 = EDGE_CURVE('',#161616,#161692,#161721,.T.); -#161721 = SURFACE_CURVE('',#161722,(#161726,#161733),.PCURVE_S1.); -#161722 = LINE('',#161723,#161724); -#161723 = CARTESIAN_POINT('',(-0.425,1.507511769892E-004,2.994243044813) - ); -#161724 = VECTOR('',#161725,1.); -#161725 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#161726 = PCURVE('',#161633,#161727); -#161727 = DEFINITIONAL_REPRESENTATION('',(#161728),#161732); -#161728 = LINE('',#161729,#161730); -#161729 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#161730 = VECTOR('',#161731,1.); -#161731 = DIRECTION('',(1.,0.E+000)); -#161732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161733 = PCURVE('',#161441,#161734); -#161734 = DEFINITIONAL_REPRESENTATION('',(#161735),#161739); -#161735 = LINE('',#161736,#161737); -#161736 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#161737 = VECTOR('',#161738,1.); -#161738 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#161739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161740 = ORIENTED_EDGE('',*,*,#161615,.T.); -#161741 = ORIENTED_EDGE('',*,*,#161742,.F.); -#161742 = EDGE_CURVE('',#161694,#161618,#161743,.T.); -#161743 = SURFACE_CURVE('',#161744,(#161748,#161755),.PCURVE_S1.); -#161744 = LINE('',#161745,#161746); -#161745 = CARTESIAN_POINT('',(-0.845,2.126026898096E-002,2.591449450184) - ); -#161746 = VECTOR('',#161747,1.); -#161747 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#161748 = PCURVE('',#161633,#161749); -#161749 = DEFINITIONAL_REPRESENTATION('',(#161750),#161754); -#161750 = LINE('',#161751,#161752); -#161751 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); -#161752 = VECTOR('',#161753,1.); -#161753 = DIRECTION('',(-1.,0.E+000)); -#161754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161755 = PCURVE('',#161388,#161756); -#161756 = DEFINITIONAL_REPRESENTATION('',(#161757),#161761); -#161757 = LINE('',#161758,#161759); -#161758 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#161759 = VECTOR('',#161760,1.); -#161760 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#161761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161762 = ADVANCED_FACE('',(#161763),#161709,.T.); -#161763 = FACE_BOUND('',#161764,.T.); -#161764 = EDGE_LOOP('',(#161765,#161794,#161815,#161816)); -#161765 = ORIENTED_EDGE('',*,*,#161766,.F.); -#161766 = EDGE_CURVE('',#161767,#161769,#161771,.T.); -#161767 = VERTEX_POINT('',#161768); -#161768 = CARTESIAN_POINT('',(-0.425,0.298978581017,2.290944451524)); -#161769 = VERTEX_POINT('',#161770); -#161770 = CARTESIAN_POINT('',(-0.845,0.298978581017,2.290944451524)); -#161771 = SURFACE_CURVE('',#161772,(#161776,#161782),.PCURVE_S1.); -#161772 = LINE('',#161773,#161774); -#161773 = CARTESIAN_POINT('',(-0.635,0.298978581017,2.290944451524)); -#161774 = VECTOR('',#161775,1.); -#161775 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161776 = PCURVE('',#161709,#161777); -#161777 = DEFINITIONAL_REPRESENTATION('',(#161778),#161781); -#161778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161779,#161780), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161779 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161780 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161782 = PCURVE('',#161783,#161788); -#161783 = PLANE('',#161784); -#161784 = AXIS2_PLACEMENT_3D('',#161785,#161786,#161787); -#161785 = CARTESIAN_POINT('',(-0.635,0.678075980964,2.240944451524)); -#161786 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); -#161787 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#161788 = DEFINITIONAL_REPRESENTATION('',(#161789),#161793); -#161789 = LINE('',#161790,#161791); -#161790 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#161791 = VECTOR('',#161792,1.); -#161792 = DIRECTION('',(0.E+000,-1.)); -#161793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161794 = ORIENTED_EDGE('',*,*,#161795,.F.); -#161795 = EDGE_CURVE('',#161692,#161767,#161796,.T.); -#161796 = SURFACE_CURVE('',#161797,(#161802,#161808),.PCURVE_S1.); -#161797 = CIRCLE('',#161798,0.32); -#161798 = AXIS2_PLACEMENT_3D('',#161799,#161800,#161801); -#161799 = CARTESIAN_POINT('',(-0.425,0.340821720102,2.608196956182)); -#161800 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161801 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); -#161802 = PCURVE('',#161709,#161803); -#161803 = DEFINITIONAL_REPRESENTATION('',(#161804),#161807); -#161804 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161805,#161806), +#164174 = PCURVE('',#164175,#164180); +#164175 = PLANE('',#164176); +#164176 = AXIS2_PLACEMENT_3D('',#164177,#164178,#164179); +#164177 = CARTESIAN_POINT('',(-0.635,0.678075980964,2.240944451524)); +#164178 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); +#164179 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#164180 = DEFINITIONAL_REPRESENTATION('',(#164181),#164185); +#164181 = LINE('',#164182,#164183); +#164182 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#164183 = VECTOR('',#164184,1.); +#164184 = DIRECTION('',(0.E+000,-1.)); +#164185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164186 = ORIENTED_EDGE('',*,*,#164187,.F.); +#164187 = EDGE_CURVE('',#164084,#164159,#164188,.T.); +#164188 = SURFACE_CURVE('',#164189,(#164194,#164200),.PCURVE_S1.); +#164189 = CIRCLE('',#164190,0.32); +#164190 = AXIS2_PLACEMENT_3D('',#164191,#164192,#164193); +#164191 = CARTESIAN_POINT('',(-0.425,0.340821720102,2.608196956182)); +#164192 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164193 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); +#164194 = PCURVE('',#164101,#164195); +#164195 = DEFINITIONAL_REPRESENTATION('',(#164196),#164199); +#164196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164197,#164198), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#161805 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#161806 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#161807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161808 = PCURVE('',#161441,#161809); -#161809 = DEFINITIONAL_REPRESENTATION('',(#161810),#161814); -#161810 = CIRCLE('',#161811,0.32); -#161811 = AXIS2_PLACEMENT_2D('',#161812,#161813); -#161812 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#161813 = DIRECTION('',(-1.,1.694065894509E-015)); -#161814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161815 = ORIENTED_EDGE('',*,*,#161691,.T.); -#161816 = ORIENTED_EDGE('',*,*,#161817,.F.); -#161817 = EDGE_CURVE('',#161769,#161694,#161818,.T.); -#161818 = SURFACE_CURVE('',#161819,(#161824,#161830),.PCURVE_S1.); -#161819 = CIRCLE('',#161820,0.32); -#161820 = AXIS2_PLACEMENT_3D('',#161821,#161822,#161823); -#161821 = CARTESIAN_POINT('',(-0.845,0.340821720102,2.608196956182)); -#161822 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161823 = DIRECTION('',(0.E+000,0.E+000,1.)); -#161824 = PCURVE('',#161709,#161825); -#161825 = DEFINITIONAL_REPRESENTATION('',(#161826),#161829); -#161826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161827,#161828), +#164197 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164198 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164200 = PCURVE('',#163833,#164201); +#164201 = DEFINITIONAL_REPRESENTATION('',(#164202),#164206); +#164202 = CIRCLE('',#164203,0.32); +#164203 = AXIS2_PLACEMENT_2D('',#164204,#164205); +#164204 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#164205 = DIRECTION('',(-1.,1.694065894509E-015)); +#164206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164207 = ORIENTED_EDGE('',*,*,#164083,.T.); +#164208 = ORIENTED_EDGE('',*,*,#164209,.F.); +#164209 = EDGE_CURVE('',#164161,#164086,#164210,.T.); +#164210 = SURFACE_CURVE('',#164211,(#164216,#164222),.PCURVE_S1.); +#164211 = CIRCLE('',#164212,0.32); +#164212 = AXIS2_PLACEMENT_3D('',#164213,#164214,#164215); +#164213 = CARTESIAN_POINT('',(-0.845,0.340821720102,2.608196956182)); +#164214 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164215 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164216 = PCURVE('',#164101,#164217); +#164217 = DEFINITIONAL_REPRESENTATION('',(#164218),#164221); +#164218 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164219,#164220), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#161827 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#161828 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#161829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161830 = PCURVE('',#161388,#161831); -#161831 = DEFINITIONAL_REPRESENTATION('',(#161832),#161836); -#161832 = CIRCLE('',#161833,0.32); -#161833 = AXIS2_PLACEMENT_2D('',#161834,#161835); -#161834 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#161835 = DIRECTION('',(1.,0.E+000)); -#161836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161837 = ADVANCED_FACE('',(#161838),#161783,.T.); -#161838 = FACE_BOUND('',#161839,.T.); -#161839 = EDGE_LOOP('',(#161840,#161869,#161890,#161891)); -#161840 = ORIENTED_EDGE('',*,*,#161841,.T.); -#161841 = EDGE_CURVE('',#161842,#161844,#161846,.T.); -#161842 = VERTEX_POINT('',#161843); -#161843 = CARTESIAN_POINT('',(-0.845,0.678075980964,2.240944451524)); -#161844 = VERTEX_POINT('',#161845); -#161845 = CARTESIAN_POINT('',(-0.425,0.678075980964,2.240944451524)); -#161846 = SURFACE_CURVE('',#161847,(#161851,#161858),.PCURVE_S1.); -#161847 = LINE('',#161848,#161849); -#161848 = CARTESIAN_POINT('',(-0.635,0.678075980964,2.240944451524)); -#161849 = VECTOR('',#161850,1.); -#161850 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161851 = PCURVE('',#161783,#161852); -#161852 = DEFINITIONAL_REPRESENTATION('',(#161853),#161857); -#161853 = LINE('',#161854,#161855); -#161854 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#161855 = VECTOR('',#161856,1.); -#161856 = DIRECTION('',(0.E+000,1.)); -#161857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161858 = PCURVE('',#161859,#161864); -#161859 = CYLINDRICAL_SURFACE('',#161860,1.E-001); -#161860 = AXIS2_PLACEMENT_3D('',#161861,#161862,#161863); -#161861 = CARTESIAN_POINT('',(-0.635,0.665,2.141803043818)); -#161862 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161863 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161864 = DEFINITIONAL_REPRESENTATION('',(#161865),#161868); -#161865 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161866,#161867), +#164219 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164220 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164221 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164222 = PCURVE('',#163780,#164223); +#164223 = DEFINITIONAL_REPRESENTATION('',(#164224),#164228); +#164224 = CIRCLE('',#164225,0.32); +#164225 = AXIS2_PLACEMENT_2D('',#164226,#164227); +#164226 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#164227 = DIRECTION('',(1.,0.E+000)); +#164228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164229 = ADVANCED_FACE('',(#164230),#164175,.T.); +#164230 = FACE_BOUND('',#164231,.T.); +#164231 = EDGE_LOOP('',(#164232,#164261,#164282,#164283)); +#164232 = ORIENTED_EDGE('',*,*,#164233,.T.); +#164233 = EDGE_CURVE('',#164234,#164236,#164238,.T.); +#164234 = VERTEX_POINT('',#164235); +#164235 = CARTESIAN_POINT('',(-0.845,0.678075980964,2.240944451524)); +#164236 = VERTEX_POINT('',#164237); +#164237 = CARTESIAN_POINT('',(-0.425,0.678075980964,2.240944451524)); +#164238 = SURFACE_CURVE('',#164239,(#164243,#164250),.PCURVE_S1.); +#164239 = LINE('',#164240,#164241); +#164240 = CARTESIAN_POINT('',(-0.635,0.678075980964,2.240944451524)); +#164241 = VECTOR('',#164242,1.); +#164242 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164243 = PCURVE('',#164175,#164244); +#164244 = DEFINITIONAL_REPRESENTATION('',(#164245),#164249); +#164245 = LINE('',#164246,#164247); +#164246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#164247 = VECTOR('',#164248,1.); +#164248 = DIRECTION('',(0.E+000,1.)); +#164249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164250 = PCURVE('',#164251,#164256); +#164251 = CYLINDRICAL_SURFACE('',#164252,1.E-001); +#164252 = AXIS2_PLACEMENT_3D('',#164253,#164254,#164255); +#164253 = CARTESIAN_POINT('',(-0.635,0.665,2.141803043818)); +#164254 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164255 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164256 = DEFINITIONAL_REPRESENTATION('',(#164257),#164260); +#164257 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164258,#164259), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#161866 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#161867 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#161868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164258 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#164259 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#164260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161869 = ORIENTED_EDGE('',*,*,#161870,.F.); -#161870 = EDGE_CURVE('',#161767,#161844,#161871,.T.); -#161871 = SURFACE_CURVE('',#161872,(#161876,#161883),.PCURVE_S1.); -#161872 = LINE('',#161873,#161874); -#161873 = CARTESIAN_POINT('',(-0.425,0.298978581017,2.290944451524)); -#161874 = VECTOR('',#161875,1.); -#161875 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#161876 = PCURVE('',#161783,#161877); -#161877 = DEFINITIONAL_REPRESENTATION('',(#161878),#161882); -#161878 = LINE('',#161879,#161880); -#161879 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#161880 = VECTOR('',#161881,1.); -#161881 = DIRECTION('',(1.,0.E+000)); -#161882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161883 = PCURVE('',#161441,#161884); -#161884 = DEFINITIONAL_REPRESENTATION('',(#161885),#161889); -#161885 = LINE('',#161886,#161887); -#161886 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#161887 = VECTOR('',#161888,1.); -#161888 = DIRECTION('',(0.130759809642,0.991414077055)); -#161889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161890 = ORIENTED_EDGE('',*,*,#161766,.T.); -#161891 = ORIENTED_EDGE('',*,*,#161892,.F.); -#161892 = EDGE_CURVE('',#161842,#161769,#161893,.T.); -#161893 = SURFACE_CURVE('',#161894,(#161898,#161905),.PCURVE_S1.); -#161894 = LINE('',#161895,#161896); -#161895 = CARTESIAN_POINT('',(-0.845,0.678075980964,2.240944451524)); -#161896 = VECTOR('',#161897,1.); -#161897 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#161898 = PCURVE('',#161783,#161899); -#161899 = DEFINITIONAL_REPRESENTATION('',(#161900),#161904); -#161900 = LINE('',#161901,#161902); -#161901 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#161902 = VECTOR('',#161903,1.); -#161903 = DIRECTION('',(-1.,0.E+000)); -#161904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161905 = PCURVE('',#161388,#161906); -#161906 = DEFINITIONAL_REPRESENTATION('',(#161907),#161911); -#161907 = LINE('',#161908,#161909); -#161908 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#161909 = VECTOR('',#161910,1.); -#161910 = DIRECTION('',(0.130759809642,-0.991414077055)); -#161911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161912 = ADVANCED_FACE('',(#161913),#161859,.F.); -#161913 = FACE_BOUND('',#161914,.F.); -#161914 = EDGE_LOOP('',(#161915,#161942,#161943,#161970)); -#161915 = ORIENTED_EDGE('',*,*,#161916,.T.); -#161916 = EDGE_CURVE('',#161917,#161842,#161919,.T.); -#161917 = VERTEX_POINT('',#161918); -#161918 = CARTESIAN_POINT('',(-0.845,0.765,2.141803043818)); -#161919 = SURFACE_CURVE('',#161920,(#161925,#161931),.PCURVE_S1.); -#161920 = CIRCLE('',#161921,1.E-001); -#161921 = AXIS2_PLACEMENT_3D('',#161922,#161923,#161924); -#161922 = CARTESIAN_POINT('',(-0.845,0.665,2.141803043818)); -#161923 = DIRECTION('',(1.,0.E+000,0.E+000)); -#161924 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#161925 = PCURVE('',#161859,#161926); -#161926 = DEFINITIONAL_REPRESENTATION('',(#161927),#161930); -#161927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161928,#161929), +#164261 = ORIENTED_EDGE('',*,*,#164262,.F.); +#164262 = EDGE_CURVE('',#164159,#164236,#164263,.T.); +#164263 = SURFACE_CURVE('',#164264,(#164268,#164275),.PCURVE_S1.); +#164264 = LINE('',#164265,#164266); +#164265 = CARTESIAN_POINT('',(-0.425,0.298978581017,2.290944451524)); +#164266 = VECTOR('',#164267,1.); +#164267 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#164268 = PCURVE('',#164175,#164269); +#164269 = DEFINITIONAL_REPRESENTATION('',(#164270),#164274); +#164270 = LINE('',#164271,#164272); +#164271 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#164272 = VECTOR('',#164273,1.); +#164273 = DIRECTION('',(1.,0.E+000)); +#164274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164275 = PCURVE('',#163833,#164276); +#164276 = DEFINITIONAL_REPRESENTATION('',(#164277),#164281); +#164277 = LINE('',#164278,#164279); +#164278 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#164279 = VECTOR('',#164280,1.); +#164280 = DIRECTION('',(0.130759809642,0.991414077055)); +#164281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164282 = ORIENTED_EDGE('',*,*,#164158,.T.); +#164283 = ORIENTED_EDGE('',*,*,#164284,.F.); +#164284 = EDGE_CURVE('',#164234,#164161,#164285,.T.); +#164285 = SURFACE_CURVE('',#164286,(#164290,#164297),.PCURVE_S1.); +#164286 = LINE('',#164287,#164288); +#164287 = CARTESIAN_POINT('',(-0.845,0.678075980964,2.240944451524)); +#164288 = VECTOR('',#164289,1.); +#164289 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#164290 = PCURVE('',#164175,#164291); +#164291 = DEFINITIONAL_REPRESENTATION('',(#164292),#164296); +#164292 = LINE('',#164293,#164294); +#164293 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#164294 = VECTOR('',#164295,1.); +#164295 = DIRECTION('',(-1.,0.E+000)); +#164296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164297 = PCURVE('',#163780,#164298); +#164298 = DEFINITIONAL_REPRESENTATION('',(#164299),#164303); +#164299 = LINE('',#164300,#164301); +#164300 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#164301 = VECTOR('',#164302,1.); +#164302 = DIRECTION('',(0.130759809642,-0.991414077055)); +#164303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164304 = ADVANCED_FACE('',(#164305),#164251,.F.); +#164305 = FACE_BOUND('',#164306,.F.); +#164306 = EDGE_LOOP('',(#164307,#164334,#164335,#164362)); +#164307 = ORIENTED_EDGE('',*,*,#164308,.T.); +#164308 = EDGE_CURVE('',#164309,#164234,#164311,.T.); +#164309 = VERTEX_POINT('',#164310); +#164310 = CARTESIAN_POINT('',(-0.845,0.765,2.141803043818)); +#164311 = SURFACE_CURVE('',#164312,(#164317,#164323),.PCURVE_S1.); +#164312 = CIRCLE('',#164313,1.E-001); +#164313 = AXIS2_PLACEMENT_3D('',#164314,#164315,#164316); +#164314 = CARTESIAN_POINT('',(-0.845,0.665,2.141803043818)); +#164315 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164316 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164317 = PCURVE('',#164251,#164318); +#164318 = DEFINITIONAL_REPRESENTATION('',(#164319),#164322); +#164319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164320,#164321), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#161928 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#161929 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#161930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164320 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#164321 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#164322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161931 = PCURVE('',#161388,#161932); -#161932 = DEFINITIONAL_REPRESENTATION('',(#161933),#161941); -#161933 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161934,#161935,#161936, - #161937,#161938,#161939,#161940),.UNSPECIFIED.,.T.,.F.) +#164323 = PCURVE('',#163780,#164324); +#164324 = DEFINITIONAL_REPRESENTATION('',(#164325),#164333); +#164325 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164326,#164327,#164328, + #164329,#164330,#164331,#164332),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161934 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#161935 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#161936 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#161937 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#161938 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#161939 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#161940 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#161941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161942 = ORIENTED_EDGE('',*,*,#161841,.T.); -#161943 = ORIENTED_EDGE('',*,*,#161944,.T.); -#161944 = EDGE_CURVE('',#161844,#161945,#161947,.T.); -#161945 = VERTEX_POINT('',#161946); -#161946 = CARTESIAN_POINT('',(-0.425,0.765,2.141803043818)); -#161947 = SURFACE_CURVE('',#161948,(#161953,#161959),.PCURVE_S1.); -#161948 = CIRCLE('',#161949,1.E-001); -#161949 = AXIS2_PLACEMENT_3D('',#161950,#161951,#161952); -#161950 = CARTESIAN_POINT('',(-0.425,0.665,2.141803043818)); -#161951 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161952 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); -#161953 = PCURVE('',#161859,#161954); -#161954 = DEFINITIONAL_REPRESENTATION('',(#161955),#161958); -#161955 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161956,#161957), +#164326 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#164327 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#164328 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#164329 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#164330 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#164331 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#164332 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#164333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164334 = ORIENTED_EDGE('',*,*,#164233,.T.); +#164335 = ORIENTED_EDGE('',*,*,#164336,.T.); +#164336 = EDGE_CURVE('',#164236,#164337,#164339,.T.); +#164337 = VERTEX_POINT('',#164338); +#164338 = CARTESIAN_POINT('',(-0.425,0.765,2.141803043818)); +#164339 = SURFACE_CURVE('',#164340,(#164345,#164351),.PCURVE_S1.); +#164340 = CIRCLE('',#164341,1.E-001); +#164341 = AXIS2_PLACEMENT_3D('',#164342,#164343,#164344); +#164342 = CARTESIAN_POINT('',(-0.425,0.665,2.141803043818)); +#164343 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164344 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); +#164345 = PCURVE('',#164251,#164346); +#164346 = DEFINITIONAL_REPRESENTATION('',(#164347),#164350); +#164347 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164348,#164349), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#161956 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#161957 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#161958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164348 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#164349 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#164350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#161959 = PCURVE('',#161441,#161960); -#161960 = DEFINITIONAL_REPRESENTATION('',(#161961),#161969); -#161961 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#161962,#161963,#161964, - #161965,#161966,#161967,#161968),.UNSPECIFIED.,.T.,.F.) +#164351 = PCURVE('',#163833,#164352); +#164352 = DEFINITIONAL_REPRESENTATION('',(#164353),#164361); +#164353 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164354,#164355,#164356, + #164357,#164358,#164359,#164360),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#161962 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#161963 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#161964 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#161965 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#161966 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#161967 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#161968 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#161969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161970 = ORIENTED_EDGE('',*,*,#161971,.T.); -#161971 = EDGE_CURVE('',#161945,#161917,#161972,.T.); -#161972 = SURFACE_CURVE('',#161973,(#161977,#161983),.PCURVE_S1.); -#161973 = LINE('',#161974,#161975); -#161974 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); -#161975 = VECTOR('',#161976,1.); -#161976 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#161977 = PCURVE('',#161859,#161978); -#161978 = DEFINITIONAL_REPRESENTATION('',(#161979),#161982); -#161979 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#161980,#161981), +#164354 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#164355 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#164356 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#164357 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#164358 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#164359 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#164360 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#164361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164362 = ORIENTED_EDGE('',*,*,#164363,.T.); +#164363 = EDGE_CURVE('',#164337,#164309,#164364,.T.); +#164364 = SURFACE_CURVE('',#164365,(#164369,#164375),.PCURVE_S1.); +#164365 = LINE('',#164366,#164367); +#164366 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); +#164367 = VECTOR('',#164368,1.); +#164368 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164369 = PCURVE('',#164251,#164370); +#164370 = DEFINITIONAL_REPRESENTATION('',(#164371),#164374); +#164371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164372,#164373), .UNSPECIFIED.,.F.,.F.,(2,2),(1.06,1.48),.PIECEWISE_BEZIER_KNOTS.); -#161980 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#161981 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#161982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161983 = PCURVE('',#159360,#161984); -#161984 = DEFINITIONAL_REPRESENTATION('',(#161985),#161989); -#161985 = LINE('',#161986,#161987); -#161986 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#161987 = VECTOR('',#161988,1.); -#161988 = DIRECTION('',(0.E+000,-1.)); -#161989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#161990 = ADVANCED_FACE('',(#161991),#162005,.T.); -#161991 = FACE_BOUND('',#161992,.T.); -#161992 = EDGE_LOOP('',(#161993,#162027,#162055,#162082)); -#161993 = ORIENTED_EDGE('',*,*,#161994,.F.); -#161994 = EDGE_CURVE('',#161995,#161997,#161999,.T.); -#161995 = VERTEX_POINT('',#161996); -#161996 = CARTESIAN_POINT('',(0.425,0.706843139085,2.459055548476)); -#161997 = VERTEX_POINT('',#161998); -#161998 = CARTESIAN_POINT('',(0.845,0.706843139085,2.459055548476)); -#161999 = SURFACE_CURVE('',#162000,(#162004,#162016),.PCURVE_S1.); -#162000 = LINE('',#162001,#162002); -#162001 = CARTESIAN_POINT('',(0.635,0.706843139085,2.459055548476)); -#162002 = VECTOR('',#162003,1.); -#162003 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162004 = PCURVE('',#162005,#162010); -#162005 = PLANE('',#162006); -#162006 = AXIS2_PLACEMENT_3D('',#162007,#162008,#162009); -#162007 = CARTESIAN_POINT('',(0.635,0.706843139085,2.459055548476)); -#162008 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); -#162009 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#162010 = DEFINITIONAL_REPRESENTATION('',(#162011),#162015); -#162011 = LINE('',#162012,#162013); -#162012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#162013 = VECTOR('',#162014,1.); -#162014 = DIRECTION('',(0.E+000,1.)); -#162015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162016 = PCURVE('',#162017,#162022); -#162017 = CYLINDRICAL_SURFACE('',#162018,0.32); -#162018 = AXIS2_PLACEMENT_3D('',#162019,#162020,#162021); -#162019 = CARTESIAN_POINT('',(0.635,0.665,2.141803043818)); -#162020 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162021 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162022 = DEFINITIONAL_REPRESENTATION('',(#162023),#162026); -#162023 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162024,#162025), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162024 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#162025 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#162026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162027 = ORIENTED_EDGE('',*,*,#162028,.F.); -#162028 = EDGE_CURVE('',#162029,#161995,#162031,.T.); -#162029 = VERTEX_POINT('',#162030); -#162030 = CARTESIAN_POINT('',(0.425,0.327745739138,2.509055548476)); -#162031 = SURFACE_CURVE('',#162032,(#162036,#162043),.PCURVE_S1.); -#162032 = LINE('',#162033,#162034); -#162033 = CARTESIAN_POINT('',(0.425,0.327745739138,2.509055548476)); -#162034 = VECTOR('',#162035,1.); -#162035 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#162036 = PCURVE('',#162005,#162037); -#162037 = DEFINITIONAL_REPRESENTATION('',(#162038),#162042); -#162038 = LINE('',#162039,#162040); -#162039 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#162040 = VECTOR('',#162041,1.); -#162041 = DIRECTION('',(-1.,0.E+000)); -#162042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162043 = PCURVE('',#162044,#162049); -#162044 = PLANE('',#162045); -#162045 = AXIS2_PLACEMENT_3D('',#162046,#162047,#162048); -#162046 = CARTESIAN_POINT('',(0.425,0.875,0.E+000)); -#162047 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162048 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162049 = DEFINITIONAL_REPRESENTATION('',(#162050),#162054); -#162050 = LINE('',#162051,#162052); -#162051 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#162052 = VECTOR('',#162053,1.); -#162053 = DIRECTION('',(-0.130759809642,0.991414077055)); -#162054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162055 = ORIENTED_EDGE('',*,*,#162056,.T.); -#162056 = EDGE_CURVE('',#162029,#162057,#162059,.T.); -#162057 = VERTEX_POINT('',#162058); -#162058 = CARTESIAN_POINT('',(0.845,0.327745739138,2.509055548476)); -#162059 = SURFACE_CURVE('',#162060,(#162064,#162071),.PCURVE_S1.); -#162060 = LINE('',#162061,#162062); -#162061 = CARTESIAN_POINT('',(0.635,0.327745739138,2.509055548476)); -#162062 = VECTOR('',#162063,1.); -#162063 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162064 = PCURVE('',#162005,#162065); -#162065 = DEFINITIONAL_REPRESENTATION('',(#162066),#162070); -#162066 = LINE('',#162067,#162068); -#162067 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#162068 = VECTOR('',#162069,1.); -#162069 = DIRECTION('',(0.E+000,1.)); -#162070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162071 = PCURVE('',#162072,#162077); -#162072 = CYLINDRICAL_SURFACE('',#162073,9.999999999999E-002); -#162073 = AXIS2_PLACEMENT_3D('',#162074,#162075,#162076); -#162074 = CARTESIAN_POINT('',(0.635,0.340821720102,2.608196956182)); -#162075 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162076 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162077 = DEFINITIONAL_REPRESENTATION('',(#162078),#162081); -#162078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162079,#162080), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162079 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162080 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164372 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#164373 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#164374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162082 = ORIENTED_EDGE('',*,*,#162083,.F.); -#162083 = EDGE_CURVE('',#161997,#162057,#162084,.T.); -#162084 = SURFACE_CURVE('',#162085,(#162089,#162096),.PCURVE_S1.); -#162085 = LINE('',#162086,#162087); -#162086 = CARTESIAN_POINT('',(0.845,0.706843139085,2.459055548476)); -#162087 = VECTOR('',#162088,1.); -#162088 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#162089 = PCURVE('',#162005,#162090); -#162090 = DEFINITIONAL_REPRESENTATION('',(#162091),#162095); -#162091 = LINE('',#162092,#162093); -#162092 = CARTESIAN_POINT('',(0.E+000,0.21)); -#162093 = VECTOR('',#162094,1.); -#162094 = DIRECTION('',(1.,0.E+000)); -#162095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162096 = PCURVE('',#162097,#162102); -#162097 = PLANE('',#162098); -#162098 = AXIS2_PLACEMENT_3D('',#162099,#162100,#162101); -#162099 = CARTESIAN_POINT('',(0.845,0.875,0.E+000)); -#162100 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162101 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162102 = DEFINITIONAL_REPRESENTATION('',(#162103),#162107); -#162103 = LINE('',#162104,#162105); -#162104 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#162105 = VECTOR('',#162106,1.); -#162106 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#162107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162108 = ADVANCED_FACE('',(#162109),#162072,.F.); -#162109 = FACE_BOUND('',#162110,.F.); -#162110 = EDGE_LOOP('',(#162111,#162138,#162165,#162190)); -#162111 = ORIENTED_EDGE('',*,*,#162112,.T.); -#162112 = EDGE_CURVE('',#162057,#162113,#162115,.T.); -#162113 = VERTEX_POINT('',#162114); -#162114 = CARTESIAN_POINT('',(0.845,0.240958766627,2.602963360557)); -#162115 = SURFACE_CURVE('',#162116,(#162121,#162127),.PCURVE_S1.); -#162116 = CIRCLE('',#162117,9.999999999999E-002); -#162117 = AXIS2_PLACEMENT_3D('',#162118,#162119,#162120); -#162118 = CARTESIAN_POINT('',(0.845,0.340821720102,2.608196956182)); -#162119 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162120 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162121 = PCURVE('',#162072,#162122); -#162122 = DEFINITIONAL_REPRESENTATION('',(#162123),#162126); -#162123 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162124,#162125), +#164375 = PCURVE('',#161752,#164376); +#164376 = DEFINITIONAL_REPRESENTATION('',(#164377),#164381); +#164377 = LINE('',#164378,#164379); +#164378 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#164379 = VECTOR('',#164380,1.); +#164380 = DIRECTION('',(0.E+000,-1.)); +#164381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164382 = ADVANCED_FACE('',(#164383),#164397,.T.); +#164383 = FACE_BOUND('',#164384,.T.); +#164384 = EDGE_LOOP('',(#164385,#164419,#164447,#164474)); +#164385 = ORIENTED_EDGE('',*,*,#164386,.F.); +#164386 = EDGE_CURVE('',#164387,#164389,#164391,.T.); +#164387 = VERTEX_POINT('',#164388); +#164388 = CARTESIAN_POINT('',(0.425,0.706843139085,2.459055548476)); +#164389 = VERTEX_POINT('',#164390); +#164390 = CARTESIAN_POINT('',(0.845,0.706843139085,2.459055548476)); +#164391 = SURFACE_CURVE('',#164392,(#164396,#164408),.PCURVE_S1.); +#164392 = LINE('',#164393,#164394); +#164393 = CARTESIAN_POINT('',(0.635,0.706843139085,2.459055548476)); +#164394 = VECTOR('',#164395,1.); +#164395 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164396 = PCURVE('',#164397,#164402); +#164397 = PLANE('',#164398); +#164398 = AXIS2_PLACEMENT_3D('',#164399,#164400,#164401); +#164399 = CARTESIAN_POINT('',(0.635,0.706843139085,2.459055548476)); +#164400 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); +#164401 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#164402 = DEFINITIONAL_REPRESENTATION('',(#164403),#164407); +#164403 = LINE('',#164404,#164405); +#164404 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#164405 = VECTOR('',#164406,1.); +#164406 = DIRECTION('',(0.E+000,1.)); +#164407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164408 = PCURVE('',#164409,#164414); +#164409 = CYLINDRICAL_SURFACE('',#164410,0.32); +#164410 = AXIS2_PLACEMENT_3D('',#164411,#164412,#164413); +#164411 = CARTESIAN_POINT('',(0.635,0.665,2.141803043818)); +#164412 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164413 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164414 = DEFINITIONAL_REPRESENTATION('',(#164415),#164418); +#164415 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164416,#164417), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#164416 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#164417 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#164418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164419 = ORIENTED_EDGE('',*,*,#164420,.F.); +#164420 = EDGE_CURVE('',#164421,#164387,#164423,.T.); +#164421 = VERTEX_POINT('',#164422); +#164422 = CARTESIAN_POINT('',(0.425,0.327745739138,2.509055548476)); +#164423 = SURFACE_CURVE('',#164424,(#164428,#164435),.PCURVE_S1.); +#164424 = LINE('',#164425,#164426); +#164425 = CARTESIAN_POINT('',(0.425,0.327745739138,2.509055548476)); +#164426 = VECTOR('',#164427,1.); +#164427 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#164428 = PCURVE('',#164397,#164429); +#164429 = DEFINITIONAL_REPRESENTATION('',(#164430),#164434); +#164430 = LINE('',#164431,#164432); +#164431 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#164432 = VECTOR('',#164433,1.); +#164433 = DIRECTION('',(-1.,0.E+000)); +#164434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164435 = PCURVE('',#164436,#164441); +#164436 = PLANE('',#164437); +#164437 = AXIS2_PLACEMENT_3D('',#164438,#164439,#164440); +#164438 = CARTESIAN_POINT('',(0.425,0.875,0.E+000)); +#164439 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164440 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164441 = DEFINITIONAL_REPRESENTATION('',(#164442),#164446); +#164442 = LINE('',#164443,#164444); +#164443 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#164444 = VECTOR('',#164445,1.); +#164445 = DIRECTION('',(-0.130759809642,0.991414077055)); +#164446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164447 = ORIENTED_EDGE('',*,*,#164448,.T.); +#164448 = EDGE_CURVE('',#164421,#164449,#164451,.T.); +#164449 = VERTEX_POINT('',#164450); +#164450 = CARTESIAN_POINT('',(0.845,0.327745739138,2.509055548476)); +#164451 = SURFACE_CURVE('',#164452,(#164456,#164463),.PCURVE_S1.); +#164452 = LINE('',#164453,#164454); +#164453 = CARTESIAN_POINT('',(0.635,0.327745739138,2.509055548476)); +#164454 = VECTOR('',#164455,1.); +#164455 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164456 = PCURVE('',#164397,#164457); +#164457 = DEFINITIONAL_REPRESENTATION('',(#164458),#164462); +#164458 = LINE('',#164459,#164460); +#164459 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#164460 = VECTOR('',#164461,1.); +#164461 = DIRECTION('',(0.E+000,1.)); +#164462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164463 = PCURVE('',#164464,#164469); +#164464 = CYLINDRICAL_SURFACE('',#164465,9.999999999999E-002); +#164465 = AXIS2_PLACEMENT_3D('',#164466,#164467,#164468); +#164466 = CARTESIAN_POINT('',(0.635,0.340821720102,2.608196956182)); +#164467 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164468 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164469 = DEFINITIONAL_REPRESENTATION('',(#164470),#164473); +#164470 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164471,#164472), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#164471 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164472 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164474 = ORIENTED_EDGE('',*,*,#164475,.F.); +#164475 = EDGE_CURVE('',#164389,#164449,#164476,.T.); +#164476 = SURFACE_CURVE('',#164477,(#164481,#164488),.PCURVE_S1.); +#164477 = LINE('',#164478,#164479); +#164478 = CARTESIAN_POINT('',(0.845,0.706843139085,2.459055548476)); +#164479 = VECTOR('',#164480,1.); +#164480 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#164481 = PCURVE('',#164397,#164482); +#164482 = DEFINITIONAL_REPRESENTATION('',(#164483),#164487); +#164483 = LINE('',#164484,#164485); +#164484 = CARTESIAN_POINT('',(0.E+000,0.21)); +#164485 = VECTOR('',#164486,1.); +#164486 = DIRECTION('',(1.,0.E+000)); +#164487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164488 = PCURVE('',#164489,#164494); +#164489 = PLANE('',#164490); +#164490 = AXIS2_PLACEMENT_3D('',#164491,#164492,#164493); +#164491 = CARTESIAN_POINT('',(0.845,0.875,0.E+000)); +#164492 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164493 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164494 = DEFINITIONAL_REPRESENTATION('',(#164495),#164499); +#164495 = LINE('',#164496,#164497); +#164496 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#164497 = VECTOR('',#164498,1.); +#164498 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#164499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164500 = ADVANCED_FACE('',(#164501),#164464,.F.); +#164501 = FACE_BOUND('',#164502,.F.); +#164502 = EDGE_LOOP('',(#164503,#164530,#164557,#164582)); +#164503 = ORIENTED_EDGE('',*,*,#164504,.T.); +#164504 = EDGE_CURVE('',#164449,#164505,#164507,.T.); +#164505 = VERTEX_POINT('',#164506); +#164506 = CARTESIAN_POINT('',(0.845,0.240958766627,2.602963360557)); +#164507 = SURFACE_CURVE('',#164508,(#164513,#164519),.PCURVE_S1.); +#164508 = CIRCLE('',#164509,9.999999999999E-002); +#164509 = AXIS2_PLACEMENT_3D('',#164510,#164511,#164512); +#164510 = CARTESIAN_POINT('',(0.845,0.340821720102,2.608196956182)); +#164511 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164512 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164513 = PCURVE('',#164464,#164514); +#164514 = DEFINITIONAL_REPRESENTATION('',(#164515),#164518); +#164515 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164516,#164517), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#162124 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162125 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164516 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164517 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162127 = PCURVE('',#162097,#162128); -#162128 = DEFINITIONAL_REPRESENTATION('',(#162129),#162137); -#162129 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162130,#162131,#162132, - #162133,#162134,#162135,#162136),.UNSPECIFIED.,.T.,.F.) +#164519 = PCURVE('',#164489,#164520); +#164520 = DEFINITIONAL_REPRESENTATION('',(#164521),#164529); +#164521 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164522,#164523,#164524, + #164525,#164526,#164527,#164528),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162130 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#162131 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#162132 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#162133 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#162134 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#162135 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#162136 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#162137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162138 = ORIENTED_EDGE('',*,*,#162139,.T.); -#162139 = EDGE_CURVE('',#162113,#162140,#162142,.T.); -#162140 = VERTEX_POINT('',#162141); -#162141 = CARTESIAN_POINT('',(0.425,0.240958766627,2.602963360557)); -#162142 = SURFACE_CURVE('',#162143,(#162147,#162153),.PCURVE_S1.); -#162143 = LINE('',#162144,#162145); -#162144 = CARTESIAN_POINT('',(0.635,0.240958766627,2.602963360557)); -#162145 = VECTOR('',#162146,1.); -#162146 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162147 = PCURVE('',#162072,#162148); -#162148 = DEFINITIONAL_REPRESENTATION('',(#162149),#162152); -#162149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162150,#162151), +#164522 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#164523 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#164524 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#164525 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#164526 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#164527 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#164528 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#164529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164530 = ORIENTED_EDGE('',*,*,#164531,.T.); +#164531 = EDGE_CURVE('',#164505,#164532,#164534,.T.); +#164532 = VERTEX_POINT('',#164533); +#164533 = CARTESIAN_POINT('',(0.425,0.240958766627,2.602963360557)); +#164534 = SURFACE_CURVE('',#164535,(#164539,#164545),.PCURVE_S1.); +#164535 = LINE('',#164536,#164537); +#164536 = CARTESIAN_POINT('',(0.635,0.240958766627,2.602963360557)); +#164537 = VECTOR('',#164538,1.); +#164538 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164539 = PCURVE('',#164464,#164540); +#164540 = DEFINITIONAL_REPRESENTATION('',(#164541),#164544); +#164541 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164542,#164543), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162150 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162151 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162153 = PCURVE('',#162154,#162159); -#162154 = PLANE('',#162155); -#162155 = AXIS2_PLACEMENT_3D('',#162156,#162157,#162158); -#162156 = CARTESIAN_POINT('',(0.635,0.240958766627,2.602963360557)); -#162157 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); -#162158 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#162159 = DEFINITIONAL_REPRESENTATION('',(#162160),#162164); -#162160 = LINE('',#162161,#162162); -#162161 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); -#162162 = VECTOR('',#162163,1.); -#162163 = DIRECTION('',(0.E+000,-1.)); -#162164 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162165 = ORIENTED_EDGE('',*,*,#162166,.T.); -#162166 = EDGE_CURVE('',#162140,#162029,#162167,.T.); -#162167 = SURFACE_CURVE('',#162168,(#162173,#162179),.PCURVE_S1.); -#162168 = CIRCLE('',#162169,9.999999999999E-002); -#162169 = AXIS2_PLACEMENT_3D('',#162170,#162171,#162172); -#162170 = CARTESIAN_POINT('',(0.425,0.340821720102,2.608196956182)); -#162171 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162172 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); -#162173 = PCURVE('',#162072,#162174); -#162174 = DEFINITIONAL_REPRESENTATION('',(#162175),#162178); -#162175 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162176,#162177), +#164542 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164543 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164545 = PCURVE('',#164546,#164551); +#164546 = PLANE('',#164547); +#164547 = AXIS2_PLACEMENT_3D('',#164548,#164549,#164550); +#164548 = CARTESIAN_POINT('',(0.635,0.240958766627,2.602963360557)); +#164549 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); +#164550 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#164551 = DEFINITIONAL_REPRESENTATION('',(#164552),#164556); +#164552 = LINE('',#164553,#164554); +#164553 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); +#164554 = VECTOR('',#164555,1.); +#164555 = DIRECTION('',(0.E+000,-1.)); +#164556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164557 = ORIENTED_EDGE('',*,*,#164558,.T.); +#164558 = EDGE_CURVE('',#164532,#164421,#164559,.T.); +#164559 = SURFACE_CURVE('',#164560,(#164565,#164571),.PCURVE_S1.); +#164560 = CIRCLE('',#164561,9.999999999999E-002); +#164561 = AXIS2_PLACEMENT_3D('',#164562,#164563,#164564); +#164562 = CARTESIAN_POINT('',(0.425,0.340821720102,2.608196956182)); +#164563 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164564 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); +#164565 = PCURVE('',#164464,#164566); +#164566 = DEFINITIONAL_REPRESENTATION('',(#164567),#164570); +#164567 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164568,#164569), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#162176 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162177 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164568 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164569 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162179 = PCURVE('',#162044,#162180); -#162180 = DEFINITIONAL_REPRESENTATION('',(#162181),#162189); -#162181 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162182,#162183,#162184, - #162185,#162186,#162187,#162188),.UNSPECIFIED.,.F.,.F.) +#164571 = PCURVE('',#164436,#164572); +#164572 = DEFINITIONAL_REPRESENTATION('',(#164573),#164581); +#164573 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164574,#164575,#164576, + #164577,#164578,#164579,#164580),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162182 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#162183 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#162184 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#162185 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#162186 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#162187 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#162188 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#162189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162190 = ORIENTED_EDGE('',*,*,#162056,.T.); -#162191 = ADVANCED_FACE('',(#162192),#162154,.T.); -#162192 = FACE_BOUND('',#162193,.T.); -#162193 = EDGE_LOOP('',(#162194,#162195,#162218,#162246)); -#162194 = ORIENTED_EDGE('',*,*,#162139,.T.); -#162195 = ORIENTED_EDGE('',*,*,#162196,.F.); -#162196 = EDGE_CURVE('',#162197,#162140,#162199,.T.); -#162197 = VERTEX_POINT('',#162198); -#162198 = CARTESIAN_POINT('',(0.425,0.219849248823,3.005756955187)); -#162199 = SURFACE_CURVE('',#162200,(#162204,#162211),.PCURVE_S1.); -#162200 = LINE('',#162201,#162202); -#162201 = CARTESIAN_POINT('',(0.425,0.219849248823,3.005756955187)); -#162202 = VECTOR('',#162203,1.); -#162203 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#162204 = PCURVE('',#162154,#162205); -#162205 = DEFINITIONAL_REPRESENTATION('',(#162206),#162210); -#162206 = LINE('',#162207,#162208); -#162207 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#162208 = VECTOR('',#162209,1.); -#162209 = DIRECTION('',(-1.,0.E+000)); -#162210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164574 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#164575 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#164576 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#164577 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#164578 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#164579 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#164580 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#164581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164582 = ORIENTED_EDGE('',*,*,#164448,.T.); +#164583 = ADVANCED_FACE('',(#164584),#164546,.T.); +#164584 = FACE_BOUND('',#164585,.T.); +#164585 = EDGE_LOOP('',(#164586,#164587,#164610,#164638)); +#164586 = ORIENTED_EDGE('',*,*,#164531,.T.); +#164587 = ORIENTED_EDGE('',*,*,#164588,.F.); +#164588 = EDGE_CURVE('',#164589,#164532,#164591,.T.); +#164589 = VERTEX_POINT('',#164590); +#164590 = CARTESIAN_POINT('',(0.425,0.219849248823,3.005756955187)); +#164591 = SURFACE_CURVE('',#164592,(#164596,#164603),.PCURVE_S1.); +#164592 = LINE('',#164593,#164594); +#164593 = CARTESIAN_POINT('',(0.425,0.219849248823,3.005756955187)); +#164594 = VECTOR('',#164595,1.); +#164595 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#164596 = PCURVE('',#164546,#164597); +#164597 = DEFINITIONAL_REPRESENTATION('',(#164598),#164602); +#164598 = LINE('',#164599,#164600); +#164599 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#164600 = VECTOR('',#164601,1.); +#164601 = DIRECTION('',(-1.,0.E+000)); +#164602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164603 = PCURVE('',#164436,#164604); +#164604 = DEFINITIONAL_REPRESENTATION('',(#164605),#164609); +#164605 = LINE('',#164606,#164607); +#164606 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#164607 = VECTOR('',#164608,1.); +#164608 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#164609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164610 = ORIENTED_EDGE('',*,*,#164611,.F.); +#164611 = EDGE_CURVE('',#164612,#164589,#164614,.T.); +#164612 = VERTEX_POINT('',#164613); +#164613 = CARTESIAN_POINT('',(0.845,0.219849248823,3.005756955187)); +#164614 = SURFACE_CURVE('',#164615,(#164619,#164626),.PCURVE_S1.); +#164615 = LINE('',#164616,#164617); +#164616 = CARTESIAN_POINT('',(0.635,0.219849248823,3.005756955187)); +#164617 = VECTOR('',#164618,1.); +#164618 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164619 = PCURVE('',#164546,#164620); +#164620 = DEFINITIONAL_REPRESENTATION('',(#164621),#164625); +#164621 = LINE('',#164622,#164623); +#164622 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#164623 = VECTOR('',#164624,1.); +#164624 = DIRECTION('',(0.E+000,-1.)); +#164625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164626 = PCURVE('',#164627,#164632); +#164627 = PLANE('',#164628); +#164628 = AXIS2_PLACEMENT_3D('',#164629,#164630,#164631); +#164629 = CARTESIAN_POINT('',(0.635,0.11,3.)); +#164630 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); +#164631 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#164632 = DEFINITIONAL_REPRESENTATION('',(#164633),#164637); +#164633 = LINE('',#164634,#164635); +#164634 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#164635 = VECTOR('',#164636,1.); +#164636 = DIRECTION('',(0.E+000,-1.)); +#164637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164638 = ORIENTED_EDGE('',*,*,#164639,.F.); +#164639 = EDGE_CURVE('',#164505,#164612,#164640,.T.); +#164640 = SURFACE_CURVE('',#164641,(#164645,#164652),.PCURVE_S1.); +#164641 = LINE('',#164642,#164643); +#164642 = CARTESIAN_POINT('',(0.845,0.240958766627,2.602963360557)); +#164643 = VECTOR('',#164644,1.); +#164644 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#164645 = PCURVE('',#164546,#164646); +#164646 = DEFINITIONAL_REPRESENTATION('',(#164647),#164651); +#164647 = LINE('',#164648,#164649); +#164648 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); +#164649 = VECTOR('',#164650,1.); +#164650 = DIRECTION('',(1.,0.E+000)); +#164651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164652 = PCURVE('',#164489,#164653); +#164653 = DEFINITIONAL_REPRESENTATION('',(#164654),#164658); +#164654 = LINE('',#164655,#164656); +#164655 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#164656 = VECTOR('',#164657,1.); +#164657 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#164658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164659 = ADVANCED_FACE('',(#164660),#164627,.T.); +#164660 = FACE_BOUND('',#164661,.T.); +#164661 = EDGE_LOOP('',(#164662,#164692,#164713,#164714)); +#164662 = ORIENTED_EDGE('',*,*,#164663,.F.); +#164663 = EDGE_CURVE('',#164664,#164666,#164668,.T.); +#164664 = VERTEX_POINT('',#164665); +#164665 = CARTESIAN_POINT('',(0.845,1.507511769915E-004,2.994243044813) + ); +#164666 = VERTEX_POINT('',#164667); +#164667 = CARTESIAN_POINT('',(0.425,1.507511769916E-004,2.994243044813) + ); +#164668 = SURFACE_CURVE('',#164669,(#164673,#164680),.PCURVE_S1.); +#164669 = LINE('',#164670,#164671); +#164670 = CARTESIAN_POINT('',(0.635,1.507511769963E-004,2.994243044813) + ); +#164671 = VECTOR('',#164672,1.); +#164672 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164673 = PCURVE('',#164627,#164674); +#164674 = DEFINITIONAL_REPRESENTATION('',(#164675),#164679); +#164675 = LINE('',#164676,#164677); +#164676 = CARTESIAN_POINT('',(0.11,0.E+000)); +#164677 = VECTOR('',#164678,1.); +#164678 = DIRECTION('',(0.E+000,-1.)); +#164679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164680 = PCURVE('',#164681,#164686); +#164681 = PLANE('',#164682); +#164682 = AXIS2_PLACEMENT_3D('',#164683,#164684,#164685); +#164683 = CARTESIAN_POINT('',(0.635,2.126026898096E-002,2.591449450184) + ); +#164684 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); +#164685 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#164686 = DEFINITIONAL_REPRESENTATION('',(#164687),#164691); +#164687 = LINE('',#164688,#164689); +#164688 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#164689 = VECTOR('',#164690,1.); +#164690 = DIRECTION('',(0.E+000,-1.)); +#164691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164692 = ORIENTED_EDGE('',*,*,#164693,.F.); +#164693 = EDGE_CURVE('',#164612,#164664,#164694,.T.); +#164694 = SURFACE_CURVE('',#164695,(#164699,#164706),.PCURVE_S1.); +#164695 = LINE('',#164696,#164697); +#164696 = CARTESIAN_POINT('',(0.845,0.219849248823,3.005756955187)); +#164697 = VECTOR('',#164698,1.); +#164698 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#164699 = PCURVE('',#164627,#164700); +#164700 = DEFINITIONAL_REPRESENTATION('',(#164701),#164705); +#164701 = LINE('',#164702,#164703); +#164702 = CARTESIAN_POINT('',(-0.11,0.21)); +#164703 = VECTOR('',#164704,1.); +#164704 = DIRECTION('',(1.,0.E+000)); +#164705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164706 = PCURVE('',#164489,#164707); +#164707 = DEFINITIONAL_REPRESENTATION('',(#164708),#164712); +#164708 = LINE('',#164709,#164710); +#164709 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#164710 = VECTOR('',#164711,1.); +#164711 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#164712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164713 = ORIENTED_EDGE('',*,*,#164611,.T.); +#164714 = ORIENTED_EDGE('',*,*,#164715,.F.); +#164715 = EDGE_CURVE('',#164666,#164589,#164716,.T.); +#164716 = SURFACE_CURVE('',#164717,(#164721,#164728),.PCURVE_S1.); +#164717 = LINE('',#164718,#164719); +#164718 = CARTESIAN_POINT('',(0.425,1.507511769892E-004,2.994243044813) + ); +#164719 = VECTOR('',#164720,1.); +#164720 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); +#164721 = PCURVE('',#164627,#164722); +#164722 = DEFINITIONAL_REPRESENTATION('',(#164723),#164727); +#164723 = LINE('',#164724,#164725); +#164724 = CARTESIAN_POINT('',(0.11,-0.21)); +#164725 = VECTOR('',#164726,1.); +#164726 = DIRECTION('',(-1.,0.E+000)); +#164727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164728 = PCURVE('',#164436,#164729); +#164729 = DEFINITIONAL_REPRESENTATION('',(#164730),#164734); +#164730 = LINE('',#164731,#164732); +#164731 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#164732 = VECTOR('',#164733,1.); +#164733 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#164734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164735 = ADVANCED_FACE('',(#164736),#164681,.T.); +#164736 = FACE_BOUND('',#164737,.T.); +#164737 = EDGE_LOOP('',(#164738,#164767,#164788,#164789)); +#164738 = ORIENTED_EDGE('',*,*,#164739,.F.); +#164739 = EDGE_CURVE('',#164740,#164742,#164744,.T.); +#164740 = VERTEX_POINT('',#164741); +#164741 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,2.591449450184) + ); +#164742 = VERTEX_POINT('',#164743); +#164743 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,2.591449450184) + ); +#164744 = SURFACE_CURVE('',#164745,(#164749,#164756),.PCURVE_S1.); +#164745 = LINE('',#164746,#164747); +#164746 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,2.591449450184) + ); +#164747 = VECTOR('',#164748,1.); +#164748 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164749 = PCURVE('',#164681,#164750); +#164750 = DEFINITIONAL_REPRESENTATION('',(#164751),#164755); +#164751 = LINE('',#164752,#164753); +#164752 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); +#164753 = VECTOR('',#164754,1.); +#164754 = DIRECTION('',(0.E+000,-1.)); +#164755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164756 = PCURVE('',#164757,#164762); +#164757 = CYLINDRICAL_SURFACE('',#164758,0.32); +#164758 = AXIS2_PLACEMENT_3D('',#164759,#164760,#164761); +#164759 = CARTESIAN_POINT('',(0.635,0.340821720102,2.608196956182)); +#164760 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164761 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164762 = DEFINITIONAL_REPRESENTATION('',(#164763),#164766); +#164763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164764,#164765), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#164764 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164765 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164767 = ORIENTED_EDGE('',*,*,#164768,.F.); +#164768 = EDGE_CURVE('',#164664,#164740,#164769,.T.); +#164769 = SURFACE_CURVE('',#164770,(#164774,#164781),.PCURVE_S1.); +#164770 = LINE('',#164771,#164772); +#164771 = CARTESIAN_POINT('',(0.845,1.507511769892E-004,2.994243044813) + ); +#164772 = VECTOR('',#164773,1.); +#164773 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#164774 = PCURVE('',#164681,#164775); +#164775 = DEFINITIONAL_REPRESENTATION('',(#164776),#164780); +#164776 = LINE('',#164777,#164778); +#164777 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#164778 = VECTOR('',#164779,1.); +#164779 = DIRECTION('',(1.,0.E+000)); +#164780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164781 = PCURVE('',#164489,#164782); +#164782 = DEFINITIONAL_REPRESENTATION('',(#164783),#164787); +#164783 = LINE('',#164784,#164785); +#164784 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#164785 = VECTOR('',#164786,1.); +#164786 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#164787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164788 = ORIENTED_EDGE('',*,*,#164663,.T.); +#164789 = ORIENTED_EDGE('',*,*,#164790,.F.); +#164790 = EDGE_CURVE('',#164742,#164666,#164791,.T.); +#164791 = SURFACE_CURVE('',#164792,(#164796,#164803),.PCURVE_S1.); +#164792 = LINE('',#164793,#164794); +#164793 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,2.591449450184) + ); +#164794 = VECTOR('',#164795,1.); +#164795 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#164796 = PCURVE('',#164681,#164797); +#164797 = DEFINITIONAL_REPRESENTATION('',(#164798),#164802); +#164798 = LINE('',#164799,#164800); +#164799 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); +#164800 = VECTOR('',#164801,1.); +#164801 = DIRECTION('',(-1.,0.E+000)); +#164802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164803 = PCURVE('',#164436,#164804); +#164804 = DEFINITIONAL_REPRESENTATION('',(#164805),#164809); +#164805 = LINE('',#164806,#164807); +#164806 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#164807 = VECTOR('',#164808,1.); +#164808 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#164809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162211 = PCURVE('',#162044,#162212); -#162212 = DEFINITIONAL_REPRESENTATION('',(#162213),#162217); -#162213 = LINE('',#162214,#162215); -#162214 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#162215 = VECTOR('',#162216,1.); -#162216 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#162217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162218 = ORIENTED_EDGE('',*,*,#162219,.F.); -#162219 = EDGE_CURVE('',#162220,#162197,#162222,.T.); -#162220 = VERTEX_POINT('',#162221); -#162221 = CARTESIAN_POINT('',(0.845,0.219849248823,3.005756955187)); -#162222 = SURFACE_CURVE('',#162223,(#162227,#162234),.PCURVE_S1.); -#162223 = LINE('',#162224,#162225); -#162224 = CARTESIAN_POINT('',(0.635,0.219849248823,3.005756955187)); -#162225 = VECTOR('',#162226,1.); -#162226 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162227 = PCURVE('',#162154,#162228); -#162228 = DEFINITIONAL_REPRESENTATION('',(#162229),#162233); -#162229 = LINE('',#162230,#162231); -#162230 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#162231 = VECTOR('',#162232,1.); -#162232 = DIRECTION('',(0.E+000,-1.)); -#162233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162234 = PCURVE('',#162235,#162240); -#162235 = PLANE('',#162236); -#162236 = AXIS2_PLACEMENT_3D('',#162237,#162238,#162239); -#162237 = CARTESIAN_POINT('',(0.635,0.11,3.)); -#162238 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); -#162239 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#162240 = DEFINITIONAL_REPRESENTATION('',(#162241),#162245); -#162241 = LINE('',#162242,#162243); -#162242 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#162243 = VECTOR('',#162244,1.); -#162244 = DIRECTION('',(0.E+000,-1.)); -#162245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162246 = ORIENTED_EDGE('',*,*,#162247,.F.); -#162247 = EDGE_CURVE('',#162113,#162220,#162248,.T.); -#162248 = SURFACE_CURVE('',#162249,(#162253,#162260),.PCURVE_S1.); -#162249 = LINE('',#162250,#162251); -#162250 = CARTESIAN_POINT('',(0.845,0.240958766627,2.602963360557)); -#162251 = VECTOR('',#162252,1.); -#162252 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#162253 = PCURVE('',#162154,#162254); -#162254 = DEFINITIONAL_REPRESENTATION('',(#162255),#162259); -#162255 = LINE('',#162256,#162257); -#162256 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); -#162257 = VECTOR('',#162258,1.); -#162258 = DIRECTION('',(1.,0.E+000)); -#162259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162260 = PCURVE('',#162097,#162261); -#162261 = DEFINITIONAL_REPRESENTATION('',(#162262),#162266); -#162262 = LINE('',#162263,#162264); -#162263 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#162264 = VECTOR('',#162265,1.); -#162265 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#162266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162267 = ADVANCED_FACE('',(#162268),#162235,.T.); -#162268 = FACE_BOUND('',#162269,.T.); -#162269 = EDGE_LOOP('',(#162270,#162300,#162321,#162322)); -#162270 = ORIENTED_EDGE('',*,*,#162271,.F.); -#162271 = EDGE_CURVE('',#162272,#162274,#162276,.T.); -#162272 = VERTEX_POINT('',#162273); -#162273 = CARTESIAN_POINT('',(0.845,1.507511769915E-004,2.994243044813) - ); -#162274 = VERTEX_POINT('',#162275); -#162275 = CARTESIAN_POINT('',(0.425,1.507511769916E-004,2.994243044813) - ); -#162276 = SURFACE_CURVE('',#162277,(#162281,#162288),.PCURVE_S1.); -#162277 = LINE('',#162278,#162279); -#162278 = CARTESIAN_POINT('',(0.635,1.507511769963E-004,2.994243044813) - ); -#162279 = VECTOR('',#162280,1.); -#162280 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162281 = PCURVE('',#162235,#162282); -#162282 = DEFINITIONAL_REPRESENTATION('',(#162283),#162287); -#162283 = LINE('',#162284,#162285); -#162284 = CARTESIAN_POINT('',(0.11,0.E+000)); -#162285 = VECTOR('',#162286,1.); -#162286 = DIRECTION('',(0.E+000,-1.)); -#162287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162288 = PCURVE('',#162289,#162294); -#162289 = PLANE('',#162290); -#162290 = AXIS2_PLACEMENT_3D('',#162291,#162292,#162293); -#162291 = CARTESIAN_POINT('',(0.635,2.126026898096E-002,2.591449450184) - ); -#162292 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); -#162293 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#162294 = DEFINITIONAL_REPRESENTATION('',(#162295),#162299); -#162295 = LINE('',#162296,#162297); -#162296 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#162297 = VECTOR('',#162298,1.); -#162298 = DIRECTION('',(0.E+000,-1.)); -#162299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162300 = ORIENTED_EDGE('',*,*,#162301,.F.); -#162301 = EDGE_CURVE('',#162220,#162272,#162302,.T.); -#162302 = SURFACE_CURVE('',#162303,(#162307,#162314),.PCURVE_S1.); -#162303 = LINE('',#162304,#162305); -#162304 = CARTESIAN_POINT('',(0.845,0.219849248823,3.005756955187)); -#162305 = VECTOR('',#162306,1.); -#162306 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#162307 = PCURVE('',#162235,#162308); -#162308 = DEFINITIONAL_REPRESENTATION('',(#162309),#162313); -#162309 = LINE('',#162310,#162311); -#162310 = CARTESIAN_POINT('',(-0.11,0.21)); -#162311 = VECTOR('',#162312,1.); -#162312 = DIRECTION('',(1.,0.E+000)); -#162313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162314 = PCURVE('',#162097,#162315); -#162315 = DEFINITIONAL_REPRESENTATION('',(#162316),#162320); -#162316 = LINE('',#162317,#162318); -#162317 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#162318 = VECTOR('',#162319,1.); -#162319 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#162320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162321 = ORIENTED_EDGE('',*,*,#162219,.T.); -#162322 = ORIENTED_EDGE('',*,*,#162323,.F.); -#162323 = EDGE_CURVE('',#162274,#162197,#162324,.T.); -#162324 = SURFACE_CURVE('',#162325,(#162329,#162336),.PCURVE_S1.); -#162325 = LINE('',#162326,#162327); -#162326 = CARTESIAN_POINT('',(0.425,1.507511769892E-004,2.994243044813) - ); -#162327 = VECTOR('',#162328,1.); -#162328 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); -#162329 = PCURVE('',#162235,#162330); -#162330 = DEFINITIONAL_REPRESENTATION('',(#162331),#162335); -#162331 = LINE('',#162332,#162333); -#162332 = CARTESIAN_POINT('',(0.11,-0.21)); -#162333 = VECTOR('',#162334,1.); -#162334 = DIRECTION('',(-1.,0.E+000)); -#162335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162336 = PCURVE('',#162044,#162337); -#162337 = DEFINITIONAL_REPRESENTATION('',(#162338),#162342); -#162338 = LINE('',#162339,#162340); -#162339 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#162340 = VECTOR('',#162341,1.); -#162341 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#162342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162343 = ADVANCED_FACE('',(#162344),#162289,.T.); -#162344 = FACE_BOUND('',#162345,.T.); -#162345 = EDGE_LOOP('',(#162346,#162375,#162396,#162397)); -#162346 = ORIENTED_EDGE('',*,*,#162347,.F.); -#162347 = EDGE_CURVE('',#162348,#162350,#162352,.T.); -#162348 = VERTEX_POINT('',#162349); -#162349 = CARTESIAN_POINT('',(0.845,2.126026898096E-002,2.591449450184) - ); -#162350 = VERTEX_POINT('',#162351); -#162351 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,2.591449450184) - ); -#162352 = SURFACE_CURVE('',#162353,(#162357,#162364),.PCURVE_S1.); -#162353 = LINE('',#162354,#162355); -#162354 = CARTESIAN_POINT('',(0.635,2.126026898095E-002,2.591449450184) - ); -#162355 = VECTOR('',#162356,1.); -#162356 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162357 = PCURVE('',#162289,#162358); -#162358 = DEFINITIONAL_REPRESENTATION('',(#162359),#162363); -#162359 = LINE('',#162360,#162361); -#162360 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); -#162361 = VECTOR('',#162362,1.); -#162362 = DIRECTION('',(0.E+000,-1.)); -#162363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162364 = PCURVE('',#162365,#162370); -#162365 = CYLINDRICAL_SURFACE('',#162366,0.32); -#162366 = AXIS2_PLACEMENT_3D('',#162367,#162368,#162369); -#162367 = CARTESIAN_POINT('',(0.635,0.340821720102,2.608196956182)); -#162368 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162369 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162370 = DEFINITIONAL_REPRESENTATION('',(#162371),#162374); -#162371 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162372,#162373), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162372 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162373 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162375 = ORIENTED_EDGE('',*,*,#162376,.F.); -#162376 = EDGE_CURVE('',#162272,#162348,#162377,.T.); -#162377 = SURFACE_CURVE('',#162378,(#162382,#162389),.PCURVE_S1.); -#162378 = LINE('',#162379,#162380); -#162379 = CARTESIAN_POINT('',(0.845,1.507511769892E-004,2.994243044813) - ); -#162380 = VECTOR('',#162381,1.); -#162381 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#162382 = PCURVE('',#162289,#162383); -#162383 = DEFINITIONAL_REPRESENTATION('',(#162384),#162388); -#162384 = LINE('',#162385,#162386); -#162385 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#162386 = VECTOR('',#162387,1.); -#162387 = DIRECTION('',(1.,0.E+000)); -#162388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162389 = PCURVE('',#162097,#162390); -#162390 = DEFINITIONAL_REPRESENTATION('',(#162391),#162395); -#162391 = LINE('',#162392,#162393); -#162392 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#162393 = VECTOR('',#162394,1.); -#162394 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#162395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162396 = ORIENTED_EDGE('',*,*,#162271,.T.); -#162397 = ORIENTED_EDGE('',*,*,#162398,.F.); -#162398 = EDGE_CURVE('',#162350,#162274,#162399,.T.); -#162399 = SURFACE_CURVE('',#162400,(#162404,#162411),.PCURVE_S1.); -#162400 = LINE('',#162401,#162402); -#162401 = CARTESIAN_POINT('',(0.425,2.126026898096E-002,2.591449450184) - ); -#162402 = VECTOR('',#162403,1.); -#162403 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#162404 = PCURVE('',#162289,#162405); -#162405 = DEFINITIONAL_REPRESENTATION('',(#162406),#162410); -#162406 = LINE('',#162407,#162408); -#162407 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); -#162408 = VECTOR('',#162409,1.); -#162409 = DIRECTION('',(-1.,0.E+000)); -#162410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162411 = PCURVE('',#162044,#162412); -#162412 = DEFINITIONAL_REPRESENTATION('',(#162413),#162417); -#162413 = LINE('',#162414,#162415); -#162414 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#162415 = VECTOR('',#162416,1.); -#162416 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#162417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162418 = ADVANCED_FACE('',(#162419),#162365,.T.); -#162419 = FACE_BOUND('',#162420,.T.); -#162420 = EDGE_LOOP('',(#162421,#162450,#162471,#162472)); -#162421 = ORIENTED_EDGE('',*,*,#162422,.F.); -#162422 = EDGE_CURVE('',#162423,#162425,#162427,.T.); -#162423 = VERTEX_POINT('',#162424); -#162424 = CARTESIAN_POINT('',(0.845,0.298978581017,2.290944451524)); -#162425 = VERTEX_POINT('',#162426); -#162426 = CARTESIAN_POINT('',(0.425,0.298978581017,2.290944451524)); -#162427 = SURFACE_CURVE('',#162428,(#162432,#162438),.PCURVE_S1.); -#162428 = LINE('',#162429,#162430); -#162429 = CARTESIAN_POINT('',(0.635,0.298978581017,2.290944451524)); -#162430 = VECTOR('',#162431,1.); -#162431 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162432 = PCURVE('',#162365,#162433); -#162433 = DEFINITIONAL_REPRESENTATION('',(#162434),#162437); -#162434 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162435,#162436), +#164810 = ADVANCED_FACE('',(#164811),#164757,.T.); +#164811 = FACE_BOUND('',#164812,.T.); +#164812 = EDGE_LOOP('',(#164813,#164842,#164863,#164864)); +#164813 = ORIENTED_EDGE('',*,*,#164814,.F.); +#164814 = EDGE_CURVE('',#164815,#164817,#164819,.T.); +#164815 = VERTEX_POINT('',#164816); +#164816 = CARTESIAN_POINT('',(0.845,0.298978581017,2.290944451524)); +#164817 = VERTEX_POINT('',#164818); +#164818 = CARTESIAN_POINT('',(0.425,0.298978581017,2.290944451524)); +#164819 = SURFACE_CURVE('',#164820,(#164824,#164830),.PCURVE_S1.); +#164820 = LINE('',#164821,#164822); +#164821 = CARTESIAN_POINT('',(0.635,0.298978581017,2.290944451524)); +#164822 = VECTOR('',#164823,1.); +#164823 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164824 = PCURVE('',#164757,#164825); +#164825 = DEFINITIONAL_REPRESENTATION('',(#164826),#164829); +#164826 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164827,#164828), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162435 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162436 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162438 = PCURVE('',#162439,#162444); -#162439 = PLANE('',#162440); -#162440 = AXIS2_PLACEMENT_3D('',#162441,#162442,#162443); -#162441 = CARTESIAN_POINT('',(0.635,0.678075980964,2.240944451524)); -#162442 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); -#162443 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#162444 = DEFINITIONAL_REPRESENTATION('',(#162445),#162449); -#162445 = LINE('',#162446,#162447); -#162446 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#162447 = VECTOR('',#162448,1.); -#162448 = DIRECTION('',(0.E+000,-1.)); -#162449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162450 = ORIENTED_EDGE('',*,*,#162451,.F.); -#162451 = EDGE_CURVE('',#162348,#162423,#162452,.T.); -#162452 = SURFACE_CURVE('',#162453,(#162458,#162464),.PCURVE_S1.); -#162453 = CIRCLE('',#162454,0.32); -#162454 = AXIS2_PLACEMENT_3D('',#162455,#162456,#162457); -#162455 = CARTESIAN_POINT('',(0.845,0.340821720102,2.608196956182)); -#162456 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162457 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); -#162458 = PCURVE('',#162365,#162459); -#162459 = DEFINITIONAL_REPRESENTATION('',(#162460),#162463); -#162460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162461,#162462), +#164827 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164828 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164830 = PCURVE('',#164831,#164836); +#164831 = PLANE('',#164832); +#164832 = AXIS2_PLACEMENT_3D('',#164833,#164834,#164835); +#164833 = CARTESIAN_POINT('',(0.635,0.678075980964,2.240944451524)); +#164834 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); +#164835 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#164836 = DEFINITIONAL_REPRESENTATION('',(#164837),#164841); +#164837 = LINE('',#164838,#164839); +#164838 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#164839 = VECTOR('',#164840,1.); +#164840 = DIRECTION('',(0.E+000,-1.)); +#164841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164842 = ORIENTED_EDGE('',*,*,#164843,.F.); +#164843 = EDGE_CURVE('',#164740,#164815,#164844,.T.); +#164844 = SURFACE_CURVE('',#164845,(#164850,#164856),.PCURVE_S1.); +#164845 = CIRCLE('',#164846,0.32); +#164846 = AXIS2_PLACEMENT_3D('',#164847,#164848,#164849); +#164847 = CARTESIAN_POINT('',(0.845,0.340821720102,2.608196956182)); +#164848 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164849 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); +#164850 = PCURVE('',#164757,#164851); +#164851 = DEFINITIONAL_REPRESENTATION('',(#164852),#164855); +#164852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164853,#164854), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#162461 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162462 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162464 = PCURVE('',#162097,#162465); -#162465 = DEFINITIONAL_REPRESENTATION('',(#162466),#162470); -#162466 = CIRCLE('',#162467,0.32); -#162467 = AXIS2_PLACEMENT_2D('',#162468,#162469); -#162468 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#162469 = DIRECTION('',(-1.,1.694065894509E-015)); -#162470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162471 = ORIENTED_EDGE('',*,*,#162347,.T.); -#162472 = ORIENTED_EDGE('',*,*,#162473,.F.); -#162473 = EDGE_CURVE('',#162425,#162350,#162474,.T.); -#162474 = SURFACE_CURVE('',#162475,(#162480,#162486),.PCURVE_S1.); -#162475 = CIRCLE('',#162476,0.32); -#162476 = AXIS2_PLACEMENT_3D('',#162477,#162478,#162479); -#162477 = CARTESIAN_POINT('',(0.425,0.340821720102,2.608196956182)); -#162478 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162479 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162480 = PCURVE('',#162365,#162481); -#162481 = DEFINITIONAL_REPRESENTATION('',(#162482),#162485); -#162482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162483,#162484), +#164853 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#164854 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#164855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164856 = PCURVE('',#164489,#164857); +#164857 = DEFINITIONAL_REPRESENTATION('',(#164858),#164862); +#164858 = CIRCLE('',#164859,0.32); +#164859 = AXIS2_PLACEMENT_2D('',#164860,#164861); +#164860 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#164861 = DIRECTION('',(-1.,1.694065894509E-015)); +#164862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164863 = ORIENTED_EDGE('',*,*,#164739,.T.); +#164864 = ORIENTED_EDGE('',*,*,#164865,.F.); +#164865 = EDGE_CURVE('',#164817,#164742,#164866,.T.); +#164866 = SURFACE_CURVE('',#164867,(#164872,#164878),.PCURVE_S1.); +#164867 = CIRCLE('',#164868,0.32); +#164868 = AXIS2_PLACEMENT_3D('',#164869,#164870,#164871); +#164869 = CARTESIAN_POINT('',(0.425,0.340821720102,2.608196956182)); +#164870 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#164871 = DIRECTION('',(0.E+000,0.E+000,1.)); +#164872 = PCURVE('',#164757,#164873); +#164873 = DEFINITIONAL_REPRESENTATION('',(#164874),#164877); +#164874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164875,#164876), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#162483 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162484 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162486 = PCURVE('',#162044,#162487); -#162487 = DEFINITIONAL_REPRESENTATION('',(#162488),#162492); -#162488 = CIRCLE('',#162489,0.32); -#162489 = AXIS2_PLACEMENT_2D('',#162490,#162491); -#162490 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#162491 = DIRECTION('',(1.,0.E+000)); -#162492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162493 = ADVANCED_FACE('',(#162494),#162439,.T.); -#162494 = FACE_BOUND('',#162495,.T.); -#162495 = EDGE_LOOP('',(#162496,#162525,#162546,#162547)); -#162496 = ORIENTED_EDGE('',*,*,#162497,.T.); -#162497 = EDGE_CURVE('',#162498,#162500,#162502,.T.); -#162498 = VERTEX_POINT('',#162499); -#162499 = CARTESIAN_POINT('',(0.425,0.678075980964,2.240944451524)); -#162500 = VERTEX_POINT('',#162501); -#162501 = CARTESIAN_POINT('',(0.845,0.678075980964,2.240944451524)); -#162502 = SURFACE_CURVE('',#162503,(#162507,#162514),.PCURVE_S1.); -#162503 = LINE('',#162504,#162505); -#162504 = CARTESIAN_POINT('',(0.635,0.678075980964,2.240944451524)); -#162505 = VECTOR('',#162506,1.); -#162506 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162507 = PCURVE('',#162439,#162508); -#162508 = DEFINITIONAL_REPRESENTATION('',(#162509),#162513); -#162509 = LINE('',#162510,#162511); -#162510 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#162511 = VECTOR('',#162512,1.); -#162512 = DIRECTION('',(0.E+000,1.)); -#162513 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162514 = PCURVE('',#162515,#162520); -#162515 = CYLINDRICAL_SURFACE('',#162516,1.E-001); -#162516 = AXIS2_PLACEMENT_3D('',#162517,#162518,#162519); -#162517 = CARTESIAN_POINT('',(0.635,0.665,2.141803043818)); -#162518 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162519 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162520 = DEFINITIONAL_REPRESENTATION('',(#162521),#162524); -#162521 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162522,#162523), +#164875 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#164876 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#164877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164878 = PCURVE('',#164436,#164879); +#164879 = DEFINITIONAL_REPRESENTATION('',(#164880),#164884); +#164880 = CIRCLE('',#164881,0.32); +#164881 = AXIS2_PLACEMENT_2D('',#164882,#164883); +#164882 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#164883 = DIRECTION('',(1.,0.E+000)); +#164884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164885 = ADVANCED_FACE('',(#164886),#164831,.T.); +#164886 = FACE_BOUND('',#164887,.T.); +#164887 = EDGE_LOOP('',(#164888,#164917,#164938,#164939)); +#164888 = ORIENTED_EDGE('',*,*,#164889,.T.); +#164889 = EDGE_CURVE('',#164890,#164892,#164894,.T.); +#164890 = VERTEX_POINT('',#164891); +#164891 = CARTESIAN_POINT('',(0.425,0.678075980964,2.240944451524)); +#164892 = VERTEX_POINT('',#164893); +#164893 = CARTESIAN_POINT('',(0.845,0.678075980964,2.240944451524)); +#164894 = SURFACE_CURVE('',#164895,(#164899,#164906),.PCURVE_S1.); +#164895 = LINE('',#164896,#164897); +#164896 = CARTESIAN_POINT('',(0.635,0.678075980964,2.240944451524)); +#164897 = VECTOR('',#164898,1.); +#164898 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164899 = PCURVE('',#164831,#164900); +#164900 = DEFINITIONAL_REPRESENTATION('',(#164901),#164905); +#164901 = LINE('',#164902,#164903); +#164902 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#164903 = VECTOR('',#164904,1.); +#164904 = DIRECTION('',(0.E+000,1.)); +#164905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164906 = PCURVE('',#164907,#164912); +#164907 = CYLINDRICAL_SURFACE('',#164908,1.E-001); +#164908 = AXIS2_PLACEMENT_3D('',#164909,#164910,#164911); +#164909 = CARTESIAN_POINT('',(0.635,0.665,2.141803043818)); +#164910 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164911 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164912 = DEFINITIONAL_REPRESENTATION('',(#164913),#164916); +#164913 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164914,#164915), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162522 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#162523 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#162524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162525 = ORIENTED_EDGE('',*,*,#162526,.F.); -#162526 = EDGE_CURVE('',#162423,#162500,#162527,.T.); -#162527 = SURFACE_CURVE('',#162528,(#162532,#162539),.PCURVE_S1.); -#162528 = LINE('',#162529,#162530); -#162529 = CARTESIAN_POINT('',(0.845,0.298978581017,2.290944451524)); -#162530 = VECTOR('',#162531,1.); -#162531 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#162532 = PCURVE('',#162439,#162533); -#162533 = DEFINITIONAL_REPRESENTATION('',(#162534),#162538); -#162534 = LINE('',#162535,#162536); -#162535 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#162536 = VECTOR('',#162537,1.); -#162537 = DIRECTION('',(1.,0.E+000)); -#162538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162539 = PCURVE('',#162097,#162540); -#162540 = DEFINITIONAL_REPRESENTATION('',(#162541),#162545); -#162541 = LINE('',#162542,#162543); -#162542 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#162543 = VECTOR('',#162544,1.); -#162544 = DIRECTION('',(0.130759809642,0.991414077055)); -#162545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162546 = ORIENTED_EDGE('',*,*,#162422,.T.); -#162547 = ORIENTED_EDGE('',*,*,#162548,.F.); -#162548 = EDGE_CURVE('',#162498,#162425,#162549,.T.); -#162549 = SURFACE_CURVE('',#162550,(#162554,#162561),.PCURVE_S1.); -#162550 = LINE('',#162551,#162552); -#162551 = CARTESIAN_POINT('',(0.425,0.678075980964,2.240944451524)); -#162552 = VECTOR('',#162553,1.); -#162553 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#162554 = PCURVE('',#162439,#162555); -#162555 = DEFINITIONAL_REPRESENTATION('',(#162556),#162560); -#162556 = LINE('',#162557,#162558); -#162557 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#162558 = VECTOR('',#162559,1.); -#162559 = DIRECTION('',(-1.,0.E+000)); -#162560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162561 = PCURVE('',#162044,#162562); -#162562 = DEFINITIONAL_REPRESENTATION('',(#162563),#162567); -#162563 = LINE('',#162564,#162565); -#162564 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#162565 = VECTOR('',#162566,1.); -#162566 = DIRECTION('',(0.130759809642,-0.991414077055)); -#162567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162568 = ADVANCED_FACE('',(#162569),#162515,.F.); -#162569 = FACE_BOUND('',#162570,.F.); -#162570 = EDGE_LOOP('',(#162571,#162598,#162599,#162626)); -#162571 = ORIENTED_EDGE('',*,*,#162572,.T.); -#162572 = EDGE_CURVE('',#162573,#162498,#162575,.T.); -#162573 = VERTEX_POINT('',#162574); -#162574 = CARTESIAN_POINT('',(0.425,0.765,2.141803043818)); -#162575 = SURFACE_CURVE('',#162576,(#162581,#162587),.PCURVE_S1.); -#162576 = CIRCLE('',#162577,1.E-001); -#162577 = AXIS2_PLACEMENT_3D('',#162578,#162579,#162580); -#162578 = CARTESIAN_POINT('',(0.425,0.665,2.141803043818)); -#162579 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162580 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162581 = PCURVE('',#162515,#162582); -#162582 = DEFINITIONAL_REPRESENTATION('',(#162583),#162586); -#162583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162584,#162585), +#164914 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#164915 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#164916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164917 = ORIENTED_EDGE('',*,*,#164918,.F.); +#164918 = EDGE_CURVE('',#164815,#164892,#164919,.T.); +#164919 = SURFACE_CURVE('',#164920,(#164924,#164931),.PCURVE_S1.); +#164920 = LINE('',#164921,#164922); +#164921 = CARTESIAN_POINT('',(0.845,0.298978581017,2.290944451524)); +#164922 = VECTOR('',#164923,1.); +#164923 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#164924 = PCURVE('',#164831,#164925); +#164925 = DEFINITIONAL_REPRESENTATION('',(#164926),#164930); +#164926 = LINE('',#164927,#164928); +#164927 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#164928 = VECTOR('',#164929,1.); +#164929 = DIRECTION('',(1.,0.E+000)); +#164930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164931 = PCURVE('',#164489,#164932); +#164932 = DEFINITIONAL_REPRESENTATION('',(#164933),#164937); +#164933 = LINE('',#164934,#164935); +#164934 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#164935 = VECTOR('',#164936,1.); +#164936 = DIRECTION('',(0.130759809642,0.991414077055)); +#164937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164938 = ORIENTED_EDGE('',*,*,#164814,.T.); +#164939 = ORIENTED_EDGE('',*,*,#164940,.F.); +#164940 = EDGE_CURVE('',#164890,#164817,#164941,.T.); +#164941 = SURFACE_CURVE('',#164942,(#164946,#164953),.PCURVE_S1.); +#164942 = LINE('',#164943,#164944); +#164943 = CARTESIAN_POINT('',(0.425,0.678075980964,2.240944451524)); +#164944 = VECTOR('',#164945,1.); +#164945 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#164946 = PCURVE('',#164831,#164947); +#164947 = DEFINITIONAL_REPRESENTATION('',(#164948),#164952); +#164948 = LINE('',#164949,#164950); +#164949 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#164950 = VECTOR('',#164951,1.); +#164951 = DIRECTION('',(-1.,0.E+000)); +#164952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164953 = PCURVE('',#164436,#164954); +#164954 = DEFINITIONAL_REPRESENTATION('',(#164955),#164959); +#164955 = LINE('',#164956,#164957); +#164956 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#164957 = VECTOR('',#164958,1.); +#164958 = DIRECTION('',(0.130759809642,-0.991414077055)); +#164959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164960 = ADVANCED_FACE('',(#164961),#164907,.F.); +#164961 = FACE_BOUND('',#164962,.F.); +#164962 = EDGE_LOOP('',(#164963,#164990,#164991,#165018)); +#164963 = ORIENTED_EDGE('',*,*,#164964,.T.); +#164964 = EDGE_CURVE('',#164965,#164890,#164967,.T.); +#164965 = VERTEX_POINT('',#164966); +#164966 = CARTESIAN_POINT('',(0.425,0.765,2.141803043818)); +#164967 = SURFACE_CURVE('',#164968,(#164973,#164979),.PCURVE_S1.); +#164968 = CIRCLE('',#164969,1.E-001); +#164969 = AXIS2_PLACEMENT_3D('',#164970,#164971,#164972); +#164970 = CARTESIAN_POINT('',(0.425,0.665,2.141803043818)); +#164971 = DIRECTION('',(1.,0.E+000,0.E+000)); +#164972 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#164973 = PCURVE('',#164907,#164974); +#164974 = DEFINITIONAL_REPRESENTATION('',(#164975),#164978); +#164975 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164976,#164977), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#162584 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#162585 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#162586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#164976 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#164977 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#164978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162587 = PCURVE('',#162044,#162588); -#162588 = DEFINITIONAL_REPRESENTATION('',(#162589),#162597); -#162589 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162590,#162591,#162592, - #162593,#162594,#162595,#162596),.UNSPECIFIED.,.T.,.F.) +#164979 = PCURVE('',#164436,#164980); +#164980 = DEFINITIONAL_REPRESENTATION('',(#164981),#164989); +#164981 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164982,#164983,#164984, + #164985,#164986,#164987,#164988),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162590 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#162591 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#162592 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#162593 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#162594 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#162595 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#162596 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#162597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162598 = ORIENTED_EDGE('',*,*,#162497,.T.); -#162599 = ORIENTED_EDGE('',*,*,#162600,.T.); -#162600 = EDGE_CURVE('',#162500,#162601,#162603,.T.); -#162601 = VERTEX_POINT('',#162602); -#162602 = CARTESIAN_POINT('',(0.845,0.765,2.141803043818)); -#162603 = SURFACE_CURVE('',#162604,(#162609,#162615),.PCURVE_S1.); -#162604 = CIRCLE('',#162605,1.E-001); -#162605 = AXIS2_PLACEMENT_3D('',#162606,#162607,#162608); -#162606 = CARTESIAN_POINT('',(0.845,0.665,2.141803043818)); -#162607 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162608 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); -#162609 = PCURVE('',#162515,#162610); -#162610 = DEFINITIONAL_REPRESENTATION('',(#162611),#162614); -#162611 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162612,#162613), +#164982 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#164983 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#164984 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#164985 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#164986 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#164987 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#164988 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#164989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#164990 = ORIENTED_EDGE('',*,*,#164889,.T.); +#164991 = ORIENTED_EDGE('',*,*,#164992,.T.); +#164992 = EDGE_CURVE('',#164892,#164993,#164995,.T.); +#164993 = VERTEX_POINT('',#164994); +#164994 = CARTESIAN_POINT('',(0.845,0.765,2.141803043818)); +#164995 = SURFACE_CURVE('',#164996,(#165001,#165007),.PCURVE_S1.); +#164996 = CIRCLE('',#164997,1.E-001); +#164997 = AXIS2_PLACEMENT_3D('',#164998,#164999,#165000); +#164998 = CARTESIAN_POINT('',(0.845,0.665,2.141803043818)); +#164999 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165000 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); +#165001 = PCURVE('',#164907,#165002); +#165002 = DEFINITIONAL_REPRESENTATION('',(#165003),#165006); +#165003 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165004,#165005), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#162612 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#162613 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#162614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165004 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#165005 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#165006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162615 = PCURVE('',#162097,#162616); -#162616 = DEFINITIONAL_REPRESENTATION('',(#162617),#162625); -#162617 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162618,#162619,#162620, - #162621,#162622,#162623,#162624),.UNSPECIFIED.,.T.,.F.) +#165007 = PCURVE('',#164489,#165008); +#165008 = DEFINITIONAL_REPRESENTATION('',(#165009),#165017); +#165009 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165010,#165011,#165012, + #165013,#165014,#165015,#165016),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162618 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#162619 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#162620 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#162621 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#162622 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#162623 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#162624 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#162625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162626 = ORIENTED_EDGE('',*,*,#162627,.T.); -#162627 = EDGE_CURVE('',#162601,#162573,#162628,.T.); -#162628 = SURFACE_CURVE('',#162629,(#162633,#162639),.PCURVE_S1.); -#162629 = LINE('',#162630,#162631); -#162630 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); -#162631 = VECTOR('',#162632,1.); -#162632 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162633 = PCURVE('',#162515,#162634); -#162634 = DEFINITIONAL_REPRESENTATION('',(#162635),#162638); -#162635 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162636,#162637), +#165010 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#165011 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#165012 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#165013 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#165014 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#165015 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#165016 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#165017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165018 = ORIENTED_EDGE('',*,*,#165019,.T.); +#165019 = EDGE_CURVE('',#164993,#164965,#165020,.T.); +#165020 = SURFACE_CURVE('',#165021,(#165025,#165031),.PCURVE_S1.); +#165021 = LINE('',#165022,#165023); +#165022 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); +#165023 = VECTOR('',#165024,1.); +#165024 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165025 = PCURVE('',#164907,#165026); +#165026 = DEFINITIONAL_REPRESENTATION('',(#165027),#165030); +#165027 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165028,#165029), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162636 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#162637 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#162638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162639 = PCURVE('',#159360,#162640); -#162640 = DEFINITIONAL_REPRESENTATION('',(#162641),#162645); -#162641 = LINE('',#162642,#162643); -#162642 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#162643 = VECTOR('',#162644,1.); -#162644 = DIRECTION('',(0.E+000,-1.)); -#162645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162646 = ADVANCED_FACE('',(#162647),#162661,.T.); -#162647 = FACE_BOUND('',#162648,.T.); -#162648 = EDGE_LOOP('',(#162649,#162683,#162711,#162738)); -#162649 = ORIENTED_EDGE('',*,*,#162650,.F.); -#162650 = EDGE_CURVE('',#162651,#162653,#162655,.T.); -#162651 = VERTEX_POINT('',#162652); -#162652 = CARTESIAN_POINT('',(1.695,0.706843139085,2.459055548476)); -#162653 = VERTEX_POINT('',#162654); -#162654 = CARTESIAN_POINT('',(2.115,0.706843139085,2.459055548476)); -#162655 = SURFACE_CURVE('',#162656,(#162660,#162672),.PCURVE_S1.); -#162656 = LINE('',#162657,#162658); -#162657 = CARTESIAN_POINT('',(1.905,0.706843139085,2.459055548476)); -#162658 = VECTOR('',#162659,1.); -#162659 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162660 = PCURVE('',#162661,#162666); -#162661 = PLANE('',#162662); -#162662 = AXIS2_PLACEMENT_3D('',#162663,#162664,#162665); -#162663 = CARTESIAN_POINT('',(1.905,0.706843139085,2.459055548476)); -#162664 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); -#162665 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#162666 = DEFINITIONAL_REPRESENTATION('',(#162667),#162671); -#162667 = LINE('',#162668,#162669); -#162668 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#162669 = VECTOR('',#162670,1.); -#162670 = DIRECTION('',(0.E+000,1.)); -#162671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162672 = PCURVE('',#162673,#162678); -#162673 = CYLINDRICAL_SURFACE('',#162674,0.32); -#162674 = AXIS2_PLACEMENT_3D('',#162675,#162676,#162677); -#162675 = CARTESIAN_POINT('',(1.905,0.665,2.141803043818)); -#162676 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162677 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162678 = DEFINITIONAL_REPRESENTATION('',(#162679),#162682); -#162679 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162680,#162681), +#165028 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#165029 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#165030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165031 = PCURVE('',#161752,#165032); +#165032 = DEFINITIONAL_REPRESENTATION('',(#165033),#165037); +#165033 = LINE('',#165034,#165035); +#165034 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#165035 = VECTOR('',#165036,1.); +#165036 = DIRECTION('',(0.E+000,-1.)); +#165037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165038 = ADVANCED_FACE('',(#165039),#165053,.T.); +#165039 = FACE_BOUND('',#165040,.T.); +#165040 = EDGE_LOOP('',(#165041,#165075,#165103,#165130)); +#165041 = ORIENTED_EDGE('',*,*,#165042,.F.); +#165042 = EDGE_CURVE('',#165043,#165045,#165047,.T.); +#165043 = VERTEX_POINT('',#165044); +#165044 = CARTESIAN_POINT('',(1.695,0.706843139085,2.459055548476)); +#165045 = VERTEX_POINT('',#165046); +#165046 = CARTESIAN_POINT('',(2.115,0.706843139085,2.459055548476)); +#165047 = SURFACE_CURVE('',#165048,(#165052,#165064),.PCURVE_S1.); +#165048 = LINE('',#165049,#165050); +#165049 = CARTESIAN_POINT('',(1.905,0.706843139085,2.459055548476)); +#165050 = VECTOR('',#165051,1.); +#165051 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165052 = PCURVE('',#165053,#165058); +#165053 = PLANE('',#165054); +#165054 = AXIS2_PLACEMENT_3D('',#165055,#165056,#165057); +#165055 = CARTESIAN_POINT('',(1.905,0.706843139085,2.459055548476)); +#165056 = DIRECTION('',(0.E+000,0.130759809642,0.991414077055)); +#165057 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#165058 = DEFINITIONAL_REPRESENTATION('',(#165059),#165063); +#165059 = LINE('',#165060,#165061); +#165060 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#165061 = VECTOR('',#165062,1.); +#165062 = DIRECTION('',(0.E+000,1.)); +#165063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165064 = PCURVE('',#165065,#165070); +#165065 = CYLINDRICAL_SURFACE('',#165066,0.32); +#165066 = AXIS2_PLACEMENT_3D('',#165067,#165068,#165069); +#165067 = CARTESIAN_POINT('',(1.905,0.665,2.141803043818)); +#165068 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165069 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165070 = DEFINITIONAL_REPRESENTATION('',(#165071),#165074); +#165071 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165072,#165073), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162680 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#162681 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#162682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162683 = ORIENTED_EDGE('',*,*,#162684,.F.); -#162684 = EDGE_CURVE('',#162685,#162651,#162687,.T.); -#162685 = VERTEX_POINT('',#162686); -#162686 = CARTESIAN_POINT('',(1.695,0.327745739138,2.509055548476)); -#162687 = SURFACE_CURVE('',#162688,(#162692,#162699),.PCURVE_S1.); -#162688 = LINE('',#162689,#162690); -#162689 = CARTESIAN_POINT('',(1.695,0.327745739138,2.509055548476)); -#162690 = VECTOR('',#162691,1.); -#162691 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#162692 = PCURVE('',#162661,#162693); -#162693 = DEFINITIONAL_REPRESENTATION('',(#162694),#162698); -#162694 = LINE('',#162695,#162696); -#162695 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#162696 = VECTOR('',#162697,1.); -#162697 = DIRECTION('',(-1.,0.E+000)); -#162698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162699 = PCURVE('',#162700,#162705); -#162700 = PLANE('',#162701); -#162701 = AXIS2_PLACEMENT_3D('',#162702,#162703,#162704); -#162702 = CARTESIAN_POINT('',(1.695,0.875,0.E+000)); -#162703 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162704 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162705 = DEFINITIONAL_REPRESENTATION('',(#162706),#162710); -#162706 = LINE('',#162707,#162708); -#162707 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#162708 = VECTOR('',#162709,1.); -#162709 = DIRECTION('',(-0.130759809642,0.991414077055)); -#162710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162711 = ORIENTED_EDGE('',*,*,#162712,.T.); -#162712 = EDGE_CURVE('',#162685,#162713,#162715,.T.); -#162713 = VERTEX_POINT('',#162714); -#162714 = CARTESIAN_POINT('',(2.115,0.327745739138,2.509055548476)); -#162715 = SURFACE_CURVE('',#162716,(#162720,#162727),.PCURVE_S1.); -#162716 = LINE('',#162717,#162718); -#162717 = CARTESIAN_POINT('',(1.905,0.327745739138,2.509055548476)); -#162718 = VECTOR('',#162719,1.); -#162719 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162720 = PCURVE('',#162661,#162721); -#162721 = DEFINITIONAL_REPRESENTATION('',(#162722),#162726); -#162722 = LINE('',#162723,#162724); -#162723 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#162724 = VECTOR('',#162725,1.); -#162725 = DIRECTION('',(0.E+000,1.)); -#162726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162727 = PCURVE('',#162728,#162733); -#162728 = CYLINDRICAL_SURFACE('',#162729,9.999999999999E-002); -#162729 = AXIS2_PLACEMENT_3D('',#162730,#162731,#162732); -#162730 = CARTESIAN_POINT('',(1.905,0.340821720102,2.608196956182)); -#162731 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162732 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162733 = DEFINITIONAL_REPRESENTATION('',(#162734),#162737); -#162734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162735,#162736), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162735 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162736 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165072 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#165073 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#165074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165075 = ORIENTED_EDGE('',*,*,#165076,.F.); +#165076 = EDGE_CURVE('',#165077,#165043,#165079,.T.); +#165077 = VERTEX_POINT('',#165078); +#165078 = CARTESIAN_POINT('',(1.695,0.327745739138,2.509055548476)); +#165079 = SURFACE_CURVE('',#165080,(#165084,#165091),.PCURVE_S1.); +#165080 = LINE('',#165081,#165082); +#165081 = CARTESIAN_POINT('',(1.695,0.327745739138,2.509055548476)); +#165082 = VECTOR('',#165083,1.); +#165083 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#165084 = PCURVE('',#165053,#165085); +#165085 = DEFINITIONAL_REPRESENTATION('',(#165086),#165090); +#165086 = LINE('',#165087,#165088); +#165087 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#165088 = VECTOR('',#165089,1.); +#165089 = DIRECTION('',(-1.,0.E+000)); +#165090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162738 = ORIENTED_EDGE('',*,*,#162739,.F.); -#162739 = EDGE_CURVE('',#162653,#162713,#162740,.T.); -#162740 = SURFACE_CURVE('',#162741,(#162745,#162752),.PCURVE_S1.); -#162741 = LINE('',#162742,#162743); -#162742 = CARTESIAN_POINT('',(2.115,0.706843139085,2.459055548476)); -#162743 = VECTOR('',#162744,1.); -#162744 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#162745 = PCURVE('',#162661,#162746); -#162746 = DEFINITIONAL_REPRESENTATION('',(#162747),#162751); -#162747 = LINE('',#162748,#162749); -#162748 = CARTESIAN_POINT('',(0.E+000,0.21)); -#162749 = VECTOR('',#162750,1.); -#162750 = DIRECTION('',(1.,0.E+000)); -#162751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162752 = PCURVE('',#162753,#162758); -#162753 = PLANE('',#162754); -#162754 = AXIS2_PLACEMENT_3D('',#162755,#162756,#162757); -#162755 = CARTESIAN_POINT('',(2.115,0.875,0.E+000)); -#162756 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162757 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#162758 = DEFINITIONAL_REPRESENTATION('',(#162759),#162763); -#162759 = LINE('',#162760,#162761); -#162760 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#162761 = VECTOR('',#162762,1.); -#162762 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#162763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162764 = ADVANCED_FACE('',(#162765),#162728,.F.); -#162765 = FACE_BOUND('',#162766,.F.); -#162766 = EDGE_LOOP('',(#162767,#162794,#162821,#162846)); -#162767 = ORIENTED_EDGE('',*,*,#162768,.T.); -#162768 = EDGE_CURVE('',#162713,#162769,#162771,.T.); -#162769 = VERTEX_POINT('',#162770); -#162770 = CARTESIAN_POINT('',(2.115,0.240958766627,2.602963360557)); -#162771 = SURFACE_CURVE('',#162772,(#162777,#162783),.PCURVE_S1.); -#162772 = CIRCLE('',#162773,9.999999999999E-002); -#162773 = AXIS2_PLACEMENT_3D('',#162774,#162775,#162776); -#162774 = CARTESIAN_POINT('',(2.115,0.340821720102,2.608196956182)); -#162775 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162776 = DIRECTION('',(0.E+000,0.E+000,1.)); -#162777 = PCURVE('',#162728,#162778); -#162778 = DEFINITIONAL_REPRESENTATION('',(#162779),#162782); -#162779 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162780,#162781), +#165091 = PCURVE('',#165092,#165097); +#165092 = PLANE('',#165093); +#165093 = AXIS2_PLACEMENT_3D('',#165094,#165095,#165096); +#165094 = CARTESIAN_POINT('',(1.695,0.875,0.E+000)); +#165095 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165096 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165097 = DEFINITIONAL_REPRESENTATION('',(#165098),#165102); +#165098 = LINE('',#165099,#165100); +#165099 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#165100 = VECTOR('',#165101,1.); +#165101 = DIRECTION('',(-0.130759809642,0.991414077055)); +#165102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165103 = ORIENTED_EDGE('',*,*,#165104,.T.); +#165104 = EDGE_CURVE('',#165077,#165105,#165107,.T.); +#165105 = VERTEX_POINT('',#165106); +#165106 = CARTESIAN_POINT('',(2.115,0.327745739138,2.509055548476)); +#165107 = SURFACE_CURVE('',#165108,(#165112,#165119),.PCURVE_S1.); +#165108 = LINE('',#165109,#165110); +#165109 = CARTESIAN_POINT('',(1.905,0.327745739138,2.509055548476)); +#165110 = VECTOR('',#165111,1.); +#165111 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165112 = PCURVE('',#165053,#165113); +#165113 = DEFINITIONAL_REPRESENTATION('',(#165114),#165118); +#165114 = LINE('',#165115,#165116); +#165115 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#165116 = VECTOR('',#165117,1.); +#165117 = DIRECTION('',(0.E+000,1.)); +#165118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165119 = PCURVE('',#165120,#165125); +#165120 = CYLINDRICAL_SURFACE('',#165121,9.999999999999E-002); +#165121 = AXIS2_PLACEMENT_3D('',#165122,#165123,#165124); +#165122 = CARTESIAN_POINT('',(1.905,0.340821720102,2.608196956182)); +#165123 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165124 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165125 = DEFINITIONAL_REPRESENTATION('',(#165126),#165129); +#165126 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165127,#165128), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); +#165127 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165128 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165130 = ORIENTED_EDGE('',*,*,#165131,.F.); +#165131 = EDGE_CURVE('',#165045,#165105,#165132,.T.); +#165132 = SURFACE_CURVE('',#165133,(#165137,#165144),.PCURVE_S1.); +#165133 = LINE('',#165134,#165135); +#165134 = CARTESIAN_POINT('',(2.115,0.706843139085,2.459055548476)); +#165135 = VECTOR('',#165136,1.); +#165136 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#165137 = PCURVE('',#165053,#165138); +#165138 = DEFINITIONAL_REPRESENTATION('',(#165139),#165143); +#165139 = LINE('',#165140,#165141); +#165140 = CARTESIAN_POINT('',(0.E+000,0.21)); +#165141 = VECTOR('',#165142,1.); +#165142 = DIRECTION('',(1.,0.E+000)); +#165143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165144 = PCURVE('',#165145,#165150); +#165145 = PLANE('',#165146); +#165146 = AXIS2_PLACEMENT_3D('',#165147,#165148,#165149); +#165147 = CARTESIAN_POINT('',(2.115,0.875,0.E+000)); +#165148 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165149 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165150 = DEFINITIONAL_REPRESENTATION('',(#165151),#165155); +#165151 = LINE('',#165152,#165153); +#165152 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#165153 = VECTOR('',#165154,1.); +#165154 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#165155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165156 = ADVANCED_FACE('',(#165157),#165120,.F.); +#165157 = FACE_BOUND('',#165158,.F.); +#165158 = EDGE_LOOP('',(#165159,#165186,#165213,#165238)); +#165159 = ORIENTED_EDGE('',*,*,#165160,.T.); +#165160 = EDGE_CURVE('',#165105,#165161,#165163,.T.); +#165161 = VERTEX_POINT('',#165162); +#165162 = CARTESIAN_POINT('',(2.115,0.240958766627,2.602963360557)); +#165163 = SURFACE_CURVE('',#165164,(#165169,#165175),.PCURVE_S1.); +#165164 = CIRCLE('',#165165,9.999999999999E-002); +#165165 = AXIS2_PLACEMENT_3D('',#165166,#165167,#165168); +#165166 = CARTESIAN_POINT('',(2.115,0.340821720102,2.608196956182)); +#165167 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165168 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165169 = PCURVE('',#165120,#165170); +#165170 = DEFINITIONAL_REPRESENTATION('',(#165171),#165174); +#165171 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165172,#165173), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#162780 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#162781 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165172 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165173 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162783 = PCURVE('',#162753,#162784); -#162784 = DEFINITIONAL_REPRESENTATION('',(#162785),#162793); -#162785 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162786,#162787,#162788, - #162789,#162790,#162791,#162792),.UNSPECIFIED.,.T.,.F.) +#165175 = PCURVE('',#165145,#165176); +#165176 = DEFINITIONAL_REPRESENTATION('',(#165177),#165185); +#165177 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165178,#165179,#165180, + #165181,#165182,#165183,#165184),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162786 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#162787 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#162788 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#162789 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#162790 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#162791 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#162792 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#162793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162794 = ORIENTED_EDGE('',*,*,#162795,.T.); -#162795 = EDGE_CURVE('',#162769,#162796,#162798,.T.); -#162796 = VERTEX_POINT('',#162797); -#162797 = CARTESIAN_POINT('',(1.695,0.240958766627,2.602963360557)); -#162798 = SURFACE_CURVE('',#162799,(#162803,#162809),.PCURVE_S1.); -#162799 = LINE('',#162800,#162801); -#162800 = CARTESIAN_POINT('',(1.905,0.240958766627,2.602963360557)); -#162801 = VECTOR('',#162802,1.); -#162802 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162803 = PCURVE('',#162728,#162804); -#162804 = DEFINITIONAL_REPRESENTATION('',(#162805),#162808); -#162805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162806,#162807), +#165178 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#165179 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#165180 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#165181 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#165182 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#165183 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#165184 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#165185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165186 = ORIENTED_EDGE('',*,*,#165187,.T.); +#165187 = EDGE_CURVE('',#165161,#165188,#165190,.T.); +#165188 = VERTEX_POINT('',#165189); +#165189 = CARTESIAN_POINT('',(1.695,0.240958766627,2.602963360557)); +#165190 = SURFACE_CURVE('',#165191,(#165195,#165201),.PCURVE_S1.); +#165191 = LINE('',#165192,#165193); +#165192 = CARTESIAN_POINT('',(1.905,0.240958766627,2.602963360557)); +#165193 = VECTOR('',#165194,1.); +#165194 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165195 = PCURVE('',#165120,#165196); +#165196 = DEFINITIONAL_REPRESENTATION('',(#165197),#165200); +#165197 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165198,#165199), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#162806 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#162807 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162809 = PCURVE('',#162810,#162815); -#162810 = PLANE('',#162811); -#162811 = AXIS2_PLACEMENT_3D('',#162812,#162813,#162814); -#162812 = CARTESIAN_POINT('',(1.905,0.240958766627,2.602963360557)); -#162813 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); -#162814 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#162815 = DEFINITIONAL_REPRESENTATION('',(#162816),#162820); -#162816 = LINE('',#162817,#162818); -#162817 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); -#162818 = VECTOR('',#162819,1.); -#162819 = DIRECTION('',(0.E+000,-1.)); -#162820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162821 = ORIENTED_EDGE('',*,*,#162822,.T.); -#162822 = EDGE_CURVE('',#162796,#162685,#162823,.T.); -#162823 = SURFACE_CURVE('',#162824,(#162829,#162835),.PCURVE_S1.); -#162824 = CIRCLE('',#162825,9.999999999999E-002); -#162825 = AXIS2_PLACEMENT_3D('',#162826,#162827,#162828); -#162826 = CARTESIAN_POINT('',(1.695,0.340821720102,2.608196956182)); -#162827 = DIRECTION('',(1.,0.E+000,0.E+000)); -#162828 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); -#162829 = PCURVE('',#162728,#162830); -#162830 = DEFINITIONAL_REPRESENTATION('',(#162831),#162834); -#162831 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#162832,#162833), +#165198 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165199 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165201 = PCURVE('',#165202,#165207); +#165202 = PLANE('',#165203); +#165203 = AXIS2_PLACEMENT_3D('',#165204,#165205,#165206); +#165204 = CARTESIAN_POINT('',(1.905,0.240958766627,2.602963360557)); +#165205 = DIRECTION('',(0.E+000,0.998629534755,5.233595624294E-002)); +#165206 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#165207 = DEFINITIONAL_REPRESENTATION('',(#165208),#165212); +#165208 = LINE('',#165209,#165210); +#165209 = CARTESIAN_POINT('',(4.44933215613E-016,0.E+000)); +#165210 = VECTOR('',#165211,1.); +#165211 = DIRECTION('',(0.E+000,-1.)); +#165212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165213 = ORIENTED_EDGE('',*,*,#165214,.T.); +#165214 = EDGE_CURVE('',#165188,#165077,#165215,.T.); +#165215 = SURFACE_CURVE('',#165216,(#165221,#165227),.PCURVE_S1.); +#165216 = CIRCLE('',#165217,9.999999999999E-002); +#165217 = AXIS2_PLACEMENT_3D('',#165218,#165219,#165220); +#165218 = CARTESIAN_POINT('',(1.695,0.340821720102,2.608196956182)); +#165219 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165220 = DIRECTION('',(0.E+000,-4.336808689942E-015,1.)); +#165221 = PCURVE('',#165120,#165222); +#165222 = DEFINITIONAL_REPRESENTATION('',(#165223),#165226); +#165223 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165224,#165225), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#162832 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#162833 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#162834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165224 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165225 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162835 = PCURVE('',#162700,#162836); -#162836 = DEFINITIONAL_REPRESENTATION('',(#162837),#162845); -#162837 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#162838,#162839,#162840, - #162841,#162842,#162843,#162844),.UNSPECIFIED.,.F.,.F.) +#165227 = PCURVE('',#165092,#165228); +#165228 = DEFINITIONAL_REPRESENTATION('',(#165229),#165237); +#165229 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165230,#165231,#165232, + #165233,#165234,#165235,#165236),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#162838 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#162839 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#162840 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#162841 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#162842 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#162843 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#162844 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#162845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162846 = ORIENTED_EDGE('',*,*,#162712,.T.); -#162847 = ADVANCED_FACE('',(#162848),#162810,.T.); -#162848 = FACE_BOUND('',#162849,.T.); -#162849 = EDGE_LOOP('',(#162850,#162851,#162874,#162902)); -#162850 = ORIENTED_EDGE('',*,*,#162795,.T.); -#162851 = ORIENTED_EDGE('',*,*,#162852,.F.); -#162852 = EDGE_CURVE('',#162853,#162796,#162855,.T.); -#162853 = VERTEX_POINT('',#162854); -#162854 = CARTESIAN_POINT('',(1.695,0.219849248823,3.005756955187)); -#162855 = SURFACE_CURVE('',#162856,(#162860,#162867),.PCURVE_S1.); -#162856 = LINE('',#162857,#162858); -#162857 = CARTESIAN_POINT('',(1.695,0.219849248823,3.005756955187)); -#162858 = VECTOR('',#162859,1.); -#162859 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#162860 = PCURVE('',#162810,#162861); -#162861 = DEFINITIONAL_REPRESENTATION('',(#162862),#162866); -#162862 = LINE('',#162863,#162864); -#162863 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#162864 = VECTOR('',#162865,1.); -#162865 = DIRECTION('',(-1.,0.E+000)); -#162866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165230 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#165231 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#165232 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#165233 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#165234 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#165235 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#165236 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#165237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165238 = ORIENTED_EDGE('',*,*,#165104,.T.); +#165239 = ADVANCED_FACE('',(#165240),#165202,.T.); +#165240 = FACE_BOUND('',#165241,.T.); +#165241 = EDGE_LOOP('',(#165242,#165243,#165266,#165294)); +#165242 = ORIENTED_EDGE('',*,*,#165187,.T.); +#165243 = ORIENTED_EDGE('',*,*,#165244,.F.); +#165244 = EDGE_CURVE('',#165245,#165188,#165247,.T.); +#165245 = VERTEX_POINT('',#165246); +#165246 = CARTESIAN_POINT('',(1.695,0.219849248823,3.005756955187)); +#165247 = SURFACE_CURVE('',#165248,(#165252,#165259),.PCURVE_S1.); +#165248 = LINE('',#165249,#165250); +#165249 = CARTESIAN_POINT('',(1.695,0.219849248823,3.005756955187)); +#165250 = VECTOR('',#165251,1.); +#165251 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#165252 = PCURVE('',#165202,#165253); +#165253 = DEFINITIONAL_REPRESENTATION('',(#165254),#165258); +#165254 = LINE('',#165255,#165256); +#165255 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#165256 = VECTOR('',#165257,1.); +#165257 = DIRECTION('',(-1.,0.E+000)); +#165258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165259 = PCURVE('',#165092,#165260); +#165260 = DEFINITIONAL_REPRESENTATION('',(#165261),#165265); +#165261 = LINE('',#165262,#165263); +#165262 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#165263 = VECTOR('',#165264,1.); +#165264 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#165265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165266 = ORIENTED_EDGE('',*,*,#165267,.F.); +#165267 = EDGE_CURVE('',#165268,#165245,#165270,.T.); +#165268 = VERTEX_POINT('',#165269); +#165269 = CARTESIAN_POINT('',(2.115,0.219849248823,3.005756955187)); +#165270 = SURFACE_CURVE('',#165271,(#165275,#165282),.PCURVE_S1.); +#165271 = LINE('',#165272,#165273); +#165272 = CARTESIAN_POINT('',(1.905,0.219849248823,3.005756955187)); +#165273 = VECTOR('',#165274,1.); +#165274 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165275 = PCURVE('',#165202,#165276); +#165276 = DEFINITIONAL_REPRESENTATION('',(#165277),#165281); +#165277 = LINE('',#165278,#165279); +#165278 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#165279 = VECTOR('',#165280,1.); +#165280 = DIRECTION('',(0.E+000,-1.)); +#165281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165282 = PCURVE('',#165283,#165288); +#165283 = PLANE('',#165284); +#165284 = AXIS2_PLACEMENT_3D('',#165285,#165286,#165287); +#165285 = CARTESIAN_POINT('',(1.905,0.11,3.)); +#165286 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); +#165287 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#165288 = DEFINITIONAL_REPRESENTATION('',(#165289),#165293); +#165289 = LINE('',#165290,#165291); +#165290 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#165291 = VECTOR('',#165292,1.); +#165292 = DIRECTION('',(0.E+000,-1.)); +#165293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165294 = ORIENTED_EDGE('',*,*,#165295,.F.); +#165295 = EDGE_CURVE('',#165161,#165268,#165296,.T.); +#165296 = SURFACE_CURVE('',#165297,(#165301,#165308),.PCURVE_S1.); +#165297 = LINE('',#165298,#165299); +#165298 = CARTESIAN_POINT('',(2.115,0.240958766627,2.602963360557)); +#165299 = VECTOR('',#165300,1.); +#165300 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#165301 = PCURVE('',#165202,#165302); +#165302 = DEFINITIONAL_REPRESENTATION('',(#165303),#165307); +#165303 = LINE('',#165304,#165305); +#165304 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); +#165305 = VECTOR('',#165306,1.); +#165306 = DIRECTION('',(1.,0.E+000)); +#165307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165308 = PCURVE('',#165145,#165309); +#165309 = DEFINITIONAL_REPRESENTATION('',(#165310),#165314); +#165310 = LINE('',#165311,#165312); +#165311 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#165312 = VECTOR('',#165313,1.); +#165313 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#165314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165315 = ADVANCED_FACE('',(#165316),#165283,.T.); +#165316 = FACE_BOUND('',#165317,.T.); +#165317 = EDGE_LOOP('',(#165318,#165348,#165369,#165370)); +#165318 = ORIENTED_EDGE('',*,*,#165319,.F.); +#165319 = EDGE_CURVE('',#165320,#165322,#165324,.T.); +#165320 = VERTEX_POINT('',#165321); +#165321 = CARTESIAN_POINT('',(2.115,1.507511769915E-004,2.994243044813) + ); +#165322 = VERTEX_POINT('',#165323); +#165323 = CARTESIAN_POINT('',(1.695,1.507511769916E-004,2.994243044813) + ); +#165324 = SURFACE_CURVE('',#165325,(#165329,#165336),.PCURVE_S1.); +#165325 = LINE('',#165326,#165327); +#165326 = CARTESIAN_POINT('',(1.905,1.507511769963E-004,2.994243044813) + ); +#165327 = VECTOR('',#165328,1.); +#165328 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165329 = PCURVE('',#165283,#165330); +#165330 = DEFINITIONAL_REPRESENTATION('',(#165331),#165335); +#165331 = LINE('',#165332,#165333); +#165332 = CARTESIAN_POINT('',(0.11,0.E+000)); +#165333 = VECTOR('',#165334,1.); +#165334 = DIRECTION('',(0.E+000,-1.)); +#165335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#162867 = PCURVE('',#162700,#162868); -#162868 = DEFINITIONAL_REPRESENTATION('',(#162869),#162873); -#162869 = LINE('',#162870,#162871); -#162870 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#162871 = VECTOR('',#162872,1.); -#162872 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#162873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162874 = ORIENTED_EDGE('',*,*,#162875,.F.); -#162875 = EDGE_CURVE('',#162876,#162853,#162878,.T.); -#162876 = VERTEX_POINT('',#162877); -#162877 = CARTESIAN_POINT('',(2.115,0.219849248823,3.005756955187)); -#162878 = SURFACE_CURVE('',#162879,(#162883,#162890),.PCURVE_S1.); -#162879 = LINE('',#162880,#162881); -#162880 = CARTESIAN_POINT('',(1.905,0.219849248823,3.005756955187)); -#162881 = VECTOR('',#162882,1.); -#162882 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162883 = PCURVE('',#162810,#162884); -#162884 = DEFINITIONAL_REPRESENTATION('',(#162885),#162889); -#162885 = LINE('',#162886,#162887); -#162886 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#162887 = VECTOR('',#162888,1.); -#162888 = DIRECTION('',(0.E+000,-1.)); -#162889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162890 = PCURVE('',#162891,#162896); -#162891 = PLANE('',#162892); -#162892 = AXIS2_PLACEMENT_3D('',#162893,#162894,#162895); -#162893 = CARTESIAN_POINT('',(1.905,0.11,3.)); -#162894 = DIRECTION('',(0.E+000,-5.233595624291E-002,0.998629534755)); -#162895 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#162896 = DEFINITIONAL_REPRESENTATION('',(#162897),#162901); -#162897 = LINE('',#162898,#162899); -#162898 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#162899 = VECTOR('',#162900,1.); -#162900 = DIRECTION('',(0.E+000,-1.)); -#162901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162902 = ORIENTED_EDGE('',*,*,#162903,.F.); -#162903 = EDGE_CURVE('',#162769,#162876,#162904,.T.); -#162904 = SURFACE_CURVE('',#162905,(#162909,#162916),.PCURVE_S1.); -#162905 = LINE('',#162906,#162907); -#162906 = CARTESIAN_POINT('',(2.115,0.240958766627,2.602963360557)); -#162907 = VECTOR('',#162908,1.); -#162908 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#162909 = PCURVE('',#162810,#162910); -#162910 = DEFINITIONAL_REPRESENTATION('',(#162911),#162915); -#162911 = LINE('',#162912,#162913); -#162912 = CARTESIAN_POINT('',(4.44933215613E-016,0.21)); -#162913 = VECTOR('',#162914,1.); -#162914 = DIRECTION('',(1.,0.E+000)); -#162915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162916 = PCURVE('',#162753,#162917); -#162917 = DEFINITIONAL_REPRESENTATION('',(#162918),#162922); -#162918 = LINE('',#162919,#162920); -#162919 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#162920 = VECTOR('',#162921,1.); -#162921 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#162922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162923 = ADVANCED_FACE('',(#162924),#162891,.T.); -#162924 = FACE_BOUND('',#162925,.T.); -#162925 = EDGE_LOOP('',(#162926,#162956,#162977,#162978)); -#162926 = ORIENTED_EDGE('',*,*,#162927,.F.); -#162927 = EDGE_CURVE('',#162928,#162930,#162932,.T.); -#162928 = VERTEX_POINT('',#162929); -#162929 = CARTESIAN_POINT('',(2.115,1.507511769915E-004,2.994243044813) - ); -#162930 = VERTEX_POINT('',#162931); -#162931 = CARTESIAN_POINT('',(1.695,1.507511769916E-004,2.994243044813) - ); -#162932 = SURFACE_CURVE('',#162933,(#162937,#162944),.PCURVE_S1.); -#162933 = LINE('',#162934,#162935); -#162934 = CARTESIAN_POINT('',(1.905,1.507511769963E-004,2.994243044813) - ); -#162935 = VECTOR('',#162936,1.); -#162936 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#162937 = PCURVE('',#162891,#162938); -#162938 = DEFINITIONAL_REPRESENTATION('',(#162939),#162943); -#162939 = LINE('',#162940,#162941); -#162940 = CARTESIAN_POINT('',(0.11,0.E+000)); -#162941 = VECTOR('',#162942,1.); -#162942 = DIRECTION('',(0.E+000,-1.)); -#162943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162944 = PCURVE('',#162945,#162950); -#162945 = PLANE('',#162946); -#162946 = AXIS2_PLACEMENT_3D('',#162947,#162948,#162949); -#162947 = CARTESIAN_POINT('',(1.905,2.126026898096E-002,2.591449450184) - ); -#162948 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); -#162949 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#162950 = DEFINITIONAL_REPRESENTATION('',(#162951),#162955); -#162951 = LINE('',#162952,#162953); -#162952 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#162953 = VECTOR('',#162954,1.); -#162954 = DIRECTION('',(0.E+000,-1.)); -#162955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162956 = ORIENTED_EDGE('',*,*,#162957,.F.); -#162957 = EDGE_CURVE('',#162876,#162928,#162958,.T.); -#162958 = SURFACE_CURVE('',#162959,(#162963,#162970),.PCURVE_S1.); -#162959 = LINE('',#162960,#162961); -#162960 = CARTESIAN_POINT('',(2.115,0.219849248823,3.005756955187)); -#162961 = VECTOR('',#162962,1.); -#162962 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); -#162963 = PCURVE('',#162891,#162964); -#162964 = DEFINITIONAL_REPRESENTATION('',(#162965),#162969); -#162965 = LINE('',#162966,#162967); -#162966 = CARTESIAN_POINT('',(-0.11,0.21)); -#162967 = VECTOR('',#162968,1.); -#162968 = DIRECTION('',(1.,0.E+000)); -#162969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162970 = PCURVE('',#162753,#162971); -#162971 = DEFINITIONAL_REPRESENTATION('',(#162972),#162976); -#162972 = LINE('',#162973,#162974); -#162973 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#162974 = VECTOR('',#162975,1.); -#162975 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#162976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162977 = ORIENTED_EDGE('',*,*,#162875,.T.); -#162978 = ORIENTED_EDGE('',*,*,#162979,.F.); -#162979 = EDGE_CURVE('',#162930,#162853,#162980,.T.); -#162980 = SURFACE_CURVE('',#162981,(#162985,#162992),.PCURVE_S1.); -#162981 = LINE('',#162982,#162983); -#162982 = CARTESIAN_POINT('',(1.695,1.507511769892E-004,2.994243044813) - ); -#162983 = VECTOR('',#162984,1.); -#162984 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); -#162985 = PCURVE('',#162891,#162986); -#162986 = DEFINITIONAL_REPRESENTATION('',(#162987),#162991); -#162987 = LINE('',#162988,#162989); -#162988 = CARTESIAN_POINT('',(0.11,-0.21)); -#162989 = VECTOR('',#162990,1.); -#162990 = DIRECTION('',(-1.,0.E+000)); -#162991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162992 = PCURVE('',#162700,#162993); -#162993 = DEFINITIONAL_REPRESENTATION('',(#162994),#162998); -#162994 = LINE('',#162995,#162996); -#162995 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#162996 = VECTOR('',#162997,1.); -#162997 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#162998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#162999 = ADVANCED_FACE('',(#163000),#162945,.T.); -#163000 = FACE_BOUND('',#163001,.T.); -#163001 = EDGE_LOOP('',(#163002,#163031,#163052,#163053)); -#163002 = ORIENTED_EDGE('',*,*,#163003,.F.); -#163003 = EDGE_CURVE('',#163004,#163006,#163008,.T.); -#163004 = VERTEX_POINT('',#163005); -#163005 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,2.591449450184) - ); -#163006 = VERTEX_POINT('',#163007); -#163007 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,2.591449450184) - ); -#163008 = SURFACE_CURVE('',#163009,(#163013,#163020),.PCURVE_S1.); -#163009 = LINE('',#163010,#163011); -#163010 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,2.591449450184) - ); -#163011 = VECTOR('',#163012,1.); -#163012 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163013 = PCURVE('',#162945,#163014); -#163014 = DEFINITIONAL_REPRESENTATION('',(#163015),#163019); -#163015 = LINE('',#163016,#163017); -#163016 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); -#163017 = VECTOR('',#163018,1.); -#163018 = DIRECTION('',(0.E+000,-1.)); -#163019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163020 = PCURVE('',#163021,#163026); -#163021 = CYLINDRICAL_SURFACE('',#163022,0.32); -#163022 = AXIS2_PLACEMENT_3D('',#163023,#163024,#163025); -#163023 = CARTESIAN_POINT('',(1.905,0.340821720102,2.608196956182)); -#163024 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163025 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163026 = DEFINITIONAL_REPRESENTATION('',(#163027),#163030); -#163027 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163028,#163029), +#165336 = PCURVE('',#165337,#165342); +#165337 = PLANE('',#165338); +#165338 = AXIS2_PLACEMENT_3D('',#165339,#165340,#165341); +#165339 = CARTESIAN_POINT('',(1.905,2.126026898096E-002,2.591449450184) + ); +#165340 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624294E-002)); +#165341 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#165342 = DEFINITIONAL_REPRESENTATION('',(#165343),#165347); +#165343 = LINE('',#165344,#165345); +#165344 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#165345 = VECTOR('',#165346,1.); +#165346 = DIRECTION('',(0.E+000,-1.)); +#165347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165348 = ORIENTED_EDGE('',*,*,#165349,.F.); +#165349 = EDGE_CURVE('',#165268,#165320,#165350,.T.); +#165350 = SURFACE_CURVE('',#165351,(#165355,#165362),.PCURVE_S1.); +#165351 = LINE('',#165352,#165353); +#165352 = CARTESIAN_POINT('',(2.115,0.219849248823,3.005756955187)); +#165353 = VECTOR('',#165354,1.); +#165354 = DIRECTION('',(0.E+000,-0.998629534755,-5.233595624291E-002)); +#165355 = PCURVE('',#165283,#165356); +#165356 = DEFINITIONAL_REPRESENTATION('',(#165357),#165361); +#165357 = LINE('',#165358,#165359); +#165358 = CARTESIAN_POINT('',(-0.11,0.21)); +#165359 = VECTOR('',#165360,1.); +#165360 = DIRECTION('',(1.,0.E+000)); +#165361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165362 = PCURVE('',#165145,#165363); +#165363 = DEFINITIONAL_REPRESENTATION('',(#165364),#165368); +#165364 = LINE('',#165365,#165366); +#165365 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#165366 = VECTOR('',#165367,1.); +#165367 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#165368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165369 = ORIENTED_EDGE('',*,*,#165267,.T.); +#165370 = ORIENTED_EDGE('',*,*,#165371,.F.); +#165371 = EDGE_CURVE('',#165322,#165245,#165372,.T.); +#165372 = SURFACE_CURVE('',#165373,(#165377,#165384),.PCURVE_S1.); +#165373 = LINE('',#165374,#165375); +#165374 = CARTESIAN_POINT('',(1.695,1.507511769892E-004,2.994243044813) + ); +#165375 = VECTOR('',#165376,1.); +#165376 = DIRECTION('',(0.E+000,0.998629534755,5.233595624291E-002)); +#165377 = PCURVE('',#165283,#165378); +#165378 = DEFINITIONAL_REPRESENTATION('',(#165379),#165383); +#165379 = LINE('',#165380,#165381); +#165380 = CARTESIAN_POINT('',(0.11,-0.21)); +#165381 = VECTOR('',#165382,1.); +#165382 = DIRECTION('',(-1.,0.E+000)); +#165383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165384 = PCURVE('',#165092,#165385); +#165385 = DEFINITIONAL_REPRESENTATION('',(#165386),#165390); +#165386 = LINE('',#165387,#165388); +#165387 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#165388 = VECTOR('',#165389,1.); +#165389 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#165390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165391 = ADVANCED_FACE('',(#165392),#165337,.T.); +#165392 = FACE_BOUND('',#165393,.T.); +#165393 = EDGE_LOOP('',(#165394,#165423,#165444,#165445)); +#165394 = ORIENTED_EDGE('',*,*,#165395,.F.); +#165395 = EDGE_CURVE('',#165396,#165398,#165400,.T.); +#165396 = VERTEX_POINT('',#165397); +#165397 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,2.591449450184) + ); +#165398 = VERTEX_POINT('',#165399); +#165399 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,2.591449450184) + ); +#165400 = SURFACE_CURVE('',#165401,(#165405,#165412),.PCURVE_S1.); +#165401 = LINE('',#165402,#165403); +#165402 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,2.591449450184) + ); +#165403 = VECTOR('',#165404,1.); +#165404 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165405 = PCURVE('',#165337,#165406); +#165406 = DEFINITIONAL_REPRESENTATION('',(#165407),#165411); +#165407 = LINE('',#165408,#165409); +#165408 = CARTESIAN_POINT('',(-4.445700619653E-016,0.E+000)); +#165409 = VECTOR('',#165410,1.); +#165410 = DIRECTION('',(0.E+000,-1.)); +#165411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165412 = PCURVE('',#165413,#165418); +#165413 = CYLINDRICAL_SURFACE('',#165414,0.32); +#165414 = AXIS2_PLACEMENT_3D('',#165415,#165416,#165417); +#165415 = CARTESIAN_POINT('',(1.905,0.340821720102,2.608196956182)); +#165416 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165417 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165418 = DEFINITIONAL_REPRESENTATION('',(#165419),#165422); +#165419 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165420,#165421), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163028 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163029 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163031 = ORIENTED_EDGE('',*,*,#163032,.F.); -#163032 = EDGE_CURVE('',#162928,#163004,#163033,.T.); -#163033 = SURFACE_CURVE('',#163034,(#163038,#163045),.PCURVE_S1.); -#163034 = LINE('',#163035,#163036); -#163035 = CARTESIAN_POINT('',(2.115,1.507511769892E-004,2.994243044813) - ); -#163036 = VECTOR('',#163037,1.); -#163037 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); -#163038 = PCURVE('',#162945,#163039); -#163039 = DEFINITIONAL_REPRESENTATION('',(#163040),#163044); -#163040 = LINE('',#163041,#163042); -#163041 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#163042 = VECTOR('',#163043,1.); -#163043 = DIRECTION('',(1.,0.E+000)); -#163044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163045 = PCURVE('',#162753,#163046); -#163046 = DEFINITIONAL_REPRESENTATION('',(#163047),#163051); -#163047 = LINE('',#163048,#163049); -#163048 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#163049 = VECTOR('',#163050,1.); -#163050 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#163051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163052 = ORIENTED_EDGE('',*,*,#162927,.T.); -#163053 = ORIENTED_EDGE('',*,*,#163054,.F.); -#163054 = EDGE_CURVE('',#163006,#162930,#163055,.T.); -#163055 = SURFACE_CURVE('',#163056,(#163060,#163067),.PCURVE_S1.); -#163056 = LINE('',#163057,#163058); -#163057 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,2.591449450184) - ); -#163058 = VECTOR('',#163059,1.); -#163059 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); -#163060 = PCURVE('',#162945,#163061); -#163061 = DEFINITIONAL_REPRESENTATION('',(#163062),#163066); -#163062 = LINE('',#163063,#163064); -#163063 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); -#163064 = VECTOR('',#163065,1.); -#163065 = DIRECTION('',(-1.,0.E+000)); -#163066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163067 = PCURVE('',#162700,#163068); -#163068 = DEFINITIONAL_REPRESENTATION('',(#163069),#163073); -#163069 = LINE('',#163070,#163071); -#163070 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#163071 = VECTOR('',#163072,1.); -#163072 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#163073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163074 = ADVANCED_FACE('',(#163075),#163021,.T.); -#163075 = FACE_BOUND('',#163076,.T.); -#163076 = EDGE_LOOP('',(#163077,#163106,#163127,#163128)); -#163077 = ORIENTED_EDGE('',*,*,#163078,.F.); -#163078 = EDGE_CURVE('',#163079,#163081,#163083,.T.); -#163079 = VERTEX_POINT('',#163080); -#163080 = CARTESIAN_POINT('',(2.115,0.298978581017,2.290944451524)); -#163081 = VERTEX_POINT('',#163082); -#163082 = CARTESIAN_POINT('',(1.695,0.298978581017,2.290944451524)); -#163083 = SURFACE_CURVE('',#163084,(#163088,#163094),.PCURVE_S1.); -#163084 = LINE('',#163085,#163086); -#163085 = CARTESIAN_POINT('',(1.905,0.298978581017,2.290944451524)); -#163086 = VECTOR('',#163087,1.); -#163087 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163088 = PCURVE('',#163021,#163089); -#163089 = DEFINITIONAL_REPRESENTATION('',(#163090),#163093); -#163090 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163091,#163092), +#165420 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165421 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165423 = ORIENTED_EDGE('',*,*,#165424,.F.); +#165424 = EDGE_CURVE('',#165320,#165396,#165425,.T.); +#165425 = SURFACE_CURVE('',#165426,(#165430,#165437),.PCURVE_S1.); +#165426 = LINE('',#165427,#165428); +#165427 = CARTESIAN_POINT('',(2.115,1.507511769892E-004,2.994243044813) + ); +#165428 = VECTOR('',#165429,1.); +#165429 = DIRECTION('',(0.E+000,5.233595624294E-002,-0.998629534755)); +#165430 = PCURVE('',#165337,#165431); +#165431 = DEFINITIONAL_REPRESENTATION('',(#165432),#165436); +#165432 = LINE('',#165433,#165434); +#165433 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#165434 = VECTOR('',#165435,1.); +#165435 = DIRECTION('',(1.,0.E+000)); +#165436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165437 = PCURVE('',#165145,#165438); +#165438 = DEFINITIONAL_REPRESENTATION('',(#165439),#165443); +#165439 = LINE('',#165440,#165441); +#165440 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#165441 = VECTOR('',#165442,1.); +#165442 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#165443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165444 = ORIENTED_EDGE('',*,*,#165319,.T.); +#165445 = ORIENTED_EDGE('',*,*,#165446,.F.); +#165446 = EDGE_CURVE('',#165398,#165322,#165447,.T.); +#165447 = SURFACE_CURVE('',#165448,(#165452,#165459),.PCURVE_S1.); +#165448 = LINE('',#165449,#165450); +#165449 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,2.591449450184) + ); +#165450 = VECTOR('',#165451,1.); +#165451 = DIRECTION('',(0.E+000,-5.233595624294E-002,0.998629534755)); +#165452 = PCURVE('',#165337,#165453); +#165453 = DEFINITIONAL_REPRESENTATION('',(#165454),#165458); +#165454 = LINE('',#165455,#165456); +#165455 = CARTESIAN_POINT('',(-4.445700619653E-016,-0.21)); +#165456 = VECTOR('',#165457,1.); +#165457 = DIRECTION('',(-1.,0.E+000)); +#165458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165459 = PCURVE('',#165092,#165460); +#165460 = DEFINITIONAL_REPRESENTATION('',(#165461),#165465); +#165461 = LINE('',#165462,#165463); +#165462 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#165463 = VECTOR('',#165464,1.); +#165464 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#165465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165466 = ADVANCED_FACE('',(#165467),#165413,.T.); +#165467 = FACE_BOUND('',#165468,.T.); +#165468 = EDGE_LOOP('',(#165469,#165498,#165519,#165520)); +#165469 = ORIENTED_EDGE('',*,*,#165470,.F.); +#165470 = EDGE_CURVE('',#165471,#165473,#165475,.T.); +#165471 = VERTEX_POINT('',#165472); +#165472 = CARTESIAN_POINT('',(2.115,0.298978581017,2.290944451524)); +#165473 = VERTEX_POINT('',#165474); +#165474 = CARTESIAN_POINT('',(1.695,0.298978581017,2.290944451524)); +#165475 = SURFACE_CURVE('',#165476,(#165480,#165486),.PCURVE_S1.); +#165476 = LINE('',#165477,#165478); +#165477 = CARTESIAN_POINT('',(1.905,0.298978581017,2.290944451524)); +#165478 = VECTOR('',#165479,1.); +#165479 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165480 = PCURVE('',#165413,#165481); +#165481 = DEFINITIONAL_REPRESENTATION('',(#165482),#165485); +#165482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165483,#165484), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163091 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163092 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163094 = PCURVE('',#163095,#163100); -#163095 = PLANE('',#163096); -#163096 = AXIS2_PLACEMENT_3D('',#163097,#163098,#163099); -#163097 = CARTESIAN_POINT('',(1.905,0.678075980964,2.240944451524)); -#163098 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); -#163099 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#163100 = DEFINITIONAL_REPRESENTATION('',(#163101),#163105); -#163101 = LINE('',#163102,#163103); -#163102 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#163103 = VECTOR('',#163104,1.); -#163104 = DIRECTION('',(0.E+000,-1.)); -#163105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163106 = ORIENTED_EDGE('',*,*,#163107,.F.); -#163107 = EDGE_CURVE('',#163004,#163079,#163108,.T.); -#163108 = SURFACE_CURVE('',#163109,(#163114,#163120),.PCURVE_S1.); -#163109 = CIRCLE('',#163110,0.32); -#163110 = AXIS2_PLACEMENT_3D('',#163111,#163112,#163113); -#163111 = CARTESIAN_POINT('',(2.115,0.340821720102,2.608196956182)); -#163112 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163113 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); -#163114 = PCURVE('',#163021,#163115); -#163115 = DEFINITIONAL_REPRESENTATION('',(#163116),#163119); -#163116 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163117,#163118), +#165483 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165484 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165486 = PCURVE('',#165487,#165492); +#165487 = PLANE('',#165488); +#165488 = AXIS2_PLACEMENT_3D('',#165489,#165490,#165491); +#165489 = CARTESIAN_POINT('',(1.905,0.678075980964,2.240944451524)); +#165490 = DIRECTION('',(0.E+000,-0.130759809642,-0.991414077055)); +#165491 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#165492 = DEFINITIONAL_REPRESENTATION('',(#165493),#165497); +#165493 = LINE('',#165494,#165495); +#165494 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#165495 = VECTOR('',#165496,1.); +#165496 = DIRECTION('',(0.E+000,-1.)); +#165497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165498 = ORIENTED_EDGE('',*,*,#165499,.F.); +#165499 = EDGE_CURVE('',#165396,#165471,#165500,.T.); +#165500 = SURFACE_CURVE('',#165501,(#165506,#165512),.PCURVE_S1.); +#165501 = CIRCLE('',#165502,0.32); +#165502 = AXIS2_PLACEMENT_3D('',#165503,#165504,#165505); +#165503 = CARTESIAN_POINT('',(2.115,0.340821720102,2.608196956182)); +#165504 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165505 = DIRECTION('',(0.E+000,1.694065894509E-015,1.)); +#165506 = PCURVE('',#165413,#165507); +#165507 = DEFINITIONAL_REPRESENTATION('',(#165508),#165511); +#165508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165509,#165510), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#163117 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163118 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163120 = PCURVE('',#162753,#163121); -#163121 = DEFINITIONAL_REPRESENTATION('',(#163122),#163126); -#163122 = CIRCLE('',#163123,0.32); -#163123 = AXIS2_PLACEMENT_2D('',#163124,#163125); -#163124 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#163125 = DIRECTION('',(-1.,1.694065894509E-015)); -#163126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163127 = ORIENTED_EDGE('',*,*,#163003,.T.); -#163128 = ORIENTED_EDGE('',*,*,#163129,.F.); -#163129 = EDGE_CURVE('',#163081,#163006,#163130,.T.); -#163130 = SURFACE_CURVE('',#163131,(#163136,#163142),.PCURVE_S1.); -#163131 = CIRCLE('',#163132,0.32); -#163132 = AXIS2_PLACEMENT_3D('',#163133,#163134,#163135); -#163133 = CARTESIAN_POINT('',(1.695,0.340821720102,2.608196956182)); -#163134 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163135 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163136 = PCURVE('',#163021,#163137); -#163137 = DEFINITIONAL_REPRESENTATION('',(#163138),#163141); -#163138 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163139,#163140), +#165509 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165510 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165512 = PCURVE('',#165145,#165513); +#165513 = DEFINITIONAL_REPRESENTATION('',(#165514),#165518); +#165514 = CIRCLE('',#165515,0.32); +#165515 = AXIS2_PLACEMENT_2D('',#165516,#165517); +#165516 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#165517 = DIRECTION('',(-1.,1.694065894509E-015)); +#165518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165519 = ORIENTED_EDGE('',*,*,#165395,.T.); +#165520 = ORIENTED_EDGE('',*,*,#165521,.F.); +#165521 = EDGE_CURVE('',#165473,#165398,#165522,.T.); +#165522 = SURFACE_CURVE('',#165523,(#165528,#165534),.PCURVE_S1.); +#165523 = CIRCLE('',#165524,0.32); +#165524 = AXIS2_PLACEMENT_3D('',#165525,#165526,#165527); +#165525 = CARTESIAN_POINT('',(1.695,0.340821720102,2.608196956182)); +#165526 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165527 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165528 = PCURVE('',#165413,#165529); +#165529 = DEFINITIONAL_REPRESENTATION('',(#165530),#165533); +#165530 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165531,#165532), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#163139 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163140 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163142 = PCURVE('',#162700,#163143); -#163143 = DEFINITIONAL_REPRESENTATION('',(#163144),#163148); -#163144 = CIRCLE('',#163145,0.32); -#163145 = AXIS2_PLACEMENT_2D('',#163146,#163147); -#163146 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#163147 = DIRECTION('',(1.,0.E+000)); -#163148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163149 = ADVANCED_FACE('',(#163150),#163095,.T.); -#163150 = FACE_BOUND('',#163151,.T.); -#163151 = EDGE_LOOP('',(#163152,#163181,#163202,#163203)); -#163152 = ORIENTED_EDGE('',*,*,#163153,.T.); -#163153 = EDGE_CURVE('',#163154,#163156,#163158,.T.); -#163154 = VERTEX_POINT('',#163155); -#163155 = CARTESIAN_POINT('',(1.695,0.678075980964,2.240944451524)); -#163156 = VERTEX_POINT('',#163157); -#163157 = CARTESIAN_POINT('',(2.115,0.678075980964,2.240944451524)); -#163158 = SURFACE_CURVE('',#163159,(#163163,#163170),.PCURVE_S1.); -#163159 = LINE('',#163160,#163161); -#163160 = CARTESIAN_POINT('',(1.905,0.678075980964,2.240944451524)); -#163161 = VECTOR('',#163162,1.); -#163162 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163163 = PCURVE('',#163095,#163164); -#163164 = DEFINITIONAL_REPRESENTATION('',(#163165),#163169); -#163165 = LINE('',#163166,#163167); -#163166 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#163167 = VECTOR('',#163168,1.); -#163168 = DIRECTION('',(0.E+000,1.)); -#163169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163170 = PCURVE('',#163171,#163176); -#163171 = CYLINDRICAL_SURFACE('',#163172,1.E-001); -#163172 = AXIS2_PLACEMENT_3D('',#163173,#163174,#163175); -#163173 = CARTESIAN_POINT('',(1.905,0.665,2.141803043818)); -#163174 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163175 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163176 = DEFINITIONAL_REPRESENTATION('',(#163177),#163180); -#163177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163178,#163179), +#165531 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165532 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165534 = PCURVE('',#165092,#165535); +#165535 = DEFINITIONAL_REPRESENTATION('',(#165536),#165540); +#165536 = CIRCLE('',#165537,0.32); +#165537 = AXIS2_PLACEMENT_2D('',#165538,#165539); +#165538 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#165539 = DIRECTION('',(1.,0.E+000)); +#165540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165541 = ADVANCED_FACE('',(#165542),#165487,.T.); +#165542 = FACE_BOUND('',#165543,.T.); +#165543 = EDGE_LOOP('',(#165544,#165573,#165594,#165595)); +#165544 = ORIENTED_EDGE('',*,*,#165545,.T.); +#165545 = EDGE_CURVE('',#165546,#165548,#165550,.T.); +#165546 = VERTEX_POINT('',#165547); +#165547 = CARTESIAN_POINT('',(1.695,0.678075980964,2.240944451524)); +#165548 = VERTEX_POINT('',#165549); +#165549 = CARTESIAN_POINT('',(2.115,0.678075980964,2.240944451524)); +#165550 = SURFACE_CURVE('',#165551,(#165555,#165562),.PCURVE_S1.); +#165551 = LINE('',#165552,#165553); +#165552 = CARTESIAN_POINT('',(1.905,0.678075980964,2.240944451524)); +#165553 = VECTOR('',#165554,1.); +#165554 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165555 = PCURVE('',#165487,#165556); +#165556 = DEFINITIONAL_REPRESENTATION('',(#165557),#165561); +#165557 = LINE('',#165558,#165559); +#165558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#165559 = VECTOR('',#165560,1.); +#165560 = DIRECTION('',(0.E+000,1.)); +#165561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165562 = PCURVE('',#165563,#165568); +#165563 = CYLINDRICAL_SURFACE('',#165564,1.E-001); +#165564 = AXIS2_PLACEMENT_3D('',#165565,#165566,#165567); +#165565 = CARTESIAN_POINT('',(1.905,0.665,2.141803043818)); +#165566 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165567 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165568 = DEFINITIONAL_REPRESENTATION('',(#165569),#165572); +#165569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165570,#165571), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163178 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#163179 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#163180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163181 = ORIENTED_EDGE('',*,*,#163182,.F.); -#163182 = EDGE_CURVE('',#163079,#163156,#163183,.T.); -#163183 = SURFACE_CURVE('',#163184,(#163188,#163195),.PCURVE_S1.); -#163184 = LINE('',#163185,#163186); -#163185 = CARTESIAN_POINT('',(2.115,0.298978581017,2.290944451524)); -#163186 = VECTOR('',#163187,1.); -#163187 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); -#163188 = PCURVE('',#163095,#163189); -#163189 = DEFINITIONAL_REPRESENTATION('',(#163190),#163194); -#163190 = LINE('',#163191,#163192); -#163191 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#163192 = VECTOR('',#163193,1.); -#163193 = DIRECTION('',(1.,0.E+000)); -#163194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163195 = PCURVE('',#162753,#163196); -#163196 = DEFINITIONAL_REPRESENTATION('',(#163197),#163201); -#163197 = LINE('',#163198,#163199); -#163198 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#163199 = VECTOR('',#163200,1.); -#163200 = DIRECTION('',(0.130759809642,0.991414077055)); -#163201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163202 = ORIENTED_EDGE('',*,*,#163078,.T.); -#163203 = ORIENTED_EDGE('',*,*,#163204,.F.); -#163204 = EDGE_CURVE('',#163154,#163081,#163205,.T.); -#163205 = SURFACE_CURVE('',#163206,(#163210,#163217),.PCURVE_S1.); -#163206 = LINE('',#163207,#163208); -#163207 = CARTESIAN_POINT('',(1.695,0.678075980964,2.240944451524)); -#163208 = VECTOR('',#163209,1.); -#163209 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); -#163210 = PCURVE('',#163095,#163211); -#163211 = DEFINITIONAL_REPRESENTATION('',(#163212),#163216); -#163212 = LINE('',#163213,#163214); -#163213 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#163214 = VECTOR('',#163215,1.); -#163215 = DIRECTION('',(-1.,0.E+000)); -#163216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163217 = PCURVE('',#162700,#163218); -#163218 = DEFINITIONAL_REPRESENTATION('',(#163219),#163223); -#163219 = LINE('',#163220,#163221); -#163220 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#163221 = VECTOR('',#163222,1.); -#163222 = DIRECTION('',(0.130759809642,-0.991414077055)); -#163223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163224 = ADVANCED_FACE('',(#163225),#163171,.F.); -#163225 = FACE_BOUND('',#163226,.F.); -#163226 = EDGE_LOOP('',(#163227,#163254,#163255,#163282)); -#163227 = ORIENTED_EDGE('',*,*,#163228,.T.); -#163228 = EDGE_CURVE('',#163229,#163154,#163231,.T.); -#163229 = VERTEX_POINT('',#163230); -#163230 = CARTESIAN_POINT('',(1.695,0.765,2.141803043818)); -#163231 = SURFACE_CURVE('',#163232,(#163237,#163243),.PCURVE_S1.); -#163232 = CIRCLE('',#163233,1.E-001); -#163233 = AXIS2_PLACEMENT_3D('',#163234,#163235,#163236); -#163234 = CARTESIAN_POINT('',(1.695,0.665,2.141803043818)); -#163235 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163236 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163237 = PCURVE('',#163171,#163238); -#163238 = DEFINITIONAL_REPRESENTATION('',(#163239),#163242); -#163239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163240,#163241), +#165570 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#165571 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#165572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165573 = ORIENTED_EDGE('',*,*,#165574,.F.); +#165574 = EDGE_CURVE('',#165471,#165548,#165575,.T.); +#165575 = SURFACE_CURVE('',#165576,(#165580,#165587),.PCURVE_S1.); +#165576 = LINE('',#165577,#165578); +#165577 = CARTESIAN_POINT('',(2.115,0.298978581017,2.290944451524)); +#165578 = VECTOR('',#165579,1.); +#165579 = DIRECTION('',(0.E+000,0.991414077055,-0.130759809642)); +#165580 = PCURVE('',#165487,#165581); +#165581 = DEFINITIONAL_REPRESENTATION('',(#165582),#165586); +#165582 = LINE('',#165583,#165584); +#165583 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#165584 = VECTOR('',#165585,1.); +#165585 = DIRECTION('',(1.,0.E+000)); +#165586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165587 = PCURVE('',#165145,#165588); +#165588 = DEFINITIONAL_REPRESENTATION('',(#165589),#165593); +#165589 = LINE('',#165590,#165591); +#165590 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#165591 = VECTOR('',#165592,1.); +#165592 = DIRECTION('',(0.130759809642,0.991414077055)); +#165593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165594 = ORIENTED_EDGE('',*,*,#165470,.T.); +#165595 = ORIENTED_EDGE('',*,*,#165596,.F.); +#165596 = EDGE_CURVE('',#165546,#165473,#165597,.T.); +#165597 = SURFACE_CURVE('',#165598,(#165602,#165609),.PCURVE_S1.); +#165598 = LINE('',#165599,#165600); +#165599 = CARTESIAN_POINT('',(1.695,0.678075980964,2.240944451524)); +#165600 = VECTOR('',#165601,1.); +#165601 = DIRECTION('',(0.E+000,-0.991414077055,0.130759809642)); +#165602 = PCURVE('',#165487,#165603); +#165603 = DEFINITIONAL_REPRESENTATION('',(#165604),#165608); +#165604 = LINE('',#165605,#165606); +#165605 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#165606 = VECTOR('',#165607,1.); +#165607 = DIRECTION('',(-1.,0.E+000)); +#165608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165609 = PCURVE('',#165092,#165610); +#165610 = DEFINITIONAL_REPRESENTATION('',(#165611),#165615); +#165611 = LINE('',#165612,#165613); +#165612 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#165613 = VECTOR('',#165614,1.); +#165614 = DIRECTION('',(0.130759809642,-0.991414077055)); +#165615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165616 = ADVANCED_FACE('',(#165617),#165563,.F.); +#165617 = FACE_BOUND('',#165618,.F.); +#165618 = EDGE_LOOP('',(#165619,#165646,#165647,#165674)); +#165619 = ORIENTED_EDGE('',*,*,#165620,.T.); +#165620 = EDGE_CURVE('',#165621,#165546,#165623,.T.); +#165621 = VERTEX_POINT('',#165622); +#165622 = CARTESIAN_POINT('',(1.695,0.765,2.141803043818)); +#165623 = SURFACE_CURVE('',#165624,(#165629,#165635),.PCURVE_S1.); +#165624 = CIRCLE('',#165625,1.E-001); +#165625 = AXIS2_PLACEMENT_3D('',#165626,#165627,#165628); +#165626 = CARTESIAN_POINT('',(1.695,0.665,2.141803043818)); +#165627 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165628 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165629 = PCURVE('',#165563,#165630); +#165630 = DEFINITIONAL_REPRESENTATION('',(#165631),#165634); +#165631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165632,#165633), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#163240 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#163241 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#163242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165632 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#165633 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#165634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163243 = PCURVE('',#162700,#163244); -#163244 = DEFINITIONAL_REPRESENTATION('',(#163245),#163253); -#163245 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163246,#163247,#163248, - #163249,#163250,#163251,#163252),.UNSPECIFIED.,.T.,.F.) +#165635 = PCURVE('',#165092,#165636); +#165636 = DEFINITIONAL_REPRESENTATION('',(#165637),#165645); +#165637 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165638,#165639,#165640, + #165641,#165642,#165643,#165644),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163246 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#163247 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#163248 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#163249 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#163250 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#163251 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#163252 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#163253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163254 = ORIENTED_EDGE('',*,*,#163153,.T.); -#163255 = ORIENTED_EDGE('',*,*,#163256,.T.); -#163256 = EDGE_CURVE('',#163156,#163257,#163259,.T.); -#163257 = VERTEX_POINT('',#163258); -#163258 = CARTESIAN_POINT('',(2.115,0.765,2.141803043818)); -#163259 = SURFACE_CURVE('',#163260,(#163265,#163271),.PCURVE_S1.); -#163260 = CIRCLE('',#163261,1.E-001); -#163261 = AXIS2_PLACEMENT_3D('',#163262,#163263,#163264); -#163262 = CARTESIAN_POINT('',(2.115,0.665,2.141803043818)); -#163263 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163264 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); -#163265 = PCURVE('',#163171,#163266); -#163266 = DEFINITIONAL_REPRESENTATION('',(#163267),#163270); -#163267 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163268,#163269), +#165638 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#165639 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#165640 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#165641 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#165642 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#165643 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#165644 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#165645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165646 = ORIENTED_EDGE('',*,*,#165545,.T.); +#165647 = ORIENTED_EDGE('',*,*,#165648,.T.); +#165648 = EDGE_CURVE('',#165548,#165649,#165651,.T.); +#165649 = VERTEX_POINT('',#165650); +#165650 = CARTESIAN_POINT('',(2.115,0.765,2.141803043818)); +#165651 = SURFACE_CURVE('',#165652,(#165657,#165663),.PCURVE_S1.); +#165652 = CIRCLE('',#165653,1.E-001); +#165653 = AXIS2_PLACEMENT_3D('',#165654,#165655,#165656); +#165654 = CARTESIAN_POINT('',(2.115,0.665,2.141803043818)); +#165655 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165656 = DIRECTION('',(0.E+000,-2.168404344971E-015,-1.)); +#165657 = PCURVE('',#165563,#165658); +#165658 = DEFINITIONAL_REPRESENTATION('',(#165659),#165662); +#165659 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165660,#165661), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#163268 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#163269 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#163270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165660 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#165661 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#165662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163271 = PCURVE('',#162753,#163272); -#163272 = DEFINITIONAL_REPRESENTATION('',(#163273),#163281); -#163273 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163274,#163275,#163276, - #163277,#163278,#163279,#163280),.UNSPECIFIED.,.T.,.F.) +#165663 = PCURVE('',#165145,#165664); +#165664 = DEFINITIONAL_REPRESENTATION('',(#165665),#165673); +#165665 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165666,#165667,#165668, + #165669,#165670,#165671,#165672),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163274 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#163275 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#163276 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#163277 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#163278 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#163279 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#163280 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#163281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163282 = ORIENTED_EDGE('',*,*,#163283,.T.); -#163283 = EDGE_CURVE('',#163257,#163229,#163284,.T.); -#163284 = SURFACE_CURVE('',#163285,(#163289,#163295),.PCURVE_S1.); -#163285 = LINE('',#163286,#163287); -#163286 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); -#163287 = VECTOR('',#163288,1.); -#163288 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163289 = PCURVE('',#163171,#163290); -#163290 = DEFINITIONAL_REPRESENTATION('',(#163291),#163294); -#163291 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163292,#163293), +#165666 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#165667 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#165668 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#165669 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#165670 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#165671 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#165672 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#165673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165674 = ORIENTED_EDGE('',*,*,#165675,.T.); +#165675 = EDGE_CURVE('',#165649,#165621,#165676,.T.); +#165676 = SURFACE_CURVE('',#165677,(#165681,#165687),.PCURVE_S1.); +#165677 = LINE('',#165678,#165679); +#165678 = CARTESIAN_POINT('',(0.635,0.765,2.141803043818)); +#165679 = VECTOR('',#165680,1.); +#165680 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165681 = PCURVE('',#165563,#165682); +#165682 = DEFINITIONAL_REPRESENTATION('',(#165683),#165686); +#165683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165684,#165685), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.48,-1.06),.PIECEWISE_BEZIER_KNOTS.); -#163292 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#163293 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#163294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163295 = PCURVE('',#159360,#163296); -#163296 = DEFINITIONAL_REPRESENTATION('',(#163297),#163301); -#163297 = LINE('',#163298,#163299); -#163298 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#163299 = VECTOR('',#163300,1.); -#163300 = DIRECTION('',(0.E+000,-1.)); -#163301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163302 = ADVANCED_FACE('',(#163303),#163317,.T.); -#163303 = FACE_BOUND('',#163304,.T.); -#163304 = EDGE_LOOP('',(#163305,#163339,#163362,#163389)); -#163305 = ORIENTED_EDGE('',*,*,#163306,.F.); -#163306 = EDGE_CURVE('',#163307,#163309,#163311,.T.); -#163307 = VERTEX_POINT('',#163308); -#163308 = CARTESIAN_POINT('',(2.115,0.706843139085,-2.459055548476)); -#163309 = VERTEX_POINT('',#163310); -#163310 = CARTESIAN_POINT('',(1.695,0.706843139085,-2.459055548476)); -#163311 = SURFACE_CURVE('',#163312,(#163316,#163328),.PCURVE_S1.); -#163312 = LINE('',#163313,#163314); -#163313 = CARTESIAN_POINT('',(1.905,0.706843139085,-2.459055548476)); -#163314 = VECTOR('',#163315,1.); -#163315 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163316 = PCURVE('',#163317,#163322); -#163317 = PLANE('',#163318); -#163318 = AXIS2_PLACEMENT_3D('',#163319,#163320,#163321); -#163319 = CARTESIAN_POINT('',(1.905,0.706843139085,-2.459055548476)); -#163320 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); -#163321 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#163322 = DEFINITIONAL_REPRESENTATION('',(#163323),#163327); -#163323 = LINE('',#163324,#163325); -#163324 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#163325 = VECTOR('',#163326,1.); -#163326 = DIRECTION('',(0.E+000,-1.)); -#163327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163328 = PCURVE('',#163329,#163334); -#163329 = CYLINDRICAL_SURFACE('',#163330,0.32); -#163330 = AXIS2_PLACEMENT_3D('',#163331,#163332,#163333); -#163331 = CARTESIAN_POINT('',(1.905,0.665,-2.141803043818)); -#163332 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163333 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163334 = DEFINITIONAL_REPRESENTATION('',(#163335),#163338); -#163335 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163336,#163337), +#165684 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#165685 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#165686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165687 = PCURVE('',#161752,#165688); +#165688 = DEFINITIONAL_REPRESENTATION('',(#165689),#165693); +#165689 = LINE('',#165690,#165691); +#165690 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#165691 = VECTOR('',#165692,1.); +#165692 = DIRECTION('',(0.E+000,-1.)); +#165693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165694 = ADVANCED_FACE('',(#165695),#165709,.T.); +#165695 = FACE_BOUND('',#165696,.T.); +#165696 = EDGE_LOOP('',(#165697,#165731,#165754,#165781)); +#165697 = ORIENTED_EDGE('',*,*,#165698,.F.); +#165698 = EDGE_CURVE('',#165699,#165701,#165703,.T.); +#165699 = VERTEX_POINT('',#165700); +#165700 = CARTESIAN_POINT('',(2.115,0.706843139085,-2.459055548476)); +#165701 = VERTEX_POINT('',#165702); +#165702 = CARTESIAN_POINT('',(1.695,0.706843139085,-2.459055548476)); +#165703 = SURFACE_CURVE('',#165704,(#165708,#165720),.PCURVE_S1.); +#165704 = LINE('',#165705,#165706); +#165705 = CARTESIAN_POINT('',(1.905,0.706843139085,-2.459055548476)); +#165706 = VECTOR('',#165707,1.); +#165707 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165708 = PCURVE('',#165709,#165714); +#165709 = PLANE('',#165710); +#165710 = AXIS2_PLACEMENT_3D('',#165711,#165712,#165713); +#165711 = CARTESIAN_POINT('',(1.905,0.706843139085,-2.459055548476)); +#165712 = DIRECTION('',(0.E+000,0.130759809642,-0.991414077055)); +#165713 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#165714 = DEFINITIONAL_REPRESENTATION('',(#165715),#165719); +#165715 = LINE('',#165716,#165717); +#165716 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#165717 = VECTOR('',#165718,1.); +#165718 = DIRECTION('',(0.E+000,-1.)); +#165719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165720 = PCURVE('',#165721,#165726); +#165721 = CYLINDRICAL_SURFACE('',#165722,0.32); +#165722 = AXIS2_PLACEMENT_3D('',#165723,#165724,#165725); +#165723 = CARTESIAN_POINT('',(1.905,0.665,-2.141803043818)); +#165724 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165725 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165726 = DEFINITIONAL_REPRESENTATION('',(#165727),#165730); +#165727 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165728,#165729), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163336 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#163337 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#163338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163339 = ORIENTED_EDGE('',*,*,#163340,.F.); -#163340 = EDGE_CURVE('',#163341,#163307,#163343,.T.); -#163341 = VERTEX_POINT('',#163342); -#163342 = CARTESIAN_POINT('',(2.115,0.327745739138,-2.509055548476)); -#163343 = SURFACE_CURVE('',#163344,(#163348,#163355),.PCURVE_S1.); -#163344 = LINE('',#163345,#163346); -#163345 = CARTESIAN_POINT('',(2.115,0.327745739138,-2.509055548476)); -#163346 = VECTOR('',#163347,1.); -#163347 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#163348 = PCURVE('',#163317,#163349); -#163349 = DEFINITIONAL_REPRESENTATION('',(#163350),#163354); -#163350 = LINE('',#163351,#163352); -#163351 = CARTESIAN_POINT('',(-0.382380489365,0.21)); -#163352 = VECTOR('',#163353,1.); -#163353 = DIRECTION('',(1.,0.E+000)); -#163354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163355 = PCURVE('',#162753,#163356); -#163356 = DEFINITIONAL_REPRESENTATION('',(#163357),#163361); -#163357 = LINE('',#163358,#163359); -#163358 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); -#163359 = VECTOR('',#163360,1.); -#163360 = DIRECTION('',(-0.130759809642,0.991414077055)); -#163361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163362 = ORIENTED_EDGE('',*,*,#163363,.T.); -#163363 = EDGE_CURVE('',#163341,#163364,#163366,.T.); -#163364 = VERTEX_POINT('',#163365); -#163365 = CARTESIAN_POINT('',(1.695,0.327745739138,-2.509055548476)); -#163366 = SURFACE_CURVE('',#163367,(#163371,#163378),.PCURVE_S1.); -#163367 = LINE('',#163368,#163369); -#163368 = CARTESIAN_POINT('',(1.905,0.327745739138,-2.509055548476)); -#163369 = VECTOR('',#163370,1.); -#163370 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163371 = PCURVE('',#163317,#163372); -#163372 = DEFINITIONAL_REPRESENTATION('',(#163373),#163377); -#163373 = LINE('',#163374,#163375); -#163374 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); -#163375 = VECTOR('',#163376,1.); -#163376 = DIRECTION('',(0.E+000,-1.)); -#163377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163378 = PCURVE('',#163379,#163384); -#163379 = CYLINDRICAL_SURFACE('',#163380,9.999999999999E-002); -#163380 = AXIS2_PLACEMENT_3D('',#163381,#163382,#163383); -#163381 = CARTESIAN_POINT('',(1.905,0.340821720102,-2.608196956182)); -#163382 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163383 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163384 = DEFINITIONAL_REPRESENTATION('',(#163385),#163388); -#163385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163386,#163387), +#165728 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#165729 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#165730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165731 = ORIENTED_EDGE('',*,*,#165732,.F.); +#165732 = EDGE_CURVE('',#165733,#165699,#165735,.T.); +#165733 = VERTEX_POINT('',#165734); +#165734 = CARTESIAN_POINT('',(2.115,0.327745739138,-2.509055548476)); +#165735 = SURFACE_CURVE('',#165736,(#165740,#165747),.PCURVE_S1.); +#165736 = LINE('',#165737,#165738); +#165737 = CARTESIAN_POINT('',(2.115,0.327745739138,-2.509055548476)); +#165738 = VECTOR('',#165739,1.); +#165739 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#165740 = PCURVE('',#165709,#165741); +#165741 = DEFINITIONAL_REPRESENTATION('',(#165742),#165746); +#165742 = LINE('',#165743,#165744); +#165743 = CARTESIAN_POINT('',(-0.382380489365,0.21)); +#165744 = VECTOR('',#165745,1.); +#165745 = DIRECTION('',(1.,0.E+000)); +#165746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165747 = PCURVE('',#165145,#165748); +#165748 = DEFINITIONAL_REPRESENTATION('',(#165749),#165753); +#165749 = LINE('',#165750,#165751); +#165750 = CARTESIAN_POINT('',(2.509055548476,-0.547254260862)); +#165751 = VECTOR('',#165752,1.); +#165752 = DIRECTION('',(-0.130759809642,0.991414077055)); +#165753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165754 = ORIENTED_EDGE('',*,*,#165755,.T.); +#165755 = EDGE_CURVE('',#165733,#165756,#165758,.T.); +#165756 = VERTEX_POINT('',#165757); +#165757 = CARTESIAN_POINT('',(1.695,0.327745739138,-2.509055548476)); +#165758 = SURFACE_CURVE('',#165759,(#165763,#165770),.PCURVE_S1.); +#165759 = LINE('',#165760,#165761); +#165760 = CARTESIAN_POINT('',(1.905,0.327745739138,-2.509055548476)); +#165761 = VECTOR('',#165762,1.); +#165762 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165763 = PCURVE('',#165709,#165764); +#165764 = DEFINITIONAL_REPRESENTATION('',(#165765),#165769); +#165765 = LINE('',#165766,#165767); +#165766 = CARTESIAN_POINT('',(-0.382380489365,0.E+000)); +#165767 = VECTOR('',#165768,1.); +#165768 = DIRECTION('',(0.E+000,-1.)); +#165769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165770 = PCURVE('',#165771,#165776); +#165771 = CYLINDRICAL_SURFACE('',#165772,9.999999999999E-002); +#165772 = AXIS2_PLACEMENT_3D('',#165773,#165774,#165775); +#165773 = CARTESIAN_POINT('',(1.905,0.340821720102,-2.608196956182)); +#165774 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165775 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165776 = DEFINITIONAL_REPRESENTATION('',(#165777),#165780); +#165777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165778,#165779), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163386 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163387 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163389 = ORIENTED_EDGE('',*,*,#163390,.F.); -#163390 = EDGE_CURVE('',#163309,#163364,#163391,.T.); -#163391 = SURFACE_CURVE('',#163392,(#163396,#163403),.PCURVE_S1.); -#163392 = LINE('',#163393,#163394); -#163393 = CARTESIAN_POINT('',(1.695,0.706843139085,-2.459055548476)); -#163394 = VECTOR('',#163395,1.); -#163395 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#163396 = PCURVE('',#163317,#163397); -#163397 = DEFINITIONAL_REPRESENTATION('',(#163398),#163402); -#163398 = LINE('',#163399,#163400); -#163399 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#163400 = VECTOR('',#163401,1.); -#163401 = DIRECTION('',(-1.,0.E+000)); -#163402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163403 = PCURVE('',#163404,#163409); -#163404 = PLANE('',#163405); -#163405 = AXIS2_PLACEMENT_3D('',#163406,#163407,#163408); -#163406 = CARTESIAN_POINT('',(1.695,0.875,0.E+000)); -#163407 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163408 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163409 = DEFINITIONAL_REPRESENTATION('',(#163410),#163414); -#163410 = LINE('',#163411,#163412); -#163411 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); -#163412 = VECTOR('',#163413,1.); -#163413 = DIRECTION('',(-0.130759809642,-0.991414077055)); -#163414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163415 = ADVANCED_FACE('',(#163416),#163379,.F.); -#163416 = FACE_BOUND('',#163417,.F.); -#163417 = EDGE_LOOP('',(#163418,#163445,#163472,#163497)); -#163418 = ORIENTED_EDGE('',*,*,#163419,.T.); -#163419 = EDGE_CURVE('',#163364,#163420,#163422,.T.); -#163420 = VERTEX_POINT('',#163421); -#163421 = CARTESIAN_POINT('',(1.695,0.240958766627,-2.602963360557)); -#163422 = SURFACE_CURVE('',#163423,(#163428,#163434),.PCURVE_S1.); -#163423 = CIRCLE('',#163424,9.999999999999E-002); -#163424 = AXIS2_PLACEMENT_3D('',#163425,#163426,#163427); -#163425 = CARTESIAN_POINT('',(1.695,0.340821720102,-2.608196956182)); -#163426 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163427 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163428 = PCURVE('',#163379,#163429); -#163429 = DEFINITIONAL_REPRESENTATION('',(#163430),#163433); -#163430 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163431,#163432), +#165778 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165779 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165781 = ORIENTED_EDGE('',*,*,#165782,.F.); +#165782 = EDGE_CURVE('',#165701,#165756,#165783,.T.); +#165783 = SURFACE_CURVE('',#165784,(#165788,#165795),.PCURVE_S1.); +#165784 = LINE('',#165785,#165786); +#165785 = CARTESIAN_POINT('',(1.695,0.706843139085,-2.459055548476)); +#165786 = VECTOR('',#165787,1.); +#165787 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#165788 = PCURVE('',#165709,#165789); +#165789 = DEFINITIONAL_REPRESENTATION('',(#165790),#165794); +#165790 = LINE('',#165791,#165792); +#165791 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#165792 = VECTOR('',#165793,1.); +#165793 = DIRECTION('',(-1.,0.E+000)); +#165794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165795 = PCURVE('',#165796,#165801); +#165796 = PLANE('',#165797); +#165797 = AXIS2_PLACEMENT_3D('',#165798,#165799,#165800); +#165798 = CARTESIAN_POINT('',(1.695,0.875,0.E+000)); +#165799 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165800 = DIRECTION('',(0.E+000,0.E+000,1.)); +#165801 = DEFINITIONAL_REPRESENTATION('',(#165802),#165806); +#165802 = LINE('',#165803,#165804); +#165803 = CARTESIAN_POINT('',(-2.459055548476,-0.168156860915)); +#165804 = VECTOR('',#165805,1.); +#165805 = DIRECTION('',(-0.130759809642,-0.991414077055)); +#165806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165807 = ADVANCED_FACE('',(#165808),#165771,.F.); +#165808 = FACE_BOUND('',#165809,.F.); +#165809 = EDGE_LOOP('',(#165810,#165837,#165864,#165889)); +#165810 = ORIENTED_EDGE('',*,*,#165811,.T.); +#165811 = EDGE_CURVE('',#165756,#165812,#165814,.T.); +#165812 = VERTEX_POINT('',#165813); +#165813 = CARTESIAN_POINT('',(1.695,0.240958766627,-2.602963360557)); +#165814 = SURFACE_CURVE('',#165815,(#165820,#165826),.PCURVE_S1.); +#165815 = CIRCLE('',#165816,9.999999999999E-002); +#165816 = AXIS2_PLACEMENT_3D('',#165817,#165818,#165819); +#165817 = CARTESIAN_POINT('',(1.695,0.340821720102,-2.608196956182)); +#165818 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165819 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#165820 = PCURVE('',#165771,#165821); +#165821 = DEFINITIONAL_REPRESENTATION('',(#165822),#165825); +#165822 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165823,#165824), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#163431 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163432 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165823 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#165824 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163434 = PCURVE('',#163404,#163435); -#163435 = DEFINITIONAL_REPRESENTATION('',(#163436),#163444); -#163436 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163437,#163438,#163439, - #163440,#163441,#163442,#163443),.UNSPECIFIED.,.T.,.F.) +#165826 = PCURVE('',#165796,#165827); +#165827 = DEFINITIONAL_REPRESENTATION('',(#165828),#165836); +#165828 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165829,#165830,#165831, + #165832,#165833,#165834,#165835),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163437 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#163438 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); -#163439 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); -#163440 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); -#163441 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); -#163442 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); -#163443 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); -#163444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163445 = ORIENTED_EDGE('',*,*,#163446,.T.); -#163446 = EDGE_CURVE('',#163420,#163447,#163449,.T.); -#163447 = VERTEX_POINT('',#163448); -#163448 = CARTESIAN_POINT('',(2.115,0.240958766627,-2.602963360557)); -#163449 = SURFACE_CURVE('',#163450,(#163454,#163460),.PCURVE_S1.); -#163450 = LINE('',#163451,#163452); -#163451 = CARTESIAN_POINT('',(1.905,0.240958766627,-2.602963360557)); -#163452 = VECTOR('',#163453,1.); -#163453 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163454 = PCURVE('',#163379,#163455); -#163455 = DEFINITIONAL_REPRESENTATION('',(#163456),#163459); -#163456 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163457,#163458), +#165829 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#165830 = CARTESIAN_POINT('',(-2.708196956182,-0.360973199141)); +#165831 = CARTESIAN_POINT('',(-2.558196956182,-0.447575739519)); +#165832 = CARTESIAN_POINT('',(-2.408196956182,-0.534178279898)); +#165833 = CARTESIAN_POINT('',(-2.558196956182,-0.620780820276)); +#165834 = CARTESIAN_POINT('',(-2.708196956182,-0.707383360654)); +#165835 = CARTESIAN_POINT('',(-2.708196956182,-0.534178279898)); +#165836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165837 = ORIENTED_EDGE('',*,*,#165838,.T.); +#165838 = EDGE_CURVE('',#165812,#165839,#165841,.T.); +#165839 = VERTEX_POINT('',#165840); +#165840 = CARTESIAN_POINT('',(2.115,0.240958766627,-2.602963360557)); +#165841 = SURFACE_CURVE('',#165842,(#165846,#165852),.PCURVE_S1.); +#165842 = LINE('',#165843,#165844); +#165843 = CARTESIAN_POINT('',(1.905,0.240958766627,-2.602963360557)); +#165844 = VECTOR('',#165845,1.); +#165845 = DIRECTION('',(1.,0.E+000,0.E+000)); +#165846 = PCURVE('',#165771,#165847); +#165847 = DEFINITIONAL_REPRESENTATION('',(#165848),#165851); +#165848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165849,#165850), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163457 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163458 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163460 = PCURVE('',#163461,#163466); -#163461 = PLANE('',#163462); -#163462 = AXIS2_PLACEMENT_3D('',#163463,#163464,#163465); -#163463 = CARTESIAN_POINT('',(1.905,0.240958766627,-2.602963360557)); -#163464 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); -#163465 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#163466 = DEFINITIONAL_REPRESENTATION('',(#163467),#163471); -#163467 = LINE('',#163468,#163469); -#163468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#163469 = VECTOR('',#163470,1.); -#163470 = DIRECTION('',(0.E+000,1.)); -#163471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163472 = ORIENTED_EDGE('',*,*,#163473,.T.); -#163473 = EDGE_CURVE('',#163447,#163341,#163474,.T.); -#163474 = SURFACE_CURVE('',#163475,(#163480,#163486),.PCURVE_S1.); -#163475 = CIRCLE('',#163476,9.999999999999E-002); -#163476 = AXIS2_PLACEMENT_3D('',#163477,#163478,#163479); -#163477 = CARTESIAN_POINT('',(2.115,0.340821720102,-2.608196956182)); -#163478 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163479 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); -#163480 = PCURVE('',#163379,#163481); -#163481 = DEFINITIONAL_REPRESENTATION('',(#163482),#163485); -#163482 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163483,#163484), +#165849 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#165850 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165852 = PCURVE('',#165853,#165858); +#165853 = PLANE('',#165854); +#165854 = AXIS2_PLACEMENT_3D('',#165855,#165856,#165857); +#165855 = CARTESIAN_POINT('',(1.905,0.240958766627,-2.602963360557)); +#165856 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624294E-002)); +#165857 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#165858 = DEFINITIONAL_REPRESENTATION('',(#165859),#165863); +#165859 = LINE('',#165860,#165861); +#165860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#165861 = VECTOR('',#165862,1.); +#165862 = DIRECTION('',(0.E+000,1.)); +#165863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165864 = ORIENTED_EDGE('',*,*,#165865,.T.); +#165865 = EDGE_CURVE('',#165839,#165733,#165866,.T.); +#165866 = SURFACE_CURVE('',#165867,(#165872,#165878),.PCURVE_S1.); +#165867 = CIRCLE('',#165868,9.999999999999E-002); +#165868 = AXIS2_PLACEMENT_3D('',#165869,#165870,#165871); +#165869 = CARTESIAN_POINT('',(2.115,0.340821720102,-2.608196956182)); +#165870 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165871 = DIRECTION('',(0.E+000,1.084202172486E-015,-1.)); +#165872 = PCURVE('',#165771,#165873); +#165873 = DEFINITIONAL_REPRESENTATION('',(#165874),#165877); +#165874 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165875,#165876), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#163483 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163484 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#165875 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#165876 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#165877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163486 = PCURVE('',#162753,#163487); -#163487 = DEFINITIONAL_REPRESENTATION('',(#163488),#163496); -#163488 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163489,#163490,#163491, - #163492,#163493,#163494,#163495),.UNSPECIFIED.,.T.,.F.) +#165878 = PCURVE('',#165145,#165879); +#165879 = DEFINITIONAL_REPRESENTATION('',(#165880),#165888); +#165880 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165881,#165882,#165883, + #165884,#165885,#165886,#165887),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163489 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#163490 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); -#163491 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); -#163492 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); -#163493 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); -#163494 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); -#163495 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); -#163496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163497 = ORIENTED_EDGE('',*,*,#163363,.T.); -#163498 = ADVANCED_FACE('',(#163499),#163461,.T.); -#163499 = FACE_BOUND('',#163500,.T.); -#163500 = EDGE_LOOP('',(#163501,#163502,#163525,#163553)); -#163501 = ORIENTED_EDGE('',*,*,#163446,.T.); -#163502 = ORIENTED_EDGE('',*,*,#163503,.F.); -#163503 = EDGE_CURVE('',#163504,#163447,#163506,.T.); -#163504 = VERTEX_POINT('',#163505); -#163505 = CARTESIAN_POINT('',(2.115,0.219849248823,-3.005756955187)); -#163506 = SURFACE_CURVE('',#163507,(#163511,#163518),.PCURVE_S1.); -#163507 = LINE('',#163508,#163509); -#163508 = CARTESIAN_POINT('',(2.115,0.219849248823,-3.005756955187)); -#163509 = VECTOR('',#163510,1.); -#163510 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#163511 = PCURVE('',#163461,#163512); -#163512 = DEFINITIONAL_REPRESENTATION('',(#163513),#163517); -#163513 = LINE('',#163514,#163515); -#163514 = CARTESIAN_POINT('',(-0.403346366807,0.21)); -#163515 = VECTOR('',#163516,1.); -#163516 = DIRECTION('',(1.,0.E+000)); -#163517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163518 = PCURVE('',#162753,#163519); -#163519 = DEFINITIONAL_REPRESENTATION('',(#163520),#163524); -#163520 = LINE('',#163521,#163522); -#163521 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); -#163522 = VECTOR('',#163523,1.); -#163523 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); -#163524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163525 = ORIENTED_EDGE('',*,*,#163526,.T.); -#163526 = EDGE_CURVE('',#163504,#163527,#163529,.T.); -#163527 = VERTEX_POINT('',#163528); -#163528 = CARTESIAN_POINT('',(1.695,0.219849248823,-3.005756955187)); -#163529 = SURFACE_CURVE('',#163530,(#163534,#163541),.PCURVE_S1.); -#163530 = LINE('',#163531,#163532); -#163531 = CARTESIAN_POINT('',(1.905,0.219849248823,-3.005756955187)); -#163532 = VECTOR('',#163533,1.); -#163533 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163534 = PCURVE('',#163461,#163535); -#163535 = DEFINITIONAL_REPRESENTATION('',(#163536),#163540); -#163536 = LINE('',#163537,#163538); -#163537 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); -#163538 = VECTOR('',#163539,1.); -#163539 = DIRECTION('',(0.E+000,-1.)); -#163540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163541 = PCURVE('',#163542,#163547); -#163542 = PLANE('',#163543); -#163543 = AXIS2_PLACEMENT_3D('',#163544,#163545,#163546); -#163544 = CARTESIAN_POINT('',(1.905,0.11,-3.)); -#163545 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); -#163546 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#163547 = DEFINITIONAL_REPRESENTATION('',(#163548),#163552); -#163548 = LINE('',#163549,#163550); -#163549 = CARTESIAN_POINT('',(-0.11,0.E+000)); -#163550 = VECTOR('',#163551,1.); -#163551 = DIRECTION('',(0.E+000,-1.)); -#163552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163553 = ORIENTED_EDGE('',*,*,#163554,.F.); -#163554 = EDGE_CURVE('',#163420,#163527,#163555,.T.); -#163555 = SURFACE_CURVE('',#163556,(#163560,#163567),.PCURVE_S1.); -#163556 = LINE('',#163557,#163558); -#163557 = CARTESIAN_POINT('',(1.695,0.240958766627,-2.602963360557)); -#163558 = VECTOR('',#163559,1.); -#163559 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#163560 = PCURVE('',#163461,#163561); -#163561 = DEFINITIONAL_REPRESENTATION('',(#163562),#163566); -#163562 = LINE('',#163563,#163564); -#163563 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#163564 = VECTOR('',#163565,1.); -#163565 = DIRECTION('',(-1.,0.E+000)); -#163566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163567 = PCURVE('',#163404,#163568); -#163568 = DEFINITIONAL_REPRESENTATION('',(#163569),#163573); -#163569 = LINE('',#163570,#163571); -#163570 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); -#163571 = VECTOR('',#163572,1.); -#163572 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); -#163573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163574 = ADVANCED_FACE('',(#163575),#163542,.F.); -#163575 = FACE_BOUND('',#163576,.T.); -#163576 = EDGE_LOOP('',(#163577,#163600,#163601,#163624)); -#163577 = ORIENTED_EDGE('',*,*,#163578,.F.); -#163578 = EDGE_CURVE('',#163527,#163579,#163581,.T.); -#163579 = VERTEX_POINT('',#163580); -#163580 = CARTESIAN_POINT('',(1.695,1.507511769881E-004,-2.994243044813) - ); -#163581 = SURFACE_CURVE('',#163582,(#163586,#163593),.PCURVE_S1.); -#163582 = LINE('',#163583,#163584); -#163583 = CARTESIAN_POINT('',(1.695,0.219849248823,-3.005756955187)); -#163584 = VECTOR('',#163585,1.); -#163585 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); -#163586 = PCURVE('',#163542,#163587); -#163587 = DEFINITIONAL_REPRESENTATION('',(#163588),#163592); -#163588 = LINE('',#163589,#163590); -#163589 = CARTESIAN_POINT('',(-0.11,-0.21)); -#163590 = VECTOR('',#163591,1.); -#163591 = DIRECTION('',(1.,0.E+000)); -#163592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163593 = PCURVE('',#163404,#163594); -#163594 = DEFINITIONAL_REPRESENTATION('',(#163595),#163599); -#163595 = LINE('',#163596,#163597); -#163596 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); -#163597 = VECTOR('',#163598,1.); -#163598 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); -#163599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163600 = ORIENTED_EDGE('',*,*,#163526,.F.); -#163601 = ORIENTED_EDGE('',*,*,#163602,.F.); -#163602 = EDGE_CURVE('',#163603,#163504,#163605,.T.); -#163603 = VERTEX_POINT('',#163604); -#163604 = CARTESIAN_POINT('',(2.115,1.507511769881E-004,-2.994243044813) - ); -#163605 = SURFACE_CURVE('',#163606,(#163610,#163617),.PCURVE_S1.); -#163606 = LINE('',#163607,#163608); -#163607 = CARTESIAN_POINT('',(2.115,1.507511769892E-004,-2.994243044813) - ); -#163608 = VECTOR('',#163609,1.); -#163609 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); -#163610 = PCURVE('',#163542,#163611); -#163611 = DEFINITIONAL_REPRESENTATION('',(#163612),#163616); -#163612 = LINE('',#163613,#163614); -#163613 = CARTESIAN_POINT('',(0.11,0.21)); -#163614 = VECTOR('',#163615,1.); -#163615 = DIRECTION('',(-1.,0.E+000)); -#163616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163617 = PCURVE('',#162753,#163618); -#163618 = DEFINITIONAL_REPRESENTATION('',(#163619),#163623); -#163619 = LINE('',#163620,#163621); -#163620 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); -#163621 = VECTOR('',#163622,1.); -#163622 = DIRECTION('',(5.233595624291E-002,0.998629534755)); -#163623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163624 = ORIENTED_EDGE('',*,*,#163625,.F.); -#163625 = EDGE_CURVE('',#163579,#163603,#163626,.T.); -#163626 = SURFACE_CURVE('',#163627,(#163631,#163638),.PCURVE_S1.); -#163627 = LINE('',#163628,#163629); -#163628 = CARTESIAN_POINT('',(1.905,1.507511769861E-004,-2.994243044813) - ); -#163629 = VECTOR('',#163630,1.); -#163630 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163631 = PCURVE('',#163542,#163632); -#163632 = DEFINITIONAL_REPRESENTATION('',(#163633),#163637); -#163633 = LINE('',#163634,#163635); -#163634 = CARTESIAN_POINT('',(0.11,0.E+000)); -#163635 = VECTOR('',#163636,1.); -#163636 = DIRECTION('',(0.E+000,1.)); -#163637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163638 = PCURVE('',#163639,#163644); -#163639 = PLANE('',#163640); -#163640 = AXIS2_PLACEMENT_3D('',#163641,#163642,#163643); -#163641 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,-2.591449450184) - ); -#163642 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); -#163643 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#163644 = DEFINITIONAL_REPRESENTATION('',(#163645),#163649); -#163645 = LINE('',#163646,#163647); -#163646 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); -#163647 = VECTOR('',#163648,1.); -#163648 = DIRECTION('',(0.E+000,1.)); -#163649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163650 = ADVANCED_FACE('',(#163651),#163639,.T.); -#163651 = FACE_BOUND('',#163652,.T.); -#163652 = EDGE_LOOP('',(#163653,#163682,#163703,#163704)); -#163653 = ORIENTED_EDGE('',*,*,#163654,.F.); -#163654 = EDGE_CURVE('',#163655,#163657,#163659,.T.); -#163655 = VERTEX_POINT('',#163656); -#163656 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,-2.591449450184) - ); -#163657 = VERTEX_POINT('',#163658); -#163658 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,-2.591449450184) - ); -#163659 = SURFACE_CURVE('',#163660,(#163664,#163671),.PCURVE_S1.); -#163660 = LINE('',#163661,#163662); -#163661 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,-2.591449450184) - ); -#163662 = VECTOR('',#163663,1.); -#163663 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163664 = PCURVE('',#163639,#163665); -#163665 = DEFINITIONAL_REPRESENTATION('',(#163666),#163670); -#163666 = LINE('',#163667,#163668); -#163667 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); -#163668 = VECTOR('',#163669,1.); -#163669 = DIRECTION('',(0.E+000,1.)); -#163670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163671 = PCURVE('',#163672,#163677); -#163672 = CYLINDRICAL_SURFACE('',#163673,0.32); -#163673 = AXIS2_PLACEMENT_3D('',#163674,#163675,#163676); -#163674 = CARTESIAN_POINT('',(1.905,0.340821720102,-2.608196956182)); -#163675 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163676 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163677 = DEFINITIONAL_REPRESENTATION('',(#163678),#163681); -#163678 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163679,#163680), +#165881 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#165882 = CARTESIAN_POINT('',(2.708196956182,-0.707383360654)); +#165883 = CARTESIAN_POINT('',(2.558196956182,-0.620780820276)); +#165884 = CARTESIAN_POINT('',(2.408196956182,-0.534178279898)); +#165885 = CARTESIAN_POINT('',(2.558196956182,-0.447575739519)); +#165886 = CARTESIAN_POINT('',(2.708196956182,-0.360973199141)); +#165887 = CARTESIAN_POINT('',(2.708196956182,-0.534178279898)); +#165888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165889 = ORIENTED_EDGE('',*,*,#165755,.T.); +#165890 = ADVANCED_FACE('',(#165891),#165853,.T.); +#165891 = FACE_BOUND('',#165892,.T.); +#165892 = EDGE_LOOP('',(#165893,#165894,#165917,#165945)); +#165893 = ORIENTED_EDGE('',*,*,#165838,.T.); +#165894 = ORIENTED_EDGE('',*,*,#165895,.F.); +#165895 = EDGE_CURVE('',#165896,#165839,#165898,.T.); +#165896 = VERTEX_POINT('',#165897); +#165897 = CARTESIAN_POINT('',(2.115,0.219849248823,-3.005756955187)); +#165898 = SURFACE_CURVE('',#165899,(#165903,#165910),.PCURVE_S1.); +#165899 = LINE('',#165900,#165901); +#165900 = CARTESIAN_POINT('',(2.115,0.219849248823,-3.005756955187)); +#165901 = VECTOR('',#165902,1.); +#165902 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#165903 = PCURVE('',#165853,#165904); +#165904 = DEFINITIONAL_REPRESENTATION('',(#165905),#165909); +#165905 = LINE('',#165906,#165907); +#165906 = CARTESIAN_POINT('',(-0.403346366807,0.21)); +#165907 = VECTOR('',#165908,1.); +#165908 = DIRECTION('',(1.,0.E+000)); +#165909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165910 = PCURVE('',#165145,#165911); +#165911 = DEFINITIONAL_REPRESENTATION('',(#165912),#165916); +#165912 = LINE('',#165913,#165914); +#165913 = CARTESIAN_POINT('',(3.005756955187,-0.655150751177)); +#165914 = VECTOR('',#165915,1.); +#165915 = DIRECTION('',(-0.998629534755,5.233595624294E-002)); +#165916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165917 = ORIENTED_EDGE('',*,*,#165918,.T.); +#165918 = EDGE_CURVE('',#165896,#165919,#165921,.T.); +#165919 = VERTEX_POINT('',#165920); +#165920 = CARTESIAN_POINT('',(1.695,0.219849248823,-3.005756955187)); +#165921 = SURFACE_CURVE('',#165922,(#165926,#165933),.PCURVE_S1.); +#165922 = LINE('',#165923,#165924); +#165923 = CARTESIAN_POINT('',(1.905,0.219849248823,-3.005756955187)); +#165924 = VECTOR('',#165925,1.); +#165925 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#165926 = PCURVE('',#165853,#165927); +#165927 = DEFINITIONAL_REPRESENTATION('',(#165928),#165932); +#165928 = LINE('',#165929,#165930); +#165929 = CARTESIAN_POINT('',(-0.403346366807,0.E+000)); +#165930 = VECTOR('',#165931,1.); +#165931 = DIRECTION('',(0.E+000,-1.)); +#165932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165933 = PCURVE('',#165934,#165939); +#165934 = PLANE('',#165935); +#165935 = AXIS2_PLACEMENT_3D('',#165936,#165937,#165938); +#165936 = CARTESIAN_POINT('',(1.905,0.11,-3.)); +#165937 = DIRECTION('',(0.E+000,5.233595624291E-002,0.998629534755)); +#165938 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#165939 = DEFINITIONAL_REPRESENTATION('',(#165940),#165944); +#165940 = LINE('',#165941,#165942); +#165941 = CARTESIAN_POINT('',(-0.11,0.E+000)); +#165942 = VECTOR('',#165943,1.); +#165943 = DIRECTION('',(0.E+000,-1.)); +#165944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165945 = ORIENTED_EDGE('',*,*,#165946,.F.); +#165946 = EDGE_CURVE('',#165812,#165919,#165947,.T.); +#165947 = SURFACE_CURVE('',#165948,(#165952,#165959),.PCURVE_S1.); +#165948 = LINE('',#165949,#165950); +#165949 = CARTESIAN_POINT('',(1.695,0.240958766627,-2.602963360557)); +#165950 = VECTOR('',#165951,1.); +#165951 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#165952 = PCURVE('',#165853,#165953); +#165953 = DEFINITIONAL_REPRESENTATION('',(#165954),#165958); +#165954 = LINE('',#165955,#165956); +#165955 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#165956 = VECTOR('',#165957,1.); +#165957 = DIRECTION('',(-1.,0.E+000)); +#165958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165959 = PCURVE('',#165796,#165960); +#165960 = DEFINITIONAL_REPRESENTATION('',(#165961),#165965); +#165961 = LINE('',#165962,#165963); +#165962 = CARTESIAN_POINT('',(-2.602963360557,-0.634041233373)); +#165963 = VECTOR('',#165964,1.); +#165964 = DIRECTION('',(-0.998629534755,-5.233595624294E-002)); +#165965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165966 = ADVANCED_FACE('',(#165967),#165934,.F.); +#165967 = FACE_BOUND('',#165968,.T.); +#165968 = EDGE_LOOP('',(#165969,#165992,#165993,#166016)); +#165969 = ORIENTED_EDGE('',*,*,#165970,.F.); +#165970 = EDGE_CURVE('',#165919,#165971,#165973,.T.); +#165971 = VERTEX_POINT('',#165972); +#165972 = CARTESIAN_POINT('',(1.695,1.507511769881E-004,-2.994243044813) + ); +#165973 = SURFACE_CURVE('',#165974,(#165978,#165985),.PCURVE_S1.); +#165974 = LINE('',#165975,#165976); +#165975 = CARTESIAN_POINT('',(1.695,0.219849248823,-3.005756955187)); +#165976 = VECTOR('',#165977,1.); +#165977 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624291E-002)); +#165978 = PCURVE('',#165934,#165979); +#165979 = DEFINITIONAL_REPRESENTATION('',(#165980),#165984); +#165980 = LINE('',#165981,#165982); +#165981 = CARTESIAN_POINT('',(-0.11,-0.21)); +#165982 = VECTOR('',#165983,1.); +#165983 = DIRECTION('',(1.,0.E+000)); +#165984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165985 = PCURVE('',#165796,#165986); +#165986 = DEFINITIONAL_REPRESENTATION('',(#165987),#165991); +#165987 = LINE('',#165988,#165989); +#165988 = CARTESIAN_POINT('',(-3.005756955187,-0.655150751177)); +#165989 = VECTOR('',#165990,1.); +#165990 = DIRECTION('',(5.233595624291E-002,-0.998629534755)); +#165991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#165992 = ORIENTED_EDGE('',*,*,#165918,.F.); +#165993 = ORIENTED_EDGE('',*,*,#165994,.F.); +#165994 = EDGE_CURVE('',#165995,#165896,#165997,.T.); +#165995 = VERTEX_POINT('',#165996); +#165996 = CARTESIAN_POINT('',(2.115,1.507511769881E-004,-2.994243044813) + ); +#165997 = SURFACE_CURVE('',#165998,(#166002,#166009),.PCURVE_S1.); +#165998 = LINE('',#165999,#166000); +#165999 = CARTESIAN_POINT('',(2.115,1.507511769892E-004,-2.994243044813) + ); +#166000 = VECTOR('',#166001,1.); +#166001 = DIRECTION('',(0.E+000,0.998629534755,-5.233595624291E-002)); +#166002 = PCURVE('',#165934,#166003); +#166003 = DEFINITIONAL_REPRESENTATION('',(#166004),#166008); +#166004 = LINE('',#166005,#166006); +#166005 = CARTESIAN_POINT('',(0.11,0.21)); +#166006 = VECTOR('',#166007,1.); +#166007 = DIRECTION('',(-1.,0.E+000)); +#166008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166009 = PCURVE('',#165145,#166010); +#166010 = DEFINITIONAL_REPRESENTATION('',(#166011),#166015); +#166011 = LINE('',#166012,#166013); +#166012 = CARTESIAN_POINT('',(2.994243044813,-0.874849248823)); +#166013 = VECTOR('',#166014,1.); +#166014 = DIRECTION('',(5.233595624291E-002,0.998629534755)); +#166015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166016 = ORIENTED_EDGE('',*,*,#166017,.F.); +#166017 = EDGE_CURVE('',#165971,#165995,#166018,.T.); +#166018 = SURFACE_CURVE('',#166019,(#166023,#166030),.PCURVE_S1.); +#166019 = LINE('',#166020,#166021); +#166020 = CARTESIAN_POINT('',(1.905,1.507511769861E-004,-2.994243044813) + ); +#166021 = VECTOR('',#166022,1.); +#166022 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166023 = PCURVE('',#165934,#166024); +#166024 = DEFINITIONAL_REPRESENTATION('',(#166025),#166029); +#166025 = LINE('',#166026,#166027); +#166026 = CARTESIAN_POINT('',(0.11,0.E+000)); +#166027 = VECTOR('',#166028,1.); +#166028 = DIRECTION('',(0.E+000,1.)); +#166029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166030 = PCURVE('',#166031,#166036); +#166031 = PLANE('',#166032); +#166032 = AXIS2_PLACEMENT_3D('',#166033,#166034,#166035); +#166033 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,-2.591449450184) + ); +#166034 = DIRECTION('',(0.E+000,-0.998629534755,5.233595624294E-002)); +#166035 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#166036 = DEFINITIONAL_REPRESENTATION('',(#166037),#166041); +#166037 = LINE('',#166038,#166039); +#166038 = CARTESIAN_POINT('',(0.403346366807,0.E+000)); +#166039 = VECTOR('',#166040,1.); +#166040 = DIRECTION('',(0.E+000,1.)); +#166041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166042 = ADVANCED_FACE('',(#166043),#166031,.T.); +#166043 = FACE_BOUND('',#166044,.T.); +#166044 = EDGE_LOOP('',(#166045,#166074,#166095,#166096)); +#166045 = ORIENTED_EDGE('',*,*,#166046,.F.); +#166046 = EDGE_CURVE('',#166047,#166049,#166051,.T.); +#166047 = VERTEX_POINT('',#166048); +#166048 = CARTESIAN_POINT('',(1.695,2.126026898096E-002,-2.591449450184) + ); +#166049 = VERTEX_POINT('',#166050); +#166050 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,-2.591449450184) + ); +#166051 = SURFACE_CURVE('',#166052,(#166056,#166063),.PCURVE_S1.); +#166052 = LINE('',#166053,#166054); +#166053 = CARTESIAN_POINT('',(1.905,2.126026898095E-002,-2.591449450184) + ); +#166054 = VECTOR('',#166055,1.); +#166055 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166056 = PCURVE('',#166031,#166057); +#166057 = DEFINITIONAL_REPRESENTATION('',(#166058),#166062); +#166058 = LINE('',#166059,#166060); +#166059 = CARTESIAN_POINT('',(-3.631536477293E-019,0.E+000)); +#166060 = VECTOR('',#166061,1.); +#166061 = DIRECTION('',(0.E+000,1.)); +#166062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166063 = PCURVE('',#166064,#166069); +#166064 = CYLINDRICAL_SURFACE('',#166065,0.32); +#166065 = AXIS2_PLACEMENT_3D('',#166066,#166067,#166068); +#166066 = CARTESIAN_POINT('',(1.905,0.340821720102,-2.608196956182)); +#166067 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166068 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166069 = DEFINITIONAL_REPRESENTATION('',(#166070),#166073); +#166070 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166071,#166072), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163679 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163680 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163682 = ORIENTED_EDGE('',*,*,#163683,.F.); -#163683 = EDGE_CURVE('',#163579,#163655,#163684,.T.); -#163684 = SURFACE_CURVE('',#163685,(#163689,#163696),.PCURVE_S1.); -#163685 = LINE('',#163686,#163687); -#163686 = CARTESIAN_POINT('',(1.695,1.507511769892E-004,-2.994243044813) - ); -#163687 = VECTOR('',#163688,1.); -#163688 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); -#163689 = PCURVE('',#163639,#163690); -#163690 = DEFINITIONAL_REPRESENTATION('',(#163691),#163695); -#163691 = LINE('',#163692,#163693); -#163692 = CARTESIAN_POINT('',(0.403346366807,-0.21)); -#163693 = VECTOR('',#163694,1.); -#163694 = DIRECTION('',(-1.,0.E+000)); -#163695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163696 = PCURVE('',#163404,#163697); -#163697 = DEFINITIONAL_REPRESENTATION('',(#163698),#163702); -#163698 = LINE('',#163699,#163700); -#163699 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); -#163700 = VECTOR('',#163701,1.); -#163701 = DIRECTION('',(0.998629534755,5.233595624294E-002)); -#163702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163703 = ORIENTED_EDGE('',*,*,#163625,.T.); -#163704 = ORIENTED_EDGE('',*,*,#163705,.F.); -#163705 = EDGE_CURVE('',#163657,#163603,#163706,.T.); -#163706 = SURFACE_CURVE('',#163707,(#163711,#163718),.PCURVE_S1.); -#163707 = LINE('',#163708,#163709); -#163708 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,-2.591449450184) - ); -#163709 = VECTOR('',#163710,1.); -#163710 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); -#163711 = PCURVE('',#163639,#163712); -#163712 = DEFINITIONAL_REPRESENTATION('',(#163713),#163717); -#163713 = LINE('',#163714,#163715); -#163714 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); -#163715 = VECTOR('',#163716,1.); -#163716 = DIRECTION('',(1.,0.E+000)); -#163717 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163718 = PCURVE('',#162753,#163719); -#163719 = DEFINITIONAL_REPRESENTATION('',(#163720),#163724); -#163720 = LINE('',#163721,#163722); -#163721 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); -#163722 = VECTOR('',#163723,1.); -#163723 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); -#163724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163725 = ADVANCED_FACE('',(#163726),#163672,.T.); -#163726 = FACE_BOUND('',#163727,.T.); -#163727 = EDGE_LOOP('',(#163728,#163757,#163778,#163779)); -#163728 = ORIENTED_EDGE('',*,*,#163729,.F.); -#163729 = EDGE_CURVE('',#163730,#163732,#163734,.T.); -#163730 = VERTEX_POINT('',#163731); -#163731 = CARTESIAN_POINT('',(1.695,0.298978581017,-2.290944451524)); -#163732 = VERTEX_POINT('',#163733); -#163733 = CARTESIAN_POINT('',(2.115,0.298978581017,-2.290944451524)); -#163734 = SURFACE_CURVE('',#163735,(#163739,#163745),.PCURVE_S1.); -#163735 = LINE('',#163736,#163737); -#163736 = CARTESIAN_POINT('',(1.905,0.298978581017,-2.290944451524)); -#163737 = VECTOR('',#163738,1.); -#163738 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163739 = PCURVE('',#163672,#163740); -#163740 = DEFINITIONAL_REPRESENTATION('',(#163741),#163744); -#163741 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163742,#163743), +#166071 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#166072 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#166073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166074 = ORIENTED_EDGE('',*,*,#166075,.F.); +#166075 = EDGE_CURVE('',#165971,#166047,#166076,.T.); +#166076 = SURFACE_CURVE('',#166077,(#166081,#166088),.PCURVE_S1.); +#166077 = LINE('',#166078,#166079); +#166078 = CARTESIAN_POINT('',(1.695,1.507511769892E-004,-2.994243044813) + ); +#166079 = VECTOR('',#166080,1.); +#166080 = DIRECTION('',(0.E+000,5.233595624294E-002,0.998629534755)); +#166081 = PCURVE('',#166031,#166082); +#166082 = DEFINITIONAL_REPRESENTATION('',(#166083),#166087); +#166083 = LINE('',#166084,#166085); +#166084 = CARTESIAN_POINT('',(0.403346366807,-0.21)); +#166085 = VECTOR('',#166086,1.); +#166086 = DIRECTION('',(-1.,0.E+000)); +#166087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166088 = PCURVE('',#165796,#166089); +#166089 = DEFINITIONAL_REPRESENTATION('',(#166090),#166094); +#166090 = LINE('',#166091,#166092); +#166091 = CARTESIAN_POINT('',(-2.994243044813,-0.874849248823)); +#166092 = VECTOR('',#166093,1.); +#166093 = DIRECTION('',(0.998629534755,5.233595624294E-002)); +#166094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166095 = ORIENTED_EDGE('',*,*,#166017,.T.); +#166096 = ORIENTED_EDGE('',*,*,#166097,.F.); +#166097 = EDGE_CURVE('',#166049,#165995,#166098,.T.); +#166098 = SURFACE_CURVE('',#166099,(#166103,#166110),.PCURVE_S1.); +#166099 = LINE('',#166100,#166101); +#166100 = CARTESIAN_POINT('',(2.115,2.126026898096E-002,-2.591449450184) + ); +#166101 = VECTOR('',#166102,1.); +#166102 = DIRECTION('',(0.E+000,-5.233595624294E-002,-0.998629534755)); +#166103 = PCURVE('',#166031,#166104); +#166104 = DEFINITIONAL_REPRESENTATION('',(#166105),#166109); +#166105 = LINE('',#166106,#166107); +#166106 = CARTESIAN_POINT('',(-3.631536477293E-019,0.21)); +#166107 = VECTOR('',#166108,1.); +#166108 = DIRECTION('',(1.,0.E+000)); +#166109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166110 = PCURVE('',#165145,#166111); +#166111 = DEFINITIONAL_REPRESENTATION('',(#166112),#166116); +#166112 = LINE('',#166113,#166114); +#166113 = CARTESIAN_POINT('',(2.591449450184,-0.853739731019)); +#166114 = VECTOR('',#166115,1.); +#166115 = DIRECTION('',(0.998629534755,-5.233595624294E-002)); +#166116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166117 = ADVANCED_FACE('',(#166118),#166064,.T.); +#166118 = FACE_BOUND('',#166119,.T.); +#166119 = EDGE_LOOP('',(#166120,#166149,#166170,#166171)); +#166120 = ORIENTED_EDGE('',*,*,#166121,.F.); +#166121 = EDGE_CURVE('',#166122,#166124,#166126,.T.); +#166122 = VERTEX_POINT('',#166123); +#166123 = CARTESIAN_POINT('',(1.695,0.298978581017,-2.290944451524)); +#166124 = VERTEX_POINT('',#166125); +#166125 = CARTESIAN_POINT('',(2.115,0.298978581017,-2.290944451524)); +#166126 = SURFACE_CURVE('',#166127,(#166131,#166137),.PCURVE_S1.); +#166127 = LINE('',#166128,#166129); +#166128 = CARTESIAN_POINT('',(1.905,0.298978581017,-2.290944451524)); +#166129 = VECTOR('',#166130,1.); +#166130 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166131 = PCURVE('',#166064,#166132); +#166132 = DEFINITIONAL_REPRESENTATION('',(#166133),#166136); +#166133 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166134,#166135), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163742 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163743 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163745 = PCURVE('',#163746,#163751); -#163746 = PLANE('',#163747); -#163747 = AXIS2_PLACEMENT_3D('',#163748,#163749,#163750); -#163748 = CARTESIAN_POINT('',(1.905,0.678075980964,-2.240944451524)); -#163749 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); -#163750 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#163751 = DEFINITIONAL_REPRESENTATION('',(#163752),#163756); -#163752 = LINE('',#163753,#163754); -#163753 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); -#163754 = VECTOR('',#163755,1.); -#163755 = DIRECTION('',(0.E+000,1.)); -#163756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163757 = ORIENTED_EDGE('',*,*,#163758,.F.); -#163758 = EDGE_CURVE('',#163655,#163730,#163759,.T.); -#163759 = SURFACE_CURVE('',#163760,(#163765,#163771),.PCURVE_S1.); -#163760 = CIRCLE('',#163761,0.32); -#163761 = AXIS2_PLACEMENT_3D('',#163762,#163763,#163764); -#163762 = CARTESIAN_POINT('',(1.695,0.340821720102,-2.608196956182)); -#163763 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163764 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); -#163765 = PCURVE('',#163672,#163766); -#163766 = DEFINITIONAL_REPRESENTATION('',(#163767),#163770); -#163767 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163768,#163769), +#166134 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#166135 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#166136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166137 = PCURVE('',#166138,#166143); +#166138 = PLANE('',#166139); +#166139 = AXIS2_PLACEMENT_3D('',#166140,#166141,#166142); +#166140 = CARTESIAN_POINT('',(1.905,0.678075980964,-2.240944451524)); +#166141 = DIRECTION('',(0.E+000,-0.130759809642,0.991414077055)); +#166142 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#166143 = DEFINITIONAL_REPRESENTATION('',(#166144),#166148); +#166144 = LINE('',#166145,#166146); +#166145 = CARTESIAN_POINT('',(0.382380489365,0.E+000)); +#166146 = VECTOR('',#166147,1.); +#166147 = DIRECTION('',(0.E+000,1.)); +#166148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166149 = ORIENTED_EDGE('',*,*,#166150,.F.); +#166150 = EDGE_CURVE('',#166047,#166122,#166151,.T.); +#166151 = SURFACE_CURVE('',#166152,(#166157,#166163),.PCURVE_S1.); +#166152 = CIRCLE('',#166153,0.32); +#166153 = AXIS2_PLACEMENT_3D('',#166154,#166155,#166156); +#166154 = CARTESIAN_POINT('',(1.695,0.340821720102,-2.608196956182)); +#166155 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166156 = DIRECTION('',(0.E+000,1.694065894509E-015,-1.)); +#166157 = PCURVE('',#166064,#166158); +#166158 = DEFINITIONAL_REPRESENTATION('',(#166159),#166162); +#166159 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166160,#166161), .UNSPECIFIED.,.F.,.F.,(2,2),(1.623156204355,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#163768 = CARTESIAN_POINT('',(4.660029102825,-0.21)); -#163769 = CARTESIAN_POINT('',(3.272727984444,-0.21)); -#163770 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163771 = PCURVE('',#163404,#163772); -#163772 = DEFINITIONAL_REPRESENTATION('',(#163773),#163777); -#163773 = CIRCLE('',#163774,0.32); -#163774 = AXIS2_PLACEMENT_2D('',#163775,#163776); -#163775 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); -#163776 = DIRECTION('',(-1.,1.694065894509E-015)); -#163777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163778 = ORIENTED_EDGE('',*,*,#163654,.T.); -#163779 = ORIENTED_EDGE('',*,*,#163780,.F.); -#163780 = EDGE_CURVE('',#163732,#163657,#163781,.T.); -#163781 = SURFACE_CURVE('',#163782,(#163787,#163793),.PCURVE_S1.); -#163782 = CIRCLE('',#163783,0.32); -#163783 = AXIS2_PLACEMENT_3D('',#163784,#163785,#163786); -#163784 = CARTESIAN_POINT('',(2.115,0.340821720102,-2.608196956182)); -#163785 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163786 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#163787 = PCURVE('',#163672,#163788); -#163788 = DEFINITIONAL_REPRESENTATION('',(#163789),#163792); -#163789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163790,#163791), +#166160 = CARTESIAN_POINT('',(4.660029102825,-0.21)); +#166161 = CARTESIAN_POINT('',(3.272727984444,-0.21)); +#166162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166163 = PCURVE('',#165796,#166164); +#166164 = DEFINITIONAL_REPRESENTATION('',(#166165),#166169); +#166165 = CIRCLE('',#166166,0.32); +#166166 = AXIS2_PLACEMENT_2D('',#166167,#166168); +#166167 = CARTESIAN_POINT('',(-2.608196956182,-0.534178279898)); +#166168 = DIRECTION('',(-1.,1.694065894509E-015)); +#166169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166170 = ORIENTED_EDGE('',*,*,#166046,.T.); +#166171 = ORIENTED_EDGE('',*,*,#166172,.F.); +#166172 = EDGE_CURVE('',#166124,#166049,#166173,.T.); +#166173 = SURFACE_CURVE('',#166174,(#166179,#166185),.PCURVE_S1.); +#166174 = CIRCLE('',#166175,0.32); +#166175 = AXIS2_PLACEMENT_3D('',#166176,#166177,#166178); +#166176 = CARTESIAN_POINT('',(2.115,0.340821720102,-2.608196956182)); +#166177 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166178 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166179 = PCURVE('',#166064,#166180); +#166180 = DEFINITIONAL_REPRESENTATION('',(#166181),#166184); +#166181 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166182,#166183), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.660029102825), .PIECEWISE_BEZIER_KNOTS.); -#163790 = CARTESIAN_POINT('',(3.272727984444,0.21)); -#163791 = CARTESIAN_POINT('',(4.660029102825,0.21)); -#163792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163793 = PCURVE('',#162753,#163794); -#163794 = DEFINITIONAL_REPRESENTATION('',(#163795),#163799); -#163795 = CIRCLE('',#163796,0.32); -#163796 = AXIS2_PLACEMENT_2D('',#163797,#163798); -#163797 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); -#163798 = DIRECTION('',(1.,0.E+000)); -#163799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163800 = ADVANCED_FACE('',(#163801),#163746,.T.); -#163801 = FACE_BOUND('',#163802,.T.); -#163802 = EDGE_LOOP('',(#163803,#163832,#163853,#163854)); -#163803 = ORIENTED_EDGE('',*,*,#163804,.T.); -#163804 = EDGE_CURVE('',#163805,#163807,#163809,.T.); -#163805 = VERTEX_POINT('',#163806); -#163806 = CARTESIAN_POINT('',(2.115,0.678075980964,-2.240944451524)); -#163807 = VERTEX_POINT('',#163808); -#163808 = CARTESIAN_POINT('',(1.695,0.678075980964,-2.240944451524)); -#163809 = SURFACE_CURVE('',#163810,(#163814,#163821),.PCURVE_S1.); -#163810 = LINE('',#163811,#163812); -#163811 = CARTESIAN_POINT('',(1.905,0.678075980964,-2.240944451524)); -#163812 = VECTOR('',#163813,1.); -#163813 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163814 = PCURVE('',#163746,#163815); -#163815 = DEFINITIONAL_REPRESENTATION('',(#163816),#163820); -#163816 = LINE('',#163817,#163818); -#163817 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#163818 = VECTOR('',#163819,1.); -#163819 = DIRECTION('',(0.E+000,-1.)); -#163820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163821 = PCURVE('',#163822,#163827); -#163822 = CYLINDRICAL_SURFACE('',#163823,1.E-001); -#163823 = AXIS2_PLACEMENT_3D('',#163824,#163825,#163826); -#163824 = CARTESIAN_POINT('',(1.905,0.665,-2.141803043818)); -#163825 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163826 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163827 = DEFINITIONAL_REPRESENTATION('',(#163828),#163831); -#163828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163829,#163830), +#166182 = CARTESIAN_POINT('',(3.272727984444,0.21)); +#166183 = CARTESIAN_POINT('',(4.660029102825,0.21)); +#166184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166185 = PCURVE('',#165145,#166186); +#166186 = DEFINITIONAL_REPRESENTATION('',(#166187),#166191); +#166187 = CIRCLE('',#166188,0.32); +#166188 = AXIS2_PLACEMENT_2D('',#166189,#166190); +#166189 = CARTESIAN_POINT('',(2.608196956182,-0.534178279898)); +#166190 = DIRECTION('',(1.,0.E+000)); +#166191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166192 = ADVANCED_FACE('',(#166193),#166138,.T.); +#166193 = FACE_BOUND('',#166194,.T.); +#166194 = EDGE_LOOP('',(#166195,#166224,#166245,#166246)); +#166195 = ORIENTED_EDGE('',*,*,#166196,.T.); +#166196 = EDGE_CURVE('',#166197,#166199,#166201,.T.); +#166197 = VERTEX_POINT('',#166198); +#166198 = CARTESIAN_POINT('',(2.115,0.678075980964,-2.240944451524)); +#166199 = VERTEX_POINT('',#166200); +#166200 = CARTESIAN_POINT('',(1.695,0.678075980964,-2.240944451524)); +#166201 = SURFACE_CURVE('',#166202,(#166206,#166213),.PCURVE_S1.); +#166202 = LINE('',#166203,#166204); +#166203 = CARTESIAN_POINT('',(1.905,0.678075980964,-2.240944451524)); +#166204 = VECTOR('',#166205,1.); +#166205 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166206 = PCURVE('',#166138,#166207); +#166207 = DEFINITIONAL_REPRESENTATION('',(#166208),#166212); +#166208 = LINE('',#166209,#166210); +#166209 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#166210 = VECTOR('',#166211,1.); +#166211 = DIRECTION('',(0.E+000,-1.)); +#166212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166213 = PCURVE('',#166214,#166219); +#166214 = CYLINDRICAL_SURFACE('',#166215,1.E-001); +#166215 = AXIS2_PLACEMENT_3D('',#166216,#166217,#166218); +#166216 = CARTESIAN_POINT('',(1.905,0.665,-2.141803043818)); +#166217 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166218 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166219 = DEFINITIONAL_REPRESENTATION('',(#166220),#166223); +#166220 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166221,#166222), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#163829 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#163830 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#163831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163832 = ORIENTED_EDGE('',*,*,#163833,.F.); -#163833 = EDGE_CURVE('',#163730,#163807,#163834,.T.); -#163834 = SURFACE_CURVE('',#163835,(#163839,#163846),.PCURVE_S1.); -#163835 = LINE('',#163836,#163837); -#163836 = CARTESIAN_POINT('',(1.695,0.298978581017,-2.290944451524)); -#163837 = VECTOR('',#163838,1.); -#163838 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); -#163839 = PCURVE('',#163746,#163840); -#163840 = DEFINITIONAL_REPRESENTATION('',(#163841),#163845); -#163841 = LINE('',#163842,#163843); -#163842 = CARTESIAN_POINT('',(0.382380489365,-0.21)); -#163843 = VECTOR('',#163844,1.); -#163844 = DIRECTION('',(-1.,0.E+000)); -#163845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163846 = PCURVE('',#163404,#163847); -#163847 = DEFINITIONAL_REPRESENTATION('',(#163848),#163852); -#163848 = LINE('',#163849,#163850); -#163849 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); -#163850 = VECTOR('',#163851,1.); -#163851 = DIRECTION('',(0.130759809642,0.991414077055)); -#163852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163853 = ORIENTED_EDGE('',*,*,#163729,.T.); -#163854 = ORIENTED_EDGE('',*,*,#163855,.F.); -#163855 = EDGE_CURVE('',#163805,#163732,#163856,.T.); -#163856 = SURFACE_CURVE('',#163857,(#163861,#163868),.PCURVE_S1.); -#163857 = LINE('',#163858,#163859); -#163858 = CARTESIAN_POINT('',(2.115,0.678075980964,-2.240944451524)); -#163859 = VECTOR('',#163860,1.); -#163860 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); -#163861 = PCURVE('',#163746,#163862); -#163862 = DEFINITIONAL_REPRESENTATION('',(#163863),#163867); -#163863 = LINE('',#163864,#163865); -#163864 = CARTESIAN_POINT('',(0.E+000,0.21)); -#163865 = VECTOR('',#163866,1.); -#163866 = DIRECTION('',(1.,0.E+000)); -#163867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163868 = PCURVE('',#162753,#163869); -#163869 = DEFINITIONAL_REPRESENTATION('',(#163870),#163874); -#163870 = LINE('',#163871,#163872); -#163871 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); -#163872 = VECTOR('',#163873,1.); -#163873 = DIRECTION('',(0.130759809642,-0.991414077055)); -#163874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163875 = ADVANCED_FACE('',(#163876),#163822,.F.); -#163876 = FACE_BOUND('',#163877,.F.); -#163877 = EDGE_LOOP('',(#163878,#163905,#163906,#163933)); -#163878 = ORIENTED_EDGE('',*,*,#163879,.T.); -#163879 = EDGE_CURVE('',#163880,#163805,#163882,.T.); -#163880 = VERTEX_POINT('',#163881); -#163881 = CARTESIAN_POINT('',(2.115,0.765,-2.141803043818)); -#163882 = SURFACE_CURVE('',#163883,(#163888,#163894),.PCURVE_S1.); -#163883 = CIRCLE('',#163884,1.E-001); -#163884 = AXIS2_PLACEMENT_3D('',#163885,#163886,#163887); -#163885 = CARTESIAN_POINT('',(2.115,0.665,-2.141803043818)); -#163886 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#163887 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163888 = PCURVE('',#163822,#163889); -#163889 = DEFINITIONAL_REPRESENTATION('',(#163890),#163893); -#163890 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163891,#163892), +#166221 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#166222 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#166223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166224 = ORIENTED_EDGE('',*,*,#166225,.F.); +#166225 = EDGE_CURVE('',#166122,#166199,#166226,.T.); +#166226 = SURFACE_CURVE('',#166227,(#166231,#166238),.PCURVE_S1.); +#166227 = LINE('',#166228,#166229); +#166228 = CARTESIAN_POINT('',(1.695,0.298978581017,-2.290944451524)); +#166229 = VECTOR('',#166230,1.); +#166230 = DIRECTION('',(0.E+000,0.991414077055,0.130759809642)); +#166231 = PCURVE('',#166138,#166232); +#166232 = DEFINITIONAL_REPRESENTATION('',(#166233),#166237); +#166233 = LINE('',#166234,#166235); +#166234 = CARTESIAN_POINT('',(0.382380489365,-0.21)); +#166235 = VECTOR('',#166236,1.); +#166236 = DIRECTION('',(-1.,0.E+000)); +#166237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166238 = PCURVE('',#165796,#166239); +#166239 = DEFINITIONAL_REPRESENTATION('',(#166240),#166244); +#166240 = LINE('',#166241,#166242); +#166241 = CARTESIAN_POINT('',(-2.290944451524,-0.576021418983)); +#166242 = VECTOR('',#166243,1.); +#166243 = DIRECTION('',(0.130759809642,0.991414077055)); +#166244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166245 = ORIENTED_EDGE('',*,*,#166121,.T.); +#166246 = ORIENTED_EDGE('',*,*,#166247,.F.); +#166247 = EDGE_CURVE('',#166197,#166124,#166248,.T.); +#166248 = SURFACE_CURVE('',#166249,(#166253,#166260),.PCURVE_S1.); +#166249 = LINE('',#166250,#166251); +#166250 = CARTESIAN_POINT('',(2.115,0.678075980964,-2.240944451524)); +#166251 = VECTOR('',#166252,1.); +#166252 = DIRECTION('',(0.E+000,-0.991414077055,-0.130759809642)); +#166253 = PCURVE('',#166138,#166254); +#166254 = DEFINITIONAL_REPRESENTATION('',(#166255),#166259); +#166255 = LINE('',#166256,#166257); +#166256 = CARTESIAN_POINT('',(0.E+000,0.21)); +#166257 = VECTOR('',#166258,1.); +#166258 = DIRECTION('',(1.,0.E+000)); +#166259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166260 = PCURVE('',#165145,#166261); +#166261 = DEFINITIONAL_REPRESENTATION('',(#166262),#166266); +#166262 = LINE('',#166263,#166264); +#166263 = CARTESIAN_POINT('',(2.240944451524,-0.196924019036)); +#166264 = VECTOR('',#166265,1.); +#166265 = DIRECTION('',(0.130759809642,-0.991414077055)); +#166266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166267 = ADVANCED_FACE('',(#166268),#166214,.F.); +#166268 = FACE_BOUND('',#166269,.F.); +#166269 = EDGE_LOOP('',(#166270,#166297,#166298,#166325)); +#166270 = ORIENTED_EDGE('',*,*,#166271,.T.); +#166271 = EDGE_CURVE('',#166272,#166197,#166274,.T.); +#166272 = VERTEX_POINT('',#166273); +#166273 = CARTESIAN_POINT('',(2.115,0.765,-2.141803043818)); +#166274 = SURFACE_CURVE('',#166275,(#166280,#166286),.PCURVE_S1.); +#166275 = CIRCLE('',#166276,1.E-001); +#166276 = AXIS2_PLACEMENT_3D('',#166277,#166278,#166279); +#166277 = CARTESIAN_POINT('',(2.115,0.665,-2.141803043818)); +#166278 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166279 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166280 = PCURVE('',#166214,#166281); +#166281 = DEFINITIONAL_REPRESENTATION('',(#166282),#166285); +#166282 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166283,#166284), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#163891 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#163892 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#163893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166283 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#166284 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#166285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163894 = PCURVE('',#162753,#163895); -#163895 = DEFINITIONAL_REPRESENTATION('',(#163896),#163904); -#163896 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163897,#163898,#163899, - #163900,#163901,#163902,#163903),.UNSPECIFIED.,.T.,.F.) +#166286 = PCURVE('',#165145,#166287); +#166287 = DEFINITIONAL_REPRESENTATION('',(#166288),#166296); +#166288 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#166289,#166290,#166291, + #166292,#166293,#166294,#166295),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163897 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#163898 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); -#163899 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); -#163900 = CARTESIAN_POINT('',(2.341803043818,-0.21)); -#163901 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); -#163902 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); -#163903 = CARTESIAN_POINT('',(2.041803043818,-0.21)); -#163904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163905 = ORIENTED_EDGE('',*,*,#163804,.T.); -#163906 = ORIENTED_EDGE('',*,*,#163907,.T.); -#163907 = EDGE_CURVE('',#163807,#163908,#163910,.T.); -#163908 = VERTEX_POINT('',#163909); -#163909 = CARTESIAN_POINT('',(1.695,0.765,-2.141803043818)); -#163910 = SURFACE_CURVE('',#163911,(#163916,#163922),.PCURVE_S1.); -#163911 = CIRCLE('',#163912,1.E-001); -#163912 = AXIS2_PLACEMENT_3D('',#163913,#163914,#163915); -#163913 = CARTESIAN_POINT('',(1.695,0.665,-2.141803043818)); -#163914 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163915 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); -#163916 = PCURVE('',#163822,#163917); -#163917 = DEFINITIONAL_REPRESENTATION('',(#163918),#163921); -#163918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163919,#163920), +#166289 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#166290 = CARTESIAN_POINT('',(2.041803043818,-3.679491924311E-002)); +#166291 = CARTESIAN_POINT('',(2.191803043818,-0.123397459622)); +#166292 = CARTESIAN_POINT('',(2.341803043818,-0.21)); +#166293 = CARTESIAN_POINT('',(2.191803043818,-0.296602540378)); +#166294 = CARTESIAN_POINT('',(2.041803043818,-0.383205080757)); +#166295 = CARTESIAN_POINT('',(2.041803043818,-0.21)); +#166296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166297 = ORIENTED_EDGE('',*,*,#166196,.T.); +#166298 = ORIENTED_EDGE('',*,*,#166299,.T.); +#166299 = EDGE_CURVE('',#166199,#166300,#166302,.T.); +#166300 = VERTEX_POINT('',#166301); +#166301 = CARTESIAN_POINT('',(1.695,0.765,-2.141803043818)); +#166302 = SURFACE_CURVE('',#166303,(#166308,#166314),.PCURVE_S1.); +#166303 = CIRCLE('',#166304,1.E-001); +#166304 = AXIS2_PLACEMENT_3D('',#166305,#166306,#166307); +#166305 = CARTESIAN_POINT('',(1.695,0.665,-2.141803043818)); +#166306 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166307 = DIRECTION('',(0.E+000,-2.168404344971E-015,1.)); +#166308 = PCURVE('',#166214,#166309); +#166309 = DEFINITIONAL_REPRESENTATION('',(#166310),#166313); +#166310 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166311,#166312), .UNSPECIFIED.,.F.,.F.,(2,2),(3.272727984444,4.712388980385), .PIECEWISE_BEZIER_KNOTS.); -#163919 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#163920 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#163921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166311 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#166312 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#166313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#163922 = PCURVE('',#163404,#163923); -#163923 = DEFINITIONAL_REPRESENTATION('',(#163924),#163932); -#163924 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#163925,#163926,#163927, - #163928,#163929,#163930,#163931),.UNSPECIFIED.,.T.,.F.) +#166314 = PCURVE('',#165796,#166315); +#166315 = DEFINITIONAL_REPRESENTATION('',(#166316),#166324); +#166316 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#166317,#166318,#166319, + #166320,#166321,#166322,#166323),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#163925 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#163926 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); -#163927 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); -#163928 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); -#163929 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); -#163930 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); -#163931 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); -#163932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163933 = ORIENTED_EDGE('',*,*,#163934,.T.); -#163934 = EDGE_CURVE('',#163908,#163880,#163935,.T.); -#163935 = SURFACE_CURVE('',#163936,(#163940,#163946),.PCURVE_S1.); -#163936 = LINE('',#163937,#163938); -#163937 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); -#163938 = VECTOR('',#163939,1.); -#163939 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163940 = PCURVE('',#163822,#163941); -#163941 = DEFINITIONAL_REPRESENTATION('',(#163942),#163945); -#163942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#163943,#163944), +#166317 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#166318 = CARTESIAN_POINT('',(-2.041803043818,-0.383205080757)); +#166319 = CARTESIAN_POINT('',(-2.191803043818,-0.296602540378)); +#166320 = CARTESIAN_POINT('',(-2.341803043818,-0.21)); +#166321 = CARTESIAN_POINT('',(-2.191803043818,-0.123397459622)); +#166322 = CARTESIAN_POINT('',(-2.041803043818,-3.679491924311E-002)); +#166323 = CARTESIAN_POINT('',(-2.041803043818,-0.21)); +#166324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166325 = ORIENTED_EDGE('',*,*,#166326,.T.); +#166326 = EDGE_CURVE('',#166300,#166272,#166327,.T.); +#166327 = SURFACE_CURVE('',#166328,(#166332,#166338),.PCURVE_S1.); +#166328 = LINE('',#166329,#166330); +#166329 = CARTESIAN_POINT('',(0.635,0.765,-2.141803043818)); +#166330 = VECTOR('',#166331,1.); +#166331 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166332 = PCURVE('',#166214,#166333); +#166333 = DEFINITIONAL_REPRESENTATION('',(#166334),#166337); +#166334 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166335,#166336), .UNSPECIFIED.,.F.,.F.,(2,2),(1.06,1.48),.PIECEWISE_BEZIER_KNOTS.); -#163943 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#163944 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#163945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163946 = PCURVE('',#159360,#163947); -#163947 = DEFINITIONAL_REPRESENTATION('',(#163948),#163952); -#163948 = LINE('',#163949,#163950); -#163949 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#163950 = VECTOR('',#163951,1.); -#163951 = DIRECTION('',(0.E+000,1.)); -#163952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163953 = ADVANCED_FACE('',(#163954),#159360,.T.); -#163954 = FACE_BOUND('',#163955,.T.); -#163955 = EDGE_LOOP('',(#163956,#163979,#164007,#164028,#164029,#164052, - #164080,#164101,#164102,#164125,#164153,#164174,#164175,#164196, - #164197,#164220,#164248,#164269,#164270,#164293,#164321,#164342, - #164343,#164366,#164394,#164415,#164416,#164437)); -#163956 = ORIENTED_EDGE('',*,*,#163957,.F.); -#163957 = EDGE_CURVE('',#163958,#163229,#163960,.T.); -#163958 = VERTEX_POINT('',#163959); -#163959 = CARTESIAN_POINT('',(1.695,0.765,0.21)); -#163960 = SURFACE_CURVE('',#163961,(#163965,#163972),.PCURVE_S1.); -#163961 = LINE('',#163962,#163963); -#163962 = CARTESIAN_POINT('',(1.695,0.765,0.E+000)); -#163963 = VECTOR('',#163964,1.); -#163964 = DIRECTION('',(0.E+000,0.E+000,1.)); -#163965 = PCURVE('',#159360,#163966); -#163966 = DEFINITIONAL_REPRESENTATION('',(#163967),#163971); -#163967 = LINE('',#163968,#163969); -#163968 = CARTESIAN_POINT('',(0.E+000,1.06)); -#163969 = VECTOR('',#163970,1.); -#163970 = DIRECTION('',(-1.,0.E+000)); -#163971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163972 = PCURVE('',#162700,#163973); -#163973 = DEFINITIONAL_REPRESENTATION('',(#163974),#163978); -#163974 = LINE('',#163975,#163976); -#163975 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#163976 = VECTOR('',#163977,1.); -#163977 = DIRECTION('',(1.,0.E+000)); -#163978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163979 = ORIENTED_EDGE('',*,*,#163980,.F.); -#163980 = EDGE_CURVE('',#163981,#163958,#163983,.T.); -#163981 = VERTEX_POINT('',#163982); -#163982 = CARTESIAN_POINT('',(0.845,0.765,0.21)); -#163983 = SURFACE_CURVE('',#163984,(#163988,#163995),.PCURVE_S1.); -#163984 = LINE('',#163985,#163986); -#163985 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); -#163986 = VECTOR('',#163987,1.); -#163987 = DIRECTION('',(1.,0.E+000,0.E+000)); -#163988 = PCURVE('',#159360,#163989); -#163989 = DEFINITIONAL_REPRESENTATION('',(#163990),#163994); -#163990 = LINE('',#163991,#163992); -#163991 = CARTESIAN_POINT('',(-0.21,-2.54)); -#163992 = VECTOR('',#163993,1.); -#163993 = DIRECTION('',(0.E+000,1.)); -#163994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#163995 = PCURVE('',#163996,#164001); -#163996 = PLANE('',#163997); -#163997 = AXIS2_PLACEMENT_3D('',#163998,#163999,#164000); -#163998 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); -#163999 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164000 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164001 = DEFINITIONAL_REPRESENTATION('',(#164002),#164006); -#164002 = LINE('',#164003,#164004); -#164003 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164004 = VECTOR('',#164005,1.); -#164005 = DIRECTION('',(1.,0.E+000)); -#164006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164007 = ORIENTED_EDGE('',*,*,#164008,.F.); -#164008 = EDGE_CURVE('',#162601,#163981,#164009,.T.); -#164009 = SURFACE_CURVE('',#164010,(#164014,#164021),.PCURVE_S1.); -#164010 = LINE('',#164011,#164012); -#164011 = CARTESIAN_POINT('',(0.845,0.765,0.E+000)); -#164012 = VECTOR('',#164013,1.); -#164013 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164014 = PCURVE('',#159360,#164015); -#164015 = DEFINITIONAL_REPRESENTATION('',(#164016),#164020); -#164016 = LINE('',#164017,#164018); -#164017 = CARTESIAN_POINT('',(0.E+000,0.21)); -#164018 = VECTOR('',#164019,1.); -#164019 = DIRECTION('',(1.,0.E+000)); -#164020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164021 = PCURVE('',#162097,#164022); -#164022 = DEFINITIONAL_REPRESENTATION('',(#164023),#164027); -#164023 = LINE('',#164024,#164025); -#164024 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164025 = VECTOR('',#164026,1.); -#164026 = DIRECTION('',(1.,0.E+000)); -#164027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164028 = ORIENTED_EDGE('',*,*,#162627,.T.); -#164029 = ORIENTED_EDGE('',*,*,#164030,.F.); -#164030 = EDGE_CURVE('',#164031,#162573,#164033,.T.); -#164031 = VERTEX_POINT('',#164032); -#164032 = CARTESIAN_POINT('',(0.425,0.765,0.21)); -#164033 = SURFACE_CURVE('',#164034,(#164038,#164045),.PCURVE_S1.); -#164034 = LINE('',#164035,#164036); -#164035 = CARTESIAN_POINT('',(0.425,0.765,0.E+000)); -#164036 = VECTOR('',#164037,1.); -#164037 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164038 = PCURVE('',#159360,#164039); -#164039 = DEFINITIONAL_REPRESENTATION('',(#164040),#164044); -#164040 = LINE('',#164041,#164042); -#164041 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#164042 = VECTOR('',#164043,1.); -#164043 = DIRECTION('',(-1.,0.E+000)); -#164044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164045 = PCURVE('',#162044,#164046); -#164046 = DEFINITIONAL_REPRESENTATION('',(#164047),#164051); -#164047 = LINE('',#164048,#164049); -#164048 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164049 = VECTOR('',#164050,1.); -#164050 = DIRECTION('',(1.,0.E+000)); -#164051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164052 = ORIENTED_EDGE('',*,*,#164053,.F.); -#164053 = EDGE_CURVE('',#164054,#164031,#164056,.T.); -#164054 = VERTEX_POINT('',#164055); -#164055 = CARTESIAN_POINT('',(-0.425,0.765,0.21)); -#164056 = SURFACE_CURVE('',#164057,(#164061,#164068),.PCURVE_S1.); -#164057 = LINE('',#164058,#164059); -#164058 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); -#164059 = VECTOR('',#164060,1.); -#164060 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164061 = PCURVE('',#159360,#164062); -#164062 = DEFINITIONAL_REPRESENTATION('',(#164063),#164067); -#164063 = LINE('',#164064,#164065); -#164064 = CARTESIAN_POINT('',(-0.21,-2.54)); -#164065 = VECTOR('',#164066,1.); -#164066 = DIRECTION('',(0.E+000,1.)); -#164067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164068 = PCURVE('',#164069,#164074); -#164069 = PLANE('',#164070); -#164070 = AXIS2_PLACEMENT_3D('',#164071,#164072,#164073); -#164071 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); -#164072 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164073 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164074 = DEFINITIONAL_REPRESENTATION('',(#164075),#164079); -#164075 = LINE('',#164076,#164077); -#164076 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164077 = VECTOR('',#164078,1.); -#164078 = DIRECTION('',(1.,0.E+000)); -#164079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164080 = ORIENTED_EDGE('',*,*,#164081,.F.); -#164081 = EDGE_CURVE('',#161945,#164054,#164082,.T.); -#164082 = SURFACE_CURVE('',#164083,(#164087,#164094),.PCURVE_S1.); -#164083 = LINE('',#164084,#164085); -#164084 = CARTESIAN_POINT('',(-0.425,0.765,0.E+000)); -#164085 = VECTOR('',#164086,1.); -#164086 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164087 = PCURVE('',#159360,#164088); -#164088 = DEFINITIONAL_REPRESENTATION('',(#164089),#164093); -#164089 = LINE('',#164090,#164091); -#164090 = CARTESIAN_POINT('',(0.E+000,-1.06)); -#164091 = VECTOR('',#164092,1.); -#164092 = DIRECTION('',(1.,0.E+000)); -#164093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164094 = PCURVE('',#161441,#164095); -#164095 = DEFINITIONAL_REPRESENTATION('',(#164096),#164100); -#164096 = LINE('',#164097,#164098); -#164097 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164098 = VECTOR('',#164099,1.); -#164099 = DIRECTION('',(1.,0.E+000)); -#164100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164101 = ORIENTED_EDGE('',*,*,#161971,.T.); -#164102 = ORIENTED_EDGE('',*,*,#164103,.F.); -#164103 = EDGE_CURVE('',#164104,#161917,#164106,.T.); -#164104 = VERTEX_POINT('',#164105); -#164105 = CARTESIAN_POINT('',(-0.845,0.765,0.21)); -#164106 = SURFACE_CURVE('',#164107,(#164111,#164118),.PCURVE_S1.); -#164107 = LINE('',#164108,#164109); -#164108 = CARTESIAN_POINT('',(-0.845,0.765,0.E+000)); -#164109 = VECTOR('',#164110,1.); -#164110 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164111 = PCURVE('',#159360,#164112); -#164112 = DEFINITIONAL_REPRESENTATION('',(#164113),#164117); -#164113 = LINE('',#164114,#164115); -#164114 = CARTESIAN_POINT('',(0.E+000,-1.48)); -#164115 = VECTOR('',#164116,1.); -#164116 = DIRECTION('',(-1.,0.E+000)); -#164117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164118 = PCURVE('',#161388,#164119); -#164119 = DEFINITIONAL_REPRESENTATION('',(#164120),#164124); -#164120 = LINE('',#164121,#164122); -#164121 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164122 = VECTOR('',#164123,1.); -#164123 = DIRECTION('',(1.,0.E+000)); -#164124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166335 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#166336 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#166337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166338 = PCURVE('',#161752,#166339); +#166339 = DEFINITIONAL_REPRESENTATION('',(#166340),#166344); +#166340 = LINE('',#166341,#166342); +#166341 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#166342 = VECTOR('',#166343,1.); +#166343 = DIRECTION('',(0.E+000,1.)); +#166344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166345 = ADVANCED_FACE('',(#166346),#161752,.T.); +#166346 = FACE_BOUND('',#166347,.T.); +#166347 = EDGE_LOOP('',(#166348,#166371,#166399,#166420,#166421,#166444, + #166472,#166493,#166494,#166517,#166545,#166566,#166567,#166588, + #166589,#166612,#166640,#166661,#166662,#166685,#166713,#166734, + #166735,#166758,#166786,#166807,#166808,#166829)); +#166348 = ORIENTED_EDGE('',*,*,#166349,.F.); +#166349 = EDGE_CURVE('',#166350,#165621,#166352,.T.); +#166350 = VERTEX_POINT('',#166351); +#166351 = CARTESIAN_POINT('',(1.695,0.765,0.21)); +#166352 = SURFACE_CURVE('',#166353,(#166357,#166364),.PCURVE_S1.); +#166353 = LINE('',#166354,#166355); +#166354 = CARTESIAN_POINT('',(1.695,0.765,0.E+000)); +#166355 = VECTOR('',#166356,1.); +#166356 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166357 = PCURVE('',#161752,#166358); +#166358 = DEFINITIONAL_REPRESENTATION('',(#166359),#166363); +#166359 = LINE('',#166360,#166361); +#166360 = CARTESIAN_POINT('',(0.E+000,1.06)); +#166361 = VECTOR('',#166362,1.); +#166362 = DIRECTION('',(-1.,0.E+000)); +#166363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166364 = PCURVE('',#165092,#166365); +#166365 = DEFINITIONAL_REPRESENTATION('',(#166366),#166370); +#166366 = LINE('',#166367,#166368); +#166367 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166368 = VECTOR('',#166369,1.); +#166369 = DIRECTION('',(1.,0.E+000)); +#166370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166371 = ORIENTED_EDGE('',*,*,#166372,.F.); +#166372 = EDGE_CURVE('',#166373,#166350,#166375,.T.); +#166373 = VERTEX_POINT('',#166374); +#166374 = CARTESIAN_POINT('',(0.845,0.765,0.21)); +#166375 = SURFACE_CURVE('',#166376,(#166380,#166387),.PCURVE_S1.); +#166376 = LINE('',#166377,#166378); +#166377 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); +#166378 = VECTOR('',#166379,1.); +#166379 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166380 = PCURVE('',#161752,#166381); +#166381 = DEFINITIONAL_REPRESENTATION('',(#166382),#166386); +#166382 = LINE('',#166383,#166384); +#166383 = CARTESIAN_POINT('',(-0.21,-2.54)); +#166384 = VECTOR('',#166385,1.); +#166385 = DIRECTION('',(0.E+000,1.)); +#166386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166387 = PCURVE('',#166388,#166393); +#166388 = PLANE('',#166389); +#166389 = AXIS2_PLACEMENT_3D('',#166390,#166391,#166392); +#166390 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); +#166391 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166392 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166393 = DEFINITIONAL_REPRESENTATION('',(#166394),#166398); +#166394 = LINE('',#166395,#166396); +#166395 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166396 = VECTOR('',#166397,1.); +#166397 = DIRECTION('',(1.,0.E+000)); +#166398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166399 = ORIENTED_EDGE('',*,*,#166400,.F.); +#166400 = EDGE_CURVE('',#164993,#166373,#166401,.T.); +#166401 = SURFACE_CURVE('',#166402,(#166406,#166413),.PCURVE_S1.); +#166402 = LINE('',#166403,#166404); +#166403 = CARTESIAN_POINT('',(0.845,0.765,0.E+000)); +#166404 = VECTOR('',#166405,1.); +#166405 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166406 = PCURVE('',#161752,#166407); +#166407 = DEFINITIONAL_REPRESENTATION('',(#166408),#166412); +#166408 = LINE('',#166409,#166410); +#166409 = CARTESIAN_POINT('',(0.E+000,0.21)); +#166410 = VECTOR('',#166411,1.); +#166411 = DIRECTION('',(1.,0.E+000)); +#166412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#164125 = ORIENTED_EDGE('',*,*,#164126,.F.); -#164126 = EDGE_CURVE('',#164127,#164104,#164129,.T.); -#164127 = VERTEX_POINT('',#164128); -#164128 = CARTESIAN_POINT('',(-1.695,0.765,0.21)); -#164129 = SURFACE_CURVE('',#164130,(#164134,#164141),.PCURVE_S1.); -#164130 = LINE('',#164131,#164132); -#164131 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); -#164132 = VECTOR('',#164133,1.); -#164133 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164134 = PCURVE('',#159360,#164135); -#164135 = DEFINITIONAL_REPRESENTATION('',(#164136),#164140); -#164136 = LINE('',#164137,#164138); -#164137 = CARTESIAN_POINT('',(-0.21,-2.54)); -#164138 = VECTOR('',#164139,1.); -#164139 = DIRECTION('',(0.E+000,1.)); -#164140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164141 = PCURVE('',#164142,#164147); -#164142 = PLANE('',#164143); -#164143 = AXIS2_PLACEMENT_3D('',#164144,#164145,#164146); -#164144 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); -#164145 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164146 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164147 = DEFINITIONAL_REPRESENTATION('',(#164148),#164152); -#164148 = LINE('',#164149,#164150); -#164149 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164150 = VECTOR('',#164151,1.); -#164151 = DIRECTION('',(1.,0.E+000)); -#164152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164153 = ORIENTED_EDGE('',*,*,#164154,.F.); -#164154 = EDGE_CURVE('',#161289,#164127,#164155,.T.); -#164155 = SURFACE_CURVE('',#164156,(#164160,#164167),.PCURVE_S1.); -#164156 = LINE('',#164157,#164158); -#164157 = CARTESIAN_POINT('',(-1.695,0.765,0.E+000)); -#164158 = VECTOR('',#164159,1.); -#164159 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164160 = PCURVE('',#159360,#164161); -#164161 = DEFINITIONAL_REPRESENTATION('',(#164162),#164166); -#164162 = LINE('',#164163,#164164); -#164163 = CARTESIAN_POINT('',(0.E+000,-2.33)); -#164164 = VECTOR('',#164165,1.); -#164165 = DIRECTION('',(1.,0.E+000)); -#164166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164167 = PCURVE('',#160785,#164168); -#164168 = DEFINITIONAL_REPRESENTATION('',(#164169),#164173); -#164169 = LINE('',#164170,#164171); -#164170 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164171 = VECTOR('',#164172,1.); -#164172 = DIRECTION('',(1.,0.E+000)); -#164173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166413 = PCURVE('',#164489,#166414); +#166414 = DEFINITIONAL_REPRESENTATION('',(#166415),#166419); +#166415 = LINE('',#166416,#166417); +#166416 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166417 = VECTOR('',#166418,1.); +#166418 = DIRECTION('',(1.,0.E+000)); +#166419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#164174 = ORIENTED_EDGE('',*,*,#161315,.T.); -#164175 = ORIENTED_EDGE('',*,*,#164176,.F.); -#164176 = EDGE_CURVE('',#160638,#161261,#164177,.T.); -#164177 = SURFACE_CURVE('',#164178,(#164182,#164189),.PCURVE_S1.); -#164178 = LINE('',#164179,#164180); -#164179 = CARTESIAN_POINT('',(-2.115,0.765,0.E+000)); -#164180 = VECTOR('',#164181,1.); -#164181 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164182 = PCURVE('',#159360,#164183); -#164183 = DEFINITIONAL_REPRESENTATION('',(#164184),#164188); -#164184 = LINE('',#164185,#164186); -#164185 = CARTESIAN_POINT('',(0.E+000,-2.75)); -#164186 = VECTOR('',#164187,1.); -#164187 = DIRECTION('',(-1.,0.E+000)); -#164188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164189 = PCURVE('',#160134,#164190); -#164190 = DEFINITIONAL_REPRESENTATION('',(#164191),#164195); -#164191 = LINE('',#164192,#164193); -#164192 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164193 = VECTOR('',#164194,1.); -#164194 = DIRECTION('',(1.,0.E+000)); -#164195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164196 = ORIENTED_EDGE('',*,*,#160664,.T.); -#164197 = ORIENTED_EDGE('',*,*,#164198,.F.); -#164198 = EDGE_CURVE('',#164199,#160610,#164201,.T.); -#164199 = VERTEX_POINT('',#164200); -#164200 = CARTESIAN_POINT('',(-1.695,0.765,-0.21)); -#164201 = SURFACE_CURVE('',#164202,(#164206,#164213),.PCURVE_S1.); -#164202 = LINE('',#164203,#164204); -#164203 = CARTESIAN_POINT('',(-1.695,0.765,0.E+000)); -#164204 = VECTOR('',#164205,1.); -#164205 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164206 = PCURVE('',#159360,#164207); -#164207 = DEFINITIONAL_REPRESENTATION('',(#164208),#164212); -#164208 = LINE('',#164209,#164210); -#164209 = CARTESIAN_POINT('',(0.E+000,-2.33)); -#164210 = VECTOR('',#164211,1.); -#164211 = DIRECTION('',(1.,0.E+000)); -#164212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164213 = PCURVE('',#160081,#164214); -#164214 = DEFINITIONAL_REPRESENTATION('',(#164215),#164219); -#164215 = LINE('',#164216,#164217); -#164216 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164217 = VECTOR('',#164218,1.); -#164218 = DIRECTION('',(1.,0.E+000)); -#164219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164220 = ORIENTED_EDGE('',*,*,#164221,.F.); -#164221 = EDGE_CURVE('',#164222,#164199,#164224,.T.); -#164222 = VERTEX_POINT('',#164223); -#164223 = CARTESIAN_POINT('',(-0.845,0.765,-0.21)); -#164224 = SURFACE_CURVE('',#164225,(#164229,#164236),.PCURVE_S1.); -#164225 = LINE('',#164226,#164227); -#164226 = CARTESIAN_POINT('',(-1.905,0.765,-0.21)); -#164227 = VECTOR('',#164228,1.); -#164228 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164229 = PCURVE('',#159360,#164230); -#164230 = DEFINITIONAL_REPRESENTATION('',(#164231),#164235); -#164231 = LINE('',#164232,#164233); -#164232 = CARTESIAN_POINT('',(0.21,-2.54)); -#164233 = VECTOR('',#164234,1.); -#164234 = DIRECTION('',(0.E+000,-1.)); -#164235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164236 = PCURVE('',#164237,#164242); -#164237 = PLANE('',#164238); -#164238 = AXIS2_PLACEMENT_3D('',#164239,#164240,#164241); -#164239 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); -#164240 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164241 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164242 = DEFINITIONAL_REPRESENTATION('',(#164243),#164247); -#164243 = LINE('',#164244,#164245); -#164244 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164245 = VECTOR('',#164246,1.); -#164246 = DIRECTION('',(1.,0.E+000)); -#164247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164248 = ORIENTED_EDGE('',*,*,#164249,.F.); -#164249 = EDGE_CURVE('',#159982,#164222,#164250,.T.); -#164250 = SURFACE_CURVE('',#164251,(#164255,#164262),.PCURVE_S1.); -#164251 = LINE('',#164252,#164253); -#164252 = CARTESIAN_POINT('',(-0.845,0.765,0.E+000)); -#164253 = VECTOR('',#164254,1.); -#164254 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164255 = PCURVE('',#159360,#164256); -#164256 = DEFINITIONAL_REPRESENTATION('',(#164257),#164261); -#164257 = LINE('',#164258,#164259); -#164258 = CARTESIAN_POINT('',(0.E+000,-1.48)); -#164259 = VECTOR('',#164260,1.); -#164260 = DIRECTION('',(-1.,0.E+000)); -#164261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164262 = PCURVE('',#159478,#164263); -#164263 = DEFINITIONAL_REPRESENTATION('',(#164264),#164268); -#164264 = LINE('',#164265,#164266); -#164265 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164266 = VECTOR('',#164267,1.); -#164267 = DIRECTION('',(1.,0.E+000)); -#164268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164269 = ORIENTED_EDGE('',*,*,#160008,.T.); -#164270 = ORIENTED_EDGE('',*,*,#164271,.F.); -#164271 = EDGE_CURVE('',#164272,#159954,#164274,.T.); -#164272 = VERTEX_POINT('',#164273); -#164273 = CARTESIAN_POINT('',(-0.425,0.765,-0.21)); -#164274 = SURFACE_CURVE('',#164275,(#164279,#164286),.PCURVE_S1.); -#164275 = LINE('',#164276,#164277); -#164276 = CARTESIAN_POINT('',(-0.425,0.765,0.E+000)); -#164277 = VECTOR('',#164278,1.); -#164278 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164279 = PCURVE('',#159360,#164280); -#164280 = DEFINITIONAL_REPRESENTATION('',(#164281),#164285); -#164281 = LINE('',#164282,#164283); -#164282 = CARTESIAN_POINT('',(0.E+000,-1.06)); -#164283 = VECTOR('',#164284,1.); -#164284 = DIRECTION('',(1.,0.E+000)); -#164285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164286 = PCURVE('',#159425,#164287); -#164287 = DEFINITIONAL_REPRESENTATION('',(#164288),#164292); -#164288 = LINE('',#164289,#164290); -#164289 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164290 = VECTOR('',#164291,1.); -#164291 = DIRECTION('',(1.,0.E+000)); -#164292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164293 = ORIENTED_EDGE('',*,*,#164294,.F.); -#164294 = EDGE_CURVE('',#164295,#164272,#164297,.T.); -#164295 = VERTEX_POINT('',#164296); -#164296 = CARTESIAN_POINT('',(0.425,0.765,-0.21)); -#164297 = SURFACE_CURVE('',#164298,(#164302,#164309),.PCURVE_S1.); -#164298 = LINE('',#164299,#164300); -#164299 = CARTESIAN_POINT('',(-1.905,0.765,-0.21)); -#164300 = VECTOR('',#164301,1.); -#164301 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164302 = PCURVE('',#159360,#164303); -#164303 = DEFINITIONAL_REPRESENTATION('',(#164304),#164308); -#164304 = LINE('',#164305,#164306); -#164305 = CARTESIAN_POINT('',(0.21,-2.54)); -#164306 = VECTOR('',#164307,1.); -#164307 = DIRECTION('',(0.E+000,-1.)); -#164308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164309 = PCURVE('',#164310,#164315); -#164310 = PLANE('',#164311); -#164311 = AXIS2_PLACEMENT_3D('',#164312,#164313,#164314); -#164312 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); -#164313 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164314 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164315 = DEFINITIONAL_REPRESENTATION('',(#164316),#164320); -#164316 = LINE('',#164317,#164318); -#164317 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164318 = VECTOR('',#164319,1.); -#164319 = DIRECTION('',(1.,0.E+000)); -#164320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164321 = ORIENTED_EDGE('',*,*,#164322,.F.); -#164322 = EDGE_CURVE('',#159321,#164295,#164323,.T.); -#164323 = SURFACE_CURVE('',#164324,(#164328,#164335),.PCURVE_S1.); -#164324 = LINE('',#164325,#164326); -#164325 = CARTESIAN_POINT('',(0.425,0.765,0.E+000)); -#164326 = VECTOR('',#164327,1.); -#164327 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164328 = PCURVE('',#159360,#164329); -#164329 = DEFINITIONAL_REPRESENTATION('',(#164330),#164334); -#164330 = LINE('',#164331,#164332); -#164331 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#164332 = VECTOR('',#164333,1.); -#164333 = DIRECTION('',(-1.,0.E+000)); -#164334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164335 = PCURVE('',#158817,#164336); -#164336 = DEFINITIONAL_REPRESENTATION('',(#164337),#164341); -#164337 = LINE('',#164338,#164339); -#164338 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164339 = VECTOR('',#164340,1.); -#164340 = DIRECTION('',(1.,0.E+000)); -#164341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164342 = ORIENTED_EDGE('',*,*,#159347,.T.); -#164343 = ORIENTED_EDGE('',*,*,#164344,.F.); -#164344 = EDGE_CURVE('',#164345,#159293,#164347,.T.); -#164345 = VERTEX_POINT('',#164346); -#164346 = CARTESIAN_POINT('',(0.845,0.765,-0.21)); -#164347 = SURFACE_CURVE('',#164348,(#164352,#164359),.PCURVE_S1.); -#164348 = LINE('',#164349,#164350); -#164349 = CARTESIAN_POINT('',(0.845,0.765,0.E+000)); -#164350 = VECTOR('',#164351,1.); -#164351 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164352 = PCURVE('',#159360,#164353); -#164353 = DEFINITIONAL_REPRESENTATION('',(#164354),#164358); -#164354 = LINE('',#164355,#164356); -#164355 = CARTESIAN_POINT('',(0.E+000,0.21)); -#164356 = VECTOR('',#164357,1.); -#164357 = DIRECTION('',(1.,0.E+000)); -#164358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164359 = PCURVE('',#158764,#164360); -#164360 = DEFINITIONAL_REPRESENTATION('',(#164361),#164365); -#164361 = LINE('',#164362,#164363); -#164362 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164363 = VECTOR('',#164364,1.); -#164364 = DIRECTION('',(1.,0.E+000)); -#164365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164366 = ORIENTED_EDGE('',*,*,#164367,.T.); -#164367 = EDGE_CURVE('',#164345,#164368,#164370,.T.); -#164368 = VERTEX_POINT('',#164369); -#164369 = CARTESIAN_POINT('',(1.695,0.765,-0.21)); -#164370 = SURFACE_CURVE('',#164371,(#164375,#164382),.PCURVE_S1.); -#164371 = LINE('',#164372,#164373); -#164372 = CARTESIAN_POINT('',(0.635,0.765,-0.21)); -#164373 = VECTOR('',#164374,1.); -#164374 = DIRECTION('',(1.,0.E+000,0.E+000)); -#164375 = PCURVE('',#159360,#164376); -#164376 = DEFINITIONAL_REPRESENTATION('',(#164377),#164381); -#164377 = LINE('',#164378,#164379); -#164378 = CARTESIAN_POINT('',(0.21,0.E+000)); -#164379 = VECTOR('',#164380,1.); -#164380 = DIRECTION('',(0.E+000,1.)); -#164381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166420 = ORIENTED_EDGE('',*,*,#165019,.T.); +#166421 = ORIENTED_EDGE('',*,*,#166422,.F.); +#166422 = EDGE_CURVE('',#166423,#164965,#166425,.T.); +#166423 = VERTEX_POINT('',#166424); +#166424 = CARTESIAN_POINT('',(0.425,0.765,0.21)); +#166425 = SURFACE_CURVE('',#166426,(#166430,#166437),.PCURVE_S1.); +#166426 = LINE('',#166427,#166428); +#166427 = CARTESIAN_POINT('',(0.425,0.765,0.E+000)); +#166428 = VECTOR('',#166429,1.); +#166429 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166430 = PCURVE('',#161752,#166431); +#166431 = DEFINITIONAL_REPRESENTATION('',(#166432),#166436); +#166432 = LINE('',#166433,#166434); +#166433 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#166434 = VECTOR('',#166435,1.); +#166435 = DIRECTION('',(-1.,0.E+000)); +#166436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166437 = PCURVE('',#164436,#166438); +#166438 = DEFINITIONAL_REPRESENTATION('',(#166439),#166443); +#166439 = LINE('',#166440,#166441); +#166440 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166441 = VECTOR('',#166442,1.); +#166442 = DIRECTION('',(1.,0.E+000)); +#166443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166444 = ORIENTED_EDGE('',*,*,#166445,.F.); +#166445 = EDGE_CURVE('',#166446,#166423,#166448,.T.); +#166446 = VERTEX_POINT('',#166447); +#166447 = CARTESIAN_POINT('',(-0.425,0.765,0.21)); +#166448 = SURFACE_CURVE('',#166449,(#166453,#166460),.PCURVE_S1.); +#166449 = LINE('',#166450,#166451); +#166450 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); +#166451 = VECTOR('',#166452,1.); +#166452 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166453 = PCURVE('',#161752,#166454); +#166454 = DEFINITIONAL_REPRESENTATION('',(#166455),#166459); +#166455 = LINE('',#166456,#166457); +#166456 = CARTESIAN_POINT('',(-0.21,-2.54)); +#166457 = VECTOR('',#166458,1.); +#166458 = DIRECTION('',(0.E+000,1.)); +#166459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166460 = PCURVE('',#166461,#166466); +#166461 = PLANE('',#166462); +#166462 = AXIS2_PLACEMENT_3D('',#166463,#166464,#166465); +#166463 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); +#166464 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166465 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166466 = DEFINITIONAL_REPRESENTATION('',(#166467),#166471); +#166467 = LINE('',#166468,#166469); +#166468 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166469 = VECTOR('',#166470,1.); +#166470 = DIRECTION('',(1.,0.E+000)); +#166471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166472 = ORIENTED_EDGE('',*,*,#166473,.F.); +#166473 = EDGE_CURVE('',#164337,#166446,#166474,.T.); +#166474 = SURFACE_CURVE('',#166475,(#166479,#166486),.PCURVE_S1.); +#166475 = LINE('',#166476,#166477); +#166476 = CARTESIAN_POINT('',(-0.425,0.765,0.E+000)); +#166477 = VECTOR('',#166478,1.); +#166478 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166479 = PCURVE('',#161752,#166480); +#166480 = DEFINITIONAL_REPRESENTATION('',(#166481),#166485); +#166481 = LINE('',#166482,#166483); +#166482 = CARTESIAN_POINT('',(0.E+000,-1.06)); +#166483 = VECTOR('',#166484,1.); +#166484 = DIRECTION('',(1.,0.E+000)); +#166485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166486 = PCURVE('',#163833,#166487); +#166487 = DEFINITIONAL_REPRESENTATION('',(#166488),#166492); +#166488 = LINE('',#166489,#166490); +#166489 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166490 = VECTOR('',#166491,1.); +#166491 = DIRECTION('',(1.,0.E+000)); +#166492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166493 = ORIENTED_EDGE('',*,*,#164363,.T.); +#166494 = ORIENTED_EDGE('',*,*,#166495,.F.); +#166495 = EDGE_CURVE('',#166496,#164309,#166498,.T.); +#166496 = VERTEX_POINT('',#166497); +#166497 = CARTESIAN_POINT('',(-0.845,0.765,0.21)); +#166498 = SURFACE_CURVE('',#166499,(#166503,#166510),.PCURVE_S1.); +#166499 = LINE('',#166500,#166501); +#166500 = CARTESIAN_POINT('',(-0.845,0.765,0.E+000)); +#166501 = VECTOR('',#166502,1.); +#166502 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166503 = PCURVE('',#161752,#166504); +#166504 = DEFINITIONAL_REPRESENTATION('',(#166505),#166509); +#166505 = LINE('',#166506,#166507); +#166506 = CARTESIAN_POINT('',(0.E+000,-1.48)); +#166507 = VECTOR('',#166508,1.); +#166508 = DIRECTION('',(-1.,0.E+000)); +#166509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166510 = PCURVE('',#163780,#166511); +#166511 = DEFINITIONAL_REPRESENTATION('',(#166512),#166516); +#166512 = LINE('',#166513,#166514); +#166513 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166514 = VECTOR('',#166515,1.); +#166515 = DIRECTION('',(1.,0.E+000)); +#166516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166517 = ORIENTED_EDGE('',*,*,#166518,.F.); +#166518 = EDGE_CURVE('',#166519,#166496,#166521,.T.); +#166519 = VERTEX_POINT('',#166520); +#166520 = CARTESIAN_POINT('',(-1.695,0.765,0.21)); +#166521 = SURFACE_CURVE('',#166522,(#166526,#166533),.PCURVE_S1.); +#166522 = LINE('',#166523,#166524); +#166523 = CARTESIAN_POINT('',(-1.905,0.765,0.21)); +#166524 = VECTOR('',#166525,1.); +#166525 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166526 = PCURVE('',#161752,#166527); +#166527 = DEFINITIONAL_REPRESENTATION('',(#166528),#166532); +#166528 = LINE('',#166529,#166530); +#166529 = CARTESIAN_POINT('',(-0.21,-2.54)); +#166530 = VECTOR('',#166531,1.); +#166531 = DIRECTION('',(0.E+000,1.)); +#166532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#164382 = PCURVE('',#164383,#164388); -#164383 = PLANE('',#164384); -#164384 = AXIS2_PLACEMENT_3D('',#164385,#164386,#164387); -#164385 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); -#164386 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164387 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164388 = DEFINITIONAL_REPRESENTATION('',(#164389),#164393); -#164389 = LINE('',#164390,#164391); -#164390 = CARTESIAN_POINT('',(-2.54,-0.11)); -#164391 = VECTOR('',#164392,1.); -#164392 = DIRECTION('',(-1.,0.E+000)); -#164393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164394 = ORIENTED_EDGE('',*,*,#164395,.F.); -#164395 = EDGE_CURVE('',#163908,#164368,#164396,.T.); -#164396 = SURFACE_CURVE('',#164397,(#164401,#164408),.PCURVE_S1.); -#164397 = LINE('',#164398,#164399); -#164398 = CARTESIAN_POINT('',(1.695,0.765,0.E+000)); -#164399 = VECTOR('',#164400,1.); -#164400 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164401 = PCURVE('',#159360,#164402); -#164402 = DEFINITIONAL_REPRESENTATION('',(#164403),#164407); -#164403 = LINE('',#164404,#164405); -#164404 = CARTESIAN_POINT('',(0.E+000,1.06)); -#164405 = VECTOR('',#164406,1.); -#164406 = DIRECTION('',(-1.,0.E+000)); -#164407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#166533 = PCURVE('',#166534,#166539); +#166534 = PLANE('',#166535); +#166535 = AXIS2_PLACEMENT_3D('',#166536,#166537,#166538); +#166536 = CARTESIAN_POINT('',(-1.905,0.875,0.21)); +#166537 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166538 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166539 = DEFINITIONAL_REPRESENTATION('',(#166540),#166544); +#166540 = LINE('',#166541,#166542); +#166541 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166542 = VECTOR('',#166543,1.); +#166543 = DIRECTION('',(1.,0.E+000)); +#166544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166545 = ORIENTED_EDGE('',*,*,#166546,.F.); +#166546 = EDGE_CURVE('',#163681,#166519,#166547,.T.); +#166547 = SURFACE_CURVE('',#166548,(#166552,#166559),.PCURVE_S1.); +#166548 = LINE('',#166549,#166550); +#166549 = CARTESIAN_POINT('',(-1.695,0.765,0.E+000)); +#166550 = VECTOR('',#166551,1.); +#166551 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166552 = PCURVE('',#161752,#166553); +#166553 = DEFINITIONAL_REPRESENTATION('',(#166554),#166558); +#166554 = LINE('',#166555,#166556); +#166555 = CARTESIAN_POINT('',(0.E+000,-2.33)); +#166556 = VECTOR('',#166557,1.); +#166557 = DIRECTION('',(1.,0.E+000)); +#166558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166559 = PCURVE('',#163177,#166560); +#166560 = DEFINITIONAL_REPRESENTATION('',(#166561),#166565); +#166561 = LINE('',#166562,#166563); +#166562 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166563 = VECTOR('',#166564,1.); +#166564 = DIRECTION('',(1.,0.E+000)); +#166565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166566 = ORIENTED_EDGE('',*,*,#163707,.T.); +#166567 = ORIENTED_EDGE('',*,*,#166568,.F.); +#166568 = EDGE_CURVE('',#163030,#163653,#166569,.T.); +#166569 = SURFACE_CURVE('',#166570,(#166574,#166581),.PCURVE_S1.); +#166570 = LINE('',#166571,#166572); +#166571 = CARTESIAN_POINT('',(-2.115,0.765,0.E+000)); +#166572 = VECTOR('',#166573,1.); +#166573 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166574 = PCURVE('',#161752,#166575); +#166575 = DEFINITIONAL_REPRESENTATION('',(#166576),#166580); +#166576 = LINE('',#166577,#166578); +#166577 = CARTESIAN_POINT('',(0.E+000,-2.75)); +#166578 = VECTOR('',#166579,1.); +#166579 = DIRECTION('',(-1.,0.E+000)); +#166580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166581 = PCURVE('',#162526,#166582); +#166582 = DEFINITIONAL_REPRESENTATION('',(#166583),#166587); +#166583 = LINE('',#166584,#166585); +#166584 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166585 = VECTOR('',#166586,1.); +#166586 = DIRECTION('',(1.,0.E+000)); +#166587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166588 = ORIENTED_EDGE('',*,*,#163056,.T.); +#166589 = ORIENTED_EDGE('',*,*,#166590,.F.); +#166590 = EDGE_CURVE('',#166591,#163002,#166593,.T.); +#166591 = VERTEX_POINT('',#166592); +#166592 = CARTESIAN_POINT('',(-1.695,0.765,-0.21)); +#166593 = SURFACE_CURVE('',#166594,(#166598,#166605),.PCURVE_S1.); +#166594 = LINE('',#166595,#166596); +#166595 = CARTESIAN_POINT('',(-1.695,0.765,0.E+000)); +#166596 = VECTOR('',#166597,1.); +#166597 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166598 = PCURVE('',#161752,#166599); +#166599 = DEFINITIONAL_REPRESENTATION('',(#166600),#166604); +#166600 = LINE('',#166601,#166602); +#166601 = CARTESIAN_POINT('',(0.E+000,-2.33)); +#166602 = VECTOR('',#166603,1.); +#166603 = DIRECTION('',(1.,0.E+000)); +#166604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166605 = PCURVE('',#162473,#166606); +#166606 = DEFINITIONAL_REPRESENTATION('',(#166607),#166611); +#166607 = LINE('',#166608,#166609); +#166608 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166609 = VECTOR('',#166610,1.); +#166610 = DIRECTION('',(1.,0.E+000)); +#166611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166612 = ORIENTED_EDGE('',*,*,#166613,.F.); +#166613 = EDGE_CURVE('',#166614,#166591,#166616,.T.); +#166614 = VERTEX_POINT('',#166615); +#166615 = CARTESIAN_POINT('',(-0.845,0.765,-0.21)); +#166616 = SURFACE_CURVE('',#166617,(#166621,#166628),.PCURVE_S1.); +#166617 = LINE('',#166618,#166619); +#166618 = CARTESIAN_POINT('',(-1.905,0.765,-0.21)); +#166619 = VECTOR('',#166620,1.); +#166620 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166621 = PCURVE('',#161752,#166622); +#166622 = DEFINITIONAL_REPRESENTATION('',(#166623),#166627); +#166623 = LINE('',#166624,#166625); +#166624 = CARTESIAN_POINT('',(0.21,-2.54)); +#166625 = VECTOR('',#166626,1.); +#166626 = DIRECTION('',(0.E+000,-1.)); +#166627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166628 = PCURVE('',#166629,#166634); +#166629 = PLANE('',#166630); +#166630 = AXIS2_PLACEMENT_3D('',#166631,#166632,#166633); +#166631 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); +#166632 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166633 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166634 = DEFINITIONAL_REPRESENTATION('',(#166635),#166639); +#166635 = LINE('',#166636,#166637); +#166636 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166637 = VECTOR('',#166638,1.); +#166638 = DIRECTION('',(1.,0.E+000)); +#166639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166640 = ORIENTED_EDGE('',*,*,#166641,.F.); +#166641 = EDGE_CURVE('',#162374,#166614,#166642,.T.); +#166642 = SURFACE_CURVE('',#166643,(#166647,#166654),.PCURVE_S1.); +#166643 = LINE('',#166644,#166645); +#166644 = CARTESIAN_POINT('',(-0.845,0.765,0.E+000)); +#166645 = VECTOR('',#166646,1.); +#166646 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166647 = PCURVE('',#161752,#166648); +#166648 = DEFINITIONAL_REPRESENTATION('',(#166649),#166653); +#166649 = LINE('',#166650,#166651); +#166650 = CARTESIAN_POINT('',(0.E+000,-1.48)); +#166651 = VECTOR('',#166652,1.); +#166652 = DIRECTION('',(-1.,0.E+000)); +#166653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166654 = PCURVE('',#161870,#166655); +#166655 = DEFINITIONAL_REPRESENTATION('',(#166656),#166660); +#166656 = LINE('',#166657,#166658); +#166657 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166658 = VECTOR('',#166659,1.); +#166659 = DIRECTION('',(1.,0.E+000)); +#166660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166661 = ORIENTED_EDGE('',*,*,#162400,.T.); +#166662 = ORIENTED_EDGE('',*,*,#166663,.F.); +#166663 = EDGE_CURVE('',#166664,#162346,#166666,.T.); +#166664 = VERTEX_POINT('',#166665); +#166665 = CARTESIAN_POINT('',(-0.425,0.765,-0.21)); +#166666 = SURFACE_CURVE('',#166667,(#166671,#166678),.PCURVE_S1.); +#166667 = LINE('',#166668,#166669); +#166668 = CARTESIAN_POINT('',(-0.425,0.765,0.E+000)); +#166669 = VECTOR('',#166670,1.); +#166670 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166671 = PCURVE('',#161752,#166672); +#166672 = DEFINITIONAL_REPRESENTATION('',(#166673),#166677); +#166673 = LINE('',#166674,#166675); +#166674 = CARTESIAN_POINT('',(0.E+000,-1.06)); +#166675 = VECTOR('',#166676,1.); +#166676 = DIRECTION('',(1.,0.E+000)); +#166677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166678 = PCURVE('',#161817,#166679); +#166679 = DEFINITIONAL_REPRESENTATION('',(#166680),#166684); +#166680 = LINE('',#166681,#166682); +#166681 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166682 = VECTOR('',#166683,1.); +#166683 = DIRECTION('',(1.,0.E+000)); +#166684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166685 = ORIENTED_EDGE('',*,*,#166686,.F.); +#166686 = EDGE_CURVE('',#166687,#166664,#166689,.T.); +#166687 = VERTEX_POINT('',#166688); +#166688 = CARTESIAN_POINT('',(0.425,0.765,-0.21)); +#166689 = SURFACE_CURVE('',#166690,(#166694,#166701),.PCURVE_S1.); +#166690 = LINE('',#166691,#166692); +#166691 = CARTESIAN_POINT('',(-1.905,0.765,-0.21)); +#166692 = VECTOR('',#166693,1.); +#166693 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166694 = PCURVE('',#161752,#166695); +#166695 = DEFINITIONAL_REPRESENTATION('',(#166696),#166700); +#166696 = LINE('',#166697,#166698); +#166697 = CARTESIAN_POINT('',(0.21,-2.54)); +#166698 = VECTOR('',#166699,1.); +#166699 = DIRECTION('',(0.E+000,-1.)); +#166700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166701 = PCURVE('',#166702,#166707); +#166702 = PLANE('',#166703); +#166703 = AXIS2_PLACEMENT_3D('',#166704,#166705,#166706); +#166704 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); +#166705 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166706 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166707 = DEFINITIONAL_REPRESENTATION('',(#166708),#166712); +#166708 = LINE('',#166709,#166710); +#166709 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166710 = VECTOR('',#166711,1.); +#166711 = DIRECTION('',(1.,0.E+000)); +#166712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166713 = ORIENTED_EDGE('',*,*,#166714,.F.); +#166714 = EDGE_CURVE('',#161713,#166687,#166715,.T.); +#166715 = SURFACE_CURVE('',#166716,(#166720,#166727),.PCURVE_S1.); +#166716 = LINE('',#166717,#166718); +#166717 = CARTESIAN_POINT('',(0.425,0.765,0.E+000)); +#166718 = VECTOR('',#166719,1.); +#166719 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166720 = PCURVE('',#161752,#166721); +#166721 = DEFINITIONAL_REPRESENTATION('',(#166722),#166726); +#166722 = LINE('',#166723,#166724); +#166723 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#166724 = VECTOR('',#166725,1.); +#166725 = DIRECTION('',(-1.,0.E+000)); +#166726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#164408 = PCURVE('',#163404,#164409); -#164409 = DEFINITIONAL_REPRESENTATION('',(#164410),#164414); -#164410 = LINE('',#164411,#164412); -#164411 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164412 = VECTOR('',#164413,1.); -#164413 = DIRECTION('',(1.,0.E+000)); -#164414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164415 = ORIENTED_EDGE('',*,*,#163934,.T.); -#164416 = ORIENTED_EDGE('',*,*,#164417,.F.); -#164417 = EDGE_CURVE('',#163257,#163880,#164418,.T.); -#164418 = SURFACE_CURVE('',#164419,(#164423,#164430),.PCURVE_S1.); -#164419 = LINE('',#164420,#164421); -#164420 = CARTESIAN_POINT('',(2.115,0.765,0.E+000)); -#164421 = VECTOR('',#164422,1.); -#164422 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164423 = PCURVE('',#159360,#164424); -#164424 = DEFINITIONAL_REPRESENTATION('',(#164425),#164429); -#164425 = LINE('',#164426,#164427); -#164426 = CARTESIAN_POINT('',(0.E+000,1.48)); -#164427 = VECTOR('',#164428,1.); -#164428 = DIRECTION('',(1.,0.E+000)); -#164429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164430 = PCURVE('',#162753,#164431); -#164431 = DEFINITIONAL_REPRESENTATION('',(#164432),#164436); -#164432 = LINE('',#164433,#164434); -#164433 = CARTESIAN_POINT('',(0.E+000,-0.11)); -#164434 = VECTOR('',#164435,1.); -#164435 = DIRECTION('',(1.,0.E+000)); -#164436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164437 = ORIENTED_EDGE('',*,*,#163283,.T.); -#164438 = ADVANCED_FACE('',(#164439),#158764,.T.); -#164439 = FACE_BOUND('',#164440,.T.); -#164440 = EDGE_LOOP('',(#164441,#164468,#164496,#164517,#164518,#164519, - #164520,#164521,#164522,#164523,#164524,#164525)); -#164441 = ORIENTED_EDGE('',*,*,#164442,.F.); -#164442 = EDGE_CURVE('',#164443,#158715,#164445,.T.); -#164443 = VERTEX_POINT('',#164444); -#164444 = CARTESIAN_POINT('',(0.845,0.985,-2.141803043818)); -#164445 = SURFACE_CURVE('',#164446,(#164451,#164462),.PCURVE_S1.); -#164446 = CIRCLE('',#164447,0.32); -#164447 = AXIS2_PLACEMENT_3D('',#164448,#164449,#164450); -#164448 = CARTESIAN_POINT('',(0.845,0.665,-2.141803043818)); -#164449 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164450 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164451 = PCURVE('',#158764,#164452); -#164452 = DEFINITIONAL_REPRESENTATION('',(#164453),#164461); -#164453 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164454,#164455,#164456, - #164457,#164458,#164459,#164460),.UNSPECIFIED.,.T.,.F.) +#166727 = PCURVE('',#161209,#166728); +#166728 = DEFINITIONAL_REPRESENTATION('',(#166729),#166733); +#166729 = LINE('',#166730,#166731); +#166730 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166731 = VECTOR('',#166732,1.); +#166732 = DIRECTION('',(1.,0.E+000)); +#166733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166734 = ORIENTED_EDGE('',*,*,#161739,.T.); +#166735 = ORIENTED_EDGE('',*,*,#166736,.F.); +#166736 = EDGE_CURVE('',#166737,#161685,#166739,.T.); +#166737 = VERTEX_POINT('',#166738); +#166738 = CARTESIAN_POINT('',(0.845,0.765,-0.21)); +#166739 = SURFACE_CURVE('',#166740,(#166744,#166751),.PCURVE_S1.); +#166740 = LINE('',#166741,#166742); +#166741 = CARTESIAN_POINT('',(0.845,0.765,0.E+000)); +#166742 = VECTOR('',#166743,1.); +#166743 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166744 = PCURVE('',#161752,#166745); +#166745 = DEFINITIONAL_REPRESENTATION('',(#166746),#166750); +#166746 = LINE('',#166747,#166748); +#166747 = CARTESIAN_POINT('',(0.E+000,0.21)); +#166748 = VECTOR('',#166749,1.); +#166749 = DIRECTION('',(1.,0.E+000)); +#166750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166751 = PCURVE('',#161156,#166752); +#166752 = DEFINITIONAL_REPRESENTATION('',(#166753),#166757); +#166753 = LINE('',#166754,#166755); +#166754 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166755 = VECTOR('',#166756,1.); +#166756 = DIRECTION('',(1.,0.E+000)); +#166757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166758 = ORIENTED_EDGE('',*,*,#166759,.T.); +#166759 = EDGE_CURVE('',#166737,#166760,#166762,.T.); +#166760 = VERTEX_POINT('',#166761); +#166761 = CARTESIAN_POINT('',(1.695,0.765,-0.21)); +#166762 = SURFACE_CURVE('',#166763,(#166767,#166774),.PCURVE_S1.); +#166763 = LINE('',#166764,#166765); +#166764 = CARTESIAN_POINT('',(0.635,0.765,-0.21)); +#166765 = VECTOR('',#166766,1.); +#166766 = DIRECTION('',(1.,0.E+000,0.E+000)); +#166767 = PCURVE('',#161752,#166768); +#166768 = DEFINITIONAL_REPRESENTATION('',(#166769),#166773); +#166769 = LINE('',#166770,#166771); +#166770 = CARTESIAN_POINT('',(0.21,0.E+000)); +#166771 = VECTOR('',#166772,1.); +#166772 = DIRECTION('',(0.E+000,1.)); +#166773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166774 = PCURVE('',#166775,#166780); +#166775 = PLANE('',#166776); +#166776 = AXIS2_PLACEMENT_3D('',#166777,#166778,#166779); +#166777 = CARTESIAN_POINT('',(-1.905,0.875,-0.21)); +#166778 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166779 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166780 = DEFINITIONAL_REPRESENTATION('',(#166781),#166785); +#166781 = LINE('',#166782,#166783); +#166782 = CARTESIAN_POINT('',(-2.54,-0.11)); +#166783 = VECTOR('',#166784,1.); +#166784 = DIRECTION('',(-1.,0.E+000)); +#166785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166786 = ORIENTED_EDGE('',*,*,#166787,.F.); +#166787 = EDGE_CURVE('',#166300,#166760,#166788,.T.); +#166788 = SURFACE_CURVE('',#166789,(#166793,#166800),.PCURVE_S1.); +#166789 = LINE('',#166790,#166791); +#166790 = CARTESIAN_POINT('',(1.695,0.765,0.E+000)); +#166791 = VECTOR('',#166792,1.); +#166792 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166793 = PCURVE('',#161752,#166794); +#166794 = DEFINITIONAL_REPRESENTATION('',(#166795),#166799); +#166795 = LINE('',#166796,#166797); +#166796 = CARTESIAN_POINT('',(0.E+000,1.06)); +#166797 = VECTOR('',#166798,1.); +#166798 = DIRECTION('',(-1.,0.E+000)); +#166799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166800 = PCURVE('',#165796,#166801); +#166801 = DEFINITIONAL_REPRESENTATION('',(#166802),#166806); +#166802 = LINE('',#166803,#166804); +#166803 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166804 = VECTOR('',#166805,1.); +#166805 = DIRECTION('',(1.,0.E+000)); +#166806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166807 = ORIENTED_EDGE('',*,*,#166326,.T.); +#166808 = ORIENTED_EDGE('',*,*,#166809,.F.); +#166809 = EDGE_CURVE('',#165649,#166272,#166810,.T.); +#166810 = SURFACE_CURVE('',#166811,(#166815,#166822),.PCURVE_S1.); +#166811 = LINE('',#166812,#166813); +#166812 = CARTESIAN_POINT('',(2.115,0.765,0.E+000)); +#166813 = VECTOR('',#166814,1.); +#166814 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166815 = PCURVE('',#161752,#166816); +#166816 = DEFINITIONAL_REPRESENTATION('',(#166817),#166821); +#166817 = LINE('',#166818,#166819); +#166818 = CARTESIAN_POINT('',(0.E+000,1.48)); +#166819 = VECTOR('',#166820,1.); +#166820 = DIRECTION('',(1.,0.E+000)); +#166821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166822 = PCURVE('',#165145,#166823); +#166823 = DEFINITIONAL_REPRESENTATION('',(#166824),#166828); +#166824 = LINE('',#166825,#166826); +#166825 = CARTESIAN_POINT('',(0.E+000,-0.11)); +#166826 = VECTOR('',#166827,1.); +#166827 = DIRECTION('',(1.,0.E+000)); +#166828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166829 = ORIENTED_EDGE('',*,*,#165675,.T.); +#166830 = ADVANCED_FACE('',(#166831),#161156,.T.); +#166831 = FACE_BOUND('',#166832,.T.); +#166832 = EDGE_LOOP('',(#166833,#166860,#166888,#166909,#166910,#166911, + #166912,#166913,#166914,#166915,#166916,#166917)); +#166833 = ORIENTED_EDGE('',*,*,#166834,.F.); +#166834 = EDGE_CURVE('',#166835,#161107,#166837,.T.); +#166835 = VERTEX_POINT('',#166836); +#166836 = CARTESIAN_POINT('',(0.845,0.985,-2.141803043818)); +#166837 = SURFACE_CURVE('',#166838,(#166843,#166854),.PCURVE_S1.); +#166838 = CIRCLE('',#166839,0.32); +#166839 = AXIS2_PLACEMENT_3D('',#166840,#166841,#166842); +#166840 = CARTESIAN_POINT('',(0.845,0.665,-2.141803043818)); +#166841 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166842 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166843 = PCURVE('',#161156,#166844); +#166844 = DEFINITIONAL_REPRESENTATION('',(#166845),#166853); +#166845 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#166846,#166847,#166848, + #166849,#166850,#166851,#166852),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#164454 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164455 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#164456 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#164457 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#164458 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#164459 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#164460 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164462 = PCURVE('',#158737,#164463); -#164463 = DEFINITIONAL_REPRESENTATION('',(#164464),#164467); -#164464 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164465,#164466), +#166846 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#166847 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#166848 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#166849 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#166850 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#166851 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#166852 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#166853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166854 = PCURVE('',#161129,#166855); +#166855 = DEFINITIONAL_REPRESENTATION('',(#166856),#166859); +#166856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166857,#166858), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#164465 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164466 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#164467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164468 = ORIENTED_EDGE('',*,*,#164469,.F.); -#164469 = EDGE_CURVE('',#164470,#164443,#164472,.T.); -#164470 = VERTEX_POINT('',#164471); -#164471 = CARTESIAN_POINT('',(0.845,0.985,-0.21)); -#164472 = SURFACE_CURVE('',#164473,(#164477,#164484),.PCURVE_S1.); -#164473 = LINE('',#164474,#164475); -#164474 = CARTESIAN_POINT('',(0.845,0.985,0.E+000)); -#164475 = VECTOR('',#164476,1.); -#164476 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164477 = PCURVE('',#158764,#164478); -#164478 = DEFINITIONAL_REPRESENTATION('',(#164479),#164483); -#164479 = LINE('',#164480,#164481); -#164480 = CARTESIAN_POINT('',(0.E+000,0.11)); -#164481 = VECTOR('',#164482,1.); -#164482 = DIRECTION('',(1.,0.E+000)); -#164483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164484 = PCURVE('',#164485,#164490); -#164485 = PLANE('',#164486); -#164486 = AXIS2_PLACEMENT_3D('',#164487,#164488,#164489); -#164487 = CARTESIAN_POINT('',(0.635,0.985,0.E+000)); -#164488 = DIRECTION('',(0.E+000,1.,0.E+000)); -#164489 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164490 = DEFINITIONAL_REPRESENTATION('',(#164491),#164495); -#164491 = LINE('',#164492,#164493); -#164492 = CARTESIAN_POINT('',(0.E+000,0.21)); -#164493 = VECTOR('',#164494,1.); -#164494 = DIRECTION('',(-1.,0.E+000)); -#164495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164496 = ORIENTED_EDGE('',*,*,#164497,.F.); -#164497 = EDGE_CURVE('',#164345,#164470,#164498,.T.); -#164498 = SURFACE_CURVE('',#164499,(#164503,#164510),.PCURVE_S1.); -#164499 = LINE('',#164500,#164501); -#164500 = CARTESIAN_POINT('',(0.845,0.875,-0.21)); -#164501 = VECTOR('',#164502,1.); -#164502 = DIRECTION('',(0.E+000,1.,0.E+000)); -#164503 = PCURVE('',#158764,#164504); -#164504 = DEFINITIONAL_REPRESENTATION('',(#164505),#164509); -#164505 = LINE('',#164506,#164507); -#164506 = CARTESIAN_POINT('',(0.21,0.E+000)); -#164507 = VECTOR('',#164508,1.); -#164508 = DIRECTION('',(0.E+000,1.)); -#164509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164510 = PCURVE('',#164383,#164511); -#164511 = DEFINITIONAL_REPRESENTATION('',(#164512),#164516); -#164512 = LINE('',#164513,#164514); -#164513 = CARTESIAN_POINT('',(-2.75,0.E+000)); -#164514 = VECTOR('',#164515,1.); -#164515 = DIRECTION('',(0.E+000,1.)); -#164516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164517 = ORIENTED_EDGE('',*,*,#164344,.T.); -#164518 = ORIENTED_EDGE('',*,*,#159292,.T.); -#164519 = ORIENTED_EDGE('',*,*,#159268,.T.); -#164520 = ORIENTED_EDGE('',*,*,#159193,.T.); -#164521 = ORIENTED_EDGE('',*,*,#159118,.T.); -#164522 = ORIENTED_EDGE('',*,*,#159015,.T.); -#164523 = ORIENTED_EDGE('',*,*,#158916,.T.); -#164524 = ORIENTED_EDGE('',*,*,#158886,.T.); -#164525 = ORIENTED_EDGE('',*,*,#158748,.T.); -#164526 = ADVANCED_FACE('',(#164527),#158737,.T.); -#164527 = FACE_BOUND('',#164528,.T.); -#164528 = EDGE_LOOP('',(#164529,#164551,#164552,#164553)); -#164529 = ORIENTED_EDGE('',*,*,#164530,.F.); -#164530 = EDGE_CURVE('',#164443,#164531,#164533,.T.); -#164531 = VERTEX_POINT('',#164532); -#164532 = CARTESIAN_POINT('',(0.425,0.985,-2.141803043818)); -#164533 = SURFACE_CURVE('',#164534,(#164538,#164544),.PCURVE_S1.); -#164534 = LINE('',#164535,#164536); -#164535 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); -#164536 = VECTOR('',#164537,1.); -#164537 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164538 = PCURVE('',#158737,#164539); -#164539 = DEFINITIONAL_REPRESENTATION('',(#164540),#164543); -#164540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164541,#164542), +#166857 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#166858 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#166859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166860 = ORIENTED_EDGE('',*,*,#166861,.F.); +#166861 = EDGE_CURVE('',#166862,#166835,#166864,.T.); +#166862 = VERTEX_POINT('',#166863); +#166863 = CARTESIAN_POINT('',(0.845,0.985,-0.21)); +#166864 = SURFACE_CURVE('',#166865,(#166869,#166876),.PCURVE_S1.); +#166865 = LINE('',#166866,#166867); +#166866 = CARTESIAN_POINT('',(0.845,0.985,0.E+000)); +#166867 = VECTOR('',#166868,1.); +#166868 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#166869 = PCURVE('',#161156,#166870); +#166870 = DEFINITIONAL_REPRESENTATION('',(#166871),#166875); +#166871 = LINE('',#166872,#166873); +#166872 = CARTESIAN_POINT('',(0.E+000,0.11)); +#166873 = VECTOR('',#166874,1.); +#166874 = DIRECTION('',(1.,0.E+000)); +#166875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166876 = PCURVE('',#166877,#166882); +#166877 = PLANE('',#166878); +#166878 = AXIS2_PLACEMENT_3D('',#166879,#166880,#166881); +#166879 = CARTESIAN_POINT('',(0.635,0.985,0.E+000)); +#166880 = DIRECTION('',(0.E+000,1.,0.E+000)); +#166881 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166882 = DEFINITIONAL_REPRESENTATION('',(#166883),#166887); +#166883 = LINE('',#166884,#166885); +#166884 = CARTESIAN_POINT('',(0.E+000,0.21)); +#166885 = VECTOR('',#166886,1.); +#166886 = DIRECTION('',(-1.,0.E+000)); +#166887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166888 = ORIENTED_EDGE('',*,*,#166889,.F.); +#166889 = EDGE_CURVE('',#166737,#166862,#166890,.T.); +#166890 = SURFACE_CURVE('',#166891,(#166895,#166902),.PCURVE_S1.); +#166891 = LINE('',#166892,#166893); +#166892 = CARTESIAN_POINT('',(0.845,0.875,-0.21)); +#166893 = VECTOR('',#166894,1.); +#166894 = DIRECTION('',(0.E+000,1.,0.E+000)); +#166895 = PCURVE('',#161156,#166896); +#166896 = DEFINITIONAL_REPRESENTATION('',(#166897),#166901); +#166897 = LINE('',#166898,#166899); +#166898 = CARTESIAN_POINT('',(0.21,0.E+000)); +#166899 = VECTOR('',#166900,1.); +#166900 = DIRECTION('',(0.E+000,1.)); +#166901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166902 = PCURVE('',#166775,#166903); +#166903 = DEFINITIONAL_REPRESENTATION('',(#166904),#166908); +#166904 = LINE('',#166905,#166906); +#166905 = CARTESIAN_POINT('',(-2.75,0.E+000)); +#166906 = VECTOR('',#166907,1.); +#166907 = DIRECTION('',(0.E+000,1.)); +#166908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166909 = ORIENTED_EDGE('',*,*,#166736,.T.); +#166910 = ORIENTED_EDGE('',*,*,#161684,.T.); +#166911 = ORIENTED_EDGE('',*,*,#161660,.T.); +#166912 = ORIENTED_EDGE('',*,*,#161585,.T.); +#166913 = ORIENTED_EDGE('',*,*,#161510,.T.); +#166914 = ORIENTED_EDGE('',*,*,#161407,.T.); +#166915 = ORIENTED_EDGE('',*,*,#161308,.T.); +#166916 = ORIENTED_EDGE('',*,*,#161278,.T.); +#166917 = ORIENTED_EDGE('',*,*,#161140,.T.); +#166918 = ADVANCED_FACE('',(#166919),#161129,.T.); +#166919 = FACE_BOUND('',#166920,.T.); +#166920 = EDGE_LOOP('',(#166921,#166943,#166944,#166945)); +#166921 = ORIENTED_EDGE('',*,*,#166922,.F.); +#166922 = EDGE_CURVE('',#166835,#166923,#166925,.T.); +#166923 = VERTEX_POINT('',#166924); +#166924 = CARTESIAN_POINT('',(0.425,0.985,-2.141803043818)); +#166925 = SURFACE_CURVE('',#166926,(#166930,#166936),.PCURVE_S1.); +#166926 = LINE('',#166927,#166928); +#166927 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); +#166928 = VECTOR('',#166929,1.); +#166929 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166930 = PCURVE('',#161129,#166931); +#166931 = DEFINITIONAL_REPRESENTATION('',(#166932),#166935); +#166932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166933,#166934), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#164541 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164542 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164544 = PCURVE('',#164485,#164545); -#164545 = DEFINITIONAL_REPRESENTATION('',(#164546),#164550); -#164546 = LINE('',#164547,#164548); -#164547 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#164548 = VECTOR('',#164549,1.); -#164549 = DIRECTION('',(0.E+000,-1.)); -#164550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164551 = ORIENTED_EDGE('',*,*,#164442,.T.); -#164552 = ORIENTED_EDGE('',*,*,#158714,.T.); -#164553 = ORIENTED_EDGE('',*,*,#164554,.F.); -#164554 = EDGE_CURVE('',#164531,#158717,#164555,.T.); -#164555 = SURFACE_CURVE('',#164556,(#164561,#164567),.PCURVE_S1.); -#164556 = CIRCLE('',#164557,0.32); -#164557 = AXIS2_PLACEMENT_3D('',#164558,#164559,#164560); -#164558 = CARTESIAN_POINT('',(0.425,0.665,-2.141803043818)); -#164559 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164560 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164561 = PCURVE('',#158737,#164562); -#164562 = DEFINITIONAL_REPRESENTATION('',(#164563),#164566); -#164563 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164564,#164565), +#166933 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#166934 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#166935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166936 = PCURVE('',#166877,#166937); +#166937 = DEFINITIONAL_REPRESENTATION('',(#166938),#166942); +#166938 = LINE('',#166939,#166940); +#166939 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#166940 = VECTOR('',#166941,1.); +#166941 = DIRECTION('',(0.E+000,-1.)); +#166942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166943 = ORIENTED_EDGE('',*,*,#166834,.T.); +#166944 = ORIENTED_EDGE('',*,*,#161106,.T.); +#166945 = ORIENTED_EDGE('',*,*,#166946,.F.); +#166946 = EDGE_CURVE('',#166923,#161109,#166947,.T.); +#166947 = SURFACE_CURVE('',#166948,(#166953,#166959),.PCURVE_S1.); +#166948 = CIRCLE('',#166949,0.32); +#166949 = AXIS2_PLACEMENT_3D('',#166950,#166951,#166952); +#166950 = CARTESIAN_POINT('',(0.425,0.665,-2.141803043818)); +#166951 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#166952 = DIRECTION('',(0.E+000,0.E+000,1.)); +#166953 = PCURVE('',#161129,#166954); +#166954 = DEFINITIONAL_REPRESENTATION('',(#166955),#166958); +#166955 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#166956,#166957), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#164564 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164565 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#164566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164567 = PCURVE('',#158817,#164568); -#164568 = DEFINITIONAL_REPRESENTATION('',(#164569),#164573); -#164569 = CIRCLE('',#164570,0.32); -#164570 = AXIS2_PLACEMENT_2D('',#164571,#164572); -#164571 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#164572 = DIRECTION('',(1.,0.E+000)); -#164573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164574 = ADVANCED_FACE('',(#164575),#158817,.T.); -#164575 = FACE_BOUND('',#164576,.T.); -#164576 = EDGE_LOOP('',(#164577,#164578,#164579,#164602,#164623,#164624, - #164625,#164626,#164627,#164628,#164629,#164630)); -#164577 = ORIENTED_EDGE('',*,*,#159320,.T.); -#164578 = ORIENTED_EDGE('',*,*,#164322,.T.); -#164579 = ORIENTED_EDGE('',*,*,#164580,.F.); -#164580 = EDGE_CURVE('',#164581,#164295,#164583,.T.); -#164581 = VERTEX_POINT('',#164582); -#164582 = CARTESIAN_POINT('',(0.425,0.985,-0.21)); -#164583 = SURFACE_CURVE('',#164584,(#164588,#164595),.PCURVE_S1.); -#164584 = LINE('',#164585,#164586); -#164585 = CARTESIAN_POINT('',(0.425,0.875,-0.21)); -#164586 = VECTOR('',#164587,1.); -#164587 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#164588 = PCURVE('',#158817,#164589); -#164589 = DEFINITIONAL_REPRESENTATION('',(#164590),#164594); -#164590 = LINE('',#164591,#164592); -#164591 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#164592 = VECTOR('',#164593,1.); -#164593 = DIRECTION('',(0.E+000,-1.)); -#164594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164595 = PCURVE('',#164310,#164596); -#164596 = DEFINITIONAL_REPRESENTATION('',(#164597),#164601); -#164597 = LINE('',#164598,#164599); -#164598 = CARTESIAN_POINT('',(-2.33,0.E+000)); -#164599 = VECTOR('',#164600,1.); -#164600 = DIRECTION('',(0.E+000,-1.)); -#164601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164602 = ORIENTED_EDGE('',*,*,#164603,.F.); -#164603 = EDGE_CURVE('',#164531,#164581,#164604,.T.); -#164604 = SURFACE_CURVE('',#164605,(#164609,#164616),.PCURVE_S1.); -#164605 = LINE('',#164606,#164607); -#164606 = CARTESIAN_POINT('',(0.425,0.985,0.E+000)); -#164607 = VECTOR('',#164608,1.); -#164608 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164609 = PCURVE('',#158817,#164610); -#164610 = DEFINITIONAL_REPRESENTATION('',(#164611),#164615); -#164611 = LINE('',#164612,#164613); -#164612 = CARTESIAN_POINT('',(0.E+000,0.11)); -#164613 = VECTOR('',#164614,1.); -#164614 = DIRECTION('',(1.,0.E+000)); -#164615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164616 = PCURVE('',#164485,#164617); -#164617 = DEFINITIONAL_REPRESENTATION('',(#164618),#164622); -#164618 = LINE('',#164619,#164620); -#164619 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#164620 = VECTOR('',#164621,1.); -#164621 = DIRECTION('',(1.,0.E+000)); -#164622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164623 = ORIENTED_EDGE('',*,*,#164554,.T.); -#164624 = ORIENTED_EDGE('',*,*,#158803,.T.); -#164625 = ORIENTED_EDGE('',*,*,#158832,.T.); -#164626 = ORIENTED_EDGE('',*,*,#158967,.T.); -#164627 = ORIENTED_EDGE('',*,*,#158991,.T.); -#164628 = ORIENTED_EDGE('',*,*,#159096,.T.); -#164629 = ORIENTED_EDGE('',*,*,#159171,.T.); -#164630 = ORIENTED_EDGE('',*,*,#159246,.T.); -#164631 = ADVANCED_FACE('',(#164632),#164310,.T.); -#164632 = FACE_BOUND('',#164633,.T.); -#164633 = EDGE_LOOP('',(#164634,#164657,#164678,#164679)); -#164634 = ORIENTED_EDGE('',*,*,#164635,.F.); -#164635 = EDGE_CURVE('',#164636,#164272,#164638,.T.); -#164636 = VERTEX_POINT('',#164637); -#164637 = CARTESIAN_POINT('',(-0.425,0.985,-0.21)); -#164638 = SURFACE_CURVE('',#164639,(#164643,#164650),.PCURVE_S1.); -#164639 = LINE('',#164640,#164641); -#164640 = CARTESIAN_POINT('',(-0.425,0.875,-0.21)); -#164641 = VECTOR('',#164642,1.); -#164642 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#164643 = PCURVE('',#164310,#164644); -#164644 = DEFINITIONAL_REPRESENTATION('',(#164645),#164649); -#164645 = LINE('',#164646,#164647); -#164646 = CARTESIAN_POINT('',(-1.48,0.E+000)); -#164647 = VECTOR('',#164648,1.); -#164648 = DIRECTION('',(0.E+000,-1.)); -#164649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164650 = PCURVE('',#159425,#164651); -#164651 = DEFINITIONAL_REPRESENTATION('',(#164652),#164656); -#164652 = LINE('',#164653,#164654); -#164653 = CARTESIAN_POINT('',(0.21,0.E+000)); -#164654 = VECTOR('',#164655,1.); -#164655 = DIRECTION('',(0.E+000,-1.)); -#164656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164657 = ORIENTED_EDGE('',*,*,#164658,.F.); -#164658 = EDGE_CURVE('',#164581,#164636,#164659,.T.); -#164659 = SURFACE_CURVE('',#164660,(#164664,#164671),.PCURVE_S1.); -#164660 = LINE('',#164661,#164662); -#164661 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); -#164662 = VECTOR('',#164663,1.); -#164663 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164664 = PCURVE('',#164310,#164665); -#164665 = DEFINITIONAL_REPRESENTATION('',(#164666),#164670); -#164666 = LINE('',#164667,#164668); -#164667 = CARTESIAN_POINT('',(-2.54,0.11)); -#164668 = VECTOR('',#164669,1.); -#164669 = DIRECTION('',(1.,0.E+000)); -#164670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164671 = PCURVE('',#164485,#164672); -#164672 = DEFINITIONAL_REPRESENTATION('',(#164673),#164677); -#164673 = LINE('',#164674,#164675); -#164674 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#164675 = VECTOR('',#164676,1.); -#164676 = DIRECTION('',(0.E+000,-1.)); -#164677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164678 = ORIENTED_EDGE('',*,*,#164580,.T.); -#164679 = ORIENTED_EDGE('',*,*,#164294,.T.); -#164680 = ADVANCED_FACE('',(#164681),#159425,.T.); -#164681 = FACE_BOUND('',#164682,.T.); -#164682 = EDGE_LOOP('',(#164683,#164710,#164731,#164732,#164733,#164734, - #164735,#164736,#164737,#164738,#164739,#164740)); -#164683 = ORIENTED_EDGE('',*,*,#164684,.F.); -#164684 = EDGE_CURVE('',#164685,#159376,#164687,.T.); -#164685 = VERTEX_POINT('',#164686); -#164686 = CARTESIAN_POINT('',(-0.425,0.985,-2.141803043818)); -#164687 = SURFACE_CURVE('',#164688,(#164693,#164704),.PCURVE_S1.); -#164688 = CIRCLE('',#164689,0.32); -#164689 = AXIS2_PLACEMENT_3D('',#164690,#164691,#164692); -#164690 = CARTESIAN_POINT('',(-0.425,0.665,-2.141803043818)); -#164691 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164692 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164693 = PCURVE('',#159425,#164694); -#164694 = DEFINITIONAL_REPRESENTATION('',(#164695),#164703); -#164695 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164696,#164697,#164698, - #164699,#164700,#164701,#164702),.UNSPECIFIED.,.T.,.F.) +#166956 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#166957 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#166958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166959 = PCURVE('',#161209,#166960); +#166960 = DEFINITIONAL_REPRESENTATION('',(#166961),#166965); +#166961 = CIRCLE('',#166962,0.32); +#166962 = AXIS2_PLACEMENT_2D('',#166963,#166964); +#166963 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#166964 = DIRECTION('',(1.,0.E+000)); +#166965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166966 = ADVANCED_FACE('',(#166967),#161209,.T.); +#166967 = FACE_BOUND('',#166968,.T.); +#166968 = EDGE_LOOP('',(#166969,#166970,#166971,#166994,#167015,#167016, + #167017,#167018,#167019,#167020,#167021,#167022)); +#166969 = ORIENTED_EDGE('',*,*,#161712,.T.); +#166970 = ORIENTED_EDGE('',*,*,#166714,.T.); +#166971 = ORIENTED_EDGE('',*,*,#166972,.F.); +#166972 = EDGE_CURVE('',#166973,#166687,#166975,.T.); +#166973 = VERTEX_POINT('',#166974); +#166974 = CARTESIAN_POINT('',(0.425,0.985,-0.21)); +#166975 = SURFACE_CURVE('',#166976,(#166980,#166987),.PCURVE_S1.); +#166976 = LINE('',#166977,#166978); +#166977 = CARTESIAN_POINT('',(0.425,0.875,-0.21)); +#166978 = VECTOR('',#166979,1.); +#166979 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#166980 = PCURVE('',#161209,#166981); +#166981 = DEFINITIONAL_REPRESENTATION('',(#166982),#166986); +#166982 = LINE('',#166983,#166984); +#166983 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#166984 = VECTOR('',#166985,1.); +#166985 = DIRECTION('',(0.E+000,-1.)); +#166986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166987 = PCURVE('',#166702,#166988); +#166988 = DEFINITIONAL_REPRESENTATION('',(#166989),#166993); +#166989 = LINE('',#166990,#166991); +#166990 = CARTESIAN_POINT('',(-2.33,0.E+000)); +#166991 = VECTOR('',#166992,1.); +#166992 = DIRECTION('',(0.E+000,-1.)); +#166993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#166994 = ORIENTED_EDGE('',*,*,#166995,.F.); +#166995 = EDGE_CURVE('',#166923,#166973,#166996,.T.); +#166996 = SURFACE_CURVE('',#166997,(#167001,#167008),.PCURVE_S1.); +#166997 = LINE('',#166998,#166999); +#166998 = CARTESIAN_POINT('',(0.425,0.985,0.E+000)); +#166999 = VECTOR('',#167000,1.); +#167000 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167001 = PCURVE('',#161209,#167002); +#167002 = DEFINITIONAL_REPRESENTATION('',(#167003),#167007); +#167003 = LINE('',#167004,#167005); +#167004 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167005 = VECTOR('',#167006,1.); +#167006 = DIRECTION('',(1.,0.E+000)); +#167007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167008 = PCURVE('',#166877,#167009); +#167009 = DEFINITIONAL_REPRESENTATION('',(#167010),#167014); +#167010 = LINE('',#167011,#167012); +#167011 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#167012 = VECTOR('',#167013,1.); +#167013 = DIRECTION('',(1.,0.E+000)); +#167014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167015 = ORIENTED_EDGE('',*,*,#166946,.T.); +#167016 = ORIENTED_EDGE('',*,*,#161195,.T.); +#167017 = ORIENTED_EDGE('',*,*,#161224,.T.); +#167018 = ORIENTED_EDGE('',*,*,#161359,.T.); +#167019 = ORIENTED_EDGE('',*,*,#161383,.T.); +#167020 = ORIENTED_EDGE('',*,*,#161488,.T.); +#167021 = ORIENTED_EDGE('',*,*,#161563,.T.); +#167022 = ORIENTED_EDGE('',*,*,#161638,.T.); +#167023 = ADVANCED_FACE('',(#167024),#166702,.T.); +#167024 = FACE_BOUND('',#167025,.T.); +#167025 = EDGE_LOOP('',(#167026,#167049,#167070,#167071)); +#167026 = ORIENTED_EDGE('',*,*,#167027,.F.); +#167027 = EDGE_CURVE('',#167028,#166664,#167030,.T.); +#167028 = VERTEX_POINT('',#167029); +#167029 = CARTESIAN_POINT('',(-0.425,0.985,-0.21)); +#167030 = SURFACE_CURVE('',#167031,(#167035,#167042),.PCURVE_S1.); +#167031 = LINE('',#167032,#167033); +#167032 = CARTESIAN_POINT('',(-0.425,0.875,-0.21)); +#167033 = VECTOR('',#167034,1.); +#167034 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167035 = PCURVE('',#166702,#167036); +#167036 = DEFINITIONAL_REPRESENTATION('',(#167037),#167041); +#167037 = LINE('',#167038,#167039); +#167038 = CARTESIAN_POINT('',(-1.48,0.E+000)); +#167039 = VECTOR('',#167040,1.); +#167040 = DIRECTION('',(0.E+000,-1.)); +#167041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167042 = PCURVE('',#161817,#167043); +#167043 = DEFINITIONAL_REPRESENTATION('',(#167044),#167048); +#167044 = LINE('',#167045,#167046); +#167045 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167046 = VECTOR('',#167047,1.); +#167047 = DIRECTION('',(0.E+000,-1.)); +#167048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167049 = ORIENTED_EDGE('',*,*,#167050,.F.); +#167050 = EDGE_CURVE('',#166973,#167028,#167051,.T.); +#167051 = SURFACE_CURVE('',#167052,(#167056,#167063),.PCURVE_S1.); +#167052 = LINE('',#167053,#167054); +#167053 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); +#167054 = VECTOR('',#167055,1.); +#167055 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167056 = PCURVE('',#166702,#167057); +#167057 = DEFINITIONAL_REPRESENTATION('',(#167058),#167062); +#167058 = LINE('',#167059,#167060); +#167059 = CARTESIAN_POINT('',(-2.54,0.11)); +#167060 = VECTOR('',#167061,1.); +#167061 = DIRECTION('',(1.,0.E+000)); +#167062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167063 = PCURVE('',#166877,#167064); +#167064 = DEFINITIONAL_REPRESENTATION('',(#167065),#167069); +#167065 = LINE('',#167066,#167067); +#167066 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167067 = VECTOR('',#167068,1.); +#167068 = DIRECTION('',(0.E+000,-1.)); +#167069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167070 = ORIENTED_EDGE('',*,*,#166972,.T.); +#167071 = ORIENTED_EDGE('',*,*,#166686,.T.); +#167072 = ADVANCED_FACE('',(#167073),#161817,.T.); +#167073 = FACE_BOUND('',#167074,.T.); +#167074 = EDGE_LOOP('',(#167075,#167102,#167123,#167124,#167125,#167126, + #167127,#167128,#167129,#167130,#167131,#167132)); +#167075 = ORIENTED_EDGE('',*,*,#167076,.F.); +#167076 = EDGE_CURVE('',#167077,#161768,#167079,.T.); +#167077 = VERTEX_POINT('',#167078); +#167078 = CARTESIAN_POINT('',(-0.425,0.985,-2.141803043818)); +#167079 = SURFACE_CURVE('',#167080,(#167085,#167096),.PCURVE_S1.); +#167080 = CIRCLE('',#167081,0.32); +#167081 = AXIS2_PLACEMENT_3D('',#167082,#167083,#167084); +#167082 = CARTESIAN_POINT('',(-0.425,0.665,-2.141803043818)); +#167083 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167084 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167085 = PCURVE('',#161817,#167086); +#167086 = DEFINITIONAL_REPRESENTATION('',(#167087),#167095); +#167087 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167088,#167089,#167090, + #167091,#167092,#167093,#167094),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#164696 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164697 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#164698 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#164699 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#164700 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#164701 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#164702 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164704 = PCURVE('',#159398,#164705); -#164705 = DEFINITIONAL_REPRESENTATION('',(#164706),#164709); -#164706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164707,#164708), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), - .PIECEWISE_BEZIER_KNOTS.); -#164707 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164708 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#164709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164710 = ORIENTED_EDGE('',*,*,#164711,.F.); -#164711 = EDGE_CURVE('',#164636,#164685,#164712,.T.); -#164712 = SURFACE_CURVE('',#164713,(#164717,#164724),.PCURVE_S1.); -#164713 = LINE('',#164714,#164715); -#164714 = CARTESIAN_POINT('',(-0.425,0.985,0.E+000)); -#164715 = VECTOR('',#164716,1.); -#164716 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164717 = PCURVE('',#159425,#164718); -#164718 = DEFINITIONAL_REPRESENTATION('',(#164719),#164723); -#164719 = LINE('',#164720,#164721); -#164720 = CARTESIAN_POINT('',(0.E+000,0.11)); -#164721 = VECTOR('',#164722,1.); -#164722 = DIRECTION('',(1.,0.E+000)); -#164723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164724 = PCURVE('',#164485,#164725); -#164725 = DEFINITIONAL_REPRESENTATION('',(#164726),#164730); -#164726 = LINE('',#164727,#164728); -#164727 = CARTESIAN_POINT('',(0.E+000,-1.06)); -#164728 = VECTOR('',#164729,1.); -#164729 = DIRECTION('',(-1.,0.E+000)); -#164730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164731 = ORIENTED_EDGE('',*,*,#164635,.T.); -#164732 = ORIENTED_EDGE('',*,*,#164271,.T.); -#164733 = ORIENTED_EDGE('',*,*,#159953,.T.); -#164734 = ORIENTED_EDGE('',*,*,#159929,.T.); -#164735 = ORIENTED_EDGE('',*,*,#159854,.T.); -#164736 = ORIENTED_EDGE('',*,*,#159779,.T.); -#164737 = ORIENTED_EDGE('',*,*,#159676,.T.); -#164738 = ORIENTED_EDGE('',*,*,#159577,.T.); -#164739 = ORIENTED_EDGE('',*,*,#159547,.T.); -#164740 = ORIENTED_EDGE('',*,*,#159409,.T.); -#164741 = ADVANCED_FACE('',(#164742),#159398,.T.); -#164742 = FACE_BOUND('',#164743,.T.); -#164743 = EDGE_LOOP('',(#164744,#164766,#164767,#164768)); -#164744 = ORIENTED_EDGE('',*,*,#164745,.F.); -#164745 = EDGE_CURVE('',#164685,#164746,#164748,.T.); -#164746 = VERTEX_POINT('',#164747); -#164747 = CARTESIAN_POINT('',(-0.845,0.985,-2.141803043818)); -#164748 = SURFACE_CURVE('',#164749,(#164753,#164759),.PCURVE_S1.); -#164749 = LINE('',#164750,#164751); -#164750 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); -#164751 = VECTOR('',#164752,1.); -#164752 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164753 = PCURVE('',#159398,#164754); -#164754 = DEFINITIONAL_REPRESENTATION('',(#164755),#164758); -#164755 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164756,#164757), - .UNSPECIFIED.,.F.,.F.,(2,2),(1.06,1.48),.PIECEWISE_BEZIER_KNOTS.); -#164756 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164757 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164759 = PCURVE('',#164485,#164760); -#164760 = DEFINITIONAL_REPRESENTATION('',(#164761),#164765); -#164761 = LINE('',#164762,#164763); -#164762 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#164763 = VECTOR('',#164764,1.); -#164764 = DIRECTION('',(0.E+000,-1.)); -#164765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164766 = ORIENTED_EDGE('',*,*,#164684,.T.); -#164767 = ORIENTED_EDGE('',*,*,#159375,.T.); -#164768 = ORIENTED_EDGE('',*,*,#164769,.F.); -#164769 = EDGE_CURVE('',#164746,#159378,#164770,.T.); -#164770 = SURFACE_CURVE('',#164771,(#164776,#164782),.PCURVE_S1.); -#164771 = CIRCLE('',#164772,0.32); -#164772 = AXIS2_PLACEMENT_3D('',#164773,#164774,#164775); -#164773 = CARTESIAN_POINT('',(-0.845,0.665,-2.141803043818)); -#164774 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164775 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164776 = PCURVE('',#159398,#164777); -#164777 = DEFINITIONAL_REPRESENTATION('',(#164778),#164781); -#164778 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164779,#164780), +#167088 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167089 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#167090 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#167091 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#167092 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#167093 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#167094 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167096 = PCURVE('',#161790,#167097); +#167097 = DEFINITIONAL_REPRESENTATION('',(#167098),#167101); +#167098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167099,#167100), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), - .PIECEWISE_BEZIER_KNOTS.); -#164779 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164780 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#164781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164782 = PCURVE('',#159478,#164783); -#164783 = DEFINITIONAL_REPRESENTATION('',(#164784),#164788); -#164784 = CIRCLE('',#164785,0.32); -#164785 = AXIS2_PLACEMENT_2D('',#164786,#164787); -#164786 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#164787 = DIRECTION('',(1.,0.E+000)); -#164788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164789 = ADVANCED_FACE('',(#164790),#159478,.T.); -#164790 = FACE_BOUND('',#164791,.T.); -#164791 = EDGE_LOOP('',(#164792,#164793,#164794,#164817,#164838,#164839, - #164840,#164841,#164842,#164843,#164844,#164845)); -#164792 = ORIENTED_EDGE('',*,*,#159981,.T.); -#164793 = ORIENTED_EDGE('',*,*,#164249,.T.); -#164794 = ORIENTED_EDGE('',*,*,#164795,.F.); -#164795 = EDGE_CURVE('',#164796,#164222,#164798,.T.); -#164796 = VERTEX_POINT('',#164797); -#164797 = CARTESIAN_POINT('',(-0.845,0.985,-0.21)); -#164798 = SURFACE_CURVE('',#164799,(#164803,#164810),.PCURVE_S1.); -#164799 = LINE('',#164800,#164801); -#164800 = CARTESIAN_POINT('',(-0.845,0.875,-0.21)); -#164801 = VECTOR('',#164802,1.); -#164802 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#164803 = PCURVE('',#159478,#164804); -#164804 = DEFINITIONAL_REPRESENTATION('',(#164805),#164809); -#164805 = LINE('',#164806,#164807); -#164806 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#164807 = VECTOR('',#164808,1.); -#164808 = DIRECTION('',(0.E+000,-1.)); -#164809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164810 = PCURVE('',#164237,#164811); -#164811 = DEFINITIONAL_REPRESENTATION('',(#164812),#164816); -#164812 = LINE('',#164813,#164814); -#164813 = CARTESIAN_POINT('',(-1.06,0.E+000)); -#164814 = VECTOR('',#164815,1.); -#164815 = DIRECTION('',(0.E+000,-1.)); -#164816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164817 = ORIENTED_EDGE('',*,*,#164818,.F.); -#164818 = EDGE_CURVE('',#164746,#164796,#164819,.T.); -#164819 = SURFACE_CURVE('',#164820,(#164824,#164831),.PCURVE_S1.); -#164820 = LINE('',#164821,#164822); -#164821 = CARTESIAN_POINT('',(-0.845,0.985,0.E+000)); -#164822 = VECTOR('',#164823,1.); -#164823 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164824 = PCURVE('',#159478,#164825); -#164825 = DEFINITIONAL_REPRESENTATION('',(#164826),#164830); -#164826 = LINE('',#164827,#164828); -#164827 = CARTESIAN_POINT('',(0.E+000,0.11)); -#164828 = VECTOR('',#164829,1.); -#164829 = DIRECTION('',(1.,0.E+000)); -#164830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164831 = PCURVE('',#164485,#164832); -#164832 = DEFINITIONAL_REPRESENTATION('',(#164833),#164837); -#164833 = LINE('',#164834,#164835); -#164834 = CARTESIAN_POINT('',(0.E+000,-1.48)); -#164835 = VECTOR('',#164836,1.); -#164836 = DIRECTION('',(1.,0.E+000)); -#164837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164838 = ORIENTED_EDGE('',*,*,#164769,.T.); -#164839 = ORIENTED_EDGE('',*,*,#159464,.T.); -#164840 = ORIENTED_EDGE('',*,*,#159493,.T.); -#164841 = ORIENTED_EDGE('',*,*,#159628,.T.); -#164842 = ORIENTED_EDGE('',*,*,#159652,.T.); -#164843 = ORIENTED_EDGE('',*,*,#159757,.T.); -#164844 = ORIENTED_EDGE('',*,*,#159832,.T.); -#164845 = ORIENTED_EDGE('',*,*,#159907,.T.); -#164846 = ADVANCED_FACE('',(#164847),#164237,.T.); -#164847 = FACE_BOUND('',#164848,.T.); -#164848 = EDGE_LOOP('',(#164849,#164850,#164851,#164874)); -#164849 = ORIENTED_EDGE('',*,*,#164795,.T.); -#164850 = ORIENTED_EDGE('',*,*,#164221,.T.); -#164851 = ORIENTED_EDGE('',*,*,#164852,.F.); -#164852 = EDGE_CURVE('',#164853,#164199,#164855,.T.); -#164853 = VERTEX_POINT('',#164854); -#164854 = CARTESIAN_POINT('',(-1.695,0.985,-0.21)); -#164855 = SURFACE_CURVE('',#164856,(#164860,#164867),.PCURVE_S1.); -#164856 = LINE('',#164857,#164858); -#164857 = CARTESIAN_POINT('',(-1.695,0.875,-0.21)); -#164858 = VECTOR('',#164859,1.); -#164859 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#164860 = PCURVE('',#164237,#164861); -#164861 = DEFINITIONAL_REPRESENTATION('',(#164862),#164866); -#164862 = LINE('',#164863,#164864); -#164863 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#164864 = VECTOR('',#164865,1.); -#164865 = DIRECTION('',(0.E+000,-1.)); -#164866 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164867 = PCURVE('',#160081,#164868); -#164868 = DEFINITIONAL_REPRESENTATION('',(#164869),#164873); -#164869 = LINE('',#164870,#164871); -#164870 = CARTESIAN_POINT('',(0.21,0.E+000)); -#164871 = VECTOR('',#164872,1.); -#164872 = DIRECTION('',(0.E+000,-1.)); -#164873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164874 = ORIENTED_EDGE('',*,*,#164875,.F.); -#164875 = EDGE_CURVE('',#164796,#164853,#164876,.T.); -#164876 = SURFACE_CURVE('',#164877,(#164881,#164888),.PCURVE_S1.); -#164877 = LINE('',#164878,#164879); -#164878 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); -#164879 = VECTOR('',#164880,1.); -#164880 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164881 = PCURVE('',#164237,#164882); -#164882 = DEFINITIONAL_REPRESENTATION('',(#164883),#164887); -#164883 = LINE('',#164884,#164885); -#164884 = CARTESIAN_POINT('',(-2.54,0.11)); -#164885 = VECTOR('',#164886,1.); -#164886 = DIRECTION('',(1.,0.E+000)); -#164887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164888 = PCURVE('',#164485,#164889); -#164889 = DEFINITIONAL_REPRESENTATION('',(#164890),#164894); -#164890 = LINE('',#164891,#164892); -#164891 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#164892 = VECTOR('',#164893,1.); -#164893 = DIRECTION('',(0.E+000,-1.)); -#164894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164895 = ADVANCED_FACE('',(#164896),#160081,.T.); -#164896 = FACE_BOUND('',#164897,.T.); -#164897 = EDGE_LOOP('',(#164898,#164925,#164946,#164947,#164948,#164949, - #164950,#164951,#164952,#164953,#164954,#164955)); -#164898 = ORIENTED_EDGE('',*,*,#164899,.F.); -#164899 = EDGE_CURVE('',#164900,#160032,#164902,.T.); -#164900 = VERTEX_POINT('',#164901); -#164901 = CARTESIAN_POINT('',(-1.695,0.985,-2.141803043818)); -#164902 = SURFACE_CURVE('',#164903,(#164908,#164919),.PCURVE_S1.); -#164903 = CIRCLE('',#164904,0.32); -#164904 = AXIS2_PLACEMENT_3D('',#164905,#164906,#164907); -#164905 = CARTESIAN_POINT('',(-1.695,0.665,-2.141803043818)); -#164906 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164907 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164908 = PCURVE('',#160081,#164909); -#164909 = DEFINITIONAL_REPRESENTATION('',(#164910),#164918); -#164910 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#164911,#164912,#164913, - #164914,#164915,#164916,#164917),.UNSPECIFIED.,.T.,.F.) + .PIECEWISE_BEZIER_KNOTS.); +#167099 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167100 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#167101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167102 = ORIENTED_EDGE('',*,*,#167103,.F.); +#167103 = EDGE_CURVE('',#167028,#167077,#167104,.T.); +#167104 = SURFACE_CURVE('',#167105,(#167109,#167116),.PCURVE_S1.); +#167105 = LINE('',#167106,#167107); +#167106 = CARTESIAN_POINT('',(-0.425,0.985,0.E+000)); +#167107 = VECTOR('',#167108,1.); +#167108 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167109 = PCURVE('',#161817,#167110); +#167110 = DEFINITIONAL_REPRESENTATION('',(#167111),#167115); +#167111 = LINE('',#167112,#167113); +#167112 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167113 = VECTOR('',#167114,1.); +#167114 = DIRECTION('',(1.,0.E+000)); +#167115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167116 = PCURVE('',#166877,#167117); +#167117 = DEFINITIONAL_REPRESENTATION('',(#167118),#167122); +#167118 = LINE('',#167119,#167120); +#167119 = CARTESIAN_POINT('',(0.E+000,-1.06)); +#167120 = VECTOR('',#167121,1.); +#167121 = DIRECTION('',(-1.,0.E+000)); +#167122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167123 = ORIENTED_EDGE('',*,*,#167027,.T.); +#167124 = ORIENTED_EDGE('',*,*,#166663,.T.); +#167125 = ORIENTED_EDGE('',*,*,#162345,.T.); +#167126 = ORIENTED_EDGE('',*,*,#162321,.T.); +#167127 = ORIENTED_EDGE('',*,*,#162246,.T.); +#167128 = ORIENTED_EDGE('',*,*,#162171,.T.); +#167129 = ORIENTED_EDGE('',*,*,#162068,.T.); +#167130 = ORIENTED_EDGE('',*,*,#161969,.T.); +#167131 = ORIENTED_EDGE('',*,*,#161939,.T.); +#167132 = ORIENTED_EDGE('',*,*,#161801,.T.); +#167133 = ADVANCED_FACE('',(#167134),#161790,.T.); +#167134 = FACE_BOUND('',#167135,.T.); +#167135 = EDGE_LOOP('',(#167136,#167158,#167159,#167160)); +#167136 = ORIENTED_EDGE('',*,*,#167137,.F.); +#167137 = EDGE_CURVE('',#167077,#167138,#167140,.T.); +#167138 = VERTEX_POINT('',#167139); +#167139 = CARTESIAN_POINT('',(-0.845,0.985,-2.141803043818)); +#167140 = SURFACE_CURVE('',#167141,(#167145,#167151),.PCURVE_S1.); +#167141 = LINE('',#167142,#167143); +#167142 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); +#167143 = VECTOR('',#167144,1.); +#167144 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167145 = PCURVE('',#161790,#167146); +#167146 = DEFINITIONAL_REPRESENTATION('',(#167147),#167150); +#167147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167148,#167149), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.06,1.48),.PIECEWISE_BEZIER_KNOTS.); +#167148 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167149 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167151 = PCURVE('',#166877,#167152); +#167152 = DEFINITIONAL_REPRESENTATION('',(#167153),#167157); +#167153 = LINE('',#167154,#167155); +#167154 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#167155 = VECTOR('',#167156,1.); +#167156 = DIRECTION('',(0.E+000,-1.)); +#167157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167158 = ORIENTED_EDGE('',*,*,#167076,.T.); +#167159 = ORIENTED_EDGE('',*,*,#161767,.T.); +#167160 = ORIENTED_EDGE('',*,*,#167161,.F.); +#167161 = EDGE_CURVE('',#167138,#161770,#167162,.T.); +#167162 = SURFACE_CURVE('',#167163,(#167168,#167174),.PCURVE_S1.); +#167163 = CIRCLE('',#167164,0.32); +#167164 = AXIS2_PLACEMENT_3D('',#167165,#167166,#167167); +#167165 = CARTESIAN_POINT('',(-0.845,0.665,-2.141803043818)); +#167166 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167167 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167168 = PCURVE('',#161790,#167169); +#167169 = DEFINITIONAL_REPRESENTATION('',(#167170),#167173); +#167170 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167171,#167172), + .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), + .PIECEWISE_BEZIER_KNOTS.); +#167171 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167172 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#167173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167174 = PCURVE('',#161870,#167175); +#167175 = DEFINITIONAL_REPRESENTATION('',(#167176),#167180); +#167176 = CIRCLE('',#167177,0.32); +#167177 = AXIS2_PLACEMENT_2D('',#167178,#167179); +#167178 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#167179 = DIRECTION('',(1.,0.E+000)); +#167180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167181 = ADVANCED_FACE('',(#167182),#161870,.T.); +#167182 = FACE_BOUND('',#167183,.T.); +#167183 = EDGE_LOOP('',(#167184,#167185,#167186,#167209,#167230,#167231, + #167232,#167233,#167234,#167235,#167236,#167237)); +#167184 = ORIENTED_EDGE('',*,*,#162373,.T.); +#167185 = ORIENTED_EDGE('',*,*,#166641,.T.); +#167186 = ORIENTED_EDGE('',*,*,#167187,.F.); +#167187 = EDGE_CURVE('',#167188,#166614,#167190,.T.); +#167188 = VERTEX_POINT('',#167189); +#167189 = CARTESIAN_POINT('',(-0.845,0.985,-0.21)); +#167190 = SURFACE_CURVE('',#167191,(#167195,#167202),.PCURVE_S1.); +#167191 = LINE('',#167192,#167193); +#167192 = CARTESIAN_POINT('',(-0.845,0.875,-0.21)); +#167193 = VECTOR('',#167194,1.); +#167194 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167195 = PCURVE('',#161870,#167196); +#167196 = DEFINITIONAL_REPRESENTATION('',(#167197),#167201); +#167197 = LINE('',#167198,#167199); +#167198 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167199 = VECTOR('',#167200,1.); +#167200 = DIRECTION('',(0.E+000,-1.)); +#167201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167202 = PCURVE('',#166629,#167203); +#167203 = DEFINITIONAL_REPRESENTATION('',(#167204),#167208); +#167204 = LINE('',#167205,#167206); +#167205 = CARTESIAN_POINT('',(-1.06,0.E+000)); +#167206 = VECTOR('',#167207,1.); +#167207 = DIRECTION('',(0.E+000,-1.)); +#167208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167209 = ORIENTED_EDGE('',*,*,#167210,.F.); +#167210 = EDGE_CURVE('',#167138,#167188,#167211,.T.); +#167211 = SURFACE_CURVE('',#167212,(#167216,#167223),.PCURVE_S1.); +#167212 = LINE('',#167213,#167214); +#167213 = CARTESIAN_POINT('',(-0.845,0.985,0.E+000)); +#167214 = VECTOR('',#167215,1.); +#167215 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167216 = PCURVE('',#161870,#167217); +#167217 = DEFINITIONAL_REPRESENTATION('',(#167218),#167222); +#167218 = LINE('',#167219,#167220); +#167219 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167220 = VECTOR('',#167221,1.); +#167221 = DIRECTION('',(1.,0.E+000)); +#167222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167223 = PCURVE('',#166877,#167224); +#167224 = DEFINITIONAL_REPRESENTATION('',(#167225),#167229); +#167225 = LINE('',#167226,#167227); +#167226 = CARTESIAN_POINT('',(0.E+000,-1.48)); +#167227 = VECTOR('',#167228,1.); +#167228 = DIRECTION('',(1.,0.E+000)); +#167229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167230 = ORIENTED_EDGE('',*,*,#167161,.T.); +#167231 = ORIENTED_EDGE('',*,*,#161856,.T.); +#167232 = ORIENTED_EDGE('',*,*,#161885,.T.); +#167233 = ORIENTED_EDGE('',*,*,#162020,.T.); +#167234 = ORIENTED_EDGE('',*,*,#162044,.T.); +#167235 = ORIENTED_EDGE('',*,*,#162149,.T.); +#167236 = ORIENTED_EDGE('',*,*,#162224,.T.); +#167237 = ORIENTED_EDGE('',*,*,#162299,.T.); +#167238 = ADVANCED_FACE('',(#167239),#166629,.T.); +#167239 = FACE_BOUND('',#167240,.T.); +#167240 = EDGE_LOOP('',(#167241,#167242,#167243,#167266)); +#167241 = ORIENTED_EDGE('',*,*,#167187,.T.); +#167242 = ORIENTED_EDGE('',*,*,#166613,.T.); +#167243 = ORIENTED_EDGE('',*,*,#167244,.F.); +#167244 = EDGE_CURVE('',#167245,#166591,#167247,.T.); +#167245 = VERTEX_POINT('',#167246); +#167246 = CARTESIAN_POINT('',(-1.695,0.985,-0.21)); +#167247 = SURFACE_CURVE('',#167248,(#167252,#167259),.PCURVE_S1.); +#167248 = LINE('',#167249,#167250); +#167249 = CARTESIAN_POINT('',(-1.695,0.875,-0.21)); +#167250 = VECTOR('',#167251,1.); +#167251 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167252 = PCURVE('',#166629,#167253); +#167253 = DEFINITIONAL_REPRESENTATION('',(#167254),#167258); +#167254 = LINE('',#167255,#167256); +#167255 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167256 = VECTOR('',#167257,1.); +#167257 = DIRECTION('',(0.E+000,-1.)); +#167258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167259 = PCURVE('',#162473,#167260); +#167260 = DEFINITIONAL_REPRESENTATION('',(#167261),#167265); +#167261 = LINE('',#167262,#167263); +#167262 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167263 = VECTOR('',#167264,1.); +#167264 = DIRECTION('',(0.E+000,-1.)); +#167265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167266 = ORIENTED_EDGE('',*,*,#167267,.F.); +#167267 = EDGE_CURVE('',#167188,#167245,#167268,.T.); +#167268 = SURFACE_CURVE('',#167269,(#167273,#167280),.PCURVE_S1.); +#167269 = LINE('',#167270,#167271); +#167270 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); +#167271 = VECTOR('',#167272,1.); +#167272 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167273 = PCURVE('',#166629,#167274); +#167274 = DEFINITIONAL_REPRESENTATION('',(#167275),#167279); +#167275 = LINE('',#167276,#167277); +#167276 = CARTESIAN_POINT('',(-2.54,0.11)); +#167277 = VECTOR('',#167278,1.); +#167278 = DIRECTION('',(1.,0.E+000)); +#167279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167280 = PCURVE('',#166877,#167281); +#167281 = DEFINITIONAL_REPRESENTATION('',(#167282),#167286); +#167282 = LINE('',#167283,#167284); +#167283 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167284 = VECTOR('',#167285,1.); +#167285 = DIRECTION('',(0.E+000,-1.)); +#167286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167287 = ADVANCED_FACE('',(#167288),#162473,.T.); +#167288 = FACE_BOUND('',#167289,.T.); +#167289 = EDGE_LOOP('',(#167290,#167317,#167338,#167339,#167340,#167341, + #167342,#167343,#167344,#167345,#167346,#167347)); +#167290 = ORIENTED_EDGE('',*,*,#167291,.F.); +#167291 = EDGE_CURVE('',#167292,#162424,#167294,.T.); +#167292 = VERTEX_POINT('',#167293); +#167293 = CARTESIAN_POINT('',(-1.695,0.985,-2.141803043818)); +#167294 = SURFACE_CURVE('',#167295,(#167300,#167311),.PCURVE_S1.); +#167295 = CIRCLE('',#167296,0.32); +#167296 = AXIS2_PLACEMENT_3D('',#167297,#167298,#167299); +#167297 = CARTESIAN_POINT('',(-1.695,0.665,-2.141803043818)); +#167298 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167299 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167300 = PCURVE('',#162473,#167301); +#167301 = DEFINITIONAL_REPRESENTATION('',(#167302),#167310); +#167302 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167303,#167304,#167305, + #167306,#167307,#167308,#167309),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#164911 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164912 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#164913 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#164914 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#164915 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#164916 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#164917 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#164918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164919 = PCURVE('',#160054,#164920); -#164920 = DEFINITIONAL_REPRESENTATION('',(#164921),#164924); -#164921 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164922,#164923), +#167303 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167304 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#167305 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#167306 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#167307 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#167308 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#167309 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167311 = PCURVE('',#162446,#167312); +#167312 = DEFINITIONAL_REPRESENTATION('',(#167313),#167316); +#167313 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167314,#167315), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#164922 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164923 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#164924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164925 = ORIENTED_EDGE('',*,*,#164926,.F.); -#164926 = EDGE_CURVE('',#164853,#164900,#164927,.T.); -#164927 = SURFACE_CURVE('',#164928,(#164932,#164939),.PCURVE_S1.); -#164928 = LINE('',#164929,#164930); -#164929 = CARTESIAN_POINT('',(-1.695,0.985,0.E+000)); -#164930 = VECTOR('',#164931,1.); -#164931 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#164932 = PCURVE('',#160081,#164933); -#164933 = DEFINITIONAL_REPRESENTATION('',(#164934),#164938); -#164934 = LINE('',#164935,#164936); -#164935 = CARTESIAN_POINT('',(0.E+000,0.11)); -#164936 = VECTOR('',#164937,1.); -#164937 = DIRECTION('',(1.,0.E+000)); -#164938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164939 = PCURVE('',#164485,#164940); -#164940 = DEFINITIONAL_REPRESENTATION('',(#164941),#164945); -#164941 = LINE('',#164942,#164943); -#164942 = CARTESIAN_POINT('',(0.E+000,-2.33)); -#164943 = VECTOR('',#164944,1.); -#164944 = DIRECTION('',(-1.,0.E+000)); -#164945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164946 = ORIENTED_EDGE('',*,*,#164852,.T.); -#164947 = ORIENTED_EDGE('',*,*,#164198,.T.); -#164948 = ORIENTED_EDGE('',*,*,#160609,.T.); -#164949 = ORIENTED_EDGE('',*,*,#160585,.T.); -#164950 = ORIENTED_EDGE('',*,*,#160510,.T.); -#164951 = ORIENTED_EDGE('',*,*,#160435,.T.); -#164952 = ORIENTED_EDGE('',*,*,#160332,.T.); -#164953 = ORIENTED_EDGE('',*,*,#160233,.T.); -#164954 = ORIENTED_EDGE('',*,*,#160203,.T.); -#164955 = ORIENTED_EDGE('',*,*,#160065,.T.); -#164956 = ADVANCED_FACE('',(#164957),#160054,.T.); -#164957 = FACE_BOUND('',#164958,.T.); -#164958 = EDGE_LOOP('',(#164959,#164981,#164982,#164983)); -#164959 = ORIENTED_EDGE('',*,*,#164960,.F.); -#164960 = EDGE_CURVE('',#164900,#164961,#164963,.T.); -#164961 = VERTEX_POINT('',#164962); -#164962 = CARTESIAN_POINT('',(-2.115,0.985,-2.141803043818)); -#164963 = SURFACE_CURVE('',#164964,(#164968,#164974),.PCURVE_S1.); -#164964 = LINE('',#164965,#164966); -#164965 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); -#164966 = VECTOR('',#164967,1.); -#164967 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164968 = PCURVE('',#160054,#164969); -#164969 = DEFINITIONAL_REPRESENTATION('',(#164970),#164973); -#164970 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164971,#164972), +#167314 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167315 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#167316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167317 = ORIENTED_EDGE('',*,*,#167318,.F.); +#167318 = EDGE_CURVE('',#167245,#167292,#167319,.T.); +#167319 = SURFACE_CURVE('',#167320,(#167324,#167331),.PCURVE_S1.); +#167320 = LINE('',#167321,#167322); +#167321 = CARTESIAN_POINT('',(-1.695,0.985,0.E+000)); +#167322 = VECTOR('',#167323,1.); +#167323 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167324 = PCURVE('',#162473,#167325); +#167325 = DEFINITIONAL_REPRESENTATION('',(#167326),#167330); +#167326 = LINE('',#167327,#167328); +#167327 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167328 = VECTOR('',#167329,1.); +#167329 = DIRECTION('',(1.,0.E+000)); +#167330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167331 = PCURVE('',#166877,#167332); +#167332 = DEFINITIONAL_REPRESENTATION('',(#167333),#167337); +#167333 = LINE('',#167334,#167335); +#167334 = CARTESIAN_POINT('',(0.E+000,-2.33)); +#167335 = VECTOR('',#167336,1.); +#167336 = DIRECTION('',(-1.,0.E+000)); +#167337 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167338 = ORIENTED_EDGE('',*,*,#167244,.T.); +#167339 = ORIENTED_EDGE('',*,*,#166590,.T.); +#167340 = ORIENTED_EDGE('',*,*,#163001,.T.); +#167341 = ORIENTED_EDGE('',*,*,#162977,.T.); +#167342 = ORIENTED_EDGE('',*,*,#162902,.T.); +#167343 = ORIENTED_EDGE('',*,*,#162827,.T.); +#167344 = ORIENTED_EDGE('',*,*,#162724,.T.); +#167345 = ORIENTED_EDGE('',*,*,#162625,.T.); +#167346 = ORIENTED_EDGE('',*,*,#162595,.T.); +#167347 = ORIENTED_EDGE('',*,*,#162457,.T.); +#167348 = ADVANCED_FACE('',(#167349),#162446,.T.); +#167349 = FACE_BOUND('',#167350,.T.); +#167350 = EDGE_LOOP('',(#167351,#167373,#167374,#167375)); +#167351 = ORIENTED_EDGE('',*,*,#167352,.F.); +#167352 = EDGE_CURVE('',#167292,#167353,#167355,.T.); +#167353 = VERTEX_POINT('',#167354); +#167354 = CARTESIAN_POINT('',(-2.115,0.985,-2.141803043818)); +#167355 = SURFACE_CURVE('',#167356,(#167360,#167366),.PCURVE_S1.); +#167356 = LINE('',#167357,#167358); +#167357 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); +#167358 = VECTOR('',#167359,1.); +#167359 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167360 = PCURVE('',#162446,#167361); +#167361 = DEFINITIONAL_REPRESENTATION('',(#167362),#167365); +#167362 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167363,#167364), .UNSPECIFIED.,.F.,.F.,(2,2),(2.33,2.75),.PIECEWISE_BEZIER_KNOTS.); -#164971 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#164972 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164974 = PCURVE('',#164485,#164975); -#164975 = DEFINITIONAL_REPRESENTATION('',(#164976),#164980); -#164976 = LINE('',#164977,#164978); -#164977 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#164978 = VECTOR('',#164979,1.); -#164979 = DIRECTION('',(0.E+000,-1.)); -#164980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164981 = ORIENTED_EDGE('',*,*,#164899,.T.); -#164982 = ORIENTED_EDGE('',*,*,#160031,.T.); -#164983 = ORIENTED_EDGE('',*,*,#164984,.F.); -#164984 = EDGE_CURVE('',#164961,#160034,#164985,.T.); -#164985 = SURFACE_CURVE('',#164986,(#164991,#164997),.PCURVE_S1.); -#164986 = CIRCLE('',#164987,0.32); -#164987 = AXIS2_PLACEMENT_3D('',#164988,#164989,#164990); -#164988 = CARTESIAN_POINT('',(-2.115,0.665,-2.141803043818)); -#164989 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#164990 = DIRECTION('',(0.E+000,0.E+000,1.)); -#164991 = PCURVE('',#160054,#164992); -#164992 = DEFINITIONAL_REPRESENTATION('',(#164993),#164996); -#164993 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#164994,#164995), +#167363 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167364 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167366 = PCURVE('',#166877,#167367); +#167367 = DEFINITIONAL_REPRESENTATION('',(#167368),#167372); +#167368 = LINE('',#167369,#167370); +#167369 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#167370 = VECTOR('',#167371,1.); +#167371 = DIRECTION('',(0.E+000,-1.)); +#167372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167373 = ORIENTED_EDGE('',*,*,#167291,.T.); +#167374 = ORIENTED_EDGE('',*,*,#162423,.T.); +#167375 = ORIENTED_EDGE('',*,*,#167376,.F.); +#167376 = EDGE_CURVE('',#167353,#162426,#167377,.T.); +#167377 = SURFACE_CURVE('',#167378,(#167383,#167389),.PCURVE_S1.); +#167378 = CIRCLE('',#167379,0.32); +#167379 = AXIS2_PLACEMENT_3D('',#167380,#167381,#167382); +#167380 = CARTESIAN_POINT('',(-2.115,0.665,-2.141803043818)); +#167381 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#167382 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167383 = PCURVE('',#162446,#167384); +#167384 = DEFINITIONAL_REPRESENTATION('',(#167385),#167388); +#167385 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167386,#167387), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#164994 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#164995 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#164996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#164997 = PCURVE('',#160134,#164998); -#164998 = DEFINITIONAL_REPRESENTATION('',(#164999),#165003); -#164999 = CIRCLE('',#165000,0.32); -#165000 = AXIS2_PLACEMENT_2D('',#165001,#165002); -#165001 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165002 = DIRECTION('',(1.,0.E+000)); -#165003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165004 = ADVANCED_FACE('',(#165005),#160134,.T.); -#165005 = FACE_BOUND('',#165006,.T.); -#165006 = EDGE_LOOP('',(#165007,#165008,#165035,#165056,#165057,#165058, - #165059,#165060,#165061,#165062,#165063,#165064,#165065,#165066, - #165067,#165068,#165069,#165070,#165071,#165072)); -#165007 = ORIENTED_EDGE('',*,*,#160721,.T.); -#165008 = ORIENTED_EDGE('',*,*,#165009,.F.); -#165009 = EDGE_CURVE('',#165010,#160688,#165012,.T.); -#165010 = VERTEX_POINT('',#165011); -#165011 = CARTESIAN_POINT('',(-2.115,0.985,2.141803043818)); -#165012 = SURFACE_CURVE('',#165013,(#165018,#165029),.PCURVE_S1.); -#165013 = CIRCLE('',#165014,0.32); -#165014 = AXIS2_PLACEMENT_3D('',#165015,#165016,#165017); -#165015 = CARTESIAN_POINT('',(-2.115,0.665,2.141803043818)); -#165016 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165017 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165018 = PCURVE('',#160134,#165019); -#165019 = DEFINITIONAL_REPRESENTATION('',(#165020),#165028); -#165020 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165021,#165022,#165023, - #165024,#165025,#165026,#165027),.UNSPECIFIED.,.T.,.F.) +#167386 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167387 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#167388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167389 = PCURVE('',#162526,#167390); +#167390 = DEFINITIONAL_REPRESENTATION('',(#167391),#167395); +#167391 = CIRCLE('',#167392,0.32); +#167392 = AXIS2_PLACEMENT_2D('',#167393,#167394); +#167393 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#167394 = DIRECTION('',(1.,0.E+000)); +#167395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167396 = ADVANCED_FACE('',(#167397),#162526,.T.); +#167397 = FACE_BOUND('',#167398,.T.); +#167398 = EDGE_LOOP('',(#167399,#167400,#167427,#167448,#167449,#167450, + #167451,#167452,#167453,#167454,#167455,#167456,#167457,#167458, + #167459,#167460,#167461,#167462,#167463,#167464)); +#167399 = ORIENTED_EDGE('',*,*,#163113,.T.); +#167400 = ORIENTED_EDGE('',*,*,#167401,.F.); +#167401 = EDGE_CURVE('',#167402,#163080,#167404,.T.); +#167402 = VERTEX_POINT('',#167403); +#167403 = CARTESIAN_POINT('',(-2.115,0.985,2.141803043818)); +#167404 = SURFACE_CURVE('',#167405,(#167410,#167421),.PCURVE_S1.); +#167405 = CIRCLE('',#167406,0.32); +#167406 = AXIS2_PLACEMENT_3D('',#167407,#167408,#167409); +#167407 = CARTESIAN_POINT('',(-2.115,0.665,2.141803043818)); +#167408 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167409 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167410 = PCURVE('',#162526,#167411); +#167411 = DEFINITIONAL_REPRESENTATION('',(#167412),#167420); +#167412 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167413,#167414,#167415, + #167416,#167417,#167418,#167419),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#165021 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165022 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#165023 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#165024 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#165025 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#165026 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#165027 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165029 = PCURVE('',#160710,#165030); -#165030 = DEFINITIONAL_REPRESENTATION('',(#165031),#165034); -#165031 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165032,#165033), +#167413 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167414 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#167415 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#167416 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#167417 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#167418 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#167419 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167421 = PCURVE('',#163102,#167422); +#167422 = DEFINITIONAL_REPRESENTATION('',(#167423),#167426); +#167423 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167424,#167425), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165032 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165033 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#165034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165035 = ORIENTED_EDGE('',*,*,#165036,.F.); -#165036 = EDGE_CURVE('',#164961,#165010,#165037,.T.); -#165037 = SURFACE_CURVE('',#165038,(#165042,#165049),.PCURVE_S1.); -#165038 = LINE('',#165039,#165040); -#165039 = CARTESIAN_POINT('',(-2.115,0.985,0.E+000)); -#165040 = VECTOR('',#165041,1.); -#165041 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165042 = PCURVE('',#160134,#165043); -#165043 = DEFINITIONAL_REPRESENTATION('',(#165044),#165048); -#165044 = LINE('',#165045,#165046); -#165045 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165046 = VECTOR('',#165047,1.); -#165047 = DIRECTION('',(1.,0.E+000)); -#165048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165049 = PCURVE('',#164485,#165050); -#165050 = DEFINITIONAL_REPRESENTATION('',(#165051),#165055); -#165051 = LINE('',#165052,#165053); -#165052 = CARTESIAN_POINT('',(0.E+000,-2.75)); -#165053 = VECTOR('',#165054,1.); -#165054 = DIRECTION('',(1.,0.E+000)); -#165055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165056 = ORIENTED_EDGE('',*,*,#164984,.T.); -#165057 = ORIENTED_EDGE('',*,*,#160120,.T.); -#165058 = ORIENTED_EDGE('',*,*,#160149,.T.); -#165059 = ORIENTED_EDGE('',*,*,#160284,.T.); -#165060 = ORIENTED_EDGE('',*,*,#160308,.T.); -#165061 = ORIENTED_EDGE('',*,*,#160413,.T.); -#165062 = ORIENTED_EDGE('',*,*,#160488,.T.); -#165063 = ORIENTED_EDGE('',*,*,#160563,.T.); -#165064 = ORIENTED_EDGE('',*,*,#160637,.T.); -#165065 = ORIENTED_EDGE('',*,*,#164176,.T.); -#165066 = ORIENTED_EDGE('',*,*,#161260,.T.); -#165067 = ORIENTED_EDGE('',*,*,#161236,.T.); -#165068 = ORIENTED_EDGE('',*,*,#161161,.T.); -#165069 = ORIENTED_EDGE('',*,*,#161086,.T.); -#165070 = ORIENTED_EDGE('',*,*,#161011,.T.); -#165071 = ORIENTED_EDGE('',*,*,#160884,.T.); -#165072 = ORIENTED_EDGE('',*,*,#160854,.T.); -#165073 = ADVANCED_FACE('',(#165074),#160710,.T.); -#165074 = FACE_BOUND('',#165075,.T.); -#165075 = EDGE_LOOP('',(#165076,#165098,#165099,#165100)); -#165076 = ORIENTED_EDGE('',*,*,#165077,.F.); -#165077 = EDGE_CURVE('',#165010,#165078,#165080,.T.); -#165078 = VERTEX_POINT('',#165079); -#165079 = CARTESIAN_POINT('',(-1.695,0.985,2.141803043818)); -#165080 = SURFACE_CURVE('',#165081,(#165085,#165091),.PCURVE_S1.); -#165081 = LINE('',#165082,#165083); -#165082 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); -#165083 = VECTOR('',#165084,1.); -#165084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165085 = PCURVE('',#160710,#165086); -#165086 = DEFINITIONAL_REPRESENTATION('',(#165087),#165090); -#165087 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165088,#165089), +#167424 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167425 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#167426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167427 = ORIENTED_EDGE('',*,*,#167428,.F.); +#167428 = EDGE_CURVE('',#167353,#167402,#167429,.T.); +#167429 = SURFACE_CURVE('',#167430,(#167434,#167441),.PCURVE_S1.); +#167430 = LINE('',#167431,#167432); +#167431 = CARTESIAN_POINT('',(-2.115,0.985,0.E+000)); +#167432 = VECTOR('',#167433,1.); +#167433 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167434 = PCURVE('',#162526,#167435); +#167435 = DEFINITIONAL_REPRESENTATION('',(#167436),#167440); +#167436 = LINE('',#167437,#167438); +#167437 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167438 = VECTOR('',#167439,1.); +#167439 = DIRECTION('',(1.,0.E+000)); +#167440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167441 = PCURVE('',#166877,#167442); +#167442 = DEFINITIONAL_REPRESENTATION('',(#167443),#167447); +#167443 = LINE('',#167444,#167445); +#167444 = CARTESIAN_POINT('',(0.E+000,-2.75)); +#167445 = VECTOR('',#167446,1.); +#167446 = DIRECTION('',(1.,0.E+000)); +#167447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167448 = ORIENTED_EDGE('',*,*,#167376,.T.); +#167449 = ORIENTED_EDGE('',*,*,#162512,.T.); +#167450 = ORIENTED_EDGE('',*,*,#162541,.T.); +#167451 = ORIENTED_EDGE('',*,*,#162676,.T.); +#167452 = ORIENTED_EDGE('',*,*,#162700,.T.); +#167453 = ORIENTED_EDGE('',*,*,#162805,.T.); +#167454 = ORIENTED_EDGE('',*,*,#162880,.T.); +#167455 = ORIENTED_EDGE('',*,*,#162955,.T.); +#167456 = ORIENTED_EDGE('',*,*,#163029,.T.); +#167457 = ORIENTED_EDGE('',*,*,#166568,.T.); +#167458 = ORIENTED_EDGE('',*,*,#163652,.T.); +#167459 = ORIENTED_EDGE('',*,*,#163628,.T.); +#167460 = ORIENTED_EDGE('',*,*,#163553,.T.); +#167461 = ORIENTED_EDGE('',*,*,#163478,.T.); +#167462 = ORIENTED_EDGE('',*,*,#163403,.T.); +#167463 = ORIENTED_EDGE('',*,*,#163276,.T.); +#167464 = ORIENTED_EDGE('',*,*,#163246,.T.); +#167465 = ADVANCED_FACE('',(#167466),#163102,.T.); +#167466 = FACE_BOUND('',#167467,.T.); +#167467 = EDGE_LOOP('',(#167468,#167490,#167491,#167492)); +#167468 = ORIENTED_EDGE('',*,*,#167469,.F.); +#167469 = EDGE_CURVE('',#167402,#167470,#167472,.T.); +#167470 = VERTEX_POINT('',#167471); +#167471 = CARTESIAN_POINT('',(-1.695,0.985,2.141803043818)); +#167472 = SURFACE_CURVE('',#167473,(#167477,#167483),.PCURVE_S1.); +#167473 = LINE('',#167474,#167475); +#167474 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); +#167475 = VECTOR('',#167476,1.); +#167476 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167477 = PCURVE('',#163102,#167478); +#167478 = DEFINITIONAL_REPRESENTATION('',(#167479),#167482); +#167479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167480,#167481), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.75,-2.33),.PIECEWISE_BEZIER_KNOTS.); -#165088 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165089 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165091 = PCURVE('',#164485,#165092); -#165092 = DEFINITIONAL_REPRESENTATION('',(#165093),#165097); -#165093 = LINE('',#165094,#165095); -#165094 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#165095 = VECTOR('',#165096,1.); -#165096 = DIRECTION('',(0.E+000,1.)); -#165097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165098 = ORIENTED_EDGE('',*,*,#165009,.T.); -#165099 = ORIENTED_EDGE('',*,*,#160687,.T.); -#165100 = ORIENTED_EDGE('',*,*,#165101,.F.); -#165101 = EDGE_CURVE('',#165078,#160690,#165102,.T.); -#165102 = SURFACE_CURVE('',#165103,(#165108,#165114),.PCURVE_S1.); -#165103 = CIRCLE('',#165104,0.32); -#165104 = AXIS2_PLACEMENT_3D('',#165105,#165106,#165107); -#165105 = CARTESIAN_POINT('',(-1.695,0.665,2.141803043818)); -#165106 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165107 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165108 = PCURVE('',#160710,#165109); -#165109 = DEFINITIONAL_REPRESENTATION('',(#165110),#165113); -#165110 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165111,#165112), +#167480 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167481 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167483 = PCURVE('',#166877,#167484); +#167484 = DEFINITIONAL_REPRESENTATION('',(#167485),#167489); +#167485 = LINE('',#167486,#167487); +#167486 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#167487 = VECTOR('',#167488,1.); +#167488 = DIRECTION('',(0.E+000,1.)); +#167489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167490 = ORIENTED_EDGE('',*,*,#167401,.T.); +#167491 = ORIENTED_EDGE('',*,*,#163079,.T.); +#167492 = ORIENTED_EDGE('',*,*,#167493,.F.); +#167493 = EDGE_CURVE('',#167470,#163082,#167494,.T.); +#167494 = SURFACE_CURVE('',#167495,(#167500,#167506),.PCURVE_S1.); +#167495 = CIRCLE('',#167496,0.32); +#167496 = AXIS2_PLACEMENT_3D('',#167497,#167498,#167499); +#167497 = CARTESIAN_POINT('',(-1.695,0.665,2.141803043818)); +#167498 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167499 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167500 = PCURVE('',#163102,#167501); +#167501 = DEFINITIONAL_REPRESENTATION('',(#167502),#167505); +#167502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167503,#167504), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165111 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165112 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#165113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165114 = PCURVE('',#160785,#165115); -#165115 = DEFINITIONAL_REPRESENTATION('',(#165116),#165120); -#165116 = CIRCLE('',#165117,0.32); -#165117 = AXIS2_PLACEMENT_2D('',#165118,#165119); -#165118 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165119 = DIRECTION('',(1.,0.E+000)); -#165120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165121 = ADVANCED_FACE('',(#165122),#160785,.T.); -#165122 = FACE_BOUND('',#165123,.T.); -#165123 = EDGE_LOOP('',(#165124,#165125,#165126,#165149,#165170,#165171, - #165172,#165173,#165174,#165175,#165176,#165177)); -#165124 = ORIENTED_EDGE('',*,*,#161288,.T.); -#165125 = ORIENTED_EDGE('',*,*,#164154,.T.); -#165126 = ORIENTED_EDGE('',*,*,#165127,.F.); -#165127 = EDGE_CURVE('',#165128,#164127,#165130,.T.); -#165128 = VERTEX_POINT('',#165129); -#165129 = CARTESIAN_POINT('',(-1.695,0.985,0.21)); -#165130 = SURFACE_CURVE('',#165131,(#165135,#165142),.PCURVE_S1.); -#165131 = LINE('',#165132,#165133); -#165132 = CARTESIAN_POINT('',(-1.695,0.875,0.21)); -#165133 = VECTOR('',#165134,1.); -#165134 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165135 = PCURVE('',#160785,#165136); -#165136 = DEFINITIONAL_REPRESENTATION('',(#165137),#165141); -#165137 = LINE('',#165138,#165139); -#165138 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#165139 = VECTOR('',#165140,1.); -#165140 = DIRECTION('',(0.E+000,-1.)); -#165141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165142 = PCURVE('',#164142,#165143); -#165143 = DEFINITIONAL_REPRESENTATION('',(#165144),#165148); -#165144 = LINE('',#165145,#165146); -#165145 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165146 = VECTOR('',#165147,1.); -#165147 = DIRECTION('',(0.E+000,-1.)); -#165148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165149 = ORIENTED_EDGE('',*,*,#165150,.F.); -#165150 = EDGE_CURVE('',#165078,#165128,#165151,.T.); -#165151 = SURFACE_CURVE('',#165152,(#165156,#165163),.PCURVE_S1.); -#165152 = LINE('',#165153,#165154); -#165153 = CARTESIAN_POINT('',(-1.695,0.985,0.E+000)); -#165154 = VECTOR('',#165155,1.); -#165155 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165156 = PCURVE('',#160785,#165157); -#165157 = DEFINITIONAL_REPRESENTATION('',(#165158),#165162); -#165158 = LINE('',#165159,#165160); -#165159 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165160 = VECTOR('',#165161,1.); -#165161 = DIRECTION('',(1.,0.E+000)); -#165162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165163 = PCURVE('',#164485,#165164); -#165164 = DEFINITIONAL_REPRESENTATION('',(#165165),#165169); -#165165 = LINE('',#165166,#165167); -#165166 = CARTESIAN_POINT('',(0.E+000,-2.33)); -#165167 = VECTOR('',#165168,1.); -#165168 = DIRECTION('',(-1.,0.E+000)); -#165169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165170 = ORIENTED_EDGE('',*,*,#165101,.T.); -#165171 = ORIENTED_EDGE('',*,*,#160771,.T.); -#165172 = ORIENTED_EDGE('',*,*,#160800,.T.); -#165173 = ORIENTED_EDGE('',*,*,#160935,.T.); -#165174 = ORIENTED_EDGE('',*,*,#160989,.T.); -#165175 = ORIENTED_EDGE('',*,*,#161064,.T.); -#165176 = ORIENTED_EDGE('',*,*,#161139,.T.); -#165177 = ORIENTED_EDGE('',*,*,#161214,.T.); -#165178 = ADVANCED_FACE('',(#165179),#164142,.T.); -#165179 = FACE_BOUND('',#165180,.T.); -#165180 = EDGE_LOOP('',(#165181,#165204,#165225,#165226)); -#165181 = ORIENTED_EDGE('',*,*,#165182,.F.); -#165182 = EDGE_CURVE('',#165183,#164104,#165185,.T.); -#165183 = VERTEX_POINT('',#165184); -#165184 = CARTESIAN_POINT('',(-0.845,0.985,0.21)); -#165185 = SURFACE_CURVE('',#165186,(#165190,#165197),.PCURVE_S1.); -#165186 = LINE('',#165187,#165188); -#165187 = CARTESIAN_POINT('',(-0.845,0.875,0.21)); -#165188 = VECTOR('',#165189,1.); -#165189 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165190 = PCURVE('',#164142,#165191); -#165191 = DEFINITIONAL_REPRESENTATION('',(#165192),#165196); -#165192 = LINE('',#165193,#165194); -#165193 = CARTESIAN_POINT('',(1.06,0.E+000)); -#165194 = VECTOR('',#165195,1.); -#165195 = DIRECTION('',(0.E+000,-1.)); -#165196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165197 = PCURVE('',#161388,#165198); -#165198 = DEFINITIONAL_REPRESENTATION('',(#165199),#165203); -#165199 = LINE('',#165200,#165201); -#165200 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165201 = VECTOR('',#165202,1.); -#165202 = DIRECTION('',(0.E+000,-1.)); -#165203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165204 = ORIENTED_EDGE('',*,*,#165205,.F.); -#165205 = EDGE_CURVE('',#165128,#165183,#165206,.T.); -#165206 = SURFACE_CURVE('',#165207,(#165211,#165218),.PCURVE_S1.); -#165207 = LINE('',#165208,#165209); -#165208 = CARTESIAN_POINT('',(0.635,0.985,0.21)); -#165209 = VECTOR('',#165210,1.); -#165210 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165211 = PCURVE('',#164142,#165212); -#165212 = DEFINITIONAL_REPRESENTATION('',(#165213),#165217); -#165213 = LINE('',#165214,#165215); -#165214 = CARTESIAN_POINT('',(2.54,0.11)); -#165215 = VECTOR('',#165216,1.); -#165216 = DIRECTION('',(1.,0.E+000)); -#165217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165218 = PCURVE('',#164485,#165219); -#165219 = DEFINITIONAL_REPRESENTATION('',(#165220),#165224); -#165220 = LINE('',#165221,#165222); -#165221 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165222 = VECTOR('',#165223,1.); -#165223 = DIRECTION('',(0.E+000,1.)); -#165224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165225 = ORIENTED_EDGE('',*,*,#165127,.T.); -#165226 = ORIENTED_EDGE('',*,*,#164126,.T.); -#165227 = ADVANCED_FACE('',(#165228),#161388,.T.); -#165228 = FACE_BOUND('',#165229,.T.); -#165229 = EDGE_LOOP('',(#165230,#165257,#165278,#165279,#165280,#165281, - #165282,#165283,#165284,#165285,#165286,#165287)); -#165230 = ORIENTED_EDGE('',*,*,#165231,.F.); -#165231 = EDGE_CURVE('',#165232,#161339,#165234,.T.); -#165232 = VERTEX_POINT('',#165233); -#165233 = CARTESIAN_POINT('',(-0.845,0.985,2.141803043818)); -#165234 = SURFACE_CURVE('',#165235,(#165240,#165251),.PCURVE_S1.); -#165235 = CIRCLE('',#165236,0.32); -#165236 = AXIS2_PLACEMENT_3D('',#165237,#165238,#165239); -#165237 = CARTESIAN_POINT('',(-0.845,0.665,2.141803043818)); -#165238 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165239 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165240 = PCURVE('',#161388,#165241); -#165241 = DEFINITIONAL_REPRESENTATION('',(#165242),#165250); -#165242 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165243,#165244,#165245, - #165246,#165247,#165248,#165249),.UNSPECIFIED.,.T.,.F.) +#167503 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167504 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#167505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167506 = PCURVE('',#163177,#167507); +#167507 = DEFINITIONAL_REPRESENTATION('',(#167508),#167512); +#167508 = CIRCLE('',#167509,0.32); +#167509 = AXIS2_PLACEMENT_2D('',#167510,#167511); +#167510 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#167511 = DIRECTION('',(1.,0.E+000)); +#167512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167513 = ADVANCED_FACE('',(#167514),#163177,.T.); +#167514 = FACE_BOUND('',#167515,.T.); +#167515 = EDGE_LOOP('',(#167516,#167517,#167518,#167541,#167562,#167563, + #167564,#167565,#167566,#167567,#167568,#167569)); +#167516 = ORIENTED_EDGE('',*,*,#163680,.T.); +#167517 = ORIENTED_EDGE('',*,*,#166546,.T.); +#167518 = ORIENTED_EDGE('',*,*,#167519,.F.); +#167519 = EDGE_CURVE('',#167520,#166519,#167522,.T.); +#167520 = VERTEX_POINT('',#167521); +#167521 = CARTESIAN_POINT('',(-1.695,0.985,0.21)); +#167522 = SURFACE_CURVE('',#167523,(#167527,#167534),.PCURVE_S1.); +#167523 = LINE('',#167524,#167525); +#167524 = CARTESIAN_POINT('',(-1.695,0.875,0.21)); +#167525 = VECTOR('',#167526,1.); +#167526 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167527 = PCURVE('',#163177,#167528); +#167528 = DEFINITIONAL_REPRESENTATION('',(#167529),#167533); +#167529 = LINE('',#167530,#167531); +#167530 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167531 = VECTOR('',#167532,1.); +#167532 = DIRECTION('',(0.E+000,-1.)); +#167533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167534 = PCURVE('',#166534,#167535); +#167535 = DEFINITIONAL_REPRESENTATION('',(#167536),#167540); +#167536 = LINE('',#167537,#167538); +#167537 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167538 = VECTOR('',#167539,1.); +#167539 = DIRECTION('',(0.E+000,-1.)); +#167540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167541 = ORIENTED_EDGE('',*,*,#167542,.F.); +#167542 = EDGE_CURVE('',#167470,#167520,#167543,.T.); +#167543 = SURFACE_CURVE('',#167544,(#167548,#167555),.PCURVE_S1.); +#167544 = LINE('',#167545,#167546); +#167545 = CARTESIAN_POINT('',(-1.695,0.985,0.E+000)); +#167546 = VECTOR('',#167547,1.); +#167547 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167548 = PCURVE('',#163177,#167549); +#167549 = DEFINITIONAL_REPRESENTATION('',(#167550),#167554); +#167550 = LINE('',#167551,#167552); +#167551 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167552 = VECTOR('',#167553,1.); +#167553 = DIRECTION('',(1.,0.E+000)); +#167554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167555 = PCURVE('',#166877,#167556); +#167556 = DEFINITIONAL_REPRESENTATION('',(#167557),#167561); +#167557 = LINE('',#167558,#167559); +#167558 = CARTESIAN_POINT('',(0.E+000,-2.33)); +#167559 = VECTOR('',#167560,1.); +#167560 = DIRECTION('',(-1.,0.E+000)); +#167561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167562 = ORIENTED_EDGE('',*,*,#167493,.T.); +#167563 = ORIENTED_EDGE('',*,*,#163163,.T.); +#167564 = ORIENTED_EDGE('',*,*,#163192,.T.); +#167565 = ORIENTED_EDGE('',*,*,#163327,.T.); +#167566 = ORIENTED_EDGE('',*,*,#163381,.T.); +#167567 = ORIENTED_EDGE('',*,*,#163456,.T.); +#167568 = ORIENTED_EDGE('',*,*,#163531,.T.); +#167569 = ORIENTED_EDGE('',*,*,#163606,.T.); +#167570 = ADVANCED_FACE('',(#167571),#166534,.T.); +#167571 = FACE_BOUND('',#167572,.T.); +#167572 = EDGE_LOOP('',(#167573,#167596,#167617,#167618)); +#167573 = ORIENTED_EDGE('',*,*,#167574,.F.); +#167574 = EDGE_CURVE('',#167575,#166496,#167577,.T.); +#167575 = VERTEX_POINT('',#167576); +#167576 = CARTESIAN_POINT('',(-0.845,0.985,0.21)); +#167577 = SURFACE_CURVE('',#167578,(#167582,#167589),.PCURVE_S1.); +#167578 = LINE('',#167579,#167580); +#167579 = CARTESIAN_POINT('',(-0.845,0.875,0.21)); +#167580 = VECTOR('',#167581,1.); +#167581 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167582 = PCURVE('',#166534,#167583); +#167583 = DEFINITIONAL_REPRESENTATION('',(#167584),#167588); +#167584 = LINE('',#167585,#167586); +#167585 = CARTESIAN_POINT('',(1.06,0.E+000)); +#167586 = VECTOR('',#167587,1.); +#167587 = DIRECTION('',(0.E+000,-1.)); +#167588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167589 = PCURVE('',#163780,#167590); +#167590 = DEFINITIONAL_REPRESENTATION('',(#167591),#167595); +#167591 = LINE('',#167592,#167593); +#167592 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167593 = VECTOR('',#167594,1.); +#167594 = DIRECTION('',(0.E+000,-1.)); +#167595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167596 = ORIENTED_EDGE('',*,*,#167597,.F.); +#167597 = EDGE_CURVE('',#167520,#167575,#167598,.T.); +#167598 = SURFACE_CURVE('',#167599,(#167603,#167610),.PCURVE_S1.); +#167599 = LINE('',#167600,#167601); +#167600 = CARTESIAN_POINT('',(0.635,0.985,0.21)); +#167601 = VECTOR('',#167602,1.); +#167602 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167603 = PCURVE('',#166534,#167604); +#167604 = DEFINITIONAL_REPRESENTATION('',(#167605),#167609); +#167605 = LINE('',#167606,#167607); +#167606 = CARTESIAN_POINT('',(2.54,0.11)); +#167607 = VECTOR('',#167608,1.); +#167608 = DIRECTION('',(1.,0.E+000)); +#167609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167610 = PCURVE('',#166877,#167611); +#167611 = DEFINITIONAL_REPRESENTATION('',(#167612),#167616); +#167612 = LINE('',#167613,#167614); +#167613 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167614 = VECTOR('',#167615,1.); +#167615 = DIRECTION('',(0.E+000,1.)); +#167616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167617 = ORIENTED_EDGE('',*,*,#167519,.T.); +#167618 = ORIENTED_EDGE('',*,*,#166518,.T.); +#167619 = ADVANCED_FACE('',(#167620),#163780,.T.); +#167620 = FACE_BOUND('',#167621,.T.); +#167621 = EDGE_LOOP('',(#167622,#167649,#167670,#167671,#167672,#167673, + #167674,#167675,#167676,#167677,#167678,#167679)); +#167622 = ORIENTED_EDGE('',*,*,#167623,.F.); +#167623 = EDGE_CURVE('',#167624,#163731,#167626,.T.); +#167624 = VERTEX_POINT('',#167625); +#167625 = CARTESIAN_POINT('',(-0.845,0.985,2.141803043818)); +#167626 = SURFACE_CURVE('',#167627,(#167632,#167643),.PCURVE_S1.); +#167627 = CIRCLE('',#167628,0.32); +#167628 = AXIS2_PLACEMENT_3D('',#167629,#167630,#167631); +#167629 = CARTESIAN_POINT('',(-0.845,0.665,2.141803043818)); +#167630 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167631 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167632 = PCURVE('',#163780,#167633); +#167633 = DEFINITIONAL_REPRESENTATION('',(#167634),#167642); +#167634 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167635,#167636,#167637, + #167638,#167639,#167640,#167641),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#165243 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165244 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#165245 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#165246 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#165247 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#165248 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#165249 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165251 = PCURVE('',#161361,#165252); -#165252 = DEFINITIONAL_REPRESENTATION('',(#165253),#165256); -#165253 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165254,#165255), +#167635 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167636 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#167637 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#167638 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#167639 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#167640 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#167641 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167643 = PCURVE('',#163753,#167644); +#167644 = DEFINITIONAL_REPRESENTATION('',(#167645),#167648); +#167645 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167646,#167647), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165254 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165255 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#165256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165257 = ORIENTED_EDGE('',*,*,#165258,.F.); -#165258 = EDGE_CURVE('',#165183,#165232,#165259,.T.); -#165259 = SURFACE_CURVE('',#165260,(#165264,#165271),.PCURVE_S1.); -#165260 = LINE('',#165261,#165262); -#165261 = CARTESIAN_POINT('',(-0.845,0.985,0.E+000)); -#165262 = VECTOR('',#165263,1.); -#165263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165264 = PCURVE('',#161388,#165265); -#165265 = DEFINITIONAL_REPRESENTATION('',(#165266),#165270); -#165266 = LINE('',#165267,#165268); -#165267 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165268 = VECTOR('',#165269,1.); -#165269 = DIRECTION('',(1.,0.E+000)); -#165270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165271 = PCURVE('',#164485,#165272); -#165272 = DEFINITIONAL_REPRESENTATION('',(#165273),#165277); -#165273 = LINE('',#165274,#165275); -#165274 = CARTESIAN_POINT('',(0.E+000,-1.48)); -#165275 = VECTOR('',#165276,1.); -#165276 = DIRECTION('',(1.,0.E+000)); -#165277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165278 = ORIENTED_EDGE('',*,*,#165182,.T.); -#165279 = ORIENTED_EDGE('',*,*,#164103,.T.); -#165280 = ORIENTED_EDGE('',*,*,#161916,.T.); -#165281 = ORIENTED_EDGE('',*,*,#161892,.T.); -#165282 = ORIENTED_EDGE('',*,*,#161817,.T.); -#165283 = ORIENTED_EDGE('',*,*,#161742,.T.); -#165284 = ORIENTED_EDGE('',*,*,#161667,.T.); -#165285 = ORIENTED_EDGE('',*,*,#161540,.T.); -#165286 = ORIENTED_EDGE('',*,*,#161510,.T.); -#165287 = ORIENTED_EDGE('',*,*,#161372,.T.); -#165288 = ADVANCED_FACE('',(#165289),#161361,.T.); -#165289 = FACE_BOUND('',#165290,.T.); -#165290 = EDGE_LOOP('',(#165291,#165313,#165314,#165315)); -#165291 = ORIENTED_EDGE('',*,*,#165292,.F.); -#165292 = EDGE_CURVE('',#165232,#165293,#165295,.T.); -#165293 = VERTEX_POINT('',#165294); -#165294 = CARTESIAN_POINT('',(-0.425,0.985,2.141803043818)); -#165295 = SURFACE_CURVE('',#165296,(#165300,#165306),.PCURVE_S1.); -#165296 = LINE('',#165297,#165298); -#165297 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); -#165298 = VECTOR('',#165299,1.); -#165299 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165300 = PCURVE('',#161361,#165301); -#165301 = DEFINITIONAL_REPRESENTATION('',(#165302),#165305); -#165302 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165303,#165304), +#167646 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167647 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#167648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167649 = ORIENTED_EDGE('',*,*,#167650,.F.); +#167650 = EDGE_CURVE('',#167575,#167624,#167651,.T.); +#167651 = SURFACE_CURVE('',#167652,(#167656,#167663),.PCURVE_S1.); +#167652 = LINE('',#167653,#167654); +#167653 = CARTESIAN_POINT('',(-0.845,0.985,0.E+000)); +#167654 = VECTOR('',#167655,1.); +#167655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167656 = PCURVE('',#163780,#167657); +#167657 = DEFINITIONAL_REPRESENTATION('',(#167658),#167662); +#167658 = LINE('',#167659,#167660); +#167659 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167660 = VECTOR('',#167661,1.); +#167661 = DIRECTION('',(1.,0.E+000)); +#167662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167663 = PCURVE('',#166877,#167664); +#167664 = DEFINITIONAL_REPRESENTATION('',(#167665),#167669); +#167665 = LINE('',#167666,#167667); +#167666 = CARTESIAN_POINT('',(0.E+000,-1.48)); +#167667 = VECTOR('',#167668,1.); +#167668 = DIRECTION('',(1.,0.E+000)); +#167669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167670 = ORIENTED_EDGE('',*,*,#167574,.T.); +#167671 = ORIENTED_EDGE('',*,*,#166495,.T.); +#167672 = ORIENTED_EDGE('',*,*,#164308,.T.); +#167673 = ORIENTED_EDGE('',*,*,#164284,.T.); +#167674 = ORIENTED_EDGE('',*,*,#164209,.T.); +#167675 = ORIENTED_EDGE('',*,*,#164134,.T.); +#167676 = ORIENTED_EDGE('',*,*,#164059,.T.); +#167677 = ORIENTED_EDGE('',*,*,#163932,.T.); +#167678 = ORIENTED_EDGE('',*,*,#163902,.T.); +#167679 = ORIENTED_EDGE('',*,*,#163764,.T.); +#167680 = ADVANCED_FACE('',(#167681),#163753,.T.); +#167681 = FACE_BOUND('',#167682,.T.); +#167682 = EDGE_LOOP('',(#167683,#167705,#167706,#167707)); +#167683 = ORIENTED_EDGE('',*,*,#167684,.F.); +#167684 = EDGE_CURVE('',#167624,#167685,#167687,.T.); +#167685 = VERTEX_POINT('',#167686); +#167686 = CARTESIAN_POINT('',(-0.425,0.985,2.141803043818)); +#167687 = SURFACE_CURVE('',#167688,(#167692,#167698),.PCURVE_S1.); +#167688 = LINE('',#167689,#167690); +#167689 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); +#167690 = VECTOR('',#167691,1.); +#167691 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167692 = PCURVE('',#163753,#167693); +#167693 = DEFINITIONAL_REPRESENTATION('',(#167694),#167697); +#167694 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167695,#167696), .UNSPECIFIED.,.F.,.F.,(2,2),(-1.48,-1.06),.PIECEWISE_BEZIER_KNOTS.); -#165303 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165304 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165306 = PCURVE('',#164485,#165307); -#165307 = DEFINITIONAL_REPRESENTATION('',(#165308),#165312); -#165308 = LINE('',#165309,#165310); -#165309 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#165310 = VECTOR('',#165311,1.); -#165311 = DIRECTION('',(0.E+000,1.)); -#165312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165313 = ORIENTED_EDGE('',*,*,#165231,.T.); -#165314 = ORIENTED_EDGE('',*,*,#161338,.T.); -#165315 = ORIENTED_EDGE('',*,*,#165316,.F.); -#165316 = EDGE_CURVE('',#165293,#161341,#165317,.T.); -#165317 = SURFACE_CURVE('',#165318,(#165323,#165329),.PCURVE_S1.); -#165318 = CIRCLE('',#165319,0.32); -#165319 = AXIS2_PLACEMENT_3D('',#165320,#165321,#165322); -#165320 = CARTESIAN_POINT('',(-0.425,0.665,2.141803043818)); -#165321 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165322 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165323 = PCURVE('',#161361,#165324); -#165324 = DEFINITIONAL_REPRESENTATION('',(#165325),#165328); -#165325 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165326,#165327), +#167695 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167696 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167698 = PCURVE('',#166877,#167699); +#167699 = DEFINITIONAL_REPRESENTATION('',(#167700),#167704); +#167700 = LINE('',#167701,#167702); +#167701 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#167702 = VECTOR('',#167703,1.); +#167703 = DIRECTION('',(0.E+000,1.)); +#167704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167705 = ORIENTED_EDGE('',*,*,#167623,.T.); +#167706 = ORIENTED_EDGE('',*,*,#163730,.T.); +#167707 = ORIENTED_EDGE('',*,*,#167708,.F.); +#167708 = EDGE_CURVE('',#167685,#163733,#167709,.T.); +#167709 = SURFACE_CURVE('',#167710,(#167715,#167721),.PCURVE_S1.); +#167710 = CIRCLE('',#167711,0.32); +#167711 = AXIS2_PLACEMENT_3D('',#167712,#167713,#167714); +#167712 = CARTESIAN_POINT('',(-0.425,0.665,2.141803043818)); +#167713 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167714 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167715 = PCURVE('',#163753,#167716); +#167716 = DEFINITIONAL_REPRESENTATION('',(#167717),#167720); +#167717 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167718,#167719), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165326 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165327 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#165328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#167718 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167719 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#167720 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#165329 = PCURVE('',#161441,#165330); -#165330 = DEFINITIONAL_REPRESENTATION('',(#165331),#165335); -#165331 = CIRCLE('',#165332,0.32); -#165332 = AXIS2_PLACEMENT_2D('',#165333,#165334); -#165333 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165334 = DIRECTION('',(1.,0.E+000)); -#165335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#167721 = PCURVE('',#163833,#167722); +#167722 = DEFINITIONAL_REPRESENTATION('',(#167723),#167727); +#167723 = CIRCLE('',#167724,0.32); +#167724 = AXIS2_PLACEMENT_2D('',#167725,#167726); +#167725 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#167726 = DIRECTION('',(1.,0.E+000)); +#167727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#165336 = ADVANCED_FACE('',(#165337),#161441,.T.); -#165337 = FACE_BOUND('',#165338,.T.); -#165338 = EDGE_LOOP('',(#165339,#165340,#165341,#165364,#165385,#165386, - #165387,#165388,#165389,#165390,#165391,#165392)); -#165339 = ORIENTED_EDGE('',*,*,#161944,.T.); -#165340 = ORIENTED_EDGE('',*,*,#164081,.T.); -#165341 = ORIENTED_EDGE('',*,*,#165342,.F.); -#165342 = EDGE_CURVE('',#165343,#164054,#165345,.T.); -#165343 = VERTEX_POINT('',#165344); -#165344 = CARTESIAN_POINT('',(-0.425,0.985,0.21)); -#165345 = SURFACE_CURVE('',#165346,(#165350,#165357),.PCURVE_S1.); -#165346 = LINE('',#165347,#165348); -#165347 = CARTESIAN_POINT('',(-0.425,0.875,0.21)); -#165348 = VECTOR('',#165349,1.); -#165349 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165350 = PCURVE('',#161441,#165351); -#165351 = DEFINITIONAL_REPRESENTATION('',(#165352),#165356); -#165352 = LINE('',#165353,#165354); -#165353 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#165354 = VECTOR('',#165355,1.); -#165355 = DIRECTION('',(0.E+000,-1.)); -#165356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165357 = PCURVE('',#164069,#165358); -#165358 = DEFINITIONAL_REPRESENTATION('',(#165359),#165363); -#165359 = LINE('',#165360,#165361); -#165360 = CARTESIAN_POINT('',(1.48,0.E+000)); -#165361 = VECTOR('',#165362,1.); -#165362 = DIRECTION('',(0.E+000,-1.)); -#165363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165364 = ORIENTED_EDGE('',*,*,#165365,.F.); -#165365 = EDGE_CURVE('',#165293,#165343,#165366,.T.); -#165366 = SURFACE_CURVE('',#165367,(#165371,#165378),.PCURVE_S1.); -#165367 = LINE('',#165368,#165369); -#165368 = CARTESIAN_POINT('',(-0.425,0.985,0.E+000)); -#165369 = VECTOR('',#165370,1.); -#165370 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165371 = PCURVE('',#161441,#165372); -#165372 = DEFINITIONAL_REPRESENTATION('',(#165373),#165377); -#165373 = LINE('',#165374,#165375); -#165374 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165375 = VECTOR('',#165376,1.); -#165376 = DIRECTION('',(1.,0.E+000)); -#165377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165378 = PCURVE('',#164485,#165379); -#165379 = DEFINITIONAL_REPRESENTATION('',(#165380),#165384); -#165380 = LINE('',#165381,#165382); -#165381 = CARTESIAN_POINT('',(0.E+000,-1.06)); -#165382 = VECTOR('',#165383,1.); -#165383 = DIRECTION('',(-1.,0.E+000)); -#165384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165385 = ORIENTED_EDGE('',*,*,#165316,.T.); -#165386 = ORIENTED_EDGE('',*,*,#161427,.T.); -#165387 = ORIENTED_EDGE('',*,*,#161456,.T.); -#165388 = ORIENTED_EDGE('',*,*,#161591,.T.); -#165389 = ORIENTED_EDGE('',*,*,#161645,.T.); -#165390 = ORIENTED_EDGE('',*,*,#161720,.T.); -#165391 = ORIENTED_EDGE('',*,*,#161795,.T.); -#165392 = ORIENTED_EDGE('',*,*,#161870,.T.); -#165393 = ADVANCED_FACE('',(#165394),#164069,.T.); -#165394 = FACE_BOUND('',#165395,.T.); -#165395 = EDGE_LOOP('',(#165396,#165397,#165398,#165421)); -#165396 = ORIENTED_EDGE('',*,*,#165342,.T.); -#165397 = ORIENTED_EDGE('',*,*,#164053,.T.); -#165398 = ORIENTED_EDGE('',*,*,#165399,.F.); -#165399 = EDGE_CURVE('',#165400,#164031,#165402,.T.); -#165400 = VERTEX_POINT('',#165401); -#165401 = CARTESIAN_POINT('',(0.425,0.985,0.21)); -#165402 = SURFACE_CURVE('',#165403,(#165407,#165414),.PCURVE_S1.); -#165403 = LINE('',#165404,#165405); -#165404 = CARTESIAN_POINT('',(0.425,0.875,0.21)); -#165405 = VECTOR('',#165406,1.); -#165406 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165407 = PCURVE('',#164069,#165408); -#165408 = DEFINITIONAL_REPRESENTATION('',(#165409),#165413); -#165409 = LINE('',#165410,#165411); -#165410 = CARTESIAN_POINT('',(2.33,0.E+000)); -#165411 = VECTOR('',#165412,1.); -#165412 = DIRECTION('',(0.E+000,-1.)); -#165413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165414 = PCURVE('',#162044,#165415); -#165415 = DEFINITIONAL_REPRESENTATION('',(#165416),#165420); -#165416 = LINE('',#165417,#165418); -#165417 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165418 = VECTOR('',#165419,1.); -#165419 = DIRECTION('',(0.E+000,-1.)); -#165420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165421 = ORIENTED_EDGE('',*,*,#165422,.F.); -#165422 = EDGE_CURVE('',#165343,#165400,#165423,.T.); -#165423 = SURFACE_CURVE('',#165424,(#165428,#165435),.PCURVE_S1.); -#165424 = LINE('',#165425,#165426); -#165425 = CARTESIAN_POINT('',(0.635,0.985,0.21)); -#165426 = VECTOR('',#165427,1.); -#165427 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165428 = PCURVE('',#164069,#165429); -#165429 = DEFINITIONAL_REPRESENTATION('',(#165430),#165434); -#165430 = LINE('',#165431,#165432); -#165431 = CARTESIAN_POINT('',(2.54,0.11)); -#165432 = VECTOR('',#165433,1.); -#165433 = DIRECTION('',(1.,0.E+000)); -#165434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165435 = PCURVE('',#164485,#165436); -#165436 = DEFINITIONAL_REPRESENTATION('',(#165437),#165441); -#165437 = LINE('',#165438,#165439); -#165438 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165439 = VECTOR('',#165440,1.); -#165440 = DIRECTION('',(0.E+000,1.)); -#165441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165442 = ADVANCED_FACE('',(#165443),#162044,.T.); -#165443 = FACE_BOUND('',#165444,.T.); -#165444 = EDGE_LOOP('',(#165445,#165472,#165493,#165494,#165495,#165496, - #165497,#165498,#165499,#165500,#165501,#165502)); -#165445 = ORIENTED_EDGE('',*,*,#165446,.F.); -#165446 = EDGE_CURVE('',#165447,#161995,#165449,.T.); -#165447 = VERTEX_POINT('',#165448); -#165448 = CARTESIAN_POINT('',(0.425,0.985,2.141803043818)); -#165449 = SURFACE_CURVE('',#165450,(#165455,#165466),.PCURVE_S1.); -#165450 = CIRCLE('',#165451,0.32); -#165451 = AXIS2_PLACEMENT_3D('',#165452,#165453,#165454); -#165452 = CARTESIAN_POINT('',(0.425,0.665,2.141803043818)); -#165453 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165454 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165455 = PCURVE('',#162044,#165456); -#165456 = DEFINITIONAL_REPRESENTATION('',(#165457),#165465); -#165457 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165458,#165459,#165460, - #165461,#165462,#165463,#165464),.UNSPECIFIED.,.T.,.F.) +#167728 = ADVANCED_FACE('',(#167729),#163833,.T.); +#167729 = FACE_BOUND('',#167730,.T.); +#167730 = EDGE_LOOP('',(#167731,#167732,#167733,#167756,#167777,#167778, + #167779,#167780,#167781,#167782,#167783,#167784)); +#167731 = ORIENTED_EDGE('',*,*,#164336,.T.); +#167732 = ORIENTED_EDGE('',*,*,#166473,.T.); +#167733 = ORIENTED_EDGE('',*,*,#167734,.F.); +#167734 = EDGE_CURVE('',#167735,#166446,#167737,.T.); +#167735 = VERTEX_POINT('',#167736); +#167736 = CARTESIAN_POINT('',(-0.425,0.985,0.21)); +#167737 = SURFACE_CURVE('',#167738,(#167742,#167749),.PCURVE_S1.); +#167738 = LINE('',#167739,#167740); +#167739 = CARTESIAN_POINT('',(-0.425,0.875,0.21)); +#167740 = VECTOR('',#167741,1.); +#167741 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167742 = PCURVE('',#163833,#167743); +#167743 = DEFINITIONAL_REPRESENTATION('',(#167744),#167748); +#167744 = LINE('',#167745,#167746); +#167745 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167746 = VECTOR('',#167747,1.); +#167747 = DIRECTION('',(0.E+000,-1.)); +#167748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167749 = PCURVE('',#166461,#167750); +#167750 = DEFINITIONAL_REPRESENTATION('',(#167751),#167755); +#167751 = LINE('',#167752,#167753); +#167752 = CARTESIAN_POINT('',(1.48,0.E+000)); +#167753 = VECTOR('',#167754,1.); +#167754 = DIRECTION('',(0.E+000,-1.)); +#167755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167756 = ORIENTED_EDGE('',*,*,#167757,.F.); +#167757 = EDGE_CURVE('',#167685,#167735,#167758,.T.); +#167758 = SURFACE_CURVE('',#167759,(#167763,#167770),.PCURVE_S1.); +#167759 = LINE('',#167760,#167761); +#167760 = CARTESIAN_POINT('',(-0.425,0.985,0.E+000)); +#167761 = VECTOR('',#167762,1.); +#167762 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167763 = PCURVE('',#163833,#167764); +#167764 = DEFINITIONAL_REPRESENTATION('',(#167765),#167769); +#167765 = LINE('',#167766,#167767); +#167766 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167767 = VECTOR('',#167768,1.); +#167768 = DIRECTION('',(1.,0.E+000)); +#167769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167770 = PCURVE('',#166877,#167771); +#167771 = DEFINITIONAL_REPRESENTATION('',(#167772),#167776); +#167772 = LINE('',#167773,#167774); +#167773 = CARTESIAN_POINT('',(0.E+000,-1.06)); +#167774 = VECTOR('',#167775,1.); +#167775 = DIRECTION('',(-1.,0.E+000)); +#167776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167777 = ORIENTED_EDGE('',*,*,#167708,.T.); +#167778 = ORIENTED_EDGE('',*,*,#163819,.T.); +#167779 = ORIENTED_EDGE('',*,*,#163848,.T.); +#167780 = ORIENTED_EDGE('',*,*,#163983,.T.); +#167781 = ORIENTED_EDGE('',*,*,#164037,.T.); +#167782 = ORIENTED_EDGE('',*,*,#164112,.T.); +#167783 = ORIENTED_EDGE('',*,*,#164187,.T.); +#167784 = ORIENTED_EDGE('',*,*,#164262,.T.); +#167785 = ADVANCED_FACE('',(#167786),#166461,.T.); +#167786 = FACE_BOUND('',#167787,.T.); +#167787 = EDGE_LOOP('',(#167788,#167789,#167790,#167813)); +#167788 = ORIENTED_EDGE('',*,*,#167734,.T.); +#167789 = ORIENTED_EDGE('',*,*,#166445,.T.); +#167790 = ORIENTED_EDGE('',*,*,#167791,.F.); +#167791 = EDGE_CURVE('',#167792,#166423,#167794,.T.); +#167792 = VERTEX_POINT('',#167793); +#167793 = CARTESIAN_POINT('',(0.425,0.985,0.21)); +#167794 = SURFACE_CURVE('',#167795,(#167799,#167806),.PCURVE_S1.); +#167795 = LINE('',#167796,#167797); +#167796 = CARTESIAN_POINT('',(0.425,0.875,0.21)); +#167797 = VECTOR('',#167798,1.); +#167798 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167799 = PCURVE('',#166461,#167800); +#167800 = DEFINITIONAL_REPRESENTATION('',(#167801),#167805); +#167801 = LINE('',#167802,#167803); +#167802 = CARTESIAN_POINT('',(2.33,0.E+000)); +#167803 = VECTOR('',#167804,1.); +#167804 = DIRECTION('',(0.E+000,-1.)); +#167805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167806 = PCURVE('',#164436,#167807); +#167807 = DEFINITIONAL_REPRESENTATION('',(#167808),#167812); +#167808 = LINE('',#167809,#167810); +#167809 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167810 = VECTOR('',#167811,1.); +#167811 = DIRECTION('',(0.E+000,-1.)); +#167812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167813 = ORIENTED_EDGE('',*,*,#167814,.F.); +#167814 = EDGE_CURVE('',#167735,#167792,#167815,.T.); +#167815 = SURFACE_CURVE('',#167816,(#167820,#167827),.PCURVE_S1.); +#167816 = LINE('',#167817,#167818); +#167817 = CARTESIAN_POINT('',(0.635,0.985,0.21)); +#167818 = VECTOR('',#167819,1.); +#167819 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167820 = PCURVE('',#166461,#167821); +#167821 = DEFINITIONAL_REPRESENTATION('',(#167822),#167826); +#167822 = LINE('',#167823,#167824); +#167823 = CARTESIAN_POINT('',(2.54,0.11)); +#167824 = VECTOR('',#167825,1.); +#167825 = DIRECTION('',(1.,0.E+000)); +#167826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167827 = PCURVE('',#166877,#167828); +#167828 = DEFINITIONAL_REPRESENTATION('',(#167829),#167833); +#167829 = LINE('',#167830,#167831); +#167830 = CARTESIAN_POINT('',(0.21,0.E+000)); +#167831 = VECTOR('',#167832,1.); +#167832 = DIRECTION('',(0.E+000,1.)); +#167833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167834 = ADVANCED_FACE('',(#167835),#164436,.T.); +#167835 = FACE_BOUND('',#167836,.T.); +#167836 = EDGE_LOOP('',(#167837,#167864,#167885,#167886,#167887,#167888, + #167889,#167890,#167891,#167892,#167893,#167894)); +#167837 = ORIENTED_EDGE('',*,*,#167838,.F.); +#167838 = EDGE_CURVE('',#167839,#164387,#167841,.T.); +#167839 = VERTEX_POINT('',#167840); +#167840 = CARTESIAN_POINT('',(0.425,0.985,2.141803043818)); +#167841 = SURFACE_CURVE('',#167842,(#167847,#167858),.PCURVE_S1.); +#167842 = CIRCLE('',#167843,0.32); +#167843 = AXIS2_PLACEMENT_3D('',#167844,#167845,#167846); +#167844 = CARTESIAN_POINT('',(0.425,0.665,2.141803043818)); +#167845 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167846 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167847 = PCURVE('',#164436,#167848); +#167848 = DEFINITIONAL_REPRESENTATION('',(#167849),#167857); +#167849 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167850,#167851,#167852, + #167853,#167854,#167855,#167856),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#165458 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165459 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#165460 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#165461 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#165462 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#165463 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#165464 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165466 = PCURVE('',#162017,#165467); -#165467 = DEFINITIONAL_REPRESENTATION('',(#165468),#165471); -#165468 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165469,#165470), +#167850 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167851 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#167852 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#167853 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#167854 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#167855 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#167856 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#167857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167858 = PCURVE('',#164409,#167859); +#167859 = DEFINITIONAL_REPRESENTATION('',(#167860),#167863); +#167860 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167861,#167862), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165469 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165470 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#165471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165472 = ORIENTED_EDGE('',*,*,#165473,.F.); -#165473 = EDGE_CURVE('',#165400,#165447,#165474,.T.); -#165474 = SURFACE_CURVE('',#165475,(#165479,#165486),.PCURVE_S1.); -#165475 = LINE('',#165476,#165477); -#165476 = CARTESIAN_POINT('',(0.425,0.985,0.E+000)); -#165477 = VECTOR('',#165478,1.); -#165478 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165479 = PCURVE('',#162044,#165480); -#165480 = DEFINITIONAL_REPRESENTATION('',(#165481),#165485); -#165481 = LINE('',#165482,#165483); -#165482 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165483 = VECTOR('',#165484,1.); -#165484 = DIRECTION('',(1.,0.E+000)); -#165485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165486 = PCURVE('',#164485,#165487); -#165487 = DEFINITIONAL_REPRESENTATION('',(#165488),#165492); -#165488 = LINE('',#165489,#165490); -#165489 = CARTESIAN_POINT('',(0.E+000,-0.21)); -#165490 = VECTOR('',#165491,1.); -#165491 = DIRECTION('',(1.,0.E+000)); -#165492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165493 = ORIENTED_EDGE('',*,*,#165399,.T.); -#165494 = ORIENTED_EDGE('',*,*,#164030,.T.); -#165495 = ORIENTED_EDGE('',*,*,#162572,.T.); -#165496 = ORIENTED_EDGE('',*,*,#162548,.T.); -#165497 = ORIENTED_EDGE('',*,*,#162473,.T.); -#165498 = ORIENTED_EDGE('',*,*,#162398,.T.); -#165499 = ORIENTED_EDGE('',*,*,#162323,.T.); -#165500 = ORIENTED_EDGE('',*,*,#162196,.T.); -#165501 = ORIENTED_EDGE('',*,*,#162166,.T.); -#165502 = ORIENTED_EDGE('',*,*,#162028,.T.); -#165503 = ADVANCED_FACE('',(#165504),#162017,.T.); -#165504 = FACE_BOUND('',#165505,.T.); -#165505 = EDGE_LOOP('',(#165506,#165528,#165529,#165530)); -#165506 = ORIENTED_EDGE('',*,*,#165507,.F.); -#165507 = EDGE_CURVE('',#165447,#165508,#165510,.T.); -#165508 = VERTEX_POINT('',#165509); -#165509 = CARTESIAN_POINT('',(0.845,0.985,2.141803043818)); -#165510 = SURFACE_CURVE('',#165511,(#165515,#165521),.PCURVE_S1.); -#165511 = LINE('',#165512,#165513); -#165512 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); -#165513 = VECTOR('',#165514,1.); -#165514 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165515 = PCURVE('',#162017,#165516); -#165516 = DEFINITIONAL_REPRESENTATION('',(#165517),#165520); -#165517 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165518,#165519), +#167861 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167862 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#167863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167864 = ORIENTED_EDGE('',*,*,#167865,.F.); +#167865 = EDGE_CURVE('',#167792,#167839,#167866,.T.); +#167866 = SURFACE_CURVE('',#167867,(#167871,#167878),.PCURVE_S1.); +#167867 = LINE('',#167868,#167869); +#167868 = CARTESIAN_POINT('',(0.425,0.985,0.E+000)); +#167869 = VECTOR('',#167870,1.); +#167870 = DIRECTION('',(0.E+000,0.E+000,1.)); +#167871 = PCURVE('',#164436,#167872); +#167872 = DEFINITIONAL_REPRESENTATION('',(#167873),#167877); +#167873 = LINE('',#167874,#167875); +#167874 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167875 = VECTOR('',#167876,1.); +#167876 = DIRECTION('',(1.,0.E+000)); +#167877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167878 = PCURVE('',#166877,#167879); +#167879 = DEFINITIONAL_REPRESENTATION('',(#167880),#167884); +#167880 = LINE('',#167881,#167882); +#167881 = CARTESIAN_POINT('',(0.E+000,-0.21)); +#167882 = VECTOR('',#167883,1.); +#167883 = DIRECTION('',(1.,0.E+000)); +#167884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167885 = ORIENTED_EDGE('',*,*,#167791,.T.); +#167886 = ORIENTED_EDGE('',*,*,#166422,.T.); +#167887 = ORIENTED_EDGE('',*,*,#164964,.T.); +#167888 = ORIENTED_EDGE('',*,*,#164940,.T.); +#167889 = ORIENTED_EDGE('',*,*,#164865,.T.); +#167890 = ORIENTED_EDGE('',*,*,#164790,.T.); +#167891 = ORIENTED_EDGE('',*,*,#164715,.T.); +#167892 = ORIENTED_EDGE('',*,*,#164588,.T.); +#167893 = ORIENTED_EDGE('',*,*,#164558,.T.); +#167894 = ORIENTED_EDGE('',*,*,#164420,.T.); +#167895 = ADVANCED_FACE('',(#167896),#164409,.T.); +#167896 = FACE_BOUND('',#167897,.T.); +#167897 = EDGE_LOOP('',(#167898,#167920,#167921,#167922)); +#167898 = ORIENTED_EDGE('',*,*,#167899,.F.); +#167899 = EDGE_CURVE('',#167839,#167900,#167902,.T.); +#167900 = VERTEX_POINT('',#167901); +#167901 = CARTESIAN_POINT('',(0.845,0.985,2.141803043818)); +#167902 = SURFACE_CURVE('',#167903,(#167907,#167913),.PCURVE_S1.); +#167903 = LINE('',#167904,#167905); +#167904 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); +#167905 = VECTOR('',#167906,1.); +#167906 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167907 = PCURVE('',#164409,#167908); +#167908 = DEFINITIONAL_REPRESENTATION('',(#167909),#167912); +#167909 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167910,#167911), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.21,0.21),.PIECEWISE_BEZIER_KNOTS.); -#165518 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165519 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165521 = PCURVE('',#164485,#165522); -#165522 = DEFINITIONAL_REPRESENTATION('',(#165523),#165527); -#165523 = LINE('',#165524,#165525); -#165524 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#165525 = VECTOR('',#165526,1.); -#165526 = DIRECTION('',(0.E+000,1.)); -#165527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165528 = ORIENTED_EDGE('',*,*,#165446,.T.); -#165529 = ORIENTED_EDGE('',*,*,#161994,.T.); -#165530 = ORIENTED_EDGE('',*,*,#165531,.F.); -#165531 = EDGE_CURVE('',#165508,#161997,#165532,.T.); -#165532 = SURFACE_CURVE('',#165533,(#165538,#165544),.PCURVE_S1.); -#165533 = CIRCLE('',#165534,0.32); -#165534 = AXIS2_PLACEMENT_3D('',#165535,#165536,#165537); -#165535 = CARTESIAN_POINT('',(0.845,0.665,2.141803043818)); -#165536 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165537 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165538 = PCURVE('',#162017,#165539); -#165539 = DEFINITIONAL_REPRESENTATION('',(#165540),#165543); -#165540 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165541,#165542), +#167910 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#167911 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167913 = PCURVE('',#166877,#167914); +#167914 = DEFINITIONAL_REPRESENTATION('',(#167915),#167919); +#167915 = LINE('',#167916,#167917); +#167916 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#167917 = VECTOR('',#167918,1.); +#167918 = DIRECTION('',(0.E+000,1.)); +#167919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167920 = ORIENTED_EDGE('',*,*,#167838,.T.); +#167921 = ORIENTED_EDGE('',*,*,#164386,.T.); +#167922 = ORIENTED_EDGE('',*,*,#167923,.F.); +#167923 = EDGE_CURVE('',#167900,#164389,#167924,.T.); +#167924 = SURFACE_CURVE('',#167925,(#167930,#167936),.PCURVE_S1.); +#167925 = CIRCLE('',#167926,0.32); +#167926 = AXIS2_PLACEMENT_3D('',#167927,#167928,#167929); +#167927 = CARTESIAN_POINT('',(0.845,0.665,2.141803043818)); +#167928 = DIRECTION('',(1.,0.E+000,0.E+000)); +#167929 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167930 = PCURVE('',#164409,#167931); +#167931 = DEFINITIONAL_REPRESENTATION('',(#167932),#167935); +#167932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167933,#167934), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165541 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165542 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#165543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165544 = PCURVE('',#162097,#165545); -#165545 = DEFINITIONAL_REPRESENTATION('',(#165546),#165550); -#165546 = CIRCLE('',#165547,0.32); -#165547 = AXIS2_PLACEMENT_2D('',#165548,#165549); -#165548 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165549 = DIRECTION('',(1.,0.E+000)); -#165550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165551 = ADVANCED_FACE('',(#165552),#162097,.T.); -#165552 = FACE_BOUND('',#165553,.T.); -#165553 = EDGE_LOOP('',(#165554,#165555,#165556,#165579,#165600,#165601, - #165602,#165603,#165604,#165605,#165606,#165607)); -#165554 = ORIENTED_EDGE('',*,*,#162600,.T.); -#165555 = ORIENTED_EDGE('',*,*,#164008,.T.); -#165556 = ORIENTED_EDGE('',*,*,#165557,.F.); -#165557 = EDGE_CURVE('',#165558,#163981,#165560,.T.); -#165558 = VERTEX_POINT('',#165559); -#165559 = CARTESIAN_POINT('',(0.845,0.985,0.21)); -#165560 = SURFACE_CURVE('',#165561,(#165565,#165572),.PCURVE_S1.); -#165561 = LINE('',#165562,#165563); -#165562 = CARTESIAN_POINT('',(0.845,0.875,0.21)); -#165563 = VECTOR('',#165564,1.); -#165564 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165565 = PCURVE('',#162097,#165566); -#165566 = DEFINITIONAL_REPRESENTATION('',(#165567),#165571); -#165567 = LINE('',#165568,#165569); -#165568 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#165569 = VECTOR('',#165570,1.); -#165570 = DIRECTION('',(0.E+000,-1.)); -#165571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165572 = PCURVE('',#163996,#165573); -#165573 = DEFINITIONAL_REPRESENTATION('',(#165574),#165578); -#165574 = LINE('',#165575,#165576); -#165575 = CARTESIAN_POINT('',(2.75,0.E+000)); -#165576 = VECTOR('',#165577,1.); -#165577 = DIRECTION('',(0.E+000,-1.)); -#165578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165579 = ORIENTED_EDGE('',*,*,#165580,.F.); -#165580 = EDGE_CURVE('',#165508,#165558,#165581,.T.); -#165581 = SURFACE_CURVE('',#165582,(#165586,#165593),.PCURVE_S1.); -#165582 = LINE('',#165583,#165584); -#165583 = CARTESIAN_POINT('',(0.845,0.985,0.E+000)); -#165584 = VECTOR('',#165585,1.); -#165585 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165586 = PCURVE('',#162097,#165587); -#165587 = DEFINITIONAL_REPRESENTATION('',(#165588),#165592); -#165588 = LINE('',#165589,#165590); -#165589 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165590 = VECTOR('',#165591,1.); -#165591 = DIRECTION('',(1.,0.E+000)); -#165592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165593 = PCURVE('',#164485,#165594); -#165594 = DEFINITIONAL_REPRESENTATION('',(#165595),#165599); -#165595 = LINE('',#165596,#165597); -#165596 = CARTESIAN_POINT('',(0.E+000,0.21)); -#165597 = VECTOR('',#165598,1.); -#165598 = DIRECTION('',(-1.,0.E+000)); -#165599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165600 = ORIENTED_EDGE('',*,*,#165531,.T.); -#165601 = ORIENTED_EDGE('',*,*,#162083,.T.); -#165602 = ORIENTED_EDGE('',*,*,#162112,.T.); -#165603 = ORIENTED_EDGE('',*,*,#162247,.T.); -#165604 = ORIENTED_EDGE('',*,*,#162301,.T.); -#165605 = ORIENTED_EDGE('',*,*,#162376,.T.); -#165606 = ORIENTED_EDGE('',*,*,#162451,.T.); -#165607 = ORIENTED_EDGE('',*,*,#162526,.T.); -#165608 = ADVANCED_FACE('',(#165609),#163996,.T.); -#165609 = FACE_BOUND('',#165610,.T.); -#165610 = EDGE_LOOP('',(#165611,#165634,#165655,#165656)); -#165611 = ORIENTED_EDGE('',*,*,#165612,.F.); -#165612 = EDGE_CURVE('',#165613,#163958,#165615,.T.); -#165613 = VERTEX_POINT('',#165614); -#165614 = CARTESIAN_POINT('',(1.695,0.985,0.21)); -#165615 = SURFACE_CURVE('',#165616,(#165620,#165627),.PCURVE_S1.); -#165616 = LINE('',#165617,#165618); -#165617 = CARTESIAN_POINT('',(1.695,0.875,0.21)); -#165618 = VECTOR('',#165619,1.); -#165619 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165620 = PCURVE('',#163996,#165621); -#165621 = DEFINITIONAL_REPRESENTATION('',(#165622),#165626); -#165622 = LINE('',#165623,#165624); -#165623 = CARTESIAN_POINT('',(3.6,0.E+000)); -#165624 = VECTOR('',#165625,1.); -#165625 = DIRECTION('',(0.E+000,-1.)); -#165626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165627 = PCURVE('',#162700,#165628); -#165628 = DEFINITIONAL_REPRESENTATION('',(#165629),#165633); -#165629 = LINE('',#165630,#165631); -#165630 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165631 = VECTOR('',#165632,1.); -#165632 = DIRECTION('',(0.E+000,-1.)); -#165633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165634 = ORIENTED_EDGE('',*,*,#165635,.F.); -#165635 = EDGE_CURVE('',#165558,#165613,#165636,.T.); -#165636 = SURFACE_CURVE('',#165637,(#165641,#165648),.PCURVE_S1.); -#165637 = LINE('',#165638,#165639); -#165638 = CARTESIAN_POINT('',(0.635,0.985,0.21)); -#165639 = VECTOR('',#165640,1.); -#165640 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165641 = PCURVE('',#163996,#165642); -#165642 = DEFINITIONAL_REPRESENTATION('',(#165643),#165647); -#165643 = LINE('',#165644,#165645); -#165644 = CARTESIAN_POINT('',(2.54,0.11)); -#165645 = VECTOR('',#165646,1.); -#165646 = DIRECTION('',(1.,0.E+000)); -#165647 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165648 = PCURVE('',#164485,#165649); -#165649 = DEFINITIONAL_REPRESENTATION('',(#165650),#165654); -#165650 = LINE('',#165651,#165652); -#165651 = CARTESIAN_POINT('',(0.21,0.E+000)); -#165652 = VECTOR('',#165653,1.); -#165653 = DIRECTION('',(0.E+000,1.)); -#165654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165655 = ORIENTED_EDGE('',*,*,#165557,.T.); -#165656 = ORIENTED_EDGE('',*,*,#163980,.T.); -#165657 = ADVANCED_FACE('',(#165658),#162700,.T.); -#165658 = FACE_BOUND('',#165659,.T.); -#165659 = EDGE_LOOP('',(#165660,#165687,#165708,#165709,#165710,#165711, - #165712,#165713,#165714,#165715,#165716,#165717)); -#165660 = ORIENTED_EDGE('',*,*,#165661,.F.); -#165661 = EDGE_CURVE('',#165662,#162651,#165664,.T.); -#165662 = VERTEX_POINT('',#165663); -#165663 = CARTESIAN_POINT('',(1.695,0.985,2.141803043818)); -#165664 = SURFACE_CURVE('',#165665,(#165670,#165681),.PCURVE_S1.); -#165665 = CIRCLE('',#165666,0.32); -#165666 = AXIS2_PLACEMENT_3D('',#165667,#165668,#165669); -#165667 = CARTESIAN_POINT('',(1.695,0.665,2.141803043818)); -#165668 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165669 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165670 = PCURVE('',#162700,#165671); -#165671 = DEFINITIONAL_REPRESENTATION('',(#165672),#165680); -#165672 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165673,#165674,#165675, - #165676,#165677,#165678,#165679),.UNSPECIFIED.,.T.,.F.) +#167933 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#167934 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#167935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167936 = PCURVE('',#164489,#167937); +#167937 = DEFINITIONAL_REPRESENTATION('',(#167938),#167942); +#167938 = CIRCLE('',#167939,0.32); +#167939 = AXIS2_PLACEMENT_2D('',#167940,#167941); +#167940 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#167941 = DIRECTION('',(1.,0.E+000)); +#167942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167943 = ADVANCED_FACE('',(#167944),#164489,.T.); +#167944 = FACE_BOUND('',#167945,.T.); +#167945 = EDGE_LOOP('',(#167946,#167947,#167948,#167971,#167992,#167993, + #167994,#167995,#167996,#167997,#167998,#167999)); +#167946 = ORIENTED_EDGE('',*,*,#164992,.T.); +#167947 = ORIENTED_EDGE('',*,*,#166400,.T.); +#167948 = ORIENTED_EDGE('',*,*,#167949,.F.); +#167949 = EDGE_CURVE('',#167950,#166373,#167952,.T.); +#167950 = VERTEX_POINT('',#167951); +#167951 = CARTESIAN_POINT('',(0.845,0.985,0.21)); +#167952 = SURFACE_CURVE('',#167953,(#167957,#167964),.PCURVE_S1.); +#167953 = LINE('',#167954,#167955); +#167954 = CARTESIAN_POINT('',(0.845,0.875,0.21)); +#167955 = VECTOR('',#167956,1.); +#167956 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#167957 = PCURVE('',#164489,#167958); +#167958 = DEFINITIONAL_REPRESENTATION('',(#167959),#167963); +#167959 = LINE('',#167960,#167961); +#167960 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#167961 = VECTOR('',#167962,1.); +#167962 = DIRECTION('',(0.E+000,-1.)); +#167963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167964 = PCURVE('',#166388,#167965); +#167965 = DEFINITIONAL_REPRESENTATION('',(#167966),#167970); +#167966 = LINE('',#167967,#167968); +#167967 = CARTESIAN_POINT('',(2.75,0.E+000)); +#167968 = VECTOR('',#167969,1.); +#167969 = DIRECTION('',(0.E+000,-1.)); +#167970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167971 = ORIENTED_EDGE('',*,*,#167972,.F.); +#167972 = EDGE_CURVE('',#167900,#167950,#167973,.T.); +#167973 = SURFACE_CURVE('',#167974,(#167978,#167985),.PCURVE_S1.); +#167974 = LINE('',#167975,#167976); +#167975 = CARTESIAN_POINT('',(0.845,0.985,0.E+000)); +#167976 = VECTOR('',#167977,1.); +#167977 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#167978 = PCURVE('',#164489,#167979); +#167979 = DEFINITIONAL_REPRESENTATION('',(#167980),#167984); +#167980 = LINE('',#167981,#167982); +#167981 = CARTESIAN_POINT('',(0.E+000,0.11)); +#167982 = VECTOR('',#167983,1.); +#167983 = DIRECTION('',(1.,0.E+000)); +#167984 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167985 = PCURVE('',#166877,#167986); +#167986 = DEFINITIONAL_REPRESENTATION('',(#167987),#167991); +#167987 = LINE('',#167988,#167989); +#167988 = CARTESIAN_POINT('',(0.E+000,0.21)); +#167989 = VECTOR('',#167990,1.); +#167990 = DIRECTION('',(-1.,0.E+000)); +#167991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#167992 = ORIENTED_EDGE('',*,*,#167923,.T.); +#167993 = ORIENTED_EDGE('',*,*,#164475,.T.); +#167994 = ORIENTED_EDGE('',*,*,#164504,.T.); +#167995 = ORIENTED_EDGE('',*,*,#164639,.T.); +#167996 = ORIENTED_EDGE('',*,*,#164693,.T.); +#167997 = ORIENTED_EDGE('',*,*,#164768,.T.); +#167998 = ORIENTED_EDGE('',*,*,#164843,.T.); +#167999 = ORIENTED_EDGE('',*,*,#164918,.T.); +#168000 = ADVANCED_FACE('',(#168001),#166388,.T.); +#168001 = FACE_BOUND('',#168002,.T.); +#168002 = EDGE_LOOP('',(#168003,#168026,#168047,#168048)); +#168003 = ORIENTED_EDGE('',*,*,#168004,.F.); +#168004 = EDGE_CURVE('',#168005,#166350,#168007,.T.); +#168005 = VERTEX_POINT('',#168006); +#168006 = CARTESIAN_POINT('',(1.695,0.985,0.21)); +#168007 = SURFACE_CURVE('',#168008,(#168012,#168019),.PCURVE_S1.); +#168008 = LINE('',#168009,#168010); +#168009 = CARTESIAN_POINT('',(1.695,0.875,0.21)); +#168010 = VECTOR('',#168011,1.); +#168011 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168012 = PCURVE('',#166388,#168013); +#168013 = DEFINITIONAL_REPRESENTATION('',(#168014),#168018); +#168014 = LINE('',#168015,#168016); +#168015 = CARTESIAN_POINT('',(3.6,0.E+000)); +#168016 = VECTOR('',#168017,1.); +#168017 = DIRECTION('',(0.E+000,-1.)); +#168018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168019 = PCURVE('',#165092,#168020); +#168020 = DEFINITIONAL_REPRESENTATION('',(#168021),#168025); +#168021 = LINE('',#168022,#168023); +#168022 = CARTESIAN_POINT('',(0.21,0.E+000)); +#168023 = VECTOR('',#168024,1.); +#168024 = DIRECTION('',(0.E+000,-1.)); +#168025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168026 = ORIENTED_EDGE('',*,*,#168027,.F.); +#168027 = EDGE_CURVE('',#167950,#168005,#168028,.T.); +#168028 = SURFACE_CURVE('',#168029,(#168033,#168040),.PCURVE_S1.); +#168029 = LINE('',#168030,#168031); +#168030 = CARTESIAN_POINT('',(0.635,0.985,0.21)); +#168031 = VECTOR('',#168032,1.); +#168032 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168033 = PCURVE('',#166388,#168034); +#168034 = DEFINITIONAL_REPRESENTATION('',(#168035),#168039); +#168035 = LINE('',#168036,#168037); +#168036 = CARTESIAN_POINT('',(2.54,0.11)); +#168037 = VECTOR('',#168038,1.); +#168038 = DIRECTION('',(1.,0.E+000)); +#168039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168040 = PCURVE('',#166877,#168041); +#168041 = DEFINITIONAL_REPRESENTATION('',(#168042),#168046); +#168042 = LINE('',#168043,#168044); +#168043 = CARTESIAN_POINT('',(0.21,0.E+000)); +#168044 = VECTOR('',#168045,1.); +#168045 = DIRECTION('',(0.E+000,1.)); +#168046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168047 = ORIENTED_EDGE('',*,*,#167949,.T.); +#168048 = ORIENTED_EDGE('',*,*,#166372,.T.); +#168049 = ADVANCED_FACE('',(#168050),#165092,.T.); +#168050 = FACE_BOUND('',#168051,.T.); +#168051 = EDGE_LOOP('',(#168052,#168079,#168100,#168101,#168102,#168103, + #168104,#168105,#168106,#168107,#168108,#168109)); +#168052 = ORIENTED_EDGE('',*,*,#168053,.F.); +#168053 = EDGE_CURVE('',#168054,#165043,#168056,.T.); +#168054 = VERTEX_POINT('',#168055); +#168055 = CARTESIAN_POINT('',(1.695,0.985,2.141803043818)); +#168056 = SURFACE_CURVE('',#168057,(#168062,#168073),.PCURVE_S1.); +#168057 = CIRCLE('',#168058,0.32); +#168058 = AXIS2_PLACEMENT_3D('',#168059,#168060,#168061); +#168059 = CARTESIAN_POINT('',(1.695,0.665,2.141803043818)); +#168060 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168061 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#168062 = PCURVE('',#165092,#168063); +#168063 = DEFINITIONAL_REPRESENTATION('',(#168064),#168072); +#168064 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#168065,#168066,#168067, + #168068,#168069,#168070,#168071),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#165673 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165674 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#165675 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#165676 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#165677 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#165678 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#165679 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165681 = PCURVE('',#162673,#165682); -#165682 = DEFINITIONAL_REPRESENTATION('',(#165683),#165686); -#165683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165684,#165685), +#168065 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#168066 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#168067 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#168068 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#168069 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#168070 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#168071 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#168072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168073 = PCURVE('',#165065,#168074); +#168074 = DEFINITIONAL_REPRESENTATION('',(#168075),#168078); +#168075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168076,#168077), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165684 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165685 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#165686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165687 = ORIENTED_EDGE('',*,*,#165688,.F.); -#165688 = EDGE_CURVE('',#165613,#165662,#165689,.T.); -#165689 = SURFACE_CURVE('',#165690,(#165694,#165701),.PCURVE_S1.); -#165690 = LINE('',#165691,#165692); -#165691 = CARTESIAN_POINT('',(1.695,0.985,0.E+000)); -#165692 = VECTOR('',#165693,1.); -#165693 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165694 = PCURVE('',#162700,#165695); -#165695 = DEFINITIONAL_REPRESENTATION('',(#165696),#165700); -#165696 = LINE('',#165697,#165698); -#165697 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165698 = VECTOR('',#165699,1.); -#165699 = DIRECTION('',(1.,0.E+000)); -#165700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165701 = PCURVE('',#164485,#165702); -#165702 = DEFINITIONAL_REPRESENTATION('',(#165703),#165707); -#165703 = LINE('',#165704,#165705); -#165704 = CARTESIAN_POINT('',(0.E+000,1.06)); -#165705 = VECTOR('',#165706,1.); -#165706 = DIRECTION('',(1.,0.E+000)); -#165707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165708 = ORIENTED_EDGE('',*,*,#165612,.T.); -#165709 = ORIENTED_EDGE('',*,*,#163957,.T.); -#165710 = ORIENTED_EDGE('',*,*,#163228,.T.); -#165711 = ORIENTED_EDGE('',*,*,#163204,.T.); -#165712 = ORIENTED_EDGE('',*,*,#163129,.T.); -#165713 = ORIENTED_EDGE('',*,*,#163054,.T.); -#165714 = ORIENTED_EDGE('',*,*,#162979,.T.); -#165715 = ORIENTED_EDGE('',*,*,#162852,.T.); -#165716 = ORIENTED_EDGE('',*,*,#162822,.T.); -#165717 = ORIENTED_EDGE('',*,*,#162684,.T.); -#165718 = ADVANCED_FACE('',(#165719),#162673,.T.); -#165719 = FACE_BOUND('',#165720,.T.); -#165720 = EDGE_LOOP('',(#165721,#165743,#165744,#165745)); -#165721 = ORIENTED_EDGE('',*,*,#165722,.F.); -#165722 = EDGE_CURVE('',#165662,#165723,#165725,.T.); -#165723 = VERTEX_POINT('',#165724); -#165724 = CARTESIAN_POINT('',(2.115,0.985,2.141803043818)); -#165725 = SURFACE_CURVE('',#165726,(#165730,#165736),.PCURVE_S1.); -#165726 = LINE('',#165727,#165728); -#165727 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); -#165728 = VECTOR('',#165729,1.); -#165729 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165730 = PCURVE('',#162673,#165731); -#165731 = DEFINITIONAL_REPRESENTATION('',(#165732),#165735); -#165732 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165733,#165734), +#168076 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#168077 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#168078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168079 = ORIENTED_EDGE('',*,*,#168080,.F.); +#168080 = EDGE_CURVE('',#168005,#168054,#168081,.T.); +#168081 = SURFACE_CURVE('',#168082,(#168086,#168093),.PCURVE_S1.); +#168082 = LINE('',#168083,#168084); +#168083 = CARTESIAN_POINT('',(1.695,0.985,0.E+000)); +#168084 = VECTOR('',#168085,1.); +#168085 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168086 = PCURVE('',#165092,#168087); +#168087 = DEFINITIONAL_REPRESENTATION('',(#168088),#168092); +#168088 = LINE('',#168089,#168090); +#168089 = CARTESIAN_POINT('',(0.E+000,0.11)); +#168090 = VECTOR('',#168091,1.); +#168091 = DIRECTION('',(1.,0.E+000)); +#168092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168093 = PCURVE('',#166877,#168094); +#168094 = DEFINITIONAL_REPRESENTATION('',(#168095),#168099); +#168095 = LINE('',#168096,#168097); +#168096 = CARTESIAN_POINT('',(0.E+000,1.06)); +#168097 = VECTOR('',#168098,1.); +#168098 = DIRECTION('',(1.,0.E+000)); +#168099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168100 = ORIENTED_EDGE('',*,*,#168004,.T.); +#168101 = ORIENTED_EDGE('',*,*,#166349,.T.); +#168102 = ORIENTED_EDGE('',*,*,#165620,.T.); +#168103 = ORIENTED_EDGE('',*,*,#165596,.T.); +#168104 = ORIENTED_EDGE('',*,*,#165521,.T.); +#168105 = ORIENTED_EDGE('',*,*,#165446,.T.); +#168106 = ORIENTED_EDGE('',*,*,#165371,.T.); +#168107 = ORIENTED_EDGE('',*,*,#165244,.T.); +#168108 = ORIENTED_EDGE('',*,*,#165214,.T.); +#168109 = ORIENTED_EDGE('',*,*,#165076,.T.); +#168110 = ADVANCED_FACE('',(#168111),#165065,.T.); +#168111 = FACE_BOUND('',#168112,.T.); +#168112 = EDGE_LOOP('',(#168113,#168135,#168136,#168137)); +#168113 = ORIENTED_EDGE('',*,*,#168114,.F.); +#168114 = EDGE_CURVE('',#168054,#168115,#168117,.T.); +#168115 = VERTEX_POINT('',#168116); +#168116 = CARTESIAN_POINT('',(2.115,0.985,2.141803043818)); +#168117 = SURFACE_CURVE('',#168118,(#168122,#168128),.PCURVE_S1.); +#168118 = LINE('',#168119,#168120); +#168119 = CARTESIAN_POINT('',(0.635,0.985,2.141803043818)); +#168120 = VECTOR('',#168121,1.); +#168121 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168122 = PCURVE('',#165065,#168123); +#168123 = DEFINITIONAL_REPRESENTATION('',(#168124),#168127); +#168124 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168125,#168126), .UNSPECIFIED.,.F.,.F.,(2,2),(1.06,1.48),.PIECEWISE_BEZIER_KNOTS.); -#165733 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165734 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165736 = PCURVE('',#164485,#165737); -#165737 = DEFINITIONAL_REPRESENTATION('',(#165738),#165742); -#165738 = LINE('',#165739,#165740); -#165739 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); -#165740 = VECTOR('',#165741,1.); -#165741 = DIRECTION('',(0.E+000,1.)); -#165742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165743 = ORIENTED_EDGE('',*,*,#165661,.T.); -#165744 = ORIENTED_EDGE('',*,*,#162650,.T.); -#165745 = ORIENTED_EDGE('',*,*,#165746,.F.); -#165746 = EDGE_CURVE('',#165723,#162653,#165747,.T.); -#165747 = SURFACE_CURVE('',#165748,(#165753,#165759),.PCURVE_S1.); -#165748 = CIRCLE('',#165749,0.32); -#165749 = AXIS2_PLACEMENT_3D('',#165750,#165751,#165752); -#165750 = CARTESIAN_POINT('',(2.115,0.665,2.141803043818)); -#165751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#165752 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165753 = PCURVE('',#162673,#165754); -#165754 = DEFINITIONAL_REPRESENTATION('',(#165755),#165758); -#165755 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165756,#165757), +#168125 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#168126 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#168127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168128 = PCURVE('',#166877,#168129); +#168129 = DEFINITIONAL_REPRESENTATION('',(#168130),#168134); +#168130 = LINE('',#168131,#168132); +#168131 = CARTESIAN_POINT('',(2.141803043818,0.E+000)); +#168132 = VECTOR('',#168133,1.); +#168133 = DIRECTION('',(0.E+000,1.)); +#168134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168135 = ORIENTED_EDGE('',*,*,#168053,.T.); +#168136 = ORIENTED_EDGE('',*,*,#165042,.T.); +#168137 = ORIENTED_EDGE('',*,*,#168138,.F.); +#168138 = EDGE_CURVE('',#168115,#165045,#168139,.T.); +#168139 = SURFACE_CURVE('',#168140,(#168145,#168151),.PCURVE_S1.); +#168140 = CIRCLE('',#168141,0.32); +#168141 = AXIS2_PLACEMENT_3D('',#168142,#168143,#168144); +#168142 = CARTESIAN_POINT('',(2.115,0.665,2.141803043818)); +#168143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168144 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#168145 = PCURVE('',#165065,#168146); +#168146 = DEFINITIONAL_REPRESENTATION('',(#168147),#168150); +#168147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168148,#168149), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165756 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165757 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#165758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165759 = PCURVE('',#162753,#165760); -#165760 = DEFINITIONAL_REPRESENTATION('',(#165761),#165765); -#165761 = CIRCLE('',#165762,0.32); -#165762 = AXIS2_PLACEMENT_2D('',#165763,#165764); -#165763 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165764 = DIRECTION('',(1.,0.E+000)); -#165765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165766 = ADVANCED_FACE('',(#165767),#162753,.T.); -#165767 = FACE_BOUND('',#165768,.T.); -#165768 = EDGE_LOOP('',(#165769,#165770,#165771,#165772,#165773,#165774, - #165775,#165776,#165777,#165778,#165779,#165780,#165807,#165828, - #165829,#165830,#165831,#165832,#165833,#165834)); -#165769 = ORIENTED_EDGE('',*,*,#163182,.T.); -#165770 = ORIENTED_EDGE('',*,*,#163256,.T.); -#165771 = ORIENTED_EDGE('',*,*,#164417,.T.); -#165772 = ORIENTED_EDGE('',*,*,#163879,.T.); -#165773 = ORIENTED_EDGE('',*,*,#163855,.T.); -#165774 = ORIENTED_EDGE('',*,*,#163780,.T.); -#165775 = ORIENTED_EDGE('',*,*,#163705,.T.); -#165776 = ORIENTED_EDGE('',*,*,#163602,.T.); -#165777 = ORIENTED_EDGE('',*,*,#163503,.T.); -#165778 = ORIENTED_EDGE('',*,*,#163473,.T.); -#165779 = ORIENTED_EDGE('',*,*,#163340,.T.); -#165780 = ORIENTED_EDGE('',*,*,#165781,.F.); -#165781 = EDGE_CURVE('',#165782,#163307,#165784,.T.); -#165782 = VERTEX_POINT('',#165783); -#165783 = CARTESIAN_POINT('',(2.115,0.985,-2.141803043818)); -#165784 = SURFACE_CURVE('',#165785,(#165790,#165801),.PCURVE_S1.); -#165785 = CIRCLE('',#165786,0.32); -#165786 = AXIS2_PLACEMENT_3D('',#165787,#165788,#165789); -#165787 = CARTESIAN_POINT('',(2.115,0.665,-2.141803043818)); -#165788 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#165789 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165790 = PCURVE('',#162753,#165791); -#165791 = DEFINITIONAL_REPRESENTATION('',(#165792),#165800); -#165792 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#165793,#165794,#165795, - #165796,#165797,#165798,#165799),.UNSPECIFIED.,.T.,.F.) +#168148 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#168149 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#168150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168151 = PCURVE('',#165145,#168152); +#168152 = DEFINITIONAL_REPRESENTATION('',(#168153),#168157); +#168153 = CIRCLE('',#168154,0.32); +#168154 = AXIS2_PLACEMENT_2D('',#168155,#168156); +#168155 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#168156 = DIRECTION('',(1.,0.E+000)); +#168157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168158 = ADVANCED_FACE('',(#168159),#165145,.T.); +#168159 = FACE_BOUND('',#168160,.T.); +#168160 = EDGE_LOOP('',(#168161,#168162,#168163,#168164,#168165,#168166, + #168167,#168168,#168169,#168170,#168171,#168172,#168199,#168220, + #168221,#168222,#168223,#168224,#168225,#168226)); +#168161 = ORIENTED_EDGE('',*,*,#165574,.T.); +#168162 = ORIENTED_EDGE('',*,*,#165648,.T.); +#168163 = ORIENTED_EDGE('',*,*,#166809,.T.); +#168164 = ORIENTED_EDGE('',*,*,#166271,.T.); +#168165 = ORIENTED_EDGE('',*,*,#166247,.T.); +#168166 = ORIENTED_EDGE('',*,*,#166172,.T.); +#168167 = ORIENTED_EDGE('',*,*,#166097,.T.); +#168168 = ORIENTED_EDGE('',*,*,#165994,.T.); +#168169 = ORIENTED_EDGE('',*,*,#165895,.T.); +#168170 = ORIENTED_EDGE('',*,*,#165865,.T.); +#168171 = ORIENTED_EDGE('',*,*,#165732,.T.); +#168172 = ORIENTED_EDGE('',*,*,#168173,.F.); +#168173 = EDGE_CURVE('',#168174,#165699,#168176,.T.); +#168174 = VERTEX_POINT('',#168175); +#168175 = CARTESIAN_POINT('',(2.115,0.985,-2.141803043818)); +#168176 = SURFACE_CURVE('',#168177,(#168182,#168193),.PCURVE_S1.); +#168177 = CIRCLE('',#168178,0.32); +#168178 = AXIS2_PLACEMENT_3D('',#168179,#168180,#168181); +#168179 = CARTESIAN_POINT('',(2.115,0.665,-2.141803043818)); +#168180 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168181 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168182 = PCURVE('',#165145,#168183); +#168183 = DEFINITIONAL_REPRESENTATION('',(#168184),#168192); +#168184 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#168185,#168186,#168187, + #168188,#168189,#168190,#168191),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#165793 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165794 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); -#165795 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); -#165796 = CARTESIAN_POINT('',(2.781803043818,-0.21)); -#165797 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); -#165798 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); -#165799 = CARTESIAN_POINT('',(1.821803043818,-0.21)); -#165800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165801 = PCURVE('',#163329,#165802); -#165802 = DEFINITIONAL_REPRESENTATION('',(#165803),#165806); -#165803 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165804,#165805), +#168185 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#168186 = CARTESIAN_POINT('',(1.821803043818,0.344256258422)); +#168187 = CARTESIAN_POINT('',(2.301803043818,6.712812921102E-002)); +#168188 = CARTESIAN_POINT('',(2.781803043818,-0.21)); +#168189 = CARTESIAN_POINT('',(2.301803043818,-0.487128129211)); +#168190 = CARTESIAN_POINT('',(1.821803043818,-0.764256258422)); +#168191 = CARTESIAN_POINT('',(1.821803043818,-0.21)); +#168192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168193 = PCURVE('',#165721,#168194); +#168194 = DEFINITIONAL_REPRESENTATION('',(#168195),#168198); +#168195 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168196,#168197), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165804 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165805 = CARTESIAN_POINT('',(3.010457322736,-0.21)); -#165806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#168196 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#168197 = CARTESIAN_POINT('',(3.010457322736,-0.21)); +#168198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168199 = ORIENTED_EDGE('',*,*,#168200,.F.); +#168200 = EDGE_CURVE('',#168115,#168174,#168201,.T.); +#168201 = SURFACE_CURVE('',#168202,(#168206,#168213),.PCURVE_S1.); +#168202 = LINE('',#168203,#168204); +#168203 = CARTESIAN_POINT('',(2.115,0.985,0.E+000)); +#168204 = VECTOR('',#168205,1.); +#168205 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#168206 = PCURVE('',#165145,#168207); +#168207 = DEFINITIONAL_REPRESENTATION('',(#168208),#168212); +#168208 = LINE('',#168209,#168210); +#168209 = CARTESIAN_POINT('',(0.E+000,0.11)); +#168210 = VECTOR('',#168211,1.); +#168211 = DIRECTION('',(1.,0.E+000)); +#168212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168213 = PCURVE('',#166877,#168214); +#168214 = DEFINITIONAL_REPRESENTATION('',(#168215),#168219); +#168215 = LINE('',#168216,#168217); +#168216 = CARTESIAN_POINT('',(0.E+000,1.48)); +#168217 = VECTOR('',#168218,1.); +#168218 = DIRECTION('',(-1.,0.E+000)); +#168219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168220 = ORIENTED_EDGE('',*,*,#168138,.T.); +#168221 = ORIENTED_EDGE('',*,*,#165131,.T.); +#168222 = ORIENTED_EDGE('',*,*,#165160,.T.); +#168223 = ORIENTED_EDGE('',*,*,#165295,.T.); +#168224 = ORIENTED_EDGE('',*,*,#165349,.T.); +#168225 = ORIENTED_EDGE('',*,*,#165424,.T.); +#168226 = ORIENTED_EDGE('',*,*,#165499,.T.); +#168227 = ADVANCED_FACE('',(#168228),#165721,.T.); +#168228 = FACE_BOUND('',#168229,.T.); +#168229 = EDGE_LOOP('',(#168230,#168252,#168253,#168254)); +#168230 = ORIENTED_EDGE('',*,*,#168231,.F.); +#168231 = EDGE_CURVE('',#168174,#168232,#168234,.T.); +#168232 = VERTEX_POINT('',#168233); +#168233 = CARTESIAN_POINT('',(1.695,0.985,-2.141803043818)); +#168234 = SURFACE_CURVE('',#168235,(#168239,#168245),.PCURVE_S1.); +#168235 = LINE('',#168236,#168237); +#168236 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); +#168237 = VECTOR('',#168238,1.); +#168238 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168239 = PCURVE('',#165721,#168240); +#168240 = DEFINITIONAL_REPRESENTATION('',(#168241),#168244); +#168241 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168242,#168243), + .UNSPECIFIED.,.F.,.F.,(2,2),(-1.48,-1.06),.PIECEWISE_BEZIER_KNOTS.); +#168242 = CARTESIAN_POINT('',(1.570796326795,-0.21)); +#168243 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#168244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#165807 = ORIENTED_EDGE('',*,*,#165808,.F.); -#165808 = EDGE_CURVE('',#165723,#165782,#165809,.T.); -#165809 = SURFACE_CURVE('',#165810,(#165814,#165821),.PCURVE_S1.); -#165810 = LINE('',#165811,#165812); -#165811 = CARTESIAN_POINT('',(2.115,0.985,0.E+000)); -#165812 = VECTOR('',#165813,1.); -#165813 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#165814 = PCURVE('',#162753,#165815); -#165815 = DEFINITIONAL_REPRESENTATION('',(#165816),#165820); -#165816 = LINE('',#165817,#165818); -#165817 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165818 = VECTOR('',#165819,1.); -#165819 = DIRECTION('',(1.,0.E+000)); -#165820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165821 = PCURVE('',#164485,#165822); -#165822 = DEFINITIONAL_REPRESENTATION('',(#165823),#165827); -#165823 = LINE('',#165824,#165825); -#165824 = CARTESIAN_POINT('',(0.E+000,1.48)); -#165825 = VECTOR('',#165826,1.); -#165826 = DIRECTION('',(-1.,0.E+000)); -#165827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165828 = ORIENTED_EDGE('',*,*,#165746,.T.); -#165829 = ORIENTED_EDGE('',*,*,#162739,.T.); -#165830 = ORIENTED_EDGE('',*,*,#162768,.T.); -#165831 = ORIENTED_EDGE('',*,*,#162903,.T.); -#165832 = ORIENTED_EDGE('',*,*,#162957,.T.); -#165833 = ORIENTED_EDGE('',*,*,#163032,.T.); -#165834 = ORIENTED_EDGE('',*,*,#163107,.T.); -#165835 = ADVANCED_FACE('',(#165836),#163329,.T.); -#165836 = FACE_BOUND('',#165837,.T.); -#165837 = EDGE_LOOP('',(#165838,#165860,#165861,#165862)); -#165838 = ORIENTED_EDGE('',*,*,#165839,.F.); -#165839 = EDGE_CURVE('',#165782,#165840,#165842,.T.); -#165840 = VERTEX_POINT('',#165841); -#165841 = CARTESIAN_POINT('',(1.695,0.985,-2.141803043818)); -#165842 = SURFACE_CURVE('',#165843,(#165847,#165853),.PCURVE_S1.); -#165843 = LINE('',#165844,#165845); -#165844 = CARTESIAN_POINT('',(0.635,0.985,-2.141803043818)); -#165845 = VECTOR('',#165846,1.); -#165846 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#165847 = PCURVE('',#163329,#165848); -#165848 = DEFINITIONAL_REPRESENTATION('',(#165849),#165852); -#165849 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165850,#165851), - .UNSPECIFIED.,.F.,.F.,(2,2),(-1.48,-1.06),.PIECEWISE_BEZIER_KNOTS.); -#165850 = CARTESIAN_POINT('',(1.570796326795,-0.21)); -#165851 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165853 = PCURVE('',#164485,#165854); -#165854 = DEFINITIONAL_REPRESENTATION('',(#165855),#165859); -#165855 = LINE('',#165856,#165857); -#165856 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); -#165857 = VECTOR('',#165858,1.); -#165858 = DIRECTION('',(0.E+000,-1.)); -#165859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165860 = ORIENTED_EDGE('',*,*,#165781,.T.); -#165861 = ORIENTED_EDGE('',*,*,#163306,.T.); -#165862 = ORIENTED_EDGE('',*,*,#165863,.F.); -#165863 = EDGE_CURVE('',#165840,#163309,#165864,.T.); -#165864 = SURFACE_CURVE('',#165865,(#165870,#165876),.PCURVE_S1.); -#165865 = CIRCLE('',#165866,0.32); -#165866 = AXIS2_PLACEMENT_3D('',#165867,#165868,#165869); -#165867 = CARTESIAN_POINT('',(1.695,0.665,-2.141803043818)); -#165868 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#165869 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165870 = PCURVE('',#163329,#165871); -#165871 = DEFINITIONAL_REPRESENTATION('',(#165872),#165875); -#165872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#165873,#165874), +#168245 = PCURVE('',#166877,#168246); +#168246 = DEFINITIONAL_REPRESENTATION('',(#168247),#168251); +#168247 = LINE('',#168248,#168249); +#168248 = CARTESIAN_POINT('',(-2.141803043818,0.E+000)); +#168249 = VECTOR('',#168250,1.); +#168250 = DIRECTION('',(0.E+000,-1.)); +#168251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168252 = ORIENTED_EDGE('',*,*,#168173,.T.); +#168253 = ORIENTED_EDGE('',*,*,#165698,.T.); +#168254 = ORIENTED_EDGE('',*,*,#168255,.F.); +#168255 = EDGE_CURVE('',#168232,#165701,#168256,.T.); +#168256 = SURFACE_CURVE('',#168257,(#168262,#168268),.PCURVE_S1.); +#168257 = CIRCLE('',#168258,0.32); +#168258 = AXIS2_PLACEMENT_3D('',#168259,#168260,#168261); +#168259 = CARTESIAN_POINT('',(1.695,0.665,-2.141803043818)); +#168260 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168261 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168262 = PCURVE('',#165721,#168263); +#168263 = DEFINITIONAL_REPRESENTATION('',(#168264),#168267); +#168264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#168265,#168266), .UNSPECIFIED.,.F.,.F.,(2,2),(1.570796326795,3.010457322736), .PIECEWISE_BEZIER_KNOTS.); -#165873 = CARTESIAN_POINT('',(1.570796326795,0.21)); -#165874 = CARTESIAN_POINT('',(3.010457322736,0.21)); -#165875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165876 = PCURVE('',#163404,#165877); -#165877 = DEFINITIONAL_REPRESENTATION('',(#165878),#165882); -#165878 = CIRCLE('',#165879,0.32); -#165879 = AXIS2_PLACEMENT_2D('',#165880,#165881); -#165880 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); -#165881 = DIRECTION('',(1.,0.E+000)); -#165882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165883 = ADVANCED_FACE('',(#165884),#163404,.T.); -#165884 = FACE_BOUND('',#165885,.T.); -#165885 = EDGE_LOOP('',(#165886,#165887,#165888,#165911,#165932,#165933, - #165934,#165935,#165936,#165937,#165938,#165939)); -#165886 = ORIENTED_EDGE('',*,*,#163907,.T.); -#165887 = ORIENTED_EDGE('',*,*,#164395,.T.); -#165888 = ORIENTED_EDGE('',*,*,#165889,.F.); -#165889 = EDGE_CURVE('',#165890,#164368,#165892,.T.); -#165890 = VERTEX_POINT('',#165891); -#165891 = CARTESIAN_POINT('',(1.695,0.985,-0.21)); -#165892 = SURFACE_CURVE('',#165893,(#165897,#165904),.PCURVE_S1.); -#165893 = LINE('',#165894,#165895); -#165894 = CARTESIAN_POINT('',(1.695,0.875,-0.21)); -#165895 = VECTOR('',#165896,1.); -#165896 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#165897 = PCURVE('',#163404,#165898); -#165898 = DEFINITIONAL_REPRESENTATION('',(#165899),#165903); -#165899 = LINE('',#165900,#165901); -#165900 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#165901 = VECTOR('',#165902,1.); -#165902 = DIRECTION('',(0.E+000,-1.)); -#165903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165904 = PCURVE('',#164383,#165905); -#165905 = DEFINITIONAL_REPRESENTATION('',(#165906),#165910); -#165906 = LINE('',#165907,#165908); -#165907 = CARTESIAN_POINT('',(-3.6,0.E+000)); -#165908 = VECTOR('',#165909,1.); -#165909 = DIRECTION('',(0.E+000,-1.)); -#165910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165911 = ORIENTED_EDGE('',*,*,#165912,.F.); -#165912 = EDGE_CURVE('',#165840,#165890,#165913,.T.); -#165913 = SURFACE_CURVE('',#165914,(#165918,#165925),.PCURVE_S1.); -#165914 = LINE('',#165915,#165916); -#165915 = CARTESIAN_POINT('',(1.695,0.985,0.E+000)); -#165916 = VECTOR('',#165917,1.); -#165917 = DIRECTION('',(0.E+000,0.E+000,1.)); -#165918 = PCURVE('',#163404,#165919); -#165919 = DEFINITIONAL_REPRESENTATION('',(#165920),#165924); -#165920 = LINE('',#165921,#165922); -#165921 = CARTESIAN_POINT('',(0.E+000,0.11)); -#165922 = VECTOR('',#165923,1.); -#165923 = DIRECTION('',(1.,0.E+000)); -#165924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165925 = PCURVE('',#164485,#165926); -#165926 = DEFINITIONAL_REPRESENTATION('',(#165927),#165931); -#165927 = LINE('',#165928,#165929); -#165928 = CARTESIAN_POINT('',(0.E+000,1.06)); -#165929 = VECTOR('',#165930,1.); -#165930 = DIRECTION('',(1.,0.E+000)); -#165931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165932 = ORIENTED_EDGE('',*,*,#165863,.T.); -#165933 = ORIENTED_EDGE('',*,*,#163390,.T.); -#165934 = ORIENTED_EDGE('',*,*,#163419,.T.); -#165935 = ORIENTED_EDGE('',*,*,#163554,.T.); -#165936 = ORIENTED_EDGE('',*,*,#163578,.T.); -#165937 = ORIENTED_EDGE('',*,*,#163683,.T.); -#165938 = ORIENTED_EDGE('',*,*,#163758,.T.); -#165939 = ORIENTED_EDGE('',*,*,#163833,.T.); -#165940 = ADVANCED_FACE('',(#165941),#164383,.T.); -#165941 = FACE_BOUND('',#165942,.T.); -#165942 = EDGE_LOOP('',(#165943,#165944,#165945,#165946)); -#165943 = ORIENTED_EDGE('',*,*,#165889,.T.); -#165944 = ORIENTED_EDGE('',*,*,#164367,.F.); -#165945 = ORIENTED_EDGE('',*,*,#164497,.T.); -#165946 = ORIENTED_EDGE('',*,*,#165947,.F.); -#165947 = EDGE_CURVE('',#165890,#164470,#165948,.T.); -#165948 = SURFACE_CURVE('',#165949,(#165953,#165960),.PCURVE_S1.); -#165949 = LINE('',#165950,#165951); -#165950 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); -#165951 = VECTOR('',#165952,1.); -#165952 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#165953 = PCURVE('',#164383,#165954); -#165954 = DEFINITIONAL_REPRESENTATION('',(#165955),#165959); -#165955 = LINE('',#165956,#165957); -#165956 = CARTESIAN_POINT('',(-2.54,0.11)); -#165957 = VECTOR('',#165958,1.); -#165958 = DIRECTION('',(1.,0.E+000)); -#165959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165960 = PCURVE('',#164485,#165961); -#165961 = DEFINITIONAL_REPRESENTATION('',(#165962),#165966); -#165962 = LINE('',#165963,#165964); -#165963 = CARTESIAN_POINT('',(-0.21,0.E+000)); -#165964 = VECTOR('',#165965,1.); -#165965 = DIRECTION('',(0.E+000,-1.)); -#165966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#165967 = ADVANCED_FACE('',(#165968),#164485,.T.); -#165968 = FACE_BOUND('',#165969,.T.); -#165969 = EDGE_LOOP('',(#165970,#165971,#165972,#165973,#165974,#165975, - #165976,#165977,#165978,#165979,#165980,#165981,#165982,#165983, - #165984,#165985,#165986,#165987,#165988,#165989,#165990,#165991, - #165992,#165993,#165994,#165995,#165996,#165997)); -#165970 = ORIENTED_EDGE('',*,*,#165912,.T.); -#165971 = ORIENTED_EDGE('',*,*,#165947,.T.); -#165972 = ORIENTED_EDGE('',*,*,#164469,.T.); -#165973 = ORIENTED_EDGE('',*,*,#164530,.T.); -#165974 = ORIENTED_EDGE('',*,*,#164603,.T.); -#165975 = ORIENTED_EDGE('',*,*,#164658,.T.); -#165976 = ORIENTED_EDGE('',*,*,#164711,.T.); -#165977 = ORIENTED_EDGE('',*,*,#164745,.T.); -#165978 = ORIENTED_EDGE('',*,*,#164818,.T.); -#165979 = ORIENTED_EDGE('',*,*,#164875,.T.); -#165980 = ORIENTED_EDGE('',*,*,#164926,.T.); -#165981 = ORIENTED_EDGE('',*,*,#164960,.T.); -#165982 = ORIENTED_EDGE('',*,*,#165036,.T.); -#165983 = ORIENTED_EDGE('',*,*,#165077,.T.); -#165984 = ORIENTED_EDGE('',*,*,#165150,.T.); -#165985 = ORIENTED_EDGE('',*,*,#165205,.T.); -#165986 = ORIENTED_EDGE('',*,*,#165258,.T.); -#165987 = ORIENTED_EDGE('',*,*,#165292,.T.); -#165988 = ORIENTED_EDGE('',*,*,#165365,.T.); -#165989 = ORIENTED_EDGE('',*,*,#165422,.T.); -#165990 = ORIENTED_EDGE('',*,*,#165473,.T.); -#165991 = ORIENTED_EDGE('',*,*,#165507,.T.); -#165992 = ORIENTED_EDGE('',*,*,#165580,.T.); -#165993 = ORIENTED_EDGE('',*,*,#165635,.T.); -#165994 = ORIENTED_EDGE('',*,*,#165688,.T.); -#165995 = ORIENTED_EDGE('',*,*,#165722,.T.); -#165996 = ORIENTED_EDGE('',*,*,#165808,.T.); -#165997 = ORIENTED_EDGE('',*,*,#165839,.T.); -#165998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166002)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#165999,#166000,#166001)) +#168265 = CARTESIAN_POINT('',(1.570796326795,0.21)); +#168266 = CARTESIAN_POINT('',(3.010457322736,0.21)); +#168267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168268 = PCURVE('',#165796,#168269); +#168269 = DEFINITIONAL_REPRESENTATION('',(#168270),#168274); +#168270 = CIRCLE('',#168271,0.32); +#168271 = AXIS2_PLACEMENT_2D('',#168272,#168273); +#168272 = CARTESIAN_POINT('',(-2.141803043818,-0.21)); +#168273 = DIRECTION('',(1.,0.E+000)); +#168274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168275 = ADVANCED_FACE('',(#168276),#165796,.T.); +#168276 = FACE_BOUND('',#168277,.T.); +#168277 = EDGE_LOOP('',(#168278,#168279,#168280,#168303,#168324,#168325, + #168326,#168327,#168328,#168329,#168330,#168331)); +#168278 = ORIENTED_EDGE('',*,*,#166299,.T.); +#168279 = ORIENTED_EDGE('',*,*,#166787,.T.); +#168280 = ORIENTED_EDGE('',*,*,#168281,.F.); +#168281 = EDGE_CURVE('',#168282,#166760,#168284,.T.); +#168282 = VERTEX_POINT('',#168283); +#168283 = CARTESIAN_POINT('',(1.695,0.985,-0.21)); +#168284 = SURFACE_CURVE('',#168285,(#168289,#168296),.PCURVE_S1.); +#168285 = LINE('',#168286,#168287); +#168286 = CARTESIAN_POINT('',(1.695,0.875,-0.21)); +#168287 = VECTOR('',#168288,1.); +#168288 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168289 = PCURVE('',#165796,#168290); +#168290 = DEFINITIONAL_REPRESENTATION('',(#168291),#168295); +#168291 = LINE('',#168292,#168293); +#168292 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#168293 = VECTOR('',#168294,1.); +#168294 = DIRECTION('',(0.E+000,-1.)); +#168295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168296 = PCURVE('',#166775,#168297); +#168297 = DEFINITIONAL_REPRESENTATION('',(#168298),#168302); +#168298 = LINE('',#168299,#168300); +#168299 = CARTESIAN_POINT('',(-3.6,0.E+000)); +#168300 = VECTOR('',#168301,1.); +#168301 = DIRECTION('',(0.E+000,-1.)); +#168302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168303 = ORIENTED_EDGE('',*,*,#168304,.F.); +#168304 = EDGE_CURVE('',#168232,#168282,#168305,.T.); +#168305 = SURFACE_CURVE('',#168306,(#168310,#168317),.PCURVE_S1.); +#168306 = LINE('',#168307,#168308); +#168307 = CARTESIAN_POINT('',(1.695,0.985,0.E+000)); +#168308 = VECTOR('',#168309,1.); +#168309 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168310 = PCURVE('',#165796,#168311); +#168311 = DEFINITIONAL_REPRESENTATION('',(#168312),#168316); +#168312 = LINE('',#168313,#168314); +#168313 = CARTESIAN_POINT('',(0.E+000,0.11)); +#168314 = VECTOR('',#168315,1.); +#168315 = DIRECTION('',(1.,0.E+000)); +#168316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168317 = PCURVE('',#166877,#168318); +#168318 = DEFINITIONAL_REPRESENTATION('',(#168319),#168323); +#168319 = LINE('',#168320,#168321); +#168320 = CARTESIAN_POINT('',(0.E+000,1.06)); +#168321 = VECTOR('',#168322,1.); +#168322 = DIRECTION('',(1.,0.E+000)); +#168323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168324 = ORIENTED_EDGE('',*,*,#168255,.T.); +#168325 = ORIENTED_EDGE('',*,*,#165782,.T.); +#168326 = ORIENTED_EDGE('',*,*,#165811,.T.); +#168327 = ORIENTED_EDGE('',*,*,#165946,.T.); +#168328 = ORIENTED_EDGE('',*,*,#165970,.T.); +#168329 = ORIENTED_EDGE('',*,*,#166075,.T.); +#168330 = ORIENTED_EDGE('',*,*,#166150,.T.); +#168331 = ORIENTED_EDGE('',*,*,#166225,.T.); +#168332 = ADVANCED_FACE('',(#168333),#166775,.T.); +#168333 = FACE_BOUND('',#168334,.T.); +#168334 = EDGE_LOOP('',(#168335,#168336,#168337,#168338)); +#168335 = ORIENTED_EDGE('',*,*,#168281,.T.); +#168336 = ORIENTED_EDGE('',*,*,#166759,.F.); +#168337 = ORIENTED_EDGE('',*,*,#166889,.T.); +#168338 = ORIENTED_EDGE('',*,*,#168339,.F.); +#168339 = EDGE_CURVE('',#168282,#166862,#168340,.T.); +#168340 = SURFACE_CURVE('',#168341,(#168345,#168352),.PCURVE_S1.); +#168341 = LINE('',#168342,#168343); +#168342 = CARTESIAN_POINT('',(0.635,0.985,-0.21)); +#168343 = VECTOR('',#168344,1.); +#168344 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168345 = PCURVE('',#166775,#168346); +#168346 = DEFINITIONAL_REPRESENTATION('',(#168347),#168351); +#168347 = LINE('',#168348,#168349); +#168348 = CARTESIAN_POINT('',(-2.54,0.11)); +#168349 = VECTOR('',#168350,1.); +#168350 = DIRECTION('',(1.,0.E+000)); +#168351 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168352 = PCURVE('',#166877,#168353); +#168353 = DEFINITIONAL_REPRESENTATION('',(#168354),#168358); +#168354 = LINE('',#168355,#168356); +#168355 = CARTESIAN_POINT('',(-0.21,0.E+000)); +#168356 = VECTOR('',#168357,1.); +#168357 = DIRECTION('',(0.E+000,-1.)); +#168358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168359 = ADVANCED_FACE('',(#168360),#166877,.T.); +#168360 = FACE_BOUND('',#168361,.T.); +#168361 = EDGE_LOOP('',(#168362,#168363,#168364,#168365,#168366,#168367, + #168368,#168369,#168370,#168371,#168372,#168373,#168374,#168375, + #168376,#168377,#168378,#168379,#168380,#168381,#168382,#168383, + #168384,#168385,#168386,#168387,#168388,#168389)); +#168362 = ORIENTED_EDGE('',*,*,#168304,.T.); +#168363 = ORIENTED_EDGE('',*,*,#168339,.T.); +#168364 = ORIENTED_EDGE('',*,*,#166861,.T.); +#168365 = ORIENTED_EDGE('',*,*,#166922,.T.); +#168366 = ORIENTED_EDGE('',*,*,#166995,.T.); +#168367 = ORIENTED_EDGE('',*,*,#167050,.T.); +#168368 = ORIENTED_EDGE('',*,*,#167103,.T.); +#168369 = ORIENTED_EDGE('',*,*,#167137,.T.); +#168370 = ORIENTED_EDGE('',*,*,#167210,.T.); +#168371 = ORIENTED_EDGE('',*,*,#167267,.T.); +#168372 = ORIENTED_EDGE('',*,*,#167318,.T.); +#168373 = ORIENTED_EDGE('',*,*,#167352,.T.); +#168374 = ORIENTED_EDGE('',*,*,#167428,.T.); +#168375 = ORIENTED_EDGE('',*,*,#167469,.T.); +#168376 = ORIENTED_EDGE('',*,*,#167542,.T.); +#168377 = ORIENTED_EDGE('',*,*,#167597,.T.); +#168378 = ORIENTED_EDGE('',*,*,#167650,.T.); +#168379 = ORIENTED_EDGE('',*,*,#167684,.T.); +#168380 = ORIENTED_EDGE('',*,*,#167757,.T.); +#168381 = ORIENTED_EDGE('',*,*,#167814,.T.); +#168382 = ORIENTED_EDGE('',*,*,#167865,.T.); +#168383 = ORIENTED_EDGE('',*,*,#167899,.T.); +#168384 = ORIENTED_EDGE('',*,*,#167972,.T.); +#168385 = ORIENTED_EDGE('',*,*,#168027,.T.); +#168386 = ORIENTED_EDGE('',*,*,#168080,.T.); +#168387 = ORIENTED_EDGE('',*,*,#168114,.T.); +#168388 = ORIENTED_EDGE('',*,*,#168200,.T.); +#168389 = ORIENTED_EDGE('',*,*,#168231,.T.); +#168390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168394)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168391,#168392,#168393)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#165999 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166000 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166001 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166002 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#165999, +#168391 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168392 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168393 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168394 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168391, 'distance_accuracy_value','confusion accuracy'); -#166003 = SHAPE_DEFINITION_REPRESENTATION(#166004,#158707); -#166004 = PRODUCT_DEFINITION_SHAPE('','',#166005); -#166005 = PRODUCT_DEFINITION('design','',#166006,#166009); -#166006 = PRODUCT_DEFINITION_FORMATION('','',#166007); -#166007 = PRODUCT('User_Library-SOIC-8_SOIC-8_Pins_1', - 'User_Library-SOIC-8_SOIC-8_Pins_1','',(#166008)); -#166008 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166009 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166010 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166011,#166013); -#166011 = ( REPRESENTATION_RELATIONSHIP('','',#158707,#156692) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166012) +#168395 = SHAPE_DEFINITION_REPRESENTATION(#168396,#161099); +#168396 = PRODUCT_DEFINITION_SHAPE('','',#168397); +#168397 = PRODUCT_DEFINITION('design','',#168398,#168401); +#168398 = PRODUCT_DEFINITION_FORMATION('','',#168399); +#168399 = PRODUCT('User_Library-SOIC-8_SOIC-8_Pins_1', + 'User_Library-SOIC-8_SOIC-8_Pins_1','',(#168400)); +#168400 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168401 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168402 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168403,#168405); +#168403 = ( REPRESENTATION_RELATIONSHIP('','',#161099,#159084) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168404) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166012 = ITEM_DEFINED_TRANSFORMATION('','',#11,#156697); -#166013 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166014); -#166014 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('272','','',#156687,#166005,$); -#166015 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166007)); -#166016 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166017,#166019); -#166017 = ( REPRESENTATION_RELATIONSHIP('','',#156692,#156675) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166018) +#168404 = ITEM_DEFINED_TRANSFORMATION('','',#11,#159089); +#168405 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168406); +#168406 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('373','','',#159079,#168397,$); +#168407 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168399)); +#168408 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168409,#168411); +#168409 = ( REPRESENTATION_RELATIONSHIP('','',#159084,#159067) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168410) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166018 = ITEM_DEFINED_TRANSFORMATION('','',#11,#156676); -#166019 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166020); -#166020 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('273','=>[0:1:1:82]','',#156670 - ,#156687,$); -#166021 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#156689)); -#166022 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166023,#166025); -#166023 = ( REPRESENTATION_RELATIONSHIP('','',#156675,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166024) +#168410 = ITEM_DEFINED_TRANSFORMATION('','',#11,#159068); +#168411 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168412); +#168412 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('374','=>[0:1:1:82]','',#159062 + ,#159079,$); +#168413 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#159081)); +#168414 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168415,#168417); +#168415 = ( REPRESENTATION_RELATIONSHIP('','',#159067,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168416) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166024 = ITEM_DEFINED_TRANSFORMATION('','',#11,#231); -#166025 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166026); -#166026 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('274','=>[0:1:1:81]','',#5, - #156670,$); -#166027 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#156672)); -#166028 = SHAPE_DEFINITION_REPRESENTATION(#166029,#166035); -#166029 = PRODUCT_DEFINITION_SHAPE('','',#166030); -#166030 = PRODUCT_DEFINITION('design','',#166031,#166034); -#166031 = PRODUCT_DEFINITION_FORMATION('','',#166032); -#166032 = PRODUCT('CONN11','CONN11','',(#166033)); -#166033 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166034 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166035 = SHAPE_REPRESENTATION('',(#11,#166036),#166040); -#166036 = AXIS2_PLACEMENT_3D('',#166037,#166038,#166039); -#166037 = CARTESIAN_POINT('',(4.5300011,12.065,-1.94818)); -#166038 = DIRECTION('',(-1.,-2.22044604925E-016,-1.110223024625E-016)); -#166039 = DIRECTION('',(-2.22044604925E-016,1.,-1.224606353822E-016)); -#166040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166044)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166041,#166042,#166043)) +#168416 = ITEM_DEFINED_TRANSFORMATION('','',#11,#231); +#168417 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168418); +#168418 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('375','=>[0:1:1:81]','',#5, + #159062,$); +#168419 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#159064)); +#168420 = SHAPE_DEFINITION_REPRESENTATION(#168421,#168427); +#168421 = PRODUCT_DEFINITION_SHAPE('','',#168422); +#168422 = PRODUCT_DEFINITION('design','',#168423,#168426); +#168423 = PRODUCT_DEFINITION_FORMATION('','',#168424); +#168424 = PRODUCT('CONN11','CONN11','',(#168425)); +#168425 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168426 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168427 = SHAPE_REPRESENTATION('',(#11,#168428),#168432); +#168428 = AXIS2_PLACEMENT_3D('',#168429,#168430,#168431); +#168429 = CARTESIAN_POINT('',(4.5300011,12.065,-1.3589)); +#168430 = DIRECTION('',(-1.,-2.22044604925E-016,-1.110223024625E-016)); +#168431 = DIRECTION('',(-2.22044604925E-016,1.,-1.224606353822E-016)); +#168432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168436)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168433,#168434,#168435)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166041 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166042 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166043 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166044 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166041, +#168433 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168434 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168435 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168436 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168433, 'distance_accuracy_value','confusion accuracy'); -#166045 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166046,#166048); -#166046 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#166035) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166047) +#168437 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168438,#168440); +#168438 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#168427) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168439) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166047 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166036); -#166048 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166049); -#166049 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('275','=>[0:1:1:31]','',#166030 - ,#28462,$); -#166050 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166051,#166053); -#166051 = ( REPRESENTATION_RELATIONSHIP('','',#166035,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166052) +#168439 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168428); +#168440 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168441); +#168441 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('376','=>[0:1:1:31]','',#168422 + ,#30854,$); +#168442 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168443,#168445); +#168443 = ( REPRESENTATION_RELATIONSHIP('','',#168427,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168444) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166052 = ITEM_DEFINED_TRANSFORMATION('','',#11,#235); -#166053 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166054); -#166054 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('276','=>[0:1:1:85]','',#5, - #166030,$); -#166055 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166032)); -#166056 = SHAPE_DEFINITION_REPRESENTATION(#166057,#166063); -#166057 = PRODUCT_DEFINITION_SHAPE('','',#166058); -#166058 = PRODUCT_DEFINITION('design','',#166059,#166062); -#166059 = PRODUCT_DEFINITION_FORMATION('','',#166060); -#166060 = PRODUCT('C10','C10','',(#166061)); -#166061 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166062 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166063 = SHAPE_REPRESENTATION('',(#11,#166064),#166068); -#166064 = AXIS2_PLACEMENT_3D('',#166065,#166066,#166067); -#166065 = CARTESIAN_POINT('',(14.8590635,28.57491872,1.27E-002)); -#166066 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166067 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); -#166068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166072)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166069,#166070,#166071)) +#168444 = ITEM_DEFINED_TRANSFORMATION('','',#11,#235); +#168445 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168446); +#168446 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('377','=>[0:1:1:85]','',#5, + #168422,$); +#168447 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168424)); +#168448 = SHAPE_DEFINITION_REPRESENTATION(#168449,#168455); +#168449 = PRODUCT_DEFINITION_SHAPE('','',#168450); +#168450 = PRODUCT_DEFINITION('design','',#168451,#168454); +#168451 = PRODUCT_DEFINITION_FORMATION('','',#168452); +#168452 = PRODUCT('C10','C10','',(#168453)); +#168453 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168454 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168455 = SHAPE_REPRESENTATION('',(#11,#168456),#168460); +#168456 = AXIS2_PLACEMENT_3D('',#168457,#168458,#168459); +#168457 = CARTESIAN_POINT('',(14.8590635,28.57491872,1.27E-002)); +#168458 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168459 = DIRECTION('',(-2.22044604925E-016,-1.,0.E+000)); +#168460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168464)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168461,#168462,#168463)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166069 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166070 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166071 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166072 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#166069, +#168461 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168462 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168463 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168464 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#168461, 'distance_accuracy_value','confusion accuracy'); -#166073 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166074,#166076); -#166074 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#166063) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166075) +#168465 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168466,#168468); +#168466 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#168455) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168467) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166075 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166064); -#166076 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166077); -#166077 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('277','=>[0:1:1:18]','',#166058 - ,#11876,$); -#166078 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166079,#166081); -#166079 = ( REPRESENTATION_RELATIONSHIP('','',#166063,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166080) +#168467 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168456); +#168468 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168469); +#168469 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('378','=>[0:1:1:18]','',#168450 + ,#14268,$); +#168470 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168471,#168473); +#168471 = ( REPRESENTATION_RELATIONSHIP('','',#168455,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168472) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166080 = ITEM_DEFINED_TRANSFORMATION('','',#11,#239); -#166081 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166082); -#166082 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('278','=>[0:1:1:86]','',#5, - #166058,$); -#166083 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166060)); -#166084 = SHAPE_DEFINITION_REPRESENTATION(#166085,#166091); -#166085 = PRODUCT_DEFINITION_SHAPE('','',#166086); -#166086 = PRODUCT_DEFINITION('design','',#166087,#166090); -#166087 = PRODUCT_DEFINITION_FORMATION('','',#166088); -#166088 = PRODUCT('C14','C14','',(#166089)); -#166089 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166090 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166091 = SHAPE_REPRESENTATION('',(#11,#166092),#166096); -#166092 = AXIS2_PLACEMENT_3D('',#166093,#166094,#166095); -#166093 = CARTESIAN_POINT('',(24.7649365,19.68508128,1.27E-002)); -#166094 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166095 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#166096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166100)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166097,#166098,#166099)) +#168472 = ITEM_DEFINED_TRANSFORMATION('','',#11,#239); +#168473 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168474); +#168474 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('379','=>[0:1:1:86]','',#5, + #168450,$); +#168475 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168452)); +#168476 = SHAPE_DEFINITION_REPRESENTATION(#168477,#168483); +#168477 = PRODUCT_DEFINITION_SHAPE('','',#168478); +#168478 = PRODUCT_DEFINITION('design','',#168479,#168482); +#168479 = PRODUCT_DEFINITION_FORMATION('','',#168480); +#168480 = PRODUCT('C14','C14','',(#168481)); +#168481 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168482 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168483 = SHAPE_REPRESENTATION('',(#11,#168484),#168488); +#168484 = AXIS2_PLACEMENT_3D('',#168485,#168486,#168487); +#168485 = CARTESIAN_POINT('',(24.7649365,19.68508128,1.27E-002)); +#168486 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168487 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#168488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168492)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168489,#168490,#168491)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166097 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166098 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166099 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166100 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#166097, +#168489 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168490 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168491 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168492 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#168489, 'distance_accuracy_value','confusion accuracy'); -#166101 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166102,#166104); -#166102 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#166091) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166103) +#168493 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168494,#168496); +#168494 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#168483) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168495) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166103 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166092); -#166104 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166105); -#166105 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('279','=>[0:1:1:18]','',#166086 - ,#11876,$); -#166106 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166107,#166109); -#166107 = ( REPRESENTATION_RELATIONSHIP('','',#166091,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166108) +#168495 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168484); +#168496 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168497); +#168497 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('380','=>[0:1:1:18]','',#168478 + ,#14268,$); +#168498 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168499,#168501); +#168499 = ( REPRESENTATION_RELATIONSHIP('','',#168483,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168500) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166108 = ITEM_DEFINED_TRANSFORMATION('','',#11,#243); -#166109 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166110); -#166110 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('280','=>[0:1:1:87]','',#5, - #166086,$); -#166111 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166088)); -#166112 = SHAPE_DEFINITION_REPRESENTATION(#166113,#166119); -#166113 = PRODUCT_DEFINITION_SHAPE('','',#166114); -#166114 = PRODUCT_DEFINITION('design','',#166115,#166118); -#166115 = PRODUCT_DEFINITION_FORMATION('','',#166116); -#166116 = PRODUCT('C11','C11','',(#166117)); -#166117 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166118 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166119 = SHAPE_REPRESENTATION('',(#11,#166120),#166124); -#166120 = AXIS2_PLACEMENT_3D('',#166121,#166122,#166123); -#166121 = CARTESIAN_POINT('',(19.93908128,30.8610635,1.27E-002)); -#166122 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166123 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#166124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166128)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166125,#166126,#166127)) +#168500 = ITEM_DEFINED_TRANSFORMATION('','',#11,#243); +#168501 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168502); +#168502 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('381','=>[0:1:1:87]','',#5, + #168478,$); +#168503 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168480)); +#168504 = SHAPE_DEFINITION_REPRESENTATION(#168505,#168511); +#168505 = PRODUCT_DEFINITION_SHAPE('','',#168506); +#168506 = PRODUCT_DEFINITION('design','',#168507,#168510); +#168507 = PRODUCT_DEFINITION_FORMATION('','',#168508); +#168508 = PRODUCT('C11','C11','',(#168509)); +#168509 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168510 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168511 = SHAPE_REPRESENTATION('',(#11,#168512),#168516); +#168512 = AXIS2_PLACEMENT_3D('',#168513,#168514,#168515); +#168513 = CARTESIAN_POINT('',(19.93908128,30.8610635,1.27E-002)); +#168514 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168515 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#168516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168520)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168517,#168518,#168519)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166125 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166126 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166127 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166128 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#166125, +#168517 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168518 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168519 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168520 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#168517, 'distance_accuracy_value','confusion accuracy'); -#166129 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166130,#166132); -#166130 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#166119) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166131) +#168521 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168522,#168524); +#168522 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#168511) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168523) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166131 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166120); -#166132 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166133); -#166133 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('281','=>[0:1:1:18]','',#166114 - ,#11876,$); -#166134 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166135,#166137); -#166135 = ( REPRESENTATION_RELATIONSHIP('','',#166119,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166136) +#168523 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168512); +#168524 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168525); +#168525 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('382','=>[0:1:1:18]','',#168506 + ,#14268,$); +#168526 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168527,#168529); +#168527 = ( REPRESENTATION_RELATIONSHIP('','',#168511,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168528) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166136 = ITEM_DEFINED_TRANSFORMATION('','',#11,#247); -#166137 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166138); -#166138 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('282','=>[0:1:1:88]','',#5, - #166114,$); -#166139 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166116)); -#166140 = SHAPE_DEFINITION_REPRESENTATION(#166141,#166147); -#166141 = PRODUCT_DEFINITION_SHAPE('','',#166142); -#166142 = PRODUCT_DEFINITION('design','',#166143,#166146); -#166143 = PRODUCT_DEFINITION_FORMATION('','',#166144); -#166144 = PRODUCT('R5','R5','',(#166145)); -#166145 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166146 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166147 = SHAPE_REPRESENTATION('',(#11,#166148),#166152); -#166148 = AXIS2_PLACEMENT_3D('',#166149,#166150,#166151); -#166149 = CARTESIAN_POINT('',(24.13,8.6400005,-1.27E-002)); -#166150 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166151 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#166152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166156)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166153,#166154,#166155)) +#168528 = ITEM_DEFINED_TRANSFORMATION('','',#11,#247); +#168529 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168530); +#168530 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('383','=>[0:1:1:88]','',#5, + #168506,$); +#168531 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168508)); +#168532 = SHAPE_DEFINITION_REPRESENTATION(#168533,#168539); +#168533 = PRODUCT_DEFINITION_SHAPE('','',#168534); +#168534 = PRODUCT_DEFINITION('design','',#168535,#168538); +#168535 = PRODUCT_DEFINITION_FORMATION('','',#168536); +#168536 = PRODUCT('R5','R5','',(#168537)); +#168537 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168538 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168539 = SHAPE_REPRESENTATION('',(#11,#168540),#168544); +#168540 = AXIS2_PLACEMENT_3D('',#168541,#168542,#168543); +#168541 = CARTESIAN_POINT('',(24.13,8.6400005,-1.27E-002)); +#168542 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168543 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#168544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168548)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168545,#168546,#168547)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166153 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166154 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166155 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166156 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166153, +#168545 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168546 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168547 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168548 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168545, 'distance_accuracy_value','confusion accuracy'); -#166157 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166158,#166160); -#166158 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#166147) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166159) +#168549 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168550,#168552); +#168550 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#168539) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168551) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166159 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166148); -#166160 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166161); -#166161 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('283','=>[0:1:1:7]','',#166142, - #7462,$); -#166162 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166163,#166165); -#166163 = ( REPRESENTATION_RELATIONSHIP('','',#166147,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166164) +#168551 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168540); +#168552 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168553); +#168553 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('384','=>[0:1:1:7]','',#168534, + #9854,$); +#168554 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168555,#168557); +#168555 = ( REPRESENTATION_RELATIONSHIP('','',#168539,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168556) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166164 = ITEM_DEFINED_TRANSFORMATION('','',#11,#251); -#166165 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166166); -#166166 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('284','=>[0:1:1:89]','',#5, - #166142,$); -#166167 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166144)); -#166168 = SHAPE_DEFINITION_REPRESENTATION(#166169,#166175); -#166169 = PRODUCT_DEFINITION_SHAPE('','',#166170); -#166170 = PRODUCT_DEFINITION('design','',#166171,#166174); -#166171 = PRODUCT_DEFINITION_FORMATION('','',#166172); -#166172 = PRODUCT('R6','R6','',(#166173)); -#166173 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166174 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166175 = SHAPE_REPRESENTATION('',(#11,#166176),#166180); -#166176 = AXIS2_PLACEMENT_3D('',#166177,#166178,#166179); -#166177 = CARTESIAN_POINT('',(16.0060005,6.35,-1.27E-002)); -#166178 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166179 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#166180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166184)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166181,#166182,#166183)) +#168556 = ITEM_DEFINED_TRANSFORMATION('','',#11,#251); +#168557 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168558); +#168558 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('385','=>[0:1:1:89]','',#5, + #168534,$); +#168559 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168536)); +#168560 = SHAPE_DEFINITION_REPRESENTATION(#168561,#168567); +#168561 = PRODUCT_DEFINITION_SHAPE('','',#168562); +#168562 = PRODUCT_DEFINITION('design','',#168563,#168566); +#168563 = PRODUCT_DEFINITION_FORMATION('','',#168564); +#168564 = PRODUCT('R6','R6','',(#168565)); +#168565 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168566 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168567 = SHAPE_REPRESENTATION('',(#11,#168568),#168572); +#168568 = AXIS2_PLACEMENT_3D('',#168569,#168570,#168571); +#168569 = CARTESIAN_POINT('',(16.0060005,6.35,-1.27E-002)); +#168570 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168571 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#168572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168576)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168573,#168574,#168575)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166181 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166182 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166183 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166184 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166181, +#168573 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168574 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168575 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168576 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168573, 'distance_accuracy_value','confusion accuracy'); -#166185 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166186,#166188); -#166186 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#166175) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166187) +#168577 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168578,#168580); +#168578 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#168567) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168579) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166187 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166176); -#166188 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166189); -#166189 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('285','=>[0:1:1:7]','',#166170, - #7462,$); -#166190 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166191,#166193); -#166191 = ( REPRESENTATION_RELATIONSHIP('','',#166175,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166192) +#168579 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168568); +#168580 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168581); +#168581 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('386','=>[0:1:1:7]','',#168562, + #9854,$); +#168582 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168583,#168585); +#168583 = ( REPRESENTATION_RELATIONSHIP('','',#168567,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168584) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166192 = ITEM_DEFINED_TRANSFORMATION('','',#11,#255); -#166193 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166194); -#166194 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('286','=>[0:1:1:90]','',#5, - #166170,$); -#166195 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166172)); -#166196 = SHAPE_DEFINITION_REPRESENTATION(#166197,#166203); -#166197 = PRODUCT_DEFINITION_SHAPE('','',#166198); -#166198 = PRODUCT_DEFINITION('design','',#166199,#166202); -#166199 = PRODUCT_DEFINITION_FORMATION('','',#166200); -#166200 = PRODUCT('C27','C27','',(#166201)); -#166201 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166202 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166203 = SHAPE_REPRESENTATION('',(#11,#166204),#166208); -#166204 = AXIS2_PLACEMENT_3D('',#166205,#166206,#166207); -#166205 = CARTESIAN_POINT('',(24.13008128,3.6830635,1.27E-002)); -#166206 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166207 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#166208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166212)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166209,#166210,#166211)) +#168584 = ITEM_DEFINED_TRANSFORMATION('','',#11,#255); +#168585 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168586); +#168586 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('387','=>[0:1:1:90]','',#5, + #168562,$); +#168587 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168564)); +#168588 = SHAPE_DEFINITION_REPRESENTATION(#168589,#168595); +#168589 = PRODUCT_DEFINITION_SHAPE('','',#168590); +#168590 = PRODUCT_DEFINITION('design','',#168591,#168594); +#168591 = PRODUCT_DEFINITION_FORMATION('','',#168592); +#168592 = PRODUCT('C27','C27','',(#168593)); +#168593 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168594 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168595 = SHAPE_REPRESENTATION('',(#11,#168596),#168600); +#168596 = AXIS2_PLACEMENT_3D('',#168597,#168598,#168599); +#168597 = CARTESIAN_POINT('',(24.13008128,3.6830635,1.27E-002)); +#168598 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168599 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#168600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168604)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168601,#168602,#168603)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166209 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166210 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166211 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166212 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#166209, +#168601 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168602 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168603 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168604 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#168601, 'distance_accuracy_value','confusion accuracy'); -#166213 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166214,#166216); -#166214 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#166203) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166215) +#168605 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168606,#168608); +#168606 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#168595) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168607) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166215 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166204); -#166216 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166217); -#166217 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('287','=>[0:1:1:18]','',#166198 - ,#11876,$); -#166218 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166219,#166221); -#166219 = ( REPRESENTATION_RELATIONSHIP('','',#166203,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166220) +#168607 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168596); +#168608 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168609); +#168609 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('388','=>[0:1:1:18]','',#168590 + ,#14268,$); +#168610 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168611,#168613); +#168611 = ( REPRESENTATION_RELATIONSHIP('','',#168595,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168612) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166220 = ITEM_DEFINED_TRANSFORMATION('','',#11,#259); -#166221 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166222); -#166222 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('288','=>[0:1:1:91]','',#5, - #166198,$); -#166223 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166200)); -#166224 = SHAPE_DEFINITION_REPRESENTATION(#166225,#166231); -#166225 = PRODUCT_DEFINITION_SHAPE('','',#166226); -#166226 = PRODUCT_DEFINITION('design','',#166227,#166230); -#166227 = PRODUCT_DEFINITION_FORMATION('','',#166228); -#166228 = PRODUCT('U7','U7','',(#166229)); -#166229 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166230 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166231 = SHAPE_REPRESENTATION('',(#11,#166232,#166236,#166240,#166244), - #166248); -#166232 = AXIS2_PLACEMENT_3D('',#166233,#166234,#166235); -#166233 = CARTESIAN_POINT('',(24.13,6.223,1.27E-002)); -#166234 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166235 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166236 = AXIS2_PLACEMENT_3D('',#166237,#166238,#166239); -#166237 = CARTESIAN_POINT('',(24.13,6.223,2.269998E-002)); -#166238 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166239 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166240 = AXIS2_PLACEMENT_3D('',#166241,#166242,#166243); -#166241 = CARTESIAN_POINT('',(22.5044,6.858,3.269996E-002)); -#166242 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166243 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#166244 = AXIS2_PLACEMENT_3D('',#166245,#166246,#166247); -#166245 = CARTESIAN_POINT('',(25.70471872,5.53728128,3.269996E-002)); -#166246 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166247 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#166248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166252)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166249,#166250,#166251)) +#168612 = ITEM_DEFINED_TRANSFORMATION('','',#11,#259); +#168613 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #168614); +#168614 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('389','=>[0:1:1:91]','',#5, + #168590,$); +#168615 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168592)); +#168616 = SHAPE_DEFINITION_REPRESENTATION(#168617,#168623); +#168617 = PRODUCT_DEFINITION_SHAPE('','',#168618); +#168618 = PRODUCT_DEFINITION('design','',#168619,#168622); +#168619 = PRODUCT_DEFINITION_FORMATION('','',#168620); +#168620 = PRODUCT('U7','U7','',(#168621)); +#168621 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168622 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168623 = SHAPE_REPRESENTATION('',(#11,#168624,#168628,#168632,#168636), + #168640); +#168624 = AXIS2_PLACEMENT_3D('',#168625,#168626,#168627); +#168625 = CARTESIAN_POINT('',(24.13,6.223,1.27E-002)); +#168626 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168627 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168628 = AXIS2_PLACEMENT_3D('',#168629,#168630,#168631); +#168629 = CARTESIAN_POINT('',(24.13,6.223,2.269998E-002)); +#168630 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168631 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168632 = AXIS2_PLACEMENT_3D('',#168633,#168634,#168635); +#168633 = CARTESIAN_POINT('',(22.5044,6.858,3.269996E-002)); +#168634 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168635 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#168636 = AXIS2_PLACEMENT_3D('',#168637,#168638,#168639); +#168637 = CARTESIAN_POINT('',(25.70471872,5.53728128,3.269996E-002)); +#168638 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168639 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#168640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168644)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168641,#168642,#168643)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166249 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166250 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166251 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166252 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166249, +#168641 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168642 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168643 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168644 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168641, 'distance_accuracy_value','confusion accuracy'); -#166253 = SHAPE_DEFINITION_REPRESENTATION(#166254,#166260); -#166254 = PRODUCT_DEFINITION_SHAPE('','',#166255); -#166255 = PRODUCT_DEFINITION('design','',#166256,#166259); -#166256 = PRODUCT_DEFINITION_FORMATION('','',#166257); -#166257 = PRODUCT('826583952','826583952','',(#166258)); -#166258 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166259 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166260 = SHAPE_REPRESENTATION('',(#11,#166261),#166265); -#166261 = AXIS2_PLACEMENT_3D('',#166262,#166263,#166264); -#166262 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#166263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166264 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166269)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166266,#166267,#166268)) +#168645 = SHAPE_DEFINITION_REPRESENTATION(#168646,#168652); +#168646 = PRODUCT_DEFINITION_SHAPE('','',#168647); +#168647 = PRODUCT_DEFINITION('design','',#168648,#168651); +#168648 = PRODUCT_DEFINITION_FORMATION('','',#168649); +#168649 = PRODUCT('549159968','549159968','',(#168650)); +#168650 = PRODUCT_CONTEXT('',#2,'mechanical'); +#168651 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#168652 = SHAPE_REPRESENTATION('',(#11,#168653),#168657); +#168653 = AXIS2_PLACEMENT_3D('',#168654,#168655,#168656); +#168654 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#168655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168656 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168661)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168658,#168659,#168660)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166266 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166267 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166268 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166269 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166266, +#168658 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168659 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168660 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168661 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168658, 'distance_accuracy_value','confusion accuracy'); -#166270 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#166271),#166601); -#166271 = MANIFOLD_SOLID_BREP('',#166272); -#166272 = CLOSED_SHELL('',(#166273,#166393,#166469,#166540,#166587, - #166594)); -#166273 = ADVANCED_FACE('',(#166274),#166288,.F.); -#166274 = FACE_BOUND('',#166275,.F.); -#166275 = EDGE_LOOP('',(#166276,#166311,#166339,#166367)); -#166276 = ORIENTED_EDGE('',*,*,#166277,.T.); -#166277 = EDGE_CURVE('',#166278,#166280,#166282,.T.); -#166278 = VERTEX_POINT('',#166279); -#166279 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); -#166280 = VERTEX_POINT('',#166281); -#166281 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); -#166282 = SURFACE_CURVE('',#166283,(#166287,#166299),.PCURVE_S1.); -#166283 = LINE('',#166284,#166285); -#166284 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); -#166285 = VECTOR('',#166286,1.); -#166286 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166287 = PCURVE('',#166288,#166293); -#166288 = PLANE('',#166289); -#166289 = AXIS2_PLACEMENT_3D('',#166290,#166291,#166292); -#166290 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); -#166291 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166292 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166293 = DEFINITIONAL_REPRESENTATION('',(#166294),#166298); -#166294 = LINE('',#166295,#166296); -#166295 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166296 = VECTOR('',#166297,1.); -#166297 = DIRECTION('',(0.E+000,-1.)); -#166298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166299 = PCURVE('',#166300,#166305); -#166300 = PLANE('',#166301); -#166301 = AXIS2_PLACEMENT_3D('',#166302,#166303,#166304); -#166302 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); -#166303 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166304 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166305 = DEFINITIONAL_REPRESENTATION('',(#166306),#166310); -#166306 = LINE('',#166307,#166308); -#166307 = CARTESIAN_POINT('',(2.9972,0.E+000)); -#166308 = VECTOR('',#166309,1.); -#166309 = DIRECTION('',(0.E+000,-1.)); -#166310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166311 = ORIENTED_EDGE('',*,*,#166312,.T.); -#166312 = EDGE_CURVE('',#166280,#166313,#166315,.T.); -#166313 = VERTEX_POINT('',#166314); -#166314 = CARTESIAN_POINT('',(2.3622,-1.4986,0.1)); -#166315 = SURFACE_CURVE('',#166316,(#166320,#166327),.PCURVE_S1.); -#166316 = LINE('',#166317,#166318); -#166317 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); -#166318 = VECTOR('',#166319,1.); -#166319 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166320 = PCURVE('',#166288,#166321); -#166321 = DEFINITIONAL_REPRESENTATION('',(#166322),#166326); -#166322 = LINE('',#166323,#166324); -#166323 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#166324 = VECTOR('',#166325,1.); -#166325 = DIRECTION('',(1.,0.E+000)); -#166326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166327 = PCURVE('',#166328,#166333); -#166328 = PLANE('',#166329); -#166329 = AXIS2_PLACEMENT_3D('',#166330,#166331,#166332); -#166330 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); -#166331 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#166332 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166333 = DEFINITIONAL_REPRESENTATION('',(#166334),#166338); -#166334 = LINE('',#166335,#166336); -#166335 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166336 = VECTOR('',#166337,1.); -#166337 = DIRECTION('',(-1.,0.E+000)); -#166338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166339 = ORIENTED_EDGE('',*,*,#166340,.F.); -#166340 = EDGE_CURVE('',#166341,#166313,#166343,.T.); -#166341 = VERTEX_POINT('',#166342); -#166342 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); -#166343 = SURFACE_CURVE('',#166344,(#166348,#166355),.PCURVE_S1.); -#166344 = LINE('',#166345,#166346); -#166345 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); -#166346 = VECTOR('',#166347,1.); -#166347 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166348 = PCURVE('',#166288,#166349); -#166349 = DEFINITIONAL_REPRESENTATION('',(#166350),#166354); -#166350 = LINE('',#166351,#166352); -#166351 = CARTESIAN_POINT('',(4.7244,0.E+000)); -#166352 = VECTOR('',#166353,1.); -#166353 = DIRECTION('',(0.E+000,-1.)); -#166354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166355 = PCURVE('',#166356,#166361); -#166356 = PLANE('',#166357); -#166357 = AXIS2_PLACEMENT_3D('',#166358,#166359,#166360); -#166358 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); -#166359 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166360 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166361 = DEFINITIONAL_REPRESENTATION('',(#166362),#166366); -#166362 = LINE('',#166363,#166364); -#166363 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166364 = VECTOR('',#166365,1.); -#166365 = DIRECTION('',(0.E+000,-1.)); -#166366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166367 = ORIENTED_EDGE('',*,*,#166368,.F.); -#166368 = EDGE_CURVE('',#166278,#166341,#166369,.T.); -#166369 = SURFACE_CURVE('',#166370,(#166374,#166381),.PCURVE_S1.); -#166370 = LINE('',#166371,#166372); -#166371 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); -#166372 = VECTOR('',#166373,1.); -#166373 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166374 = PCURVE('',#166288,#166375); -#166375 = DEFINITIONAL_REPRESENTATION('',(#166376),#166380); -#166376 = LINE('',#166377,#166378); -#166377 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166378 = VECTOR('',#166379,1.); -#166379 = DIRECTION('',(1.,0.E+000)); -#166380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166381 = PCURVE('',#166382,#166387); -#166382 = PLANE('',#166383); -#166383 = AXIS2_PLACEMENT_3D('',#166384,#166385,#166386); -#166384 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); -#166385 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#166386 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166387 = DEFINITIONAL_REPRESENTATION('',(#166388),#166392); -#166388 = LINE('',#166389,#166390); -#166389 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166390 = VECTOR('',#166391,1.); -#166391 = DIRECTION('',(-1.,0.E+000)); -#166392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166393 = ADVANCED_FACE('',(#166394),#166356,.F.); -#166394 = FACE_BOUND('',#166395,.F.); -#166395 = EDGE_LOOP('',(#166396,#166397,#166420,#166448)); -#166396 = ORIENTED_EDGE('',*,*,#166340,.T.); -#166397 = ORIENTED_EDGE('',*,*,#166398,.T.); -#166398 = EDGE_CURVE('',#166313,#166399,#166401,.T.); -#166399 = VERTEX_POINT('',#166400); -#166400 = CARTESIAN_POINT('',(2.3622,1.4986,0.1)); -#166401 = SURFACE_CURVE('',#166402,(#166406,#166413),.PCURVE_S1.); -#166402 = LINE('',#166403,#166404); -#166403 = CARTESIAN_POINT('',(2.3622,-1.4986,0.1)); -#166404 = VECTOR('',#166405,1.); -#166405 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166406 = PCURVE('',#166356,#166407); -#166407 = DEFINITIONAL_REPRESENTATION('',(#166408),#166412); -#166408 = LINE('',#166409,#166410); -#166409 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#166410 = VECTOR('',#166411,1.); -#166411 = DIRECTION('',(1.,0.E+000)); -#166412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166413 = PCURVE('',#166328,#166414); -#166414 = DEFINITIONAL_REPRESENTATION('',(#166415),#166419); -#166415 = LINE('',#166416,#166417); -#166416 = CARTESIAN_POINT('',(-4.7244,0.E+000)); -#166417 = VECTOR('',#166418,1.); -#166418 = DIRECTION('',(0.E+000,1.)); -#166419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166420 = ORIENTED_EDGE('',*,*,#166421,.F.); -#166421 = EDGE_CURVE('',#166422,#166399,#166424,.T.); -#166422 = VERTEX_POINT('',#166423); -#166423 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); -#166424 = SURFACE_CURVE('',#166425,(#166429,#166436),.PCURVE_S1.); -#166425 = LINE('',#166426,#166427); -#166426 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); -#166427 = VECTOR('',#166428,1.); -#166428 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166429 = PCURVE('',#166356,#166430); -#166430 = DEFINITIONAL_REPRESENTATION('',(#166431),#166435); -#166431 = LINE('',#166432,#166433); -#166432 = CARTESIAN_POINT('',(2.9972,0.E+000)); -#166433 = VECTOR('',#166434,1.); -#166434 = DIRECTION('',(0.E+000,-1.)); -#166435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166436 = PCURVE('',#166437,#166442); -#166437 = PLANE('',#166438); -#166438 = AXIS2_PLACEMENT_3D('',#166439,#166440,#166441); -#166439 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); -#166440 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166441 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166442 = DEFINITIONAL_REPRESENTATION('',(#166443),#166447); -#166443 = LINE('',#166444,#166445); -#166444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166445 = VECTOR('',#166446,1.); -#166446 = DIRECTION('',(0.E+000,-1.)); -#166447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166448 = ORIENTED_EDGE('',*,*,#166449,.F.); -#166449 = EDGE_CURVE('',#166341,#166422,#166450,.T.); -#166450 = SURFACE_CURVE('',#166451,(#166455,#166462),.PCURVE_S1.); -#166451 = LINE('',#166452,#166453); -#166452 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); -#166453 = VECTOR('',#166454,1.); -#166454 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166455 = PCURVE('',#166356,#166456); -#166456 = DEFINITIONAL_REPRESENTATION('',(#166457),#166461); -#166457 = LINE('',#166458,#166459); -#166458 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166459 = VECTOR('',#166460,1.); -#166460 = DIRECTION('',(1.,0.E+000)); -#166461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166462 = PCURVE('',#166382,#166463); -#166463 = DEFINITIONAL_REPRESENTATION('',(#166464),#166468); -#166464 = LINE('',#166465,#166466); -#166465 = CARTESIAN_POINT('',(-4.7244,0.E+000)); -#166466 = VECTOR('',#166467,1.); -#166467 = DIRECTION('',(0.E+000,1.)); -#166468 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166469 = ADVANCED_FACE('',(#166470),#166437,.F.); -#166470 = FACE_BOUND('',#166471,.F.); -#166471 = EDGE_LOOP('',(#166472,#166473,#166496,#166519)); -#166472 = ORIENTED_EDGE('',*,*,#166421,.T.); -#166473 = ORIENTED_EDGE('',*,*,#166474,.T.); -#166474 = EDGE_CURVE('',#166399,#166475,#166477,.T.); -#166475 = VERTEX_POINT('',#166476); -#166476 = CARTESIAN_POINT('',(-2.3622,1.4986,0.1)); -#166477 = SURFACE_CURVE('',#166478,(#166482,#166489),.PCURVE_S1.); -#166478 = LINE('',#166479,#166480); -#166479 = CARTESIAN_POINT('',(2.3622,1.4986,0.1)); -#166480 = VECTOR('',#166481,1.); -#166481 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166482 = PCURVE('',#166437,#166483); -#166483 = DEFINITIONAL_REPRESENTATION('',(#166484),#166488); -#166484 = LINE('',#166485,#166486); -#166485 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#166486 = VECTOR('',#166487,1.); -#166487 = DIRECTION('',(1.,0.E+000)); -#166488 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166489 = PCURVE('',#166328,#166490); -#166490 = DEFINITIONAL_REPRESENTATION('',(#166491),#166495); -#166491 = LINE('',#166492,#166493); -#166492 = CARTESIAN_POINT('',(-4.7244,2.9972)); -#166493 = VECTOR('',#166494,1.); -#166494 = DIRECTION('',(1.,0.E+000)); -#166495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166496 = ORIENTED_EDGE('',*,*,#166497,.F.); -#166497 = EDGE_CURVE('',#166498,#166475,#166500,.T.); -#166498 = VERTEX_POINT('',#166499); -#166499 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); -#166500 = SURFACE_CURVE('',#166501,(#166505,#166512),.PCURVE_S1.); -#166501 = LINE('',#166502,#166503); -#166502 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); -#166503 = VECTOR('',#166504,1.); -#166504 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166505 = PCURVE('',#166437,#166506); -#166506 = DEFINITIONAL_REPRESENTATION('',(#166507),#166511); -#166507 = LINE('',#166508,#166509); -#166508 = CARTESIAN_POINT('',(4.7244,0.E+000)); -#166509 = VECTOR('',#166510,1.); -#166510 = DIRECTION('',(0.E+000,-1.)); -#166511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166512 = PCURVE('',#166300,#166513); -#166513 = DEFINITIONAL_REPRESENTATION('',(#166514),#166518); -#166514 = LINE('',#166515,#166516); -#166515 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166516 = VECTOR('',#166517,1.); -#166517 = DIRECTION('',(0.E+000,-1.)); -#166518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166519 = ORIENTED_EDGE('',*,*,#166520,.F.); -#166520 = EDGE_CURVE('',#166422,#166498,#166521,.T.); -#166521 = SURFACE_CURVE('',#166522,(#166526,#166533),.PCURVE_S1.); -#166522 = LINE('',#166523,#166524); -#166523 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); -#166524 = VECTOR('',#166525,1.); -#166525 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166526 = PCURVE('',#166437,#166527); -#166527 = DEFINITIONAL_REPRESENTATION('',(#166528),#166532); -#166528 = LINE('',#166529,#166530); -#166529 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166530 = VECTOR('',#166531,1.); -#166531 = DIRECTION('',(1.,0.E+000)); -#166532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166533 = PCURVE('',#166382,#166534); -#166534 = DEFINITIONAL_REPRESENTATION('',(#166535),#166539); -#166535 = LINE('',#166536,#166537); -#166536 = CARTESIAN_POINT('',(-4.7244,2.9972)); -#166537 = VECTOR('',#166538,1.); -#166538 = DIRECTION('',(1.,0.E+000)); -#166539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166540 = ADVANCED_FACE('',(#166541),#166300,.F.); -#166541 = FACE_BOUND('',#166542,.F.); -#166542 = EDGE_LOOP('',(#166543,#166544,#166565,#166566)); -#166543 = ORIENTED_EDGE('',*,*,#166497,.T.); -#166544 = ORIENTED_EDGE('',*,*,#166545,.T.); -#166545 = EDGE_CURVE('',#166475,#166280,#166546,.T.); -#166546 = SURFACE_CURVE('',#166547,(#166551,#166558),.PCURVE_S1.); -#166547 = LINE('',#166548,#166549); -#166548 = CARTESIAN_POINT('',(-2.3622,1.4986,0.1)); -#166549 = VECTOR('',#166550,1.); -#166550 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166551 = PCURVE('',#166300,#166552); -#166552 = DEFINITIONAL_REPRESENTATION('',(#166553),#166557); -#166553 = LINE('',#166554,#166555); -#166554 = CARTESIAN_POINT('',(0.E+000,-0.1)); -#166555 = VECTOR('',#166556,1.); -#166556 = DIRECTION('',(1.,0.E+000)); -#166557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166558 = PCURVE('',#166328,#166559); -#166559 = DEFINITIONAL_REPRESENTATION('',(#166560),#166564); -#166560 = LINE('',#166561,#166562); -#166561 = CARTESIAN_POINT('',(0.E+000,2.9972)); -#166562 = VECTOR('',#166563,1.); -#166563 = DIRECTION('',(0.E+000,-1.)); -#166564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166565 = ORIENTED_EDGE('',*,*,#166277,.F.); -#166566 = ORIENTED_EDGE('',*,*,#166567,.F.); -#166567 = EDGE_CURVE('',#166498,#166278,#166568,.T.); -#166568 = SURFACE_CURVE('',#166569,(#166573,#166580),.PCURVE_S1.); -#166569 = LINE('',#166570,#166571); -#166570 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); -#166571 = VECTOR('',#166572,1.); -#166572 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166573 = PCURVE('',#166300,#166574); -#166574 = DEFINITIONAL_REPRESENTATION('',(#166575),#166579); -#166575 = LINE('',#166576,#166577); -#166576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166577 = VECTOR('',#166578,1.); -#166578 = DIRECTION('',(1.,0.E+000)); -#166579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166580 = PCURVE('',#166382,#166581); -#166581 = DEFINITIONAL_REPRESENTATION('',(#166582),#166586); -#166582 = LINE('',#166583,#166584); -#166583 = CARTESIAN_POINT('',(0.E+000,2.9972)); -#166584 = VECTOR('',#166585,1.); -#166585 = DIRECTION('',(0.E+000,-1.)); -#166586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166587 = ADVANCED_FACE('',(#166588),#166382,.T.); -#166588 = FACE_BOUND('',#166589,.F.); -#166589 = EDGE_LOOP('',(#166590,#166591,#166592,#166593)); -#166590 = ORIENTED_EDGE('',*,*,#166368,.T.); -#166591 = ORIENTED_EDGE('',*,*,#166449,.T.); -#166592 = ORIENTED_EDGE('',*,*,#166520,.T.); -#166593 = ORIENTED_EDGE('',*,*,#166567,.T.); -#166594 = ADVANCED_FACE('',(#166595),#166328,.F.); -#166595 = FACE_BOUND('',#166596,.T.); -#166596 = EDGE_LOOP('',(#166597,#166598,#166599,#166600)); -#166597 = ORIENTED_EDGE('',*,*,#166312,.T.); -#166598 = ORIENTED_EDGE('',*,*,#166398,.T.); -#166599 = ORIENTED_EDGE('',*,*,#166474,.T.); -#166600 = ORIENTED_EDGE('',*,*,#166545,.T.); -#166601 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166605)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166602,#166603,#166604)) +#168662 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#168663),#168993); +#168663 = MANIFOLD_SOLID_BREP('',#168664); +#168664 = CLOSED_SHELL('',(#168665,#168785,#168861,#168932,#168979, + #168986)); +#168665 = ADVANCED_FACE('',(#168666),#168680,.F.); +#168666 = FACE_BOUND('',#168667,.F.); +#168667 = EDGE_LOOP('',(#168668,#168703,#168731,#168759)); +#168668 = ORIENTED_EDGE('',*,*,#168669,.T.); +#168669 = EDGE_CURVE('',#168670,#168672,#168674,.T.); +#168670 = VERTEX_POINT('',#168671); +#168671 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); +#168672 = VERTEX_POINT('',#168673); +#168673 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); +#168674 = SURFACE_CURVE('',#168675,(#168679,#168691),.PCURVE_S1.); +#168675 = LINE('',#168676,#168677); +#168676 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); +#168677 = VECTOR('',#168678,1.); +#168678 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168679 = PCURVE('',#168680,#168685); +#168680 = PLANE('',#168681); +#168681 = AXIS2_PLACEMENT_3D('',#168682,#168683,#168684); +#168682 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); +#168683 = DIRECTION('',(0.E+000,1.,0.E+000)); +#168684 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168685 = DEFINITIONAL_REPRESENTATION('',(#168686),#168690); +#168686 = LINE('',#168687,#168688); +#168687 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168688 = VECTOR('',#168689,1.); +#168689 = DIRECTION('',(0.E+000,-1.)); +#168690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168691 = PCURVE('',#168692,#168697); +#168692 = PLANE('',#168693); +#168693 = AXIS2_PLACEMENT_3D('',#168694,#168695,#168696); +#168694 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); +#168695 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168696 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168697 = DEFINITIONAL_REPRESENTATION('',(#168698),#168702); +#168698 = LINE('',#168699,#168700); +#168699 = CARTESIAN_POINT('',(2.9972,0.E+000)); +#168700 = VECTOR('',#168701,1.); +#168701 = DIRECTION('',(0.E+000,-1.)); +#168702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168703 = ORIENTED_EDGE('',*,*,#168704,.T.); +#168704 = EDGE_CURVE('',#168672,#168705,#168707,.T.); +#168705 = VERTEX_POINT('',#168706); +#168706 = CARTESIAN_POINT('',(2.3622,-1.4986,0.1)); +#168707 = SURFACE_CURVE('',#168708,(#168712,#168719),.PCURVE_S1.); +#168708 = LINE('',#168709,#168710); +#168709 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); +#168710 = VECTOR('',#168711,1.); +#168711 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168712 = PCURVE('',#168680,#168713); +#168713 = DEFINITIONAL_REPRESENTATION('',(#168714),#168718); +#168714 = LINE('',#168715,#168716); +#168715 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#168716 = VECTOR('',#168717,1.); +#168717 = DIRECTION('',(1.,0.E+000)); +#168718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168719 = PCURVE('',#168720,#168725); +#168720 = PLANE('',#168721); +#168721 = AXIS2_PLACEMENT_3D('',#168722,#168723,#168724); +#168722 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.1)); +#168723 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#168724 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168725 = DEFINITIONAL_REPRESENTATION('',(#168726),#168730); +#168726 = LINE('',#168727,#168728); +#168727 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168728 = VECTOR('',#168729,1.); +#168729 = DIRECTION('',(-1.,0.E+000)); +#168730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168731 = ORIENTED_EDGE('',*,*,#168732,.F.); +#168732 = EDGE_CURVE('',#168733,#168705,#168735,.T.); +#168733 = VERTEX_POINT('',#168734); +#168734 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); +#168735 = SURFACE_CURVE('',#168736,(#168740,#168747),.PCURVE_S1.); +#168736 = LINE('',#168737,#168738); +#168737 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); +#168738 = VECTOR('',#168739,1.); +#168739 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168740 = PCURVE('',#168680,#168741); +#168741 = DEFINITIONAL_REPRESENTATION('',(#168742),#168746); +#168742 = LINE('',#168743,#168744); +#168743 = CARTESIAN_POINT('',(4.7244,0.E+000)); +#168744 = VECTOR('',#168745,1.); +#168745 = DIRECTION('',(0.E+000,-1.)); +#168746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168747 = PCURVE('',#168748,#168753); +#168748 = PLANE('',#168749); +#168749 = AXIS2_PLACEMENT_3D('',#168750,#168751,#168752); +#168750 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); +#168751 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168752 = DIRECTION('',(0.E+000,1.,0.E+000)); +#168753 = DEFINITIONAL_REPRESENTATION('',(#168754),#168758); +#168754 = LINE('',#168755,#168756); +#168755 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168756 = VECTOR('',#168757,1.); +#168757 = DIRECTION('',(0.E+000,-1.)); +#168758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168759 = ORIENTED_EDGE('',*,*,#168760,.F.); +#168760 = EDGE_CURVE('',#168670,#168733,#168761,.T.); +#168761 = SURFACE_CURVE('',#168762,(#168766,#168773),.PCURVE_S1.); +#168762 = LINE('',#168763,#168764); +#168763 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); +#168764 = VECTOR('',#168765,1.); +#168765 = DIRECTION('',(1.,0.E+000,0.E+000)); +#168766 = PCURVE('',#168680,#168767); +#168767 = DEFINITIONAL_REPRESENTATION('',(#168768),#168772); +#168768 = LINE('',#168769,#168770); +#168769 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168770 = VECTOR('',#168771,1.); +#168771 = DIRECTION('',(1.,0.E+000)); +#168772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168773 = PCURVE('',#168774,#168779); +#168774 = PLANE('',#168775); +#168775 = AXIS2_PLACEMENT_3D('',#168776,#168777,#168778); +#168776 = CARTESIAN_POINT('',(-2.3622,-1.4986,0.E+000)); +#168777 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#168778 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168779 = DEFINITIONAL_REPRESENTATION('',(#168780),#168784); +#168780 = LINE('',#168781,#168782); +#168781 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168782 = VECTOR('',#168783,1.); +#168783 = DIRECTION('',(-1.,0.E+000)); +#168784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168785 = ADVANCED_FACE('',(#168786),#168748,.F.); +#168786 = FACE_BOUND('',#168787,.F.); +#168787 = EDGE_LOOP('',(#168788,#168789,#168812,#168840)); +#168788 = ORIENTED_EDGE('',*,*,#168732,.T.); +#168789 = ORIENTED_EDGE('',*,*,#168790,.T.); +#168790 = EDGE_CURVE('',#168705,#168791,#168793,.T.); +#168791 = VERTEX_POINT('',#168792); +#168792 = CARTESIAN_POINT('',(2.3622,1.4986,0.1)); +#168793 = SURFACE_CURVE('',#168794,(#168798,#168805),.PCURVE_S1.); +#168794 = LINE('',#168795,#168796); +#168795 = CARTESIAN_POINT('',(2.3622,-1.4986,0.1)); +#168796 = VECTOR('',#168797,1.); +#168797 = DIRECTION('',(0.E+000,1.,0.E+000)); +#168798 = PCURVE('',#168748,#168799); +#168799 = DEFINITIONAL_REPRESENTATION('',(#168800),#168804); +#168800 = LINE('',#168801,#168802); +#168801 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#168802 = VECTOR('',#168803,1.); +#168803 = DIRECTION('',(1.,0.E+000)); +#168804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168805 = PCURVE('',#168720,#168806); +#168806 = DEFINITIONAL_REPRESENTATION('',(#168807),#168811); +#168807 = LINE('',#168808,#168809); +#168808 = CARTESIAN_POINT('',(-4.7244,0.E+000)); +#168809 = VECTOR('',#168810,1.); +#168810 = DIRECTION('',(0.E+000,1.)); +#168811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168812 = ORIENTED_EDGE('',*,*,#168813,.F.); +#168813 = EDGE_CURVE('',#168814,#168791,#168816,.T.); +#168814 = VERTEX_POINT('',#168815); +#168815 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); +#168816 = SURFACE_CURVE('',#168817,(#168821,#168828),.PCURVE_S1.); +#168817 = LINE('',#168818,#168819); +#168818 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); +#168819 = VECTOR('',#168820,1.); +#168820 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168821 = PCURVE('',#168748,#168822); +#168822 = DEFINITIONAL_REPRESENTATION('',(#168823),#168827); +#168823 = LINE('',#168824,#168825); +#168824 = CARTESIAN_POINT('',(2.9972,0.E+000)); +#168825 = VECTOR('',#168826,1.); +#168826 = DIRECTION('',(0.E+000,-1.)); +#168827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168828 = PCURVE('',#168829,#168834); +#168829 = PLANE('',#168830); +#168830 = AXIS2_PLACEMENT_3D('',#168831,#168832,#168833); +#168831 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); +#168832 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168833 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168834 = DEFINITIONAL_REPRESENTATION('',(#168835),#168839); +#168835 = LINE('',#168836,#168837); +#168836 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168837 = VECTOR('',#168838,1.); +#168838 = DIRECTION('',(0.E+000,-1.)); +#168839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168840 = ORIENTED_EDGE('',*,*,#168841,.F.); +#168841 = EDGE_CURVE('',#168733,#168814,#168842,.T.); +#168842 = SURFACE_CURVE('',#168843,(#168847,#168854),.PCURVE_S1.); +#168843 = LINE('',#168844,#168845); +#168844 = CARTESIAN_POINT('',(2.3622,-1.4986,0.E+000)); +#168845 = VECTOR('',#168846,1.); +#168846 = DIRECTION('',(0.E+000,1.,0.E+000)); +#168847 = PCURVE('',#168748,#168848); +#168848 = DEFINITIONAL_REPRESENTATION('',(#168849),#168853); +#168849 = LINE('',#168850,#168851); +#168850 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168851 = VECTOR('',#168852,1.); +#168852 = DIRECTION('',(1.,0.E+000)); +#168853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168854 = PCURVE('',#168774,#168855); +#168855 = DEFINITIONAL_REPRESENTATION('',(#168856),#168860); +#168856 = LINE('',#168857,#168858); +#168857 = CARTESIAN_POINT('',(-4.7244,0.E+000)); +#168858 = VECTOR('',#168859,1.); +#168859 = DIRECTION('',(0.E+000,1.)); +#168860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168861 = ADVANCED_FACE('',(#168862),#168829,.F.); +#168862 = FACE_BOUND('',#168863,.F.); +#168863 = EDGE_LOOP('',(#168864,#168865,#168888,#168911)); +#168864 = ORIENTED_EDGE('',*,*,#168813,.T.); +#168865 = ORIENTED_EDGE('',*,*,#168866,.T.); +#168866 = EDGE_CURVE('',#168791,#168867,#168869,.T.); +#168867 = VERTEX_POINT('',#168868); +#168868 = CARTESIAN_POINT('',(-2.3622,1.4986,0.1)); +#168869 = SURFACE_CURVE('',#168870,(#168874,#168881),.PCURVE_S1.); +#168870 = LINE('',#168871,#168872); +#168871 = CARTESIAN_POINT('',(2.3622,1.4986,0.1)); +#168872 = VECTOR('',#168873,1.); +#168873 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168874 = PCURVE('',#168829,#168875); +#168875 = DEFINITIONAL_REPRESENTATION('',(#168876),#168880); +#168876 = LINE('',#168877,#168878); +#168877 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#168878 = VECTOR('',#168879,1.); +#168879 = DIRECTION('',(1.,0.E+000)); +#168880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168881 = PCURVE('',#168720,#168882); +#168882 = DEFINITIONAL_REPRESENTATION('',(#168883),#168887); +#168883 = LINE('',#168884,#168885); +#168884 = CARTESIAN_POINT('',(-4.7244,2.9972)); +#168885 = VECTOR('',#168886,1.); +#168886 = DIRECTION('',(1.,0.E+000)); +#168887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168888 = ORIENTED_EDGE('',*,*,#168889,.F.); +#168889 = EDGE_CURVE('',#168890,#168867,#168892,.T.); +#168890 = VERTEX_POINT('',#168891); +#168891 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); +#168892 = SURFACE_CURVE('',#168893,(#168897,#168904),.PCURVE_S1.); +#168893 = LINE('',#168894,#168895); +#168894 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); +#168895 = VECTOR('',#168896,1.); +#168896 = DIRECTION('',(0.E+000,0.E+000,1.)); +#168897 = PCURVE('',#168829,#168898); +#168898 = DEFINITIONAL_REPRESENTATION('',(#168899),#168903); +#168899 = LINE('',#168900,#168901); +#168900 = CARTESIAN_POINT('',(4.7244,0.E+000)); +#168901 = VECTOR('',#168902,1.); +#168902 = DIRECTION('',(0.E+000,-1.)); +#168903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168904 = PCURVE('',#168692,#168905); +#168905 = DEFINITIONAL_REPRESENTATION('',(#168906),#168910); +#168906 = LINE('',#168907,#168908); +#168907 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168908 = VECTOR('',#168909,1.); +#168909 = DIRECTION('',(0.E+000,-1.)); +#168910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168911 = ORIENTED_EDGE('',*,*,#168912,.F.); +#168912 = EDGE_CURVE('',#168814,#168890,#168913,.T.); +#168913 = SURFACE_CURVE('',#168914,(#168918,#168925),.PCURVE_S1.); +#168914 = LINE('',#168915,#168916); +#168915 = CARTESIAN_POINT('',(2.3622,1.4986,0.E+000)); +#168916 = VECTOR('',#168917,1.); +#168917 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#168918 = PCURVE('',#168829,#168919); +#168919 = DEFINITIONAL_REPRESENTATION('',(#168920),#168924); +#168920 = LINE('',#168921,#168922); +#168921 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168922 = VECTOR('',#168923,1.); +#168923 = DIRECTION('',(1.,0.E+000)); +#168924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168925 = PCURVE('',#168774,#168926); +#168926 = DEFINITIONAL_REPRESENTATION('',(#168927),#168931); +#168927 = LINE('',#168928,#168929); +#168928 = CARTESIAN_POINT('',(-4.7244,2.9972)); +#168929 = VECTOR('',#168930,1.); +#168930 = DIRECTION('',(1.,0.E+000)); +#168931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168932 = ADVANCED_FACE('',(#168933),#168692,.F.); +#168933 = FACE_BOUND('',#168934,.F.); +#168934 = EDGE_LOOP('',(#168935,#168936,#168957,#168958)); +#168935 = ORIENTED_EDGE('',*,*,#168889,.T.); +#168936 = ORIENTED_EDGE('',*,*,#168937,.T.); +#168937 = EDGE_CURVE('',#168867,#168672,#168938,.T.); +#168938 = SURFACE_CURVE('',#168939,(#168943,#168950),.PCURVE_S1.); +#168939 = LINE('',#168940,#168941); +#168940 = CARTESIAN_POINT('',(-2.3622,1.4986,0.1)); +#168941 = VECTOR('',#168942,1.); +#168942 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168943 = PCURVE('',#168692,#168944); +#168944 = DEFINITIONAL_REPRESENTATION('',(#168945),#168949); +#168945 = LINE('',#168946,#168947); +#168946 = CARTESIAN_POINT('',(0.E+000,-0.1)); +#168947 = VECTOR('',#168948,1.); +#168948 = DIRECTION('',(1.,0.E+000)); +#168949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168950 = PCURVE('',#168720,#168951); +#168951 = DEFINITIONAL_REPRESENTATION('',(#168952),#168956); +#168952 = LINE('',#168953,#168954); +#168953 = CARTESIAN_POINT('',(0.E+000,2.9972)); +#168954 = VECTOR('',#168955,1.); +#168955 = DIRECTION('',(0.E+000,-1.)); +#168956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168957 = ORIENTED_EDGE('',*,*,#168669,.F.); +#168958 = ORIENTED_EDGE('',*,*,#168959,.F.); +#168959 = EDGE_CURVE('',#168890,#168670,#168960,.T.); +#168960 = SURFACE_CURVE('',#168961,(#168965,#168972),.PCURVE_S1.); +#168961 = LINE('',#168962,#168963); +#168962 = CARTESIAN_POINT('',(-2.3622,1.4986,0.E+000)); +#168963 = VECTOR('',#168964,1.); +#168964 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#168965 = PCURVE('',#168692,#168966); +#168966 = DEFINITIONAL_REPRESENTATION('',(#168967),#168971); +#168967 = LINE('',#168968,#168969); +#168968 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#168969 = VECTOR('',#168970,1.); +#168970 = DIRECTION('',(1.,0.E+000)); +#168971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168972 = PCURVE('',#168774,#168973); +#168973 = DEFINITIONAL_REPRESENTATION('',(#168974),#168978); +#168974 = LINE('',#168975,#168976); +#168975 = CARTESIAN_POINT('',(0.E+000,2.9972)); +#168976 = VECTOR('',#168977,1.); +#168977 = DIRECTION('',(0.E+000,-1.)); +#168978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#168979 = ADVANCED_FACE('',(#168980),#168774,.T.); +#168980 = FACE_BOUND('',#168981,.F.); +#168981 = EDGE_LOOP('',(#168982,#168983,#168984,#168985)); +#168982 = ORIENTED_EDGE('',*,*,#168760,.T.); +#168983 = ORIENTED_EDGE('',*,*,#168841,.T.); +#168984 = ORIENTED_EDGE('',*,*,#168912,.T.); +#168985 = ORIENTED_EDGE('',*,*,#168959,.T.); +#168986 = ADVANCED_FACE('',(#168987),#168720,.F.); +#168987 = FACE_BOUND('',#168988,.T.); +#168988 = EDGE_LOOP('',(#168989,#168990,#168991,#168992)); +#168989 = ORIENTED_EDGE('',*,*,#168704,.T.); +#168990 = ORIENTED_EDGE('',*,*,#168790,.T.); +#168991 = ORIENTED_EDGE('',*,*,#168866,.T.); +#168992 = ORIENTED_EDGE('',*,*,#168937,.T.); +#168993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168997)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#168994,#168995,#168996)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166602 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166603 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166604 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166605 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166602, +#168994 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#168995 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#168996 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#168997 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168994, 'distance_accuracy_value','confusion accuracy'); -#166606 = SHAPE_DEFINITION_REPRESENTATION(#166607,#166270); -#166607 = PRODUCT_DEFINITION_SHAPE('','',#166608); -#166608 = PRODUCT_DEFINITION('design','',#166609,#166612); -#166609 = PRODUCT_DEFINITION_FORMATION('','',#166610); -#166610 = PRODUCT('Extruded','Extruded','',(#166611)); -#166611 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166612 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166613 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166614,#166616); -#166614 = ( REPRESENTATION_RELATIONSHIP('','',#166270,#166260) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166615) +#168998 = SHAPE_DEFINITION_REPRESENTATION(#168999,#168662); +#168999 = PRODUCT_DEFINITION_SHAPE('','',#169000); +#169000 = PRODUCT_DEFINITION('design','',#169001,#169004); +#169001 = PRODUCT_DEFINITION_FORMATION('','',#169002); +#169002 = PRODUCT('Extruded','Extruded','',(#169003)); +#169003 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169004 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169005 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169006,#169008); +#169006 = ( REPRESENTATION_RELATIONSHIP('','',#168662,#168652) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169007) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166615 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166261); -#166616 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166617); -#166617 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('289','=>[0:1:1:2]','',#166255, - #166608,$); -#166618 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166610)); -#166619 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166620,#166622); -#166620 = ( REPRESENTATION_RELATIONSHIP('','',#166260,#166231) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166621) +#169007 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168653); +#169008 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169009); +#169009 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('390','=>[0:1:1:2]','',#168647, + #169000,$); +#169010 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169002)); +#169011 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169012,#169014); +#169012 = ( REPRESENTATION_RELATIONSHIP('','',#168652,#168623) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169013) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166621 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166232); -#166622 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166623); -#166623 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('290','=>[0:1:1:93]','',#166226 - ,#166255,$); -#166624 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166257)); -#166625 = SHAPE_DEFINITION_REPRESENTATION(#166626,#166632); -#166626 = PRODUCT_DEFINITION_SHAPE('','',#166627); -#166627 = PRODUCT_DEFINITION('design','',#166628,#166631); -#166628 = PRODUCT_DEFINITION_FORMATION('','',#166629); -#166629 = PRODUCT('622912288','622912288','',(#166630)); -#166630 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166631 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166632 = SHAPE_REPRESENTATION('',(#11,#166633),#166637); -#166633 = AXIS2_PLACEMENT_3D('',#166634,#166635,#166636); -#166634 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#166635 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166636 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166641)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166638,#166639,#166640)) +#169013 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168624); +#169014 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169015); +#169015 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('391','=>[0:1:1:93]','',#168618 + ,#168647,$); +#169016 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168649)); +#169017 = SHAPE_DEFINITION_REPRESENTATION(#169018,#169024); +#169018 = PRODUCT_DEFINITION_SHAPE('','',#169019); +#169019 = PRODUCT_DEFINITION('design','',#169020,#169023); +#169020 = PRODUCT_DEFINITION_FORMATION('','',#169021); +#169021 = PRODUCT('549159712','549159712','',(#169022)); +#169022 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169023 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169024 = SHAPE_REPRESENTATION('',(#11,#169025),#169029); +#169025 = AXIS2_PLACEMENT_3D('',#169026,#169027,#169028); +#169026 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169027 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169028 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169033)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169030,#169031,#169032)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166638 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166639 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166640 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166641 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166638, +#169030 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169031 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169032 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169033 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169030, 'distance_accuracy_value','confusion accuracy'); -#166642 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#166643),#166973); -#166643 = MANIFOLD_SOLID_BREP('',#166644); -#166644 = CLOSED_SHELL('',(#166645,#166765,#166841,#166912,#166959, - #166966)); -#166645 = ADVANCED_FACE('',(#166646),#166660,.T.); -#166646 = FACE_BOUND('',#166647,.T.); -#166647 = EDGE_LOOP('',(#166648,#166683,#166711,#166739)); -#166648 = ORIENTED_EDGE('',*,*,#166649,.T.); -#166649 = EDGE_CURVE('',#166650,#166652,#166654,.T.); -#166650 = VERTEX_POINT('',#166651); -#166651 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); -#166652 = VERTEX_POINT('',#166653); -#166653 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); -#166654 = SURFACE_CURVE('',#166655,(#166659,#166671),.PCURVE_S1.); -#166655 = LINE('',#166656,#166657); -#166656 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); -#166657 = VECTOR('',#166658,1.); -#166658 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166659 = PCURVE('',#166660,#166665); -#166660 = PLANE('',#166661); -#166661 = AXIS2_PLACEMENT_3D('',#166662,#166663,#166664); -#166662 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); -#166663 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166664 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166665 = DEFINITIONAL_REPRESENTATION('',(#166666),#166670); -#166666 = LINE('',#166667,#166668); -#166667 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166668 = VECTOR('',#166669,1.); -#166669 = DIRECTION('',(0.E+000,-1.)); -#166670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166671 = PCURVE('',#166672,#166677); -#166672 = PLANE('',#166673); -#166673 = AXIS2_PLACEMENT_3D('',#166674,#166675,#166676); -#166674 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); -#166675 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166676 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166677 = DEFINITIONAL_REPRESENTATION('',(#166678),#166682); -#166678 = LINE('',#166679,#166680); -#166679 = CARTESIAN_POINT('',(4.4704,0.E+000)); -#166680 = VECTOR('',#166681,1.); -#166681 = DIRECTION('',(0.E+000,-1.)); -#166682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166683 = ORIENTED_EDGE('',*,*,#166684,.T.); -#166684 = EDGE_CURVE('',#166652,#166685,#166687,.T.); -#166685 = VERTEX_POINT('',#166686); -#166686 = CARTESIAN_POINT('',(-2.2352,1.27,0.99)); -#166687 = SURFACE_CURVE('',#166688,(#166692,#166699),.PCURVE_S1.); -#166688 = LINE('',#166689,#166690); -#166689 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); -#166690 = VECTOR('',#166691,1.); -#166691 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166692 = PCURVE('',#166660,#166693); -#166693 = DEFINITIONAL_REPRESENTATION('',(#166694),#166698); -#166694 = LINE('',#166695,#166696); -#166695 = CARTESIAN_POINT('',(0.E+000,-0.99)); -#166696 = VECTOR('',#166697,1.); -#166697 = DIRECTION('',(1.,0.E+000)); -#166698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166699 = PCURVE('',#166700,#166705); -#166700 = PLANE('',#166701); -#166701 = AXIS2_PLACEMENT_3D('',#166702,#166703,#166704); -#166702 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); -#166703 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166704 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166705 = DEFINITIONAL_REPRESENTATION('',(#166706),#166710); -#166706 = LINE('',#166707,#166708); -#166707 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166708 = VECTOR('',#166709,1.); -#166709 = DIRECTION('',(0.E+000,1.)); -#166710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166711 = ORIENTED_EDGE('',*,*,#166712,.F.); -#166712 = EDGE_CURVE('',#166713,#166685,#166715,.T.); -#166713 = VERTEX_POINT('',#166714); -#166714 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); -#166715 = SURFACE_CURVE('',#166716,(#166720,#166727),.PCURVE_S1.); -#166716 = LINE('',#166717,#166718); -#166717 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); -#166718 = VECTOR('',#166719,1.); -#166719 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166720 = PCURVE('',#166660,#166721); -#166721 = DEFINITIONAL_REPRESENTATION('',(#166722),#166726); -#166722 = LINE('',#166723,#166724); -#166723 = CARTESIAN_POINT('',(2.54,0.E+000)); -#166724 = VECTOR('',#166725,1.); -#166725 = DIRECTION('',(0.E+000,-1.)); -#166726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166727 = PCURVE('',#166728,#166733); -#166728 = PLANE('',#166729); -#166729 = AXIS2_PLACEMENT_3D('',#166730,#166731,#166732); -#166730 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); -#166731 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166732 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166733 = DEFINITIONAL_REPRESENTATION('',(#166734),#166738); -#166734 = LINE('',#166735,#166736); -#166735 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166736 = VECTOR('',#166737,1.); -#166737 = DIRECTION('',(0.E+000,-1.)); -#166738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166739 = ORIENTED_EDGE('',*,*,#166740,.F.); -#166740 = EDGE_CURVE('',#166650,#166713,#166741,.T.); -#166741 = SURFACE_CURVE('',#166742,(#166746,#166753),.PCURVE_S1.); -#166742 = LINE('',#166743,#166744); -#166743 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); -#166744 = VECTOR('',#166745,1.); -#166745 = DIRECTION('',(0.E+000,1.,0.E+000)); -#166746 = PCURVE('',#166660,#166747); -#166747 = DEFINITIONAL_REPRESENTATION('',(#166748),#166752); -#166748 = LINE('',#166749,#166750); -#166749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166750 = VECTOR('',#166751,1.); -#166751 = DIRECTION('',(1.,0.E+000)); -#166752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166753 = PCURVE('',#166754,#166759); -#166754 = PLANE('',#166755); -#166755 = AXIS2_PLACEMENT_3D('',#166756,#166757,#166758); -#166756 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); -#166757 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166758 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166759 = DEFINITIONAL_REPRESENTATION('',(#166760),#166764); -#166760 = LINE('',#166761,#166762); -#166761 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166762 = VECTOR('',#166763,1.); -#166763 = DIRECTION('',(0.E+000,1.)); -#166764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166765 = ADVANCED_FACE('',(#166766),#166728,.T.); -#166766 = FACE_BOUND('',#166767,.T.); -#166767 = EDGE_LOOP('',(#166768,#166769,#166792,#166820)); -#166768 = ORIENTED_EDGE('',*,*,#166712,.T.); -#166769 = ORIENTED_EDGE('',*,*,#166770,.T.); -#166770 = EDGE_CURVE('',#166685,#166771,#166773,.T.); -#166771 = VERTEX_POINT('',#166772); -#166772 = CARTESIAN_POINT('',(2.2352,1.27,0.99)); -#166773 = SURFACE_CURVE('',#166774,(#166778,#166785),.PCURVE_S1.); -#166774 = LINE('',#166775,#166776); -#166775 = CARTESIAN_POINT('',(-2.2352,1.27,0.99)); -#166776 = VECTOR('',#166777,1.); -#166777 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166778 = PCURVE('',#166728,#166779); -#166779 = DEFINITIONAL_REPRESENTATION('',(#166780),#166784); -#166780 = LINE('',#166781,#166782); -#166781 = CARTESIAN_POINT('',(0.E+000,-0.99)); -#166782 = VECTOR('',#166783,1.); -#166783 = DIRECTION('',(1.,0.E+000)); -#166784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166785 = PCURVE('',#166700,#166786); -#166786 = DEFINITIONAL_REPRESENTATION('',(#166787),#166791); -#166787 = LINE('',#166788,#166789); -#166788 = CARTESIAN_POINT('',(0.E+000,2.54)); -#166789 = VECTOR('',#166790,1.); -#166790 = DIRECTION('',(1.,0.E+000)); -#166791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166792 = ORIENTED_EDGE('',*,*,#166793,.F.); -#166793 = EDGE_CURVE('',#166794,#166771,#166796,.T.); -#166794 = VERTEX_POINT('',#166795); -#166795 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); -#166796 = SURFACE_CURVE('',#166797,(#166801,#166808),.PCURVE_S1.); -#166797 = LINE('',#166798,#166799); -#166798 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); -#166799 = VECTOR('',#166800,1.); -#166800 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166801 = PCURVE('',#166728,#166802); -#166802 = DEFINITIONAL_REPRESENTATION('',(#166803),#166807); -#166803 = LINE('',#166804,#166805); -#166804 = CARTESIAN_POINT('',(4.4704,0.E+000)); -#166805 = VECTOR('',#166806,1.); -#166806 = DIRECTION('',(0.E+000,-1.)); -#166807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166808 = PCURVE('',#166809,#166814); -#166809 = PLANE('',#166810); -#166810 = AXIS2_PLACEMENT_3D('',#166811,#166812,#166813); -#166811 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); -#166812 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166813 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166814 = DEFINITIONAL_REPRESENTATION('',(#166815),#166819); -#166815 = LINE('',#166816,#166817); -#166816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166817 = VECTOR('',#166818,1.); -#166818 = DIRECTION('',(0.E+000,-1.)); -#166819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166820 = ORIENTED_EDGE('',*,*,#166821,.F.); -#166821 = EDGE_CURVE('',#166713,#166794,#166822,.T.); -#166822 = SURFACE_CURVE('',#166823,(#166827,#166834),.PCURVE_S1.); -#166823 = LINE('',#166824,#166825); -#166824 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); -#166825 = VECTOR('',#166826,1.); -#166826 = DIRECTION('',(1.,0.E+000,0.E+000)); -#166827 = PCURVE('',#166728,#166828); -#166828 = DEFINITIONAL_REPRESENTATION('',(#166829),#166833); -#166829 = LINE('',#166830,#166831); -#166830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166831 = VECTOR('',#166832,1.); -#166832 = DIRECTION('',(1.,0.E+000)); -#166833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166834 = PCURVE('',#166754,#166835); -#166835 = DEFINITIONAL_REPRESENTATION('',(#166836),#166840); -#166836 = LINE('',#166837,#166838); -#166837 = CARTESIAN_POINT('',(0.E+000,2.54)); -#166838 = VECTOR('',#166839,1.); -#166839 = DIRECTION('',(1.,0.E+000)); -#166840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166841 = ADVANCED_FACE('',(#166842),#166809,.T.); -#166842 = FACE_BOUND('',#166843,.T.); -#166843 = EDGE_LOOP('',(#166844,#166845,#166868,#166891)); -#166844 = ORIENTED_EDGE('',*,*,#166793,.T.); -#166845 = ORIENTED_EDGE('',*,*,#166846,.T.); -#166846 = EDGE_CURVE('',#166771,#166847,#166849,.T.); -#166847 = VERTEX_POINT('',#166848); -#166848 = CARTESIAN_POINT('',(2.2352,-1.27,0.99)); -#166849 = SURFACE_CURVE('',#166850,(#166854,#166861),.PCURVE_S1.); -#166850 = LINE('',#166851,#166852); -#166851 = CARTESIAN_POINT('',(2.2352,1.27,0.99)); -#166852 = VECTOR('',#166853,1.); -#166853 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166854 = PCURVE('',#166809,#166855); -#166855 = DEFINITIONAL_REPRESENTATION('',(#166856),#166860); -#166856 = LINE('',#166857,#166858); -#166857 = CARTESIAN_POINT('',(0.E+000,-0.99)); -#166858 = VECTOR('',#166859,1.); -#166859 = DIRECTION('',(1.,0.E+000)); -#166860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166861 = PCURVE('',#166700,#166862); -#166862 = DEFINITIONAL_REPRESENTATION('',(#166863),#166867); -#166863 = LINE('',#166864,#166865); -#166864 = CARTESIAN_POINT('',(4.4704,2.54)); -#166865 = VECTOR('',#166866,1.); -#166866 = DIRECTION('',(0.E+000,-1.)); -#166867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166868 = ORIENTED_EDGE('',*,*,#166869,.F.); -#166869 = EDGE_CURVE('',#166870,#166847,#166872,.T.); -#166870 = VERTEX_POINT('',#166871); -#166871 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); -#166872 = SURFACE_CURVE('',#166873,(#166877,#166884),.PCURVE_S1.); -#166873 = LINE('',#166874,#166875); -#166874 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); -#166875 = VECTOR('',#166876,1.); -#166876 = DIRECTION('',(0.E+000,0.E+000,1.)); -#166877 = PCURVE('',#166809,#166878); -#166878 = DEFINITIONAL_REPRESENTATION('',(#166879),#166883); -#166879 = LINE('',#166880,#166881); -#166880 = CARTESIAN_POINT('',(2.54,0.E+000)); -#166881 = VECTOR('',#166882,1.); -#166882 = DIRECTION('',(0.E+000,-1.)); -#166883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166884 = PCURVE('',#166672,#166885); -#166885 = DEFINITIONAL_REPRESENTATION('',(#166886),#166890); -#166886 = LINE('',#166887,#166888); -#166887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166888 = VECTOR('',#166889,1.); -#166889 = DIRECTION('',(0.E+000,-1.)); -#166890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166891 = ORIENTED_EDGE('',*,*,#166892,.F.); -#166892 = EDGE_CURVE('',#166794,#166870,#166893,.T.); -#166893 = SURFACE_CURVE('',#166894,(#166898,#166905),.PCURVE_S1.); -#166894 = LINE('',#166895,#166896); -#166895 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); -#166896 = VECTOR('',#166897,1.); -#166897 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#166898 = PCURVE('',#166809,#166899); -#166899 = DEFINITIONAL_REPRESENTATION('',(#166900),#166904); -#166900 = LINE('',#166901,#166902); -#166901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166902 = VECTOR('',#166903,1.); -#166903 = DIRECTION('',(1.,0.E+000)); -#166904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166905 = PCURVE('',#166754,#166906); -#166906 = DEFINITIONAL_REPRESENTATION('',(#166907),#166911); -#166907 = LINE('',#166908,#166909); -#166908 = CARTESIAN_POINT('',(4.4704,2.54)); -#166909 = VECTOR('',#166910,1.); -#166910 = DIRECTION('',(0.E+000,-1.)); -#166911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166912 = ADVANCED_FACE('',(#166913),#166672,.T.); -#166913 = FACE_BOUND('',#166914,.T.); -#166914 = EDGE_LOOP('',(#166915,#166916,#166937,#166938)); -#166915 = ORIENTED_EDGE('',*,*,#166869,.T.); -#166916 = ORIENTED_EDGE('',*,*,#166917,.T.); -#166917 = EDGE_CURVE('',#166847,#166652,#166918,.T.); -#166918 = SURFACE_CURVE('',#166919,(#166923,#166930),.PCURVE_S1.); -#166919 = LINE('',#166920,#166921); -#166920 = CARTESIAN_POINT('',(2.2352,-1.27,0.99)); -#166921 = VECTOR('',#166922,1.); -#166922 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166923 = PCURVE('',#166672,#166924); -#166924 = DEFINITIONAL_REPRESENTATION('',(#166925),#166929); -#166925 = LINE('',#166926,#166927); -#166926 = CARTESIAN_POINT('',(0.E+000,-0.99)); -#166927 = VECTOR('',#166928,1.); -#166928 = DIRECTION('',(1.,0.E+000)); -#166929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166930 = PCURVE('',#166700,#166931); -#166931 = DEFINITIONAL_REPRESENTATION('',(#166932),#166936); -#166932 = LINE('',#166933,#166934); -#166933 = CARTESIAN_POINT('',(4.4704,0.E+000)); -#166934 = VECTOR('',#166935,1.); -#166935 = DIRECTION('',(-1.,0.E+000)); -#166936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166937 = ORIENTED_EDGE('',*,*,#166649,.F.); -#166938 = ORIENTED_EDGE('',*,*,#166939,.F.); -#166939 = EDGE_CURVE('',#166870,#166650,#166940,.T.); -#166940 = SURFACE_CURVE('',#166941,(#166945,#166952),.PCURVE_S1.); -#166941 = LINE('',#166942,#166943); -#166942 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); -#166943 = VECTOR('',#166944,1.); -#166944 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#166945 = PCURVE('',#166672,#166946); -#166946 = DEFINITIONAL_REPRESENTATION('',(#166947),#166951); -#166947 = LINE('',#166948,#166949); -#166948 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#166949 = VECTOR('',#166950,1.); -#166950 = DIRECTION('',(1.,0.E+000)); -#166951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166952 = PCURVE('',#166754,#166953); -#166953 = DEFINITIONAL_REPRESENTATION('',(#166954),#166958); -#166954 = LINE('',#166955,#166956); -#166955 = CARTESIAN_POINT('',(4.4704,0.E+000)); -#166956 = VECTOR('',#166957,1.); -#166957 = DIRECTION('',(-1.,0.E+000)); -#166958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#166959 = ADVANCED_FACE('',(#166960),#166754,.F.); -#166960 = FACE_BOUND('',#166961,.T.); -#166961 = EDGE_LOOP('',(#166962,#166963,#166964,#166965)); -#166962 = ORIENTED_EDGE('',*,*,#166740,.T.); -#166963 = ORIENTED_EDGE('',*,*,#166821,.T.); -#166964 = ORIENTED_EDGE('',*,*,#166892,.T.); -#166965 = ORIENTED_EDGE('',*,*,#166939,.T.); -#166966 = ADVANCED_FACE('',(#166967),#166700,.T.); -#166967 = FACE_BOUND('',#166968,.F.); -#166968 = EDGE_LOOP('',(#166969,#166970,#166971,#166972)); -#166969 = ORIENTED_EDGE('',*,*,#166684,.T.); -#166970 = ORIENTED_EDGE('',*,*,#166770,.T.); -#166971 = ORIENTED_EDGE('',*,*,#166846,.T.); -#166972 = ORIENTED_EDGE('',*,*,#166917,.T.); -#166973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#166977)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#166974,#166975,#166976)) +#169034 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#169035),#169365); +#169035 = MANIFOLD_SOLID_BREP('',#169036); +#169036 = CLOSED_SHELL('',(#169037,#169157,#169233,#169304,#169351, + #169358)); +#169037 = ADVANCED_FACE('',(#169038),#169052,.T.); +#169038 = FACE_BOUND('',#169039,.T.); +#169039 = EDGE_LOOP('',(#169040,#169075,#169103,#169131)); +#169040 = ORIENTED_EDGE('',*,*,#169041,.T.); +#169041 = EDGE_CURVE('',#169042,#169044,#169046,.T.); +#169042 = VERTEX_POINT('',#169043); +#169043 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); +#169044 = VERTEX_POINT('',#169045); +#169045 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); +#169046 = SURFACE_CURVE('',#169047,(#169051,#169063),.PCURVE_S1.); +#169047 = LINE('',#169048,#169049); +#169048 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); +#169049 = VECTOR('',#169050,1.); +#169050 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169051 = PCURVE('',#169052,#169057); +#169052 = PLANE('',#169053); +#169053 = AXIS2_PLACEMENT_3D('',#169054,#169055,#169056); +#169054 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); +#169055 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169056 = DIRECTION('',(0.E+000,1.,0.E+000)); +#169057 = DEFINITIONAL_REPRESENTATION('',(#169058),#169062); +#169058 = LINE('',#169059,#169060); +#169059 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169060 = VECTOR('',#169061,1.); +#169061 = DIRECTION('',(0.E+000,-1.)); +#169062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169063 = PCURVE('',#169064,#169069); +#169064 = PLANE('',#169065); +#169065 = AXIS2_PLACEMENT_3D('',#169066,#169067,#169068); +#169066 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); +#169067 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#169068 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169069 = DEFINITIONAL_REPRESENTATION('',(#169070),#169074); +#169070 = LINE('',#169071,#169072); +#169071 = CARTESIAN_POINT('',(4.4704,0.E+000)); +#169072 = VECTOR('',#169073,1.); +#169073 = DIRECTION('',(0.E+000,-1.)); +#169074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169075 = ORIENTED_EDGE('',*,*,#169076,.T.); +#169076 = EDGE_CURVE('',#169044,#169077,#169079,.T.); +#169077 = VERTEX_POINT('',#169078); +#169078 = CARTESIAN_POINT('',(-2.2352,1.27,0.99)); +#169079 = SURFACE_CURVE('',#169080,(#169084,#169091),.PCURVE_S1.); +#169080 = LINE('',#169081,#169082); +#169081 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); +#169082 = VECTOR('',#169083,1.); +#169083 = DIRECTION('',(0.E+000,1.,0.E+000)); +#169084 = PCURVE('',#169052,#169085); +#169085 = DEFINITIONAL_REPRESENTATION('',(#169086),#169090); +#169086 = LINE('',#169087,#169088); +#169087 = CARTESIAN_POINT('',(0.E+000,-0.99)); +#169088 = VECTOR('',#169089,1.); +#169089 = DIRECTION('',(1.,0.E+000)); +#169090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169091 = PCURVE('',#169092,#169097); +#169092 = PLANE('',#169093); +#169093 = AXIS2_PLACEMENT_3D('',#169094,#169095,#169096); +#169094 = CARTESIAN_POINT('',(-2.2352,-1.27,0.99)); +#169095 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169096 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169097 = DEFINITIONAL_REPRESENTATION('',(#169098),#169102); +#169098 = LINE('',#169099,#169100); +#169099 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169100 = VECTOR('',#169101,1.); +#169101 = DIRECTION('',(0.E+000,1.)); +#169102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169103 = ORIENTED_EDGE('',*,*,#169104,.F.); +#169104 = EDGE_CURVE('',#169105,#169077,#169107,.T.); +#169105 = VERTEX_POINT('',#169106); +#169106 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); +#169107 = SURFACE_CURVE('',#169108,(#169112,#169119),.PCURVE_S1.); +#169108 = LINE('',#169109,#169110); +#169109 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); +#169110 = VECTOR('',#169111,1.); +#169111 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169112 = PCURVE('',#169052,#169113); +#169113 = DEFINITIONAL_REPRESENTATION('',(#169114),#169118); +#169114 = LINE('',#169115,#169116); +#169115 = CARTESIAN_POINT('',(2.54,0.E+000)); +#169116 = VECTOR('',#169117,1.); +#169117 = DIRECTION('',(0.E+000,-1.)); +#169118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169119 = PCURVE('',#169120,#169125); +#169120 = PLANE('',#169121); +#169121 = AXIS2_PLACEMENT_3D('',#169122,#169123,#169124); +#169122 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); +#169123 = DIRECTION('',(0.E+000,1.,0.E+000)); +#169124 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169125 = DEFINITIONAL_REPRESENTATION('',(#169126),#169130); +#169126 = LINE('',#169127,#169128); +#169127 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169128 = VECTOR('',#169129,1.); +#169129 = DIRECTION('',(0.E+000,-1.)); +#169130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169131 = ORIENTED_EDGE('',*,*,#169132,.F.); +#169132 = EDGE_CURVE('',#169042,#169105,#169133,.T.); +#169133 = SURFACE_CURVE('',#169134,(#169138,#169145),.PCURVE_S1.); +#169134 = LINE('',#169135,#169136); +#169135 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); +#169136 = VECTOR('',#169137,1.); +#169137 = DIRECTION('',(0.E+000,1.,0.E+000)); +#169138 = PCURVE('',#169052,#169139); +#169139 = DEFINITIONAL_REPRESENTATION('',(#169140),#169144); +#169140 = LINE('',#169141,#169142); +#169141 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169142 = VECTOR('',#169143,1.); +#169143 = DIRECTION('',(1.,0.E+000)); +#169144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169145 = PCURVE('',#169146,#169151); +#169146 = PLANE('',#169147); +#169147 = AXIS2_PLACEMENT_3D('',#169148,#169149,#169150); +#169148 = CARTESIAN_POINT('',(-2.2352,-1.27,0.E+000)); +#169149 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169150 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169151 = DEFINITIONAL_REPRESENTATION('',(#169152),#169156); +#169152 = LINE('',#169153,#169154); +#169153 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169154 = VECTOR('',#169155,1.); +#169155 = DIRECTION('',(0.E+000,1.)); +#169156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169157 = ADVANCED_FACE('',(#169158),#169120,.T.); +#169158 = FACE_BOUND('',#169159,.T.); +#169159 = EDGE_LOOP('',(#169160,#169161,#169184,#169212)); +#169160 = ORIENTED_EDGE('',*,*,#169104,.T.); +#169161 = ORIENTED_EDGE('',*,*,#169162,.T.); +#169162 = EDGE_CURVE('',#169077,#169163,#169165,.T.); +#169163 = VERTEX_POINT('',#169164); +#169164 = CARTESIAN_POINT('',(2.2352,1.27,0.99)); +#169165 = SURFACE_CURVE('',#169166,(#169170,#169177),.PCURVE_S1.); +#169166 = LINE('',#169167,#169168); +#169167 = CARTESIAN_POINT('',(-2.2352,1.27,0.99)); +#169168 = VECTOR('',#169169,1.); +#169169 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169170 = PCURVE('',#169120,#169171); +#169171 = DEFINITIONAL_REPRESENTATION('',(#169172),#169176); +#169172 = LINE('',#169173,#169174); +#169173 = CARTESIAN_POINT('',(0.E+000,-0.99)); +#169174 = VECTOR('',#169175,1.); +#169175 = DIRECTION('',(1.,0.E+000)); +#169176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169177 = PCURVE('',#169092,#169178); +#169178 = DEFINITIONAL_REPRESENTATION('',(#169179),#169183); +#169179 = LINE('',#169180,#169181); +#169180 = CARTESIAN_POINT('',(0.E+000,2.54)); +#169181 = VECTOR('',#169182,1.); +#169182 = DIRECTION('',(1.,0.E+000)); +#169183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169184 = ORIENTED_EDGE('',*,*,#169185,.F.); +#169185 = EDGE_CURVE('',#169186,#169163,#169188,.T.); +#169186 = VERTEX_POINT('',#169187); +#169187 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); +#169188 = SURFACE_CURVE('',#169189,(#169193,#169200),.PCURVE_S1.); +#169189 = LINE('',#169190,#169191); +#169190 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); +#169191 = VECTOR('',#169192,1.); +#169192 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169193 = PCURVE('',#169120,#169194); +#169194 = DEFINITIONAL_REPRESENTATION('',(#169195),#169199); +#169195 = LINE('',#169196,#169197); +#169196 = CARTESIAN_POINT('',(4.4704,0.E+000)); +#169197 = VECTOR('',#169198,1.); +#169198 = DIRECTION('',(0.E+000,-1.)); +#169199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169200 = PCURVE('',#169201,#169206); +#169201 = PLANE('',#169202); +#169202 = AXIS2_PLACEMENT_3D('',#169203,#169204,#169205); +#169203 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); +#169204 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169205 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#169206 = DEFINITIONAL_REPRESENTATION('',(#169207),#169211); +#169207 = LINE('',#169208,#169209); +#169208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169209 = VECTOR('',#169210,1.); +#169210 = DIRECTION('',(0.E+000,-1.)); +#169211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169212 = ORIENTED_EDGE('',*,*,#169213,.F.); +#169213 = EDGE_CURVE('',#169105,#169186,#169214,.T.); +#169214 = SURFACE_CURVE('',#169215,(#169219,#169226),.PCURVE_S1.); +#169215 = LINE('',#169216,#169217); +#169216 = CARTESIAN_POINT('',(-2.2352,1.27,0.E+000)); +#169217 = VECTOR('',#169218,1.); +#169218 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169219 = PCURVE('',#169120,#169220); +#169220 = DEFINITIONAL_REPRESENTATION('',(#169221),#169225); +#169221 = LINE('',#169222,#169223); +#169222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169223 = VECTOR('',#169224,1.); +#169224 = DIRECTION('',(1.,0.E+000)); +#169225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169226 = PCURVE('',#169146,#169227); +#169227 = DEFINITIONAL_REPRESENTATION('',(#169228),#169232); +#169228 = LINE('',#169229,#169230); +#169229 = CARTESIAN_POINT('',(0.E+000,2.54)); +#169230 = VECTOR('',#169231,1.); +#169231 = DIRECTION('',(1.,0.E+000)); +#169232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169233 = ADVANCED_FACE('',(#169234),#169201,.T.); +#169234 = FACE_BOUND('',#169235,.T.); +#169235 = EDGE_LOOP('',(#169236,#169237,#169260,#169283)); +#169236 = ORIENTED_EDGE('',*,*,#169185,.T.); +#169237 = ORIENTED_EDGE('',*,*,#169238,.T.); +#169238 = EDGE_CURVE('',#169163,#169239,#169241,.T.); +#169239 = VERTEX_POINT('',#169240); +#169240 = CARTESIAN_POINT('',(2.2352,-1.27,0.99)); +#169241 = SURFACE_CURVE('',#169242,(#169246,#169253),.PCURVE_S1.); +#169242 = LINE('',#169243,#169244); +#169243 = CARTESIAN_POINT('',(2.2352,1.27,0.99)); +#169244 = VECTOR('',#169245,1.); +#169245 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#169246 = PCURVE('',#169201,#169247); +#169247 = DEFINITIONAL_REPRESENTATION('',(#169248),#169252); +#169248 = LINE('',#169249,#169250); +#169249 = CARTESIAN_POINT('',(0.E+000,-0.99)); +#169250 = VECTOR('',#169251,1.); +#169251 = DIRECTION('',(1.,0.E+000)); +#169252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169253 = PCURVE('',#169092,#169254); +#169254 = DEFINITIONAL_REPRESENTATION('',(#169255),#169259); +#169255 = LINE('',#169256,#169257); +#169256 = CARTESIAN_POINT('',(4.4704,2.54)); +#169257 = VECTOR('',#169258,1.); +#169258 = DIRECTION('',(0.E+000,-1.)); +#169259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169260 = ORIENTED_EDGE('',*,*,#169261,.F.); +#169261 = EDGE_CURVE('',#169262,#169239,#169264,.T.); +#169262 = VERTEX_POINT('',#169263); +#169263 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); +#169264 = SURFACE_CURVE('',#169265,(#169269,#169276),.PCURVE_S1.); +#169265 = LINE('',#169266,#169267); +#169266 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); +#169267 = VECTOR('',#169268,1.); +#169268 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169269 = PCURVE('',#169201,#169270); +#169270 = DEFINITIONAL_REPRESENTATION('',(#169271),#169275); +#169271 = LINE('',#169272,#169273); +#169272 = CARTESIAN_POINT('',(2.54,0.E+000)); +#169273 = VECTOR('',#169274,1.); +#169274 = DIRECTION('',(0.E+000,-1.)); +#169275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169276 = PCURVE('',#169064,#169277); +#169277 = DEFINITIONAL_REPRESENTATION('',(#169278),#169282); +#169278 = LINE('',#169279,#169280); +#169279 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169280 = VECTOR('',#169281,1.); +#169281 = DIRECTION('',(0.E+000,-1.)); +#169282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169283 = ORIENTED_EDGE('',*,*,#169284,.F.); +#169284 = EDGE_CURVE('',#169186,#169262,#169285,.T.); +#169285 = SURFACE_CURVE('',#169286,(#169290,#169297),.PCURVE_S1.); +#169286 = LINE('',#169287,#169288); +#169287 = CARTESIAN_POINT('',(2.2352,1.27,0.E+000)); +#169288 = VECTOR('',#169289,1.); +#169289 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#169290 = PCURVE('',#169201,#169291); +#169291 = DEFINITIONAL_REPRESENTATION('',(#169292),#169296); +#169292 = LINE('',#169293,#169294); +#169293 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169294 = VECTOR('',#169295,1.); +#169295 = DIRECTION('',(1.,0.E+000)); +#169296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169297 = PCURVE('',#169146,#169298); +#169298 = DEFINITIONAL_REPRESENTATION('',(#169299),#169303); +#169299 = LINE('',#169300,#169301); +#169300 = CARTESIAN_POINT('',(4.4704,2.54)); +#169301 = VECTOR('',#169302,1.); +#169302 = DIRECTION('',(0.E+000,-1.)); +#169303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169304 = ADVANCED_FACE('',(#169305),#169064,.T.); +#169305 = FACE_BOUND('',#169306,.T.); +#169306 = EDGE_LOOP('',(#169307,#169308,#169329,#169330)); +#169307 = ORIENTED_EDGE('',*,*,#169261,.T.); +#169308 = ORIENTED_EDGE('',*,*,#169309,.T.); +#169309 = EDGE_CURVE('',#169239,#169044,#169310,.T.); +#169310 = SURFACE_CURVE('',#169311,(#169315,#169322),.PCURVE_S1.); +#169311 = LINE('',#169312,#169313); +#169312 = CARTESIAN_POINT('',(2.2352,-1.27,0.99)); +#169313 = VECTOR('',#169314,1.); +#169314 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169315 = PCURVE('',#169064,#169316); +#169316 = DEFINITIONAL_REPRESENTATION('',(#169317),#169321); +#169317 = LINE('',#169318,#169319); +#169318 = CARTESIAN_POINT('',(0.E+000,-0.99)); +#169319 = VECTOR('',#169320,1.); +#169320 = DIRECTION('',(1.,0.E+000)); +#169321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169322 = PCURVE('',#169092,#169323); +#169323 = DEFINITIONAL_REPRESENTATION('',(#169324),#169328); +#169324 = LINE('',#169325,#169326); +#169325 = CARTESIAN_POINT('',(4.4704,0.E+000)); +#169326 = VECTOR('',#169327,1.); +#169327 = DIRECTION('',(-1.,0.E+000)); +#169328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169329 = ORIENTED_EDGE('',*,*,#169041,.F.); +#169330 = ORIENTED_EDGE('',*,*,#169331,.F.); +#169331 = EDGE_CURVE('',#169262,#169042,#169332,.T.); +#169332 = SURFACE_CURVE('',#169333,(#169337,#169344),.PCURVE_S1.); +#169333 = LINE('',#169334,#169335); +#169334 = CARTESIAN_POINT('',(2.2352,-1.27,0.E+000)); +#169335 = VECTOR('',#169336,1.); +#169336 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169337 = PCURVE('',#169064,#169338); +#169338 = DEFINITIONAL_REPRESENTATION('',(#169339),#169343); +#169339 = LINE('',#169340,#169341); +#169340 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169341 = VECTOR('',#169342,1.); +#169342 = DIRECTION('',(1.,0.E+000)); +#169343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169344 = PCURVE('',#169146,#169345); +#169345 = DEFINITIONAL_REPRESENTATION('',(#169346),#169350); +#169346 = LINE('',#169347,#169348); +#169347 = CARTESIAN_POINT('',(4.4704,0.E+000)); +#169348 = VECTOR('',#169349,1.); +#169349 = DIRECTION('',(-1.,0.E+000)); +#169350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169351 = ADVANCED_FACE('',(#169352),#169146,.F.); +#169352 = FACE_BOUND('',#169353,.T.); +#169353 = EDGE_LOOP('',(#169354,#169355,#169356,#169357)); +#169354 = ORIENTED_EDGE('',*,*,#169132,.T.); +#169355 = ORIENTED_EDGE('',*,*,#169213,.T.); +#169356 = ORIENTED_EDGE('',*,*,#169284,.T.); +#169357 = ORIENTED_EDGE('',*,*,#169331,.T.); +#169358 = ADVANCED_FACE('',(#169359),#169092,.T.); +#169359 = FACE_BOUND('',#169360,.F.); +#169360 = EDGE_LOOP('',(#169361,#169362,#169363,#169364)); +#169361 = ORIENTED_EDGE('',*,*,#169076,.T.); +#169362 = ORIENTED_EDGE('',*,*,#169162,.T.); +#169363 = ORIENTED_EDGE('',*,*,#169238,.T.); +#169364 = ORIENTED_EDGE('',*,*,#169309,.T.); +#169365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169369)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169366,#169367,#169368)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#166974 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#166975 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#166976 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#166977 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#166974, +#169366 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169367 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169368 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169369 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169366, 'distance_accuracy_value','confusion accuracy'); -#166978 = SHAPE_DEFINITION_REPRESENTATION(#166979,#166642); -#166979 = PRODUCT_DEFINITION_SHAPE('','',#166980); -#166980 = PRODUCT_DEFINITION('design','',#166981,#166984); -#166981 = PRODUCT_DEFINITION_FORMATION('','',#166982); -#166982 = PRODUCT('Extruded','Extruded','',(#166983)); -#166983 = PRODUCT_CONTEXT('',#2,'mechanical'); -#166984 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#166985 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166986,#166988); -#166986 = ( REPRESENTATION_RELATIONSHIP('','',#166642,#166632) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166987) +#169370 = SHAPE_DEFINITION_REPRESENTATION(#169371,#169034); +#169371 = PRODUCT_DEFINITION_SHAPE('','',#169372); +#169372 = PRODUCT_DEFINITION('design','',#169373,#169376); +#169373 = PRODUCT_DEFINITION_FORMATION('','',#169374); +#169374 = PRODUCT('Extruded','Extruded','',(#169375)); +#169375 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169376 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169377 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169378,#169380); +#169378 = ( REPRESENTATION_RELATIONSHIP('','',#169034,#169024) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169379) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166987 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166633); -#166988 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166989); -#166989 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('291','=>[0:1:1:2]','',#166627, - #166980,$); -#166990 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166982)); -#166991 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#166992,#166994); -#166992 = ( REPRESENTATION_RELATIONSHIP('','',#166632,#166231) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#166993) +#169379 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169025); +#169380 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169381); +#169381 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('392','=>[0:1:1:2]','',#169019, + #169372,$); +#169382 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169374)); +#169383 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169384,#169386); +#169384 = ( REPRESENTATION_RELATIONSHIP('','',#169024,#168623) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169385) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#166993 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166236); -#166994 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #166995); -#166995 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('292','=>[0:1:1:95]','',#166226 - ,#166627,$); -#166996 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166629)); -#166997 = SHAPE_DEFINITION_REPRESENTATION(#166998,#167004); -#166998 = PRODUCT_DEFINITION_SHAPE('','',#166999); -#166999 = PRODUCT_DEFINITION('design','',#167000,#167003); -#167000 = PRODUCT_DEFINITION_FORMATION('','',#167001); -#167001 = PRODUCT('961681136','961681136','',(#167002)); -#167002 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167003 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167004 = SHAPE_REPRESENTATION('',(#11,#167005),#167009); -#167005 = AXIS2_PLACEMENT_3D('',#167006,#167007,#167008); -#167006 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167007 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167008 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167013)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167010,#167011,#167012)) +#169385 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168628); +#169386 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169387); +#169387 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('393','=>[0:1:1:95]','',#168618 + ,#169019,$); +#169388 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169021)); +#169389 = SHAPE_DEFINITION_REPRESENTATION(#169390,#169396); +#169390 = PRODUCT_DEFINITION_SHAPE('','',#169391); +#169391 = PRODUCT_DEFINITION('design','',#169392,#169395); +#169392 = PRODUCT_DEFINITION_FORMATION('','',#169393); +#169393 = PRODUCT('549043680','549043680','',(#169394)); +#169394 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169395 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169396 = SHAPE_REPRESENTATION('',(#11,#169397),#169401); +#169397 = AXIS2_PLACEMENT_3D('',#169398,#169399,#169400); +#169398 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169399 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169400 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169405)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169402,#169403,#169404)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167010 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167011 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167012 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167013 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167010, +#169402 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169403 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169404 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169405 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169402, 'distance_accuracy_value','confusion accuracy'); -#167014 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#167015),#167119); -#167015 = MANIFOLD_SOLID_BREP('',#167016); -#167016 = CLOSED_SHELL('',(#167017,#167111,#167115)); -#167017 = ADVANCED_FACE('',(#167018),#167032,.T.); -#167018 = FACE_BOUND('',#167019,.T.); -#167019 = EDGE_LOOP('',(#167020,#167050,#167080,#167081)); -#167020 = ORIENTED_EDGE('',*,*,#167021,.F.); -#167021 = EDGE_CURVE('',#167022,#167024,#167026,.T.); -#167022 = VERTEX_POINT('',#167023); -#167023 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); -#167024 = VERTEX_POINT('',#167025); -#167025 = CARTESIAN_POINT('',(0.3,0.E+000,1.)); -#167026 = SEAM_CURVE('',#167027,(#167031,#167043),.PCURVE_S1.); -#167027 = LINE('',#167028,#167029); -#167028 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); -#167029 = VECTOR('',#167030,1.); -#167030 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167031 = PCURVE('',#167032,#167037); -#167032 = CYLINDRICAL_SURFACE('',#167033,0.3); -#167033 = AXIS2_PLACEMENT_3D('',#167034,#167035,#167036); -#167034 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167035 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167036 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167037 = DEFINITIONAL_REPRESENTATION('',(#167038),#167042); -#167038 = LINE('',#167039,#167040); -#167039 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#167040 = VECTOR('',#167041,1.); -#167041 = DIRECTION('',(0.E+000,-1.)); -#167042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167043 = PCURVE('',#167032,#167044); -#167044 = DEFINITIONAL_REPRESENTATION('',(#167045),#167049); -#167045 = LINE('',#167046,#167047); -#167046 = CARTESIAN_POINT('',(-4.138911435803E-013,0.E+000)); -#167047 = VECTOR('',#167048,1.); -#167048 = DIRECTION('',(0.E+000,-1.)); -#167049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167050 = ORIENTED_EDGE('',*,*,#167051,.T.); -#167051 = EDGE_CURVE('',#167022,#167022,#167052,.T.); -#167052 = SURFACE_CURVE('',#167053,(#167058,#167064),.PCURVE_S1.); -#167053 = CIRCLE('',#167054,0.3); -#167054 = AXIS2_PLACEMENT_3D('',#167055,#167056,#167057); -#167055 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167056 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167057 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167058 = PCURVE('',#167032,#167059); -#167059 = DEFINITIONAL_REPRESENTATION('',(#167060),#167063); -#167060 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167061,#167062), +#169406 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#169407),#169511); +#169407 = MANIFOLD_SOLID_BREP('',#169408); +#169408 = CLOSED_SHELL('',(#169409,#169503,#169507)); +#169409 = ADVANCED_FACE('',(#169410),#169424,.T.); +#169410 = FACE_BOUND('',#169411,.T.); +#169411 = EDGE_LOOP('',(#169412,#169442,#169472,#169473)); +#169412 = ORIENTED_EDGE('',*,*,#169413,.F.); +#169413 = EDGE_CURVE('',#169414,#169416,#169418,.T.); +#169414 = VERTEX_POINT('',#169415); +#169415 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); +#169416 = VERTEX_POINT('',#169417); +#169417 = CARTESIAN_POINT('',(0.3,0.E+000,1.)); +#169418 = SEAM_CURVE('',#169419,(#169423,#169435),.PCURVE_S1.); +#169419 = LINE('',#169420,#169421); +#169420 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); +#169421 = VECTOR('',#169422,1.); +#169422 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169423 = PCURVE('',#169424,#169429); +#169424 = CYLINDRICAL_SURFACE('',#169425,0.3); +#169425 = AXIS2_PLACEMENT_3D('',#169426,#169427,#169428); +#169426 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169427 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169428 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169429 = DEFINITIONAL_REPRESENTATION('',(#169430),#169434); +#169430 = LINE('',#169431,#169432); +#169431 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#169432 = VECTOR('',#169433,1.); +#169433 = DIRECTION('',(0.E+000,-1.)); +#169434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169435 = PCURVE('',#169424,#169436); +#169436 = DEFINITIONAL_REPRESENTATION('',(#169437),#169441); +#169437 = LINE('',#169438,#169439); +#169438 = CARTESIAN_POINT('',(-4.138911435803E-013,0.E+000)); +#169439 = VECTOR('',#169440,1.); +#169440 = DIRECTION('',(0.E+000,-1.)); +#169441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169442 = ORIENTED_EDGE('',*,*,#169443,.T.); +#169443 = EDGE_CURVE('',#169414,#169414,#169444,.T.); +#169444 = SURFACE_CURVE('',#169445,(#169450,#169456),.PCURVE_S1.); +#169445 = CIRCLE('',#169446,0.3); +#169446 = AXIS2_PLACEMENT_3D('',#169447,#169448,#169449); +#169447 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169448 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169449 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169450 = PCURVE('',#169424,#169451); +#169451 = DEFINITIONAL_REPRESENTATION('',(#169452),#169455); +#169452 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#169453,#169454), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#167061 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#167062 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#169453 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#169454 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#167064 = PCURVE('',#167065,#167070); -#167065 = PLANE('',#167066); -#167066 = AXIS2_PLACEMENT_3D('',#167067,#167068,#167069); -#167067 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); -#167068 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167069 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167070 = DEFINITIONAL_REPRESENTATION('',(#167071),#167079); -#167071 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167072,#167073,#167074, - #167075,#167076,#167077,#167078),.UNSPECIFIED.,.F.,.F.) +#169456 = PCURVE('',#169457,#169462); +#169457 = PLANE('',#169458); +#169458 = AXIS2_PLACEMENT_3D('',#169459,#169460,#169461); +#169459 = CARTESIAN_POINT('',(0.3,0.E+000,0.E+000)); +#169460 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169461 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169462 = DEFINITIONAL_REPRESENTATION('',(#169463),#169471); +#169463 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#169464,#169465,#169466, + #169467,#169468,#169469,#169470),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#167072 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167073 = CARTESIAN_POINT('',(0.E+000,0.519615242271)); -#167074 = CARTESIAN_POINT('',(0.45,0.259807621135)); -#167075 = CARTESIAN_POINT('',(0.9,2.067031441844E-016)); -#167076 = CARTESIAN_POINT('',(0.45,-0.259807621135)); -#167077 = CARTESIAN_POINT('',(3.885780586188E-016,-0.519615242271)); -#167078 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167079 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167080 = ORIENTED_EDGE('',*,*,#167021,.T.); -#167081 = ORIENTED_EDGE('',*,*,#167082,.F.); -#167082 = EDGE_CURVE('',#167024,#167024,#167083,.T.); -#167083 = SURFACE_CURVE('',#167084,(#167089,#167095),.PCURVE_S1.); -#167084 = CIRCLE('',#167085,0.3); -#167085 = AXIS2_PLACEMENT_3D('',#167086,#167087,#167088); -#167086 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.)); -#167087 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167088 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167089 = PCURVE('',#167032,#167090); -#167090 = DEFINITIONAL_REPRESENTATION('',(#167091),#167094); -#167091 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#167092,#167093), +#169464 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169465 = CARTESIAN_POINT('',(0.E+000,0.519615242271)); +#169466 = CARTESIAN_POINT('',(0.45,0.259807621135)); +#169467 = CARTESIAN_POINT('',(0.9,2.067031441844E-016)); +#169468 = CARTESIAN_POINT('',(0.45,-0.259807621135)); +#169469 = CARTESIAN_POINT('',(3.885780586188E-016,-0.519615242271)); +#169470 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169472 = ORIENTED_EDGE('',*,*,#169413,.T.); +#169473 = ORIENTED_EDGE('',*,*,#169474,.F.); +#169474 = EDGE_CURVE('',#169416,#169416,#169475,.T.); +#169475 = SURFACE_CURVE('',#169476,(#169481,#169487),.PCURVE_S1.); +#169476 = CIRCLE('',#169477,0.3); +#169477 = AXIS2_PLACEMENT_3D('',#169478,#169479,#169480); +#169478 = CARTESIAN_POINT('',(0.E+000,0.E+000,1.)); +#169479 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169480 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169481 = PCURVE('',#169424,#169482); +#169482 = DEFINITIONAL_REPRESENTATION('',(#169483),#169486); +#169483 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#169484,#169485), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#167092 = CARTESIAN_POINT('',(6.28318530718,-1.)); -#167093 = CARTESIAN_POINT('',(0.E+000,-1.)); -#167094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#169484 = CARTESIAN_POINT('',(6.28318530718,-1.)); +#169485 = CARTESIAN_POINT('',(0.E+000,-1.)); +#169486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#167095 = PCURVE('',#167096,#167101); -#167096 = PLANE('',#167097); -#167097 = AXIS2_PLACEMENT_3D('',#167098,#167099,#167100); -#167098 = CARTESIAN_POINT('',(0.3,0.E+000,1.)); -#167099 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167100 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167101 = DEFINITIONAL_REPRESENTATION('',(#167102),#167110); -#167102 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#167103,#167104,#167105, - #167106,#167107,#167108,#167109),.UNSPECIFIED.,.F.,.F.) +#169487 = PCURVE('',#169488,#169493); +#169488 = PLANE('',#169489); +#169489 = AXIS2_PLACEMENT_3D('',#169490,#169491,#169492); +#169490 = CARTESIAN_POINT('',(0.3,0.E+000,1.)); +#169491 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169492 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169493 = DEFINITIONAL_REPRESENTATION('',(#169494),#169502); +#169494 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#169495,#169496,#169497, + #169498,#169499,#169500,#169501),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#167103 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167104 = CARTESIAN_POINT('',(0.E+000,0.519615242271)); -#167105 = CARTESIAN_POINT('',(0.45,0.259807621135)); -#167106 = CARTESIAN_POINT('',(0.9,2.067031441844E-016)); -#167107 = CARTESIAN_POINT('',(0.45,-0.259807621135)); -#167108 = CARTESIAN_POINT('',(3.885780586188E-016,-0.519615242271)); -#167109 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167111 = ADVANCED_FACE('',(#167112),#167065,.T.); -#167112 = FACE_BOUND('',#167113,.F.); -#167113 = EDGE_LOOP('',(#167114)); -#167114 = ORIENTED_EDGE('',*,*,#167051,.T.); -#167115 = ADVANCED_FACE('',(#167116),#167096,.F.); -#167116 = FACE_BOUND('',#167117,.T.); -#167117 = EDGE_LOOP('',(#167118)); -#167118 = ORIENTED_EDGE('',*,*,#167082,.T.); -#167119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167123)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167120,#167121,#167122)) +#169495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169496 = CARTESIAN_POINT('',(0.E+000,0.519615242271)); +#169497 = CARTESIAN_POINT('',(0.45,0.259807621135)); +#169498 = CARTESIAN_POINT('',(0.9,2.067031441844E-016)); +#169499 = CARTESIAN_POINT('',(0.45,-0.259807621135)); +#169500 = CARTESIAN_POINT('',(3.885780586188E-016,-0.519615242271)); +#169501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#169502 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169503 = ADVANCED_FACE('',(#169504),#169457,.T.); +#169504 = FACE_BOUND('',#169505,.F.); +#169505 = EDGE_LOOP('',(#169506)); +#169506 = ORIENTED_EDGE('',*,*,#169443,.T.); +#169507 = ADVANCED_FACE('',(#169508),#169488,.F.); +#169508 = FACE_BOUND('',#169509,.T.); +#169509 = EDGE_LOOP('',(#169510)); +#169510 = ORIENTED_EDGE('',*,*,#169474,.T.); +#169511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169515)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169512,#169513,#169514)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167120 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167121 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167122 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167123 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167120, +#169512 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169513 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169514 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169515 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169512, 'distance_accuracy_value','confusion accuracy'); -#167124 = SHAPE_DEFINITION_REPRESENTATION(#167125,#167014); -#167125 = PRODUCT_DEFINITION_SHAPE('','',#167126); -#167126 = PRODUCT_DEFINITION('design','',#167127,#167130); -#167127 = PRODUCT_DEFINITION_FORMATION('','',#167128); -#167128 = PRODUCT('Cylinder','Cylinder','',(#167129)); -#167129 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167130 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167131 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167132,#167134); -#167132 = ( REPRESENTATION_RELATIONSHIP('','',#167014,#167004) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167133) +#169516 = SHAPE_DEFINITION_REPRESENTATION(#169517,#169406); +#169517 = PRODUCT_DEFINITION_SHAPE('','',#169518); +#169518 = PRODUCT_DEFINITION('design','',#169519,#169522); +#169519 = PRODUCT_DEFINITION_FORMATION('','',#169520); +#169520 = PRODUCT('Cylinder','Cylinder','',(#169521)); +#169521 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169522 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169523 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169524,#169526); +#169524 = ( REPRESENTATION_RELATIONSHIP('','',#169406,#169396) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169525) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167133 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167005); -#167134 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167135); -#167135 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('293','=>[0:1:1:2]','',#166999, - #167126,$); -#167136 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167128)); -#167137 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167138,#167140); -#167138 = ( REPRESENTATION_RELATIONSHIP('','',#167004,#166231) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167139) +#169525 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169397); +#169526 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169527); +#169527 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('394','=>[0:1:1:2]','',#169391, + #169518,$); +#169528 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169520)); +#169529 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169530,#169532); +#169530 = ( REPRESENTATION_RELATIONSHIP('','',#169396,#168623) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169531) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167139 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166240); -#167140 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167141); -#167141 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('294','=>[0:1:1:97]','',#166226 - ,#166999,$); -#167142 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167001)); -#167143 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167144,#167146); -#167144 = ( REPRESENTATION_RELATIONSHIP('','',#167004,#166231) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167145) +#169531 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168632); +#169532 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169533); +#169533 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('395','=>[0:1:1:97]','',#168618 + ,#169391,$); +#169534 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169393)); +#169535 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169536,#169538); +#169536 = ( REPRESENTATION_RELATIONSHIP('','',#169396,#168623) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169537) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167145 = ITEM_DEFINED_TRANSFORMATION('','',#11,#166244); -#167146 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167147); -#167147 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('295','=>[0:1:1:97]','',#166226 - ,#166999,$); -#167148 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167149,#167151); -#167149 = ( REPRESENTATION_RELATIONSHIP('','',#166231,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167150) +#169537 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168636); +#169538 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169539); +#169539 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('396','=>[0:1:1:97]','',#168618 + ,#169391,$); +#169540 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169541,#169543); +#169541 = ( REPRESENTATION_RELATIONSHIP('','',#168623,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169542) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167150 = ITEM_DEFINED_TRANSFORMATION('','',#11,#263); -#167151 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167152); -#167152 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('296','=>[0:1:1:92]','',#5, - #166226,$); -#167153 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#166228)); -#167154 = SHAPE_DEFINITION_REPRESENTATION(#167155,#167161); -#167155 = PRODUCT_DEFINITION_SHAPE('','',#167156); -#167156 = PRODUCT_DEFINITION('design','',#167157,#167160); -#167157 = PRODUCT_DEFINITION_FORMATION('','',#167158); -#167158 = PRODUCT('C1','C1','',(#167159)); -#167159 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167160 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167161 = SHAPE_REPRESENTATION('',(#11,#167162),#167166); -#167162 = AXIS2_PLACEMENT_3D('',#167163,#167164,#167165); -#167163 = CARTESIAN_POINT('',(8.76308128,21.9710635,1.27E-002)); -#167164 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167165 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167170)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167167,#167168,#167169)) +#169542 = ITEM_DEFINED_TRANSFORMATION('','',#11,#263); +#169543 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169544); +#169544 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('397','=>[0:1:1:92]','',#5, + #168618,$); +#169545 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168620)); +#169546 = SHAPE_DEFINITION_REPRESENTATION(#169547,#169553); +#169547 = PRODUCT_DEFINITION_SHAPE('','',#169548); +#169548 = PRODUCT_DEFINITION('design','',#169549,#169552); +#169549 = PRODUCT_DEFINITION_FORMATION('','',#169550); +#169550 = PRODUCT('C1','C1','',(#169551)); +#169551 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169552 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169553 = SHAPE_REPRESENTATION('',(#11,#169554),#169558); +#169554 = AXIS2_PLACEMENT_3D('',#169555,#169556,#169557); +#169555 = CARTESIAN_POINT('',(8.76308128,21.9710635,1.27E-002)); +#169556 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169557 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169562)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169559,#169560,#169561)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167167 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167168 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167169 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167170 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#167167, +#169559 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169560 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169561 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169562 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-005),#169559, 'distance_accuracy_value','confusion accuracy'); -#167171 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167172,#167174); -#167172 = ( REPRESENTATION_RELATIONSHIP('','',#11881,#167161) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167173) +#169563 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169564,#169566); +#169564 = ( REPRESENTATION_RELATIONSHIP('','',#14273,#169553) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169565) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167173 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167162); -#167174 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167175); -#167175 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('297','=>[0:1:1:18]','',#167156 - ,#11876,$); -#167176 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167177,#167179); -#167177 = ( REPRESENTATION_RELATIONSHIP('','',#167161,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167178) +#169565 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169554); +#169566 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169567); +#169567 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('398','=>[0:1:1:18]','',#169548 + ,#14268,$); +#169568 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169569,#169571); +#169569 = ( REPRESENTATION_RELATIONSHIP('','',#169553,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169570) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167178 = ITEM_DEFINED_TRANSFORMATION('','',#11,#267); -#167179 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167180); -#167180 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('298','=>[0:1:1:99]','',#5, - #167156,$); -#167181 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167158)); -#167182 = SHAPE_DEFINITION_REPRESENTATION(#167183,#167189); -#167183 = PRODUCT_DEFINITION_SHAPE('','',#167184); -#167184 = PRODUCT_DEFINITION('design','',#167185,#167188); -#167185 = PRODUCT_DEFINITION_FORMATION('','',#167186); -#167186 = PRODUCT('R9','R9','',(#167187)); -#167187 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167188 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167189 = SHAPE_REPRESENTATION('',(#11,#167190),#167194); -#167190 = AXIS2_PLACEMENT_3D('',#167191,#167192,#167193); -#167191 = CARTESIAN_POINT('',(28.067,10.0289995,-1.27E-002)); -#167192 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167193 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167198)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167195,#167196,#167197)) +#169570 = ITEM_DEFINED_TRANSFORMATION('','',#11,#267); +#169571 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169572); +#169572 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('399','=>[0:1:1:99]','',#5, + #169548,$); +#169573 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169550)); +#169574 = SHAPE_DEFINITION_REPRESENTATION(#169575,#169581); +#169575 = PRODUCT_DEFINITION_SHAPE('','',#169576); +#169576 = PRODUCT_DEFINITION('design','',#169577,#169580); +#169577 = PRODUCT_DEFINITION_FORMATION('','',#169578); +#169578 = PRODUCT('R9','R9','',(#169579)); +#169579 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169580 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169581 = SHAPE_REPRESENTATION('',(#11,#169582),#169586); +#169582 = AXIS2_PLACEMENT_3D('',#169583,#169584,#169585); +#169583 = CARTESIAN_POINT('',(28.067,10.0289995,-1.27E-002)); +#169584 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169585 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169590)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169587,#169588,#169589)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167195 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167196 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167197 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167198 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167195, +#169587 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169588 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169589 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169590 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169587, 'distance_accuracy_value','confusion accuracy'); -#167199 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167200,#167202); -#167200 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#167189) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167201) +#169591 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169592,#169594); +#169592 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#169581) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169593) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167201 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167190); -#167202 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167203); -#167203 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('299','=>[0:1:1:7]','',#167184, - #7462,$); -#167204 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167205,#167207); -#167205 = ( REPRESENTATION_RELATIONSHIP('','',#167189,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167206) +#169593 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169582); +#169594 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169595); +#169595 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('400','=>[0:1:1:7]','',#169576, + #9854,$); +#169596 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169597,#169599); +#169597 = ( REPRESENTATION_RELATIONSHIP('','',#169581,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169598) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167206 = ITEM_DEFINED_TRANSFORMATION('','',#11,#271); -#167207 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167208); -#167208 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('300','=>[0:1:1:100]','',#5, - #167184,$); -#167209 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167186)); -#167210 = SHAPE_DEFINITION_REPRESENTATION(#167211,#167217); -#167211 = PRODUCT_DEFINITION_SHAPE('','',#167212); -#167212 = PRODUCT_DEFINITION('design','',#167213,#167216); -#167213 = PRODUCT_DEFINITION_FORMATION('','',#167214); -#167214 = PRODUCT('R12','R12','',(#167215)); -#167215 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167216 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167217 = SHAPE_REPRESENTATION('',(#11,#167218),#167222); -#167218 = AXIS2_PLACEMENT_3D('',#167219,#167220,#167221); -#167219 = CARTESIAN_POINT('',(28.067,8.8859995,-1.27E-002)); -#167220 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167221 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#167222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167226)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167223,#167224,#167225)) +#169598 = ITEM_DEFINED_TRANSFORMATION('','',#11,#271); +#169599 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169600); +#169600 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('401','=>[0:1:1:100]','',#5, + #169576,$); +#169601 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169578)); +#169602 = SHAPE_DEFINITION_REPRESENTATION(#169603,#169609); +#169603 = PRODUCT_DEFINITION_SHAPE('','',#169604); +#169604 = PRODUCT_DEFINITION('design','',#169605,#169608); +#169605 = PRODUCT_DEFINITION_FORMATION('','',#169606); +#169606 = PRODUCT('R12','R12','',(#169607)); +#169607 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169608 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169609 = SHAPE_REPRESENTATION('',(#11,#169610),#169614); +#169610 = AXIS2_PLACEMENT_3D('',#169611,#169612,#169613); +#169611 = CARTESIAN_POINT('',(28.067,8.8859995,-1.27E-002)); +#169612 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169613 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#169614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169618)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169615,#169616,#169617)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167223 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167224 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167225 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167226 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167223, +#169615 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169616 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169617 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169618 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169615, 'distance_accuracy_value','confusion accuracy'); -#167227 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167228,#167230); -#167228 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#167217) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167229) +#169619 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169620,#169622); +#169620 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#169609) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169621) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167229 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167218); -#167230 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167231); -#167231 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('301','=>[0:1:1:7]','',#167212, - #7462,$); -#167232 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167233,#167235); -#167233 = ( REPRESENTATION_RELATIONSHIP('','',#167217,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167234) +#169621 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169610); +#169622 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169623); +#169623 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('402','=>[0:1:1:7]','',#169604, + #9854,$); +#169624 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#169625,#169627); +#169625 = ( REPRESENTATION_RELATIONSHIP('','',#169609,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#169626) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167234 = ITEM_DEFINED_TRANSFORMATION('','',#11,#275); -#167235 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167236); -#167236 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('302','=>[0:1:1:101]','',#5, - #167212,$); -#167237 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167214)); -#167238 = SHAPE_DEFINITION_REPRESENTATION(#167239,#167245); -#167239 = PRODUCT_DEFINITION_SHAPE('','',#167240); -#167240 = PRODUCT_DEFINITION('design','',#167241,#167244); -#167241 = PRODUCT_DEFINITION_FORMATION('','',#167242); -#167242 = PRODUCT('R14','R14','',(#167243)); -#167243 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167244 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167245 = SHAPE_REPRESENTATION('',(#11,#167246),#167250); -#167246 = AXIS2_PLACEMENT_3D('',#167247,#167248,#167249); -#167247 = CARTESIAN_POINT('',(8.76291872,27.30493904,0.2159)); -#167248 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); -#167249 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); -#167250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167254)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167251,#167252,#167253)) +#169626 = ITEM_DEFINED_TRANSFORMATION('','',#11,#275); +#169627 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #169628); +#169628 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('403','=>[0:1:1:101]','',#5, + #169604,$); +#169629 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169606)); +#169630 = SHAPE_DEFINITION_REPRESENTATION(#169631,#169637); +#169631 = PRODUCT_DEFINITION_SHAPE('','',#169632); +#169632 = PRODUCT_DEFINITION('design','',#169633,#169636); +#169633 = PRODUCT_DEFINITION_FORMATION('','',#169634); +#169634 = PRODUCT('R14','R14','',(#169635)); +#169635 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169636 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169637 = SHAPE_REPRESENTATION('',(#11,#169638),#169642); +#169638 = AXIS2_PLACEMENT_3D('',#169639,#169640,#169641); +#169639 = CARTESIAN_POINT('',(8.76291872,27.30493904,0.2159)); +#169640 = DIRECTION('',(1.224606353822E-016,1.,1.110223024625E-016)); +#169641 = DIRECTION('',(-1.,1.224606353822E-016,0.E+000)); +#169642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169646)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169643,#169644,#169645)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167251 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167252 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167253 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167254 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167251, +#169643 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169644 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169645 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169646 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169643, 'distance_accuracy_value','confusion accuracy'); -#167255 = SHAPE_DEFINITION_REPRESENTATION(#167256,#167262); -#167256 = PRODUCT_DEFINITION_SHAPE('','',#167257); -#167257 = PRODUCT_DEFINITION('design','',#167258,#167261); -#167258 = PRODUCT_DEFINITION_FORMATION('','',#167259); -#167259 = PRODUCT('User_Library-RES_0603L','User_Library-RES_0603L','',( - #167260)); -#167260 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167261 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167262 = SHAPE_REPRESENTATION('',(#11,#167263,#167267,#167271),#167275 - ); -#167263 = AXIS2_PLACEMENT_3D('',#167264,#167265,#167266); -#167264 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167265 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167266 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167267 = AXIS2_PLACEMENT_3D('',#167268,#167269,#167270); -#167268 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167269 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167270 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167271 = AXIS2_PLACEMENT_3D('',#167272,#167273,#167274); -#167272 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#167273 = DIRECTION('',(1.224606353822E-016,0.E+000,-1.)); -#167274 = DIRECTION('',(-1.,0.E+000,-1.224606353822E-016)); -#167275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167279)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167276,#167277,#167278)) +#169647 = SHAPE_DEFINITION_REPRESENTATION(#169648,#169654); +#169648 = PRODUCT_DEFINITION_SHAPE('','',#169649); +#169649 = PRODUCT_DEFINITION('design','',#169650,#169653); +#169650 = PRODUCT_DEFINITION_FORMATION('','',#169651); +#169651 = PRODUCT('User_Library-RES_0603L','User_Library-RES_0603L','',( + #169652)); +#169652 = PRODUCT_CONTEXT('',#2,'mechanical'); +#169653 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#169654 = SHAPE_REPRESENTATION('',(#11,#169655,#169659,#169663),#169667 + ); +#169655 = AXIS2_PLACEMENT_3D('',#169656,#169657,#169658); +#169656 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169657 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169658 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169659 = AXIS2_PLACEMENT_3D('',#169660,#169661,#169662); +#169660 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169661 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169662 = DIRECTION('',(1.,0.E+000,0.E+000)); +#169663 = AXIS2_PLACEMENT_3D('',#169664,#169665,#169666); +#169664 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#169665 = DIRECTION('',(1.224606353822E-016,0.E+000,-1.)); +#169666 = DIRECTION('',(-1.,0.E+000,-1.224606353822E-016)); +#169667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#169671)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#169668,#169669,#169670)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167276 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167277 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167278 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167279 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167276, +#169668 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#169669 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#169670 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#169671 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#169668, 'distance_accuracy_value','confusion accuracy'); -#167280 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#167281),#167923); -#167281 = MANIFOLD_SOLID_BREP('',#167282); -#167282 = CLOSED_SHELL('',(#167283,#167403,#167479,#167555,#167631, - #167707,#167787,#167836,#167889,#167916)); -#167283 = ADVANCED_FACE('',(#167284),#167298,.T.); -#167284 = FACE_BOUND('',#167285,.T.); -#167285 = EDGE_LOOP('',(#167286,#167321,#167349,#167377)); -#167286 = ORIENTED_EDGE('',*,*,#167287,.T.); -#167287 = EDGE_CURVE('',#167288,#167290,#167292,.T.); -#167288 = VERTEX_POINT('',#167289); -#167289 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); -#167290 = VERTEX_POINT('',#167291); -#167291 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); -#167292 = SURFACE_CURVE('',#167293,(#167297,#167309),.PCURVE_S1.); -#167293 = LINE('',#167294,#167295); -#167294 = CARTESIAN_POINT('',(0.717647058824,0.175,-0.4)); -#167295 = VECTOR('',#167296,1.); -#167296 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); -#167297 = PCURVE('',#167298,#167303); -#167298 = PLANE('',#167299); -#167299 = AXIS2_PLACEMENT_3D('',#167300,#167301,#167302); -#167300 = CARTESIAN_POINT('',(0.675,0.175,-0.4)); -#167301 = DIRECTION('',(2.312964634636E-016,-1.,0.E+000)); -#167302 = DIRECTION('',(1.,2.312964634636E-016,0.E+000)); -#167303 = DEFINITIONAL_REPRESENTATION('',(#167304),#167308); -#167304 = LINE('',#167305,#167306); -#167305 = CARTESIAN_POINT('',(4.264705882353E-002,0.E+000)); -#167306 = VECTOR('',#167307,1.); -#167307 = DIRECTION('',(1.,-3.425227816038E-030)); -#167308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167309 = PCURVE('',#167310,#167315); -#167310 = PLANE('',#167311); -#167311 = AXIS2_PLACEMENT_3D('',#167312,#167313,#167314); -#167312 = CARTESIAN_POINT('',(0.717647058824,-1.176470588235E-002,-0.4) - ); -#167313 = DIRECTION('',(3.425227816038E-030,-6.020148719118E-031,1.)); -#167314 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); -#167315 = DEFINITIONAL_REPRESENTATION('',(#167316),#167320); -#167316 = LINE('',#167317,#167318); -#167317 = CARTESIAN_POINT('',(0.E+000,0.186764705882)); -#167318 = VECTOR('',#167319,1.); -#167319 = DIRECTION('',(1.,-1.349401336734E-076)); -#167320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167321 = ORIENTED_EDGE('',*,*,#167322,.F.); -#167322 = EDGE_CURVE('',#167323,#167290,#167325,.T.); -#167323 = VERTEX_POINT('',#167324); -#167324 = CARTESIAN_POINT('',(0.75,0.175,0.4)); -#167325 = SURFACE_CURVE('',#167326,(#167330,#167337),.PCURVE_S1.); -#167326 = LINE('',#167327,#167328); -#167327 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); -#167328 = VECTOR('',#167329,1.); -#167329 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167330 = PCURVE('',#167298,#167331); -#167331 = DEFINITIONAL_REPRESENTATION('',(#167332),#167336); -#167332 = LINE('',#167333,#167334); -#167333 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); -#167334 = VECTOR('',#167335,1.); -#167335 = DIRECTION('',(0.E+000,-1.)); -#167336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167337 = PCURVE('',#167338,#167343); -#167338 = PLANE('',#167339); -#167339 = AXIS2_PLACEMENT_3D('',#167340,#167341,#167342); -#167340 = CARTESIAN_POINT('',(0.75,0.E+000,-0.4)); -#167341 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167342 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167343 = DEFINITIONAL_REPRESENTATION('',(#167344),#167348); -#167344 = LINE('',#167345,#167346); -#167345 = CARTESIAN_POINT('',(0.E+000,0.175)); -#167346 = VECTOR('',#167347,1.); -#167347 = DIRECTION('',(-1.,0.E+000)); -#167348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167349 = ORIENTED_EDGE('',*,*,#167350,.F.); -#167350 = EDGE_CURVE('',#167351,#167323,#167353,.T.); -#167351 = VERTEX_POINT('',#167352); -#167352 = CARTESIAN_POINT('',(0.6,0.175,0.4)); -#167353 = SURFACE_CURVE('',#167354,(#167358,#167365),.PCURVE_S1.); -#167354 = LINE('',#167355,#167356); -#167355 = CARTESIAN_POINT('',(0.717647058824,0.175,0.4)); -#167356 = VECTOR('',#167357,1.); -#167357 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); -#167358 = PCURVE('',#167298,#167359); -#167359 = DEFINITIONAL_REPRESENTATION('',(#167360),#167364); -#167360 = LINE('',#167361,#167362); -#167361 = CARTESIAN_POINT('',(4.264705882353E-002,0.8)); -#167362 = VECTOR('',#167363,1.); -#167363 = DIRECTION('',(1.,-3.425227816038E-030)); -#167364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167365 = PCURVE('',#167366,#167371); -#167366 = PLANE('',#167367); -#167367 = AXIS2_PLACEMENT_3D('',#167368,#167369,#167370); -#167368 = CARTESIAN_POINT('',(0.717647058824,-1.176470588235E-002,0.4)); -#167369 = DIRECTION('',(3.425227816038E-030,-6.020148719118E-031,1.)); -#167370 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); -#167371 = DEFINITIONAL_REPRESENTATION('',(#167372),#167376); -#167372 = LINE('',#167373,#167374); -#167373 = CARTESIAN_POINT('',(0.E+000,0.186764705882)); -#167374 = VECTOR('',#167375,1.); -#167375 = DIRECTION('',(1.,-1.349401336734E-076)); -#167376 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167377 = ORIENTED_EDGE('',*,*,#167378,.F.); -#167378 = EDGE_CURVE('',#167288,#167351,#167379,.T.); -#167379 = SURFACE_CURVE('',#167380,(#167384,#167391),.PCURVE_S1.); -#167380 = LINE('',#167381,#167382); -#167381 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); -#167382 = VECTOR('',#167383,1.); -#167383 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167384 = PCURVE('',#167298,#167385); -#167385 = DEFINITIONAL_REPRESENTATION('',(#167386),#167390); -#167386 = LINE('',#167387,#167388); -#167387 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); -#167388 = VECTOR('',#167389,1.); -#167389 = DIRECTION('',(0.E+000,1.)); -#167390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167391 = PCURVE('',#167392,#167397); -#167392 = PLANE('',#167393); -#167393 = AXIS2_PLACEMENT_3D('',#167394,#167395,#167396); -#167394 = CARTESIAN_POINT('',(0.6,0.2,-0.4)); -#167395 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167396 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167397 = DEFINITIONAL_REPRESENTATION('',(#167398),#167402); -#167398 = LINE('',#167399,#167400); -#167399 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#167400 = VECTOR('',#167401,1.); -#167401 = DIRECTION('',(1.,0.E+000)); -#167402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167403 = ADVANCED_FACE('',(#167404),#167338,.T.); -#167404 = FACE_BOUND('',#167405,.T.); -#167405 = EDGE_LOOP('',(#167406,#167429,#167457,#167478)); -#167406 = ORIENTED_EDGE('',*,*,#167407,.T.); -#167407 = EDGE_CURVE('',#167290,#167408,#167410,.T.); -#167408 = VERTEX_POINT('',#167409); -#167409 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); -#167410 = SURFACE_CURVE('',#167411,(#167415,#167422),.PCURVE_S1.); -#167411 = LINE('',#167412,#167413); -#167412 = CARTESIAN_POINT('',(0.75,-1.176470588235E-002,-0.4)); -#167413 = VECTOR('',#167414,1.); -#167414 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167415 = PCURVE('',#167338,#167416); -#167416 = DEFINITIONAL_REPRESENTATION('',(#167417),#167421); -#167417 = LINE('',#167418,#167419); -#167418 = CARTESIAN_POINT('',(0.E+000,-1.176470588235E-002)); -#167419 = VECTOR('',#167420,1.); -#167420 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167422 = PCURVE('',#167310,#167423); -#167423 = DEFINITIONAL_REPRESENTATION('',(#167424),#167428); -#167424 = LINE('',#167425,#167426); -#167425 = CARTESIAN_POINT('',(3.235294117647E-002,6.671299686574E-062)); -#167426 = VECTOR('',#167427,1.); -#167427 = DIRECTION('',(1.349401336734E-076,-1.)); -#167428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167429 = ORIENTED_EDGE('',*,*,#167430,.F.); -#167430 = EDGE_CURVE('',#167431,#167408,#167433,.T.); -#167431 = VERTEX_POINT('',#167432); -#167432 = CARTESIAN_POINT('',(0.75,-0.175,0.4)); -#167433 = SURFACE_CURVE('',#167434,(#167438,#167445),.PCURVE_S1.); -#167434 = LINE('',#167435,#167436); -#167435 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); -#167436 = VECTOR('',#167437,1.); -#167437 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167438 = PCURVE('',#167338,#167439); -#167439 = DEFINITIONAL_REPRESENTATION('',(#167440),#167444); -#167440 = LINE('',#167441,#167442); -#167441 = CARTESIAN_POINT('',(0.E+000,-0.175)); -#167442 = VECTOR('',#167443,1.); -#167443 = DIRECTION('',(-1.,0.E+000)); -#167444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167445 = PCURVE('',#167446,#167451); -#167446 = PLANE('',#167447); -#167447 = AXIS2_PLACEMENT_3D('',#167448,#167449,#167450); -#167448 = CARTESIAN_POINT('',(0.65,-0.175,-0.4)); -#167449 = DIRECTION('',(6.938893903907E-016,1.,0.E+000)); -#167450 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); -#167451 = DEFINITIONAL_REPRESENTATION('',(#167452),#167456); -#167452 = LINE('',#167453,#167454); -#167453 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); -#167454 = VECTOR('',#167455,1.); -#167455 = DIRECTION('',(0.E+000,-1.)); -#167456 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167457 = ORIENTED_EDGE('',*,*,#167458,.F.); -#167458 = EDGE_CURVE('',#167323,#167431,#167459,.T.); -#167459 = SURFACE_CURVE('',#167460,(#167464,#167471),.PCURVE_S1.); -#167460 = LINE('',#167461,#167462); -#167461 = CARTESIAN_POINT('',(0.75,-1.176470588235E-002,0.4)); -#167462 = VECTOR('',#167463,1.); -#167463 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167464 = PCURVE('',#167338,#167465); -#167465 = DEFINITIONAL_REPRESENTATION('',(#167466),#167470); -#167466 = LINE('',#167467,#167468); -#167467 = CARTESIAN_POINT('',(0.8,-1.176470588235E-002)); -#167468 = VECTOR('',#167469,1.); -#167469 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167471 = PCURVE('',#167366,#167472); -#167472 = DEFINITIONAL_REPRESENTATION('',(#167473),#167477); -#167473 = LINE('',#167474,#167475); -#167474 = CARTESIAN_POINT('',(3.235294117647E-002,6.671299686574E-062)); -#167475 = VECTOR('',#167476,1.); -#167476 = DIRECTION('',(1.349401336734E-076,-1.)); -#167477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167478 = ORIENTED_EDGE('',*,*,#167322,.T.); -#167479 = ADVANCED_FACE('',(#167480),#167446,.T.); -#167480 = FACE_BOUND('',#167481,.T.); -#167481 = EDGE_LOOP('',(#167482,#167505,#167533,#167554)); -#167482 = ORIENTED_EDGE('',*,*,#167483,.T.); -#167483 = EDGE_CURVE('',#167408,#167484,#167486,.T.); -#167484 = VERTEX_POINT('',#167485); -#167485 = CARTESIAN_POINT('',(0.55,-0.175,-0.4)); -#167486 = SURFACE_CURVE('',#167487,(#167491,#167498),.PCURVE_S1.); -#167487 = LINE('',#167488,#167489); -#167488 = CARTESIAN_POINT('',(0.717647058824,-0.175,-0.4)); -#167489 = VECTOR('',#167490,1.); -#167490 = DIRECTION('',(-1.,0.E+000,3.425227816038E-030)); -#167491 = PCURVE('',#167446,#167492); -#167492 = DEFINITIONAL_REPRESENTATION('',(#167493),#167497); -#167493 = LINE('',#167494,#167495); -#167494 = CARTESIAN_POINT('',(-6.764705882353E-002,0.E+000)); -#167495 = VECTOR('',#167496,1.); -#167496 = DIRECTION('',(1.,3.425227816038E-030)); -#167497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167498 = PCURVE('',#167310,#167499); -#167499 = DEFINITIONAL_REPRESENTATION('',(#167500),#167504); -#167500 = LINE('',#167501,#167502); -#167501 = CARTESIAN_POINT('',(0.E+000,-0.163235294118)); -#167502 = VECTOR('',#167503,1.); -#167503 = DIRECTION('',(-1.,1.349401336734E-076)); -#167504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167505 = ORIENTED_EDGE('',*,*,#167506,.F.); -#167506 = EDGE_CURVE('',#167507,#167484,#167509,.T.); -#167507 = VERTEX_POINT('',#167508); -#167508 = CARTESIAN_POINT('',(0.55,-0.175,0.4)); -#167509 = SURFACE_CURVE('',#167510,(#167514,#167521),.PCURVE_S1.); -#167510 = LINE('',#167511,#167512); -#167511 = CARTESIAN_POINT('',(0.55,-0.175,-0.4)); -#167512 = VECTOR('',#167513,1.); -#167513 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167514 = PCURVE('',#167446,#167515); -#167515 = DEFINITIONAL_REPRESENTATION('',(#167516),#167520); -#167516 = LINE('',#167517,#167518); -#167517 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#167518 = VECTOR('',#167519,1.); -#167519 = DIRECTION('',(0.E+000,-1.)); -#167520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167521 = PCURVE('',#167522,#167527); -#167522 = PLANE('',#167523); -#167523 = AXIS2_PLACEMENT_3D('',#167524,#167525,#167526); -#167524 = CARTESIAN_POINT('',(0.55,-0.2,-0.4)); -#167525 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167526 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167527 = DEFINITIONAL_REPRESENTATION('',(#167528),#167532); -#167528 = LINE('',#167529,#167530); -#167529 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#167530 = VECTOR('',#167531,1.); -#167531 = DIRECTION('',(-1.,0.E+000)); -#167532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167533 = ORIENTED_EDGE('',*,*,#167534,.F.); -#167534 = EDGE_CURVE('',#167431,#167507,#167535,.T.); -#167535 = SURFACE_CURVE('',#167536,(#167540,#167547),.PCURVE_S1.); -#167536 = LINE('',#167537,#167538); -#167537 = CARTESIAN_POINT('',(0.717647058824,-0.175,0.4)); -#167538 = VECTOR('',#167539,1.); -#167539 = DIRECTION('',(-1.,0.E+000,3.425227816038E-030)); -#167540 = PCURVE('',#167446,#167541); -#167541 = DEFINITIONAL_REPRESENTATION('',(#167542),#167546); -#167542 = LINE('',#167543,#167544); -#167543 = CARTESIAN_POINT('',(-6.764705882353E-002,0.8)); -#167544 = VECTOR('',#167545,1.); -#167545 = DIRECTION('',(1.,3.425227816038E-030)); -#167546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167547 = PCURVE('',#167366,#167548); -#167548 = DEFINITIONAL_REPRESENTATION('',(#167549),#167553); -#167549 = LINE('',#167550,#167551); -#167550 = CARTESIAN_POINT('',(0.E+000,-0.163235294118)); -#167551 = VECTOR('',#167552,1.); -#167552 = DIRECTION('',(-1.,1.349401336734E-076)); -#167553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167554 = ORIENTED_EDGE('',*,*,#167430,.T.); -#167555 = ADVANCED_FACE('',(#167556),#167522,.T.); -#167556 = FACE_BOUND('',#167557,.T.); -#167557 = EDGE_LOOP('',(#167558,#167581,#167609,#167630)); -#167558 = ORIENTED_EDGE('',*,*,#167559,.T.); -#167559 = EDGE_CURVE('',#167484,#167560,#167562,.T.); -#167560 = VERTEX_POINT('',#167561); -#167561 = CARTESIAN_POINT('',(0.55,-0.225,-0.4)); -#167562 = SURFACE_CURVE('',#167563,(#167567,#167574),.PCURVE_S1.); -#167563 = LINE('',#167564,#167565); -#167564 = CARTESIAN_POINT('',(0.55,-1.176470588235E-002,-0.4)); -#167565 = VECTOR('',#167566,1.); -#167566 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167567 = PCURVE('',#167522,#167568); -#167568 = DEFINITIONAL_REPRESENTATION('',(#167569),#167573); -#167569 = LINE('',#167570,#167571); -#167570 = CARTESIAN_POINT('',(0.E+000,0.188235294118)); -#167571 = VECTOR('',#167572,1.); -#167572 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167574 = PCURVE('',#167310,#167575); -#167575 = DEFINITIONAL_REPRESENTATION('',(#167576),#167580); -#167576 = LINE('',#167577,#167578); -#167577 = CARTESIAN_POINT('',(-0.167647058824,-3.456946201225E-061)); -#167578 = VECTOR('',#167579,1.); -#167579 = DIRECTION('',(1.349401336734E-076,-1.)); -#167580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167581 = ORIENTED_EDGE('',*,*,#167582,.F.); -#167582 = EDGE_CURVE('',#167583,#167560,#167585,.T.); -#167583 = VERTEX_POINT('',#167584); -#167584 = CARTESIAN_POINT('',(0.55,-0.225,0.4)); -#167585 = SURFACE_CURVE('',#167586,(#167590,#167597),.PCURVE_S1.); -#167586 = LINE('',#167587,#167588); -#167587 = CARTESIAN_POINT('',(0.55,-0.225,-0.4)); -#167588 = VECTOR('',#167589,1.); -#167589 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167590 = PCURVE('',#167522,#167591); -#167591 = DEFINITIONAL_REPRESENTATION('',(#167592),#167596); -#167592 = LINE('',#167593,#167594); -#167593 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); -#167594 = VECTOR('',#167595,1.); -#167595 = DIRECTION('',(-1.,0.E+000)); -#167596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167597 = PCURVE('',#167598,#167603); -#167598 = PLANE('',#167599); -#167599 = AXIS2_PLACEMENT_3D('',#167600,#167601,#167602); -#167600 = CARTESIAN_POINT('',(0.675,-0.225,-0.4)); -#167601 = DIRECTION('',(1.387778780781E-016,-1.,0.E+000)); -#167602 = DIRECTION('',(1.,1.387778780781E-016,0.E+000)); -#167603 = DEFINITIONAL_REPRESENTATION('',(#167604),#167608); -#167604 = LINE('',#167605,#167606); -#167605 = CARTESIAN_POINT('',(-0.125,0.E+000)); -#167606 = VECTOR('',#167607,1.); -#167607 = DIRECTION('',(0.E+000,-1.)); -#167608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167609 = ORIENTED_EDGE('',*,*,#167610,.F.); -#167610 = EDGE_CURVE('',#167507,#167583,#167611,.T.); -#167611 = SURFACE_CURVE('',#167612,(#167616,#167623),.PCURVE_S1.); -#167612 = LINE('',#167613,#167614); -#167613 = CARTESIAN_POINT('',(0.55,-1.176470588235E-002,0.4)); -#167614 = VECTOR('',#167615,1.); -#167615 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167616 = PCURVE('',#167522,#167617); -#167617 = DEFINITIONAL_REPRESENTATION('',(#167618),#167622); -#167618 = LINE('',#167619,#167620); -#167619 = CARTESIAN_POINT('',(0.8,0.188235294118)); -#167620 = VECTOR('',#167621,1.); -#167621 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167623 = PCURVE('',#167366,#167624); -#167624 = DEFINITIONAL_REPRESENTATION('',(#167625),#167629); -#167625 = LINE('',#167626,#167627); -#167626 = CARTESIAN_POINT('',(-0.167647058824,-3.456946201225E-061)); -#167627 = VECTOR('',#167628,1.); -#167628 = DIRECTION('',(1.349401336734E-076,-1.)); -#167629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167630 = ORIENTED_EDGE('',*,*,#167506,.T.); -#167631 = ADVANCED_FACE('',(#167632),#167392,.T.); -#167632 = FACE_BOUND('',#167633,.T.); -#167633 = EDGE_LOOP('',(#167634,#167657,#167658,#167681)); -#167634 = ORIENTED_EDGE('',*,*,#167635,.T.); -#167635 = EDGE_CURVE('',#167636,#167288,#167638,.T.); -#167636 = VERTEX_POINT('',#167637); -#167637 = CARTESIAN_POINT('',(0.6,0.225,-0.4)); -#167638 = SURFACE_CURVE('',#167639,(#167643,#167650),.PCURVE_S1.); -#167639 = LINE('',#167640,#167641); -#167640 = CARTESIAN_POINT('',(0.6,-1.176470588235E-002,-0.4)); -#167641 = VECTOR('',#167642,1.); -#167642 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167643 = PCURVE('',#167392,#167644); -#167644 = DEFINITIONAL_REPRESENTATION('',(#167645),#167649); -#167645 = LINE('',#167646,#167647); -#167646 = CARTESIAN_POINT('',(0.E+000,-0.211764705882)); -#167647 = VECTOR('',#167648,1.); -#167648 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167650 = PCURVE('',#167310,#167651); -#167651 = DEFINITIONAL_REPRESENTATION('',(#167652),#167656); -#167652 = LINE('',#167653,#167654); -#167653 = CARTESIAN_POINT('',(-0.117647058824,-2.425927158754E-061)); -#167654 = VECTOR('',#167655,1.); -#167655 = DIRECTION('',(1.349401336734E-076,-1.)); -#167656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167657 = ORIENTED_EDGE('',*,*,#167378,.T.); -#167658 = ORIENTED_EDGE('',*,*,#167659,.F.); -#167659 = EDGE_CURVE('',#167660,#167351,#167662,.T.); -#167660 = VERTEX_POINT('',#167661); -#167661 = CARTESIAN_POINT('',(0.6,0.225,0.4)); -#167662 = SURFACE_CURVE('',#167663,(#167667,#167674),.PCURVE_S1.); -#167663 = LINE('',#167664,#167665); -#167664 = CARTESIAN_POINT('',(0.6,-1.176470588235E-002,0.4)); -#167665 = VECTOR('',#167666,1.); -#167666 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); -#167667 = PCURVE('',#167392,#167668); -#167668 = DEFINITIONAL_REPRESENTATION('',(#167669),#167673); -#167669 = LINE('',#167670,#167671); -#167670 = CARTESIAN_POINT('',(0.8,-0.211764705882)); -#167671 = VECTOR('',#167672,1.); -#167672 = DIRECTION('',(-6.020148719118E-031,-1.)); -#167673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167674 = PCURVE('',#167366,#167675); -#167675 = DEFINITIONAL_REPRESENTATION('',(#167676),#167680); -#167676 = LINE('',#167677,#167678); -#167677 = CARTESIAN_POINT('',(-0.117647058824,-2.425927158754E-061)); -#167678 = VECTOR('',#167679,1.); -#167679 = DIRECTION('',(1.349401336734E-076,-1.)); -#167680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167681 = ORIENTED_EDGE('',*,*,#167682,.F.); -#167682 = EDGE_CURVE('',#167636,#167660,#167683,.T.); -#167683 = SURFACE_CURVE('',#167684,(#167688,#167695),.PCURVE_S1.); -#167684 = LINE('',#167685,#167686); -#167685 = CARTESIAN_POINT('',(0.6,0.225,-0.4)); -#167686 = VECTOR('',#167687,1.); -#167687 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167688 = PCURVE('',#167392,#167689); -#167689 = DEFINITIONAL_REPRESENTATION('',(#167690),#167694); -#167690 = LINE('',#167691,#167692); -#167691 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); -#167692 = VECTOR('',#167693,1.); -#167693 = DIRECTION('',(1.,0.E+000)); -#167694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167695 = PCURVE('',#167696,#167701); -#167696 = PLANE('',#167697); -#167697 = AXIS2_PLACEMENT_3D('',#167698,#167699,#167700); -#167698 = CARTESIAN_POINT('',(0.7,0.225,-0.4)); -#167699 = DIRECTION('',(6.938893903907E-016,1.,0.E+000)); -#167700 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); -#167701 = DEFINITIONAL_REPRESENTATION('',(#167702),#167706); -#167702 = LINE('',#167703,#167704); -#167703 = CARTESIAN_POINT('',(1.E-001,0.E+000)); -#167704 = VECTOR('',#167705,1.); -#167705 = DIRECTION('',(0.E+000,1.)); -#167706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167707 = ADVANCED_FACE('',(#167708),#167366,.T.); -#167708 = FACE_BOUND('',#167709,.T.); -#167709 = EDGE_LOOP('',(#167710,#167733,#167761,#167782,#167783,#167784, - #167785,#167786)); -#167710 = ORIENTED_EDGE('',*,*,#167711,.F.); -#167711 = EDGE_CURVE('',#167712,#167583,#167714,.T.); -#167712 = VERTEX_POINT('',#167713); -#167713 = CARTESIAN_POINT('',(0.8,-0.225,0.4)); -#167714 = SURFACE_CURVE('',#167715,(#167719,#167726),.PCURVE_S1.); -#167715 = LINE('',#167716,#167717); -#167716 = CARTESIAN_POINT('',(0.675,-0.225,0.4)); -#167717 = VECTOR('',#167718,1.); -#167718 = DIRECTION('',(-1.,-1.387778780781E-016,0.E+000)); -#167719 = PCURVE('',#167366,#167720); -#167720 = DEFINITIONAL_REPRESENTATION('',(#167721),#167725); -#167721 = LINE('',#167722,#167723); -#167722 = CARTESIAN_POINT('',(-4.264705882353E-002,-0.213235294118)); -#167723 = VECTOR('',#167724,1.); -#167724 = DIRECTION('',(-1.,-1.387778780781E-016)); -#167725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167726 = PCURVE('',#167598,#167727); -#167727 = DEFINITIONAL_REPRESENTATION('',(#167728),#167732); -#167728 = LINE('',#167729,#167730); -#167729 = CARTESIAN_POINT('',(0.E+000,0.8)); -#167730 = VECTOR('',#167731,1.); -#167731 = DIRECTION('',(-1.,0.E+000)); -#167732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167733 = ORIENTED_EDGE('',*,*,#167734,.F.); -#167734 = EDGE_CURVE('',#167735,#167712,#167737,.T.); -#167735 = VERTEX_POINT('',#167736); -#167736 = CARTESIAN_POINT('',(0.8,0.225,0.4)); -#167737 = SURFACE_CURVE('',#167738,(#167742,#167749),.PCURVE_S1.); -#167738 = LINE('',#167739,#167740); -#167739 = CARTESIAN_POINT('',(0.8,0.E+000,0.4)); -#167740 = VECTOR('',#167741,1.); -#167741 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#167742 = PCURVE('',#167366,#167743); -#167743 = DEFINITIONAL_REPRESENTATION('',(#167744),#167748); -#167744 = LINE('',#167745,#167746); -#167745 = CARTESIAN_POINT('',(8.235294117647E-002,1.176470588235E-002)); -#167746 = VECTOR('',#167747,1.); -#167747 = DIRECTION('',(1.349401336734E-076,-1.)); -#167748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167749 = PCURVE('',#167750,#167755); -#167750 = PLANE('',#167751); -#167751 = AXIS2_PLACEMENT_3D('',#167752,#167753,#167754); -#167752 = CARTESIAN_POINT('',(0.8,0.E+000,-0.4)); -#167753 = DIRECTION('',(1.,0.E+000,0.E+000)); -#167754 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167755 = DEFINITIONAL_REPRESENTATION('',(#167756),#167760); -#167756 = LINE('',#167757,#167758); -#167757 = CARTESIAN_POINT('',(-0.8,0.E+000)); -#167758 = VECTOR('',#167759,1.); -#167759 = DIRECTION('',(0.E+000,-1.)); -#167760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167761 = ORIENTED_EDGE('',*,*,#167762,.F.); -#167762 = EDGE_CURVE('',#167660,#167735,#167763,.T.); -#167763 = SURFACE_CURVE('',#167764,(#167768,#167775),.PCURVE_S1.); -#167764 = LINE('',#167765,#167766); -#167765 = CARTESIAN_POINT('',(0.7,0.225,0.4)); -#167766 = VECTOR('',#167767,1.); -#167767 = DIRECTION('',(1.,-6.938893903907E-016,0.E+000)); -#167768 = PCURVE('',#167366,#167769); -#167769 = DEFINITIONAL_REPRESENTATION('',(#167770),#167774); -#167770 = LINE('',#167771,#167772); -#167771 = CARTESIAN_POINT('',(-1.764705882353E-002,0.236764705882)); -#167772 = VECTOR('',#167773,1.); -#167773 = DIRECTION('',(1.,-6.938893903907E-016)); -#167774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167775 = PCURVE('',#167696,#167776); -#167776 = DEFINITIONAL_REPRESENTATION('',(#167777),#167781); -#167777 = LINE('',#167778,#167779); -#167778 = CARTESIAN_POINT('',(0.E+000,0.8)); -#167779 = VECTOR('',#167780,1.); -#167780 = DIRECTION('',(-1.,0.E+000)); -#167781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167782 = ORIENTED_EDGE('',*,*,#167659,.T.); -#167783 = ORIENTED_EDGE('',*,*,#167350,.T.); -#167784 = ORIENTED_EDGE('',*,*,#167458,.T.); -#167785 = ORIENTED_EDGE('',*,*,#167534,.T.); -#167786 = ORIENTED_EDGE('',*,*,#167610,.T.); -#167787 = ADVANCED_FACE('',(#167788),#167598,.T.); -#167788 = FACE_BOUND('',#167789,.T.); -#167789 = EDGE_LOOP('',(#167790,#167813,#167834,#167835)); -#167790 = ORIENTED_EDGE('',*,*,#167791,.T.); -#167791 = EDGE_CURVE('',#167560,#167792,#167794,.T.); -#167792 = VERTEX_POINT('',#167793); -#167793 = CARTESIAN_POINT('',(0.8,-0.225,-0.4)); -#167794 = SURFACE_CURVE('',#167795,(#167799,#167806),.PCURVE_S1.); -#167795 = LINE('',#167796,#167797); -#167796 = CARTESIAN_POINT('',(0.717647058824,-0.225,-0.4)); -#167797 = VECTOR('',#167798,1.); -#167798 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); -#167799 = PCURVE('',#167598,#167800); -#167800 = DEFINITIONAL_REPRESENTATION('',(#167801),#167805); -#167801 = LINE('',#167802,#167803); -#167802 = CARTESIAN_POINT('',(4.264705882353E-002,0.E+000)); -#167803 = VECTOR('',#167804,1.); -#167804 = DIRECTION('',(1.,-3.425227816038E-030)); -#167805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167806 = PCURVE('',#167310,#167807); -#167807 = DEFINITIONAL_REPRESENTATION('',(#167808),#167812); -#167808 = LINE('',#167809,#167810); -#167809 = CARTESIAN_POINT('',(0.E+000,-0.213235294118)); -#167810 = VECTOR('',#167811,1.); -#167811 = DIRECTION('',(1.,-1.349401336734E-076)); -#167812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167813 = ORIENTED_EDGE('',*,*,#167814,.F.); -#167814 = EDGE_CURVE('',#167712,#167792,#167815,.T.); -#167815 = SURFACE_CURVE('',#167816,(#167820,#167827),.PCURVE_S1.); -#167816 = LINE('',#167817,#167818); -#167817 = CARTESIAN_POINT('',(0.8,-0.225,-0.4)); -#167818 = VECTOR('',#167819,1.); -#167819 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167820 = PCURVE('',#167598,#167821); -#167821 = DEFINITIONAL_REPRESENTATION('',(#167822),#167826); -#167822 = LINE('',#167823,#167824); -#167823 = CARTESIAN_POINT('',(0.125,0.E+000)); -#167824 = VECTOR('',#167825,1.); -#167825 = DIRECTION('',(0.E+000,-1.)); -#167826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167827 = PCURVE('',#167750,#167828); -#167828 = DEFINITIONAL_REPRESENTATION('',(#167829),#167833); -#167829 = LINE('',#167830,#167831); -#167830 = CARTESIAN_POINT('',(0.E+000,-0.225)); -#167831 = VECTOR('',#167832,1.); -#167832 = DIRECTION('',(1.,0.E+000)); -#167833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167834 = ORIENTED_EDGE('',*,*,#167711,.T.); -#167835 = ORIENTED_EDGE('',*,*,#167582,.T.); -#167836 = ADVANCED_FACE('',(#167837),#167310,.F.); -#167837 = FACE_BOUND('',#167838,.T.); -#167838 = EDGE_LOOP('',(#167839,#167862,#167883,#167884,#167885,#167886, - #167887,#167888)); -#167839 = ORIENTED_EDGE('',*,*,#167840,.F.); -#167840 = EDGE_CURVE('',#167841,#167636,#167843,.T.); -#167841 = VERTEX_POINT('',#167842); -#167842 = CARTESIAN_POINT('',(0.8,0.225,-0.4)); -#167843 = SURFACE_CURVE('',#167844,(#167848,#167855),.PCURVE_S1.); -#167844 = LINE('',#167845,#167846); -#167845 = CARTESIAN_POINT('',(0.7,0.225,-0.4)); -#167846 = VECTOR('',#167847,1.); -#167847 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); -#167848 = PCURVE('',#167310,#167849); -#167849 = DEFINITIONAL_REPRESENTATION('',(#167850),#167854); -#167850 = LINE('',#167851,#167852); -#167851 = CARTESIAN_POINT('',(-1.764705882353E-002,0.236764705882)); -#167852 = VECTOR('',#167853,1.); -#167853 = DIRECTION('',(-1.,6.938893903907E-016)); -#167854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167855 = PCURVE('',#167696,#167856); -#167856 = DEFINITIONAL_REPRESENTATION('',(#167857),#167861); -#167857 = LINE('',#167858,#167859); -#167858 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167859 = VECTOR('',#167860,1.); -#167860 = DIRECTION('',(1.,0.E+000)); -#167861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167862 = ORIENTED_EDGE('',*,*,#167863,.F.); -#167863 = EDGE_CURVE('',#167792,#167841,#167864,.T.); -#167864 = SURFACE_CURVE('',#167865,(#167869,#167876),.PCURVE_S1.); -#167865 = LINE('',#167866,#167867); -#167866 = CARTESIAN_POINT('',(0.8,0.E+000,-0.4)); -#167867 = VECTOR('',#167868,1.); -#167868 = DIRECTION('',(0.E+000,1.,0.E+000)); -#167869 = PCURVE('',#167310,#167870); -#167870 = DEFINITIONAL_REPRESENTATION('',(#167871),#167875); -#167871 = LINE('',#167872,#167873); -#167872 = CARTESIAN_POINT('',(8.235294117647E-002,1.176470588235E-002)); -#167873 = VECTOR('',#167874,1.); -#167874 = DIRECTION('',(-1.349401336734E-076,1.)); -#167875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167876 = PCURVE('',#167750,#167877); -#167877 = DEFINITIONAL_REPRESENTATION('',(#167878),#167882); -#167878 = LINE('',#167879,#167880); -#167879 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#167880 = VECTOR('',#167881,1.); -#167881 = DIRECTION('',(0.E+000,1.)); -#167882 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167883 = ORIENTED_EDGE('',*,*,#167791,.F.); -#167884 = ORIENTED_EDGE('',*,*,#167559,.F.); -#167885 = ORIENTED_EDGE('',*,*,#167483,.F.); -#167886 = ORIENTED_EDGE('',*,*,#167407,.F.); -#167887 = ORIENTED_EDGE('',*,*,#167287,.F.); -#167888 = ORIENTED_EDGE('',*,*,#167635,.F.); -#167889 = ADVANCED_FACE('',(#167890),#167696,.T.); -#167890 = FACE_BOUND('',#167891,.T.); -#167891 = EDGE_LOOP('',(#167892,#167893,#167894,#167895)); -#167892 = ORIENTED_EDGE('',*,*,#167840,.T.); -#167893 = ORIENTED_EDGE('',*,*,#167682,.T.); -#167894 = ORIENTED_EDGE('',*,*,#167762,.T.); -#167895 = ORIENTED_EDGE('',*,*,#167896,.F.); -#167896 = EDGE_CURVE('',#167841,#167735,#167897,.T.); -#167897 = SURFACE_CURVE('',#167898,(#167902,#167909),.PCURVE_S1.); -#167898 = LINE('',#167899,#167900); -#167899 = CARTESIAN_POINT('',(0.8,0.225,-0.4)); -#167900 = VECTOR('',#167901,1.); -#167901 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167902 = PCURVE('',#167696,#167903); -#167903 = DEFINITIONAL_REPRESENTATION('',(#167904),#167908); -#167904 = LINE('',#167905,#167906); -#167905 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#167906 = VECTOR('',#167907,1.); -#167907 = DIRECTION('',(0.E+000,1.)); -#167908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167909 = PCURVE('',#167750,#167910); -#167910 = DEFINITIONAL_REPRESENTATION('',(#167911),#167915); -#167911 = LINE('',#167912,#167913); -#167912 = CARTESIAN_POINT('',(0.E+000,0.225)); -#167913 = VECTOR('',#167914,1.); -#167914 = DIRECTION('',(-1.,0.E+000)); -#167915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167916 = ADVANCED_FACE('',(#167917),#167750,.T.); -#167917 = FACE_BOUND('',#167918,.T.); -#167918 = EDGE_LOOP('',(#167919,#167920,#167921,#167922)); -#167919 = ORIENTED_EDGE('',*,*,#167863,.T.); -#167920 = ORIENTED_EDGE('',*,*,#167896,.T.); -#167921 = ORIENTED_EDGE('',*,*,#167734,.T.); -#167922 = ORIENTED_EDGE('',*,*,#167814,.T.); -#167923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#167927)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#167924,#167925,#167926)) +#169672 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#169673),#170315); +#169673 = MANIFOLD_SOLID_BREP('',#169674); +#169674 = CLOSED_SHELL('',(#169675,#169795,#169871,#169947,#170023, + #170099,#170179,#170228,#170281,#170308)); +#169675 = ADVANCED_FACE('',(#169676),#169690,.T.); +#169676 = FACE_BOUND('',#169677,.T.); +#169677 = EDGE_LOOP('',(#169678,#169713,#169741,#169769)); +#169678 = ORIENTED_EDGE('',*,*,#169679,.T.); +#169679 = EDGE_CURVE('',#169680,#169682,#169684,.T.); +#169680 = VERTEX_POINT('',#169681); +#169681 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); +#169682 = VERTEX_POINT('',#169683); +#169683 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); +#169684 = SURFACE_CURVE('',#169685,(#169689,#169701),.PCURVE_S1.); +#169685 = LINE('',#169686,#169687); +#169686 = CARTESIAN_POINT('',(0.717647058824,0.175,-0.4)); +#169687 = VECTOR('',#169688,1.); +#169688 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); +#169689 = PCURVE('',#169690,#169695); +#169690 = PLANE('',#169691); +#169691 = AXIS2_PLACEMENT_3D('',#169692,#169693,#169694); +#169692 = CARTESIAN_POINT('',(0.675,0.175,-0.4)); +#169693 = DIRECTION('',(2.312964634636E-016,-1.,0.E+000)); +#169694 = DIRECTION('',(1.,2.312964634636E-016,0.E+000)); +#169695 = DEFINITIONAL_REPRESENTATION('',(#169696),#169700); +#169696 = LINE('',#169697,#169698); +#169697 = CARTESIAN_POINT('',(4.264705882353E-002,0.E+000)); +#169698 = VECTOR('',#169699,1.); +#169699 = DIRECTION('',(1.,-3.425227816038E-030)); +#169700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169701 = PCURVE('',#169702,#169707); +#169702 = PLANE('',#169703); +#169703 = AXIS2_PLACEMENT_3D('',#169704,#169705,#169706); +#169704 = CARTESIAN_POINT('',(0.717647058824,-1.176470588235E-002,-0.4) + ); +#169705 = DIRECTION('',(3.425227816038E-030,-6.020148719118E-031,1.)); +#169706 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); +#169707 = DEFINITIONAL_REPRESENTATION('',(#169708),#169712); +#169708 = LINE('',#169709,#169710); +#169709 = CARTESIAN_POINT('',(0.E+000,0.186764705882)); +#169710 = VECTOR('',#169711,1.); +#169711 = DIRECTION('',(1.,-1.349401336734E-076)); +#169712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169713 = ORIENTED_EDGE('',*,*,#169714,.F.); +#169714 = EDGE_CURVE('',#169715,#169682,#169717,.T.); +#169715 = VERTEX_POINT('',#169716); +#169716 = CARTESIAN_POINT('',(0.75,0.175,0.4)); +#169717 = SURFACE_CURVE('',#169718,(#169722,#169729),.PCURVE_S1.); +#169718 = LINE('',#169719,#169720); +#169719 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); +#169720 = VECTOR('',#169721,1.); +#169721 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169722 = PCURVE('',#169690,#169723); +#169723 = DEFINITIONAL_REPRESENTATION('',(#169724),#169728); +#169724 = LINE('',#169725,#169726); +#169725 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); +#169726 = VECTOR('',#169727,1.); +#169727 = DIRECTION('',(0.E+000,-1.)); +#169728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169729 = PCURVE('',#169730,#169735); +#169730 = PLANE('',#169731); +#169731 = AXIS2_PLACEMENT_3D('',#169732,#169733,#169734); +#169732 = CARTESIAN_POINT('',(0.75,0.E+000,-0.4)); +#169733 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169734 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169735 = DEFINITIONAL_REPRESENTATION('',(#169736),#169740); +#169736 = LINE('',#169737,#169738); +#169737 = CARTESIAN_POINT('',(0.E+000,0.175)); +#169738 = VECTOR('',#169739,1.); +#169739 = DIRECTION('',(-1.,0.E+000)); +#169740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169741 = ORIENTED_EDGE('',*,*,#169742,.F.); +#169742 = EDGE_CURVE('',#169743,#169715,#169745,.T.); +#169743 = VERTEX_POINT('',#169744); +#169744 = CARTESIAN_POINT('',(0.6,0.175,0.4)); +#169745 = SURFACE_CURVE('',#169746,(#169750,#169757),.PCURVE_S1.); +#169746 = LINE('',#169747,#169748); +#169747 = CARTESIAN_POINT('',(0.717647058824,0.175,0.4)); +#169748 = VECTOR('',#169749,1.); +#169749 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); +#169750 = PCURVE('',#169690,#169751); +#169751 = DEFINITIONAL_REPRESENTATION('',(#169752),#169756); +#169752 = LINE('',#169753,#169754); +#169753 = CARTESIAN_POINT('',(4.264705882353E-002,0.8)); +#169754 = VECTOR('',#169755,1.); +#169755 = DIRECTION('',(1.,-3.425227816038E-030)); +#169756 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169757 = PCURVE('',#169758,#169763); +#169758 = PLANE('',#169759); +#169759 = AXIS2_PLACEMENT_3D('',#169760,#169761,#169762); +#169760 = CARTESIAN_POINT('',(0.717647058824,-1.176470588235E-002,0.4)); +#169761 = DIRECTION('',(3.425227816038E-030,-6.020148719118E-031,1.)); +#169762 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); +#169763 = DEFINITIONAL_REPRESENTATION('',(#169764),#169768); +#169764 = LINE('',#169765,#169766); +#169765 = CARTESIAN_POINT('',(0.E+000,0.186764705882)); +#169766 = VECTOR('',#169767,1.); +#169767 = DIRECTION('',(1.,-1.349401336734E-076)); +#169768 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169769 = ORIENTED_EDGE('',*,*,#169770,.F.); +#169770 = EDGE_CURVE('',#169680,#169743,#169771,.T.); +#169771 = SURFACE_CURVE('',#169772,(#169776,#169783),.PCURVE_S1.); +#169772 = LINE('',#169773,#169774); +#169773 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); +#169774 = VECTOR('',#169775,1.); +#169775 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169776 = PCURVE('',#169690,#169777); +#169777 = DEFINITIONAL_REPRESENTATION('',(#169778),#169782); +#169778 = LINE('',#169779,#169780); +#169779 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); +#169780 = VECTOR('',#169781,1.); +#169781 = DIRECTION('',(0.E+000,1.)); +#169782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169783 = PCURVE('',#169784,#169789); +#169784 = PLANE('',#169785); +#169785 = AXIS2_PLACEMENT_3D('',#169786,#169787,#169788); +#169786 = CARTESIAN_POINT('',(0.6,0.2,-0.4)); +#169787 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169788 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169789 = DEFINITIONAL_REPRESENTATION('',(#169790),#169794); +#169790 = LINE('',#169791,#169792); +#169791 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#169792 = VECTOR('',#169793,1.); +#169793 = DIRECTION('',(1.,0.E+000)); +#169794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169795 = ADVANCED_FACE('',(#169796),#169730,.T.); +#169796 = FACE_BOUND('',#169797,.T.); +#169797 = EDGE_LOOP('',(#169798,#169821,#169849,#169870)); +#169798 = ORIENTED_EDGE('',*,*,#169799,.T.); +#169799 = EDGE_CURVE('',#169682,#169800,#169802,.T.); +#169800 = VERTEX_POINT('',#169801); +#169801 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); +#169802 = SURFACE_CURVE('',#169803,(#169807,#169814),.PCURVE_S1.); +#169803 = LINE('',#169804,#169805); +#169804 = CARTESIAN_POINT('',(0.75,-1.176470588235E-002,-0.4)); +#169805 = VECTOR('',#169806,1.); +#169806 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#169807 = PCURVE('',#169730,#169808); +#169808 = DEFINITIONAL_REPRESENTATION('',(#169809),#169813); +#169809 = LINE('',#169810,#169811); +#169810 = CARTESIAN_POINT('',(0.E+000,-1.176470588235E-002)); +#169811 = VECTOR('',#169812,1.); +#169812 = DIRECTION('',(-6.020148719118E-031,-1.)); +#169813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169814 = PCURVE('',#169702,#169815); +#169815 = DEFINITIONAL_REPRESENTATION('',(#169816),#169820); +#169816 = LINE('',#169817,#169818); +#169817 = CARTESIAN_POINT('',(3.235294117647E-002,6.671299686574E-062)); +#169818 = VECTOR('',#169819,1.); +#169819 = DIRECTION('',(1.349401336734E-076,-1.)); +#169820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169821 = ORIENTED_EDGE('',*,*,#169822,.F.); +#169822 = EDGE_CURVE('',#169823,#169800,#169825,.T.); +#169823 = VERTEX_POINT('',#169824); +#169824 = CARTESIAN_POINT('',(0.75,-0.175,0.4)); +#169825 = SURFACE_CURVE('',#169826,(#169830,#169837),.PCURVE_S1.); +#169826 = LINE('',#169827,#169828); +#169827 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); +#169828 = VECTOR('',#169829,1.); +#169829 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169830 = PCURVE('',#169730,#169831); +#169831 = DEFINITIONAL_REPRESENTATION('',(#169832),#169836); +#169832 = LINE('',#169833,#169834); +#169833 = CARTESIAN_POINT('',(0.E+000,-0.175)); +#169834 = VECTOR('',#169835,1.); +#169835 = DIRECTION('',(-1.,0.E+000)); +#169836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169837 = PCURVE('',#169838,#169843); +#169838 = PLANE('',#169839); +#169839 = AXIS2_PLACEMENT_3D('',#169840,#169841,#169842); +#169840 = CARTESIAN_POINT('',(0.65,-0.175,-0.4)); +#169841 = DIRECTION('',(6.938893903907E-016,1.,0.E+000)); +#169842 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); +#169843 = DEFINITIONAL_REPRESENTATION('',(#169844),#169848); +#169844 = LINE('',#169845,#169846); +#169845 = CARTESIAN_POINT('',(-1.E-001,0.E+000)); +#169846 = VECTOR('',#169847,1.); +#169847 = DIRECTION('',(0.E+000,-1.)); +#169848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169849 = ORIENTED_EDGE('',*,*,#169850,.F.); +#169850 = EDGE_CURVE('',#169715,#169823,#169851,.T.); +#169851 = SURFACE_CURVE('',#169852,(#169856,#169863),.PCURVE_S1.); +#169852 = LINE('',#169853,#169854); +#169853 = CARTESIAN_POINT('',(0.75,-1.176470588235E-002,0.4)); +#169854 = VECTOR('',#169855,1.); +#169855 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#169856 = PCURVE('',#169730,#169857); +#169857 = DEFINITIONAL_REPRESENTATION('',(#169858),#169862); +#169858 = LINE('',#169859,#169860); +#169859 = CARTESIAN_POINT('',(0.8,-1.176470588235E-002)); +#169860 = VECTOR('',#169861,1.); +#169861 = DIRECTION('',(-6.020148719118E-031,-1.)); +#169862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169863 = PCURVE('',#169758,#169864); +#169864 = DEFINITIONAL_REPRESENTATION('',(#169865),#169869); +#169865 = LINE('',#169866,#169867); +#169866 = CARTESIAN_POINT('',(3.235294117647E-002,6.671299686574E-062)); +#169867 = VECTOR('',#169868,1.); +#169868 = DIRECTION('',(1.349401336734E-076,-1.)); +#169869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169870 = ORIENTED_EDGE('',*,*,#169714,.T.); +#169871 = ADVANCED_FACE('',(#169872),#169838,.T.); +#169872 = FACE_BOUND('',#169873,.T.); +#169873 = EDGE_LOOP('',(#169874,#169897,#169925,#169946)); +#169874 = ORIENTED_EDGE('',*,*,#169875,.T.); +#169875 = EDGE_CURVE('',#169800,#169876,#169878,.T.); +#169876 = VERTEX_POINT('',#169877); +#169877 = CARTESIAN_POINT('',(0.55,-0.175,-0.4)); +#169878 = SURFACE_CURVE('',#169879,(#169883,#169890),.PCURVE_S1.); +#169879 = LINE('',#169880,#169881); +#169880 = CARTESIAN_POINT('',(0.717647058824,-0.175,-0.4)); +#169881 = VECTOR('',#169882,1.); +#169882 = DIRECTION('',(-1.,0.E+000,3.425227816038E-030)); +#169883 = PCURVE('',#169838,#169884); +#169884 = DEFINITIONAL_REPRESENTATION('',(#169885),#169889); +#169885 = LINE('',#169886,#169887); +#169886 = CARTESIAN_POINT('',(-6.764705882353E-002,0.E+000)); +#169887 = VECTOR('',#169888,1.); +#169888 = DIRECTION('',(1.,3.425227816038E-030)); +#169889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169890 = PCURVE('',#169702,#169891); +#169891 = DEFINITIONAL_REPRESENTATION('',(#169892),#169896); +#169892 = LINE('',#169893,#169894); +#169893 = CARTESIAN_POINT('',(0.E+000,-0.163235294118)); +#169894 = VECTOR('',#169895,1.); +#169895 = DIRECTION('',(-1.,1.349401336734E-076)); +#169896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169897 = ORIENTED_EDGE('',*,*,#169898,.F.); +#169898 = EDGE_CURVE('',#169899,#169876,#169901,.T.); +#169899 = VERTEX_POINT('',#169900); +#169900 = CARTESIAN_POINT('',(0.55,-0.175,0.4)); +#169901 = SURFACE_CURVE('',#169902,(#169906,#169913),.PCURVE_S1.); +#169902 = LINE('',#169903,#169904); +#169903 = CARTESIAN_POINT('',(0.55,-0.175,-0.4)); +#169904 = VECTOR('',#169905,1.); +#169905 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169906 = PCURVE('',#169838,#169907); +#169907 = DEFINITIONAL_REPRESENTATION('',(#169908),#169912); +#169908 = LINE('',#169909,#169910); +#169909 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#169910 = VECTOR('',#169911,1.); +#169911 = DIRECTION('',(0.E+000,-1.)); +#169912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169913 = PCURVE('',#169914,#169919); +#169914 = PLANE('',#169915); +#169915 = AXIS2_PLACEMENT_3D('',#169916,#169917,#169918); +#169916 = CARTESIAN_POINT('',(0.55,-0.2,-0.4)); +#169917 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#169918 = DIRECTION('',(0.E+000,0.E+000,1.)); +#169919 = DEFINITIONAL_REPRESENTATION('',(#169920),#169924); +#169920 = LINE('',#169921,#169922); +#169921 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#169922 = VECTOR('',#169923,1.); +#169923 = DIRECTION('',(-1.,0.E+000)); +#169924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169925 = ORIENTED_EDGE('',*,*,#169926,.F.); +#169926 = EDGE_CURVE('',#169823,#169899,#169927,.T.); +#169927 = SURFACE_CURVE('',#169928,(#169932,#169939),.PCURVE_S1.); +#169928 = LINE('',#169929,#169930); +#169929 = CARTESIAN_POINT('',(0.717647058824,-0.175,0.4)); +#169930 = VECTOR('',#169931,1.); +#169931 = DIRECTION('',(-1.,0.E+000,3.425227816038E-030)); +#169932 = PCURVE('',#169838,#169933); +#169933 = DEFINITIONAL_REPRESENTATION('',(#169934),#169938); +#169934 = LINE('',#169935,#169936); +#169935 = CARTESIAN_POINT('',(-6.764705882353E-002,0.8)); +#169936 = VECTOR('',#169937,1.); +#169937 = DIRECTION('',(1.,3.425227816038E-030)); +#169938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169939 = PCURVE('',#169758,#169940); +#169940 = DEFINITIONAL_REPRESENTATION('',(#169941),#169945); +#169941 = LINE('',#169942,#169943); +#169942 = CARTESIAN_POINT('',(0.E+000,-0.163235294118)); +#169943 = VECTOR('',#169944,1.); +#169944 = DIRECTION('',(-1.,1.349401336734E-076)); +#169945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169946 = ORIENTED_EDGE('',*,*,#169822,.T.); +#169947 = ADVANCED_FACE('',(#169948),#169914,.T.); +#169948 = FACE_BOUND('',#169949,.T.); +#169949 = EDGE_LOOP('',(#169950,#169973,#170001,#170022)); +#169950 = ORIENTED_EDGE('',*,*,#169951,.T.); +#169951 = EDGE_CURVE('',#169876,#169952,#169954,.T.); +#169952 = VERTEX_POINT('',#169953); +#169953 = CARTESIAN_POINT('',(0.55,-0.225,-0.4)); +#169954 = SURFACE_CURVE('',#169955,(#169959,#169966),.PCURVE_S1.); +#169955 = LINE('',#169956,#169957); +#169956 = CARTESIAN_POINT('',(0.55,-1.176470588235E-002,-0.4)); +#169957 = VECTOR('',#169958,1.); +#169958 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#169959 = PCURVE('',#169914,#169960); +#169960 = DEFINITIONAL_REPRESENTATION('',(#169961),#169965); +#169961 = LINE('',#169962,#169963); +#169962 = CARTESIAN_POINT('',(0.E+000,0.188235294118)); +#169963 = VECTOR('',#169964,1.); +#169964 = DIRECTION('',(-6.020148719118E-031,-1.)); +#169965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169966 = PCURVE('',#169702,#169967); +#169967 = DEFINITIONAL_REPRESENTATION('',(#169968),#169972); +#169968 = LINE('',#169969,#169970); +#169969 = CARTESIAN_POINT('',(-0.167647058824,-3.456946201225E-061)); +#169970 = VECTOR('',#169971,1.); +#169971 = DIRECTION('',(1.349401336734E-076,-1.)); +#169972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169973 = ORIENTED_EDGE('',*,*,#169974,.F.); +#169974 = EDGE_CURVE('',#169975,#169952,#169977,.T.); +#169975 = VERTEX_POINT('',#169976); +#169976 = CARTESIAN_POINT('',(0.55,-0.225,0.4)); +#169977 = SURFACE_CURVE('',#169978,(#169982,#169989),.PCURVE_S1.); +#169978 = LINE('',#169979,#169980); +#169979 = CARTESIAN_POINT('',(0.55,-0.225,-0.4)); +#169980 = VECTOR('',#169981,1.); +#169981 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#169982 = PCURVE('',#169914,#169983); +#169983 = DEFINITIONAL_REPRESENTATION('',(#169984),#169988); +#169984 = LINE('',#169985,#169986); +#169985 = CARTESIAN_POINT('',(0.E+000,-2.5E-002)); +#169986 = VECTOR('',#169987,1.); +#169987 = DIRECTION('',(-1.,0.E+000)); +#169988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#169989 = PCURVE('',#169990,#169995); +#169990 = PLANE('',#169991); +#169991 = AXIS2_PLACEMENT_3D('',#169992,#169993,#169994); +#169992 = CARTESIAN_POINT('',(0.675,-0.225,-0.4)); +#169993 = DIRECTION('',(1.387778780781E-016,-1.,0.E+000)); +#169994 = DIRECTION('',(1.,1.387778780781E-016,0.E+000)); +#169995 = DEFINITIONAL_REPRESENTATION('',(#169996),#170000); +#169996 = LINE('',#169997,#169998); +#169997 = CARTESIAN_POINT('',(-0.125,0.E+000)); +#169998 = VECTOR('',#169999,1.); +#169999 = DIRECTION('',(0.E+000,-1.)); +#170000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170001 = ORIENTED_EDGE('',*,*,#170002,.F.); +#170002 = EDGE_CURVE('',#169899,#169975,#170003,.T.); +#170003 = SURFACE_CURVE('',#170004,(#170008,#170015),.PCURVE_S1.); +#170004 = LINE('',#170005,#170006); +#170005 = CARTESIAN_POINT('',(0.55,-1.176470588235E-002,0.4)); +#170006 = VECTOR('',#170007,1.); +#170007 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#170008 = PCURVE('',#169914,#170009); +#170009 = DEFINITIONAL_REPRESENTATION('',(#170010),#170014); +#170010 = LINE('',#170011,#170012); +#170011 = CARTESIAN_POINT('',(0.8,0.188235294118)); +#170012 = VECTOR('',#170013,1.); +#170013 = DIRECTION('',(-6.020148719118E-031,-1.)); +#170014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170015 = PCURVE('',#169758,#170016); +#170016 = DEFINITIONAL_REPRESENTATION('',(#170017),#170021); +#170017 = LINE('',#170018,#170019); +#170018 = CARTESIAN_POINT('',(-0.167647058824,-3.456946201225E-061)); +#170019 = VECTOR('',#170020,1.); +#170020 = DIRECTION('',(1.349401336734E-076,-1.)); +#170021 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170022 = ORIENTED_EDGE('',*,*,#169898,.T.); +#170023 = ADVANCED_FACE('',(#170024),#169784,.T.); +#170024 = FACE_BOUND('',#170025,.T.); +#170025 = EDGE_LOOP('',(#170026,#170049,#170050,#170073)); +#170026 = ORIENTED_EDGE('',*,*,#170027,.T.); +#170027 = EDGE_CURVE('',#170028,#169680,#170030,.T.); +#170028 = VERTEX_POINT('',#170029); +#170029 = CARTESIAN_POINT('',(0.6,0.225,-0.4)); +#170030 = SURFACE_CURVE('',#170031,(#170035,#170042),.PCURVE_S1.); +#170031 = LINE('',#170032,#170033); +#170032 = CARTESIAN_POINT('',(0.6,-1.176470588235E-002,-0.4)); +#170033 = VECTOR('',#170034,1.); +#170034 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#170035 = PCURVE('',#169784,#170036); +#170036 = DEFINITIONAL_REPRESENTATION('',(#170037),#170041); +#170037 = LINE('',#170038,#170039); +#170038 = CARTESIAN_POINT('',(0.E+000,-0.211764705882)); +#170039 = VECTOR('',#170040,1.); +#170040 = DIRECTION('',(-6.020148719118E-031,-1.)); +#170041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170042 = PCURVE('',#169702,#170043); +#170043 = DEFINITIONAL_REPRESENTATION('',(#170044),#170048); +#170044 = LINE('',#170045,#170046); +#170045 = CARTESIAN_POINT('',(-0.117647058824,-2.425927158754E-061)); +#170046 = VECTOR('',#170047,1.); +#170047 = DIRECTION('',(1.349401336734E-076,-1.)); +#170048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170049 = ORIENTED_EDGE('',*,*,#169770,.T.); +#170050 = ORIENTED_EDGE('',*,*,#170051,.F.); +#170051 = EDGE_CURVE('',#170052,#169743,#170054,.T.); +#170052 = VERTEX_POINT('',#170053); +#170053 = CARTESIAN_POINT('',(0.6,0.225,0.4)); +#170054 = SURFACE_CURVE('',#170055,(#170059,#170066),.PCURVE_S1.); +#170055 = LINE('',#170056,#170057); +#170056 = CARTESIAN_POINT('',(0.6,-1.176470588235E-002,0.4)); +#170057 = VECTOR('',#170058,1.); +#170058 = DIRECTION('',(-2.062038084941E-060,-1.,-6.020148719118E-031)); +#170059 = PCURVE('',#169784,#170060); +#170060 = DEFINITIONAL_REPRESENTATION('',(#170061),#170065); +#170061 = LINE('',#170062,#170063); +#170062 = CARTESIAN_POINT('',(0.8,-0.211764705882)); +#170063 = VECTOR('',#170064,1.); +#170064 = DIRECTION('',(-6.020148719118E-031,-1.)); +#170065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170066 = PCURVE('',#169758,#170067); +#170067 = DEFINITIONAL_REPRESENTATION('',(#170068),#170072); +#170068 = LINE('',#170069,#170070); +#170069 = CARTESIAN_POINT('',(-0.117647058824,-2.425927158754E-061)); +#170070 = VECTOR('',#170071,1.); +#170071 = DIRECTION('',(1.349401336734E-076,-1.)); +#170072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170073 = ORIENTED_EDGE('',*,*,#170074,.F.); +#170074 = EDGE_CURVE('',#170028,#170052,#170075,.T.); +#170075 = SURFACE_CURVE('',#170076,(#170080,#170087),.PCURVE_S1.); +#170076 = LINE('',#170077,#170078); +#170077 = CARTESIAN_POINT('',(0.6,0.225,-0.4)); +#170078 = VECTOR('',#170079,1.); +#170079 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170080 = PCURVE('',#169784,#170081); +#170081 = DEFINITIONAL_REPRESENTATION('',(#170082),#170086); +#170082 = LINE('',#170083,#170084); +#170083 = CARTESIAN_POINT('',(0.E+000,2.5E-002)); +#170084 = VECTOR('',#170085,1.); +#170085 = DIRECTION('',(1.,0.E+000)); +#170086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170087 = PCURVE('',#170088,#170093); +#170088 = PLANE('',#170089); +#170089 = AXIS2_PLACEMENT_3D('',#170090,#170091,#170092); +#170090 = CARTESIAN_POINT('',(0.7,0.225,-0.4)); +#170091 = DIRECTION('',(6.938893903907E-016,1.,0.E+000)); +#170092 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); +#170093 = DEFINITIONAL_REPRESENTATION('',(#170094),#170098); +#170094 = LINE('',#170095,#170096); +#170095 = CARTESIAN_POINT('',(1.E-001,0.E+000)); +#170096 = VECTOR('',#170097,1.); +#170097 = DIRECTION('',(0.E+000,1.)); +#170098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170099 = ADVANCED_FACE('',(#170100),#169758,.T.); +#170100 = FACE_BOUND('',#170101,.T.); +#170101 = EDGE_LOOP('',(#170102,#170125,#170153,#170174,#170175,#170176, + #170177,#170178)); +#170102 = ORIENTED_EDGE('',*,*,#170103,.F.); +#170103 = EDGE_CURVE('',#170104,#169975,#170106,.T.); +#170104 = VERTEX_POINT('',#170105); +#170105 = CARTESIAN_POINT('',(0.8,-0.225,0.4)); +#170106 = SURFACE_CURVE('',#170107,(#170111,#170118),.PCURVE_S1.); +#170107 = LINE('',#170108,#170109); +#170108 = CARTESIAN_POINT('',(0.675,-0.225,0.4)); +#170109 = VECTOR('',#170110,1.); +#170110 = DIRECTION('',(-1.,-1.387778780781E-016,0.E+000)); +#170111 = PCURVE('',#169758,#170112); +#170112 = DEFINITIONAL_REPRESENTATION('',(#170113),#170117); +#170113 = LINE('',#170114,#170115); +#170114 = CARTESIAN_POINT('',(-4.264705882353E-002,-0.213235294118)); +#170115 = VECTOR('',#170116,1.); +#170116 = DIRECTION('',(-1.,-1.387778780781E-016)); +#170117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170118 = PCURVE('',#169990,#170119); +#170119 = DEFINITIONAL_REPRESENTATION('',(#170120),#170124); +#170120 = LINE('',#170121,#170122); +#170121 = CARTESIAN_POINT('',(0.E+000,0.8)); +#170122 = VECTOR('',#170123,1.); +#170123 = DIRECTION('',(-1.,0.E+000)); +#170124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170125 = ORIENTED_EDGE('',*,*,#170126,.F.); +#170126 = EDGE_CURVE('',#170127,#170104,#170129,.T.); +#170127 = VERTEX_POINT('',#170128); +#170128 = CARTESIAN_POINT('',(0.8,0.225,0.4)); +#170129 = SURFACE_CURVE('',#170130,(#170134,#170141),.PCURVE_S1.); +#170130 = LINE('',#170131,#170132); +#170131 = CARTESIAN_POINT('',(0.8,0.E+000,0.4)); +#170132 = VECTOR('',#170133,1.); +#170133 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#170134 = PCURVE('',#169758,#170135); +#170135 = DEFINITIONAL_REPRESENTATION('',(#170136),#170140); +#170136 = LINE('',#170137,#170138); +#170137 = CARTESIAN_POINT('',(8.235294117647E-002,1.176470588235E-002)); +#170138 = VECTOR('',#170139,1.); +#170139 = DIRECTION('',(1.349401336734E-076,-1.)); +#170140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170141 = PCURVE('',#170142,#170147); +#170142 = PLANE('',#170143); +#170143 = AXIS2_PLACEMENT_3D('',#170144,#170145,#170146); +#170144 = CARTESIAN_POINT('',(0.8,0.E+000,-0.4)); +#170145 = DIRECTION('',(1.,0.E+000,0.E+000)); +#170146 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170147 = DEFINITIONAL_REPRESENTATION('',(#170148),#170152); +#170148 = LINE('',#170149,#170150); +#170149 = CARTESIAN_POINT('',(-0.8,0.E+000)); +#170150 = VECTOR('',#170151,1.); +#170151 = DIRECTION('',(0.E+000,-1.)); +#170152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170153 = ORIENTED_EDGE('',*,*,#170154,.F.); +#170154 = EDGE_CURVE('',#170052,#170127,#170155,.T.); +#170155 = SURFACE_CURVE('',#170156,(#170160,#170167),.PCURVE_S1.); +#170156 = LINE('',#170157,#170158); +#170157 = CARTESIAN_POINT('',(0.7,0.225,0.4)); +#170158 = VECTOR('',#170159,1.); +#170159 = DIRECTION('',(1.,-6.938893903907E-016,0.E+000)); +#170160 = PCURVE('',#169758,#170161); +#170161 = DEFINITIONAL_REPRESENTATION('',(#170162),#170166); +#170162 = LINE('',#170163,#170164); +#170163 = CARTESIAN_POINT('',(-1.764705882353E-002,0.236764705882)); +#170164 = VECTOR('',#170165,1.); +#170165 = DIRECTION('',(1.,-6.938893903907E-016)); +#170166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170167 = PCURVE('',#170088,#170168); +#170168 = DEFINITIONAL_REPRESENTATION('',(#170169),#170173); +#170169 = LINE('',#170170,#170171); +#170170 = CARTESIAN_POINT('',(0.E+000,0.8)); +#170171 = VECTOR('',#170172,1.); +#170172 = DIRECTION('',(-1.,0.E+000)); +#170173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170174 = ORIENTED_EDGE('',*,*,#170051,.T.); +#170175 = ORIENTED_EDGE('',*,*,#169742,.T.); +#170176 = ORIENTED_EDGE('',*,*,#169850,.T.); +#170177 = ORIENTED_EDGE('',*,*,#169926,.T.); +#170178 = ORIENTED_EDGE('',*,*,#170002,.T.); +#170179 = ADVANCED_FACE('',(#170180),#169990,.T.); +#170180 = FACE_BOUND('',#170181,.T.); +#170181 = EDGE_LOOP('',(#170182,#170205,#170226,#170227)); +#170182 = ORIENTED_EDGE('',*,*,#170183,.T.); +#170183 = EDGE_CURVE('',#169952,#170184,#170186,.T.); +#170184 = VERTEX_POINT('',#170185); +#170185 = CARTESIAN_POINT('',(0.8,-0.225,-0.4)); +#170186 = SURFACE_CURVE('',#170187,(#170191,#170198),.PCURVE_S1.); +#170187 = LINE('',#170188,#170189); +#170188 = CARTESIAN_POINT('',(0.717647058824,-0.225,-0.4)); +#170189 = VECTOR('',#170190,1.); +#170190 = DIRECTION('',(1.,0.E+000,-3.425227816038E-030)); +#170191 = PCURVE('',#169990,#170192); +#170192 = DEFINITIONAL_REPRESENTATION('',(#170193),#170197); +#170193 = LINE('',#170194,#170195); +#170194 = CARTESIAN_POINT('',(4.264705882353E-002,0.E+000)); +#170195 = VECTOR('',#170196,1.); +#170196 = DIRECTION('',(1.,-3.425227816038E-030)); +#170197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170198 = PCURVE('',#169702,#170199); +#170199 = DEFINITIONAL_REPRESENTATION('',(#170200),#170204); +#170200 = LINE('',#170201,#170202); +#170201 = CARTESIAN_POINT('',(0.E+000,-0.213235294118)); +#170202 = VECTOR('',#170203,1.); +#170203 = DIRECTION('',(1.,-1.349401336734E-076)); +#170204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170205 = ORIENTED_EDGE('',*,*,#170206,.F.); +#170206 = EDGE_CURVE('',#170104,#170184,#170207,.T.); +#170207 = SURFACE_CURVE('',#170208,(#170212,#170219),.PCURVE_S1.); +#170208 = LINE('',#170209,#170210); +#170209 = CARTESIAN_POINT('',(0.8,-0.225,-0.4)); +#170210 = VECTOR('',#170211,1.); +#170211 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170212 = PCURVE('',#169990,#170213); +#170213 = DEFINITIONAL_REPRESENTATION('',(#170214),#170218); +#170214 = LINE('',#170215,#170216); +#170215 = CARTESIAN_POINT('',(0.125,0.E+000)); +#170216 = VECTOR('',#170217,1.); +#170217 = DIRECTION('',(0.E+000,-1.)); +#170218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170219 = PCURVE('',#170142,#170220); +#170220 = DEFINITIONAL_REPRESENTATION('',(#170221),#170225); +#170221 = LINE('',#170222,#170223); +#170222 = CARTESIAN_POINT('',(0.E+000,-0.225)); +#170223 = VECTOR('',#170224,1.); +#170224 = DIRECTION('',(1.,0.E+000)); +#170225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170226 = ORIENTED_EDGE('',*,*,#170103,.T.); +#170227 = ORIENTED_EDGE('',*,*,#169974,.T.); +#170228 = ADVANCED_FACE('',(#170229),#169702,.F.); +#170229 = FACE_BOUND('',#170230,.T.); +#170230 = EDGE_LOOP('',(#170231,#170254,#170275,#170276,#170277,#170278, + #170279,#170280)); +#170231 = ORIENTED_EDGE('',*,*,#170232,.F.); +#170232 = EDGE_CURVE('',#170233,#170028,#170235,.T.); +#170233 = VERTEX_POINT('',#170234); +#170234 = CARTESIAN_POINT('',(0.8,0.225,-0.4)); +#170235 = SURFACE_CURVE('',#170236,(#170240,#170247),.PCURVE_S1.); +#170236 = LINE('',#170237,#170238); +#170237 = CARTESIAN_POINT('',(0.7,0.225,-0.4)); +#170238 = VECTOR('',#170239,1.); +#170239 = DIRECTION('',(-1.,6.938893903907E-016,0.E+000)); +#170240 = PCURVE('',#169702,#170241); +#170241 = DEFINITIONAL_REPRESENTATION('',(#170242),#170246); +#170242 = LINE('',#170243,#170244); +#170243 = CARTESIAN_POINT('',(-1.764705882353E-002,0.236764705882)); +#170244 = VECTOR('',#170245,1.); +#170245 = DIRECTION('',(-1.,6.938893903907E-016)); +#170246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170247 = PCURVE('',#170088,#170248); +#170248 = DEFINITIONAL_REPRESENTATION('',(#170249),#170253); +#170249 = LINE('',#170250,#170251); +#170250 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#170251 = VECTOR('',#170252,1.); +#170252 = DIRECTION('',(1.,0.E+000)); +#170253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170254 = ORIENTED_EDGE('',*,*,#170255,.F.); +#170255 = EDGE_CURVE('',#170184,#170233,#170256,.T.); +#170256 = SURFACE_CURVE('',#170257,(#170261,#170268),.PCURVE_S1.); +#170257 = LINE('',#170258,#170259); +#170258 = CARTESIAN_POINT('',(0.8,0.E+000,-0.4)); +#170259 = VECTOR('',#170260,1.); +#170260 = DIRECTION('',(0.E+000,1.,0.E+000)); +#170261 = PCURVE('',#169702,#170262); +#170262 = DEFINITIONAL_REPRESENTATION('',(#170263),#170267); +#170263 = LINE('',#170264,#170265); +#170264 = CARTESIAN_POINT('',(8.235294117647E-002,1.176470588235E-002)); +#170265 = VECTOR('',#170266,1.); +#170266 = DIRECTION('',(-1.349401336734E-076,1.)); +#170267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170268 = PCURVE('',#170142,#170269); +#170269 = DEFINITIONAL_REPRESENTATION('',(#170270),#170274); +#170270 = LINE('',#170271,#170272); +#170271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#170272 = VECTOR('',#170273,1.); +#170273 = DIRECTION('',(0.E+000,1.)); +#170274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170275 = ORIENTED_EDGE('',*,*,#170183,.F.); +#170276 = ORIENTED_EDGE('',*,*,#169951,.F.); +#170277 = ORIENTED_EDGE('',*,*,#169875,.F.); +#170278 = ORIENTED_EDGE('',*,*,#169799,.F.); +#170279 = ORIENTED_EDGE('',*,*,#169679,.F.); +#170280 = ORIENTED_EDGE('',*,*,#170027,.F.); +#170281 = ADVANCED_FACE('',(#170282),#170088,.T.); +#170282 = FACE_BOUND('',#170283,.T.); +#170283 = EDGE_LOOP('',(#170284,#170285,#170286,#170287)); +#170284 = ORIENTED_EDGE('',*,*,#170232,.T.); +#170285 = ORIENTED_EDGE('',*,*,#170074,.T.); +#170286 = ORIENTED_EDGE('',*,*,#170154,.T.); +#170287 = ORIENTED_EDGE('',*,*,#170288,.F.); +#170288 = EDGE_CURVE('',#170233,#170127,#170289,.T.); +#170289 = SURFACE_CURVE('',#170290,(#170294,#170301),.PCURVE_S1.); +#170290 = LINE('',#170291,#170292); +#170291 = CARTESIAN_POINT('',(0.8,0.225,-0.4)); +#170292 = VECTOR('',#170293,1.); +#170293 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170294 = PCURVE('',#170088,#170295); +#170295 = DEFINITIONAL_REPRESENTATION('',(#170296),#170300); +#170296 = LINE('',#170297,#170298); +#170297 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#170298 = VECTOR('',#170299,1.); +#170299 = DIRECTION('',(0.E+000,1.)); +#170300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170301 = PCURVE('',#170142,#170302); +#170302 = DEFINITIONAL_REPRESENTATION('',(#170303),#170307); +#170303 = LINE('',#170304,#170305); +#170304 = CARTESIAN_POINT('',(0.E+000,0.225)); +#170305 = VECTOR('',#170306,1.); +#170306 = DIRECTION('',(-1.,0.E+000)); +#170307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170308 = ADVANCED_FACE('',(#170309),#170142,.T.); +#170309 = FACE_BOUND('',#170310,.T.); +#170310 = EDGE_LOOP('',(#170311,#170312,#170313,#170314)); +#170311 = ORIENTED_EDGE('',*,*,#170255,.T.); +#170312 = ORIENTED_EDGE('',*,*,#170288,.T.); +#170313 = ORIENTED_EDGE('',*,*,#170126,.T.); +#170314 = ORIENTED_EDGE('',*,*,#170206,.T.); +#170315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#170319)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#170316,#170317,#170318)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#167924 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#167925 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#167926 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#167927 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#167924, +#170316 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#170317 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#170318 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#170319 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#170316, 'distance_accuracy_value','confusion accuracy'); -#167928 = SHAPE_DEFINITION_REPRESENTATION(#167929,#167280); -#167929 = PRODUCT_DEFINITION_SHAPE('','',#167930); -#167930 = PRODUCT_DEFINITION('design','',#167931,#167934); -#167931 = PRODUCT_DEFINITION_FORMATION('','',#167932); -#167932 = PRODUCT('User_Library-RES_0603L_RES_0603_Lead_1', - 'User_Library-RES_0603L_RES_0603_Lead_1','',(#167933)); -#167933 = PRODUCT_CONTEXT('',#2,'mechanical'); -#167934 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#167935 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#167936,#167938); -#167936 = ( REPRESENTATION_RELATIONSHIP('','',#167280,#167262) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#167937) +#170320 = SHAPE_DEFINITION_REPRESENTATION(#170321,#169672); +#170321 = PRODUCT_DEFINITION_SHAPE('','',#170322); +#170322 = PRODUCT_DEFINITION('design','',#170323,#170326); +#170323 = PRODUCT_DEFINITION_FORMATION('','',#170324); +#170324 = PRODUCT('User_Library-RES_0603L_RES_0603_Lead_1', + 'User_Library-RES_0603L_RES_0603_Lead_1','',(#170325)); +#170325 = PRODUCT_CONTEXT('',#2,'mechanical'); +#170326 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#170327 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#170328,#170330); +#170328 = ( REPRESENTATION_RELATIONSHIP('','',#169672,#169654) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#170329) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#167937 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167263); -#167938 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #167939); -#167939 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('303','','',#167257,#167930,$); -#167940 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167932)); -#167941 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#167942),#168584); -#167942 = MANIFOLD_SOLID_BREP('',#167943); -#167943 = CLOSED_SHELL('',(#167944,#168064,#168140,#168245,#168292, - #168368,#168448,#168497,#168550,#168577)); -#167944 = ADVANCED_FACE('',(#167945),#167959,.T.); -#167945 = FACE_BOUND('',#167946,.T.); -#167946 = EDGE_LOOP('',(#167947,#167982,#168010,#168038)); -#167947 = ORIENTED_EDGE('',*,*,#167948,.T.); -#167948 = EDGE_CURVE('',#167949,#167951,#167953,.T.); -#167949 = VERTEX_POINT('',#167950); -#167950 = CARTESIAN_POINT('',(-0.6,0.235,-0.4)); -#167951 = VERTEX_POINT('',#167952); -#167952 = CARTESIAN_POINT('',(-0.6,0.175,-0.4)); -#167953 = SURFACE_CURVE('',#167954,(#167958,#167970),.PCURVE_S1.); -#167954 = LINE('',#167955,#167956); -#167955 = CARTESIAN_POINT('',(-0.6,2.528795811518E-002,-0.4)); -#167956 = VECTOR('',#167957,1.); -#167957 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); -#167958 = PCURVE('',#167959,#167964); -#167959 = PLANE('',#167960); -#167960 = AXIS2_PLACEMENT_3D('',#167961,#167962,#167963); -#167961 = CARTESIAN_POINT('',(-0.6,0.205,-0.4)); -#167962 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#167963 = DIRECTION('',(0.E+000,0.E+000,1.)); -#167964 = DEFINITIONAL_REPRESENTATION('',(#167965),#167969); -#167965 = LINE('',#167966,#167967); -#167966 = CARTESIAN_POINT('',(0.E+000,-0.179712041885)); -#167967 = VECTOR('',#167968,1.); -#167968 = DIRECTION('',(2.314036761889E-031,-1.)); -#167969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167970 = PCURVE('',#167971,#167976); -#167971 = PLANE('',#167972); -#167972 = AXIS2_PLACEMENT_3D('',#167973,#167974,#167975); -#167973 = CARTESIAN_POINT('',(-1.149254302835E-016,2.528795811518E-002, +#170329 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169655); +#170330 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #170331); +#170331 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('404','','',#169649,#170322,$); +#170332 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#170324)); +#170333 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#170334),#170976); +#170334 = MANIFOLD_SOLID_BREP('',#170335); +#170335 = CLOSED_SHELL('',(#170336,#170456,#170532,#170637,#170684, + #170760,#170840,#170889,#170942,#170969)); +#170336 = ADVANCED_FACE('',(#170337),#170351,.T.); +#170337 = FACE_BOUND('',#170338,.T.); +#170338 = EDGE_LOOP('',(#170339,#170374,#170402,#170430)); +#170339 = ORIENTED_EDGE('',*,*,#170340,.T.); +#170340 = EDGE_CURVE('',#170341,#170343,#170345,.T.); +#170341 = VERTEX_POINT('',#170342); +#170342 = CARTESIAN_POINT('',(-0.6,0.235,-0.4)); +#170343 = VERTEX_POINT('',#170344); +#170344 = CARTESIAN_POINT('',(-0.6,0.175,-0.4)); +#170345 = SURFACE_CURVE('',#170346,(#170350,#170362),.PCURVE_S1.); +#170346 = LINE('',#170347,#170348); +#170347 = CARTESIAN_POINT('',(-0.6,2.528795811518E-002,-0.4)); +#170348 = VECTOR('',#170349,1.); +#170349 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); +#170350 = PCURVE('',#170351,#170356); +#170351 = PLANE('',#170352); +#170352 = AXIS2_PLACEMENT_3D('',#170353,#170354,#170355); +#170353 = CARTESIAN_POINT('',(-0.6,0.205,-0.4)); +#170354 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#170355 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170356 = DEFINITIONAL_REPRESENTATION('',(#170357),#170361); +#170357 = LINE('',#170358,#170359); +#170358 = CARTESIAN_POINT('',(0.E+000,-0.179712041885)); +#170359 = VECTOR('',#170360,1.); +#170360 = DIRECTION('',(2.314036761889E-031,-1.)); +#170361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170362 = PCURVE('',#170363,#170368); +#170363 = PLANE('',#170364); +#170364 = AXIS2_PLACEMENT_3D('',#170365,#170366,#170367); +#170365 = CARTESIAN_POINT('',(-1.149254302835E-016,2.528795811518E-002, -0.4)); -#167974 = DIRECTION('',(2.882261016903E-032,2.314036761889E-031,1.)); -#167975 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); -#167976 = DEFINITIONAL_REPRESENTATION('',(#167977),#167981); -#167977 = LINE('',#167978,#167979); -#167978 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#167979 = VECTOR('',#167980,1.); -#167980 = DIRECTION('',(1.,1.138557377869E-079)); -#167981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167982 = ORIENTED_EDGE('',*,*,#167983,.F.); -#167983 = EDGE_CURVE('',#167984,#167951,#167986,.T.); -#167984 = VERTEX_POINT('',#167985); -#167985 = CARTESIAN_POINT('',(-0.6,0.175,0.4)); -#167986 = SURFACE_CURVE('',#167987,(#167991,#167998),.PCURVE_S1.); -#167987 = LINE('',#167988,#167989); -#167988 = CARTESIAN_POINT('',(-0.6,0.175,-0.4)); -#167989 = VECTOR('',#167990,1.); -#167990 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#167991 = PCURVE('',#167959,#167992); -#167992 = DEFINITIONAL_REPRESENTATION('',(#167993),#167997); -#167993 = LINE('',#167994,#167995); -#167994 = CARTESIAN_POINT('',(0.E+000,-3.E-002)); -#167995 = VECTOR('',#167996,1.); -#167996 = DIRECTION('',(-1.,0.E+000)); -#167997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#167998 = PCURVE('',#167999,#168004); -#167999 = PLANE('',#168000); -#168000 = AXIS2_PLACEMENT_3D('',#168001,#168002,#168003); -#168001 = CARTESIAN_POINT('',(-0.675,0.175,-0.4)); -#168002 = DIRECTION('',(2.312964634636E-016,1.,0.E+000)); -#168003 = DIRECTION('',(-1.,2.312964634636E-016,0.E+000)); -#168004 = DEFINITIONAL_REPRESENTATION('',(#168005),#168009); -#168005 = LINE('',#168006,#168007); -#168006 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); -#168007 = VECTOR('',#168008,1.); -#168008 = DIRECTION('',(0.E+000,-1.)); -#168009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168010 = ORIENTED_EDGE('',*,*,#168011,.F.); -#168011 = EDGE_CURVE('',#168012,#167984,#168014,.T.); -#168012 = VERTEX_POINT('',#168013); -#168013 = CARTESIAN_POINT('',(-0.6,0.235,0.4)); -#168014 = SURFACE_CURVE('',#168015,(#168019,#168026),.PCURVE_S1.); -#168015 = LINE('',#168016,#168017); -#168016 = CARTESIAN_POINT('',(-0.6,2.528795811518E-002,0.4)); -#168017 = VECTOR('',#168018,1.); -#168018 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); -#168019 = PCURVE('',#167959,#168020); -#168020 = DEFINITIONAL_REPRESENTATION('',(#168021),#168025); -#168021 = LINE('',#168022,#168023); -#168022 = CARTESIAN_POINT('',(0.8,-0.179712041885)); -#168023 = VECTOR('',#168024,1.); -#168024 = DIRECTION('',(2.314036761889E-031,-1.)); -#168025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168026 = PCURVE('',#168027,#168032); -#168027 = PLANE('',#168028); -#168028 = AXIS2_PLACEMENT_3D('',#168029,#168030,#168031); -#168029 = CARTESIAN_POINT('',(-1.149254302835E-016,2.528795811518E-002, +#170366 = DIRECTION('',(2.882261016903E-032,2.314036761889E-031,1.)); +#170367 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); +#170368 = DEFINITIONAL_REPRESENTATION('',(#170369),#170373); +#170369 = LINE('',#170370,#170371); +#170370 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#170371 = VECTOR('',#170372,1.); +#170372 = DIRECTION('',(1.,1.138557377869E-079)); +#170373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170374 = ORIENTED_EDGE('',*,*,#170375,.F.); +#170375 = EDGE_CURVE('',#170376,#170343,#170378,.T.); +#170376 = VERTEX_POINT('',#170377); +#170377 = CARTESIAN_POINT('',(-0.6,0.175,0.4)); +#170378 = SURFACE_CURVE('',#170379,(#170383,#170390),.PCURVE_S1.); +#170379 = LINE('',#170380,#170381); +#170380 = CARTESIAN_POINT('',(-0.6,0.175,-0.4)); +#170381 = VECTOR('',#170382,1.); +#170382 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170383 = PCURVE('',#170351,#170384); +#170384 = DEFINITIONAL_REPRESENTATION('',(#170385),#170389); +#170385 = LINE('',#170386,#170387); +#170386 = CARTESIAN_POINT('',(0.E+000,-3.E-002)); +#170387 = VECTOR('',#170388,1.); +#170388 = DIRECTION('',(-1.,0.E+000)); +#170389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170390 = PCURVE('',#170391,#170396); +#170391 = PLANE('',#170392); +#170392 = AXIS2_PLACEMENT_3D('',#170393,#170394,#170395); +#170393 = CARTESIAN_POINT('',(-0.675,0.175,-0.4)); +#170394 = DIRECTION('',(2.312964634636E-016,1.,0.E+000)); +#170395 = DIRECTION('',(-1.,2.312964634636E-016,0.E+000)); +#170396 = DEFINITIONAL_REPRESENTATION('',(#170397),#170401); +#170397 = LINE('',#170398,#170399); +#170398 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); +#170399 = VECTOR('',#170400,1.); +#170400 = DIRECTION('',(0.E+000,-1.)); +#170401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170402 = ORIENTED_EDGE('',*,*,#170403,.F.); +#170403 = EDGE_CURVE('',#170404,#170376,#170406,.T.); +#170404 = VERTEX_POINT('',#170405); +#170405 = CARTESIAN_POINT('',(-0.6,0.235,0.4)); +#170406 = SURFACE_CURVE('',#170407,(#170411,#170418),.PCURVE_S1.); +#170407 = LINE('',#170408,#170409); +#170408 = CARTESIAN_POINT('',(-0.6,2.528795811518E-002,0.4)); +#170409 = VECTOR('',#170410,1.); +#170410 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); +#170411 = PCURVE('',#170351,#170412); +#170412 = DEFINITIONAL_REPRESENTATION('',(#170413),#170417); +#170413 = LINE('',#170414,#170415); +#170414 = CARTESIAN_POINT('',(0.8,-0.179712041885)); +#170415 = VECTOR('',#170416,1.); +#170416 = DIRECTION('',(2.314036761889E-031,-1.)); +#170417 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170418 = PCURVE('',#170419,#170424); +#170419 = PLANE('',#170420); +#170420 = AXIS2_PLACEMENT_3D('',#170421,#170422,#170423); +#170421 = CARTESIAN_POINT('',(-1.149254302835E-016,2.528795811518E-002, 0.4)); -#168030 = DIRECTION('',(2.882261016903E-032,2.314036761889E-031,1.)); -#168031 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); -#168032 = DEFINITIONAL_REPRESENTATION('',(#168033),#168037); -#168033 = LINE('',#168034,#168035); -#168034 = CARTESIAN_POINT('',(0.E+000,-0.6)); -#168035 = VECTOR('',#168036,1.); -#168036 = DIRECTION('',(1.,1.138557377869E-079)); -#168037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168038 = ORIENTED_EDGE('',*,*,#168039,.F.); -#168039 = EDGE_CURVE('',#167949,#168012,#168040,.T.); -#168040 = SURFACE_CURVE('',#168041,(#168045,#168052),.PCURVE_S1.); -#168041 = LINE('',#168042,#168043); -#168042 = CARTESIAN_POINT('',(-0.6,0.235,-0.4)); -#168043 = VECTOR('',#168044,1.); -#168044 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168045 = PCURVE('',#167959,#168046); -#168046 = DEFINITIONAL_REPRESENTATION('',(#168047),#168051); -#168047 = LINE('',#168048,#168049); -#168048 = CARTESIAN_POINT('',(0.E+000,3.E-002)); -#168049 = VECTOR('',#168050,1.); -#168050 = DIRECTION('',(1.,0.E+000)); -#168051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168052 = PCURVE('',#168053,#168058); -#168053 = PLANE('',#168054); -#168054 = AXIS2_PLACEMENT_3D('',#168055,#168056,#168057); -#168055 = CARTESIAN_POINT('',(0.E+000,0.235,-0.4)); -#168056 = DIRECTION('',(5.782411586589E-017,1.,0.E+000)); -#168057 = DIRECTION('',(-1.,5.782411586589E-017,0.E+000)); -#168058 = DEFINITIONAL_REPRESENTATION('',(#168059),#168063); -#168059 = LINE('',#168060,#168061); -#168060 = CARTESIAN_POINT('',(0.6,0.E+000)); -#168061 = VECTOR('',#168062,1.); -#168062 = DIRECTION('',(0.E+000,1.)); -#168063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168064 = ADVANCED_FACE('',(#168065),#167999,.T.); -#168065 = FACE_BOUND('',#168066,.T.); -#168066 = EDGE_LOOP('',(#168067,#168090,#168118,#168139)); -#168067 = ORIENTED_EDGE('',*,*,#168068,.T.); -#168068 = EDGE_CURVE('',#167951,#168069,#168071,.T.); -#168069 = VERTEX_POINT('',#168070); -#168070 = CARTESIAN_POINT('',(-0.75,0.175,-0.4)); -#168071 = SURFACE_CURVE('',#168072,(#168076,#168083),.PCURVE_S1.); -#168072 = LINE('',#168073,#168074); -#168073 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,-0.4)); -#168074 = VECTOR('',#168075,1.); -#168075 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168076 = PCURVE('',#167999,#168077); -#168077 = DEFINITIONAL_REPRESENTATION('',(#168078),#168082); -#168078 = LINE('',#168079,#168080); -#168079 = CARTESIAN_POINT('',(-0.675,0.E+000)); -#168080 = VECTOR('',#168081,1.); -#168081 = DIRECTION('',(1.,2.882261016903E-032)); -#168082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168083 = PCURVE('',#167971,#168084); -#168084 = DEFINITIONAL_REPRESENTATION('',(#168085),#168089); -#168085 = LINE('',#168086,#168087); -#168086 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); -#168087 = VECTOR('',#168088,1.); -#168088 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168090 = ORIENTED_EDGE('',*,*,#168091,.F.); -#168091 = EDGE_CURVE('',#168092,#168069,#168094,.T.); -#168092 = VERTEX_POINT('',#168093); -#168093 = CARTESIAN_POINT('',(-0.75,0.175,0.4)); -#168094 = SURFACE_CURVE('',#168095,(#168099,#168106),.PCURVE_S1.); -#168095 = LINE('',#168096,#168097); -#168096 = CARTESIAN_POINT('',(-0.75,0.175,-0.4)); -#168097 = VECTOR('',#168098,1.); -#168098 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#168099 = PCURVE('',#167999,#168100); -#168100 = DEFINITIONAL_REPRESENTATION('',(#168101),#168105); -#168101 = LINE('',#168102,#168103); -#168102 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); -#168103 = VECTOR('',#168104,1.); -#168104 = DIRECTION('',(0.E+000,-1.)); -#168105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168106 = PCURVE('',#168107,#168112); -#168107 = PLANE('',#168108); -#168108 = AXIS2_PLACEMENT_3D('',#168109,#168110,#168111); -#168109 = CARTESIAN_POINT('',(-0.75,2.775557561563E-016,-0.4)); -#168110 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#168111 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168112 = DEFINITIONAL_REPRESENTATION('',(#168113),#168117); -#168113 = LINE('',#168114,#168115); -#168114 = CARTESIAN_POINT('',(0.E+000,0.175)); -#168115 = VECTOR('',#168116,1.); -#168116 = DIRECTION('',(-1.,0.E+000)); -#168117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168118 = ORIENTED_EDGE('',*,*,#168119,.F.); -#168119 = EDGE_CURVE('',#167984,#168092,#168120,.T.); -#168120 = SURFACE_CURVE('',#168121,(#168125,#168132),.PCURVE_S1.); -#168121 = LINE('',#168122,#168123); -#168122 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,0.4)); -#168123 = VECTOR('',#168124,1.); -#168124 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168125 = PCURVE('',#167999,#168126); -#168126 = DEFINITIONAL_REPRESENTATION('',(#168127),#168131); -#168127 = LINE('',#168128,#168129); -#168128 = CARTESIAN_POINT('',(-0.675,0.8)); -#168129 = VECTOR('',#168130,1.); -#168130 = DIRECTION('',(1.,2.882261016903E-032)); -#168131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168132 = PCURVE('',#168027,#168133); -#168133 = DEFINITIONAL_REPRESENTATION('',(#168134),#168138); -#168134 = LINE('',#168135,#168136); -#168135 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); -#168136 = VECTOR('',#168137,1.); -#168137 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168139 = ORIENTED_EDGE('',*,*,#167983,.T.); -#168140 = ADVANCED_FACE('',(#168141),#168155,.T.); -#168141 = FACE_BOUND('',#168142,.T.); -#168142 = EDGE_LOOP('',(#168143,#168173,#168196,#168219)); -#168143 = ORIENTED_EDGE('',*,*,#168144,.T.); -#168144 = EDGE_CURVE('',#168145,#168147,#168149,.T.); -#168145 = VERTEX_POINT('',#168146); -#168146 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); -#168147 = VERTEX_POINT('',#168148); -#168148 = CARTESIAN_POINT('',(0.6,0.235,-0.4)); -#168149 = SURFACE_CURVE('',#168150,(#168154,#168166),.PCURVE_S1.); -#168150 = LINE('',#168151,#168152); -#168151 = CARTESIAN_POINT('',(0.6,2.528795811518E-002,-0.4)); -#168152 = VECTOR('',#168153,1.); -#168153 = DIRECTION('',(0.E+000,1.,-2.314036761889E-031)); -#168154 = PCURVE('',#168155,#168160); -#168155 = PLANE('',#168156); -#168156 = AXIS2_PLACEMENT_3D('',#168157,#168158,#168159); -#168157 = CARTESIAN_POINT('',(0.6,0.205,-0.4)); -#168158 = DIRECTION('',(1.,0.E+000,0.E+000)); -#168159 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#168160 = DEFINITIONAL_REPRESENTATION('',(#168161),#168165); -#168161 = LINE('',#168162,#168163); -#168162 = CARTESIAN_POINT('',(0.E+000,-0.179712041885)); -#168163 = VECTOR('',#168164,1.); -#168164 = DIRECTION('',(2.314036761889E-031,1.)); -#168165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168166 = PCURVE('',#167971,#168167); -#168167 = DEFINITIONAL_REPRESENTATION('',(#168168),#168172); -#168168 = LINE('',#168169,#168170); -#168169 = CARTESIAN_POINT('',(0.E+000,0.6)); -#168170 = VECTOR('',#168171,1.); -#168171 = DIRECTION('',(-1.,-1.138557377869E-079)); -#168172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168173 = ORIENTED_EDGE('',*,*,#168174,.F.); -#168174 = EDGE_CURVE('',#168175,#168147,#168177,.T.); -#168175 = VERTEX_POINT('',#168176); -#168176 = CARTESIAN_POINT('',(0.6,0.235,0.4)); -#168177 = SURFACE_CURVE('',#168178,(#168182,#168189),.PCURVE_S1.); -#168178 = LINE('',#168179,#168180); -#168179 = CARTESIAN_POINT('',(0.6,0.235,-0.4)); -#168180 = VECTOR('',#168181,1.); -#168181 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#168182 = PCURVE('',#168155,#168183); -#168183 = DEFINITIONAL_REPRESENTATION('',(#168184),#168188); -#168184 = LINE('',#168185,#168186); -#168185 = CARTESIAN_POINT('',(0.E+000,3.E-002)); -#168186 = VECTOR('',#168187,1.); -#168187 = DIRECTION('',(1.,0.E+000)); -#168188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168189 = PCURVE('',#168053,#168190); -#168190 = DEFINITIONAL_REPRESENTATION('',(#168191),#168195); -#168191 = LINE('',#168192,#168193); -#168192 = CARTESIAN_POINT('',(-0.6,0.E+000)); -#168193 = VECTOR('',#168194,1.); -#168194 = DIRECTION('',(0.E+000,-1.)); -#168195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168196 = ORIENTED_EDGE('',*,*,#168197,.F.); -#168197 = EDGE_CURVE('',#168198,#168175,#168200,.T.); -#168198 = VERTEX_POINT('',#168199); -#168199 = CARTESIAN_POINT('',(0.6,0.175,0.4)); -#168200 = SURFACE_CURVE('',#168201,(#168205,#168212),.PCURVE_S1.); -#168201 = LINE('',#168202,#168203); -#168202 = CARTESIAN_POINT('',(0.6,2.528795811518E-002,0.4)); -#168203 = VECTOR('',#168204,1.); -#168204 = DIRECTION('',(0.E+000,1.,-2.314036761889E-031)); -#168205 = PCURVE('',#168155,#168206); -#168206 = DEFINITIONAL_REPRESENTATION('',(#168207),#168211); -#168207 = LINE('',#168208,#168209); -#168208 = CARTESIAN_POINT('',(-0.8,-0.179712041885)); -#168209 = VECTOR('',#168210,1.); -#168210 = DIRECTION('',(2.314036761889E-031,1.)); -#168211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168212 = PCURVE('',#168027,#168213); -#168213 = DEFINITIONAL_REPRESENTATION('',(#168214),#168218); -#168214 = LINE('',#168215,#168216); -#168215 = CARTESIAN_POINT('',(0.E+000,0.6)); -#168216 = VECTOR('',#168217,1.); -#168217 = DIRECTION('',(-1.,-1.138557377869E-079)); -#168218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168219 = ORIENTED_EDGE('',*,*,#168220,.F.); -#168220 = EDGE_CURVE('',#168145,#168198,#168221,.T.); -#168221 = SURFACE_CURVE('',#168222,(#168226,#168233),.PCURVE_S1.); -#168222 = LINE('',#168223,#168224); -#168223 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); -#168224 = VECTOR('',#168225,1.); -#168225 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168226 = PCURVE('',#168155,#168227); -#168227 = DEFINITIONAL_REPRESENTATION('',(#168228),#168232); -#168228 = LINE('',#168229,#168230); -#168229 = CARTESIAN_POINT('',(0.E+000,-3.E-002)); -#168230 = VECTOR('',#168231,1.); -#168231 = DIRECTION('',(-1.,0.E+000)); -#168232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168233 = PCURVE('',#168234,#168239); -#168234 = PLANE('',#168235); -#168235 = AXIS2_PLACEMENT_3D('',#168236,#168237,#168238); -#168236 = CARTESIAN_POINT('',(0.675,0.175,-0.4)); -#168237 = DIRECTION('',(-2.312964634636E-016,1.,0.E+000)); -#168238 = DIRECTION('',(-1.,-2.312964634636E-016,0.E+000)); -#168239 = DEFINITIONAL_REPRESENTATION('',(#168240),#168244); -#168240 = LINE('',#168241,#168242); -#168241 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); -#168242 = VECTOR('',#168243,1.); -#168243 = DIRECTION('',(0.E+000,1.)); -#168244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#170422 = DIRECTION('',(2.882261016903E-032,2.314036761889E-031,1.)); +#170423 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); +#170424 = DEFINITIONAL_REPRESENTATION('',(#170425),#170429); +#170425 = LINE('',#170426,#170427); +#170426 = CARTESIAN_POINT('',(0.E+000,-0.6)); +#170427 = VECTOR('',#170428,1.); +#170428 = DIRECTION('',(1.,1.138557377869E-079)); +#170429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170430 = ORIENTED_EDGE('',*,*,#170431,.F.); +#170431 = EDGE_CURVE('',#170341,#170404,#170432,.T.); +#170432 = SURFACE_CURVE('',#170433,(#170437,#170444),.PCURVE_S1.); +#170433 = LINE('',#170434,#170435); +#170434 = CARTESIAN_POINT('',(-0.6,0.235,-0.4)); +#170435 = VECTOR('',#170436,1.); +#170436 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170437 = PCURVE('',#170351,#170438); +#170438 = DEFINITIONAL_REPRESENTATION('',(#170439),#170443); +#170439 = LINE('',#170440,#170441); +#170440 = CARTESIAN_POINT('',(0.E+000,3.E-002)); +#170441 = VECTOR('',#170442,1.); +#170442 = DIRECTION('',(1.,0.E+000)); +#170443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170444 = PCURVE('',#170445,#170450); +#170445 = PLANE('',#170446); +#170446 = AXIS2_PLACEMENT_3D('',#170447,#170448,#170449); +#170447 = CARTESIAN_POINT('',(0.E+000,0.235,-0.4)); +#170448 = DIRECTION('',(5.782411586589E-017,1.,0.E+000)); +#170449 = DIRECTION('',(-1.,5.782411586589E-017,0.E+000)); +#170450 = DEFINITIONAL_REPRESENTATION('',(#170451),#170455); +#170451 = LINE('',#170452,#170453); +#170452 = CARTESIAN_POINT('',(0.6,0.E+000)); +#170453 = VECTOR('',#170454,1.); +#170454 = DIRECTION('',(0.E+000,1.)); +#170455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#168245 = ADVANCED_FACE('',(#168246),#168053,.T.); -#168246 = FACE_BOUND('',#168247,.T.); -#168247 = EDGE_LOOP('',(#168248,#168269,#168270,#168291)); -#168248 = ORIENTED_EDGE('',*,*,#168249,.T.); -#168249 = EDGE_CURVE('',#168147,#167949,#168250,.T.); -#168250 = SURFACE_CURVE('',#168251,(#168255,#168262),.PCURVE_S1.); -#168251 = LINE('',#168252,#168253); -#168252 = CARTESIAN_POINT('',(-1.149254302835E-016,0.235,-0.4)); -#168253 = VECTOR('',#168254,1.); -#168254 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168255 = PCURVE('',#168053,#168256); -#168256 = DEFINITIONAL_REPRESENTATION('',(#168257),#168261); -#168257 = LINE('',#168258,#168259); -#168258 = CARTESIAN_POINT('',(1.149254302835E-016,0.E+000)); -#168259 = VECTOR('',#168260,1.); -#168260 = DIRECTION('',(1.,2.882261016903E-032)); -#168261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168262 = PCURVE('',#167971,#168263); -#168263 = DEFINITIONAL_REPRESENTATION('',(#168264),#168268); -#168264 = LINE('',#168265,#168266); -#168265 = CARTESIAN_POINT('',(-0.209712041885,-1.398707587467E-063)); -#168266 = VECTOR('',#168267,1.); -#168267 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168269 = ORIENTED_EDGE('',*,*,#168039,.T.); -#168270 = ORIENTED_EDGE('',*,*,#168271,.F.); -#168271 = EDGE_CURVE('',#168175,#168012,#168272,.T.); -#168272 = SURFACE_CURVE('',#168273,(#168277,#168284),.PCURVE_S1.); -#168273 = LINE('',#168274,#168275); -#168274 = CARTESIAN_POINT('',(-1.149254302835E-016,0.235,0.4)); -#168275 = VECTOR('',#168276,1.); -#168276 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168277 = PCURVE('',#168053,#168278); -#168278 = DEFINITIONAL_REPRESENTATION('',(#168279),#168283); -#168279 = LINE('',#168280,#168281); -#168280 = CARTESIAN_POINT('',(1.149254302835E-016,0.8)); -#168281 = VECTOR('',#168282,1.); -#168282 = DIRECTION('',(1.,2.882261016903E-032)); -#168283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168284 = PCURVE('',#168027,#168285); -#168285 = DEFINITIONAL_REPRESENTATION('',(#168286),#168290); -#168286 = LINE('',#168287,#168288); -#168287 = CARTESIAN_POINT('',(-0.209712041885,-1.398707587467E-063)); -#168288 = VECTOR('',#168289,1.); -#168289 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168291 = ORIENTED_EDGE('',*,*,#168174,.T.); -#168292 = ADVANCED_FACE('',(#168293),#168234,.T.); -#168293 = FACE_BOUND('',#168294,.T.); -#168294 = EDGE_LOOP('',(#168295,#168318,#168319,#168342)); -#168295 = ORIENTED_EDGE('',*,*,#168296,.T.); -#168296 = EDGE_CURVE('',#168297,#168145,#168299,.T.); -#168297 = VERTEX_POINT('',#168298); -#168298 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); -#168299 = SURFACE_CURVE('',#168300,(#168304,#168311),.PCURVE_S1.); -#168300 = LINE('',#168301,#168302); -#168301 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,-0.4)); -#168302 = VECTOR('',#168303,1.); -#168303 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168304 = PCURVE('',#168234,#168305); -#168305 = DEFINITIONAL_REPRESENTATION('',(#168306),#168310); -#168306 = LINE('',#168307,#168308); -#168307 = CARTESIAN_POINT('',(0.675,0.E+000)); -#168308 = VECTOR('',#168309,1.); -#168309 = DIRECTION('',(1.,2.882261016903E-032)); -#168310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168311 = PCURVE('',#167971,#168312); -#168312 = DEFINITIONAL_REPRESENTATION('',(#168313),#168317); -#168313 = LINE('',#168314,#168315); -#168314 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); -#168315 = VECTOR('',#168316,1.); -#168316 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168318 = ORIENTED_EDGE('',*,*,#168220,.T.); -#168319 = ORIENTED_EDGE('',*,*,#168320,.F.); -#168320 = EDGE_CURVE('',#168321,#168198,#168323,.T.); -#168321 = VERTEX_POINT('',#168322); -#168322 = CARTESIAN_POINT('',(0.75,0.175,0.4)); -#168323 = SURFACE_CURVE('',#168324,(#168328,#168335),.PCURVE_S1.); -#168324 = LINE('',#168325,#168326); -#168325 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,0.4)); -#168326 = VECTOR('',#168327,1.); -#168327 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); -#168328 = PCURVE('',#168234,#168329); -#168329 = DEFINITIONAL_REPRESENTATION('',(#168330),#168334); -#168330 = LINE('',#168331,#168332); -#168331 = CARTESIAN_POINT('',(0.675,0.8)); -#168332 = VECTOR('',#168333,1.); -#168333 = DIRECTION('',(1.,2.882261016903E-032)); -#168334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168335 = PCURVE('',#168027,#168336); -#168336 = DEFINITIONAL_REPRESENTATION('',(#168337),#168341); -#168337 = LINE('',#168338,#168339); -#168338 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); -#168339 = VECTOR('',#168340,1.); -#168340 = DIRECTION('',(-1.138557377869E-079,-1.)); -#168341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168342 = ORIENTED_EDGE('',*,*,#168343,.F.); -#168343 = EDGE_CURVE('',#168297,#168321,#168344,.T.); -#168344 = SURFACE_CURVE('',#168345,(#168349,#168356),.PCURVE_S1.); -#168345 = LINE('',#168346,#168347); -#168346 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); -#168347 = VECTOR('',#168348,1.); -#168348 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168349 = PCURVE('',#168234,#168350); -#168350 = DEFINITIONAL_REPRESENTATION('',(#168351),#168355); -#168351 = LINE('',#168352,#168353); -#168352 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); -#168353 = VECTOR('',#168354,1.); -#168354 = DIRECTION('',(0.E+000,1.)); -#168355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168356 = PCURVE('',#168357,#168362); -#168357 = PLANE('',#168358); -#168358 = AXIS2_PLACEMENT_3D('',#168359,#168360,#168361); -#168359 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,-0.4)); -#168360 = DIRECTION('',(1.,0.E+000,0.E+000)); -#168361 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#168362 = DEFINITIONAL_REPRESENTATION('',(#168363),#168367); -#168363 = LINE('',#168364,#168365); -#168364 = CARTESIAN_POINT('',(0.E+000,0.175)); -#168365 = VECTOR('',#168366,1.); -#168366 = DIRECTION('',(-1.,0.E+000)); -#168367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168368 = ADVANCED_FACE('',(#168369),#168027,.T.); -#168369 = FACE_BOUND('',#168370,.T.); -#168370 = EDGE_LOOP('',(#168371,#168394,#168395,#168396,#168397,#168398, - #168399,#168422)); -#168371 = ORIENTED_EDGE('',*,*,#168372,.F.); -#168372 = EDGE_CURVE('',#168321,#168373,#168375,.T.); -#168373 = VERTEX_POINT('',#168374); -#168374 = CARTESIAN_POINT('',(0.75,-0.175,0.4)); -#168375 = SURFACE_CURVE('',#168376,(#168380,#168387),.PCURVE_S1.); -#168376 = LINE('',#168377,#168378); -#168377 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,0.4)); -#168378 = VECTOR('',#168379,1.); -#168379 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#168380 = PCURVE('',#168027,#168381); -#168381 = DEFINITIONAL_REPRESENTATION('',(#168382),#168386); -#168382 = LINE('',#168383,#168384); -#168383 = CARTESIAN_POINT('',(2.528795811518E-002,0.75)); -#168384 = VECTOR('',#168385,1.); -#168385 = DIRECTION('',(1.,6.669657950473E-063)); -#168386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168387 = PCURVE('',#168357,#168388); -#168388 = DEFINITIONAL_REPRESENTATION('',(#168389),#168393); -#168389 = LINE('',#168390,#168391); -#168390 = CARTESIAN_POINT('',(-0.8,0.E+000)); -#168391 = VECTOR('',#168392,1.); -#168392 = DIRECTION('',(0.E+000,-1.)); -#168393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168394 = ORIENTED_EDGE('',*,*,#168320,.T.); -#168395 = ORIENTED_EDGE('',*,*,#168197,.T.); -#168396 = ORIENTED_EDGE('',*,*,#168271,.T.); -#168397 = ORIENTED_EDGE('',*,*,#168011,.T.); -#168398 = ORIENTED_EDGE('',*,*,#168119,.T.); -#168399 = ORIENTED_EDGE('',*,*,#168400,.F.); -#168400 = EDGE_CURVE('',#168401,#168092,#168403,.T.); -#168401 = VERTEX_POINT('',#168402); -#168402 = CARTESIAN_POINT('',(-0.75,-0.175,0.4)); -#168403 = SURFACE_CURVE('',#168404,(#168408,#168415),.PCURVE_S1.); -#168404 = LINE('',#168405,#168406); -#168405 = CARTESIAN_POINT('',(-0.75,2.775557561563E-016,0.4)); -#168406 = VECTOR('',#168407,1.); -#168407 = DIRECTION('',(0.E+000,1.,0.E+000)); -#168408 = PCURVE('',#168027,#168409); -#168409 = DEFINITIONAL_REPRESENTATION('',(#168410),#168414); -#168410 = LINE('',#168411,#168412); -#168411 = CARTESIAN_POINT('',(2.528795811518E-002,-0.75)); -#168412 = VECTOR('',#168413,1.); -#168413 = DIRECTION('',(-1.,-6.669657950473E-063)); -#168414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168415 = PCURVE('',#168107,#168416); -#168416 = DEFINITIONAL_REPRESENTATION('',(#168417),#168421); -#168417 = LINE('',#168418,#168419); -#168418 = CARTESIAN_POINT('',(0.8,0.E+000)); -#168419 = VECTOR('',#168420,1.); -#168420 = DIRECTION('',(0.E+000,1.)); -#168421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168422 = ORIENTED_EDGE('',*,*,#168423,.F.); -#168423 = EDGE_CURVE('',#168373,#168401,#168424,.T.); -#168424 = SURFACE_CURVE('',#168425,(#168429,#168436),.PCURVE_S1.); -#168425 = LINE('',#168426,#168427); -#168426 = CARTESIAN_POINT('',(0.E+000,-0.175,0.4)); -#168427 = VECTOR('',#168428,1.); -#168428 = DIRECTION('',(-1.,-3.469446951954E-016,0.E+000)); -#168429 = PCURVE('',#168027,#168430); -#168430 = DEFINITIONAL_REPRESENTATION('',(#168431),#168435); -#168431 = LINE('',#168432,#168433); -#168432 = CARTESIAN_POINT('',(0.200287958115,1.149254302835E-016)); -#168433 = VECTOR('',#168434,1.); -#168434 = DIRECTION('',(3.469446951954E-016,-1.)); -#168435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168436 = PCURVE('',#168437,#168442); -#168437 = PLANE('',#168438); -#168438 = AXIS2_PLACEMENT_3D('',#168439,#168440,#168441); -#168439 = CARTESIAN_POINT('',(0.E+000,-0.175,-0.4)); -#168440 = DIRECTION('',(3.469446951954E-016,-1.,0.E+000)); -#168441 = DIRECTION('',(1.,3.469446951954E-016,0.E+000)); -#168442 = DEFINITIONAL_REPRESENTATION('',(#168443),#168447); -#168443 = LINE('',#168444,#168445); -#168444 = CARTESIAN_POINT('',(0.E+000,0.8)); -#168445 = VECTOR('',#168446,1.); -#168446 = DIRECTION('',(-1.,0.E+000)); -#168447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168448 = ADVANCED_FACE('',(#168449),#168107,.T.); -#168449 = FACE_BOUND('',#168450,.T.); -#168450 = EDGE_LOOP('',(#168451,#168474,#168495,#168496)); -#168451 = ORIENTED_EDGE('',*,*,#168452,.T.); -#168452 = EDGE_CURVE('',#168069,#168453,#168455,.T.); -#168453 = VERTEX_POINT('',#168454); -#168454 = CARTESIAN_POINT('',(-0.75,-0.175,-0.4)); -#168455 = SURFACE_CURVE('',#168456,(#168460,#168467),.PCURVE_S1.); -#168456 = LINE('',#168457,#168458); -#168457 = CARTESIAN_POINT('',(-0.75,2.528795811518E-002,-0.4)); -#168458 = VECTOR('',#168459,1.); -#168459 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); -#168460 = PCURVE('',#168107,#168461); -#168461 = DEFINITIONAL_REPRESENTATION('',(#168462),#168466); -#168462 = LINE('',#168463,#168464); -#168463 = CARTESIAN_POINT('',(0.E+000,2.528795811518E-002)); -#168464 = VECTOR('',#168465,1.); -#168465 = DIRECTION('',(2.314036761889E-031,-1.)); -#168466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168467 = PCURVE('',#167971,#168468); -#168468 = DEFINITIONAL_REPRESENTATION('',(#168469),#168473); -#168469 = LINE('',#168470,#168471); -#168470 = CARTESIAN_POINT('',(0.E+000,-0.75)); -#168471 = VECTOR('',#168472,1.); -#168472 = DIRECTION('',(1.,1.138557377869E-079)); -#168473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168474 = ORIENTED_EDGE('',*,*,#168475,.F.); -#168475 = EDGE_CURVE('',#168401,#168453,#168476,.T.); -#168476 = SURFACE_CURVE('',#168477,(#168481,#168488),.PCURVE_S1.); -#168477 = LINE('',#168478,#168479); -#168478 = CARTESIAN_POINT('',(-0.75,-0.175,-0.4)); -#168479 = VECTOR('',#168480,1.); -#168480 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#168481 = PCURVE('',#168107,#168482); -#168482 = DEFINITIONAL_REPRESENTATION('',(#168483),#168487); -#168483 = LINE('',#168484,#168485); -#168484 = CARTESIAN_POINT('',(0.E+000,-0.175)); -#168485 = VECTOR('',#168486,1.); -#168486 = DIRECTION('',(-1.,0.E+000)); -#168487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168488 = PCURVE('',#168437,#168489); -#168489 = DEFINITIONAL_REPRESENTATION('',(#168490),#168494); -#168490 = LINE('',#168491,#168492); -#168491 = CARTESIAN_POINT('',(-0.75,0.E+000)); -#168492 = VECTOR('',#168493,1.); -#168493 = DIRECTION('',(0.E+000,-1.)); -#168494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168495 = ORIENTED_EDGE('',*,*,#168400,.T.); -#168496 = ORIENTED_EDGE('',*,*,#168091,.T.); -#168497 = ADVANCED_FACE('',(#168498),#167971,.F.); -#168498 = FACE_BOUND('',#168499,.T.); -#168499 = EDGE_LOOP('',(#168500,#168501,#168502,#168525,#168546,#168547, - #168548,#168549)); -#168500 = ORIENTED_EDGE('',*,*,#168144,.F.); -#168501 = ORIENTED_EDGE('',*,*,#168296,.F.); -#168502 = ORIENTED_EDGE('',*,*,#168503,.F.); -#168503 = EDGE_CURVE('',#168504,#168297,#168506,.T.); -#168504 = VERTEX_POINT('',#168505); -#168505 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); -#168506 = SURFACE_CURVE('',#168507,(#168511,#168518),.PCURVE_S1.); -#168507 = LINE('',#168508,#168509); -#168508 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,-0.4)); -#168509 = VECTOR('',#168510,1.); -#168510 = DIRECTION('',(0.E+000,1.,0.E+000)); -#168511 = PCURVE('',#167971,#168512); -#168512 = DEFINITIONAL_REPRESENTATION('',(#168513),#168517); -#168513 = LINE('',#168514,#168515); -#168514 = CARTESIAN_POINT('',(2.528795811518E-002,0.75)); -#168515 = VECTOR('',#168516,1.); -#168516 = DIRECTION('',(-1.,-6.669657950473E-063)); -#168517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168518 = PCURVE('',#168357,#168519); -#168519 = DEFINITIONAL_REPRESENTATION('',(#168520),#168524); -#168520 = LINE('',#168521,#168522); -#168521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#168522 = VECTOR('',#168523,1.); -#168523 = DIRECTION('',(0.E+000,1.)); -#168524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168525 = ORIENTED_EDGE('',*,*,#168526,.F.); -#168526 = EDGE_CURVE('',#168453,#168504,#168527,.T.); -#168527 = SURFACE_CURVE('',#168528,(#168532,#168539),.PCURVE_S1.); -#168528 = LINE('',#168529,#168530); -#168529 = CARTESIAN_POINT('',(0.E+000,-0.175,-0.4)); -#168530 = VECTOR('',#168531,1.); -#168531 = DIRECTION('',(1.,3.469446951954E-016,0.E+000)); -#168532 = PCURVE('',#167971,#168533); -#168533 = DEFINITIONAL_REPRESENTATION('',(#168534),#168538); -#168534 = LINE('',#168535,#168536); -#168535 = CARTESIAN_POINT('',(0.200287958115,1.149254302835E-016)); -#168536 = VECTOR('',#168537,1.); -#168537 = DIRECTION('',(-3.469446951954E-016,1.)); -#168538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168539 = PCURVE('',#168437,#168540); -#168540 = DEFINITIONAL_REPRESENTATION('',(#168541),#168545); -#168541 = LINE('',#168542,#168543); -#168542 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#168543 = VECTOR('',#168544,1.); -#168544 = DIRECTION('',(1.,0.E+000)); -#168545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168546 = ORIENTED_EDGE('',*,*,#168452,.F.); -#168547 = ORIENTED_EDGE('',*,*,#168068,.F.); -#168548 = ORIENTED_EDGE('',*,*,#167948,.F.); -#168549 = ORIENTED_EDGE('',*,*,#168249,.F.); -#168550 = ADVANCED_FACE('',(#168551),#168357,.T.); -#168551 = FACE_BOUND('',#168552,.T.); -#168552 = EDGE_LOOP('',(#168553,#168554,#168555,#168556)); -#168553 = ORIENTED_EDGE('',*,*,#168503,.T.); -#168554 = ORIENTED_EDGE('',*,*,#168343,.T.); -#168555 = ORIENTED_EDGE('',*,*,#168372,.T.); -#168556 = ORIENTED_EDGE('',*,*,#168557,.F.); -#168557 = EDGE_CURVE('',#168504,#168373,#168558,.T.); -#168558 = SURFACE_CURVE('',#168559,(#168563,#168570),.PCURVE_S1.); -#168559 = LINE('',#168560,#168561); -#168560 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); -#168561 = VECTOR('',#168562,1.); -#168562 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168563 = PCURVE('',#168357,#168564); -#168564 = DEFINITIONAL_REPRESENTATION('',(#168565),#168569); -#168565 = LINE('',#168566,#168567); -#168566 = CARTESIAN_POINT('',(0.E+000,-0.175)); -#168567 = VECTOR('',#168568,1.); -#168568 = DIRECTION('',(-1.,0.E+000)); -#168569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168570 = PCURVE('',#168437,#168571); -#168571 = DEFINITIONAL_REPRESENTATION('',(#168572),#168576); -#168572 = LINE('',#168573,#168574); -#168573 = CARTESIAN_POINT('',(0.75,0.E+000)); -#168574 = VECTOR('',#168575,1.); -#168575 = DIRECTION('',(0.E+000,1.)); -#168576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168577 = ADVANCED_FACE('',(#168578),#168437,.T.); -#168578 = FACE_BOUND('',#168579,.T.); -#168579 = EDGE_LOOP('',(#168580,#168581,#168582,#168583)); -#168580 = ORIENTED_EDGE('',*,*,#168526,.T.); -#168581 = ORIENTED_EDGE('',*,*,#168557,.T.); -#168582 = ORIENTED_EDGE('',*,*,#168423,.T.); -#168583 = ORIENTED_EDGE('',*,*,#168475,.T.); -#168584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168588)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#168585,#168586,#168587)) +#170456 = ADVANCED_FACE('',(#170457),#170391,.T.); +#170457 = FACE_BOUND('',#170458,.T.); +#170458 = EDGE_LOOP('',(#170459,#170482,#170510,#170531)); +#170459 = ORIENTED_EDGE('',*,*,#170460,.T.); +#170460 = EDGE_CURVE('',#170343,#170461,#170463,.T.); +#170461 = VERTEX_POINT('',#170462); +#170462 = CARTESIAN_POINT('',(-0.75,0.175,-0.4)); +#170463 = SURFACE_CURVE('',#170464,(#170468,#170475),.PCURVE_S1.); +#170464 = LINE('',#170465,#170466); +#170465 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,-0.4)); +#170466 = VECTOR('',#170467,1.); +#170467 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170468 = PCURVE('',#170391,#170469); +#170469 = DEFINITIONAL_REPRESENTATION('',(#170470),#170474); +#170470 = LINE('',#170471,#170472); +#170471 = CARTESIAN_POINT('',(-0.675,0.E+000)); +#170472 = VECTOR('',#170473,1.); +#170473 = DIRECTION('',(1.,2.882261016903E-032)); +#170474 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170475 = PCURVE('',#170363,#170476); +#170476 = DEFINITIONAL_REPRESENTATION('',(#170477),#170481); +#170477 = LINE('',#170478,#170479); +#170478 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); +#170479 = VECTOR('',#170480,1.); +#170480 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170482 = ORIENTED_EDGE('',*,*,#170483,.F.); +#170483 = EDGE_CURVE('',#170484,#170461,#170486,.T.); +#170484 = VERTEX_POINT('',#170485); +#170485 = CARTESIAN_POINT('',(-0.75,0.175,0.4)); +#170486 = SURFACE_CURVE('',#170487,(#170491,#170498),.PCURVE_S1.); +#170487 = LINE('',#170488,#170489); +#170488 = CARTESIAN_POINT('',(-0.75,0.175,-0.4)); +#170489 = VECTOR('',#170490,1.); +#170490 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170491 = PCURVE('',#170391,#170492); +#170492 = DEFINITIONAL_REPRESENTATION('',(#170493),#170497); +#170493 = LINE('',#170494,#170495); +#170494 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); +#170495 = VECTOR('',#170496,1.); +#170496 = DIRECTION('',(0.E+000,-1.)); +#170497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170498 = PCURVE('',#170499,#170504); +#170499 = PLANE('',#170500); +#170500 = AXIS2_PLACEMENT_3D('',#170501,#170502,#170503); +#170501 = CARTESIAN_POINT('',(-0.75,2.775557561563E-016,-0.4)); +#170502 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#170503 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170504 = DEFINITIONAL_REPRESENTATION('',(#170505),#170509); +#170505 = LINE('',#170506,#170507); +#170506 = CARTESIAN_POINT('',(0.E+000,0.175)); +#170507 = VECTOR('',#170508,1.); +#170508 = DIRECTION('',(-1.,0.E+000)); +#170509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170510 = ORIENTED_EDGE('',*,*,#170511,.F.); +#170511 = EDGE_CURVE('',#170376,#170484,#170512,.T.); +#170512 = SURFACE_CURVE('',#170513,(#170517,#170524),.PCURVE_S1.); +#170513 = LINE('',#170514,#170515); +#170514 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,0.4)); +#170515 = VECTOR('',#170516,1.); +#170516 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170517 = PCURVE('',#170391,#170518); +#170518 = DEFINITIONAL_REPRESENTATION('',(#170519),#170523); +#170519 = LINE('',#170520,#170521); +#170520 = CARTESIAN_POINT('',(-0.675,0.8)); +#170521 = VECTOR('',#170522,1.); +#170522 = DIRECTION('',(1.,2.882261016903E-032)); +#170523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170524 = PCURVE('',#170419,#170525); +#170525 = DEFINITIONAL_REPRESENTATION('',(#170526),#170530); +#170526 = LINE('',#170527,#170528); +#170527 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); +#170528 = VECTOR('',#170529,1.); +#170529 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170531 = ORIENTED_EDGE('',*,*,#170375,.T.); +#170532 = ADVANCED_FACE('',(#170533),#170547,.T.); +#170533 = FACE_BOUND('',#170534,.T.); +#170534 = EDGE_LOOP('',(#170535,#170565,#170588,#170611)); +#170535 = ORIENTED_EDGE('',*,*,#170536,.T.); +#170536 = EDGE_CURVE('',#170537,#170539,#170541,.T.); +#170537 = VERTEX_POINT('',#170538); +#170538 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); +#170539 = VERTEX_POINT('',#170540); +#170540 = CARTESIAN_POINT('',(0.6,0.235,-0.4)); +#170541 = SURFACE_CURVE('',#170542,(#170546,#170558),.PCURVE_S1.); +#170542 = LINE('',#170543,#170544); +#170543 = CARTESIAN_POINT('',(0.6,2.528795811518E-002,-0.4)); +#170544 = VECTOR('',#170545,1.); +#170545 = DIRECTION('',(0.E+000,1.,-2.314036761889E-031)); +#170546 = PCURVE('',#170547,#170552); +#170547 = PLANE('',#170548); +#170548 = AXIS2_PLACEMENT_3D('',#170549,#170550,#170551); +#170549 = CARTESIAN_POINT('',(0.6,0.205,-0.4)); +#170550 = DIRECTION('',(1.,0.E+000,0.E+000)); +#170551 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170552 = DEFINITIONAL_REPRESENTATION('',(#170553),#170557); +#170553 = LINE('',#170554,#170555); +#170554 = CARTESIAN_POINT('',(0.E+000,-0.179712041885)); +#170555 = VECTOR('',#170556,1.); +#170556 = DIRECTION('',(2.314036761889E-031,1.)); +#170557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170558 = PCURVE('',#170363,#170559); +#170559 = DEFINITIONAL_REPRESENTATION('',(#170560),#170564); +#170560 = LINE('',#170561,#170562); +#170561 = CARTESIAN_POINT('',(0.E+000,0.6)); +#170562 = VECTOR('',#170563,1.); +#170563 = DIRECTION('',(-1.,-1.138557377869E-079)); +#170564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170565 = ORIENTED_EDGE('',*,*,#170566,.F.); +#170566 = EDGE_CURVE('',#170567,#170539,#170569,.T.); +#170567 = VERTEX_POINT('',#170568); +#170568 = CARTESIAN_POINT('',(0.6,0.235,0.4)); +#170569 = SURFACE_CURVE('',#170570,(#170574,#170581),.PCURVE_S1.); +#170570 = LINE('',#170571,#170572); +#170571 = CARTESIAN_POINT('',(0.6,0.235,-0.4)); +#170572 = VECTOR('',#170573,1.); +#170573 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170574 = PCURVE('',#170547,#170575); +#170575 = DEFINITIONAL_REPRESENTATION('',(#170576),#170580); +#170576 = LINE('',#170577,#170578); +#170577 = CARTESIAN_POINT('',(0.E+000,3.E-002)); +#170578 = VECTOR('',#170579,1.); +#170579 = DIRECTION('',(1.,0.E+000)); +#170580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170581 = PCURVE('',#170445,#170582); +#170582 = DEFINITIONAL_REPRESENTATION('',(#170583),#170587); +#170583 = LINE('',#170584,#170585); +#170584 = CARTESIAN_POINT('',(-0.6,0.E+000)); +#170585 = VECTOR('',#170586,1.); +#170586 = DIRECTION('',(0.E+000,-1.)); +#170587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170588 = ORIENTED_EDGE('',*,*,#170589,.F.); +#170589 = EDGE_CURVE('',#170590,#170567,#170592,.T.); +#170590 = VERTEX_POINT('',#170591); +#170591 = CARTESIAN_POINT('',(0.6,0.175,0.4)); +#170592 = SURFACE_CURVE('',#170593,(#170597,#170604),.PCURVE_S1.); +#170593 = LINE('',#170594,#170595); +#170594 = CARTESIAN_POINT('',(0.6,2.528795811518E-002,0.4)); +#170595 = VECTOR('',#170596,1.); +#170596 = DIRECTION('',(0.E+000,1.,-2.314036761889E-031)); +#170597 = PCURVE('',#170547,#170598); +#170598 = DEFINITIONAL_REPRESENTATION('',(#170599),#170603); +#170599 = LINE('',#170600,#170601); +#170600 = CARTESIAN_POINT('',(-0.8,-0.179712041885)); +#170601 = VECTOR('',#170602,1.); +#170602 = DIRECTION('',(2.314036761889E-031,1.)); +#170603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170604 = PCURVE('',#170419,#170605); +#170605 = DEFINITIONAL_REPRESENTATION('',(#170606),#170610); +#170606 = LINE('',#170607,#170608); +#170607 = CARTESIAN_POINT('',(0.E+000,0.6)); +#170608 = VECTOR('',#170609,1.); +#170609 = DIRECTION('',(-1.,-1.138557377869E-079)); +#170610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170611 = ORIENTED_EDGE('',*,*,#170612,.F.); +#170612 = EDGE_CURVE('',#170537,#170590,#170613,.T.); +#170613 = SURFACE_CURVE('',#170614,(#170618,#170625),.PCURVE_S1.); +#170614 = LINE('',#170615,#170616); +#170615 = CARTESIAN_POINT('',(0.6,0.175,-0.4)); +#170616 = VECTOR('',#170617,1.); +#170617 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170618 = PCURVE('',#170547,#170619); +#170619 = DEFINITIONAL_REPRESENTATION('',(#170620),#170624); +#170620 = LINE('',#170621,#170622); +#170621 = CARTESIAN_POINT('',(0.E+000,-3.E-002)); +#170622 = VECTOR('',#170623,1.); +#170623 = DIRECTION('',(-1.,0.E+000)); +#170624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170625 = PCURVE('',#170626,#170631); +#170626 = PLANE('',#170627); +#170627 = AXIS2_PLACEMENT_3D('',#170628,#170629,#170630); +#170628 = CARTESIAN_POINT('',(0.675,0.175,-0.4)); +#170629 = DIRECTION('',(-2.312964634636E-016,1.,0.E+000)); +#170630 = DIRECTION('',(-1.,-2.312964634636E-016,0.E+000)); +#170631 = DEFINITIONAL_REPRESENTATION('',(#170632),#170636); +#170632 = LINE('',#170633,#170634); +#170633 = CARTESIAN_POINT('',(7.5E-002,0.E+000)); +#170634 = VECTOR('',#170635,1.); +#170635 = DIRECTION('',(0.E+000,1.)); +#170636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170637 = ADVANCED_FACE('',(#170638),#170445,.T.); +#170638 = FACE_BOUND('',#170639,.T.); +#170639 = EDGE_LOOP('',(#170640,#170661,#170662,#170683)); +#170640 = ORIENTED_EDGE('',*,*,#170641,.T.); +#170641 = EDGE_CURVE('',#170539,#170341,#170642,.T.); +#170642 = SURFACE_CURVE('',#170643,(#170647,#170654),.PCURVE_S1.); +#170643 = LINE('',#170644,#170645); +#170644 = CARTESIAN_POINT('',(-1.149254302835E-016,0.235,-0.4)); +#170645 = VECTOR('',#170646,1.); +#170646 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170647 = PCURVE('',#170445,#170648); +#170648 = DEFINITIONAL_REPRESENTATION('',(#170649),#170653); +#170649 = LINE('',#170650,#170651); +#170650 = CARTESIAN_POINT('',(1.149254302835E-016,0.E+000)); +#170651 = VECTOR('',#170652,1.); +#170652 = DIRECTION('',(1.,2.882261016903E-032)); +#170653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170654 = PCURVE('',#170363,#170655); +#170655 = DEFINITIONAL_REPRESENTATION('',(#170656),#170660); +#170656 = LINE('',#170657,#170658); +#170657 = CARTESIAN_POINT('',(-0.209712041885,-1.398707587467E-063)); +#170658 = VECTOR('',#170659,1.); +#170659 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170661 = ORIENTED_EDGE('',*,*,#170431,.T.); +#170662 = ORIENTED_EDGE('',*,*,#170663,.F.); +#170663 = EDGE_CURVE('',#170567,#170404,#170664,.T.); +#170664 = SURFACE_CURVE('',#170665,(#170669,#170676),.PCURVE_S1.); +#170665 = LINE('',#170666,#170667); +#170666 = CARTESIAN_POINT('',(-1.149254302835E-016,0.235,0.4)); +#170667 = VECTOR('',#170668,1.); +#170668 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170669 = PCURVE('',#170445,#170670); +#170670 = DEFINITIONAL_REPRESENTATION('',(#170671),#170675); +#170671 = LINE('',#170672,#170673); +#170672 = CARTESIAN_POINT('',(1.149254302835E-016,0.8)); +#170673 = VECTOR('',#170674,1.); +#170674 = DIRECTION('',(1.,2.882261016903E-032)); +#170675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170676 = PCURVE('',#170419,#170677); +#170677 = DEFINITIONAL_REPRESENTATION('',(#170678),#170682); +#170678 = LINE('',#170679,#170680); +#170679 = CARTESIAN_POINT('',(-0.209712041885,-1.398707587467E-063)); +#170680 = VECTOR('',#170681,1.); +#170681 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170683 = ORIENTED_EDGE('',*,*,#170566,.T.); +#170684 = ADVANCED_FACE('',(#170685),#170626,.T.); +#170685 = FACE_BOUND('',#170686,.T.); +#170686 = EDGE_LOOP('',(#170687,#170710,#170711,#170734)); +#170687 = ORIENTED_EDGE('',*,*,#170688,.T.); +#170688 = EDGE_CURVE('',#170689,#170537,#170691,.T.); +#170689 = VERTEX_POINT('',#170690); +#170690 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); +#170691 = SURFACE_CURVE('',#170692,(#170696,#170703),.PCURVE_S1.); +#170692 = LINE('',#170693,#170694); +#170693 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,-0.4)); +#170694 = VECTOR('',#170695,1.); +#170695 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170696 = PCURVE('',#170626,#170697); +#170697 = DEFINITIONAL_REPRESENTATION('',(#170698),#170702); +#170698 = LINE('',#170699,#170700); +#170699 = CARTESIAN_POINT('',(0.675,0.E+000)); +#170700 = VECTOR('',#170701,1.); +#170701 = DIRECTION('',(1.,2.882261016903E-032)); +#170702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170703 = PCURVE('',#170363,#170704); +#170704 = DEFINITIONAL_REPRESENTATION('',(#170705),#170709); +#170705 = LINE('',#170706,#170707); +#170706 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); +#170707 = VECTOR('',#170708,1.); +#170708 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170710 = ORIENTED_EDGE('',*,*,#170612,.T.); +#170711 = ORIENTED_EDGE('',*,*,#170712,.F.); +#170712 = EDGE_CURVE('',#170713,#170590,#170715,.T.); +#170713 = VERTEX_POINT('',#170714); +#170714 = CARTESIAN_POINT('',(0.75,0.175,0.4)); +#170715 = SURFACE_CURVE('',#170716,(#170720,#170727),.PCURVE_S1.); +#170716 = LINE('',#170717,#170718); +#170717 = CARTESIAN_POINT('',(-1.149254302835E-016,0.175,0.4)); +#170718 = VECTOR('',#170719,1.); +#170719 = DIRECTION('',(-1.,6.669657950473E-063,2.882261016903E-032)); +#170720 = PCURVE('',#170626,#170721); +#170721 = DEFINITIONAL_REPRESENTATION('',(#170722),#170726); +#170722 = LINE('',#170723,#170724); +#170723 = CARTESIAN_POINT('',(0.675,0.8)); +#170724 = VECTOR('',#170725,1.); +#170725 = DIRECTION('',(1.,2.882261016903E-032)); +#170726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170727 = PCURVE('',#170419,#170728); +#170728 = DEFINITIONAL_REPRESENTATION('',(#170729),#170733); +#170729 = LINE('',#170730,#170731); +#170730 = CARTESIAN_POINT('',(-0.149712041885,-9.985281104386E-064)); +#170731 = VECTOR('',#170732,1.); +#170732 = DIRECTION('',(-1.138557377869E-079,-1.)); +#170733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170734 = ORIENTED_EDGE('',*,*,#170735,.F.); +#170735 = EDGE_CURVE('',#170689,#170713,#170736,.T.); +#170736 = SURFACE_CURVE('',#170737,(#170741,#170748),.PCURVE_S1.); +#170737 = LINE('',#170738,#170739); +#170738 = CARTESIAN_POINT('',(0.75,0.175,-0.4)); +#170739 = VECTOR('',#170740,1.); +#170740 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170741 = PCURVE('',#170626,#170742); +#170742 = DEFINITIONAL_REPRESENTATION('',(#170743),#170747); +#170743 = LINE('',#170744,#170745); +#170744 = CARTESIAN_POINT('',(-7.5E-002,0.E+000)); +#170745 = VECTOR('',#170746,1.); +#170746 = DIRECTION('',(0.E+000,1.)); +#170747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170748 = PCURVE('',#170749,#170754); +#170749 = PLANE('',#170750); +#170750 = AXIS2_PLACEMENT_3D('',#170751,#170752,#170753); +#170751 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,-0.4)); +#170752 = DIRECTION('',(1.,0.E+000,0.E+000)); +#170753 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170754 = DEFINITIONAL_REPRESENTATION('',(#170755),#170759); +#170755 = LINE('',#170756,#170757); +#170756 = CARTESIAN_POINT('',(0.E+000,0.175)); +#170757 = VECTOR('',#170758,1.); +#170758 = DIRECTION('',(-1.,0.E+000)); +#170759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170760 = ADVANCED_FACE('',(#170761),#170419,.T.); +#170761 = FACE_BOUND('',#170762,.T.); +#170762 = EDGE_LOOP('',(#170763,#170786,#170787,#170788,#170789,#170790, + #170791,#170814)); +#170763 = ORIENTED_EDGE('',*,*,#170764,.F.); +#170764 = EDGE_CURVE('',#170713,#170765,#170767,.T.); +#170765 = VERTEX_POINT('',#170766); +#170766 = CARTESIAN_POINT('',(0.75,-0.175,0.4)); +#170767 = SURFACE_CURVE('',#170768,(#170772,#170779),.PCURVE_S1.); +#170768 = LINE('',#170769,#170770); +#170769 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,0.4)); +#170770 = VECTOR('',#170771,1.); +#170771 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#170772 = PCURVE('',#170419,#170773); +#170773 = DEFINITIONAL_REPRESENTATION('',(#170774),#170778); +#170774 = LINE('',#170775,#170776); +#170775 = CARTESIAN_POINT('',(2.528795811518E-002,0.75)); +#170776 = VECTOR('',#170777,1.); +#170777 = DIRECTION('',(1.,6.669657950473E-063)); +#170778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170779 = PCURVE('',#170749,#170780); +#170780 = DEFINITIONAL_REPRESENTATION('',(#170781),#170785); +#170781 = LINE('',#170782,#170783); +#170782 = CARTESIAN_POINT('',(-0.8,0.E+000)); +#170783 = VECTOR('',#170784,1.); +#170784 = DIRECTION('',(0.E+000,-1.)); +#170785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170786 = ORIENTED_EDGE('',*,*,#170712,.T.); +#170787 = ORIENTED_EDGE('',*,*,#170589,.T.); +#170788 = ORIENTED_EDGE('',*,*,#170663,.T.); +#170789 = ORIENTED_EDGE('',*,*,#170403,.T.); +#170790 = ORIENTED_EDGE('',*,*,#170511,.T.); +#170791 = ORIENTED_EDGE('',*,*,#170792,.F.); +#170792 = EDGE_CURVE('',#170793,#170484,#170795,.T.); +#170793 = VERTEX_POINT('',#170794); +#170794 = CARTESIAN_POINT('',(-0.75,-0.175,0.4)); +#170795 = SURFACE_CURVE('',#170796,(#170800,#170807),.PCURVE_S1.); +#170796 = LINE('',#170797,#170798); +#170797 = CARTESIAN_POINT('',(-0.75,2.775557561563E-016,0.4)); +#170798 = VECTOR('',#170799,1.); +#170799 = DIRECTION('',(0.E+000,1.,0.E+000)); +#170800 = PCURVE('',#170419,#170801); +#170801 = DEFINITIONAL_REPRESENTATION('',(#170802),#170806); +#170802 = LINE('',#170803,#170804); +#170803 = CARTESIAN_POINT('',(2.528795811518E-002,-0.75)); +#170804 = VECTOR('',#170805,1.); +#170805 = DIRECTION('',(-1.,-6.669657950473E-063)); +#170806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170807 = PCURVE('',#170499,#170808); +#170808 = DEFINITIONAL_REPRESENTATION('',(#170809),#170813); +#170809 = LINE('',#170810,#170811); +#170810 = CARTESIAN_POINT('',(0.8,0.E+000)); +#170811 = VECTOR('',#170812,1.); +#170812 = DIRECTION('',(0.E+000,1.)); +#170813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170814 = ORIENTED_EDGE('',*,*,#170815,.F.); +#170815 = EDGE_CURVE('',#170765,#170793,#170816,.T.); +#170816 = SURFACE_CURVE('',#170817,(#170821,#170828),.PCURVE_S1.); +#170817 = LINE('',#170818,#170819); +#170818 = CARTESIAN_POINT('',(0.E+000,-0.175,0.4)); +#170819 = VECTOR('',#170820,1.); +#170820 = DIRECTION('',(-1.,-3.469446951954E-016,0.E+000)); +#170821 = PCURVE('',#170419,#170822); +#170822 = DEFINITIONAL_REPRESENTATION('',(#170823),#170827); +#170823 = LINE('',#170824,#170825); +#170824 = CARTESIAN_POINT('',(0.200287958115,1.149254302835E-016)); +#170825 = VECTOR('',#170826,1.); +#170826 = DIRECTION('',(3.469446951954E-016,-1.)); +#170827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170828 = PCURVE('',#170829,#170834); +#170829 = PLANE('',#170830); +#170830 = AXIS2_PLACEMENT_3D('',#170831,#170832,#170833); +#170831 = CARTESIAN_POINT('',(0.E+000,-0.175,-0.4)); +#170832 = DIRECTION('',(3.469446951954E-016,-1.,0.E+000)); +#170833 = DIRECTION('',(1.,3.469446951954E-016,0.E+000)); +#170834 = DEFINITIONAL_REPRESENTATION('',(#170835),#170839); +#170835 = LINE('',#170836,#170837); +#170836 = CARTESIAN_POINT('',(0.E+000,0.8)); +#170837 = VECTOR('',#170838,1.); +#170838 = DIRECTION('',(-1.,0.E+000)); +#170839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170840 = ADVANCED_FACE('',(#170841),#170499,.T.); +#170841 = FACE_BOUND('',#170842,.T.); +#170842 = EDGE_LOOP('',(#170843,#170866,#170887,#170888)); +#170843 = ORIENTED_EDGE('',*,*,#170844,.T.); +#170844 = EDGE_CURVE('',#170461,#170845,#170847,.T.); +#170845 = VERTEX_POINT('',#170846); +#170846 = CARTESIAN_POINT('',(-0.75,-0.175,-0.4)); +#170847 = SURFACE_CURVE('',#170848,(#170852,#170859),.PCURVE_S1.); +#170848 = LINE('',#170849,#170850); +#170849 = CARTESIAN_POINT('',(-0.75,2.528795811518E-002,-0.4)); +#170850 = VECTOR('',#170851,1.); +#170851 = DIRECTION('',(0.E+000,-1.,2.314036761889E-031)); +#170852 = PCURVE('',#170499,#170853); +#170853 = DEFINITIONAL_REPRESENTATION('',(#170854),#170858); +#170854 = LINE('',#170855,#170856); +#170855 = CARTESIAN_POINT('',(0.E+000,2.528795811518E-002)); +#170856 = VECTOR('',#170857,1.); +#170857 = DIRECTION('',(2.314036761889E-031,-1.)); +#170858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170859 = PCURVE('',#170363,#170860); +#170860 = DEFINITIONAL_REPRESENTATION('',(#170861),#170865); +#170861 = LINE('',#170862,#170863); +#170862 = CARTESIAN_POINT('',(0.E+000,-0.75)); +#170863 = VECTOR('',#170864,1.); +#170864 = DIRECTION('',(1.,1.138557377869E-079)); +#170865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170866 = ORIENTED_EDGE('',*,*,#170867,.F.); +#170867 = EDGE_CURVE('',#170793,#170845,#170868,.T.); +#170868 = SURFACE_CURVE('',#170869,(#170873,#170880),.PCURVE_S1.); +#170869 = LINE('',#170870,#170871); +#170870 = CARTESIAN_POINT('',(-0.75,-0.175,-0.4)); +#170871 = VECTOR('',#170872,1.); +#170872 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#170873 = PCURVE('',#170499,#170874); +#170874 = DEFINITIONAL_REPRESENTATION('',(#170875),#170879); +#170875 = LINE('',#170876,#170877); +#170876 = CARTESIAN_POINT('',(0.E+000,-0.175)); +#170877 = VECTOR('',#170878,1.); +#170878 = DIRECTION('',(-1.,0.E+000)); +#170879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170880 = PCURVE('',#170829,#170881); +#170881 = DEFINITIONAL_REPRESENTATION('',(#170882),#170886); +#170882 = LINE('',#170883,#170884); +#170883 = CARTESIAN_POINT('',(-0.75,0.E+000)); +#170884 = VECTOR('',#170885,1.); +#170885 = DIRECTION('',(0.E+000,-1.)); +#170886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170887 = ORIENTED_EDGE('',*,*,#170792,.T.); +#170888 = ORIENTED_EDGE('',*,*,#170483,.T.); +#170889 = ADVANCED_FACE('',(#170890),#170363,.F.); +#170890 = FACE_BOUND('',#170891,.T.); +#170891 = EDGE_LOOP('',(#170892,#170893,#170894,#170917,#170938,#170939, + #170940,#170941)); +#170892 = ORIENTED_EDGE('',*,*,#170536,.F.); +#170893 = ORIENTED_EDGE('',*,*,#170688,.F.); +#170894 = ORIENTED_EDGE('',*,*,#170895,.F.); +#170895 = EDGE_CURVE('',#170896,#170689,#170898,.T.); +#170896 = VERTEX_POINT('',#170897); +#170897 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); +#170898 = SURFACE_CURVE('',#170899,(#170903,#170910),.PCURVE_S1.); +#170899 = LINE('',#170900,#170901); +#170900 = CARTESIAN_POINT('',(0.75,5.20417042793E-016,-0.4)); +#170901 = VECTOR('',#170902,1.); +#170902 = DIRECTION('',(0.E+000,1.,0.E+000)); +#170903 = PCURVE('',#170363,#170904); +#170904 = DEFINITIONAL_REPRESENTATION('',(#170905),#170909); +#170905 = LINE('',#170906,#170907); +#170906 = CARTESIAN_POINT('',(2.528795811518E-002,0.75)); +#170907 = VECTOR('',#170908,1.); +#170908 = DIRECTION('',(-1.,-6.669657950473E-063)); +#170909 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170910 = PCURVE('',#170749,#170911); +#170911 = DEFINITIONAL_REPRESENTATION('',(#170912),#170916); +#170912 = LINE('',#170913,#170914); +#170913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#170914 = VECTOR('',#170915,1.); +#170915 = DIRECTION('',(0.E+000,1.)); +#170916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170917 = ORIENTED_EDGE('',*,*,#170918,.F.); +#170918 = EDGE_CURVE('',#170845,#170896,#170919,.T.); +#170919 = SURFACE_CURVE('',#170920,(#170924,#170931),.PCURVE_S1.); +#170920 = LINE('',#170921,#170922); +#170921 = CARTESIAN_POINT('',(0.E+000,-0.175,-0.4)); +#170922 = VECTOR('',#170923,1.); +#170923 = DIRECTION('',(1.,3.469446951954E-016,0.E+000)); +#170924 = PCURVE('',#170363,#170925); +#170925 = DEFINITIONAL_REPRESENTATION('',(#170926),#170930); +#170926 = LINE('',#170927,#170928); +#170927 = CARTESIAN_POINT('',(0.200287958115,1.149254302835E-016)); +#170928 = VECTOR('',#170929,1.); +#170929 = DIRECTION('',(-3.469446951954E-016,1.)); +#170930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170931 = PCURVE('',#170829,#170932); +#170932 = DEFINITIONAL_REPRESENTATION('',(#170933),#170937); +#170933 = LINE('',#170934,#170935); +#170934 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#170935 = VECTOR('',#170936,1.); +#170936 = DIRECTION('',(1.,0.E+000)); +#170937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170938 = ORIENTED_EDGE('',*,*,#170844,.F.); +#170939 = ORIENTED_EDGE('',*,*,#170460,.F.); +#170940 = ORIENTED_EDGE('',*,*,#170340,.F.); +#170941 = ORIENTED_EDGE('',*,*,#170641,.F.); +#170942 = ADVANCED_FACE('',(#170943),#170749,.T.); +#170943 = FACE_BOUND('',#170944,.T.); +#170944 = EDGE_LOOP('',(#170945,#170946,#170947,#170948)); +#170945 = ORIENTED_EDGE('',*,*,#170895,.T.); +#170946 = ORIENTED_EDGE('',*,*,#170735,.T.); +#170947 = ORIENTED_EDGE('',*,*,#170764,.T.); +#170948 = ORIENTED_EDGE('',*,*,#170949,.F.); +#170949 = EDGE_CURVE('',#170896,#170765,#170950,.T.); +#170950 = SURFACE_CURVE('',#170951,(#170955,#170962),.PCURVE_S1.); +#170951 = LINE('',#170952,#170953); +#170952 = CARTESIAN_POINT('',(0.75,-0.175,-0.4)); +#170953 = VECTOR('',#170954,1.); +#170954 = DIRECTION('',(0.E+000,0.E+000,1.)); +#170955 = PCURVE('',#170749,#170956); +#170956 = DEFINITIONAL_REPRESENTATION('',(#170957),#170961); +#170957 = LINE('',#170958,#170959); +#170958 = CARTESIAN_POINT('',(0.E+000,-0.175)); +#170959 = VECTOR('',#170960,1.); +#170960 = DIRECTION('',(-1.,0.E+000)); +#170961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170962 = PCURVE('',#170829,#170963); +#170963 = DEFINITIONAL_REPRESENTATION('',(#170964),#170968); +#170964 = LINE('',#170965,#170966); +#170965 = CARTESIAN_POINT('',(0.75,0.E+000)); +#170966 = VECTOR('',#170967,1.); +#170967 = DIRECTION('',(0.E+000,1.)); +#170968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#170969 = ADVANCED_FACE('',(#170970),#170829,.T.); +#170970 = FACE_BOUND('',#170971,.T.); +#170971 = EDGE_LOOP('',(#170972,#170973,#170974,#170975)); +#170972 = ORIENTED_EDGE('',*,*,#170918,.T.); +#170973 = ORIENTED_EDGE('',*,*,#170949,.T.); +#170974 = ORIENTED_EDGE('',*,*,#170815,.T.); +#170975 = ORIENTED_EDGE('',*,*,#170867,.T.); +#170976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#170980)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#170977,#170978,#170979)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#168585 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#168586 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#168587 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#168588 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#168585, +#170977 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#170978 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#170979 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#170980 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#170977, 'distance_accuracy_value','confusion accuracy'); -#168589 = SHAPE_DEFINITION_REPRESENTATION(#168590,#167941); -#168590 = PRODUCT_DEFINITION_SHAPE('','',#168591); -#168591 = PRODUCT_DEFINITION('design','',#168592,#168595); -#168592 = PRODUCT_DEFINITION_FORMATION('','',#168593); -#168593 = PRODUCT('User_Library-RES_0603L_RES_0603_Body_1', - 'User_Library-RES_0603L_RES_0603_Body_1','',(#168594)); -#168594 = PRODUCT_CONTEXT('',#2,'mechanical'); -#168595 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#168596 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168597,#168599); -#168597 = ( REPRESENTATION_RELATIONSHIP('','',#167941,#167262) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168598) +#170981 = SHAPE_DEFINITION_REPRESENTATION(#170982,#170333); +#170982 = PRODUCT_DEFINITION_SHAPE('','',#170983); +#170983 = PRODUCT_DEFINITION('design','',#170984,#170987); +#170984 = PRODUCT_DEFINITION_FORMATION('','',#170985); +#170985 = PRODUCT('User_Library-RES_0603L_RES_0603_Body_1', + 'User_Library-RES_0603L_RES_0603_Body_1','',(#170986)); +#170986 = PRODUCT_CONTEXT('',#2,'mechanical'); +#170987 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#170988 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#170989,#170991); +#170989 = ( REPRESENTATION_RELATIONSHIP('','',#170333,#169654) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#170990) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#168598 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167267); -#168599 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #168600); -#168600 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('304','','',#167257,#168591,$); -#168601 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168593)); -#168602 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168603,#168605); -#168603 = ( REPRESENTATION_RELATIONSHIP('','',#167280,#167262) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168604) +#170990 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169659); +#170991 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #170992); +#170992 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('405','','',#169649,#170983,$); +#170993 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#170985)); +#170994 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#170995,#170997); +#170995 = ( REPRESENTATION_RELATIONSHIP('','',#169672,#169654) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#170996) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#168604 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167271); -#168605 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #168606); -#168606 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('305','','',#167257,#167930,$); -#168607 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168608,#168610); -#168608 = ( REPRESENTATION_RELATIONSHIP('','',#167262,#167245) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168609) +#170996 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169663); +#170997 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #170998); +#170998 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('406','','',#169649,#170322,$); +#170999 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#171000,#171002); +#171000 = ( REPRESENTATION_RELATIONSHIP('','',#169654,#169637) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#171001) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#168609 = ITEM_DEFINED_TRANSFORMATION('','',#11,#167246); -#168610 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #168611); -#168611 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('306','=>[0:1:1:103]','', - #167240,#167257,$); -#168612 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167259)); -#168613 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#168614,#168616); -#168614 = ( REPRESENTATION_RELATIONSHIP('','',#167245,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#168615) +#171001 = ITEM_DEFINED_TRANSFORMATION('','',#11,#169638); +#171002 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #171003); +#171003 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('407','=>[0:1:1:103]','', + #169632,#169649,$); +#171004 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169651)); +#171005 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#171006,#171008); +#171006 = ( REPRESENTATION_RELATIONSHIP('','',#169637,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#171007) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#168615 = ITEM_DEFINED_TRANSFORMATION('','',#11,#279); -#168616 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #168617); -#168617 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('307','=>[0:1:1:102]','',#5, - #167240,$); -#168618 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#167242)); -#168619 = SHAPE_DEFINITION_REPRESENTATION(#168620,#168626); -#168620 = PRODUCT_DEFINITION_SHAPE('','',#168621); -#168621 = PRODUCT_DEFINITION('design','',#168622,#168625); -#168622 = PRODUCT_DEFINITION_FORMATION('','',#168623); -#168623 = PRODUCT('U3','U3','',(#168624)); -#168624 = PRODUCT_CONTEXT('',#2,'mechanical'); -#168625 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#168626 = SHAPE_REPRESENTATION('',(#11,#168627),#168631); -#168627 = AXIS2_PLACEMENT_3D('',#168628,#168629,#168630); -#168628 = CARTESIAN_POINT('',(8.76291872,24.51108128,1.27E-002)); -#168629 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168630 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#168631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#168635)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#168632,#168633,#168634)) +#171007 = ITEM_DEFINED_TRANSFORMATION('','',#11,#279); +#171008 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #171009); +#171009 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('408','=>[0:1:1:102]','',#5, + #169632,$); +#171010 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#169634)); +#171011 = SHAPE_DEFINITION_REPRESENTATION(#171012,#171018); +#171012 = PRODUCT_DEFINITION_SHAPE('','',#171013); +#171013 = PRODUCT_DEFINITION('design','',#171014,#171017); +#171014 = PRODUCT_DEFINITION_FORMATION('','',#171015); +#171015 = PRODUCT('U3','U3','',(#171016)); +#171016 = PRODUCT_CONTEXT('',#2,'mechanical'); +#171017 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#171018 = SHAPE_REPRESENTATION('',(#11,#171019),#171023); +#171019 = AXIS2_PLACEMENT_3D('',#171020,#171021,#171022); +#171020 = CARTESIAN_POINT('',(8.76291872,24.51108128,1.27E-002)); +#171021 = DIRECTION('',(0.E+000,0.E+000,1.)); +#171022 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#171023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#171027)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#171024,#171025,#171026)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#168632 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#168633 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#168634 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#168635 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#168632, +#171024 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#171025 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#171026 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#171027 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#171024, 'distance_accuracy_value','confusion accuracy'); -#168636 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#168637),#182344); -#168637 = MANIFOLD_SOLID_BREP('',#168638); -#168638 = CLOSED_SHELL('',(#168639,#168942,#169217,#169492,#169767, - #170047,#170322,#170597,#170872,#171024,#171598,#171767,#172117, - #172286,#172506,#172827,#172962,#173097,#173541,#173909,#173984, - #174059,#174313,#174532,#174558,#174584,#174633,#174660,#174687, - #174736,#174762,#174788,#174795,#174870,#174945,#175199,#175418, - #175444,#175470,#175519,#175546,#175573,#175622,#175648,#175674, - #175681,#175819,#175892,#176030,#176103,#176241,#176314,#176452, - #176525,#176575,#176580,#176629,#176636,#176685,#176734,#176741, - #176748,#176797,#176804,#176853,#176902,#176909,#176916,#176965, - #177014,#177021,#177028,#177103,#177384,#177432,#177651,#177677, - #177703,#177752,#177779,#177806,#177855,#177881,#177907,#177914, - #177989,#178270,#178318,#178537,#178563,#178589,#178638,#178665, - #178692,#178741,#178767,#178793,#178800,#178875,#179156,#179204, - #179423,#179449,#179475,#179524,#179551,#179578,#179627,#179653, - #179679,#179686,#179761,#180042,#180090,#180309,#180335,#180361, - #180410,#180437,#180464,#180513,#180539,#180565,#180572,#180647, - #180928,#180976,#181195,#181221,#181247,#181296,#181323,#181350, - #181399,#181425,#181451,#181458,#181533,#181814,#181862,#182081, - #182107,#182133,#182182,#182209,#182236,#182285,#182311,#182337)); -#168639 = ADVANCED_FACE('',(#168640),#168655,.T.); -#168640 = FACE_BOUND('',#168641,.T.); -#168641 = EDGE_LOOP('',(#168642,#168713,#168798,#168871)); -#168642 = ORIENTED_EDGE('',*,*,#168643,.F.); -#168643 = EDGE_CURVE('',#168644,#168646,#168648,.T.); -#168644 = VERTEX_POINT('',#168645); -#168645 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); -#168646 = VERTEX_POINT('',#168647); -#168647 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); -#168648 = SURFACE_CURVE('',#168649,(#168654,#168700),.PCURVE_S1.); -#168649 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#168650,#168651,#168652, -#168653),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171028 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#171029),#184736); +#171029 = MANIFOLD_SOLID_BREP('',#171030); +#171030 = CLOSED_SHELL('',(#171031,#171334,#171609,#171884,#172159, + #172439,#172714,#172989,#173264,#173416,#173990,#174159,#174509, + #174678,#174898,#175219,#175354,#175489,#175933,#176301,#176376, + #176451,#176705,#176924,#176950,#176976,#177025,#177052,#177079, + #177128,#177154,#177180,#177187,#177262,#177337,#177591,#177810, + #177836,#177862,#177911,#177938,#177965,#178014,#178040,#178066, + #178073,#178211,#178284,#178422,#178495,#178633,#178706,#178844, + #178917,#178967,#178972,#179021,#179028,#179077,#179126,#179133, + #179140,#179189,#179196,#179245,#179294,#179301,#179308,#179357, + #179406,#179413,#179420,#179495,#179776,#179824,#180043,#180069, + #180095,#180144,#180171,#180198,#180247,#180273,#180299,#180306, + #180381,#180662,#180710,#180929,#180955,#180981,#181030,#181057, + #181084,#181133,#181159,#181185,#181192,#181267,#181548,#181596, + #181815,#181841,#181867,#181916,#181943,#181970,#182019,#182045, + #182071,#182078,#182153,#182434,#182482,#182701,#182727,#182753, + #182802,#182829,#182856,#182905,#182931,#182957,#182964,#183039, + #183320,#183368,#183587,#183613,#183639,#183688,#183715,#183742, + #183791,#183817,#183843,#183850,#183925,#184206,#184254,#184473, + #184499,#184525,#184574,#184601,#184628,#184677,#184703,#184729)); +#171031 = ADVANCED_FACE('',(#171032),#171047,.T.); +#171032 = FACE_BOUND('',#171033,.T.); +#171033 = EDGE_LOOP('',(#171034,#171105,#171190,#171263)); +#171034 = ORIENTED_EDGE('',*,*,#171035,.F.); +#171035 = EDGE_CURVE('',#171036,#171038,#171040,.T.); +#171036 = VERTEX_POINT('',#171037); +#171037 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); +#171038 = VERTEX_POINT('',#171039); +#171039 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); +#171040 = SURFACE_CURVE('',#171041,(#171046,#171092),.PCURVE_S1.); +#171041 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171042,#171043,#171044, +#171045),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.355252715607E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#168650 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); -#168651 = CARTESIAN_POINT('',(1.251596067115,-0.61790129499,1.E-001)); -#168652 = CARTESIAN_POINT('',(1.227584046027,-0.627659054385,1.E-001)); -#168653 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); -#168654 = PCURVE('',#168655,#168672); -#168655 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#168656,#168657,#168658,#168659) - ,(#168660,#168661,#168662,#168663) - ,(#168664,#168665,#168666,#168667) - ,(#168668,#168669,#168670,#168671 +#171042 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); +#171043 = CARTESIAN_POINT('',(1.251596067115,-0.61790129499,1.E-001)); +#171044 = CARTESIAN_POINT('',(1.227584046027,-0.627659054385,1.E-001)); +#171045 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); +#171046 = PCURVE('',#171047,#171064); +#171047 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171048,#171049,#171050,#171051) + ,(#171052,#171053,#171054,#171055) + ,(#171056,#171057,#171058,#171059) + ,(#171060,#171061,#171062,#171063 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#168656 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); -#168657 = CARTESIAN_POINT('',(1.201066471757,-0.649475670035,1.E-001)); -#168658 = CARTESIAN_POINT('',(1.201066471757,-0.67030879007, +#171048 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,1.E-001)); +#171049 = CARTESIAN_POINT('',(1.201066471757,-0.649475670035,1.E-001)); +#171050 = CARTESIAN_POINT('',(1.201066471757,-0.67030879007, 0.115985815246)); -#168659 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, +#171051 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, 0.137059047745)); -#168660 = CARTESIAN_POINT('',(1.22695495248,-0.627659054385,1.E-001)); -#168661 = CARTESIAN_POINT('',(1.232435083194,-0.648429042165,1.E-001)); -#168662 = CARTESIAN_POINT('',(1.237668168966,-0.668443665671, +#171052 = CARTESIAN_POINT('',(1.22695495248,-0.627659054385,1.E-001)); +#171053 = CARTESIAN_POINT('',(1.232435083194,-0.648429042165,1.E-001)); +#171054 = CARTESIAN_POINT('',(1.237668168966,-0.668443665671, 0.114318476015)); -#168663 = CARTESIAN_POINT('',(1.239086531164,-0.675142684022, +#171055 = CARTESIAN_POINT('',(1.239086531164,-0.675142684022, 0.134026153074)); -#168664 = CARTESIAN_POINT('',(1.252026713303,-0.617470648802,1.E-001)); -#168665 = CARTESIAN_POINT('',(1.262452511959,-0.635531311073,1.E-001)); -#168666 = CARTESIAN_POINT('',(1.272532596412,-0.65299309093, +#171056 = CARTESIAN_POINT('',(1.252026713303,-0.617470648802,1.E-001)); +#171057 = CARTESIAN_POINT('',(1.262452511959,-0.635531311073,1.E-001)); +#171058 = CARTESIAN_POINT('',(1.272532596412,-0.65299309093, 0.113446578632)); -#168667 = CARTESIAN_POINT('',(1.276226971076,-0.659392874324,0.132282534 +#171059 = CARTESIAN_POINT('',(1.276226971076,-0.659392874324,0.132282534 )); -#168668 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); -#168669 = CARTESIAN_POINT('',(1.283991911516,-0.613991911516,1.E-001)); -#168670 = CARTESIAN_POINT('',(1.297762843671,-0.627762843671, +#171060 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); +#171061 = CARTESIAN_POINT('',(1.283991911516,-0.613991911516,1.E-001)); +#171062 = CARTESIAN_POINT('',(1.297762843671,-0.627762843671, 0.113446578632)); -#168671 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); -#168672 = DEFINITIONAL_REPRESENTATION('',(#168673),#168699); -#168673 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168674,#168675,#168676, - #168677,#168678,#168679,#168680,#168681,#168682,#168683,#168684, - #168685,#168686,#168687,#168688,#168689,#168690,#168691,#168692, - #168693,#168694,#168695,#168696,#168697,#168698),.UNSPECIFIED.,.F., +#171063 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); +#171064 = DEFINITIONAL_REPRESENTATION('',(#171065),#171091); +#171065 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171066,#171067,#171068, + #171069,#171070,#171071,#171072,#171073,#171074,#171075,#171076, + #171077,#171078,#171079,#171080,#171081,#171082,#171083,#171084, + #171085,#171086,#171087,#171088,#171089,#171090),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.355252715607E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -208161,69 +211163,69 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#168674 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#168675 = CARTESIAN_POINT('',(6.272059569215,1.37531842524E-008)); -#168676 = CARTESIAN_POINT('',(6.24973263213,2.924134009999E-005)); -#168677 = CARTESIAN_POINT('',(6.21603939964,1.413707577617E-004)); -#168678 = CARTESIAN_POINT('',(6.182167276026,3.022859269968E-004)); -#168679 = CARTESIAN_POINT('',(6.148138870073,4.931498468541E-004)); -#168680 = CARTESIAN_POINT('',(6.113975913115,6.962198987745E-004)); -#168681 = CARTESIAN_POINT('',(6.079699188623,8.953387637253E-004)); -#168682 = CARTESIAN_POINT('',(6.045328652128,1.076339414001E-003)); -#168683 = CARTESIAN_POINT('',(6.010883543172,1.227390254481E-003)); -#168684 = CARTESIAN_POINT('',(5.976382533559,1.339263477878E-003)); -#168685 = CARTESIAN_POINT('',(5.941843890817,1.405524714325E-003)); -#168686 = CARTESIAN_POINT('',(5.907285653264,1.422641316493E-003)); -#168687 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); -#168688 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); -#168689 = CARTESIAN_POINT('',(5.803674042174,1.187353930377E-003)); -#168690 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); -#168691 = CARTESIAN_POINT('',(5.734837892756,8.475624467404E-004)); -#168692 = CARTESIAN_POINT('',(5.700549707253,6.520952931811E-004)); -#168693 = CARTESIAN_POINT('',(5.666375694827,4.570658043158E-004)); -#168694 = CARTESIAN_POINT('',(5.632337541793,2.772530388729E-004)); -#168695 = CARTESIAN_POINT('',(5.598457782919,1.282673134862E-004)); -#168696 = CARTESIAN_POINT('',(5.564759695218,2.616756246961E-005)); -#168697 = CARTESIAN_POINT('',(5.542431609433,-2.901324273457E-008)); -#168698 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#168699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168700 = PCURVE('',#168701,#168706); -#168701 = PLANE('',#168702); -#168702 = AXIS2_PLACEMENT_3D('',#168703,#168704,#168705); -#168703 = CARTESIAN_POINT('',(1.47,-0.8,1.E-001)); -#168704 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168705 = DIRECTION('',(1.,0.E+000,0.E+000)); -#168706 = DEFINITIONAL_REPRESENTATION('',(#168707),#168712); -#168707 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#168708,#168709,#168710, -#168711),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171066 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171067 = CARTESIAN_POINT('',(6.272059569215,1.37531842524E-008)); +#171068 = CARTESIAN_POINT('',(6.24973263213,2.924134009999E-005)); +#171069 = CARTESIAN_POINT('',(6.21603939964,1.413707577617E-004)); +#171070 = CARTESIAN_POINT('',(6.182167276026,3.022859269968E-004)); +#171071 = CARTESIAN_POINT('',(6.148138870073,4.931498468541E-004)); +#171072 = CARTESIAN_POINT('',(6.113975913115,6.962198987745E-004)); +#171073 = CARTESIAN_POINT('',(6.079699188623,8.953387637253E-004)); +#171074 = CARTESIAN_POINT('',(6.045328652128,1.076339414001E-003)); +#171075 = CARTESIAN_POINT('',(6.010883543172,1.227390254481E-003)); +#171076 = CARTESIAN_POINT('',(5.976382533559,1.339263477878E-003)); +#171077 = CARTESIAN_POINT('',(5.941843890817,1.405524714325E-003)); +#171078 = CARTESIAN_POINT('',(5.907285653264,1.422641316493E-003)); +#171079 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); +#171080 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); +#171081 = CARTESIAN_POINT('',(5.803674042174,1.187353930377E-003)); +#171082 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); +#171083 = CARTESIAN_POINT('',(5.734837892756,8.475624467404E-004)); +#171084 = CARTESIAN_POINT('',(5.700549707253,6.520952931811E-004)); +#171085 = CARTESIAN_POINT('',(5.666375694827,4.570658043158E-004)); +#171086 = CARTESIAN_POINT('',(5.632337541793,2.772530388729E-004)); +#171087 = CARTESIAN_POINT('',(5.598457782919,1.282673134862E-004)); +#171088 = CARTESIAN_POINT('',(5.564759695218,2.616756246961E-005)); +#171089 = CARTESIAN_POINT('',(5.542431609433,-2.901324273457E-008)); +#171090 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171092 = PCURVE('',#171093,#171098); +#171093 = PLANE('',#171094); +#171094 = AXIS2_PLACEMENT_3D('',#171095,#171096,#171097); +#171095 = CARTESIAN_POINT('',(1.47,-0.8,1.E-001)); +#171096 = DIRECTION('',(0.E+000,0.E+000,1.)); +#171097 = DIRECTION('',(1.,0.E+000,0.E+000)); +#171098 = DEFINITIONAL_REPRESENTATION('',(#171099),#171104); +#171099 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171100,#171101,#171102, +#171103),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.355252715607E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#168708 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#168709 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); -#168710 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); -#168711 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); -#168712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168713 = ORIENTED_EDGE('',*,*,#168714,.T.); -#168714 = EDGE_CURVE('',#168644,#168715,#168717,.T.); -#168715 = VERTEX_POINT('',#168716); -#168716 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); -#168717 = SURFACE_CURVE('',#168718,(#168723,#168752),.PCURVE_S1.); -#168718 = CIRCLE('',#168719,5.E-002); -#168719 = AXIS2_PLACEMENT_3D('',#168720,#168721,#168722); -#168720 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,0.15)); -#168721 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#168722 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#168723 = PCURVE('',#168655,#168724); -#168724 = DEFINITIONAL_REPRESENTATION('',(#168725),#168751); -#168725 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168726,#168727,#168728, - #168729,#168730,#168731,#168732,#168733,#168734,#168735,#168736, - #168737,#168738,#168739,#168740,#168741,#168742,#168743,#168744, - #168745,#168746,#168747,#168748,#168749,#168750),.UNSPECIFIED.,.F., +#171100 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#171101 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); +#171102 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); +#171103 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); +#171104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171105 = ORIENTED_EDGE('',*,*,#171106,.T.); +#171106 = EDGE_CURVE('',#171036,#171107,#171109,.T.); +#171107 = VERTEX_POINT('',#171108); +#171108 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); +#171109 = SURFACE_CURVE('',#171110,(#171115,#171144),.PCURVE_S1.); +#171110 = CIRCLE('',#171111,5.E-002); +#171111 = AXIS2_PLACEMENT_3D('',#171112,#171113,#171114); +#171112 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,0.15)); +#171113 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#171114 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#171115 = PCURVE('',#171047,#171116); +#171116 = DEFINITIONAL_REPRESENTATION('',(#171117),#171143); +#171117 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171118,#171119,#171120, + #171121,#171122,#171123,#171124,#171125,#171126,#171127,#171128, + #171129,#171130,#171131,#171132,#171133,#171134,#171135,#171136, + #171137,#171138,#171139,#171140,#171141,#171142),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -208231,70 +211233,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#168726 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#168727 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#168728 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#168729 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#168730 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#168731 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#168732 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#168733 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#168734 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#168735 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#168736 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#168737 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#168738 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#168739 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#168740 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#168741 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#168742 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#168743 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#168744 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#168745 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#168746 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#168747 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#168748 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#168749 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#168750 = CARTESIAN_POINT('',(6.28318530718,1.)); -#168751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168752 = PCURVE('',#168753,#168770); -#168753 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#168754,#168755,#168756,#168757) - ,(#168758,#168759,#168760,#168761) - ,(#168762,#168763,#168764,#168765) - ,(#168766,#168767,#168768,#168769 +#171118 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171119 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#171120 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#171121 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#171122 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#171123 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#171124 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#171125 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#171126 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#171127 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#171128 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#171129 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#171130 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#171131 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#171132 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#171133 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#171134 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#171135 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#171136 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#171137 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#171138 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#171139 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#171140 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#171141 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#171142 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171144 = PCURVE('',#171145,#171162); +#171145 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171146,#171147,#171148,#171149) + ,(#171150,#171151,#171152,#171153) + ,(#171154,#171155,#171156,#171157) + ,(#171158,#171159,#171160,#171161 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(0.E+000,0.751879414295),( 0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#168754 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); -#168755 = CARTESIAN_POINT('',(1.283991911516,-0.613991911516,1.E-001)); -#168756 = CARTESIAN_POINT('',(1.297762843671,-0.627762843671, +#171146 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); +#171147 = CARTESIAN_POINT('',(1.283991911516,-0.613991911516,1.E-001)); +#171148 = CARTESIAN_POINT('',(1.297762843671,-0.627762843671, 0.113446578632)); -#168757 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); -#168758 = CARTESIAN_POINT('',(1.287470648802,-0.582026713303,1.E-001)); -#168759 = CARTESIAN_POINT('',(1.305531311073,-0.592452511959,1.E-001)); -#168760 = CARTESIAN_POINT('',(1.32299309093,-0.602532596412, +#171149 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); +#171150 = CARTESIAN_POINT('',(1.287470648802,-0.582026713303,1.E-001)); +#171151 = CARTESIAN_POINT('',(1.305531311073,-0.592452511959,1.E-001)); +#171152 = CARTESIAN_POINT('',(1.32299309093,-0.602532596412, 0.113446578632)); -#168761 = CARTESIAN_POINT('',(1.329392874324,-0.606226971076,0.132282534 +#171153 = CARTESIAN_POINT('',(1.329392874324,-0.606226971076,0.132282534 )); -#168762 = CARTESIAN_POINT('',(1.297659054385,-0.55695495248,1.E-001)); -#168763 = CARTESIAN_POINT('',(1.318429042165,-0.562435083194,1.E-001)); -#168764 = CARTESIAN_POINT('',(1.338443665671,-0.567668168966, +#171154 = CARTESIAN_POINT('',(1.297659054385,-0.55695495248,1.E-001)); +#171155 = CARTESIAN_POINT('',(1.318429042165,-0.562435083194,1.E-001)); +#171156 = CARTESIAN_POINT('',(1.338443665671,-0.567668168966, 0.114318476015)); -#168765 = CARTESIAN_POINT('',(1.345142684022,-0.569086531164, +#171157 = CARTESIAN_POINT('',(1.345142684022,-0.569086531164, 0.134026153074)); -#168766 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); -#168767 = CARTESIAN_POINT('',(1.319475670035,-0.531066471757,1.E-001)); -#168768 = CARTESIAN_POINT('',(1.34030879007,-0.531066471757, +#171158 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); +#171159 = CARTESIAN_POINT('',(1.319475670035,-0.531066471757,1.E-001)); +#171160 = CARTESIAN_POINT('',(1.34030879007,-0.531066471757, 0.115985815246)); -#168769 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, +#171161 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, 0.137059047745)); -#168770 = DEFINITIONAL_REPRESENTATION('',(#168771),#168797); -#168771 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168772,#168773,#168774, - #168775,#168776,#168777,#168778,#168779,#168780,#168781,#168782, - #168783,#168784,#168785,#168786,#168787,#168788,#168789,#168790, - #168791,#168792,#168793,#168794,#168795,#168796),.UNSPECIFIED.,.F., +#171162 = DEFINITIONAL_REPRESENTATION('',(#171163),#171189); +#171163 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171164,#171165,#171166, + #171167,#171168,#171169,#171170,#171171,#171172,#171173,#171174, + #171175,#171176,#171177,#171178,#171179,#171180,#171181,#171182, + #171183,#171184,#171185,#171186,#171187,#171188),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -208302,58 +211304,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#168772 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#168773 = CARTESIAN_POINT('',(1.251954286553E-015,1.515278164504E-002)); -#168774 = CARTESIAN_POINT('',(2.893000723342E-015,4.549920749135E-002)); -#168775 = CARTESIAN_POINT('',(3.733996380078E-015,9.109101074357E-002)); -#168776 = CARTESIAN_POINT('',(2.895529662975E-016,0.136698748187)); -#168777 = CARTESIAN_POINT('',(2.609876598908E-015,0.1822865144)); -#168778 = CARTESIAN_POINT('',(-1.194086863399E-015,0.2278300409)); -#168779 = CARTESIAN_POINT('',(1.380825292863E-015,0.27331674602)); -#168780 = CARTESIAN_POINT('',(6.140012269215E-016,0.318743220066)); -#168781 = CARTESIAN_POINT('',(-1.044657411467E-015,0.364113426255)); -#168782 = CARTESIAN_POINT('',(3.463639219909E-016,0.409436881051)); -#168783 = CARTESIAN_POINT('',(1.670880637898E-015,0.454727066523)); -#168784 = CARTESIAN_POINT('',(1.692961299191E-016,0.5)); -#168785 = CARTESIAN_POINT('',(2.774314336202E-015,0.545272933477)); -#168786 = CARTESIAN_POINT('',(-1.141997786996E-015,0.590563118949)); -#168787 = CARTESIAN_POINT('',(-5.773623532759E-016,0.635886573745)); -#168788 = CARTESIAN_POINT('',(2.313508859485E-015,0.681256779934)); -#168789 = CARTESIAN_POINT('',(-1.850106336844E-015,0.72668325398)); -#168790 = CARTESIAN_POINT('',(-1.741807731167E-016,0.7721699591)); -#168791 = CARTESIAN_POINT('',(1.671164712279E-015,0.8177134856)); -#168792 = CARTESIAN_POINT('',(2.415886529257E-016,0.863301251813)); -#168793 = CARTESIAN_POINT('',(2.067350977158E-015,0.908908989256)); -#168794 = CARTESIAN_POINT('',(5.249075804736E-016,0.954500792509)); -#168795 = CARTESIAN_POINT('',(-2.014648786824E-017,0.984847218355)); -#168796 = CARTESIAN_POINT('',(0.E+000,1.)); -#168797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168798 = ORIENTED_EDGE('',*,*,#168799,.F.); -#168799 = EDGE_CURVE('',#168800,#168715,#168802,.T.); -#168800 = VERTEX_POINT('',#168801); -#168801 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, +#171164 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#171165 = CARTESIAN_POINT('',(1.251954286553E-015,1.515278164504E-002)); +#171166 = CARTESIAN_POINT('',(2.893000723342E-015,4.549920749135E-002)); +#171167 = CARTESIAN_POINT('',(3.733996380078E-015,9.109101074357E-002)); +#171168 = CARTESIAN_POINT('',(2.895529662975E-016,0.136698748187)); +#171169 = CARTESIAN_POINT('',(2.609876598908E-015,0.1822865144)); +#171170 = CARTESIAN_POINT('',(-1.194086863399E-015,0.2278300409)); +#171171 = CARTESIAN_POINT('',(1.380825292863E-015,0.27331674602)); +#171172 = CARTESIAN_POINT('',(6.140012269215E-016,0.318743220066)); +#171173 = CARTESIAN_POINT('',(-1.044657411467E-015,0.364113426255)); +#171174 = CARTESIAN_POINT('',(3.463639219909E-016,0.409436881051)); +#171175 = CARTESIAN_POINT('',(1.670880637898E-015,0.454727066523)); +#171176 = CARTESIAN_POINT('',(1.692961299191E-016,0.5)); +#171177 = CARTESIAN_POINT('',(2.774314336202E-015,0.545272933477)); +#171178 = CARTESIAN_POINT('',(-1.141997786996E-015,0.590563118949)); +#171179 = CARTESIAN_POINT('',(-5.773623532759E-016,0.635886573745)); +#171180 = CARTESIAN_POINT('',(2.313508859485E-015,0.681256779934)); +#171181 = CARTESIAN_POINT('',(-1.850106336844E-015,0.72668325398)); +#171182 = CARTESIAN_POINT('',(-1.741807731167E-016,0.7721699591)); +#171183 = CARTESIAN_POINT('',(1.671164712279E-015,0.8177134856)); +#171184 = CARTESIAN_POINT('',(2.415886529257E-016,0.863301251813)); +#171185 = CARTESIAN_POINT('',(2.067350977158E-015,0.908908989256)); +#171186 = CARTESIAN_POINT('',(5.249075804736E-016,0.954500792509)); +#171187 = CARTESIAN_POINT('',(-2.014648786824E-017,0.984847218355)); +#171188 = CARTESIAN_POINT('',(0.E+000,1.)); +#171189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171190 = ORIENTED_EDGE('',*,*,#171191,.F.); +#171191 = EDGE_CURVE('',#171192,#171107,#171194,.T.); +#171192 = VERTEX_POINT('',#171193); +#171193 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, 0.137059047745)); -#168802 = SURFACE_CURVE('',#168803,(#168808,#168837),.PCURVE_S1.); -#168803 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#168804,#168805,#168806, -#168807),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171194 = SURFACE_CURVE('',#171195,(#171200,#171229),.PCURVE_S1.); +#171195 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171196,#171197,#171198, +#171199),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#168804 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, +#171196 = CARTESIAN_POINT('',(1.201066471757,-0.6759553457, 0.137059047745)); -#168805 = CARTESIAN_POINT('',(1.240010423697,-0.675122936235, +#171197 = CARTESIAN_POINT('',(1.240010423697,-0.675122936235, 0.133952453327)); -#168806 = CARTESIAN_POINT('',(1.275581001793,-0.660038843607,0.132282534 +#171198 = CARTESIAN_POINT('',(1.275581001793,-0.660038843607,0.132282534 )); -#168807 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); -#168808 = PCURVE('',#168655,#168809); -#168809 = DEFINITIONAL_REPRESENTATION('',(#168810),#168836); -#168810 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168811,#168812,#168813, - #168814,#168815,#168816,#168817,#168818,#168819,#168820,#168821, - #168822,#168823,#168824,#168825,#168826,#168827,#168828,#168829, - #168830,#168831,#168832,#168833,#168834,#168835),.UNSPECIFIED.,.F., +#171199 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); +#171200 = PCURVE('',#171047,#171201); +#171201 = DEFINITIONAL_REPRESENTATION('',(#171202),#171228); +#171202 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171203,#171204,#171205, + #171206,#171207,#171208,#171209,#171210,#171211,#171212,#171213, + #171214,#171215,#171216,#171217,#171218,#171219,#171220,#171221, + #171222,#171223,#171224,#171225,#171226,#171227),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -208361,47 +211363,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#168811 = CARTESIAN_POINT('',(5.531305892885,1.)); -#168812 = CARTESIAN_POINT('',(5.542431620278,0.999999942971)); -#168813 = CARTESIAN_POINT('',(5.564759360757,1.000007920749)); -#168814 = CARTESIAN_POINT('',(5.598455804408,1.00003211524)); -#168815 = CARTESIAN_POINT('',(5.632333796998,1.000091359578)); -#168816 = CARTESIAN_POINT('',(5.666367464031,1.000086431829)); -#168817 = CARTESIAN_POINT('',(5.700537102678,1.000086874059)); -#168818 = CARTESIAN_POINT('',(5.734821280547,1.000085935426)); -#168819 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#168820 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#168821 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#168822 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#168823 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#168824 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#168825 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#168826 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#168827 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#168828 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#168829 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#168830 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#168831 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#168832 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#168833 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#168834 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#168835 = CARTESIAN_POINT('',(6.28318530718,1.)); -#168836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168837 = PCURVE('',#168838,#168843); -#168838 = CYLINDRICAL_SURFACE('',#168839,0.15); -#168839 = AXIS2_PLACEMENT_3D('',#168840,#168841,#168842); -#168840 = CARTESIAN_POINT('',(1.149629241148,-0.479629241148, +#171203 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171204 = CARTESIAN_POINT('',(5.542431620278,0.999999942971)); +#171205 = CARTESIAN_POINT('',(5.564759360757,1.000007920749)); +#171206 = CARTESIAN_POINT('',(5.598455804408,1.00003211524)); +#171207 = CARTESIAN_POINT('',(5.632333796998,1.000091359578)); +#171208 = CARTESIAN_POINT('',(5.666367464031,1.000086431829)); +#171209 = CARTESIAN_POINT('',(5.700537102678,1.000086874059)); +#171210 = CARTESIAN_POINT('',(5.734821280547,1.000085935426)); +#171211 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#171212 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#171213 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#171214 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#171215 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#171216 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#171217 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#171218 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#171219 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#171220 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#171221 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#171222 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#171223 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#171224 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#171225 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#171226 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#171227 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171229 = PCURVE('',#171230,#171235); +#171230 = CYLINDRICAL_SURFACE('',#171231,0.15); +#171231 = AXIS2_PLACEMENT_3D('',#171232,#171233,#171234); +#171232 = CARTESIAN_POINT('',(1.149629241148,-0.479629241148, -1.608445352162E-002)); -#168841 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#168842 = DIRECTION('',(0.965925826289,5.263462734238E-017, +#171233 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#171234 = DIRECTION('',(0.965925826289,5.263462734238E-017, -0.258819045103)); -#168843 = DEFINITIONAL_REPRESENTATION('',(#168844),#168870); -#168844 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168845,#168846,#168847, - #168848,#168849,#168850,#168851,#168852,#168853,#168854,#168855, - #168856,#168857,#168858,#168859,#168860,#168861,#168862,#168863, - #168864,#168865,#168866,#168867,#168868,#168869),.UNSPECIFIED.,.F., +#171235 = DEFINITIONAL_REPRESENTATION('',(#171236),#171262); +#171236 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171237,#171238,#171239, + #171240,#171241,#171242,#171243,#171244,#171245,#171246,#171247, + #171248,#171249,#171250,#171251,#171252,#171253,#171254,#171255, + #171256,#171257,#171258,#171259,#171260,#171261),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -208409,48 +211411,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#168845 = CARTESIAN_POINT('',(4.77942647859,0.205286775028)); -#168846 = CARTESIAN_POINT('',(4.790552085824,0.205574732686)); -#168847 = CARTESIAN_POINT('',(4.812874135705,0.206142181906)); -#168848 = CARTESIAN_POINT('',(4.846552114392,0.2069660569)); -#168849 = CARTESIAN_POINT('',(4.880407630888,0.207760708899)); -#168850 = CARTESIAN_POINT('',(4.914422492066,0.208524296394)); -#168851 = CARTESIAN_POINT('',(4.948578027862,0.20925504796)); -#168852 = CARTESIAN_POINT('',(4.98285506838,0.209951281181)); -#168853 = CARTESIAN_POINT('',(5.017234026195,0.210611412568)); -#168854 = CARTESIAN_POINT('',(5.051694955172,0.211233969132)); -#168855 = CARTESIAN_POINT('',(5.086217619636,0.211817598546)); -#168856 = CARTESIAN_POINT('',(5.120781564146,0.21236107854)); -#168857 = CARTESIAN_POINT('',(5.155366185737,0.212863325183)); -#168858 = CARTESIAN_POINT('',(5.189950807328,0.213323399993)); -#168859 = CARTESIAN_POINT('',(5.224514751839,0.213740515769)); -#168860 = CARTESIAN_POINT('',(5.259037416303,0.214114041064)); -#168861 = CARTESIAN_POINT('',(5.293498345279,0.214443503246)); -#168862 = CARTESIAN_POINT('',(5.327877303094,0.21472859015)); -#168863 = CARTESIAN_POINT('',(5.362154343612,0.214969150173)); -#168864 = CARTESIAN_POINT('',(5.396309879408,0.215165191368)); -#168865 = CARTESIAN_POINT('',(5.430324740587,0.215316877584)); -#168866 = CARTESIAN_POINT('',(5.464180257082,0.215424529131)); -#168867 = CARTESIAN_POINT('',(5.49785823577,0.215488600414)); -#168868 = CARTESIAN_POINT('',(5.52018028565,0.215502691983)); -#168869 = CARTESIAN_POINT('',(5.531305892885,0.215502680697)); -#168870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168871 = ORIENTED_EDGE('',*,*,#168872,.T.); -#168872 = EDGE_CURVE('',#168800,#168646,#168873,.T.); -#168873 = SURFACE_CURVE('',#168874,(#168879,#168908),.PCURVE_S1.); -#168874 = CIRCLE('',#168875,5.E-002); -#168875 = AXIS2_PLACEMENT_3D('',#168876,#168877,#168878); -#168876 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,0.15)); -#168877 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); -#168878 = DIRECTION('',(-4.336808689942E-015,-3.063287707413E-045,-1.)); -#168879 = PCURVE('',#168655,#168880); -#168880 = DEFINITIONAL_REPRESENTATION('',(#168881),#168907); -#168881 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168882,#168883,#168884, - #168885,#168886,#168887,#168888,#168889,#168890,#168891,#168892, - #168893,#168894,#168895,#168896,#168897,#168898,#168899,#168900, - #168901,#168902,#168903,#168904,#168905,#168906),.UNSPECIFIED.,.F., +#171237 = CARTESIAN_POINT('',(4.77942647859,0.205286775028)); +#171238 = CARTESIAN_POINT('',(4.790552085824,0.205574732686)); +#171239 = CARTESIAN_POINT('',(4.812874135705,0.206142181906)); +#171240 = CARTESIAN_POINT('',(4.846552114392,0.2069660569)); +#171241 = CARTESIAN_POINT('',(4.880407630888,0.207760708899)); +#171242 = CARTESIAN_POINT('',(4.914422492066,0.208524296394)); +#171243 = CARTESIAN_POINT('',(4.948578027862,0.20925504796)); +#171244 = CARTESIAN_POINT('',(4.98285506838,0.209951281181)); +#171245 = CARTESIAN_POINT('',(5.017234026195,0.210611412568)); +#171246 = CARTESIAN_POINT('',(5.051694955172,0.211233969132)); +#171247 = CARTESIAN_POINT('',(5.086217619636,0.211817598546)); +#171248 = CARTESIAN_POINT('',(5.120781564146,0.21236107854)); +#171249 = CARTESIAN_POINT('',(5.155366185737,0.212863325183)); +#171250 = CARTESIAN_POINT('',(5.189950807328,0.213323399993)); +#171251 = CARTESIAN_POINT('',(5.224514751839,0.213740515769)); +#171252 = CARTESIAN_POINT('',(5.259037416303,0.214114041064)); +#171253 = CARTESIAN_POINT('',(5.293498345279,0.214443503246)); +#171254 = CARTESIAN_POINT('',(5.327877303094,0.21472859015)); +#171255 = CARTESIAN_POINT('',(5.362154343612,0.214969150173)); +#171256 = CARTESIAN_POINT('',(5.396309879408,0.215165191368)); +#171257 = CARTESIAN_POINT('',(5.430324740587,0.215316877584)); +#171258 = CARTESIAN_POINT('',(5.464180257082,0.215424529131)); +#171259 = CARTESIAN_POINT('',(5.49785823577,0.215488600414)); +#171260 = CARTESIAN_POINT('',(5.52018028565,0.215502691983)); +#171261 = CARTESIAN_POINT('',(5.531305892885,0.215502680697)); +#171262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171263 = ORIENTED_EDGE('',*,*,#171264,.T.); +#171264 = EDGE_CURVE('',#171192,#171038,#171265,.T.); +#171265 = SURFACE_CURVE('',#171266,(#171271,#171300),.PCURVE_S1.); +#171266 = CIRCLE('',#171267,5.E-002); +#171267 = AXIS2_PLACEMENT_3D('',#171268,#171269,#171270); +#171268 = CARTESIAN_POINT('',(1.201066471757,-0.627659054385,0.15)); +#171269 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); +#171270 = DIRECTION('',(-4.336808689942E-015,-3.063287707413E-045,-1.)); +#171271 = PCURVE('',#171047,#171272); +#171272 = DEFINITIONAL_REPRESENTATION('',(#171273),#171299); +#171273 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171274,#171275,#171276, + #171277,#171278,#171279,#171280,#171281,#171282,#171283,#171284, + #171285,#171286,#171287,#171288,#171289,#171290,#171291,#171292, + #171293,#171294,#171295,#171296,#171297,#171298),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -208458,45 +211460,45 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#168882 = CARTESIAN_POINT('',(5.531305892885,1.)); -#168883 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#168884 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#168885 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#168886 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#168887 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#168888 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#168889 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#168890 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#168891 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#168892 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#168893 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#168894 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#168895 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#168896 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#168897 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#168898 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#168899 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#168900 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#168901 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#168902 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#168903 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); -#168904 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#168905 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#168906 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#168907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168908 = PCURVE('',#168909,#168914); -#168909 = CYLINDRICAL_SURFACE('',#168910,5.E-002); -#168910 = AXIS2_PLACEMENT_3D('',#168911,#168912,#168913); -#168911 = CARTESIAN_POINT('',(-1.47,-0.627659054385,0.15)); -#168912 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#168913 = DIRECTION('',(0.E+000,0.E+000,1.)); -#168914 = DEFINITIONAL_REPRESENTATION('',(#168915),#168941); -#168915 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168916,#168917,#168918, - #168919,#168920,#168921,#168922,#168923,#168924,#168925,#168926, - #168927,#168928,#168929,#168930,#168931,#168932,#168933,#168934, - #168935,#168936,#168937,#168938,#168939,#168940),.UNSPECIFIED.,.F., +#171274 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171275 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#171276 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#171277 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#171278 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#171279 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#171280 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#171281 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#171282 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#171283 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#171284 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#171285 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#171286 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#171287 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#171288 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#171289 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#171290 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#171291 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#171292 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#171293 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#171294 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#171295 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); +#171296 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#171297 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#171298 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171300 = PCURVE('',#171301,#171306); +#171301 = CYLINDRICAL_SURFACE('',#171302,5.E-002); +#171302 = AXIS2_PLACEMENT_3D('',#171303,#171304,#171305); +#171303 = CARTESIAN_POINT('',(-1.47,-0.627659054385,0.15)); +#171304 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#171305 = DIRECTION('',(0.E+000,0.E+000,1.)); +#171306 = DEFINITIONAL_REPRESENTATION('',(#171307),#171333); +#171307 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171308,#171309,#171310, + #171311,#171312,#171313,#171314,#171315,#171316,#171317,#171318, + #171319,#171320,#171321,#171322,#171323,#171324,#171325,#171326, + #171327,#171328,#171329,#171330,#171331,#171332),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -208504,89 +211506,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#168916 = CARTESIAN_POINT('',(4.450589592586,-2.671066471757)); -#168917 = CARTESIAN_POINT('',(4.430756305631,-2.671066471757)); -#168918 = CARTESIAN_POINT('',(4.391089731722,-2.671066471757)); -#168919 = CARTESIAN_POINT('',(4.331589870859,-2.671066471757)); -#168920 = CARTESIAN_POINT('',(4.272090009995,-2.671066471757)); -#168921 = CARTESIAN_POINT('',(4.212590149132,-2.671066471757)); -#168922 = CARTESIAN_POINT('',(4.153090288268,-2.671066471757)); -#168923 = CARTESIAN_POINT('',(4.093590427405,-2.671066471757)); -#168924 = CARTESIAN_POINT('',(4.034090566541,-2.671066471757)); -#168925 = CARTESIAN_POINT('',(3.974590705678,-2.671066471757)); -#168926 = CARTESIAN_POINT('',(3.915090844815,-2.671066471757)); -#168927 = CARTESIAN_POINT('',(3.855590983951,-2.671066471757)); -#168928 = CARTESIAN_POINT('',(3.796091123088,-2.671066471757)); -#168929 = CARTESIAN_POINT('',(3.736591262224,-2.671066471757)); -#168930 = CARTESIAN_POINT('',(3.677091401361,-2.671066471757)); -#168931 = CARTESIAN_POINT('',(3.617591540497,-2.671066471757)); -#168932 = CARTESIAN_POINT('',(3.558091679634,-2.671066471757)); -#168933 = CARTESIAN_POINT('',(3.49859181877,-2.671066471757)); -#168934 = CARTESIAN_POINT('',(3.439091957907,-2.671066471757)); -#168935 = CARTESIAN_POINT('',(3.379592097044,-2.671066471757)); -#168936 = CARTESIAN_POINT('',(3.32009223618,-2.671066471757)); -#168937 = CARTESIAN_POINT('',(3.260592375317,-2.671066471757)); -#168938 = CARTESIAN_POINT('',(3.201092514453,-2.671066471757)); -#168939 = CARTESIAN_POINT('',(3.161425940544,-2.671066471757)); -#168940 = CARTESIAN_POINT('',(3.14159265359,-2.671066471757)); -#168941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#168942 = ADVANCED_FACE('',(#168943),#168958,.T.); -#168943 = FACE_BOUND('',#168944,.T.); -#168944 = EDGE_LOOP('',(#168945,#169011,#169096,#169169)); -#168945 = ORIENTED_EDGE('',*,*,#168946,.F.); -#168946 = EDGE_CURVE('',#168947,#168949,#168951,.T.); -#168947 = VERTEX_POINT('',#168948); -#168948 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); -#168949 = VERTEX_POINT('',#168950); -#168950 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); -#168951 = SURFACE_CURVE('',#168952,(#168957,#169003),.PCURVE_S1.); -#168952 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#168953,#168954,#168955, -#168956),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171308 = CARTESIAN_POINT('',(4.450589592586,-2.671066471757)); +#171309 = CARTESIAN_POINT('',(4.430756305631,-2.671066471757)); +#171310 = CARTESIAN_POINT('',(4.391089731722,-2.671066471757)); +#171311 = CARTESIAN_POINT('',(4.331589870859,-2.671066471757)); +#171312 = CARTESIAN_POINT('',(4.272090009995,-2.671066471757)); +#171313 = CARTESIAN_POINT('',(4.212590149132,-2.671066471757)); +#171314 = CARTESIAN_POINT('',(4.153090288268,-2.671066471757)); +#171315 = CARTESIAN_POINT('',(4.093590427405,-2.671066471757)); +#171316 = CARTESIAN_POINT('',(4.034090566541,-2.671066471757)); +#171317 = CARTESIAN_POINT('',(3.974590705678,-2.671066471757)); +#171318 = CARTESIAN_POINT('',(3.915090844815,-2.671066471757)); +#171319 = CARTESIAN_POINT('',(3.855590983951,-2.671066471757)); +#171320 = CARTESIAN_POINT('',(3.796091123088,-2.671066471757)); +#171321 = CARTESIAN_POINT('',(3.736591262224,-2.671066471757)); +#171322 = CARTESIAN_POINT('',(3.677091401361,-2.671066471757)); +#171323 = CARTESIAN_POINT('',(3.617591540497,-2.671066471757)); +#171324 = CARTESIAN_POINT('',(3.558091679634,-2.671066471757)); +#171325 = CARTESIAN_POINT('',(3.49859181877,-2.671066471757)); +#171326 = CARTESIAN_POINT('',(3.439091957907,-2.671066471757)); +#171327 = CARTESIAN_POINT('',(3.379592097044,-2.671066471757)); +#171328 = CARTESIAN_POINT('',(3.32009223618,-2.671066471757)); +#171329 = CARTESIAN_POINT('',(3.260592375317,-2.671066471757)); +#171330 = CARTESIAN_POINT('',(3.201092514453,-2.671066471757)); +#171331 = CARTESIAN_POINT('',(3.161425940544,-2.671066471757)); +#171332 = CARTESIAN_POINT('',(3.14159265359,-2.671066471757)); +#171333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171334 = ADVANCED_FACE('',(#171335),#171350,.T.); +#171335 = FACE_BOUND('',#171336,.T.); +#171336 = EDGE_LOOP('',(#171337,#171403,#171488,#171561)); +#171337 = ORIENTED_EDGE('',*,*,#171338,.F.); +#171338 = EDGE_CURVE('',#171339,#171341,#171343,.T.); +#171339 = VERTEX_POINT('',#171340); +#171340 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); +#171341 = VERTEX_POINT('',#171342); +#171342 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); +#171343 = SURFACE_CURVE('',#171344,(#171349,#171395),.PCURVE_S1.); +#171344 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171345,#171346,#171347, +#171348),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#168953 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); -#168954 = CARTESIAN_POINT('',(-1.28790129499,-0.581596067115,1.E-001)); -#168955 = CARTESIAN_POINT('',(-1.297659054385,-0.557584046027,1.E-001)); -#168956 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); -#168957 = PCURVE('',#168958,#168975); -#168958 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#168959,#168960,#168961,#168962) - ,(#168963,#168964,#168965,#168966) - ,(#168967,#168968,#168969,#168970) - ,(#168971,#168972,#168973,#168974 +#171345 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); +#171346 = CARTESIAN_POINT('',(-1.28790129499,-0.581596067115,1.E-001)); +#171347 = CARTESIAN_POINT('',(-1.297659054385,-0.557584046027,1.E-001)); +#171348 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); +#171349 = PCURVE('',#171350,#171367); +#171350 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171351,#171352,#171353,#171354) + ,(#171355,#171356,#171357,#171358) + ,(#171359,#171360,#171361,#171362) + ,(#171363,#171364,#171365,#171366 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#168959 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); -#168960 = CARTESIAN_POINT('',(-1.319475670035,-0.531066471757,1.E-001)); -#168961 = CARTESIAN_POINT('',(-1.34030879007,-0.531066471757, +#171351 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,1.E-001)); +#171352 = CARTESIAN_POINT('',(-1.319475670035,-0.531066471757,1.E-001)); +#171353 = CARTESIAN_POINT('',(-1.34030879007,-0.531066471757, 0.115985815246)); -#168962 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, +#171354 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, 0.137059047745)); -#168963 = CARTESIAN_POINT('',(-1.297659054385,-0.55695495248,1.E-001)); -#168964 = CARTESIAN_POINT('',(-1.318429042165,-0.562435083194,1.E-001)); -#168965 = CARTESIAN_POINT('',(-1.338443665671,-0.567668168966, +#171355 = CARTESIAN_POINT('',(-1.297659054385,-0.55695495248,1.E-001)); +#171356 = CARTESIAN_POINT('',(-1.318429042165,-0.562435083194,1.E-001)); +#171357 = CARTESIAN_POINT('',(-1.338443665671,-0.567668168966, 0.114318476015)); -#168966 = CARTESIAN_POINT('',(-1.345142684022,-0.569086531164, +#171358 = CARTESIAN_POINT('',(-1.345142684022,-0.569086531164, 0.134026153074)); -#168967 = CARTESIAN_POINT('',(-1.287470648802,-0.582026713303,1.E-001)); -#168968 = CARTESIAN_POINT('',(-1.305531311073,-0.592452511959,1.E-001)); -#168969 = CARTESIAN_POINT('',(-1.32299309093,-0.602532596412, +#171359 = CARTESIAN_POINT('',(-1.287470648802,-0.582026713303,1.E-001)); +#171360 = CARTESIAN_POINT('',(-1.305531311073,-0.592452511959,1.E-001)); +#171361 = CARTESIAN_POINT('',(-1.32299309093,-0.602532596412, 0.113446578632)); -#168970 = CARTESIAN_POINT('',(-1.329392874324,-0.606226971076, +#171362 = CARTESIAN_POINT('',(-1.329392874324,-0.606226971076, 0.132282534)); -#168971 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); -#168972 = CARTESIAN_POINT('',(-1.283991911516,-0.613991911516,1.E-001)); -#168973 = CARTESIAN_POINT('',(-1.297762843671,-0.627762843671, +#171363 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); +#171364 = CARTESIAN_POINT('',(-1.283991911516,-0.613991911516,1.E-001)); +#171365 = CARTESIAN_POINT('',(-1.297762843671,-0.627762843671, 0.113446578632)); -#168974 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); -#168975 = DEFINITIONAL_REPRESENTATION('',(#168976),#169002); -#168976 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#168977,#168978,#168979, - #168980,#168981,#168982,#168983,#168984,#168985,#168986,#168987, - #168988,#168989,#168990,#168991,#168992,#168993,#168994,#168995, - #168996,#168997,#168998,#168999,#169000,#169001),.UNSPECIFIED.,.F., +#171366 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); +#171367 = DEFINITIONAL_REPRESENTATION('',(#171368),#171394); +#171368 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171369,#171370,#171371, + #171372,#171373,#171374,#171375,#171376,#171377,#171378,#171379, + #171380,#171381,#171382,#171383,#171384,#171385,#171386,#171387, + #171388,#171389,#171390,#171391,#171392,#171393),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -208595,64 +211597,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#168977 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#168978 = CARTESIAN_POINT('',(6.272059569215,1.375318737982E-008)); -#168979 = CARTESIAN_POINT('',(6.24973263213,2.924134010365E-005)); -#168980 = CARTESIAN_POINT('',(6.21603939964,1.413707577584E-004)); -#168981 = CARTESIAN_POINT('',(6.182167276026,3.022859269952E-004)); -#168982 = CARTESIAN_POINT('',(6.148138870073,4.931498468553E-004)); -#168983 = CARTESIAN_POINT('',(6.113975913115,6.962198987713E-004)); -#168984 = CARTESIAN_POINT('',(6.079699188623,8.953387637324E-004)); -#168985 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); -#168986 = CARTESIAN_POINT('',(6.010883543172,1.227390254479E-003)); -#168987 = CARTESIAN_POINT('',(5.976382533559,1.339263477875E-003)); -#168988 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); -#168989 = CARTESIAN_POINT('',(5.907285653264,1.422641316493E-003)); -#168990 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); -#168991 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); -#168992 = CARTESIAN_POINT('',(5.803674042174,1.187353930387E-003)); -#168993 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); -#168994 = CARTESIAN_POINT('',(5.734837892756,8.475624467407E-004)); -#168995 = CARTESIAN_POINT('',(5.700549707253,6.520952931877E-004)); -#168996 = CARTESIAN_POINT('',(5.666375694827,4.570658043064E-004)); -#168997 = CARTESIAN_POINT('',(5.632337541793,2.772530388795E-004)); -#168998 = CARTESIAN_POINT('',(5.598457782919,1.28267313484E-004)); -#168999 = CARTESIAN_POINT('',(5.564759695218,2.616756247143E-005)); -#169000 = CARTESIAN_POINT('',(5.542431609433,-2.901324139516E-008)); -#169001 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169003 = PCURVE('',#168701,#169004); -#169004 = DEFINITIONAL_REPRESENTATION('',(#169005),#169010); -#169005 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169006,#169007,#169008, -#169009),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171369 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171370 = CARTESIAN_POINT('',(6.272059569215,1.375318737982E-008)); +#171371 = CARTESIAN_POINT('',(6.24973263213,2.924134010365E-005)); +#171372 = CARTESIAN_POINT('',(6.21603939964,1.413707577584E-004)); +#171373 = CARTESIAN_POINT('',(6.182167276026,3.022859269952E-004)); +#171374 = CARTESIAN_POINT('',(6.148138870073,4.931498468553E-004)); +#171375 = CARTESIAN_POINT('',(6.113975913115,6.962198987713E-004)); +#171376 = CARTESIAN_POINT('',(6.079699188623,8.953387637324E-004)); +#171377 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); +#171378 = CARTESIAN_POINT('',(6.010883543172,1.227390254479E-003)); +#171379 = CARTESIAN_POINT('',(5.976382533559,1.339263477875E-003)); +#171380 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); +#171381 = CARTESIAN_POINT('',(5.907285653264,1.422641316493E-003)); +#171382 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); +#171383 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); +#171384 = CARTESIAN_POINT('',(5.803674042174,1.187353930387E-003)); +#171385 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); +#171386 = CARTESIAN_POINT('',(5.734837892756,8.475624467407E-004)); +#171387 = CARTESIAN_POINT('',(5.700549707253,6.520952931877E-004)); +#171388 = CARTESIAN_POINT('',(5.666375694827,4.570658043064E-004)); +#171389 = CARTESIAN_POINT('',(5.632337541793,2.772530388795E-004)); +#171390 = CARTESIAN_POINT('',(5.598457782919,1.28267313484E-004)); +#171391 = CARTESIAN_POINT('',(5.564759695218,2.616756247143E-005)); +#171392 = CARTESIAN_POINT('',(5.542431609433,-2.901324139516E-008)); +#171393 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171395 = PCURVE('',#171093,#171396); +#171396 = DEFINITIONAL_REPRESENTATION('',(#171397),#171402); +#171397 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171398,#171399,#171400, +#171401),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169006 = CARTESIAN_POINT('',(-2.739748681053,0.200251318947)); -#169007 = CARTESIAN_POINT('',(-2.75790129499,0.218403932885)); -#169008 = CARTESIAN_POINT('',(-2.767659054385,0.242415953973)); -#169009 = CARTESIAN_POINT('',(-2.767659054385,0.268933528243)); -#169010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169011 = ORIENTED_EDGE('',*,*,#169012,.T.); -#169012 = EDGE_CURVE('',#168947,#169013,#169015,.T.); -#169013 = VERTEX_POINT('',#169014); -#169014 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); -#169015 = SURFACE_CURVE('',#169016,(#169021,#169050),.PCURVE_S1.); -#169016 = CIRCLE('',#169017,5.E-002); -#169017 = AXIS2_PLACEMENT_3D('',#169018,#169019,#169020); -#169018 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,0.15)); -#169019 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#169020 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#169021 = PCURVE('',#168958,#169022); -#169022 = DEFINITIONAL_REPRESENTATION('',(#169023),#169049); -#169023 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169024,#169025,#169026, - #169027,#169028,#169029,#169030,#169031,#169032,#169033,#169034, - #169035,#169036,#169037,#169038,#169039,#169040,#169041,#169042, - #169043,#169044,#169045,#169046,#169047,#169048),.UNSPECIFIED.,.F., +#171398 = CARTESIAN_POINT('',(-2.739748681053,0.200251318947)); +#171399 = CARTESIAN_POINT('',(-2.75790129499,0.218403932885)); +#171400 = CARTESIAN_POINT('',(-2.767659054385,0.242415953973)); +#171401 = CARTESIAN_POINT('',(-2.767659054385,0.268933528243)); +#171402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171403 = ORIENTED_EDGE('',*,*,#171404,.T.); +#171404 = EDGE_CURVE('',#171339,#171405,#171407,.T.); +#171405 = VERTEX_POINT('',#171406); +#171406 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); +#171407 = SURFACE_CURVE('',#171408,(#171413,#171442),.PCURVE_S1.); +#171408 = CIRCLE('',#171409,5.E-002); +#171409 = AXIS2_PLACEMENT_3D('',#171410,#171411,#171412); +#171410 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,0.15)); +#171411 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#171412 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#171413 = PCURVE('',#171350,#171414); +#171414 = DEFINITIONAL_REPRESENTATION('',(#171415),#171441); +#171415 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171416,#171417,#171418, + #171419,#171420,#171421,#171422,#171423,#171424,#171425,#171426, + #171427,#171428,#171429,#171430,#171431,#171432,#171433,#171434, + #171435,#171436,#171437,#171438,#171439,#171440),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -208660,70 +211662,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169024 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169025 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#169026 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#169027 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#169028 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#169029 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#169030 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#169031 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#169032 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#169033 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#169034 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#169035 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#169036 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#169037 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#169038 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#169039 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#169040 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#169041 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#169042 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#169043 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#169044 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#169045 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#169046 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#169047 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#169048 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169050 = PCURVE('',#169051,#169068); -#169051 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169052,#169053,#169054,#169055) - ,(#169056,#169057,#169058,#169059) - ,(#169060,#169061,#169062,#169063) - ,(#169064,#169065,#169066,#169067 +#171416 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171417 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#171418 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#171419 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#171420 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#171421 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#171422 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#171423 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#171424 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#171425 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#171426 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#171427 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#171428 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#171429 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#171430 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#171431 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#171432 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#171433 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#171434 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#171435 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#171436 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#171437 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#171438 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#171439 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#171440 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171442 = PCURVE('',#171443,#171460); +#171443 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171444,#171445,#171446,#171447) + ,(#171448,#171449,#171450,#171451) + ,(#171452,#171453,#171454,#171455) + ,(#171456,#171457,#171458,#171459 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(7.453889935838E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169052 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); -#169053 = CARTESIAN_POINT('',(-1.283991911516,-0.613991911516,1.E-001)); -#169054 = CARTESIAN_POINT('',(-1.297762843671,-0.627762843671, +#171444 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); +#171445 = CARTESIAN_POINT('',(-1.283991911516,-0.613991911516,1.E-001)); +#171446 = CARTESIAN_POINT('',(-1.297762843671,-0.627762843671, 0.113446578632)); -#169055 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); -#169056 = CARTESIAN_POINT('',(-1.252026713303,-0.617470648802,1.E-001)); -#169057 = CARTESIAN_POINT('',(-1.262452511959,-0.635531311073,1.E-001)); -#169058 = CARTESIAN_POINT('',(-1.272532596412,-0.65299309093, +#171447 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); +#171448 = CARTESIAN_POINT('',(-1.252026713303,-0.617470648802,1.E-001)); +#171449 = CARTESIAN_POINT('',(-1.262452511959,-0.635531311073,1.E-001)); +#171450 = CARTESIAN_POINT('',(-1.272532596412,-0.65299309093, 0.113446578632)); -#169059 = CARTESIAN_POINT('',(-1.276226971076,-0.659392874324, +#171451 = CARTESIAN_POINT('',(-1.276226971076,-0.659392874324, 0.132282534)); -#169060 = CARTESIAN_POINT('',(-1.22695495248,-0.627659054385,1.E-001)); -#169061 = CARTESIAN_POINT('',(-1.232435083194,-0.648429042165,1.E-001)); -#169062 = CARTESIAN_POINT('',(-1.237668168966,-0.668443665671, +#171452 = CARTESIAN_POINT('',(-1.22695495248,-0.627659054385,1.E-001)); +#171453 = CARTESIAN_POINT('',(-1.232435083194,-0.648429042165,1.E-001)); +#171454 = CARTESIAN_POINT('',(-1.237668168966,-0.668443665671, 0.114318476015)); -#169063 = CARTESIAN_POINT('',(-1.239086531164,-0.675142684022, +#171455 = CARTESIAN_POINT('',(-1.239086531164,-0.675142684022, 0.134026153074)); -#169064 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); -#169065 = CARTESIAN_POINT('',(-1.201066471757,-0.649475670035,1.E-001)); -#169066 = CARTESIAN_POINT('',(-1.201066471757,-0.67030879007, +#171456 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); +#171457 = CARTESIAN_POINT('',(-1.201066471757,-0.649475670035,1.E-001)); +#171458 = CARTESIAN_POINT('',(-1.201066471757,-0.67030879007, 0.115985815246)); -#169067 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, +#171459 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, 0.137059047745)); -#169068 = DEFINITIONAL_REPRESENTATION('',(#169069),#169095); -#169069 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169070,#169071,#169072, - #169073,#169074,#169075,#169076,#169077,#169078,#169079,#169080, - #169081,#169082,#169083,#169084,#169085,#169086,#169087,#169088, - #169089,#169090,#169091,#169092,#169093,#169094),.UNSPECIFIED.,.F., +#171460 = DEFINITIONAL_REPRESENTATION('',(#171461),#171487); +#171461 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171462,#171463,#171464, + #171465,#171466,#171467,#171468,#171469,#171470,#171471,#171472, + #171473,#171474,#171475,#171476,#171477,#171478,#171479,#171480, + #171481,#171482,#171483,#171484,#171485,#171486),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -208731,58 +211733,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169070 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#169071 = CARTESIAN_POINT('',(1.423216452209E-015,1.515278164503E-002)); -#169072 = CARTESIAN_POINT('',(1.75595713908E-015,4.549920749134E-002)); -#169073 = CARTESIAN_POINT('',(9.762231287129E-016,9.109101074357E-002)); -#169074 = CARTESIAN_POINT('',(-5.214691685001E-016,0.136698748187)); -#169075 = CARTESIAN_POINT('',(2.125305139523E-015,0.1822865144)); -#169076 = CARTESIAN_POINT('',(1.555326918456E-015,0.2278300409)); -#169077 = CARTESIAN_POINT('',(1.451172717516E-015,0.27331674602)); -#169078 = CARTESIAN_POINT('',(-1.348995074008E-015,0.318743220066)); -#169079 = CARTESIAN_POINT('',(2.21417027727E-015,0.364113426255)); -#169080 = CARTESIAN_POINT('',(-1.662127185702E-015,0.409436881051)); -#169081 = CARTESIAN_POINT('',(2.773713525706E-015,0.454727066523)); -#169082 = CARTESIAN_POINT('',(-2.28767670117E-016,0.5)); -#169083 = CARTESIAN_POINT('',(8.926385316667E-017,0.545272933477)); -#169084 = CARTESIAN_POINT('',(1.652656186198E-015,0.590563118949)); -#169085 = CARTESIAN_POINT('',(1.840658887771E-015,0.635886573745)); -#169086 = CARTESIAN_POINT('',(-6.429146922744E-016,0.681256779934)); -#169087 = CARTESIAN_POINT('',(2.140447691881E-015,0.72668325398)); -#169088 = CARTESIAN_POINT('',(-1.449455416269E-016,0.7721699591)); -#169089 = CARTESIAN_POINT('',(-6.244354999135E-016,0.8177134856)); -#169090 = CARTESIAN_POINT('',(-3.949641981777E-018,0.863301251813)); -#169091 = CARTESIAN_POINT('',(8.564583362975E-016,0.908908989256)); -#169092 = CARTESIAN_POINT('',(-3.439866929022E-016,0.954500792509)); -#169093 = CARTESIAN_POINT('',(-2.737282005933E-017,0.984847218355)); -#169094 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#169095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169096 = ORIENTED_EDGE('',*,*,#169097,.F.); -#169097 = EDGE_CURVE('',#169098,#169013,#169100,.T.); -#169098 = VERTEX_POINT('',#169099); -#169099 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, +#171462 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#171463 = CARTESIAN_POINT('',(1.423216452209E-015,1.515278164503E-002)); +#171464 = CARTESIAN_POINT('',(1.75595713908E-015,4.549920749134E-002)); +#171465 = CARTESIAN_POINT('',(9.762231287129E-016,9.109101074357E-002)); +#171466 = CARTESIAN_POINT('',(-5.214691685001E-016,0.136698748187)); +#171467 = CARTESIAN_POINT('',(2.125305139523E-015,0.1822865144)); +#171468 = CARTESIAN_POINT('',(1.555326918456E-015,0.2278300409)); +#171469 = CARTESIAN_POINT('',(1.451172717516E-015,0.27331674602)); +#171470 = CARTESIAN_POINT('',(-1.348995074008E-015,0.318743220066)); +#171471 = CARTESIAN_POINT('',(2.21417027727E-015,0.364113426255)); +#171472 = CARTESIAN_POINT('',(-1.662127185702E-015,0.409436881051)); +#171473 = CARTESIAN_POINT('',(2.773713525706E-015,0.454727066523)); +#171474 = CARTESIAN_POINT('',(-2.28767670117E-016,0.5)); +#171475 = CARTESIAN_POINT('',(8.926385316667E-017,0.545272933477)); +#171476 = CARTESIAN_POINT('',(1.652656186198E-015,0.590563118949)); +#171477 = CARTESIAN_POINT('',(1.840658887771E-015,0.635886573745)); +#171478 = CARTESIAN_POINT('',(-6.429146922744E-016,0.681256779934)); +#171479 = CARTESIAN_POINT('',(2.140447691881E-015,0.72668325398)); +#171480 = CARTESIAN_POINT('',(-1.449455416269E-016,0.7721699591)); +#171481 = CARTESIAN_POINT('',(-6.244354999135E-016,0.8177134856)); +#171482 = CARTESIAN_POINT('',(-3.949641981777E-018,0.863301251813)); +#171483 = CARTESIAN_POINT('',(8.564583362975E-016,0.908908989256)); +#171484 = CARTESIAN_POINT('',(-3.439866929022E-016,0.954500792509)); +#171485 = CARTESIAN_POINT('',(-2.737282005933E-017,0.984847218355)); +#171486 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#171487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171488 = ORIENTED_EDGE('',*,*,#171489,.F.); +#171489 = EDGE_CURVE('',#171490,#171405,#171492,.T.); +#171490 = VERTEX_POINT('',#171491); +#171491 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, 0.137059047745)); -#169100 = SURFACE_CURVE('',#169101,(#169106,#169135),.PCURVE_S1.); -#169101 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169102,#169103,#169104, -#169105),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171492 = SURFACE_CURVE('',#171493,(#171498,#171527),.PCURVE_S1.); +#171493 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171494,#171495,#171496, +#171497),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169102 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, +#171494 = CARTESIAN_POINT('',(-1.3459553457,-0.531066471757, 0.137059047745)); -#169103 = CARTESIAN_POINT('',(-1.345122936235,-0.570010423697, +#171495 = CARTESIAN_POINT('',(-1.345122936235,-0.570010423697, 0.133952453327)); -#169104 = CARTESIAN_POINT('',(-1.330038843607,-0.605581001793, +#171496 = CARTESIAN_POINT('',(-1.330038843607,-0.605581001793, 0.132282534)); -#169105 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); -#169106 = PCURVE('',#168958,#169107); -#169107 = DEFINITIONAL_REPRESENTATION('',(#169108),#169134); -#169108 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169109,#169110,#169111, - #169112,#169113,#169114,#169115,#169116,#169117,#169118,#169119, - #169120,#169121,#169122,#169123,#169124,#169125,#169126,#169127, - #169128,#169129,#169130,#169131,#169132,#169133),.UNSPECIFIED.,.F., +#171497 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); +#171498 = PCURVE('',#171350,#171499); +#171499 = DEFINITIONAL_REPRESENTATION('',(#171500),#171526); +#171500 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171501,#171502,#171503, + #171504,#171505,#171506,#171507,#171508,#171509,#171510,#171511, + #171512,#171513,#171514,#171515,#171516,#171517,#171518,#171519, + #171520,#171521,#171522,#171523,#171524,#171525),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -208790,48 +211792,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169109 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169110 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#169111 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#169112 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#169113 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#169114 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#169115 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#169116 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#169117 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#169118 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#169119 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#169120 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#169121 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#169122 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#169123 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#169124 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#169125 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#169126 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#169127 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#169128 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#169129 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#169130 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#169131 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#169132 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#169133 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169135 = PCURVE('',#169136,#169141); -#169136 = CYLINDRICAL_SURFACE('',#169137,0.15); -#169137 = AXIS2_PLACEMENT_3D('',#169138,#169139,#169140); -#169138 = CARTESIAN_POINT('',(-1.233756746343,-0.563756746343, +#171501 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171502 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#171503 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#171504 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#171505 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#171506 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#171507 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#171508 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#171509 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#171510 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#171511 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#171512 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#171513 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#171514 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#171515 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#171516 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#171517 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#171518 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#171519 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#171520 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#171521 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#171522 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#171523 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#171524 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#171525 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171527 = PCURVE('',#171528,#171533); +#171528 = CYLINDRICAL_SURFACE('',#171529,0.15); +#171529 = AXIS2_PLACEMENT_3D('',#171530,#171531,#171532); +#171530 = CARTESIAN_POINT('',(-1.233756746343,-0.563756746343, 0.29788367018)); -#169139 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) +#171531 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) ); -#169140 = DIRECTION('',(0.965925826289,-4.046106982444E-017, +#171532 = DIRECTION('',(0.965925826289,-4.046106982444E-017, 0.258819045103)); -#169141 = DEFINITIONAL_REPRESENTATION('',(#169142),#169168); -#169142 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169143,#169144,#169145, - #169146,#169147,#169148,#169149,#169150,#169151,#169152,#169153, - #169154,#169155,#169156,#169157,#169158,#169159,#169160,#169161, - #169162,#169163,#169164,#169165,#169166,#169167),.UNSPECIFIED.,.F., +#171533 = DEFINITIONAL_REPRESENTATION('',(#171534),#171560); +#171534 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171535,#171536,#171537, + #171538,#171539,#171540,#171541,#171542,#171543,#171544,#171545, + #171546,#171547,#171548,#171549,#171550,#171551,#171552,#171553, + #171554,#171555,#171556,#171557,#171558,#171559),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -208839,48 +211841,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169143 = CARTESIAN_POINT('',(3.14159265359,-0.130467386467)); -#169144 = CARTESIAN_POINT('',(3.152718260825,-0.130179428809)); -#169145 = CARTESIAN_POINT('',(3.175040310705,-0.129611979589)); -#169146 = CARTESIAN_POINT('',(3.208718289392,-0.128788104595)); -#169147 = CARTESIAN_POINT('',(3.242573805888,-0.127993452596)); -#169148 = CARTESIAN_POINT('',(3.276588667066,-0.127229865101)); -#169149 = CARTESIAN_POINT('',(3.310744202863,-0.126499113534)); -#169150 = CARTESIAN_POINT('',(3.34502124338,-0.125802880314)); -#169151 = CARTESIAN_POINT('',(3.379400201195,-0.125142748927)); -#169152 = CARTESIAN_POINT('',(3.413861130172,-0.124520192363)); -#169153 = CARTESIAN_POINT('',(3.448383794636,-0.123936562949)); -#169154 = CARTESIAN_POINT('',(3.482947739147,-0.123393082955)); -#169155 = CARTESIAN_POINT('',(3.517532360737,-0.122890836312)); -#169156 = CARTESIAN_POINT('',(3.552116982328,-0.122430761502)); -#169157 = CARTESIAN_POINT('',(3.586680926839,-0.122013645726)); -#169158 = CARTESIAN_POINT('',(3.621203591303,-0.121640120431)); -#169159 = CARTESIAN_POINT('',(3.65566452028,-0.121310658249)); -#169160 = CARTESIAN_POINT('',(3.690043478095,-0.121025571345)); -#169161 = CARTESIAN_POINT('',(3.724320518612,-0.120785011321)); -#169162 = CARTESIAN_POINT('',(3.758476054408,-0.120588970126)); -#169163 = CARTESIAN_POINT('',(3.792490915587,-0.120437283911)); -#169164 = CARTESIAN_POINT('',(3.826346432082,-0.120329632363)); -#169165 = CARTESIAN_POINT('',(3.86002441077,-0.120265561081)); -#169166 = CARTESIAN_POINT('',(3.88234646065,-0.120251469511)); -#169167 = CARTESIAN_POINT('',(3.893472067885,-0.120251480798)); -#169168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169169 = ORIENTED_EDGE('',*,*,#169170,.T.); -#169170 = EDGE_CURVE('',#169098,#168949,#169171,.T.); -#169171 = SURFACE_CURVE('',#169172,(#169177,#169206),.PCURVE_S1.); -#169172 = CIRCLE('',#169173,5.E-002); -#169173 = AXIS2_PLACEMENT_3D('',#169174,#169175,#169176); -#169174 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,0.15)); -#169175 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#169176 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#169177 = PCURVE('',#168958,#169178); -#169178 = DEFINITIONAL_REPRESENTATION('',(#169179),#169205); -#169179 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169180,#169181,#169182, - #169183,#169184,#169185,#169186,#169187,#169188,#169189,#169190, - #169191,#169192,#169193,#169194,#169195,#169196,#169197,#169198, - #169199,#169200,#169201,#169202,#169203,#169204),.UNSPECIFIED.,.F., +#171535 = CARTESIAN_POINT('',(3.14159265359,-0.130467386467)); +#171536 = CARTESIAN_POINT('',(3.152718260825,-0.130179428809)); +#171537 = CARTESIAN_POINT('',(3.175040310705,-0.129611979589)); +#171538 = CARTESIAN_POINT('',(3.208718289392,-0.128788104595)); +#171539 = CARTESIAN_POINT('',(3.242573805888,-0.127993452596)); +#171540 = CARTESIAN_POINT('',(3.276588667066,-0.127229865101)); +#171541 = CARTESIAN_POINT('',(3.310744202863,-0.126499113534)); +#171542 = CARTESIAN_POINT('',(3.34502124338,-0.125802880314)); +#171543 = CARTESIAN_POINT('',(3.379400201195,-0.125142748927)); +#171544 = CARTESIAN_POINT('',(3.413861130172,-0.124520192363)); +#171545 = CARTESIAN_POINT('',(3.448383794636,-0.123936562949)); +#171546 = CARTESIAN_POINT('',(3.482947739147,-0.123393082955)); +#171547 = CARTESIAN_POINT('',(3.517532360737,-0.122890836312)); +#171548 = CARTESIAN_POINT('',(3.552116982328,-0.122430761502)); +#171549 = CARTESIAN_POINT('',(3.586680926839,-0.122013645726)); +#171550 = CARTESIAN_POINT('',(3.621203591303,-0.121640120431)); +#171551 = CARTESIAN_POINT('',(3.65566452028,-0.121310658249)); +#171552 = CARTESIAN_POINT('',(3.690043478095,-0.121025571345)); +#171553 = CARTESIAN_POINT('',(3.724320518612,-0.120785011321)); +#171554 = CARTESIAN_POINT('',(3.758476054408,-0.120588970126)); +#171555 = CARTESIAN_POINT('',(3.792490915587,-0.120437283911)); +#171556 = CARTESIAN_POINT('',(3.826346432082,-0.120329632363)); +#171557 = CARTESIAN_POINT('',(3.86002441077,-0.120265561081)); +#171558 = CARTESIAN_POINT('',(3.88234646065,-0.120251469511)); +#171559 = CARTESIAN_POINT('',(3.893472067885,-0.120251480798)); +#171560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171561 = ORIENTED_EDGE('',*,*,#171562,.T.); +#171562 = EDGE_CURVE('',#171490,#171341,#171563,.T.); +#171563 = SURFACE_CURVE('',#171564,(#171569,#171598),.PCURVE_S1.); +#171564 = CIRCLE('',#171565,5.E-002); +#171565 = AXIS2_PLACEMENT_3D('',#171566,#171567,#171568); +#171566 = CARTESIAN_POINT('',(-1.297659054385,-0.531066471757,0.15)); +#171567 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#171568 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#171569 = PCURVE('',#171350,#171570); +#171570 = DEFINITIONAL_REPRESENTATION('',(#171571),#171597); +#171571 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171572,#171573,#171574, + #171575,#171576,#171577,#171578,#171579,#171580,#171581,#171582, + #171583,#171584,#171585,#171586,#171587,#171588,#171589,#171590, + #171591,#171592,#171593,#171594,#171595,#171596),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -208888,104 +211890,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169180 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169181 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#169182 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#169183 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#169184 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#169185 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#169186 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#169187 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#169188 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#169189 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#169190 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#169191 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#169192 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#169193 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#169194 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); -#169195 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#169196 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#169197 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#169198 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#169199 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#169200 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#169201 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); -#169202 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#169203 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#169204 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169206 = PCURVE('',#169207,#169212); -#169207 = CYLINDRICAL_SURFACE('',#169208,5.E-002); -#169208 = AXIS2_PLACEMENT_3D('',#169209,#169210,#169211); -#169209 = CARTESIAN_POINT('',(-1.297659054385,0.8,0.15)); -#169210 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#169211 = DIRECTION('',(-1.,-1.355252715607E-016,0.E+000)); -#169212 = DEFINITIONAL_REPRESENTATION('',(#169213),#169216); -#169213 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#169214,#169215), +#171572 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171573 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#171574 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#171575 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#171576 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#171577 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#171578 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#171579 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#171580 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#171581 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#171582 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#171583 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#171584 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#171585 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#171586 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); +#171587 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#171588 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#171589 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#171590 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#171591 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#171592 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#171593 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); +#171594 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#171595 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#171596 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171598 = PCURVE('',#171599,#171604); +#171599 = CYLINDRICAL_SURFACE('',#171600,5.E-002); +#171600 = AXIS2_PLACEMENT_3D('',#171601,#171602,#171603); +#171601 = CARTESIAN_POINT('',(-1.297659054385,0.8,0.15)); +#171602 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#171603 = DIRECTION('',(-1.,-1.355252715607E-016,0.E+000)); +#171604 = DEFINITIONAL_REPRESENTATION('',(#171605),#171608); +#171605 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171606,#171607), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#169214 = CARTESIAN_POINT('',(6.02138591938,-1.331066471757)); -#169215 = CARTESIAN_POINT('',(4.712388980385,-1.331066471757)); -#169216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169217 = ADVANCED_FACE('',(#169218),#169233,.T.); -#169218 = FACE_BOUND('',#169219,.T.); -#169219 = EDGE_LOOP('',(#169220,#169286,#169371,#169444)); -#169220 = ORIENTED_EDGE('',*,*,#169221,.F.); -#169221 = EDGE_CURVE('',#169222,#169224,#169226,.T.); -#169222 = VERTEX_POINT('',#169223); -#169223 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); -#169224 = VERTEX_POINT('',#169225); -#169225 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); -#169226 = SURFACE_CURVE('',#169227,(#169232,#169278),.PCURVE_S1.); -#169227 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169228,#169229,#169230, -#169231),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171606 = CARTESIAN_POINT('',(6.02138591938,-1.331066471757)); +#171607 = CARTESIAN_POINT('',(4.712388980385,-1.331066471757)); +#171608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171609 = ADVANCED_FACE('',(#171610),#171625,.T.); +#171610 = FACE_BOUND('',#171611,.T.); +#171611 = EDGE_LOOP('',(#171612,#171678,#171763,#171836)); +#171612 = ORIENTED_EDGE('',*,*,#171613,.F.); +#171613 = EDGE_CURVE('',#171614,#171616,#171618,.T.); +#171614 = VERTEX_POINT('',#171615); +#171615 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); +#171616 = VERTEX_POINT('',#171617); +#171617 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); +#171618 = SURFACE_CURVE('',#171619,(#171624,#171670),.PCURVE_S1.); +#171619 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171620,#171621,#171622, +#171623),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169228 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); -#169229 = CARTESIAN_POINT('',(1.28790129499,0.581596067115,1.E-001)); -#169230 = CARTESIAN_POINT('',(1.297659054385,0.557584046027,1.E-001)); -#169231 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); -#169232 = PCURVE('',#169233,#169250); -#169233 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169234,#169235,#169236,#169237) - ,(#169238,#169239,#169240,#169241) - ,(#169242,#169243,#169244,#169245) - ,(#169246,#169247,#169248,#169249 +#171620 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); +#171621 = CARTESIAN_POINT('',(1.28790129499,0.581596067115,1.E-001)); +#171622 = CARTESIAN_POINT('',(1.297659054385,0.557584046027,1.E-001)); +#171623 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); +#171624 = PCURVE('',#171625,#171642); +#171625 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171626,#171627,#171628,#171629) + ,(#171630,#171631,#171632,#171633) + ,(#171634,#171635,#171636,#171637) + ,(#171638,#171639,#171640,#171641 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169234 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); -#169235 = CARTESIAN_POINT('',(1.319475670035,0.531066471757,1.E-001)); -#169236 = CARTESIAN_POINT('',(1.34030879007,0.531066471757, +#171626 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,1.E-001)); +#171627 = CARTESIAN_POINT('',(1.319475670035,0.531066471757,1.E-001)); +#171628 = CARTESIAN_POINT('',(1.34030879007,0.531066471757, 0.115985815246)); -#169237 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 +#171629 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 )); -#169238 = CARTESIAN_POINT('',(1.297659054385,0.55695495248,1.E-001)); -#169239 = CARTESIAN_POINT('',(1.318429042165,0.562435083194,1.E-001)); -#169240 = CARTESIAN_POINT('',(1.338443665671,0.567668168966, +#171630 = CARTESIAN_POINT('',(1.297659054385,0.55695495248,1.E-001)); +#171631 = CARTESIAN_POINT('',(1.318429042165,0.562435083194,1.E-001)); +#171632 = CARTESIAN_POINT('',(1.338443665671,0.567668168966, 0.114318476015)); -#169241 = CARTESIAN_POINT('',(1.345142684022,0.569086531164, +#171633 = CARTESIAN_POINT('',(1.345142684022,0.569086531164, 0.134026153074)); -#169242 = CARTESIAN_POINT('',(1.287470648802,0.582026713303,1.E-001)); -#169243 = CARTESIAN_POINT('',(1.305531311073,0.592452511959,1.E-001)); -#169244 = CARTESIAN_POINT('',(1.32299309093,0.602532596412, +#171634 = CARTESIAN_POINT('',(1.287470648802,0.582026713303,1.E-001)); +#171635 = CARTESIAN_POINT('',(1.305531311073,0.592452511959,1.E-001)); +#171636 = CARTESIAN_POINT('',(1.32299309093,0.602532596412, 0.113446578632)); -#169245 = CARTESIAN_POINT('',(1.329392874324,0.606226971076,0.132282534) +#171637 = CARTESIAN_POINT('',(1.329392874324,0.606226971076,0.132282534) ); -#169246 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); -#169247 = CARTESIAN_POINT('',(1.283991911516,0.613991911516,1.E-001)); -#169248 = CARTESIAN_POINT('',(1.297762843671,0.627762843671, +#171638 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); +#171639 = CARTESIAN_POINT('',(1.283991911516,0.613991911516,1.E-001)); +#171640 = CARTESIAN_POINT('',(1.297762843671,0.627762843671, 0.113446578632)); -#169249 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); -#169250 = DEFINITIONAL_REPRESENTATION('',(#169251),#169277); -#169251 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169252,#169253,#169254, - #169255,#169256,#169257,#169258,#169259,#169260,#169261,#169262, - #169263,#169264,#169265,#169266,#169267,#169268,#169269,#169270, - #169271,#169272,#169273,#169274,#169275,#169276),.UNSPECIFIED.,.F., +#171641 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); +#171642 = DEFINITIONAL_REPRESENTATION('',(#171643),#171669); +#171643 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171644,#171645,#171646, + #171647,#171648,#171649,#171650,#171651,#171652,#171653,#171654, + #171655,#171656,#171657,#171658,#171659,#171660,#171661,#171662, + #171663,#171664,#171665,#171666,#171667,#171668),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -208994,64 +211996,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#169252 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169253 = CARTESIAN_POINT('',(6.272059569215,1.375319208894E-008)); -#169254 = CARTESIAN_POINT('',(6.24973263213,2.924134010988E-005)); -#169255 = CARTESIAN_POINT('',(6.21603939964,1.413707577554E-004)); -#169256 = CARTESIAN_POINT('',(6.182167276026,3.022859270027E-004)); -#169257 = CARTESIAN_POINT('',(6.148138870073,4.931498468574E-004)); -#169258 = CARTESIAN_POINT('',(6.113975913115,6.962198987765E-004)); -#169259 = CARTESIAN_POINT('',(6.079699188623,8.953387637345E-004)); -#169260 = CARTESIAN_POINT('',(6.045328652128,1.076339414003E-003)); -#169261 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); -#169262 = CARTESIAN_POINT('',(5.976382533559,1.339263477888E-003)); -#169263 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); -#169264 = CARTESIAN_POINT('',(5.907285653264,1.422641316498E-003)); -#169265 = CARTESIAN_POINT('',(5.87272580864,1.390009812364E-003)); -#169266 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); -#169267 = CARTESIAN_POINT('',(5.803674042174,1.187353930384E-003)); -#169268 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); -#169269 = CARTESIAN_POINT('',(5.734837892756,8.475624467453E-004)); -#169270 = CARTESIAN_POINT('',(5.700549707253,6.52095293181E-004)); -#169271 = CARTESIAN_POINT('',(5.666375694827,4.570658043226E-004)); -#169272 = CARTESIAN_POINT('',(5.632337541793,2.772530388767E-004)); -#169273 = CARTESIAN_POINT('',(5.598457782919,1.282673134912E-004)); -#169274 = CARTESIAN_POINT('',(5.564759695218,2.61675624768E-005)); -#169275 = CARTESIAN_POINT('',(5.542431609433,-2.901323880985E-008)); -#169276 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169277 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169278 = PCURVE('',#168701,#169279); -#169279 = DEFINITIONAL_REPRESENTATION('',(#169280),#169285); -#169280 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169281,#169282,#169283, -#169284),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171644 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171645 = CARTESIAN_POINT('',(6.272059569215,1.375319208894E-008)); +#171646 = CARTESIAN_POINT('',(6.24973263213,2.924134010988E-005)); +#171647 = CARTESIAN_POINT('',(6.21603939964,1.413707577554E-004)); +#171648 = CARTESIAN_POINT('',(6.182167276026,3.022859270027E-004)); +#171649 = CARTESIAN_POINT('',(6.148138870073,4.931498468574E-004)); +#171650 = CARTESIAN_POINT('',(6.113975913115,6.962198987765E-004)); +#171651 = CARTESIAN_POINT('',(6.079699188623,8.953387637345E-004)); +#171652 = CARTESIAN_POINT('',(6.045328652128,1.076339414003E-003)); +#171653 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); +#171654 = CARTESIAN_POINT('',(5.976382533559,1.339263477888E-003)); +#171655 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); +#171656 = CARTESIAN_POINT('',(5.907285653264,1.422641316498E-003)); +#171657 = CARTESIAN_POINT('',(5.87272580864,1.390009812364E-003)); +#171658 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); +#171659 = CARTESIAN_POINT('',(5.803674042174,1.187353930384E-003)); +#171660 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); +#171661 = CARTESIAN_POINT('',(5.734837892756,8.475624467453E-004)); +#171662 = CARTESIAN_POINT('',(5.700549707253,6.52095293181E-004)); +#171663 = CARTESIAN_POINT('',(5.666375694827,4.570658043226E-004)); +#171664 = CARTESIAN_POINT('',(5.632337541793,2.772530388767E-004)); +#171665 = CARTESIAN_POINT('',(5.598457782919,1.282673134912E-004)); +#171666 = CARTESIAN_POINT('',(5.564759695218,2.61675624768E-005)); +#171667 = CARTESIAN_POINT('',(5.542431609433,-2.901323880985E-008)); +#171668 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171670 = PCURVE('',#171093,#171671); +#171671 = DEFINITIONAL_REPRESENTATION('',(#171672),#171677); +#171672 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171673,#171674,#171675, +#171676),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169281 = CARTESIAN_POINT('',(-0.200251318947,1.399748681053)); -#169282 = CARTESIAN_POINT('',(-0.18209870501,1.381596067115)); -#169283 = CARTESIAN_POINT('',(-0.172340945615,1.357584046027)); -#169284 = CARTESIAN_POINT('',(-0.172340945615,1.331066471757)); -#169285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169286 = ORIENTED_EDGE('',*,*,#169287,.T.); -#169287 = EDGE_CURVE('',#169222,#169288,#169290,.T.); -#169288 = VERTEX_POINT('',#169289); -#169289 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); -#169290 = SURFACE_CURVE('',#169291,(#169296,#169325),.PCURVE_S1.); -#169291 = CIRCLE('',#169292,5.E-002); -#169292 = AXIS2_PLACEMENT_3D('',#169293,#169294,#169295); -#169293 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,0.15)); -#169294 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#169295 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#169296 = PCURVE('',#169233,#169297); -#169297 = DEFINITIONAL_REPRESENTATION('',(#169298),#169324); -#169298 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169299,#169300,#169301, - #169302,#169303,#169304,#169305,#169306,#169307,#169308,#169309, - #169310,#169311,#169312,#169313,#169314,#169315,#169316,#169317, - #169318,#169319,#169320,#169321,#169322,#169323),.UNSPECIFIED.,.F., +#171673 = CARTESIAN_POINT('',(-0.200251318947,1.399748681053)); +#171674 = CARTESIAN_POINT('',(-0.18209870501,1.381596067115)); +#171675 = CARTESIAN_POINT('',(-0.172340945615,1.357584046027)); +#171676 = CARTESIAN_POINT('',(-0.172340945615,1.331066471757)); +#171677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171678 = ORIENTED_EDGE('',*,*,#171679,.T.); +#171679 = EDGE_CURVE('',#171614,#171680,#171682,.T.); +#171680 = VERTEX_POINT('',#171681); +#171681 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); +#171682 = SURFACE_CURVE('',#171683,(#171688,#171717),.PCURVE_S1.); +#171683 = CIRCLE('',#171684,5.E-002); +#171684 = AXIS2_PLACEMENT_3D('',#171685,#171686,#171687); +#171685 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,0.15)); +#171686 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#171687 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#171688 = PCURVE('',#171625,#171689); +#171689 = DEFINITIONAL_REPRESENTATION('',(#171690),#171716); +#171690 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171691,#171692,#171693, + #171694,#171695,#171696,#171697,#171698,#171699,#171700,#171701, + #171702,#171703,#171704,#171705,#171706,#171707,#171708,#171709, + #171710,#171711,#171712,#171713,#171714,#171715),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -209059,70 +212061,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169299 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169300 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#169301 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#169302 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#169303 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#169304 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#169305 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#169306 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#169307 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#169308 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#169309 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#169310 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#169311 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#169312 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#169313 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#169314 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#169315 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#169316 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#169317 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#169318 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#169319 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#169320 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#169321 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#169322 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#169323 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169325 = PCURVE('',#169326,#169343); -#169326 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169327,#169328,#169329,#169330) - ,(#169331,#169332,#169333,#169334) - ,(#169335,#169336,#169337,#169338) - ,(#169339,#169340,#169341,#169342 +#171691 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171692 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#171693 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#171694 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#171695 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#171696 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#171697 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#171698 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#171699 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#171700 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#171701 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#171702 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#171703 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#171704 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#171705 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#171706 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#171707 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#171708 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#171709 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#171710 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#171711 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#171712 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#171713 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#171714 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#171715 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171717 = PCURVE('',#171718,#171735); +#171718 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171719,#171720,#171721,#171722) + ,(#171723,#171724,#171725,#171726) + ,(#171727,#171728,#171729,#171730) + ,(#171731,#171732,#171733,#171734 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(7.453889935838E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169327 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); -#169328 = CARTESIAN_POINT('',(1.283991911516,0.613991911516,1.E-001)); -#169329 = CARTESIAN_POINT('',(1.297762843671,0.627762843671, +#171719 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); +#171720 = CARTESIAN_POINT('',(1.283991911516,0.613991911516,1.E-001)); +#171721 = CARTESIAN_POINT('',(1.297762843671,0.627762843671, 0.113446578632)); -#169330 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); -#169331 = CARTESIAN_POINT('',(1.252026713303,0.617470648802,1.E-001)); -#169332 = CARTESIAN_POINT('',(1.262452511959,0.635531311073,1.E-001)); -#169333 = CARTESIAN_POINT('',(1.272532596412,0.65299309093, +#171722 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); +#171723 = CARTESIAN_POINT('',(1.252026713303,0.617470648802,1.E-001)); +#171724 = CARTESIAN_POINT('',(1.262452511959,0.635531311073,1.E-001)); +#171725 = CARTESIAN_POINT('',(1.272532596412,0.65299309093, 0.113446578632)); -#169334 = CARTESIAN_POINT('',(1.276226971076,0.659392874324,0.132282534) +#171726 = CARTESIAN_POINT('',(1.276226971076,0.659392874324,0.132282534) ); -#169335 = CARTESIAN_POINT('',(1.22695495248,0.627659054385,1.E-001)); -#169336 = CARTESIAN_POINT('',(1.232435083194,0.648429042165,1.E-001)); -#169337 = CARTESIAN_POINT('',(1.237668168966,0.668443665671, +#171727 = CARTESIAN_POINT('',(1.22695495248,0.627659054385,1.E-001)); +#171728 = CARTESIAN_POINT('',(1.232435083194,0.648429042165,1.E-001)); +#171729 = CARTESIAN_POINT('',(1.237668168966,0.668443665671, 0.114318476015)); -#169338 = CARTESIAN_POINT('',(1.239086531164,0.675142684022, +#171730 = CARTESIAN_POINT('',(1.239086531164,0.675142684022, 0.134026153074)); -#169339 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); -#169340 = CARTESIAN_POINT('',(1.201066471757,0.649475670035,1.E-001)); -#169341 = CARTESIAN_POINT('',(1.201066471757,0.67030879007, +#171731 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); +#171732 = CARTESIAN_POINT('',(1.201066471757,0.649475670035,1.E-001)); +#171733 = CARTESIAN_POINT('',(1.201066471757,0.67030879007, 0.115985815246)); -#169342 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 +#171734 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 )); -#169343 = DEFINITIONAL_REPRESENTATION('',(#169344),#169370); -#169344 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169345,#169346,#169347, - #169348,#169349,#169350,#169351,#169352,#169353,#169354,#169355, - #169356,#169357,#169358,#169359,#169360,#169361,#169362,#169363, - #169364,#169365,#169366,#169367,#169368,#169369),.UNSPECIFIED.,.F., +#171735 = DEFINITIONAL_REPRESENTATION('',(#171736),#171762); +#171736 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171737,#171738,#171739, + #171740,#171741,#171742,#171743,#171744,#171745,#171746,#171747, + #171748,#171749,#171750,#171751,#171752,#171753,#171754,#171755, + #171756,#171757,#171758,#171759,#171760,#171761),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -209130,58 +212132,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169345 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#169346 = CARTESIAN_POINT('',(3.182778260938E-015,1.515278164503E-002)); -#169347 = CARTESIAN_POINT('',(4.917472208917E-015,4.549920749134E-002)); -#169348 = CARTESIAN_POINT('',(2.667183505798E-015,9.109101074356E-002)); -#169349 = CARTESIAN_POINT('',(2.542923082486E-015,0.136698748187)); -#169350 = CARTESIAN_POINT('',(3.086530649608E-015,0.1822865144)); -#169351 = CARTESIAN_POINT('',(3.030131277102E-015,0.2278300409)); -#169352 = CARTESIAN_POINT('',(5.57702116374E-016,0.27331674602)); -#169353 = CARTESIAN_POINT('',(2.733185497753E-016,0.318743220066)); -#169354 = CARTESIAN_POINT('',(1.466427048709E-015,0.364113426255)); -#169355 = CARTESIAN_POINT('',(2.179794601582E-015,0.409436881051)); -#169356 = CARTESIAN_POINT('',(-4.797347793256E-016,0.454727066523)); -#169357 = CARTESIAN_POINT('',(3.399952520448E-015,0.5)); -#169358 = CARTESIAN_POINT('',(-1.078444880883E-015,0.545272933477)); -#169359 = CARTESIAN_POINT('',(3.559625237581E-015,0.590563118949)); -#169360 = CARTESIAN_POINT('',(1.002677584272E-015,0.635886573745)); -#169361 = CARTESIAN_POINT('',(8.803940494535E-016,0.681256779934)); -#169362 = CARTESIAN_POINT('',(1.565692304759E-015,0.72668325398)); -#169363 = CARTESIAN_POINT('',(-9.954723332179E-017,0.7721699591)); -#169364 = CARTESIAN_POINT('',(2.168003715351E-016,0.8177134856)); -#169365 = CARTESIAN_POINT('',(1.462855007613E-015,0.863301251813)); -#169366 = CARTESIAN_POINT('',(2.234712226566E-016,0.908908989256)); -#169367 = CARTESIAN_POINT('',(1.611600225266E-015,0.954500792509)); -#169368 = CARTESIAN_POINT('',(1.404048840344E-015,0.984847218355)); -#169369 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#169370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169371 = ORIENTED_EDGE('',*,*,#169372,.F.); -#169372 = EDGE_CURVE('',#169373,#169288,#169375,.T.); -#169373 = VERTEX_POINT('',#169374); -#169374 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 +#171737 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#171738 = CARTESIAN_POINT('',(3.182778260938E-015,1.515278164503E-002)); +#171739 = CARTESIAN_POINT('',(4.917472208917E-015,4.549920749134E-002)); +#171740 = CARTESIAN_POINT('',(2.667183505798E-015,9.109101074356E-002)); +#171741 = CARTESIAN_POINT('',(2.542923082486E-015,0.136698748187)); +#171742 = CARTESIAN_POINT('',(3.086530649608E-015,0.1822865144)); +#171743 = CARTESIAN_POINT('',(3.030131277102E-015,0.2278300409)); +#171744 = CARTESIAN_POINT('',(5.57702116374E-016,0.27331674602)); +#171745 = CARTESIAN_POINT('',(2.733185497753E-016,0.318743220066)); +#171746 = CARTESIAN_POINT('',(1.466427048709E-015,0.364113426255)); +#171747 = CARTESIAN_POINT('',(2.179794601582E-015,0.409436881051)); +#171748 = CARTESIAN_POINT('',(-4.797347793256E-016,0.454727066523)); +#171749 = CARTESIAN_POINT('',(3.399952520448E-015,0.5)); +#171750 = CARTESIAN_POINT('',(-1.078444880883E-015,0.545272933477)); +#171751 = CARTESIAN_POINT('',(3.559625237581E-015,0.590563118949)); +#171752 = CARTESIAN_POINT('',(1.002677584272E-015,0.635886573745)); +#171753 = CARTESIAN_POINT('',(8.803940494535E-016,0.681256779934)); +#171754 = CARTESIAN_POINT('',(1.565692304759E-015,0.72668325398)); +#171755 = CARTESIAN_POINT('',(-9.954723332179E-017,0.7721699591)); +#171756 = CARTESIAN_POINT('',(2.168003715351E-016,0.8177134856)); +#171757 = CARTESIAN_POINT('',(1.462855007613E-015,0.863301251813)); +#171758 = CARTESIAN_POINT('',(2.234712226566E-016,0.908908989256)); +#171759 = CARTESIAN_POINT('',(1.611600225266E-015,0.954500792509)); +#171760 = CARTESIAN_POINT('',(1.404048840344E-015,0.984847218355)); +#171761 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#171762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171763 = ORIENTED_EDGE('',*,*,#171764,.F.); +#171764 = EDGE_CURVE('',#171765,#171680,#171767,.T.); +#171765 = VERTEX_POINT('',#171766); +#171766 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 )); -#169375 = SURFACE_CURVE('',#169376,(#169381,#169410),.PCURVE_S1.); -#169376 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169377,#169378,#169379, -#169380),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171767 = SURFACE_CURVE('',#171768,(#171773,#171802),.PCURVE_S1.); +#171768 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171769,#171770,#171771, +#171772),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169377 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 +#171769 = CARTESIAN_POINT('',(1.3459553457,0.531066471757,0.137059047745 )); -#169378 = CARTESIAN_POINT('',(1.345122936235,0.570010423697, +#171770 = CARTESIAN_POINT('',(1.345122936235,0.570010423697, 0.133952453327)); -#169379 = CARTESIAN_POINT('',(1.330038843607,0.605581001793,0.132282534) - ); -#169380 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); -#169381 = PCURVE('',#169233,#169382); -#169382 = DEFINITIONAL_REPRESENTATION('',(#169383),#169409); -#169383 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169384,#169385,#169386, - #169387,#169388,#169389,#169390,#169391,#169392,#169393,#169394, - #169395,#169396,#169397,#169398,#169399,#169400,#169401,#169402, - #169403,#169404,#169405,#169406,#169407,#169408),.UNSPECIFIED.,.F., +#171771 = CARTESIAN_POINT('',(1.330038843607,0.605581001793,0.132282534) + ); +#171772 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); +#171773 = PCURVE('',#171625,#171774); +#171774 = DEFINITIONAL_REPRESENTATION('',(#171775),#171801); +#171775 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171776,#171777,#171778, + #171779,#171780,#171781,#171782,#171783,#171784,#171785,#171786, + #171787,#171788,#171789,#171790,#171791,#171792,#171793,#171794, + #171795,#171796,#171797,#171798,#171799,#171800),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -209189,47 +212191,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169384 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169385 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#169386 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#169387 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#169388 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#169389 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#169390 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#169391 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#169392 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#169393 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#169394 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#169395 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#169396 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#169397 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#169398 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#169399 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#169400 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#169401 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#169402 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#169403 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#169404 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#169405 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#169406 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#169407 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#169408 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169410 = PCURVE('',#169411,#169416); -#169411 = CYLINDRICAL_SURFACE('',#169412,0.15); -#169412 = AXIS2_PLACEMENT_3D('',#169413,#169414,#169415); -#169413 = CARTESIAN_POINT('',(1.334207498814,0.664207498814, +#171776 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171777 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#171778 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#171779 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#171780 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#171781 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#171782 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#171783 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#171784 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#171785 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#171786 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#171787 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#171788 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#171789 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#171790 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#171791 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#171792 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#171793 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#171794 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#171795 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#171796 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#171797 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#171798 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#171799 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#171800 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171802 = PCURVE('',#171803,#171808); +#171803 = CYLINDRICAL_SURFACE('',#171804,0.15); +#171804 = AXIS2_PLACEMENT_3D('',#171805,#171806,#171807); +#171805 = CARTESIAN_POINT('',(1.334207498814,0.664207498814, 0.672770982062)); -#169414 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#169415 = DIRECTION('',(0.965925826289,-1.331129217269E-016, +#171806 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#171807 = DIRECTION('',(0.965925826289,-1.331129217269E-016, -0.258819045103)); -#169416 = DEFINITIONAL_REPRESENTATION('',(#169417),#169443); -#169417 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169418,#169419,#169420, - #169421,#169422,#169423,#169424,#169425,#169426,#169427,#169428, - #169429,#169430,#169431,#169432,#169433,#169434,#169435,#169436, - #169437,#169438,#169439,#169440,#169441,#169442),.UNSPECIFIED.,.F., +#171808 = DEFINITIONAL_REPRESENTATION('',(#171809),#171835); +#171809 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171810,#171811,#171812, + #171813,#171814,#171815,#171816,#171817,#171818,#171819,#171820, + #171821,#171822,#171823,#171824,#171825,#171826,#171827,#171828, + #171829,#171830,#171831,#171832,#171833,#171834),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -209237,48 +212239,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169418 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#169419 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); -#169420 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); -#169421 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); -#169422 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); -#169423 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); -#169424 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); -#169425 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); -#169426 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); -#169427 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); -#169428 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); -#169429 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); -#169430 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); -#169431 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); -#169432 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); -#169433 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); -#169434 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); -#169435 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); -#169436 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); -#169437 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); -#169438 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); -#169439 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); -#169440 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); -#169441 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); -#169442 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#169443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169444 = ORIENTED_EDGE('',*,*,#169445,.F.); -#169445 = EDGE_CURVE('',#169224,#169373,#169446,.T.); -#169446 = SURFACE_CURVE('',#169447,(#169452,#169481),.PCURVE_S1.); -#169447 = CIRCLE('',#169448,5.E-002); -#169448 = AXIS2_PLACEMENT_3D('',#169449,#169450,#169451); -#169449 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,0.15)); -#169450 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#169451 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#169452 = PCURVE('',#169233,#169453); -#169453 = DEFINITIONAL_REPRESENTATION('',(#169454),#169480); -#169454 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169455,#169456,#169457, - #169458,#169459,#169460,#169461,#169462,#169463,#169464,#169465, - #169466,#169467,#169468,#169469,#169470,#169471,#169472,#169473, - #169474,#169475,#169476,#169477,#169478,#169479),.UNSPECIFIED.,.F., +#171810 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#171811 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); +#171812 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); +#171813 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); +#171814 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); +#171815 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); +#171816 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); +#171817 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); +#171818 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); +#171819 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); +#171820 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); +#171821 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); +#171822 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); +#171823 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); +#171824 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); +#171825 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); +#171826 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); +#171827 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); +#171828 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); +#171829 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); +#171830 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); +#171831 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); +#171832 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); +#171833 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); +#171834 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#171835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171836 = ORIENTED_EDGE('',*,*,#171837,.F.); +#171837 = EDGE_CURVE('',#171616,#171765,#171838,.T.); +#171838 = SURFACE_CURVE('',#171839,(#171844,#171873),.PCURVE_S1.); +#171839 = CIRCLE('',#171840,5.E-002); +#171840 = AXIS2_PLACEMENT_3D('',#171841,#171842,#171843); +#171841 = CARTESIAN_POINT('',(1.297659054385,0.531066471757,0.15)); +#171842 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#171843 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#171844 = PCURVE('',#171625,#171845); +#171845 = DEFINITIONAL_REPRESENTATION('',(#171846),#171872); +#171846 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171847,#171848,#171849, + #171850,#171851,#171852,#171853,#171854,#171855,#171856,#171857, + #171858,#171859,#171860,#171861,#171862,#171863,#171864,#171865, + #171866,#171867,#171868,#171869,#171870,#171871),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -209286,104 +212288,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#169455 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169456 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#169457 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#169458 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#169459 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#169460 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#169461 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#169462 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#169463 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#169464 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#169465 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); -#169466 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#169467 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#169468 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#169469 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#169470 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#169471 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#169472 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#169473 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#169474 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#169475 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#169476 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#169477 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#169478 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#169479 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169481 = PCURVE('',#169482,#169487); -#169482 = CYLINDRICAL_SURFACE('',#169483,5.E-002); -#169483 = AXIS2_PLACEMENT_3D('',#169484,#169485,#169486); -#169484 = CARTESIAN_POINT('',(1.297659054385,0.8,0.15)); -#169485 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#169486 = DIRECTION('',(1.,1.355252715607E-016,0.E+000)); -#169487 = DEFINITIONAL_REPRESENTATION('',(#169488),#169491); -#169488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#169489,#169490), +#171847 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171848 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#171849 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#171850 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#171851 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#171852 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#171853 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#171854 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#171855 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#171856 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#171857 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); +#171858 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#171859 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#171860 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#171861 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#171862 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#171863 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#171864 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#171865 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#171866 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#171867 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#171868 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#171869 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#171870 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#171871 = CARTESIAN_POINT('',(5.531305892885,1.)); +#171872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171873 = PCURVE('',#171874,#171879); +#171874 = CYLINDRICAL_SURFACE('',#171875,5.E-002); +#171875 = AXIS2_PLACEMENT_3D('',#171876,#171877,#171878); +#171876 = CARTESIAN_POINT('',(1.297659054385,0.8,0.15)); +#171877 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#171878 = DIRECTION('',(1.,1.355252715607E-016,0.E+000)); +#171879 = DEFINITIONAL_REPRESENTATION('',(#171880),#171883); +#171880 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171881,#171882), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#169489 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#169490 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#169491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169492 = ADVANCED_FACE('',(#169493),#169508,.T.); -#169493 = FACE_BOUND('',#169494,.T.); -#169494 = EDGE_LOOP('',(#169495,#169561,#169646,#169719)); -#169495 = ORIENTED_EDGE('',*,*,#169496,.F.); -#169496 = EDGE_CURVE('',#169497,#169499,#169501,.T.); -#169497 = VERTEX_POINT('',#169498); -#169498 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); -#169499 = VERTEX_POINT('',#169500); -#169500 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); -#169501 = SURFACE_CURVE('',#169502,(#169507,#169553),.PCURVE_S1.); -#169502 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169503,#169504,#169505, -#169506),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171881 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#171882 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#171883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171884 = ADVANCED_FACE('',(#171885),#171900,.T.); +#171885 = FACE_BOUND('',#171886,.T.); +#171886 = EDGE_LOOP('',(#171887,#171953,#172038,#172111)); +#171887 = ORIENTED_EDGE('',*,*,#171888,.F.); +#171888 = EDGE_CURVE('',#171889,#171891,#171893,.T.); +#171889 = VERTEX_POINT('',#171890); +#171890 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); +#171891 = VERTEX_POINT('',#171892); +#171892 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); +#171893 = SURFACE_CURVE('',#171894,(#171899,#171945),.PCURVE_S1.); +#171894 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171895,#171896,#171897, +#171898),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169503 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); -#169504 = CARTESIAN_POINT('',(-1.251596067115,0.61790129499,1.E-001)); -#169505 = CARTESIAN_POINT('',(-1.227584046027,0.627659054385,1.E-001)); -#169506 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); -#169507 = PCURVE('',#169508,#169525); -#169508 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169509,#169510,#169511,#169512) - ,(#169513,#169514,#169515,#169516) - ,(#169517,#169518,#169519,#169520) - ,(#169521,#169522,#169523,#169524 +#171895 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); +#171896 = CARTESIAN_POINT('',(-1.251596067115,0.61790129499,1.E-001)); +#171897 = CARTESIAN_POINT('',(-1.227584046027,0.627659054385,1.E-001)); +#171898 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); +#171899 = PCURVE('',#171900,#171917); +#171900 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171901,#171902,#171903,#171904) + ,(#171905,#171906,#171907,#171908) + ,(#171909,#171910,#171911,#171912) + ,(#171913,#171914,#171915,#171916 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169509 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); -#169510 = CARTESIAN_POINT('',(-1.201066471757,0.649475670035,1.E-001)); -#169511 = CARTESIAN_POINT('',(-1.201066471757,0.67030879007, +#171901 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,1.E-001)); +#171902 = CARTESIAN_POINT('',(-1.201066471757,0.649475670035,1.E-001)); +#171903 = CARTESIAN_POINT('',(-1.201066471757,0.67030879007, 0.115985815246)); -#169512 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, +#171904 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, 0.137059047745)); -#169513 = CARTESIAN_POINT('',(-1.22695495248,0.627659054385,1.E-001)); -#169514 = CARTESIAN_POINT('',(-1.232435083194,0.648429042165,1.E-001)); -#169515 = CARTESIAN_POINT('',(-1.237668168966,0.668443665671, +#171905 = CARTESIAN_POINT('',(-1.22695495248,0.627659054385,1.E-001)); +#171906 = CARTESIAN_POINT('',(-1.232435083194,0.648429042165,1.E-001)); +#171907 = CARTESIAN_POINT('',(-1.237668168966,0.668443665671, 0.114318476015)); -#169516 = CARTESIAN_POINT('',(-1.239086531164,0.675142684022, +#171908 = CARTESIAN_POINT('',(-1.239086531164,0.675142684022, 0.134026153074)); -#169517 = CARTESIAN_POINT('',(-1.252026713303,0.617470648802,1.E-001)); -#169518 = CARTESIAN_POINT('',(-1.262452511959,0.635531311073,1.E-001)); -#169519 = CARTESIAN_POINT('',(-1.272532596412,0.65299309093, +#171909 = CARTESIAN_POINT('',(-1.252026713303,0.617470648802,1.E-001)); +#171910 = CARTESIAN_POINT('',(-1.262452511959,0.635531311073,1.E-001)); +#171911 = CARTESIAN_POINT('',(-1.272532596412,0.65299309093, 0.113446578632)); -#169520 = CARTESIAN_POINT('',(-1.276226971076,0.659392874324,0.132282534 +#171912 = CARTESIAN_POINT('',(-1.276226971076,0.659392874324,0.132282534 )); -#169521 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); -#169522 = CARTESIAN_POINT('',(-1.283991911516,0.613991911516,1.E-001)); -#169523 = CARTESIAN_POINT('',(-1.297762843671,0.627762843671, +#171913 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); +#171914 = CARTESIAN_POINT('',(-1.283991911516,0.613991911516,1.E-001)); +#171915 = CARTESIAN_POINT('',(-1.297762843671,0.627762843671, 0.113446578632)); -#169524 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); -#169525 = DEFINITIONAL_REPRESENTATION('',(#169526),#169552); -#169526 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169527,#169528,#169529, - #169530,#169531,#169532,#169533,#169534,#169535,#169536,#169537, - #169538,#169539,#169540,#169541,#169542,#169543,#169544,#169545, - #169546,#169547,#169548,#169549,#169550,#169551),.UNSPECIFIED.,.F., +#171916 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); +#171917 = DEFINITIONAL_REPRESENTATION('',(#171918),#171944); +#171918 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171919,#171920,#171921, + #171922,#171923,#171924,#171925,#171926,#171927,#171928,#171929, + #171930,#171931,#171932,#171933,#171934,#171935,#171936,#171937, + #171938,#171939,#171940,#171941,#171942,#171943),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 8.809142651445E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -209392,64 +212394,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#169527 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169528 = CARTESIAN_POINT('',(6.272059569215,1.37531873857E-008)); -#169529 = CARTESIAN_POINT('',(6.24973263213,2.924134010582E-005)); -#169530 = CARTESIAN_POINT('',(6.21603939964,1.413707577664E-004)); -#169531 = CARTESIAN_POINT('',(6.182167276026,3.022859269923E-004)); -#169532 = CARTESIAN_POINT('',(6.148138870073,4.931498468592E-004)); -#169533 = CARTESIAN_POINT('',(6.113975913115,6.962198987652E-004)); -#169534 = CARTESIAN_POINT('',(6.079699188623,8.953387637294E-004)); -#169535 = CARTESIAN_POINT('',(6.045328652128,1.076339414004E-003)); -#169536 = CARTESIAN_POINT('',(6.010883543172,1.227390254473E-003)); -#169537 = CARTESIAN_POINT('',(5.976382533559,1.339263477881E-003)); -#169538 = CARTESIAN_POINT('',(5.941843890817,1.405524714326E-003)); -#169539 = CARTESIAN_POINT('',(5.907285653264,1.422641316495E-003)); -#169540 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); -#169541 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); -#169542 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); -#169543 = CARTESIAN_POINT('',(5.769219374506,1.029943289551E-003)); -#169544 = CARTESIAN_POINT('',(5.734837892756,8.475624467429E-004)); -#169545 = CARTESIAN_POINT('',(5.700549707253,6.520952931796E-004)); -#169546 = CARTESIAN_POINT('',(5.666375694827,4.570658043151E-004)); -#169547 = CARTESIAN_POINT('',(5.632337541793,2.772530388733E-004)); -#169548 = CARTESIAN_POINT('',(5.598457782919,1.282673134882E-004)); -#169549 = CARTESIAN_POINT('',(5.564759695218,2.616756247072E-005)); -#169550 = CARTESIAN_POINT('',(5.542431609433,-2.901324240656E-008)); -#169551 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169553 = PCURVE('',#168701,#169554); -#169554 = DEFINITIONAL_REPRESENTATION('',(#169555),#169560); -#169555 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169556,#169557,#169558, -#169559),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#171919 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171920 = CARTESIAN_POINT('',(6.272059569215,1.37531873857E-008)); +#171921 = CARTESIAN_POINT('',(6.24973263213,2.924134010582E-005)); +#171922 = CARTESIAN_POINT('',(6.21603939964,1.413707577664E-004)); +#171923 = CARTESIAN_POINT('',(6.182167276026,3.022859269923E-004)); +#171924 = CARTESIAN_POINT('',(6.148138870073,4.931498468592E-004)); +#171925 = CARTESIAN_POINT('',(6.113975913115,6.962198987652E-004)); +#171926 = CARTESIAN_POINT('',(6.079699188623,8.953387637294E-004)); +#171927 = CARTESIAN_POINT('',(6.045328652128,1.076339414004E-003)); +#171928 = CARTESIAN_POINT('',(6.010883543172,1.227390254473E-003)); +#171929 = CARTESIAN_POINT('',(5.976382533559,1.339263477881E-003)); +#171930 = CARTESIAN_POINT('',(5.941843890817,1.405524714326E-003)); +#171931 = CARTESIAN_POINT('',(5.907285653264,1.422641316495E-003)); +#171932 = CARTESIAN_POINT('',(5.87272580864,1.390009812361E-003)); +#171933 = CARTESIAN_POINT('',(5.838182469936,1.30990486719E-003)); +#171934 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); +#171935 = CARTESIAN_POINT('',(5.769219374506,1.029943289551E-003)); +#171936 = CARTESIAN_POINT('',(5.734837892756,8.475624467429E-004)); +#171937 = CARTESIAN_POINT('',(5.700549707253,6.520952931796E-004)); +#171938 = CARTESIAN_POINT('',(5.666375694827,4.570658043151E-004)); +#171939 = CARTESIAN_POINT('',(5.632337541793,2.772530388733E-004)); +#171940 = CARTESIAN_POINT('',(5.598457782919,1.282673134882E-004)); +#171941 = CARTESIAN_POINT('',(5.564759695218,2.616756247072E-005)); +#171942 = CARTESIAN_POINT('',(5.542431609433,-2.901324240656E-008)); +#171943 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#171944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171945 = PCURVE('',#171093,#171946); +#171946 = DEFINITIONAL_REPRESENTATION('',(#171947),#171952); +#171947 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#171948,#171949,#171950, +#171951),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169556 = CARTESIAN_POINT('',(-2.739748681053,1.399748681053)); -#169557 = CARTESIAN_POINT('',(-2.721596067115,1.41790129499)); -#169558 = CARTESIAN_POINT('',(-2.697584046027,1.427659054385)); -#169559 = CARTESIAN_POINT('',(-2.671066471757,1.427659054385)); -#169560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169561 = ORIENTED_EDGE('',*,*,#169562,.T.); -#169562 = EDGE_CURVE('',#169497,#169563,#169565,.T.); -#169563 = VERTEX_POINT('',#169564); -#169564 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); -#169565 = SURFACE_CURVE('',#169566,(#169571,#169600),.PCURVE_S1.); -#169566 = CIRCLE('',#169567,5.E-002); -#169567 = AXIS2_PLACEMENT_3D('',#169568,#169569,#169570); -#169568 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,0.15)); -#169569 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#169570 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#169571 = PCURVE('',#169508,#169572); -#169572 = DEFINITIONAL_REPRESENTATION('',(#169573),#169599); -#169573 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169574,#169575,#169576, - #169577,#169578,#169579,#169580,#169581,#169582,#169583,#169584, - #169585,#169586,#169587,#169588,#169589,#169590,#169591,#169592, - #169593,#169594,#169595,#169596,#169597,#169598),.UNSPECIFIED.,.F., +#171948 = CARTESIAN_POINT('',(-2.739748681053,1.399748681053)); +#171949 = CARTESIAN_POINT('',(-2.721596067115,1.41790129499)); +#171950 = CARTESIAN_POINT('',(-2.697584046027,1.427659054385)); +#171951 = CARTESIAN_POINT('',(-2.671066471757,1.427659054385)); +#171952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171953 = ORIENTED_EDGE('',*,*,#171954,.T.); +#171954 = EDGE_CURVE('',#171889,#171955,#171957,.T.); +#171955 = VERTEX_POINT('',#171956); +#171956 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); +#171957 = SURFACE_CURVE('',#171958,(#171963,#171992),.PCURVE_S1.); +#171958 = CIRCLE('',#171959,5.E-002); +#171959 = AXIS2_PLACEMENT_3D('',#171960,#171961,#171962); +#171960 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,0.15)); +#171961 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#171962 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#171963 = PCURVE('',#171900,#171964); +#171964 = DEFINITIONAL_REPRESENTATION('',(#171965),#171991); +#171965 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171966,#171967,#171968, + #171969,#171970,#171971,#171972,#171973,#171974,#171975,#171976, + #171977,#171978,#171979,#171980,#171981,#171982,#171983,#171984, + #171985,#171986,#171987,#171988,#171989,#171990),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -209457,70 +212459,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169574 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169575 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#169576 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#169577 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#169578 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#169579 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#169580 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#169581 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#169582 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#169583 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#169584 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#169585 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#169586 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#169587 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#169588 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#169589 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#169590 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#169591 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#169592 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#169593 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#169594 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#169595 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#169596 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#169597 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#169598 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169600 = PCURVE('',#169601,#169618); -#169601 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169602,#169603,#169604,#169605) - ,(#169606,#169607,#169608,#169609) - ,(#169610,#169611,#169612,#169613) - ,(#169614,#169615,#169616,#169617 +#171966 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#171967 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#171968 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#171969 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#171970 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#171971 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#171972 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#171973 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#171974 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#171975 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#171976 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#171977 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#171978 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#171979 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#171980 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#171981 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#171982 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#171983 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#171984 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#171985 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#171986 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#171987 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#171988 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#171989 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#171990 = CARTESIAN_POINT('',(6.28318530718,1.)); +#171991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#171992 = PCURVE('',#171993,#172010); +#171993 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#171994,#171995,#171996,#171997) + ,(#171998,#171999,#172000,#172001) + ,(#172002,#172003,#172004,#172005) + ,(#172006,#172007,#172008,#172009 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169602 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); -#169603 = CARTESIAN_POINT('',(-1.283991911516,0.613991911516,1.E-001)); -#169604 = CARTESIAN_POINT('',(-1.297762843671,0.627762843671, +#171994 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); +#171995 = CARTESIAN_POINT('',(-1.283991911516,0.613991911516,1.E-001)); +#171996 = CARTESIAN_POINT('',(-1.297762843671,0.627762843671, 0.113446578632)); -#169605 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); -#169606 = CARTESIAN_POINT('',(-1.287470648802,0.582026713303,1.E-001)); -#169607 = CARTESIAN_POINT('',(-1.305531311073,0.592452511959,1.E-001)); -#169608 = CARTESIAN_POINT('',(-1.32299309093,0.602532596412, +#171997 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); +#171998 = CARTESIAN_POINT('',(-1.287470648802,0.582026713303,1.E-001)); +#171999 = CARTESIAN_POINT('',(-1.305531311073,0.592452511959,1.E-001)); +#172000 = CARTESIAN_POINT('',(-1.32299309093,0.602532596412, 0.113446578632)); -#169609 = CARTESIAN_POINT('',(-1.329392874324,0.606226971076,0.132282534 +#172001 = CARTESIAN_POINT('',(-1.329392874324,0.606226971076,0.132282534 )); -#169610 = CARTESIAN_POINT('',(-1.297659054385,0.55695495248,1.E-001)); -#169611 = CARTESIAN_POINT('',(-1.318429042165,0.562435083194,1.E-001)); -#169612 = CARTESIAN_POINT('',(-1.338443665671,0.567668168966, +#172002 = CARTESIAN_POINT('',(-1.297659054385,0.55695495248,1.E-001)); +#172003 = CARTESIAN_POINT('',(-1.318429042165,0.562435083194,1.E-001)); +#172004 = CARTESIAN_POINT('',(-1.338443665671,0.567668168966, 0.114318476015)); -#169613 = CARTESIAN_POINT('',(-1.345142684022,0.569086531164, +#172005 = CARTESIAN_POINT('',(-1.345142684022,0.569086531164, 0.134026153074)); -#169614 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); -#169615 = CARTESIAN_POINT('',(-1.319475670035,0.531066471757,1.E-001)); -#169616 = CARTESIAN_POINT('',(-1.34030879007,0.531066471757, +#172006 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); +#172007 = CARTESIAN_POINT('',(-1.319475670035,0.531066471757,1.E-001)); +#172008 = CARTESIAN_POINT('',(-1.34030879007,0.531066471757, 0.115985815246)); -#169617 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, +#172009 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, 0.137059047745)); -#169618 = DEFINITIONAL_REPRESENTATION('',(#169619),#169645); -#169619 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169620,#169621,#169622, - #169623,#169624,#169625,#169626,#169627,#169628,#169629,#169630, - #169631,#169632,#169633,#169634,#169635,#169636,#169637,#169638, - #169639,#169640,#169641,#169642,#169643,#169644),.UNSPECIFIED.,.F., +#172010 = DEFINITIONAL_REPRESENTATION('',(#172011),#172037); +#172011 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172012,#172013,#172014, + #172015,#172016,#172017,#172018,#172019,#172020,#172021,#172022, + #172023,#172024,#172025,#172026,#172027,#172028,#172029,#172030, + #172031,#172032,#172033,#172034,#172035,#172036),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -209528,59 +212530,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#169620 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#169621 = CARTESIAN_POINT('',(-7.712029133934E-016,1.515278164504E-002) - ); -#169622 = CARTESIAN_POINT('',(1.25625350775E-016,4.549920749135E-002)); -#169623 = CARTESIAN_POINT('',(1.821600457514E-015,9.109101074357E-002)); -#169624 = CARTESIAN_POINT('',(1.184686899972E-016,0.136698748187)); -#169625 = CARTESIAN_POINT('',(-1.341817644549E-015,0.1822865144)); -#169626 = CARTESIAN_POINT('',(-3.87939999787E-016,0.2278300409)); -#169627 = CARTESIAN_POINT('',(-1.122364033566E-015,0.27331674602)); -#169628 = CARTESIAN_POINT('',(2.456563704797E-015,0.318743220066)); -#169629 = CARTESIAN_POINT('',(-1.720316333122E-015,0.364113426255)); -#169630 = CARTESIAN_POINT('',(1.581331095141E-015,0.409436881051)); -#169631 = CARTESIAN_POINT('',(-2.279808055138E-015,0.454727066523)); -#169632 = CARTESIAN_POINT('',(2.597443969817E-016,0.5)); -#169633 = CARTESIAN_POINT('',(-1.193273114044E-015,0.545272933477)); -#169634 = CARTESIAN_POINT('',(-1.908648086906E-016,0.590563118949)); -#169635 = CARTESIAN_POINT('',(-1.540294209186E-015,0.635886573745)); -#169636 = CARTESIAN_POINT('',(6.365980812824E-016,0.681256779934)); -#169637 = CARTESIAN_POINT('',(-2.180852382687E-015,0.72668325398)); -#169638 = CARTESIAN_POINT('',(-1.89962773497E-015,0.7721699591)); -#169639 = CARTESIAN_POINT('',(8.694713425129E-016,0.8177134856)); -#169640 = CARTESIAN_POINT('',(-2.906886688395E-015,0.863301251813)); -#169641 = CARTESIAN_POINT('',(8.951444972773E-016,0.908908989256)); -#169642 = CARTESIAN_POINT('',(-3.119015640034E-015,0.954500792509)); -#169643 = CARTESIAN_POINT('',(-2.659343466324E-015,0.984847218355)); -#169644 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#169645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169646 = ORIENTED_EDGE('',*,*,#169647,.F.); -#169647 = EDGE_CURVE('',#169648,#169563,#169650,.T.); -#169648 = VERTEX_POINT('',#169649); -#169649 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, +#172012 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#172013 = CARTESIAN_POINT('',(-7.712029133934E-016,1.515278164504E-002) + ); +#172014 = CARTESIAN_POINT('',(1.25625350775E-016,4.549920749135E-002)); +#172015 = CARTESIAN_POINT('',(1.821600457514E-015,9.109101074357E-002)); +#172016 = CARTESIAN_POINT('',(1.184686899972E-016,0.136698748187)); +#172017 = CARTESIAN_POINT('',(-1.341817644549E-015,0.1822865144)); +#172018 = CARTESIAN_POINT('',(-3.87939999787E-016,0.2278300409)); +#172019 = CARTESIAN_POINT('',(-1.122364033566E-015,0.27331674602)); +#172020 = CARTESIAN_POINT('',(2.456563704797E-015,0.318743220066)); +#172021 = CARTESIAN_POINT('',(-1.720316333122E-015,0.364113426255)); +#172022 = CARTESIAN_POINT('',(1.581331095141E-015,0.409436881051)); +#172023 = CARTESIAN_POINT('',(-2.279808055138E-015,0.454727066523)); +#172024 = CARTESIAN_POINT('',(2.597443969817E-016,0.5)); +#172025 = CARTESIAN_POINT('',(-1.193273114044E-015,0.545272933477)); +#172026 = CARTESIAN_POINT('',(-1.908648086906E-016,0.590563118949)); +#172027 = CARTESIAN_POINT('',(-1.540294209186E-015,0.635886573745)); +#172028 = CARTESIAN_POINT('',(6.365980812824E-016,0.681256779934)); +#172029 = CARTESIAN_POINT('',(-2.180852382687E-015,0.72668325398)); +#172030 = CARTESIAN_POINT('',(-1.89962773497E-015,0.7721699591)); +#172031 = CARTESIAN_POINT('',(8.694713425129E-016,0.8177134856)); +#172032 = CARTESIAN_POINT('',(-2.906886688395E-015,0.863301251813)); +#172033 = CARTESIAN_POINT('',(8.951444972773E-016,0.908908989256)); +#172034 = CARTESIAN_POINT('',(-3.119015640034E-015,0.954500792509)); +#172035 = CARTESIAN_POINT('',(-2.659343466324E-015,0.984847218355)); +#172036 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#172037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172038 = ORIENTED_EDGE('',*,*,#172039,.F.); +#172039 = EDGE_CURVE('',#172040,#171955,#172042,.T.); +#172040 = VERTEX_POINT('',#172041); +#172041 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, 0.137059047745)); -#169650 = SURFACE_CURVE('',#169651,(#169656,#169685),.PCURVE_S1.); -#169651 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169652,#169653,#169654, -#169655),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172042 = SURFACE_CURVE('',#172043,(#172048,#172077),.PCURVE_S1.); +#172043 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172044,#172045,#172046, +#172047),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169652 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, +#172044 = CARTESIAN_POINT('',(-1.201066471757,0.6759553457, 0.137059047745)); -#169653 = CARTESIAN_POINT('',(-1.240010423697,0.675122936235, +#172045 = CARTESIAN_POINT('',(-1.240010423697,0.675122936235, 0.133952453327)); -#169654 = CARTESIAN_POINT('',(-1.275581001793,0.660038843607,0.132282534 +#172046 = CARTESIAN_POINT('',(-1.275581001793,0.660038843607,0.132282534 )); -#169655 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); -#169656 = PCURVE('',#169508,#169657); -#169657 = DEFINITIONAL_REPRESENTATION('',(#169658),#169684); -#169658 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169659,#169660,#169661, - #169662,#169663,#169664,#169665,#169666,#169667,#169668,#169669, - #169670,#169671,#169672,#169673,#169674,#169675,#169676,#169677, - #169678,#169679,#169680,#169681,#169682,#169683),.UNSPECIFIED.,.F., +#172047 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); +#172048 = PCURVE('',#171900,#172049); +#172049 = DEFINITIONAL_REPRESENTATION('',(#172050),#172076); +#172050 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172051,#172052,#172053, + #172054,#172055,#172056,#172057,#172058,#172059,#172060,#172061, + #172062,#172063,#172064,#172065,#172066,#172067,#172068,#172069, + #172070,#172071,#172072,#172073,#172074,#172075),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -209588,47 +212590,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169659 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169660 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); -#169661 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); -#169662 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); -#169663 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); -#169664 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); -#169665 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); -#169666 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); -#169667 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#169668 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#169669 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#169670 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#169671 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#169672 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#169673 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#169674 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#169675 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#169676 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#169677 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#169678 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#169679 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#169680 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#169681 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#169682 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#169683 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169685 = PCURVE('',#169686,#169691); -#169686 = CYLINDRICAL_SURFACE('',#169687,0.15); -#169687 = AXIS2_PLACEMENT_3D('',#169688,#169689,#169690); -#169688 = CARTESIAN_POINT('',(-1.334207498814,0.664207498814, +#172051 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172052 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); +#172053 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); +#172054 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); +#172055 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); +#172056 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); +#172057 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); +#172058 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); +#172059 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#172060 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#172061 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#172062 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#172063 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#172064 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#172065 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#172066 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#172067 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#172068 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#172069 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#172070 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#172071 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#172072 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#172073 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#172074 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#172075 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172077 = PCURVE('',#172078,#172083); +#172078 = CYLINDRICAL_SURFACE('',#172079,0.15); +#172079 = AXIS2_PLACEMENT_3D('',#172080,#172081,#172082); +#172080 = CARTESIAN_POINT('',(-1.334207498814,0.664207498814, 0.672770982062)); -#169689 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#169690 = DIRECTION('',(0.965925826289,-3.026618127129E-017, +#172081 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#172082 = DIRECTION('',(0.965925826289,-3.026618127129E-017, 0.258819045103)); -#169691 = DEFINITIONAL_REPRESENTATION('',(#169692),#169718); -#169692 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169693,#169694,#169695, - #169696,#169697,#169698,#169699,#169700,#169701,#169702,#169703, - #169704,#169705,#169706,#169707,#169708,#169709,#169710,#169711, - #169712,#169713,#169714,#169715,#169716,#169717),.UNSPECIFIED.,.F., +#172083 = DEFINITIONAL_REPRESENTATION('',(#172084),#172110); +#172084 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172085,#172086,#172087, + #172088,#172089,#172090,#172091,#172092,#172093,#172094,#172095, + #172096,#172097,#172098,#172099,#172100,#172101,#172102,#172103, + #172104,#172105,#172106,#172107,#172108,#172109),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -209636,48 +212638,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169693 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#169694 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); -#169695 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); -#169696 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); -#169697 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); -#169698 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); -#169699 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); -#169700 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); -#169701 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); -#169702 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); -#169703 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); -#169704 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); -#169705 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); -#169706 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); -#169707 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); -#169708 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); -#169709 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); -#169710 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); -#169711 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); -#169712 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); -#169713 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); -#169714 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); -#169715 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); -#169716 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); -#169717 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#169718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169719 = ORIENTED_EDGE('',*,*,#169720,.F.); -#169720 = EDGE_CURVE('',#169499,#169648,#169721,.T.); -#169721 = SURFACE_CURVE('',#169722,(#169727,#169756),.PCURVE_S1.); -#169722 = CIRCLE('',#169723,5.E-002); -#169723 = AXIS2_PLACEMENT_3D('',#169724,#169725,#169726); -#169724 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,0.15)); -#169725 = DIRECTION('',(1.,0.E+000,0.E+000)); -#169726 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#169727 = PCURVE('',#169508,#169728); -#169728 = DEFINITIONAL_REPRESENTATION('',(#169729),#169755); -#169729 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169730,#169731,#169732, - #169733,#169734,#169735,#169736,#169737,#169738,#169739,#169740, - #169741,#169742,#169743,#169744,#169745,#169746,#169747,#169748, - #169749,#169750,#169751,#169752,#169753,#169754),.UNSPECIFIED.,.F., +#172085 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#172086 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); +#172087 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); +#172088 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); +#172089 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); +#172090 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); +#172091 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); +#172092 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); +#172093 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); +#172094 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); +#172095 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); +#172096 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); +#172097 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); +#172098 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); +#172099 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); +#172100 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); +#172101 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); +#172102 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); +#172103 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); +#172104 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); +#172105 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); +#172106 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); +#172107 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); +#172108 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); +#172109 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#172110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172111 = ORIENTED_EDGE('',*,*,#172112,.F.); +#172112 = EDGE_CURVE('',#171891,#172040,#172113,.T.); +#172113 = SURFACE_CURVE('',#172114,(#172119,#172148),.PCURVE_S1.); +#172114 = CIRCLE('',#172115,5.E-002); +#172115 = AXIS2_PLACEMENT_3D('',#172116,#172117,#172118); +#172116 = CARTESIAN_POINT('',(-1.201066471757,0.627659054385,0.15)); +#172117 = DIRECTION('',(1.,0.E+000,0.E+000)); +#172118 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#172119 = PCURVE('',#171900,#172120); +#172120 = DEFINITIONAL_REPRESENTATION('',(#172121),#172147); +#172121 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172122,#172123,#172124, + #172125,#172126,#172127,#172128,#172129,#172130,#172131,#172132, + #172133,#172134,#172135,#172136,#172137,#172138,#172139,#172140, + #172141,#172142,#172143,#172144,#172145,#172146),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -209685,111 +212687,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#169730 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169731 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#169732 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#169733 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); -#169734 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#169735 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#169736 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#169737 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#169738 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#169739 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#169740 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); -#169741 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#169742 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#169743 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#169744 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#169745 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#169746 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#169747 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#169748 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#169749 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#169750 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#169751 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#169752 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#169753 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#169754 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169756 = PCURVE('',#169757,#169762); -#169757 = CYLINDRICAL_SURFACE('',#169758,5.E-002); -#169758 = AXIS2_PLACEMENT_3D('',#169759,#169760,#169761); -#169759 = CARTESIAN_POINT('',(-1.47,0.627659054385,0.15)); -#169760 = DIRECTION('',(1.,0.E+000,0.E+000)); -#169761 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#169762 = DEFINITIONAL_REPRESENTATION('',(#169763),#169766); -#169763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#169764,#169765), +#172122 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172123 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#172124 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#172125 = CARTESIAN_POINT('',(5.531305917798,9.115660726251E-002)); +#172126 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#172127 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#172128 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#172129 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#172130 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#172131 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#172132 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); +#172133 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#172134 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#172135 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#172136 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#172137 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#172138 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#172139 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#172140 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#172141 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#172142 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#172143 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#172144 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#172145 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#172146 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172148 = PCURVE('',#172149,#172154); +#172149 = CYLINDRICAL_SURFACE('',#172150,5.E-002); +#172150 = AXIS2_PLACEMENT_3D('',#172151,#172152,#172153); +#172151 = CARTESIAN_POINT('',(-1.47,0.627659054385,0.15)); +#172152 = DIRECTION('',(1.,0.E+000,0.E+000)); +#172153 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#172154 = DEFINITIONAL_REPRESENTATION('',(#172155),#172158); +#172155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172156,#172157), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#169764 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#169765 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#169766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#172156 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#172157 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#172158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#169767 = ADVANCED_FACE('',(#169768),#169783,.T.); -#169768 = FACE_BOUND('',#169769,.T.); -#169769 = EDGE_LOOP('',(#169770,#169862,#169947,#169999)); -#169770 = ORIENTED_EDGE('',*,*,#169771,.F.); -#169771 = EDGE_CURVE('',#169772,#169774,#169776,.T.); -#169772 = VERTEX_POINT('',#169773); -#169773 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, +#172159 = ADVANCED_FACE('',(#172160),#172175,.T.); +#172160 = FACE_BOUND('',#172161,.T.); +#172161 = EDGE_LOOP('',(#172162,#172254,#172339,#172391)); +#172162 = ORIENTED_EDGE('',*,*,#172163,.F.); +#172163 = EDGE_CURVE('',#172164,#172166,#172168,.T.); +#172164 = VERTEX_POINT('',#172165); +#172165 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, 1.167717466)); -#169774 = VERTEX_POINT('',#169775); -#169775 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, +#172166 = VERTEX_POINT('',#172167); +#172167 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, 1.162940952255)); -#169776 = SURFACE_CURVE('',#169777,(#169782,#169828),.PCURVE_S1.); -#169777 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169778,#169779,#169780, -#169781),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#172168 = SURFACE_CURVE('',#172169,(#172174,#172220),.PCURVE_S1.); +#172169 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172170,#172171,#172172, +#172173),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169778 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, +#172170 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, 1.167717466)); -#169779 = CARTESIAN_POINT('',(-1.303243924364,-0.57878608255,1.167717466 +#172171 = CARTESIAN_POINT('',(-1.303243924364,-0.57878608255,1.167717466 )); -#169780 = CARTESIAN_POINT('',(-1.318328016991,-0.543215504454, +#172172 = CARTESIAN_POINT('',(-1.318328016991,-0.543215504454, 1.166047546673)); -#169781 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, +#172173 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, 1.162940952255)); -#169782 = PCURVE('',#169783,#169800); -#169783 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169784,#169785,#169786,#169787) - ,(#169788,#169789,#169790,#169791) - ,(#169792,#169793,#169794,#169795) - ,(#169796,#169797,#169798,#169799 +#172174 = PCURVE('',#172175,#172192); +#172175 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172176,#172177,#172178,#172179) + ,(#172180,#172181,#172182,#172183) + ,(#172184,#172185,#172186,#172187) + ,(#172188,#172189,#172190,#172191 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169784 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, +#172176 = CARTESIAN_POINT('',(-1.319160426457,-0.504271552513, 1.162940952255)); -#169785 = CARTESIAN_POINT('',(-1.313513870827,-0.504271552513, +#172177 = CARTESIAN_POINT('',(-1.313513870827,-0.504271552513, 1.184014184754)); -#169786 = CARTESIAN_POINT('',(-1.292680750792,-0.504271552513,1.2)); -#169787 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); -#169788 = CARTESIAN_POINT('',(-1.318347764779,-0.542291611921, +#172178 = CARTESIAN_POINT('',(-1.292680750792,-0.504271552513,1.2)); +#172179 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); +#172180 = CARTESIAN_POINT('',(-1.318347764779,-0.542291611921, 1.165973846926)); -#169789 = CARTESIAN_POINT('',(-1.311648746428,-0.540873249723, +#172181 = CARTESIAN_POINT('',(-1.311648746428,-0.540873249723, 1.185681523985)); -#169790 = CARTESIAN_POINT('',(-1.291634122922,-0.535640163951,1.2)); -#169791 = CARTESIAN_POINT('',(-1.270864135142,-0.530160033237,1.2)); -#169792 = CARTESIAN_POINT('',(-1.302597955081,-0.579432051833, +#172182 = CARTESIAN_POINT('',(-1.291634122922,-0.535640163951,1.2)); +#172183 = CARTESIAN_POINT('',(-1.270864135142,-0.530160033237,1.2)); +#172184 = CARTESIAN_POINT('',(-1.302597955081,-0.579432051833, 1.167717466)); -#169793 = CARTESIAN_POINT('',(-1.296198171686,-0.575737677168, +#172185 = CARTESIAN_POINT('',(-1.296198171686,-0.575737677168, 1.186553421368)); -#169794 = CARTESIAN_POINT('',(-1.27873639183,-0.565657592716,1.2)); -#169795 = CARTESIAN_POINT('',(-1.260675729559,-0.55523179406,1.2)); -#169796 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, +#172186 = CARTESIAN_POINT('',(-1.27873639183,-0.565657592716,1.2)); +#172187 = CARTESIAN_POINT('',(-1.260675729559,-0.55523179406,1.2)); +#172188 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, 1.167717466)); -#169797 = CARTESIAN_POINT('',(-1.270967924427,-0.600967924427, +#172189 = CARTESIAN_POINT('',(-1.270967924427,-0.600967924427, 1.186553421368)); -#169798 = CARTESIAN_POINT('',(-1.257196992273,-0.587196992273,1.2)); -#169799 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); -#169800 = DEFINITIONAL_REPRESENTATION('',(#169801),#169827); -#169801 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169802,#169803,#169804, - #169805,#169806,#169807,#169808,#169809,#169810,#169811,#169812, - #169813,#169814,#169815,#169816,#169817,#169818,#169819,#169820, - #169821,#169822,#169823,#169824,#169825,#169826),.UNSPECIFIED.,.F., +#172190 = CARTESIAN_POINT('',(-1.257196992273,-0.587196992273,1.2)); +#172191 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); +#172192 = DEFINITIONAL_REPRESENTATION('',(#172193),#172219); +#172193 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172194,#172195,#172196, + #172197,#172198,#172199,#172200,#172201,#172202,#172203,#172204, + #172205,#172206,#172207,#172208,#172209,#172210,#172211,#172212, + #172213,#172214,#172215,#172216,#172217,#172218),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -209797,48 +212799,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#169802 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169803 = CARTESIAN_POINT('',(6.272059551128,2.972804135532E-006)); -#169804 = CARTESIAN_POINT('',(6.249732638972,-1.037052467203E-005)); -#169805 = CARTESIAN_POINT('',(6.216039360813,-5.446484095649E-005)); -#169806 = CARTESIAN_POINT('',(6.182166930891,-8.868396576155E-005)); -#169807 = CARTESIAN_POINT('',(6.148137469616,-7.965797689894E-005)); -#169808 = CARTESIAN_POINT('',(6.113972837442,-8.226451401249E-005)); -#169809 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); -#169810 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#169811 = CARTESIAN_POINT('',(6.010871913477,-8.242390084137E-005)); -#169812 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#169813 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#169814 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); -#169815 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); -#169816 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#169817 = CARTESIAN_POINT('',(5.803652201529,-8.485308429908E-005)); -#169818 = CARTESIAN_POINT('',(5.769199593774,-8.542361824742E-005)); -#169819 = CARTESIAN_POINT('',(5.734821280548,-8.593542635477E-005)); -#169820 = CARTESIAN_POINT('',(5.700537102675,-8.687405903479E-005)); -#169821 = CARTESIAN_POINT('',(5.666367464043,-8.643182884048E-005)); -#169822 = CARTESIAN_POINT('',(5.632333796953,-9.135957814091E-005)); -#169823 = CARTESIAN_POINT('',(5.59845580442,-3.211524037404E-005)); -#169824 = CARTESIAN_POINT('',(5.564759360754,-7.920748667922E-006)); -#169825 = CARTESIAN_POINT('',(5.542431620275,5.702886884999E-008)); -#169826 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#169827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169828 = PCURVE('',#169829,#169834); -#169829 = CYLINDRICAL_SURFACE('',#169830,0.15); -#169830 = AXIS2_PLACEMENT_3D('',#169831,#169832,#169833); -#169831 = CARTESIAN_POINT('',(-1.334207498814,-0.664207498814, +#172194 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172195 = CARTESIAN_POINT('',(6.272059551128,2.972804135532E-006)); +#172196 = CARTESIAN_POINT('',(6.249732638972,-1.037052467203E-005)); +#172197 = CARTESIAN_POINT('',(6.216039360813,-5.446484095649E-005)); +#172198 = CARTESIAN_POINT('',(6.182166930891,-8.868396576155E-005)); +#172199 = CARTESIAN_POINT('',(6.148137469616,-7.965797689894E-005)); +#172200 = CARTESIAN_POINT('',(6.113972837442,-8.226451401249E-005)); +#172201 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); +#172202 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#172203 = CARTESIAN_POINT('',(6.010871913477,-8.242390084137E-005)); +#172204 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#172205 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#172206 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); +#172207 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); +#172208 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#172209 = CARTESIAN_POINT('',(5.803652201529,-8.485308429908E-005)); +#172210 = CARTESIAN_POINT('',(5.769199593774,-8.542361824742E-005)); +#172211 = CARTESIAN_POINT('',(5.734821280548,-8.593542635477E-005)); +#172212 = CARTESIAN_POINT('',(5.700537102675,-8.687405903479E-005)); +#172213 = CARTESIAN_POINT('',(5.666367464043,-8.643182884048E-005)); +#172214 = CARTESIAN_POINT('',(5.632333796953,-9.135957814091E-005)); +#172215 = CARTESIAN_POINT('',(5.59845580442,-3.211524037404E-005)); +#172216 = CARTESIAN_POINT('',(5.564759360754,-7.920748667922E-006)); +#172217 = CARTESIAN_POINT('',(5.542431620275,5.702886884999E-008)); +#172218 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172220 = PCURVE('',#172221,#172226); +#172221 = CYLINDRICAL_SURFACE('',#172222,0.15); +#172222 = AXIS2_PLACEMENT_3D('',#172223,#172224,#172225); +#172223 = CARTESIAN_POINT('',(-1.334207498814,-0.664207498814, 0.527229017938)); -#169832 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) +#172224 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) ); -#169833 = DIRECTION('',(-0.965925826289,4.046106982444E-017, +#172225 = DIRECTION('',(-0.965925826289,4.046106982444E-017, 0.258819045103)); -#169834 = DEFINITIONAL_REPRESENTATION('',(#169835),#169861); -#169835 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169836,#169837,#169838, - #169839,#169840,#169841,#169842,#169843,#169844,#169845,#169846, - #169847,#169848,#169849,#169850,#169851,#169852,#169853,#169854, - #169855,#169856,#169857,#169858,#169859,#169860),.UNSPECIFIED.,.F., +#172226 = DEFINITIONAL_REPRESENTATION('',(#172227),#172253); +#172227 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172228,#172229,#172230, + #172231,#172232,#172233,#172234,#172235,#172236,#172237,#172238, + #172239,#172240,#172241,#172242,#172243,#172244,#172245,#172246, + #172247,#172248,#172249,#172250,#172251,#172252),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -209846,50 +212848,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#169836 = CARTESIAN_POINT('',(5.531305892885,-0.628090905151)); -#169837 = CARTESIAN_POINT('',(5.542431500119,-0.628090893864)); -#169838 = CARTESIAN_POINT('',(5.56475355,-0.628104985434)); -#169839 = CARTESIAN_POINT('',(5.598431528687,-0.628169056716)); -#169840 = CARTESIAN_POINT('',(5.632287045183,-0.628276708263)); -#169841 = CARTESIAN_POINT('',(5.666301906361,-0.628428394479)); -#169842 = CARTESIAN_POINT('',(5.700457442157,-0.628624435674)); -#169843 = CARTESIAN_POINT('',(5.734734482675,-0.628864995698)); -#169844 = CARTESIAN_POINT('',(5.76911344049,-0.629150082601)); -#169845 = CARTESIAN_POINT('',(5.803574369467,-0.629479544784)); -#169846 = CARTESIAN_POINT('',(5.838097033931,-0.629853070079)); -#169847 = CARTESIAN_POINT('',(5.872660978441,-0.630270185855)); -#169848 = CARTESIAN_POINT('',(5.907245600032,-0.630730260665)); -#169849 = CARTESIAN_POINT('',(5.941830221623,-0.631232507307)); -#169850 = CARTESIAN_POINT('',(5.976394166134,-0.631775987301)); -#169851 = CARTESIAN_POINT('',(6.010916830598,-0.632359616715)); -#169852 = CARTESIAN_POINT('',(6.045377759574,-0.632982173279)); -#169853 = CARTESIAN_POINT('',(6.079756717389,-0.633642304667)); -#169854 = CARTESIAN_POINT('',(6.114033757907,-0.634338537887)); -#169855 = CARTESIAN_POINT('',(6.148189293703,-0.635069289453)); -#169856 = CARTESIAN_POINT('',(6.182204154882,-0.635832876948)); -#169857 = CARTESIAN_POINT('',(6.216059671377,-0.636627528948)); -#169858 = CARTESIAN_POINT('',(6.249737650065,-0.637451403942)); -#169859 = CARTESIAN_POINT('',(6.272059699945,-0.638018853161)); -#169860 = CARTESIAN_POINT('',(6.28318530718,-0.63830681082)); -#169861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169862 = ORIENTED_EDGE('',*,*,#169863,.T.); -#169863 = EDGE_CURVE('',#169772,#169864,#169866,.T.); -#169864 = VERTEX_POINT('',#169865); -#169865 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); -#169866 = SURFACE_CURVE('',#169867,(#169872,#169901),.PCURVE_S1.); -#169867 = CIRCLE('',#169868,5.E-002); -#169868 = AXIS2_PLACEMENT_3D('',#169869,#169870,#169871); -#169869 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.15)); -#169870 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#169871 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#169872 = PCURVE('',#169783,#169873); -#169873 = DEFINITIONAL_REPRESENTATION('',(#169874),#169900); -#169874 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169875,#169876,#169877, - #169878,#169879,#169880,#169881,#169882,#169883,#169884,#169885, - #169886,#169887,#169888,#169889,#169890,#169891,#169892,#169893, - #169894,#169895,#169896,#169897,#169898,#169899),.UNSPECIFIED.,.F., +#172228 = CARTESIAN_POINT('',(5.531305892885,-0.628090905151)); +#172229 = CARTESIAN_POINT('',(5.542431500119,-0.628090893864)); +#172230 = CARTESIAN_POINT('',(5.56475355,-0.628104985434)); +#172231 = CARTESIAN_POINT('',(5.598431528687,-0.628169056716)); +#172232 = CARTESIAN_POINT('',(5.632287045183,-0.628276708263)); +#172233 = CARTESIAN_POINT('',(5.666301906361,-0.628428394479)); +#172234 = CARTESIAN_POINT('',(5.700457442157,-0.628624435674)); +#172235 = CARTESIAN_POINT('',(5.734734482675,-0.628864995698)); +#172236 = CARTESIAN_POINT('',(5.76911344049,-0.629150082601)); +#172237 = CARTESIAN_POINT('',(5.803574369467,-0.629479544784)); +#172238 = CARTESIAN_POINT('',(5.838097033931,-0.629853070079)); +#172239 = CARTESIAN_POINT('',(5.872660978441,-0.630270185855)); +#172240 = CARTESIAN_POINT('',(5.907245600032,-0.630730260665)); +#172241 = CARTESIAN_POINT('',(5.941830221623,-0.631232507307)); +#172242 = CARTESIAN_POINT('',(5.976394166134,-0.631775987301)); +#172243 = CARTESIAN_POINT('',(6.010916830598,-0.632359616715)); +#172244 = CARTESIAN_POINT('',(6.045377759574,-0.632982173279)); +#172245 = CARTESIAN_POINT('',(6.079756717389,-0.633642304667)); +#172246 = CARTESIAN_POINT('',(6.114033757907,-0.634338537887)); +#172247 = CARTESIAN_POINT('',(6.148189293703,-0.635069289453)); +#172248 = CARTESIAN_POINT('',(6.182204154882,-0.635832876948)); +#172249 = CARTESIAN_POINT('',(6.216059671377,-0.636627528948)); +#172250 = CARTESIAN_POINT('',(6.249737650065,-0.637451403942)); +#172251 = CARTESIAN_POINT('',(6.272059699945,-0.638018853161)); +#172252 = CARTESIAN_POINT('',(6.28318530718,-0.63830681082)); +#172253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172254 = ORIENTED_EDGE('',*,*,#172255,.T.); +#172255 = EDGE_CURVE('',#172164,#172256,#172258,.T.); +#172256 = VERTEX_POINT('',#172257); +#172257 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); +#172258 = SURFACE_CURVE('',#172259,(#172264,#172293),.PCURVE_S1.); +#172259 = CIRCLE('',#172260,5.E-002); +#172260 = AXIS2_PLACEMENT_3D('',#172261,#172262,#172263); +#172261 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.15)); +#172262 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#172263 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#172264 = PCURVE('',#172175,#172265); +#172265 = DEFINITIONAL_REPRESENTATION('',(#172266),#172292); +#172266 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172267,#172268,#172269, + #172270,#172271,#172272,#172273,#172274,#172275,#172276,#172277, + #172278,#172279,#172280,#172281,#172282,#172283,#172284,#172285, + #172286,#172287,#172288,#172289,#172290,#172291),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -209897,71 +212899,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#169875 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#169876 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#169877 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#169878 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#169879 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#169880 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#169881 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#169882 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#169883 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#169884 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#169885 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#169886 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#169887 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#169888 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#169889 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#169890 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#169891 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#169892 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#169893 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#169894 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#169895 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#169896 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#169897 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#169898 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#169899 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169901 = PCURVE('',#169902,#169919); -#169902 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#169903,#169904,#169905,#169906) - ,(#169907,#169908,#169909,#169910) - ,(#169911,#169912,#169913,#169914) - ,(#169915,#169916,#169917,#169918 +#172267 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172268 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#172269 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#172270 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#172271 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#172272 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#172273 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#172274 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#172275 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#172276 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#172277 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#172278 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#172279 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#172280 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#172281 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#172282 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#172283 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#172284 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#172285 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#172286 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#172287 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#172288 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#172289 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#172290 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#172291 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172293 = PCURVE('',#172294,#172311); +#172294 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172295,#172296,#172297,#172298) + ,(#172299,#172300,#172301,#172302) + ,(#172303,#172304,#172305,#172306) + ,(#172307,#172308,#172309,#172310 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(7.453889935838E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#169903 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, +#172295 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, 1.167717466)); -#169904 = CARTESIAN_POINT('',(-1.270967924427,-0.600967924427, +#172296 = CARTESIAN_POINT('',(-1.270967924427,-0.600967924427, 1.186553421368)); -#169905 = CARTESIAN_POINT('',(-1.257196992273,-0.587196992273,1.2)); -#169906 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); -#169907 = CARTESIAN_POINT('',(-1.249432051833,-0.632597955081, +#172297 = CARTESIAN_POINT('',(-1.257196992273,-0.587196992273,1.2)); +#172298 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); +#172299 = CARTESIAN_POINT('',(-1.249432051833,-0.632597955081, 1.167717466)); -#169908 = CARTESIAN_POINT('',(-1.245737677168,-0.626198171686, +#172300 = CARTESIAN_POINT('',(-1.245737677168,-0.626198171686, 1.186553421368)); -#169909 = CARTESIAN_POINT('',(-1.235657592716,-0.60873639183,1.2)); -#169910 = CARTESIAN_POINT('',(-1.22523179406,-0.590675729559,1.2)); -#169911 = CARTESIAN_POINT('',(-1.212291611921,-0.648347764779, +#172301 = CARTESIAN_POINT('',(-1.235657592716,-0.60873639183,1.2)); +#172302 = CARTESIAN_POINT('',(-1.22523179406,-0.590675729559,1.2)); +#172303 = CARTESIAN_POINT('',(-1.212291611921,-0.648347764779, 1.165973846926)); -#169912 = CARTESIAN_POINT('',(-1.210873249723,-0.641648746428, +#172304 = CARTESIAN_POINT('',(-1.210873249723,-0.641648746428, 1.185681523985)); -#169913 = CARTESIAN_POINT('',(-1.205640163951,-0.621634122922,1.2)); -#169914 = CARTESIAN_POINT('',(-1.200160033237,-0.600864135142,1.2)); -#169915 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, +#172305 = CARTESIAN_POINT('',(-1.205640163951,-0.621634122922,1.2)); +#172306 = CARTESIAN_POINT('',(-1.200160033237,-0.600864135142,1.2)); +#172307 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, 1.162940952255)); -#169916 = CARTESIAN_POINT('',(-1.174271552513,-0.643513870827, +#172308 = CARTESIAN_POINT('',(-1.174271552513,-0.643513870827, 1.184014184754)); -#169917 = CARTESIAN_POINT('',(-1.174271552513,-0.622680750792,1.2)); -#169918 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); -#169919 = DEFINITIONAL_REPRESENTATION('',(#169920),#169946); -#169920 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169921,#169922,#169923, - #169924,#169925,#169926,#169927,#169928,#169929,#169930,#169931, - #169932,#169933,#169934,#169935,#169936,#169937,#169938,#169939, - #169940,#169941,#169942,#169943,#169944,#169945),.UNSPECIFIED.,.F., +#172309 = CARTESIAN_POINT('',(-1.174271552513,-0.622680750792,1.2)); +#172310 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); +#172311 = DEFINITIONAL_REPRESENTATION('',(#172312),#172338); +#172312 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172313,#172314,#172315, + #172316,#172317,#172318,#172319,#172320,#172321,#172322,#172323, + #172324,#172325,#172326,#172327,#172328,#172329,#172330,#172331, + #172332,#172333,#172334,#172335,#172336,#172337),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -209969,54 +212971,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#169921 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#169922 = CARTESIAN_POINT('',(2.668293038802E-016,1.515278164503E-002)); -#169923 = CARTESIAN_POINT('',(3.4033097696E-016,4.549920749134E-002)); -#169924 = CARTESIAN_POINT('',(1.733619753216E-015,9.109101074357E-002)); -#169925 = CARTESIAN_POINT('',(1.287145270728E-015,0.136698748187)); -#169926 = CARTESIAN_POINT('',(4.770122250585E-016,0.1822865144)); -#169927 = CARTESIAN_POINT('',(-2.744538869866E-016,0.2278300409)); -#169928 = CARTESIAN_POINT('',(2.429582618788E-015,0.27331674602)); -#169929 = CARTESIAN_POINT('',(-2.047309683755E-015,0.318743220066)); -#169930 = CARTESIAN_POINT('',(1.86407131158E-015,0.364113426255)); -#169931 = CARTESIAN_POINT('',(7.005697303568E-017,0.409436881051)); -#169932 = CARTESIAN_POINT('',(2.271720134471E-015,0.454727066523)); -#169933 = CARTESIAN_POINT('',(-2.205768725449E-015,0.5)); -#169934 = CARTESIAN_POINT('',(1.613571902988E-015,0.545272933477)); -#169935 = CARTESIAN_POINT('',(1.057305520159E-015,0.590563118949)); -#169936 = CARTESIAN_POINT('',(-1.539016564857E-015,0.635886573745)); -#169937 = CARTESIAN_POINT('',(7.600246030302E-016,0.681256779934)); -#169938 = CARTESIAN_POINT('',(1.244702625706E-015,0.72668325398)); -#169939 = CARTESIAN_POINT('',(9.73723001771E-017,0.7721699591)); -#169940 = CARTESIAN_POINT('',(3.186733907882E-015,0.8177134856)); -#169941 = CARTESIAN_POINT('',(-5.948021068823E-016,0.863301251813)); -#169942 = CARTESIAN_POINT('',(1.55186920834E-015,0.908908989256)); -#169943 = CARTESIAN_POINT('',(4.65601519583E-015,0.954500792509)); -#169944 = CARTESIAN_POINT('',(3.269994085118E-015,0.984847218355)); -#169945 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#169946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169947 = ORIENTED_EDGE('',*,*,#169948,.F.); -#169948 = EDGE_CURVE('',#169949,#169864,#169951,.T.); -#169949 = VERTEX_POINT('',#169950); -#169950 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); -#169951 = SURFACE_CURVE('',#169952,(#169957,#169986),.PCURVE_S1.); -#169952 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169953,#169954,#169955, -#169956),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172313 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#172314 = CARTESIAN_POINT('',(2.668293038802E-016,1.515278164503E-002)); +#172315 = CARTESIAN_POINT('',(3.4033097696E-016,4.549920749134E-002)); +#172316 = CARTESIAN_POINT('',(1.733619753216E-015,9.109101074357E-002)); +#172317 = CARTESIAN_POINT('',(1.287145270728E-015,0.136698748187)); +#172318 = CARTESIAN_POINT('',(4.770122250585E-016,0.1822865144)); +#172319 = CARTESIAN_POINT('',(-2.744538869866E-016,0.2278300409)); +#172320 = CARTESIAN_POINT('',(2.429582618788E-015,0.27331674602)); +#172321 = CARTESIAN_POINT('',(-2.047309683755E-015,0.318743220066)); +#172322 = CARTESIAN_POINT('',(1.86407131158E-015,0.364113426255)); +#172323 = CARTESIAN_POINT('',(7.005697303568E-017,0.409436881051)); +#172324 = CARTESIAN_POINT('',(2.271720134471E-015,0.454727066523)); +#172325 = CARTESIAN_POINT('',(-2.205768725449E-015,0.5)); +#172326 = CARTESIAN_POINT('',(1.613571902988E-015,0.545272933477)); +#172327 = CARTESIAN_POINT('',(1.057305520159E-015,0.590563118949)); +#172328 = CARTESIAN_POINT('',(-1.539016564857E-015,0.635886573745)); +#172329 = CARTESIAN_POINT('',(7.600246030302E-016,0.681256779934)); +#172330 = CARTESIAN_POINT('',(1.244702625706E-015,0.72668325398)); +#172331 = CARTESIAN_POINT('',(9.73723001771E-017,0.7721699591)); +#172332 = CARTESIAN_POINT('',(3.186733907882E-015,0.8177134856)); +#172333 = CARTESIAN_POINT('',(-5.948021068823E-016,0.863301251813)); +#172334 = CARTESIAN_POINT('',(1.55186920834E-015,0.908908989256)); +#172335 = CARTESIAN_POINT('',(4.65601519583E-015,0.954500792509)); +#172336 = CARTESIAN_POINT('',(3.269994085118E-015,0.984847218355)); +#172337 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#172338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172339 = ORIENTED_EDGE('',*,*,#172340,.F.); +#172340 = EDGE_CURVE('',#172341,#172256,#172343,.T.); +#172341 = VERTEX_POINT('',#172342); +#172342 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); +#172343 = SURFACE_CURVE('',#172344,(#172349,#172378),.PCURVE_S1.); +#172344 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172345,#172346,#172347, +#172348),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169953 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); -#169954 = CARTESIAN_POINT('',(-1.270864135142,-0.530789126784,1.2)); -#169955 = CARTESIAN_POINT('',(-1.261106375747,-0.554801147872,1.2)); -#169956 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); -#169957 = PCURVE('',#169783,#169958); -#169958 = DEFINITIONAL_REPRESENTATION('',(#169959),#169985); -#169959 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#169960,#169961,#169962, - #169963,#169964,#169965,#169966,#169967,#169968,#169969,#169970, - #169971,#169972,#169973,#169974,#169975,#169976,#169977,#169978, - #169979,#169980,#169981,#169982,#169983,#169984),.UNSPECIFIED.,.F., +#172345 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.2)); +#172346 = CARTESIAN_POINT('',(-1.270864135142,-0.530789126784,1.2)); +#172347 = CARTESIAN_POINT('',(-1.261106375747,-0.554801147872,1.2)); +#172348 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); +#172349 = PCURVE('',#172175,#172350); +#172350 = DEFINITIONAL_REPRESENTATION('',(#172351),#172377); +#172351 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172352,#172353,#172354, + #172355,#172356,#172357,#172358,#172359,#172360,#172361,#172362, + #172363,#172364,#172365,#172366,#172367,#172368,#172369,#172370, + #172371,#172372,#172373,#172374,#172375,#172376),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -210024,67 +213026,67 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#169960 = CARTESIAN_POINT('',(5.531305892885,1.)); -#169961 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#169962 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#169963 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#169964 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#169965 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#169966 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#169967 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#169968 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#169969 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#169970 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#169971 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#169972 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#169973 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#169974 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#169975 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#169976 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#169977 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#169978 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#169979 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#169980 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#169981 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#169982 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#169983 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#169984 = CARTESIAN_POINT('',(6.28318530718,1.)); -#169985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169986 = PCURVE('',#169987,#169992); -#169987 = PLANE('',#169988); -#169988 = AXIS2_PLACEMENT_3D('',#169989,#169990,#169991); -#169989 = CARTESIAN_POINT('',(1.47,-0.8,1.2)); -#169990 = DIRECTION('',(0.E+000,0.E+000,1.)); -#169991 = DIRECTION('',(1.,0.E+000,0.E+000)); -#169992 = DEFINITIONAL_REPRESENTATION('',(#169993),#169998); -#169993 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#169994,#169995,#169996, -#169997),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172352 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172353 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#172354 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#172355 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#172356 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#172357 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#172358 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#172359 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#172360 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#172361 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#172362 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#172363 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#172364 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#172365 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#172366 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#172367 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#172368 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#172369 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#172370 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#172371 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#172372 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#172373 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#172374 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#172375 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#172376 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172378 = PCURVE('',#172379,#172384); +#172379 = PLANE('',#172380); +#172380 = AXIS2_PLACEMENT_3D('',#172381,#172382,#172383); +#172381 = CARTESIAN_POINT('',(1.47,-0.8,1.2)); +#172382 = DIRECTION('',(0.E+000,0.E+000,1.)); +#172383 = DIRECTION('',(1.,0.E+000,0.E+000)); +#172384 = DEFINITIONAL_REPRESENTATION('',(#172385),#172390); +#172385 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172386,#172387,#172388, +#172389),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#169994 = CARTESIAN_POINT('',(-2.740864135142,0.295728447487)); -#169995 = CARTESIAN_POINT('',(-2.740864135142,0.269210873216)); -#169996 = CARTESIAN_POINT('',(-2.731106375747,0.245198852128)); -#169997 = CARTESIAN_POINT('',(-2.712953761809,0.227046238191)); -#169998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#169999 = ORIENTED_EDGE('',*,*,#170000,.T.); -#170000 = EDGE_CURVE('',#169949,#169774,#170001,.T.); -#170001 = SURFACE_CURVE('',#170002,(#170007,#170036),.PCURVE_S1.); -#170002 = CIRCLE('',#170003,5.E-002); -#170003 = AXIS2_PLACEMENT_3D('',#170004,#170005,#170006); -#170004 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.15)); -#170005 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#170006 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#170007 = PCURVE('',#169783,#170008); -#170008 = DEFINITIONAL_REPRESENTATION('',(#170009),#170035); -#170009 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170010,#170011,#170012, - #170013,#170014,#170015,#170016,#170017,#170018,#170019,#170020, - #170021,#170022,#170023,#170024,#170025,#170026,#170027,#170028, - #170029,#170030,#170031,#170032,#170033,#170034),.UNSPECIFIED.,.F., +#172386 = CARTESIAN_POINT('',(-2.740864135142,0.295728447487)); +#172387 = CARTESIAN_POINT('',(-2.740864135142,0.269210873216)); +#172388 = CARTESIAN_POINT('',(-2.731106375747,0.245198852128)); +#172389 = CARTESIAN_POINT('',(-2.712953761809,0.227046238191)); +#172390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172391 = ORIENTED_EDGE('',*,*,#172392,.T.); +#172392 = EDGE_CURVE('',#172341,#172166,#172393,.T.); +#172393 = SURFACE_CURVE('',#172394,(#172399,#172428),.PCURVE_S1.); +#172394 = CIRCLE('',#172395,5.E-002); +#172395 = AXIS2_PLACEMENT_3D('',#172396,#172397,#172398); +#172396 = CARTESIAN_POINT('',(-1.270864135142,-0.504271552513,1.15)); +#172397 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#172398 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#172399 = PCURVE('',#172175,#172400); +#172400 = DEFINITIONAL_REPRESENTATION('',(#172401),#172427); +#172401 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172402,#172403,#172404, + #172405,#172406,#172407,#172408,#172409,#172410,#172411,#172412, + #172413,#172414,#172415,#172416,#172417,#172418,#172419,#172420, + #172421,#172422,#172423,#172424,#172425,#172426),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.201092514453,3.260592375317,3.32009223618,3.379592097044, 3.439091957907,3.49859181877,3.558091679634,3.617591540497, @@ -210092,111 +213094,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 3.915090844815,3.974590705678,4.034090566541,4.093590427405, 4.153090288268,4.212590149132,4.272090009995,4.331589870859, 4.391089731722,4.450589592586),.QUASI_UNIFORM_KNOTS.); -#170010 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170011 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#170012 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#170013 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#170014 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#170015 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#170016 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#170017 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#170018 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#170019 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#170020 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#170021 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#170022 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#170023 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#170024 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#170025 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#170026 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#170027 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#170028 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#170029 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#170030 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#170031 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#170032 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#170033 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#170034 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170036 = PCURVE('',#170037,#170042); -#170037 = CYLINDRICAL_SURFACE('',#170038,5.E-002); -#170038 = AXIS2_PLACEMENT_3D('',#170039,#170040,#170041); -#170039 = CARTESIAN_POINT('',(-1.270864135142,-0.8,1.15)); -#170040 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#170041 = DIRECTION('',(1.,1.355252715607E-016,0.E+000)); -#170042 = DEFINITIONAL_REPRESENTATION('',(#170043),#170046); -#170043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170044,#170045), +#172402 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172403 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#172404 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#172405 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#172406 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#172407 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#172408 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#172409 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#172410 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#172411 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#172412 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#172413 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#172414 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#172415 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#172416 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#172417 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#172418 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#172419 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#172420 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#172421 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#172422 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#172423 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#172424 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#172425 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#172426 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172428 = PCURVE('',#172429,#172434); +#172429 = CYLINDRICAL_SURFACE('',#172430,5.E-002); +#172430 = AXIS2_PLACEMENT_3D('',#172431,#172432,#172433); +#172431 = CARTESIAN_POINT('',(-1.270864135142,-0.8,1.15)); +#172432 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#172433 = DIRECTION('',(1.,1.355252715607E-016,0.E+000)); +#172434 = DEFINITIONAL_REPRESENTATION('',(#172435),#172438); +#172435 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172436,#172437), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.450589592586), .PIECEWISE_BEZIER_KNOTS.); -#170044 = CARTESIAN_POINT('',(1.570796326795,-0.295728447487)); -#170045 = CARTESIAN_POINT('',(2.879793265791,-0.295728447487)); -#170046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#172436 = CARTESIAN_POINT('',(1.570796326795,-0.295728447487)); +#172437 = CARTESIAN_POINT('',(2.879793265791,-0.295728447487)); +#172438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#170047 = ADVANCED_FACE('',(#170048),#170063,.T.); -#170048 = FACE_BOUND('',#170049,.T.); -#170049 = EDGE_LOOP('',(#170050,#170142,#170227,#170274)); -#170050 = ORIENTED_EDGE('',*,*,#170051,.F.); -#170051 = EDGE_CURVE('',#170052,#170054,#170056,.T.); -#170052 = VERTEX_POINT('',#170053); -#170053 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 +#172439 = ADVANCED_FACE('',(#172440),#172455,.T.); +#172440 = FACE_BOUND('',#172441,.T.); +#172441 = EDGE_LOOP('',(#172442,#172534,#172619,#172666)); +#172442 = ORIENTED_EDGE('',*,*,#172443,.F.); +#172443 = EDGE_CURVE('',#172444,#172446,#172448,.T.); +#172444 = VERTEX_POINT('',#172445); +#172445 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 )); -#170054 = VERTEX_POINT('',#170055); -#170055 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, +#172446 = VERTEX_POINT('',#172447); +#172447 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, 1.162940952255)); -#170056 = SURFACE_CURVE('',#170057,(#170062,#170108),.PCURVE_S1.); -#170057 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170058,#170059,#170060, -#170061),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172448 = SURFACE_CURVE('',#172449,(#172454,#172500),.PCURVE_S1.); +#172449 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172450,#172451,#172452, +#172453),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.614007241618E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170058 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 +#172450 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 )); -#170059 = CARTESIAN_POINT('',(1.24878608255,-0.633243924364,1.167717466) +#172451 = CARTESIAN_POINT('',(1.24878608255,-0.633243924364,1.167717466) ); -#170060 = CARTESIAN_POINT('',(1.213215504454,-0.648328016991, +#172452 = CARTESIAN_POINT('',(1.213215504454,-0.648328016991, 1.166047546673)); -#170061 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, +#172453 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, 1.162940952255)); -#170062 = PCURVE('',#170063,#170080); -#170063 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170064,#170065,#170066,#170067) - ,(#170068,#170069,#170070,#170071) - ,(#170072,#170073,#170074,#170075) - ,(#170076,#170077,#170078,#170079 +#172454 = PCURVE('',#172455,#172472); +#172455 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172456,#172457,#172458,#172459) + ,(#172460,#172461,#172462,#172463) + ,(#172464,#172465,#172466,#172467) + ,(#172468,#172469,#172470,#172471 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170064 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, +#172456 = CARTESIAN_POINT('',(1.174271552513,-0.649160426457, 1.162940952255)); -#170065 = CARTESIAN_POINT('',(1.174271552513,-0.643513870827, +#172457 = CARTESIAN_POINT('',(1.174271552513,-0.643513870827, 1.184014184754)); -#170066 = CARTESIAN_POINT('',(1.174271552513,-0.622680750792,1.2)); -#170067 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); -#170068 = CARTESIAN_POINT('',(1.212291611921,-0.648347764779, +#172458 = CARTESIAN_POINT('',(1.174271552513,-0.622680750792,1.2)); +#172459 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); +#172460 = CARTESIAN_POINT('',(1.212291611921,-0.648347764779, 1.165973846926)); -#170069 = CARTESIAN_POINT('',(1.210873249723,-0.641648746428, +#172461 = CARTESIAN_POINT('',(1.210873249723,-0.641648746428, 1.185681523985)); -#170070 = CARTESIAN_POINT('',(1.205640163951,-0.621634122922,1.2)); -#170071 = CARTESIAN_POINT('',(1.200160033237,-0.600864135142,1.2)); -#170072 = CARTESIAN_POINT('',(1.249432051833,-0.632597955081,1.167717466 +#172462 = CARTESIAN_POINT('',(1.205640163951,-0.621634122922,1.2)); +#172463 = CARTESIAN_POINT('',(1.200160033237,-0.600864135142,1.2)); +#172464 = CARTESIAN_POINT('',(1.249432051833,-0.632597955081,1.167717466 )); -#170073 = CARTESIAN_POINT('',(1.245737677168,-0.626198171686, +#172465 = CARTESIAN_POINT('',(1.245737677168,-0.626198171686, 1.186553421368)); -#170074 = CARTESIAN_POINT('',(1.235657592716,-0.60873639183,1.2)); -#170075 = CARTESIAN_POINT('',(1.22523179406,-0.590675729559,1.2)); -#170076 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 +#172466 = CARTESIAN_POINT('',(1.235657592716,-0.60873639183,1.2)); +#172467 = CARTESIAN_POINT('',(1.22523179406,-0.590675729559,1.2)); +#172468 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 )); -#170077 = CARTESIAN_POINT('',(1.270967924427,-0.600967924427, +#172469 = CARTESIAN_POINT('',(1.270967924427,-0.600967924427, 1.186553421368)); -#170078 = CARTESIAN_POINT('',(1.257196992273,-0.587196992273,1.2)); -#170079 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); -#170080 = DEFINITIONAL_REPRESENTATION('',(#170081),#170107); -#170081 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170082,#170083,#170084, - #170085,#170086,#170087,#170088,#170089,#170090,#170091,#170092, - #170093,#170094,#170095,#170096,#170097,#170098,#170099,#170100, - #170101,#170102,#170103,#170104,#170105,#170106),.UNSPECIFIED.,.F., +#172470 = CARTESIAN_POINT('',(1.257196992273,-0.587196992273,1.2)); +#172471 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); +#172472 = DEFINITIONAL_REPRESENTATION('',(#172473),#172499); +#172473 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172474,#172475,#172476, + #172477,#172478,#172479,#172480,#172481,#172482,#172483,#172484, + #172485,#172486,#172487,#172488,#172489,#172490,#172491,#172492, + #172493,#172494,#172495,#172496,#172497,#172498),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.614007241618E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -210205,48 +213207,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#170082 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170083 = CARTESIAN_POINT('',(6.272059551128,2.972804141012E-006)); -#170084 = CARTESIAN_POINT('',(6.249732638972,-1.037052466103E-005)); -#170085 = CARTESIAN_POINT('',(6.216039360813,-5.446484094687E-005)); -#170086 = CARTESIAN_POINT('',(6.182166930891,-8.868396576412E-005)); -#170087 = CARTESIAN_POINT('',(6.148137469616,-7.965797689825E-005)); -#170088 = CARTESIAN_POINT('',(6.113972837442,-8.226451401267E-005)); -#170089 = CARTESIAN_POINT('',(6.079693755153,-8.179989506526E-005)); -#170090 = CARTESIAN_POINT('',(6.045320300361,-8.220472162612E-005)); -#170091 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); -#170092 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#170093 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#170094 = CARTESIAN_POINT('',(5.907265074214,-8.346461194624E-005)); -#170095 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); -#170096 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#170097 = CARTESIAN_POINT('',(5.803652201529,-8.485308429908E-005)); -#170098 = CARTESIAN_POINT('',(5.769199593774,-8.542361824745E-005)); -#170099 = CARTESIAN_POINT('',(5.734821280548,-8.593542635465E-005)); -#170100 = CARTESIAN_POINT('',(5.700537102675,-8.687405903526E-005)); -#170101 = CARTESIAN_POINT('',(5.666367464043,-8.643182883874E-005)); -#170102 = CARTESIAN_POINT('',(5.632333796953,-9.135957814741E-005)); -#170103 = CARTESIAN_POINT('',(5.59845580442,-3.211524036937E-005)); -#170104 = CARTESIAN_POINT('',(5.564759360754,-7.920748667577E-006)); -#170105 = CARTESIAN_POINT('',(5.542431620275,5.702886828105E-008)); -#170106 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170107 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170108 = PCURVE('',#170109,#170114); -#170109 = CYLINDRICAL_SURFACE('',#170110,0.15); -#170110 = AXIS2_PLACEMENT_3D('',#170111,#170112,#170113); -#170111 = CARTESIAN_POINT('',(1.233756746343,-0.563756746343, +#172474 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172475 = CARTESIAN_POINT('',(6.272059551128,2.972804141012E-006)); +#172476 = CARTESIAN_POINT('',(6.249732638972,-1.037052466103E-005)); +#172477 = CARTESIAN_POINT('',(6.216039360813,-5.446484094687E-005)); +#172478 = CARTESIAN_POINT('',(6.182166930891,-8.868396576412E-005)); +#172479 = CARTESIAN_POINT('',(6.148137469616,-7.965797689825E-005)); +#172480 = CARTESIAN_POINT('',(6.113972837442,-8.226451401267E-005)); +#172481 = CARTESIAN_POINT('',(6.079693755153,-8.179989506526E-005)); +#172482 = CARTESIAN_POINT('',(6.045320300361,-8.220472162612E-005)); +#172483 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); +#172484 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#172485 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#172486 = CARTESIAN_POINT('',(5.907265074214,-8.346461194624E-005)); +#172487 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); +#172488 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#172489 = CARTESIAN_POINT('',(5.803652201529,-8.485308429908E-005)); +#172490 = CARTESIAN_POINT('',(5.769199593774,-8.542361824745E-005)); +#172491 = CARTESIAN_POINT('',(5.734821280548,-8.593542635465E-005)); +#172492 = CARTESIAN_POINT('',(5.700537102675,-8.687405903526E-005)); +#172493 = CARTESIAN_POINT('',(5.666367464043,-8.643182883874E-005)); +#172494 = CARTESIAN_POINT('',(5.632333796953,-9.135957814741E-005)); +#172495 = CARTESIAN_POINT('',(5.59845580442,-3.211524036937E-005)); +#172496 = CARTESIAN_POINT('',(5.564759360754,-7.920748667577E-006)); +#172497 = CARTESIAN_POINT('',(5.542431620275,5.702886828105E-008)); +#172498 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172500 = PCURVE('',#172501,#172506); +#172501 = CYLINDRICAL_SURFACE('',#172502,0.15); +#172502 = AXIS2_PLACEMENT_3D('',#172503,#172504,#172505); +#172503 = CARTESIAN_POINT('',(1.233756746343,-0.563756746343, 0.90211632982)); -#170112 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) +#172504 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) ); -#170113 = DIRECTION('',(-0.965925826289,3.026618127129E-017, +#172505 = DIRECTION('',(-0.965925826289,3.026618127129E-017, -0.258819045103)); -#170114 = DEFINITIONAL_REPRESENTATION('',(#170115),#170141); -#170115 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170116,#170117,#170118, - #170119,#170120,#170121,#170122,#170123,#170124,#170125,#170126, - #170127,#170128,#170129,#170130,#170131,#170132,#170133,#170134, - #170135,#170136,#170137,#170138,#170139,#170140),.UNSPECIFIED.,.F., +#172506 = DEFINITIONAL_REPRESENTATION('',(#172507),#172533); +#172507 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172508,#172509,#172510, + #172511,#172512,#172513,#172514,#172515,#172516,#172517,#172518, + #172519,#172520,#172521,#172522,#172523,#172524,#172525,#172526, + #172527,#172528,#172529,#172530,#172531,#172532),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.614007241618E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -210255,50 +213257,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#170116 = CARTESIAN_POINT('',(3.893472067885,-0.227190413813)); -#170117 = CARTESIAN_POINT('',(3.90459767512,-0.227190402527)); -#170118 = CARTESIAN_POINT('',(3.926919725,-0.227204494097)); -#170119 = CARTESIAN_POINT('',(3.960597703687,-0.227268565379)); -#170120 = CARTESIAN_POINT('',(3.994453220183,-0.227376216926)); -#170121 = CARTESIAN_POINT('',(4.028468081361,-0.227527903142)); -#170122 = CARTESIAN_POINT('',(4.062623617158,-0.227723944337)); -#170123 = CARTESIAN_POINT('',(4.096900657675,-0.22796450436)); -#170124 = CARTESIAN_POINT('',(4.13127961549,-0.228249591264)); -#170125 = CARTESIAN_POINT('',(4.165740544467,-0.228579053446)); -#170126 = CARTESIAN_POINT('',(4.200263208931,-0.228952578741)); -#170127 = CARTESIAN_POINT('',(4.234827153442,-0.229369694517)); -#170128 = CARTESIAN_POINT('',(4.269411775032,-0.229829769328)); -#170129 = CARTESIAN_POINT('',(4.303996396623,-0.23033201597)); -#170130 = CARTESIAN_POINT('',(4.338560341134,-0.230875495964)); -#170131 = CARTESIAN_POINT('',(4.373083005598,-0.231459125378)); -#170132 = CARTESIAN_POINT('',(4.407543934574,-0.232081681942)); -#170133 = CARTESIAN_POINT('',(4.44192289239,-0.232741813329)); -#170134 = CARTESIAN_POINT('',(4.476199932907,-0.23343804655)); -#170135 = CARTESIAN_POINT('',(4.510355468703,-0.234168798116)); -#170136 = CARTESIAN_POINT('',(4.544370329882,-0.234932385611)); -#170137 = CARTESIAN_POINT('',(4.578225846377,-0.235727037611)); -#170138 = CARTESIAN_POINT('',(4.611903825065,-0.236550912605)); -#170139 = CARTESIAN_POINT('',(4.634225874945,-0.237118361824)); -#170140 = CARTESIAN_POINT('',(4.64535148218,-0.237406319482)); -#170141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170142 = ORIENTED_EDGE('',*,*,#170143,.T.); -#170143 = EDGE_CURVE('',#170052,#170144,#170146,.T.); -#170144 = VERTEX_POINT('',#170145); -#170145 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); -#170146 = SURFACE_CURVE('',#170147,(#170152,#170181),.PCURVE_S1.); -#170147 = CIRCLE('',#170148,5.E-002); -#170148 = AXIS2_PLACEMENT_3D('',#170149,#170150,#170151); -#170149 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.15)); -#170150 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#170151 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#170152 = PCURVE('',#170063,#170153); -#170153 = DEFINITIONAL_REPRESENTATION('',(#170154),#170180); -#170154 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170155,#170156,#170157, - #170158,#170159,#170160,#170161,#170162,#170163,#170164,#170165, - #170166,#170167,#170168,#170169,#170170,#170171,#170172,#170173, - #170174,#170175,#170176,#170177,#170178,#170179),.UNSPECIFIED.,.F., +#172508 = CARTESIAN_POINT('',(3.893472067885,-0.227190413813)); +#172509 = CARTESIAN_POINT('',(3.90459767512,-0.227190402527)); +#172510 = CARTESIAN_POINT('',(3.926919725,-0.227204494097)); +#172511 = CARTESIAN_POINT('',(3.960597703687,-0.227268565379)); +#172512 = CARTESIAN_POINT('',(3.994453220183,-0.227376216926)); +#172513 = CARTESIAN_POINT('',(4.028468081361,-0.227527903142)); +#172514 = CARTESIAN_POINT('',(4.062623617158,-0.227723944337)); +#172515 = CARTESIAN_POINT('',(4.096900657675,-0.22796450436)); +#172516 = CARTESIAN_POINT('',(4.13127961549,-0.228249591264)); +#172517 = CARTESIAN_POINT('',(4.165740544467,-0.228579053446)); +#172518 = CARTESIAN_POINT('',(4.200263208931,-0.228952578741)); +#172519 = CARTESIAN_POINT('',(4.234827153442,-0.229369694517)); +#172520 = CARTESIAN_POINT('',(4.269411775032,-0.229829769328)); +#172521 = CARTESIAN_POINT('',(4.303996396623,-0.23033201597)); +#172522 = CARTESIAN_POINT('',(4.338560341134,-0.230875495964)); +#172523 = CARTESIAN_POINT('',(4.373083005598,-0.231459125378)); +#172524 = CARTESIAN_POINT('',(4.407543934574,-0.232081681942)); +#172525 = CARTESIAN_POINT('',(4.44192289239,-0.232741813329)); +#172526 = CARTESIAN_POINT('',(4.476199932907,-0.23343804655)); +#172527 = CARTESIAN_POINT('',(4.510355468703,-0.234168798116)); +#172528 = CARTESIAN_POINT('',(4.544370329882,-0.234932385611)); +#172529 = CARTESIAN_POINT('',(4.578225846377,-0.235727037611)); +#172530 = CARTESIAN_POINT('',(4.611903825065,-0.236550912605)); +#172531 = CARTESIAN_POINT('',(4.634225874945,-0.237118361824)); +#172532 = CARTESIAN_POINT('',(4.64535148218,-0.237406319482)); +#172533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172534 = ORIENTED_EDGE('',*,*,#172535,.T.); +#172535 = EDGE_CURVE('',#172444,#172536,#172538,.T.); +#172536 = VERTEX_POINT('',#172537); +#172537 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); +#172538 = SURFACE_CURVE('',#172539,(#172544,#172573),.PCURVE_S1.); +#172539 = CIRCLE('',#172540,5.E-002); +#172540 = AXIS2_PLACEMENT_3D('',#172541,#172542,#172543); +#172541 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.15)); +#172542 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#172543 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#172544 = PCURVE('',#172455,#172545); +#172545 = DEFINITIONAL_REPRESENTATION('',(#172546),#172572); +#172546 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172547,#172548,#172549, + #172550,#172551,#172552,#172553,#172554,#172555,#172556,#172557, + #172558,#172559,#172560,#172561,#172562,#172563,#172564,#172565, + #172566,#172567,#172568,#172569,#172570,#172571),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -210306,71 +213308,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170155 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170156 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#170157 = CARTESIAN_POINT('',(6.28318530718,4.549920749136E-002)); -#170158 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#170159 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#170160 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#170161 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#170162 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#170163 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#170164 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#170165 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#170166 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#170167 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#170168 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#170169 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#170170 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#170171 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#170172 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#170173 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#170174 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#170175 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#170176 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#170177 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#170178 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#170179 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170181 = PCURVE('',#170182,#170199); -#170182 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170183,#170184,#170185,#170186) - ,(#170187,#170188,#170189,#170190) - ,(#170191,#170192,#170193,#170194) - ,(#170195,#170196,#170197,#170198 +#172547 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172548 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#172549 = CARTESIAN_POINT('',(6.28318530718,4.549920749136E-002)); +#172550 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#172551 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#172552 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#172553 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#172554 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#172555 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#172556 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#172557 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#172558 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#172559 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#172560 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#172561 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#172562 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#172563 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#172564 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#172565 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#172566 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#172567 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#172568 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#172569 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#172570 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#172571 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172573 = PCURVE('',#172574,#172591); +#172574 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172575,#172576,#172577,#172578) + ,(#172579,#172580,#172581,#172582) + ,(#172583,#172584,#172585,#172586) + ,(#172587,#172588,#172589,#172590 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170183 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 +#172575 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 )); -#170184 = CARTESIAN_POINT('',(1.270967924427,-0.600967924427, +#172576 = CARTESIAN_POINT('',(1.270967924427,-0.600967924427, 1.186553421368)); -#170185 = CARTESIAN_POINT('',(1.257196992273,-0.587196992273,1.2)); -#170186 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); -#170187 = CARTESIAN_POINT('',(1.302597955081,-0.579432051833,1.167717466 +#172577 = CARTESIAN_POINT('',(1.257196992273,-0.587196992273,1.2)); +#172578 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); +#172579 = CARTESIAN_POINT('',(1.302597955081,-0.579432051833,1.167717466 )); -#170188 = CARTESIAN_POINT('',(1.296198171686,-0.575737677168, +#172580 = CARTESIAN_POINT('',(1.296198171686,-0.575737677168, 1.186553421368)); -#170189 = CARTESIAN_POINT('',(1.27873639183,-0.565657592716,1.2)); -#170190 = CARTESIAN_POINT('',(1.260675729559,-0.55523179406,1.2)); -#170191 = CARTESIAN_POINT('',(1.318347764779,-0.542291611921, +#172581 = CARTESIAN_POINT('',(1.27873639183,-0.565657592716,1.2)); +#172582 = CARTESIAN_POINT('',(1.260675729559,-0.55523179406,1.2)); +#172583 = CARTESIAN_POINT('',(1.318347764779,-0.542291611921, 1.165973846926)); -#170192 = CARTESIAN_POINT('',(1.311648746428,-0.540873249723, +#172584 = CARTESIAN_POINT('',(1.311648746428,-0.540873249723, 1.185681523985)); -#170193 = CARTESIAN_POINT('',(1.291634122922,-0.535640163951,1.2)); -#170194 = CARTESIAN_POINT('',(1.270864135142,-0.530160033237,1.2)); -#170195 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, +#172585 = CARTESIAN_POINT('',(1.291634122922,-0.535640163951,1.2)); +#172586 = CARTESIAN_POINT('',(1.270864135142,-0.530160033237,1.2)); +#172587 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, 1.162940952255)); -#170196 = CARTESIAN_POINT('',(1.313513870827,-0.504271552513, +#172588 = CARTESIAN_POINT('',(1.313513870827,-0.504271552513, 1.184014184754)); -#170197 = CARTESIAN_POINT('',(1.292680750792,-0.504271552513,1.2)); -#170198 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); -#170199 = DEFINITIONAL_REPRESENTATION('',(#170200),#170226); -#170200 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170201,#170202,#170203, - #170204,#170205,#170206,#170207,#170208,#170209,#170210,#170211, - #170212,#170213,#170214,#170215,#170216,#170217,#170218,#170219, - #170220,#170221,#170222,#170223,#170224,#170225),.UNSPECIFIED.,.F., +#172589 = CARTESIAN_POINT('',(1.292680750792,-0.504271552513,1.2)); +#172590 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); +#172591 = DEFINITIONAL_REPRESENTATION('',(#172592),#172618); +#172592 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172593,#172594,#172595, + #172596,#172597,#172598,#172599,#172600,#172601,#172602,#172603, + #172604,#172605,#172606,#172607,#172608,#172609,#172610,#172611, + #172612,#172613,#172614,#172615,#172616,#172617),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -210378,55 +213380,55 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170201 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#170202 = CARTESIAN_POINT('',(-7.447137389069E-016,1.515278164504E-002) - ); -#170203 = CARTESIAN_POINT('',(1.690896660366E-017,4.549920749135E-002)); -#170204 = CARTESIAN_POINT('',(1.534404611661E-015,9.109101074356E-002)); -#170205 = CARTESIAN_POINT('',(1.223015755288E-016,0.136698748187)); -#170206 = CARTESIAN_POINT('',(3.706859707299E-016,0.1822865144)); -#170207 = CARTESIAN_POINT('',(1.292126551717E-016,0.2278300409)); -#170208 = CARTESIAN_POINT('',(1.428877274553E-016,0.27331674602)); -#170209 = CARTESIAN_POINT('',(2.901329581389E-015,0.318743220066)); -#170210 = CARTESIAN_POINT('',(1.10991240116E-015,0.364113426255)); -#170211 = CARTESIAN_POINT('',(9.421683493546E-016,0.409436881051)); -#170212 = CARTESIAN_POINT('',(-1.262777204249E-015,0.454727066523)); -#170213 = CARTESIAN_POINT('',(2.987963663652E-015,0.5)); -#170214 = CARTESIAN_POINT('',(1.477870713674E-015,0.545272933477)); -#170215 = CARTESIAN_POINT('',(1.779620592885E-015,0.590563118949)); -#170216 = CARTESIAN_POINT('',(5.403108069643E-016,0.635886573745)); -#170217 = CARTESIAN_POINT('',(-2.405239912553E-016,0.681256779934)); -#170218 = CARTESIAN_POINT('',(2.572303406239E-015,0.72668325398)); -#170219 = CARTESIAN_POINT('',(2.560004544556E-015,0.7721699591)); -#170220 = CARTESIAN_POINT('',(1.996650058231E-015,0.8177134856)); -#170221 = CARTESIAN_POINT('',(2.228920504541E-015,0.863301251813)); -#170222 = CARTESIAN_POINT('',(-1.780045041639E-016,0.908908989256)); -#170223 = CARTESIAN_POINT('',(2.724252971116E-015,0.954500792509)); -#170224 = CARTESIAN_POINT('',(1.412575536931E-015,0.984847218355)); -#170225 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#170226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170227 = ORIENTED_EDGE('',*,*,#170228,.F.); -#170228 = EDGE_CURVE('',#170229,#170144,#170231,.T.); -#170229 = VERTEX_POINT('',#170230); -#170230 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); -#170231 = SURFACE_CURVE('',#170232,(#170237,#170266),.PCURVE_S1.); -#170232 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170233,#170234,#170235, -#170236),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172593 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#172594 = CARTESIAN_POINT('',(-7.447137389069E-016,1.515278164504E-002) + ); +#172595 = CARTESIAN_POINT('',(1.690896660366E-017,4.549920749135E-002)); +#172596 = CARTESIAN_POINT('',(1.534404611661E-015,9.109101074356E-002)); +#172597 = CARTESIAN_POINT('',(1.223015755288E-016,0.136698748187)); +#172598 = CARTESIAN_POINT('',(3.706859707299E-016,0.1822865144)); +#172599 = CARTESIAN_POINT('',(1.292126551717E-016,0.2278300409)); +#172600 = CARTESIAN_POINT('',(1.428877274553E-016,0.27331674602)); +#172601 = CARTESIAN_POINT('',(2.901329581389E-015,0.318743220066)); +#172602 = CARTESIAN_POINT('',(1.10991240116E-015,0.364113426255)); +#172603 = CARTESIAN_POINT('',(9.421683493546E-016,0.409436881051)); +#172604 = CARTESIAN_POINT('',(-1.262777204249E-015,0.454727066523)); +#172605 = CARTESIAN_POINT('',(2.987963663652E-015,0.5)); +#172606 = CARTESIAN_POINT('',(1.477870713674E-015,0.545272933477)); +#172607 = CARTESIAN_POINT('',(1.779620592885E-015,0.590563118949)); +#172608 = CARTESIAN_POINT('',(5.403108069643E-016,0.635886573745)); +#172609 = CARTESIAN_POINT('',(-2.405239912553E-016,0.681256779934)); +#172610 = CARTESIAN_POINT('',(2.572303406239E-015,0.72668325398)); +#172611 = CARTESIAN_POINT('',(2.560004544556E-015,0.7721699591)); +#172612 = CARTESIAN_POINT('',(1.996650058231E-015,0.8177134856)); +#172613 = CARTESIAN_POINT('',(2.228920504541E-015,0.863301251813)); +#172614 = CARTESIAN_POINT('',(-1.780045041639E-016,0.908908989256)); +#172615 = CARTESIAN_POINT('',(2.724252971116E-015,0.954500792509)); +#172616 = CARTESIAN_POINT('',(1.412575536931E-015,0.984847218355)); +#172617 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#172618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172619 = ORIENTED_EDGE('',*,*,#172620,.F.); +#172620 = EDGE_CURVE('',#172621,#172536,#172623,.T.); +#172621 = VERTEX_POINT('',#172622); +#172622 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); +#172623 = SURFACE_CURVE('',#172624,(#172629,#172658),.PCURVE_S1.); +#172624 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172625,#172626,#172627, +#172628),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170233 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); -#170234 = CARTESIAN_POINT('',(1.200789126784,-0.600864135142,1.2)); -#170235 = CARTESIAN_POINT('',(1.224801147872,-0.591106375747,1.2)); -#170236 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); -#170237 = PCURVE('',#170063,#170238); -#170238 = DEFINITIONAL_REPRESENTATION('',(#170239),#170265); -#170239 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170240,#170241,#170242, - #170243,#170244,#170245,#170246,#170247,#170248,#170249,#170250, - #170251,#170252,#170253,#170254,#170255,#170256,#170257,#170258, - #170259,#170260,#170261,#170262,#170263,#170264),.UNSPECIFIED.,.F., +#172625 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.2)); +#172626 = CARTESIAN_POINT('',(1.200789126784,-0.600864135142,1.2)); +#172627 = CARTESIAN_POINT('',(1.224801147872,-0.591106375747,1.2)); +#172628 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); +#172629 = PCURVE('',#172455,#172630); +#172630 = DEFINITIONAL_REPRESENTATION('',(#172631),#172657); +#172631 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172632,#172633,#172634, + #172635,#172636,#172637,#172638,#172639,#172640,#172641,#172642, + #172643,#172644,#172645,#172646,#172647,#172648,#172649,#172650, + #172651,#172652,#172653,#172654,#172655,#172656),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -210434,62 +213436,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170240 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170241 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#170242 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#170243 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#170244 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#170245 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#170246 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#170247 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#170248 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#170249 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#170250 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#170251 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#170252 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#170253 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#170254 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#170255 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#170256 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#170257 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#170258 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#170259 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#170260 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#170261 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#170262 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#170263 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#170264 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170266 = PCURVE('',#169987,#170267); -#170267 = DEFINITIONAL_REPRESENTATION('',(#170268),#170273); -#170268 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170269,#170270,#170271, -#170272),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172632 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172633 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#172634 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#172635 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#172636 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#172637 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#172638 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#172639 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#172640 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#172641 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#172642 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#172643 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#172644 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#172645 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#172646 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#172647 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#172648 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#172649 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#172650 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#172651 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#172652 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#172653 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#172654 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#172655 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#172656 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172658 = PCURVE('',#172379,#172659); +#172659 = DEFINITIONAL_REPRESENTATION('',(#172660),#172665); +#172660 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172661,#172662,#172663, +#172664),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170269 = CARTESIAN_POINT('',(-0.295728447487,0.199135864858)); -#170270 = CARTESIAN_POINT('',(-0.269210873216,0.199135864858)); -#170271 = CARTESIAN_POINT('',(-0.245198852128,0.208893624253)); -#170272 = CARTESIAN_POINT('',(-0.227046238191,0.227046238191)); -#170273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170274 = ORIENTED_EDGE('',*,*,#170275,.F.); -#170275 = EDGE_CURVE('',#170054,#170229,#170276,.T.); -#170276 = SURFACE_CURVE('',#170277,(#170282,#170311),.PCURVE_S1.); -#170277 = CIRCLE('',#170278,5.E-002); -#170278 = AXIS2_PLACEMENT_3D('',#170279,#170280,#170281); -#170279 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.15)); -#170280 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#170281 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170282 = PCURVE('',#170063,#170283); -#170283 = DEFINITIONAL_REPRESENTATION('',(#170284),#170310); -#170284 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170285,#170286,#170287, - #170288,#170289,#170290,#170291,#170292,#170293,#170294,#170295, - #170296,#170297,#170298,#170299,#170300,#170301,#170302,#170303, - #170304,#170305,#170306,#170307,#170308,#170309),.UNSPECIFIED.,.F., +#172661 = CARTESIAN_POINT('',(-0.295728447487,0.199135864858)); +#172662 = CARTESIAN_POINT('',(-0.269210873216,0.199135864858)); +#172663 = CARTESIAN_POINT('',(-0.245198852128,0.208893624253)); +#172664 = CARTESIAN_POINT('',(-0.227046238191,0.227046238191)); +#172665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172666 = ORIENTED_EDGE('',*,*,#172667,.F.); +#172667 = EDGE_CURVE('',#172446,#172621,#172668,.T.); +#172668 = SURFACE_CURVE('',#172669,(#172674,#172703),.PCURVE_S1.); +#172669 = CIRCLE('',#172670,5.E-002); +#172670 = AXIS2_PLACEMENT_3D('',#172671,#172672,#172673); +#172671 = CARTESIAN_POINT('',(1.174271552513,-0.600864135142,1.15)); +#172672 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#172673 = DIRECTION('',(0.E+000,0.E+000,1.)); +#172674 = PCURVE('',#172455,#172675); +#172675 = DEFINITIONAL_REPRESENTATION('',(#172676),#172702); +#172676 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172677,#172678,#172679, + #172680,#172681,#172682,#172683,#172684,#172685,#172686,#172687, + #172688,#172689,#172690,#172691,#172692,#172693,#172694,#172695, + #172696,#172697,#172698,#172699,#172700,#172701),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -210497,111 +213499,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170285 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170286 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#170287 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#170288 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#170289 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#170290 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#170291 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#170292 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#170293 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#170294 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#170295 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#170296 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#170297 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#170298 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#170299 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#170300 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#170301 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#170302 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#170303 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#170304 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#170305 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#170306 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#170307 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#170308 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#170309 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170311 = PCURVE('',#170312,#170317); -#170312 = CYLINDRICAL_SURFACE('',#170313,5.E-002); -#170313 = AXIS2_PLACEMENT_3D('',#170314,#170315,#170316); -#170314 = CARTESIAN_POINT('',(1.47,-0.600864135142,1.15)); -#170315 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170316 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#170317 = DEFINITIONAL_REPRESENTATION('',(#170318),#170321); -#170318 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170319,#170320), +#172677 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172678 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#172679 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#172680 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#172681 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#172682 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#172683 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#172684 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#172685 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#172686 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#172687 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#172688 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#172689 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#172690 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#172691 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#172692 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#172693 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#172694 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#172695 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#172696 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#172697 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#172698 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#172699 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#172700 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#172701 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172703 = PCURVE('',#172704,#172709); +#172704 = CYLINDRICAL_SURFACE('',#172705,5.E-002); +#172705 = AXIS2_PLACEMENT_3D('',#172706,#172707,#172708); +#172706 = CARTESIAN_POINT('',(1.47,-0.600864135142,1.15)); +#172707 = DIRECTION('',(1.,0.E+000,0.E+000)); +#172708 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#172709 = DEFINITIONAL_REPRESENTATION('',(#172710),#172713); +#172710 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172711,#172712), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#170319 = CARTESIAN_POINT('',(4.450589592586,-0.295728447487)); -#170320 = CARTESIAN_POINT('',(3.14159265359,-0.295728447487)); -#170321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#172711 = CARTESIAN_POINT('',(4.450589592586,-0.295728447487)); +#172712 = CARTESIAN_POINT('',(3.14159265359,-0.295728447487)); +#172713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#170322 = ADVANCED_FACE('',(#170323),#170338,.T.); -#170323 = FACE_BOUND('',#170324,.T.); -#170324 = EDGE_LOOP('',(#170325,#170417,#170502,#170549)); -#170325 = ORIENTED_EDGE('',*,*,#170326,.F.); -#170326 = EDGE_CURVE('',#170327,#170329,#170331,.T.); -#170327 = VERTEX_POINT('',#170328); -#170328 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 +#172714 = ADVANCED_FACE('',(#172715),#172730,.T.); +#172715 = FACE_BOUND('',#172716,.T.); +#172716 = EDGE_LOOP('',(#172717,#172809,#172894,#172941)); +#172717 = ORIENTED_EDGE('',*,*,#172718,.F.); +#172718 = EDGE_CURVE('',#172719,#172721,#172723,.T.); +#172719 = VERTEX_POINT('',#172720); +#172720 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 )); -#170329 = VERTEX_POINT('',#170330); -#170330 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, +#172721 = VERTEX_POINT('',#172722); +#172722 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, 1.162940952255)); -#170331 = SURFACE_CURVE('',#170332,(#170337,#170383),.PCURVE_S1.); -#170332 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170333,#170334,#170335, -#170336),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#172723 = SURFACE_CURVE('',#172724,(#172729,#172775),.PCURVE_S1.); +#172724 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172725,#172726,#172727, +#172728),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170333 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 +#172725 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 )); -#170334 = CARTESIAN_POINT('',(-1.24878608255,0.633243924364,1.167717466) +#172726 = CARTESIAN_POINT('',(-1.24878608255,0.633243924364,1.167717466) ); -#170335 = CARTESIAN_POINT('',(-1.213215504454,0.648328016991, +#172727 = CARTESIAN_POINT('',(-1.213215504454,0.648328016991, 1.166047546673)); -#170336 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, +#172728 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, 1.162940952255)); -#170337 = PCURVE('',#170338,#170355); -#170338 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170339,#170340,#170341,#170342) - ,(#170343,#170344,#170345,#170346) - ,(#170347,#170348,#170349,#170350) - ,(#170351,#170352,#170353,#170354 +#172729 = PCURVE('',#172730,#172747); +#172730 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172731,#172732,#172733,#172734) + ,(#172735,#172736,#172737,#172738) + ,(#172739,#172740,#172741,#172742) + ,(#172743,#172744,#172745,#172746 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170339 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, +#172731 = CARTESIAN_POINT('',(-1.174271552513,0.649160426457, 1.162940952255)); -#170340 = CARTESIAN_POINT('',(-1.174271552513,0.643513870827, +#172732 = CARTESIAN_POINT('',(-1.174271552513,0.643513870827, 1.184014184754)); -#170341 = CARTESIAN_POINT('',(-1.174271552513,0.622680750792,1.2)); -#170342 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); -#170343 = CARTESIAN_POINT('',(-1.212291611921,0.648347764779, +#172733 = CARTESIAN_POINT('',(-1.174271552513,0.622680750792,1.2)); +#172734 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); +#172735 = CARTESIAN_POINT('',(-1.212291611921,0.648347764779, 1.165973846926)); -#170344 = CARTESIAN_POINT('',(-1.210873249723,0.641648746428, +#172736 = CARTESIAN_POINT('',(-1.210873249723,0.641648746428, 1.185681523985)); -#170345 = CARTESIAN_POINT('',(-1.205640163951,0.621634122922,1.2)); -#170346 = CARTESIAN_POINT('',(-1.200160033237,0.600864135142,1.2)); -#170347 = CARTESIAN_POINT('',(-1.249432051833,0.632597955081,1.167717466 +#172737 = CARTESIAN_POINT('',(-1.205640163951,0.621634122922,1.2)); +#172738 = CARTESIAN_POINT('',(-1.200160033237,0.600864135142,1.2)); +#172739 = CARTESIAN_POINT('',(-1.249432051833,0.632597955081,1.167717466 )); -#170348 = CARTESIAN_POINT('',(-1.245737677168,0.626198171686, +#172740 = CARTESIAN_POINT('',(-1.245737677168,0.626198171686, 1.186553421368)); -#170349 = CARTESIAN_POINT('',(-1.235657592716,0.60873639183,1.2)); -#170350 = CARTESIAN_POINT('',(-1.22523179406,0.590675729559,1.2)); -#170351 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 +#172741 = CARTESIAN_POINT('',(-1.235657592716,0.60873639183,1.2)); +#172742 = CARTESIAN_POINT('',(-1.22523179406,0.590675729559,1.2)); +#172743 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 )); -#170352 = CARTESIAN_POINT('',(-1.270967924427,0.600967924427, +#172744 = CARTESIAN_POINT('',(-1.270967924427,0.600967924427, 1.186553421368)); -#170353 = CARTESIAN_POINT('',(-1.257196992273,0.587196992273,1.2)); -#170354 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); -#170355 = DEFINITIONAL_REPRESENTATION('',(#170356),#170382); -#170356 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170357,#170358,#170359, - #170360,#170361,#170362,#170363,#170364,#170365,#170366,#170367, - #170368,#170369,#170370,#170371,#170372,#170373,#170374,#170375, - #170376,#170377,#170378,#170379,#170380,#170381),.UNSPECIFIED.,.F., +#172745 = CARTESIAN_POINT('',(-1.257196992273,0.587196992273,1.2)); +#172746 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); +#172747 = DEFINITIONAL_REPRESENTATION('',(#172748),#172774); +#172748 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172749,#172750,#172751, + #172752,#172753,#172754,#172755,#172756,#172757,#172758,#172759, + #172760,#172761,#172762,#172763,#172764,#172765,#172766,#172767, + #172768,#172769,#172770,#172771,#172772,#172773),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -210609,48 +213611,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#170357 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170358 = CARTESIAN_POINT('',(6.272059551128,2.972804134033E-006)); -#170359 = CARTESIAN_POINT('',(6.249732638972,-1.037052467453E-005)); -#170360 = CARTESIAN_POINT('',(6.216039360813,-5.446484095738E-005)); -#170361 = CARTESIAN_POINT('',(6.182166930891,-8.868396576131E-005)); -#170362 = CARTESIAN_POINT('',(6.148137469616,-7.9657976899E-005)); -#170363 = CARTESIAN_POINT('',(6.113972837442,-8.226451401247E-005)); -#170364 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); -#170365 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#170366 = CARTESIAN_POINT('',(6.010871913477,-8.242390084137E-005)); -#170367 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#170368 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#170369 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); -#170370 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); -#170371 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#170372 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); -#170373 = CARTESIAN_POINT('',(5.769199593774,-8.542361824742E-005)); -#170374 = CARTESIAN_POINT('',(5.734821280548,-8.593542635477E-005)); -#170375 = CARTESIAN_POINT('',(5.700537102675,-8.687405903478E-005)); -#170376 = CARTESIAN_POINT('',(5.666367464043,-8.643182884053E-005)); -#170377 = CARTESIAN_POINT('',(5.632333796953,-9.135957814074E-005)); -#170378 = CARTESIAN_POINT('',(5.59845580442,-3.211524037021E-005)); -#170379 = CARTESIAN_POINT('',(5.564759360754,-7.920748672386E-006)); -#170380 = CARTESIAN_POINT('',(5.542431620275,5.702886511363E-008)); -#170381 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170383 = PCURVE('',#170384,#170389); -#170384 = CYLINDRICAL_SURFACE('',#170385,0.15); -#170385 = AXIS2_PLACEMENT_3D('',#170386,#170387,#170388); -#170386 = CARTESIAN_POINT('',(-1.334207498814,0.664207498814, +#172749 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172750 = CARTESIAN_POINT('',(6.272059551128,2.972804134033E-006)); +#172751 = CARTESIAN_POINT('',(6.249732638972,-1.037052467453E-005)); +#172752 = CARTESIAN_POINT('',(6.216039360813,-5.446484095738E-005)); +#172753 = CARTESIAN_POINT('',(6.182166930891,-8.868396576131E-005)); +#172754 = CARTESIAN_POINT('',(6.148137469616,-7.9657976899E-005)); +#172755 = CARTESIAN_POINT('',(6.113972837442,-8.226451401247E-005)); +#172756 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); +#172757 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#172758 = CARTESIAN_POINT('',(6.010871913477,-8.242390084137E-005)); +#172759 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#172760 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#172761 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); +#172762 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); +#172763 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#172764 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); +#172765 = CARTESIAN_POINT('',(5.769199593774,-8.542361824742E-005)); +#172766 = CARTESIAN_POINT('',(5.734821280548,-8.593542635477E-005)); +#172767 = CARTESIAN_POINT('',(5.700537102675,-8.687405903478E-005)); +#172768 = CARTESIAN_POINT('',(5.666367464043,-8.643182884053E-005)); +#172769 = CARTESIAN_POINT('',(5.632333796953,-9.135957814074E-005)); +#172770 = CARTESIAN_POINT('',(5.59845580442,-3.211524037021E-005)); +#172771 = CARTESIAN_POINT('',(5.564759360754,-7.920748672386E-006)); +#172772 = CARTESIAN_POINT('',(5.542431620275,5.702886511363E-008)); +#172773 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172775 = PCURVE('',#172776,#172781); +#172776 = CYLINDRICAL_SURFACE('',#172777,0.15); +#172777 = AXIS2_PLACEMENT_3D('',#172778,#172779,#172780); +#172778 = CARTESIAN_POINT('',(-1.334207498814,0.664207498814, 0.527229017938)); -#170387 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) +#172779 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) ); -#170388 = DIRECTION('',(-0.965925826289,3.026618127129E-017, +#172780 = DIRECTION('',(-0.965925826289,3.026618127129E-017, 0.258819045103)); -#170389 = DEFINITIONAL_REPRESENTATION('',(#170390),#170416); -#170390 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170391,#170392,#170393, - #170394,#170395,#170396,#170397,#170398,#170399,#170400,#170401, - #170402,#170403,#170404,#170405,#170406,#170407,#170408,#170409, - #170410,#170411,#170412,#170413,#170414,#170415),.UNSPECIFIED.,.F., +#172781 = DEFINITIONAL_REPRESENTATION('',(#172782),#172808); +#172782 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172783,#172784,#172785, + #172786,#172787,#172788,#172789,#172790,#172791,#172792,#172793, + #172794,#172795,#172796,#172797,#172798,#172799,#172800,#172801, + #172802,#172803,#172804,#172805,#172806,#172807),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -210658,50 +213660,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#170391 = CARTESIAN_POINT('',(0.751879414295,-0.628090905151)); -#170392 = CARTESIAN_POINT('',(0.76300502153,-0.628090893864)); -#170393 = CARTESIAN_POINT('',(0.78532707141,-0.628104985434)); -#170394 = CARTESIAN_POINT('',(0.819005050097,-0.628169056716)); -#170395 = CARTESIAN_POINT('',(0.852860566593,-0.628276708263)); -#170396 = CARTESIAN_POINT('',(0.886875427771,-0.628428394479)); -#170397 = CARTESIAN_POINT('',(0.921030963568,-0.628624435674)); -#170398 = CARTESIAN_POINT('',(0.955308004085,-0.628864995698)); -#170399 = CARTESIAN_POINT('',(0.9896869619,-0.629150082601)); -#170400 = CARTESIAN_POINT('',(1.024147890877,-0.629479544784)); -#170401 = CARTESIAN_POINT('',(1.058670555341,-0.629853070079)); -#170402 = CARTESIAN_POINT('',(1.093234499852,-0.630270185855)); -#170403 = CARTESIAN_POINT('',(1.127819121442,-0.630730260665)); -#170404 = CARTESIAN_POINT('',(1.162403743033,-0.631232507307)); -#170405 = CARTESIAN_POINT('',(1.196967687544,-0.631775987301)); -#170406 = CARTESIAN_POINT('',(1.231490352008,-0.632359616715)); -#170407 = CARTESIAN_POINT('',(1.265951280985,-0.632982173279)); -#170408 = CARTESIAN_POINT('',(1.3003302388,-0.633642304667)); -#170409 = CARTESIAN_POINT('',(1.334607279317,-0.634338537887)); -#170410 = CARTESIAN_POINT('',(1.368762815114,-0.635069289453)); -#170411 = CARTESIAN_POINT('',(1.402777676292,-0.635832876948)); -#170412 = CARTESIAN_POINT('',(1.436633192788,-0.636627528948)); -#170413 = CARTESIAN_POINT('',(1.470311171475,-0.637451403942)); -#170414 = CARTESIAN_POINT('',(1.492633221355,-0.638018853161)); -#170415 = CARTESIAN_POINT('',(1.50375882859,-0.63830681082)); -#170416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170417 = ORIENTED_EDGE('',*,*,#170418,.T.); -#170418 = EDGE_CURVE('',#170327,#170419,#170421,.T.); -#170419 = VERTEX_POINT('',#170420); -#170420 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); -#170421 = SURFACE_CURVE('',#170422,(#170427,#170456),.PCURVE_S1.); -#170422 = CIRCLE('',#170423,5.E-002); -#170423 = AXIS2_PLACEMENT_3D('',#170424,#170425,#170426); -#170424 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.15)); -#170425 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#170426 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#170427 = PCURVE('',#170338,#170428); -#170428 = DEFINITIONAL_REPRESENTATION('',(#170429),#170455); -#170429 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170430,#170431,#170432, - #170433,#170434,#170435,#170436,#170437,#170438,#170439,#170440, - #170441,#170442,#170443,#170444,#170445,#170446,#170447,#170448, - #170449,#170450,#170451,#170452,#170453,#170454),.UNSPECIFIED.,.F., +#172783 = CARTESIAN_POINT('',(0.751879414295,-0.628090905151)); +#172784 = CARTESIAN_POINT('',(0.76300502153,-0.628090893864)); +#172785 = CARTESIAN_POINT('',(0.78532707141,-0.628104985434)); +#172786 = CARTESIAN_POINT('',(0.819005050097,-0.628169056716)); +#172787 = CARTESIAN_POINT('',(0.852860566593,-0.628276708263)); +#172788 = CARTESIAN_POINT('',(0.886875427771,-0.628428394479)); +#172789 = CARTESIAN_POINT('',(0.921030963568,-0.628624435674)); +#172790 = CARTESIAN_POINT('',(0.955308004085,-0.628864995698)); +#172791 = CARTESIAN_POINT('',(0.9896869619,-0.629150082601)); +#172792 = CARTESIAN_POINT('',(1.024147890877,-0.629479544784)); +#172793 = CARTESIAN_POINT('',(1.058670555341,-0.629853070079)); +#172794 = CARTESIAN_POINT('',(1.093234499852,-0.630270185855)); +#172795 = CARTESIAN_POINT('',(1.127819121442,-0.630730260665)); +#172796 = CARTESIAN_POINT('',(1.162403743033,-0.631232507307)); +#172797 = CARTESIAN_POINT('',(1.196967687544,-0.631775987301)); +#172798 = CARTESIAN_POINT('',(1.231490352008,-0.632359616715)); +#172799 = CARTESIAN_POINT('',(1.265951280985,-0.632982173279)); +#172800 = CARTESIAN_POINT('',(1.3003302388,-0.633642304667)); +#172801 = CARTESIAN_POINT('',(1.334607279317,-0.634338537887)); +#172802 = CARTESIAN_POINT('',(1.368762815114,-0.635069289453)); +#172803 = CARTESIAN_POINT('',(1.402777676292,-0.635832876948)); +#172804 = CARTESIAN_POINT('',(1.436633192788,-0.636627528948)); +#172805 = CARTESIAN_POINT('',(1.470311171475,-0.637451403942)); +#172806 = CARTESIAN_POINT('',(1.492633221355,-0.638018853161)); +#172807 = CARTESIAN_POINT('',(1.50375882859,-0.63830681082)); +#172808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172809 = ORIENTED_EDGE('',*,*,#172810,.T.); +#172810 = EDGE_CURVE('',#172719,#172811,#172813,.T.); +#172811 = VERTEX_POINT('',#172812); +#172812 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); +#172813 = SURFACE_CURVE('',#172814,(#172819,#172848),.PCURVE_S1.); +#172814 = CIRCLE('',#172815,5.E-002); +#172815 = AXIS2_PLACEMENT_3D('',#172816,#172817,#172818); +#172816 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.15)); +#172817 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#172818 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#172819 = PCURVE('',#172730,#172820); +#172820 = DEFINITIONAL_REPRESENTATION('',(#172821),#172847); +#172821 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172822,#172823,#172824, + #172825,#172826,#172827,#172828,#172829,#172830,#172831,#172832, + #172833,#172834,#172835,#172836,#172837,#172838,#172839,#172840, + #172841,#172842,#172843,#172844,#172845,#172846),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -210709,71 +213711,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170430 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170431 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#170432 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#170433 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#170434 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#170435 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#170436 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#170437 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#170438 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#170439 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#170440 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#170441 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#170442 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#170443 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#170444 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#170445 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#170446 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#170447 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#170448 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#170449 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#170450 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#170451 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#170452 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#170453 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#170454 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170456 = PCURVE('',#170457,#170474); -#170457 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170458,#170459,#170460,#170461) - ,(#170462,#170463,#170464,#170465) - ,(#170466,#170467,#170468,#170469) - ,(#170470,#170471,#170472,#170473 +#172822 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#172823 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#172824 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#172825 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#172826 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#172827 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#172828 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#172829 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#172830 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#172831 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#172832 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#172833 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#172834 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#172835 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#172836 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#172837 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#172838 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#172839 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#172840 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#172841 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#172842 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#172843 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#172844 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#172845 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#172846 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172848 = PCURVE('',#172849,#172866); +#172849 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#172850,#172851,#172852,#172853) + ,(#172854,#172855,#172856,#172857) + ,(#172858,#172859,#172860,#172861) + ,(#172862,#172863,#172864,#172865 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(0.E+000,0.751879414295),( 0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170458 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 +#172850 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 )); -#170459 = CARTESIAN_POINT('',(-1.270967924427,0.600967924427, +#172851 = CARTESIAN_POINT('',(-1.270967924427,0.600967924427, 1.186553421368)); -#170460 = CARTESIAN_POINT('',(-1.257196992273,0.587196992273,1.2)); -#170461 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); -#170462 = CARTESIAN_POINT('',(-1.302597955081,0.579432051833,1.167717466 +#172852 = CARTESIAN_POINT('',(-1.257196992273,0.587196992273,1.2)); +#172853 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); +#172854 = CARTESIAN_POINT('',(-1.302597955081,0.579432051833,1.167717466 )); -#170463 = CARTESIAN_POINT('',(-1.296198171686,0.575737677168, +#172855 = CARTESIAN_POINT('',(-1.296198171686,0.575737677168, 1.186553421368)); -#170464 = CARTESIAN_POINT('',(-1.27873639183,0.565657592716,1.2)); -#170465 = CARTESIAN_POINT('',(-1.260675729559,0.55523179406,1.2)); -#170466 = CARTESIAN_POINT('',(-1.318347764779,0.542291611921, +#172856 = CARTESIAN_POINT('',(-1.27873639183,0.565657592716,1.2)); +#172857 = CARTESIAN_POINT('',(-1.260675729559,0.55523179406,1.2)); +#172858 = CARTESIAN_POINT('',(-1.318347764779,0.542291611921, 1.165973846926)); -#170467 = CARTESIAN_POINT('',(-1.311648746428,0.540873249723, +#172859 = CARTESIAN_POINT('',(-1.311648746428,0.540873249723, 1.185681523985)); -#170468 = CARTESIAN_POINT('',(-1.291634122922,0.535640163951,1.2)); -#170469 = CARTESIAN_POINT('',(-1.270864135142,0.530160033237,1.2)); -#170470 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, +#172860 = CARTESIAN_POINT('',(-1.291634122922,0.535640163951,1.2)); +#172861 = CARTESIAN_POINT('',(-1.270864135142,0.530160033237,1.2)); +#172862 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, 1.162940952255)); -#170471 = CARTESIAN_POINT('',(-1.313513870827,0.504271552513, +#172863 = CARTESIAN_POINT('',(-1.313513870827,0.504271552513, 1.184014184754)); -#170472 = CARTESIAN_POINT('',(-1.292680750792,0.504271552513,1.2)); -#170473 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); -#170474 = DEFINITIONAL_REPRESENTATION('',(#170475),#170501); -#170475 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170476,#170477,#170478, - #170479,#170480,#170481,#170482,#170483,#170484,#170485,#170486, - #170487,#170488,#170489,#170490,#170491,#170492,#170493,#170494, - #170495,#170496,#170497,#170498,#170499,#170500),.UNSPECIFIED.,.F., +#172864 = CARTESIAN_POINT('',(-1.292680750792,0.504271552513,1.2)); +#172865 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); +#172866 = DEFINITIONAL_REPRESENTATION('',(#172867),#172893); +#172867 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172868,#172869,#172870, + #172871,#172872,#172873,#172874,#172875,#172876,#172877,#172878, + #172879,#172880,#172881,#172882,#172883,#172884,#172885,#172886, + #172887,#172888,#172889,#172890,#172891,#172892),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -210781,54 +213783,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170476 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#170477 = CARTESIAN_POINT('',(4.605886458701E-016,1.515278164504E-002)); -#170478 = CARTESIAN_POINT('',(1.249869054257E-015,4.549920749135E-002)); -#170479 = CARTESIAN_POINT('',(2.200630136876E-015,9.109101074357E-002)); -#170480 = CARTESIAN_POINT('',(-1.909847672284E-015,0.136698748187)); -#170481 = CARTESIAN_POINT('',(1.55749295167E-015,0.1822865144)); -#170482 = CARTESIAN_POINT('',(-7.010987997227E-016,0.2278300409)); -#170483 = CARTESIAN_POINT('',(2.459215994125E-015,0.27331674602)); -#170484 = CARTESIAN_POINT('',(-3.471785340859E-016,0.318743220066)); -#170485 = CARTESIAN_POINT('',(1.719283554942E-015,0.364113426255)); -#170486 = CARTESIAN_POINT('',(5.463873865317E-016,0.409436881051)); -#170487 = CARTESIAN_POINT('',(4.474559446246E-016,0.454727066523)); -#170488 = CARTESIAN_POINT('',(2.832724619794E-015,0.5)); -#170489 = CARTESIAN_POINT('',(1.423647178365E-015,0.545272933477)); -#170490 = CARTESIAN_POINT('',(1.639945776136E-015,0.590563118949)); -#170491 = CARTESIAN_POINT('',(-8.71090294816E-016,0.635886573745)); -#170492 = CARTESIAN_POINT('',(2.068709461597E-015,0.681256779934)); -#170493 = CARTESIAN_POINT('',(1.632883397003E-015,0.72668325398)); -#170494 = CARTESIAN_POINT('',(1.211183695508E-015,0.7721699591)); -#170495 = CARTESIAN_POINT('',(-6.100276863084E-018,0.8177134856)); -#170496 = CARTESIAN_POINT('',(1.941885032304E-015,0.863301251813)); -#170497 = CARTESIAN_POINT('',(6.835213458011E-016,0.908908989256)); -#170498 = CARTESIAN_POINT('',(1.849678152467E-016,0.954500792509)); -#170499 = CARTESIAN_POINT('',(-3.58291987102E-017,0.984847218355)); -#170500 = CARTESIAN_POINT('',(0.E+000,1.)); -#170501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170502 = ORIENTED_EDGE('',*,*,#170503,.F.); -#170503 = EDGE_CURVE('',#170504,#170419,#170506,.T.); -#170504 = VERTEX_POINT('',#170505); -#170505 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); -#170506 = SURFACE_CURVE('',#170507,(#170512,#170541),.PCURVE_S1.); -#170507 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170508,#170509,#170510, -#170511),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172868 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#172869 = CARTESIAN_POINT('',(4.605886458701E-016,1.515278164504E-002)); +#172870 = CARTESIAN_POINT('',(1.249869054257E-015,4.549920749135E-002)); +#172871 = CARTESIAN_POINT('',(2.200630136876E-015,9.109101074357E-002)); +#172872 = CARTESIAN_POINT('',(-1.909847672284E-015,0.136698748187)); +#172873 = CARTESIAN_POINT('',(1.55749295167E-015,0.1822865144)); +#172874 = CARTESIAN_POINT('',(-7.010987997227E-016,0.2278300409)); +#172875 = CARTESIAN_POINT('',(2.459215994125E-015,0.27331674602)); +#172876 = CARTESIAN_POINT('',(-3.471785340859E-016,0.318743220066)); +#172877 = CARTESIAN_POINT('',(1.719283554942E-015,0.364113426255)); +#172878 = CARTESIAN_POINT('',(5.463873865317E-016,0.409436881051)); +#172879 = CARTESIAN_POINT('',(4.474559446246E-016,0.454727066523)); +#172880 = CARTESIAN_POINT('',(2.832724619794E-015,0.5)); +#172881 = CARTESIAN_POINT('',(1.423647178365E-015,0.545272933477)); +#172882 = CARTESIAN_POINT('',(1.639945776136E-015,0.590563118949)); +#172883 = CARTESIAN_POINT('',(-8.71090294816E-016,0.635886573745)); +#172884 = CARTESIAN_POINT('',(2.068709461597E-015,0.681256779934)); +#172885 = CARTESIAN_POINT('',(1.632883397003E-015,0.72668325398)); +#172886 = CARTESIAN_POINT('',(1.211183695508E-015,0.7721699591)); +#172887 = CARTESIAN_POINT('',(-6.100276863084E-018,0.8177134856)); +#172888 = CARTESIAN_POINT('',(1.941885032304E-015,0.863301251813)); +#172889 = CARTESIAN_POINT('',(6.835213458011E-016,0.908908989256)); +#172890 = CARTESIAN_POINT('',(1.849678152467E-016,0.954500792509)); +#172891 = CARTESIAN_POINT('',(-3.58291987102E-017,0.984847218355)); +#172892 = CARTESIAN_POINT('',(0.E+000,1.)); +#172893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172894 = ORIENTED_EDGE('',*,*,#172895,.F.); +#172895 = EDGE_CURVE('',#172896,#172811,#172898,.T.); +#172896 = VERTEX_POINT('',#172897); +#172897 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); +#172898 = SURFACE_CURVE('',#172899,(#172904,#172933),.PCURVE_S1.); +#172899 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172900,#172901,#172902, +#172903),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170508 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); -#170509 = CARTESIAN_POINT('',(-1.200789126784,0.600864135142,1.2)); -#170510 = CARTESIAN_POINT('',(-1.224801147872,0.591106375747,1.2)); -#170511 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); -#170512 = PCURVE('',#170338,#170513); -#170513 = DEFINITIONAL_REPRESENTATION('',(#170514),#170540); -#170514 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170515,#170516,#170517, - #170518,#170519,#170520,#170521,#170522,#170523,#170524,#170525, - #170526,#170527,#170528,#170529,#170530,#170531,#170532,#170533, - #170534,#170535,#170536,#170537,#170538,#170539),.UNSPECIFIED.,.F., +#172900 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.2)); +#172901 = CARTESIAN_POINT('',(-1.200789126784,0.600864135142,1.2)); +#172902 = CARTESIAN_POINT('',(-1.224801147872,0.591106375747,1.2)); +#172903 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); +#172904 = PCURVE('',#172730,#172905); +#172905 = DEFINITIONAL_REPRESENTATION('',(#172906),#172932); +#172906 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172907,#172908,#172909, + #172910,#172911,#172912,#172913,#172914,#172915,#172916,#172917, + #172918,#172919,#172920,#172921,#172922,#172923,#172924,#172925, + #172926,#172927,#172928,#172929,#172930,#172931),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -210836,62 +213838,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170515 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170516 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#170517 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#170518 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#170519 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#170520 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#170521 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#170522 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#170523 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#170524 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#170525 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#170526 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#170527 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#170528 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#170529 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#170530 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#170531 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#170532 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#170533 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#170534 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#170535 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#170536 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#170537 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#170538 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#170539 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170541 = PCURVE('',#169987,#170542); -#170542 = DEFINITIONAL_REPRESENTATION('',(#170543),#170548); -#170543 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170544,#170545,#170546, -#170547),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172907 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172908 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#172909 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#172910 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#172911 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#172912 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#172913 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#172914 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#172915 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#172916 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#172917 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#172918 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#172919 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#172920 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#172921 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#172922 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#172923 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#172924 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#172925 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#172926 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#172927 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#172928 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#172929 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#172930 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#172931 = CARTESIAN_POINT('',(6.28318530718,1.)); +#172932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172933 = PCURVE('',#172379,#172934); +#172934 = DEFINITIONAL_REPRESENTATION('',(#172935),#172940); +#172935 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172936,#172937,#172938, +#172939),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170544 = CARTESIAN_POINT('',(-2.644271552513,1.400864135142)); -#170545 = CARTESIAN_POINT('',(-2.670789126784,1.400864135142)); -#170546 = CARTESIAN_POINT('',(-2.694801147872,1.391106375747)); -#170547 = CARTESIAN_POINT('',(-2.712953761809,1.372953761809)); -#170548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170549 = ORIENTED_EDGE('',*,*,#170550,.T.); -#170550 = EDGE_CURVE('',#170504,#170329,#170551,.T.); -#170551 = SURFACE_CURVE('',#170552,(#170557,#170586),.PCURVE_S1.); -#170552 = CIRCLE('',#170553,5.E-002); -#170553 = AXIS2_PLACEMENT_3D('',#170554,#170555,#170556); -#170554 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.15)); -#170555 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#170556 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170557 = PCURVE('',#170338,#170558); -#170558 = DEFINITIONAL_REPRESENTATION('',(#170559),#170585); -#170559 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170560,#170561,#170562, - #170563,#170564,#170565,#170566,#170567,#170568,#170569,#170570, - #170571,#170572,#170573,#170574,#170575,#170576,#170577,#170578, - #170579,#170580,#170581,#170582,#170583,#170584),.UNSPECIFIED.,.F., +#172936 = CARTESIAN_POINT('',(-2.644271552513,1.400864135142)); +#172937 = CARTESIAN_POINT('',(-2.670789126784,1.400864135142)); +#172938 = CARTESIAN_POINT('',(-2.694801147872,1.391106375747)); +#172939 = CARTESIAN_POINT('',(-2.712953761809,1.372953761809)); +#172940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172941 = ORIENTED_EDGE('',*,*,#172942,.T.); +#172942 = EDGE_CURVE('',#172896,#172721,#172943,.T.); +#172943 = SURFACE_CURVE('',#172944,(#172949,#172978),.PCURVE_S1.); +#172944 = CIRCLE('',#172945,5.E-002); +#172945 = AXIS2_PLACEMENT_3D('',#172946,#172947,#172948); +#172946 = CARTESIAN_POINT('',(-1.174271552513,0.600864135142,1.15)); +#172947 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#172948 = DIRECTION('',(0.E+000,0.E+000,1.)); +#172949 = PCURVE('',#172730,#172950); +#172950 = DEFINITIONAL_REPRESENTATION('',(#172951),#172977); +#172951 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172952,#172953,#172954, + #172955,#172956,#172957,#172958,#172959,#172960,#172961,#172962, + #172963,#172964,#172965,#172966,#172967,#172968,#172969,#172970, + #172971,#172972,#172973,#172974,#172975,#172976),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -210899,111 +213901,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#170560 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170561 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#170562 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#170563 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#170564 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#170565 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#170566 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#170567 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#170568 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#170569 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#170570 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#170571 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#170572 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#170573 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#170574 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#170575 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#170576 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#170577 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#170578 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#170579 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#170580 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#170581 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#170582 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#170583 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#170584 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170586 = PCURVE('',#170587,#170592); -#170587 = CYLINDRICAL_SURFACE('',#170588,5.E-002); -#170588 = AXIS2_PLACEMENT_3D('',#170589,#170590,#170591); -#170589 = CARTESIAN_POINT('',(1.47,0.600864135142,1.15)); -#170590 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#170591 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170592 = DEFINITIONAL_REPRESENTATION('',(#170593),#170596); -#170593 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170594,#170595), +#172952 = CARTESIAN_POINT('',(5.531305892885,1.)); +#172953 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#172954 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#172955 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#172956 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#172957 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#172958 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#172959 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#172960 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#172961 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#172962 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#172963 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#172964 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#172965 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#172966 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#172967 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#172968 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#172969 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#172970 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#172971 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#172972 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#172973 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#172974 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#172975 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#172976 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#172977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#172978 = PCURVE('',#172979,#172984); +#172979 = CYLINDRICAL_SURFACE('',#172980,5.E-002); +#172980 = AXIS2_PLACEMENT_3D('',#172981,#172982,#172983); +#172981 = CARTESIAN_POINT('',(1.47,0.600864135142,1.15)); +#172982 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#172983 = DIRECTION('',(0.E+000,0.E+000,1.)); +#172984 = DEFINITIONAL_REPRESENTATION('',(#172985),#172988); +#172985 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172986,#172987), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#170594 = CARTESIAN_POINT('',(0.E+000,2.644271552513)); -#170595 = CARTESIAN_POINT('',(1.308996938996,2.644271552513)); -#170596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#172986 = CARTESIAN_POINT('',(0.E+000,2.644271552513)); +#172987 = CARTESIAN_POINT('',(1.308996938996,2.644271552513)); +#172988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#170597 = ADVANCED_FACE('',(#170598),#170613,.T.); -#170598 = FACE_BOUND('',#170599,.T.); -#170599 = EDGE_LOOP('',(#170600,#170692,#170777,#170824)); -#170600 = ORIENTED_EDGE('',*,*,#170601,.F.); -#170601 = EDGE_CURVE('',#170602,#170604,#170606,.T.); -#170602 = VERTEX_POINT('',#170603); -#170603 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) +#172989 = ADVANCED_FACE('',(#172990),#173005,.T.); +#172990 = FACE_BOUND('',#172991,.T.); +#172991 = EDGE_LOOP('',(#172992,#173084,#173169,#173216)); +#172992 = ORIENTED_EDGE('',*,*,#172993,.F.); +#172993 = EDGE_CURVE('',#172994,#172996,#172998,.T.); +#172994 = VERTEX_POINT('',#172995); +#172995 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) ); -#170604 = VERTEX_POINT('',#170605); -#170605 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, +#172996 = VERTEX_POINT('',#172997); +#172997 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, 1.162940952255)); -#170606 = SURFACE_CURVE('',#170607,(#170612,#170658),.PCURVE_S1.); -#170607 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170608,#170609,#170610, -#170611),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#172998 = SURFACE_CURVE('',#172999,(#173004,#173050),.PCURVE_S1.); +#172999 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173000,#173001,#173002, +#173003),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.807003620809E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170608 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) +#173000 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) ); -#170609 = CARTESIAN_POINT('',(1.303243924364,0.57878608255,1.167717466) +#173001 = CARTESIAN_POINT('',(1.303243924364,0.57878608255,1.167717466) ); -#170610 = CARTESIAN_POINT('',(1.318328016991,0.543215504454, +#173002 = CARTESIAN_POINT('',(1.318328016991,0.543215504454, 1.166047546673)); -#170611 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, +#173003 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, 1.162940952255)); -#170612 = PCURVE('',#170613,#170630); -#170613 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170614,#170615,#170616,#170617) - ,(#170618,#170619,#170620,#170621) - ,(#170622,#170623,#170624,#170625) - ,(#170626,#170627,#170628,#170629 +#173004 = PCURVE('',#173005,#173022); +#173005 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#173006,#173007,#173008,#173009) + ,(#173010,#173011,#173012,#173013) + ,(#173014,#173015,#173016,#173017) + ,(#173018,#173019,#173020,#173021 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170614 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, +#173006 = CARTESIAN_POINT('',(1.319160426457,0.504271552513, 1.162940952255)); -#170615 = CARTESIAN_POINT('',(1.313513870827,0.504271552513, +#173007 = CARTESIAN_POINT('',(1.313513870827,0.504271552513, 1.184014184754)); -#170616 = CARTESIAN_POINT('',(1.292680750792,0.504271552513,1.2)); -#170617 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); -#170618 = CARTESIAN_POINT('',(1.318347764779,0.542291611921, +#173008 = CARTESIAN_POINT('',(1.292680750792,0.504271552513,1.2)); +#173009 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); +#173010 = CARTESIAN_POINT('',(1.318347764779,0.542291611921, 1.165973846926)); -#170619 = CARTESIAN_POINT('',(1.311648746428,0.540873249723, +#173011 = CARTESIAN_POINT('',(1.311648746428,0.540873249723, 1.185681523985)); -#170620 = CARTESIAN_POINT('',(1.291634122922,0.535640163951,1.2)); -#170621 = CARTESIAN_POINT('',(1.270864135142,0.530160033237,1.2)); -#170622 = CARTESIAN_POINT('',(1.302597955081,0.579432051833,1.167717466) +#173012 = CARTESIAN_POINT('',(1.291634122922,0.535640163951,1.2)); +#173013 = CARTESIAN_POINT('',(1.270864135142,0.530160033237,1.2)); +#173014 = CARTESIAN_POINT('',(1.302597955081,0.579432051833,1.167717466) ); -#170623 = CARTESIAN_POINT('',(1.296198171686,0.575737677168, +#173015 = CARTESIAN_POINT('',(1.296198171686,0.575737677168, 1.186553421368)); -#170624 = CARTESIAN_POINT('',(1.27873639183,0.565657592716,1.2)); -#170625 = CARTESIAN_POINT('',(1.260675729559,0.55523179406,1.2)); -#170626 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) +#173016 = CARTESIAN_POINT('',(1.27873639183,0.565657592716,1.2)); +#173017 = CARTESIAN_POINT('',(1.260675729559,0.55523179406,1.2)); +#173018 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) ); -#170627 = CARTESIAN_POINT('',(1.270967924427,0.600967924427, +#173019 = CARTESIAN_POINT('',(1.270967924427,0.600967924427, 1.186553421368)); -#170628 = CARTESIAN_POINT('',(1.257196992273,0.587196992273,1.2)); -#170629 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); -#170630 = DEFINITIONAL_REPRESENTATION('',(#170631),#170657); -#170631 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170632,#170633,#170634, - #170635,#170636,#170637,#170638,#170639,#170640,#170641,#170642, - #170643,#170644,#170645,#170646,#170647,#170648,#170649,#170650, - #170651,#170652,#170653,#170654,#170655,#170656),.UNSPECIFIED.,.F., +#173020 = CARTESIAN_POINT('',(1.257196992273,0.587196992273,1.2)); +#173021 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); +#173022 = DEFINITIONAL_REPRESENTATION('',(#173023),#173049); +#173023 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173024,#173025,#173026, + #173027,#173028,#173029,#173030,#173031,#173032,#173033,#173034, + #173035,#173036,#173037,#173038,#173039,#173040,#173041,#173042, + #173043,#173044,#173045,#173046,#173047,#173048),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -211012,47 +214014,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#170632 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170633 = CARTESIAN_POINT('',(6.272059551128,2.972804142315E-006)); -#170634 = CARTESIAN_POINT('',(6.249732638972,-1.037052465879E-005)); -#170635 = CARTESIAN_POINT('',(6.216039360813,-5.44648409459E-005)); -#170636 = CARTESIAN_POINT('',(6.182166930891,-8.868396576438E-005)); -#170637 = CARTESIAN_POINT('',(6.148137469616,-7.965797689818E-005)); -#170638 = CARTESIAN_POINT('',(6.113972837442,-8.226451401267E-005)); -#170639 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); -#170640 = CARTESIAN_POINT('',(6.045320300361,-8.220472162593E-005)); -#170641 = CARTESIAN_POINT('',(6.010871913477,-8.242390084209E-005)); -#170642 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); -#170643 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); -#170644 = CARTESIAN_POINT('',(5.907265074214,-8.346461190826E-005)); -#170645 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); -#170646 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); -#170647 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); -#170648 = CARTESIAN_POINT('',(5.769199593774,-8.542361087674E-005)); -#170649 = CARTESIAN_POINT('',(5.734821280548,-8.593545386252E-005)); -#170650 = CARTESIAN_POINT('',(5.700537102675,-8.687395637446E-005)); -#170651 = CARTESIAN_POINT('',(5.666367464043,-8.643221197408E-005)); -#170652 = CARTESIAN_POINT('',(5.632333796953,-9.135814826686E-005)); -#170653 = CARTESIAN_POINT('',(5.59845580442,-3.211561472994E-005)); -#170654 = CARTESIAN_POINT('',(5.564759360754,-7.920681088833E-006)); -#170655 = CARTESIAN_POINT('',(5.542431620275,5.712075556605E-008)); -#170656 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170658 = PCURVE('',#170659,#170664); -#170659 = CYLINDRICAL_SURFACE('',#170660,0.15); -#170660 = AXIS2_PLACEMENT_3D('',#170661,#170662,#170663); -#170661 = CARTESIAN_POINT('',(1.149629241148,0.479629241148, +#173024 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#173025 = CARTESIAN_POINT('',(6.272059551128,2.972804142315E-006)); +#173026 = CARTESIAN_POINT('',(6.249732638972,-1.037052465879E-005)); +#173027 = CARTESIAN_POINT('',(6.216039360813,-5.44648409459E-005)); +#173028 = CARTESIAN_POINT('',(6.182166930891,-8.868396576438E-005)); +#173029 = CARTESIAN_POINT('',(6.148137469616,-7.965797689818E-005)); +#173030 = CARTESIAN_POINT('',(6.113972837442,-8.226451401267E-005)); +#173031 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); +#173032 = CARTESIAN_POINT('',(6.045320300361,-8.220472162593E-005)); +#173033 = CARTESIAN_POINT('',(6.010871913477,-8.242390084209E-005)); +#173034 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); +#173035 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); +#173036 = CARTESIAN_POINT('',(5.907265074214,-8.346461190826E-005)); +#173037 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); +#173038 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); +#173039 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); +#173040 = CARTESIAN_POINT('',(5.769199593774,-8.542361087674E-005)); +#173041 = CARTESIAN_POINT('',(5.734821280548,-8.593545386252E-005)); +#173042 = CARTESIAN_POINT('',(5.700537102675,-8.687395637446E-005)); +#173043 = CARTESIAN_POINT('',(5.666367464043,-8.643221197408E-005)); +#173044 = CARTESIAN_POINT('',(5.632333796953,-9.135814826686E-005)); +#173045 = CARTESIAN_POINT('',(5.59845580442,-3.211561472994E-005)); +#173046 = CARTESIAN_POINT('',(5.564759360754,-7.920681088833E-006)); +#173047 = CARTESIAN_POINT('',(5.542431620275,5.712075556605E-008)); +#173048 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#173049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173050 = PCURVE('',#173051,#173056); +#173051 = CYLINDRICAL_SURFACE('',#173052,0.15); +#173052 = AXIS2_PLACEMENT_3D('',#173053,#173054,#173055); +#173053 = CARTESIAN_POINT('',(1.149629241148,0.479629241148, 1.216084453522)); -#170662 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#170663 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, +#173054 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#173055 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, -0.258819045103)); -#170664 = DEFINITIONAL_REPRESENTATION('',(#170665),#170691); -#170665 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170666,#170667,#170668, - #170669,#170670,#170671,#170672,#170673,#170674,#170675,#170676, - #170677,#170678,#170679,#170680,#170681,#170682,#170683,#170684, - #170685,#170686,#170687,#170688,#170689,#170690),.UNSPECIFIED.,.F., +#173056 = DEFINITIONAL_REPRESENTATION('',(#173057),#173083); +#173057 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173058,#173059,#173060, + #173061,#173062,#173063,#173064,#173065,#173066,#173067,#173068, + #173069,#173070,#173071,#173072,#173073,#173074,#173075,#173076, + #173077,#173078,#173079,#173080,#173081,#173082),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -211061,50 +214063,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#170666 = CARTESIAN_POINT('',(2.389713239295,0.108563747681)); -#170667 = CARTESIAN_POINT('',(2.40083884653,0.108563758968)); -#170668 = CARTESIAN_POINT('',(2.42316089641,0.108549667398)); -#170669 = CARTESIAN_POINT('',(2.456838875097,0.108485596116)); -#170670 = CARTESIAN_POINT('',(2.490694391593,0.108377944569)); -#170671 = CARTESIAN_POINT('',(2.524709252771,0.108226258353)); -#170672 = CARTESIAN_POINT('',(2.558864788568,0.108030217158)); -#170673 = CARTESIAN_POINT('',(2.593141829085,0.107789657135)); -#170674 = CARTESIAN_POINT('',(2.6275207869,0.107504570231)); -#170675 = CARTESIAN_POINT('',(2.661981715877,0.107175108049)); -#170676 = CARTESIAN_POINT('',(2.696504380341,0.106801582753)); -#170677 = CARTESIAN_POINT('',(2.731068324852,0.106384466977)); -#170678 = CARTESIAN_POINT('',(2.765652946442,0.105924392167)); -#170679 = CARTESIAN_POINT('',(2.800237568033,0.105422145525)); -#170680 = CARTESIAN_POINT('',(2.834801512544,0.104878665531)); -#170681 = CARTESIAN_POINT('',(2.869324177008,0.104295036117)); -#170682 = CARTESIAN_POINT('',(2.903785105985,0.103672479553)); -#170683 = CARTESIAN_POINT('',(2.9381640638,0.103012348166)); -#170684 = CARTESIAN_POINT('',(2.972441104317,0.102316114945)); -#170685 = CARTESIAN_POINT('',(3.006596640113,0.101585363379)); -#170686 = CARTESIAN_POINT('',(3.040611501292,0.100821775884)); -#170687 = CARTESIAN_POINT('',(3.074467017787,0.100027123884)); -#170688 = CARTESIAN_POINT('',(3.108144996475,9.920324889014E-002)); -#170689 = CARTESIAN_POINT('',(3.130467046355,9.863579967057E-002)); -#170690 = CARTESIAN_POINT('',(3.14159265359,9.834784201249E-002)); -#170691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170692 = ORIENTED_EDGE('',*,*,#170693,.T.); -#170693 = EDGE_CURVE('',#170602,#170694,#170696,.T.); -#170694 = VERTEX_POINT('',#170695); -#170695 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); -#170696 = SURFACE_CURVE('',#170697,(#170702,#170731),.PCURVE_S1.); -#170697 = CIRCLE('',#170698,5.E-002); -#170698 = AXIS2_PLACEMENT_3D('',#170699,#170700,#170701); -#170699 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.15)); -#170700 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#170701 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#170702 = PCURVE('',#170613,#170703); -#170703 = DEFINITIONAL_REPRESENTATION('',(#170704),#170730); -#170704 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170705,#170706,#170707, - #170708,#170709,#170710,#170711,#170712,#170713,#170714,#170715, - #170716,#170717,#170718,#170719,#170720,#170721,#170722,#170723, - #170724,#170725,#170726,#170727,#170728,#170729),.UNSPECIFIED.,.F., +#173058 = CARTESIAN_POINT('',(2.389713239295,0.108563747681)); +#173059 = CARTESIAN_POINT('',(2.40083884653,0.108563758968)); +#173060 = CARTESIAN_POINT('',(2.42316089641,0.108549667398)); +#173061 = CARTESIAN_POINT('',(2.456838875097,0.108485596116)); +#173062 = CARTESIAN_POINT('',(2.490694391593,0.108377944569)); +#173063 = CARTESIAN_POINT('',(2.524709252771,0.108226258353)); +#173064 = CARTESIAN_POINT('',(2.558864788568,0.108030217158)); +#173065 = CARTESIAN_POINT('',(2.593141829085,0.107789657135)); +#173066 = CARTESIAN_POINT('',(2.6275207869,0.107504570231)); +#173067 = CARTESIAN_POINT('',(2.661981715877,0.107175108049)); +#173068 = CARTESIAN_POINT('',(2.696504380341,0.106801582753)); +#173069 = CARTESIAN_POINT('',(2.731068324852,0.106384466977)); +#173070 = CARTESIAN_POINT('',(2.765652946442,0.105924392167)); +#173071 = CARTESIAN_POINT('',(2.800237568033,0.105422145525)); +#173072 = CARTESIAN_POINT('',(2.834801512544,0.104878665531)); +#173073 = CARTESIAN_POINT('',(2.869324177008,0.104295036117)); +#173074 = CARTESIAN_POINT('',(2.903785105985,0.103672479553)); +#173075 = CARTESIAN_POINT('',(2.9381640638,0.103012348166)); +#173076 = CARTESIAN_POINT('',(2.972441104317,0.102316114945)); +#173077 = CARTESIAN_POINT('',(3.006596640113,0.101585363379)); +#173078 = CARTESIAN_POINT('',(3.040611501292,0.100821775884)); +#173079 = CARTESIAN_POINT('',(3.074467017787,0.100027123884)); +#173080 = CARTESIAN_POINT('',(3.108144996475,9.920324889014E-002)); +#173081 = CARTESIAN_POINT('',(3.130467046355,9.863579967057E-002)); +#173082 = CARTESIAN_POINT('',(3.14159265359,9.834784201249E-002)); +#173083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173084 = ORIENTED_EDGE('',*,*,#173085,.T.); +#173085 = EDGE_CURVE('',#172994,#173086,#173088,.T.); +#173086 = VERTEX_POINT('',#173087); +#173087 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); +#173088 = SURFACE_CURVE('',#173089,(#173094,#173123),.PCURVE_S1.); +#173089 = CIRCLE('',#173090,5.E-002); +#173090 = AXIS2_PLACEMENT_3D('',#173091,#173092,#173093); +#173091 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.15)); +#173092 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#173093 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#173094 = PCURVE('',#173005,#173095); +#173095 = DEFINITIONAL_REPRESENTATION('',(#173096),#173122); +#173096 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173097,#173098,#173099, + #173100,#173101,#173102,#173103,#173104,#173105,#173106,#173107, + #173108,#173109,#173110,#173111,#173112,#173113,#173114,#173115, + #173116,#173117,#173118,#173119,#173120,#173121),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -211112,71 +214114,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170705 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170706 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#170707 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#170708 = CARTESIAN_POINT('',(6.28318530718,9.109101074358E-002)); -#170709 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#170710 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#170711 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#170712 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#170713 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#170714 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#170715 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#170716 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#170717 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#170718 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#170719 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#170720 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#170721 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#170722 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#170723 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#170724 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#170725 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#170726 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#170727 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#170728 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#170729 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170731 = PCURVE('',#170732,#170749); -#170732 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#170733,#170734,#170735,#170736) - ,(#170737,#170738,#170739,#170740) - ,(#170741,#170742,#170743,#170744) - ,(#170745,#170746,#170747,#170748 +#173097 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#173098 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#173099 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#173100 = CARTESIAN_POINT('',(6.28318530718,9.109101074358E-002)); +#173101 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#173102 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#173103 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#173104 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#173105 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#173106 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#173107 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#173108 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#173109 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#173110 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#173111 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#173112 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#173113 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#173114 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#173115 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#173116 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#173117 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#173118 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#173119 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#173120 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#173121 = CARTESIAN_POINT('',(6.28318530718,1.)); +#173122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173123 = PCURVE('',#173124,#173141); +#173124 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#173125,#173126,#173127,#173128) + ,(#173129,#173130,#173131,#173132) + ,(#173133,#173134,#173135,#173136) + ,(#173137,#173138,#173139,#173140 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(7.453889935838E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#170733 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) +#173125 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) ); -#170734 = CARTESIAN_POINT('',(1.270967924427,0.600967924427, +#173126 = CARTESIAN_POINT('',(1.270967924427,0.600967924427, 1.186553421368)); -#170735 = CARTESIAN_POINT('',(1.257196992273,0.587196992273,1.2)); -#170736 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); -#170737 = CARTESIAN_POINT('',(1.249432051833,0.632597955081,1.167717466) +#173127 = CARTESIAN_POINT('',(1.257196992273,0.587196992273,1.2)); +#173128 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); +#173129 = CARTESIAN_POINT('',(1.249432051833,0.632597955081,1.167717466) ); -#170738 = CARTESIAN_POINT('',(1.245737677168,0.626198171686, +#173130 = CARTESIAN_POINT('',(1.245737677168,0.626198171686, 1.186553421368)); -#170739 = CARTESIAN_POINT('',(1.235657592716,0.60873639183,1.2)); -#170740 = CARTESIAN_POINT('',(1.22523179406,0.590675729559,1.2)); -#170741 = CARTESIAN_POINT('',(1.212291611921,0.648347764779, +#173131 = CARTESIAN_POINT('',(1.235657592716,0.60873639183,1.2)); +#173132 = CARTESIAN_POINT('',(1.22523179406,0.590675729559,1.2)); +#173133 = CARTESIAN_POINT('',(1.212291611921,0.648347764779, 1.165973846926)); -#170742 = CARTESIAN_POINT('',(1.210873249723,0.641648746428, +#173134 = CARTESIAN_POINT('',(1.210873249723,0.641648746428, 1.185681523985)); -#170743 = CARTESIAN_POINT('',(1.205640163951,0.621634122922,1.2)); -#170744 = CARTESIAN_POINT('',(1.200160033237,0.600864135142,1.2)); -#170745 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, +#173135 = CARTESIAN_POINT('',(1.205640163951,0.621634122922,1.2)); +#173136 = CARTESIAN_POINT('',(1.200160033237,0.600864135142,1.2)); +#173137 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, 1.162940952255)); -#170746 = CARTESIAN_POINT('',(1.174271552513,0.643513870827, +#173138 = CARTESIAN_POINT('',(1.174271552513,0.643513870827, 1.184014184754)); -#170747 = CARTESIAN_POINT('',(1.174271552513,0.622680750792,1.2)); -#170748 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); -#170749 = DEFINITIONAL_REPRESENTATION('',(#170750),#170776); -#170750 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170751,#170752,#170753, - #170754,#170755,#170756,#170757,#170758,#170759,#170760,#170761, - #170762,#170763,#170764,#170765,#170766,#170767,#170768,#170769, - #170770,#170771,#170772,#170773,#170774,#170775),.UNSPECIFIED.,.F., +#173139 = CARTESIAN_POINT('',(1.174271552513,0.622680750792,1.2)); +#173140 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); +#173141 = DEFINITIONAL_REPRESENTATION('',(#173142),#173168); +#173142 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173143,#173144,#173145, + #173146,#173147,#173148,#173149,#173150,#173151,#173152,#173153, + #173154,#173155,#173156,#173157,#173158,#173159,#173160,#173161, + #173162,#173163,#173164,#173165,#173166,#173167),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -211184,54 +214186,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#170751 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#170752 = CARTESIAN_POINT('',(6.22515012749E-016,1.515278164504E-002)); -#170753 = CARTESIAN_POINT('',(9.523927622974E-016,4.549920749135E-002)); -#170754 = CARTESIAN_POINT('',(1.723018262017E-015,9.109101074357E-002)); -#170755 = CARTESIAN_POINT('',(2.848165730371E-015,0.136698748187)); -#170756 = CARTESIAN_POINT('',(-9.476864696325E-016,0.1822865144)); -#170757 = CARTESIAN_POINT('',(1.55757159559E-015,0.2278300409)); -#170758 = CARTESIAN_POINT('',(2.654463119772E-016,0.27331674602)); -#170759 = CARTESIAN_POINT('',(1.186636994281E-015,0.318743220066)); -#170760 = CARTESIAN_POINT('',(4.458691497233E-016,0.364113426255)); -#170761 = CARTESIAN_POINT('',(7.133125207904E-016,0.409436881051)); -#170762 = CARTESIAN_POINT('',(2.105040484675E-015,0.454727066523)); -#170763 = CARTESIAN_POINT('',(-2.027548964625E-015,0.5)); -#170764 = CARTESIAN_POINT('',(3.979220164298E-015,0.545272933477)); -#170765 = CARTESIAN_POINT('',(7.48629095535E-016,0.590563118949)); -#170766 = CARTESIAN_POINT('',(1.768882070231E-015,0.635886573745)); -#170767 = CARTESIAN_POINT('',(-1.149281833183E-015,0.681256779934)); -#170768 = CARTESIAN_POINT('',(3.511402716452E-015,0.72668325398)); -#170769 = CARTESIAN_POINT('',(1.871273250376E-015,0.7721699591)); -#170770 = CARTESIAN_POINT('',(1.392626307672E-015,0.8177134856)); -#170771 = CARTESIAN_POINT('',(2.566314655234E-015,0.863301251813)); -#170772 = CARTESIAN_POINT('',(4.626557155827E-015,0.908908989256)); -#170773 = CARTESIAN_POINT('',(1.48628024508E-015,0.954500792509)); -#170774 = CARTESIAN_POINT('',(4.661665979224E-016,0.984847218355)); -#170775 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#170776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170777 = ORIENTED_EDGE('',*,*,#170778,.F.); -#170778 = EDGE_CURVE('',#170779,#170694,#170781,.T.); -#170779 = VERTEX_POINT('',#170780); -#170780 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); -#170781 = SURFACE_CURVE('',#170782,(#170787,#170816),.PCURVE_S1.); -#170782 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170783,#170784,#170785, -#170786),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#173143 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#173144 = CARTESIAN_POINT('',(6.22515012749E-016,1.515278164504E-002)); +#173145 = CARTESIAN_POINT('',(9.523927622974E-016,4.549920749135E-002)); +#173146 = CARTESIAN_POINT('',(1.723018262017E-015,9.109101074357E-002)); +#173147 = CARTESIAN_POINT('',(2.848165730371E-015,0.136698748187)); +#173148 = CARTESIAN_POINT('',(-9.476864696325E-016,0.1822865144)); +#173149 = CARTESIAN_POINT('',(1.55757159559E-015,0.2278300409)); +#173150 = CARTESIAN_POINT('',(2.654463119772E-016,0.27331674602)); +#173151 = CARTESIAN_POINT('',(1.186636994281E-015,0.318743220066)); +#173152 = CARTESIAN_POINT('',(4.458691497233E-016,0.364113426255)); +#173153 = CARTESIAN_POINT('',(7.133125207904E-016,0.409436881051)); +#173154 = CARTESIAN_POINT('',(2.105040484675E-015,0.454727066523)); +#173155 = CARTESIAN_POINT('',(-2.027548964625E-015,0.5)); +#173156 = CARTESIAN_POINT('',(3.979220164298E-015,0.545272933477)); +#173157 = CARTESIAN_POINT('',(7.48629095535E-016,0.590563118949)); +#173158 = CARTESIAN_POINT('',(1.768882070231E-015,0.635886573745)); +#173159 = CARTESIAN_POINT('',(-1.149281833183E-015,0.681256779934)); +#173160 = CARTESIAN_POINT('',(3.511402716452E-015,0.72668325398)); +#173161 = CARTESIAN_POINT('',(1.871273250376E-015,0.7721699591)); +#173162 = CARTESIAN_POINT('',(1.392626307672E-015,0.8177134856)); +#173163 = CARTESIAN_POINT('',(2.566314655234E-015,0.863301251813)); +#173164 = CARTESIAN_POINT('',(4.626557155827E-015,0.908908989256)); +#173165 = CARTESIAN_POINT('',(1.48628024508E-015,0.954500792509)); +#173166 = CARTESIAN_POINT('',(4.661665979224E-016,0.984847218355)); +#173167 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#173168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173169 = ORIENTED_EDGE('',*,*,#173170,.F.); +#173170 = EDGE_CURVE('',#173171,#173086,#173173,.T.); +#173171 = VERTEX_POINT('',#173172); +#173172 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); +#173173 = SURFACE_CURVE('',#173174,(#173179,#173208),.PCURVE_S1.); +#173174 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173175,#173176,#173177, +#173178),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170783 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); -#170784 = CARTESIAN_POINT('',(1.270864135142,0.530789126784,1.2)); -#170785 = CARTESIAN_POINT('',(1.261106375747,0.554801147872,1.2)); -#170786 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); -#170787 = PCURVE('',#170613,#170788); -#170788 = DEFINITIONAL_REPRESENTATION('',(#170789),#170815); -#170789 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170790,#170791,#170792, - #170793,#170794,#170795,#170796,#170797,#170798,#170799,#170800, - #170801,#170802,#170803,#170804,#170805,#170806,#170807,#170808, - #170809,#170810,#170811,#170812,#170813,#170814),.UNSPECIFIED.,.F., +#173175 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.2)); +#173176 = CARTESIAN_POINT('',(1.270864135142,0.530789126784,1.2)); +#173177 = CARTESIAN_POINT('',(1.261106375747,0.554801147872,1.2)); +#173178 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); +#173179 = PCURVE('',#173005,#173180); +#173180 = DEFINITIONAL_REPRESENTATION('',(#173181),#173207); +#173181 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173182,#173183,#173184, + #173185,#173186,#173187,#173188,#173189,#173190,#173191,#173192, + #173193,#173194,#173195,#173196,#173197,#173198,#173199,#173200, + #173201,#173202,#173203,#173204,#173205,#173206),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -211239,62 +214241,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170790 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170791 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#170792 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#170793 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#170794 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#170795 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#170796 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#170797 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#170798 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#170799 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#170800 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#170801 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#170802 = CARTESIAN_POINT('',(5.907285653264,0.998577358683)); -#170803 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#170804 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#170805 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#170806 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#170807 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#170808 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#170809 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#170810 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#170811 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#170812 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#170813 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#170814 = CARTESIAN_POINT('',(6.28318530718,1.)); -#170815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170816 = PCURVE('',#169987,#170817); -#170817 = DEFINITIONAL_REPRESENTATION('',(#170818),#170823); -#170818 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#170819,#170820,#170821, -#170822),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#173182 = CARTESIAN_POINT('',(5.531305892885,1.)); +#173183 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#173184 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#173185 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#173186 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#173187 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#173188 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#173189 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#173190 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#173191 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#173192 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#173193 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#173194 = CARTESIAN_POINT('',(5.907285653264,0.998577358683)); +#173195 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#173196 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#173197 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#173198 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#173199 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#173200 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#173201 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#173202 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#173203 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#173204 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#173205 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#173206 = CARTESIAN_POINT('',(6.28318530718,1.)); +#173207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173208 = PCURVE('',#172379,#173209); +#173209 = DEFINITIONAL_REPRESENTATION('',(#173210),#173215); +#173210 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173211,#173212,#173213, +#173214),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#170819 = CARTESIAN_POINT('',(-0.199135864858,1.304271552513)); -#170820 = CARTESIAN_POINT('',(-0.199135864858,1.330789126784)); -#170821 = CARTESIAN_POINT('',(-0.208893624253,1.354801147872)); -#170822 = CARTESIAN_POINT('',(-0.227046238191,1.372953761809)); -#170823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170824 = ORIENTED_EDGE('',*,*,#170825,.F.); -#170825 = EDGE_CURVE('',#170604,#170779,#170826,.T.); -#170826 = SURFACE_CURVE('',#170827,(#170832,#170861),.PCURVE_S1.); -#170827 = CIRCLE('',#170828,5.E-002); -#170828 = AXIS2_PLACEMENT_3D('',#170829,#170830,#170831); -#170829 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.15)); -#170830 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#170831 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#170832 = PCURVE('',#170613,#170833); -#170833 = DEFINITIONAL_REPRESENTATION('',(#170834),#170860); -#170834 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170835,#170836,#170837, - #170838,#170839,#170840,#170841,#170842,#170843,#170844,#170845, - #170846,#170847,#170848,#170849,#170850,#170851,#170852,#170853, - #170854,#170855,#170856,#170857,#170858,#170859),.UNSPECIFIED.,.F., +#173211 = CARTESIAN_POINT('',(-0.199135864858,1.304271552513)); +#173212 = CARTESIAN_POINT('',(-0.199135864858,1.330789126784)); +#173213 = CARTESIAN_POINT('',(-0.208893624253,1.354801147872)); +#173214 = CARTESIAN_POINT('',(-0.227046238191,1.372953761809)); +#173215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173216 = ORIENTED_EDGE('',*,*,#173217,.F.); +#173217 = EDGE_CURVE('',#172996,#173171,#173218,.T.); +#173218 = SURFACE_CURVE('',#173219,(#173224,#173253),.PCURVE_S1.); +#173219 = CIRCLE('',#173220,5.E-002); +#173220 = AXIS2_PLACEMENT_3D('',#173221,#173222,#173223); +#173221 = CARTESIAN_POINT('',(1.270864135142,0.504271552513,1.15)); +#173222 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#173223 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173224 = PCURVE('',#173005,#173225); +#173225 = DEFINITIONAL_REPRESENTATION('',(#173226),#173252); +#173226 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173227,#173228,#173229, + #173230,#173231,#173232,#173233,#173234,#173235,#173236,#173237, + #173238,#173239,#173240,#173241,#173242,#173243,#173244,#173245, + #173246,#173247,#173248,#173249,#173250,#173251),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594, 1.892095575457,1.951595436321,2.011095297184,2.070595158048, 2.130095018911,2.189594879775,2.249094740638,2.308594601502, @@ -211302,75 +214304,75 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.606093905819,2.665593766682,2.725093627546,2.784593488409, 2.844093349273,2.903593210136,2.963093070999,3.022592931863, 3.082092792726,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#170835 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#170836 = CARTESIAN_POINT('',(5.531305884234,1.51532140276E-002)); -#170837 = CARTESIAN_POINT('',(5.531305899752,4.551530551224E-002)); -#170838 = CARTESIAN_POINT('',(5.531306102499,9.115656938683E-002)); -#170839 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#170840 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#170841 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#170842 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#170843 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#170844 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#170845 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#170846 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#170847 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#170848 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#170849 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); -#170850 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#170851 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#170852 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#170853 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#170854 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#170855 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#170856 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#170857 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#170858 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#170859 = CARTESIAN_POINT('',(5.531305892885,1.)); -#170860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170861 = PCURVE('',#170862,#170867); -#170862 = CYLINDRICAL_SURFACE('',#170863,5.E-002); -#170863 = AXIS2_PLACEMENT_3D('',#170864,#170865,#170866); -#170864 = CARTESIAN_POINT('',(1.270864135142,-0.8,1.15)); -#170865 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#170866 = DIRECTION('',(-1.,-1.355252715607E-016,0.E+000)); -#170867 = DEFINITIONAL_REPRESENTATION('',(#170868),#170871); -#170868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170869,#170870), +#173227 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#173228 = CARTESIAN_POINT('',(5.531305884234,1.51532140276E-002)); +#173229 = CARTESIAN_POINT('',(5.531305899752,4.551530551224E-002)); +#173230 = CARTESIAN_POINT('',(5.531306102499,9.115656938683E-002)); +#173231 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#173232 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#173233 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#173234 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#173235 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#173236 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#173237 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#173238 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#173239 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#173240 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#173241 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); +#173242 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#173243 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#173244 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#173245 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#173246 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#173247 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#173248 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#173249 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#173250 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#173251 = CARTESIAN_POINT('',(5.531305892885,1.)); +#173252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173253 = PCURVE('',#173254,#173259); +#173254 = CYLINDRICAL_SURFACE('',#173255,5.E-002); +#173255 = AXIS2_PLACEMENT_3D('',#173256,#173257,#173258); +#173256 = CARTESIAN_POINT('',(1.270864135142,-0.8,1.15)); +#173257 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#173258 = DIRECTION('',(-1.,-1.355252715607E-016,0.E+000)); +#173259 = DEFINITIONAL_REPRESENTATION('',(#173260),#173263); +#173260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173261,#173262), .UNSPECIFIED.,.F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#170869 = CARTESIAN_POINT('',(2.879793265791,1.304271552513)); -#170870 = CARTESIAN_POINT('',(1.570796326795,1.304271552513)); -#170871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170872 = ADVANCED_FACE('',(#170873),#170888,.F.); -#170873 = FACE_BOUND('',#170874,.F.); -#170874 = EDGE_LOOP('',(#170875,#170933,#170959,#171005)); -#170875 = ORIENTED_EDGE('',*,*,#170876,.T.); -#170876 = EDGE_CURVE('',#170877,#170879,#170881,.T.); -#170877 = VERTEX_POINT('',#170878); -#170878 = CARTESIAN_POINT('',(-1.083045018441,-0.4,1.15)); -#170879 = VERTEX_POINT('',#170880); -#170880 = CARTESIAN_POINT('',(-0.866954981559,-0.4,1.15)); -#170881 = SURFACE_CURVE('',#170882,(#170887,#170921),.PCURVE_S1.); -#170882 = CIRCLE('',#170883,0.108045018441); -#170883 = AXIS2_PLACEMENT_3D('',#170884,#170885,#170886); -#170884 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); -#170885 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170886 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170887 = PCURVE('',#170888,#170893); -#170888 = CONICAL_SURFACE('',#170889,0.15,0.698131700798); -#170889 = AXIS2_PLACEMENT_3D('',#170890,#170891,#170892); -#170890 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); -#170891 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170892 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170893 = DEFINITIONAL_REPRESENTATION('',(#170894),#170920); -#170894 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170895,#170896,#170897, - #170898,#170899,#170900,#170901,#170902,#170903,#170904,#170905, - #170906,#170907,#170908,#170909,#170910,#170911,#170912,#170913, - #170914,#170915,#170916,#170917,#170918,#170919),.UNSPECIFIED.,.F., +#173261 = CARTESIAN_POINT('',(2.879793265791,1.304271552513)); +#173262 = CARTESIAN_POINT('',(1.570796326795,1.304271552513)); +#173263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173264 = ADVANCED_FACE('',(#173265),#173280,.F.); +#173265 = FACE_BOUND('',#173266,.F.); +#173266 = EDGE_LOOP('',(#173267,#173325,#173351,#173397)); +#173267 = ORIENTED_EDGE('',*,*,#173268,.T.); +#173268 = EDGE_CURVE('',#173269,#173271,#173273,.T.); +#173269 = VERTEX_POINT('',#173270); +#173270 = CARTESIAN_POINT('',(-1.083045018441,-0.4,1.15)); +#173271 = VERTEX_POINT('',#173272); +#173272 = CARTESIAN_POINT('',(-0.866954981559,-0.4,1.15)); +#173273 = SURFACE_CURVE('',#173274,(#173279,#173313),.PCURVE_S1.); +#173274 = CIRCLE('',#173275,0.108045018441); +#173275 = AXIS2_PLACEMENT_3D('',#173276,#173277,#173278); +#173276 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); +#173277 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173278 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173279 = PCURVE('',#173280,#173285); +#173280 = CONICAL_SURFACE('',#173281,0.15,0.698131700798); +#173281 = AXIS2_PLACEMENT_3D('',#173282,#173283,#173284); +#173282 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); +#173283 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173284 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173285 = DEFINITIONAL_REPRESENTATION('',(#173286),#173312); +#173286 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173287,#173288,#173289, + #173290,#173291,#173292,#173293,#173294,#173295,#173296,#173297, + #173298,#173299,#173300,#173301,#173302,#173303,#173304,#173305, + #173306,#173307,#173308,#173309,#173310,#173311),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.284392319662,3.427191985734,3.569991651807,3.712791317879, 3.855590983951,3.998390650023,4.141190316096,4.283989982168, @@ -211378,98 +214380,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.997988312529,5.140787978601,5.283587644674,5.426387310746, 5.569186976818,5.711986642891,5.854786308963,5.997585975035, 6.140385641107,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170895 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#170896 = CARTESIAN_POINT('',(3.189192542281,-5.E-002)); -#170897 = CARTESIAN_POINT('',(3.284392319662,-5.E-002)); -#170898 = CARTESIAN_POINT('',(3.427191985734,-5.E-002)); -#170899 = CARTESIAN_POINT('',(3.569991651807,-5.E-002)); -#170900 = CARTESIAN_POINT('',(3.712791317879,-5.E-002)); -#170901 = CARTESIAN_POINT('',(3.855590983951,-5.E-002)); -#170902 = CARTESIAN_POINT('',(3.998390650023,-5.E-002)); -#170903 = CARTESIAN_POINT('',(4.141190316096,-5.E-002)); -#170904 = CARTESIAN_POINT('',(4.283989982168,-5.E-002)); -#170905 = CARTESIAN_POINT('',(4.42678964824,-5.E-002)); -#170906 = CARTESIAN_POINT('',(4.569589314312,-5.E-002)); -#170907 = CARTESIAN_POINT('',(4.712388980385,-5.E-002)); -#170908 = CARTESIAN_POINT('',(4.855188646457,-5.E-002)); -#170909 = CARTESIAN_POINT('',(4.997988312529,-5.E-002)); -#170910 = CARTESIAN_POINT('',(5.140787978601,-5.E-002)); -#170911 = CARTESIAN_POINT('',(5.283587644674,-5.E-002)); -#170912 = CARTESIAN_POINT('',(5.426387310746,-5.E-002)); -#170913 = CARTESIAN_POINT('',(5.569186976818,-5.E-002)); -#170914 = CARTESIAN_POINT('',(5.711986642891,-5.E-002)); -#170915 = CARTESIAN_POINT('',(5.854786308963,-5.E-002)); -#170916 = CARTESIAN_POINT('',(5.997585975035,-5.E-002)); -#170917 = CARTESIAN_POINT('',(6.140385641107,-5.E-002)); -#170918 = CARTESIAN_POINT('',(6.235585418489,-5.E-002)); -#170919 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#170920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170921 = PCURVE('',#170922,#170927); -#170922 = PLANE('',#170923); -#170923 = AXIS2_PLACEMENT_3D('',#170924,#170925,#170926); -#170924 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); -#170925 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170927 = DEFINITIONAL_REPRESENTATION('',(#170928),#170932); -#170928 = CIRCLE('',#170929,0.108045018441); -#170929 = AXIS2_PLACEMENT_2D('',#170930,#170931); -#170930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#170931 = DIRECTION('',(1.,0.E+000)); -#170932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170933 = ORIENTED_EDGE('',*,*,#170934,.T.); -#170934 = EDGE_CURVE('',#170879,#170935,#170937,.T.); -#170935 = VERTEX_POINT('',#170936); -#170936 = CARTESIAN_POINT('',(-0.825,-0.4,1.2)); -#170937 = SURFACE_CURVE('',#170938,(#170942,#170948),.PCURVE_S1.); -#170938 = LINE('',#170939,#170940); -#170939 = CARTESIAN_POINT('',(-0.825,-0.4,1.2)); -#170940 = VECTOR('',#170941,1.); -#170941 = DIRECTION('',(0.642787609687,0.E+000,0.766044443119)); -#170942 = PCURVE('',#170888,#170943); -#170943 = DEFINITIONAL_REPRESENTATION('',(#170944),#170947); -#170944 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170945,#170946), +#173287 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#173288 = CARTESIAN_POINT('',(3.189192542281,-5.E-002)); +#173289 = CARTESIAN_POINT('',(3.284392319662,-5.E-002)); +#173290 = CARTESIAN_POINT('',(3.427191985734,-5.E-002)); +#173291 = CARTESIAN_POINT('',(3.569991651807,-5.E-002)); +#173292 = CARTESIAN_POINT('',(3.712791317879,-5.E-002)); +#173293 = CARTESIAN_POINT('',(3.855590983951,-5.E-002)); +#173294 = CARTESIAN_POINT('',(3.998390650023,-5.E-002)); +#173295 = CARTESIAN_POINT('',(4.141190316096,-5.E-002)); +#173296 = CARTESIAN_POINT('',(4.283989982168,-5.E-002)); +#173297 = CARTESIAN_POINT('',(4.42678964824,-5.E-002)); +#173298 = CARTESIAN_POINT('',(4.569589314312,-5.E-002)); +#173299 = CARTESIAN_POINT('',(4.712388980385,-5.E-002)); +#173300 = CARTESIAN_POINT('',(4.855188646457,-5.E-002)); +#173301 = CARTESIAN_POINT('',(4.997988312529,-5.E-002)); +#173302 = CARTESIAN_POINT('',(5.140787978601,-5.E-002)); +#173303 = CARTESIAN_POINT('',(5.283587644674,-5.E-002)); +#173304 = CARTESIAN_POINT('',(5.426387310746,-5.E-002)); +#173305 = CARTESIAN_POINT('',(5.569186976818,-5.E-002)); +#173306 = CARTESIAN_POINT('',(5.711986642891,-5.E-002)); +#173307 = CARTESIAN_POINT('',(5.854786308963,-5.E-002)); +#173308 = CARTESIAN_POINT('',(5.997585975035,-5.E-002)); +#173309 = CARTESIAN_POINT('',(6.140385641107,-5.E-002)); +#173310 = CARTESIAN_POINT('',(6.235585418489,-5.E-002)); +#173311 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#173312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173313 = PCURVE('',#173314,#173319); +#173314 = PLANE('',#173315); +#173315 = AXIS2_PLACEMENT_3D('',#173316,#173317,#173318); +#173316 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); +#173317 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173319 = DEFINITIONAL_REPRESENTATION('',(#173320),#173324); +#173320 = CIRCLE('',#173321,0.108045018441); +#173321 = AXIS2_PLACEMENT_2D('',#173322,#173323); +#173322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173323 = DIRECTION('',(1.,0.E+000)); +#173324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173325 = ORIENTED_EDGE('',*,*,#173326,.T.); +#173326 = EDGE_CURVE('',#173271,#173327,#173329,.T.); +#173327 = VERTEX_POINT('',#173328); +#173328 = CARTESIAN_POINT('',(-0.825,-0.4,1.2)); +#173329 = SURFACE_CURVE('',#173330,(#173334,#173340),.PCURVE_S1.); +#173330 = LINE('',#173331,#173332); +#173331 = CARTESIAN_POINT('',(-0.825,-0.4,1.2)); +#173332 = VECTOR('',#173333,1.); +#173333 = DIRECTION('',(0.642787609687,0.E+000,0.766044443119)); +#173334 = PCURVE('',#173280,#173335); +#173335 = DEFINITIONAL_REPRESENTATION('',(#173336),#173339); +#173336 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173337,#173338), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#170945 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#170946 = CARTESIAN_POINT('',(6.28318530718,1.063100223296E-017)); -#170947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#173337 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#173338 = CARTESIAN_POINT('',(6.28318530718,1.063100223296E-017)); +#173339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#170948 = PCURVE('',#170949,#170954); -#170949 = CONICAL_SURFACE('',#170950,0.15,0.698131700798); -#170950 = AXIS2_PLACEMENT_3D('',#170951,#170952,#170953); -#170951 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); -#170952 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170953 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170954 = DEFINITIONAL_REPRESENTATION('',(#170955),#170958); -#170955 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#170956,#170957), +#173340 = PCURVE('',#173341,#173346); +#173341 = CONICAL_SURFACE('',#173342,0.15,0.698131700798); +#173342 = AXIS2_PLACEMENT_3D('',#173343,#173344,#173345); +#173343 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); +#173344 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173345 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173346 = DEFINITIONAL_REPRESENTATION('',(#173347),#173350); +#173347 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173348,#173349), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#170956 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#170957 = CARTESIAN_POINT('',(0.E+000,1.063100223296E-017)); -#170958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170959 = ORIENTED_EDGE('',*,*,#170960,.F.); -#170960 = EDGE_CURVE('',#170961,#170935,#170963,.T.); -#170961 = VERTEX_POINT('',#170962); -#170962 = CARTESIAN_POINT('',(-1.125,-0.4,1.2)); -#170963 = SURFACE_CURVE('',#170964,(#170969,#170998),.PCURVE_S1.); -#170964 = CIRCLE('',#170965,0.15); -#170965 = AXIS2_PLACEMENT_3D('',#170966,#170967,#170968); -#170966 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); -#170967 = DIRECTION('',(0.E+000,0.E+000,1.)); -#170968 = DIRECTION('',(1.,0.E+000,0.E+000)); -#170969 = PCURVE('',#170888,#170970); -#170970 = DEFINITIONAL_REPRESENTATION('',(#170971),#170997); -#170971 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#170972,#170973,#170974, - #170975,#170976,#170977,#170978,#170979,#170980,#170981,#170982, - #170983,#170984,#170985,#170986,#170987,#170988,#170989,#170990, - #170991,#170992,#170993,#170994,#170995,#170996),.UNSPECIFIED.,.F., +#173348 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#173349 = CARTESIAN_POINT('',(0.E+000,1.063100223296E-017)); +#173350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173351 = ORIENTED_EDGE('',*,*,#173352,.F.); +#173352 = EDGE_CURVE('',#173353,#173327,#173355,.T.); +#173353 = VERTEX_POINT('',#173354); +#173354 = CARTESIAN_POINT('',(-1.125,-0.4,1.2)); +#173355 = SURFACE_CURVE('',#173356,(#173361,#173390),.PCURVE_S1.); +#173356 = CIRCLE('',#173357,0.15); +#173357 = AXIS2_PLACEMENT_3D('',#173358,#173359,#173360); +#173358 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); +#173359 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173360 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173361 = PCURVE('',#173280,#173362); +#173362 = DEFINITIONAL_REPRESENTATION('',(#173363),#173389); +#173363 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173364,#173365,#173366, + #173367,#173368,#173369,#173370,#173371,#173372,#173373,#173374, + #173375,#173376,#173377,#173378,#173379,#173380,#173381,#173382, + #173383,#173384,#173385,#173386,#173387,#173388),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.284392319662,3.427191985734,3.569991651807,3.712791317879, 3.855590983951,3.998390650023,4.141190316096,4.283989982168, @@ -211477,170 +214479,170 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.997988312529,5.140787978601,5.283587644674,5.426387310746, 5.569186976818,5.711986642891,5.854786308963,5.997585975035, 6.140385641107,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#170972 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); -#170973 = CARTESIAN_POINT('',(3.189192542281,6.043763605789E-017)); -#170974 = CARTESIAN_POINT('',(3.284392319662,4.612443542099E-017)); -#170975 = CARTESIAN_POINT('',(3.427191985734,-7.559609247481E-017)); -#170976 = CARTESIAN_POINT('',(3.569991651807,3.551995779203E-017)); -#170977 = CARTESIAN_POINT('',(3.712791317879,4.13437159078E-017)); -#170978 = CARTESIAN_POINT('',(3.855590983951,3.586111584242E-017)); -#170979 = CARTESIAN_POINT('',(3.998390650023,-1.405430642837E-018)); -#170980 = CARTESIAN_POINT('',(4.141190316096,1.264334118039E-017)); -#170981 = CARTESIAN_POINT('',(4.283989982168,3.213841117583E-019)); -#170982 = CARTESIAN_POINT('',(4.42678964824,2.575066470815E-017)); -#170983 = CARTESIAN_POINT('',(4.569589314312,-5.555644051617E-017)); -#170984 = CARTESIAN_POINT('',(4.712388980385,7.16707245412E-017)); -#170985 = CARTESIAN_POINT('',(4.855188646457,-6.712302131509E-017)); -#170986 = CARTESIAN_POINT('',(4.997988312529,2.537050271619E-017)); -#170987 = CARTESIAN_POINT('',(5.140787978601,1.336857297709E-017)); -#170988 = CARTESIAN_POINT('',(5.283587644674,-3.916525228897E-017)); -#170989 = CARTESIAN_POINT('',(5.426387310746,1.544503085335E-017)); -#170990 = CARTESIAN_POINT('',(5.569186976818,2.026786332703E-017)); -#170991 = CARTESIAN_POINT('',(5.711986642891,-2.052075121202E-017)); -#170992 = CARTESIAN_POINT('',(5.854786308963,2.265611790429E-017)); -#170993 = CARTESIAN_POINT('',(5.997585975035,3.772373419599E-017)); -#170994 = CARTESIAN_POINT('',(6.140385641107,-3.337135971666E-017)); -#170995 = CARTESIAN_POINT('',(6.235585418489,-3.048556533535E-017)); -#170996 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#170997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#170998 = PCURVE('',#169987,#170999); -#170999 = DEFINITIONAL_REPRESENTATION('',(#171000),#171004); -#171000 = CIRCLE('',#171001,0.15); -#171001 = AXIS2_PLACEMENT_2D('',#171002,#171003); -#171002 = CARTESIAN_POINT('',(-2.445,0.4)); -#171003 = DIRECTION('',(1.,0.E+000)); -#171004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171005 = ORIENTED_EDGE('',*,*,#171006,.F.); -#171006 = EDGE_CURVE('',#170877,#170961,#171007,.T.); -#171007 = SURFACE_CURVE('',#171008,(#171012,#171018),.PCURVE_S1.); -#171008 = LINE('',#171009,#171010); -#171009 = CARTESIAN_POINT('',(-1.125,-0.4,1.2)); -#171010 = VECTOR('',#171011,1.); -#171011 = DIRECTION('',(-0.642787609687,7.871877887342E-017, +#173364 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); +#173365 = CARTESIAN_POINT('',(3.189192542281,6.043763605789E-017)); +#173366 = CARTESIAN_POINT('',(3.284392319662,4.612443542099E-017)); +#173367 = CARTESIAN_POINT('',(3.427191985734,-7.559609247481E-017)); +#173368 = CARTESIAN_POINT('',(3.569991651807,3.551995779203E-017)); +#173369 = CARTESIAN_POINT('',(3.712791317879,4.13437159078E-017)); +#173370 = CARTESIAN_POINT('',(3.855590983951,3.586111584242E-017)); +#173371 = CARTESIAN_POINT('',(3.998390650023,-1.405430642837E-018)); +#173372 = CARTESIAN_POINT('',(4.141190316096,1.264334118039E-017)); +#173373 = CARTESIAN_POINT('',(4.283989982168,3.213841117583E-019)); +#173374 = CARTESIAN_POINT('',(4.42678964824,2.575066470815E-017)); +#173375 = CARTESIAN_POINT('',(4.569589314312,-5.555644051617E-017)); +#173376 = CARTESIAN_POINT('',(4.712388980385,7.16707245412E-017)); +#173377 = CARTESIAN_POINT('',(4.855188646457,-6.712302131509E-017)); +#173378 = CARTESIAN_POINT('',(4.997988312529,2.537050271619E-017)); +#173379 = CARTESIAN_POINT('',(5.140787978601,1.336857297709E-017)); +#173380 = CARTESIAN_POINT('',(5.283587644674,-3.916525228897E-017)); +#173381 = CARTESIAN_POINT('',(5.426387310746,1.544503085335E-017)); +#173382 = CARTESIAN_POINT('',(5.569186976818,2.026786332703E-017)); +#173383 = CARTESIAN_POINT('',(5.711986642891,-2.052075121202E-017)); +#173384 = CARTESIAN_POINT('',(5.854786308963,2.265611790429E-017)); +#173385 = CARTESIAN_POINT('',(5.997585975035,3.772373419599E-017)); +#173386 = CARTESIAN_POINT('',(6.140385641107,-3.337135971666E-017)); +#173387 = CARTESIAN_POINT('',(6.235585418489,-3.048556533535E-017)); +#173388 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#173389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173390 = PCURVE('',#172379,#173391); +#173391 = DEFINITIONAL_REPRESENTATION('',(#173392),#173396); +#173392 = CIRCLE('',#173393,0.15); +#173393 = AXIS2_PLACEMENT_2D('',#173394,#173395); +#173394 = CARTESIAN_POINT('',(-2.445,0.4)); +#173395 = DIRECTION('',(1.,0.E+000)); +#173396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173397 = ORIENTED_EDGE('',*,*,#173398,.F.); +#173398 = EDGE_CURVE('',#173269,#173353,#173399,.T.); +#173399 = SURFACE_CURVE('',#173400,(#173404,#173410),.PCURVE_S1.); +#173400 = LINE('',#173401,#173402); +#173401 = CARTESIAN_POINT('',(-1.125,-0.4,1.2)); +#173402 = VECTOR('',#173403,1.); +#173403 = DIRECTION('',(-0.642787609687,7.871877887342E-017, 0.766044443119)); -#171012 = PCURVE('',#170888,#171013); -#171013 = DEFINITIONAL_REPRESENTATION('',(#171014),#171017); -#171014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171015,#171016), +#173404 = PCURVE('',#173280,#173405); +#173405 = DEFINITIONAL_REPRESENTATION('',(#173406),#173409); +#173406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173407,#173408), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#171015 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#171016 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); -#171017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#173407 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#173408 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); +#173409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#171018 = PCURVE('',#170949,#171019); -#171019 = DEFINITIONAL_REPRESENTATION('',(#171020),#171023); -#171020 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171021,#171022), +#173410 = PCURVE('',#173341,#173411); +#173411 = DEFINITIONAL_REPRESENTATION('',(#173412),#173415); +#173412 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173413,#173414), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#171021 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#171022 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); -#171023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171024 = ADVANCED_FACE('',(#171025),#171039,.T.); -#171025 = FACE_BOUND('',#171026,.T.); -#171026 = EDGE_LOOP('',(#171027,#171062,#171090,#171133,#171155,#171200, - #171223,#171251,#171279,#171307,#171330,#171358,#171386,#171414, - #171437,#171465,#171493,#171521,#171544,#171572)); -#171027 = ORIENTED_EDGE('',*,*,#171028,.F.); -#171028 = EDGE_CURVE('',#171029,#171031,#171033,.T.); -#171029 = VERTEX_POINT('',#171030); -#171030 = CARTESIAN_POINT('',(-1.165,0.8,0.6)); -#171031 = VERTEX_POINT('',#171032); -#171032 = CARTESIAN_POINT('',(-1.165,0.759807621135,0.75)); -#171033 = SURFACE_CURVE('',#171034,(#171038,#171050),.PCURVE_S1.); -#171034 = LINE('',#171035,#171036); -#171035 = CARTESIAN_POINT('',(-1.165,0.8,0.6)); -#171036 = VECTOR('',#171037,1.); -#171037 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171038 = PCURVE('',#171039,#171044); -#171039 = PLANE('',#171040); -#171040 = AXIS2_PLACEMENT_3D('',#171041,#171042,#171043); -#171041 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171042 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); -#171043 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171044 = DEFINITIONAL_REPRESENTATION('',(#171045),#171049); -#171045 = LINE('',#171046,#171047); -#171046 = CARTESIAN_POINT('',(-2.432133047937E-016,0.305)); -#171047 = VECTOR('',#171048,1.); -#171048 = DIRECTION('',(1.,0.E+000)); -#171049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171050 = PCURVE('',#171051,#171056); -#171051 = PLANE('',#171052); -#171052 = AXIS2_PLACEMENT_3D('',#171053,#171054,#171055); -#171053 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); -#171054 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171055 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171056 = DEFINITIONAL_REPRESENTATION('',(#171057),#171061); -#171057 = LINE('',#171058,#171059); -#171058 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171059 = VECTOR('',#171060,1.); -#171060 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171062 = ORIENTED_EDGE('',*,*,#171063,.T.); -#171063 = EDGE_CURVE('',#171029,#171064,#171066,.T.); -#171064 = VERTEX_POINT('',#171065); -#171065 = CARTESIAN_POINT('',(-1.325111126057,0.8,0.6)); -#171066 = SURFACE_CURVE('',#171067,(#171071,#171078),.PCURVE_S1.); -#171067 = LINE('',#171068,#171069); -#171068 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171069 = VECTOR('',#171070,1.); -#171070 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171071 = PCURVE('',#171039,#171072); -#171072 = DEFINITIONAL_REPRESENTATION('',(#171073),#171077); -#171073 = LINE('',#171074,#171075); -#171074 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171075 = VECTOR('',#171076,1.); -#171076 = DIRECTION('',(0.E+000,-1.)); -#171077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171078 = PCURVE('',#171079,#171084); -#171079 = PLANE('',#171080); -#171080 = AXIS2_PLACEMENT_3D('',#171081,#171082,#171083); -#171081 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171082 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); -#171083 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#171084 = DEFINITIONAL_REPRESENTATION('',(#171085),#171089); -#171085 = LINE('',#171086,#171087); -#171086 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171087 = VECTOR('',#171088,1.); -#171088 = DIRECTION('',(0.E+000,-1.)); -#171089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171090 = ORIENTED_EDGE('',*,*,#171091,.T.); -#171091 = EDGE_CURVE('',#171064,#170329,#171092,.T.); -#171092 = SURFACE_CURVE('',#171093,(#171097,#171104),.PCURVE_S1.); -#171093 = LINE('',#171094,#171095); -#171094 = CARTESIAN_POINT('',(-1.334207498814,0.809096372758, +#173413 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#173414 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); +#173415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173416 = ADVANCED_FACE('',(#173417),#173431,.T.); +#173417 = FACE_BOUND('',#173418,.T.); +#173418 = EDGE_LOOP('',(#173419,#173454,#173482,#173525,#173547,#173592, + #173615,#173643,#173671,#173699,#173722,#173750,#173778,#173806, + #173829,#173857,#173885,#173913,#173936,#173964)); +#173419 = ORIENTED_EDGE('',*,*,#173420,.F.); +#173420 = EDGE_CURVE('',#173421,#173423,#173425,.T.); +#173421 = VERTEX_POINT('',#173422); +#173422 = CARTESIAN_POINT('',(-1.165,0.8,0.6)); +#173423 = VERTEX_POINT('',#173424); +#173424 = CARTESIAN_POINT('',(-1.165,0.759807621135,0.75)); +#173425 = SURFACE_CURVE('',#173426,(#173430,#173442),.PCURVE_S1.); +#173426 = LINE('',#173427,#173428); +#173427 = CARTESIAN_POINT('',(-1.165,0.8,0.6)); +#173428 = VECTOR('',#173429,1.); +#173429 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173430 = PCURVE('',#173431,#173436); +#173431 = PLANE('',#173432); +#173432 = AXIS2_PLACEMENT_3D('',#173433,#173434,#173435); +#173433 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173434 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); +#173435 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173436 = DEFINITIONAL_REPRESENTATION('',(#173437),#173441); +#173437 = LINE('',#173438,#173439); +#173438 = CARTESIAN_POINT('',(-2.432133047937E-016,0.305)); +#173439 = VECTOR('',#173440,1.); +#173440 = DIRECTION('',(1.,0.E+000)); +#173441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173442 = PCURVE('',#173443,#173448); +#173443 = PLANE('',#173444); +#173444 = AXIS2_PLACEMENT_3D('',#173445,#173446,#173447); +#173445 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); +#173446 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173447 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173448 = DEFINITIONAL_REPRESENTATION('',(#173449),#173453); +#173449 = LINE('',#173450,#173451); +#173450 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173451 = VECTOR('',#173452,1.); +#173452 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173454 = ORIENTED_EDGE('',*,*,#173455,.T.); +#173455 = EDGE_CURVE('',#173421,#173456,#173458,.T.); +#173456 = VERTEX_POINT('',#173457); +#173457 = CARTESIAN_POINT('',(-1.325111126057,0.8,0.6)); +#173458 = SURFACE_CURVE('',#173459,(#173463,#173470),.PCURVE_S1.); +#173459 = LINE('',#173460,#173461); +#173460 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173461 = VECTOR('',#173462,1.); +#173462 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173463 = PCURVE('',#173431,#173464); +#173464 = DEFINITIONAL_REPRESENTATION('',(#173465),#173469); +#173465 = LINE('',#173466,#173467); +#173466 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173467 = VECTOR('',#173468,1.); +#173468 = DIRECTION('',(0.E+000,-1.)); +#173469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173470 = PCURVE('',#173471,#173476); +#173471 = PLANE('',#173472); +#173472 = AXIS2_PLACEMENT_3D('',#173473,#173474,#173475); +#173473 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173474 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); +#173475 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#173476 = DEFINITIONAL_REPRESENTATION('',(#173477),#173481); +#173477 = LINE('',#173478,#173479); +#173478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173479 = VECTOR('',#173480,1.); +#173480 = DIRECTION('',(0.E+000,-1.)); +#173481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173482 = ORIENTED_EDGE('',*,*,#173483,.T.); +#173483 = EDGE_CURVE('',#173456,#172721,#173484,.T.); +#173484 = SURFACE_CURVE('',#173485,(#173489,#173496),.PCURVE_S1.); +#173485 = LINE('',#173486,#173487); +#173486 = CARTESIAN_POINT('',(-1.334207498814,0.809096372758, 0.566051874704)); -#171095 = VECTOR('',#171096,1.); -#171096 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#171097 = PCURVE('',#171039,#171098); -#171098 = DEFINITIONAL_REPRESENTATION('',(#171099),#171103); -#171099 = LINE('',#171100,#171101); -#171100 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#171101 = VECTOR('',#171102,1.); -#171102 = DIRECTION('',(0.968100345886,0.250562807086)); -#171103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171104 = PCURVE('',#170384,#171105); -#171105 = DEFINITIONAL_REPRESENTATION('',(#171106),#171132); -#171106 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171107,#171108,#171109, - #171110,#171111,#171112,#171113,#171114,#171115,#171116,#171117, - #171118,#171119,#171120,#171121,#171122,#171123,#171124,#171125, - #171126,#171127,#171128,#171129,#171130,#171131),.UNSPECIFIED.,.F., +#173487 = VECTOR('',#173488,1.); +#173488 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#173489 = PCURVE('',#173431,#173490); +#173490 = DEFINITIONAL_REPRESENTATION('',(#173491),#173495); +#173491 = LINE('',#173492,#173493); +#173492 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#173493 = VECTOR('',#173494,1.); +#173494 = DIRECTION('',(0.968100345886,0.250562807086)); +#173495 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173496 = PCURVE('',#172776,#173497); +#173497 = DEFINITIONAL_REPRESENTATION('',(#173498),#173524); +#173498 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173499,#173500,#173501, + #173502,#173503,#173504,#173505,#173506,#173507,#173508,#173509, + #173510,#173511,#173512,#173513,#173514,#173515,#173516,#173517, + #173518,#173519,#173520,#173521,#173522,#173523),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,6.366753787296E-002,9.103131277518E-002, 0.118395087677,0.14575886258,0.173122637482,0.200486412384, @@ -211649,89 +214651,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.446760386504,0.474124161406,0.501487936308,0.528851711211, 0.556215486113,0.583579261015,0.610943035917,0.63830681082), .QUASI_UNIFORM_KNOTS.); -#171107 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#171108 = CARTESIAN_POINT('',(1.50375882859,-4.542502127148E-002)); -#171109 = CARTESIAN_POINT('',(1.50375882859,-6.366753787296E-002)); -#171110 = CARTESIAN_POINT('',(1.50375882859,-9.103131277518E-002)); -#171111 = CARTESIAN_POINT('',(1.50375882859,-0.118395087677)); -#171112 = CARTESIAN_POINT('',(1.50375882859,-0.14575886258)); -#171113 = CARTESIAN_POINT('',(1.50375882859,-0.173122637482)); -#171114 = CARTESIAN_POINT('',(1.50375882859,-0.200486412384)); -#171115 = CARTESIAN_POINT('',(1.50375882859,-0.227850187286)); -#171116 = CARTESIAN_POINT('',(1.50375882859,-0.255213962188)); -#171117 = CARTESIAN_POINT('',(1.50375882859,-0.282577737091)); -#171118 = CARTESIAN_POINT('',(1.50375882859,-0.309941511993)); -#171119 = CARTESIAN_POINT('',(1.50375882859,-0.337305286895)); -#171120 = CARTESIAN_POINT('',(1.50375882859,-0.364669061797)); -#171121 = CARTESIAN_POINT('',(1.50375882859,-0.3920328367)); -#171122 = CARTESIAN_POINT('',(1.50375882859,-0.419396611602)); -#171123 = CARTESIAN_POINT('',(1.50375882859,-0.446760386504)); -#171124 = CARTESIAN_POINT('',(1.50375882859,-0.474124161406)); -#171125 = CARTESIAN_POINT('',(1.50375882859,-0.501487936308)); -#171126 = CARTESIAN_POINT('',(1.50375882859,-0.528851711211)); -#171127 = CARTESIAN_POINT('',(1.50375882859,-0.556215486113)); -#171128 = CARTESIAN_POINT('',(1.50375882859,-0.583579261015)); -#171129 = CARTESIAN_POINT('',(1.50375882859,-0.610943035917)); -#171130 = CARTESIAN_POINT('',(1.50375882859,-0.629185552519)); -#171131 = CARTESIAN_POINT('',(1.50375882859,-0.63830681082)); -#171132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171133 = ORIENTED_EDGE('',*,*,#171134,.T.); -#171134 = EDGE_CURVE('',#170329,#171135,#171137,.T.); -#171135 = VERTEX_POINT('',#171136); -#171136 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, +#173499 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#173500 = CARTESIAN_POINT('',(1.50375882859,-4.542502127148E-002)); +#173501 = CARTESIAN_POINT('',(1.50375882859,-6.366753787296E-002)); +#173502 = CARTESIAN_POINT('',(1.50375882859,-9.103131277518E-002)); +#173503 = CARTESIAN_POINT('',(1.50375882859,-0.118395087677)); +#173504 = CARTESIAN_POINT('',(1.50375882859,-0.14575886258)); +#173505 = CARTESIAN_POINT('',(1.50375882859,-0.173122637482)); +#173506 = CARTESIAN_POINT('',(1.50375882859,-0.200486412384)); +#173507 = CARTESIAN_POINT('',(1.50375882859,-0.227850187286)); +#173508 = CARTESIAN_POINT('',(1.50375882859,-0.255213962188)); +#173509 = CARTESIAN_POINT('',(1.50375882859,-0.282577737091)); +#173510 = CARTESIAN_POINT('',(1.50375882859,-0.309941511993)); +#173511 = CARTESIAN_POINT('',(1.50375882859,-0.337305286895)); +#173512 = CARTESIAN_POINT('',(1.50375882859,-0.364669061797)); +#173513 = CARTESIAN_POINT('',(1.50375882859,-0.3920328367)); +#173514 = CARTESIAN_POINT('',(1.50375882859,-0.419396611602)); +#173515 = CARTESIAN_POINT('',(1.50375882859,-0.446760386504)); +#173516 = CARTESIAN_POINT('',(1.50375882859,-0.474124161406)); +#173517 = CARTESIAN_POINT('',(1.50375882859,-0.501487936308)); +#173518 = CARTESIAN_POINT('',(1.50375882859,-0.528851711211)); +#173519 = CARTESIAN_POINT('',(1.50375882859,-0.556215486113)); +#173520 = CARTESIAN_POINT('',(1.50375882859,-0.583579261015)); +#173521 = CARTESIAN_POINT('',(1.50375882859,-0.610943035917)); +#173522 = CARTESIAN_POINT('',(1.50375882859,-0.629185552519)); +#173523 = CARTESIAN_POINT('',(1.50375882859,-0.63830681082)); +#173524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173525 = ORIENTED_EDGE('',*,*,#173526,.T.); +#173526 = EDGE_CURVE('',#172721,#173527,#173529,.T.); +#173527 = VERTEX_POINT('',#173528); +#173528 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, 1.162940952255)); -#171137 = SURFACE_CURVE('',#171138,(#171142,#171149),.PCURVE_S1.); -#171138 = LINE('',#171139,#171140); -#171139 = CARTESIAN_POINT('',(1.164341610598,0.649160426457, +#173529 = SURFACE_CURVE('',#173530,(#173534,#173541),.PCURVE_S1.); +#173530 = LINE('',#173531,#173532); +#173531 = CARTESIAN_POINT('',(1.164341610598,0.649160426457, 1.162940952255)); -#171140 = VECTOR('',#171141,1.); -#171141 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171142 = PCURVE('',#171039,#171143); -#171143 = DEFINITIONAL_REPRESENTATION('',(#171144),#171148); -#171144 = LINE('',#171145,#171146); -#171145 = CARTESIAN_POINT('',(0.582799358847,2.634341610598)); -#171146 = VECTOR('',#171147,1.); -#171147 = DIRECTION('',(0.E+000,1.)); -#171148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171149 = PCURVE('',#170587,#171150); -#171150 = DEFINITIONAL_REPRESENTATION('',(#171151),#171154); -#171151 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171152,#171153), +#173532 = VECTOR('',#173533,1.); +#173533 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173534 = PCURVE('',#173431,#173535); +#173535 = DEFINITIONAL_REPRESENTATION('',(#173536),#173540); +#173536 = LINE('',#173537,#173538); +#173537 = CARTESIAN_POINT('',(0.582799358847,2.634341610598)); +#173538 = VECTOR('',#173539,1.); +#173539 = DIRECTION('',(0.E+000,1.)); +#173540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173541 = PCURVE('',#172979,#173542); +#173542 = DEFINITIONAL_REPRESENTATION('',(#173543),#173546); +#173543 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173544,#173545), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.338613163111,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#171152 = CARTESIAN_POINT('',(1.308996938996,2.644271552513)); -#171153 = CARTESIAN_POINT('',(1.308996938996,0.295728447487)); -#171154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#173544 = CARTESIAN_POINT('',(1.308996938996,2.644271552513)); +#173545 = CARTESIAN_POINT('',(1.308996938996,0.295728447487)); +#173546 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#171155 = ORIENTED_EDGE('',*,*,#171156,.T.); -#171156 = EDGE_CURVE('',#171135,#171157,#171159,.T.); -#171157 = VERTEX_POINT('',#171158); -#171158 = CARTESIAN_POINT('',(1.325111126057,0.8,0.6)); -#171159 = SURFACE_CURVE('',#171160,(#171164,#171171),.PCURVE_S1.); -#171160 = LINE('',#171161,#171162); -#171161 = CARTESIAN_POINT('',(1.149629241148,0.624518115091, +#173547 = ORIENTED_EDGE('',*,*,#173548,.T.); +#173548 = EDGE_CURVE('',#173527,#173549,#173551,.T.); +#173549 = VERTEX_POINT('',#173550); +#173550 = CARTESIAN_POINT('',(1.325111126057,0.8,0.6)); +#173551 = SURFACE_CURVE('',#173552,(#173556,#173563),.PCURVE_S1.); +#173552 = LINE('',#173553,#173554); +#173553 = CARTESIAN_POINT('',(1.149629241148,0.624518115091, 1.254907310287)); -#171162 = VECTOR('',#171163,1.); -#171163 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#171164 = PCURVE('',#171039,#171165); -#171165 = DEFINITIONAL_REPRESENTATION('',(#171166),#171170); -#171166 = LINE('',#171167,#171168); -#171167 = CARTESIAN_POINT('',(0.678009938717,2.619629241148)); -#171168 = VECTOR('',#171169,1.); -#171169 = DIRECTION('',(-0.968100345886,0.250562807086)); -#171170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171171 = PCURVE('',#170659,#171172); -#171172 = DEFINITIONAL_REPRESENTATION('',(#171173),#171199); -#171173 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171174,#171175,#171176, - #171177,#171178,#171179,#171180,#171181,#171182,#171183,#171184, - #171185,#171186,#171187,#171188,#171189,#171190,#171191,#171192, - #171193,#171194,#171195,#171196,#171197,#171198),.UNSPECIFIED.,.F., +#173554 = VECTOR('',#173555,1.); +#173555 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#173556 = PCURVE('',#173431,#173557); +#173557 = DEFINITIONAL_REPRESENTATION('',(#173558),#173562); +#173558 = LINE('',#173559,#173560); +#173559 = CARTESIAN_POINT('',(0.678009938717,2.619629241148)); +#173560 = VECTOR('',#173561,1.); +#173561 = DIRECTION('',(-0.968100345886,0.250562807086)); +#173562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173563 = PCURVE('',#173051,#173564); +#173564 = DEFINITIONAL_REPRESENTATION('',(#173565),#173591); +#173565 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173566,#173567,#173568, + #173569,#173570,#173571,#173572,#173573,#173574,#173575,#173576, + #173577,#173578,#173579,#173580,#173581,#173582,#173583,#173584, + #173585,#173586,#173587,#173588,#173589,#173590),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 9.834784201249E-002,0.125711616915,0.153075391817,0.180439166719, 0.207802941621,0.235166716524,0.262530491426,0.289894266328, @@ -211740,531 +214742,531 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.536168240448,0.56353201535,0.590895790252,0.618259565155, 0.645623340057,0.672987114959,0.700350889861), .QUASI_UNIFORM_KNOTS.); -#171174 = CARTESIAN_POINT('',(1.637833825,9.834784201249E-002)); -#171175 = CARTESIAN_POINT('',(1.637833825,0.107469100313)); -#171176 = CARTESIAN_POINT('',(1.637833825,0.125711616915)); -#171177 = CARTESIAN_POINT('',(1.637833825,0.153075391817)); -#171178 = CARTESIAN_POINT('',(1.637833825,0.180439166719)); -#171179 = CARTESIAN_POINT('',(1.637833825,0.207802941621)); -#171180 = CARTESIAN_POINT('',(1.637833825,0.235166716524)); -#171181 = CARTESIAN_POINT('',(1.637833825,0.262530491426)); -#171182 = CARTESIAN_POINT('',(1.637833825,0.289894266328)); -#171183 = CARTESIAN_POINT('',(1.637833825,0.31725804123)); -#171184 = CARTESIAN_POINT('',(1.637833825,0.344621816132)); -#171185 = CARTESIAN_POINT('',(1.637833825,0.371985591035)); -#171186 = CARTESIAN_POINT('',(1.637833825,0.399349365937)); -#171187 = CARTESIAN_POINT('',(1.637833825,0.426713140839)); -#171188 = CARTESIAN_POINT('',(1.637833825,0.454076915741)); -#171189 = CARTESIAN_POINT('',(1.637833825,0.481440690644)); -#171190 = CARTESIAN_POINT('',(1.637833825,0.508804465546)); -#171191 = CARTESIAN_POINT('',(1.637833825,0.536168240448)); -#171192 = CARTESIAN_POINT('',(1.637833825,0.56353201535)); -#171193 = CARTESIAN_POINT('',(1.637833825,0.590895790252)); -#171194 = CARTESIAN_POINT('',(1.637833825,0.618259565155)); -#171195 = CARTESIAN_POINT('',(1.637833825,0.645623340057)); -#171196 = CARTESIAN_POINT('',(1.637833825,0.672987114959)); -#171197 = CARTESIAN_POINT('',(1.637833825,0.691229631561)); -#171198 = CARTESIAN_POINT('',(1.637833825,0.700350889861)); -#171199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171200 = ORIENTED_EDGE('',*,*,#171201,.T.); -#171201 = EDGE_CURVE('',#171157,#171202,#171204,.T.); -#171202 = VERTEX_POINT('',#171203); -#171203 = CARTESIAN_POINT('',(1.125,0.8,0.6)); -#171204 = SURFACE_CURVE('',#171205,(#171209,#171216),.PCURVE_S1.); -#171205 = LINE('',#171206,#171207); -#171206 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171207 = VECTOR('',#171208,1.); -#171208 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171209 = PCURVE('',#171039,#171210); -#171210 = DEFINITIONAL_REPRESENTATION('',(#171211),#171215); -#171211 = LINE('',#171212,#171213); -#171212 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171213 = VECTOR('',#171214,1.); -#171214 = DIRECTION('',(0.E+000,-1.)); -#171215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171216 = PCURVE('',#171079,#171217); -#171217 = DEFINITIONAL_REPRESENTATION('',(#171218),#171222); -#171218 = LINE('',#171219,#171220); -#171219 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171220 = VECTOR('',#171221,1.); -#171221 = DIRECTION('',(0.E+000,-1.)); -#171222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171223 = ORIENTED_EDGE('',*,*,#171224,.T.); -#171224 = EDGE_CURVE('',#171202,#171225,#171227,.T.); -#171225 = VERTEX_POINT('',#171226); -#171226 = CARTESIAN_POINT('',(1.125,0.759807621135,0.75)); -#171227 = SURFACE_CURVE('',#171228,(#171232,#171239),.PCURVE_S1.); -#171228 = LINE('',#171229,#171230); -#171229 = CARTESIAN_POINT('',(1.125,0.8,0.6)); -#171230 = VECTOR('',#171231,1.); -#171231 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171232 = PCURVE('',#171039,#171233); -#171233 = DEFINITIONAL_REPRESENTATION('',(#171234),#171238); -#171234 = LINE('',#171235,#171236); -#171235 = CARTESIAN_POINT('',(0.E+000,2.595)); -#171236 = VECTOR('',#171237,1.); -#171237 = DIRECTION('',(1.,0.E+000)); -#171238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171239 = PCURVE('',#171240,#171245); -#171240 = PLANE('',#171241); -#171241 = AXIS2_PLACEMENT_3D('',#171242,#171243,#171244); -#171242 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); -#171243 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171244 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171245 = DEFINITIONAL_REPRESENTATION('',(#171246),#171250); -#171246 = LINE('',#171247,#171248); -#171247 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171248 = VECTOR('',#171249,1.); -#171249 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171251 = ORIENTED_EDGE('',*,*,#171252,.T.); -#171252 = EDGE_CURVE('',#171225,#171253,#171255,.T.); -#171253 = VERTEX_POINT('',#171254); -#171254 = CARTESIAN_POINT('',(0.785,0.759807621135,0.75)); -#171255 = SURFACE_CURVE('',#171256,(#171260,#171267),.PCURVE_S1.); -#171256 = LINE('',#171257,#171258); -#171257 = CARTESIAN_POINT('',(-1.47,0.759807621135,0.75)); -#171258 = VECTOR('',#171259,1.); -#171259 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171260 = PCURVE('',#171039,#171261); -#171261 = DEFINITIONAL_REPRESENTATION('',(#171262),#171266); -#171262 = LINE('',#171263,#171264); -#171263 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); -#171264 = VECTOR('',#171265,1.); -#171265 = DIRECTION('',(0.E+000,-1.)); -#171266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171267 = PCURVE('',#171268,#171273); -#171268 = PLANE('',#171269); -#171269 = AXIS2_PLACEMENT_3D('',#171270,#171271,#171272); -#171270 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); -#171271 = DIRECTION('',(0.E+000,0.E+000,1.)); -#171272 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171273 = DEFINITIONAL_REPRESENTATION('',(#171274),#171278); -#171274 = LINE('',#171275,#171276); -#171275 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); -#171276 = VECTOR('',#171277,1.); -#171277 = DIRECTION('',(-1.,0.E+000)); -#171278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171279 = ORIENTED_EDGE('',*,*,#171280,.F.); -#171280 = EDGE_CURVE('',#171281,#171253,#171283,.T.); -#171281 = VERTEX_POINT('',#171282); -#171282 = CARTESIAN_POINT('',(0.785,0.8,0.6)); -#171283 = SURFACE_CURVE('',#171284,(#171288,#171295),.PCURVE_S1.); -#171284 = LINE('',#171285,#171286); -#171285 = CARTESIAN_POINT('',(0.785,0.8,0.6)); -#171286 = VECTOR('',#171287,1.); -#171287 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171288 = PCURVE('',#171039,#171289); -#171289 = DEFINITIONAL_REPRESENTATION('',(#171290),#171294); -#171290 = LINE('',#171291,#171292); -#171291 = CARTESIAN_POINT('',(0.E+000,2.255)); -#171292 = VECTOR('',#171293,1.); -#171293 = DIRECTION('',(1.,0.E+000)); -#171294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171295 = PCURVE('',#171296,#171301); -#171296 = PLANE('',#171297); -#171297 = AXIS2_PLACEMENT_3D('',#171298,#171299,#171300); -#171298 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); -#171299 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171300 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171301 = DEFINITIONAL_REPRESENTATION('',(#171302),#171306); -#171302 = LINE('',#171303,#171304); -#171303 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171304 = VECTOR('',#171305,1.); -#171305 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171307 = ORIENTED_EDGE('',*,*,#171308,.T.); -#171308 = EDGE_CURVE('',#171281,#171309,#171311,.T.); -#171309 = VERTEX_POINT('',#171310); -#171310 = CARTESIAN_POINT('',(0.475,0.8,0.6)); -#171311 = SURFACE_CURVE('',#171312,(#171316,#171323),.PCURVE_S1.); -#171312 = LINE('',#171313,#171314); -#171313 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171314 = VECTOR('',#171315,1.); -#171315 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171316 = PCURVE('',#171039,#171317); -#171317 = DEFINITIONAL_REPRESENTATION('',(#171318),#171322); -#171318 = LINE('',#171319,#171320); -#171319 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171320 = VECTOR('',#171321,1.); -#171321 = DIRECTION('',(0.E+000,-1.)); -#171322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171323 = PCURVE('',#171079,#171324); -#171324 = DEFINITIONAL_REPRESENTATION('',(#171325),#171329); -#171325 = LINE('',#171326,#171327); -#171326 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171327 = VECTOR('',#171328,1.); -#171328 = DIRECTION('',(0.E+000,-1.)); -#171329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171330 = ORIENTED_EDGE('',*,*,#171331,.T.); -#171331 = EDGE_CURVE('',#171309,#171332,#171334,.T.); -#171332 = VERTEX_POINT('',#171333); -#171333 = CARTESIAN_POINT('',(0.475,0.759807621135,0.75)); -#171334 = SURFACE_CURVE('',#171335,(#171339,#171346),.PCURVE_S1.); -#171335 = LINE('',#171336,#171337); -#171336 = CARTESIAN_POINT('',(0.475,0.8,0.6)); -#171337 = VECTOR('',#171338,1.); -#171338 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171339 = PCURVE('',#171039,#171340); -#171340 = DEFINITIONAL_REPRESENTATION('',(#171341),#171345); -#171341 = LINE('',#171342,#171343); -#171342 = CARTESIAN_POINT('',(-1.072393092426E-016,1.945)); -#171343 = VECTOR('',#171344,1.); -#171344 = DIRECTION('',(1.,0.E+000)); -#171345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171346 = PCURVE('',#171347,#171352); -#171347 = PLANE('',#171348); -#171348 = AXIS2_PLACEMENT_3D('',#171349,#171350,#171351); -#171349 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); -#171350 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171351 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171352 = DEFINITIONAL_REPRESENTATION('',(#171353),#171357); -#171353 = LINE('',#171354,#171355); -#171354 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171355 = VECTOR('',#171356,1.); -#171356 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171358 = ORIENTED_EDGE('',*,*,#171359,.T.); -#171359 = EDGE_CURVE('',#171332,#171360,#171362,.T.); -#171360 = VERTEX_POINT('',#171361); -#171361 = CARTESIAN_POINT('',(0.135,0.759807621135,0.75)); -#171362 = SURFACE_CURVE('',#171363,(#171367,#171374),.PCURVE_S1.); -#171363 = LINE('',#171364,#171365); -#171364 = CARTESIAN_POINT('',(-2.12,0.759807621135,0.75)); -#171365 = VECTOR('',#171366,1.); -#171366 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171367 = PCURVE('',#171039,#171368); -#171368 = DEFINITIONAL_REPRESENTATION('',(#171369),#171373); -#171369 = LINE('',#171370,#171371); -#171370 = CARTESIAN_POINT('',(0.155291427062,-0.65)); -#171371 = VECTOR('',#171372,1.); -#171372 = DIRECTION('',(0.E+000,-1.)); -#171373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171374 = PCURVE('',#171375,#171380); -#171375 = PLANE('',#171376); -#171376 = AXIS2_PLACEMENT_3D('',#171377,#171378,#171379); -#171377 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); -#171378 = DIRECTION('',(0.E+000,0.E+000,1.)); -#171379 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171380 = DEFINITIONAL_REPRESENTATION('',(#171381),#171385); -#171381 = LINE('',#171382,#171383); -#171382 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); -#171383 = VECTOR('',#171384,1.); -#171384 = DIRECTION('',(-1.,0.E+000)); -#171385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171386 = ORIENTED_EDGE('',*,*,#171387,.F.); -#171387 = EDGE_CURVE('',#171388,#171360,#171390,.T.); -#171388 = VERTEX_POINT('',#171389); -#171389 = CARTESIAN_POINT('',(0.135,0.8,0.6)); -#171390 = SURFACE_CURVE('',#171391,(#171395,#171402),.PCURVE_S1.); -#171391 = LINE('',#171392,#171393); -#171392 = CARTESIAN_POINT('',(0.135,0.8,0.6)); -#171393 = VECTOR('',#171394,1.); -#171394 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171395 = PCURVE('',#171039,#171396); -#171396 = DEFINITIONAL_REPRESENTATION('',(#171397),#171401); -#171397 = LINE('',#171398,#171399); -#171398 = CARTESIAN_POINT('',(-1.072393092426E-016,1.605)); -#171399 = VECTOR('',#171400,1.); -#171400 = DIRECTION('',(1.,0.E+000)); -#171401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171402 = PCURVE('',#171403,#171408); -#171403 = PLANE('',#171404); -#171404 = AXIS2_PLACEMENT_3D('',#171405,#171406,#171407); -#171405 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); -#171406 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171407 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171408 = DEFINITIONAL_REPRESENTATION('',(#171409),#171413); -#171409 = LINE('',#171410,#171411); -#171410 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171411 = VECTOR('',#171412,1.); -#171412 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171413 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171414 = ORIENTED_EDGE('',*,*,#171415,.T.); -#171415 = EDGE_CURVE('',#171388,#171416,#171418,.T.); -#171416 = VERTEX_POINT('',#171417); -#171417 = CARTESIAN_POINT('',(-0.175,0.8,0.6)); -#171418 = SURFACE_CURVE('',#171419,(#171423,#171430),.PCURVE_S1.); -#171419 = LINE('',#171420,#171421); -#171420 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171421 = VECTOR('',#171422,1.); -#171422 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171423 = PCURVE('',#171039,#171424); -#171424 = DEFINITIONAL_REPRESENTATION('',(#171425),#171429); -#171425 = LINE('',#171426,#171427); -#171426 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171427 = VECTOR('',#171428,1.); -#171428 = DIRECTION('',(0.E+000,-1.)); -#171429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171430 = PCURVE('',#171079,#171431); -#171431 = DEFINITIONAL_REPRESENTATION('',(#171432),#171436); -#171432 = LINE('',#171433,#171434); -#171433 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171434 = VECTOR('',#171435,1.); -#171435 = DIRECTION('',(0.E+000,-1.)); -#171436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171437 = ORIENTED_EDGE('',*,*,#171438,.T.); -#171438 = EDGE_CURVE('',#171416,#171439,#171441,.T.); -#171439 = VERTEX_POINT('',#171440); -#171440 = CARTESIAN_POINT('',(-0.175,0.759807621135,0.75)); -#171441 = SURFACE_CURVE('',#171442,(#171446,#171453),.PCURVE_S1.); -#171442 = LINE('',#171443,#171444); -#171443 = CARTESIAN_POINT('',(-0.175,0.8,0.6)); -#171444 = VECTOR('',#171445,1.); -#171445 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171446 = PCURVE('',#171039,#171447); -#171447 = DEFINITIONAL_REPRESENTATION('',(#171448),#171452); -#171448 = LINE('',#171449,#171450); -#171449 = CARTESIAN_POINT('',(-1.072393092426E-016,1.295)); -#171450 = VECTOR('',#171451,1.); -#171451 = DIRECTION('',(1.,0.E+000)); -#171452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171453 = PCURVE('',#171454,#171459); -#171454 = PLANE('',#171455); -#171455 = AXIS2_PLACEMENT_3D('',#171456,#171457,#171458); -#171456 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); -#171457 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171458 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171459 = DEFINITIONAL_REPRESENTATION('',(#171460),#171464); -#171460 = LINE('',#171461,#171462); -#171461 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171462 = VECTOR('',#171463,1.); -#171463 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171465 = ORIENTED_EDGE('',*,*,#171466,.T.); -#171466 = EDGE_CURVE('',#171439,#171467,#171469,.T.); -#171467 = VERTEX_POINT('',#171468); -#171468 = CARTESIAN_POINT('',(-0.515,0.759807621135,0.75)); -#171469 = SURFACE_CURVE('',#171470,(#171474,#171481),.PCURVE_S1.); -#171470 = LINE('',#171471,#171472); -#171471 = CARTESIAN_POINT('',(-2.77,0.759807621135,0.75)); -#171472 = VECTOR('',#171473,1.); -#171473 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171474 = PCURVE('',#171039,#171475); -#171475 = DEFINITIONAL_REPRESENTATION('',(#171476),#171480); -#171476 = LINE('',#171477,#171478); -#171477 = CARTESIAN_POINT('',(0.155291427062,-1.3)); -#171478 = VECTOR('',#171479,1.); -#171479 = DIRECTION('',(0.E+000,-1.)); -#171480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171481 = PCURVE('',#171482,#171487); -#171482 = PLANE('',#171483); -#171483 = AXIS2_PLACEMENT_3D('',#171484,#171485,#171486); -#171484 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); -#171485 = DIRECTION('',(0.E+000,0.E+000,1.)); -#171486 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171487 = DEFINITIONAL_REPRESENTATION('',(#171488),#171492); -#171488 = LINE('',#171489,#171490); -#171489 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); -#171490 = VECTOR('',#171491,1.); -#171491 = DIRECTION('',(-1.,0.E+000)); -#171492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171493 = ORIENTED_EDGE('',*,*,#171494,.F.); -#171494 = EDGE_CURVE('',#171495,#171467,#171497,.T.); -#171495 = VERTEX_POINT('',#171496); -#171496 = CARTESIAN_POINT('',(-0.515,0.8,0.6)); -#171497 = SURFACE_CURVE('',#171498,(#171502,#171509),.PCURVE_S1.); -#171498 = LINE('',#171499,#171500); -#171499 = CARTESIAN_POINT('',(-0.515,0.8,0.6)); -#171500 = VECTOR('',#171501,1.); -#171501 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171502 = PCURVE('',#171039,#171503); -#171503 = DEFINITIONAL_REPRESENTATION('',(#171504),#171508); -#171504 = LINE('',#171505,#171506); -#171505 = CARTESIAN_POINT('',(-1.072393092426E-016,0.955)); -#171506 = VECTOR('',#171507,1.); -#171507 = DIRECTION('',(1.,0.E+000)); -#171508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171509 = PCURVE('',#171510,#171515); -#171510 = PLANE('',#171511); -#171511 = AXIS2_PLACEMENT_3D('',#171512,#171513,#171514); -#171512 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); -#171513 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171514 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171515 = DEFINITIONAL_REPRESENTATION('',(#171516),#171520); -#171516 = LINE('',#171517,#171518); -#171517 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171518 = VECTOR('',#171519,1.); -#171519 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171521 = ORIENTED_EDGE('',*,*,#171522,.T.); -#171522 = EDGE_CURVE('',#171495,#171523,#171525,.T.); -#171523 = VERTEX_POINT('',#171524); -#171524 = CARTESIAN_POINT('',(-0.825,0.8,0.6)); -#171525 = SURFACE_CURVE('',#171526,(#171530,#171537),.PCURVE_S1.); -#171526 = LINE('',#171527,#171528); -#171527 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#171528 = VECTOR('',#171529,1.); -#171529 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171530 = PCURVE('',#171039,#171531); -#171531 = DEFINITIONAL_REPRESENTATION('',(#171532),#171536); -#171532 = LINE('',#171533,#171534); -#171533 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171534 = VECTOR('',#171535,1.); -#171535 = DIRECTION('',(0.E+000,-1.)); -#171536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171537 = PCURVE('',#171079,#171538); -#171538 = DEFINITIONAL_REPRESENTATION('',(#171539),#171543); -#171539 = LINE('',#171540,#171541); -#171540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171541 = VECTOR('',#171542,1.); -#171542 = DIRECTION('',(0.E+000,-1.)); -#171543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171544 = ORIENTED_EDGE('',*,*,#171545,.T.); -#171545 = EDGE_CURVE('',#171523,#171546,#171548,.T.); -#171546 = VERTEX_POINT('',#171547); -#171547 = CARTESIAN_POINT('',(-0.825,0.759807621135,0.75)); -#171548 = SURFACE_CURVE('',#171549,(#171553,#171560),.PCURVE_S1.); -#171549 = LINE('',#171550,#171551); -#171550 = CARTESIAN_POINT('',(-0.825,0.8,0.6)); -#171551 = VECTOR('',#171552,1.); -#171552 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#171553 = PCURVE('',#171039,#171554); -#171554 = DEFINITIONAL_REPRESENTATION('',(#171555),#171559); -#171555 = LINE('',#171556,#171557); -#171556 = CARTESIAN_POINT('',(-2.432133047937E-016,0.645)); -#171557 = VECTOR('',#171558,1.); -#171558 = DIRECTION('',(1.,0.E+000)); -#171559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171560 = PCURVE('',#171561,#171566); -#171561 = PLANE('',#171562); -#171562 = AXIS2_PLACEMENT_3D('',#171563,#171564,#171565); -#171563 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); -#171564 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171565 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171566 = DEFINITIONAL_REPRESENTATION('',(#171567),#171571); -#171567 = LINE('',#171568,#171569); -#171568 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); -#171569 = VECTOR('',#171570,1.); -#171570 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#171571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171572 = ORIENTED_EDGE('',*,*,#171573,.T.); -#171573 = EDGE_CURVE('',#171546,#171031,#171574,.T.); -#171574 = SURFACE_CURVE('',#171575,(#171579,#171586),.PCURVE_S1.); -#171575 = LINE('',#171576,#171577); -#171576 = CARTESIAN_POINT('',(-3.42,0.759807621135,0.75)); -#171577 = VECTOR('',#171578,1.); -#171578 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171579 = PCURVE('',#171039,#171580); -#171580 = DEFINITIONAL_REPRESENTATION('',(#171581),#171585); -#171581 = LINE('',#171582,#171583); -#171582 = CARTESIAN_POINT('',(0.155291427062,-1.95)); -#171583 = VECTOR('',#171584,1.); -#171584 = DIRECTION('',(0.E+000,-1.)); -#171585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171586 = PCURVE('',#171587,#171592); -#171587 = PLANE('',#171588); -#171588 = AXIS2_PLACEMENT_3D('',#171589,#171590,#171591); -#171589 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); -#171590 = DIRECTION('',(0.E+000,0.E+000,1.)); -#171591 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171592 = DEFINITIONAL_REPRESENTATION('',(#171593),#171597); -#171593 = LINE('',#171594,#171595); -#171594 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); -#171595 = VECTOR('',#171596,1.); -#171596 = DIRECTION('',(-1.,0.E+000)); -#171597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#173566 = CARTESIAN_POINT('',(1.637833825,9.834784201249E-002)); +#173567 = CARTESIAN_POINT('',(1.637833825,0.107469100313)); +#173568 = CARTESIAN_POINT('',(1.637833825,0.125711616915)); +#173569 = CARTESIAN_POINT('',(1.637833825,0.153075391817)); +#173570 = CARTESIAN_POINT('',(1.637833825,0.180439166719)); +#173571 = CARTESIAN_POINT('',(1.637833825,0.207802941621)); +#173572 = CARTESIAN_POINT('',(1.637833825,0.235166716524)); +#173573 = CARTESIAN_POINT('',(1.637833825,0.262530491426)); +#173574 = CARTESIAN_POINT('',(1.637833825,0.289894266328)); +#173575 = CARTESIAN_POINT('',(1.637833825,0.31725804123)); +#173576 = CARTESIAN_POINT('',(1.637833825,0.344621816132)); +#173577 = CARTESIAN_POINT('',(1.637833825,0.371985591035)); +#173578 = CARTESIAN_POINT('',(1.637833825,0.399349365937)); +#173579 = CARTESIAN_POINT('',(1.637833825,0.426713140839)); +#173580 = CARTESIAN_POINT('',(1.637833825,0.454076915741)); +#173581 = CARTESIAN_POINT('',(1.637833825,0.481440690644)); +#173582 = CARTESIAN_POINT('',(1.637833825,0.508804465546)); +#173583 = CARTESIAN_POINT('',(1.637833825,0.536168240448)); +#173584 = CARTESIAN_POINT('',(1.637833825,0.56353201535)); +#173585 = CARTESIAN_POINT('',(1.637833825,0.590895790252)); +#173586 = CARTESIAN_POINT('',(1.637833825,0.618259565155)); +#173587 = CARTESIAN_POINT('',(1.637833825,0.645623340057)); +#173588 = CARTESIAN_POINT('',(1.637833825,0.672987114959)); +#173589 = CARTESIAN_POINT('',(1.637833825,0.691229631561)); +#173590 = CARTESIAN_POINT('',(1.637833825,0.700350889861)); +#173591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173592 = ORIENTED_EDGE('',*,*,#173593,.T.); +#173593 = EDGE_CURVE('',#173549,#173594,#173596,.T.); +#173594 = VERTEX_POINT('',#173595); +#173595 = CARTESIAN_POINT('',(1.125,0.8,0.6)); +#173596 = SURFACE_CURVE('',#173597,(#173601,#173608),.PCURVE_S1.); +#173597 = LINE('',#173598,#173599); +#173598 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173599 = VECTOR('',#173600,1.); +#173600 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173601 = PCURVE('',#173431,#173602); +#173602 = DEFINITIONAL_REPRESENTATION('',(#173603),#173607); +#173603 = LINE('',#173604,#173605); +#173604 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173605 = VECTOR('',#173606,1.); +#173606 = DIRECTION('',(0.E+000,-1.)); +#173607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173608 = PCURVE('',#173471,#173609); +#173609 = DEFINITIONAL_REPRESENTATION('',(#173610),#173614); +#173610 = LINE('',#173611,#173612); +#173611 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173612 = VECTOR('',#173613,1.); +#173613 = DIRECTION('',(0.E+000,-1.)); +#173614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173615 = ORIENTED_EDGE('',*,*,#173616,.T.); +#173616 = EDGE_CURVE('',#173594,#173617,#173619,.T.); +#173617 = VERTEX_POINT('',#173618); +#173618 = CARTESIAN_POINT('',(1.125,0.759807621135,0.75)); +#173619 = SURFACE_CURVE('',#173620,(#173624,#173631),.PCURVE_S1.); +#173620 = LINE('',#173621,#173622); +#173621 = CARTESIAN_POINT('',(1.125,0.8,0.6)); +#173622 = VECTOR('',#173623,1.); +#173623 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173624 = PCURVE('',#173431,#173625); +#173625 = DEFINITIONAL_REPRESENTATION('',(#173626),#173630); +#173626 = LINE('',#173627,#173628); +#173627 = CARTESIAN_POINT('',(0.E+000,2.595)); +#173628 = VECTOR('',#173629,1.); +#173629 = DIRECTION('',(1.,0.E+000)); +#173630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173631 = PCURVE('',#173632,#173637); +#173632 = PLANE('',#173633); +#173633 = AXIS2_PLACEMENT_3D('',#173634,#173635,#173636); +#173634 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); +#173635 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173636 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173637 = DEFINITIONAL_REPRESENTATION('',(#173638),#173642); +#173638 = LINE('',#173639,#173640); +#173639 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173640 = VECTOR('',#173641,1.); +#173641 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173643 = ORIENTED_EDGE('',*,*,#173644,.T.); +#173644 = EDGE_CURVE('',#173617,#173645,#173647,.T.); +#173645 = VERTEX_POINT('',#173646); +#173646 = CARTESIAN_POINT('',(0.785,0.759807621135,0.75)); +#173647 = SURFACE_CURVE('',#173648,(#173652,#173659),.PCURVE_S1.); +#173648 = LINE('',#173649,#173650); +#173649 = CARTESIAN_POINT('',(-1.47,0.759807621135,0.75)); +#173650 = VECTOR('',#173651,1.); +#173651 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173652 = PCURVE('',#173431,#173653); +#173653 = DEFINITIONAL_REPRESENTATION('',(#173654),#173658); +#173654 = LINE('',#173655,#173656); +#173655 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); +#173656 = VECTOR('',#173657,1.); +#173657 = DIRECTION('',(0.E+000,-1.)); +#173658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173659 = PCURVE('',#173660,#173665); +#173660 = PLANE('',#173661); +#173661 = AXIS2_PLACEMENT_3D('',#173662,#173663,#173664); +#173662 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); +#173663 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173664 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173665 = DEFINITIONAL_REPRESENTATION('',(#173666),#173670); +#173666 = LINE('',#173667,#173668); +#173667 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); +#173668 = VECTOR('',#173669,1.); +#173669 = DIRECTION('',(-1.,0.E+000)); +#173670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173671 = ORIENTED_EDGE('',*,*,#173672,.F.); +#173672 = EDGE_CURVE('',#173673,#173645,#173675,.T.); +#173673 = VERTEX_POINT('',#173674); +#173674 = CARTESIAN_POINT('',(0.785,0.8,0.6)); +#173675 = SURFACE_CURVE('',#173676,(#173680,#173687),.PCURVE_S1.); +#173676 = LINE('',#173677,#173678); +#173677 = CARTESIAN_POINT('',(0.785,0.8,0.6)); +#173678 = VECTOR('',#173679,1.); +#173679 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173680 = PCURVE('',#173431,#173681); +#173681 = DEFINITIONAL_REPRESENTATION('',(#173682),#173686); +#173682 = LINE('',#173683,#173684); +#173683 = CARTESIAN_POINT('',(0.E+000,2.255)); +#173684 = VECTOR('',#173685,1.); +#173685 = DIRECTION('',(1.,0.E+000)); +#173686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173687 = PCURVE('',#173688,#173693); +#173688 = PLANE('',#173689); +#173689 = AXIS2_PLACEMENT_3D('',#173690,#173691,#173692); +#173690 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); +#173691 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173692 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173693 = DEFINITIONAL_REPRESENTATION('',(#173694),#173698); +#173694 = LINE('',#173695,#173696); +#173695 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173696 = VECTOR('',#173697,1.); +#173697 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173699 = ORIENTED_EDGE('',*,*,#173700,.T.); +#173700 = EDGE_CURVE('',#173673,#173701,#173703,.T.); +#173701 = VERTEX_POINT('',#173702); +#173702 = CARTESIAN_POINT('',(0.475,0.8,0.6)); +#173703 = SURFACE_CURVE('',#173704,(#173708,#173715),.PCURVE_S1.); +#173704 = LINE('',#173705,#173706); +#173705 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173706 = VECTOR('',#173707,1.); +#173707 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173708 = PCURVE('',#173431,#173709); +#173709 = DEFINITIONAL_REPRESENTATION('',(#173710),#173714); +#173710 = LINE('',#173711,#173712); +#173711 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173712 = VECTOR('',#173713,1.); +#173713 = DIRECTION('',(0.E+000,-1.)); +#173714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173715 = PCURVE('',#173471,#173716); +#173716 = DEFINITIONAL_REPRESENTATION('',(#173717),#173721); +#173717 = LINE('',#173718,#173719); +#173718 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173719 = VECTOR('',#173720,1.); +#173720 = DIRECTION('',(0.E+000,-1.)); +#173721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173722 = ORIENTED_EDGE('',*,*,#173723,.T.); +#173723 = EDGE_CURVE('',#173701,#173724,#173726,.T.); +#173724 = VERTEX_POINT('',#173725); +#173725 = CARTESIAN_POINT('',(0.475,0.759807621135,0.75)); +#173726 = SURFACE_CURVE('',#173727,(#173731,#173738),.PCURVE_S1.); +#173727 = LINE('',#173728,#173729); +#173728 = CARTESIAN_POINT('',(0.475,0.8,0.6)); +#173729 = VECTOR('',#173730,1.); +#173730 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173731 = PCURVE('',#173431,#173732); +#173732 = DEFINITIONAL_REPRESENTATION('',(#173733),#173737); +#173733 = LINE('',#173734,#173735); +#173734 = CARTESIAN_POINT('',(-1.072393092426E-016,1.945)); +#173735 = VECTOR('',#173736,1.); +#173736 = DIRECTION('',(1.,0.E+000)); +#173737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173738 = PCURVE('',#173739,#173744); +#173739 = PLANE('',#173740); +#173740 = AXIS2_PLACEMENT_3D('',#173741,#173742,#173743); +#173741 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); +#173742 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173743 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173744 = DEFINITIONAL_REPRESENTATION('',(#173745),#173749); +#173745 = LINE('',#173746,#173747); +#173746 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173747 = VECTOR('',#173748,1.); +#173748 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173749 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173750 = ORIENTED_EDGE('',*,*,#173751,.T.); +#173751 = EDGE_CURVE('',#173724,#173752,#173754,.T.); +#173752 = VERTEX_POINT('',#173753); +#173753 = CARTESIAN_POINT('',(0.135,0.759807621135,0.75)); +#173754 = SURFACE_CURVE('',#173755,(#173759,#173766),.PCURVE_S1.); +#173755 = LINE('',#173756,#173757); +#173756 = CARTESIAN_POINT('',(-2.12,0.759807621135,0.75)); +#173757 = VECTOR('',#173758,1.); +#173758 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173759 = PCURVE('',#173431,#173760); +#173760 = DEFINITIONAL_REPRESENTATION('',(#173761),#173765); +#173761 = LINE('',#173762,#173763); +#173762 = CARTESIAN_POINT('',(0.155291427062,-0.65)); +#173763 = VECTOR('',#173764,1.); +#173764 = DIRECTION('',(0.E+000,-1.)); +#173765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173766 = PCURVE('',#173767,#173772); +#173767 = PLANE('',#173768); +#173768 = AXIS2_PLACEMENT_3D('',#173769,#173770,#173771); +#173769 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); +#173770 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173771 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173772 = DEFINITIONAL_REPRESENTATION('',(#173773),#173777); +#173773 = LINE('',#173774,#173775); +#173774 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); +#173775 = VECTOR('',#173776,1.); +#173776 = DIRECTION('',(-1.,0.E+000)); +#173777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173778 = ORIENTED_EDGE('',*,*,#173779,.F.); +#173779 = EDGE_CURVE('',#173780,#173752,#173782,.T.); +#173780 = VERTEX_POINT('',#173781); +#173781 = CARTESIAN_POINT('',(0.135,0.8,0.6)); +#173782 = SURFACE_CURVE('',#173783,(#173787,#173794),.PCURVE_S1.); +#173783 = LINE('',#173784,#173785); +#173784 = CARTESIAN_POINT('',(0.135,0.8,0.6)); +#173785 = VECTOR('',#173786,1.); +#173786 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173787 = PCURVE('',#173431,#173788); +#173788 = DEFINITIONAL_REPRESENTATION('',(#173789),#173793); +#173789 = LINE('',#173790,#173791); +#173790 = CARTESIAN_POINT('',(-1.072393092426E-016,1.605)); +#173791 = VECTOR('',#173792,1.); +#173792 = DIRECTION('',(1.,0.E+000)); +#173793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173794 = PCURVE('',#173795,#173800); +#173795 = PLANE('',#173796); +#173796 = AXIS2_PLACEMENT_3D('',#173797,#173798,#173799); +#173797 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); +#173798 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173799 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173800 = DEFINITIONAL_REPRESENTATION('',(#173801),#173805); +#173801 = LINE('',#173802,#173803); +#173802 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173803 = VECTOR('',#173804,1.); +#173804 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173806 = ORIENTED_EDGE('',*,*,#173807,.T.); +#173807 = EDGE_CURVE('',#173780,#173808,#173810,.T.); +#173808 = VERTEX_POINT('',#173809); +#173809 = CARTESIAN_POINT('',(-0.175,0.8,0.6)); +#173810 = SURFACE_CURVE('',#173811,(#173815,#173822),.PCURVE_S1.); +#173811 = LINE('',#173812,#173813); +#173812 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173813 = VECTOR('',#173814,1.); +#173814 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173815 = PCURVE('',#173431,#173816); +#173816 = DEFINITIONAL_REPRESENTATION('',(#173817),#173821); +#173817 = LINE('',#173818,#173819); +#173818 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173819 = VECTOR('',#173820,1.); +#173820 = DIRECTION('',(0.E+000,-1.)); +#173821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173822 = PCURVE('',#173471,#173823); +#173823 = DEFINITIONAL_REPRESENTATION('',(#173824),#173828); +#173824 = LINE('',#173825,#173826); +#173825 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173826 = VECTOR('',#173827,1.); +#173827 = DIRECTION('',(0.E+000,-1.)); +#173828 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173829 = ORIENTED_EDGE('',*,*,#173830,.T.); +#173830 = EDGE_CURVE('',#173808,#173831,#173833,.T.); +#173831 = VERTEX_POINT('',#173832); +#173832 = CARTESIAN_POINT('',(-0.175,0.759807621135,0.75)); +#173833 = SURFACE_CURVE('',#173834,(#173838,#173845),.PCURVE_S1.); +#173834 = LINE('',#173835,#173836); +#173835 = CARTESIAN_POINT('',(-0.175,0.8,0.6)); +#173836 = VECTOR('',#173837,1.); +#173837 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173838 = PCURVE('',#173431,#173839); +#173839 = DEFINITIONAL_REPRESENTATION('',(#173840),#173844); +#173840 = LINE('',#173841,#173842); +#173841 = CARTESIAN_POINT('',(-1.072393092426E-016,1.295)); +#173842 = VECTOR('',#173843,1.); +#173843 = DIRECTION('',(1.,0.E+000)); +#173844 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173845 = PCURVE('',#173846,#173851); +#173846 = PLANE('',#173847); +#173847 = AXIS2_PLACEMENT_3D('',#173848,#173849,#173850); +#173848 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); +#173849 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173850 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173851 = DEFINITIONAL_REPRESENTATION('',(#173852),#173856); +#173852 = LINE('',#173853,#173854); +#173853 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173854 = VECTOR('',#173855,1.); +#173855 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173857 = ORIENTED_EDGE('',*,*,#173858,.T.); +#173858 = EDGE_CURVE('',#173831,#173859,#173861,.T.); +#173859 = VERTEX_POINT('',#173860); +#173860 = CARTESIAN_POINT('',(-0.515,0.759807621135,0.75)); +#173861 = SURFACE_CURVE('',#173862,(#173866,#173873),.PCURVE_S1.); +#173862 = LINE('',#173863,#173864); +#173863 = CARTESIAN_POINT('',(-2.77,0.759807621135,0.75)); +#173864 = VECTOR('',#173865,1.); +#173865 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173866 = PCURVE('',#173431,#173867); +#173867 = DEFINITIONAL_REPRESENTATION('',(#173868),#173872); +#173868 = LINE('',#173869,#173870); +#173869 = CARTESIAN_POINT('',(0.155291427062,-1.3)); +#173870 = VECTOR('',#173871,1.); +#173871 = DIRECTION('',(0.E+000,-1.)); +#173872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173873 = PCURVE('',#173874,#173879); +#173874 = PLANE('',#173875); +#173875 = AXIS2_PLACEMENT_3D('',#173876,#173877,#173878); +#173876 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); +#173877 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173878 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173879 = DEFINITIONAL_REPRESENTATION('',(#173880),#173884); +#173880 = LINE('',#173881,#173882); +#173881 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); +#173882 = VECTOR('',#173883,1.); +#173883 = DIRECTION('',(-1.,0.E+000)); +#173884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173885 = ORIENTED_EDGE('',*,*,#173886,.F.); +#173886 = EDGE_CURVE('',#173887,#173859,#173889,.T.); +#173887 = VERTEX_POINT('',#173888); +#173888 = CARTESIAN_POINT('',(-0.515,0.8,0.6)); +#173889 = SURFACE_CURVE('',#173890,(#173894,#173901),.PCURVE_S1.); +#173890 = LINE('',#173891,#173892); +#173891 = CARTESIAN_POINT('',(-0.515,0.8,0.6)); +#173892 = VECTOR('',#173893,1.); +#173893 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173894 = PCURVE('',#173431,#173895); +#173895 = DEFINITIONAL_REPRESENTATION('',(#173896),#173900); +#173896 = LINE('',#173897,#173898); +#173897 = CARTESIAN_POINT('',(-1.072393092426E-016,0.955)); +#173898 = VECTOR('',#173899,1.); +#173899 = DIRECTION('',(1.,0.E+000)); +#173900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173901 = PCURVE('',#173902,#173907); +#173902 = PLANE('',#173903); +#173903 = AXIS2_PLACEMENT_3D('',#173904,#173905,#173906); +#173904 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); +#173905 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173906 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173907 = DEFINITIONAL_REPRESENTATION('',(#173908),#173912); +#173908 = LINE('',#173909,#173910); +#173909 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173910 = VECTOR('',#173911,1.); +#173911 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173913 = ORIENTED_EDGE('',*,*,#173914,.T.); +#173914 = EDGE_CURVE('',#173887,#173915,#173917,.T.); +#173915 = VERTEX_POINT('',#173916); +#173916 = CARTESIAN_POINT('',(-0.825,0.8,0.6)); +#173917 = SURFACE_CURVE('',#173918,(#173922,#173929),.PCURVE_S1.); +#173918 = LINE('',#173919,#173920); +#173919 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#173920 = VECTOR('',#173921,1.); +#173921 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173922 = PCURVE('',#173431,#173923); +#173923 = DEFINITIONAL_REPRESENTATION('',(#173924),#173928); +#173924 = LINE('',#173925,#173926); +#173925 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173926 = VECTOR('',#173927,1.); +#173927 = DIRECTION('',(0.E+000,-1.)); +#173928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173929 = PCURVE('',#173471,#173930); +#173930 = DEFINITIONAL_REPRESENTATION('',(#173931),#173935); +#173931 = LINE('',#173932,#173933); +#173932 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#173933 = VECTOR('',#173934,1.); +#173934 = DIRECTION('',(0.E+000,-1.)); +#173935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173936 = ORIENTED_EDGE('',*,*,#173937,.T.); +#173937 = EDGE_CURVE('',#173915,#173938,#173940,.T.); +#173938 = VERTEX_POINT('',#173939); +#173939 = CARTESIAN_POINT('',(-0.825,0.759807621135,0.75)); +#173940 = SURFACE_CURVE('',#173941,(#173945,#173952),.PCURVE_S1.); +#173941 = LINE('',#173942,#173943); +#173942 = CARTESIAN_POINT('',(-0.825,0.8,0.6)); +#173943 = VECTOR('',#173944,1.); +#173944 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#173945 = PCURVE('',#173431,#173946); +#173946 = DEFINITIONAL_REPRESENTATION('',(#173947),#173951); +#173947 = LINE('',#173948,#173949); +#173948 = CARTESIAN_POINT('',(-2.432133047937E-016,0.645)); +#173949 = VECTOR('',#173950,1.); +#173950 = DIRECTION('',(1.,0.E+000)); +#173951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#171598 = ADVANCED_FACE('',(#171599),#171613,.T.); -#171599 = FACE_BOUND('',#171600,.T.); -#171600 = EDGE_LOOP('',(#171601,#171653,#171696,#171741)); -#171601 = ORIENTED_EDGE('',*,*,#171602,.T.); -#171602 = EDGE_CURVE('',#171603,#171605,#171607,.T.); -#171603 = VERTEX_POINT('',#171604); -#171604 = CARTESIAN_POINT('',(1.47,-0.655111126057,0.6)); -#171605 = VERTEX_POINT('',#171606); -#171606 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, +#173952 = PCURVE('',#173953,#173958); +#173953 = PLANE('',#173954); +#173954 = AXIS2_PLACEMENT_3D('',#173955,#173956,#173957); +#173955 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); +#173956 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173957 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#173958 = DEFINITIONAL_REPRESENTATION('',(#173959),#173963); +#173959 = LINE('',#173960,#173961); +#173960 = CARTESIAN_POINT('',(-1.E-001,-7.264967154127E-003)); +#173961 = VECTOR('',#173962,1.); +#173962 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#173963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173964 = ORIENTED_EDGE('',*,*,#173965,.T.); +#173965 = EDGE_CURVE('',#173938,#173423,#173966,.T.); +#173966 = SURFACE_CURVE('',#173967,(#173971,#173978),.PCURVE_S1.); +#173967 = LINE('',#173968,#173969); +#173968 = CARTESIAN_POINT('',(-3.42,0.759807621135,0.75)); +#173969 = VECTOR('',#173970,1.); +#173970 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#173971 = PCURVE('',#173431,#173972); +#173972 = DEFINITIONAL_REPRESENTATION('',(#173973),#173977); +#173973 = LINE('',#173974,#173975); +#173974 = CARTESIAN_POINT('',(0.155291427062,-1.95)); +#173975 = VECTOR('',#173976,1.); +#173976 = DIRECTION('',(0.E+000,-1.)); +#173977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173978 = PCURVE('',#173979,#173984); +#173979 = PLANE('',#173980); +#173980 = AXIS2_PLACEMENT_3D('',#173981,#173982,#173983); +#173981 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); +#173982 = DIRECTION('',(0.E+000,0.E+000,1.)); +#173983 = DIRECTION('',(1.,0.E+000,0.E+000)); +#173984 = DEFINITIONAL_REPRESENTATION('',(#173985),#173989); +#173985 = LINE('',#173986,#173987); +#173986 = CARTESIAN_POINT('',(-2.255,-4.745734601879E-002)); +#173987 = VECTOR('',#173988,1.); +#173988 = DIRECTION('',(-1.,0.E+000)); +#173989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#173990 = ADVANCED_FACE('',(#173991),#174005,.T.); +#173991 = FACE_BOUND('',#173992,.T.); +#173992 = EDGE_LOOP('',(#173993,#174045,#174088,#174133)); +#173993 = ORIENTED_EDGE('',*,*,#173994,.T.); +#173994 = EDGE_CURVE('',#173995,#173997,#173999,.T.); +#173995 = VERTEX_POINT('',#173996); +#173996 = CARTESIAN_POINT('',(1.47,-0.655111126057,0.6)); +#173997 = VERTEX_POINT('',#173998); +#173998 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, 0.137059047745)); -#171607 = SURFACE_CURVE('',#171608,(#171612,#171624),.PCURVE_S1.); -#171608 = LINE('',#171609,#171610); -#171609 = CARTESIAN_POINT('',(1.378645620286,-0.563756746343, +#173999 = SURFACE_CURVE('',#174000,(#174004,#174016),.PCURVE_S1.); +#174000 = LINE('',#174001,#174002); +#174001 = CARTESIAN_POINT('',(1.378645620286,-0.563756746343, 0.259060813414)); -#171610 = VECTOR('',#171611,1.); -#171611 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) - ); -#171612 = PCURVE('',#171613,#171618); -#171613 = PLANE('',#171614); -#171614 = AXIS2_PLACEMENT_3D('',#171615,#171616,#171617); -#171615 = CARTESIAN_POINT('',(1.47,0.8,0.6)); -#171616 = DIRECTION('',(0.965925826289,1.309073599153E-016, +#174002 = VECTOR('',#174003,1.); +#174003 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) + ); +#174004 = PCURVE('',#174005,#174010); +#174005 = PLANE('',#174006); +#174006 = AXIS2_PLACEMENT_3D('',#174007,#174008,#174009); +#174007 = CARTESIAN_POINT('',(1.47,0.8,0.6)); +#174008 = DIRECTION('',(0.965925826289,1.309073599153E-016, -0.258819045103)); -#171617 = DIRECTION('',(-0.258819045103,5.910197516838E-033, +#174009 = DIRECTION('',(-0.258819045103,5.910197516838E-033, -0.965925826289)); -#171618 = DEFINITIONAL_REPRESENTATION('',(#171619),#171623); -#171619 = LINE('',#171620,#171621); -#171620 = CARTESIAN_POINT('',(0.352966218841,-1.363756746343)); -#171621 = VECTOR('',#171622,1.); -#171622 = DIRECTION('',(0.968100345886,0.250562807086)); -#171623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171624 = PCURVE('',#168838,#171625); -#171625 = DEFINITIONAL_REPRESENTATION('',(#171626),#171652); -#171626 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171627,#171628,#171629, - #171630,#171631,#171632,#171633,#171634,#171635,#171636,#171637, - #171638,#171639,#171640,#171641,#171642,#171643,#171644,#171645, - #171646,#171647,#171648,#171649,#171650,#171651),.UNSPECIFIED.,.F., +#174010 = DEFINITIONAL_REPRESENTATION('',(#174011),#174015); +#174011 = LINE('',#174012,#174013); +#174012 = CARTESIAN_POINT('',(0.352966218841,-1.363756746343)); +#174013 = VECTOR('',#174014,1.); +#174014 = DIRECTION('',(0.968100345886,0.250562807086)); +#174015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174016 = PCURVE('',#171230,#174017); +#174017 = DEFINITIONAL_REPRESENTATION('',(#174018),#174044); +#174018 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174019,#174020,#174021, + #174022,#174023,#174024,#174025,#174026,#174027,#174028,#174029, + #174030,#174031,#174032,#174033,#174034,#174035,#174036,#174037, + #174038,#174039,#174040,#174041,#174042,#174043),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.364596728366, -0.342093814056,-0.319590899745,-0.297087985435,-0.274585071124, -0.252082156813,-0.229579242503,-0.207076328192,-0.184573413882, @@ -212273,57 +215275,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -4.550099396727E-003,1.795281491388E-002,4.045572922449E-002, 6.295864353509E-002,8.54615578457E-002,0.107964472156,0.130467386467 ),.UNSPECIFIED.); -#171627 = CARTESIAN_POINT('',(6.28318530718,0.700350889861)); -#171628 = CARTESIAN_POINT('',(6.28318530718,0.692849918424)); -#171629 = CARTESIAN_POINT('',(6.28318530718,0.677847975551)); -#171630 = CARTESIAN_POINT('',(6.28318530718,0.65534506124)); -#171631 = CARTESIAN_POINT('',(6.28318530718,0.632842146929)); -#171632 = CARTESIAN_POINT('',(6.28318530718,0.610339232619)); -#171633 = CARTESIAN_POINT('',(6.28318530718,0.587836318308)); -#171634 = CARTESIAN_POINT('',(6.28318530718,0.565333403998)); -#171635 = CARTESIAN_POINT('',(6.28318530718,0.542830489687)); -#171636 = CARTESIAN_POINT('',(6.28318530718,0.520327575376)); -#171637 = CARTESIAN_POINT('',(6.28318530718,0.497824661066)); -#171638 = CARTESIAN_POINT('',(6.28318530718,0.475321746755)); -#171639 = CARTESIAN_POINT('',(6.28318530718,0.452818832445)); -#171640 = CARTESIAN_POINT('',(6.28318530718,0.430315918134)); -#171641 = CARTESIAN_POINT('',(6.28318530718,0.407813003823)); -#171642 = CARTESIAN_POINT('',(6.28318530718,0.385310089513)); -#171643 = CARTESIAN_POINT('',(6.28318530718,0.362807175202)); -#171644 = CARTESIAN_POINT('',(6.28318530718,0.340304260892)); -#171645 = CARTESIAN_POINT('',(6.28318530718,0.317801346581)); -#171646 = CARTESIAN_POINT('',(6.28318530718,0.29529843227)); -#171647 = CARTESIAN_POINT('',(6.28318530718,0.27279551796)); -#171648 = CARTESIAN_POINT('',(6.28318530718,0.250292603649)); -#171649 = CARTESIAN_POINT('',(6.28318530718,0.227789689339)); -#171650 = CARTESIAN_POINT('',(6.28318530718,0.212787746465)); -#171651 = CARTESIAN_POINT('',(6.28318530718,0.205286775028)); -#171652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171653 = ORIENTED_EDGE('',*,*,#171654,.T.); -#171654 = EDGE_CURVE('',#171605,#169373,#171655,.T.); -#171655 = SURFACE_CURVE('',#171656,(#171660,#171667),.PCURVE_S1.); -#171656 = LINE('',#171657,#171658); -#171657 = CARTESIAN_POINT('',(1.3459553457,0.521136529841,0.137059047745 +#174019 = CARTESIAN_POINT('',(6.28318530718,0.700350889861)); +#174020 = CARTESIAN_POINT('',(6.28318530718,0.692849918424)); +#174021 = CARTESIAN_POINT('',(6.28318530718,0.677847975551)); +#174022 = CARTESIAN_POINT('',(6.28318530718,0.65534506124)); +#174023 = CARTESIAN_POINT('',(6.28318530718,0.632842146929)); +#174024 = CARTESIAN_POINT('',(6.28318530718,0.610339232619)); +#174025 = CARTESIAN_POINT('',(6.28318530718,0.587836318308)); +#174026 = CARTESIAN_POINT('',(6.28318530718,0.565333403998)); +#174027 = CARTESIAN_POINT('',(6.28318530718,0.542830489687)); +#174028 = CARTESIAN_POINT('',(6.28318530718,0.520327575376)); +#174029 = CARTESIAN_POINT('',(6.28318530718,0.497824661066)); +#174030 = CARTESIAN_POINT('',(6.28318530718,0.475321746755)); +#174031 = CARTESIAN_POINT('',(6.28318530718,0.452818832445)); +#174032 = CARTESIAN_POINT('',(6.28318530718,0.430315918134)); +#174033 = CARTESIAN_POINT('',(6.28318530718,0.407813003823)); +#174034 = CARTESIAN_POINT('',(6.28318530718,0.385310089513)); +#174035 = CARTESIAN_POINT('',(6.28318530718,0.362807175202)); +#174036 = CARTESIAN_POINT('',(6.28318530718,0.340304260892)); +#174037 = CARTESIAN_POINT('',(6.28318530718,0.317801346581)); +#174038 = CARTESIAN_POINT('',(6.28318530718,0.29529843227)); +#174039 = CARTESIAN_POINT('',(6.28318530718,0.27279551796)); +#174040 = CARTESIAN_POINT('',(6.28318530718,0.250292603649)); +#174041 = CARTESIAN_POINT('',(6.28318530718,0.227789689339)); +#174042 = CARTESIAN_POINT('',(6.28318530718,0.212787746465)); +#174043 = CARTESIAN_POINT('',(6.28318530718,0.205286775028)); +#174044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174045 = ORIENTED_EDGE('',*,*,#174046,.T.); +#174046 = EDGE_CURVE('',#173997,#171765,#174047,.T.); +#174047 = SURFACE_CURVE('',#174048,(#174052,#174059),.PCURVE_S1.); +#174048 = LINE('',#174049,#174050); +#174049 = CARTESIAN_POINT('',(1.3459553457,0.521136529841,0.137059047745 )); -#171658 = VECTOR('',#171659,1.); -#171659 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#171660 = PCURVE('',#171613,#171661); -#171661 = DEFINITIONAL_REPRESENTATION('',(#171662),#171666); -#171662 = LINE('',#171663,#171664); -#171663 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); -#171664 = VECTOR('',#171665,1.); -#171665 = DIRECTION('',(3.50765213726E-017,1.)); -#171666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171667 = PCURVE('',#169482,#171668); -#171668 = DEFINITIONAL_REPRESENTATION('',(#171669),#171695); -#171669 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171670,#171671,#171672, - #171673,#171674,#171675,#171676,#171677,#171678,#171679,#171680, - #171681,#171682,#171683,#171684,#171685,#171686,#171687,#171688, - #171689,#171690,#171691,#171692,#171693,#171694),.UNSPECIFIED.,.F., +#174050 = VECTOR('',#174051,1.); +#174051 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#174052 = PCURVE('',#174005,#174053); +#174053 = DEFINITIONAL_REPRESENTATION('',(#174054),#174058); +#174054 = LINE('',#174055,#174056); +#174055 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); +#174056 = VECTOR('',#174057,1.); +#174057 = DIRECTION('',(3.50765213726E-017,1.)); +#174058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174059 = PCURVE('',#171874,#174060); +#174060 = DEFINITIONAL_REPRESENTATION('',(#174061),#174087); +#174061 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174062,#174063,#174064, + #174065,#174066,#174067,#174068,#174069,#174070,#174071,#174072, + #174073,#174074,#174075,#174076,#174077,#174078,#174079,#174080, + #174081,#174082,#174083,#174084,#174085,#174086),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-1.052203001598, -1.003924231438,-0.955645461278,-0.907366691119,-0.859087920959, -0.810809150799,-0.76253038064,-0.71425161048,-0.66597284032, @@ -212331,59 +215333,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.424578989522,-0.376300219362,-0.328021449202,-0.279742679043, -0.231463908883,-0.183185138723,-0.134906368564,-8.662759840387E-002 ,-3.834882824418E-002,9.929941915506E-003),.UNSPECIFIED.); -#171670 = CARTESIAN_POINT('',(6.02138591938,1.331066471757)); -#171671 = CARTESIAN_POINT('',(6.02138591938,1.31497354837)); -#171672 = CARTESIAN_POINT('',(6.02138591938,1.282787701597)); -#171673 = CARTESIAN_POINT('',(6.02138591938,1.234508931437)); -#171674 = CARTESIAN_POINT('',(6.02138591938,1.186230161278)); -#171675 = CARTESIAN_POINT('',(6.02138591938,1.137951391118)); -#171676 = CARTESIAN_POINT('',(6.02138591938,1.089672620958)); -#171677 = CARTESIAN_POINT('',(6.02138591938,1.041393850798)); -#171678 = CARTESIAN_POINT('',(6.02138591938,0.993115080639)); -#171679 = CARTESIAN_POINT('',(6.02138591938,0.944836310479)); -#171680 = CARTESIAN_POINT('',(6.02138591938,0.896557540319)); -#171681 = CARTESIAN_POINT('',(6.02138591938,0.84827877016)); -#171682 = CARTESIAN_POINT('',(6.02138591938,0.8)); -#171683 = CARTESIAN_POINT('',(6.02138591938,0.75172122984)); -#171684 = CARTESIAN_POINT('',(6.02138591938,0.703442459681)); -#171685 = CARTESIAN_POINT('',(6.02138591938,0.655163689521)); -#171686 = CARTESIAN_POINT('',(6.02138591938,0.606884919361)); -#171687 = CARTESIAN_POINT('',(6.02138591938,0.558606149202)); -#171688 = CARTESIAN_POINT('',(6.02138591938,0.510327379042)); -#171689 = CARTESIAN_POINT('',(6.02138591938,0.462048608882)); -#171690 = CARTESIAN_POINT('',(6.02138591938,0.413769838722)); -#171691 = CARTESIAN_POINT('',(6.02138591938,0.365491068563)); -#171692 = CARTESIAN_POINT('',(6.02138591938,0.317212298403)); -#171693 = CARTESIAN_POINT('',(6.02138591938,0.28502645163)); -#171694 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#171695 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171696 = ORIENTED_EDGE('',*,*,#171697,.T.); -#171697 = EDGE_CURVE('',#169373,#171698,#171700,.T.); -#171698 = VERTEX_POINT('',#171699); -#171699 = CARTESIAN_POINT('',(1.47,0.655111126057,0.6)); -#171700 = SURFACE_CURVE('',#171701,(#171705,#171712),.PCURVE_S1.); -#171701 = LINE('',#171702,#171703); -#171702 = CARTESIAN_POINT('',(1.479096372758,0.664207498814, +#174062 = CARTESIAN_POINT('',(6.02138591938,1.331066471757)); +#174063 = CARTESIAN_POINT('',(6.02138591938,1.31497354837)); +#174064 = CARTESIAN_POINT('',(6.02138591938,1.282787701597)); +#174065 = CARTESIAN_POINT('',(6.02138591938,1.234508931437)); +#174066 = CARTESIAN_POINT('',(6.02138591938,1.186230161278)); +#174067 = CARTESIAN_POINT('',(6.02138591938,1.137951391118)); +#174068 = CARTESIAN_POINT('',(6.02138591938,1.089672620958)); +#174069 = CARTESIAN_POINT('',(6.02138591938,1.041393850798)); +#174070 = CARTESIAN_POINT('',(6.02138591938,0.993115080639)); +#174071 = CARTESIAN_POINT('',(6.02138591938,0.944836310479)); +#174072 = CARTESIAN_POINT('',(6.02138591938,0.896557540319)); +#174073 = CARTESIAN_POINT('',(6.02138591938,0.84827877016)); +#174074 = CARTESIAN_POINT('',(6.02138591938,0.8)); +#174075 = CARTESIAN_POINT('',(6.02138591938,0.75172122984)); +#174076 = CARTESIAN_POINT('',(6.02138591938,0.703442459681)); +#174077 = CARTESIAN_POINT('',(6.02138591938,0.655163689521)); +#174078 = CARTESIAN_POINT('',(6.02138591938,0.606884919361)); +#174079 = CARTESIAN_POINT('',(6.02138591938,0.558606149202)); +#174080 = CARTESIAN_POINT('',(6.02138591938,0.510327379042)); +#174081 = CARTESIAN_POINT('',(6.02138591938,0.462048608882)); +#174082 = CARTESIAN_POINT('',(6.02138591938,0.413769838722)); +#174083 = CARTESIAN_POINT('',(6.02138591938,0.365491068563)); +#174084 = CARTESIAN_POINT('',(6.02138591938,0.317212298403)); +#174085 = CARTESIAN_POINT('',(6.02138591938,0.28502645163)); +#174086 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#174087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174088 = ORIENTED_EDGE('',*,*,#174089,.T.); +#174089 = EDGE_CURVE('',#171765,#174090,#174092,.T.); +#174090 = VERTEX_POINT('',#174091); +#174091 = CARTESIAN_POINT('',(1.47,0.655111126057,0.6)); +#174092 = SURFACE_CURVE('',#174093,(#174097,#174104),.PCURVE_S1.); +#174093 = LINE('',#174094,#174095); +#174094 = CARTESIAN_POINT('',(1.479096372758,0.664207498814, 0.633948125296)); -#171703 = VECTOR('',#171704,1.); -#171704 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#171705 = PCURVE('',#171613,#171706); -#171706 = DEFINITIONAL_REPRESENTATION('',(#171707),#171711); -#171707 = LINE('',#171708,#171709); -#171708 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#171709 = VECTOR('',#171710,1.); -#171710 = DIRECTION('',(-0.968100345886,0.250562807086)); -#171711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171712 = PCURVE('',#169411,#171713); -#171713 = DEFINITIONAL_REPRESENTATION('',(#171714),#171740); -#171714 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171715,#171716,#171717, - #171718,#171719,#171720,#171721,#171722,#171723,#171724,#171725, - #171726,#171727,#171728,#171729,#171730,#171731,#171732,#171733, - #171734,#171735,#171736,#171737,#171738,#171739),.UNSPECIFIED.,.F., +#174095 = VECTOR('',#174096,1.); +#174096 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#174097 = PCURVE('',#174005,#174098); +#174098 = DEFINITIONAL_REPRESENTATION('',(#174099),#174103); +#174099 = LINE('',#174100,#174101); +#174100 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#174101 = VECTOR('',#174102,1.); +#174102 = DIRECTION('',(-0.968100345886,0.250562807086)); +#174103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174104 = PCURVE('',#171803,#174105); +#174105 = DEFINITIONAL_REPRESENTATION('',(#174106),#174132); +#174106 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174107,#174108,#174109, + #174110,#174111,#174112,#174113,#174114,#174115,#174116,#174117, + #174118,#174119,#174120,#174121,#174122,#174123,#174124,#174125, + #174126,#174127,#174128,#174129,#174130,#174131),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.531367877804, -0.508864963493,-0.486362049183,-0.463859134872,-0.441356220562, -0.418853306251,-0.39635039194,-0.37384747763,-0.351344563319, @@ -212391,106 +215393,106 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.238829991766,-0.216327077456,-0.193824163145,-0.171321248834, -0.148818334524,-0.126315420213,-0.103812505903,-8.130959159195E-002 ,-5.880667728135E-002,-3.630376297074E-002),.QUASI_UNIFORM_KNOTS.); -#171715 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#171716 = CARTESIAN_POINT('',(0.E+000,-0.523866906367)); -#171717 = CARTESIAN_POINT('',(5.218420319449E-025,-0.508864963493)); -#171718 = CARTESIAN_POINT('',(-1.826447111807E-024,-0.486362049183)); -#171719 = CARTESIAN_POINT('',(6.783946415283E-024,-0.463859134872)); -#171720 = CARTESIAN_POINT('',(-2.530933854933E-023,-0.441356220562)); -#171721 = CARTESIAN_POINT('',(9.445340778202E-023,-0.418853306251)); -#171722 = CARTESIAN_POINT('',(-3.525042925788E-022,-0.39635039194)); -#171723 = CARTESIAN_POINT('',(1.315563762533E-021,-0.37384747763)); -#171724 = CARTESIAN_POINT('',(-4.909750757553E-021,-0.351344563319)); -#171725 = CARTESIAN_POINT('',(1.832343926768E-020,-0.328841649009)); -#171726 = CARTESIAN_POINT('',(-6.838400631317E-020,-0.306338734698)); -#171727 = CARTESIAN_POINT('',(2.55212585985E-019,-0.283835820387)); -#171728 = CARTESIAN_POINT('',(-9.524663376268E-019,-0.261332906077)); -#171729 = CARTESIAN_POINT('',(3.554652764522E-018,-0.238829991766)); -#171730 = CARTESIAN_POINT('',(-1.326614472046E-017,-0.216327077456)); -#171731 = CARTESIAN_POINT('',(4.950992611733E-017,-0.193824163145)); -#171732 = CARTESIAN_POINT('',(-1.847735597488E-016,-0.171321248834)); -#171733 = CARTESIAN_POINT('',(6.89584312878E-016,-0.148818334524)); -#171734 = CARTESIAN_POINT('',(-3.53117642513E-016,-0.126315420213)); -#171735 = CARTESIAN_POINT('',(7.22886257174E-016,-0.103812505903)); -#171736 = CARTESIAN_POINT('',(-3.179813369325E-016,-8.130959159195E-002) - ); -#171737 = CARTESIAN_POINT('',(5.490390905562E-016,-5.880667728135E-002) - ); -#171738 = CARTESIAN_POINT('',(4.111937128241E-016,-4.380473440761E-002) - ); -#171739 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#171740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171741 = ORIENTED_EDGE('',*,*,#171742,.F.); -#171742 = EDGE_CURVE('',#171603,#171698,#171743,.T.); -#171743 = SURFACE_CURVE('',#171744,(#171748,#171755),.PCURVE_S1.); -#171744 = LINE('',#171745,#171746); -#171745 = CARTESIAN_POINT('',(1.47,0.8,0.6)); -#171746 = VECTOR('',#171747,1.); -#171747 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#171748 = PCURVE('',#171613,#171749); -#171749 = DEFINITIONAL_REPRESENTATION('',(#171750),#171754); -#171750 = LINE('',#171751,#171752); -#171751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171752 = VECTOR('',#171753,1.); -#171753 = DIRECTION('',(3.50765213726E-017,1.)); -#171754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171755 = PCURVE('',#171756,#171761); -#171756 = PLANE('',#171757); -#171757 = AXIS2_PLACEMENT_3D('',#171758,#171759,#171760); -#171758 = CARTESIAN_POINT('',(1.47,0.8,0.6)); -#171759 = DIRECTION('',(0.965925826289,1.309073599153E-016, +#174107 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#174108 = CARTESIAN_POINT('',(0.E+000,-0.523866906367)); +#174109 = CARTESIAN_POINT('',(5.218420319449E-025,-0.508864963493)); +#174110 = CARTESIAN_POINT('',(-1.826447111807E-024,-0.486362049183)); +#174111 = CARTESIAN_POINT('',(6.783946415283E-024,-0.463859134872)); +#174112 = CARTESIAN_POINT('',(-2.530933854933E-023,-0.441356220562)); +#174113 = CARTESIAN_POINT('',(9.445340778202E-023,-0.418853306251)); +#174114 = CARTESIAN_POINT('',(-3.525042925788E-022,-0.39635039194)); +#174115 = CARTESIAN_POINT('',(1.315563762533E-021,-0.37384747763)); +#174116 = CARTESIAN_POINT('',(-4.909750757553E-021,-0.351344563319)); +#174117 = CARTESIAN_POINT('',(1.832343926768E-020,-0.328841649009)); +#174118 = CARTESIAN_POINT('',(-6.838400631317E-020,-0.306338734698)); +#174119 = CARTESIAN_POINT('',(2.55212585985E-019,-0.283835820387)); +#174120 = CARTESIAN_POINT('',(-9.524663376268E-019,-0.261332906077)); +#174121 = CARTESIAN_POINT('',(3.554652764522E-018,-0.238829991766)); +#174122 = CARTESIAN_POINT('',(-1.326614472046E-017,-0.216327077456)); +#174123 = CARTESIAN_POINT('',(4.950992611733E-017,-0.193824163145)); +#174124 = CARTESIAN_POINT('',(-1.847735597488E-016,-0.171321248834)); +#174125 = CARTESIAN_POINT('',(6.89584312878E-016,-0.148818334524)); +#174126 = CARTESIAN_POINT('',(-3.53117642513E-016,-0.126315420213)); +#174127 = CARTESIAN_POINT('',(7.22886257174E-016,-0.103812505903)); +#174128 = CARTESIAN_POINT('',(-3.179813369325E-016,-8.130959159195E-002) + ); +#174129 = CARTESIAN_POINT('',(5.490390905562E-016,-5.880667728135E-002) + ); +#174130 = CARTESIAN_POINT('',(4.111937128241E-016,-4.380473440761E-002) + ); +#174131 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#174132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174133 = ORIENTED_EDGE('',*,*,#174134,.F.); +#174134 = EDGE_CURVE('',#173995,#174090,#174135,.T.); +#174135 = SURFACE_CURVE('',#174136,(#174140,#174147),.PCURVE_S1.); +#174136 = LINE('',#174137,#174138); +#174137 = CARTESIAN_POINT('',(1.47,0.8,0.6)); +#174138 = VECTOR('',#174139,1.); +#174139 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#174140 = PCURVE('',#174005,#174141); +#174141 = DEFINITIONAL_REPRESENTATION('',(#174142),#174146); +#174142 = LINE('',#174143,#174144); +#174143 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174144 = VECTOR('',#174145,1.); +#174145 = DIRECTION('',(3.50765213726E-017,1.)); +#174146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174147 = PCURVE('',#174148,#174153); +#174148 = PLANE('',#174149); +#174149 = AXIS2_PLACEMENT_3D('',#174150,#174151,#174152); +#174150 = CARTESIAN_POINT('',(1.47,0.8,0.6)); +#174151 = DIRECTION('',(0.965925826289,1.309073599153E-016, 0.258819045103)); -#171760 = DIRECTION('',(0.258819045103,-5.910197516838E-033, +#174152 = DIRECTION('',(0.258819045103,-5.910197516838E-033, -0.965925826289)); -#171761 = DEFINITIONAL_REPRESENTATION('',(#171762),#171766); -#171762 = LINE('',#171763,#171764); -#171763 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171764 = VECTOR('',#171765,1.); -#171765 = DIRECTION('',(-3.50765213726E-017,1.)); -#171766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171767 = ADVANCED_FACE('',(#171768),#171782,.T.); -#171768 = FACE_BOUND('',#171769,.T.); -#171769 = EDGE_LOOP('',(#171770,#171822,#171842,#171887,#171915,#171943, - #171966,#171994,#172017,#172045,#172068,#172096)); -#171770 = ORIENTED_EDGE('',*,*,#171771,.T.); -#171771 = EDGE_CURVE('',#171772,#171774,#171776,.T.); -#171772 = VERTEX_POINT('',#171773); -#171773 = CARTESIAN_POINT('',(-1.325111126057,-0.8,0.6)); -#171774 = VERTEX_POINT('',#171775); -#171775 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, +#174153 = DEFINITIONAL_REPRESENTATION('',(#174154),#174158); +#174154 = LINE('',#174155,#174156); +#174155 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174156 = VECTOR('',#174157,1.); +#174157 = DIRECTION('',(-3.50765213726E-017,1.)); +#174158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174159 = ADVANCED_FACE('',(#174160),#174174,.T.); +#174160 = FACE_BOUND('',#174161,.T.); +#174161 = EDGE_LOOP('',(#174162,#174214,#174234,#174279,#174307,#174335, + #174358,#174386,#174409,#174437,#174460,#174488)); +#174162 = ORIENTED_EDGE('',*,*,#174163,.T.); +#174163 = EDGE_CURVE('',#174164,#174166,#174168,.T.); +#174164 = VERTEX_POINT('',#174165); +#174165 = CARTESIAN_POINT('',(-1.325111126057,-0.8,0.6)); +#174166 = VERTEX_POINT('',#174167); +#174167 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, 0.137059047745)); -#171776 = SURFACE_CURVE('',#171777,(#171781,#171793),.PCURVE_S1.); -#171777 = LINE('',#171778,#171779); -#171778 = CARTESIAN_POINT('',(-1.334207498814,-0.809096372758, +#174168 = SURFACE_CURVE('',#174169,(#174173,#174185),.PCURVE_S1.); +#174169 = LINE('',#174170,#174171); +#174170 = CARTESIAN_POINT('',(-1.334207498814,-0.809096372758, 0.633948125296)); -#171779 = VECTOR('',#171780,1.); -#171780 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#171781 = PCURVE('',#171782,#171787); -#171782 = PLANE('',#171783); -#171783 = AXIS2_PLACEMENT_3D('',#171784,#171785,#171786); -#171784 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#171785 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); -#171786 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); -#171787 = DEFINITIONAL_REPRESENTATION('',(#171788),#171792); -#171788 = LINE('',#171789,#171790); -#171789 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#171790 = VECTOR('',#171791,1.); -#171791 = DIRECTION('',(0.968100345886,0.250562807086)); -#171792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171793 = PCURVE('',#169136,#171794); -#171794 = DEFINITIONAL_REPRESENTATION('',(#171795),#171821); -#171795 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171796,#171797,#171798, - #171799,#171800,#171801,#171802,#171803,#171804,#171805,#171806, - #171807,#171808,#171809,#171810,#171811,#171812,#171813,#171814, - #171815,#171816,#171817,#171818,#171819,#171820),.UNSPECIFIED.,.F., +#174171 = VECTOR('',#174172,1.); +#174172 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#174173 = PCURVE('',#174174,#174179); +#174174 = PLANE('',#174175); +#174175 = AXIS2_PLACEMENT_3D('',#174176,#174177,#174178); +#174176 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174177 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); +#174178 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); +#174179 = DEFINITIONAL_REPRESENTATION('',(#174180),#174184); +#174180 = LINE('',#174181,#174182); +#174181 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#174182 = VECTOR('',#174183,1.); +#174183 = DIRECTION('',(0.968100345886,0.250562807086)); +#174184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174185 = PCURVE('',#171528,#174186); +#174186 = DEFINITIONAL_REPRESENTATION('',(#174187),#174213); +#174187 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174188,#174189,#174190, + #174191,#174192,#174193,#174194,#174195,#174196,#174197,#174198, + #174199,#174200,#174201,#174202,#174203,#174204,#174205,#174206, + #174207,#174208,#174209,#174210,#174211,#174212),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,5.880667728135E-002,8.130959159195E-002, 0.103812505903,0.126315420213,0.148818334524,0.171321248834, @@ -212499,86 +215501,86 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.37384747763,0.39635039194,0.418853306251,0.441356220562, 0.463859134872,0.486362049183,0.508864963493,0.531367877804), .QUASI_UNIFORM_KNOTS.); -#171796 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); -#171797 = CARTESIAN_POINT('',(4.64535148218,0.35709575693)); -#171798 = CARTESIAN_POINT('',(4.64535148218,0.342093814056)); -#171799 = CARTESIAN_POINT('',(4.64535148218,0.319590899745)); -#171800 = CARTESIAN_POINT('',(4.64535148218,0.297087985435)); -#171801 = CARTESIAN_POINT('',(4.64535148218,0.274585071124)); -#171802 = CARTESIAN_POINT('',(4.64535148218,0.252082156813)); -#171803 = CARTESIAN_POINT('',(4.64535148218,0.229579242503)); -#171804 = CARTESIAN_POINT('',(4.64535148218,0.207076328192)); -#171805 = CARTESIAN_POINT('',(4.64535148218,0.184573413882)); -#171806 = CARTESIAN_POINT('',(4.64535148218,0.162070499571)); -#171807 = CARTESIAN_POINT('',(4.64535148218,0.13956758526)); -#171808 = CARTESIAN_POINT('',(4.64535148218,0.11706467095)); -#171809 = CARTESIAN_POINT('',(4.64535148218,9.456175663915E-002)); -#171810 = CARTESIAN_POINT('',(4.64535148218,7.205884232855E-002)); -#171811 = CARTESIAN_POINT('',(4.64535148218,4.955592801794E-002)); -#171812 = CARTESIAN_POINT('',(4.64535148218,2.705301370733E-002)); -#171813 = CARTESIAN_POINT('',(4.64535148218,4.550099396726E-003)); -#171814 = CARTESIAN_POINT('',(4.64535148218,-1.795281491388E-002)); -#171815 = CARTESIAN_POINT('',(4.64535148218,-4.045572922449E-002)); -#171816 = CARTESIAN_POINT('',(4.64535148218,-6.295864353509E-002)); -#171817 = CARTESIAN_POINT('',(4.64535148218,-8.54615578457E-002)); -#171818 = CARTESIAN_POINT('',(4.64535148218,-0.107964472156)); -#171819 = CARTESIAN_POINT('',(4.64535148218,-0.12296641503)); -#171820 = CARTESIAN_POINT('',(4.64535148218,-0.130467386467)); -#171821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171822 = ORIENTED_EDGE('',*,*,#171823,.T.); -#171823 = EDGE_CURVE('',#171774,#168800,#171824,.T.); -#171824 = SURFACE_CURVE('',#171825,(#171829,#171836),.PCURVE_S1.); -#171825 = LINE('',#171826,#171827); -#171826 = CARTESIAN_POINT('',(1.191136529841,-0.6759553457, +#174188 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); +#174189 = CARTESIAN_POINT('',(4.64535148218,0.35709575693)); +#174190 = CARTESIAN_POINT('',(4.64535148218,0.342093814056)); +#174191 = CARTESIAN_POINT('',(4.64535148218,0.319590899745)); +#174192 = CARTESIAN_POINT('',(4.64535148218,0.297087985435)); +#174193 = CARTESIAN_POINT('',(4.64535148218,0.274585071124)); +#174194 = CARTESIAN_POINT('',(4.64535148218,0.252082156813)); +#174195 = CARTESIAN_POINT('',(4.64535148218,0.229579242503)); +#174196 = CARTESIAN_POINT('',(4.64535148218,0.207076328192)); +#174197 = CARTESIAN_POINT('',(4.64535148218,0.184573413882)); +#174198 = CARTESIAN_POINT('',(4.64535148218,0.162070499571)); +#174199 = CARTESIAN_POINT('',(4.64535148218,0.13956758526)); +#174200 = CARTESIAN_POINT('',(4.64535148218,0.11706467095)); +#174201 = CARTESIAN_POINT('',(4.64535148218,9.456175663915E-002)); +#174202 = CARTESIAN_POINT('',(4.64535148218,7.205884232855E-002)); +#174203 = CARTESIAN_POINT('',(4.64535148218,4.955592801794E-002)); +#174204 = CARTESIAN_POINT('',(4.64535148218,2.705301370733E-002)); +#174205 = CARTESIAN_POINT('',(4.64535148218,4.550099396726E-003)); +#174206 = CARTESIAN_POINT('',(4.64535148218,-1.795281491388E-002)); +#174207 = CARTESIAN_POINT('',(4.64535148218,-4.045572922449E-002)); +#174208 = CARTESIAN_POINT('',(4.64535148218,-6.295864353509E-002)); +#174209 = CARTESIAN_POINT('',(4.64535148218,-8.54615578457E-002)); +#174210 = CARTESIAN_POINT('',(4.64535148218,-0.107964472156)); +#174211 = CARTESIAN_POINT('',(4.64535148218,-0.12296641503)); +#174212 = CARTESIAN_POINT('',(4.64535148218,-0.130467386467)); +#174213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174214 = ORIENTED_EDGE('',*,*,#174215,.T.); +#174215 = EDGE_CURVE('',#174166,#171192,#174216,.T.); +#174216 = SURFACE_CURVE('',#174217,(#174221,#174228),.PCURVE_S1.); +#174217 = LINE('',#174218,#174219); +#174218 = CARTESIAN_POINT('',(1.191136529841,-0.6759553457, 0.137059047745)); -#171827 = VECTOR('',#171828,1.); -#171828 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171829 = PCURVE('',#171782,#171830); -#171830 = DEFINITIONAL_REPRESENTATION('',(#171831),#171835); -#171831 = LINE('',#171832,#171833); -#171832 = CARTESIAN_POINT('',(0.479271740806,2.661136529841)); -#171833 = VECTOR('',#171834,1.); -#171834 = DIRECTION('',(0.E+000,1.)); -#171835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171836 = PCURVE('',#168909,#171837); -#171837 = DEFINITIONAL_REPRESENTATION('',(#171838),#171841); -#171838 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#171839,#171840), +#174219 = VECTOR('',#174220,1.); +#174220 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174221 = PCURVE('',#174174,#174222); +#174222 = DEFINITIONAL_REPRESENTATION('',(#174223),#174227); +#174223 = LINE('',#174224,#174225); +#174224 = CARTESIAN_POINT('',(0.479271740806,2.661136529841)); +#174225 = VECTOR('',#174226,1.); +#174226 = DIRECTION('',(0.E+000,1.)); +#174227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174228 = PCURVE('',#171301,#174229); +#174229 = DEFINITIONAL_REPRESENTATION('',(#174230),#174233); +#174230 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174231,#174232), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.392203001598,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#171839 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#171840 = CARTESIAN_POINT('',(4.450589592586,-2.671066471757)); -#171841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#174231 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#174232 = CARTESIAN_POINT('',(4.450589592586,-2.671066471757)); +#174233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#171842 = ORIENTED_EDGE('',*,*,#171843,.T.); -#171843 = EDGE_CURVE('',#168800,#171844,#171846,.T.); -#171844 = VERTEX_POINT('',#171845); -#171845 = CARTESIAN_POINT('',(1.325111126057,-0.8,0.6)); -#171846 = SURFACE_CURVE('',#171847,(#171851,#171858),.PCURVE_S1.); -#171847 = LINE('',#171848,#171849); -#171848 = CARTESIAN_POINT('',(1.149629241148,-0.624518115091, +#174234 = ORIENTED_EDGE('',*,*,#174235,.T.); +#174235 = EDGE_CURVE('',#171192,#174236,#174238,.T.); +#174236 = VERTEX_POINT('',#174237); +#174237 = CARTESIAN_POINT('',(1.325111126057,-0.8,0.6)); +#174238 = SURFACE_CURVE('',#174239,(#174243,#174250),.PCURVE_S1.); +#174239 = LINE('',#174240,#174241); +#174240 = CARTESIAN_POINT('',(1.149629241148,-0.624518115091, -5.4907310287E-002)); -#171849 = VECTOR('',#171850,1.); -#171850 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#171851 = PCURVE('',#171782,#171852); -#171852 = DEFINITIONAL_REPRESENTATION('',(#171853),#171857); -#171853 = LINE('',#171854,#171855); -#171854 = CARTESIAN_POINT('',(0.678009938717,2.619629241148)); -#171855 = VECTOR('',#171856,1.); -#171856 = DIRECTION('',(-0.968100345886,0.250562807086)); -#171857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171858 = PCURVE('',#168838,#171859); -#171859 = DEFINITIONAL_REPRESENTATION('',(#171860),#171886); -#171860 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#171861,#171862,#171863, - #171864,#171865,#171866,#171867,#171868,#171869,#171870,#171871, - #171872,#171873,#171874,#171875,#171876,#171877,#171878,#171879, - #171880,#171881,#171882,#171883,#171884,#171885),.UNSPECIFIED.,.F., +#174241 = VECTOR('',#174242,1.); +#174242 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#174243 = PCURVE('',#174174,#174244); +#174244 = DEFINITIONAL_REPRESENTATION('',(#174245),#174249); +#174245 = LINE('',#174246,#174247); +#174246 = CARTESIAN_POINT('',(0.678009938717,2.619629241148)); +#174247 = VECTOR('',#174248,1.); +#174248 = DIRECTION('',(-0.968100345886,0.250562807086)); +#174249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174250 = PCURVE('',#171230,#174251); +#174251 = DEFINITIONAL_REPRESENTATION('',(#174252),#174278); +#174252 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174253,#174254,#174255, + #174256,#174257,#174258,#174259,#174260,#174261,#174262,#174263, + #174264,#174265,#174266,#174267,#174268,#174269,#174270,#174271, + #174272,#174273,#174274,#174275,#174276,#174277),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.205286775028, 0.227789689339,0.250292603649,0.27279551796,0.29529843227, 0.317801346581,0.340304260892,0.362807175202,0.385310089513, @@ -212586,339 +215588,339 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.497824661066,0.520327575376,0.542830489687,0.565333403998, 0.587836318308,0.610339232619,0.632842146929,0.65534506124, 0.677847975551,0.700350889861),.QUASI_UNIFORM_KNOTS.); -#171861 = CARTESIAN_POINT('',(4.77942647859,0.205286775028)); -#171862 = CARTESIAN_POINT('',(4.77942647859,0.212787746465)); -#171863 = CARTESIAN_POINT('',(4.77942647859,0.227789689339)); -#171864 = CARTESIAN_POINT('',(4.77942647859,0.250292603649)); -#171865 = CARTESIAN_POINT('',(4.77942647859,0.27279551796)); -#171866 = CARTESIAN_POINT('',(4.77942647859,0.29529843227)); -#171867 = CARTESIAN_POINT('',(4.77942647859,0.317801346581)); -#171868 = CARTESIAN_POINT('',(4.77942647859,0.340304260892)); -#171869 = CARTESIAN_POINT('',(4.77942647859,0.362807175202)); -#171870 = CARTESIAN_POINT('',(4.77942647859,0.385310089513)); -#171871 = CARTESIAN_POINT('',(4.77942647859,0.407813003823)); -#171872 = CARTESIAN_POINT('',(4.77942647859,0.430315918134)); -#171873 = CARTESIAN_POINT('',(4.77942647859,0.452818832445)); -#171874 = CARTESIAN_POINT('',(4.77942647859,0.475321746755)); -#171875 = CARTESIAN_POINT('',(4.77942647859,0.497824661066)); -#171876 = CARTESIAN_POINT('',(4.77942647859,0.520327575376)); -#171877 = CARTESIAN_POINT('',(4.77942647859,0.542830489687)); -#171878 = CARTESIAN_POINT('',(4.77942647859,0.565333403998)); -#171879 = CARTESIAN_POINT('',(4.77942647859,0.587836318308)); -#171880 = CARTESIAN_POINT('',(4.77942647859,0.610339232619)); -#171881 = CARTESIAN_POINT('',(4.77942647859,0.632842146929)); -#171882 = CARTESIAN_POINT('',(4.77942647859,0.65534506124)); -#171883 = CARTESIAN_POINT('',(4.77942647859,0.677847975551)); -#171884 = CARTESIAN_POINT('',(4.77942647859,0.692849918424)); -#171885 = CARTESIAN_POINT('',(4.77942647859,0.700350889861)); -#171886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#174253 = CARTESIAN_POINT('',(4.77942647859,0.205286775028)); +#174254 = CARTESIAN_POINT('',(4.77942647859,0.212787746465)); +#174255 = CARTESIAN_POINT('',(4.77942647859,0.227789689339)); +#174256 = CARTESIAN_POINT('',(4.77942647859,0.250292603649)); +#174257 = CARTESIAN_POINT('',(4.77942647859,0.27279551796)); +#174258 = CARTESIAN_POINT('',(4.77942647859,0.29529843227)); +#174259 = CARTESIAN_POINT('',(4.77942647859,0.317801346581)); +#174260 = CARTESIAN_POINT('',(4.77942647859,0.340304260892)); +#174261 = CARTESIAN_POINT('',(4.77942647859,0.362807175202)); +#174262 = CARTESIAN_POINT('',(4.77942647859,0.385310089513)); +#174263 = CARTESIAN_POINT('',(4.77942647859,0.407813003823)); +#174264 = CARTESIAN_POINT('',(4.77942647859,0.430315918134)); +#174265 = CARTESIAN_POINT('',(4.77942647859,0.452818832445)); +#174266 = CARTESIAN_POINT('',(4.77942647859,0.475321746755)); +#174267 = CARTESIAN_POINT('',(4.77942647859,0.497824661066)); +#174268 = CARTESIAN_POINT('',(4.77942647859,0.520327575376)); +#174269 = CARTESIAN_POINT('',(4.77942647859,0.542830489687)); +#174270 = CARTESIAN_POINT('',(4.77942647859,0.565333403998)); +#174271 = CARTESIAN_POINT('',(4.77942647859,0.587836318308)); +#174272 = CARTESIAN_POINT('',(4.77942647859,0.610339232619)); +#174273 = CARTESIAN_POINT('',(4.77942647859,0.632842146929)); +#174274 = CARTESIAN_POINT('',(4.77942647859,0.65534506124)); +#174275 = CARTESIAN_POINT('',(4.77942647859,0.677847975551)); +#174276 = CARTESIAN_POINT('',(4.77942647859,0.692849918424)); +#174277 = CARTESIAN_POINT('',(4.77942647859,0.700350889861)); +#174278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174279 = ORIENTED_EDGE('',*,*,#174280,.F.); +#174280 = EDGE_CURVE('',#174281,#174236,#174283,.T.); +#174281 = VERTEX_POINT('',#174282); +#174282 = CARTESIAN_POINT('',(1.125,-0.8,0.6)); +#174283 = SURFACE_CURVE('',#174284,(#174288,#174295),.PCURVE_S1.); +#174284 = LINE('',#174285,#174286); +#174285 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174286 = VECTOR('',#174287,1.); +#174287 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174288 = PCURVE('',#174174,#174289); +#174289 = DEFINITIONAL_REPRESENTATION('',(#174290),#174294); +#174290 = LINE('',#174291,#174292); +#174291 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174292 = VECTOR('',#174293,1.); +#174293 = DIRECTION('',(0.E+000,1.)); +#174294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174295 = PCURVE('',#174296,#174301); +#174296 = PLANE('',#174297); +#174297 = AXIS2_PLACEMENT_3D('',#174298,#174299,#174300); +#174298 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174299 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); +#174300 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#174301 = DEFINITIONAL_REPRESENTATION('',(#174302),#174306); +#174302 = LINE('',#174303,#174304); +#174303 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174304 = VECTOR('',#174305,1.); +#174305 = DIRECTION('',(0.E+000,1.)); +#174306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174307 = ORIENTED_EDGE('',*,*,#174308,.F.); +#174308 = EDGE_CURVE('',#174309,#174281,#174311,.T.); +#174309 = VERTEX_POINT('',#174310); +#174310 = CARTESIAN_POINT('',(0.785,-0.8,0.6)); +#174311 = SURFACE_CURVE('',#174312,(#174316,#174323),.PCURVE_S1.); +#174312 = LINE('',#174313,#174314); +#174313 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174314 = VECTOR('',#174315,1.); +#174315 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174316 = PCURVE('',#174174,#174317); +#174317 = DEFINITIONAL_REPRESENTATION('',(#174318),#174322); +#174318 = LINE('',#174319,#174320); +#174319 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174320 = VECTOR('',#174321,1.); +#174321 = DIRECTION('',(0.E+000,1.)); +#174322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174323 = PCURVE('',#174324,#174329); +#174324 = PLANE('',#174325); +#174325 = AXIS2_PLACEMENT_3D('',#174326,#174327,#174328); +#174326 = CARTESIAN_POINT('',(0.785,-0.7,0.6)); +#174327 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174328 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174329 = DEFINITIONAL_REPRESENTATION('',(#174330),#174334); +#174330 = LINE('',#174331,#174332); +#174331 = CARTESIAN_POINT('',(2.255,-0.1)); +#174332 = VECTOR('',#174333,1.); +#174333 = DIRECTION('',(-1.,0.E+000)); +#174334 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174335 = ORIENTED_EDGE('',*,*,#174336,.F.); +#174336 = EDGE_CURVE('',#174337,#174309,#174339,.T.); +#174337 = VERTEX_POINT('',#174338); +#174338 = CARTESIAN_POINT('',(0.475,-0.8,0.6)); +#174339 = SURFACE_CURVE('',#174340,(#174344,#174351),.PCURVE_S1.); +#174340 = LINE('',#174341,#174342); +#174341 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174342 = VECTOR('',#174343,1.); +#174343 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174344 = PCURVE('',#174174,#174345); +#174345 = DEFINITIONAL_REPRESENTATION('',(#174346),#174350); +#174346 = LINE('',#174347,#174348); +#174347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174348 = VECTOR('',#174349,1.); +#174349 = DIRECTION('',(0.E+000,1.)); +#174350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174351 = PCURVE('',#174296,#174352); +#174352 = DEFINITIONAL_REPRESENTATION('',(#174353),#174357); +#174353 = LINE('',#174354,#174355); +#174354 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174355 = VECTOR('',#174356,1.); +#174356 = DIRECTION('',(0.E+000,1.)); +#174357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174358 = ORIENTED_EDGE('',*,*,#174359,.F.); +#174359 = EDGE_CURVE('',#174360,#174337,#174362,.T.); +#174360 = VERTEX_POINT('',#174361); +#174361 = CARTESIAN_POINT('',(0.135,-0.8,0.6)); +#174362 = SURFACE_CURVE('',#174363,(#174367,#174374),.PCURVE_S1.); +#174363 = LINE('',#174364,#174365); +#174364 = CARTESIAN_POINT('',(-2.12,-0.8,0.6)); +#174365 = VECTOR('',#174366,1.); +#174366 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174367 = PCURVE('',#174174,#174368); +#174368 = DEFINITIONAL_REPRESENTATION('',(#174369),#174373); +#174369 = LINE('',#174370,#174371); +#174370 = CARTESIAN_POINT('',(1.072393092426E-016,-0.65)); +#174371 = VECTOR('',#174372,1.); +#174372 = DIRECTION('',(0.E+000,1.)); +#174373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174374 = PCURVE('',#174375,#174380); +#174375 = PLANE('',#174376); +#174376 = AXIS2_PLACEMENT_3D('',#174377,#174378,#174379); +#174377 = CARTESIAN_POINT('',(0.135,-0.7,0.6)); +#174378 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174379 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174380 = DEFINITIONAL_REPRESENTATION('',(#174381),#174385); +#174381 = LINE('',#174382,#174383); +#174382 = CARTESIAN_POINT('',(2.255,-0.1)); +#174383 = VECTOR('',#174384,1.); +#174384 = DIRECTION('',(-1.,0.E+000)); +#174385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#171887 = ORIENTED_EDGE('',*,*,#171888,.F.); -#171888 = EDGE_CURVE('',#171889,#171844,#171891,.T.); -#171889 = VERTEX_POINT('',#171890); -#171890 = CARTESIAN_POINT('',(1.125,-0.8,0.6)); -#171891 = SURFACE_CURVE('',#171892,(#171896,#171903),.PCURVE_S1.); -#171892 = LINE('',#171893,#171894); -#171893 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#171894 = VECTOR('',#171895,1.); -#171895 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171896 = PCURVE('',#171782,#171897); -#171897 = DEFINITIONAL_REPRESENTATION('',(#171898),#171902); -#171898 = LINE('',#171899,#171900); -#171899 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171900 = VECTOR('',#171901,1.); -#171901 = DIRECTION('',(0.E+000,1.)); -#171902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171903 = PCURVE('',#171904,#171909); -#171904 = PLANE('',#171905); -#171905 = AXIS2_PLACEMENT_3D('',#171906,#171907,#171908); -#171906 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#171907 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); -#171908 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#171909 = DEFINITIONAL_REPRESENTATION('',(#171910),#171914); -#171910 = LINE('',#171911,#171912); -#171911 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171912 = VECTOR('',#171913,1.); -#171913 = DIRECTION('',(0.E+000,1.)); -#171914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171915 = ORIENTED_EDGE('',*,*,#171916,.F.); -#171916 = EDGE_CURVE('',#171917,#171889,#171919,.T.); -#171917 = VERTEX_POINT('',#171918); -#171918 = CARTESIAN_POINT('',(0.785,-0.8,0.6)); -#171919 = SURFACE_CURVE('',#171920,(#171924,#171931),.PCURVE_S1.); -#171920 = LINE('',#171921,#171922); -#171921 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#171922 = VECTOR('',#171923,1.); -#171923 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171924 = PCURVE('',#171782,#171925); -#171925 = DEFINITIONAL_REPRESENTATION('',(#171926),#171930); -#171926 = LINE('',#171927,#171928); -#171927 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171928 = VECTOR('',#171929,1.); -#171929 = DIRECTION('',(0.E+000,1.)); -#171930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171931 = PCURVE('',#171932,#171937); -#171932 = PLANE('',#171933); -#171933 = AXIS2_PLACEMENT_3D('',#171934,#171935,#171936); -#171934 = CARTESIAN_POINT('',(0.785,-0.7,0.6)); -#171935 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171936 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171937 = DEFINITIONAL_REPRESENTATION('',(#171938),#171942); -#171938 = LINE('',#171939,#171940); -#171939 = CARTESIAN_POINT('',(2.255,-0.1)); -#171940 = VECTOR('',#171941,1.); -#171941 = DIRECTION('',(-1.,0.E+000)); -#171942 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171943 = ORIENTED_EDGE('',*,*,#171944,.F.); -#171944 = EDGE_CURVE('',#171945,#171917,#171947,.T.); -#171945 = VERTEX_POINT('',#171946); -#171946 = CARTESIAN_POINT('',(0.475,-0.8,0.6)); -#171947 = SURFACE_CURVE('',#171948,(#171952,#171959),.PCURVE_S1.); -#171948 = LINE('',#171949,#171950); -#171949 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#171950 = VECTOR('',#171951,1.); -#171951 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171952 = PCURVE('',#171782,#171953); -#171953 = DEFINITIONAL_REPRESENTATION('',(#171954),#171958); -#171954 = LINE('',#171955,#171956); -#171955 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171956 = VECTOR('',#171957,1.); -#171957 = DIRECTION('',(0.E+000,1.)); -#171958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171959 = PCURVE('',#171904,#171960); -#171960 = DEFINITIONAL_REPRESENTATION('',(#171961),#171965); -#171961 = LINE('',#171962,#171963); -#171962 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#171963 = VECTOR('',#171964,1.); -#171964 = DIRECTION('',(0.E+000,1.)); -#171965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171966 = ORIENTED_EDGE('',*,*,#171967,.F.); -#171967 = EDGE_CURVE('',#171968,#171945,#171970,.T.); -#171968 = VERTEX_POINT('',#171969); -#171969 = CARTESIAN_POINT('',(0.135,-0.8,0.6)); -#171970 = SURFACE_CURVE('',#171971,(#171975,#171982),.PCURVE_S1.); -#171971 = LINE('',#171972,#171973); -#171972 = CARTESIAN_POINT('',(-2.12,-0.8,0.6)); -#171973 = VECTOR('',#171974,1.); -#171974 = DIRECTION('',(1.,0.E+000,0.E+000)); -#171975 = PCURVE('',#171782,#171976); -#171976 = DEFINITIONAL_REPRESENTATION('',(#171977),#171981); -#171977 = LINE('',#171978,#171979); -#171978 = CARTESIAN_POINT('',(1.072393092426E-016,-0.65)); -#171979 = VECTOR('',#171980,1.); -#171980 = DIRECTION('',(0.E+000,1.)); -#171981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171982 = PCURVE('',#171983,#171988); -#171983 = PLANE('',#171984); -#171984 = AXIS2_PLACEMENT_3D('',#171985,#171986,#171987); -#171985 = CARTESIAN_POINT('',(0.135,-0.7,0.6)); -#171986 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#171987 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#171988 = DEFINITIONAL_REPRESENTATION('',(#171989),#171993); -#171989 = LINE('',#171990,#171991); -#171990 = CARTESIAN_POINT('',(2.255,-0.1)); -#171991 = VECTOR('',#171992,1.); -#171992 = DIRECTION('',(-1.,0.E+000)); -#171993 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#171994 = ORIENTED_EDGE('',*,*,#171995,.F.); -#171995 = EDGE_CURVE('',#171996,#171968,#171998,.T.); -#171996 = VERTEX_POINT('',#171997); -#171997 = CARTESIAN_POINT('',(-0.175,-0.8,0.6)); -#171998 = SURFACE_CURVE('',#171999,(#172003,#172010),.PCURVE_S1.); -#171999 = LINE('',#172000,#172001); -#172000 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#172001 = VECTOR('',#172002,1.); -#172002 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172003 = PCURVE('',#171782,#172004); -#172004 = DEFINITIONAL_REPRESENTATION('',(#172005),#172009); -#172005 = LINE('',#172006,#172007); -#172006 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172007 = VECTOR('',#172008,1.); -#172008 = DIRECTION('',(0.E+000,1.)); -#172009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172010 = PCURVE('',#171904,#172011); -#172011 = DEFINITIONAL_REPRESENTATION('',(#172012),#172016); -#172012 = LINE('',#172013,#172014); -#172013 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172014 = VECTOR('',#172015,1.); -#172015 = DIRECTION('',(0.E+000,1.)); -#172016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172017 = ORIENTED_EDGE('',*,*,#172018,.F.); -#172018 = EDGE_CURVE('',#172019,#171996,#172021,.T.); -#172019 = VERTEX_POINT('',#172020); -#172020 = CARTESIAN_POINT('',(-0.515,-0.8,0.6)); -#172021 = SURFACE_CURVE('',#172022,(#172026,#172033),.PCURVE_S1.); -#172022 = LINE('',#172023,#172024); -#172023 = CARTESIAN_POINT('',(-2.77,-0.8,0.6)); -#172024 = VECTOR('',#172025,1.); -#172025 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172026 = PCURVE('',#171782,#172027); -#172027 = DEFINITIONAL_REPRESENTATION('',(#172028),#172032); -#172028 = LINE('',#172029,#172030); -#172029 = CARTESIAN_POINT('',(1.072393092426E-016,-1.3)); -#172030 = VECTOR('',#172031,1.); -#172031 = DIRECTION('',(0.E+000,1.)); -#172032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172033 = PCURVE('',#172034,#172039); -#172034 = PLANE('',#172035); -#172035 = AXIS2_PLACEMENT_3D('',#172036,#172037,#172038); -#172036 = CARTESIAN_POINT('',(-0.515,-0.7,0.6)); -#172037 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172038 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172039 = DEFINITIONAL_REPRESENTATION('',(#172040),#172044); -#172040 = LINE('',#172041,#172042); -#172041 = CARTESIAN_POINT('',(2.255,-0.1)); -#172042 = VECTOR('',#172043,1.); -#172043 = DIRECTION('',(-1.,0.E+000)); -#172044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172045 = ORIENTED_EDGE('',*,*,#172046,.F.); -#172046 = EDGE_CURVE('',#172047,#172019,#172049,.T.); -#172047 = VERTEX_POINT('',#172048); -#172048 = CARTESIAN_POINT('',(-0.825,-0.8,0.6)); -#172049 = SURFACE_CURVE('',#172050,(#172054,#172061),.PCURVE_S1.); -#172050 = LINE('',#172051,#172052); -#172051 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#172052 = VECTOR('',#172053,1.); -#172053 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172054 = PCURVE('',#171782,#172055); -#172055 = DEFINITIONAL_REPRESENTATION('',(#172056),#172060); -#172056 = LINE('',#172057,#172058); -#172057 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172058 = VECTOR('',#172059,1.); -#172059 = DIRECTION('',(0.E+000,1.)); -#172060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172061 = PCURVE('',#171904,#172062); -#172062 = DEFINITIONAL_REPRESENTATION('',(#172063),#172067); -#172063 = LINE('',#172064,#172065); -#172064 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172065 = VECTOR('',#172066,1.); -#172066 = DIRECTION('',(0.E+000,1.)); -#172067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172068 = ORIENTED_EDGE('',*,*,#172069,.F.); -#172069 = EDGE_CURVE('',#172070,#172047,#172072,.T.); -#172070 = VERTEX_POINT('',#172071); -#172071 = CARTESIAN_POINT('',(-1.165,-0.8,0.6)); -#172072 = SURFACE_CURVE('',#172073,(#172077,#172084),.PCURVE_S1.); -#172073 = LINE('',#172074,#172075); -#172074 = CARTESIAN_POINT('',(-3.42,-0.8,0.6)); -#172075 = VECTOR('',#172076,1.); -#172076 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172077 = PCURVE('',#171782,#172078); -#172078 = DEFINITIONAL_REPRESENTATION('',(#172079),#172083); -#172079 = LINE('',#172080,#172081); -#172080 = CARTESIAN_POINT('',(2.432133047937E-016,-1.95)); -#172081 = VECTOR('',#172082,1.); -#172082 = DIRECTION('',(0.E+000,1.)); -#172083 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172084 = PCURVE('',#172085,#172090); -#172085 = PLANE('',#172086); -#172086 = AXIS2_PLACEMENT_3D('',#172087,#172088,#172089); -#172087 = CARTESIAN_POINT('',(-1.165,-0.7,0.6)); -#172088 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172089 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172090 = DEFINITIONAL_REPRESENTATION('',(#172091),#172095); -#172091 = LINE('',#172092,#172093); -#172092 = CARTESIAN_POINT('',(2.255,-0.1)); -#172093 = VECTOR('',#172094,1.); -#172094 = DIRECTION('',(-1.,0.E+000)); -#172095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172096 = ORIENTED_EDGE('',*,*,#172097,.F.); -#172097 = EDGE_CURVE('',#171772,#172070,#172098,.T.); -#172098 = SURFACE_CURVE('',#172099,(#172103,#172110),.PCURVE_S1.); -#172099 = LINE('',#172100,#172101); -#172100 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); -#172101 = VECTOR('',#172102,1.); -#172102 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172103 = PCURVE('',#171782,#172104); -#172104 = DEFINITIONAL_REPRESENTATION('',(#172105),#172109); -#172105 = LINE('',#172106,#172107); -#172106 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172107 = VECTOR('',#172108,1.); -#172108 = DIRECTION('',(0.E+000,1.)); -#172109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172110 = PCURVE('',#171904,#172111); -#172111 = DEFINITIONAL_REPRESENTATION('',(#172112),#172116); -#172112 = LINE('',#172113,#172114); -#172113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172114 = VECTOR('',#172115,1.); -#172115 = DIRECTION('',(0.E+000,1.)); -#172116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172117 = ADVANCED_FACE('',(#172118),#172132,.T.); -#172118 = FACE_BOUND('',#172119,.T.); -#172119 = EDGE_LOOP('',(#172120,#172172,#172215,#172260)); -#172120 = ORIENTED_EDGE('',*,*,#172121,.T.); -#172121 = EDGE_CURVE('',#172122,#172124,#172126,.T.); -#172122 = VERTEX_POINT('',#172123); -#172123 = CARTESIAN_POINT('',(-1.47,0.655111126057,0.6)); -#172124 = VERTEX_POINT('',#172125); -#172125 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, +#174386 = ORIENTED_EDGE('',*,*,#174387,.F.); +#174387 = EDGE_CURVE('',#174388,#174360,#174390,.T.); +#174388 = VERTEX_POINT('',#174389); +#174389 = CARTESIAN_POINT('',(-0.175,-0.8,0.6)); +#174390 = SURFACE_CURVE('',#174391,(#174395,#174402),.PCURVE_S1.); +#174391 = LINE('',#174392,#174393); +#174392 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174393 = VECTOR('',#174394,1.); +#174394 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174395 = PCURVE('',#174174,#174396); +#174396 = DEFINITIONAL_REPRESENTATION('',(#174397),#174401); +#174397 = LINE('',#174398,#174399); +#174398 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174399 = VECTOR('',#174400,1.); +#174400 = DIRECTION('',(0.E+000,1.)); +#174401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174402 = PCURVE('',#174296,#174403); +#174403 = DEFINITIONAL_REPRESENTATION('',(#174404),#174408); +#174404 = LINE('',#174405,#174406); +#174405 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174406 = VECTOR('',#174407,1.); +#174407 = DIRECTION('',(0.E+000,1.)); +#174408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174409 = ORIENTED_EDGE('',*,*,#174410,.F.); +#174410 = EDGE_CURVE('',#174411,#174388,#174413,.T.); +#174411 = VERTEX_POINT('',#174412); +#174412 = CARTESIAN_POINT('',(-0.515,-0.8,0.6)); +#174413 = SURFACE_CURVE('',#174414,(#174418,#174425),.PCURVE_S1.); +#174414 = LINE('',#174415,#174416); +#174415 = CARTESIAN_POINT('',(-2.77,-0.8,0.6)); +#174416 = VECTOR('',#174417,1.); +#174417 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174418 = PCURVE('',#174174,#174419); +#174419 = DEFINITIONAL_REPRESENTATION('',(#174420),#174424); +#174420 = LINE('',#174421,#174422); +#174421 = CARTESIAN_POINT('',(1.072393092426E-016,-1.3)); +#174422 = VECTOR('',#174423,1.); +#174423 = DIRECTION('',(0.E+000,1.)); +#174424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174425 = PCURVE('',#174426,#174431); +#174426 = PLANE('',#174427); +#174427 = AXIS2_PLACEMENT_3D('',#174428,#174429,#174430); +#174428 = CARTESIAN_POINT('',(-0.515,-0.7,0.6)); +#174429 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174430 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174431 = DEFINITIONAL_REPRESENTATION('',(#174432),#174436); +#174432 = LINE('',#174433,#174434); +#174433 = CARTESIAN_POINT('',(2.255,-0.1)); +#174434 = VECTOR('',#174435,1.); +#174435 = DIRECTION('',(-1.,0.E+000)); +#174436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174437 = ORIENTED_EDGE('',*,*,#174438,.F.); +#174438 = EDGE_CURVE('',#174439,#174411,#174441,.T.); +#174439 = VERTEX_POINT('',#174440); +#174440 = CARTESIAN_POINT('',(-0.825,-0.8,0.6)); +#174441 = SURFACE_CURVE('',#174442,(#174446,#174453),.PCURVE_S1.); +#174442 = LINE('',#174443,#174444); +#174443 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174444 = VECTOR('',#174445,1.); +#174445 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174446 = PCURVE('',#174174,#174447); +#174447 = DEFINITIONAL_REPRESENTATION('',(#174448),#174452); +#174448 = LINE('',#174449,#174450); +#174449 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174450 = VECTOR('',#174451,1.); +#174451 = DIRECTION('',(0.E+000,1.)); +#174452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174453 = PCURVE('',#174296,#174454); +#174454 = DEFINITIONAL_REPRESENTATION('',(#174455),#174459); +#174455 = LINE('',#174456,#174457); +#174456 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174457 = VECTOR('',#174458,1.); +#174458 = DIRECTION('',(0.E+000,1.)); +#174459 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174460 = ORIENTED_EDGE('',*,*,#174461,.F.); +#174461 = EDGE_CURVE('',#174462,#174439,#174464,.T.); +#174462 = VERTEX_POINT('',#174463); +#174463 = CARTESIAN_POINT('',(-1.165,-0.8,0.6)); +#174464 = SURFACE_CURVE('',#174465,(#174469,#174476),.PCURVE_S1.); +#174465 = LINE('',#174466,#174467); +#174466 = CARTESIAN_POINT('',(-3.42,-0.8,0.6)); +#174467 = VECTOR('',#174468,1.); +#174468 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174469 = PCURVE('',#174174,#174470); +#174470 = DEFINITIONAL_REPRESENTATION('',(#174471),#174475); +#174471 = LINE('',#174472,#174473); +#174472 = CARTESIAN_POINT('',(2.432133047937E-016,-1.95)); +#174473 = VECTOR('',#174474,1.); +#174474 = DIRECTION('',(0.E+000,1.)); +#174475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174476 = PCURVE('',#174477,#174482); +#174477 = PLANE('',#174478); +#174478 = AXIS2_PLACEMENT_3D('',#174479,#174480,#174481); +#174479 = CARTESIAN_POINT('',(-1.165,-0.7,0.6)); +#174480 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174481 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174482 = DEFINITIONAL_REPRESENTATION('',(#174483),#174487); +#174483 = LINE('',#174484,#174485); +#174484 = CARTESIAN_POINT('',(2.255,-0.1)); +#174485 = VECTOR('',#174486,1.); +#174486 = DIRECTION('',(-1.,0.E+000)); +#174487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174488 = ORIENTED_EDGE('',*,*,#174489,.F.); +#174489 = EDGE_CURVE('',#174164,#174462,#174490,.T.); +#174490 = SURFACE_CURVE('',#174491,(#174495,#174502),.PCURVE_S1.); +#174491 = LINE('',#174492,#174493); +#174492 = CARTESIAN_POINT('',(-1.47,-0.8,0.6)); +#174493 = VECTOR('',#174494,1.); +#174494 = DIRECTION('',(1.,0.E+000,0.E+000)); +#174495 = PCURVE('',#174174,#174496); +#174496 = DEFINITIONAL_REPRESENTATION('',(#174497),#174501); +#174497 = LINE('',#174498,#174499); +#174498 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174499 = VECTOR('',#174500,1.); +#174500 = DIRECTION('',(0.E+000,1.)); +#174501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174502 = PCURVE('',#174296,#174503); +#174503 = DEFINITIONAL_REPRESENTATION('',(#174504),#174508); +#174504 = LINE('',#174505,#174506); +#174505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174506 = VECTOR('',#174507,1.); +#174507 = DIRECTION('',(0.E+000,1.)); +#174508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174509 = ADVANCED_FACE('',(#174510),#174524,.T.); +#174510 = FACE_BOUND('',#174511,.T.); +#174511 = EDGE_LOOP('',(#174512,#174564,#174607,#174652)); +#174512 = ORIENTED_EDGE('',*,*,#174513,.T.); +#174513 = EDGE_CURVE('',#174514,#174516,#174518,.T.); +#174514 = VERTEX_POINT('',#174515); +#174515 = CARTESIAN_POINT('',(-1.47,0.655111126057,0.6)); +#174516 = VERTEX_POINT('',#174517); +#174517 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, 0.137059047745)); -#172126 = SURFACE_CURVE('',#172127,(#172131,#172143),.PCURVE_S1.); -#172127 = LINE('',#172128,#172129); -#172128 = CARTESIAN_POINT('',(-1.479096372758,0.664207498814, +#174518 = SURFACE_CURVE('',#174519,(#174523,#174535),.PCURVE_S1.); +#174519 = LINE('',#174520,#174521); +#174520 = CARTESIAN_POINT('',(-1.479096372758,0.664207498814, 0.633948125296)); -#172129 = VECTOR('',#172130,1.); -#172130 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) - ); -#172131 = PCURVE('',#172132,#172137); -#172132 = PLANE('',#172133); -#172133 = AXIS2_PLACEMENT_3D('',#172134,#172135,#172136); -#172134 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#172135 = DIRECTION('',(-0.965925826289,-1.309073599153E-016, +#174521 = VECTOR('',#174522,1.); +#174522 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) + ); +#174523 = PCURVE('',#174524,#174529); +#174524 = PLANE('',#174525); +#174525 = AXIS2_PLACEMENT_3D('',#174526,#174527,#174528); +#174526 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#174527 = DIRECTION('',(-0.965925826289,-1.309073599153E-016, -0.258819045103)); -#172136 = DIRECTION('',(-0.258819045103,5.910197516838E-033, +#174528 = DIRECTION('',(-0.258819045103,5.910197516838E-033, 0.965925826289)); -#172137 = DEFINITIONAL_REPRESENTATION('',(#172138),#172142); -#172138 = LINE('',#172139,#172140); -#172139 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#172140 = VECTOR('',#172141,1.); -#172141 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#172142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172143 = PCURVE('',#169686,#172144); -#172144 = DEFINITIONAL_REPRESENTATION('',(#172145),#172171); -#172145 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172146,#172147,#172148, - #172149,#172150,#172151,#172152,#172153,#172154,#172155,#172156, - #172157,#172158,#172159,#172160,#172161,#172162,#172163,#172164, - #172165,#172166,#172167,#172168,#172169,#172170),.UNSPECIFIED.,.F., +#174529 = DEFINITIONAL_REPRESENTATION('',(#174530),#174534); +#174530 = LINE('',#174531,#174532); +#174531 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#174532 = VECTOR('',#174533,1.); +#174533 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#174534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174535 = PCURVE('',#172078,#174536); +#174536 = DEFINITIONAL_REPRESENTATION('',(#174537),#174563); +#174537 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174538,#174539,#174540, + #174541,#174542,#174543,#174544,#174545,#174546,#174547,#174548, + #174549,#174550,#174551,#174552,#174553,#174554,#174555,#174556, + #174557,#174558,#174559,#174560,#174561,#174562),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,5.880667728135E-002,8.130959159195E-002, 0.103812505903,0.126315420213,0.148818334524,0.171321248834, @@ -212927,57 +215929,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.37384747763,0.39635039194,0.418853306251,0.441356220562, 0.463859134872,0.486362049183,0.508864963493,0.531367877804), .QUASI_UNIFORM_KNOTS.); -#172146 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#172147 = CARTESIAN_POINT('',(3.14159265359,-4.380473440761E-002)); -#172148 = CARTESIAN_POINT('',(3.14159265359,-5.880667728135E-002)); -#172149 = CARTESIAN_POINT('',(3.14159265359,-8.130959159195E-002)); -#172150 = CARTESIAN_POINT('',(3.14159265359,-0.103812505903)); -#172151 = CARTESIAN_POINT('',(3.14159265359,-0.126315420213)); -#172152 = CARTESIAN_POINT('',(3.14159265359,-0.148818334524)); -#172153 = CARTESIAN_POINT('',(3.14159265359,-0.171321248834)); -#172154 = CARTESIAN_POINT('',(3.14159265359,-0.193824163145)); -#172155 = CARTESIAN_POINT('',(3.14159265359,-0.216327077456)); -#172156 = CARTESIAN_POINT('',(3.14159265359,-0.238829991766)); -#172157 = CARTESIAN_POINT('',(3.14159265359,-0.261332906077)); -#172158 = CARTESIAN_POINT('',(3.14159265359,-0.283835820387)); -#172159 = CARTESIAN_POINT('',(3.14159265359,-0.306338734698)); -#172160 = CARTESIAN_POINT('',(3.14159265359,-0.328841649009)); -#172161 = CARTESIAN_POINT('',(3.14159265359,-0.351344563319)); -#172162 = CARTESIAN_POINT('',(3.14159265359,-0.37384747763)); -#172163 = CARTESIAN_POINT('',(3.14159265359,-0.39635039194)); -#172164 = CARTESIAN_POINT('',(3.14159265359,-0.418853306251)); -#172165 = CARTESIAN_POINT('',(3.14159265359,-0.441356220562)); -#172166 = CARTESIAN_POINT('',(3.14159265359,-0.463859134872)); -#172167 = CARTESIAN_POINT('',(3.14159265359,-0.486362049183)); -#172168 = CARTESIAN_POINT('',(3.14159265359,-0.508864963493)); -#172169 = CARTESIAN_POINT('',(3.14159265359,-0.523866906367)); -#172170 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#172171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172172 = ORIENTED_EDGE('',*,*,#172173,.T.); -#172173 = EDGE_CURVE('',#172124,#169098,#172174,.T.); -#172174 = SURFACE_CURVE('',#172175,(#172179,#172186),.PCURVE_S1.); -#172175 = LINE('',#172176,#172177); -#172176 = CARTESIAN_POINT('',(-1.3459553457,-0.521136529841, +#174538 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#174539 = CARTESIAN_POINT('',(3.14159265359,-4.380473440761E-002)); +#174540 = CARTESIAN_POINT('',(3.14159265359,-5.880667728135E-002)); +#174541 = CARTESIAN_POINT('',(3.14159265359,-8.130959159195E-002)); +#174542 = CARTESIAN_POINT('',(3.14159265359,-0.103812505903)); +#174543 = CARTESIAN_POINT('',(3.14159265359,-0.126315420213)); +#174544 = CARTESIAN_POINT('',(3.14159265359,-0.148818334524)); +#174545 = CARTESIAN_POINT('',(3.14159265359,-0.171321248834)); +#174546 = CARTESIAN_POINT('',(3.14159265359,-0.193824163145)); +#174547 = CARTESIAN_POINT('',(3.14159265359,-0.216327077456)); +#174548 = CARTESIAN_POINT('',(3.14159265359,-0.238829991766)); +#174549 = CARTESIAN_POINT('',(3.14159265359,-0.261332906077)); +#174550 = CARTESIAN_POINT('',(3.14159265359,-0.283835820387)); +#174551 = CARTESIAN_POINT('',(3.14159265359,-0.306338734698)); +#174552 = CARTESIAN_POINT('',(3.14159265359,-0.328841649009)); +#174553 = CARTESIAN_POINT('',(3.14159265359,-0.351344563319)); +#174554 = CARTESIAN_POINT('',(3.14159265359,-0.37384747763)); +#174555 = CARTESIAN_POINT('',(3.14159265359,-0.39635039194)); +#174556 = CARTESIAN_POINT('',(3.14159265359,-0.418853306251)); +#174557 = CARTESIAN_POINT('',(3.14159265359,-0.441356220562)); +#174558 = CARTESIAN_POINT('',(3.14159265359,-0.463859134872)); +#174559 = CARTESIAN_POINT('',(3.14159265359,-0.486362049183)); +#174560 = CARTESIAN_POINT('',(3.14159265359,-0.508864963493)); +#174561 = CARTESIAN_POINT('',(3.14159265359,-0.523866906367)); +#174562 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#174563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174564 = ORIENTED_EDGE('',*,*,#174565,.T.); +#174565 = EDGE_CURVE('',#174516,#171490,#174566,.T.); +#174566 = SURFACE_CURVE('',#174567,(#174571,#174578),.PCURVE_S1.); +#174567 = LINE('',#174568,#174569); +#174568 = CARTESIAN_POINT('',(-1.3459553457,-0.521136529841, 0.137059047745)); -#172177 = VECTOR('',#172178,1.); -#172178 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#172179 = PCURVE('',#172132,#172180); -#172180 = DEFINITIONAL_REPRESENTATION('',(#172181),#172185); -#172181 = LINE('',#172182,#172183); -#172182 = CARTESIAN_POINT('',(-0.479271740806,-1.321136529841)); -#172183 = VECTOR('',#172184,1.); -#172184 = DIRECTION('',(-3.50765213726E-017,-1.)); -#172185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172186 = PCURVE('',#169207,#172187); -#172187 = DEFINITIONAL_REPRESENTATION('',(#172188),#172214); -#172188 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172189,#172190,#172191, - #172192,#172193,#172194,#172195,#172196,#172197,#172198,#172199, - #172200,#172201,#172202,#172203,#172204,#172205,#172206,#172207, - #172208,#172209,#172210,#172211,#172212,#172213),.UNSPECIFIED.,.F., +#174569 = VECTOR('',#174570,1.); +#174570 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#174571 = PCURVE('',#174524,#174572); +#174572 = DEFINITIONAL_REPRESENTATION('',(#174573),#174577); +#174573 = LINE('',#174574,#174575); +#174574 = CARTESIAN_POINT('',(-0.479271740806,-1.321136529841)); +#174575 = VECTOR('',#174576,1.); +#174576 = DIRECTION('',(-3.50765213726E-017,-1.)); +#174577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174578 = PCURVE('',#171599,#174579); +#174579 = DEFINITIONAL_REPRESENTATION('',(#174580),#174606); +#174580 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174581,#174582,#174583, + #174584,#174585,#174586,#174587,#174588,#174589,#174590,#174591, + #174592,#174593,#174594,#174595,#174596,#174597,#174598,#174599, + #174600,#174601,#174602,#174603,#174604,#174605),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-1.052203001598, -1.003924231438,-0.955645461278,-0.907366691119,-0.859087920959, -0.810809150799,-0.76253038064,-0.71425161048,-0.66597284032, @@ -212985,60 +215987,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.424578989522,-0.376300219362,-0.328021449202,-0.279742679043, -0.231463908883,-0.183185138723,-0.134906368564,-8.662759840387E-002 ,-3.834882824418E-002,9.929941915506E-003),.UNSPECIFIED.); -#172189 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#172190 = CARTESIAN_POINT('',(6.02138591938,-0.28502645163)); -#172191 = CARTESIAN_POINT('',(6.02138591938,-0.317212298403)); -#172192 = CARTESIAN_POINT('',(6.02138591938,-0.365491068563)); -#172193 = CARTESIAN_POINT('',(6.02138591938,-0.413769838722)); -#172194 = CARTESIAN_POINT('',(6.02138591938,-0.462048608882)); -#172195 = CARTESIAN_POINT('',(6.02138591938,-0.510327379042)); -#172196 = CARTESIAN_POINT('',(6.02138591938,-0.558606149202)); -#172197 = CARTESIAN_POINT('',(6.02138591938,-0.606884919361)); -#172198 = CARTESIAN_POINT('',(6.02138591938,-0.655163689521)); -#172199 = CARTESIAN_POINT('',(6.02138591938,-0.703442459681)); -#172200 = CARTESIAN_POINT('',(6.02138591938,-0.75172122984)); -#172201 = CARTESIAN_POINT('',(6.02138591938,-0.8)); -#172202 = CARTESIAN_POINT('',(6.02138591938,-0.84827877016)); -#172203 = CARTESIAN_POINT('',(6.02138591938,-0.896557540319)); -#172204 = CARTESIAN_POINT('',(6.02138591938,-0.944836310479)); -#172205 = CARTESIAN_POINT('',(6.02138591938,-0.993115080639)); -#172206 = CARTESIAN_POINT('',(6.02138591938,-1.041393850798)); -#172207 = CARTESIAN_POINT('',(6.02138591938,-1.089672620958)); -#172208 = CARTESIAN_POINT('',(6.02138591938,-1.137951391118)); -#172209 = CARTESIAN_POINT('',(6.02138591938,-1.186230161278)); -#172210 = CARTESIAN_POINT('',(6.02138591938,-1.234508931437)); -#172211 = CARTESIAN_POINT('',(6.02138591938,-1.282787701597)); -#172212 = CARTESIAN_POINT('',(6.02138591938,-1.31497354837)); -#172213 = CARTESIAN_POINT('',(6.02138591938,-1.331066471757)); -#172214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172215 = ORIENTED_EDGE('',*,*,#172216,.T.); -#172216 = EDGE_CURVE('',#169098,#172217,#172219,.T.); -#172217 = VERTEX_POINT('',#172218); -#172218 = CARTESIAN_POINT('',(-1.47,-0.655111126057,0.6)); -#172219 = SURFACE_CURVE('',#172220,(#172224,#172231),.PCURVE_S1.); -#172220 = LINE('',#172221,#172222); -#172221 = CARTESIAN_POINT('',(-1.378645620286,-0.563756746343, +#174581 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#174582 = CARTESIAN_POINT('',(6.02138591938,-0.28502645163)); +#174583 = CARTESIAN_POINT('',(6.02138591938,-0.317212298403)); +#174584 = CARTESIAN_POINT('',(6.02138591938,-0.365491068563)); +#174585 = CARTESIAN_POINT('',(6.02138591938,-0.413769838722)); +#174586 = CARTESIAN_POINT('',(6.02138591938,-0.462048608882)); +#174587 = CARTESIAN_POINT('',(6.02138591938,-0.510327379042)); +#174588 = CARTESIAN_POINT('',(6.02138591938,-0.558606149202)); +#174589 = CARTESIAN_POINT('',(6.02138591938,-0.606884919361)); +#174590 = CARTESIAN_POINT('',(6.02138591938,-0.655163689521)); +#174591 = CARTESIAN_POINT('',(6.02138591938,-0.703442459681)); +#174592 = CARTESIAN_POINT('',(6.02138591938,-0.75172122984)); +#174593 = CARTESIAN_POINT('',(6.02138591938,-0.8)); +#174594 = CARTESIAN_POINT('',(6.02138591938,-0.84827877016)); +#174595 = CARTESIAN_POINT('',(6.02138591938,-0.896557540319)); +#174596 = CARTESIAN_POINT('',(6.02138591938,-0.944836310479)); +#174597 = CARTESIAN_POINT('',(6.02138591938,-0.993115080639)); +#174598 = CARTESIAN_POINT('',(6.02138591938,-1.041393850798)); +#174599 = CARTESIAN_POINT('',(6.02138591938,-1.089672620958)); +#174600 = CARTESIAN_POINT('',(6.02138591938,-1.137951391118)); +#174601 = CARTESIAN_POINT('',(6.02138591938,-1.186230161278)); +#174602 = CARTESIAN_POINT('',(6.02138591938,-1.234508931437)); +#174603 = CARTESIAN_POINT('',(6.02138591938,-1.282787701597)); +#174604 = CARTESIAN_POINT('',(6.02138591938,-1.31497354837)); +#174605 = CARTESIAN_POINT('',(6.02138591938,-1.331066471757)); +#174606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174607 = ORIENTED_EDGE('',*,*,#174608,.T.); +#174608 = EDGE_CURVE('',#171490,#174609,#174611,.T.); +#174609 = VERTEX_POINT('',#174610); +#174610 = CARTESIAN_POINT('',(-1.47,-0.655111126057,0.6)); +#174611 = SURFACE_CURVE('',#174612,(#174616,#174623),.PCURVE_S1.); +#174612 = LINE('',#174613,#174614); +#174613 = CARTESIAN_POINT('',(-1.378645620286,-0.563756746343, 0.259060813414)); -#172222 = VECTOR('',#172223,1.); -#172223 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) - ); -#172224 = PCURVE('',#172132,#172225); -#172225 = DEFINITIONAL_REPRESENTATION('',(#172226),#172230); -#172226 = LINE('',#172227,#172228); -#172227 = CARTESIAN_POINT('',(-0.352966218841,-1.363756746343)); -#172228 = VECTOR('',#172229,1.); -#172229 = DIRECTION('',(0.968100345886,-0.250562807086)); -#172230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172231 = PCURVE('',#169136,#172232); -#172232 = DEFINITIONAL_REPRESENTATION('',(#172233),#172259); -#172233 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172234,#172235,#172236, - #172237,#172238,#172239,#172240,#172241,#172242,#172243,#172244, - #172245,#172246,#172247,#172248,#172249,#172250,#172251,#172252, - #172253,#172254,#172255,#172256,#172257,#172258),.UNSPECIFIED.,.F., +#174614 = VECTOR('',#174615,1.); +#174615 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) + ); +#174616 = PCURVE('',#174524,#174617); +#174617 = DEFINITIONAL_REPRESENTATION('',(#174618),#174622); +#174618 = LINE('',#174619,#174620); +#174619 = CARTESIAN_POINT('',(-0.352966218841,-1.363756746343)); +#174620 = VECTOR('',#174621,1.); +#174621 = DIRECTION('',(0.968100345886,-0.250562807086)); +#174622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174623 = PCURVE('',#171528,#174624); +#174624 = DEFINITIONAL_REPRESENTATION('',(#174625),#174651); +#174625 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174626,#174627,#174628, + #174629,#174630,#174631,#174632,#174633,#174634,#174635,#174636, + #174637,#174638,#174639,#174640,#174641,#174642,#174643,#174644, + #174645,#174646,#174647,#174648,#174649,#174650),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.130467386467, -0.107964472156,-8.54615578457E-002,-6.295864353509E-002, -4.045572922449E-002,-1.795281491388E-002,4.550099396726E-003, @@ -213047,97 +216049,97 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.184573413882,0.207076328192,0.229579242503,0.252082156813, 0.274585071124,0.297087985435,0.319590899745,0.342093814056, 0.364596728366),.UNSPECIFIED.); -#172234 = CARTESIAN_POINT('',(3.14159265359,-0.130467386467)); -#172235 = CARTESIAN_POINT('',(3.14159265359,-0.12296641503)); -#172236 = CARTESIAN_POINT('',(3.14159265359,-0.107964472156)); -#172237 = CARTESIAN_POINT('',(3.14159265359,-8.54615578457E-002)); -#172238 = CARTESIAN_POINT('',(3.14159265359,-6.295864353509E-002)); -#172239 = CARTESIAN_POINT('',(3.14159265359,-4.045572922449E-002)); -#172240 = CARTESIAN_POINT('',(3.14159265359,-1.795281491388E-002)); -#172241 = CARTESIAN_POINT('',(3.14159265359,4.550099396726E-003)); -#172242 = CARTESIAN_POINT('',(3.14159265359,2.705301370733E-002)); -#172243 = CARTESIAN_POINT('',(3.14159265359,4.955592801794E-002)); -#172244 = CARTESIAN_POINT('',(3.14159265359,7.205884232855E-002)); -#172245 = CARTESIAN_POINT('',(3.14159265359,9.456175663915E-002)); -#172246 = CARTESIAN_POINT('',(3.14159265359,0.11706467095)); -#172247 = CARTESIAN_POINT('',(3.14159265359,0.13956758526)); -#172248 = CARTESIAN_POINT('',(3.14159265359,0.162070499571)); -#172249 = CARTESIAN_POINT('',(3.14159265359,0.184573413882)); -#172250 = CARTESIAN_POINT('',(3.14159265359,0.207076328192)); -#172251 = CARTESIAN_POINT('',(3.14159265359,0.229579242503)); -#172252 = CARTESIAN_POINT('',(3.14159265359,0.252082156813)); -#172253 = CARTESIAN_POINT('',(3.14159265359,0.274585071124)); -#172254 = CARTESIAN_POINT('',(3.14159265359,0.297087985435)); -#172255 = CARTESIAN_POINT('',(3.14159265359,0.319590899745)); -#172256 = CARTESIAN_POINT('',(3.14159265359,0.342093814056)); -#172257 = CARTESIAN_POINT('',(3.14159265359,0.35709575693)); -#172258 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); -#172259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172260 = ORIENTED_EDGE('',*,*,#172261,.F.); -#172261 = EDGE_CURVE('',#172122,#172217,#172262,.T.); -#172262 = SURFACE_CURVE('',#172263,(#172267,#172274),.PCURVE_S1.); -#172263 = LINE('',#172264,#172265); -#172264 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#172265 = VECTOR('',#172266,1.); -#172266 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#172267 = PCURVE('',#172132,#172268); -#172268 = DEFINITIONAL_REPRESENTATION('',(#172269),#172273); -#172269 = LINE('',#172270,#172271); -#172270 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172271 = VECTOR('',#172272,1.); -#172272 = DIRECTION('',(-3.50765213726E-017,-1.)); -#172273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172274 = PCURVE('',#172275,#172280); -#172275 = PLANE('',#172276); -#172276 = AXIS2_PLACEMENT_3D('',#172277,#172278,#172279); -#172277 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#172278 = DIRECTION('',(-0.965925826289,-1.309073599153E-016, +#174626 = CARTESIAN_POINT('',(3.14159265359,-0.130467386467)); +#174627 = CARTESIAN_POINT('',(3.14159265359,-0.12296641503)); +#174628 = CARTESIAN_POINT('',(3.14159265359,-0.107964472156)); +#174629 = CARTESIAN_POINT('',(3.14159265359,-8.54615578457E-002)); +#174630 = CARTESIAN_POINT('',(3.14159265359,-6.295864353509E-002)); +#174631 = CARTESIAN_POINT('',(3.14159265359,-4.045572922449E-002)); +#174632 = CARTESIAN_POINT('',(3.14159265359,-1.795281491388E-002)); +#174633 = CARTESIAN_POINT('',(3.14159265359,4.550099396726E-003)); +#174634 = CARTESIAN_POINT('',(3.14159265359,2.705301370733E-002)); +#174635 = CARTESIAN_POINT('',(3.14159265359,4.955592801794E-002)); +#174636 = CARTESIAN_POINT('',(3.14159265359,7.205884232855E-002)); +#174637 = CARTESIAN_POINT('',(3.14159265359,9.456175663915E-002)); +#174638 = CARTESIAN_POINT('',(3.14159265359,0.11706467095)); +#174639 = CARTESIAN_POINT('',(3.14159265359,0.13956758526)); +#174640 = CARTESIAN_POINT('',(3.14159265359,0.162070499571)); +#174641 = CARTESIAN_POINT('',(3.14159265359,0.184573413882)); +#174642 = CARTESIAN_POINT('',(3.14159265359,0.207076328192)); +#174643 = CARTESIAN_POINT('',(3.14159265359,0.229579242503)); +#174644 = CARTESIAN_POINT('',(3.14159265359,0.252082156813)); +#174645 = CARTESIAN_POINT('',(3.14159265359,0.274585071124)); +#174646 = CARTESIAN_POINT('',(3.14159265359,0.297087985435)); +#174647 = CARTESIAN_POINT('',(3.14159265359,0.319590899745)); +#174648 = CARTESIAN_POINT('',(3.14159265359,0.342093814056)); +#174649 = CARTESIAN_POINT('',(3.14159265359,0.35709575693)); +#174650 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); +#174651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174652 = ORIENTED_EDGE('',*,*,#174653,.F.); +#174653 = EDGE_CURVE('',#174514,#174609,#174654,.T.); +#174654 = SURFACE_CURVE('',#174655,(#174659,#174666),.PCURVE_S1.); +#174655 = LINE('',#174656,#174657); +#174656 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#174657 = VECTOR('',#174658,1.); +#174658 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#174659 = PCURVE('',#174524,#174660); +#174660 = DEFINITIONAL_REPRESENTATION('',(#174661),#174665); +#174661 = LINE('',#174662,#174663); +#174662 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174663 = VECTOR('',#174664,1.); +#174664 = DIRECTION('',(-3.50765213726E-017,-1.)); +#174665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174666 = PCURVE('',#174667,#174672); +#174667 = PLANE('',#174668); +#174668 = AXIS2_PLACEMENT_3D('',#174669,#174670,#174671); +#174669 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#174670 = DIRECTION('',(-0.965925826289,-1.309073599153E-016, 0.258819045103)); -#172279 = DIRECTION('',(0.258819045103,-5.910197516838E-033, +#174671 = DIRECTION('',(0.258819045103,-5.910197516838E-033, 0.965925826289)); -#172280 = DEFINITIONAL_REPRESENTATION('',(#172281),#172285); -#172281 = LINE('',#172282,#172283); -#172282 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172283 = VECTOR('',#172284,1.); -#172284 = DIRECTION('',(3.50765213726E-017,-1.)); -#172285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172286 = ADVANCED_FACE('',(#172287),#171079,.T.); -#172287 = FACE_BOUND('',#172288,.T.); -#172288 = EDGE_LOOP('',(#172289,#172334,#172354,#172397,#172398,#172424, - #172425,#172451,#172452,#172478,#172479,#172505)); -#172289 = ORIENTED_EDGE('',*,*,#172290,.T.); -#172290 = EDGE_CURVE('',#171157,#172291,#172293,.T.); -#172291 = VERTEX_POINT('',#172292); -#172292 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 +#174672 = DEFINITIONAL_REPRESENTATION('',(#174673),#174677); +#174673 = LINE('',#174674,#174675); +#174674 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174675 = VECTOR('',#174676,1.); +#174676 = DIRECTION('',(3.50765213726E-017,-1.)); +#174677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174678 = ADVANCED_FACE('',(#174679),#173471,.T.); +#174679 = FACE_BOUND('',#174680,.T.); +#174680 = EDGE_LOOP('',(#174681,#174726,#174746,#174789,#174790,#174816, + #174817,#174843,#174844,#174870,#174871,#174897)); +#174681 = ORIENTED_EDGE('',*,*,#174682,.T.); +#174682 = EDGE_CURVE('',#173549,#174683,#174685,.T.); +#174683 = VERTEX_POINT('',#174684); +#174684 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 )); -#172293 = SURFACE_CURVE('',#172294,(#172298,#172305),.PCURVE_S1.); -#172294 = LINE('',#172295,#172296); -#172295 = CARTESIAN_POINT('',(1.149629241148,0.624518115091, +#174685 = SURFACE_CURVE('',#174686,(#174690,#174697),.PCURVE_S1.); +#174686 = LINE('',#174687,#174688); +#174687 = CARTESIAN_POINT('',(1.149629241148,0.624518115091, -5.4907310287E-002)); -#172296 = VECTOR('',#172297,1.); -#172297 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#172298 = PCURVE('',#171079,#172299); -#172299 = DEFINITIONAL_REPRESENTATION('',(#172300),#172304); -#172300 = LINE('',#172301,#172302); -#172301 = CARTESIAN_POINT('',(-0.678009938717,2.619629241148)); -#172302 = VECTOR('',#172303,1.); -#172303 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#172304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172305 = PCURVE('',#169411,#172306); -#172306 = DEFINITIONAL_REPRESENTATION('',(#172307),#172333); -#172307 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172308,#172309,#172310, - #172311,#172312,#172313,#172314,#172315,#172316,#172317,#172318, - #172319,#172320,#172321,#172322,#172323,#172324,#172325,#172326, - #172327,#172328,#172329,#172330,#172331,#172332),.UNSPECIFIED.,.F., +#174688 = VECTOR('',#174689,1.); +#174689 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#174690 = PCURVE('',#173471,#174691); +#174691 = DEFINITIONAL_REPRESENTATION('',(#174692),#174696); +#174692 = LINE('',#174693,#174694); +#174693 = CARTESIAN_POINT('',(-0.678009938717,2.619629241148)); +#174694 = VECTOR('',#174695,1.); +#174695 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#174696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174697 = PCURVE('',#171803,#174698); +#174698 = DEFINITIONAL_REPRESENTATION('',(#174699),#174725); +#174699 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174700,#174701,#174702, + #174703,#174704,#174705,#174706,#174707,#174708,#174709,#174710, + #174711,#174712,#174713,#174714,#174715,#174716,#174717,#174718, + #174719,#174720,#174721,#174722,#174723,#174724),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.700350889861, -0.677847975551,-0.65534506124,-0.632842146929,-0.610339232619, -0.587836318308,-0.565333403998,-0.542830489687,-0.520327575376, @@ -213145,84 +216147,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.407813003823,-0.385310089513,-0.362807175202,-0.340304260892, -0.317801346581,-0.29529843227,-0.27279551796,-0.250292603649, -0.227789689339,-0.205286775028),.QUASI_UNIFORM_KNOTS.); -#172308 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#172309 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); -#172310 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); -#172311 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); -#172312 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); -#172313 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); -#172314 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); -#172315 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); -#172316 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); -#172317 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); -#172318 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); -#172319 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); -#172320 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); -#172321 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); -#172322 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); -#172323 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); -#172324 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); -#172325 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); -#172326 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); -#172327 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); -#172328 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); -#172329 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); -#172330 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); -#172331 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); -#172332 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#172333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172334 = ORIENTED_EDGE('',*,*,#172335,.T.); -#172335 = EDGE_CURVE('',#172291,#169648,#172336,.T.); -#172336 = SURFACE_CURVE('',#172337,(#172341,#172348),.PCURVE_S1.); -#172337 = LINE('',#172338,#172339); -#172338 = CARTESIAN_POINT('',(-1.191136529841,0.6759553457, +#174700 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#174701 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); +#174702 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); +#174703 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); +#174704 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); +#174705 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); +#174706 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); +#174707 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); +#174708 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); +#174709 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); +#174710 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); +#174711 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); +#174712 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); +#174713 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); +#174714 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); +#174715 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); +#174716 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); +#174717 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); +#174718 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); +#174719 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); +#174720 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); +#174721 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); +#174722 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); +#174723 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); +#174724 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#174725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174726 = ORIENTED_EDGE('',*,*,#174727,.T.); +#174727 = EDGE_CURVE('',#174683,#172040,#174728,.T.); +#174728 = SURFACE_CURVE('',#174729,(#174733,#174740),.PCURVE_S1.); +#174729 = LINE('',#174730,#174731); +#174730 = CARTESIAN_POINT('',(-1.191136529841,0.6759553457, 0.137059047745)); -#172339 = VECTOR('',#172340,1.); -#172340 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172341 = PCURVE('',#171079,#172342); -#172342 = DEFINITIONAL_REPRESENTATION('',(#172343),#172347); -#172343 = LINE('',#172344,#172345); -#172344 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); -#172345 = VECTOR('',#172346,1.); -#172346 = DIRECTION('',(0.E+000,-1.)); -#172347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172348 = PCURVE('',#169757,#172349); -#172349 = DEFINITIONAL_REPRESENTATION('',(#172350),#172353); -#172350 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172351,#172352), +#174731 = VECTOR('',#174732,1.); +#174732 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174733 = PCURVE('',#173471,#174734); +#174734 = DEFINITIONAL_REPRESENTATION('',(#174735),#174739); +#174735 = LINE('',#174736,#174737); +#174736 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); +#174737 = VECTOR('',#174738,1.); +#174738 = DIRECTION('',(0.E+000,-1.)); +#174739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174740 = PCURVE('',#172149,#174741); +#174741 = DEFINITIONAL_REPRESENTATION('',(#174742),#174745); +#174742 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174743,#174744), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.392203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#172351 = CARTESIAN_POINT('',(1.308996938996,2.671066471757)); -#172352 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#172353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#174743 = CARTESIAN_POINT('',(1.308996938996,2.671066471757)); +#174744 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#174745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#172354 = ORIENTED_EDGE('',*,*,#172355,.T.); -#172355 = EDGE_CURVE('',#169648,#171064,#172356,.T.); -#172356 = SURFACE_CURVE('',#172357,(#172361,#172368),.PCURVE_S1.); -#172357 = LINE('',#172358,#172359); -#172358 = CARTESIAN_POINT('',(-1.334207498814,0.809096372758, +#174746 = ORIENTED_EDGE('',*,*,#174747,.T.); +#174747 = EDGE_CURVE('',#172040,#173456,#174748,.T.); +#174748 = SURFACE_CURVE('',#174749,(#174753,#174760),.PCURVE_S1.); +#174749 = LINE('',#174750,#174751); +#174750 = CARTESIAN_POINT('',(-1.334207498814,0.809096372758, 0.633948125296)); -#172359 = VECTOR('',#172360,1.); -#172360 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#172361 = PCURVE('',#171079,#172362); -#172362 = DEFINITIONAL_REPRESENTATION('',(#172363),#172367); -#172363 = LINE('',#172364,#172365); -#172364 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#172365 = VECTOR('',#172366,1.); -#172366 = DIRECTION('',(0.968100345886,-0.250562807086)); -#172367 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172368 = PCURVE('',#169686,#172369); -#172369 = DEFINITIONAL_REPRESENTATION('',(#172370),#172396); -#172370 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172371,#172372,#172373, - #172374,#172375,#172376,#172377,#172378,#172379,#172380,#172381, - #172382,#172383,#172384,#172385,#172386,#172387,#172388,#172389, - #172390,#172391,#172392,#172393,#172394,#172395),.UNSPECIFIED.,.F., +#174751 = VECTOR('',#174752,1.); +#174752 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#174753 = PCURVE('',#173471,#174754); +#174754 = DEFINITIONAL_REPRESENTATION('',(#174755),#174759); +#174755 = LINE('',#174756,#174757); +#174756 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#174757 = VECTOR('',#174758,1.); +#174758 = DIRECTION('',(0.968100345886,-0.250562807086)); +#174759 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174760 = PCURVE('',#172078,#174761); +#174761 = DEFINITIONAL_REPRESENTATION('',(#174762),#174788); +#174762 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174763,#174764,#174765, + #174766,#174767,#174768,#174769,#174770,#174771,#174772,#174773, + #174774,#174775,#174776,#174777,#174778,#174779,#174780,#174781, + #174782,#174783,#174784,#174785,#174786,#174787),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.531367877804, -0.508864963493,-0.486362049183,-0.463859134872,-0.441356220562, -0.418853306251,-0.39635039194,-0.37384747763,-0.351344563319, @@ -213230,187 +216232,187 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.238829991766,-0.216327077456,-0.193824163145,-0.171321248834, -0.148818334524,-0.126315420213,-0.103812505903,-8.130959159195E-002 ,-5.880667728135E-002,-3.630376297074E-002),.QUASI_UNIFORM_KNOTS.); -#172371 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#172372 = CARTESIAN_POINT('',(1.637833825,-0.523866906367)); -#172373 = CARTESIAN_POINT('',(1.637833825,-0.508864963493)); -#172374 = CARTESIAN_POINT('',(1.637833825,-0.486362049183)); -#172375 = CARTESIAN_POINT('',(1.637833825,-0.463859134872)); -#172376 = CARTESIAN_POINT('',(1.637833825,-0.441356220562)); -#172377 = CARTESIAN_POINT('',(1.637833825,-0.418853306251)); -#172378 = CARTESIAN_POINT('',(1.637833825,-0.39635039194)); -#172379 = CARTESIAN_POINT('',(1.637833825,-0.37384747763)); -#172380 = CARTESIAN_POINT('',(1.637833825,-0.351344563319)); -#172381 = CARTESIAN_POINT('',(1.637833825,-0.328841649009)); -#172382 = CARTESIAN_POINT('',(1.637833825,-0.306338734698)); -#172383 = CARTESIAN_POINT('',(1.637833825,-0.283835820387)); -#172384 = CARTESIAN_POINT('',(1.637833825,-0.261332906077)); -#172385 = CARTESIAN_POINT('',(1.637833825,-0.238829991766)); -#172386 = CARTESIAN_POINT('',(1.637833825,-0.216327077456)); -#172387 = CARTESIAN_POINT('',(1.637833825,-0.193824163145)); -#172388 = CARTESIAN_POINT('',(1.637833825,-0.171321248834)); -#172389 = CARTESIAN_POINT('',(1.637833825,-0.148818334524)); -#172390 = CARTESIAN_POINT('',(1.637833825,-0.126315420213)); -#172391 = CARTESIAN_POINT('',(1.637833825,-0.103812505903)); -#172392 = CARTESIAN_POINT('',(1.637833825,-8.130959159195E-002)); -#172393 = CARTESIAN_POINT('',(1.637833825,-5.880667728135E-002)); -#172394 = CARTESIAN_POINT('',(1.637833825,-4.380473440761E-002)); -#172395 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#172396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172397 = ORIENTED_EDGE('',*,*,#171063,.F.); -#172398 = ORIENTED_EDGE('',*,*,#172399,.F.); -#172399 = EDGE_CURVE('',#171523,#171029,#172400,.T.); -#172400 = SURFACE_CURVE('',#172401,(#172405,#172412),.PCURVE_S1.); -#172401 = LINE('',#172402,#172403); -#172402 = CARTESIAN_POINT('',(-3.42,0.8,0.6)); -#172403 = VECTOR('',#172404,1.); -#172404 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172405 = PCURVE('',#171079,#172406); -#172406 = DEFINITIONAL_REPRESENTATION('',(#172407),#172411); -#172407 = LINE('',#172408,#172409); -#172408 = CARTESIAN_POINT('',(-2.144786184852E-016,-1.95)); -#172409 = VECTOR('',#172410,1.); -#172410 = DIRECTION('',(0.E+000,-1.)); -#172411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172412 = PCURVE('',#172413,#172418); -#172413 = PLANE('',#172414); -#172414 = AXIS2_PLACEMENT_3D('',#172415,#172416,#172417); -#172415 = CARTESIAN_POINT('',(-1.165,0.7,0.6)); -#172416 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172417 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172418 = DEFINITIONAL_REPRESENTATION('',(#172419),#172423); -#172419 = LINE('',#172420,#172421); -#172420 = CARTESIAN_POINT('',(2.255,0.1)); -#172421 = VECTOR('',#172422,1.); -#172422 = DIRECTION('',(1.,0.E+000)); -#172423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172424 = ORIENTED_EDGE('',*,*,#171522,.F.); -#172425 = ORIENTED_EDGE('',*,*,#172426,.F.); -#172426 = EDGE_CURVE('',#171416,#171495,#172427,.T.); -#172427 = SURFACE_CURVE('',#172428,(#172432,#172439),.PCURVE_S1.); -#172428 = LINE('',#172429,#172430); -#172429 = CARTESIAN_POINT('',(-2.77,0.8,0.6)); -#172430 = VECTOR('',#172431,1.); -#172431 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172432 = PCURVE('',#171079,#172433); -#172433 = DEFINITIONAL_REPRESENTATION('',(#172434),#172438); -#172434 = LINE('',#172435,#172436); -#172435 = CARTESIAN_POINT('',(-1.072393092426E-016,-1.3)); -#172436 = VECTOR('',#172437,1.); -#172437 = DIRECTION('',(0.E+000,-1.)); -#172438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#174763 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#174764 = CARTESIAN_POINT('',(1.637833825,-0.523866906367)); +#174765 = CARTESIAN_POINT('',(1.637833825,-0.508864963493)); +#174766 = CARTESIAN_POINT('',(1.637833825,-0.486362049183)); +#174767 = CARTESIAN_POINT('',(1.637833825,-0.463859134872)); +#174768 = CARTESIAN_POINT('',(1.637833825,-0.441356220562)); +#174769 = CARTESIAN_POINT('',(1.637833825,-0.418853306251)); +#174770 = CARTESIAN_POINT('',(1.637833825,-0.39635039194)); +#174771 = CARTESIAN_POINT('',(1.637833825,-0.37384747763)); +#174772 = CARTESIAN_POINT('',(1.637833825,-0.351344563319)); +#174773 = CARTESIAN_POINT('',(1.637833825,-0.328841649009)); +#174774 = CARTESIAN_POINT('',(1.637833825,-0.306338734698)); +#174775 = CARTESIAN_POINT('',(1.637833825,-0.283835820387)); +#174776 = CARTESIAN_POINT('',(1.637833825,-0.261332906077)); +#174777 = CARTESIAN_POINT('',(1.637833825,-0.238829991766)); +#174778 = CARTESIAN_POINT('',(1.637833825,-0.216327077456)); +#174779 = CARTESIAN_POINT('',(1.637833825,-0.193824163145)); +#174780 = CARTESIAN_POINT('',(1.637833825,-0.171321248834)); +#174781 = CARTESIAN_POINT('',(1.637833825,-0.148818334524)); +#174782 = CARTESIAN_POINT('',(1.637833825,-0.126315420213)); +#174783 = CARTESIAN_POINT('',(1.637833825,-0.103812505903)); +#174784 = CARTESIAN_POINT('',(1.637833825,-8.130959159195E-002)); +#174785 = CARTESIAN_POINT('',(1.637833825,-5.880667728135E-002)); +#174786 = CARTESIAN_POINT('',(1.637833825,-4.380473440761E-002)); +#174787 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#174788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174789 = ORIENTED_EDGE('',*,*,#173455,.F.); +#174790 = ORIENTED_EDGE('',*,*,#174791,.F.); +#174791 = EDGE_CURVE('',#173915,#173421,#174792,.T.); +#174792 = SURFACE_CURVE('',#174793,(#174797,#174804),.PCURVE_S1.); +#174793 = LINE('',#174794,#174795); +#174794 = CARTESIAN_POINT('',(-3.42,0.8,0.6)); +#174795 = VECTOR('',#174796,1.); +#174796 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174797 = PCURVE('',#173471,#174798); +#174798 = DEFINITIONAL_REPRESENTATION('',(#174799),#174803); +#174799 = LINE('',#174800,#174801); +#174800 = CARTESIAN_POINT('',(-2.144786184852E-016,-1.95)); +#174801 = VECTOR('',#174802,1.); +#174802 = DIRECTION('',(0.E+000,-1.)); +#174803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174804 = PCURVE('',#174805,#174810); +#174805 = PLANE('',#174806); +#174806 = AXIS2_PLACEMENT_3D('',#174807,#174808,#174809); +#174807 = CARTESIAN_POINT('',(-1.165,0.7,0.6)); +#174808 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174809 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174810 = DEFINITIONAL_REPRESENTATION('',(#174811),#174815); +#174811 = LINE('',#174812,#174813); +#174812 = CARTESIAN_POINT('',(2.255,0.1)); +#174813 = VECTOR('',#174814,1.); +#174814 = DIRECTION('',(1.,0.E+000)); +#174815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174816 = ORIENTED_EDGE('',*,*,#173914,.F.); +#174817 = ORIENTED_EDGE('',*,*,#174818,.F.); +#174818 = EDGE_CURVE('',#173808,#173887,#174819,.T.); +#174819 = SURFACE_CURVE('',#174820,(#174824,#174831),.PCURVE_S1.); +#174820 = LINE('',#174821,#174822); +#174821 = CARTESIAN_POINT('',(-2.77,0.8,0.6)); +#174822 = VECTOR('',#174823,1.); +#174823 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174824 = PCURVE('',#173471,#174825); +#174825 = DEFINITIONAL_REPRESENTATION('',(#174826),#174830); +#174826 = LINE('',#174827,#174828); +#174827 = CARTESIAN_POINT('',(-1.072393092426E-016,-1.3)); +#174828 = VECTOR('',#174829,1.); +#174829 = DIRECTION('',(0.E+000,-1.)); +#174830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174831 = PCURVE('',#174832,#174837); +#174832 = PLANE('',#174833); +#174833 = AXIS2_PLACEMENT_3D('',#174834,#174835,#174836); +#174834 = CARTESIAN_POINT('',(-0.515,0.7,0.6)); +#174835 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174836 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174837 = DEFINITIONAL_REPRESENTATION('',(#174838),#174842); +#174838 = LINE('',#174839,#174840); +#174839 = CARTESIAN_POINT('',(2.255,0.1)); +#174840 = VECTOR('',#174841,1.); +#174841 = DIRECTION('',(1.,0.E+000)); +#174842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174843 = ORIENTED_EDGE('',*,*,#173807,.F.); +#174844 = ORIENTED_EDGE('',*,*,#174845,.F.); +#174845 = EDGE_CURVE('',#173701,#173780,#174846,.T.); +#174846 = SURFACE_CURVE('',#174847,(#174851,#174858),.PCURVE_S1.); +#174847 = LINE('',#174848,#174849); +#174848 = CARTESIAN_POINT('',(-2.12,0.8,0.6)); +#174849 = VECTOR('',#174850,1.); +#174850 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174851 = PCURVE('',#173471,#174852); +#174852 = DEFINITIONAL_REPRESENTATION('',(#174853),#174857); +#174853 = LINE('',#174854,#174855); +#174854 = CARTESIAN_POINT('',(-1.072393092426E-016,-0.65)); +#174855 = VECTOR('',#174856,1.); +#174856 = DIRECTION('',(0.E+000,-1.)); +#174857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174858 = PCURVE('',#174859,#174864); +#174859 = PLANE('',#174860); +#174860 = AXIS2_PLACEMENT_3D('',#174861,#174862,#174863); +#174861 = CARTESIAN_POINT('',(0.135,0.7,0.6)); +#174862 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174863 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174864 = DEFINITIONAL_REPRESENTATION('',(#174865),#174869); +#174865 = LINE('',#174866,#174867); +#174866 = CARTESIAN_POINT('',(2.255,0.1)); +#174867 = VECTOR('',#174868,1.); +#174868 = DIRECTION('',(1.,0.E+000)); +#174869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#172439 = PCURVE('',#172440,#172445); -#172440 = PLANE('',#172441); -#172441 = AXIS2_PLACEMENT_3D('',#172442,#172443,#172444); -#172442 = CARTESIAN_POINT('',(-0.515,0.7,0.6)); -#172443 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172444 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172445 = DEFINITIONAL_REPRESENTATION('',(#172446),#172450); -#172446 = LINE('',#172447,#172448); -#172447 = CARTESIAN_POINT('',(2.255,0.1)); -#172448 = VECTOR('',#172449,1.); -#172449 = DIRECTION('',(1.,0.E+000)); -#172450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172451 = ORIENTED_EDGE('',*,*,#171415,.F.); -#172452 = ORIENTED_EDGE('',*,*,#172453,.F.); -#172453 = EDGE_CURVE('',#171309,#171388,#172454,.T.); -#172454 = SURFACE_CURVE('',#172455,(#172459,#172466),.PCURVE_S1.); -#172455 = LINE('',#172456,#172457); -#172456 = CARTESIAN_POINT('',(-2.12,0.8,0.6)); -#172457 = VECTOR('',#172458,1.); -#172458 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172459 = PCURVE('',#171079,#172460); -#172460 = DEFINITIONAL_REPRESENTATION('',(#172461),#172465); -#172461 = LINE('',#172462,#172463); -#172462 = CARTESIAN_POINT('',(-1.072393092426E-016,-0.65)); -#172463 = VECTOR('',#172464,1.); -#172464 = DIRECTION('',(0.E+000,-1.)); -#172465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172466 = PCURVE('',#172467,#172472); -#172467 = PLANE('',#172468); -#172468 = AXIS2_PLACEMENT_3D('',#172469,#172470,#172471); -#172469 = CARTESIAN_POINT('',(0.135,0.7,0.6)); -#172470 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172471 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172472 = DEFINITIONAL_REPRESENTATION('',(#172473),#172477); -#172473 = LINE('',#172474,#172475); -#172474 = CARTESIAN_POINT('',(2.255,0.1)); -#172475 = VECTOR('',#172476,1.); -#172476 = DIRECTION('',(1.,0.E+000)); -#172477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172478 = ORIENTED_EDGE('',*,*,#171308,.F.); -#172479 = ORIENTED_EDGE('',*,*,#172480,.F.); -#172480 = EDGE_CURVE('',#171202,#171281,#172481,.T.); -#172481 = SURFACE_CURVE('',#172482,(#172486,#172493),.PCURVE_S1.); -#172482 = LINE('',#172483,#172484); -#172483 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); -#172484 = VECTOR('',#172485,1.); -#172485 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172486 = PCURVE('',#171079,#172487); -#172487 = DEFINITIONAL_REPRESENTATION('',(#172488),#172492); -#172488 = LINE('',#172489,#172490); -#172489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172490 = VECTOR('',#172491,1.); -#172491 = DIRECTION('',(0.E+000,-1.)); -#172492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172493 = PCURVE('',#172494,#172499); -#172494 = PLANE('',#172495); -#172495 = AXIS2_PLACEMENT_3D('',#172496,#172497,#172498); -#172496 = CARTESIAN_POINT('',(0.785,0.7,0.6)); -#172497 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#172498 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172499 = DEFINITIONAL_REPRESENTATION('',(#172500),#172504); -#172500 = LINE('',#172501,#172502); -#172501 = CARTESIAN_POINT('',(2.255,0.1)); -#172502 = VECTOR('',#172503,1.); -#172503 = DIRECTION('',(1.,0.E+000)); -#172504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172505 = ORIENTED_EDGE('',*,*,#171201,.F.); -#172506 = ADVANCED_FACE('',(#172507),#168701,.F.); -#172507 = FACE_BOUND('',#172508,.T.); -#172508 = EDGE_LOOP('',(#172509,#172554,#172599,#172600,#172622,#172667, - #172668,#172713,#172758,#172759,#172781,#172826)); -#172509 = ORIENTED_EDGE('',*,*,#172510,.T.); -#172510 = EDGE_CURVE('',#169224,#172511,#172513,.T.); -#172511 = VERTEX_POINT('',#172512); -#172512 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); -#172513 = SURFACE_CURVE('',#172514,(#172518,#172525),.PCURVE_S1.); -#172514 = LINE('',#172515,#172516); -#172515 = CARTESIAN_POINT('',(1.297659054385,-0.521136529841,1.E-001)); -#172516 = VECTOR('',#172517,1.); -#172517 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#172518 = PCURVE('',#168701,#172519); -#172519 = DEFINITIONAL_REPRESENTATION('',(#172520),#172524); -#172520 = LINE('',#172521,#172522); -#172521 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); -#172522 = VECTOR('',#172523,1.); -#172523 = DIRECTION('',(1.355252715607E-016,-1.)); -#172524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172525 = PCURVE('',#169482,#172526); -#172526 = DEFINITIONAL_REPRESENTATION('',(#172527),#172553); -#172527 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172528,#172529,#172530, - #172531,#172532,#172533,#172534,#172535,#172536,#172537,#172538, - #172539,#172540,#172541,#172542,#172543,#172544,#172545,#172546, - #172547,#172548,#172549,#172550,#172551,#172552),.UNSPECIFIED.,.F., +#174870 = ORIENTED_EDGE('',*,*,#173700,.F.); +#174871 = ORIENTED_EDGE('',*,*,#174872,.F.); +#174872 = EDGE_CURVE('',#173594,#173673,#174873,.T.); +#174873 = SURFACE_CURVE('',#174874,(#174878,#174885),.PCURVE_S1.); +#174874 = LINE('',#174875,#174876); +#174875 = CARTESIAN_POINT('',(-1.47,0.8,0.6)); +#174876 = VECTOR('',#174877,1.); +#174877 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174878 = PCURVE('',#173471,#174879); +#174879 = DEFINITIONAL_REPRESENTATION('',(#174880),#174884); +#174880 = LINE('',#174881,#174882); +#174881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174882 = VECTOR('',#174883,1.); +#174883 = DIRECTION('',(0.E+000,-1.)); +#174884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174885 = PCURVE('',#174886,#174891); +#174886 = PLANE('',#174887); +#174887 = AXIS2_PLACEMENT_3D('',#174888,#174889,#174890); +#174888 = CARTESIAN_POINT('',(0.785,0.7,0.6)); +#174889 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#174890 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#174891 = DEFINITIONAL_REPRESENTATION('',(#174892),#174896); +#174892 = LINE('',#174893,#174894); +#174893 = CARTESIAN_POINT('',(2.255,0.1)); +#174894 = VECTOR('',#174895,1.); +#174895 = DIRECTION('',(1.,0.E+000)); +#174896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174897 = ORIENTED_EDGE('',*,*,#173593,.F.); +#174898 = ADVANCED_FACE('',(#174899),#171093,.F.); +#174899 = FACE_BOUND('',#174900,.T.); +#174900 = EDGE_LOOP('',(#174901,#174946,#174991,#174992,#175014,#175059, + #175060,#175105,#175150,#175151,#175173,#175218)); +#174901 = ORIENTED_EDGE('',*,*,#174902,.T.); +#174902 = EDGE_CURVE('',#171616,#174903,#174905,.T.); +#174903 = VERTEX_POINT('',#174904); +#174904 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); +#174905 = SURFACE_CURVE('',#174906,(#174910,#174917),.PCURVE_S1.); +#174906 = LINE('',#174907,#174908); +#174907 = CARTESIAN_POINT('',(1.297659054385,-0.521136529841,1.E-001)); +#174908 = VECTOR('',#174909,1.); +#174909 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#174910 = PCURVE('',#171093,#174911); +#174911 = DEFINITIONAL_REPRESENTATION('',(#174912),#174916); +#174912 = LINE('',#174913,#174914); +#174913 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); +#174914 = VECTOR('',#174915,1.); +#174915 = DIRECTION('',(1.355252715607E-016,-1.)); +#174916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174917 = PCURVE('',#171874,#174918); +#174918 = DEFINITIONAL_REPRESENTATION('',(#174919),#174945); +#174919 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174920,#174921,#174922, + #174923,#174924,#174925,#174926,#174927,#174928,#174929,#174930, + #174931,#174932,#174933,#174934,#174935,#174936,#174937,#174938, + #174939,#174940,#174941,#174942,#174943,#174944),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-1.052203001598, -1.003924231438,-0.955645461278,-0.907366691119,-0.859087920959, -0.810809150799,-0.76253038064,-0.71425161048,-0.66597284032, @@ -213418,66 +216420,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.424578989522,-0.376300219362,-0.328021449202,-0.279742679043, -0.231463908883,-0.183185138723,-0.134906368564,-8.662759840387E-002 ,-3.834882824418E-002,9.929941915506E-003),.UNSPECIFIED.); -#172528 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#172529 = CARTESIAN_POINT('',(4.712388980385,0.28502645163)); -#172530 = CARTESIAN_POINT('',(4.712388980385,0.317212298403)); -#172531 = CARTESIAN_POINT('',(4.712388980385,0.365491068563)); -#172532 = CARTESIAN_POINT('',(4.712388980385,0.413769838722)); -#172533 = CARTESIAN_POINT('',(4.712388980385,0.462048608882)); -#172534 = CARTESIAN_POINT('',(4.712388980385,0.510327379042)); -#172535 = CARTESIAN_POINT('',(4.712388980385,0.558606149202)); -#172536 = CARTESIAN_POINT('',(4.712388980385,0.606884919361)); -#172537 = CARTESIAN_POINT('',(4.712388980385,0.655163689521)); -#172538 = CARTESIAN_POINT('',(4.712388980385,0.703442459681)); -#172539 = CARTESIAN_POINT('',(4.712388980385,0.75172122984)); -#172540 = CARTESIAN_POINT('',(4.712388980385,0.8)); -#172541 = CARTESIAN_POINT('',(4.712388980385,0.84827877016)); -#172542 = CARTESIAN_POINT('',(4.712388980385,0.896557540319)); -#172543 = CARTESIAN_POINT('',(4.712388980385,0.944836310479)); -#172544 = CARTESIAN_POINT('',(4.712388980385,0.993115080639)); -#172545 = CARTESIAN_POINT('',(4.712388980385,1.041393850798)); -#172546 = CARTESIAN_POINT('',(4.712388980385,1.089672620958)); -#172547 = CARTESIAN_POINT('',(4.712388980385,1.137951391118)); -#172548 = CARTESIAN_POINT('',(4.712388980385,1.186230161278)); -#172549 = CARTESIAN_POINT('',(4.712388980385,1.234508931437)); -#172550 = CARTESIAN_POINT('',(4.712388980385,1.282787701597)); -#172551 = CARTESIAN_POINT('',(4.712388980385,1.31497354837)); -#172552 = CARTESIAN_POINT('',(4.712388980385,1.331066471757)); -#172553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172554 = ORIENTED_EDGE('',*,*,#172555,.T.); -#172555 = EDGE_CURVE('',#172511,#168644,#172556,.T.); -#172556 = SURFACE_CURVE('',#172557,(#172562,#172570),.PCURVE_S1.); -#172557 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172558,#172559,#172560, -#172561),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#174920 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#174921 = CARTESIAN_POINT('',(4.712388980385,0.28502645163)); +#174922 = CARTESIAN_POINT('',(4.712388980385,0.317212298403)); +#174923 = CARTESIAN_POINT('',(4.712388980385,0.365491068563)); +#174924 = CARTESIAN_POINT('',(4.712388980385,0.413769838722)); +#174925 = CARTESIAN_POINT('',(4.712388980385,0.462048608882)); +#174926 = CARTESIAN_POINT('',(4.712388980385,0.510327379042)); +#174927 = CARTESIAN_POINT('',(4.712388980385,0.558606149202)); +#174928 = CARTESIAN_POINT('',(4.712388980385,0.606884919361)); +#174929 = CARTESIAN_POINT('',(4.712388980385,0.655163689521)); +#174930 = CARTESIAN_POINT('',(4.712388980385,0.703442459681)); +#174931 = CARTESIAN_POINT('',(4.712388980385,0.75172122984)); +#174932 = CARTESIAN_POINT('',(4.712388980385,0.8)); +#174933 = CARTESIAN_POINT('',(4.712388980385,0.84827877016)); +#174934 = CARTESIAN_POINT('',(4.712388980385,0.896557540319)); +#174935 = CARTESIAN_POINT('',(4.712388980385,0.944836310479)); +#174936 = CARTESIAN_POINT('',(4.712388980385,0.993115080639)); +#174937 = CARTESIAN_POINT('',(4.712388980385,1.041393850798)); +#174938 = CARTESIAN_POINT('',(4.712388980385,1.089672620958)); +#174939 = CARTESIAN_POINT('',(4.712388980385,1.137951391118)); +#174940 = CARTESIAN_POINT('',(4.712388980385,1.186230161278)); +#174941 = CARTESIAN_POINT('',(4.712388980385,1.234508931437)); +#174942 = CARTESIAN_POINT('',(4.712388980385,1.282787701597)); +#174943 = CARTESIAN_POINT('',(4.712388980385,1.31497354837)); +#174944 = CARTESIAN_POINT('',(4.712388980385,1.331066471757)); +#174945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174946 = ORIENTED_EDGE('',*,*,#174947,.T.); +#174947 = EDGE_CURVE('',#174903,#171036,#174948,.T.); +#174948 = SURFACE_CURVE('',#174949,(#174954,#174962),.PCURVE_S1.); +#174949 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#174950,#174951,#174952, +#174953),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172558 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); -#172559 = CARTESIAN_POINT('',(1.297659054385,-0.557584046027,1.E-001)); -#172560 = CARTESIAN_POINT('',(1.28790129499,-0.581596067115,1.E-001)); -#172561 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); -#172562 = PCURVE('',#168701,#172563); -#172563 = DEFINITIONAL_REPRESENTATION('',(#172564),#172569); -#172564 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172565,#172566,#172567, -#172568),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#174950 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,1.E-001)); +#174951 = CARTESIAN_POINT('',(1.297659054385,-0.557584046027,1.E-001)); +#174952 = CARTESIAN_POINT('',(1.28790129499,-0.581596067115,1.E-001)); +#174953 = CARTESIAN_POINT('',(1.269748681053,-0.599748681053,1.E-001)); +#174954 = PCURVE('',#171093,#174955); +#174955 = DEFINITIONAL_REPRESENTATION('',(#174956),#174961); +#174956 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#174957,#174958,#174959, +#174960),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172565 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); -#172566 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); -#172567 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); -#172568 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#172569 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172570 = PCURVE('',#168753,#172571); -#172571 = DEFINITIONAL_REPRESENTATION('',(#172572),#172598); -#172572 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172573,#172574,#172575, - #172576,#172577,#172578,#172579,#172580,#172581,#172582,#172583, - #172584,#172585,#172586,#172587,#172588,#172589,#172590,#172591, - #172592,#172593,#172594,#172595,#172596,#172597),.UNSPECIFIED.,.F., +#174957 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); +#174958 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); +#174959 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); +#174960 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#174961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174962 = PCURVE('',#171145,#174963); +#174963 = DEFINITIONAL_REPRESENTATION('',(#174964),#174990); +#174964 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174965,#174966,#174967, + #174968,#174969,#174970,#174971,#174972,#174973,#174974,#174975, + #174976,#174977,#174978,#174979,#174980,#174981,#174982,#174983, + #174984,#174985,#174986,#174987,#174988,#174989),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -213485,95 +216487,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#172573 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#172574 = CARTESIAN_POINT('',(0.740753697746,-2.901323131841E-008)); -#172575 = CARTESIAN_POINT('',(0.718425611961,2.616756249238E-005)); -#172576 = CARTESIAN_POINT('',(0.684727524261,1.282673135066E-004)); -#172577 = CARTESIAN_POINT('',(0.650847765387,2.772530388867E-004)); -#172578 = CARTESIAN_POINT('',(0.616809612353,4.570658043331E-004)); -#172579 = CARTESIAN_POINT('',(0.582635599926,6.52095293192E-004)); -#172580 = CARTESIAN_POINT('',(0.548347414424,8.475624467578E-004)); -#172581 = CARTESIAN_POINT('',(0.513965932674,1.02994328956E-003)); -#172582 = CARTESIAN_POINT('',(0.479511265006,1.187353930382E-003)); -#172583 = CARTESIAN_POINT('',(0.445002837244,1.3099048672E-003)); -#172584 = CARTESIAN_POINT('',(0.41045949854,1.390009812367E-003)); -#172585 = CARTESIAN_POINT('',(0.375899653916,1.422641316497E-003)); -#172586 = CARTESIAN_POINT('',(0.341341416362,1.405524714337E-003)); -#172587 = CARTESIAN_POINT('',(0.306802773621,1.339263477878E-003)); -#172588 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); -#172589 = CARTESIAN_POINT('',(0.237856655052,1.076339414009E-003)); -#172590 = CARTESIAN_POINT('',(0.203486118557,8.953387637328E-004)); -#172591 = CARTESIAN_POINT('',(0.169209394064,6.962198987721E-004)); -#172592 = CARTESIAN_POINT('',(0.135046437107,4.931498468591E-004)); -#172593 = CARTESIAN_POINT('',(0.101018031154,3.022859269967E-004)); -#172594 = CARTESIAN_POINT('',(6.714590753945E-002,1.413707577685E-004)); -#172595 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134010315E-005)); -#172596 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318512633E-008)); -#172597 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#172598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172599 = ORIENTED_EDGE('',*,*,#168643,.T.); -#172600 = ORIENTED_EDGE('',*,*,#172601,.T.); -#172601 = EDGE_CURVE('',#168646,#172602,#172604,.T.); -#172602 = VERTEX_POINT('',#172603); -#172603 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); -#172604 = SURFACE_CURVE('',#172605,(#172609,#172616),.PCURVE_S1.); -#172605 = LINE('',#172606,#172607); -#172606 = CARTESIAN_POINT('',(-1.191136529841,-0.627659054385,1.E-001)); -#172607 = VECTOR('',#172608,1.); -#172608 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#172609 = PCURVE('',#168701,#172610); -#172610 = DEFINITIONAL_REPRESENTATION('',(#172611),#172615); -#172611 = LINE('',#172612,#172613); -#172612 = CARTESIAN_POINT('',(-2.661136529841,0.172340945615)); -#172613 = VECTOR('',#172614,1.); -#172614 = DIRECTION('',(-1.,0.E+000)); -#172615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172616 = PCURVE('',#168909,#172617); -#172617 = DEFINITIONAL_REPRESENTATION('',(#172618),#172621); -#172618 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172619,#172620), +#174965 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#174966 = CARTESIAN_POINT('',(0.740753697746,-2.901323131841E-008)); +#174967 = CARTESIAN_POINT('',(0.718425611961,2.616756249238E-005)); +#174968 = CARTESIAN_POINT('',(0.684727524261,1.282673135066E-004)); +#174969 = CARTESIAN_POINT('',(0.650847765387,2.772530388867E-004)); +#174970 = CARTESIAN_POINT('',(0.616809612353,4.570658043331E-004)); +#174971 = CARTESIAN_POINT('',(0.582635599926,6.52095293192E-004)); +#174972 = CARTESIAN_POINT('',(0.548347414424,8.475624467578E-004)); +#174973 = CARTESIAN_POINT('',(0.513965932674,1.02994328956E-003)); +#174974 = CARTESIAN_POINT('',(0.479511265006,1.187353930382E-003)); +#174975 = CARTESIAN_POINT('',(0.445002837244,1.3099048672E-003)); +#174976 = CARTESIAN_POINT('',(0.41045949854,1.390009812367E-003)); +#174977 = CARTESIAN_POINT('',(0.375899653916,1.422641316497E-003)); +#174978 = CARTESIAN_POINT('',(0.341341416362,1.405524714337E-003)); +#174979 = CARTESIAN_POINT('',(0.306802773621,1.339263477878E-003)); +#174980 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); +#174981 = CARTESIAN_POINT('',(0.237856655052,1.076339414009E-003)); +#174982 = CARTESIAN_POINT('',(0.203486118557,8.953387637328E-004)); +#174983 = CARTESIAN_POINT('',(0.169209394064,6.962198987721E-004)); +#174984 = CARTESIAN_POINT('',(0.135046437107,4.931498468591E-004)); +#174985 = CARTESIAN_POINT('',(0.101018031154,3.022859269967E-004)); +#174986 = CARTESIAN_POINT('',(6.714590753945E-002,1.413707577685E-004)); +#174987 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134010315E-005)); +#174988 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318512633E-008)); +#174989 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#174990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#174991 = ORIENTED_EDGE('',*,*,#171035,.T.); +#174992 = ORIENTED_EDGE('',*,*,#174993,.T.); +#174993 = EDGE_CURVE('',#171038,#174994,#174996,.T.); +#174994 = VERTEX_POINT('',#174995); +#174995 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); +#174996 = SURFACE_CURVE('',#174997,(#175001,#175008),.PCURVE_S1.); +#174997 = LINE('',#174998,#174999); +#174998 = CARTESIAN_POINT('',(-1.191136529841,-0.627659054385,1.E-001)); +#174999 = VECTOR('',#175000,1.); +#175000 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175001 = PCURVE('',#171093,#175002); +#175002 = DEFINITIONAL_REPRESENTATION('',(#175003),#175007); +#175003 = LINE('',#175004,#175005); +#175004 = CARTESIAN_POINT('',(-2.661136529841,0.172340945615)); +#175005 = VECTOR('',#175006,1.); +#175006 = DIRECTION('',(-1.,0.E+000)); +#175007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175008 = PCURVE('',#171301,#175009); +#175009 = DEFINITIONAL_REPRESENTATION('',(#175010),#175013); +#175010 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175011,#175012), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.392203001598,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#172619 = CARTESIAN_POINT('',(3.14159265359,-2.671066471757)); -#172620 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#172621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#175011 = CARTESIAN_POINT('',(3.14159265359,-2.671066471757)); +#175012 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#175013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#172622 = ORIENTED_EDGE('',*,*,#172623,.T.); -#172623 = EDGE_CURVE('',#172602,#168947,#172624,.T.); -#172624 = SURFACE_CURVE('',#172625,(#172630,#172638),.PCURVE_S1.); -#172625 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172626,#172627,#172628, -#172629),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175014 = ORIENTED_EDGE('',*,*,#175015,.T.); +#175015 = EDGE_CURVE('',#174994,#171339,#175016,.T.); +#175016 = SURFACE_CURVE('',#175017,(#175022,#175030),.PCURVE_S1.); +#175017 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175018,#175019,#175020, +#175021),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172626 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); -#172627 = CARTESIAN_POINT('',(-1.227584046027,-0.627659054385,1.E-001)); -#172628 = CARTESIAN_POINT('',(-1.251596067115,-0.61790129499,1.E-001)); -#172629 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); -#172630 = PCURVE('',#168701,#172631); -#172631 = DEFINITIONAL_REPRESENTATION('',(#172632),#172637); -#172632 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172633,#172634,#172635, -#172636),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175018 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,1.E-001)); +#175019 = CARTESIAN_POINT('',(-1.227584046027,-0.627659054385,1.E-001)); +#175020 = CARTESIAN_POINT('',(-1.251596067115,-0.61790129499,1.E-001)); +#175021 = CARTESIAN_POINT('',(-1.269748681053,-0.599748681053,1.E-001)); +#175022 = PCURVE('',#171093,#175023); +#175023 = DEFINITIONAL_REPRESENTATION('',(#175024),#175029); +#175024 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175025,#175026,#175027, +#175028),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172633 = CARTESIAN_POINT('',(-2.671066471757,0.172340945615)); -#172634 = CARTESIAN_POINT('',(-2.697584046027,0.172340945615)); -#172635 = CARTESIAN_POINT('',(-2.721596067115,0.18209870501)); -#172636 = CARTESIAN_POINT('',(-2.739748681053,0.200251318947)); -#172637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172638 = PCURVE('',#169051,#172639); -#172639 = DEFINITIONAL_REPRESENTATION('',(#172640),#172666); -#172640 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172641,#172642,#172643, - #172644,#172645,#172646,#172647,#172648,#172649,#172650,#172651, - #172652,#172653,#172654,#172655,#172656,#172657,#172658,#172659, - #172660,#172661,#172662,#172663,#172664,#172665),.UNSPECIFIED.,.F., +#175025 = CARTESIAN_POINT('',(-2.671066471757,0.172340945615)); +#175026 = CARTESIAN_POINT('',(-2.697584046027,0.172340945615)); +#175027 = CARTESIAN_POINT('',(-2.721596067115,0.18209870501)); +#175028 = CARTESIAN_POINT('',(-2.739748681053,0.200251318947)); +#175029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175030 = PCURVE('',#171443,#175031); +#175031 = DEFINITIONAL_REPRESENTATION('',(#175032),#175058); +#175032 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175033,#175034,#175035, + #175036,#175037,#175038,#175039,#175040,#175041,#175042,#175043, + #175044,#175045,#175046,#175047,#175048,#175049,#175050,#175051, + #175052,#175053,#175054,#175055,#175056,#175057),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -213581,59 +216583,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#172641 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#172642 = CARTESIAN_POINT('',(0.740753697746,-2.901324180064E-008)); -#172643 = CARTESIAN_POINT('',(0.718425611961,2.616756247297E-005)); -#172644 = CARTESIAN_POINT('',(0.684727524261,1.282673134931E-004)); -#172645 = CARTESIAN_POINT('',(0.650847765387,2.772530388751E-004)); -#172646 = CARTESIAN_POINT('',(0.616809612353,4.570658043194E-004)); -#172647 = CARTESIAN_POINT('',(0.582635599926,6.520952931843E-004)); -#172648 = CARTESIAN_POINT('',(0.548347414424,8.475624467436E-004)); -#172649 = CARTESIAN_POINT('',(0.513965932674,1.029943289556E-003)); -#172650 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); -#172651 = CARTESIAN_POINT('',(0.445002837244,1.309904867196E-003)); -#172652 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); -#172653 = CARTESIAN_POINT('',(0.375899653916,1.422641316494E-003)); -#172654 = CARTESIAN_POINT('',(0.341341416362,1.405524714325E-003)); -#172655 = CARTESIAN_POINT('',(0.306802773621,1.339263477881E-003)); -#172656 = CARTESIAN_POINT('',(0.272301764008,1.227390254478E-003)); -#172657 = CARTESIAN_POINT('',(0.237856655052,1.076339414007E-003)); -#172658 = CARTESIAN_POINT('',(0.203486118557,8.953387637231E-004)); -#172659 = CARTESIAN_POINT('',(0.169209394064,6.962198987711E-004)); -#172660 = CARTESIAN_POINT('',(0.135046437107,4.931498468582E-004)); -#172661 = CARTESIAN_POINT('',(0.101018031154,3.022859269987E-004)); -#172662 = CARTESIAN_POINT('',(6.714590753944E-002,1.41370757766E-004)); -#172663 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009907E-005)); -#172664 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318285551E-008)); -#172665 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#172666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172667 = ORIENTED_EDGE('',*,*,#168946,.T.); -#172668 = ORIENTED_EDGE('',*,*,#172669,.T.); -#172669 = EDGE_CURVE('',#168949,#172670,#172672,.T.); -#172670 = VERTEX_POINT('',#172671); -#172671 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); -#172672 = SURFACE_CURVE('',#172673,(#172677,#172684),.PCURVE_S1.); -#172673 = LINE('',#172674,#172675); -#172674 = CARTESIAN_POINT('',(-1.297659054385,0.521136529841,1.E-001)); -#172675 = VECTOR('',#172676,1.); -#172676 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#172677 = PCURVE('',#168701,#172678); -#172678 = DEFINITIONAL_REPRESENTATION('',(#172679),#172683); -#172679 = LINE('',#172680,#172681); -#172680 = CARTESIAN_POINT('',(-2.767659054385,1.321136529841)); -#172681 = VECTOR('',#172682,1.); -#172682 = DIRECTION('',(-1.355252715607E-016,1.)); -#172683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172684 = PCURVE('',#169207,#172685); -#172685 = DEFINITIONAL_REPRESENTATION('',(#172686),#172712); -#172686 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172687,#172688,#172689, - #172690,#172691,#172692,#172693,#172694,#172695,#172696,#172697, - #172698,#172699,#172700,#172701,#172702,#172703,#172704,#172705, - #172706,#172707,#172708,#172709,#172710,#172711),.UNSPECIFIED.,.F., +#175033 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#175034 = CARTESIAN_POINT('',(0.740753697746,-2.901324180064E-008)); +#175035 = CARTESIAN_POINT('',(0.718425611961,2.616756247297E-005)); +#175036 = CARTESIAN_POINT('',(0.684727524261,1.282673134931E-004)); +#175037 = CARTESIAN_POINT('',(0.650847765387,2.772530388751E-004)); +#175038 = CARTESIAN_POINT('',(0.616809612353,4.570658043194E-004)); +#175039 = CARTESIAN_POINT('',(0.582635599926,6.520952931843E-004)); +#175040 = CARTESIAN_POINT('',(0.548347414424,8.475624467436E-004)); +#175041 = CARTESIAN_POINT('',(0.513965932674,1.029943289556E-003)); +#175042 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); +#175043 = CARTESIAN_POINT('',(0.445002837244,1.309904867196E-003)); +#175044 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); +#175045 = CARTESIAN_POINT('',(0.375899653916,1.422641316494E-003)); +#175046 = CARTESIAN_POINT('',(0.341341416362,1.405524714325E-003)); +#175047 = CARTESIAN_POINT('',(0.306802773621,1.339263477881E-003)); +#175048 = CARTESIAN_POINT('',(0.272301764008,1.227390254478E-003)); +#175049 = CARTESIAN_POINT('',(0.237856655052,1.076339414007E-003)); +#175050 = CARTESIAN_POINT('',(0.203486118557,8.953387637231E-004)); +#175051 = CARTESIAN_POINT('',(0.169209394064,6.962198987711E-004)); +#175052 = CARTESIAN_POINT('',(0.135046437107,4.931498468582E-004)); +#175053 = CARTESIAN_POINT('',(0.101018031154,3.022859269987E-004)); +#175054 = CARTESIAN_POINT('',(6.714590753944E-002,1.41370757766E-004)); +#175055 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009907E-005)); +#175056 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318285551E-008)); +#175057 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#175058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175059 = ORIENTED_EDGE('',*,*,#171338,.T.); +#175060 = ORIENTED_EDGE('',*,*,#175061,.T.); +#175061 = EDGE_CURVE('',#171341,#175062,#175064,.T.); +#175062 = VERTEX_POINT('',#175063); +#175063 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); +#175064 = SURFACE_CURVE('',#175065,(#175069,#175076),.PCURVE_S1.); +#175065 = LINE('',#175066,#175067); +#175066 = CARTESIAN_POINT('',(-1.297659054385,0.521136529841,1.E-001)); +#175067 = VECTOR('',#175068,1.); +#175068 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#175069 = PCURVE('',#171093,#175070); +#175070 = DEFINITIONAL_REPRESENTATION('',(#175071),#175075); +#175071 = LINE('',#175072,#175073); +#175072 = CARTESIAN_POINT('',(-2.767659054385,1.321136529841)); +#175073 = VECTOR('',#175074,1.); +#175074 = DIRECTION('',(-1.355252715607E-016,1.)); +#175075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175076 = PCURVE('',#171599,#175077); +#175077 = DEFINITIONAL_REPRESENTATION('',(#175078),#175104); +#175078 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175079,#175080,#175081, + #175082,#175083,#175084,#175085,#175086,#175087,#175088,#175089, + #175090,#175091,#175092,#175093,#175094,#175095,#175096,#175097, + #175098,#175099,#175100,#175101,#175102,#175103),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-1.052203001598, -1.003924231438,-0.955645461278,-0.907366691119,-0.859087920959, -0.810809150799,-0.76253038064,-0.71425161048,-0.66597284032, @@ -213641,66 +216643,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.424578989522,-0.376300219362,-0.328021449202,-0.279742679043, -0.231463908883,-0.183185138723,-0.134906368564,-8.662759840387E-002 ,-3.834882824418E-002,9.929941915506E-003),.UNSPECIFIED.); -#172687 = CARTESIAN_POINT('',(4.712388980385,-1.331066471757)); -#172688 = CARTESIAN_POINT('',(4.712388980385,-1.31497354837)); -#172689 = CARTESIAN_POINT('',(4.712388980385,-1.282787701597)); -#172690 = CARTESIAN_POINT('',(4.712388980385,-1.234508931437)); -#172691 = CARTESIAN_POINT('',(4.712388980385,-1.186230161278)); -#172692 = CARTESIAN_POINT('',(4.712388980385,-1.137951391118)); -#172693 = CARTESIAN_POINT('',(4.712388980385,-1.089672620958)); -#172694 = CARTESIAN_POINT('',(4.712388980385,-1.041393850798)); -#172695 = CARTESIAN_POINT('',(4.712388980385,-0.993115080639)); -#172696 = CARTESIAN_POINT('',(4.712388980385,-0.944836310479)); -#172697 = CARTESIAN_POINT('',(4.712388980385,-0.896557540319)); -#172698 = CARTESIAN_POINT('',(4.712388980385,-0.84827877016)); -#172699 = CARTESIAN_POINT('',(4.712388980385,-0.8)); -#172700 = CARTESIAN_POINT('',(4.712388980385,-0.75172122984)); -#172701 = CARTESIAN_POINT('',(4.712388980385,-0.703442459681)); -#172702 = CARTESIAN_POINT('',(4.712388980385,-0.655163689521)); -#172703 = CARTESIAN_POINT('',(4.712388980385,-0.606884919361)); -#172704 = CARTESIAN_POINT('',(4.712388980385,-0.558606149202)); -#172705 = CARTESIAN_POINT('',(4.712388980385,-0.510327379042)); -#172706 = CARTESIAN_POINT('',(4.712388980385,-0.462048608882)); -#172707 = CARTESIAN_POINT('',(4.712388980385,-0.413769838722)); -#172708 = CARTESIAN_POINT('',(4.712388980385,-0.365491068563)); -#172709 = CARTESIAN_POINT('',(4.712388980385,-0.317212298403)); -#172710 = CARTESIAN_POINT('',(4.712388980385,-0.28502645163)); -#172711 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#172712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172713 = ORIENTED_EDGE('',*,*,#172714,.T.); -#172714 = EDGE_CURVE('',#172670,#169497,#172715,.T.); -#172715 = SURFACE_CURVE('',#172716,(#172721,#172729),.PCURVE_S1.); -#172716 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172717,#172718,#172719, -#172720),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175079 = CARTESIAN_POINT('',(4.712388980385,-1.331066471757)); +#175080 = CARTESIAN_POINT('',(4.712388980385,-1.31497354837)); +#175081 = CARTESIAN_POINT('',(4.712388980385,-1.282787701597)); +#175082 = CARTESIAN_POINT('',(4.712388980385,-1.234508931437)); +#175083 = CARTESIAN_POINT('',(4.712388980385,-1.186230161278)); +#175084 = CARTESIAN_POINT('',(4.712388980385,-1.137951391118)); +#175085 = CARTESIAN_POINT('',(4.712388980385,-1.089672620958)); +#175086 = CARTESIAN_POINT('',(4.712388980385,-1.041393850798)); +#175087 = CARTESIAN_POINT('',(4.712388980385,-0.993115080639)); +#175088 = CARTESIAN_POINT('',(4.712388980385,-0.944836310479)); +#175089 = CARTESIAN_POINT('',(4.712388980385,-0.896557540319)); +#175090 = CARTESIAN_POINT('',(4.712388980385,-0.84827877016)); +#175091 = CARTESIAN_POINT('',(4.712388980385,-0.8)); +#175092 = CARTESIAN_POINT('',(4.712388980385,-0.75172122984)); +#175093 = CARTESIAN_POINT('',(4.712388980385,-0.703442459681)); +#175094 = CARTESIAN_POINT('',(4.712388980385,-0.655163689521)); +#175095 = CARTESIAN_POINT('',(4.712388980385,-0.606884919361)); +#175096 = CARTESIAN_POINT('',(4.712388980385,-0.558606149202)); +#175097 = CARTESIAN_POINT('',(4.712388980385,-0.510327379042)); +#175098 = CARTESIAN_POINT('',(4.712388980385,-0.462048608882)); +#175099 = CARTESIAN_POINT('',(4.712388980385,-0.413769838722)); +#175100 = CARTESIAN_POINT('',(4.712388980385,-0.365491068563)); +#175101 = CARTESIAN_POINT('',(4.712388980385,-0.317212298403)); +#175102 = CARTESIAN_POINT('',(4.712388980385,-0.28502645163)); +#175103 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#175104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175105 = ORIENTED_EDGE('',*,*,#175106,.T.); +#175106 = EDGE_CURVE('',#175062,#171889,#175107,.T.); +#175107 = SURFACE_CURVE('',#175108,(#175113,#175121),.PCURVE_S1.); +#175108 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175109,#175110,#175111, +#175112),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172717 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); -#172718 = CARTESIAN_POINT('',(-1.297659054385,0.557584046027,1.E-001)); -#172719 = CARTESIAN_POINT('',(-1.28790129499,0.581596067115,1.E-001)); -#172720 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); -#172721 = PCURVE('',#168701,#172722); -#172722 = DEFINITIONAL_REPRESENTATION('',(#172723),#172728); -#172723 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172724,#172725,#172726, -#172727),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175109 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,1.E-001)); +#175110 = CARTESIAN_POINT('',(-1.297659054385,0.557584046027,1.E-001)); +#175111 = CARTESIAN_POINT('',(-1.28790129499,0.581596067115,1.E-001)); +#175112 = CARTESIAN_POINT('',(-1.269748681053,0.599748681053,1.E-001)); +#175113 = PCURVE('',#171093,#175114); +#175114 = DEFINITIONAL_REPRESENTATION('',(#175115),#175120); +#175115 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175116,#175117,#175118, +#175119),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172724 = CARTESIAN_POINT('',(-2.767659054385,1.331066471757)); -#172725 = CARTESIAN_POINT('',(-2.767659054385,1.357584046027)); -#172726 = CARTESIAN_POINT('',(-2.75790129499,1.381596067115)); -#172727 = CARTESIAN_POINT('',(-2.739748681053,1.399748681053)); -#172728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172729 = PCURVE('',#169601,#172730); -#172730 = DEFINITIONAL_REPRESENTATION('',(#172731),#172757); -#172731 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172732,#172733,#172734, - #172735,#172736,#172737,#172738,#172739,#172740,#172741,#172742, - #172743,#172744,#172745,#172746,#172747,#172748,#172749,#172750, - #172751,#172752,#172753,#172754,#172755,#172756),.UNSPECIFIED.,.F., +#175116 = CARTESIAN_POINT('',(-2.767659054385,1.331066471757)); +#175117 = CARTESIAN_POINT('',(-2.767659054385,1.357584046027)); +#175118 = CARTESIAN_POINT('',(-2.75790129499,1.381596067115)); +#175119 = CARTESIAN_POINT('',(-2.739748681053,1.399748681053)); +#175120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175121 = PCURVE('',#171993,#175122); +#175122 = DEFINITIONAL_REPRESENTATION('',(#175123),#175149); +#175123 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175124,#175125,#175126, + #175127,#175128,#175129,#175130,#175131,#175132,#175133,#175134, + #175135,#175136,#175137,#175138,#175139,#175140,#175141,#175142, + #175143,#175144,#175145,#175146,#175147,#175148),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -213708,95 +216710,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#172732 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#172733 = CARTESIAN_POINT('',(0.740753697746,-2.90132432272E-008)); -#172734 = CARTESIAN_POINT('',(0.718425611961,2.616756247148E-005)); -#172735 = CARTESIAN_POINT('',(0.684727524261,1.282673134958E-004)); -#172736 = CARTESIAN_POINT('',(0.650847765387,2.772530388726E-004)); -#172737 = CARTESIAN_POINT('',(0.616809612353,4.570658043221E-004)); -#172738 = CARTESIAN_POINT('',(0.582635599926,6.520952931775E-004)); -#172739 = CARTESIAN_POINT('',(0.548347414424,8.475624467508E-004)); -#172740 = CARTESIAN_POINT('',(0.513965932674,1.029943289556E-003)); -#172741 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); -#172742 = CARTESIAN_POINT('',(0.445002837244,1.309904867193E-003)); -#172743 = CARTESIAN_POINT('',(0.41045949854,1.390009812369E-003)); -#172744 = CARTESIAN_POINT('',(0.375899653916,1.422641316495E-003)); -#172745 = CARTESIAN_POINT('',(0.341341416362,1.405524714321E-003)); -#172746 = CARTESIAN_POINT('',(0.306802773621,1.339263477888E-003)); -#172747 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); -#172748 = CARTESIAN_POINT('',(0.237856655052,1.076339414005E-003)); -#172749 = CARTESIAN_POINT('',(0.203486118557,8.953387637337E-004)); -#172750 = CARTESIAN_POINT('',(0.169209394064,6.962198987725E-004)); -#172751 = CARTESIAN_POINT('',(0.135046437107,4.931498468549E-004)); -#172752 = CARTESIAN_POINT('',(0.101018031154,3.022859269992E-004)); -#172753 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577642E-004)); -#172754 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134010145E-005)); -#172755 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318471132E-008)); -#172756 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#172757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172758 = ORIENTED_EDGE('',*,*,#169496,.T.); -#172759 = ORIENTED_EDGE('',*,*,#172760,.T.); -#172760 = EDGE_CURVE('',#169499,#172761,#172763,.T.); -#172761 = VERTEX_POINT('',#172762); -#172762 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); -#172763 = SURFACE_CURVE('',#172764,(#172768,#172775),.PCURVE_S1.); -#172764 = LINE('',#172765,#172766); -#172765 = CARTESIAN_POINT('',(1.191136529841,0.627659054385,1.E-001)); -#172766 = VECTOR('',#172767,1.); -#172767 = DIRECTION('',(1.,0.E+000,0.E+000)); -#172768 = PCURVE('',#168701,#172769); -#172769 = DEFINITIONAL_REPRESENTATION('',(#172770),#172774); -#172770 = LINE('',#172771,#172772); -#172771 = CARTESIAN_POINT('',(-0.278863470159,1.427659054385)); -#172772 = VECTOR('',#172773,1.); -#172773 = DIRECTION('',(1.,0.E+000)); -#172774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172775 = PCURVE('',#169757,#172776); -#172776 = DEFINITIONAL_REPRESENTATION('',(#172777),#172780); -#172777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#172778,#172779), +#175124 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#175125 = CARTESIAN_POINT('',(0.740753697746,-2.90132432272E-008)); +#175126 = CARTESIAN_POINT('',(0.718425611961,2.616756247148E-005)); +#175127 = CARTESIAN_POINT('',(0.684727524261,1.282673134958E-004)); +#175128 = CARTESIAN_POINT('',(0.650847765387,2.772530388726E-004)); +#175129 = CARTESIAN_POINT('',(0.616809612353,4.570658043221E-004)); +#175130 = CARTESIAN_POINT('',(0.582635599926,6.520952931775E-004)); +#175131 = CARTESIAN_POINT('',(0.548347414424,8.475624467508E-004)); +#175132 = CARTESIAN_POINT('',(0.513965932674,1.029943289556E-003)); +#175133 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); +#175134 = CARTESIAN_POINT('',(0.445002837244,1.309904867193E-003)); +#175135 = CARTESIAN_POINT('',(0.41045949854,1.390009812369E-003)); +#175136 = CARTESIAN_POINT('',(0.375899653916,1.422641316495E-003)); +#175137 = CARTESIAN_POINT('',(0.341341416362,1.405524714321E-003)); +#175138 = CARTESIAN_POINT('',(0.306802773621,1.339263477888E-003)); +#175139 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); +#175140 = CARTESIAN_POINT('',(0.237856655052,1.076339414005E-003)); +#175141 = CARTESIAN_POINT('',(0.203486118557,8.953387637337E-004)); +#175142 = CARTESIAN_POINT('',(0.169209394064,6.962198987725E-004)); +#175143 = CARTESIAN_POINT('',(0.135046437107,4.931498468549E-004)); +#175144 = CARTESIAN_POINT('',(0.101018031154,3.022859269992E-004)); +#175145 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577642E-004)); +#175146 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134010145E-005)); +#175147 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318471132E-008)); +#175148 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#175149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175150 = ORIENTED_EDGE('',*,*,#171888,.T.); +#175151 = ORIENTED_EDGE('',*,*,#175152,.T.); +#175152 = EDGE_CURVE('',#171891,#175153,#175155,.T.); +#175153 = VERTEX_POINT('',#175154); +#175154 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); +#175155 = SURFACE_CURVE('',#175156,(#175160,#175167),.PCURVE_S1.); +#175156 = LINE('',#175157,#175158); +#175157 = CARTESIAN_POINT('',(1.191136529841,0.627659054385,1.E-001)); +#175158 = VECTOR('',#175159,1.); +#175159 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175160 = PCURVE('',#171093,#175161); +#175161 = DEFINITIONAL_REPRESENTATION('',(#175162),#175166); +#175162 = LINE('',#175163,#175164); +#175163 = CARTESIAN_POINT('',(-0.278863470159,1.427659054385)); +#175164 = VECTOR('',#175165,1.); +#175165 = DIRECTION('',(1.,0.E+000)); +#175166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175167 = PCURVE('',#172149,#175168); +#175168 = DEFINITIONAL_REPRESENTATION('',(#175169),#175172); +#175169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175170,#175171), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.392203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#172778 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#172779 = CARTESIAN_POINT('',(0.E+000,2.671066471757)); -#172780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#175170 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#175171 = CARTESIAN_POINT('',(0.E+000,2.671066471757)); +#175172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#172781 = ORIENTED_EDGE('',*,*,#172782,.T.); -#172782 = EDGE_CURVE('',#172761,#169222,#172783,.T.); -#172783 = SURFACE_CURVE('',#172784,(#172789,#172797),.PCURVE_S1.); -#172784 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172785,#172786,#172787, -#172788),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175173 = ORIENTED_EDGE('',*,*,#175174,.T.); +#175174 = EDGE_CURVE('',#175153,#171614,#175175,.T.); +#175175 = SURFACE_CURVE('',#175176,(#175181,#175189),.PCURVE_S1.); +#175176 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175177,#175178,#175179, +#175180),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172785 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); -#172786 = CARTESIAN_POINT('',(1.227584046027,0.627659054385,1.E-001)); -#172787 = CARTESIAN_POINT('',(1.251596067115,0.61790129499,1.E-001)); -#172788 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); -#172789 = PCURVE('',#168701,#172790); -#172790 = DEFINITIONAL_REPRESENTATION('',(#172791),#172796); -#172791 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#172792,#172793,#172794, -#172795),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175177 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,1.E-001)); +#175178 = CARTESIAN_POINT('',(1.227584046027,0.627659054385,1.E-001)); +#175179 = CARTESIAN_POINT('',(1.251596067115,0.61790129499,1.E-001)); +#175180 = CARTESIAN_POINT('',(1.269748681053,0.599748681053,1.E-001)); +#175181 = PCURVE('',#171093,#175182); +#175182 = DEFINITIONAL_REPRESENTATION('',(#175183),#175188); +#175183 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175184,#175185,#175186, +#175187),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#172792 = CARTESIAN_POINT('',(-0.268933528243,1.427659054385)); -#172793 = CARTESIAN_POINT('',(-0.242415953973,1.427659054385)); -#172794 = CARTESIAN_POINT('',(-0.218403932885,1.41790129499)); -#172795 = CARTESIAN_POINT('',(-0.200251318947,1.399748681053)); -#172796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172797 = PCURVE('',#169326,#172798); -#172798 = DEFINITIONAL_REPRESENTATION('',(#172799),#172825); -#172799 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172800,#172801,#172802, - #172803,#172804,#172805,#172806,#172807,#172808,#172809,#172810, - #172811,#172812,#172813,#172814,#172815,#172816,#172817,#172818, - #172819,#172820,#172821,#172822,#172823,#172824),.UNSPECIFIED.,.F., +#175184 = CARTESIAN_POINT('',(-0.268933528243,1.427659054385)); +#175185 = CARTESIAN_POINT('',(-0.242415953973,1.427659054385)); +#175186 = CARTESIAN_POINT('',(-0.218403932885,1.41790129499)); +#175187 = CARTESIAN_POINT('',(-0.200251318947,1.399748681053)); +#175188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175189 = PCURVE('',#171718,#175190); +#175190 = DEFINITIONAL_REPRESENTATION('',(#175191),#175217); +#175191 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175192,#175193,#175194, + #175195,#175196,#175197,#175198,#175199,#175200,#175201,#175202, + #175203,#175204,#175205,#175206,#175207,#175208,#175209,#175210, + #175211,#175212,#175213,#175214,#175215,#175216),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -213804,62 +216806,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#172800 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#172801 = CARTESIAN_POINT('',(0.740753697746,-2.901324493272E-008)); -#172802 = CARTESIAN_POINT('',(0.718425611961,2.616756246568E-005)); -#172803 = CARTESIAN_POINT('',(0.684727524261,1.282673134842E-004)); -#172804 = CARTESIAN_POINT('',(0.650847765387,2.77253038872E-004)); -#172805 = CARTESIAN_POINT('',(0.616809612353,4.570658043168E-004)); -#172806 = CARTESIAN_POINT('',(0.582635599926,6.520952931783E-004)); -#172807 = CARTESIAN_POINT('',(0.548347414424,8.475624467441E-004)); -#172808 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); -#172809 = CARTESIAN_POINT('',(0.479511265006,1.187353930378E-003)); -#172810 = CARTESIAN_POINT('',(0.445002837244,1.309904867192E-003)); -#172811 = CARTESIAN_POINT('',(0.41045949854,1.390009812364E-003)); -#172812 = CARTESIAN_POINT('',(0.375899653916,1.422641316496E-003)); -#172813 = CARTESIAN_POINT('',(0.341341416362,1.405524714328E-003)); -#172814 = CARTESIAN_POINT('',(0.306802773621,1.339263477881E-003)); -#172815 = CARTESIAN_POINT('',(0.272301764008,1.227390254482E-003)); -#172816 = CARTESIAN_POINT('',(0.237856655052,1.076339414006E-003)); -#172817 = CARTESIAN_POINT('',(0.203486118557,8.95338763726E-004)); -#172818 = CARTESIAN_POINT('',(0.169209394064,6.962198987741E-004)); -#172819 = CARTESIAN_POINT('',(0.135046437107,4.931498468609E-004)); -#172820 = CARTESIAN_POINT('',(0.101018031154,3.022859269979E-004)); -#172821 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577624E-004)); -#172822 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009556E-005)); -#172823 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318129523E-008)); -#172824 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#172825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172826 = ORIENTED_EDGE('',*,*,#169221,.T.); -#172827 = ADVANCED_FACE('',(#172828),#171756,.T.); -#172828 = FACE_BOUND('',#172829,.T.); -#172829 = EDGE_LOOP('',(#172830,#172873,#172918,#172961)); -#172830 = ORIENTED_EDGE('',*,*,#172831,.T.); -#172831 = EDGE_CURVE('',#171698,#170604,#172832,.T.); -#172832 = SURFACE_CURVE('',#172833,(#172837,#172844),.PCURVE_S1.); -#172833 = LINE('',#172834,#172835); -#172834 = CARTESIAN_POINT('',(1.479096372758,0.664207498814, +#175192 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#175193 = CARTESIAN_POINT('',(0.740753697746,-2.901324493272E-008)); +#175194 = CARTESIAN_POINT('',(0.718425611961,2.616756246568E-005)); +#175195 = CARTESIAN_POINT('',(0.684727524261,1.282673134842E-004)); +#175196 = CARTESIAN_POINT('',(0.650847765387,2.77253038872E-004)); +#175197 = CARTESIAN_POINT('',(0.616809612353,4.570658043168E-004)); +#175198 = CARTESIAN_POINT('',(0.582635599926,6.520952931783E-004)); +#175199 = CARTESIAN_POINT('',(0.548347414424,8.475624467441E-004)); +#175200 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); +#175201 = CARTESIAN_POINT('',(0.479511265006,1.187353930378E-003)); +#175202 = CARTESIAN_POINT('',(0.445002837244,1.309904867192E-003)); +#175203 = CARTESIAN_POINT('',(0.41045949854,1.390009812364E-003)); +#175204 = CARTESIAN_POINT('',(0.375899653916,1.422641316496E-003)); +#175205 = CARTESIAN_POINT('',(0.341341416362,1.405524714328E-003)); +#175206 = CARTESIAN_POINT('',(0.306802773621,1.339263477881E-003)); +#175207 = CARTESIAN_POINT('',(0.272301764008,1.227390254482E-003)); +#175208 = CARTESIAN_POINT('',(0.237856655052,1.076339414006E-003)); +#175209 = CARTESIAN_POINT('',(0.203486118557,8.95338763726E-004)); +#175210 = CARTESIAN_POINT('',(0.169209394064,6.962198987741E-004)); +#175211 = CARTESIAN_POINT('',(0.135046437107,4.931498468609E-004)); +#175212 = CARTESIAN_POINT('',(0.101018031154,3.022859269979E-004)); +#175213 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577624E-004)); +#175214 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009556E-005)); +#175215 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318129523E-008)); +#175216 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#175217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175218 = ORIENTED_EDGE('',*,*,#171613,.T.); +#175219 = ADVANCED_FACE('',(#175220),#174148,.T.); +#175220 = FACE_BOUND('',#175221,.T.); +#175221 = EDGE_LOOP('',(#175222,#175265,#175310,#175353)); +#175222 = ORIENTED_EDGE('',*,*,#175223,.T.); +#175223 = EDGE_CURVE('',#174090,#172996,#175224,.T.); +#175224 = SURFACE_CURVE('',#175225,(#175229,#175236),.PCURVE_S1.); +#175225 = LINE('',#175226,#175227); +#175226 = CARTESIAN_POINT('',(1.479096372758,0.664207498814, 0.566051874704)); -#172835 = VECTOR('',#172836,1.); -#172836 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) - ); -#172837 = PCURVE('',#171756,#172838); -#172838 = DEFINITIONAL_REPRESENTATION('',(#172839),#172843); -#172839 = LINE('',#172840,#172841); -#172840 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#172841 = VECTOR('',#172842,1.); -#172842 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#172843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172844 = PCURVE('',#170659,#172845); -#172845 = DEFINITIONAL_REPRESENTATION('',(#172846),#172872); -#172846 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172847,#172848,#172849, - #172850,#172851,#172852,#172853,#172854,#172855,#172856,#172857, - #172858,#172859,#172860,#172861,#172862,#172863,#172864,#172865, - #172866,#172867,#172868,#172869,#172870,#172871),.UNSPECIFIED.,.F., +#175227 = VECTOR('',#175228,1.); +#175228 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) + ); +#175229 = PCURVE('',#174148,#175230); +#175230 = DEFINITIONAL_REPRESENTATION('',(#175231),#175235); +#175231 = LINE('',#175232,#175233); +#175232 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#175233 = VECTOR('',#175234,1.); +#175234 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#175235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175236 = PCURVE('',#173051,#175237); +#175237 = DEFINITIONAL_REPRESENTATION('',(#175238),#175264); +#175238 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175239,#175240,#175241, + #175242,#175243,#175244,#175245,#175246,#175247,#175248,#175249, + #175250,#175251,#175252,#175253,#175254,#175255,#175256,#175257, + #175258,#175259,#175260,#175261,#175262,#175263),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,6.366753787296E-002,9.103131277518E-002, 0.118395087677,0.14575886258,0.173122637482,0.200486412384, @@ -213868,60 +216870,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.446760386504,0.474124161406,0.501487936308,0.528851711211, 0.556215486113,0.583579261015,0.610943035917,0.63830681082), .QUASI_UNIFORM_KNOTS.); -#172847 = CARTESIAN_POINT('',(3.14159265359,0.700350889861)); -#172848 = CARTESIAN_POINT('',(3.14159265359,0.691229631561)); -#172849 = CARTESIAN_POINT('',(3.14159265359,0.672987114959)); -#172850 = CARTESIAN_POINT('',(3.14159265359,0.645623340057)); -#172851 = CARTESIAN_POINT('',(3.14159265359,0.618259565155)); -#172852 = CARTESIAN_POINT('',(3.14159265359,0.590895790252)); -#172853 = CARTESIAN_POINT('',(3.14159265359,0.56353201535)); -#172854 = CARTESIAN_POINT('',(3.14159265359,0.536168240448)); -#172855 = CARTESIAN_POINT('',(3.14159265359,0.508804465546)); -#172856 = CARTESIAN_POINT('',(3.14159265359,0.481440690644)); -#172857 = CARTESIAN_POINT('',(3.14159265359,0.454076915741)); -#172858 = CARTESIAN_POINT('',(3.14159265359,0.426713140839)); -#172859 = CARTESIAN_POINT('',(3.14159265359,0.399349365937)); -#172860 = CARTESIAN_POINT('',(3.14159265359,0.371985591035)); -#172861 = CARTESIAN_POINT('',(3.14159265359,0.344621816132)); -#172862 = CARTESIAN_POINT('',(3.14159265359,0.31725804123)); -#172863 = CARTESIAN_POINT('',(3.14159265359,0.289894266328)); -#172864 = CARTESIAN_POINT('',(3.14159265359,0.262530491426)); -#172865 = CARTESIAN_POINT('',(3.14159265359,0.235166716524)); -#172866 = CARTESIAN_POINT('',(3.14159265359,0.207802941621)); -#172867 = CARTESIAN_POINT('',(3.14159265359,0.180439166719)); -#172868 = CARTESIAN_POINT('',(3.14159265359,0.153075391817)); -#172869 = CARTESIAN_POINT('',(3.14159265359,0.125711616915)); -#172870 = CARTESIAN_POINT('',(3.14159265359,0.107469100313)); -#172871 = CARTESIAN_POINT('',(3.14159265359,9.834784201249E-002)); -#172872 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172873 = ORIENTED_EDGE('',*,*,#172874,.T.); -#172874 = EDGE_CURVE('',#170604,#172875,#172877,.T.); -#172875 = VERTEX_POINT('',#172876); -#172876 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, +#175239 = CARTESIAN_POINT('',(3.14159265359,0.700350889861)); +#175240 = CARTESIAN_POINT('',(3.14159265359,0.691229631561)); +#175241 = CARTESIAN_POINT('',(3.14159265359,0.672987114959)); +#175242 = CARTESIAN_POINT('',(3.14159265359,0.645623340057)); +#175243 = CARTESIAN_POINT('',(3.14159265359,0.618259565155)); +#175244 = CARTESIAN_POINT('',(3.14159265359,0.590895790252)); +#175245 = CARTESIAN_POINT('',(3.14159265359,0.56353201535)); +#175246 = CARTESIAN_POINT('',(3.14159265359,0.536168240448)); +#175247 = CARTESIAN_POINT('',(3.14159265359,0.508804465546)); +#175248 = CARTESIAN_POINT('',(3.14159265359,0.481440690644)); +#175249 = CARTESIAN_POINT('',(3.14159265359,0.454076915741)); +#175250 = CARTESIAN_POINT('',(3.14159265359,0.426713140839)); +#175251 = CARTESIAN_POINT('',(3.14159265359,0.399349365937)); +#175252 = CARTESIAN_POINT('',(3.14159265359,0.371985591035)); +#175253 = CARTESIAN_POINT('',(3.14159265359,0.344621816132)); +#175254 = CARTESIAN_POINT('',(3.14159265359,0.31725804123)); +#175255 = CARTESIAN_POINT('',(3.14159265359,0.289894266328)); +#175256 = CARTESIAN_POINT('',(3.14159265359,0.262530491426)); +#175257 = CARTESIAN_POINT('',(3.14159265359,0.235166716524)); +#175258 = CARTESIAN_POINT('',(3.14159265359,0.207802941621)); +#175259 = CARTESIAN_POINT('',(3.14159265359,0.180439166719)); +#175260 = CARTESIAN_POINT('',(3.14159265359,0.153075391817)); +#175261 = CARTESIAN_POINT('',(3.14159265359,0.125711616915)); +#175262 = CARTESIAN_POINT('',(3.14159265359,0.107469100313)); +#175263 = CARTESIAN_POINT('',(3.14159265359,9.834784201249E-002)); +#175264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175265 = ORIENTED_EDGE('',*,*,#175266,.T.); +#175266 = EDGE_CURVE('',#172996,#175267,#175269,.T.); +#175267 = VERTEX_POINT('',#175268); +#175268 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, 1.162940952255)); -#172877 = SURFACE_CURVE('',#172878,(#172882,#172889),.PCURVE_S1.); -#172878 = LINE('',#172879,#172880); -#172879 = CARTESIAN_POINT('',(1.319160426457,-0.494341610598, +#175269 = SURFACE_CURVE('',#175270,(#175274,#175281),.PCURVE_S1.); +#175270 = LINE('',#175271,#175272); +#175271 = CARTESIAN_POINT('',(1.319160426457,-0.494341610598, 1.162940952255)); -#172880 = VECTOR('',#172881,1.); -#172881 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#172882 = PCURVE('',#171756,#172883); -#172883 = DEFINITIONAL_REPRESENTATION('',(#172884),#172888); -#172884 = LINE('',#172885,#172886); -#172885 = CARTESIAN_POINT('',(-0.582799358847,-1.294341610598)); -#172886 = VECTOR('',#172887,1.); -#172887 = DIRECTION('',(3.50765213726E-017,-1.)); -#172888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172889 = PCURVE('',#170862,#172890); -#172890 = DEFINITIONAL_REPRESENTATION('',(#172891),#172917); -#172891 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172892,#172893,#172894, - #172895,#172896,#172897,#172898,#172899,#172900,#172901,#172902, - #172903,#172904,#172905,#172906,#172907,#172908,#172909,#172910, - #172911,#172912,#172913,#172914,#172915,#172916),.UNSPECIFIED.,.F., +#175272 = VECTOR('',#175273,1.); +#175273 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#175274 = PCURVE('',#174148,#175275); +#175275 = DEFINITIONAL_REPRESENTATION('',(#175276),#175280); +#175276 = LINE('',#175277,#175278); +#175277 = CARTESIAN_POINT('',(-0.582799358847,-1.294341610598)); +#175278 = VECTOR('',#175279,1.); +#175279 = DIRECTION('',(3.50765213726E-017,-1.)); +#175280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175281 = PCURVE('',#173254,#175282); +#175282 = DEFINITIONAL_REPRESENTATION('',(#175283),#175309); +#175283 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175284,#175285,#175286, + #175287,#175288,#175289,#175290,#175291,#175292,#175293,#175294, + #175295,#175296,#175297,#175298,#175299,#175300,#175301,#175302, + #175303,#175304,#175305,#175306,#175307,#175308),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.998613163111, -0.952770294701,-0.906927426291,-0.86108455788,-0.81524168947, -0.76939882106,-0.72355595265,-0.677713084239,-0.631870215829, @@ -213929,58 +216931,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.402655873777,-0.356813005367,-0.310970136957,-0.265127268546, -0.219284400136,-0.173441531726,-0.127598663315,-8.175579490513E-002 ,-3.591292649481E-002,9.929941915506E-003),.UNSPECIFIED.); -#172892 = CARTESIAN_POINT('',(2.879793265791,1.304271552513)); -#172893 = CARTESIAN_POINT('',(2.879793265791,1.288990596377)); -#172894 = CARTESIAN_POINT('',(2.879793265791,1.258428684103)); -#172895 = CARTESIAN_POINT('',(2.879793265791,1.212585815693)); -#172896 = CARTESIAN_POINT('',(2.879793265791,1.166742947283)); -#172897 = CARTESIAN_POINT('',(2.879793265791,1.120900078872)); -#172898 = CARTESIAN_POINT('',(2.879793265791,1.075057210462)); -#172899 = CARTESIAN_POINT('',(2.879793265791,1.029214342052)); -#172900 = CARTESIAN_POINT('',(2.879793265791,0.983371473641)); -#172901 = CARTESIAN_POINT('',(2.879793265791,0.937528605231)); -#172902 = CARTESIAN_POINT('',(2.879793265791,0.891685736821)); -#172903 = CARTESIAN_POINT('',(2.879793265791,0.84584286841)); -#172904 = CARTESIAN_POINT('',(2.879793265791,0.8)); -#172905 = CARTESIAN_POINT('',(2.879793265791,0.75415713159)); -#172906 = CARTESIAN_POINT('',(2.879793265791,0.708314263179)); -#172907 = CARTESIAN_POINT('',(2.879793265791,0.662471394769)); -#172908 = CARTESIAN_POINT('',(2.879793265791,0.616628526359)); -#172909 = CARTESIAN_POINT('',(2.879793265791,0.570785657948)); -#172910 = CARTESIAN_POINT('',(2.879793265791,0.524942789538)); -#172911 = CARTESIAN_POINT('',(2.879793265791,0.479099921128)); -#172912 = CARTESIAN_POINT('',(2.879793265791,0.433257052717)); -#172913 = CARTESIAN_POINT('',(2.879793265791,0.387414184307)); -#172914 = CARTESIAN_POINT('',(2.879793265791,0.341571315897)); -#172915 = CARTESIAN_POINT('',(2.879793265791,0.311009403623)); -#172916 = CARTESIAN_POINT('',(2.879793265791,0.295728447487)); -#172917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172918 = ORIENTED_EDGE('',*,*,#172919,.T.); -#172919 = EDGE_CURVE('',#172875,#171603,#172920,.T.); -#172920 = SURFACE_CURVE('',#172921,(#172925,#172932),.PCURVE_S1.); -#172921 = LINE('',#172922,#172923); -#172922 = CARTESIAN_POINT('',(1.378645620286,-0.563756746343, +#175284 = CARTESIAN_POINT('',(2.879793265791,1.304271552513)); +#175285 = CARTESIAN_POINT('',(2.879793265791,1.288990596377)); +#175286 = CARTESIAN_POINT('',(2.879793265791,1.258428684103)); +#175287 = CARTESIAN_POINT('',(2.879793265791,1.212585815693)); +#175288 = CARTESIAN_POINT('',(2.879793265791,1.166742947283)); +#175289 = CARTESIAN_POINT('',(2.879793265791,1.120900078872)); +#175290 = CARTESIAN_POINT('',(2.879793265791,1.075057210462)); +#175291 = CARTESIAN_POINT('',(2.879793265791,1.029214342052)); +#175292 = CARTESIAN_POINT('',(2.879793265791,0.983371473641)); +#175293 = CARTESIAN_POINT('',(2.879793265791,0.937528605231)); +#175294 = CARTESIAN_POINT('',(2.879793265791,0.891685736821)); +#175295 = CARTESIAN_POINT('',(2.879793265791,0.84584286841)); +#175296 = CARTESIAN_POINT('',(2.879793265791,0.8)); +#175297 = CARTESIAN_POINT('',(2.879793265791,0.75415713159)); +#175298 = CARTESIAN_POINT('',(2.879793265791,0.708314263179)); +#175299 = CARTESIAN_POINT('',(2.879793265791,0.662471394769)); +#175300 = CARTESIAN_POINT('',(2.879793265791,0.616628526359)); +#175301 = CARTESIAN_POINT('',(2.879793265791,0.570785657948)); +#175302 = CARTESIAN_POINT('',(2.879793265791,0.524942789538)); +#175303 = CARTESIAN_POINT('',(2.879793265791,0.479099921128)); +#175304 = CARTESIAN_POINT('',(2.879793265791,0.433257052717)); +#175305 = CARTESIAN_POINT('',(2.879793265791,0.387414184307)); +#175306 = CARTESIAN_POINT('',(2.879793265791,0.341571315897)); +#175307 = CARTESIAN_POINT('',(2.879793265791,0.311009403623)); +#175308 = CARTESIAN_POINT('',(2.879793265791,0.295728447487)); +#175309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175310 = ORIENTED_EDGE('',*,*,#175311,.T.); +#175311 = EDGE_CURVE('',#175267,#173995,#175312,.T.); +#175312 = SURFACE_CURVE('',#175313,(#175317,#175324),.PCURVE_S1.); +#175313 = LINE('',#175314,#175315); +#175314 = CARTESIAN_POINT('',(1.378645620286,-0.563756746343, 0.940939186586)); -#172923 = VECTOR('',#172924,1.); -#172924 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) - ); -#172925 = PCURVE('',#171756,#172926); -#172926 = DEFINITIONAL_REPRESENTATION('',(#172927),#172931); -#172927 = LINE('',#172928,#172929); -#172928 = CARTESIAN_POINT('',(-0.352966218841,-1.363756746343)); -#172929 = VECTOR('',#172930,1.); -#172930 = DIRECTION('',(0.968100345886,-0.250562807086)); -#172931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172932 = PCURVE('',#170109,#172933); -#172933 = DEFINITIONAL_REPRESENTATION('',(#172934),#172960); -#172934 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172935,#172936,#172937, - #172938,#172939,#172940,#172941,#172942,#172943,#172944,#172945, - #172946,#172947,#172948,#172949,#172950,#172951,#172952,#172953, - #172954,#172955,#172956,#172957,#172958,#172959),.UNSPECIFIED.,.F., +#175315 = VECTOR('',#175316,1.); +#175316 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) + ); +#175317 = PCURVE('',#174148,#175318); +#175318 = DEFINITIONAL_REPRESENTATION('',(#175319),#175323); +#175319 = LINE('',#175320,#175321); +#175320 = CARTESIAN_POINT('',(-0.352966218841,-1.363756746343)); +#175321 = VECTOR('',#175322,1.); +#175322 = DIRECTION('',(0.968100345886,-0.250562807086)); +#175323 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175324 = PCURVE('',#172501,#175325); +#175325 = DEFINITIONAL_REPRESENTATION('',(#175326),#175352); +#175326 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175327,#175328,#175329, + #175330,#175331,#175332,#175333,#175334,#175335,#175336,#175337, + #175338,#175339,#175340,#175341,#175342,#175343,#175344,#175345, + #175346,#175347,#175348,#175349,#175350,#175351),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.237406319482, -0.21004254458,-0.182678769678,-0.155314994776,-0.127951219874, -0.100587444971,-7.322367006908E-002,-4.585989516686E-002, @@ -213989,61 +216991,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.145686529149,0.173050304051,0.200414078953,0.227777853855, 0.255141628758,0.28250540366,0.309869178562,0.337232953464, 0.364596728366),.UNSPECIFIED.); -#172935 = CARTESIAN_POINT('',(3.14159265359,-0.237406319482)); -#172936 = CARTESIAN_POINT('',(3.14159265359,-0.228285061182)); -#172937 = CARTESIAN_POINT('',(3.14159265359,-0.21004254458)); -#172938 = CARTESIAN_POINT('',(3.14159265359,-0.182678769678)); -#172939 = CARTESIAN_POINT('',(3.14159265359,-0.155314994776)); -#172940 = CARTESIAN_POINT('',(3.14159265359,-0.127951219874)); -#172941 = CARTESIAN_POINT('',(3.14159265359,-0.100587444971)); -#172942 = CARTESIAN_POINT('',(3.14159265359,-7.322367006908E-002)); -#172943 = CARTESIAN_POINT('',(3.14159265359,-4.585989516686E-002)); -#172944 = CARTESIAN_POINT('',(3.14159265359,-1.849612026464E-002)); -#172945 = CARTESIAN_POINT('',(3.14159265359,8.867654637579E-003)); -#172946 = CARTESIAN_POINT('',(3.14159265359,3.62314295398E-002)); -#172947 = CARTESIAN_POINT('',(3.14159265359,6.359520444202E-002)); -#172948 = CARTESIAN_POINT('',(3.14159265359,9.095897934424E-002)); -#172949 = CARTESIAN_POINT('',(3.14159265359,0.118322754246)); -#172950 = CARTESIAN_POINT('',(3.14159265359,0.145686529149)); -#172951 = CARTESIAN_POINT('',(3.14159265359,0.173050304051)); -#172952 = CARTESIAN_POINT('',(3.14159265359,0.200414078953)); -#172953 = CARTESIAN_POINT('',(3.14159265359,0.227777853855)); -#172954 = CARTESIAN_POINT('',(3.14159265359,0.255141628758)); -#172955 = CARTESIAN_POINT('',(3.14159265359,0.28250540366)); -#172956 = CARTESIAN_POINT('',(3.14159265359,0.309869178562)); -#172957 = CARTESIAN_POINT('',(3.14159265359,0.337232953464)); -#172958 = CARTESIAN_POINT('',(3.14159265359,0.355475470066)); -#172959 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); -#172960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172961 = ORIENTED_EDGE('',*,*,#171742,.T.); -#172962 = ADVANCED_FACE('',(#172963),#172275,.T.); -#172963 = FACE_BOUND('',#172964,.T.); -#172964 = EDGE_LOOP('',(#172965,#173008,#173053,#173096)); -#172965 = ORIENTED_EDGE('',*,*,#172966,.T.); -#172966 = EDGE_CURVE('',#172217,#169774,#172967,.T.); -#172967 = SURFACE_CURVE('',#172968,(#172972,#172979),.PCURVE_S1.); -#172968 = LINE('',#172969,#172970); -#172969 = CARTESIAN_POINT('',(-1.378645620286,-0.563756746343, +#175327 = CARTESIAN_POINT('',(3.14159265359,-0.237406319482)); +#175328 = CARTESIAN_POINT('',(3.14159265359,-0.228285061182)); +#175329 = CARTESIAN_POINT('',(3.14159265359,-0.21004254458)); +#175330 = CARTESIAN_POINT('',(3.14159265359,-0.182678769678)); +#175331 = CARTESIAN_POINT('',(3.14159265359,-0.155314994776)); +#175332 = CARTESIAN_POINT('',(3.14159265359,-0.127951219874)); +#175333 = CARTESIAN_POINT('',(3.14159265359,-0.100587444971)); +#175334 = CARTESIAN_POINT('',(3.14159265359,-7.322367006908E-002)); +#175335 = CARTESIAN_POINT('',(3.14159265359,-4.585989516686E-002)); +#175336 = CARTESIAN_POINT('',(3.14159265359,-1.849612026464E-002)); +#175337 = CARTESIAN_POINT('',(3.14159265359,8.867654637579E-003)); +#175338 = CARTESIAN_POINT('',(3.14159265359,3.62314295398E-002)); +#175339 = CARTESIAN_POINT('',(3.14159265359,6.359520444202E-002)); +#175340 = CARTESIAN_POINT('',(3.14159265359,9.095897934424E-002)); +#175341 = CARTESIAN_POINT('',(3.14159265359,0.118322754246)); +#175342 = CARTESIAN_POINT('',(3.14159265359,0.145686529149)); +#175343 = CARTESIAN_POINT('',(3.14159265359,0.173050304051)); +#175344 = CARTESIAN_POINT('',(3.14159265359,0.200414078953)); +#175345 = CARTESIAN_POINT('',(3.14159265359,0.227777853855)); +#175346 = CARTESIAN_POINT('',(3.14159265359,0.255141628758)); +#175347 = CARTESIAN_POINT('',(3.14159265359,0.28250540366)); +#175348 = CARTESIAN_POINT('',(3.14159265359,0.309869178562)); +#175349 = CARTESIAN_POINT('',(3.14159265359,0.337232953464)); +#175350 = CARTESIAN_POINT('',(3.14159265359,0.355475470066)); +#175351 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); +#175352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175353 = ORIENTED_EDGE('',*,*,#174134,.T.); +#175354 = ADVANCED_FACE('',(#175355),#174667,.T.); +#175355 = FACE_BOUND('',#175356,.T.); +#175356 = EDGE_LOOP('',(#175357,#175400,#175445,#175488)); +#175357 = ORIENTED_EDGE('',*,*,#175358,.T.); +#175358 = EDGE_CURVE('',#174609,#172166,#175359,.T.); +#175359 = SURFACE_CURVE('',#175360,(#175364,#175371),.PCURVE_S1.); +#175360 = LINE('',#175361,#175362); +#175361 = CARTESIAN_POINT('',(-1.378645620286,-0.563756746343, 0.940939186586)); -#172970 = VECTOR('',#172971,1.); -#172971 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#172972 = PCURVE('',#172275,#172973); -#172973 = DEFINITIONAL_REPRESENTATION('',(#172974),#172978); -#172974 = LINE('',#172975,#172976); -#172975 = CARTESIAN_POINT('',(0.352966218841,-1.363756746343)); -#172976 = VECTOR('',#172977,1.); -#172977 = DIRECTION('',(0.968100345886,0.250562807086)); -#172978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#172979 = PCURVE('',#169829,#172980); -#172980 = DEFINITIONAL_REPRESENTATION('',(#172981),#173007); -#172981 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#172982,#172983,#172984, - #172985,#172986,#172987,#172988,#172989,#172990,#172991,#172992, - #172993,#172994,#172995,#172996,#172997,#172998,#172999,#173000, - #173001,#173002,#173003,#173004,#173005,#173006),.UNSPECIFIED.,.F., +#175362 = VECTOR('',#175363,1.); +#175363 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#175364 = PCURVE('',#174667,#175365); +#175365 = DEFINITIONAL_REPRESENTATION('',(#175366),#175370); +#175366 = LINE('',#175367,#175368); +#175367 = CARTESIAN_POINT('',(0.352966218841,-1.363756746343)); +#175368 = VECTOR('',#175369,1.); +#175369 = DIRECTION('',(0.968100345886,0.250562807086)); +#175370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175371 = PCURVE('',#172221,#175372); +#175372 = DEFINITIONAL_REPRESENTATION('',(#175373),#175399); +#175373 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175374,#175375,#175376, + #175377,#175378,#175379,#175380,#175381,#175382,#175383,#175384, + #175385,#175386,#175387,#175388,#175389,#175390,#175391,#175392, + #175393,#175394,#175395,#175396,#175397,#175398),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.364596728366, -0.337232953464,-0.309869178562,-0.28250540366,-0.255141628758, -0.227777853855,-0.200414078953,-0.173050304051,-0.145686529149, @@ -214052,60 +217054,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.585989516686E-002,7.322367006908E-002,0.100587444971, 0.127951219874,0.155314994776,0.182678769678,0.21004254458, 0.237406319482),.UNSPECIFIED.); -#172982 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#172983 = CARTESIAN_POINT('',(6.28318530718,-4.542502127148E-002)); -#172984 = CARTESIAN_POINT('',(6.28318530718,-6.366753787296E-002)); -#172985 = CARTESIAN_POINT('',(6.28318530718,-9.103131277518E-002)); -#172986 = CARTESIAN_POINT('',(6.28318530718,-0.118395087677)); -#172987 = CARTESIAN_POINT('',(6.28318530718,-0.14575886258)); -#172988 = CARTESIAN_POINT('',(6.28318530718,-0.173122637482)); -#172989 = CARTESIAN_POINT('',(6.28318530718,-0.200486412384)); -#172990 = CARTESIAN_POINT('',(6.28318530718,-0.227850187286)); -#172991 = CARTESIAN_POINT('',(6.28318530718,-0.255213962188)); -#172992 = CARTESIAN_POINT('',(6.28318530718,-0.282577737091)); -#172993 = CARTESIAN_POINT('',(6.28318530718,-0.309941511993)); -#172994 = CARTESIAN_POINT('',(6.28318530718,-0.337305286895)); -#172995 = CARTESIAN_POINT('',(6.28318530718,-0.364669061797)); -#172996 = CARTESIAN_POINT('',(6.28318530718,-0.3920328367)); -#172997 = CARTESIAN_POINT('',(6.28318530718,-0.419396611602)); -#172998 = CARTESIAN_POINT('',(6.28318530718,-0.446760386504)); -#172999 = CARTESIAN_POINT('',(6.28318530718,-0.474124161406)); -#173000 = CARTESIAN_POINT('',(6.28318530718,-0.501487936308)); -#173001 = CARTESIAN_POINT('',(6.28318530718,-0.528851711211)); -#173002 = CARTESIAN_POINT('',(6.28318530718,-0.556215486113)); -#173003 = CARTESIAN_POINT('',(6.28318530718,-0.583579261015)); -#173004 = CARTESIAN_POINT('',(6.28318530718,-0.610943035917)); -#173005 = CARTESIAN_POINT('',(6.28318530718,-0.629185552519)); -#173006 = CARTESIAN_POINT('',(6.28318530718,-0.63830681082)); -#173007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173008 = ORIENTED_EDGE('',*,*,#173009,.T.); -#173009 = EDGE_CURVE('',#169774,#173010,#173012,.T.); -#173010 = VERTEX_POINT('',#173011); -#173011 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, +#175374 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#175375 = CARTESIAN_POINT('',(6.28318530718,-4.542502127148E-002)); +#175376 = CARTESIAN_POINT('',(6.28318530718,-6.366753787296E-002)); +#175377 = CARTESIAN_POINT('',(6.28318530718,-9.103131277518E-002)); +#175378 = CARTESIAN_POINT('',(6.28318530718,-0.118395087677)); +#175379 = CARTESIAN_POINT('',(6.28318530718,-0.14575886258)); +#175380 = CARTESIAN_POINT('',(6.28318530718,-0.173122637482)); +#175381 = CARTESIAN_POINT('',(6.28318530718,-0.200486412384)); +#175382 = CARTESIAN_POINT('',(6.28318530718,-0.227850187286)); +#175383 = CARTESIAN_POINT('',(6.28318530718,-0.255213962188)); +#175384 = CARTESIAN_POINT('',(6.28318530718,-0.282577737091)); +#175385 = CARTESIAN_POINT('',(6.28318530718,-0.309941511993)); +#175386 = CARTESIAN_POINT('',(6.28318530718,-0.337305286895)); +#175387 = CARTESIAN_POINT('',(6.28318530718,-0.364669061797)); +#175388 = CARTESIAN_POINT('',(6.28318530718,-0.3920328367)); +#175389 = CARTESIAN_POINT('',(6.28318530718,-0.419396611602)); +#175390 = CARTESIAN_POINT('',(6.28318530718,-0.446760386504)); +#175391 = CARTESIAN_POINT('',(6.28318530718,-0.474124161406)); +#175392 = CARTESIAN_POINT('',(6.28318530718,-0.501487936308)); +#175393 = CARTESIAN_POINT('',(6.28318530718,-0.528851711211)); +#175394 = CARTESIAN_POINT('',(6.28318530718,-0.556215486113)); +#175395 = CARTESIAN_POINT('',(6.28318530718,-0.583579261015)); +#175396 = CARTESIAN_POINT('',(6.28318530718,-0.610943035917)); +#175397 = CARTESIAN_POINT('',(6.28318530718,-0.629185552519)); +#175398 = CARTESIAN_POINT('',(6.28318530718,-0.63830681082)); +#175399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175400 = ORIENTED_EDGE('',*,*,#175401,.T.); +#175401 = EDGE_CURVE('',#172166,#175402,#175404,.T.); +#175402 = VERTEX_POINT('',#175403); +#175403 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, 1.162940952255)); -#173012 = SURFACE_CURVE('',#173013,(#173017,#173024),.PCURVE_S1.); -#173013 = LINE('',#173014,#173015); -#173014 = CARTESIAN_POINT('',(-1.319160426457,0.494341610598, +#175404 = SURFACE_CURVE('',#175405,(#175409,#175416),.PCURVE_S1.); +#175405 = LINE('',#175406,#175407); +#175406 = CARTESIAN_POINT('',(-1.319160426457,0.494341610598, 1.162940952255)); -#173015 = VECTOR('',#173016,1.); -#173016 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#173017 = PCURVE('',#172275,#173018); -#173018 = DEFINITIONAL_REPRESENTATION('',(#173019),#173023); -#173019 = LINE('',#173020,#173021); -#173020 = CARTESIAN_POINT('',(0.582799358847,-0.305658389402)); -#173021 = VECTOR('',#173022,1.); -#173022 = DIRECTION('',(-3.50765213726E-017,1.)); -#173023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173024 = PCURVE('',#170037,#173025); -#173025 = DEFINITIONAL_REPRESENTATION('',(#173026),#173052); -#173026 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173027,#173028,#173029, - #173030,#173031,#173032,#173033,#173034,#173035,#173036,#173037, - #173038,#173039,#173040,#173041,#173042,#173043,#173044,#173045, - #173046,#173047,#173048,#173049,#173050,#173051),.UNSPECIFIED.,.F., +#175407 = VECTOR('',#175408,1.); +#175408 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#175409 = PCURVE('',#174667,#175410); +#175410 = DEFINITIONAL_REPRESENTATION('',(#175411),#175415); +#175411 = LINE('',#175412,#175413); +#175412 = CARTESIAN_POINT('',(0.582799358847,-0.305658389402)); +#175413 = VECTOR('',#175414,1.); +#175414 = DIRECTION('',(-3.50765213726E-017,1.)); +#175415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175416 = PCURVE('',#172429,#175417); +#175417 = DEFINITIONAL_REPRESENTATION('',(#175418),#175444); +#175418 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175419,#175420,#175421, + #175422,#175423,#175424,#175425,#175426,#175427,#175428,#175429, + #175430,#175431,#175432,#175433,#175434,#175435,#175436,#175437, + #175438,#175439,#175440,#175441,#175442,#175443),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.998613163111, -0.952770294701,-0.906927426291,-0.86108455788,-0.81524168947, -0.76939882106,-0.72355595265,-0.677713084239,-0.631870215829, @@ -214113,58 +217115,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.402655873777,-0.356813005367,-0.310970136957,-0.265127268546, -0.219284400136,-0.173441531726,-0.127598663315,-8.175579490513E-002 ,-3.591292649481E-002,9.929941915506E-003),.UNSPECIFIED.); -#173027 = CARTESIAN_POINT('',(2.879793265791,-0.295728447487)); -#173028 = CARTESIAN_POINT('',(2.879793265791,-0.311009403623)); -#173029 = CARTESIAN_POINT('',(2.879793265791,-0.341571315897)); -#173030 = CARTESIAN_POINT('',(2.879793265791,-0.387414184307)); -#173031 = CARTESIAN_POINT('',(2.879793265791,-0.433257052717)); -#173032 = CARTESIAN_POINT('',(2.879793265791,-0.479099921128)); -#173033 = CARTESIAN_POINT('',(2.879793265791,-0.524942789538)); -#173034 = CARTESIAN_POINT('',(2.879793265791,-0.570785657948)); -#173035 = CARTESIAN_POINT('',(2.879793265791,-0.616628526359)); -#173036 = CARTESIAN_POINT('',(2.879793265791,-0.662471394769)); -#173037 = CARTESIAN_POINT('',(2.879793265791,-0.708314263179)); -#173038 = CARTESIAN_POINT('',(2.879793265791,-0.75415713159)); -#173039 = CARTESIAN_POINT('',(2.879793265791,-0.8)); -#173040 = CARTESIAN_POINT('',(2.879793265791,-0.84584286841)); -#173041 = CARTESIAN_POINT('',(2.879793265791,-0.891685736821)); -#173042 = CARTESIAN_POINT('',(2.879793265791,-0.937528605231)); -#173043 = CARTESIAN_POINT('',(2.879793265791,-0.983371473641)); -#173044 = CARTESIAN_POINT('',(2.879793265791,-1.029214342052)); -#173045 = CARTESIAN_POINT('',(2.879793265791,-1.075057210462)); -#173046 = CARTESIAN_POINT('',(2.879793265791,-1.120900078872)); -#173047 = CARTESIAN_POINT('',(2.879793265791,-1.166742947283)); -#173048 = CARTESIAN_POINT('',(2.879793265791,-1.212585815693)); -#173049 = CARTESIAN_POINT('',(2.879793265791,-1.258428684103)); -#173050 = CARTESIAN_POINT('',(2.879793265791,-1.288990596377)); -#173051 = CARTESIAN_POINT('',(2.879793265791,-1.304271552513)); -#173052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173053 = ORIENTED_EDGE('',*,*,#173054,.T.); -#173054 = EDGE_CURVE('',#173010,#172122,#173055,.T.); -#173055 = SURFACE_CURVE('',#173056,(#173060,#173067),.PCURVE_S1.); -#173056 = LINE('',#173057,#173058); -#173057 = CARTESIAN_POINT('',(-1.479096372758,0.664207498814, +#175419 = CARTESIAN_POINT('',(2.879793265791,-0.295728447487)); +#175420 = CARTESIAN_POINT('',(2.879793265791,-0.311009403623)); +#175421 = CARTESIAN_POINT('',(2.879793265791,-0.341571315897)); +#175422 = CARTESIAN_POINT('',(2.879793265791,-0.387414184307)); +#175423 = CARTESIAN_POINT('',(2.879793265791,-0.433257052717)); +#175424 = CARTESIAN_POINT('',(2.879793265791,-0.479099921128)); +#175425 = CARTESIAN_POINT('',(2.879793265791,-0.524942789538)); +#175426 = CARTESIAN_POINT('',(2.879793265791,-0.570785657948)); +#175427 = CARTESIAN_POINT('',(2.879793265791,-0.616628526359)); +#175428 = CARTESIAN_POINT('',(2.879793265791,-0.662471394769)); +#175429 = CARTESIAN_POINT('',(2.879793265791,-0.708314263179)); +#175430 = CARTESIAN_POINT('',(2.879793265791,-0.75415713159)); +#175431 = CARTESIAN_POINT('',(2.879793265791,-0.8)); +#175432 = CARTESIAN_POINT('',(2.879793265791,-0.84584286841)); +#175433 = CARTESIAN_POINT('',(2.879793265791,-0.891685736821)); +#175434 = CARTESIAN_POINT('',(2.879793265791,-0.937528605231)); +#175435 = CARTESIAN_POINT('',(2.879793265791,-0.983371473641)); +#175436 = CARTESIAN_POINT('',(2.879793265791,-1.029214342052)); +#175437 = CARTESIAN_POINT('',(2.879793265791,-1.075057210462)); +#175438 = CARTESIAN_POINT('',(2.879793265791,-1.120900078872)); +#175439 = CARTESIAN_POINT('',(2.879793265791,-1.166742947283)); +#175440 = CARTESIAN_POINT('',(2.879793265791,-1.212585815693)); +#175441 = CARTESIAN_POINT('',(2.879793265791,-1.258428684103)); +#175442 = CARTESIAN_POINT('',(2.879793265791,-1.288990596377)); +#175443 = CARTESIAN_POINT('',(2.879793265791,-1.304271552513)); +#175444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175445 = ORIENTED_EDGE('',*,*,#175446,.T.); +#175446 = EDGE_CURVE('',#175402,#174514,#175447,.T.); +#175447 = SURFACE_CURVE('',#175448,(#175452,#175459),.PCURVE_S1.); +#175448 = LINE('',#175449,#175450); +#175449 = CARTESIAN_POINT('',(-1.479096372758,0.664207498814, 0.566051874704)); -#173058 = VECTOR('',#173059,1.); -#173059 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) - ); -#173060 = PCURVE('',#172275,#173061); -#173061 = DEFINITIONAL_REPRESENTATION('',(#173062),#173066); -#173062 = LINE('',#173063,#173064); -#173063 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#173064 = VECTOR('',#173065,1.); -#173065 = DIRECTION('',(-0.968100345886,0.250562807086)); -#173066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173067 = PCURVE('',#170384,#173068); -#173068 = DEFINITIONAL_REPRESENTATION('',(#173069),#173095); -#173069 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173070,#173071,#173072, - #173073,#173074,#173075,#173076,#173077,#173078,#173079,#173080, - #173081,#173082,#173083,#173084,#173085,#173086,#173087,#173088, - #173089,#173090,#173091,#173092,#173093,#173094),.UNSPECIFIED.,.F., +#175450 = VECTOR('',#175451,1.); +#175451 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) + ); +#175452 = PCURVE('',#174667,#175453); +#175453 = DEFINITIONAL_REPRESENTATION('',(#175454),#175458); +#175454 = LINE('',#175455,#175456); +#175455 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#175456 = VECTOR('',#175457,1.); +#175457 = DIRECTION('',(-0.968100345886,0.250562807086)); +#175458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175459 = PCURVE('',#172776,#175460); +#175460 = DEFINITIONAL_REPRESENTATION('',(#175461),#175487); +#175461 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175462,#175463,#175464, + #175465,#175466,#175467,#175468,#175469,#175470,#175471,#175472, + #175473,#175474,#175475,#175476,#175477,#175478,#175479,#175480, + #175481,#175482,#175483,#175484,#175485,#175486),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.63830681082, -0.610943035917,-0.583579261015,-0.556215486113,-0.528851711211, -0.501487936308,-0.474124161406,-0.446760386504,-0.419396611602, @@ -214172,446 +217174,446 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.282577737091,-0.255213962188,-0.227850187286,-0.200486412384, -0.173122637482,-0.14575886258,-0.118395087677,-9.103131277518E-002, -6.366753787296E-002,-3.630376297074E-002),.QUASI_UNIFORM_KNOTS.); -#173070 = CARTESIAN_POINT('',(0.E+000,-0.63830681082)); -#173071 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.629185552519)); -#173072 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.610943035917)); -#173073 = CARTESIAN_POINT('',(0.E+000,-0.583579261015)); -#173074 = CARTESIAN_POINT('',(0.E+000,-0.556215486113)); -#173075 = CARTESIAN_POINT('',(0.E+000,-0.528851711211)); -#173076 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.501487936308)); -#173077 = CARTESIAN_POINT('',(1.7763568394E-015,-0.474124161406)); -#173078 = CARTESIAN_POINT('',(-3.552713678801E-015,-0.446760386504)); -#173079 = CARTESIAN_POINT('',(2.6645352591E-015,-0.419396611602)); -#173080 = CARTESIAN_POINT('',(0.E+000,-0.3920328367)); -#173081 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.364669061797)); -#173082 = CARTESIAN_POINT('',(8.881784197001E-016,-0.337305286895)); -#173083 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.309941511993)); -#173084 = CARTESIAN_POINT('',(0.E+000,-0.282577737091)); -#173085 = CARTESIAN_POINT('',(0.E+000,-0.255213962188)); -#173086 = CARTESIAN_POINT('',(0.E+000,-0.227850187286)); -#173087 = CARTESIAN_POINT('',(0.E+000,-0.200486412384)); -#173088 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.173122637482)); -#173089 = CARTESIAN_POINT('',(8.881784197001E-016,-0.14575886258)); -#173090 = CARTESIAN_POINT('',(1.7763568394E-015,-0.118395087677)); -#173091 = CARTESIAN_POINT('',(-8.881784197001E-016,-9.103131277518E-002) - ); -#173092 = CARTESIAN_POINT('',(-1.7763568394E-015,-6.366753787296E-002)); -#173093 = CARTESIAN_POINT('',(-8.881784197001E-016,-4.542502127148E-002) - ); -#173094 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#173095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173096 = ORIENTED_EDGE('',*,*,#172261,.T.); -#173097 = ADVANCED_FACE('',(#173098),#171904,.T.); -#173098 = FACE_BOUND('',#173099,.T.); -#173099 = EDGE_LOOP('',(#173100,#173101,#173129,#173157,#173183,#173184, - #173212,#173240,#173266,#173267,#173295,#173323,#173349,#173350, - #173378,#173406,#173432,#173433,#173476,#173498)); -#173100 = ORIENTED_EDGE('',*,*,#172097,.T.); -#173101 = ORIENTED_EDGE('',*,*,#173102,.T.); -#173102 = EDGE_CURVE('',#172070,#173103,#173105,.T.); -#173103 = VERTEX_POINT('',#173104); -#173104 = CARTESIAN_POINT('',(-1.165,-0.759807621135,0.75)); -#173105 = SURFACE_CURVE('',#173106,(#173110,#173117),.PCURVE_S1.); -#173106 = LINE('',#173107,#173108); -#173107 = CARTESIAN_POINT('',(-1.165,-0.8,0.6)); -#173108 = VECTOR('',#173109,1.); -#173109 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173110 = PCURVE('',#171904,#173111); -#173111 = DEFINITIONAL_REPRESENTATION('',(#173112),#173116); -#173112 = LINE('',#173113,#173114); -#173113 = CARTESIAN_POINT('',(2.144786184852E-016,0.305)); -#173114 = VECTOR('',#173115,1.); -#173115 = DIRECTION('',(-1.,0.E+000)); -#173116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173117 = PCURVE('',#173118,#173123); -#173118 = PLANE('',#173119); -#173119 = AXIS2_PLACEMENT_3D('',#173120,#173121,#173122); -#173120 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); -#173121 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173122 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173123 = DEFINITIONAL_REPRESENTATION('',(#173124),#173128); -#173124 = LINE('',#173125,#173126); -#173125 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173126 = VECTOR('',#173127,1.); -#173127 = DIRECTION('',(0.965925826289,0.258819045103)); -#173128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173129 = ORIENTED_EDGE('',*,*,#173130,.T.); -#173130 = EDGE_CURVE('',#173103,#173131,#173133,.T.); -#173131 = VERTEX_POINT('',#173132); -#173132 = CARTESIAN_POINT('',(-0.825,-0.759807621135,0.75)); -#173133 = SURFACE_CURVE('',#173134,(#173138,#173145),.PCURVE_S1.); -#173134 = LINE('',#173135,#173136); -#173135 = CARTESIAN_POINT('',(-3.42,-0.759807621135,0.75)); -#173136 = VECTOR('',#173137,1.); -#173137 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173138 = PCURVE('',#171904,#173139); -#173139 = DEFINITIONAL_REPRESENTATION('',(#173140),#173144); -#173140 = LINE('',#173141,#173142); -#173141 = CARTESIAN_POINT('',(-0.155291427062,-1.95)); -#173142 = VECTOR('',#173143,1.); -#173143 = DIRECTION('',(0.E+000,1.)); -#173144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173145 = PCURVE('',#173146,#173151); -#173146 = PLANE('',#173147); -#173147 = AXIS2_PLACEMENT_3D('',#173148,#173149,#173150); -#173148 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); -#173149 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173150 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173151 = DEFINITIONAL_REPRESENTATION('',(#173152),#173156); -#173152 = LINE('',#173153,#173154); -#173153 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); -#173154 = VECTOR('',#173155,1.); -#173155 = DIRECTION('',(1.,0.E+000)); -#173156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173157 = ORIENTED_EDGE('',*,*,#173158,.F.); -#173158 = EDGE_CURVE('',#172047,#173131,#173159,.T.); -#173159 = SURFACE_CURVE('',#173160,(#173164,#173171),.PCURVE_S1.); -#173160 = LINE('',#173161,#173162); -#173161 = CARTESIAN_POINT('',(-0.825,-0.8,0.6)); -#173162 = VECTOR('',#173163,1.); -#173163 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173164 = PCURVE('',#171904,#173165); -#173165 = DEFINITIONAL_REPRESENTATION('',(#173166),#173170); -#173166 = LINE('',#173167,#173168); -#173167 = CARTESIAN_POINT('',(2.144786184852E-016,0.645)); -#173168 = VECTOR('',#173169,1.); -#173169 = DIRECTION('',(-1.,0.E+000)); -#173170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173171 = PCURVE('',#173172,#173177); -#173172 = PLANE('',#173173); -#173173 = AXIS2_PLACEMENT_3D('',#173174,#173175,#173176); -#173174 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); -#173175 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173176 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173177 = DEFINITIONAL_REPRESENTATION('',(#173178),#173182); -#173178 = LINE('',#173179,#173180); -#173179 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173180 = VECTOR('',#173181,1.); -#173181 = DIRECTION('',(0.965925826289,0.258819045103)); -#173182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173183 = ORIENTED_EDGE('',*,*,#172046,.T.); -#173184 = ORIENTED_EDGE('',*,*,#173185,.T.); -#173185 = EDGE_CURVE('',#172019,#173186,#173188,.T.); -#173186 = VERTEX_POINT('',#173187); -#173187 = CARTESIAN_POINT('',(-0.515,-0.759807621135,0.75)); -#173188 = SURFACE_CURVE('',#173189,(#173193,#173200),.PCURVE_S1.); -#173189 = LINE('',#173190,#173191); -#173190 = CARTESIAN_POINT('',(-0.515,-0.8,0.6)); -#173191 = VECTOR('',#173192,1.); -#173192 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173193 = PCURVE('',#171904,#173194); -#173194 = DEFINITIONAL_REPRESENTATION('',(#173195),#173199); -#173195 = LINE('',#173196,#173197); -#173196 = CARTESIAN_POINT('',(1.072393092426E-016,0.955)); -#173197 = VECTOR('',#173198,1.); -#173198 = DIRECTION('',(-1.,0.E+000)); -#173199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173200 = PCURVE('',#173201,#173206); -#173201 = PLANE('',#173202); -#173202 = AXIS2_PLACEMENT_3D('',#173203,#173204,#173205); -#173203 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); -#173204 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173205 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173206 = DEFINITIONAL_REPRESENTATION('',(#173207),#173211); -#173207 = LINE('',#173208,#173209); -#173208 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173209 = VECTOR('',#173210,1.); -#173210 = DIRECTION('',(0.965925826289,0.258819045103)); -#173211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173212 = ORIENTED_EDGE('',*,*,#173213,.T.); -#173213 = EDGE_CURVE('',#173186,#173214,#173216,.T.); -#173214 = VERTEX_POINT('',#173215); -#173215 = CARTESIAN_POINT('',(-0.175,-0.759807621135,0.75)); -#173216 = SURFACE_CURVE('',#173217,(#173221,#173228),.PCURVE_S1.); -#173217 = LINE('',#173218,#173219); -#173218 = CARTESIAN_POINT('',(-2.77,-0.759807621135,0.75)); -#173219 = VECTOR('',#173220,1.); -#173220 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173221 = PCURVE('',#171904,#173222); -#173222 = DEFINITIONAL_REPRESENTATION('',(#173223),#173227); -#173223 = LINE('',#173224,#173225); -#173224 = CARTESIAN_POINT('',(-0.155291427062,-1.3)); -#173225 = VECTOR('',#173226,1.); -#173226 = DIRECTION('',(0.E+000,1.)); -#173227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173228 = PCURVE('',#173229,#173234); -#173229 = PLANE('',#173230); -#173230 = AXIS2_PLACEMENT_3D('',#173231,#173232,#173233); -#173231 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); -#173232 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173233 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173234 = DEFINITIONAL_REPRESENTATION('',(#173235),#173239); -#173235 = LINE('',#173236,#173237); -#173236 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); -#173237 = VECTOR('',#173238,1.); -#173238 = DIRECTION('',(1.,0.E+000)); -#173239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173240 = ORIENTED_EDGE('',*,*,#173241,.F.); -#173241 = EDGE_CURVE('',#171996,#173214,#173242,.T.); -#173242 = SURFACE_CURVE('',#173243,(#173247,#173254),.PCURVE_S1.); -#173243 = LINE('',#173244,#173245); -#173244 = CARTESIAN_POINT('',(-0.175,-0.8,0.6)); -#173245 = VECTOR('',#173246,1.); -#173246 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173247 = PCURVE('',#171904,#173248); -#173248 = DEFINITIONAL_REPRESENTATION('',(#173249),#173253); -#173249 = LINE('',#173250,#173251); -#173250 = CARTESIAN_POINT('',(1.072393092426E-016,1.295)); -#173251 = VECTOR('',#173252,1.); -#173252 = DIRECTION('',(-1.,0.E+000)); -#173253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173254 = PCURVE('',#173255,#173260); -#173255 = PLANE('',#173256); -#173256 = AXIS2_PLACEMENT_3D('',#173257,#173258,#173259); -#173257 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); -#173258 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173259 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173260 = DEFINITIONAL_REPRESENTATION('',(#173261),#173265); -#173261 = LINE('',#173262,#173263); -#173262 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173263 = VECTOR('',#173264,1.); -#173264 = DIRECTION('',(0.965925826289,0.258819045103)); -#173265 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173266 = ORIENTED_EDGE('',*,*,#171995,.T.); -#173267 = ORIENTED_EDGE('',*,*,#173268,.T.); -#173268 = EDGE_CURVE('',#171968,#173269,#173271,.T.); -#173269 = VERTEX_POINT('',#173270); -#173270 = CARTESIAN_POINT('',(0.135,-0.759807621135,0.75)); -#173271 = SURFACE_CURVE('',#173272,(#173276,#173283),.PCURVE_S1.); -#173272 = LINE('',#173273,#173274); -#173273 = CARTESIAN_POINT('',(0.135,-0.8,0.6)); -#173274 = VECTOR('',#173275,1.); -#173275 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173276 = PCURVE('',#171904,#173277); -#173277 = DEFINITIONAL_REPRESENTATION('',(#173278),#173282); -#173278 = LINE('',#173279,#173280); -#173279 = CARTESIAN_POINT('',(1.072393092426E-016,1.605)); -#173280 = VECTOR('',#173281,1.); -#173281 = DIRECTION('',(-1.,0.E+000)); -#173282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173283 = PCURVE('',#173284,#173289); -#173284 = PLANE('',#173285); -#173285 = AXIS2_PLACEMENT_3D('',#173286,#173287,#173288); -#173286 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); -#173287 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173288 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173289 = DEFINITIONAL_REPRESENTATION('',(#173290),#173294); -#173290 = LINE('',#173291,#173292); -#173291 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173292 = VECTOR('',#173293,1.); -#173293 = DIRECTION('',(0.965925826289,0.258819045103)); -#173294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173295 = ORIENTED_EDGE('',*,*,#173296,.T.); -#173296 = EDGE_CURVE('',#173269,#173297,#173299,.T.); -#173297 = VERTEX_POINT('',#173298); -#173298 = CARTESIAN_POINT('',(0.475,-0.759807621135,0.75)); -#173299 = SURFACE_CURVE('',#173300,(#173304,#173311),.PCURVE_S1.); -#173300 = LINE('',#173301,#173302); -#173301 = CARTESIAN_POINT('',(-2.12,-0.759807621135,0.75)); -#173302 = VECTOR('',#173303,1.); -#173303 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173304 = PCURVE('',#171904,#173305); -#173305 = DEFINITIONAL_REPRESENTATION('',(#173306),#173310); -#173306 = LINE('',#173307,#173308); -#173307 = CARTESIAN_POINT('',(-0.155291427062,-0.65)); -#173308 = VECTOR('',#173309,1.); -#173309 = DIRECTION('',(0.E+000,1.)); -#173310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173311 = PCURVE('',#173312,#173317); -#173312 = PLANE('',#173313); -#173313 = AXIS2_PLACEMENT_3D('',#173314,#173315,#173316); -#173314 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); -#173315 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173316 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173317 = DEFINITIONAL_REPRESENTATION('',(#173318),#173322); -#173318 = LINE('',#173319,#173320); -#173319 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); -#173320 = VECTOR('',#173321,1.); -#173321 = DIRECTION('',(1.,0.E+000)); -#173322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173323 = ORIENTED_EDGE('',*,*,#173324,.F.); -#173324 = EDGE_CURVE('',#171945,#173297,#173325,.T.); -#173325 = SURFACE_CURVE('',#173326,(#173330,#173337),.PCURVE_S1.); -#173326 = LINE('',#173327,#173328); -#173327 = CARTESIAN_POINT('',(0.475,-0.8,0.6)); -#173328 = VECTOR('',#173329,1.); -#173329 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173330 = PCURVE('',#171904,#173331); -#173331 = DEFINITIONAL_REPRESENTATION('',(#173332),#173336); -#173332 = LINE('',#173333,#173334); -#173333 = CARTESIAN_POINT('',(1.072393092426E-016,1.945)); -#173334 = VECTOR('',#173335,1.); -#173335 = DIRECTION('',(-1.,0.E+000)); -#173336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173337 = PCURVE('',#173338,#173343); -#173338 = PLANE('',#173339); -#173339 = AXIS2_PLACEMENT_3D('',#173340,#173341,#173342); -#173340 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); -#173341 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173342 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173343 = DEFINITIONAL_REPRESENTATION('',(#173344),#173348); -#173344 = LINE('',#173345,#173346); -#173345 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173346 = VECTOR('',#173347,1.); -#173347 = DIRECTION('',(0.965925826289,0.258819045103)); -#173348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173349 = ORIENTED_EDGE('',*,*,#171944,.T.); -#173350 = ORIENTED_EDGE('',*,*,#173351,.T.); -#173351 = EDGE_CURVE('',#171917,#173352,#173354,.T.); -#173352 = VERTEX_POINT('',#173353); -#173353 = CARTESIAN_POINT('',(0.785,-0.759807621135,0.75)); -#173354 = SURFACE_CURVE('',#173355,(#173359,#173366),.PCURVE_S1.); -#173355 = LINE('',#173356,#173357); -#173356 = CARTESIAN_POINT('',(0.785,-0.8,0.6)); -#173357 = VECTOR('',#173358,1.); -#173358 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173359 = PCURVE('',#171904,#173360); -#173360 = DEFINITIONAL_REPRESENTATION('',(#173361),#173365); -#173361 = LINE('',#173362,#173363); -#173362 = CARTESIAN_POINT('',(0.E+000,2.255)); -#173363 = VECTOR('',#173364,1.); -#173364 = DIRECTION('',(-1.,0.E+000)); -#173365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173366 = PCURVE('',#173367,#173372); -#173367 = PLANE('',#173368); -#173368 = AXIS2_PLACEMENT_3D('',#173369,#173370,#173371); -#173369 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); -#173370 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173371 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173372 = DEFINITIONAL_REPRESENTATION('',(#173373),#173377); -#173373 = LINE('',#173374,#173375); -#173374 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173375 = VECTOR('',#173376,1.); -#173376 = DIRECTION('',(0.965925826289,0.258819045103)); -#173377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173378 = ORIENTED_EDGE('',*,*,#173379,.T.); -#173379 = EDGE_CURVE('',#173352,#173380,#173382,.T.); -#173380 = VERTEX_POINT('',#173381); -#173381 = CARTESIAN_POINT('',(1.125,-0.759807621135,0.75)); -#173382 = SURFACE_CURVE('',#173383,(#173387,#173394),.PCURVE_S1.); -#173383 = LINE('',#173384,#173385); -#173384 = CARTESIAN_POINT('',(-1.47,-0.759807621135,0.75)); -#173385 = VECTOR('',#173386,1.); -#173386 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173387 = PCURVE('',#171904,#173388); -#173388 = DEFINITIONAL_REPRESENTATION('',(#173389),#173393); -#173389 = LINE('',#173390,#173391); -#173390 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); -#173391 = VECTOR('',#173392,1.); -#173392 = DIRECTION('',(0.E+000,1.)); -#173393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173394 = PCURVE('',#173395,#173400); -#173395 = PLANE('',#173396); -#173396 = AXIS2_PLACEMENT_3D('',#173397,#173398,#173399); -#173397 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); -#173398 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173399 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173400 = DEFINITIONAL_REPRESENTATION('',(#173401),#173405); -#173401 = LINE('',#173402,#173403); -#173402 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); -#173403 = VECTOR('',#173404,1.); -#173404 = DIRECTION('',(1.,0.E+000)); -#173405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173406 = ORIENTED_EDGE('',*,*,#173407,.F.); -#173407 = EDGE_CURVE('',#171889,#173380,#173408,.T.); -#173408 = SURFACE_CURVE('',#173409,(#173413,#173420),.PCURVE_S1.); -#173409 = LINE('',#173410,#173411); -#173410 = CARTESIAN_POINT('',(1.125,-0.8,0.6)); -#173411 = VECTOR('',#173412,1.); -#173412 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#173413 = PCURVE('',#171904,#173414); -#173414 = DEFINITIONAL_REPRESENTATION('',(#173415),#173419); -#173415 = LINE('',#173416,#173417); -#173416 = CARTESIAN_POINT('',(0.E+000,2.595)); -#173417 = VECTOR('',#173418,1.); -#173418 = DIRECTION('',(-1.,0.E+000)); -#173419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173420 = PCURVE('',#173421,#173426); -#173421 = PLANE('',#173422); -#173422 = AXIS2_PLACEMENT_3D('',#173423,#173424,#173425); -#173423 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); -#173424 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173425 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173426 = DEFINITIONAL_REPRESENTATION('',(#173427),#173431); -#173427 = LINE('',#173428,#173429); -#173428 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); -#173429 = VECTOR('',#173430,1.); -#173430 = DIRECTION('',(0.965925826289,0.258819045103)); -#173431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173432 = ORIENTED_EDGE('',*,*,#171888,.T.); -#173433 = ORIENTED_EDGE('',*,*,#173434,.T.); -#173434 = EDGE_CURVE('',#171844,#170054,#173435,.T.); -#173435 = SURFACE_CURVE('',#173436,(#173440,#173447),.PCURVE_S1.); -#173436 = LINE('',#173437,#173438); -#173437 = CARTESIAN_POINT('',(1.149629241148,-0.624518115091, +#175462 = CARTESIAN_POINT('',(0.E+000,-0.63830681082)); +#175463 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.629185552519)); +#175464 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.610943035917)); +#175465 = CARTESIAN_POINT('',(0.E+000,-0.583579261015)); +#175466 = CARTESIAN_POINT('',(0.E+000,-0.556215486113)); +#175467 = CARTESIAN_POINT('',(0.E+000,-0.528851711211)); +#175468 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.501487936308)); +#175469 = CARTESIAN_POINT('',(1.7763568394E-015,-0.474124161406)); +#175470 = CARTESIAN_POINT('',(-3.552713678801E-015,-0.446760386504)); +#175471 = CARTESIAN_POINT('',(2.6645352591E-015,-0.419396611602)); +#175472 = CARTESIAN_POINT('',(0.E+000,-0.3920328367)); +#175473 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.364669061797)); +#175474 = CARTESIAN_POINT('',(8.881784197001E-016,-0.337305286895)); +#175475 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.309941511993)); +#175476 = CARTESIAN_POINT('',(0.E+000,-0.282577737091)); +#175477 = CARTESIAN_POINT('',(0.E+000,-0.255213962188)); +#175478 = CARTESIAN_POINT('',(0.E+000,-0.227850187286)); +#175479 = CARTESIAN_POINT('',(0.E+000,-0.200486412384)); +#175480 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.173122637482)); +#175481 = CARTESIAN_POINT('',(8.881784197001E-016,-0.14575886258)); +#175482 = CARTESIAN_POINT('',(1.7763568394E-015,-0.118395087677)); +#175483 = CARTESIAN_POINT('',(-8.881784197001E-016,-9.103131277518E-002) + ); +#175484 = CARTESIAN_POINT('',(-1.7763568394E-015,-6.366753787296E-002)); +#175485 = CARTESIAN_POINT('',(-8.881784197001E-016,-4.542502127148E-002) + ); +#175486 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#175487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175488 = ORIENTED_EDGE('',*,*,#174653,.T.); +#175489 = ADVANCED_FACE('',(#175490),#174296,.T.); +#175490 = FACE_BOUND('',#175491,.T.); +#175491 = EDGE_LOOP('',(#175492,#175493,#175521,#175549,#175575,#175576, + #175604,#175632,#175658,#175659,#175687,#175715,#175741,#175742, + #175770,#175798,#175824,#175825,#175868,#175890)); +#175492 = ORIENTED_EDGE('',*,*,#174489,.T.); +#175493 = ORIENTED_EDGE('',*,*,#175494,.T.); +#175494 = EDGE_CURVE('',#174462,#175495,#175497,.T.); +#175495 = VERTEX_POINT('',#175496); +#175496 = CARTESIAN_POINT('',(-1.165,-0.759807621135,0.75)); +#175497 = SURFACE_CURVE('',#175498,(#175502,#175509),.PCURVE_S1.); +#175498 = LINE('',#175499,#175500); +#175499 = CARTESIAN_POINT('',(-1.165,-0.8,0.6)); +#175500 = VECTOR('',#175501,1.); +#175501 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175502 = PCURVE('',#174296,#175503); +#175503 = DEFINITIONAL_REPRESENTATION('',(#175504),#175508); +#175504 = LINE('',#175505,#175506); +#175505 = CARTESIAN_POINT('',(2.144786184852E-016,0.305)); +#175506 = VECTOR('',#175507,1.); +#175507 = DIRECTION('',(-1.,0.E+000)); +#175508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175509 = PCURVE('',#175510,#175515); +#175510 = PLANE('',#175511); +#175511 = AXIS2_PLACEMENT_3D('',#175512,#175513,#175514); +#175512 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); +#175513 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175514 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175515 = DEFINITIONAL_REPRESENTATION('',(#175516),#175520); +#175516 = LINE('',#175517,#175518); +#175517 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175518 = VECTOR('',#175519,1.); +#175519 = DIRECTION('',(0.965925826289,0.258819045103)); +#175520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175521 = ORIENTED_EDGE('',*,*,#175522,.T.); +#175522 = EDGE_CURVE('',#175495,#175523,#175525,.T.); +#175523 = VERTEX_POINT('',#175524); +#175524 = CARTESIAN_POINT('',(-0.825,-0.759807621135,0.75)); +#175525 = SURFACE_CURVE('',#175526,(#175530,#175537),.PCURVE_S1.); +#175526 = LINE('',#175527,#175528); +#175527 = CARTESIAN_POINT('',(-3.42,-0.759807621135,0.75)); +#175528 = VECTOR('',#175529,1.); +#175529 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175530 = PCURVE('',#174296,#175531); +#175531 = DEFINITIONAL_REPRESENTATION('',(#175532),#175536); +#175532 = LINE('',#175533,#175534); +#175533 = CARTESIAN_POINT('',(-0.155291427062,-1.95)); +#175534 = VECTOR('',#175535,1.); +#175535 = DIRECTION('',(0.E+000,1.)); +#175536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175537 = PCURVE('',#175538,#175543); +#175538 = PLANE('',#175539); +#175539 = AXIS2_PLACEMENT_3D('',#175540,#175541,#175542); +#175540 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); +#175541 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175542 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175543 = DEFINITIONAL_REPRESENTATION('',(#175544),#175548); +#175544 = LINE('',#175545,#175546); +#175545 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); +#175546 = VECTOR('',#175547,1.); +#175547 = DIRECTION('',(1.,0.E+000)); +#175548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175549 = ORIENTED_EDGE('',*,*,#175550,.F.); +#175550 = EDGE_CURVE('',#174439,#175523,#175551,.T.); +#175551 = SURFACE_CURVE('',#175552,(#175556,#175563),.PCURVE_S1.); +#175552 = LINE('',#175553,#175554); +#175553 = CARTESIAN_POINT('',(-0.825,-0.8,0.6)); +#175554 = VECTOR('',#175555,1.); +#175555 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175556 = PCURVE('',#174296,#175557); +#175557 = DEFINITIONAL_REPRESENTATION('',(#175558),#175562); +#175558 = LINE('',#175559,#175560); +#175559 = CARTESIAN_POINT('',(2.144786184852E-016,0.645)); +#175560 = VECTOR('',#175561,1.); +#175561 = DIRECTION('',(-1.,0.E+000)); +#175562 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175563 = PCURVE('',#175564,#175569); +#175564 = PLANE('',#175565); +#175565 = AXIS2_PLACEMENT_3D('',#175566,#175567,#175568); +#175566 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); +#175567 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175568 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175569 = DEFINITIONAL_REPRESENTATION('',(#175570),#175574); +#175570 = LINE('',#175571,#175572); +#175571 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175572 = VECTOR('',#175573,1.); +#175573 = DIRECTION('',(0.965925826289,0.258819045103)); +#175574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175575 = ORIENTED_EDGE('',*,*,#174438,.T.); +#175576 = ORIENTED_EDGE('',*,*,#175577,.T.); +#175577 = EDGE_CURVE('',#174411,#175578,#175580,.T.); +#175578 = VERTEX_POINT('',#175579); +#175579 = CARTESIAN_POINT('',(-0.515,-0.759807621135,0.75)); +#175580 = SURFACE_CURVE('',#175581,(#175585,#175592),.PCURVE_S1.); +#175581 = LINE('',#175582,#175583); +#175582 = CARTESIAN_POINT('',(-0.515,-0.8,0.6)); +#175583 = VECTOR('',#175584,1.); +#175584 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175585 = PCURVE('',#174296,#175586); +#175586 = DEFINITIONAL_REPRESENTATION('',(#175587),#175591); +#175587 = LINE('',#175588,#175589); +#175588 = CARTESIAN_POINT('',(1.072393092426E-016,0.955)); +#175589 = VECTOR('',#175590,1.); +#175590 = DIRECTION('',(-1.,0.E+000)); +#175591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175592 = PCURVE('',#175593,#175598); +#175593 = PLANE('',#175594); +#175594 = AXIS2_PLACEMENT_3D('',#175595,#175596,#175597); +#175595 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); +#175596 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175597 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175598 = DEFINITIONAL_REPRESENTATION('',(#175599),#175603); +#175599 = LINE('',#175600,#175601); +#175600 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175601 = VECTOR('',#175602,1.); +#175602 = DIRECTION('',(0.965925826289,0.258819045103)); +#175603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175604 = ORIENTED_EDGE('',*,*,#175605,.T.); +#175605 = EDGE_CURVE('',#175578,#175606,#175608,.T.); +#175606 = VERTEX_POINT('',#175607); +#175607 = CARTESIAN_POINT('',(-0.175,-0.759807621135,0.75)); +#175608 = SURFACE_CURVE('',#175609,(#175613,#175620),.PCURVE_S1.); +#175609 = LINE('',#175610,#175611); +#175610 = CARTESIAN_POINT('',(-2.77,-0.759807621135,0.75)); +#175611 = VECTOR('',#175612,1.); +#175612 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175613 = PCURVE('',#174296,#175614); +#175614 = DEFINITIONAL_REPRESENTATION('',(#175615),#175619); +#175615 = LINE('',#175616,#175617); +#175616 = CARTESIAN_POINT('',(-0.155291427062,-1.3)); +#175617 = VECTOR('',#175618,1.); +#175618 = DIRECTION('',(0.E+000,1.)); +#175619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175620 = PCURVE('',#175621,#175626); +#175621 = PLANE('',#175622); +#175622 = AXIS2_PLACEMENT_3D('',#175623,#175624,#175625); +#175623 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); +#175624 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175625 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175626 = DEFINITIONAL_REPRESENTATION('',(#175627),#175631); +#175627 = LINE('',#175628,#175629); +#175628 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); +#175629 = VECTOR('',#175630,1.); +#175630 = DIRECTION('',(1.,0.E+000)); +#175631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175632 = ORIENTED_EDGE('',*,*,#175633,.F.); +#175633 = EDGE_CURVE('',#174388,#175606,#175634,.T.); +#175634 = SURFACE_CURVE('',#175635,(#175639,#175646),.PCURVE_S1.); +#175635 = LINE('',#175636,#175637); +#175636 = CARTESIAN_POINT('',(-0.175,-0.8,0.6)); +#175637 = VECTOR('',#175638,1.); +#175638 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175639 = PCURVE('',#174296,#175640); +#175640 = DEFINITIONAL_REPRESENTATION('',(#175641),#175645); +#175641 = LINE('',#175642,#175643); +#175642 = CARTESIAN_POINT('',(1.072393092426E-016,1.295)); +#175643 = VECTOR('',#175644,1.); +#175644 = DIRECTION('',(-1.,0.E+000)); +#175645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175646 = PCURVE('',#175647,#175652); +#175647 = PLANE('',#175648); +#175648 = AXIS2_PLACEMENT_3D('',#175649,#175650,#175651); +#175649 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); +#175650 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175651 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175652 = DEFINITIONAL_REPRESENTATION('',(#175653),#175657); +#175653 = LINE('',#175654,#175655); +#175654 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175655 = VECTOR('',#175656,1.); +#175656 = DIRECTION('',(0.965925826289,0.258819045103)); +#175657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175658 = ORIENTED_EDGE('',*,*,#174387,.T.); +#175659 = ORIENTED_EDGE('',*,*,#175660,.T.); +#175660 = EDGE_CURVE('',#174360,#175661,#175663,.T.); +#175661 = VERTEX_POINT('',#175662); +#175662 = CARTESIAN_POINT('',(0.135,-0.759807621135,0.75)); +#175663 = SURFACE_CURVE('',#175664,(#175668,#175675),.PCURVE_S1.); +#175664 = LINE('',#175665,#175666); +#175665 = CARTESIAN_POINT('',(0.135,-0.8,0.6)); +#175666 = VECTOR('',#175667,1.); +#175667 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175668 = PCURVE('',#174296,#175669); +#175669 = DEFINITIONAL_REPRESENTATION('',(#175670),#175674); +#175670 = LINE('',#175671,#175672); +#175671 = CARTESIAN_POINT('',(1.072393092426E-016,1.605)); +#175672 = VECTOR('',#175673,1.); +#175673 = DIRECTION('',(-1.,0.E+000)); +#175674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175675 = PCURVE('',#175676,#175681); +#175676 = PLANE('',#175677); +#175677 = AXIS2_PLACEMENT_3D('',#175678,#175679,#175680); +#175678 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); +#175679 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175680 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175681 = DEFINITIONAL_REPRESENTATION('',(#175682),#175686); +#175682 = LINE('',#175683,#175684); +#175683 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175684 = VECTOR('',#175685,1.); +#175685 = DIRECTION('',(0.965925826289,0.258819045103)); +#175686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175687 = ORIENTED_EDGE('',*,*,#175688,.T.); +#175688 = EDGE_CURVE('',#175661,#175689,#175691,.T.); +#175689 = VERTEX_POINT('',#175690); +#175690 = CARTESIAN_POINT('',(0.475,-0.759807621135,0.75)); +#175691 = SURFACE_CURVE('',#175692,(#175696,#175703),.PCURVE_S1.); +#175692 = LINE('',#175693,#175694); +#175693 = CARTESIAN_POINT('',(-2.12,-0.759807621135,0.75)); +#175694 = VECTOR('',#175695,1.); +#175695 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175696 = PCURVE('',#174296,#175697); +#175697 = DEFINITIONAL_REPRESENTATION('',(#175698),#175702); +#175698 = LINE('',#175699,#175700); +#175699 = CARTESIAN_POINT('',(-0.155291427062,-0.65)); +#175700 = VECTOR('',#175701,1.); +#175701 = DIRECTION('',(0.E+000,1.)); +#175702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175703 = PCURVE('',#175704,#175709); +#175704 = PLANE('',#175705); +#175705 = AXIS2_PLACEMENT_3D('',#175706,#175707,#175708); +#175706 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); +#175707 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175708 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175709 = DEFINITIONAL_REPRESENTATION('',(#175710),#175714); +#175710 = LINE('',#175711,#175712); +#175711 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); +#175712 = VECTOR('',#175713,1.); +#175713 = DIRECTION('',(1.,0.E+000)); +#175714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175715 = ORIENTED_EDGE('',*,*,#175716,.F.); +#175716 = EDGE_CURVE('',#174337,#175689,#175717,.T.); +#175717 = SURFACE_CURVE('',#175718,(#175722,#175729),.PCURVE_S1.); +#175718 = LINE('',#175719,#175720); +#175719 = CARTESIAN_POINT('',(0.475,-0.8,0.6)); +#175720 = VECTOR('',#175721,1.); +#175721 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175722 = PCURVE('',#174296,#175723); +#175723 = DEFINITIONAL_REPRESENTATION('',(#175724),#175728); +#175724 = LINE('',#175725,#175726); +#175725 = CARTESIAN_POINT('',(1.072393092426E-016,1.945)); +#175726 = VECTOR('',#175727,1.); +#175727 = DIRECTION('',(-1.,0.E+000)); +#175728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175729 = PCURVE('',#175730,#175735); +#175730 = PLANE('',#175731); +#175731 = AXIS2_PLACEMENT_3D('',#175732,#175733,#175734); +#175732 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); +#175733 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175734 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175735 = DEFINITIONAL_REPRESENTATION('',(#175736),#175740); +#175736 = LINE('',#175737,#175738); +#175737 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175738 = VECTOR('',#175739,1.); +#175739 = DIRECTION('',(0.965925826289,0.258819045103)); +#175740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175741 = ORIENTED_EDGE('',*,*,#174336,.T.); +#175742 = ORIENTED_EDGE('',*,*,#175743,.T.); +#175743 = EDGE_CURVE('',#174309,#175744,#175746,.T.); +#175744 = VERTEX_POINT('',#175745); +#175745 = CARTESIAN_POINT('',(0.785,-0.759807621135,0.75)); +#175746 = SURFACE_CURVE('',#175747,(#175751,#175758),.PCURVE_S1.); +#175747 = LINE('',#175748,#175749); +#175748 = CARTESIAN_POINT('',(0.785,-0.8,0.6)); +#175749 = VECTOR('',#175750,1.); +#175750 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175751 = PCURVE('',#174296,#175752); +#175752 = DEFINITIONAL_REPRESENTATION('',(#175753),#175757); +#175753 = LINE('',#175754,#175755); +#175754 = CARTESIAN_POINT('',(0.E+000,2.255)); +#175755 = VECTOR('',#175756,1.); +#175756 = DIRECTION('',(-1.,0.E+000)); +#175757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175758 = PCURVE('',#175759,#175764); +#175759 = PLANE('',#175760); +#175760 = AXIS2_PLACEMENT_3D('',#175761,#175762,#175763); +#175761 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); +#175762 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175763 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175764 = DEFINITIONAL_REPRESENTATION('',(#175765),#175769); +#175765 = LINE('',#175766,#175767); +#175766 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175767 = VECTOR('',#175768,1.); +#175768 = DIRECTION('',(0.965925826289,0.258819045103)); +#175769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175770 = ORIENTED_EDGE('',*,*,#175771,.T.); +#175771 = EDGE_CURVE('',#175744,#175772,#175774,.T.); +#175772 = VERTEX_POINT('',#175773); +#175773 = CARTESIAN_POINT('',(1.125,-0.759807621135,0.75)); +#175774 = SURFACE_CURVE('',#175775,(#175779,#175786),.PCURVE_S1.); +#175775 = LINE('',#175776,#175777); +#175776 = CARTESIAN_POINT('',(-1.47,-0.759807621135,0.75)); +#175777 = VECTOR('',#175778,1.); +#175778 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175779 = PCURVE('',#174296,#175780); +#175780 = DEFINITIONAL_REPRESENTATION('',(#175781),#175785); +#175781 = LINE('',#175782,#175783); +#175782 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); +#175783 = VECTOR('',#175784,1.); +#175784 = DIRECTION('',(0.E+000,1.)); +#175785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175786 = PCURVE('',#175787,#175792); +#175787 = PLANE('',#175788); +#175788 = AXIS2_PLACEMENT_3D('',#175789,#175790,#175791); +#175789 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); +#175790 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175791 = DIRECTION('',(1.,0.E+000,0.E+000)); +#175792 = DEFINITIONAL_REPRESENTATION('',(#175793),#175797); +#175793 = LINE('',#175794,#175795); +#175794 = CARTESIAN_POINT('',(-2.255,4.745734601879E-002)); +#175795 = VECTOR('',#175796,1.); +#175796 = DIRECTION('',(1.,0.E+000)); +#175797 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175798 = ORIENTED_EDGE('',*,*,#175799,.F.); +#175799 = EDGE_CURVE('',#174281,#175772,#175800,.T.); +#175800 = SURFACE_CURVE('',#175801,(#175805,#175812),.PCURVE_S1.); +#175801 = LINE('',#175802,#175803); +#175802 = CARTESIAN_POINT('',(1.125,-0.8,0.6)); +#175803 = VECTOR('',#175804,1.); +#175804 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#175805 = PCURVE('',#174296,#175806); +#175806 = DEFINITIONAL_REPRESENTATION('',(#175807),#175811); +#175807 = LINE('',#175808,#175809); +#175808 = CARTESIAN_POINT('',(0.E+000,2.595)); +#175809 = VECTOR('',#175810,1.); +#175810 = DIRECTION('',(-1.,0.E+000)); +#175811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175812 = PCURVE('',#175813,#175818); +#175813 = PLANE('',#175814); +#175814 = AXIS2_PLACEMENT_3D('',#175815,#175816,#175817); +#175815 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); +#175816 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175817 = DIRECTION('',(0.E+000,0.E+000,1.)); +#175818 = DEFINITIONAL_REPRESENTATION('',(#175819),#175823); +#175819 = LINE('',#175820,#175821); +#175820 = CARTESIAN_POINT('',(0.1,7.264967154128E-003)); +#175821 = VECTOR('',#175822,1.); +#175822 = DIRECTION('',(0.965925826289,0.258819045103)); +#175823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175824 = ORIENTED_EDGE('',*,*,#174280,.T.); +#175825 = ORIENTED_EDGE('',*,*,#175826,.T.); +#175826 = EDGE_CURVE('',#174236,#172446,#175827,.T.); +#175827 = SURFACE_CURVE('',#175828,(#175832,#175839),.PCURVE_S1.); +#175828 = LINE('',#175829,#175830); +#175829 = CARTESIAN_POINT('',(1.149629241148,-0.624518115091, 1.254907310287)); -#173438 = VECTOR('',#173439,1.); -#173439 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#173440 = PCURVE('',#171904,#173441); -#173441 = DEFINITIONAL_REPRESENTATION('',(#173442),#173446); -#173442 = LINE('',#173443,#173444); -#173443 = CARTESIAN_POINT('',(-0.678009938717,2.619629241148)); -#173444 = VECTOR('',#173445,1.); -#173445 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#173446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173447 = PCURVE('',#170109,#173448); -#173448 = DEFINITIONAL_REPRESENTATION('',(#173449),#173475); -#173449 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173450,#173451,#173452, - #173453,#173454,#173455,#173456,#173457,#173458,#173459,#173460, - #173461,#173462,#173463,#173464,#173465,#173466,#173467,#173468, - #173469,#173470,#173471,#173472,#173473,#173474),.UNSPECIFIED.,.F., +#175830 = VECTOR('',#175831,1.); +#175831 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#175832 = PCURVE('',#174296,#175833); +#175833 = DEFINITIONAL_REPRESENTATION('',(#175834),#175838); +#175834 = LINE('',#175835,#175836); +#175835 = CARTESIAN_POINT('',(-0.678009938717,2.619629241148)); +#175836 = VECTOR('',#175837,1.); +#175837 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#175838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175839 = PCURVE('',#172501,#175840); +#175840 = DEFINITIONAL_REPRESENTATION('',(#175841),#175867); +#175841 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175842,#175843,#175844, + #175845,#175846,#175847,#175848,#175849,#175850,#175851,#175852, + #175853,#175854,#175855,#175856,#175857,#175858,#175859,#175860, + #175861,#175862,#175863,#175864,#175865,#175866),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.700350889861, -0.672987114959,-0.645623340057,-0.618259565155,-0.590895790252, -0.56353201535,-0.536168240448,-0.508804465546,-0.481440690644, @@ -214619,88 +217621,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.344621816132,-0.31725804123,-0.289894266328,-0.262530491426, -0.235166716524,-0.207802941621,-0.180439166719,-0.153075391817, -0.125711616915,-9.834784201249E-002),.QUASI_UNIFORM_KNOTS.); -#173450 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); -#173451 = CARTESIAN_POINT('',(4.64535148218,0.355475470066)); -#173452 = CARTESIAN_POINT('',(4.64535148218,0.337232953464)); -#173453 = CARTESIAN_POINT('',(4.64535148218,0.309869178562)); -#173454 = CARTESIAN_POINT('',(4.64535148218,0.28250540366)); -#173455 = CARTESIAN_POINT('',(4.64535148218,0.255141628758)); -#173456 = CARTESIAN_POINT('',(4.64535148218,0.227777853855)); -#173457 = CARTESIAN_POINT('',(4.64535148218,0.200414078953)); -#173458 = CARTESIAN_POINT('',(4.64535148218,0.173050304051)); -#173459 = CARTESIAN_POINT('',(4.64535148218,0.145686529149)); -#173460 = CARTESIAN_POINT('',(4.64535148218,0.118322754246)); -#173461 = CARTESIAN_POINT('',(4.64535148218,9.095897934424E-002)); -#173462 = CARTESIAN_POINT('',(4.64535148218,6.359520444202E-002)); -#173463 = CARTESIAN_POINT('',(4.64535148218,3.62314295398E-002)); -#173464 = CARTESIAN_POINT('',(4.64535148218,8.86765463758E-003)); -#173465 = CARTESIAN_POINT('',(4.64535148218,-1.849612026464E-002)); -#173466 = CARTESIAN_POINT('',(4.64535148218,-4.585989516686E-002)); -#173467 = CARTESIAN_POINT('',(4.64535148218,-7.322367006908E-002)); -#173468 = CARTESIAN_POINT('',(4.64535148218,-0.100587444971)); -#173469 = CARTESIAN_POINT('',(4.64535148218,-0.127951219874)); -#173470 = CARTESIAN_POINT('',(4.64535148218,-0.155314994776)); -#173471 = CARTESIAN_POINT('',(4.64535148218,-0.182678769678)); -#173472 = CARTESIAN_POINT('',(4.64535148218,-0.21004254458)); -#173473 = CARTESIAN_POINT('',(4.64535148218,-0.228285061182)); -#173474 = CARTESIAN_POINT('',(4.64535148218,-0.237406319482)); -#173475 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173476 = ORIENTED_EDGE('',*,*,#173477,.T.); -#173477 = EDGE_CURVE('',#170054,#173478,#173480,.T.); -#173478 = VERTEX_POINT('',#173479); -#173479 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, +#175842 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); +#175843 = CARTESIAN_POINT('',(4.64535148218,0.355475470066)); +#175844 = CARTESIAN_POINT('',(4.64535148218,0.337232953464)); +#175845 = CARTESIAN_POINT('',(4.64535148218,0.309869178562)); +#175846 = CARTESIAN_POINT('',(4.64535148218,0.28250540366)); +#175847 = CARTESIAN_POINT('',(4.64535148218,0.255141628758)); +#175848 = CARTESIAN_POINT('',(4.64535148218,0.227777853855)); +#175849 = CARTESIAN_POINT('',(4.64535148218,0.200414078953)); +#175850 = CARTESIAN_POINT('',(4.64535148218,0.173050304051)); +#175851 = CARTESIAN_POINT('',(4.64535148218,0.145686529149)); +#175852 = CARTESIAN_POINT('',(4.64535148218,0.118322754246)); +#175853 = CARTESIAN_POINT('',(4.64535148218,9.095897934424E-002)); +#175854 = CARTESIAN_POINT('',(4.64535148218,6.359520444202E-002)); +#175855 = CARTESIAN_POINT('',(4.64535148218,3.62314295398E-002)); +#175856 = CARTESIAN_POINT('',(4.64535148218,8.86765463758E-003)); +#175857 = CARTESIAN_POINT('',(4.64535148218,-1.849612026464E-002)); +#175858 = CARTESIAN_POINT('',(4.64535148218,-4.585989516686E-002)); +#175859 = CARTESIAN_POINT('',(4.64535148218,-7.322367006908E-002)); +#175860 = CARTESIAN_POINT('',(4.64535148218,-0.100587444971)); +#175861 = CARTESIAN_POINT('',(4.64535148218,-0.127951219874)); +#175862 = CARTESIAN_POINT('',(4.64535148218,-0.155314994776)); +#175863 = CARTESIAN_POINT('',(4.64535148218,-0.182678769678)); +#175864 = CARTESIAN_POINT('',(4.64535148218,-0.21004254458)); +#175865 = CARTESIAN_POINT('',(4.64535148218,-0.228285061182)); +#175866 = CARTESIAN_POINT('',(4.64535148218,-0.237406319482)); +#175867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175868 = ORIENTED_EDGE('',*,*,#175869,.T.); +#175869 = EDGE_CURVE('',#172446,#175870,#175872,.T.); +#175870 = VERTEX_POINT('',#175871); +#175871 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, 1.162940952255)); -#173480 = SURFACE_CURVE('',#173481,(#173485,#173492),.PCURVE_S1.); -#173481 = LINE('',#173482,#173483); -#173482 = CARTESIAN_POINT('',(-1.164341610598,-0.649160426457, +#175872 = SURFACE_CURVE('',#175873,(#175877,#175884),.PCURVE_S1.); +#175873 = LINE('',#175874,#175875); +#175874 = CARTESIAN_POINT('',(-1.164341610598,-0.649160426457, 1.162940952255)); -#173483 = VECTOR('',#173484,1.); -#173484 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173485 = PCURVE('',#171904,#173486); -#173486 = DEFINITIONAL_REPRESENTATION('',(#173487),#173491); -#173487 = LINE('',#173488,#173489); -#173488 = CARTESIAN_POINT('',(-0.582799358847,0.305658389402)); -#173489 = VECTOR('',#173490,1.); -#173490 = DIRECTION('',(0.E+000,-1.)); -#173491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173492 = PCURVE('',#170312,#173493); -#173493 = DEFINITIONAL_REPRESENTATION('',(#173494),#173497); -#173494 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173495,#173496), +#175875 = VECTOR('',#175876,1.); +#175876 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#175877 = PCURVE('',#174296,#175878); +#175878 = DEFINITIONAL_REPRESENTATION('',(#175879),#175883); +#175879 = LINE('',#175880,#175881); +#175880 = CARTESIAN_POINT('',(-0.582799358847,0.305658389402)); +#175881 = VECTOR('',#175882,1.); +#175882 = DIRECTION('',(0.E+000,-1.)); +#175883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175884 = PCURVE('',#172704,#175885); +#175885 = DEFINITIONAL_REPRESENTATION('',(#175886),#175889); +#175886 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175887,#175888), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.338613163111,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#173495 = CARTESIAN_POINT('',(4.450589592586,-0.295728447487)); -#173496 = CARTESIAN_POINT('',(4.450589592586,-2.644271552513)); -#173497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#175887 = CARTESIAN_POINT('',(4.450589592586,-0.295728447487)); +#175888 = CARTESIAN_POINT('',(4.450589592586,-2.644271552513)); +#175889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#173498 = ORIENTED_EDGE('',*,*,#173499,.T.); -#173499 = EDGE_CURVE('',#173478,#171772,#173500,.T.); -#173500 = SURFACE_CURVE('',#173501,(#173505,#173512),.PCURVE_S1.); -#173501 = LINE('',#173502,#173503); -#173502 = CARTESIAN_POINT('',(-1.334207498814,-0.809096372758, +#175890 = ORIENTED_EDGE('',*,*,#175891,.T.); +#175891 = EDGE_CURVE('',#175870,#174164,#175892,.T.); +#175892 = SURFACE_CURVE('',#175893,(#175897,#175904),.PCURVE_S1.); +#175893 = LINE('',#175894,#175895); +#175894 = CARTESIAN_POINT('',(-1.334207498814,-0.809096372758, 0.566051874704)); -#173503 = VECTOR('',#173504,1.); -#173504 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#173505 = PCURVE('',#171904,#173506); -#173506 = DEFINITIONAL_REPRESENTATION('',(#173507),#173511); -#173507 = LINE('',#173508,#173509); -#173508 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#173509 = VECTOR('',#173510,1.); -#173510 = DIRECTION('',(0.968100345886,-0.250562807086)); -#173511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173512 = PCURVE('',#169829,#173513); -#173513 = DEFINITIONAL_REPRESENTATION('',(#173514),#173540); -#173514 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173515,#173516,#173517, - #173518,#173519,#173520,#173521,#173522,#173523,#173524,#173525, - #173526,#173527,#173528,#173529,#173530,#173531,#173532,#173533, - #173534,#173535,#173536,#173537,#173538,#173539),.UNSPECIFIED.,.F., +#175895 = VECTOR('',#175896,1.); +#175896 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#175897 = PCURVE('',#174296,#175898); +#175898 = DEFINITIONAL_REPRESENTATION('',(#175899),#175903); +#175899 = LINE('',#175900,#175901); +#175900 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#175901 = VECTOR('',#175902,1.); +#175902 = DIRECTION('',(0.968100345886,-0.250562807086)); +#175903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175904 = PCURVE('',#172221,#175905); +#175905 = DEFINITIONAL_REPRESENTATION('',(#175906),#175932); +#175906 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175907,#175908,#175909, + #175910,#175911,#175912,#175913,#175914,#175915,#175916,#175917, + #175918,#175919,#175920,#175921,#175922,#175923,#175924,#175925, + #175926,#175927,#175928,#175929,#175930,#175931),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.63830681082, -0.610943035917,-0.583579261015,-0.556215486113,-0.528851711211, -0.501487936308,-0.474124161406,-0.446760386504,-0.419396611602, @@ -214708,62 +217710,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.282577737091,-0.255213962188,-0.227850187286,-0.200486412384, -0.173122637482,-0.14575886258,-0.118395087677,-9.103131277518E-002, -6.366753787296E-002,-3.630376297074E-002),.QUASI_UNIFORM_KNOTS.); -#173515 = CARTESIAN_POINT('',(4.77942647859,-0.63830681082)); -#173516 = CARTESIAN_POINT('',(4.77942647859,-0.629185552519)); -#173517 = CARTESIAN_POINT('',(4.77942647859,-0.610943035917)); -#173518 = CARTESIAN_POINT('',(4.77942647859,-0.583579261015)); -#173519 = CARTESIAN_POINT('',(4.77942647859,-0.556215486113)); -#173520 = CARTESIAN_POINT('',(4.77942647859,-0.528851711211)); -#173521 = CARTESIAN_POINT('',(4.77942647859,-0.501487936308)); -#173522 = CARTESIAN_POINT('',(4.77942647859,-0.474124161406)); -#173523 = CARTESIAN_POINT('',(4.77942647859,-0.446760386504)); -#173524 = CARTESIAN_POINT('',(4.77942647859,-0.419396611602)); -#173525 = CARTESIAN_POINT('',(4.77942647859,-0.3920328367)); -#173526 = CARTESIAN_POINT('',(4.77942647859,-0.364669061797)); -#173527 = CARTESIAN_POINT('',(4.77942647859,-0.337305286895)); -#173528 = CARTESIAN_POINT('',(4.77942647859,-0.309941511993)); -#173529 = CARTESIAN_POINT('',(4.77942647859,-0.282577737091)); -#173530 = CARTESIAN_POINT('',(4.77942647859,-0.255213962188)); -#173531 = CARTESIAN_POINT('',(4.77942647859,-0.227850187286)); -#173532 = CARTESIAN_POINT('',(4.77942647859,-0.200486412384)); -#173533 = CARTESIAN_POINT('',(4.77942647859,-0.173122637482)); -#173534 = CARTESIAN_POINT('',(4.77942647859,-0.14575886258)); -#173535 = CARTESIAN_POINT('',(4.77942647859,-0.118395087677)); -#173536 = CARTESIAN_POINT('',(4.77942647859,-9.103131277518E-002)); -#173537 = CARTESIAN_POINT('',(4.77942647859,-6.366753787296E-002)); -#173538 = CARTESIAN_POINT('',(4.77942647859,-4.542502127148E-002)); -#173539 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#173540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#175907 = CARTESIAN_POINT('',(4.77942647859,-0.63830681082)); +#175908 = CARTESIAN_POINT('',(4.77942647859,-0.629185552519)); +#175909 = CARTESIAN_POINT('',(4.77942647859,-0.610943035917)); +#175910 = CARTESIAN_POINT('',(4.77942647859,-0.583579261015)); +#175911 = CARTESIAN_POINT('',(4.77942647859,-0.556215486113)); +#175912 = CARTESIAN_POINT('',(4.77942647859,-0.528851711211)); +#175913 = CARTESIAN_POINT('',(4.77942647859,-0.501487936308)); +#175914 = CARTESIAN_POINT('',(4.77942647859,-0.474124161406)); +#175915 = CARTESIAN_POINT('',(4.77942647859,-0.446760386504)); +#175916 = CARTESIAN_POINT('',(4.77942647859,-0.419396611602)); +#175917 = CARTESIAN_POINT('',(4.77942647859,-0.3920328367)); +#175918 = CARTESIAN_POINT('',(4.77942647859,-0.364669061797)); +#175919 = CARTESIAN_POINT('',(4.77942647859,-0.337305286895)); +#175920 = CARTESIAN_POINT('',(4.77942647859,-0.309941511993)); +#175921 = CARTESIAN_POINT('',(4.77942647859,-0.282577737091)); +#175922 = CARTESIAN_POINT('',(4.77942647859,-0.255213962188)); +#175923 = CARTESIAN_POINT('',(4.77942647859,-0.227850187286)); +#175924 = CARTESIAN_POINT('',(4.77942647859,-0.200486412384)); +#175925 = CARTESIAN_POINT('',(4.77942647859,-0.173122637482)); +#175926 = CARTESIAN_POINT('',(4.77942647859,-0.14575886258)); +#175927 = CARTESIAN_POINT('',(4.77942647859,-0.118395087677)); +#175928 = CARTESIAN_POINT('',(4.77942647859,-9.103131277518E-002)); +#175929 = CARTESIAN_POINT('',(4.77942647859,-6.366753787296E-002)); +#175930 = CARTESIAN_POINT('',(4.77942647859,-4.542502127148E-002)); +#175931 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#175932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#173541 = ADVANCED_FACE('',(#173542,#173862),#169987,.T.); -#173542 = FACE_BOUND('',#173543,.T.); -#173543 = EDGE_LOOP('',(#173544,#173589,#173590,#173637,#173657,#173658, - #173705,#173748,#173749,#173796,#173816,#173817)); -#173544 = ORIENTED_EDGE('',*,*,#173545,.T.); -#173545 = EDGE_CURVE('',#173546,#169949,#173548,.T.); -#173546 = VERTEX_POINT('',#173547); -#173547 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); -#173548 = SURFACE_CURVE('',#173549,(#173553,#173560),.PCURVE_S1.); -#173549 = LINE('',#173550,#173551); -#173550 = CARTESIAN_POINT('',(-1.270864135142,-0.494341610598,1.2)); -#173551 = VECTOR('',#173552,1.); -#173552 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); -#173553 = PCURVE('',#169987,#173554); -#173554 = DEFINITIONAL_REPRESENTATION('',(#173555),#173559); -#173555 = LINE('',#173556,#173557); -#173556 = CARTESIAN_POINT('',(-2.740864135142,0.305658389402)); -#173557 = VECTOR('',#173558,1.); -#173558 = DIRECTION('',(1.355252715607E-016,-1.)); -#173559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173560 = PCURVE('',#170037,#173561); -#173561 = DEFINITIONAL_REPRESENTATION('',(#173562),#173588); -#173562 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173563,#173564,#173565, - #173566,#173567,#173568,#173569,#173570,#173571,#173572,#173573, - #173574,#173575,#173576,#173577,#173578,#173579,#173580,#173581, - #173582,#173583,#173584,#173585,#173586,#173587),.UNSPECIFIED.,.F., +#175933 = ADVANCED_FACE('',(#175934,#176254),#172379,.T.); +#175934 = FACE_BOUND('',#175935,.T.); +#175935 = EDGE_LOOP('',(#175936,#175981,#175982,#176029,#176049,#176050, + #176097,#176140,#176141,#176188,#176208,#176209)); +#175936 = ORIENTED_EDGE('',*,*,#175937,.T.); +#175937 = EDGE_CURVE('',#175938,#172341,#175940,.T.); +#175938 = VERTEX_POINT('',#175939); +#175939 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); +#175940 = SURFACE_CURVE('',#175941,(#175945,#175952),.PCURVE_S1.); +#175941 = LINE('',#175942,#175943); +#175942 = CARTESIAN_POINT('',(-1.270864135142,-0.494341610598,1.2)); +#175943 = VECTOR('',#175944,1.); +#175944 = DIRECTION('',(1.355252715607E-016,-1.,0.E+000)); +#175945 = PCURVE('',#172379,#175946); +#175946 = DEFINITIONAL_REPRESENTATION('',(#175947),#175951); +#175947 = LINE('',#175948,#175949); +#175948 = CARTESIAN_POINT('',(-2.740864135142,0.305658389402)); +#175949 = VECTOR('',#175950,1.); +#175950 = DIRECTION('',(1.355252715607E-016,-1.)); +#175951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175952 = PCURVE('',#172429,#175953); +#175953 = DEFINITIONAL_REPRESENTATION('',(#175954),#175980); +#175954 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175955,#175956,#175957, + #175958,#175959,#175960,#175961,#175962,#175963,#175964,#175965, + #175966,#175967,#175968,#175969,#175970,#175971,#175972,#175973, + #175974,#175975,#175976,#175977,#175978,#175979),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.998613163111, -0.952770294701,-0.906927426291,-0.86108455788,-0.81524168947, -0.76939882106,-0.72355595265,-0.677713084239,-0.631870215829, @@ -214771,69 +217773,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.402655873777,-0.356813005367,-0.310970136957,-0.265127268546, -0.219284400136,-0.173441531726,-0.127598663315,-8.175579490513E-002 ,-3.591292649481E-002,9.929941915506E-003),.UNSPECIFIED.); -#173563 = CARTESIAN_POINT('',(1.570796326795,-1.304271552513)); -#173564 = CARTESIAN_POINT('',(1.570796326795,-1.288990596377)); -#173565 = CARTESIAN_POINT('',(1.570796326795,-1.258428684103)); -#173566 = CARTESIAN_POINT('',(1.570796326795,-1.212585815693)); -#173567 = CARTESIAN_POINT('',(1.570796326795,-1.166742947283)); -#173568 = CARTESIAN_POINT('',(1.570796326795,-1.120900078872)); -#173569 = CARTESIAN_POINT('',(1.570796326795,-1.075057210462)); -#173570 = CARTESIAN_POINT('',(1.570796326795,-1.029214342052)); -#173571 = CARTESIAN_POINT('',(1.570796326795,-0.983371473641)); -#173572 = CARTESIAN_POINT('',(1.570796326795,-0.937528605231)); -#173573 = CARTESIAN_POINT('',(1.570796326795,-0.891685736821)); -#173574 = CARTESIAN_POINT('',(1.570796326795,-0.84584286841)); -#173575 = CARTESIAN_POINT('',(1.570796326795,-0.8)); -#173576 = CARTESIAN_POINT('',(1.570796326795,-0.75415713159)); -#173577 = CARTESIAN_POINT('',(1.570796326795,-0.708314263179)); -#173578 = CARTESIAN_POINT('',(1.570796326795,-0.662471394769)); -#173579 = CARTESIAN_POINT('',(1.570796326795,-0.616628526359)); -#173580 = CARTESIAN_POINT('',(1.570796326795,-0.570785657948)); -#173581 = CARTESIAN_POINT('',(1.570796326795,-0.524942789538)); -#173582 = CARTESIAN_POINT('',(1.570796326795,-0.479099921128)); -#173583 = CARTESIAN_POINT('',(1.570796326795,-0.433257052717)); -#173584 = CARTESIAN_POINT('',(1.570796326795,-0.387414184307)); -#173585 = CARTESIAN_POINT('',(1.570796326795,-0.341571315897)); -#173586 = CARTESIAN_POINT('',(1.570796326795,-0.311009403623)); -#173587 = CARTESIAN_POINT('',(1.570796326795,-0.295728447487)); -#173588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173589 = ORIENTED_EDGE('',*,*,#169948,.T.); -#173590 = ORIENTED_EDGE('',*,*,#173591,.T.); -#173591 = EDGE_CURVE('',#169864,#173592,#173594,.T.); -#173592 = VERTEX_POINT('',#173593); -#173593 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); -#173594 = SURFACE_CURVE('',#173595,(#173600,#173608),.PCURVE_S1.); -#173595 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173596,#173597,#173598, -#173599),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175955 = CARTESIAN_POINT('',(1.570796326795,-1.304271552513)); +#175956 = CARTESIAN_POINT('',(1.570796326795,-1.288990596377)); +#175957 = CARTESIAN_POINT('',(1.570796326795,-1.258428684103)); +#175958 = CARTESIAN_POINT('',(1.570796326795,-1.212585815693)); +#175959 = CARTESIAN_POINT('',(1.570796326795,-1.166742947283)); +#175960 = CARTESIAN_POINT('',(1.570796326795,-1.120900078872)); +#175961 = CARTESIAN_POINT('',(1.570796326795,-1.075057210462)); +#175962 = CARTESIAN_POINT('',(1.570796326795,-1.029214342052)); +#175963 = CARTESIAN_POINT('',(1.570796326795,-0.983371473641)); +#175964 = CARTESIAN_POINT('',(1.570796326795,-0.937528605231)); +#175965 = CARTESIAN_POINT('',(1.570796326795,-0.891685736821)); +#175966 = CARTESIAN_POINT('',(1.570796326795,-0.84584286841)); +#175967 = CARTESIAN_POINT('',(1.570796326795,-0.8)); +#175968 = CARTESIAN_POINT('',(1.570796326795,-0.75415713159)); +#175969 = CARTESIAN_POINT('',(1.570796326795,-0.708314263179)); +#175970 = CARTESIAN_POINT('',(1.570796326795,-0.662471394769)); +#175971 = CARTESIAN_POINT('',(1.570796326795,-0.616628526359)); +#175972 = CARTESIAN_POINT('',(1.570796326795,-0.570785657948)); +#175973 = CARTESIAN_POINT('',(1.570796326795,-0.524942789538)); +#175974 = CARTESIAN_POINT('',(1.570796326795,-0.479099921128)); +#175975 = CARTESIAN_POINT('',(1.570796326795,-0.433257052717)); +#175976 = CARTESIAN_POINT('',(1.570796326795,-0.387414184307)); +#175977 = CARTESIAN_POINT('',(1.570796326795,-0.341571315897)); +#175978 = CARTESIAN_POINT('',(1.570796326795,-0.311009403623)); +#175979 = CARTESIAN_POINT('',(1.570796326795,-0.295728447487)); +#175980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#175981 = ORIENTED_EDGE('',*,*,#172340,.T.); +#175982 = ORIENTED_EDGE('',*,*,#175983,.T.); +#175983 = EDGE_CURVE('',#172256,#175984,#175986,.T.); +#175984 = VERTEX_POINT('',#175985); +#175985 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); +#175986 = SURFACE_CURVE('',#175987,(#175992,#176000),.PCURVE_S1.); +#175987 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175988,#175989,#175990, +#175991),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 7.453889935838E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173596 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); -#173597 = CARTESIAN_POINT('',(-1.224801147872,-0.591106375747,1.2)); -#173598 = CARTESIAN_POINT('',(-1.200789126784,-0.600864135142,1.2)); -#173599 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); -#173600 = PCURVE('',#169987,#173601); -#173601 = DEFINITIONAL_REPRESENTATION('',(#173602),#173607); -#173602 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173603,#173604,#173605, -#173606),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#175988 = CARTESIAN_POINT('',(-1.242953761809,-0.572953761809,1.2)); +#175989 = CARTESIAN_POINT('',(-1.224801147872,-0.591106375747,1.2)); +#175990 = CARTESIAN_POINT('',(-1.200789126784,-0.600864135142,1.2)); +#175991 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.2)); +#175992 = PCURVE('',#172379,#175993); +#175993 = DEFINITIONAL_REPRESENTATION('',(#175994),#175999); +#175994 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175995,#175996,#175997, +#175998),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 7.453889935838E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173603 = CARTESIAN_POINT('',(-2.712953761809,0.227046238191)); -#173604 = CARTESIAN_POINT('',(-2.694801147872,0.208893624253)); -#173605 = CARTESIAN_POINT('',(-2.670789126784,0.199135864858)); -#173606 = CARTESIAN_POINT('',(-2.644271552513,0.199135864858)); -#173607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173608 = PCURVE('',#169902,#173609); -#173609 = DEFINITIONAL_REPRESENTATION('',(#173610),#173636); -#173610 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173611,#173612,#173613, - #173614,#173615,#173616,#173617,#173618,#173619,#173620,#173621, - #173622,#173623,#173624,#173625,#173626,#173627,#173628,#173629, - #173630,#173631,#173632,#173633,#173634,#173635),.UNSPECIFIED.,.F., +#175995 = CARTESIAN_POINT('',(-2.712953761809,0.227046238191)); +#175996 = CARTESIAN_POINT('',(-2.694801147872,0.208893624253)); +#175997 = CARTESIAN_POINT('',(-2.670789126784,0.199135864858)); +#175998 = CARTESIAN_POINT('',(-2.644271552513,0.199135864858)); +#175999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176000 = PCURVE('',#172294,#176001); +#176001 = DEFINITIONAL_REPRESENTATION('',(#176002),#176028); +#176002 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176003,#176004,#176005, + #176006,#176007,#176008,#176009,#176010,#176011,#176012,#176013, + #176014,#176015,#176016,#176017,#176018,#176019,#176020,#176021, + #176022,#176023,#176024,#176025,#176026,#176027),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 7.453889935838E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -214842,95 +217844,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#173611 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#173612 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#173613 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#173614 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#173615 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#173616 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#173617 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#173618 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#173619 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#173620 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#173621 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#173622 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#173623 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#173624 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#173625 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#173626 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#173627 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#173628 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#173629 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#173630 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#173631 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#173632 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#173633 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#173634 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#173635 = CARTESIAN_POINT('',(0.751879414295,1.)); -#173636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173637 = ORIENTED_EDGE('',*,*,#173638,.T.); -#173638 = EDGE_CURVE('',#173592,#170229,#173639,.T.); -#173639 = SURFACE_CURVE('',#173640,(#173644,#173651),.PCURVE_S1.); -#173640 = LINE('',#173641,#173642); -#173641 = CARTESIAN_POINT('',(1.164341610598,-0.600864135142,1.2)); -#173642 = VECTOR('',#173643,1.); -#173643 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173644 = PCURVE('',#169987,#173645); -#173645 = DEFINITIONAL_REPRESENTATION('',(#173646),#173650); -#173646 = LINE('',#173647,#173648); -#173647 = CARTESIAN_POINT('',(-0.305658389402,0.199135864858)); -#173648 = VECTOR('',#173649,1.); -#173649 = DIRECTION('',(1.,0.E+000)); -#173650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173651 = PCURVE('',#170312,#173652); -#173652 = DEFINITIONAL_REPRESENTATION('',(#173653),#173656); -#173653 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173654,#173655), +#176003 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#176004 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#176005 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#176006 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#176007 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#176008 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#176009 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#176010 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#176011 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#176012 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#176013 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#176014 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#176015 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#176016 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#176017 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#176018 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#176019 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#176020 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#176021 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#176022 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#176023 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#176024 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#176025 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#176026 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#176027 = CARTESIAN_POINT('',(0.751879414295,1.)); +#176028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176029 = ORIENTED_EDGE('',*,*,#176030,.T.); +#176030 = EDGE_CURVE('',#175984,#172621,#176031,.T.); +#176031 = SURFACE_CURVE('',#176032,(#176036,#176043),.PCURVE_S1.); +#176032 = LINE('',#176033,#176034); +#176033 = CARTESIAN_POINT('',(1.164341610598,-0.600864135142,1.2)); +#176034 = VECTOR('',#176035,1.); +#176035 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176036 = PCURVE('',#172379,#176037); +#176037 = DEFINITIONAL_REPRESENTATION('',(#176038),#176042); +#176038 = LINE('',#176039,#176040); +#176039 = CARTESIAN_POINT('',(-0.305658389402,0.199135864858)); +#176040 = VECTOR('',#176041,1.); +#176041 = DIRECTION('',(1.,0.E+000)); +#176042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176043 = PCURVE('',#172704,#176044); +#176044 = DEFINITIONAL_REPRESENTATION('',(#176045),#176048); +#176045 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176046,#176047), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.338613163111,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#173654 = CARTESIAN_POINT('',(3.14159265359,-2.644271552513)); -#173655 = CARTESIAN_POINT('',(3.14159265359,-0.295728447487)); -#173656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#176046 = CARTESIAN_POINT('',(3.14159265359,-2.644271552513)); +#176047 = CARTESIAN_POINT('',(3.14159265359,-0.295728447487)); +#176048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#173657 = ORIENTED_EDGE('',*,*,#170228,.T.); -#173658 = ORIENTED_EDGE('',*,*,#173659,.T.); -#173659 = EDGE_CURVE('',#170144,#173660,#173662,.T.); -#173660 = VERTEX_POINT('',#173661); -#173661 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); -#173662 = SURFACE_CURVE('',#173663,(#173668,#173676),.PCURVE_S1.); -#173663 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173664,#173665,#173666, -#173667),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#176049 = ORIENTED_EDGE('',*,*,#172620,.T.); +#176050 = ORIENTED_EDGE('',*,*,#176051,.T.); +#176051 = EDGE_CURVE('',#172536,#176052,#176054,.T.); +#176052 = VERTEX_POINT('',#176053); +#176053 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); +#176054 = SURFACE_CURVE('',#176055,(#176060,#176068),.PCURVE_S1.); +#176055 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176056,#176057,#176058, +#176059),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173664 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); -#173665 = CARTESIAN_POINT('',(1.261106375747,-0.554801147872,1.2)); -#173666 = CARTESIAN_POINT('',(1.270864135142,-0.530789126784,1.2)); -#173667 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); -#173668 = PCURVE('',#169987,#173669); -#173669 = DEFINITIONAL_REPRESENTATION('',(#173670),#173675); -#173670 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173671,#173672,#173673, -#173674),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#176056 = CARTESIAN_POINT('',(1.242953761809,-0.572953761809,1.2)); +#176057 = CARTESIAN_POINT('',(1.261106375747,-0.554801147872,1.2)); +#176058 = CARTESIAN_POINT('',(1.270864135142,-0.530789126784,1.2)); +#176059 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.2)); +#176060 = PCURVE('',#172379,#176061); +#176061 = DEFINITIONAL_REPRESENTATION('',(#176062),#176067); +#176062 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176063,#176064,#176065, +#176066),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173671 = CARTESIAN_POINT('',(-0.227046238191,0.227046238191)); -#173672 = CARTESIAN_POINT('',(-0.208893624253,0.245198852128)); -#173673 = CARTESIAN_POINT('',(-0.199135864858,0.269210873216)); -#173674 = CARTESIAN_POINT('',(-0.199135864858,0.295728447487)); -#173675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173676 = PCURVE('',#170182,#173677); -#173677 = DEFINITIONAL_REPRESENTATION('',(#173678),#173704); -#173678 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173679,#173680,#173681, - #173682,#173683,#173684,#173685,#173686,#173687,#173688,#173689, - #173690,#173691,#173692,#173693,#173694,#173695,#173696,#173697, - #173698,#173699,#173700,#173701,#173702,#173703),.UNSPECIFIED.,.F., +#176063 = CARTESIAN_POINT('',(-0.227046238191,0.227046238191)); +#176064 = CARTESIAN_POINT('',(-0.208893624253,0.245198852128)); +#176065 = CARTESIAN_POINT('',(-0.199135864858,0.269210873216)); +#176066 = CARTESIAN_POINT('',(-0.199135864858,0.295728447487)); +#176067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176068 = PCURVE('',#172574,#176069); +#176069 = DEFINITIONAL_REPRESENTATION('',(#176070),#176096); +#176070 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176071,#176072,#176073, + #176074,#176075,#176076,#176077,#176078,#176079,#176080,#176081, + #176082,#176083,#176084,#176085,#176086,#176087,#176088,#176089, + #176090,#176091,#176092,#176093,#176094,#176095),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -214938,56 +217940,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#173679 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#173680 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#173681 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); -#173682 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#173683 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#173684 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#173685 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#173686 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#173687 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#173688 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#173689 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#173690 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#173691 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#173692 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#173693 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#173694 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#173695 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#173696 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#173697 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#173698 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#173699 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#173700 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#173701 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#173702 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#173703 = CARTESIAN_POINT('',(0.751879414295,1.)); -#173704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173705 = ORIENTED_EDGE('',*,*,#173706,.T.); -#173706 = EDGE_CURVE('',#173660,#170779,#173707,.T.); -#173707 = SURFACE_CURVE('',#173708,(#173712,#173719),.PCURVE_S1.); -#173708 = LINE('',#173709,#173710); -#173709 = CARTESIAN_POINT('',(1.270864135142,0.494341610598,1.2)); -#173710 = VECTOR('',#173711,1.); -#173711 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); -#173712 = PCURVE('',#169987,#173713); -#173713 = DEFINITIONAL_REPRESENTATION('',(#173714),#173718); -#173714 = LINE('',#173715,#173716); -#173715 = CARTESIAN_POINT('',(-0.199135864858,1.294341610598)); -#173716 = VECTOR('',#173717,1.); -#173717 = DIRECTION('',(-1.355252715607E-016,1.)); -#173718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173719 = PCURVE('',#170862,#173720); -#173720 = DEFINITIONAL_REPRESENTATION('',(#173721),#173747); -#173721 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173722,#173723,#173724, - #173725,#173726,#173727,#173728,#173729,#173730,#173731,#173732, - #173733,#173734,#173735,#173736,#173737,#173738,#173739,#173740, - #173741,#173742,#173743,#173744,#173745,#173746),.UNSPECIFIED.,.F., +#176071 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#176072 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#176073 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); +#176074 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#176075 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#176076 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#176077 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#176078 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#176079 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#176080 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#176081 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#176082 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#176083 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#176084 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#176085 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#176086 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#176087 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#176088 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#176089 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#176090 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#176091 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#176092 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#176093 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#176094 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#176095 = CARTESIAN_POINT('',(0.751879414295,1.)); +#176096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176097 = ORIENTED_EDGE('',*,*,#176098,.T.); +#176098 = EDGE_CURVE('',#176052,#173171,#176099,.T.); +#176099 = SURFACE_CURVE('',#176100,(#176104,#176111),.PCURVE_S1.); +#176100 = LINE('',#176101,#176102); +#176101 = CARTESIAN_POINT('',(1.270864135142,0.494341610598,1.2)); +#176102 = VECTOR('',#176103,1.); +#176103 = DIRECTION('',(-1.355252715607E-016,1.,0.E+000)); +#176104 = PCURVE('',#172379,#176105); +#176105 = DEFINITIONAL_REPRESENTATION('',(#176106),#176110); +#176106 = LINE('',#176107,#176108); +#176107 = CARTESIAN_POINT('',(-0.199135864858,1.294341610598)); +#176108 = VECTOR('',#176109,1.); +#176109 = DIRECTION('',(-1.355252715607E-016,1.)); +#176110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176111 = PCURVE('',#173254,#176112); +#176112 = DEFINITIONAL_REPRESENTATION('',(#176113),#176139); +#176113 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176114,#176115,#176116, + #176117,#176118,#176119,#176120,#176121,#176122,#176123,#176124, + #176125,#176126,#176127,#176128,#176129,#176130,#176131,#176132, + #176133,#176134,#176135,#176136,#176137,#176138),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.998613163111, -0.952770294701,-0.906927426291,-0.86108455788,-0.81524168947, -0.76939882106,-0.72355595265,-0.677713084239,-0.631870215829, @@ -214995,69 +217997,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.402655873777,-0.356813005367,-0.310970136957,-0.265127268546, -0.219284400136,-0.173441531726,-0.127598663315,-8.175579490513E-002 ,-3.591292649481E-002,9.929941915506E-003),.UNSPECIFIED.); -#173722 = CARTESIAN_POINT('',(1.570796326795,0.295728447487)); -#173723 = CARTESIAN_POINT('',(1.570796326795,0.311009403623)); -#173724 = CARTESIAN_POINT('',(1.570796326795,0.341571315897)); -#173725 = CARTESIAN_POINT('',(1.570796326795,0.387414184307)); -#173726 = CARTESIAN_POINT('',(1.570796326795,0.433257052717)); -#173727 = CARTESIAN_POINT('',(1.570796326795,0.479099921128)); -#173728 = CARTESIAN_POINT('',(1.570796326795,0.524942789538)); -#173729 = CARTESIAN_POINT('',(1.570796326795,0.570785657948)); -#173730 = CARTESIAN_POINT('',(1.570796326795,0.616628526359)); -#173731 = CARTESIAN_POINT('',(1.570796326795,0.662471394769)); -#173732 = CARTESIAN_POINT('',(1.570796326795,0.708314263179)); -#173733 = CARTESIAN_POINT('',(1.570796326795,0.75415713159)); -#173734 = CARTESIAN_POINT('',(1.570796326795,0.8)); -#173735 = CARTESIAN_POINT('',(1.570796326795,0.84584286841)); -#173736 = CARTESIAN_POINT('',(1.570796326795,0.891685736821)); -#173737 = CARTESIAN_POINT('',(1.570796326795,0.937528605231)); -#173738 = CARTESIAN_POINT('',(1.570796326795,0.983371473641)); -#173739 = CARTESIAN_POINT('',(1.570796326795,1.029214342052)); -#173740 = CARTESIAN_POINT('',(1.570796326795,1.075057210462)); -#173741 = CARTESIAN_POINT('',(1.570796326795,1.120900078872)); -#173742 = CARTESIAN_POINT('',(1.570796326795,1.166742947283)); -#173743 = CARTESIAN_POINT('',(1.570796326795,1.212585815693)); -#173744 = CARTESIAN_POINT('',(1.570796326795,1.258428684103)); -#173745 = CARTESIAN_POINT('',(1.570796326795,1.288990596377)); -#173746 = CARTESIAN_POINT('',(1.570796326795,1.304271552513)); -#173747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173748 = ORIENTED_EDGE('',*,*,#170778,.T.); -#173749 = ORIENTED_EDGE('',*,*,#173750,.T.); -#173750 = EDGE_CURVE('',#170694,#173751,#173753,.T.); -#173751 = VERTEX_POINT('',#173752); -#173752 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); -#173753 = SURFACE_CURVE('',#173754,(#173759,#173767),.PCURVE_S1.); -#173754 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173755,#173756,#173757, -#173758),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#176114 = CARTESIAN_POINT('',(1.570796326795,0.295728447487)); +#176115 = CARTESIAN_POINT('',(1.570796326795,0.311009403623)); +#176116 = CARTESIAN_POINT('',(1.570796326795,0.341571315897)); +#176117 = CARTESIAN_POINT('',(1.570796326795,0.387414184307)); +#176118 = CARTESIAN_POINT('',(1.570796326795,0.433257052717)); +#176119 = CARTESIAN_POINT('',(1.570796326795,0.479099921128)); +#176120 = CARTESIAN_POINT('',(1.570796326795,0.524942789538)); +#176121 = CARTESIAN_POINT('',(1.570796326795,0.570785657948)); +#176122 = CARTESIAN_POINT('',(1.570796326795,0.616628526359)); +#176123 = CARTESIAN_POINT('',(1.570796326795,0.662471394769)); +#176124 = CARTESIAN_POINT('',(1.570796326795,0.708314263179)); +#176125 = CARTESIAN_POINT('',(1.570796326795,0.75415713159)); +#176126 = CARTESIAN_POINT('',(1.570796326795,0.8)); +#176127 = CARTESIAN_POINT('',(1.570796326795,0.84584286841)); +#176128 = CARTESIAN_POINT('',(1.570796326795,0.891685736821)); +#176129 = CARTESIAN_POINT('',(1.570796326795,0.937528605231)); +#176130 = CARTESIAN_POINT('',(1.570796326795,0.983371473641)); +#176131 = CARTESIAN_POINT('',(1.570796326795,1.029214342052)); +#176132 = CARTESIAN_POINT('',(1.570796326795,1.075057210462)); +#176133 = CARTESIAN_POINT('',(1.570796326795,1.120900078872)); +#176134 = CARTESIAN_POINT('',(1.570796326795,1.166742947283)); +#176135 = CARTESIAN_POINT('',(1.570796326795,1.212585815693)); +#176136 = CARTESIAN_POINT('',(1.570796326795,1.258428684103)); +#176137 = CARTESIAN_POINT('',(1.570796326795,1.288990596377)); +#176138 = CARTESIAN_POINT('',(1.570796326795,1.304271552513)); +#176139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176140 = ORIENTED_EDGE('',*,*,#173170,.T.); +#176141 = ORIENTED_EDGE('',*,*,#176142,.T.); +#176142 = EDGE_CURVE('',#173086,#176143,#176145,.T.); +#176143 = VERTEX_POINT('',#176144); +#176144 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); +#176145 = SURFACE_CURVE('',#176146,(#176151,#176159),.PCURVE_S1.); +#176146 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176147,#176148,#176149, +#176150),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.490777987168E-015,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173755 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); -#173756 = CARTESIAN_POINT('',(1.224801147872,0.591106375747,1.2)); -#173757 = CARTESIAN_POINT('',(1.200789126784,0.600864135142,1.2)); -#173758 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); -#173759 = PCURVE('',#169987,#173760); -#173760 = DEFINITIONAL_REPRESENTATION('',(#173761),#173766); -#173761 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173762,#173763,#173764, -#173765),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#176147 = CARTESIAN_POINT('',(1.242953761809,0.572953761809,1.2)); +#176148 = CARTESIAN_POINT('',(1.224801147872,0.591106375747,1.2)); +#176149 = CARTESIAN_POINT('',(1.200789126784,0.600864135142,1.2)); +#176150 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.2)); +#176151 = PCURVE('',#172379,#176152); +#176152 = DEFINITIONAL_REPRESENTATION('',(#176153),#176158); +#176153 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176154,#176155,#176156, +#176157),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.490777987168E-015,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173762 = CARTESIAN_POINT('',(-0.227046238191,1.372953761809)); -#173763 = CARTESIAN_POINT('',(-0.245198852128,1.391106375747)); -#173764 = CARTESIAN_POINT('',(-0.269210873216,1.400864135142)); -#173765 = CARTESIAN_POINT('',(-0.295728447487,1.400864135142)); -#173766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173767 = PCURVE('',#170732,#173768); -#173768 = DEFINITIONAL_REPRESENTATION('',(#173769),#173795); -#173769 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173770,#173771,#173772, - #173773,#173774,#173775,#173776,#173777,#173778,#173779,#173780, - #173781,#173782,#173783,#173784,#173785,#173786,#173787,#173788, - #173789,#173790,#173791,#173792,#173793,#173794),.UNSPECIFIED.,.F., +#176154 = CARTESIAN_POINT('',(-0.227046238191,1.372953761809)); +#176155 = CARTESIAN_POINT('',(-0.245198852128,1.391106375747)); +#176156 = CARTESIAN_POINT('',(-0.269210873216,1.400864135142)); +#176157 = CARTESIAN_POINT('',(-0.295728447487,1.400864135142)); +#176158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176159 = PCURVE('',#173124,#176160); +#176160 = DEFINITIONAL_REPRESENTATION('',(#176161),#176187); +#176161 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176162,#176163,#176164, + #176165,#176166,#176167,#176168,#176169,#176170,#176171,#176172, + #176173,#176174,#176175,#176176,#176177,#176178,#176179,#176180, + #176181,#176182,#176183,#176184,#176185,#176186),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.490777987168E-015,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -215066,93 +218068,93 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#173770 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#173771 = CARTESIAN_POINT('',(1.112573796453E-002,0.999999986247)); -#173772 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#173773 = CARTESIAN_POINT('',(6.714590753945E-002,0.999858629242)); -#173774 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#173775 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#173776 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#173777 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#173778 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#173779 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#173780 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#173781 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#173782 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#173783 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#173784 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#173785 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#173786 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#173787 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#173788 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#173789 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#173790 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#173791 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#173792 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#173793 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#173794 = CARTESIAN_POINT('',(0.751879414295,1.)); -#173795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173796 = ORIENTED_EDGE('',*,*,#173797,.T.); -#173797 = EDGE_CURVE('',#173751,#170504,#173798,.T.); -#173798 = SURFACE_CURVE('',#173799,(#173803,#173810),.PCURVE_S1.); -#173799 = LINE('',#173800,#173801); -#173800 = CARTESIAN_POINT('',(-1.164341610598,0.600864135142,1.2)); -#173801 = VECTOR('',#173802,1.); -#173802 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#173803 = PCURVE('',#169987,#173804); -#173804 = DEFINITIONAL_REPRESENTATION('',(#173805),#173809); -#173805 = LINE('',#173806,#173807); -#173806 = CARTESIAN_POINT('',(-2.634341610598,1.400864135142)); -#173807 = VECTOR('',#173808,1.); -#173808 = DIRECTION('',(-1.,0.E+000)); -#173809 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173810 = PCURVE('',#170587,#173811); -#173811 = DEFINITIONAL_REPRESENTATION('',(#173812),#173815); -#173812 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173813,#173814), +#176162 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#176163 = CARTESIAN_POINT('',(1.112573796453E-002,0.999999986247)); +#176164 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#176165 = CARTESIAN_POINT('',(6.714590753945E-002,0.999858629242)); +#176166 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#176167 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#176168 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#176169 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#176170 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#176171 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#176172 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#176173 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#176174 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#176175 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#176176 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#176177 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#176178 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#176179 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#176180 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#176181 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#176182 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#176183 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#176184 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#176185 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#176186 = CARTESIAN_POINT('',(0.751879414295,1.)); +#176187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176188 = ORIENTED_EDGE('',*,*,#176189,.T.); +#176189 = EDGE_CURVE('',#176143,#172896,#176190,.T.); +#176190 = SURFACE_CURVE('',#176191,(#176195,#176202),.PCURVE_S1.); +#176191 = LINE('',#176192,#176193); +#176192 = CARTESIAN_POINT('',(-1.164341610598,0.600864135142,1.2)); +#176193 = VECTOR('',#176194,1.); +#176194 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176195 = PCURVE('',#172379,#176196); +#176196 = DEFINITIONAL_REPRESENTATION('',(#176197),#176201); +#176197 = LINE('',#176198,#176199); +#176198 = CARTESIAN_POINT('',(-2.634341610598,1.400864135142)); +#176199 = VECTOR('',#176200,1.); +#176200 = DIRECTION('',(-1.,0.E+000)); +#176201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176202 = PCURVE('',#172979,#176203); +#176203 = DEFINITIONAL_REPRESENTATION('',(#176204),#176207); +#176204 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176205,#176206), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.338613163111,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#173813 = CARTESIAN_POINT('',(0.E+000,0.295728447487)); -#173814 = CARTESIAN_POINT('',(0.E+000,2.644271552513)); -#173815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#176205 = CARTESIAN_POINT('',(0.E+000,0.295728447487)); +#176206 = CARTESIAN_POINT('',(0.E+000,2.644271552513)); +#176207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#173816 = ORIENTED_EDGE('',*,*,#170503,.T.); -#173817 = ORIENTED_EDGE('',*,*,#173818,.T.); -#173818 = EDGE_CURVE('',#170419,#173546,#173819,.T.); -#173819 = SURFACE_CURVE('',#173820,(#173825,#173833),.PCURVE_S1.); -#173820 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173821,#173822,#173823, -#173824),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#176208 = ORIENTED_EDGE('',*,*,#172895,.T.); +#176209 = ORIENTED_EDGE('',*,*,#176210,.T.); +#176210 = EDGE_CURVE('',#172811,#175938,#176211,.T.); +#176211 = SURFACE_CURVE('',#176212,(#176217,#176225),.PCURVE_S1.); +#176212 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176213,#176214,#176215, +#176216),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173821 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); -#173822 = CARTESIAN_POINT('',(-1.261106375747,0.554801147872,1.2)); -#173823 = CARTESIAN_POINT('',(-1.270864135142,0.530789126784,1.2)); -#173824 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); -#173825 = PCURVE('',#169987,#173826); -#173826 = DEFINITIONAL_REPRESENTATION('',(#173827),#173832); -#173827 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#173828,#173829,#173830, -#173831),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#176213 = CARTESIAN_POINT('',(-1.242953761809,0.572953761809,1.2)); +#176214 = CARTESIAN_POINT('',(-1.261106375747,0.554801147872,1.2)); +#176215 = CARTESIAN_POINT('',(-1.270864135142,0.530789126784,1.2)); +#176216 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.2)); +#176217 = PCURVE('',#172379,#176218); +#176218 = DEFINITIONAL_REPRESENTATION('',(#176219),#176224); +#176219 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176220,#176221,#176222, +#176223),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#173828 = CARTESIAN_POINT('',(-2.712953761809,1.372953761809)); -#173829 = CARTESIAN_POINT('',(-2.731106375747,1.354801147872)); -#173830 = CARTESIAN_POINT('',(-2.740864135142,1.330789126784)); -#173831 = CARTESIAN_POINT('',(-2.740864135142,1.304271552513)); -#173832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173833 = PCURVE('',#170457,#173834); -#173834 = DEFINITIONAL_REPRESENTATION('',(#173835),#173861); -#173835 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173836,#173837,#173838, - #173839,#173840,#173841,#173842,#173843,#173844,#173845,#173846, - #173847,#173848,#173849,#173850,#173851,#173852,#173853,#173854, - #173855,#173856,#173857,#173858,#173859,#173860),.UNSPECIFIED.,.F., +#176220 = CARTESIAN_POINT('',(-2.712953761809,1.372953761809)); +#176221 = CARTESIAN_POINT('',(-2.731106375747,1.354801147872)); +#176222 = CARTESIAN_POINT('',(-2.740864135142,1.330789126784)); +#176223 = CARTESIAN_POINT('',(-2.740864135142,1.304271552513)); +#176224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176225 = PCURVE('',#172849,#176226); +#176226 = DEFINITIONAL_REPRESENTATION('',(#176227),#176253); +#176227 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176228,#176229,#176230, + #176231,#176232,#176233,#176234,#176235,#176236,#176237,#176238, + #176239,#176240,#176241,#176242,#176243,#176244,#176245,#176246, + #176247,#176248,#176249,#176250,#176251,#176252),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -215160,59 +218162,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#173836 = CARTESIAN_POINT('',(0.E+000,1.)); -#173837 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#173838 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#173839 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#173840 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#173841 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#173842 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#173843 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#173844 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#173845 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#173846 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#173847 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#173848 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#173849 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#173850 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#173851 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#173852 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#173853 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#173854 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#173855 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#173856 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#173857 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#173858 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#173859 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#173860 = CARTESIAN_POINT('',(0.751879414295,1.)); -#173861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173862 = FACE_BOUND('',#173863,.T.); -#173863 = EDGE_LOOP('',(#173864,#173908)); -#173864 = ORIENTED_EDGE('',*,*,#173865,.F.); -#173865 = EDGE_CURVE('',#170935,#170961,#173866,.T.); -#173866 = SURFACE_CURVE('',#173867,(#173872,#173879),.PCURVE_S1.); -#173867 = CIRCLE('',#173868,0.15); -#173868 = AXIS2_PLACEMENT_3D('',#173869,#173870,#173871); -#173869 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); -#173870 = DIRECTION('',(0.E+000,0.E+000,1.)); -#173871 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173872 = PCURVE('',#169987,#173873); -#173873 = DEFINITIONAL_REPRESENTATION('',(#173874),#173878); -#173874 = CIRCLE('',#173875,0.15); -#173875 = AXIS2_PLACEMENT_2D('',#173876,#173877); -#173876 = CARTESIAN_POINT('',(-2.445,0.4)); -#173877 = DIRECTION('',(1.,0.E+000)); -#173878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173879 = PCURVE('',#170949,#173880); -#173880 = DEFINITIONAL_REPRESENTATION('',(#173881),#173907); -#173881 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#173882,#173883,#173884, - #173885,#173886,#173887,#173888,#173889,#173890,#173891,#173892, - #173893,#173894,#173895,#173896,#173897,#173898,#173899,#173900, - #173901,#173902,#173903,#173904,#173905,#173906),.UNSPECIFIED.,.F., +#176228 = CARTESIAN_POINT('',(0.E+000,1.)); +#176229 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#176230 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#176231 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#176232 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#176233 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#176234 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#176235 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#176236 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#176237 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#176238 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#176239 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#176240 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#176241 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#176242 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#176243 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#176244 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#176245 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#176246 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#176247 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#176248 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#176249 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#176250 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#176251 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#176252 = CARTESIAN_POINT('',(0.751879414295,1.)); +#176253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176254 = FACE_BOUND('',#176255,.T.); +#176255 = EDGE_LOOP('',(#176256,#176300)); +#176256 = ORIENTED_EDGE('',*,*,#176257,.F.); +#176257 = EDGE_CURVE('',#173327,#173353,#176258,.T.); +#176258 = SURFACE_CURVE('',#176259,(#176264,#176271),.PCURVE_S1.); +#176259 = CIRCLE('',#176260,0.15); +#176260 = AXIS2_PLACEMENT_3D('',#176261,#176262,#176263); +#176261 = CARTESIAN_POINT('',(-0.975,-0.4,1.2)); +#176262 = DIRECTION('',(0.E+000,0.E+000,1.)); +#176263 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176264 = PCURVE('',#172379,#176265); +#176265 = DEFINITIONAL_REPRESENTATION('',(#176266),#176270); +#176266 = CIRCLE('',#176267,0.15); +#176267 = AXIS2_PLACEMENT_2D('',#176268,#176269); +#176268 = CARTESIAN_POINT('',(-2.445,0.4)); +#176269 = DIRECTION('',(1.,0.E+000)); +#176270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176271 = PCURVE('',#173341,#176272); +#176272 = DEFINITIONAL_REPRESENTATION('',(#176273),#176299); +#176273 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176274,#176275,#176276, + #176277,#176278,#176279,#176280,#176281,#176282,#176283,#176284, + #176285,#176286,#176287,#176288,#176289,#176290,#176291,#176292, + #176293,#176294,#176295,#176296,#176297,#176298),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 0.142799666072,0.285599332145,0.428398998217,0.571198664289, 0.713998330361,0.856797996434,0.999597662506,1.142397328578, @@ -215220,882 +218222,882 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.856395658939,1.999195325012,2.141994991084,2.284794657156, 2.427594323228,2.570393989301,2.713193655373,2.855993321445, 2.998792987518,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#173882 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#173883 = CARTESIAN_POINT('',(4.759988869075E-002,-3.048556533535E-017) - ); -#173884 = CARTESIAN_POINT('',(0.142799666072,-3.353709924348E-017)); -#173885 = CARTESIAN_POINT('',(0.285599332145,3.830382253988E-017)); -#173886 = CARTESIAN_POINT('',(0.428398998217,2.050150405556E-017)); -#173887 = CARTESIAN_POINT('',(0.571198664289,-1.248238416098E-017)); -#173888 = CARTESIAN_POINT('',(0.713998330361,-9.730991028367E-018)); -#173889 = CARTESIAN_POINT('',(0.856797996434,-1.313797286072E-017)); -#173890 = CARTESIAN_POINT('',(0.999597662506,1.431508053579E-017)); -#173891 = CARTESIAN_POINT('',(1.142397328578,5.366968908038E-018)); -#173892 = CARTESIAN_POINT('',(1.28519699465,-9.03630200027E-018)); -#173893 = CARTESIAN_POINT('',(1.427996660723,1.360112137159E-017)); -#173894 = CARTESIAN_POINT('',(1.570796326795,-7.850795828722E-018)); -#173895 = CARTESIAN_POINT('',(1.713595992867,1.78020619433E-017)); -#173896 = CARTESIAN_POINT('',(1.856395658939,-2.584006428713E-017)); -#173897 = CARTESIAN_POINT('',(1.999195325012,-2.407105496107E-017)); -#173898 = CARTESIAN_POINT('',(2.141994991084,1.265519357092E-017)); -#173899 = CARTESIAN_POINT('',(2.284794657156,2.293959886789E-017)); -#173900 = CARTESIAN_POINT('',(2.427594323228,6.239264039247E-017)); -#173901 = CARTESIAN_POINT('',(2.570393989301,-8.912741180311E-017)); -#173902 = CARTESIAN_POINT('',(2.713193655373,6.765132422659E-017)); -#173903 = CARTESIAN_POINT('',(2.855993321445,-7.361039060068E-017)); -#173904 = CARTESIAN_POINT('',(2.998792987518,5.221626786018E-017)); -#173905 = CARTESIAN_POINT('',(3.093992764899,6.048842741435E-017)); -#173906 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); -#173907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173908 = ORIENTED_EDGE('',*,*,#170960,.F.); -#173909 = ADVANCED_FACE('',(#173910),#171932,.T.); -#173910 = FACE_BOUND('',#173911,.T.); -#173911 = EDGE_LOOP('',(#173912,#173913,#173936,#173963)); -#173912 = ORIENTED_EDGE('',*,*,#171916,.T.); -#173913 = ORIENTED_EDGE('',*,*,#173914,.F.); -#173914 = EDGE_CURVE('',#173915,#171889,#173917,.T.); -#173915 = VERTEX_POINT('',#173916); -#173916 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.6)); -#173917 = SURFACE_CURVE('',#173918,(#173922,#173929),.PCURVE_S1.); -#173918 = LINE('',#173919,#173920); -#173919 = CARTESIAN_POINT('',(1.125,-0.7,0.6)); -#173920 = VECTOR('',#173921,1.); -#173921 = DIRECTION('',(0.E+000,1.,0.E+000)); -#173922 = PCURVE('',#171932,#173923); -#173923 = DEFINITIONAL_REPRESENTATION('',(#173924),#173928); -#173924 = LINE('',#173925,#173926); -#173925 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#173926 = VECTOR('',#173927,1.); -#173927 = DIRECTION('',(0.E+000,1.)); -#173928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173929 = PCURVE('',#173421,#173930); -#173930 = DEFINITIONAL_REPRESENTATION('',(#173931),#173935); -#173931 = LINE('',#173932,#173933); -#173932 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#173933 = VECTOR('',#173934,1.); -#173934 = DIRECTION('',(0.E+000,1.)); -#173935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173936 = ORIENTED_EDGE('',*,*,#173937,.F.); -#173937 = EDGE_CURVE('',#173938,#173915,#173940,.T.); -#173938 = VERTEX_POINT('',#173939); -#173939 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.6)); -#173940 = SURFACE_CURVE('',#173941,(#173945,#173952),.PCURVE_S1.); -#173941 = LINE('',#173942,#173943); -#173942 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.6)); -#173943 = VECTOR('',#173944,1.); -#173944 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173945 = PCURVE('',#171932,#173946); -#173946 = DEFINITIONAL_REPRESENTATION('',(#173947),#173951); -#173947 = LINE('',#173948,#173949); -#173948 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); -#173949 = VECTOR('',#173950,1.); -#173950 = DIRECTION('',(-1.,0.E+000)); -#173951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173952 = PCURVE('',#173953,#173958); -#173953 = CYLINDRICAL_SURFACE('',#173954,0.1); -#173954 = AXIS2_PLACEMENT_3D('',#173955,#173956,#173957); -#173955 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); -#173956 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173957 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#173958 = DEFINITIONAL_REPRESENTATION('',(#173959),#173962); -#173959 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#173960,#173961), +#176274 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176275 = CARTESIAN_POINT('',(4.759988869075E-002,-3.048556533535E-017) + ); +#176276 = CARTESIAN_POINT('',(0.142799666072,-3.353709924348E-017)); +#176277 = CARTESIAN_POINT('',(0.285599332145,3.830382253988E-017)); +#176278 = CARTESIAN_POINT('',(0.428398998217,2.050150405556E-017)); +#176279 = CARTESIAN_POINT('',(0.571198664289,-1.248238416098E-017)); +#176280 = CARTESIAN_POINT('',(0.713998330361,-9.730991028367E-018)); +#176281 = CARTESIAN_POINT('',(0.856797996434,-1.313797286072E-017)); +#176282 = CARTESIAN_POINT('',(0.999597662506,1.431508053579E-017)); +#176283 = CARTESIAN_POINT('',(1.142397328578,5.366968908038E-018)); +#176284 = CARTESIAN_POINT('',(1.28519699465,-9.03630200027E-018)); +#176285 = CARTESIAN_POINT('',(1.427996660723,1.360112137159E-017)); +#176286 = CARTESIAN_POINT('',(1.570796326795,-7.850795828722E-018)); +#176287 = CARTESIAN_POINT('',(1.713595992867,1.78020619433E-017)); +#176288 = CARTESIAN_POINT('',(1.856395658939,-2.584006428713E-017)); +#176289 = CARTESIAN_POINT('',(1.999195325012,-2.407105496107E-017)); +#176290 = CARTESIAN_POINT('',(2.141994991084,1.265519357092E-017)); +#176291 = CARTESIAN_POINT('',(2.284794657156,2.293959886789E-017)); +#176292 = CARTESIAN_POINT('',(2.427594323228,6.239264039247E-017)); +#176293 = CARTESIAN_POINT('',(2.570393989301,-8.912741180311E-017)); +#176294 = CARTESIAN_POINT('',(2.713193655373,6.765132422659E-017)); +#176295 = CARTESIAN_POINT('',(2.855993321445,-7.361039060068E-017)); +#176296 = CARTESIAN_POINT('',(2.998792987518,5.221626786018E-017)); +#176297 = CARTESIAN_POINT('',(3.093992764899,6.048842741435E-017)); +#176298 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); +#176299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176300 = ORIENTED_EDGE('',*,*,#173352,.F.); +#176301 = ADVANCED_FACE('',(#176302),#174324,.T.); +#176302 = FACE_BOUND('',#176303,.T.); +#176303 = EDGE_LOOP('',(#176304,#176305,#176328,#176355)); +#176304 = ORIENTED_EDGE('',*,*,#174308,.T.); +#176305 = ORIENTED_EDGE('',*,*,#176306,.F.); +#176306 = EDGE_CURVE('',#176307,#174281,#176309,.T.); +#176307 = VERTEX_POINT('',#176308); +#176308 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.6)); +#176309 = SURFACE_CURVE('',#176310,(#176314,#176321),.PCURVE_S1.); +#176310 = LINE('',#176311,#176312); +#176311 = CARTESIAN_POINT('',(1.125,-0.7,0.6)); +#176312 = VECTOR('',#176313,1.); +#176313 = DIRECTION('',(0.E+000,1.,0.E+000)); +#176314 = PCURVE('',#174324,#176315); +#176315 = DEFINITIONAL_REPRESENTATION('',(#176316),#176320); +#176316 = LINE('',#176317,#176318); +#176317 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#176318 = VECTOR('',#176319,1.); +#176319 = DIRECTION('',(0.E+000,1.)); +#176320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176321 = PCURVE('',#175813,#176322); +#176322 = DEFINITIONAL_REPRESENTATION('',(#176323),#176327); +#176323 = LINE('',#176324,#176325); +#176324 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#176325 = VECTOR('',#176326,1.); +#176326 = DIRECTION('',(0.E+000,1.)); +#176327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176328 = ORIENTED_EDGE('',*,*,#176329,.F.); +#176329 = EDGE_CURVE('',#176330,#176307,#176332,.T.); +#176330 = VERTEX_POINT('',#176331); +#176331 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.6)); +#176332 = SURFACE_CURVE('',#176333,(#176337,#176344),.PCURVE_S1.); +#176333 = LINE('',#176334,#176335); +#176334 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.6)); +#176335 = VECTOR('',#176336,1.); +#176336 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176337 = PCURVE('',#174324,#176338); +#176338 = DEFINITIONAL_REPRESENTATION('',(#176339),#176343); +#176339 = LINE('',#176340,#176341); +#176340 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); +#176341 = VECTOR('',#176342,1.); +#176342 = DIRECTION('',(-1.,0.E+000)); +#176343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176344 = PCURVE('',#176345,#176350); +#176345 = CYLINDRICAL_SURFACE('',#176346,0.1); +#176346 = AXIS2_PLACEMENT_3D('',#176347,#176348,#176349); +#176347 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); +#176348 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176349 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176350 = DEFINITIONAL_REPRESENTATION('',(#176351),#176354); +#176351 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176352,#176353), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#173960 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#173961 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#173962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173963 = ORIENTED_EDGE('',*,*,#173964,.T.); -#173964 = EDGE_CURVE('',#173938,#171917,#173965,.T.); -#173965 = SURFACE_CURVE('',#173966,(#173970,#173977),.PCURVE_S1.); -#173966 = LINE('',#173967,#173968); -#173967 = CARTESIAN_POINT('',(0.785,-0.7,0.6)); -#173968 = VECTOR('',#173969,1.); -#173969 = DIRECTION('',(0.E+000,1.,0.E+000)); -#173970 = PCURVE('',#171932,#173971); -#173971 = DEFINITIONAL_REPRESENTATION('',(#173972),#173976); -#173972 = LINE('',#173973,#173974); -#173973 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#173974 = VECTOR('',#173975,1.); -#173975 = DIRECTION('',(0.E+000,1.)); -#173976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173977 = PCURVE('',#173367,#173978); -#173978 = DEFINITIONAL_REPRESENTATION('',(#173979),#173983); -#173979 = LINE('',#173980,#173981); -#173980 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#173981 = VECTOR('',#173982,1.); -#173982 = DIRECTION('',(0.E+000,1.)); -#173983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#173984 = ADVANCED_FACE('',(#173985),#173395,.T.); -#173985 = FACE_BOUND('',#173986,.T.); -#173986 = EDGE_LOOP('',(#173987,#174016,#174037,#174038)); -#173987 = ORIENTED_EDGE('',*,*,#173988,.T.); -#173988 = EDGE_CURVE('',#173989,#173991,#173993,.T.); -#173989 = VERTEX_POINT('',#173990); -#173990 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); -#173991 = VERTEX_POINT('',#173992); -#173992 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.75)); -#173993 = SURFACE_CURVE('',#173994,(#173998,#174005),.PCURVE_S1.); -#173994 = LINE('',#173995,#173996); -#173995 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); -#173996 = VECTOR('',#173997,1.); -#173997 = DIRECTION('',(1.,0.E+000,0.E+000)); -#173998 = PCURVE('',#173395,#173999); -#173999 = DEFINITIONAL_REPRESENTATION('',(#174000),#174004); -#174000 = LINE('',#174001,#174002); -#174001 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); -#174002 = VECTOR('',#174003,1.); -#174003 = DIRECTION('',(1.,0.E+000)); -#174004 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174005 = PCURVE('',#174006,#174011); -#174006 = CYLINDRICAL_SURFACE('',#174007,0.25); -#174007 = AXIS2_PLACEMENT_3D('',#174008,#174009,#174010); -#174008 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); -#174009 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174010 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174011 = DEFINITIONAL_REPRESENTATION('',(#174012),#174015); -#174012 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174013,#174014), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174013 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174014 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#174015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174016 = ORIENTED_EDGE('',*,*,#174017,.F.); -#174017 = EDGE_CURVE('',#173380,#173991,#174018,.T.); -#174018 = SURFACE_CURVE('',#174019,(#174023,#174030),.PCURVE_S1.); -#174019 = LINE('',#174020,#174021); -#174020 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.75)); -#174021 = VECTOR('',#174022,1.); -#174022 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174023 = PCURVE('',#173395,#174024); -#174024 = DEFINITIONAL_REPRESENTATION('',(#174025),#174029); -#174025 = LINE('',#174026,#174027); -#174026 = CARTESIAN_POINT('',(0.34,0.E+000)); -#174027 = VECTOR('',#174028,1.); -#174028 = DIRECTION('',(0.E+000,-1.)); -#174029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174030 = PCURVE('',#173421,#174031); -#174031 = DEFINITIONAL_REPRESENTATION('',(#174032),#174036); -#174032 = LINE('',#174033,#174034); -#174033 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#174034 = VECTOR('',#174035,1.); -#174035 = DIRECTION('',(0.E+000,-1.)); -#174036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174037 = ORIENTED_EDGE('',*,*,#173379,.F.); -#174038 = ORIENTED_EDGE('',*,*,#174039,.T.); -#174039 = EDGE_CURVE('',#173352,#173989,#174040,.T.); -#174040 = SURFACE_CURVE('',#174041,(#174045,#174052),.PCURVE_S1.); -#174041 = LINE('',#174042,#174043); -#174042 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); -#174043 = VECTOR('',#174044,1.); -#174044 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174045 = PCURVE('',#173395,#174046); -#174046 = DEFINITIONAL_REPRESENTATION('',(#174047),#174051); -#174047 = LINE('',#174048,#174049); -#174048 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174049 = VECTOR('',#174050,1.); -#174050 = DIRECTION('',(0.E+000,-1.)); -#174051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174052 = PCURVE('',#173367,#174053); -#174053 = DEFINITIONAL_REPRESENTATION('',(#174054),#174058); -#174054 = LINE('',#174055,#174056); -#174055 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#174056 = VECTOR('',#174057,1.); -#174057 = DIRECTION('',(0.E+000,-1.)); -#174058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#176352 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#176353 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#176354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#174059 = ADVANCED_FACE('',(#174060),#173367,.T.); -#174060 = FACE_BOUND('',#174061,.T.); -#174061 = EDGE_LOOP('',(#174062,#174063,#174064,#174087,#174115,#174147, - #174175,#174203,#174231,#174259,#174287,#174312)); -#174062 = ORIENTED_EDGE('',*,*,#173351,.F.); -#174063 = ORIENTED_EDGE('',*,*,#173964,.F.); -#174064 = ORIENTED_EDGE('',*,*,#174065,.F.); -#174065 = EDGE_CURVE('',#174066,#173938,#174068,.T.); -#174066 = VERTEX_POINT('',#174067); -#174067 = CARTESIAN_POINT('',(0.785,-0.906981201809,0.50752811704)); -#174068 = SURFACE_CURVE('',#174069,(#174074,#174081),.PCURVE_S1.); -#174069 = CIRCLE('',#174070,0.1); -#174070 = AXIS2_PLACEMENT_3D('',#174071,#174072,#174073); -#174071 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); -#174072 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#174073 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174074 = PCURVE('',#173367,#174075); -#174075 = DEFINITIONAL_REPRESENTATION('',(#174076),#174080); -#174076 = CIRCLE('',#174077,0.1); -#174077 = AXIS2_PLACEMENT_2D('',#174078,#174079); -#174078 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#174079 = DIRECTION('',(-1.,0.E+000)); -#174080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174081 = PCURVE('',#173953,#174082); -#174082 = DEFINITIONAL_REPRESENTATION('',(#174083),#174086); -#174083 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174084,#174085), +#176355 = ORIENTED_EDGE('',*,*,#176356,.T.); +#176356 = EDGE_CURVE('',#176330,#174309,#176357,.T.); +#176357 = SURFACE_CURVE('',#176358,(#176362,#176369),.PCURVE_S1.); +#176358 = LINE('',#176359,#176360); +#176359 = CARTESIAN_POINT('',(0.785,-0.7,0.6)); +#176360 = VECTOR('',#176361,1.); +#176361 = DIRECTION('',(0.E+000,1.,0.E+000)); +#176362 = PCURVE('',#174324,#176363); +#176363 = DEFINITIONAL_REPRESENTATION('',(#176364),#176368); +#176364 = LINE('',#176365,#176366); +#176365 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176366 = VECTOR('',#176367,1.); +#176367 = DIRECTION('',(0.E+000,1.)); +#176368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176369 = PCURVE('',#175759,#176370); +#176370 = DEFINITIONAL_REPRESENTATION('',(#176371),#176375); +#176371 = LINE('',#176372,#176373); +#176372 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#176373 = VECTOR('',#176374,1.); +#176374 = DIRECTION('',(0.E+000,1.)); +#176375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176376 = ADVANCED_FACE('',(#176377),#175787,.T.); +#176377 = FACE_BOUND('',#176378,.T.); +#176378 = EDGE_LOOP('',(#176379,#176408,#176429,#176430)); +#176379 = ORIENTED_EDGE('',*,*,#176380,.T.); +#176380 = EDGE_CURVE('',#176381,#176383,#176385,.T.); +#176381 = VERTEX_POINT('',#176382); +#176382 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); +#176383 = VERTEX_POINT('',#176384); +#176384 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.75)); +#176385 = SURFACE_CURVE('',#176386,(#176390,#176397),.PCURVE_S1.); +#176386 = LINE('',#176387,#176388); +#176387 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); +#176388 = VECTOR('',#176389,1.); +#176389 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176390 = PCURVE('',#175787,#176391); +#176391 = DEFINITIONAL_REPRESENTATION('',(#176392),#176396); +#176392 = LINE('',#176393,#176394); +#176393 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); +#176394 = VECTOR('',#176395,1.); +#176395 = DIRECTION('',(1.,0.E+000)); +#176396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176397 = PCURVE('',#176398,#176403); +#176398 = CYLINDRICAL_SURFACE('',#176399,0.25); +#176399 = AXIS2_PLACEMENT_3D('',#176400,#176401,#176402); +#176400 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); +#176401 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176402 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176403 = DEFINITIONAL_REPRESENTATION('',(#176404),#176407); +#176404 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176405,#176406), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); +#176405 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#176406 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#176407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176408 = ORIENTED_EDGE('',*,*,#176409,.F.); +#176409 = EDGE_CURVE('',#175772,#176383,#176410,.T.); +#176410 = SURFACE_CURVE('',#176411,(#176415,#176422),.PCURVE_S1.); +#176411 = LINE('',#176412,#176413); +#176412 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.75)); +#176413 = VECTOR('',#176414,1.); +#176414 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#176415 = PCURVE('',#175787,#176416); +#176416 = DEFINITIONAL_REPRESENTATION('',(#176417),#176421); +#176417 = LINE('',#176418,#176419); +#176418 = CARTESIAN_POINT('',(0.34,0.E+000)); +#176419 = VECTOR('',#176420,1.); +#176420 = DIRECTION('',(0.E+000,-1.)); +#176421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176422 = PCURVE('',#175813,#176423); +#176423 = DEFINITIONAL_REPRESENTATION('',(#176424),#176428); +#176424 = LINE('',#176425,#176426); +#176425 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#176426 = VECTOR('',#176427,1.); +#176427 = DIRECTION('',(0.E+000,-1.)); +#176428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176429 = ORIENTED_EDGE('',*,*,#175771,.F.); +#176430 = ORIENTED_EDGE('',*,*,#176431,.T.); +#176431 = EDGE_CURVE('',#175744,#176381,#176432,.T.); +#176432 = SURFACE_CURVE('',#176433,(#176437,#176444),.PCURVE_S1.); +#176433 = LINE('',#176434,#176435); +#176434 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.75)); +#176435 = VECTOR('',#176436,1.); +#176436 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#176437 = PCURVE('',#175787,#176438); +#176438 = DEFINITIONAL_REPRESENTATION('',(#176439),#176443); +#176439 = LINE('',#176440,#176441); +#176440 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176441 = VECTOR('',#176442,1.); +#176442 = DIRECTION('',(0.E+000,-1.)); +#176443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176444 = PCURVE('',#175759,#176445); +#176445 = DEFINITIONAL_REPRESENTATION('',(#176446),#176450); +#176446 = LINE('',#176447,#176448); +#176447 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#176448 = VECTOR('',#176449,1.); +#176449 = DIRECTION('',(0.E+000,-1.)); +#176450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176451 = ADVANCED_FACE('',(#176452),#175759,.T.); +#176452 = FACE_BOUND('',#176453,.T.); +#176453 = EDGE_LOOP('',(#176454,#176455,#176456,#176479,#176507,#176539, + #176567,#176595,#176623,#176651,#176679,#176704)); +#176454 = ORIENTED_EDGE('',*,*,#175743,.F.); +#176455 = ORIENTED_EDGE('',*,*,#176356,.F.); +#176456 = ORIENTED_EDGE('',*,*,#176457,.F.); +#176457 = EDGE_CURVE('',#176458,#176330,#176460,.T.); +#176458 = VERTEX_POINT('',#176459); +#176459 = CARTESIAN_POINT('',(0.785,-0.906981201809,0.50752811704)); +#176460 = SURFACE_CURVE('',#176461,(#176466,#176473),.PCURVE_S1.); +#176461 = CIRCLE('',#176462,0.1); +#176462 = AXIS2_PLACEMENT_3D('',#176463,#176464,#176465); +#176463 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); +#176464 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176465 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176466 = PCURVE('',#175759,#176467); +#176467 = DEFINITIONAL_REPRESENTATION('',(#176468),#176472); +#176468 = CIRCLE('',#176469,0.1); +#176469 = AXIS2_PLACEMENT_2D('',#176470,#176471); +#176470 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#176471 = DIRECTION('',(-1.,0.E+000)); +#176472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176473 = PCURVE('',#176345,#176474); +#176474 = DEFINITIONAL_REPRESENTATION('',(#176475),#176478); +#176475 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176476,#176477), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#174084 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#174085 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174087 = ORIENTED_EDGE('',*,*,#174088,.F.); -#174088 = EDGE_CURVE('',#174089,#174066,#174091,.T.); -#174089 = VERTEX_POINT('',#174090); -#174090 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); -#174091 = SURFACE_CURVE('',#174092,(#174096,#174103),.PCURVE_S1.); -#174092 = LINE('',#174093,#174094); -#174093 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); -#174094 = VECTOR('',#174095,1.); -#174095 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#174096 = PCURVE('',#173367,#174097); -#174097 = DEFINITIONAL_REPRESENTATION('',(#174098),#174102); -#174098 = LINE('',#174099,#174100); -#174099 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#174100 = VECTOR('',#174101,1.); -#174101 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#174102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174103 = PCURVE('',#174104,#174109); -#174104 = PLANE('',#174105); -#174105 = AXIS2_PLACEMENT_3D('',#174106,#174107,#174108); -#174106 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); -#174107 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); -#174108 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#174109 = DEFINITIONAL_REPRESENTATION('',(#174110),#174114); -#174110 = LINE('',#174111,#174112); -#174111 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174112 = VECTOR('',#174113,1.); -#174113 = DIRECTION('',(1.,0.E+000)); -#174114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174115 = ORIENTED_EDGE('',*,*,#174116,.F.); -#174116 = EDGE_CURVE('',#174117,#174089,#174119,.T.); -#174117 = VERTEX_POINT('',#174118); -#174118 = CARTESIAN_POINT('',(0.785,-1.1307673058,-5.421010862428E-017) - ); -#174119 = SURFACE_CURVE('',#174120,(#174125,#174136),.PCURVE_S1.); -#174120 = CIRCLE('',#174121,0.2); -#174121 = AXIS2_PLACEMENT_3D('',#174122,#174123,#174124); -#174122 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); -#174123 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174124 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174125 = PCURVE('',#173367,#174126); -#174126 = DEFINITIONAL_REPRESENTATION('',(#174127),#174135); -#174127 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#174128,#174129,#174130, - #174131,#174132,#174133,#174134),.UNSPECIFIED.,.T.,.F.) +#176476 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#176477 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#176478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176479 = ORIENTED_EDGE('',*,*,#176480,.F.); +#176480 = EDGE_CURVE('',#176481,#176458,#176483,.T.); +#176481 = VERTEX_POINT('',#176482); +#176482 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); +#176483 = SURFACE_CURVE('',#176484,(#176488,#176495),.PCURVE_S1.); +#176484 = LINE('',#176485,#176486); +#176485 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); +#176486 = VECTOR('',#176487,1.); +#176487 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#176488 = PCURVE('',#175759,#176489); +#176489 = DEFINITIONAL_REPRESENTATION('',(#176490),#176494); +#176490 = LINE('',#176491,#176492); +#176491 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#176492 = VECTOR('',#176493,1.); +#176493 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#176494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176495 = PCURVE('',#176496,#176501); +#176496 = PLANE('',#176497); +#176497 = AXIS2_PLACEMENT_3D('',#176498,#176499,#176500); +#176498 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); +#176499 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); +#176500 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#176501 = DEFINITIONAL_REPRESENTATION('',(#176502),#176506); +#176502 = LINE('',#176503,#176504); +#176503 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176504 = VECTOR('',#176505,1.); +#176505 = DIRECTION('',(1.,0.E+000)); +#176506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176507 = ORIENTED_EDGE('',*,*,#176508,.F.); +#176508 = EDGE_CURVE('',#176509,#176481,#176511,.T.); +#176509 = VERTEX_POINT('',#176510); +#176510 = CARTESIAN_POINT('',(0.785,-1.1307673058,-5.421010862428E-017) + ); +#176511 = SURFACE_CURVE('',#176512,(#176517,#176528),.PCURVE_S1.); +#176512 = CIRCLE('',#176513,0.2); +#176513 = AXIS2_PLACEMENT_3D('',#176514,#176515,#176516); +#176514 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); +#176515 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176516 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176517 = PCURVE('',#175759,#176518); +#176518 = DEFINITIONAL_REPRESENTATION('',(#176519),#176527); +#176519 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#176520,#176521,#176522, + #176523,#176524,#176525,#176526),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#174128 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#174129 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#174130 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#174131 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#174132 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#174133 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#174134 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#174135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174136 = PCURVE('',#174137,#174142); -#174137 = CYLINDRICAL_SURFACE('',#174138,0.2); -#174138 = AXIS2_PLACEMENT_3D('',#174139,#174140,#174141); -#174139 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); -#174140 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174141 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174142 = DEFINITIONAL_REPRESENTATION('',(#174143),#174146); -#174143 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174144,#174145), +#176520 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#176521 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#176522 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#176523 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#176524 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#176525 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#176526 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#176527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176528 = PCURVE('',#176529,#176534); +#176529 = CYLINDRICAL_SURFACE('',#176530,0.2); +#176530 = AXIS2_PLACEMENT_3D('',#176531,#176532,#176533); +#176531 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); +#176532 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176533 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176534 = DEFINITIONAL_REPRESENTATION('',(#176535),#176538); +#176535 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176536,#176537), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#174144 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174145 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#174146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174147 = ORIENTED_EDGE('',*,*,#174148,.F.); -#174148 = EDGE_CURVE('',#174149,#174117,#174151,.T.); -#174149 = VERTEX_POINT('',#174150); -#174150 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174151 = SURFACE_CURVE('',#174152,(#174156,#174163),.PCURVE_S1.); -#174152 = LINE('',#174153,#174154); -#174153 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174154 = VECTOR('',#174155,1.); -#174155 = DIRECTION('',(0.E+000,1.,0.E+000)); -#174156 = PCURVE('',#173367,#174157); -#174157 = DEFINITIONAL_REPRESENTATION('',(#174158),#174162); -#174158 = LINE('',#174159,#174160); -#174159 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#174160 = VECTOR('',#174161,1.); -#174161 = DIRECTION('',(0.E+000,1.)); -#174162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174163 = PCURVE('',#174164,#174169); -#174164 = PLANE('',#174165); -#174165 = AXIS2_PLACEMENT_3D('',#174166,#174167,#174168); -#174166 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174167 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174168 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#174169 = DEFINITIONAL_REPRESENTATION('',(#174170),#174174); -#174170 = LINE('',#174171,#174172); -#174171 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174172 = VECTOR('',#174173,1.); -#174173 = DIRECTION('',(0.E+000,1.)); -#174174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174175 = ORIENTED_EDGE('',*,*,#174176,.F.); -#174176 = EDGE_CURVE('',#174177,#174149,#174179,.T.); -#174177 = VERTEX_POINT('',#174178); -#174178 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); -#174179 = SURFACE_CURVE('',#174180,(#174184,#174191),.PCURVE_S1.); -#174180 = LINE('',#174181,#174182); -#174181 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174182 = VECTOR('',#174183,1.); -#174183 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174184 = PCURVE('',#173367,#174185); -#174185 = DEFINITIONAL_REPRESENTATION('',(#174186),#174190); -#174186 = LINE('',#174187,#174188); -#174187 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#174188 = VECTOR('',#174189,1.); -#174189 = DIRECTION('',(-1.,0.E+000)); -#174190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174191 = PCURVE('',#174192,#174197); -#174192 = PLANE('',#174193); -#174193 = AXIS2_PLACEMENT_3D('',#174194,#174195,#174196); -#174194 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174195 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174196 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174197 = DEFINITIONAL_REPRESENTATION('',(#174198),#174202); -#174198 = LINE('',#174199,#174200); -#174199 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174200 = VECTOR('',#174201,1.); -#174201 = DIRECTION('',(1.,0.E+000)); -#174202 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174203 = ORIENTED_EDGE('',*,*,#174204,.F.); -#174204 = EDGE_CURVE('',#174205,#174177,#174207,.T.); -#174205 = VERTEX_POINT('',#174206); -#174206 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.15)); -#174207 = SURFACE_CURVE('',#174208,(#174212,#174219),.PCURVE_S1.); -#174208 = LINE('',#174209,#174210); -#174209 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); -#174210 = VECTOR('',#174211,1.); -#174211 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174212 = PCURVE('',#173367,#174213); -#174213 = DEFINITIONAL_REPRESENTATION('',(#174214),#174218); -#174214 = LINE('',#174215,#174216); -#174215 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#174216 = VECTOR('',#174217,1.); -#174217 = DIRECTION('',(0.E+000,-1.)); -#174218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174219 = PCURVE('',#174220,#174225); -#174220 = PLANE('',#174221); -#174221 = AXIS2_PLACEMENT_3D('',#174222,#174223,#174224); -#174222 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); -#174223 = DIRECTION('',(0.E+000,0.E+000,1.)); -#174224 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174225 = DEFINITIONAL_REPRESENTATION('',(#174226),#174230); -#174226 = LINE('',#174227,#174228); -#174227 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174228 = VECTOR('',#174229,1.); -#174229 = DIRECTION('',(0.E+000,-1.)); -#174230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174231 = ORIENTED_EDGE('',*,*,#174232,.F.); -#174232 = EDGE_CURVE('',#174233,#174205,#174235,.T.); -#174233 = VERTEX_POINT('',#174234); -#174234 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); -#174235 = SURFACE_CURVE('',#174236,(#174241,#174248),.PCURVE_S1.); -#174236 = CIRCLE('',#174237,5.E-002); -#174237 = AXIS2_PLACEMENT_3D('',#174238,#174239,#174240); -#174238 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); -#174239 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#174240 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174241 = PCURVE('',#173367,#174242); -#174242 = DEFINITIONAL_REPRESENTATION('',(#174243),#174247); -#174243 = CIRCLE('',#174244,5.E-002); -#174244 = AXIS2_PLACEMENT_2D('',#174245,#174246); -#174245 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#174246 = DIRECTION('',(-1.,0.E+000)); -#174247 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174248 = PCURVE('',#174249,#174254); -#174249 = CYLINDRICAL_SURFACE('',#174250,5.E-002); -#174250 = AXIS2_PLACEMENT_3D('',#174251,#174252,#174253); -#174251 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); -#174252 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174253 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174254 = DEFINITIONAL_REPRESENTATION('',(#174255),#174258); -#174255 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174256,#174257), +#176536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176537 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#176538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176539 = ORIENTED_EDGE('',*,*,#176540,.F.); +#176540 = EDGE_CURVE('',#176541,#176509,#176543,.T.); +#176541 = VERTEX_POINT('',#176542); +#176542 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#176543 = SURFACE_CURVE('',#176544,(#176548,#176555),.PCURVE_S1.); +#176544 = LINE('',#176545,#176546); +#176545 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#176546 = VECTOR('',#176547,1.); +#176547 = DIRECTION('',(0.E+000,1.,0.E+000)); +#176548 = PCURVE('',#175759,#176549); +#176549 = DEFINITIONAL_REPRESENTATION('',(#176550),#176554); +#176550 = LINE('',#176551,#176552); +#176551 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#176552 = VECTOR('',#176553,1.); +#176553 = DIRECTION('',(0.E+000,1.)); +#176554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176555 = PCURVE('',#176556,#176561); +#176556 = PLANE('',#176557); +#176557 = AXIS2_PLACEMENT_3D('',#176558,#176559,#176560); +#176558 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#176559 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176560 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176561 = DEFINITIONAL_REPRESENTATION('',(#176562),#176566); +#176562 = LINE('',#176563,#176564); +#176563 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176564 = VECTOR('',#176565,1.); +#176565 = DIRECTION('',(0.E+000,1.)); +#176566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176567 = ORIENTED_EDGE('',*,*,#176568,.F.); +#176568 = EDGE_CURVE('',#176569,#176541,#176571,.T.); +#176569 = VERTEX_POINT('',#176570); +#176570 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); +#176571 = SURFACE_CURVE('',#176572,(#176576,#176583),.PCURVE_S1.); +#176572 = LINE('',#176573,#176574); +#176573 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#176574 = VECTOR('',#176575,1.); +#176575 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176576 = PCURVE('',#175759,#176577); +#176577 = DEFINITIONAL_REPRESENTATION('',(#176578),#176582); +#176578 = LINE('',#176579,#176580); +#176579 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#176580 = VECTOR('',#176581,1.); +#176581 = DIRECTION('',(-1.,0.E+000)); +#176582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176583 = PCURVE('',#176584,#176589); +#176584 = PLANE('',#176585); +#176585 = AXIS2_PLACEMENT_3D('',#176586,#176587,#176588); +#176586 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#176587 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#176588 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176589 = DEFINITIONAL_REPRESENTATION('',(#176590),#176594); +#176590 = LINE('',#176591,#176592); +#176591 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176592 = VECTOR('',#176593,1.); +#176593 = DIRECTION('',(1.,0.E+000)); +#176594 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176595 = ORIENTED_EDGE('',*,*,#176596,.F.); +#176596 = EDGE_CURVE('',#176597,#176569,#176599,.T.); +#176597 = VERTEX_POINT('',#176598); +#176598 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.15)); +#176599 = SURFACE_CURVE('',#176600,(#176604,#176611),.PCURVE_S1.); +#176600 = LINE('',#176601,#176602); +#176601 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); +#176602 = VECTOR('',#176603,1.); +#176603 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#176604 = PCURVE('',#175759,#176605); +#176605 = DEFINITIONAL_REPRESENTATION('',(#176606),#176610); +#176606 = LINE('',#176607,#176608); +#176607 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#176608 = VECTOR('',#176609,1.); +#176609 = DIRECTION('',(0.E+000,-1.)); +#176610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176611 = PCURVE('',#176612,#176617); +#176612 = PLANE('',#176613); +#176613 = AXIS2_PLACEMENT_3D('',#176614,#176615,#176616); +#176614 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); +#176615 = DIRECTION('',(0.E+000,0.E+000,1.)); +#176616 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176617 = DEFINITIONAL_REPRESENTATION('',(#176618),#176622); +#176618 = LINE('',#176619,#176620); +#176619 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176620 = VECTOR('',#176621,1.); +#176621 = DIRECTION('',(0.E+000,-1.)); +#176622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176623 = ORIENTED_EDGE('',*,*,#176624,.F.); +#176624 = EDGE_CURVE('',#176625,#176597,#176627,.T.); +#176625 = VERTEX_POINT('',#176626); +#176626 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); +#176627 = SURFACE_CURVE('',#176628,(#176633,#176640),.PCURVE_S1.); +#176628 = CIRCLE('',#176629,5.E-002); +#176629 = AXIS2_PLACEMENT_3D('',#176630,#176631,#176632); +#176630 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); +#176631 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176632 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176633 = PCURVE('',#175759,#176634); +#176634 = DEFINITIONAL_REPRESENTATION('',(#176635),#176639); +#176635 = CIRCLE('',#176636,5.E-002); +#176636 = AXIS2_PLACEMENT_2D('',#176637,#176638); +#176637 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#176638 = DIRECTION('',(-1.,0.E+000)); +#176639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176640 = PCURVE('',#176641,#176646); +#176641 = CYLINDRICAL_SURFACE('',#176642,5.E-002); +#176642 = AXIS2_PLACEMENT_3D('',#176643,#176644,#176645); +#176643 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.2)); +#176644 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176645 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176646 = DEFINITIONAL_REPRESENTATION('',(#176647),#176650); +#176647 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176648,#176649), .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#174256 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#174257 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174259 = ORIENTED_EDGE('',*,*,#174260,.F.); -#174260 = EDGE_CURVE('',#174261,#174233,#174263,.T.); -#174261 = VERTEX_POINT('',#174262); -#174262 = CARTESIAN_POINT('',(0.785,-1.056555553792,0.518820292599)); -#174263 = SURFACE_CURVE('',#174264,(#174268,#174275),.PCURVE_S1.); -#174264 = LINE('',#174265,#174266); -#174265 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); -#174266 = VECTOR('',#174267,1.); -#174267 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#174268 = PCURVE('',#173367,#174269); -#174269 = DEFINITIONAL_REPRESENTATION('',(#174270),#174274); -#174270 = LINE('',#174271,#174272); -#174271 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#174272 = VECTOR('',#174273,1.); -#174273 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#174274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174275 = PCURVE('',#174276,#174281); -#174276 = PLANE('',#174277); -#174277 = AXIS2_PLACEMENT_3D('',#174278,#174279,#174280); -#174278 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); -#174279 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); -#174280 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#174281 = DEFINITIONAL_REPRESENTATION('',(#174282),#174286); -#174282 = LINE('',#174283,#174284); -#174283 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174284 = VECTOR('',#174285,1.); -#174285 = DIRECTION('',(1.,0.E+000)); -#174286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174287 = ORIENTED_EDGE('',*,*,#174288,.F.); -#174288 = EDGE_CURVE('',#173989,#174261,#174289,.T.); -#174289 = SURFACE_CURVE('',#174290,(#174295,#174306),.PCURVE_S1.); -#174290 = CIRCLE('',#174291,0.25); -#174291 = AXIS2_PLACEMENT_3D('',#174292,#174293,#174294); -#174292 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); -#174293 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174294 = DIRECTION('',(0.E+000,0.E+000,1.)); -#174295 = PCURVE('',#173367,#174296); -#174296 = DEFINITIONAL_REPRESENTATION('',(#174297),#174305); -#174297 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#174298,#174299,#174300, - #174301,#174302,#174303,#174304),.UNSPECIFIED.,.F.,.F.) +#176648 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#176649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176651 = ORIENTED_EDGE('',*,*,#176652,.F.); +#176652 = EDGE_CURVE('',#176653,#176625,#176655,.T.); +#176653 = VERTEX_POINT('',#176654); +#176654 = CARTESIAN_POINT('',(0.785,-1.056555553792,0.518820292599)); +#176655 = SURFACE_CURVE('',#176656,(#176660,#176667),.PCURVE_S1.); +#176656 = LINE('',#176657,#176658); +#176657 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); +#176658 = VECTOR('',#176659,1.); +#176659 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#176660 = PCURVE('',#175759,#176661); +#176661 = DEFINITIONAL_REPRESENTATION('',(#176662),#176666); +#176662 = LINE('',#176663,#176664); +#176663 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#176664 = VECTOR('',#176665,1.); +#176665 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#176666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176667 = PCURVE('',#176668,#176673); +#176668 = PLANE('',#176669); +#176669 = AXIS2_PLACEMENT_3D('',#176670,#176671,#176672); +#176670 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); +#176671 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); +#176672 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#176673 = DEFINITIONAL_REPRESENTATION('',(#176674),#176678); +#176674 = LINE('',#176675,#176676); +#176675 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176676 = VECTOR('',#176677,1.); +#176677 = DIRECTION('',(1.,0.E+000)); +#176678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176679 = ORIENTED_EDGE('',*,*,#176680,.F.); +#176680 = EDGE_CURVE('',#176381,#176653,#176681,.T.); +#176681 = SURFACE_CURVE('',#176682,(#176687,#176698),.PCURVE_S1.); +#176682 = CIRCLE('',#176683,0.25); +#176683 = AXIS2_PLACEMENT_3D('',#176684,#176685,#176686); +#176684 = CARTESIAN_POINT('',(0.785,-0.807264967154,0.5)); +#176685 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176686 = DIRECTION('',(0.E+000,0.E+000,1.)); +#176687 = PCURVE('',#175759,#176688); +#176688 = DEFINITIONAL_REPRESENTATION('',(#176689),#176697); +#176689 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#176690,#176691,#176692, + #176693,#176694,#176695,#176696),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#174298 = CARTESIAN_POINT('',(0.25,0.E+000)); -#174299 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#174300 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#174301 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#174302 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#174303 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#174304 = CARTESIAN_POINT('',(0.25,0.E+000)); -#174305 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174306 = PCURVE('',#174006,#174307); -#174307 = DEFINITIONAL_REPRESENTATION('',(#174308),#174311); -#174308 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174309,#174310), +#176690 = CARTESIAN_POINT('',(0.25,0.E+000)); +#176691 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#176692 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#176693 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#176694 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#176695 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#176696 = CARTESIAN_POINT('',(0.25,0.E+000)); +#176697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176698 = PCURVE('',#176398,#176699); +#176699 = DEFINITIONAL_REPRESENTATION('',(#176700),#176703); +#176700 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176701,#176702), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#174309 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174310 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#174311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174312 = ORIENTED_EDGE('',*,*,#174039,.F.); -#174313 = ADVANCED_FACE('',(#174314),#173421,.F.); -#174314 = FACE_BOUND('',#174315,.T.); -#174315 = EDGE_LOOP('',(#174316,#174317,#174318,#174319,#174346,#174369, - #174392,#174415,#174438,#174461,#174488,#174511)); -#174316 = ORIENTED_EDGE('',*,*,#173914,.T.); -#174317 = ORIENTED_EDGE('',*,*,#173407,.T.); -#174318 = ORIENTED_EDGE('',*,*,#174017,.T.); -#174319 = ORIENTED_EDGE('',*,*,#174320,.T.); -#174320 = EDGE_CURVE('',#173991,#174321,#174323,.T.); -#174321 = VERTEX_POINT('',#174322); -#174322 = CARTESIAN_POINT('',(1.125,-1.056555553792,0.518820292599)); -#174323 = SURFACE_CURVE('',#174324,(#174329,#174340),.PCURVE_S1.); -#174324 = CIRCLE('',#174325,0.25); -#174325 = AXIS2_PLACEMENT_3D('',#174326,#174327,#174328); -#174326 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); -#174327 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174328 = DIRECTION('',(0.E+000,0.E+000,1.)); -#174329 = PCURVE('',#173421,#174330); -#174330 = DEFINITIONAL_REPRESENTATION('',(#174331),#174339); -#174331 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#174332,#174333,#174334, - #174335,#174336,#174337,#174338),.UNSPECIFIED.,.F.,.F.) +#176701 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#176702 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#176703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176704 = ORIENTED_EDGE('',*,*,#176431,.F.); +#176705 = ADVANCED_FACE('',(#176706),#175813,.F.); +#176706 = FACE_BOUND('',#176707,.T.); +#176707 = EDGE_LOOP('',(#176708,#176709,#176710,#176711,#176738,#176761, + #176784,#176807,#176830,#176853,#176880,#176903)); +#176708 = ORIENTED_EDGE('',*,*,#176306,.T.); +#176709 = ORIENTED_EDGE('',*,*,#175799,.T.); +#176710 = ORIENTED_EDGE('',*,*,#176409,.T.); +#176711 = ORIENTED_EDGE('',*,*,#176712,.T.); +#176712 = EDGE_CURVE('',#176383,#176713,#176715,.T.); +#176713 = VERTEX_POINT('',#176714); +#176714 = CARTESIAN_POINT('',(1.125,-1.056555553792,0.518820292599)); +#176715 = SURFACE_CURVE('',#176716,(#176721,#176732),.PCURVE_S1.); +#176716 = CIRCLE('',#176717,0.25); +#176717 = AXIS2_PLACEMENT_3D('',#176718,#176719,#176720); +#176718 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); +#176719 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176720 = DIRECTION('',(0.E+000,0.E+000,1.)); +#176721 = PCURVE('',#175813,#176722); +#176722 = DEFINITIONAL_REPRESENTATION('',(#176723),#176731); +#176723 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#176724,#176725,#176726, + #176727,#176728,#176729,#176730),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#174332 = CARTESIAN_POINT('',(0.25,0.E+000)); -#174333 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#174334 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#174335 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#174336 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#174337 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#174338 = CARTESIAN_POINT('',(0.25,0.E+000)); -#174339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174340 = PCURVE('',#174006,#174341); -#174341 = DEFINITIONAL_REPRESENTATION('',(#174342),#174345); -#174342 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174343,#174344), +#176724 = CARTESIAN_POINT('',(0.25,0.E+000)); +#176725 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#176726 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#176727 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#176728 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#176729 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#176730 = CARTESIAN_POINT('',(0.25,0.E+000)); +#176731 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176732 = PCURVE('',#176398,#176733); +#176733 = DEFINITIONAL_REPRESENTATION('',(#176734),#176737); +#176734 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176735,#176736), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#174343 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#174344 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#174345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174346 = ORIENTED_EDGE('',*,*,#174347,.T.); -#174347 = EDGE_CURVE('',#174321,#174348,#174350,.T.); -#174348 = VERTEX_POINT('',#174349); -#174349 = CARTESIAN_POINT('',(1.125,-1.080909188472,0.19623594148)); -#174350 = SURFACE_CURVE('',#174351,(#174355,#174362),.PCURVE_S1.); -#174351 = LINE('',#174352,#174353); -#174352 = CARTESIAN_POINT('',(1.125,-1.080909188472,0.19623594148)); -#174353 = VECTOR('',#174354,1.); -#174354 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#174355 = PCURVE('',#173421,#174356); -#174356 = DEFINITIONAL_REPRESENTATION('',(#174357),#174361); -#174357 = LINE('',#174358,#174359); -#174358 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#174359 = VECTOR('',#174360,1.); -#174360 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#174361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174362 = PCURVE('',#174276,#174363); -#174363 = DEFINITIONAL_REPRESENTATION('',(#174364),#174368); -#174364 = LINE('',#174365,#174366); -#174365 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174366 = VECTOR('',#174367,1.); -#174367 = DIRECTION('',(1.,0.E+000)); -#174368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174369 = ORIENTED_EDGE('',*,*,#174370,.T.); -#174370 = EDGE_CURVE('',#174348,#174371,#174373,.T.); -#174371 = VERTEX_POINT('',#174372); -#174372 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.15)); -#174373 = SURFACE_CURVE('',#174374,(#174379,#174386),.PCURVE_S1.); -#174374 = CIRCLE('',#174375,5.E-002); -#174375 = AXIS2_PLACEMENT_3D('',#174376,#174377,#174378); -#174376 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.2)); -#174377 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#174378 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174379 = PCURVE('',#173421,#174380); -#174380 = DEFINITIONAL_REPRESENTATION('',(#174381),#174385); -#174381 = CIRCLE('',#174382,5.E-002); -#174382 = AXIS2_PLACEMENT_2D('',#174383,#174384); -#174383 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#174384 = DIRECTION('',(-1.,0.E+000)); -#174385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174386 = PCURVE('',#174249,#174387); -#174387 = DEFINITIONAL_REPRESENTATION('',(#174388),#174391); -#174388 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174389,#174390), +#176735 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#176736 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#176737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176738 = ORIENTED_EDGE('',*,*,#176739,.T.); +#176739 = EDGE_CURVE('',#176713,#176740,#176742,.T.); +#176740 = VERTEX_POINT('',#176741); +#176741 = CARTESIAN_POINT('',(1.125,-1.080909188472,0.19623594148)); +#176742 = SURFACE_CURVE('',#176743,(#176747,#176754),.PCURVE_S1.); +#176743 = LINE('',#176744,#176745); +#176744 = CARTESIAN_POINT('',(1.125,-1.080909188472,0.19623594148)); +#176745 = VECTOR('',#176746,1.); +#176746 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#176747 = PCURVE('',#175813,#176748); +#176748 = DEFINITIONAL_REPRESENTATION('',(#176749),#176753); +#176749 = LINE('',#176750,#176751); +#176750 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#176751 = VECTOR('',#176752,1.); +#176752 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#176753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176754 = PCURVE('',#176668,#176755); +#176755 = DEFINITIONAL_REPRESENTATION('',(#176756),#176760); +#176756 = LINE('',#176757,#176758); +#176757 = CARTESIAN_POINT('',(0.E+000,0.34)); +#176758 = VECTOR('',#176759,1.); +#176759 = DIRECTION('',(1.,0.E+000)); +#176760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176761 = ORIENTED_EDGE('',*,*,#176762,.T.); +#176762 = EDGE_CURVE('',#176740,#176763,#176765,.T.); +#176763 = VERTEX_POINT('',#176764); +#176764 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.15)); +#176765 = SURFACE_CURVE('',#176766,(#176771,#176778),.PCURVE_S1.); +#176766 = CIRCLE('',#176767,5.E-002); +#176767 = AXIS2_PLACEMENT_3D('',#176768,#176769,#176770); +#176768 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.2)); +#176769 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176770 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176771 = PCURVE('',#175813,#176772); +#176772 = DEFINITIONAL_REPRESENTATION('',(#176773),#176777); +#176773 = CIRCLE('',#176774,5.E-002); +#176774 = AXIS2_PLACEMENT_2D('',#176775,#176776); +#176775 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#176776 = DIRECTION('',(-1.,0.E+000)); +#176777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176778 = PCURVE('',#176641,#176779); +#176779 = DEFINITIONAL_REPRESENTATION('',(#176780),#176783); +#176780 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176781,#176782), .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#174389 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#174390 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#176781 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#176782 = CARTESIAN_POINT('',(0.E+000,0.34)); +#176783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176784 = ORIENTED_EDGE('',*,*,#176785,.T.); +#176785 = EDGE_CURVE('',#176763,#176786,#176788,.T.); +#176786 = VERTEX_POINT('',#176787); +#176787 = CARTESIAN_POINT('',(1.125,-1.4,0.15)); +#176788 = SURFACE_CURVE('',#176789,(#176793,#176800),.PCURVE_S1.); +#176789 = LINE('',#176790,#176791); +#176790 = CARTESIAN_POINT('',(1.125,-1.4,0.15)); +#176791 = VECTOR('',#176792,1.); +#176792 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#176793 = PCURVE('',#175813,#176794); +#176794 = DEFINITIONAL_REPRESENTATION('',(#176795),#176799); +#176795 = LINE('',#176796,#176797); +#176796 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#176797 = VECTOR('',#176798,1.); +#176798 = DIRECTION('',(0.E+000,-1.)); +#176799 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176800 = PCURVE('',#176612,#176801); +#176801 = DEFINITIONAL_REPRESENTATION('',(#176802),#176806); +#176802 = LINE('',#176803,#176804); +#176803 = CARTESIAN_POINT('',(0.34,0.E+000)); +#176804 = VECTOR('',#176805,1.); +#176805 = DIRECTION('',(0.E+000,-1.)); +#176806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176807 = ORIENTED_EDGE('',*,*,#176808,.T.); +#176808 = EDGE_CURVE('',#176786,#176809,#176811,.T.); +#176809 = VERTEX_POINT('',#176810); +#176810 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); +#176811 = SURFACE_CURVE('',#176812,(#176816,#176823),.PCURVE_S1.); +#176812 = LINE('',#176813,#176814); +#176813 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); +#176814 = VECTOR('',#176815,1.); +#176815 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176816 = PCURVE('',#175813,#176817); +#176817 = DEFINITIONAL_REPRESENTATION('',(#176818),#176822); +#176818 = LINE('',#176819,#176820); +#176819 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#176820 = VECTOR('',#176821,1.); +#176821 = DIRECTION('',(-1.,0.E+000)); +#176822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176823 = PCURVE('',#176584,#176824); +#176824 = DEFINITIONAL_REPRESENTATION('',(#176825),#176829); +#176825 = LINE('',#176826,#176827); +#176826 = CARTESIAN_POINT('',(0.E+000,0.34)); +#176827 = VECTOR('',#176828,1.); +#176828 = DIRECTION('',(1.,0.E+000)); +#176829 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176830 = ORIENTED_EDGE('',*,*,#176831,.T.); +#176831 = EDGE_CURVE('',#176809,#176832,#176834,.T.); +#176832 = VERTEX_POINT('',#176833); +#176833 = CARTESIAN_POINT('',(1.125,-1.1307673058,-5.421010862428E-017) + ); +#176834 = SURFACE_CURVE('',#176835,(#176839,#176846),.PCURVE_S1.); +#176835 = LINE('',#176836,#176837); +#176836 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); +#176837 = VECTOR('',#176838,1.); +#176838 = DIRECTION('',(0.E+000,1.,0.E+000)); +#176839 = PCURVE('',#175813,#176840); +#176840 = DEFINITIONAL_REPRESENTATION('',(#176841),#176845); +#176841 = LINE('',#176842,#176843); +#176842 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#176843 = VECTOR('',#176844,1.); +#176844 = DIRECTION('',(0.E+000,1.)); +#176845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#174392 = ORIENTED_EDGE('',*,*,#174393,.T.); -#174393 = EDGE_CURVE('',#174371,#174394,#174396,.T.); -#174394 = VERTEX_POINT('',#174395); -#174395 = CARTESIAN_POINT('',(1.125,-1.4,0.15)); -#174396 = SURFACE_CURVE('',#174397,(#174401,#174408),.PCURVE_S1.); -#174397 = LINE('',#174398,#174399); -#174398 = CARTESIAN_POINT('',(1.125,-1.4,0.15)); -#174399 = VECTOR('',#174400,1.); -#174400 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174401 = PCURVE('',#173421,#174402); -#174402 = DEFINITIONAL_REPRESENTATION('',(#174403),#174407); -#174403 = LINE('',#174404,#174405); -#174404 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#174405 = VECTOR('',#174406,1.); -#174406 = DIRECTION('',(0.E+000,-1.)); -#174407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174408 = PCURVE('',#174220,#174409); -#174409 = DEFINITIONAL_REPRESENTATION('',(#174410),#174414); -#174410 = LINE('',#174411,#174412); -#174411 = CARTESIAN_POINT('',(0.34,0.E+000)); -#174412 = VECTOR('',#174413,1.); -#174413 = DIRECTION('',(0.E+000,-1.)); -#174414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174415 = ORIENTED_EDGE('',*,*,#174416,.T.); -#174416 = EDGE_CURVE('',#174394,#174417,#174419,.T.); -#174417 = VERTEX_POINT('',#174418); -#174418 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); -#174419 = SURFACE_CURVE('',#174420,(#174424,#174431),.PCURVE_S1.); -#174420 = LINE('',#174421,#174422); -#174421 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); -#174422 = VECTOR('',#174423,1.); -#174423 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174424 = PCURVE('',#173421,#174425); -#174425 = DEFINITIONAL_REPRESENTATION('',(#174426),#174430); -#174426 = LINE('',#174427,#174428); -#174427 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#174428 = VECTOR('',#174429,1.); -#174429 = DIRECTION('',(-1.,0.E+000)); -#174430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174431 = PCURVE('',#174192,#174432); -#174432 = DEFINITIONAL_REPRESENTATION('',(#174433),#174437); -#174433 = LINE('',#174434,#174435); -#174434 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174435 = VECTOR('',#174436,1.); -#174436 = DIRECTION('',(1.,0.E+000)); -#174437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174438 = ORIENTED_EDGE('',*,*,#174439,.T.); -#174439 = EDGE_CURVE('',#174417,#174440,#174442,.T.); -#174440 = VERTEX_POINT('',#174441); -#174441 = CARTESIAN_POINT('',(1.125,-1.1307673058,-5.421010862428E-017) - ); -#174442 = SURFACE_CURVE('',#174443,(#174447,#174454),.PCURVE_S1.); -#174443 = LINE('',#174444,#174445); -#174444 = CARTESIAN_POINT('',(1.125,-1.4,0.E+000)); -#174445 = VECTOR('',#174446,1.); -#174446 = DIRECTION('',(0.E+000,1.,0.E+000)); -#174447 = PCURVE('',#173421,#174448); -#174448 = DEFINITIONAL_REPRESENTATION('',(#174449),#174453); -#174449 = LINE('',#174450,#174451); -#174450 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#174451 = VECTOR('',#174452,1.); -#174452 = DIRECTION('',(0.E+000,1.)); -#174453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174454 = PCURVE('',#174164,#174455); -#174455 = DEFINITIONAL_REPRESENTATION('',(#174456),#174460); -#174456 = LINE('',#174457,#174458); -#174457 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#174458 = VECTOR('',#174459,1.); -#174459 = DIRECTION('',(0.E+000,1.)); -#174460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174461 = ORIENTED_EDGE('',*,*,#174462,.T.); -#174462 = EDGE_CURVE('',#174440,#174463,#174465,.T.); -#174463 = VERTEX_POINT('',#174464); -#174464 = CARTESIAN_POINT('',(1.125,-0.931334836489,0.184943765921)); -#174465 = SURFACE_CURVE('',#174466,(#174471,#174482),.PCURVE_S1.); -#174466 = CIRCLE('',#174467,0.2); -#174467 = AXIS2_PLACEMENT_3D('',#174468,#174469,#174470); -#174468 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.2)); -#174469 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174470 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174471 = PCURVE('',#173421,#174472); -#174472 = DEFINITIONAL_REPRESENTATION('',(#174473),#174481); -#174473 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#174474,#174475,#174476, - #174477,#174478,#174479,#174480),.UNSPECIFIED.,.T.,.F.) +#176846 = PCURVE('',#176556,#176847); +#176847 = DEFINITIONAL_REPRESENTATION('',(#176848),#176852); +#176848 = LINE('',#176849,#176850); +#176849 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#176850 = VECTOR('',#176851,1.); +#176851 = DIRECTION('',(0.E+000,1.)); +#176852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176853 = ORIENTED_EDGE('',*,*,#176854,.T.); +#176854 = EDGE_CURVE('',#176832,#176855,#176857,.T.); +#176855 = VERTEX_POINT('',#176856); +#176856 = CARTESIAN_POINT('',(1.125,-0.931334836489,0.184943765921)); +#176857 = SURFACE_CURVE('',#176858,(#176863,#176874),.PCURVE_S1.); +#176858 = CIRCLE('',#176859,0.2); +#176859 = AXIS2_PLACEMENT_3D('',#176860,#176861,#176862); +#176860 = CARTESIAN_POINT('',(1.125,-1.1307673058,0.2)); +#176861 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176862 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176863 = PCURVE('',#175813,#176864); +#176864 = DEFINITIONAL_REPRESENTATION('',(#176865),#176873); +#176865 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#176866,#176867,#176868, + #176869,#176870,#176871,#176872),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#174474 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#174475 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#174476 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#174477 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#174478 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#174479 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#174480 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#174481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174482 = PCURVE('',#174137,#174483); -#174483 = DEFINITIONAL_REPRESENTATION('',(#174484),#174487); -#174484 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174485,#174486), +#176866 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#176867 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#176868 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#176869 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#176870 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#176871 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#176872 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#176873 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176874 = PCURVE('',#176529,#176875); +#176875 = DEFINITIONAL_REPRESENTATION('',(#176876),#176879); +#176876 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176877,#176878), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#174485 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174486 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#174487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174488 = ORIENTED_EDGE('',*,*,#174489,.T.); -#174489 = EDGE_CURVE('',#174463,#174490,#174492,.T.); -#174490 = VERTEX_POINT('',#174491); -#174491 = CARTESIAN_POINT('',(1.125,-0.906981201809,0.50752811704)); -#174492 = SURFACE_CURVE('',#174493,(#174497,#174504),.PCURVE_S1.); -#174493 = LINE('',#174494,#174495); -#174494 = CARTESIAN_POINT('',(1.125,-0.931334836489,0.184943765921)); -#174495 = VECTOR('',#174496,1.); -#174496 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#174497 = PCURVE('',#173421,#174498); -#174498 = DEFINITIONAL_REPRESENTATION('',(#174499),#174503); -#174499 = LINE('',#174500,#174501); -#174500 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#174501 = VECTOR('',#174502,1.); -#174502 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#174503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174504 = PCURVE('',#174104,#174505); -#174505 = DEFINITIONAL_REPRESENTATION('',(#174506),#174510); -#174506 = LINE('',#174507,#174508); -#174507 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174508 = VECTOR('',#174509,1.); -#174509 = DIRECTION('',(1.,0.E+000)); -#174510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174511 = ORIENTED_EDGE('',*,*,#174512,.T.); -#174512 = EDGE_CURVE('',#174490,#173915,#174513,.T.); -#174513 = SURFACE_CURVE('',#174514,(#174519,#174526),.PCURVE_S1.); -#174514 = CIRCLE('',#174515,0.1); -#174515 = AXIS2_PLACEMENT_3D('',#174516,#174517,#174518); -#174516 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); -#174517 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#174518 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174519 = PCURVE('',#173421,#174520); -#174520 = DEFINITIONAL_REPRESENTATION('',(#174521),#174525); -#174521 = CIRCLE('',#174522,0.1); -#174522 = AXIS2_PLACEMENT_2D('',#174523,#174524); -#174523 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#174524 = DIRECTION('',(-1.,0.E+000)); -#174525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174526 = PCURVE('',#173953,#174527); -#174527 = DEFINITIONAL_REPRESENTATION('',(#174528),#174531); -#174528 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174529,#174530), +#176877 = CARTESIAN_POINT('',(0.E+000,0.34)); +#176878 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#176879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176880 = ORIENTED_EDGE('',*,*,#176881,.T.); +#176881 = EDGE_CURVE('',#176855,#176882,#176884,.T.); +#176882 = VERTEX_POINT('',#176883); +#176883 = CARTESIAN_POINT('',(1.125,-0.906981201809,0.50752811704)); +#176884 = SURFACE_CURVE('',#176885,(#176889,#176896),.PCURVE_S1.); +#176885 = LINE('',#176886,#176887); +#176886 = CARTESIAN_POINT('',(1.125,-0.931334836489,0.184943765921)); +#176887 = VECTOR('',#176888,1.); +#176888 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#176889 = PCURVE('',#175813,#176890); +#176890 = DEFINITIONAL_REPRESENTATION('',(#176891),#176895); +#176891 = LINE('',#176892,#176893); +#176892 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#176893 = VECTOR('',#176894,1.); +#176894 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#176895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176896 = PCURVE('',#176496,#176897); +#176897 = DEFINITIONAL_REPRESENTATION('',(#176898),#176902); +#176898 = LINE('',#176899,#176900); +#176899 = CARTESIAN_POINT('',(0.E+000,0.34)); +#176900 = VECTOR('',#176901,1.); +#176901 = DIRECTION('',(1.,0.E+000)); +#176902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176903 = ORIENTED_EDGE('',*,*,#176904,.T.); +#176904 = EDGE_CURVE('',#176882,#176307,#176905,.T.); +#176905 = SURFACE_CURVE('',#176906,(#176911,#176918),.PCURVE_S1.); +#176906 = CIRCLE('',#176907,0.1); +#176907 = AXIS2_PLACEMENT_3D('',#176908,#176909,#176910); +#176908 = CARTESIAN_POINT('',(1.125,-0.807264967154,0.5)); +#176909 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#176910 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#176911 = PCURVE('',#175813,#176912); +#176912 = DEFINITIONAL_REPRESENTATION('',(#176913),#176917); +#176913 = CIRCLE('',#176914,0.1); +#176914 = AXIS2_PLACEMENT_2D('',#176915,#176916); +#176915 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#176916 = DIRECTION('',(-1.,0.E+000)); +#176917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176918 = PCURVE('',#176345,#176919); +#176919 = DEFINITIONAL_REPRESENTATION('',(#176920),#176923); +#176920 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176921,#176922), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#174529 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#174530 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#174531 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174532 = ADVANCED_FACE('',(#174533),#173953,.F.); -#174533 = FACE_BOUND('',#174534,.F.); -#174534 = EDGE_LOOP('',(#174535,#174536,#174537,#174557)); -#174535 = ORIENTED_EDGE('',*,*,#173937,.F.); -#174536 = ORIENTED_EDGE('',*,*,#174065,.F.); -#174537 = ORIENTED_EDGE('',*,*,#174538,.T.); -#174538 = EDGE_CURVE('',#174066,#174490,#174539,.T.); -#174539 = SURFACE_CURVE('',#174540,(#174544,#174550),.PCURVE_S1.); -#174540 = LINE('',#174541,#174542); -#174541 = CARTESIAN_POINT('',(0.785,-0.906981201809,0.50752811704)); -#174542 = VECTOR('',#174543,1.); -#174543 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174544 = PCURVE('',#173953,#174545); -#174545 = DEFINITIONAL_REPRESENTATION('',(#174546),#174549); -#174546 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174547,#174548), +#176921 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#176922 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#176923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176924 = ADVANCED_FACE('',(#176925),#176345,.F.); +#176925 = FACE_BOUND('',#176926,.F.); +#176926 = EDGE_LOOP('',(#176927,#176928,#176929,#176949)); +#176927 = ORIENTED_EDGE('',*,*,#176329,.F.); +#176928 = ORIENTED_EDGE('',*,*,#176457,.F.); +#176929 = ORIENTED_EDGE('',*,*,#176930,.T.); +#176930 = EDGE_CURVE('',#176458,#176882,#176931,.T.); +#176931 = SURFACE_CURVE('',#176932,(#176936,#176942),.PCURVE_S1.); +#176932 = LINE('',#176933,#176934); +#176933 = CARTESIAN_POINT('',(0.785,-0.906981201809,0.50752811704)); +#176934 = VECTOR('',#176935,1.); +#176935 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176936 = PCURVE('',#176345,#176937); +#176937 = DEFINITIONAL_REPRESENTATION('',(#176938),#176941); +#176938 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176939,#176940), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174547 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#174548 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#174549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174550 = PCURVE('',#174104,#174551); -#174551 = DEFINITIONAL_REPRESENTATION('',(#174552),#174556); -#174552 = LINE('',#174553,#174554); -#174553 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#174554 = VECTOR('',#174555,1.); -#174555 = DIRECTION('',(0.E+000,1.)); -#174556 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174557 = ORIENTED_EDGE('',*,*,#174512,.T.); -#174558 = ADVANCED_FACE('',(#174559),#174104,.T.); -#174559 = FACE_BOUND('',#174560,.T.); -#174560 = EDGE_LOOP('',(#174561,#174562,#174563,#174583)); -#174561 = ORIENTED_EDGE('',*,*,#174538,.T.); -#174562 = ORIENTED_EDGE('',*,*,#174489,.F.); -#174563 = ORIENTED_EDGE('',*,*,#174564,.F.); -#174564 = EDGE_CURVE('',#174089,#174463,#174565,.T.); -#174565 = SURFACE_CURVE('',#174566,(#174570,#174577),.PCURVE_S1.); -#174566 = LINE('',#174567,#174568); -#174567 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); -#174568 = VECTOR('',#174569,1.); -#174569 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174570 = PCURVE('',#174104,#174571); -#174571 = DEFINITIONAL_REPRESENTATION('',(#174572),#174576); -#174572 = LINE('',#174573,#174574); -#174573 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174574 = VECTOR('',#174575,1.); -#174575 = DIRECTION('',(0.E+000,1.)); -#174576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174577 = PCURVE('',#174137,#174578); -#174578 = DEFINITIONAL_REPRESENTATION('',(#174579),#174582); -#174579 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174580,#174581), +#176939 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#176940 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#176941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176942 = PCURVE('',#176496,#176943); +#176943 = DEFINITIONAL_REPRESENTATION('',(#176944),#176948); +#176944 = LINE('',#176945,#176946); +#176945 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#176946 = VECTOR('',#176947,1.); +#176947 = DIRECTION('',(0.E+000,1.)); +#176948 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176949 = ORIENTED_EDGE('',*,*,#176904,.T.); +#176950 = ADVANCED_FACE('',(#176951),#176496,.T.); +#176951 = FACE_BOUND('',#176952,.T.); +#176952 = EDGE_LOOP('',(#176953,#176954,#176955,#176975)); +#176953 = ORIENTED_EDGE('',*,*,#176930,.T.); +#176954 = ORIENTED_EDGE('',*,*,#176881,.F.); +#176955 = ORIENTED_EDGE('',*,*,#176956,.F.); +#176956 = EDGE_CURVE('',#176481,#176855,#176957,.T.); +#176957 = SURFACE_CURVE('',#176958,(#176962,#176969),.PCURVE_S1.); +#176958 = LINE('',#176959,#176960); +#176959 = CARTESIAN_POINT('',(0.785,-0.931334836489,0.184943765921)); +#176960 = VECTOR('',#176961,1.); +#176961 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176962 = PCURVE('',#176496,#176963); +#176963 = DEFINITIONAL_REPRESENTATION('',(#176964),#176968); +#176964 = LINE('',#176965,#176966); +#176965 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176966 = VECTOR('',#176967,1.); +#176967 = DIRECTION('',(0.E+000,1.)); +#176968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176969 = PCURVE('',#176529,#176970); +#176970 = DEFINITIONAL_REPRESENTATION('',(#176971),#176974); +#176971 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176972,#176973), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174580 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#174581 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#174582 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174583 = ORIENTED_EDGE('',*,*,#174088,.T.); -#174584 = ADVANCED_FACE('',(#174585),#174137,.T.); -#174585 = FACE_BOUND('',#174586,.T.); -#174586 = EDGE_LOOP('',(#174587,#174588,#174589,#174632)); -#174587 = ORIENTED_EDGE('',*,*,#174564,.T.); -#174588 = ORIENTED_EDGE('',*,*,#174462,.F.); -#174589 = ORIENTED_EDGE('',*,*,#174590,.F.); -#174590 = EDGE_CURVE('',#174117,#174440,#174591,.T.); -#174591 = SURFACE_CURVE('',#174592,(#174596,#174625),.PCURVE_S1.); -#174592 = LINE('',#174593,#174594); -#174593 = CARTESIAN_POINT('',(0.785,-1.1307673058,-5.421010862428E-017) - ); -#174594 = VECTOR('',#174595,1.); -#174595 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174596 = PCURVE('',#174137,#174597); -#174597 = DEFINITIONAL_REPRESENTATION('',(#174598),#174624); -#174598 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174599,#174600,#174601, - #174602,#174603,#174604,#174605,#174606,#174607,#174608,#174609, - #174610,#174611,#174612,#174613,#174614,#174615,#174616,#174617, - #174618,#174619,#174620,#174621,#174622,#174623),.UNSPECIFIED.,.F., +#176972 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#176973 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#176974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#176975 = ORIENTED_EDGE('',*,*,#176480,.T.); +#176976 = ADVANCED_FACE('',(#176977),#176529,.T.); +#176977 = FACE_BOUND('',#176978,.T.); +#176978 = EDGE_LOOP('',(#176979,#176980,#176981,#177024)); +#176979 = ORIENTED_EDGE('',*,*,#176956,.T.); +#176980 = ORIENTED_EDGE('',*,*,#176854,.F.); +#176981 = ORIENTED_EDGE('',*,*,#176982,.F.); +#176982 = EDGE_CURVE('',#176509,#176832,#176983,.T.); +#176983 = SURFACE_CURVE('',#176984,(#176988,#177017),.PCURVE_S1.); +#176984 = LINE('',#176985,#176986); +#176985 = CARTESIAN_POINT('',(0.785,-1.1307673058,-5.421010862428E-017) + ); +#176986 = VECTOR('',#176987,1.); +#176987 = DIRECTION('',(1.,0.E+000,0.E+000)); +#176988 = PCURVE('',#176529,#176989); +#176989 = DEFINITIONAL_REPRESENTATION('',(#176990),#177016); +#176990 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176991,#176992,#176993, + #176994,#176995,#176996,#176997,#176998,#176999,#177000,#177001, + #177002,#177003,#177004,#177005,#177006,#177007,#177008,#177009, + #177010,#177011,#177012,#177013,#177014,#177015),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -216103,140 +219105,140 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#174599 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174600 = CARTESIAN_POINT('',(-4.440892098501E-015,5.151515151515E-003) - ); -#174601 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) - ); -#174602 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) - ); -#174603 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) - ); -#174604 = CARTESIAN_POINT('',(-7.105427357601E-015,6.181818181818E-002) - ); -#174605 = CARTESIAN_POINT('',(-7.105427357601E-015,7.727272727273E-002) - ); -#174606 = CARTESIAN_POINT('',(-6.217248937901E-015,9.272727272727E-002) - ); -#174607 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); -#174608 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); -#174609 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); -#174610 = CARTESIAN_POINT('',(-6.217248937901E-015,0.154545454545)); -#174611 = CARTESIAN_POINT('',(-7.993605777301E-015,0.17)); -#174612 = CARTESIAN_POINT('',(-7.993605777301E-015,0.185454545455)); -#174613 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); -#174614 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); -#174615 = CARTESIAN_POINT('',(-7.105427357601E-015,0.231818181818)); -#174616 = CARTESIAN_POINT('',(-8.881784197001E-015,0.247272727273)); -#174617 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); -#174618 = CARTESIAN_POINT('',(-7.993605777301E-015,0.278181818182)); -#174619 = CARTESIAN_POINT('',(-5.329070518201E-015,0.293636363636)); -#174620 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#174621 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); -#174622 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); -#174623 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174625 = PCURVE('',#174164,#174626); -#174626 = DEFINITIONAL_REPRESENTATION('',(#174627),#174631); -#174627 = LINE('',#174628,#174629); -#174628 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#174629 = VECTOR('',#174630,1.); -#174630 = DIRECTION('',(-1.,0.E+000)); -#174631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174632 = ORIENTED_EDGE('',*,*,#174116,.T.); -#174633 = ADVANCED_FACE('',(#174634),#174164,.T.); -#174634 = FACE_BOUND('',#174635,.T.); -#174635 = EDGE_LOOP('',(#174636,#174637,#174638,#174659)); -#174636 = ORIENTED_EDGE('',*,*,#174590,.T.); -#174637 = ORIENTED_EDGE('',*,*,#174439,.F.); -#174638 = ORIENTED_EDGE('',*,*,#174639,.F.); -#174639 = EDGE_CURVE('',#174149,#174417,#174640,.T.); -#174640 = SURFACE_CURVE('',#174641,(#174645,#174652),.PCURVE_S1.); -#174641 = LINE('',#174642,#174643); -#174642 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); -#174643 = VECTOR('',#174644,1.); -#174644 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174645 = PCURVE('',#174164,#174646); -#174646 = DEFINITIONAL_REPRESENTATION('',(#174647),#174651); -#174647 = LINE('',#174648,#174649); -#174648 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174649 = VECTOR('',#174650,1.); -#174650 = DIRECTION('',(-1.,0.E+000)); -#174651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#176991 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#176992 = CARTESIAN_POINT('',(-4.440892098501E-015,5.151515151515E-003) + ); +#176993 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) + ); +#176994 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) + ); +#176995 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) + ); +#176996 = CARTESIAN_POINT('',(-7.105427357601E-015,6.181818181818E-002) + ); +#176997 = CARTESIAN_POINT('',(-7.105427357601E-015,7.727272727273E-002) + ); +#176998 = CARTESIAN_POINT('',(-6.217248937901E-015,9.272727272727E-002) + ); +#176999 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); +#177000 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); +#177001 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); +#177002 = CARTESIAN_POINT('',(-6.217248937901E-015,0.154545454545)); +#177003 = CARTESIAN_POINT('',(-7.993605777301E-015,0.17)); +#177004 = CARTESIAN_POINT('',(-7.993605777301E-015,0.185454545455)); +#177005 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); +#177006 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); +#177007 = CARTESIAN_POINT('',(-7.105427357601E-015,0.231818181818)); +#177008 = CARTESIAN_POINT('',(-8.881784197001E-015,0.247272727273)); +#177009 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); +#177010 = CARTESIAN_POINT('',(-7.993605777301E-015,0.278181818182)); +#177011 = CARTESIAN_POINT('',(-5.329070518201E-015,0.293636363636)); +#177012 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#177013 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); +#177014 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); +#177015 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177017 = PCURVE('',#176556,#177018); +#177018 = DEFINITIONAL_REPRESENTATION('',(#177019),#177023); +#177019 = LINE('',#177020,#177021); +#177020 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#177021 = VECTOR('',#177022,1.); +#177022 = DIRECTION('',(-1.,0.E+000)); +#177023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177024 = ORIENTED_EDGE('',*,*,#176508,.T.); +#177025 = ADVANCED_FACE('',(#177026),#176556,.T.); +#177026 = FACE_BOUND('',#177027,.T.); +#177027 = EDGE_LOOP('',(#177028,#177029,#177030,#177051)); +#177028 = ORIENTED_EDGE('',*,*,#176982,.T.); +#177029 = ORIENTED_EDGE('',*,*,#176831,.F.); +#177030 = ORIENTED_EDGE('',*,*,#177031,.F.); +#177031 = EDGE_CURVE('',#176541,#176809,#177032,.T.); +#177032 = SURFACE_CURVE('',#177033,(#177037,#177044),.PCURVE_S1.); +#177033 = LINE('',#177034,#177035); +#177034 = CARTESIAN_POINT('',(0.785,-1.4,0.E+000)); +#177035 = VECTOR('',#177036,1.); +#177036 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177037 = PCURVE('',#176556,#177038); +#177038 = DEFINITIONAL_REPRESENTATION('',(#177039),#177043); +#177039 = LINE('',#177040,#177041); +#177040 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177041 = VECTOR('',#177042,1.); +#177042 = DIRECTION('',(-1.,0.E+000)); +#177043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177044 = PCURVE('',#176584,#177045); +#177045 = DEFINITIONAL_REPRESENTATION('',(#177046),#177050); +#177046 = LINE('',#177047,#177048); +#177047 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177048 = VECTOR('',#177049,1.); +#177049 = DIRECTION('',(0.E+000,1.)); +#177050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177051 = ORIENTED_EDGE('',*,*,#176540,.T.); +#177052 = ADVANCED_FACE('',(#177053),#176584,.T.); +#177053 = FACE_BOUND('',#177054,.T.); +#177054 = EDGE_LOOP('',(#177055,#177056,#177057,#177078)); +#177055 = ORIENTED_EDGE('',*,*,#177031,.T.); +#177056 = ORIENTED_EDGE('',*,*,#176808,.F.); +#177057 = ORIENTED_EDGE('',*,*,#177058,.F.); +#177058 = EDGE_CURVE('',#176569,#176786,#177059,.T.); +#177059 = SURFACE_CURVE('',#177060,(#177064,#177071),.PCURVE_S1.); +#177060 = LINE('',#177061,#177062); +#177061 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); +#177062 = VECTOR('',#177063,1.); +#177063 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177064 = PCURVE('',#176584,#177065); +#177065 = DEFINITIONAL_REPRESENTATION('',(#177066),#177070); +#177066 = LINE('',#177067,#177068); +#177067 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#177068 = VECTOR('',#177069,1.); +#177069 = DIRECTION('',(0.E+000,1.)); +#177070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#174652 = PCURVE('',#174192,#174653); -#174653 = DEFINITIONAL_REPRESENTATION('',(#174654),#174658); -#174654 = LINE('',#174655,#174656); -#174655 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174656 = VECTOR('',#174657,1.); -#174657 = DIRECTION('',(0.E+000,1.)); -#174658 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174659 = ORIENTED_EDGE('',*,*,#174148,.T.); -#174660 = ADVANCED_FACE('',(#174661),#174192,.T.); -#174661 = FACE_BOUND('',#174662,.T.); -#174662 = EDGE_LOOP('',(#174663,#174664,#174665,#174686)); -#174663 = ORIENTED_EDGE('',*,*,#174639,.T.); -#174664 = ORIENTED_EDGE('',*,*,#174416,.F.); -#174665 = ORIENTED_EDGE('',*,*,#174666,.F.); -#174666 = EDGE_CURVE('',#174177,#174394,#174667,.T.); -#174667 = SURFACE_CURVE('',#174668,(#174672,#174679),.PCURVE_S1.); -#174668 = LINE('',#174669,#174670); -#174669 = CARTESIAN_POINT('',(0.785,-1.4,0.15)); -#174670 = VECTOR('',#174671,1.); -#174671 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174672 = PCURVE('',#174192,#174673); -#174673 = DEFINITIONAL_REPRESENTATION('',(#174674),#174678); -#174674 = LINE('',#174675,#174676); -#174675 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#174676 = VECTOR('',#174677,1.); -#174677 = DIRECTION('',(0.E+000,1.)); -#174678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174679 = PCURVE('',#174220,#174680); -#174680 = DEFINITIONAL_REPRESENTATION('',(#174681),#174685); -#174681 = LINE('',#174682,#174683); -#174682 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174683 = VECTOR('',#174684,1.); -#174684 = DIRECTION('',(1.,0.E+000)); -#174685 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174686 = ORIENTED_EDGE('',*,*,#174176,.T.); -#174687 = ADVANCED_FACE('',(#174688),#174220,.T.); -#174688 = FACE_BOUND('',#174689,.T.); -#174689 = EDGE_LOOP('',(#174690,#174691,#174692,#174735)); -#174690 = ORIENTED_EDGE('',*,*,#174666,.T.); -#174691 = ORIENTED_EDGE('',*,*,#174393,.F.); -#174692 = ORIENTED_EDGE('',*,*,#174693,.F.); -#174693 = EDGE_CURVE('',#174205,#174371,#174694,.T.); -#174694 = SURFACE_CURVE('',#174695,(#174699,#174706),.PCURVE_S1.); -#174695 = LINE('',#174696,#174697); -#174696 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.15)); -#174697 = VECTOR('',#174698,1.); -#174698 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174699 = PCURVE('',#174220,#174700); -#174700 = DEFINITIONAL_REPRESENTATION('',(#174701),#174705); -#174701 = LINE('',#174702,#174703); -#174702 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#174703 = VECTOR('',#174704,1.); -#174704 = DIRECTION('',(1.,0.E+000)); -#174705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174706 = PCURVE('',#174249,#174707); -#174707 = DEFINITIONAL_REPRESENTATION('',(#174708),#174734); -#174708 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#174709,#174710,#174711, - #174712,#174713,#174714,#174715,#174716,#174717,#174718,#174719, - #174720,#174721,#174722,#174723,#174724,#174725,#174726,#174727, - #174728,#174729,#174730,#174731,#174732,#174733),.UNSPECIFIED.,.F., +#177071 = PCURVE('',#176612,#177072); +#177072 = DEFINITIONAL_REPRESENTATION('',(#177073),#177077); +#177073 = LINE('',#177074,#177075); +#177074 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177075 = VECTOR('',#177076,1.); +#177076 = DIRECTION('',(1.,0.E+000)); +#177077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177078 = ORIENTED_EDGE('',*,*,#176568,.T.); +#177079 = ADVANCED_FACE('',(#177080),#176612,.T.); +#177080 = FACE_BOUND('',#177081,.T.); +#177081 = EDGE_LOOP('',(#177082,#177083,#177084,#177127)); +#177082 = ORIENTED_EDGE('',*,*,#177058,.T.); +#177083 = ORIENTED_EDGE('',*,*,#176785,.F.); +#177084 = ORIENTED_EDGE('',*,*,#177085,.F.); +#177085 = EDGE_CURVE('',#176597,#176763,#177086,.T.); +#177086 = SURFACE_CURVE('',#177087,(#177091,#177098),.PCURVE_S1.); +#177087 = LINE('',#177088,#177089); +#177088 = CARTESIAN_POINT('',(0.785,-1.1307673058,0.15)); +#177089 = VECTOR('',#177090,1.); +#177090 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177091 = PCURVE('',#176612,#177092); +#177092 = DEFINITIONAL_REPRESENTATION('',(#177093),#177097); +#177093 = LINE('',#177094,#177095); +#177094 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#177095 = VECTOR('',#177096,1.); +#177096 = DIRECTION('',(1.,0.E+000)); +#177097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177098 = PCURVE('',#176641,#177099); +#177099 = DEFINITIONAL_REPRESENTATION('',(#177100),#177126); +#177100 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#177101,#177102,#177103, + #177104,#177105,#177106,#177107,#177108,#177109,#177110,#177111, + #177112,#177113,#177114,#177115,#177116,#177117,#177118,#177119, + #177120,#177121,#177122,#177123,#177124,#177125),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -216244,955 +219246,955 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#174709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174710 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) - ); -#174711 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) - ); -#174712 = CARTESIAN_POINT('',(-3.552713678801E-015,3.090909090909E-002) - ); -#174713 = CARTESIAN_POINT('',(-5.329070518201E-015,4.636363636364E-002) - ); -#174714 = CARTESIAN_POINT('',(-4.440892098501E-015,6.181818181818E-002) - ); -#174715 = CARTESIAN_POINT('',(-5.329070518201E-015,7.727272727273E-002) - ); -#174716 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) - ); -#174717 = CARTESIAN_POINT('',(-3.552713678801E-015,0.108181818182)); -#174718 = CARTESIAN_POINT('',(-3.552713678801E-015,0.123636363636)); -#174719 = CARTESIAN_POINT('',(-4.440892098501E-015,0.139090909091)); -#174720 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); -#174721 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); -#174722 = CARTESIAN_POINT('',(-3.552713678801E-015,0.185454545455)); -#174723 = CARTESIAN_POINT('',(-4.440892098501E-015,0.200909090909)); -#174724 = CARTESIAN_POINT('',(-3.552713678801E-015,0.216363636364)); -#174725 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); -#174726 = CARTESIAN_POINT('',(-6.217248937901E-015,0.247272727273)); -#174727 = CARTESIAN_POINT('',(-4.440892098501E-015,0.262727272727)); -#174728 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); -#174729 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); -#174730 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); -#174731 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); -#174732 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); -#174733 = CARTESIAN_POINT('',(0.E+000,0.34)); -#174734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174735 = ORIENTED_EDGE('',*,*,#174204,.T.); -#174736 = ADVANCED_FACE('',(#174737),#174249,.F.); -#174737 = FACE_BOUND('',#174738,.F.); -#174738 = EDGE_LOOP('',(#174739,#174740,#174741,#174761)); -#174739 = ORIENTED_EDGE('',*,*,#174693,.F.); -#174740 = ORIENTED_EDGE('',*,*,#174232,.F.); -#174741 = ORIENTED_EDGE('',*,*,#174742,.T.); -#174742 = EDGE_CURVE('',#174233,#174348,#174743,.T.); -#174743 = SURFACE_CURVE('',#174744,(#174748,#174754),.PCURVE_S1.); -#174744 = LINE('',#174745,#174746); -#174745 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); -#174746 = VECTOR('',#174747,1.); -#174747 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174748 = PCURVE('',#174249,#174749); -#174749 = DEFINITIONAL_REPRESENTATION('',(#174750),#174753); -#174750 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174751,#174752), +#177101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177102 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) + ); +#177103 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) + ); +#177104 = CARTESIAN_POINT('',(-3.552713678801E-015,3.090909090909E-002) + ); +#177105 = CARTESIAN_POINT('',(-5.329070518201E-015,4.636363636364E-002) + ); +#177106 = CARTESIAN_POINT('',(-4.440892098501E-015,6.181818181818E-002) + ); +#177107 = CARTESIAN_POINT('',(-5.329070518201E-015,7.727272727273E-002) + ); +#177108 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) + ); +#177109 = CARTESIAN_POINT('',(-3.552713678801E-015,0.108181818182)); +#177110 = CARTESIAN_POINT('',(-3.552713678801E-015,0.123636363636)); +#177111 = CARTESIAN_POINT('',(-4.440892098501E-015,0.139090909091)); +#177112 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); +#177113 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); +#177114 = CARTESIAN_POINT('',(-3.552713678801E-015,0.185454545455)); +#177115 = CARTESIAN_POINT('',(-4.440892098501E-015,0.200909090909)); +#177116 = CARTESIAN_POINT('',(-3.552713678801E-015,0.216363636364)); +#177117 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); +#177118 = CARTESIAN_POINT('',(-6.217248937901E-015,0.247272727273)); +#177119 = CARTESIAN_POINT('',(-4.440892098501E-015,0.262727272727)); +#177120 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); +#177121 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); +#177122 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); +#177123 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); +#177124 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); +#177125 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177127 = ORIENTED_EDGE('',*,*,#176596,.T.); +#177128 = ADVANCED_FACE('',(#177129),#176641,.F.); +#177129 = FACE_BOUND('',#177130,.F.); +#177130 = EDGE_LOOP('',(#177131,#177132,#177133,#177153)); +#177131 = ORIENTED_EDGE('',*,*,#177085,.F.); +#177132 = ORIENTED_EDGE('',*,*,#176624,.F.); +#177133 = ORIENTED_EDGE('',*,*,#177134,.T.); +#177134 = EDGE_CURVE('',#176625,#176740,#177135,.T.); +#177135 = SURFACE_CURVE('',#177136,(#177140,#177146),.PCURVE_S1.); +#177136 = LINE('',#177137,#177138); +#177137 = CARTESIAN_POINT('',(0.785,-1.080909188472,0.19623594148)); +#177138 = VECTOR('',#177139,1.); +#177139 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177140 = PCURVE('',#176641,#177141); +#177141 = DEFINITIONAL_REPRESENTATION('',(#177142),#177145); +#177142 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177143,#177144), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174751 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#174752 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#174753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174754 = PCURVE('',#174276,#174755); -#174755 = DEFINITIONAL_REPRESENTATION('',(#174756),#174760); -#174756 = LINE('',#174757,#174758); -#174757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174758 = VECTOR('',#174759,1.); -#174759 = DIRECTION('',(0.E+000,1.)); -#174760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174761 = ORIENTED_EDGE('',*,*,#174370,.T.); -#174762 = ADVANCED_FACE('',(#174763),#174276,.T.); -#174763 = FACE_BOUND('',#174764,.T.); -#174764 = EDGE_LOOP('',(#174765,#174766,#174767,#174787)); -#174765 = ORIENTED_EDGE('',*,*,#174742,.T.); -#174766 = ORIENTED_EDGE('',*,*,#174347,.F.); -#174767 = ORIENTED_EDGE('',*,*,#174768,.F.); -#174768 = EDGE_CURVE('',#174261,#174321,#174769,.T.); -#174769 = SURFACE_CURVE('',#174770,(#174774,#174781),.PCURVE_S1.); -#174770 = LINE('',#174771,#174772); -#174771 = CARTESIAN_POINT('',(0.785,-1.056555553792,0.518820292599)); -#174772 = VECTOR('',#174773,1.); -#174773 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174774 = PCURVE('',#174276,#174775); -#174775 = DEFINITIONAL_REPRESENTATION('',(#174776),#174780); -#174776 = LINE('',#174777,#174778); -#174777 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#174778 = VECTOR('',#174779,1.); -#174779 = DIRECTION('',(0.E+000,1.)); -#174780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174781 = PCURVE('',#174006,#174782); -#174782 = DEFINITIONAL_REPRESENTATION('',(#174783),#174786); -#174783 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174784,#174785), +#177143 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#177144 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#177145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177146 = PCURVE('',#176668,#177147); +#177147 = DEFINITIONAL_REPRESENTATION('',(#177148),#177152); +#177148 = LINE('',#177149,#177150); +#177149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177150 = VECTOR('',#177151,1.); +#177151 = DIRECTION('',(0.E+000,1.)); +#177152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177153 = ORIENTED_EDGE('',*,*,#176762,.T.); +#177154 = ADVANCED_FACE('',(#177155),#176668,.T.); +#177155 = FACE_BOUND('',#177156,.T.); +#177156 = EDGE_LOOP('',(#177157,#177158,#177159,#177179)); +#177157 = ORIENTED_EDGE('',*,*,#177134,.T.); +#177158 = ORIENTED_EDGE('',*,*,#176739,.F.); +#177159 = ORIENTED_EDGE('',*,*,#177160,.F.); +#177160 = EDGE_CURVE('',#176653,#176713,#177161,.T.); +#177161 = SURFACE_CURVE('',#177162,(#177166,#177173),.PCURVE_S1.); +#177162 = LINE('',#177163,#177164); +#177163 = CARTESIAN_POINT('',(0.785,-1.056555553792,0.518820292599)); +#177164 = VECTOR('',#177165,1.); +#177165 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177166 = PCURVE('',#176668,#177167); +#177167 = DEFINITIONAL_REPRESENTATION('',(#177168),#177172); +#177168 = LINE('',#177169,#177170); +#177169 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#177170 = VECTOR('',#177171,1.); +#177171 = DIRECTION('',(0.E+000,1.)); +#177172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177173 = PCURVE('',#176398,#177174); +#177174 = DEFINITIONAL_REPRESENTATION('',(#177175),#177178); +#177175 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177176,#177177), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174784 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#174785 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#174786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174787 = ORIENTED_EDGE('',*,*,#174260,.T.); -#174788 = ADVANCED_FACE('',(#174789),#174006,.T.); -#174789 = FACE_BOUND('',#174790,.T.); -#174790 = EDGE_LOOP('',(#174791,#174792,#174793,#174794)); -#174791 = ORIENTED_EDGE('',*,*,#174768,.T.); -#174792 = ORIENTED_EDGE('',*,*,#174320,.F.); -#174793 = ORIENTED_EDGE('',*,*,#173988,.F.); -#174794 = ORIENTED_EDGE('',*,*,#174288,.T.); -#174795 = ADVANCED_FACE('',(#174796),#172494,.T.); -#174796 = FACE_BOUND('',#174797,.T.); -#174797 = EDGE_LOOP('',(#174798,#174799,#174822,#174849)); -#174798 = ORIENTED_EDGE('',*,*,#172480,.T.); -#174799 = ORIENTED_EDGE('',*,*,#174800,.T.); -#174800 = EDGE_CURVE('',#171281,#174801,#174803,.T.); -#174801 = VERTEX_POINT('',#174802); -#174802 = CARTESIAN_POINT('',(0.785,0.807264967154,0.6)); -#174803 = SURFACE_CURVE('',#174804,(#174808,#174815),.PCURVE_S1.); -#174804 = LINE('',#174805,#174806); -#174805 = CARTESIAN_POINT('',(0.785,0.7,0.6)); -#174806 = VECTOR('',#174807,1.); -#174807 = DIRECTION('',(0.E+000,1.,0.E+000)); -#174808 = PCURVE('',#172494,#174809); -#174809 = DEFINITIONAL_REPRESENTATION('',(#174810),#174814); -#174810 = LINE('',#174811,#174812); -#174811 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174812 = VECTOR('',#174813,1.); -#174813 = DIRECTION('',(0.E+000,1.)); -#174814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174815 = PCURVE('',#171296,#174816); -#174816 = DEFINITIONAL_REPRESENTATION('',(#174817),#174821); -#174817 = LINE('',#174818,#174819); -#174818 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#174819 = VECTOR('',#174820,1.); -#174820 = DIRECTION('',(0.E+000,1.)); -#174821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174822 = ORIENTED_EDGE('',*,*,#174823,.T.); -#174823 = EDGE_CURVE('',#174801,#174824,#174826,.T.); -#174824 = VERTEX_POINT('',#174825); -#174825 = CARTESIAN_POINT('',(1.125,0.807264967154,0.6)); -#174826 = SURFACE_CURVE('',#174827,(#174831,#174838),.PCURVE_S1.); -#174827 = LINE('',#174828,#174829); -#174828 = CARTESIAN_POINT('',(0.785,0.807264967154,0.6)); -#174829 = VECTOR('',#174830,1.); -#174830 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174831 = PCURVE('',#172494,#174832); -#174832 = DEFINITIONAL_REPRESENTATION('',(#174833),#174837); -#174833 = LINE('',#174834,#174835); -#174834 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); -#174835 = VECTOR('',#174836,1.); -#174836 = DIRECTION('',(-1.,0.E+000)); -#174837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174838 = PCURVE('',#174839,#174844); -#174839 = CYLINDRICAL_SURFACE('',#174840,0.1); -#174840 = AXIS2_PLACEMENT_3D('',#174841,#174842,#174843); -#174841 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); -#174842 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174843 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174844 = DEFINITIONAL_REPRESENTATION('',(#174845),#174848); -#174845 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174846,#174847), +#177176 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#177177 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#177178 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177179 = ORIENTED_EDGE('',*,*,#176652,.T.); +#177180 = ADVANCED_FACE('',(#177181),#176398,.T.); +#177181 = FACE_BOUND('',#177182,.T.); +#177182 = EDGE_LOOP('',(#177183,#177184,#177185,#177186)); +#177183 = ORIENTED_EDGE('',*,*,#177160,.T.); +#177184 = ORIENTED_EDGE('',*,*,#176712,.F.); +#177185 = ORIENTED_EDGE('',*,*,#176380,.F.); +#177186 = ORIENTED_EDGE('',*,*,#176680,.T.); +#177187 = ADVANCED_FACE('',(#177188),#174886,.T.); +#177188 = FACE_BOUND('',#177189,.T.); +#177189 = EDGE_LOOP('',(#177190,#177191,#177214,#177241)); +#177190 = ORIENTED_EDGE('',*,*,#174872,.T.); +#177191 = ORIENTED_EDGE('',*,*,#177192,.T.); +#177192 = EDGE_CURVE('',#173673,#177193,#177195,.T.); +#177193 = VERTEX_POINT('',#177194); +#177194 = CARTESIAN_POINT('',(0.785,0.807264967154,0.6)); +#177195 = SURFACE_CURVE('',#177196,(#177200,#177207),.PCURVE_S1.); +#177196 = LINE('',#177197,#177198); +#177197 = CARTESIAN_POINT('',(0.785,0.7,0.6)); +#177198 = VECTOR('',#177199,1.); +#177199 = DIRECTION('',(0.E+000,1.,0.E+000)); +#177200 = PCURVE('',#174886,#177201); +#177201 = DEFINITIONAL_REPRESENTATION('',(#177202),#177206); +#177202 = LINE('',#177203,#177204); +#177203 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177204 = VECTOR('',#177205,1.); +#177205 = DIRECTION('',(0.E+000,1.)); +#177206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177207 = PCURVE('',#173688,#177208); +#177208 = DEFINITIONAL_REPRESENTATION('',(#177209),#177213); +#177209 = LINE('',#177210,#177211); +#177210 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#177211 = VECTOR('',#177212,1.); +#177212 = DIRECTION('',(0.E+000,1.)); +#177213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177214 = ORIENTED_EDGE('',*,*,#177215,.T.); +#177215 = EDGE_CURVE('',#177193,#177216,#177218,.T.); +#177216 = VERTEX_POINT('',#177217); +#177217 = CARTESIAN_POINT('',(1.125,0.807264967154,0.6)); +#177218 = SURFACE_CURVE('',#177219,(#177223,#177230),.PCURVE_S1.); +#177219 = LINE('',#177220,#177221); +#177220 = CARTESIAN_POINT('',(0.785,0.807264967154,0.6)); +#177221 = VECTOR('',#177222,1.); +#177222 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177223 = PCURVE('',#174886,#177224); +#177224 = DEFINITIONAL_REPRESENTATION('',(#177225),#177229); +#177225 = LINE('',#177226,#177227); +#177226 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); +#177227 = VECTOR('',#177228,1.); +#177228 = DIRECTION('',(-1.,0.E+000)); +#177229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177230 = PCURVE('',#177231,#177236); +#177231 = CYLINDRICAL_SURFACE('',#177232,0.1); +#177232 = AXIS2_PLACEMENT_3D('',#177233,#177234,#177235); +#177233 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); +#177234 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177235 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177236 = DEFINITIONAL_REPRESENTATION('',(#177237),#177240); +#177237 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177238,#177239), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174846 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174847 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#174848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174849 = ORIENTED_EDGE('',*,*,#174850,.F.); -#174850 = EDGE_CURVE('',#171202,#174824,#174851,.T.); -#174851 = SURFACE_CURVE('',#174852,(#174856,#174863),.PCURVE_S1.); -#174852 = LINE('',#174853,#174854); -#174853 = CARTESIAN_POINT('',(1.125,0.7,0.6)); -#174854 = VECTOR('',#174855,1.); -#174855 = DIRECTION('',(0.E+000,1.,0.E+000)); -#174856 = PCURVE('',#172494,#174857); -#174857 = DEFINITIONAL_REPRESENTATION('',(#174858),#174862); -#174858 = LINE('',#174859,#174860); -#174859 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#174860 = VECTOR('',#174861,1.); -#174861 = DIRECTION('',(0.E+000,1.)); -#174862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174863 = PCURVE('',#171240,#174864); -#174864 = DEFINITIONAL_REPRESENTATION('',(#174865),#174869); -#174865 = LINE('',#174866,#174867); -#174866 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#174867 = VECTOR('',#174868,1.); -#174868 = DIRECTION('',(0.E+000,1.)); -#174869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174870 = ADVANCED_FACE('',(#174871),#171268,.T.); -#174871 = FACE_BOUND('',#174872,.T.); -#174872 = EDGE_LOOP('',(#174873,#174896,#174923,#174944)); -#174873 = ORIENTED_EDGE('',*,*,#174874,.F.); -#174874 = EDGE_CURVE('',#174875,#171225,#174877,.T.); -#174875 = VERTEX_POINT('',#174876); -#174876 = CARTESIAN_POINT('',(1.125,0.807264967154,0.75)); -#174877 = SURFACE_CURVE('',#174878,(#174882,#174889),.PCURVE_S1.); -#174878 = LINE('',#174879,#174880); -#174879 = CARTESIAN_POINT('',(1.125,0.807264967154,0.75)); -#174880 = VECTOR('',#174881,1.); -#174881 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174882 = PCURVE('',#171268,#174883); -#174883 = DEFINITIONAL_REPRESENTATION('',(#174884),#174888); -#174884 = LINE('',#174885,#174886); -#174885 = CARTESIAN_POINT('',(0.34,0.E+000)); -#174886 = VECTOR('',#174887,1.); -#174887 = DIRECTION('',(0.E+000,-1.)); -#174888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174889 = PCURVE('',#171240,#174890); -#174890 = DEFINITIONAL_REPRESENTATION('',(#174891),#174895); -#174891 = LINE('',#174892,#174893); -#174892 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#174893 = VECTOR('',#174894,1.); -#174894 = DIRECTION('',(0.E+000,-1.)); -#174895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174896 = ORIENTED_EDGE('',*,*,#174897,.F.); -#174897 = EDGE_CURVE('',#174898,#174875,#174900,.T.); -#174898 = VERTEX_POINT('',#174899); -#174899 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); -#174900 = SURFACE_CURVE('',#174901,(#174905,#174912),.PCURVE_S1.); -#174901 = LINE('',#174902,#174903); -#174902 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); -#174903 = VECTOR('',#174904,1.); -#174904 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174905 = PCURVE('',#171268,#174906); -#174906 = DEFINITIONAL_REPRESENTATION('',(#174907),#174911); -#174907 = LINE('',#174908,#174909); -#174908 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174909 = VECTOR('',#174910,1.); -#174910 = DIRECTION('',(1.,0.E+000)); -#174911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174912 = PCURVE('',#174913,#174918); -#174913 = CYLINDRICAL_SURFACE('',#174914,0.25); -#174914 = AXIS2_PLACEMENT_3D('',#174915,#174916,#174917); -#174915 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); -#174916 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174917 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174918 = DEFINITIONAL_REPRESENTATION('',(#174919),#174922); -#174919 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174920,#174921), +#177238 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#177239 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#177240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177241 = ORIENTED_EDGE('',*,*,#177242,.F.); +#177242 = EDGE_CURVE('',#173594,#177216,#177243,.T.); +#177243 = SURFACE_CURVE('',#177244,(#177248,#177255),.PCURVE_S1.); +#177244 = LINE('',#177245,#177246); +#177245 = CARTESIAN_POINT('',(1.125,0.7,0.6)); +#177246 = VECTOR('',#177247,1.); +#177247 = DIRECTION('',(0.E+000,1.,0.E+000)); +#177248 = PCURVE('',#174886,#177249); +#177249 = DEFINITIONAL_REPRESENTATION('',(#177250),#177254); +#177250 = LINE('',#177251,#177252); +#177251 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#177252 = VECTOR('',#177253,1.); +#177253 = DIRECTION('',(0.E+000,1.)); +#177254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177255 = PCURVE('',#173632,#177256); +#177256 = DEFINITIONAL_REPRESENTATION('',(#177257),#177261); +#177257 = LINE('',#177258,#177259); +#177258 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#177259 = VECTOR('',#177260,1.); +#177260 = DIRECTION('',(0.E+000,1.)); +#177261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177262 = ADVANCED_FACE('',(#177263),#173660,.T.); +#177263 = FACE_BOUND('',#177264,.T.); +#177264 = EDGE_LOOP('',(#177265,#177288,#177315,#177336)); +#177265 = ORIENTED_EDGE('',*,*,#177266,.F.); +#177266 = EDGE_CURVE('',#177267,#173617,#177269,.T.); +#177267 = VERTEX_POINT('',#177268); +#177268 = CARTESIAN_POINT('',(1.125,0.807264967154,0.75)); +#177269 = SURFACE_CURVE('',#177270,(#177274,#177281),.PCURVE_S1.); +#177270 = LINE('',#177271,#177272); +#177271 = CARTESIAN_POINT('',(1.125,0.807264967154,0.75)); +#177272 = VECTOR('',#177273,1.); +#177273 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#177274 = PCURVE('',#173660,#177275); +#177275 = DEFINITIONAL_REPRESENTATION('',(#177276),#177280); +#177276 = LINE('',#177277,#177278); +#177277 = CARTESIAN_POINT('',(0.34,0.E+000)); +#177278 = VECTOR('',#177279,1.); +#177279 = DIRECTION('',(0.E+000,-1.)); +#177280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177281 = PCURVE('',#173632,#177282); +#177282 = DEFINITIONAL_REPRESENTATION('',(#177283),#177287); +#177283 = LINE('',#177284,#177285); +#177284 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#177285 = VECTOR('',#177286,1.); +#177286 = DIRECTION('',(0.E+000,-1.)); +#177287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177288 = ORIENTED_EDGE('',*,*,#177289,.F.); +#177289 = EDGE_CURVE('',#177290,#177267,#177292,.T.); +#177290 = VERTEX_POINT('',#177291); +#177291 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); +#177292 = SURFACE_CURVE('',#177293,(#177297,#177304),.PCURVE_S1.); +#177293 = LINE('',#177294,#177295); +#177294 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); +#177295 = VECTOR('',#177296,1.); +#177296 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177297 = PCURVE('',#173660,#177298); +#177298 = DEFINITIONAL_REPRESENTATION('',(#177299),#177303); +#177299 = LINE('',#177300,#177301); +#177300 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177301 = VECTOR('',#177302,1.); +#177302 = DIRECTION('',(1.,0.E+000)); +#177303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177304 = PCURVE('',#177305,#177310); +#177305 = CYLINDRICAL_SURFACE('',#177306,0.25); +#177306 = AXIS2_PLACEMENT_3D('',#177307,#177308,#177309); +#177307 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); +#177308 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177309 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177310 = DEFINITIONAL_REPRESENTATION('',(#177311),#177314); +#177311 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177312,#177313), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#174920 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174921 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#174922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174923 = ORIENTED_EDGE('',*,*,#174924,.T.); -#174924 = EDGE_CURVE('',#174898,#171253,#174925,.T.); -#174925 = SURFACE_CURVE('',#174926,(#174930,#174937),.PCURVE_S1.); -#174926 = LINE('',#174927,#174928); -#174927 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); -#174928 = VECTOR('',#174929,1.); -#174929 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#174930 = PCURVE('',#171268,#174931); -#174931 = DEFINITIONAL_REPRESENTATION('',(#174932),#174936); -#174932 = LINE('',#174933,#174934); -#174933 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174934 = VECTOR('',#174935,1.); -#174935 = DIRECTION('',(0.E+000,-1.)); -#174936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174937 = PCURVE('',#171296,#174938); -#174938 = DEFINITIONAL_REPRESENTATION('',(#174939),#174943); -#174939 = LINE('',#174940,#174941); -#174940 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#174941 = VECTOR('',#174942,1.); -#174942 = DIRECTION('',(0.E+000,-1.)); -#174943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174944 = ORIENTED_EDGE('',*,*,#171252,.F.); -#174945 = ADVANCED_FACE('',(#174946),#171296,.F.); -#174946 = FACE_BOUND('',#174947,.T.); -#174947 = EDGE_LOOP('',(#174948,#174949,#174950,#174951,#174974,#175002, - #175034,#175062,#175090,#175118,#175146,#175174)); -#174948 = ORIENTED_EDGE('',*,*,#174800,.F.); -#174949 = ORIENTED_EDGE('',*,*,#171280,.T.); -#174950 = ORIENTED_EDGE('',*,*,#174924,.F.); -#174951 = ORIENTED_EDGE('',*,*,#174952,.F.); -#174952 = EDGE_CURVE('',#174953,#174898,#174955,.T.); -#174953 = VERTEX_POINT('',#174954); -#174954 = CARTESIAN_POINT('',(0.785,1.056555553792,0.518820292599)); -#174955 = SURFACE_CURVE('',#174956,(#174961,#174968),.PCURVE_S1.); -#174956 = CIRCLE('',#174957,0.25); -#174957 = AXIS2_PLACEMENT_3D('',#174958,#174959,#174960); -#174958 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); -#174959 = DIRECTION('',(1.,0.E+000,0.E+000)); -#174960 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#174961 = PCURVE('',#171296,#174962); -#174962 = DEFINITIONAL_REPRESENTATION('',(#174963),#174967); -#174963 = CIRCLE('',#174964,0.25); -#174964 = AXIS2_PLACEMENT_2D('',#174965,#174966); -#174965 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174966 = DIRECTION('',(1.,0.E+000)); -#174967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174968 = PCURVE('',#174913,#174969); -#174969 = DEFINITIONAL_REPRESENTATION('',(#174970),#174973); -#174970 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#174971,#174972), +#177312 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#177313 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#177314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177315 = ORIENTED_EDGE('',*,*,#177316,.T.); +#177316 = EDGE_CURVE('',#177290,#173645,#177317,.T.); +#177317 = SURFACE_CURVE('',#177318,(#177322,#177329),.PCURVE_S1.); +#177318 = LINE('',#177319,#177320); +#177319 = CARTESIAN_POINT('',(0.785,0.807264967154,0.75)); +#177320 = VECTOR('',#177321,1.); +#177321 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#177322 = PCURVE('',#173660,#177323); +#177323 = DEFINITIONAL_REPRESENTATION('',(#177324),#177328); +#177324 = LINE('',#177325,#177326); +#177325 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177326 = VECTOR('',#177327,1.); +#177327 = DIRECTION('',(0.E+000,-1.)); +#177328 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177329 = PCURVE('',#173688,#177330); +#177330 = DEFINITIONAL_REPRESENTATION('',(#177331),#177335); +#177331 = LINE('',#177332,#177333); +#177332 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#177333 = VECTOR('',#177334,1.); +#177334 = DIRECTION('',(0.E+000,-1.)); +#177335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177336 = ORIENTED_EDGE('',*,*,#173644,.F.); +#177337 = ADVANCED_FACE('',(#177338),#173688,.F.); +#177338 = FACE_BOUND('',#177339,.T.); +#177339 = EDGE_LOOP('',(#177340,#177341,#177342,#177343,#177366,#177394, + #177426,#177454,#177482,#177510,#177538,#177566)); +#177340 = ORIENTED_EDGE('',*,*,#177192,.F.); +#177341 = ORIENTED_EDGE('',*,*,#173672,.T.); +#177342 = ORIENTED_EDGE('',*,*,#177316,.F.); +#177343 = ORIENTED_EDGE('',*,*,#177344,.F.); +#177344 = EDGE_CURVE('',#177345,#177290,#177347,.T.); +#177345 = VERTEX_POINT('',#177346); +#177346 = CARTESIAN_POINT('',(0.785,1.056555553792,0.518820292599)); +#177347 = SURFACE_CURVE('',#177348,(#177353,#177360),.PCURVE_S1.); +#177348 = CIRCLE('',#177349,0.25); +#177349 = AXIS2_PLACEMENT_3D('',#177350,#177351,#177352); +#177350 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); +#177351 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177352 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177353 = PCURVE('',#173688,#177354); +#177354 = DEFINITIONAL_REPRESENTATION('',(#177355),#177359); +#177355 = CIRCLE('',#177356,0.25); +#177356 = AXIS2_PLACEMENT_2D('',#177357,#177358); +#177357 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177358 = DIRECTION('',(1.,0.E+000)); +#177359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177360 = PCURVE('',#177305,#177361); +#177361 = DEFINITIONAL_REPRESENTATION('',(#177362),#177365); +#177362 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177363,#177364), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#174971 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#174972 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#174973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174974 = ORIENTED_EDGE('',*,*,#174975,.F.); -#174975 = EDGE_CURVE('',#174976,#174953,#174978,.T.); -#174976 = VERTEX_POINT('',#174977); -#174977 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); -#174978 = SURFACE_CURVE('',#174979,(#174983,#174990),.PCURVE_S1.); -#174979 = LINE('',#174980,#174981); -#174980 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); -#174981 = VECTOR('',#174982,1.); -#174982 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#174983 = PCURVE('',#171296,#174984); -#174984 = DEFINITIONAL_REPRESENTATION('',(#174985),#174989); -#174985 = LINE('',#174986,#174987); -#174986 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#174987 = VECTOR('',#174988,1.); -#174988 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#174989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#174990 = PCURVE('',#174991,#174996); -#174991 = PLANE('',#174992); -#174992 = AXIS2_PLACEMENT_3D('',#174993,#174994,#174995); -#174993 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); -#174994 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); -#174995 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#174996 = DEFINITIONAL_REPRESENTATION('',(#174997),#175001); -#174997 = LINE('',#174998,#174999); -#174998 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#174999 = VECTOR('',#175000,1.); -#175000 = DIRECTION('',(1.,0.E+000)); -#175001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175002 = ORIENTED_EDGE('',*,*,#175003,.F.); -#175003 = EDGE_CURVE('',#175004,#174976,#175006,.T.); -#175004 = VERTEX_POINT('',#175005); -#175005 = CARTESIAN_POINT('',(0.785,1.1307673058,0.15)); -#175006 = SURFACE_CURVE('',#175007,(#175012,#175023),.PCURVE_S1.); -#175007 = CIRCLE('',#175008,5.E-002); -#175008 = AXIS2_PLACEMENT_3D('',#175009,#175010,#175011); -#175009 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); -#175010 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#175011 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175012 = PCURVE('',#171296,#175013); -#175013 = DEFINITIONAL_REPRESENTATION('',(#175014),#175022); -#175014 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#175015,#175016,#175017, - #175018,#175019,#175020,#175021),.UNSPECIFIED.,.F.,.F.) +#177363 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#177364 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#177365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177366 = ORIENTED_EDGE('',*,*,#177367,.F.); +#177367 = EDGE_CURVE('',#177368,#177345,#177370,.T.); +#177368 = VERTEX_POINT('',#177369); +#177369 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); +#177370 = SURFACE_CURVE('',#177371,(#177375,#177382),.PCURVE_S1.); +#177371 = LINE('',#177372,#177373); +#177372 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); +#177373 = VECTOR('',#177374,1.); +#177374 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#177375 = PCURVE('',#173688,#177376); +#177376 = DEFINITIONAL_REPRESENTATION('',(#177377),#177381); +#177377 = LINE('',#177378,#177379); +#177378 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#177379 = VECTOR('',#177380,1.); +#177380 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#177381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177382 = PCURVE('',#177383,#177388); +#177383 = PLANE('',#177384); +#177384 = AXIS2_PLACEMENT_3D('',#177385,#177386,#177387); +#177385 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); +#177386 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); +#177387 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#177388 = DEFINITIONAL_REPRESENTATION('',(#177389),#177393); +#177389 = LINE('',#177390,#177391); +#177390 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177391 = VECTOR('',#177392,1.); +#177392 = DIRECTION('',(1.,0.E+000)); +#177393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177394 = ORIENTED_EDGE('',*,*,#177395,.F.); +#177395 = EDGE_CURVE('',#177396,#177368,#177398,.T.); +#177396 = VERTEX_POINT('',#177397); +#177397 = CARTESIAN_POINT('',(0.785,1.1307673058,0.15)); +#177398 = SURFACE_CURVE('',#177399,(#177404,#177415),.PCURVE_S1.); +#177399 = CIRCLE('',#177400,5.E-002); +#177400 = AXIS2_PLACEMENT_3D('',#177401,#177402,#177403); +#177401 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); +#177402 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#177403 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177404 = PCURVE('',#173688,#177405); +#177405 = DEFINITIONAL_REPRESENTATION('',(#177406),#177414); +#177406 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177407,#177408,#177409, + #177410,#177411,#177412,#177413),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#175015 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#175016 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#175017 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#175018 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#175019 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#175020 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#175021 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#175022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175023 = PCURVE('',#175024,#175029); -#175024 = CYLINDRICAL_SURFACE('',#175025,5.E-002); -#175025 = AXIS2_PLACEMENT_3D('',#175026,#175027,#175028); -#175026 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); -#175027 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175028 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#175029 = DEFINITIONAL_REPRESENTATION('',(#175030),#175033); -#175030 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175031,#175032), +#177407 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#177408 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#177409 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#177410 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#177411 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#177412 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#177413 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#177414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177415 = PCURVE('',#177416,#177421); +#177416 = CYLINDRICAL_SURFACE('',#177417,5.E-002); +#177417 = AXIS2_PLACEMENT_3D('',#177418,#177419,#177420); +#177418 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); +#177419 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177420 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177421 = DEFINITIONAL_REPRESENTATION('',(#177422),#177425); +#177422 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177423,#177424), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#175031 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#175032 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#175033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175034 = ORIENTED_EDGE('',*,*,#175035,.F.); -#175035 = EDGE_CURVE('',#175036,#175004,#175038,.T.); -#175036 = VERTEX_POINT('',#175037); -#175037 = CARTESIAN_POINT('',(0.785,1.4,0.15)); -#175038 = SURFACE_CURVE('',#175039,(#175043,#175050),.PCURVE_S1.); -#175039 = LINE('',#175040,#175041); -#175040 = CARTESIAN_POINT('',(0.785,1.4,0.15)); -#175041 = VECTOR('',#175042,1.); -#175042 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#175043 = PCURVE('',#171296,#175044); -#175044 = DEFINITIONAL_REPRESENTATION('',(#175045),#175049); -#175045 = LINE('',#175046,#175047); -#175046 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#175047 = VECTOR('',#175048,1.); -#175048 = DIRECTION('',(3.020255886006E-016,-1.)); -#175049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175050 = PCURVE('',#175051,#175056); -#175051 = PLANE('',#175052); -#175052 = AXIS2_PLACEMENT_3D('',#175053,#175054,#175055); -#175053 = CARTESIAN_POINT('',(0.785,1.4,0.15)); -#175054 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); -#175055 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#175056 = DEFINITIONAL_REPRESENTATION('',(#175057),#175061); -#175057 = LINE('',#175058,#175059); -#175058 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175059 = VECTOR('',#175060,1.); -#175060 = DIRECTION('',(1.,0.E+000)); -#175061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175062 = ORIENTED_EDGE('',*,*,#175063,.F.); -#175063 = EDGE_CURVE('',#175064,#175036,#175066,.T.); -#175064 = VERTEX_POINT('',#175065); -#175065 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175066 = SURFACE_CURVE('',#175067,(#175071,#175078),.PCURVE_S1.); -#175067 = LINE('',#175068,#175069); -#175068 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175069 = VECTOR('',#175070,1.); -#175070 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175071 = PCURVE('',#171296,#175072); -#175072 = DEFINITIONAL_REPRESENTATION('',(#175073),#175077); -#175073 = LINE('',#175074,#175075); -#175074 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#175075 = VECTOR('',#175076,1.); -#175076 = DIRECTION('',(-1.,0.E+000)); -#175077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175078 = PCURVE('',#175079,#175084); -#175079 = PLANE('',#175080); -#175080 = AXIS2_PLACEMENT_3D('',#175081,#175082,#175083); -#175081 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175082 = DIRECTION('',(0.E+000,1.,0.E+000)); -#175083 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175084 = DEFINITIONAL_REPRESENTATION('',(#175085),#175089); -#175085 = LINE('',#175086,#175087); -#175086 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175087 = VECTOR('',#175088,1.); -#175088 = DIRECTION('',(1.,0.E+000)); -#175089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175090 = ORIENTED_EDGE('',*,*,#175091,.F.); -#175091 = EDGE_CURVE('',#175092,#175064,#175094,.T.); -#175092 = VERTEX_POINT('',#175093); -#175093 = CARTESIAN_POINT('',(0.785,1.1307673058,2.710505431214E-016)); -#175094 = SURFACE_CURVE('',#175095,(#175099,#175106),.PCURVE_S1.); -#175095 = LINE('',#175096,#175097); -#175096 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175097 = VECTOR('',#175098,1.); -#175098 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#175099 = PCURVE('',#171296,#175100); -#175100 = DEFINITIONAL_REPRESENTATION('',(#175101),#175105); -#175101 = LINE('',#175102,#175103); -#175102 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#175103 = VECTOR('',#175104,1.); -#175104 = DIRECTION('',(-2.516879905005E-016,1.)); -#175105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175106 = PCURVE('',#175107,#175112); -#175107 = PLANE('',#175108); -#175108 = AXIS2_PLACEMENT_3D('',#175109,#175110,#175111); -#175109 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175110 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); -#175111 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#175112 = DEFINITIONAL_REPRESENTATION('',(#175113),#175117); -#175113 = LINE('',#175114,#175115); -#175114 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175115 = VECTOR('',#175116,1.); -#175116 = DIRECTION('',(1.,0.E+000)); -#175117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175118 = ORIENTED_EDGE('',*,*,#175119,.F.); -#175119 = EDGE_CURVE('',#175120,#175092,#175122,.T.); -#175120 = VERTEX_POINT('',#175121); -#175121 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); -#175122 = SURFACE_CURVE('',#175123,(#175128,#175135),.PCURVE_S1.); -#175123 = CIRCLE('',#175124,0.2); -#175124 = AXIS2_PLACEMENT_3D('',#175125,#175126,#175127); -#175125 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); -#175126 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175127 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175128 = PCURVE('',#171296,#175129); -#175129 = DEFINITIONAL_REPRESENTATION('',(#175130),#175134); -#175130 = CIRCLE('',#175131,0.2); -#175131 = AXIS2_PLACEMENT_2D('',#175132,#175133); -#175132 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#175133 = DIRECTION('',(-1.,0.E+000)); -#175134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175135 = PCURVE('',#175136,#175141); -#175136 = CYLINDRICAL_SURFACE('',#175137,0.2); -#175137 = AXIS2_PLACEMENT_3D('',#175138,#175139,#175140); -#175138 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); -#175139 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175140 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#175141 = DEFINITIONAL_REPRESENTATION('',(#175142),#175145); -#175142 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175143,#175144), +#177423 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#177424 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#177425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177426 = ORIENTED_EDGE('',*,*,#177427,.F.); +#177427 = EDGE_CURVE('',#177428,#177396,#177430,.T.); +#177428 = VERTEX_POINT('',#177429); +#177429 = CARTESIAN_POINT('',(0.785,1.4,0.15)); +#177430 = SURFACE_CURVE('',#177431,(#177435,#177442),.PCURVE_S1.); +#177431 = LINE('',#177432,#177433); +#177432 = CARTESIAN_POINT('',(0.785,1.4,0.15)); +#177433 = VECTOR('',#177434,1.); +#177434 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#177435 = PCURVE('',#173688,#177436); +#177436 = DEFINITIONAL_REPRESENTATION('',(#177437),#177441); +#177437 = LINE('',#177438,#177439); +#177438 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#177439 = VECTOR('',#177440,1.); +#177440 = DIRECTION('',(3.020255886006E-016,-1.)); +#177441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177442 = PCURVE('',#177443,#177448); +#177443 = PLANE('',#177444); +#177444 = AXIS2_PLACEMENT_3D('',#177445,#177446,#177447); +#177445 = CARTESIAN_POINT('',(0.785,1.4,0.15)); +#177446 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); +#177447 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#177448 = DEFINITIONAL_REPRESENTATION('',(#177449),#177453); +#177449 = LINE('',#177450,#177451); +#177450 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177451 = VECTOR('',#177452,1.); +#177452 = DIRECTION('',(1.,0.E+000)); +#177453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177454 = ORIENTED_EDGE('',*,*,#177455,.F.); +#177455 = EDGE_CURVE('',#177456,#177428,#177458,.T.); +#177456 = VERTEX_POINT('',#177457); +#177457 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177458 = SURFACE_CURVE('',#177459,(#177463,#177470),.PCURVE_S1.); +#177459 = LINE('',#177460,#177461); +#177460 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177461 = VECTOR('',#177462,1.); +#177462 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177463 = PCURVE('',#173688,#177464); +#177464 = DEFINITIONAL_REPRESENTATION('',(#177465),#177469); +#177465 = LINE('',#177466,#177467); +#177466 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#177467 = VECTOR('',#177468,1.); +#177468 = DIRECTION('',(-1.,0.E+000)); +#177469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177470 = PCURVE('',#177471,#177476); +#177471 = PLANE('',#177472); +#177472 = AXIS2_PLACEMENT_3D('',#177473,#177474,#177475); +#177473 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177474 = DIRECTION('',(0.E+000,1.,0.E+000)); +#177475 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177476 = DEFINITIONAL_REPRESENTATION('',(#177477),#177481); +#177477 = LINE('',#177478,#177479); +#177478 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177479 = VECTOR('',#177480,1.); +#177480 = DIRECTION('',(1.,0.E+000)); +#177481 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177482 = ORIENTED_EDGE('',*,*,#177483,.F.); +#177483 = EDGE_CURVE('',#177484,#177456,#177486,.T.); +#177484 = VERTEX_POINT('',#177485); +#177485 = CARTESIAN_POINT('',(0.785,1.1307673058,2.710505431214E-016)); +#177486 = SURFACE_CURVE('',#177487,(#177491,#177498),.PCURVE_S1.); +#177487 = LINE('',#177488,#177489); +#177488 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177489 = VECTOR('',#177490,1.); +#177490 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#177491 = PCURVE('',#173688,#177492); +#177492 = DEFINITIONAL_REPRESENTATION('',(#177493),#177497); +#177493 = LINE('',#177494,#177495); +#177494 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#177495 = VECTOR('',#177496,1.); +#177496 = DIRECTION('',(-2.516879905005E-016,1.)); +#177497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177498 = PCURVE('',#177499,#177504); +#177499 = PLANE('',#177500); +#177500 = AXIS2_PLACEMENT_3D('',#177501,#177502,#177503); +#177501 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177502 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); +#177503 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#177504 = DEFINITIONAL_REPRESENTATION('',(#177505),#177509); +#177505 = LINE('',#177506,#177507); +#177506 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177507 = VECTOR('',#177508,1.); +#177508 = DIRECTION('',(1.,0.E+000)); +#177509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177510 = ORIENTED_EDGE('',*,*,#177511,.F.); +#177511 = EDGE_CURVE('',#177512,#177484,#177514,.T.); +#177512 = VERTEX_POINT('',#177513); +#177513 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); +#177514 = SURFACE_CURVE('',#177515,(#177520,#177527),.PCURVE_S1.); +#177515 = CIRCLE('',#177516,0.2); +#177516 = AXIS2_PLACEMENT_3D('',#177517,#177518,#177519); +#177517 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); +#177518 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177519 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177520 = PCURVE('',#173688,#177521); +#177521 = DEFINITIONAL_REPRESENTATION('',(#177522),#177526); +#177522 = CIRCLE('',#177523,0.2); +#177523 = AXIS2_PLACEMENT_2D('',#177524,#177525); +#177524 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#177525 = DIRECTION('',(-1.,0.E+000)); +#177526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177527 = PCURVE('',#177528,#177533); +#177528 = CYLINDRICAL_SURFACE('',#177529,0.2); +#177529 = AXIS2_PLACEMENT_3D('',#177530,#177531,#177532); +#177530 = CARTESIAN_POINT('',(0.785,1.1307673058,0.2)); +#177531 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177532 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177533 = DEFINITIONAL_REPRESENTATION('',(#177534),#177537); +#177534 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177535,#177536), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#175143 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#175144 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#175145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175146 = ORIENTED_EDGE('',*,*,#175147,.F.); -#175147 = EDGE_CURVE('',#175148,#175120,#175150,.T.); -#175148 = VERTEX_POINT('',#175149); -#175149 = CARTESIAN_POINT('',(0.785,0.906981201809,0.50752811704)); -#175150 = SURFACE_CURVE('',#175151,(#175155,#175162),.PCURVE_S1.); -#175151 = LINE('',#175152,#175153); -#175152 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); -#175153 = VECTOR('',#175154,1.); -#175154 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#175155 = PCURVE('',#171296,#175156); -#175156 = DEFINITIONAL_REPRESENTATION('',(#175157),#175161); -#175157 = LINE('',#175158,#175159); -#175158 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#175159 = VECTOR('',#175160,1.); -#175160 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#175161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175162 = PCURVE('',#175163,#175168); -#175163 = PLANE('',#175164); -#175164 = AXIS2_PLACEMENT_3D('',#175165,#175166,#175167); -#175165 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); -#175166 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); -#175167 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#175168 = DEFINITIONAL_REPRESENTATION('',(#175169),#175173); -#175169 = LINE('',#175170,#175171); -#175170 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175171 = VECTOR('',#175172,1.); -#175172 = DIRECTION('',(1.,0.E+000)); -#175173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175174 = ORIENTED_EDGE('',*,*,#175175,.F.); -#175175 = EDGE_CURVE('',#174801,#175148,#175176,.T.); -#175176 = SURFACE_CURVE('',#175177,(#175182,#175193),.PCURVE_S1.); -#175177 = CIRCLE('',#175178,0.1); -#175178 = AXIS2_PLACEMENT_3D('',#175179,#175180,#175181); -#175179 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); -#175180 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#175181 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175182 = PCURVE('',#171296,#175183); -#175183 = DEFINITIONAL_REPRESENTATION('',(#175184),#175192); -#175184 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#175185,#175186,#175187, - #175188,#175189,#175190,#175191),.UNSPECIFIED.,.F.,.F.) +#177535 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#177536 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#177537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177538 = ORIENTED_EDGE('',*,*,#177539,.F.); +#177539 = EDGE_CURVE('',#177540,#177512,#177542,.T.); +#177540 = VERTEX_POINT('',#177541); +#177541 = CARTESIAN_POINT('',(0.785,0.906981201809,0.50752811704)); +#177542 = SURFACE_CURVE('',#177543,(#177547,#177554),.PCURVE_S1.); +#177543 = LINE('',#177544,#177545); +#177544 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); +#177545 = VECTOR('',#177546,1.); +#177546 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#177547 = PCURVE('',#173688,#177548); +#177548 = DEFINITIONAL_REPRESENTATION('',(#177549),#177553); +#177549 = LINE('',#177550,#177551); +#177550 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#177551 = VECTOR('',#177552,1.); +#177552 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#177553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177554 = PCURVE('',#177555,#177560); +#177555 = PLANE('',#177556); +#177556 = AXIS2_PLACEMENT_3D('',#177557,#177558,#177559); +#177557 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); +#177558 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); +#177559 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#177560 = DEFINITIONAL_REPRESENTATION('',(#177561),#177565); +#177561 = LINE('',#177562,#177563); +#177562 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177563 = VECTOR('',#177564,1.); +#177564 = DIRECTION('',(1.,0.E+000)); +#177565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177566 = ORIENTED_EDGE('',*,*,#177567,.F.); +#177567 = EDGE_CURVE('',#177193,#177540,#177568,.T.); +#177568 = SURFACE_CURVE('',#177569,(#177574,#177585),.PCURVE_S1.); +#177569 = CIRCLE('',#177570,0.1); +#177570 = AXIS2_PLACEMENT_3D('',#177571,#177572,#177573); +#177571 = CARTESIAN_POINT('',(0.785,0.807264967154,0.5)); +#177572 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#177573 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177574 = PCURVE('',#173688,#177575); +#177575 = DEFINITIONAL_REPRESENTATION('',(#177576),#177584); +#177576 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177577,#177578,#177579, + #177580,#177581,#177582,#177583),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#175185 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#175186 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#175187 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#175188 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#175189 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#175190 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#175191 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#175192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175193 = PCURVE('',#174839,#175194); -#175194 = DEFINITIONAL_REPRESENTATION('',(#175195),#175198); -#175195 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175196,#175197), +#177577 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#177578 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#177579 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#177580 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#177581 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#177582 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#177583 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#177584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177585 = PCURVE('',#177231,#177586); +#177586 = DEFINITIONAL_REPRESENTATION('',(#177587),#177590); +#177587 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177588,#177589), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#175196 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#175197 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#175198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175199 = ADVANCED_FACE('',(#175200),#171240,.T.); -#175200 = FACE_BOUND('',#175201,.T.); -#175201 = EDGE_LOOP('',(#175202,#175203,#175204,#175231,#175254,#175277, - #175300,#175323,#175346,#175373,#175396,#175417)); -#175202 = ORIENTED_EDGE('',*,*,#171224,.F.); -#175203 = ORIENTED_EDGE('',*,*,#174850,.T.); -#175204 = ORIENTED_EDGE('',*,*,#175205,.T.); -#175205 = EDGE_CURVE('',#174824,#175206,#175208,.T.); -#175206 = VERTEX_POINT('',#175207); -#175207 = CARTESIAN_POINT('',(1.125,0.906981201809,0.50752811704)); -#175208 = SURFACE_CURVE('',#175209,(#175214,#175225),.PCURVE_S1.); -#175209 = CIRCLE('',#175210,0.1); -#175210 = AXIS2_PLACEMENT_3D('',#175211,#175212,#175213); -#175211 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); -#175212 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#175213 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175214 = PCURVE('',#171240,#175215); -#175215 = DEFINITIONAL_REPRESENTATION('',(#175216),#175224); -#175216 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#175217,#175218,#175219, - #175220,#175221,#175222,#175223),.UNSPECIFIED.,.F.,.F.) +#177588 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#177589 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#177590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177591 = ADVANCED_FACE('',(#177592),#173632,.T.); +#177592 = FACE_BOUND('',#177593,.T.); +#177593 = EDGE_LOOP('',(#177594,#177595,#177596,#177623,#177646,#177669, + #177692,#177715,#177738,#177765,#177788,#177809)); +#177594 = ORIENTED_EDGE('',*,*,#173616,.F.); +#177595 = ORIENTED_EDGE('',*,*,#177242,.T.); +#177596 = ORIENTED_EDGE('',*,*,#177597,.T.); +#177597 = EDGE_CURVE('',#177216,#177598,#177600,.T.); +#177598 = VERTEX_POINT('',#177599); +#177599 = CARTESIAN_POINT('',(1.125,0.906981201809,0.50752811704)); +#177600 = SURFACE_CURVE('',#177601,(#177606,#177617),.PCURVE_S1.); +#177601 = CIRCLE('',#177602,0.1); +#177602 = AXIS2_PLACEMENT_3D('',#177603,#177604,#177605); +#177603 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); +#177604 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#177605 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177606 = PCURVE('',#173632,#177607); +#177607 = DEFINITIONAL_REPRESENTATION('',(#177608),#177616); +#177608 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177609,#177610,#177611, + #177612,#177613,#177614,#177615),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#175217 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#175218 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#175219 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#175220 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#175221 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#175222 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#175223 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#175224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175225 = PCURVE('',#174839,#175226); -#175226 = DEFINITIONAL_REPRESENTATION('',(#175227),#175230); -#175227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175228,#175229), +#177609 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#177610 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#177611 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#177612 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#177613 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#177614 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#177615 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#177616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177617 = PCURVE('',#177231,#177618); +#177618 = DEFINITIONAL_REPRESENTATION('',(#177619),#177622); +#177619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177620,#177621), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#175228 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#175229 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#175230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175231 = ORIENTED_EDGE('',*,*,#175232,.T.); -#175232 = EDGE_CURVE('',#175206,#175233,#175235,.T.); -#175233 = VERTEX_POINT('',#175234); -#175234 = CARTESIAN_POINT('',(1.125,0.931334836489,0.184943765921)); -#175235 = SURFACE_CURVE('',#175236,(#175240,#175247),.PCURVE_S1.); -#175236 = LINE('',#175237,#175238); -#175237 = CARTESIAN_POINT('',(1.125,0.931334836489,0.184943765921)); -#175238 = VECTOR('',#175239,1.); -#175239 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#175240 = PCURVE('',#171240,#175241); -#175241 = DEFINITIONAL_REPRESENTATION('',(#175242),#175246); -#175242 = LINE('',#175243,#175244); -#175243 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#175244 = VECTOR('',#175245,1.); -#175245 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#175246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175247 = PCURVE('',#175163,#175248); -#175248 = DEFINITIONAL_REPRESENTATION('',(#175249),#175253); -#175249 = LINE('',#175250,#175251); -#175250 = CARTESIAN_POINT('',(0.E+000,0.34)); -#175251 = VECTOR('',#175252,1.); -#175252 = DIRECTION('',(1.,0.E+000)); -#175253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175254 = ORIENTED_EDGE('',*,*,#175255,.T.); -#175255 = EDGE_CURVE('',#175233,#175256,#175258,.T.); -#175256 = VERTEX_POINT('',#175257); -#175257 = CARTESIAN_POINT('',(1.125,1.1307673058,2.710505431214E-016)); -#175258 = SURFACE_CURVE('',#175259,(#175264,#175271),.PCURVE_S1.); -#175259 = CIRCLE('',#175260,0.2); -#175260 = AXIS2_PLACEMENT_3D('',#175261,#175262,#175263); -#175261 = CARTESIAN_POINT('',(1.125,1.1307673058,0.2)); -#175262 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175263 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175264 = PCURVE('',#171240,#175265); -#175265 = DEFINITIONAL_REPRESENTATION('',(#175266),#175270); -#175266 = CIRCLE('',#175267,0.2); -#175267 = AXIS2_PLACEMENT_2D('',#175268,#175269); -#175268 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#175269 = DIRECTION('',(-1.,0.E+000)); -#175270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175271 = PCURVE('',#175136,#175272); -#175272 = DEFINITIONAL_REPRESENTATION('',(#175273),#175276); -#175273 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175274,#175275), +#177620 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#177621 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#177622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177623 = ORIENTED_EDGE('',*,*,#177624,.T.); +#177624 = EDGE_CURVE('',#177598,#177625,#177627,.T.); +#177625 = VERTEX_POINT('',#177626); +#177626 = CARTESIAN_POINT('',(1.125,0.931334836489,0.184943765921)); +#177627 = SURFACE_CURVE('',#177628,(#177632,#177639),.PCURVE_S1.); +#177628 = LINE('',#177629,#177630); +#177629 = CARTESIAN_POINT('',(1.125,0.931334836489,0.184943765921)); +#177630 = VECTOR('',#177631,1.); +#177631 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#177632 = PCURVE('',#173632,#177633); +#177633 = DEFINITIONAL_REPRESENTATION('',(#177634),#177638); +#177634 = LINE('',#177635,#177636); +#177635 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#177636 = VECTOR('',#177637,1.); +#177637 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#177638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177639 = PCURVE('',#177555,#177640); +#177640 = DEFINITIONAL_REPRESENTATION('',(#177641),#177645); +#177641 = LINE('',#177642,#177643); +#177642 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177643 = VECTOR('',#177644,1.); +#177644 = DIRECTION('',(1.,0.E+000)); +#177645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177646 = ORIENTED_EDGE('',*,*,#177647,.T.); +#177647 = EDGE_CURVE('',#177625,#177648,#177650,.T.); +#177648 = VERTEX_POINT('',#177649); +#177649 = CARTESIAN_POINT('',(1.125,1.1307673058,2.710505431214E-016)); +#177650 = SURFACE_CURVE('',#177651,(#177656,#177663),.PCURVE_S1.); +#177651 = CIRCLE('',#177652,0.2); +#177652 = AXIS2_PLACEMENT_3D('',#177653,#177654,#177655); +#177653 = CARTESIAN_POINT('',(1.125,1.1307673058,0.2)); +#177654 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177655 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177656 = PCURVE('',#173632,#177657); +#177657 = DEFINITIONAL_REPRESENTATION('',(#177658),#177662); +#177658 = CIRCLE('',#177659,0.2); +#177659 = AXIS2_PLACEMENT_2D('',#177660,#177661); +#177660 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#177661 = DIRECTION('',(-1.,0.E+000)); +#177662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177663 = PCURVE('',#177528,#177664); +#177664 = DEFINITIONAL_REPRESENTATION('',(#177665),#177668); +#177665 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177666,#177667), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#175274 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#175275 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#175276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175277 = ORIENTED_EDGE('',*,*,#175278,.T.); -#175278 = EDGE_CURVE('',#175256,#175279,#175281,.T.); -#175279 = VERTEX_POINT('',#175280); -#175280 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); -#175281 = SURFACE_CURVE('',#175282,(#175286,#175293),.PCURVE_S1.); -#175282 = LINE('',#175283,#175284); -#175283 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); -#175284 = VECTOR('',#175285,1.); -#175285 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#175286 = PCURVE('',#171240,#175287); -#175287 = DEFINITIONAL_REPRESENTATION('',(#175288),#175292); -#175288 = LINE('',#175289,#175290); -#175289 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#175290 = VECTOR('',#175291,1.); -#175291 = DIRECTION('',(-2.516879905005E-016,1.)); -#175292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175293 = PCURVE('',#175107,#175294); -#175294 = DEFINITIONAL_REPRESENTATION('',(#175295),#175299); -#175295 = LINE('',#175296,#175297); -#175296 = CARTESIAN_POINT('',(0.E+000,0.34)); -#175297 = VECTOR('',#175298,1.); -#175298 = DIRECTION('',(1.,0.E+000)); -#175299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175300 = ORIENTED_EDGE('',*,*,#175301,.T.); -#175301 = EDGE_CURVE('',#175279,#175302,#175304,.T.); -#175302 = VERTEX_POINT('',#175303); -#175303 = CARTESIAN_POINT('',(1.125,1.4,0.15)); -#175304 = SURFACE_CURVE('',#175305,(#175309,#175316),.PCURVE_S1.); -#175305 = LINE('',#175306,#175307); -#175306 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); -#175307 = VECTOR('',#175308,1.); -#175308 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175309 = PCURVE('',#171240,#175310); -#175310 = DEFINITIONAL_REPRESENTATION('',(#175311),#175315); -#175311 = LINE('',#175312,#175313); -#175312 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#175313 = VECTOR('',#175314,1.); -#175314 = DIRECTION('',(-1.,0.E+000)); -#175315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175316 = PCURVE('',#175079,#175317); -#175317 = DEFINITIONAL_REPRESENTATION('',(#175318),#175322); -#175318 = LINE('',#175319,#175320); -#175319 = CARTESIAN_POINT('',(0.E+000,0.34)); -#175320 = VECTOR('',#175321,1.); -#175321 = DIRECTION('',(1.,0.E+000)); -#175322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175323 = ORIENTED_EDGE('',*,*,#175324,.T.); -#175324 = EDGE_CURVE('',#175302,#175325,#175327,.T.); -#175325 = VERTEX_POINT('',#175326); -#175326 = CARTESIAN_POINT('',(1.125,1.1307673058,0.15)); -#175327 = SURFACE_CURVE('',#175328,(#175332,#175339),.PCURVE_S1.); -#175328 = LINE('',#175329,#175330); -#175329 = CARTESIAN_POINT('',(1.125,1.4,0.15)); -#175330 = VECTOR('',#175331,1.); -#175331 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#175332 = PCURVE('',#171240,#175333); -#175333 = DEFINITIONAL_REPRESENTATION('',(#175334),#175338); -#175334 = LINE('',#175335,#175336); -#175335 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#175336 = VECTOR('',#175337,1.); -#175337 = DIRECTION('',(3.020255886006E-016,-1.)); -#175338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175339 = PCURVE('',#175051,#175340); -#175340 = DEFINITIONAL_REPRESENTATION('',(#175341),#175345); -#175341 = LINE('',#175342,#175343); -#175342 = CARTESIAN_POINT('',(0.E+000,0.34)); -#175343 = VECTOR('',#175344,1.); -#175344 = DIRECTION('',(1.,0.E+000)); -#175345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175346 = ORIENTED_EDGE('',*,*,#175347,.T.); -#175347 = EDGE_CURVE('',#175325,#175348,#175350,.T.); -#175348 = VERTEX_POINT('',#175349); -#175349 = CARTESIAN_POINT('',(1.125,1.080909188472,0.19623594148)); -#175350 = SURFACE_CURVE('',#175351,(#175356,#175367),.PCURVE_S1.); -#175351 = CIRCLE('',#175352,5.E-002); -#175352 = AXIS2_PLACEMENT_3D('',#175353,#175354,#175355); -#175353 = CARTESIAN_POINT('',(1.125,1.1307673058,0.2)); -#175354 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#175355 = DIRECTION('',(0.E+000,0.E+000,1.)); -#175356 = PCURVE('',#171240,#175357); -#175357 = DEFINITIONAL_REPRESENTATION('',(#175358),#175366); -#175358 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#175359,#175360,#175361, - #175362,#175363,#175364,#175365),.UNSPECIFIED.,.F.,.F.) +#177666 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#177667 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#177668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177669 = ORIENTED_EDGE('',*,*,#177670,.T.); +#177670 = EDGE_CURVE('',#177648,#177671,#177673,.T.); +#177671 = VERTEX_POINT('',#177672); +#177672 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); +#177673 = SURFACE_CURVE('',#177674,(#177678,#177685),.PCURVE_S1.); +#177674 = LINE('',#177675,#177676); +#177675 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); +#177676 = VECTOR('',#177677,1.); +#177677 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#177678 = PCURVE('',#173632,#177679); +#177679 = DEFINITIONAL_REPRESENTATION('',(#177680),#177684); +#177680 = LINE('',#177681,#177682); +#177681 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#177682 = VECTOR('',#177683,1.); +#177683 = DIRECTION('',(-2.516879905005E-016,1.)); +#177684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177685 = PCURVE('',#177499,#177686); +#177686 = DEFINITIONAL_REPRESENTATION('',(#177687),#177691); +#177687 = LINE('',#177688,#177689); +#177688 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177689 = VECTOR('',#177690,1.); +#177690 = DIRECTION('',(1.,0.E+000)); +#177691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177692 = ORIENTED_EDGE('',*,*,#177693,.T.); +#177693 = EDGE_CURVE('',#177671,#177694,#177696,.T.); +#177694 = VERTEX_POINT('',#177695); +#177695 = CARTESIAN_POINT('',(1.125,1.4,0.15)); +#177696 = SURFACE_CURVE('',#177697,(#177701,#177708),.PCURVE_S1.); +#177697 = LINE('',#177698,#177699); +#177698 = CARTESIAN_POINT('',(1.125,1.4,3.388131789017E-016)); +#177699 = VECTOR('',#177700,1.); +#177700 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177701 = PCURVE('',#173632,#177702); +#177702 = DEFINITIONAL_REPRESENTATION('',(#177703),#177707); +#177703 = LINE('',#177704,#177705); +#177704 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#177705 = VECTOR('',#177706,1.); +#177706 = DIRECTION('',(-1.,0.E+000)); +#177707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177708 = PCURVE('',#177471,#177709); +#177709 = DEFINITIONAL_REPRESENTATION('',(#177710),#177714); +#177710 = LINE('',#177711,#177712); +#177711 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177712 = VECTOR('',#177713,1.); +#177713 = DIRECTION('',(1.,0.E+000)); +#177714 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177715 = ORIENTED_EDGE('',*,*,#177716,.T.); +#177716 = EDGE_CURVE('',#177694,#177717,#177719,.T.); +#177717 = VERTEX_POINT('',#177718); +#177718 = CARTESIAN_POINT('',(1.125,1.1307673058,0.15)); +#177719 = SURFACE_CURVE('',#177720,(#177724,#177731),.PCURVE_S1.); +#177720 = LINE('',#177721,#177722); +#177721 = CARTESIAN_POINT('',(1.125,1.4,0.15)); +#177722 = VECTOR('',#177723,1.); +#177723 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#177724 = PCURVE('',#173632,#177725); +#177725 = DEFINITIONAL_REPRESENTATION('',(#177726),#177730); +#177726 = LINE('',#177727,#177728); +#177727 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#177728 = VECTOR('',#177729,1.); +#177729 = DIRECTION('',(3.020255886006E-016,-1.)); +#177730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177731 = PCURVE('',#177443,#177732); +#177732 = DEFINITIONAL_REPRESENTATION('',(#177733),#177737); +#177733 = LINE('',#177734,#177735); +#177734 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177735 = VECTOR('',#177736,1.); +#177736 = DIRECTION('',(1.,0.E+000)); +#177737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177738 = ORIENTED_EDGE('',*,*,#177739,.T.); +#177739 = EDGE_CURVE('',#177717,#177740,#177742,.T.); +#177740 = VERTEX_POINT('',#177741); +#177741 = CARTESIAN_POINT('',(1.125,1.080909188472,0.19623594148)); +#177742 = SURFACE_CURVE('',#177743,(#177748,#177759),.PCURVE_S1.); +#177743 = CIRCLE('',#177744,5.E-002); +#177744 = AXIS2_PLACEMENT_3D('',#177745,#177746,#177747); +#177745 = CARTESIAN_POINT('',(1.125,1.1307673058,0.2)); +#177746 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#177747 = DIRECTION('',(0.E+000,0.E+000,1.)); +#177748 = PCURVE('',#173632,#177749); +#177749 = DEFINITIONAL_REPRESENTATION('',(#177750),#177758); +#177750 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177751,#177752,#177753, + #177754,#177755,#177756,#177757),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#175359 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#175360 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#175361 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#175362 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#175363 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#175364 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#175365 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#175366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175367 = PCURVE('',#175024,#175368); -#175368 = DEFINITIONAL_REPRESENTATION('',(#175369),#175372); -#175369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175370,#175371), +#177751 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#177752 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#177753 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#177754 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#177755 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#177756 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#177757 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#177758 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177759 = PCURVE('',#177416,#177760); +#177760 = DEFINITIONAL_REPRESENTATION('',(#177761),#177764); +#177761 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177762,#177763), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#175370 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#175371 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#175372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175373 = ORIENTED_EDGE('',*,*,#175374,.T.); -#175374 = EDGE_CURVE('',#175348,#175375,#175377,.T.); -#175375 = VERTEX_POINT('',#175376); -#175376 = CARTESIAN_POINT('',(1.125,1.056555553792,0.518820292599)); -#175377 = SURFACE_CURVE('',#175378,(#175382,#175389),.PCURVE_S1.); -#175378 = LINE('',#175379,#175380); -#175379 = CARTESIAN_POINT('',(1.125,1.080909188472,0.19623594148)); -#175380 = VECTOR('',#175381,1.); -#175381 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#175382 = PCURVE('',#171240,#175383); -#175383 = DEFINITIONAL_REPRESENTATION('',(#175384),#175388); -#175384 = LINE('',#175385,#175386); -#175385 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#175386 = VECTOR('',#175387,1.); -#175387 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#175388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175389 = PCURVE('',#174991,#175390); -#175390 = DEFINITIONAL_REPRESENTATION('',(#175391),#175395); -#175391 = LINE('',#175392,#175393); -#175392 = CARTESIAN_POINT('',(0.E+000,0.34)); -#175393 = VECTOR('',#175394,1.); -#175394 = DIRECTION('',(1.,0.E+000)); -#175395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175396 = ORIENTED_EDGE('',*,*,#175397,.T.); -#175397 = EDGE_CURVE('',#175375,#174875,#175398,.T.); -#175398 = SURFACE_CURVE('',#175399,(#175404,#175411),.PCURVE_S1.); -#175399 = CIRCLE('',#175400,0.25); -#175400 = AXIS2_PLACEMENT_3D('',#175401,#175402,#175403); -#175401 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); -#175402 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175403 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#175404 = PCURVE('',#171240,#175405); -#175405 = DEFINITIONAL_REPRESENTATION('',(#175406),#175410); -#175406 = CIRCLE('',#175407,0.25); -#175407 = AXIS2_PLACEMENT_2D('',#175408,#175409); -#175408 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175409 = DIRECTION('',(1.,0.E+000)); -#175410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175411 = PCURVE('',#174913,#175412); -#175412 = DEFINITIONAL_REPRESENTATION('',(#175413),#175416); -#175413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175414,#175415), +#177762 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#177763 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#177764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177765 = ORIENTED_EDGE('',*,*,#177766,.T.); +#177766 = EDGE_CURVE('',#177740,#177767,#177769,.T.); +#177767 = VERTEX_POINT('',#177768); +#177768 = CARTESIAN_POINT('',(1.125,1.056555553792,0.518820292599)); +#177769 = SURFACE_CURVE('',#177770,(#177774,#177781),.PCURVE_S1.); +#177770 = LINE('',#177771,#177772); +#177771 = CARTESIAN_POINT('',(1.125,1.080909188472,0.19623594148)); +#177772 = VECTOR('',#177773,1.); +#177773 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#177774 = PCURVE('',#173632,#177775); +#177775 = DEFINITIONAL_REPRESENTATION('',(#177776),#177780); +#177776 = LINE('',#177777,#177778); +#177777 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#177778 = VECTOR('',#177779,1.); +#177779 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#177780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177781 = PCURVE('',#177383,#177782); +#177782 = DEFINITIONAL_REPRESENTATION('',(#177783),#177787); +#177783 = LINE('',#177784,#177785); +#177784 = CARTESIAN_POINT('',(0.E+000,0.34)); +#177785 = VECTOR('',#177786,1.); +#177786 = DIRECTION('',(1.,0.E+000)); +#177787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177788 = ORIENTED_EDGE('',*,*,#177789,.T.); +#177789 = EDGE_CURVE('',#177767,#177267,#177790,.T.); +#177790 = SURFACE_CURVE('',#177791,(#177796,#177803),.PCURVE_S1.); +#177791 = CIRCLE('',#177792,0.25); +#177792 = AXIS2_PLACEMENT_3D('',#177793,#177794,#177795); +#177793 = CARTESIAN_POINT('',(1.125,0.807264967154,0.5)); +#177794 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177795 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#177796 = PCURVE('',#173632,#177797); +#177797 = DEFINITIONAL_REPRESENTATION('',(#177798),#177802); +#177798 = CIRCLE('',#177799,0.25); +#177799 = AXIS2_PLACEMENT_2D('',#177800,#177801); +#177800 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177801 = DIRECTION('',(1.,0.E+000)); +#177802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177803 = PCURVE('',#177305,#177804); +#177804 = DEFINITIONAL_REPRESENTATION('',(#177805),#177808); +#177805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177806,#177807), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#175414 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#175415 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#175416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175417 = ORIENTED_EDGE('',*,*,#174874,.T.); -#175418 = ADVANCED_FACE('',(#175419),#174913,.T.); -#175419 = FACE_BOUND('',#175420,.T.); -#175420 = EDGE_LOOP('',(#175421,#175422,#175442,#175443)); -#175421 = ORIENTED_EDGE('',*,*,#175397,.F.); -#175422 = ORIENTED_EDGE('',*,*,#175423,.F.); -#175423 = EDGE_CURVE('',#174953,#175375,#175424,.T.); -#175424 = SURFACE_CURVE('',#175425,(#175429,#175435),.PCURVE_S1.); -#175425 = LINE('',#175426,#175427); -#175426 = CARTESIAN_POINT('',(0.785,1.056555553792,0.518820292599)); -#175427 = VECTOR('',#175428,1.); -#175428 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175429 = PCURVE('',#174913,#175430); -#175430 = DEFINITIONAL_REPRESENTATION('',(#175431),#175434); -#175431 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175432,#175433), +#177806 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#177807 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#177808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177809 = ORIENTED_EDGE('',*,*,#177266,.T.); +#177810 = ADVANCED_FACE('',(#177811),#177305,.T.); +#177811 = FACE_BOUND('',#177812,.T.); +#177812 = EDGE_LOOP('',(#177813,#177814,#177834,#177835)); +#177813 = ORIENTED_EDGE('',*,*,#177789,.F.); +#177814 = ORIENTED_EDGE('',*,*,#177815,.F.); +#177815 = EDGE_CURVE('',#177345,#177767,#177816,.T.); +#177816 = SURFACE_CURVE('',#177817,(#177821,#177827),.PCURVE_S1.); +#177817 = LINE('',#177818,#177819); +#177818 = CARTESIAN_POINT('',(0.785,1.056555553792,0.518820292599)); +#177819 = VECTOR('',#177820,1.); +#177820 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177821 = PCURVE('',#177305,#177822); +#177822 = DEFINITIONAL_REPRESENTATION('',(#177823),#177826); +#177823 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177824,#177825), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#175432 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#175433 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#175434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175435 = PCURVE('',#174991,#175436); -#175436 = DEFINITIONAL_REPRESENTATION('',(#175437),#175441); -#175437 = LINE('',#175438,#175439); -#175438 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#175439 = VECTOR('',#175440,1.); -#175440 = DIRECTION('',(0.E+000,1.)); -#175441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175442 = ORIENTED_EDGE('',*,*,#174952,.T.); -#175443 = ORIENTED_EDGE('',*,*,#174897,.T.); -#175444 = ADVANCED_FACE('',(#175445),#174991,.T.); -#175445 = FACE_BOUND('',#175446,.T.); -#175446 = EDGE_LOOP('',(#175447,#175448,#175468,#175469)); -#175447 = ORIENTED_EDGE('',*,*,#175374,.F.); -#175448 = ORIENTED_EDGE('',*,*,#175449,.F.); -#175449 = EDGE_CURVE('',#174976,#175348,#175450,.T.); -#175450 = SURFACE_CURVE('',#175451,(#175455,#175462),.PCURVE_S1.); -#175451 = LINE('',#175452,#175453); -#175452 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); -#175453 = VECTOR('',#175454,1.); -#175454 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175455 = PCURVE('',#174991,#175456); -#175456 = DEFINITIONAL_REPRESENTATION('',(#175457),#175461); -#175457 = LINE('',#175458,#175459); -#175458 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175459 = VECTOR('',#175460,1.); -#175460 = DIRECTION('',(0.E+000,1.)); -#175461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175462 = PCURVE('',#175024,#175463); -#175463 = DEFINITIONAL_REPRESENTATION('',(#175464),#175467); -#175464 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175465,#175466), +#177824 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#177825 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#177826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177827 = PCURVE('',#177383,#177828); +#177828 = DEFINITIONAL_REPRESENTATION('',(#177829),#177833); +#177829 = LINE('',#177830,#177831); +#177830 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#177831 = VECTOR('',#177832,1.); +#177832 = DIRECTION('',(0.E+000,1.)); +#177833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177834 = ORIENTED_EDGE('',*,*,#177344,.T.); +#177835 = ORIENTED_EDGE('',*,*,#177289,.T.); +#177836 = ADVANCED_FACE('',(#177837),#177383,.T.); +#177837 = FACE_BOUND('',#177838,.T.); +#177838 = EDGE_LOOP('',(#177839,#177840,#177860,#177861)); +#177839 = ORIENTED_EDGE('',*,*,#177766,.F.); +#177840 = ORIENTED_EDGE('',*,*,#177841,.F.); +#177841 = EDGE_CURVE('',#177368,#177740,#177842,.T.); +#177842 = SURFACE_CURVE('',#177843,(#177847,#177854),.PCURVE_S1.); +#177843 = LINE('',#177844,#177845); +#177844 = CARTESIAN_POINT('',(0.785,1.080909188472,0.19623594148)); +#177845 = VECTOR('',#177846,1.); +#177846 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177847 = PCURVE('',#177383,#177848); +#177848 = DEFINITIONAL_REPRESENTATION('',(#177849),#177853); +#177849 = LINE('',#177850,#177851); +#177850 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177851 = VECTOR('',#177852,1.); +#177852 = DIRECTION('',(0.E+000,1.)); +#177853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177854 = PCURVE('',#177416,#177855); +#177855 = DEFINITIONAL_REPRESENTATION('',(#177856),#177859); +#177856 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177857,#177858), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#175465 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#175466 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#175467 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175468 = ORIENTED_EDGE('',*,*,#174975,.T.); -#175469 = ORIENTED_EDGE('',*,*,#175423,.T.); -#175470 = ADVANCED_FACE('',(#175471),#175024,.F.); -#175471 = FACE_BOUND('',#175472,.F.); -#175472 = EDGE_LOOP('',(#175473,#175474,#175475,#175476)); -#175473 = ORIENTED_EDGE('',*,*,#175347,.T.); -#175474 = ORIENTED_EDGE('',*,*,#175449,.F.); -#175475 = ORIENTED_EDGE('',*,*,#175003,.F.); -#175476 = ORIENTED_EDGE('',*,*,#175477,.T.); -#175477 = EDGE_CURVE('',#175004,#175325,#175478,.T.); -#175478 = SURFACE_CURVE('',#175479,(#175483,#175512),.PCURVE_S1.); -#175479 = LINE('',#175480,#175481); -#175480 = CARTESIAN_POINT('',(0.785,1.1307673058,0.15)); -#175481 = VECTOR('',#175482,1.); -#175482 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175483 = PCURVE('',#175024,#175484); -#175484 = DEFINITIONAL_REPRESENTATION('',(#175485),#175511); -#175485 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175486,#175487,#175488, - #175489,#175490,#175491,#175492,#175493,#175494,#175495,#175496, - #175497,#175498,#175499,#175500,#175501,#175502,#175503,#175504, - #175505,#175506,#175507,#175508,#175509,#175510),.UNSPECIFIED.,.F., +#177857 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#177858 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#177859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177860 = ORIENTED_EDGE('',*,*,#177367,.T.); +#177861 = ORIENTED_EDGE('',*,*,#177815,.T.); +#177862 = ADVANCED_FACE('',(#177863),#177416,.F.); +#177863 = FACE_BOUND('',#177864,.F.); +#177864 = EDGE_LOOP('',(#177865,#177866,#177867,#177868)); +#177865 = ORIENTED_EDGE('',*,*,#177739,.T.); +#177866 = ORIENTED_EDGE('',*,*,#177841,.F.); +#177867 = ORIENTED_EDGE('',*,*,#177395,.F.); +#177868 = ORIENTED_EDGE('',*,*,#177869,.T.); +#177869 = EDGE_CURVE('',#177396,#177717,#177870,.T.); +#177870 = SURFACE_CURVE('',#177871,(#177875,#177904),.PCURVE_S1.); +#177871 = LINE('',#177872,#177873); +#177872 = CARTESIAN_POINT('',(0.785,1.1307673058,0.15)); +#177873 = VECTOR('',#177874,1.); +#177874 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177875 = PCURVE('',#177416,#177876); +#177876 = DEFINITIONAL_REPRESENTATION('',(#177877),#177903); +#177877 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#177878,#177879,#177880, + #177881,#177882,#177883,#177884,#177885,#177886,#177887,#177888, + #177889,#177890,#177891,#177892,#177893,#177894,#177895,#177896, + #177897,#177898,#177899,#177900,#177901,#177902),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -217200,131 +220202,131 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#175486 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#175487 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#175488 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#175489 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#175490 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#175491 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#175492 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#175493 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#175494 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#175495 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#175496 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#175497 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#175498 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#175499 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#175500 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#175501 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#175502 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#175503 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#175504 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#175505 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#175506 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#175507 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#175508 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#175509 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#175510 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#175511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175512 = PCURVE('',#175051,#175513); -#175513 = DEFINITIONAL_REPRESENTATION('',(#175514),#175518); -#175514 = LINE('',#175515,#175516); -#175515 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); -#175516 = VECTOR('',#175517,1.); -#175517 = DIRECTION('',(0.E+000,1.)); -#175518 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175519 = ADVANCED_FACE('',(#175520),#175051,.T.); -#175520 = FACE_BOUND('',#175521,.T.); -#175521 = EDGE_LOOP('',(#175522,#175523,#175544,#175545)); -#175522 = ORIENTED_EDGE('',*,*,#175324,.F.); -#175523 = ORIENTED_EDGE('',*,*,#175524,.F.); -#175524 = EDGE_CURVE('',#175036,#175302,#175525,.T.); -#175525 = SURFACE_CURVE('',#175526,(#175530,#175537),.PCURVE_S1.); -#175526 = LINE('',#175527,#175528); -#175527 = CARTESIAN_POINT('',(0.785,1.4,0.15)); -#175528 = VECTOR('',#175529,1.); -#175529 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175530 = PCURVE('',#175051,#175531); -#175531 = DEFINITIONAL_REPRESENTATION('',(#175532),#175536); -#175532 = LINE('',#175533,#175534); -#175533 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175534 = VECTOR('',#175535,1.); -#175535 = DIRECTION('',(0.E+000,1.)); -#175536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175537 = PCURVE('',#175079,#175538); -#175538 = DEFINITIONAL_REPRESENTATION('',(#175539),#175543); -#175539 = LINE('',#175540,#175541); -#175540 = CARTESIAN_POINT('',(0.15,0.E+000)); -#175541 = VECTOR('',#175542,1.); -#175542 = DIRECTION('',(0.E+000,1.)); -#175543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175544 = ORIENTED_EDGE('',*,*,#175035,.T.); -#175545 = ORIENTED_EDGE('',*,*,#175477,.T.); -#175546 = ADVANCED_FACE('',(#175547),#175079,.T.); -#175547 = FACE_BOUND('',#175548,.T.); -#175548 = EDGE_LOOP('',(#175549,#175550,#175571,#175572)); -#175549 = ORIENTED_EDGE('',*,*,#175301,.F.); -#175550 = ORIENTED_EDGE('',*,*,#175551,.F.); -#175551 = EDGE_CURVE('',#175064,#175279,#175552,.T.); -#175552 = SURFACE_CURVE('',#175553,(#175557,#175564),.PCURVE_S1.); -#175553 = LINE('',#175554,#175555); -#175554 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); -#175555 = VECTOR('',#175556,1.); -#175556 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175557 = PCURVE('',#175079,#175558); -#175558 = DEFINITIONAL_REPRESENTATION('',(#175559),#175563); -#175559 = LINE('',#175560,#175561); -#175560 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175561 = VECTOR('',#175562,1.); -#175562 = DIRECTION('',(0.E+000,1.)); -#175563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175564 = PCURVE('',#175107,#175565); -#175565 = DEFINITIONAL_REPRESENTATION('',(#175566),#175570); -#175566 = LINE('',#175567,#175568); -#175567 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175568 = VECTOR('',#175569,1.); -#175569 = DIRECTION('',(0.E+000,1.)); -#175570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175571 = ORIENTED_EDGE('',*,*,#175063,.T.); -#175572 = ORIENTED_EDGE('',*,*,#175524,.T.); -#175573 = ADVANCED_FACE('',(#175574),#175107,.T.); -#175574 = FACE_BOUND('',#175575,.T.); -#175575 = EDGE_LOOP('',(#175576,#175577,#175620,#175621)); -#175576 = ORIENTED_EDGE('',*,*,#175278,.F.); -#175577 = ORIENTED_EDGE('',*,*,#175578,.F.); -#175578 = EDGE_CURVE('',#175092,#175256,#175579,.T.); -#175579 = SURFACE_CURVE('',#175580,(#175584,#175591),.PCURVE_S1.); -#175580 = LINE('',#175581,#175582); -#175581 = CARTESIAN_POINT('',(0.785,1.1307673058,2.710505431214E-016)); -#175582 = VECTOR('',#175583,1.); -#175583 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175584 = PCURVE('',#175107,#175585); -#175585 = DEFINITIONAL_REPRESENTATION('',(#175586),#175590); -#175586 = LINE('',#175587,#175588); -#175587 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); -#175588 = VECTOR('',#175589,1.); -#175589 = DIRECTION('',(0.E+000,1.)); -#175590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175591 = PCURVE('',#175136,#175592); -#175592 = DEFINITIONAL_REPRESENTATION('',(#175593),#175619); -#175593 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175594,#175595,#175596, - #175597,#175598,#175599,#175600,#175601,#175602,#175603,#175604, - #175605,#175606,#175607,#175608,#175609,#175610,#175611,#175612, - #175613,#175614,#175615,#175616,#175617,#175618),.UNSPECIFIED.,.F., +#177878 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#177879 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#177880 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#177881 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#177882 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#177883 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#177884 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#177885 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#177886 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#177887 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#177888 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#177889 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#177890 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#177891 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#177892 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#177893 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#177894 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#177895 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#177896 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#177897 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#177898 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#177899 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#177900 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#177901 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#177902 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#177903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177904 = PCURVE('',#177443,#177905); +#177905 = DEFINITIONAL_REPRESENTATION('',(#177906),#177910); +#177906 = LINE('',#177907,#177908); +#177907 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); +#177908 = VECTOR('',#177909,1.); +#177909 = DIRECTION('',(0.E+000,1.)); +#177910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177911 = ADVANCED_FACE('',(#177912),#177443,.T.); +#177912 = FACE_BOUND('',#177913,.T.); +#177913 = EDGE_LOOP('',(#177914,#177915,#177936,#177937)); +#177914 = ORIENTED_EDGE('',*,*,#177716,.F.); +#177915 = ORIENTED_EDGE('',*,*,#177916,.F.); +#177916 = EDGE_CURVE('',#177428,#177694,#177917,.T.); +#177917 = SURFACE_CURVE('',#177918,(#177922,#177929),.PCURVE_S1.); +#177918 = LINE('',#177919,#177920); +#177919 = CARTESIAN_POINT('',(0.785,1.4,0.15)); +#177920 = VECTOR('',#177921,1.); +#177921 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177922 = PCURVE('',#177443,#177923); +#177923 = DEFINITIONAL_REPRESENTATION('',(#177924),#177928); +#177924 = LINE('',#177925,#177926); +#177925 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177926 = VECTOR('',#177927,1.); +#177927 = DIRECTION('',(0.E+000,1.)); +#177928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177929 = PCURVE('',#177471,#177930); +#177930 = DEFINITIONAL_REPRESENTATION('',(#177931),#177935); +#177931 = LINE('',#177932,#177933); +#177932 = CARTESIAN_POINT('',(0.15,0.E+000)); +#177933 = VECTOR('',#177934,1.); +#177934 = DIRECTION('',(0.E+000,1.)); +#177935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177936 = ORIENTED_EDGE('',*,*,#177427,.T.); +#177937 = ORIENTED_EDGE('',*,*,#177869,.T.); +#177938 = ADVANCED_FACE('',(#177939),#177471,.T.); +#177939 = FACE_BOUND('',#177940,.T.); +#177940 = EDGE_LOOP('',(#177941,#177942,#177963,#177964)); +#177941 = ORIENTED_EDGE('',*,*,#177693,.F.); +#177942 = ORIENTED_EDGE('',*,*,#177943,.F.); +#177943 = EDGE_CURVE('',#177456,#177671,#177944,.T.); +#177944 = SURFACE_CURVE('',#177945,(#177949,#177956),.PCURVE_S1.); +#177945 = LINE('',#177946,#177947); +#177946 = CARTESIAN_POINT('',(0.785,1.4,3.388131789017E-016)); +#177947 = VECTOR('',#177948,1.); +#177948 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177949 = PCURVE('',#177471,#177950); +#177950 = DEFINITIONAL_REPRESENTATION('',(#177951),#177955); +#177951 = LINE('',#177952,#177953); +#177952 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177953 = VECTOR('',#177954,1.); +#177954 = DIRECTION('',(0.E+000,1.)); +#177955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177956 = PCURVE('',#177499,#177957); +#177957 = DEFINITIONAL_REPRESENTATION('',(#177958),#177962); +#177958 = LINE('',#177959,#177960); +#177959 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#177960 = VECTOR('',#177961,1.); +#177961 = DIRECTION('',(0.E+000,1.)); +#177962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177963 = ORIENTED_EDGE('',*,*,#177455,.T.); +#177964 = ORIENTED_EDGE('',*,*,#177916,.T.); +#177965 = ADVANCED_FACE('',(#177966),#177499,.T.); +#177966 = FACE_BOUND('',#177967,.T.); +#177967 = EDGE_LOOP('',(#177968,#177969,#178012,#178013)); +#177968 = ORIENTED_EDGE('',*,*,#177670,.F.); +#177969 = ORIENTED_EDGE('',*,*,#177970,.F.); +#177970 = EDGE_CURVE('',#177484,#177648,#177971,.T.); +#177971 = SURFACE_CURVE('',#177972,(#177976,#177983),.PCURVE_S1.); +#177972 = LINE('',#177973,#177974); +#177973 = CARTESIAN_POINT('',(0.785,1.1307673058,2.710505431214E-016)); +#177974 = VECTOR('',#177975,1.); +#177975 = DIRECTION('',(1.,0.E+000,0.E+000)); +#177976 = PCURVE('',#177499,#177977); +#177977 = DEFINITIONAL_REPRESENTATION('',(#177978),#177982); +#177978 = LINE('',#177979,#177980); +#177979 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); +#177980 = VECTOR('',#177981,1.); +#177981 = DIRECTION('',(0.E+000,1.)); +#177982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#177983 = PCURVE('',#177528,#177984); +#177984 = DEFINITIONAL_REPRESENTATION('',(#177985),#178011); +#177985 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#177986,#177987,#177988, + #177989,#177990,#177991,#177992,#177993,#177994,#177995,#177996, + #177997,#177998,#177999,#178000,#178001,#178002,#178003,#178004, + #178005,#178006,#178007,#178008,#178009,#178010),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -217332,131 +220334,131 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#175594 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#175595 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#175596 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#175597 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#175598 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#175599 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#175600 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#175601 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#175602 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#175603 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#175604 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#175605 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#175606 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#175607 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#175608 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#175609 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#175610 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#175611 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#175612 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#175613 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#175614 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#175615 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#175616 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#175617 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#175618 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#175619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175620 = ORIENTED_EDGE('',*,*,#175091,.T.); -#175621 = ORIENTED_EDGE('',*,*,#175551,.T.); -#175622 = ADVANCED_FACE('',(#175623),#175136,.T.); -#175623 = FACE_BOUND('',#175624,.T.); -#175624 = EDGE_LOOP('',(#175625,#175626,#175646,#175647)); -#175625 = ORIENTED_EDGE('',*,*,#175255,.F.); -#175626 = ORIENTED_EDGE('',*,*,#175627,.F.); -#175627 = EDGE_CURVE('',#175120,#175233,#175628,.T.); -#175628 = SURFACE_CURVE('',#175629,(#175633,#175639),.PCURVE_S1.); -#175629 = LINE('',#175630,#175631); -#175630 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); -#175631 = VECTOR('',#175632,1.); -#175632 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175633 = PCURVE('',#175136,#175634); -#175634 = DEFINITIONAL_REPRESENTATION('',(#175635),#175638); -#175635 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175636,#175637), +#177986 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#177987 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#177988 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#177989 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#177990 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#177991 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#177992 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#177993 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#177994 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#177995 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#177996 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#177997 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#177998 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#177999 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#178000 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#178001 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#178002 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#178003 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#178004 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#178005 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#178006 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#178007 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#178008 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#178009 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#178010 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#178011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178012 = ORIENTED_EDGE('',*,*,#177483,.T.); +#178013 = ORIENTED_EDGE('',*,*,#177943,.T.); +#178014 = ADVANCED_FACE('',(#178015),#177528,.T.); +#178015 = FACE_BOUND('',#178016,.T.); +#178016 = EDGE_LOOP('',(#178017,#178018,#178038,#178039)); +#178017 = ORIENTED_EDGE('',*,*,#177647,.F.); +#178018 = ORIENTED_EDGE('',*,*,#178019,.F.); +#178019 = EDGE_CURVE('',#177512,#177625,#178020,.T.); +#178020 = SURFACE_CURVE('',#178021,(#178025,#178031),.PCURVE_S1.); +#178021 = LINE('',#178022,#178023); +#178022 = CARTESIAN_POINT('',(0.785,0.931334836489,0.184943765921)); +#178023 = VECTOR('',#178024,1.); +#178024 = DIRECTION('',(1.,0.E+000,0.E+000)); +#178025 = PCURVE('',#177528,#178026); +#178026 = DEFINITIONAL_REPRESENTATION('',(#178027),#178030); +#178027 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178028,#178029), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#175636 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#175637 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#175638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175639 = PCURVE('',#175163,#175640); -#175640 = DEFINITIONAL_REPRESENTATION('',(#175641),#175645); -#175641 = LINE('',#175642,#175643); -#175642 = CARTESIAN_POINT('',(8.303044473245E-017,0.E+000)); -#175643 = VECTOR('',#175644,1.); -#175644 = DIRECTION('',(0.E+000,1.)); -#175645 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175646 = ORIENTED_EDGE('',*,*,#175119,.T.); -#175647 = ORIENTED_EDGE('',*,*,#175578,.T.); -#175648 = ADVANCED_FACE('',(#175649),#175163,.T.); -#175649 = FACE_BOUND('',#175650,.T.); -#175650 = EDGE_LOOP('',(#175651,#175652,#175672,#175673)); -#175651 = ORIENTED_EDGE('',*,*,#175232,.F.); -#175652 = ORIENTED_EDGE('',*,*,#175653,.F.); -#175653 = EDGE_CURVE('',#175148,#175206,#175654,.T.); -#175654 = SURFACE_CURVE('',#175655,(#175659,#175666),.PCURVE_S1.); -#175655 = LINE('',#175656,#175657); -#175656 = CARTESIAN_POINT('',(0.785,0.906981201809,0.50752811704)); -#175657 = VECTOR('',#175658,1.); -#175658 = DIRECTION('',(1.,0.E+000,0.E+000)); -#175659 = PCURVE('',#175163,#175660); -#175660 = DEFINITIONAL_REPRESENTATION('',(#175661),#175665); -#175661 = LINE('',#175662,#175663); -#175662 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#175663 = VECTOR('',#175664,1.); -#175664 = DIRECTION('',(0.E+000,1.)); -#175665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175666 = PCURVE('',#174839,#175667); -#175667 = DEFINITIONAL_REPRESENTATION('',(#175668),#175671); -#175668 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#175669,#175670), +#178028 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#178029 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#178030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178031 = PCURVE('',#177555,#178032); +#178032 = DEFINITIONAL_REPRESENTATION('',(#178033),#178037); +#178033 = LINE('',#178034,#178035); +#178034 = CARTESIAN_POINT('',(8.303044473245E-017,0.E+000)); +#178035 = VECTOR('',#178036,1.); +#178036 = DIRECTION('',(0.E+000,1.)); +#178037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178038 = ORIENTED_EDGE('',*,*,#177511,.T.); +#178039 = ORIENTED_EDGE('',*,*,#177970,.T.); +#178040 = ADVANCED_FACE('',(#178041),#177555,.T.); +#178041 = FACE_BOUND('',#178042,.T.); +#178042 = EDGE_LOOP('',(#178043,#178044,#178064,#178065)); +#178043 = ORIENTED_EDGE('',*,*,#177624,.F.); +#178044 = ORIENTED_EDGE('',*,*,#178045,.F.); +#178045 = EDGE_CURVE('',#177540,#177598,#178046,.T.); +#178046 = SURFACE_CURVE('',#178047,(#178051,#178058),.PCURVE_S1.); +#178047 = LINE('',#178048,#178049); +#178048 = CARTESIAN_POINT('',(0.785,0.906981201809,0.50752811704)); +#178049 = VECTOR('',#178050,1.); +#178050 = DIRECTION('',(1.,0.E+000,0.E+000)); +#178051 = PCURVE('',#177555,#178052); +#178052 = DEFINITIONAL_REPRESENTATION('',(#178053),#178057); +#178053 = LINE('',#178054,#178055); +#178054 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#178055 = VECTOR('',#178056,1.); +#178056 = DIRECTION('',(0.E+000,1.)); +#178057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178058 = PCURVE('',#177231,#178059); +#178059 = DEFINITIONAL_REPRESENTATION('',(#178060),#178063); +#178060 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178061,#178062), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#175669 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#175670 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#175671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175672 = ORIENTED_EDGE('',*,*,#175147,.T.); -#175673 = ORIENTED_EDGE('',*,*,#175627,.T.); -#175674 = ADVANCED_FACE('',(#175675),#174839,.F.); -#175675 = FACE_BOUND('',#175676,.F.); -#175676 = EDGE_LOOP('',(#175677,#175678,#175679,#175680)); -#175677 = ORIENTED_EDGE('',*,*,#175205,.T.); -#175678 = ORIENTED_EDGE('',*,*,#175653,.F.); -#175679 = ORIENTED_EDGE('',*,*,#175175,.F.); -#175680 = ORIENTED_EDGE('',*,*,#174823,.T.); -#175681 = ADVANCED_FACE('',(#175682),#169829,.T.); -#175682 = FACE_BOUND('',#175683,.T.); -#175683 = EDGE_LOOP('',(#175684,#175685,#175751,#175752,#175753)); -#175684 = ORIENTED_EDGE('',*,*,#173499,.F.); -#175685 = ORIENTED_EDGE('',*,*,#175686,.T.); -#175686 = EDGE_CURVE('',#173478,#169772,#175687,.T.); -#175687 = SURFACE_CURVE('',#175688,(#175693,#175722),.PCURVE_S1.); -#175688 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175689,#175690,#175691, -#175692),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178061 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#178062 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#178063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178064 = ORIENTED_EDGE('',*,*,#177539,.T.); +#178065 = ORIENTED_EDGE('',*,*,#178019,.T.); +#178066 = ADVANCED_FACE('',(#178067),#177231,.F.); +#178067 = FACE_BOUND('',#178068,.F.); +#178068 = EDGE_LOOP('',(#178069,#178070,#178071,#178072)); +#178069 = ORIENTED_EDGE('',*,*,#177597,.T.); +#178070 = ORIENTED_EDGE('',*,*,#178045,.F.); +#178071 = ORIENTED_EDGE('',*,*,#177567,.F.); +#178072 = ORIENTED_EDGE('',*,*,#177215,.T.); +#178073 = ADVANCED_FACE('',(#178074),#172221,.T.); +#178074 = FACE_BOUND('',#178075,.T.); +#178075 = EDGE_LOOP('',(#178076,#178077,#178143,#178144,#178145)); +#178076 = ORIENTED_EDGE('',*,*,#175891,.F.); +#178077 = ORIENTED_EDGE('',*,*,#178078,.T.); +#178078 = EDGE_CURVE('',#175870,#172164,#178079,.T.); +#178079 = SURFACE_CURVE('',#178080,(#178085,#178114),.PCURVE_S1.); +#178080 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178081,#178082,#178083, +#178084),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#175689 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, +#178081 = CARTESIAN_POINT('',(-1.174271552513,-0.649160426457, 1.162940952255)); -#175690 = CARTESIAN_POINT('',(-1.213215504454,-0.648328016991, +#178082 = CARTESIAN_POINT('',(-1.213215504454,-0.648328016991, 1.166047546673)); -#175691 = CARTESIAN_POINT('',(-1.24878608255,-0.633243924364,1.167717466 +#178083 = CARTESIAN_POINT('',(-1.24878608255,-0.633243924364,1.167717466 )); -#175692 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, +#178084 = CARTESIAN_POINT('',(-1.276015003457,-0.606015003457, 1.167717466)); -#175693 = PCURVE('',#169829,#175694); -#175694 = DEFINITIONAL_REPRESENTATION('',(#175695),#175721); -#175695 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175696,#175697,#175698, - #175699,#175700,#175701,#175702,#175703,#175704,#175705,#175706, - #175707,#175708,#175709,#175710,#175711,#175712,#175713,#175714, - #175715,#175716,#175717,#175718,#175719,#175720),.UNSPECIFIED.,.F., +#178085 = PCURVE('',#172221,#178086); +#178086 = DEFINITIONAL_REPRESENTATION('',(#178087),#178113); +#178087 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178088,#178089,#178090, + #178091,#178092,#178093,#178094,#178095,#178096,#178097,#178098, + #178099,#178100,#178101,#178102,#178103,#178104,#178105,#178106, + #178107,#178108,#178109,#178110,#178111,#178112),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -217464,40 +220466,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#175696 = CARTESIAN_POINT('',(4.77942647859,-0.63830681082)); -#175697 = CARTESIAN_POINT('',(4.790552085824,-0.638018853161)); -#175698 = CARTESIAN_POINT('',(4.812874135705,-0.637451403942)); -#175699 = CARTESIAN_POINT('',(4.846552114392,-0.636627528948)); -#175700 = CARTESIAN_POINT('',(4.880407630888,-0.635832876948)); -#175701 = CARTESIAN_POINT('',(4.914422492066,-0.635069289453)); -#175702 = CARTESIAN_POINT('',(4.948578027862,-0.634338537887)); -#175703 = CARTESIAN_POINT('',(4.98285506838,-0.633642304667)); -#175704 = CARTESIAN_POINT('',(5.017234026195,-0.632982173279)); -#175705 = CARTESIAN_POINT('',(5.051694955172,-0.632359616715)); -#175706 = CARTESIAN_POINT('',(5.086217619636,-0.631775987301)); -#175707 = CARTESIAN_POINT('',(5.120781564146,-0.631232507307)); -#175708 = CARTESIAN_POINT('',(5.155366185737,-0.630730260665)); -#175709 = CARTESIAN_POINT('',(5.189950807328,-0.630270185855)); -#175710 = CARTESIAN_POINT('',(5.224514751839,-0.629853070079)); -#175711 = CARTESIAN_POINT('',(5.259037416303,-0.629479544784)); -#175712 = CARTESIAN_POINT('',(5.293498345279,-0.629150082601)); -#175713 = CARTESIAN_POINT('',(5.327877303094,-0.628864995698)); -#175714 = CARTESIAN_POINT('',(5.362154343612,-0.628624435674)); -#175715 = CARTESIAN_POINT('',(5.396309879408,-0.628428394479)); -#175716 = CARTESIAN_POINT('',(5.430324740587,-0.628276708263)); -#175717 = CARTESIAN_POINT('',(5.464180257082,-0.628169056716)); -#175718 = CARTESIAN_POINT('',(5.49785823577,-0.628104985434)); -#175719 = CARTESIAN_POINT('',(5.52018028565,-0.628090893864)); -#175720 = CARTESIAN_POINT('',(5.531305892885,-0.628090905151)); -#175721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175722 = PCURVE('',#169902,#175723); -#175723 = DEFINITIONAL_REPRESENTATION('',(#175724),#175750); -#175724 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175725,#175726,#175727, - #175728,#175729,#175730,#175731,#175732,#175733,#175734,#175735, - #175736,#175737,#175738,#175739,#175740,#175741,#175742,#175743, - #175744,#175745,#175746,#175747,#175748,#175749),.UNSPECIFIED.,.F., +#178088 = CARTESIAN_POINT('',(4.77942647859,-0.63830681082)); +#178089 = CARTESIAN_POINT('',(4.790552085824,-0.638018853161)); +#178090 = CARTESIAN_POINT('',(4.812874135705,-0.637451403942)); +#178091 = CARTESIAN_POINT('',(4.846552114392,-0.636627528948)); +#178092 = CARTESIAN_POINT('',(4.880407630888,-0.635832876948)); +#178093 = CARTESIAN_POINT('',(4.914422492066,-0.635069289453)); +#178094 = CARTESIAN_POINT('',(4.948578027862,-0.634338537887)); +#178095 = CARTESIAN_POINT('',(4.98285506838,-0.633642304667)); +#178096 = CARTESIAN_POINT('',(5.017234026195,-0.632982173279)); +#178097 = CARTESIAN_POINT('',(5.051694955172,-0.632359616715)); +#178098 = CARTESIAN_POINT('',(5.086217619636,-0.631775987301)); +#178099 = CARTESIAN_POINT('',(5.120781564146,-0.631232507307)); +#178100 = CARTESIAN_POINT('',(5.155366185737,-0.630730260665)); +#178101 = CARTESIAN_POINT('',(5.189950807328,-0.630270185855)); +#178102 = CARTESIAN_POINT('',(5.224514751839,-0.629853070079)); +#178103 = CARTESIAN_POINT('',(5.259037416303,-0.629479544784)); +#178104 = CARTESIAN_POINT('',(5.293498345279,-0.629150082601)); +#178105 = CARTESIAN_POINT('',(5.327877303094,-0.628864995698)); +#178106 = CARTESIAN_POINT('',(5.362154343612,-0.628624435674)); +#178107 = CARTESIAN_POINT('',(5.396309879408,-0.628428394479)); +#178108 = CARTESIAN_POINT('',(5.430324740587,-0.628276708263)); +#178109 = CARTESIAN_POINT('',(5.464180257082,-0.628169056716)); +#178110 = CARTESIAN_POINT('',(5.49785823577,-0.628104985434)); +#178111 = CARTESIAN_POINT('',(5.52018028565,-0.628090893864)); +#178112 = CARTESIAN_POINT('',(5.531305892885,-0.628090905151)); +#178113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178114 = PCURVE('',#172294,#178115); +#178115 = DEFINITIONAL_REPRESENTATION('',(#178116),#178142); +#178116 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178117,#178118,#178119, + #178120,#178121,#178122,#178123,#178124,#178125,#178126,#178127, + #178128,#178129,#178130,#178131,#178132,#178133,#178134,#178135, + #178136,#178137,#178138,#178139,#178140,#178141),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -217505,56 +220507,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#175725 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#175726 = CARTESIAN_POINT('',(0.740753686904,5.702886390918E-008)); -#175727 = CARTESIAN_POINT('',(0.718425946425,-7.920748673545E-006)); -#175728 = CARTESIAN_POINT('',(0.684729502759,-3.211524036781E-005)); -#175729 = CARTESIAN_POINT('',(0.650851510226,-9.135957814302E-005)); -#175730 = CARTESIAN_POINT('',(0.616817843137,-8.643182883992E-005)); -#175731 = CARTESIAN_POINT('',(0.582648204505,-8.687405903494E-005)); -#175732 = CARTESIAN_POINT('',(0.548364026632,-8.593542635473E-005)); -#175733 = CARTESIAN_POINT('',(0.513985713406,-8.542361824743E-005)); -#175734 = CARTESIAN_POINT('',(0.479533105651,-8.485308429908E-005)); -#175735 = CARTESIAN_POINT('',(0.445025477762,-8.435280861153E-005)); -#175736 = CARTESIAN_POINT('',(0.410481676253,-8.388702468127E-005)); -#175737 = CARTESIAN_POINT('',(0.375920232966,-8.346461194626E-005)); -#175738 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); -#175739 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); -#175740 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); -#175741 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#175742 = CARTESIAN_POINT('',(0.203491552027,-8.179989506529E-005)); -#175743 = CARTESIAN_POINT('',(0.169212469737,-8.226451401255E-005)); -#175744 = CARTESIAN_POINT('',(0.135047837564,-7.965797689872E-005)); -#175745 = CARTESIAN_POINT('',(0.101018376289,-8.868396576237E-005)); -#175746 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095341E-005) - ); -#175747 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467481E-005) - ); -#175748 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804133082E-006)); -#175749 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#175750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175751 = ORIENTED_EDGE('',*,*,#169771,.T.); -#175752 = ORIENTED_EDGE('',*,*,#172966,.F.); -#175753 = ORIENTED_EDGE('',*,*,#175754,.F.); -#175754 = EDGE_CURVE('',#171772,#172217,#175755,.T.); -#175755 = SURFACE_CURVE('',#175756,(#175761,#175790),.PCURVE_S1.); -#175756 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175757,#175758,#175759, -#175760),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178117 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#178118 = CARTESIAN_POINT('',(0.740753686904,5.702886390918E-008)); +#178119 = CARTESIAN_POINT('',(0.718425946425,-7.920748673545E-006)); +#178120 = CARTESIAN_POINT('',(0.684729502759,-3.211524036781E-005)); +#178121 = CARTESIAN_POINT('',(0.650851510226,-9.135957814302E-005)); +#178122 = CARTESIAN_POINT('',(0.616817843137,-8.643182883992E-005)); +#178123 = CARTESIAN_POINT('',(0.582648204505,-8.687405903494E-005)); +#178124 = CARTESIAN_POINT('',(0.548364026632,-8.593542635473E-005)); +#178125 = CARTESIAN_POINT('',(0.513985713406,-8.542361824743E-005)); +#178126 = CARTESIAN_POINT('',(0.479533105651,-8.485308429908E-005)); +#178127 = CARTESIAN_POINT('',(0.445025477762,-8.435280861153E-005)); +#178128 = CARTESIAN_POINT('',(0.410481676253,-8.388702468127E-005)); +#178129 = CARTESIAN_POINT('',(0.375920232966,-8.346461194626E-005)); +#178130 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); +#178131 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); +#178132 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); +#178133 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#178134 = CARTESIAN_POINT('',(0.203491552027,-8.179989506529E-005)); +#178135 = CARTESIAN_POINT('',(0.169212469737,-8.226451401255E-005)); +#178136 = CARTESIAN_POINT('',(0.135047837564,-7.965797689872E-005)); +#178137 = CARTESIAN_POINT('',(0.101018376289,-8.868396576237E-005)); +#178138 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095341E-005) + ); +#178139 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467481E-005) + ); +#178140 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804133082E-006)); +#178141 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#178142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178143 = ORIENTED_EDGE('',*,*,#172163,.T.); +#178144 = ORIENTED_EDGE('',*,*,#175358,.F.); +#178145 = ORIENTED_EDGE('',*,*,#178146,.F.); +#178146 = EDGE_CURVE('',#174164,#174609,#178147,.T.); +#178147 = SURFACE_CURVE('',#178148,(#178153,#178182),.PCURVE_S1.); +#178148 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178149,#178150,#178151, +#178152),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#175757 = CARTESIAN_POINT('',(-1.325111126057,-0.8,0.6)); -#175758 = CARTESIAN_POINT('',(-1.411121542172,-0.8,0.6)); -#175759 = CARTESIAN_POINT('',(-1.47,-0.741121542172,0.6)); -#175760 = CARTESIAN_POINT('',(-1.47,-0.655111126057,0.6)); -#175761 = PCURVE('',#169829,#175762); -#175762 = DEFINITIONAL_REPRESENTATION('',(#175763),#175789); -#175763 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175764,#175765,#175766, - #175767,#175768,#175769,#175770,#175771,#175772,#175773,#175774, - #175775,#175776,#175777,#175778,#175779,#175780,#175781,#175782, - #175783,#175784,#175785,#175786,#175787,#175788),.UNSPECIFIED.,.F., +#178149 = CARTESIAN_POINT('',(-1.325111126057,-0.8,0.6)); +#178150 = CARTESIAN_POINT('',(-1.411121542172,-0.8,0.6)); +#178151 = CARTESIAN_POINT('',(-1.47,-0.741121542172,0.6)); +#178152 = CARTESIAN_POINT('',(-1.47,-0.655111126057,0.6)); +#178153 = PCURVE('',#172221,#178154); +#178154 = DEFINITIONAL_REPRESENTATION('',(#178155),#178181); +#178155 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178156,#178157,#178158, + #178159,#178160,#178161,#178162,#178163,#178164,#178165,#178166, + #178167,#178168,#178169,#178170,#178171,#178172,#178173,#178174, + #178175,#178176,#178177,#178178,#178179,#178180),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -217562,40 +220564,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#175764 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#175765 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); -#175766 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); -#175767 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); -#175768 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); -#175769 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); -#175770 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); -#175771 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); -#175772 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); -#175773 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); -#175774 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); -#175775 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); -#175776 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); -#175777 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); -#175778 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); -#175779 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); -#175780 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); -#175781 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); -#175782 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); -#175783 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); -#175784 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); -#175785 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); -#175786 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); -#175787 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); -#175788 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#175789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175790 = PCURVE('',#169136,#175791); -#175791 = DEFINITIONAL_REPRESENTATION('',(#175792),#175818); -#175792 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175793,#175794,#175795, - #175796,#175797,#175798,#175799,#175800,#175801,#175802,#175803, - #175804,#175805,#175806,#175807,#175808,#175809,#175810,#175811, - #175812,#175813,#175814,#175815,#175816,#175817),.UNSPECIFIED.,.F., +#178156 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#178157 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); +#178158 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); +#178159 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); +#178160 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); +#178161 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); +#178162 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); +#178163 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); +#178164 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); +#178165 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); +#178166 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); +#178167 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); +#178168 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); +#178169 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); +#178170 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); +#178171 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); +#178172 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); +#178173 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); +#178174 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); +#178175 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); +#178176 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); +#178177 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); +#178178 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); +#178179 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); +#178180 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#178181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178182 = PCURVE('',#171528,#178183); +#178183 = DEFINITIONAL_REPRESENTATION('',(#178184),#178210); +#178184 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178185,#178186,#178187, + #178188,#178189,#178190,#178191,#178192,#178193,#178194,#178195, + #178196,#178197,#178198,#178199,#178200,#178201,#178202,#178203, + #178204,#178205,#178206,#178207,#178208,#178209),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -217603,60 +220605,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#175793 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); -#175794 = CARTESIAN_POINT('',(4.624655406418,0.365400225879)); -#175795 = CARTESIAN_POINT('',(4.582751146823,0.366973697443)); -#175796 = CARTESIAN_POINT('',(4.518446530087,0.369208928071)); -#175797 = CARTESIAN_POINT('',(4.452775723043,0.37129480778)); -#175798 = CARTESIAN_POINT('',(4.38584197213,0.373206849898)); -#175799 = CARTESIAN_POINT('',(4.317762259171,0.374921245363)); -#175800 = CARTESIAN_POINT('',(4.248668639375,0.376415470566)); -#175801 = CARTESIAN_POINT('',(4.178706688026,0.37766897808)); -#175802 = CARTESIAN_POINT('',(4.108034183076,0.378663857621)); -#175803 = CARTESIAN_POINT('',(4.036819204936,0.379385451047)); -#175804 = CARTESIAN_POINT('',(3.965237921948,0.379822878243)); -#175805 = CARTESIAN_POINT('',(3.893472067885,0.379969441183)); -#175806 = CARTESIAN_POINT('',(3.821706213821,0.379822878243)); -#175807 = CARTESIAN_POINT('',(3.750124930834,0.379385451047)); -#175808 = CARTESIAN_POINT('',(3.678909952694,0.378663857621)); -#175809 = CARTESIAN_POINT('',(3.608237447743,0.37766897808)); -#175810 = CARTESIAN_POINT('',(3.538275496395,0.376415470566)); -#175811 = CARTESIAN_POINT('',(3.469181876598,0.374921245363)); -#175812 = CARTESIAN_POINT('',(3.401102163639,0.373206849898)); -#175813 = CARTESIAN_POINT('',(3.334168412726,0.37129480778)); -#175814 = CARTESIAN_POINT('',(3.268497605682,0.369208928071)); -#175815 = CARTESIAN_POINT('',(3.204192988946,0.366973697443)); -#175816 = CARTESIAN_POINT('',(3.162288729352,0.365400225879)); -#175817 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); -#175818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175819 = ADVANCED_FACE('',(#175820),#169136,.T.); -#175820 = FACE_BOUND('',#175821,.T.); -#175821 = EDGE_LOOP('',(#175822,#175823,#175824,#175890,#175891)); -#175822 = ORIENTED_EDGE('',*,*,#172216,.F.); -#175823 = ORIENTED_EDGE('',*,*,#169097,.T.); -#175824 = ORIENTED_EDGE('',*,*,#175825,.T.); -#175825 = EDGE_CURVE('',#169013,#171774,#175826,.T.); -#175826 = SURFACE_CURVE('',#175827,(#175832,#175861),.PCURVE_S1.); -#175827 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175828,#175829,#175830, -#175831),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#178185 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); +#178186 = CARTESIAN_POINT('',(4.624655406418,0.365400225879)); +#178187 = CARTESIAN_POINT('',(4.582751146823,0.366973697443)); +#178188 = CARTESIAN_POINT('',(4.518446530087,0.369208928071)); +#178189 = CARTESIAN_POINT('',(4.452775723043,0.37129480778)); +#178190 = CARTESIAN_POINT('',(4.38584197213,0.373206849898)); +#178191 = CARTESIAN_POINT('',(4.317762259171,0.374921245363)); +#178192 = CARTESIAN_POINT('',(4.248668639375,0.376415470566)); +#178193 = CARTESIAN_POINT('',(4.178706688026,0.37766897808)); +#178194 = CARTESIAN_POINT('',(4.108034183076,0.378663857621)); +#178195 = CARTESIAN_POINT('',(4.036819204936,0.379385451047)); +#178196 = CARTESIAN_POINT('',(3.965237921948,0.379822878243)); +#178197 = CARTESIAN_POINT('',(3.893472067885,0.379969441183)); +#178198 = CARTESIAN_POINT('',(3.821706213821,0.379822878243)); +#178199 = CARTESIAN_POINT('',(3.750124930834,0.379385451047)); +#178200 = CARTESIAN_POINT('',(3.678909952694,0.378663857621)); +#178201 = CARTESIAN_POINT('',(3.608237447743,0.37766897808)); +#178202 = CARTESIAN_POINT('',(3.538275496395,0.376415470566)); +#178203 = CARTESIAN_POINT('',(3.469181876598,0.374921245363)); +#178204 = CARTESIAN_POINT('',(3.401102163639,0.373206849898)); +#178205 = CARTESIAN_POINT('',(3.334168412726,0.37129480778)); +#178206 = CARTESIAN_POINT('',(3.268497605682,0.369208928071)); +#178207 = CARTESIAN_POINT('',(3.204192988946,0.366973697443)); +#178208 = CARTESIAN_POINT('',(3.162288729352,0.365400225879)); +#178209 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); +#178210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178211 = ADVANCED_FACE('',(#178212),#171528,.T.); +#178212 = FACE_BOUND('',#178213,.T.); +#178213 = EDGE_LOOP('',(#178214,#178215,#178216,#178282,#178283)); +#178214 = ORIENTED_EDGE('',*,*,#174608,.F.); +#178215 = ORIENTED_EDGE('',*,*,#171489,.T.); +#178216 = ORIENTED_EDGE('',*,*,#178217,.T.); +#178217 = EDGE_CURVE('',#171405,#174166,#178218,.T.); +#178218 = SURFACE_CURVE('',#178219,(#178224,#178253),.PCURVE_S1.); +#178219 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178220,#178221,#178222, +#178223),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#175828 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); -#175829 = CARTESIAN_POINT('',(-1.275581001793,-0.660038843607, +#178220 = CARTESIAN_POINT('',(-1.3028099227,-0.6328099227,0.132282534)); +#178221 = CARTESIAN_POINT('',(-1.275581001793,-0.660038843607, 0.132282534)); -#175830 = CARTESIAN_POINT('',(-1.240010423697,-0.675122936235, +#178222 = CARTESIAN_POINT('',(-1.240010423697,-0.675122936235, 0.133952453327)); -#175831 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, +#178223 = CARTESIAN_POINT('',(-1.201066471757,-0.6759553457, 0.137059047745)); -#175832 = PCURVE('',#169136,#175833); -#175833 = DEFINITIONAL_REPRESENTATION('',(#175834),#175860); -#175834 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175835,#175836,#175837, - #175838,#175839,#175840,#175841,#175842,#175843,#175844,#175845, - #175846,#175847,#175848,#175849,#175850,#175851,#175852,#175853, - #175854,#175855,#175856,#175857,#175858,#175859),.UNSPECIFIED.,.F., +#178224 = PCURVE('',#171528,#178225); +#178225 = DEFINITIONAL_REPRESENTATION('',(#178226),#178252); +#178226 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178227,#178228,#178229, + #178230,#178231,#178232,#178233,#178234,#178235,#178236,#178237, + #178238,#178239,#178240,#178241,#178242,#178243,#178244,#178245, + #178246,#178247,#178248,#178249,#178250,#178251),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -217664,40 +220666,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#175835 = CARTESIAN_POINT('',(3.893472067885,-0.120251480798)); -#175836 = CARTESIAN_POINT('',(3.90459767512,-0.120251469511)); -#175837 = CARTESIAN_POINT('',(3.926919725,-0.120265561081)); -#175838 = CARTESIAN_POINT('',(3.960597703687,-0.120329632363)); -#175839 = CARTESIAN_POINT('',(3.994453220183,-0.120437283911)); -#175840 = CARTESIAN_POINT('',(4.028468081361,-0.120588970126)); -#175841 = CARTESIAN_POINT('',(4.062623617158,-0.120785011321)); -#175842 = CARTESIAN_POINT('',(4.096900657675,-0.121025571345)); -#175843 = CARTESIAN_POINT('',(4.13127961549,-0.121310658249)); -#175844 = CARTESIAN_POINT('',(4.165740544467,-0.121640120431)); -#175845 = CARTESIAN_POINT('',(4.200263208931,-0.122013645726)); -#175846 = CARTESIAN_POINT('',(4.234827153442,-0.122430761502)); -#175847 = CARTESIAN_POINT('',(4.269411775032,-0.122890836312)); -#175848 = CARTESIAN_POINT('',(4.303996396623,-0.123393082955)); -#175849 = CARTESIAN_POINT('',(4.338560341134,-0.123936562949)); -#175850 = CARTESIAN_POINT('',(4.373083005598,-0.124520192363)); -#175851 = CARTESIAN_POINT('',(4.407543934574,-0.125142748927)); -#175852 = CARTESIAN_POINT('',(4.44192289239,-0.125802880314)); -#175853 = CARTESIAN_POINT('',(4.476199932907,-0.126499113534)); -#175854 = CARTESIAN_POINT('',(4.510355468703,-0.127229865101)); -#175855 = CARTESIAN_POINT('',(4.544370329882,-0.127993452596)); -#175856 = CARTESIAN_POINT('',(4.578225846377,-0.128788104595)); -#175857 = CARTESIAN_POINT('',(4.611903825065,-0.129611979589)); -#175858 = CARTESIAN_POINT('',(4.634225874945,-0.130179428809)); -#175859 = CARTESIAN_POINT('',(4.64535148218,-0.130467386467)); -#175860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175861 = PCURVE('',#169051,#175862); -#175862 = DEFINITIONAL_REPRESENTATION('',(#175863),#175889); -#175863 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175864,#175865,#175866, - #175867,#175868,#175869,#175870,#175871,#175872,#175873,#175874, - #175875,#175876,#175877,#175878,#175879,#175880,#175881,#175882, - #175883,#175884,#175885,#175886,#175887,#175888),.UNSPECIFIED.,.F., +#178227 = CARTESIAN_POINT('',(3.893472067885,-0.120251480798)); +#178228 = CARTESIAN_POINT('',(3.90459767512,-0.120251469511)); +#178229 = CARTESIAN_POINT('',(3.926919725,-0.120265561081)); +#178230 = CARTESIAN_POINT('',(3.960597703687,-0.120329632363)); +#178231 = CARTESIAN_POINT('',(3.994453220183,-0.120437283911)); +#178232 = CARTESIAN_POINT('',(4.028468081361,-0.120588970126)); +#178233 = CARTESIAN_POINT('',(4.062623617158,-0.120785011321)); +#178234 = CARTESIAN_POINT('',(4.096900657675,-0.121025571345)); +#178235 = CARTESIAN_POINT('',(4.13127961549,-0.121310658249)); +#178236 = CARTESIAN_POINT('',(4.165740544467,-0.121640120431)); +#178237 = CARTESIAN_POINT('',(4.200263208931,-0.122013645726)); +#178238 = CARTESIAN_POINT('',(4.234827153442,-0.122430761502)); +#178239 = CARTESIAN_POINT('',(4.269411775032,-0.122890836312)); +#178240 = CARTESIAN_POINT('',(4.303996396623,-0.123393082955)); +#178241 = CARTESIAN_POINT('',(4.338560341134,-0.123936562949)); +#178242 = CARTESIAN_POINT('',(4.373083005598,-0.124520192363)); +#178243 = CARTESIAN_POINT('',(4.407543934574,-0.125142748927)); +#178244 = CARTESIAN_POINT('',(4.44192289239,-0.125802880314)); +#178245 = CARTESIAN_POINT('',(4.476199932907,-0.126499113534)); +#178246 = CARTESIAN_POINT('',(4.510355468703,-0.127229865101)); +#178247 = CARTESIAN_POINT('',(4.544370329882,-0.127993452596)); +#178248 = CARTESIAN_POINT('',(4.578225846377,-0.128788104595)); +#178249 = CARTESIAN_POINT('',(4.611903825065,-0.129611979589)); +#178250 = CARTESIAN_POINT('',(4.634225874945,-0.130179428809)); +#178251 = CARTESIAN_POINT('',(4.64535148218,-0.130467386467)); +#178252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178253 = PCURVE('',#171443,#178254); +#178254 = DEFINITIONAL_REPRESENTATION('',(#178255),#178281); +#178255 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178256,#178257,#178258, + #178259,#178260,#178261,#178262,#178263,#178264,#178265,#178266, + #178267,#178268,#178269,#178270,#178271,#178272,#178273,#178274, + #178275,#178276,#178277,#178278,#178279,#178280),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -217705,62 +220707,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#175864 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#175865 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#175866 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#175867 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#175868 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#175869 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#175870 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#175871 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#175872 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#175873 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#175874 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#175875 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#175876 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#175877 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#175878 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#175879 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#175880 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); -#175881 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); -#175882 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); -#175883 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); -#175884 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); -#175885 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); -#175886 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); -#175887 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); -#175888 = CARTESIAN_POINT('',(0.751879414295,1.)); -#175889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175890 = ORIENTED_EDGE('',*,*,#171771,.F.); -#175891 = ORIENTED_EDGE('',*,*,#175754,.T.); -#175892 = ADVANCED_FACE('',(#175893),#170384,.T.); -#175893 = FACE_BOUND('',#175894,.T.); -#175894 = EDGE_LOOP('',(#175895,#175896,#175962,#175963,#175964)); -#175895 = ORIENTED_EDGE('',*,*,#173054,.F.); -#175896 = ORIENTED_EDGE('',*,*,#175897,.T.); -#175897 = EDGE_CURVE('',#173010,#170327,#175898,.T.); -#175898 = SURFACE_CURVE('',#175899,(#175904,#175933),.PCURVE_S1.); -#175899 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175900,#175901,#175902, -#175903),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178256 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#178257 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#178258 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#178259 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#178260 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#178261 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#178262 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#178263 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#178264 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#178265 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#178266 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#178267 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#178268 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#178269 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#178270 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#178271 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#178272 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); +#178273 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); +#178274 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); +#178275 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); +#178276 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); +#178277 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); +#178278 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); +#178279 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); +#178280 = CARTESIAN_POINT('',(0.751879414295,1.)); +#178281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178282 = ORIENTED_EDGE('',*,*,#174163,.F.); +#178283 = ORIENTED_EDGE('',*,*,#178146,.T.); +#178284 = ADVANCED_FACE('',(#178285),#172776,.T.); +#178285 = FACE_BOUND('',#178286,.T.); +#178286 = EDGE_LOOP('',(#178287,#178288,#178354,#178355,#178356)); +#178287 = ORIENTED_EDGE('',*,*,#175446,.F.); +#178288 = ORIENTED_EDGE('',*,*,#178289,.T.); +#178289 = EDGE_CURVE('',#175402,#172719,#178290,.T.); +#178290 = SURFACE_CURVE('',#178291,(#178296,#178325),.PCURVE_S1.); +#178291 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178292,#178293,#178294, +#178295),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#175900 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, +#178292 = CARTESIAN_POINT('',(-1.319160426457,0.504271552513, 1.162940952255)); -#175901 = CARTESIAN_POINT('',(-1.318328016991,0.543215504454, +#178293 = CARTESIAN_POINT('',(-1.318328016991,0.543215504454, 1.166047546673)); -#175902 = CARTESIAN_POINT('',(-1.303243924364,0.57878608255,1.167717466) +#178294 = CARTESIAN_POINT('',(-1.303243924364,0.57878608255,1.167717466) ); -#175903 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 +#178295 = CARTESIAN_POINT('',(-1.276015003457,0.606015003457,1.167717466 )); -#175904 = PCURVE('',#170384,#175905); -#175905 = DEFINITIONAL_REPRESENTATION('',(#175906),#175932); -#175906 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175907,#175908,#175909, - #175910,#175911,#175912,#175913,#175914,#175915,#175916,#175917, - #175918,#175919,#175920,#175921,#175922,#175923,#175924,#175925, - #175926,#175927,#175928,#175929,#175930,#175931),.UNSPECIFIED.,.F., +#178296 = PCURVE('',#172776,#178297); +#178297 = DEFINITIONAL_REPRESENTATION('',(#178298),#178324); +#178298 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178299,#178300,#178301, + #178302,#178303,#178304,#178305,#178306,#178307,#178308,#178309, + #178310,#178311,#178312,#178313,#178314,#178315,#178316,#178317, + #178318,#178319,#178320,#178321,#178322,#178323),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -217768,40 +220770,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#175907 = CARTESIAN_POINT('',(0.E+000,-0.63830681082)); -#175908 = CARTESIAN_POINT('',(1.112560723485E-002,-0.638018853161)); -#175909 = CARTESIAN_POINT('',(3.344765711494E-002,-0.637451403942)); -#175910 = CARTESIAN_POINT('',(6.712563580238E-002,-0.636627528948)); -#175911 = CARTESIAN_POINT('',(0.100981152298,-0.635832876948)); -#175912 = CARTESIAN_POINT('',(0.134996013476,-0.635069289453)); -#175913 = CARTESIAN_POINT('',(0.169151549273,-0.634338537887)); -#175914 = CARTESIAN_POINT('',(0.20342858979,-0.633642304667)); -#175915 = CARTESIAN_POINT('',(0.237807547605,-0.632982173279)); -#175916 = CARTESIAN_POINT('',(0.272268476582,-0.632359616715)); -#175917 = CARTESIAN_POINT('',(0.306791141046,-0.631775987301)); -#175918 = CARTESIAN_POINT('',(0.341355085557,-0.631232507307)); -#175919 = CARTESIAN_POINT('',(0.375939707147,-0.630730260665)); -#175920 = CARTESIAN_POINT('',(0.410524328738,-0.630270185855)); -#175921 = CARTESIAN_POINT('',(0.445088273249,-0.629853070079)); -#175922 = CARTESIAN_POINT('',(0.479610937713,-0.629479544784)); -#175923 = CARTESIAN_POINT('',(0.51407186669,-0.629150082601)); -#175924 = CARTESIAN_POINT('',(0.548450824505,-0.628864995698)); -#175925 = CARTESIAN_POINT('',(0.582727865022,-0.628624435674)); -#175926 = CARTESIAN_POINT('',(0.616883400819,-0.628428394479)); -#175927 = CARTESIAN_POINT('',(0.650898261997,-0.628276708263)); -#175928 = CARTESIAN_POINT('',(0.684753778493,-0.628169056716)); -#175929 = CARTESIAN_POINT('',(0.71843175718,-0.628104985434)); -#175930 = CARTESIAN_POINT('',(0.74075380706,-0.628090893864)); -#175931 = CARTESIAN_POINT('',(0.751879414295,-0.628090905151)); -#175932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175933 = PCURVE('',#170457,#175934); -#175934 = DEFINITIONAL_REPRESENTATION('',(#175935),#175961); -#175935 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175936,#175937,#175938, - #175939,#175940,#175941,#175942,#175943,#175944,#175945,#175946, - #175947,#175948,#175949,#175950,#175951,#175952,#175953,#175954, - #175955,#175956,#175957,#175958,#175959,#175960),.UNSPECIFIED.,.F., +#178299 = CARTESIAN_POINT('',(0.E+000,-0.63830681082)); +#178300 = CARTESIAN_POINT('',(1.112560723485E-002,-0.638018853161)); +#178301 = CARTESIAN_POINT('',(3.344765711494E-002,-0.637451403942)); +#178302 = CARTESIAN_POINT('',(6.712563580238E-002,-0.636627528948)); +#178303 = CARTESIAN_POINT('',(0.100981152298,-0.635832876948)); +#178304 = CARTESIAN_POINT('',(0.134996013476,-0.635069289453)); +#178305 = CARTESIAN_POINT('',(0.169151549273,-0.634338537887)); +#178306 = CARTESIAN_POINT('',(0.20342858979,-0.633642304667)); +#178307 = CARTESIAN_POINT('',(0.237807547605,-0.632982173279)); +#178308 = CARTESIAN_POINT('',(0.272268476582,-0.632359616715)); +#178309 = CARTESIAN_POINT('',(0.306791141046,-0.631775987301)); +#178310 = CARTESIAN_POINT('',(0.341355085557,-0.631232507307)); +#178311 = CARTESIAN_POINT('',(0.375939707147,-0.630730260665)); +#178312 = CARTESIAN_POINT('',(0.410524328738,-0.630270185855)); +#178313 = CARTESIAN_POINT('',(0.445088273249,-0.629853070079)); +#178314 = CARTESIAN_POINT('',(0.479610937713,-0.629479544784)); +#178315 = CARTESIAN_POINT('',(0.51407186669,-0.629150082601)); +#178316 = CARTESIAN_POINT('',(0.548450824505,-0.628864995698)); +#178317 = CARTESIAN_POINT('',(0.582727865022,-0.628624435674)); +#178318 = CARTESIAN_POINT('',(0.616883400819,-0.628428394479)); +#178319 = CARTESIAN_POINT('',(0.650898261997,-0.628276708263)); +#178320 = CARTESIAN_POINT('',(0.684753778493,-0.628169056716)); +#178321 = CARTESIAN_POINT('',(0.71843175718,-0.628104985434)); +#178322 = CARTESIAN_POINT('',(0.74075380706,-0.628090893864)); +#178323 = CARTESIAN_POINT('',(0.751879414295,-0.628090905151)); +#178324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178325 = PCURVE('',#172849,#178326); +#178326 = DEFINITIONAL_REPRESENTATION('',(#178327),#178353); +#178327 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178328,#178329,#178330, + #178331,#178332,#178333,#178334,#178335,#178336,#178337,#178338, + #178339,#178340,#178341,#178342,#178343,#178344,#178345,#178346, + #178347,#178348,#178349,#178350,#178351,#178352),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -217809,56 +220811,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#175936 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#175937 = CARTESIAN_POINT('',(0.740753686904,5.712075686879E-008)); -#175938 = CARTESIAN_POINT('',(0.718425946425,-7.920681087551E-006)); -#175939 = CARTESIAN_POINT('',(0.684729502759,-3.211561473272E-005)); -#175940 = CARTESIAN_POINT('',(0.650851510226,-9.13581482616E-005)); -#175941 = CARTESIAN_POINT('',(0.616817843137,-8.643221197549E-005)); -#175942 = CARTESIAN_POINT('',(0.582648204505,-8.687395637408E-005)); -#175943 = CARTESIAN_POINT('',(0.548364026632,-8.593545386263E-005)); -#175944 = CARTESIAN_POINT('',(0.513985713406,-8.542361087671E-005)); -#175945 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); -#175946 = CARTESIAN_POINT('',(0.445025477762,-8.435280808233E-005)); -#175947 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); -#175948 = CARTESIAN_POINT('',(0.375920232966,-8.346461190826E-005)); -#175949 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); -#175950 = CARTESIAN_POINT('',(0.306817755739,-8.274098333128E-005)); -#175951 = CARTESIAN_POINT('',(0.272313393703,-8.242390084209E-005)); -#175952 = CARTESIAN_POINT('',(0.237865006819,-8.220472162592E-005)); -#175953 = CARTESIAN_POINT('',(0.203491552027,-8.179989506532E-005)); -#175954 = CARTESIAN_POINT('',(0.169212469737,-8.226451401263E-005)); -#175955 = CARTESIAN_POINT('',(0.135047837564,-7.965797689837E-005)); -#175956 = CARTESIAN_POINT('',(0.101018376289,-8.868396576368E-005)); -#175957 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484094852E-005) - ); -#175958 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467099E-005) - ); -#175959 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134687E-006)); -#175960 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#175961 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#175962 = ORIENTED_EDGE('',*,*,#170326,.T.); -#175963 = ORIENTED_EDGE('',*,*,#171091,.F.); -#175964 = ORIENTED_EDGE('',*,*,#175965,.F.); -#175965 = EDGE_CURVE('',#172122,#171064,#175966,.T.); -#175966 = SURFACE_CURVE('',#175967,(#175972,#176001),.PCURVE_S1.); -#175967 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#175968,#175969,#175970, -#175971),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178328 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#178329 = CARTESIAN_POINT('',(0.740753686904,5.712075686879E-008)); +#178330 = CARTESIAN_POINT('',(0.718425946425,-7.920681087551E-006)); +#178331 = CARTESIAN_POINT('',(0.684729502759,-3.211561473272E-005)); +#178332 = CARTESIAN_POINT('',(0.650851510226,-9.13581482616E-005)); +#178333 = CARTESIAN_POINT('',(0.616817843137,-8.643221197549E-005)); +#178334 = CARTESIAN_POINT('',(0.582648204505,-8.687395637408E-005)); +#178335 = CARTESIAN_POINT('',(0.548364026632,-8.593545386263E-005)); +#178336 = CARTESIAN_POINT('',(0.513985713406,-8.542361087671E-005)); +#178337 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); +#178338 = CARTESIAN_POINT('',(0.445025477762,-8.435280808233E-005)); +#178339 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); +#178340 = CARTESIAN_POINT('',(0.375920232966,-8.346461190826E-005)); +#178341 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); +#178342 = CARTESIAN_POINT('',(0.306817755739,-8.274098333128E-005)); +#178343 = CARTESIAN_POINT('',(0.272313393703,-8.242390084209E-005)); +#178344 = CARTESIAN_POINT('',(0.237865006819,-8.220472162592E-005)); +#178345 = CARTESIAN_POINT('',(0.203491552027,-8.179989506532E-005)); +#178346 = CARTESIAN_POINT('',(0.169212469737,-8.226451401263E-005)); +#178347 = CARTESIAN_POINT('',(0.135047837564,-7.965797689837E-005)); +#178348 = CARTESIAN_POINT('',(0.101018376289,-8.868396576368E-005)); +#178349 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484094852E-005) + ); +#178350 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467099E-005) + ); +#178351 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134687E-006)); +#178352 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#178353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178354 = ORIENTED_EDGE('',*,*,#172718,.T.); +#178355 = ORIENTED_EDGE('',*,*,#173483,.F.); +#178356 = ORIENTED_EDGE('',*,*,#178357,.F.); +#178357 = EDGE_CURVE('',#174514,#173456,#178358,.T.); +#178358 = SURFACE_CURVE('',#178359,(#178364,#178393),.PCURVE_S1.); +#178359 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178360,#178361,#178362, +#178363),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#175968 = CARTESIAN_POINT('',(-1.47,0.655111126057,0.6)); -#175969 = CARTESIAN_POINT('',(-1.47,0.741121542172,0.6)); -#175970 = CARTESIAN_POINT('',(-1.411121542172,0.8,0.6)); -#175971 = CARTESIAN_POINT('',(-1.325111126057,0.8,0.6)); -#175972 = PCURVE('',#170384,#175973); -#175973 = DEFINITIONAL_REPRESENTATION('',(#175974),#176000); -#175974 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#175975,#175976,#175977, - #175978,#175979,#175980,#175981,#175982,#175983,#175984,#175985, - #175986,#175987,#175988,#175989,#175990,#175991,#175992,#175993, - #175994,#175995,#175996,#175997,#175998,#175999),.UNSPECIFIED.,.F., +#178360 = CARTESIAN_POINT('',(-1.47,0.655111126057,0.6)); +#178361 = CARTESIAN_POINT('',(-1.47,0.741121542172,0.6)); +#178362 = CARTESIAN_POINT('',(-1.411121542172,0.8,0.6)); +#178363 = CARTESIAN_POINT('',(-1.325111126057,0.8,0.6)); +#178364 = PCURVE('',#172776,#178365); +#178365 = DEFINITIONAL_REPRESENTATION('',(#178366),#178392); +#178366 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178367,#178368,#178369, + #178370,#178371,#178372,#178373,#178374,#178375,#178376,#178377, + #178378,#178379,#178380,#178381,#178382,#178383,#178384,#178385, + #178386,#178387,#178388,#178389,#178390,#178391),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -217866,41 +220868,41 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#175975 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#175976 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#175977 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) - ); -#175978 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#175979 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#175980 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#175981 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#175982 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#175983 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#175984 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#175985 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#175986 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#175987 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#175988 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#175989 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#175990 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#175991 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#175992 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#175993 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#175994 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#175995 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#175996 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#175997 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#175998 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#175999 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#176000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176001 = PCURVE('',#169686,#176002); -#176002 = DEFINITIONAL_REPRESENTATION('',(#176003),#176029); -#176003 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176004,#176005,#176006, - #176007,#176008,#176009,#176010,#176011,#176012,#176013,#176014, - #176015,#176016,#176017,#176018,#176019,#176020,#176021,#176022, - #176023,#176024,#176025,#176026,#176027,#176028),.UNSPECIFIED.,.F., +#178367 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#178368 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#178369 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) + ); +#178370 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#178371 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#178372 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#178373 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#178374 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#178375 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#178376 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#178377 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#178378 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#178379 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#178380 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#178381 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#178382 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#178383 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#178384 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#178385 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#178386 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#178387 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#178388 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#178389 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#178390 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#178391 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#178392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178393 = PCURVE('',#172078,#178394); +#178394 = DEFINITIONAL_REPRESENTATION('',(#178395),#178421); +#178395 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178396,#178397,#178398, + #178399,#178400,#178401,#178402,#178403,#178404,#178405,#178406, + #178407,#178408,#178409,#178410,#178411,#178412,#178413,#178414, + #178415,#178416,#178417,#178418,#178419,#178420),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -217908,60 +220910,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#176004 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#176005 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); -#176006 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); -#176007 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); -#176008 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); -#176009 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); -#176010 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); -#176011 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); -#176012 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); -#176013 = CARTESIAN_POINT('',(2.604275354486,-2.223663371572E-002)); -#176014 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); -#176015 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); -#176016 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); -#176017 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); -#176018 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); -#176019 = CARTESIAN_POINT('',(2.175151124104,-2.223663371572E-002)); -#176020 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); -#176021 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); -#176022 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); -#176023 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); -#176024 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); -#176025 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); -#176026 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); -#176027 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); -#176028 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#176029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176030 = ADVANCED_FACE('',(#176031),#169686,.T.); -#176031 = FACE_BOUND('',#176032,.T.); -#176032 = EDGE_LOOP('',(#176033,#176034,#176035,#176101,#176102)); -#176033 = ORIENTED_EDGE('',*,*,#172355,.F.); -#176034 = ORIENTED_EDGE('',*,*,#169647,.T.); -#176035 = ORIENTED_EDGE('',*,*,#176036,.T.); -#176036 = EDGE_CURVE('',#169563,#172124,#176037,.T.); -#176037 = SURFACE_CURVE('',#176038,(#176043,#176072),.PCURVE_S1.); -#176038 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176039,#176040,#176041, -#176042),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178396 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#178397 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); +#178398 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); +#178399 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); +#178400 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); +#178401 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); +#178402 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); +#178403 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); +#178404 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); +#178405 = CARTESIAN_POINT('',(2.604275354486,-2.223663371572E-002)); +#178406 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); +#178407 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); +#178408 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); +#178409 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); +#178410 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); +#178411 = CARTESIAN_POINT('',(2.175151124104,-2.223663371572E-002)); +#178412 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); +#178413 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); +#178414 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); +#178415 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); +#178416 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); +#178417 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); +#178418 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); +#178419 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); +#178420 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#178421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178422 = ADVANCED_FACE('',(#178423),#172078,.T.); +#178423 = FACE_BOUND('',#178424,.T.); +#178424 = EDGE_LOOP('',(#178425,#178426,#178427,#178493,#178494)); +#178425 = ORIENTED_EDGE('',*,*,#174747,.F.); +#178426 = ORIENTED_EDGE('',*,*,#172039,.T.); +#178427 = ORIENTED_EDGE('',*,*,#178428,.T.); +#178428 = EDGE_CURVE('',#171955,#174516,#178429,.T.); +#178429 = SURFACE_CURVE('',#178430,(#178435,#178464),.PCURVE_S1.); +#178430 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178431,#178432,#178433, +#178434),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.807003620809E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#176039 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); -#176040 = CARTESIAN_POINT('',(-1.330038843607,0.605581001793,0.132282534 +#178431 = CARTESIAN_POINT('',(-1.3028099227,0.6328099227,0.132282534)); +#178432 = CARTESIAN_POINT('',(-1.330038843607,0.605581001793,0.132282534 )); -#176041 = CARTESIAN_POINT('',(-1.345122936235,0.570010423697, +#178433 = CARTESIAN_POINT('',(-1.345122936235,0.570010423697, 0.133952453327)); -#176042 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, +#178434 = CARTESIAN_POINT('',(-1.3459553457,0.531066471757, 0.137059047745)); -#176043 = PCURVE('',#169686,#176044); -#176044 = DEFINITIONAL_REPRESENTATION('',(#176045),#176071); -#176045 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176046,#176047,#176048, - #176049,#176050,#176051,#176052,#176053,#176054,#176055,#176056, - #176057,#176058,#176059,#176060,#176061,#176062,#176063,#176064, - #176065,#176066,#176067,#176068,#176069,#176070),.UNSPECIFIED.,.F., +#178435 = PCURVE('',#172078,#178436); +#178436 = DEFINITIONAL_REPRESENTATION('',(#178437),#178463); +#178437 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178438,#178439,#178440, + #178441,#178442,#178443,#178444,#178445,#178446,#178447,#178448, + #178449,#178450,#178451,#178452,#178453,#178454,#178455,#178456, + #178457,#178458,#178459,#178460,#178461,#178462),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -217970,40 +220972,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#176046 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#176047 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); -#176048 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); -#176049 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); -#176050 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); -#176051 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); -#176052 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); -#176053 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); -#176054 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); -#176055 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); -#176056 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); -#176057 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); -#176058 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); -#176059 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); -#176060 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); -#176061 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); -#176062 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); -#176063 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); -#176064 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); -#176065 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); -#176066 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); -#176067 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); -#176068 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); -#176069 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); -#176070 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#176071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176072 = PCURVE('',#169601,#176073); -#176073 = DEFINITIONAL_REPRESENTATION('',(#176074),#176100); -#176074 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176075,#176076,#176077, - #176078,#176079,#176080,#176081,#176082,#176083,#176084,#176085, - #176086,#176087,#176088,#176089,#176090,#176091,#176092,#176093, - #176094,#176095,#176096,#176097,#176098,#176099),.UNSPECIFIED.,.F., +#178438 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#178439 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); +#178440 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); +#178441 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); +#178442 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); +#178443 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); +#178444 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); +#178445 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); +#178446 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); +#178447 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); +#178448 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); +#178449 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); +#178450 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); +#178451 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); +#178452 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); +#178453 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); +#178454 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); +#178455 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); +#178456 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); +#178457 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); +#178458 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); +#178459 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); +#178460 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); +#178461 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); +#178462 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#178463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178464 = PCURVE('',#171993,#178465); +#178465 = DEFINITIONAL_REPRESENTATION('',(#178466),#178492); +#178466 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178467,#178468,#178469, + #178470,#178471,#178472,#178473,#178474,#178475,#178476,#178477, + #178478,#178479,#178480,#178481,#178482,#178483,#178484,#178485, + #178486,#178487,#178488,#178489,#178490,#178491),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -218012,62 +221014,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#176075 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#176076 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#176077 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#176078 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#176079 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#176080 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#176081 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#176082 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#176083 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#176084 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#176085 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#176086 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#176087 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#176088 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#176089 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); -#176090 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); -#176091 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); -#176092 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); -#176093 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); -#176094 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); -#176095 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); -#176096 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); -#176097 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); -#176098 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); -#176099 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176101 = ORIENTED_EDGE('',*,*,#172121,.F.); -#176102 = ORIENTED_EDGE('',*,*,#175965,.T.); -#176103 = ADVANCED_FACE('',(#176104),#170109,.T.); -#176104 = FACE_BOUND('',#176105,.T.); -#176105 = EDGE_LOOP('',(#176106,#176107,#176173,#176174,#176175)); -#176106 = ORIENTED_EDGE('',*,*,#172919,.F.); -#176107 = ORIENTED_EDGE('',*,*,#176108,.T.); -#176108 = EDGE_CURVE('',#172875,#170052,#176109,.T.); -#176109 = SURFACE_CURVE('',#176110,(#176115,#176144),.PCURVE_S1.); -#176110 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176111,#176112,#176113, -#176114),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178467 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#178468 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#178469 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#178470 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#178471 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#178472 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#178473 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#178474 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#178475 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#178476 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#178477 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#178478 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#178479 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#178480 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#178481 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); +#178482 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); +#178483 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); +#178484 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); +#178485 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); +#178486 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); +#178487 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); +#178488 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); +#178489 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); +#178490 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); +#178491 = CARTESIAN_POINT('',(0.751879414295,1.)); +#178492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178493 = ORIENTED_EDGE('',*,*,#174513,.F.); +#178494 = ORIENTED_EDGE('',*,*,#178357,.T.); +#178495 = ADVANCED_FACE('',(#178496),#172501,.T.); +#178496 = FACE_BOUND('',#178497,.T.); +#178497 = EDGE_LOOP('',(#178498,#178499,#178565,#178566,#178567)); +#178498 = ORIENTED_EDGE('',*,*,#175311,.F.); +#178499 = ORIENTED_EDGE('',*,*,#178500,.T.); +#178500 = EDGE_CURVE('',#175267,#172444,#178501,.T.); +#178501 = SURFACE_CURVE('',#178502,(#178507,#178536),.PCURVE_S1.); +#178502 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178503,#178504,#178505, +#178506),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#176111 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, +#178503 = CARTESIAN_POINT('',(1.319160426457,-0.504271552513, 1.162940952255)); -#176112 = CARTESIAN_POINT('',(1.318328016991,-0.543215504454, +#178504 = CARTESIAN_POINT('',(1.318328016991,-0.543215504454, 1.166047546673)); -#176113 = CARTESIAN_POINT('',(1.303243924364,-0.57878608255,1.167717466) +#178505 = CARTESIAN_POINT('',(1.303243924364,-0.57878608255,1.167717466) ); -#176114 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 +#178506 = CARTESIAN_POINT('',(1.276015003457,-0.606015003457,1.167717466 )); -#176115 = PCURVE('',#170109,#176116); -#176116 = DEFINITIONAL_REPRESENTATION('',(#176117),#176143); -#176117 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176118,#176119,#176120, - #176121,#176122,#176123,#176124,#176125,#176126,#176127,#176128, - #176129,#176130,#176131,#176132,#176133,#176134,#176135,#176136, - #176137,#176138,#176139,#176140,#176141,#176142),.UNSPECIFIED.,.F., +#178507 = PCURVE('',#172501,#178508); +#178508 = DEFINITIONAL_REPRESENTATION('',(#178509),#178535); +#178509 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178510,#178511,#178512, + #178513,#178514,#178515,#178516,#178517,#178518,#178519,#178520, + #178521,#178522,#178523,#178524,#178525,#178526,#178527,#178528, + #178529,#178530,#178531,#178532,#178533,#178534),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -218075,40 +221077,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176118 = CARTESIAN_POINT('',(3.14159265359,-0.237406319482)); -#176119 = CARTESIAN_POINT('',(3.152718260825,-0.237118361824)); -#176120 = CARTESIAN_POINT('',(3.175040310705,-0.236550912605)); -#176121 = CARTESIAN_POINT('',(3.208718289392,-0.235727037611)); -#176122 = CARTESIAN_POINT('',(3.242573805888,-0.234932385611)); -#176123 = CARTESIAN_POINT('',(3.276588667066,-0.234168798116)); -#176124 = CARTESIAN_POINT('',(3.310744202863,-0.23343804655)); -#176125 = CARTESIAN_POINT('',(3.34502124338,-0.232741813329)); -#176126 = CARTESIAN_POINT('',(3.379400201195,-0.232081681942)); -#176127 = CARTESIAN_POINT('',(3.413861130172,-0.231459125378)); -#176128 = CARTESIAN_POINT('',(3.448383794636,-0.230875495964)); -#176129 = CARTESIAN_POINT('',(3.482947739147,-0.23033201597)); -#176130 = CARTESIAN_POINT('',(3.517532360737,-0.229829769328)); -#176131 = CARTESIAN_POINT('',(3.552116982328,-0.229369694517)); -#176132 = CARTESIAN_POINT('',(3.586680926839,-0.228952578741)); -#176133 = CARTESIAN_POINT('',(3.621203591303,-0.228579053446)); -#176134 = CARTESIAN_POINT('',(3.65566452028,-0.228249591264)); -#176135 = CARTESIAN_POINT('',(3.690043478095,-0.22796450436)); -#176136 = CARTESIAN_POINT('',(3.724320518612,-0.227723944337)); -#176137 = CARTESIAN_POINT('',(3.758476054408,-0.227527903142)); -#176138 = CARTESIAN_POINT('',(3.792490915587,-0.227376216926)); -#176139 = CARTESIAN_POINT('',(3.826346432082,-0.227268565379)); -#176140 = CARTESIAN_POINT('',(3.86002441077,-0.227204494097)); -#176141 = CARTESIAN_POINT('',(3.88234646065,-0.227190402527)); -#176142 = CARTESIAN_POINT('',(3.893472067885,-0.227190413813)); -#176143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176144 = PCURVE('',#170182,#176145); -#176145 = DEFINITIONAL_REPRESENTATION('',(#176146),#176172); -#176146 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176147,#176148,#176149, - #176150,#176151,#176152,#176153,#176154,#176155,#176156,#176157, - #176158,#176159,#176160,#176161,#176162,#176163,#176164,#176165, - #176166,#176167,#176168,#176169,#176170,#176171),.UNSPECIFIED.,.F., +#178510 = CARTESIAN_POINT('',(3.14159265359,-0.237406319482)); +#178511 = CARTESIAN_POINT('',(3.152718260825,-0.237118361824)); +#178512 = CARTESIAN_POINT('',(3.175040310705,-0.236550912605)); +#178513 = CARTESIAN_POINT('',(3.208718289392,-0.235727037611)); +#178514 = CARTESIAN_POINT('',(3.242573805888,-0.234932385611)); +#178515 = CARTESIAN_POINT('',(3.276588667066,-0.234168798116)); +#178516 = CARTESIAN_POINT('',(3.310744202863,-0.23343804655)); +#178517 = CARTESIAN_POINT('',(3.34502124338,-0.232741813329)); +#178518 = CARTESIAN_POINT('',(3.379400201195,-0.232081681942)); +#178519 = CARTESIAN_POINT('',(3.413861130172,-0.231459125378)); +#178520 = CARTESIAN_POINT('',(3.448383794636,-0.230875495964)); +#178521 = CARTESIAN_POINT('',(3.482947739147,-0.23033201597)); +#178522 = CARTESIAN_POINT('',(3.517532360737,-0.229829769328)); +#178523 = CARTESIAN_POINT('',(3.552116982328,-0.229369694517)); +#178524 = CARTESIAN_POINT('',(3.586680926839,-0.228952578741)); +#178525 = CARTESIAN_POINT('',(3.621203591303,-0.228579053446)); +#178526 = CARTESIAN_POINT('',(3.65566452028,-0.228249591264)); +#178527 = CARTESIAN_POINT('',(3.690043478095,-0.22796450436)); +#178528 = CARTESIAN_POINT('',(3.724320518612,-0.227723944337)); +#178529 = CARTESIAN_POINT('',(3.758476054408,-0.227527903142)); +#178530 = CARTESIAN_POINT('',(3.792490915587,-0.227376216926)); +#178531 = CARTESIAN_POINT('',(3.826346432082,-0.227268565379)); +#178532 = CARTESIAN_POINT('',(3.86002441077,-0.227204494097)); +#178533 = CARTESIAN_POINT('',(3.88234646065,-0.227190402527)); +#178534 = CARTESIAN_POINT('',(3.893472067885,-0.227190413813)); +#178535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178536 = PCURVE('',#172574,#178537); +#178537 = DEFINITIONAL_REPRESENTATION('',(#178538),#178564); +#178538 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178539,#178540,#178541, + #178542,#178543,#178544,#178545,#178546,#178547,#178548,#178549, + #178550,#178551,#178552,#178553,#178554,#178555,#178556,#178557, + #178558,#178559,#178560,#178561,#178562,#178563),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -218116,56 +221118,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176147 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176148 = CARTESIAN_POINT('',(0.740753686904,5.712074963404E-008)); -#176149 = CARTESIAN_POINT('',(0.718425946425,-7.920681100656E-006)); -#176150 = CARTESIAN_POINT('',(0.684729502759,-3.211561473987E-005)); -#176151 = CARTESIAN_POINT('',(0.650851510226,-9.135814826637E-005)); -#176152 = CARTESIAN_POINT('',(0.616817843137,-8.643221197421E-005)); -#176153 = CARTESIAN_POINT('',(0.582648204505,-8.687395637442E-005)); -#176154 = CARTESIAN_POINT('',(0.548364026632,-8.593545386253E-005)); -#176155 = CARTESIAN_POINT('',(0.513985713406,-8.542361087674E-005)); -#176156 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); -#176157 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); -#176158 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); -#176159 = CARTESIAN_POINT('',(0.375920232966,-8.346461190826E-005)); -#176160 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); -#176161 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); -#176162 = CARTESIAN_POINT('',(0.272313393703,-8.242390084209E-005)); -#176163 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); -#176164 = CARTESIAN_POINT('',(0.203491552027,-8.179989506536E-005)); -#176165 = CARTESIAN_POINT('',(0.169212469737,-8.226451401248E-005)); -#176166 = CARTESIAN_POINT('',(0.135047837564,-7.96579768989E-005)); -#176167 = CARTESIAN_POINT('',(0.101018376289,-8.868396576171E-005)); -#176168 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095586E-005) - ); -#176169 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467206E-005) - ); -#176170 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135387E-006)); -#176171 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#176172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176173 = ORIENTED_EDGE('',*,*,#170051,.T.); -#176174 = ORIENTED_EDGE('',*,*,#173434,.F.); -#176175 = ORIENTED_EDGE('',*,*,#176176,.F.); -#176176 = EDGE_CURVE('',#171603,#171844,#176177,.T.); -#176177 = SURFACE_CURVE('',#176178,(#176183,#176212),.PCURVE_S1.); -#176178 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176179,#176180,#176181, -#176182),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178539 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#178540 = CARTESIAN_POINT('',(0.740753686904,5.712074963404E-008)); +#178541 = CARTESIAN_POINT('',(0.718425946425,-7.920681100656E-006)); +#178542 = CARTESIAN_POINT('',(0.684729502759,-3.211561473987E-005)); +#178543 = CARTESIAN_POINT('',(0.650851510226,-9.135814826637E-005)); +#178544 = CARTESIAN_POINT('',(0.616817843137,-8.643221197421E-005)); +#178545 = CARTESIAN_POINT('',(0.582648204505,-8.687395637442E-005)); +#178546 = CARTESIAN_POINT('',(0.548364026632,-8.593545386253E-005)); +#178547 = CARTESIAN_POINT('',(0.513985713406,-8.542361087674E-005)); +#178548 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); +#178549 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); +#178550 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); +#178551 = CARTESIAN_POINT('',(0.375920232966,-8.346461190826E-005)); +#178552 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); +#178553 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); +#178554 = CARTESIAN_POINT('',(0.272313393703,-8.242390084209E-005)); +#178555 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); +#178556 = CARTESIAN_POINT('',(0.203491552027,-8.179989506536E-005)); +#178557 = CARTESIAN_POINT('',(0.169212469737,-8.226451401248E-005)); +#178558 = CARTESIAN_POINT('',(0.135047837564,-7.96579768989E-005)); +#178559 = CARTESIAN_POINT('',(0.101018376289,-8.868396576171E-005)); +#178560 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095586E-005) + ); +#178561 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467206E-005) + ); +#178562 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135387E-006)); +#178563 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#178564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178565 = ORIENTED_EDGE('',*,*,#172443,.T.); +#178566 = ORIENTED_EDGE('',*,*,#175826,.F.); +#178567 = ORIENTED_EDGE('',*,*,#178568,.F.); +#178568 = EDGE_CURVE('',#173995,#174236,#178569,.T.); +#178569 = SURFACE_CURVE('',#178570,(#178575,#178604),.PCURVE_S1.); +#178570 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178571,#178572,#178573, +#178574),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#176179 = CARTESIAN_POINT('',(1.47,-0.655111126057,0.6)); -#176180 = CARTESIAN_POINT('',(1.47,-0.741121542172,0.6)); -#176181 = CARTESIAN_POINT('',(1.411121542172,-0.8,0.6)); -#176182 = CARTESIAN_POINT('',(1.325111126057,-0.8,0.6)); -#176183 = PCURVE('',#170109,#176184); -#176184 = DEFINITIONAL_REPRESENTATION('',(#176185),#176211); -#176185 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176186,#176187,#176188, - #176189,#176190,#176191,#176192,#176193,#176194,#176195,#176196, - #176197,#176198,#176199,#176200,#176201,#176202,#176203,#176204, - #176205,#176206,#176207,#176208,#176209,#176210),.UNSPECIFIED.,.F., +#178571 = CARTESIAN_POINT('',(1.47,-0.655111126057,0.6)); +#178572 = CARTESIAN_POINT('',(1.47,-0.741121542172,0.6)); +#178573 = CARTESIAN_POINT('',(1.411121542172,-0.8,0.6)); +#178574 = CARTESIAN_POINT('',(1.325111126057,-0.8,0.6)); +#178575 = PCURVE('',#172501,#178576); +#178576 = DEFINITIONAL_REPRESENTATION('',(#178577),#178603); +#178577 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178578,#178579,#178580, + #178581,#178582,#178583,#178584,#178585,#178586,#178587,#178588, + #178589,#178590,#178591,#178592,#178593,#178594,#178595,#178596, + #178597,#178598,#178599,#178600,#178601,#178602),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -218173,40 +221175,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#176186 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); -#176187 = CARTESIAN_POINT('',(3.162288729352,0.365400225879)); -#176188 = CARTESIAN_POINT('',(3.204192988946,0.366973697443)); -#176189 = CARTESIAN_POINT('',(3.268497605682,0.369208928071)); -#176190 = CARTESIAN_POINT('',(3.334168412726,0.37129480778)); -#176191 = CARTESIAN_POINT('',(3.401102163639,0.373206849898)); -#176192 = CARTESIAN_POINT('',(3.469181876599,0.374921245363)); -#176193 = CARTESIAN_POINT('',(3.538275496395,0.376415470566)); -#176194 = CARTESIAN_POINT('',(3.608237447743,0.37766897808)); -#176195 = CARTESIAN_POINT('',(3.678909952694,0.378663857621)); -#176196 = CARTESIAN_POINT('',(3.750124930834,0.379385451047)); -#176197 = CARTESIAN_POINT('',(3.821706213821,0.379822878243)); -#176198 = CARTESIAN_POINT('',(3.893472067885,0.379969441183)); -#176199 = CARTESIAN_POINT('',(3.965237921948,0.379822878243)); -#176200 = CARTESIAN_POINT('',(4.036819204936,0.379385451047)); -#176201 = CARTESIAN_POINT('',(4.108034183076,0.378663857621)); -#176202 = CARTESIAN_POINT('',(4.178706688026,0.37766897808)); -#176203 = CARTESIAN_POINT('',(4.248668639375,0.376415470566)); -#176204 = CARTESIAN_POINT('',(4.317762259171,0.374921245363)); -#176205 = CARTESIAN_POINT('',(4.38584197213,0.373206849898)); -#176206 = CARTESIAN_POINT('',(4.452775723043,0.37129480778)); -#176207 = CARTESIAN_POINT('',(4.518446530087,0.369208928071)); -#176208 = CARTESIAN_POINT('',(4.582751146823,0.366973697443)); -#176209 = CARTESIAN_POINT('',(4.624655406418,0.365400225879)); -#176210 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); -#176211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176212 = PCURVE('',#168838,#176213); -#176213 = DEFINITIONAL_REPRESENTATION('',(#176214),#176240); -#176214 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176215,#176216,#176217, - #176218,#176219,#176220,#176221,#176222,#176223,#176224,#176225, - #176226,#176227,#176228,#176229,#176230,#176231,#176232,#176233, - #176234,#176235,#176236,#176237,#176238,#176239),.UNSPECIFIED.,.F., +#178578 = CARTESIAN_POINT('',(3.14159265359,0.364596728366)); +#178579 = CARTESIAN_POINT('',(3.162288729352,0.365400225879)); +#178580 = CARTESIAN_POINT('',(3.204192988946,0.366973697443)); +#178581 = CARTESIAN_POINT('',(3.268497605682,0.369208928071)); +#178582 = CARTESIAN_POINT('',(3.334168412726,0.37129480778)); +#178583 = CARTESIAN_POINT('',(3.401102163639,0.373206849898)); +#178584 = CARTESIAN_POINT('',(3.469181876599,0.374921245363)); +#178585 = CARTESIAN_POINT('',(3.538275496395,0.376415470566)); +#178586 = CARTESIAN_POINT('',(3.608237447743,0.37766897808)); +#178587 = CARTESIAN_POINT('',(3.678909952694,0.378663857621)); +#178588 = CARTESIAN_POINT('',(3.750124930834,0.379385451047)); +#178589 = CARTESIAN_POINT('',(3.821706213821,0.379822878243)); +#178590 = CARTESIAN_POINT('',(3.893472067885,0.379969441183)); +#178591 = CARTESIAN_POINT('',(3.965237921948,0.379822878243)); +#178592 = CARTESIAN_POINT('',(4.036819204936,0.379385451047)); +#178593 = CARTESIAN_POINT('',(4.108034183076,0.378663857621)); +#178594 = CARTESIAN_POINT('',(4.178706688026,0.37766897808)); +#178595 = CARTESIAN_POINT('',(4.248668639375,0.376415470566)); +#178596 = CARTESIAN_POINT('',(4.317762259171,0.374921245363)); +#178597 = CARTESIAN_POINT('',(4.38584197213,0.373206849898)); +#178598 = CARTESIAN_POINT('',(4.452775723043,0.37129480778)); +#178599 = CARTESIAN_POINT('',(4.518446530087,0.369208928071)); +#178600 = CARTESIAN_POINT('',(4.582751146823,0.366973697443)); +#178601 = CARTESIAN_POINT('',(4.624655406418,0.365400225879)); +#178602 = CARTESIAN_POINT('',(4.64535148218,0.364596728366)); +#178603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178604 = PCURVE('',#171230,#178605); +#178605 = DEFINITIONAL_REPRESENTATION('',(#178606),#178632); +#178606 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178607,#178608,#178609, + #178610,#178611,#178612,#178613,#178614,#178615,#178616,#178617, + #178618,#178619,#178620,#178621,#178622,#178623,#178624,#178625, + #178626,#178627,#178628,#178629,#178630,#178631),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -218214,60 +221216,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#176215 = CARTESIAN_POINT('',(6.28318530718,0.700350889861)); -#176216 = CARTESIAN_POINT('',(6.262489231417,0.701154387374)); -#176217 = CARTESIAN_POINT('',(6.220584971823,0.702727858938)); -#176218 = CARTESIAN_POINT('',(6.156280355087,0.704963089566)); -#176219 = CARTESIAN_POINT('',(6.090609548043,0.707048969275)); -#176220 = CARTESIAN_POINT('',(6.02367579713,0.708961011393)); -#176221 = CARTESIAN_POINT('',(5.955596084171,0.710675406858)); -#176222 = CARTESIAN_POINT('',(5.886502464374,0.712169632061)); -#176223 = CARTESIAN_POINT('',(5.816540513026,0.713423139575)); -#176224 = CARTESIAN_POINT('',(5.745868008076,0.714418019116)); -#176225 = CARTESIAN_POINT('',(5.674653029936,0.715139612542)); -#176226 = CARTESIAN_POINT('',(5.603071746948,0.715577039738)); -#176227 = CARTESIAN_POINT('',(5.531305892885,0.715723602678)); -#176228 = CARTESIAN_POINT('',(5.459540038821,0.715577039738)); -#176229 = CARTESIAN_POINT('',(5.387958755834,0.715139612542)); -#176230 = CARTESIAN_POINT('',(5.316743777694,0.714418019116)); -#176231 = CARTESIAN_POINT('',(5.246071272743,0.713423139575)); -#176232 = CARTESIAN_POINT('',(5.176109321395,0.712169632061)); -#176233 = CARTESIAN_POINT('',(5.107015701598,0.710675406858)); -#176234 = CARTESIAN_POINT('',(5.038935988639,0.708961011393)); -#176235 = CARTESIAN_POINT('',(4.972002237726,0.707048969275)); -#176236 = CARTESIAN_POINT('',(4.906331430682,0.704963089566)); -#176237 = CARTESIAN_POINT('',(4.842026813946,0.702727858938)); -#176238 = CARTESIAN_POINT('',(4.800122554352,0.701154387374)); -#176239 = CARTESIAN_POINT('',(4.77942647859,0.700350889861)); -#176240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176241 = ADVANCED_FACE('',(#176242),#168838,.T.); -#176242 = FACE_BOUND('',#176243,.T.); -#176243 = EDGE_LOOP('',(#176244,#176245,#176246,#176312,#176313)); -#176244 = ORIENTED_EDGE('',*,*,#171843,.F.); -#176245 = ORIENTED_EDGE('',*,*,#168799,.T.); -#176246 = ORIENTED_EDGE('',*,*,#176247,.T.); -#176247 = EDGE_CURVE('',#168715,#171605,#176248,.T.); -#176248 = SURFACE_CURVE('',#176249,(#176254,#176283),.PCURVE_S1.); -#176249 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176250,#176251,#176252, -#176253),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178607 = CARTESIAN_POINT('',(6.28318530718,0.700350889861)); +#178608 = CARTESIAN_POINT('',(6.262489231417,0.701154387374)); +#178609 = CARTESIAN_POINT('',(6.220584971823,0.702727858938)); +#178610 = CARTESIAN_POINT('',(6.156280355087,0.704963089566)); +#178611 = CARTESIAN_POINT('',(6.090609548043,0.707048969275)); +#178612 = CARTESIAN_POINT('',(6.02367579713,0.708961011393)); +#178613 = CARTESIAN_POINT('',(5.955596084171,0.710675406858)); +#178614 = CARTESIAN_POINT('',(5.886502464374,0.712169632061)); +#178615 = CARTESIAN_POINT('',(5.816540513026,0.713423139575)); +#178616 = CARTESIAN_POINT('',(5.745868008076,0.714418019116)); +#178617 = CARTESIAN_POINT('',(5.674653029936,0.715139612542)); +#178618 = CARTESIAN_POINT('',(5.603071746948,0.715577039738)); +#178619 = CARTESIAN_POINT('',(5.531305892885,0.715723602678)); +#178620 = CARTESIAN_POINT('',(5.459540038821,0.715577039738)); +#178621 = CARTESIAN_POINT('',(5.387958755834,0.715139612542)); +#178622 = CARTESIAN_POINT('',(5.316743777694,0.714418019116)); +#178623 = CARTESIAN_POINT('',(5.246071272743,0.713423139575)); +#178624 = CARTESIAN_POINT('',(5.176109321395,0.712169632061)); +#178625 = CARTESIAN_POINT('',(5.107015701598,0.710675406858)); +#178626 = CARTESIAN_POINT('',(5.038935988639,0.708961011393)); +#178627 = CARTESIAN_POINT('',(4.972002237726,0.707048969275)); +#178628 = CARTESIAN_POINT('',(4.906331430682,0.704963089566)); +#178629 = CARTESIAN_POINT('',(4.842026813946,0.702727858938)); +#178630 = CARTESIAN_POINT('',(4.800122554352,0.701154387374)); +#178631 = CARTESIAN_POINT('',(4.77942647859,0.700350889861)); +#178632 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178633 = ADVANCED_FACE('',(#178634),#171230,.T.); +#178634 = FACE_BOUND('',#178635,.T.); +#178635 = EDGE_LOOP('',(#178636,#178637,#178638,#178704,#178705)); +#178636 = ORIENTED_EDGE('',*,*,#174235,.F.); +#178637 = ORIENTED_EDGE('',*,*,#171191,.T.); +#178638 = ORIENTED_EDGE('',*,*,#178639,.T.); +#178639 = EDGE_CURVE('',#171107,#173997,#178640,.T.); +#178640 = SURFACE_CURVE('',#178641,(#178646,#178675),.PCURVE_S1.); +#178641 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178642,#178643,#178644, +#178645),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#176250 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); -#176251 = CARTESIAN_POINT('',(1.330038843607,-0.605581001793,0.132282534 +#178642 = CARTESIAN_POINT('',(1.3028099227,-0.6328099227,0.132282534)); +#178643 = CARTESIAN_POINT('',(1.330038843607,-0.605581001793,0.132282534 )); -#176252 = CARTESIAN_POINT('',(1.345122936235,-0.570010423697, +#178644 = CARTESIAN_POINT('',(1.345122936235,-0.570010423697, 0.133952453327)); -#176253 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, +#178645 = CARTESIAN_POINT('',(1.3459553457,-0.531066471757, 0.137059047745)); -#176254 = PCURVE('',#168838,#176255); -#176255 = DEFINITIONAL_REPRESENTATION('',(#176256),#176282); -#176256 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176257,#176258,#176259, - #176260,#176261,#176262,#176263,#176264,#176265,#176266,#176267, - #176268,#176269,#176270,#176271,#176272,#176273,#176274,#176275, - #176276,#176277,#176278,#176279,#176280,#176281),.UNSPECIFIED.,.F., +#178646 = PCURVE('',#171230,#178647); +#178647 = DEFINITIONAL_REPRESENTATION('',(#178648),#178674); +#178648 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178649,#178650,#178651, + #178652,#178653,#178654,#178655,#178656,#178657,#178658,#178659, + #178660,#178661,#178662,#178663,#178664,#178665,#178666,#178667, + #178668,#178669,#178670,#178671,#178672,#178673),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -218276,40 +221278,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#176257 = CARTESIAN_POINT('',(5.531305892885,0.215502680697)); -#176258 = CARTESIAN_POINT('',(5.542431500119,0.215502691983)); -#176259 = CARTESIAN_POINT('',(5.56475355,0.215488600414)); -#176260 = CARTESIAN_POINT('',(5.598431528687,0.215424529131)); -#176261 = CARTESIAN_POINT('',(5.632287045183,0.215316877584)); -#176262 = CARTESIAN_POINT('',(5.666301906361,0.215165191368)); -#176263 = CARTESIAN_POINT('',(5.700457442157,0.214969150173)); -#176264 = CARTESIAN_POINT('',(5.734734482675,0.21472859015)); -#176265 = CARTESIAN_POINT('',(5.76911344049,0.214443503246)); -#176266 = CARTESIAN_POINT('',(5.803574369467,0.214114041064)); -#176267 = CARTESIAN_POINT('',(5.838097033931,0.213740515769)); -#176268 = CARTESIAN_POINT('',(5.872660978441,0.213323399993)); -#176269 = CARTESIAN_POINT('',(5.907245600032,0.212863325183)); -#176270 = CARTESIAN_POINT('',(5.941830221623,0.21236107854)); -#176271 = CARTESIAN_POINT('',(5.976394166134,0.211817598546)); -#176272 = CARTESIAN_POINT('',(6.010916830598,0.211233969132)); -#176273 = CARTESIAN_POINT('',(6.045377759574,0.210611412568)); -#176274 = CARTESIAN_POINT('',(6.079756717389,0.209951281181)); -#176275 = CARTESIAN_POINT('',(6.114033757907,0.20925504796)); -#176276 = CARTESIAN_POINT('',(6.148189293703,0.208524296394)); -#176277 = CARTESIAN_POINT('',(6.182204154882,0.207760708899)); -#176278 = CARTESIAN_POINT('',(6.216059671377,0.2069660569)); -#176279 = CARTESIAN_POINT('',(6.249737650065,0.206142181906)); -#176280 = CARTESIAN_POINT('',(6.272059699945,0.205574732686)); -#176281 = CARTESIAN_POINT('',(6.28318530718,0.205286775028)); -#176282 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176283 = PCURVE('',#168753,#176284); -#176284 = DEFINITIONAL_REPRESENTATION('',(#176285),#176311); -#176285 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176286,#176287,#176288, - #176289,#176290,#176291,#176292,#176293,#176294,#176295,#176296, - #176297,#176298,#176299,#176300,#176301,#176302,#176303,#176304, - #176305,#176306,#176307,#176308,#176309,#176310),.UNSPECIFIED.,.F., +#178649 = CARTESIAN_POINT('',(5.531305892885,0.215502680697)); +#178650 = CARTESIAN_POINT('',(5.542431500119,0.215502691983)); +#178651 = CARTESIAN_POINT('',(5.56475355,0.215488600414)); +#178652 = CARTESIAN_POINT('',(5.598431528687,0.215424529131)); +#178653 = CARTESIAN_POINT('',(5.632287045183,0.215316877584)); +#178654 = CARTESIAN_POINT('',(5.666301906361,0.215165191368)); +#178655 = CARTESIAN_POINT('',(5.700457442157,0.214969150173)); +#178656 = CARTESIAN_POINT('',(5.734734482675,0.21472859015)); +#178657 = CARTESIAN_POINT('',(5.76911344049,0.214443503246)); +#178658 = CARTESIAN_POINT('',(5.803574369467,0.214114041064)); +#178659 = CARTESIAN_POINT('',(5.838097033931,0.213740515769)); +#178660 = CARTESIAN_POINT('',(5.872660978441,0.213323399993)); +#178661 = CARTESIAN_POINT('',(5.907245600032,0.212863325183)); +#178662 = CARTESIAN_POINT('',(5.941830221623,0.21236107854)); +#178663 = CARTESIAN_POINT('',(5.976394166134,0.211817598546)); +#178664 = CARTESIAN_POINT('',(6.010916830598,0.211233969132)); +#178665 = CARTESIAN_POINT('',(6.045377759574,0.210611412568)); +#178666 = CARTESIAN_POINT('',(6.079756717389,0.209951281181)); +#178667 = CARTESIAN_POINT('',(6.114033757907,0.20925504796)); +#178668 = CARTESIAN_POINT('',(6.148189293703,0.208524296394)); +#178669 = CARTESIAN_POINT('',(6.182204154882,0.207760708899)); +#178670 = CARTESIAN_POINT('',(6.216059671377,0.2069660569)); +#178671 = CARTESIAN_POINT('',(6.249737650065,0.206142181906)); +#178672 = CARTESIAN_POINT('',(6.272059699945,0.205574732686)); +#178673 = CARTESIAN_POINT('',(6.28318530718,0.205286775028)); +#178674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178675 = PCURVE('',#171145,#178676); +#178676 = DEFINITIONAL_REPRESENTATION('',(#178677),#178703); +#178677 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178678,#178679,#178680, + #178681,#178682,#178683,#178684,#178685,#178686,#178687,#178688, + #178689,#178690,#178691,#178692,#178693,#178694,#178695,#178696, + #178697,#178698,#178699,#178700,#178701,#178702),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -218318,62 +221320,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#176286 = CARTESIAN_POINT('',(0.E+000,1.)); -#176287 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#176288 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#176289 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#176290 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#176291 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#176292 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#176293 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#176294 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#176295 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#176296 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#176297 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#176298 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#176299 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#176300 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#176301 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#176302 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); -#176303 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); -#176304 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); -#176305 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); -#176306 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); -#176307 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); -#176308 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); -#176309 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); -#176310 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176312 = ORIENTED_EDGE('',*,*,#171602,.F.); -#176313 = ORIENTED_EDGE('',*,*,#176176,.T.); -#176314 = ADVANCED_FACE('',(#176315),#170659,.T.); -#176315 = FACE_BOUND('',#176316,.T.); -#176316 = EDGE_LOOP('',(#176317,#176318,#176384,#176385,#176386)); -#176317 = ORIENTED_EDGE('',*,*,#171156,.F.); -#176318 = ORIENTED_EDGE('',*,*,#176319,.T.); -#176319 = EDGE_CURVE('',#171135,#170602,#176320,.T.); -#176320 = SURFACE_CURVE('',#176321,(#176326,#176355),.PCURVE_S1.); -#176321 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176322,#176323,#176324, -#176325),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178678 = CARTESIAN_POINT('',(0.E+000,1.)); +#178679 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#178680 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#178681 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#178682 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#178683 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#178684 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#178685 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#178686 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#178687 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#178688 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#178689 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#178690 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#178691 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#178692 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#178693 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#178694 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); +#178695 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); +#178696 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); +#178697 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); +#178698 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); +#178699 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); +#178700 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); +#178701 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); +#178702 = CARTESIAN_POINT('',(0.751879414295,1.)); +#178703 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178704 = ORIENTED_EDGE('',*,*,#173994,.F.); +#178705 = ORIENTED_EDGE('',*,*,#178568,.T.); +#178706 = ADVANCED_FACE('',(#178707),#173051,.T.); +#178707 = FACE_BOUND('',#178708,.T.); +#178708 = EDGE_LOOP('',(#178709,#178710,#178776,#178777,#178778)); +#178709 = ORIENTED_EDGE('',*,*,#173548,.F.); +#178710 = ORIENTED_EDGE('',*,*,#178711,.T.); +#178711 = EDGE_CURVE('',#173527,#172994,#178712,.T.); +#178712 = SURFACE_CURVE('',#178713,(#178718,#178747),.PCURVE_S1.); +#178713 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178714,#178715,#178716, +#178717),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#176322 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, +#178714 = CARTESIAN_POINT('',(1.174271552513,0.649160426457, 1.162940952255)); -#176323 = CARTESIAN_POINT('',(1.213215504454,0.648328016991, +#178715 = CARTESIAN_POINT('',(1.213215504454,0.648328016991, 1.166047546673)); -#176324 = CARTESIAN_POINT('',(1.24878608255,0.633243924364,1.167717466) +#178716 = CARTESIAN_POINT('',(1.24878608255,0.633243924364,1.167717466) ); -#176325 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) +#178717 = CARTESIAN_POINT('',(1.276015003457,0.606015003457,1.167717466) ); -#176326 = PCURVE('',#170659,#176327); -#176327 = DEFINITIONAL_REPRESENTATION('',(#176328),#176354); -#176328 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176329,#176330,#176331, - #176332,#176333,#176334,#176335,#176336,#176337,#176338,#176339, - #176340,#176341,#176342,#176343,#176344,#176345,#176346,#176347, - #176348,#176349,#176350,#176351,#176352,#176353),.UNSPECIFIED.,.F., +#178718 = PCURVE('',#173051,#178719); +#178719 = DEFINITIONAL_REPRESENTATION('',(#178720),#178746); +#178720 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178721,#178722,#178723, + #178724,#178725,#178726,#178727,#178728,#178729,#178730,#178731, + #178732,#178733,#178734,#178735,#178736,#178737,#178738,#178739, + #178740,#178741,#178742,#178743,#178744,#178745),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -218381,40 +221383,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176329 = CARTESIAN_POINT('',(1.637833825,9.834784201249E-002)); -#176330 = CARTESIAN_POINT('',(1.648959432235,9.863579967057E-002)); -#176331 = CARTESIAN_POINT('',(1.671281482115,9.920324889014E-002)); -#176332 = CARTESIAN_POINT('',(1.704959460802,0.100027123884)); -#176333 = CARTESIAN_POINT('',(1.738814977298,0.100821775884)); -#176334 = CARTESIAN_POINT('',(1.772829838476,0.101585363379)); -#176335 = CARTESIAN_POINT('',(1.806985374273,0.102316114945)); -#176336 = CARTESIAN_POINT('',(1.84126241479,0.103012348166)); -#176337 = CARTESIAN_POINT('',(1.875641372605,0.103672479553)); -#176338 = CARTESIAN_POINT('',(1.910102301582,0.104295036117)); -#176339 = CARTESIAN_POINT('',(1.944624966046,0.104878665531)); -#176340 = CARTESIAN_POINT('',(1.979188910557,0.105422145525)); -#176341 = CARTESIAN_POINT('',(2.013773532147,0.105924392167)); -#176342 = CARTESIAN_POINT('',(2.048358153738,0.106384466977)); -#176343 = CARTESIAN_POINT('',(2.082922098249,0.106801582753)); -#176344 = CARTESIAN_POINT('',(2.117444762713,0.107175108049)); -#176345 = CARTESIAN_POINT('',(2.15190569169,0.107504570231)); -#176346 = CARTESIAN_POINT('',(2.186284649505,0.107789657135)); -#176347 = CARTESIAN_POINT('',(2.220561690022,0.108030217158)); -#176348 = CARTESIAN_POINT('',(2.254717225818,0.108226258353)); -#176349 = CARTESIAN_POINT('',(2.288732086997,0.108377944569)); -#176350 = CARTESIAN_POINT('',(2.322587603492,0.108485596116)); -#176351 = CARTESIAN_POINT('',(2.35626558218,0.108549667398)); -#176352 = CARTESIAN_POINT('',(2.37858763206,0.108563758968)); -#176353 = CARTESIAN_POINT('',(2.389713239295,0.108563747681)); -#176354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176355 = PCURVE('',#170732,#176356); -#176356 = DEFINITIONAL_REPRESENTATION('',(#176357),#176383); -#176357 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176358,#176359,#176360, - #176361,#176362,#176363,#176364,#176365,#176366,#176367,#176368, - #176369,#176370,#176371,#176372,#176373,#176374,#176375,#176376, - #176377,#176378,#176379,#176380,#176381,#176382),.UNSPECIFIED.,.F., +#178721 = CARTESIAN_POINT('',(1.637833825,9.834784201249E-002)); +#178722 = CARTESIAN_POINT('',(1.648959432235,9.863579967057E-002)); +#178723 = CARTESIAN_POINT('',(1.671281482115,9.920324889014E-002)); +#178724 = CARTESIAN_POINT('',(1.704959460802,0.100027123884)); +#178725 = CARTESIAN_POINT('',(1.738814977298,0.100821775884)); +#178726 = CARTESIAN_POINT('',(1.772829838476,0.101585363379)); +#178727 = CARTESIAN_POINT('',(1.806985374273,0.102316114945)); +#178728 = CARTESIAN_POINT('',(1.84126241479,0.103012348166)); +#178729 = CARTESIAN_POINT('',(1.875641372605,0.103672479553)); +#178730 = CARTESIAN_POINT('',(1.910102301582,0.104295036117)); +#178731 = CARTESIAN_POINT('',(1.944624966046,0.104878665531)); +#178732 = CARTESIAN_POINT('',(1.979188910557,0.105422145525)); +#178733 = CARTESIAN_POINT('',(2.013773532147,0.105924392167)); +#178734 = CARTESIAN_POINT('',(2.048358153738,0.106384466977)); +#178735 = CARTESIAN_POINT('',(2.082922098249,0.106801582753)); +#178736 = CARTESIAN_POINT('',(2.117444762713,0.107175108049)); +#178737 = CARTESIAN_POINT('',(2.15190569169,0.107504570231)); +#178738 = CARTESIAN_POINT('',(2.186284649505,0.107789657135)); +#178739 = CARTESIAN_POINT('',(2.220561690022,0.108030217158)); +#178740 = CARTESIAN_POINT('',(2.254717225818,0.108226258353)); +#178741 = CARTESIAN_POINT('',(2.288732086997,0.108377944569)); +#178742 = CARTESIAN_POINT('',(2.322587603492,0.108485596116)); +#178743 = CARTESIAN_POINT('',(2.35626558218,0.108549667398)); +#178744 = CARTESIAN_POINT('',(2.37858763206,0.108563758968)); +#178745 = CARTESIAN_POINT('',(2.389713239295,0.108563747681)); +#178746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178747 = PCURVE('',#173124,#178748); +#178748 = DEFINITIONAL_REPRESENTATION('',(#178749),#178775); +#178749 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178750,#178751,#178752, + #178753,#178754,#178755,#178756,#178757,#178758,#178759,#178760, + #178761,#178762,#178763,#178764,#178765,#178766,#178767,#178768, + #178769,#178770,#178771,#178772,#178773,#178774),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -218422,56 +221424,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176358 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176359 = CARTESIAN_POINT('',(0.740753686904,5.702886323698E-008)); -#176360 = CARTESIAN_POINT('',(0.718425946425,-7.920748678546E-006)); -#176361 = CARTESIAN_POINT('',(0.684729502759,-3.211524038167E-005)); -#176362 = CARTESIAN_POINT('',(0.650851510226,-9.135957813898E-005)); -#176363 = CARTESIAN_POINT('',(0.616817843137,-8.6431828841E-005)); -#176364 = CARTESIAN_POINT('',(0.582648204505,-8.687405903465E-005)); -#176365 = CARTESIAN_POINT('',(0.548364026632,-8.593542635481E-005)); -#176366 = CARTESIAN_POINT('',(0.513985713406,-8.542361824741E-005)); -#176367 = CARTESIAN_POINT('',(0.479533105651,-8.485308429909E-005)); -#176368 = CARTESIAN_POINT('',(0.445025477762,-8.435280861153E-005)); -#176369 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); -#176370 = CARTESIAN_POINT('',(0.375920232966,-8.346461194624E-005)); -#176371 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); -#176372 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); -#176373 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); -#176374 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#176375 = CARTESIAN_POINT('',(0.203491552027,-8.179989506532E-005)); -#176376 = CARTESIAN_POINT('',(0.169212469737,-8.226451401245E-005)); -#176377 = CARTESIAN_POINT('',(0.135047837564,-7.965797689906E-005)); -#176378 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); -#176379 = CARTESIAN_POINT('',(6.714594636695E-002,-5.446484095812E-005) - ); -#176380 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467025E-005) - ); -#176381 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804137033E-006)); -#176382 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); -#176383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176384 = ORIENTED_EDGE('',*,*,#170601,.T.); -#176385 = ORIENTED_EDGE('',*,*,#172831,.F.); -#176386 = ORIENTED_EDGE('',*,*,#176387,.F.); -#176387 = EDGE_CURVE('',#171157,#171698,#176388,.T.); -#176388 = SURFACE_CURVE('',#176389,(#176394,#176423),.PCURVE_S1.); -#176389 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176390,#176391,#176392, -#176393),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#178750 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#178751 = CARTESIAN_POINT('',(0.740753686904,5.702886323698E-008)); +#178752 = CARTESIAN_POINT('',(0.718425946425,-7.920748678546E-006)); +#178753 = CARTESIAN_POINT('',(0.684729502759,-3.211524038167E-005)); +#178754 = CARTESIAN_POINT('',(0.650851510226,-9.135957813898E-005)); +#178755 = CARTESIAN_POINT('',(0.616817843137,-8.6431828841E-005)); +#178756 = CARTESIAN_POINT('',(0.582648204505,-8.687405903465E-005)); +#178757 = CARTESIAN_POINT('',(0.548364026632,-8.593542635481E-005)); +#178758 = CARTESIAN_POINT('',(0.513985713406,-8.542361824741E-005)); +#178759 = CARTESIAN_POINT('',(0.479533105651,-8.485308429909E-005)); +#178760 = CARTESIAN_POINT('',(0.445025477762,-8.435280861153E-005)); +#178761 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); +#178762 = CARTESIAN_POINT('',(0.375920232966,-8.346461194624E-005)); +#178763 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); +#178764 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); +#178765 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); +#178766 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#178767 = CARTESIAN_POINT('',(0.203491552027,-8.179989506532E-005)); +#178768 = CARTESIAN_POINT('',(0.169212469737,-8.226451401245E-005)); +#178769 = CARTESIAN_POINT('',(0.135047837564,-7.965797689906E-005)); +#178770 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); +#178771 = CARTESIAN_POINT('',(6.714594636695E-002,-5.446484095812E-005) + ); +#178772 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467025E-005) + ); +#178773 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804137033E-006)); +#178774 = CARTESIAN_POINT('',(7.453889935838E-016,0.E+000)); +#178775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178776 = ORIENTED_EDGE('',*,*,#172993,.T.); +#178777 = ORIENTED_EDGE('',*,*,#175223,.F.); +#178778 = ORIENTED_EDGE('',*,*,#178779,.F.); +#178779 = EDGE_CURVE('',#173549,#174090,#178780,.T.); +#178780 = SURFACE_CURVE('',#178781,(#178786,#178815),.PCURVE_S1.); +#178781 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178782,#178783,#178784, +#178785),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#176390 = CARTESIAN_POINT('',(1.325111126057,0.8,0.6)); -#176391 = CARTESIAN_POINT('',(1.411121542172,0.8,0.6)); -#176392 = CARTESIAN_POINT('',(1.47,0.741121542172,0.6)); -#176393 = CARTESIAN_POINT('',(1.47,0.655111126057,0.6)); -#176394 = PCURVE('',#170659,#176395); -#176395 = DEFINITIONAL_REPRESENTATION('',(#176396),#176422); -#176396 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176397,#176398,#176399, - #176400,#176401,#176402,#176403,#176404,#176405,#176406,#176407, - #176408,#176409,#176410,#176411,#176412,#176413,#176414,#176415, - #176416,#176417,#176418,#176419,#176420,#176421),.UNSPECIFIED.,.F., +#178782 = CARTESIAN_POINT('',(1.325111126057,0.8,0.6)); +#178783 = CARTESIAN_POINT('',(1.411121542172,0.8,0.6)); +#178784 = CARTESIAN_POINT('',(1.47,0.741121542172,0.6)); +#178785 = CARTESIAN_POINT('',(1.47,0.655111126057,0.6)); +#178786 = PCURVE('',#173051,#178787); +#178787 = DEFINITIONAL_REPRESENTATION('',(#178788),#178814); +#178788 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178789,#178790,#178791, + #178792,#178793,#178794,#178795,#178796,#178797,#178798,#178799, + #178800,#178801,#178802,#178803,#178804,#178805,#178806,#178807, + #178808,#178809,#178810,#178811,#178812,#178813),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937045,6.009774611072,6.078127285099, @@ -218479,40 +221481,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#176397 = CARTESIAN_POINT('',(1.637833825,0.700350889861)); -#176398 = CARTESIAN_POINT('',(1.658529900762,0.701154387374)); -#176399 = CARTESIAN_POINT('',(1.700434160356,0.702727858938)); -#176400 = CARTESIAN_POINT('',(1.764738777092,0.704963089566)); -#176401 = CARTESIAN_POINT('',(1.830409584136,0.707048969275)); -#176402 = CARTESIAN_POINT('',(1.89734333505,0.708961011393)); -#176403 = CARTESIAN_POINT('',(1.965423048009,0.710675406858)); -#176404 = CARTESIAN_POINT('',(2.034516667805,0.712169632061)); -#176405 = CARTESIAN_POINT('',(2.104478619153,0.713423139575)); -#176406 = CARTESIAN_POINT('',(2.175151124104,0.714418019116)); -#176407 = CARTESIAN_POINT('',(2.246366102244,0.715139612542)); -#176408 = CARTESIAN_POINT('',(2.317947385231,0.715577039738)); -#176409 = CARTESIAN_POINT('',(2.389713239295,0.715723602678)); -#176410 = CARTESIAN_POINT('',(2.461479093359,0.715577039738)); -#176411 = CARTESIAN_POINT('',(2.533060376346,0.715139612542)); -#176412 = CARTESIAN_POINT('',(2.604275354486,0.714418019116)); -#176413 = CARTESIAN_POINT('',(2.674947859436,0.713423139575)); -#176414 = CARTESIAN_POINT('',(2.744909810785,0.712169632061)); -#176415 = CARTESIAN_POINT('',(2.814003430581,0.710675406858)); -#176416 = CARTESIAN_POINT('',(2.88208314354,0.708961011393)); -#176417 = CARTESIAN_POINT('',(2.949016894454,0.707048969275)); -#176418 = CARTESIAN_POINT('',(3.014687701497,0.704963089566)); -#176419 = CARTESIAN_POINT('',(3.078992318233,0.702727858938)); -#176420 = CARTESIAN_POINT('',(3.120896577828,0.701154387374)); -#176421 = CARTESIAN_POINT('',(3.14159265359,0.700350889861)); -#176422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176423 = PCURVE('',#169411,#176424); -#176424 = DEFINITIONAL_REPRESENTATION('',(#176425),#176451); -#176425 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176426,#176427,#176428, - #176429,#176430,#176431,#176432,#176433,#176434,#176435,#176436, - #176437,#176438,#176439,#176440,#176441,#176442,#176443,#176444, - #176445,#176446,#176447,#176448,#176449,#176450),.UNSPECIFIED.,.F., +#178789 = CARTESIAN_POINT('',(1.637833825,0.700350889861)); +#178790 = CARTESIAN_POINT('',(1.658529900762,0.701154387374)); +#178791 = CARTESIAN_POINT('',(1.700434160356,0.702727858938)); +#178792 = CARTESIAN_POINT('',(1.764738777092,0.704963089566)); +#178793 = CARTESIAN_POINT('',(1.830409584136,0.707048969275)); +#178794 = CARTESIAN_POINT('',(1.89734333505,0.708961011393)); +#178795 = CARTESIAN_POINT('',(1.965423048009,0.710675406858)); +#178796 = CARTESIAN_POINT('',(2.034516667805,0.712169632061)); +#178797 = CARTESIAN_POINT('',(2.104478619153,0.713423139575)); +#178798 = CARTESIAN_POINT('',(2.175151124104,0.714418019116)); +#178799 = CARTESIAN_POINT('',(2.246366102244,0.715139612542)); +#178800 = CARTESIAN_POINT('',(2.317947385231,0.715577039738)); +#178801 = CARTESIAN_POINT('',(2.389713239295,0.715723602678)); +#178802 = CARTESIAN_POINT('',(2.461479093359,0.715577039738)); +#178803 = CARTESIAN_POINT('',(2.533060376346,0.715139612542)); +#178804 = CARTESIAN_POINT('',(2.604275354486,0.714418019116)); +#178805 = CARTESIAN_POINT('',(2.674947859436,0.713423139575)); +#178806 = CARTESIAN_POINT('',(2.744909810785,0.712169632061)); +#178807 = CARTESIAN_POINT('',(2.814003430581,0.710675406858)); +#178808 = CARTESIAN_POINT('',(2.88208314354,0.708961011393)); +#178809 = CARTESIAN_POINT('',(2.949016894454,0.707048969275)); +#178810 = CARTESIAN_POINT('',(3.014687701497,0.704963089566)); +#178811 = CARTESIAN_POINT('',(3.078992318233,0.702727858938)); +#178812 = CARTESIAN_POINT('',(3.120896577828,0.701154387374)); +#178813 = CARTESIAN_POINT('',(3.14159265359,0.700350889861)); +#178814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178815 = PCURVE('',#171803,#178816); +#178816 = DEFINITIONAL_REPRESENTATION('',(#178817),#178843); +#178817 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178818,#178819,#178820, + #178821,#178822,#178823,#178824,#178825,#178826,#178827,#178828, + #178829,#178830,#178831,#178832,#178833,#178834,#178835,#178836, + #178837,#178838,#178839,#178840,#178841,#178842),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937045,6.009774611072,6.078127285099, @@ -218520,61 +221522,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#176426 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#176427 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#176428 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#176429 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#176430 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#176431 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#176432 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#176433 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#176434 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#176435 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#176436 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#176437 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#176438 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#176439 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#176440 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#176441 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#176442 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#176443 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#176444 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#176445 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#176446 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#176447 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#176448 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) - ); -#176449 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#176450 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#176451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176452 = ADVANCED_FACE('',(#176453),#169411,.T.); -#176453 = FACE_BOUND('',#176454,.T.); -#176454 = EDGE_LOOP('',(#176455,#176456,#176457,#176523,#176524)); -#176455 = ORIENTED_EDGE('',*,*,#171697,.F.); -#176456 = ORIENTED_EDGE('',*,*,#169372,.T.); -#176457 = ORIENTED_EDGE('',*,*,#176458,.T.); -#176458 = EDGE_CURVE('',#169288,#172291,#176459,.T.); -#176459 = SURFACE_CURVE('',#176460,(#176465,#176494),.PCURVE_S1.); -#176460 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#176461,#176462,#176463, -#176464),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#178818 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#178819 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#178820 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#178821 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#178822 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#178823 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#178824 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#178825 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#178826 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#178827 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#178828 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#178829 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#178830 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#178831 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#178832 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#178833 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#178834 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#178835 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#178836 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#178837 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#178838 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#178839 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#178840 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) + ); +#178841 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#178842 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#178843 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178844 = ADVANCED_FACE('',(#178845),#171803,.T.); +#178845 = FACE_BOUND('',#178846,.T.); +#178846 = EDGE_LOOP('',(#178847,#178848,#178849,#178915,#178916)); +#178847 = ORIENTED_EDGE('',*,*,#174089,.F.); +#178848 = ORIENTED_EDGE('',*,*,#171764,.T.); +#178849 = ORIENTED_EDGE('',*,*,#178850,.T.); +#178850 = EDGE_CURVE('',#171680,#174683,#178851,.T.); +#178851 = SURFACE_CURVE('',#178852,(#178857,#178886),.PCURVE_S1.); +#178852 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#178853,#178854,#178855, +#178856),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#176461 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); -#176462 = CARTESIAN_POINT('',(1.275581001793,0.660038843607,0.132282534) +#178853 = CARTESIAN_POINT('',(1.3028099227,0.6328099227,0.132282534)); +#178854 = CARTESIAN_POINT('',(1.275581001793,0.660038843607,0.132282534) ); -#176463 = CARTESIAN_POINT('',(1.240010423697,0.675122936235, +#178855 = CARTESIAN_POINT('',(1.240010423697,0.675122936235, 0.133952453327)); -#176464 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 +#178856 = CARTESIAN_POINT('',(1.201066471757,0.6759553457,0.137059047745 )); -#176465 = PCURVE('',#169411,#176466); -#176466 = DEFINITIONAL_REPRESENTATION('',(#176467),#176493); -#176467 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176468,#176469,#176470, - #176471,#176472,#176473,#176474,#176475,#176476,#176477,#176478, - #176479,#176480,#176481,#176482,#176483,#176484,#176485,#176486, - #176487,#176488,#176489,#176490,#176491,#176492),.UNSPECIFIED.,.F., +#178857 = PCURVE('',#171803,#178858); +#178858 = DEFINITIONAL_REPRESENTATION('',(#178859),#178885); +#178859 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178860,#178861,#178862, + #178863,#178864,#178865,#178866,#178867,#178868,#178869,#178870, + #178871,#178872,#178873,#178874,#178875,#178876,#178877,#178878, + #178879,#178880,#178881,#178882,#178883,#178884),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -218582,40 +221584,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#176468 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#176469 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); -#176470 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); -#176471 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); -#176472 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); -#176473 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); -#176474 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); -#176475 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); -#176476 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); -#176477 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); -#176478 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); -#176479 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); -#176480 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); -#176481 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); -#176482 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); -#176483 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); -#176484 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); -#176485 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); -#176486 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); -#176487 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); -#176488 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); -#176489 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); -#176490 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); -#176491 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); -#176492 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#176493 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176494 = PCURVE('',#169326,#176495); -#176495 = DEFINITIONAL_REPRESENTATION('',(#176496),#176522); -#176496 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176497,#176498,#176499, - #176500,#176501,#176502,#176503,#176504,#176505,#176506,#176507, - #176508,#176509,#176510,#176511,#176512,#176513,#176514,#176515, - #176516,#176517,#176518,#176519,#176520,#176521),.UNSPECIFIED.,.F., +#178860 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#178861 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); +#178862 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); +#178863 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); +#178864 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); +#178865 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); +#178866 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); +#178867 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); +#178868 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); +#178869 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); +#178870 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); +#178871 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); +#178872 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); +#178873 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); +#178874 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); +#178875 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); +#178876 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); +#178877 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); +#178878 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); +#178879 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); +#178880 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); +#178881 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); +#178882 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); +#178883 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); +#178884 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#178885 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178886 = PCURVE('',#171718,#178887); +#178887 = DEFINITIONAL_REPRESENTATION('',(#178888),#178914); +#178888 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178889,#178890,#178891, + #178892,#178893,#178894,#178895,#178896,#178897,#178898,#178899, + #178900,#178901,#178902,#178903,#178904,#178905,#178906,#178907, + #178908,#178909,#178910,#178911,#178912,#178913),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -218623,56 +221625,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#176497 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); -#176498 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#176499 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#176500 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#176501 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#176502 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#176503 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#176504 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#176505 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#176506 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#176507 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#176508 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#176509 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#176510 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#176511 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#176512 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#176513 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); -#176514 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); -#176515 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); -#176516 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); -#176517 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); -#176518 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); -#176519 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); -#176520 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); -#176521 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176523 = ORIENTED_EDGE('',*,*,#172290,.F.); -#176524 = ORIENTED_EDGE('',*,*,#176387,.T.); -#176525 = ADVANCED_FACE('',(#176526),#170949,.F.); -#176526 = FACE_BOUND('',#176527,.F.); -#176527 = EDGE_LOOP('',(#176528,#176529,#176530,#176531)); -#176528 = ORIENTED_EDGE('',*,*,#171006,.T.); -#176529 = ORIENTED_EDGE('',*,*,#173865,.F.); -#176530 = ORIENTED_EDGE('',*,*,#170934,.F.); -#176531 = ORIENTED_EDGE('',*,*,#176532,.T.); -#176532 = EDGE_CURVE('',#170879,#170877,#176533,.T.); -#176533 = SURFACE_CURVE('',#176534,(#176539,#176568),.PCURVE_S1.); -#176534 = CIRCLE('',#176535,0.108045018441); -#176535 = AXIS2_PLACEMENT_3D('',#176536,#176537,#176538); -#176536 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); -#176537 = DIRECTION('',(0.E+000,0.E+000,1.)); -#176538 = DIRECTION('',(1.,0.E+000,0.E+000)); -#176539 = PCURVE('',#170949,#176540); -#176540 = DEFINITIONAL_REPRESENTATION('',(#176541),#176567); -#176541 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176542,#176543,#176544, - #176545,#176546,#176547,#176548,#176549,#176550,#176551,#176552, - #176553,#176554,#176555,#176556,#176557,#176558,#176559,#176560, - #176561,#176562,#176563,#176564,#176565,#176566),.UNSPECIFIED.,.F., +#178889 = CARTESIAN_POINT('',(7.453889935838E-016,1.)); +#178890 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#178891 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#178892 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#178893 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#178894 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#178895 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#178896 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#178897 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#178898 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#178899 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#178900 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#178901 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#178902 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#178903 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#178904 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#178905 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); +#178906 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); +#178907 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); +#178908 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); +#178909 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); +#178910 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); +#178911 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); +#178912 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); +#178913 = CARTESIAN_POINT('',(0.751879414295,1.)); +#178914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178915 = ORIENTED_EDGE('',*,*,#174682,.F.); +#178916 = ORIENTED_EDGE('',*,*,#178779,.T.); +#178917 = ADVANCED_FACE('',(#178918),#173341,.F.); +#178918 = FACE_BOUND('',#178919,.F.); +#178919 = EDGE_LOOP('',(#178920,#178921,#178922,#178923)); +#178920 = ORIENTED_EDGE('',*,*,#173398,.T.); +#178921 = ORIENTED_EDGE('',*,*,#176257,.F.); +#178922 = ORIENTED_EDGE('',*,*,#173326,.F.); +#178923 = ORIENTED_EDGE('',*,*,#178924,.T.); +#178924 = EDGE_CURVE('',#173271,#173269,#178925,.T.); +#178925 = SURFACE_CURVE('',#178926,(#178931,#178960),.PCURVE_S1.); +#178926 = CIRCLE('',#178927,0.108045018441); +#178927 = AXIS2_PLACEMENT_3D('',#178928,#178929,#178930); +#178928 = CARTESIAN_POINT('',(-0.975,-0.4,1.15)); +#178929 = DIRECTION('',(0.E+000,0.E+000,1.)); +#178930 = DIRECTION('',(1.,0.E+000,0.E+000)); +#178931 = PCURVE('',#173341,#178932); +#178932 = DEFINITIONAL_REPRESENTATION('',(#178933),#178959); +#178933 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178934,#178935,#178936, + #178937,#178938,#178939,#178940,#178941,#178942,#178943,#178944, + #178945,#178946,#178947,#178948,#178949,#178950,#178951,#178952, + #178953,#178954,#178955,#178956,#178957,#178958),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 0.142799666072,0.285599332145,0.428398998217,0.571198664289, 0.713998330361,0.856797996434,0.999597662506,1.142397328578, @@ -218680,67 +221682,67 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.856395658939,1.999195325012,2.141994991084,2.284794657156, 2.427594323228,2.570393989301,2.713193655373,2.855993321445, 2.998792987518,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#176542 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#176543 = CARTESIAN_POINT('',(4.759988869075E-002,-5.E-002)); -#176544 = CARTESIAN_POINT('',(0.142799666072,-5.E-002)); -#176545 = CARTESIAN_POINT('',(0.285599332145,-5.E-002)); -#176546 = CARTESIAN_POINT('',(0.428398998217,-5.E-002)); -#176547 = CARTESIAN_POINT('',(0.571198664289,-5.E-002)); -#176548 = CARTESIAN_POINT('',(0.713998330361,-5.E-002)); -#176549 = CARTESIAN_POINT('',(0.856797996434,-5.E-002)); -#176550 = CARTESIAN_POINT('',(0.999597662506,-5.E-002)); -#176551 = CARTESIAN_POINT('',(1.142397328578,-5.E-002)); -#176552 = CARTESIAN_POINT('',(1.28519699465,-5.E-002)); -#176553 = CARTESIAN_POINT('',(1.427996660723,-5.E-002)); -#176554 = CARTESIAN_POINT('',(1.570796326795,-5.E-002)); -#176555 = CARTESIAN_POINT('',(1.713595992867,-5.E-002)); -#176556 = CARTESIAN_POINT('',(1.856395658939,-5.E-002)); -#176557 = CARTESIAN_POINT('',(1.999195325012,-5.E-002)); -#176558 = CARTESIAN_POINT('',(2.141994991084,-5.E-002)); -#176559 = CARTESIAN_POINT('',(2.284794657156,-5.E-002)); -#176560 = CARTESIAN_POINT('',(2.427594323228,-5.E-002)); -#176561 = CARTESIAN_POINT('',(2.570393989301,-5.E-002)); -#176562 = CARTESIAN_POINT('',(2.713193655373,-5.E-002)); -#176563 = CARTESIAN_POINT('',(2.855993321445,-5.E-002)); -#176564 = CARTESIAN_POINT('',(2.998792987518,-5.E-002)); -#176565 = CARTESIAN_POINT('',(3.093992764899,-5.E-002)); -#176566 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#176567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176568 = PCURVE('',#170922,#176569); -#176569 = DEFINITIONAL_REPRESENTATION('',(#176570),#176574); -#176570 = CIRCLE('',#176571,0.108045018441); -#176571 = AXIS2_PLACEMENT_2D('',#176572,#176573); -#176572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#176573 = DIRECTION('',(1.,0.E+000)); -#176574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176575 = ADVANCED_FACE('',(#176576),#170922,.T.); -#176576 = FACE_BOUND('',#176577,.T.); -#176577 = EDGE_LOOP('',(#176578,#176579)); -#176578 = ORIENTED_EDGE('',*,*,#176532,.T.); -#176579 = ORIENTED_EDGE('',*,*,#170876,.T.); -#176580 = ADVANCED_FACE('',(#176581),#170732,.T.); -#176581 = FACE_BOUND('',#176582,.T.); -#176582 = EDGE_LOOP('',(#176583,#176584,#176585,#176628)); -#176583 = ORIENTED_EDGE('',*,*,#170693,.F.); -#176584 = ORIENTED_EDGE('',*,*,#176319,.F.); -#176585 = ORIENTED_EDGE('',*,*,#176586,.F.); -#176586 = EDGE_CURVE('',#173751,#171135,#176587,.T.); -#176587 = SURFACE_CURVE('',#176588,(#176593,#176622),.PCURVE_S1.); -#176588 = CIRCLE('',#176589,5.E-002); -#176589 = AXIS2_PLACEMENT_3D('',#176590,#176591,#176592); -#176590 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.15)); -#176591 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#176592 = DIRECTION('',(0.E+000,0.E+000,1.)); -#176593 = PCURVE('',#170732,#176594); -#176594 = DEFINITIONAL_REPRESENTATION('',(#176595),#176621); -#176595 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176596,#176597,#176598, - #176599,#176600,#176601,#176602,#176603,#176604,#176605,#176606, - #176607,#176608,#176609,#176610,#176611,#176612,#176613,#176614, - #176615,#176616,#176617,#176618,#176619,#176620),.UNSPECIFIED.,.F., +#178934 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#178935 = CARTESIAN_POINT('',(4.759988869075E-002,-5.E-002)); +#178936 = CARTESIAN_POINT('',(0.142799666072,-5.E-002)); +#178937 = CARTESIAN_POINT('',(0.285599332145,-5.E-002)); +#178938 = CARTESIAN_POINT('',(0.428398998217,-5.E-002)); +#178939 = CARTESIAN_POINT('',(0.571198664289,-5.E-002)); +#178940 = CARTESIAN_POINT('',(0.713998330361,-5.E-002)); +#178941 = CARTESIAN_POINT('',(0.856797996434,-5.E-002)); +#178942 = CARTESIAN_POINT('',(0.999597662506,-5.E-002)); +#178943 = CARTESIAN_POINT('',(1.142397328578,-5.E-002)); +#178944 = CARTESIAN_POINT('',(1.28519699465,-5.E-002)); +#178945 = CARTESIAN_POINT('',(1.427996660723,-5.E-002)); +#178946 = CARTESIAN_POINT('',(1.570796326795,-5.E-002)); +#178947 = CARTESIAN_POINT('',(1.713595992867,-5.E-002)); +#178948 = CARTESIAN_POINT('',(1.856395658939,-5.E-002)); +#178949 = CARTESIAN_POINT('',(1.999195325012,-5.E-002)); +#178950 = CARTESIAN_POINT('',(2.141994991084,-5.E-002)); +#178951 = CARTESIAN_POINT('',(2.284794657156,-5.E-002)); +#178952 = CARTESIAN_POINT('',(2.427594323228,-5.E-002)); +#178953 = CARTESIAN_POINT('',(2.570393989301,-5.E-002)); +#178954 = CARTESIAN_POINT('',(2.713193655373,-5.E-002)); +#178955 = CARTESIAN_POINT('',(2.855993321445,-5.E-002)); +#178956 = CARTESIAN_POINT('',(2.998792987518,-5.E-002)); +#178957 = CARTESIAN_POINT('',(3.093992764899,-5.E-002)); +#178958 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#178959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178960 = PCURVE('',#173314,#178961); +#178961 = DEFINITIONAL_REPRESENTATION('',(#178962),#178966); +#178962 = CIRCLE('',#178963,0.108045018441); +#178963 = AXIS2_PLACEMENT_2D('',#178964,#178965); +#178964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#178965 = DIRECTION('',(1.,0.E+000)); +#178966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#178967 = ADVANCED_FACE('',(#178968),#173314,.T.); +#178968 = FACE_BOUND('',#178969,.T.); +#178969 = EDGE_LOOP('',(#178970,#178971)); +#178970 = ORIENTED_EDGE('',*,*,#178924,.T.); +#178971 = ORIENTED_EDGE('',*,*,#173268,.T.); +#178972 = ADVANCED_FACE('',(#178973),#173124,.T.); +#178973 = FACE_BOUND('',#178974,.T.); +#178974 = EDGE_LOOP('',(#178975,#178976,#178977,#179020)); +#178975 = ORIENTED_EDGE('',*,*,#173085,.F.); +#178976 = ORIENTED_EDGE('',*,*,#178711,.F.); +#178977 = ORIENTED_EDGE('',*,*,#178978,.F.); +#178978 = EDGE_CURVE('',#176143,#173527,#178979,.T.); +#178979 = SURFACE_CURVE('',#178980,(#178985,#179014),.PCURVE_S1.); +#178980 = CIRCLE('',#178981,5.E-002); +#178981 = AXIS2_PLACEMENT_3D('',#178982,#178983,#178984); +#178982 = CARTESIAN_POINT('',(1.174271552513,0.600864135142,1.15)); +#178983 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#178984 = DIRECTION('',(0.E+000,0.E+000,1.)); +#178985 = PCURVE('',#173124,#178986); +#178986 = DEFINITIONAL_REPRESENTATION('',(#178987),#179013); +#178987 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178988,#178989,#178990, + #178991,#178992,#178993,#178994,#178995,#178996,#178997,#178998, + #178999,#179000,#179001,#179002,#179003,#179004,#179005,#179006, + #179007,#179008,#179009,#179010,#179011,#179012),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -218748,81 +221750,81 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#176596 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176597 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#176598 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#176599 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#176600 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#176601 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#176602 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#176603 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#176604 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#176605 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#176606 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#176607 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#176608 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#176609 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#176610 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#176611 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#176612 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#176613 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#176614 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#176615 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#176616 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#176617 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#176618 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#176619 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#176620 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176622 = PCURVE('',#170587,#176623); -#176623 = DEFINITIONAL_REPRESENTATION('',(#176624),#176627); -#176624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176625,#176626), +#178988 = CARTESIAN_POINT('',(0.751879414295,1.)); +#178989 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#178990 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#178991 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#178992 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#178993 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#178994 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#178995 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#178996 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#178997 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#178998 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#178999 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#179000 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#179001 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#179002 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#179003 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#179004 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#179005 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#179006 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#179007 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#179008 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#179009 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#179010 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#179011 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#179012 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179014 = PCURVE('',#172979,#179015); +#179015 = DEFINITIONAL_REPRESENTATION('',(#179016),#179019); +#179016 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179017,#179018), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#176625 = CARTESIAN_POINT('',(0.E+000,0.295728447487)); -#176626 = CARTESIAN_POINT('',(1.308996938996,0.295728447487)); -#176627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176628 = ORIENTED_EDGE('',*,*,#173750,.F.); -#176629 = ADVANCED_FACE('',(#176630),#170587,.T.); -#176630 = FACE_BOUND('',#176631,.T.); -#176631 = EDGE_LOOP('',(#176632,#176633,#176634,#176635)); -#176632 = ORIENTED_EDGE('',*,*,#176586,.T.); -#176633 = ORIENTED_EDGE('',*,*,#171134,.F.); -#176634 = ORIENTED_EDGE('',*,*,#170550,.F.); -#176635 = ORIENTED_EDGE('',*,*,#173797,.F.); -#176636 = ADVANCED_FACE('',(#176637),#170862,.T.); -#176637 = FACE_BOUND('',#176638,.T.); -#176638 = EDGE_LOOP('',(#176639,#176640,#176641,#176684)); -#176639 = ORIENTED_EDGE('',*,*,#170825,.T.); -#176640 = ORIENTED_EDGE('',*,*,#173706,.F.); -#176641 = ORIENTED_EDGE('',*,*,#176642,.F.); -#176642 = EDGE_CURVE('',#172875,#173660,#176643,.T.); -#176643 = SURFACE_CURVE('',#176644,(#176649,#176655),.PCURVE_S1.); -#176644 = CIRCLE('',#176645,5.E-002); -#176645 = AXIS2_PLACEMENT_3D('',#176646,#176647,#176648); -#176646 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.15)); -#176647 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#176648 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#176649 = PCURVE('',#170862,#176650); -#176650 = DEFINITIONAL_REPRESENTATION('',(#176651),#176654); -#176651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176652,#176653), +#179017 = CARTESIAN_POINT('',(0.E+000,0.295728447487)); +#179018 = CARTESIAN_POINT('',(1.308996938996,0.295728447487)); +#179019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179020 = ORIENTED_EDGE('',*,*,#176142,.F.); +#179021 = ADVANCED_FACE('',(#179022),#172979,.T.); +#179022 = FACE_BOUND('',#179023,.T.); +#179023 = EDGE_LOOP('',(#179024,#179025,#179026,#179027)); +#179024 = ORIENTED_EDGE('',*,*,#178978,.T.); +#179025 = ORIENTED_EDGE('',*,*,#173526,.F.); +#179026 = ORIENTED_EDGE('',*,*,#172942,.F.); +#179027 = ORIENTED_EDGE('',*,*,#176189,.F.); +#179028 = ADVANCED_FACE('',(#179029),#173254,.T.); +#179029 = FACE_BOUND('',#179030,.T.); +#179030 = EDGE_LOOP('',(#179031,#179032,#179033,#179076)); +#179031 = ORIENTED_EDGE('',*,*,#173217,.T.); +#179032 = ORIENTED_EDGE('',*,*,#176098,.F.); +#179033 = ORIENTED_EDGE('',*,*,#179034,.F.); +#179034 = EDGE_CURVE('',#175267,#176052,#179035,.T.); +#179035 = SURFACE_CURVE('',#179036,(#179041,#179047),.PCURVE_S1.); +#179036 = CIRCLE('',#179037,5.E-002); +#179037 = AXIS2_PLACEMENT_3D('',#179038,#179039,#179040); +#179038 = CARTESIAN_POINT('',(1.270864135142,-0.504271552513,1.15)); +#179039 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#179040 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179041 = PCURVE('',#173254,#179042); +#179042 = DEFINITIONAL_REPRESENTATION('',(#179043),#179046); +#179043 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179044,#179045), .UNSPECIFIED.,.F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#176652 = CARTESIAN_POINT('',(2.879793265791,0.295728447487)); -#176653 = CARTESIAN_POINT('',(1.570796326795,0.295728447487)); -#176654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#179044 = CARTESIAN_POINT('',(2.879793265791,0.295728447487)); +#179045 = CARTESIAN_POINT('',(1.570796326795,0.295728447487)); +#179046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#176655 = PCURVE('',#170182,#176656); -#176656 = DEFINITIONAL_REPRESENTATION('',(#176657),#176683); -#176657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176658,#176659,#176660, - #176661,#176662,#176663,#176664,#176665,#176666,#176667,#176668, - #176669,#176670,#176671,#176672,#176673,#176674,#176675,#176676, - #176677,#176678,#176679,#176680,#176681,#176682),.UNSPECIFIED.,.F., +#179047 = PCURVE('',#172574,#179048); +#179048 = DEFINITIONAL_REPRESENTATION('',(#179049),#179075); +#179049 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179050,#179051,#179052, + #179053,#179054,#179055,#179056,#179057,#179058,#179059,#179060, + #179061,#179062,#179063,#179064,#179065,#179066,#179067,#179068, + #179069,#179070,#179071,#179072,#179073,#179074),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594, 1.892095575457,1.951595436321,2.011095297184,2.070595158048, 2.130095018911,2.189594879775,2.249094740638,2.308594601502, @@ -218830,54 +221832,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.606093905819,2.665593766682,2.725093627546,2.784593488409, 2.844093349273,2.903593210136,2.963093070999,3.022592931863, 3.082092792726,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#176658 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176659 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#176660 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#176661 = CARTESIAN_POINT('',(0.751879204681,9.115656938681E-002)); -#176662 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#176663 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#176664 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#176665 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#176666 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#176667 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#176668 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#176669 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#176670 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#176671 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#176672 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#176673 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#176674 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#176675 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#176676 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#176677 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#176678 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#176679 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#176680 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#176681 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#176682 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176684 = ORIENTED_EDGE('',*,*,#172874,.F.); -#176685 = ADVANCED_FACE('',(#176686),#170457,.T.); -#176686 = FACE_BOUND('',#176687,.T.); -#176687 = EDGE_LOOP('',(#176688,#176689,#176690,#176733)); -#176688 = ORIENTED_EDGE('',*,*,#170418,.F.); -#176689 = ORIENTED_EDGE('',*,*,#175897,.F.); -#176690 = ORIENTED_EDGE('',*,*,#176691,.F.); -#176691 = EDGE_CURVE('',#173546,#173010,#176692,.T.); -#176692 = SURFACE_CURVE('',#176693,(#176698,#176727),.PCURVE_S1.); -#176693 = CIRCLE('',#176694,5.E-002); -#176694 = AXIS2_PLACEMENT_3D('',#176695,#176696,#176697); -#176695 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.15)); -#176696 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#176697 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#176698 = PCURVE('',#170457,#176699); -#176699 = DEFINITIONAL_REPRESENTATION('',(#176700),#176726); -#176700 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176701,#176702,#176703, - #176704,#176705,#176706,#176707,#176708,#176709,#176710,#176711, - #176712,#176713,#176714,#176715,#176716,#176717,#176718,#176719, - #176720,#176721,#176722,#176723,#176724,#176725),.UNSPECIFIED.,.F., +#179050 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179051 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#179052 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#179053 = CARTESIAN_POINT('',(0.751879204681,9.115656938681E-002)); +#179054 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#179055 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#179056 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#179057 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#179058 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#179059 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#179060 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#179061 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#179062 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#179063 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#179064 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#179065 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#179066 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#179067 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#179068 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#179069 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#179070 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#179071 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#179072 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#179073 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#179074 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179076 = ORIENTED_EDGE('',*,*,#175266,.F.); +#179077 = ADVANCED_FACE('',(#179078),#172849,.T.); +#179078 = FACE_BOUND('',#179079,.T.); +#179079 = EDGE_LOOP('',(#179080,#179081,#179082,#179125)); +#179080 = ORIENTED_EDGE('',*,*,#172810,.F.); +#179081 = ORIENTED_EDGE('',*,*,#178289,.F.); +#179082 = ORIENTED_EDGE('',*,*,#179083,.F.); +#179083 = EDGE_CURVE('',#175938,#175402,#179084,.T.); +#179084 = SURFACE_CURVE('',#179085,(#179090,#179119),.PCURVE_S1.); +#179085 = CIRCLE('',#179086,5.E-002); +#179086 = AXIS2_PLACEMENT_3D('',#179087,#179088,#179089); +#179087 = CARTESIAN_POINT('',(-1.270864135142,0.504271552513,1.15)); +#179088 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#179089 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179090 = PCURVE('',#172849,#179091); +#179091 = DEFINITIONAL_REPRESENTATION('',(#179092),#179118); +#179092 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179093,#179094,#179095, + #179096,#179097,#179098,#179099,#179100,#179101,#179102,#179103, + #179104,#179105,#179106,#179107,#179108,#179109,#179110,#179111, + #179112,#179113,#179114,#179115,#179116,#179117),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.201092514453,3.260592375317,3.32009223618,3.379592097044, 3.439091957907,3.49859181877,3.558091679634,3.617591540497, @@ -218885,88 +221887,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 3.915090844815,3.974590705678,4.034090566541,4.093590427405, 4.153090288268,4.212590149132,4.272090009995,4.331589870859, 4.391089731722,4.450589592586),.QUASI_UNIFORM_KNOTS.); -#176701 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176702 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#176703 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#176704 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#176705 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#176706 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#176707 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#176708 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#176709 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#176710 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#176711 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#176712 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#176713 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#176714 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#176715 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#176716 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#176717 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#176718 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#176719 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#176720 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#176721 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#176722 = CARTESIAN_POINT('',(0.751879204681,9.115656938683E-002)); -#176723 = CARTESIAN_POINT('',(0.751879407428,4.551530551224E-002)); -#176724 = CARTESIAN_POINT('',(0.751879422945,1.51532140276E-002)); -#176725 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176726 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176727 = PCURVE('',#170037,#176728); -#176728 = DEFINITIONAL_REPRESENTATION('',(#176729),#176732); -#176729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176730,#176731), +#179093 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179094 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#179095 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#179096 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#179097 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#179098 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#179099 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#179100 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#179101 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#179102 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#179103 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#179104 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#179105 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#179106 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#179107 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#179108 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#179109 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#179110 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#179111 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#179112 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#179113 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#179114 = CARTESIAN_POINT('',(0.751879204681,9.115656938683E-002)); +#179115 = CARTESIAN_POINT('',(0.751879407428,4.551530551224E-002)); +#179116 = CARTESIAN_POINT('',(0.751879422945,1.51532140276E-002)); +#179117 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179119 = PCURVE('',#172429,#179120); +#179120 = DEFINITIONAL_REPRESENTATION('',(#179121),#179124); +#179121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179122,#179123), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.450589592586), .PIECEWISE_BEZIER_KNOTS.); -#176730 = CARTESIAN_POINT('',(1.570796326795,-1.304271552513)); -#176731 = CARTESIAN_POINT('',(2.879793265791,-1.304271552513)); -#176732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176733 = ORIENTED_EDGE('',*,*,#173818,.F.); -#176734 = ADVANCED_FACE('',(#176735),#170182,.T.); -#176735 = FACE_BOUND('',#176736,.T.); -#176736 = EDGE_LOOP('',(#176737,#176738,#176739,#176740)); -#176737 = ORIENTED_EDGE('',*,*,#170143,.F.); -#176738 = ORIENTED_EDGE('',*,*,#176108,.F.); -#176739 = ORIENTED_EDGE('',*,*,#176642,.T.); -#176740 = ORIENTED_EDGE('',*,*,#173659,.F.); -#176741 = ADVANCED_FACE('',(#176742),#170037,.T.); -#176742 = FACE_BOUND('',#176743,.T.); -#176743 = EDGE_LOOP('',(#176744,#176745,#176746,#176747)); -#176744 = ORIENTED_EDGE('',*,*,#176691,.T.); -#176745 = ORIENTED_EDGE('',*,*,#173009,.F.); -#176746 = ORIENTED_EDGE('',*,*,#170000,.F.); -#176747 = ORIENTED_EDGE('',*,*,#173545,.F.); -#176748 = ADVANCED_FACE('',(#176749),#170312,.T.); -#176749 = FACE_BOUND('',#176750,.T.); -#176750 = EDGE_LOOP('',(#176751,#176752,#176753,#176796)); -#176751 = ORIENTED_EDGE('',*,*,#170275,.T.); -#176752 = ORIENTED_EDGE('',*,*,#173638,.F.); -#176753 = ORIENTED_EDGE('',*,*,#176754,.F.); -#176754 = EDGE_CURVE('',#173478,#173592,#176755,.T.); -#176755 = SURFACE_CURVE('',#176756,(#176761,#176767),.PCURVE_S1.); -#176756 = CIRCLE('',#176757,5.E-002); -#176757 = AXIS2_PLACEMENT_3D('',#176758,#176759,#176760); -#176758 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.15)); -#176759 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#176760 = DIRECTION('',(0.E+000,0.E+000,1.)); -#176761 = PCURVE('',#170312,#176762); -#176762 = DEFINITIONAL_REPRESENTATION('',(#176763),#176766); -#176763 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176764,#176765), +#179122 = CARTESIAN_POINT('',(1.570796326795,-1.304271552513)); +#179123 = CARTESIAN_POINT('',(2.879793265791,-1.304271552513)); +#179124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179125 = ORIENTED_EDGE('',*,*,#176210,.F.); +#179126 = ADVANCED_FACE('',(#179127),#172574,.T.); +#179127 = FACE_BOUND('',#179128,.T.); +#179128 = EDGE_LOOP('',(#179129,#179130,#179131,#179132)); +#179129 = ORIENTED_EDGE('',*,*,#172535,.F.); +#179130 = ORIENTED_EDGE('',*,*,#178500,.F.); +#179131 = ORIENTED_EDGE('',*,*,#179034,.T.); +#179132 = ORIENTED_EDGE('',*,*,#176051,.F.); +#179133 = ADVANCED_FACE('',(#179134),#172429,.T.); +#179134 = FACE_BOUND('',#179135,.T.); +#179135 = EDGE_LOOP('',(#179136,#179137,#179138,#179139)); +#179136 = ORIENTED_EDGE('',*,*,#179083,.T.); +#179137 = ORIENTED_EDGE('',*,*,#175401,.F.); +#179138 = ORIENTED_EDGE('',*,*,#172392,.F.); +#179139 = ORIENTED_EDGE('',*,*,#175937,.F.); +#179140 = ADVANCED_FACE('',(#179141),#172704,.T.); +#179141 = FACE_BOUND('',#179142,.T.); +#179142 = EDGE_LOOP('',(#179143,#179144,#179145,#179188)); +#179143 = ORIENTED_EDGE('',*,*,#172667,.T.); +#179144 = ORIENTED_EDGE('',*,*,#176030,.F.); +#179145 = ORIENTED_EDGE('',*,*,#179146,.F.); +#179146 = EDGE_CURVE('',#175870,#175984,#179147,.T.); +#179147 = SURFACE_CURVE('',#179148,(#179153,#179159),.PCURVE_S1.); +#179148 = CIRCLE('',#179149,5.E-002); +#179149 = AXIS2_PLACEMENT_3D('',#179150,#179151,#179152); +#179150 = CARTESIAN_POINT('',(-1.174271552513,-0.600864135142,1.15)); +#179151 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#179152 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179153 = PCURVE('',#172704,#179154); +#179154 = DEFINITIONAL_REPRESENTATION('',(#179155),#179158); +#179155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179156,#179157), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#176764 = CARTESIAN_POINT('',(4.450589592586,-2.644271552513)); -#176765 = CARTESIAN_POINT('',(3.14159265359,-2.644271552513)); -#176766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#179156 = CARTESIAN_POINT('',(4.450589592586,-2.644271552513)); +#179157 = CARTESIAN_POINT('',(3.14159265359,-2.644271552513)); +#179158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#176767 = PCURVE('',#169902,#176768); -#176768 = DEFINITIONAL_REPRESENTATION('',(#176769),#176795); -#176769 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176770,#176771,#176772, - #176773,#176774,#176775,#176776,#176777,#176778,#176779,#176780, - #176781,#176782,#176783,#176784,#176785,#176786,#176787,#176788, - #176789,#176790,#176791,#176792,#176793,#176794),.UNSPECIFIED.,.F., +#179159 = PCURVE('',#172294,#179160); +#179160 = DEFINITIONAL_REPRESENTATION('',(#179161),#179187); +#179161 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179162,#179163,#179164, + #179165,#179166,#179167,#179168,#179169,#179170,#179171,#179172, + #179173,#179174,#179175,#179176,#179177,#179178,#179179,#179180, + #179181,#179182,#179183,#179184,#179185,#179186),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533365,5.390687394228,5.450187255091, @@ -218974,61 +221976,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176770 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176771 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#176772 = CARTESIAN_POINT('',(0.751879407428,4.551530551224E-002)); -#176773 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#176774 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#176775 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#176776 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#176777 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#176778 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#176779 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#176780 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#176781 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#176782 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#176783 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#176784 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#176785 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#176786 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#176787 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#176788 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#176789 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#176790 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#176791 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#176792 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#176793 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#176794 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176796 = ORIENTED_EDGE('',*,*,#173477,.F.); -#176797 = ADVANCED_FACE('',(#176798),#169902,.T.); -#176798 = FACE_BOUND('',#176799,.T.); -#176799 = EDGE_LOOP('',(#176800,#176801,#176802,#176803)); -#176800 = ORIENTED_EDGE('',*,*,#169863,.F.); -#176801 = ORIENTED_EDGE('',*,*,#175686,.F.); -#176802 = ORIENTED_EDGE('',*,*,#176754,.T.); -#176803 = ORIENTED_EDGE('',*,*,#173591,.F.); -#176804 = ADVANCED_FACE('',(#176805),#169601,.T.); -#176805 = FACE_BOUND('',#176806,.T.); -#176806 = EDGE_LOOP('',(#176807,#176808,#176809,#176852)); -#176807 = ORIENTED_EDGE('',*,*,#169562,.F.); -#176808 = ORIENTED_EDGE('',*,*,#172714,.F.); -#176809 = ORIENTED_EDGE('',*,*,#176810,.F.); -#176810 = EDGE_CURVE('',#172124,#172670,#176811,.T.); -#176811 = SURFACE_CURVE('',#176812,(#176817,#176846),.PCURVE_S1.); -#176812 = CIRCLE('',#176813,5.E-002); -#176813 = AXIS2_PLACEMENT_3D('',#176814,#176815,#176816); -#176814 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,0.15)); -#176815 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#176816 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#176817 = PCURVE('',#169601,#176818); -#176818 = DEFINITIONAL_REPRESENTATION('',(#176819),#176845); -#176819 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176820,#176821,#176822, - #176823,#176824,#176825,#176826,#176827,#176828,#176829,#176830, - #176831,#176832,#176833,#176834,#176835,#176836,#176837,#176838, - #176839,#176840,#176841,#176842,#176843,#176844),.UNSPECIFIED.,.F., +#179162 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179163 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#179164 = CARTESIAN_POINT('',(0.751879407428,4.551530551224E-002)); +#179165 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#179166 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#179167 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#179168 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#179169 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#179170 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#179171 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#179172 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#179173 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#179174 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#179175 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#179176 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#179177 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#179178 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#179179 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#179180 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#179181 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#179182 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#179183 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#179184 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#179185 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#179186 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179188 = ORIENTED_EDGE('',*,*,#175869,.F.); +#179189 = ADVANCED_FACE('',(#179190),#172294,.T.); +#179190 = FACE_BOUND('',#179191,.T.); +#179191 = EDGE_LOOP('',(#179192,#179193,#179194,#179195)); +#179192 = ORIENTED_EDGE('',*,*,#172255,.F.); +#179193 = ORIENTED_EDGE('',*,*,#178078,.F.); +#179194 = ORIENTED_EDGE('',*,*,#179146,.T.); +#179195 = ORIENTED_EDGE('',*,*,#175983,.F.); +#179196 = ADVANCED_FACE('',(#179197),#171993,.T.); +#179197 = FACE_BOUND('',#179198,.T.); +#179198 = EDGE_LOOP('',(#179199,#179200,#179201,#179244)); +#179199 = ORIENTED_EDGE('',*,*,#171954,.F.); +#179200 = ORIENTED_EDGE('',*,*,#175106,.F.); +#179201 = ORIENTED_EDGE('',*,*,#179202,.F.); +#179202 = EDGE_CURVE('',#174516,#175062,#179203,.T.); +#179203 = SURFACE_CURVE('',#179204,(#179209,#179238),.PCURVE_S1.); +#179204 = CIRCLE('',#179205,5.E-002); +#179205 = AXIS2_PLACEMENT_3D('',#179206,#179207,#179208); +#179206 = CARTESIAN_POINT('',(-1.297659054385,0.531066471757,0.15)); +#179207 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#179208 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179209 = PCURVE('',#171993,#179210); +#179210 = DEFINITIONAL_REPRESENTATION('',(#179211),#179237); +#179211 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179212,#179213,#179214, + #179215,#179216,#179217,#179218,#179219,#179220,#179221,#179222, + #179223,#179224,#179225,#179226,#179227,#179228,#179229,#179230, + #179231,#179232,#179233,#179234,#179235,#179236),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -219036,74 +222038,74 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176820 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176821 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#176822 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#176823 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#176824 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#176825 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#176826 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#176827 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#176828 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#176829 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#176830 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#176831 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#176832 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#176833 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#176834 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#176835 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#176836 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#176837 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#176838 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#176839 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#176840 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#176841 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); -#176842 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); -#176843 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); -#176844 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176846 = PCURVE('',#169207,#176847); -#176847 = DEFINITIONAL_REPRESENTATION('',(#176848),#176851); -#176848 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176849,#176850), +#179212 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179213 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#179214 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#179215 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#179216 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#179217 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#179218 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#179219 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#179220 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#179221 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#179222 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#179223 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#179224 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#179225 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#179226 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#179227 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#179228 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#179229 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#179230 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#179231 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#179232 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#179233 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); +#179234 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); +#179235 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); +#179236 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179238 = PCURVE('',#171599,#179239); +#179239 = DEFINITIONAL_REPRESENTATION('',(#179240),#179243); +#179240 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179241,#179242), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#176849 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#176850 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#176851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176852 = ORIENTED_EDGE('',*,*,#176036,.F.); -#176853 = ADVANCED_FACE('',(#176854),#169757,.T.); -#176854 = FACE_BOUND('',#176855,.T.); -#176855 = EDGE_LOOP('',(#176856,#176857,#176858,#176901)); -#176856 = ORIENTED_EDGE('',*,*,#169720,.T.); -#176857 = ORIENTED_EDGE('',*,*,#172335,.F.); -#176858 = ORIENTED_EDGE('',*,*,#176859,.F.); -#176859 = EDGE_CURVE('',#172761,#172291,#176860,.T.); -#176860 = SURFACE_CURVE('',#176861,(#176866,#176872),.PCURVE_S1.); -#176861 = CIRCLE('',#176862,5.E-002); -#176862 = AXIS2_PLACEMENT_3D('',#176863,#176864,#176865); -#176863 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,0.15)); -#176864 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); -#176865 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); -#176866 = PCURVE('',#169757,#176867); -#176867 = DEFINITIONAL_REPRESENTATION('',(#176868),#176871); -#176868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176869,#176870), +#179241 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#179242 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#179243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179244 = ORIENTED_EDGE('',*,*,#178428,.F.); +#179245 = ADVANCED_FACE('',(#179246),#172149,.T.); +#179246 = FACE_BOUND('',#179247,.T.); +#179247 = EDGE_LOOP('',(#179248,#179249,#179250,#179293)); +#179248 = ORIENTED_EDGE('',*,*,#172112,.T.); +#179249 = ORIENTED_EDGE('',*,*,#174727,.F.); +#179250 = ORIENTED_EDGE('',*,*,#179251,.F.); +#179251 = EDGE_CURVE('',#175153,#174683,#179252,.T.); +#179252 = SURFACE_CURVE('',#179253,(#179258,#179264),.PCURVE_S1.); +#179253 = CIRCLE('',#179254,5.E-002); +#179254 = AXIS2_PLACEMENT_3D('',#179255,#179256,#179257); +#179255 = CARTESIAN_POINT('',(1.201066471757,0.627659054385,0.15)); +#179256 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); +#179257 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); +#179258 = PCURVE('',#172149,#179259); +#179259 = DEFINITIONAL_REPRESENTATION('',(#179260),#179263); +#179260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179261,#179262), .UNSPECIFIED.,.F.,.F.,(2,2),(4.712388980385,6.02138591938), .PIECEWISE_BEZIER_KNOTS.); -#176869 = CARTESIAN_POINT('',(0.E+000,2.671066471757)); -#176870 = CARTESIAN_POINT('',(1.308996938996,2.671066471757)); -#176871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#179261 = CARTESIAN_POINT('',(0.E+000,2.671066471757)); +#179262 = CARTESIAN_POINT('',(1.308996938996,2.671066471757)); +#179263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#176872 = PCURVE('',#169326,#176873); -#176873 = DEFINITIONAL_REPRESENTATION('',(#176874),#176900); -#176874 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176875,#176876,#176877, - #176878,#176879,#176880,#176881,#176882,#176883,#176884,#176885, - #176886,#176887,#176888,#176889,#176890,#176891,#176892,#176893, - #176894,#176895,#176896,#176897,#176898,#176899),.UNSPECIFIED.,.F., +#179264 = PCURVE('',#171718,#179265); +#179265 = DEFINITIONAL_REPRESENTATION('',(#179266),#179292); +#179266 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179267,#179268,#179269, + #179270,#179271,#179272,#179273,#179274,#179275,#179276,#179277, + #179278,#179279,#179280,#179281,#179282,#179283,#179284,#179285, + #179286,#179287,#179288,#179289,#179290,#179291),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -219111,68 +222113,68 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#176875 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176876 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#176877 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#176878 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#176879 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#176880 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#176881 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#176882 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#176883 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#176884 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#176885 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#176886 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#176887 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#176888 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#176889 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#176890 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#176891 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#176892 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#176893 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#176894 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#176895 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#176896 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#176897 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#176898 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#176899 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176901 = ORIENTED_EDGE('',*,*,#172760,.F.); -#176902 = ADVANCED_FACE('',(#176903),#169207,.T.); -#176903 = FACE_BOUND('',#176904,.T.); -#176904 = EDGE_LOOP('',(#176905,#176906,#176907,#176908)); -#176905 = ORIENTED_EDGE('',*,*,#176810,.T.); -#176906 = ORIENTED_EDGE('',*,*,#172669,.F.); -#176907 = ORIENTED_EDGE('',*,*,#169170,.F.); -#176908 = ORIENTED_EDGE('',*,*,#172173,.F.); -#176909 = ADVANCED_FACE('',(#176910),#169326,.T.); -#176910 = FACE_BOUND('',#176911,.T.); -#176911 = EDGE_LOOP('',(#176912,#176913,#176914,#176915)); -#176912 = ORIENTED_EDGE('',*,*,#169287,.F.); -#176913 = ORIENTED_EDGE('',*,*,#172782,.F.); -#176914 = ORIENTED_EDGE('',*,*,#176859,.T.); -#176915 = ORIENTED_EDGE('',*,*,#176458,.F.); -#176916 = ADVANCED_FACE('',(#176917),#169051,.T.); -#176917 = FACE_BOUND('',#176918,.T.); -#176918 = EDGE_LOOP('',(#176919,#176920,#176921,#176964)); -#176919 = ORIENTED_EDGE('',*,*,#169012,.F.); -#176920 = ORIENTED_EDGE('',*,*,#172623,.F.); -#176921 = ORIENTED_EDGE('',*,*,#176922,.F.); -#176922 = EDGE_CURVE('',#171774,#172602,#176923,.T.); -#176923 = SURFACE_CURVE('',#176924,(#176929,#176958),.PCURVE_S1.); -#176924 = CIRCLE('',#176925,5.E-002); -#176925 = AXIS2_PLACEMENT_3D('',#176926,#176927,#176928); -#176926 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,0.15)); -#176927 = DIRECTION('',(1.,0.E+000,0.E+000)); -#176928 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#176929 = PCURVE('',#169051,#176930); -#176930 = DEFINITIONAL_REPRESENTATION('',(#176931),#176957); -#176931 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176932,#176933,#176934, - #176935,#176936,#176937,#176938,#176939,#176940,#176941,#176942, - #176943,#176944,#176945,#176946,#176947,#176948,#176949,#176950, - #176951,#176952,#176953,#176954,#176955,#176956),.UNSPECIFIED.,.F., +#179267 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179268 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#179269 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#179270 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#179271 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#179272 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#179273 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#179274 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#179275 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#179276 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#179277 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#179278 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#179279 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#179280 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#179281 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#179282 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#179283 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#179284 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#179285 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#179286 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#179287 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#179288 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#179289 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#179290 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#179291 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179293 = ORIENTED_EDGE('',*,*,#175152,.F.); +#179294 = ADVANCED_FACE('',(#179295),#171599,.T.); +#179295 = FACE_BOUND('',#179296,.T.); +#179296 = EDGE_LOOP('',(#179297,#179298,#179299,#179300)); +#179297 = ORIENTED_EDGE('',*,*,#179202,.T.); +#179298 = ORIENTED_EDGE('',*,*,#175061,.F.); +#179299 = ORIENTED_EDGE('',*,*,#171562,.F.); +#179300 = ORIENTED_EDGE('',*,*,#174565,.F.); +#179301 = ADVANCED_FACE('',(#179302),#171718,.T.); +#179302 = FACE_BOUND('',#179303,.T.); +#179303 = EDGE_LOOP('',(#179304,#179305,#179306,#179307)); +#179304 = ORIENTED_EDGE('',*,*,#171679,.F.); +#179305 = ORIENTED_EDGE('',*,*,#175174,.F.); +#179306 = ORIENTED_EDGE('',*,*,#179251,.T.); +#179307 = ORIENTED_EDGE('',*,*,#178850,.F.); +#179308 = ADVANCED_FACE('',(#179309),#171443,.T.); +#179309 = FACE_BOUND('',#179310,.T.); +#179310 = EDGE_LOOP('',(#179311,#179312,#179313,#179356)); +#179311 = ORIENTED_EDGE('',*,*,#171404,.F.); +#179312 = ORIENTED_EDGE('',*,*,#175015,.F.); +#179313 = ORIENTED_EDGE('',*,*,#179314,.F.); +#179314 = EDGE_CURVE('',#174166,#174994,#179315,.T.); +#179315 = SURFACE_CURVE('',#179316,(#179321,#179350),.PCURVE_S1.); +#179316 = CIRCLE('',#179317,5.E-002); +#179317 = AXIS2_PLACEMENT_3D('',#179318,#179319,#179320); +#179318 = CARTESIAN_POINT('',(-1.201066471757,-0.627659054385,0.15)); +#179319 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179320 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179321 = PCURVE('',#171443,#179322); +#179322 = DEFINITIONAL_REPRESENTATION('',(#179323),#179349); +#179323 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179324,#179325,#179326, + #179327,#179328,#179329,#179330,#179331,#179332,#179333,#179334, + #179335,#179336,#179337,#179338,#179339,#179340,#179341,#179342, + #179343,#179344,#179345,#179346,#179347,#179348),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533365,5.390687394228,5.450187255091, @@ -219180,74 +222182,74 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#176932 = CARTESIAN_POINT('',(0.751879414295,1.)); -#176933 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#176934 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#176935 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#176936 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#176937 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#176938 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#176939 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#176940 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#176941 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#176942 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#176943 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#176944 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#176945 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#176946 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#176947 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#176948 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#176949 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#176950 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#176951 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#176952 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#176953 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#176954 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#176955 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#176956 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176957 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176958 = PCURVE('',#168909,#176959); -#176959 = DEFINITIONAL_REPRESENTATION('',(#176960),#176963); -#176960 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176961,#176962), +#179324 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179325 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#179326 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#179327 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#179328 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#179329 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#179330 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#179331 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#179332 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#179333 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#179334 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#179335 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#179336 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#179337 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#179338 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#179339 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#179340 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#179341 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#179342 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#179343 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#179344 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#179345 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#179346 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#179347 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#179348 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179350 = PCURVE('',#171301,#179351); +#179351 = DEFINITIONAL_REPRESENTATION('',(#179352),#179355); +#179352 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179353,#179354), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#176961 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#176962 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#176963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#176964 = ORIENTED_EDGE('',*,*,#175825,.F.); -#176965 = ADVANCED_FACE('',(#176966),#169482,.T.); -#176966 = FACE_BOUND('',#176967,.T.); -#176967 = EDGE_LOOP('',(#176968,#176969,#176970,#177013)); -#176968 = ORIENTED_EDGE('',*,*,#169445,.T.); -#176969 = ORIENTED_EDGE('',*,*,#171654,.F.); -#176970 = ORIENTED_EDGE('',*,*,#176971,.F.); -#176971 = EDGE_CURVE('',#172511,#171605,#176972,.T.); -#176972 = SURFACE_CURVE('',#176973,(#176978,#176984),.PCURVE_S1.); -#176973 = CIRCLE('',#176974,5.E-002); -#176974 = AXIS2_PLACEMENT_3D('',#176975,#176976,#176977); -#176975 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,0.15)); -#176976 = DIRECTION('',(-2.244897367846E-015,-1.,0.E+000)); -#176977 = DIRECTION('',(1.,-2.244897367846E-015,0.E+000)); -#176978 = PCURVE('',#169482,#176979); -#176979 = DEFINITIONAL_REPRESENTATION('',(#176980),#176983); -#176980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#176981,#176982), +#179353 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#179354 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#179355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179356 = ORIENTED_EDGE('',*,*,#178217,.F.); +#179357 = ADVANCED_FACE('',(#179358),#171874,.T.); +#179358 = FACE_BOUND('',#179359,.T.); +#179359 = EDGE_LOOP('',(#179360,#179361,#179362,#179405)); +#179360 = ORIENTED_EDGE('',*,*,#171837,.T.); +#179361 = ORIENTED_EDGE('',*,*,#174046,.F.); +#179362 = ORIENTED_EDGE('',*,*,#179363,.F.); +#179363 = EDGE_CURVE('',#174903,#173997,#179364,.T.); +#179364 = SURFACE_CURVE('',#179365,(#179370,#179376),.PCURVE_S1.); +#179365 = CIRCLE('',#179366,5.E-002); +#179366 = AXIS2_PLACEMENT_3D('',#179367,#179368,#179369); +#179367 = CARTESIAN_POINT('',(1.297659054385,-0.531066471757,0.15)); +#179368 = DIRECTION('',(-2.244897367846E-015,-1.,0.E+000)); +#179369 = DIRECTION('',(1.,-2.244897367846E-015,0.E+000)); +#179370 = PCURVE('',#171874,#179371); +#179371 = DEFINITIONAL_REPRESENTATION('',(#179372),#179375); +#179372 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179373,#179374), .UNSPECIFIED.,.F.,.F.,(2,2),(4.712388980385,6.02138591938), .PIECEWISE_BEZIER_KNOTS.); -#176981 = CARTESIAN_POINT('',(4.712388980385,1.331066471757)); -#176982 = CARTESIAN_POINT('',(6.02138591938,1.331066471757)); -#176983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#179373 = CARTESIAN_POINT('',(4.712388980385,1.331066471757)); +#179374 = CARTESIAN_POINT('',(6.02138591938,1.331066471757)); +#179375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#176984 = PCURVE('',#168753,#176985); -#176985 = DEFINITIONAL_REPRESENTATION('',(#176986),#177012); -#176986 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#176987,#176988,#176989, - #176990,#176991,#176992,#176993,#176994,#176995,#176996,#176997, - #176998,#176999,#177000,#177001,#177002,#177003,#177004,#177005, - #177006,#177007,#177008,#177009,#177010,#177011),.UNSPECIFIED.,.F., +#179376 = PCURVE('',#171145,#179377); +#179377 = DEFINITIONAL_REPRESENTATION('',(#179378),#179404); +#179378 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179379,#179380,#179381, + #179382,#179383,#179384,#179385,#179386,#179387,#179388,#179389, + #179390,#179391,#179392,#179393,#179394,#179395,#179396,#179397, + #179398,#179399,#179400,#179401,#179402,#179403),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -219255,893 +222257,893 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#176987 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#176988 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); -#176989 = CARTESIAN_POINT('',(0.751879417419,4.55153070375E-002)); -#176990 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); -#176991 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#176992 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#176993 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#176994 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#176995 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#176996 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#176997 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#176998 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#176999 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#177000 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#177001 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#177002 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#177003 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#177004 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#177005 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#177006 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#177007 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#177008 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#177009 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#177010 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#177011 = CARTESIAN_POINT('',(0.751879414295,1.)); -#177012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177013 = ORIENTED_EDGE('',*,*,#172510,.F.); -#177014 = ADVANCED_FACE('',(#177015),#168909,.T.); -#177015 = FACE_BOUND('',#177016,.T.); -#177016 = EDGE_LOOP('',(#177017,#177018,#177019,#177020)); -#177017 = ORIENTED_EDGE('',*,*,#176922,.T.); -#177018 = ORIENTED_EDGE('',*,*,#172601,.F.); -#177019 = ORIENTED_EDGE('',*,*,#168872,.F.); -#177020 = ORIENTED_EDGE('',*,*,#171823,.F.); -#177021 = ADVANCED_FACE('',(#177022),#168753,.T.); -#177022 = FACE_BOUND('',#177023,.T.); -#177023 = EDGE_LOOP('',(#177024,#177025,#177026,#177027)); -#177024 = ORIENTED_EDGE('',*,*,#168714,.F.); -#177025 = ORIENTED_EDGE('',*,*,#172555,.F.); -#177026 = ORIENTED_EDGE('',*,*,#176971,.T.); -#177027 = ORIENTED_EDGE('',*,*,#176247,.F.); -#177028 = ADVANCED_FACE('',(#177029),#172467,.T.); -#177029 = FACE_BOUND('',#177030,.T.); -#177030 = EDGE_LOOP('',(#177031,#177032,#177055,#177082)); -#177031 = ORIENTED_EDGE('',*,*,#172453,.T.); -#177032 = ORIENTED_EDGE('',*,*,#177033,.T.); -#177033 = EDGE_CURVE('',#171388,#177034,#177036,.T.); -#177034 = VERTEX_POINT('',#177035); -#177035 = CARTESIAN_POINT('',(0.135,0.807264967154,0.6)); -#177036 = SURFACE_CURVE('',#177037,(#177041,#177048),.PCURVE_S1.); -#177037 = LINE('',#177038,#177039); -#177038 = CARTESIAN_POINT('',(0.135,0.7,0.6)); -#177039 = VECTOR('',#177040,1.); -#177040 = DIRECTION('',(0.E+000,1.,0.E+000)); -#177041 = PCURVE('',#172467,#177042); -#177042 = DEFINITIONAL_REPRESENTATION('',(#177043),#177047); -#177043 = LINE('',#177044,#177045); -#177044 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177045 = VECTOR('',#177046,1.); -#177046 = DIRECTION('',(0.E+000,1.)); -#177047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177048 = PCURVE('',#171403,#177049); -#177049 = DEFINITIONAL_REPRESENTATION('',(#177050),#177054); -#177050 = LINE('',#177051,#177052); -#177051 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#177052 = VECTOR('',#177053,1.); -#177053 = DIRECTION('',(0.E+000,1.)); -#177054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177055 = ORIENTED_EDGE('',*,*,#177056,.T.); -#177056 = EDGE_CURVE('',#177034,#177057,#177059,.T.); -#177057 = VERTEX_POINT('',#177058); -#177058 = CARTESIAN_POINT('',(0.475,0.807264967154,0.6)); -#177059 = SURFACE_CURVE('',#177060,(#177064,#177071),.PCURVE_S1.); -#177060 = LINE('',#177061,#177062); -#177061 = CARTESIAN_POINT('',(0.135,0.807264967154,0.6)); -#177062 = VECTOR('',#177063,1.); -#177063 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177064 = PCURVE('',#172467,#177065); -#177065 = DEFINITIONAL_REPRESENTATION('',(#177066),#177070); -#177066 = LINE('',#177067,#177068); -#177067 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); -#177068 = VECTOR('',#177069,1.); -#177069 = DIRECTION('',(-1.,0.E+000)); -#177070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#179379 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#179380 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); +#179381 = CARTESIAN_POINT('',(0.751879417419,4.55153070375E-002)); +#179382 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); +#179383 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#179384 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#179385 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#179386 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#179387 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#179388 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#179389 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#179390 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#179391 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#179392 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#179393 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#179394 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#179395 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#179396 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#179397 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#179398 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#179399 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#179400 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#179401 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#179402 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#179403 = CARTESIAN_POINT('',(0.751879414295,1.)); +#179404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179405 = ORIENTED_EDGE('',*,*,#174902,.F.); +#179406 = ADVANCED_FACE('',(#179407),#171301,.T.); +#179407 = FACE_BOUND('',#179408,.T.); +#179408 = EDGE_LOOP('',(#179409,#179410,#179411,#179412)); +#179409 = ORIENTED_EDGE('',*,*,#179314,.T.); +#179410 = ORIENTED_EDGE('',*,*,#174993,.F.); +#179411 = ORIENTED_EDGE('',*,*,#171264,.F.); +#179412 = ORIENTED_EDGE('',*,*,#174215,.F.); +#179413 = ADVANCED_FACE('',(#179414),#171145,.T.); +#179414 = FACE_BOUND('',#179415,.T.); +#179415 = EDGE_LOOP('',(#179416,#179417,#179418,#179419)); +#179416 = ORIENTED_EDGE('',*,*,#171106,.F.); +#179417 = ORIENTED_EDGE('',*,*,#174947,.F.); +#179418 = ORIENTED_EDGE('',*,*,#179363,.T.); +#179419 = ORIENTED_EDGE('',*,*,#178639,.F.); +#179420 = ADVANCED_FACE('',(#179421),#174859,.T.); +#179421 = FACE_BOUND('',#179422,.T.); +#179422 = EDGE_LOOP('',(#179423,#179424,#179447,#179474)); +#179423 = ORIENTED_EDGE('',*,*,#174845,.T.); +#179424 = ORIENTED_EDGE('',*,*,#179425,.T.); +#179425 = EDGE_CURVE('',#173780,#179426,#179428,.T.); +#179426 = VERTEX_POINT('',#179427); +#179427 = CARTESIAN_POINT('',(0.135,0.807264967154,0.6)); +#179428 = SURFACE_CURVE('',#179429,(#179433,#179440),.PCURVE_S1.); +#179429 = LINE('',#179430,#179431); +#179430 = CARTESIAN_POINT('',(0.135,0.7,0.6)); +#179431 = VECTOR('',#179432,1.); +#179432 = DIRECTION('',(0.E+000,1.,0.E+000)); +#179433 = PCURVE('',#174859,#179434); +#179434 = DEFINITIONAL_REPRESENTATION('',(#179435),#179439); +#179435 = LINE('',#179436,#179437); +#179436 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179437 = VECTOR('',#179438,1.); +#179438 = DIRECTION('',(0.E+000,1.)); +#179439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179440 = PCURVE('',#173795,#179441); +#179441 = DEFINITIONAL_REPRESENTATION('',(#179442),#179446); +#179442 = LINE('',#179443,#179444); +#179443 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#179444 = VECTOR('',#179445,1.); +#179445 = DIRECTION('',(0.E+000,1.)); +#179446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#177071 = PCURVE('',#177072,#177077); -#177072 = CYLINDRICAL_SURFACE('',#177073,0.1); -#177073 = AXIS2_PLACEMENT_3D('',#177074,#177075,#177076); -#177074 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); -#177075 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177076 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177077 = DEFINITIONAL_REPRESENTATION('',(#177078),#177081); -#177078 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177079,#177080), +#179447 = ORIENTED_EDGE('',*,*,#179448,.T.); +#179448 = EDGE_CURVE('',#179426,#179449,#179451,.T.); +#179449 = VERTEX_POINT('',#179450); +#179450 = CARTESIAN_POINT('',(0.475,0.807264967154,0.6)); +#179451 = SURFACE_CURVE('',#179452,(#179456,#179463),.PCURVE_S1.); +#179452 = LINE('',#179453,#179454); +#179453 = CARTESIAN_POINT('',(0.135,0.807264967154,0.6)); +#179454 = VECTOR('',#179455,1.); +#179455 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179456 = PCURVE('',#174859,#179457); +#179457 = DEFINITIONAL_REPRESENTATION('',(#179458),#179462); +#179458 = LINE('',#179459,#179460); +#179459 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); +#179460 = VECTOR('',#179461,1.); +#179461 = DIRECTION('',(-1.,0.E+000)); +#179462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179463 = PCURVE('',#179464,#179469); +#179464 = CYLINDRICAL_SURFACE('',#179465,0.1); +#179465 = AXIS2_PLACEMENT_3D('',#179466,#179467,#179468); +#179466 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); +#179467 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179468 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179469 = DEFINITIONAL_REPRESENTATION('',(#179470),#179473); +#179470 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179471,#179472), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177079 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#177080 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#177081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177082 = ORIENTED_EDGE('',*,*,#177083,.F.); -#177083 = EDGE_CURVE('',#171309,#177057,#177084,.T.); -#177084 = SURFACE_CURVE('',#177085,(#177089,#177096),.PCURVE_S1.); -#177085 = LINE('',#177086,#177087); -#177086 = CARTESIAN_POINT('',(0.475,0.7,0.6)); -#177087 = VECTOR('',#177088,1.); -#177088 = DIRECTION('',(0.E+000,1.,0.E+000)); -#177089 = PCURVE('',#172467,#177090); -#177090 = DEFINITIONAL_REPRESENTATION('',(#177091),#177095); -#177091 = LINE('',#177092,#177093); -#177092 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#177093 = VECTOR('',#177094,1.); -#177094 = DIRECTION('',(0.E+000,1.)); -#177095 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177096 = PCURVE('',#171347,#177097); -#177097 = DEFINITIONAL_REPRESENTATION('',(#177098),#177102); -#177098 = LINE('',#177099,#177100); -#177099 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#177100 = VECTOR('',#177101,1.); -#177101 = DIRECTION('',(0.E+000,1.)); -#177102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177103 = ADVANCED_FACE('',(#177104),#171403,.F.); -#177104 = FACE_BOUND('',#177105,.T.); -#177105 = EDGE_LOOP('',(#177106,#177107,#177108,#177131,#177159,#177187, - #177219,#177247,#177275,#177303,#177331,#177359)); -#177106 = ORIENTED_EDGE('',*,*,#177033,.F.); -#177107 = ORIENTED_EDGE('',*,*,#171387,.T.); -#177108 = ORIENTED_EDGE('',*,*,#177109,.F.); -#177109 = EDGE_CURVE('',#177110,#171360,#177112,.T.); -#177110 = VERTEX_POINT('',#177111); -#177111 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); -#177112 = SURFACE_CURVE('',#177113,(#177117,#177124),.PCURVE_S1.); -#177113 = LINE('',#177114,#177115); -#177114 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); -#177115 = VECTOR('',#177116,1.); -#177116 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#177117 = PCURVE('',#171403,#177118); -#177118 = DEFINITIONAL_REPRESENTATION('',(#177119),#177123); -#177119 = LINE('',#177120,#177121); -#177120 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#177121 = VECTOR('',#177122,1.); -#177122 = DIRECTION('',(0.E+000,-1.)); -#177123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177124 = PCURVE('',#171375,#177125); -#177125 = DEFINITIONAL_REPRESENTATION('',(#177126),#177130); -#177126 = LINE('',#177127,#177128); -#177127 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177128 = VECTOR('',#177129,1.); -#177129 = DIRECTION('',(0.E+000,-1.)); -#177130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177131 = ORIENTED_EDGE('',*,*,#177132,.F.); -#177132 = EDGE_CURVE('',#177133,#177110,#177135,.T.); -#177133 = VERTEX_POINT('',#177134); -#177134 = CARTESIAN_POINT('',(0.135,1.056555553792,0.518820292599)); -#177135 = SURFACE_CURVE('',#177136,(#177141,#177148),.PCURVE_S1.); -#177136 = CIRCLE('',#177137,0.25); -#177137 = AXIS2_PLACEMENT_3D('',#177138,#177139,#177140); -#177138 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); -#177139 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177140 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177141 = PCURVE('',#171403,#177142); -#177142 = DEFINITIONAL_REPRESENTATION('',(#177143),#177147); -#177143 = CIRCLE('',#177144,0.25); -#177144 = AXIS2_PLACEMENT_2D('',#177145,#177146); -#177145 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177146 = DIRECTION('',(1.,0.E+000)); -#177147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177148 = PCURVE('',#177149,#177154); -#177149 = CYLINDRICAL_SURFACE('',#177150,0.25); -#177150 = AXIS2_PLACEMENT_3D('',#177151,#177152,#177153); -#177151 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); -#177152 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177153 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177154 = DEFINITIONAL_REPRESENTATION('',(#177155),#177158); -#177155 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177156,#177157), +#179471 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#179472 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#179473 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179474 = ORIENTED_EDGE('',*,*,#179475,.F.); +#179475 = EDGE_CURVE('',#173701,#179449,#179476,.T.); +#179476 = SURFACE_CURVE('',#179477,(#179481,#179488),.PCURVE_S1.); +#179477 = LINE('',#179478,#179479); +#179478 = CARTESIAN_POINT('',(0.475,0.7,0.6)); +#179479 = VECTOR('',#179480,1.); +#179480 = DIRECTION('',(0.E+000,1.,0.E+000)); +#179481 = PCURVE('',#174859,#179482); +#179482 = DEFINITIONAL_REPRESENTATION('',(#179483),#179487); +#179483 = LINE('',#179484,#179485); +#179484 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#179485 = VECTOR('',#179486,1.); +#179486 = DIRECTION('',(0.E+000,1.)); +#179487 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179488 = PCURVE('',#173739,#179489); +#179489 = DEFINITIONAL_REPRESENTATION('',(#179490),#179494); +#179490 = LINE('',#179491,#179492); +#179491 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#179492 = VECTOR('',#179493,1.); +#179493 = DIRECTION('',(0.E+000,1.)); +#179494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179495 = ADVANCED_FACE('',(#179496),#173795,.F.); +#179496 = FACE_BOUND('',#179497,.T.); +#179497 = EDGE_LOOP('',(#179498,#179499,#179500,#179523,#179551,#179579, + #179611,#179639,#179667,#179695,#179723,#179751)); +#179498 = ORIENTED_EDGE('',*,*,#179425,.F.); +#179499 = ORIENTED_EDGE('',*,*,#173779,.T.); +#179500 = ORIENTED_EDGE('',*,*,#179501,.F.); +#179501 = EDGE_CURVE('',#179502,#173752,#179504,.T.); +#179502 = VERTEX_POINT('',#179503); +#179503 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); +#179504 = SURFACE_CURVE('',#179505,(#179509,#179516),.PCURVE_S1.); +#179505 = LINE('',#179506,#179507); +#179506 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); +#179507 = VECTOR('',#179508,1.); +#179508 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#179509 = PCURVE('',#173795,#179510); +#179510 = DEFINITIONAL_REPRESENTATION('',(#179511),#179515); +#179511 = LINE('',#179512,#179513); +#179512 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#179513 = VECTOR('',#179514,1.); +#179514 = DIRECTION('',(0.E+000,-1.)); +#179515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179516 = PCURVE('',#173767,#179517); +#179517 = DEFINITIONAL_REPRESENTATION('',(#179518),#179522); +#179518 = LINE('',#179519,#179520); +#179519 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179520 = VECTOR('',#179521,1.); +#179521 = DIRECTION('',(0.E+000,-1.)); +#179522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179523 = ORIENTED_EDGE('',*,*,#179524,.F.); +#179524 = EDGE_CURVE('',#179525,#179502,#179527,.T.); +#179525 = VERTEX_POINT('',#179526); +#179526 = CARTESIAN_POINT('',(0.135,1.056555553792,0.518820292599)); +#179527 = SURFACE_CURVE('',#179528,(#179533,#179540),.PCURVE_S1.); +#179528 = CIRCLE('',#179529,0.25); +#179529 = AXIS2_PLACEMENT_3D('',#179530,#179531,#179532); +#179530 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); +#179531 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179532 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179533 = PCURVE('',#173795,#179534); +#179534 = DEFINITIONAL_REPRESENTATION('',(#179535),#179539); +#179535 = CIRCLE('',#179536,0.25); +#179536 = AXIS2_PLACEMENT_2D('',#179537,#179538); +#179537 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179538 = DIRECTION('',(1.,0.E+000)); +#179539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179540 = PCURVE('',#179541,#179546); +#179541 = CYLINDRICAL_SURFACE('',#179542,0.25); +#179542 = AXIS2_PLACEMENT_3D('',#179543,#179544,#179545); +#179543 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); +#179544 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179545 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179546 = DEFINITIONAL_REPRESENTATION('',(#179547),#179550); +#179547 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179548,#179549), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#177156 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#177157 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#177158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177159 = ORIENTED_EDGE('',*,*,#177160,.F.); -#177160 = EDGE_CURVE('',#177161,#177133,#177163,.T.); -#177161 = VERTEX_POINT('',#177162); -#177162 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); -#177163 = SURFACE_CURVE('',#177164,(#177168,#177175),.PCURVE_S1.); -#177164 = LINE('',#177165,#177166); -#177165 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); -#177166 = VECTOR('',#177167,1.); -#177167 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#177168 = PCURVE('',#171403,#177169); -#177169 = DEFINITIONAL_REPRESENTATION('',(#177170),#177174); -#177170 = LINE('',#177171,#177172); -#177171 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#177172 = VECTOR('',#177173,1.); -#177173 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#177174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177175 = PCURVE('',#177176,#177181); -#177176 = PLANE('',#177177); -#177177 = AXIS2_PLACEMENT_3D('',#177178,#177179,#177180); -#177178 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); -#177179 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); -#177180 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#177181 = DEFINITIONAL_REPRESENTATION('',(#177182),#177186); -#177182 = LINE('',#177183,#177184); -#177183 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177184 = VECTOR('',#177185,1.); -#177185 = DIRECTION('',(1.,0.E+000)); -#177186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177187 = ORIENTED_EDGE('',*,*,#177188,.F.); -#177188 = EDGE_CURVE('',#177189,#177161,#177191,.T.); -#177189 = VERTEX_POINT('',#177190); -#177190 = CARTESIAN_POINT('',(0.135,1.1307673058,0.15)); -#177191 = SURFACE_CURVE('',#177192,(#177197,#177208),.PCURVE_S1.); -#177192 = CIRCLE('',#177193,5.E-002); -#177193 = AXIS2_PLACEMENT_3D('',#177194,#177195,#177196); -#177194 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); -#177195 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#177196 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177197 = PCURVE('',#171403,#177198); -#177198 = DEFINITIONAL_REPRESENTATION('',(#177199),#177207); -#177199 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177200,#177201,#177202, - #177203,#177204,#177205,#177206),.UNSPECIFIED.,.F.,.F.) +#179548 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#179549 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#179550 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179551 = ORIENTED_EDGE('',*,*,#179552,.F.); +#179552 = EDGE_CURVE('',#179553,#179525,#179555,.T.); +#179553 = VERTEX_POINT('',#179554); +#179554 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); +#179555 = SURFACE_CURVE('',#179556,(#179560,#179567),.PCURVE_S1.); +#179556 = LINE('',#179557,#179558); +#179557 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); +#179558 = VECTOR('',#179559,1.); +#179559 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#179560 = PCURVE('',#173795,#179561); +#179561 = DEFINITIONAL_REPRESENTATION('',(#179562),#179566); +#179562 = LINE('',#179563,#179564); +#179563 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#179564 = VECTOR('',#179565,1.); +#179565 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#179566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179567 = PCURVE('',#179568,#179573); +#179568 = PLANE('',#179569); +#179569 = AXIS2_PLACEMENT_3D('',#179570,#179571,#179572); +#179570 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); +#179571 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); +#179572 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#179573 = DEFINITIONAL_REPRESENTATION('',(#179574),#179578); +#179574 = LINE('',#179575,#179576); +#179575 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179576 = VECTOR('',#179577,1.); +#179577 = DIRECTION('',(1.,0.E+000)); +#179578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179579 = ORIENTED_EDGE('',*,*,#179580,.F.); +#179580 = EDGE_CURVE('',#179581,#179553,#179583,.T.); +#179581 = VERTEX_POINT('',#179582); +#179582 = CARTESIAN_POINT('',(0.135,1.1307673058,0.15)); +#179583 = SURFACE_CURVE('',#179584,(#179589,#179600),.PCURVE_S1.); +#179584 = CIRCLE('',#179585,5.E-002); +#179585 = AXIS2_PLACEMENT_3D('',#179586,#179587,#179588); +#179586 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); +#179587 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#179588 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179589 = PCURVE('',#173795,#179590); +#179590 = DEFINITIONAL_REPRESENTATION('',(#179591),#179599); +#179591 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179592,#179593,#179594, + #179595,#179596,#179597,#179598),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#177200 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#177201 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#177202 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#177203 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#177204 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#177205 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#177206 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#177207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177208 = PCURVE('',#177209,#177214); -#177209 = CYLINDRICAL_SURFACE('',#177210,5.E-002); -#177210 = AXIS2_PLACEMENT_3D('',#177211,#177212,#177213); -#177211 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); -#177212 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177213 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177214 = DEFINITIONAL_REPRESENTATION('',(#177215),#177218); -#177215 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177216,#177217), +#179592 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#179593 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#179594 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#179595 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#179596 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#179597 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#179598 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#179599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179600 = PCURVE('',#179601,#179606); +#179601 = CYLINDRICAL_SURFACE('',#179602,5.E-002); +#179602 = AXIS2_PLACEMENT_3D('',#179603,#179604,#179605); +#179603 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); +#179604 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179605 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179606 = DEFINITIONAL_REPRESENTATION('',(#179607),#179610); +#179607 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179608,#179609), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#177216 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#177217 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#177218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177219 = ORIENTED_EDGE('',*,*,#177220,.F.); -#177220 = EDGE_CURVE('',#177221,#177189,#177223,.T.); -#177221 = VERTEX_POINT('',#177222); -#177222 = CARTESIAN_POINT('',(0.135,1.4,0.15)); -#177223 = SURFACE_CURVE('',#177224,(#177228,#177235),.PCURVE_S1.); -#177224 = LINE('',#177225,#177226); -#177225 = CARTESIAN_POINT('',(0.135,1.4,0.15)); -#177226 = VECTOR('',#177227,1.); -#177227 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#177228 = PCURVE('',#171403,#177229); -#177229 = DEFINITIONAL_REPRESENTATION('',(#177230),#177234); -#177230 = LINE('',#177231,#177232); -#177231 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#177232 = VECTOR('',#177233,1.); -#177233 = DIRECTION('',(3.020255886006E-016,-1.)); -#177234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177235 = PCURVE('',#177236,#177241); -#177236 = PLANE('',#177237); -#177237 = AXIS2_PLACEMENT_3D('',#177238,#177239,#177240); -#177238 = CARTESIAN_POINT('',(0.135,1.4,0.15)); -#177239 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); -#177240 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#177241 = DEFINITIONAL_REPRESENTATION('',(#177242),#177246); -#177242 = LINE('',#177243,#177244); -#177243 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177244 = VECTOR('',#177245,1.); -#177245 = DIRECTION('',(1.,0.E+000)); -#177246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177247 = ORIENTED_EDGE('',*,*,#177248,.F.); -#177248 = EDGE_CURVE('',#177249,#177221,#177251,.T.); -#177249 = VERTEX_POINT('',#177250); -#177250 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177251 = SURFACE_CURVE('',#177252,(#177256,#177263),.PCURVE_S1.); -#177252 = LINE('',#177253,#177254); -#177253 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177254 = VECTOR('',#177255,1.); -#177255 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177256 = PCURVE('',#171403,#177257); -#177257 = DEFINITIONAL_REPRESENTATION('',(#177258),#177262); -#177258 = LINE('',#177259,#177260); -#177259 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#177260 = VECTOR('',#177261,1.); -#177261 = DIRECTION('',(-1.,0.E+000)); -#177262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177263 = PCURVE('',#177264,#177269); -#177264 = PLANE('',#177265); -#177265 = AXIS2_PLACEMENT_3D('',#177266,#177267,#177268); -#177266 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177267 = DIRECTION('',(0.E+000,1.,0.E+000)); -#177268 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177269 = DEFINITIONAL_REPRESENTATION('',(#177270),#177274); -#177270 = LINE('',#177271,#177272); -#177271 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177272 = VECTOR('',#177273,1.); -#177273 = DIRECTION('',(1.,0.E+000)); -#177274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177275 = ORIENTED_EDGE('',*,*,#177276,.F.); -#177276 = EDGE_CURVE('',#177277,#177249,#177279,.T.); -#177277 = VERTEX_POINT('',#177278); -#177278 = CARTESIAN_POINT('',(0.135,1.1307673058,2.042548750247E-016)); -#177279 = SURFACE_CURVE('',#177280,(#177284,#177291),.PCURVE_S1.); -#177280 = LINE('',#177281,#177282); -#177281 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177282 = VECTOR('',#177283,1.); -#177283 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#177284 = PCURVE('',#171403,#177285); -#177285 = DEFINITIONAL_REPRESENTATION('',(#177286),#177290); -#177286 = LINE('',#177287,#177288); -#177287 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#177288 = VECTOR('',#177289,1.); -#177289 = DIRECTION('',(-2.516879905005E-016,1.)); -#177290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177291 = PCURVE('',#177292,#177297); -#177292 = PLANE('',#177293); -#177293 = AXIS2_PLACEMENT_3D('',#177294,#177295,#177296); -#177294 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177295 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); -#177296 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#177297 = DEFINITIONAL_REPRESENTATION('',(#177298),#177302); -#177298 = LINE('',#177299,#177300); -#177299 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177300 = VECTOR('',#177301,1.); -#177301 = DIRECTION('',(1.,0.E+000)); -#177302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177303 = ORIENTED_EDGE('',*,*,#177304,.F.); -#177304 = EDGE_CURVE('',#177305,#177277,#177307,.T.); -#177305 = VERTEX_POINT('',#177306); -#177306 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); -#177307 = SURFACE_CURVE('',#177308,(#177313,#177320),.PCURVE_S1.); -#177308 = CIRCLE('',#177309,0.2); -#177309 = AXIS2_PLACEMENT_3D('',#177310,#177311,#177312); -#177310 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); -#177311 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177312 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177313 = PCURVE('',#171403,#177314); -#177314 = DEFINITIONAL_REPRESENTATION('',(#177315),#177319); -#177315 = CIRCLE('',#177316,0.2); -#177316 = AXIS2_PLACEMENT_2D('',#177317,#177318); -#177317 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#177318 = DIRECTION('',(-1.,0.E+000)); -#177319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177320 = PCURVE('',#177321,#177326); -#177321 = CYLINDRICAL_SURFACE('',#177322,0.2); -#177322 = AXIS2_PLACEMENT_3D('',#177323,#177324,#177325); -#177323 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); -#177324 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177325 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177326 = DEFINITIONAL_REPRESENTATION('',(#177327),#177330); -#177327 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177328,#177329), +#179608 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#179609 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#179610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179611 = ORIENTED_EDGE('',*,*,#179612,.F.); +#179612 = EDGE_CURVE('',#179613,#179581,#179615,.T.); +#179613 = VERTEX_POINT('',#179614); +#179614 = CARTESIAN_POINT('',(0.135,1.4,0.15)); +#179615 = SURFACE_CURVE('',#179616,(#179620,#179627),.PCURVE_S1.); +#179616 = LINE('',#179617,#179618); +#179617 = CARTESIAN_POINT('',(0.135,1.4,0.15)); +#179618 = VECTOR('',#179619,1.); +#179619 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#179620 = PCURVE('',#173795,#179621); +#179621 = DEFINITIONAL_REPRESENTATION('',(#179622),#179626); +#179622 = LINE('',#179623,#179624); +#179623 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#179624 = VECTOR('',#179625,1.); +#179625 = DIRECTION('',(3.020255886006E-016,-1.)); +#179626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179627 = PCURVE('',#179628,#179633); +#179628 = PLANE('',#179629); +#179629 = AXIS2_PLACEMENT_3D('',#179630,#179631,#179632); +#179630 = CARTESIAN_POINT('',(0.135,1.4,0.15)); +#179631 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); +#179632 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#179633 = DEFINITIONAL_REPRESENTATION('',(#179634),#179638); +#179634 = LINE('',#179635,#179636); +#179635 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179636 = VECTOR('',#179637,1.); +#179637 = DIRECTION('',(1.,0.E+000)); +#179638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179639 = ORIENTED_EDGE('',*,*,#179640,.F.); +#179640 = EDGE_CURVE('',#179641,#179613,#179643,.T.); +#179641 = VERTEX_POINT('',#179642); +#179642 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#179643 = SURFACE_CURVE('',#179644,(#179648,#179655),.PCURVE_S1.); +#179644 = LINE('',#179645,#179646); +#179645 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#179646 = VECTOR('',#179647,1.); +#179647 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179648 = PCURVE('',#173795,#179649); +#179649 = DEFINITIONAL_REPRESENTATION('',(#179650),#179654); +#179650 = LINE('',#179651,#179652); +#179651 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#179652 = VECTOR('',#179653,1.); +#179653 = DIRECTION('',(-1.,0.E+000)); +#179654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179655 = PCURVE('',#179656,#179661); +#179656 = PLANE('',#179657); +#179657 = AXIS2_PLACEMENT_3D('',#179658,#179659,#179660); +#179658 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#179659 = DIRECTION('',(0.E+000,1.,0.E+000)); +#179660 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179661 = DEFINITIONAL_REPRESENTATION('',(#179662),#179666); +#179662 = LINE('',#179663,#179664); +#179663 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179664 = VECTOR('',#179665,1.); +#179665 = DIRECTION('',(1.,0.E+000)); +#179666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179667 = ORIENTED_EDGE('',*,*,#179668,.F.); +#179668 = EDGE_CURVE('',#179669,#179641,#179671,.T.); +#179669 = VERTEX_POINT('',#179670); +#179670 = CARTESIAN_POINT('',(0.135,1.1307673058,2.042548750247E-016)); +#179671 = SURFACE_CURVE('',#179672,(#179676,#179683),.PCURVE_S1.); +#179672 = LINE('',#179673,#179674); +#179673 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#179674 = VECTOR('',#179675,1.); +#179675 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#179676 = PCURVE('',#173795,#179677); +#179677 = DEFINITIONAL_REPRESENTATION('',(#179678),#179682); +#179678 = LINE('',#179679,#179680); +#179679 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#179680 = VECTOR('',#179681,1.); +#179681 = DIRECTION('',(-2.516879905005E-016,1.)); +#179682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179683 = PCURVE('',#179684,#179689); +#179684 = PLANE('',#179685); +#179685 = AXIS2_PLACEMENT_3D('',#179686,#179687,#179688); +#179686 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#179687 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); +#179688 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#179689 = DEFINITIONAL_REPRESENTATION('',(#179690),#179694); +#179690 = LINE('',#179691,#179692); +#179691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179692 = VECTOR('',#179693,1.); +#179693 = DIRECTION('',(1.,0.E+000)); +#179694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179695 = ORIENTED_EDGE('',*,*,#179696,.F.); +#179696 = EDGE_CURVE('',#179697,#179669,#179699,.T.); +#179697 = VERTEX_POINT('',#179698); +#179698 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); +#179699 = SURFACE_CURVE('',#179700,(#179705,#179712),.PCURVE_S1.); +#179700 = CIRCLE('',#179701,0.2); +#179701 = AXIS2_PLACEMENT_3D('',#179702,#179703,#179704); +#179702 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); +#179703 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179704 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179705 = PCURVE('',#173795,#179706); +#179706 = DEFINITIONAL_REPRESENTATION('',(#179707),#179711); +#179707 = CIRCLE('',#179708,0.2); +#179708 = AXIS2_PLACEMENT_2D('',#179709,#179710); +#179709 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#179710 = DIRECTION('',(-1.,0.E+000)); +#179711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179712 = PCURVE('',#179713,#179718); +#179713 = CYLINDRICAL_SURFACE('',#179714,0.2); +#179714 = AXIS2_PLACEMENT_3D('',#179715,#179716,#179717); +#179715 = CARTESIAN_POINT('',(0.135,1.1307673058,0.2)); +#179716 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179717 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#179718 = DEFINITIONAL_REPRESENTATION('',(#179719),#179722); +#179719 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179720,#179721), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#177328 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#177329 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#177330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177331 = ORIENTED_EDGE('',*,*,#177332,.F.); -#177332 = EDGE_CURVE('',#177333,#177305,#177335,.T.); -#177333 = VERTEX_POINT('',#177334); -#177334 = CARTESIAN_POINT('',(0.135,0.906981201809,0.50752811704)); -#177335 = SURFACE_CURVE('',#177336,(#177340,#177347),.PCURVE_S1.); -#177336 = LINE('',#177337,#177338); -#177337 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); -#177338 = VECTOR('',#177339,1.); -#177339 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#177340 = PCURVE('',#171403,#177341); -#177341 = DEFINITIONAL_REPRESENTATION('',(#177342),#177346); -#177342 = LINE('',#177343,#177344); -#177343 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#177344 = VECTOR('',#177345,1.); -#177345 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#177346 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177347 = PCURVE('',#177348,#177353); -#177348 = PLANE('',#177349); -#177349 = AXIS2_PLACEMENT_3D('',#177350,#177351,#177352); -#177350 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); -#177351 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); -#177352 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#177353 = DEFINITIONAL_REPRESENTATION('',(#177354),#177358); -#177354 = LINE('',#177355,#177356); -#177355 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177356 = VECTOR('',#177357,1.); -#177357 = DIRECTION('',(1.,0.E+000)); -#177358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177359 = ORIENTED_EDGE('',*,*,#177360,.F.); -#177360 = EDGE_CURVE('',#177034,#177333,#177361,.T.); -#177361 = SURFACE_CURVE('',#177362,(#177367,#177378),.PCURVE_S1.); -#177362 = CIRCLE('',#177363,0.1); -#177363 = AXIS2_PLACEMENT_3D('',#177364,#177365,#177366); -#177364 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); -#177365 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#177366 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177367 = PCURVE('',#171403,#177368); -#177368 = DEFINITIONAL_REPRESENTATION('',(#177369),#177377); -#177369 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177370,#177371,#177372, - #177373,#177374,#177375,#177376),.UNSPECIFIED.,.F.,.F.) +#179720 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#179721 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#179722 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179723 = ORIENTED_EDGE('',*,*,#179724,.F.); +#179724 = EDGE_CURVE('',#179725,#179697,#179727,.T.); +#179725 = VERTEX_POINT('',#179726); +#179726 = CARTESIAN_POINT('',(0.135,0.906981201809,0.50752811704)); +#179727 = SURFACE_CURVE('',#179728,(#179732,#179739),.PCURVE_S1.); +#179728 = LINE('',#179729,#179730); +#179729 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); +#179730 = VECTOR('',#179731,1.); +#179731 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#179732 = PCURVE('',#173795,#179733); +#179733 = DEFINITIONAL_REPRESENTATION('',(#179734),#179738); +#179734 = LINE('',#179735,#179736); +#179735 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#179736 = VECTOR('',#179737,1.); +#179737 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#179738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179739 = PCURVE('',#179740,#179745); +#179740 = PLANE('',#179741); +#179741 = AXIS2_PLACEMENT_3D('',#179742,#179743,#179744); +#179742 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); +#179743 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); +#179744 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#179745 = DEFINITIONAL_REPRESENTATION('',(#179746),#179750); +#179746 = LINE('',#179747,#179748); +#179747 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179748 = VECTOR('',#179749,1.); +#179749 = DIRECTION('',(1.,0.E+000)); +#179750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179751 = ORIENTED_EDGE('',*,*,#179752,.F.); +#179752 = EDGE_CURVE('',#179426,#179725,#179753,.T.); +#179753 = SURFACE_CURVE('',#179754,(#179759,#179770),.PCURVE_S1.); +#179754 = CIRCLE('',#179755,0.1); +#179755 = AXIS2_PLACEMENT_3D('',#179756,#179757,#179758); +#179756 = CARTESIAN_POINT('',(0.135,0.807264967154,0.5)); +#179757 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#179758 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179759 = PCURVE('',#173795,#179760); +#179760 = DEFINITIONAL_REPRESENTATION('',(#179761),#179769); +#179761 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179762,#179763,#179764, + #179765,#179766,#179767,#179768),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#177370 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#177371 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#177372 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#177373 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#177374 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#177375 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#177376 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#177377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177378 = PCURVE('',#177072,#177379); -#177379 = DEFINITIONAL_REPRESENTATION('',(#177380),#177383); -#177380 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177381,#177382), +#179762 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#179763 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#179764 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#179765 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#179766 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#179767 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#179768 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#179769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179770 = PCURVE('',#179464,#179771); +#179771 = DEFINITIONAL_REPRESENTATION('',(#179772),#179775); +#179772 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179773,#179774), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#177381 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#177382 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#177383 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177384 = ADVANCED_FACE('',(#177385),#171375,.T.); -#177385 = FACE_BOUND('',#177386,.T.); -#177386 = EDGE_LOOP('',(#177387,#177410,#177430,#177431)); -#177387 = ORIENTED_EDGE('',*,*,#177388,.F.); -#177388 = EDGE_CURVE('',#177389,#171332,#177391,.T.); -#177389 = VERTEX_POINT('',#177390); -#177390 = CARTESIAN_POINT('',(0.475,0.807264967154,0.75)); -#177391 = SURFACE_CURVE('',#177392,(#177396,#177403),.PCURVE_S1.); -#177392 = LINE('',#177393,#177394); -#177393 = CARTESIAN_POINT('',(0.475,0.807264967154,0.75)); -#177394 = VECTOR('',#177395,1.); -#177395 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#177396 = PCURVE('',#171375,#177397); -#177397 = DEFINITIONAL_REPRESENTATION('',(#177398),#177402); -#177398 = LINE('',#177399,#177400); -#177399 = CARTESIAN_POINT('',(0.34,0.E+000)); -#177400 = VECTOR('',#177401,1.); -#177401 = DIRECTION('',(0.E+000,-1.)); -#177402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177403 = PCURVE('',#171347,#177404); -#177404 = DEFINITIONAL_REPRESENTATION('',(#177405),#177409); -#177405 = LINE('',#177406,#177407); -#177406 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#177407 = VECTOR('',#177408,1.); -#177408 = DIRECTION('',(0.E+000,-1.)); -#177409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177410 = ORIENTED_EDGE('',*,*,#177411,.F.); -#177411 = EDGE_CURVE('',#177110,#177389,#177412,.T.); -#177412 = SURFACE_CURVE('',#177413,(#177417,#177424),.PCURVE_S1.); -#177413 = LINE('',#177414,#177415); -#177414 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); -#177415 = VECTOR('',#177416,1.); -#177416 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177417 = PCURVE('',#171375,#177418); -#177418 = DEFINITIONAL_REPRESENTATION('',(#177419),#177423); -#177419 = LINE('',#177420,#177421); -#177420 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177421 = VECTOR('',#177422,1.); -#177422 = DIRECTION('',(1.,0.E+000)); -#177423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177424 = PCURVE('',#177149,#177425); -#177425 = DEFINITIONAL_REPRESENTATION('',(#177426),#177429); -#177426 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177427,#177428), +#179773 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#179774 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#179775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179776 = ADVANCED_FACE('',(#179777),#173767,.T.); +#179777 = FACE_BOUND('',#179778,.T.); +#179778 = EDGE_LOOP('',(#179779,#179802,#179822,#179823)); +#179779 = ORIENTED_EDGE('',*,*,#179780,.F.); +#179780 = EDGE_CURVE('',#179781,#173724,#179783,.T.); +#179781 = VERTEX_POINT('',#179782); +#179782 = CARTESIAN_POINT('',(0.475,0.807264967154,0.75)); +#179783 = SURFACE_CURVE('',#179784,(#179788,#179795),.PCURVE_S1.); +#179784 = LINE('',#179785,#179786); +#179785 = CARTESIAN_POINT('',(0.475,0.807264967154,0.75)); +#179786 = VECTOR('',#179787,1.); +#179787 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#179788 = PCURVE('',#173767,#179789); +#179789 = DEFINITIONAL_REPRESENTATION('',(#179790),#179794); +#179790 = LINE('',#179791,#179792); +#179791 = CARTESIAN_POINT('',(0.34,0.E+000)); +#179792 = VECTOR('',#179793,1.); +#179793 = DIRECTION('',(0.E+000,-1.)); +#179794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179795 = PCURVE('',#173739,#179796); +#179796 = DEFINITIONAL_REPRESENTATION('',(#179797),#179801); +#179797 = LINE('',#179798,#179799); +#179798 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#179799 = VECTOR('',#179800,1.); +#179800 = DIRECTION('',(0.E+000,-1.)); +#179801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179802 = ORIENTED_EDGE('',*,*,#179803,.F.); +#179803 = EDGE_CURVE('',#179502,#179781,#179804,.T.); +#179804 = SURFACE_CURVE('',#179805,(#179809,#179816),.PCURVE_S1.); +#179805 = LINE('',#179806,#179807); +#179806 = CARTESIAN_POINT('',(0.135,0.807264967154,0.75)); +#179807 = VECTOR('',#179808,1.); +#179808 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179809 = PCURVE('',#173767,#179810); +#179810 = DEFINITIONAL_REPRESENTATION('',(#179811),#179815); +#179811 = LINE('',#179812,#179813); +#179812 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#179813 = VECTOR('',#179814,1.); +#179814 = DIRECTION('',(1.,0.E+000)); +#179815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179816 = PCURVE('',#179541,#179817); +#179817 = DEFINITIONAL_REPRESENTATION('',(#179818),#179821); +#179818 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179819,#179820), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177427 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#177428 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#177429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177430 = ORIENTED_EDGE('',*,*,#177109,.T.); -#177431 = ORIENTED_EDGE('',*,*,#171359,.F.); -#177432 = ADVANCED_FACE('',(#177433),#171347,.T.); -#177433 = FACE_BOUND('',#177434,.T.); -#177434 = EDGE_LOOP('',(#177435,#177436,#177437,#177464,#177487,#177510, - #177533,#177556,#177579,#177606,#177629,#177650)); -#177435 = ORIENTED_EDGE('',*,*,#171331,.F.); -#177436 = ORIENTED_EDGE('',*,*,#177083,.T.); -#177437 = ORIENTED_EDGE('',*,*,#177438,.T.); -#177438 = EDGE_CURVE('',#177057,#177439,#177441,.T.); -#177439 = VERTEX_POINT('',#177440); -#177440 = CARTESIAN_POINT('',(0.475,0.906981201809,0.50752811704)); -#177441 = SURFACE_CURVE('',#177442,(#177447,#177458),.PCURVE_S1.); -#177442 = CIRCLE('',#177443,0.1); -#177443 = AXIS2_PLACEMENT_3D('',#177444,#177445,#177446); -#177444 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); -#177445 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#177446 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177447 = PCURVE('',#171347,#177448); -#177448 = DEFINITIONAL_REPRESENTATION('',(#177449),#177457); -#177449 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177450,#177451,#177452, - #177453,#177454,#177455,#177456),.UNSPECIFIED.,.F.,.F.) +#179819 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#179820 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#179821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179822 = ORIENTED_EDGE('',*,*,#179501,.T.); +#179823 = ORIENTED_EDGE('',*,*,#173751,.F.); +#179824 = ADVANCED_FACE('',(#179825),#173739,.T.); +#179825 = FACE_BOUND('',#179826,.T.); +#179826 = EDGE_LOOP('',(#179827,#179828,#179829,#179856,#179879,#179902, + #179925,#179948,#179971,#179998,#180021,#180042)); +#179827 = ORIENTED_EDGE('',*,*,#173723,.F.); +#179828 = ORIENTED_EDGE('',*,*,#179475,.T.); +#179829 = ORIENTED_EDGE('',*,*,#179830,.T.); +#179830 = EDGE_CURVE('',#179449,#179831,#179833,.T.); +#179831 = VERTEX_POINT('',#179832); +#179832 = CARTESIAN_POINT('',(0.475,0.906981201809,0.50752811704)); +#179833 = SURFACE_CURVE('',#179834,(#179839,#179850),.PCURVE_S1.); +#179834 = CIRCLE('',#179835,0.1); +#179835 = AXIS2_PLACEMENT_3D('',#179836,#179837,#179838); +#179836 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); +#179837 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#179838 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179839 = PCURVE('',#173739,#179840); +#179840 = DEFINITIONAL_REPRESENTATION('',(#179841),#179849); +#179841 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179842,#179843,#179844, + #179845,#179846,#179847,#179848),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#177450 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#177451 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#177452 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#177453 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#177454 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#177455 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#177456 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#177457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177458 = PCURVE('',#177072,#177459); -#177459 = DEFINITIONAL_REPRESENTATION('',(#177460),#177463); -#177460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177461,#177462), +#179842 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#179843 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#179844 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#179845 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#179846 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#179847 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#179848 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#179849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179850 = PCURVE('',#179464,#179851); +#179851 = DEFINITIONAL_REPRESENTATION('',(#179852),#179855); +#179852 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179853,#179854), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#177461 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#177462 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#177463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177464 = ORIENTED_EDGE('',*,*,#177465,.T.); -#177465 = EDGE_CURVE('',#177439,#177466,#177468,.T.); -#177466 = VERTEX_POINT('',#177467); -#177467 = CARTESIAN_POINT('',(0.475,0.931334836489,0.184943765921)); -#177468 = SURFACE_CURVE('',#177469,(#177473,#177480),.PCURVE_S1.); -#177469 = LINE('',#177470,#177471); -#177470 = CARTESIAN_POINT('',(0.475,0.931334836489,0.184943765921)); -#177471 = VECTOR('',#177472,1.); -#177472 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#177473 = PCURVE('',#171347,#177474); -#177474 = DEFINITIONAL_REPRESENTATION('',(#177475),#177479); -#177475 = LINE('',#177476,#177477); -#177476 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#177477 = VECTOR('',#177478,1.); -#177478 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#177479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177480 = PCURVE('',#177348,#177481); -#177481 = DEFINITIONAL_REPRESENTATION('',(#177482),#177486); -#177482 = LINE('',#177483,#177484); -#177483 = CARTESIAN_POINT('',(0.E+000,0.34)); -#177484 = VECTOR('',#177485,1.); -#177485 = DIRECTION('',(1.,0.E+000)); -#177486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177487 = ORIENTED_EDGE('',*,*,#177488,.T.); -#177488 = EDGE_CURVE('',#177466,#177489,#177491,.T.); -#177489 = VERTEX_POINT('',#177490); -#177490 = CARTESIAN_POINT('',(0.475,1.1307673058,2.042548750247E-016)); -#177491 = SURFACE_CURVE('',#177492,(#177497,#177504),.PCURVE_S1.); -#177492 = CIRCLE('',#177493,0.2); -#177493 = AXIS2_PLACEMENT_3D('',#177494,#177495,#177496); -#177494 = CARTESIAN_POINT('',(0.475,1.1307673058,0.2)); -#177495 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177496 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177497 = PCURVE('',#171347,#177498); -#177498 = DEFINITIONAL_REPRESENTATION('',(#177499),#177503); -#177499 = CIRCLE('',#177500,0.2); -#177500 = AXIS2_PLACEMENT_2D('',#177501,#177502); -#177501 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#177502 = DIRECTION('',(-1.,0.E+000)); -#177503 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177504 = PCURVE('',#177321,#177505); -#177505 = DEFINITIONAL_REPRESENTATION('',(#177506),#177509); -#177506 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177507,#177508), +#179853 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#179854 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#179855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179856 = ORIENTED_EDGE('',*,*,#179857,.T.); +#179857 = EDGE_CURVE('',#179831,#179858,#179860,.T.); +#179858 = VERTEX_POINT('',#179859); +#179859 = CARTESIAN_POINT('',(0.475,0.931334836489,0.184943765921)); +#179860 = SURFACE_CURVE('',#179861,(#179865,#179872),.PCURVE_S1.); +#179861 = LINE('',#179862,#179863); +#179862 = CARTESIAN_POINT('',(0.475,0.931334836489,0.184943765921)); +#179863 = VECTOR('',#179864,1.); +#179864 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#179865 = PCURVE('',#173739,#179866); +#179866 = DEFINITIONAL_REPRESENTATION('',(#179867),#179871); +#179867 = LINE('',#179868,#179869); +#179868 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#179869 = VECTOR('',#179870,1.); +#179870 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#179871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179872 = PCURVE('',#179740,#179873); +#179873 = DEFINITIONAL_REPRESENTATION('',(#179874),#179878); +#179874 = LINE('',#179875,#179876); +#179875 = CARTESIAN_POINT('',(0.E+000,0.34)); +#179876 = VECTOR('',#179877,1.); +#179877 = DIRECTION('',(1.,0.E+000)); +#179878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179879 = ORIENTED_EDGE('',*,*,#179880,.T.); +#179880 = EDGE_CURVE('',#179858,#179881,#179883,.T.); +#179881 = VERTEX_POINT('',#179882); +#179882 = CARTESIAN_POINT('',(0.475,1.1307673058,2.042548750247E-016)); +#179883 = SURFACE_CURVE('',#179884,(#179889,#179896),.PCURVE_S1.); +#179884 = CIRCLE('',#179885,0.2); +#179885 = AXIS2_PLACEMENT_3D('',#179886,#179887,#179888); +#179886 = CARTESIAN_POINT('',(0.475,1.1307673058,0.2)); +#179887 = DIRECTION('',(1.,0.E+000,0.E+000)); +#179888 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179889 = PCURVE('',#173739,#179890); +#179890 = DEFINITIONAL_REPRESENTATION('',(#179891),#179895); +#179891 = CIRCLE('',#179892,0.2); +#179892 = AXIS2_PLACEMENT_2D('',#179893,#179894); +#179893 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#179894 = DIRECTION('',(-1.,0.E+000)); +#179895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179896 = PCURVE('',#179713,#179897); +#179897 = DEFINITIONAL_REPRESENTATION('',(#179898),#179901); +#179898 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179899,#179900), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#177507 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#177508 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#177509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177510 = ORIENTED_EDGE('',*,*,#177511,.T.); -#177511 = EDGE_CURVE('',#177489,#177512,#177514,.T.); -#177512 = VERTEX_POINT('',#177513); -#177513 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); -#177514 = SURFACE_CURVE('',#177515,(#177519,#177526),.PCURVE_S1.); -#177515 = LINE('',#177516,#177517); -#177516 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); -#177517 = VECTOR('',#177518,1.); -#177518 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#177519 = PCURVE('',#171347,#177520); -#177520 = DEFINITIONAL_REPRESENTATION('',(#177521),#177525); -#177521 = LINE('',#177522,#177523); -#177522 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#177523 = VECTOR('',#177524,1.); -#177524 = DIRECTION('',(-2.516879905005E-016,1.)); -#177525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177526 = PCURVE('',#177292,#177527); -#177527 = DEFINITIONAL_REPRESENTATION('',(#177528),#177532); -#177528 = LINE('',#177529,#177530); -#177529 = CARTESIAN_POINT('',(0.E+000,0.34)); -#177530 = VECTOR('',#177531,1.); -#177531 = DIRECTION('',(1.,0.E+000)); -#177532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177533 = ORIENTED_EDGE('',*,*,#177534,.T.); -#177534 = EDGE_CURVE('',#177512,#177535,#177537,.T.); -#177535 = VERTEX_POINT('',#177536); -#177536 = CARTESIAN_POINT('',(0.475,1.4,0.15)); -#177537 = SURFACE_CURVE('',#177538,(#177542,#177549),.PCURVE_S1.); -#177538 = LINE('',#177539,#177540); -#177539 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); -#177540 = VECTOR('',#177541,1.); -#177541 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177542 = PCURVE('',#171347,#177543); -#177543 = DEFINITIONAL_REPRESENTATION('',(#177544),#177548); -#177544 = LINE('',#177545,#177546); -#177545 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#177546 = VECTOR('',#177547,1.); -#177547 = DIRECTION('',(-1.,0.E+000)); -#177548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177549 = PCURVE('',#177264,#177550); -#177550 = DEFINITIONAL_REPRESENTATION('',(#177551),#177555); -#177551 = LINE('',#177552,#177553); -#177552 = CARTESIAN_POINT('',(0.E+000,0.34)); -#177553 = VECTOR('',#177554,1.); -#177554 = DIRECTION('',(1.,0.E+000)); -#177555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177556 = ORIENTED_EDGE('',*,*,#177557,.T.); -#177557 = EDGE_CURVE('',#177535,#177558,#177560,.T.); -#177558 = VERTEX_POINT('',#177559); -#177559 = CARTESIAN_POINT('',(0.475,1.1307673058,0.15)); -#177560 = SURFACE_CURVE('',#177561,(#177565,#177572),.PCURVE_S1.); -#177561 = LINE('',#177562,#177563); -#177562 = CARTESIAN_POINT('',(0.475,1.4,0.15)); -#177563 = VECTOR('',#177564,1.); -#177564 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#177565 = PCURVE('',#171347,#177566); -#177566 = DEFINITIONAL_REPRESENTATION('',(#177567),#177571); -#177567 = LINE('',#177568,#177569); -#177568 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#177569 = VECTOR('',#177570,1.); -#177570 = DIRECTION('',(3.020255886006E-016,-1.)); -#177571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177572 = PCURVE('',#177236,#177573); -#177573 = DEFINITIONAL_REPRESENTATION('',(#177574),#177578); -#177574 = LINE('',#177575,#177576); -#177575 = CARTESIAN_POINT('',(0.E+000,0.34)); -#177576 = VECTOR('',#177577,1.); -#177577 = DIRECTION('',(1.,0.E+000)); -#177578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177579 = ORIENTED_EDGE('',*,*,#177580,.T.); -#177580 = EDGE_CURVE('',#177558,#177581,#177583,.T.); -#177581 = VERTEX_POINT('',#177582); -#177582 = CARTESIAN_POINT('',(0.475,1.080909188472,0.19623594148)); -#177583 = SURFACE_CURVE('',#177584,(#177589,#177600),.PCURVE_S1.); -#177584 = CIRCLE('',#177585,5.E-002); -#177585 = AXIS2_PLACEMENT_3D('',#177586,#177587,#177588); -#177586 = CARTESIAN_POINT('',(0.475,1.1307673058,0.2)); -#177587 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#177588 = DIRECTION('',(0.E+000,0.E+000,1.)); -#177589 = PCURVE('',#171347,#177590); -#177590 = DEFINITIONAL_REPRESENTATION('',(#177591),#177599); -#177591 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#177592,#177593,#177594, - #177595,#177596,#177597,#177598),.UNSPECIFIED.,.F.,.F.) +#179899 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#179900 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#179901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179902 = ORIENTED_EDGE('',*,*,#179903,.T.); +#179903 = EDGE_CURVE('',#179881,#179904,#179906,.T.); +#179904 = VERTEX_POINT('',#179905); +#179905 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); +#179906 = SURFACE_CURVE('',#179907,(#179911,#179918),.PCURVE_S1.); +#179907 = LINE('',#179908,#179909); +#179908 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); +#179909 = VECTOR('',#179910,1.); +#179910 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#179911 = PCURVE('',#173739,#179912); +#179912 = DEFINITIONAL_REPRESENTATION('',(#179913),#179917); +#179913 = LINE('',#179914,#179915); +#179914 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#179915 = VECTOR('',#179916,1.); +#179916 = DIRECTION('',(-2.516879905005E-016,1.)); +#179917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179918 = PCURVE('',#179684,#179919); +#179919 = DEFINITIONAL_REPRESENTATION('',(#179920),#179924); +#179920 = LINE('',#179921,#179922); +#179921 = CARTESIAN_POINT('',(0.E+000,0.34)); +#179922 = VECTOR('',#179923,1.); +#179923 = DIRECTION('',(1.,0.E+000)); +#179924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179925 = ORIENTED_EDGE('',*,*,#179926,.T.); +#179926 = EDGE_CURVE('',#179904,#179927,#179929,.T.); +#179927 = VERTEX_POINT('',#179928); +#179928 = CARTESIAN_POINT('',(0.475,1.4,0.15)); +#179929 = SURFACE_CURVE('',#179930,(#179934,#179941),.PCURVE_S1.); +#179930 = LINE('',#179931,#179932); +#179931 = CARTESIAN_POINT('',(0.475,1.4,2.720175108051E-016)); +#179932 = VECTOR('',#179933,1.); +#179933 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179934 = PCURVE('',#173739,#179935); +#179935 = DEFINITIONAL_REPRESENTATION('',(#179936),#179940); +#179936 = LINE('',#179937,#179938); +#179937 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#179938 = VECTOR('',#179939,1.); +#179939 = DIRECTION('',(-1.,0.E+000)); +#179940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179941 = PCURVE('',#179656,#179942); +#179942 = DEFINITIONAL_REPRESENTATION('',(#179943),#179947); +#179943 = LINE('',#179944,#179945); +#179944 = CARTESIAN_POINT('',(0.E+000,0.34)); +#179945 = VECTOR('',#179946,1.); +#179946 = DIRECTION('',(1.,0.E+000)); +#179947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179948 = ORIENTED_EDGE('',*,*,#179949,.T.); +#179949 = EDGE_CURVE('',#179927,#179950,#179952,.T.); +#179950 = VERTEX_POINT('',#179951); +#179951 = CARTESIAN_POINT('',(0.475,1.1307673058,0.15)); +#179952 = SURFACE_CURVE('',#179953,(#179957,#179964),.PCURVE_S1.); +#179953 = LINE('',#179954,#179955); +#179954 = CARTESIAN_POINT('',(0.475,1.4,0.15)); +#179955 = VECTOR('',#179956,1.); +#179956 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#179957 = PCURVE('',#173739,#179958); +#179958 = DEFINITIONAL_REPRESENTATION('',(#179959),#179963); +#179959 = LINE('',#179960,#179961); +#179960 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#179961 = VECTOR('',#179962,1.); +#179962 = DIRECTION('',(3.020255886006E-016,-1.)); +#179963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179964 = PCURVE('',#179628,#179965); +#179965 = DEFINITIONAL_REPRESENTATION('',(#179966),#179970); +#179966 = LINE('',#179967,#179968); +#179967 = CARTESIAN_POINT('',(0.E+000,0.34)); +#179968 = VECTOR('',#179969,1.); +#179969 = DIRECTION('',(1.,0.E+000)); +#179970 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179971 = ORIENTED_EDGE('',*,*,#179972,.T.); +#179972 = EDGE_CURVE('',#179950,#179973,#179975,.T.); +#179973 = VERTEX_POINT('',#179974); +#179974 = CARTESIAN_POINT('',(0.475,1.080909188472,0.19623594148)); +#179975 = SURFACE_CURVE('',#179976,(#179981,#179992),.PCURVE_S1.); +#179976 = CIRCLE('',#179977,5.E-002); +#179977 = AXIS2_PLACEMENT_3D('',#179978,#179979,#179980); +#179978 = CARTESIAN_POINT('',(0.475,1.1307673058,0.2)); +#179979 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#179980 = DIRECTION('',(0.E+000,0.E+000,1.)); +#179981 = PCURVE('',#173739,#179982); +#179982 = DEFINITIONAL_REPRESENTATION('',(#179983),#179991); +#179983 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179984,#179985,#179986, + #179987,#179988,#179989,#179990),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#177592 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#177593 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#177594 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#177595 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#177596 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#177597 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#177598 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#177599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177600 = PCURVE('',#177209,#177601); -#177601 = DEFINITIONAL_REPRESENTATION('',(#177602),#177605); -#177602 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177603,#177604), +#179984 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#179985 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#179986 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#179987 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#179988 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#179989 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#179990 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#179991 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179992 = PCURVE('',#179601,#179993); +#179993 = DEFINITIONAL_REPRESENTATION('',(#179994),#179997); +#179994 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179995,#179996), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#177603 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#177604 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#177605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177606 = ORIENTED_EDGE('',*,*,#177607,.T.); -#177607 = EDGE_CURVE('',#177581,#177608,#177610,.T.); -#177608 = VERTEX_POINT('',#177609); -#177609 = CARTESIAN_POINT('',(0.475,1.056555553792,0.518820292599)); -#177610 = SURFACE_CURVE('',#177611,(#177615,#177622),.PCURVE_S1.); -#177611 = LINE('',#177612,#177613); -#177612 = CARTESIAN_POINT('',(0.475,1.080909188472,0.19623594148)); -#177613 = VECTOR('',#177614,1.); -#177614 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#177615 = PCURVE('',#171347,#177616); -#177616 = DEFINITIONAL_REPRESENTATION('',(#177617),#177621); -#177617 = LINE('',#177618,#177619); -#177618 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#177619 = VECTOR('',#177620,1.); -#177620 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#177621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177622 = PCURVE('',#177176,#177623); -#177623 = DEFINITIONAL_REPRESENTATION('',(#177624),#177628); -#177624 = LINE('',#177625,#177626); -#177625 = CARTESIAN_POINT('',(0.E+000,0.34)); -#177626 = VECTOR('',#177627,1.); -#177627 = DIRECTION('',(1.,0.E+000)); -#177628 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177629 = ORIENTED_EDGE('',*,*,#177630,.T.); -#177630 = EDGE_CURVE('',#177608,#177389,#177631,.T.); -#177631 = SURFACE_CURVE('',#177632,(#177637,#177644),.PCURVE_S1.); -#177632 = CIRCLE('',#177633,0.25); -#177633 = AXIS2_PLACEMENT_3D('',#177634,#177635,#177636); -#177634 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); -#177635 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177636 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177637 = PCURVE('',#171347,#177638); -#177638 = DEFINITIONAL_REPRESENTATION('',(#177639),#177643); -#177639 = CIRCLE('',#177640,0.25); -#177640 = AXIS2_PLACEMENT_2D('',#177641,#177642); -#177641 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177642 = DIRECTION('',(1.,0.E+000)); -#177643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177644 = PCURVE('',#177149,#177645); -#177645 = DEFINITIONAL_REPRESENTATION('',(#177646),#177649); -#177646 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177647,#177648), +#179995 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#179996 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#179997 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#179998 = ORIENTED_EDGE('',*,*,#179999,.T.); +#179999 = EDGE_CURVE('',#179973,#180000,#180002,.T.); +#180000 = VERTEX_POINT('',#180001); +#180001 = CARTESIAN_POINT('',(0.475,1.056555553792,0.518820292599)); +#180002 = SURFACE_CURVE('',#180003,(#180007,#180014),.PCURVE_S1.); +#180003 = LINE('',#180004,#180005); +#180004 = CARTESIAN_POINT('',(0.475,1.080909188472,0.19623594148)); +#180005 = VECTOR('',#180006,1.); +#180006 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#180007 = PCURVE('',#173739,#180008); +#180008 = DEFINITIONAL_REPRESENTATION('',(#180009),#180013); +#180009 = LINE('',#180010,#180011); +#180010 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#180011 = VECTOR('',#180012,1.); +#180012 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#180013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180014 = PCURVE('',#179568,#180015); +#180015 = DEFINITIONAL_REPRESENTATION('',(#180016),#180020); +#180016 = LINE('',#180017,#180018); +#180017 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180018 = VECTOR('',#180019,1.); +#180019 = DIRECTION('',(1.,0.E+000)); +#180020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180021 = ORIENTED_EDGE('',*,*,#180022,.T.); +#180022 = EDGE_CURVE('',#180000,#179781,#180023,.T.); +#180023 = SURFACE_CURVE('',#180024,(#180029,#180036),.PCURVE_S1.); +#180024 = CIRCLE('',#180025,0.25); +#180025 = AXIS2_PLACEMENT_3D('',#180026,#180027,#180028); +#180026 = CARTESIAN_POINT('',(0.475,0.807264967154,0.5)); +#180027 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180028 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180029 = PCURVE('',#173739,#180030); +#180030 = DEFINITIONAL_REPRESENTATION('',(#180031),#180035); +#180031 = CIRCLE('',#180032,0.25); +#180032 = AXIS2_PLACEMENT_2D('',#180033,#180034); +#180033 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180034 = DIRECTION('',(1.,0.E+000)); +#180035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180036 = PCURVE('',#179541,#180037); +#180037 = DEFINITIONAL_REPRESENTATION('',(#180038),#180041); +#180038 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180039,#180040), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#177647 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#177648 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#177649 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177650 = ORIENTED_EDGE('',*,*,#177388,.T.); -#177651 = ADVANCED_FACE('',(#177652),#177149,.T.); -#177652 = FACE_BOUND('',#177653,.T.); -#177653 = EDGE_LOOP('',(#177654,#177655,#177675,#177676)); -#177654 = ORIENTED_EDGE('',*,*,#177630,.F.); -#177655 = ORIENTED_EDGE('',*,*,#177656,.F.); -#177656 = EDGE_CURVE('',#177133,#177608,#177657,.T.); -#177657 = SURFACE_CURVE('',#177658,(#177662,#177668),.PCURVE_S1.); -#177658 = LINE('',#177659,#177660); -#177659 = CARTESIAN_POINT('',(0.135,1.056555553792,0.518820292599)); -#177660 = VECTOR('',#177661,1.); -#177661 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177662 = PCURVE('',#177149,#177663); -#177663 = DEFINITIONAL_REPRESENTATION('',(#177664),#177667); -#177664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177665,#177666), +#180039 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180040 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#180041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180042 = ORIENTED_EDGE('',*,*,#179780,.T.); +#180043 = ADVANCED_FACE('',(#180044),#179541,.T.); +#180044 = FACE_BOUND('',#180045,.T.); +#180045 = EDGE_LOOP('',(#180046,#180047,#180067,#180068)); +#180046 = ORIENTED_EDGE('',*,*,#180022,.F.); +#180047 = ORIENTED_EDGE('',*,*,#180048,.F.); +#180048 = EDGE_CURVE('',#179525,#180000,#180049,.T.); +#180049 = SURFACE_CURVE('',#180050,(#180054,#180060),.PCURVE_S1.); +#180050 = LINE('',#180051,#180052); +#180051 = CARTESIAN_POINT('',(0.135,1.056555553792,0.518820292599)); +#180052 = VECTOR('',#180053,1.); +#180053 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180054 = PCURVE('',#179541,#180055); +#180055 = DEFINITIONAL_REPRESENTATION('',(#180056),#180059); +#180056 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180057,#180058), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177665 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#177666 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#177667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177668 = PCURVE('',#177176,#177669); -#177669 = DEFINITIONAL_REPRESENTATION('',(#177670),#177674); -#177670 = LINE('',#177671,#177672); -#177671 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#177672 = VECTOR('',#177673,1.); -#177673 = DIRECTION('',(0.E+000,1.)); -#177674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177675 = ORIENTED_EDGE('',*,*,#177132,.T.); -#177676 = ORIENTED_EDGE('',*,*,#177411,.T.); -#177677 = ADVANCED_FACE('',(#177678),#177176,.T.); -#177678 = FACE_BOUND('',#177679,.T.); -#177679 = EDGE_LOOP('',(#177680,#177681,#177701,#177702)); -#177680 = ORIENTED_EDGE('',*,*,#177607,.F.); -#177681 = ORIENTED_EDGE('',*,*,#177682,.F.); -#177682 = EDGE_CURVE('',#177161,#177581,#177683,.T.); -#177683 = SURFACE_CURVE('',#177684,(#177688,#177695),.PCURVE_S1.); -#177684 = LINE('',#177685,#177686); -#177685 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); -#177686 = VECTOR('',#177687,1.); -#177687 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177688 = PCURVE('',#177176,#177689); -#177689 = DEFINITIONAL_REPRESENTATION('',(#177690),#177694); -#177690 = LINE('',#177691,#177692); -#177691 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177692 = VECTOR('',#177693,1.); -#177693 = DIRECTION('',(0.E+000,1.)); -#177694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177695 = PCURVE('',#177209,#177696); -#177696 = DEFINITIONAL_REPRESENTATION('',(#177697),#177700); -#177697 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177698,#177699), +#180057 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#180058 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180060 = PCURVE('',#179568,#180061); +#180061 = DEFINITIONAL_REPRESENTATION('',(#180062),#180066); +#180062 = LINE('',#180063,#180064); +#180063 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#180064 = VECTOR('',#180065,1.); +#180065 = DIRECTION('',(0.E+000,1.)); +#180066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180067 = ORIENTED_EDGE('',*,*,#179524,.T.); +#180068 = ORIENTED_EDGE('',*,*,#179803,.T.); +#180069 = ADVANCED_FACE('',(#180070),#179568,.T.); +#180070 = FACE_BOUND('',#180071,.T.); +#180071 = EDGE_LOOP('',(#180072,#180073,#180093,#180094)); +#180072 = ORIENTED_EDGE('',*,*,#179999,.F.); +#180073 = ORIENTED_EDGE('',*,*,#180074,.F.); +#180074 = EDGE_CURVE('',#179553,#179973,#180075,.T.); +#180075 = SURFACE_CURVE('',#180076,(#180080,#180087),.PCURVE_S1.); +#180076 = LINE('',#180077,#180078); +#180077 = CARTESIAN_POINT('',(0.135,1.080909188472,0.19623594148)); +#180078 = VECTOR('',#180079,1.); +#180079 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180080 = PCURVE('',#179568,#180081); +#180081 = DEFINITIONAL_REPRESENTATION('',(#180082),#180086); +#180082 = LINE('',#180083,#180084); +#180083 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180084 = VECTOR('',#180085,1.); +#180085 = DIRECTION('',(0.E+000,1.)); +#180086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180087 = PCURVE('',#179601,#180088); +#180088 = DEFINITIONAL_REPRESENTATION('',(#180089),#180092); +#180089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180090,#180091), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177698 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#177699 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#177700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177701 = ORIENTED_EDGE('',*,*,#177160,.T.); -#177702 = ORIENTED_EDGE('',*,*,#177656,.T.); -#177703 = ADVANCED_FACE('',(#177704),#177209,.F.); -#177704 = FACE_BOUND('',#177705,.F.); -#177705 = EDGE_LOOP('',(#177706,#177707,#177708,#177709)); -#177706 = ORIENTED_EDGE('',*,*,#177580,.T.); -#177707 = ORIENTED_EDGE('',*,*,#177682,.F.); -#177708 = ORIENTED_EDGE('',*,*,#177188,.F.); -#177709 = ORIENTED_EDGE('',*,*,#177710,.T.); -#177710 = EDGE_CURVE('',#177189,#177558,#177711,.T.); -#177711 = SURFACE_CURVE('',#177712,(#177716,#177745),.PCURVE_S1.); -#177712 = LINE('',#177713,#177714); -#177713 = CARTESIAN_POINT('',(0.135,1.1307673058,0.15)); -#177714 = VECTOR('',#177715,1.); -#177715 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177716 = PCURVE('',#177209,#177717); -#177717 = DEFINITIONAL_REPRESENTATION('',(#177718),#177744); -#177718 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#177719,#177720,#177721, - #177722,#177723,#177724,#177725,#177726,#177727,#177728,#177729, - #177730,#177731,#177732,#177733,#177734,#177735,#177736,#177737, - #177738,#177739,#177740,#177741,#177742,#177743),.UNSPECIFIED.,.F., +#180090 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#180091 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#180092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180093 = ORIENTED_EDGE('',*,*,#179552,.T.); +#180094 = ORIENTED_EDGE('',*,*,#180048,.T.); +#180095 = ADVANCED_FACE('',(#180096),#179601,.F.); +#180096 = FACE_BOUND('',#180097,.F.); +#180097 = EDGE_LOOP('',(#180098,#180099,#180100,#180101)); +#180098 = ORIENTED_EDGE('',*,*,#179972,.T.); +#180099 = ORIENTED_EDGE('',*,*,#180074,.F.); +#180100 = ORIENTED_EDGE('',*,*,#179580,.F.); +#180101 = ORIENTED_EDGE('',*,*,#180102,.T.); +#180102 = EDGE_CURVE('',#179581,#179950,#180103,.T.); +#180103 = SURFACE_CURVE('',#180104,(#180108,#180137),.PCURVE_S1.); +#180104 = LINE('',#180105,#180106); +#180105 = CARTESIAN_POINT('',(0.135,1.1307673058,0.15)); +#180106 = VECTOR('',#180107,1.); +#180107 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180108 = PCURVE('',#179601,#180109); +#180109 = DEFINITIONAL_REPRESENTATION('',(#180110),#180136); +#180110 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#180111,#180112,#180113, + #180114,#180115,#180116,#180117,#180118,#180119,#180120,#180121, + #180122,#180123,#180124,#180125,#180126,#180127,#180128,#180129, + #180130,#180131,#180132,#180133,#180134,#180135),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -220149,131 +223151,131 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#177719 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#177720 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#177721 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#177722 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#177723 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#177724 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#177725 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#177726 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#177727 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#177728 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#177729 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#177730 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#177731 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#177732 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#177733 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#177734 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#177735 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#177736 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#177737 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#177738 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#177739 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#177740 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#177741 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#177742 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#177743 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#177744 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177745 = PCURVE('',#177236,#177746); -#177746 = DEFINITIONAL_REPRESENTATION('',(#177747),#177751); -#177747 = LINE('',#177748,#177749); -#177748 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); -#177749 = VECTOR('',#177750,1.); -#177750 = DIRECTION('',(0.E+000,1.)); -#177751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177752 = ADVANCED_FACE('',(#177753),#177236,.T.); -#177753 = FACE_BOUND('',#177754,.T.); -#177754 = EDGE_LOOP('',(#177755,#177756,#177777,#177778)); -#177755 = ORIENTED_EDGE('',*,*,#177557,.F.); -#177756 = ORIENTED_EDGE('',*,*,#177757,.F.); -#177757 = EDGE_CURVE('',#177221,#177535,#177758,.T.); -#177758 = SURFACE_CURVE('',#177759,(#177763,#177770),.PCURVE_S1.); -#177759 = LINE('',#177760,#177761); -#177760 = CARTESIAN_POINT('',(0.135,1.4,0.15)); -#177761 = VECTOR('',#177762,1.); -#177762 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177763 = PCURVE('',#177236,#177764); -#177764 = DEFINITIONAL_REPRESENTATION('',(#177765),#177769); -#177765 = LINE('',#177766,#177767); -#177766 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177767 = VECTOR('',#177768,1.); -#177768 = DIRECTION('',(0.E+000,1.)); -#177769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177770 = PCURVE('',#177264,#177771); -#177771 = DEFINITIONAL_REPRESENTATION('',(#177772),#177776); -#177772 = LINE('',#177773,#177774); -#177773 = CARTESIAN_POINT('',(0.15,0.E+000)); -#177774 = VECTOR('',#177775,1.); -#177775 = DIRECTION('',(0.E+000,1.)); -#177776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177777 = ORIENTED_EDGE('',*,*,#177220,.T.); -#177778 = ORIENTED_EDGE('',*,*,#177710,.T.); -#177779 = ADVANCED_FACE('',(#177780),#177264,.T.); -#177780 = FACE_BOUND('',#177781,.T.); -#177781 = EDGE_LOOP('',(#177782,#177783,#177804,#177805)); -#177782 = ORIENTED_EDGE('',*,*,#177534,.F.); -#177783 = ORIENTED_EDGE('',*,*,#177784,.F.); -#177784 = EDGE_CURVE('',#177249,#177512,#177785,.T.); -#177785 = SURFACE_CURVE('',#177786,(#177790,#177797),.PCURVE_S1.); -#177786 = LINE('',#177787,#177788); -#177787 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); -#177788 = VECTOR('',#177789,1.); -#177789 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177790 = PCURVE('',#177264,#177791); -#177791 = DEFINITIONAL_REPRESENTATION('',(#177792),#177796); -#177792 = LINE('',#177793,#177794); -#177793 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177794 = VECTOR('',#177795,1.); -#177795 = DIRECTION('',(0.E+000,1.)); -#177796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177797 = PCURVE('',#177292,#177798); -#177798 = DEFINITIONAL_REPRESENTATION('',(#177799),#177803); -#177799 = LINE('',#177800,#177801); -#177800 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177801 = VECTOR('',#177802,1.); -#177802 = DIRECTION('',(0.E+000,1.)); -#177803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177804 = ORIENTED_EDGE('',*,*,#177248,.T.); -#177805 = ORIENTED_EDGE('',*,*,#177757,.T.); -#177806 = ADVANCED_FACE('',(#177807),#177292,.T.); -#177807 = FACE_BOUND('',#177808,.T.); -#177808 = EDGE_LOOP('',(#177809,#177810,#177853,#177854)); -#177809 = ORIENTED_EDGE('',*,*,#177511,.F.); -#177810 = ORIENTED_EDGE('',*,*,#177811,.F.); -#177811 = EDGE_CURVE('',#177277,#177489,#177812,.T.); -#177812 = SURFACE_CURVE('',#177813,(#177817,#177824),.PCURVE_S1.); -#177813 = LINE('',#177814,#177815); -#177814 = CARTESIAN_POINT('',(0.135,1.1307673058,2.042548750247E-016)); -#177815 = VECTOR('',#177816,1.); -#177816 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177817 = PCURVE('',#177292,#177818); -#177818 = DEFINITIONAL_REPRESENTATION('',(#177819),#177823); -#177819 = LINE('',#177820,#177821); -#177820 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); -#177821 = VECTOR('',#177822,1.); -#177822 = DIRECTION('',(0.E+000,1.)); -#177823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177824 = PCURVE('',#177321,#177825); -#177825 = DEFINITIONAL_REPRESENTATION('',(#177826),#177852); -#177826 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#177827,#177828,#177829, - #177830,#177831,#177832,#177833,#177834,#177835,#177836,#177837, - #177838,#177839,#177840,#177841,#177842,#177843,#177844,#177845, - #177846,#177847,#177848,#177849,#177850,#177851),.UNSPECIFIED.,.F., +#180111 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#180112 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#180113 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#180114 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#180115 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#180116 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#180117 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#180118 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#180119 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#180120 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#180121 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#180122 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#180123 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#180124 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#180125 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#180126 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#180127 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#180128 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#180129 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#180130 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#180131 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#180132 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#180133 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#180134 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#180135 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#180136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180137 = PCURVE('',#179628,#180138); +#180138 = DEFINITIONAL_REPRESENTATION('',(#180139),#180143); +#180139 = LINE('',#180140,#180141); +#180140 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); +#180141 = VECTOR('',#180142,1.); +#180142 = DIRECTION('',(0.E+000,1.)); +#180143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180144 = ADVANCED_FACE('',(#180145),#179628,.T.); +#180145 = FACE_BOUND('',#180146,.T.); +#180146 = EDGE_LOOP('',(#180147,#180148,#180169,#180170)); +#180147 = ORIENTED_EDGE('',*,*,#179949,.F.); +#180148 = ORIENTED_EDGE('',*,*,#180149,.F.); +#180149 = EDGE_CURVE('',#179613,#179927,#180150,.T.); +#180150 = SURFACE_CURVE('',#180151,(#180155,#180162),.PCURVE_S1.); +#180151 = LINE('',#180152,#180153); +#180152 = CARTESIAN_POINT('',(0.135,1.4,0.15)); +#180153 = VECTOR('',#180154,1.); +#180154 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180155 = PCURVE('',#179628,#180156); +#180156 = DEFINITIONAL_REPRESENTATION('',(#180157),#180161); +#180157 = LINE('',#180158,#180159); +#180158 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180159 = VECTOR('',#180160,1.); +#180160 = DIRECTION('',(0.E+000,1.)); +#180161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180162 = PCURVE('',#179656,#180163); +#180163 = DEFINITIONAL_REPRESENTATION('',(#180164),#180168); +#180164 = LINE('',#180165,#180166); +#180165 = CARTESIAN_POINT('',(0.15,0.E+000)); +#180166 = VECTOR('',#180167,1.); +#180167 = DIRECTION('',(0.E+000,1.)); +#180168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180169 = ORIENTED_EDGE('',*,*,#179612,.T.); +#180170 = ORIENTED_EDGE('',*,*,#180102,.T.); +#180171 = ADVANCED_FACE('',(#180172),#179656,.T.); +#180172 = FACE_BOUND('',#180173,.T.); +#180173 = EDGE_LOOP('',(#180174,#180175,#180196,#180197)); +#180174 = ORIENTED_EDGE('',*,*,#179926,.F.); +#180175 = ORIENTED_EDGE('',*,*,#180176,.F.); +#180176 = EDGE_CURVE('',#179641,#179904,#180177,.T.); +#180177 = SURFACE_CURVE('',#180178,(#180182,#180189),.PCURVE_S1.); +#180178 = LINE('',#180179,#180180); +#180179 = CARTESIAN_POINT('',(0.135,1.4,2.720175108051E-016)); +#180180 = VECTOR('',#180181,1.); +#180181 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180182 = PCURVE('',#179656,#180183); +#180183 = DEFINITIONAL_REPRESENTATION('',(#180184),#180188); +#180184 = LINE('',#180185,#180186); +#180185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180186 = VECTOR('',#180187,1.); +#180187 = DIRECTION('',(0.E+000,1.)); +#180188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180189 = PCURVE('',#179684,#180190); +#180190 = DEFINITIONAL_REPRESENTATION('',(#180191),#180195); +#180191 = LINE('',#180192,#180193); +#180192 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180193 = VECTOR('',#180194,1.); +#180194 = DIRECTION('',(0.E+000,1.)); +#180195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180196 = ORIENTED_EDGE('',*,*,#179640,.T.); +#180197 = ORIENTED_EDGE('',*,*,#180149,.T.); +#180198 = ADVANCED_FACE('',(#180199),#179684,.T.); +#180199 = FACE_BOUND('',#180200,.T.); +#180200 = EDGE_LOOP('',(#180201,#180202,#180245,#180246)); +#180201 = ORIENTED_EDGE('',*,*,#179903,.F.); +#180202 = ORIENTED_EDGE('',*,*,#180203,.F.); +#180203 = EDGE_CURVE('',#179669,#179881,#180204,.T.); +#180204 = SURFACE_CURVE('',#180205,(#180209,#180216),.PCURVE_S1.); +#180205 = LINE('',#180206,#180207); +#180206 = CARTESIAN_POINT('',(0.135,1.1307673058,2.042548750247E-016)); +#180207 = VECTOR('',#180208,1.); +#180208 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180209 = PCURVE('',#179684,#180210); +#180210 = DEFINITIONAL_REPRESENTATION('',(#180211),#180215); +#180211 = LINE('',#180212,#180213); +#180212 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); +#180213 = VECTOR('',#180214,1.); +#180214 = DIRECTION('',(0.E+000,1.)); +#180215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180216 = PCURVE('',#179713,#180217); +#180217 = DEFINITIONAL_REPRESENTATION('',(#180218),#180244); +#180218 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#180219,#180220,#180221, + #180222,#180223,#180224,#180225,#180226,#180227,#180228,#180229, + #180230,#180231,#180232,#180233,#180234,#180235,#180236,#180237, + #180238,#180239,#180240,#180241,#180242,#180243),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -220281,949 +223283,949 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#177827 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#177828 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#177829 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#177830 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#177831 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#177832 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#177833 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#177834 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#177835 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#177836 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#177837 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#177838 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#177839 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#177840 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#177841 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#177842 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#177843 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#177844 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#177845 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#177846 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#177847 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#177848 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#177849 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#177850 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#177851 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#177852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177853 = ORIENTED_EDGE('',*,*,#177276,.T.); -#177854 = ORIENTED_EDGE('',*,*,#177784,.T.); -#177855 = ADVANCED_FACE('',(#177856),#177321,.T.); -#177856 = FACE_BOUND('',#177857,.T.); -#177857 = EDGE_LOOP('',(#177858,#177859,#177879,#177880)); -#177858 = ORIENTED_EDGE('',*,*,#177488,.F.); -#177859 = ORIENTED_EDGE('',*,*,#177860,.F.); -#177860 = EDGE_CURVE('',#177305,#177466,#177861,.T.); -#177861 = SURFACE_CURVE('',#177862,(#177866,#177872),.PCURVE_S1.); -#177862 = LINE('',#177863,#177864); -#177863 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); -#177864 = VECTOR('',#177865,1.); -#177865 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177866 = PCURVE('',#177321,#177867); -#177867 = DEFINITIONAL_REPRESENTATION('',(#177868),#177871); -#177868 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177869,#177870), +#180219 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#180220 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#180221 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#180222 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#180223 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#180224 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#180225 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#180226 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#180227 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#180228 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#180229 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#180230 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#180231 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#180232 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#180233 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#180234 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#180235 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#180236 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#180237 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#180238 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#180239 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#180240 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#180241 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#180242 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#180243 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#180244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180245 = ORIENTED_EDGE('',*,*,#179668,.T.); +#180246 = ORIENTED_EDGE('',*,*,#180176,.T.); +#180247 = ADVANCED_FACE('',(#180248),#179713,.T.); +#180248 = FACE_BOUND('',#180249,.T.); +#180249 = EDGE_LOOP('',(#180250,#180251,#180271,#180272)); +#180250 = ORIENTED_EDGE('',*,*,#179880,.F.); +#180251 = ORIENTED_EDGE('',*,*,#180252,.F.); +#180252 = EDGE_CURVE('',#179697,#179858,#180253,.T.); +#180253 = SURFACE_CURVE('',#180254,(#180258,#180264),.PCURVE_S1.); +#180254 = LINE('',#180255,#180256); +#180255 = CARTESIAN_POINT('',(0.135,0.931334836489,0.184943765921)); +#180256 = VECTOR('',#180257,1.); +#180257 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180258 = PCURVE('',#179713,#180259); +#180259 = DEFINITIONAL_REPRESENTATION('',(#180260),#180263); +#180260 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180261,#180262), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177869 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#177870 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#177871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177872 = PCURVE('',#177348,#177873); -#177873 = DEFINITIONAL_REPRESENTATION('',(#177874),#177878); -#177874 = LINE('',#177875,#177876); -#177875 = CARTESIAN_POINT('',(8.303044473245E-017,0.E+000)); -#177876 = VECTOR('',#177877,1.); -#177877 = DIRECTION('',(0.E+000,1.)); -#177878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177879 = ORIENTED_EDGE('',*,*,#177304,.T.); -#177880 = ORIENTED_EDGE('',*,*,#177811,.T.); -#177881 = ADVANCED_FACE('',(#177882),#177348,.T.); -#177882 = FACE_BOUND('',#177883,.T.); -#177883 = EDGE_LOOP('',(#177884,#177885,#177905,#177906)); -#177884 = ORIENTED_EDGE('',*,*,#177465,.F.); -#177885 = ORIENTED_EDGE('',*,*,#177886,.F.); -#177886 = EDGE_CURVE('',#177333,#177439,#177887,.T.); -#177887 = SURFACE_CURVE('',#177888,(#177892,#177899),.PCURVE_S1.); -#177888 = LINE('',#177889,#177890); -#177889 = CARTESIAN_POINT('',(0.135,0.906981201809,0.50752811704)); -#177890 = VECTOR('',#177891,1.); -#177891 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177892 = PCURVE('',#177348,#177893); -#177893 = DEFINITIONAL_REPRESENTATION('',(#177894),#177898); -#177894 = LINE('',#177895,#177896); -#177895 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#177896 = VECTOR('',#177897,1.); -#177897 = DIRECTION('',(0.E+000,1.)); -#177898 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177899 = PCURVE('',#177072,#177900); -#177900 = DEFINITIONAL_REPRESENTATION('',(#177901),#177904); -#177901 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177902,#177903), +#180261 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#180262 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#180263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180264 = PCURVE('',#179740,#180265); +#180265 = DEFINITIONAL_REPRESENTATION('',(#180266),#180270); +#180266 = LINE('',#180267,#180268); +#180267 = CARTESIAN_POINT('',(8.303044473245E-017,0.E+000)); +#180268 = VECTOR('',#180269,1.); +#180269 = DIRECTION('',(0.E+000,1.)); +#180270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180271 = ORIENTED_EDGE('',*,*,#179696,.T.); +#180272 = ORIENTED_EDGE('',*,*,#180203,.T.); +#180273 = ADVANCED_FACE('',(#180274),#179740,.T.); +#180274 = FACE_BOUND('',#180275,.T.); +#180275 = EDGE_LOOP('',(#180276,#180277,#180297,#180298)); +#180276 = ORIENTED_EDGE('',*,*,#179857,.F.); +#180277 = ORIENTED_EDGE('',*,*,#180278,.F.); +#180278 = EDGE_CURVE('',#179725,#179831,#180279,.T.); +#180279 = SURFACE_CURVE('',#180280,(#180284,#180291),.PCURVE_S1.); +#180280 = LINE('',#180281,#180282); +#180281 = CARTESIAN_POINT('',(0.135,0.906981201809,0.50752811704)); +#180282 = VECTOR('',#180283,1.); +#180283 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180284 = PCURVE('',#179740,#180285); +#180285 = DEFINITIONAL_REPRESENTATION('',(#180286),#180290); +#180286 = LINE('',#180287,#180288); +#180287 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#180288 = VECTOR('',#180289,1.); +#180289 = DIRECTION('',(0.E+000,1.)); +#180290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180291 = PCURVE('',#179464,#180292); +#180292 = DEFINITIONAL_REPRESENTATION('',(#180293),#180296); +#180293 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180294,#180295), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177902 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#177903 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#177904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177905 = ORIENTED_EDGE('',*,*,#177332,.T.); -#177906 = ORIENTED_EDGE('',*,*,#177860,.T.); -#177907 = ADVANCED_FACE('',(#177908),#177072,.F.); -#177908 = FACE_BOUND('',#177909,.F.); -#177909 = EDGE_LOOP('',(#177910,#177911,#177912,#177913)); -#177910 = ORIENTED_EDGE('',*,*,#177438,.T.); -#177911 = ORIENTED_EDGE('',*,*,#177886,.F.); -#177912 = ORIENTED_EDGE('',*,*,#177360,.F.); -#177913 = ORIENTED_EDGE('',*,*,#177056,.T.); -#177914 = ADVANCED_FACE('',(#177915),#172440,.T.); -#177915 = FACE_BOUND('',#177916,.T.); -#177916 = EDGE_LOOP('',(#177917,#177918,#177941,#177968)); -#177917 = ORIENTED_EDGE('',*,*,#172426,.T.); -#177918 = ORIENTED_EDGE('',*,*,#177919,.T.); -#177919 = EDGE_CURVE('',#171495,#177920,#177922,.T.); -#177920 = VERTEX_POINT('',#177921); -#177921 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.6)); -#177922 = SURFACE_CURVE('',#177923,(#177927,#177934),.PCURVE_S1.); -#177923 = LINE('',#177924,#177925); -#177924 = CARTESIAN_POINT('',(-0.515,0.7,0.6)); -#177925 = VECTOR('',#177926,1.); -#177926 = DIRECTION('',(0.E+000,1.,0.E+000)); -#177927 = PCURVE('',#172440,#177928); -#177928 = DEFINITIONAL_REPRESENTATION('',(#177929),#177933); -#177929 = LINE('',#177930,#177931); -#177930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#177931 = VECTOR('',#177932,1.); -#177932 = DIRECTION('',(0.E+000,1.)); -#177933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177934 = PCURVE('',#171510,#177935); -#177935 = DEFINITIONAL_REPRESENTATION('',(#177936),#177940); -#177936 = LINE('',#177937,#177938); -#177937 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#177938 = VECTOR('',#177939,1.); -#177939 = DIRECTION('',(0.E+000,1.)); -#177940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177941 = ORIENTED_EDGE('',*,*,#177942,.T.); -#177942 = EDGE_CURVE('',#177920,#177943,#177945,.T.); -#177943 = VERTEX_POINT('',#177944); -#177944 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.6)); -#177945 = SURFACE_CURVE('',#177946,(#177950,#177957),.PCURVE_S1.); -#177946 = LINE('',#177947,#177948); -#177947 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.6)); -#177948 = VECTOR('',#177949,1.); -#177949 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177950 = PCURVE('',#172440,#177951); -#177951 = DEFINITIONAL_REPRESENTATION('',(#177952),#177956); -#177952 = LINE('',#177953,#177954); -#177953 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); -#177954 = VECTOR('',#177955,1.); -#177955 = DIRECTION('',(-1.,0.E+000)); -#177956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177957 = PCURVE('',#177958,#177963); -#177958 = CYLINDRICAL_SURFACE('',#177959,0.1); -#177959 = AXIS2_PLACEMENT_3D('',#177960,#177961,#177962); -#177960 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); -#177961 = DIRECTION('',(1.,0.E+000,0.E+000)); -#177962 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#177963 = DEFINITIONAL_REPRESENTATION('',(#177964),#177967); -#177964 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#177965,#177966), +#180294 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#180295 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180297 = ORIENTED_EDGE('',*,*,#179724,.T.); +#180298 = ORIENTED_EDGE('',*,*,#180252,.T.); +#180299 = ADVANCED_FACE('',(#180300),#179464,.F.); +#180300 = FACE_BOUND('',#180301,.F.); +#180301 = EDGE_LOOP('',(#180302,#180303,#180304,#180305)); +#180302 = ORIENTED_EDGE('',*,*,#179830,.T.); +#180303 = ORIENTED_EDGE('',*,*,#180278,.F.); +#180304 = ORIENTED_EDGE('',*,*,#179752,.F.); +#180305 = ORIENTED_EDGE('',*,*,#179448,.T.); +#180306 = ADVANCED_FACE('',(#180307),#174832,.T.); +#180307 = FACE_BOUND('',#180308,.T.); +#180308 = EDGE_LOOP('',(#180309,#180310,#180333,#180360)); +#180309 = ORIENTED_EDGE('',*,*,#174818,.T.); +#180310 = ORIENTED_EDGE('',*,*,#180311,.T.); +#180311 = EDGE_CURVE('',#173887,#180312,#180314,.T.); +#180312 = VERTEX_POINT('',#180313); +#180313 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.6)); +#180314 = SURFACE_CURVE('',#180315,(#180319,#180326),.PCURVE_S1.); +#180315 = LINE('',#180316,#180317); +#180316 = CARTESIAN_POINT('',(-0.515,0.7,0.6)); +#180317 = VECTOR('',#180318,1.); +#180318 = DIRECTION('',(0.E+000,1.,0.E+000)); +#180319 = PCURVE('',#174832,#180320); +#180320 = DEFINITIONAL_REPRESENTATION('',(#180321),#180325); +#180321 = LINE('',#180322,#180323); +#180322 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180323 = VECTOR('',#180324,1.); +#180324 = DIRECTION('',(0.E+000,1.)); +#180325 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180326 = PCURVE('',#173902,#180327); +#180327 = DEFINITIONAL_REPRESENTATION('',(#180328),#180332); +#180328 = LINE('',#180329,#180330); +#180329 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#180330 = VECTOR('',#180331,1.); +#180331 = DIRECTION('',(0.E+000,1.)); +#180332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180333 = ORIENTED_EDGE('',*,*,#180334,.T.); +#180334 = EDGE_CURVE('',#180312,#180335,#180337,.T.); +#180335 = VERTEX_POINT('',#180336); +#180336 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.6)); +#180337 = SURFACE_CURVE('',#180338,(#180342,#180349),.PCURVE_S1.); +#180338 = LINE('',#180339,#180340); +#180339 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.6)); +#180340 = VECTOR('',#180341,1.); +#180341 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180342 = PCURVE('',#174832,#180343); +#180343 = DEFINITIONAL_REPRESENTATION('',(#180344),#180348); +#180344 = LINE('',#180345,#180346); +#180345 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); +#180346 = VECTOR('',#180347,1.); +#180347 = DIRECTION('',(-1.,0.E+000)); +#180348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180349 = PCURVE('',#180350,#180355); +#180350 = CYLINDRICAL_SURFACE('',#180351,0.1); +#180351 = AXIS2_PLACEMENT_3D('',#180352,#180353,#180354); +#180352 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); +#180353 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180354 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180355 = DEFINITIONAL_REPRESENTATION('',(#180356),#180359); +#180356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180357,#180358), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#177965 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#177966 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#177967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177968 = ORIENTED_EDGE('',*,*,#177969,.F.); -#177969 = EDGE_CURVE('',#171416,#177943,#177970,.T.); -#177970 = SURFACE_CURVE('',#177971,(#177975,#177982),.PCURVE_S1.); -#177971 = LINE('',#177972,#177973); -#177972 = CARTESIAN_POINT('',(-0.175,0.7,0.6)); -#177973 = VECTOR('',#177974,1.); -#177974 = DIRECTION('',(0.E+000,1.,0.E+000)); -#177975 = PCURVE('',#172440,#177976); -#177976 = DEFINITIONAL_REPRESENTATION('',(#177977),#177981); -#177977 = LINE('',#177978,#177979); -#177978 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#177979 = VECTOR('',#177980,1.); -#177980 = DIRECTION('',(0.E+000,1.)); -#177981 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177982 = PCURVE('',#171454,#177983); -#177983 = DEFINITIONAL_REPRESENTATION('',(#177984),#177988); -#177984 = LINE('',#177985,#177986); -#177985 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#177986 = VECTOR('',#177987,1.); -#177987 = DIRECTION('',(0.E+000,1.)); -#177988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#177989 = ADVANCED_FACE('',(#177990),#171510,.F.); -#177990 = FACE_BOUND('',#177991,.T.); -#177991 = EDGE_LOOP('',(#177992,#177993,#177994,#178017,#178045,#178073, - #178105,#178133,#178161,#178189,#178217,#178245)); -#177992 = ORIENTED_EDGE('',*,*,#177919,.F.); -#177993 = ORIENTED_EDGE('',*,*,#171494,.T.); -#177994 = ORIENTED_EDGE('',*,*,#177995,.F.); -#177995 = EDGE_CURVE('',#177996,#171467,#177998,.T.); -#177996 = VERTEX_POINT('',#177997); -#177997 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); -#177998 = SURFACE_CURVE('',#177999,(#178003,#178010),.PCURVE_S1.); -#177999 = LINE('',#178000,#178001); -#178000 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); -#178001 = VECTOR('',#178002,1.); -#178002 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#178003 = PCURVE('',#171510,#178004); -#178004 = DEFINITIONAL_REPRESENTATION('',(#178005),#178009); -#178005 = LINE('',#178006,#178007); -#178006 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#178007 = VECTOR('',#178008,1.); -#178008 = DIRECTION('',(0.E+000,-1.)); -#178009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178010 = PCURVE('',#171482,#178011); -#178011 = DEFINITIONAL_REPRESENTATION('',(#178012),#178016); -#178012 = LINE('',#178013,#178014); -#178013 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178014 = VECTOR('',#178015,1.); -#178015 = DIRECTION('',(0.E+000,-1.)); -#178016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178017 = ORIENTED_EDGE('',*,*,#178018,.F.); -#178018 = EDGE_CURVE('',#178019,#177996,#178021,.T.); -#178019 = VERTEX_POINT('',#178020); -#178020 = CARTESIAN_POINT('',(-0.515,1.056555553792,0.518820292599)); -#178021 = SURFACE_CURVE('',#178022,(#178027,#178034),.PCURVE_S1.); -#178022 = CIRCLE('',#178023,0.25); -#178023 = AXIS2_PLACEMENT_3D('',#178024,#178025,#178026); -#178024 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); -#178025 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178026 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178027 = PCURVE('',#171510,#178028); -#178028 = DEFINITIONAL_REPRESENTATION('',(#178029),#178033); -#178029 = CIRCLE('',#178030,0.25); -#178030 = AXIS2_PLACEMENT_2D('',#178031,#178032); -#178031 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178032 = DIRECTION('',(1.,0.E+000)); -#178033 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178034 = PCURVE('',#178035,#178040); -#178035 = CYLINDRICAL_SURFACE('',#178036,0.25); -#178036 = AXIS2_PLACEMENT_3D('',#178037,#178038,#178039); -#178037 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); -#178038 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178039 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178040 = DEFINITIONAL_REPRESENTATION('',(#178041),#178044); -#178041 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178042,#178043), +#180357 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#180358 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#180359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180360 = ORIENTED_EDGE('',*,*,#180361,.F.); +#180361 = EDGE_CURVE('',#173808,#180335,#180362,.T.); +#180362 = SURFACE_CURVE('',#180363,(#180367,#180374),.PCURVE_S1.); +#180363 = LINE('',#180364,#180365); +#180364 = CARTESIAN_POINT('',(-0.175,0.7,0.6)); +#180365 = VECTOR('',#180366,1.); +#180366 = DIRECTION('',(0.E+000,1.,0.E+000)); +#180367 = PCURVE('',#174832,#180368); +#180368 = DEFINITIONAL_REPRESENTATION('',(#180369),#180373); +#180369 = LINE('',#180370,#180371); +#180370 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#180371 = VECTOR('',#180372,1.); +#180372 = DIRECTION('',(0.E+000,1.)); +#180373 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180374 = PCURVE('',#173846,#180375); +#180375 = DEFINITIONAL_REPRESENTATION('',(#180376),#180380); +#180376 = LINE('',#180377,#180378); +#180377 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#180378 = VECTOR('',#180379,1.); +#180379 = DIRECTION('',(0.E+000,1.)); +#180380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180381 = ADVANCED_FACE('',(#180382),#173902,.F.); +#180382 = FACE_BOUND('',#180383,.T.); +#180383 = EDGE_LOOP('',(#180384,#180385,#180386,#180409,#180437,#180465, + #180497,#180525,#180553,#180581,#180609,#180637)); +#180384 = ORIENTED_EDGE('',*,*,#180311,.F.); +#180385 = ORIENTED_EDGE('',*,*,#173886,.T.); +#180386 = ORIENTED_EDGE('',*,*,#180387,.F.); +#180387 = EDGE_CURVE('',#180388,#173859,#180390,.T.); +#180388 = VERTEX_POINT('',#180389); +#180389 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); +#180390 = SURFACE_CURVE('',#180391,(#180395,#180402),.PCURVE_S1.); +#180391 = LINE('',#180392,#180393); +#180392 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); +#180393 = VECTOR('',#180394,1.); +#180394 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#180395 = PCURVE('',#173902,#180396); +#180396 = DEFINITIONAL_REPRESENTATION('',(#180397),#180401); +#180397 = LINE('',#180398,#180399); +#180398 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#180399 = VECTOR('',#180400,1.); +#180400 = DIRECTION('',(0.E+000,-1.)); +#180401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180402 = PCURVE('',#173874,#180403); +#180403 = DEFINITIONAL_REPRESENTATION('',(#180404),#180408); +#180404 = LINE('',#180405,#180406); +#180405 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180406 = VECTOR('',#180407,1.); +#180407 = DIRECTION('',(0.E+000,-1.)); +#180408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180409 = ORIENTED_EDGE('',*,*,#180410,.F.); +#180410 = EDGE_CURVE('',#180411,#180388,#180413,.T.); +#180411 = VERTEX_POINT('',#180412); +#180412 = CARTESIAN_POINT('',(-0.515,1.056555553792,0.518820292599)); +#180413 = SURFACE_CURVE('',#180414,(#180419,#180426),.PCURVE_S1.); +#180414 = CIRCLE('',#180415,0.25); +#180415 = AXIS2_PLACEMENT_3D('',#180416,#180417,#180418); +#180416 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); +#180417 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180418 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180419 = PCURVE('',#173902,#180420); +#180420 = DEFINITIONAL_REPRESENTATION('',(#180421),#180425); +#180421 = CIRCLE('',#180422,0.25); +#180422 = AXIS2_PLACEMENT_2D('',#180423,#180424); +#180423 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180424 = DIRECTION('',(1.,0.E+000)); +#180425 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180426 = PCURVE('',#180427,#180432); +#180427 = CYLINDRICAL_SURFACE('',#180428,0.25); +#180428 = AXIS2_PLACEMENT_3D('',#180429,#180430,#180431); +#180429 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); +#180430 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180431 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180432 = DEFINITIONAL_REPRESENTATION('',(#180433),#180436); +#180433 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180434,#180435), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#178042 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#178043 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#178044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178045 = ORIENTED_EDGE('',*,*,#178046,.F.); -#178046 = EDGE_CURVE('',#178047,#178019,#178049,.T.); -#178047 = VERTEX_POINT('',#178048); -#178048 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); -#178049 = SURFACE_CURVE('',#178050,(#178054,#178061),.PCURVE_S1.); -#178050 = LINE('',#178051,#178052); -#178051 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); -#178052 = VECTOR('',#178053,1.); -#178053 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#178054 = PCURVE('',#171510,#178055); -#178055 = DEFINITIONAL_REPRESENTATION('',(#178056),#178060); -#178056 = LINE('',#178057,#178058); -#178057 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#178058 = VECTOR('',#178059,1.); -#178059 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#178060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178061 = PCURVE('',#178062,#178067); -#178062 = PLANE('',#178063); -#178063 = AXIS2_PLACEMENT_3D('',#178064,#178065,#178066); -#178064 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); -#178065 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); -#178066 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#178067 = DEFINITIONAL_REPRESENTATION('',(#178068),#178072); -#178068 = LINE('',#178069,#178070); -#178069 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178070 = VECTOR('',#178071,1.); -#178071 = DIRECTION('',(1.,0.E+000)); -#178072 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178073 = ORIENTED_EDGE('',*,*,#178074,.F.); -#178074 = EDGE_CURVE('',#178075,#178047,#178077,.T.); -#178075 = VERTEX_POINT('',#178076); -#178076 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.15)); -#178077 = SURFACE_CURVE('',#178078,(#178083,#178094),.PCURVE_S1.); -#178078 = CIRCLE('',#178079,5.E-002); -#178079 = AXIS2_PLACEMENT_3D('',#178080,#178081,#178082); -#178080 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); -#178081 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#178082 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178083 = PCURVE('',#171510,#178084); -#178084 = DEFINITIONAL_REPRESENTATION('',(#178085),#178093); -#178085 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#178086,#178087,#178088, - #178089,#178090,#178091,#178092),.UNSPECIFIED.,.T.,.F.) +#180434 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#180435 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#180436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180437 = ORIENTED_EDGE('',*,*,#180438,.F.); +#180438 = EDGE_CURVE('',#180439,#180411,#180441,.T.); +#180439 = VERTEX_POINT('',#180440); +#180440 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); +#180441 = SURFACE_CURVE('',#180442,(#180446,#180453),.PCURVE_S1.); +#180442 = LINE('',#180443,#180444); +#180443 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); +#180444 = VECTOR('',#180445,1.); +#180445 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#180446 = PCURVE('',#173902,#180447); +#180447 = DEFINITIONAL_REPRESENTATION('',(#180448),#180452); +#180448 = LINE('',#180449,#180450); +#180449 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#180450 = VECTOR('',#180451,1.); +#180451 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#180452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180453 = PCURVE('',#180454,#180459); +#180454 = PLANE('',#180455); +#180455 = AXIS2_PLACEMENT_3D('',#180456,#180457,#180458); +#180456 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); +#180457 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); +#180458 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#180459 = DEFINITIONAL_REPRESENTATION('',(#180460),#180464); +#180460 = LINE('',#180461,#180462); +#180461 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180462 = VECTOR('',#180463,1.); +#180463 = DIRECTION('',(1.,0.E+000)); +#180464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180465 = ORIENTED_EDGE('',*,*,#180466,.F.); +#180466 = EDGE_CURVE('',#180467,#180439,#180469,.T.); +#180467 = VERTEX_POINT('',#180468); +#180468 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.15)); +#180469 = SURFACE_CURVE('',#180470,(#180475,#180486),.PCURVE_S1.); +#180470 = CIRCLE('',#180471,5.E-002); +#180471 = AXIS2_PLACEMENT_3D('',#180472,#180473,#180474); +#180472 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); +#180473 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#180474 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180475 = PCURVE('',#173902,#180476); +#180476 = DEFINITIONAL_REPRESENTATION('',(#180477),#180485); +#180477 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180478,#180479,#180480, + #180481,#180482,#180483,#180484),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#178086 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178087 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#178088 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#178089 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#178090 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#178091 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#178092 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178094 = PCURVE('',#178095,#178100); -#178095 = CYLINDRICAL_SURFACE('',#178096,5.E-002); -#178096 = AXIS2_PLACEMENT_3D('',#178097,#178098,#178099); -#178097 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); -#178098 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178099 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178100 = DEFINITIONAL_REPRESENTATION('',(#178101),#178104); -#178101 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178102,#178103), +#180478 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#180479 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#180480 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#180481 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#180482 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#180483 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#180484 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#180485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180486 = PCURVE('',#180487,#180492); +#180487 = CYLINDRICAL_SURFACE('',#180488,5.E-002); +#180488 = AXIS2_PLACEMENT_3D('',#180489,#180490,#180491); +#180489 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); +#180490 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180491 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180492 = DEFINITIONAL_REPRESENTATION('',(#180493),#180496); +#180493 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180494,#180495), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#178102 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#178103 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#178104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178105 = ORIENTED_EDGE('',*,*,#178106,.F.); -#178106 = EDGE_CURVE('',#178107,#178075,#178109,.T.); -#178107 = VERTEX_POINT('',#178108); -#178108 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); -#178109 = SURFACE_CURVE('',#178110,(#178114,#178121),.PCURVE_S1.); -#178110 = LINE('',#178111,#178112); -#178111 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); -#178112 = VECTOR('',#178113,1.); -#178113 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#178114 = PCURVE('',#171510,#178115); -#178115 = DEFINITIONAL_REPRESENTATION('',(#178116),#178120); -#178116 = LINE('',#178117,#178118); -#178117 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#178118 = VECTOR('',#178119,1.); -#178119 = DIRECTION('',(3.020255886006E-016,-1.)); -#178120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178121 = PCURVE('',#178122,#178127); -#178122 = PLANE('',#178123); -#178123 = AXIS2_PLACEMENT_3D('',#178124,#178125,#178126); -#178124 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); -#178125 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); -#178126 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#178127 = DEFINITIONAL_REPRESENTATION('',(#178128),#178132); -#178128 = LINE('',#178129,#178130); -#178129 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178130 = VECTOR('',#178131,1.); -#178131 = DIRECTION('',(1.,0.E+000)); -#178132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178133 = ORIENTED_EDGE('',*,*,#178134,.F.); -#178134 = EDGE_CURVE('',#178135,#178107,#178137,.T.); -#178135 = VERTEX_POINT('',#178136); -#178136 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178137 = SURFACE_CURVE('',#178138,(#178142,#178149),.PCURVE_S1.); -#178138 = LINE('',#178139,#178140); -#178139 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178140 = VECTOR('',#178141,1.); -#178141 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178142 = PCURVE('',#171510,#178143); -#178143 = DEFINITIONAL_REPRESENTATION('',(#178144),#178148); -#178144 = LINE('',#178145,#178146); -#178145 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#178146 = VECTOR('',#178147,1.); -#178147 = DIRECTION('',(-1.,0.E+000)); -#178148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178149 = PCURVE('',#178150,#178155); -#178150 = PLANE('',#178151); -#178151 = AXIS2_PLACEMENT_3D('',#178152,#178153,#178154); -#178152 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178153 = DIRECTION('',(0.E+000,1.,0.E+000)); -#178154 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178155 = DEFINITIONAL_REPRESENTATION('',(#178156),#178160); -#178156 = LINE('',#178157,#178158); -#178157 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178158 = VECTOR('',#178159,1.); -#178159 = DIRECTION('',(1.,0.E+000)); -#178160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178161 = ORIENTED_EDGE('',*,*,#178162,.F.); -#178162 = EDGE_CURVE('',#178163,#178135,#178165,.T.); -#178163 = VERTEX_POINT('',#178164); -#178164 = CARTESIAN_POINT('',(-0.515,1.1307673058,1.374592069281E-016)); -#178165 = SURFACE_CURVE('',#178166,(#178170,#178177),.PCURVE_S1.); -#178166 = LINE('',#178167,#178168); -#178167 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178168 = VECTOR('',#178169,1.); -#178169 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#178170 = PCURVE('',#171510,#178171); -#178171 = DEFINITIONAL_REPRESENTATION('',(#178172),#178176); -#178172 = LINE('',#178173,#178174); -#178173 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#178174 = VECTOR('',#178175,1.); -#178175 = DIRECTION('',(-2.516879905005E-016,1.)); -#178176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178177 = PCURVE('',#178178,#178183); -#178178 = PLANE('',#178179); -#178179 = AXIS2_PLACEMENT_3D('',#178180,#178181,#178182); -#178180 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178181 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); -#178182 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#178183 = DEFINITIONAL_REPRESENTATION('',(#178184),#178188); -#178184 = LINE('',#178185,#178186); -#178185 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178186 = VECTOR('',#178187,1.); -#178187 = DIRECTION('',(1.,0.E+000)); -#178188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178189 = ORIENTED_EDGE('',*,*,#178190,.F.); -#178190 = EDGE_CURVE('',#178191,#178163,#178193,.T.); -#178191 = VERTEX_POINT('',#178192); -#178192 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); -#178193 = SURFACE_CURVE('',#178194,(#178199,#178206),.PCURVE_S1.); -#178194 = CIRCLE('',#178195,0.2); -#178195 = AXIS2_PLACEMENT_3D('',#178196,#178197,#178198); -#178196 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); -#178197 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178198 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178199 = PCURVE('',#171510,#178200); -#178200 = DEFINITIONAL_REPRESENTATION('',(#178201),#178205); -#178201 = CIRCLE('',#178202,0.2); -#178202 = AXIS2_PLACEMENT_2D('',#178203,#178204); -#178203 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#178204 = DIRECTION('',(-1.,0.E+000)); -#178205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178206 = PCURVE('',#178207,#178212); -#178207 = CYLINDRICAL_SURFACE('',#178208,0.2); -#178208 = AXIS2_PLACEMENT_3D('',#178209,#178210,#178211); -#178209 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); -#178210 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178211 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178212 = DEFINITIONAL_REPRESENTATION('',(#178213),#178216); -#178213 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178214,#178215), +#180494 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#180495 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#180496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180497 = ORIENTED_EDGE('',*,*,#180498,.F.); +#180498 = EDGE_CURVE('',#180499,#180467,#180501,.T.); +#180499 = VERTEX_POINT('',#180500); +#180500 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); +#180501 = SURFACE_CURVE('',#180502,(#180506,#180513),.PCURVE_S1.); +#180502 = LINE('',#180503,#180504); +#180503 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); +#180504 = VECTOR('',#180505,1.); +#180505 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#180506 = PCURVE('',#173902,#180507); +#180507 = DEFINITIONAL_REPRESENTATION('',(#180508),#180512); +#180508 = LINE('',#180509,#180510); +#180509 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#180510 = VECTOR('',#180511,1.); +#180511 = DIRECTION('',(3.020255886006E-016,-1.)); +#180512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180513 = PCURVE('',#180514,#180519); +#180514 = PLANE('',#180515); +#180515 = AXIS2_PLACEMENT_3D('',#180516,#180517,#180518); +#180516 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); +#180517 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); +#180518 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#180519 = DEFINITIONAL_REPRESENTATION('',(#180520),#180524); +#180520 = LINE('',#180521,#180522); +#180521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180522 = VECTOR('',#180523,1.); +#180523 = DIRECTION('',(1.,0.E+000)); +#180524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180525 = ORIENTED_EDGE('',*,*,#180526,.F.); +#180526 = EDGE_CURVE('',#180527,#180499,#180529,.T.); +#180527 = VERTEX_POINT('',#180528); +#180528 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#180529 = SURFACE_CURVE('',#180530,(#180534,#180541),.PCURVE_S1.); +#180530 = LINE('',#180531,#180532); +#180531 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#180532 = VECTOR('',#180533,1.); +#180533 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180534 = PCURVE('',#173902,#180535); +#180535 = DEFINITIONAL_REPRESENTATION('',(#180536),#180540); +#180536 = LINE('',#180537,#180538); +#180537 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#180538 = VECTOR('',#180539,1.); +#180539 = DIRECTION('',(-1.,0.E+000)); +#180540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180541 = PCURVE('',#180542,#180547); +#180542 = PLANE('',#180543); +#180543 = AXIS2_PLACEMENT_3D('',#180544,#180545,#180546); +#180544 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#180545 = DIRECTION('',(0.E+000,1.,0.E+000)); +#180546 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180547 = DEFINITIONAL_REPRESENTATION('',(#180548),#180552); +#180548 = LINE('',#180549,#180550); +#180549 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180550 = VECTOR('',#180551,1.); +#180551 = DIRECTION('',(1.,0.E+000)); +#180552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180553 = ORIENTED_EDGE('',*,*,#180554,.F.); +#180554 = EDGE_CURVE('',#180555,#180527,#180557,.T.); +#180555 = VERTEX_POINT('',#180556); +#180556 = CARTESIAN_POINT('',(-0.515,1.1307673058,1.374592069281E-016)); +#180557 = SURFACE_CURVE('',#180558,(#180562,#180569),.PCURVE_S1.); +#180558 = LINE('',#180559,#180560); +#180559 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#180560 = VECTOR('',#180561,1.); +#180561 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#180562 = PCURVE('',#173902,#180563); +#180563 = DEFINITIONAL_REPRESENTATION('',(#180564),#180568); +#180564 = LINE('',#180565,#180566); +#180565 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#180566 = VECTOR('',#180567,1.); +#180567 = DIRECTION('',(-2.516879905005E-016,1.)); +#180568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180569 = PCURVE('',#180570,#180575); +#180570 = PLANE('',#180571); +#180571 = AXIS2_PLACEMENT_3D('',#180572,#180573,#180574); +#180572 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#180573 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); +#180574 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#180575 = DEFINITIONAL_REPRESENTATION('',(#180576),#180580); +#180576 = LINE('',#180577,#180578); +#180577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180578 = VECTOR('',#180579,1.); +#180579 = DIRECTION('',(1.,0.E+000)); +#180580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180581 = ORIENTED_EDGE('',*,*,#180582,.F.); +#180582 = EDGE_CURVE('',#180583,#180555,#180585,.T.); +#180583 = VERTEX_POINT('',#180584); +#180584 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); +#180585 = SURFACE_CURVE('',#180586,(#180591,#180598),.PCURVE_S1.); +#180586 = CIRCLE('',#180587,0.2); +#180587 = AXIS2_PLACEMENT_3D('',#180588,#180589,#180590); +#180588 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); +#180589 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180590 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180591 = PCURVE('',#173902,#180592); +#180592 = DEFINITIONAL_REPRESENTATION('',(#180593),#180597); +#180593 = CIRCLE('',#180594,0.2); +#180594 = AXIS2_PLACEMENT_2D('',#180595,#180596); +#180595 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#180596 = DIRECTION('',(-1.,0.E+000)); +#180597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180598 = PCURVE('',#180599,#180604); +#180599 = CYLINDRICAL_SURFACE('',#180600,0.2); +#180600 = AXIS2_PLACEMENT_3D('',#180601,#180602,#180603); +#180601 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.2)); +#180602 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180603 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180604 = DEFINITIONAL_REPRESENTATION('',(#180605),#180608); +#180605 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180606,#180607), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#178214 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#178215 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#178216 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178217 = ORIENTED_EDGE('',*,*,#178218,.F.); -#178218 = EDGE_CURVE('',#178219,#178191,#178221,.T.); -#178219 = VERTEX_POINT('',#178220); -#178220 = CARTESIAN_POINT('',(-0.515,0.906981201809,0.50752811704)); -#178221 = SURFACE_CURVE('',#178222,(#178226,#178233),.PCURVE_S1.); -#178222 = LINE('',#178223,#178224); -#178223 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); -#178224 = VECTOR('',#178225,1.); -#178225 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#178226 = PCURVE('',#171510,#178227); -#178227 = DEFINITIONAL_REPRESENTATION('',(#178228),#178232); -#178228 = LINE('',#178229,#178230); -#178229 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#178230 = VECTOR('',#178231,1.); -#178231 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#178232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178233 = PCURVE('',#178234,#178239); -#178234 = PLANE('',#178235); -#178235 = AXIS2_PLACEMENT_3D('',#178236,#178237,#178238); -#178236 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); -#178237 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); -#178238 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#178239 = DEFINITIONAL_REPRESENTATION('',(#178240),#178244); -#178240 = LINE('',#178241,#178242); -#178241 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178242 = VECTOR('',#178243,1.); -#178243 = DIRECTION('',(1.,0.E+000)); -#178244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178245 = ORIENTED_EDGE('',*,*,#178246,.F.); -#178246 = EDGE_CURVE('',#177920,#178219,#178247,.T.); -#178247 = SURFACE_CURVE('',#178248,(#178253,#178264),.PCURVE_S1.); -#178248 = CIRCLE('',#178249,0.1); -#178249 = AXIS2_PLACEMENT_3D('',#178250,#178251,#178252); -#178250 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); -#178251 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#178252 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178253 = PCURVE('',#171510,#178254); -#178254 = DEFINITIONAL_REPRESENTATION('',(#178255),#178263); -#178255 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#178256,#178257,#178258, - #178259,#178260,#178261,#178262),.UNSPECIFIED.,.F.,.F.) +#180606 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#180607 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#180608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180609 = ORIENTED_EDGE('',*,*,#180610,.F.); +#180610 = EDGE_CURVE('',#180611,#180583,#180613,.T.); +#180611 = VERTEX_POINT('',#180612); +#180612 = CARTESIAN_POINT('',(-0.515,0.906981201809,0.50752811704)); +#180613 = SURFACE_CURVE('',#180614,(#180618,#180625),.PCURVE_S1.); +#180614 = LINE('',#180615,#180616); +#180615 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); +#180616 = VECTOR('',#180617,1.); +#180617 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#180618 = PCURVE('',#173902,#180619); +#180619 = DEFINITIONAL_REPRESENTATION('',(#180620),#180624); +#180620 = LINE('',#180621,#180622); +#180621 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#180622 = VECTOR('',#180623,1.); +#180623 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#180624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180625 = PCURVE('',#180626,#180631); +#180626 = PLANE('',#180627); +#180627 = AXIS2_PLACEMENT_3D('',#180628,#180629,#180630); +#180628 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); +#180629 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); +#180630 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#180631 = DEFINITIONAL_REPRESENTATION('',(#180632),#180636); +#180632 = LINE('',#180633,#180634); +#180633 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180634 = VECTOR('',#180635,1.); +#180635 = DIRECTION('',(1.,0.E+000)); +#180636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180637 = ORIENTED_EDGE('',*,*,#180638,.F.); +#180638 = EDGE_CURVE('',#180312,#180611,#180639,.T.); +#180639 = SURFACE_CURVE('',#180640,(#180645,#180656),.PCURVE_S1.); +#180640 = CIRCLE('',#180641,0.1); +#180641 = AXIS2_PLACEMENT_3D('',#180642,#180643,#180644); +#180642 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.5)); +#180643 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#180644 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180645 = PCURVE('',#173902,#180646); +#180646 = DEFINITIONAL_REPRESENTATION('',(#180647),#180655); +#180647 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180648,#180649,#180650, + #180651,#180652,#180653,#180654),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#178256 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#178257 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#178258 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#178259 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#178260 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#178261 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#178262 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#178263 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178264 = PCURVE('',#177958,#178265); -#178265 = DEFINITIONAL_REPRESENTATION('',(#178266),#178269); -#178266 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178267,#178268), +#180648 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#180649 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#180650 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#180651 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#180652 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#180653 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#180654 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#180655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180656 = PCURVE('',#180350,#180657); +#180657 = DEFINITIONAL_REPRESENTATION('',(#180658),#180661); +#180658 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180659,#180660), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#178267 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#178268 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#178269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178270 = ADVANCED_FACE('',(#178271),#171482,.T.); -#178271 = FACE_BOUND('',#178272,.T.); -#178272 = EDGE_LOOP('',(#178273,#178296,#178316,#178317)); -#178273 = ORIENTED_EDGE('',*,*,#178274,.F.); -#178274 = EDGE_CURVE('',#178275,#171439,#178277,.T.); -#178275 = VERTEX_POINT('',#178276); -#178276 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.75)); -#178277 = SURFACE_CURVE('',#178278,(#178282,#178289),.PCURVE_S1.); -#178278 = LINE('',#178279,#178280); -#178279 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.75)); -#178280 = VECTOR('',#178281,1.); -#178281 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#178282 = PCURVE('',#171482,#178283); -#178283 = DEFINITIONAL_REPRESENTATION('',(#178284),#178288); -#178284 = LINE('',#178285,#178286); -#178285 = CARTESIAN_POINT('',(0.34,0.E+000)); -#178286 = VECTOR('',#178287,1.); -#178287 = DIRECTION('',(0.E+000,-1.)); -#178288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178289 = PCURVE('',#171454,#178290); -#178290 = DEFINITIONAL_REPRESENTATION('',(#178291),#178295); -#178291 = LINE('',#178292,#178293); -#178292 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#178293 = VECTOR('',#178294,1.); -#178294 = DIRECTION('',(0.E+000,-1.)); -#178295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178296 = ORIENTED_EDGE('',*,*,#178297,.F.); -#178297 = EDGE_CURVE('',#177996,#178275,#178298,.T.); -#178298 = SURFACE_CURVE('',#178299,(#178303,#178310),.PCURVE_S1.); -#178299 = LINE('',#178300,#178301); -#178300 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); -#178301 = VECTOR('',#178302,1.); -#178302 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178303 = PCURVE('',#171482,#178304); -#178304 = DEFINITIONAL_REPRESENTATION('',(#178305),#178309); -#178305 = LINE('',#178306,#178307); -#178306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178307 = VECTOR('',#178308,1.); -#178308 = DIRECTION('',(1.,0.E+000)); -#178309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178310 = PCURVE('',#178035,#178311); -#178311 = DEFINITIONAL_REPRESENTATION('',(#178312),#178315); -#178312 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178313,#178314), +#180659 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#180660 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#180661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180662 = ADVANCED_FACE('',(#180663),#173874,.T.); +#180663 = FACE_BOUND('',#180664,.T.); +#180664 = EDGE_LOOP('',(#180665,#180688,#180708,#180709)); +#180665 = ORIENTED_EDGE('',*,*,#180666,.F.); +#180666 = EDGE_CURVE('',#180667,#173831,#180669,.T.); +#180667 = VERTEX_POINT('',#180668); +#180668 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.75)); +#180669 = SURFACE_CURVE('',#180670,(#180674,#180681),.PCURVE_S1.); +#180670 = LINE('',#180671,#180672); +#180671 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.75)); +#180672 = VECTOR('',#180673,1.); +#180673 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#180674 = PCURVE('',#173874,#180675); +#180675 = DEFINITIONAL_REPRESENTATION('',(#180676),#180680); +#180676 = LINE('',#180677,#180678); +#180677 = CARTESIAN_POINT('',(0.34,0.E+000)); +#180678 = VECTOR('',#180679,1.); +#180679 = DIRECTION('',(0.E+000,-1.)); +#180680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180681 = PCURVE('',#173846,#180682); +#180682 = DEFINITIONAL_REPRESENTATION('',(#180683),#180687); +#180683 = LINE('',#180684,#180685); +#180684 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#180685 = VECTOR('',#180686,1.); +#180686 = DIRECTION('',(0.E+000,-1.)); +#180687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180688 = ORIENTED_EDGE('',*,*,#180689,.F.); +#180689 = EDGE_CURVE('',#180388,#180667,#180690,.T.); +#180690 = SURFACE_CURVE('',#180691,(#180695,#180702),.PCURVE_S1.); +#180691 = LINE('',#180692,#180693); +#180692 = CARTESIAN_POINT('',(-0.515,0.807264967154,0.75)); +#180693 = VECTOR('',#180694,1.); +#180694 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180695 = PCURVE('',#173874,#180696); +#180696 = DEFINITIONAL_REPRESENTATION('',(#180697),#180701); +#180697 = LINE('',#180698,#180699); +#180698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180699 = VECTOR('',#180700,1.); +#180700 = DIRECTION('',(1.,0.E+000)); +#180701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180702 = PCURVE('',#180427,#180703); +#180703 = DEFINITIONAL_REPRESENTATION('',(#180704),#180707); +#180704 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180705,#180706), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178313 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#178314 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#178315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178316 = ORIENTED_EDGE('',*,*,#177995,.T.); -#178317 = ORIENTED_EDGE('',*,*,#171466,.F.); -#178318 = ADVANCED_FACE('',(#178319),#171454,.T.); -#178319 = FACE_BOUND('',#178320,.T.); -#178320 = EDGE_LOOP('',(#178321,#178322,#178323,#178350,#178373,#178396, - #178419,#178442,#178465,#178492,#178515,#178536)); -#178321 = ORIENTED_EDGE('',*,*,#171438,.F.); -#178322 = ORIENTED_EDGE('',*,*,#177969,.T.); -#178323 = ORIENTED_EDGE('',*,*,#178324,.T.); -#178324 = EDGE_CURVE('',#177943,#178325,#178327,.T.); -#178325 = VERTEX_POINT('',#178326); -#178326 = CARTESIAN_POINT('',(-0.175,0.906981201809,0.50752811704)); -#178327 = SURFACE_CURVE('',#178328,(#178333,#178344),.PCURVE_S1.); -#178328 = CIRCLE('',#178329,0.1); -#178329 = AXIS2_PLACEMENT_3D('',#178330,#178331,#178332); -#178330 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); -#178331 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#178332 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178333 = PCURVE('',#171454,#178334); -#178334 = DEFINITIONAL_REPRESENTATION('',(#178335),#178343); -#178335 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#178336,#178337,#178338, - #178339,#178340,#178341,#178342),.UNSPECIFIED.,.F.,.F.) +#180705 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#180706 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#180707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180708 = ORIENTED_EDGE('',*,*,#180387,.T.); +#180709 = ORIENTED_EDGE('',*,*,#173858,.F.); +#180710 = ADVANCED_FACE('',(#180711),#173846,.T.); +#180711 = FACE_BOUND('',#180712,.T.); +#180712 = EDGE_LOOP('',(#180713,#180714,#180715,#180742,#180765,#180788, + #180811,#180834,#180857,#180884,#180907,#180928)); +#180713 = ORIENTED_EDGE('',*,*,#173830,.F.); +#180714 = ORIENTED_EDGE('',*,*,#180361,.T.); +#180715 = ORIENTED_EDGE('',*,*,#180716,.T.); +#180716 = EDGE_CURVE('',#180335,#180717,#180719,.T.); +#180717 = VERTEX_POINT('',#180718); +#180718 = CARTESIAN_POINT('',(-0.175,0.906981201809,0.50752811704)); +#180719 = SURFACE_CURVE('',#180720,(#180725,#180736),.PCURVE_S1.); +#180720 = CIRCLE('',#180721,0.1); +#180721 = AXIS2_PLACEMENT_3D('',#180722,#180723,#180724); +#180722 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); +#180723 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#180724 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180725 = PCURVE('',#173846,#180726); +#180726 = DEFINITIONAL_REPRESENTATION('',(#180727),#180735); +#180727 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180728,#180729,#180730, + #180731,#180732,#180733,#180734),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#178336 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#178337 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#178338 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#178339 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#178340 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#178341 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#178342 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#178343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178344 = PCURVE('',#177958,#178345); -#178345 = DEFINITIONAL_REPRESENTATION('',(#178346),#178349); -#178346 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178347,#178348), +#180728 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#180729 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#180730 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#180731 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#180732 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#180733 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#180734 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#180735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180736 = PCURVE('',#180350,#180737); +#180737 = DEFINITIONAL_REPRESENTATION('',(#180738),#180741); +#180738 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180739,#180740), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#178347 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#178348 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#178349 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178350 = ORIENTED_EDGE('',*,*,#178351,.T.); -#178351 = EDGE_CURVE('',#178325,#178352,#178354,.T.); -#178352 = VERTEX_POINT('',#178353); -#178353 = CARTESIAN_POINT('',(-0.175,0.931334836489,0.184943765921)); -#178354 = SURFACE_CURVE('',#178355,(#178359,#178366),.PCURVE_S1.); -#178355 = LINE('',#178356,#178357); -#178356 = CARTESIAN_POINT('',(-0.175,0.931334836489,0.184943765921)); -#178357 = VECTOR('',#178358,1.); -#178358 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#178359 = PCURVE('',#171454,#178360); -#178360 = DEFINITIONAL_REPRESENTATION('',(#178361),#178365); -#178361 = LINE('',#178362,#178363); -#178362 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#178363 = VECTOR('',#178364,1.); -#178364 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#178365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178366 = PCURVE('',#178234,#178367); -#178367 = DEFINITIONAL_REPRESENTATION('',(#178368),#178372); -#178368 = LINE('',#178369,#178370); -#178369 = CARTESIAN_POINT('',(0.E+000,0.34)); -#178370 = VECTOR('',#178371,1.); -#178371 = DIRECTION('',(1.,0.E+000)); -#178372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178373 = ORIENTED_EDGE('',*,*,#178374,.T.); -#178374 = EDGE_CURVE('',#178352,#178375,#178377,.T.); -#178375 = VERTEX_POINT('',#178376); -#178376 = CARTESIAN_POINT('',(-0.175,1.1307673058,1.374592069281E-016)); -#178377 = SURFACE_CURVE('',#178378,(#178383,#178390),.PCURVE_S1.); -#178378 = CIRCLE('',#178379,0.2); -#178379 = AXIS2_PLACEMENT_3D('',#178380,#178381,#178382); -#178380 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.2)); -#178381 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178382 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178383 = PCURVE('',#171454,#178384); -#178384 = DEFINITIONAL_REPRESENTATION('',(#178385),#178389); -#178385 = CIRCLE('',#178386,0.2); -#178386 = AXIS2_PLACEMENT_2D('',#178387,#178388); -#178387 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#178388 = DIRECTION('',(-1.,0.E+000)); -#178389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178390 = PCURVE('',#178207,#178391); -#178391 = DEFINITIONAL_REPRESENTATION('',(#178392),#178395); -#178392 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178393,#178394), +#180739 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#180740 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180742 = ORIENTED_EDGE('',*,*,#180743,.T.); +#180743 = EDGE_CURVE('',#180717,#180744,#180746,.T.); +#180744 = VERTEX_POINT('',#180745); +#180745 = CARTESIAN_POINT('',(-0.175,0.931334836489,0.184943765921)); +#180746 = SURFACE_CURVE('',#180747,(#180751,#180758),.PCURVE_S1.); +#180747 = LINE('',#180748,#180749); +#180748 = CARTESIAN_POINT('',(-0.175,0.931334836489,0.184943765921)); +#180749 = VECTOR('',#180750,1.); +#180750 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#180751 = PCURVE('',#173846,#180752); +#180752 = DEFINITIONAL_REPRESENTATION('',(#180753),#180757); +#180753 = LINE('',#180754,#180755); +#180754 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#180755 = VECTOR('',#180756,1.); +#180756 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#180757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180758 = PCURVE('',#180626,#180759); +#180759 = DEFINITIONAL_REPRESENTATION('',(#180760),#180764); +#180760 = LINE('',#180761,#180762); +#180761 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180762 = VECTOR('',#180763,1.); +#180763 = DIRECTION('',(1.,0.E+000)); +#180764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180765 = ORIENTED_EDGE('',*,*,#180766,.T.); +#180766 = EDGE_CURVE('',#180744,#180767,#180769,.T.); +#180767 = VERTEX_POINT('',#180768); +#180768 = CARTESIAN_POINT('',(-0.175,1.1307673058,1.374592069281E-016)); +#180769 = SURFACE_CURVE('',#180770,(#180775,#180782),.PCURVE_S1.); +#180770 = CIRCLE('',#180771,0.2); +#180771 = AXIS2_PLACEMENT_3D('',#180772,#180773,#180774); +#180772 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.2)); +#180773 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180774 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180775 = PCURVE('',#173846,#180776); +#180776 = DEFINITIONAL_REPRESENTATION('',(#180777),#180781); +#180777 = CIRCLE('',#180778,0.2); +#180778 = AXIS2_PLACEMENT_2D('',#180779,#180780); +#180779 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#180780 = DIRECTION('',(-1.,0.E+000)); +#180781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180782 = PCURVE('',#180599,#180783); +#180783 = DEFINITIONAL_REPRESENTATION('',(#180784),#180787); +#180784 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180785,#180786), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#178393 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#178394 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#178395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178396 = ORIENTED_EDGE('',*,*,#178397,.T.); -#178397 = EDGE_CURVE('',#178375,#178398,#178400,.T.); -#178398 = VERTEX_POINT('',#178399); -#178399 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); -#178400 = SURFACE_CURVE('',#178401,(#178405,#178412),.PCURVE_S1.); -#178401 = LINE('',#178402,#178403); -#178402 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); -#178403 = VECTOR('',#178404,1.); -#178404 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#178405 = PCURVE('',#171454,#178406); -#178406 = DEFINITIONAL_REPRESENTATION('',(#178407),#178411); -#178407 = LINE('',#178408,#178409); -#178408 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#178409 = VECTOR('',#178410,1.); -#178410 = DIRECTION('',(-2.516879905005E-016,1.)); -#178411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178412 = PCURVE('',#178178,#178413); -#178413 = DEFINITIONAL_REPRESENTATION('',(#178414),#178418); -#178414 = LINE('',#178415,#178416); -#178415 = CARTESIAN_POINT('',(0.E+000,0.34)); -#178416 = VECTOR('',#178417,1.); -#178417 = DIRECTION('',(1.,0.E+000)); -#178418 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178419 = ORIENTED_EDGE('',*,*,#178420,.T.); -#178420 = EDGE_CURVE('',#178398,#178421,#178423,.T.); -#178421 = VERTEX_POINT('',#178422); -#178422 = CARTESIAN_POINT('',(-0.175,1.4,0.15)); -#178423 = SURFACE_CURVE('',#178424,(#178428,#178435),.PCURVE_S1.); -#178424 = LINE('',#178425,#178426); -#178425 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); -#178426 = VECTOR('',#178427,1.); -#178427 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178428 = PCURVE('',#171454,#178429); -#178429 = DEFINITIONAL_REPRESENTATION('',(#178430),#178434); -#178430 = LINE('',#178431,#178432); -#178431 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#178432 = VECTOR('',#178433,1.); -#178433 = DIRECTION('',(-1.,0.E+000)); -#178434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178435 = PCURVE('',#178150,#178436); -#178436 = DEFINITIONAL_REPRESENTATION('',(#178437),#178441); -#178437 = LINE('',#178438,#178439); -#178438 = CARTESIAN_POINT('',(0.E+000,0.34)); -#178439 = VECTOR('',#178440,1.); -#178440 = DIRECTION('',(1.,0.E+000)); -#178441 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178442 = ORIENTED_EDGE('',*,*,#178443,.T.); -#178443 = EDGE_CURVE('',#178421,#178444,#178446,.T.); -#178444 = VERTEX_POINT('',#178445); -#178445 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.15)); -#178446 = SURFACE_CURVE('',#178447,(#178451,#178458),.PCURVE_S1.); -#178447 = LINE('',#178448,#178449); -#178448 = CARTESIAN_POINT('',(-0.175,1.4,0.15)); -#178449 = VECTOR('',#178450,1.); -#178450 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#178451 = PCURVE('',#171454,#178452); -#178452 = DEFINITIONAL_REPRESENTATION('',(#178453),#178457); -#178453 = LINE('',#178454,#178455); -#178454 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#178455 = VECTOR('',#178456,1.); -#178456 = DIRECTION('',(3.020255886006E-016,-1.)); -#178457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178458 = PCURVE('',#178122,#178459); -#178459 = DEFINITIONAL_REPRESENTATION('',(#178460),#178464); -#178460 = LINE('',#178461,#178462); -#178461 = CARTESIAN_POINT('',(0.E+000,0.34)); -#178462 = VECTOR('',#178463,1.); -#178463 = DIRECTION('',(1.,0.E+000)); -#178464 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178465 = ORIENTED_EDGE('',*,*,#178466,.T.); -#178466 = EDGE_CURVE('',#178444,#178467,#178469,.T.); -#178467 = VERTEX_POINT('',#178468); -#178468 = CARTESIAN_POINT('',(-0.175,1.080909188472,0.19623594148)); -#178469 = SURFACE_CURVE('',#178470,(#178475,#178486),.PCURVE_S1.); -#178470 = CIRCLE('',#178471,5.E-002); -#178471 = AXIS2_PLACEMENT_3D('',#178472,#178473,#178474); -#178472 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.2)); -#178473 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#178474 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178475 = PCURVE('',#171454,#178476); -#178476 = DEFINITIONAL_REPRESENTATION('',(#178477),#178485); -#178477 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#178478,#178479,#178480, - #178481,#178482,#178483,#178484),.UNSPECIFIED.,.T.,.F.) +#180785 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#180786 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#180787 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180788 = ORIENTED_EDGE('',*,*,#180789,.T.); +#180789 = EDGE_CURVE('',#180767,#180790,#180792,.T.); +#180790 = VERTEX_POINT('',#180791); +#180791 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); +#180792 = SURFACE_CURVE('',#180793,(#180797,#180804),.PCURVE_S1.); +#180793 = LINE('',#180794,#180795); +#180794 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); +#180795 = VECTOR('',#180796,1.); +#180796 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#180797 = PCURVE('',#173846,#180798); +#180798 = DEFINITIONAL_REPRESENTATION('',(#180799),#180803); +#180799 = LINE('',#180800,#180801); +#180800 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#180801 = VECTOR('',#180802,1.); +#180802 = DIRECTION('',(-2.516879905005E-016,1.)); +#180803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180804 = PCURVE('',#180570,#180805); +#180805 = DEFINITIONAL_REPRESENTATION('',(#180806),#180810); +#180806 = LINE('',#180807,#180808); +#180807 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180808 = VECTOR('',#180809,1.); +#180809 = DIRECTION('',(1.,0.E+000)); +#180810 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180811 = ORIENTED_EDGE('',*,*,#180812,.T.); +#180812 = EDGE_CURVE('',#180790,#180813,#180815,.T.); +#180813 = VERTEX_POINT('',#180814); +#180814 = CARTESIAN_POINT('',(-0.175,1.4,0.15)); +#180815 = SURFACE_CURVE('',#180816,(#180820,#180827),.PCURVE_S1.); +#180816 = LINE('',#180817,#180818); +#180817 = CARTESIAN_POINT('',(-0.175,1.4,2.052218427084E-016)); +#180818 = VECTOR('',#180819,1.); +#180819 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180820 = PCURVE('',#173846,#180821); +#180821 = DEFINITIONAL_REPRESENTATION('',(#180822),#180826); +#180822 = LINE('',#180823,#180824); +#180823 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#180824 = VECTOR('',#180825,1.); +#180825 = DIRECTION('',(-1.,0.E+000)); +#180826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180827 = PCURVE('',#180542,#180828); +#180828 = DEFINITIONAL_REPRESENTATION('',(#180829),#180833); +#180829 = LINE('',#180830,#180831); +#180830 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180831 = VECTOR('',#180832,1.); +#180832 = DIRECTION('',(1.,0.E+000)); +#180833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180834 = ORIENTED_EDGE('',*,*,#180835,.T.); +#180835 = EDGE_CURVE('',#180813,#180836,#180838,.T.); +#180836 = VERTEX_POINT('',#180837); +#180837 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.15)); +#180838 = SURFACE_CURVE('',#180839,(#180843,#180850),.PCURVE_S1.); +#180839 = LINE('',#180840,#180841); +#180840 = CARTESIAN_POINT('',(-0.175,1.4,0.15)); +#180841 = VECTOR('',#180842,1.); +#180842 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#180843 = PCURVE('',#173846,#180844); +#180844 = DEFINITIONAL_REPRESENTATION('',(#180845),#180849); +#180845 = LINE('',#180846,#180847); +#180846 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#180847 = VECTOR('',#180848,1.); +#180848 = DIRECTION('',(3.020255886006E-016,-1.)); +#180849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180850 = PCURVE('',#180514,#180851); +#180851 = DEFINITIONAL_REPRESENTATION('',(#180852),#180856); +#180852 = LINE('',#180853,#180854); +#180853 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180854 = VECTOR('',#180855,1.); +#180855 = DIRECTION('',(1.,0.E+000)); +#180856 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180857 = ORIENTED_EDGE('',*,*,#180858,.T.); +#180858 = EDGE_CURVE('',#180836,#180859,#180861,.T.); +#180859 = VERTEX_POINT('',#180860); +#180860 = CARTESIAN_POINT('',(-0.175,1.080909188472,0.19623594148)); +#180861 = SURFACE_CURVE('',#180862,(#180867,#180878),.PCURVE_S1.); +#180862 = CIRCLE('',#180863,5.E-002); +#180863 = AXIS2_PLACEMENT_3D('',#180864,#180865,#180866); +#180864 = CARTESIAN_POINT('',(-0.175,1.1307673058,0.2)); +#180865 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#180866 = DIRECTION('',(0.E+000,0.E+000,1.)); +#180867 = PCURVE('',#173846,#180868); +#180868 = DEFINITIONAL_REPRESENTATION('',(#180869),#180877); +#180869 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180870,#180871,#180872, + #180873,#180874,#180875,#180876),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#178478 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178479 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#178480 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#178481 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#178482 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#178483 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#178484 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178486 = PCURVE('',#178095,#178487); -#178487 = DEFINITIONAL_REPRESENTATION('',(#178488),#178491); -#178488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178489,#178490), +#180870 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#180871 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#180872 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#180873 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#180874 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#180875 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#180876 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#180877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180878 = PCURVE('',#180487,#180879); +#180879 = DEFINITIONAL_REPRESENTATION('',(#180880),#180883); +#180880 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180881,#180882), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#178489 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#178490 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#178491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178492 = ORIENTED_EDGE('',*,*,#178493,.T.); -#178493 = EDGE_CURVE('',#178467,#178494,#178496,.T.); -#178494 = VERTEX_POINT('',#178495); -#178495 = CARTESIAN_POINT('',(-0.175,1.056555553792,0.518820292599)); -#178496 = SURFACE_CURVE('',#178497,(#178501,#178508),.PCURVE_S1.); -#178497 = LINE('',#178498,#178499); -#178498 = CARTESIAN_POINT('',(-0.175,1.080909188472,0.19623594148)); -#178499 = VECTOR('',#178500,1.); -#178500 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#178501 = PCURVE('',#171454,#178502); -#178502 = DEFINITIONAL_REPRESENTATION('',(#178503),#178507); -#178503 = LINE('',#178504,#178505); -#178504 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#178505 = VECTOR('',#178506,1.); -#178506 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#178507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178508 = PCURVE('',#178062,#178509); -#178509 = DEFINITIONAL_REPRESENTATION('',(#178510),#178514); -#178510 = LINE('',#178511,#178512); -#178511 = CARTESIAN_POINT('',(0.E+000,0.34)); -#178512 = VECTOR('',#178513,1.); -#178513 = DIRECTION('',(1.,0.E+000)); -#178514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178515 = ORIENTED_EDGE('',*,*,#178516,.T.); -#178516 = EDGE_CURVE('',#178494,#178275,#178517,.T.); -#178517 = SURFACE_CURVE('',#178518,(#178523,#178530),.PCURVE_S1.); -#178518 = CIRCLE('',#178519,0.25); -#178519 = AXIS2_PLACEMENT_3D('',#178520,#178521,#178522); -#178520 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); -#178521 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178522 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178523 = PCURVE('',#171454,#178524); -#178524 = DEFINITIONAL_REPRESENTATION('',(#178525),#178529); -#178525 = CIRCLE('',#178526,0.25); -#178526 = AXIS2_PLACEMENT_2D('',#178527,#178528); -#178527 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178528 = DIRECTION('',(1.,0.E+000)); -#178529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178530 = PCURVE('',#178035,#178531); -#178531 = DEFINITIONAL_REPRESENTATION('',(#178532),#178535); -#178532 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178533,#178534), +#180881 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#180882 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#180883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180884 = ORIENTED_EDGE('',*,*,#180885,.T.); +#180885 = EDGE_CURVE('',#180859,#180886,#180888,.T.); +#180886 = VERTEX_POINT('',#180887); +#180887 = CARTESIAN_POINT('',(-0.175,1.056555553792,0.518820292599)); +#180888 = SURFACE_CURVE('',#180889,(#180893,#180900),.PCURVE_S1.); +#180889 = LINE('',#180890,#180891); +#180890 = CARTESIAN_POINT('',(-0.175,1.080909188472,0.19623594148)); +#180891 = VECTOR('',#180892,1.); +#180892 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#180893 = PCURVE('',#173846,#180894); +#180894 = DEFINITIONAL_REPRESENTATION('',(#180895),#180899); +#180895 = LINE('',#180896,#180897); +#180896 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#180897 = VECTOR('',#180898,1.); +#180898 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#180899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180900 = PCURVE('',#180454,#180901); +#180901 = DEFINITIONAL_REPRESENTATION('',(#180902),#180906); +#180902 = LINE('',#180903,#180904); +#180903 = CARTESIAN_POINT('',(0.E+000,0.34)); +#180904 = VECTOR('',#180905,1.); +#180905 = DIRECTION('',(1.,0.E+000)); +#180906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180907 = ORIENTED_EDGE('',*,*,#180908,.T.); +#180908 = EDGE_CURVE('',#180886,#180667,#180909,.T.); +#180909 = SURFACE_CURVE('',#180910,(#180915,#180922),.PCURVE_S1.); +#180910 = CIRCLE('',#180911,0.25); +#180911 = AXIS2_PLACEMENT_3D('',#180912,#180913,#180914); +#180912 = CARTESIAN_POINT('',(-0.175,0.807264967154,0.5)); +#180913 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180914 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#180915 = PCURVE('',#173846,#180916); +#180916 = DEFINITIONAL_REPRESENTATION('',(#180917),#180921); +#180917 = CIRCLE('',#180918,0.25); +#180918 = AXIS2_PLACEMENT_2D('',#180919,#180920); +#180919 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180920 = DIRECTION('',(1.,0.E+000)); +#180921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180922 = PCURVE('',#180427,#180923); +#180923 = DEFINITIONAL_REPRESENTATION('',(#180924),#180927); +#180924 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180925,#180926), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#178533 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#178534 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#178535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#180925 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180926 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#180927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#178536 = ORIENTED_EDGE('',*,*,#178274,.T.); -#178537 = ADVANCED_FACE('',(#178538),#178035,.T.); -#178538 = FACE_BOUND('',#178539,.T.); -#178539 = EDGE_LOOP('',(#178540,#178541,#178561,#178562)); -#178540 = ORIENTED_EDGE('',*,*,#178516,.F.); -#178541 = ORIENTED_EDGE('',*,*,#178542,.F.); -#178542 = EDGE_CURVE('',#178019,#178494,#178543,.T.); -#178543 = SURFACE_CURVE('',#178544,(#178548,#178554),.PCURVE_S1.); -#178544 = LINE('',#178545,#178546); -#178545 = CARTESIAN_POINT('',(-0.515,1.056555553792,0.518820292599)); -#178546 = VECTOR('',#178547,1.); -#178547 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178548 = PCURVE('',#178035,#178549); -#178549 = DEFINITIONAL_REPRESENTATION('',(#178550),#178553); -#178550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178551,#178552), +#180928 = ORIENTED_EDGE('',*,*,#180666,.T.); +#180929 = ADVANCED_FACE('',(#180930),#180427,.T.); +#180930 = FACE_BOUND('',#180931,.T.); +#180931 = EDGE_LOOP('',(#180932,#180933,#180953,#180954)); +#180932 = ORIENTED_EDGE('',*,*,#180908,.F.); +#180933 = ORIENTED_EDGE('',*,*,#180934,.F.); +#180934 = EDGE_CURVE('',#180411,#180886,#180935,.T.); +#180935 = SURFACE_CURVE('',#180936,(#180940,#180946),.PCURVE_S1.); +#180936 = LINE('',#180937,#180938); +#180937 = CARTESIAN_POINT('',(-0.515,1.056555553792,0.518820292599)); +#180938 = VECTOR('',#180939,1.); +#180939 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180940 = PCURVE('',#180427,#180941); +#180941 = DEFINITIONAL_REPRESENTATION('',(#180942),#180945); +#180942 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180943,#180944), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178551 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#178552 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#178553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178554 = PCURVE('',#178062,#178555); -#178555 = DEFINITIONAL_REPRESENTATION('',(#178556),#178560); -#178556 = LINE('',#178557,#178558); -#178557 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#178558 = VECTOR('',#178559,1.); -#178559 = DIRECTION('',(0.E+000,1.)); -#178560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178561 = ORIENTED_EDGE('',*,*,#178018,.T.); -#178562 = ORIENTED_EDGE('',*,*,#178297,.T.); -#178563 = ADVANCED_FACE('',(#178564),#178062,.T.); -#178564 = FACE_BOUND('',#178565,.T.); -#178565 = EDGE_LOOP('',(#178566,#178567,#178587,#178588)); -#178566 = ORIENTED_EDGE('',*,*,#178493,.F.); -#178567 = ORIENTED_EDGE('',*,*,#178568,.F.); -#178568 = EDGE_CURVE('',#178047,#178467,#178569,.T.); -#178569 = SURFACE_CURVE('',#178570,(#178574,#178581),.PCURVE_S1.); -#178570 = LINE('',#178571,#178572); -#178571 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); -#178572 = VECTOR('',#178573,1.); -#178573 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178574 = PCURVE('',#178062,#178575); -#178575 = DEFINITIONAL_REPRESENTATION('',(#178576),#178580); -#178576 = LINE('',#178577,#178578); -#178577 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178578 = VECTOR('',#178579,1.); -#178579 = DIRECTION('',(0.E+000,1.)); -#178580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178581 = PCURVE('',#178095,#178582); -#178582 = DEFINITIONAL_REPRESENTATION('',(#178583),#178586); -#178583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178584,#178585), +#180943 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#180944 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#180945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180946 = PCURVE('',#180454,#180947); +#180947 = DEFINITIONAL_REPRESENTATION('',(#180948),#180952); +#180948 = LINE('',#180949,#180950); +#180949 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#180950 = VECTOR('',#180951,1.); +#180951 = DIRECTION('',(0.E+000,1.)); +#180952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180953 = ORIENTED_EDGE('',*,*,#180410,.T.); +#180954 = ORIENTED_EDGE('',*,*,#180689,.T.); +#180955 = ADVANCED_FACE('',(#180956),#180454,.T.); +#180956 = FACE_BOUND('',#180957,.T.); +#180957 = EDGE_LOOP('',(#180958,#180959,#180979,#180980)); +#180958 = ORIENTED_EDGE('',*,*,#180885,.F.); +#180959 = ORIENTED_EDGE('',*,*,#180960,.F.); +#180960 = EDGE_CURVE('',#180439,#180859,#180961,.T.); +#180961 = SURFACE_CURVE('',#180962,(#180966,#180973),.PCURVE_S1.); +#180962 = LINE('',#180963,#180964); +#180963 = CARTESIAN_POINT('',(-0.515,1.080909188472,0.19623594148)); +#180964 = VECTOR('',#180965,1.); +#180965 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180966 = PCURVE('',#180454,#180967); +#180967 = DEFINITIONAL_REPRESENTATION('',(#180968),#180972); +#180968 = LINE('',#180969,#180970); +#180969 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#180970 = VECTOR('',#180971,1.); +#180971 = DIRECTION('',(0.E+000,1.)); +#180972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180973 = PCURVE('',#180487,#180974); +#180974 = DEFINITIONAL_REPRESENTATION('',(#180975),#180978); +#180975 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180976,#180977), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178584 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#178585 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#178586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178587 = ORIENTED_EDGE('',*,*,#178046,.T.); -#178588 = ORIENTED_EDGE('',*,*,#178542,.T.); -#178589 = ADVANCED_FACE('',(#178590),#178095,.F.); -#178590 = FACE_BOUND('',#178591,.F.); -#178591 = EDGE_LOOP('',(#178592,#178593,#178594,#178595)); -#178592 = ORIENTED_EDGE('',*,*,#178466,.T.); -#178593 = ORIENTED_EDGE('',*,*,#178568,.F.); -#178594 = ORIENTED_EDGE('',*,*,#178074,.F.); -#178595 = ORIENTED_EDGE('',*,*,#178596,.T.); -#178596 = EDGE_CURVE('',#178075,#178444,#178597,.T.); -#178597 = SURFACE_CURVE('',#178598,(#178602,#178631),.PCURVE_S1.); -#178598 = LINE('',#178599,#178600); -#178599 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.15)); -#178600 = VECTOR('',#178601,1.); -#178601 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178602 = PCURVE('',#178095,#178603); -#178603 = DEFINITIONAL_REPRESENTATION('',(#178604),#178630); -#178604 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178605,#178606,#178607, - #178608,#178609,#178610,#178611,#178612,#178613,#178614,#178615, - #178616,#178617,#178618,#178619,#178620,#178621,#178622,#178623, - #178624,#178625,#178626,#178627,#178628,#178629),.UNSPECIFIED.,.F., +#180976 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#180977 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#180978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#180979 = ORIENTED_EDGE('',*,*,#180438,.T.); +#180980 = ORIENTED_EDGE('',*,*,#180934,.T.); +#180981 = ADVANCED_FACE('',(#180982),#180487,.F.); +#180982 = FACE_BOUND('',#180983,.F.); +#180983 = EDGE_LOOP('',(#180984,#180985,#180986,#180987)); +#180984 = ORIENTED_EDGE('',*,*,#180858,.T.); +#180985 = ORIENTED_EDGE('',*,*,#180960,.F.); +#180986 = ORIENTED_EDGE('',*,*,#180466,.F.); +#180987 = ORIENTED_EDGE('',*,*,#180988,.T.); +#180988 = EDGE_CURVE('',#180467,#180836,#180989,.T.); +#180989 = SURFACE_CURVE('',#180990,(#180994,#181023),.PCURVE_S1.); +#180990 = LINE('',#180991,#180992); +#180991 = CARTESIAN_POINT('',(-0.515,1.1307673058,0.15)); +#180992 = VECTOR('',#180993,1.); +#180993 = DIRECTION('',(1.,0.E+000,0.E+000)); +#180994 = PCURVE('',#180487,#180995); +#180995 = DEFINITIONAL_REPRESENTATION('',(#180996),#181022); +#180996 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#180997,#180998,#180999, + #181000,#181001,#181002,#181003,#181004,#181005,#181006,#181007, + #181008,#181009,#181010,#181011,#181012,#181013,#181014,#181015, + #181016,#181017,#181018,#181019,#181020,#181021),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -221231,131 +224233,131 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#178605 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#178606 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#178607 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#178608 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#178609 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#178610 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#178611 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#178612 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#178613 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#178614 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#178615 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#178616 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#178617 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#178618 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#178619 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#178620 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#178621 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#178622 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#178623 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#178624 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#178625 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#178626 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#178627 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#178628 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#178629 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#178630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178631 = PCURVE('',#178122,#178632); -#178632 = DEFINITIONAL_REPRESENTATION('',(#178633),#178637); -#178633 = LINE('',#178634,#178635); -#178634 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); -#178635 = VECTOR('',#178636,1.); -#178636 = DIRECTION('',(0.E+000,1.)); -#178637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178638 = ADVANCED_FACE('',(#178639),#178122,.T.); -#178639 = FACE_BOUND('',#178640,.T.); -#178640 = EDGE_LOOP('',(#178641,#178642,#178663,#178664)); -#178641 = ORIENTED_EDGE('',*,*,#178443,.F.); -#178642 = ORIENTED_EDGE('',*,*,#178643,.F.); -#178643 = EDGE_CURVE('',#178107,#178421,#178644,.T.); -#178644 = SURFACE_CURVE('',#178645,(#178649,#178656),.PCURVE_S1.); -#178645 = LINE('',#178646,#178647); -#178646 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); -#178647 = VECTOR('',#178648,1.); -#178648 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178649 = PCURVE('',#178122,#178650); -#178650 = DEFINITIONAL_REPRESENTATION('',(#178651),#178655); -#178651 = LINE('',#178652,#178653); -#178652 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178653 = VECTOR('',#178654,1.); -#178654 = DIRECTION('',(0.E+000,1.)); -#178655 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178656 = PCURVE('',#178150,#178657); -#178657 = DEFINITIONAL_REPRESENTATION('',(#178658),#178662); -#178658 = LINE('',#178659,#178660); -#178659 = CARTESIAN_POINT('',(0.15,0.E+000)); -#178660 = VECTOR('',#178661,1.); -#178661 = DIRECTION('',(0.E+000,1.)); -#178662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178663 = ORIENTED_EDGE('',*,*,#178106,.T.); -#178664 = ORIENTED_EDGE('',*,*,#178596,.T.); -#178665 = ADVANCED_FACE('',(#178666),#178150,.T.); -#178666 = FACE_BOUND('',#178667,.T.); -#178667 = EDGE_LOOP('',(#178668,#178669,#178690,#178691)); -#178668 = ORIENTED_EDGE('',*,*,#178420,.F.); -#178669 = ORIENTED_EDGE('',*,*,#178670,.F.); -#178670 = EDGE_CURVE('',#178135,#178398,#178671,.T.); -#178671 = SURFACE_CURVE('',#178672,(#178676,#178683),.PCURVE_S1.); -#178672 = LINE('',#178673,#178674); -#178673 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); -#178674 = VECTOR('',#178675,1.); -#178675 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178676 = PCURVE('',#178150,#178677); -#178677 = DEFINITIONAL_REPRESENTATION('',(#178678),#178682); -#178678 = LINE('',#178679,#178680); -#178679 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178680 = VECTOR('',#178681,1.); -#178681 = DIRECTION('',(0.E+000,1.)); -#178682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178683 = PCURVE('',#178178,#178684); -#178684 = DEFINITIONAL_REPRESENTATION('',(#178685),#178689); -#178685 = LINE('',#178686,#178687); -#178686 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178687 = VECTOR('',#178688,1.); -#178688 = DIRECTION('',(0.E+000,1.)); -#178689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178690 = ORIENTED_EDGE('',*,*,#178134,.T.); -#178691 = ORIENTED_EDGE('',*,*,#178643,.T.); -#178692 = ADVANCED_FACE('',(#178693),#178178,.T.); -#178693 = FACE_BOUND('',#178694,.T.); -#178694 = EDGE_LOOP('',(#178695,#178696,#178739,#178740)); -#178695 = ORIENTED_EDGE('',*,*,#178397,.F.); -#178696 = ORIENTED_EDGE('',*,*,#178697,.F.); -#178697 = EDGE_CURVE('',#178163,#178375,#178698,.T.); -#178698 = SURFACE_CURVE('',#178699,(#178703,#178710),.PCURVE_S1.); -#178699 = LINE('',#178700,#178701); -#178700 = CARTESIAN_POINT('',(-0.515,1.1307673058,1.374592069281E-016)); -#178701 = VECTOR('',#178702,1.); -#178702 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178703 = PCURVE('',#178178,#178704); -#178704 = DEFINITIONAL_REPRESENTATION('',(#178705),#178709); -#178705 = LINE('',#178706,#178707); -#178706 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); -#178707 = VECTOR('',#178708,1.); -#178708 = DIRECTION('',(0.E+000,1.)); -#178709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178710 = PCURVE('',#178207,#178711); -#178711 = DEFINITIONAL_REPRESENTATION('',(#178712),#178738); -#178712 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#178713,#178714,#178715, - #178716,#178717,#178718,#178719,#178720,#178721,#178722,#178723, - #178724,#178725,#178726,#178727,#178728,#178729,#178730,#178731, - #178732,#178733,#178734,#178735,#178736,#178737),.UNSPECIFIED.,.F., +#180997 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#180998 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#180999 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#181000 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#181001 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#181002 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#181003 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#181004 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#181005 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#181006 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#181007 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#181008 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#181009 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#181010 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#181011 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#181012 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#181013 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#181014 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#181015 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#181016 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#181017 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#181018 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#181019 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#181020 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#181021 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#181022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181023 = PCURVE('',#180514,#181024); +#181024 = DEFINITIONAL_REPRESENTATION('',(#181025),#181029); +#181025 = LINE('',#181026,#181027); +#181026 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); +#181027 = VECTOR('',#181028,1.); +#181028 = DIRECTION('',(0.E+000,1.)); +#181029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181030 = ADVANCED_FACE('',(#181031),#180514,.T.); +#181031 = FACE_BOUND('',#181032,.T.); +#181032 = EDGE_LOOP('',(#181033,#181034,#181055,#181056)); +#181033 = ORIENTED_EDGE('',*,*,#180835,.F.); +#181034 = ORIENTED_EDGE('',*,*,#181035,.F.); +#181035 = EDGE_CURVE('',#180499,#180813,#181036,.T.); +#181036 = SURFACE_CURVE('',#181037,(#181041,#181048),.PCURVE_S1.); +#181037 = LINE('',#181038,#181039); +#181038 = CARTESIAN_POINT('',(-0.515,1.4,0.15)); +#181039 = VECTOR('',#181040,1.); +#181040 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181041 = PCURVE('',#180514,#181042); +#181042 = DEFINITIONAL_REPRESENTATION('',(#181043),#181047); +#181043 = LINE('',#181044,#181045); +#181044 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181045 = VECTOR('',#181046,1.); +#181046 = DIRECTION('',(0.E+000,1.)); +#181047 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181048 = PCURVE('',#180542,#181049); +#181049 = DEFINITIONAL_REPRESENTATION('',(#181050),#181054); +#181050 = LINE('',#181051,#181052); +#181051 = CARTESIAN_POINT('',(0.15,0.E+000)); +#181052 = VECTOR('',#181053,1.); +#181053 = DIRECTION('',(0.E+000,1.)); +#181054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181055 = ORIENTED_EDGE('',*,*,#180498,.T.); +#181056 = ORIENTED_EDGE('',*,*,#180988,.T.); +#181057 = ADVANCED_FACE('',(#181058),#180542,.T.); +#181058 = FACE_BOUND('',#181059,.T.); +#181059 = EDGE_LOOP('',(#181060,#181061,#181082,#181083)); +#181060 = ORIENTED_EDGE('',*,*,#180812,.F.); +#181061 = ORIENTED_EDGE('',*,*,#181062,.F.); +#181062 = EDGE_CURVE('',#180527,#180790,#181063,.T.); +#181063 = SURFACE_CURVE('',#181064,(#181068,#181075),.PCURVE_S1.); +#181064 = LINE('',#181065,#181066); +#181065 = CARTESIAN_POINT('',(-0.515,1.4,2.052218427084E-016)); +#181066 = VECTOR('',#181067,1.); +#181067 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181068 = PCURVE('',#180542,#181069); +#181069 = DEFINITIONAL_REPRESENTATION('',(#181070),#181074); +#181070 = LINE('',#181071,#181072); +#181071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181072 = VECTOR('',#181073,1.); +#181073 = DIRECTION('',(0.E+000,1.)); +#181074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181075 = PCURVE('',#180570,#181076); +#181076 = DEFINITIONAL_REPRESENTATION('',(#181077),#181081); +#181077 = LINE('',#181078,#181079); +#181078 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181079 = VECTOR('',#181080,1.); +#181080 = DIRECTION('',(0.E+000,1.)); +#181081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181082 = ORIENTED_EDGE('',*,*,#180526,.T.); +#181083 = ORIENTED_EDGE('',*,*,#181035,.T.); +#181084 = ADVANCED_FACE('',(#181085),#180570,.T.); +#181085 = FACE_BOUND('',#181086,.T.); +#181086 = EDGE_LOOP('',(#181087,#181088,#181131,#181132)); +#181087 = ORIENTED_EDGE('',*,*,#180789,.F.); +#181088 = ORIENTED_EDGE('',*,*,#181089,.F.); +#181089 = EDGE_CURVE('',#180555,#180767,#181090,.T.); +#181090 = SURFACE_CURVE('',#181091,(#181095,#181102),.PCURVE_S1.); +#181091 = LINE('',#181092,#181093); +#181092 = CARTESIAN_POINT('',(-0.515,1.1307673058,1.374592069281E-016)); +#181093 = VECTOR('',#181094,1.); +#181094 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181095 = PCURVE('',#180570,#181096); +#181096 = DEFINITIONAL_REPRESENTATION('',(#181097),#181101); +#181097 = LINE('',#181098,#181099); +#181098 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); +#181099 = VECTOR('',#181100,1.); +#181100 = DIRECTION('',(0.E+000,1.)); +#181101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181102 = PCURVE('',#180599,#181103); +#181103 = DEFINITIONAL_REPRESENTATION('',(#181104),#181130); +#181104 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#181105,#181106,#181107, + #181108,#181109,#181110,#181111,#181112,#181113,#181114,#181115, + #181116,#181117,#181118,#181119,#181120,#181121,#181122,#181123, + #181124,#181125,#181126,#181127,#181128,#181129),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -221363,949 +224365,949 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#178713 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#178714 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#178715 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#178716 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#178717 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#178718 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#178719 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#178720 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#178721 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#178722 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#178723 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#178724 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#178725 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#178726 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#178727 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#178728 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#178729 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#178730 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#178731 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#178732 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#178733 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#178734 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#178735 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#178736 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#178737 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#178738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178739 = ORIENTED_EDGE('',*,*,#178162,.T.); -#178740 = ORIENTED_EDGE('',*,*,#178670,.T.); -#178741 = ADVANCED_FACE('',(#178742),#178207,.T.); -#178742 = FACE_BOUND('',#178743,.T.); -#178743 = EDGE_LOOP('',(#178744,#178745,#178765,#178766)); -#178744 = ORIENTED_EDGE('',*,*,#178374,.F.); -#178745 = ORIENTED_EDGE('',*,*,#178746,.F.); -#178746 = EDGE_CURVE('',#178191,#178352,#178747,.T.); -#178747 = SURFACE_CURVE('',#178748,(#178752,#178758),.PCURVE_S1.); -#178748 = LINE('',#178749,#178750); -#178749 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); -#178750 = VECTOR('',#178751,1.); -#178751 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178752 = PCURVE('',#178207,#178753); -#178753 = DEFINITIONAL_REPRESENTATION('',(#178754),#178757); -#178754 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178755,#178756), +#181105 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#181106 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#181107 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#181108 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#181109 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#181110 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#181111 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#181112 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#181113 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#181114 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#181115 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#181116 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#181117 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#181118 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#181119 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#181120 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#181121 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#181122 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#181123 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#181124 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#181125 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#181126 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#181127 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#181128 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#181129 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#181130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181131 = ORIENTED_EDGE('',*,*,#180554,.T.); +#181132 = ORIENTED_EDGE('',*,*,#181062,.T.); +#181133 = ADVANCED_FACE('',(#181134),#180599,.T.); +#181134 = FACE_BOUND('',#181135,.T.); +#181135 = EDGE_LOOP('',(#181136,#181137,#181157,#181158)); +#181136 = ORIENTED_EDGE('',*,*,#180766,.F.); +#181137 = ORIENTED_EDGE('',*,*,#181138,.F.); +#181138 = EDGE_CURVE('',#180583,#180744,#181139,.T.); +#181139 = SURFACE_CURVE('',#181140,(#181144,#181150),.PCURVE_S1.); +#181140 = LINE('',#181141,#181142); +#181141 = CARTESIAN_POINT('',(-0.515,0.931334836489,0.184943765921)); +#181142 = VECTOR('',#181143,1.); +#181143 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181144 = PCURVE('',#180599,#181145); +#181145 = DEFINITIONAL_REPRESENTATION('',(#181146),#181149); +#181146 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181147,#181148), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178755 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#178756 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#178757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178758 = PCURVE('',#178234,#178759); -#178759 = DEFINITIONAL_REPRESENTATION('',(#178760),#178764); -#178760 = LINE('',#178761,#178762); -#178761 = CARTESIAN_POINT('',(1.107072596433E-016,0.E+000)); -#178762 = VECTOR('',#178763,1.); -#178763 = DIRECTION('',(0.E+000,1.)); -#178764 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178765 = ORIENTED_EDGE('',*,*,#178190,.T.); -#178766 = ORIENTED_EDGE('',*,*,#178697,.T.); -#178767 = ADVANCED_FACE('',(#178768),#178234,.T.); -#178768 = FACE_BOUND('',#178769,.T.); -#178769 = EDGE_LOOP('',(#178770,#178771,#178791,#178792)); -#178770 = ORIENTED_EDGE('',*,*,#178351,.F.); -#178771 = ORIENTED_EDGE('',*,*,#178772,.F.); -#178772 = EDGE_CURVE('',#178219,#178325,#178773,.T.); -#178773 = SURFACE_CURVE('',#178774,(#178778,#178785),.PCURVE_S1.); -#178774 = LINE('',#178775,#178776); -#178775 = CARTESIAN_POINT('',(-0.515,0.906981201809,0.50752811704)); -#178776 = VECTOR('',#178777,1.); -#178777 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178778 = PCURVE('',#178234,#178779); -#178779 = DEFINITIONAL_REPRESENTATION('',(#178780),#178784); -#178780 = LINE('',#178781,#178782); -#178781 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#178782 = VECTOR('',#178783,1.); -#178783 = DIRECTION('',(0.E+000,1.)); -#178784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178785 = PCURVE('',#177958,#178786); -#178786 = DEFINITIONAL_REPRESENTATION('',(#178787),#178790); -#178787 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178788,#178789), +#181147 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#181148 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#181149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181150 = PCURVE('',#180626,#181151); +#181151 = DEFINITIONAL_REPRESENTATION('',(#181152),#181156); +#181152 = LINE('',#181153,#181154); +#181153 = CARTESIAN_POINT('',(1.107072596433E-016,0.E+000)); +#181154 = VECTOR('',#181155,1.); +#181155 = DIRECTION('',(0.E+000,1.)); +#181156 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181157 = ORIENTED_EDGE('',*,*,#180582,.T.); +#181158 = ORIENTED_EDGE('',*,*,#181089,.T.); +#181159 = ADVANCED_FACE('',(#181160),#180626,.T.); +#181160 = FACE_BOUND('',#181161,.T.); +#181161 = EDGE_LOOP('',(#181162,#181163,#181183,#181184)); +#181162 = ORIENTED_EDGE('',*,*,#180743,.F.); +#181163 = ORIENTED_EDGE('',*,*,#181164,.F.); +#181164 = EDGE_CURVE('',#180611,#180717,#181165,.T.); +#181165 = SURFACE_CURVE('',#181166,(#181170,#181177),.PCURVE_S1.); +#181166 = LINE('',#181167,#181168); +#181167 = CARTESIAN_POINT('',(-0.515,0.906981201809,0.50752811704)); +#181168 = VECTOR('',#181169,1.); +#181169 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181170 = PCURVE('',#180626,#181171); +#181171 = DEFINITIONAL_REPRESENTATION('',(#181172),#181176); +#181172 = LINE('',#181173,#181174); +#181173 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#181174 = VECTOR('',#181175,1.); +#181175 = DIRECTION('',(0.E+000,1.)); +#181176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181177 = PCURVE('',#180350,#181178); +#181178 = DEFINITIONAL_REPRESENTATION('',(#181179),#181182); +#181179 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181180,#181181), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178788 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#178789 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#178790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178791 = ORIENTED_EDGE('',*,*,#178218,.T.); -#178792 = ORIENTED_EDGE('',*,*,#178746,.T.); -#178793 = ADVANCED_FACE('',(#178794),#177958,.F.); -#178794 = FACE_BOUND('',#178795,.F.); -#178795 = EDGE_LOOP('',(#178796,#178797,#178798,#178799)); -#178796 = ORIENTED_EDGE('',*,*,#178324,.T.); -#178797 = ORIENTED_EDGE('',*,*,#178772,.F.); -#178798 = ORIENTED_EDGE('',*,*,#178246,.F.); -#178799 = ORIENTED_EDGE('',*,*,#177942,.T.); -#178800 = ADVANCED_FACE('',(#178801),#172413,.T.); -#178801 = FACE_BOUND('',#178802,.T.); -#178802 = EDGE_LOOP('',(#178803,#178804,#178827,#178854)); -#178803 = ORIENTED_EDGE('',*,*,#172399,.T.); -#178804 = ORIENTED_EDGE('',*,*,#178805,.T.); -#178805 = EDGE_CURVE('',#171029,#178806,#178808,.T.); -#178806 = VERTEX_POINT('',#178807); -#178807 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.6)); -#178808 = SURFACE_CURVE('',#178809,(#178813,#178820),.PCURVE_S1.); -#178809 = LINE('',#178810,#178811); -#178810 = CARTESIAN_POINT('',(-1.165,0.7,0.6)); -#178811 = VECTOR('',#178812,1.); -#178812 = DIRECTION('',(0.E+000,1.,0.E+000)); -#178813 = PCURVE('',#172413,#178814); -#178814 = DEFINITIONAL_REPRESENTATION('',(#178815),#178819); -#178815 = LINE('',#178816,#178817); -#178816 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178817 = VECTOR('',#178818,1.); -#178818 = DIRECTION('',(0.E+000,1.)); -#178819 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178820 = PCURVE('',#171051,#178821); -#178821 = DEFINITIONAL_REPRESENTATION('',(#178822),#178826); -#178822 = LINE('',#178823,#178824); -#178823 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#178824 = VECTOR('',#178825,1.); -#178825 = DIRECTION('',(0.E+000,1.)); -#178826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178827 = ORIENTED_EDGE('',*,*,#178828,.T.); -#178828 = EDGE_CURVE('',#178806,#178829,#178831,.T.); -#178829 = VERTEX_POINT('',#178830); -#178830 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.6)); -#178831 = SURFACE_CURVE('',#178832,(#178836,#178843),.PCURVE_S1.); -#178832 = LINE('',#178833,#178834); -#178833 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.6)); -#178834 = VECTOR('',#178835,1.); -#178835 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178836 = PCURVE('',#172413,#178837); -#178837 = DEFINITIONAL_REPRESENTATION('',(#178838),#178842); -#178838 = LINE('',#178839,#178840); -#178839 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); -#178840 = VECTOR('',#178841,1.); -#178841 = DIRECTION('',(-1.,0.E+000)); -#178842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178843 = PCURVE('',#178844,#178849); -#178844 = CYLINDRICAL_SURFACE('',#178845,0.1); -#178845 = AXIS2_PLACEMENT_3D('',#178846,#178847,#178848); -#178846 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); -#178847 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178848 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178849 = DEFINITIONAL_REPRESENTATION('',(#178850),#178853); -#178850 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178851,#178852), +#181180 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#181181 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#181182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181183 = ORIENTED_EDGE('',*,*,#180610,.T.); +#181184 = ORIENTED_EDGE('',*,*,#181138,.T.); +#181185 = ADVANCED_FACE('',(#181186),#180350,.F.); +#181186 = FACE_BOUND('',#181187,.F.); +#181187 = EDGE_LOOP('',(#181188,#181189,#181190,#181191)); +#181188 = ORIENTED_EDGE('',*,*,#180716,.T.); +#181189 = ORIENTED_EDGE('',*,*,#181164,.F.); +#181190 = ORIENTED_EDGE('',*,*,#180638,.F.); +#181191 = ORIENTED_EDGE('',*,*,#180334,.T.); +#181192 = ADVANCED_FACE('',(#181193),#174805,.T.); +#181193 = FACE_BOUND('',#181194,.T.); +#181194 = EDGE_LOOP('',(#181195,#181196,#181219,#181246)); +#181195 = ORIENTED_EDGE('',*,*,#174791,.T.); +#181196 = ORIENTED_EDGE('',*,*,#181197,.T.); +#181197 = EDGE_CURVE('',#173421,#181198,#181200,.T.); +#181198 = VERTEX_POINT('',#181199); +#181199 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.6)); +#181200 = SURFACE_CURVE('',#181201,(#181205,#181212),.PCURVE_S1.); +#181201 = LINE('',#181202,#181203); +#181202 = CARTESIAN_POINT('',(-1.165,0.7,0.6)); +#181203 = VECTOR('',#181204,1.); +#181204 = DIRECTION('',(0.E+000,1.,0.E+000)); +#181205 = PCURVE('',#174805,#181206); +#181206 = DEFINITIONAL_REPRESENTATION('',(#181207),#181211); +#181207 = LINE('',#181208,#181209); +#181208 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181209 = VECTOR('',#181210,1.); +#181210 = DIRECTION('',(0.E+000,1.)); +#181211 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181212 = PCURVE('',#173443,#181213); +#181213 = DEFINITIONAL_REPRESENTATION('',(#181214),#181218); +#181214 = LINE('',#181215,#181216); +#181215 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#181216 = VECTOR('',#181217,1.); +#181217 = DIRECTION('',(0.E+000,1.)); +#181218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181219 = ORIENTED_EDGE('',*,*,#181220,.T.); +#181220 = EDGE_CURVE('',#181198,#181221,#181223,.T.); +#181221 = VERTEX_POINT('',#181222); +#181222 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.6)); +#181223 = SURFACE_CURVE('',#181224,(#181228,#181235),.PCURVE_S1.); +#181224 = LINE('',#181225,#181226); +#181225 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.6)); +#181226 = VECTOR('',#181227,1.); +#181227 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181228 = PCURVE('',#174805,#181229); +#181229 = DEFINITIONAL_REPRESENTATION('',(#181230),#181234); +#181230 = LINE('',#181231,#181232); +#181231 = CARTESIAN_POINT('',(0.E+000,0.107264967154)); +#181232 = VECTOR('',#181233,1.); +#181233 = DIRECTION('',(-1.,0.E+000)); +#181234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181235 = PCURVE('',#181236,#181241); +#181236 = CYLINDRICAL_SURFACE('',#181237,0.1); +#181237 = AXIS2_PLACEMENT_3D('',#181238,#181239,#181240); +#181238 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); +#181239 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181240 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181241 = DEFINITIONAL_REPRESENTATION('',(#181242),#181245); +#181242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181243,#181244), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#178851 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#178852 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#178853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178854 = ORIENTED_EDGE('',*,*,#178855,.F.); -#178855 = EDGE_CURVE('',#171523,#178829,#178856,.T.); -#178856 = SURFACE_CURVE('',#178857,(#178861,#178868),.PCURVE_S1.); -#178857 = LINE('',#178858,#178859); -#178858 = CARTESIAN_POINT('',(-0.825,0.7,0.6)); -#178859 = VECTOR('',#178860,1.); -#178860 = DIRECTION('',(0.E+000,1.,0.E+000)); -#178861 = PCURVE('',#172413,#178862); -#178862 = DEFINITIONAL_REPRESENTATION('',(#178863),#178867); -#178863 = LINE('',#178864,#178865); -#178864 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#178865 = VECTOR('',#178866,1.); -#178866 = DIRECTION('',(0.E+000,1.)); -#178867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178868 = PCURVE('',#171561,#178869); -#178869 = DEFINITIONAL_REPRESENTATION('',(#178870),#178874); -#178870 = LINE('',#178871,#178872); -#178871 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); -#178872 = VECTOR('',#178873,1.); -#178873 = DIRECTION('',(0.E+000,1.)); -#178874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178875 = ADVANCED_FACE('',(#178876),#171051,.F.); -#178876 = FACE_BOUND('',#178877,.T.); -#178877 = EDGE_LOOP('',(#178878,#178879,#178880,#178903,#178931,#178959, - #178991,#179019,#179047,#179075,#179103,#179131)); -#178878 = ORIENTED_EDGE('',*,*,#178805,.F.); -#178879 = ORIENTED_EDGE('',*,*,#171028,.T.); -#178880 = ORIENTED_EDGE('',*,*,#178881,.F.); -#178881 = EDGE_CURVE('',#178882,#171031,#178884,.T.); -#178882 = VERTEX_POINT('',#178883); -#178883 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); -#178884 = SURFACE_CURVE('',#178885,(#178889,#178896),.PCURVE_S1.); -#178885 = LINE('',#178886,#178887); -#178886 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); -#178887 = VECTOR('',#178888,1.); -#178888 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#178889 = PCURVE('',#171051,#178890); -#178890 = DEFINITIONAL_REPRESENTATION('',(#178891),#178895); -#178891 = LINE('',#178892,#178893); -#178892 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#178893 = VECTOR('',#178894,1.); -#178894 = DIRECTION('',(0.E+000,-1.)); -#178895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178896 = PCURVE('',#171587,#178897); -#178897 = DEFINITIONAL_REPRESENTATION('',(#178898),#178902); -#178898 = LINE('',#178899,#178900); -#178899 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178900 = VECTOR('',#178901,1.); -#178901 = DIRECTION('',(0.E+000,-1.)); -#178902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178903 = ORIENTED_EDGE('',*,*,#178904,.F.); -#178904 = EDGE_CURVE('',#178905,#178882,#178907,.T.); -#178905 = VERTEX_POINT('',#178906); -#178906 = CARTESIAN_POINT('',(-1.165,1.056555553792,0.518820292599)); -#178907 = SURFACE_CURVE('',#178908,(#178913,#178920),.PCURVE_S1.); -#178908 = CIRCLE('',#178909,0.25); -#178909 = AXIS2_PLACEMENT_3D('',#178910,#178911,#178912); -#178910 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); -#178911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178913 = PCURVE('',#171051,#178914); -#178914 = DEFINITIONAL_REPRESENTATION('',(#178915),#178919); -#178915 = CIRCLE('',#178916,0.25); -#178916 = AXIS2_PLACEMENT_2D('',#178917,#178918); -#178917 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178918 = DIRECTION('',(1.,0.E+000)); -#178919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178920 = PCURVE('',#178921,#178926); -#178921 = CYLINDRICAL_SURFACE('',#178922,0.25); -#178922 = AXIS2_PLACEMENT_3D('',#178923,#178924,#178925); -#178923 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); -#178924 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178925 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178926 = DEFINITIONAL_REPRESENTATION('',(#178927),#178930); -#178927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178928,#178929), +#181243 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#181244 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#181245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181246 = ORIENTED_EDGE('',*,*,#181247,.F.); +#181247 = EDGE_CURVE('',#173915,#181221,#181248,.T.); +#181248 = SURFACE_CURVE('',#181249,(#181253,#181260),.PCURVE_S1.); +#181249 = LINE('',#181250,#181251); +#181250 = CARTESIAN_POINT('',(-0.825,0.7,0.6)); +#181251 = VECTOR('',#181252,1.); +#181252 = DIRECTION('',(0.E+000,1.,0.E+000)); +#181253 = PCURVE('',#174805,#181254); +#181254 = DEFINITIONAL_REPRESENTATION('',(#181255),#181259); +#181255 = LINE('',#181256,#181257); +#181256 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#181257 = VECTOR('',#181258,1.); +#181258 = DIRECTION('',(0.E+000,1.)); +#181259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181260 = PCURVE('',#173953,#181261); +#181261 = DEFINITIONAL_REPRESENTATION('',(#181262),#181266); +#181262 = LINE('',#181263,#181264); +#181263 = CARTESIAN_POINT('',(-0.1,-0.107264967154)); +#181264 = VECTOR('',#181265,1.); +#181265 = DIRECTION('',(0.E+000,1.)); +#181266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181267 = ADVANCED_FACE('',(#181268),#173443,.F.); +#181268 = FACE_BOUND('',#181269,.T.); +#181269 = EDGE_LOOP('',(#181270,#181271,#181272,#181295,#181323,#181351, + #181383,#181411,#181439,#181467,#181495,#181523)); +#181270 = ORIENTED_EDGE('',*,*,#181197,.F.); +#181271 = ORIENTED_EDGE('',*,*,#173420,.T.); +#181272 = ORIENTED_EDGE('',*,*,#181273,.F.); +#181273 = EDGE_CURVE('',#181274,#173423,#181276,.T.); +#181274 = VERTEX_POINT('',#181275); +#181275 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); +#181276 = SURFACE_CURVE('',#181277,(#181281,#181288),.PCURVE_S1.); +#181277 = LINE('',#181278,#181279); +#181278 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); +#181279 = VECTOR('',#181280,1.); +#181280 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#181281 = PCURVE('',#173443,#181282); +#181282 = DEFINITIONAL_REPRESENTATION('',(#181283),#181287); +#181283 = LINE('',#181284,#181285); +#181284 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#181285 = VECTOR('',#181286,1.); +#181286 = DIRECTION('',(0.E+000,-1.)); +#181287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181288 = PCURVE('',#173979,#181289); +#181289 = DEFINITIONAL_REPRESENTATION('',(#181290),#181294); +#181290 = LINE('',#181291,#181292); +#181291 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181292 = VECTOR('',#181293,1.); +#181293 = DIRECTION('',(0.E+000,-1.)); +#181294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181295 = ORIENTED_EDGE('',*,*,#181296,.F.); +#181296 = EDGE_CURVE('',#181297,#181274,#181299,.T.); +#181297 = VERTEX_POINT('',#181298); +#181298 = CARTESIAN_POINT('',(-1.165,1.056555553792,0.518820292599)); +#181299 = SURFACE_CURVE('',#181300,(#181305,#181312),.PCURVE_S1.); +#181300 = CIRCLE('',#181301,0.25); +#181301 = AXIS2_PLACEMENT_3D('',#181302,#181303,#181304); +#181302 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); +#181303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181305 = PCURVE('',#173443,#181306); +#181306 = DEFINITIONAL_REPRESENTATION('',(#181307),#181311); +#181307 = CIRCLE('',#181308,0.25); +#181308 = AXIS2_PLACEMENT_2D('',#181309,#181310); +#181309 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181310 = DIRECTION('',(1.,0.E+000)); +#181311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181312 = PCURVE('',#181313,#181318); +#181313 = CYLINDRICAL_SURFACE('',#181314,0.25); +#181314 = AXIS2_PLACEMENT_3D('',#181315,#181316,#181317); +#181315 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); +#181316 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181317 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181318 = DEFINITIONAL_REPRESENTATION('',(#181319),#181322); +#181319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181320,#181321), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#178928 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#178929 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#178930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178931 = ORIENTED_EDGE('',*,*,#178932,.F.); -#178932 = EDGE_CURVE('',#178933,#178905,#178935,.T.); -#178933 = VERTEX_POINT('',#178934); -#178934 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); -#178935 = SURFACE_CURVE('',#178936,(#178940,#178947),.PCURVE_S1.); -#178936 = LINE('',#178937,#178938); -#178937 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); -#178938 = VECTOR('',#178939,1.); -#178939 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#178940 = PCURVE('',#171051,#178941); -#178941 = DEFINITIONAL_REPRESENTATION('',(#178942),#178946); -#178942 = LINE('',#178943,#178944); -#178943 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#178944 = VECTOR('',#178945,1.); -#178945 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#178946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178947 = PCURVE('',#178948,#178953); -#178948 = PLANE('',#178949); -#178949 = AXIS2_PLACEMENT_3D('',#178950,#178951,#178952); -#178950 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); -#178951 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); -#178952 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#178953 = DEFINITIONAL_REPRESENTATION('',(#178954),#178958); -#178954 = LINE('',#178955,#178956); -#178955 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#178956 = VECTOR('',#178957,1.); -#178957 = DIRECTION('',(1.,0.E+000)); -#178958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178959 = ORIENTED_EDGE('',*,*,#178960,.F.); -#178960 = EDGE_CURVE('',#178961,#178933,#178963,.T.); -#178961 = VERTEX_POINT('',#178962); -#178962 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.15)); -#178963 = SURFACE_CURVE('',#178964,(#178969,#178980),.PCURVE_S1.); -#178964 = CIRCLE('',#178965,5.E-002); -#178965 = AXIS2_PLACEMENT_3D('',#178966,#178967,#178968); -#178966 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); -#178967 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#178968 = DIRECTION('',(0.E+000,0.E+000,1.)); -#178969 = PCURVE('',#171051,#178970); -#178970 = DEFINITIONAL_REPRESENTATION('',(#178971),#178979); -#178971 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#178972,#178973,#178974, - #178975,#178976,#178977,#178978),.UNSPECIFIED.,.T.,.F.) +#181320 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#181321 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#181322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181323 = ORIENTED_EDGE('',*,*,#181324,.F.); +#181324 = EDGE_CURVE('',#181325,#181297,#181327,.T.); +#181325 = VERTEX_POINT('',#181326); +#181326 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); +#181327 = SURFACE_CURVE('',#181328,(#181332,#181339),.PCURVE_S1.); +#181328 = LINE('',#181329,#181330); +#181329 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); +#181330 = VECTOR('',#181331,1.); +#181331 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#181332 = PCURVE('',#173443,#181333); +#181333 = DEFINITIONAL_REPRESENTATION('',(#181334),#181338); +#181334 = LINE('',#181335,#181336); +#181335 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#181336 = VECTOR('',#181337,1.); +#181337 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#181338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181339 = PCURVE('',#181340,#181345); +#181340 = PLANE('',#181341); +#181341 = AXIS2_PLACEMENT_3D('',#181342,#181343,#181344); +#181342 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); +#181343 = DIRECTION('',(0.E+000,0.997162346553,7.528117039715E-002)); +#181344 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#181345 = DEFINITIONAL_REPRESENTATION('',(#181346),#181350); +#181346 = LINE('',#181347,#181348); +#181347 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181348 = VECTOR('',#181349,1.); +#181349 = DIRECTION('',(1.,0.E+000)); +#181350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181351 = ORIENTED_EDGE('',*,*,#181352,.F.); +#181352 = EDGE_CURVE('',#181353,#181325,#181355,.T.); +#181353 = VERTEX_POINT('',#181354); +#181354 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.15)); +#181355 = SURFACE_CURVE('',#181356,(#181361,#181372),.PCURVE_S1.); +#181356 = CIRCLE('',#181357,5.E-002); +#181357 = AXIS2_PLACEMENT_3D('',#181358,#181359,#181360); +#181358 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); +#181359 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#181360 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181361 = PCURVE('',#173443,#181362); +#181362 = DEFINITIONAL_REPRESENTATION('',(#181363),#181371); +#181363 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181364,#181365,#181366, + #181367,#181368,#181369,#181370),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#178972 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178973 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#178974 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#178975 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#178976 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#178977 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#178978 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#178979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178980 = PCURVE('',#178981,#178986); -#178981 = CYLINDRICAL_SURFACE('',#178982,5.E-002); -#178982 = AXIS2_PLACEMENT_3D('',#178983,#178984,#178985); -#178983 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); -#178984 = DIRECTION('',(1.,0.E+000,0.E+000)); -#178985 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#178986 = DEFINITIONAL_REPRESENTATION('',(#178987),#178990); -#178987 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#178988,#178989), +#181364 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#181365 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#181366 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#181367 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#181368 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#181369 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#181370 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#181371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181372 = PCURVE('',#181373,#181378); +#181373 = CYLINDRICAL_SURFACE('',#181374,5.E-002); +#181374 = AXIS2_PLACEMENT_3D('',#181375,#181376,#181377); +#181375 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); +#181376 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181377 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181378 = DEFINITIONAL_REPRESENTATION('',(#181379),#181382); +#181379 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181380,#181381), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#178988 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#178989 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#178990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#178991 = ORIENTED_EDGE('',*,*,#178992,.F.); -#178992 = EDGE_CURVE('',#178993,#178961,#178995,.T.); -#178993 = VERTEX_POINT('',#178994); -#178994 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); -#178995 = SURFACE_CURVE('',#178996,(#179000,#179007),.PCURVE_S1.); -#178996 = LINE('',#178997,#178998); -#178997 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); -#178998 = VECTOR('',#178999,1.); -#178999 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#179000 = PCURVE('',#171051,#179001); -#179001 = DEFINITIONAL_REPRESENTATION('',(#179002),#179006); -#179002 = LINE('',#179003,#179004); -#179003 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#179004 = VECTOR('',#179005,1.); -#179005 = DIRECTION('',(3.020255886006E-016,-1.)); -#179006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179007 = PCURVE('',#179008,#179013); -#179008 = PLANE('',#179009); -#179009 = AXIS2_PLACEMENT_3D('',#179010,#179011,#179012); -#179010 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); -#179011 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); -#179012 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#179013 = DEFINITIONAL_REPRESENTATION('',(#179014),#179018); -#179014 = LINE('',#179015,#179016); -#179015 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179016 = VECTOR('',#179017,1.); -#179017 = DIRECTION('',(1.,0.E+000)); -#179018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179019 = ORIENTED_EDGE('',*,*,#179020,.F.); -#179020 = EDGE_CURVE('',#179021,#178993,#179023,.T.); -#179021 = VERTEX_POINT('',#179022); -#179022 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179023 = SURFACE_CURVE('',#179024,(#179028,#179035),.PCURVE_S1.); -#179024 = LINE('',#179025,#179026); -#179025 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179026 = VECTOR('',#179027,1.); -#179027 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179028 = PCURVE('',#171051,#179029); -#179029 = DEFINITIONAL_REPRESENTATION('',(#179030),#179034); -#179030 = LINE('',#179031,#179032); -#179031 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#179032 = VECTOR('',#179033,1.); -#179033 = DIRECTION('',(-1.,0.E+000)); -#179034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179035 = PCURVE('',#179036,#179041); -#179036 = PLANE('',#179037); -#179037 = AXIS2_PLACEMENT_3D('',#179038,#179039,#179040); -#179038 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179039 = DIRECTION('',(0.E+000,1.,0.E+000)); -#179040 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179041 = DEFINITIONAL_REPRESENTATION('',(#179042),#179046); -#179042 = LINE('',#179043,#179044); -#179043 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179044 = VECTOR('',#179045,1.); -#179045 = DIRECTION('',(1.,0.E+000)); -#179046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179047 = ORIENTED_EDGE('',*,*,#179048,.F.); -#179048 = EDGE_CURVE('',#179049,#179021,#179051,.T.); -#179049 = VERTEX_POINT('',#179050); -#179050 = CARTESIAN_POINT('',(-1.165,1.1307673058,7.066353883144E-017)); -#179051 = SURFACE_CURVE('',#179052,(#179056,#179063),.PCURVE_S1.); -#179052 = LINE('',#179053,#179054); -#179053 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179054 = VECTOR('',#179055,1.); -#179055 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#179056 = PCURVE('',#171051,#179057); -#179057 = DEFINITIONAL_REPRESENTATION('',(#179058),#179062); -#179058 = LINE('',#179059,#179060); -#179059 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#179060 = VECTOR('',#179061,1.); -#179061 = DIRECTION('',(-2.516879905005E-016,1.)); -#179062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179063 = PCURVE('',#179064,#179069); -#179064 = PLANE('',#179065); -#179065 = AXIS2_PLACEMENT_3D('',#179066,#179067,#179068); -#179066 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179067 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); -#179068 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#179069 = DEFINITIONAL_REPRESENTATION('',(#179070),#179074); -#179070 = LINE('',#179071,#179072); -#179071 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179072 = VECTOR('',#179073,1.); -#179073 = DIRECTION('',(1.,0.E+000)); -#179074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179075 = ORIENTED_EDGE('',*,*,#179076,.F.); -#179076 = EDGE_CURVE('',#179077,#179049,#179079,.T.); -#179077 = VERTEX_POINT('',#179078); -#179078 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); -#179079 = SURFACE_CURVE('',#179080,(#179085,#179092),.PCURVE_S1.); -#179080 = CIRCLE('',#179081,0.2); -#179081 = AXIS2_PLACEMENT_3D('',#179082,#179083,#179084); -#179082 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); -#179083 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179084 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179085 = PCURVE('',#171051,#179086); -#179086 = DEFINITIONAL_REPRESENTATION('',(#179087),#179091); -#179087 = CIRCLE('',#179088,0.2); -#179088 = AXIS2_PLACEMENT_2D('',#179089,#179090); -#179089 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#179090 = DIRECTION('',(-1.,0.E+000)); -#179091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179092 = PCURVE('',#179093,#179098); -#179093 = CYLINDRICAL_SURFACE('',#179094,0.2); -#179094 = AXIS2_PLACEMENT_3D('',#179095,#179096,#179097); -#179095 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); -#179096 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179097 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179098 = DEFINITIONAL_REPRESENTATION('',(#179099),#179102); -#179099 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179100,#179101), +#181380 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#181381 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#181382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181383 = ORIENTED_EDGE('',*,*,#181384,.F.); +#181384 = EDGE_CURVE('',#181385,#181353,#181387,.T.); +#181385 = VERTEX_POINT('',#181386); +#181386 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); +#181387 = SURFACE_CURVE('',#181388,(#181392,#181399),.PCURVE_S1.); +#181388 = LINE('',#181389,#181390); +#181389 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); +#181390 = VECTOR('',#181391,1.); +#181391 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#181392 = PCURVE('',#173443,#181393); +#181393 = DEFINITIONAL_REPRESENTATION('',(#181394),#181398); +#181394 = LINE('',#181395,#181396); +#181395 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#181396 = VECTOR('',#181397,1.); +#181397 = DIRECTION('',(3.020255886006E-016,-1.)); +#181398 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181399 = PCURVE('',#181400,#181405); +#181400 = PLANE('',#181401); +#181401 = AXIS2_PLACEMENT_3D('',#181402,#181403,#181404); +#181402 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); +#181403 = DIRECTION('',(0.E+000,-3.020255886006E-016,1.)); +#181404 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#181405 = DEFINITIONAL_REPRESENTATION('',(#181406),#181410); +#181406 = LINE('',#181407,#181408); +#181407 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181408 = VECTOR('',#181409,1.); +#181409 = DIRECTION('',(1.,0.E+000)); +#181410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181411 = ORIENTED_EDGE('',*,*,#181412,.F.); +#181412 = EDGE_CURVE('',#181413,#181385,#181415,.T.); +#181413 = VERTEX_POINT('',#181414); +#181414 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181415 = SURFACE_CURVE('',#181416,(#181420,#181427),.PCURVE_S1.); +#181416 = LINE('',#181417,#181418); +#181417 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181418 = VECTOR('',#181419,1.); +#181419 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181420 = PCURVE('',#173443,#181421); +#181421 = DEFINITIONAL_REPRESENTATION('',(#181422),#181426); +#181422 = LINE('',#181423,#181424); +#181423 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#181424 = VECTOR('',#181425,1.); +#181425 = DIRECTION('',(-1.,0.E+000)); +#181426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181427 = PCURVE('',#181428,#181433); +#181428 = PLANE('',#181429); +#181429 = AXIS2_PLACEMENT_3D('',#181430,#181431,#181432); +#181430 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181431 = DIRECTION('',(0.E+000,1.,0.E+000)); +#181432 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181433 = DEFINITIONAL_REPRESENTATION('',(#181434),#181438); +#181434 = LINE('',#181435,#181436); +#181435 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181436 = VECTOR('',#181437,1.); +#181437 = DIRECTION('',(1.,0.E+000)); +#181438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181439 = ORIENTED_EDGE('',*,*,#181440,.F.); +#181440 = EDGE_CURVE('',#181441,#181413,#181443,.T.); +#181441 = VERTEX_POINT('',#181442); +#181442 = CARTESIAN_POINT('',(-1.165,1.1307673058,7.066353883144E-017)); +#181443 = SURFACE_CURVE('',#181444,(#181448,#181455),.PCURVE_S1.); +#181444 = LINE('',#181445,#181446); +#181445 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181446 = VECTOR('',#181447,1.); +#181447 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#181448 = PCURVE('',#173443,#181449); +#181449 = DEFINITIONAL_REPRESENTATION('',(#181450),#181454); +#181450 = LINE('',#181451,#181452); +#181451 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#181452 = VECTOR('',#181453,1.); +#181453 = DIRECTION('',(-2.516879905005E-016,1.)); +#181454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181455 = PCURVE('',#181456,#181461); +#181456 = PLANE('',#181457); +#181457 = AXIS2_PLACEMENT_3D('',#181458,#181459,#181460); +#181458 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181459 = DIRECTION('',(0.E+000,2.516879905005E-016,-1.)); +#181460 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#181461 = DEFINITIONAL_REPRESENTATION('',(#181462),#181466); +#181462 = LINE('',#181463,#181464); +#181463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181464 = VECTOR('',#181465,1.); +#181465 = DIRECTION('',(1.,0.E+000)); +#181466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181467 = ORIENTED_EDGE('',*,*,#181468,.F.); +#181468 = EDGE_CURVE('',#181469,#181441,#181471,.T.); +#181469 = VERTEX_POINT('',#181470); +#181470 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); +#181471 = SURFACE_CURVE('',#181472,(#181477,#181484),.PCURVE_S1.); +#181472 = CIRCLE('',#181473,0.2); +#181473 = AXIS2_PLACEMENT_3D('',#181474,#181475,#181476); +#181474 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); +#181475 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181476 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181477 = PCURVE('',#173443,#181478); +#181478 = DEFINITIONAL_REPRESENTATION('',(#181479),#181483); +#181479 = CIRCLE('',#181480,0.2); +#181480 = AXIS2_PLACEMENT_2D('',#181481,#181482); +#181481 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#181482 = DIRECTION('',(-1.,0.E+000)); +#181483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181484 = PCURVE('',#181485,#181490); +#181485 = CYLINDRICAL_SURFACE('',#181486,0.2); +#181486 = AXIS2_PLACEMENT_3D('',#181487,#181488,#181489); +#181487 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.2)); +#181488 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181489 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181490 = DEFINITIONAL_REPRESENTATION('',(#181491),#181494); +#181491 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181492,#181493), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#179100 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#179101 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#179102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179103 = ORIENTED_EDGE('',*,*,#179104,.F.); -#179104 = EDGE_CURVE('',#179105,#179077,#179107,.T.); -#179105 = VERTEX_POINT('',#179106); -#179106 = CARTESIAN_POINT('',(-1.165,0.906981201809,0.50752811704)); -#179107 = SURFACE_CURVE('',#179108,(#179112,#179119),.PCURVE_S1.); -#179108 = LINE('',#179109,#179110); -#179109 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); -#179110 = VECTOR('',#179111,1.); -#179111 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#179112 = PCURVE('',#171051,#179113); -#179113 = DEFINITIONAL_REPRESENTATION('',(#179114),#179118); -#179114 = LINE('',#179115,#179116); -#179115 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#179116 = VECTOR('',#179117,1.); -#179117 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#179118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179119 = PCURVE('',#179120,#179125); -#179120 = PLANE('',#179121); -#179121 = AXIS2_PLACEMENT_3D('',#179122,#179123,#179124); -#179122 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); -#179123 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); -#179124 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#179125 = DEFINITIONAL_REPRESENTATION('',(#179126),#179130); -#179126 = LINE('',#179127,#179128); -#179127 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179128 = VECTOR('',#179129,1.); -#179129 = DIRECTION('',(1.,0.E+000)); -#179130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179131 = ORIENTED_EDGE('',*,*,#179132,.F.); -#179132 = EDGE_CURVE('',#178806,#179105,#179133,.T.); -#179133 = SURFACE_CURVE('',#179134,(#179139,#179150),.PCURVE_S1.); -#179134 = CIRCLE('',#179135,0.1); -#179135 = AXIS2_PLACEMENT_3D('',#179136,#179137,#179138); -#179136 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); -#179137 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179138 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179139 = PCURVE('',#171051,#179140); -#179140 = DEFINITIONAL_REPRESENTATION('',(#179141),#179149); -#179141 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179142,#179143,#179144, - #179145,#179146,#179147,#179148),.UNSPECIFIED.,.F.,.F.) +#181492 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#181493 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#181494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181495 = ORIENTED_EDGE('',*,*,#181496,.F.); +#181496 = EDGE_CURVE('',#181497,#181469,#181499,.T.); +#181497 = VERTEX_POINT('',#181498); +#181498 = CARTESIAN_POINT('',(-1.165,0.906981201809,0.50752811704)); +#181499 = SURFACE_CURVE('',#181500,(#181504,#181511),.PCURVE_S1.); +#181500 = LINE('',#181501,#181502); +#181501 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); +#181502 = VECTOR('',#181503,1.); +#181503 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#181504 = PCURVE('',#173443,#181505); +#181505 = DEFINITIONAL_REPRESENTATION('',(#181506),#181510); +#181506 = LINE('',#181507,#181508); +#181507 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#181508 = VECTOR('',#181509,1.); +#181509 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#181510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181511 = PCURVE('',#181512,#181517); +#181512 = PLANE('',#181513); +#181513 = AXIS2_PLACEMENT_3D('',#181514,#181515,#181516); +#181514 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); +#181515 = DIRECTION('',(0.E+000,-0.997162346553,-7.528117039715E-002)); +#181516 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#181517 = DEFINITIONAL_REPRESENTATION('',(#181518),#181522); +#181518 = LINE('',#181519,#181520); +#181519 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181520 = VECTOR('',#181521,1.); +#181521 = DIRECTION('',(1.,0.E+000)); +#181522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181523 = ORIENTED_EDGE('',*,*,#181524,.F.); +#181524 = EDGE_CURVE('',#181198,#181497,#181525,.T.); +#181525 = SURFACE_CURVE('',#181526,(#181531,#181542),.PCURVE_S1.); +#181526 = CIRCLE('',#181527,0.1); +#181527 = AXIS2_PLACEMENT_3D('',#181528,#181529,#181530); +#181528 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.5)); +#181529 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#181530 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181531 = PCURVE('',#173443,#181532); +#181532 = DEFINITIONAL_REPRESENTATION('',(#181533),#181541); +#181533 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181534,#181535,#181536, + #181537,#181538,#181539,#181540),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#179142 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#179143 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#179144 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#179145 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#179146 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#179147 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#179148 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#179149 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179150 = PCURVE('',#178844,#179151); -#179151 = DEFINITIONAL_REPRESENTATION('',(#179152),#179155); -#179152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179153,#179154), +#181534 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#181535 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#181536 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#181537 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#181538 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#181539 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#181540 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#181541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181542 = PCURVE('',#181236,#181543); +#181543 = DEFINITIONAL_REPRESENTATION('',(#181544),#181547); +#181544 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181545,#181546), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#179153 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#179154 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#179155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179156 = ADVANCED_FACE('',(#179157),#171587,.T.); -#179157 = FACE_BOUND('',#179158,.T.); -#179158 = EDGE_LOOP('',(#179159,#179182,#179202,#179203)); -#179159 = ORIENTED_EDGE('',*,*,#179160,.F.); -#179160 = EDGE_CURVE('',#179161,#171546,#179163,.T.); -#179161 = VERTEX_POINT('',#179162); -#179162 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.75)); -#179163 = SURFACE_CURVE('',#179164,(#179168,#179175),.PCURVE_S1.); -#179164 = LINE('',#179165,#179166); -#179165 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.75)); -#179166 = VECTOR('',#179167,1.); -#179167 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#179168 = PCURVE('',#171587,#179169); -#179169 = DEFINITIONAL_REPRESENTATION('',(#179170),#179174); -#179170 = LINE('',#179171,#179172); -#179171 = CARTESIAN_POINT('',(0.34,0.E+000)); -#179172 = VECTOR('',#179173,1.); -#179173 = DIRECTION('',(0.E+000,-1.)); -#179174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179175 = PCURVE('',#171561,#179176); -#179176 = DEFINITIONAL_REPRESENTATION('',(#179177),#179181); -#179177 = LINE('',#179178,#179179); -#179178 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); -#179179 = VECTOR('',#179180,1.); -#179180 = DIRECTION('',(0.E+000,-1.)); -#179181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179182 = ORIENTED_EDGE('',*,*,#179183,.F.); -#179183 = EDGE_CURVE('',#178882,#179161,#179184,.T.); -#179184 = SURFACE_CURVE('',#179185,(#179189,#179196),.PCURVE_S1.); -#179185 = LINE('',#179186,#179187); -#179186 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); -#179187 = VECTOR('',#179188,1.); -#179188 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179189 = PCURVE('',#171587,#179190); -#179190 = DEFINITIONAL_REPRESENTATION('',(#179191),#179195); -#179191 = LINE('',#179192,#179193); -#179192 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179193 = VECTOR('',#179194,1.); -#179194 = DIRECTION('',(1.,0.E+000)); -#179195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179196 = PCURVE('',#178921,#179197); -#179197 = DEFINITIONAL_REPRESENTATION('',(#179198),#179201); -#179198 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179199,#179200), +#181545 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#181546 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#181547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181548 = ADVANCED_FACE('',(#181549),#173979,.T.); +#181549 = FACE_BOUND('',#181550,.T.); +#181550 = EDGE_LOOP('',(#181551,#181574,#181594,#181595)); +#181551 = ORIENTED_EDGE('',*,*,#181552,.F.); +#181552 = EDGE_CURVE('',#181553,#173938,#181555,.T.); +#181553 = VERTEX_POINT('',#181554); +#181554 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.75)); +#181555 = SURFACE_CURVE('',#181556,(#181560,#181567),.PCURVE_S1.); +#181556 = LINE('',#181557,#181558); +#181557 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.75)); +#181558 = VECTOR('',#181559,1.); +#181559 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#181560 = PCURVE('',#173979,#181561); +#181561 = DEFINITIONAL_REPRESENTATION('',(#181562),#181566); +#181562 = LINE('',#181563,#181564); +#181563 = CARTESIAN_POINT('',(0.34,0.E+000)); +#181564 = VECTOR('',#181565,1.); +#181565 = DIRECTION('',(0.E+000,-1.)); +#181566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181567 = PCURVE('',#173953,#181568); +#181568 = DEFINITIONAL_REPRESENTATION('',(#181569),#181573); +#181569 = LINE('',#181570,#181571); +#181570 = CARTESIAN_POINT('',(-0.25,-1.665334536938E-015)); +#181571 = VECTOR('',#181572,1.); +#181572 = DIRECTION('',(0.E+000,-1.)); +#181573 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181574 = ORIENTED_EDGE('',*,*,#181575,.F.); +#181575 = EDGE_CURVE('',#181274,#181553,#181576,.T.); +#181576 = SURFACE_CURVE('',#181577,(#181581,#181588),.PCURVE_S1.); +#181577 = LINE('',#181578,#181579); +#181578 = CARTESIAN_POINT('',(-1.165,0.807264967154,0.75)); +#181579 = VECTOR('',#181580,1.); +#181580 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181581 = PCURVE('',#173979,#181582); +#181582 = DEFINITIONAL_REPRESENTATION('',(#181583),#181587); +#181583 = LINE('',#181584,#181585); +#181584 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181585 = VECTOR('',#181586,1.); +#181586 = DIRECTION('',(1.,0.E+000)); +#181587 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181588 = PCURVE('',#181313,#181589); +#181589 = DEFINITIONAL_REPRESENTATION('',(#181590),#181593); +#181590 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181591,#181592), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179199 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#179200 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#179201 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179202 = ORIENTED_EDGE('',*,*,#178881,.T.); -#179203 = ORIENTED_EDGE('',*,*,#171573,.F.); -#179204 = ADVANCED_FACE('',(#179205),#171561,.T.); -#179205 = FACE_BOUND('',#179206,.T.); -#179206 = EDGE_LOOP('',(#179207,#179208,#179209,#179236,#179259,#179282, - #179305,#179328,#179351,#179378,#179401,#179422)); -#179207 = ORIENTED_EDGE('',*,*,#171545,.F.); -#179208 = ORIENTED_EDGE('',*,*,#178855,.T.); -#179209 = ORIENTED_EDGE('',*,*,#179210,.T.); -#179210 = EDGE_CURVE('',#178829,#179211,#179213,.T.); -#179211 = VERTEX_POINT('',#179212); -#179212 = CARTESIAN_POINT('',(-0.825,0.906981201809,0.50752811704)); -#179213 = SURFACE_CURVE('',#179214,(#179219,#179230),.PCURVE_S1.); -#179214 = CIRCLE('',#179215,0.1); -#179215 = AXIS2_PLACEMENT_3D('',#179216,#179217,#179218); -#179216 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); -#179217 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179218 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179219 = PCURVE('',#171561,#179220); -#179220 = DEFINITIONAL_REPRESENTATION('',(#179221),#179229); -#179221 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179222,#179223,#179224, - #179225,#179226,#179227,#179228),.UNSPECIFIED.,.F.,.F.) +#181591 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#181592 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#181593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181594 = ORIENTED_EDGE('',*,*,#181273,.T.); +#181595 = ORIENTED_EDGE('',*,*,#173965,.F.); +#181596 = ADVANCED_FACE('',(#181597),#173953,.T.); +#181597 = FACE_BOUND('',#181598,.T.); +#181598 = EDGE_LOOP('',(#181599,#181600,#181601,#181628,#181651,#181674, + #181697,#181720,#181743,#181770,#181793,#181814)); +#181599 = ORIENTED_EDGE('',*,*,#173937,.F.); +#181600 = ORIENTED_EDGE('',*,*,#181247,.T.); +#181601 = ORIENTED_EDGE('',*,*,#181602,.T.); +#181602 = EDGE_CURVE('',#181221,#181603,#181605,.T.); +#181603 = VERTEX_POINT('',#181604); +#181604 = CARTESIAN_POINT('',(-0.825,0.906981201809,0.50752811704)); +#181605 = SURFACE_CURVE('',#181606,(#181611,#181622),.PCURVE_S1.); +#181606 = CIRCLE('',#181607,0.1); +#181607 = AXIS2_PLACEMENT_3D('',#181608,#181609,#181610); +#181608 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); +#181609 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#181610 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181611 = PCURVE('',#173953,#181612); +#181612 = DEFINITIONAL_REPRESENTATION('',(#181613),#181621); +#181613 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181614,#181615,#181616, + #181617,#181618,#181619,#181620),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#179222 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#179223 = CARTESIAN_POINT('',(-0.1,0.173205080757)); -#179224 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#179225 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); -#179226 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#179227 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); -#179228 = CARTESIAN_POINT('',(-0.1,0.E+000)); -#179229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179230 = PCURVE('',#178844,#179231); -#179231 = DEFINITIONAL_REPRESENTATION('',(#179232),#179235); -#179232 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179233,#179234), +#181614 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#181615 = CARTESIAN_POINT('',(-0.1,0.173205080757)); +#181616 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#181617 = CARTESIAN_POINT('',(0.2,6.890104806145E-017)); +#181618 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#181619 = CARTESIAN_POINT('',(-1.E-001,-0.173205080757)); +#181620 = CARTESIAN_POINT('',(-0.1,0.E+000)); +#181621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181622 = PCURVE('',#181236,#181623); +#181623 = DEFINITIONAL_REPRESENTATION('',(#181624),#181627); +#181624 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181625,#181626), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#179233 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#179234 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#179235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179236 = ORIENTED_EDGE('',*,*,#179237,.T.); -#179237 = EDGE_CURVE('',#179211,#179238,#179240,.T.); -#179238 = VERTEX_POINT('',#179239); -#179239 = CARTESIAN_POINT('',(-0.825,0.931334836489,0.184943765921)); -#179240 = SURFACE_CURVE('',#179241,(#179245,#179252),.PCURVE_S1.); -#179241 = LINE('',#179242,#179243); -#179242 = CARTESIAN_POINT('',(-0.825,0.931334836489,0.184943765921)); -#179243 = VECTOR('',#179244,1.); -#179244 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); -#179245 = PCURVE('',#171561,#179246); -#179246 = DEFINITIONAL_REPRESENTATION('',(#179247),#179251); -#179247 = LINE('',#179248,#179249); -#179248 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); -#179249 = VECTOR('',#179250,1.); -#179250 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#179251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179252 = PCURVE('',#179120,#179253); -#179253 = DEFINITIONAL_REPRESENTATION('',(#179254),#179258); -#179254 = LINE('',#179255,#179256); -#179255 = CARTESIAN_POINT('',(0.E+000,0.34)); -#179256 = VECTOR('',#179257,1.); -#179257 = DIRECTION('',(1.,0.E+000)); -#179258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179259 = ORIENTED_EDGE('',*,*,#179260,.T.); -#179260 = EDGE_CURVE('',#179238,#179261,#179263,.T.); -#179261 = VERTEX_POINT('',#179262); -#179262 = CARTESIAN_POINT('',(-0.825,1.1307673058,7.066353883144E-017)); -#179263 = SURFACE_CURVE('',#179264,(#179269,#179276),.PCURVE_S1.); -#179264 = CIRCLE('',#179265,0.2); -#179265 = AXIS2_PLACEMENT_3D('',#179266,#179267,#179268); -#179266 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.2)); -#179267 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179268 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179269 = PCURVE('',#171561,#179270); -#179270 = DEFINITIONAL_REPRESENTATION('',(#179271),#179275); -#179271 = CIRCLE('',#179272,0.2); -#179272 = AXIS2_PLACEMENT_2D('',#179273,#179274); -#179273 = CARTESIAN_POINT('',(0.3,0.323502338645)); -#179274 = DIRECTION('',(-1.,0.E+000)); -#179275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179276 = PCURVE('',#179093,#179277); -#179277 = DEFINITIONAL_REPRESENTATION('',(#179278),#179281); -#179278 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179279,#179280), +#181625 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#181626 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#181627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181628 = ORIENTED_EDGE('',*,*,#181629,.T.); +#181629 = EDGE_CURVE('',#181603,#181630,#181632,.T.); +#181630 = VERTEX_POINT('',#181631); +#181631 = CARTESIAN_POINT('',(-0.825,0.931334836489,0.184943765921)); +#181632 = SURFACE_CURVE('',#181633,(#181637,#181644),.PCURVE_S1.); +#181633 = LINE('',#181634,#181635); +#181634 = CARTESIAN_POINT('',(-0.825,0.931334836489,0.184943765921)); +#181635 = VECTOR('',#181636,1.); +#181636 = DIRECTION('',(0.E+000,7.528117039715E-002,-0.997162346553)); +#181637 = PCURVE('',#173953,#181638); +#181638 = DEFINITIONAL_REPRESENTATION('',(#181639),#181643); +#181639 = LINE('',#181640,#181641); +#181640 = CARTESIAN_POINT('',(0.315056234079,0.124069869335)); +#181641 = VECTOR('',#181642,1.); +#181642 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#181643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181644 = PCURVE('',#181512,#181645); +#181645 = DEFINITIONAL_REPRESENTATION('',(#181646),#181650); +#181646 = LINE('',#181647,#181648); +#181647 = CARTESIAN_POINT('',(0.E+000,0.34)); +#181648 = VECTOR('',#181649,1.); +#181649 = DIRECTION('',(1.,0.E+000)); +#181650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181651 = ORIENTED_EDGE('',*,*,#181652,.T.); +#181652 = EDGE_CURVE('',#181630,#181653,#181655,.T.); +#181653 = VERTEX_POINT('',#181654); +#181654 = CARTESIAN_POINT('',(-0.825,1.1307673058,7.066353883144E-017)); +#181655 = SURFACE_CURVE('',#181656,(#181661,#181668),.PCURVE_S1.); +#181656 = CIRCLE('',#181657,0.2); +#181657 = AXIS2_PLACEMENT_3D('',#181658,#181659,#181660); +#181658 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.2)); +#181659 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181660 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181661 = PCURVE('',#173953,#181662); +#181662 = DEFINITIONAL_REPRESENTATION('',(#181663),#181667); +#181663 = CIRCLE('',#181664,0.2); +#181664 = AXIS2_PLACEMENT_2D('',#181665,#181666); +#181665 = CARTESIAN_POINT('',(0.3,0.323502338645)); +#181666 = DIRECTION('',(-1.,0.E+000)); +#181667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181668 = PCURVE('',#181485,#181669); +#181669 = DEFINITIONAL_REPRESENTATION('',(#181670),#181673); +#181670 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181671,#181672), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#179279 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#179280 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#179281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179282 = ORIENTED_EDGE('',*,*,#179283,.T.); -#179283 = EDGE_CURVE('',#179261,#179284,#179286,.T.); -#179284 = VERTEX_POINT('',#179285); -#179285 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); -#179286 = SURFACE_CURVE('',#179287,(#179291,#179298),.PCURVE_S1.); -#179287 = LINE('',#179288,#179289); -#179288 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); -#179289 = VECTOR('',#179290,1.); -#179290 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); -#179291 = PCURVE('',#171561,#179292); -#179292 = DEFINITIONAL_REPRESENTATION('',(#179293),#179297); -#179293 = LINE('',#179294,#179295); -#179294 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#179295 = VECTOR('',#179296,1.); -#179296 = DIRECTION('',(-2.516879905005E-016,1.)); -#179297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179298 = PCURVE('',#179064,#179299); -#179299 = DEFINITIONAL_REPRESENTATION('',(#179300),#179304); -#179300 = LINE('',#179301,#179302); -#179301 = CARTESIAN_POINT('',(0.E+000,0.34)); -#179302 = VECTOR('',#179303,1.); -#179303 = DIRECTION('',(1.,0.E+000)); -#179304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179305 = ORIENTED_EDGE('',*,*,#179306,.T.); -#179306 = EDGE_CURVE('',#179284,#179307,#179309,.T.); -#179307 = VERTEX_POINT('',#179308); -#179308 = CARTESIAN_POINT('',(-0.825,1.4,0.15)); -#179309 = SURFACE_CURVE('',#179310,(#179314,#179321),.PCURVE_S1.); -#179310 = LINE('',#179311,#179312); -#179311 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); -#179312 = VECTOR('',#179313,1.); -#179313 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179314 = PCURVE('',#171561,#179315); -#179315 = DEFINITIONAL_REPRESENTATION('',(#179316),#179320); -#179316 = LINE('',#179317,#179318); -#179317 = CARTESIAN_POINT('',(0.5,0.592735032846)); -#179318 = VECTOR('',#179319,1.); -#179319 = DIRECTION('',(-1.,0.E+000)); -#179320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179321 = PCURVE('',#179036,#179322); -#179322 = DEFINITIONAL_REPRESENTATION('',(#179323),#179327); -#179323 = LINE('',#179324,#179325); -#179324 = CARTESIAN_POINT('',(0.E+000,0.34)); -#179325 = VECTOR('',#179326,1.); -#179326 = DIRECTION('',(1.,0.E+000)); -#179327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179328 = ORIENTED_EDGE('',*,*,#179329,.T.); -#179329 = EDGE_CURVE('',#179307,#179330,#179332,.T.); -#179330 = VERTEX_POINT('',#179331); -#179331 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.15)); -#179332 = SURFACE_CURVE('',#179333,(#179337,#179344),.PCURVE_S1.); -#179333 = LINE('',#179334,#179335); -#179334 = CARTESIAN_POINT('',(-0.825,1.4,0.15)); -#179335 = VECTOR('',#179336,1.); -#179336 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); -#179337 = PCURVE('',#171561,#179338); -#179338 = DEFINITIONAL_REPRESENTATION('',(#179339),#179343); -#179339 = LINE('',#179340,#179341); -#179340 = CARTESIAN_POINT('',(0.35,0.592735032846)); -#179341 = VECTOR('',#179342,1.); -#179342 = DIRECTION('',(3.020255886006E-016,-1.)); -#179343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179344 = PCURVE('',#179008,#179345); -#179345 = DEFINITIONAL_REPRESENTATION('',(#179346),#179350); -#179346 = LINE('',#179347,#179348); -#179347 = CARTESIAN_POINT('',(0.E+000,0.34)); -#179348 = VECTOR('',#179349,1.); -#179349 = DIRECTION('',(1.,0.E+000)); -#179350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179351 = ORIENTED_EDGE('',*,*,#179352,.T.); -#179352 = EDGE_CURVE('',#179330,#179353,#179355,.T.); -#179353 = VERTEX_POINT('',#179354); -#179354 = CARTESIAN_POINT('',(-0.825,1.080909188472,0.19623594148)); -#179355 = SURFACE_CURVE('',#179356,(#179361,#179372),.PCURVE_S1.); -#179356 = CIRCLE('',#179357,5.E-002); -#179357 = AXIS2_PLACEMENT_3D('',#179358,#179359,#179360); -#179358 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.2)); -#179359 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179360 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179361 = PCURVE('',#171561,#179362); -#179362 = DEFINITIONAL_REPRESENTATION('',(#179363),#179371); -#179363 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179364,#179365,#179366, - #179367,#179368,#179369,#179370),.UNSPECIFIED.,.T.,.F.) +#181671 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#181672 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#181673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181674 = ORIENTED_EDGE('',*,*,#181675,.T.); +#181675 = EDGE_CURVE('',#181653,#181676,#181678,.T.); +#181676 = VERTEX_POINT('',#181677); +#181677 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); +#181678 = SURFACE_CURVE('',#181679,(#181683,#181690),.PCURVE_S1.); +#181679 = LINE('',#181680,#181681); +#181680 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); +#181681 = VECTOR('',#181682,1.); +#181682 = DIRECTION('',(0.E+000,1.,2.516879905005E-016)); +#181683 = PCURVE('',#173953,#181684); +#181684 = DEFINITIONAL_REPRESENTATION('',(#181685),#181689); +#181685 = LINE('',#181686,#181687); +#181686 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#181687 = VECTOR('',#181688,1.); +#181688 = DIRECTION('',(-2.516879905005E-016,1.)); +#181689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181690 = PCURVE('',#181456,#181691); +#181691 = DEFINITIONAL_REPRESENTATION('',(#181692),#181696); +#181692 = LINE('',#181693,#181694); +#181693 = CARTESIAN_POINT('',(0.E+000,0.34)); +#181694 = VECTOR('',#181695,1.); +#181695 = DIRECTION('',(1.,0.E+000)); +#181696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181697 = ORIENTED_EDGE('',*,*,#181698,.T.); +#181698 = EDGE_CURVE('',#181676,#181699,#181701,.T.); +#181699 = VERTEX_POINT('',#181700); +#181700 = CARTESIAN_POINT('',(-0.825,1.4,0.15)); +#181701 = SURFACE_CURVE('',#181702,(#181706,#181713),.PCURVE_S1.); +#181702 = LINE('',#181703,#181704); +#181703 = CARTESIAN_POINT('',(-0.825,1.4,1.384261746118E-016)); +#181704 = VECTOR('',#181705,1.); +#181705 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181706 = PCURVE('',#173953,#181707); +#181707 = DEFINITIONAL_REPRESENTATION('',(#181708),#181712); +#181708 = LINE('',#181709,#181710); +#181709 = CARTESIAN_POINT('',(0.5,0.592735032846)); +#181710 = VECTOR('',#181711,1.); +#181711 = DIRECTION('',(-1.,0.E+000)); +#181712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181713 = PCURVE('',#181428,#181714); +#181714 = DEFINITIONAL_REPRESENTATION('',(#181715),#181719); +#181715 = LINE('',#181716,#181717); +#181716 = CARTESIAN_POINT('',(0.E+000,0.34)); +#181717 = VECTOR('',#181718,1.); +#181718 = DIRECTION('',(1.,0.E+000)); +#181719 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181720 = ORIENTED_EDGE('',*,*,#181721,.T.); +#181721 = EDGE_CURVE('',#181699,#181722,#181724,.T.); +#181722 = VERTEX_POINT('',#181723); +#181723 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.15)); +#181724 = SURFACE_CURVE('',#181725,(#181729,#181736),.PCURVE_S1.); +#181725 = LINE('',#181726,#181727); +#181726 = CARTESIAN_POINT('',(-0.825,1.4,0.15)); +#181727 = VECTOR('',#181728,1.); +#181728 = DIRECTION('',(0.E+000,-1.,-3.020255886006E-016)); +#181729 = PCURVE('',#173953,#181730); +#181730 = DEFINITIONAL_REPRESENTATION('',(#181731),#181735); +#181731 = LINE('',#181732,#181733); +#181732 = CARTESIAN_POINT('',(0.35,0.592735032846)); +#181733 = VECTOR('',#181734,1.); +#181734 = DIRECTION('',(3.020255886006E-016,-1.)); +#181735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181736 = PCURVE('',#181400,#181737); +#181737 = DEFINITIONAL_REPRESENTATION('',(#181738),#181742); +#181738 = LINE('',#181739,#181740); +#181739 = CARTESIAN_POINT('',(0.E+000,0.34)); +#181740 = VECTOR('',#181741,1.); +#181741 = DIRECTION('',(1.,0.E+000)); +#181742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181743 = ORIENTED_EDGE('',*,*,#181744,.T.); +#181744 = EDGE_CURVE('',#181722,#181745,#181747,.T.); +#181745 = VERTEX_POINT('',#181746); +#181746 = CARTESIAN_POINT('',(-0.825,1.080909188472,0.19623594148)); +#181747 = SURFACE_CURVE('',#181748,(#181753,#181764),.PCURVE_S1.); +#181748 = CIRCLE('',#181749,5.E-002); +#181749 = AXIS2_PLACEMENT_3D('',#181750,#181751,#181752); +#181750 = CARTESIAN_POINT('',(-0.825,1.1307673058,0.2)); +#181751 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#181752 = DIRECTION('',(0.E+000,0.E+000,1.)); +#181753 = PCURVE('',#173953,#181754); +#181754 = DEFINITIONAL_REPRESENTATION('',(#181755),#181763); +#181755 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181756,#181757,#181758, + #181759,#181760,#181761,#181762),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#179364 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#179365 = CARTESIAN_POINT('',(0.25,0.410104879024)); -#179366 = CARTESIAN_POINT('',(0.325,0.366803608835)); -#179367 = CARTESIAN_POINT('',(0.4,0.323502338645)); -#179368 = CARTESIAN_POINT('',(0.325,0.280201068456)); -#179369 = CARTESIAN_POINT('',(0.25,0.236899798267)); -#179370 = CARTESIAN_POINT('',(0.25,0.323502338645)); -#179371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179372 = PCURVE('',#178981,#179373); -#179373 = DEFINITIONAL_REPRESENTATION('',(#179374),#179377); -#179374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179375,#179376), +#181756 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#181757 = CARTESIAN_POINT('',(0.25,0.410104879024)); +#181758 = CARTESIAN_POINT('',(0.325,0.366803608835)); +#181759 = CARTESIAN_POINT('',(0.4,0.323502338645)); +#181760 = CARTESIAN_POINT('',(0.325,0.280201068456)); +#181761 = CARTESIAN_POINT('',(0.25,0.236899798267)); +#181762 = CARTESIAN_POINT('',(0.25,0.323502338645)); +#181763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181764 = PCURVE('',#181373,#181765); +#181765 = DEFINITIONAL_REPRESENTATION('',(#181766),#181769); +#181766 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181767,#181768), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.637036521774), .PIECEWISE_BEZIER_KNOTS.); -#179375 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#179376 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#179377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179378 = ORIENTED_EDGE('',*,*,#179379,.T.); -#179379 = EDGE_CURVE('',#179353,#179380,#179382,.T.); -#179380 = VERTEX_POINT('',#179381); -#179381 = CARTESIAN_POINT('',(-0.825,1.056555553792,0.518820292599)); -#179382 = SURFACE_CURVE('',#179383,(#179387,#179394),.PCURVE_S1.); -#179383 = LINE('',#179384,#179385); -#179384 = CARTESIAN_POINT('',(-0.825,1.080909188472,0.19623594148)); -#179385 = VECTOR('',#179386,1.); -#179386 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); -#179387 = PCURVE('',#171561,#179388); -#179388 = DEFINITIONAL_REPRESENTATION('',(#179389),#179393); -#179389 = LINE('',#179390,#179391); -#179390 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); -#179391 = VECTOR('',#179392,1.); -#179392 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#179393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179394 = PCURVE('',#178948,#179395); -#179395 = DEFINITIONAL_REPRESENTATION('',(#179396),#179400); -#179396 = LINE('',#179397,#179398); -#179397 = CARTESIAN_POINT('',(0.E+000,0.34)); -#179398 = VECTOR('',#179399,1.); -#179399 = DIRECTION('',(1.,0.E+000)); -#179400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179401 = ORIENTED_EDGE('',*,*,#179402,.T.); -#179402 = EDGE_CURVE('',#179380,#179161,#179403,.T.); -#179403 = SURFACE_CURVE('',#179404,(#179409,#179416),.PCURVE_S1.); -#179404 = CIRCLE('',#179405,0.25); -#179405 = AXIS2_PLACEMENT_3D('',#179406,#179407,#179408); -#179406 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); -#179407 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179408 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179409 = PCURVE('',#171561,#179410); -#179410 = DEFINITIONAL_REPRESENTATION('',(#179411),#179415); -#179411 = CIRCLE('',#179412,0.25); -#179412 = AXIS2_PLACEMENT_2D('',#179413,#179414); -#179413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179414 = DIRECTION('',(1.,0.E+000)); -#179415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179416 = PCURVE('',#178921,#179417); -#179417 = DEFINITIONAL_REPRESENTATION('',(#179418),#179421); -#179418 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179419,#179420), +#181767 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#181768 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#181769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181770 = ORIENTED_EDGE('',*,*,#181771,.T.); +#181771 = EDGE_CURVE('',#181745,#181772,#181774,.T.); +#181772 = VERTEX_POINT('',#181773); +#181773 = CARTESIAN_POINT('',(-0.825,1.056555553792,0.518820292599)); +#181774 = SURFACE_CURVE('',#181775,(#181779,#181786),.PCURVE_S1.); +#181775 = LINE('',#181776,#181777); +#181776 = CARTESIAN_POINT('',(-0.825,1.080909188472,0.19623594148)); +#181777 = VECTOR('',#181778,1.); +#181778 = DIRECTION('',(0.E+000,-7.528117039715E-002,0.997162346553)); +#181779 = PCURVE('',#173953,#181780); +#181780 = DEFINITIONAL_REPRESENTATION('',(#181781),#181785); +#181781 = LINE('',#181782,#181783); +#181782 = CARTESIAN_POINT('',(0.30376405852,0.273644221318)); +#181783 = VECTOR('',#181784,1.); +#181784 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#181785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181786 = PCURVE('',#181340,#181787); +#181787 = DEFINITIONAL_REPRESENTATION('',(#181788),#181792); +#181788 = LINE('',#181789,#181790); +#181789 = CARTESIAN_POINT('',(0.E+000,0.34)); +#181790 = VECTOR('',#181791,1.); +#181791 = DIRECTION('',(1.,0.E+000)); +#181792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181793 = ORIENTED_EDGE('',*,*,#181794,.T.); +#181794 = EDGE_CURVE('',#181772,#181553,#181795,.T.); +#181795 = SURFACE_CURVE('',#181796,(#181801,#181808),.PCURVE_S1.); +#181796 = CIRCLE('',#181797,0.25); +#181797 = AXIS2_PLACEMENT_3D('',#181798,#181799,#181800); +#181798 = CARTESIAN_POINT('',(-0.825,0.807264967154,0.5)); +#181799 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181800 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#181801 = PCURVE('',#173953,#181802); +#181802 = DEFINITIONAL_REPRESENTATION('',(#181803),#181807); +#181803 = CIRCLE('',#181804,0.25); +#181804 = AXIS2_PLACEMENT_2D('',#181805,#181806); +#181805 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181806 = DIRECTION('',(1.,0.E+000)); +#181807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181808 = PCURVE('',#181313,#181809); +#181809 = DEFINITIONAL_REPRESENTATION('',(#181810),#181813); +#181810 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181811,#181812), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#179419 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#179420 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#179421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179422 = ORIENTED_EDGE('',*,*,#179160,.T.); -#179423 = ADVANCED_FACE('',(#179424),#178921,.T.); -#179424 = FACE_BOUND('',#179425,.T.); -#179425 = EDGE_LOOP('',(#179426,#179427,#179447,#179448)); -#179426 = ORIENTED_EDGE('',*,*,#179402,.F.); -#179427 = ORIENTED_EDGE('',*,*,#179428,.F.); -#179428 = EDGE_CURVE('',#178905,#179380,#179429,.T.); -#179429 = SURFACE_CURVE('',#179430,(#179434,#179440),.PCURVE_S1.); -#179430 = LINE('',#179431,#179432); -#179431 = CARTESIAN_POINT('',(-1.165,1.056555553792,0.518820292599)); -#179432 = VECTOR('',#179433,1.); -#179433 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179434 = PCURVE('',#178921,#179435); -#179435 = DEFINITIONAL_REPRESENTATION('',(#179436),#179439); -#179436 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179437,#179438), +#181811 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#181812 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#181813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181814 = ORIENTED_EDGE('',*,*,#181552,.T.); +#181815 = ADVANCED_FACE('',(#181816),#181313,.T.); +#181816 = FACE_BOUND('',#181817,.T.); +#181817 = EDGE_LOOP('',(#181818,#181819,#181839,#181840)); +#181818 = ORIENTED_EDGE('',*,*,#181794,.F.); +#181819 = ORIENTED_EDGE('',*,*,#181820,.F.); +#181820 = EDGE_CURVE('',#181297,#181772,#181821,.T.); +#181821 = SURFACE_CURVE('',#181822,(#181826,#181832),.PCURVE_S1.); +#181822 = LINE('',#181823,#181824); +#181823 = CARTESIAN_POINT('',(-1.165,1.056555553792,0.518820292599)); +#181824 = VECTOR('',#181825,1.); +#181825 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181826 = PCURVE('',#181313,#181827); +#181827 = DEFINITIONAL_REPRESENTATION('',(#181828),#181831); +#181828 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181829,#181830), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179437 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#179438 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#179439 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#181829 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#181830 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#181831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#179440 = PCURVE('',#178948,#179441); -#179441 = DEFINITIONAL_REPRESENTATION('',(#179442),#179446); -#179442 = LINE('',#179443,#179444); -#179443 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#179444 = VECTOR('',#179445,1.); -#179445 = DIRECTION('',(0.E+000,1.)); -#179446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#181832 = PCURVE('',#181340,#181833); +#181833 = DEFINITIONAL_REPRESENTATION('',(#181834),#181838); +#181834 = LINE('',#181835,#181836); +#181835 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#181836 = VECTOR('',#181837,1.); +#181837 = DIRECTION('',(0.E+000,1.)); +#181838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#179447 = ORIENTED_EDGE('',*,*,#178904,.T.); -#179448 = ORIENTED_EDGE('',*,*,#179183,.T.); -#179449 = ADVANCED_FACE('',(#179450),#178948,.T.); -#179450 = FACE_BOUND('',#179451,.T.); -#179451 = EDGE_LOOP('',(#179452,#179453,#179473,#179474)); -#179452 = ORIENTED_EDGE('',*,*,#179379,.F.); -#179453 = ORIENTED_EDGE('',*,*,#179454,.F.); -#179454 = EDGE_CURVE('',#178933,#179353,#179455,.T.); -#179455 = SURFACE_CURVE('',#179456,(#179460,#179467),.PCURVE_S1.); -#179456 = LINE('',#179457,#179458); -#179457 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); -#179458 = VECTOR('',#179459,1.); -#179459 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179460 = PCURVE('',#178948,#179461); -#179461 = DEFINITIONAL_REPRESENTATION('',(#179462),#179466); -#179462 = LINE('',#179463,#179464); -#179463 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179464 = VECTOR('',#179465,1.); -#179465 = DIRECTION('',(0.E+000,1.)); -#179466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179467 = PCURVE('',#178981,#179468); -#179468 = DEFINITIONAL_REPRESENTATION('',(#179469),#179472); -#179469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179470,#179471), +#181839 = ORIENTED_EDGE('',*,*,#181296,.T.); +#181840 = ORIENTED_EDGE('',*,*,#181575,.T.); +#181841 = ADVANCED_FACE('',(#181842),#181340,.T.); +#181842 = FACE_BOUND('',#181843,.T.); +#181843 = EDGE_LOOP('',(#181844,#181845,#181865,#181866)); +#181844 = ORIENTED_EDGE('',*,*,#181771,.F.); +#181845 = ORIENTED_EDGE('',*,*,#181846,.F.); +#181846 = EDGE_CURVE('',#181325,#181745,#181847,.T.); +#181847 = SURFACE_CURVE('',#181848,(#181852,#181859),.PCURVE_S1.); +#181848 = LINE('',#181849,#181850); +#181849 = CARTESIAN_POINT('',(-1.165,1.080909188472,0.19623594148)); +#181850 = VECTOR('',#181851,1.); +#181851 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181852 = PCURVE('',#181340,#181853); +#181853 = DEFINITIONAL_REPRESENTATION('',(#181854),#181858); +#181854 = LINE('',#181855,#181856); +#181855 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181856 = VECTOR('',#181857,1.); +#181857 = DIRECTION('',(0.E+000,1.)); +#181858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181859 = PCURVE('',#181373,#181860); +#181860 = DEFINITIONAL_REPRESENTATION('',(#181861),#181864); +#181861 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181862,#181863), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179470 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#179471 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#179472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179473 = ORIENTED_EDGE('',*,*,#178932,.T.); -#179474 = ORIENTED_EDGE('',*,*,#179428,.T.); -#179475 = ADVANCED_FACE('',(#179476),#178981,.F.); -#179476 = FACE_BOUND('',#179477,.F.); -#179477 = EDGE_LOOP('',(#179478,#179479,#179480,#179481)); -#179478 = ORIENTED_EDGE('',*,*,#179352,.T.); -#179479 = ORIENTED_EDGE('',*,*,#179454,.F.); -#179480 = ORIENTED_EDGE('',*,*,#178960,.F.); -#179481 = ORIENTED_EDGE('',*,*,#179482,.T.); -#179482 = EDGE_CURVE('',#178961,#179330,#179483,.T.); -#179483 = SURFACE_CURVE('',#179484,(#179488,#179517),.PCURVE_S1.); -#179484 = LINE('',#179485,#179486); -#179485 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.15)); -#179486 = VECTOR('',#179487,1.); -#179487 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179488 = PCURVE('',#178981,#179489); -#179489 = DEFINITIONAL_REPRESENTATION('',(#179490),#179516); -#179490 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179491,#179492,#179493, - #179494,#179495,#179496,#179497,#179498,#179499,#179500,#179501, - #179502,#179503,#179504,#179505,#179506,#179507,#179508,#179509, - #179510,#179511,#179512,#179513,#179514,#179515),.UNSPECIFIED.,.F., +#181862 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#181863 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#181864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181865 = ORIENTED_EDGE('',*,*,#181324,.T.); +#181866 = ORIENTED_EDGE('',*,*,#181820,.T.); +#181867 = ADVANCED_FACE('',(#181868),#181373,.F.); +#181868 = FACE_BOUND('',#181869,.F.); +#181869 = EDGE_LOOP('',(#181870,#181871,#181872,#181873)); +#181870 = ORIENTED_EDGE('',*,*,#181744,.T.); +#181871 = ORIENTED_EDGE('',*,*,#181846,.F.); +#181872 = ORIENTED_EDGE('',*,*,#181352,.F.); +#181873 = ORIENTED_EDGE('',*,*,#181874,.T.); +#181874 = EDGE_CURVE('',#181353,#181722,#181875,.T.); +#181875 = SURFACE_CURVE('',#181876,(#181880,#181909),.PCURVE_S1.); +#181876 = LINE('',#181877,#181878); +#181877 = CARTESIAN_POINT('',(-1.165,1.1307673058,0.15)); +#181878 = VECTOR('',#181879,1.); +#181879 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181880 = PCURVE('',#181373,#181881); +#181881 = DEFINITIONAL_REPRESENTATION('',(#181882),#181908); +#181882 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#181883,#181884,#181885, + #181886,#181887,#181888,#181889,#181890,#181891,#181892,#181893, + #181894,#181895,#181896,#181897,#181898,#181899,#181900,#181901, + #181902,#181903,#181904,#181905,#181906,#181907),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -222313,131 +225315,131 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#179491 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#179492 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#179493 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#179494 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#179495 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#179496 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#179497 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#179498 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#179499 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#179500 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#179501 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#179502 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#179503 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#179504 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#179505 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#179506 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#179507 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#179508 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#179509 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#179510 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#179511 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#179512 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#179513 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#179514 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#179515 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#179516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179517 = PCURVE('',#179008,#179518); -#179518 = DEFINITIONAL_REPRESENTATION('',(#179519),#179523); -#179519 = LINE('',#179520,#179521); -#179520 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); -#179521 = VECTOR('',#179522,1.); -#179522 = DIRECTION('',(0.E+000,1.)); -#179523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179524 = ADVANCED_FACE('',(#179525),#179008,.T.); -#179525 = FACE_BOUND('',#179526,.T.); -#179526 = EDGE_LOOP('',(#179527,#179528,#179549,#179550)); -#179527 = ORIENTED_EDGE('',*,*,#179329,.F.); -#179528 = ORIENTED_EDGE('',*,*,#179529,.F.); -#179529 = EDGE_CURVE('',#178993,#179307,#179530,.T.); -#179530 = SURFACE_CURVE('',#179531,(#179535,#179542),.PCURVE_S1.); -#179531 = LINE('',#179532,#179533); -#179532 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); -#179533 = VECTOR('',#179534,1.); -#179534 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179535 = PCURVE('',#179008,#179536); -#179536 = DEFINITIONAL_REPRESENTATION('',(#179537),#179541); -#179537 = LINE('',#179538,#179539); -#179538 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179539 = VECTOR('',#179540,1.); -#179540 = DIRECTION('',(0.E+000,1.)); -#179541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179542 = PCURVE('',#179036,#179543); -#179543 = DEFINITIONAL_REPRESENTATION('',(#179544),#179548); -#179544 = LINE('',#179545,#179546); -#179545 = CARTESIAN_POINT('',(0.15,0.E+000)); -#179546 = VECTOR('',#179547,1.); -#179547 = DIRECTION('',(0.E+000,1.)); -#179548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179549 = ORIENTED_EDGE('',*,*,#178992,.T.); -#179550 = ORIENTED_EDGE('',*,*,#179482,.T.); -#179551 = ADVANCED_FACE('',(#179552),#179036,.T.); -#179552 = FACE_BOUND('',#179553,.T.); -#179553 = EDGE_LOOP('',(#179554,#179555,#179576,#179577)); -#179554 = ORIENTED_EDGE('',*,*,#179306,.F.); -#179555 = ORIENTED_EDGE('',*,*,#179556,.F.); -#179556 = EDGE_CURVE('',#179021,#179284,#179557,.T.); -#179557 = SURFACE_CURVE('',#179558,(#179562,#179569),.PCURVE_S1.); -#179558 = LINE('',#179559,#179560); -#179559 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); -#179560 = VECTOR('',#179561,1.); -#179561 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179562 = PCURVE('',#179036,#179563); -#179563 = DEFINITIONAL_REPRESENTATION('',(#179564),#179568); -#179564 = LINE('',#179565,#179566); -#179565 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179566 = VECTOR('',#179567,1.); -#179567 = DIRECTION('',(0.E+000,1.)); -#179568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179569 = PCURVE('',#179064,#179570); -#179570 = DEFINITIONAL_REPRESENTATION('',(#179571),#179575); -#179571 = LINE('',#179572,#179573); -#179572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179573 = VECTOR('',#179574,1.); -#179574 = DIRECTION('',(0.E+000,1.)); -#179575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179576 = ORIENTED_EDGE('',*,*,#179020,.T.); -#179577 = ORIENTED_EDGE('',*,*,#179529,.T.); -#179578 = ADVANCED_FACE('',(#179579),#179064,.T.); -#179579 = FACE_BOUND('',#179580,.T.); -#179580 = EDGE_LOOP('',(#179581,#179582,#179625,#179626)); -#179581 = ORIENTED_EDGE('',*,*,#179283,.F.); -#179582 = ORIENTED_EDGE('',*,*,#179583,.F.); -#179583 = EDGE_CURVE('',#179049,#179261,#179584,.T.); -#179584 = SURFACE_CURVE('',#179585,(#179589,#179596),.PCURVE_S1.); -#179585 = LINE('',#179586,#179587); -#179586 = CARTESIAN_POINT('',(-1.165,1.1307673058,7.066353883144E-017)); -#179587 = VECTOR('',#179588,1.); -#179588 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179589 = PCURVE('',#179064,#179590); -#179590 = DEFINITIONAL_REPRESENTATION('',(#179591),#179595); -#179591 = LINE('',#179592,#179593); -#179592 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); -#179593 = VECTOR('',#179594,1.); -#179594 = DIRECTION('',(0.E+000,1.)); -#179595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179596 = PCURVE('',#179093,#179597); -#179597 = DEFINITIONAL_REPRESENTATION('',(#179598),#179624); -#179598 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#179599,#179600,#179601, - #179602,#179603,#179604,#179605,#179606,#179607,#179608,#179609, - #179610,#179611,#179612,#179613,#179614,#179615,#179616,#179617, - #179618,#179619,#179620,#179621,#179622,#179623),.UNSPECIFIED.,.F., +#181883 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#181884 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#181885 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#181886 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#181887 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#181888 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#181889 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#181890 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#181891 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#181892 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#181893 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#181894 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#181895 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#181896 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#181897 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#181898 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#181899 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#181900 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#181901 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#181902 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#181903 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#181904 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#181905 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#181906 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#181907 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#181908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181909 = PCURVE('',#181400,#181910); +#181910 = DEFINITIONAL_REPRESENTATION('',(#181911),#181915); +#181911 = LINE('',#181912,#181913); +#181912 = CARTESIAN_POINT('',(0.2692326942,0.E+000)); +#181913 = VECTOR('',#181914,1.); +#181914 = DIRECTION('',(0.E+000,1.)); +#181915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181916 = ADVANCED_FACE('',(#181917),#181400,.T.); +#181917 = FACE_BOUND('',#181918,.T.); +#181918 = EDGE_LOOP('',(#181919,#181920,#181941,#181942)); +#181919 = ORIENTED_EDGE('',*,*,#181721,.F.); +#181920 = ORIENTED_EDGE('',*,*,#181921,.F.); +#181921 = EDGE_CURVE('',#181385,#181699,#181922,.T.); +#181922 = SURFACE_CURVE('',#181923,(#181927,#181934),.PCURVE_S1.); +#181923 = LINE('',#181924,#181925); +#181924 = CARTESIAN_POINT('',(-1.165,1.4,0.15)); +#181925 = VECTOR('',#181926,1.); +#181926 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181927 = PCURVE('',#181400,#181928); +#181928 = DEFINITIONAL_REPRESENTATION('',(#181929),#181933); +#181929 = LINE('',#181930,#181931); +#181930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181931 = VECTOR('',#181932,1.); +#181932 = DIRECTION('',(0.E+000,1.)); +#181933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181934 = PCURVE('',#181428,#181935); +#181935 = DEFINITIONAL_REPRESENTATION('',(#181936),#181940); +#181936 = LINE('',#181937,#181938); +#181937 = CARTESIAN_POINT('',(0.15,0.E+000)); +#181938 = VECTOR('',#181939,1.); +#181939 = DIRECTION('',(0.E+000,1.)); +#181940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181941 = ORIENTED_EDGE('',*,*,#181384,.T.); +#181942 = ORIENTED_EDGE('',*,*,#181874,.T.); +#181943 = ADVANCED_FACE('',(#181944),#181428,.T.); +#181944 = FACE_BOUND('',#181945,.T.); +#181945 = EDGE_LOOP('',(#181946,#181947,#181968,#181969)); +#181946 = ORIENTED_EDGE('',*,*,#181698,.F.); +#181947 = ORIENTED_EDGE('',*,*,#181948,.F.); +#181948 = EDGE_CURVE('',#181413,#181676,#181949,.T.); +#181949 = SURFACE_CURVE('',#181950,(#181954,#181961),.PCURVE_S1.); +#181950 = LINE('',#181951,#181952); +#181951 = CARTESIAN_POINT('',(-1.165,1.4,1.384261746118E-016)); +#181952 = VECTOR('',#181953,1.); +#181953 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181954 = PCURVE('',#181428,#181955); +#181955 = DEFINITIONAL_REPRESENTATION('',(#181956),#181960); +#181956 = LINE('',#181957,#181958); +#181957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181958 = VECTOR('',#181959,1.); +#181959 = DIRECTION('',(0.E+000,1.)); +#181960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181961 = PCURVE('',#181456,#181962); +#181962 = DEFINITIONAL_REPRESENTATION('',(#181963),#181967); +#181963 = LINE('',#181964,#181965); +#181964 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#181965 = VECTOR('',#181966,1.); +#181966 = DIRECTION('',(0.E+000,1.)); +#181967 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181968 = ORIENTED_EDGE('',*,*,#181412,.T.); +#181969 = ORIENTED_EDGE('',*,*,#181921,.T.); +#181970 = ADVANCED_FACE('',(#181971),#181456,.T.); +#181971 = FACE_BOUND('',#181972,.T.); +#181972 = EDGE_LOOP('',(#181973,#181974,#182017,#182018)); +#181973 = ORIENTED_EDGE('',*,*,#181675,.F.); +#181974 = ORIENTED_EDGE('',*,*,#181975,.F.); +#181975 = EDGE_CURVE('',#181441,#181653,#181976,.T.); +#181976 = SURFACE_CURVE('',#181977,(#181981,#181988),.PCURVE_S1.); +#181977 = LINE('',#181978,#181979); +#181978 = CARTESIAN_POINT('',(-1.165,1.1307673058,7.066353883144E-017)); +#181979 = VECTOR('',#181980,1.); +#181980 = DIRECTION('',(1.,0.E+000,0.E+000)); +#181981 = PCURVE('',#181456,#181982); +#181982 = DEFINITIONAL_REPRESENTATION('',(#181983),#181987); +#181983 = LINE('',#181984,#181985); +#181984 = CARTESIAN_POINT('',(-0.2692326942,0.E+000)); +#181985 = VECTOR('',#181986,1.); +#181986 = DIRECTION('',(0.E+000,1.)); +#181987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#181988 = PCURVE('',#181485,#181989); +#181989 = DEFINITIONAL_REPRESENTATION('',(#181990),#182016); +#181990 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#181991,#181992,#181993, + #181994,#181995,#181996,#181997,#181998,#181999,#182000,#182001, + #182002,#182003,#182004,#182005,#182006,#182007,#182008,#182009, + #182010,#182011,#182012,#182013,#182014,#182015),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -222445,951 +225447,951 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#179599 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#179600 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); -#179601 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); -#179602 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); -#179603 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); -#179604 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); -#179605 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); -#179606 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); -#179607 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); -#179608 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); -#179609 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); -#179610 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); -#179611 = CARTESIAN_POINT('',(6.28318530718,0.17)); -#179612 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); -#179613 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); -#179614 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); -#179615 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); -#179616 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); -#179617 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); -#179618 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); -#179619 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); -#179620 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#179621 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); -#179622 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); -#179623 = CARTESIAN_POINT('',(6.28318530718,0.34)); -#179624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179625 = ORIENTED_EDGE('',*,*,#179048,.T.); -#179626 = ORIENTED_EDGE('',*,*,#179556,.T.); -#179627 = ADVANCED_FACE('',(#179628),#179093,.T.); -#179628 = FACE_BOUND('',#179629,.T.); -#179629 = EDGE_LOOP('',(#179630,#179631,#179651,#179652)); -#179630 = ORIENTED_EDGE('',*,*,#179260,.F.); -#179631 = ORIENTED_EDGE('',*,*,#179632,.F.); -#179632 = EDGE_CURVE('',#179077,#179238,#179633,.T.); -#179633 = SURFACE_CURVE('',#179634,(#179638,#179644),.PCURVE_S1.); -#179634 = LINE('',#179635,#179636); -#179635 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); -#179636 = VECTOR('',#179637,1.); -#179637 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179638 = PCURVE('',#179093,#179639); -#179639 = DEFINITIONAL_REPRESENTATION('',(#179640),#179643); -#179640 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179641,#179642), +#181991 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#181992 = CARTESIAN_POINT('',(6.28318530718,5.151515151515E-003)); +#181993 = CARTESIAN_POINT('',(6.28318530718,1.545454545455E-002)); +#181994 = CARTESIAN_POINT('',(6.28318530718,3.090909090909E-002)); +#181995 = CARTESIAN_POINT('',(6.28318530718,4.636363636364E-002)); +#181996 = CARTESIAN_POINT('',(6.28318530718,6.181818181818E-002)); +#181997 = CARTESIAN_POINT('',(6.28318530718,7.727272727273E-002)); +#181998 = CARTESIAN_POINT('',(6.28318530718,9.272727272727E-002)); +#181999 = CARTESIAN_POINT('',(6.28318530718,0.108181818182)); +#182000 = CARTESIAN_POINT('',(6.28318530718,0.123636363636)); +#182001 = CARTESIAN_POINT('',(6.28318530718,0.139090909091)); +#182002 = CARTESIAN_POINT('',(6.28318530718,0.154545454545)); +#182003 = CARTESIAN_POINT('',(6.28318530718,0.17)); +#182004 = CARTESIAN_POINT('',(6.28318530718,0.185454545455)); +#182005 = CARTESIAN_POINT('',(6.28318530718,0.200909090909)); +#182006 = CARTESIAN_POINT('',(6.28318530718,0.216363636364)); +#182007 = CARTESIAN_POINT('',(6.28318530718,0.231818181818)); +#182008 = CARTESIAN_POINT('',(6.28318530718,0.247272727273)); +#182009 = CARTESIAN_POINT('',(6.28318530718,0.262727272727)); +#182010 = CARTESIAN_POINT('',(6.28318530718,0.278181818182)); +#182011 = CARTESIAN_POINT('',(6.28318530718,0.293636363636)); +#182012 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#182013 = CARTESIAN_POINT('',(6.28318530718,0.324545454545)); +#182014 = CARTESIAN_POINT('',(6.28318530718,0.334848484848)); +#182015 = CARTESIAN_POINT('',(6.28318530718,0.34)); +#182016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182017 = ORIENTED_EDGE('',*,*,#181440,.T.); +#182018 = ORIENTED_EDGE('',*,*,#181948,.T.); +#182019 = ADVANCED_FACE('',(#182020),#181485,.T.); +#182020 = FACE_BOUND('',#182021,.T.); +#182021 = EDGE_LOOP('',(#182022,#182023,#182043,#182044)); +#182022 = ORIENTED_EDGE('',*,*,#181652,.F.); +#182023 = ORIENTED_EDGE('',*,*,#182024,.F.); +#182024 = EDGE_CURVE('',#181469,#181630,#182025,.T.); +#182025 = SURFACE_CURVE('',#182026,(#182030,#182036),.PCURVE_S1.); +#182026 = LINE('',#182027,#182028); +#182027 = CARTESIAN_POINT('',(-1.165,0.931334836489,0.184943765921)); +#182028 = VECTOR('',#182029,1.); +#182029 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182030 = PCURVE('',#181485,#182031); +#182031 = DEFINITIONAL_REPRESENTATION('',(#182032),#182035); +#182032 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182033,#182034), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179641 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); -#179642 = CARTESIAN_POINT('',(4.787741438996,0.34)); -#179643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179644 = PCURVE('',#179120,#179645); -#179645 = DEFINITIONAL_REPRESENTATION('',(#179646),#179650); -#179646 = LINE('',#179647,#179648); -#179647 = CARTESIAN_POINT('',(1.107072596433E-016,0.E+000)); -#179648 = VECTOR('',#179649,1.); -#179649 = DIRECTION('',(0.E+000,1.)); -#179650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179651 = ORIENTED_EDGE('',*,*,#179076,.T.); -#179652 = ORIENTED_EDGE('',*,*,#179583,.T.); -#179653 = ADVANCED_FACE('',(#179654),#179120,.T.); -#179654 = FACE_BOUND('',#179655,.T.); -#179655 = EDGE_LOOP('',(#179656,#179657,#179677,#179678)); -#179656 = ORIENTED_EDGE('',*,*,#179237,.F.); -#179657 = ORIENTED_EDGE('',*,*,#179658,.F.); -#179658 = EDGE_CURVE('',#179105,#179211,#179659,.T.); -#179659 = SURFACE_CURVE('',#179660,(#179664,#179671),.PCURVE_S1.); -#179660 = LINE('',#179661,#179662); -#179661 = CARTESIAN_POINT('',(-1.165,0.906981201809,0.50752811704)); -#179662 = VECTOR('',#179663,1.); -#179663 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179664 = PCURVE('',#179120,#179665); -#179665 = DEFINITIONAL_REPRESENTATION('',(#179666),#179670); -#179666 = LINE('',#179667,#179668); -#179667 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#179668 = VECTOR('',#179669,1.); -#179669 = DIRECTION('',(0.E+000,1.)); -#179670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179671 = PCURVE('',#178844,#179672); -#179672 = DEFINITIONAL_REPRESENTATION('',(#179673),#179676); -#179673 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179674,#179675), +#182033 = CARTESIAN_POINT('',(4.787741438996,0.E+000)); +#182034 = CARTESIAN_POINT('',(4.787741438996,0.34)); +#182035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182036 = PCURVE('',#181512,#182037); +#182037 = DEFINITIONAL_REPRESENTATION('',(#182038),#182042); +#182038 = LINE('',#182039,#182040); +#182039 = CARTESIAN_POINT('',(1.107072596433E-016,0.E+000)); +#182040 = VECTOR('',#182041,1.); +#182041 = DIRECTION('',(0.E+000,1.)); +#182042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182043 = ORIENTED_EDGE('',*,*,#181468,.T.); +#182044 = ORIENTED_EDGE('',*,*,#181975,.T.); +#182045 = ADVANCED_FACE('',(#182046),#181512,.T.); +#182046 = FACE_BOUND('',#182047,.T.); +#182047 = EDGE_LOOP('',(#182048,#182049,#182069,#182070)); +#182048 = ORIENTED_EDGE('',*,*,#181629,.F.); +#182049 = ORIENTED_EDGE('',*,*,#182050,.F.); +#182050 = EDGE_CURVE('',#181497,#181603,#182051,.T.); +#182051 = SURFACE_CURVE('',#182052,(#182056,#182063),.PCURVE_S1.); +#182052 = LINE('',#182053,#182054); +#182053 = CARTESIAN_POINT('',(-1.165,0.906981201809,0.50752811704)); +#182054 = VECTOR('',#182055,1.); +#182055 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182056 = PCURVE('',#181512,#182057); +#182057 = DEFINITIONAL_REPRESENTATION('',(#182058),#182062); +#182058 = LINE('',#182059,#182060); +#182059 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#182060 = VECTOR('',#182061,1.); +#182061 = DIRECTION('',(0.E+000,1.)); +#182062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182063 = PCURVE('',#181236,#182064); +#182064 = DEFINITIONAL_REPRESENTATION('',(#182065),#182068); +#182065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182066,#182067), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179674 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); -#179675 = CARTESIAN_POINT('',(1.646148785406,0.34)); -#179676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179677 = ORIENTED_EDGE('',*,*,#179104,.T.); -#179678 = ORIENTED_EDGE('',*,*,#179632,.T.); -#179679 = ADVANCED_FACE('',(#179680),#178844,.F.); -#179680 = FACE_BOUND('',#179681,.F.); -#179681 = EDGE_LOOP('',(#179682,#179683,#179684,#179685)); -#179682 = ORIENTED_EDGE('',*,*,#179210,.T.); -#179683 = ORIENTED_EDGE('',*,*,#179658,.F.); -#179684 = ORIENTED_EDGE('',*,*,#179132,.F.); -#179685 = ORIENTED_EDGE('',*,*,#178828,.T.); -#179686 = ADVANCED_FACE('',(#179687),#171983,.T.); -#179687 = FACE_BOUND('',#179688,.T.); -#179688 = EDGE_LOOP('',(#179689,#179690,#179713,#179740)); -#179689 = ORIENTED_EDGE('',*,*,#171967,.T.); -#179690 = ORIENTED_EDGE('',*,*,#179691,.F.); -#179691 = EDGE_CURVE('',#179692,#171945,#179694,.T.); -#179692 = VERTEX_POINT('',#179693); -#179693 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.6)); -#179694 = SURFACE_CURVE('',#179695,(#179699,#179706),.PCURVE_S1.); -#179695 = LINE('',#179696,#179697); -#179696 = CARTESIAN_POINT('',(0.475,-0.7,0.6)); -#179697 = VECTOR('',#179698,1.); -#179698 = DIRECTION('',(0.E+000,1.,0.E+000)); -#179699 = PCURVE('',#171983,#179700); -#179700 = DEFINITIONAL_REPRESENTATION('',(#179701),#179705); -#179701 = LINE('',#179702,#179703); -#179702 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#179703 = VECTOR('',#179704,1.); -#179704 = DIRECTION('',(0.E+000,1.)); -#179705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179706 = PCURVE('',#173338,#179707); -#179707 = DEFINITIONAL_REPRESENTATION('',(#179708),#179712); -#179708 = LINE('',#179709,#179710); -#179709 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#179710 = VECTOR('',#179711,1.); -#179711 = DIRECTION('',(0.E+000,1.)); -#179712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179713 = ORIENTED_EDGE('',*,*,#179714,.F.); -#179714 = EDGE_CURVE('',#179715,#179692,#179717,.T.); -#179715 = VERTEX_POINT('',#179716); -#179716 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.6)); -#179717 = SURFACE_CURVE('',#179718,(#179722,#179729),.PCURVE_S1.); -#179718 = LINE('',#179719,#179720); -#179719 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.6)); -#179720 = VECTOR('',#179721,1.); -#179721 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179722 = PCURVE('',#171983,#179723); -#179723 = DEFINITIONAL_REPRESENTATION('',(#179724),#179728); -#179724 = LINE('',#179725,#179726); -#179725 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); -#179726 = VECTOR('',#179727,1.); -#179727 = DIRECTION('',(-1.,0.E+000)); -#179728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179729 = PCURVE('',#179730,#179735); -#179730 = CYLINDRICAL_SURFACE('',#179731,0.1); -#179731 = AXIS2_PLACEMENT_3D('',#179732,#179733,#179734); -#179732 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); -#179733 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179734 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179735 = DEFINITIONAL_REPRESENTATION('',(#179736),#179739); -#179736 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179737,#179738), +#182066 = CARTESIAN_POINT('',(1.646148785406,0.E+000)); +#182067 = CARTESIAN_POINT('',(1.646148785406,0.34)); +#182068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182069 = ORIENTED_EDGE('',*,*,#181496,.T.); +#182070 = ORIENTED_EDGE('',*,*,#182024,.T.); +#182071 = ADVANCED_FACE('',(#182072),#181236,.F.); +#182072 = FACE_BOUND('',#182073,.F.); +#182073 = EDGE_LOOP('',(#182074,#182075,#182076,#182077)); +#182074 = ORIENTED_EDGE('',*,*,#181602,.T.); +#182075 = ORIENTED_EDGE('',*,*,#182050,.F.); +#182076 = ORIENTED_EDGE('',*,*,#181524,.F.); +#182077 = ORIENTED_EDGE('',*,*,#181220,.T.); +#182078 = ADVANCED_FACE('',(#182079),#174375,.T.); +#182079 = FACE_BOUND('',#182080,.T.); +#182080 = EDGE_LOOP('',(#182081,#182082,#182105,#182132)); +#182081 = ORIENTED_EDGE('',*,*,#174359,.T.); +#182082 = ORIENTED_EDGE('',*,*,#182083,.F.); +#182083 = EDGE_CURVE('',#182084,#174337,#182086,.T.); +#182084 = VERTEX_POINT('',#182085); +#182085 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.6)); +#182086 = SURFACE_CURVE('',#182087,(#182091,#182098),.PCURVE_S1.); +#182087 = LINE('',#182088,#182089); +#182088 = CARTESIAN_POINT('',(0.475,-0.7,0.6)); +#182089 = VECTOR('',#182090,1.); +#182090 = DIRECTION('',(0.E+000,1.,0.E+000)); +#182091 = PCURVE('',#174375,#182092); +#182092 = DEFINITIONAL_REPRESENTATION('',(#182093),#182097); +#182093 = LINE('',#182094,#182095); +#182094 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#182095 = VECTOR('',#182096,1.); +#182096 = DIRECTION('',(0.E+000,1.)); +#182097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182098 = PCURVE('',#175730,#182099); +#182099 = DEFINITIONAL_REPRESENTATION('',(#182100),#182104); +#182100 = LINE('',#182101,#182102); +#182101 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#182102 = VECTOR('',#182103,1.); +#182103 = DIRECTION('',(0.E+000,1.)); +#182104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182105 = ORIENTED_EDGE('',*,*,#182106,.F.); +#182106 = EDGE_CURVE('',#182107,#182084,#182109,.T.); +#182107 = VERTEX_POINT('',#182108); +#182108 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.6)); +#182109 = SURFACE_CURVE('',#182110,(#182114,#182121),.PCURVE_S1.); +#182110 = LINE('',#182111,#182112); +#182111 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.6)); +#182112 = VECTOR('',#182113,1.); +#182113 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182114 = PCURVE('',#174375,#182115); +#182115 = DEFINITIONAL_REPRESENTATION('',(#182116),#182120); +#182116 = LINE('',#182117,#182118); +#182117 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); +#182118 = VECTOR('',#182119,1.); +#182119 = DIRECTION('',(-1.,0.E+000)); +#182120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182121 = PCURVE('',#182122,#182127); +#182122 = CYLINDRICAL_SURFACE('',#182123,0.1); +#182123 = AXIS2_PLACEMENT_3D('',#182124,#182125,#182126); +#182124 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); +#182125 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182126 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182127 = DEFINITIONAL_REPRESENTATION('',(#182128),#182131); +#182128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182129,#182130), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#179737 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#179738 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#179739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179740 = ORIENTED_EDGE('',*,*,#179741,.T.); -#179741 = EDGE_CURVE('',#179715,#171968,#179742,.T.); -#179742 = SURFACE_CURVE('',#179743,(#179747,#179754),.PCURVE_S1.); -#179743 = LINE('',#179744,#179745); -#179744 = CARTESIAN_POINT('',(0.135,-0.7,0.6)); -#179745 = VECTOR('',#179746,1.); -#179746 = DIRECTION('',(0.E+000,1.,0.E+000)); -#179747 = PCURVE('',#171983,#179748); -#179748 = DEFINITIONAL_REPRESENTATION('',(#179749),#179753); -#179749 = LINE('',#179750,#179751); -#179750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179751 = VECTOR('',#179752,1.); -#179752 = DIRECTION('',(0.E+000,1.)); -#179753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179754 = PCURVE('',#173284,#179755); -#179755 = DEFINITIONAL_REPRESENTATION('',(#179756),#179760); -#179756 = LINE('',#179757,#179758); -#179757 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#179758 = VECTOR('',#179759,1.); -#179759 = DIRECTION('',(0.E+000,1.)); -#179760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179761 = ADVANCED_FACE('',(#179762),#173284,.T.); -#179762 = FACE_BOUND('',#179763,.T.); -#179763 = EDGE_LOOP('',(#179764,#179765,#179766,#179789,#179817,#179849, - #179877,#179905,#179933,#179961,#179989,#180021)); -#179764 = ORIENTED_EDGE('',*,*,#173268,.F.); -#179765 = ORIENTED_EDGE('',*,*,#179741,.F.); -#179766 = ORIENTED_EDGE('',*,*,#179767,.F.); -#179767 = EDGE_CURVE('',#179768,#179715,#179770,.T.); -#179768 = VERTEX_POINT('',#179769); -#179769 = CARTESIAN_POINT('',(0.135,-0.906981201809,0.50752811704)); -#179770 = SURFACE_CURVE('',#179771,(#179776,#179783),.PCURVE_S1.); -#179771 = CIRCLE('',#179772,0.1); -#179772 = AXIS2_PLACEMENT_3D('',#179773,#179774,#179775); -#179773 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); -#179774 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179775 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179776 = PCURVE('',#173284,#179777); -#179777 = DEFINITIONAL_REPRESENTATION('',(#179778),#179782); -#179778 = CIRCLE('',#179779,0.1); -#179779 = AXIS2_PLACEMENT_2D('',#179780,#179781); -#179780 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#179781 = DIRECTION('',(-1.,0.E+000)); -#179782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179783 = PCURVE('',#179730,#179784); -#179784 = DEFINITIONAL_REPRESENTATION('',(#179785),#179788); -#179785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179786,#179787), +#182129 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#182130 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#182131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182132 = ORIENTED_EDGE('',*,*,#182133,.T.); +#182133 = EDGE_CURVE('',#182107,#174360,#182134,.T.); +#182134 = SURFACE_CURVE('',#182135,(#182139,#182146),.PCURVE_S1.); +#182135 = LINE('',#182136,#182137); +#182136 = CARTESIAN_POINT('',(0.135,-0.7,0.6)); +#182137 = VECTOR('',#182138,1.); +#182138 = DIRECTION('',(0.E+000,1.,0.E+000)); +#182139 = PCURVE('',#174375,#182140); +#182140 = DEFINITIONAL_REPRESENTATION('',(#182141),#182145); +#182141 = LINE('',#182142,#182143); +#182142 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182143 = VECTOR('',#182144,1.); +#182144 = DIRECTION('',(0.E+000,1.)); +#182145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182146 = PCURVE('',#175676,#182147); +#182147 = DEFINITIONAL_REPRESENTATION('',(#182148),#182152); +#182148 = LINE('',#182149,#182150); +#182149 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#182150 = VECTOR('',#182151,1.); +#182151 = DIRECTION('',(0.E+000,1.)); +#182152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182153 = ADVANCED_FACE('',(#182154),#175676,.T.); +#182154 = FACE_BOUND('',#182155,.T.); +#182155 = EDGE_LOOP('',(#182156,#182157,#182158,#182181,#182209,#182241, + #182269,#182297,#182325,#182353,#182381,#182413)); +#182156 = ORIENTED_EDGE('',*,*,#175660,.F.); +#182157 = ORIENTED_EDGE('',*,*,#182133,.F.); +#182158 = ORIENTED_EDGE('',*,*,#182159,.F.); +#182159 = EDGE_CURVE('',#182160,#182107,#182162,.T.); +#182160 = VERTEX_POINT('',#182161); +#182161 = CARTESIAN_POINT('',(0.135,-0.906981201809,0.50752811704)); +#182162 = SURFACE_CURVE('',#182163,(#182168,#182175),.PCURVE_S1.); +#182163 = CIRCLE('',#182164,0.1); +#182164 = AXIS2_PLACEMENT_3D('',#182165,#182166,#182167); +#182165 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); +#182166 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#182167 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182168 = PCURVE('',#175676,#182169); +#182169 = DEFINITIONAL_REPRESENTATION('',(#182170),#182174); +#182170 = CIRCLE('',#182171,0.1); +#182171 = AXIS2_PLACEMENT_2D('',#182172,#182173); +#182172 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#182173 = DIRECTION('',(-1.,0.E+000)); +#182174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182175 = PCURVE('',#182122,#182176); +#182176 = DEFINITIONAL_REPRESENTATION('',(#182177),#182180); +#182177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182178,#182179), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#179786 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#179787 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#179788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179789 = ORIENTED_EDGE('',*,*,#179790,.F.); -#179790 = EDGE_CURVE('',#179791,#179768,#179793,.T.); -#179791 = VERTEX_POINT('',#179792); -#179792 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); -#179793 = SURFACE_CURVE('',#179794,(#179798,#179805),.PCURVE_S1.); -#179794 = LINE('',#179795,#179796); -#179795 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); -#179796 = VECTOR('',#179797,1.); -#179797 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#179798 = PCURVE('',#173284,#179799); -#179799 = DEFINITIONAL_REPRESENTATION('',(#179800),#179804); -#179800 = LINE('',#179801,#179802); -#179801 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#179802 = VECTOR('',#179803,1.); -#179803 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#179804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179805 = PCURVE('',#179806,#179811); -#179806 = PLANE('',#179807); -#179807 = AXIS2_PLACEMENT_3D('',#179808,#179809,#179810); -#179808 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); -#179809 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); -#179810 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#179811 = DEFINITIONAL_REPRESENTATION('',(#179812),#179816); -#179812 = LINE('',#179813,#179814); -#179813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179814 = VECTOR('',#179815,1.); -#179815 = DIRECTION('',(1.,0.E+000)); -#179816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179817 = ORIENTED_EDGE('',*,*,#179818,.F.); -#179818 = EDGE_CURVE('',#179819,#179791,#179821,.T.); -#179819 = VERTEX_POINT('',#179820); -#179820 = CARTESIAN_POINT('',(0.135,-1.1307673058,-1.210057767209E-016) - ); -#179821 = SURFACE_CURVE('',#179822,(#179827,#179838),.PCURVE_S1.); -#179822 = CIRCLE('',#179823,0.2); -#179823 = AXIS2_PLACEMENT_3D('',#179824,#179825,#179826); -#179824 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); -#179825 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179826 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179827 = PCURVE('',#173284,#179828); -#179828 = DEFINITIONAL_REPRESENTATION('',(#179829),#179837); -#179829 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#179830,#179831,#179832, - #179833,#179834,#179835,#179836),.UNSPECIFIED.,.T.,.F.) +#182178 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#182179 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#182180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182181 = ORIENTED_EDGE('',*,*,#182182,.F.); +#182182 = EDGE_CURVE('',#182183,#182160,#182185,.T.); +#182183 = VERTEX_POINT('',#182184); +#182184 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); +#182185 = SURFACE_CURVE('',#182186,(#182190,#182197),.PCURVE_S1.); +#182186 = LINE('',#182187,#182188); +#182187 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); +#182188 = VECTOR('',#182189,1.); +#182189 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#182190 = PCURVE('',#175676,#182191); +#182191 = DEFINITIONAL_REPRESENTATION('',(#182192),#182196); +#182192 = LINE('',#182193,#182194); +#182193 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#182194 = VECTOR('',#182195,1.); +#182195 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#182196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182197 = PCURVE('',#182198,#182203); +#182198 = PLANE('',#182199); +#182199 = AXIS2_PLACEMENT_3D('',#182200,#182201,#182202); +#182200 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); +#182201 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); +#182202 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#182203 = DEFINITIONAL_REPRESENTATION('',(#182204),#182208); +#182204 = LINE('',#182205,#182206); +#182205 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182206 = VECTOR('',#182207,1.); +#182207 = DIRECTION('',(1.,0.E+000)); +#182208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182209 = ORIENTED_EDGE('',*,*,#182210,.F.); +#182210 = EDGE_CURVE('',#182211,#182183,#182213,.T.); +#182211 = VERTEX_POINT('',#182212); +#182212 = CARTESIAN_POINT('',(0.135,-1.1307673058,-1.210057767209E-016) + ); +#182213 = SURFACE_CURVE('',#182214,(#182219,#182230),.PCURVE_S1.); +#182214 = CIRCLE('',#182215,0.2); +#182215 = AXIS2_PLACEMENT_3D('',#182216,#182217,#182218); +#182216 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); +#182217 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182218 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182219 = PCURVE('',#175676,#182220); +#182220 = DEFINITIONAL_REPRESENTATION('',(#182221),#182229); +#182221 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#182222,#182223,#182224, + #182225,#182226,#182227,#182228),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#179830 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#179831 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#179832 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#179833 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#179834 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#179835 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#179836 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#179837 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179838 = PCURVE('',#179839,#179844); -#179839 = CYLINDRICAL_SURFACE('',#179840,0.2); -#179840 = AXIS2_PLACEMENT_3D('',#179841,#179842,#179843); -#179841 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); -#179842 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179843 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179844 = DEFINITIONAL_REPRESENTATION('',(#179845),#179848); -#179845 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179846,#179847), +#182222 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#182223 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#182224 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#182225 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#182226 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#182227 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#182228 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#182229 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182230 = PCURVE('',#182231,#182236); +#182231 = CYLINDRICAL_SURFACE('',#182232,0.2); +#182232 = AXIS2_PLACEMENT_3D('',#182233,#182234,#182235); +#182233 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); +#182234 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182235 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182236 = DEFINITIONAL_REPRESENTATION('',(#182237),#182240); +#182237 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182238,#182239), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#179846 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179847 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#179848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179849 = ORIENTED_EDGE('',*,*,#179850,.F.); -#179850 = EDGE_CURVE('',#179851,#179819,#179853,.T.); -#179851 = VERTEX_POINT('',#179852); -#179852 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#179853 = SURFACE_CURVE('',#179854,(#179858,#179865),.PCURVE_S1.); -#179854 = LINE('',#179855,#179856); -#179855 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#179856 = VECTOR('',#179857,1.); -#179857 = DIRECTION('',(0.E+000,1.,0.E+000)); -#179858 = PCURVE('',#173284,#179859); -#179859 = DEFINITIONAL_REPRESENTATION('',(#179860),#179864); -#179860 = LINE('',#179861,#179862); -#179861 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#179862 = VECTOR('',#179863,1.); -#179863 = DIRECTION('',(0.E+000,1.)); -#179864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179865 = PCURVE('',#179866,#179871); -#179866 = PLANE('',#179867); -#179867 = AXIS2_PLACEMENT_3D('',#179868,#179869,#179870); -#179868 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#179869 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179870 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179871 = DEFINITIONAL_REPRESENTATION('',(#179872),#179876); -#179872 = LINE('',#179873,#179874); -#179873 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179874 = VECTOR('',#179875,1.); -#179875 = DIRECTION('',(0.E+000,1.)); -#179876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179877 = ORIENTED_EDGE('',*,*,#179878,.F.); -#179878 = EDGE_CURVE('',#179879,#179851,#179881,.T.); -#179879 = VERTEX_POINT('',#179880); -#179880 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); -#179881 = SURFACE_CURVE('',#179882,(#179886,#179893),.PCURVE_S1.); -#179882 = LINE('',#179883,#179884); -#179883 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#179884 = VECTOR('',#179885,1.); -#179885 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179886 = PCURVE('',#173284,#179887); -#179887 = DEFINITIONAL_REPRESENTATION('',(#179888),#179892); -#179888 = LINE('',#179889,#179890); -#179889 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#179890 = VECTOR('',#179891,1.); -#179891 = DIRECTION('',(-1.,0.E+000)); -#179892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179893 = PCURVE('',#179894,#179899); -#179894 = PLANE('',#179895); -#179895 = AXIS2_PLACEMENT_3D('',#179896,#179897,#179898); -#179896 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#179897 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#179898 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179899 = DEFINITIONAL_REPRESENTATION('',(#179900),#179904); -#179900 = LINE('',#179901,#179902); -#179901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179902 = VECTOR('',#179903,1.); -#179903 = DIRECTION('',(1.,0.E+000)); -#179904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179905 = ORIENTED_EDGE('',*,*,#179906,.F.); -#179906 = EDGE_CURVE('',#179907,#179879,#179909,.T.); -#179907 = VERTEX_POINT('',#179908); -#179908 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.15)); -#179909 = SURFACE_CURVE('',#179910,(#179914,#179921),.PCURVE_S1.); -#179910 = LINE('',#179911,#179912); -#179911 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); -#179912 = VECTOR('',#179913,1.); -#179913 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#179914 = PCURVE('',#173284,#179915); -#179915 = DEFINITIONAL_REPRESENTATION('',(#179916),#179920); -#179916 = LINE('',#179917,#179918); -#179917 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#179918 = VECTOR('',#179919,1.); -#179919 = DIRECTION('',(0.E+000,-1.)); -#179920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179921 = PCURVE('',#179922,#179927); -#179922 = PLANE('',#179923); -#179923 = AXIS2_PLACEMENT_3D('',#179924,#179925,#179926); -#179924 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); -#179925 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179926 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179927 = DEFINITIONAL_REPRESENTATION('',(#179928),#179932); -#179928 = LINE('',#179929,#179930); -#179929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179930 = VECTOR('',#179931,1.); -#179931 = DIRECTION('',(0.E+000,-1.)); -#179932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179933 = ORIENTED_EDGE('',*,*,#179934,.F.); -#179934 = EDGE_CURVE('',#179935,#179907,#179937,.T.); -#179935 = VERTEX_POINT('',#179936); -#179936 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); -#179937 = SURFACE_CURVE('',#179938,(#179943,#179950),.PCURVE_S1.); -#179938 = CIRCLE('',#179939,5.E-002); -#179939 = AXIS2_PLACEMENT_3D('',#179940,#179941,#179942); -#179940 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); -#179941 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#179942 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179943 = PCURVE('',#173284,#179944); -#179944 = DEFINITIONAL_REPRESENTATION('',(#179945),#179949); -#179945 = CIRCLE('',#179946,5.E-002); -#179946 = AXIS2_PLACEMENT_2D('',#179947,#179948); -#179947 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#179948 = DIRECTION('',(-1.,0.E+000)); -#179949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179950 = PCURVE('',#179951,#179956); -#179951 = CYLINDRICAL_SURFACE('',#179952,5.E-002); -#179952 = AXIS2_PLACEMENT_3D('',#179953,#179954,#179955); -#179953 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); -#179954 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179955 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#179956 = DEFINITIONAL_REPRESENTATION('',(#179957),#179960); -#179957 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#179958,#179959), - .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#179958 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#179959 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#182238 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182239 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#182240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#179961 = ORIENTED_EDGE('',*,*,#179962,.F.); -#179962 = EDGE_CURVE('',#179963,#179935,#179965,.T.); -#179963 = VERTEX_POINT('',#179964); -#179964 = CARTESIAN_POINT('',(0.135,-1.056555553792,0.518820292599)); -#179965 = SURFACE_CURVE('',#179966,(#179970,#179977),.PCURVE_S1.); -#179966 = LINE('',#179967,#179968); -#179967 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); -#179968 = VECTOR('',#179969,1.); -#179969 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#179970 = PCURVE('',#173284,#179971); -#179971 = DEFINITIONAL_REPRESENTATION('',(#179972),#179976); -#179972 = LINE('',#179973,#179974); -#179973 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#179974 = VECTOR('',#179975,1.); -#179975 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#179976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179977 = PCURVE('',#179978,#179983); -#179978 = PLANE('',#179979); -#179979 = AXIS2_PLACEMENT_3D('',#179980,#179981,#179982); -#179980 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); -#179981 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); -#179982 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#179983 = DEFINITIONAL_REPRESENTATION('',(#179984),#179988); -#179984 = LINE('',#179985,#179986); -#179985 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#179986 = VECTOR('',#179987,1.); -#179987 = DIRECTION('',(1.,0.E+000)); -#179988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#179989 = ORIENTED_EDGE('',*,*,#179990,.F.); -#179990 = EDGE_CURVE('',#179991,#179963,#179993,.T.); -#179991 = VERTEX_POINT('',#179992); -#179992 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); -#179993 = SURFACE_CURVE('',#179994,(#179999,#180010),.PCURVE_S1.); -#179994 = CIRCLE('',#179995,0.25); -#179995 = AXIS2_PLACEMENT_3D('',#179996,#179997,#179998); -#179996 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); -#179997 = DIRECTION('',(1.,0.E+000,0.E+000)); -#179998 = DIRECTION('',(0.E+000,0.E+000,1.)); -#179999 = PCURVE('',#173284,#180000); -#180000 = DEFINITIONAL_REPRESENTATION('',(#180001),#180009); -#180001 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180002,#180003,#180004, - #180005,#180006,#180007,#180008),.UNSPECIFIED.,.F.,.F.) +#182241 = ORIENTED_EDGE('',*,*,#182242,.F.); +#182242 = EDGE_CURVE('',#182243,#182211,#182245,.T.); +#182243 = VERTEX_POINT('',#182244); +#182244 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182245 = SURFACE_CURVE('',#182246,(#182250,#182257),.PCURVE_S1.); +#182246 = LINE('',#182247,#182248); +#182247 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182248 = VECTOR('',#182249,1.); +#182249 = DIRECTION('',(0.E+000,1.,0.E+000)); +#182250 = PCURVE('',#175676,#182251); +#182251 = DEFINITIONAL_REPRESENTATION('',(#182252),#182256); +#182252 = LINE('',#182253,#182254); +#182253 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#182254 = VECTOR('',#182255,1.); +#182255 = DIRECTION('',(0.E+000,1.)); +#182256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182257 = PCURVE('',#182258,#182263); +#182258 = PLANE('',#182259); +#182259 = AXIS2_PLACEMENT_3D('',#182260,#182261,#182262); +#182260 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182261 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182262 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#182263 = DEFINITIONAL_REPRESENTATION('',(#182264),#182268); +#182264 = LINE('',#182265,#182266); +#182265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182266 = VECTOR('',#182267,1.); +#182267 = DIRECTION('',(0.E+000,1.)); +#182268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182269 = ORIENTED_EDGE('',*,*,#182270,.F.); +#182270 = EDGE_CURVE('',#182271,#182243,#182273,.T.); +#182271 = VERTEX_POINT('',#182272); +#182272 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); +#182273 = SURFACE_CURVE('',#182274,(#182278,#182285),.PCURVE_S1.); +#182274 = LINE('',#182275,#182276); +#182275 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182276 = VECTOR('',#182277,1.); +#182277 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182278 = PCURVE('',#175676,#182279); +#182279 = DEFINITIONAL_REPRESENTATION('',(#182280),#182284); +#182280 = LINE('',#182281,#182282); +#182281 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#182282 = VECTOR('',#182283,1.); +#182283 = DIRECTION('',(-1.,0.E+000)); +#182284 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182285 = PCURVE('',#182286,#182291); +#182286 = PLANE('',#182287); +#182287 = AXIS2_PLACEMENT_3D('',#182288,#182289,#182290); +#182288 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182289 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#182290 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182291 = DEFINITIONAL_REPRESENTATION('',(#182292),#182296); +#182292 = LINE('',#182293,#182294); +#182293 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182294 = VECTOR('',#182295,1.); +#182295 = DIRECTION('',(1.,0.E+000)); +#182296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182297 = ORIENTED_EDGE('',*,*,#182298,.F.); +#182298 = EDGE_CURVE('',#182299,#182271,#182301,.T.); +#182299 = VERTEX_POINT('',#182300); +#182300 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.15)); +#182301 = SURFACE_CURVE('',#182302,(#182306,#182313),.PCURVE_S1.); +#182302 = LINE('',#182303,#182304); +#182303 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); +#182304 = VECTOR('',#182305,1.); +#182305 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#182306 = PCURVE('',#175676,#182307); +#182307 = DEFINITIONAL_REPRESENTATION('',(#182308),#182312); +#182308 = LINE('',#182309,#182310); +#182309 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#182310 = VECTOR('',#182311,1.); +#182311 = DIRECTION('',(0.E+000,-1.)); +#182312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182313 = PCURVE('',#182314,#182319); +#182314 = PLANE('',#182315); +#182315 = AXIS2_PLACEMENT_3D('',#182316,#182317,#182318); +#182316 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); +#182317 = DIRECTION('',(0.E+000,0.E+000,1.)); +#182318 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182319 = DEFINITIONAL_REPRESENTATION('',(#182320),#182324); +#182320 = LINE('',#182321,#182322); +#182321 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182322 = VECTOR('',#182323,1.); +#182323 = DIRECTION('',(0.E+000,-1.)); +#182324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182325 = ORIENTED_EDGE('',*,*,#182326,.F.); +#182326 = EDGE_CURVE('',#182327,#182299,#182329,.T.); +#182327 = VERTEX_POINT('',#182328); +#182328 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); +#182329 = SURFACE_CURVE('',#182330,(#182335,#182342),.PCURVE_S1.); +#182330 = CIRCLE('',#182331,5.E-002); +#182331 = AXIS2_PLACEMENT_3D('',#182332,#182333,#182334); +#182332 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); +#182333 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#182334 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182335 = PCURVE('',#175676,#182336); +#182336 = DEFINITIONAL_REPRESENTATION('',(#182337),#182341); +#182337 = CIRCLE('',#182338,5.E-002); +#182338 = AXIS2_PLACEMENT_2D('',#182339,#182340); +#182339 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#182340 = DIRECTION('',(-1.,0.E+000)); +#182341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182342 = PCURVE('',#182343,#182348); +#182343 = CYLINDRICAL_SURFACE('',#182344,5.E-002); +#182344 = AXIS2_PLACEMENT_3D('',#182345,#182346,#182347); +#182345 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.2)); +#182346 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182347 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182348 = DEFINITIONAL_REPRESENTATION('',(#182349),#182352); +#182349 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182350,#182351), + .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), + .PIECEWISE_BEZIER_KNOTS.); +#182350 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#182351 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182352 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182353 = ORIENTED_EDGE('',*,*,#182354,.F.); +#182354 = EDGE_CURVE('',#182355,#182327,#182357,.T.); +#182355 = VERTEX_POINT('',#182356); +#182356 = CARTESIAN_POINT('',(0.135,-1.056555553792,0.518820292599)); +#182357 = SURFACE_CURVE('',#182358,(#182362,#182369),.PCURVE_S1.); +#182358 = LINE('',#182359,#182360); +#182359 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); +#182360 = VECTOR('',#182361,1.); +#182361 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#182362 = PCURVE('',#175676,#182363); +#182363 = DEFINITIONAL_REPRESENTATION('',(#182364),#182368); +#182364 = LINE('',#182365,#182366); +#182365 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#182366 = VECTOR('',#182367,1.); +#182367 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#182368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182369 = PCURVE('',#182370,#182375); +#182370 = PLANE('',#182371); +#182371 = AXIS2_PLACEMENT_3D('',#182372,#182373,#182374); +#182372 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); +#182373 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); +#182374 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#182375 = DEFINITIONAL_REPRESENTATION('',(#182376),#182380); +#182376 = LINE('',#182377,#182378); +#182377 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182378 = VECTOR('',#182379,1.); +#182379 = DIRECTION('',(1.,0.E+000)); +#182380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182381 = ORIENTED_EDGE('',*,*,#182382,.F.); +#182382 = EDGE_CURVE('',#182383,#182355,#182385,.T.); +#182383 = VERTEX_POINT('',#182384); +#182384 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); +#182385 = SURFACE_CURVE('',#182386,(#182391,#182402),.PCURVE_S1.); +#182386 = CIRCLE('',#182387,0.25); +#182387 = AXIS2_PLACEMENT_3D('',#182388,#182389,#182390); +#182388 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); +#182389 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182390 = DIRECTION('',(0.E+000,0.E+000,1.)); +#182391 = PCURVE('',#175676,#182392); +#182392 = DEFINITIONAL_REPRESENTATION('',(#182393),#182401); +#182393 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#182394,#182395,#182396, + #182397,#182398,#182399,#182400),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180002 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180003 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#180004 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#180005 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#180006 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#180007 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#180008 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180010 = PCURVE('',#180011,#180016); -#180011 = CYLINDRICAL_SURFACE('',#180012,0.25); -#180012 = AXIS2_PLACEMENT_3D('',#180013,#180014,#180015); -#180013 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); -#180014 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180015 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180016 = DEFINITIONAL_REPRESENTATION('',(#180017),#180020); -#180017 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180018,#180019), +#182394 = CARTESIAN_POINT('',(0.25,0.E+000)); +#182395 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#182396 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#182397 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#182398 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#182399 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#182400 = CARTESIAN_POINT('',(0.25,0.E+000)); +#182401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182402 = PCURVE('',#182403,#182408); +#182403 = CYLINDRICAL_SURFACE('',#182404,0.25); +#182404 = AXIS2_PLACEMENT_3D('',#182405,#182406,#182407); +#182405 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.5)); +#182406 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182407 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182408 = DEFINITIONAL_REPRESENTATION('',(#182409),#182412); +#182409 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182410,#182411), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#180018 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180019 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#180020 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180021 = ORIENTED_EDGE('',*,*,#180022,.F.); -#180022 = EDGE_CURVE('',#173269,#179991,#180023,.T.); -#180023 = SURFACE_CURVE('',#180024,(#180028,#180035),.PCURVE_S1.); -#180024 = LINE('',#180025,#180026); -#180025 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); -#180026 = VECTOR('',#180027,1.); -#180027 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180028 = PCURVE('',#173284,#180029); -#180029 = DEFINITIONAL_REPRESENTATION('',(#180030),#180034); -#180030 = LINE('',#180031,#180032); -#180031 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#180032 = VECTOR('',#180033,1.); -#180033 = DIRECTION('',(0.E+000,-1.)); -#180034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180035 = PCURVE('',#173312,#180036); -#180036 = DEFINITIONAL_REPRESENTATION('',(#180037),#180041); -#180037 = LINE('',#180038,#180039); -#180038 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180039 = VECTOR('',#180040,1.); -#180040 = DIRECTION('',(0.E+000,-1.)); -#180041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#182410 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#182411 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#182412 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182413 = ORIENTED_EDGE('',*,*,#182414,.F.); +#182414 = EDGE_CURVE('',#175661,#182383,#182415,.T.); +#182415 = SURFACE_CURVE('',#182416,(#182420,#182427),.PCURVE_S1.); +#182416 = LINE('',#182417,#182418); +#182417 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); +#182418 = VECTOR('',#182419,1.); +#182419 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#182420 = PCURVE('',#175676,#182421); +#182421 = DEFINITIONAL_REPRESENTATION('',(#182422),#182426); +#182422 = LINE('',#182423,#182424); +#182423 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#182424 = VECTOR('',#182425,1.); +#182425 = DIRECTION('',(0.E+000,-1.)); +#182426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182427 = PCURVE('',#175704,#182428); +#182428 = DEFINITIONAL_REPRESENTATION('',(#182429),#182433); +#182429 = LINE('',#182430,#182431); +#182430 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182431 = VECTOR('',#182432,1.); +#182432 = DIRECTION('',(0.E+000,-1.)); +#182433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182434 = ADVANCED_FACE('',(#182435),#175704,.T.); +#182435 = FACE_BOUND('',#182436,.T.); +#182436 = EDGE_LOOP('',(#182437,#182459,#182480,#182481)); +#182437 = ORIENTED_EDGE('',*,*,#182438,.T.); +#182438 = EDGE_CURVE('',#182383,#182439,#182441,.T.); +#182439 = VERTEX_POINT('',#182440); +#182440 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.75)); +#182441 = SURFACE_CURVE('',#182442,(#182446,#182453),.PCURVE_S1.); +#182442 = LINE('',#182443,#182444); +#182443 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); +#182444 = VECTOR('',#182445,1.); +#182445 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182446 = PCURVE('',#175704,#182447); +#182447 = DEFINITIONAL_REPRESENTATION('',(#182448),#182452); +#182448 = LINE('',#182449,#182450); +#182449 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); +#182450 = VECTOR('',#182451,1.); +#182451 = DIRECTION('',(1.,0.E+000)); +#182452 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180042 = ADVANCED_FACE('',(#180043),#173312,.T.); -#180043 = FACE_BOUND('',#180044,.T.); -#180044 = EDGE_LOOP('',(#180045,#180067,#180088,#180089)); -#180045 = ORIENTED_EDGE('',*,*,#180046,.T.); -#180046 = EDGE_CURVE('',#179991,#180047,#180049,.T.); -#180047 = VERTEX_POINT('',#180048); -#180048 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.75)); -#180049 = SURFACE_CURVE('',#180050,(#180054,#180061),.PCURVE_S1.); -#180050 = LINE('',#180051,#180052); -#180051 = CARTESIAN_POINT('',(0.135,-0.807264967154,0.75)); -#180052 = VECTOR('',#180053,1.); -#180053 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180054 = PCURVE('',#173312,#180055); -#180055 = DEFINITIONAL_REPRESENTATION('',(#180056),#180060); -#180056 = LINE('',#180057,#180058); -#180057 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); -#180058 = VECTOR('',#180059,1.); -#180059 = DIRECTION('',(1.,0.E+000)); -#180060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180061 = PCURVE('',#180011,#180062); -#180062 = DEFINITIONAL_REPRESENTATION('',(#180063),#180066); -#180063 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180064,#180065), +#182453 = PCURVE('',#182403,#182454); +#182454 = DEFINITIONAL_REPRESENTATION('',(#182455),#182458); +#182455 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182456,#182457), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180064 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180065 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#180066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#182456 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#182457 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#182458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180067 = ORIENTED_EDGE('',*,*,#180068,.F.); -#180068 = EDGE_CURVE('',#173297,#180047,#180069,.T.); -#180069 = SURFACE_CURVE('',#180070,(#180074,#180081),.PCURVE_S1.); -#180070 = LINE('',#180071,#180072); -#180071 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.75)); -#180072 = VECTOR('',#180073,1.); -#180073 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180074 = PCURVE('',#173312,#180075); -#180075 = DEFINITIONAL_REPRESENTATION('',(#180076),#180080); -#180076 = LINE('',#180077,#180078); -#180077 = CARTESIAN_POINT('',(0.34,0.E+000)); -#180078 = VECTOR('',#180079,1.); -#180079 = DIRECTION('',(0.E+000,-1.)); -#180080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180081 = PCURVE('',#173338,#180082); -#180082 = DEFINITIONAL_REPRESENTATION('',(#180083),#180087); -#180083 = LINE('',#180084,#180085); -#180084 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#180085 = VECTOR('',#180086,1.); -#180086 = DIRECTION('',(0.E+000,-1.)); -#180087 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180088 = ORIENTED_EDGE('',*,*,#173296,.F.); -#180089 = ORIENTED_EDGE('',*,*,#180022,.T.); -#180090 = ADVANCED_FACE('',(#180091),#173338,.F.); -#180091 = FACE_BOUND('',#180092,.T.); -#180092 = EDGE_LOOP('',(#180093,#180094,#180095,#180096,#180123,#180146, - #180169,#180192,#180215,#180238,#180265,#180288)); -#180093 = ORIENTED_EDGE('',*,*,#179691,.T.); -#180094 = ORIENTED_EDGE('',*,*,#173324,.T.); -#180095 = ORIENTED_EDGE('',*,*,#180068,.T.); -#180096 = ORIENTED_EDGE('',*,*,#180097,.T.); -#180097 = EDGE_CURVE('',#180047,#180098,#180100,.T.); -#180098 = VERTEX_POINT('',#180099); -#180099 = CARTESIAN_POINT('',(0.475,-1.056555553792,0.518820292599)); -#180100 = SURFACE_CURVE('',#180101,(#180106,#180117),.PCURVE_S1.); -#180101 = CIRCLE('',#180102,0.25); -#180102 = AXIS2_PLACEMENT_3D('',#180103,#180104,#180105); -#180103 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); -#180104 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180105 = DIRECTION('',(0.E+000,0.E+000,1.)); -#180106 = PCURVE('',#173338,#180107); -#180107 = DEFINITIONAL_REPRESENTATION('',(#180108),#180116); -#180108 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180109,#180110,#180111, - #180112,#180113,#180114,#180115),.UNSPECIFIED.,.F.,.F.) +#182459 = ORIENTED_EDGE('',*,*,#182460,.F.); +#182460 = EDGE_CURVE('',#175689,#182439,#182461,.T.); +#182461 = SURFACE_CURVE('',#182462,(#182466,#182473),.PCURVE_S1.); +#182462 = LINE('',#182463,#182464); +#182463 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.75)); +#182464 = VECTOR('',#182465,1.); +#182465 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#182466 = PCURVE('',#175704,#182467); +#182467 = DEFINITIONAL_REPRESENTATION('',(#182468),#182472); +#182468 = LINE('',#182469,#182470); +#182469 = CARTESIAN_POINT('',(0.34,0.E+000)); +#182470 = VECTOR('',#182471,1.); +#182471 = DIRECTION('',(0.E+000,-1.)); +#182472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182473 = PCURVE('',#175730,#182474); +#182474 = DEFINITIONAL_REPRESENTATION('',(#182475),#182479); +#182475 = LINE('',#182476,#182477); +#182476 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#182477 = VECTOR('',#182478,1.); +#182478 = DIRECTION('',(0.E+000,-1.)); +#182479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182480 = ORIENTED_EDGE('',*,*,#175688,.F.); +#182481 = ORIENTED_EDGE('',*,*,#182414,.T.); +#182482 = ADVANCED_FACE('',(#182483),#175730,.F.); +#182483 = FACE_BOUND('',#182484,.T.); +#182484 = EDGE_LOOP('',(#182485,#182486,#182487,#182488,#182515,#182538, + #182561,#182584,#182607,#182630,#182657,#182680)); +#182485 = ORIENTED_EDGE('',*,*,#182083,.T.); +#182486 = ORIENTED_EDGE('',*,*,#175716,.T.); +#182487 = ORIENTED_EDGE('',*,*,#182460,.T.); +#182488 = ORIENTED_EDGE('',*,*,#182489,.T.); +#182489 = EDGE_CURVE('',#182439,#182490,#182492,.T.); +#182490 = VERTEX_POINT('',#182491); +#182491 = CARTESIAN_POINT('',(0.475,-1.056555553792,0.518820292599)); +#182492 = SURFACE_CURVE('',#182493,(#182498,#182509),.PCURVE_S1.); +#182493 = CIRCLE('',#182494,0.25); +#182494 = AXIS2_PLACEMENT_3D('',#182495,#182496,#182497); +#182495 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); +#182496 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182497 = DIRECTION('',(0.E+000,0.E+000,1.)); +#182498 = PCURVE('',#175730,#182499); +#182499 = DEFINITIONAL_REPRESENTATION('',(#182500),#182508); +#182500 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#182501,#182502,#182503, + #182504,#182505,#182506,#182507),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180109 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180110 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#180111 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#180112 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#180113 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#180114 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#180115 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180117 = PCURVE('',#180011,#180118); -#180118 = DEFINITIONAL_REPRESENTATION('',(#180119),#180122); -#180119 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180120,#180121), +#182501 = CARTESIAN_POINT('',(0.25,0.E+000)); +#182502 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#182503 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#182504 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#182505 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#182506 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#182507 = CARTESIAN_POINT('',(0.25,0.E+000)); +#182508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182509 = PCURVE('',#182403,#182510); +#182510 = DEFINITIONAL_REPRESENTATION('',(#182511),#182514); +#182511 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182512,#182513), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#180120 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#180121 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#180122 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180123 = ORIENTED_EDGE('',*,*,#180124,.T.); -#180124 = EDGE_CURVE('',#180098,#180125,#180127,.T.); -#180125 = VERTEX_POINT('',#180126); -#180126 = CARTESIAN_POINT('',(0.475,-1.080909188472,0.19623594148)); -#180127 = SURFACE_CURVE('',#180128,(#180132,#180139),.PCURVE_S1.); -#180128 = LINE('',#180129,#180130); -#180129 = CARTESIAN_POINT('',(0.475,-1.080909188472,0.19623594148)); -#180130 = VECTOR('',#180131,1.); -#180131 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#180132 = PCURVE('',#173338,#180133); -#180133 = DEFINITIONAL_REPRESENTATION('',(#180134),#180138); -#180134 = LINE('',#180135,#180136); -#180135 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#180136 = VECTOR('',#180137,1.); -#180137 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#180138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180139 = PCURVE('',#179978,#180140); -#180140 = DEFINITIONAL_REPRESENTATION('',(#180141),#180145); -#180141 = LINE('',#180142,#180143); -#180142 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180143 = VECTOR('',#180144,1.); -#180144 = DIRECTION('',(1.,0.E+000)); -#180145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180146 = ORIENTED_EDGE('',*,*,#180147,.T.); -#180147 = EDGE_CURVE('',#180125,#180148,#180150,.T.); -#180148 = VERTEX_POINT('',#180149); -#180149 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.15)); -#180150 = SURFACE_CURVE('',#180151,(#180156,#180163),.PCURVE_S1.); -#180151 = CIRCLE('',#180152,5.E-002); -#180152 = AXIS2_PLACEMENT_3D('',#180153,#180154,#180155); -#180153 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.2)); -#180154 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#180155 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180156 = PCURVE('',#173338,#180157); -#180157 = DEFINITIONAL_REPRESENTATION('',(#180158),#180162); -#180158 = CIRCLE('',#180159,5.E-002); -#180159 = AXIS2_PLACEMENT_2D('',#180160,#180161); -#180160 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#180161 = DIRECTION('',(-1.,0.E+000)); -#180162 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180163 = PCURVE('',#179951,#180164); -#180164 = DEFINITIONAL_REPRESENTATION('',(#180165),#180168); -#180165 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180166,#180167), - .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#180166 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#180167 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#182512 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#182513 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#182514 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180169 = ORIENTED_EDGE('',*,*,#180170,.T.); -#180170 = EDGE_CURVE('',#180148,#180171,#180173,.T.); -#180171 = VERTEX_POINT('',#180172); -#180172 = CARTESIAN_POINT('',(0.475,-1.4,0.15)); -#180173 = SURFACE_CURVE('',#180174,(#180178,#180185),.PCURVE_S1.); -#180174 = LINE('',#180175,#180176); -#180175 = CARTESIAN_POINT('',(0.475,-1.4,0.15)); -#180176 = VECTOR('',#180177,1.); -#180177 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180178 = PCURVE('',#173338,#180179); -#180179 = DEFINITIONAL_REPRESENTATION('',(#180180),#180184); -#180180 = LINE('',#180181,#180182); -#180181 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#180182 = VECTOR('',#180183,1.); -#180183 = DIRECTION('',(0.E+000,-1.)); -#180184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180185 = PCURVE('',#179922,#180186); -#180186 = DEFINITIONAL_REPRESENTATION('',(#180187),#180191); -#180187 = LINE('',#180188,#180189); -#180188 = CARTESIAN_POINT('',(0.34,0.E+000)); -#180189 = VECTOR('',#180190,1.); -#180190 = DIRECTION('',(0.E+000,-1.)); -#180191 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180192 = ORIENTED_EDGE('',*,*,#180193,.T.); -#180193 = EDGE_CURVE('',#180171,#180194,#180196,.T.); -#180194 = VERTEX_POINT('',#180195); -#180195 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); -#180196 = SURFACE_CURVE('',#180197,(#180201,#180208),.PCURVE_S1.); -#180197 = LINE('',#180198,#180199); -#180198 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); -#180199 = VECTOR('',#180200,1.); -#180200 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180201 = PCURVE('',#173338,#180202); -#180202 = DEFINITIONAL_REPRESENTATION('',(#180203),#180207); -#180203 = LINE('',#180204,#180205); -#180204 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#180205 = VECTOR('',#180206,1.); -#180206 = DIRECTION('',(-1.,0.E+000)); -#180207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180208 = PCURVE('',#179894,#180209); -#180209 = DEFINITIONAL_REPRESENTATION('',(#180210),#180214); -#180210 = LINE('',#180211,#180212); -#180211 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180212 = VECTOR('',#180213,1.); -#180213 = DIRECTION('',(1.,0.E+000)); -#180214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180215 = ORIENTED_EDGE('',*,*,#180216,.T.); -#180216 = EDGE_CURVE('',#180194,#180217,#180219,.T.); -#180217 = VERTEX_POINT('',#180218); -#180218 = CARTESIAN_POINT('',(0.475,-1.1307673058,-1.210057767209E-016) - ); -#180219 = SURFACE_CURVE('',#180220,(#180224,#180231),.PCURVE_S1.); -#180220 = LINE('',#180221,#180222); -#180221 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); -#180222 = VECTOR('',#180223,1.); -#180223 = DIRECTION('',(0.E+000,1.,0.E+000)); -#180224 = PCURVE('',#173338,#180225); -#180225 = DEFINITIONAL_REPRESENTATION('',(#180226),#180230); -#180226 = LINE('',#180227,#180228); -#180227 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#180228 = VECTOR('',#180229,1.); -#180229 = DIRECTION('',(0.E+000,1.)); -#180230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180231 = PCURVE('',#179866,#180232); -#180232 = DEFINITIONAL_REPRESENTATION('',(#180233),#180237); -#180233 = LINE('',#180234,#180235); -#180234 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#180235 = VECTOR('',#180236,1.); -#180236 = DIRECTION('',(0.E+000,1.)); -#180237 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180238 = ORIENTED_EDGE('',*,*,#180239,.T.); -#180239 = EDGE_CURVE('',#180217,#180240,#180242,.T.); -#180240 = VERTEX_POINT('',#180241); -#180241 = CARTESIAN_POINT('',(0.475,-0.931334836489,0.184943765921)); -#180242 = SURFACE_CURVE('',#180243,(#180248,#180259),.PCURVE_S1.); -#180243 = CIRCLE('',#180244,0.2); -#180244 = AXIS2_PLACEMENT_3D('',#180245,#180246,#180247); -#180245 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.2)); -#180246 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180247 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180248 = PCURVE('',#173338,#180249); -#180249 = DEFINITIONAL_REPRESENTATION('',(#180250),#180258); -#180250 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180251,#180252,#180253, - #180254,#180255,#180256,#180257),.UNSPECIFIED.,.T.,.F.) +#182515 = ORIENTED_EDGE('',*,*,#182516,.T.); +#182516 = EDGE_CURVE('',#182490,#182517,#182519,.T.); +#182517 = VERTEX_POINT('',#182518); +#182518 = CARTESIAN_POINT('',(0.475,-1.080909188472,0.19623594148)); +#182519 = SURFACE_CURVE('',#182520,(#182524,#182531),.PCURVE_S1.); +#182520 = LINE('',#182521,#182522); +#182521 = CARTESIAN_POINT('',(0.475,-1.080909188472,0.19623594148)); +#182522 = VECTOR('',#182523,1.); +#182523 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#182524 = PCURVE('',#175730,#182525); +#182525 = DEFINITIONAL_REPRESENTATION('',(#182526),#182530); +#182526 = LINE('',#182527,#182528); +#182527 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#182528 = VECTOR('',#182529,1.); +#182529 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#182530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182531 = PCURVE('',#182370,#182532); +#182532 = DEFINITIONAL_REPRESENTATION('',(#182533),#182537); +#182533 = LINE('',#182534,#182535); +#182534 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182535 = VECTOR('',#182536,1.); +#182536 = DIRECTION('',(1.,0.E+000)); +#182537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182538 = ORIENTED_EDGE('',*,*,#182539,.T.); +#182539 = EDGE_CURVE('',#182517,#182540,#182542,.T.); +#182540 = VERTEX_POINT('',#182541); +#182541 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.15)); +#182542 = SURFACE_CURVE('',#182543,(#182548,#182555),.PCURVE_S1.); +#182543 = CIRCLE('',#182544,5.E-002); +#182544 = AXIS2_PLACEMENT_3D('',#182545,#182546,#182547); +#182545 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.2)); +#182546 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#182547 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182548 = PCURVE('',#175730,#182549); +#182549 = DEFINITIONAL_REPRESENTATION('',(#182550),#182554); +#182550 = CIRCLE('',#182551,5.E-002); +#182551 = AXIS2_PLACEMENT_2D('',#182552,#182553); +#182552 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#182553 = DIRECTION('',(-1.,0.E+000)); +#182554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182555 = PCURVE('',#182343,#182556); +#182556 = DEFINITIONAL_REPRESENTATION('',(#182557),#182560); +#182557 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182558,#182559), + .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), + .PIECEWISE_BEZIER_KNOTS.); +#182558 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#182559 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182561 = ORIENTED_EDGE('',*,*,#182562,.T.); +#182562 = EDGE_CURVE('',#182540,#182563,#182565,.T.); +#182563 = VERTEX_POINT('',#182564); +#182564 = CARTESIAN_POINT('',(0.475,-1.4,0.15)); +#182565 = SURFACE_CURVE('',#182566,(#182570,#182577),.PCURVE_S1.); +#182566 = LINE('',#182567,#182568); +#182567 = CARTESIAN_POINT('',(0.475,-1.4,0.15)); +#182568 = VECTOR('',#182569,1.); +#182569 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#182570 = PCURVE('',#175730,#182571); +#182571 = DEFINITIONAL_REPRESENTATION('',(#182572),#182576); +#182572 = LINE('',#182573,#182574); +#182573 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#182574 = VECTOR('',#182575,1.); +#182575 = DIRECTION('',(0.E+000,-1.)); +#182576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182577 = PCURVE('',#182314,#182578); +#182578 = DEFINITIONAL_REPRESENTATION('',(#182579),#182583); +#182579 = LINE('',#182580,#182581); +#182580 = CARTESIAN_POINT('',(0.34,0.E+000)); +#182581 = VECTOR('',#182582,1.); +#182582 = DIRECTION('',(0.E+000,-1.)); +#182583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182584 = ORIENTED_EDGE('',*,*,#182585,.T.); +#182585 = EDGE_CURVE('',#182563,#182586,#182588,.T.); +#182586 = VERTEX_POINT('',#182587); +#182587 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); +#182588 = SURFACE_CURVE('',#182589,(#182593,#182600),.PCURVE_S1.); +#182589 = LINE('',#182590,#182591); +#182590 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); +#182591 = VECTOR('',#182592,1.); +#182592 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182593 = PCURVE('',#175730,#182594); +#182594 = DEFINITIONAL_REPRESENTATION('',(#182595),#182599); +#182595 = LINE('',#182596,#182597); +#182596 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#182597 = VECTOR('',#182598,1.); +#182598 = DIRECTION('',(-1.,0.E+000)); +#182599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182600 = PCURVE('',#182286,#182601); +#182601 = DEFINITIONAL_REPRESENTATION('',(#182602),#182606); +#182602 = LINE('',#182603,#182604); +#182603 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182604 = VECTOR('',#182605,1.); +#182605 = DIRECTION('',(1.,0.E+000)); +#182606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182607 = ORIENTED_EDGE('',*,*,#182608,.T.); +#182608 = EDGE_CURVE('',#182586,#182609,#182611,.T.); +#182609 = VERTEX_POINT('',#182610); +#182610 = CARTESIAN_POINT('',(0.475,-1.1307673058,-1.210057767209E-016) + ); +#182611 = SURFACE_CURVE('',#182612,(#182616,#182623),.PCURVE_S1.); +#182612 = LINE('',#182613,#182614); +#182613 = CARTESIAN_POINT('',(0.475,-1.4,-6.679566809664E-017)); +#182614 = VECTOR('',#182615,1.); +#182615 = DIRECTION('',(0.E+000,1.,0.E+000)); +#182616 = PCURVE('',#175730,#182617); +#182617 = DEFINITIONAL_REPRESENTATION('',(#182618),#182622); +#182618 = LINE('',#182619,#182620); +#182619 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#182620 = VECTOR('',#182621,1.); +#182621 = DIRECTION('',(0.E+000,1.)); +#182622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182623 = PCURVE('',#182258,#182624); +#182624 = DEFINITIONAL_REPRESENTATION('',(#182625),#182629); +#182625 = LINE('',#182626,#182627); +#182626 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#182627 = VECTOR('',#182628,1.); +#182628 = DIRECTION('',(0.E+000,1.)); +#182629 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182630 = ORIENTED_EDGE('',*,*,#182631,.T.); +#182631 = EDGE_CURVE('',#182609,#182632,#182634,.T.); +#182632 = VERTEX_POINT('',#182633); +#182633 = CARTESIAN_POINT('',(0.475,-0.931334836489,0.184943765921)); +#182634 = SURFACE_CURVE('',#182635,(#182640,#182651),.PCURVE_S1.); +#182635 = CIRCLE('',#182636,0.2); +#182636 = AXIS2_PLACEMENT_3D('',#182637,#182638,#182639); +#182637 = CARTESIAN_POINT('',(0.475,-1.1307673058,0.2)); +#182638 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182639 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182640 = PCURVE('',#175730,#182641); +#182641 = DEFINITIONAL_REPRESENTATION('',(#182642),#182650); +#182642 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#182643,#182644,#182645, + #182646,#182647,#182648,#182649),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180251 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#180252 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#180253 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#180254 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#180255 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#180256 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#180257 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#180258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180259 = PCURVE('',#179839,#180260); -#180260 = DEFINITIONAL_REPRESENTATION('',(#180261),#180264); -#180261 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180262,#180263), +#182643 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#182644 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#182645 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#182646 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#182647 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#182648 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#182649 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#182650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182651 = PCURVE('',#182231,#182652); +#182652 = DEFINITIONAL_REPRESENTATION('',(#182653),#182656); +#182653 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182654,#182655), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#180262 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180263 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#180264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180265 = ORIENTED_EDGE('',*,*,#180266,.T.); -#180266 = EDGE_CURVE('',#180240,#180267,#180269,.T.); -#180267 = VERTEX_POINT('',#180268); -#180268 = CARTESIAN_POINT('',(0.475,-0.906981201809,0.50752811704)); -#180269 = SURFACE_CURVE('',#180270,(#180274,#180281),.PCURVE_S1.); -#180270 = LINE('',#180271,#180272); -#180271 = CARTESIAN_POINT('',(0.475,-0.931334836489,0.184943765921)); -#180272 = VECTOR('',#180273,1.); -#180273 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#180274 = PCURVE('',#173338,#180275); -#180275 = DEFINITIONAL_REPRESENTATION('',(#180276),#180280); -#180276 = LINE('',#180277,#180278); -#180277 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#180278 = VECTOR('',#180279,1.); -#180279 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#180280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180281 = PCURVE('',#179806,#180282); -#180282 = DEFINITIONAL_REPRESENTATION('',(#180283),#180287); -#180283 = LINE('',#180284,#180285); -#180284 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180285 = VECTOR('',#180286,1.); -#180286 = DIRECTION('',(1.,0.E+000)); -#180287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180288 = ORIENTED_EDGE('',*,*,#180289,.T.); -#180289 = EDGE_CURVE('',#180267,#179692,#180290,.T.); -#180290 = SURFACE_CURVE('',#180291,(#180296,#180303),.PCURVE_S1.); -#180291 = CIRCLE('',#180292,0.1); -#180292 = AXIS2_PLACEMENT_3D('',#180293,#180294,#180295); -#180293 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); -#180294 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#180295 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180296 = PCURVE('',#173338,#180297); -#180297 = DEFINITIONAL_REPRESENTATION('',(#180298),#180302); -#180298 = CIRCLE('',#180299,0.1); -#180299 = AXIS2_PLACEMENT_2D('',#180300,#180301); -#180300 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#180301 = DIRECTION('',(-1.,0.E+000)); -#180302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180303 = PCURVE('',#179730,#180304); -#180304 = DEFINITIONAL_REPRESENTATION('',(#180305),#180308); -#180305 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180306,#180307), +#182654 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182655 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#182656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182657 = ORIENTED_EDGE('',*,*,#182658,.T.); +#182658 = EDGE_CURVE('',#182632,#182659,#182661,.T.); +#182659 = VERTEX_POINT('',#182660); +#182660 = CARTESIAN_POINT('',(0.475,-0.906981201809,0.50752811704)); +#182661 = SURFACE_CURVE('',#182662,(#182666,#182673),.PCURVE_S1.); +#182662 = LINE('',#182663,#182664); +#182663 = CARTESIAN_POINT('',(0.475,-0.931334836489,0.184943765921)); +#182664 = VECTOR('',#182665,1.); +#182665 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#182666 = PCURVE('',#175730,#182667); +#182667 = DEFINITIONAL_REPRESENTATION('',(#182668),#182672); +#182668 = LINE('',#182669,#182670); +#182669 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#182670 = VECTOR('',#182671,1.); +#182671 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#182672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182673 = PCURVE('',#182198,#182674); +#182674 = DEFINITIONAL_REPRESENTATION('',(#182675),#182679); +#182675 = LINE('',#182676,#182677); +#182676 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182677 = VECTOR('',#182678,1.); +#182678 = DIRECTION('',(1.,0.E+000)); +#182679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182680 = ORIENTED_EDGE('',*,*,#182681,.T.); +#182681 = EDGE_CURVE('',#182659,#182084,#182682,.T.); +#182682 = SURFACE_CURVE('',#182683,(#182688,#182695),.PCURVE_S1.); +#182683 = CIRCLE('',#182684,0.1); +#182684 = AXIS2_PLACEMENT_3D('',#182685,#182686,#182687); +#182685 = CARTESIAN_POINT('',(0.475,-0.807264967154,0.5)); +#182686 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#182687 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#182688 = PCURVE('',#175730,#182689); +#182689 = DEFINITIONAL_REPRESENTATION('',(#182690),#182694); +#182690 = CIRCLE('',#182691,0.1); +#182691 = AXIS2_PLACEMENT_2D('',#182692,#182693); +#182692 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#182693 = DIRECTION('',(-1.,0.E+000)); +#182694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182695 = PCURVE('',#182122,#182696); +#182696 = DEFINITIONAL_REPRESENTATION('',(#182697),#182700); +#182697 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182698,#182699), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#180306 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#180307 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#180308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180309 = ADVANCED_FACE('',(#180310),#179730,.F.); -#180310 = FACE_BOUND('',#180311,.F.); -#180311 = EDGE_LOOP('',(#180312,#180313,#180314,#180334)); -#180312 = ORIENTED_EDGE('',*,*,#179714,.F.); -#180313 = ORIENTED_EDGE('',*,*,#179767,.F.); -#180314 = ORIENTED_EDGE('',*,*,#180315,.T.); -#180315 = EDGE_CURVE('',#179768,#180267,#180316,.T.); -#180316 = SURFACE_CURVE('',#180317,(#180321,#180327),.PCURVE_S1.); -#180317 = LINE('',#180318,#180319); -#180318 = CARTESIAN_POINT('',(0.135,-0.906981201809,0.50752811704)); -#180319 = VECTOR('',#180320,1.); -#180320 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180321 = PCURVE('',#179730,#180322); -#180322 = DEFINITIONAL_REPRESENTATION('',(#180323),#180326); -#180323 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180324,#180325), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180324 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#180325 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#180326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180327 = PCURVE('',#179806,#180328); -#180328 = DEFINITIONAL_REPRESENTATION('',(#180329),#180333); -#180329 = LINE('',#180330,#180331); -#180330 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#180331 = VECTOR('',#180332,1.); -#180332 = DIRECTION('',(0.E+000,1.)); -#180333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180334 = ORIENTED_EDGE('',*,*,#180289,.T.); -#180335 = ADVANCED_FACE('',(#180336),#179806,.T.); -#180336 = FACE_BOUND('',#180337,.T.); -#180337 = EDGE_LOOP('',(#180338,#180339,#180340,#180360)); -#180338 = ORIENTED_EDGE('',*,*,#180315,.T.); -#180339 = ORIENTED_EDGE('',*,*,#180266,.F.); -#180340 = ORIENTED_EDGE('',*,*,#180341,.F.); -#180341 = EDGE_CURVE('',#179791,#180240,#180342,.T.); -#180342 = SURFACE_CURVE('',#180343,(#180347,#180354),.PCURVE_S1.); -#180343 = LINE('',#180344,#180345); -#180344 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); -#180345 = VECTOR('',#180346,1.); -#180346 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180347 = PCURVE('',#179806,#180348); -#180348 = DEFINITIONAL_REPRESENTATION('',(#180349),#180353); -#180349 = LINE('',#180350,#180351); -#180350 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180351 = VECTOR('',#180352,1.); -#180352 = DIRECTION('',(0.E+000,1.)); -#180353 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180354 = PCURVE('',#179839,#180355); -#180355 = DEFINITIONAL_REPRESENTATION('',(#180356),#180359); -#180356 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180357,#180358), +#182698 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#182699 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#182700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182701 = ADVANCED_FACE('',(#182702),#182122,.F.); +#182702 = FACE_BOUND('',#182703,.F.); +#182703 = EDGE_LOOP('',(#182704,#182705,#182706,#182726)); +#182704 = ORIENTED_EDGE('',*,*,#182106,.F.); +#182705 = ORIENTED_EDGE('',*,*,#182159,.F.); +#182706 = ORIENTED_EDGE('',*,*,#182707,.T.); +#182707 = EDGE_CURVE('',#182160,#182659,#182708,.T.); +#182708 = SURFACE_CURVE('',#182709,(#182713,#182719),.PCURVE_S1.); +#182709 = LINE('',#182710,#182711); +#182710 = CARTESIAN_POINT('',(0.135,-0.906981201809,0.50752811704)); +#182711 = VECTOR('',#182712,1.); +#182712 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182713 = PCURVE('',#182122,#182714); +#182714 = DEFINITIONAL_REPRESENTATION('',(#182715),#182718); +#182715 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182716,#182717), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180357 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#180358 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#180359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#182716 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#182717 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#182718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180360 = ORIENTED_EDGE('',*,*,#179790,.T.); -#180361 = ADVANCED_FACE('',(#180362),#179839,.T.); -#180362 = FACE_BOUND('',#180363,.T.); -#180363 = EDGE_LOOP('',(#180364,#180365,#180366,#180409)); -#180364 = ORIENTED_EDGE('',*,*,#180341,.T.); -#180365 = ORIENTED_EDGE('',*,*,#180239,.F.); -#180366 = ORIENTED_EDGE('',*,*,#180367,.F.); -#180367 = EDGE_CURVE('',#179819,#180217,#180368,.T.); -#180368 = SURFACE_CURVE('',#180369,(#180373,#180402),.PCURVE_S1.); -#180369 = LINE('',#180370,#180371); -#180370 = CARTESIAN_POINT('',(0.135,-1.1307673058,-1.210057767209E-016) - ); -#180371 = VECTOR('',#180372,1.); -#180372 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180373 = PCURVE('',#179839,#180374); -#180374 = DEFINITIONAL_REPRESENTATION('',(#180375),#180401); -#180375 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#180376,#180377,#180378, - #180379,#180380,#180381,#180382,#180383,#180384,#180385,#180386, - #180387,#180388,#180389,#180390,#180391,#180392,#180393,#180394, - #180395,#180396,#180397,#180398,#180399,#180400),.UNSPECIFIED.,.F., +#182719 = PCURVE('',#182198,#182720); +#182720 = DEFINITIONAL_REPRESENTATION('',(#182721),#182725); +#182721 = LINE('',#182722,#182723); +#182722 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#182723 = VECTOR('',#182724,1.); +#182724 = DIRECTION('',(0.E+000,1.)); +#182725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182726 = ORIENTED_EDGE('',*,*,#182681,.T.); +#182727 = ADVANCED_FACE('',(#182728),#182198,.T.); +#182728 = FACE_BOUND('',#182729,.T.); +#182729 = EDGE_LOOP('',(#182730,#182731,#182732,#182752)); +#182730 = ORIENTED_EDGE('',*,*,#182707,.T.); +#182731 = ORIENTED_EDGE('',*,*,#182658,.F.); +#182732 = ORIENTED_EDGE('',*,*,#182733,.F.); +#182733 = EDGE_CURVE('',#182183,#182632,#182734,.T.); +#182734 = SURFACE_CURVE('',#182735,(#182739,#182746),.PCURVE_S1.); +#182735 = LINE('',#182736,#182737); +#182736 = CARTESIAN_POINT('',(0.135,-0.931334836489,0.184943765921)); +#182737 = VECTOR('',#182738,1.); +#182738 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182739 = PCURVE('',#182198,#182740); +#182740 = DEFINITIONAL_REPRESENTATION('',(#182741),#182745); +#182741 = LINE('',#182742,#182743); +#182742 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182743 = VECTOR('',#182744,1.); +#182744 = DIRECTION('',(0.E+000,1.)); +#182745 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182746 = PCURVE('',#182231,#182747); +#182747 = DEFINITIONAL_REPRESENTATION('',(#182748),#182751); +#182748 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182749,#182750), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); +#182749 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#182750 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#182751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182752 = ORIENTED_EDGE('',*,*,#182182,.T.); +#182753 = ADVANCED_FACE('',(#182754),#182231,.T.); +#182754 = FACE_BOUND('',#182755,.T.); +#182755 = EDGE_LOOP('',(#182756,#182757,#182758,#182801)); +#182756 = ORIENTED_EDGE('',*,*,#182733,.T.); +#182757 = ORIENTED_EDGE('',*,*,#182631,.F.); +#182758 = ORIENTED_EDGE('',*,*,#182759,.F.); +#182759 = EDGE_CURVE('',#182211,#182609,#182760,.T.); +#182760 = SURFACE_CURVE('',#182761,(#182765,#182794),.PCURVE_S1.); +#182761 = LINE('',#182762,#182763); +#182762 = CARTESIAN_POINT('',(0.135,-1.1307673058,-1.210057767209E-016) + ); +#182763 = VECTOR('',#182764,1.); +#182764 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182765 = PCURVE('',#182231,#182766); +#182766 = DEFINITIONAL_REPRESENTATION('',(#182767),#182793); +#182767 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#182768,#182769,#182770, + #182771,#182772,#182773,#182774,#182775,#182776,#182777,#182778, + #182779,#182780,#182781,#182782,#182783,#182784,#182785,#182786, + #182787,#182788,#182789,#182790,#182791,#182792),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -223397,140 +226399,140 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#180376 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180377 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) - ); -#180378 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) - ); -#180379 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) - ); -#180380 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) - ); -#180381 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) - ); -#180382 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) - ); -#180383 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) - ); -#180384 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); -#180385 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); -#180386 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); -#180387 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); -#180388 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); -#180389 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); -#180390 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); -#180391 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); -#180392 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); -#180393 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); -#180394 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); -#180395 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); -#180396 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); -#180397 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); -#180398 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); -#180399 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); -#180400 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180402 = PCURVE('',#179866,#180403); -#180403 = DEFINITIONAL_REPRESENTATION('',(#180404),#180408); -#180404 = LINE('',#180405,#180406); -#180405 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#180406 = VECTOR('',#180407,1.); -#180407 = DIRECTION('',(-1.,0.E+000)); -#180408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180409 = ORIENTED_EDGE('',*,*,#179818,.T.); -#180410 = ADVANCED_FACE('',(#180411),#179866,.T.); -#180411 = FACE_BOUND('',#180412,.T.); -#180412 = EDGE_LOOP('',(#180413,#180414,#180415,#180436)); -#180413 = ORIENTED_EDGE('',*,*,#180367,.T.); -#180414 = ORIENTED_EDGE('',*,*,#180216,.F.); -#180415 = ORIENTED_EDGE('',*,*,#180416,.F.); -#180416 = EDGE_CURVE('',#179851,#180194,#180417,.T.); -#180417 = SURFACE_CURVE('',#180418,(#180422,#180429),.PCURVE_S1.); -#180418 = LINE('',#180419,#180420); -#180419 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); -#180420 = VECTOR('',#180421,1.); -#180421 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180422 = PCURVE('',#179866,#180423); -#180423 = DEFINITIONAL_REPRESENTATION('',(#180424),#180428); -#180424 = LINE('',#180425,#180426); -#180425 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180426 = VECTOR('',#180427,1.); -#180427 = DIRECTION('',(-1.,0.E+000)); -#180428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180429 = PCURVE('',#179894,#180430); -#180430 = DEFINITIONAL_REPRESENTATION('',(#180431),#180435); -#180431 = LINE('',#180432,#180433); -#180432 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180433 = VECTOR('',#180434,1.); -#180434 = DIRECTION('',(0.E+000,1.)); -#180435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180436 = ORIENTED_EDGE('',*,*,#179850,.T.); -#180437 = ADVANCED_FACE('',(#180438),#179894,.T.); -#180438 = FACE_BOUND('',#180439,.T.); -#180439 = EDGE_LOOP('',(#180440,#180441,#180442,#180463)); -#180440 = ORIENTED_EDGE('',*,*,#180416,.T.); -#180441 = ORIENTED_EDGE('',*,*,#180193,.F.); -#180442 = ORIENTED_EDGE('',*,*,#180443,.F.); -#180443 = EDGE_CURVE('',#179879,#180171,#180444,.T.); -#180444 = SURFACE_CURVE('',#180445,(#180449,#180456),.PCURVE_S1.); -#180445 = LINE('',#180446,#180447); -#180446 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); -#180447 = VECTOR('',#180448,1.); -#180448 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180449 = PCURVE('',#179894,#180450); -#180450 = DEFINITIONAL_REPRESENTATION('',(#180451),#180455); -#180451 = LINE('',#180452,#180453); -#180452 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#180453 = VECTOR('',#180454,1.); -#180454 = DIRECTION('',(0.E+000,1.)); -#180455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180456 = PCURVE('',#179922,#180457); -#180457 = DEFINITIONAL_REPRESENTATION('',(#180458),#180462); -#180458 = LINE('',#180459,#180460); -#180459 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180460 = VECTOR('',#180461,1.); -#180461 = DIRECTION('',(1.,0.E+000)); -#180462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180463 = ORIENTED_EDGE('',*,*,#179878,.T.); -#180464 = ADVANCED_FACE('',(#180465),#179922,.T.); -#180465 = FACE_BOUND('',#180466,.T.); -#180466 = EDGE_LOOP('',(#180467,#180468,#180469,#180512)); -#180467 = ORIENTED_EDGE('',*,*,#180443,.T.); -#180468 = ORIENTED_EDGE('',*,*,#180170,.F.); -#180469 = ORIENTED_EDGE('',*,*,#180470,.F.); -#180470 = EDGE_CURVE('',#179907,#180148,#180471,.T.); -#180471 = SURFACE_CURVE('',#180472,(#180476,#180483),.PCURVE_S1.); -#180472 = LINE('',#180473,#180474); -#180473 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.15)); -#180474 = VECTOR('',#180475,1.); -#180475 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180476 = PCURVE('',#179922,#180477); -#180477 = DEFINITIONAL_REPRESENTATION('',(#180478),#180482); -#180478 = LINE('',#180479,#180480); -#180479 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#180480 = VECTOR('',#180481,1.); -#180481 = DIRECTION('',(1.,0.E+000)); -#180482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180483 = PCURVE('',#179951,#180484); -#180484 = DEFINITIONAL_REPRESENTATION('',(#180485),#180511); -#180485 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#180486,#180487,#180488, - #180489,#180490,#180491,#180492,#180493,#180494,#180495,#180496, - #180497,#180498,#180499,#180500,#180501,#180502,#180503,#180504, - #180505,#180506,#180507,#180508,#180509,#180510),.UNSPECIFIED.,.F., +#182768 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182769 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) + ); +#182770 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) + ); +#182771 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) + ); +#182772 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) + ); +#182773 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) + ); +#182774 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) + ); +#182775 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) + ); +#182776 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); +#182777 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); +#182778 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); +#182779 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); +#182780 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); +#182781 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); +#182782 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); +#182783 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); +#182784 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); +#182785 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); +#182786 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); +#182787 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); +#182788 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); +#182789 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); +#182790 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); +#182791 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); +#182792 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182794 = PCURVE('',#182258,#182795); +#182795 = DEFINITIONAL_REPRESENTATION('',(#182796),#182800); +#182796 = LINE('',#182797,#182798); +#182797 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#182798 = VECTOR('',#182799,1.); +#182799 = DIRECTION('',(-1.,0.E+000)); +#182800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182801 = ORIENTED_EDGE('',*,*,#182210,.T.); +#182802 = ADVANCED_FACE('',(#182803),#182258,.T.); +#182803 = FACE_BOUND('',#182804,.T.); +#182804 = EDGE_LOOP('',(#182805,#182806,#182807,#182828)); +#182805 = ORIENTED_EDGE('',*,*,#182759,.T.); +#182806 = ORIENTED_EDGE('',*,*,#182608,.F.); +#182807 = ORIENTED_EDGE('',*,*,#182808,.F.); +#182808 = EDGE_CURVE('',#182243,#182586,#182809,.T.); +#182809 = SURFACE_CURVE('',#182810,(#182814,#182821),.PCURVE_S1.); +#182810 = LINE('',#182811,#182812); +#182811 = CARTESIAN_POINT('',(0.135,-1.4,-6.679566809664E-017)); +#182812 = VECTOR('',#182813,1.); +#182813 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182814 = PCURVE('',#182258,#182815); +#182815 = DEFINITIONAL_REPRESENTATION('',(#182816),#182820); +#182816 = LINE('',#182817,#182818); +#182817 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182818 = VECTOR('',#182819,1.); +#182819 = DIRECTION('',(-1.,0.E+000)); +#182820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182821 = PCURVE('',#182286,#182822); +#182822 = DEFINITIONAL_REPRESENTATION('',(#182823),#182827); +#182823 = LINE('',#182824,#182825); +#182824 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182825 = VECTOR('',#182826,1.); +#182826 = DIRECTION('',(0.E+000,1.)); +#182827 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182828 = ORIENTED_EDGE('',*,*,#182242,.T.); +#182829 = ADVANCED_FACE('',(#182830),#182286,.T.); +#182830 = FACE_BOUND('',#182831,.T.); +#182831 = EDGE_LOOP('',(#182832,#182833,#182834,#182855)); +#182832 = ORIENTED_EDGE('',*,*,#182808,.T.); +#182833 = ORIENTED_EDGE('',*,*,#182585,.F.); +#182834 = ORIENTED_EDGE('',*,*,#182835,.F.); +#182835 = EDGE_CURVE('',#182271,#182563,#182836,.T.); +#182836 = SURFACE_CURVE('',#182837,(#182841,#182848),.PCURVE_S1.); +#182837 = LINE('',#182838,#182839); +#182838 = CARTESIAN_POINT('',(0.135,-1.4,0.15)); +#182839 = VECTOR('',#182840,1.); +#182840 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182841 = PCURVE('',#182286,#182842); +#182842 = DEFINITIONAL_REPRESENTATION('',(#182843),#182847); +#182843 = LINE('',#182844,#182845); +#182844 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#182845 = VECTOR('',#182846,1.); +#182846 = DIRECTION('',(0.E+000,1.)); +#182847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182848 = PCURVE('',#182314,#182849); +#182849 = DEFINITIONAL_REPRESENTATION('',(#182850),#182854); +#182850 = LINE('',#182851,#182852); +#182851 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182852 = VECTOR('',#182853,1.); +#182853 = DIRECTION('',(1.,0.E+000)); +#182854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182855 = ORIENTED_EDGE('',*,*,#182270,.T.); +#182856 = ADVANCED_FACE('',(#182857),#182314,.T.); +#182857 = FACE_BOUND('',#182858,.T.); +#182858 = EDGE_LOOP('',(#182859,#182860,#182861,#182904)); +#182859 = ORIENTED_EDGE('',*,*,#182835,.T.); +#182860 = ORIENTED_EDGE('',*,*,#182562,.F.); +#182861 = ORIENTED_EDGE('',*,*,#182862,.F.); +#182862 = EDGE_CURVE('',#182299,#182540,#182863,.T.); +#182863 = SURFACE_CURVE('',#182864,(#182868,#182875),.PCURVE_S1.); +#182864 = LINE('',#182865,#182866); +#182865 = CARTESIAN_POINT('',(0.135,-1.1307673058,0.15)); +#182866 = VECTOR('',#182867,1.); +#182867 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182868 = PCURVE('',#182314,#182869); +#182869 = DEFINITIONAL_REPRESENTATION('',(#182870),#182874); +#182870 = LINE('',#182871,#182872); +#182871 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#182872 = VECTOR('',#182873,1.); +#182873 = DIRECTION('',(1.,0.E+000)); +#182874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182875 = PCURVE('',#182343,#182876); +#182876 = DEFINITIONAL_REPRESENTATION('',(#182877),#182903); +#182877 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#182878,#182879,#182880, + #182881,#182882,#182883,#182884,#182885,#182886,#182887,#182888, + #182889,#182890,#182891,#182892,#182893,#182894,#182895,#182896, + #182897,#182898,#182899,#182900,#182901,#182902),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -223538,955 +226540,955 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#180486 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180487 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); -#180488 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) - ); -#180489 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); -#180490 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) - ); -#180491 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) - ); -#180492 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) - ); -#180493 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) - ); -#180494 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); -#180495 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); -#180496 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); -#180497 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); -#180498 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); -#180499 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); -#180500 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); -#180501 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); -#180502 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); -#180503 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); -#180504 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); -#180505 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); -#180506 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); -#180507 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); -#180508 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); -#180509 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); -#180510 = CARTESIAN_POINT('',(0.E+000,0.34)); -#180511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180512 = ORIENTED_EDGE('',*,*,#179906,.T.); -#180513 = ADVANCED_FACE('',(#180514),#179951,.F.); -#180514 = FACE_BOUND('',#180515,.F.); -#180515 = EDGE_LOOP('',(#180516,#180517,#180518,#180538)); -#180516 = ORIENTED_EDGE('',*,*,#180470,.F.); -#180517 = ORIENTED_EDGE('',*,*,#179934,.F.); -#180518 = ORIENTED_EDGE('',*,*,#180519,.T.); -#180519 = EDGE_CURVE('',#179935,#180125,#180520,.T.); -#180520 = SURFACE_CURVE('',#180521,(#180525,#180531),.PCURVE_S1.); -#180521 = LINE('',#180522,#180523); -#180522 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); -#180523 = VECTOR('',#180524,1.); -#180524 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180525 = PCURVE('',#179951,#180526); -#180526 = DEFINITIONAL_REPRESENTATION('',(#180527),#180530); -#180527 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180528,#180529), +#182878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182879 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); +#182880 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) + ); +#182881 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); +#182882 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) + ); +#182883 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) + ); +#182884 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) + ); +#182885 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) + ); +#182886 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); +#182887 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); +#182888 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); +#182889 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); +#182890 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); +#182891 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); +#182892 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); +#182893 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); +#182894 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); +#182895 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); +#182896 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); +#182897 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); +#182898 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); +#182899 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); +#182900 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); +#182901 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); +#182902 = CARTESIAN_POINT('',(0.E+000,0.34)); +#182903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182904 = ORIENTED_EDGE('',*,*,#182298,.T.); +#182905 = ADVANCED_FACE('',(#182906),#182343,.F.); +#182906 = FACE_BOUND('',#182907,.F.); +#182907 = EDGE_LOOP('',(#182908,#182909,#182910,#182930)); +#182908 = ORIENTED_EDGE('',*,*,#182862,.F.); +#182909 = ORIENTED_EDGE('',*,*,#182326,.F.); +#182910 = ORIENTED_EDGE('',*,*,#182911,.T.); +#182911 = EDGE_CURVE('',#182327,#182517,#182912,.T.); +#182912 = SURFACE_CURVE('',#182913,(#182917,#182923),.PCURVE_S1.); +#182913 = LINE('',#182914,#182915); +#182914 = CARTESIAN_POINT('',(0.135,-1.080909188472,0.19623594148)); +#182915 = VECTOR('',#182916,1.); +#182916 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182917 = PCURVE('',#182343,#182918); +#182918 = DEFINITIONAL_REPRESENTATION('',(#182919),#182922); +#182919 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182920,#182921), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180528 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#180529 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#180530 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180531 = PCURVE('',#179978,#180532); -#180532 = DEFINITIONAL_REPRESENTATION('',(#180533),#180537); -#180533 = LINE('',#180534,#180535); -#180534 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180535 = VECTOR('',#180536,1.); -#180536 = DIRECTION('',(0.E+000,1.)); -#180537 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180538 = ORIENTED_EDGE('',*,*,#180147,.T.); -#180539 = ADVANCED_FACE('',(#180540),#179978,.T.); -#180540 = FACE_BOUND('',#180541,.T.); -#180541 = EDGE_LOOP('',(#180542,#180543,#180544,#180564)); -#180542 = ORIENTED_EDGE('',*,*,#180519,.T.); -#180543 = ORIENTED_EDGE('',*,*,#180124,.F.); -#180544 = ORIENTED_EDGE('',*,*,#180545,.F.); -#180545 = EDGE_CURVE('',#179963,#180098,#180546,.T.); -#180546 = SURFACE_CURVE('',#180547,(#180551,#180558),.PCURVE_S1.); -#180547 = LINE('',#180548,#180549); -#180548 = CARTESIAN_POINT('',(0.135,-1.056555553792,0.518820292599)); -#180549 = VECTOR('',#180550,1.); -#180550 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180551 = PCURVE('',#179978,#180552); -#180552 = DEFINITIONAL_REPRESENTATION('',(#180553),#180557); -#180553 = LINE('',#180554,#180555); -#180554 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#180555 = VECTOR('',#180556,1.); -#180556 = DIRECTION('',(0.E+000,1.)); -#180557 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180558 = PCURVE('',#180011,#180559); -#180559 = DEFINITIONAL_REPRESENTATION('',(#180560),#180563); -#180560 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180561,#180562), +#182920 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#182921 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#182922 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182923 = PCURVE('',#182370,#182924); +#182924 = DEFINITIONAL_REPRESENTATION('',(#182925),#182929); +#182925 = LINE('',#182926,#182927); +#182926 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#182927 = VECTOR('',#182928,1.); +#182928 = DIRECTION('',(0.E+000,1.)); +#182929 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182930 = ORIENTED_EDGE('',*,*,#182539,.T.); +#182931 = ADVANCED_FACE('',(#182932),#182370,.T.); +#182932 = FACE_BOUND('',#182933,.T.); +#182933 = EDGE_LOOP('',(#182934,#182935,#182936,#182956)); +#182934 = ORIENTED_EDGE('',*,*,#182911,.T.); +#182935 = ORIENTED_EDGE('',*,*,#182516,.F.); +#182936 = ORIENTED_EDGE('',*,*,#182937,.F.); +#182937 = EDGE_CURVE('',#182355,#182490,#182938,.T.); +#182938 = SURFACE_CURVE('',#182939,(#182943,#182950),.PCURVE_S1.); +#182939 = LINE('',#182940,#182941); +#182940 = CARTESIAN_POINT('',(0.135,-1.056555553792,0.518820292599)); +#182941 = VECTOR('',#182942,1.); +#182942 = DIRECTION('',(1.,0.E+000,0.E+000)); +#182943 = PCURVE('',#182370,#182944); +#182944 = DEFINITIONAL_REPRESENTATION('',(#182945),#182949); +#182945 = LINE('',#182946,#182947); +#182946 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#182947 = VECTOR('',#182948,1.); +#182948 = DIRECTION('',(0.E+000,1.)); +#182949 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182950 = PCURVE('',#182403,#182951); +#182951 = DEFINITIONAL_REPRESENTATION('',(#182952),#182955); +#182952 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182953,#182954), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180561 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#180562 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#180563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180564 = ORIENTED_EDGE('',*,*,#179962,.T.); -#180565 = ADVANCED_FACE('',(#180566),#180011,.T.); -#180566 = FACE_BOUND('',#180567,.T.); -#180567 = EDGE_LOOP('',(#180568,#180569,#180570,#180571)); -#180568 = ORIENTED_EDGE('',*,*,#180545,.T.); -#180569 = ORIENTED_EDGE('',*,*,#180097,.F.); -#180570 = ORIENTED_EDGE('',*,*,#180046,.F.); -#180571 = ORIENTED_EDGE('',*,*,#179990,.T.); -#180572 = ADVANCED_FACE('',(#180573),#172034,.T.); -#180573 = FACE_BOUND('',#180574,.T.); -#180574 = EDGE_LOOP('',(#180575,#180576,#180599,#180626)); -#180575 = ORIENTED_EDGE('',*,*,#172018,.T.); -#180576 = ORIENTED_EDGE('',*,*,#180577,.F.); -#180577 = EDGE_CURVE('',#180578,#171996,#180580,.T.); -#180578 = VERTEX_POINT('',#180579); -#180579 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.6)); -#180580 = SURFACE_CURVE('',#180581,(#180585,#180592),.PCURVE_S1.); -#180581 = LINE('',#180582,#180583); -#180582 = CARTESIAN_POINT('',(-0.175,-0.7,0.6)); -#180583 = VECTOR('',#180584,1.); -#180584 = DIRECTION('',(0.E+000,1.,0.E+000)); -#180585 = PCURVE('',#172034,#180586); -#180586 = DEFINITIONAL_REPRESENTATION('',(#180587),#180591); -#180587 = LINE('',#180588,#180589); -#180588 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#180589 = VECTOR('',#180590,1.); -#180590 = DIRECTION('',(0.E+000,1.)); -#180591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180592 = PCURVE('',#173255,#180593); -#180593 = DEFINITIONAL_REPRESENTATION('',(#180594),#180598); -#180594 = LINE('',#180595,#180596); -#180595 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#180596 = VECTOR('',#180597,1.); -#180597 = DIRECTION('',(0.E+000,1.)); -#180598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180599 = ORIENTED_EDGE('',*,*,#180600,.F.); -#180600 = EDGE_CURVE('',#180601,#180578,#180603,.T.); -#180601 = VERTEX_POINT('',#180602); -#180602 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.6)); -#180603 = SURFACE_CURVE('',#180604,(#180608,#180615),.PCURVE_S1.); -#180604 = LINE('',#180605,#180606); -#180605 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.6)); -#180606 = VECTOR('',#180607,1.); -#180607 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180608 = PCURVE('',#172034,#180609); -#180609 = DEFINITIONAL_REPRESENTATION('',(#180610),#180614); -#180610 = LINE('',#180611,#180612); -#180611 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); -#180612 = VECTOR('',#180613,1.); -#180613 = DIRECTION('',(-1.,0.E+000)); -#180614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180615 = PCURVE('',#180616,#180621); -#180616 = CYLINDRICAL_SURFACE('',#180617,0.1); -#180617 = AXIS2_PLACEMENT_3D('',#180618,#180619,#180620); -#180618 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); -#180619 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180620 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180621 = DEFINITIONAL_REPRESENTATION('',(#180622),#180625); -#180622 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180623,#180624), +#182953 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#182954 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#182955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182956 = ORIENTED_EDGE('',*,*,#182354,.T.); +#182957 = ADVANCED_FACE('',(#182958),#182403,.T.); +#182958 = FACE_BOUND('',#182959,.T.); +#182959 = EDGE_LOOP('',(#182960,#182961,#182962,#182963)); +#182960 = ORIENTED_EDGE('',*,*,#182937,.T.); +#182961 = ORIENTED_EDGE('',*,*,#182489,.F.); +#182962 = ORIENTED_EDGE('',*,*,#182438,.F.); +#182963 = ORIENTED_EDGE('',*,*,#182382,.T.); +#182964 = ADVANCED_FACE('',(#182965),#174426,.T.); +#182965 = FACE_BOUND('',#182966,.T.); +#182966 = EDGE_LOOP('',(#182967,#182968,#182991,#183018)); +#182967 = ORIENTED_EDGE('',*,*,#174410,.T.); +#182968 = ORIENTED_EDGE('',*,*,#182969,.F.); +#182969 = EDGE_CURVE('',#182970,#174388,#182972,.T.); +#182970 = VERTEX_POINT('',#182971); +#182971 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.6)); +#182972 = SURFACE_CURVE('',#182973,(#182977,#182984),.PCURVE_S1.); +#182973 = LINE('',#182974,#182975); +#182974 = CARTESIAN_POINT('',(-0.175,-0.7,0.6)); +#182975 = VECTOR('',#182976,1.); +#182976 = DIRECTION('',(0.E+000,1.,0.E+000)); +#182977 = PCURVE('',#174426,#182978); +#182978 = DEFINITIONAL_REPRESENTATION('',(#182979),#182983); +#182979 = LINE('',#182980,#182981); +#182980 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#182981 = VECTOR('',#182982,1.); +#182982 = DIRECTION('',(0.E+000,1.)); +#182983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182984 = PCURVE('',#175647,#182985); +#182985 = DEFINITIONAL_REPRESENTATION('',(#182986),#182990); +#182986 = LINE('',#182987,#182988); +#182987 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#182988 = VECTOR('',#182989,1.); +#182989 = DIRECTION('',(0.E+000,1.)); +#182990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#182991 = ORIENTED_EDGE('',*,*,#182992,.F.); +#182992 = EDGE_CURVE('',#182993,#182970,#182995,.T.); +#182993 = VERTEX_POINT('',#182994); +#182994 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.6)); +#182995 = SURFACE_CURVE('',#182996,(#183000,#183007),.PCURVE_S1.); +#182996 = LINE('',#182997,#182998); +#182997 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.6)); +#182998 = VECTOR('',#182999,1.); +#182999 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183000 = PCURVE('',#174426,#183001); +#183001 = DEFINITIONAL_REPRESENTATION('',(#183002),#183006); +#183002 = LINE('',#183003,#183004); +#183003 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); +#183004 = VECTOR('',#183005,1.); +#183005 = DIRECTION('',(-1.,0.E+000)); +#183006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183007 = PCURVE('',#183008,#183013); +#183008 = CYLINDRICAL_SURFACE('',#183009,0.1); +#183009 = AXIS2_PLACEMENT_3D('',#183010,#183011,#183012); +#183010 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); +#183011 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183012 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183013 = DEFINITIONAL_REPRESENTATION('',(#183014),#183017); +#183014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183015,#183016), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180623 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180624 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#180625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180626 = ORIENTED_EDGE('',*,*,#180627,.T.); -#180627 = EDGE_CURVE('',#180601,#172019,#180628,.T.); -#180628 = SURFACE_CURVE('',#180629,(#180633,#180640),.PCURVE_S1.); -#180629 = LINE('',#180630,#180631); -#180630 = CARTESIAN_POINT('',(-0.515,-0.7,0.6)); -#180631 = VECTOR('',#180632,1.); -#180632 = DIRECTION('',(0.E+000,1.,0.E+000)); -#180633 = PCURVE('',#172034,#180634); -#180634 = DEFINITIONAL_REPRESENTATION('',(#180635),#180639); -#180635 = LINE('',#180636,#180637); -#180636 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180637 = VECTOR('',#180638,1.); -#180638 = DIRECTION('',(0.E+000,1.)); -#180639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180640 = PCURVE('',#173201,#180641); -#180641 = DEFINITIONAL_REPRESENTATION('',(#180642),#180646); -#180642 = LINE('',#180643,#180644); -#180643 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#180644 = VECTOR('',#180645,1.); -#180645 = DIRECTION('',(0.E+000,1.)); -#180646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180647 = ADVANCED_FACE('',(#180648),#173201,.T.); -#180648 = FACE_BOUND('',#180649,.T.); -#180649 = EDGE_LOOP('',(#180650,#180651,#180652,#180675,#180703,#180735, - #180763,#180791,#180819,#180847,#180875,#180907)); -#180650 = ORIENTED_EDGE('',*,*,#173185,.F.); -#180651 = ORIENTED_EDGE('',*,*,#180627,.F.); -#180652 = ORIENTED_EDGE('',*,*,#180653,.F.); -#180653 = EDGE_CURVE('',#180654,#180601,#180656,.T.); -#180654 = VERTEX_POINT('',#180655); -#180655 = CARTESIAN_POINT('',(-0.515,-0.906981201809,0.50752811704)); -#180656 = SURFACE_CURVE('',#180657,(#180662,#180669),.PCURVE_S1.); -#180657 = CIRCLE('',#180658,0.1); -#180658 = AXIS2_PLACEMENT_3D('',#180659,#180660,#180661); -#180659 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); -#180660 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#180661 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180662 = PCURVE('',#173201,#180663); -#180663 = DEFINITIONAL_REPRESENTATION('',(#180664),#180668); -#180664 = CIRCLE('',#180665,0.1); -#180665 = AXIS2_PLACEMENT_2D('',#180666,#180667); -#180666 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#180667 = DIRECTION('',(-1.,0.E+000)); -#180668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180669 = PCURVE('',#180616,#180670); -#180670 = DEFINITIONAL_REPRESENTATION('',(#180671),#180674); -#180671 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180672,#180673), +#183015 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183016 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#183017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183018 = ORIENTED_EDGE('',*,*,#183019,.T.); +#183019 = EDGE_CURVE('',#182993,#174411,#183020,.T.); +#183020 = SURFACE_CURVE('',#183021,(#183025,#183032),.PCURVE_S1.); +#183021 = LINE('',#183022,#183023); +#183022 = CARTESIAN_POINT('',(-0.515,-0.7,0.6)); +#183023 = VECTOR('',#183024,1.); +#183024 = DIRECTION('',(0.E+000,1.,0.E+000)); +#183025 = PCURVE('',#174426,#183026); +#183026 = DEFINITIONAL_REPRESENTATION('',(#183027),#183031); +#183027 = LINE('',#183028,#183029); +#183028 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183029 = VECTOR('',#183030,1.); +#183030 = DIRECTION('',(0.E+000,1.)); +#183031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183032 = PCURVE('',#175593,#183033); +#183033 = DEFINITIONAL_REPRESENTATION('',(#183034),#183038); +#183034 = LINE('',#183035,#183036); +#183035 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#183036 = VECTOR('',#183037,1.); +#183037 = DIRECTION('',(0.E+000,1.)); +#183038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183039 = ADVANCED_FACE('',(#183040),#175593,.T.); +#183040 = FACE_BOUND('',#183041,.T.); +#183041 = EDGE_LOOP('',(#183042,#183043,#183044,#183067,#183095,#183127, + #183155,#183183,#183211,#183239,#183267,#183299)); +#183042 = ORIENTED_EDGE('',*,*,#175577,.F.); +#183043 = ORIENTED_EDGE('',*,*,#183019,.F.); +#183044 = ORIENTED_EDGE('',*,*,#183045,.F.); +#183045 = EDGE_CURVE('',#183046,#182993,#183048,.T.); +#183046 = VERTEX_POINT('',#183047); +#183047 = CARTESIAN_POINT('',(-0.515,-0.906981201809,0.50752811704)); +#183048 = SURFACE_CURVE('',#183049,(#183054,#183061),.PCURVE_S1.); +#183049 = CIRCLE('',#183050,0.1); +#183050 = AXIS2_PLACEMENT_3D('',#183051,#183052,#183053); +#183051 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); +#183052 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183053 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183054 = PCURVE('',#175593,#183055); +#183055 = DEFINITIONAL_REPRESENTATION('',(#183056),#183060); +#183056 = CIRCLE('',#183057,0.1); +#183057 = AXIS2_PLACEMENT_2D('',#183058,#183059); +#183058 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#183059 = DIRECTION('',(-1.,0.E+000)); +#183060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183061 = PCURVE('',#183008,#183062); +#183062 = DEFINITIONAL_REPRESENTATION('',(#183063),#183066); +#183063 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183064,#183065), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#180672 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#180673 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180675 = ORIENTED_EDGE('',*,*,#180676,.F.); -#180676 = EDGE_CURVE('',#180677,#180654,#180679,.T.); -#180677 = VERTEX_POINT('',#180678); -#180678 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); -#180679 = SURFACE_CURVE('',#180680,(#180684,#180691),.PCURVE_S1.); -#180680 = LINE('',#180681,#180682); -#180681 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); -#180682 = VECTOR('',#180683,1.); -#180683 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#180684 = PCURVE('',#173201,#180685); -#180685 = DEFINITIONAL_REPRESENTATION('',(#180686),#180690); -#180686 = LINE('',#180687,#180688); -#180687 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#180688 = VECTOR('',#180689,1.); -#180689 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#180690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180691 = PCURVE('',#180692,#180697); -#180692 = PLANE('',#180693); -#180693 = AXIS2_PLACEMENT_3D('',#180694,#180695,#180696); -#180694 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); -#180695 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); -#180696 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#180697 = DEFINITIONAL_REPRESENTATION('',(#180698),#180702); -#180698 = LINE('',#180699,#180700); -#180699 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180700 = VECTOR('',#180701,1.); -#180701 = DIRECTION('',(1.,0.E+000)); -#180702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180703 = ORIENTED_EDGE('',*,*,#180704,.F.); -#180704 = EDGE_CURVE('',#180705,#180677,#180707,.T.); -#180705 = VERTEX_POINT('',#180706); -#180706 = CARTESIAN_POINT('',(-0.515,-1.1307673058,-1.878014448176E-016) - ); -#180707 = SURFACE_CURVE('',#180708,(#180713,#180724),.PCURVE_S1.); -#180708 = CIRCLE('',#180709,0.2); -#180709 = AXIS2_PLACEMENT_3D('',#180710,#180711,#180712); -#180710 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); -#180711 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180712 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180713 = PCURVE('',#173201,#180714); -#180714 = DEFINITIONAL_REPRESENTATION('',(#180715),#180723); -#180715 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180716,#180717,#180718, - #180719,#180720,#180721,#180722),.UNSPECIFIED.,.T.,.F.) +#183064 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#183065 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183067 = ORIENTED_EDGE('',*,*,#183068,.F.); +#183068 = EDGE_CURVE('',#183069,#183046,#183071,.T.); +#183069 = VERTEX_POINT('',#183070); +#183070 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); +#183071 = SURFACE_CURVE('',#183072,(#183076,#183083),.PCURVE_S1.); +#183072 = LINE('',#183073,#183074); +#183073 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); +#183074 = VECTOR('',#183075,1.); +#183075 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#183076 = PCURVE('',#175593,#183077); +#183077 = DEFINITIONAL_REPRESENTATION('',(#183078),#183082); +#183078 = LINE('',#183079,#183080); +#183079 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#183080 = VECTOR('',#183081,1.); +#183081 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#183082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183083 = PCURVE('',#183084,#183089); +#183084 = PLANE('',#183085); +#183085 = AXIS2_PLACEMENT_3D('',#183086,#183087,#183088); +#183086 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); +#183087 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); +#183088 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#183089 = DEFINITIONAL_REPRESENTATION('',(#183090),#183094); +#183090 = LINE('',#183091,#183092); +#183091 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183092 = VECTOR('',#183093,1.); +#183093 = DIRECTION('',(1.,0.E+000)); +#183094 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183095 = ORIENTED_EDGE('',*,*,#183096,.F.); +#183096 = EDGE_CURVE('',#183097,#183069,#183099,.T.); +#183097 = VERTEX_POINT('',#183098); +#183098 = CARTESIAN_POINT('',(-0.515,-1.1307673058,-1.878014448176E-016) + ); +#183099 = SURFACE_CURVE('',#183100,(#183105,#183116),.PCURVE_S1.); +#183100 = CIRCLE('',#183101,0.2); +#183101 = AXIS2_PLACEMENT_3D('',#183102,#183103,#183104); +#183102 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); +#183103 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183104 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183105 = PCURVE('',#175593,#183106); +#183106 = DEFINITIONAL_REPRESENTATION('',(#183107),#183115); +#183107 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#183108,#183109,#183110, + #183111,#183112,#183113,#183114),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180716 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#180717 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#180718 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#180719 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#180720 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#180721 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#180722 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#180723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180724 = PCURVE('',#180725,#180730); -#180725 = CYLINDRICAL_SURFACE('',#180726,0.2); -#180726 = AXIS2_PLACEMENT_3D('',#180727,#180728,#180729); -#180727 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); -#180728 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180729 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180730 = DEFINITIONAL_REPRESENTATION('',(#180731),#180734); -#180731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180732,#180733), +#183108 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#183109 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#183110 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#183111 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#183112 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#183113 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#183114 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#183115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183116 = PCURVE('',#183117,#183122); +#183117 = CYLINDRICAL_SURFACE('',#183118,0.2); +#183118 = AXIS2_PLACEMENT_3D('',#183119,#183120,#183121); +#183119 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); +#183120 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183121 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183122 = DEFINITIONAL_REPRESENTATION('',(#183123),#183126); +#183123 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183124,#183125), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#180732 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180733 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#180734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180735 = ORIENTED_EDGE('',*,*,#180736,.F.); -#180736 = EDGE_CURVE('',#180737,#180705,#180739,.T.); -#180737 = VERTEX_POINT('',#180738); -#180738 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#180739 = SURFACE_CURVE('',#180740,(#180744,#180751),.PCURVE_S1.); -#180740 = LINE('',#180741,#180742); -#180741 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#180742 = VECTOR('',#180743,1.); -#180743 = DIRECTION('',(0.E+000,1.,0.E+000)); -#180744 = PCURVE('',#173201,#180745); -#180745 = DEFINITIONAL_REPRESENTATION('',(#180746),#180750); -#180746 = LINE('',#180747,#180748); -#180747 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#180748 = VECTOR('',#180749,1.); -#180749 = DIRECTION('',(0.E+000,1.)); -#180750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180751 = PCURVE('',#180752,#180757); -#180752 = PLANE('',#180753); -#180753 = AXIS2_PLACEMENT_3D('',#180754,#180755,#180756); -#180754 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#180755 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180756 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#180757 = DEFINITIONAL_REPRESENTATION('',(#180758),#180762); -#180758 = LINE('',#180759,#180760); -#180759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180760 = VECTOR('',#180761,1.); -#180761 = DIRECTION('',(0.E+000,1.)); -#180762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180763 = ORIENTED_EDGE('',*,*,#180764,.F.); -#180764 = EDGE_CURVE('',#180765,#180737,#180767,.T.); -#180765 = VERTEX_POINT('',#180766); -#180766 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); -#180767 = SURFACE_CURVE('',#180768,(#180772,#180779),.PCURVE_S1.); -#180768 = LINE('',#180769,#180770); -#180769 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#180770 = VECTOR('',#180771,1.); -#180771 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180772 = PCURVE('',#173201,#180773); -#180773 = DEFINITIONAL_REPRESENTATION('',(#180774),#180778); -#180774 = LINE('',#180775,#180776); -#180775 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#180776 = VECTOR('',#180777,1.); -#180777 = DIRECTION('',(-1.,0.E+000)); -#180778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180779 = PCURVE('',#180780,#180785); -#180780 = PLANE('',#180781); -#180781 = AXIS2_PLACEMENT_3D('',#180782,#180783,#180784); -#180782 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#180783 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180784 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180785 = DEFINITIONAL_REPRESENTATION('',(#180786),#180790); -#180786 = LINE('',#180787,#180788); -#180787 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180788 = VECTOR('',#180789,1.); -#180789 = DIRECTION('',(1.,0.E+000)); -#180790 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180791 = ORIENTED_EDGE('',*,*,#180792,.F.); -#180792 = EDGE_CURVE('',#180793,#180765,#180795,.T.); -#180793 = VERTEX_POINT('',#180794); -#180794 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.15)); -#180795 = SURFACE_CURVE('',#180796,(#180800,#180807),.PCURVE_S1.); -#180796 = LINE('',#180797,#180798); -#180797 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); -#180798 = VECTOR('',#180799,1.); -#180799 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180800 = PCURVE('',#173201,#180801); -#180801 = DEFINITIONAL_REPRESENTATION('',(#180802),#180806); -#180802 = LINE('',#180803,#180804); -#180803 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#180804 = VECTOR('',#180805,1.); -#180805 = DIRECTION('',(0.E+000,-1.)); -#180806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180807 = PCURVE('',#180808,#180813); -#180808 = PLANE('',#180809); -#180809 = AXIS2_PLACEMENT_3D('',#180810,#180811,#180812); -#180810 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); -#180811 = DIRECTION('',(0.E+000,0.E+000,1.)); -#180812 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180813 = DEFINITIONAL_REPRESENTATION('',(#180814),#180818); -#180814 = LINE('',#180815,#180816); -#180815 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180816 = VECTOR('',#180817,1.); -#180817 = DIRECTION('',(0.E+000,-1.)); -#180818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180819 = ORIENTED_EDGE('',*,*,#180820,.F.); -#180820 = EDGE_CURVE('',#180821,#180793,#180823,.T.); -#180821 = VERTEX_POINT('',#180822); -#180822 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); -#180823 = SURFACE_CURVE('',#180824,(#180829,#180836),.PCURVE_S1.); -#180824 = CIRCLE('',#180825,5.E-002); -#180825 = AXIS2_PLACEMENT_3D('',#180826,#180827,#180828); -#180826 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); -#180827 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#180828 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180829 = PCURVE('',#173201,#180830); -#180830 = DEFINITIONAL_REPRESENTATION('',(#180831),#180835); -#180831 = CIRCLE('',#180832,5.E-002); -#180832 = AXIS2_PLACEMENT_2D('',#180833,#180834); -#180833 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#180834 = DIRECTION('',(-1.,0.E+000)); -#180835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180836 = PCURVE('',#180837,#180842); -#180837 = CYLINDRICAL_SURFACE('',#180838,5.E-002); -#180838 = AXIS2_PLACEMENT_3D('',#180839,#180840,#180841); -#180839 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); -#180840 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180841 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180842 = DEFINITIONAL_REPRESENTATION('',(#180843),#180846); -#180843 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180844,#180845), - .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#180844 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#180845 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180846 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#183124 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183125 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#183126 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183127 = ORIENTED_EDGE('',*,*,#183128,.F.); +#183128 = EDGE_CURVE('',#183129,#183097,#183131,.T.); +#183129 = VERTEX_POINT('',#183130); +#183130 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183131 = SURFACE_CURVE('',#183132,(#183136,#183143),.PCURVE_S1.); +#183132 = LINE('',#183133,#183134); +#183133 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183134 = VECTOR('',#183135,1.); +#183135 = DIRECTION('',(0.E+000,1.,0.E+000)); +#183136 = PCURVE('',#175593,#183137); +#183137 = DEFINITIONAL_REPRESENTATION('',(#183138),#183142); +#183138 = LINE('',#183139,#183140); +#183139 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#183140 = VECTOR('',#183141,1.); +#183141 = DIRECTION('',(0.E+000,1.)); +#183142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183143 = PCURVE('',#183144,#183149); +#183144 = PLANE('',#183145); +#183145 = AXIS2_PLACEMENT_3D('',#183146,#183147,#183148); +#183146 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183147 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183148 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183149 = DEFINITIONAL_REPRESENTATION('',(#183150),#183154); +#183150 = LINE('',#183151,#183152); +#183151 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183152 = VECTOR('',#183153,1.); +#183153 = DIRECTION('',(0.E+000,1.)); +#183154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183155 = ORIENTED_EDGE('',*,*,#183156,.F.); +#183156 = EDGE_CURVE('',#183157,#183129,#183159,.T.); +#183157 = VERTEX_POINT('',#183158); +#183158 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); +#183159 = SURFACE_CURVE('',#183160,(#183164,#183171),.PCURVE_S1.); +#183160 = LINE('',#183161,#183162); +#183161 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183162 = VECTOR('',#183163,1.); +#183163 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183164 = PCURVE('',#175593,#183165); +#183165 = DEFINITIONAL_REPRESENTATION('',(#183166),#183170); +#183166 = LINE('',#183167,#183168); +#183167 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#183168 = VECTOR('',#183169,1.); +#183169 = DIRECTION('',(-1.,0.E+000)); +#183170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183171 = PCURVE('',#183172,#183177); +#183172 = PLANE('',#183173); +#183173 = AXIS2_PLACEMENT_3D('',#183174,#183175,#183176); +#183174 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183175 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#183176 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183177 = DEFINITIONAL_REPRESENTATION('',(#183178),#183182); +#183178 = LINE('',#183179,#183180); +#183179 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183180 = VECTOR('',#183181,1.); +#183181 = DIRECTION('',(1.,0.E+000)); +#183182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180847 = ORIENTED_EDGE('',*,*,#180848,.F.); -#180848 = EDGE_CURVE('',#180849,#180821,#180851,.T.); -#180849 = VERTEX_POINT('',#180850); -#180850 = CARTESIAN_POINT('',(-0.515,-1.056555553792,0.518820292599)); -#180851 = SURFACE_CURVE('',#180852,(#180856,#180863),.PCURVE_S1.); -#180852 = LINE('',#180853,#180854); -#180853 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); -#180854 = VECTOR('',#180855,1.); -#180855 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#180856 = PCURVE('',#173201,#180857); -#180857 = DEFINITIONAL_REPRESENTATION('',(#180858),#180862); -#180858 = LINE('',#180859,#180860); -#180859 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#180860 = VECTOR('',#180861,1.); -#180861 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#180862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180863 = PCURVE('',#180864,#180869); -#180864 = PLANE('',#180865); -#180865 = AXIS2_PLACEMENT_3D('',#180866,#180867,#180868); -#180866 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); -#180867 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); -#180868 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#180869 = DEFINITIONAL_REPRESENTATION('',(#180870),#180874); -#180870 = LINE('',#180871,#180872); -#180871 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180872 = VECTOR('',#180873,1.); -#180873 = DIRECTION('',(1.,0.E+000)); -#180874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180875 = ORIENTED_EDGE('',*,*,#180876,.F.); -#180876 = EDGE_CURVE('',#180877,#180849,#180879,.T.); -#180877 = VERTEX_POINT('',#180878); -#180878 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); -#180879 = SURFACE_CURVE('',#180880,(#180885,#180896),.PCURVE_S1.); -#180880 = CIRCLE('',#180881,0.25); -#180881 = AXIS2_PLACEMENT_3D('',#180882,#180883,#180884); -#180882 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); -#180883 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180884 = DIRECTION('',(0.E+000,0.E+000,1.)); -#180885 = PCURVE('',#173201,#180886); -#180886 = DEFINITIONAL_REPRESENTATION('',(#180887),#180895); -#180887 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180888,#180889,#180890, - #180891,#180892,#180893,#180894),.UNSPECIFIED.,.F.,.F.) +#183183 = ORIENTED_EDGE('',*,*,#183184,.F.); +#183184 = EDGE_CURVE('',#183185,#183157,#183187,.T.); +#183185 = VERTEX_POINT('',#183186); +#183186 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.15)); +#183187 = SURFACE_CURVE('',#183188,(#183192,#183199),.PCURVE_S1.); +#183188 = LINE('',#183189,#183190); +#183189 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); +#183190 = VECTOR('',#183191,1.); +#183191 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#183192 = PCURVE('',#175593,#183193); +#183193 = DEFINITIONAL_REPRESENTATION('',(#183194),#183198); +#183194 = LINE('',#183195,#183196); +#183195 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#183196 = VECTOR('',#183197,1.); +#183197 = DIRECTION('',(0.E+000,-1.)); +#183198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183199 = PCURVE('',#183200,#183205); +#183200 = PLANE('',#183201); +#183201 = AXIS2_PLACEMENT_3D('',#183202,#183203,#183204); +#183202 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); +#183203 = DIRECTION('',(0.E+000,0.E+000,1.)); +#183204 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183205 = DEFINITIONAL_REPRESENTATION('',(#183206),#183210); +#183206 = LINE('',#183207,#183208); +#183207 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183208 = VECTOR('',#183209,1.); +#183209 = DIRECTION('',(0.E+000,-1.)); +#183210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183211 = ORIENTED_EDGE('',*,*,#183212,.F.); +#183212 = EDGE_CURVE('',#183213,#183185,#183215,.T.); +#183213 = VERTEX_POINT('',#183214); +#183214 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); +#183215 = SURFACE_CURVE('',#183216,(#183221,#183228),.PCURVE_S1.); +#183216 = CIRCLE('',#183217,5.E-002); +#183217 = AXIS2_PLACEMENT_3D('',#183218,#183219,#183220); +#183218 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); +#183219 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183220 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183221 = PCURVE('',#175593,#183222); +#183222 = DEFINITIONAL_REPRESENTATION('',(#183223),#183227); +#183223 = CIRCLE('',#183224,5.E-002); +#183224 = AXIS2_PLACEMENT_2D('',#183225,#183226); +#183225 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#183226 = DIRECTION('',(-1.,0.E+000)); +#183227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183228 = PCURVE('',#183229,#183234); +#183229 = CYLINDRICAL_SURFACE('',#183230,5.E-002); +#183230 = AXIS2_PLACEMENT_3D('',#183231,#183232,#183233); +#183231 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.2)); +#183232 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183233 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183234 = DEFINITIONAL_REPRESENTATION('',(#183235),#183238); +#183235 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183236,#183237), + .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), + .PIECEWISE_BEZIER_KNOTS.); +#183236 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#183237 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183238 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183239 = ORIENTED_EDGE('',*,*,#183240,.F.); +#183240 = EDGE_CURVE('',#183241,#183213,#183243,.T.); +#183241 = VERTEX_POINT('',#183242); +#183242 = CARTESIAN_POINT('',(-0.515,-1.056555553792,0.518820292599)); +#183243 = SURFACE_CURVE('',#183244,(#183248,#183255),.PCURVE_S1.); +#183244 = LINE('',#183245,#183246); +#183245 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); +#183246 = VECTOR('',#183247,1.); +#183247 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#183248 = PCURVE('',#175593,#183249); +#183249 = DEFINITIONAL_REPRESENTATION('',(#183250),#183254); +#183250 = LINE('',#183251,#183252); +#183251 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#183252 = VECTOR('',#183253,1.); +#183253 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#183254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183255 = PCURVE('',#183256,#183261); +#183256 = PLANE('',#183257); +#183257 = AXIS2_PLACEMENT_3D('',#183258,#183259,#183260); +#183258 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); +#183259 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); +#183260 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#183261 = DEFINITIONAL_REPRESENTATION('',(#183262),#183266); +#183262 = LINE('',#183263,#183264); +#183263 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183264 = VECTOR('',#183265,1.); +#183265 = DIRECTION('',(1.,0.E+000)); +#183266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183267 = ORIENTED_EDGE('',*,*,#183268,.F.); +#183268 = EDGE_CURVE('',#183269,#183241,#183271,.T.); +#183269 = VERTEX_POINT('',#183270); +#183270 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); +#183271 = SURFACE_CURVE('',#183272,(#183277,#183288),.PCURVE_S1.); +#183272 = CIRCLE('',#183273,0.25); +#183273 = AXIS2_PLACEMENT_3D('',#183274,#183275,#183276); +#183274 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); +#183275 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183276 = DIRECTION('',(0.E+000,0.E+000,1.)); +#183277 = PCURVE('',#175593,#183278); +#183278 = DEFINITIONAL_REPRESENTATION('',(#183279),#183287); +#183279 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#183280,#183281,#183282, + #183283,#183284,#183285,#183286),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180888 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180889 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#180890 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#180891 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#180892 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#180893 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#180894 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180896 = PCURVE('',#180897,#180902); -#180897 = CYLINDRICAL_SURFACE('',#180898,0.25); -#180898 = AXIS2_PLACEMENT_3D('',#180899,#180900,#180901); -#180899 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); -#180900 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180901 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#180902 = DEFINITIONAL_REPRESENTATION('',(#180903),#180906); -#180903 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180904,#180905), +#183280 = CARTESIAN_POINT('',(0.25,0.E+000)); +#183281 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#183282 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#183283 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#183284 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#183285 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#183286 = CARTESIAN_POINT('',(0.25,0.E+000)); +#183287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183288 = PCURVE('',#183289,#183294); +#183289 = CYLINDRICAL_SURFACE('',#183290,0.25); +#183290 = AXIS2_PLACEMENT_3D('',#183291,#183292,#183293); +#183291 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.5)); +#183292 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183293 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183294 = DEFINITIONAL_REPRESENTATION('',(#183295),#183298); +#183295 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183296,#183297), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#180904 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180905 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#180906 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180907 = ORIENTED_EDGE('',*,*,#180908,.F.); -#180908 = EDGE_CURVE('',#173186,#180877,#180909,.T.); -#180909 = SURFACE_CURVE('',#180910,(#180914,#180921),.PCURVE_S1.); -#180910 = LINE('',#180911,#180912); -#180911 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); -#180912 = VECTOR('',#180913,1.); -#180913 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180914 = PCURVE('',#173201,#180915); -#180915 = DEFINITIONAL_REPRESENTATION('',(#180916),#180920); -#180916 = LINE('',#180917,#180918); -#180917 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#180918 = VECTOR('',#180919,1.); -#180919 = DIRECTION('',(0.E+000,-1.)); -#180920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180921 = PCURVE('',#173229,#180922); -#180922 = DEFINITIONAL_REPRESENTATION('',(#180923),#180927); -#180923 = LINE('',#180924,#180925); -#180924 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#180925 = VECTOR('',#180926,1.); -#180926 = DIRECTION('',(0.E+000,-1.)); -#180927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#183296 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183297 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#183298 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183299 = ORIENTED_EDGE('',*,*,#183300,.F.); +#183300 = EDGE_CURVE('',#175578,#183269,#183301,.T.); +#183301 = SURFACE_CURVE('',#183302,(#183306,#183313),.PCURVE_S1.); +#183302 = LINE('',#183303,#183304); +#183303 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); +#183304 = VECTOR('',#183305,1.); +#183305 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#183306 = PCURVE('',#175593,#183307); +#183307 = DEFINITIONAL_REPRESENTATION('',(#183308),#183312); +#183308 = LINE('',#183309,#183310); +#183309 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#183310 = VECTOR('',#183311,1.); +#183311 = DIRECTION('',(0.E+000,-1.)); +#183312 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183313 = PCURVE('',#175621,#183314); +#183314 = DEFINITIONAL_REPRESENTATION('',(#183315),#183319); +#183315 = LINE('',#183316,#183317); +#183316 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183317 = VECTOR('',#183318,1.); +#183318 = DIRECTION('',(0.E+000,-1.)); +#183319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183320 = ADVANCED_FACE('',(#183321),#175621,.T.); +#183321 = FACE_BOUND('',#183322,.T.); +#183322 = EDGE_LOOP('',(#183323,#183345,#183366,#183367)); +#183323 = ORIENTED_EDGE('',*,*,#183324,.T.); +#183324 = EDGE_CURVE('',#183269,#183325,#183327,.T.); +#183325 = VERTEX_POINT('',#183326); +#183326 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.75)); +#183327 = SURFACE_CURVE('',#183328,(#183332,#183339),.PCURVE_S1.); +#183328 = LINE('',#183329,#183330); +#183329 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); +#183330 = VECTOR('',#183331,1.); +#183331 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183332 = PCURVE('',#175621,#183333); +#183333 = DEFINITIONAL_REPRESENTATION('',(#183334),#183338); +#183334 = LINE('',#183335,#183336); +#183335 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); +#183336 = VECTOR('',#183337,1.); +#183337 = DIRECTION('',(1.,0.E+000)); +#183338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#180928 = ADVANCED_FACE('',(#180929),#173229,.T.); -#180929 = FACE_BOUND('',#180930,.T.); -#180930 = EDGE_LOOP('',(#180931,#180953,#180974,#180975)); -#180931 = ORIENTED_EDGE('',*,*,#180932,.T.); -#180932 = EDGE_CURVE('',#180877,#180933,#180935,.T.); -#180933 = VERTEX_POINT('',#180934); -#180934 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.75)); -#180935 = SURFACE_CURVE('',#180936,(#180940,#180947),.PCURVE_S1.); -#180936 = LINE('',#180937,#180938); -#180937 = CARTESIAN_POINT('',(-0.515,-0.807264967154,0.75)); -#180938 = VECTOR('',#180939,1.); -#180939 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180940 = PCURVE('',#173229,#180941); -#180941 = DEFINITIONAL_REPRESENTATION('',(#180942),#180946); -#180942 = LINE('',#180943,#180944); -#180943 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); -#180944 = VECTOR('',#180945,1.); -#180945 = DIRECTION('',(1.,0.E+000)); -#180946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180947 = PCURVE('',#180897,#180948); -#180948 = DEFINITIONAL_REPRESENTATION('',(#180949),#180952); -#180949 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#180950,#180951), +#183339 = PCURVE('',#183289,#183340); +#183340 = DEFINITIONAL_REPRESENTATION('',(#183341),#183344); +#183341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183342,#183343), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#180950 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#180951 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#180952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180953 = ORIENTED_EDGE('',*,*,#180954,.F.); -#180954 = EDGE_CURVE('',#173214,#180933,#180955,.T.); -#180955 = SURFACE_CURVE('',#180956,(#180960,#180967),.PCURVE_S1.); -#180956 = LINE('',#180957,#180958); -#180957 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.75)); -#180958 = VECTOR('',#180959,1.); -#180959 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#180960 = PCURVE('',#173229,#180961); -#180961 = DEFINITIONAL_REPRESENTATION('',(#180962),#180966); -#180962 = LINE('',#180963,#180964); -#180963 = CARTESIAN_POINT('',(0.34,0.E+000)); -#180964 = VECTOR('',#180965,1.); -#180965 = DIRECTION('',(0.E+000,-1.)); -#180966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180967 = PCURVE('',#173255,#180968); -#180968 = DEFINITIONAL_REPRESENTATION('',(#180969),#180973); -#180969 = LINE('',#180970,#180971); -#180970 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#180971 = VECTOR('',#180972,1.); -#180972 = DIRECTION('',(0.E+000,-1.)); -#180973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#180974 = ORIENTED_EDGE('',*,*,#173213,.F.); -#180975 = ORIENTED_EDGE('',*,*,#180908,.T.); -#180976 = ADVANCED_FACE('',(#180977),#173255,.F.); -#180977 = FACE_BOUND('',#180978,.T.); -#180978 = EDGE_LOOP('',(#180979,#180980,#180981,#180982,#181009,#181032, - #181055,#181078,#181101,#181124,#181151,#181174)); -#180979 = ORIENTED_EDGE('',*,*,#180577,.T.); -#180980 = ORIENTED_EDGE('',*,*,#173241,.T.); -#180981 = ORIENTED_EDGE('',*,*,#180954,.T.); -#180982 = ORIENTED_EDGE('',*,*,#180983,.T.); -#180983 = EDGE_CURVE('',#180933,#180984,#180986,.T.); -#180984 = VERTEX_POINT('',#180985); -#180985 = CARTESIAN_POINT('',(-0.175,-1.056555553792,0.518820292599)); -#180986 = SURFACE_CURVE('',#180987,(#180992,#181003),.PCURVE_S1.); -#180987 = CIRCLE('',#180988,0.25); -#180988 = AXIS2_PLACEMENT_3D('',#180989,#180990,#180991); -#180989 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); -#180990 = DIRECTION('',(1.,0.E+000,0.E+000)); -#180991 = DIRECTION('',(0.E+000,0.E+000,1.)); -#180992 = PCURVE('',#173255,#180993); -#180993 = DEFINITIONAL_REPRESENTATION('',(#180994),#181002); -#180994 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#180995,#180996,#180997, - #180998,#180999,#181000,#181001),.UNSPECIFIED.,.F.,.F.) +#183342 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183343 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#183344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183345 = ORIENTED_EDGE('',*,*,#183346,.F.); +#183346 = EDGE_CURVE('',#175606,#183325,#183347,.T.); +#183347 = SURFACE_CURVE('',#183348,(#183352,#183359),.PCURVE_S1.); +#183348 = LINE('',#183349,#183350); +#183349 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.75)); +#183350 = VECTOR('',#183351,1.); +#183351 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#183352 = PCURVE('',#175621,#183353); +#183353 = DEFINITIONAL_REPRESENTATION('',(#183354),#183358); +#183354 = LINE('',#183355,#183356); +#183355 = CARTESIAN_POINT('',(0.34,0.E+000)); +#183356 = VECTOR('',#183357,1.); +#183357 = DIRECTION('',(0.E+000,-1.)); +#183358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183359 = PCURVE('',#175647,#183360); +#183360 = DEFINITIONAL_REPRESENTATION('',(#183361),#183365); +#183361 = LINE('',#183362,#183363); +#183362 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#183363 = VECTOR('',#183364,1.); +#183364 = DIRECTION('',(0.E+000,-1.)); +#183365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183366 = ORIENTED_EDGE('',*,*,#175605,.F.); +#183367 = ORIENTED_EDGE('',*,*,#183300,.T.); +#183368 = ADVANCED_FACE('',(#183369),#175647,.F.); +#183369 = FACE_BOUND('',#183370,.T.); +#183370 = EDGE_LOOP('',(#183371,#183372,#183373,#183374,#183401,#183424, + #183447,#183470,#183493,#183516,#183543,#183566)); +#183371 = ORIENTED_EDGE('',*,*,#182969,.T.); +#183372 = ORIENTED_EDGE('',*,*,#175633,.T.); +#183373 = ORIENTED_EDGE('',*,*,#183346,.T.); +#183374 = ORIENTED_EDGE('',*,*,#183375,.T.); +#183375 = EDGE_CURVE('',#183325,#183376,#183378,.T.); +#183376 = VERTEX_POINT('',#183377); +#183377 = CARTESIAN_POINT('',(-0.175,-1.056555553792,0.518820292599)); +#183378 = SURFACE_CURVE('',#183379,(#183384,#183395),.PCURVE_S1.); +#183379 = CIRCLE('',#183380,0.25); +#183380 = AXIS2_PLACEMENT_3D('',#183381,#183382,#183383); +#183381 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); +#183382 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183383 = DIRECTION('',(0.E+000,0.E+000,1.)); +#183384 = PCURVE('',#175647,#183385); +#183385 = DEFINITIONAL_REPRESENTATION('',(#183386),#183394); +#183386 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#183387,#183388,#183389, + #183390,#183391,#183392,#183393),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#180995 = CARTESIAN_POINT('',(0.25,0.E+000)); -#180996 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#180997 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#180998 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#180999 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#181000 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#181001 = CARTESIAN_POINT('',(0.25,0.E+000)); -#181002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181003 = PCURVE('',#180897,#181004); -#181004 = DEFINITIONAL_REPRESENTATION('',(#181005),#181008); -#181005 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181006,#181007), +#183387 = CARTESIAN_POINT('',(0.25,0.E+000)); +#183388 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#183389 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#183390 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#183391 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#183392 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#183393 = CARTESIAN_POINT('',(0.25,0.E+000)); +#183394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183395 = PCURVE('',#183289,#183396); +#183396 = DEFINITIONAL_REPRESENTATION('',(#183397),#183400); +#183397 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183398,#183399), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#181006 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#181007 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#181008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181009 = ORIENTED_EDGE('',*,*,#181010,.T.); -#181010 = EDGE_CURVE('',#180984,#181011,#181013,.T.); -#181011 = VERTEX_POINT('',#181012); -#181012 = CARTESIAN_POINT('',(-0.175,-1.080909188472,0.19623594148)); -#181013 = SURFACE_CURVE('',#181014,(#181018,#181025),.PCURVE_S1.); -#181014 = LINE('',#181015,#181016); -#181015 = CARTESIAN_POINT('',(-0.175,-1.080909188472,0.19623594148)); -#181016 = VECTOR('',#181017,1.); -#181017 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#181018 = PCURVE('',#173255,#181019); -#181019 = DEFINITIONAL_REPRESENTATION('',(#181020),#181024); -#181020 = LINE('',#181021,#181022); -#181021 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#181022 = VECTOR('',#181023,1.); -#181023 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#181024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181025 = PCURVE('',#180864,#181026); -#181026 = DEFINITIONAL_REPRESENTATION('',(#181027),#181031); -#181027 = LINE('',#181028,#181029); -#181028 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181029 = VECTOR('',#181030,1.); -#181030 = DIRECTION('',(1.,0.E+000)); -#181031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181032 = ORIENTED_EDGE('',*,*,#181033,.T.); -#181033 = EDGE_CURVE('',#181011,#181034,#181036,.T.); -#181034 = VERTEX_POINT('',#181035); -#181035 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.15)); -#181036 = SURFACE_CURVE('',#181037,(#181042,#181049),.PCURVE_S1.); -#181037 = CIRCLE('',#181038,5.E-002); -#181038 = AXIS2_PLACEMENT_3D('',#181039,#181040,#181041); -#181039 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.2)); -#181040 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181041 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181042 = PCURVE('',#173255,#181043); -#181043 = DEFINITIONAL_REPRESENTATION('',(#181044),#181048); -#181044 = CIRCLE('',#181045,5.E-002); -#181045 = AXIS2_PLACEMENT_2D('',#181046,#181047); -#181046 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#181047 = DIRECTION('',(-1.,0.E+000)); -#181048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181049 = PCURVE('',#180837,#181050); -#181050 = DEFINITIONAL_REPRESENTATION('',(#181051),#181054); -#181051 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181052,#181053), - .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#181052 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#181053 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#183398 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#183399 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#183400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183401 = ORIENTED_EDGE('',*,*,#183402,.T.); +#183402 = EDGE_CURVE('',#183376,#183403,#183405,.T.); +#183403 = VERTEX_POINT('',#183404); +#183404 = CARTESIAN_POINT('',(-0.175,-1.080909188472,0.19623594148)); +#183405 = SURFACE_CURVE('',#183406,(#183410,#183417),.PCURVE_S1.); +#183406 = LINE('',#183407,#183408); +#183407 = CARTESIAN_POINT('',(-0.175,-1.080909188472,0.19623594148)); +#183408 = VECTOR('',#183409,1.); +#183409 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#183410 = PCURVE('',#175647,#183411); +#183411 = DEFINITIONAL_REPRESENTATION('',(#183412),#183416); +#183412 = LINE('',#183413,#183414); +#183413 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#183414 = VECTOR('',#183415,1.); +#183415 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#183416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183417 = PCURVE('',#183256,#183418); +#183418 = DEFINITIONAL_REPRESENTATION('',(#183419),#183423); +#183419 = LINE('',#183420,#183421); +#183420 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183421 = VECTOR('',#183422,1.); +#183422 = DIRECTION('',(1.,0.E+000)); +#183423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#181055 = ORIENTED_EDGE('',*,*,#181056,.T.); -#181056 = EDGE_CURVE('',#181034,#181057,#181059,.T.); -#181057 = VERTEX_POINT('',#181058); -#181058 = CARTESIAN_POINT('',(-0.175,-1.4,0.15)); -#181059 = SURFACE_CURVE('',#181060,(#181064,#181071),.PCURVE_S1.); -#181060 = LINE('',#181061,#181062); -#181061 = CARTESIAN_POINT('',(-0.175,-1.4,0.15)); -#181062 = VECTOR('',#181063,1.); -#181063 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181064 = PCURVE('',#173255,#181065); -#181065 = DEFINITIONAL_REPRESENTATION('',(#181066),#181070); -#181066 = LINE('',#181067,#181068); -#181067 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#181068 = VECTOR('',#181069,1.); -#181069 = DIRECTION('',(0.E+000,-1.)); -#181070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181071 = PCURVE('',#180808,#181072); -#181072 = DEFINITIONAL_REPRESENTATION('',(#181073),#181077); -#181073 = LINE('',#181074,#181075); -#181074 = CARTESIAN_POINT('',(0.34,0.E+000)); -#181075 = VECTOR('',#181076,1.); -#181076 = DIRECTION('',(0.E+000,-1.)); -#181077 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181078 = ORIENTED_EDGE('',*,*,#181079,.T.); -#181079 = EDGE_CURVE('',#181057,#181080,#181082,.T.); -#181080 = VERTEX_POINT('',#181081); -#181081 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); -#181082 = SURFACE_CURVE('',#181083,(#181087,#181094),.PCURVE_S1.); -#181083 = LINE('',#181084,#181085); -#181084 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); -#181085 = VECTOR('',#181086,1.); -#181086 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181087 = PCURVE('',#173255,#181088); -#181088 = DEFINITIONAL_REPRESENTATION('',(#181089),#181093); -#181089 = LINE('',#181090,#181091); -#181090 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#181091 = VECTOR('',#181092,1.); -#181092 = DIRECTION('',(-1.,0.E+000)); -#181093 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181094 = PCURVE('',#180780,#181095); -#181095 = DEFINITIONAL_REPRESENTATION('',(#181096),#181100); -#181096 = LINE('',#181097,#181098); -#181097 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181098 = VECTOR('',#181099,1.); -#181099 = DIRECTION('',(1.,0.E+000)); -#181100 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181101 = ORIENTED_EDGE('',*,*,#181102,.T.); -#181102 = EDGE_CURVE('',#181080,#181103,#181105,.T.); -#181103 = VERTEX_POINT('',#181104); -#181104 = CARTESIAN_POINT('',(-0.175,-1.1307673058,-1.878014448176E-016) - ); -#181105 = SURFACE_CURVE('',#181106,(#181110,#181117),.PCURVE_S1.); -#181106 = LINE('',#181107,#181108); -#181107 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); -#181108 = VECTOR('',#181109,1.); -#181109 = DIRECTION('',(0.E+000,1.,0.E+000)); -#181110 = PCURVE('',#173255,#181111); -#181111 = DEFINITIONAL_REPRESENTATION('',(#181112),#181116); -#181112 = LINE('',#181113,#181114); -#181113 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#181114 = VECTOR('',#181115,1.); -#181115 = DIRECTION('',(0.E+000,1.)); -#181116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181117 = PCURVE('',#180752,#181118); -#181118 = DEFINITIONAL_REPRESENTATION('',(#181119),#181123); -#181119 = LINE('',#181120,#181121); -#181120 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#181121 = VECTOR('',#181122,1.); -#181122 = DIRECTION('',(0.E+000,1.)); -#181123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181124 = ORIENTED_EDGE('',*,*,#181125,.T.); -#181125 = EDGE_CURVE('',#181103,#181126,#181128,.T.); -#181126 = VERTEX_POINT('',#181127); -#181127 = CARTESIAN_POINT('',(-0.175,-0.931334836489,0.184943765921)); -#181128 = SURFACE_CURVE('',#181129,(#181134,#181145),.PCURVE_S1.); -#181129 = CIRCLE('',#181130,0.2); -#181130 = AXIS2_PLACEMENT_3D('',#181131,#181132,#181133); -#181131 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.2)); -#181132 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181133 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181134 = PCURVE('',#173255,#181135); -#181135 = DEFINITIONAL_REPRESENTATION('',(#181136),#181144); -#181136 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181137,#181138,#181139, - #181140,#181141,#181142,#181143),.UNSPECIFIED.,.T.,.F.) +#183424 = ORIENTED_EDGE('',*,*,#183425,.T.); +#183425 = EDGE_CURVE('',#183403,#183426,#183428,.T.); +#183426 = VERTEX_POINT('',#183427); +#183427 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.15)); +#183428 = SURFACE_CURVE('',#183429,(#183434,#183441),.PCURVE_S1.); +#183429 = CIRCLE('',#183430,5.E-002); +#183430 = AXIS2_PLACEMENT_3D('',#183431,#183432,#183433); +#183431 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.2)); +#183432 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183433 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183434 = PCURVE('',#175647,#183435); +#183435 = DEFINITIONAL_REPRESENTATION('',(#183436),#183440); +#183436 = CIRCLE('',#183437,5.E-002); +#183437 = AXIS2_PLACEMENT_2D('',#183438,#183439); +#183438 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#183439 = DIRECTION('',(-1.,0.E+000)); +#183440 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183441 = PCURVE('',#183229,#183442); +#183442 = DEFINITIONAL_REPRESENTATION('',(#183443),#183446); +#183443 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183444,#183445), + .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), + .PIECEWISE_BEZIER_KNOTS.); +#183444 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#183445 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183446 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183447 = ORIENTED_EDGE('',*,*,#183448,.T.); +#183448 = EDGE_CURVE('',#183426,#183449,#183451,.T.); +#183449 = VERTEX_POINT('',#183450); +#183450 = CARTESIAN_POINT('',(-0.175,-1.4,0.15)); +#183451 = SURFACE_CURVE('',#183452,(#183456,#183463),.PCURVE_S1.); +#183452 = LINE('',#183453,#183454); +#183453 = CARTESIAN_POINT('',(-0.175,-1.4,0.15)); +#183454 = VECTOR('',#183455,1.); +#183455 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#183456 = PCURVE('',#175647,#183457); +#183457 = DEFINITIONAL_REPRESENTATION('',(#183458),#183462); +#183458 = LINE('',#183459,#183460); +#183459 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#183460 = VECTOR('',#183461,1.); +#183461 = DIRECTION('',(0.E+000,-1.)); +#183462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183463 = PCURVE('',#183200,#183464); +#183464 = DEFINITIONAL_REPRESENTATION('',(#183465),#183469); +#183465 = LINE('',#183466,#183467); +#183466 = CARTESIAN_POINT('',(0.34,0.E+000)); +#183467 = VECTOR('',#183468,1.); +#183468 = DIRECTION('',(0.E+000,-1.)); +#183469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183470 = ORIENTED_EDGE('',*,*,#183471,.T.); +#183471 = EDGE_CURVE('',#183449,#183472,#183474,.T.); +#183472 = VERTEX_POINT('',#183473); +#183473 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); +#183474 = SURFACE_CURVE('',#183475,(#183479,#183486),.PCURVE_S1.); +#183475 = LINE('',#183476,#183477); +#183476 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); +#183477 = VECTOR('',#183478,1.); +#183478 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183479 = PCURVE('',#175647,#183480); +#183480 = DEFINITIONAL_REPRESENTATION('',(#183481),#183485); +#183481 = LINE('',#183482,#183483); +#183482 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#183483 = VECTOR('',#183484,1.); +#183484 = DIRECTION('',(-1.,0.E+000)); +#183485 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183486 = PCURVE('',#183172,#183487); +#183487 = DEFINITIONAL_REPRESENTATION('',(#183488),#183492); +#183488 = LINE('',#183489,#183490); +#183489 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183490 = VECTOR('',#183491,1.); +#183491 = DIRECTION('',(1.,0.E+000)); +#183492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183493 = ORIENTED_EDGE('',*,*,#183494,.T.); +#183494 = EDGE_CURVE('',#183472,#183495,#183497,.T.); +#183495 = VERTEX_POINT('',#183496); +#183496 = CARTESIAN_POINT('',(-0.175,-1.1307673058,-1.878014448176E-016) + ); +#183497 = SURFACE_CURVE('',#183498,(#183502,#183509),.PCURVE_S1.); +#183498 = LINE('',#183499,#183500); +#183499 = CARTESIAN_POINT('',(-0.175,-1.4,-1.335913361933E-016)); +#183500 = VECTOR('',#183501,1.); +#183501 = DIRECTION('',(0.E+000,1.,0.E+000)); +#183502 = PCURVE('',#175647,#183503); +#183503 = DEFINITIONAL_REPRESENTATION('',(#183504),#183508); +#183504 = LINE('',#183505,#183506); +#183505 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#183506 = VECTOR('',#183507,1.); +#183507 = DIRECTION('',(0.E+000,1.)); +#183508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183509 = PCURVE('',#183144,#183510); +#183510 = DEFINITIONAL_REPRESENTATION('',(#183511),#183515); +#183511 = LINE('',#183512,#183513); +#183512 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#183513 = VECTOR('',#183514,1.); +#183514 = DIRECTION('',(0.E+000,1.)); +#183515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183516 = ORIENTED_EDGE('',*,*,#183517,.T.); +#183517 = EDGE_CURVE('',#183495,#183518,#183520,.T.); +#183518 = VERTEX_POINT('',#183519); +#183519 = CARTESIAN_POINT('',(-0.175,-0.931334836489,0.184943765921)); +#183520 = SURFACE_CURVE('',#183521,(#183526,#183537),.PCURVE_S1.); +#183521 = CIRCLE('',#183522,0.2); +#183522 = AXIS2_PLACEMENT_3D('',#183523,#183524,#183525); +#183523 = CARTESIAN_POINT('',(-0.175,-1.1307673058,0.2)); +#183524 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183525 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183526 = PCURVE('',#175647,#183527); +#183527 = DEFINITIONAL_REPRESENTATION('',(#183528),#183536); +#183528 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#183529,#183530,#183531, + #183532,#183533,#183534,#183535),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#181137 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#181138 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#181139 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#181140 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#181141 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#181142 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#181143 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#181144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181145 = PCURVE('',#180725,#181146); -#181146 = DEFINITIONAL_REPRESENTATION('',(#181147),#181150); -#181147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181148,#181149), +#183529 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#183530 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#183531 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#183532 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#183533 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#183534 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#183535 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#183536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183537 = PCURVE('',#183117,#183538); +#183538 = DEFINITIONAL_REPRESENTATION('',(#183539),#183542); +#183539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183540,#183541), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#181148 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181149 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#181150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181151 = ORIENTED_EDGE('',*,*,#181152,.T.); -#181152 = EDGE_CURVE('',#181126,#181153,#181155,.T.); -#181153 = VERTEX_POINT('',#181154); -#181154 = CARTESIAN_POINT('',(-0.175,-0.906981201809,0.50752811704)); -#181155 = SURFACE_CURVE('',#181156,(#181160,#181167),.PCURVE_S1.); -#181156 = LINE('',#181157,#181158); -#181157 = CARTESIAN_POINT('',(-0.175,-0.931334836489,0.184943765921)); -#181158 = VECTOR('',#181159,1.); -#181159 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#181160 = PCURVE('',#173255,#181161); -#181161 = DEFINITIONAL_REPRESENTATION('',(#181162),#181166); -#181162 = LINE('',#181163,#181164); -#181163 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#181164 = VECTOR('',#181165,1.); -#181165 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#181166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181167 = PCURVE('',#180692,#181168); -#181168 = DEFINITIONAL_REPRESENTATION('',(#181169),#181173); -#181169 = LINE('',#181170,#181171); -#181170 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181171 = VECTOR('',#181172,1.); -#181172 = DIRECTION('',(1.,0.E+000)); -#181173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181174 = ORIENTED_EDGE('',*,*,#181175,.T.); -#181175 = EDGE_CURVE('',#181153,#180578,#181176,.T.); -#181176 = SURFACE_CURVE('',#181177,(#181182,#181189),.PCURVE_S1.); -#181177 = CIRCLE('',#181178,0.1); -#181178 = AXIS2_PLACEMENT_3D('',#181179,#181180,#181181); -#181179 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); -#181180 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181181 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181182 = PCURVE('',#173255,#181183); -#181183 = DEFINITIONAL_REPRESENTATION('',(#181184),#181188); -#181184 = CIRCLE('',#181185,0.1); -#181185 = AXIS2_PLACEMENT_2D('',#181186,#181187); -#181186 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#181187 = DIRECTION('',(-1.,0.E+000)); -#181188 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181189 = PCURVE('',#180616,#181190); -#181190 = DEFINITIONAL_REPRESENTATION('',(#181191),#181194); -#181191 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181192,#181193), +#183540 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183541 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#183542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183543 = ORIENTED_EDGE('',*,*,#183544,.T.); +#183544 = EDGE_CURVE('',#183518,#183545,#183547,.T.); +#183545 = VERTEX_POINT('',#183546); +#183546 = CARTESIAN_POINT('',(-0.175,-0.906981201809,0.50752811704)); +#183547 = SURFACE_CURVE('',#183548,(#183552,#183559),.PCURVE_S1.); +#183548 = LINE('',#183549,#183550); +#183549 = CARTESIAN_POINT('',(-0.175,-0.931334836489,0.184943765921)); +#183550 = VECTOR('',#183551,1.); +#183551 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#183552 = PCURVE('',#175647,#183553); +#183553 = DEFINITIONAL_REPRESENTATION('',(#183554),#183558); +#183554 = LINE('',#183555,#183556); +#183555 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#183556 = VECTOR('',#183557,1.); +#183557 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#183558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183559 = PCURVE('',#183084,#183560); +#183560 = DEFINITIONAL_REPRESENTATION('',(#183561),#183565); +#183561 = LINE('',#183562,#183563); +#183562 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183563 = VECTOR('',#183564,1.); +#183564 = DIRECTION('',(1.,0.E+000)); +#183565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183566 = ORIENTED_EDGE('',*,*,#183567,.T.); +#183567 = EDGE_CURVE('',#183545,#182970,#183568,.T.); +#183568 = SURFACE_CURVE('',#183569,(#183574,#183581),.PCURVE_S1.); +#183569 = CIRCLE('',#183570,0.1); +#183570 = AXIS2_PLACEMENT_3D('',#183571,#183572,#183573); +#183571 = CARTESIAN_POINT('',(-0.175,-0.807264967154,0.5)); +#183572 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183573 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183574 = PCURVE('',#175647,#183575); +#183575 = DEFINITIONAL_REPRESENTATION('',(#183576),#183580); +#183576 = CIRCLE('',#183577,0.1); +#183577 = AXIS2_PLACEMENT_2D('',#183578,#183579); +#183578 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#183579 = DIRECTION('',(-1.,0.E+000)); +#183580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183581 = PCURVE('',#183008,#183582); +#183582 = DEFINITIONAL_REPRESENTATION('',(#183583),#183586); +#183583 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183584,#183585), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#181192 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#181193 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#181194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181195 = ADVANCED_FACE('',(#181196),#180616,.F.); -#181196 = FACE_BOUND('',#181197,.F.); -#181197 = EDGE_LOOP('',(#181198,#181199,#181200,#181220)); -#181198 = ORIENTED_EDGE('',*,*,#180600,.F.); -#181199 = ORIENTED_EDGE('',*,*,#180653,.F.); -#181200 = ORIENTED_EDGE('',*,*,#181201,.T.); -#181201 = EDGE_CURVE('',#180654,#181153,#181202,.T.); -#181202 = SURFACE_CURVE('',#181203,(#181207,#181213),.PCURVE_S1.); -#181203 = LINE('',#181204,#181205); -#181204 = CARTESIAN_POINT('',(-0.515,-0.906981201809,0.50752811704)); -#181205 = VECTOR('',#181206,1.); -#181206 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181207 = PCURVE('',#180616,#181208); -#181208 = DEFINITIONAL_REPRESENTATION('',(#181209),#181212); -#181209 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181210,#181211), +#183584 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#183585 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#183586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183587 = ADVANCED_FACE('',(#183588),#183008,.F.); +#183588 = FACE_BOUND('',#183589,.F.); +#183589 = EDGE_LOOP('',(#183590,#183591,#183592,#183612)); +#183590 = ORIENTED_EDGE('',*,*,#182992,.F.); +#183591 = ORIENTED_EDGE('',*,*,#183045,.F.); +#183592 = ORIENTED_EDGE('',*,*,#183593,.T.); +#183593 = EDGE_CURVE('',#183046,#183545,#183594,.T.); +#183594 = SURFACE_CURVE('',#183595,(#183599,#183605),.PCURVE_S1.); +#183595 = LINE('',#183596,#183597); +#183596 = CARTESIAN_POINT('',(-0.515,-0.906981201809,0.50752811704)); +#183597 = VECTOR('',#183598,1.); +#183598 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183599 = PCURVE('',#183008,#183600); +#183600 = DEFINITIONAL_REPRESENTATION('',(#183601),#183604); +#183601 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183602,#183603), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181210 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#181211 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#181212 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181213 = PCURVE('',#180692,#181214); -#181214 = DEFINITIONAL_REPRESENTATION('',(#181215),#181219); -#181215 = LINE('',#181216,#181217); -#181216 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#181217 = VECTOR('',#181218,1.); -#181218 = DIRECTION('',(0.E+000,1.)); -#181219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181220 = ORIENTED_EDGE('',*,*,#181175,.T.); -#181221 = ADVANCED_FACE('',(#181222),#180692,.T.); -#181222 = FACE_BOUND('',#181223,.T.); -#181223 = EDGE_LOOP('',(#181224,#181225,#181226,#181246)); -#181224 = ORIENTED_EDGE('',*,*,#181201,.T.); -#181225 = ORIENTED_EDGE('',*,*,#181152,.F.); -#181226 = ORIENTED_EDGE('',*,*,#181227,.F.); -#181227 = EDGE_CURVE('',#180677,#181126,#181228,.T.); -#181228 = SURFACE_CURVE('',#181229,(#181233,#181240),.PCURVE_S1.); -#181229 = LINE('',#181230,#181231); -#181230 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); -#181231 = VECTOR('',#181232,1.); -#181232 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181233 = PCURVE('',#180692,#181234); -#181234 = DEFINITIONAL_REPRESENTATION('',(#181235),#181239); -#181235 = LINE('',#181236,#181237); -#181236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181237 = VECTOR('',#181238,1.); -#181238 = DIRECTION('',(0.E+000,1.)); -#181239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181240 = PCURVE('',#180725,#181241); -#181241 = DEFINITIONAL_REPRESENTATION('',(#181242),#181245); -#181242 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181243,#181244), +#183602 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#183603 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#183604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183605 = PCURVE('',#183084,#183606); +#183606 = DEFINITIONAL_REPRESENTATION('',(#183607),#183611); +#183607 = LINE('',#183608,#183609); +#183608 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#183609 = VECTOR('',#183610,1.); +#183610 = DIRECTION('',(0.E+000,1.)); +#183611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183612 = ORIENTED_EDGE('',*,*,#183567,.T.); +#183613 = ADVANCED_FACE('',(#183614),#183084,.T.); +#183614 = FACE_BOUND('',#183615,.T.); +#183615 = EDGE_LOOP('',(#183616,#183617,#183618,#183638)); +#183616 = ORIENTED_EDGE('',*,*,#183593,.T.); +#183617 = ORIENTED_EDGE('',*,*,#183544,.F.); +#183618 = ORIENTED_EDGE('',*,*,#183619,.F.); +#183619 = EDGE_CURVE('',#183069,#183518,#183620,.T.); +#183620 = SURFACE_CURVE('',#183621,(#183625,#183632),.PCURVE_S1.); +#183621 = LINE('',#183622,#183623); +#183622 = CARTESIAN_POINT('',(-0.515,-0.931334836489,0.184943765921)); +#183623 = VECTOR('',#183624,1.); +#183624 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183625 = PCURVE('',#183084,#183626); +#183626 = DEFINITIONAL_REPRESENTATION('',(#183627),#183631); +#183627 = LINE('',#183628,#183629); +#183628 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183629 = VECTOR('',#183630,1.); +#183630 = DIRECTION('',(0.E+000,1.)); +#183631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183632 = PCURVE('',#183117,#183633); +#183633 = DEFINITIONAL_REPRESENTATION('',(#183634),#183637); +#183634 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183635,#183636), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181243 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#181244 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#181245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181246 = ORIENTED_EDGE('',*,*,#180676,.T.); -#181247 = ADVANCED_FACE('',(#181248),#180725,.T.); -#181248 = FACE_BOUND('',#181249,.T.); -#181249 = EDGE_LOOP('',(#181250,#181251,#181252,#181295)); -#181250 = ORIENTED_EDGE('',*,*,#181227,.T.); -#181251 = ORIENTED_EDGE('',*,*,#181125,.F.); -#181252 = ORIENTED_EDGE('',*,*,#181253,.F.); -#181253 = EDGE_CURVE('',#180705,#181103,#181254,.T.); -#181254 = SURFACE_CURVE('',#181255,(#181259,#181288),.PCURVE_S1.); -#181255 = LINE('',#181256,#181257); -#181256 = CARTESIAN_POINT('',(-0.515,-1.1307673058,-1.878014448176E-016) - ); -#181257 = VECTOR('',#181258,1.); -#181258 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181259 = PCURVE('',#180725,#181260); -#181260 = DEFINITIONAL_REPRESENTATION('',(#181261),#181287); -#181261 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#181262,#181263,#181264, - #181265,#181266,#181267,#181268,#181269,#181270,#181271,#181272, - #181273,#181274,#181275,#181276,#181277,#181278,#181279,#181280, - #181281,#181282,#181283,#181284,#181285,#181286),.UNSPECIFIED.,.F., +#183635 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#183636 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#183637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183638 = ORIENTED_EDGE('',*,*,#183068,.T.); +#183639 = ADVANCED_FACE('',(#183640),#183117,.T.); +#183640 = FACE_BOUND('',#183641,.T.); +#183641 = EDGE_LOOP('',(#183642,#183643,#183644,#183687)); +#183642 = ORIENTED_EDGE('',*,*,#183619,.T.); +#183643 = ORIENTED_EDGE('',*,*,#183517,.F.); +#183644 = ORIENTED_EDGE('',*,*,#183645,.F.); +#183645 = EDGE_CURVE('',#183097,#183495,#183646,.T.); +#183646 = SURFACE_CURVE('',#183647,(#183651,#183680),.PCURVE_S1.); +#183647 = LINE('',#183648,#183649); +#183648 = CARTESIAN_POINT('',(-0.515,-1.1307673058,-1.878014448176E-016) + ); +#183649 = VECTOR('',#183650,1.); +#183650 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183651 = PCURVE('',#183117,#183652); +#183652 = DEFINITIONAL_REPRESENTATION('',(#183653),#183679); +#183653 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183654,#183655,#183656, + #183657,#183658,#183659,#183660,#183661,#183662,#183663,#183664, + #183665,#183666,#183667,#183668,#183669,#183670,#183671,#183672, + #183673,#183674,#183675,#183676,#183677,#183678),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -224494,140 +227496,140 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#181262 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181263 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) - ); -#181264 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) - ); -#181265 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) - ); -#181266 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) - ); -#181267 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) - ); -#181268 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) - ); -#181269 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) - ); -#181270 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); -#181271 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); -#181272 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); -#181273 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); -#181274 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); -#181275 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); -#181276 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); -#181277 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); -#181278 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); -#181279 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); -#181280 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); -#181281 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); -#181282 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); -#181283 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); -#181284 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); -#181285 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); -#181286 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181288 = PCURVE('',#180752,#181289); -#181289 = DEFINITIONAL_REPRESENTATION('',(#181290),#181294); -#181290 = LINE('',#181291,#181292); -#181291 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#181292 = VECTOR('',#181293,1.); -#181293 = DIRECTION('',(-1.,0.E+000)); -#181294 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181295 = ORIENTED_EDGE('',*,*,#180704,.T.); -#181296 = ADVANCED_FACE('',(#181297),#180752,.T.); -#181297 = FACE_BOUND('',#181298,.T.); -#181298 = EDGE_LOOP('',(#181299,#181300,#181301,#181322)); -#181299 = ORIENTED_EDGE('',*,*,#181253,.T.); -#181300 = ORIENTED_EDGE('',*,*,#181102,.F.); -#181301 = ORIENTED_EDGE('',*,*,#181302,.F.); -#181302 = EDGE_CURVE('',#180737,#181080,#181303,.T.); -#181303 = SURFACE_CURVE('',#181304,(#181308,#181315),.PCURVE_S1.); -#181304 = LINE('',#181305,#181306); -#181305 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); -#181306 = VECTOR('',#181307,1.); -#181307 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181308 = PCURVE('',#180752,#181309); -#181309 = DEFINITIONAL_REPRESENTATION('',(#181310),#181314); -#181310 = LINE('',#181311,#181312); -#181311 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181312 = VECTOR('',#181313,1.); -#181313 = DIRECTION('',(-1.,0.E+000)); -#181314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181315 = PCURVE('',#180780,#181316); -#181316 = DEFINITIONAL_REPRESENTATION('',(#181317),#181321); -#181317 = LINE('',#181318,#181319); -#181318 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181319 = VECTOR('',#181320,1.); -#181320 = DIRECTION('',(0.E+000,1.)); -#181321 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181322 = ORIENTED_EDGE('',*,*,#180736,.T.); -#181323 = ADVANCED_FACE('',(#181324),#180780,.T.); -#181324 = FACE_BOUND('',#181325,.T.); -#181325 = EDGE_LOOP('',(#181326,#181327,#181328,#181349)); -#181326 = ORIENTED_EDGE('',*,*,#181302,.T.); -#181327 = ORIENTED_EDGE('',*,*,#181079,.F.); -#181328 = ORIENTED_EDGE('',*,*,#181329,.F.); -#181329 = EDGE_CURVE('',#180765,#181057,#181330,.T.); -#181330 = SURFACE_CURVE('',#181331,(#181335,#181342),.PCURVE_S1.); -#181331 = LINE('',#181332,#181333); -#181332 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); -#181333 = VECTOR('',#181334,1.); -#181334 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181335 = PCURVE('',#180780,#181336); -#181336 = DEFINITIONAL_REPRESENTATION('',(#181337),#181341); -#181337 = LINE('',#181338,#181339); -#181338 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#181339 = VECTOR('',#181340,1.); -#181340 = DIRECTION('',(0.E+000,1.)); -#181341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181342 = PCURVE('',#180808,#181343); -#181343 = DEFINITIONAL_REPRESENTATION('',(#181344),#181348); -#181344 = LINE('',#181345,#181346); -#181345 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181346 = VECTOR('',#181347,1.); -#181347 = DIRECTION('',(1.,0.E+000)); -#181348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181349 = ORIENTED_EDGE('',*,*,#180764,.T.); -#181350 = ADVANCED_FACE('',(#181351),#180808,.T.); -#181351 = FACE_BOUND('',#181352,.T.); -#181352 = EDGE_LOOP('',(#181353,#181354,#181355,#181398)); -#181353 = ORIENTED_EDGE('',*,*,#181329,.T.); -#181354 = ORIENTED_EDGE('',*,*,#181056,.F.); -#181355 = ORIENTED_EDGE('',*,*,#181356,.F.); -#181356 = EDGE_CURVE('',#180793,#181034,#181357,.T.); -#181357 = SURFACE_CURVE('',#181358,(#181362,#181369),.PCURVE_S1.); -#181358 = LINE('',#181359,#181360); -#181359 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.15)); -#181360 = VECTOR('',#181361,1.); -#181361 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181362 = PCURVE('',#180808,#181363); -#181363 = DEFINITIONAL_REPRESENTATION('',(#181364),#181368); -#181364 = LINE('',#181365,#181366); -#181365 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#181366 = VECTOR('',#181367,1.); -#181367 = DIRECTION('',(1.,0.E+000)); -#181368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181369 = PCURVE('',#180837,#181370); -#181370 = DEFINITIONAL_REPRESENTATION('',(#181371),#181397); -#181371 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#181372,#181373,#181374, - #181375,#181376,#181377,#181378,#181379,#181380,#181381,#181382, - #181383,#181384,#181385,#181386,#181387,#181388,#181389,#181390, - #181391,#181392,#181393,#181394,#181395,#181396),.UNSPECIFIED.,.F., +#183654 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183655 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) + ); +#183656 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) + ); +#183657 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) + ); +#183658 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) + ); +#183659 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) + ); +#183660 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) + ); +#183661 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) + ); +#183662 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); +#183663 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); +#183664 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); +#183665 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); +#183666 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); +#183667 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); +#183668 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); +#183669 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); +#183670 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); +#183671 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); +#183672 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); +#183673 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); +#183674 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); +#183675 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); +#183676 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); +#183677 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); +#183678 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183680 = PCURVE('',#183144,#183681); +#183681 = DEFINITIONAL_REPRESENTATION('',(#183682),#183686); +#183682 = LINE('',#183683,#183684); +#183683 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#183684 = VECTOR('',#183685,1.); +#183685 = DIRECTION('',(-1.,0.E+000)); +#183686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183687 = ORIENTED_EDGE('',*,*,#183096,.T.); +#183688 = ADVANCED_FACE('',(#183689),#183144,.T.); +#183689 = FACE_BOUND('',#183690,.T.); +#183690 = EDGE_LOOP('',(#183691,#183692,#183693,#183714)); +#183691 = ORIENTED_EDGE('',*,*,#183645,.T.); +#183692 = ORIENTED_EDGE('',*,*,#183494,.F.); +#183693 = ORIENTED_EDGE('',*,*,#183694,.F.); +#183694 = EDGE_CURVE('',#183129,#183472,#183695,.T.); +#183695 = SURFACE_CURVE('',#183696,(#183700,#183707),.PCURVE_S1.); +#183696 = LINE('',#183697,#183698); +#183697 = CARTESIAN_POINT('',(-0.515,-1.4,-1.335913361933E-016)); +#183698 = VECTOR('',#183699,1.); +#183699 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183700 = PCURVE('',#183144,#183701); +#183701 = DEFINITIONAL_REPRESENTATION('',(#183702),#183706); +#183702 = LINE('',#183703,#183704); +#183703 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183704 = VECTOR('',#183705,1.); +#183705 = DIRECTION('',(-1.,0.E+000)); +#183706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183707 = PCURVE('',#183172,#183708); +#183708 = DEFINITIONAL_REPRESENTATION('',(#183709),#183713); +#183709 = LINE('',#183710,#183711); +#183710 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183711 = VECTOR('',#183712,1.); +#183712 = DIRECTION('',(0.E+000,1.)); +#183713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183714 = ORIENTED_EDGE('',*,*,#183128,.T.); +#183715 = ADVANCED_FACE('',(#183716),#183172,.T.); +#183716 = FACE_BOUND('',#183717,.T.); +#183717 = EDGE_LOOP('',(#183718,#183719,#183720,#183741)); +#183718 = ORIENTED_EDGE('',*,*,#183694,.T.); +#183719 = ORIENTED_EDGE('',*,*,#183471,.F.); +#183720 = ORIENTED_EDGE('',*,*,#183721,.F.); +#183721 = EDGE_CURVE('',#183157,#183449,#183722,.T.); +#183722 = SURFACE_CURVE('',#183723,(#183727,#183734),.PCURVE_S1.); +#183723 = LINE('',#183724,#183725); +#183724 = CARTESIAN_POINT('',(-0.515,-1.4,0.15)); +#183725 = VECTOR('',#183726,1.); +#183726 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183727 = PCURVE('',#183172,#183728); +#183728 = DEFINITIONAL_REPRESENTATION('',(#183729),#183733); +#183729 = LINE('',#183730,#183731); +#183730 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#183731 = VECTOR('',#183732,1.); +#183732 = DIRECTION('',(0.E+000,1.)); +#183733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183734 = PCURVE('',#183200,#183735); +#183735 = DEFINITIONAL_REPRESENTATION('',(#183736),#183740); +#183736 = LINE('',#183737,#183738); +#183737 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183738 = VECTOR('',#183739,1.); +#183739 = DIRECTION('',(1.,0.E+000)); +#183740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183741 = ORIENTED_EDGE('',*,*,#183156,.T.); +#183742 = ADVANCED_FACE('',(#183743),#183200,.T.); +#183743 = FACE_BOUND('',#183744,.T.); +#183744 = EDGE_LOOP('',(#183745,#183746,#183747,#183790)); +#183745 = ORIENTED_EDGE('',*,*,#183721,.T.); +#183746 = ORIENTED_EDGE('',*,*,#183448,.F.); +#183747 = ORIENTED_EDGE('',*,*,#183748,.F.); +#183748 = EDGE_CURVE('',#183185,#183426,#183749,.T.); +#183749 = SURFACE_CURVE('',#183750,(#183754,#183761),.PCURVE_S1.); +#183750 = LINE('',#183751,#183752); +#183751 = CARTESIAN_POINT('',(-0.515,-1.1307673058,0.15)); +#183752 = VECTOR('',#183753,1.); +#183753 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183754 = PCURVE('',#183200,#183755); +#183755 = DEFINITIONAL_REPRESENTATION('',(#183756),#183760); +#183756 = LINE('',#183757,#183758); +#183757 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#183758 = VECTOR('',#183759,1.); +#183759 = DIRECTION('',(1.,0.E+000)); +#183760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183761 = PCURVE('',#183229,#183762); +#183762 = DEFINITIONAL_REPRESENTATION('',(#183763),#183789); +#183763 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183764,#183765,#183766, + #183767,#183768,#183769,#183770,#183771,#183772,#183773,#183774, + #183775,#183776,#183777,#183778,#183779,#183780,#183781,#183782, + #183783,#183784,#183785,#183786,#183787,#183788),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -224635,955 +227637,955 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#181372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181373 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); -#181374 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) - ); -#181375 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); -#181376 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) - ); -#181377 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) - ); -#181378 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) - ); -#181379 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) - ); -#181380 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); -#181381 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); -#181382 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); -#181383 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); -#181384 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); -#181385 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); -#181386 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); -#181387 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); -#181388 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); -#181389 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); -#181390 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); -#181391 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); -#181392 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); -#181393 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); -#181394 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); -#181395 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); -#181396 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181398 = ORIENTED_EDGE('',*,*,#180792,.T.); -#181399 = ADVANCED_FACE('',(#181400),#180837,.F.); -#181400 = FACE_BOUND('',#181401,.F.); -#181401 = EDGE_LOOP('',(#181402,#181403,#181404,#181424)); -#181402 = ORIENTED_EDGE('',*,*,#181356,.F.); -#181403 = ORIENTED_EDGE('',*,*,#180820,.F.); -#181404 = ORIENTED_EDGE('',*,*,#181405,.T.); -#181405 = EDGE_CURVE('',#180821,#181011,#181406,.T.); -#181406 = SURFACE_CURVE('',#181407,(#181411,#181417),.PCURVE_S1.); -#181407 = LINE('',#181408,#181409); -#181408 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); -#181409 = VECTOR('',#181410,1.); -#181410 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181411 = PCURVE('',#180837,#181412); -#181412 = DEFINITIONAL_REPRESENTATION('',(#181413),#181416); -#181413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181414,#181415), +#183764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183765 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); +#183766 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) + ); +#183767 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); +#183768 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) + ); +#183769 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) + ); +#183770 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) + ); +#183771 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) + ); +#183772 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); +#183773 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); +#183774 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); +#183775 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); +#183776 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); +#183777 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); +#183778 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); +#183779 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); +#183780 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); +#183781 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); +#183782 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); +#183783 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); +#183784 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); +#183785 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); +#183786 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); +#183787 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); +#183788 = CARTESIAN_POINT('',(0.E+000,0.34)); +#183789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183790 = ORIENTED_EDGE('',*,*,#183184,.T.); +#183791 = ADVANCED_FACE('',(#183792),#183229,.F.); +#183792 = FACE_BOUND('',#183793,.F.); +#183793 = EDGE_LOOP('',(#183794,#183795,#183796,#183816)); +#183794 = ORIENTED_EDGE('',*,*,#183748,.F.); +#183795 = ORIENTED_EDGE('',*,*,#183212,.F.); +#183796 = ORIENTED_EDGE('',*,*,#183797,.T.); +#183797 = EDGE_CURVE('',#183213,#183403,#183798,.T.); +#183798 = SURFACE_CURVE('',#183799,(#183803,#183809),.PCURVE_S1.); +#183799 = LINE('',#183800,#183801); +#183800 = CARTESIAN_POINT('',(-0.515,-1.080909188472,0.19623594148)); +#183801 = VECTOR('',#183802,1.); +#183802 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183803 = PCURVE('',#183229,#183804); +#183804 = DEFINITIONAL_REPRESENTATION('',(#183805),#183808); +#183805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183806,#183807), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181414 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#181415 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#181416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181417 = PCURVE('',#180864,#181418); -#181418 = DEFINITIONAL_REPRESENTATION('',(#181419),#181423); -#181419 = LINE('',#181420,#181421); -#181420 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181421 = VECTOR('',#181422,1.); -#181422 = DIRECTION('',(0.E+000,1.)); -#181423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181424 = ORIENTED_EDGE('',*,*,#181033,.T.); -#181425 = ADVANCED_FACE('',(#181426),#180864,.T.); -#181426 = FACE_BOUND('',#181427,.T.); -#181427 = EDGE_LOOP('',(#181428,#181429,#181430,#181450)); -#181428 = ORIENTED_EDGE('',*,*,#181405,.T.); -#181429 = ORIENTED_EDGE('',*,*,#181010,.F.); -#181430 = ORIENTED_EDGE('',*,*,#181431,.F.); -#181431 = EDGE_CURVE('',#180849,#180984,#181432,.T.); -#181432 = SURFACE_CURVE('',#181433,(#181437,#181444),.PCURVE_S1.); -#181433 = LINE('',#181434,#181435); -#181434 = CARTESIAN_POINT('',(-0.515,-1.056555553792,0.518820292599)); -#181435 = VECTOR('',#181436,1.); -#181436 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181437 = PCURVE('',#180864,#181438); -#181438 = DEFINITIONAL_REPRESENTATION('',(#181439),#181443); -#181439 = LINE('',#181440,#181441); -#181440 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#181441 = VECTOR('',#181442,1.); -#181442 = DIRECTION('',(0.E+000,1.)); -#181443 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181444 = PCURVE('',#180897,#181445); -#181445 = DEFINITIONAL_REPRESENTATION('',(#181446),#181449); -#181446 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181447,#181448), +#183806 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#183807 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#183808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183809 = PCURVE('',#183256,#183810); +#183810 = DEFINITIONAL_REPRESENTATION('',(#183811),#183815); +#183811 = LINE('',#183812,#183813); +#183812 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183813 = VECTOR('',#183814,1.); +#183814 = DIRECTION('',(0.E+000,1.)); +#183815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183816 = ORIENTED_EDGE('',*,*,#183425,.T.); +#183817 = ADVANCED_FACE('',(#183818),#183256,.T.); +#183818 = FACE_BOUND('',#183819,.T.); +#183819 = EDGE_LOOP('',(#183820,#183821,#183822,#183842)); +#183820 = ORIENTED_EDGE('',*,*,#183797,.T.); +#183821 = ORIENTED_EDGE('',*,*,#183402,.F.); +#183822 = ORIENTED_EDGE('',*,*,#183823,.F.); +#183823 = EDGE_CURVE('',#183241,#183376,#183824,.T.); +#183824 = SURFACE_CURVE('',#183825,(#183829,#183836),.PCURVE_S1.); +#183825 = LINE('',#183826,#183827); +#183826 = CARTESIAN_POINT('',(-0.515,-1.056555553792,0.518820292599)); +#183827 = VECTOR('',#183828,1.); +#183828 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183829 = PCURVE('',#183256,#183830); +#183830 = DEFINITIONAL_REPRESENTATION('',(#183831),#183835); +#183831 = LINE('',#183832,#183833); +#183832 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#183833 = VECTOR('',#183834,1.); +#183834 = DIRECTION('',(0.E+000,1.)); +#183835 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183836 = PCURVE('',#183289,#183837); +#183837 = DEFINITIONAL_REPRESENTATION('',(#183838),#183841); +#183838 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183839,#183840), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181447 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#181448 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#181449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181450 = ORIENTED_EDGE('',*,*,#180848,.T.); -#181451 = ADVANCED_FACE('',(#181452),#180897,.T.); -#181452 = FACE_BOUND('',#181453,.T.); -#181453 = EDGE_LOOP('',(#181454,#181455,#181456,#181457)); -#181454 = ORIENTED_EDGE('',*,*,#181431,.T.); -#181455 = ORIENTED_EDGE('',*,*,#180983,.F.); -#181456 = ORIENTED_EDGE('',*,*,#180932,.F.); -#181457 = ORIENTED_EDGE('',*,*,#180876,.T.); -#181458 = ADVANCED_FACE('',(#181459),#172085,.T.); -#181459 = FACE_BOUND('',#181460,.T.); -#181460 = EDGE_LOOP('',(#181461,#181462,#181485,#181512)); -#181461 = ORIENTED_EDGE('',*,*,#172069,.T.); -#181462 = ORIENTED_EDGE('',*,*,#181463,.F.); -#181463 = EDGE_CURVE('',#181464,#172047,#181466,.T.); -#181464 = VERTEX_POINT('',#181465); -#181465 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.6)); -#181466 = SURFACE_CURVE('',#181467,(#181471,#181478),.PCURVE_S1.); -#181467 = LINE('',#181468,#181469); -#181468 = CARTESIAN_POINT('',(-0.825,-0.7,0.6)); -#181469 = VECTOR('',#181470,1.); -#181470 = DIRECTION('',(0.E+000,1.,0.E+000)); -#181471 = PCURVE('',#172085,#181472); -#181472 = DEFINITIONAL_REPRESENTATION('',(#181473),#181477); -#181473 = LINE('',#181474,#181475); -#181474 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#181475 = VECTOR('',#181476,1.); -#181476 = DIRECTION('',(0.E+000,1.)); -#181477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181478 = PCURVE('',#173172,#181479); -#181479 = DEFINITIONAL_REPRESENTATION('',(#181480),#181484); -#181480 = LINE('',#181481,#181482); -#181481 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#181482 = VECTOR('',#181483,1.); -#181483 = DIRECTION('',(0.E+000,1.)); -#181484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181485 = ORIENTED_EDGE('',*,*,#181486,.F.); -#181486 = EDGE_CURVE('',#181487,#181464,#181489,.T.); -#181487 = VERTEX_POINT('',#181488); -#181488 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.6)); -#181489 = SURFACE_CURVE('',#181490,(#181494,#181501),.PCURVE_S1.); -#181490 = LINE('',#181491,#181492); -#181491 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.6)); -#181492 = VECTOR('',#181493,1.); -#181493 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181494 = PCURVE('',#172085,#181495); -#181495 = DEFINITIONAL_REPRESENTATION('',(#181496),#181500); -#181496 = LINE('',#181497,#181498); -#181497 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); -#181498 = VECTOR('',#181499,1.); -#181499 = DIRECTION('',(-1.,0.E+000)); -#181500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181501 = PCURVE('',#181502,#181507); -#181502 = CYLINDRICAL_SURFACE('',#181503,0.1); -#181503 = AXIS2_PLACEMENT_3D('',#181504,#181505,#181506); -#181504 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); -#181505 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181506 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181507 = DEFINITIONAL_REPRESENTATION('',(#181508),#181511); -#181508 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181509,#181510), +#183839 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#183840 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#183841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183842 = ORIENTED_EDGE('',*,*,#183240,.T.); +#183843 = ADVANCED_FACE('',(#183844),#183289,.T.); +#183844 = FACE_BOUND('',#183845,.T.); +#183845 = EDGE_LOOP('',(#183846,#183847,#183848,#183849)); +#183846 = ORIENTED_EDGE('',*,*,#183823,.T.); +#183847 = ORIENTED_EDGE('',*,*,#183375,.F.); +#183848 = ORIENTED_EDGE('',*,*,#183324,.F.); +#183849 = ORIENTED_EDGE('',*,*,#183268,.T.); +#183850 = ADVANCED_FACE('',(#183851),#174477,.T.); +#183851 = FACE_BOUND('',#183852,.T.); +#183852 = EDGE_LOOP('',(#183853,#183854,#183877,#183904)); +#183853 = ORIENTED_EDGE('',*,*,#174461,.T.); +#183854 = ORIENTED_EDGE('',*,*,#183855,.F.); +#183855 = EDGE_CURVE('',#183856,#174439,#183858,.T.); +#183856 = VERTEX_POINT('',#183857); +#183857 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.6)); +#183858 = SURFACE_CURVE('',#183859,(#183863,#183870),.PCURVE_S1.); +#183859 = LINE('',#183860,#183861); +#183860 = CARTESIAN_POINT('',(-0.825,-0.7,0.6)); +#183861 = VECTOR('',#183862,1.); +#183862 = DIRECTION('',(0.E+000,1.,0.E+000)); +#183863 = PCURVE('',#174477,#183864); +#183864 = DEFINITIONAL_REPRESENTATION('',(#183865),#183869); +#183865 = LINE('',#183866,#183867); +#183866 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#183867 = VECTOR('',#183868,1.); +#183868 = DIRECTION('',(0.E+000,1.)); +#183869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183870 = PCURVE('',#175564,#183871); +#183871 = DEFINITIONAL_REPRESENTATION('',(#183872),#183876); +#183872 = LINE('',#183873,#183874); +#183873 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#183874 = VECTOR('',#183875,1.); +#183875 = DIRECTION('',(0.E+000,1.)); +#183876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183877 = ORIENTED_EDGE('',*,*,#183878,.F.); +#183878 = EDGE_CURVE('',#183879,#183856,#183881,.T.); +#183879 = VERTEX_POINT('',#183880); +#183880 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.6)); +#183881 = SURFACE_CURVE('',#183882,(#183886,#183893),.PCURVE_S1.); +#183882 = LINE('',#183883,#183884); +#183883 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.6)); +#183884 = VECTOR('',#183885,1.); +#183885 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183886 = PCURVE('',#174477,#183887); +#183887 = DEFINITIONAL_REPRESENTATION('',(#183888),#183892); +#183888 = LINE('',#183889,#183890); +#183889 = CARTESIAN_POINT('',(0.E+000,-0.107264967154)); +#183890 = VECTOR('',#183891,1.); +#183891 = DIRECTION('',(-1.,0.E+000)); +#183892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183893 = PCURVE('',#183894,#183899); +#183894 = CYLINDRICAL_SURFACE('',#183895,0.1); +#183895 = AXIS2_PLACEMENT_3D('',#183896,#183897,#183898); +#183896 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); +#183897 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183898 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183899 = DEFINITIONAL_REPRESENTATION('',(#183900),#183903); +#183900 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183901,#183902), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181509 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#181510 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#181511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181512 = ORIENTED_EDGE('',*,*,#181513,.T.); -#181513 = EDGE_CURVE('',#181487,#172070,#181514,.T.); -#181514 = SURFACE_CURVE('',#181515,(#181519,#181526),.PCURVE_S1.); -#181515 = LINE('',#181516,#181517); -#181516 = CARTESIAN_POINT('',(-1.165,-0.7,0.6)); -#181517 = VECTOR('',#181518,1.); -#181518 = DIRECTION('',(0.E+000,1.,0.E+000)); -#181519 = PCURVE('',#172085,#181520); -#181520 = DEFINITIONAL_REPRESENTATION('',(#181521),#181525); -#181521 = LINE('',#181522,#181523); -#181522 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181523 = VECTOR('',#181524,1.); -#181524 = DIRECTION('',(0.E+000,1.)); -#181525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181526 = PCURVE('',#173118,#181527); -#181527 = DEFINITIONAL_REPRESENTATION('',(#181528),#181532); -#181528 = LINE('',#181529,#181530); -#181529 = CARTESIAN_POINT('',(0.1,0.107264967154)); -#181530 = VECTOR('',#181531,1.); -#181531 = DIRECTION('',(0.E+000,1.)); -#181532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181533 = ADVANCED_FACE('',(#181534),#173118,.T.); -#181534 = FACE_BOUND('',#181535,.T.); -#181535 = EDGE_LOOP('',(#181536,#181537,#181538,#181561,#181589,#181621, - #181649,#181677,#181705,#181733,#181761,#181793)); -#181536 = ORIENTED_EDGE('',*,*,#173102,.F.); -#181537 = ORIENTED_EDGE('',*,*,#181513,.F.); -#181538 = ORIENTED_EDGE('',*,*,#181539,.F.); -#181539 = EDGE_CURVE('',#181540,#181487,#181542,.T.); -#181540 = VERTEX_POINT('',#181541); -#181541 = CARTESIAN_POINT('',(-1.165,-0.906981201809,0.50752811704)); -#181542 = SURFACE_CURVE('',#181543,(#181548,#181555),.PCURVE_S1.); -#181543 = CIRCLE('',#181544,0.1); -#181544 = AXIS2_PLACEMENT_3D('',#181545,#181546,#181547); -#181545 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); -#181546 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181547 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181548 = PCURVE('',#173118,#181549); -#181549 = DEFINITIONAL_REPRESENTATION('',(#181550),#181554); -#181550 = CIRCLE('',#181551,0.1); -#181551 = AXIS2_PLACEMENT_2D('',#181552,#181553); -#181552 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#181553 = DIRECTION('',(-1.,0.E+000)); -#181554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181555 = PCURVE('',#181502,#181556); -#181556 = DEFINITIONAL_REPRESENTATION('',(#181557),#181560); -#181557 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181558,#181559), +#183901 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183902 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#183903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183904 = ORIENTED_EDGE('',*,*,#183905,.T.); +#183905 = EDGE_CURVE('',#183879,#174462,#183906,.T.); +#183906 = SURFACE_CURVE('',#183907,(#183911,#183918),.PCURVE_S1.); +#183907 = LINE('',#183908,#183909); +#183908 = CARTESIAN_POINT('',(-1.165,-0.7,0.6)); +#183909 = VECTOR('',#183910,1.); +#183910 = DIRECTION('',(0.E+000,1.,0.E+000)); +#183911 = PCURVE('',#174477,#183912); +#183912 = DEFINITIONAL_REPRESENTATION('',(#183913),#183917); +#183913 = LINE('',#183914,#183915); +#183914 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183915 = VECTOR('',#183916,1.); +#183916 = DIRECTION('',(0.E+000,1.)); +#183917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183918 = PCURVE('',#175510,#183919); +#183919 = DEFINITIONAL_REPRESENTATION('',(#183920),#183924); +#183920 = LINE('',#183921,#183922); +#183921 = CARTESIAN_POINT('',(0.1,0.107264967154)); +#183922 = VECTOR('',#183923,1.); +#183923 = DIRECTION('',(0.E+000,1.)); +#183924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183925 = ADVANCED_FACE('',(#183926),#175510,.T.); +#183926 = FACE_BOUND('',#183927,.T.); +#183927 = EDGE_LOOP('',(#183928,#183929,#183930,#183953,#183981,#184013, + #184041,#184069,#184097,#184125,#184153,#184185)); +#183928 = ORIENTED_EDGE('',*,*,#175494,.F.); +#183929 = ORIENTED_EDGE('',*,*,#183905,.F.); +#183930 = ORIENTED_EDGE('',*,*,#183931,.F.); +#183931 = EDGE_CURVE('',#183932,#183879,#183934,.T.); +#183932 = VERTEX_POINT('',#183933); +#183933 = CARTESIAN_POINT('',(-1.165,-0.906981201809,0.50752811704)); +#183934 = SURFACE_CURVE('',#183935,(#183940,#183947),.PCURVE_S1.); +#183935 = CIRCLE('',#183936,0.1); +#183936 = AXIS2_PLACEMENT_3D('',#183937,#183938,#183939); +#183937 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); +#183938 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#183939 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183940 = PCURVE('',#175510,#183941); +#183941 = DEFINITIONAL_REPRESENTATION('',(#183942),#183946); +#183942 = CIRCLE('',#183943,0.1); +#183943 = AXIS2_PLACEMENT_2D('',#183944,#183945); +#183944 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#183945 = DIRECTION('',(-1.,0.E+000)); +#183946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183947 = PCURVE('',#183894,#183948); +#183948 = DEFINITIONAL_REPRESENTATION('',(#183949),#183952); +#183949 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183950,#183951), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#181558 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#181559 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#181560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181561 = ORIENTED_EDGE('',*,*,#181562,.F.); -#181562 = EDGE_CURVE('',#181563,#181540,#181565,.T.); -#181563 = VERTEX_POINT('',#181564); -#181564 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); -#181565 = SURFACE_CURVE('',#181566,(#181570,#181577),.PCURVE_S1.); -#181566 = LINE('',#181567,#181568); -#181567 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); -#181568 = VECTOR('',#181569,1.); -#181569 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#181570 = PCURVE('',#173118,#181571); -#181571 = DEFINITIONAL_REPRESENTATION('',(#181572),#181576); -#181572 = LINE('',#181573,#181574); -#181573 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#181574 = VECTOR('',#181575,1.); -#181575 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#181576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181577 = PCURVE('',#181578,#181583); -#181578 = PLANE('',#181579); -#181579 = AXIS2_PLACEMENT_3D('',#181580,#181581,#181582); -#181580 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); -#181581 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); -#181582 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#181583 = DEFINITIONAL_REPRESENTATION('',(#181584),#181588); -#181584 = LINE('',#181585,#181586); -#181585 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181586 = VECTOR('',#181587,1.); -#181587 = DIRECTION('',(1.,0.E+000)); -#181588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181589 = ORIENTED_EDGE('',*,*,#181590,.F.); -#181590 = EDGE_CURVE('',#181591,#181563,#181593,.T.); -#181591 = VERTEX_POINT('',#181592); -#181592 = CARTESIAN_POINT('',(-1.165,-1.1307673058,-2.545971129142E-016) - ); -#181593 = SURFACE_CURVE('',#181594,(#181599,#181610),.PCURVE_S1.); -#181594 = CIRCLE('',#181595,0.2); -#181595 = AXIS2_PLACEMENT_3D('',#181596,#181597,#181598); -#181596 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); -#181597 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181598 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181599 = PCURVE('',#173118,#181600); -#181600 = DEFINITIONAL_REPRESENTATION('',(#181601),#181609); -#181601 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181602,#181603,#181604, - #181605,#181606,#181607,#181608),.UNSPECIFIED.,.T.,.F.) +#183950 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#183951 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#183952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183953 = ORIENTED_EDGE('',*,*,#183954,.F.); +#183954 = EDGE_CURVE('',#183955,#183932,#183957,.T.); +#183955 = VERTEX_POINT('',#183956); +#183956 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); +#183957 = SURFACE_CURVE('',#183958,(#183962,#183969),.PCURVE_S1.); +#183958 = LINE('',#183959,#183960); +#183959 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); +#183960 = VECTOR('',#183961,1.); +#183961 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#183962 = PCURVE('',#175510,#183963); +#183963 = DEFINITIONAL_REPRESENTATION('',(#183964),#183968); +#183964 = LINE('',#183965,#183966); +#183965 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#183966 = VECTOR('',#183967,1.); +#183967 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#183968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183969 = PCURVE('',#183970,#183975); +#183970 = PLANE('',#183971); +#183971 = AXIS2_PLACEMENT_3D('',#183972,#183973,#183974); +#183972 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); +#183973 = DIRECTION('',(0.E+000,0.997162346553,-7.528117039715E-002)); +#183974 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#183975 = DEFINITIONAL_REPRESENTATION('',(#183976),#183980); +#183976 = LINE('',#183977,#183978); +#183977 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#183978 = VECTOR('',#183979,1.); +#183979 = DIRECTION('',(1.,0.E+000)); +#183980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#183981 = ORIENTED_EDGE('',*,*,#183982,.F.); +#183982 = EDGE_CURVE('',#183983,#183955,#183985,.T.); +#183983 = VERTEX_POINT('',#183984); +#183984 = CARTESIAN_POINT('',(-1.165,-1.1307673058,-2.545971129142E-016) + ); +#183985 = SURFACE_CURVE('',#183986,(#183991,#184002),.PCURVE_S1.); +#183986 = CIRCLE('',#183987,0.2); +#183987 = AXIS2_PLACEMENT_3D('',#183988,#183989,#183990); +#183988 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); +#183989 = DIRECTION('',(1.,0.E+000,0.E+000)); +#183990 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#183991 = PCURVE('',#175510,#183992); +#183992 = DEFINITIONAL_REPRESENTATION('',(#183993),#184001); +#183993 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#183994,#183995,#183996, + #183997,#183998,#183999,#184000),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#181602 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#181603 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#181604 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#181605 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#181606 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#181607 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#181608 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#181609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181610 = PCURVE('',#181611,#181616); -#181611 = CYLINDRICAL_SURFACE('',#181612,0.2); -#181612 = AXIS2_PLACEMENT_3D('',#181613,#181614,#181615); -#181613 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); -#181614 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181615 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181616 = DEFINITIONAL_REPRESENTATION('',(#181617),#181620); -#181617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181618,#181619), +#183994 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#183995 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#183996 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#183997 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#183998 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#183999 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#184000 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#184001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184002 = PCURVE('',#184003,#184008); +#184003 = CYLINDRICAL_SURFACE('',#184004,0.2); +#184004 = AXIS2_PLACEMENT_3D('',#184005,#184006,#184007); +#184005 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); +#184006 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184007 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184008 = DEFINITIONAL_REPRESENTATION('',(#184009),#184012); +#184009 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184010,#184011), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#181618 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181619 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#181620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181621 = ORIENTED_EDGE('',*,*,#181622,.F.); -#181622 = EDGE_CURVE('',#181623,#181591,#181625,.T.); -#181623 = VERTEX_POINT('',#181624); -#181624 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#181625 = SURFACE_CURVE('',#181626,(#181630,#181637),.PCURVE_S1.); -#181626 = LINE('',#181627,#181628); -#181627 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#181628 = VECTOR('',#181629,1.); -#181629 = DIRECTION('',(0.E+000,1.,0.E+000)); -#181630 = PCURVE('',#173118,#181631); -#181631 = DEFINITIONAL_REPRESENTATION('',(#181632),#181636); -#181632 = LINE('',#181633,#181634); -#181633 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#181634 = VECTOR('',#181635,1.); -#181635 = DIRECTION('',(0.E+000,1.)); -#181636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181637 = PCURVE('',#181638,#181643); -#181638 = PLANE('',#181639); -#181639 = AXIS2_PLACEMENT_3D('',#181640,#181641,#181642); -#181640 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#181641 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181642 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181643 = DEFINITIONAL_REPRESENTATION('',(#181644),#181648); -#181644 = LINE('',#181645,#181646); -#181645 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181646 = VECTOR('',#181647,1.); -#181647 = DIRECTION('',(0.E+000,1.)); -#181648 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181649 = ORIENTED_EDGE('',*,*,#181650,.F.); -#181650 = EDGE_CURVE('',#181651,#181623,#181653,.T.); -#181651 = VERTEX_POINT('',#181652); -#181652 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); -#181653 = SURFACE_CURVE('',#181654,(#181658,#181665),.PCURVE_S1.); -#181654 = LINE('',#181655,#181656); -#181655 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#181656 = VECTOR('',#181657,1.); -#181657 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181658 = PCURVE('',#173118,#181659); -#181659 = DEFINITIONAL_REPRESENTATION('',(#181660),#181664); -#181660 = LINE('',#181661,#181662); -#181661 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#181662 = VECTOR('',#181663,1.); -#181663 = DIRECTION('',(-1.,0.E+000)); -#181664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181665 = PCURVE('',#181666,#181671); -#181666 = PLANE('',#181667); -#181667 = AXIS2_PLACEMENT_3D('',#181668,#181669,#181670); -#181668 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#181669 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181670 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181671 = DEFINITIONAL_REPRESENTATION('',(#181672),#181676); -#181672 = LINE('',#181673,#181674); -#181673 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181674 = VECTOR('',#181675,1.); -#181675 = DIRECTION('',(1.,0.E+000)); -#181676 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181677 = ORIENTED_EDGE('',*,*,#181678,.F.); -#181678 = EDGE_CURVE('',#181679,#181651,#181681,.T.); -#181679 = VERTEX_POINT('',#181680); -#181680 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.15)); -#181681 = SURFACE_CURVE('',#181682,(#181686,#181693),.PCURVE_S1.); -#181682 = LINE('',#181683,#181684); -#181683 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); -#181684 = VECTOR('',#181685,1.); -#181685 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181686 = PCURVE('',#173118,#181687); -#181687 = DEFINITIONAL_REPRESENTATION('',(#181688),#181692); -#181688 = LINE('',#181689,#181690); -#181689 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#181690 = VECTOR('',#181691,1.); -#181691 = DIRECTION('',(0.E+000,-1.)); -#181692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181693 = PCURVE('',#181694,#181699); -#181694 = PLANE('',#181695); -#181695 = AXIS2_PLACEMENT_3D('',#181696,#181697,#181698); -#181696 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); -#181697 = DIRECTION('',(0.E+000,0.E+000,1.)); -#181698 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181699 = DEFINITIONAL_REPRESENTATION('',(#181700),#181704); -#181700 = LINE('',#181701,#181702); -#181701 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181702 = VECTOR('',#181703,1.); -#181703 = DIRECTION('',(0.E+000,-1.)); -#181704 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181705 = ORIENTED_EDGE('',*,*,#181706,.F.); -#181706 = EDGE_CURVE('',#181707,#181679,#181709,.T.); -#181707 = VERTEX_POINT('',#181708); -#181708 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); -#181709 = SURFACE_CURVE('',#181710,(#181715,#181722),.PCURVE_S1.); -#181710 = CIRCLE('',#181711,5.E-002); -#181711 = AXIS2_PLACEMENT_3D('',#181712,#181713,#181714); -#181712 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); -#181713 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181714 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181715 = PCURVE('',#173118,#181716); -#181716 = DEFINITIONAL_REPRESENTATION('',(#181717),#181721); -#181717 = CIRCLE('',#181718,5.E-002); -#181718 = AXIS2_PLACEMENT_2D('',#181719,#181720); -#181719 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#181720 = DIRECTION('',(-1.,0.E+000)); -#181721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181722 = PCURVE('',#181723,#181728); -#181723 = CYLINDRICAL_SURFACE('',#181724,5.E-002); -#181724 = AXIS2_PLACEMENT_3D('',#181725,#181726,#181727); -#181725 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); -#181726 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181727 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181728 = DEFINITIONAL_REPRESENTATION('',(#181729),#181732); -#181729 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181730,#181731), +#184010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184011 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#184012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184013 = ORIENTED_EDGE('',*,*,#184014,.F.); +#184014 = EDGE_CURVE('',#184015,#183983,#184017,.T.); +#184015 = VERTEX_POINT('',#184016); +#184016 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184017 = SURFACE_CURVE('',#184018,(#184022,#184029),.PCURVE_S1.); +#184018 = LINE('',#184019,#184020); +#184019 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184020 = VECTOR('',#184021,1.); +#184021 = DIRECTION('',(0.E+000,1.,0.E+000)); +#184022 = PCURVE('',#175510,#184023); +#184023 = DEFINITIONAL_REPRESENTATION('',(#184024),#184028); +#184024 = LINE('',#184025,#184026); +#184025 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#184026 = VECTOR('',#184027,1.); +#184027 = DIRECTION('',(0.E+000,1.)); +#184028 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184029 = PCURVE('',#184030,#184035); +#184030 = PLANE('',#184031); +#184031 = AXIS2_PLACEMENT_3D('',#184032,#184033,#184034); +#184032 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184033 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184034 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184035 = DEFINITIONAL_REPRESENTATION('',(#184036),#184040); +#184036 = LINE('',#184037,#184038); +#184037 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184038 = VECTOR('',#184039,1.); +#184039 = DIRECTION('',(0.E+000,1.)); +#184040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184041 = ORIENTED_EDGE('',*,*,#184042,.F.); +#184042 = EDGE_CURVE('',#184043,#184015,#184045,.T.); +#184043 = VERTEX_POINT('',#184044); +#184044 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); +#184045 = SURFACE_CURVE('',#184046,(#184050,#184057),.PCURVE_S1.); +#184046 = LINE('',#184047,#184048); +#184047 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184048 = VECTOR('',#184049,1.); +#184049 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184050 = PCURVE('',#175510,#184051); +#184051 = DEFINITIONAL_REPRESENTATION('',(#184052),#184056); +#184052 = LINE('',#184053,#184054); +#184053 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#184054 = VECTOR('',#184055,1.); +#184055 = DIRECTION('',(-1.,0.E+000)); +#184056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184057 = PCURVE('',#184058,#184063); +#184058 = PLANE('',#184059); +#184059 = AXIS2_PLACEMENT_3D('',#184060,#184061,#184062); +#184060 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184061 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#184062 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184063 = DEFINITIONAL_REPRESENTATION('',(#184064),#184068); +#184064 = LINE('',#184065,#184066); +#184065 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184066 = VECTOR('',#184067,1.); +#184067 = DIRECTION('',(1.,0.E+000)); +#184068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184069 = ORIENTED_EDGE('',*,*,#184070,.F.); +#184070 = EDGE_CURVE('',#184071,#184043,#184073,.T.); +#184071 = VERTEX_POINT('',#184072); +#184072 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.15)); +#184073 = SURFACE_CURVE('',#184074,(#184078,#184085),.PCURVE_S1.); +#184074 = LINE('',#184075,#184076); +#184075 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); +#184076 = VECTOR('',#184077,1.); +#184077 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#184078 = PCURVE('',#175510,#184079); +#184079 = DEFINITIONAL_REPRESENTATION('',(#184080),#184084); +#184080 = LINE('',#184081,#184082); +#184081 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#184082 = VECTOR('',#184083,1.); +#184083 = DIRECTION('',(0.E+000,-1.)); +#184084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184085 = PCURVE('',#184086,#184091); +#184086 = PLANE('',#184087); +#184087 = AXIS2_PLACEMENT_3D('',#184088,#184089,#184090); +#184088 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); +#184089 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184090 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184091 = DEFINITIONAL_REPRESENTATION('',(#184092),#184096); +#184092 = LINE('',#184093,#184094); +#184093 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184094 = VECTOR('',#184095,1.); +#184095 = DIRECTION('',(0.E+000,-1.)); +#184096 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184097 = ORIENTED_EDGE('',*,*,#184098,.F.); +#184098 = EDGE_CURVE('',#184099,#184071,#184101,.T.); +#184099 = VERTEX_POINT('',#184100); +#184100 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); +#184101 = SURFACE_CURVE('',#184102,(#184107,#184114),.PCURVE_S1.); +#184102 = CIRCLE('',#184103,5.E-002); +#184103 = AXIS2_PLACEMENT_3D('',#184104,#184105,#184106); +#184104 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); +#184105 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184106 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184107 = PCURVE('',#175510,#184108); +#184108 = DEFINITIONAL_REPRESENTATION('',(#184109),#184113); +#184109 = CIRCLE('',#184110,5.E-002); +#184110 = AXIS2_PLACEMENT_2D('',#184111,#184112); +#184111 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#184112 = DIRECTION('',(-1.,0.E+000)); +#184113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184114 = PCURVE('',#184115,#184120); +#184115 = CYLINDRICAL_SURFACE('',#184116,5.E-002); +#184116 = AXIS2_PLACEMENT_3D('',#184117,#184118,#184119); +#184117 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.2)); +#184118 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184119 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184120 = DEFINITIONAL_REPRESENTATION('',(#184121),#184124); +#184121 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184122,#184123), .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#181730 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#181731 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181733 = ORIENTED_EDGE('',*,*,#181734,.F.); -#181734 = EDGE_CURVE('',#181735,#181707,#181737,.T.); -#181735 = VERTEX_POINT('',#181736); -#181736 = CARTESIAN_POINT('',(-1.165,-1.056555553792,0.518820292599)); -#181737 = SURFACE_CURVE('',#181738,(#181742,#181749),.PCURVE_S1.); -#181738 = LINE('',#181739,#181740); -#181739 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); -#181740 = VECTOR('',#181741,1.); -#181741 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#181742 = PCURVE('',#173118,#181743); -#181743 = DEFINITIONAL_REPRESENTATION('',(#181744),#181748); -#181744 = LINE('',#181745,#181746); -#181745 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#181746 = VECTOR('',#181747,1.); -#181747 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#181748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181749 = PCURVE('',#181750,#181755); -#181750 = PLANE('',#181751); -#181751 = AXIS2_PLACEMENT_3D('',#181752,#181753,#181754); -#181752 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); -#181753 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); -#181754 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#181755 = DEFINITIONAL_REPRESENTATION('',(#181756),#181760); -#181756 = LINE('',#181757,#181758); -#181757 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181758 = VECTOR('',#181759,1.); -#181759 = DIRECTION('',(1.,0.E+000)); -#181760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181761 = ORIENTED_EDGE('',*,*,#181762,.F.); -#181762 = EDGE_CURVE('',#181763,#181735,#181765,.T.); -#181763 = VERTEX_POINT('',#181764); -#181764 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); -#181765 = SURFACE_CURVE('',#181766,(#181771,#181782),.PCURVE_S1.); -#181766 = CIRCLE('',#181767,0.25); -#181767 = AXIS2_PLACEMENT_3D('',#181768,#181769,#181770); -#181768 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); -#181769 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181770 = DIRECTION('',(0.E+000,0.E+000,1.)); -#181771 = PCURVE('',#173118,#181772); -#181772 = DEFINITIONAL_REPRESENTATION('',(#181773),#181781); -#181773 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181774,#181775,#181776, - #181777,#181778,#181779,#181780),.UNSPECIFIED.,.F.,.F.) +#184122 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#184123 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184125 = ORIENTED_EDGE('',*,*,#184126,.F.); +#184126 = EDGE_CURVE('',#184127,#184099,#184129,.T.); +#184127 = VERTEX_POINT('',#184128); +#184128 = CARTESIAN_POINT('',(-1.165,-1.056555553792,0.518820292599)); +#184129 = SURFACE_CURVE('',#184130,(#184134,#184141),.PCURVE_S1.); +#184130 = LINE('',#184131,#184132); +#184131 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); +#184132 = VECTOR('',#184133,1.); +#184133 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#184134 = PCURVE('',#175510,#184135); +#184135 = DEFINITIONAL_REPRESENTATION('',(#184136),#184140); +#184136 = LINE('',#184137,#184138); +#184137 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#184138 = VECTOR('',#184139,1.); +#184139 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#184140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184141 = PCURVE('',#184142,#184147); +#184142 = PLANE('',#184143); +#184143 = AXIS2_PLACEMENT_3D('',#184144,#184145,#184146); +#184144 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); +#184145 = DIRECTION('',(0.E+000,-0.997162346553,7.528117039715E-002)); +#184146 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#184147 = DEFINITIONAL_REPRESENTATION('',(#184148),#184152); +#184148 = LINE('',#184149,#184150); +#184149 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184150 = VECTOR('',#184151,1.); +#184151 = DIRECTION('',(1.,0.E+000)); +#184152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184153 = ORIENTED_EDGE('',*,*,#184154,.F.); +#184154 = EDGE_CURVE('',#184155,#184127,#184157,.T.); +#184155 = VERTEX_POINT('',#184156); +#184156 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); +#184157 = SURFACE_CURVE('',#184158,(#184163,#184174),.PCURVE_S1.); +#184158 = CIRCLE('',#184159,0.25); +#184159 = AXIS2_PLACEMENT_3D('',#184160,#184161,#184162); +#184160 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); +#184161 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184162 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184163 = PCURVE('',#175510,#184164); +#184164 = DEFINITIONAL_REPRESENTATION('',(#184165),#184173); +#184165 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#184166,#184167,#184168, + #184169,#184170,#184171,#184172),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#181774 = CARTESIAN_POINT('',(0.25,0.E+000)); -#181775 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#181776 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#181777 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#181778 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#181779 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#181780 = CARTESIAN_POINT('',(0.25,0.E+000)); -#181781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181782 = PCURVE('',#181783,#181788); -#181783 = CYLINDRICAL_SURFACE('',#181784,0.25); -#181784 = AXIS2_PLACEMENT_3D('',#181785,#181786,#181787); -#181785 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); -#181786 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181787 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181788 = DEFINITIONAL_REPRESENTATION('',(#181789),#181792); -#181789 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181790,#181791), +#184166 = CARTESIAN_POINT('',(0.25,0.E+000)); +#184167 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#184168 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#184169 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#184170 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#184171 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#184172 = CARTESIAN_POINT('',(0.25,0.E+000)); +#184173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184174 = PCURVE('',#184175,#184180); +#184175 = CYLINDRICAL_SURFACE('',#184176,0.25); +#184176 = AXIS2_PLACEMENT_3D('',#184177,#184178,#184179); +#184177 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.5)); +#184178 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184179 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184180 = DEFINITIONAL_REPRESENTATION('',(#184181),#184184); +#184181 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184182,#184183), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#181790 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#181791 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#181792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181793 = ORIENTED_EDGE('',*,*,#181794,.F.); -#181794 = EDGE_CURVE('',#173103,#181763,#181795,.T.); -#181795 = SURFACE_CURVE('',#181796,(#181800,#181807),.PCURVE_S1.); -#181796 = LINE('',#181797,#181798); -#181797 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); -#181798 = VECTOR('',#181799,1.); -#181799 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181800 = PCURVE('',#173118,#181801); -#181801 = DEFINITIONAL_REPRESENTATION('',(#181802),#181806); -#181802 = LINE('',#181803,#181804); -#181803 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#181804 = VECTOR('',#181805,1.); -#181805 = DIRECTION('',(0.E+000,-1.)); -#181806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181807 = PCURVE('',#173146,#181808); -#181808 = DEFINITIONAL_REPRESENTATION('',(#181809),#181813); -#181809 = LINE('',#181810,#181811); -#181810 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#181811 = VECTOR('',#181812,1.); -#181812 = DIRECTION('',(0.E+000,-1.)); -#181813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181814 = ADVANCED_FACE('',(#181815),#173146,.T.); -#181815 = FACE_BOUND('',#181816,.T.); -#181816 = EDGE_LOOP('',(#181817,#181839,#181860,#181861)); -#181817 = ORIENTED_EDGE('',*,*,#181818,.T.); -#181818 = EDGE_CURVE('',#181763,#181819,#181821,.T.); -#181819 = VERTEX_POINT('',#181820); -#181820 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.75)); -#181821 = SURFACE_CURVE('',#181822,(#181826,#181833),.PCURVE_S1.); -#181822 = LINE('',#181823,#181824); -#181823 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); -#181824 = VECTOR('',#181825,1.); -#181825 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181826 = PCURVE('',#173146,#181827); -#181827 = DEFINITIONAL_REPRESENTATION('',(#181828),#181832); -#181828 = LINE('',#181829,#181830); -#181829 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); -#181830 = VECTOR('',#181831,1.); -#181831 = DIRECTION('',(1.,0.E+000)); -#181832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181833 = PCURVE('',#181783,#181834); -#181834 = DEFINITIONAL_REPRESENTATION('',(#181835),#181838); -#181835 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181836,#181837), +#184182 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#184183 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#184184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184185 = ORIENTED_EDGE('',*,*,#184186,.F.); +#184186 = EDGE_CURVE('',#175495,#184155,#184187,.T.); +#184187 = SURFACE_CURVE('',#184188,(#184192,#184199),.PCURVE_S1.); +#184188 = LINE('',#184189,#184190); +#184189 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); +#184190 = VECTOR('',#184191,1.); +#184191 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#184192 = PCURVE('',#175510,#184193); +#184193 = DEFINITIONAL_REPRESENTATION('',(#184194),#184198); +#184194 = LINE('',#184195,#184196); +#184195 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#184196 = VECTOR('',#184197,1.); +#184197 = DIRECTION('',(0.E+000,-1.)); +#184198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184199 = PCURVE('',#175538,#184200); +#184200 = DEFINITIONAL_REPRESENTATION('',(#184201),#184205); +#184201 = LINE('',#184202,#184203); +#184202 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184203 = VECTOR('',#184204,1.); +#184204 = DIRECTION('',(0.E+000,-1.)); +#184205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184206 = ADVANCED_FACE('',(#184207),#175538,.T.); +#184207 = FACE_BOUND('',#184208,.T.); +#184208 = EDGE_LOOP('',(#184209,#184231,#184252,#184253)); +#184209 = ORIENTED_EDGE('',*,*,#184210,.T.); +#184210 = EDGE_CURVE('',#184155,#184211,#184213,.T.); +#184211 = VERTEX_POINT('',#184212); +#184212 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.75)); +#184213 = SURFACE_CURVE('',#184214,(#184218,#184225),.PCURVE_S1.); +#184214 = LINE('',#184215,#184216); +#184215 = CARTESIAN_POINT('',(-1.165,-0.807264967154,0.75)); +#184216 = VECTOR('',#184217,1.); +#184217 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184218 = PCURVE('',#175538,#184219); +#184219 = DEFINITIONAL_REPRESENTATION('',(#184220),#184224); +#184220 = LINE('',#184221,#184222); +#184221 = CARTESIAN_POINT('',(0.E+000,-1.110223024625E-016)); +#184222 = VECTOR('',#184223,1.); +#184223 = DIRECTION('',(1.,0.E+000)); +#184224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184225 = PCURVE('',#184175,#184226); +#184226 = DEFINITIONAL_REPRESENTATION('',(#184227),#184230); +#184227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184228,#184229), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#181836 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#181837 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#181838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181839 = ORIENTED_EDGE('',*,*,#181840,.F.); -#181840 = EDGE_CURVE('',#173131,#181819,#181841,.T.); -#181841 = SURFACE_CURVE('',#181842,(#181846,#181853),.PCURVE_S1.); -#181842 = LINE('',#181843,#181844); -#181843 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.75)); -#181844 = VECTOR('',#181845,1.); -#181845 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181846 = PCURVE('',#173146,#181847); -#181847 = DEFINITIONAL_REPRESENTATION('',(#181848),#181852); -#181848 = LINE('',#181849,#181850); -#181849 = CARTESIAN_POINT('',(0.34,0.E+000)); -#181850 = VECTOR('',#181851,1.); -#181851 = DIRECTION('',(0.E+000,-1.)); -#181852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181853 = PCURVE('',#173172,#181854); -#181854 = DEFINITIONAL_REPRESENTATION('',(#181855),#181859); -#181855 = LINE('',#181856,#181857); -#181856 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); -#181857 = VECTOR('',#181858,1.); -#181858 = DIRECTION('',(0.E+000,-1.)); -#181859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181860 = ORIENTED_EDGE('',*,*,#173130,.F.); -#181861 = ORIENTED_EDGE('',*,*,#181794,.T.); -#181862 = ADVANCED_FACE('',(#181863),#173172,.F.); -#181863 = FACE_BOUND('',#181864,.T.); -#181864 = EDGE_LOOP('',(#181865,#181866,#181867,#181868,#181895,#181918, - #181941,#181964,#181987,#182010,#182037,#182060)); -#181865 = ORIENTED_EDGE('',*,*,#181463,.T.); -#181866 = ORIENTED_EDGE('',*,*,#173158,.T.); -#181867 = ORIENTED_EDGE('',*,*,#181840,.T.); -#181868 = ORIENTED_EDGE('',*,*,#181869,.T.); -#181869 = EDGE_CURVE('',#181819,#181870,#181872,.T.); -#181870 = VERTEX_POINT('',#181871); -#181871 = CARTESIAN_POINT('',(-0.825,-1.056555553792,0.518820292599)); -#181872 = SURFACE_CURVE('',#181873,(#181878,#181889),.PCURVE_S1.); -#181873 = CIRCLE('',#181874,0.25); -#181874 = AXIS2_PLACEMENT_3D('',#181875,#181876,#181877); -#181875 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); -#181876 = DIRECTION('',(1.,0.E+000,0.E+000)); -#181877 = DIRECTION('',(0.E+000,0.E+000,1.)); -#181878 = PCURVE('',#173172,#181879); -#181879 = DEFINITIONAL_REPRESENTATION('',(#181880),#181888); -#181880 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#181881,#181882,#181883, - #181884,#181885,#181886,#181887),.UNSPECIFIED.,.F.,.F.) +#184228 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#184229 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#184230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184231 = ORIENTED_EDGE('',*,*,#184232,.F.); +#184232 = EDGE_CURVE('',#175523,#184211,#184233,.T.); +#184233 = SURFACE_CURVE('',#184234,(#184238,#184245),.PCURVE_S1.); +#184234 = LINE('',#184235,#184236); +#184235 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.75)); +#184236 = VECTOR('',#184237,1.); +#184237 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#184238 = PCURVE('',#175538,#184239); +#184239 = DEFINITIONAL_REPRESENTATION('',(#184240),#184244); +#184240 = LINE('',#184241,#184242); +#184241 = CARTESIAN_POINT('',(0.34,0.E+000)); +#184242 = VECTOR('',#184243,1.); +#184243 = DIRECTION('',(0.E+000,-1.)); +#184244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184245 = PCURVE('',#175564,#184246); +#184246 = DEFINITIONAL_REPRESENTATION('',(#184247),#184251); +#184247 = LINE('',#184248,#184249); +#184248 = CARTESIAN_POINT('',(0.25,1.665334536938E-015)); +#184249 = VECTOR('',#184250,1.); +#184250 = DIRECTION('',(0.E+000,-1.)); +#184251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184252 = ORIENTED_EDGE('',*,*,#175522,.F.); +#184253 = ORIENTED_EDGE('',*,*,#184186,.T.); +#184254 = ADVANCED_FACE('',(#184255),#175564,.F.); +#184255 = FACE_BOUND('',#184256,.T.); +#184256 = EDGE_LOOP('',(#184257,#184258,#184259,#184260,#184287,#184310, + #184333,#184356,#184379,#184402,#184429,#184452)); +#184257 = ORIENTED_EDGE('',*,*,#183855,.T.); +#184258 = ORIENTED_EDGE('',*,*,#175550,.T.); +#184259 = ORIENTED_EDGE('',*,*,#184232,.T.); +#184260 = ORIENTED_EDGE('',*,*,#184261,.T.); +#184261 = EDGE_CURVE('',#184211,#184262,#184264,.T.); +#184262 = VERTEX_POINT('',#184263); +#184263 = CARTESIAN_POINT('',(-0.825,-1.056555553792,0.518820292599)); +#184264 = SURFACE_CURVE('',#184265,(#184270,#184281),.PCURVE_S1.); +#184265 = CIRCLE('',#184266,0.25); +#184266 = AXIS2_PLACEMENT_3D('',#184267,#184268,#184269); +#184267 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); +#184268 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184269 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184270 = PCURVE('',#175564,#184271); +#184271 = DEFINITIONAL_REPRESENTATION('',(#184272),#184280); +#184272 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#184273,#184274,#184275, + #184276,#184277,#184278,#184279),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#181881 = CARTESIAN_POINT('',(0.25,0.E+000)); -#181882 = CARTESIAN_POINT('',(0.25,-0.433012701892)); -#181883 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); -#181884 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); -#181885 = CARTESIAN_POINT('',(-0.125,0.216506350946)); -#181886 = CARTESIAN_POINT('',(0.25,0.433012701892)); -#181887 = CARTESIAN_POINT('',(0.25,0.E+000)); -#181888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181889 = PCURVE('',#181783,#181890); -#181890 = DEFINITIONAL_REPRESENTATION('',(#181891),#181894); -#181891 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181892,#181893), +#184273 = CARTESIAN_POINT('',(0.25,0.E+000)); +#184274 = CARTESIAN_POINT('',(0.25,-0.433012701892)); +#184275 = CARTESIAN_POINT('',(-0.125,-0.216506350946)); +#184276 = CARTESIAN_POINT('',(-0.5,-1.722526201536E-016)); +#184277 = CARTESIAN_POINT('',(-0.125,0.216506350946)); +#184278 = CARTESIAN_POINT('',(0.25,0.433012701892)); +#184279 = CARTESIAN_POINT('',(0.25,0.E+000)); +#184280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184281 = PCURVE('',#184175,#184282); +#184282 = DEFINITIONAL_REPRESENTATION('',(#184283),#184286); +#184283 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184284,#184285), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#181892 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#181893 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#181894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181895 = ORIENTED_EDGE('',*,*,#181896,.T.); -#181896 = EDGE_CURVE('',#181870,#181897,#181899,.T.); -#181897 = VERTEX_POINT('',#181898); -#181898 = CARTESIAN_POINT('',(-0.825,-1.080909188472,0.19623594148)); -#181899 = SURFACE_CURVE('',#181900,(#181904,#181911),.PCURVE_S1.); -#181900 = LINE('',#181901,#181902); -#181901 = CARTESIAN_POINT('',(-0.825,-1.080909188472,0.19623594148)); -#181902 = VECTOR('',#181903,1.); -#181903 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); -#181904 = PCURVE('',#173172,#181905); -#181905 = DEFINITIONAL_REPRESENTATION('',(#181906),#181910); -#181906 = LINE('',#181907,#181908); -#181907 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); -#181908 = VECTOR('',#181909,1.); -#181909 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); -#181910 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181911 = PCURVE('',#181750,#181912); -#181912 = DEFINITIONAL_REPRESENTATION('',(#181913),#181917); -#181913 = LINE('',#181914,#181915); -#181914 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181915 = VECTOR('',#181916,1.); -#181916 = DIRECTION('',(1.,0.E+000)); -#181917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181918 = ORIENTED_EDGE('',*,*,#181919,.T.); -#181919 = EDGE_CURVE('',#181897,#181920,#181922,.T.); -#181920 = VERTEX_POINT('',#181921); -#181921 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.15)); -#181922 = SURFACE_CURVE('',#181923,(#181928,#181935),.PCURVE_S1.); -#181923 = CIRCLE('',#181924,5.E-002); -#181924 = AXIS2_PLACEMENT_3D('',#181925,#181926,#181927); -#181925 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.2)); -#181926 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#181927 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181928 = PCURVE('',#173172,#181929); -#181929 = DEFINITIONAL_REPRESENTATION('',(#181930),#181934); -#181930 = CIRCLE('',#181931,5.E-002); -#181931 = AXIS2_PLACEMENT_2D('',#181932,#181933); -#181932 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); -#181933 = DIRECTION('',(-1.,0.E+000)); -#181934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181935 = PCURVE('',#181723,#181936); -#181936 = DEFINITIONAL_REPRESENTATION('',(#181937),#181940); -#181937 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#181938,#181939), +#184284 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#184285 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#184286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184287 = ORIENTED_EDGE('',*,*,#184288,.T.); +#184288 = EDGE_CURVE('',#184262,#184289,#184291,.T.); +#184289 = VERTEX_POINT('',#184290); +#184290 = CARTESIAN_POINT('',(-0.825,-1.080909188472,0.19623594148)); +#184291 = SURFACE_CURVE('',#184292,(#184296,#184303),.PCURVE_S1.); +#184292 = LINE('',#184293,#184294); +#184293 = CARTESIAN_POINT('',(-0.825,-1.080909188472,0.19623594148)); +#184294 = VECTOR('',#184295,1.); +#184295 = DIRECTION('',(0.E+000,-7.528117039715E-002,-0.997162346553)); +#184296 = PCURVE('',#175564,#184297); +#184297 = DEFINITIONAL_REPRESENTATION('',(#184298),#184302); +#184298 = LINE('',#184299,#184300); +#184299 = CARTESIAN_POINT('',(-0.30376405852,-0.273644221318)); +#184300 = VECTOR('',#184301,1.); +#184301 = DIRECTION('',(-0.997162346553,-7.528117039715E-002)); +#184302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184303 = PCURVE('',#184142,#184304); +#184304 = DEFINITIONAL_REPRESENTATION('',(#184305),#184309); +#184305 = LINE('',#184306,#184307); +#184306 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184307 = VECTOR('',#184308,1.); +#184308 = DIRECTION('',(1.,0.E+000)); +#184309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184310 = ORIENTED_EDGE('',*,*,#184311,.T.); +#184311 = EDGE_CURVE('',#184289,#184312,#184314,.T.); +#184312 = VERTEX_POINT('',#184313); +#184313 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.15)); +#184314 = SURFACE_CURVE('',#184315,(#184320,#184327),.PCURVE_S1.); +#184315 = CIRCLE('',#184316,5.E-002); +#184316 = AXIS2_PLACEMENT_3D('',#184317,#184318,#184319); +#184317 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.2)); +#184318 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184319 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184320 = PCURVE('',#175564,#184321); +#184321 = DEFINITIONAL_REPRESENTATION('',(#184322),#184326); +#184322 = CIRCLE('',#184323,5.E-002); +#184323 = AXIS2_PLACEMENT_2D('',#184324,#184325); +#184324 = CARTESIAN_POINT('',(-0.3,-0.323502338645)); +#184325 = DIRECTION('',(-1.,0.E+000)); +#184326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184327 = PCURVE('',#184115,#184328); +#184328 = DEFINITIONAL_REPRESENTATION('',(#184329),#184332); +#184329 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184330,#184331), .UNSPECIFIED.,.F.,.F.,(2,2),(4.787741438996,6.28318530718), - .PIECEWISE_BEZIER_KNOTS.); -#181938 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#181939 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181941 = ORIENTED_EDGE('',*,*,#181942,.T.); -#181942 = EDGE_CURVE('',#181920,#181943,#181945,.T.); -#181943 = VERTEX_POINT('',#181944); -#181944 = CARTESIAN_POINT('',(-0.825,-1.4,0.15)); -#181945 = SURFACE_CURVE('',#181946,(#181950,#181957),.PCURVE_S1.); -#181946 = LINE('',#181947,#181948); -#181947 = CARTESIAN_POINT('',(-0.825,-1.4,0.15)); -#181948 = VECTOR('',#181949,1.); -#181949 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#181950 = PCURVE('',#173172,#181951); -#181951 = DEFINITIONAL_REPRESENTATION('',(#181952),#181956); -#181952 = LINE('',#181953,#181954); -#181953 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); -#181954 = VECTOR('',#181955,1.); -#181955 = DIRECTION('',(0.E+000,-1.)); -#181956 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181957 = PCURVE('',#181694,#181958); -#181958 = DEFINITIONAL_REPRESENTATION('',(#181959),#181963); -#181959 = LINE('',#181960,#181961); -#181960 = CARTESIAN_POINT('',(0.34,0.E+000)); -#181961 = VECTOR('',#181962,1.); -#181962 = DIRECTION('',(0.E+000,-1.)); -#181963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181964 = ORIENTED_EDGE('',*,*,#181965,.T.); -#181965 = EDGE_CURVE('',#181943,#181966,#181968,.T.); -#181966 = VERTEX_POINT('',#181967); -#181967 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); -#181968 = SURFACE_CURVE('',#181969,(#181973,#181980),.PCURVE_S1.); -#181969 = LINE('',#181970,#181971); -#181970 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); -#181971 = VECTOR('',#181972,1.); -#181972 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#181973 = PCURVE('',#173172,#181974); -#181974 = DEFINITIONAL_REPRESENTATION('',(#181975),#181979); -#181975 = LINE('',#181976,#181977); -#181976 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#181977 = VECTOR('',#181978,1.); -#181978 = DIRECTION('',(-1.,0.E+000)); -#181979 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181980 = PCURVE('',#181666,#181981); -#181981 = DEFINITIONAL_REPRESENTATION('',(#181982),#181986); -#181982 = LINE('',#181983,#181984); -#181983 = CARTESIAN_POINT('',(0.E+000,0.34)); -#181984 = VECTOR('',#181985,1.); -#181985 = DIRECTION('',(1.,0.E+000)); -#181986 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#181987 = ORIENTED_EDGE('',*,*,#181988,.T.); -#181988 = EDGE_CURVE('',#181966,#181989,#181991,.T.); -#181989 = VERTEX_POINT('',#181990); -#181990 = CARTESIAN_POINT('',(-0.825,-1.1307673058,-2.545971129142E-016) - ); -#181991 = SURFACE_CURVE('',#181992,(#181996,#182003),.PCURVE_S1.); -#181992 = LINE('',#181993,#181994); -#181993 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); -#181994 = VECTOR('',#181995,1.); -#181995 = DIRECTION('',(0.E+000,1.,0.E+000)); -#181996 = PCURVE('',#173172,#181997); -#181997 = DEFINITIONAL_REPRESENTATION('',(#181998),#182002); -#181998 = LINE('',#181999,#182000); -#181999 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); -#182000 = VECTOR('',#182001,1.); -#182001 = DIRECTION('',(0.E+000,1.)); -#182002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182003 = PCURVE('',#181638,#182004); -#182004 = DEFINITIONAL_REPRESENTATION('',(#182005),#182009); -#182005 = LINE('',#182006,#182007); -#182006 = CARTESIAN_POINT('',(-0.34,0.E+000)); -#182007 = VECTOR('',#182008,1.); -#182008 = DIRECTION('',(0.E+000,1.)); -#182009 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182010 = ORIENTED_EDGE('',*,*,#182011,.T.); -#182011 = EDGE_CURVE('',#181989,#182012,#182014,.T.); -#182012 = VERTEX_POINT('',#182013); -#182013 = CARTESIAN_POINT('',(-0.825,-0.931334836489,0.184943765921)); -#182014 = SURFACE_CURVE('',#182015,(#182020,#182031),.PCURVE_S1.); -#182015 = CIRCLE('',#182016,0.2); -#182016 = AXIS2_PLACEMENT_3D('',#182017,#182018,#182019); -#182017 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.2)); -#182018 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182019 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#182020 = PCURVE('',#173172,#182021); -#182021 = DEFINITIONAL_REPRESENTATION('',(#182022),#182030); -#182022 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#182023,#182024,#182025, - #182026,#182027,#182028,#182029),.UNSPECIFIED.,.T.,.F.) + .PIECEWISE_BEZIER_KNOTS.); +#184330 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#184331 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184332 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184333 = ORIENTED_EDGE('',*,*,#184334,.T.); +#184334 = EDGE_CURVE('',#184312,#184335,#184337,.T.); +#184335 = VERTEX_POINT('',#184336); +#184336 = CARTESIAN_POINT('',(-0.825,-1.4,0.15)); +#184337 = SURFACE_CURVE('',#184338,(#184342,#184349),.PCURVE_S1.); +#184338 = LINE('',#184339,#184340); +#184339 = CARTESIAN_POINT('',(-0.825,-1.4,0.15)); +#184340 = VECTOR('',#184341,1.); +#184341 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#184342 = PCURVE('',#175564,#184343); +#184343 = DEFINITIONAL_REPRESENTATION('',(#184344),#184348); +#184344 = LINE('',#184345,#184346); +#184345 = CARTESIAN_POINT('',(-0.35,-0.592735032846)); +#184346 = VECTOR('',#184347,1.); +#184347 = DIRECTION('',(0.E+000,-1.)); +#184348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184349 = PCURVE('',#184086,#184350); +#184350 = DEFINITIONAL_REPRESENTATION('',(#184351),#184355); +#184351 = LINE('',#184352,#184353); +#184352 = CARTESIAN_POINT('',(0.34,0.E+000)); +#184353 = VECTOR('',#184354,1.); +#184354 = DIRECTION('',(0.E+000,-1.)); +#184355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184356 = ORIENTED_EDGE('',*,*,#184357,.T.); +#184357 = EDGE_CURVE('',#184335,#184358,#184360,.T.); +#184358 = VERTEX_POINT('',#184359); +#184359 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); +#184360 = SURFACE_CURVE('',#184361,(#184365,#184372),.PCURVE_S1.); +#184361 = LINE('',#184362,#184363); +#184362 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); +#184363 = VECTOR('',#184364,1.); +#184364 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184365 = PCURVE('',#175564,#184366); +#184366 = DEFINITIONAL_REPRESENTATION('',(#184367),#184371); +#184367 = LINE('',#184368,#184369); +#184368 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#184369 = VECTOR('',#184370,1.); +#184370 = DIRECTION('',(-1.,0.E+000)); +#184371 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184372 = PCURVE('',#184058,#184373); +#184373 = DEFINITIONAL_REPRESENTATION('',(#184374),#184378); +#184374 = LINE('',#184375,#184376); +#184375 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184376 = VECTOR('',#184377,1.); +#184377 = DIRECTION('',(1.,0.E+000)); +#184378 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184379 = ORIENTED_EDGE('',*,*,#184380,.T.); +#184380 = EDGE_CURVE('',#184358,#184381,#184383,.T.); +#184381 = VERTEX_POINT('',#184382); +#184382 = CARTESIAN_POINT('',(-0.825,-1.1307673058,-2.545971129142E-016) + ); +#184383 = SURFACE_CURVE('',#184384,(#184388,#184395),.PCURVE_S1.); +#184384 = LINE('',#184385,#184386); +#184385 = CARTESIAN_POINT('',(-0.825,-1.4,-2.003870042899E-016)); +#184386 = VECTOR('',#184387,1.); +#184387 = DIRECTION('',(0.E+000,1.,0.E+000)); +#184388 = PCURVE('',#175564,#184389); +#184389 = DEFINITIONAL_REPRESENTATION('',(#184390),#184394); +#184390 = LINE('',#184391,#184392); +#184391 = CARTESIAN_POINT('',(-0.5,-0.592735032846)); +#184392 = VECTOR('',#184393,1.); +#184393 = DIRECTION('',(0.E+000,1.)); +#184394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184395 = PCURVE('',#184030,#184396); +#184396 = DEFINITIONAL_REPRESENTATION('',(#184397),#184401); +#184397 = LINE('',#184398,#184399); +#184398 = CARTESIAN_POINT('',(-0.34,0.E+000)); +#184399 = VECTOR('',#184400,1.); +#184400 = DIRECTION('',(0.E+000,1.)); +#184401 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184402 = ORIENTED_EDGE('',*,*,#184403,.T.); +#184403 = EDGE_CURVE('',#184381,#184404,#184406,.T.); +#184404 = VERTEX_POINT('',#184405); +#184405 = CARTESIAN_POINT('',(-0.825,-0.931334836489,0.184943765921)); +#184406 = SURFACE_CURVE('',#184407,(#184412,#184423),.PCURVE_S1.); +#184407 = CIRCLE('',#184408,0.2); +#184408 = AXIS2_PLACEMENT_3D('',#184409,#184410,#184411); +#184409 = CARTESIAN_POINT('',(-0.825,-1.1307673058,0.2)); +#184410 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184411 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184412 = PCURVE('',#175564,#184413); +#184413 = DEFINITIONAL_REPRESENTATION('',(#184414),#184422); +#184414 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#184415,#184416,#184417, + #184418,#184419,#184420,#184421),.UNSPECIFIED.,.T.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#182023 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#182024 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); -#182025 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); -#182026 = CARTESIAN_POINT('',(0.1,-0.323502338645)); -#182027 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); -#182028 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); -#182029 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); -#182030 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182031 = PCURVE('',#181611,#182032); -#182032 = DEFINITIONAL_REPRESENTATION('',(#182033),#182036); -#182033 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182034,#182035), +#184415 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#184416 = CARTESIAN_POINT('',(-0.5,2.290782286835E-002)); +#184417 = CARTESIAN_POINT('',(-0.2,-0.150297257889)); +#184418 = CARTESIAN_POINT('',(0.1,-0.323502338645)); +#184419 = CARTESIAN_POINT('',(-0.2,-0.496707419402)); +#184420 = CARTESIAN_POINT('',(-0.5,-0.669912500159)); +#184421 = CARTESIAN_POINT('',(-0.5,-0.323502338645)); +#184422 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184423 = PCURVE('',#184003,#184424); +#184424 = DEFINITIONAL_REPRESENTATION('',(#184425),#184428); +#184425 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184426,#184427), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.495443868184), .PIECEWISE_BEZIER_KNOTS.); -#182034 = CARTESIAN_POINT('',(0.E+000,0.34)); -#182035 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#182036 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182037 = ORIENTED_EDGE('',*,*,#182038,.T.); -#182038 = EDGE_CURVE('',#182012,#182039,#182041,.T.); -#182039 = VERTEX_POINT('',#182040); -#182040 = CARTESIAN_POINT('',(-0.825,-0.906981201809,0.50752811704)); -#182041 = SURFACE_CURVE('',#182042,(#182046,#182053),.PCURVE_S1.); -#182042 = LINE('',#182043,#182044); -#182043 = CARTESIAN_POINT('',(-0.825,-0.931334836489,0.184943765921)); -#182044 = VECTOR('',#182045,1.); -#182045 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); -#182046 = PCURVE('',#173172,#182047); -#182047 = DEFINITIONAL_REPRESENTATION('',(#182048),#182052); -#182048 = LINE('',#182049,#182050); -#182049 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); -#182050 = VECTOR('',#182051,1.); -#182051 = DIRECTION('',(0.997162346553,7.528117039715E-002)); -#182052 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182053 = PCURVE('',#181578,#182054); -#182054 = DEFINITIONAL_REPRESENTATION('',(#182055),#182059); -#182055 = LINE('',#182056,#182057); -#182056 = CARTESIAN_POINT('',(0.E+000,0.34)); -#182057 = VECTOR('',#182058,1.); -#182058 = DIRECTION('',(1.,0.E+000)); -#182059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182060 = ORIENTED_EDGE('',*,*,#182061,.T.); -#182061 = EDGE_CURVE('',#182039,#181464,#182062,.T.); -#182062 = SURFACE_CURVE('',#182063,(#182068,#182075),.PCURVE_S1.); -#182063 = CIRCLE('',#182064,0.1); -#182064 = AXIS2_PLACEMENT_3D('',#182065,#182066,#182067); -#182065 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); -#182066 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#182067 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#182068 = PCURVE('',#173172,#182069); -#182069 = DEFINITIONAL_REPRESENTATION('',(#182070),#182074); -#182070 = CIRCLE('',#182071,0.1); -#182071 = AXIS2_PLACEMENT_2D('',#182072,#182073); -#182072 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); -#182073 = DIRECTION('',(-1.,0.E+000)); -#182074 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182075 = PCURVE('',#181502,#182076); -#182076 = DEFINITIONAL_REPRESENTATION('',(#182077),#182080); -#182077 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182078,#182079), +#184426 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184427 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#184428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184429 = ORIENTED_EDGE('',*,*,#184430,.T.); +#184430 = EDGE_CURVE('',#184404,#184431,#184433,.T.); +#184431 = VERTEX_POINT('',#184432); +#184432 = CARTESIAN_POINT('',(-0.825,-0.906981201809,0.50752811704)); +#184433 = SURFACE_CURVE('',#184434,(#184438,#184445),.PCURVE_S1.); +#184434 = LINE('',#184435,#184436); +#184435 = CARTESIAN_POINT('',(-0.825,-0.931334836489,0.184943765921)); +#184436 = VECTOR('',#184437,1.); +#184437 = DIRECTION('',(0.E+000,7.528117039715E-002,0.997162346553)); +#184438 = PCURVE('',#175564,#184439); +#184439 = DEFINITIONAL_REPRESENTATION('',(#184440),#184444); +#184440 = LINE('',#184441,#184442); +#184441 = CARTESIAN_POINT('',(-0.315056234079,-0.124069869335)); +#184442 = VECTOR('',#184443,1.); +#184443 = DIRECTION('',(0.997162346553,7.528117039715E-002)); +#184444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184445 = PCURVE('',#183970,#184446); +#184446 = DEFINITIONAL_REPRESENTATION('',(#184447),#184451); +#184447 = LINE('',#184448,#184449); +#184448 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184449 = VECTOR('',#184450,1.); +#184450 = DIRECTION('',(1.,0.E+000)); +#184451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184452 = ORIENTED_EDGE('',*,*,#184453,.T.); +#184453 = EDGE_CURVE('',#184431,#183856,#184454,.T.); +#184454 = SURFACE_CURVE('',#184455,(#184460,#184467),.PCURVE_S1.); +#184455 = CIRCLE('',#184456,0.1); +#184456 = AXIS2_PLACEMENT_3D('',#184457,#184458,#184459); +#184457 = CARTESIAN_POINT('',(-0.825,-0.807264967154,0.5)); +#184458 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184459 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184460 = PCURVE('',#175564,#184461); +#184461 = DEFINITIONAL_REPRESENTATION('',(#184462),#184466); +#184462 = CIRCLE('',#184463,0.1); +#184463 = AXIS2_PLACEMENT_2D('',#184464,#184465); +#184464 = CARTESIAN_POINT('',(1.110223024625E-016,1.110223024625E-016)); +#184465 = DIRECTION('',(-1.,0.E+000)); +#184466 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184467 = PCURVE('',#183894,#184468); +#184468 = DEFINITIONAL_REPRESENTATION('',(#184469),#184472); +#184469 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184470,#184471), .UNSPECIFIED.,.F.,.F.,(2,2),(1.646148785406,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#182078 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#182079 = CARTESIAN_POINT('',(3.14159265359,0.34)); -#182080 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182081 = ADVANCED_FACE('',(#182082),#181502,.F.); -#182082 = FACE_BOUND('',#182083,.F.); -#182083 = EDGE_LOOP('',(#182084,#182085,#182086,#182106)); -#182084 = ORIENTED_EDGE('',*,*,#181486,.F.); -#182085 = ORIENTED_EDGE('',*,*,#181539,.F.); -#182086 = ORIENTED_EDGE('',*,*,#182087,.T.); -#182087 = EDGE_CURVE('',#181540,#182039,#182088,.T.); -#182088 = SURFACE_CURVE('',#182089,(#182093,#182099),.PCURVE_S1.); -#182089 = LINE('',#182090,#182091); -#182090 = CARTESIAN_POINT('',(-1.165,-0.906981201809,0.50752811704)); -#182091 = VECTOR('',#182092,1.); -#182092 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182093 = PCURVE('',#181502,#182094); -#182094 = DEFINITIONAL_REPRESENTATION('',(#182095),#182098); -#182095 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182096,#182097), +#184470 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#184471 = CARTESIAN_POINT('',(3.14159265359,0.34)); +#184472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184473 = ADVANCED_FACE('',(#184474),#183894,.F.); +#184474 = FACE_BOUND('',#184475,.F.); +#184475 = EDGE_LOOP('',(#184476,#184477,#184478,#184498)); +#184476 = ORIENTED_EDGE('',*,*,#183878,.F.); +#184477 = ORIENTED_EDGE('',*,*,#183931,.F.); +#184478 = ORIENTED_EDGE('',*,*,#184479,.T.); +#184479 = EDGE_CURVE('',#183932,#184431,#184480,.T.); +#184480 = SURFACE_CURVE('',#184481,(#184485,#184491),.PCURVE_S1.); +#184481 = LINE('',#184482,#184483); +#184482 = CARTESIAN_POINT('',(-1.165,-0.906981201809,0.50752811704)); +#184483 = VECTOR('',#184484,1.); +#184484 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184485 = PCURVE('',#183894,#184486); +#184486 = DEFINITIONAL_REPRESENTATION('',(#184487),#184490); +#184487 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184488,#184489), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#182096 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#182097 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#182098 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182099 = PCURVE('',#181578,#182100); -#182100 = DEFINITIONAL_REPRESENTATION('',(#182101),#182105); -#182101 = LINE('',#182102,#182103); -#182102 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); -#182103 = VECTOR('',#182104,1.); -#182104 = DIRECTION('',(0.E+000,1.)); -#182105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182106 = ORIENTED_EDGE('',*,*,#182061,.T.); -#182107 = ADVANCED_FACE('',(#182108),#181578,.T.); -#182108 = FACE_BOUND('',#182109,.T.); -#182109 = EDGE_LOOP('',(#182110,#182111,#182112,#182132)); -#182110 = ORIENTED_EDGE('',*,*,#182087,.T.); -#182111 = ORIENTED_EDGE('',*,*,#182038,.F.); -#182112 = ORIENTED_EDGE('',*,*,#182113,.F.); -#182113 = EDGE_CURVE('',#181563,#182012,#182114,.T.); -#182114 = SURFACE_CURVE('',#182115,(#182119,#182126),.PCURVE_S1.); -#182115 = LINE('',#182116,#182117); -#182116 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); -#182117 = VECTOR('',#182118,1.); -#182118 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182119 = PCURVE('',#181578,#182120); -#182120 = DEFINITIONAL_REPRESENTATION('',(#182121),#182125); -#182121 = LINE('',#182122,#182123); -#182122 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182123 = VECTOR('',#182124,1.); -#182124 = DIRECTION('',(0.E+000,1.)); -#182125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182126 = PCURVE('',#181611,#182127); -#182127 = DEFINITIONAL_REPRESENTATION('',(#182128),#182131); -#182128 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182129,#182130), +#184488 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#184489 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#184490 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184491 = PCURVE('',#183970,#184492); +#184492 = DEFINITIONAL_REPRESENTATION('',(#184493),#184497); +#184493 = LINE('',#184494,#184495); +#184494 = CARTESIAN_POINT('',(0.323502338645,0.E+000)); +#184495 = VECTOR('',#184496,1.); +#184496 = DIRECTION('',(0.E+000,1.)); +#184497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184498 = ORIENTED_EDGE('',*,*,#184453,.T.); +#184499 = ADVANCED_FACE('',(#184500),#183970,.T.); +#184500 = FACE_BOUND('',#184501,.T.); +#184501 = EDGE_LOOP('',(#184502,#184503,#184504,#184524)); +#184502 = ORIENTED_EDGE('',*,*,#184479,.T.); +#184503 = ORIENTED_EDGE('',*,*,#184430,.F.); +#184504 = ORIENTED_EDGE('',*,*,#184505,.F.); +#184505 = EDGE_CURVE('',#183955,#184404,#184506,.T.); +#184506 = SURFACE_CURVE('',#184507,(#184511,#184518),.PCURVE_S1.); +#184507 = LINE('',#184508,#184509); +#184508 = CARTESIAN_POINT('',(-1.165,-0.931334836489,0.184943765921)); +#184509 = VECTOR('',#184510,1.); +#184510 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184511 = PCURVE('',#183970,#184512); +#184512 = DEFINITIONAL_REPRESENTATION('',(#184513),#184517); +#184513 = LINE('',#184514,#184515); +#184514 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184515 = VECTOR('',#184516,1.); +#184516 = DIRECTION('',(0.E+000,1.)); +#184517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184518 = PCURVE('',#184003,#184519); +#184519 = DEFINITIONAL_REPRESENTATION('',(#184520),#184523); +#184520 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184521,#184522), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#182129 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#182130 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#182131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182132 = ORIENTED_EDGE('',*,*,#181562,.T.); -#182133 = ADVANCED_FACE('',(#182134),#181611,.T.); -#182134 = FACE_BOUND('',#182135,.T.); -#182135 = EDGE_LOOP('',(#182136,#182137,#182138,#182181)); -#182136 = ORIENTED_EDGE('',*,*,#182113,.T.); -#182137 = ORIENTED_EDGE('',*,*,#182011,.F.); -#182138 = ORIENTED_EDGE('',*,*,#182139,.F.); -#182139 = EDGE_CURVE('',#181591,#181989,#182140,.T.); -#182140 = SURFACE_CURVE('',#182141,(#182145,#182174),.PCURVE_S1.); -#182141 = LINE('',#182142,#182143); -#182142 = CARTESIAN_POINT('',(-1.165,-1.1307673058,-2.545971129142E-016) - ); -#182143 = VECTOR('',#182144,1.); -#182144 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182145 = PCURVE('',#181611,#182146); -#182146 = DEFINITIONAL_REPRESENTATION('',(#182147),#182173); -#182147 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#182148,#182149,#182150, - #182151,#182152,#182153,#182154,#182155,#182156,#182157,#182158, - #182159,#182160,#182161,#182162,#182163,#182164,#182165,#182166, - #182167,#182168,#182169,#182170,#182171,#182172),.UNSPECIFIED.,.F., +#184521 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#184522 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#184523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184524 = ORIENTED_EDGE('',*,*,#183954,.T.); +#184525 = ADVANCED_FACE('',(#184526),#184003,.T.); +#184526 = FACE_BOUND('',#184527,.T.); +#184527 = EDGE_LOOP('',(#184528,#184529,#184530,#184573)); +#184528 = ORIENTED_EDGE('',*,*,#184505,.T.); +#184529 = ORIENTED_EDGE('',*,*,#184403,.F.); +#184530 = ORIENTED_EDGE('',*,*,#184531,.F.); +#184531 = EDGE_CURVE('',#183983,#184381,#184532,.T.); +#184532 = SURFACE_CURVE('',#184533,(#184537,#184566),.PCURVE_S1.); +#184533 = LINE('',#184534,#184535); +#184534 = CARTESIAN_POINT('',(-1.165,-1.1307673058,-2.545971129142E-016) + ); +#184535 = VECTOR('',#184536,1.); +#184536 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184537 = PCURVE('',#184003,#184538); +#184538 = DEFINITIONAL_REPRESENTATION('',(#184539),#184565); +#184539 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184540,#184541,#184542, + #184543,#184544,#184545,#184546,#184547,#184548,#184549,#184550, + #184551,#184552,#184553,#184554,#184555,#184556,#184557,#184558, + #184559,#184560,#184561,#184562,#184563,#184564),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -225591,140 +228593,140 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#182148 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182149 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) - ); -#182150 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) - ); -#182151 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) - ); -#182152 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) - ); -#182153 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) - ); -#182154 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) - ); -#182155 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) - ); -#182156 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); -#182157 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); -#182158 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); -#182159 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); -#182160 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); -#182161 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); -#182162 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); -#182163 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); -#182164 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); -#182165 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); -#182166 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); -#182167 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); -#182168 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); -#182169 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); -#182170 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); -#182171 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); -#182172 = CARTESIAN_POINT('',(0.E+000,0.34)); -#182173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182174 = PCURVE('',#181638,#182175); -#182175 = DEFINITIONAL_REPRESENTATION('',(#182176),#182180); -#182176 = LINE('',#182177,#182178); -#182177 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#182178 = VECTOR('',#182179,1.); -#182179 = DIRECTION('',(-1.,0.E+000)); -#182180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182181 = ORIENTED_EDGE('',*,*,#181590,.T.); -#182182 = ADVANCED_FACE('',(#182183),#181638,.T.); -#182183 = FACE_BOUND('',#182184,.T.); -#182184 = EDGE_LOOP('',(#182185,#182186,#182187,#182208)); -#182185 = ORIENTED_EDGE('',*,*,#182139,.T.); -#182186 = ORIENTED_EDGE('',*,*,#181988,.F.); -#182187 = ORIENTED_EDGE('',*,*,#182188,.F.); -#182188 = EDGE_CURVE('',#181623,#181966,#182189,.T.); -#182189 = SURFACE_CURVE('',#182190,(#182194,#182201),.PCURVE_S1.); -#182190 = LINE('',#182191,#182192); -#182191 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); -#182192 = VECTOR('',#182193,1.); -#182193 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182194 = PCURVE('',#181638,#182195); -#182195 = DEFINITIONAL_REPRESENTATION('',(#182196),#182200); -#182196 = LINE('',#182197,#182198); -#182197 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182198 = VECTOR('',#182199,1.); -#182199 = DIRECTION('',(-1.,0.E+000)); -#182200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182201 = PCURVE('',#181666,#182202); -#182202 = DEFINITIONAL_REPRESENTATION('',(#182203),#182207); -#182203 = LINE('',#182204,#182205); -#182204 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182205 = VECTOR('',#182206,1.); -#182206 = DIRECTION('',(0.E+000,1.)); -#182207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182208 = ORIENTED_EDGE('',*,*,#181622,.T.); -#182209 = ADVANCED_FACE('',(#182210),#181666,.T.); -#182210 = FACE_BOUND('',#182211,.T.); -#182211 = EDGE_LOOP('',(#182212,#182213,#182214,#182235)); -#182212 = ORIENTED_EDGE('',*,*,#182188,.T.); -#182213 = ORIENTED_EDGE('',*,*,#181965,.F.); -#182214 = ORIENTED_EDGE('',*,*,#182215,.F.); -#182215 = EDGE_CURVE('',#181651,#181943,#182216,.T.); -#182216 = SURFACE_CURVE('',#182217,(#182221,#182228),.PCURVE_S1.); -#182217 = LINE('',#182218,#182219); -#182218 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); -#182219 = VECTOR('',#182220,1.); -#182220 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182221 = PCURVE('',#181666,#182222); -#182222 = DEFINITIONAL_REPRESENTATION('',(#182223),#182227); -#182223 = LINE('',#182224,#182225); -#182224 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#182225 = VECTOR('',#182226,1.); -#182226 = DIRECTION('',(0.E+000,1.)); -#182227 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182228 = PCURVE('',#181694,#182229); -#182229 = DEFINITIONAL_REPRESENTATION('',(#182230),#182234); -#182230 = LINE('',#182231,#182232); -#182231 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182232 = VECTOR('',#182233,1.); -#182233 = DIRECTION('',(1.,0.E+000)); -#182234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182235 = ORIENTED_EDGE('',*,*,#181650,.T.); -#182236 = ADVANCED_FACE('',(#182237),#181694,.T.); -#182237 = FACE_BOUND('',#182238,.T.); -#182238 = EDGE_LOOP('',(#182239,#182240,#182241,#182284)); -#182239 = ORIENTED_EDGE('',*,*,#182215,.T.); -#182240 = ORIENTED_EDGE('',*,*,#181942,.F.); -#182241 = ORIENTED_EDGE('',*,*,#182242,.F.); -#182242 = EDGE_CURVE('',#181679,#181920,#182243,.T.); -#182243 = SURFACE_CURVE('',#182244,(#182248,#182255),.PCURVE_S1.); -#182244 = LINE('',#182245,#182246); -#182245 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.15)); -#182246 = VECTOR('',#182247,1.); -#182247 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182248 = PCURVE('',#181694,#182249); -#182249 = DEFINITIONAL_REPRESENTATION('',(#182250),#182254); -#182250 = LINE('',#182251,#182252); -#182251 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); -#182252 = VECTOR('',#182253,1.); -#182253 = DIRECTION('',(1.,0.E+000)); -#182254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182255 = PCURVE('',#181723,#182256); -#182256 = DEFINITIONAL_REPRESENTATION('',(#182257),#182283); -#182257 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#182258,#182259,#182260, - #182261,#182262,#182263,#182264,#182265,#182266,#182267,#182268, - #182269,#182270,#182271,#182272,#182273,#182274,#182275,#182276, - #182277,#182278,#182279,#182280,#182281,#182282),.UNSPECIFIED.,.F., +#184540 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184541 = CARTESIAN_POINT('',(-3.552713678801E-015,5.151515151515E-003) + ); +#184542 = CARTESIAN_POINT('',(-7.993605777301E-015,1.545454545455E-002) + ); +#184543 = CARTESIAN_POINT('',(-6.217248937901E-015,3.090909090909E-002) + ); +#184544 = CARTESIAN_POINT('',(-8.881784197001E-015,4.636363636364E-002) + ); +#184545 = CARTESIAN_POINT('',(-5.329070518201E-015,6.181818181818E-002) + ); +#184546 = CARTESIAN_POINT('',(-6.217248937901E-015,7.727272727273E-002) + ); +#184547 = CARTESIAN_POINT('',(-7.105427357601E-015,9.272727272727E-002) + ); +#184548 = CARTESIAN_POINT('',(-7.105427357601E-015,0.108181818182)); +#184549 = CARTESIAN_POINT('',(-6.217248937901E-015,0.123636363636)); +#184550 = CARTESIAN_POINT('',(-7.105427357601E-015,0.139090909091)); +#184551 = CARTESIAN_POINT('',(-7.993605777301E-015,0.154545454545)); +#184552 = CARTESIAN_POINT('',(-8.881784197001E-015,0.17)); +#184553 = CARTESIAN_POINT('',(-6.217248937901E-015,0.185454545455)); +#184554 = CARTESIAN_POINT('',(-7.105427357601E-015,0.200909090909)); +#184555 = CARTESIAN_POINT('',(-7.105427357601E-015,0.216363636364)); +#184556 = CARTESIAN_POINT('',(-5.329070518201E-015,0.231818181818)); +#184557 = CARTESIAN_POINT('',(-7.105427357601E-015,0.247272727273)); +#184558 = CARTESIAN_POINT('',(-7.993605777301E-015,0.262727272727)); +#184559 = CARTESIAN_POINT('',(-6.217248937901E-015,0.278181818182)); +#184560 = CARTESIAN_POINT('',(-7.993605777301E-015,0.293636363636)); +#184561 = CARTESIAN_POINT('',(-7.105427357601E-015,0.309090909091)); +#184562 = CARTESIAN_POINT('',(-7.105427357601E-015,0.324545454545)); +#184563 = CARTESIAN_POINT('',(-4.440892098501E-015,0.334848484848)); +#184564 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184565 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184566 = PCURVE('',#184030,#184567); +#184567 = DEFINITIONAL_REPRESENTATION('',(#184568),#184572); +#184568 = LINE('',#184569,#184570); +#184569 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#184570 = VECTOR('',#184571,1.); +#184571 = DIRECTION('',(-1.,0.E+000)); +#184572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184573 = ORIENTED_EDGE('',*,*,#183982,.T.); +#184574 = ADVANCED_FACE('',(#184575),#184030,.T.); +#184575 = FACE_BOUND('',#184576,.T.); +#184576 = EDGE_LOOP('',(#184577,#184578,#184579,#184600)); +#184577 = ORIENTED_EDGE('',*,*,#184531,.T.); +#184578 = ORIENTED_EDGE('',*,*,#184380,.F.); +#184579 = ORIENTED_EDGE('',*,*,#184580,.F.); +#184580 = EDGE_CURVE('',#184015,#184358,#184581,.T.); +#184581 = SURFACE_CURVE('',#184582,(#184586,#184593),.PCURVE_S1.); +#184582 = LINE('',#184583,#184584); +#184583 = CARTESIAN_POINT('',(-1.165,-1.4,-2.003870042899E-016)); +#184584 = VECTOR('',#184585,1.); +#184585 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184586 = PCURVE('',#184030,#184587); +#184587 = DEFINITIONAL_REPRESENTATION('',(#184588),#184592); +#184588 = LINE('',#184589,#184590); +#184589 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184590 = VECTOR('',#184591,1.); +#184591 = DIRECTION('',(-1.,0.E+000)); +#184592 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184593 = PCURVE('',#184058,#184594); +#184594 = DEFINITIONAL_REPRESENTATION('',(#184595),#184599); +#184595 = LINE('',#184596,#184597); +#184596 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184597 = VECTOR('',#184598,1.); +#184598 = DIRECTION('',(0.E+000,1.)); +#184599 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184600 = ORIENTED_EDGE('',*,*,#184014,.T.); +#184601 = ADVANCED_FACE('',(#184602),#184058,.T.); +#184602 = FACE_BOUND('',#184603,.T.); +#184603 = EDGE_LOOP('',(#184604,#184605,#184606,#184627)); +#184604 = ORIENTED_EDGE('',*,*,#184580,.T.); +#184605 = ORIENTED_EDGE('',*,*,#184357,.F.); +#184606 = ORIENTED_EDGE('',*,*,#184607,.F.); +#184607 = EDGE_CURVE('',#184043,#184335,#184608,.T.); +#184608 = SURFACE_CURVE('',#184609,(#184613,#184620),.PCURVE_S1.); +#184609 = LINE('',#184610,#184611); +#184610 = CARTESIAN_POINT('',(-1.165,-1.4,0.15)); +#184611 = VECTOR('',#184612,1.); +#184612 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184613 = PCURVE('',#184058,#184614); +#184614 = DEFINITIONAL_REPRESENTATION('',(#184615),#184619); +#184615 = LINE('',#184616,#184617); +#184616 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#184617 = VECTOR('',#184618,1.); +#184618 = DIRECTION('',(0.E+000,1.)); +#184619 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184620 = PCURVE('',#184086,#184621); +#184621 = DEFINITIONAL_REPRESENTATION('',(#184622),#184626); +#184622 = LINE('',#184623,#184624); +#184623 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184624 = VECTOR('',#184625,1.); +#184625 = DIRECTION('',(1.,0.E+000)); +#184626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184627 = ORIENTED_EDGE('',*,*,#184042,.T.); +#184628 = ADVANCED_FACE('',(#184629),#184086,.T.); +#184629 = FACE_BOUND('',#184630,.T.); +#184630 = EDGE_LOOP('',(#184631,#184632,#184633,#184676)); +#184631 = ORIENTED_EDGE('',*,*,#184607,.T.); +#184632 = ORIENTED_EDGE('',*,*,#184334,.F.); +#184633 = ORIENTED_EDGE('',*,*,#184634,.F.); +#184634 = EDGE_CURVE('',#184071,#184312,#184635,.T.); +#184635 = SURFACE_CURVE('',#184636,(#184640,#184647),.PCURVE_S1.); +#184636 = LINE('',#184637,#184638); +#184637 = CARTESIAN_POINT('',(-1.165,-1.1307673058,0.15)); +#184638 = VECTOR('',#184639,1.); +#184639 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184640 = PCURVE('',#184086,#184641); +#184641 = DEFINITIONAL_REPRESENTATION('',(#184642),#184646); +#184642 = LINE('',#184643,#184644); +#184643 = CARTESIAN_POINT('',(0.E+000,0.2692326942)); +#184644 = VECTOR('',#184645,1.); +#184645 = DIRECTION('',(1.,0.E+000)); +#184646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184647 = PCURVE('',#184115,#184648); +#184648 = DEFINITIONAL_REPRESENTATION('',(#184649),#184675); +#184649 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184650,#184651,#184652, + #184653,#184654,#184655,#184656,#184657,#184658,#184659,#184660, + #184661,#184662,#184663,#184664,#184665,#184666,#184667,#184668, + #184669,#184670,#184671,#184672,#184673,#184674),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.545454545455E-002,3.090909090909E-002,4.636363636364E-002, 6.181818181818E-002,7.727272727273E-002,9.272727272727E-002, @@ -225732,959 +228734,959 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.185454545455,0.200909090909,0.216363636364,0.231818181818, 0.247272727273,0.262727272727,0.278181818182,0.293636363636, 0.309090909091,0.324545454545,0.34),.QUASI_UNIFORM_KNOTS.); -#182258 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182259 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); -#182260 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) - ); -#182261 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); -#182262 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) - ); -#182263 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) - ); -#182264 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) - ); -#182265 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) - ); -#182266 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); -#182267 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); -#182268 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); -#182269 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); -#182270 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); -#182271 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); -#182272 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); -#182273 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); -#182274 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); -#182275 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); -#182276 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); -#182277 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); -#182278 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); -#182279 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); -#182280 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); -#182281 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); -#182282 = CARTESIAN_POINT('',(0.E+000,0.34)); -#182283 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182284 = ORIENTED_EDGE('',*,*,#181678,.T.); -#182285 = ADVANCED_FACE('',(#182286),#181723,.F.); -#182286 = FACE_BOUND('',#182287,.F.); -#182287 = EDGE_LOOP('',(#182288,#182289,#182290,#182310)); -#182288 = ORIENTED_EDGE('',*,*,#182242,.F.); -#182289 = ORIENTED_EDGE('',*,*,#181706,.F.); -#182290 = ORIENTED_EDGE('',*,*,#182291,.T.); -#182291 = EDGE_CURVE('',#181707,#181897,#182292,.T.); -#182292 = SURFACE_CURVE('',#182293,(#182297,#182303),.PCURVE_S1.); -#182293 = LINE('',#182294,#182295); -#182294 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); -#182295 = VECTOR('',#182296,1.); -#182296 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182297 = PCURVE('',#181723,#182298); -#182298 = DEFINITIONAL_REPRESENTATION('',(#182299),#182302); -#182299 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182300,#182301), +#184650 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184651 = CARTESIAN_POINT('',(-2.6645352591E-015,5.151515151515E-003)); +#184652 = CARTESIAN_POINT('',(-4.440892098501E-015,1.545454545455E-002) + ); +#184653 = CARTESIAN_POINT('',(-2.6645352591E-015,3.090909090909E-002)); +#184654 = CARTESIAN_POINT('',(-7.105427357601E-015,4.636363636364E-002) + ); +#184655 = CARTESIAN_POINT('',(-3.552713678801E-015,6.181818181818E-002) + ); +#184656 = CARTESIAN_POINT('',(-4.440892098501E-015,7.727272727273E-002) + ); +#184657 = CARTESIAN_POINT('',(-4.440892098501E-015,9.272727272727E-002) + ); +#184658 = CARTESIAN_POINT('',(-4.440892098501E-015,0.108181818182)); +#184659 = CARTESIAN_POINT('',(-5.329070518201E-015,0.123636363636)); +#184660 = CARTESIAN_POINT('',(-3.552713678801E-015,0.139090909091)); +#184661 = CARTESIAN_POINT('',(-4.440892098501E-015,0.154545454545)); +#184662 = CARTESIAN_POINT('',(-4.440892098501E-015,0.17)); +#184663 = CARTESIAN_POINT('',(-4.440892098501E-015,0.185454545455)); +#184664 = CARTESIAN_POINT('',(-5.329070518201E-015,0.200909090909)); +#184665 = CARTESIAN_POINT('',(-5.329070518201E-015,0.216363636364)); +#184666 = CARTESIAN_POINT('',(-3.552713678801E-015,0.231818181818)); +#184667 = CARTESIAN_POINT('',(-5.329070518201E-015,0.247272727273)); +#184668 = CARTESIAN_POINT('',(-5.329070518201E-015,0.262727272727)); +#184669 = CARTESIAN_POINT('',(-4.440892098501E-015,0.278181818182)); +#184670 = CARTESIAN_POINT('',(-3.552713678801E-015,0.293636363636)); +#184671 = CARTESIAN_POINT('',(-5.329070518201E-015,0.309090909091)); +#184672 = CARTESIAN_POINT('',(-4.440892098501E-015,0.324545454545)); +#184673 = CARTESIAN_POINT('',(-1.7763568394E-015,0.334848484848)); +#184674 = CARTESIAN_POINT('',(0.E+000,0.34)); +#184675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184676 = ORIENTED_EDGE('',*,*,#184070,.T.); +#184677 = ADVANCED_FACE('',(#184678),#184115,.F.); +#184678 = FACE_BOUND('',#184679,.F.); +#184679 = EDGE_LOOP('',(#184680,#184681,#184682,#184702)); +#184680 = ORIENTED_EDGE('',*,*,#184634,.F.); +#184681 = ORIENTED_EDGE('',*,*,#184098,.F.); +#184682 = ORIENTED_EDGE('',*,*,#184683,.T.); +#184683 = EDGE_CURVE('',#184099,#184289,#184684,.T.); +#184684 = SURFACE_CURVE('',#184685,(#184689,#184695),.PCURVE_S1.); +#184685 = LINE('',#184686,#184687); +#184686 = CARTESIAN_POINT('',(-1.165,-1.080909188472,0.19623594148)); +#184687 = VECTOR('',#184688,1.); +#184688 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184689 = PCURVE('',#184115,#184690); +#184690 = DEFINITIONAL_REPRESENTATION('',(#184691),#184694); +#184691 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184692,#184693), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#182300 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); -#182301 = CARTESIAN_POINT('',(1.495443868184,0.34)); -#182302 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182303 = PCURVE('',#181750,#182304); -#182304 = DEFINITIONAL_REPRESENTATION('',(#182305),#182309); -#182305 = LINE('',#182306,#182307); -#182306 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182307 = VECTOR('',#182308,1.); -#182308 = DIRECTION('',(0.E+000,1.)); -#182309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182310 = ORIENTED_EDGE('',*,*,#181919,.T.); -#182311 = ADVANCED_FACE('',(#182312),#181750,.T.); -#182312 = FACE_BOUND('',#182313,.T.); -#182313 = EDGE_LOOP('',(#182314,#182315,#182316,#182336)); -#182314 = ORIENTED_EDGE('',*,*,#182291,.T.); -#182315 = ORIENTED_EDGE('',*,*,#181896,.F.); -#182316 = ORIENTED_EDGE('',*,*,#182317,.F.); -#182317 = EDGE_CURVE('',#181735,#181870,#182318,.T.); -#182318 = SURFACE_CURVE('',#182319,(#182323,#182330),.PCURVE_S1.); -#182319 = LINE('',#182320,#182321); -#182320 = CARTESIAN_POINT('',(-1.165,-1.056555553792,0.518820292599)); -#182321 = VECTOR('',#182322,1.); -#182322 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182323 = PCURVE('',#181750,#182324); -#182324 = DEFINITIONAL_REPRESENTATION('',(#182325),#182329); -#182325 = LINE('',#182326,#182327); -#182326 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); -#182327 = VECTOR('',#182328,1.); -#182328 = DIRECTION('',(0.E+000,1.)); -#182329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182330 = PCURVE('',#181783,#182331); -#182331 = DEFINITIONAL_REPRESENTATION('',(#182332),#182335); -#182332 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#182333,#182334), +#184692 = CARTESIAN_POINT('',(1.495443868184,0.E+000)); +#184693 = CARTESIAN_POINT('',(1.495443868184,0.34)); +#184694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184695 = PCURVE('',#184142,#184696); +#184696 = DEFINITIONAL_REPRESENTATION('',(#184697),#184701); +#184697 = LINE('',#184698,#184699); +#184698 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184699 = VECTOR('',#184700,1.); +#184700 = DIRECTION('',(0.E+000,1.)); +#184701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184702 = ORIENTED_EDGE('',*,*,#184311,.T.); +#184703 = ADVANCED_FACE('',(#184704),#184142,.T.); +#184704 = FACE_BOUND('',#184705,.T.); +#184705 = EDGE_LOOP('',(#184706,#184707,#184708,#184728)); +#184706 = ORIENTED_EDGE('',*,*,#184683,.T.); +#184707 = ORIENTED_EDGE('',*,*,#184288,.F.); +#184708 = ORIENTED_EDGE('',*,*,#184709,.F.); +#184709 = EDGE_CURVE('',#184127,#184262,#184710,.T.); +#184710 = SURFACE_CURVE('',#184711,(#184715,#184722),.PCURVE_S1.); +#184711 = LINE('',#184712,#184713); +#184712 = CARTESIAN_POINT('',(-1.165,-1.056555553792,0.518820292599)); +#184713 = VECTOR('',#184714,1.); +#184714 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184715 = PCURVE('',#184142,#184716); +#184716 = DEFINITIONAL_REPRESENTATION('',(#184717),#184721); +#184717 = LINE('',#184718,#184719); +#184718 = CARTESIAN_POINT('',(-0.323502338645,0.E+000)); +#184719 = VECTOR('',#184720,1.); +#184720 = DIRECTION('',(0.E+000,1.)); +#184721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184722 = PCURVE('',#184175,#184723); +#184723 = DEFINITIONAL_REPRESENTATION('',(#184724),#184727); +#184724 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184725,#184726), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.34),.PIECEWISE_BEZIER_KNOTS.); -#182333 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); -#182334 = CARTESIAN_POINT('',(4.637036521774,0.34)); -#182335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182336 = ORIENTED_EDGE('',*,*,#181734,.T.); -#182337 = ADVANCED_FACE('',(#182338),#181783,.T.); -#182338 = FACE_BOUND('',#182339,.T.); -#182339 = EDGE_LOOP('',(#182340,#182341,#182342,#182343)); -#182340 = ORIENTED_EDGE('',*,*,#182317,.T.); -#182341 = ORIENTED_EDGE('',*,*,#181869,.F.); -#182342 = ORIENTED_EDGE('',*,*,#181818,.F.); -#182343 = ORIENTED_EDGE('',*,*,#181762,.T.); -#182344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182348)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182345,#182346,#182347)) +#184725 = CARTESIAN_POINT('',(4.637036521774,0.E+000)); +#184726 = CARTESIAN_POINT('',(4.637036521774,0.34)); +#184727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184728 = ORIENTED_EDGE('',*,*,#184126,.T.); +#184729 = ADVANCED_FACE('',(#184730),#184175,.T.); +#184730 = FACE_BOUND('',#184731,.T.); +#184731 = EDGE_LOOP('',(#184732,#184733,#184734,#184735)); +#184732 = ORIENTED_EDGE('',*,*,#184709,.T.); +#184733 = ORIENTED_EDGE('',*,*,#184261,.F.); +#184734 = ORIENTED_EDGE('',*,*,#184210,.F.); +#184735 = ORIENTED_EDGE('',*,*,#184154,.T.); +#184736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#184740)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#184737,#184738,#184739)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182345 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182346 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182347 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182348 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#182345, +#184737 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#184738 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#184739 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#184740 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#184737, 'distance_accuracy_value','confusion accuracy'); -#182349 = SHAPE_DEFINITION_REPRESENTATION(#182350,#168636); -#182350 = PRODUCT_DEFINITION_SHAPE('','',#182351); -#182351 = PRODUCT_DEFINITION('design','',#182352,#182355); -#182352 = PRODUCT_DEFINITION_FORMATION('','',#182353); -#182353 = PRODUCT('User_Library-sot238','User_Library-sot238','',( - #182354)); -#182354 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182355 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182356 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182357,#182359); -#182357 = ( REPRESENTATION_RELATIONSHIP('','',#168636,#168626) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182358) +#184741 = SHAPE_DEFINITION_REPRESENTATION(#184742,#171028); +#184742 = PRODUCT_DEFINITION_SHAPE('','',#184743); +#184743 = PRODUCT_DEFINITION('design','',#184744,#184747); +#184744 = PRODUCT_DEFINITION_FORMATION('','',#184745); +#184745 = PRODUCT('User_Library-sot238','User_Library-sot238','',( + #184746)); +#184746 = PRODUCT_CONTEXT('',#2,'mechanical'); +#184747 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#184748 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#184749,#184751); +#184749 = ( REPRESENTATION_RELATIONSHIP('','',#171028,#171018) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#184750) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182358 = ITEM_DEFINED_TRANSFORMATION('','',#11,#168627); -#182359 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182360); -#182360 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('308','=>[0:1:1:107]','', - #168621,#182351,$); -#182361 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182353)); -#182362 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182363,#182365); -#182363 = ( REPRESENTATION_RELATIONSHIP('','',#168626,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182364) +#184750 = ITEM_DEFINED_TRANSFORMATION('','',#11,#171019); +#184751 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #184752); +#184752 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('409','=>[0:1:1:107]','', + #171013,#184743,$); +#184753 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#184745)); +#184754 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#184755,#184757); +#184755 = ( REPRESENTATION_RELATIONSHIP('','',#171018,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#184756) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182364 = ITEM_DEFINED_TRANSFORMATION('','',#11,#283); -#182365 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182366); -#182366 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('309','=>[0:1:1:106]','',#5, - #168621,$); -#182367 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#168623)); -#182368 = SHAPE_DEFINITION_REPRESENTATION(#182369,#182375); -#182369 = PRODUCT_DEFINITION_SHAPE('','',#182370); -#182370 = PRODUCT_DEFINITION('design','',#182371,#182374); -#182371 = PRODUCT_DEFINITION_FORMATION('','',#182372); -#182372 = PRODUCT('RF1','RF1','',(#182373)); -#182373 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182374 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182375 = SHAPE_REPRESENTATION('',(#11,#182376),#182380); -#182376 = AXIS2_PLACEMENT_3D('',#182377,#182378,#182379); -#182377 = CARTESIAN_POINT('',(18.00899878,20.2429999,-4.17837874)); -#182378 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182379 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182384)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182381,#182382,#182383)) +#184756 = ITEM_DEFINED_TRANSFORMATION('','',#11,#283); +#184757 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #184758); +#184758 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('410','=>[0:1:1:106]','',#5, + #171013,$); +#184759 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#171015)); +#184760 = SHAPE_DEFINITION_REPRESENTATION(#184761,#184767); +#184761 = PRODUCT_DEFINITION_SHAPE('','',#184762); +#184762 = PRODUCT_DEFINITION('design','',#184763,#184766); +#184763 = PRODUCT_DEFINITION_FORMATION('','',#184764); +#184764 = PRODUCT('RF1','RF1','',(#184765)); +#184765 = PRODUCT_CONTEXT('',#2,'mechanical'); +#184766 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#184767 = SHAPE_REPRESENTATION('',(#11,#184768),#184772); +#184768 = AXIS2_PLACEMENT_3D('',#184769,#184770,#184771); +#184769 = CARTESIAN_POINT('',(18.00899878,20.2429999,-3.58909874)); +#184770 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184771 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184772 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#184776)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#184773,#184774,#184775)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182381 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182382 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182383 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182384 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182381, +#184773 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#184774 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#184775 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#184776 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#184773, 'distance_accuracy_value','confusion accuracy'); -#182385 = SHAPE_DEFINITION_REPRESENTATION(#182386,#182392); -#182386 = PRODUCT_DEFINITION_SHAPE('','',#182387); -#182387 = PRODUCT_DEFINITION('design','',#182388,#182391); -#182388 = PRODUCT_DEFINITION_FORMATION('','',#182389); -#182389 = PRODUCT('622913696','622913696','',(#182390)); -#182390 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182391 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182392 = SHAPE_REPRESENTATION('',(#11,#182393),#182397); -#182393 = AXIS2_PLACEMENT_3D('',#182394,#182395,#182396); -#182394 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#182395 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182396 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182397 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182401)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182398,#182399,#182400)) +#184777 = SHAPE_DEFINITION_REPRESENTATION(#184778,#184784); +#184778 = PRODUCT_DEFINITION_SHAPE('','',#184779); +#184779 = PRODUCT_DEFINITION('design','',#184780,#184783); +#184780 = PRODUCT_DEFINITION_FORMATION('','',#184781); +#184781 = PRODUCT('549179936','549179936','',(#184782)); +#184782 = PRODUCT_CONTEXT('',#2,'mechanical'); +#184783 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#184784 = SHAPE_REPRESENTATION('',(#11,#184785),#184789); +#184785 = AXIS2_PLACEMENT_3D('',#184786,#184787,#184788); +#184786 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#184787 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184788 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#184793)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#184790,#184791,#184792)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182398 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182399 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182400 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182401 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182398, +#184790 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#184791 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#184792 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#184793 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#184790, 'distance_accuracy_value','confusion accuracy'); -#182402 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#182403),#182733); -#182403 = MANIFOLD_SOLID_BREP('',#182404); -#182404 = CLOSED_SHELL('',(#182405,#182525,#182601,#182672,#182719, - #182726)); -#182405 = ADVANCED_FACE('',(#182406),#182420,.F.); -#182406 = FACE_BOUND('',#182407,.F.); -#182407 = EDGE_LOOP('',(#182408,#182443,#182471,#182499)); -#182408 = ORIENTED_EDGE('',*,*,#182409,.T.); -#182409 = EDGE_CURVE('',#182410,#182412,#182414,.T.); -#182410 = VERTEX_POINT('',#182411); -#182411 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); -#182412 = VERTEX_POINT('',#182413); -#182413 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); -#182414 = SURFACE_CURVE('',#182415,(#182419,#182431),.PCURVE_S1.); -#182415 = LINE('',#182416,#182417); -#182416 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); -#182417 = VECTOR('',#182418,1.); -#182418 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182419 = PCURVE('',#182420,#182425); -#182420 = PLANE('',#182421); -#182421 = AXIS2_PLACEMENT_3D('',#182422,#182423,#182424); -#182422 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); -#182423 = DIRECTION('',(0.99999517722,3.105726478418E-003,0.E+000)); -#182424 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); -#182425 = DEFINITIONAL_REPRESENTATION('',(#182426),#182430); -#182426 = LINE('',#182427,#182428); -#182427 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182428 = VECTOR('',#182429,1.); -#182429 = DIRECTION('',(0.E+000,-1.)); -#182430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182431 = PCURVE('',#182432,#182437); -#182432 = PLANE('',#182433); -#182433 = AXIS2_PLACEMENT_3D('',#182434,#182435,#182436); -#182434 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); -#182435 = DIRECTION('',(-6.230554094296E-003,-0.999980589909,0.E+000)); -#182436 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); -#182437 = DEFINITIONAL_REPRESENTATION('',(#182438),#182442); -#182438 = LINE('',#182439,#182440); -#182439 = CARTESIAN_POINT('',(16.050312458018,0.E+000)); -#182440 = VECTOR('',#182441,1.); -#182441 = DIRECTION('',(0.E+000,-1.)); -#182442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182443 = ORIENTED_EDGE('',*,*,#182444,.T.); -#182444 = EDGE_CURVE('',#182412,#182445,#182447,.T.); -#182445 = VERTEX_POINT('',#182446); -#182446 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,1.9)); -#182447 = SURFACE_CURVE('',#182448,(#182452,#182459),.PCURVE_S1.); -#182448 = LINE('',#182449,#182450); -#182449 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); -#182450 = VECTOR('',#182451,1.); -#182451 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); -#182452 = PCURVE('',#182420,#182453); -#182453 = DEFINITIONAL_REPRESENTATION('',(#182454),#182458); -#182454 = LINE('',#182455,#182456); -#182455 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#182456 = VECTOR('',#182457,1.); -#182457 = DIRECTION('',(1.,0.E+000)); -#182458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182459 = PCURVE('',#182460,#182465); -#182460 = PLANE('',#182461); -#182461 = AXIS2_PLACEMENT_3D('',#182462,#182463,#182464); -#182462 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); -#182463 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#182464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#182465 = DEFINITIONAL_REPRESENTATION('',(#182466),#182470); -#182466 = LINE('',#182467,#182468); -#182467 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182468 = VECTOR('',#182469,1.); -#182469 = DIRECTION('',(-3.105726478418E-003,-0.99999517722)); -#182470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182471 = ORIENTED_EDGE('',*,*,#182472,.F.); -#182472 = EDGE_CURVE('',#182473,#182445,#182475,.T.); -#182473 = VERTEX_POINT('',#182474); -#182474 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); -#182475 = SURFACE_CURVE('',#182476,(#182480,#182487),.PCURVE_S1.); -#182476 = LINE('',#182477,#182478); -#182477 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); -#182478 = VECTOR('',#182479,1.); -#182479 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182480 = PCURVE('',#182420,#182481); -#182481 = DEFINITIONAL_REPRESENTATION('',(#182482),#182486); -#182482 = LINE('',#182483,#182484); -#182483 = CARTESIAN_POINT('',(16.100078467138,0.E+000)); -#182484 = VECTOR('',#182485,1.); -#182485 = DIRECTION('',(0.E+000,-1.)); -#182486 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182487 = PCURVE('',#182488,#182493); -#182488 = PLANE('',#182489); -#182489 = AXIS2_PLACEMENT_3D('',#182490,#182491,#182492); -#182490 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); -#182491 = DIRECTION('',(0.E+000,1.,0.E+000)); -#182492 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182493 = DEFINITIONAL_REPRESENTATION('',(#182494),#182498); -#182494 = LINE('',#182495,#182496); -#182495 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182496 = VECTOR('',#182497,1.); -#182497 = DIRECTION('',(0.E+000,-1.)); -#182498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182499 = ORIENTED_EDGE('',*,*,#182500,.F.); -#182500 = EDGE_CURVE('',#182410,#182473,#182501,.T.); -#182501 = SURFACE_CURVE('',#182502,(#182506,#182513),.PCURVE_S1.); -#182502 = LINE('',#182503,#182504); -#182503 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); -#182504 = VECTOR('',#182505,1.); -#182505 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); -#182506 = PCURVE('',#182420,#182507); -#182507 = DEFINITIONAL_REPRESENTATION('',(#182508),#182512); -#182508 = LINE('',#182509,#182510); -#182509 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182510 = VECTOR('',#182511,1.); -#182511 = DIRECTION('',(1.,0.E+000)); -#182512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182513 = PCURVE('',#182514,#182519); -#182514 = PLANE('',#182515); -#182515 = AXIS2_PLACEMENT_3D('',#182516,#182517,#182518); -#182516 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); -#182517 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#182518 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#182519 = DEFINITIONAL_REPRESENTATION('',(#182520),#182524); -#182520 = LINE('',#182521,#182522); -#182521 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182522 = VECTOR('',#182523,1.); -#182523 = DIRECTION('',(-3.105726478418E-003,-0.99999517722)); -#182524 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182525 = ADVANCED_FACE('',(#182526),#182488,.F.); -#182526 = FACE_BOUND('',#182527,.F.); -#182527 = EDGE_LOOP('',(#182528,#182529,#182552,#182580)); -#182528 = ORIENTED_EDGE('',*,*,#182472,.T.); -#182529 = ORIENTED_EDGE('',*,*,#182530,.T.); -#182530 = EDGE_CURVE('',#182445,#182531,#182533,.T.); -#182531 = VERTEX_POINT('',#182532); -#182532 = CARTESIAN_POINT('',(8.02500046,-8.04999914,1.9)); -#182533 = SURFACE_CURVE('',#182534,(#182538,#182545),.PCURVE_S1.); -#182534 = LINE('',#182535,#182536); -#182535 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,1.9)); -#182536 = VECTOR('',#182537,1.); -#182537 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182538 = PCURVE('',#182488,#182539); -#182539 = DEFINITIONAL_REPRESENTATION('',(#182540),#182544); -#182540 = LINE('',#182541,#182542); -#182541 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#182542 = VECTOR('',#182543,1.); -#182543 = DIRECTION('',(1.,0.E+000)); -#182544 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182545 = PCURVE('',#182460,#182546); -#182546 = DEFINITIONAL_REPRESENTATION('',(#182547),#182551); -#182547 = LINE('',#182548,#182549); -#182548 = CARTESIAN_POINT('',(-5.000244E-002,-16.10000082)); -#182549 = VECTOR('',#182550,1.); -#182550 = DIRECTION('',(-1.,0.E+000)); -#182551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182552 = ORIENTED_EDGE('',*,*,#182553,.F.); -#182553 = EDGE_CURVE('',#182554,#182531,#182556,.T.); -#182554 = VERTEX_POINT('',#182555); -#182555 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); -#182556 = SURFACE_CURVE('',#182557,(#182561,#182568),.PCURVE_S1.); -#182557 = LINE('',#182558,#182559); -#182558 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); -#182559 = VECTOR('',#182560,1.); -#182560 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182561 = PCURVE('',#182488,#182562); -#182562 = DEFINITIONAL_REPRESENTATION('',(#182563),#182567); -#182563 = LINE('',#182564,#182565); -#182564 = CARTESIAN_POINT('',(15.99999848,0.E+000)); -#182565 = VECTOR('',#182566,1.); -#182566 = DIRECTION('',(0.E+000,-1.)); -#182567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182568 = PCURVE('',#182569,#182574); -#182569 = PLANE('',#182570); -#182570 = AXIS2_PLACEMENT_3D('',#182571,#182572,#182573); -#182571 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); -#182572 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#182573 = DIRECTION('',(0.E+000,1.,0.E+000)); -#182574 = DEFINITIONAL_REPRESENTATION('',(#182575),#182579); -#182575 = LINE('',#182576,#182577); -#182576 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182577 = VECTOR('',#182578,1.); -#182578 = DIRECTION('',(0.E+000,-1.)); -#182579 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182580 = ORIENTED_EDGE('',*,*,#182581,.F.); -#182581 = EDGE_CURVE('',#182473,#182554,#182582,.T.); -#182582 = SURFACE_CURVE('',#182583,(#182587,#182594),.PCURVE_S1.); -#182583 = LINE('',#182584,#182585); -#182584 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); -#182585 = VECTOR('',#182586,1.); -#182586 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182587 = PCURVE('',#182488,#182588); -#182588 = DEFINITIONAL_REPRESENTATION('',(#182589),#182593); -#182589 = LINE('',#182590,#182591); -#182590 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182591 = VECTOR('',#182592,1.); -#182592 = DIRECTION('',(1.,0.E+000)); -#182593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182594 = PCURVE('',#182514,#182595); -#182595 = DEFINITIONAL_REPRESENTATION('',(#182596),#182600); -#182596 = LINE('',#182597,#182598); -#182597 = CARTESIAN_POINT('',(-5.000244E-002,-16.10000082)); -#182598 = VECTOR('',#182599,1.); -#182599 = DIRECTION('',(-1.,0.E+000)); -#182600 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182601 = ADVANCED_FACE('',(#182602),#182569,.F.); -#182602 = FACE_BOUND('',#182603,.F.); -#182603 = EDGE_LOOP('',(#182604,#182605,#182628,#182651)); -#182604 = ORIENTED_EDGE('',*,*,#182553,.T.); -#182605 = ORIENTED_EDGE('',*,*,#182606,.T.); -#182606 = EDGE_CURVE('',#182531,#182607,#182609,.T.); -#182607 = VERTEX_POINT('',#182608); -#182608 = CARTESIAN_POINT('',(8.02500046,7.94999934,1.9)); -#182609 = SURFACE_CURVE('',#182610,(#182614,#182621),.PCURVE_S1.); -#182610 = LINE('',#182611,#182612); -#182611 = CARTESIAN_POINT('',(8.02500046,-8.04999914,1.9)); -#182612 = VECTOR('',#182613,1.); -#182613 = DIRECTION('',(0.E+000,1.,0.E+000)); -#182614 = PCURVE('',#182569,#182615); -#182615 = DEFINITIONAL_REPRESENTATION('',(#182616),#182620); -#182616 = LINE('',#182617,#182618); -#182617 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#182618 = VECTOR('',#182619,1.); -#182619 = DIRECTION('',(1.,0.E+000)); -#182620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182621 = PCURVE('',#182460,#182622); -#182622 = DEFINITIONAL_REPRESENTATION('',(#182623),#182627); -#182623 = LINE('',#182624,#182625); -#182624 = CARTESIAN_POINT('',(-16.05000092,-16.10000082)); -#182625 = VECTOR('',#182626,1.); -#182626 = DIRECTION('',(0.E+000,1.)); -#182627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182628 = ORIENTED_EDGE('',*,*,#182629,.F.); -#182629 = EDGE_CURVE('',#182630,#182607,#182632,.T.); -#182630 = VERTEX_POINT('',#182631); -#182631 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); -#182632 = SURFACE_CURVE('',#182633,(#182637,#182644),.PCURVE_S1.); -#182633 = LINE('',#182634,#182635); -#182634 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); -#182635 = VECTOR('',#182636,1.); -#182636 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182637 = PCURVE('',#182569,#182638); -#182638 = DEFINITIONAL_REPRESENTATION('',(#182639),#182643); -#182639 = LINE('',#182640,#182641); -#182640 = CARTESIAN_POINT('',(15.99999848,0.E+000)); -#182641 = VECTOR('',#182642,1.); -#182642 = DIRECTION('',(0.E+000,-1.)); -#182643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182644 = PCURVE('',#182432,#182645); -#182645 = DEFINITIONAL_REPRESENTATION('',(#182646),#182650); -#182646 = LINE('',#182647,#182648); -#182647 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182648 = VECTOR('',#182649,1.); -#182649 = DIRECTION('',(0.E+000,-1.)); -#182650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#184794 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#184795),#185125); +#184795 = MANIFOLD_SOLID_BREP('',#184796); +#184796 = CLOSED_SHELL('',(#184797,#184917,#184993,#185064,#185111, + #185118)); +#184797 = ADVANCED_FACE('',(#184798),#184812,.F.); +#184798 = FACE_BOUND('',#184799,.F.); +#184799 = EDGE_LOOP('',(#184800,#184835,#184863,#184891)); +#184800 = ORIENTED_EDGE('',*,*,#184801,.T.); +#184801 = EDGE_CURVE('',#184802,#184804,#184806,.T.); +#184802 = VERTEX_POINT('',#184803); +#184803 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); +#184804 = VERTEX_POINT('',#184805); +#184805 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); +#184806 = SURFACE_CURVE('',#184807,(#184811,#184823),.PCURVE_S1.); +#184807 = LINE('',#184808,#184809); +#184808 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); +#184809 = VECTOR('',#184810,1.); +#184810 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184811 = PCURVE('',#184812,#184817); +#184812 = PLANE('',#184813); +#184813 = AXIS2_PLACEMENT_3D('',#184814,#184815,#184816); +#184814 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); +#184815 = DIRECTION('',(0.99999517722,3.105726478418E-003,0.E+000)); +#184816 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); +#184817 = DEFINITIONAL_REPRESENTATION('',(#184818),#184822); +#184818 = LINE('',#184819,#184820); +#184819 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184820 = VECTOR('',#184821,1.); +#184821 = DIRECTION('',(0.E+000,-1.)); +#184822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184823 = PCURVE('',#184824,#184829); +#184824 = PLANE('',#184825); +#184825 = AXIS2_PLACEMENT_3D('',#184826,#184827,#184828); +#184826 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); +#184827 = DIRECTION('',(-6.230554094296E-003,-0.999980589909,0.E+000)); +#184828 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); +#184829 = DEFINITIONAL_REPRESENTATION('',(#184830),#184834); +#184830 = LINE('',#184831,#184832); +#184831 = CARTESIAN_POINT('',(16.050312458018,0.E+000)); +#184832 = VECTOR('',#184833,1.); +#184833 = DIRECTION('',(0.E+000,-1.)); +#184834 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184835 = ORIENTED_EDGE('',*,*,#184836,.T.); +#184836 = EDGE_CURVE('',#184804,#184837,#184839,.T.); +#184837 = VERTEX_POINT('',#184838); +#184838 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,1.9)); +#184839 = SURFACE_CURVE('',#184840,(#184844,#184851),.PCURVE_S1.); +#184840 = LINE('',#184841,#184842); +#184841 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); +#184842 = VECTOR('',#184843,1.); +#184843 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); +#184844 = PCURVE('',#184812,#184845); +#184845 = DEFINITIONAL_REPRESENTATION('',(#184846),#184850); +#184846 = LINE('',#184847,#184848); +#184847 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#184848 = VECTOR('',#184849,1.); +#184849 = DIRECTION('',(1.,0.E+000)); +#184850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184851 = PCURVE('',#184852,#184857); +#184852 = PLANE('',#184853); +#184853 = AXIS2_PLACEMENT_3D('',#184854,#184855,#184856); +#184854 = CARTESIAN_POINT('',(-8.02500046,8.05000168,1.9)); +#184855 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184857 = DEFINITIONAL_REPRESENTATION('',(#184858),#184862); +#184858 = LINE('',#184859,#184860); +#184859 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184860 = VECTOR('',#184861,1.); +#184861 = DIRECTION('',(-3.105726478418E-003,-0.99999517722)); +#184862 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184863 = ORIENTED_EDGE('',*,*,#184864,.F.); +#184864 = EDGE_CURVE('',#184865,#184837,#184867,.T.); +#184865 = VERTEX_POINT('',#184866); +#184866 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); +#184867 = SURFACE_CURVE('',#184868,(#184872,#184879),.PCURVE_S1.); +#184868 = LINE('',#184869,#184870); +#184869 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); +#184870 = VECTOR('',#184871,1.); +#184871 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184872 = PCURVE('',#184812,#184873); +#184873 = DEFINITIONAL_REPRESENTATION('',(#184874),#184878); +#184874 = LINE('',#184875,#184876); +#184875 = CARTESIAN_POINT('',(16.100078467138,0.E+000)); +#184876 = VECTOR('',#184877,1.); +#184877 = DIRECTION('',(0.E+000,-1.)); +#184878 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184879 = PCURVE('',#184880,#184885); +#184880 = PLANE('',#184881); +#184881 = AXIS2_PLACEMENT_3D('',#184882,#184883,#184884); +#184882 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); +#184883 = DIRECTION('',(0.E+000,1.,0.E+000)); +#184884 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184885 = DEFINITIONAL_REPRESENTATION('',(#184886),#184890); +#184886 = LINE('',#184887,#184888); +#184887 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184888 = VECTOR('',#184889,1.); +#184889 = DIRECTION('',(0.E+000,-1.)); +#184890 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184891 = ORIENTED_EDGE('',*,*,#184892,.F.); +#184892 = EDGE_CURVE('',#184802,#184865,#184893,.T.); +#184893 = SURFACE_CURVE('',#184894,(#184898,#184905),.PCURVE_S1.); +#184894 = LINE('',#184895,#184896); +#184895 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); +#184896 = VECTOR('',#184897,1.); +#184897 = DIRECTION('',(3.105726478418E-003,-0.99999517722,0.E+000)); +#184898 = PCURVE('',#184812,#184899); +#184899 = DEFINITIONAL_REPRESENTATION('',(#184900),#184904); +#184900 = LINE('',#184901,#184902); +#184901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184902 = VECTOR('',#184903,1.); +#184903 = DIRECTION('',(1.,0.E+000)); +#184904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184905 = PCURVE('',#184906,#184911); +#184906 = PLANE('',#184907); +#184907 = AXIS2_PLACEMENT_3D('',#184908,#184909,#184910); +#184908 = CARTESIAN_POINT('',(-8.02500046,8.05000168,0.E+000)); +#184909 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#184910 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184911 = DEFINITIONAL_REPRESENTATION('',(#184912),#184916); +#184912 = LINE('',#184913,#184914); +#184913 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184914 = VECTOR('',#184915,1.); +#184915 = DIRECTION('',(-3.105726478418E-003,-0.99999517722)); +#184916 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184917 = ADVANCED_FACE('',(#184918),#184880,.F.); +#184918 = FACE_BOUND('',#184919,.F.); +#184919 = EDGE_LOOP('',(#184920,#184921,#184944,#184972)); +#184920 = ORIENTED_EDGE('',*,*,#184864,.T.); +#184921 = ORIENTED_EDGE('',*,*,#184922,.T.); +#184922 = EDGE_CURVE('',#184837,#184923,#184925,.T.); +#184923 = VERTEX_POINT('',#184924); +#184924 = CARTESIAN_POINT('',(8.02500046,-8.04999914,1.9)); +#184925 = SURFACE_CURVE('',#184926,(#184930,#184937),.PCURVE_S1.); +#184926 = LINE('',#184927,#184928); +#184927 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,1.9)); +#184928 = VECTOR('',#184929,1.); +#184929 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184930 = PCURVE('',#184880,#184931); +#184931 = DEFINITIONAL_REPRESENTATION('',(#184932),#184936); +#184932 = LINE('',#184933,#184934); +#184933 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#184934 = VECTOR('',#184935,1.); +#184935 = DIRECTION('',(1.,0.E+000)); +#184936 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184937 = PCURVE('',#184852,#184938); +#184938 = DEFINITIONAL_REPRESENTATION('',(#184939),#184943); +#184939 = LINE('',#184940,#184941); +#184940 = CARTESIAN_POINT('',(-5.000244E-002,-16.10000082)); +#184941 = VECTOR('',#184942,1.); +#184942 = DIRECTION('',(-1.,0.E+000)); +#184943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184944 = ORIENTED_EDGE('',*,*,#184945,.F.); +#184945 = EDGE_CURVE('',#184946,#184923,#184948,.T.); +#184946 = VERTEX_POINT('',#184947); +#184947 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); +#184948 = SURFACE_CURVE('',#184949,(#184953,#184960),.PCURVE_S1.); +#184949 = LINE('',#184950,#184951); +#184950 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); +#184951 = VECTOR('',#184952,1.); +#184952 = DIRECTION('',(0.E+000,0.E+000,1.)); +#184953 = PCURVE('',#184880,#184954); +#184954 = DEFINITIONAL_REPRESENTATION('',(#184955),#184959); +#184955 = LINE('',#184956,#184957); +#184956 = CARTESIAN_POINT('',(15.99999848,0.E+000)); +#184957 = VECTOR('',#184958,1.); +#184958 = DIRECTION('',(0.E+000,-1.)); +#184959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184960 = PCURVE('',#184961,#184966); +#184961 = PLANE('',#184962); +#184962 = AXIS2_PLACEMENT_3D('',#184963,#184964,#184965); +#184963 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); +#184964 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#184965 = DIRECTION('',(0.E+000,1.,0.E+000)); +#184966 = DEFINITIONAL_REPRESENTATION('',(#184967),#184971); +#184967 = LINE('',#184968,#184969); +#184968 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184969 = VECTOR('',#184970,1.); +#184970 = DIRECTION('',(0.E+000,-1.)); +#184971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184972 = ORIENTED_EDGE('',*,*,#184973,.F.); +#184973 = EDGE_CURVE('',#184865,#184946,#184974,.T.); +#184974 = SURFACE_CURVE('',#184975,(#184979,#184986),.PCURVE_S1.); +#184975 = LINE('',#184976,#184977); +#184976 = CARTESIAN_POINT('',(-7.97499802,-8.04999914,0.E+000)); +#184977 = VECTOR('',#184978,1.); +#184978 = DIRECTION('',(1.,0.E+000,0.E+000)); +#184979 = PCURVE('',#184880,#184980); +#184980 = DEFINITIONAL_REPRESENTATION('',(#184981),#184985); +#184981 = LINE('',#184982,#184983); +#184982 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#184983 = VECTOR('',#184984,1.); +#184984 = DIRECTION('',(1.,0.E+000)); +#184985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184986 = PCURVE('',#184906,#184987); +#184987 = DEFINITIONAL_REPRESENTATION('',(#184988),#184992); +#184988 = LINE('',#184989,#184990); +#184989 = CARTESIAN_POINT('',(-5.000244E-002,-16.10000082)); +#184990 = VECTOR('',#184991,1.); +#184991 = DIRECTION('',(-1.,0.E+000)); +#184992 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#184993 = ADVANCED_FACE('',(#184994),#184961,.F.); +#184994 = FACE_BOUND('',#184995,.F.); +#184995 = EDGE_LOOP('',(#184996,#184997,#185020,#185043)); +#184996 = ORIENTED_EDGE('',*,*,#184945,.T.); +#184997 = ORIENTED_EDGE('',*,*,#184998,.T.); +#184998 = EDGE_CURVE('',#184923,#184999,#185001,.T.); +#184999 = VERTEX_POINT('',#185000); +#185000 = CARTESIAN_POINT('',(8.02500046,7.94999934,1.9)); +#185001 = SURFACE_CURVE('',#185002,(#185006,#185013),.PCURVE_S1.); +#185002 = LINE('',#185003,#185004); +#185003 = CARTESIAN_POINT('',(8.02500046,-8.04999914,1.9)); +#185004 = VECTOR('',#185005,1.); +#185005 = DIRECTION('',(0.E+000,1.,0.E+000)); +#185006 = PCURVE('',#184961,#185007); +#185007 = DEFINITIONAL_REPRESENTATION('',(#185008),#185012); +#185008 = LINE('',#185009,#185010); +#185009 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#185010 = VECTOR('',#185011,1.); +#185011 = DIRECTION('',(1.,0.E+000)); +#185012 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185013 = PCURVE('',#184852,#185014); +#185014 = DEFINITIONAL_REPRESENTATION('',(#185015),#185019); +#185015 = LINE('',#185016,#185017); +#185016 = CARTESIAN_POINT('',(-16.05000092,-16.10000082)); +#185017 = VECTOR('',#185018,1.); +#185018 = DIRECTION('',(0.E+000,1.)); +#185019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185020 = ORIENTED_EDGE('',*,*,#185021,.F.); +#185021 = EDGE_CURVE('',#185022,#184999,#185024,.T.); +#185022 = VERTEX_POINT('',#185023); +#185023 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); +#185024 = SURFACE_CURVE('',#185025,(#185029,#185036),.PCURVE_S1.); +#185025 = LINE('',#185026,#185027); +#185026 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); +#185027 = VECTOR('',#185028,1.); +#185028 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185029 = PCURVE('',#184961,#185030); +#185030 = DEFINITIONAL_REPRESENTATION('',(#185031),#185035); +#185031 = LINE('',#185032,#185033); +#185032 = CARTESIAN_POINT('',(15.99999848,0.E+000)); +#185033 = VECTOR('',#185034,1.); +#185034 = DIRECTION('',(0.E+000,-1.)); +#185035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185036 = PCURVE('',#184824,#185037); +#185037 = DEFINITIONAL_REPRESENTATION('',(#185038),#185042); +#185038 = LINE('',#185039,#185040); +#185039 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#185040 = VECTOR('',#185041,1.); +#185041 = DIRECTION('',(0.E+000,-1.)); +#185042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#182651 = ORIENTED_EDGE('',*,*,#182652,.F.); -#182652 = EDGE_CURVE('',#182554,#182630,#182653,.T.); -#182653 = SURFACE_CURVE('',#182654,(#182658,#182665),.PCURVE_S1.); -#182654 = LINE('',#182655,#182656); -#182655 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); -#182656 = VECTOR('',#182657,1.); -#182657 = DIRECTION('',(0.E+000,1.,0.E+000)); -#182658 = PCURVE('',#182569,#182659); -#182659 = DEFINITIONAL_REPRESENTATION('',(#182660),#182664); -#182660 = LINE('',#182661,#182662); -#182661 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182662 = VECTOR('',#182663,1.); -#182663 = DIRECTION('',(1.,0.E+000)); -#182664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182665 = PCURVE('',#182514,#182666); -#182666 = DEFINITIONAL_REPRESENTATION('',(#182667),#182671); -#182667 = LINE('',#182668,#182669); -#182668 = CARTESIAN_POINT('',(-16.05000092,-16.10000082)); -#182669 = VECTOR('',#182670,1.); -#182670 = DIRECTION('',(0.E+000,1.)); -#182671 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182672 = ADVANCED_FACE('',(#182673),#182432,.F.); -#182673 = FACE_BOUND('',#182674,.F.); -#182674 = EDGE_LOOP('',(#182675,#182676,#182697,#182698)); -#182675 = ORIENTED_EDGE('',*,*,#182629,.T.); -#182676 = ORIENTED_EDGE('',*,*,#182677,.T.); -#182677 = EDGE_CURVE('',#182607,#182412,#182678,.T.); -#182678 = SURFACE_CURVE('',#182679,(#182683,#182690),.PCURVE_S1.); -#182679 = LINE('',#182680,#182681); -#182680 = CARTESIAN_POINT('',(8.02500046,7.94999934,1.9)); -#182681 = VECTOR('',#182682,1.); -#182682 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); -#182683 = PCURVE('',#182432,#182684); -#182684 = DEFINITIONAL_REPRESENTATION('',(#182685),#182689); -#182685 = LINE('',#182686,#182687); -#182686 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#182687 = VECTOR('',#182688,1.); -#182688 = DIRECTION('',(1.,0.E+000)); -#182689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182690 = PCURVE('',#182460,#182691); -#182691 = DEFINITIONAL_REPRESENTATION('',(#182692),#182696); -#182692 = LINE('',#182693,#182694); -#182693 = CARTESIAN_POINT('',(-16.05000092,-0.10000234)); -#182694 = VECTOR('',#182695,1.); -#182695 = DIRECTION('',(0.999980589909,6.230554094296E-003)); -#182696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182697 = ORIENTED_EDGE('',*,*,#182409,.F.); -#182698 = ORIENTED_EDGE('',*,*,#182699,.F.); -#182699 = EDGE_CURVE('',#182630,#182410,#182700,.T.); -#182700 = SURFACE_CURVE('',#182701,(#182705,#182712),.PCURVE_S1.); -#182701 = LINE('',#182702,#182703); -#182702 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); -#182703 = VECTOR('',#182704,1.); -#182704 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); -#182705 = PCURVE('',#182432,#182706); -#182706 = DEFINITIONAL_REPRESENTATION('',(#182707),#182711); -#182707 = LINE('',#182708,#182709); -#182708 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#182709 = VECTOR('',#182710,1.); -#182710 = DIRECTION('',(1.,0.E+000)); -#182711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#182712 = PCURVE('',#182514,#182713); -#182713 = DEFINITIONAL_REPRESENTATION('',(#182714),#182718); -#182714 = LINE('',#182715,#182716); -#182715 = CARTESIAN_POINT('',(-16.05000092,-0.10000234)); -#182716 = VECTOR('',#182717,1.); -#182717 = DIRECTION('',(0.999980589909,6.230554094296E-003)); -#182718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#185043 = ORIENTED_EDGE('',*,*,#185044,.F.); +#185044 = EDGE_CURVE('',#184946,#185022,#185045,.T.); +#185045 = SURFACE_CURVE('',#185046,(#185050,#185057),.PCURVE_S1.); +#185046 = LINE('',#185047,#185048); +#185047 = CARTESIAN_POINT('',(8.02500046,-8.04999914,0.E+000)); +#185048 = VECTOR('',#185049,1.); +#185049 = DIRECTION('',(0.E+000,1.,0.E+000)); +#185050 = PCURVE('',#184961,#185051); +#185051 = DEFINITIONAL_REPRESENTATION('',(#185052),#185056); +#185052 = LINE('',#185053,#185054); +#185053 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#185054 = VECTOR('',#185055,1.); +#185055 = DIRECTION('',(1.,0.E+000)); +#185056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185057 = PCURVE('',#184906,#185058); +#185058 = DEFINITIONAL_REPRESENTATION('',(#185059),#185063); +#185059 = LINE('',#185060,#185061); +#185060 = CARTESIAN_POINT('',(-16.05000092,-16.10000082)); +#185061 = VECTOR('',#185062,1.); +#185062 = DIRECTION('',(0.E+000,1.)); +#185063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185064 = ADVANCED_FACE('',(#185065),#184824,.F.); +#185065 = FACE_BOUND('',#185066,.F.); +#185066 = EDGE_LOOP('',(#185067,#185068,#185089,#185090)); +#185067 = ORIENTED_EDGE('',*,*,#185021,.T.); +#185068 = ORIENTED_EDGE('',*,*,#185069,.T.); +#185069 = EDGE_CURVE('',#184999,#184804,#185070,.T.); +#185070 = SURFACE_CURVE('',#185071,(#185075,#185082),.PCURVE_S1.); +#185071 = LINE('',#185072,#185073); +#185072 = CARTESIAN_POINT('',(8.02500046,7.94999934,1.9)); +#185073 = VECTOR('',#185074,1.); +#185074 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); +#185075 = PCURVE('',#184824,#185076); +#185076 = DEFINITIONAL_REPRESENTATION('',(#185077),#185081); +#185077 = LINE('',#185078,#185079); +#185078 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#185079 = VECTOR('',#185080,1.); +#185080 = DIRECTION('',(1.,0.E+000)); +#185081 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185082 = PCURVE('',#184852,#185083); +#185083 = DEFINITIONAL_REPRESENTATION('',(#185084),#185088); +#185084 = LINE('',#185085,#185086); +#185085 = CARTESIAN_POINT('',(-16.05000092,-0.10000234)); +#185086 = VECTOR('',#185087,1.); +#185087 = DIRECTION('',(0.999980589909,6.230554094296E-003)); +#185088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#182719 = ADVANCED_FACE('',(#182720),#182514,.T.); -#182720 = FACE_BOUND('',#182721,.F.); -#182721 = EDGE_LOOP('',(#182722,#182723,#182724,#182725)); -#182722 = ORIENTED_EDGE('',*,*,#182500,.T.); -#182723 = ORIENTED_EDGE('',*,*,#182581,.T.); -#182724 = ORIENTED_EDGE('',*,*,#182652,.T.); -#182725 = ORIENTED_EDGE('',*,*,#182699,.T.); -#182726 = ADVANCED_FACE('',(#182727),#182460,.F.); -#182727 = FACE_BOUND('',#182728,.T.); -#182728 = EDGE_LOOP('',(#182729,#182730,#182731,#182732)); -#182729 = ORIENTED_EDGE('',*,*,#182444,.T.); -#182730 = ORIENTED_EDGE('',*,*,#182530,.T.); -#182731 = ORIENTED_EDGE('',*,*,#182606,.T.); -#182732 = ORIENTED_EDGE('',*,*,#182677,.T.); -#182733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182737)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182734,#182735,#182736)) +#185089 = ORIENTED_EDGE('',*,*,#184801,.F.); +#185090 = ORIENTED_EDGE('',*,*,#185091,.F.); +#185091 = EDGE_CURVE('',#185022,#184802,#185092,.T.); +#185092 = SURFACE_CURVE('',#185093,(#185097,#185104),.PCURVE_S1.); +#185093 = LINE('',#185094,#185095); +#185094 = CARTESIAN_POINT('',(8.02500046,7.94999934,0.E+000)); +#185095 = VECTOR('',#185096,1.); +#185096 = DIRECTION('',(-0.999980589909,6.230554094296E-003,0.E+000)); +#185097 = PCURVE('',#184824,#185098); +#185098 = DEFINITIONAL_REPRESENTATION('',(#185099),#185103); +#185099 = LINE('',#185100,#185101); +#185100 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#185101 = VECTOR('',#185102,1.); +#185102 = DIRECTION('',(1.,0.E+000)); +#185103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185104 = PCURVE('',#184906,#185105); +#185105 = DEFINITIONAL_REPRESENTATION('',(#185106),#185110); +#185106 = LINE('',#185107,#185108); +#185107 = CARTESIAN_POINT('',(-16.05000092,-0.10000234)); +#185108 = VECTOR('',#185109,1.); +#185109 = DIRECTION('',(0.999980589909,6.230554094296E-003)); +#185110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185111 = ADVANCED_FACE('',(#185112),#184906,.T.); +#185112 = FACE_BOUND('',#185113,.F.); +#185113 = EDGE_LOOP('',(#185114,#185115,#185116,#185117)); +#185114 = ORIENTED_EDGE('',*,*,#184892,.T.); +#185115 = ORIENTED_EDGE('',*,*,#184973,.T.); +#185116 = ORIENTED_EDGE('',*,*,#185044,.T.); +#185117 = ORIENTED_EDGE('',*,*,#185091,.T.); +#185118 = ADVANCED_FACE('',(#185119),#184852,.F.); +#185119 = FACE_BOUND('',#185120,.T.); +#185120 = EDGE_LOOP('',(#185121,#185122,#185123,#185124)); +#185121 = ORIENTED_EDGE('',*,*,#184836,.T.); +#185122 = ORIENTED_EDGE('',*,*,#184922,.T.); +#185123 = ORIENTED_EDGE('',*,*,#184998,.T.); +#185124 = ORIENTED_EDGE('',*,*,#185069,.T.); +#185125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185129)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185126,#185127,#185128)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182734 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182735 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182736 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182737 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182734, +#185126 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185127 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185128 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185129 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185126, 'distance_accuracy_value','confusion accuracy'); -#182738 = SHAPE_DEFINITION_REPRESENTATION(#182739,#182402); -#182739 = PRODUCT_DEFINITION_SHAPE('','',#182740); -#182740 = PRODUCT_DEFINITION('design','',#182741,#182744); -#182741 = PRODUCT_DEFINITION_FORMATION('','',#182742); -#182742 = PRODUCT('Extruded','Extruded','',(#182743)); -#182743 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182744 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182745 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182746,#182748); -#182746 = ( REPRESENTATION_RELATIONSHIP('','',#182402,#182392) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182747) +#185130 = SHAPE_DEFINITION_REPRESENTATION(#185131,#184794); +#185131 = PRODUCT_DEFINITION_SHAPE('','',#185132); +#185132 = PRODUCT_DEFINITION('design','',#185133,#185136); +#185133 = PRODUCT_DEFINITION_FORMATION('','',#185134); +#185134 = PRODUCT('Extruded','Extruded','',(#185135)); +#185135 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185136 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185137 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185138,#185140); +#185138 = ( REPRESENTATION_RELATIONSHIP('','',#184794,#184784) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185139) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182747 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182393); -#182748 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182749); -#182749 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('310','=>[0:1:1:2]','',#182387, - #182740,$); -#182750 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182742)); -#182751 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182752,#182754); -#182752 = ( REPRESENTATION_RELATIONSHIP('','',#182392,#182375) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182753) +#185139 = ITEM_DEFINED_TRANSFORMATION('','',#11,#184785); +#185140 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185141); +#185141 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('411','=>[0:1:1:2]','',#184779, + #185132,$); +#185142 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185134)); +#185143 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185144,#185146); +#185144 = ( REPRESENTATION_RELATIONSHIP('','',#184784,#184767) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185145) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182753 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182376); -#182754 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182755); -#182755 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('311','=>[0:1:1:109]','', - #182370,#182387,$); -#182756 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182389)); -#182757 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182758,#182760); -#182758 = ( REPRESENTATION_RELATIONSHIP('','',#182375,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182759) +#185145 = ITEM_DEFINED_TRANSFORMATION('','',#11,#184768); +#185146 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185147); +#185147 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('412','=>[0:1:1:109]','', + #184762,#184779,$); +#185148 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#184781)); +#185149 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185150,#185152); +#185150 = ( REPRESENTATION_RELATIONSHIP('','',#184767,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185151) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182759 = ITEM_DEFINED_TRANSFORMATION('','',#11,#287); -#182760 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182761); -#182761 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('312','=>[0:1:1:108]','',#5, - #182370,$); -#182762 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182372)); -#182763 = SHAPE_DEFINITION_REPRESENTATION(#182764,#182770); -#182764 = PRODUCT_DEFINITION_SHAPE('','',#182765); -#182765 = PRODUCT_DEFINITION('design','',#182766,#182769); -#182766 = PRODUCT_DEFINITION_FORMATION('','',#182767); -#182767 = PRODUCT('R15','R15','',(#182768)); -#182768 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182769 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182770 = SHAPE_REPRESENTATION('',(#11,#182771),#182775); -#182771 = AXIS2_PLACEMENT_3D('',#182772,#182773,#182774); -#182772 = CARTESIAN_POINT('',(27.813,32.26199796,-2.25298)); -#182773 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#182774 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182775 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182779)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182776,#182777,#182778)) +#185151 = ITEM_DEFINED_TRANSFORMATION('','',#11,#287); +#185152 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185153); +#185153 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('413','=>[0:1:1:108]','',#5, + #184762,$); +#185154 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#184764)); +#185155 = SHAPE_DEFINITION_REPRESENTATION(#185156,#185162); +#185156 = PRODUCT_DEFINITION_SHAPE('','',#185157); +#185157 = PRODUCT_DEFINITION('design','',#185158,#185161); +#185158 = PRODUCT_DEFINITION_FORMATION('','',#185159); +#185159 = PRODUCT('R15','R15','',(#185160)); +#185160 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185161 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185162 = SHAPE_REPRESENTATION('',(#11,#185163),#185167); +#185163 = AXIS2_PLACEMENT_3D('',#185164,#185165,#185166); +#185164 = CARTESIAN_POINT('',(27.813,32.26199796,-1.6637)); +#185165 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#185166 = DIRECTION('',(1.,0.E+000,0.E+000)); +#185167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185171)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185168,#185169,#185170)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182776 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182777 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182778 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182779 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182776, +#185168 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185169 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185170 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185171 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185168, 'distance_accuracy_value','confusion accuracy'); -#182780 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182781,#182783); -#182781 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#182770) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182782) +#185172 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185173,#185175); +#185173 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#185162) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185174) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182782 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182771); -#182783 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182784); -#182784 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('313','=>[0:1:1:7]','',#182765, - #7462,$); -#182785 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182786,#182788); -#182786 = ( REPRESENTATION_RELATIONSHIP('','',#182770,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182787) +#185174 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185163); +#185175 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185176); +#185176 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('414','=>[0:1:1:7]','',#185157, + #9854,$); +#185177 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185178,#185180); +#185178 = ( REPRESENTATION_RELATIONSHIP('','',#185162,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185179) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182787 = ITEM_DEFINED_TRANSFORMATION('','',#11,#291); -#182788 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182789); -#182789 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('314','=>[0:1:1:111]','',#5, - #182765,$); -#182790 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182767)); -#182791 = SHAPE_DEFINITION_REPRESENTATION(#182792,#182798); -#182792 = PRODUCT_DEFINITION_SHAPE('','',#182793); -#182793 = PRODUCT_DEFINITION('design','',#182794,#182797); -#182794 = PRODUCT_DEFINITION_FORMATION('','',#182795); -#182795 = PRODUCT('R17','R17','',(#182796)); -#182796 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182797 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182798 = SHAPE_REPRESENTATION('',(#11,#182799),#182803); -#182799 = AXIS2_PLACEMENT_3D('',#182800,#182801,#182802); -#182800 = CARTESIAN_POINT('',(24.257,32.2620005,-2.25298)); -#182801 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#182802 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182807)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182804,#182805,#182806)) +#185179 = ITEM_DEFINED_TRANSFORMATION('','',#11,#291); +#185180 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185181); +#185181 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('415','=>[0:1:1:111]','',#5, + #185157,$); +#185182 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185159)); +#185183 = SHAPE_DEFINITION_REPRESENTATION(#185184,#185190); +#185184 = PRODUCT_DEFINITION_SHAPE('','',#185185); +#185185 = PRODUCT_DEFINITION('design','',#185186,#185189); +#185186 = PRODUCT_DEFINITION_FORMATION('','',#185187); +#185187 = PRODUCT('R17','R17','',(#185188)); +#185188 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185189 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185190 = SHAPE_REPRESENTATION('',(#11,#185191),#185195); +#185191 = AXIS2_PLACEMENT_3D('',#185192,#185193,#185194); +#185192 = CARTESIAN_POINT('',(24.257,32.2620005,-1.6637)); +#185193 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#185194 = DIRECTION('',(1.,0.E+000,0.E+000)); +#185195 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185199)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185196,#185197,#185198)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182804 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182805 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182806 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182807 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182804, +#185196 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185197 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185198 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185199 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185196, 'distance_accuracy_value','confusion accuracy'); -#182808 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182809,#182811); -#182809 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#182798) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182810) +#185200 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185201,#185203); +#185201 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#185190) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185202) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182810 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182799); -#182811 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182812); -#182812 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('315','=>[0:1:1:7]','',#182793, - #7462,$); -#182813 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182814,#182816); -#182814 = ( REPRESENTATION_RELATIONSHIP('','',#182798,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182815) +#185202 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185191); +#185203 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185204); +#185204 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('416','=>[0:1:1:7]','',#185185, + #9854,$); +#185205 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185206,#185208); +#185206 = ( REPRESENTATION_RELATIONSHIP('','',#185190,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185207) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182815 = ITEM_DEFINED_TRANSFORMATION('','',#11,#295); -#182816 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182817); -#182817 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('316','=>[0:1:1:112]','',#5, - #182793,$); -#182818 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182795)); -#182819 = SHAPE_DEFINITION_REPRESENTATION(#182820,#182826); -#182820 = PRODUCT_DEFINITION_SHAPE('','',#182821); -#182821 = PRODUCT_DEFINITION('design','',#182822,#182825); -#182822 = PRODUCT_DEFINITION_FORMATION('','',#182823); -#182823 = PRODUCT('R18','R18','',(#182824)); -#182824 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182825 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182826 = SHAPE_REPRESENTATION('',(#11,#182827),#182831); -#182827 = AXIS2_PLACEMENT_3D('',#182828,#182829,#182830); -#182828 = CARTESIAN_POINT('',(6.1000005,17.653,-1.27E-002)); -#182829 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182830 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#182831 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182835)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182832,#182833,#182834)) +#185207 = ITEM_DEFINED_TRANSFORMATION('','',#11,#295); +#185208 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185209); +#185209 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('417','=>[0:1:1:112]','',#5, + #185185,$); +#185210 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185187)); +#185211 = SHAPE_DEFINITION_REPRESENTATION(#185212,#185218); +#185212 = PRODUCT_DEFINITION_SHAPE('','',#185213); +#185213 = PRODUCT_DEFINITION('design','',#185214,#185217); +#185214 = PRODUCT_DEFINITION_FORMATION('','',#185215); +#185215 = PRODUCT('R18','R18','',(#185216)); +#185216 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185217 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185218 = SHAPE_REPRESENTATION('',(#11,#185219),#185223); +#185219 = AXIS2_PLACEMENT_3D('',#185220,#185221,#185222); +#185220 = CARTESIAN_POINT('',(6.1000005,17.653,-1.27E-002)); +#185221 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185222 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#185223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185227)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185224,#185225,#185226)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182832 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182833 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182834 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182835 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182832, +#185224 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185225 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185226 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185227 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185224, 'distance_accuracy_value','confusion accuracy'); -#182836 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182837,#182839); -#182837 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#182826) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182838) +#185228 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185229,#185231); +#185229 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#185218) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185230) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182838 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182827); -#182839 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182840); -#182840 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('317','=>[0:1:1:7]','',#182821, - #7462,$); -#182841 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182842,#182844); -#182842 = ( REPRESENTATION_RELATIONSHIP('','',#182826,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182843) +#185230 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185219); +#185231 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185232); +#185232 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('418','=>[0:1:1:7]','',#185213, + #9854,$); +#185233 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185234,#185236); +#185234 = ( REPRESENTATION_RELATIONSHIP('','',#185218,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185235) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182843 = ITEM_DEFINED_TRANSFORMATION('','',#11,#299); -#182844 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182845); -#182845 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('318','=>[0:1:1:113]','',#5, - #182821,$); -#182846 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182823)); -#182847 = SHAPE_DEFINITION_REPRESENTATION(#182848,#182854); -#182848 = PRODUCT_DEFINITION_SHAPE('','',#182849); -#182849 = PRODUCT_DEFINITION('design','',#182850,#182853); -#182850 = PRODUCT_DEFINITION_FORMATION('','',#182851); -#182851 = PRODUCT('D5','D5','',(#182852)); -#182852 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182853 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182854 = SHAPE_REPRESENTATION('',(#11,#182855),#182859); -#182855 = AXIS2_PLACEMENT_3D('',#182856,#182857,#182858); -#182856 = CARTESIAN_POINT('',(17.3858428,4.04644098,1.27E-002)); -#182857 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182858 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); -#182859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182863)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182860,#182861,#182862)) +#185235 = ITEM_DEFINED_TRANSFORMATION('','',#11,#299); +#185236 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185237); +#185237 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('419','=>[0:1:1:113]','',#5, + #185213,$); +#185238 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185215)); +#185239 = SHAPE_DEFINITION_REPRESENTATION(#185240,#185246); +#185240 = PRODUCT_DEFINITION_SHAPE('','',#185241); +#185241 = PRODUCT_DEFINITION('design','',#185242,#185245); +#185242 = PRODUCT_DEFINITION_FORMATION('','',#185243); +#185243 = PRODUCT('D5','D5','',(#185244)); +#185244 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185245 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185246 = SHAPE_REPRESENTATION('',(#11,#185247),#185251); +#185247 = AXIS2_PLACEMENT_3D('',#185248,#185249,#185250); +#185248 = CARTESIAN_POINT('',(17.3858428,4.04644098,1.27E-002)); +#185249 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185250 = DIRECTION('',(1.,-2.449212707645E-016,0.E+000)); +#185251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185255)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185252,#185253,#185254)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182860 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182861 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182862 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182863 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182860, +#185252 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185253 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185254 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185255 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185252, 'distance_accuracy_value','confusion accuracy'); -#182864 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182865,#182867); -#182865 = ( REPRESENTATION_RELATIONSHIP('','',#7524,#182854) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182866) +#185256 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185257,#185259); +#185257 = ( REPRESENTATION_RELATIONSHIP('','',#9916,#185246) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185258) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182866 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182855); -#182867 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182868); -#182868 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('319','=>[0:1:1:10]','',#182849 - ,#11023,$); -#182869 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182870,#182872); -#182870 = ( REPRESENTATION_RELATIONSHIP('','',#182854,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182871) +#185258 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185247); +#185259 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185260); +#185260 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('420','=>[0:1:1:10]','',#185241 + ,#13415,$); +#185261 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185262,#185264); +#185262 = ( REPRESENTATION_RELATIONSHIP('','',#185246,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185263) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182871 = ITEM_DEFINED_TRANSFORMATION('','',#11,#303); -#182872 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182873); -#182873 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('320','=>[0:1:1:114]','',#5, - #182849,$); -#182874 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182851)); -#182875 = SHAPE_DEFINITION_REPRESENTATION(#182876,#182882); -#182876 = PRODUCT_DEFINITION_SHAPE('','',#182877); -#182877 = PRODUCT_DEFINITION('design','',#182878,#182881); -#182878 = PRODUCT_DEFINITION_FORMATION('','',#182879); -#182879 = PRODUCT('R19','R19','',(#182880)); -#182880 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182881 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182882 = SHAPE_REPRESENTATION('',(#11,#182883),#182887); -#182883 = AXIS2_PLACEMENT_3D('',#182884,#182885,#182886); -#182884 = CARTESIAN_POINT('',(18.8000005,6.35,-1.27E-002)); -#182885 = DIRECTION('',(0.E+000,0.E+000,1.)); -#182886 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); -#182887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182891)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182888,#182889,#182890)) +#185263 = ITEM_DEFINED_TRANSFORMATION('','',#11,#303); +#185264 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185265); +#185265 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('421','=>[0:1:1:114]','',#5, + #185241,$); +#185266 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185243)); +#185267 = SHAPE_DEFINITION_REPRESENTATION(#185268,#185274); +#185268 = PRODUCT_DEFINITION_SHAPE('','',#185269); +#185269 = PRODUCT_DEFINITION('design','',#185270,#185273); +#185270 = PRODUCT_DEFINITION_FORMATION('','',#185271); +#185271 = PRODUCT('R19','R19','',(#185272)); +#185272 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185273 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185274 = SHAPE_REPRESENTATION('',(#11,#185275),#185279); +#185275 = AXIS2_PLACEMENT_3D('',#185276,#185277,#185278); +#185276 = CARTESIAN_POINT('',(18.8000005,6.35,-1.27E-002)); +#185277 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185278 = DIRECTION('',(1.110223024625E-016,1.,0.E+000)); +#185279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185283)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185280,#185281,#185282)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182888 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182889 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182890 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182891 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182888, +#185280 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185281 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185282 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185283 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185280, 'distance_accuracy_value','confusion accuracy'); -#182892 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182893,#182895); -#182893 = ( REPRESENTATION_RELATIONSHIP('','',#5072,#182882) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182894) +#185284 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185285,#185287); +#185285 = ( REPRESENTATION_RELATIONSHIP('','',#7464,#185274) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185286) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182894 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182883); -#182895 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182896); -#182896 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('321','=>[0:1:1:7]','',#182877, - #7462,$); -#182897 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182898,#182900); -#182898 = ( REPRESENTATION_RELATIONSHIP('','',#182882,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182899) +#185286 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185275); +#185287 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185288); +#185288 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('422','=>[0:1:1:7]','',#185269, + #9854,$); +#185289 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185290,#185292); +#185290 = ( REPRESENTATION_RELATIONSHIP('','',#185274,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185291) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182899 = ITEM_DEFINED_TRANSFORMATION('','',#11,#307); -#182900 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182901); -#182901 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('322','=>[0:1:1:115]','',#5, - #182877,$); -#182902 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182879)); -#182903 = SHAPE_DEFINITION_REPRESENTATION(#182904,#182910); -#182904 = PRODUCT_DEFINITION_SHAPE('','',#182905); -#182905 = PRODUCT_DEFINITION('design','',#182906,#182909); -#182906 = PRODUCT_DEFINITION_FORMATION('','',#182907); -#182907 = PRODUCT('CONN6','CONN6','',(#182908)); -#182908 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182909 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182910 = SHAPE_REPRESENTATION('',(#11,#182911),#182915); -#182911 = AXIS2_PLACEMENT_3D('',#182912,#182913,#182914); -#182912 = CARTESIAN_POINT('',(4.5300011,25.019,-1.94818)); -#182913 = DIRECTION('',(-1.,-2.22044604925E-016,-1.110223024625E-016)); -#182914 = DIRECTION('',(-2.22044604925E-016,1.,-1.224606353822E-016)); -#182915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182919)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182916,#182917,#182918)) +#185291 = ITEM_DEFINED_TRANSFORMATION('','',#11,#307); +#185292 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185293); +#185293 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('423','=>[0:1:1:115]','',#5, + #185269,$); +#185294 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185271)); +#185295 = SHAPE_DEFINITION_REPRESENTATION(#185296,#185302); +#185296 = PRODUCT_DEFINITION_SHAPE('','',#185297); +#185297 = PRODUCT_DEFINITION('design','',#185298,#185301); +#185298 = PRODUCT_DEFINITION_FORMATION('','',#185299); +#185299 = PRODUCT('CONN6','CONN6','',(#185300)); +#185300 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185301 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185302 = SHAPE_REPRESENTATION('',(#11,#185303),#185307); +#185303 = AXIS2_PLACEMENT_3D('',#185304,#185305,#185306); +#185304 = CARTESIAN_POINT('',(4.5300011,25.019,-1.3589)); +#185305 = DIRECTION('',(-1.,-2.22044604925E-016,-1.110223024625E-016)); +#185306 = DIRECTION('',(-2.22044604925E-016,1.,-1.224606353822E-016)); +#185307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185311)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185308,#185309,#185310)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182916 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182917 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182918 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182919 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#182916, +#185308 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185309 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185310 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185311 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#185308, 'distance_accuracy_value','confusion accuracy'); -#182920 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182921,#182923); -#182921 = ( REPRESENTATION_RELATIONSHIP('','',#22038,#182910) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182922) +#185312 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185313,#185315); +#185313 = ( REPRESENTATION_RELATIONSHIP('','',#24430,#185302) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185314) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182922 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182911); -#182923 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182924); -#182924 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('323','=>[0:1:1:31]','',#182905 - ,#28462,$); -#182925 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#182926,#182928); -#182926 = ( REPRESENTATION_RELATIONSHIP('','',#182910,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#182927) +#185314 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185303); +#185315 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185316); +#185316 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('424','=>[0:1:1:31]','',#185297 + ,#30854,$); +#185317 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#185318,#185320); +#185318 = ( REPRESENTATION_RELATIONSHIP('','',#185302,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#185319) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#182927 = ITEM_DEFINED_TRANSFORMATION('','',#11,#311); -#182928 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #182929); -#182929 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('324','=>[0:1:1:116]','',#5, - #182905,$); -#182930 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182907)); -#182931 = SHAPE_DEFINITION_REPRESENTATION(#182932,#182938); -#182932 = PRODUCT_DEFINITION_SHAPE('','',#182933); -#182933 = PRODUCT_DEFINITION('design','',#182934,#182937); -#182934 = PRODUCT_DEFINITION_FORMATION('','',#182935); -#182935 = PRODUCT('Q1','Q1','',(#182936)); -#182936 = PRODUCT_CONTEXT('',#2,'mechanical'); -#182937 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#182938 = SHAPE_REPRESENTATION('',(#11,#182939),#182943); -#182939 = AXIS2_PLACEMENT_3D('',#182940,#182941,#182942); -#182940 = CARTESIAN_POINT('',(7.874,8.382,-2.27838)); -#182941 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#182942 = DIRECTION('',(1.,0.E+000,0.E+000)); -#182943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#182947)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#182944,#182945,#182946)) +#185319 = ITEM_DEFINED_TRANSFORMATION('','',#11,#311); +#185320 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #185321); +#185321 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('425','=>[0:1:1:116]','',#5, + #185297,$); +#185322 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185299)); +#185323 = SHAPE_DEFINITION_REPRESENTATION(#185324,#185330); +#185324 = PRODUCT_DEFINITION_SHAPE('','',#185325); +#185325 = PRODUCT_DEFINITION('design','',#185326,#185329); +#185326 = PRODUCT_DEFINITION_FORMATION('','',#185327); +#185327 = PRODUCT('Q1','Q1','',(#185328)); +#185328 = PRODUCT_CONTEXT('',#2,'mechanical'); +#185329 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#185330 = SHAPE_REPRESENTATION('',(#11,#185331),#185335); +#185331 = AXIS2_PLACEMENT_3D('',#185332,#185333,#185334); +#185332 = CARTESIAN_POINT('',(7.874,8.382,-1.6891)); +#185333 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#185334 = DIRECTION('',(1.,0.E+000,0.E+000)); +#185335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#185339)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#185336,#185337,#185338)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#182944 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#182945 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#182946 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#182947 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#182944, +#185336 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#185337 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#185338 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#185339 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#185336, 'distance_accuracy_value','confusion accuracy'); -#182948 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#182949),#194570); -#182949 = MANIFOLD_SOLID_BREP('',#182950); -#182950 = CLOSED_SHELL('',(#182951,#183231,#183506,#183781,#184056, - #184359,#184634,#184909,#185184,#185336,#185803,#186247,#186416, - #186609,#186755,#186925,#187246,#187358,#187493,#187861,#187936, - #188011,#188265,#188484,#188510,#188536,#188585,#188612,#188639, - #188688,#188714,#188740,#188747,#188822,#188897,#189151,#189370, - #189396,#189422,#189471,#189498,#189525,#189574,#189600,#189626, - #189633,#189708,#189989,#190037,#190256,#190282,#190308,#190357, - #190384,#190411,#190460,#190486,#190512,#190519,#190594,#190875, - #190923,#191142,#191168,#191194,#191243,#191270,#191297,#191346, - #191372,#191398,#191405,#191480,#191761,#192002,#192047,#192073, - #192122,#192149,#192176,#192225,#192251,#192277,#192284,#192291, - #192366,#192647,#192888,#192914,#192940,#192989,#193016,#193043, - #193092,#193118,#193144,#193170,#193177,#193315,#193388,#193526, - #193599,#193737,#193810,#193948,#194021,#194071,#194076,#194125, - #194132,#194181,#194230,#194237,#194244,#194293,#194300,#194349, - #194421,#194428,#194435,#194484,#194556,#194563)); -#182951 = ADVANCED_FACE('',(#182952),#182967,.T.); -#182952 = FACE_BOUND('',#182953,.T.); -#182953 = EDGE_LOOP('',(#182954,#183025,#183110,#183183)); -#182954 = ORIENTED_EDGE('',*,*,#182955,.F.); -#182955 = EDGE_CURVE('',#182956,#182958,#182960,.T.); -#182956 = VERTEX_POINT('',#182957); -#182957 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#182958 = VERTEX_POINT('',#182959); -#182959 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#182960 = SURFACE_CURVE('',#182961,(#182966,#183012),.PCURVE_S1.); -#182961 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#182962,#182963,#182964, -#182965),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#185340 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#185341),#196962); +#185341 = MANIFOLD_SOLID_BREP('',#185342); +#185342 = CLOSED_SHELL('',(#185343,#185623,#185898,#186173,#186448, + #186751,#187026,#187301,#187576,#187728,#188195,#188639,#188808, + #189001,#189147,#189317,#189638,#189750,#189885,#190253,#190328, + #190403,#190657,#190876,#190902,#190928,#190977,#191004,#191031, + #191080,#191106,#191132,#191139,#191214,#191289,#191543,#191762, + #191788,#191814,#191863,#191890,#191917,#191966,#191992,#192018, + #192025,#192100,#192381,#192429,#192648,#192674,#192700,#192749, + #192776,#192803,#192852,#192878,#192904,#192911,#192986,#193267, + #193315,#193534,#193560,#193586,#193635,#193662,#193689,#193738, + #193764,#193790,#193797,#193872,#194153,#194394,#194439,#194465, + #194514,#194541,#194568,#194617,#194643,#194669,#194676,#194683, + #194758,#195039,#195280,#195306,#195332,#195381,#195408,#195435, + #195484,#195510,#195536,#195562,#195569,#195707,#195780,#195918, + #195991,#196129,#196202,#196340,#196413,#196463,#196468,#196517, + #196524,#196573,#196622,#196629,#196636,#196685,#196692,#196741, + #196813,#196820,#196827,#196876,#196948,#196955)); +#185343 = ADVANCED_FACE('',(#185344),#185359,.T.); +#185344 = FACE_BOUND('',#185345,.T.); +#185345 = EDGE_LOOP('',(#185346,#185417,#185502,#185575)); +#185346 = ORIENTED_EDGE('',*,*,#185347,.F.); +#185347 = EDGE_CURVE('',#185348,#185350,#185352,.T.); +#185348 = VERTEX_POINT('',#185349); +#185349 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#185350 = VERTEX_POINT('',#185351); +#185351 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#185352 = SURFACE_CURVE('',#185353,(#185358,#185404),.PCURVE_S1.); +#185353 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185354,#185355,#185356, +#185357),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#182962 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#182963 = CARTESIAN_POINT('',(1.241596067115,-0.46790129499,1.E-001)); -#182964 = CARTESIAN_POINT('',(1.217584046027,-0.477659054385,1.E-001)); -#182965 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#182966 = PCURVE('',#182967,#182984); -#182967 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#182968,#182969,#182970,#182971) - ,(#182972,#182973,#182974,#182975) - ,(#182976,#182977,#182978,#182979) - ,(#182980,#182981,#182982,#182983 +#185354 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#185355 = CARTESIAN_POINT('',(1.241596067115,-0.46790129499,1.E-001)); +#185356 = CARTESIAN_POINT('',(1.217584046027,-0.477659054385,1.E-001)); +#185357 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#185358 = PCURVE('',#185359,#185376); +#185359 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#185360,#185361,#185362,#185363) + ,(#185364,#185365,#185366,#185367) + ,(#185368,#185369,#185370,#185371) + ,(#185372,#185373,#185374,#185375 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#182968 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); -#182969 = CARTESIAN_POINT('',(1.191066471757,-0.499475670035,1.E-001)); -#182970 = CARTESIAN_POINT('',(1.191066471757,-0.52030879007, +#185360 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,1.E-001)); +#185361 = CARTESIAN_POINT('',(1.191066471757,-0.499475670035,1.E-001)); +#185362 = CARTESIAN_POINT('',(1.191066471757,-0.52030879007, 0.115985815246)); -#182971 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, +#185363 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, 0.137059047745)); -#182972 = CARTESIAN_POINT('',(1.21695495248,-0.477659054385,1.E-001)); -#182973 = CARTESIAN_POINT('',(1.222435083194,-0.498429042165,1.E-001)); -#182974 = CARTESIAN_POINT('',(1.227668168966,-0.518443665671, +#185364 = CARTESIAN_POINT('',(1.21695495248,-0.477659054385,1.E-001)); +#185365 = CARTESIAN_POINT('',(1.222435083194,-0.498429042165,1.E-001)); +#185366 = CARTESIAN_POINT('',(1.227668168966,-0.518443665671, 0.114318476015)); -#182975 = CARTESIAN_POINT('',(1.229086531164,-0.525142684022, +#185367 = CARTESIAN_POINT('',(1.229086531164,-0.525142684022, 0.134026153074)); -#182976 = CARTESIAN_POINT('',(1.242026713303,-0.467470648802,1.E-001)); -#182977 = CARTESIAN_POINT('',(1.252452511959,-0.485531311073,1.E-001)); -#182978 = CARTESIAN_POINT('',(1.262532596412,-0.50299309093, +#185368 = CARTESIAN_POINT('',(1.242026713303,-0.467470648802,1.E-001)); +#185369 = CARTESIAN_POINT('',(1.252452511959,-0.485531311073,1.E-001)); +#185370 = CARTESIAN_POINT('',(1.262532596412,-0.50299309093, 0.113446578632)); -#182979 = CARTESIAN_POINT('',(1.266226971076,-0.509392874324,0.132282534 +#185371 = CARTESIAN_POINT('',(1.266226971076,-0.509392874324,0.132282534 )); -#182980 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#182981 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); -#182982 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, +#185372 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#185373 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); +#185374 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, 0.113446578632)); -#182983 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#182984 = DEFINITIONAL_REPRESENTATION('',(#182985),#183011); -#182985 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#182986,#182987,#182988, - #182989,#182990,#182991,#182992,#182993,#182994,#182995,#182996, - #182997,#182998,#182999,#183000,#183001,#183002,#183003,#183004, - #183005,#183006,#183007,#183008,#183009,#183010),.UNSPECIFIED.,.F., +#185375 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#185376 = DEFINITIONAL_REPRESENTATION('',(#185377),#185403); +#185377 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185378,#185379,#185380, + #185381,#185382,#185383,#185384,#185385,#185386,#185387,#185388, + #185389,#185390,#185391,#185392,#185393,#185394,#185395,#185396, + #185397,#185398,#185399,#185400,#185401,#185402),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 8.809142651445E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -226693,69 +229695,69 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#182986 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#182987 = CARTESIAN_POINT('',(6.272059569215,1.375318786182E-008)); -#182988 = CARTESIAN_POINT('',(6.24973263213,2.924134010748E-005)); -#182989 = CARTESIAN_POINT('',(6.21603939964,1.4137075777E-004)); -#182990 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); -#182991 = CARTESIAN_POINT('',(6.148138870073,4.93149846864E-004)); -#182992 = CARTESIAN_POINT('',(6.113975913115,6.962198987687E-004)); -#182993 = CARTESIAN_POINT('',(6.079699188623,8.953387637315E-004)); -#182994 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); -#182995 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); -#182996 = CARTESIAN_POINT('',(5.976382533559,1.33926347788E-003)); -#182997 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); -#182998 = CARTESIAN_POINT('',(5.907285653264,1.422641316496E-003)); -#182999 = CARTESIAN_POINT('',(5.87272580864,1.390009812367E-003)); -#183000 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); -#183001 = CARTESIAN_POINT('',(5.803674042174,1.187353930381E-003)); -#183002 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); -#183003 = CARTESIAN_POINT('',(5.734837892756,8.475624467434E-004)); -#183004 = CARTESIAN_POINT('',(5.700549707253,6.520952931825E-004)); -#183005 = CARTESIAN_POINT('',(5.666375694827,4.570658043145E-004)); -#183006 = CARTESIAN_POINT('',(5.632337541793,2.772530388755E-004)); -#183007 = CARTESIAN_POINT('',(5.598457782919,1.282673134885E-004)); -#183008 = CARTESIAN_POINT('',(5.564759695218,2.616756246979E-005)); -#183009 = CARTESIAN_POINT('',(5.542431609433,-2.901324312813E-008)); -#183010 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183012 = PCURVE('',#183013,#183018); -#183013 = PLANE('',#183014); -#183014 = AXIS2_PLACEMENT_3D('',#183015,#183016,#183017); -#183015 = CARTESIAN_POINT('',(1.46,-0.65,1.E-001)); -#183016 = DIRECTION('',(0.E+000,0.E+000,1.)); -#183017 = DIRECTION('',(1.,0.E+000,0.E+000)); -#183018 = DEFINITIONAL_REPRESENTATION('',(#183019),#183024); -#183019 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183020,#183021,#183022, -#183023),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#185378 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185379 = CARTESIAN_POINT('',(6.272059569215,1.375318786182E-008)); +#185380 = CARTESIAN_POINT('',(6.24973263213,2.924134010748E-005)); +#185381 = CARTESIAN_POINT('',(6.21603939964,1.4137075777E-004)); +#185382 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); +#185383 = CARTESIAN_POINT('',(6.148138870073,4.93149846864E-004)); +#185384 = CARTESIAN_POINT('',(6.113975913115,6.962198987687E-004)); +#185385 = CARTESIAN_POINT('',(6.079699188623,8.953387637315E-004)); +#185386 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); +#185387 = CARTESIAN_POINT('',(6.010883543172,1.22739025448E-003)); +#185388 = CARTESIAN_POINT('',(5.976382533559,1.33926347788E-003)); +#185389 = CARTESIAN_POINT('',(5.941843890817,1.405524714328E-003)); +#185390 = CARTESIAN_POINT('',(5.907285653264,1.422641316496E-003)); +#185391 = CARTESIAN_POINT('',(5.87272580864,1.390009812367E-003)); +#185392 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); +#185393 = CARTESIAN_POINT('',(5.803674042174,1.187353930381E-003)); +#185394 = CARTESIAN_POINT('',(5.769219374506,1.029943289552E-003)); +#185395 = CARTESIAN_POINT('',(5.734837892756,8.475624467434E-004)); +#185396 = CARTESIAN_POINT('',(5.700549707253,6.520952931825E-004)); +#185397 = CARTESIAN_POINT('',(5.666375694827,4.570658043145E-004)); +#185398 = CARTESIAN_POINT('',(5.632337541793,2.772530388755E-004)); +#185399 = CARTESIAN_POINT('',(5.598457782919,1.282673134885E-004)); +#185400 = CARTESIAN_POINT('',(5.564759695218,2.616756246979E-005)); +#185401 = CARTESIAN_POINT('',(5.542431609433,-2.901324312813E-008)); +#185402 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#185403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185404 = PCURVE('',#185405,#185410); +#185405 = PLANE('',#185406); +#185406 = AXIS2_PLACEMENT_3D('',#185407,#185408,#185409); +#185407 = CARTESIAN_POINT('',(1.46,-0.65,1.E-001)); +#185408 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185409 = DIRECTION('',(1.,0.E+000,0.E+000)); +#185410 = DEFINITIONAL_REPRESENTATION('',(#185411),#185416); +#185411 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185412,#185413,#185414, +#185415),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183020 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#183021 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); -#183022 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); -#183023 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); -#183024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183025 = ORIENTED_EDGE('',*,*,#183026,.T.); -#183026 = EDGE_CURVE('',#182956,#183027,#183029,.T.); -#183027 = VERTEX_POINT('',#183028); -#183028 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#183029 = SURFACE_CURVE('',#183030,(#183035,#183064),.PCURVE_S1.); -#183030 = CIRCLE('',#183031,5.E-002); -#183031 = AXIS2_PLACEMENT_3D('',#183032,#183033,#183034); -#183032 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,0.15)); -#183033 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#183034 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#183035 = PCURVE('',#182967,#183036); -#183036 = DEFINITIONAL_REPRESENTATION('',(#183037),#183063); -#183037 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183038,#183039,#183040, - #183041,#183042,#183043,#183044,#183045,#183046,#183047,#183048, - #183049,#183050,#183051,#183052,#183053,#183054,#183055,#183056, - #183057,#183058,#183059,#183060,#183061,#183062),.UNSPECIFIED.,.F., +#185412 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#185413 = CARTESIAN_POINT('',(-0.218403932885,0.18209870501)); +#185414 = CARTESIAN_POINT('',(-0.242415953973,0.172340945615)); +#185415 = CARTESIAN_POINT('',(-0.268933528243,0.172340945615)); +#185416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185417 = ORIENTED_EDGE('',*,*,#185418,.T.); +#185418 = EDGE_CURVE('',#185348,#185419,#185421,.T.); +#185419 = VERTEX_POINT('',#185420); +#185420 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#185421 = SURFACE_CURVE('',#185422,(#185427,#185456),.PCURVE_S1.); +#185422 = CIRCLE('',#185423,5.E-002); +#185423 = AXIS2_PLACEMENT_3D('',#185424,#185425,#185426); +#185424 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,0.15)); +#185425 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#185426 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#185427 = PCURVE('',#185359,#185428); +#185428 = DEFINITIONAL_REPRESENTATION('',(#185429),#185455); +#185429 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185430,#185431,#185432, + #185433,#185434,#185435,#185436,#185437,#185438,#185439,#185440, + #185441,#185442,#185443,#185444,#185445,#185446,#185447,#185448, + #185449,#185450,#185451,#185452,#185453,#185454),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -226763,70 +229765,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183038 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183039 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#183040 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#183041 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#183042 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#183043 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#183044 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#183045 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#183046 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#183047 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#183048 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#183049 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#183050 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#183051 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#183052 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#183053 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#183054 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#183055 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#183056 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#183057 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#183058 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#183059 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#183060 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#183061 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#183062 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183064 = PCURVE('',#183065,#183082); -#183065 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183066,#183067,#183068,#183069) - ,(#183070,#183071,#183072,#183073) - ,(#183074,#183075,#183076,#183077) - ,(#183078,#183079,#183080,#183081 +#185430 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185431 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#185432 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#185433 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#185434 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#185435 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#185436 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#185437 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#185438 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#185439 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#185440 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#185441 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#185442 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#185443 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#185444 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#185445 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#185446 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#185447 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#185448 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#185449 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#185450 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#185451 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#185452 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#185453 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#185454 = CARTESIAN_POINT('',(6.28318530718,1.)); +#185455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185456 = PCURVE('',#185457,#185474); +#185457 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#185458,#185459,#185460,#185461) + ,(#185462,#185463,#185464,#185465) + ,(#185466,#185467,#185468,#185469) + ,(#185470,#185471,#185472,#185473 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183066 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#183067 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); -#183068 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, +#185458 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#185459 = CARTESIAN_POINT('',(1.273991911516,-0.463991911516,1.E-001)); +#185460 = CARTESIAN_POINT('',(1.287762843671,-0.477762843671, 0.113446578632)); -#183069 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#183070 = CARTESIAN_POINT('',(1.277470648802,-0.432026713303,1.E-001)); -#183071 = CARTESIAN_POINT('',(1.295531311073,-0.442452511959,1.E-001)); -#183072 = CARTESIAN_POINT('',(1.31299309093,-0.452532596412, +#185461 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#185462 = CARTESIAN_POINT('',(1.277470648802,-0.432026713303,1.E-001)); +#185463 = CARTESIAN_POINT('',(1.295531311073,-0.442452511959,1.E-001)); +#185464 = CARTESIAN_POINT('',(1.31299309093,-0.452532596412, 0.113446578632)); -#183073 = CARTESIAN_POINT('',(1.319392874324,-0.456226971076,0.132282534 +#185465 = CARTESIAN_POINT('',(1.319392874324,-0.456226971076,0.132282534 )); -#183074 = CARTESIAN_POINT('',(1.287659054385,-0.40695495248,1.E-001)); -#183075 = CARTESIAN_POINT('',(1.308429042165,-0.412435083194,1.E-001)); -#183076 = CARTESIAN_POINT('',(1.328443665671,-0.417668168966, +#185466 = CARTESIAN_POINT('',(1.287659054385,-0.40695495248,1.E-001)); +#185467 = CARTESIAN_POINT('',(1.308429042165,-0.412435083194,1.E-001)); +#185468 = CARTESIAN_POINT('',(1.328443665671,-0.417668168966, 0.114318476015)); -#183077 = CARTESIAN_POINT('',(1.335142684022,-0.419086531164, +#185469 = CARTESIAN_POINT('',(1.335142684022,-0.419086531164, 0.134026153074)); -#183078 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#183079 = CARTESIAN_POINT('',(1.309475670035,-0.381066471757,1.E-001)); -#183080 = CARTESIAN_POINT('',(1.33030879007,-0.381066471757, +#185470 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#185471 = CARTESIAN_POINT('',(1.309475670035,-0.381066471757,1.E-001)); +#185472 = CARTESIAN_POINT('',(1.33030879007,-0.381066471757, 0.115985815246)); -#183081 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, +#185473 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, 0.137059047745)); -#183082 = DEFINITIONAL_REPRESENTATION('',(#183083),#183109); -#183083 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183084,#183085,#183086, - #183087,#183088,#183089,#183090,#183091,#183092,#183093,#183094, - #183095,#183096,#183097,#183098,#183099,#183100,#183101,#183102, - #183103,#183104,#183105,#183106,#183107,#183108),.UNSPECIFIED.,.F., +#185474 = DEFINITIONAL_REPRESENTATION('',(#185475),#185501); +#185475 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185476,#185477,#185478, + #185479,#185480,#185481,#185482,#185483,#185484,#185485,#185486, + #185487,#185488,#185489,#185490,#185491,#185492,#185493,#185494, + #185495,#185496,#185497,#185498,#185499,#185500),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -226834,60 +229836,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183084 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#183085 = CARTESIAN_POINT('',(-1.144439603192E-015,1.515278164504E-002) - ); -#183086 = CARTESIAN_POINT('',(-9.175368395657E-016,4.549920749135E-002) - ); -#183087 = CARTESIAN_POINT('',(1.372925320255E-016,9.109101074357E-002)); -#183088 = CARTESIAN_POINT('',(5.6159890698E-016,0.136698748187)); -#183089 = CARTESIAN_POINT('',(-1.545422737611E-015,0.1822865144)); -#183090 = CARTESIAN_POINT('',(-1.348585819112E-015,0.2278300409)); -#183091 = CARTESIAN_POINT('',(3.786426572017E-016,0.27331674602)); -#183092 = CARTESIAN_POINT('',(-3.253009613166E-016,0.318743220066)); -#183093 = CARTESIAN_POINT('',(-7.297245182018E-016,0.364113426255)); -#183094 = CARTESIAN_POINT('',(1.988956429665E-015,0.409436881051)); -#183095 = CARTESIAN_POINT('',(-6.120609827186E-016,0.454727066523)); -#183096 = CARTESIAN_POINT('',(-1.685236759928E-015,0.5)); -#183097 = CARTESIAN_POINT('',(1.855627463945E-015,0.545272933477)); -#183098 = CARTESIAN_POINT('',(-2.167943843688E-015,0.590563118949)); -#183099 = CARTESIAN_POINT('',(2.303008870842E-016,0.635886573745)); -#183100 = CARTESIAN_POINT('',(-3.217601376884E-017,0.681256779934)); -#183101 = CARTESIAN_POINT('',(5.276053820311E-016,0.72668325398)); -#183102 = CARTESIAN_POINT('',(-1.216399179866E-015,0.7721699591)); -#183103 = CARTESIAN_POINT('',(4.872508256886E-016,0.8177134856)); -#183104 = CARTESIAN_POINT('',(-1.155567275167E-015,0.863301251813)); -#183105 = CARTESIAN_POINT('',(6.923566871284E-016,0.908908989256)); -#183106 = CARTESIAN_POINT('',(-1.695305503108E-015,0.954500792509)); -#183107 = CARTESIAN_POINT('',(-1.701205294602E-015,0.984847218355)); -#183108 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#183109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183110 = ORIENTED_EDGE('',*,*,#183111,.F.); -#183111 = EDGE_CURVE('',#183112,#183027,#183114,.T.); -#183112 = VERTEX_POINT('',#183113); -#183113 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, +#185476 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#185477 = CARTESIAN_POINT('',(-1.144439603192E-015,1.515278164504E-002) + ); +#185478 = CARTESIAN_POINT('',(-9.175368395657E-016,4.549920749135E-002) + ); +#185479 = CARTESIAN_POINT('',(1.372925320255E-016,9.109101074357E-002)); +#185480 = CARTESIAN_POINT('',(5.6159890698E-016,0.136698748187)); +#185481 = CARTESIAN_POINT('',(-1.545422737611E-015,0.1822865144)); +#185482 = CARTESIAN_POINT('',(-1.348585819112E-015,0.2278300409)); +#185483 = CARTESIAN_POINT('',(3.786426572017E-016,0.27331674602)); +#185484 = CARTESIAN_POINT('',(-3.253009613166E-016,0.318743220066)); +#185485 = CARTESIAN_POINT('',(-7.297245182018E-016,0.364113426255)); +#185486 = CARTESIAN_POINT('',(1.988956429665E-015,0.409436881051)); +#185487 = CARTESIAN_POINT('',(-6.120609827186E-016,0.454727066523)); +#185488 = CARTESIAN_POINT('',(-1.685236759928E-015,0.5)); +#185489 = CARTESIAN_POINT('',(1.855627463945E-015,0.545272933477)); +#185490 = CARTESIAN_POINT('',(-2.167943843688E-015,0.590563118949)); +#185491 = CARTESIAN_POINT('',(2.303008870842E-016,0.635886573745)); +#185492 = CARTESIAN_POINT('',(-3.217601376884E-017,0.681256779934)); +#185493 = CARTESIAN_POINT('',(5.276053820311E-016,0.72668325398)); +#185494 = CARTESIAN_POINT('',(-1.216399179866E-015,0.7721699591)); +#185495 = CARTESIAN_POINT('',(4.872508256886E-016,0.8177134856)); +#185496 = CARTESIAN_POINT('',(-1.155567275167E-015,0.863301251813)); +#185497 = CARTESIAN_POINT('',(6.923566871284E-016,0.908908989256)); +#185498 = CARTESIAN_POINT('',(-1.695305503108E-015,0.954500792509)); +#185499 = CARTESIAN_POINT('',(-1.701205294602E-015,0.984847218355)); +#185500 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#185501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185502 = ORIENTED_EDGE('',*,*,#185503,.F.); +#185503 = EDGE_CURVE('',#185504,#185419,#185506,.T.); +#185504 = VERTEX_POINT('',#185505); +#185505 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, 0.137059047745)); -#183114 = SURFACE_CURVE('',#183115,(#183120,#183149),.PCURVE_S1.); -#183115 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183116,#183117,#183118, -#183119),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#185506 = SURFACE_CURVE('',#185507,(#185512,#185541),.PCURVE_S1.); +#185507 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185508,#185509,#185510, +#185511),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183116 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, +#185508 = CARTESIAN_POINT('',(1.191066471757,-0.5259553457, 0.137059047745)); -#183117 = CARTESIAN_POINT('',(1.230010423697,-0.525122936235, +#185509 = CARTESIAN_POINT('',(1.230010423697,-0.525122936235, 0.133952453327)); -#183118 = CARTESIAN_POINT('',(1.265581001793,-0.510038843607,0.132282534 +#185510 = CARTESIAN_POINT('',(1.265581001793,-0.510038843607,0.132282534 )); -#183119 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#183120 = PCURVE('',#182967,#183121); -#183121 = DEFINITIONAL_REPRESENTATION('',(#183122),#183148); -#183122 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183123,#183124,#183125, - #183126,#183127,#183128,#183129,#183130,#183131,#183132,#183133, - #183134,#183135,#183136,#183137,#183138,#183139,#183140,#183141, - #183142,#183143,#183144,#183145,#183146,#183147),.UNSPECIFIED.,.F., +#185511 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#185512 = PCURVE('',#185359,#185513); +#185513 = DEFINITIONAL_REPRESENTATION('',(#185514),#185540); +#185514 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185515,#185516,#185517, + #185518,#185519,#185520,#185521,#185522,#185523,#185524,#185525, + #185526,#185527,#185528,#185529,#185530,#185531,#185532,#185533, + #185534,#185535,#185536,#185537,#185538,#185539),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -226895,47 +229897,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183123 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183124 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); -#183125 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); -#183126 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); -#183127 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); -#183128 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); -#183129 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); -#183130 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); -#183131 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#183132 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#183133 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#183134 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#183135 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#183136 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#183137 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#183138 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#183139 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#183140 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#183141 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#183142 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#183143 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#183144 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#183145 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#183146 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#183147 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183148 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183149 = PCURVE('',#183150,#183155); -#183150 = CYLINDRICAL_SURFACE('',#183151,0.15); -#183151 = AXIS2_PLACEMENT_3D('',#183152,#183153,#183154); -#183152 = CARTESIAN_POINT('',(1.140884875554,-0.330884875554, +#185515 = CARTESIAN_POINT('',(5.531305892885,1.)); +#185516 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); +#185517 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); +#185518 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); +#185519 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); +#185520 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); +#185521 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); +#185522 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); +#185523 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#185524 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#185525 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#185526 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#185527 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#185528 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#185529 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#185530 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#185531 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#185532 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#185533 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#185534 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#185535 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#185536 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#185537 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#185538 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#185539 = CARTESIAN_POINT('',(6.28318530718,1.)); +#185540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185541 = PCURVE('',#185542,#185547); +#185542 = CYLINDRICAL_SURFACE('',#185543,0.15); +#185543 = AXIS2_PLACEMENT_3D('',#185544,#185545,#185546); +#185544 = CARTESIAN_POINT('',(1.140884875554,-0.330884875554, -1.13983621231E-002)); -#183153 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#183154 = DIRECTION('',(0.965925826289,5.263462734238E-017, +#185545 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#185546 = DIRECTION('',(0.965925826289,5.263462734238E-017, -0.258819045103)); -#183155 = DEFINITIONAL_REPRESENTATION('',(#183156),#183182); -#183156 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183157,#183158,#183159, - #183160,#183161,#183162,#183163,#183164,#183165,#183166,#183167, - #183168,#183169,#183170,#183171,#183172,#183173,#183174,#183175, - #183176,#183177,#183178,#183179,#183180,#183181),.UNSPECIFIED.,.F., +#185547 = DEFINITIONAL_REPRESENTATION('',(#185548),#185574); +#185548 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185549,#185550,#185551, + #185552,#185553,#185554,#185555,#185556,#185557,#185558,#185559, + #185560,#185561,#185562,#185563,#185564,#185565,#185566,#185567, + #185568,#185569,#185570,#185571,#185572,#185573),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -226943,48 +229945,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183157 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); -#183158 = CARTESIAN_POINT('',(4.790552085824,0.200563476544)); -#183159 = CARTESIAN_POINT('',(4.812874135705,0.201130925764)); -#183160 = CARTESIAN_POINT('',(4.846552114392,0.201954800758)); -#183161 = CARTESIAN_POINT('',(4.880407630888,0.202749452758)); -#183162 = CARTESIAN_POINT('',(4.914422492066,0.203513040252)); -#183163 = CARTESIAN_POINT('',(4.948578027862,0.204243791819)); -#183164 = CARTESIAN_POINT('',(4.98285506838,0.204940025039)); -#183165 = CARTESIAN_POINT('',(5.017234026195,0.205600156427)); -#183166 = CARTESIAN_POINT('',(5.051694955172,0.206222712991)); -#183167 = CARTESIAN_POINT('',(5.086217619636,0.206806342405)); -#183168 = CARTESIAN_POINT('',(5.120781564146,0.207349822399)); -#183169 = CARTESIAN_POINT('',(5.155366185737,0.207852069041)); -#183170 = CARTESIAN_POINT('',(5.189950807328,0.208312143851)); -#183171 = CARTESIAN_POINT('',(5.224514751839,0.208729259627)); -#183172 = CARTESIAN_POINT('',(5.259037416303,0.209102784922)); -#183173 = CARTESIAN_POINT('',(5.293498345279,0.209432247104)); -#183174 = CARTESIAN_POINT('',(5.327877303094,0.209717334008)); -#183175 = CARTESIAN_POINT('',(5.362154343612,0.209957894032)); -#183176 = CARTESIAN_POINT('',(5.396309879408,0.210153935227)); -#183177 = CARTESIAN_POINT('',(5.430324740587,0.210305621442)); -#183178 = CARTESIAN_POINT('',(5.464180257082,0.21041327299)); -#183179 = CARTESIAN_POINT('',(5.49785823577,0.210477344272)); -#183180 = CARTESIAN_POINT('',(5.52018028565,0.210491435842)); -#183181 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); -#183182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183183 = ORIENTED_EDGE('',*,*,#183184,.T.); -#183184 = EDGE_CURVE('',#183112,#182958,#183185,.T.); -#183185 = SURFACE_CURVE('',#183186,(#183191,#183220),.PCURVE_S1.); -#183186 = CIRCLE('',#183187,5.E-002); -#183187 = AXIS2_PLACEMENT_3D('',#183188,#183189,#183190); -#183188 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,0.15)); -#183189 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); -#183190 = DIRECTION('',(-4.336808689942E-015,3.735199373413E-045,-1.)); -#183191 = PCURVE('',#182967,#183192); -#183192 = DEFINITIONAL_REPRESENTATION('',(#183193),#183219); -#183193 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183194,#183195,#183196, - #183197,#183198,#183199,#183200,#183201,#183202,#183203,#183204, - #183205,#183206,#183207,#183208,#183209,#183210,#183211,#183212, - #183213,#183214,#183215,#183216,#183217,#183218),.UNSPECIFIED.,.F., +#185549 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); +#185550 = CARTESIAN_POINT('',(4.790552085824,0.200563476544)); +#185551 = CARTESIAN_POINT('',(4.812874135705,0.201130925764)); +#185552 = CARTESIAN_POINT('',(4.846552114392,0.201954800758)); +#185553 = CARTESIAN_POINT('',(4.880407630888,0.202749452758)); +#185554 = CARTESIAN_POINT('',(4.914422492066,0.203513040252)); +#185555 = CARTESIAN_POINT('',(4.948578027862,0.204243791819)); +#185556 = CARTESIAN_POINT('',(4.98285506838,0.204940025039)); +#185557 = CARTESIAN_POINT('',(5.017234026195,0.205600156427)); +#185558 = CARTESIAN_POINT('',(5.051694955172,0.206222712991)); +#185559 = CARTESIAN_POINT('',(5.086217619636,0.206806342405)); +#185560 = CARTESIAN_POINT('',(5.120781564146,0.207349822399)); +#185561 = CARTESIAN_POINT('',(5.155366185737,0.207852069041)); +#185562 = CARTESIAN_POINT('',(5.189950807328,0.208312143851)); +#185563 = CARTESIAN_POINT('',(5.224514751839,0.208729259627)); +#185564 = CARTESIAN_POINT('',(5.259037416303,0.209102784922)); +#185565 = CARTESIAN_POINT('',(5.293498345279,0.209432247104)); +#185566 = CARTESIAN_POINT('',(5.327877303094,0.209717334008)); +#185567 = CARTESIAN_POINT('',(5.362154343612,0.209957894032)); +#185568 = CARTESIAN_POINT('',(5.396309879408,0.210153935227)); +#185569 = CARTESIAN_POINT('',(5.430324740587,0.210305621442)); +#185570 = CARTESIAN_POINT('',(5.464180257082,0.21041327299)); +#185571 = CARTESIAN_POINT('',(5.49785823577,0.210477344272)); +#185572 = CARTESIAN_POINT('',(5.52018028565,0.210491435842)); +#185573 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); +#185574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185575 = ORIENTED_EDGE('',*,*,#185576,.T.); +#185576 = EDGE_CURVE('',#185504,#185350,#185577,.T.); +#185577 = SURFACE_CURVE('',#185578,(#185583,#185612),.PCURVE_S1.); +#185578 = CIRCLE('',#185579,5.E-002); +#185579 = AXIS2_PLACEMENT_3D('',#185580,#185581,#185582); +#185580 = CARTESIAN_POINT('',(1.191066471757,-0.477659054385,0.15)); +#185581 = DIRECTION('',(1.,1.162044386198E-015,-4.336808689942E-015)); +#185582 = DIRECTION('',(-4.336808689942E-015,3.735199373413E-045,-1.)); +#185583 = PCURVE('',#185359,#185584); +#185584 = DEFINITIONAL_REPRESENTATION('',(#185585),#185611); +#185585 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185586,#185587,#185588, + #185589,#185590,#185591,#185592,#185593,#185594,#185595,#185596, + #185597,#185598,#185599,#185600,#185601,#185602,#185603,#185604, + #185605,#185606,#185607,#185608,#185609,#185610),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -226992,104 +229994,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183194 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183195 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#183196 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#183197 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#183198 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#183199 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#183200 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#183201 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#183202 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#183203 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#183204 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#183205 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#183206 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#183207 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#183208 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#183209 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#183210 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#183211 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#183212 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#183213 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#183214 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#183215 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#183216 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#183217 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#183218 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183219 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183220 = PCURVE('',#183221,#183226); -#183221 = CYLINDRICAL_SURFACE('',#183222,5.E-002); -#183222 = AXIS2_PLACEMENT_3D('',#183223,#183224,#183225); -#183223 = CARTESIAN_POINT('',(-1.46,-0.477659054385,0.15)); -#183224 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#183225 = DIRECTION('',(0.E+000,0.E+000,1.)); -#183226 = DEFINITIONAL_REPRESENTATION('',(#183227),#183230); -#183227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183228,#183229), +#185586 = CARTESIAN_POINT('',(5.531305892885,1.)); +#185587 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#185588 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#185589 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#185590 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#185591 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#185592 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#185593 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#185594 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#185595 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#185596 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#185597 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#185598 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#185599 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#185600 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#185601 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#185602 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#185603 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#185604 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#185605 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#185606 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#185607 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#185608 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#185609 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#185610 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#185611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185612 = PCURVE('',#185613,#185618); +#185613 = CYLINDRICAL_SURFACE('',#185614,5.E-002); +#185614 = AXIS2_PLACEMENT_3D('',#185615,#185616,#185617); +#185615 = CARTESIAN_POINT('',(-1.46,-0.477659054385,0.15)); +#185616 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#185617 = DIRECTION('',(0.E+000,0.E+000,1.)); +#185618 = DEFINITIONAL_REPRESENTATION('',(#185619),#185622); +#185619 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185620,#185621), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#183228 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); -#183229 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); -#183230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183231 = ADVANCED_FACE('',(#183232),#183247,.T.); -#183232 = FACE_BOUND('',#183233,.T.); -#183233 = EDGE_LOOP('',(#183234,#183300,#183385,#183458)); -#183234 = ORIENTED_EDGE('',*,*,#183235,.F.); -#183235 = EDGE_CURVE('',#183236,#183238,#183240,.T.); -#183236 = VERTEX_POINT('',#183237); -#183237 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#183238 = VERTEX_POINT('',#183239); -#183239 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#183240 = SURFACE_CURVE('',#183241,(#183246,#183292),.PCURVE_S1.); -#183241 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183242,#183243,#183244, -#183245),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#185620 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); +#185621 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); +#185622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185623 = ADVANCED_FACE('',(#185624),#185639,.T.); +#185624 = FACE_BOUND('',#185625,.T.); +#185625 = EDGE_LOOP('',(#185626,#185692,#185777,#185850)); +#185626 = ORIENTED_EDGE('',*,*,#185627,.F.); +#185627 = EDGE_CURVE('',#185628,#185630,#185632,.T.); +#185628 = VERTEX_POINT('',#185629); +#185629 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#185630 = VERTEX_POINT('',#185631); +#185631 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#185632 = SURFACE_CURVE('',#185633,(#185638,#185684),.PCURVE_S1.); +#185633 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185634,#185635,#185636, +#185637),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183242 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#183243 = CARTESIAN_POINT('',(-1.27790129499,-0.431596067115,1.E-001)); -#183244 = CARTESIAN_POINT('',(-1.287659054385,-0.407584046027,1.E-001)); -#183245 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#183246 = PCURVE('',#183247,#183264); -#183247 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183248,#183249,#183250,#183251) - ,(#183252,#183253,#183254,#183255) - ,(#183256,#183257,#183258,#183259) - ,(#183260,#183261,#183262,#183263 +#185634 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#185635 = CARTESIAN_POINT('',(-1.27790129499,-0.431596067115,1.E-001)); +#185636 = CARTESIAN_POINT('',(-1.287659054385,-0.407584046027,1.E-001)); +#185637 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#185638 = PCURVE('',#185639,#185656); +#185639 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#185640,#185641,#185642,#185643) + ,(#185644,#185645,#185646,#185647) + ,(#185648,#185649,#185650,#185651) + ,(#185652,#185653,#185654,#185655 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183248 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); -#183249 = CARTESIAN_POINT('',(-1.309475670035,-0.381066471757,1.E-001)); -#183250 = CARTESIAN_POINT('',(-1.33030879007,-0.381066471757, +#185640 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,1.E-001)); +#185641 = CARTESIAN_POINT('',(-1.309475670035,-0.381066471757,1.E-001)); +#185642 = CARTESIAN_POINT('',(-1.33030879007,-0.381066471757, 0.115985815246)); -#183251 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#185643 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#183252 = CARTESIAN_POINT('',(-1.287659054385,-0.40695495248,1.E-001)); -#183253 = CARTESIAN_POINT('',(-1.308429042165,-0.412435083194,1.E-001)); -#183254 = CARTESIAN_POINT('',(-1.328443665671,-0.417668168966, +#185644 = CARTESIAN_POINT('',(-1.287659054385,-0.40695495248,1.E-001)); +#185645 = CARTESIAN_POINT('',(-1.308429042165,-0.412435083194,1.E-001)); +#185646 = CARTESIAN_POINT('',(-1.328443665671,-0.417668168966, 0.114318476015)); -#183255 = CARTESIAN_POINT('',(-1.335142684022,-0.419086531164, +#185647 = CARTESIAN_POINT('',(-1.335142684022,-0.419086531164, 0.134026153074)); -#183256 = CARTESIAN_POINT('',(-1.277470648802,-0.432026713303,1.E-001)); -#183257 = CARTESIAN_POINT('',(-1.295531311073,-0.442452511959,1.E-001)); -#183258 = CARTESIAN_POINT('',(-1.31299309093,-0.452532596412, +#185648 = CARTESIAN_POINT('',(-1.277470648802,-0.432026713303,1.E-001)); +#185649 = CARTESIAN_POINT('',(-1.295531311073,-0.442452511959,1.E-001)); +#185650 = CARTESIAN_POINT('',(-1.31299309093,-0.452532596412, 0.113446578632)); -#183259 = CARTESIAN_POINT('',(-1.319392874324,-0.456226971076, +#185651 = CARTESIAN_POINT('',(-1.319392874324,-0.456226971076, 0.132282534)); -#183260 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#183261 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); -#183262 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, +#185652 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#185653 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); +#185654 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, 0.113446578632)); -#183263 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#183264 = DEFINITIONAL_REPRESENTATION('',(#183265),#183291); -#183265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183266,#183267,#183268, - #183269,#183270,#183271,#183272,#183273,#183274,#183275,#183276, - #183277,#183278,#183279,#183280,#183281,#183282,#183283,#183284, - #183285,#183286,#183287,#183288,#183289,#183290),.UNSPECIFIED.,.F., +#185655 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#185656 = DEFINITIONAL_REPRESENTATION('',(#185657),#185683); +#185657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185658,#185659,#185660, + #185661,#185662,#185663,#185664,#185665,#185666,#185667,#185668, + #185669,#185670,#185671,#185672,#185673,#185674,#185675,#185676, + #185677,#185678,#185679,#185680,#185681,#185682),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -227097,64 +230099,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#183266 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183267 = CARTESIAN_POINT('',(6.272059569215,1.375318524705E-008)); -#183268 = CARTESIAN_POINT('',(6.24973263213,2.924134010322E-005)); -#183269 = CARTESIAN_POINT('',(6.21603939964,1.413707577683E-004)); -#183270 = CARTESIAN_POINT('',(6.182167276026,3.02285926994E-004)); -#183271 = CARTESIAN_POINT('',(6.148138870073,4.931498468587E-004)); -#183272 = CARTESIAN_POINT('',(6.113975913115,6.962198987668E-004)); -#183273 = CARTESIAN_POINT('',(6.079699188623,8.953387637366E-004)); -#183274 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); -#183275 = CARTESIAN_POINT('',(6.010883543172,1.227390254484E-003)); -#183276 = CARTESIAN_POINT('',(5.976382533559,1.339263477876E-003)); -#183277 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); -#183278 = CARTESIAN_POINT('',(5.907285653264,1.422641316502E-003)); -#183279 = CARTESIAN_POINT('',(5.87272580864,1.390009812359E-003)); -#183280 = CARTESIAN_POINT('',(5.838182469936,1.309904867194E-003)); -#183281 = CARTESIAN_POINT('',(5.803674042174,1.187353930373E-003)); -#183282 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); -#183283 = CARTESIAN_POINT('',(5.734837892756,8.475624467463E-004)); -#183284 = CARTESIAN_POINT('',(5.700549707253,6.520952931822E-004)); -#183285 = CARTESIAN_POINT('',(5.666375694827,4.570658043163E-004)); -#183286 = CARTESIAN_POINT('',(5.632337541793,2.772530388765E-004)); -#183287 = CARTESIAN_POINT('',(5.598457782919,1.282673134888E-004)); -#183288 = CARTESIAN_POINT('',(5.564759695218,2.616756247326E-005)); -#183289 = CARTESIAN_POINT('',(5.542431609433,-2.901324085024E-008)); -#183290 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183292 = PCURVE('',#183013,#183293); -#183293 = DEFINITIONAL_REPRESENTATION('',(#183294),#183299); -#183294 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183295,#183296,#183297, -#183298),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#185658 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185659 = CARTESIAN_POINT('',(6.272059569215,1.375318524705E-008)); +#185660 = CARTESIAN_POINT('',(6.24973263213,2.924134010322E-005)); +#185661 = CARTESIAN_POINT('',(6.21603939964,1.413707577683E-004)); +#185662 = CARTESIAN_POINT('',(6.182167276026,3.02285926994E-004)); +#185663 = CARTESIAN_POINT('',(6.148138870073,4.931498468587E-004)); +#185664 = CARTESIAN_POINT('',(6.113975913115,6.962198987668E-004)); +#185665 = CARTESIAN_POINT('',(6.079699188623,8.953387637366E-004)); +#185666 = CARTESIAN_POINT('',(6.045328652128,1.076339414002E-003)); +#185667 = CARTESIAN_POINT('',(6.010883543172,1.227390254484E-003)); +#185668 = CARTESIAN_POINT('',(5.976382533559,1.339263477876E-003)); +#185669 = CARTESIAN_POINT('',(5.941843890817,1.405524714329E-003)); +#185670 = CARTESIAN_POINT('',(5.907285653264,1.422641316502E-003)); +#185671 = CARTESIAN_POINT('',(5.87272580864,1.390009812359E-003)); +#185672 = CARTESIAN_POINT('',(5.838182469936,1.309904867194E-003)); +#185673 = CARTESIAN_POINT('',(5.803674042174,1.187353930373E-003)); +#185674 = CARTESIAN_POINT('',(5.769219374506,1.029943289554E-003)); +#185675 = CARTESIAN_POINT('',(5.734837892756,8.475624467463E-004)); +#185676 = CARTESIAN_POINT('',(5.700549707253,6.520952931822E-004)); +#185677 = CARTESIAN_POINT('',(5.666375694827,4.570658043163E-004)); +#185678 = CARTESIAN_POINT('',(5.632337541793,2.772530388765E-004)); +#185679 = CARTESIAN_POINT('',(5.598457782919,1.282673134888E-004)); +#185680 = CARTESIAN_POINT('',(5.564759695218,2.616756247326E-005)); +#185681 = CARTESIAN_POINT('',(5.542431609433,-2.901324085024E-008)); +#185682 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#185683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185684 = PCURVE('',#185405,#185685); +#185685 = DEFINITIONAL_REPRESENTATION('',(#185686),#185691); +#185686 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185687,#185688,#185689, +#185690),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183295 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); -#183296 = CARTESIAN_POINT('',(-2.73790129499,0.218403932885)); -#183297 = CARTESIAN_POINT('',(-2.747659054385,0.242415953973)); -#183298 = CARTESIAN_POINT('',(-2.747659054385,0.268933528243)); -#183299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183300 = ORIENTED_EDGE('',*,*,#183301,.T.); -#183301 = EDGE_CURVE('',#183236,#183302,#183304,.T.); -#183302 = VERTEX_POINT('',#183303); -#183303 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#183304 = SURFACE_CURVE('',#183305,(#183310,#183339),.PCURVE_S1.); -#183305 = CIRCLE('',#183306,5.E-002); -#183306 = AXIS2_PLACEMENT_3D('',#183307,#183308,#183309); -#183307 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,0.15)); -#183308 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#183309 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#183310 = PCURVE('',#183247,#183311); -#183311 = DEFINITIONAL_REPRESENTATION('',(#183312),#183338); -#183312 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183313,#183314,#183315, - #183316,#183317,#183318,#183319,#183320,#183321,#183322,#183323, - #183324,#183325,#183326,#183327,#183328,#183329,#183330,#183331, - #183332,#183333,#183334,#183335,#183336,#183337),.UNSPECIFIED.,.F., +#185687 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); +#185688 = CARTESIAN_POINT('',(-2.73790129499,0.218403932885)); +#185689 = CARTESIAN_POINT('',(-2.747659054385,0.242415953973)); +#185690 = CARTESIAN_POINT('',(-2.747659054385,0.268933528243)); +#185691 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185692 = ORIENTED_EDGE('',*,*,#185693,.T.); +#185693 = EDGE_CURVE('',#185628,#185694,#185696,.T.); +#185694 = VERTEX_POINT('',#185695); +#185695 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#185696 = SURFACE_CURVE('',#185697,(#185702,#185731),.PCURVE_S1.); +#185697 = CIRCLE('',#185698,5.E-002); +#185698 = AXIS2_PLACEMENT_3D('',#185699,#185700,#185701); +#185699 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,0.15)); +#185700 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#185701 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#185702 = PCURVE('',#185639,#185703); +#185703 = DEFINITIONAL_REPRESENTATION('',(#185704),#185730); +#185704 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185705,#185706,#185707, + #185708,#185709,#185710,#185711,#185712,#185713,#185714,#185715, + #185716,#185717,#185718,#185719,#185720,#185721,#185722,#185723, + #185724,#185725,#185726,#185727,#185728,#185729),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -227162,70 +230164,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183313 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183314 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#183315 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#183316 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#183317 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#183318 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#183319 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#183320 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#183321 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#183322 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#183323 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#183324 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#183325 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#183326 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#183327 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#183328 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#183329 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#183330 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#183331 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#183332 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#183333 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#183334 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#183335 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#183336 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#183337 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183339 = PCURVE('',#183340,#183357); -#183340 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183341,#183342,#183343,#183344) - ,(#183345,#183346,#183347,#183348) - ,(#183349,#183350,#183351,#183352) - ,(#183353,#183354,#183355,#183356 +#185705 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185706 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#185707 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#185708 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#185709 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#185710 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#185711 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#185712 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#185713 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#185714 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#185715 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#185716 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#185717 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#185718 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#185719 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#185720 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#185721 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#185722 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#185723 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#185724 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#185725 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#185726 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#185727 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#185728 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#185729 = CARTESIAN_POINT('',(6.28318530718,1.)); +#185730 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185731 = PCURVE('',#185732,#185749); +#185732 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#185733,#185734,#185735,#185736) + ,(#185737,#185738,#185739,#185740) + ,(#185741,#185742,#185743,#185744) + ,(#185745,#185746,#185747,#185748 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183341 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#183342 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); -#183343 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, +#185733 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#185734 = CARTESIAN_POINT('',(-1.273991911516,-0.463991911516,1.E-001)); +#185735 = CARTESIAN_POINT('',(-1.287762843671,-0.477762843671, 0.113446578632)); -#183344 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#183345 = CARTESIAN_POINT('',(-1.242026713303,-0.467470648802,1.E-001)); -#183346 = CARTESIAN_POINT('',(-1.252452511959,-0.485531311073,1.E-001)); -#183347 = CARTESIAN_POINT('',(-1.262532596412,-0.50299309093, +#185736 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#185737 = CARTESIAN_POINT('',(-1.242026713303,-0.467470648802,1.E-001)); +#185738 = CARTESIAN_POINT('',(-1.252452511959,-0.485531311073,1.E-001)); +#185739 = CARTESIAN_POINT('',(-1.262532596412,-0.50299309093, 0.113446578632)); -#183348 = CARTESIAN_POINT('',(-1.266226971076,-0.509392874324, +#185740 = CARTESIAN_POINT('',(-1.266226971076,-0.509392874324, 0.132282534)); -#183349 = CARTESIAN_POINT('',(-1.21695495248,-0.477659054385,1.E-001)); -#183350 = CARTESIAN_POINT('',(-1.222435083194,-0.498429042165,1.E-001)); -#183351 = CARTESIAN_POINT('',(-1.227668168966,-0.518443665671, +#185741 = CARTESIAN_POINT('',(-1.21695495248,-0.477659054385,1.E-001)); +#185742 = CARTESIAN_POINT('',(-1.222435083194,-0.498429042165,1.E-001)); +#185743 = CARTESIAN_POINT('',(-1.227668168966,-0.518443665671, 0.114318476015)); -#183352 = CARTESIAN_POINT('',(-1.229086531164,-0.525142684022, +#185744 = CARTESIAN_POINT('',(-1.229086531164,-0.525142684022, 0.134026153074)); -#183353 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#183354 = CARTESIAN_POINT('',(-1.191066471757,-0.499475670035,1.E-001)); -#183355 = CARTESIAN_POINT('',(-1.191066471757,-0.52030879007, +#185745 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#185746 = CARTESIAN_POINT('',(-1.191066471757,-0.499475670035,1.E-001)); +#185747 = CARTESIAN_POINT('',(-1.191066471757,-0.52030879007, 0.115985815246)); -#183356 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#185748 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#183357 = DEFINITIONAL_REPRESENTATION('',(#183358),#183384); -#183358 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183359,#183360,#183361, - #183362,#183363,#183364,#183365,#183366,#183367,#183368,#183369, - #183370,#183371,#183372,#183373,#183374,#183375,#183376,#183377, - #183378,#183379,#183380,#183381,#183382,#183383),.UNSPECIFIED.,.F., +#185749 = DEFINITIONAL_REPRESENTATION('',(#185750),#185776); +#185750 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185751,#185752,#185753, + #185754,#185755,#185756,#185757,#185758,#185759,#185760,#185761, + #185762,#185763,#185764,#185765,#185766,#185767,#185768,#185769, + #185770,#185771,#185772,#185773,#185774,#185775),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -227233,58 +230235,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183359 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#183360 = CARTESIAN_POINT('',(1.249334129403E-015,1.515278164503E-002)); -#183361 = CARTESIAN_POINT('',(1.92028783152E-015,4.549920749134E-002)); -#183362 = CARTESIAN_POINT('',(1.277950380648E-015,9.109101074356E-002)); -#183363 = CARTESIAN_POINT('',(-4.452410912024E-016,0.136698748187)); -#183364 = CARTESIAN_POINT('',(1.63616653244E-015,0.1822865144)); -#183365 = CARTESIAN_POINT('',(1.217038436523E-016,0.2278300409)); -#183366 = CARTESIAN_POINT('',(9.520556691239E-016,0.27331674602)); -#183367 = CARTESIAN_POINT('',(-1.993255720205E-015,0.318743220066)); -#183368 = CARTESIAN_POINT('',(1.941660140614E-015,0.364113426255)); -#183369 = CARTESIAN_POINT('',(-2.507252454051E-015,0.409436881051)); -#183370 = CARTESIAN_POINT('',(9.244817616574E-016,0.454727066523)); -#183371 = CARTESIAN_POINT('',(-2.178843416601E-015,0.5)); -#183372 = CARTESIAN_POINT('',(-1.460413071254E-015,0.545272933477)); -#183373 = CARTESIAN_POINT('',(-2.368640258981E-015,0.590563118949)); -#183374 = CARTESIAN_POINT('',(1.200342950948E-015,0.635886573745)); -#183375 = CARTESIAN_POINT('',(-2.891058446001E-015,0.681256779934)); -#183376 = CARTESIAN_POINT('',(-1.089100273504E-015,0.72668325398)); -#183377 = CARTESIAN_POINT('',(-1.35470191066E-016,0.7721699591)); -#183378 = CARTESIAN_POINT('',(-1.653663396122E-015,0.8177134856)); -#183379 = CARTESIAN_POINT('',(-2.183887769705E-015,0.863301251813)); -#183380 = CARTESIAN_POINT('',(-9.551908994562E-016,0.908908989256)); -#183381 = CARTESIAN_POINT('',(-1.359363333985E-015,0.954500792509)); -#183382 = CARTESIAN_POINT('',(-5.557512487972E-016,0.984847218355)); -#183383 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#183384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183385 = ORIENTED_EDGE('',*,*,#183386,.F.); -#183386 = EDGE_CURVE('',#183387,#183302,#183389,.T.); -#183387 = VERTEX_POINT('',#183388); -#183388 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#185751 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#185752 = CARTESIAN_POINT('',(1.249334129403E-015,1.515278164503E-002)); +#185753 = CARTESIAN_POINT('',(1.92028783152E-015,4.549920749134E-002)); +#185754 = CARTESIAN_POINT('',(1.277950380648E-015,9.109101074356E-002)); +#185755 = CARTESIAN_POINT('',(-4.452410912024E-016,0.136698748187)); +#185756 = CARTESIAN_POINT('',(1.63616653244E-015,0.1822865144)); +#185757 = CARTESIAN_POINT('',(1.217038436523E-016,0.2278300409)); +#185758 = CARTESIAN_POINT('',(9.520556691239E-016,0.27331674602)); +#185759 = CARTESIAN_POINT('',(-1.993255720205E-015,0.318743220066)); +#185760 = CARTESIAN_POINT('',(1.941660140614E-015,0.364113426255)); +#185761 = CARTESIAN_POINT('',(-2.507252454051E-015,0.409436881051)); +#185762 = CARTESIAN_POINT('',(9.244817616574E-016,0.454727066523)); +#185763 = CARTESIAN_POINT('',(-2.178843416601E-015,0.5)); +#185764 = CARTESIAN_POINT('',(-1.460413071254E-015,0.545272933477)); +#185765 = CARTESIAN_POINT('',(-2.368640258981E-015,0.590563118949)); +#185766 = CARTESIAN_POINT('',(1.200342950948E-015,0.635886573745)); +#185767 = CARTESIAN_POINT('',(-2.891058446001E-015,0.681256779934)); +#185768 = CARTESIAN_POINT('',(-1.089100273504E-015,0.72668325398)); +#185769 = CARTESIAN_POINT('',(-1.35470191066E-016,0.7721699591)); +#185770 = CARTESIAN_POINT('',(-1.653663396122E-015,0.8177134856)); +#185771 = CARTESIAN_POINT('',(-2.183887769705E-015,0.863301251813)); +#185772 = CARTESIAN_POINT('',(-9.551908994562E-016,0.908908989256)); +#185773 = CARTESIAN_POINT('',(-1.359363333985E-015,0.954500792509)); +#185774 = CARTESIAN_POINT('',(-5.557512487972E-016,0.984847218355)); +#185775 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#185776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185777 = ORIENTED_EDGE('',*,*,#185778,.F.); +#185778 = EDGE_CURVE('',#185779,#185694,#185781,.T.); +#185779 = VERTEX_POINT('',#185780); +#185780 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#183389 = SURFACE_CURVE('',#183390,(#183395,#183424),.PCURVE_S1.); -#183390 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183391,#183392,#183393, -#183394),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#185781 = SURFACE_CURVE('',#185782,(#185787,#185816),.PCURVE_S1.); +#185782 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185783,#185784,#185785, +#185786),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183391 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, +#185783 = CARTESIAN_POINT('',(-1.3359553457,-0.381066471757, 0.137059047745)); -#183392 = CARTESIAN_POINT('',(-1.335122936235,-0.420010423697, +#185784 = CARTESIAN_POINT('',(-1.335122936235,-0.420010423697, 0.133952453327)); -#183393 = CARTESIAN_POINT('',(-1.320038843607,-0.455581001793, +#185785 = CARTESIAN_POINT('',(-1.320038843607,-0.455581001793, 0.132282534)); -#183394 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#183395 = PCURVE('',#183247,#183396); -#183396 = DEFINITIONAL_REPRESENTATION('',(#183397),#183423); -#183397 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183398,#183399,#183400, - #183401,#183402,#183403,#183404,#183405,#183406,#183407,#183408, - #183409,#183410,#183411,#183412,#183413,#183414,#183415,#183416, - #183417,#183418,#183419,#183420,#183421,#183422),.UNSPECIFIED.,.F., +#185786 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#185787 = PCURVE('',#185639,#185788); +#185788 = DEFINITIONAL_REPRESENTATION('',(#185789),#185815); +#185789 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185790,#185791,#185792, + #185793,#185794,#185795,#185796,#185797,#185798,#185799,#185800, + #185801,#185802,#185803,#185804,#185805,#185806,#185807,#185808, + #185809,#185810,#185811,#185812,#185813,#185814),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -227292,48 +230294,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183398 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183399 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#183400 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#183401 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#183402 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#183403 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#183404 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#183405 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#183406 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#183407 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#183408 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#183409 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#183410 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#183411 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#183412 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#183413 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#183414 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#183415 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#183416 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#183417 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#183418 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#183419 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#183420 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#183421 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#183422 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183423 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183424 = PCURVE('',#183425,#183430); -#183425 = CYLINDRICAL_SURFACE('',#183426,0.15); -#183426 = AXIS2_PLACEMENT_3D('',#183427,#183428,#183429); -#183427 = CARTESIAN_POINT('',(-1.242591262431,-0.432591262431, +#185790 = CARTESIAN_POINT('',(5.531305892885,1.)); +#185791 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#185792 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#185793 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#185794 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#185795 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#185796 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#185797 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#185798 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#185799 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#185800 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#185801 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#185802 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#185803 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#185804 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#185805 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#185806 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#185807 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#185808 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#185809 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#185810 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#185811 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#185812 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#185813 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#185814 = CARTESIAN_POINT('',(6.28318530718,1.)); +#185815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185816 = PCURVE('',#185817,#185822); +#185817 = CYLINDRICAL_SURFACE('',#185818,0.15); +#185818 = AXIS2_PLACEMENT_3D('',#185819,#185820,#185821); +#185819 = CARTESIAN_POINT('',(-1.242591262431,-0.432591262431, 0.368175041158)); -#183428 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) +#185820 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) ); -#183429 = DIRECTION('',(0.965925826289,4.24499031846E-017,0.258819045103 +#185821 = DIRECTION('',(0.965925826289,4.24499031846E-017,0.258819045103 )); -#183430 = DEFINITIONAL_REPRESENTATION('',(#183431),#183457); -#183431 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183432,#183433,#183434, - #183435,#183436,#183437,#183438,#183439,#183440,#183441,#183442, - #183443,#183444,#183445,#183446,#183447,#183448,#183449,#183450, - #183451,#183452,#183453,#183454,#183455,#183456),.UNSPECIFIED.,.F., +#185822 = DEFINITIONAL_REPRESENTATION('',(#185823),#185849); +#185823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185824,#185825,#185826, + #185827,#185828,#185829,#185830,#185831,#185832,#185833,#185834, + #185835,#185836,#185837,#185838,#185839,#185840,#185841,#185842, + #185843,#185844,#185845,#185846,#185847,#185848),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -227341,48 +230343,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183432 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); -#183433 = CARTESIAN_POINT('',(3.152718260825,-0.205348270935)); -#183434 = CARTESIAN_POINT('',(3.175040310705,-0.204780821715)); -#183435 = CARTESIAN_POINT('',(3.208718289392,-0.203956946721)); -#183436 = CARTESIAN_POINT('',(3.242573805888,-0.203162294721)); -#183437 = CARTESIAN_POINT('',(3.276588667066,-0.202398707226)); -#183438 = CARTESIAN_POINT('',(3.310744202863,-0.20166795566)); -#183439 = CARTESIAN_POINT('',(3.34502124338,-0.20097172244)); -#183440 = CARTESIAN_POINT('',(3.379400201195,-0.200311591052)); -#183441 = CARTESIAN_POINT('',(3.413861130172,-0.199689034488)); -#183442 = CARTESIAN_POINT('',(3.448383794636,-0.199105405074)); -#183443 = CARTESIAN_POINT('',(3.482947739147,-0.19856192508)); -#183444 = CARTESIAN_POINT('',(3.517532360737,-0.198059678438)); -#183445 = CARTESIAN_POINT('',(3.552116982328,-0.197599603628)); -#183446 = CARTESIAN_POINT('',(3.586680926839,-0.197182487852)); -#183447 = CARTESIAN_POINT('',(3.621203591303,-0.196808962557)); -#183448 = CARTESIAN_POINT('',(3.65566452028,-0.196479500374)); -#183449 = CARTESIAN_POINT('',(3.690043478095,-0.196194413471)); -#183450 = CARTESIAN_POINT('',(3.724320518612,-0.195953853447)); -#183451 = CARTESIAN_POINT('',(3.758476054408,-0.195757812252)); -#183452 = CARTESIAN_POINT('',(3.792490915587,-0.195606126036)); -#183453 = CARTESIAN_POINT('',(3.826346432082,-0.195498474489)); -#183454 = CARTESIAN_POINT('',(3.86002441077,-0.195434403207)); -#183455 = CARTESIAN_POINT('',(3.88234646065,-0.195420311637)); -#183456 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); -#183457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183458 = ORIENTED_EDGE('',*,*,#183459,.T.); -#183459 = EDGE_CURVE('',#183387,#183238,#183460,.T.); -#183460 = SURFACE_CURVE('',#183461,(#183466,#183495),.PCURVE_S1.); -#183461 = CIRCLE('',#183462,5.E-002); -#183462 = AXIS2_PLACEMENT_3D('',#183463,#183464,#183465); -#183463 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,0.15)); -#183464 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#183465 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#183466 = PCURVE('',#183247,#183467); -#183467 = DEFINITIONAL_REPRESENTATION('',(#183468),#183494); -#183468 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183469,#183470,#183471, - #183472,#183473,#183474,#183475,#183476,#183477,#183478,#183479, - #183480,#183481,#183482,#183483,#183484,#183485,#183486,#183487, - #183488,#183489,#183490,#183491,#183492,#183493),.UNSPECIFIED.,.F., +#185824 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); +#185825 = CARTESIAN_POINT('',(3.152718260825,-0.205348270935)); +#185826 = CARTESIAN_POINT('',(3.175040310705,-0.204780821715)); +#185827 = CARTESIAN_POINT('',(3.208718289392,-0.203956946721)); +#185828 = CARTESIAN_POINT('',(3.242573805888,-0.203162294721)); +#185829 = CARTESIAN_POINT('',(3.276588667066,-0.202398707226)); +#185830 = CARTESIAN_POINT('',(3.310744202863,-0.20166795566)); +#185831 = CARTESIAN_POINT('',(3.34502124338,-0.20097172244)); +#185832 = CARTESIAN_POINT('',(3.379400201195,-0.200311591052)); +#185833 = CARTESIAN_POINT('',(3.413861130172,-0.199689034488)); +#185834 = CARTESIAN_POINT('',(3.448383794636,-0.199105405074)); +#185835 = CARTESIAN_POINT('',(3.482947739147,-0.19856192508)); +#185836 = CARTESIAN_POINT('',(3.517532360737,-0.198059678438)); +#185837 = CARTESIAN_POINT('',(3.552116982328,-0.197599603628)); +#185838 = CARTESIAN_POINT('',(3.586680926839,-0.197182487852)); +#185839 = CARTESIAN_POINT('',(3.621203591303,-0.196808962557)); +#185840 = CARTESIAN_POINT('',(3.65566452028,-0.196479500374)); +#185841 = CARTESIAN_POINT('',(3.690043478095,-0.196194413471)); +#185842 = CARTESIAN_POINT('',(3.724320518612,-0.195953853447)); +#185843 = CARTESIAN_POINT('',(3.758476054408,-0.195757812252)); +#185844 = CARTESIAN_POINT('',(3.792490915587,-0.195606126036)); +#185845 = CARTESIAN_POINT('',(3.826346432082,-0.195498474489)); +#185846 = CARTESIAN_POINT('',(3.86002441077,-0.195434403207)); +#185847 = CARTESIAN_POINT('',(3.88234646065,-0.195420311637)); +#185848 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); +#185849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185850 = ORIENTED_EDGE('',*,*,#185851,.T.); +#185851 = EDGE_CURVE('',#185779,#185630,#185852,.T.); +#185852 = SURFACE_CURVE('',#185853,(#185858,#185887),.PCURVE_S1.); +#185853 = CIRCLE('',#185854,5.E-002); +#185854 = AXIS2_PLACEMENT_3D('',#185855,#185856,#185857); +#185855 = CARTESIAN_POINT('',(-1.287659054385,-0.381066471757,0.15)); +#185856 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#185857 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#185858 = PCURVE('',#185639,#185859); +#185859 = DEFINITIONAL_REPRESENTATION('',(#185860),#185886); +#185860 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185861,#185862,#185863, + #185864,#185865,#185866,#185867,#185868,#185869,#185870,#185871, + #185872,#185873,#185874,#185875,#185876,#185877,#185878,#185879, + #185880,#185881,#185882,#185883,#185884,#185885),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -227390,104 +230392,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183469 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183470 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#183471 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#183472 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#183473 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#183474 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#183475 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#183476 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#183477 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#183478 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#183479 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#183480 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#183481 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#183482 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#183483 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#183484 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#183485 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#183486 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#183487 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#183488 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#183489 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#183490 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#183491 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#183492 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#183493 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183495 = PCURVE('',#183496,#183501); -#183496 = CYLINDRICAL_SURFACE('',#183497,5.E-002); -#183497 = AXIS2_PLACEMENT_3D('',#183498,#183499,#183500); -#183498 = CARTESIAN_POINT('',(-1.287659054385,0.65,0.15)); -#183499 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#183500 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); -#183501 = DEFINITIONAL_REPRESENTATION('',(#183502),#183505); -#183502 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183503,#183504), +#185861 = CARTESIAN_POINT('',(5.531305892885,1.)); +#185862 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#185863 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#185864 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#185865 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#185866 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#185867 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#185868 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#185869 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#185870 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#185871 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#185872 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#185873 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#185874 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#185875 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#185876 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#185877 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#185878 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#185879 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#185880 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#185881 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#185882 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#185883 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#185884 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#185885 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#185886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185887 = PCURVE('',#185888,#185893); +#185888 = CYLINDRICAL_SURFACE('',#185889,5.E-002); +#185889 = AXIS2_PLACEMENT_3D('',#185890,#185891,#185892); +#185890 = CARTESIAN_POINT('',(-1.287659054385,0.65,0.15)); +#185891 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#185892 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); +#185893 = DEFINITIONAL_REPRESENTATION('',(#185894),#185897); +#185894 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185895,#185896), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#183503 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); -#183504 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); -#183505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183506 = ADVANCED_FACE('',(#183507),#183522,.T.); -#183507 = FACE_BOUND('',#183508,.T.); -#183508 = EDGE_LOOP('',(#183509,#183575,#183660,#183733)); -#183509 = ORIENTED_EDGE('',*,*,#183510,.F.); -#183510 = EDGE_CURVE('',#183511,#183513,#183515,.T.); -#183511 = VERTEX_POINT('',#183512); -#183512 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#183513 = VERTEX_POINT('',#183514); -#183514 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#183515 = SURFACE_CURVE('',#183516,(#183521,#183567),.PCURVE_S1.); -#183516 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183517,#183518,#183519, -#183520),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#185895 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); +#185896 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); +#185897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185898 = ADVANCED_FACE('',(#185899),#185914,.T.); +#185899 = FACE_BOUND('',#185900,.T.); +#185900 = EDGE_LOOP('',(#185901,#185967,#186052,#186125)); +#185901 = ORIENTED_EDGE('',*,*,#185902,.F.); +#185902 = EDGE_CURVE('',#185903,#185905,#185907,.T.); +#185903 = VERTEX_POINT('',#185904); +#185904 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#185905 = VERTEX_POINT('',#185906); +#185906 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#185907 = SURFACE_CURVE('',#185908,(#185913,#185959),.PCURVE_S1.); +#185908 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185909,#185910,#185911, +#185912),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183517 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#183518 = CARTESIAN_POINT('',(1.27790129499,0.431596067115,1.E-001)); -#183519 = CARTESIAN_POINT('',(1.287659054385,0.407584046027,1.E-001)); -#183520 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#183521 = PCURVE('',#183522,#183539); -#183522 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183523,#183524,#183525,#183526) - ,(#183527,#183528,#183529,#183530) - ,(#183531,#183532,#183533,#183534) - ,(#183535,#183536,#183537,#183538 +#185909 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#185910 = CARTESIAN_POINT('',(1.27790129499,0.431596067115,1.E-001)); +#185911 = CARTESIAN_POINT('',(1.287659054385,0.407584046027,1.E-001)); +#185912 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#185913 = PCURVE('',#185914,#185931); +#185914 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#185915,#185916,#185917,#185918) + ,(#185919,#185920,#185921,#185922) + ,(#185923,#185924,#185925,#185926) + ,(#185927,#185928,#185929,#185930 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183523 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); -#183524 = CARTESIAN_POINT('',(1.309475670035,0.381066471757,1.E-001)); -#183525 = CARTESIAN_POINT('',(1.33030879007,0.381066471757, +#185915 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,1.E-001)); +#185916 = CARTESIAN_POINT('',(1.309475670035,0.381066471757,1.E-001)); +#185917 = CARTESIAN_POINT('',(1.33030879007,0.381066471757, 0.115985815246)); -#183526 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 +#185918 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 )); -#183527 = CARTESIAN_POINT('',(1.287659054385,0.40695495248,1.E-001)); -#183528 = CARTESIAN_POINT('',(1.308429042165,0.412435083194,1.E-001)); -#183529 = CARTESIAN_POINT('',(1.328443665671,0.417668168966, +#185919 = CARTESIAN_POINT('',(1.287659054385,0.40695495248,1.E-001)); +#185920 = CARTESIAN_POINT('',(1.308429042165,0.412435083194,1.E-001)); +#185921 = CARTESIAN_POINT('',(1.328443665671,0.417668168966, 0.114318476015)); -#183530 = CARTESIAN_POINT('',(1.335142684022,0.419086531164, +#185922 = CARTESIAN_POINT('',(1.335142684022,0.419086531164, 0.134026153074)); -#183531 = CARTESIAN_POINT('',(1.277470648802,0.432026713303,1.E-001)); -#183532 = CARTESIAN_POINT('',(1.295531311073,0.442452511959,1.E-001)); -#183533 = CARTESIAN_POINT('',(1.31299309093,0.452532596412, +#185923 = CARTESIAN_POINT('',(1.277470648802,0.432026713303,1.E-001)); +#185924 = CARTESIAN_POINT('',(1.295531311073,0.442452511959,1.E-001)); +#185925 = CARTESIAN_POINT('',(1.31299309093,0.452532596412, 0.113446578632)); -#183534 = CARTESIAN_POINT('',(1.319392874324,0.456226971076,0.132282534) +#185926 = CARTESIAN_POINT('',(1.319392874324,0.456226971076,0.132282534) ); -#183535 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#183536 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); -#183537 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, +#185927 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#185928 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); +#185929 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, 0.113446578632)); -#183538 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#183539 = DEFINITIONAL_REPRESENTATION('',(#183540),#183566); -#183540 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183541,#183542,#183543, - #183544,#183545,#183546,#183547,#183548,#183549,#183550,#183551, - #183552,#183553,#183554,#183555,#183556,#183557,#183558,#183559, - #183560,#183561,#183562,#183563,#183564,#183565),.UNSPECIFIED.,.F., +#185930 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#185931 = DEFINITIONAL_REPRESENTATION('',(#185932),#185958); +#185932 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185933,#185934,#185935, + #185936,#185937,#185938,#185939,#185940,#185941,#185942,#185943, + #185944,#185945,#185946,#185947,#185948,#185949,#185950,#185951, + #185952,#185953,#185954,#185955,#185956,#185957),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -227495,64 +230497,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#183541 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183542 = CARTESIAN_POINT('',(6.272059569215,1.375318315925E-008)); -#183543 = CARTESIAN_POINT('',(6.24973263213,2.92413401008E-005)); -#183544 = CARTESIAN_POINT('',(6.21603939964,1.413707577698E-004)); -#183545 = CARTESIAN_POINT('',(6.182167276026,3.022859269977E-004)); -#183546 = CARTESIAN_POINT('',(6.148138870073,4.931498468535E-004)); -#183547 = CARTESIAN_POINT('',(6.113975913115,6.962198987843E-004)); -#183548 = CARTESIAN_POINT('',(6.079699188623,8.953387637273E-004)); -#183549 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); -#183550 = CARTESIAN_POINT('',(6.010883543172,1.22739025449E-003)); -#183551 = CARTESIAN_POINT('',(5.976382533559,1.339263477879E-003)); -#183552 = CARTESIAN_POINT('',(5.941843890817,1.405524714334E-003)); -#183553 = CARTESIAN_POINT('',(5.907285653264,1.422641316504E-003)); -#183554 = CARTESIAN_POINT('',(5.87272580864,1.390009812369E-003)); -#183555 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); -#183556 = CARTESIAN_POINT('',(5.803674042174,1.187353930383E-003)); -#183557 = CARTESIAN_POINT('',(5.769219374506,1.029943289557E-003)); -#183558 = CARTESIAN_POINT('',(5.734837892756,8.475624467446E-004)); -#183559 = CARTESIAN_POINT('',(5.700549707253,6.520952931874E-004)); -#183560 = CARTESIAN_POINT('',(5.666375694827,4.57065804322E-004)); -#183561 = CARTESIAN_POINT('',(5.632337541793,2.772530388735E-004)); -#183562 = CARTESIAN_POINT('',(5.598457782919,1.282673135018E-004)); -#183563 = CARTESIAN_POINT('',(5.564759695218,2.616756247318E-005)); -#183564 = CARTESIAN_POINT('',(5.542431609433,-2.901324327884E-008)); -#183565 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183567 = PCURVE('',#183013,#183568); -#183568 = DEFINITIONAL_REPRESENTATION('',(#183569),#183574); -#183569 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183570,#183571,#183572, -#183573),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#185933 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185934 = CARTESIAN_POINT('',(6.272059569215,1.375318315925E-008)); +#185935 = CARTESIAN_POINT('',(6.24973263213,2.92413401008E-005)); +#185936 = CARTESIAN_POINT('',(6.21603939964,1.413707577698E-004)); +#185937 = CARTESIAN_POINT('',(6.182167276026,3.022859269977E-004)); +#185938 = CARTESIAN_POINT('',(6.148138870073,4.931498468535E-004)); +#185939 = CARTESIAN_POINT('',(6.113975913115,6.962198987843E-004)); +#185940 = CARTESIAN_POINT('',(6.079699188623,8.953387637273E-004)); +#185941 = CARTESIAN_POINT('',(6.045328652128,1.076339414E-003)); +#185942 = CARTESIAN_POINT('',(6.010883543172,1.22739025449E-003)); +#185943 = CARTESIAN_POINT('',(5.976382533559,1.339263477879E-003)); +#185944 = CARTESIAN_POINT('',(5.941843890817,1.405524714334E-003)); +#185945 = CARTESIAN_POINT('',(5.907285653264,1.422641316504E-003)); +#185946 = CARTESIAN_POINT('',(5.87272580864,1.390009812369E-003)); +#185947 = CARTESIAN_POINT('',(5.838182469935,1.309904867195E-003)); +#185948 = CARTESIAN_POINT('',(5.803674042174,1.187353930383E-003)); +#185949 = CARTESIAN_POINT('',(5.769219374506,1.029943289557E-003)); +#185950 = CARTESIAN_POINT('',(5.734837892756,8.475624467446E-004)); +#185951 = CARTESIAN_POINT('',(5.700549707253,6.520952931874E-004)); +#185952 = CARTESIAN_POINT('',(5.666375694827,4.57065804322E-004)); +#185953 = CARTESIAN_POINT('',(5.632337541793,2.772530388735E-004)); +#185954 = CARTESIAN_POINT('',(5.598457782919,1.282673135018E-004)); +#185955 = CARTESIAN_POINT('',(5.564759695218,2.616756247318E-005)); +#185956 = CARTESIAN_POINT('',(5.542431609433,-2.901324327884E-008)); +#185957 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#185958 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185959 = PCURVE('',#185405,#185960); +#185960 = DEFINITIONAL_REPRESENTATION('',(#185961),#185966); +#185961 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185962,#185963,#185964, +#185965),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183570 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); -#183571 = CARTESIAN_POINT('',(-0.18209870501,1.081596067115)); -#183572 = CARTESIAN_POINT('',(-0.172340945615,1.057584046027)); -#183573 = CARTESIAN_POINT('',(-0.172340945615,1.031066471757)); -#183574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183575 = ORIENTED_EDGE('',*,*,#183576,.T.); -#183576 = EDGE_CURVE('',#183511,#183577,#183579,.T.); -#183577 = VERTEX_POINT('',#183578); -#183578 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#183579 = SURFACE_CURVE('',#183580,(#183585,#183614),.PCURVE_S1.); -#183580 = CIRCLE('',#183581,5.E-002); -#183581 = AXIS2_PLACEMENT_3D('',#183582,#183583,#183584); -#183582 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,0.15)); -#183583 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#183584 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#183585 = PCURVE('',#183522,#183586); -#183586 = DEFINITIONAL_REPRESENTATION('',(#183587),#183613); -#183587 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183588,#183589,#183590, - #183591,#183592,#183593,#183594,#183595,#183596,#183597,#183598, - #183599,#183600,#183601,#183602,#183603,#183604,#183605,#183606, - #183607,#183608,#183609,#183610,#183611,#183612),.UNSPECIFIED.,.F., +#185962 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); +#185963 = CARTESIAN_POINT('',(-0.18209870501,1.081596067115)); +#185964 = CARTESIAN_POINT('',(-0.172340945615,1.057584046027)); +#185965 = CARTESIAN_POINT('',(-0.172340945615,1.031066471757)); +#185966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#185967 = ORIENTED_EDGE('',*,*,#185968,.T.); +#185968 = EDGE_CURVE('',#185903,#185969,#185971,.T.); +#185969 = VERTEX_POINT('',#185970); +#185970 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#185971 = SURFACE_CURVE('',#185972,(#185977,#186006),.PCURVE_S1.); +#185972 = CIRCLE('',#185973,5.E-002); +#185973 = AXIS2_PLACEMENT_3D('',#185974,#185975,#185976); +#185974 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,0.15)); +#185975 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#185976 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#185977 = PCURVE('',#185914,#185978); +#185978 = DEFINITIONAL_REPRESENTATION('',(#185979),#186005); +#185979 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185980,#185981,#185982, + #185983,#185984,#185985,#185986,#185987,#185988,#185989,#185990, + #185991,#185992,#185993,#185994,#185995,#185996,#185997,#185998, + #185999,#186000,#186001,#186002,#186003,#186004),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -227560,70 +230562,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183588 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183589 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#183590 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#183591 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#183592 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#183593 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#183594 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#183595 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#183596 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#183597 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#183598 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#183599 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#183600 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#183601 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#183602 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#183603 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#183604 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#183605 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#183606 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#183607 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#183608 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#183609 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#183610 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#183611 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#183612 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183613 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183614 = PCURVE('',#183615,#183632); -#183615 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183616,#183617,#183618,#183619) - ,(#183620,#183621,#183622,#183623) - ,(#183624,#183625,#183626,#183627) - ,(#183628,#183629,#183630,#183631 +#185980 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#185981 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#185982 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#185983 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#185984 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#185985 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#185986 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#185987 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#185988 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#185989 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#185990 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#185991 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#185992 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#185993 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#185994 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#185995 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#185996 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#185997 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#185998 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#185999 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#186000 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#186001 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#186002 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#186003 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#186004 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186005 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186006 = PCURVE('',#186007,#186024); +#186007 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186008,#186009,#186010,#186011) + ,(#186012,#186013,#186014,#186015) + ,(#186016,#186017,#186018,#186019) + ,(#186020,#186021,#186022,#186023 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183616 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#183617 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); -#183618 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, +#186008 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#186009 = CARTESIAN_POINT('',(1.273991911516,0.463991911516,1.E-001)); +#186010 = CARTESIAN_POINT('',(1.287762843671,0.477762843671, 0.113446578632)); -#183619 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#183620 = CARTESIAN_POINT('',(1.242026713303,0.467470648802,1.E-001)); -#183621 = CARTESIAN_POINT('',(1.252452511959,0.485531311073,1.E-001)); -#183622 = CARTESIAN_POINT('',(1.262532596412,0.50299309093, +#186011 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#186012 = CARTESIAN_POINT('',(1.242026713303,0.467470648802,1.E-001)); +#186013 = CARTESIAN_POINT('',(1.252452511959,0.485531311073,1.E-001)); +#186014 = CARTESIAN_POINT('',(1.262532596412,0.50299309093, 0.113446578632)); -#183623 = CARTESIAN_POINT('',(1.266226971076,0.509392874324,0.132282534) +#186015 = CARTESIAN_POINT('',(1.266226971076,0.509392874324,0.132282534) ); -#183624 = CARTESIAN_POINT('',(1.21695495248,0.477659054385,1.E-001)); -#183625 = CARTESIAN_POINT('',(1.222435083194,0.498429042165,1.E-001)); -#183626 = CARTESIAN_POINT('',(1.227668168966,0.518443665671, +#186016 = CARTESIAN_POINT('',(1.21695495248,0.477659054385,1.E-001)); +#186017 = CARTESIAN_POINT('',(1.222435083194,0.498429042165,1.E-001)); +#186018 = CARTESIAN_POINT('',(1.227668168966,0.518443665671, 0.114318476015)); -#183627 = CARTESIAN_POINT('',(1.229086531164,0.525142684022, +#186019 = CARTESIAN_POINT('',(1.229086531164,0.525142684022, 0.134026153074)); -#183628 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#183629 = CARTESIAN_POINT('',(1.191066471757,0.499475670035,1.E-001)); -#183630 = CARTESIAN_POINT('',(1.191066471757,0.52030879007, +#186020 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#186021 = CARTESIAN_POINT('',(1.191066471757,0.499475670035,1.E-001)); +#186022 = CARTESIAN_POINT('',(1.191066471757,0.52030879007, 0.115985815246)); -#183631 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 +#186023 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 )); -#183632 = DEFINITIONAL_REPRESENTATION('',(#183633),#183659); -#183633 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183634,#183635,#183636, - #183637,#183638,#183639,#183640,#183641,#183642,#183643,#183644, - #183645,#183646,#183647,#183648,#183649,#183650,#183651,#183652, - #183653,#183654,#183655,#183656,#183657,#183658),.UNSPECIFIED.,.F., +#186024 = DEFINITIONAL_REPRESENTATION('',(#186025),#186051); +#186025 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186026,#186027,#186028, + #186029,#186030,#186031,#186032,#186033,#186034,#186035,#186036, + #186037,#186038,#186039,#186040,#186041,#186042,#186043,#186044, + #186045,#186046,#186047,#186048,#186049,#186050),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -227631,58 +230633,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183634 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#183635 = CARTESIAN_POINT('',(2.91033471756E-015,1.515278164503E-002)); -#183636 = CARTESIAN_POINT('',(4.632036949666E-015,4.549920749134E-002)); -#183637 = CARTESIAN_POINT('',(2.193829578482E-015,9.109101074356E-002)); -#183638 = CARTESIAN_POINT('',(1.17318239543E-015,0.136698748187)); -#183639 = CARTESIAN_POINT('',(3.825709488835E-015,0.1822865144)); -#183640 = CARTESIAN_POINT('',(3.007585829836E-015,0.2278300409)); -#183641 = CARTESIAN_POINT('',(2.081705218533E-015,0.27331674602)); -#183642 = CARTESIAN_POINT('',(-9.978985593511E-016,0.318743220066)); -#183643 = CARTESIAN_POINT('',(6.847313983409E-016,0.364113426255)); -#183644 = CARTESIAN_POINT('',(-1.12737588722E-015,0.409436881051)); -#183645 = CARTESIAN_POINT('',(6.035053617114E-016,0.454727066523)); -#183646 = CARTESIAN_POINT('',(8.32511851254E-016,0.5)); -#183647 = CARTESIAN_POINT('',(-1.205030190221E-016,0.545272933477)); -#183648 = CARTESIAN_POINT('',(-1.833983566176E-016,0.590563118949)); -#183649 = CARTESIAN_POINT('',(8.47972121338E-016,0.635886573745)); -#183650 = CARTESIAN_POINT('',(-1.687035406625E-015,0.681256779934)); -#183651 = CARTESIAN_POINT('',(4.840019940136E-016,0.72668325398)); -#183652 = CARTESIAN_POINT('',(-9.263151972584E-016,0.7721699591)); -#183653 = CARTESIAN_POINT('',(6.893490225787E-016,0.8177134856)); -#183654 = CARTESIAN_POINT('',(2.97210397481E-016,0.863301251813)); -#183655 = CARTESIAN_POINT('',(8.03868702767E-017,0.908908989256)); -#183656 = CARTESIAN_POINT('',(-4.245535665613E-016,0.954500792509)); -#183657 = CARTESIAN_POINT('',(-1.098819920641E-016,0.984847218355)); -#183658 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#183659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183660 = ORIENTED_EDGE('',*,*,#183661,.F.); -#183661 = EDGE_CURVE('',#183662,#183577,#183664,.T.); -#183662 = VERTEX_POINT('',#183663); -#183663 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 +#186026 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#186027 = CARTESIAN_POINT('',(2.91033471756E-015,1.515278164503E-002)); +#186028 = CARTESIAN_POINT('',(4.632036949666E-015,4.549920749134E-002)); +#186029 = CARTESIAN_POINT('',(2.193829578482E-015,9.109101074356E-002)); +#186030 = CARTESIAN_POINT('',(1.17318239543E-015,0.136698748187)); +#186031 = CARTESIAN_POINT('',(3.825709488835E-015,0.1822865144)); +#186032 = CARTESIAN_POINT('',(3.007585829836E-015,0.2278300409)); +#186033 = CARTESIAN_POINT('',(2.081705218533E-015,0.27331674602)); +#186034 = CARTESIAN_POINT('',(-9.978985593511E-016,0.318743220066)); +#186035 = CARTESIAN_POINT('',(6.847313983409E-016,0.364113426255)); +#186036 = CARTESIAN_POINT('',(-1.12737588722E-015,0.409436881051)); +#186037 = CARTESIAN_POINT('',(6.035053617114E-016,0.454727066523)); +#186038 = CARTESIAN_POINT('',(8.32511851254E-016,0.5)); +#186039 = CARTESIAN_POINT('',(-1.205030190221E-016,0.545272933477)); +#186040 = CARTESIAN_POINT('',(-1.833983566176E-016,0.590563118949)); +#186041 = CARTESIAN_POINT('',(8.47972121338E-016,0.635886573745)); +#186042 = CARTESIAN_POINT('',(-1.687035406625E-015,0.681256779934)); +#186043 = CARTESIAN_POINT('',(4.840019940136E-016,0.72668325398)); +#186044 = CARTESIAN_POINT('',(-9.263151972584E-016,0.7721699591)); +#186045 = CARTESIAN_POINT('',(6.893490225787E-016,0.8177134856)); +#186046 = CARTESIAN_POINT('',(2.97210397481E-016,0.863301251813)); +#186047 = CARTESIAN_POINT('',(8.03868702767E-017,0.908908989256)); +#186048 = CARTESIAN_POINT('',(-4.245535665613E-016,0.954500792509)); +#186049 = CARTESIAN_POINT('',(-1.098819920641E-016,0.984847218355)); +#186050 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#186051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186052 = ORIENTED_EDGE('',*,*,#186053,.F.); +#186053 = EDGE_CURVE('',#186054,#185969,#186056,.T.); +#186054 = VERTEX_POINT('',#186055); +#186055 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 )); -#183664 = SURFACE_CURVE('',#183665,(#183670,#183699),.PCURVE_S1.); -#183665 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183666,#183667,#183668, -#183669),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186056 = SURFACE_CURVE('',#186057,(#186062,#186091),.PCURVE_S1.); +#186057 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186058,#186059,#186060, +#186061),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183666 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 +#186058 = CARTESIAN_POINT('',(1.3359553457,0.381066471757,0.137059047745 )); -#183667 = CARTESIAN_POINT('',(1.335122936235,0.420010423697, +#186059 = CARTESIAN_POINT('',(1.335122936235,0.420010423697, 0.133952453327)); -#183668 = CARTESIAN_POINT('',(1.320038843607,0.455581001793,0.132282534) - ); -#183669 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#183670 = PCURVE('',#183522,#183671); -#183671 = DEFINITIONAL_REPRESENTATION('',(#183672),#183698); -#183672 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183673,#183674,#183675, - #183676,#183677,#183678,#183679,#183680,#183681,#183682,#183683, - #183684,#183685,#183686,#183687,#183688,#183689,#183690,#183691, - #183692,#183693,#183694,#183695,#183696,#183697),.UNSPECIFIED.,.F., +#186060 = CARTESIAN_POINT('',(1.320038843607,0.455581001793,0.132282534) + ); +#186061 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#186062 = PCURVE('',#185914,#186063); +#186063 = DEFINITIONAL_REPRESENTATION('',(#186064),#186090); +#186064 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186065,#186066,#186067, + #186068,#186069,#186070,#186071,#186072,#186073,#186074,#186075, + #186076,#186077,#186078,#186079,#186080,#186081,#186082,#186083, + #186084,#186085,#186086,#186087,#186088,#186089),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -227690,47 +230692,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183673 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183674 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); -#183675 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); -#183676 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); -#183677 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); -#183678 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); -#183679 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); -#183680 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); -#183681 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); -#183682 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); -#183683 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); -#183684 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#183685 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#183686 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#183687 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#183688 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#183689 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#183690 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#183691 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#183692 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#183693 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#183694 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#183695 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#183696 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#183697 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183699 = PCURVE('',#183700,#183705); -#183700 = CYLINDRICAL_SURFACE('',#183701,0.15); -#183701 = AXIS2_PLACEMENT_3D('',#183702,#183703,#183704); -#183702 = CARTESIAN_POINT('',(1.324207498814,0.514207498814, +#186065 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186066 = CARTESIAN_POINT('',(5.542431620275,0.999999942879)); +#186067 = CARTESIAN_POINT('',(5.564759360754,1.000007920681)); +#186068 = CARTESIAN_POINT('',(5.59845580442,1.000032115615)); +#186069 = CARTESIAN_POINT('',(5.632333796953,1.000091358148)); +#186070 = CARTESIAN_POINT('',(5.666367464043,1.000086432212)); +#186071 = CARTESIAN_POINT('',(5.700537102675,1.000086873956)); +#186072 = CARTESIAN_POINT('',(5.734821280548,1.000085935454)); +#186073 = CARTESIAN_POINT('',(5.769199593774,1.000085423611)); +#186074 = CARTESIAN_POINT('',(5.803652201529,1.000084853086)); +#186075 = CARTESIAN_POINT('',(5.838159829417,1.000084352808)); +#186076 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#186077 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#186078 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#186079 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#186080 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#186081 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#186082 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#186083 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#186084 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#186085 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#186086 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#186087 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#186088 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#186089 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186091 = PCURVE('',#186092,#186097); +#186092 = CYLINDRICAL_SURFACE('',#186093,0.15); +#186093 = AXIS2_PLACEMENT_3D('',#186094,#186095,#186096); +#186094 = CARTESIAN_POINT('',(1.324207498814,0.514207498814, 0.672770982062)); -#183703 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#183704 = DIRECTION('',(0.965925826289,-1.331129217269E-016, +#186095 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#186096 = DIRECTION('',(0.965925826289,-1.331129217269E-016, -0.258819045103)); -#183705 = DEFINITIONAL_REPRESENTATION('',(#183706),#183732); -#183706 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183707,#183708,#183709, - #183710,#183711,#183712,#183713,#183714,#183715,#183716,#183717, - #183718,#183719,#183720,#183721,#183722,#183723,#183724,#183725, - #183726,#183727,#183728,#183729,#183730,#183731),.UNSPECIFIED.,.F., +#186097 = DEFINITIONAL_REPRESENTATION('',(#186098),#186124); +#186098 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186099,#186100,#186101, + #186102,#186103,#186104,#186105,#186106,#186107,#186108,#186109, + #186110,#186111,#186112,#186113,#186114,#186115,#186116,#186117, + #186118,#186119,#186120,#186121,#186122,#186123),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -227738,48 +230740,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183707 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#183708 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); -#183709 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); -#183710 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); -#183711 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); -#183712 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); -#183713 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); -#183714 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); -#183715 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); -#183716 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); -#183717 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); -#183718 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); -#183719 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); -#183720 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); -#183721 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); -#183722 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); -#183723 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); -#183724 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); -#183725 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); -#183726 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); -#183727 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); -#183728 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); -#183729 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); -#183730 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); -#183731 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#183732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183733 = ORIENTED_EDGE('',*,*,#183734,.F.); -#183734 = EDGE_CURVE('',#183513,#183662,#183735,.T.); -#183735 = SURFACE_CURVE('',#183736,(#183741,#183770),.PCURVE_S1.); -#183736 = CIRCLE('',#183737,5.E-002); -#183737 = AXIS2_PLACEMENT_3D('',#183738,#183739,#183740); -#183738 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,0.15)); -#183739 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#183740 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#183741 = PCURVE('',#183522,#183742); -#183742 = DEFINITIONAL_REPRESENTATION('',(#183743),#183769); -#183743 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183744,#183745,#183746, - #183747,#183748,#183749,#183750,#183751,#183752,#183753,#183754, - #183755,#183756,#183757,#183758,#183759,#183760,#183761,#183762, - #183763,#183764,#183765,#183766,#183767,#183768),.UNSPECIFIED.,.F., +#186099 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#186100 = CARTESIAN_POINT('',(1.112560723485E-002,-0.531079920146)); +#186101 = CARTESIAN_POINT('',(3.344765711494E-002,-0.530512470926)); +#186102 = CARTESIAN_POINT('',(6.712563580239E-002,-0.529688595932)); +#186103 = CARTESIAN_POINT('',(0.100981152298,-0.528893943933)); +#186104 = CARTESIAN_POINT('',(0.134996013476,-0.528130356438)); +#186105 = CARTESIAN_POINT('',(0.169151549273,-0.527399604872)); +#186106 = CARTESIAN_POINT('',(0.20342858979,-0.526703371651)); +#186107 = CARTESIAN_POINT('',(0.237807547605,-0.526043240264)); +#186108 = CARTESIAN_POINT('',(0.272268476582,-0.5254206837)); +#186109 = CARTESIAN_POINT('',(0.306791141046,-0.524837054286)); +#186110 = CARTESIAN_POINT('',(0.341355085557,-0.524293574292)); +#186111 = CARTESIAN_POINT('',(0.375939707147,-0.523791327649)); +#186112 = CARTESIAN_POINT('',(0.410524328738,-0.523331252839)); +#186113 = CARTESIAN_POINT('',(0.445088273249,-0.522914137063)); +#186114 = CARTESIAN_POINT('',(0.479610937713,-0.522540611768)); +#186115 = CARTESIAN_POINT('',(0.51407186669,-0.522211149586)); +#186116 = CARTESIAN_POINT('',(0.548450824505,-0.521926062682)); +#186117 = CARTESIAN_POINT('',(0.582727865022,-0.521685502659)); +#186118 = CARTESIAN_POINT('',(0.616883400819,-0.521489461464)); +#186119 = CARTESIAN_POINT('',(0.650898261997,-0.521337775248)); +#186120 = CARTESIAN_POINT('',(0.684753778493,-0.521230123701)); +#186121 = CARTESIAN_POINT('',(0.71843175718,-0.521166052418)); +#186122 = CARTESIAN_POINT('',(0.74075380706,-0.521151960849)); +#186123 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#186124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186125 = ORIENTED_EDGE('',*,*,#186126,.F.); +#186126 = EDGE_CURVE('',#185905,#186054,#186127,.T.); +#186127 = SURFACE_CURVE('',#186128,(#186133,#186162),.PCURVE_S1.); +#186128 = CIRCLE('',#186129,5.E-002); +#186129 = AXIS2_PLACEMENT_3D('',#186130,#186131,#186132); +#186130 = CARTESIAN_POINT('',(1.287659054385,0.381066471757,0.15)); +#186131 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#186132 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#186133 = PCURVE('',#185914,#186134); +#186134 = DEFINITIONAL_REPRESENTATION('',(#186135),#186161); +#186135 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186136,#186137,#186138, + #186139,#186140,#186141,#186142,#186143,#186144,#186145,#186146, + #186147,#186148,#186149,#186150,#186151,#186152,#186153,#186154, + #186155,#186156,#186157,#186158,#186159,#186160),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -227787,104 +230789,104 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#183744 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183745 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#183746 = CARTESIAN_POINT('',(5.531305889761,4.551530703749E-002)); -#183747 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#183748 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#183749 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#183750 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#183751 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#183752 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#183753 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#183754 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); -#183755 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#183756 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#183757 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#183758 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#183759 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#183760 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#183761 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#183762 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#183763 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#183764 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#183765 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#183766 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#183767 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#183768 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183770 = PCURVE('',#183771,#183776); -#183771 = CYLINDRICAL_SURFACE('',#183772,5.E-002); -#183772 = AXIS2_PLACEMENT_3D('',#183773,#183774,#183775); -#183773 = CARTESIAN_POINT('',(1.287659054385,0.65,0.15)); -#183774 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#183775 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); -#183776 = DEFINITIONAL_REPRESENTATION('',(#183777),#183780); -#183777 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#183778,#183779), +#186136 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186137 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#186138 = CARTESIAN_POINT('',(5.531305889761,4.551530703749E-002)); +#186139 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#186140 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#186141 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#186142 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#186143 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#186144 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#186145 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#186146 = CARTESIAN_POINT('',(5.531310456364,0.409558517818)); +#186147 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#186148 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#186149 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#186150 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#186151 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#186152 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#186153 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#186154 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#186155 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#186156 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#186157 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#186158 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#186159 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#186160 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186162 = PCURVE('',#186163,#186168); +#186163 = CYLINDRICAL_SURFACE('',#186164,5.E-002); +#186164 = AXIS2_PLACEMENT_3D('',#186165,#186166,#186167); +#186165 = CARTESIAN_POINT('',(1.287659054385,0.65,0.15)); +#186166 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#186167 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); +#186168 = DEFINITIONAL_REPRESENTATION('',(#186169),#186172); +#186169 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186170,#186171), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#183778 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#183779 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#183780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183781 = ADVANCED_FACE('',(#183782),#183797,.T.); -#183782 = FACE_BOUND('',#183783,.T.); -#183783 = EDGE_LOOP('',(#183784,#183850,#183935,#184008)); -#183784 = ORIENTED_EDGE('',*,*,#183785,.F.); -#183785 = EDGE_CURVE('',#183786,#183788,#183790,.T.); -#183786 = VERTEX_POINT('',#183787); -#183787 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#183788 = VERTEX_POINT('',#183789); -#183789 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#183790 = SURFACE_CURVE('',#183791,(#183796,#183842),.PCURVE_S1.); -#183791 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183792,#183793,#183794, -#183795),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186170 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#186171 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#186172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186173 = ADVANCED_FACE('',(#186174),#186189,.T.); +#186174 = FACE_BOUND('',#186175,.T.); +#186175 = EDGE_LOOP('',(#186176,#186242,#186327,#186400)); +#186176 = ORIENTED_EDGE('',*,*,#186177,.F.); +#186177 = EDGE_CURVE('',#186178,#186180,#186182,.T.); +#186178 = VERTEX_POINT('',#186179); +#186179 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#186180 = VERTEX_POINT('',#186181); +#186181 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#186182 = SURFACE_CURVE('',#186183,(#186188,#186234),.PCURVE_S1.); +#186183 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186184,#186185,#186186, +#186187),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183792 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#183793 = CARTESIAN_POINT('',(-1.241596067115,0.46790129499,1.E-001)); -#183794 = CARTESIAN_POINT('',(-1.217584046027,0.477659054385,1.E-001)); -#183795 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#183796 = PCURVE('',#183797,#183814); -#183797 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183798,#183799,#183800,#183801) - ,(#183802,#183803,#183804,#183805) - ,(#183806,#183807,#183808,#183809) - ,(#183810,#183811,#183812,#183813 +#186184 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#186185 = CARTESIAN_POINT('',(-1.241596067115,0.46790129499,1.E-001)); +#186186 = CARTESIAN_POINT('',(-1.217584046027,0.477659054385,1.E-001)); +#186187 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#186188 = PCURVE('',#186189,#186206); +#186189 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186190,#186191,#186192,#186193) + ,(#186194,#186195,#186196,#186197) + ,(#186198,#186199,#186200,#186201) + ,(#186202,#186203,#186204,#186205 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183798 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); -#183799 = CARTESIAN_POINT('',(-1.191066471757,0.499475670035,1.E-001)); -#183800 = CARTESIAN_POINT('',(-1.191066471757,0.52030879007, +#186190 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,1.E-001)); +#186191 = CARTESIAN_POINT('',(-1.191066471757,0.499475670035,1.E-001)); +#186192 = CARTESIAN_POINT('',(-1.191066471757,0.52030879007, 0.115985815246)); -#183801 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, +#186193 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, 0.137059047745)); -#183802 = CARTESIAN_POINT('',(-1.21695495248,0.477659054385,1.E-001)); -#183803 = CARTESIAN_POINT('',(-1.222435083194,0.498429042165,1.E-001)); -#183804 = CARTESIAN_POINT('',(-1.227668168966,0.518443665671, +#186194 = CARTESIAN_POINT('',(-1.21695495248,0.477659054385,1.E-001)); +#186195 = CARTESIAN_POINT('',(-1.222435083194,0.498429042165,1.E-001)); +#186196 = CARTESIAN_POINT('',(-1.227668168966,0.518443665671, 0.114318476015)); -#183805 = CARTESIAN_POINT('',(-1.229086531164,0.525142684022, +#186197 = CARTESIAN_POINT('',(-1.229086531164,0.525142684022, 0.134026153074)); -#183806 = CARTESIAN_POINT('',(-1.242026713303,0.467470648802,1.E-001)); -#183807 = CARTESIAN_POINT('',(-1.252452511959,0.485531311073,1.E-001)); -#183808 = CARTESIAN_POINT('',(-1.262532596412,0.50299309093, +#186198 = CARTESIAN_POINT('',(-1.242026713303,0.467470648802,1.E-001)); +#186199 = CARTESIAN_POINT('',(-1.252452511959,0.485531311073,1.E-001)); +#186200 = CARTESIAN_POINT('',(-1.262532596412,0.50299309093, 0.113446578632)); -#183809 = CARTESIAN_POINT('',(-1.266226971076,0.509392874324,0.132282534 +#186201 = CARTESIAN_POINT('',(-1.266226971076,0.509392874324,0.132282534 )); -#183810 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#183811 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); -#183812 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, +#186202 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#186203 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); +#186204 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, 0.113446578632)); -#183813 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#183814 = DEFINITIONAL_REPRESENTATION('',(#183815),#183841); -#183815 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183816,#183817,#183818, - #183819,#183820,#183821,#183822,#183823,#183824,#183825,#183826, - #183827,#183828,#183829,#183830,#183831,#183832,#183833,#183834, - #183835,#183836,#183837,#183838,#183839,#183840),.UNSPECIFIED.,.F., +#186205 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#186206 = DEFINITIONAL_REPRESENTATION('',(#186207),#186233); +#186207 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186208,#186209,#186210, + #186211,#186212,#186213,#186214,#186215,#186216,#186217,#186218, + #186219,#186220,#186221,#186222,#186223,#186224,#186225,#186226, + #186227,#186228,#186229,#186230,#186231,#186232),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 8.809142651445E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -227893,64 +230895,64 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#183816 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183817 = CARTESIAN_POINT('',(6.272059569215,1.375318493936E-008)); -#183818 = CARTESIAN_POINT('',(6.24973263213,2.924134010172E-005)); -#183819 = CARTESIAN_POINT('',(6.21603939964,1.413707577648E-004)); -#183820 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); -#183821 = CARTESIAN_POINT('',(6.148138870073,4.931498468595E-004)); -#183822 = CARTESIAN_POINT('',(6.113975913115,6.962198987677E-004)); -#183823 = CARTESIAN_POINT('',(6.079699188623,8.953387637279E-004)); -#183824 = CARTESIAN_POINT('',(6.045328652128,1.076339414005E-003)); -#183825 = CARTESIAN_POINT('',(6.010883543172,1.227390254476E-003)); -#183826 = CARTESIAN_POINT('',(5.976382533559,1.339263477883E-003)); -#183827 = CARTESIAN_POINT('',(5.941843890817,1.405524714321E-003)); -#183828 = CARTESIAN_POINT('',(5.907285653264,1.422641316499E-003)); -#183829 = CARTESIAN_POINT('',(5.87272580864,1.39000981236E-003)); -#183830 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); -#183831 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); -#183832 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); -#183833 = CARTESIAN_POINT('',(5.734837892756,8.475624467432E-004)); -#183834 = CARTESIAN_POINT('',(5.700549707253,6.520952931824E-004)); -#183835 = CARTESIAN_POINT('',(5.666375694827,4.570658043143E-004)); -#183836 = CARTESIAN_POINT('',(5.632337541793,2.772530388753E-004)); -#183837 = CARTESIAN_POINT('',(5.598457782919,1.282673134886E-004)); -#183838 = CARTESIAN_POINT('',(5.564759695218,2.61675624706E-005)); -#183839 = CARTESIAN_POINT('',(5.542431609433,-2.901324262083E-008)); -#183840 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#183841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183842 = PCURVE('',#183013,#183843); -#183843 = DEFINITIONAL_REPRESENTATION('',(#183844),#183849); -#183844 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183845,#183846,#183847, -#183848),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186208 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186209 = CARTESIAN_POINT('',(6.272059569215,1.375318493936E-008)); +#186210 = CARTESIAN_POINT('',(6.24973263213,2.924134010172E-005)); +#186211 = CARTESIAN_POINT('',(6.21603939964,1.413707577648E-004)); +#186212 = CARTESIAN_POINT('',(6.182167276026,3.022859269945E-004)); +#186213 = CARTESIAN_POINT('',(6.148138870073,4.931498468595E-004)); +#186214 = CARTESIAN_POINT('',(6.113975913115,6.962198987677E-004)); +#186215 = CARTESIAN_POINT('',(6.079699188623,8.953387637279E-004)); +#186216 = CARTESIAN_POINT('',(6.045328652128,1.076339414005E-003)); +#186217 = CARTESIAN_POINT('',(6.010883543172,1.227390254476E-003)); +#186218 = CARTESIAN_POINT('',(5.976382533559,1.339263477883E-003)); +#186219 = CARTESIAN_POINT('',(5.941843890817,1.405524714321E-003)); +#186220 = CARTESIAN_POINT('',(5.907285653264,1.422641316499E-003)); +#186221 = CARTESIAN_POINT('',(5.87272580864,1.39000981236E-003)); +#186222 = CARTESIAN_POINT('',(5.838182469936,1.309904867189E-003)); +#186223 = CARTESIAN_POINT('',(5.803674042174,1.187353930379E-003)); +#186224 = CARTESIAN_POINT('',(5.769219374506,1.02994328955E-003)); +#186225 = CARTESIAN_POINT('',(5.734837892756,8.475624467432E-004)); +#186226 = CARTESIAN_POINT('',(5.700549707253,6.520952931824E-004)); +#186227 = CARTESIAN_POINT('',(5.666375694827,4.570658043143E-004)); +#186228 = CARTESIAN_POINT('',(5.632337541793,2.772530388753E-004)); +#186229 = CARTESIAN_POINT('',(5.598457782919,1.282673134886E-004)); +#186230 = CARTESIAN_POINT('',(5.564759695218,2.61675624706E-005)); +#186231 = CARTESIAN_POINT('',(5.542431609433,-2.901324262083E-008)); +#186232 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186234 = PCURVE('',#185405,#186235); +#186235 = DEFINITIONAL_REPRESENTATION('',(#186236),#186241); +#186236 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186237,#186238,#186239, +#186240),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 8.809142651445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183845 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); -#183846 = CARTESIAN_POINT('',(-2.701596067115,1.11790129499)); -#183847 = CARTESIAN_POINT('',(-2.677584046027,1.127659054385)); -#183848 = CARTESIAN_POINT('',(-2.651066471757,1.127659054385)); -#183849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183850 = ORIENTED_EDGE('',*,*,#183851,.T.); -#183851 = EDGE_CURVE('',#183786,#183852,#183854,.T.); -#183852 = VERTEX_POINT('',#183853); -#183853 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#183854 = SURFACE_CURVE('',#183855,(#183860,#183889),.PCURVE_S1.); -#183855 = CIRCLE('',#183856,5.E-002); -#183856 = AXIS2_PLACEMENT_3D('',#183857,#183858,#183859); -#183857 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,0.15)); -#183858 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#183859 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#183860 = PCURVE('',#183797,#183861); -#183861 = DEFINITIONAL_REPRESENTATION('',(#183862),#183888); -#183862 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183863,#183864,#183865, - #183866,#183867,#183868,#183869,#183870,#183871,#183872,#183873, - #183874,#183875,#183876,#183877,#183878,#183879,#183880,#183881, - #183882,#183883,#183884,#183885,#183886,#183887),.UNSPECIFIED.,.F., +#186237 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); +#186238 = CARTESIAN_POINT('',(-2.701596067115,1.11790129499)); +#186239 = CARTESIAN_POINT('',(-2.677584046027,1.127659054385)); +#186240 = CARTESIAN_POINT('',(-2.651066471757,1.127659054385)); +#186241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186242 = ORIENTED_EDGE('',*,*,#186243,.T.); +#186243 = EDGE_CURVE('',#186178,#186244,#186246,.T.); +#186244 = VERTEX_POINT('',#186245); +#186245 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#186246 = SURFACE_CURVE('',#186247,(#186252,#186281),.PCURVE_S1.); +#186247 = CIRCLE('',#186248,5.E-002); +#186248 = AXIS2_PLACEMENT_3D('',#186249,#186250,#186251); +#186249 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,0.15)); +#186250 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#186251 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#186252 = PCURVE('',#186189,#186253); +#186253 = DEFINITIONAL_REPRESENTATION('',(#186254),#186280); +#186254 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186255,#186256,#186257, + #186258,#186259,#186260,#186261,#186262,#186263,#186264,#186265, + #186266,#186267,#186268,#186269,#186270,#186271,#186272,#186273, + #186274,#186275,#186276,#186277,#186278,#186279),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -227958,70 +230960,70 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183863 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#183864 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#183865 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#183866 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#183867 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#183868 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#183869 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#183870 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#183871 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#183872 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#183873 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#183874 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#183875 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#183876 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#183877 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#183878 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#183879 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#183880 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#183881 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#183882 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#183883 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#183884 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#183885 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#183886 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#183887 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183889 = PCURVE('',#183890,#183907); -#183890 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#183891,#183892,#183893,#183894) - ,(#183895,#183896,#183897,#183898) - ,(#183899,#183900,#183901,#183902) - ,(#183903,#183904,#183905,#183906 +#186255 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186256 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#186257 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#186258 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#186259 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#186260 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#186261 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#186262 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#186263 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#186264 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#186265 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#186266 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#186267 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#186268 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#186269 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#186270 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#186271 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#186272 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#186273 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#186274 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#186275 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#186276 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#186277 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#186278 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#186279 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186281 = PCURVE('',#186282,#186299); +#186282 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186283,#186284,#186285,#186286) + ,(#186287,#186288,#186289,#186290) + ,(#186291,#186292,#186293,#186294) + ,(#186295,#186296,#186297,#186298 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#183891 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#183892 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); -#183893 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, +#186283 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#186284 = CARTESIAN_POINT('',(-1.273991911516,0.463991911516,1.E-001)); +#186285 = CARTESIAN_POINT('',(-1.287762843671,0.477762843671, 0.113446578632)); -#183894 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#183895 = CARTESIAN_POINT('',(-1.277470648802,0.432026713303,1.E-001)); -#183896 = CARTESIAN_POINT('',(-1.295531311073,0.442452511959,1.E-001)); -#183897 = CARTESIAN_POINT('',(-1.31299309093,0.452532596412, +#186286 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#186287 = CARTESIAN_POINT('',(-1.277470648802,0.432026713303,1.E-001)); +#186288 = CARTESIAN_POINT('',(-1.295531311073,0.442452511959,1.E-001)); +#186289 = CARTESIAN_POINT('',(-1.31299309093,0.452532596412, 0.113446578632)); -#183898 = CARTESIAN_POINT('',(-1.319392874324,0.456226971076,0.132282534 +#186290 = CARTESIAN_POINT('',(-1.319392874324,0.456226971076,0.132282534 )); -#183899 = CARTESIAN_POINT('',(-1.287659054385,0.40695495248,1.E-001)); -#183900 = CARTESIAN_POINT('',(-1.308429042165,0.412435083194,1.E-001)); -#183901 = CARTESIAN_POINT('',(-1.328443665671,0.417668168966, +#186291 = CARTESIAN_POINT('',(-1.287659054385,0.40695495248,1.E-001)); +#186292 = CARTESIAN_POINT('',(-1.308429042165,0.412435083194,1.E-001)); +#186293 = CARTESIAN_POINT('',(-1.328443665671,0.417668168966, 0.114318476015)); -#183902 = CARTESIAN_POINT('',(-1.335142684022,0.419086531164, +#186294 = CARTESIAN_POINT('',(-1.335142684022,0.419086531164, 0.134026153074)); -#183903 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#183904 = CARTESIAN_POINT('',(-1.309475670035,0.381066471757,1.E-001)); -#183905 = CARTESIAN_POINT('',(-1.33030879007,0.381066471757, +#186295 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#186296 = CARTESIAN_POINT('',(-1.309475670035,0.381066471757,1.E-001)); +#186297 = CARTESIAN_POINT('',(-1.33030879007,0.381066471757, 0.115985815246)); -#183906 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, +#186298 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, 0.137059047745)); -#183907 = DEFINITIONAL_REPRESENTATION('',(#183908),#183934); -#183908 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183909,#183910,#183911, - #183912,#183913,#183914,#183915,#183916,#183917,#183918,#183919, - #183920,#183921,#183922,#183923,#183924,#183925,#183926,#183927, - #183928,#183929,#183930,#183931,#183932,#183933),.UNSPECIFIED.,.F., +#186299 = DEFINITIONAL_REPRESENTATION('',(#186300),#186326); +#186300 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186301,#186302,#186303, + #186304,#186305,#186306,#186307,#186308,#186309,#186310,#186311, + #186312,#186313,#186314,#186315,#186316,#186317,#186318,#186319, + #186320,#186321,#186322,#186323,#186324,#186325),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.767324352275,4.822259724165,4.877195096055,4.932130467945, 4.987065839835,5.042001211726,5.096936583616,5.151871955506, @@ -228029,60 +231031,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.426548814957,5.481484186847,5.536419558737,5.591354930627, 5.646290302517,5.701225674407,5.756161046297,5.811096418188, 5.866031790078,5.920967161968),.QUASI_UNIFORM_KNOTS.); -#183909 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#183910 = CARTESIAN_POINT('',(-1.46330102167E-015,1.515278164503E-002)); -#183911 = CARTESIAN_POINT('',(-1.464455124249E-015,4.549920749134E-002) - ); -#183912 = CARTESIAN_POINT('',(-2.215304484765E-016,9.109101074357E-002) - ); -#183913 = CARTESIAN_POINT('',(1.493819329251E-015,0.136698748187)); -#183914 = CARTESIAN_POINT('',(-2.096990132421E-015,0.1822865144)); -#183915 = CARTESIAN_POINT('',(-1.821258059536E-015,0.2278300409)); -#183916 = CARTESIAN_POINT('',(-1.426172734298E-015,0.27331674602)); -#183917 = CARTESIAN_POINT('',(2.639844373571E-015,0.318743220066)); -#183918 = CARTESIAN_POINT('',(-2.242246185818E-015,0.364113426255)); -#183919 = CARTESIAN_POINT('',(1.933048259393E-015,0.409436881051)); -#183920 = CARTESIAN_POINT('',(-5.27771497447E-016,0.454727066523)); -#183921 = CARTESIAN_POINT('',(1.562527491438E-015,0.5)); -#183922 = CARTESIAN_POINT('',(1.106310870334E-015,0.545272933477)); -#183923 = CARTESIAN_POINT('',(9.420665051041E-016,0.590563118949)); -#183924 = CARTESIAN_POINT('',(-1.359829843782E-015,0.635886573745)); -#183925 = CARTESIAN_POINT('',(2.853349287298E-015,0.681256779934)); -#183926 = CARTESIAN_POINT('',(3.785671830011E-017,0.72668325398)); -#183927 = CARTESIAN_POINT('',(2.100632383276E-015,0.7721699591)); -#183928 = CARTESIAN_POINT('',(-1.017498792288E-016,0.8177134856)); -#183929 = CARTESIAN_POINT('',(1.712000903909E-015,0.863301251813)); -#183930 = CARTESIAN_POINT('',(2.988232549161E-015,0.908908989256)); -#183931 = CARTESIAN_POINT('',(7.917676621896E-016,0.954500792509)); -#183932 = CARTESIAN_POINT('',(-5.466081644211E-016,0.984847218355)); -#183933 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#183934 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183935 = ORIENTED_EDGE('',*,*,#183936,.F.); -#183936 = EDGE_CURVE('',#183937,#183852,#183939,.T.); -#183937 = VERTEX_POINT('',#183938); -#183938 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, +#186301 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#186302 = CARTESIAN_POINT('',(-1.46330102167E-015,1.515278164503E-002)); +#186303 = CARTESIAN_POINT('',(-1.464455124249E-015,4.549920749134E-002) + ); +#186304 = CARTESIAN_POINT('',(-2.215304484765E-016,9.109101074357E-002) + ); +#186305 = CARTESIAN_POINT('',(1.493819329251E-015,0.136698748187)); +#186306 = CARTESIAN_POINT('',(-2.096990132421E-015,0.1822865144)); +#186307 = CARTESIAN_POINT('',(-1.821258059536E-015,0.2278300409)); +#186308 = CARTESIAN_POINT('',(-1.426172734298E-015,0.27331674602)); +#186309 = CARTESIAN_POINT('',(2.639844373571E-015,0.318743220066)); +#186310 = CARTESIAN_POINT('',(-2.242246185818E-015,0.364113426255)); +#186311 = CARTESIAN_POINT('',(1.933048259393E-015,0.409436881051)); +#186312 = CARTESIAN_POINT('',(-5.27771497447E-016,0.454727066523)); +#186313 = CARTESIAN_POINT('',(1.562527491438E-015,0.5)); +#186314 = CARTESIAN_POINT('',(1.106310870334E-015,0.545272933477)); +#186315 = CARTESIAN_POINT('',(9.420665051041E-016,0.590563118949)); +#186316 = CARTESIAN_POINT('',(-1.359829843782E-015,0.635886573745)); +#186317 = CARTESIAN_POINT('',(2.853349287298E-015,0.681256779934)); +#186318 = CARTESIAN_POINT('',(3.785671830011E-017,0.72668325398)); +#186319 = CARTESIAN_POINT('',(2.100632383276E-015,0.7721699591)); +#186320 = CARTESIAN_POINT('',(-1.017498792288E-016,0.8177134856)); +#186321 = CARTESIAN_POINT('',(1.712000903909E-015,0.863301251813)); +#186322 = CARTESIAN_POINT('',(2.988232549161E-015,0.908908989256)); +#186323 = CARTESIAN_POINT('',(7.917676621896E-016,0.954500792509)); +#186324 = CARTESIAN_POINT('',(-5.466081644211E-016,0.984847218355)); +#186325 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#186326 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186327 = ORIENTED_EDGE('',*,*,#186328,.F.); +#186328 = EDGE_CURVE('',#186329,#186244,#186331,.T.); +#186329 = VERTEX_POINT('',#186330); +#186330 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, 0.137059047745)); -#183939 = SURFACE_CURVE('',#183940,(#183945,#183974),.PCURVE_S1.); -#183940 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#183941,#183942,#183943, -#183944),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186331 = SURFACE_CURVE('',#186332,(#186337,#186366),.PCURVE_S1.); +#186332 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186333,#186334,#186335, +#186336),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#183941 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, +#186333 = CARTESIAN_POINT('',(-1.191066471757,0.5259553457, 0.137059047745)); -#183942 = CARTESIAN_POINT('',(-1.230010423697,0.525122936235, +#186334 = CARTESIAN_POINT('',(-1.230010423697,0.525122936235, 0.133952453327)); -#183943 = CARTESIAN_POINT('',(-1.265581001793,0.510038843607,0.132282534 +#186335 = CARTESIAN_POINT('',(-1.265581001793,0.510038843607,0.132282534 )); -#183944 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#183945 = PCURVE('',#183797,#183946); -#183946 = DEFINITIONAL_REPRESENTATION('',(#183947),#183973); -#183947 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183948,#183949,#183950, - #183951,#183952,#183953,#183954,#183955,#183956,#183957,#183958, - #183959,#183960,#183961,#183962,#183963,#183964,#183965,#183966, - #183967,#183968,#183969,#183970,#183971,#183972),.UNSPECIFIED.,.F., +#186336 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#186337 = PCURVE('',#186189,#186338); +#186338 = DEFINITIONAL_REPRESENTATION('',(#186339),#186365); +#186339 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186340,#186341,#186342, + #186343,#186344,#186345,#186346,#186347,#186348,#186349,#186350, + #186351,#186352,#186353,#186354,#186355,#186356,#186357,#186358, + #186359,#186360,#186361,#186362,#186363,#186364),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -228090,47 +231092,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183948 = CARTESIAN_POINT('',(5.531305892885,1.)); -#183949 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); -#183950 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); -#183951 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); -#183952 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); -#183953 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); -#183954 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); -#183955 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); -#183956 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); -#183957 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); -#183958 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); -#183959 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); -#183960 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); -#183961 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); -#183962 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); -#183963 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); -#183964 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); -#183965 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); -#183966 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); -#183967 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); -#183968 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); -#183969 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); -#183970 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); -#183971 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); -#183972 = CARTESIAN_POINT('',(6.28318530718,1.)); -#183973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#183974 = PCURVE('',#183975,#183980); -#183975 = CYLINDRICAL_SURFACE('',#183976,0.15); -#183976 = AXIS2_PLACEMENT_3D('',#183977,#183978,#183979); -#183977 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, +#186340 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186341 = CARTESIAN_POINT('',(5.542431620275,0.999999942971)); +#186342 = CARTESIAN_POINT('',(5.564759360754,1.000007920749)); +#186343 = CARTESIAN_POINT('',(5.59845580442,1.00003211524)); +#186344 = CARTESIAN_POINT('',(5.632333796953,1.000091359578)); +#186345 = CARTESIAN_POINT('',(5.666367464043,1.000086431829)); +#186346 = CARTESIAN_POINT('',(5.700537102675,1.000086874059)); +#186347 = CARTESIAN_POINT('',(5.734821280548,1.000085935426)); +#186348 = CARTESIAN_POINT('',(5.769199593774,1.000085423618)); +#186349 = CARTESIAN_POINT('',(5.803652201529,1.000084853084)); +#186350 = CARTESIAN_POINT('',(5.838159829417,1.000084352809)); +#186351 = CARTESIAN_POINT('',(5.872703630927,1.000083887025)); +#186352 = CARTESIAN_POINT('',(5.907265074214,1.000083464612)); +#186353 = CARTESIAN_POINT('',(5.941825812427,1.000083080815)); +#186354 = CARTESIAN_POINT('',(5.97636755144,1.000082740983)); +#186355 = CARTESIAN_POINT('',(6.010871913477,1.000082423901)); +#186356 = CARTESIAN_POINT('',(6.045320300361,1.000082204722)); +#186357 = CARTESIAN_POINT('',(6.079693755153,1.000081799895)); +#186358 = CARTESIAN_POINT('',(6.113972837442,1.000082264514)); +#186359 = CARTESIAN_POINT('',(6.148137469616,1.000079657977)); +#186360 = CARTESIAN_POINT('',(6.182166930891,1.000088683966)); +#186361 = CARTESIAN_POINT('',(6.216039360813,1.000054464841)); +#186362 = CARTESIAN_POINT('',(6.249732638972,1.000010370525)); +#186363 = CARTESIAN_POINT('',(6.272059551128,0.999997027196)); +#186364 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186366 = PCURVE('',#186367,#186372); +#186367 = CYLINDRICAL_SURFACE('',#186368,0.15); +#186368 = AXIS2_PLACEMENT_3D('',#186369,#186370,#186371); +#186369 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, 0.672770982062)); -#183978 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#183979 = DIRECTION('',(0.965925826289,-3.026618127129E-017, +#186370 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#186371 = DIRECTION('',(0.965925826289,-3.026618127129E-017, 0.258819045103)); -#183980 = DEFINITIONAL_REPRESENTATION('',(#183981),#184007); -#183981 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#183982,#183983,#183984, - #183985,#183986,#183987,#183988,#183989,#183990,#183991,#183992, - #183993,#183994,#183995,#183996,#183997,#183998,#183999,#184000, - #184001,#184002,#184003,#184004,#184005,#184006),.UNSPECIFIED.,.F., +#186372 = DEFINITIONAL_REPRESENTATION('',(#186373),#186399); +#186373 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186374,#186375,#186376, + #186377,#186378,#186379,#186380,#186381,#186382,#186383,#186384, + #186385,#186386,#186387,#186388,#186389,#186390,#186391,#186392, + #186393,#186394,#186395,#186396,#186397,#186398),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -228138,48 +231140,48 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#183982 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#183983 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); -#183984 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); -#183985 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); -#183986 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); -#183987 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); -#183988 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); -#183989 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); -#183990 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); -#183991 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); -#183992 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); -#183993 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); -#183994 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); -#183995 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); -#183996 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); -#183997 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); -#183998 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); -#183999 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); -#184000 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); -#184001 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); -#184002 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); -#184003 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); -#184004 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); -#184005 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); -#184006 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#184007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184008 = ORIENTED_EDGE('',*,*,#184009,.F.); -#184009 = EDGE_CURVE('',#183788,#183937,#184010,.T.); -#184010 = SURFACE_CURVE('',#184011,(#184016,#184045),.PCURVE_S1.); -#184011 = CIRCLE('',#184012,5.E-002); -#184012 = AXIS2_PLACEMENT_3D('',#184013,#184014,#184015); -#184013 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,0.15)); -#184014 = DIRECTION('',(1.,0.E+000,0.E+000)); -#184015 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#184016 = PCURVE('',#183797,#184017); -#184017 = DEFINITIONAL_REPRESENTATION('',(#184018),#184044); -#184018 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184019,#184020,#184021, - #184022,#184023,#184024,#184025,#184026,#184027,#184028,#184029, - #184030,#184031,#184032,#184033,#184034,#184035,#184036,#184037, - #184038,#184039,#184040,#184041,#184042,#184043),.UNSPECIFIED.,.F., +#186374 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#186375 = CARTESIAN_POINT('',(1.648959432235,-0.531079920146)); +#186376 = CARTESIAN_POINT('',(1.671281482115,-0.530512470926)); +#186377 = CARTESIAN_POINT('',(1.704959460802,-0.529688595932)); +#186378 = CARTESIAN_POINT('',(1.738814977298,-0.528893943933)); +#186379 = CARTESIAN_POINT('',(1.772829838476,-0.528130356438)); +#186380 = CARTESIAN_POINT('',(1.806985374273,-0.527399604872)); +#186381 = CARTESIAN_POINT('',(1.84126241479,-0.526703371651)); +#186382 = CARTESIAN_POINT('',(1.875641372605,-0.526043240264)); +#186383 = CARTESIAN_POINT('',(1.910102301582,-0.5254206837)); +#186384 = CARTESIAN_POINT('',(1.944624966046,-0.524837054286)); +#186385 = CARTESIAN_POINT('',(1.979188910557,-0.524293574292)); +#186386 = CARTESIAN_POINT('',(2.013773532147,-0.523791327649)); +#186387 = CARTESIAN_POINT('',(2.048358153738,-0.523331252839)); +#186388 = CARTESIAN_POINT('',(2.082922098249,-0.522914137063)); +#186389 = CARTESIAN_POINT('',(2.117444762713,-0.522540611768)); +#186390 = CARTESIAN_POINT('',(2.15190569169,-0.522211149586)); +#186391 = CARTESIAN_POINT('',(2.186284649505,-0.521926062682)); +#186392 = CARTESIAN_POINT('',(2.220561690022,-0.521685502659)); +#186393 = CARTESIAN_POINT('',(2.254717225818,-0.521489461464)); +#186394 = CARTESIAN_POINT('',(2.288732086997,-0.521337775248)); +#186395 = CARTESIAN_POINT('',(2.322587603492,-0.521230123701)); +#186396 = CARTESIAN_POINT('',(2.35626558218,-0.521166052418)); +#186397 = CARTESIAN_POINT('',(2.37858763206,-0.521151960849)); +#186398 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#186399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186400 = ORIENTED_EDGE('',*,*,#186401,.F.); +#186401 = EDGE_CURVE('',#186180,#186329,#186402,.T.); +#186402 = SURFACE_CURVE('',#186403,(#186408,#186437),.PCURVE_S1.); +#186403 = CIRCLE('',#186404,5.E-002); +#186404 = AXIS2_PLACEMENT_3D('',#186405,#186406,#186407); +#186405 = CARTESIAN_POINT('',(-1.191066471757,0.477659054385,0.15)); +#186406 = DIRECTION('',(1.,0.E+000,0.E+000)); +#186407 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#186408 = PCURVE('',#186189,#186409); +#186409 = DEFINITIONAL_REPRESENTATION('',(#186410),#186436); +#186410 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186411,#186412,#186413, + #186414,#186415,#186416,#186417,#186418,#186419,#186420,#186421, + #186422,#186423,#186424,#186425,#186426,#186427,#186428,#186429, + #186430,#186431,#186432,#186433,#186434,#186435),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -228187,111 +231189,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#184019 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184020 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); -#184021 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); -#184022 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); -#184023 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); -#184024 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); -#184025 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); -#184026 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); -#184027 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); -#184028 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); -#184029 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); -#184030 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); -#184031 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); -#184032 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); -#184033 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); -#184034 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); -#184035 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); -#184036 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); -#184037 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); -#184038 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); -#184039 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); -#184040 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); -#184041 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); -#184042 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); -#184043 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184045 = PCURVE('',#184046,#184051); -#184046 = CYLINDRICAL_SURFACE('',#184047,5.E-002); -#184047 = AXIS2_PLACEMENT_3D('',#184048,#184049,#184050); -#184048 = CARTESIAN_POINT('',(-1.46,0.477659054385,0.15)); -#184049 = DIRECTION('',(1.,0.E+000,0.E+000)); -#184050 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#184051 = DEFINITIONAL_REPRESENTATION('',(#184052),#184055); -#184052 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184053,#184054), +#186411 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186412 = CARTESIAN_POINT('',(5.531305895404,1.515321229167E-002)); +#186413 = CARTESIAN_POINT('',(5.531305889761,4.551530703748E-002)); +#186414 = CARTESIAN_POINT('',(5.531305917798,9.115660726252E-002)); +#186415 = CARTESIAN_POINT('',(5.531306048207,0.136819295439)); +#186416 = CARTESIAN_POINT('',(5.531306356223,0.182454313621)); +#186417 = CARTESIAN_POINT('',(5.531306883237,0.228028782364)); +#186418 = CARTESIAN_POINT('',(5.531307625546,0.273525947495)); +#186419 = CARTESIAN_POINT('',(5.531308531949,0.318941593796)); +#186420 = CARTESIAN_POINT('',(5.531309512999,0.364281431335)); +#186421 = CARTESIAN_POINT('',(5.531310456365,0.409558517818)); +#186422 = CARTESIAN_POINT('',(5.531311245056,0.454791070439)); +#186423 = CARTESIAN_POINT('',(5.531311775431,0.500000558794)); +#186424 = CARTESIAN_POINT('',(5.531311972785,0.545210022336)); +#186425 = CARTESIAN_POINT('',(5.531311802952,0.590442502307)); +#186426 = CARTESIAN_POINT('',(5.531311278795,0.635719473711)); +#186427 = CARTESIAN_POINT('',(5.531310460769,0.681059162837)); +#186428 = CARTESIAN_POINT('',(5.531309450978,0.726474640117)); +#186429 = CARTESIAN_POINT('',(5.531308380511,0.771971631535)); +#186430 = CARTESIAN_POINT('',(5.531307389788,0.817545939745)); +#186431 = CARTESIAN_POINT('',(5.531306604351,0.863180828254)); +#186432 = CARTESIAN_POINT('',(5.531306102499,0.908843430613)); +#186433 = CARTESIAN_POINT('',(5.531305899752,0.954484694488)); +#186434 = CARTESIAN_POINT('',(5.531305884234,0.984846785972)); +#186435 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186436 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186437 = PCURVE('',#186438,#186443); +#186438 = CYLINDRICAL_SURFACE('',#186439,5.E-002); +#186439 = AXIS2_PLACEMENT_3D('',#186440,#186441,#186442); +#186440 = CARTESIAN_POINT('',(-1.46,0.477659054385,0.15)); +#186441 = DIRECTION('',(1.,0.E+000,0.E+000)); +#186442 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#186443 = DEFINITIONAL_REPRESENTATION('',(#186444),#186447); +#186444 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186445,#186446), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#184053 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#184054 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#184055 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#186445 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#186446 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#186447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#184056 = ADVANCED_FACE('',(#184057),#184072,.T.); -#184057 = FACE_BOUND('',#184058,.T.); -#184058 = EDGE_LOOP('',(#184059,#184151,#184236,#184288)); -#184059 = ORIENTED_EDGE('',*,*,#184060,.F.); -#184060 = EDGE_CURVE('',#184061,#184063,#184065,.T.); -#184061 = VERTEX_POINT('',#184062); -#184062 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, +#186448 = ADVANCED_FACE('',(#186449),#186464,.T.); +#186449 = FACE_BOUND('',#186450,.T.); +#186450 = EDGE_LOOP('',(#186451,#186543,#186628,#186680)); +#186451 = ORIENTED_EDGE('',*,*,#186452,.F.); +#186452 = EDGE_CURVE('',#186453,#186455,#186457,.T.); +#186453 = VERTEX_POINT('',#186454); +#186454 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, 0.967717466)); -#184063 = VERTEX_POINT('',#184064); -#184064 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, +#186455 = VERTEX_POINT('',#186456); +#186456 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, 0.962940952255)); -#184065 = SURFACE_CURVE('',#184066,(#184071,#184117),.PCURVE_S1.); -#184066 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184067,#184068,#184069, -#184070),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186457 = SURFACE_CURVE('',#186458,(#186463,#186509),.PCURVE_S1.); +#186458 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186459,#186460,#186461, +#186462),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.614007241618E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184067 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, +#186459 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, 0.967717466)); -#184068 = CARTESIAN_POINT('',(-1.34683376285,-0.482375921036,0.967717466 +#186460 = CARTESIAN_POINT('',(-1.34683376285,-0.482375921036,0.967717466 )); -#184069 = CARTESIAN_POINT('',(-1.361917855478,-0.44680534294, +#186461 = CARTESIAN_POINT('',(-1.361917855478,-0.44680534294, 0.966047546673)); -#184070 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, +#186462 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, 0.962940952255)); -#184071 = PCURVE('',#184072,#184089); -#184072 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184073,#184074,#184075,#184076) - ,(#184077,#184078,#184079,#184080) - ,(#184081,#184082,#184083,#184084) - ,(#184085,#184086,#184087,#184088 +#186463 = PCURVE('',#186464,#186481); +#186464 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186465,#186466,#186467,#186468) + ,(#186469,#186470,#186471,#186472) + ,(#186473,#186474,#186475,#186476) + ,(#186477,#186478,#186479,#186480 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184073 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, +#186465 = CARTESIAN_POINT('',(-1.362750264943,-0.407861391, 0.962940952255)); -#184074 = CARTESIAN_POINT('',(-1.357103709313,-0.407861391, +#186466 = CARTESIAN_POINT('',(-1.357103709313,-0.407861391, 0.984014184754)); -#184075 = CARTESIAN_POINT('',(-1.336270589279,-0.407861391,1.)); -#184076 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#184077 = CARTESIAN_POINT('',(-1.361937603265,-0.445881450408, +#186467 = CARTESIAN_POINT('',(-1.336270589279,-0.407861391,1.)); +#186468 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#186469 = CARTESIAN_POINT('',(-1.361937603265,-0.445881450408, 0.965973846926)); -#184078 = CARTESIAN_POINT('',(-1.355238584914,-0.444463088209, +#186470 = CARTESIAN_POINT('',(-1.355238584914,-0.444463088209, 0.985681523985)); -#184079 = CARTESIAN_POINT('',(-1.335223961408,-0.439230002437,1.)); -#184080 = CARTESIAN_POINT('',(-1.314453973629,-0.433749871723,1.)); -#184081 = CARTESIAN_POINT('',(-1.346187793567,-0.483021890319, +#186471 = CARTESIAN_POINT('',(-1.335223961408,-0.439230002437,1.)); +#186472 = CARTESIAN_POINT('',(-1.314453973629,-0.433749871723,1.)); +#186473 = CARTESIAN_POINT('',(-1.346187793567,-0.483021890319, 0.967717466)); -#184082 = CARTESIAN_POINT('',(-1.339788010173,-0.479327515655, +#186474 = CARTESIAN_POINT('',(-1.339788010173,-0.479327515655, 0.986553421368)); -#184083 = CARTESIAN_POINT('',(-1.322326230316,-0.469247431202,1.)); -#184084 = CARTESIAN_POINT('',(-1.304265568045,-0.458821632546,1.)); -#184085 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, +#186475 = CARTESIAN_POINT('',(-1.322326230316,-0.469247431202,1.)); +#186476 = CARTESIAN_POINT('',(-1.304265568045,-0.458821632546,1.)); +#186477 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, 0.967717466)); -#184086 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, +#186478 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, 0.986553421368)); -#184087 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); -#184088 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#184089 = DEFINITIONAL_REPRESENTATION('',(#184090),#184116); -#184090 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184091,#184092,#184093, - #184094,#184095,#184096,#184097,#184098,#184099,#184100,#184101, - #184102,#184103,#184104,#184105,#184106,#184107,#184108,#184109, - #184110,#184111,#184112,#184113,#184114,#184115),.UNSPECIFIED.,.F., +#186479 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); +#186480 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#186481 = DEFINITIONAL_REPRESENTATION('',(#186482),#186508); +#186482 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186483,#186484,#186485, + #186486,#186487,#186488,#186489,#186490,#186491,#186492,#186493, + #186494,#186495,#186496,#186497,#186498,#186499,#186500,#186501, + #186502,#186503,#186504,#186505,#186506,#186507),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.614007241618E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -228300,48 +231302,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#184091 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184092 = CARTESIAN_POINT('',(6.272059551128,2.972804133766E-006)); -#184093 = CARTESIAN_POINT('',(6.249732638972,-1.037052467445E-005)); -#184094 = CARTESIAN_POINT('',(6.216039360813,-5.446484095571E-005)); -#184095 = CARTESIAN_POINT('',(6.182166930891,-8.868396576175E-005)); -#184096 = CARTESIAN_POINT('',(6.148137469616,-7.965797689889E-005)); -#184097 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); -#184098 = CARTESIAN_POINT('',(6.079693755153,-8.179989506536E-005)); -#184099 = CARTESIAN_POINT('',(6.045320300361,-8.220472162591E-005)); -#184100 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); -#184101 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); -#184102 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); -#184103 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); -#184104 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); -#184105 = CARTESIAN_POINT('',(5.838159829417,-8.435280808233E-005)); -#184106 = CARTESIAN_POINT('',(5.803652201529,-8.485308627406E-005)); -#184107 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); -#184108 = CARTESIAN_POINT('',(5.734821280548,-8.593545386256E-005)); -#184109 = CARTESIAN_POINT('',(5.700537102675,-8.687395637433E-005)); -#184110 = CARTESIAN_POINT('',(5.666367464043,-8.643221197456E-005)); -#184111 = CARTESIAN_POINT('',(5.632333796953,-9.135814826506E-005)); -#184112 = CARTESIAN_POINT('',(5.59845580442,-3.211561474224E-005)); -#184113 = CARTESIAN_POINT('',(5.564759360754,-7.920681094116E-006)); -#184114 = CARTESIAN_POINT('',(5.542431620275,5.712075443838E-008)); -#184115 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184117 = PCURVE('',#184118,#184123); -#184118 = CYLINDRICAL_SURFACE('',#184119,0.15); -#184119 = AXIS2_PLACEMENT_3D('',#184120,#184121,#184122); -#184120 = CARTESIAN_POINT('',(-1.324207498814,-0.514207498814, +#186483 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186484 = CARTESIAN_POINT('',(6.272059551128,2.972804133766E-006)); +#186485 = CARTESIAN_POINT('',(6.249732638972,-1.037052467445E-005)); +#186486 = CARTESIAN_POINT('',(6.216039360813,-5.446484095571E-005)); +#186487 = CARTESIAN_POINT('',(6.182166930891,-8.868396576175E-005)); +#186488 = CARTESIAN_POINT('',(6.148137469616,-7.965797689889E-005)); +#186489 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); +#186490 = CARTESIAN_POINT('',(6.079693755153,-8.179989506536E-005)); +#186491 = CARTESIAN_POINT('',(6.045320300361,-8.220472162591E-005)); +#186492 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); +#186493 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); +#186494 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); +#186495 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); +#186496 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); +#186497 = CARTESIAN_POINT('',(5.838159829417,-8.435280808233E-005)); +#186498 = CARTESIAN_POINT('',(5.803652201529,-8.485308627406E-005)); +#186499 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); +#186500 = CARTESIAN_POINT('',(5.734821280548,-8.593545386256E-005)); +#186501 = CARTESIAN_POINT('',(5.700537102675,-8.687395637433E-005)); +#186502 = CARTESIAN_POINT('',(5.666367464043,-8.643221197456E-005)); +#186503 = CARTESIAN_POINT('',(5.632333796953,-9.135814826506E-005)); +#186504 = CARTESIAN_POINT('',(5.59845580442,-3.211561474224E-005)); +#186505 = CARTESIAN_POINT('',(5.564759360754,-7.920681094116E-006)); +#186506 = CARTESIAN_POINT('',(5.542431620275,5.712075443838E-008)); +#186507 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186509 = PCURVE('',#186510,#186515); +#186510 = CYLINDRICAL_SURFACE('',#186511,0.15); +#186511 = AXIS2_PLACEMENT_3D('',#186512,#186513,#186514); +#186512 = CARTESIAN_POINT('',(-1.324207498814,-0.514207498814, 0.527229017938)); -#184121 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) +#186513 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) ); -#184122 = DIRECTION('',(-0.965925826289,4.046106982444E-017, +#186514 = DIRECTION('',(-0.965925826289,4.046106982444E-017, 0.258819045103)); -#184123 = DEFINITIONAL_REPRESENTATION('',(#184124),#184150); -#184124 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184125,#184126,#184127, - #184128,#184129,#184130,#184131,#184132,#184133,#184134,#184135, - #184136,#184137,#184138,#184139,#184140,#184141,#184142,#184143, - #184144,#184145,#184146,#184147,#184148,#184149),.UNSPECIFIED.,.F., +#186515 = DEFINITIONAL_REPRESENTATION('',(#186516),#186542); +#186516 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186517,#186518,#186519, + #186520,#186521,#186522,#186523,#186524,#186525,#186526,#186527, + #186528,#186529,#186530,#186531,#186532,#186533,#186534,#186535, + #186536,#186537,#186538,#186539,#186540,#186541),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.614007241618E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -228350,50 +231352,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#184125 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); -#184126 = CARTESIAN_POINT('',(5.542431500119,-0.414213027833)); -#184127 = CARTESIAN_POINT('',(5.56475355,-0.414227119403)); -#184128 = CARTESIAN_POINT('',(5.598431528687,-0.414291190685)); -#184129 = CARTESIAN_POINT('',(5.632287045183,-0.414398842232)); -#184130 = CARTESIAN_POINT('',(5.666301906361,-0.414550528448)); -#184131 = CARTESIAN_POINT('',(5.700457442157,-0.414746569643)); -#184132 = CARTESIAN_POINT('',(5.734734482675,-0.414987129667)); -#184133 = CARTESIAN_POINT('',(5.76911344049,-0.41527221657)); -#184134 = CARTESIAN_POINT('',(5.803574369467,-0.415601678753)); -#184135 = CARTESIAN_POINT('',(5.838097033931,-0.415975204048)); -#184136 = CARTESIAN_POINT('',(5.872660978441,-0.416392319824)); -#184137 = CARTESIAN_POINT('',(5.907245600032,-0.416852394634)); -#184138 = CARTESIAN_POINT('',(5.941830221623,-0.417354641276)); -#184139 = CARTESIAN_POINT('',(5.976394166134,-0.41789812127)); -#184140 = CARTESIAN_POINT('',(6.010916830598,-0.418481750684)); -#184141 = CARTESIAN_POINT('',(6.045377759574,-0.419104307248)); -#184142 = CARTESIAN_POINT('',(6.079756717389,-0.419764438636)); -#184143 = CARTESIAN_POINT('',(6.114033757907,-0.420460671856)); -#184144 = CARTESIAN_POINT('',(6.148189293703,-0.421191423422)); -#184145 = CARTESIAN_POINT('',(6.182204154882,-0.421955010917)); -#184146 = CARTESIAN_POINT('',(6.216059671377,-0.422749662917)); -#184147 = CARTESIAN_POINT('',(6.249737650065,-0.423573537911)); -#184148 = CARTESIAN_POINT('',(6.272059699945,-0.424140987131)); -#184149 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); -#184150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184151 = ORIENTED_EDGE('',*,*,#184152,.T.); -#184152 = EDGE_CURVE('',#184061,#184153,#184155,.T.); -#184153 = VERTEX_POINT('',#184154); -#184154 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#184155 = SURFACE_CURVE('',#184156,(#184161,#184190),.PCURVE_S1.); -#184156 = CIRCLE('',#184157,5.E-002); -#184157 = AXIS2_PLACEMENT_3D('',#184158,#184159,#184160); -#184158 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,0.95)); -#184159 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#184160 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#184161 = PCURVE('',#184072,#184162); -#184162 = DEFINITIONAL_REPRESENTATION('',(#184163),#184189); -#184163 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184164,#184165,#184166, - #184167,#184168,#184169,#184170,#184171,#184172,#184173,#184174, - #184175,#184176,#184177,#184178,#184179,#184180,#184181,#184182, - #184183,#184184,#184185,#184186,#184187,#184188),.UNSPECIFIED.,.F., +#186517 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); +#186518 = CARTESIAN_POINT('',(5.542431500119,-0.414213027833)); +#186519 = CARTESIAN_POINT('',(5.56475355,-0.414227119403)); +#186520 = CARTESIAN_POINT('',(5.598431528687,-0.414291190685)); +#186521 = CARTESIAN_POINT('',(5.632287045183,-0.414398842232)); +#186522 = CARTESIAN_POINT('',(5.666301906361,-0.414550528448)); +#186523 = CARTESIAN_POINT('',(5.700457442157,-0.414746569643)); +#186524 = CARTESIAN_POINT('',(5.734734482675,-0.414987129667)); +#186525 = CARTESIAN_POINT('',(5.76911344049,-0.41527221657)); +#186526 = CARTESIAN_POINT('',(5.803574369467,-0.415601678753)); +#186527 = CARTESIAN_POINT('',(5.838097033931,-0.415975204048)); +#186528 = CARTESIAN_POINT('',(5.872660978441,-0.416392319824)); +#186529 = CARTESIAN_POINT('',(5.907245600032,-0.416852394634)); +#186530 = CARTESIAN_POINT('',(5.941830221623,-0.417354641276)); +#186531 = CARTESIAN_POINT('',(5.976394166134,-0.41789812127)); +#186532 = CARTESIAN_POINT('',(6.010916830598,-0.418481750684)); +#186533 = CARTESIAN_POINT('',(6.045377759574,-0.419104307248)); +#186534 = CARTESIAN_POINT('',(6.079756717389,-0.419764438636)); +#186535 = CARTESIAN_POINT('',(6.114033757907,-0.420460671856)); +#186536 = CARTESIAN_POINT('',(6.148189293703,-0.421191423422)); +#186537 = CARTESIAN_POINT('',(6.182204154882,-0.421955010917)); +#186538 = CARTESIAN_POINT('',(6.216059671377,-0.422749662917)); +#186539 = CARTESIAN_POINT('',(6.249737650065,-0.423573537911)); +#186540 = CARTESIAN_POINT('',(6.272059699945,-0.424140987131)); +#186541 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); +#186542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186543 = ORIENTED_EDGE('',*,*,#186544,.T.); +#186544 = EDGE_CURVE('',#186453,#186545,#186547,.T.); +#186545 = VERTEX_POINT('',#186546); +#186546 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#186547 = SURFACE_CURVE('',#186548,(#186553,#186582),.PCURVE_S1.); +#186548 = CIRCLE('',#186549,5.E-002); +#186549 = AXIS2_PLACEMENT_3D('',#186550,#186551,#186552); +#186550 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,0.95)); +#186551 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#186552 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#186553 = PCURVE('',#186464,#186554); +#186554 = DEFINITIONAL_REPRESENTATION('',(#186555),#186581); +#186555 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186556,#186557,#186558, + #186559,#186560,#186561,#186562,#186563,#186564,#186565,#186566, + #186567,#186568,#186569,#186570,#186571,#186572,#186573,#186574, + #186575,#186576,#186577,#186578,#186579,#186580),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -228401,71 +231403,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184164 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184165 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#184166 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#184167 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); -#184168 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#184169 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#184170 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#184171 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#184172 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#184173 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#184174 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#184175 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#184176 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#184177 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#184178 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#184179 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#184180 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#184181 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#184182 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#184183 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#184184 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#184185 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#184186 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#184187 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#184188 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184189 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184190 = PCURVE('',#184191,#184208); -#184191 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184192,#184193,#184194,#184195) - ,(#184196,#184197,#184198,#184199) - ,(#184200,#184201,#184202,#184203) - ,(#184204,#184205,#184206,#184207 +#186556 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186557 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#186558 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#186559 = CARTESIAN_POINT('',(6.28318530718,9.109101074357E-002)); +#186560 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#186561 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#186562 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#186563 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#186564 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#186565 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#186566 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#186567 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#186568 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#186569 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#186570 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#186571 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#186572 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#186573 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#186574 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#186575 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#186576 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#186577 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#186578 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#186579 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#186580 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186581 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186582 = PCURVE('',#186583,#186600); +#186583 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186584,#186585,#186586,#186587) + ,(#186588,#186589,#186590,#186591) + ,(#186592,#186593,#186594,#186595) + ,(#186596,#186597,#186598,#186599 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184192 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, +#186584 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, 0.967717466)); -#184193 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, +#186585 = CARTESIAN_POINT('',(-1.314557762914,-0.504557762914, 0.986553421368)); -#184194 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); -#184195 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#184196 = CARTESIAN_POINT('',(-1.293021890319,-0.536187793567, +#186586 = CARTESIAN_POINT('',(-1.300786830759,-0.490786830759,1.)); +#186587 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#186588 = CARTESIAN_POINT('',(-1.293021890319,-0.536187793567, 0.967717466)); -#184197 = CARTESIAN_POINT('',(-1.289327515655,-0.529788010173, +#186589 = CARTESIAN_POINT('',(-1.289327515655,-0.529788010173, 0.986553421368)); -#184198 = CARTESIAN_POINT('',(-1.279247431202,-0.512326230316,1.)); -#184199 = CARTESIAN_POINT('',(-1.268821632546,-0.494265568045,1.)); -#184200 = CARTESIAN_POINT('',(-1.255881450408,-0.551937603265, +#186590 = CARTESIAN_POINT('',(-1.279247431202,-0.512326230316,1.)); +#186591 = CARTESIAN_POINT('',(-1.268821632546,-0.494265568045,1.)); +#186592 = CARTESIAN_POINT('',(-1.255881450408,-0.551937603265, 0.965973846926)); -#184201 = CARTESIAN_POINT('',(-1.254463088209,-0.545238584914, +#186593 = CARTESIAN_POINT('',(-1.254463088209,-0.545238584914, 0.985681523985)); -#184202 = CARTESIAN_POINT('',(-1.249230002437,-0.525223961408,1.)); -#184203 = CARTESIAN_POINT('',(-1.243749871723,-0.504453973629,1.)); -#184204 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, +#186594 = CARTESIAN_POINT('',(-1.249230002437,-0.525223961408,1.)); +#186595 = CARTESIAN_POINT('',(-1.243749871723,-0.504453973629,1.)); +#186596 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, 0.962940952255)); -#184205 = CARTESIAN_POINT('',(-1.217861391,-0.547103709313, +#186597 = CARTESIAN_POINT('',(-1.217861391,-0.547103709313, 0.984014184754)); -#184206 = CARTESIAN_POINT('',(-1.217861391,-0.526270589279,1.)); -#184207 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#184208 = DEFINITIONAL_REPRESENTATION('',(#184209),#184235); -#184209 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184210,#184211,#184212, - #184213,#184214,#184215,#184216,#184217,#184218,#184219,#184220, - #184221,#184222,#184223,#184224,#184225,#184226,#184227,#184228, - #184229,#184230,#184231,#184232,#184233,#184234),.UNSPECIFIED.,.F., +#186598 = CARTESIAN_POINT('',(-1.217861391,-0.526270589279,1.)); +#186599 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#186600 = DEFINITIONAL_REPRESENTATION('',(#186601),#186627); +#186601 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186602,#186603,#186604, + #186605,#186606,#186607,#186608,#186609,#186610,#186611,#186612, + #186613,#186614,#186615,#186616,#186617,#186618,#186619,#186620, + #186621,#186622,#186623,#186624,#186625,#186626),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -228473,57 +231475,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184210 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#184211 = CARTESIAN_POINT('',(-7.405118739674E-017,1.515278164503E-002) - ); -#184212 = CARTESIAN_POINT('',(-3.985677504963E-016,4.549920749134E-002) - ); -#184213 = CARTESIAN_POINT('',(-1.580210697048E-016,9.109101074356E-002) - ); -#184214 = CARTESIAN_POINT('',(-1.134047533416E-015,0.136698748187)); -#184215 = CARTESIAN_POINT('',(-1.18401290745E-015,0.1822865144)); -#184216 = CARTESIAN_POINT('',(-4.407567392352E-016,0.2278300409)); -#184217 = CARTESIAN_POINT('',(-4.839912429467E-016,0.27331674602)); -#184218 = CARTESIAN_POINT('',(-1.491400225705E-015,0.318743220066)); -#184219 = CARTESIAN_POINT('',(-1.224284056902E-015,0.364113426255)); -#184220 = CARTESIAN_POINT('',(1.807913054958E-015,0.409436881051)); -#184221 = CARTESIAN_POINT('',(-2.245594212443E-015,0.454727066523)); -#184222 = CARTESIAN_POINT('',(-2.261564653344E-016,0.5)); -#184223 = CARTESIAN_POINT('',(8.823179217072E-016,0.545272933477)); -#184224 = CARTESIAN_POINT('',(-4.43084088851E-016,0.590563118949)); -#184225 = CARTESIAN_POINT('',(1.354931126903E-015,0.635886573745)); -#184226 = CARTESIAN_POINT('',(-1.161199682066E-015,0.681256779934)); -#184227 = CARTESIAN_POINT('',(6.31123117599E-016,0.72668325398)); -#184228 = CARTESIAN_POINT('',(1.538180390986E-015,0.7721699591)); -#184229 = CARTESIAN_POINT('',(1.66425983616E-015,0.8177134856)); -#184230 = CARTESIAN_POINT('',(1.570550897846E-015,0.863301251813)); -#184231 = CARTESIAN_POINT('',(9.673829897528E-016,0.908908989256)); -#184232 = CARTESIAN_POINT('',(3.957986323149E-016,0.954500792509)); -#184233 = CARTESIAN_POINT('',(2.701619826828E-016,0.984847218355)); -#184234 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#184235 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184236 = ORIENTED_EDGE('',*,*,#184237,.F.); -#184237 = EDGE_CURVE('',#184238,#184153,#184240,.T.); -#184238 = VERTEX_POINT('',#184239); -#184239 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#184240 = SURFACE_CURVE('',#184241,(#184246,#184275),.PCURVE_S1.); -#184241 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184242,#184243,#184244, -#184245),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186602 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#186603 = CARTESIAN_POINT('',(-7.405118739674E-017,1.515278164503E-002) + ); +#186604 = CARTESIAN_POINT('',(-3.985677504963E-016,4.549920749134E-002) + ); +#186605 = CARTESIAN_POINT('',(-1.580210697048E-016,9.109101074356E-002) + ); +#186606 = CARTESIAN_POINT('',(-1.134047533416E-015,0.136698748187)); +#186607 = CARTESIAN_POINT('',(-1.18401290745E-015,0.1822865144)); +#186608 = CARTESIAN_POINT('',(-4.407567392352E-016,0.2278300409)); +#186609 = CARTESIAN_POINT('',(-4.839912429467E-016,0.27331674602)); +#186610 = CARTESIAN_POINT('',(-1.491400225705E-015,0.318743220066)); +#186611 = CARTESIAN_POINT('',(-1.224284056902E-015,0.364113426255)); +#186612 = CARTESIAN_POINT('',(1.807913054958E-015,0.409436881051)); +#186613 = CARTESIAN_POINT('',(-2.245594212443E-015,0.454727066523)); +#186614 = CARTESIAN_POINT('',(-2.261564653344E-016,0.5)); +#186615 = CARTESIAN_POINT('',(8.823179217072E-016,0.545272933477)); +#186616 = CARTESIAN_POINT('',(-4.43084088851E-016,0.590563118949)); +#186617 = CARTESIAN_POINT('',(1.354931126903E-015,0.635886573745)); +#186618 = CARTESIAN_POINT('',(-1.161199682066E-015,0.681256779934)); +#186619 = CARTESIAN_POINT('',(6.31123117599E-016,0.72668325398)); +#186620 = CARTESIAN_POINT('',(1.538180390986E-015,0.7721699591)); +#186621 = CARTESIAN_POINT('',(1.66425983616E-015,0.8177134856)); +#186622 = CARTESIAN_POINT('',(1.570550897846E-015,0.863301251813)); +#186623 = CARTESIAN_POINT('',(9.673829897528E-016,0.908908989256)); +#186624 = CARTESIAN_POINT('',(3.957986323149E-016,0.954500792509)); +#186625 = CARTESIAN_POINT('',(2.701619826828E-016,0.984847218355)); +#186626 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#186627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186628 = ORIENTED_EDGE('',*,*,#186629,.F.); +#186629 = EDGE_CURVE('',#186630,#186545,#186632,.T.); +#186630 = VERTEX_POINT('',#186631); +#186631 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#186632 = SURFACE_CURVE('',#186633,(#186638,#186667),.PCURVE_S1.); +#186633 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186634,#186635,#186636, +#186637),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184242 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); -#184243 = CARTESIAN_POINT('',(-1.314453973629,-0.43437896527,1.)); -#184244 = CARTESIAN_POINT('',(-1.304696214234,-0.458390986358,1.)); -#184245 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#184246 = PCURVE('',#184072,#184247); -#184247 = DEFINITIONAL_REPRESENTATION('',(#184248),#184274); -#184248 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184249,#184250,#184251, - #184252,#184253,#184254,#184255,#184256,#184257,#184258,#184259, - #184260,#184261,#184262,#184263,#184264,#184265,#184266,#184267, - #184268,#184269,#184270,#184271,#184272,#184273),.UNSPECIFIED.,.F., +#186634 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,1.)); +#186635 = CARTESIAN_POINT('',(-1.314453973629,-0.43437896527,1.)); +#186636 = CARTESIAN_POINT('',(-1.304696214234,-0.458390986358,1.)); +#186637 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#186638 = PCURVE('',#186464,#186639); +#186639 = DEFINITIONAL_REPRESENTATION('',(#186640),#186666); +#186640 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186641,#186642,#186643, + #186644,#186645,#186646,#186647,#186648,#186649,#186650,#186651, + #186652,#186653,#186654,#186655,#186656,#186657,#186658,#186659, + #186660,#186661,#186662,#186663,#186664,#186665),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -228531,67 +231533,67 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#184249 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184250 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#184251 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#184252 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#184253 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#184254 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#184255 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#184256 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#184257 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#184258 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#184259 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#184260 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#184261 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#184262 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#184263 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#184264 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#184265 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#184266 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#184267 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#184268 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#184269 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#184270 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#184271 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#184272 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#184273 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184275 = PCURVE('',#184276,#184281); -#184276 = PLANE('',#184277); -#184277 = AXIS2_PLACEMENT_3D('',#184278,#184279,#184280); -#184278 = CARTESIAN_POINT('',(1.46,-0.65,1.)); -#184279 = DIRECTION('',(0.E+000,0.E+000,1.)); -#184280 = DIRECTION('',(1.,0.E+000,0.E+000)); -#184281 = DEFINITIONAL_REPRESENTATION('',(#184282),#184287); -#184282 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184283,#184284,#184285, -#184286),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186641 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186642 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#186643 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#186644 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#186645 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#186646 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#186647 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#186648 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#186649 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#186650 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#186651 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#186652 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#186653 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#186654 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#186655 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#186656 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#186657 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#186658 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#186659 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#186660 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#186661 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#186662 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#186663 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#186664 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#186665 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186667 = PCURVE('',#186668,#186673); +#186668 = PLANE('',#186669); +#186669 = AXIS2_PLACEMENT_3D('',#186670,#186671,#186672); +#186670 = CARTESIAN_POINT('',(1.46,-0.65,1.)); +#186671 = DIRECTION('',(0.E+000,0.E+000,1.)); +#186672 = DIRECTION('',(1.,0.E+000,0.E+000)); +#186673 = DEFINITIONAL_REPRESENTATION('',(#186674),#186679); +#186674 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186675,#186676,#186677, +#186678),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184283 = CARTESIAN_POINT('',(-2.774453973629,0.242138609)); -#184284 = CARTESIAN_POINT('',(-2.774453973629,0.21562103473)); -#184285 = CARTESIAN_POINT('',(-2.764696214234,0.191609013642)); -#184286 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); -#184287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184288 = ORIENTED_EDGE('',*,*,#184289,.T.); -#184289 = EDGE_CURVE('',#184238,#184063,#184290,.T.); -#184290 = SURFACE_CURVE('',#184291,(#184296,#184325),.PCURVE_S1.); -#184291 = CIRCLE('',#184292,5.E-002); -#184292 = AXIS2_PLACEMENT_3D('',#184293,#184294,#184295); -#184293 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,0.95)); -#184294 = DIRECTION('',(2.244897367846E-015,-1.,0.E+000)); -#184295 = DIRECTION('',(1.,2.244897367846E-015,0.E+000)); -#184296 = PCURVE('',#184072,#184297); -#184297 = DEFINITIONAL_REPRESENTATION('',(#184298),#184324); -#184298 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184299,#184300,#184301, - #184302,#184303,#184304,#184305,#184306,#184307,#184308,#184309, - #184310,#184311,#184312,#184313,#184314,#184315,#184316,#184317, - #184318,#184319,#184320,#184321,#184322,#184323),.UNSPECIFIED.,.F., +#186675 = CARTESIAN_POINT('',(-2.774453973629,0.242138609)); +#186676 = CARTESIAN_POINT('',(-2.774453973629,0.21562103473)); +#186677 = CARTESIAN_POINT('',(-2.764696214234,0.191609013642)); +#186678 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); +#186679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186680 = ORIENTED_EDGE('',*,*,#186681,.T.); +#186681 = EDGE_CURVE('',#186630,#186455,#186682,.T.); +#186682 = SURFACE_CURVE('',#186683,(#186688,#186717),.PCURVE_S1.); +#186683 = CIRCLE('',#186684,5.E-002); +#186684 = AXIS2_PLACEMENT_3D('',#186685,#186686,#186687); +#186685 = CARTESIAN_POINT('',(-1.314453973629,-0.407861391,0.95)); +#186686 = DIRECTION('',(2.244897367846E-015,-1.,0.E+000)); +#186687 = DIRECTION('',(1.,2.244897367846E-015,0.E+000)); +#186688 = PCURVE('',#186464,#186689); +#186689 = DEFINITIONAL_REPRESENTATION('',(#186690),#186716); +#186690 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186691,#186692,#186693, + #186694,#186695,#186696,#186697,#186698,#186699,#186700,#186701, + #186702,#186703,#186704,#186705,#186706,#186707,#186708,#186709, + #186710,#186711,#186712,#186713,#186714,#186715),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795, 1.630296187658,1.689796048522,1.749295909385,1.808795770249, 1.868295631112,1.927795491976,1.987295352839,2.046795213702, @@ -228599,45 +231601,45 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.34429451802,2.403794378883,2.463294239747,2.52279410061, 2.582293961473,2.641793822337,2.7012936832,2.760793544064, 2.820293404927,2.879793265791),.QUASI_UNIFORM_KNOTS.); -#184299 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184300 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#184301 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#184302 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#184303 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#184304 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#184305 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#184306 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#184307 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#184308 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#184309 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#184310 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#184311 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#184312 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#184313 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#184314 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#184315 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#184316 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#184317 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#184318 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#184319 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#184320 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#184321 = CARTESIAN_POINT('',(5.531305899752,4.551530551222E-002)); -#184322 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#184323 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184325 = PCURVE('',#184326,#184331); -#184326 = CYLINDRICAL_SURFACE('',#184327,5.E-002); -#184327 = AXIS2_PLACEMENT_3D('',#184328,#184329,#184330); -#184328 = CARTESIAN_POINT('',(-1.314453973629,-0.65,0.95)); -#184329 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#184330 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); -#184331 = DEFINITIONAL_REPRESENTATION('',(#184332),#184358); -#184332 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184333,#184334,#184335, - #184336,#184337,#184338,#184339,#184340,#184341,#184342,#184343, - #184344,#184345,#184346,#184347,#184348,#184349,#184350,#184351, - #184352,#184353,#184354,#184355,#184356,#184357),.UNSPECIFIED.,.F., +#186691 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186692 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#186693 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#186694 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#186695 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#186696 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#186697 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#186698 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#186699 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#186700 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#186701 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#186702 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#186703 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#186704 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#186705 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#186706 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#186707 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#186708 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#186709 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#186710 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#186711 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#186712 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#186713 = CARTESIAN_POINT('',(5.531305899752,4.551530551222E-002)); +#186714 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#186715 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186717 = PCURVE('',#186718,#186723); +#186718 = CYLINDRICAL_SURFACE('',#186719,5.E-002); +#186719 = AXIS2_PLACEMENT_3D('',#186720,#186721,#186722); +#186720 = CARTESIAN_POINT('',(-1.314453973629,-0.65,0.95)); +#186721 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#186722 = DIRECTION('',(1.,1.668003342285E-016,0.E+000)); +#186723 = DEFINITIONAL_REPRESENTATION('',(#186724),#186750); +#186724 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186725,#186726,#186727, + #186728,#186729,#186730,#186731,#186732,#186733,#186734,#186735, + #186736,#186737,#186738,#186739,#186740,#186741,#186742,#186743, + #186744,#186745,#186746,#186747,#186748,#186749),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.570796326795, 1.630296187658,1.689796048522,1.749295909385,1.808795770249, 1.868295631112,1.927795491976,1.987295352839,2.046795213702, @@ -228645,96 +231647,96 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.34429451802,2.403794378883,2.463294239747,2.52279410061, 2.582293961473,2.641793822337,2.7012936832,2.760793544064, 2.820293404927,2.879793265791),.QUASI_UNIFORM_KNOTS.); -#184333 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); -#184334 = CARTESIAN_POINT('',(1.590629613749,-0.242138609)); -#184335 = CARTESIAN_POINT('',(1.630296187658,-0.242138609)); -#184336 = CARTESIAN_POINT('',(1.689796048522,-0.242138609)); -#184337 = CARTESIAN_POINT('',(1.749295909385,-0.242138609)); -#184338 = CARTESIAN_POINT('',(1.808795770249,-0.242138609)); -#184339 = CARTESIAN_POINT('',(1.868295631112,-0.242138609)); -#184340 = CARTESIAN_POINT('',(1.927795491976,-0.242138609)); -#184341 = CARTESIAN_POINT('',(1.987295352839,-0.242138609)); -#184342 = CARTESIAN_POINT('',(2.046795213702,-0.242138609)); -#184343 = CARTESIAN_POINT('',(2.106295074566,-0.242138609)); -#184344 = CARTESIAN_POINT('',(2.165794935429,-0.242138609)); -#184345 = CARTESIAN_POINT('',(2.225294796293,-0.242138609)); -#184346 = CARTESIAN_POINT('',(2.284794657156,-0.242138609)); -#184347 = CARTESIAN_POINT('',(2.34429451802,-0.242138609)); -#184348 = CARTESIAN_POINT('',(2.403794378883,-0.242138609)); -#184349 = CARTESIAN_POINT('',(2.463294239747,-0.242138609)); -#184350 = CARTESIAN_POINT('',(2.52279410061,-0.242138609)); -#184351 = CARTESIAN_POINT('',(2.582293961473,-0.242138609)); -#184352 = CARTESIAN_POINT('',(2.641793822337,-0.242138609)); -#184353 = CARTESIAN_POINT('',(2.7012936832,-0.242138609)); -#184354 = CARTESIAN_POINT('',(2.760793544064,-0.242138609)); -#184355 = CARTESIAN_POINT('',(2.820293404927,-0.242138609)); -#184356 = CARTESIAN_POINT('',(2.859959978836,-0.242138609)); -#184357 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); -#184358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184359 = ADVANCED_FACE('',(#184360),#184375,.T.); -#184360 = FACE_BOUND('',#184361,.T.); -#184361 = EDGE_LOOP('',(#184362,#184454,#184539,#184586)); -#184362 = ORIENTED_EDGE('',*,*,#184363,.F.); -#184363 = EDGE_CURVE('',#184364,#184366,#184368,.T.); -#184364 = VERTEX_POINT('',#184365); -#184365 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 +#186725 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); +#186726 = CARTESIAN_POINT('',(1.590629613749,-0.242138609)); +#186727 = CARTESIAN_POINT('',(1.630296187658,-0.242138609)); +#186728 = CARTESIAN_POINT('',(1.689796048522,-0.242138609)); +#186729 = CARTESIAN_POINT('',(1.749295909385,-0.242138609)); +#186730 = CARTESIAN_POINT('',(1.808795770249,-0.242138609)); +#186731 = CARTESIAN_POINT('',(1.868295631112,-0.242138609)); +#186732 = CARTESIAN_POINT('',(1.927795491976,-0.242138609)); +#186733 = CARTESIAN_POINT('',(1.987295352839,-0.242138609)); +#186734 = CARTESIAN_POINT('',(2.046795213702,-0.242138609)); +#186735 = CARTESIAN_POINT('',(2.106295074566,-0.242138609)); +#186736 = CARTESIAN_POINT('',(2.165794935429,-0.242138609)); +#186737 = CARTESIAN_POINT('',(2.225294796293,-0.242138609)); +#186738 = CARTESIAN_POINT('',(2.284794657156,-0.242138609)); +#186739 = CARTESIAN_POINT('',(2.34429451802,-0.242138609)); +#186740 = CARTESIAN_POINT('',(2.403794378883,-0.242138609)); +#186741 = CARTESIAN_POINT('',(2.463294239747,-0.242138609)); +#186742 = CARTESIAN_POINT('',(2.52279410061,-0.242138609)); +#186743 = CARTESIAN_POINT('',(2.582293961473,-0.242138609)); +#186744 = CARTESIAN_POINT('',(2.641793822337,-0.242138609)); +#186745 = CARTESIAN_POINT('',(2.7012936832,-0.242138609)); +#186746 = CARTESIAN_POINT('',(2.760793544064,-0.242138609)); +#186747 = CARTESIAN_POINT('',(2.820293404927,-0.242138609)); +#186748 = CARTESIAN_POINT('',(2.859959978836,-0.242138609)); +#186749 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); +#186750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186751 = ADVANCED_FACE('',(#186752),#186767,.T.); +#186752 = FACE_BOUND('',#186753,.T.); +#186753 = EDGE_LOOP('',(#186754,#186846,#186931,#186978)); +#186754 = ORIENTED_EDGE('',*,*,#186755,.F.); +#186755 = EDGE_CURVE('',#186756,#186758,#186760,.T.); +#186756 = VERTEX_POINT('',#186757); +#186757 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 )); -#184366 = VERTEX_POINT('',#184367); -#184367 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 +#186758 = VERTEX_POINT('',#186759); +#186759 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 )); -#184368 = SURFACE_CURVE('',#184369,(#184374,#184420),.PCURVE_S1.); -#184369 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184370,#184371,#184372, -#184373),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#186760 = SURFACE_CURVE('',#186761,(#186766,#186812),.PCURVE_S1.); +#186761 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186762,#186763,#186764, +#186765),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184370 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 +#186762 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 )); -#184371 = CARTESIAN_POINT('',(1.292375921036,-0.53683376285,0.967717466) +#186763 = CARTESIAN_POINT('',(1.292375921036,-0.53683376285,0.967717466) ); -#184372 = CARTESIAN_POINT('',(1.25680534294,-0.551917855478, +#186764 = CARTESIAN_POINT('',(1.25680534294,-0.551917855478, 0.966047546673)); -#184373 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 +#186765 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 )); -#184374 = PCURVE('',#184375,#184392); -#184375 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184376,#184377,#184378,#184379) - ,(#184380,#184381,#184382,#184383) - ,(#184384,#184385,#184386,#184387) - ,(#184388,#184389,#184390,#184391 +#186766 = PCURVE('',#186767,#186784); +#186767 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186768,#186769,#186770,#186771) + ,(#186772,#186773,#186774,#186775) + ,(#186776,#186777,#186778,#186779) + ,(#186780,#186781,#186782,#186783 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184376 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 +#186768 = CARTESIAN_POINT('',(1.217861391,-0.552750264943,0.962940952255 )); -#184377 = CARTESIAN_POINT('',(1.217861391,-0.547103709313,0.984014184754 +#186769 = CARTESIAN_POINT('',(1.217861391,-0.547103709313,0.984014184754 )); -#184378 = CARTESIAN_POINT('',(1.217861391,-0.526270589279,1.)); -#184379 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#184380 = CARTESIAN_POINT('',(1.255881450408,-0.551937603265, +#186770 = CARTESIAN_POINT('',(1.217861391,-0.526270589279,1.)); +#186771 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#186772 = CARTESIAN_POINT('',(1.255881450408,-0.551937603265, 0.965973846926)); -#184381 = CARTESIAN_POINT('',(1.254463088209,-0.545238584914, +#186773 = CARTESIAN_POINT('',(1.254463088209,-0.545238584914, 0.985681523985)); -#184382 = CARTESIAN_POINT('',(1.249230002437,-0.525223961408,1.)); -#184383 = CARTESIAN_POINT('',(1.243749871723,-0.504453973629,1.)); -#184384 = CARTESIAN_POINT('',(1.293021890319,-0.536187793567,0.967717466 +#186774 = CARTESIAN_POINT('',(1.249230002437,-0.525223961408,1.)); +#186775 = CARTESIAN_POINT('',(1.243749871723,-0.504453973629,1.)); +#186776 = CARTESIAN_POINT('',(1.293021890319,-0.536187793567,0.967717466 )); -#184385 = CARTESIAN_POINT('',(1.289327515655,-0.529788010173, +#186777 = CARTESIAN_POINT('',(1.289327515655,-0.529788010173, 0.986553421368)); -#184386 = CARTESIAN_POINT('',(1.279247431202,-0.512326230316,1.)); -#184387 = CARTESIAN_POINT('',(1.268821632546,-0.494265568045,1.)); -#184388 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 +#186778 = CARTESIAN_POINT('',(1.279247431202,-0.512326230316,1.)); +#186779 = CARTESIAN_POINT('',(1.268821632546,-0.494265568045,1.)); +#186780 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 )); -#184389 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, +#186781 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, 0.986553421368)); -#184390 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); -#184391 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#184392 = DEFINITIONAL_REPRESENTATION('',(#184393),#184419); -#184393 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184394,#184395,#184396, - #184397,#184398,#184399,#184400,#184401,#184402,#184403,#184404, - #184405,#184406,#184407,#184408,#184409,#184410,#184411,#184412, - #184413,#184414,#184415,#184416,#184417,#184418),.UNSPECIFIED.,.F., +#186782 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); +#186783 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#186784 = DEFINITIONAL_REPRESENTATION('',(#186785),#186811); +#186785 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186786,#186787,#186788, + #186789,#186790,#186791,#186792,#186793,#186794,#186795,#186796, + #186797,#186798,#186799,#186800,#186801,#186802,#186803,#186804, + #186805,#186806,#186807,#186808,#186809,#186810),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -228742,48 +231744,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#184394 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184395 = CARTESIAN_POINT('',(6.272059551128,2.972804133168E-006)); -#184396 = CARTESIAN_POINT('',(6.249732638972,-1.037052467567E-005)); -#184397 = CARTESIAN_POINT('',(6.216039360813,-5.446484095684E-005)); -#184398 = CARTESIAN_POINT('',(6.182166930891,-8.868396576145E-005)); -#184399 = CARTESIAN_POINT('',(6.148137469616,-7.965797689896E-005)); -#184400 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); -#184401 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); -#184402 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#184403 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); -#184404 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#184405 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#184406 = CARTESIAN_POINT('',(5.907265074214,-8.346461194622E-005)); -#184407 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); -#184408 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#184409 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); -#184410 = CARTESIAN_POINT('',(5.769199593774,-8.542361824739E-005)); -#184411 = CARTESIAN_POINT('',(5.734821280547,-8.593542635488E-005)); -#184412 = CARTESIAN_POINT('',(5.700537102678,-8.687405903438E-005)); -#184413 = CARTESIAN_POINT('',(5.666367464031,-8.643182884201E-005)); -#184414 = CARTESIAN_POINT('',(5.632333796998,-9.13595781352E-005)); -#184415 = CARTESIAN_POINT('',(5.598455804408,-3.211524037865E-005)); -#184416 = CARTESIAN_POINT('',(5.564759360757,-7.920748676221E-006)); -#184417 = CARTESIAN_POINT('',(5.542431620278,5.702886411975E-008)); -#184418 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184420 = PCURVE('',#184421,#184426); -#184421 = CYLINDRICAL_SURFACE('',#184422,0.15); -#184422 = AXIS2_PLACEMENT_3D('',#184423,#184424,#184425); -#184423 = CARTESIAN_POINT('',(1.242591262431,-0.432591262431, +#186786 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186787 = CARTESIAN_POINT('',(6.272059551128,2.972804133168E-006)); +#186788 = CARTESIAN_POINT('',(6.249732638972,-1.037052467567E-005)); +#186789 = CARTESIAN_POINT('',(6.216039360813,-5.446484095684E-005)); +#186790 = CARTESIAN_POINT('',(6.182166930891,-8.868396576145E-005)); +#186791 = CARTESIAN_POINT('',(6.148137469616,-7.965797689896E-005)); +#186792 = CARTESIAN_POINT('',(6.113972837442,-8.226451401248E-005)); +#186793 = CARTESIAN_POINT('',(6.079693755153,-8.179989506531E-005)); +#186794 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#186795 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); +#186796 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#186797 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#186798 = CARTESIAN_POINT('',(5.907265074214,-8.346461194622E-005)); +#186799 = CARTESIAN_POINT('',(5.872703630927,-8.388702468128E-005)); +#186800 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#186801 = CARTESIAN_POINT('',(5.803652201529,-8.485308429909E-005)); +#186802 = CARTESIAN_POINT('',(5.769199593774,-8.542361824739E-005)); +#186803 = CARTESIAN_POINT('',(5.734821280547,-8.593542635488E-005)); +#186804 = CARTESIAN_POINT('',(5.700537102678,-8.687405903438E-005)); +#186805 = CARTESIAN_POINT('',(5.666367464031,-8.643182884201E-005)); +#186806 = CARTESIAN_POINT('',(5.632333796998,-9.13595781352E-005)); +#186807 = CARTESIAN_POINT('',(5.598455804408,-3.211524037865E-005)); +#186808 = CARTESIAN_POINT('',(5.564759360757,-7.920748676221E-006)); +#186809 = CARTESIAN_POINT('',(5.542431620278,5.702886411975E-008)); +#186810 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186812 = PCURVE('',#186813,#186818); +#186813 = CYLINDRICAL_SURFACE('',#186814,0.15); +#186814 = AXIS2_PLACEMENT_3D('',#186815,#186816,#186817); +#186815 = CARTESIAN_POINT('',(1.242591262431,-0.432591262431, 0.831824958842)); -#184424 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) +#186816 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) ); -#184425 = DIRECTION('',(-0.965925826289,1.229180331738E-016, +#186817 = DIRECTION('',(-0.965925826289,1.229180331738E-016, -0.258819045103)); -#184426 = DEFINITIONAL_REPRESENTATION('',(#184427),#184453); -#184427 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184428,#184429,#184430, - #184431,#184432,#184433,#184434,#184435,#184436,#184437,#184438, - #184439,#184440,#184441,#184442,#184443,#184444,#184445,#184446, - #184447,#184448,#184449,#184450,#184451,#184452),.UNSPECIFIED.,.F., +#186818 = DEFINITIONAL_REPRESENTATION('',(#186819),#186845); +#186819 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186820,#186821,#186822, + #186823,#186824,#186825,#186826,#186827,#186828,#186829,#186830, + #186831,#186832,#186833,#186834,#186835,#186836,#186837,#186838, + #186839,#186840,#186841,#186842,#186843,#186844),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -228791,50 +231793,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#184428 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); -#184429 = CARTESIAN_POINT('',(3.90459767512,-8.848137862171E-002)); -#184430 = CARTESIAN_POINT('',(3.926919725,-8.849547019148E-002)); -#184431 = CARTESIAN_POINT('',(3.960597703687,-8.855954147362E-002)); -#184432 = CARTESIAN_POINT('',(3.994453220183,-8.866719302101E-002)); -#184433 = CARTESIAN_POINT('',(4.028468081361,-8.881887923673E-002)); -#184434 = CARTESIAN_POINT('',(4.062623617158,-8.901492043166E-002)); -#184435 = CARTESIAN_POINT('',(4.096900657675,-8.92554804551E-002)); -#184436 = CARTESIAN_POINT('',(4.13127961549,-8.954056735899E-002)); -#184437 = CARTESIAN_POINT('',(4.165740544467,-8.987002954109E-002)); -#184438 = CARTESIAN_POINT('',(4.200263208931,-9.024355483614E-002)); -#184439 = CARTESIAN_POINT('',(4.234827153442,-9.066067061216E-002)); -#184440 = CARTESIAN_POINT('',(4.269411775032,-9.112074542238E-002)); -#184441 = CARTESIAN_POINT('',(4.303996396623,-9.162299206488E-002)); -#184442 = CARTESIAN_POINT('',(4.338560341134,-9.216647205879E-002)); -#184443 = CARTESIAN_POINT('',(4.373083005598,-9.275010147284E-002)); -#184444 = CARTESIAN_POINT('',(4.407543934574,-9.337265803686E-002)); -#184445 = CARTESIAN_POINT('',(4.44192289239,-9.403278942409E-002)); -#184446 = CARTESIAN_POINT('',(4.476199932907,-9.472902264469E-002)); -#184447 = CARTESIAN_POINT('',(4.510355468703,-9.545977421098E-002)); -#184448 = CARTESIAN_POINT('',(4.544370329882,-9.622336170581E-002)); -#184449 = CARTESIAN_POINT('',(4.578225846377,-9.701801370533E-002)); -#184450 = CARTESIAN_POINT('',(4.611903825065,-9.78418886995E-002)); -#184451 = CARTESIAN_POINT('',(4.634225874945,-9.840933791906E-002)); -#184452 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); -#184453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184454 = ORIENTED_EDGE('',*,*,#184455,.T.); -#184455 = EDGE_CURVE('',#184364,#184456,#184458,.T.); -#184456 = VERTEX_POINT('',#184457); -#184457 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#184458 = SURFACE_CURVE('',#184459,(#184464,#184493),.PCURVE_S1.); -#184459 = CIRCLE('',#184460,5.E-002); -#184460 = AXIS2_PLACEMENT_3D('',#184461,#184462,#184463); -#184461 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,0.95)); -#184462 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); -#184463 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#184464 = PCURVE('',#184375,#184465); -#184465 = DEFINITIONAL_REPRESENTATION('',(#184466),#184492); -#184466 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184467,#184468,#184469, - #184470,#184471,#184472,#184473,#184474,#184475,#184476,#184477, - #184478,#184479,#184480,#184481,#184482,#184483,#184484,#184485, - #184486,#184487,#184488,#184489,#184490,#184491),.UNSPECIFIED.,.F., +#186820 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); +#186821 = CARTESIAN_POINT('',(3.90459767512,-8.848137862171E-002)); +#186822 = CARTESIAN_POINT('',(3.926919725,-8.849547019148E-002)); +#186823 = CARTESIAN_POINT('',(3.960597703687,-8.855954147362E-002)); +#186824 = CARTESIAN_POINT('',(3.994453220183,-8.866719302101E-002)); +#186825 = CARTESIAN_POINT('',(4.028468081361,-8.881887923673E-002)); +#186826 = CARTESIAN_POINT('',(4.062623617158,-8.901492043166E-002)); +#186827 = CARTESIAN_POINT('',(4.096900657675,-8.92554804551E-002)); +#186828 = CARTESIAN_POINT('',(4.13127961549,-8.954056735899E-002)); +#186829 = CARTESIAN_POINT('',(4.165740544467,-8.987002954109E-002)); +#186830 = CARTESIAN_POINT('',(4.200263208931,-9.024355483614E-002)); +#186831 = CARTESIAN_POINT('',(4.234827153442,-9.066067061216E-002)); +#186832 = CARTESIAN_POINT('',(4.269411775032,-9.112074542238E-002)); +#186833 = CARTESIAN_POINT('',(4.303996396623,-9.162299206488E-002)); +#186834 = CARTESIAN_POINT('',(4.338560341134,-9.216647205879E-002)); +#186835 = CARTESIAN_POINT('',(4.373083005598,-9.275010147284E-002)); +#186836 = CARTESIAN_POINT('',(4.407543934574,-9.337265803686E-002)); +#186837 = CARTESIAN_POINT('',(4.44192289239,-9.403278942409E-002)); +#186838 = CARTESIAN_POINT('',(4.476199932907,-9.472902264469E-002)); +#186839 = CARTESIAN_POINT('',(4.510355468703,-9.545977421098E-002)); +#186840 = CARTESIAN_POINT('',(4.544370329882,-9.622336170581E-002)); +#186841 = CARTESIAN_POINT('',(4.578225846377,-9.701801370533E-002)); +#186842 = CARTESIAN_POINT('',(4.611903825065,-9.78418886995E-002)); +#186843 = CARTESIAN_POINT('',(4.634225874945,-9.840933791906E-002)); +#186844 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); +#186845 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186846 = ORIENTED_EDGE('',*,*,#186847,.T.); +#186847 = EDGE_CURVE('',#186756,#186848,#186850,.T.); +#186848 = VERTEX_POINT('',#186849); +#186849 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#186850 = SURFACE_CURVE('',#186851,(#186856,#186885),.PCURVE_S1.); +#186851 = CIRCLE('',#186852,5.E-002); +#186852 = AXIS2_PLACEMENT_3D('',#186853,#186854,#186855); +#186853 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,0.95)); +#186854 = DIRECTION('',(-0.707106781187,-0.707106781187,0.E+000)); +#186855 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#186856 = PCURVE('',#186767,#186857); +#186857 = DEFINITIONAL_REPRESENTATION('',(#186858),#186884); +#186858 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186859,#186860,#186861, + #186862,#186863,#186864,#186865,#186866,#186867,#186868,#186869, + #186870,#186871,#186872,#186873,#186874,#186875,#186876,#186877, + #186878,#186879,#186880,#186881,#186882,#186883),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -228842,71 +231844,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184467 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184468 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#184469 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#184470 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#184471 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#184472 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#184473 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#184474 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#184475 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#184476 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#184477 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#184478 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#184479 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#184480 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#184481 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#184482 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#184483 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#184484 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#184485 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#184486 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#184487 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#184488 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#184489 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#184490 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#184491 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184493 = PCURVE('',#184494,#184511); -#184494 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184495,#184496,#184497,#184498) - ,(#184499,#184500,#184501,#184502) - ,(#184503,#184504,#184505,#184506) - ,(#184507,#184508,#184509,#184510 +#186859 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#186860 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#186861 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#186862 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#186863 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#186864 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#186865 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#186866 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#186867 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#186868 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#186869 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#186870 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#186871 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#186872 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#186873 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#186874 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#186875 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#186876 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#186877 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#186878 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#186879 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#186880 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#186881 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#186882 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#186883 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186885 = PCURVE('',#186886,#186903); +#186886 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#186887,#186888,#186889,#186890) + ,(#186891,#186892,#186893,#186894) + ,(#186895,#186896,#186897,#186898) + ,(#186899,#186900,#186901,#186902 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184495 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 +#186887 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 )); -#184496 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, +#186888 = CARTESIAN_POINT('',(1.314557762914,-0.504557762914, 0.986553421368)); -#184497 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); -#184498 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#184499 = CARTESIAN_POINT('',(1.346187793567,-0.483021890319,0.967717466 +#186889 = CARTESIAN_POINT('',(1.300786830759,-0.490786830759,1.)); +#186890 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#186891 = CARTESIAN_POINT('',(1.346187793567,-0.483021890319,0.967717466 )); -#184500 = CARTESIAN_POINT('',(1.339788010173,-0.479327515655, +#186892 = CARTESIAN_POINT('',(1.339788010173,-0.479327515655, 0.986553421368)); -#184501 = CARTESIAN_POINT('',(1.322326230316,-0.469247431202,1.)); -#184502 = CARTESIAN_POINT('',(1.304265568045,-0.458821632546,1.)); -#184503 = CARTESIAN_POINT('',(1.361937603265,-0.445881450408, +#186893 = CARTESIAN_POINT('',(1.322326230316,-0.469247431202,1.)); +#186894 = CARTESIAN_POINT('',(1.304265568045,-0.458821632546,1.)); +#186895 = CARTESIAN_POINT('',(1.361937603265,-0.445881450408, 0.965973846926)); -#184504 = CARTESIAN_POINT('',(1.355238584914,-0.444463088209, +#186896 = CARTESIAN_POINT('',(1.355238584914,-0.444463088209, 0.985681523985)); -#184505 = CARTESIAN_POINT('',(1.335223961408,-0.439230002437,1.)); -#184506 = CARTESIAN_POINT('',(1.314453973629,-0.433749871723,1.)); -#184507 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 +#186897 = CARTESIAN_POINT('',(1.335223961408,-0.439230002437,1.)); +#186898 = CARTESIAN_POINT('',(1.314453973629,-0.433749871723,1.)); +#186899 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 )); -#184508 = CARTESIAN_POINT('',(1.357103709313,-0.407861391,0.984014184754 +#186900 = CARTESIAN_POINT('',(1.357103709313,-0.407861391,0.984014184754 )); -#184509 = CARTESIAN_POINT('',(1.336270589279,-0.407861391,1.)); -#184510 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#184511 = DEFINITIONAL_REPRESENTATION('',(#184512),#184538); -#184512 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184513,#184514,#184515, - #184516,#184517,#184518,#184519,#184520,#184521,#184522,#184523, - #184524,#184525,#184526,#184527,#184528,#184529,#184530,#184531, - #184532,#184533,#184534,#184535,#184536,#184537),.UNSPECIFIED.,.F., +#186901 = CARTESIAN_POINT('',(1.336270589279,-0.407861391,1.)); +#186902 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#186903 = DEFINITIONAL_REPRESENTATION('',(#186904),#186930); +#186904 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186905,#186906,#186907, + #186908,#186909,#186910,#186911,#186912,#186913,#186914,#186915, + #186916,#186917,#186918,#186919,#186920,#186921,#186922,#186923, + #186924,#186925,#186926,#186927,#186928,#186929),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -228914,56 +231916,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184513 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#184514 = CARTESIAN_POINT('',(-1.392688852623E-015,1.515278164503E-002) - ); -#184515 = CARTESIAN_POINT('',(-9.628449452701E-016,4.549920749135E-002) - ); -#184516 = CARTESIAN_POINT('',(1.739110110531E-015,9.109101074357E-002)); -#184517 = CARTESIAN_POINT('',(-1.724871081711E-015,0.136698748187)); -#184518 = CARTESIAN_POINT('',(1.295107148168E-015,0.1822865144)); -#184519 = CARTESIAN_POINT('',(8.060381873871E-016,0.2278300409)); -#184520 = CARTESIAN_POINT('',(-2.06538645198E-015,0.27331674602)); -#184521 = CARTESIAN_POINT('',(1.379945602909E-015,0.318743220066)); -#184522 = CARTESIAN_POINT('',(-1.19027085225E-015,0.364113426255)); -#184523 = CARTESIAN_POINT('',(1.647771114557E-016,0.409436881051)); -#184524 = CARTESIAN_POINT('',(4.913799127153E-016,0.454727066523)); -#184525 = CARTESIAN_POINT('',(8.971598177169E-016,0.5)); -#184526 = CARTESIAN_POINT('',(1.340550616274E-016,0.545272933477)); -#184527 = CARTESIAN_POINT('',(2.524318819079E-016,0.590563118949)); -#184528 = CARTESIAN_POINT('',(1.690560413567E-015,0.635886573745)); -#184529 = CARTESIAN_POINT('',(7.375212679738E-016,0.681256779934)); -#184530 = CARTESIAN_POINT('',(-1.835607109901E-015,0.72668325398)); -#184531 = CARTESIAN_POINT('',(2.426164767721E-015,0.7721699591)); -#184532 = CARTESIAN_POINT('',(1.519062126208E-015,0.8177134856)); -#184533 = CARTESIAN_POINT('',(1.783037821893E-015,0.863301251813)); -#184534 = CARTESIAN_POINT('',(3.621548057198E-016,0.908908989256)); -#184535 = CARTESIAN_POINT('',(5.998332923287E-017,0.954500792509)); -#184536 = CARTESIAN_POINT('',(-4.765899297509E-016,0.984847218355)); -#184537 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#184538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184539 = ORIENTED_EDGE('',*,*,#184540,.F.); -#184540 = EDGE_CURVE('',#184541,#184456,#184543,.T.); -#184541 = VERTEX_POINT('',#184542); -#184542 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#184543 = SURFACE_CURVE('',#184544,(#184549,#184578),.PCURVE_S1.); -#184544 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184545,#184546,#184547, -#184548),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186905 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#186906 = CARTESIAN_POINT('',(-1.392688852623E-015,1.515278164503E-002) + ); +#186907 = CARTESIAN_POINT('',(-9.628449452701E-016,4.549920749135E-002) + ); +#186908 = CARTESIAN_POINT('',(1.739110110531E-015,9.109101074357E-002)); +#186909 = CARTESIAN_POINT('',(-1.724871081711E-015,0.136698748187)); +#186910 = CARTESIAN_POINT('',(1.295107148168E-015,0.1822865144)); +#186911 = CARTESIAN_POINT('',(8.060381873871E-016,0.2278300409)); +#186912 = CARTESIAN_POINT('',(-2.06538645198E-015,0.27331674602)); +#186913 = CARTESIAN_POINT('',(1.379945602909E-015,0.318743220066)); +#186914 = CARTESIAN_POINT('',(-1.19027085225E-015,0.364113426255)); +#186915 = CARTESIAN_POINT('',(1.647771114557E-016,0.409436881051)); +#186916 = CARTESIAN_POINT('',(4.913799127153E-016,0.454727066523)); +#186917 = CARTESIAN_POINT('',(8.971598177169E-016,0.5)); +#186918 = CARTESIAN_POINT('',(1.340550616274E-016,0.545272933477)); +#186919 = CARTESIAN_POINT('',(2.524318819079E-016,0.590563118949)); +#186920 = CARTESIAN_POINT('',(1.690560413567E-015,0.635886573745)); +#186921 = CARTESIAN_POINT('',(7.375212679738E-016,0.681256779934)); +#186922 = CARTESIAN_POINT('',(-1.835607109901E-015,0.72668325398)); +#186923 = CARTESIAN_POINT('',(2.426164767721E-015,0.7721699591)); +#186924 = CARTESIAN_POINT('',(1.519062126208E-015,0.8177134856)); +#186925 = CARTESIAN_POINT('',(1.783037821893E-015,0.863301251813)); +#186926 = CARTESIAN_POINT('',(3.621548057198E-016,0.908908989256)); +#186927 = CARTESIAN_POINT('',(5.998332923287E-017,0.954500792509)); +#186928 = CARTESIAN_POINT('',(-4.765899297509E-016,0.984847218355)); +#186929 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#186930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186931 = ORIENTED_EDGE('',*,*,#186932,.F.); +#186932 = EDGE_CURVE('',#186933,#186848,#186935,.T.); +#186933 = VERTEX_POINT('',#186934); +#186934 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#186935 = SURFACE_CURVE('',#186936,(#186941,#186970),.PCURVE_S1.); +#186936 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186937,#186938,#186939, +#186940),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184545 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); -#184546 = CARTESIAN_POINT('',(1.24437896527,-0.504453973629,1.)); -#184547 = CARTESIAN_POINT('',(1.268390986358,-0.494696214234,1.)); -#184548 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#184549 = PCURVE('',#184375,#184550); -#184550 = DEFINITIONAL_REPRESENTATION('',(#184551),#184577); -#184551 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184552,#184553,#184554, - #184555,#184556,#184557,#184558,#184559,#184560,#184561,#184562, - #184563,#184564,#184565,#184566,#184567,#184568,#184569,#184570, - #184571,#184572,#184573,#184574,#184575,#184576),.UNSPECIFIED.,.F., +#186937 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,1.)); +#186938 = CARTESIAN_POINT('',(1.24437896527,-0.504453973629,1.)); +#186939 = CARTESIAN_POINT('',(1.268390986358,-0.494696214234,1.)); +#186940 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#186941 = PCURVE('',#186767,#186942); +#186942 = DEFINITIONAL_REPRESENTATION('',(#186943),#186969); +#186943 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186944,#186945,#186946, + #186947,#186948,#186949,#186950,#186951,#186952,#186953,#186954, + #186955,#186956,#186957,#186958,#186959,#186960,#186961,#186962, + #186963,#186964,#186965,#186966,#186967,#186968),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -228971,62 +231973,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#184552 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184553 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#184554 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#184555 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#184556 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#184557 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#184558 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#184559 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#184560 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#184561 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#184562 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#184563 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#184564 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#184565 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#184566 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#184567 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#184568 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#184569 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#184570 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#184571 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#184572 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#184573 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#184574 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#184575 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#184576 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184578 = PCURVE('',#184276,#184579); -#184579 = DEFINITIONAL_REPRESENTATION('',(#184580),#184585); -#184580 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184581,#184582,#184583, -#184584),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#186944 = CARTESIAN_POINT('',(5.531305892885,1.)); +#186945 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#186946 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#186947 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#186948 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#186949 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#186950 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#186951 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#186952 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#186953 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#186954 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#186955 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#186956 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#186957 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#186958 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#186959 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#186960 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#186961 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#186962 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#186963 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#186964 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#186965 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#186966 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#186967 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#186968 = CARTESIAN_POINT('',(6.28318530718,1.)); +#186969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186970 = PCURVE('',#186668,#186971); +#186971 = DEFINITIONAL_REPRESENTATION('',(#186972),#186977); +#186972 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186973,#186974,#186975, +#186976),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184581 = CARTESIAN_POINT('',(-0.242138609,0.145546026371)); -#184582 = CARTESIAN_POINT('',(-0.21562103473,0.145546026371)); -#184583 = CARTESIAN_POINT('',(-0.191609013642,0.155303785766)); -#184584 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); -#184585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184586 = ORIENTED_EDGE('',*,*,#184587,.F.); -#184587 = EDGE_CURVE('',#184366,#184541,#184588,.T.); -#184588 = SURFACE_CURVE('',#184589,(#184594,#184623),.PCURVE_S1.); -#184589 = CIRCLE('',#184590,5.E-002); -#184590 = AXIS2_PLACEMENT_3D('',#184591,#184592,#184593); -#184591 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,0.95)); -#184592 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#184593 = DIRECTION('',(0.E+000,0.E+000,1.)); -#184594 = PCURVE('',#184375,#184595); -#184595 = DEFINITIONAL_REPRESENTATION('',(#184596),#184622); -#184596 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184597,#184598,#184599, - #184600,#184601,#184602,#184603,#184604,#184605,#184606,#184607, - #184608,#184609,#184610,#184611,#184612,#184613,#184614,#184615, - #184616,#184617,#184618,#184619,#184620,#184621),.UNSPECIFIED.,.F., +#186973 = CARTESIAN_POINT('',(-0.242138609,0.145546026371)); +#186974 = CARTESIAN_POINT('',(-0.21562103473,0.145546026371)); +#186975 = CARTESIAN_POINT('',(-0.191609013642,0.155303785766)); +#186976 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); +#186977 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#186978 = ORIENTED_EDGE('',*,*,#186979,.F.); +#186979 = EDGE_CURVE('',#186758,#186933,#186980,.T.); +#186980 = SURFACE_CURVE('',#186981,(#186986,#187015),.PCURVE_S1.); +#186981 = CIRCLE('',#186982,5.E-002); +#186982 = AXIS2_PLACEMENT_3D('',#186983,#186984,#186985); +#186983 = CARTESIAN_POINT('',(1.217861391,-0.504453973629,0.95)); +#186984 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#186985 = DIRECTION('',(0.E+000,0.E+000,1.)); +#186986 = PCURVE('',#186767,#186987); +#186987 = DEFINITIONAL_REPRESENTATION('',(#186988),#187014); +#186988 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186989,#186990,#186991, + #186992,#186993,#186994,#186995,#186996,#186997,#186998,#186999, + #187000,#187001,#187002,#187003,#187004,#187005,#187006,#187007, + #187008,#187009,#187010,#187011,#187012,#187013),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -229034,111 +232036,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#184597 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184598 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#184599 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#184600 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#184601 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#184602 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#184603 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#184604 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#184605 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#184606 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#184607 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#184608 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#184609 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#184610 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#184611 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); -#184612 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#184613 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#184614 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#184615 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#184616 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#184617 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#184618 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#184619 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#184620 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#184621 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184622 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184623 = PCURVE('',#184624,#184629); -#184624 = CYLINDRICAL_SURFACE('',#184625,5.E-002); -#184625 = AXIS2_PLACEMENT_3D('',#184626,#184627,#184628); -#184626 = CARTESIAN_POINT('',(1.46,-0.504453973629,0.95)); -#184627 = DIRECTION('',(1.,0.E+000,0.E+000)); -#184628 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#184629 = DEFINITIONAL_REPRESENTATION('',(#184630),#184633); -#184630 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184631,#184632), +#186989 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#186990 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#186991 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#186992 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#186993 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#186994 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#186995 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#186996 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#186997 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#186998 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#186999 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#187000 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#187001 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#187002 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#187003 = CARTESIAN_POINT('',(5.531310456365,0.590441482182)); +#187004 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#187005 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#187006 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#187007 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#187008 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#187009 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#187010 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#187011 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#187012 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#187013 = CARTESIAN_POINT('',(5.531305892885,1.)); +#187014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187015 = PCURVE('',#187016,#187021); +#187016 = CYLINDRICAL_SURFACE('',#187017,5.E-002); +#187017 = AXIS2_PLACEMENT_3D('',#187018,#187019,#187020); +#187018 = CARTESIAN_POINT('',(1.46,-0.504453973629,0.95)); +#187019 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187020 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#187021 = DEFINITIONAL_REPRESENTATION('',(#187022),#187025); +#187022 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187023,#187024), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#184631 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); -#184632 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); -#184633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187023 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); +#187024 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); +#187025 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#184634 = ADVANCED_FACE('',(#184635),#184650,.T.); -#184635 = FACE_BOUND('',#184636,.T.); -#184636 = EDGE_LOOP('',(#184637,#184729,#184814,#184861)); -#184637 = ORIENTED_EDGE('',*,*,#184638,.F.); -#184638 = EDGE_CURVE('',#184639,#184641,#184643,.T.); -#184639 = VERTEX_POINT('',#184640); -#184640 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 +#187026 = ADVANCED_FACE('',(#187027),#187042,.T.); +#187027 = FACE_BOUND('',#187028,.T.); +#187028 = EDGE_LOOP('',(#187029,#187121,#187206,#187253)); +#187029 = ORIENTED_EDGE('',*,*,#187030,.F.); +#187030 = EDGE_CURVE('',#187031,#187033,#187035,.T.); +#187031 = VERTEX_POINT('',#187032); +#187032 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 )); -#184641 = VERTEX_POINT('',#184642); -#184642 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 +#187033 = VERTEX_POINT('',#187034); +#187034 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 )); -#184643 = SURFACE_CURVE('',#184644,(#184649,#184695),.PCURVE_S1.); -#184644 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184645,#184646,#184647, -#184648),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#187035 = SURFACE_CURVE('',#187036,(#187041,#187087),.PCURVE_S1.); +#187036 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187037,#187038,#187039, +#187040),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184645 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 +#187037 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 )); -#184646 = CARTESIAN_POINT('',(-1.292375921036,0.53683376285,0.967717466) +#187038 = CARTESIAN_POINT('',(-1.292375921036,0.53683376285,0.967717466) ); -#184647 = CARTESIAN_POINT('',(-1.25680534294,0.551917855478, +#187039 = CARTESIAN_POINT('',(-1.25680534294,0.551917855478, 0.966047546673)); -#184648 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 +#187040 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 )); -#184649 = PCURVE('',#184650,#184667); -#184650 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184651,#184652,#184653,#184654) - ,(#184655,#184656,#184657,#184658) - ,(#184659,#184660,#184661,#184662) - ,(#184663,#184664,#184665,#184666 +#187041 = PCURVE('',#187042,#187059); +#187042 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#187043,#187044,#187045,#187046) + ,(#187047,#187048,#187049,#187050) + ,(#187051,#187052,#187053,#187054) + ,(#187055,#187056,#187057,#187058 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184651 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 +#187043 = CARTESIAN_POINT('',(-1.217861391,0.552750264943,0.962940952255 )); -#184652 = CARTESIAN_POINT('',(-1.217861391,0.547103709313,0.984014184754 +#187044 = CARTESIAN_POINT('',(-1.217861391,0.547103709313,0.984014184754 )); -#184653 = CARTESIAN_POINT('',(-1.217861391,0.526270589279,1.)); -#184654 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#184655 = CARTESIAN_POINT('',(-1.255881450408,0.551937603265, +#187045 = CARTESIAN_POINT('',(-1.217861391,0.526270589279,1.)); +#187046 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#187047 = CARTESIAN_POINT('',(-1.255881450408,0.551937603265, 0.965973846926)); -#184656 = CARTESIAN_POINT('',(-1.254463088209,0.545238584914, +#187048 = CARTESIAN_POINT('',(-1.254463088209,0.545238584914, 0.985681523985)); -#184657 = CARTESIAN_POINT('',(-1.249230002437,0.525223961408,1.)); -#184658 = CARTESIAN_POINT('',(-1.243749871723,0.504453973629,1.)); -#184659 = CARTESIAN_POINT('',(-1.293021890319,0.536187793567,0.967717466 +#187049 = CARTESIAN_POINT('',(-1.249230002437,0.525223961408,1.)); +#187050 = CARTESIAN_POINT('',(-1.243749871723,0.504453973629,1.)); +#187051 = CARTESIAN_POINT('',(-1.293021890319,0.536187793567,0.967717466 )); -#184660 = CARTESIAN_POINT('',(-1.289327515655,0.529788010173, +#187052 = CARTESIAN_POINT('',(-1.289327515655,0.529788010173, 0.986553421368)); -#184661 = CARTESIAN_POINT('',(-1.279247431202,0.512326230316,1.)); -#184662 = CARTESIAN_POINT('',(-1.268821632546,0.494265568045,1.)); -#184663 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 +#187053 = CARTESIAN_POINT('',(-1.279247431202,0.512326230316,1.)); +#187054 = CARTESIAN_POINT('',(-1.268821632546,0.494265568045,1.)); +#187055 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 )); -#184664 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, +#187056 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, 0.986553421368)); -#184665 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); -#184666 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#184667 = DEFINITIONAL_REPRESENTATION('',(#184668),#184694); -#184668 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184669,#184670,#184671, - #184672,#184673,#184674,#184675,#184676,#184677,#184678,#184679, - #184680,#184681,#184682,#184683,#184684,#184685,#184686,#184687, - #184688,#184689,#184690,#184691,#184692,#184693),.UNSPECIFIED.,.F., +#187057 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); +#187058 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#187059 = DEFINITIONAL_REPRESENTATION('',(#187060),#187086); +#187060 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187061,#187062,#187063, + #187064,#187065,#187066,#187067,#187068,#187069,#187070,#187071, + #187072,#187073,#187074,#187075,#187076,#187077,#187078,#187079, + #187080,#187081,#187082,#187083,#187084,#187085),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -229146,48 +232148,48 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#184669 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184670 = CARTESIAN_POINT('',(6.272059551128,2.972804134475E-006)); -#184671 = CARTESIAN_POINT('',(6.249732638972,-1.037052467297E-005)); -#184672 = CARTESIAN_POINT('',(6.216039360813,-5.446484095426E-005)); -#184673 = CARTESIAN_POINT('',(6.182166930891,-8.868396576214E-005)); -#184674 = CARTESIAN_POINT('',(6.148137469616,-7.965797689878E-005)); -#184675 = CARTESIAN_POINT('',(6.113972837442,-8.226451401253E-005)); -#184676 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); -#184677 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); -#184678 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); -#184679 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); -#184680 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); -#184681 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); -#184682 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); -#184683 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); -#184684 = CARTESIAN_POINT('',(5.803652201529,-8.48530842991E-005)); -#184685 = CARTESIAN_POINT('',(5.769199593774,-8.542361824737E-005)); -#184686 = CARTESIAN_POINT('',(5.734821280547,-8.593542635494E-005)); -#184687 = CARTESIAN_POINT('',(5.700537102678,-8.687405903416E-005)); -#184688 = CARTESIAN_POINT('',(5.666367464031,-8.643182884285E-005)); -#184689 = CARTESIAN_POINT('',(5.632333796998,-9.135957813208E-005)); -#184690 = CARTESIAN_POINT('',(5.598455804408,-3.211524038017E-005)); -#184691 = CARTESIAN_POINT('',(5.564759360757,-7.920748672451E-006)); -#184692 = CARTESIAN_POINT('',(5.542431620278,5.702886687369E-008)); -#184693 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184695 = PCURVE('',#184696,#184701); -#184696 = CYLINDRICAL_SURFACE('',#184697,0.15); -#184697 = AXIS2_PLACEMENT_3D('',#184698,#184699,#184700); -#184698 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, +#187061 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#187062 = CARTESIAN_POINT('',(6.272059551128,2.972804134475E-006)); +#187063 = CARTESIAN_POINT('',(6.249732638972,-1.037052467297E-005)); +#187064 = CARTESIAN_POINT('',(6.216039360813,-5.446484095426E-005)); +#187065 = CARTESIAN_POINT('',(6.182166930891,-8.868396576214E-005)); +#187066 = CARTESIAN_POINT('',(6.148137469616,-7.965797689878E-005)); +#187067 = CARTESIAN_POINT('',(6.113972837442,-8.226451401253E-005)); +#187068 = CARTESIAN_POINT('',(6.079693755153,-8.17998950653E-005)); +#187069 = CARTESIAN_POINT('',(6.045320300361,-8.220472162611E-005)); +#187070 = CARTESIAN_POINT('',(6.010871913477,-8.242390084136E-005)); +#187071 = CARTESIAN_POINT('',(5.97636755144,-8.2740983334E-005)); +#187072 = CARTESIAN_POINT('',(5.941825812427,-8.308081521482E-005)); +#187073 = CARTESIAN_POINT('',(5.907265074214,-8.346461194626E-005)); +#187074 = CARTESIAN_POINT('',(5.872703630927,-8.388702468127E-005)); +#187075 = CARTESIAN_POINT('',(5.838159829417,-8.435280861153E-005)); +#187076 = CARTESIAN_POINT('',(5.803652201529,-8.48530842991E-005)); +#187077 = CARTESIAN_POINT('',(5.769199593774,-8.542361824737E-005)); +#187078 = CARTESIAN_POINT('',(5.734821280547,-8.593542635494E-005)); +#187079 = CARTESIAN_POINT('',(5.700537102678,-8.687405903416E-005)); +#187080 = CARTESIAN_POINT('',(5.666367464031,-8.643182884285E-005)); +#187081 = CARTESIAN_POINT('',(5.632333796998,-9.135957813208E-005)); +#187082 = CARTESIAN_POINT('',(5.598455804408,-3.211524038017E-005)); +#187083 = CARTESIAN_POINT('',(5.564759360757,-7.920748672451E-006)); +#187084 = CARTESIAN_POINT('',(5.542431620278,5.702886687369E-008)); +#187085 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#187086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187087 = PCURVE('',#187088,#187093); +#187088 = CYLINDRICAL_SURFACE('',#187089,0.15); +#187089 = AXIS2_PLACEMENT_3D('',#187090,#187091,#187092); +#187090 = CARTESIAN_POINT('',(-1.324207498814,0.514207498814, 0.527229017938)); -#184699 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) +#187091 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) ); -#184700 = DIRECTION('',(-0.965925826289,3.026618127129E-017, +#187092 = DIRECTION('',(-0.965925826289,3.026618127129E-017, 0.258819045103)); -#184701 = DEFINITIONAL_REPRESENTATION('',(#184702),#184728); -#184702 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184703,#184704,#184705, - #184706,#184707,#184708,#184709,#184710,#184711,#184712,#184713, - #184714,#184715,#184716,#184717,#184718,#184719,#184720,#184721, - #184722,#184723,#184724,#184725,#184726,#184727),.UNSPECIFIED.,.F., +#187093 = DEFINITIONAL_REPRESENTATION('',(#187094),#187120); +#187094 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187095,#187096,#187097, + #187098,#187099,#187100,#187101,#187102,#187103,#187104,#187105, + #187106,#187107,#187108,#187109,#187110,#187111,#187112,#187113, + #187114,#187115,#187116,#187117,#187118,#187119),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -229195,50 +232197,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#184703 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); -#184704 = CARTESIAN_POINT('',(0.76300502153,-0.414213027833)); -#184705 = CARTESIAN_POINT('',(0.78532707141,-0.414227119403)); -#184706 = CARTESIAN_POINT('',(0.819005050097,-0.414291190685)); -#184707 = CARTESIAN_POINT('',(0.852860566593,-0.414398842232)); -#184708 = CARTESIAN_POINT('',(0.886875427771,-0.414550528448)); -#184709 = CARTESIAN_POINT('',(0.921030963568,-0.414746569643)); -#184710 = CARTESIAN_POINT('',(0.955308004085,-0.414987129667)); -#184711 = CARTESIAN_POINT('',(0.9896869619,-0.41527221657)); -#184712 = CARTESIAN_POINT('',(1.024147890877,-0.415601678753)); -#184713 = CARTESIAN_POINT('',(1.058670555341,-0.415975204048)); -#184714 = CARTESIAN_POINT('',(1.093234499852,-0.416392319824)); -#184715 = CARTESIAN_POINT('',(1.127819121442,-0.416852394634)); -#184716 = CARTESIAN_POINT('',(1.162403743033,-0.417354641276)); -#184717 = CARTESIAN_POINT('',(1.196967687544,-0.41789812127)); -#184718 = CARTESIAN_POINT('',(1.231490352008,-0.418481750684)); -#184719 = CARTESIAN_POINT('',(1.265951280985,-0.419104307248)); -#184720 = CARTESIAN_POINT('',(1.3003302388,-0.419764438636)); -#184721 = CARTESIAN_POINT('',(1.334607279317,-0.420460671856)); -#184722 = CARTESIAN_POINT('',(1.368762815114,-0.421191423422)); -#184723 = CARTESIAN_POINT('',(1.402777676292,-0.421955010917)); -#184724 = CARTESIAN_POINT('',(1.436633192788,-0.422749662917)); -#184725 = CARTESIAN_POINT('',(1.470311171475,-0.423573537911)); -#184726 = CARTESIAN_POINT('',(1.492633221355,-0.424140987131)); -#184727 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); -#184728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184729 = ORIENTED_EDGE('',*,*,#184730,.T.); -#184730 = EDGE_CURVE('',#184639,#184731,#184733,.T.); -#184731 = VERTEX_POINT('',#184732); -#184732 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#184733 = SURFACE_CURVE('',#184734,(#184739,#184768),.PCURVE_S1.); -#184734 = CIRCLE('',#184735,5.E-002); -#184735 = AXIS2_PLACEMENT_3D('',#184736,#184737,#184738); -#184736 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,0.95)); -#184737 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#184738 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); -#184739 = PCURVE('',#184650,#184740); -#184740 = DEFINITIONAL_REPRESENTATION('',(#184741),#184767); -#184741 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184742,#184743,#184744, - #184745,#184746,#184747,#184748,#184749,#184750,#184751,#184752, - #184753,#184754,#184755,#184756,#184757,#184758,#184759,#184760, - #184761,#184762,#184763,#184764,#184765,#184766),.UNSPECIFIED.,.F., +#187095 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); +#187096 = CARTESIAN_POINT('',(0.76300502153,-0.414213027833)); +#187097 = CARTESIAN_POINT('',(0.78532707141,-0.414227119403)); +#187098 = CARTESIAN_POINT('',(0.819005050097,-0.414291190685)); +#187099 = CARTESIAN_POINT('',(0.852860566593,-0.414398842232)); +#187100 = CARTESIAN_POINT('',(0.886875427771,-0.414550528448)); +#187101 = CARTESIAN_POINT('',(0.921030963568,-0.414746569643)); +#187102 = CARTESIAN_POINT('',(0.955308004085,-0.414987129667)); +#187103 = CARTESIAN_POINT('',(0.9896869619,-0.41527221657)); +#187104 = CARTESIAN_POINT('',(1.024147890877,-0.415601678753)); +#187105 = CARTESIAN_POINT('',(1.058670555341,-0.415975204048)); +#187106 = CARTESIAN_POINT('',(1.093234499852,-0.416392319824)); +#187107 = CARTESIAN_POINT('',(1.127819121442,-0.416852394634)); +#187108 = CARTESIAN_POINT('',(1.162403743033,-0.417354641276)); +#187109 = CARTESIAN_POINT('',(1.196967687544,-0.41789812127)); +#187110 = CARTESIAN_POINT('',(1.231490352008,-0.418481750684)); +#187111 = CARTESIAN_POINT('',(1.265951280985,-0.419104307248)); +#187112 = CARTESIAN_POINT('',(1.3003302388,-0.419764438636)); +#187113 = CARTESIAN_POINT('',(1.334607279317,-0.420460671856)); +#187114 = CARTESIAN_POINT('',(1.368762815114,-0.421191423422)); +#187115 = CARTESIAN_POINT('',(1.402777676292,-0.421955010917)); +#187116 = CARTESIAN_POINT('',(1.436633192788,-0.422749662917)); +#187117 = CARTESIAN_POINT('',(1.470311171475,-0.423573537911)); +#187118 = CARTESIAN_POINT('',(1.492633221355,-0.424140987131)); +#187119 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); +#187120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187121 = ORIENTED_EDGE('',*,*,#187122,.T.); +#187122 = EDGE_CURVE('',#187031,#187123,#187125,.T.); +#187123 = VERTEX_POINT('',#187124); +#187124 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#187125 = SURFACE_CURVE('',#187126,(#187131,#187160),.PCURVE_S1.); +#187126 = CIRCLE('',#187127,5.E-002); +#187127 = AXIS2_PLACEMENT_3D('',#187128,#187129,#187130); +#187128 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,0.95)); +#187129 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#187130 = DIRECTION('',(-0.707106781187,0.707106781187,0.E+000)); +#187131 = PCURVE('',#187042,#187132); +#187132 = DEFINITIONAL_REPRESENTATION('',(#187133),#187159); +#187133 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187134,#187135,#187136, + #187137,#187138,#187139,#187140,#187141,#187142,#187143,#187144, + #187145,#187146,#187147,#187148,#187149,#187150,#187151,#187152, + #187153,#187154,#187155,#187156,#187157,#187158),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -229246,71 +232248,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184742 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184743 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); -#184744 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); -#184745 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#184746 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#184747 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#184748 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#184749 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#184750 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#184751 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#184752 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#184753 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#184754 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#184755 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#184756 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#184757 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#184758 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#184759 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#184760 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#184761 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#184762 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#184763 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#184764 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#184765 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#184766 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184768 = PCURVE('',#184769,#184786); -#184769 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184770,#184771,#184772,#184773) - ,(#184774,#184775,#184776,#184777) - ,(#184778,#184779,#184780,#184781) - ,(#184782,#184783,#184784,#184785 +#187134 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#187135 = CARTESIAN_POINT('',(6.28318530718,1.515278164504E-002)); +#187136 = CARTESIAN_POINT('',(6.28318530718,4.549920749135E-002)); +#187137 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#187138 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#187139 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#187140 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#187141 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#187142 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#187143 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#187144 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#187145 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#187146 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#187147 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#187148 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#187149 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#187150 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#187151 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#187152 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#187153 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#187154 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#187155 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#187156 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#187157 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#187158 = CARTESIAN_POINT('',(6.28318530718,1.)); +#187159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187160 = PCURVE('',#187161,#187178); +#187161 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#187162,#187163,#187164,#187165) + ,(#187166,#187167,#187168,#187169) + ,(#187170,#187171,#187172,#187173) + ,(#187174,#187175,#187176,#187177 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(-8.881784197001E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184770 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 +#187162 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 )); -#184771 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, +#187163 = CARTESIAN_POINT('',(-1.314557762914,0.504557762914, 0.986553421368)); -#184772 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); -#184773 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#184774 = CARTESIAN_POINT('',(-1.346187793567,0.483021890319,0.967717466 +#187164 = CARTESIAN_POINT('',(-1.300786830759,0.490786830759,1.)); +#187165 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#187166 = CARTESIAN_POINT('',(-1.346187793567,0.483021890319,0.967717466 )); -#184775 = CARTESIAN_POINT('',(-1.339788010173,0.479327515655, +#187167 = CARTESIAN_POINT('',(-1.339788010173,0.479327515655, 0.986553421368)); -#184776 = CARTESIAN_POINT('',(-1.322326230316,0.469247431202,1.)); -#184777 = CARTESIAN_POINT('',(-1.304265568045,0.458821632546,1.)); -#184778 = CARTESIAN_POINT('',(-1.361937603265,0.445881450408, +#187168 = CARTESIAN_POINT('',(-1.322326230316,0.469247431202,1.)); +#187169 = CARTESIAN_POINT('',(-1.304265568045,0.458821632546,1.)); +#187170 = CARTESIAN_POINT('',(-1.361937603265,0.445881450408, 0.965973846926)); -#184779 = CARTESIAN_POINT('',(-1.355238584914,0.444463088209, +#187171 = CARTESIAN_POINT('',(-1.355238584914,0.444463088209, 0.985681523985)); -#184780 = CARTESIAN_POINT('',(-1.335223961408,0.439230002437,1.)); -#184781 = CARTESIAN_POINT('',(-1.314453973629,0.433749871723,1.)); -#184782 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 +#187172 = CARTESIAN_POINT('',(-1.335223961408,0.439230002437,1.)); +#187173 = CARTESIAN_POINT('',(-1.314453973629,0.433749871723,1.)); +#187174 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 )); -#184783 = CARTESIAN_POINT('',(-1.357103709313,0.407861391,0.984014184754 +#187175 = CARTESIAN_POINT('',(-1.357103709313,0.407861391,0.984014184754 )); -#184784 = CARTESIAN_POINT('',(-1.336270589279,0.407861391,1.)); -#184785 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#184786 = DEFINITIONAL_REPRESENTATION('',(#184787),#184813); -#184787 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184788,#184789,#184790, - #184791,#184792,#184793,#184794,#184795,#184796,#184797,#184798, - #184799,#184800,#184801,#184802,#184803,#184804,#184805,#184806, - #184807,#184808,#184809,#184810,#184811,#184812),.UNSPECIFIED.,.F., +#187176 = CARTESIAN_POINT('',(-1.336270589279,0.407861391,1.)); +#187177 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#187178 = DEFINITIONAL_REPRESENTATION('',(#187179),#187205); +#187179 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187180,#187181,#187182, + #187183,#187184,#187185,#187186,#187187,#187188,#187189,#187190, + #187191,#187192,#187193,#187194,#187195,#187196,#187197,#187198, + #187199,#187200,#187201,#187202,#187203,#187204),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -229318,55 +232320,55 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#184788 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#184789 = CARTESIAN_POINT('',(-5.97196979057E-016,1.515278164504E-002)); -#184790 = CARTESIAN_POINT('',(-2.300290560433E-016,4.549920749135E-002) - ); -#184791 = CARTESIAN_POINT('',(2.351976805257E-017,9.109101074357E-002)); -#184792 = CARTESIAN_POINT('',(-1.077052714274E-015,0.136698748187)); -#184793 = CARTESIAN_POINT('',(3.256854623462E-016,0.1822865144)); -#184794 = CARTESIAN_POINT('',(-4.097288967669E-016,0.2278300409)); -#184795 = CARTESIAN_POINT('',(-1.672479737944E-015,0.27331674602)); -#184796 = CARTESIAN_POINT('',(1.332393111868E-015,0.318743220066)); -#184797 = CARTESIAN_POINT('',(-2.039656136759E-015,0.364113426255)); -#184798 = CARTESIAN_POINT('',(-1.328144975024E-015,0.409436881051)); -#184799 = CARTESIAN_POINT('',(1.686259519686E-015,0.454727066523)); -#184800 = CARTESIAN_POINT('',(-1.485085254245E-015,0.5)); -#184801 = CARTESIAN_POINT('',(-2.107721094731E-015,0.545272933477)); -#184802 = CARTESIAN_POINT('',(6.424773659417E-016,0.590563118949)); -#184803 = CARTESIAN_POINT('',(-3.238482269288E-015,0.635886573745)); -#184804 = CARTESIAN_POINT('',(6.910290152852E-016,0.681256779934)); -#184805 = CARTESIAN_POINT('',(-2.327227246002E-015,0.72668325398)); -#184806 = CARTESIAN_POINT('',(5.7970355512E-016,0.7721699591)); -#184807 = CARTESIAN_POINT('',(1.129336876171E-015,0.8177134856)); -#184808 = CARTESIAN_POINT('',(-1.149947593023E-015,0.863301251813)); -#184809 = CARTESIAN_POINT('',(-2.747238813904E-015,0.908908989256)); -#184810 = CARTESIAN_POINT('',(2.063513688634E-016,0.954500792509)); -#184811 = CARTESIAN_POINT('',(2.617768229511E-016,0.984847218355)); -#184812 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#184813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184814 = ORIENTED_EDGE('',*,*,#184815,.F.); -#184815 = EDGE_CURVE('',#184816,#184731,#184818,.T.); -#184816 = VERTEX_POINT('',#184817); -#184817 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#184818 = SURFACE_CURVE('',#184819,(#184824,#184853),.PCURVE_S1.); -#184819 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184820,#184821,#184822, -#184823),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#187180 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#187181 = CARTESIAN_POINT('',(-5.97196979057E-016,1.515278164504E-002)); +#187182 = CARTESIAN_POINT('',(-2.300290560433E-016,4.549920749135E-002) + ); +#187183 = CARTESIAN_POINT('',(2.351976805257E-017,9.109101074357E-002)); +#187184 = CARTESIAN_POINT('',(-1.077052714274E-015,0.136698748187)); +#187185 = CARTESIAN_POINT('',(3.256854623462E-016,0.1822865144)); +#187186 = CARTESIAN_POINT('',(-4.097288967669E-016,0.2278300409)); +#187187 = CARTESIAN_POINT('',(-1.672479737944E-015,0.27331674602)); +#187188 = CARTESIAN_POINT('',(1.332393111868E-015,0.318743220066)); +#187189 = CARTESIAN_POINT('',(-2.039656136759E-015,0.364113426255)); +#187190 = CARTESIAN_POINT('',(-1.328144975024E-015,0.409436881051)); +#187191 = CARTESIAN_POINT('',(1.686259519686E-015,0.454727066523)); +#187192 = CARTESIAN_POINT('',(-1.485085254245E-015,0.5)); +#187193 = CARTESIAN_POINT('',(-2.107721094731E-015,0.545272933477)); +#187194 = CARTESIAN_POINT('',(6.424773659417E-016,0.590563118949)); +#187195 = CARTESIAN_POINT('',(-3.238482269288E-015,0.635886573745)); +#187196 = CARTESIAN_POINT('',(6.910290152852E-016,0.681256779934)); +#187197 = CARTESIAN_POINT('',(-2.327227246002E-015,0.72668325398)); +#187198 = CARTESIAN_POINT('',(5.7970355512E-016,0.7721699591)); +#187199 = CARTESIAN_POINT('',(1.129336876171E-015,0.8177134856)); +#187200 = CARTESIAN_POINT('',(-1.149947593023E-015,0.863301251813)); +#187201 = CARTESIAN_POINT('',(-2.747238813904E-015,0.908908989256)); +#187202 = CARTESIAN_POINT('',(2.063513688634E-016,0.954500792509)); +#187203 = CARTESIAN_POINT('',(2.617768229511E-016,0.984847218355)); +#187204 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#187205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187206 = ORIENTED_EDGE('',*,*,#187207,.F.); +#187207 = EDGE_CURVE('',#187208,#187123,#187210,.T.); +#187208 = VERTEX_POINT('',#187209); +#187209 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#187210 = SURFACE_CURVE('',#187211,(#187216,#187245),.PCURVE_S1.); +#187211 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187212,#187213,#187214, +#187215),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184820 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); -#184821 = CARTESIAN_POINT('',(-1.24437896527,0.504453973629,1.)); -#184822 = CARTESIAN_POINT('',(-1.268390986358,0.494696214234,1.)); -#184823 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#184824 = PCURVE('',#184650,#184825); -#184825 = DEFINITIONAL_REPRESENTATION('',(#184826),#184852); -#184826 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184827,#184828,#184829, - #184830,#184831,#184832,#184833,#184834,#184835,#184836,#184837, - #184838,#184839,#184840,#184841,#184842,#184843,#184844,#184845, - #184846,#184847,#184848,#184849,#184850,#184851),.UNSPECIFIED.,.F., +#187212 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,1.)); +#187213 = CARTESIAN_POINT('',(-1.24437896527,0.504453973629,1.)); +#187214 = CARTESIAN_POINT('',(-1.268390986358,0.494696214234,1.)); +#187215 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#187216 = PCURVE('',#187042,#187217); +#187217 = DEFINITIONAL_REPRESENTATION('',(#187218),#187244); +#187218 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187219,#187220,#187221, + #187222,#187223,#187224,#187225,#187226,#187227,#187228,#187229, + #187230,#187231,#187232,#187233,#187234,#187235,#187236,#187237, + #187238,#187239,#187240,#187241,#187242,#187243),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -229374,62 +232376,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#184827 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184828 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#184829 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#184830 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#184831 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#184832 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#184833 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#184834 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#184835 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#184836 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#184837 = CARTESIAN_POINT('',(5.838182469935,0.998690095133)); -#184838 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#184839 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#184840 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#184841 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#184842 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#184843 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#184844 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#184845 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#184846 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#184847 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#184848 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#184849 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#184850 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#184851 = CARTESIAN_POINT('',(6.28318530718,1.)); -#184852 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184853 = PCURVE('',#184276,#184854); -#184854 = DEFINITIONAL_REPRESENTATION('',(#184855),#184860); -#184855 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184856,#184857,#184858, -#184859),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#187219 = CARTESIAN_POINT('',(5.531305892885,1.)); +#187220 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#187221 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#187222 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#187223 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#187224 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#187225 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#187226 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#187227 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#187228 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#187229 = CARTESIAN_POINT('',(5.838182469935,0.998690095133)); +#187230 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#187231 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#187232 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#187233 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#187234 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#187235 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#187236 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#187237 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#187238 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#187239 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#187240 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#187241 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#187242 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#187243 = CARTESIAN_POINT('',(6.28318530718,1.)); +#187244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187245 = PCURVE('',#186668,#187246); +#187246 = DEFINITIONAL_REPRESENTATION('',(#187247),#187252); +#187247 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187248,#187249,#187250, +#187251),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184856 = CARTESIAN_POINT('',(-2.677861391,1.154453973629)); -#184857 = CARTESIAN_POINT('',(-2.70437896527,1.154453973629)); -#184858 = CARTESIAN_POINT('',(-2.728390986358,1.144696214234)); -#184859 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); -#184860 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184861 = ORIENTED_EDGE('',*,*,#184862,.T.); -#184862 = EDGE_CURVE('',#184816,#184641,#184863,.T.); -#184863 = SURFACE_CURVE('',#184864,(#184869,#184898),.PCURVE_S1.); -#184864 = CIRCLE('',#184865,5.E-002); -#184865 = AXIS2_PLACEMENT_3D('',#184866,#184867,#184868); -#184866 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,0.95)); -#184867 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#184868 = DIRECTION('',(0.E+000,0.E+000,1.)); -#184869 = PCURVE('',#184650,#184870); -#184870 = DEFINITIONAL_REPRESENTATION('',(#184871),#184897); -#184871 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184872,#184873,#184874, - #184875,#184876,#184877,#184878,#184879,#184880,#184881,#184882, - #184883,#184884,#184885,#184886,#184887,#184888,#184889,#184890, - #184891,#184892,#184893,#184894,#184895,#184896),.UNSPECIFIED.,.F., +#187248 = CARTESIAN_POINT('',(-2.677861391,1.154453973629)); +#187249 = CARTESIAN_POINT('',(-2.70437896527,1.154453973629)); +#187250 = CARTESIAN_POINT('',(-2.728390986358,1.144696214234)); +#187251 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); +#187252 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187253 = ORIENTED_EDGE('',*,*,#187254,.T.); +#187254 = EDGE_CURVE('',#187208,#187033,#187255,.T.); +#187255 = SURFACE_CURVE('',#187256,(#187261,#187290),.PCURVE_S1.); +#187256 = CIRCLE('',#187257,5.E-002); +#187257 = AXIS2_PLACEMENT_3D('',#187258,#187259,#187260); +#187258 = CARTESIAN_POINT('',(-1.217861391,0.504453973629,0.95)); +#187259 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#187260 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187261 = PCURVE('',#187042,#187262); +#187262 = DEFINITIONAL_REPRESENTATION('',(#187263),#187289); +#187263 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187264,#187265,#187266, + #187267,#187268,#187269,#187270,#187271,#187272,#187273,#187274, + #187275,#187276,#187277,#187278,#187279,#187280,#187281,#187282, + #187283,#187284,#187285,#187286,#187287,#187288),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -229437,111 +232439,111 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#184872 = CARTESIAN_POINT('',(5.531305892885,1.)); -#184873 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#184874 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#184875 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#184876 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#184877 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#184878 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#184879 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#184880 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#184881 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#184882 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); -#184883 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#184884 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#184885 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#184886 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#184887 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#184888 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#184889 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#184890 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#184891 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#184892 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#184893 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#184894 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#184895 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#184896 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184898 = PCURVE('',#184899,#184904); -#184899 = CYLINDRICAL_SURFACE('',#184900,5.E-002); -#184900 = AXIS2_PLACEMENT_3D('',#184901,#184902,#184903); -#184901 = CARTESIAN_POINT('',(1.46,0.504453973629,0.95)); -#184902 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#184903 = DIRECTION('',(0.E+000,0.E+000,1.)); -#184904 = DEFINITIONAL_REPRESENTATION('',(#184905),#184908); -#184905 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#184906,#184907), +#187264 = CARTESIAN_POINT('',(5.531305892885,1.)); +#187265 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#187266 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#187267 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#187268 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#187269 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#187270 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#187271 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#187272 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#187273 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#187274 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); +#187275 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#187276 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#187277 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#187278 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#187279 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#187280 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#187281 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#187282 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#187283 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#187284 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#187285 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#187286 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#187287 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#187288 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#187289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187290 = PCURVE('',#187291,#187296); +#187291 = CYLINDRICAL_SURFACE('',#187292,5.E-002); +#187292 = AXIS2_PLACEMENT_3D('',#187293,#187294,#187295); +#187293 = CARTESIAN_POINT('',(1.46,0.504453973629,0.95)); +#187294 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#187295 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187296 = DEFINITIONAL_REPRESENTATION('',(#187297),#187300); +#187297 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187298,#187299), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#184906 = CARTESIAN_POINT('',(0.E+000,2.677861391)); -#184907 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); -#184908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187298 = CARTESIAN_POINT('',(0.E+000,2.677861391)); +#187299 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); +#187300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#184909 = ADVANCED_FACE('',(#184910),#184925,.T.); -#184910 = FACE_BOUND('',#184911,.T.); -#184911 = EDGE_LOOP('',(#184912,#185004,#185089,#185136)); -#184912 = ORIENTED_EDGE('',*,*,#184913,.F.); -#184913 = EDGE_CURVE('',#184914,#184916,#184918,.T.); -#184914 = VERTEX_POINT('',#184915); -#184915 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#187301 = ADVANCED_FACE('',(#187302),#187317,.T.); +#187302 = FACE_BOUND('',#187303,.T.); +#187303 = EDGE_LOOP('',(#187304,#187396,#187481,#187528)); +#187304 = ORIENTED_EDGE('',*,*,#187305,.F.); +#187305 = EDGE_CURVE('',#187306,#187308,#187310,.T.); +#187306 = VERTEX_POINT('',#187307); +#187307 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#184916 = VERTEX_POINT('',#184917); -#184917 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) +#187308 = VERTEX_POINT('',#187309); +#187309 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) ); -#184918 = SURFACE_CURVE('',#184919,(#184924,#184970),.PCURVE_S1.); -#184919 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#184920,#184921,#184922, -#184923),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#187310 = SURFACE_CURVE('',#187311,(#187316,#187362),.PCURVE_S1.); +#187311 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187312,#187313,#187314, +#187315),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 9.93851991445E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#184920 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#187312 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#184921 = CARTESIAN_POINT('',(1.34683376285,0.482375921036,0.967717466) +#187313 = CARTESIAN_POINT('',(1.34683376285,0.482375921036,0.967717466) ); -#184922 = CARTESIAN_POINT('',(1.361917855478,0.44680534294, +#187314 = CARTESIAN_POINT('',(1.361917855478,0.44680534294, 0.966047546673)); -#184923 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) - ); -#184924 = PCURVE('',#184925,#184942); -#184925 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#184926,#184927,#184928,#184929) - ,(#184930,#184931,#184932,#184933) - ,(#184934,#184935,#184936,#184937) - ,(#184938,#184939,#184940,#184941 +#187315 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) + ); +#187316 = PCURVE('',#187317,#187334); +#187317 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#187318,#187319,#187320,#187321) + ,(#187322,#187323,#187324,#187325) + ,(#187326,#187327,#187328,#187329) + ,(#187330,#187331,#187332,#187333 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(5.531305892885,6.28318530718 ),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#184926 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) +#187318 = CARTESIAN_POINT('',(1.362750264943,0.407861391,0.962940952255) ); -#184927 = CARTESIAN_POINT('',(1.357103709313,0.407861391,0.984014184754) +#187319 = CARTESIAN_POINT('',(1.357103709313,0.407861391,0.984014184754) ); -#184928 = CARTESIAN_POINT('',(1.336270589279,0.407861391,1.)); -#184929 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#184930 = CARTESIAN_POINT('',(1.361937603265,0.445881450408, +#187320 = CARTESIAN_POINT('',(1.336270589279,0.407861391,1.)); +#187321 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#187322 = CARTESIAN_POINT('',(1.361937603265,0.445881450408, 0.965973846926)); -#184931 = CARTESIAN_POINT('',(1.355238584914,0.444463088209, +#187323 = CARTESIAN_POINT('',(1.355238584914,0.444463088209, 0.985681523985)); -#184932 = CARTESIAN_POINT('',(1.335223961408,0.439230002437,1.)); -#184933 = CARTESIAN_POINT('',(1.314453973629,0.433749871723,1.)); -#184934 = CARTESIAN_POINT('',(1.346187793567,0.483021890319,0.967717466) +#187324 = CARTESIAN_POINT('',(1.335223961408,0.439230002437,1.)); +#187325 = CARTESIAN_POINT('',(1.314453973629,0.433749871723,1.)); +#187326 = CARTESIAN_POINT('',(1.346187793567,0.483021890319,0.967717466) ); -#184935 = CARTESIAN_POINT('',(1.339788010173,0.479327515655, +#187327 = CARTESIAN_POINT('',(1.339788010173,0.479327515655, 0.986553421368)); -#184936 = CARTESIAN_POINT('',(1.322326230316,0.469247431202,1.)); -#184937 = CARTESIAN_POINT('',(1.304265568045,0.458821632546,1.)); -#184938 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#187328 = CARTESIAN_POINT('',(1.322326230316,0.469247431202,1.)); +#187329 = CARTESIAN_POINT('',(1.304265568045,0.458821632546,1.)); +#187330 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#184939 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, +#187331 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, 0.986553421368)); -#184940 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); -#184941 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#184942 = DEFINITIONAL_REPRESENTATION('',(#184943),#184969); -#184943 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184944,#184945,#184946, - #184947,#184948,#184949,#184950,#184951,#184952,#184953,#184954, - #184955,#184956,#184957,#184958,#184959,#184960,#184961,#184962, - #184963,#184964,#184965,#184966,#184967,#184968),.UNSPECIFIED.,.F., +#187332 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); +#187333 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#187334 = DEFINITIONAL_REPRESENTATION('',(#187335),#187361); +#187335 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187336,#187337,#187338, + #187339,#187340,#187341,#187342,#187343,#187344,#187345,#187346, + #187347,#187348,#187349,#187350,#187351,#187352,#187353,#187354, + #187355,#187356,#187357,#187358,#187359,#187360),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 9.93851991445E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -229550,47 +232552,47 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#184944 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#184945 = CARTESIAN_POINT('',(6.272059551128,2.972804133332E-006)); -#184946 = CARTESIAN_POINT('',(6.249732638972,-1.037052467407E-005)); -#184947 = CARTESIAN_POINT('',(6.216039360813,-5.446484095213E-005)); -#184948 = CARTESIAN_POINT('',(6.182166930891,-8.868396576271E-005)); -#184949 = CARTESIAN_POINT('',(6.148137469616,-7.965797689863E-005)); -#184950 = CARTESIAN_POINT('',(6.113972837442,-8.226451401256E-005)); -#184951 = CARTESIAN_POINT('',(6.079693755153,-8.179989506534E-005)); -#184952 = CARTESIAN_POINT('',(6.045320300361,-8.220472162592E-005)); -#184953 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); -#184954 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); -#184955 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); -#184956 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); -#184957 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); -#184958 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); -#184959 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); -#184960 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); -#184961 = CARTESIAN_POINT('',(5.734821280548,-8.593545386255E-005)); -#184962 = CARTESIAN_POINT('',(5.700537102675,-8.687395637438E-005)); -#184963 = CARTESIAN_POINT('',(5.666367464043,-8.643221197436E-005)); -#184964 = CARTESIAN_POINT('',(5.632333796953,-9.13581482658E-005)); -#184965 = CARTESIAN_POINT('',(5.59845580442,-3.211561474274E-005)); -#184966 = CARTESIAN_POINT('',(5.564759360754,-7.920681089086E-006)); -#184967 = CARTESIAN_POINT('',(5.542431620275,5.712075790494E-008)); -#184968 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#184969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#184970 = PCURVE('',#184971,#184976); -#184971 = CYLINDRICAL_SURFACE('',#184972,0.15); -#184972 = AXIS2_PLACEMENT_3D('',#184973,#184974,#184975); -#184973 = CARTESIAN_POINT('',(1.140884875554,0.330884875554, +#187336 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#187337 = CARTESIAN_POINT('',(6.272059551128,2.972804133332E-006)); +#187338 = CARTESIAN_POINT('',(6.249732638972,-1.037052467407E-005)); +#187339 = CARTESIAN_POINT('',(6.216039360813,-5.446484095213E-005)); +#187340 = CARTESIAN_POINT('',(6.182166930891,-8.868396576271E-005)); +#187341 = CARTESIAN_POINT('',(6.148137469616,-7.965797689863E-005)); +#187342 = CARTESIAN_POINT('',(6.113972837442,-8.226451401256E-005)); +#187343 = CARTESIAN_POINT('',(6.079693755153,-8.179989506534E-005)); +#187344 = CARTESIAN_POINT('',(6.045320300361,-8.220472162592E-005)); +#187345 = CARTESIAN_POINT('',(6.010871913477,-8.24239008421E-005)); +#187346 = CARTESIAN_POINT('',(5.97636755144,-8.274098333127E-005)); +#187347 = CARTESIAN_POINT('',(5.941825812427,-8.3080815225E-005)); +#187348 = CARTESIAN_POINT('',(5.907265074214,-8.346461190825E-005)); +#187349 = CARTESIAN_POINT('',(5.872703630927,-8.388702482307E-005)); +#187350 = CARTESIAN_POINT('',(5.838159829417,-8.435280808234E-005)); +#187351 = CARTESIAN_POINT('',(5.803652201529,-8.485308627405E-005)); +#187352 = CARTESIAN_POINT('',(5.769199593774,-8.542361087673E-005)); +#187353 = CARTESIAN_POINT('',(5.734821280548,-8.593545386255E-005)); +#187354 = CARTESIAN_POINT('',(5.700537102675,-8.687395637438E-005)); +#187355 = CARTESIAN_POINT('',(5.666367464043,-8.643221197436E-005)); +#187356 = CARTESIAN_POINT('',(5.632333796953,-9.13581482658E-005)); +#187357 = CARTESIAN_POINT('',(5.59845580442,-3.211561474274E-005)); +#187358 = CARTESIAN_POINT('',(5.564759360754,-7.920681089086E-006)); +#187359 = CARTESIAN_POINT('',(5.542431620275,5.712075790494E-008)); +#187360 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#187361 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187362 = PCURVE('',#187363,#187368); +#187363 = CYLINDRICAL_SURFACE('',#187364,0.15); +#187364 = AXIS2_PLACEMENT_3D('',#187365,#187366,#187367); +#187365 = CARTESIAN_POINT('',(1.140884875554,0.330884875554, 1.211398362123)); -#184974 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#184975 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, +#187366 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#187367 = DIRECTION('',(-0.965925826289,-1.350983669553E-016, -0.258819045103)); -#184976 = DEFINITIONAL_REPRESENTATION('',(#184977),#185003); -#184977 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#184978,#184979,#184980, - #184981,#184982,#184983,#184984,#184985,#184986,#184987,#184988, - #184989,#184990,#184991,#184992,#184993,#184994,#184995,#184996, - #184997,#184998,#184999,#185000,#185001,#185002),.UNSPECIFIED.,.F., +#187368 = DEFINITIONAL_REPRESENTATION('',(#187369),#187395); +#187369 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187370,#187371,#187372, + #187373,#187374,#187375,#187376,#187377,#187378,#187379,#187380, + #187381,#187382,#187383,#187384,#187385,#187386,#187387,#187388, + #187389,#187390,#187391,#187392,#187393,#187394),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 9.93851991445E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -229599,50 +232601,50 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#184978 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); -#184979 = CARTESIAN_POINT('',(2.40083884653,0.317430368857)); -#184980 = CARTESIAN_POINT('',(2.42316089641,0.317416277287)); -#184981 = CARTESIAN_POINT('',(2.456838875097,0.317352206005)); -#184982 = CARTESIAN_POINT('',(2.490694391593,0.317244554458)); -#184983 = CARTESIAN_POINT('',(2.524709252771,0.317092868242)); -#184984 = CARTESIAN_POINT('',(2.558864788568,0.316896827047)); -#184985 = CARTESIAN_POINT('',(2.593141829085,0.316656267024)); -#184986 = CARTESIAN_POINT('',(2.6275207869,0.31637118012)); -#184987 = CARTESIAN_POINT('',(2.661981715877,0.316041717938)); -#184988 = CARTESIAN_POINT('',(2.696504380341,0.315668192643)); -#184989 = CARTESIAN_POINT('',(2.731068324852,0.315251076867)); -#184990 = CARTESIAN_POINT('',(2.765652946442,0.314791002057)); -#184991 = CARTESIAN_POINT('',(2.800237568033,0.314288755414)); -#184992 = CARTESIAN_POINT('',(2.834801512544,0.31374527542)); -#184993 = CARTESIAN_POINT('',(2.869324177008,0.313161646006)); -#184994 = CARTESIAN_POINT('',(2.903785105985,0.312539089442)); -#184995 = CARTESIAN_POINT('',(2.9381640638,0.311878958055)); -#184996 = CARTESIAN_POINT('',(2.972441104317,0.311182724834)); -#184997 = CARTESIAN_POINT('',(3.006596640113,0.310451973268)); -#184998 = CARTESIAN_POINT('',(3.040611501292,0.309688385773)); -#184999 = CARTESIAN_POINT('',(3.074467017787,0.308893733774)); -#185000 = CARTESIAN_POINT('',(3.108144996475,0.308069858779)); -#185001 = CARTESIAN_POINT('',(3.130467046355,0.30750240956)); -#185002 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); -#185003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185004 = ORIENTED_EDGE('',*,*,#185005,.T.); -#185005 = EDGE_CURVE('',#184914,#185006,#185008,.T.); -#185006 = VERTEX_POINT('',#185007); -#185007 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#185008 = SURFACE_CURVE('',#185009,(#185014,#185043),.PCURVE_S1.); -#185009 = CIRCLE('',#185010,5.E-002); -#185010 = AXIS2_PLACEMENT_3D('',#185011,#185012,#185013); -#185011 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,0.95)); -#185012 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); -#185013 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); -#185014 = PCURVE('',#184925,#185015); -#185015 = DEFINITIONAL_REPRESENTATION('',(#185016),#185042); -#185016 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185017,#185018,#185019, - #185020,#185021,#185022,#185023,#185024,#185025,#185026,#185027, - #185028,#185029,#185030,#185031,#185032,#185033,#185034,#185035, - #185036,#185037,#185038,#185039,#185040,#185041),.UNSPECIFIED.,.F., +#187370 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); +#187371 = CARTESIAN_POINT('',(2.40083884653,0.317430368857)); +#187372 = CARTESIAN_POINT('',(2.42316089641,0.317416277287)); +#187373 = CARTESIAN_POINT('',(2.456838875097,0.317352206005)); +#187374 = CARTESIAN_POINT('',(2.490694391593,0.317244554458)); +#187375 = CARTESIAN_POINT('',(2.524709252771,0.317092868242)); +#187376 = CARTESIAN_POINT('',(2.558864788568,0.316896827047)); +#187377 = CARTESIAN_POINT('',(2.593141829085,0.316656267024)); +#187378 = CARTESIAN_POINT('',(2.6275207869,0.31637118012)); +#187379 = CARTESIAN_POINT('',(2.661981715877,0.316041717938)); +#187380 = CARTESIAN_POINT('',(2.696504380341,0.315668192643)); +#187381 = CARTESIAN_POINT('',(2.731068324852,0.315251076867)); +#187382 = CARTESIAN_POINT('',(2.765652946442,0.314791002057)); +#187383 = CARTESIAN_POINT('',(2.800237568033,0.314288755414)); +#187384 = CARTESIAN_POINT('',(2.834801512544,0.31374527542)); +#187385 = CARTESIAN_POINT('',(2.869324177008,0.313161646006)); +#187386 = CARTESIAN_POINT('',(2.903785105985,0.312539089442)); +#187387 = CARTESIAN_POINT('',(2.9381640638,0.311878958055)); +#187388 = CARTESIAN_POINT('',(2.972441104317,0.311182724834)); +#187389 = CARTESIAN_POINT('',(3.006596640113,0.310451973268)); +#187390 = CARTESIAN_POINT('',(3.040611501292,0.309688385773)); +#187391 = CARTESIAN_POINT('',(3.074467017787,0.308893733774)); +#187392 = CARTESIAN_POINT('',(3.108144996475,0.308069858779)); +#187393 = CARTESIAN_POINT('',(3.130467046355,0.30750240956)); +#187394 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); +#187395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187396 = ORIENTED_EDGE('',*,*,#187397,.T.); +#187397 = EDGE_CURVE('',#187306,#187398,#187400,.T.); +#187398 = VERTEX_POINT('',#187399); +#187399 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#187400 = SURFACE_CURVE('',#187401,(#187406,#187435),.PCURVE_S1.); +#187401 = CIRCLE('',#187402,5.E-002); +#187402 = AXIS2_PLACEMENT_3D('',#187403,#187404,#187405); +#187403 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,0.95)); +#187404 = DIRECTION('',(0.707106781187,-0.707106781187,0.E+000)); +#187405 = DIRECTION('',(0.707106781187,0.707106781187,0.E+000)); +#187406 = PCURVE('',#187317,#187407); +#187407 = DEFINITIONAL_REPRESENTATION('',(#187408),#187434); +#187408 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187409,#187410,#187411, + #187412,#187413,#187414,#187415,#187416,#187417,#187418,#187419, + #187420,#187421,#187422,#187423,#187424,#187425,#187426,#187427, + #187428,#187429,#187430,#187431,#187432,#187433),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -229650,71 +232652,71 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#185017 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#185018 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); -#185019 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); -#185020 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); -#185021 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); -#185022 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); -#185023 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); -#185024 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); -#185025 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); -#185026 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); -#185027 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); -#185028 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); -#185029 = CARTESIAN_POINT('',(6.28318530718,0.5)); -#185030 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); -#185031 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); -#185032 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); -#185033 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); -#185034 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); -#185035 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); -#185036 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); -#185037 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); -#185038 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); -#185039 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); -#185040 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); -#185041 = CARTESIAN_POINT('',(6.28318530718,1.)); -#185042 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185043 = PCURVE('',#185044,#185061); -#185044 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( - (#185045,#185046,#185047,#185048) - ,(#185049,#185050,#185051,#185052) - ,(#185053,#185054,#185055,#185056) - ,(#185057,#185058,#185059,#185060 +#187409 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#187410 = CARTESIAN_POINT('',(6.28318530718,1.515278164503E-002)); +#187411 = CARTESIAN_POINT('',(6.28318530718,4.549920749134E-002)); +#187412 = CARTESIAN_POINT('',(6.28318530718,9.109101074356E-002)); +#187413 = CARTESIAN_POINT('',(6.28318530718,0.136698748187)); +#187414 = CARTESIAN_POINT('',(6.28318530718,0.1822865144)); +#187415 = CARTESIAN_POINT('',(6.28318530718,0.2278300409)); +#187416 = CARTESIAN_POINT('',(6.28318530718,0.27331674602)); +#187417 = CARTESIAN_POINT('',(6.28318530718,0.318743220066)); +#187418 = CARTESIAN_POINT('',(6.28318530718,0.364113426255)); +#187419 = CARTESIAN_POINT('',(6.28318530718,0.409436881051)); +#187420 = CARTESIAN_POINT('',(6.28318530718,0.454727066523)); +#187421 = CARTESIAN_POINT('',(6.28318530718,0.5)); +#187422 = CARTESIAN_POINT('',(6.28318530718,0.545272933477)); +#187423 = CARTESIAN_POINT('',(6.28318530718,0.590563118949)); +#187424 = CARTESIAN_POINT('',(6.28318530718,0.635886573745)); +#187425 = CARTESIAN_POINT('',(6.28318530718,0.681256779934)); +#187426 = CARTESIAN_POINT('',(6.28318530718,0.72668325398)); +#187427 = CARTESIAN_POINT('',(6.28318530718,0.7721699591)); +#187428 = CARTESIAN_POINT('',(6.28318530718,0.8177134856)); +#187429 = CARTESIAN_POINT('',(6.28318530718,0.863301251813)); +#187430 = CARTESIAN_POINT('',(6.28318530718,0.908908989256)); +#187431 = CARTESIAN_POINT('',(6.28318530718,0.954500792509)); +#187432 = CARTESIAN_POINT('',(6.28318530718,0.984847218355)); +#187433 = CARTESIAN_POINT('',(6.28318530718,1.)); +#187434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187435 = PCURVE('',#187436,#187453); +#187436 = B_SPLINE_SURFACE_WITH_KNOTS('',3,3,( + (#187437,#187438,#187439,#187440) + ,(#187441,#187442,#187443,#187444) + ,(#187445,#187446,#187447,#187448) + ,(#187449,#187450,#187451,#187452 )),.UNSPECIFIED.,.F.,.F.,.F.,(4,4),(4,4),(3.388131789017E-016, 0.751879414295),(0.E+000,1.),.PIECEWISE_BEZIER_KNOTS.); -#185045 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#187437 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#185046 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, +#187438 = CARTESIAN_POINT('',(1.314557762914,0.504557762914, 0.986553421368)); -#185047 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); -#185048 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#185049 = CARTESIAN_POINT('',(1.293021890319,0.536187793567,0.967717466) +#187439 = CARTESIAN_POINT('',(1.300786830759,0.490786830759,1.)); +#187440 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#187441 = CARTESIAN_POINT('',(1.293021890319,0.536187793567,0.967717466) ); -#185050 = CARTESIAN_POINT('',(1.289327515655,0.529788010173, +#187442 = CARTESIAN_POINT('',(1.289327515655,0.529788010173, 0.986553421368)); -#185051 = CARTESIAN_POINT('',(1.279247431202,0.512326230316,1.)); -#185052 = CARTESIAN_POINT('',(1.268821632546,0.494265568045,1.)); -#185053 = CARTESIAN_POINT('',(1.255881450408,0.551937603265, +#187443 = CARTESIAN_POINT('',(1.279247431202,0.512326230316,1.)); +#187444 = CARTESIAN_POINT('',(1.268821632546,0.494265568045,1.)); +#187445 = CARTESIAN_POINT('',(1.255881450408,0.551937603265, 0.965973846926)); -#185054 = CARTESIAN_POINT('',(1.254463088209,0.545238584914, +#187446 = CARTESIAN_POINT('',(1.254463088209,0.545238584914, 0.985681523985)); -#185055 = CARTESIAN_POINT('',(1.249230002437,0.525223961408,1.)); -#185056 = CARTESIAN_POINT('',(1.243749871723,0.504453973629,1.)); -#185057 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) - ); -#185058 = CARTESIAN_POINT('',(1.217861391,0.547103709313,0.984014184754) - ); -#185059 = CARTESIAN_POINT('',(1.217861391,0.526270589279,1.)); -#185060 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#185061 = DEFINITIONAL_REPRESENTATION('',(#185062),#185088); -#185062 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185063,#185064,#185065, - #185066,#185067,#185068,#185069,#185070,#185071,#185072,#185073, - #185074,#185075,#185076,#185077,#185078,#185079,#185080,#185081, - #185082,#185083,#185084,#185085,#185086,#185087),.UNSPECIFIED.,.F., +#187447 = CARTESIAN_POINT('',(1.249230002437,0.525223961408,1.)); +#187448 = CARTESIAN_POINT('',(1.243749871723,0.504453973629,1.)); +#187449 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) + ); +#187450 = CARTESIAN_POINT('',(1.217861391,0.547103709313,0.984014184754) + ); +#187451 = CARTESIAN_POINT('',(1.217861391,0.526270589279,1.)); +#187452 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#187453 = DEFINITIONAL_REPRESENTATION('',(#187454),#187480); +#187454 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187455,#187456,#187457, + #187458,#187459,#187460,#187461,#187462,#187463,#187464,#187465, + #187466,#187467,#187468,#187469,#187470,#187471,#187472,#187473, + #187474,#187475,#187476,#187477,#187478,#187479),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.362218145212, 0.417153517102,0.472088888992,0.527024260882,0.581959632772, 0.636895004662,0.691830376553,0.746765748443,0.801701120333, @@ -229722,55 +232724,55 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.076377979784,1.131313351674,1.186248723564,1.241184095454, 1.296119467344,1.351054839234,1.405990211124,1.460925583015, 1.515860954905,1.570796326795),.QUASI_UNIFORM_KNOTS.); -#185063 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#185064 = CARTESIAN_POINT('',(1.061661611134E-015,1.515278164503E-002)); -#185065 = CARTESIAN_POINT('',(6.739209458866E-016,4.549920749134E-002)); -#185066 = CARTESIAN_POINT('',(-2.253788534801E-015,9.109101074357E-002) - ); -#185067 = CARTESIAN_POINT('',(1.35298307003E-016,0.136698748187)); -#185068 = CARTESIAN_POINT('',(-2.763061698481E-016,0.1822865144)); -#185069 = CARTESIAN_POINT('',(-1.298830252807E-015,0.2278300409)); -#185070 = CARTESIAN_POINT('',(-3.515607692919E-016,0.27331674602)); -#185071 = CARTESIAN_POINT('',(2.497661180885E-017,0.318743220066)); -#185072 = CARTESIAN_POINT('',(7.334648223176E-016,0.364113426255)); -#185073 = CARTESIAN_POINT('',(7.016373077783E-016,0.409436881051)); -#185074 = CARTESIAN_POINT('',(-1.916593767267E-015,0.454727066523)); -#185075 = CARTESIAN_POINT('',(1.267507683608E-015,0.5)); -#185076 = CARTESIAN_POINT('',(1.162539513313E-016,0.545272933477)); -#185077 = CARTESIAN_POINT('',(-5.556713119141E-016,0.590563118949)); -#185078 = CARTESIAN_POINT('',(1.19988048939E-015,0.635886573745)); -#185079 = CARTESIAN_POINT('',(-1.47765137311E-015,0.681256779934)); -#185080 = CARTESIAN_POINT('',(-6.210166973602E-016,0.72668325398)); -#185081 = CARTESIAN_POINT('',(2.579818538055E-015,0.7721699591)); -#185082 = CARTESIAN_POINT('',(-3.024846433617E-015,0.8177134856)); -#185083 = CARTESIAN_POINT('',(1.042025613774E-015,0.863301251813)); -#185084 = CARTESIAN_POINT('',(1.210297274954E-015,0.908908989256)); -#185085 = CARTESIAN_POINT('',(6.259121812265E-016,0.954500792509)); -#185086 = CARTESIAN_POINT('',(2.663325483931E-016,0.984847218355)); -#185087 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#185088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185089 = ORIENTED_EDGE('',*,*,#185090,.F.); -#185090 = EDGE_CURVE('',#185091,#185006,#185093,.T.); -#185091 = VERTEX_POINT('',#185092); -#185092 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#185093 = SURFACE_CURVE('',#185094,(#185099,#185128),.PCURVE_S1.); -#185094 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185095,#185096,#185097, -#185098),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#187455 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#187456 = CARTESIAN_POINT('',(1.061661611134E-015,1.515278164503E-002)); +#187457 = CARTESIAN_POINT('',(6.739209458866E-016,4.549920749134E-002)); +#187458 = CARTESIAN_POINT('',(-2.253788534801E-015,9.109101074357E-002) + ); +#187459 = CARTESIAN_POINT('',(1.35298307003E-016,0.136698748187)); +#187460 = CARTESIAN_POINT('',(-2.763061698481E-016,0.1822865144)); +#187461 = CARTESIAN_POINT('',(-1.298830252807E-015,0.2278300409)); +#187462 = CARTESIAN_POINT('',(-3.515607692919E-016,0.27331674602)); +#187463 = CARTESIAN_POINT('',(2.497661180885E-017,0.318743220066)); +#187464 = CARTESIAN_POINT('',(7.334648223176E-016,0.364113426255)); +#187465 = CARTESIAN_POINT('',(7.016373077783E-016,0.409436881051)); +#187466 = CARTESIAN_POINT('',(-1.916593767267E-015,0.454727066523)); +#187467 = CARTESIAN_POINT('',(1.267507683608E-015,0.5)); +#187468 = CARTESIAN_POINT('',(1.162539513313E-016,0.545272933477)); +#187469 = CARTESIAN_POINT('',(-5.556713119141E-016,0.590563118949)); +#187470 = CARTESIAN_POINT('',(1.19988048939E-015,0.635886573745)); +#187471 = CARTESIAN_POINT('',(-1.47765137311E-015,0.681256779934)); +#187472 = CARTESIAN_POINT('',(-6.210166973602E-016,0.72668325398)); +#187473 = CARTESIAN_POINT('',(2.579818538055E-015,0.7721699591)); +#187474 = CARTESIAN_POINT('',(-3.024846433617E-015,0.8177134856)); +#187475 = CARTESIAN_POINT('',(1.042025613774E-015,0.863301251813)); +#187476 = CARTESIAN_POINT('',(1.210297274954E-015,0.908908989256)); +#187477 = CARTESIAN_POINT('',(6.259121812265E-016,0.954500792509)); +#187478 = CARTESIAN_POINT('',(2.663325483931E-016,0.984847218355)); +#187479 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#187480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187481 = ORIENTED_EDGE('',*,*,#187482,.F.); +#187482 = EDGE_CURVE('',#187483,#187398,#187485,.T.); +#187483 = VERTEX_POINT('',#187484); +#187484 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#187485 = SURFACE_CURVE('',#187486,(#187491,#187520),.PCURVE_S1.); +#187486 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187487,#187488,#187489, +#187490),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#185095 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); -#185096 = CARTESIAN_POINT('',(1.314453973629,0.43437896527,1.)); -#185097 = CARTESIAN_POINT('',(1.304696214234,0.458390986358,1.)); -#185098 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#185099 = PCURVE('',#184925,#185100); -#185100 = DEFINITIONAL_REPRESENTATION('',(#185101),#185127); -#185101 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185102,#185103,#185104, - #185105,#185106,#185107,#185108,#185109,#185110,#185111,#185112, - #185113,#185114,#185115,#185116,#185117,#185118,#185119,#185120, - #185121,#185122,#185123,#185124,#185125,#185126),.UNSPECIFIED.,.F., +#187487 = CARTESIAN_POINT('',(1.314453973629,0.407861391,1.)); +#187488 = CARTESIAN_POINT('',(1.314453973629,0.43437896527,1.)); +#187489 = CARTESIAN_POINT('',(1.304696214234,0.458390986358,1.)); +#187490 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#187491 = PCURVE('',#187317,#187492); +#187492 = DEFINITIONAL_REPRESENTATION('',(#187493),#187519); +#187493 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187494,#187495,#187496, + #187497,#187498,#187499,#187500,#187501,#187502,#187503,#187504, + #187505,#187506,#187507,#187508,#187509,#187510,#187511,#187512, + #187513,#187514,#187515,#187516,#187517,#187518),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -229778,62 +232780,62 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#185102 = CARTESIAN_POINT('',(5.531305892885,1.)); -#185103 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); -#185104 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); -#185105 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); -#185106 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); -#185107 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); -#185108 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); -#185109 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); -#185110 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); -#185111 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); -#185112 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); -#185113 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); -#185114 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); -#185115 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); -#185116 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); -#185117 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); -#185118 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); -#185119 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); -#185120 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); -#185121 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); -#185122 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); -#185123 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); -#185124 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); -#185125 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); -#185126 = CARTESIAN_POINT('',(6.28318530718,1.)); -#185127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185128 = PCURVE('',#184276,#185129); -#185129 = DEFINITIONAL_REPRESENTATION('',(#185130),#185135); -#185130 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#185131,#185132,#185133, -#185134),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#187494 = CARTESIAN_POINT('',(5.531305892885,1.)); +#187495 = CARTESIAN_POINT('',(5.542431609433,1.000000029013)); +#187496 = CARTESIAN_POINT('',(5.564759695218,0.999973832438)); +#187497 = CARTESIAN_POINT('',(5.598457782919,0.999871732687)); +#187498 = CARTESIAN_POINT('',(5.632337541793,0.999722746961)); +#187499 = CARTESIAN_POINT('',(5.666375694827,0.999542934196)); +#187500 = CARTESIAN_POINT('',(5.700549707253,0.999347904707)); +#187501 = CARTESIAN_POINT('',(5.734837892756,0.999152437553)); +#187502 = CARTESIAN_POINT('',(5.769219374506,0.99897005671)); +#187503 = CARTESIAN_POINT('',(5.803674042174,0.99881264607)); +#187504 = CARTESIAN_POINT('',(5.838182469936,0.998690095133)); +#187505 = CARTESIAN_POINT('',(5.87272580864,0.998609990188)); +#187506 = CARTESIAN_POINT('',(5.907285653264,0.998577358684)); +#187507 = CARTESIAN_POINT('',(5.941843890817,0.998594475286)); +#187508 = CARTESIAN_POINT('',(5.976382533559,0.998660736522)); +#187509 = CARTESIAN_POINT('',(6.010883543172,0.998772609746)); +#187510 = CARTESIAN_POINT('',(6.045328652128,0.998923660586)); +#187511 = CARTESIAN_POINT('',(6.079699188623,0.999104661236)); +#187512 = CARTESIAN_POINT('',(6.113975913115,0.999303780101)); +#187513 = CARTESIAN_POINT('',(6.148138870073,0.999506850153)); +#187514 = CARTESIAN_POINT('',(6.182167276026,0.999697714073)); +#187515 = CARTESIAN_POINT('',(6.21603939964,0.999858629242)); +#187516 = CARTESIAN_POINT('',(6.24973263213,0.99997075866)); +#187517 = CARTESIAN_POINT('',(6.272059569215,0.999999986247)); +#187518 = CARTESIAN_POINT('',(6.28318530718,1.)); +#187519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187520 = PCURVE('',#186668,#187521); +#187521 = DEFINITIONAL_REPRESENTATION('',(#187522),#187527); +#187522 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187523,#187524,#187525, +#187526),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#185131 = CARTESIAN_POINT('',(-0.145546026371,1.057861391)); -#185132 = CARTESIAN_POINT('',(-0.145546026371,1.08437896527)); -#185133 = CARTESIAN_POINT('',(-0.155303785766,1.108390986358)); -#185134 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); -#185135 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185136 = ORIENTED_EDGE('',*,*,#185137,.F.); -#185137 = EDGE_CURVE('',#184916,#185091,#185138,.T.); -#185138 = SURFACE_CURVE('',#185139,(#185144,#185173),.PCURVE_S1.); -#185139 = CIRCLE('',#185140,5.E-002); -#185140 = AXIS2_PLACEMENT_3D('',#185141,#185142,#185143); -#185141 = CARTESIAN_POINT('',(1.314453973629,0.407861391,0.95)); -#185142 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#185143 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185144 = PCURVE('',#184925,#185145); -#185145 = DEFINITIONAL_REPRESENTATION('',(#185146),#185172); -#185146 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185147,#185148,#185149, - #185150,#185151,#185152,#185153,#185154,#185155,#185156,#185157, - #185158,#185159,#185160,#185161,#185162,#185163,#185164,#185165, - #185166,#185167,#185168,#185169,#185170,#185171),.UNSPECIFIED.,.F., +#187523 = CARTESIAN_POINT('',(-0.145546026371,1.057861391)); +#187524 = CARTESIAN_POINT('',(-0.145546026371,1.08437896527)); +#187525 = CARTESIAN_POINT('',(-0.155303785766,1.108390986358)); +#187526 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); +#187527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187528 = ORIENTED_EDGE('',*,*,#187529,.F.); +#187529 = EDGE_CURVE('',#187308,#187483,#187530,.T.); +#187530 = SURFACE_CURVE('',#187531,(#187536,#187565),.PCURVE_S1.); +#187531 = CIRCLE('',#187532,5.E-002); +#187532 = AXIS2_PLACEMENT_3D('',#187533,#187534,#187535); +#187533 = CARTESIAN_POINT('',(1.314453973629,0.407861391,0.95)); +#187534 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#187535 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#187536 = PCURVE('',#187317,#187537); +#187537 = DEFINITIONAL_REPRESENTATION('',(#187538),#187564); +#187538 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187539,#187540,#187541, + #187542,#187543,#187544,#187545,#187546,#187547,#187548,#187549, + #187550,#187551,#187552,#187553,#187554,#187555,#187556,#187557, + #187558,#187559,#187560,#187561,#187562,#187563),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594, 1.892095575457,1.951595436321,2.011095297184,2.070595158048, 2.130095018911,2.189594879775,2.249094740638,2.308594601502, @@ -229841,75 +232843,75 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.606093905819,2.665593766682,2.725093627546,2.784593488409, 2.844093349273,2.903593210136,2.963093070999,3.022592931863, 3.082092792726,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#185147 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); -#185148 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); -#185149 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); -#185150 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); -#185151 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); -#185152 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); -#185153 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); -#185154 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); -#185155 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); -#185156 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); -#185157 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); -#185158 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); -#185159 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); -#185160 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); -#185161 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); -#185162 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); -#185163 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); -#185164 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); -#185165 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); -#185166 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); -#185167 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); -#185168 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); -#185169 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); -#185170 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); -#185171 = CARTESIAN_POINT('',(5.531305892885,1.)); -#185172 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185173 = PCURVE('',#185174,#185179); -#185174 = CYLINDRICAL_SURFACE('',#185175,5.E-002); -#185175 = AXIS2_PLACEMENT_3D('',#185176,#185177,#185178); -#185176 = CARTESIAN_POINT('',(1.314453973629,-0.65,0.95)); -#185177 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#185178 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); -#185179 = DEFINITIONAL_REPRESENTATION('',(#185180),#185183); -#185180 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185181,#185182), +#187539 = CARTESIAN_POINT('',(5.531305892885,0.E+000)); +#187540 = CARTESIAN_POINT('',(5.531305884234,1.515321402759E-002)); +#187541 = CARTESIAN_POINT('',(5.531305899752,4.551530551223E-002)); +#187542 = CARTESIAN_POINT('',(5.531306102499,9.115656938682E-002)); +#187543 = CARTESIAN_POINT('',(5.531306604351,0.136819171746)); +#187544 = CARTESIAN_POINT('',(5.531307389788,0.182454060255)); +#187545 = CARTESIAN_POINT('',(5.531308380511,0.228028368465)); +#187546 = CARTESIAN_POINT('',(5.531309450978,0.273525359883)); +#187547 = CARTESIAN_POINT('',(5.531310460769,0.318940837163)); +#187548 = CARTESIAN_POINT('',(5.531311278795,0.364280526289)); +#187549 = CARTESIAN_POINT('',(5.531311802952,0.409557497693)); +#187550 = CARTESIAN_POINT('',(5.531311972785,0.454789977664)); +#187551 = CARTESIAN_POINT('',(5.531311775431,0.499999441206)); +#187552 = CARTESIAN_POINT('',(5.531311245056,0.545208929561)); +#187553 = CARTESIAN_POINT('',(5.531310456364,0.590441482182)); +#187554 = CARTESIAN_POINT('',(5.531309512999,0.635718568665)); +#187555 = CARTESIAN_POINT('',(5.531308531949,0.681058406204)); +#187556 = CARTESIAN_POINT('',(5.531307625546,0.726474052505)); +#187557 = CARTESIAN_POINT('',(5.531306883237,0.771971217636)); +#187558 = CARTESIAN_POINT('',(5.531306356223,0.817545686379)); +#187559 = CARTESIAN_POINT('',(5.531306048207,0.863180704561)); +#187560 = CARTESIAN_POINT('',(5.531305917798,0.908843392737)); +#187561 = CARTESIAN_POINT('',(5.531305889761,0.954484692963)); +#187562 = CARTESIAN_POINT('',(5.531305895404,0.984846787708)); +#187563 = CARTESIAN_POINT('',(5.531305892885,1.)); +#187564 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187565 = PCURVE('',#187566,#187571); +#187566 = CYLINDRICAL_SURFACE('',#187567,5.E-002); +#187567 = AXIS2_PLACEMENT_3D('',#187568,#187569,#187570); +#187568 = CARTESIAN_POINT('',(1.314453973629,-0.65,0.95)); +#187569 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#187570 = DIRECTION('',(-1.,-1.668003342285E-016,0.E+000)); +#187571 = DEFINITIONAL_REPRESENTATION('',(#187572),#187575); +#187572 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187573,#187574), .UNSPECIFIED.,.F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#185181 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); -#185182 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); -#185183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185184 = ADVANCED_FACE('',(#185185),#185200,.F.); -#185185 = FACE_BOUND('',#185186,.F.); -#185186 = EDGE_LOOP('',(#185187,#185245,#185271,#185317)); -#185187 = ORIENTED_EDGE('',*,*,#185188,.T.); -#185188 = EDGE_CURVE('',#185189,#185191,#185193,.T.); -#185189 = VERTEX_POINT('',#185190); -#185190 = CARTESIAN_POINT('',(-1.052486786062,-0.241005873715,0.95)); -#185191 = VERTEX_POINT('',#185192); -#185192 = CARTESIAN_POINT('',(-0.83639674918,-0.241005873715,0.95)); -#185193 = SURFACE_CURVE('',#185194,(#185199,#185233),.PCURVE_S1.); -#185194 = CIRCLE('',#185195,0.108045018441); -#185195 = AXIS2_PLACEMENT_3D('',#185196,#185197,#185198); -#185196 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); -#185197 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185198 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185199 = PCURVE('',#185200,#185205); -#185200 = CONICAL_SURFACE('',#185201,0.15,0.698131700798); -#185201 = AXIS2_PLACEMENT_3D('',#185202,#185203,#185204); -#185202 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); -#185203 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185204 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185205 = DEFINITIONAL_REPRESENTATION('',(#185206),#185232); -#185206 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185207,#185208,#185209, - #185210,#185211,#185212,#185213,#185214,#185215,#185216,#185217, - #185218,#185219,#185220,#185221,#185222,#185223,#185224,#185225, - #185226,#185227,#185228,#185229,#185230,#185231),.UNSPECIFIED.,.F., +#187573 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); +#187574 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); +#187575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187576 = ADVANCED_FACE('',(#187577),#187592,.F.); +#187577 = FACE_BOUND('',#187578,.F.); +#187578 = EDGE_LOOP('',(#187579,#187637,#187663,#187709)); +#187579 = ORIENTED_EDGE('',*,*,#187580,.T.); +#187580 = EDGE_CURVE('',#187581,#187583,#187585,.T.); +#187581 = VERTEX_POINT('',#187582); +#187582 = CARTESIAN_POINT('',(-1.052486786062,-0.241005873715,0.95)); +#187583 = VERTEX_POINT('',#187584); +#187584 = CARTESIAN_POINT('',(-0.83639674918,-0.241005873715,0.95)); +#187585 = SURFACE_CURVE('',#187586,(#187591,#187625),.PCURVE_S1.); +#187586 = CIRCLE('',#187587,0.108045018441); +#187587 = AXIS2_PLACEMENT_3D('',#187588,#187589,#187590); +#187588 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); +#187589 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187590 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187591 = PCURVE('',#187592,#187597); +#187592 = CONICAL_SURFACE('',#187593,0.15,0.698131700798); +#187593 = AXIS2_PLACEMENT_3D('',#187594,#187595,#187596); +#187594 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); +#187595 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187596 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187597 = DEFINITIONAL_REPRESENTATION('',(#187598),#187624); +#187598 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187599,#187600,#187601, + #187602,#187603,#187604,#187605,#187606,#187607,#187608,#187609, + #187610,#187611,#187612,#187613,#187614,#187615,#187616,#187617, + #187618,#187619,#187620,#187621,#187622,#187623),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.284392319662,3.427191985734,3.569991651807,3.712791317879, 3.855590983951,3.998390650023,4.141190316096,4.283989982168, @@ -229917,98 +232919,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.997988312529,5.140787978601,5.283587644674,5.426387310746, 5.569186976818,5.711986642891,5.854786308963,5.997585975035, 6.140385641107,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#185207 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#185208 = CARTESIAN_POINT('',(3.189192542281,-5.E-002)); -#185209 = CARTESIAN_POINT('',(3.284392319662,-5.E-002)); -#185210 = CARTESIAN_POINT('',(3.427191985734,-5.E-002)); -#185211 = CARTESIAN_POINT('',(3.569991651807,-5.E-002)); -#185212 = CARTESIAN_POINT('',(3.712791317879,-5.E-002)); -#185213 = CARTESIAN_POINT('',(3.855590983951,-5.E-002)); -#185214 = CARTESIAN_POINT('',(3.998390650023,-5.E-002)); -#185215 = CARTESIAN_POINT('',(4.141190316096,-5.E-002)); -#185216 = CARTESIAN_POINT('',(4.283989982168,-5.E-002)); -#185217 = CARTESIAN_POINT('',(4.42678964824,-5.E-002)); -#185218 = CARTESIAN_POINT('',(4.569589314312,-5.E-002)); -#185219 = CARTESIAN_POINT('',(4.712388980385,-5.E-002)); -#185220 = CARTESIAN_POINT('',(4.855188646457,-5.E-002)); -#185221 = CARTESIAN_POINT('',(4.997988312529,-5.E-002)); -#185222 = CARTESIAN_POINT('',(5.140787978601,-5.E-002)); -#185223 = CARTESIAN_POINT('',(5.283587644674,-5.E-002)); -#185224 = CARTESIAN_POINT('',(5.426387310746,-5.E-002)); -#185225 = CARTESIAN_POINT('',(5.569186976818,-5.E-002)); -#185226 = CARTESIAN_POINT('',(5.711986642891,-5.E-002)); -#185227 = CARTESIAN_POINT('',(5.854786308963,-5.E-002)); -#185228 = CARTESIAN_POINT('',(5.997585975035,-5.E-002)); -#185229 = CARTESIAN_POINT('',(6.140385641107,-5.E-002)); -#185230 = CARTESIAN_POINT('',(6.235585418489,-5.E-002)); -#185231 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#185232 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185233 = PCURVE('',#185234,#185239); -#185234 = PLANE('',#185235); -#185235 = AXIS2_PLACEMENT_3D('',#185236,#185237,#185238); -#185236 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); -#185237 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185238 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185239 = DEFINITIONAL_REPRESENTATION('',(#185240),#185244); -#185240 = CIRCLE('',#185241,0.108045018441); -#185241 = AXIS2_PLACEMENT_2D('',#185242,#185243); -#185242 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185243 = DIRECTION('',(1.,0.E+000)); -#185244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185245 = ORIENTED_EDGE('',*,*,#185246,.T.); -#185246 = EDGE_CURVE('',#185191,#185247,#185249,.T.); -#185247 = VERTEX_POINT('',#185248); -#185248 = CARTESIAN_POINT('',(-0.794441767621,-0.241005873715,1.)); -#185249 = SURFACE_CURVE('',#185250,(#185254,#185260),.PCURVE_S1.); -#185250 = LINE('',#185251,#185252); -#185251 = CARTESIAN_POINT('',(-0.794441767621,-0.241005873715,1.)); -#185252 = VECTOR('',#185253,1.); -#185253 = DIRECTION('',(0.642787609687,0.E+000,0.766044443119)); -#185254 = PCURVE('',#185200,#185255); -#185255 = DEFINITIONAL_REPRESENTATION('',(#185256),#185259); -#185256 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185257,#185258), +#187599 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#187600 = CARTESIAN_POINT('',(3.189192542281,-5.E-002)); +#187601 = CARTESIAN_POINT('',(3.284392319662,-5.E-002)); +#187602 = CARTESIAN_POINT('',(3.427191985734,-5.E-002)); +#187603 = CARTESIAN_POINT('',(3.569991651807,-5.E-002)); +#187604 = CARTESIAN_POINT('',(3.712791317879,-5.E-002)); +#187605 = CARTESIAN_POINT('',(3.855590983951,-5.E-002)); +#187606 = CARTESIAN_POINT('',(3.998390650023,-5.E-002)); +#187607 = CARTESIAN_POINT('',(4.141190316096,-5.E-002)); +#187608 = CARTESIAN_POINT('',(4.283989982168,-5.E-002)); +#187609 = CARTESIAN_POINT('',(4.42678964824,-5.E-002)); +#187610 = CARTESIAN_POINT('',(4.569589314312,-5.E-002)); +#187611 = CARTESIAN_POINT('',(4.712388980385,-5.E-002)); +#187612 = CARTESIAN_POINT('',(4.855188646457,-5.E-002)); +#187613 = CARTESIAN_POINT('',(4.997988312529,-5.E-002)); +#187614 = CARTESIAN_POINT('',(5.140787978601,-5.E-002)); +#187615 = CARTESIAN_POINT('',(5.283587644674,-5.E-002)); +#187616 = CARTESIAN_POINT('',(5.426387310746,-5.E-002)); +#187617 = CARTESIAN_POINT('',(5.569186976818,-5.E-002)); +#187618 = CARTESIAN_POINT('',(5.711986642891,-5.E-002)); +#187619 = CARTESIAN_POINT('',(5.854786308963,-5.E-002)); +#187620 = CARTESIAN_POINT('',(5.997585975035,-5.E-002)); +#187621 = CARTESIAN_POINT('',(6.140385641107,-5.E-002)); +#187622 = CARTESIAN_POINT('',(6.235585418489,-5.E-002)); +#187623 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#187624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187625 = PCURVE('',#187626,#187631); +#187626 = PLANE('',#187627); +#187627 = AXIS2_PLACEMENT_3D('',#187628,#187629,#187630); +#187628 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); +#187629 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187630 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187631 = DEFINITIONAL_REPRESENTATION('',(#187632),#187636); +#187632 = CIRCLE('',#187633,0.108045018441); +#187633 = AXIS2_PLACEMENT_2D('',#187634,#187635); +#187634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#187635 = DIRECTION('',(1.,0.E+000)); +#187636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187637 = ORIENTED_EDGE('',*,*,#187638,.T.); +#187638 = EDGE_CURVE('',#187583,#187639,#187641,.T.); +#187639 = VERTEX_POINT('',#187640); +#187640 = CARTESIAN_POINT('',(-0.794441767621,-0.241005873715,1.)); +#187641 = SURFACE_CURVE('',#187642,(#187646,#187652),.PCURVE_S1.); +#187642 = LINE('',#187643,#187644); +#187643 = CARTESIAN_POINT('',(-0.794441767621,-0.241005873715,1.)); +#187644 = VECTOR('',#187645,1.); +#187645 = DIRECTION('',(0.642787609687,0.E+000,0.766044443119)); +#187646 = PCURVE('',#187592,#187647); +#187647 = DEFINITIONAL_REPRESENTATION('',(#187648),#187651); +#187648 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187649,#187650), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#185257 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); -#185258 = CARTESIAN_POINT('',(6.28318530718,-5.31550111648E-017)); -#185259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187649 = CARTESIAN_POINT('',(6.28318530718,-5.E-002)); +#187650 = CARTESIAN_POINT('',(6.28318530718,-5.31550111648E-017)); +#187651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185260 = PCURVE('',#185261,#185266); -#185261 = CONICAL_SURFACE('',#185262,0.15,0.698131700798); -#185262 = AXIS2_PLACEMENT_3D('',#185263,#185264,#185265); -#185263 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); -#185264 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185265 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185266 = DEFINITIONAL_REPRESENTATION('',(#185267),#185270); -#185267 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185268,#185269), +#187652 = PCURVE('',#187653,#187658); +#187653 = CONICAL_SURFACE('',#187654,0.15,0.698131700798); +#187654 = AXIS2_PLACEMENT_3D('',#187655,#187656,#187657); +#187655 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); +#187656 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187657 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187658 = DEFINITIONAL_REPRESENTATION('',(#187659),#187662); +#187659 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187660,#187661), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#185268 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#185269 = CARTESIAN_POINT('',(0.E+000,-5.31550111648E-017)); -#185270 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185271 = ORIENTED_EDGE('',*,*,#185272,.F.); -#185272 = EDGE_CURVE('',#185273,#185247,#185275,.T.); -#185273 = VERTEX_POINT('',#185274); -#185274 = CARTESIAN_POINT('',(-1.094441767621,-0.241005873715,1.)); -#185275 = SURFACE_CURVE('',#185276,(#185281,#185310),.PCURVE_S1.); -#185276 = CIRCLE('',#185277,0.15); -#185277 = AXIS2_PLACEMENT_3D('',#185278,#185279,#185280); -#185278 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); -#185279 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185280 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185281 = PCURVE('',#185200,#185282); -#185282 = DEFINITIONAL_REPRESENTATION('',(#185283),#185309); -#185283 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185284,#185285,#185286, - #185287,#185288,#185289,#185290,#185291,#185292,#185293,#185294, - #185295,#185296,#185297,#185298,#185299,#185300,#185301,#185302, - #185303,#185304,#185305,#185306,#185307,#185308),.UNSPECIFIED.,.F., +#187660 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#187661 = CARTESIAN_POINT('',(0.E+000,-5.31550111648E-017)); +#187662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187663 = ORIENTED_EDGE('',*,*,#187664,.F.); +#187664 = EDGE_CURVE('',#187665,#187639,#187667,.T.); +#187665 = VERTEX_POINT('',#187666); +#187666 = CARTESIAN_POINT('',(-1.094441767621,-0.241005873715,1.)); +#187667 = SURFACE_CURVE('',#187668,(#187673,#187702),.PCURVE_S1.); +#187668 = CIRCLE('',#187669,0.15); +#187669 = AXIS2_PLACEMENT_3D('',#187670,#187671,#187672); +#187670 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); +#187671 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187672 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187673 = PCURVE('',#187592,#187674); +#187674 = DEFINITIONAL_REPRESENTATION('',(#187675),#187701); +#187675 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187676,#187677,#187678, + #187679,#187680,#187681,#187682,#187683,#187684,#187685,#187686, + #187687,#187688,#187689,#187690,#187691,#187692,#187693,#187694, + #187695,#187696,#187697,#187698,#187699,#187700),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.284392319662,3.427191985734,3.569991651807,3.712791317879, 3.855590983951,3.998390650023,4.141190316096,4.283989982168, @@ -230016,106 +233018,106 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.997988312529,5.140787978601,5.283587644674,5.426387310746, 5.569186976818,5.711986642891,5.854786308963,5.997585975035, 6.140385641107,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#185284 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); -#185285 = CARTESIAN_POINT('',(3.189192542281,6.105528861171E-017)); -#185286 = CARTESIAN_POINT('',(3.284392319662,4.454229154955E-017)); -#185287 = CARTESIAN_POINT('',(3.427191985734,-8.263667907703E-017)); -#185288 = CARTESIAN_POINT('',(3.569991651807,4.212138503508E-017)); -#185289 = CARTESIAN_POINT('',(3.712791317879,5.605254967062E-017)); -#185290 = CARTESIAN_POINT('',(3.855590983951,1.474852445171E-017)); -#185291 = CARTESIAN_POINT('',(3.998390650023,1.460255341316E-017)); -#185292 = CARTESIAN_POINT('',(4.141190316096,3.166572388811E-017)); -#185293 = CARTESIAN_POINT('',(4.283989982168,-2.278738057914E-017)); -#185294 = CARTESIAN_POINT('',(4.42678964824,2.456900436528E-017)); -#185295 = CARTESIAN_POINT('',(4.569589314312,-1.398734825689E-017)); -#185296 = CARTESIAN_POINT('',(4.712388980385,-1.226310391672E-017)); -#185297 = CARTESIAN_POINT('',(4.855188646457,-1.896195424299E-017)); -#185298 = CARTESIAN_POINT('',(4.997988312529,-2.17905687793E-018)); -#185299 = CARTESIAN_POINT('',(5.140787978601,-3.192582262168E-018)); -#185300 = CARTESIAN_POINT('',(5.283587644674,-1.992536823514E-017)); -#185301 = CARTESIAN_POINT('',(5.426387310746,2.403540007327E-017)); -#185302 = CARTESIAN_POINT('',(5.569186976818,2.860822993453E-017)); -#185303 = CARTESIAN_POINT('',(5.711986642891,-8.819118920779E-018)); -#185304 = CARTESIAN_POINT('',(5.854786308963,1.183339303545E-017)); -#185305 = CARTESIAN_POINT('',(5.997585975035,3.523904524731E-017)); -#185306 = CARTESIAN_POINT('',(6.140385641107,-3.571290218894E-017)); -#185307 = CARTESIAN_POINT('',(6.235585418489,-3.113324781527E-017)); -#185308 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#185309 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185310 = PCURVE('',#184276,#185311); -#185311 = DEFINITIONAL_REPRESENTATION('',(#185312),#185316); -#185312 = CIRCLE('',#185313,0.15); -#185313 = AXIS2_PLACEMENT_2D('',#185314,#185315); -#185314 = CARTESIAN_POINT('',(-2.404441767621,0.408994126285)); -#185315 = DIRECTION('',(1.,0.E+000)); -#185316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185317 = ORIENTED_EDGE('',*,*,#185318,.F.); -#185318 = EDGE_CURVE('',#185189,#185273,#185319,.T.); -#185319 = SURFACE_CURVE('',#185320,(#185324,#185330),.PCURVE_S1.); -#185320 = LINE('',#185321,#185322); -#185321 = CARTESIAN_POINT('',(-1.094441767621,-0.241005873715,1.)); -#185322 = VECTOR('',#185323,1.); -#185323 = DIRECTION('',(-0.642787609687,7.871877887342E-017, +#187676 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); +#187677 = CARTESIAN_POINT('',(3.189192542281,6.105528861171E-017)); +#187678 = CARTESIAN_POINT('',(3.284392319662,4.454229154955E-017)); +#187679 = CARTESIAN_POINT('',(3.427191985734,-8.263667907703E-017)); +#187680 = CARTESIAN_POINT('',(3.569991651807,4.212138503508E-017)); +#187681 = CARTESIAN_POINT('',(3.712791317879,5.605254967062E-017)); +#187682 = CARTESIAN_POINT('',(3.855590983951,1.474852445171E-017)); +#187683 = CARTESIAN_POINT('',(3.998390650023,1.460255341316E-017)); +#187684 = CARTESIAN_POINT('',(4.141190316096,3.166572388811E-017)); +#187685 = CARTESIAN_POINT('',(4.283989982168,-2.278738057914E-017)); +#187686 = CARTESIAN_POINT('',(4.42678964824,2.456900436528E-017)); +#187687 = CARTESIAN_POINT('',(4.569589314312,-1.398734825689E-017)); +#187688 = CARTESIAN_POINT('',(4.712388980385,-1.226310391672E-017)); +#187689 = CARTESIAN_POINT('',(4.855188646457,-1.896195424299E-017)); +#187690 = CARTESIAN_POINT('',(4.997988312529,-2.17905687793E-018)); +#187691 = CARTESIAN_POINT('',(5.140787978601,-3.192582262168E-018)); +#187692 = CARTESIAN_POINT('',(5.283587644674,-1.992536823514E-017)); +#187693 = CARTESIAN_POINT('',(5.426387310746,2.403540007327E-017)); +#187694 = CARTESIAN_POINT('',(5.569186976818,2.860822993453E-017)); +#187695 = CARTESIAN_POINT('',(5.711986642891,-8.819118920779E-018)); +#187696 = CARTESIAN_POINT('',(5.854786308963,1.183339303545E-017)); +#187697 = CARTESIAN_POINT('',(5.997585975035,3.523904524731E-017)); +#187698 = CARTESIAN_POINT('',(6.140385641107,-3.571290218894E-017)); +#187699 = CARTESIAN_POINT('',(6.235585418489,-3.113324781527E-017)); +#187700 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#187701 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187702 = PCURVE('',#186668,#187703); +#187703 = DEFINITIONAL_REPRESENTATION('',(#187704),#187708); +#187704 = CIRCLE('',#187705,0.15); +#187705 = AXIS2_PLACEMENT_2D('',#187706,#187707); +#187706 = CARTESIAN_POINT('',(-2.404441767621,0.408994126285)); +#187707 = DIRECTION('',(1.,0.E+000)); +#187708 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187709 = ORIENTED_EDGE('',*,*,#187710,.F.); +#187710 = EDGE_CURVE('',#187581,#187665,#187711,.T.); +#187711 = SURFACE_CURVE('',#187712,(#187716,#187722),.PCURVE_S1.); +#187712 = LINE('',#187713,#187714); +#187713 = CARTESIAN_POINT('',(-1.094441767621,-0.241005873715,1.)); +#187714 = VECTOR('',#187715,1.); +#187715 = DIRECTION('',(-0.642787609687,7.871877887342E-017, 0.766044443119)); -#185324 = PCURVE('',#185200,#185325); -#185325 = DEFINITIONAL_REPRESENTATION('',(#185326),#185329); -#185326 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185327,#185328), +#187716 = PCURVE('',#187592,#187717); +#187717 = DEFINITIONAL_REPRESENTATION('',(#187718),#187721); +#187718 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187719,#187720), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#185327 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#185328 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); -#185329 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187719 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#187720 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); +#187721 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185330 = PCURVE('',#185261,#185331); -#185331 = DEFINITIONAL_REPRESENTATION('',(#185332),#185335); -#185332 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185333,#185334), +#187722 = PCURVE('',#187653,#187723); +#187723 = DEFINITIONAL_REPRESENTATION('',(#187724),#187727); +#187724 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187725,#187726), .UNSPECIFIED.,.F.,.F.,(2,2),(-6.527036446661E-002,0.E+000), .PIECEWISE_BEZIER_KNOTS.); -#185333 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#185334 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); -#185335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185336 = ADVANCED_FACE('',(#185337),#185349,.T.); -#185337 = FACE_BOUND('',#185338,.T.); -#185338 = EDGE_LOOP('',(#185339,#185389,#185411,#185456,#185484,#185512, - #185540,#185568,#185591,#185619,#185647,#185675,#185698,#185726, - #185754,#185782)); -#185339 = ORIENTED_EDGE('',*,*,#185340,.T.); -#185340 = EDGE_CURVE('',#185341,#184641,#185343,.T.); -#185341 = VERTEX_POINT('',#185342); -#185342 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); -#185343 = SURFACE_CURVE('',#185344,(#185348,#185360),.PCURVE_S1.); -#185344 = LINE('',#185345,#185346); -#185345 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, +#187725 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#187726 = CARTESIAN_POINT('',(3.14159265359,3.189300669888E-017)); +#187727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187728 = ADVANCED_FACE('',(#187729),#187741,.T.); +#187729 = FACE_BOUND('',#187730,.T.); +#187730 = EDGE_LOOP('',(#187731,#187781,#187803,#187848,#187876,#187904, + #187932,#187960,#187983,#188011,#188039,#188067,#188090,#188118, + #188146,#188174)); +#187731 = ORIENTED_EDGE('',*,*,#187732,.T.); +#187732 = EDGE_CURVE('',#187733,#187033,#187735,.T.); +#187733 = VERTEX_POINT('',#187734); +#187734 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); +#187735 = SURFACE_CURVE('',#187736,(#187740,#187752),.PCURVE_S1.); +#187736 = LINE('',#187737,#187738); +#187737 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, 0.566051874704)); -#185346 = VECTOR('',#185347,1.); -#185347 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#185348 = PCURVE('',#185349,#185354); -#185349 = PLANE('',#185350); -#185350 = AXIS2_PLACEMENT_3D('',#185351,#185352,#185353); -#185351 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185352 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); -#185353 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185354 = DEFINITIONAL_REPRESENTATION('',(#185355),#185359); -#185355 = LINE('',#185356,#185357); -#185356 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#185357 = VECTOR('',#185358,1.); -#185358 = DIRECTION('',(0.968100345886,0.250562807086)); -#185359 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185360 = PCURVE('',#184696,#185361); -#185361 = DEFINITIONAL_REPRESENTATION('',(#185362),#185388); -#185362 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185363,#185364,#185365, - #185366,#185367,#185368,#185369,#185370,#185371,#185372,#185373, - #185374,#185375,#185376,#185377,#185378,#185379,#185380,#185381, - #185382,#185383,#185384,#185385,#185386,#185387),.UNSPECIFIED.,.F., +#187738 = VECTOR('',#187739,1.); +#187739 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#187740 = PCURVE('',#187741,#187746); +#187741 = PLANE('',#187742); +#187742 = AXIS2_PLACEMENT_3D('',#187743,#187744,#187745); +#187743 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#187744 = DIRECTION('',(0.E+000,0.965925826289,0.258819045103)); +#187745 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#187746 = DEFINITIONAL_REPRESENTATION('',(#187747),#187751); +#187747 = LINE('',#187748,#187749); +#187748 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#187749 = VECTOR('',#187750,1.); +#187750 = DIRECTION('',(0.968100345886,0.250562807086)); +#187751 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187752 = PCURVE('',#187088,#187753); +#187753 = DEFINITIONAL_REPRESENTATION('',(#187754),#187780); +#187754 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187755,#187756,#187757, + #187758,#187759,#187760,#187761,#187762,#187763,#187764,#187765, + #187766,#187767,#187768,#187769,#187770,#187771,#187772,#187773, + #187774,#187775,#187776,#187777,#187778,#187779),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,5.394581668973E-002,7.158787040873E-002, 8.922992412772E-002,0.106871977847,0.124514031566,0.142156085285, @@ -230124,89 +233126,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.300934568756,0.318576622475,0.336218676194,0.353860729913, 0.371502783632,0.389144837351,0.40678689107,0.424428944789), .QUASI_UNIFORM_KNOTS.); -#185363 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#185364 = CARTESIAN_POINT('',(1.50375882859,-4.218444754374E-002)); -#185365 = CARTESIAN_POINT('',(1.50375882859,-5.394581668973E-002)); -#185366 = CARTESIAN_POINT('',(1.50375882859,-7.158787040873E-002)); -#185367 = CARTESIAN_POINT('',(1.50375882859,-8.922992412772E-002)); -#185368 = CARTESIAN_POINT('',(1.50375882859,-0.106871977847)); -#185369 = CARTESIAN_POINT('',(1.50375882859,-0.124514031566)); -#185370 = CARTESIAN_POINT('',(1.50375882859,-0.142156085285)); -#185371 = CARTESIAN_POINT('',(1.50375882859,-0.159798139004)); -#185372 = CARTESIAN_POINT('',(1.50375882859,-0.177440192723)); -#185373 = CARTESIAN_POINT('',(1.50375882859,-0.195082246442)); -#185374 = CARTESIAN_POINT('',(1.50375882859,-0.212724300161)); -#185375 = CARTESIAN_POINT('',(1.50375882859,-0.23036635388)); -#185376 = CARTESIAN_POINT('',(1.50375882859,-0.248008407599)); -#185377 = CARTESIAN_POINT('',(1.50375882859,-0.265650461318)); -#185378 = CARTESIAN_POINT('',(1.50375882859,-0.283292515037)); -#185379 = CARTESIAN_POINT('',(1.50375882859,-0.300934568756)); -#185380 = CARTESIAN_POINT('',(1.50375882859,-0.318576622475)); -#185381 = CARTESIAN_POINT('',(1.50375882859,-0.336218676194)); -#185382 = CARTESIAN_POINT('',(1.50375882859,-0.353860729913)); -#185383 = CARTESIAN_POINT('',(1.50375882859,-0.371502783632)); -#185384 = CARTESIAN_POINT('',(1.50375882859,-0.389144837351)); -#185385 = CARTESIAN_POINT('',(1.50375882859,-0.40678689107)); -#185386 = CARTESIAN_POINT('',(1.50375882859,-0.418548260216)); -#185387 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); -#185388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185389 = ORIENTED_EDGE('',*,*,#185390,.T.); -#185390 = EDGE_CURVE('',#184641,#185391,#185393,.T.); -#185391 = VERTEX_POINT('',#185392); -#185392 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) - ); -#185393 = SURFACE_CURVE('',#185394,(#185398,#185405),.PCURVE_S1.); -#185394 = LINE('',#185395,#185396); -#185395 = CARTESIAN_POINT('',(1.207931449084,0.552750264943, +#187755 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#187756 = CARTESIAN_POINT('',(1.50375882859,-4.218444754374E-002)); +#187757 = CARTESIAN_POINT('',(1.50375882859,-5.394581668973E-002)); +#187758 = CARTESIAN_POINT('',(1.50375882859,-7.158787040873E-002)); +#187759 = CARTESIAN_POINT('',(1.50375882859,-8.922992412772E-002)); +#187760 = CARTESIAN_POINT('',(1.50375882859,-0.106871977847)); +#187761 = CARTESIAN_POINT('',(1.50375882859,-0.124514031566)); +#187762 = CARTESIAN_POINT('',(1.50375882859,-0.142156085285)); +#187763 = CARTESIAN_POINT('',(1.50375882859,-0.159798139004)); +#187764 = CARTESIAN_POINT('',(1.50375882859,-0.177440192723)); +#187765 = CARTESIAN_POINT('',(1.50375882859,-0.195082246442)); +#187766 = CARTESIAN_POINT('',(1.50375882859,-0.212724300161)); +#187767 = CARTESIAN_POINT('',(1.50375882859,-0.23036635388)); +#187768 = CARTESIAN_POINT('',(1.50375882859,-0.248008407599)); +#187769 = CARTESIAN_POINT('',(1.50375882859,-0.265650461318)); +#187770 = CARTESIAN_POINT('',(1.50375882859,-0.283292515037)); +#187771 = CARTESIAN_POINT('',(1.50375882859,-0.300934568756)); +#187772 = CARTESIAN_POINT('',(1.50375882859,-0.318576622475)); +#187773 = CARTESIAN_POINT('',(1.50375882859,-0.336218676194)); +#187774 = CARTESIAN_POINT('',(1.50375882859,-0.353860729913)); +#187775 = CARTESIAN_POINT('',(1.50375882859,-0.371502783632)); +#187776 = CARTESIAN_POINT('',(1.50375882859,-0.389144837351)); +#187777 = CARTESIAN_POINT('',(1.50375882859,-0.40678689107)); +#187778 = CARTESIAN_POINT('',(1.50375882859,-0.418548260216)); +#187779 = CARTESIAN_POINT('',(1.50375882859,-0.424428944789)); +#187780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187781 = ORIENTED_EDGE('',*,*,#187782,.T.); +#187782 = EDGE_CURVE('',#187033,#187783,#187785,.T.); +#187783 = VERTEX_POINT('',#187784); +#187784 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) + ); +#187785 = SURFACE_CURVE('',#187786,(#187790,#187797),.PCURVE_S1.); +#187786 = LINE('',#187787,#187788); +#187787 = CARTESIAN_POINT('',(1.207931449084,0.552750264943, 0.962940952255)); -#185396 = VECTOR('',#185397,1.); -#185397 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185398 = PCURVE('',#185349,#185399); -#185399 = DEFINITIONAL_REPRESENTATION('',(#185400),#185404); -#185400 = LINE('',#185401,#185402); -#185401 = CARTESIAN_POINT('',(0.375744122765,2.667931449084)); -#185402 = VECTOR('',#185403,1.); -#185403 = DIRECTION('',(0.E+000,1.)); -#185404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185405 = PCURVE('',#184899,#185406); -#185406 = DEFINITIONAL_REPRESENTATION('',(#185407),#185410); -#185407 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185408,#185409), +#187788 = VECTOR('',#187789,1.); +#187789 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187790 = PCURVE('',#187741,#187791); +#187791 = DEFINITIONAL_REPRESENTATION('',(#187792),#187796); +#187792 = LINE('',#187793,#187794); +#187793 = CARTESIAN_POINT('',(0.375744122765,2.667931449084)); +#187794 = VECTOR('',#187795,1.); +#187795 = DIRECTION('',(0.E+000,1.)); +#187796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187797 = PCURVE('',#187291,#187798); +#187798 = DEFINITIONAL_REPRESENTATION('',(#187799),#187802); +#187799 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187800,#187801), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#185408 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); -#185409 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); -#185410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187800 = CARTESIAN_POINT('',(1.308996938996,2.677861391)); +#187801 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); +#187802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185411 = ORIENTED_EDGE('',*,*,#185412,.T.); -#185412 = EDGE_CURVE('',#185391,#185413,#185415,.T.); -#185413 = VERTEX_POINT('',#185414); -#185414 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); -#185415 = SURFACE_CURVE('',#185416,(#185420,#185427),.PCURVE_S1.); -#185416 = LINE('',#185417,#185418); -#185417 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, +#187803 = ORIENTED_EDGE('',*,*,#187804,.T.); +#187804 = EDGE_CURVE('',#187783,#187805,#187807,.T.); +#187805 = VERTEX_POINT('',#187806); +#187806 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); +#187807 = SURFACE_CURVE('',#187808,(#187812,#187819),.PCURVE_S1.); +#187808 = LINE('',#187809,#187810); +#187809 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, 1.250221218888)); -#185418 = VECTOR('',#185419,1.); -#185419 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#185420 = PCURVE('',#185349,#185421); -#185421 = DEFINITIONAL_REPRESENTATION('',(#185422),#185426); -#185422 = LINE('',#185423,#185424); -#185423 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); -#185424 = VECTOR('',#185425,1.); -#185425 = DIRECTION('',(-0.968100345886,0.250562807086)); -#185426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185427 = PCURVE('',#184971,#185428); -#185428 = DEFINITIONAL_REPRESENTATION('',(#185429),#185455); -#185429 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185430,#185431,#185432, - #185433,#185434,#185435,#185436,#185437,#185438,#185439,#185440, - #185441,#185442,#185443,#185444,#185445,#185446,#185447,#185448, - #185449,#185450,#185451,#185452,#185453,#185454),.UNSPECIFIED.,.F., +#187810 = VECTOR('',#187811,1.); +#187811 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#187812 = PCURVE('',#187741,#187813); +#187813 = DEFINITIONAL_REPRESENTATION('',(#187814),#187818); +#187814 = LINE('',#187815,#187816); +#187815 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); +#187816 = VECTOR('',#187817,1.); +#187817 = DIRECTION('',(-0.968100345886,0.250562807086)); +#187818 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187819 = PCURVE('',#187363,#187820); +#187820 = DEFINITIONAL_REPRESENTATION('',(#187821),#187847); +#187821 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187822,#187823,#187824, + #187825,#187826,#187827,#187828,#187829,#187830,#187831,#187832, + #187833,#187834,#187835,#187836,#187837,#187838,#187839,#187840, + #187841,#187842,#187843,#187844,#187845,#187846),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.307214451902, 0.324856505621,0.34249855934,0.360140613059,0.377782666778, 0.395424720497,0.413066774216,0.430708827935,0.448350881654, @@ -230214,528 +233216,528 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.536561150249,0.554203203968,0.571845257687,0.589487311406, 0.607129365125,0.624771418844,0.642413472563,0.660055526282, 0.677697580001,0.69533963372),.QUASI_UNIFORM_KNOTS.); -#185430 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); -#185431 = CARTESIAN_POINT('',(1.637833825,0.313095136475)); -#185432 = CARTESIAN_POINT('',(1.637833825,0.324856505621)); -#185433 = CARTESIAN_POINT('',(1.637833825,0.34249855934)); -#185434 = CARTESIAN_POINT('',(1.637833825,0.360140613059)); -#185435 = CARTESIAN_POINT('',(1.637833825,0.377782666778)); -#185436 = CARTESIAN_POINT('',(1.637833825,0.395424720497)); -#185437 = CARTESIAN_POINT('',(1.637833825,0.413066774216)); -#185438 = CARTESIAN_POINT('',(1.637833825,0.430708827935)); -#185439 = CARTESIAN_POINT('',(1.637833825,0.448350881654)); -#185440 = CARTESIAN_POINT('',(1.637833825,0.465992935373)); -#185441 = CARTESIAN_POINT('',(1.637833825,0.483634989092)); -#185442 = CARTESIAN_POINT('',(1.637833825,0.501277042811)); -#185443 = CARTESIAN_POINT('',(1.637833825,0.51891909653)); -#185444 = CARTESIAN_POINT('',(1.637833825,0.536561150249)); -#185445 = CARTESIAN_POINT('',(1.637833825,0.554203203968)); -#185446 = CARTESIAN_POINT('',(1.637833825,0.571845257687)); -#185447 = CARTESIAN_POINT('',(1.637833825,0.589487311406)); -#185448 = CARTESIAN_POINT('',(1.637833825,0.607129365125)); -#185449 = CARTESIAN_POINT('',(1.637833825,0.624771418844)); -#185450 = CARTESIAN_POINT('',(1.637833825,0.642413472563)); -#185451 = CARTESIAN_POINT('',(1.637833825,0.660055526282)); -#185452 = CARTESIAN_POINT('',(1.637833825,0.677697580001)); -#185453 = CARTESIAN_POINT('',(1.637833825,0.689458949147)); -#185454 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); -#185455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#187822 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); +#187823 = CARTESIAN_POINT('',(1.637833825,0.313095136475)); +#187824 = CARTESIAN_POINT('',(1.637833825,0.324856505621)); +#187825 = CARTESIAN_POINT('',(1.637833825,0.34249855934)); +#187826 = CARTESIAN_POINT('',(1.637833825,0.360140613059)); +#187827 = CARTESIAN_POINT('',(1.637833825,0.377782666778)); +#187828 = CARTESIAN_POINT('',(1.637833825,0.395424720497)); +#187829 = CARTESIAN_POINT('',(1.637833825,0.413066774216)); +#187830 = CARTESIAN_POINT('',(1.637833825,0.430708827935)); +#187831 = CARTESIAN_POINT('',(1.637833825,0.448350881654)); +#187832 = CARTESIAN_POINT('',(1.637833825,0.465992935373)); +#187833 = CARTESIAN_POINT('',(1.637833825,0.483634989092)); +#187834 = CARTESIAN_POINT('',(1.637833825,0.501277042811)); +#187835 = CARTESIAN_POINT('',(1.637833825,0.51891909653)); +#187836 = CARTESIAN_POINT('',(1.637833825,0.536561150249)); +#187837 = CARTESIAN_POINT('',(1.637833825,0.554203203968)); +#187838 = CARTESIAN_POINT('',(1.637833825,0.571845257687)); +#187839 = CARTESIAN_POINT('',(1.637833825,0.589487311406)); +#187840 = CARTESIAN_POINT('',(1.637833825,0.607129365125)); +#187841 = CARTESIAN_POINT('',(1.637833825,0.624771418844)); +#187842 = CARTESIAN_POINT('',(1.637833825,0.642413472563)); +#187843 = CARTESIAN_POINT('',(1.637833825,0.660055526282)); +#187844 = CARTESIAN_POINT('',(1.637833825,0.677697580001)); +#187845 = CARTESIAN_POINT('',(1.637833825,0.689458949147)); +#187846 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); +#187847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187848 = ORIENTED_EDGE('',*,*,#187849,.T.); +#187849 = EDGE_CURVE('',#187805,#187850,#187852,.T.); +#187850 = VERTEX_POINT('',#187851); +#187851 = CARTESIAN_POINT('',(1.155,0.65,0.6)); +#187852 = SURFACE_CURVE('',#187853,(#187857,#187864),.PCURVE_S1.); +#187853 = LINE('',#187854,#187855); +#187854 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#187855 = VECTOR('',#187856,1.); +#187856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#187857 = PCURVE('',#187741,#187858); +#187858 = DEFINITIONAL_REPRESENTATION('',(#187859),#187863); +#187859 = LINE('',#187860,#187861); +#187860 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#187861 = VECTOR('',#187862,1.); +#187862 = DIRECTION('',(0.E+000,-1.)); +#187863 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187864 = PCURVE('',#187865,#187870); +#187865 = PLANE('',#187866); +#187866 = AXIS2_PLACEMENT_3D('',#187867,#187868,#187869); +#187867 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#187868 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); +#187869 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); +#187870 = DEFINITIONAL_REPRESENTATION('',(#187871),#187875); +#187871 = LINE('',#187872,#187873); +#187872 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#187873 = VECTOR('',#187874,1.); +#187874 = DIRECTION('',(0.E+000,-1.)); +#187875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187876 = ORIENTED_EDGE('',*,*,#187877,.T.); +#187877 = EDGE_CURVE('',#187850,#187878,#187880,.T.); +#187878 = VERTEX_POINT('',#187879); +#187879 = CARTESIAN_POINT('',(1.155,0.609807621135,0.75)); +#187880 = SURFACE_CURVE('',#187881,(#187885,#187892),.PCURVE_S1.); +#187881 = LINE('',#187882,#187883); +#187882 = CARTESIAN_POINT('',(1.155,0.65,0.6)); +#187883 = VECTOR('',#187884,1.); +#187884 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#187885 = PCURVE('',#187741,#187886); +#187886 = DEFINITIONAL_REPRESENTATION('',(#187887),#187891); +#187887 = LINE('',#187888,#187889); +#187888 = CARTESIAN_POINT('',(0.E+000,2.615)); +#187889 = VECTOR('',#187890,1.); +#187890 = DIRECTION('',(1.,0.E+000)); +#187891 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187892 = PCURVE('',#187893,#187898); +#187893 = PLANE('',#187894); +#187894 = AXIS2_PLACEMENT_3D('',#187895,#187896,#187897); +#187895 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#187896 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187897 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#187898 = DEFINITIONAL_REPRESENTATION('',(#187899),#187903); +#187899 = LINE('',#187900,#187901); +#187900 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#187901 = VECTOR('',#187902,1.); +#187902 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#187903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187904 = ORIENTED_EDGE('',*,*,#187905,.T.); +#187905 = EDGE_CURVE('',#187878,#187906,#187908,.T.); +#187906 = VERTEX_POINT('',#187907); +#187907 = CARTESIAN_POINT('',(0.755,0.609807621135,0.75)); +#187908 = SURFACE_CURVE('',#187909,(#187913,#187920),.PCURVE_S1.); +#187909 = LINE('',#187910,#187911); +#187910 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); +#187911 = VECTOR('',#187912,1.); +#187912 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#187913 = PCURVE('',#187741,#187914); +#187914 = DEFINITIONAL_REPRESENTATION('',(#187915),#187919); +#187915 = LINE('',#187916,#187917); +#187916 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); +#187917 = VECTOR('',#187918,1.); +#187918 = DIRECTION('',(0.E+000,-1.)); +#187919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187920 = PCURVE('',#187921,#187926); +#187921 = PLANE('',#187922); +#187922 = AXIS2_PLACEMENT_3D('',#187923,#187924,#187925); +#187923 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#187924 = DIRECTION('',(0.E+000,0.E+000,1.)); +#187925 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187926 = DEFINITIONAL_REPRESENTATION('',(#187927),#187931); +#187927 = LINE('',#187928,#187929); +#187928 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); +#187929 = VECTOR('',#187930,1.); +#187930 = DIRECTION('',(-1.,0.E+000)); +#187931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187932 = ORIENTED_EDGE('',*,*,#187933,.F.); +#187933 = EDGE_CURVE('',#187934,#187906,#187936,.T.); +#187934 = VERTEX_POINT('',#187935); +#187935 = CARTESIAN_POINT('',(0.755,0.65,0.6)); +#187936 = SURFACE_CURVE('',#187937,(#187941,#187948),.PCURVE_S1.); +#187937 = LINE('',#187938,#187939); +#187938 = CARTESIAN_POINT('',(0.755,0.65,0.6)); +#187939 = VECTOR('',#187940,1.); +#187940 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#187941 = PCURVE('',#187741,#187942); +#187942 = DEFINITIONAL_REPRESENTATION('',(#187943),#187947); +#187943 = LINE('',#187944,#187945); +#187944 = CARTESIAN_POINT('',(0.E+000,2.215)); +#187945 = VECTOR('',#187946,1.); +#187946 = DIRECTION('',(1.,0.E+000)); +#187947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187948 = PCURVE('',#187949,#187954); +#187949 = PLANE('',#187950); +#187950 = AXIS2_PLACEMENT_3D('',#187951,#187952,#187953); +#187951 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#187952 = DIRECTION('',(1.,0.E+000,0.E+000)); +#187953 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#187954 = DEFINITIONAL_REPRESENTATION('',(#187955),#187959); +#187955 = LINE('',#187956,#187957); +#187956 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#187957 = VECTOR('',#187958,1.); +#187958 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#187959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187960 = ORIENTED_EDGE('',*,*,#187961,.T.); +#187961 = EDGE_CURVE('',#187934,#187962,#187964,.T.); +#187962 = VERTEX_POINT('',#187963); +#187963 = CARTESIAN_POINT('',(0.2,0.65,0.6)); +#187964 = SURFACE_CURVE('',#187965,(#187969,#187976),.PCURVE_S1.); +#187965 = LINE('',#187966,#187967); +#187966 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#187967 = VECTOR('',#187968,1.); +#187968 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#187969 = PCURVE('',#187741,#187970); +#187970 = DEFINITIONAL_REPRESENTATION('',(#187971),#187975); +#187971 = LINE('',#187972,#187973); +#187972 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#187973 = VECTOR('',#187974,1.); +#187974 = DIRECTION('',(0.E+000,-1.)); +#187975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187976 = PCURVE('',#187865,#187977); +#187977 = DEFINITIONAL_REPRESENTATION('',(#187978),#187982); +#187978 = LINE('',#187979,#187980); +#187979 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#187980 = VECTOR('',#187981,1.); +#187981 = DIRECTION('',(0.E+000,-1.)); +#187982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187983 = ORIENTED_EDGE('',*,*,#187984,.T.); +#187984 = EDGE_CURVE('',#187962,#187985,#187987,.T.); +#187985 = VERTEX_POINT('',#187986); +#187986 = CARTESIAN_POINT('',(0.2,0.609807621135,0.75)); +#187987 = SURFACE_CURVE('',#187988,(#187992,#187999),.PCURVE_S1.); +#187988 = LINE('',#187989,#187990); +#187989 = CARTESIAN_POINT('',(0.2,0.65,0.6)); +#187990 = VECTOR('',#187991,1.); +#187991 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#187992 = PCURVE('',#187741,#187993); +#187993 = DEFINITIONAL_REPRESENTATION('',(#187994),#187998); +#187994 = LINE('',#187995,#187996); +#187995 = CARTESIAN_POINT('',(0.E+000,1.66)); +#187996 = VECTOR('',#187997,1.); +#187997 = DIRECTION('',(1.,0.E+000)); +#187998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#187999 = PCURVE('',#188000,#188005); +#188000 = PLANE('',#188001); +#188001 = AXIS2_PLACEMENT_3D('',#188002,#188003,#188004); +#188002 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); +#188003 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188004 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188005 = DEFINITIONAL_REPRESENTATION('',(#188006),#188010); +#188006 = LINE('',#188007,#188008); +#188007 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#188008 = VECTOR('',#188009,1.); +#188009 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#188010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185456 = ORIENTED_EDGE('',*,*,#185457,.T.); -#185457 = EDGE_CURVE('',#185413,#185458,#185460,.T.); -#185458 = VERTEX_POINT('',#185459); -#185459 = CARTESIAN_POINT('',(1.155,0.65,0.6)); -#185460 = SURFACE_CURVE('',#185461,(#185465,#185472),.PCURVE_S1.); -#185461 = LINE('',#185462,#185463); -#185462 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185463 = VECTOR('',#185464,1.); -#185464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185465 = PCURVE('',#185349,#185466); -#185466 = DEFINITIONAL_REPRESENTATION('',(#185467),#185471); -#185467 = LINE('',#185468,#185469); -#185468 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185469 = VECTOR('',#185470,1.); -#185470 = DIRECTION('',(0.E+000,-1.)); -#185471 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185472 = PCURVE('',#185473,#185478); -#185473 = PLANE('',#185474); -#185474 = AXIS2_PLACEMENT_3D('',#185475,#185476,#185477); -#185475 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185476 = DIRECTION('',(0.E+000,0.965925826289,-0.258819045103)); -#185477 = DIRECTION('',(0.E+000,0.258819045103,0.965925826289)); -#185478 = DEFINITIONAL_REPRESENTATION('',(#185479),#185483); -#185479 = LINE('',#185480,#185481); -#185480 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185481 = VECTOR('',#185482,1.); -#185482 = DIRECTION('',(0.E+000,-1.)); -#185483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185484 = ORIENTED_EDGE('',*,*,#185485,.T.); -#185485 = EDGE_CURVE('',#185458,#185486,#185488,.T.); -#185486 = VERTEX_POINT('',#185487); -#185487 = CARTESIAN_POINT('',(1.155,0.609807621135,0.75)); -#185488 = SURFACE_CURVE('',#185489,(#185493,#185500),.PCURVE_S1.); -#185489 = LINE('',#185490,#185491); -#185490 = CARTESIAN_POINT('',(1.155,0.65,0.6)); -#185491 = VECTOR('',#185492,1.); -#185492 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185493 = PCURVE('',#185349,#185494); -#185494 = DEFINITIONAL_REPRESENTATION('',(#185495),#185499); -#185495 = LINE('',#185496,#185497); -#185496 = CARTESIAN_POINT('',(0.E+000,2.615)); -#185497 = VECTOR('',#185498,1.); -#185498 = DIRECTION('',(1.,0.E+000)); -#185499 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185500 = PCURVE('',#185501,#185506); -#185501 = PLANE('',#185502); -#185502 = AXIS2_PLACEMENT_3D('',#185503,#185504,#185505); -#185503 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#185504 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185505 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185506 = DEFINITIONAL_REPRESENTATION('',(#185507),#185511); -#185507 = LINE('',#185508,#185509); -#185508 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185509 = VECTOR('',#185510,1.); -#185510 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185512 = ORIENTED_EDGE('',*,*,#185513,.T.); -#185513 = EDGE_CURVE('',#185486,#185514,#185516,.T.); -#185514 = VERTEX_POINT('',#185515); -#185515 = CARTESIAN_POINT('',(0.755,0.609807621135,0.75)); -#185516 = SURFACE_CURVE('',#185517,(#185521,#185528),.PCURVE_S1.); -#185517 = LINE('',#185518,#185519); -#185518 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); -#185519 = VECTOR('',#185520,1.); -#185520 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185521 = PCURVE('',#185349,#185522); -#185522 = DEFINITIONAL_REPRESENTATION('',(#185523),#185527); -#185523 = LINE('',#185524,#185525); -#185524 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); -#185525 = VECTOR('',#185526,1.); -#185526 = DIRECTION('',(0.E+000,-1.)); -#185527 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185528 = PCURVE('',#185529,#185534); -#185529 = PLANE('',#185530); -#185530 = AXIS2_PLACEMENT_3D('',#185531,#185532,#185533); -#185531 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#185532 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185533 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185534 = DEFINITIONAL_REPRESENTATION('',(#185535),#185539); -#185535 = LINE('',#185536,#185537); -#185536 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); -#185537 = VECTOR('',#185538,1.); -#185538 = DIRECTION('',(-1.,0.E+000)); -#185539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185540 = ORIENTED_EDGE('',*,*,#185541,.F.); -#185541 = EDGE_CURVE('',#185542,#185514,#185544,.T.); -#185542 = VERTEX_POINT('',#185543); -#185543 = CARTESIAN_POINT('',(0.755,0.65,0.6)); -#185544 = SURFACE_CURVE('',#185545,(#185549,#185556),.PCURVE_S1.); -#185545 = LINE('',#185546,#185547); -#185546 = CARTESIAN_POINT('',(0.755,0.65,0.6)); -#185547 = VECTOR('',#185548,1.); -#185548 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185549 = PCURVE('',#185349,#185550); -#185550 = DEFINITIONAL_REPRESENTATION('',(#185551),#185555); -#185551 = LINE('',#185552,#185553); -#185552 = CARTESIAN_POINT('',(0.E+000,2.215)); -#185553 = VECTOR('',#185554,1.); -#185554 = DIRECTION('',(1.,0.E+000)); -#185555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185556 = PCURVE('',#185557,#185562); -#185557 = PLANE('',#185558); -#185558 = AXIS2_PLACEMENT_3D('',#185559,#185560,#185561); -#185559 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#185560 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185561 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185562 = DEFINITIONAL_REPRESENTATION('',(#185563),#185567); -#185563 = LINE('',#185564,#185565); -#185564 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185565 = VECTOR('',#185566,1.); -#185566 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185568 = ORIENTED_EDGE('',*,*,#185569,.T.); -#185569 = EDGE_CURVE('',#185542,#185570,#185572,.T.); -#185570 = VERTEX_POINT('',#185571); -#185571 = CARTESIAN_POINT('',(0.2,0.65,0.6)); -#185572 = SURFACE_CURVE('',#185573,(#185577,#185584),.PCURVE_S1.); -#185573 = LINE('',#185574,#185575); -#185574 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185575 = VECTOR('',#185576,1.); -#185576 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185577 = PCURVE('',#185349,#185578); -#185578 = DEFINITIONAL_REPRESENTATION('',(#185579),#185583); -#185579 = LINE('',#185580,#185581); -#185580 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185581 = VECTOR('',#185582,1.); -#185582 = DIRECTION('',(0.E+000,-1.)); -#185583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185584 = PCURVE('',#185473,#185585); -#185585 = DEFINITIONAL_REPRESENTATION('',(#185586),#185590); -#185586 = LINE('',#185587,#185588); -#185587 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185588 = VECTOR('',#185589,1.); -#185589 = DIRECTION('',(0.E+000,-1.)); -#185590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185591 = ORIENTED_EDGE('',*,*,#185592,.T.); -#185592 = EDGE_CURVE('',#185570,#185593,#185595,.T.); -#185593 = VERTEX_POINT('',#185594); -#185594 = CARTESIAN_POINT('',(0.2,0.609807621135,0.75)); -#185595 = SURFACE_CURVE('',#185596,(#185600,#185607),.PCURVE_S1.); -#185596 = LINE('',#185597,#185598); -#185597 = CARTESIAN_POINT('',(0.2,0.65,0.6)); -#185598 = VECTOR('',#185599,1.); -#185599 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185600 = PCURVE('',#185349,#185601); -#185601 = DEFINITIONAL_REPRESENTATION('',(#185602),#185606); -#185602 = LINE('',#185603,#185604); -#185603 = CARTESIAN_POINT('',(0.E+000,1.66)); -#185604 = VECTOR('',#185605,1.); -#185605 = DIRECTION('',(1.,0.E+000)); -#185606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185607 = PCURVE('',#185608,#185613); -#185608 = PLANE('',#185609); -#185609 = AXIS2_PLACEMENT_3D('',#185610,#185611,#185612); -#185610 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); -#185611 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185612 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185613 = DEFINITIONAL_REPRESENTATION('',(#185614),#185618); -#185614 = LINE('',#185615,#185616); -#185615 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185616 = VECTOR('',#185617,1.); -#185617 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185619 = ORIENTED_EDGE('',*,*,#185620,.T.); -#185620 = EDGE_CURVE('',#185593,#185621,#185623,.T.); -#185621 = VERTEX_POINT('',#185622); -#185622 = CARTESIAN_POINT('',(-0.2,0.609807621135,0.75)); -#185623 = SURFACE_CURVE('',#185624,(#185628,#185635),.PCURVE_S1.); -#185624 = LINE('',#185625,#185626); -#185625 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); -#185626 = VECTOR('',#185627,1.); -#185627 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185628 = PCURVE('',#185349,#185629); -#185629 = DEFINITIONAL_REPRESENTATION('',(#185630),#185634); -#185630 = LINE('',#185631,#185632); -#185631 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); -#185632 = VECTOR('',#185633,1.); -#185633 = DIRECTION('',(0.E+000,-1.)); -#185634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185635 = PCURVE('',#185636,#185641); -#185636 = PLANE('',#185637); -#185637 = AXIS2_PLACEMENT_3D('',#185638,#185639,#185640); -#185638 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#185639 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185640 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185641 = DEFINITIONAL_REPRESENTATION('',(#185642),#185646); -#185642 = LINE('',#185643,#185644); -#185643 = CARTESIAN_POINT('',(-1.26,-4.54003800589E-002)); -#185644 = VECTOR('',#185645,1.); -#185645 = DIRECTION('',(-1.,0.E+000)); -#185646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185647 = ORIENTED_EDGE('',*,*,#185648,.F.); -#185648 = EDGE_CURVE('',#185649,#185621,#185651,.T.); -#185649 = VERTEX_POINT('',#185650); -#185650 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); -#185651 = SURFACE_CURVE('',#185652,(#185656,#185663),.PCURVE_S1.); -#185652 = LINE('',#185653,#185654); -#185653 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); -#185654 = VECTOR('',#185655,1.); -#185655 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185656 = PCURVE('',#185349,#185657); -#185657 = DEFINITIONAL_REPRESENTATION('',(#185658),#185662); -#185658 = LINE('',#185659,#185660); -#185659 = CARTESIAN_POINT('',(0.E+000,1.26)); -#185660 = VECTOR('',#185661,1.); -#185661 = DIRECTION('',(1.,0.E+000)); -#185662 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185663 = PCURVE('',#185664,#185669); -#185664 = PLANE('',#185665); -#185665 = AXIS2_PLACEMENT_3D('',#185666,#185667,#185668); -#185666 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#185667 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185668 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185669 = DEFINITIONAL_REPRESENTATION('',(#185670),#185674); -#185670 = LINE('',#185671,#185672); -#185671 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185672 = VECTOR('',#185673,1.); -#185673 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185674 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185675 = ORIENTED_EDGE('',*,*,#185676,.T.); -#185676 = EDGE_CURVE('',#185649,#185677,#185679,.T.); -#185677 = VERTEX_POINT('',#185678); -#185678 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); -#185679 = SURFACE_CURVE('',#185680,(#185684,#185691),.PCURVE_S1.); -#185680 = LINE('',#185681,#185682); -#185681 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185682 = VECTOR('',#185683,1.); -#185683 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185684 = PCURVE('',#185349,#185685); -#185685 = DEFINITIONAL_REPRESENTATION('',(#185686),#185690); -#185686 = LINE('',#185687,#185688); -#185687 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185688 = VECTOR('',#185689,1.); -#185689 = DIRECTION('',(0.E+000,-1.)); -#185690 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185691 = PCURVE('',#185473,#185692); -#185692 = DEFINITIONAL_REPRESENTATION('',(#185693),#185697); -#185693 = LINE('',#185694,#185695); -#185694 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185695 = VECTOR('',#185696,1.); -#185696 = DIRECTION('',(0.E+000,-1.)); -#185697 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185698 = ORIENTED_EDGE('',*,*,#185699,.T.); -#185699 = EDGE_CURVE('',#185677,#185700,#185702,.T.); -#185700 = VERTEX_POINT('',#185701); -#185701 = CARTESIAN_POINT('',(-0.745,0.609807621135,0.75)); -#185702 = SURFACE_CURVE('',#185703,(#185707,#185714),.PCURVE_S1.); -#185703 = LINE('',#185704,#185705); -#185704 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); -#185705 = VECTOR('',#185706,1.); -#185706 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185707 = PCURVE('',#185349,#185708); -#185708 = DEFINITIONAL_REPRESENTATION('',(#185709),#185713); -#185709 = LINE('',#185710,#185711); -#185710 = CARTESIAN_POINT('',(0.E+000,0.715)); -#185711 = VECTOR('',#185712,1.); -#185712 = DIRECTION('',(1.,0.E+000)); -#185713 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185714 = PCURVE('',#185715,#185720); -#185715 = PLANE('',#185716); -#185716 = AXIS2_PLACEMENT_3D('',#185717,#185718,#185719); -#185717 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#185718 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185719 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185720 = DEFINITIONAL_REPRESENTATION('',(#185721),#185725); -#185721 = LINE('',#185722,#185723); -#185722 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185723 = VECTOR('',#185724,1.); -#185724 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185726 = ORIENTED_EDGE('',*,*,#185727,.T.); -#185727 = EDGE_CURVE('',#185700,#185728,#185730,.T.); -#185728 = VERTEX_POINT('',#185729); -#185729 = CARTESIAN_POINT('',(-1.145,0.609807621135,0.75)); -#185730 = SURFACE_CURVE('',#185731,(#185735,#185742),.PCURVE_S1.); -#185731 = LINE('',#185732,#185733); -#185732 = CARTESIAN_POINT('',(-3.36,0.609807621135,0.75)); -#185733 = VECTOR('',#185734,1.); -#185734 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185735 = PCURVE('',#185349,#185736); -#185736 = DEFINITIONAL_REPRESENTATION('',(#185737),#185741); -#185737 = LINE('',#185738,#185739); -#185738 = CARTESIAN_POINT('',(0.155291427062,-1.9)); -#185739 = VECTOR('',#185740,1.); -#185740 = DIRECTION('',(0.E+000,-1.)); -#185741 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185742 = PCURVE('',#185743,#185748); -#185743 = PLANE('',#185744); -#185744 = AXIS2_PLACEMENT_3D('',#185745,#185746,#185747); -#185745 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#185746 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185747 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185748 = DEFINITIONAL_REPRESENTATION('',(#185749),#185753); -#185749 = LINE('',#185750,#185751); -#185750 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); -#185751 = VECTOR('',#185752,1.); -#185752 = DIRECTION('',(-1.,0.E+000)); -#185753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185754 = ORIENTED_EDGE('',*,*,#185755,.F.); -#185755 = EDGE_CURVE('',#185756,#185728,#185758,.T.); -#185756 = VERTEX_POINT('',#185757); -#185757 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); -#185758 = SURFACE_CURVE('',#185759,(#185763,#185770),.PCURVE_S1.); -#185759 = LINE('',#185760,#185761); -#185760 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); -#185761 = VECTOR('',#185762,1.); -#185762 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); -#185763 = PCURVE('',#185349,#185764); -#185764 = DEFINITIONAL_REPRESENTATION('',(#185765),#185769); -#185765 = LINE('',#185766,#185767); -#185766 = CARTESIAN_POINT('',(0.E+000,0.315)); -#185767 = VECTOR('',#185768,1.); -#185768 = DIRECTION('',(1.,0.E+000)); -#185769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185770 = PCURVE('',#185771,#185776); -#185771 = PLANE('',#185772); -#185772 = AXIS2_PLACEMENT_3D('',#185773,#185774,#185775); -#185773 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#185774 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185775 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185776 = DEFINITIONAL_REPRESENTATION('',(#185777),#185781); -#185777 = LINE('',#185778,#185779); -#185778 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); -#185779 = VECTOR('',#185780,1.); -#185780 = DIRECTION('',(-0.965925826289,-0.258819045103)); -#185781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185782 = ORIENTED_EDGE('',*,*,#185783,.T.); -#185783 = EDGE_CURVE('',#185756,#185341,#185784,.T.); -#185784 = SURFACE_CURVE('',#185785,(#185789,#185796),.PCURVE_S1.); -#185785 = LINE('',#185786,#185787); -#185786 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#185787 = VECTOR('',#185788,1.); -#185788 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185789 = PCURVE('',#185349,#185790); -#185790 = DEFINITIONAL_REPRESENTATION('',(#185791),#185795); -#185791 = LINE('',#185792,#185793); -#185792 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185793 = VECTOR('',#185794,1.); -#185794 = DIRECTION('',(0.E+000,-1.)); -#185795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185796 = PCURVE('',#185473,#185797); -#185797 = DEFINITIONAL_REPRESENTATION('',(#185798),#185802); -#185798 = LINE('',#185799,#185800); -#185799 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185800 = VECTOR('',#185801,1.); -#185801 = DIRECTION('',(0.E+000,-1.)); -#185802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185803 = ADVANCED_FACE('',(#185804),#185816,.T.); -#185804 = FACE_BOUND('',#185805,.T.); -#185805 = EDGE_LOOP('',(#185806,#185833,#185855,#185900,#185928,#185956, - #185984,#186012,#186035,#186063,#186091,#186119,#186142,#186170, - #186198,#186226)); -#185806 = ORIENTED_EDGE('',*,*,#185807,.T.); -#185807 = EDGE_CURVE('',#185808,#184366,#185810,.T.); -#185808 = VERTEX_POINT('',#185809); -#185809 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); -#185810 = SURFACE_CURVE('',#185811,(#185815,#185827),.PCURVE_S1.); -#185811 = LINE('',#185812,#185813); -#185812 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, +#188011 = ORIENTED_EDGE('',*,*,#188012,.T.); +#188012 = EDGE_CURVE('',#187985,#188013,#188015,.T.); +#188013 = VERTEX_POINT('',#188014); +#188014 = CARTESIAN_POINT('',(-0.2,0.609807621135,0.75)); +#188015 = SURFACE_CURVE('',#188016,(#188020,#188027),.PCURVE_S1.); +#188016 = LINE('',#188017,#188018); +#188017 = CARTESIAN_POINT('',(-1.46,0.609807621135,0.75)); +#188018 = VECTOR('',#188019,1.); +#188019 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188020 = PCURVE('',#187741,#188021); +#188021 = DEFINITIONAL_REPRESENTATION('',(#188022),#188026); +#188022 = LINE('',#188023,#188024); +#188023 = CARTESIAN_POINT('',(0.155291427062,0.E+000)); +#188024 = VECTOR('',#188025,1.); +#188025 = DIRECTION('',(0.E+000,-1.)); +#188026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188027 = PCURVE('',#188028,#188033); +#188028 = PLANE('',#188029); +#188029 = AXIS2_PLACEMENT_3D('',#188030,#188031,#188032); +#188030 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#188031 = DIRECTION('',(0.E+000,0.E+000,1.)); +#188032 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188033 = DEFINITIONAL_REPRESENTATION('',(#188034),#188038); +#188034 = LINE('',#188035,#188036); +#188035 = CARTESIAN_POINT('',(-1.26,-4.54003800589E-002)); +#188036 = VECTOR('',#188037,1.); +#188037 = DIRECTION('',(-1.,0.E+000)); +#188038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188039 = ORIENTED_EDGE('',*,*,#188040,.F.); +#188040 = EDGE_CURVE('',#188041,#188013,#188043,.T.); +#188041 = VERTEX_POINT('',#188042); +#188042 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); +#188043 = SURFACE_CURVE('',#188044,(#188048,#188055),.PCURVE_S1.); +#188044 = LINE('',#188045,#188046); +#188045 = CARTESIAN_POINT('',(-0.2,0.65,0.6)); +#188046 = VECTOR('',#188047,1.); +#188047 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#188048 = PCURVE('',#187741,#188049); +#188049 = DEFINITIONAL_REPRESENTATION('',(#188050),#188054); +#188050 = LINE('',#188051,#188052); +#188051 = CARTESIAN_POINT('',(0.E+000,1.26)); +#188052 = VECTOR('',#188053,1.); +#188053 = DIRECTION('',(1.,0.E+000)); +#188054 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188055 = PCURVE('',#188056,#188061); +#188056 = PLANE('',#188057); +#188057 = AXIS2_PLACEMENT_3D('',#188058,#188059,#188060); +#188058 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#188059 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188060 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188061 = DEFINITIONAL_REPRESENTATION('',(#188062),#188066); +#188062 = LINE('',#188063,#188064); +#188063 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#188064 = VECTOR('',#188065,1.); +#188065 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#188066 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188067 = ORIENTED_EDGE('',*,*,#188068,.T.); +#188068 = EDGE_CURVE('',#188041,#188069,#188071,.T.); +#188069 = VERTEX_POINT('',#188070); +#188070 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); +#188071 = SURFACE_CURVE('',#188072,(#188076,#188083),.PCURVE_S1.); +#188072 = LINE('',#188073,#188074); +#188073 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#188074 = VECTOR('',#188075,1.); +#188075 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188076 = PCURVE('',#187741,#188077); +#188077 = DEFINITIONAL_REPRESENTATION('',(#188078),#188082); +#188078 = LINE('',#188079,#188080); +#188079 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188080 = VECTOR('',#188081,1.); +#188081 = DIRECTION('',(0.E+000,-1.)); +#188082 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188083 = PCURVE('',#187865,#188084); +#188084 = DEFINITIONAL_REPRESENTATION('',(#188085),#188089); +#188085 = LINE('',#188086,#188087); +#188086 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188087 = VECTOR('',#188088,1.); +#188088 = DIRECTION('',(0.E+000,-1.)); +#188089 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188090 = ORIENTED_EDGE('',*,*,#188091,.T.); +#188091 = EDGE_CURVE('',#188069,#188092,#188094,.T.); +#188092 = VERTEX_POINT('',#188093); +#188093 = CARTESIAN_POINT('',(-0.745,0.609807621135,0.75)); +#188094 = SURFACE_CURVE('',#188095,(#188099,#188106),.PCURVE_S1.); +#188095 = LINE('',#188096,#188097); +#188096 = CARTESIAN_POINT('',(-0.745,0.65,0.6)); +#188097 = VECTOR('',#188098,1.); +#188098 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#188099 = PCURVE('',#187741,#188100); +#188100 = DEFINITIONAL_REPRESENTATION('',(#188101),#188105); +#188101 = LINE('',#188102,#188103); +#188102 = CARTESIAN_POINT('',(0.E+000,0.715)); +#188103 = VECTOR('',#188104,1.); +#188104 = DIRECTION('',(1.,0.E+000)); +#188105 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188106 = PCURVE('',#188107,#188112); +#188107 = PLANE('',#188108); +#188108 = AXIS2_PLACEMENT_3D('',#188109,#188110,#188111); +#188109 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#188110 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188111 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188112 = DEFINITIONAL_REPRESENTATION('',(#188113),#188117); +#188113 = LINE('',#188114,#188115); +#188114 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#188115 = VECTOR('',#188116,1.); +#188116 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#188117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188118 = ORIENTED_EDGE('',*,*,#188119,.T.); +#188119 = EDGE_CURVE('',#188092,#188120,#188122,.T.); +#188120 = VERTEX_POINT('',#188121); +#188121 = CARTESIAN_POINT('',(-1.145,0.609807621135,0.75)); +#188122 = SURFACE_CURVE('',#188123,(#188127,#188134),.PCURVE_S1.); +#188123 = LINE('',#188124,#188125); +#188124 = CARTESIAN_POINT('',(-3.36,0.609807621135,0.75)); +#188125 = VECTOR('',#188126,1.); +#188126 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188127 = PCURVE('',#187741,#188128); +#188128 = DEFINITIONAL_REPRESENTATION('',(#188129),#188133); +#188129 = LINE('',#188130,#188131); +#188130 = CARTESIAN_POINT('',(0.155291427062,-1.9)); +#188131 = VECTOR('',#188132,1.); +#188132 = DIRECTION('',(0.E+000,-1.)); +#188133 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188134 = PCURVE('',#188135,#188140); +#188135 = PLANE('',#188136); +#188136 = AXIS2_PLACEMENT_3D('',#188137,#188138,#188139); +#188137 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#188138 = DIRECTION('',(0.E+000,0.E+000,1.)); +#188139 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188140 = DEFINITIONAL_REPRESENTATION('',(#188141),#188145); +#188141 = LINE('',#188142,#188143); +#188142 = CARTESIAN_POINT('',(-2.215,-4.54003800589E-002)); +#188143 = VECTOR('',#188144,1.); +#188144 = DIRECTION('',(-1.,0.E+000)); +#188145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188146 = ORIENTED_EDGE('',*,*,#188147,.F.); +#188147 = EDGE_CURVE('',#188148,#188120,#188150,.T.); +#188148 = VERTEX_POINT('',#188149); +#188149 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); +#188150 = SURFACE_CURVE('',#188151,(#188155,#188162),.PCURVE_S1.); +#188151 = LINE('',#188152,#188153); +#188152 = CARTESIAN_POINT('',(-1.145,0.65,0.6)); +#188153 = VECTOR('',#188154,1.); +#188154 = DIRECTION('',(0.E+000,-0.258819045103,0.965925826289)); +#188155 = PCURVE('',#187741,#188156); +#188156 = DEFINITIONAL_REPRESENTATION('',(#188157),#188161); +#188157 = LINE('',#188158,#188159); +#188158 = CARTESIAN_POINT('',(0.E+000,0.315)); +#188159 = VECTOR('',#188160,1.); +#188160 = DIRECTION('',(1.,0.E+000)); +#188161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188162 = PCURVE('',#188163,#188168); +#188163 = PLANE('',#188164); +#188164 = AXIS2_PLACEMENT_3D('',#188165,#188166,#188167); +#188165 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#188166 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188167 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188168 = DEFINITIONAL_REPRESENTATION('',(#188169),#188173); +#188169 = LINE('',#188170,#188171); +#188170 = CARTESIAN_POINT('',(-5.E-002,-5.208001194232E-003)); +#188171 = VECTOR('',#188172,1.); +#188172 = DIRECTION('',(-0.965925826289,-0.258819045103)); +#188173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188174 = ORIENTED_EDGE('',*,*,#188175,.T.); +#188175 = EDGE_CURVE('',#188148,#187733,#188176,.T.); +#188176 = SURFACE_CURVE('',#188177,(#188181,#188188),.PCURVE_S1.); +#188177 = LINE('',#188178,#188179); +#188178 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#188179 = VECTOR('',#188180,1.); +#188180 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188181 = PCURVE('',#187741,#188182); +#188182 = DEFINITIONAL_REPRESENTATION('',(#188183),#188187); +#188183 = LINE('',#188184,#188185); +#188184 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188185 = VECTOR('',#188186,1.); +#188186 = DIRECTION('',(0.E+000,-1.)); +#188187 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188188 = PCURVE('',#187865,#188189); +#188189 = DEFINITIONAL_REPRESENTATION('',(#188190),#188194); +#188190 = LINE('',#188191,#188192); +#188191 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188192 = VECTOR('',#188193,1.); +#188193 = DIRECTION('',(0.E+000,-1.)); +#188194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188195 = ADVANCED_FACE('',(#188196),#188208,.T.); +#188196 = FACE_BOUND('',#188197,.T.); +#188197 = EDGE_LOOP('',(#188198,#188225,#188247,#188292,#188320,#188348, + #188376,#188404,#188427,#188455,#188483,#188511,#188534,#188562, + #188590,#188618)); +#188198 = ORIENTED_EDGE('',*,*,#188199,.T.); +#188199 = EDGE_CURVE('',#188200,#186758,#188202,.T.); +#188200 = VERTEX_POINT('',#188201); +#188201 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); +#188202 = SURFACE_CURVE('',#188203,(#188207,#188219),.PCURVE_S1.); +#188203 = LINE('',#188204,#188205); +#188204 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, 1.250221218888)); -#185813 = VECTOR('',#185814,1.); -#185814 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#185815 = PCURVE('',#185816,#185821); -#185816 = PLANE('',#185817); -#185817 = AXIS2_PLACEMENT_3D('',#185818,#185819,#185820); -#185818 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#185819 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); -#185820 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#185821 = DEFINITIONAL_REPRESENTATION('',(#185822),#185826); -#185822 = LINE('',#185823,#185824); -#185823 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); -#185824 = VECTOR('',#185825,1.); -#185825 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#185826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185827 = PCURVE('',#184421,#185828); -#185828 = DEFINITIONAL_REPRESENTATION('',(#185829),#185832); -#185829 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185830,#185831), +#188205 = VECTOR('',#188206,1.); +#188206 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#188207 = PCURVE('',#188208,#188213); +#188208 = PLANE('',#188209); +#188209 = AXIS2_PLACEMENT_3D('',#188210,#188211,#188212); +#188210 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188211 = DIRECTION('',(0.E+000,-0.965925826289,0.258819045103)); +#188212 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188213 = DEFINITIONAL_REPRESENTATION('',(#188214),#188218); +#188214 = LINE('',#188215,#188216); +#188215 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); +#188216 = VECTOR('',#188217,1.); +#188217 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#188218 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188219 = PCURVE('',#186813,#188220); +#188220 = DEFINITIONAL_REPRESENTATION('',(#188221),#188224); +#188221 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188222,#188223), .UNSPECIFIED.,.F.,.F.,(2,2),(-0.69533963372,-0.307214451902), .PIECEWISE_BEZIER_KNOTS.); -#185830 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#185831 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); -#185832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#188222 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#188223 = CARTESIAN_POINT('',(4.64535148218,-9.869729557715E-002)); +#188224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185833 = ORIENTED_EDGE('',*,*,#185834,.T.); -#185834 = EDGE_CURVE('',#184366,#185835,#185837,.T.); -#185835 = VERTEX_POINT('',#185836); -#185836 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, +#188225 = ORIENTED_EDGE('',*,*,#188226,.T.); +#188226 = EDGE_CURVE('',#186758,#188227,#188229,.T.); +#188227 = VERTEX_POINT('',#188228); +#188228 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, 0.962940952255)); -#185837 = SURFACE_CURVE('',#185838,(#185842,#185849),.PCURVE_S1.); -#185838 = LINE('',#185839,#185840); -#185839 = CARTESIAN_POINT('',(-1.207931449084,-0.552750264943, +#188229 = SURFACE_CURVE('',#188230,(#188234,#188241),.PCURVE_S1.); +#188230 = LINE('',#188231,#188232); +#188231 = CARTESIAN_POINT('',(-1.207931449084,-0.552750264943, 0.962940952255)); -#185840 = VECTOR('',#185841,1.); -#185841 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#185842 = PCURVE('',#185816,#185843); -#185843 = DEFINITIONAL_REPRESENTATION('',(#185844),#185848); -#185844 = LINE('',#185845,#185846); -#185845 = CARTESIAN_POINT('',(-0.375744122765,0.252068550916)); -#185846 = VECTOR('',#185847,1.); -#185847 = DIRECTION('',(0.E+000,-1.)); -#185848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185849 = PCURVE('',#184624,#185850); -#185850 = DEFINITIONAL_REPRESENTATION('',(#185851),#185854); -#185851 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#185852,#185853), +#188232 = VECTOR('',#188233,1.); +#188233 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188234 = PCURVE('',#188208,#188235); +#188235 = DEFINITIONAL_REPRESENTATION('',(#188236),#188240); +#188236 = LINE('',#188237,#188238); +#188237 = CARTESIAN_POINT('',(-0.375744122765,0.252068550916)); +#188238 = VECTOR('',#188239,1.); +#188239 = DIRECTION('',(0.E+000,-1.)); +#188240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188241 = PCURVE('',#187016,#188242); +#188242 = DEFINITIONAL_REPRESENTATION('',(#188243),#188246); +#188243 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188244,#188245), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#185852 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); -#185853 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); -#185854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#188244 = CARTESIAN_POINT('',(4.450589592586,-0.242138609)); +#188245 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); +#188246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#185855 = ORIENTED_EDGE('',*,*,#185856,.T.); -#185856 = EDGE_CURVE('',#185835,#185857,#185859,.T.); -#185857 = VERTEX_POINT('',#185858); -#185858 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); -#185859 = SURFACE_CURVE('',#185860,(#185864,#185871),.PCURVE_S1.); -#185860 = LINE('',#185861,#185862); -#185861 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, +#188247 = ORIENTED_EDGE('',*,*,#188248,.T.); +#188248 = EDGE_CURVE('',#188227,#188249,#188251,.T.); +#188249 = VERTEX_POINT('',#188250); +#188250 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); +#188251 = SURFACE_CURVE('',#188252,(#188256,#188263),.PCURVE_S1.); +#188252 = LINE('',#188253,#188254); +#188253 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, 0.566051874704)); -#185862 = VECTOR('',#185863,1.); -#185863 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#185864 = PCURVE('',#185816,#185865); -#185865 = DEFINITIONAL_REPRESENTATION('',(#185866),#185870); -#185866 = LINE('',#185867,#185868); -#185867 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#185868 = VECTOR('',#185869,1.); -#185869 = DIRECTION('',(0.968100345886,-0.250562807086)); -#185870 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185871 = PCURVE('',#184118,#185872); -#185872 = DEFINITIONAL_REPRESENTATION('',(#185873),#185899); -#185873 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#185874,#185875,#185876, - #185877,#185878,#185879,#185880,#185881,#185882,#185883,#185884, - #185885,#185886,#185887,#185888,#185889,#185890,#185891,#185892, - #185893,#185894,#185895,#185896,#185897,#185898),.UNSPECIFIED.,.F., +#188254 = VECTOR('',#188255,1.); +#188255 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#188256 = PCURVE('',#188208,#188257); +#188257 = DEFINITIONAL_REPRESENTATION('',(#188258),#188262); +#188258 = LINE('',#188259,#188260); +#188259 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#188260 = VECTOR('',#188261,1.); +#188261 = DIRECTION('',(0.968100345886,-0.250562807086)); +#188262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188263 = PCURVE('',#186510,#188264); +#188264 = DEFINITIONAL_REPRESENTATION('',(#188265),#188291); +#188265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188266,#188267,#188268, + #188269,#188270,#188271,#188272,#188273,#188274,#188275,#188276, + #188277,#188278,#188279,#188280,#188281,#188282,#188283,#188284, + #188285,#188286,#188287,#188288,#188289,#188290),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.424428944789, -0.40678689107,-0.389144837351,-0.371502783632,-0.353860729913, -0.336218676194,-0.318576622475,-0.300934568756,-0.283292515037, @@ -230744,472 +233746,472 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.124514031566,-0.106871977847,-8.922992412772E-002, -7.158787040873E-002,-5.394581668973E-002,-3.630376297074E-002), .QUASI_UNIFORM_KNOTS.); -#185874 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); -#185875 = CARTESIAN_POINT('',(4.77942647859,-0.418548260216)); -#185876 = CARTESIAN_POINT('',(4.77942647859,-0.40678689107)); -#185877 = CARTESIAN_POINT('',(4.77942647859,-0.389144837351)); -#185878 = CARTESIAN_POINT('',(4.77942647859,-0.371502783632)); -#185879 = CARTESIAN_POINT('',(4.77942647859,-0.353860729913)); -#185880 = CARTESIAN_POINT('',(4.77942647859,-0.336218676194)); -#185881 = CARTESIAN_POINT('',(4.77942647859,-0.318576622475)); -#185882 = CARTESIAN_POINT('',(4.77942647859,-0.300934568756)); -#185883 = CARTESIAN_POINT('',(4.77942647859,-0.283292515037)); -#185884 = CARTESIAN_POINT('',(4.77942647859,-0.265650461318)); -#185885 = CARTESIAN_POINT('',(4.77942647859,-0.248008407599)); -#185886 = CARTESIAN_POINT('',(4.77942647859,-0.23036635388)); -#185887 = CARTESIAN_POINT('',(4.77942647859,-0.212724300161)); -#185888 = CARTESIAN_POINT('',(4.77942647859,-0.195082246442)); -#185889 = CARTESIAN_POINT('',(4.77942647859,-0.177440192723)); -#185890 = CARTESIAN_POINT('',(4.77942647859,-0.159798139004)); -#185891 = CARTESIAN_POINT('',(4.77942647859,-0.142156085285)); -#185892 = CARTESIAN_POINT('',(4.77942647859,-0.124514031566)); -#185893 = CARTESIAN_POINT('',(4.77942647859,-0.106871977847)); -#185894 = CARTESIAN_POINT('',(4.77942647859,-8.922992412772E-002)); -#185895 = CARTESIAN_POINT('',(4.77942647859,-7.158787040873E-002)); -#185896 = CARTESIAN_POINT('',(4.77942647859,-5.394581668973E-002)); -#185897 = CARTESIAN_POINT('',(4.77942647859,-4.218444754374E-002)); -#185898 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#185899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185900 = ORIENTED_EDGE('',*,*,#185901,.T.); -#185901 = EDGE_CURVE('',#185857,#185902,#185904,.T.); -#185902 = VERTEX_POINT('',#185903); -#185903 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); -#185904 = SURFACE_CURVE('',#185905,(#185909,#185916),.PCURVE_S1.); -#185905 = LINE('',#185906,#185907); -#185906 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#185907 = VECTOR('',#185908,1.); -#185908 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185909 = PCURVE('',#185816,#185910); -#185910 = DEFINITIONAL_REPRESENTATION('',(#185911),#185915); -#185911 = LINE('',#185912,#185913); -#185912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185913 = VECTOR('',#185914,1.); -#185914 = DIRECTION('',(0.E+000,1.)); -#185915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185916 = PCURVE('',#185917,#185922); -#185917 = PLANE('',#185918); -#185918 = AXIS2_PLACEMENT_3D('',#185919,#185920,#185921); -#185919 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#185920 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); -#185921 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); -#185922 = DEFINITIONAL_REPRESENTATION('',(#185923),#185927); -#185923 = LINE('',#185924,#185925); -#185924 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#185925 = VECTOR('',#185926,1.); -#185926 = DIRECTION('',(0.E+000,1.)); -#185927 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185928 = ORIENTED_EDGE('',*,*,#185929,.F.); -#185929 = EDGE_CURVE('',#185930,#185902,#185932,.T.); -#185930 = VERTEX_POINT('',#185931); -#185931 = CARTESIAN_POINT('',(-1.145,-0.609807621135,0.75)); -#185932 = SURFACE_CURVE('',#185933,(#185937,#185944),.PCURVE_S1.); -#185933 = LINE('',#185934,#185935); -#185934 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); -#185935 = VECTOR('',#185936,1.); -#185936 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#185937 = PCURVE('',#185816,#185938); -#185938 = DEFINITIONAL_REPRESENTATION('',(#185939),#185943); -#185939 = LINE('',#185940,#185941); -#185940 = CARTESIAN_POINT('',(0.E+000,0.315)); -#185941 = VECTOR('',#185942,1.); -#185942 = DIRECTION('',(1.,0.E+000)); -#185943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185944 = PCURVE('',#185945,#185950); -#185945 = PLANE('',#185946); -#185946 = AXIS2_PLACEMENT_3D('',#185947,#185948,#185949); -#185947 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#185948 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185949 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#185950 = DEFINITIONAL_REPRESENTATION('',(#185951),#185955); -#185951 = LINE('',#185952,#185953); -#185952 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#185953 = VECTOR('',#185954,1.); -#185954 = DIRECTION('',(0.965925826289,-0.258819045103)); -#185955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185956 = ORIENTED_EDGE('',*,*,#185957,.T.); -#185957 = EDGE_CURVE('',#185930,#185958,#185960,.T.); -#185958 = VERTEX_POINT('',#185959); -#185959 = CARTESIAN_POINT('',(-0.745,-0.609807621135,0.75)); -#185960 = SURFACE_CURVE('',#185961,(#185965,#185972),.PCURVE_S1.); -#185961 = LINE('',#185962,#185963); -#185962 = CARTESIAN_POINT('',(-3.36,-0.609807621135,0.75)); -#185963 = VECTOR('',#185964,1.); -#185964 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185965 = PCURVE('',#185816,#185966); -#185966 = DEFINITIONAL_REPRESENTATION('',(#185967),#185971); -#185967 = LINE('',#185968,#185969); -#185968 = CARTESIAN_POINT('',(-0.155291427062,-1.9)); -#185969 = VECTOR('',#185970,1.); -#185970 = DIRECTION('',(0.E+000,1.)); -#185971 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185972 = PCURVE('',#185973,#185978); -#185973 = PLANE('',#185974); -#185974 = AXIS2_PLACEMENT_3D('',#185975,#185976,#185977); -#185975 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#185976 = DIRECTION('',(0.E+000,0.E+000,1.)); -#185977 = DIRECTION('',(1.,0.E+000,0.E+000)); -#185978 = DEFINITIONAL_REPRESENTATION('',(#185979),#185983); -#185979 = LINE('',#185980,#185981); -#185980 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); -#185981 = VECTOR('',#185982,1.); -#185982 = DIRECTION('',(1.,0.E+000)); -#185983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#185984 = ORIENTED_EDGE('',*,*,#185985,.T.); -#185985 = EDGE_CURVE('',#185958,#185986,#185988,.T.); -#185986 = VERTEX_POINT('',#185987); -#185987 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); -#185988 = SURFACE_CURVE('',#185989,(#185993,#186000),.PCURVE_S1.); -#185989 = LINE('',#185990,#185991); -#185990 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); -#185991 = VECTOR('',#185992,1.); -#185992 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#185993 = PCURVE('',#185816,#185994); -#185994 = DEFINITIONAL_REPRESENTATION('',(#185995),#185999); -#185995 = LINE('',#185996,#185997); -#185996 = CARTESIAN_POINT('',(0.E+000,0.715)); -#185997 = VECTOR('',#185998,1.); -#185998 = DIRECTION('',(1.,0.E+000)); -#185999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186000 = PCURVE('',#186001,#186006); -#186001 = PLANE('',#186002); -#186002 = AXIS2_PLACEMENT_3D('',#186003,#186004,#186005); -#186003 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#186004 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186005 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186006 = DEFINITIONAL_REPRESENTATION('',(#186007),#186011); -#186007 = LINE('',#186008,#186009); -#186008 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#186009 = VECTOR('',#186010,1.); -#186010 = DIRECTION('',(0.965925826289,-0.258819045103)); -#186011 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186012 = ORIENTED_EDGE('',*,*,#186013,.T.); -#186013 = EDGE_CURVE('',#185986,#186014,#186016,.T.); -#186014 = VERTEX_POINT('',#186015); -#186015 = CARTESIAN_POINT('',(-0.2,-0.65,0.6)); -#186016 = SURFACE_CURVE('',#186017,(#186021,#186028),.PCURVE_S1.); -#186017 = LINE('',#186018,#186019); -#186018 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#186019 = VECTOR('',#186020,1.); -#186020 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186021 = PCURVE('',#185816,#186022); -#186022 = DEFINITIONAL_REPRESENTATION('',(#186023),#186027); -#186023 = LINE('',#186024,#186025); -#186024 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186025 = VECTOR('',#186026,1.); -#186026 = DIRECTION('',(0.E+000,1.)); -#186027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186028 = PCURVE('',#185917,#186029); -#186029 = DEFINITIONAL_REPRESENTATION('',(#186030),#186034); -#186030 = LINE('',#186031,#186032); -#186031 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186032 = VECTOR('',#186033,1.); -#186033 = DIRECTION('',(0.E+000,1.)); -#186034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186035 = ORIENTED_EDGE('',*,*,#186036,.F.); -#186036 = EDGE_CURVE('',#186037,#186014,#186039,.T.); -#186037 = VERTEX_POINT('',#186038); -#186038 = CARTESIAN_POINT('',(-0.2,-0.609807621135,0.75)); -#186039 = SURFACE_CURVE('',#186040,(#186044,#186051),.PCURVE_S1.); -#186040 = LINE('',#186041,#186042); -#186041 = CARTESIAN_POINT('',(-0.2,-0.65,0.6)); -#186042 = VECTOR('',#186043,1.); -#186043 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#186044 = PCURVE('',#185816,#186045); -#186045 = DEFINITIONAL_REPRESENTATION('',(#186046),#186050); -#186046 = LINE('',#186047,#186048); -#186047 = CARTESIAN_POINT('',(0.E+000,1.26)); -#186048 = VECTOR('',#186049,1.); -#186049 = DIRECTION('',(1.,0.E+000)); -#186050 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186051 = PCURVE('',#186052,#186057); -#186052 = PLANE('',#186053); -#186053 = AXIS2_PLACEMENT_3D('',#186054,#186055,#186056); -#186054 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); -#186055 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186056 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186057 = DEFINITIONAL_REPRESENTATION('',(#186058),#186062); -#186058 = LINE('',#186059,#186060); -#186059 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#186060 = VECTOR('',#186061,1.); -#186061 = DIRECTION('',(0.965925826289,-0.258819045103)); -#186062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186063 = ORIENTED_EDGE('',*,*,#186064,.T.); -#186064 = EDGE_CURVE('',#186037,#186065,#186067,.T.); -#186065 = VERTEX_POINT('',#186066); -#186066 = CARTESIAN_POINT('',(0.2,-0.609807621135,0.75)); -#186067 = SURFACE_CURVE('',#186068,(#186072,#186079),.PCURVE_S1.); -#186068 = LINE('',#186069,#186070); -#186069 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); -#186070 = VECTOR('',#186071,1.); -#186071 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186072 = PCURVE('',#185816,#186073); -#186073 = DEFINITIONAL_REPRESENTATION('',(#186074),#186078); -#186074 = LINE('',#186075,#186076); -#186075 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); -#186076 = VECTOR('',#186077,1.); -#186077 = DIRECTION('',(0.E+000,1.)); -#186078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186079 = PCURVE('',#186080,#186085); -#186080 = PLANE('',#186081); -#186081 = AXIS2_PLACEMENT_3D('',#186082,#186083,#186084); -#186082 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); -#186083 = DIRECTION('',(0.E+000,0.E+000,1.)); -#186084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186085 = DEFINITIONAL_REPRESENTATION('',(#186086),#186090); -#186086 = LINE('',#186087,#186088); -#186087 = CARTESIAN_POINT('',(-1.26,4.54003800589E-002)); -#186088 = VECTOR('',#186089,1.); -#186089 = DIRECTION('',(1.,0.E+000)); -#186090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#188266 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); +#188267 = CARTESIAN_POINT('',(4.77942647859,-0.418548260216)); +#188268 = CARTESIAN_POINT('',(4.77942647859,-0.40678689107)); +#188269 = CARTESIAN_POINT('',(4.77942647859,-0.389144837351)); +#188270 = CARTESIAN_POINT('',(4.77942647859,-0.371502783632)); +#188271 = CARTESIAN_POINT('',(4.77942647859,-0.353860729913)); +#188272 = CARTESIAN_POINT('',(4.77942647859,-0.336218676194)); +#188273 = CARTESIAN_POINT('',(4.77942647859,-0.318576622475)); +#188274 = CARTESIAN_POINT('',(4.77942647859,-0.300934568756)); +#188275 = CARTESIAN_POINT('',(4.77942647859,-0.283292515037)); +#188276 = CARTESIAN_POINT('',(4.77942647859,-0.265650461318)); +#188277 = CARTESIAN_POINT('',(4.77942647859,-0.248008407599)); +#188278 = CARTESIAN_POINT('',(4.77942647859,-0.23036635388)); +#188279 = CARTESIAN_POINT('',(4.77942647859,-0.212724300161)); +#188280 = CARTESIAN_POINT('',(4.77942647859,-0.195082246442)); +#188281 = CARTESIAN_POINT('',(4.77942647859,-0.177440192723)); +#188282 = CARTESIAN_POINT('',(4.77942647859,-0.159798139004)); +#188283 = CARTESIAN_POINT('',(4.77942647859,-0.142156085285)); +#188284 = CARTESIAN_POINT('',(4.77942647859,-0.124514031566)); +#188285 = CARTESIAN_POINT('',(4.77942647859,-0.106871977847)); +#188286 = CARTESIAN_POINT('',(4.77942647859,-8.922992412772E-002)); +#188287 = CARTESIAN_POINT('',(4.77942647859,-7.158787040873E-002)); +#188288 = CARTESIAN_POINT('',(4.77942647859,-5.394581668973E-002)); +#188289 = CARTESIAN_POINT('',(4.77942647859,-4.218444754374E-002)); +#188290 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#188291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188292 = ORIENTED_EDGE('',*,*,#188293,.T.); +#188293 = EDGE_CURVE('',#188249,#188294,#188296,.T.); +#188294 = VERTEX_POINT('',#188295); +#188295 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); +#188296 = SURFACE_CURVE('',#188297,(#188301,#188308),.PCURVE_S1.); +#188297 = LINE('',#188298,#188299); +#188298 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188299 = VECTOR('',#188300,1.); +#188300 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188301 = PCURVE('',#188208,#188302); +#188302 = DEFINITIONAL_REPRESENTATION('',(#188303),#188307); +#188303 = LINE('',#188304,#188305); +#188304 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188305 = VECTOR('',#188306,1.); +#188306 = DIRECTION('',(0.E+000,1.)); +#188307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188308 = PCURVE('',#188309,#188314); +#188309 = PLANE('',#188310); +#188310 = AXIS2_PLACEMENT_3D('',#188311,#188312,#188313); +#188311 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188312 = DIRECTION('',(0.E+000,-0.965925826289,-0.258819045103)); +#188313 = DIRECTION('',(0.E+000,0.258819045103,-0.965925826289)); +#188314 = DEFINITIONAL_REPRESENTATION('',(#188315),#188319); +#188315 = LINE('',#188316,#188317); +#188316 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188317 = VECTOR('',#188318,1.); +#188318 = DIRECTION('',(0.E+000,1.)); +#188319 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188320 = ORIENTED_EDGE('',*,*,#188321,.F.); +#188321 = EDGE_CURVE('',#188322,#188294,#188324,.T.); +#188322 = VERTEX_POINT('',#188323); +#188323 = CARTESIAN_POINT('',(-1.145,-0.609807621135,0.75)); +#188324 = SURFACE_CURVE('',#188325,(#188329,#188336),.PCURVE_S1.); +#188325 = LINE('',#188326,#188327); +#188326 = CARTESIAN_POINT('',(-1.145,-0.65,0.6)); +#188327 = VECTOR('',#188328,1.); +#188328 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188329 = PCURVE('',#188208,#188330); +#188330 = DEFINITIONAL_REPRESENTATION('',(#188331),#188335); +#188331 = LINE('',#188332,#188333); +#188332 = CARTESIAN_POINT('',(0.E+000,0.315)); +#188333 = VECTOR('',#188334,1.); +#188334 = DIRECTION('',(1.,0.E+000)); +#188335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188336 = PCURVE('',#188337,#188342); +#188337 = PLANE('',#188338); +#188338 = AXIS2_PLACEMENT_3D('',#188339,#188340,#188341); +#188339 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#188340 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188341 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188342 = DEFINITIONAL_REPRESENTATION('',(#188343),#188347); +#188343 = LINE('',#188344,#188345); +#188344 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188345 = VECTOR('',#188346,1.); +#188346 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188348 = ORIENTED_EDGE('',*,*,#188349,.T.); +#188349 = EDGE_CURVE('',#188322,#188350,#188352,.T.); +#188350 = VERTEX_POINT('',#188351); +#188351 = CARTESIAN_POINT('',(-0.745,-0.609807621135,0.75)); +#188352 = SURFACE_CURVE('',#188353,(#188357,#188364),.PCURVE_S1.); +#188353 = LINE('',#188354,#188355); +#188354 = CARTESIAN_POINT('',(-3.36,-0.609807621135,0.75)); +#188355 = VECTOR('',#188356,1.); +#188356 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188357 = PCURVE('',#188208,#188358); +#188358 = DEFINITIONAL_REPRESENTATION('',(#188359),#188363); +#188359 = LINE('',#188360,#188361); +#188360 = CARTESIAN_POINT('',(-0.155291427062,-1.9)); +#188361 = VECTOR('',#188362,1.); +#188362 = DIRECTION('',(0.E+000,1.)); +#188363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188364 = PCURVE('',#188365,#188370); +#188365 = PLANE('',#188366); +#188366 = AXIS2_PLACEMENT_3D('',#188367,#188368,#188369); +#188367 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#188368 = DIRECTION('',(0.E+000,0.E+000,1.)); +#188369 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188370 = DEFINITIONAL_REPRESENTATION('',(#188371),#188375); +#188371 = LINE('',#188372,#188373); +#188372 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); +#188373 = VECTOR('',#188374,1.); +#188374 = DIRECTION('',(1.,0.E+000)); +#188375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188376 = ORIENTED_EDGE('',*,*,#188377,.T.); +#188377 = EDGE_CURVE('',#188350,#188378,#188380,.T.); +#188378 = VERTEX_POINT('',#188379); +#188379 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); +#188380 = SURFACE_CURVE('',#188381,(#188385,#188392),.PCURVE_S1.); +#188381 = LINE('',#188382,#188383); +#188382 = CARTESIAN_POINT('',(-0.745,-0.65,0.6)); +#188383 = VECTOR('',#188384,1.); +#188384 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188385 = PCURVE('',#188208,#188386); +#188386 = DEFINITIONAL_REPRESENTATION('',(#188387),#188391); +#188387 = LINE('',#188388,#188389); +#188388 = CARTESIAN_POINT('',(0.E+000,0.715)); +#188389 = VECTOR('',#188390,1.); +#188390 = DIRECTION('',(1.,0.E+000)); +#188391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188392 = PCURVE('',#188393,#188398); +#188393 = PLANE('',#188394); +#188394 = AXIS2_PLACEMENT_3D('',#188395,#188396,#188397); +#188395 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#188396 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188397 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188398 = DEFINITIONAL_REPRESENTATION('',(#188399),#188403); +#188399 = LINE('',#188400,#188401); +#188400 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188401 = VECTOR('',#188402,1.); +#188402 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188404 = ORIENTED_EDGE('',*,*,#188405,.T.); +#188405 = EDGE_CURVE('',#188378,#188406,#188408,.T.); +#188406 = VERTEX_POINT('',#188407); +#188407 = CARTESIAN_POINT('',(-0.2,-0.65,0.6)); +#188408 = SURFACE_CURVE('',#188409,(#188413,#188420),.PCURVE_S1.); +#188409 = LINE('',#188410,#188411); +#188410 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188411 = VECTOR('',#188412,1.); +#188412 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188413 = PCURVE('',#188208,#188414); +#188414 = DEFINITIONAL_REPRESENTATION('',(#188415),#188419); +#188415 = LINE('',#188416,#188417); +#188416 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188417 = VECTOR('',#188418,1.); +#188418 = DIRECTION('',(0.E+000,1.)); +#188419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188420 = PCURVE('',#188309,#188421); +#188421 = DEFINITIONAL_REPRESENTATION('',(#188422),#188426); +#188422 = LINE('',#188423,#188424); +#188423 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188424 = VECTOR('',#188425,1.); +#188425 = DIRECTION('',(0.E+000,1.)); +#188426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188427 = ORIENTED_EDGE('',*,*,#188428,.F.); +#188428 = EDGE_CURVE('',#188429,#188406,#188431,.T.); +#188429 = VERTEX_POINT('',#188430); +#188430 = CARTESIAN_POINT('',(-0.2,-0.609807621135,0.75)); +#188431 = SURFACE_CURVE('',#188432,(#188436,#188443),.PCURVE_S1.); +#188432 = LINE('',#188433,#188434); +#188433 = CARTESIAN_POINT('',(-0.2,-0.65,0.6)); +#188434 = VECTOR('',#188435,1.); +#188435 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188436 = PCURVE('',#188208,#188437); +#188437 = DEFINITIONAL_REPRESENTATION('',(#188438),#188442); +#188438 = LINE('',#188439,#188440); +#188439 = CARTESIAN_POINT('',(0.E+000,1.26)); +#188440 = VECTOR('',#188441,1.); +#188441 = DIRECTION('',(1.,0.E+000)); +#188442 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188443 = PCURVE('',#188444,#188449); +#188444 = PLANE('',#188445); +#188445 = AXIS2_PLACEMENT_3D('',#188446,#188447,#188448); +#188446 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); +#188447 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188448 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188449 = DEFINITIONAL_REPRESENTATION('',(#188450),#188454); +#188450 = LINE('',#188451,#188452); +#188451 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188452 = VECTOR('',#188453,1.); +#188453 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188455 = ORIENTED_EDGE('',*,*,#188456,.T.); +#188456 = EDGE_CURVE('',#188429,#188457,#188459,.T.); +#188457 = VERTEX_POINT('',#188458); +#188458 = CARTESIAN_POINT('',(0.2,-0.609807621135,0.75)); +#188459 = SURFACE_CURVE('',#188460,(#188464,#188471),.PCURVE_S1.); +#188460 = LINE('',#188461,#188462); +#188461 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); +#188462 = VECTOR('',#188463,1.); +#188463 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188464 = PCURVE('',#188208,#188465); +#188465 = DEFINITIONAL_REPRESENTATION('',(#188466),#188470); +#188466 = LINE('',#188467,#188468); +#188467 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); +#188468 = VECTOR('',#188469,1.); +#188469 = DIRECTION('',(0.E+000,1.)); +#188470 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188471 = PCURVE('',#188472,#188477); +#188472 = PLANE('',#188473); +#188473 = AXIS2_PLACEMENT_3D('',#188474,#188475,#188476); +#188474 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); +#188475 = DIRECTION('',(0.E+000,0.E+000,1.)); +#188476 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188477 = DEFINITIONAL_REPRESENTATION('',(#188478),#188482); +#188478 = LINE('',#188479,#188480); +#188479 = CARTESIAN_POINT('',(-1.26,4.54003800589E-002)); +#188480 = VECTOR('',#188481,1.); +#188481 = DIRECTION('',(1.,0.E+000)); +#188482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186091 = ORIENTED_EDGE('',*,*,#186092,.T.); -#186092 = EDGE_CURVE('',#186065,#186093,#186095,.T.); -#186093 = VERTEX_POINT('',#186094); -#186094 = CARTESIAN_POINT('',(0.2,-0.65,0.6)); -#186095 = SURFACE_CURVE('',#186096,(#186100,#186107),.PCURVE_S1.); -#186096 = LINE('',#186097,#186098); -#186097 = CARTESIAN_POINT('',(0.2,-0.65,0.6)); -#186098 = VECTOR('',#186099,1.); -#186099 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#186100 = PCURVE('',#185816,#186101); -#186101 = DEFINITIONAL_REPRESENTATION('',(#186102),#186106); -#186102 = LINE('',#186103,#186104); -#186103 = CARTESIAN_POINT('',(0.E+000,1.66)); -#186104 = VECTOR('',#186105,1.); -#186105 = DIRECTION('',(1.,0.E+000)); -#186106 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186107 = PCURVE('',#186108,#186113); -#186108 = PLANE('',#186109); -#186109 = AXIS2_PLACEMENT_3D('',#186110,#186111,#186112); -#186110 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); -#186111 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186112 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186113 = DEFINITIONAL_REPRESENTATION('',(#186114),#186118); -#186114 = LINE('',#186115,#186116); -#186115 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#186116 = VECTOR('',#186117,1.); -#186117 = DIRECTION('',(0.965925826289,-0.258819045103)); -#186118 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186119 = ORIENTED_EDGE('',*,*,#186120,.T.); -#186120 = EDGE_CURVE('',#186093,#186121,#186123,.T.); -#186121 = VERTEX_POINT('',#186122); -#186122 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); -#186123 = SURFACE_CURVE('',#186124,(#186128,#186135),.PCURVE_S1.); -#186124 = LINE('',#186125,#186126); -#186125 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#186126 = VECTOR('',#186127,1.); -#186127 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186128 = PCURVE('',#185816,#186129); -#186129 = DEFINITIONAL_REPRESENTATION('',(#186130),#186134); -#186130 = LINE('',#186131,#186132); -#186131 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186132 = VECTOR('',#186133,1.); -#186133 = DIRECTION('',(0.E+000,1.)); -#186134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186135 = PCURVE('',#185917,#186136); -#186136 = DEFINITIONAL_REPRESENTATION('',(#186137),#186141); -#186137 = LINE('',#186138,#186139); -#186138 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186139 = VECTOR('',#186140,1.); -#186140 = DIRECTION('',(0.E+000,1.)); -#186141 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186142 = ORIENTED_EDGE('',*,*,#186143,.F.); -#186143 = EDGE_CURVE('',#186144,#186121,#186146,.T.); -#186144 = VERTEX_POINT('',#186145); -#186145 = CARTESIAN_POINT('',(0.755,-0.609807621135,0.75)); -#186146 = SURFACE_CURVE('',#186147,(#186151,#186158),.PCURVE_S1.); -#186147 = LINE('',#186148,#186149); -#186148 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); -#186149 = VECTOR('',#186150,1.); -#186150 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#186151 = PCURVE('',#185816,#186152); -#186152 = DEFINITIONAL_REPRESENTATION('',(#186153),#186157); -#186153 = LINE('',#186154,#186155); -#186154 = CARTESIAN_POINT('',(0.E+000,2.215)); -#186155 = VECTOR('',#186156,1.); -#186156 = DIRECTION('',(1.,0.E+000)); -#186157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186158 = PCURVE('',#186159,#186164); -#186159 = PLANE('',#186160); -#186160 = AXIS2_PLACEMENT_3D('',#186161,#186162,#186163); -#186161 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#186162 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186163 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186164 = DEFINITIONAL_REPRESENTATION('',(#186165),#186169); -#186165 = LINE('',#186166,#186167); -#186166 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#186167 = VECTOR('',#186168,1.); -#186168 = DIRECTION('',(0.965925826289,-0.258819045103)); -#186169 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186170 = ORIENTED_EDGE('',*,*,#186171,.T.); -#186171 = EDGE_CURVE('',#186144,#186172,#186174,.T.); -#186172 = VERTEX_POINT('',#186173); -#186173 = CARTESIAN_POINT('',(1.155,-0.609807621135,0.75)); -#186174 = SURFACE_CURVE('',#186175,(#186179,#186186),.PCURVE_S1.); -#186175 = LINE('',#186176,#186177); -#186176 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); -#186177 = VECTOR('',#186178,1.); -#186178 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186179 = PCURVE('',#185816,#186180); -#186180 = DEFINITIONAL_REPRESENTATION('',(#186181),#186185); -#186181 = LINE('',#186182,#186183); -#186182 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); -#186183 = VECTOR('',#186184,1.); -#186184 = DIRECTION('',(0.E+000,1.)); -#186185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186186 = PCURVE('',#186187,#186192); -#186187 = PLANE('',#186188); -#186188 = AXIS2_PLACEMENT_3D('',#186189,#186190,#186191); -#186189 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#186190 = DIRECTION('',(0.E+000,0.E+000,1.)); -#186191 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186192 = DEFINITIONAL_REPRESENTATION('',(#186193),#186197); -#186193 = LINE('',#186194,#186195); -#186194 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); -#186195 = VECTOR('',#186196,1.); -#186196 = DIRECTION('',(1.,0.E+000)); -#186197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186198 = ORIENTED_EDGE('',*,*,#186199,.T.); -#186199 = EDGE_CURVE('',#186172,#186200,#186202,.T.); -#186200 = VERTEX_POINT('',#186201); -#186201 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); -#186202 = SURFACE_CURVE('',#186203,(#186207,#186214),.PCURVE_S1.); -#186203 = LINE('',#186204,#186205); -#186204 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); -#186205 = VECTOR('',#186206,1.); -#186206 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); -#186207 = PCURVE('',#185816,#186208); -#186208 = DEFINITIONAL_REPRESENTATION('',(#186209),#186213); -#186209 = LINE('',#186210,#186211); -#186210 = CARTESIAN_POINT('',(0.E+000,2.615)); -#186211 = VECTOR('',#186212,1.); -#186212 = DIRECTION('',(1.,0.E+000)); -#186213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186214 = PCURVE('',#186215,#186220); -#186215 = PLANE('',#186216); -#186216 = AXIS2_PLACEMENT_3D('',#186217,#186218,#186219); -#186217 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#186218 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186219 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186220 = DEFINITIONAL_REPRESENTATION('',(#186221),#186225); -#186221 = LINE('',#186222,#186223); -#186222 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); -#186223 = VECTOR('',#186224,1.); -#186224 = DIRECTION('',(0.965925826289,-0.258819045103)); -#186225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186226 = ORIENTED_EDGE('',*,*,#186227,.T.); -#186227 = EDGE_CURVE('',#186200,#185808,#186228,.T.); -#186228 = SURFACE_CURVE('',#186229,(#186233,#186240),.PCURVE_S1.); -#186229 = LINE('',#186230,#186231); -#186230 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#186231 = VECTOR('',#186232,1.); -#186232 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186233 = PCURVE('',#185816,#186234); -#186234 = DEFINITIONAL_REPRESENTATION('',(#186235),#186239); -#186235 = LINE('',#186236,#186237); -#186236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186237 = VECTOR('',#186238,1.); -#186238 = DIRECTION('',(0.E+000,1.)); -#186239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186240 = PCURVE('',#185917,#186241); -#186241 = DEFINITIONAL_REPRESENTATION('',(#186242),#186246); -#186242 = LINE('',#186243,#186244); -#186243 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186244 = VECTOR('',#186245,1.); -#186245 = DIRECTION('',(0.E+000,1.)); -#186246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186247 = ADVANCED_FACE('',(#186248),#186262,.T.); -#186248 = FACE_BOUND('',#186249,.T.); -#186249 = EDGE_LOOP('',(#186250,#186302,#186345,#186390)); -#186250 = ORIENTED_EDGE('',*,*,#186251,.T.); -#186251 = EDGE_CURVE('',#186252,#186254,#186256,.T.); -#186252 = VERTEX_POINT('',#186253); -#186253 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); -#186254 = VERTEX_POINT('',#186255); -#186255 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, +#188483 = ORIENTED_EDGE('',*,*,#188484,.T.); +#188484 = EDGE_CURVE('',#188457,#188485,#188487,.T.); +#188485 = VERTEX_POINT('',#188486); +#188486 = CARTESIAN_POINT('',(0.2,-0.65,0.6)); +#188487 = SURFACE_CURVE('',#188488,(#188492,#188499),.PCURVE_S1.); +#188488 = LINE('',#188489,#188490); +#188489 = CARTESIAN_POINT('',(0.2,-0.65,0.6)); +#188490 = VECTOR('',#188491,1.); +#188491 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188492 = PCURVE('',#188208,#188493); +#188493 = DEFINITIONAL_REPRESENTATION('',(#188494),#188498); +#188494 = LINE('',#188495,#188496); +#188495 = CARTESIAN_POINT('',(0.E+000,1.66)); +#188496 = VECTOR('',#188497,1.); +#188497 = DIRECTION('',(1.,0.E+000)); +#188498 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188499 = PCURVE('',#188500,#188505); +#188500 = PLANE('',#188501); +#188501 = AXIS2_PLACEMENT_3D('',#188502,#188503,#188504); +#188502 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); +#188503 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188504 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188505 = DEFINITIONAL_REPRESENTATION('',(#188506),#188510); +#188506 = LINE('',#188507,#188508); +#188507 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188508 = VECTOR('',#188509,1.); +#188509 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188511 = ORIENTED_EDGE('',*,*,#188512,.T.); +#188512 = EDGE_CURVE('',#188485,#188513,#188515,.T.); +#188513 = VERTEX_POINT('',#188514); +#188514 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); +#188515 = SURFACE_CURVE('',#188516,(#188520,#188527),.PCURVE_S1.); +#188516 = LINE('',#188517,#188518); +#188517 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188518 = VECTOR('',#188519,1.); +#188519 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188520 = PCURVE('',#188208,#188521); +#188521 = DEFINITIONAL_REPRESENTATION('',(#188522),#188526); +#188522 = LINE('',#188523,#188524); +#188523 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188524 = VECTOR('',#188525,1.); +#188525 = DIRECTION('',(0.E+000,1.)); +#188526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188527 = PCURVE('',#188309,#188528); +#188528 = DEFINITIONAL_REPRESENTATION('',(#188529),#188533); +#188529 = LINE('',#188530,#188531); +#188530 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188531 = VECTOR('',#188532,1.); +#188532 = DIRECTION('',(0.E+000,1.)); +#188533 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188534 = ORIENTED_EDGE('',*,*,#188535,.F.); +#188535 = EDGE_CURVE('',#188536,#188513,#188538,.T.); +#188536 = VERTEX_POINT('',#188537); +#188537 = CARTESIAN_POINT('',(0.755,-0.609807621135,0.75)); +#188538 = SURFACE_CURVE('',#188539,(#188543,#188550),.PCURVE_S1.); +#188539 = LINE('',#188540,#188541); +#188540 = CARTESIAN_POINT('',(0.755,-0.65,0.6)); +#188541 = VECTOR('',#188542,1.); +#188542 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188543 = PCURVE('',#188208,#188544); +#188544 = DEFINITIONAL_REPRESENTATION('',(#188545),#188549); +#188545 = LINE('',#188546,#188547); +#188546 = CARTESIAN_POINT('',(0.E+000,2.215)); +#188547 = VECTOR('',#188548,1.); +#188548 = DIRECTION('',(1.,0.E+000)); +#188549 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188550 = PCURVE('',#188551,#188556); +#188551 = PLANE('',#188552); +#188552 = AXIS2_PLACEMENT_3D('',#188553,#188554,#188555); +#188553 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#188554 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188555 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188556 = DEFINITIONAL_REPRESENTATION('',(#188557),#188561); +#188557 = LINE('',#188558,#188559); +#188558 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188559 = VECTOR('',#188560,1.); +#188560 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188562 = ORIENTED_EDGE('',*,*,#188563,.T.); +#188563 = EDGE_CURVE('',#188536,#188564,#188566,.T.); +#188564 = VERTEX_POINT('',#188565); +#188565 = CARTESIAN_POINT('',(1.155,-0.609807621135,0.75)); +#188566 = SURFACE_CURVE('',#188567,(#188571,#188578),.PCURVE_S1.); +#188567 = LINE('',#188568,#188569); +#188568 = CARTESIAN_POINT('',(-1.46,-0.609807621135,0.75)); +#188569 = VECTOR('',#188570,1.); +#188570 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188571 = PCURVE('',#188208,#188572); +#188572 = DEFINITIONAL_REPRESENTATION('',(#188573),#188577); +#188573 = LINE('',#188574,#188575); +#188574 = CARTESIAN_POINT('',(-0.155291427062,0.E+000)); +#188575 = VECTOR('',#188576,1.); +#188576 = DIRECTION('',(0.E+000,1.)); +#188577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188578 = PCURVE('',#188579,#188584); +#188579 = PLANE('',#188580); +#188580 = AXIS2_PLACEMENT_3D('',#188581,#188582,#188583); +#188581 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#188582 = DIRECTION('',(0.E+000,0.E+000,1.)); +#188583 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188584 = DEFINITIONAL_REPRESENTATION('',(#188585),#188589); +#188585 = LINE('',#188586,#188587); +#188586 = CARTESIAN_POINT('',(-2.215,4.54003800589E-002)); +#188587 = VECTOR('',#188588,1.); +#188588 = DIRECTION('',(1.,0.E+000)); +#188589 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188590 = ORIENTED_EDGE('',*,*,#188591,.T.); +#188591 = EDGE_CURVE('',#188564,#188592,#188594,.T.); +#188592 = VERTEX_POINT('',#188593); +#188593 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); +#188594 = SURFACE_CURVE('',#188595,(#188599,#188606),.PCURVE_S1.); +#188595 = LINE('',#188596,#188597); +#188596 = CARTESIAN_POINT('',(1.155,-0.65,0.6)); +#188597 = VECTOR('',#188598,1.); +#188598 = DIRECTION('',(0.E+000,-0.258819045103,-0.965925826289)); +#188599 = PCURVE('',#188208,#188600); +#188600 = DEFINITIONAL_REPRESENTATION('',(#188601),#188605); +#188601 = LINE('',#188602,#188603); +#188602 = CARTESIAN_POINT('',(0.E+000,2.615)); +#188603 = VECTOR('',#188604,1.); +#188604 = DIRECTION('',(1.,0.E+000)); +#188605 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188606 = PCURVE('',#188607,#188612); +#188607 = PLANE('',#188608); +#188608 = AXIS2_PLACEMENT_3D('',#188609,#188610,#188611); +#188609 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#188610 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188611 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188612 = DEFINITIONAL_REPRESENTATION('',(#188613),#188617); +#188613 = LINE('',#188614,#188615); +#188614 = CARTESIAN_POINT('',(-5.E-002,5.208001194228E-003)); +#188615 = VECTOR('',#188616,1.); +#188616 = DIRECTION('',(0.965925826289,-0.258819045103)); +#188617 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188618 = ORIENTED_EDGE('',*,*,#188619,.T.); +#188619 = EDGE_CURVE('',#188592,#188200,#188620,.T.); +#188620 = SURFACE_CURVE('',#188621,(#188625,#188632),.PCURVE_S1.); +#188621 = LINE('',#188622,#188623); +#188622 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188623 = VECTOR('',#188624,1.); +#188624 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188625 = PCURVE('',#188208,#188626); +#188626 = DEFINITIONAL_REPRESENTATION('',(#188627),#188631); +#188627 = LINE('',#188628,#188629); +#188628 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188629 = VECTOR('',#188630,1.); +#188630 = DIRECTION('',(0.E+000,1.)); +#188631 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188632 = PCURVE('',#188309,#188633); +#188633 = DEFINITIONAL_REPRESENTATION('',(#188634),#188638); +#188634 = LINE('',#188635,#188636); +#188635 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188636 = VECTOR('',#188637,1.); +#188637 = DIRECTION('',(0.E+000,1.)); +#188638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188639 = ADVANCED_FACE('',(#188640),#188654,.T.); +#188640 = FACE_BOUND('',#188641,.T.); +#188641 = EDGE_LOOP('',(#188642,#188694,#188737,#188782)); +#188642 = ORIENTED_EDGE('',*,*,#188643,.T.); +#188643 = EDGE_CURVE('',#188644,#188646,#188648,.T.); +#188644 = VERTEX_POINT('',#188645); +#188645 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); +#188646 = VERTEX_POINT('',#188647); +#188647 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, 0.137059047745)); -#186256 = SURFACE_CURVE('',#186257,(#186261,#186273),.PCURVE_S1.); -#186257 = LINE('',#186258,#186259); -#186258 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, +#188648 = SURFACE_CURVE('',#188649,(#188653,#188665),.PCURVE_S1.); +#188649 = LINE('',#188650,#188651); +#188650 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, 0.329352184392)); -#186259 = VECTOR('',#186260,1.); -#186260 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) - ); -#186261 = PCURVE('',#186262,#186267); -#186262 = PLANE('',#186263); -#186263 = AXIS2_PLACEMENT_3D('',#186264,#186265,#186266); -#186264 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#186265 = DIRECTION('',(0.965925826289,1.61116750665E-016, +#188651 = VECTOR('',#188652,1.); +#188652 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) + ); +#188653 = PCURVE('',#188654,#188659); +#188654 = PLANE('',#188655); +#188655 = AXIS2_PLACEMENT_3D('',#188656,#188657,#188658); +#188656 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#188657 = DIRECTION('',(0.965925826289,1.61116750665E-016, -0.258819045103)); -#186266 = DIRECTION('',(-0.258819045103,9.069926331849E-033, +#188658 = DIRECTION('',(-0.258819045103,9.069926331849E-033, -0.965925826289)); -#186267 = DEFINITIONAL_REPRESENTATION('',(#186268),#186272); -#186268 = LINE('',#186269,#186270); -#186269 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); -#186270 = VECTOR('',#186271,1.); -#186271 = DIRECTION('',(0.968100345886,0.250562807086)); -#186272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186273 = PCURVE('',#183150,#186274); -#186274 = DEFINITIONAL_REPRESENTATION('',(#186275),#186301); -#186275 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186276,#186277,#186278, - #186279,#186280,#186281,#186282,#186283,#186284,#186285,#186286, - #186287,#186288,#186289,#186290,#186291,#186292,#186293,#186294, - #186295,#186296,#186297,#186298,#186299,#186300),.UNSPECIFIED.,.F., +#188659 = DEFINITIONAL_REPRESENTATION('',(#188660),#188664); +#188660 = LINE('',#188661,#188662); +#188661 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); +#188662 = VECTOR('',#188663,1.); +#188663 = DIRECTION('',(0.968100345886,0.250562807086)); +#188664 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188665 = PCURVE('',#185542,#188666); +#188666 = DEFINITIONAL_REPRESENTATION('',(#188667),#188693); +#188667 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188668,#188669,#188670, + #188671,#188672,#188673,#188674,#188675,#188676,#188677,#188678, + #188679,#188680,#188681,#188682,#188683,#188684,#188685,#188686, + #188687,#188688,#188689,#188690,#188691,#188692),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.289427886241, -0.26692497193,-0.244422057619,-0.221919143309,-0.199416228998, -0.176913314688,-0.154410400377,-0.131907486066,-0.109404571756, @@ -231218,57 +234220,57 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 4.811582841839E-002,7.061874272899E-002,9.31216570396E-002, 0.11562457135,0.138127485661,0.160630399971,0.183133314282, 0.205636228593),.UNSPECIFIED.); -#186276 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); -#186277 = CARTESIAN_POINT('',(6.28318530718,0.687838662283)); -#186278 = CARTESIAN_POINT('',(6.28318530718,0.672836719409)); -#186279 = CARTESIAN_POINT('',(6.28318530718,0.650333805098)); -#186280 = CARTESIAN_POINT('',(6.28318530718,0.627830890788)); -#186281 = CARTESIAN_POINT('',(6.28318530718,0.605327976477)); -#186282 = CARTESIAN_POINT('',(6.28318530718,0.582825062167)); -#186283 = CARTESIAN_POINT('',(6.28318530718,0.560322147856)); -#186284 = CARTESIAN_POINT('',(6.28318530718,0.537819233545)); -#186285 = CARTESIAN_POINT('',(6.28318530718,0.515316319235)); -#186286 = CARTESIAN_POINT('',(6.28318530718,0.492813404924)); -#186287 = CARTESIAN_POINT('',(6.28318530718,0.470310490614)); -#186288 = CARTESIAN_POINT('',(6.28318530718,0.447807576303)); -#186289 = CARTESIAN_POINT('',(6.28318530718,0.425304661992)); -#186290 = CARTESIAN_POINT('',(6.28318530718,0.402801747682)); -#186291 = CARTESIAN_POINT('',(6.28318530718,0.380298833371)); -#186292 = CARTESIAN_POINT('',(6.28318530718,0.35779591906)); -#186293 = CARTESIAN_POINT('',(6.28318530718,0.33529300475)); -#186294 = CARTESIAN_POINT('',(6.28318530718,0.312790090439)); -#186295 = CARTESIAN_POINT('',(6.28318530718,0.290287176129)); -#186296 = CARTESIAN_POINT('',(6.28318530718,0.267784261818)); -#186297 = CARTESIAN_POINT('',(6.28318530718,0.245281347507)); -#186298 = CARTESIAN_POINT('',(6.28318530718,0.222778433197)); -#186299 = CARTESIAN_POINT('',(6.28318530718,0.207776490323)); -#186300 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); -#186301 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186302 = ORIENTED_EDGE('',*,*,#186303,.T.); -#186303 = EDGE_CURVE('',#186254,#183662,#186304,.T.); -#186304 = SURFACE_CURVE('',#186305,(#186309,#186316),.PCURVE_S1.); -#186305 = LINE('',#186306,#186307); -#186306 = CARTESIAN_POINT('',(1.3359553457,0.371136529841,0.137059047745 +#188668 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); +#188669 = CARTESIAN_POINT('',(6.28318530718,0.687838662283)); +#188670 = CARTESIAN_POINT('',(6.28318530718,0.672836719409)); +#188671 = CARTESIAN_POINT('',(6.28318530718,0.650333805098)); +#188672 = CARTESIAN_POINT('',(6.28318530718,0.627830890788)); +#188673 = CARTESIAN_POINT('',(6.28318530718,0.605327976477)); +#188674 = CARTESIAN_POINT('',(6.28318530718,0.582825062167)); +#188675 = CARTESIAN_POINT('',(6.28318530718,0.560322147856)); +#188676 = CARTESIAN_POINT('',(6.28318530718,0.537819233545)); +#188677 = CARTESIAN_POINT('',(6.28318530718,0.515316319235)); +#188678 = CARTESIAN_POINT('',(6.28318530718,0.492813404924)); +#188679 = CARTESIAN_POINT('',(6.28318530718,0.470310490614)); +#188680 = CARTESIAN_POINT('',(6.28318530718,0.447807576303)); +#188681 = CARTESIAN_POINT('',(6.28318530718,0.425304661992)); +#188682 = CARTESIAN_POINT('',(6.28318530718,0.402801747682)); +#188683 = CARTESIAN_POINT('',(6.28318530718,0.380298833371)); +#188684 = CARTESIAN_POINT('',(6.28318530718,0.35779591906)); +#188685 = CARTESIAN_POINT('',(6.28318530718,0.33529300475)); +#188686 = CARTESIAN_POINT('',(6.28318530718,0.312790090439)); +#188687 = CARTESIAN_POINT('',(6.28318530718,0.290287176129)); +#188688 = CARTESIAN_POINT('',(6.28318530718,0.267784261818)); +#188689 = CARTESIAN_POINT('',(6.28318530718,0.245281347507)); +#188690 = CARTESIAN_POINT('',(6.28318530718,0.222778433197)); +#188691 = CARTESIAN_POINT('',(6.28318530718,0.207776490323)); +#188692 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); +#188693 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188694 = ORIENTED_EDGE('',*,*,#188695,.T.); +#188695 = EDGE_CURVE('',#188646,#186054,#188696,.T.); +#188696 = SURFACE_CURVE('',#188697,(#188701,#188708),.PCURVE_S1.); +#188697 = LINE('',#188698,#188699); +#188698 = CARTESIAN_POINT('',(1.3359553457,0.371136529841,0.137059047745 )); -#186307 = VECTOR('',#186308,1.); -#186308 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); -#186309 = PCURVE('',#186262,#186310); -#186310 = DEFINITIONAL_REPRESENTATION('',(#186311),#186315); -#186311 = LINE('',#186312,#186313); -#186312 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); -#186313 = VECTOR('',#186314,1.); -#186314 = DIRECTION('',(4.317110322781E-017,1.)); -#186315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186316 = PCURVE('',#183771,#186317); -#186317 = DEFINITIONAL_REPRESENTATION('',(#186318),#186344); -#186318 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186319,#186320,#186321, - #186322,#186323,#186324,#186325,#186326,#186327,#186328,#186329, - #186330,#186331,#186332,#186333,#186334,#186335,#186336,#186337, - #186338,#186339,#186340,#186341,#186342,#186343),.UNSPECIFIED.,.F., +#188699 = VECTOR('',#188700,1.); +#188700 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); +#188701 = PCURVE('',#188654,#188702); +#188702 = DEFINITIONAL_REPRESENTATION('',(#188703),#188707); +#188703 = LINE('',#188704,#188705); +#188704 = CARTESIAN_POINT('',(0.479271740806,-0.278863470159)); +#188705 = VECTOR('',#188706,1.); +#188706 = DIRECTION('',(4.317110322781E-017,1.)); +#188707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188708 = PCURVE('',#186163,#188709); +#188709 = DEFINITIONAL_REPRESENTATION('',(#188710),#188736); +#188710 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188711,#188712,#188713, + #188714,#188715,#188716,#188717,#188718,#188719,#188720,#188721, + #188722,#188723,#188724,#188725,#188726,#188727,#188728,#188729, + #188730,#188731,#188732,#188733,#188734,#188735),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598, -0.717560595074,-0.682918188551,-0.648275782028,-0.613633375504, -0.578990968981,-0.544348562458,-0.509706155934,-0.475063749411, @@ -231277,59 +234279,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.163282090701,-0.128639684178,-9.399727765447E-002, -5.935487113115E-002,-2.471246460782E-002,9.929941915506E-003), .UNSPECIFIED.); -#186319 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); -#186320 = CARTESIAN_POINT('',(6.02138591938,1.019519002915)); -#186321 = CARTESIAN_POINT('',(6.02138591938,0.996424065233)); -#186322 = CARTESIAN_POINT('',(6.02138591938,0.96178165871)); -#186323 = CARTESIAN_POINT('',(6.02138591938,0.927139252187)); -#186324 = CARTESIAN_POINT('',(6.02138591938,0.892496845663)); -#186325 = CARTESIAN_POINT('',(6.02138591938,0.85785443914)); -#186326 = CARTESIAN_POINT('',(6.02138591938,0.823212032617)); -#186327 = CARTESIAN_POINT('',(6.02138591938,0.788569626093)); -#186328 = CARTESIAN_POINT('',(6.02138591938,0.75392721957)); -#186329 = CARTESIAN_POINT('',(6.02138591938,0.719284813047)); -#186330 = CARTESIAN_POINT('',(6.02138591938,0.684642406523)); -#186331 = CARTESIAN_POINT('',(6.02138591938,0.65)); -#186332 = CARTESIAN_POINT('',(6.02138591938,0.615357593477)); -#186333 = CARTESIAN_POINT('',(6.02138591938,0.580715186953)); -#186334 = CARTESIAN_POINT('',(6.02138591938,0.54607278043)); -#186335 = CARTESIAN_POINT('',(6.02138591938,0.511430373907)); -#186336 = CARTESIAN_POINT('',(6.02138591938,0.476787967383)); -#186337 = CARTESIAN_POINT('',(6.02138591938,0.44214556086)); -#186338 = CARTESIAN_POINT('',(6.02138591938,0.407503154337)); -#186339 = CARTESIAN_POINT('',(6.02138591938,0.372860747813)); -#186340 = CARTESIAN_POINT('',(6.02138591938,0.33821834129)); -#186341 = CARTESIAN_POINT('',(6.02138591938,0.303575934767)); -#186342 = CARTESIAN_POINT('',(6.02138591938,0.280480997085)); -#186343 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); -#186344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186345 = ORIENTED_EDGE('',*,*,#186346,.T.); -#186346 = EDGE_CURVE('',#183662,#186347,#186349,.T.); -#186347 = VERTEX_POINT('',#186348); -#186348 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); -#186349 = SURFACE_CURVE('',#186350,(#186354,#186361),.PCURVE_S1.); -#186350 = LINE('',#186351,#186352); -#186351 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, +#188711 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); +#188712 = CARTESIAN_POINT('',(6.02138591938,1.019519002915)); +#188713 = CARTESIAN_POINT('',(6.02138591938,0.996424065233)); +#188714 = CARTESIAN_POINT('',(6.02138591938,0.96178165871)); +#188715 = CARTESIAN_POINT('',(6.02138591938,0.927139252187)); +#188716 = CARTESIAN_POINT('',(6.02138591938,0.892496845663)); +#188717 = CARTESIAN_POINT('',(6.02138591938,0.85785443914)); +#188718 = CARTESIAN_POINT('',(6.02138591938,0.823212032617)); +#188719 = CARTESIAN_POINT('',(6.02138591938,0.788569626093)); +#188720 = CARTESIAN_POINT('',(6.02138591938,0.75392721957)); +#188721 = CARTESIAN_POINT('',(6.02138591938,0.719284813047)); +#188722 = CARTESIAN_POINT('',(6.02138591938,0.684642406523)); +#188723 = CARTESIAN_POINT('',(6.02138591938,0.65)); +#188724 = CARTESIAN_POINT('',(6.02138591938,0.615357593477)); +#188725 = CARTESIAN_POINT('',(6.02138591938,0.580715186953)); +#188726 = CARTESIAN_POINT('',(6.02138591938,0.54607278043)); +#188727 = CARTESIAN_POINT('',(6.02138591938,0.511430373907)); +#188728 = CARTESIAN_POINT('',(6.02138591938,0.476787967383)); +#188729 = CARTESIAN_POINT('',(6.02138591938,0.44214556086)); +#188730 = CARTESIAN_POINT('',(6.02138591938,0.407503154337)); +#188731 = CARTESIAN_POINT('',(6.02138591938,0.372860747813)); +#188732 = CARTESIAN_POINT('',(6.02138591938,0.33821834129)); +#188733 = CARTESIAN_POINT('',(6.02138591938,0.303575934767)); +#188734 = CARTESIAN_POINT('',(6.02138591938,0.280480997085)); +#188735 = CARTESIAN_POINT('',(6.02138591938,0.268933528243)); +#188736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188737 = ORIENTED_EDGE('',*,*,#188738,.T.); +#188738 = EDGE_CURVE('',#186054,#188739,#188741,.T.); +#188739 = VERTEX_POINT('',#188740); +#188740 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); +#188741 = SURFACE_CURVE('',#188742,(#188746,#188753),.PCURVE_S1.); +#188742 = LINE('',#188743,#188744); +#188743 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, 0.633948125296)); -#186352 = VECTOR('',#186353,1.); -#186353 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#186354 = PCURVE('',#186262,#186355); -#186355 = DEFINITIONAL_REPRESENTATION('',(#186356),#186360); -#186356 = LINE('',#186357,#186358); -#186357 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#186358 = VECTOR('',#186359,1.); -#186359 = DIRECTION('',(-0.968100345886,0.250562807086)); -#186360 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186361 = PCURVE('',#183700,#186362); -#186362 = DEFINITIONAL_REPRESENTATION('',(#186363),#186389); -#186363 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186364,#186365,#186366, - #186367,#186368,#186369,#186370,#186371,#186372,#186373,#186374, - #186375,#186376,#186377,#186378,#186379,#186380,#186381,#186382, - #186383,#186384,#186385,#186386,#186387,#186388),.UNSPECIFIED.,.F., +#188744 = VECTOR('',#188745,1.); +#188745 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#188746 = PCURVE('',#188654,#188747); +#188747 = DEFINITIONAL_REPRESENTATION('',(#188748),#188752); +#188748 = LINE('',#188749,#188750); +#188749 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#188750 = VECTOR('',#188751,1.); +#188751 = DIRECTION('',(-0.968100345886,0.250562807086)); +#188752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188753 = PCURVE('',#186092,#188754); +#188754 = DEFINITIONAL_REPRESENTATION('',(#188755),#188781); +#188755 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188756,#188757,#188758, + #188759,#188760,#188761,#188762,#188763,#188764,#188765,#188766, + #188767,#188768,#188769,#188770,#188771,#188772,#188773,#188774, + #188775,#188776,#188777,#188778,#188779,#188780),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.531367877804, -0.508864963493,-0.486362049183,-0.463859134872,-0.441356220562, -0.418853306251,-0.39635039194,-0.37384747763,-0.351344563319, @@ -231337,98 +234339,98 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.238829991766,-0.216327077456,-0.193824163145,-0.171321248834, -0.148818334524,-0.126315420213,-0.103812505903,-8.130959159195E-002 ,-5.880667728135E-002,-3.630376297074E-002),.UNSPECIFIED.); -#186364 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); -#186365 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.523866906367)); -#186366 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.508864963493)); -#186367 = CARTESIAN_POINT('',(0.E+000,-0.486362049183)); -#186368 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.463859134872)); -#186369 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.441356220562)); -#186370 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.418853306251)); -#186371 = CARTESIAN_POINT('',(0.E+000,-0.39635039194)); -#186372 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.37384747763)); -#186373 = CARTESIAN_POINT('',(8.881784197001E-016,-0.351344563319)); -#186374 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.328841649009)); -#186375 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.306338734698)); -#186376 = CARTESIAN_POINT('',(0.E+000,-0.283835820387)); -#186377 = CARTESIAN_POINT('',(0.E+000,-0.261332906077)); -#186378 = CARTESIAN_POINT('',(8.881784197001E-016,-0.238829991766)); -#186379 = CARTESIAN_POINT('',(0.E+000,-0.216327077456)); -#186380 = CARTESIAN_POINT('',(8.881784197001E-016,-0.193824163145)); -#186381 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.171321248834)); -#186382 = CARTESIAN_POINT('',(8.881784197001E-016,-0.148818334524)); -#186383 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.126315420213)); -#186384 = CARTESIAN_POINT('',(8.881784197001E-016,-0.103812505903)); -#186385 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.130959159195E-002) - ); -#186386 = CARTESIAN_POINT('',(-8.881784197001E-016,-5.880667728135E-002) - ); -#186387 = CARTESIAN_POINT('',(0.E+000,-4.380473440761E-002)); -#186388 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#186389 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186390 = ORIENTED_EDGE('',*,*,#186391,.F.); -#186391 = EDGE_CURVE('',#186252,#186347,#186392,.T.); -#186392 = SURFACE_CURVE('',#186393,(#186397,#186404),.PCURVE_S1.); -#186393 = LINE('',#186394,#186395); -#186394 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#186395 = VECTOR('',#186396,1.); -#186396 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#186397 = PCURVE('',#186262,#186398); -#186398 = DEFINITIONAL_REPRESENTATION('',(#186399),#186403); -#186399 = LINE('',#186400,#186401); -#186400 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186401 = VECTOR('',#186402,1.); -#186402 = DIRECTION('',(4.317110322781E-017,1.)); -#186403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186404 = PCURVE('',#186405,#186410); -#186405 = PLANE('',#186406); -#186406 = AXIS2_PLACEMENT_3D('',#186407,#186408,#186409); -#186407 = CARTESIAN_POINT('',(1.46,0.65,0.6)); -#186408 = DIRECTION('',(0.965925826289,1.61116750665E-016,0.258819045103 +#188756 = CARTESIAN_POINT('',(0.E+000,-0.531367877804)); +#188757 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.523866906367)); +#188758 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.508864963493)); +#188759 = CARTESIAN_POINT('',(0.E+000,-0.486362049183)); +#188760 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.463859134872)); +#188761 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.441356220562)); +#188762 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.418853306251)); +#188763 = CARTESIAN_POINT('',(0.E+000,-0.39635039194)); +#188764 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.37384747763)); +#188765 = CARTESIAN_POINT('',(8.881784197001E-016,-0.351344563319)); +#188766 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.328841649009)); +#188767 = CARTESIAN_POINT('',(-8.881784197001E-016,-0.306338734698)); +#188768 = CARTESIAN_POINT('',(0.E+000,-0.283835820387)); +#188769 = CARTESIAN_POINT('',(0.E+000,-0.261332906077)); +#188770 = CARTESIAN_POINT('',(8.881784197001E-016,-0.238829991766)); +#188771 = CARTESIAN_POINT('',(0.E+000,-0.216327077456)); +#188772 = CARTESIAN_POINT('',(8.881784197001E-016,-0.193824163145)); +#188773 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.171321248834)); +#188774 = CARTESIAN_POINT('',(8.881784197001E-016,-0.148818334524)); +#188775 = CARTESIAN_POINT('',(-1.7763568394E-015,-0.126315420213)); +#188776 = CARTESIAN_POINT('',(8.881784197001E-016,-0.103812505903)); +#188777 = CARTESIAN_POINT('',(-8.881784197001E-016,-8.130959159195E-002) + ); +#188778 = CARTESIAN_POINT('',(-8.881784197001E-016,-5.880667728135E-002) + ); +#188779 = CARTESIAN_POINT('',(0.E+000,-4.380473440761E-002)); +#188780 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#188781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188782 = ORIENTED_EDGE('',*,*,#188783,.F.); +#188783 = EDGE_CURVE('',#188644,#188739,#188784,.T.); +#188784 = SURFACE_CURVE('',#188785,(#188789,#188796),.PCURVE_S1.); +#188785 = LINE('',#188786,#188787); +#188786 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#188787 = VECTOR('',#188788,1.); +#188788 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#188789 = PCURVE('',#188654,#188790); +#188790 = DEFINITIONAL_REPRESENTATION('',(#188791),#188795); +#188791 = LINE('',#188792,#188793); +#188792 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188793 = VECTOR('',#188794,1.); +#188794 = DIRECTION('',(4.317110322781E-017,1.)); +#188795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188796 = PCURVE('',#188797,#188802); +#188797 = PLANE('',#188798); +#188798 = AXIS2_PLACEMENT_3D('',#188799,#188800,#188801); +#188799 = CARTESIAN_POINT('',(1.46,0.65,0.6)); +#188800 = DIRECTION('',(0.965925826289,1.61116750665E-016,0.258819045103 )); -#186409 = DIRECTION('',(0.258819045103,-9.069926331849E-033, +#188801 = DIRECTION('',(0.258819045103,-9.069926331849E-033, -0.965925826289)); -#186410 = DEFINITIONAL_REPRESENTATION('',(#186411),#186415); -#186411 = LINE('',#186412,#186413); -#186412 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186413 = VECTOR('',#186414,1.); -#186414 = DIRECTION('',(-4.317110322781E-017,1.)); -#186415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186416 = ADVANCED_FACE('',(#186417),#185917,.T.); -#186417 = FACE_BOUND('',#186418,.T.); -#186418 = EDGE_LOOP('',(#186419,#186464,#186484,#186527,#186528,#186554, - #186555,#186581,#186582,#186608)); -#186419 = ORIENTED_EDGE('',*,*,#186420,.T.); -#186420 = EDGE_CURVE('',#185857,#186421,#186423,.T.); -#186421 = VERTEX_POINT('',#186422); -#186422 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#188802 = DEFINITIONAL_REPRESENTATION('',(#188803),#188807); +#188803 = LINE('',#188804,#188805); +#188804 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188805 = VECTOR('',#188806,1.); +#188806 = DIRECTION('',(-4.317110322781E-017,1.)); +#188807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188808 = ADVANCED_FACE('',(#188809),#188309,.T.); +#188809 = FACE_BOUND('',#188810,.T.); +#188810 = EDGE_LOOP('',(#188811,#188856,#188876,#188919,#188920,#188946, + #188947,#188973,#188974,#189000)); +#188811 = ORIENTED_EDGE('',*,*,#188812,.T.); +#188812 = EDGE_CURVE('',#188249,#188813,#188815,.T.); +#188813 = VERTEX_POINT('',#188814); +#188814 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#186423 = SURFACE_CURVE('',#186424,(#186428,#186435),.PCURVE_S1.); -#186424 = LINE('',#186425,#186426); -#186425 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, +#188815 = SURFACE_CURVE('',#188816,(#188820,#188827),.PCURVE_S1.); +#188816 = LINE('',#188817,#188818); +#188817 = CARTESIAN_POINT('',(-1.324207498814,-0.659096372758, 0.633948125296)); -#186426 = VECTOR('',#186427,1.); -#186427 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); -#186428 = PCURVE('',#185917,#186429); -#186429 = DEFINITIONAL_REPRESENTATION('',(#186430),#186434); -#186430 = LINE('',#186431,#186432); -#186431 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); -#186432 = VECTOR('',#186433,1.); -#186433 = DIRECTION('',(0.968100345886,0.250562807086)); -#186434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186435 = PCURVE('',#183425,#186436); -#186436 = DEFINITIONAL_REPRESENTATION('',(#186437),#186463); -#186437 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186438,#186439,#186440, - #186441,#186442,#186443,#186444,#186445,#186446,#186447,#186448, - #186449,#186450,#186451,#186452,#186453,#186454,#186455,#186456, - #186457,#186458,#186459,#186460,#186461,#186462),.UNSPECIFIED.,.F., +#188818 = VECTOR('',#188819,1.); +#188819 = DIRECTION('',(0.250562807086,0.250562807086,-0.935113126531)); +#188820 = PCURVE('',#188309,#188821); +#188821 = DEFINITIONAL_REPRESENTATION('',(#188822),#188826); +#188822 = LINE('',#188823,#188824); +#188823 = CARTESIAN_POINT('',(-3.514568548895E-002,0.135792501186)); +#188824 = VECTOR('',#188825,1.); +#188825 = DIRECTION('',(0.968100345886,0.250562807086)); +#188826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188827 = PCURVE('',#185817,#188828); +#188828 = DEFINITIONAL_REPRESENTATION('',(#188829),#188855); +#188829 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188830,#188831,#188832, + #188833,#188834,#188835,#188836,#188837,#188838,#188839,#188840, + #188841,#188842,#188843,#188844,#188845,#188846,#188847,#188848, + #188849,#188850,#188851,#188852,#188853,#188854),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,5.880667728135E-002,8.130959159195E-002, 0.103812505903,0.126315420213,0.148818334524,0.171321248834, @@ -231437,84 +234439,84 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.37384747763,0.39635039194,0.418853306251,0.441356220562, 0.463859134872,0.486362049183,0.508864963493,0.531367877804), .QUASI_UNIFORM_KNOTS.); -#186438 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#186439 = CARTESIAN_POINT('',(4.64535148218,0.281926914804)); -#186440 = CARTESIAN_POINT('',(4.64535148218,0.26692497193)); -#186441 = CARTESIAN_POINT('',(4.64535148218,0.244422057619)); -#186442 = CARTESIAN_POINT('',(4.64535148218,0.221919143309)); -#186443 = CARTESIAN_POINT('',(4.64535148218,0.199416228998)); -#186444 = CARTESIAN_POINT('',(4.64535148218,0.176913314688)); -#186445 = CARTESIAN_POINT('',(4.64535148218,0.154410400377)); -#186446 = CARTESIAN_POINT('',(4.64535148218,0.131907486066)); -#186447 = CARTESIAN_POINT('',(4.64535148218,0.109404571756)); -#186448 = CARTESIAN_POINT('',(4.64535148218,8.690165744525E-002)); -#186449 = CARTESIAN_POINT('',(4.64535148218,6.439874313465E-002)); -#186450 = CARTESIAN_POINT('',(4.64535148218,4.189582882404E-002)); -#186451 = CARTESIAN_POINT('',(4.64535148218,1.939291451343E-002)); -#186452 = CARTESIAN_POINT('',(4.64535148218,-3.109999797174E-003)); -#186453 = CARTESIAN_POINT('',(4.64535148218,-2.561291410778E-002)); -#186454 = CARTESIAN_POINT('',(4.64535148218,-4.811582841839E-002)); -#186455 = CARTESIAN_POINT('',(4.64535148218,-7.061874272899E-002)); -#186456 = CARTESIAN_POINT('',(4.64535148218,-9.31216570396E-002)); -#186457 = CARTESIAN_POINT('',(4.64535148218,-0.11562457135)); -#186458 = CARTESIAN_POINT('',(4.64535148218,-0.138127485661)); -#186459 = CARTESIAN_POINT('',(4.64535148218,-0.160630399971)); -#186460 = CARTESIAN_POINT('',(4.64535148218,-0.183133314282)); -#186461 = CARTESIAN_POINT('',(4.64535148218,-0.198135257156)); -#186462 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); -#186463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186464 = ORIENTED_EDGE('',*,*,#186465,.T.); -#186465 = EDGE_CURVE('',#186421,#183112,#186466,.T.); -#186466 = SURFACE_CURVE('',#186467,(#186471,#186478),.PCURVE_S1.); -#186467 = LINE('',#186468,#186469); -#186468 = CARTESIAN_POINT('',(1.181136529841,-0.5259553457, +#188830 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#188831 = CARTESIAN_POINT('',(4.64535148218,0.281926914804)); +#188832 = CARTESIAN_POINT('',(4.64535148218,0.26692497193)); +#188833 = CARTESIAN_POINT('',(4.64535148218,0.244422057619)); +#188834 = CARTESIAN_POINT('',(4.64535148218,0.221919143309)); +#188835 = CARTESIAN_POINT('',(4.64535148218,0.199416228998)); +#188836 = CARTESIAN_POINT('',(4.64535148218,0.176913314688)); +#188837 = CARTESIAN_POINT('',(4.64535148218,0.154410400377)); +#188838 = CARTESIAN_POINT('',(4.64535148218,0.131907486066)); +#188839 = CARTESIAN_POINT('',(4.64535148218,0.109404571756)); +#188840 = CARTESIAN_POINT('',(4.64535148218,8.690165744525E-002)); +#188841 = CARTESIAN_POINT('',(4.64535148218,6.439874313465E-002)); +#188842 = CARTESIAN_POINT('',(4.64535148218,4.189582882404E-002)); +#188843 = CARTESIAN_POINT('',(4.64535148218,1.939291451343E-002)); +#188844 = CARTESIAN_POINT('',(4.64535148218,-3.109999797174E-003)); +#188845 = CARTESIAN_POINT('',(4.64535148218,-2.561291410778E-002)); +#188846 = CARTESIAN_POINT('',(4.64535148218,-4.811582841839E-002)); +#188847 = CARTESIAN_POINT('',(4.64535148218,-7.061874272899E-002)); +#188848 = CARTESIAN_POINT('',(4.64535148218,-9.31216570396E-002)); +#188849 = CARTESIAN_POINT('',(4.64535148218,-0.11562457135)); +#188850 = CARTESIAN_POINT('',(4.64535148218,-0.138127485661)); +#188851 = CARTESIAN_POINT('',(4.64535148218,-0.160630399971)); +#188852 = CARTESIAN_POINT('',(4.64535148218,-0.183133314282)); +#188853 = CARTESIAN_POINT('',(4.64535148218,-0.198135257156)); +#188854 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); +#188855 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188856 = ORIENTED_EDGE('',*,*,#188857,.T.); +#188857 = EDGE_CURVE('',#188813,#185504,#188858,.T.); +#188858 = SURFACE_CURVE('',#188859,(#188863,#188870),.PCURVE_S1.); +#188859 = LINE('',#188860,#188861); +#188860 = CARTESIAN_POINT('',(1.181136529841,-0.5259553457, 0.137059047745)); -#186469 = VECTOR('',#186470,1.); -#186470 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186471 = PCURVE('',#185917,#186472); -#186472 = DEFINITIONAL_REPRESENTATION('',(#186473),#186477); -#186473 = LINE('',#186474,#186475); -#186474 = CARTESIAN_POINT('',(0.479271740806,2.641136529841)); -#186475 = VECTOR('',#186476,1.); -#186476 = DIRECTION('',(0.E+000,1.)); -#186477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186478 = PCURVE('',#183221,#186479); -#186479 = DEFINITIONAL_REPRESENTATION('',(#186480),#186483); -#186480 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186481,#186482), +#188861 = VECTOR('',#188862,1.); +#188862 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188863 = PCURVE('',#188309,#188864); +#188864 = DEFINITIONAL_REPRESENTATION('',(#188865),#188869); +#188865 = LINE('',#188866,#188867); +#188866 = CARTESIAN_POINT('',(0.479271740806,2.641136529841)); +#188867 = VECTOR('',#188868,1.); +#188868 = DIRECTION('',(0.E+000,1.)); +#188869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188870 = PCURVE('',#185613,#188871); +#188871 = DEFINITIONAL_REPRESENTATION('',(#188872),#188875); +#188872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188873,#188874), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.372203001598,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#186481 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#186482 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); -#186483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#188873 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#188874 = CARTESIAN_POINT('',(4.450589592586,-2.651066471757)); +#188875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186484 = ORIENTED_EDGE('',*,*,#186485,.T.); -#186485 = EDGE_CURVE('',#183112,#185808,#186486,.T.); -#186486 = SURFACE_CURVE('',#186487,(#186491,#186498),.PCURVE_S1.); -#186487 = LINE('',#186488,#186489); -#186488 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, +#188876 = ORIENTED_EDGE('',*,*,#188877,.T.); +#188877 = EDGE_CURVE('',#185504,#188200,#188878,.T.); +#188878 = SURFACE_CURVE('',#188879,(#188883,#188890),.PCURVE_S1.); +#188879 = LINE('',#188880,#188881); +#188880 = CARTESIAN_POINT('',(1.140884875554,-0.475773749497, -5.022121888847E-002)); -#186489 = VECTOR('',#186490,1.); -#186490 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); -#186491 = PCURVE('',#185917,#186492); -#186492 = DEFINITIONAL_REPRESENTATION('',(#186493),#186497); -#186493 = LINE('',#186494,#186495); -#186494 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); -#186495 = VECTOR('',#186496,1.); -#186496 = DIRECTION('',(-0.968100345886,0.250562807086)); -#186497 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186498 = PCURVE('',#183150,#186499); -#186499 = DEFINITIONAL_REPRESENTATION('',(#186500),#186526); -#186500 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186501,#186502,#186503, - #186504,#186505,#186506,#186507,#186508,#186509,#186510,#186511, - #186512,#186513,#186514,#186515,#186516,#186517,#186518,#186519, - #186520,#186521,#186522,#186523,#186524,#186525),.UNSPECIFIED.,.F., +#188881 = VECTOR('',#188882,1.); +#188882 = DIRECTION('',(0.250562807086,-0.250562807086,0.935113126531)); +#188883 = PCURVE('',#188309,#188884); +#188884 = DEFINITIONAL_REPRESENTATION('',(#188885),#188889); +#188885 = LINE('',#188886,#188887); +#188886 = CARTESIAN_POINT('',(0.673158539912,2.600884875554)); +#188887 = VECTOR('',#188888,1.); +#188888 = DIRECTION('',(-0.968100345886,0.250562807086)); +#188889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188890 = PCURVE('',#185542,#188891); +#188891 = DEFINITIONAL_REPRESENTATION('',(#188892),#188918); +#188892 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188893,#188894,#188895, + #188896,#188897,#188898,#188899,#188900,#188901,#188902,#188903, + #188904,#188905,#188906,#188907,#188908,#188909,#188910,#188911, + #188912,#188913,#188914,#188915,#188916,#188917),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.200275518886, 0.222778433197,0.245281347507,0.267784261818,0.290287176129, 0.312790090439,0.33529300475,0.35779591906,0.380298833371, @@ -231522,194 +234524,194 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.492813404924,0.515316319235,0.537819233545,0.560322147856, 0.582825062167,0.605327976477,0.627830890788,0.650333805098, 0.672836719409,0.69533963372),.QUASI_UNIFORM_KNOTS.); -#186501 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); -#186502 = CARTESIAN_POINT('',(4.77942647859,0.207776490323)); -#186503 = CARTESIAN_POINT('',(4.77942647859,0.222778433197)); -#186504 = CARTESIAN_POINT('',(4.77942647859,0.245281347507)); -#186505 = CARTESIAN_POINT('',(4.77942647859,0.267784261818)); -#186506 = CARTESIAN_POINT('',(4.77942647859,0.290287176129)); -#186507 = CARTESIAN_POINT('',(4.77942647859,0.312790090439)); -#186508 = CARTESIAN_POINT('',(4.77942647859,0.33529300475)); -#186509 = CARTESIAN_POINT('',(4.77942647859,0.35779591906)); -#186510 = CARTESIAN_POINT('',(4.77942647859,0.380298833371)); -#186511 = CARTESIAN_POINT('',(4.77942647859,0.402801747682)); -#186512 = CARTESIAN_POINT('',(4.77942647859,0.425304661992)); -#186513 = CARTESIAN_POINT('',(4.77942647859,0.447807576303)); -#186514 = CARTESIAN_POINT('',(4.77942647859,0.470310490614)); -#186515 = CARTESIAN_POINT('',(4.77942647859,0.492813404924)); -#186516 = CARTESIAN_POINT('',(4.77942647859,0.515316319235)); -#186517 = CARTESIAN_POINT('',(4.77942647859,0.537819233545)); -#186518 = CARTESIAN_POINT('',(4.77942647859,0.560322147856)); -#186519 = CARTESIAN_POINT('',(4.77942647859,0.582825062167)); -#186520 = CARTESIAN_POINT('',(4.77942647859,0.605327976477)); -#186521 = CARTESIAN_POINT('',(4.77942647859,0.627830890788)); -#186522 = CARTESIAN_POINT('',(4.77942647859,0.650333805098)); -#186523 = CARTESIAN_POINT('',(4.77942647859,0.672836719409)); -#186524 = CARTESIAN_POINT('',(4.77942647859,0.687838662283)); -#186525 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); -#186526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186527 = ORIENTED_EDGE('',*,*,#186227,.F.); -#186528 = ORIENTED_EDGE('',*,*,#186529,.F.); -#186529 = EDGE_CURVE('',#186121,#186200,#186530,.T.); -#186530 = SURFACE_CURVE('',#186531,(#186535,#186542),.PCURVE_S1.); -#186531 = LINE('',#186532,#186533); -#186532 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#186533 = VECTOR('',#186534,1.); -#186534 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186535 = PCURVE('',#185917,#186536); -#186536 = DEFINITIONAL_REPRESENTATION('',(#186537),#186541); -#186537 = LINE('',#186538,#186539); -#186538 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186539 = VECTOR('',#186540,1.); -#186540 = DIRECTION('',(0.E+000,1.)); -#186541 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186542 = PCURVE('',#186543,#186548); -#186543 = PLANE('',#186544); -#186544 = AXIS2_PLACEMENT_3D('',#186545,#186546,#186547); -#186545 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#186546 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186547 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186548 = DEFINITIONAL_REPRESENTATION('',(#186549),#186553); -#186549 = LINE('',#186550,#186551); -#186550 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); -#186551 = VECTOR('',#186552,1.); -#186552 = DIRECTION('',(-1.,0.E+000)); -#186553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186554 = ORIENTED_EDGE('',*,*,#186120,.F.); -#186555 = ORIENTED_EDGE('',*,*,#186556,.F.); -#186556 = EDGE_CURVE('',#186014,#186093,#186557,.T.); -#186557 = SURFACE_CURVE('',#186558,(#186562,#186569),.PCURVE_S1.); -#186558 = LINE('',#186559,#186560); -#186559 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); -#186560 = VECTOR('',#186561,1.); -#186561 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186562 = PCURVE('',#185917,#186563); -#186563 = DEFINITIONAL_REPRESENTATION('',(#186564),#186568); -#186564 = LINE('',#186565,#186566); -#186565 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186566 = VECTOR('',#186567,1.); -#186567 = DIRECTION('',(0.E+000,1.)); -#186568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186569 = PCURVE('',#186570,#186575); -#186570 = PLANE('',#186571); -#186571 = AXIS2_PLACEMENT_3D('',#186572,#186573,#186574); -#186572 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); -#186573 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186574 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186575 = DEFINITIONAL_REPRESENTATION('',(#186576),#186580); -#186576 = LINE('',#186577,#186578); -#186577 = CARTESIAN_POINT('',(1.26,5.208001194228E-003)); -#186578 = VECTOR('',#186579,1.); -#186579 = DIRECTION('',(-1.,0.E+000)); -#186580 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186581 = ORIENTED_EDGE('',*,*,#186013,.F.); -#186582 = ORIENTED_EDGE('',*,*,#186583,.F.); -#186583 = EDGE_CURVE('',#185902,#185986,#186584,.T.); -#186584 = SURFACE_CURVE('',#186585,(#186589,#186596),.PCURVE_S1.); -#186585 = LINE('',#186586,#186587); -#186586 = CARTESIAN_POINT('',(-3.36,-0.65,0.6)); -#186587 = VECTOR('',#186588,1.); -#186588 = DIRECTION('',(1.,0.E+000,0.E+000)); -#186589 = PCURVE('',#185917,#186590); -#186590 = DEFINITIONAL_REPRESENTATION('',(#186591),#186595); -#186591 = LINE('',#186592,#186593); -#186592 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#186593 = VECTOR('',#186594,1.); -#186594 = DIRECTION('',(0.E+000,1.)); -#186595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186596 = PCURVE('',#186597,#186602); -#186597 = PLANE('',#186598); -#186598 = AXIS2_PLACEMENT_3D('',#186599,#186600,#186601); -#186599 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#186600 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186601 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186602 = DEFINITIONAL_REPRESENTATION('',(#186603),#186607); -#186603 = LINE('',#186604,#186605); -#186604 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); -#186605 = VECTOR('',#186606,1.); -#186606 = DIRECTION('',(-1.,0.E+000)); -#186607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186608 = ORIENTED_EDGE('',*,*,#185901,.F.); -#186609 = ADVANCED_FACE('',(#186610),#186624,.T.); -#186610 = FACE_BOUND('',#186611,.T.); -#186611 = EDGE_LOOP('',(#186612,#186641,#186684,#186729)); -#186612 = ORIENTED_EDGE('',*,*,#186613,.T.); -#186613 = EDGE_CURVE('',#186614,#186616,#186618,.T.); -#186614 = VERTEX_POINT('',#186615); -#186615 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); -#186616 = VERTEX_POINT('',#186617); -#186617 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, +#188893 = CARTESIAN_POINT('',(4.77942647859,0.200275518886)); +#188894 = CARTESIAN_POINT('',(4.77942647859,0.207776490323)); +#188895 = CARTESIAN_POINT('',(4.77942647859,0.222778433197)); +#188896 = CARTESIAN_POINT('',(4.77942647859,0.245281347507)); +#188897 = CARTESIAN_POINT('',(4.77942647859,0.267784261818)); +#188898 = CARTESIAN_POINT('',(4.77942647859,0.290287176129)); +#188899 = CARTESIAN_POINT('',(4.77942647859,0.312790090439)); +#188900 = CARTESIAN_POINT('',(4.77942647859,0.33529300475)); +#188901 = CARTESIAN_POINT('',(4.77942647859,0.35779591906)); +#188902 = CARTESIAN_POINT('',(4.77942647859,0.380298833371)); +#188903 = CARTESIAN_POINT('',(4.77942647859,0.402801747682)); +#188904 = CARTESIAN_POINT('',(4.77942647859,0.425304661992)); +#188905 = CARTESIAN_POINT('',(4.77942647859,0.447807576303)); +#188906 = CARTESIAN_POINT('',(4.77942647859,0.470310490614)); +#188907 = CARTESIAN_POINT('',(4.77942647859,0.492813404924)); +#188908 = CARTESIAN_POINT('',(4.77942647859,0.515316319235)); +#188909 = CARTESIAN_POINT('',(4.77942647859,0.537819233545)); +#188910 = CARTESIAN_POINT('',(4.77942647859,0.560322147856)); +#188911 = CARTESIAN_POINT('',(4.77942647859,0.582825062167)); +#188912 = CARTESIAN_POINT('',(4.77942647859,0.605327976477)); +#188913 = CARTESIAN_POINT('',(4.77942647859,0.627830890788)); +#188914 = CARTESIAN_POINT('',(4.77942647859,0.650333805098)); +#188915 = CARTESIAN_POINT('',(4.77942647859,0.672836719409)); +#188916 = CARTESIAN_POINT('',(4.77942647859,0.687838662283)); +#188917 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); +#188918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188919 = ORIENTED_EDGE('',*,*,#188619,.F.); +#188920 = ORIENTED_EDGE('',*,*,#188921,.F.); +#188921 = EDGE_CURVE('',#188513,#188592,#188922,.T.); +#188922 = SURFACE_CURVE('',#188923,(#188927,#188934),.PCURVE_S1.); +#188923 = LINE('',#188924,#188925); +#188924 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188925 = VECTOR('',#188926,1.); +#188926 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188927 = PCURVE('',#188309,#188928); +#188928 = DEFINITIONAL_REPRESENTATION('',(#188929),#188933); +#188929 = LINE('',#188930,#188931); +#188930 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188931 = VECTOR('',#188932,1.); +#188932 = DIRECTION('',(0.E+000,1.)); +#188933 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188934 = PCURVE('',#188935,#188940); +#188935 = PLANE('',#188936); +#188936 = AXIS2_PLACEMENT_3D('',#188937,#188938,#188939); +#188937 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#188938 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188939 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188940 = DEFINITIONAL_REPRESENTATION('',(#188941),#188945); +#188941 = LINE('',#188942,#188943); +#188942 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); +#188943 = VECTOR('',#188944,1.); +#188944 = DIRECTION('',(-1.,0.E+000)); +#188945 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188946 = ORIENTED_EDGE('',*,*,#188512,.F.); +#188947 = ORIENTED_EDGE('',*,*,#188948,.F.); +#188948 = EDGE_CURVE('',#188406,#188485,#188949,.T.); +#188949 = SURFACE_CURVE('',#188950,(#188954,#188961),.PCURVE_S1.); +#188950 = LINE('',#188951,#188952); +#188951 = CARTESIAN_POINT('',(-1.46,-0.65,0.6)); +#188952 = VECTOR('',#188953,1.); +#188953 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188954 = PCURVE('',#188309,#188955); +#188955 = DEFINITIONAL_REPRESENTATION('',(#188956),#188960); +#188956 = LINE('',#188957,#188958); +#188957 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#188958 = VECTOR('',#188959,1.); +#188959 = DIRECTION('',(0.E+000,1.)); +#188960 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188961 = PCURVE('',#188962,#188967); +#188962 = PLANE('',#188963); +#188963 = AXIS2_PLACEMENT_3D('',#188964,#188965,#188966); +#188964 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); +#188965 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188966 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188967 = DEFINITIONAL_REPRESENTATION('',(#188968),#188972); +#188968 = LINE('',#188969,#188970); +#188969 = CARTESIAN_POINT('',(1.26,5.208001194228E-003)); +#188970 = VECTOR('',#188971,1.); +#188971 = DIRECTION('',(-1.,0.E+000)); +#188972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188973 = ORIENTED_EDGE('',*,*,#188405,.F.); +#188974 = ORIENTED_EDGE('',*,*,#188975,.F.); +#188975 = EDGE_CURVE('',#188294,#188378,#188976,.T.); +#188976 = SURFACE_CURVE('',#188977,(#188981,#188988),.PCURVE_S1.); +#188977 = LINE('',#188978,#188979); +#188978 = CARTESIAN_POINT('',(-3.36,-0.65,0.6)); +#188979 = VECTOR('',#188980,1.); +#188980 = DIRECTION('',(1.,0.E+000,0.E+000)); +#188981 = PCURVE('',#188309,#188982); +#188982 = DEFINITIONAL_REPRESENTATION('',(#188983),#188987); +#188983 = LINE('',#188984,#188985); +#188984 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#188985 = VECTOR('',#188986,1.); +#188986 = DIRECTION('',(0.E+000,1.)); +#188987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#188988 = PCURVE('',#188989,#188994); +#188989 = PLANE('',#188990); +#188990 = AXIS2_PLACEMENT_3D('',#188991,#188992,#188993); +#188991 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#188992 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#188993 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#188994 = DEFINITIONAL_REPRESENTATION('',(#188995),#188999); +#188995 = LINE('',#188996,#188997); +#188996 = CARTESIAN_POINT('',(2.215,5.208001194228E-003)); +#188997 = VECTOR('',#188998,1.); +#188998 = DIRECTION('',(-1.,0.E+000)); +#188999 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189000 = ORIENTED_EDGE('',*,*,#188293,.F.); +#189001 = ADVANCED_FACE('',(#189002),#189016,.T.); +#189002 = FACE_BOUND('',#189003,.T.); +#189003 = EDGE_LOOP('',(#189004,#189033,#189076,#189121)); +#189004 = ORIENTED_EDGE('',*,*,#189005,.T.); +#189005 = EDGE_CURVE('',#189006,#189008,#189010,.T.); +#189006 = VERTEX_POINT('',#189007); +#189007 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); +#189008 = VERTEX_POINT('',#189009); +#189009 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, 0.137059047745)); -#186618 = SURFACE_CURVE('',#186619,(#186623,#186635),.PCURVE_S1.); -#186619 = LINE('',#186620,#186621); -#186620 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, +#189010 = SURFACE_CURVE('',#189011,(#189015,#189027),.PCURVE_S1.); +#189011 = LINE('',#189012,#189013); +#189012 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, 0.633948125296)); -#186621 = VECTOR('',#186622,1.); -#186622 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) - ); -#186623 = PCURVE('',#186624,#186629); -#186624 = PLANE('',#186625); -#186625 = AXIS2_PLACEMENT_3D('',#186626,#186627,#186628); -#186626 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#186627 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, +#189013 = VECTOR('',#189014,1.); +#189014 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) + ); +#189015 = PCURVE('',#189016,#189021); +#189016 = PLANE('',#189017); +#189017 = AXIS2_PLACEMENT_3D('',#189018,#189019,#189020); +#189018 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#189019 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, -0.258819045103)); -#186628 = DIRECTION('',(-0.258819045103,9.069926331849E-033, +#189020 = DIRECTION('',(-0.258819045103,9.069926331849E-033, 0.965925826289)); -#186629 = DEFINITIONAL_REPRESENTATION('',(#186630),#186634); -#186630 = LINE('',#186631,#186632); -#186631 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#186632 = VECTOR('',#186633,1.); -#186633 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#186634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189021 = DEFINITIONAL_REPRESENTATION('',(#189022),#189026); +#189022 = LINE('',#189023,#189024); +#189023 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#189024 = VECTOR('',#189025,1.); +#189025 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#189026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186635 = PCURVE('',#183975,#186636); -#186636 = DEFINITIONAL_REPRESENTATION('',(#186637),#186640); -#186637 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186638,#186639), +#189027 = PCURVE('',#186367,#189028); +#189028 = DEFINITIONAL_REPRESENTATION('',(#189029),#189032); +#189029 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189030,#189031), .UNSPECIFIED.,.F.,.F.,(2,2),(3.630376297074E-002,0.531367877804), .PIECEWISE_BEZIER_KNOTS.); -#186638 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#186639 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#186640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189030 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#189031 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#189032 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186641 = ORIENTED_EDGE('',*,*,#186642,.T.); -#186642 = EDGE_CURVE('',#186616,#183387,#186643,.T.); -#186643 = SURFACE_CURVE('',#186644,(#186648,#186655),.PCURVE_S1.); -#186644 = LINE('',#186645,#186646); -#186645 = CARTESIAN_POINT('',(-1.3359553457,-0.371136529841, +#189033 = ORIENTED_EDGE('',*,*,#189034,.T.); +#189034 = EDGE_CURVE('',#189008,#185779,#189035,.T.); +#189035 = SURFACE_CURVE('',#189036,(#189040,#189047),.PCURVE_S1.); +#189036 = LINE('',#189037,#189038); +#189037 = CARTESIAN_POINT('',(-1.3359553457,-0.371136529841, 0.137059047745)); -#186646 = VECTOR('',#186647,1.); -#186647 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); -#186648 = PCURVE('',#186624,#186649); -#186649 = DEFINITIONAL_REPRESENTATION('',(#186650),#186654); -#186650 = LINE('',#186651,#186652); -#186651 = CARTESIAN_POINT('',(-0.479271740806,-1.021136529841)); -#186652 = VECTOR('',#186653,1.); -#186653 = DIRECTION('',(-4.317110322781E-017,-1.)); -#186654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186655 = PCURVE('',#183496,#186656); -#186656 = DEFINITIONAL_REPRESENTATION('',(#186657),#186683); -#186657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186658,#186659,#186660, - #186661,#186662,#186663,#186664,#186665,#186666,#186667,#186668, - #186669,#186670,#186671,#186672,#186673,#186674,#186675,#186676, - #186677,#186678,#186679,#186680,#186681,#186682),.UNSPECIFIED.,.F., +#189038 = VECTOR('',#189039,1.); +#189039 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); +#189040 = PCURVE('',#189016,#189041); +#189041 = DEFINITIONAL_REPRESENTATION('',(#189042),#189046); +#189042 = LINE('',#189043,#189044); +#189043 = CARTESIAN_POINT('',(-0.479271740806,-1.021136529841)); +#189044 = VECTOR('',#189045,1.); +#189045 = DIRECTION('',(-4.317110322781E-017,-1.)); +#189046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189047 = PCURVE('',#185888,#189048); +#189048 = DEFINITIONAL_REPRESENTATION('',(#189049),#189075); +#189049 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189050,#189051,#189052, + #189053,#189054,#189055,#189056,#189057,#189058,#189059,#189060, + #189061,#189062,#189063,#189064,#189065,#189066,#189067,#189068, + #189069,#189070,#189071,#189072,#189073,#189074),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598, -0.717560595074,-0.682918188551,-0.648275782028,-0.613633375504, -0.578990968981,-0.544348562458,-0.509706155934,-0.475063749411, @@ -231718,60 +234720,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.163282090701,-0.128639684178,-9.399727765447E-002, -5.935487113115E-002,-2.471246460782E-002,9.929941915506E-003), .UNSPECIFIED.); -#186658 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#186659 = CARTESIAN_POINT('',(6.02138591938,-0.280480997085)); -#186660 = CARTESIAN_POINT('',(6.02138591938,-0.303575934767)); -#186661 = CARTESIAN_POINT('',(6.02138591938,-0.33821834129)); -#186662 = CARTESIAN_POINT('',(6.02138591938,-0.372860747813)); -#186663 = CARTESIAN_POINT('',(6.02138591938,-0.407503154337)); -#186664 = CARTESIAN_POINT('',(6.02138591938,-0.44214556086)); -#186665 = CARTESIAN_POINT('',(6.02138591938,-0.476787967383)); -#186666 = CARTESIAN_POINT('',(6.02138591938,-0.511430373907)); -#186667 = CARTESIAN_POINT('',(6.02138591938,-0.54607278043)); -#186668 = CARTESIAN_POINT('',(6.02138591938,-0.580715186953)); -#186669 = CARTESIAN_POINT('',(6.02138591938,-0.615357593477)); -#186670 = CARTESIAN_POINT('',(6.02138591938,-0.65)); -#186671 = CARTESIAN_POINT('',(6.02138591938,-0.684642406523)); -#186672 = CARTESIAN_POINT('',(6.02138591938,-0.719284813047)); -#186673 = CARTESIAN_POINT('',(6.02138591938,-0.75392721957)); -#186674 = CARTESIAN_POINT('',(6.02138591938,-0.788569626093)); -#186675 = CARTESIAN_POINT('',(6.02138591938,-0.823212032617)); -#186676 = CARTESIAN_POINT('',(6.02138591938,-0.85785443914)); -#186677 = CARTESIAN_POINT('',(6.02138591938,-0.892496845663)); -#186678 = CARTESIAN_POINT('',(6.02138591938,-0.927139252187)); -#186679 = CARTESIAN_POINT('',(6.02138591938,-0.96178165871)); -#186680 = CARTESIAN_POINT('',(6.02138591938,-0.996424065233)); -#186681 = CARTESIAN_POINT('',(6.02138591938,-1.019519002915)); -#186682 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); -#186683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186684 = ORIENTED_EDGE('',*,*,#186685,.T.); -#186685 = EDGE_CURVE('',#183387,#186686,#186688,.T.); -#186686 = VERTEX_POINT('',#186687); -#186687 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); -#186688 = SURFACE_CURVE('',#186689,(#186693,#186700),.PCURVE_S1.); -#186689 = LINE('',#186690,#186691); -#186690 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, +#189050 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#189051 = CARTESIAN_POINT('',(6.02138591938,-0.280480997085)); +#189052 = CARTESIAN_POINT('',(6.02138591938,-0.303575934767)); +#189053 = CARTESIAN_POINT('',(6.02138591938,-0.33821834129)); +#189054 = CARTESIAN_POINT('',(6.02138591938,-0.372860747813)); +#189055 = CARTESIAN_POINT('',(6.02138591938,-0.407503154337)); +#189056 = CARTESIAN_POINT('',(6.02138591938,-0.44214556086)); +#189057 = CARTESIAN_POINT('',(6.02138591938,-0.476787967383)); +#189058 = CARTESIAN_POINT('',(6.02138591938,-0.511430373907)); +#189059 = CARTESIAN_POINT('',(6.02138591938,-0.54607278043)); +#189060 = CARTESIAN_POINT('',(6.02138591938,-0.580715186953)); +#189061 = CARTESIAN_POINT('',(6.02138591938,-0.615357593477)); +#189062 = CARTESIAN_POINT('',(6.02138591938,-0.65)); +#189063 = CARTESIAN_POINT('',(6.02138591938,-0.684642406523)); +#189064 = CARTESIAN_POINT('',(6.02138591938,-0.719284813047)); +#189065 = CARTESIAN_POINT('',(6.02138591938,-0.75392721957)); +#189066 = CARTESIAN_POINT('',(6.02138591938,-0.788569626093)); +#189067 = CARTESIAN_POINT('',(6.02138591938,-0.823212032617)); +#189068 = CARTESIAN_POINT('',(6.02138591938,-0.85785443914)); +#189069 = CARTESIAN_POINT('',(6.02138591938,-0.892496845663)); +#189070 = CARTESIAN_POINT('',(6.02138591938,-0.927139252187)); +#189071 = CARTESIAN_POINT('',(6.02138591938,-0.96178165871)); +#189072 = CARTESIAN_POINT('',(6.02138591938,-0.996424065233)); +#189073 = CARTESIAN_POINT('',(6.02138591938,-1.019519002915)); +#189074 = CARTESIAN_POINT('',(6.02138591938,-1.031066471757)); +#189075 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189076 = ORIENTED_EDGE('',*,*,#189077,.T.); +#189077 = EDGE_CURVE('',#185779,#189078,#189080,.T.); +#189078 = VERTEX_POINT('',#189079); +#189079 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); +#189080 = SURFACE_CURVE('',#189081,(#189085,#189092),.PCURVE_S1.); +#189081 = LINE('',#189082,#189083); +#189082 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, 0.329352184392)); -#186691 = VECTOR('',#186692,1.); -#186692 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) - ); -#186693 = PCURVE('',#186624,#186694); -#186694 = DEFINITIONAL_REPRESENTATION('',(#186695),#186699); -#186695 = LINE('',#186696,#186697); -#186696 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); -#186697 = VECTOR('',#186698,1.); -#186698 = DIRECTION('',(0.968100345886,-0.250562807086)); -#186699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186700 = PCURVE('',#183425,#186701); -#186701 = DEFINITIONAL_REPRESENTATION('',(#186702),#186728); -#186702 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186703,#186704,#186705, - #186706,#186707,#186708,#186709,#186710,#186711,#186712,#186713, - #186714,#186715,#186716,#186717,#186718,#186719,#186720,#186721, - #186722,#186723,#186724,#186725,#186726,#186727),.UNSPECIFIED.,.F., +#189083 = VECTOR('',#189084,1.); +#189084 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) + ); +#189085 = PCURVE('',#189016,#189086); +#189086 = DEFINITIONAL_REPRESENTATION('',(#189087),#189091); +#189087 = LINE('',#189088,#189089); +#189088 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); +#189089 = VECTOR('',#189090,1.); +#189090 = DIRECTION('',(0.968100345886,-0.250562807086)); +#189091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189092 = PCURVE('',#185817,#189093); +#189093 = DEFINITIONAL_REPRESENTATION('',(#189094),#189120); +#189094 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189095,#189096,#189097, + #189098,#189099,#189100,#189101,#189102,#189103,#189104,#189105, + #189106,#189107,#189108,#189109,#189110,#189111,#189112,#189113, + #189114,#189115,#189116,#189117,#189118,#189119),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.205636228593, -0.183133314282,-0.160630399971,-0.138127485661,-0.11562457135, -9.31216570396E-002,-7.061874272899E-002,-4.811582841839E-002, @@ -231780,97 +234782,97 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.109404571756,0.131907486066,0.154410400377,0.176913314688, 0.199416228998,0.221919143309,0.244422057619,0.26692497193, 0.289427886241),.UNSPECIFIED.); -#186703 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); -#186704 = CARTESIAN_POINT('',(3.14159265359,-0.198135257156)); -#186705 = CARTESIAN_POINT('',(3.14159265359,-0.183133314282)); -#186706 = CARTESIAN_POINT('',(3.14159265359,-0.160630399971)); -#186707 = CARTESIAN_POINT('',(3.14159265359,-0.138127485661)); -#186708 = CARTESIAN_POINT('',(3.14159265359,-0.11562457135)); -#186709 = CARTESIAN_POINT('',(3.14159265359,-9.31216570396E-002)); -#186710 = CARTESIAN_POINT('',(3.14159265359,-7.061874272899E-002)); -#186711 = CARTESIAN_POINT('',(3.14159265359,-4.811582841839E-002)); -#186712 = CARTESIAN_POINT('',(3.14159265359,-2.561291410778E-002)); -#186713 = CARTESIAN_POINT('',(3.14159265359,-3.109999797174E-003)); -#186714 = CARTESIAN_POINT('',(3.14159265359,1.939291451343E-002)); -#186715 = CARTESIAN_POINT('',(3.14159265359,4.189582882404E-002)); -#186716 = CARTESIAN_POINT('',(3.14159265359,6.439874313465E-002)); -#186717 = CARTESIAN_POINT('',(3.14159265359,8.690165744525E-002)); -#186718 = CARTESIAN_POINT('',(3.14159265359,0.109404571756)); -#186719 = CARTESIAN_POINT('',(3.14159265359,0.131907486066)); -#186720 = CARTESIAN_POINT('',(3.14159265359,0.154410400377)); -#186721 = CARTESIAN_POINT('',(3.14159265359,0.176913314688)); -#186722 = CARTESIAN_POINT('',(3.14159265359,0.199416228998)); -#186723 = CARTESIAN_POINT('',(3.14159265359,0.221919143309)); -#186724 = CARTESIAN_POINT('',(3.14159265359,0.244422057619)); -#186725 = CARTESIAN_POINT('',(3.14159265359,0.26692497193)); -#186726 = CARTESIAN_POINT('',(3.14159265359,0.281926914804)); -#186727 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#186728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186729 = ORIENTED_EDGE('',*,*,#186730,.F.); -#186730 = EDGE_CURVE('',#186614,#186686,#186731,.T.); -#186731 = SURFACE_CURVE('',#186732,(#186736,#186743),.PCURVE_S1.); -#186732 = LINE('',#186733,#186734); -#186733 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#186734 = VECTOR('',#186735,1.); -#186735 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#186736 = PCURVE('',#186624,#186737); -#186737 = DEFINITIONAL_REPRESENTATION('',(#186738),#186742); -#186738 = LINE('',#186739,#186740); -#186739 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186740 = VECTOR('',#186741,1.); -#186741 = DIRECTION('',(-4.317110322781E-017,-1.)); -#186742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186743 = PCURVE('',#186744,#186749); -#186744 = PLANE('',#186745); -#186745 = AXIS2_PLACEMENT_3D('',#186746,#186747,#186748); -#186746 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#186747 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, +#189095 = CARTESIAN_POINT('',(3.14159265359,-0.205636228593)); +#189096 = CARTESIAN_POINT('',(3.14159265359,-0.198135257156)); +#189097 = CARTESIAN_POINT('',(3.14159265359,-0.183133314282)); +#189098 = CARTESIAN_POINT('',(3.14159265359,-0.160630399971)); +#189099 = CARTESIAN_POINT('',(3.14159265359,-0.138127485661)); +#189100 = CARTESIAN_POINT('',(3.14159265359,-0.11562457135)); +#189101 = CARTESIAN_POINT('',(3.14159265359,-9.31216570396E-002)); +#189102 = CARTESIAN_POINT('',(3.14159265359,-7.061874272899E-002)); +#189103 = CARTESIAN_POINT('',(3.14159265359,-4.811582841839E-002)); +#189104 = CARTESIAN_POINT('',(3.14159265359,-2.561291410778E-002)); +#189105 = CARTESIAN_POINT('',(3.14159265359,-3.109999797174E-003)); +#189106 = CARTESIAN_POINT('',(3.14159265359,1.939291451343E-002)); +#189107 = CARTESIAN_POINT('',(3.14159265359,4.189582882404E-002)); +#189108 = CARTESIAN_POINT('',(3.14159265359,6.439874313465E-002)); +#189109 = CARTESIAN_POINT('',(3.14159265359,8.690165744525E-002)); +#189110 = CARTESIAN_POINT('',(3.14159265359,0.109404571756)); +#189111 = CARTESIAN_POINT('',(3.14159265359,0.131907486066)); +#189112 = CARTESIAN_POINT('',(3.14159265359,0.154410400377)); +#189113 = CARTESIAN_POINT('',(3.14159265359,0.176913314688)); +#189114 = CARTESIAN_POINT('',(3.14159265359,0.199416228998)); +#189115 = CARTESIAN_POINT('',(3.14159265359,0.221919143309)); +#189116 = CARTESIAN_POINT('',(3.14159265359,0.244422057619)); +#189117 = CARTESIAN_POINT('',(3.14159265359,0.26692497193)); +#189118 = CARTESIAN_POINT('',(3.14159265359,0.281926914804)); +#189119 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#189120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189121 = ORIENTED_EDGE('',*,*,#189122,.F.); +#189122 = EDGE_CURVE('',#189006,#189078,#189123,.T.); +#189123 = SURFACE_CURVE('',#189124,(#189128,#189135),.PCURVE_S1.); +#189124 = LINE('',#189125,#189126); +#189125 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#189126 = VECTOR('',#189127,1.); +#189127 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#189128 = PCURVE('',#189016,#189129); +#189129 = DEFINITIONAL_REPRESENTATION('',(#189130),#189134); +#189130 = LINE('',#189131,#189132); +#189131 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#189132 = VECTOR('',#189133,1.); +#189133 = DIRECTION('',(-4.317110322781E-017,-1.)); +#189134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189135 = PCURVE('',#189136,#189141); +#189136 = PLANE('',#189137); +#189137 = AXIS2_PLACEMENT_3D('',#189138,#189139,#189140); +#189138 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#189139 = DIRECTION('',(-0.965925826289,-1.61116750665E-016, 0.258819045103)); -#186748 = DIRECTION('',(0.258819045103,-9.069926331849E-033, +#189140 = DIRECTION('',(0.258819045103,-9.069926331849E-033, 0.965925826289)); -#186749 = DEFINITIONAL_REPRESENTATION('',(#186750),#186754); -#186750 = LINE('',#186751,#186752); -#186751 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186752 = VECTOR('',#186753,1.); -#186753 = DIRECTION('',(4.317110322781E-017,-1.)); -#186754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186755 = ADVANCED_FACE('',(#186756),#185473,.T.); -#186756 = FACE_BOUND('',#186757,.T.); -#186757 = EDGE_LOOP('',(#186758,#186803,#186823,#186843,#186844,#186870, - #186871,#186897,#186898,#186924)); -#186758 = ORIENTED_EDGE('',*,*,#186759,.T.); -#186759 = EDGE_CURVE('',#185413,#186760,#186762,.T.); -#186760 = VERTEX_POINT('',#186761); -#186761 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 +#189141 = DEFINITIONAL_REPRESENTATION('',(#189142),#189146); +#189142 = LINE('',#189143,#189144); +#189143 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#189144 = VECTOR('',#189145,1.); +#189145 = DIRECTION('',(4.317110322781E-017,-1.)); +#189146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189147 = ADVANCED_FACE('',(#189148),#187865,.T.); +#189148 = FACE_BOUND('',#189149,.T.); +#189149 = EDGE_LOOP('',(#189150,#189195,#189215,#189235,#189236,#189262, + #189263,#189289,#189290,#189316)); +#189150 = ORIENTED_EDGE('',*,*,#189151,.T.); +#189151 = EDGE_CURVE('',#187805,#189152,#189154,.T.); +#189152 = VERTEX_POINT('',#189153); +#189153 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 )); -#186762 = SURFACE_CURVE('',#186763,(#186767,#186774),.PCURVE_S1.); -#186763 = LINE('',#186764,#186765); -#186764 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, +#189154 = SURFACE_CURVE('',#189155,(#189159,#189166),.PCURVE_S1.); +#189155 = LINE('',#189156,#189157); +#189156 = CARTESIAN_POINT('',(1.140884875554,0.475773749497, -5.022121888847E-002)); -#186765 = VECTOR('',#186766,1.); -#186766 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) - ); -#186767 = PCURVE('',#185473,#186768); -#186768 = DEFINITIONAL_REPRESENTATION('',(#186769),#186773); -#186769 = LINE('',#186770,#186771); -#186770 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); -#186771 = VECTOR('',#186772,1.); -#186772 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#186773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186774 = PCURVE('',#183700,#186775); -#186775 = DEFINITIONAL_REPRESENTATION('',(#186776),#186802); -#186776 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186777,#186778,#186779, - #186780,#186781,#186782,#186783,#186784,#186785,#186786,#186787, - #186788,#186789,#186790,#186791,#186792,#186793,#186794,#186795, - #186796,#186797,#186798,#186799,#186800,#186801),.UNSPECIFIED.,.F., +#189157 = VECTOR('',#189158,1.); +#189158 = DIRECTION('',(-0.250562807086,-0.250562807086,-0.935113126531) + ); +#189159 = PCURVE('',#187865,#189160); +#189160 = DEFINITIONAL_REPRESENTATION('',(#189161),#189165); +#189161 = LINE('',#189162,#189163); +#189162 = CARTESIAN_POINT('',(-0.673158539912,2.600884875554)); +#189163 = VECTOR('',#189164,1.); +#189164 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#189165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189166 = PCURVE('',#186092,#189167); +#189167 = DEFINITIONAL_REPRESENTATION('',(#189168),#189194); +#189168 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189169,#189170,#189171, + #189172,#189173,#189174,#189175,#189176,#189177,#189178,#189179, + #189180,#189181,#189182,#189183,#189184,#189185,#189186,#189187, + #189188,#189189,#189190,#189191,#189192,#189193),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.69533963372, -0.672836719409,-0.650333805098,-0.627830890788,-0.605327976477, -0.582825062167,-0.560322147856,-0.537819233545,-0.515316319235, @@ -231878,210 +234880,210 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.402801747682,-0.380298833371,-0.35779591906,-0.33529300475, -0.312790090439,-0.290287176129,-0.267784261818,-0.245281347507, -0.222778433197,-0.200275518886),.QUASI_UNIFORM_KNOTS.); -#186777 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#186778 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); -#186779 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); -#186780 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); -#186781 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); -#186782 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); -#186783 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); -#186784 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); -#186785 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); -#186786 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); -#186787 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); -#186788 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); -#186789 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); -#186790 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); -#186791 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); -#186792 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); -#186793 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); -#186794 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); -#186795 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); -#186796 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); -#186797 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); -#186798 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); -#186799 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); -#186800 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); -#186801 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#186802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186803 = ORIENTED_EDGE('',*,*,#186804,.T.); -#186804 = EDGE_CURVE('',#186760,#183937,#186805,.T.); -#186805 = SURFACE_CURVE('',#186806,(#186810,#186817),.PCURVE_S1.); -#186806 = LINE('',#186807,#186808); -#186807 = CARTESIAN_POINT('',(-1.181136529841,0.5259553457, +#189169 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#189170 = CARTESIAN_POINT('',(1.50375882859,-4.380473440761E-002)); +#189171 = CARTESIAN_POINT('',(1.50375882859,-5.880667728135E-002)); +#189172 = CARTESIAN_POINT('',(1.50375882859,-8.130959159195E-002)); +#189173 = CARTESIAN_POINT('',(1.50375882859,-0.103812505903)); +#189174 = CARTESIAN_POINT('',(1.50375882859,-0.126315420213)); +#189175 = CARTESIAN_POINT('',(1.50375882859,-0.148818334524)); +#189176 = CARTESIAN_POINT('',(1.50375882859,-0.171321248834)); +#189177 = CARTESIAN_POINT('',(1.50375882859,-0.193824163145)); +#189178 = CARTESIAN_POINT('',(1.50375882859,-0.216327077456)); +#189179 = CARTESIAN_POINT('',(1.50375882859,-0.238829991766)); +#189180 = CARTESIAN_POINT('',(1.50375882859,-0.261332906077)); +#189181 = CARTESIAN_POINT('',(1.50375882859,-0.283835820387)); +#189182 = CARTESIAN_POINT('',(1.50375882859,-0.306338734698)); +#189183 = CARTESIAN_POINT('',(1.50375882859,-0.328841649009)); +#189184 = CARTESIAN_POINT('',(1.50375882859,-0.351344563319)); +#189185 = CARTESIAN_POINT('',(1.50375882859,-0.37384747763)); +#189186 = CARTESIAN_POINT('',(1.50375882859,-0.39635039194)); +#189187 = CARTESIAN_POINT('',(1.50375882859,-0.418853306251)); +#189188 = CARTESIAN_POINT('',(1.50375882859,-0.441356220562)); +#189189 = CARTESIAN_POINT('',(1.50375882859,-0.463859134872)); +#189190 = CARTESIAN_POINT('',(1.50375882859,-0.486362049183)); +#189191 = CARTESIAN_POINT('',(1.50375882859,-0.508864963493)); +#189192 = CARTESIAN_POINT('',(1.50375882859,-0.523866906367)); +#189193 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#189194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189195 = ORIENTED_EDGE('',*,*,#189196,.T.); +#189196 = EDGE_CURVE('',#189152,#186329,#189197,.T.); +#189197 = SURFACE_CURVE('',#189198,(#189202,#189209),.PCURVE_S1.); +#189198 = LINE('',#189199,#189200); +#189199 = CARTESIAN_POINT('',(-1.181136529841,0.5259553457, 0.137059047745)); -#186808 = VECTOR('',#186809,1.); -#186809 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186810 = PCURVE('',#185473,#186811); -#186811 = DEFINITIONAL_REPRESENTATION('',(#186812),#186816); -#186812 = LINE('',#186813,#186814); -#186813 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); -#186814 = VECTOR('',#186815,1.); -#186815 = DIRECTION('',(0.E+000,-1.)); -#186816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186817 = PCURVE('',#184046,#186818); -#186818 = DEFINITIONAL_REPRESENTATION('',(#186819),#186822); -#186819 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186820,#186821), +#189200 = VECTOR('',#189201,1.); +#189201 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189202 = PCURVE('',#187865,#189203); +#189203 = DEFINITIONAL_REPRESENTATION('',(#189204),#189208); +#189204 = LINE('',#189205,#189206); +#189205 = CARTESIAN_POINT('',(-0.479271740806,0.278863470159)); +#189206 = VECTOR('',#189207,1.); +#189207 = DIRECTION('',(0.E+000,-1.)); +#189208 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189209 = PCURVE('',#186438,#189210); +#189210 = DEFINITIONAL_REPRESENTATION('',(#189211),#189214); +#189211 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189212,#189213), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#186820 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); -#186821 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); -#186822 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189212 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); +#189213 = CARTESIAN_POINT('',(1.308996938996,0.268933528243)); +#189214 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186823 = ORIENTED_EDGE('',*,*,#186824,.T.); -#186824 = EDGE_CURVE('',#183937,#185341,#186825,.T.); -#186825 = SURFACE_CURVE('',#186826,(#186830,#186837),.PCURVE_S1.); -#186826 = LINE('',#186827,#186828); -#186827 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, +#189215 = ORIENTED_EDGE('',*,*,#189216,.T.); +#189216 = EDGE_CURVE('',#186329,#187733,#189217,.T.); +#189217 = SURFACE_CURVE('',#189218,(#189222,#189229),.PCURVE_S1.); +#189218 = LINE('',#189219,#189220); +#189219 = CARTESIAN_POINT('',(-1.324207498814,0.659096372758, 0.633948125296)); -#186828 = VECTOR('',#186829,1.); -#186829 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); -#186830 = PCURVE('',#185473,#186831); -#186831 = DEFINITIONAL_REPRESENTATION('',(#186832),#186836); -#186832 = LINE('',#186833,#186834); -#186833 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); -#186834 = VECTOR('',#186835,1.); -#186835 = DIRECTION('',(0.968100345886,-0.250562807086)); -#186836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186837 = PCURVE('',#183975,#186838); -#186838 = DEFINITIONAL_REPRESENTATION('',(#186839),#186842); -#186839 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#186840,#186841), - .UNSPECIFIED.,.F.,.F.,(2,2),(-0.531367877804,-3.630376297074E-002), - .PIECEWISE_BEZIER_KNOTS.); -#186840 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); -#186841 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#186842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186843 = ORIENTED_EDGE('',*,*,#185783,.F.); -#186844 = ORIENTED_EDGE('',*,*,#186845,.F.); -#186845 = EDGE_CURVE('',#185677,#185756,#186846,.T.); -#186846 = SURFACE_CURVE('',#186847,(#186851,#186858),.PCURVE_S1.); -#186847 = LINE('',#186848,#186849); -#186848 = CARTESIAN_POINT('',(-3.36,0.65,0.6)); -#186849 = VECTOR('',#186850,1.); -#186850 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186851 = PCURVE('',#185473,#186852); -#186852 = DEFINITIONAL_REPRESENTATION('',(#186853),#186857); -#186853 = LINE('',#186854,#186855); -#186854 = CARTESIAN_POINT('',(0.E+000,-1.9)); -#186855 = VECTOR('',#186856,1.); -#186856 = DIRECTION('',(0.E+000,-1.)); -#186857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186858 = PCURVE('',#186859,#186864); -#186859 = PLANE('',#186860); -#186860 = AXIS2_PLACEMENT_3D('',#186861,#186862,#186863); -#186861 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#186862 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186863 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186864 = DEFINITIONAL_REPRESENTATION('',(#186865),#186869); -#186865 = LINE('',#186866,#186867); -#186866 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); -#186867 = VECTOR('',#186868,1.); -#186868 = DIRECTION('',(1.,0.E+000)); -#186869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186870 = ORIENTED_EDGE('',*,*,#185676,.F.); -#186871 = ORIENTED_EDGE('',*,*,#186872,.F.); -#186872 = EDGE_CURVE('',#185570,#185649,#186873,.T.); -#186873 = SURFACE_CURVE('',#186874,(#186878,#186885),.PCURVE_S1.); -#186874 = LINE('',#186875,#186876); -#186875 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#186876 = VECTOR('',#186877,1.); -#186877 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186878 = PCURVE('',#185473,#186879); -#186879 = DEFINITIONAL_REPRESENTATION('',(#186880),#186884); -#186880 = LINE('',#186881,#186882); -#186881 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186882 = VECTOR('',#186883,1.); -#186883 = DIRECTION('',(0.E+000,-1.)); -#186884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189220 = VECTOR('',#189221,1.); +#189221 = DIRECTION('',(-0.250562807086,0.250562807086,0.935113126531)); +#189222 = PCURVE('',#187865,#189223); +#189223 = DEFINITIONAL_REPRESENTATION('',(#189224),#189228); +#189224 = LINE('',#189225,#189226); +#189225 = CARTESIAN_POINT('',(3.514568548895E-002,0.135792501186)); +#189226 = VECTOR('',#189227,1.); +#189227 = DIRECTION('',(0.968100345886,-0.250562807086)); +#189228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#186885 = PCURVE('',#186886,#186891); -#186886 = PLANE('',#186887); -#186887 = AXIS2_PLACEMENT_3D('',#186888,#186889,#186890); -#186888 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#186889 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186890 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186891 = DEFINITIONAL_REPRESENTATION('',(#186892),#186896); -#186892 = LINE('',#186893,#186894); -#186893 = CARTESIAN_POINT('',(1.26,-5.208001194231E-003)); -#186894 = VECTOR('',#186895,1.); -#186895 = DIRECTION('',(1.,0.E+000)); -#186896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186897 = ORIENTED_EDGE('',*,*,#185569,.F.); -#186898 = ORIENTED_EDGE('',*,*,#186899,.F.); -#186899 = EDGE_CURVE('',#185458,#185542,#186900,.T.); -#186900 = SURFACE_CURVE('',#186901,(#186905,#186912),.PCURVE_S1.); -#186901 = LINE('',#186902,#186903); -#186902 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); -#186903 = VECTOR('',#186904,1.); -#186904 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186905 = PCURVE('',#185473,#186906); -#186906 = DEFINITIONAL_REPRESENTATION('',(#186907),#186911); -#186907 = LINE('',#186908,#186909); -#186908 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#186909 = VECTOR('',#186910,1.); -#186910 = DIRECTION('',(0.E+000,-1.)); -#186911 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186912 = PCURVE('',#186913,#186918); -#186913 = PLANE('',#186914); -#186914 = AXIS2_PLACEMENT_3D('',#186915,#186916,#186917); -#186915 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#186916 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#186917 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#186918 = DEFINITIONAL_REPRESENTATION('',(#186919),#186923); -#186919 = LINE('',#186920,#186921); -#186920 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); -#186921 = VECTOR('',#186922,1.); -#186922 = DIRECTION('',(1.,0.E+000)); -#186923 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186924 = ORIENTED_EDGE('',*,*,#185457,.F.); -#186925 = ADVANCED_FACE('',(#186926),#183013,.F.); -#186926 = FACE_BOUND('',#186927,.T.); -#186927 = EDGE_LOOP('',(#186928,#186973,#187018,#187019,#187041,#187086, - #187087,#187132,#187177,#187178,#187200,#187245)); -#186928 = ORIENTED_EDGE('',*,*,#186929,.T.); -#186929 = EDGE_CURVE('',#183513,#186930,#186932,.T.); -#186930 = VERTEX_POINT('',#186931); -#186931 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#186932 = SURFACE_CURVE('',#186933,(#186937,#186944),.PCURVE_S1.); -#186933 = LINE('',#186934,#186935); -#186934 = CARTESIAN_POINT('',(1.287659054385,-0.371136529841,1.E-001)); -#186935 = VECTOR('',#186936,1.); -#186936 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#186937 = PCURVE('',#183013,#186938); -#186938 = DEFINITIONAL_REPRESENTATION('',(#186939),#186943); -#186939 = LINE('',#186940,#186941); -#186940 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); -#186941 = VECTOR('',#186942,1.); -#186942 = DIRECTION('',(1.668003342285E-016,-1.)); -#186943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186944 = PCURVE('',#183771,#186945); -#186945 = DEFINITIONAL_REPRESENTATION('',(#186946),#186972); -#186946 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186947,#186948,#186949, - #186950,#186951,#186952,#186953,#186954,#186955,#186956,#186957, - #186958,#186959,#186960,#186961,#186962,#186963,#186964,#186965, - #186966,#186967,#186968,#186969,#186970,#186971),.UNSPECIFIED.,.F., +#189229 = PCURVE('',#186367,#189230); +#189230 = DEFINITIONAL_REPRESENTATION('',(#189231),#189234); +#189231 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189232,#189233), + .UNSPECIFIED.,.F.,.F.,(2,2),(-0.531367877804,-3.630376297074E-002), + .PIECEWISE_BEZIER_KNOTS.); +#189232 = CARTESIAN_POINT('',(1.637833825,-0.531367877804)); +#189233 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#189234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189235 = ORIENTED_EDGE('',*,*,#188175,.F.); +#189236 = ORIENTED_EDGE('',*,*,#189237,.F.); +#189237 = EDGE_CURVE('',#188069,#188148,#189238,.T.); +#189238 = SURFACE_CURVE('',#189239,(#189243,#189250),.PCURVE_S1.); +#189239 = LINE('',#189240,#189241); +#189240 = CARTESIAN_POINT('',(-3.36,0.65,0.6)); +#189241 = VECTOR('',#189242,1.); +#189242 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189243 = PCURVE('',#187865,#189244); +#189244 = DEFINITIONAL_REPRESENTATION('',(#189245),#189249); +#189245 = LINE('',#189246,#189247); +#189246 = CARTESIAN_POINT('',(0.E+000,-1.9)); +#189247 = VECTOR('',#189248,1.); +#189248 = DIRECTION('',(0.E+000,-1.)); +#189249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189250 = PCURVE('',#189251,#189256); +#189251 = PLANE('',#189252); +#189252 = AXIS2_PLACEMENT_3D('',#189253,#189254,#189255); +#189253 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#189254 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#189255 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189256 = DEFINITIONAL_REPRESENTATION('',(#189257),#189261); +#189257 = LINE('',#189258,#189259); +#189258 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); +#189259 = VECTOR('',#189260,1.); +#189260 = DIRECTION('',(1.,0.E+000)); +#189261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189262 = ORIENTED_EDGE('',*,*,#188068,.F.); +#189263 = ORIENTED_EDGE('',*,*,#189264,.F.); +#189264 = EDGE_CURVE('',#187962,#188041,#189265,.T.); +#189265 = SURFACE_CURVE('',#189266,(#189270,#189277),.PCURVE_S1.); +#189266 = LINE('',#189267,#189268); +#189267 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#189268 = VECTOR('',#189269,1.); +#189269 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189270 = PCURVE('',#187865,#189271); +#189271 = DEFINITIONAL_REPRESENTATION('',(#189272),#189276); +#189272 = LINE('',#189273,#189274); +#189273 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#189274 = VECTOR('',#189275,1.); +#189275 = DIRECTION('',(0.E+000,-1.)); +#189276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189277 = PCURVE('',#189278,#189283); +#189278 = PLANE('',#189279); +#189279 = AXIS2_PLACEMENT_3D('',#189280,#189281,#189282); +#189280 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#189281 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#189282 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189283 = DEFINITIONAL_REPRESENTATION('',(#189284),#189288); +#189284 = LINE('',#189285,#189286); +#189285 = CARTESIAN_POINT('',(1.26,-5.208001194231E-003)); +#189286 = VECTOR('',#189287,1.); +#189287 = DIRECTION('',(1.,0.E+000)); +#189288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189289 = ORIENTED_EDGE('',*,*,#187961,.F.); +#189290 = ORIENTED_EDGE('',*,*,#189291,.F.); +#189291 = EDGE_CURVE('',#187850,#187934,#189292,.T.); +#189292 = SURFACE_CURVE('',#189293,(#189297,#189304),.PCURVE_S1.); +#189293 = LINE('',#189294,#189295); +#189294 = CARTESIAN_POINT('',(-1.46,0.65,0.6)); +#189295 = VECTOR('',#189296,1.); +#189296 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189297 = PCURVE('',#187865,#189298); +#189298 = DEFINITIONAL_REPRESENTATION('',(#189299),#189303); +#189299 = LINE('',#189300,#189301); +#189300 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#189301 = VECTOR('',#189302,1.); +#189302 = DIRECTION('',(0.E+000,-1.)); +#189303 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189304 = PCURVE('',#189305,#189310); +#189305 = PLANE('',#189306); +#189306 = AXIS2_PLACEMENT_3D('',#189307,#189308,#189309); +#189307 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#189308 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#189309 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189310 = DEFINITIONAL_REPRESENTATION('',(#189311),#189315); +#189311 = LINE('',#189312,#189313); +#189312 = CARTESIAN_POINT('',(2.215,-5.208001194231E-003)); +#189313 = VECTOR('',#189314,1.); +#189314 = DIRECTION('',(1.,0.E+000)); +#189315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189316 = ORIENTED_EDGE('',*,*,#187849,.F.); +#189317 = ADVANCED_FACE('',(#189318),#185405,.F.); +#189318 = FACE_BOUND('',#189319,.T.); +#189319 = EDGE_LOOP('',(#189320,#189365,#189410,#189411,#189433,#189478, + #189479,#189524,#189569,#189570,#189592,#189637)); +#189320 = ORIENTED_EDGE('',*,*,#189321,.T.); +#189321 = EDGE_CURVE('',#185905,#189322,#189324,.T.); +#189322 = VERTEX_POINT('',#189323); +#189323 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#189324 = SURFACE_CURVE('',#189325,(#189329,#189336),.PCURVE_S1.); +#189325 = LINE('',#189326,#189327); +#189326 = CARTESIAN_POINT('',(1.287659054385,-0.371136529841,1.E-001)); +#189327 = VECTOR('',#189328,1.); +#189328 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#189329 = PCURVE('',#185405,#189330); +#189330 = DEFINITIONAL_REPRESENTATION('',(#189331),#189335); +#189331 = LINE('',#189332,#189333); +#189332 = CARTESIAN_POINT('',(-0.172340945615,0.278863470159)); +#189333 = VECTOR('',#189334,1.); +#189334 = DIRECTION('',(1.668003342285E-016,-1.)); +#189335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189336 = PCURVE('',#186163,#189337); +#189337 = DEFINITIONAL_REPRESENTATION('',(#189338),#189364); +#189338 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189339,#189340,#189341, + #189342,#189343,#189344,#189345,#189346,#189347,#189348,#189349, + #189350,#189351,#189352,#189353,#189354,#189355,#189356,#189357, + #189358,#189359,#189360,#189361,#189362,#189363),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598, -0.717560595074,-0.682918188551,-0.648275782028,-0.613633375504, -0.578990968981,-0.544348562458,-0.509706155934,-0.475063749411, @@ -232090,66 +235092,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.163282090701,-0.128639684178,-9.399727765447E-002, -5.935487113115E-002,-2.471246460782E-002,9.929941915506E-003), .UNSPECIFIED.); -#186947 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); -#186948 = CARTESIAN_POINT('',(4.712388980385,0.280480997085)); -#186949 = CARTESIAN_POINT('',(4.712388980385,0.303575934767)); -#186950 = CARTESIAN_POINT('',(4.712388980385,0.33821834129)); -#186951 = CARTESIAN_POINT('',(4.712388980385,0.372860747813)); -#186952 = CARTESIAN_POINT('',(4.712388980385,0.407503154337)); -#186953 = CARTESIAN_POINT('',(4.712388980385,0.44214556086)); -#186954 = CARTESIAN_POINT('',(4.712388980385,0.476787967383)); -#186955 = CARTESIAN_POINT('',(4.712388980385,0.511430373907)); -#186956 = CARTESIAN_POINT('',(4.712388980385,0.54607278043)); -#186957 = CARTESIAN_POINT('',(4.712388980385,0.580715186953)); -#186958 = CARTESIAN_POINT('',(4.712388980385,0.615357593477)); -#186959 = CARTESIAN_POINT('',(4.712388980385,0.65)); -#186960 = CARTESIAN_POINT('',(4.712388980385,0.684642406523)); -#186961 = CARTESIAN_POINT('',(4.712388980385,0.719284813047)); -#186962 = CARTESIAN_POINT('',(4.712388980385,0.75392721957)); -#186963 = CARTESIAN_POINT('',(4.712388980385,0.788569626093)); -#186964 = CARTESIAN_POINT('',(4.712388980385,0.823212032617)); -#186965 = CARTESIAN_POINT('',(4.712388980385,0.85785443914)); -#186966 = CARTESIAN_POINT('',(4.712388980385,0.892496845663)); -#186967 = CARTESIAN_POINT('',(4.712388980385,0.927139252187)); -#186968 = CARTESIAN_POINT('',(4.712388980385,0.96178165871)); -#186969 = CARTESIAN_POINT('',(4.712388980385,0.996424065233)); -#186970 = CARTESIAN_POINT('',(4.712388980385,1.019519002915)); -#186971 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); -#186972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186973 = ORIENTED_EDGE('',*,*,#186974,.T.); -#186974 = EDGE_CURVE('',#186930,#182956,#186975,.T.); -#186975 = SURFACE_CURVE('',#186976,(#186981,#186989),.PCURVE_S1.); -#186976 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186977,#186978,#186979, -#186980),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189339 = CARTESIAN_POINT('',(4.712388980385,0.268933528243)); +#189340 = CARTESIAN_POINT('',(4.712388980385,0.280480997085)); +#189341 = CARTESIAN_POINT('',(4.712388980385,0.303575934767)); +#189342 = CARTESIAN_POINT('',(4.712388980385,0.33821834129)); +#189343 = CARTESIAN_POINT('',(4.712388980385,0.372860747813)); +#189344 = CARTESIAN_POINT('',(4.712388980385,0.407503154337)); +#189345 = CARTESIAN_POINT('',(4.712388980385,0.44214556086)); +#189346 = CARTESIAN_POINT('',(4.712388980385,0.476787967383)); +#189347 = CARTESIAN_POINT('',(4.712388980385,0.511430373907)); +#189348 = CARTESIAN_POINT('',(4.712388980385,0.54607278043)); +#189349 = CARTESIAN_POINT('',(4.712388980385,0.580715186953)); +#189350 = CARTESIAN_POINT('',(4.712388980385,0.615357593477)); +#189351 = CARTESIAN_POINT('',(4.712388980385,0.65)); +#189352 = CARTESIAN_POINT('',(4.712388980385,0.684642406523)); +#189353 = CARTESIAN_POINT('',(4.712388980385,0.719284813047)); +#189354 = CARTESIAN_POINT('',(4.712388980385,0.75392721957)); +#189355 = CARTESIAN_POINT('',(4.712388980385,0.788569626093)); +#189356 = CARTESIAN_POINT('',(4.712388980385,0.823212032617)); +#189357 = CARTESIAN_POINT('',(4.712388980385,0.85785443914)); +#189358 = CARTESIAN_POINT('',(4.712388980385,0.892496845663)); +#189359 = CARTESIAN_POINT('',(4.712388980385,0.927139252187)); +#189360 = CARTESIAN_POINT('',(4.712388980385,0.96178165871)); +#189361 = CARTESIAN_POINT('',(4.712388980385,0.996424065233)); +#189362 = CARTESIAN_POINT('',(4.712388980385,1.019519002915)); +#189363 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); +#189364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189365 = ORIENTED_EDGE('',*,*,#189366,.T.); +#189366 = EDGE_CURVE('',#189322,#185348,#189367,.T.); +#189367 = SURFACE_CURVE('',#189368,(#189373,#189381),.PCURVE_S1.); +#189368 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189369,#189370,#189371, +#189372),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#186977 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); -#186978 = CARTESIAN_POINT('',(1.287659054385,-0.407584046027,1.E-001)); -#186979 = CARTESIAN_POINT('',(1.27790129499,-0.431596067115,1.E-001)); -#186980 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); -#186981 = PCURVE('',#183013,#186982); -#186982 = DEFINITIONAL_REPRESENTATION('',(#186983),#186988); -#186983 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#186984,#186985,#186986, -#186987),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189369 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,1.E-001)); +#189370 = CARTESIAN_POINT('',(1.287659054385,-0.407584046027,1.E-001)); +#189371 = CARTESIAN_POINT('',(1.27790129499,-0.431596067115,1.E-001)); +#189372 = CARTESIAN_POINT('',(1.259748681053,-0.449748681053,1.E-001)); +#189373 = PCURVE('',#185405,#189374); +#189374 = DEFINITIONAL_REPRESENTATION('',(#189375),#189380); +#189375 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189376,#189377,#189378, +#189379),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#186984 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); -#186985 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); -#186986 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); -#186987 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); -#186988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#186989 = PCURVE('',#183065,#186990); -#186990 = DEFINITIONAL_REPRESENTATION('',(#186991),#187017); -#186991 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#186992,#186993,#186994, - #186995,#186996,#186997,#186998,#186999,#187000,#187001,#187002, - #187003,#187004,#187005,#187006,#187007,#187008,#187009,#187010, - #187011,#187012,#187013,#187014,#187015,#187016),.UNSPECIFIED.,.F., +#189376 = CARTESIAN_POINT('',(-0.172340945615,0.268933528243)); +#189377 = CARTESIAN_POINT('',(-0.172340945615,0.242415953973)); +#189378 = CARTESIAN_POINT('',(-0.18209870501,0.218403932885)); +#189379 = CARTESIAN_POINT('',(-0.200251318947,0.200251318947)); +#189380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189381 = PCURVE('',#185457,#189382); +#189382 = DEFINITIONAL_REPRESENTATION('',(#189383),#189409); +#189383 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189384,#189385,#189386, + #189387,#189388,#189389,#189390,#189391,#189392,#189393,#189394, + #189395,#189396,#189397,#189398,#189399,#189400,#189401,#189402, + #189403,#189404,#189405,#189406,#189407,#189408),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -232157,95 +235159,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#186992 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#186993 = CARTESIAN_POINT('',(0.740753697746,-2.901323913156E-008)); -#186994 = CARTESIAN_POINT('',(0.718425611961,2.616756247982E-005)); -#186995 = CARTESIAN_POINT('',(0.684727524261,1.282673135031E-004)); -#186996 = CARTESIAN_POINT('',(0.650847765387,2.772530388756E-004)); -#186997 = CARTESIAN_POINT('',(0.616809612353,4.570658043226E-004)); -#186998 = CARTESIAN_POINT('',(0.582635599926,6.520952931882E-004)); -#186999 = CARTESIAN_POINT('',(0.548347414424,8.475624467471E-004)); -#187000 = CARTESIAN_POINT('',(0.513965932674,1.029943289554E-003)); -#187001 = CARTESIAN_POINT('',(0.479511265006,1.18735393038E-003)); -#187002 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); -#187003 = CARTESIAN_POINT('',(0.41045949854,1.390009812362E-003)); -#187004 = CARTESIAN_POINT('',(0.375899653916,1.422641316503E-003)); -#187005 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); -#187006 = CARTESIAN_POINT('',(0.306802773621,1.339263477882E-003)); -#187007 = CARTESIAN_POINT('',(0.272301764008,1.227390254485E-003)); -#187008 = CARTESIAN_POINT('',(0.237856655052,1.076339414003E-003)); -#187009 = CARTESIAN_POINT('',(0.203486118557,8.953387637339E-004)); -#187010 = CARTESIAN_POINT('',(0.169209394064,6.962198987728E-004)); -#187011 = CARTESIAN_POINT('',(0.135046437107,4.93149846856E-004)); -#187012 = CARTESIAN_POINT('',(0.101018031154,3.022859269965E-004)); -#187013 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577683E-004)); -#187014 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401059E-005)); -#187015 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318693053E-008)); -#187016 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#187017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187018 = ORIENTED_EDGE('',*,*,#182955,.T.); -#187019 = ORIENTED_EDGE('',*,*,#187020,.T.); -#187020 = EDGE_CURVE('',#182958,#187021,#187023,.T.); -#187021 = VERTEX_POINT('',#187022); -#187022 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#187023 = SURFACE_CURVE('',#187024,(#187028,#187035),.PCURVE_S1.); -#187024 = LINE('',#187025,#187026); -#187025 = CARTESIAN_POINT('',(-1.181136529841,-0.477659054385,1.E-001)); -#187026 = VECTOR('',#187027,1.); -#187027 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#187028 = PCURVE('',#183013,#187029); -#187029 = DEFINITIONAL_REPRESENTATION('',(#187030),#187034); -#187030 = LINE('',#187031,#187032); -#187031 = CARTESIAN_POINT('',(-2.641136529841,0.172340945615)); -#187032 = VECTOR('',#187033,1.); -#187033 = DIRECTION('',(-1.,0.E+000)); -#187034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187035 = PCURVE('',#183221,#187036); -#187036 = DEFINITIONAL_REPRESENTATION('',(#187037),#187040); -#187037 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187038,#187039), +#189384 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#189385 = CARTESIAN_POINT('',(0.740753697746,-2.901323913156E-008)); +#189386 = CARTESIAN_POINT('',(0.718425611961,2.616756247982E-005)); +#189387 = CARTESIAN_POINT('',(0.684727524261,1.282673135031E-004)); +#189388 = CARTESIAN_POINT('',(0.650847765387,2.772530388756E-004)); +#189389 = CARTESIAN_POINT('',(0.616809612353,4.570658043226E-004)); +#189390 = CARTESIAN_POINT('',(0.582635599926,6.520952931882E-004)); +#189391 = CARTESIAN_POINT('',(0.548347414424,8.475624467471E-004)); +#189392 = CARTESIAN_POINT('',(0.513965932674,1.029943289554E-003)); +#189393 = CARTESIAN_POINT('',(0.479511265006,1.18735393038E-003)); +#189394 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); +#189395 = CARTESIAN_POINT('',(0.41045949854,1.390009812362E-003)); +#189396 = CARTESIAN_POINT('',(0.375899653916,1.422641316503E-003)); +#189397 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); +#189398 = CARTESIAN_POINT('',(0.306802773621,1.339263477882E-003)); +#189399 = CARTESIAN_POINT('',(0.272301764008,1.227390254485E-003)); +#189400 = CARTESIAN_POINT('',(0.237856655052,1.076339414003E-003)); +#189401 = CARTESIAN_POINT('',(0.203486118557,8.953387637339E-004)); +#189402 = CARTESIAN_POINT('',(0.169209394064,6.962198987728E-004)); +#189403 = CARTESIAN_POINT('',(0.135046437107,4.93149846856E-004)); +#189404 = CARTESIAN_POINT('',(0.101018031154,3.022859269965E-004)); +#189405 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577683E-004)); +#189406 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401059E-005)); +#189407 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318693053E-008)); +#189408 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#189409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189410 = ORIENTED_EDGE('',*,*,#185347,.T.); +#189411 = ORIENTED_EDGE('',*,*,#189412,.T.); +#189412 = EDGE_CURVE('',#185350,#189413,#189415,.T.); +#189413 = VERTEX_POINT('',#189414); +#189414 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#189415 = SURFACE_CURVE('',#189416,(#189420,#189427),.PCURVE_S1.); +#189416 = LINE('',#189417,#189418); +#189417 = CARTESIAN_POINT('',(-1.181136529841,-0.477659054385,1.E-001)); +#189418 = VECTOR('',#189419,1.); +#189419 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#189420 = PCURVE('',#185405,#189421); +#189421 = DEFINITIONAL_REPRESENTATION('',(#189422),#189426); +#189422 = LINE('',#189423,#189424); +#189423 = CARTESIAN_POINT('',(-2.641136529841,0.172340945615)); +#189424 = VECTOR('',#189425,1.); +#189425 = DIRECTION('',(-1.,0.E+000)); +#189426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189427 = PCURVE('',#185613,#189428); +#189428 = DEFINITIONAL_REPRESENTATION('',(#189429),#189432); +#189429 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189430,#189431), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#187038 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); -#187039 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#187040 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189430 = CARTESIAN_POINT('',(3.14159265359,-2.651066471757)); +#189431 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#189432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187041 = ORIENTED_EDGE('',*,*,#187042,.T.); -#187042 = EDGE_CURVE('',#187021,#183236,#187043,.T.); -#187043 = SURFACE_CURVE('',#187044,(#187049,#187057),.PCURVE_S1.); -#187044 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187045,#187046,#187047, -#187048),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189433 = ORIENTED_EDGE('',*,*,#189434,.T.); +#189434 = EDGE_CURVE('',#189413,#185628,#189435,.T.); +#189435 = SURFACE_CURVE('',#189436,(#189441,#189449),.PCURVE_S1.); +#189436 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189437,#189438,#189439, +#189440),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187045 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); -#187046 = CARTESIAN_POINT('',(-1.217584046027,-0.477659054385,1.E-001)); -#187047 = CARTESIAN_POINT('',(-1.241596067115,-0.46790129499,1.E-001)); -#187048 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); -#187049 = PCURVE('',#183013,#187050); -#187050 = DEFINITIONAL_REPRESENTATION('',(#187051),#187056); -#187051 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187052,#187053,#187054, -#187055),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189437 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,1.E-001)); +#189438 = CARTESIAN_POINT('',(-1.217584046027,-0.477659054385,1.E-001)); +#189439 = CARTESIAN_POINT('',(-1.241596067115,-0.46790129499,1.E-001)); +#189440 = CARTESIAN_POINT('',(-1.259748681053,-0.449748681053,1.E-001)); +#189441 = PCURVE('',#185405,#189442); +#189442 = DEFINITIONAL_REPRESENTATION('',(#189443),#189448); +#189443 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189444,#189445,#189446, +#189447),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187052 = CARTESIAN_POINT('',(-2.651066471757,0.172340945615)); -#187053 = CARTESIAN_POINT('',(-2.677584046027,0.172340945615)); -#187054 = CARTESIAN_POINT('',(-2.701596067115,0.18209870501)); -#187055 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); -#187056 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187057 = PCURVE('',#183340,#187058); -#187058 = DEFINITIONAL_REPRESENTATION('',(#187059),#187085); -#187059 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187060,#187061,#187062, - #187063,#187064,#187065,#187066,#187067,#187068,#187069,#187070, - #187071,#187072,#187073,#187074,#187075,#187076,#187077,#187078, - #187079,#187080,#187081,#187082,#187083,#187084),.UNSPECIFIED.,.F., +#189444 = CARTESIAN_POINT('',(-2.651066471757,0.172340945615)); +#189445 = CARTESIAN_POINT('',(-2.677584046027,0.172340945615)); +#189446 = CARTESIAN_POINT('',(-2.701596067115,0.18209870501)); +#189447 = CARTESIAN_POINT('',(-2.719748681053,0.200251318947)); +#189448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189449 = PCURVE('',#185732,#189450); +#189450 = DEFINITIONAL_REPRESENTATION('',(#189451),#189477); +#189451 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189452,#189453,#189454, + #189455,#189456,#189457,#189458,#189459,#189460,#189461,#189462, + #189463,#189464,#189465,#189466,#189467,#189468,#189469,#189470, + #189471,#189472,#189473,#189474,#189475,#189476),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -232253,59 +235255,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#187060 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#187061 = CARTESIAN_POINT('',(0.740753697746,-2.901324287027E-008)); -#187062 = CARTESIAN_POINT('',(0.718425611961,2.616756246917E-005)); -#187063 = CARTESIAN_POINT('',(0.684727524261,1.282673134852E-004)); -#187064 = CARTESIAN_POINT('',(0.650847765387,2.772530388731E-004)); -#187065 = CARTESIAN_POINT('',(0.616809612353,4.570658043139E-004)); -#187066 = CARTESIAN_POINT('',(0.582635599926,6.5209529318E-004)); -#187067 = CARTESIAN_POINT('',(0.548347414424,8.475624467432E-004)); -#187068 = CARTESIAN_POINT('',(0.513965932674,1.029943289548E-003)); -#187069 = CARTESIAN_POINT('',(0.479511265006,1.187353930379E-003)); -#187070 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); -#187071 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); -#187072 = CARTESIAN_POINT('',(0.375899653916,1.422641316492E-003)); -#187073 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); -#187074 = CARTESIAN_POINT('',(0.306802773621,1.339263477879E-003)); -#187075 = CARTESIAN_POINT('',(0.272301764008,1.227390254476E-003)); -#187076 = CARTESIAN_POINT('',(0.237856655052,1.076339413998E-003)); -#187077 = CARTESIAN_POINT('',(0.203486118557,8.953387637282E-004)); -#187078 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); -#187079 = CARTESIAN_POINT('',(0.135046437107,4.931498468552E-004)); -#187080 = CARTESIAN_POINT('',(0.101018031154,3.022859269932E-004)); -#187081 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577614E-004)); -#187082 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009786E-005)); -#187083 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318295513E-008)); -#187084 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#187085 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187086 = ORIENTED_EDGE('',*,*,#183235,.T.); -#187087 = ORIENTED_EDGE('',*,*,#187088,.T.); -#187088 = EDGE_CURVE('',#183238,#187089,#187091,.T.); -#187089 = VERTEX_POINT('',#187090); -#187090 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#187091 = SURFACE_CURVE('',#187092,(#187096,#187103),.PCURVE_S1.); -#187092 = LINE('',#187093,#187094); -#187093 = CARTESIAN_POINT('',(-1.287659054385,0.371136529841,1.E-001)); -#187094 = VECTOR('',#187095,1.); -#187095 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#187096 = PCURVE('',#183013,#187097); -#187097 = DEFINITIONAL_REPRESENTATION('',(#187098),#187102); -#187098 = LINE('',#187099,#187100); -#187099 = CARTESIAN_POINT('',(-2.747659054385,1.021136529841)); -#187100 = VECTOR('',#187101,1.); -#187101 = DIRECTION('',(-1.668003342285E-016,1.)); -#187102 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187103 = PCURVE('',#183496,#187104); -#187104 = DEFINITIONAL_REPRESENTATION('',(#187105),#187131); -#187105 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187106,#187107,#187108, - #187109,#187110,#187111,#187112,#187113,#187114,#187115,#187116, - #187117,#187118,#187119,#187120,#187121,#187122,#187123,#187124, - #187125,#187126,#187127,#187128,#187129,#187130),.UNSPECIFIED.,.F., +#189452 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#189453 = CARTESIAN_POINT('',(0.740753697746,-2.901324287027E-008)); +#189454 = CARTESIAN_POINT('',(0.718425611961,2.616756246917E-005)); +#189455 = CARTESIAN_POINT('',(0.684727524261,1.282673134852E-004)); +#189456 = CARTESIAN_POINT('',(0.650847765387,2.772530388731E-004)); +#189457 = CARTESIAN_POINT('',(0.616809612353,4.570658043139E-004)); +#189458 = CARTESIAN_POINT('',(0.582635599926,6.5209529318E-004)); +#189459 = CARTESIAN_POINT('',(0.548347414424,8.475624467432E-004)); +#189460 = CARTESIAN_POINT('',(0.513965932674,1.029943289548E-003)); +#189461 = CARTESIAN_POINT('',(0.479511265006,1.187353930379E-003)); +#189462 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); +#189463 = CARTESIAN_POINT('',(0.41045949854,1.390009812361E-003)); +#189464 = CARTESIAN_POINT('',(0.375899653916,1.422641316492E-003)); +#189465 = CARTESIAN_POINT('',(0.341341416362,1.405524714326E-003)); +#189466 = CARTESIAN_POINT('',(0.306802773621,1.339263477879E-003)); +#189467 = CARTESIAN_POINT('',(0.272301764008,1.227390254476E-003)); +#189468 = CARTESIAN_POINT('',(0.237856655052,1.076339413998E-003)); +#189469 = CARTESIAN_POINT('',(0.203486118557,8.953387637282E-004)); +#189470 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); +#189471 = CARTESIAN_POINT('',(0.135046437107,4.931498468552E-004)); +#189472 = CARTESIAN_POINT('',(0.101018031154,3.022859269932E-004)); +#189473 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577614E-004)); +#189474 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009786E-005)); +#189475 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318295513E-008)); +#189476 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#189477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189478 = ORIENTED_EDGE('',*,*,#185627,.T.); +#189479 = ORIENTED_EDGE('',*,*,#189480,.T.); +#189480 = EDGE_CURVE('',#185630,#189481,#189483,.T.); +#189481 = VERTEX_POINT('',#189482); +#189482 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#189483 = SURFACE_CURVE('',#189484,(#189488,#189495),.PCURVE_S1.); +#189484 = LINE('',#189485,#189486); +#189485 = CARTESIAN_POINT('',(-1.287659054385,0.371136529841,1.E-001)); +#189486 = VECTOR('',#189487,1.); +#189487 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#189488 = PCURVE('',#185405,#189489); +#189489 = DEFINITIONAL_REPRESENTATION('',(#189490),#189494); +#189490 = LINE('',#189491,#189492); +#189491 = CARTESIAN_POINT('',(-2.747659054385,1.021136529841)); +#189492 = VECTOR('',#189493,1.); +#189493 = DIRECTION('',(-1.668003342285E-016,1.)); +#189494 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189495 = PCURVE('',#185888,#189496); +#189496 = DEFINITIONAL_REPRESENTATION('',(#189497),#189523); +#189497 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189498,#189499,#189500, + #189501,#189502,#189503,#189504,#189505,#189506,#189507,#189508, + #189509,#189510,#189511,#189512,#189513,#189514,#189515,#189516, + #189517,#189518,#189519,#189520,#189521,#189522),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.752203001598, -0.717560595074,-0.682918188551,-0.648275782028,-0.613633375504, -0.578990968981,-0.544348562458,-0.509706155934,-0.475063749411, @@ -232314,66 +235316,66 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.163282090701,-0.128639684178,-9.399727765447E-002, -5.935487113115E-002,-2.471246460782E-002,9.929941915506E-003), .UNSPECIFIED.); -#187106 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); -#187107 = CARTESIAN_POINT('',(4.712388980385,-1.019519002915)); -#187108 = CARTESIAN_POINT('',(4.712388980385,-0.996424065233)); -#187109 = CARTESIAN_POINT('',(4.712388980385,-0.96178165871)); -#187110 = CARTESIAN_POINT('',(4.712388980385,-0.927139252187)); -#187111 = CARTESIAN_POINT('',(4.712388980385,-0.892496845663)); -#187112 = CARTESIAN_POINT('',(4.712388980385,-0.85785443914)); -#187113 = CARTESIAN_POINT('',(4.712388980385,-0.823212032617)); -#187114 = CARTESIAN_POINT('',(4.712388980385,-0.788569626093)); -#187115 = CARTESIAN_POINT('',(4.712388980385,-0.75392721957)); -#187116 = CARTESIAN_POINT('',(4.712388980385,-0.719284813047)); -#187117 = CARTESIAN_POINT('',(4.712388980385,-0.684642406523)); -#187118 = CARTESIAN_POINT('',(4.712388980385,-0.65)); -#187119 = CARTESIAN_POINT('',(4.712388980385,-0.615357593477)); -#187120 = CARTESIAN_POINT('',(4.712388980385,-0.580715186953)); -#187121 = CARTESIAN_POINT('',(4.712388980385,-0.54607278043)); -#187122 = CARTESIAN_POINT('',(4.712388980385,-0.511430373907)); -#187123 = CARTESIAN_POINT('',(4.712388980385,-0.476787967383)); -#187124 = CARTESIAN_POINT('',(4.712388980385,-0.44214556086)); -#187125 = CARTESIAN_POINT('',(4.712388980385,-0.407503154337)); -#187126 = CARTESIAN_POINT('',(4.712388980385,-0.372860747813)); -#187127 = CARTESIAN_POINT('',(4.712388980385,-0.33821834129)); -#187128 = CARTESIAN_POINT('',(4.712388980385,-0.303575934767)); -#187129 = CARTESIAN_POINT('',(4.712388980385,-0.280480997085)); -#187130 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#187131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187132 = ORIENTED_EDGE('',*,*,#187133,.T.); -#187133 = EDGE_CURVE('',#187089,#183786,#187134,.T.); -#187134 = SURFACE_CURVE('',#187135,(#187140,#187148),.PCURVE_S1.); -#187135 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187136,#187137,#187138, -#187139),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189498 = CARTESIAN_POINT('',(4.712388980385,-1.031066471757)); +#189499 = CARTESIAN_POINT('',(4.712388980385,-1.019519002915)); +#189500 = CARTESIAN_POINT('',(4.712388980385,-0.996424065233)); +#189501 = CARTESIAN_POINT('',(4.712388980385,-0.96178165871)); +#189502 = CARTESIAN_POINT('',(4.712388980385,-0.927139252187)); +#189503 = CARTESIAN_POINT('',(4.712388980385,-0.892496845663)); +#189504 = CARTESIAN_POINT('',(4.712388980385,-0.85785443914)); +#189505 = CARTESIAN_POINT('',(4.712388980385,-0.823212032617)); +#189506 = CARTESIAN_POINT('',(4.712388980385,-0.788569626093)); +#189507 = CARTESIAN_POINT('',(4.712388980385,-0.75392721957)); +#189508 = CARTESIAN_POINT('',(4.712388980385,-0.719284813047)); +#189509 = CARTESIAN_POINT('',(4.712388980385,-0.684642406523)); +#189510 = CARTESIAN_POINT('',(4.712388980385,-0.65)); +#189511 = CARTESIAN_POINT('',(4.712388980385,-0.615357593477)); +#189512 = CARTESIAN_POINT('',(4.712388980385,-0.580715186953)); +#189513 = CARTESIAN_POINT('',(4.712388980385,-0.54607278043)); +#189514 = CARTESIAN_POINT('',(4.712388980385,-0.511430373907)); +#189515 = CARTESIAN_POINT('',(4.712388980385,-0.476787967383)); +#189516 = CARTESIAN_POINT('',(4.712388980385,-0.44214556086)); +#189517 = CARTESIAN_POINT('',(4.712388980385,-0.407503154337)); +#189518 = CARTESIAN_POINT('',(4.712388980385,-0.372860747813)); +#189519 = CARTESIAN_POINT('',(4.712388980385,-0.33821834129)); +#189520 = CARTESIAN_POINT('',(4.712388980385,-0.303575934767)); +#189521 = CARTESIAN_POINT('',(4.712388980385,-0.280480997085)); +#189522 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#189523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189524 = ORIENTED_EDGE('',*,*,#189525,.T.); +#189525 = EDGE_CURVE('',#189481,#186178,#189526,.T.); +#189526 = SURFACE_CURVE('',#189527,(#189532,#189540),.PCURVE_S1.); +#189527 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189528,#189529,#189530, +#189531),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187136 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); -#187137 = CARTESIAN_POINT('',(-1.287659054385,0.407584046027,1.E-001)); -#187138 = CARTESIAN_POINT('',(-1.27790129499,0.431596067115,1.E-001)); -#187139 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); -#187140 = PCURVE('',#183013,#187141); -#187141 = DEFINITIONAL_REPRESENTATION('',(#187142),#187147); -#187142 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187143,#187144,#187145, -#187146),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189528 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,1.E-001)); +#189529 = CARTESIAN_POINT('',(-1.287659054385,0.407584046027,1.E-001)); +#189530 = CARTESIAN_POINT('',(-1.27790129499,0.431596067115,1.E-001)); +#189531 = CARTESIAN_POINT('',(-1.259748681053,0.449748681053,1.E-001)); +#189532 = PCURVE('',#185405,#189533); +#189533 = DEFINITIONAL_REPRESENTATION('',(#189534),#189539); +#189534 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189535,#189536,#189537, +#189538),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187143 = CARTESIAN_POINT('',(-2.747659054385,1.031066471757)); -#187144 = CARTESIAN_POINT('',(-2.747659054385,1.057584046027)); -#187145 = CARTESIAN_POINT('',(-2.73790129499,1.081596067115)); -#187146 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); -#187147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187148 = PCURVE('',#183890,#187149); -#187149 = DEFINITIONAL_REPRESENTATION('',(#187150),#187176); -#187150 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187151,#187152,#187153, - #187154,#187155,#187156,#187157,#187158,#187159,#187160,#187161, - #187162,#187163,#187164,#187165,#187166,#187167,#187168,#187169, - #187170,#187171,#187172,#187173,#187174,#187175),.UNSPECIFIED.,.F., +#189535 = CARTESIAN_POINT('',(-2.747659054385,1.031066471757)); +#189536 = CARTESIAN_POINT('',(-2.747659054385,1.057584046027)); +#189537 = CARTESIAN_POINT('',(-2.73790129499,1.081596067115)); +#189538 = CARTESIAN_POINT('',(-2.719748681053,1.099748681053)); +#189539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189540 = PCURVE('',#186282,#189541); +#189541 = DEFINITIONAL_REPRESENTATION('',(#189542),#189568); +#189542 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189543,#189544,#189545, + #189546,#189547,#189548,#189549,#189550,#189551,#189552,#189553, + #189554,#189555,#189556,#189557,#189558,#189559,#189560,#189561, + #189562,#189563,#189564,#189565,#189566,#189567),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -232381,95 +235383,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#187151 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#187152 = CARTESIAN_POINT('',(0.740753697746,-2.901324291685E-008)); -#187153 = CARTESIAN_POINT('',(0.718425611961,2.616756246933E-005)); -#187154 = CARTESIAN_POINT('',(0.684727524261,1.282673134849E-004)); -#187155 = CARTESIAN_POINT('',(0.650847765387,2.772530388796E-004)); -#187156 = CARTESIAN_POINT('',(0.616809612353,4.570658043087E-004)); -#187157 = CARTESIAN_POINT('',(0.582635599926,6.52095293185E-004)); -#187158 = CARTESIAN_POINT('',(0.548347414424,8.475624467394E-004)); -#187159 = CARTESIAN_POINT('',(0.513965932674,1.029943289555E-003)); -#187160 = CARTESIAN_POINT('',(0.479511265006,1.187353930376E-003)); -#187161 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); -#187162 = CARTESIAN_POINT('',(0.41045949854,1.390009812356E-003)); -#187163 = CARTESIAN_POINT('',(0.375899653916,1.422641316499E-003)); -#187164 = CARTESIAN_POINT('',(0.341341416362,1.405524714319E-003)); -#187165 = CARTESIAN_POINT('',(0.306802773621,1.33926347789E-003)); -#187166 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); -#187167 = CARTESIAN_POINT('',(0.237856655052,1.076339413999E-003)); -#187168 = CARTESIAN_POINT('',(0.203486118557,8.953387637356E-004)); -#187169 = CARTESIAN_POINT('',(0.169209394064,6.962198987701E-004)); -#187170 = CARTESIAN_POINT('',(0.135046437107,4.931498468579E-004)); -#187171 = CARTESIAN_POINT('',(0.101018031154,3.022859269955E-004)); -#187172 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577615E-004)); -#187173 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401014E-005)); -#187174 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318532432E-008)); -#187175 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#187176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187177 = ORIENTED_EDGE('',*,*,#183785,.T.); -#187178 = ORIENTED_EDGE('',*,*,#187179,.T.); -#187179 = EDGE_CURVE('',#183788,#187180,#187182,.T.); -#187180 = VERTEX_POINT('',#187181); -#187181 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#187182 = SURFACE_CURVE('',#187183,(#187187,#187194),.PCURVE_S1.); -#187183 = LINE('',#187184,#187185); -#187184 = CARTESIAN_POINT('',(1.181136529841,0.477659054385,1.E-001)); -#187185 = VECTOR('',#187186,1.); -#187186 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187187 = PCURVE('',#183013,#187188); -#187188 = DEFINITIONAL_REPRESENTATION('',(#187189),#187193); -#187189 = LINE('',#187190,#187191); -#187190 = CARTESIAN_POINT('',(-0.278863470159,1.127659054385)); -#187191 = VECTOR('',#187192,1.); -#187192 = DIRECTION('',(1.,0.E+000)); -#187193 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187194 = PCURVE('',#184046,#187195); -#187195 = DEFINITIONAL_REPRESENTATION('',(#187196),#187199); -#187196 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187197,#187198), +#189543 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#189544 = CARTESIAN_POINT('',(0.740753697746,-2.901324291685E-008)); +#189545 = CARTESIAN_POINT('',(0.718425611961,2.616756246933E-005)); +#189546 = CARTESIAN_POINT('',(0.684727524261,1.282673134849E-004)); +#189547 = CARTESIAN_POINT('',(0.650847765387,2.772530388796E-004)); +#189548 = CARTESIAN_POINT('',(0.616809612353,4.570658043087E-004)); +#189549 = CARTESIAN_POINT('',(0.582635599926,6.52095293185E-004)); +#189550 = CARTESIAN_POINT('',(0.548347414424,8.475624467394E-004)); +#189551 = CARTESIAN_POINT('',(0.513965932674,1.029943289555E-003)); +#189552 = CARTESIAN_POINT('',(0.479511265006,1.187353930376E-003)); +#189553 = CARTESIAN_POINT('',(0.445002837244,1.309904867203E-003)); +#189554 = CARTESIAN_POINT('',(0.41045949854,1.390009812356E-003)); +#189555 = CARTESIAN_POINT('',(0.375899653916,1.422641316499E-003)); +#189556 = CARTESIAN_POINT('',(0.341341416362,1.405524714319E-003)); +#189557 = CARTESIAN_POINT('',(0.306802773621,1.33926347789E-003)); +#189558 = CARTESIAN_POINT('',(0.272301764008,1.22739025448E-003)); +#189559 = CARTESIAN_POINT('',(0.237856655052,1.076339413999E-003)); +#189560 = CARTESIAN_POINT('',(0.203486118557,8.953387637356E-004)); +#189561 = CARTESIAN_POINT('',(0.169209394064,6.962198987701E-004)); +#189562 = CARTESIAN_POINT('',(0.135046437107,4.931498468579E-004)); +#189563 = CARTESIAN_POINT('',(0.101018031154,3.022859269955E-004)); +#189564 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577615E-004)); +#189565 = CARTESIAN_POINT('',(3.345267504997E-002,2.92413401014E-005)); +#189566 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318532432E-008)); +#189567 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#189568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189569 = ORIENTED_EDGE('',*,*,#186177,.T.); +#189570 = ORIENTED_EDGE('',*,*,#189571,.T.); +#189571 = EDGE_CURVE('',#186180,#189572,#189574,.T.); +#189572 = VERTEX_POINT('',#189573); +#189573 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#189574 = SURFACE_CURVE('',#189575,(#189579,#189586),.PCURVE_S1.); +#189575 = LINE('',#189576,#189577); +#189576 = CARTESIAN_POINT('',(1.181136529841,0.477659054385,1.E-001)); +#189577 = VECTOR('',#189578,1.); +#189578 = DIRECTION('',(1.,0.E+000,0.E+000)); +#189579 = PCURVE('',#185405,#189580); +#189580 = DEFINITIONAL_REPRESENTATION('',(#189581),#189585); +#189581 = LINE('',#189582,#189583); +#189582 = CARTESIAN_POINT('',(-0.278863470159,1.127659054385)); +#189583 = VECTOR('',#189584,1.); +#189584 = DIRECTION('',(1.,0.E+000)); +#189585 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189586 = PCURVE('',#186438,#189587); +#189587 = DEFINITIONAL_REPRESENTATION('',(#189588),#189591); +#189588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189589,#189590), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.372203001598,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#187197 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); -#187198 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); -#187199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189589 = CARTESIAN_POINT('',(0.E+000,0.268933528243)); +#189590 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); +#189591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187200 = ORIENTED_EDGE('',*,*,#187201,.T.); -#187201 = EDGE_CURVE('',#187180,#183511,#187202,.T.); -#187202 = SURFACE_CURVE('',#187203,(#187208,#187216),.PCURVE_S1.); -#187203 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187204,#187205,#187206, -#187207),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189592 = ORIENTED_EDGE('',*,*,#189593,.T.); +#189593 = EDGE_CURVE('',#189572,#185903,#189594,.T.); +#189594 = SURFACE_CURVE('',#189595,(#189600,#189608),.PCURVE_S1.); +#189595 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189596,#189597,#189598, +#189599),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187204 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); -#187205 = CARTESIAN_POINT('',(1.217584046027,0.477659054385,1.E-001)); -#187206 = CARTESIAN_POINT('',(1.241596067115,0.46790129499,1.E-001)); -#187207 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); -#187208 = PCURVE('',#183013,#187209); -#187209 = DEFINITIONAL_REPRESENTATION('',(#187210),#187215); -#187210 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187211,#187212,#187213, -#187214),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189596 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,1.E-001)); +#189597 = CARTESIAN_POINT('',(1.217584046027,0.477659054385,1.E-001)); +#189598 = CARTESIAN_POINT('',(1.241596067115,0.46790129499,1.E-001)); +#189599 = CARTESIAN_POINT('',(1.259748681053,0.449748681053,1.E-001)); +#189600 = PCURVE('',#185405,#189601); +#189601 = DEFINITIONAL_REPRESENTATION('',(#189602),#189607); +#189602 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189603,#189604,#189605, +#189606),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187211 = CARTESIAN_POINT('',(-0.268933528243,1.127659054385)); -#187212 = CARTESIAN_POINT('',(-0.242415953973,1.127659054385)); -#187213 = CARTESIAN_POINT('',(-0.218403932885,1.11790129499)); -#187214 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); -#187215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187216 = PCURVE('',#183615,#187217); -#187217 = DEFINITIONAL_REPRESENTATION('',(#187218),#187244); -#187218 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187219,#187220,#187221, - #187222,#187223,#187224,#187225,#187226,#187227,#187228,#187229, - #187230,#187231,#187232,#187233,#187234,#187235,#187236,#187237, - #187238,#187239,#187240,#187241,#187242,#187243),.UNSPECIFIED.,.F., +#189603 = CARTESIAN_POINT('',(-0.268933528243,1.127659054385)); +#189604 = CARTESIAN_POINT('',(-0.242415953973,1.127659054385)); +#189605 = CARTESIAN_POINT('',(-0.218403932885,1.11790129499)); +#189606 = CARTESIAN_POINT('',(-0.200251318947,1.099748681053)); +#189607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189608 = PCURVE('',#186007,#189609); +#189609 = DEFINITIONAL_REPRESENTATION('',(#189610),#189636); +#189610 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189611,#189612,#189613, + #189614,#189615,#189616,#189617,#189618,#189619,#189620,#189621, + #189622,#189623,#189624,#189625,#189626,#189627,#189628,#189629, + #189630,#189631,#189632,#189633,#189634,#189635),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -232477,62 +235479,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#187219 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#187220 = CARTESIAN_POINT('',(0.740753697746,-2.901324288341E-008)); -#187221 = CARTESIAN_POINT('',(0.718425611961,2.616756246965E-005)); -#187222 = CARTESIAN_POINT('',(0.684727524261,1.282673134864E-004)); -#187223 = CARTESIAN_POINT('',(0.650847765387,2.772530388755E-004)); -#187224 = CARTESIAN_POINT('',(0.616809612353,4.570658043114E-004)); -#187225 = CARTESIAN_POINT('',(0.582635599926,6.520952931831E-004)); -#187226 = CARTESIAN_POINT('',(0.548347414424,8.475624467404E-004)); -#187227 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); -#187228 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); -#187229 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); -#187230 = CARTESIAN_POINT('',(0.41045949854,1.390009812357E-003)); -#187231 = CARTESIAN_POINT('',(0.375899653916,1.422641316493E-003)); -#187232 = CARTESIAN_POINT('',(0.341341416362,1.405524714323E-003)); -#187233 = CARTESIAN_POINT('',(0.306802773621,1.339263477877E-003)); -#187234 = CARTESIAN_POINT('',(0.272301764008,1.227390254469E-003)); -#187235 = CARTESIAN_POINT('',(0.237856655052,1.076339414E-003)); -#187236 = CARTESIAN_POINT('',(0.203486118557,8.95338763721E-004)); -#187237 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); -#187238 = CARTESIAN_POINT('',(0.135046437107,4.931498468535E-004)); -#187239 = CARTESIAN_POINT('',(0.101018031154,3.022859269914E-004)); -#187240 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577579E-004)); -#187241 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009729E-005)); -#187242 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318323614E-008)); -#187243 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#187244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187245 = ORIENTED_EDGE('',*,*,#183510,.T.); -#187246 = ADVANCED_FACE('',(#187247),#186405,.T.); -#187247 = FACE_BOUND('',#187248,.T.); -#187248 = EDGE_LOOP('',(#187249,#187292,#187337,#187357)); -#187249 = ORIENTED_EDGE('',*,*,#187250,.T.); -#187250 = EDGE_CURVE('',#186347,#184916,#187251,.T.); -#187251 = SURFACE_CURVE('',#187252,(#187256,#187263),.PCURVE_S1.); -#187252 = LINE('',#187253,#187254); -#187253 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, +#189611 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#189612 = CARTESIAN_POINT('',(0.740753697746,-2.901324288341E-008)); +#189613 = CARTESIAN_POINT('',(0.718425611961,2.616756246965E-005)); +#189614 = CARTESIAN_POINT('',(0.684727524261,1.282673134864E-004)); +#189615 = CARTESIAN_POINT('',(0.650847765387,2.772530388755E-004)); +#189616 = CARTESIAN_POINT('',(0.616809612353,4.570658043114E-004)); +#189617 = CARTESIAN_POINT('',(0.582635599926,6.520952931831E-004)); +#189618 = CARTESIAN_POINT('',(0.548347414424,8.475624467404E-004)); +#189619 = CARTESIAN_POINT('',(0.513965932674,1.029943289549E-003)); +#189620 = CARTESIAN_POINT('',(0.479511265006,1.187353930377E-003)); +#189621 = CARTESIAN_POINT('',(0.445002837244,1.309904867189E-003)); +#189622 = CARTESIAN_POINT('',(0.41045949854,1.390009812357E-003)); +#189623 = CARTESIAN_POINT('',(0.375899653916,1.422641316493E-003)); +#189624 = CARTESIAN_POINT('',(0.341341416362,1.405524714323E-003)); +#189625 = CARTESIAN_POINT('',(0.306802773621,1.339263477877E-003)); +#189626 = CARTESIAN_POINT('',(0.272301764008,1.227390254469E-003)); +#189627 = CARTESIAN_POINT('',(0.237856655052,1.076339414E-003)); +#189628 = CARTESIAN_POINT('',(0.203486118557,8.95338763721E-004)); +#189629 = CARTESIAN_POINT('',(0.169209394064,6.96219898765E-004)); +#189630 = CARTESIAN_POINT('',(0.135046437107,4.931498468535E-004)); +#189631 = CARTESIAN_POINT('',(0.101018031154,3.022859269914E-004)); +#189632 = CARTESIAN_POINT('',(6.714590753944E-002,1.413707577579E-004)); +#189633 = CARTESIAN_POINT('',(3.345267504997E-002,2.924134009729E-005)); +#189634 = CARTESIAN_POINT('',(1.112573796452E-002,1.375318323614E-008)); +#189635 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#189636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189637 = ORIENTED_EDGE('',*,*,#185902,.T.); +#189638 = ADVANCED_FACE('',(#189639),#188797,.T.); +#189639 = FACE_BOUND('',#189640,.T.); +#189640 = EDGE_LOOP('',(#189641,#189684,#189729,#189749)); +#189641 = ORIENTED_EDGE('',*,*,#189642,.T.); +#189642 = EDGE_CURVE('',#188739,#187308,#189643,.T.); +#189643 = SURFACE_CURVE('',#189644,(#189648,#189655),.PCURVE_S1.); +#189644 = LINE('',#189645,#189646); +#189645 = CARTESIAN_POINT('',(1.469096372758,0.514207498814, 0.566051874704)); -#187254 = VECTOR('',#187255,1.); -#187255 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) - ); -#187256 = PCURVE('',#186405,#187257); -#187257 = DEFINITIONAL_REPRESENTATION('',(#187258),#187262); -#187258 = LINE('',#187259,#187260); -#187259 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); -#187260 = VECTOR('',#187261,1.); -#187261 = DIRECTION('',(-0.968100345886,-0.250562807086)); -#187262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187263 = PCURVE('',#184971,#187264); -#187264 = DEFINITIONAL_REPRESENTATION('',(#187265),#187291); -#187265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187266,#187267,#187268, - #187269,#187270,#187271,#187272,#187273,#187274,#187275,#187276, - #187277,#187278,#187279,#187280,#187281,#187282,#187283,#187284, - #187285,#187286,#187287,#187288,#187289,#187290),.UNSPECIFIED.,.F., +#189646 = VECTOR('',#189647,1.); +#189647 = DIRECTION('',(-0.250562807086,-0.250562807086,0.935113126531) + ); +#189648 = PCURVE('',#188797,#189649); +#189649 = DEFINITIONAL_REPRESENTATION('',(#189650),#189654); +#189650 = LINE('',#189651,#189652); +#189651 = CARTESIAN_POINT('',(3.514568548895E-002,-0.135792501186)); +#189652 = VECTOR('',#189653,1.); +#189653 = DIRECTION('',(-0.968100345886,-0.250562807086)); +#189654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189655 = PCURVE('',#187363,#189656); +#189656 = DEFINITIONAL_REPRESENTATION('',(#189657),#189683); +#189657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189658,#189659,#189660, + #189661,#189662,#189663,#189664,#189665,#189666,#189667,#189668, + #189669,#189670,#189671,#189672,#189673,#189674,#189675,#189676, + #189677,#189678,#189679,#189680,#189681,#189682),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.630376297074E-002,5.394581668973E-002,7.158787040873E-002, 8.922992412772E-002,0.106871977847,0.124514031566,0.142156085285, @@ -232541,60 +235543,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.300934568756,0.318576622475,0.336218676194,0.353860729913, 0.371502783632,0.389144837351,0.40678689107,0.424428944789), .QUASI_UNIFORM_KNOTS.); -#187266 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); -#187267 = CARTESIAN_POINT('',(3.14159265359,0.689458949147)); -#187268 = CARTESIAN_POINT('',(3.14159265359,0.677697580001)); -#187269 = CARTESIAN_POINT('',(3.14159265359,0.660055526282)); -#187270 = CARTESIAN_POINT('',(3.14159265359,0.642413472563)); -#187271 = CARTESIAN_POINT('',(3.14159265359,0.624771418844)); -#187272 = CARTESIAN_POINT('',(3.14159265359,0.607129365125)); -#187273 = CARTESIAN_POINT('',(3.14159265359,0.589487311406)); -#187274 = CARTESIAN_POINT('',(3.14159265359,0.571845257687)); -#187275 = CARTESIAN_POINT('',(3.14159265359,0.554203203968)); -#187276 = CARTESIAN_POINT('',(3.14159265359,0.536561150249)); -#187277 = CARTESIAN_POINT('',(3.14159265359,0.51891909653)); -#187278 = CARTESIAN_POINT('',(3.14159265359,0.501277042811)); -#187279 = CARTESIAN_POINT('',(3.14159265359,0.483634989092)); -#187280 = CARTESIAN_POINT('',(3.14159265359,0.465992935373)); -#187281 = CARTESIAN_POINT('',(3.14159265359,0.448350881654)); -#187282 = CARTESIAN_POINT('',(3.14159265359,0.430708827935)); -#187283 = CARTESIAN_POINT('',(3.14159265359,0.413066774216)); -#187284 = CARTESIAN_POINT('',(3.14159265359,0.395424720497)); -#187285 = CARTESIAN_POINT('',(3.14159265359,0.377782666778)); -#187286 = CARTESIAN_POINT('',(3.14159265359,0.360140613059)); -#187287 = CARTESIAN_POINT('',(3.14159265359,0.34249855934)); -#187288 = CARTESIAN_POINT('',(3.14159265359,0.324856505621)); -#187289 = CARTESIAN_POINT('',(3.14159265359,0.313095136475)); -#187290 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); -#187291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187292 = ORIENTED_EDGE('',*,*,#187293,.T.); -#187293 = EDGE_CURVE('',#184916,#187294,#187296,.T.); -#187294 = VERTEX_POINT('',#187295); -#187295 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 +#189658 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); +#189659 = CARTESIAN_POINT('',(3.14159265359,0.689458949147)); +#189660 = CARTESIAN_POINT('',(3.14159265359,0.677697580001)); +#189661 = CARTESIAN_POINT('',(3.14159265359,0.660055526282)); +#189662 = CARTESIAN_POINT('',(3.14159265359,0.642413472563)); +#189663 = CARTESIAN_POINT('',(3.14159265359,0.624771418844)); +#189664 = CARTESIAN_POINT('',(3.14159265359,0.607129365125)); +#189665 = CARTESIAN_POINT('',(3.14159265359,0.589487311406)); +#189666 = CARTESIAN_POINT('',(3.14159265359,0.571845257687)); +#189667 = CARTESIAN_POINT('',(3.14159265359,0.554203203968)); +#189668 = CARTESIAN_POINT('',(3.14159265359,0.536561150249)); +#189669 = CARTESIAN_POINT('',(3.14159265359,0.51891909653)); +#189670 = CARTESIAN_POINT('',(3.14159265359,0.501277042811)); +#189671 = CARTESIAN_POINT('',(3.14159265359,0.483634989092)); +#189672 = CARTESIAN_POINT('',(3.14159265359,0.465992935373)); +#189673 = CARTESIAN_POINT('',(3.14159265359,0.448350881654)); +#189674 = CARTESIAN_POINT('',(3.14159265359,0.430708827935)); +#189675 = CARTESIAN_POINT('',(3.14159265359,0.413066774216)); +#189676 = CARTESIAN_POINT('',(3.14159265359,0.395424720497)); +#189677 = CARTESIAN_POINT('',(3.14159265359,0.377782666778)); +#189678 = CARTESIAN_POINT('',(3.14159265359,0.360140613059)); +#189679 = CARTESIAN_POINT('',(3.14159265359,0.34249855934)); +#189680 = CARTESIAN_POINT('',(3.14159265359,0.324856505621)); +#189681 = CARTESIAN_POINT('',(3.14159265359,0.313095136475)); +#189682 = CARTESIAN_POINT('',(3.14159265359,0.307214451902)); +#189683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189684 = ORIENTED_EDGE('',*,*,#189685,.T.); +#189685 = EDGE_CURVE('',#187308,#189686,#189688,.T.); +#189686 = VERTEX_POINT('',#189687); +#189687 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 )); -#187296 = SURFACE_CURVE('',#187297,(#187301,#187308),.PCURVE_S1.); -#187297 = LINE('',#187298,#187299); -#187298 = CARTESIAN_POINT('',(1.362750264943,-0.397931449084, +#189688 = SURFACE_CURVE('',#189689,(#189693,#189700),.PCURVE_S1.); +#189689 = LINE('',#189690,#189691); +#189690 = CARTESIAN_POINT('',(1.362750264943,-0.397931449084, 0.962940952255)); -#187299 = VECTOR('',#187300,1.); -#187300 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); -#187301 = PCURVE('',#186405,#187302); -#187302 = DEFINITIONAL_REPRESENTATION('',(#187303),#187307); -#187303 = LINE('',#187304,#187305); -#187304 = CARTESIAN_POINT('',(-0.375744122765,-1.047931449084)); -#187305 = VECTOR('',#187306,1.); -#187306 = DIRECTION('',(4.317110322781E-017,-1.)); -#187307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187308 = PCURVE('',#185174,#187309); -#187309 = DEFINITIONAL_REPRESENTATION('',(#187310),#187336); -#187310 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187311,#187312,#187313, - #187314,#187315,#187316,#187317,#187318,#187319,#187320,#187321, - #187322,#187323,#187324,#187325,#187326,#187327,#187328,#187329, - #187330,#187331,#187332,#187333,#187334,#187335),.UNSPECIFIED.,.F., +#189691 = VECTOR('',#189692,1.); +#189692 = DIRECTION('',(1.668003342285E-016,-1.,-5.939389622868E-033)); +#189693 = PCURVE('',#188797,#189694); +#189694 = DEFINITIONAL_REPRESENTATION('',(#189695),#189699); +#189695 = LINE('',#189696,#189697); +#189696 = CARTESIAN_POINT('',(-0.375744122765,-1.047931449084)); +#189697 = VECTOR('',#189698,1.); +#189698 = DIRECTION('',(4.317110322781E-017,-1.)); +#189699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189700 = PCURVE('',#187566,#189701); +#189701 = DEFINITIONAL_REPRESENTATION('',(#189702),#189728); +#189702 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189703,#189704,#189705, + #189706,#189707,#189708,#189709,#189710,#189711,#189712,#189713, + #189714,#189715,#189716,#189717,#189718,#189719,#189720,#189721, + #189722,#189723,#189724,#189725,#189726,#189727),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084, -0.768714531811,-0.731636223538,-0.694557915266,-0.657479606993, -0.62040129872,-0.583322990448,-0.546244682175,-0.509166373902, @@ -232602,89 +235604,89 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.323774832539,-0.286696524266,-0.249618215993,-0.212539907721, -0.175461599448,-0.138383291175,-0.101304982903,-6.422667462989E-002 ,-2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#187311 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); -#187312 = CARTESIAN_POINT('',(2.879793265791,1.045501954909)); -#187313 = CARTESIAN_POINT('',(2.879793265791,1.020783082727)); -#187314 = CARTESIAN_POINT('',(2.879793265791,0.983704774454)); -#187315 = CARTESIAN_POINT('',(2.879793265791,0.946626466182)); -#187316 = CARTESIAN_POINT('',(2.879793265791,0.909548157909)); -#187317 = CARTESIAN_POINT('',(2.879793265791,0.872469849636)); -#187318 = CARTESIAN_POINT('',(2.879793265791,0.835391541363)); -#187319 = CARTESIAN_POINT('',(2.879793265791,0.798313233091)); -#187320 = CARTESIAN_POINT('',(2.879793265791,0.761234924818)); -#187321 = CARTESIAN_POINT('',(2.879793265791,0.724156616545)); -#187322 = CARTESIAN_POINT('',(2.879793265791,0.687078308273)); -#187323 = CARTESIAN_POINT('',(2.879793265791,0.65)); -#187324 = CARTESIAN_POINT('',(2.879793265791,0.612921691727)); -#187325 = CARTESIAN_POINT('',(2.879793265791,0.575843383455)); -#187326 = CARTESIAN_POINT('',(2.879793265791,0.538765075182)); -#187327 = CARTESIAN_POINT('',(2.879793265791,0.501686766909)); -#187328 = CARTESIAN_POINT('',(2.879793265791,0.464608458637)); -#187329 = CARTESIAN_POINT('',(2.879793265791,0.427530150364)); -#187330 = CARTESIAN_POINT('',(2.879793265791,0.390451842091)); -#187331 = CARTESIAN_POINT('',(2.879793265791,0.353373533818)); -#187332 = CARTESIAN_POINT('',(2.879793265791,0.316295225546)); -#187333 = CARTESIAN_POINT('',(2.879793265791,0.279216917273)); -#187334 = CARTESIAN_POINT('',(2.879793265791,0.254498045091)); -#187335 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); -#187336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187337 = ORIENTED_EDGE('',*,*,#187338,.T.); -#187338 = EDGE_CURVE('',#187294,#186252,#187339,.T.); -#187339 = SURFACE_CURVE('',#187340,(#187344,#187351),.PCURVE_S1.); -#187340 = LINE('',#187341,#187342); -#187341 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, +#189703 = CARTESIAN_POINT('',(2.879793265791,1.057861391)); +#189704 = CARTESIAN_POINT('',(2.879793265791,1.045501954909)); +#189705 = CARTESIAN_POINT('',(2.879793265791,1.020783082727)); +#189706 = CARTESIAN_POINT('',(2.879793265791,0.983704774454)); +#189707 = CARTESIAN_POINT('',(2.879793265791,0.946626466182)); +#189708 = CARTESIAN_POINT('',(2.879793265791,0.909548157909)); +#189709 = CARTESIAN_POINT('',(2.879793265791,0.872469849636)); +#189710 = CARTESIAN_POINT('',(2.879793265791,0.835391541363)); +#189711 = CARTESIAN_POINT('',(2.879793265791,0.798313233091)); +#189712 = CARTESIAN_POINT('',(2.879793265791,0.761234924818)); +#189713 = CARTESIAN_POINT('',(2.879793265791,0.724156616545)); +#189714 = CARTESIAN_POINT('',(2.879793265791,0.687078308273)); +#189715 = CARTESIAN_POINT('',(2.879793265791,0.65)); +#189716 = CARTESIAN_POINT('',(2.879793265791,0.612921691727)); +#189717 = CARTESIAN_POINT('',(2.879793265791,0.575843383455)); +#189718 = CARTESIAN_POINT('',(2.879793265791,0.538765075182)); +#189719 = CARTESIAN_POINT('',(2.879793265791,0.501686766909)); +#189720 = CARTESIAN_POINT('',(2.879793265791,0.464608458637)); +#189721 = CARTESIAN_POINT('',(2.879793265791,0.427530150364)); +#189722 = CARTESIAN_POINT('',(2.879793265791,0.390451842091)); +#189723 = CARTESIAN_POINT('',(2.879793265791,0.353373533818)); +#189724 = CARTESIAN_POINT('',(2.879793265791,0.316295225546)); +#189725 = CARTESIAN_POINT('',(2.879793265791,0.279216917273)); +#189726 = CARTESIAN_POINT('',(2.879793265791,0.254498045091)); +#189727 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); +#189728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189729 = ORIENTED_EDGE('',*,*,#189730,.T.); +#189730 = EDGE_CURVE('',#189686,#188644,#189731,.T.); +#189731 = SURFACE_CURVE('',#189732,(#189736,#189743),.PCURVE_S1.); +#189732 = LINE('',#189733,#189734); +#189733 = CARTESIAN_POINT('',(1.387480136375,-0.432591262431, 0.870647815608)); -#187342 = VECTOR('',#187343,1.); -#187343 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) +#189734 = VECTOR('',#189735,1.); +#189735 = DIRECTION('',(0.250562807086,-0.250562807086,-0.935113126531) ); -#187344 = PCURVE('',#186405,#187345); -#187345 = DEFINITIONAL_REPRESENTATION('',(#187346),#187350); -#187346 = LINE('',#187347,#187348); -#187347 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); -#187348 = VECTOR('',#187349,1.); -#187349 = DIRECTION('',(0.968100345886,-0.250562807086)); -#187350 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189736 = PCURVE('',#188797,#189737); +#189737 = DEFINITIONAL_REPRESENTATION('',(#189738),#189742); +#189738 = LINE('',#189739,#189740); +#189739 = CARTESIAN_POINT('',(-0.280195236779,-1.082591262431)); +#189740 = VECTOR('',#189741,1.); +#189741 = DIRECTION('',(0.968100345886,-0.250562807086)); +#189742 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187351 = PCURVE('',#184421,#187352); -#187352 = DEFINITIONAL_REPRESENTATION('',(#187353),#187356); -#187353 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187354,#187355), +#189743 = PCURVE('',#186813,#189744); +#189744 = DEFINITIONAL_REPRESENTATION('',(#189745),#189748); +#189745 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189746,#189747), .UNSPECIFIED.,.F.,.F.,(2,2),(-9.869729557715E-002,0.289427886241), .PIECEWISE_BEZIER_KNOTS.); -#187354 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); -#187355 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#187356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189746 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); +#189747 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#189748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187357 = ORIENTED_EDGE('',*,*,#186391,.T.); -#187358 = ADVANCED_FACE('',(#187359),#186744,.T.); -#187359 = FACE_BOUND('',#187360,.T.); -#187360 = EDGE_LOOP('',(#187361,#187404,#187449,#187492)); -#187361 = ORIENTED_EDGE('',*,*,#187362,.T.); -#187362 = EDGE_CURVE('',#186686,#184063,#187363,.T.); -#187363 = SURFACE_CURVE('',#187364,(#187368,#187375),.PCURVE_S1.); -#187364 = LINE('',#187365,#187366); -#187365 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, +#189749 = ORIENTED_EDGE('',*,*,#188783,.T.); +#189750 = ADVANCED_FACE('',(#189751),#189136,.T.); +#189751 = FACE_BOUND('',#189752,.T.); +#189752 = EDGE_LOOP('',(#189753,#189796,#189841,#189884)); +#189753 = ORIENTED_EDGE('',*,*,#189754,.T.); +#189754 = EDGE_CURVE('',#189078,#186455,#189755,.T.); +#189755 = SURFACE_CURVE('',#189756,(#189760,#189767),.PCURVE_S1.); +#189756 = LINE('',#189757,#189758); +#189757 = CARTESIAN_POINT('',(-1.387480136375,-0.432591262431, 0.870647815608)); -#187366 = VECTOR('',#187367,1.); -#187367 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); -#187368 = PCURVE('',#186744,#187369); -#187369 = DEFINITIONAL_REPRESENTATION('',(#187370),#187374); -#187370 = LINE('',#187371,#187372); -#187371 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); -#187372 = VECTOR('',#187373,1.); -#187373 = DIRECTION('',(0.968100345886,0.250562807086)); -#187374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187375 = PCURVE('',#184118,#187376); -#187376 = DEFINITIONAL_REPRESENTATION('',(#187377),#187403); -#187377 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187378,#187379,#187380, - #187381,#187382,#187383,#187384,#187385,#187386,#187387,#187388, - #187389,#187390,#187391,#187392,#187393,#187394,#187395,#187396, - #187397,#187398,#187399,#187400,#187401,#187402),.UNSPECIFIED.,.F., +#189758 = VECTOR('',#189759,1.); +#189759 = DIRECTION('',(0.250562807086,0.250562807086,0.935113126531)); +#189760 = PCURVE('',#189136,#189761); +#189761 = DEFINITIONAL_REPRESENTATION('',(#189762),#189766); +#189762 = LINE('',#189763,#189764); +#189763 = CARTESIAN_POINT('',(0.280195236779,-1.082591262431)); +#189764 = VECTOR('',#189765,1.); +#189765 = DIRECTION('',(0.968100345886,0.250562807086)); +#189766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189767 = PCURVE('',#186510,#189768); +#189768 = DEFINITIONAL_REPRESENTATION('',(#189769),#189795); +#189769 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189770,#189771,#189772, + #189773,#189774,#189775,#189776,#189777,#189778,#189779,#189780, + #189781,#189782,#189783,#189784,#189785,#189786,#189787,#189788, + #189789,#189790,#189791,#189792,#189793,#189794),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.289427886241, -0.271785832522,-0.254143778803,-0.236501725084,-0.218859671365, -0.201217617646,-0.183575563927,-0.165933510208,-0.148291456489, @@ -232693,60 +235695,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -2.479708045581E-002,-7.155026736812E-003,1.048702698218E-002, 2.812908070118E-002,4.577113442017E-002,6.341318813916E-002, 8.105524185816E-002,9.869729557715E-002),.UNSPECIFIED.); -#187378 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#187379 = CARTESIAN_POINT('',(6.28318530718,-4.218444754374E-002)); -#187380 = CARTESIAN_POINT('',(6.28318530718,-5.394581668973E-002)); -#187381 = CARTESIAN_POINT('',(6.28318530718,-7.158787040873E-002)); -#187382 = CARTESIAN_POINT('',(6.28318530718,-8.922992412772E-002)); -#187383 = CARTESIAN_POINT('',(6.28318530718,-0.106871977847)); -#187384 = CARTESIAN_POINT('',(6.28318530718,-0.124514031566)); -#187385 = CARTESIAN_POINT('',(6.28318530718,-0.142156085285)); -#187386 = CARTESIAN_POINT('',(6.28318530718,-0.159798139004)); -#187387 = CARTESIAN_POINT('',(6.28318530718,-0.177440192723)); -#187388 = CARTESIAN_POINT('',(6.28318530718,-0.195082246442)); -#187389 = CARTESIAN_POINT('',(6.28318530718,-0.212724300161)); -#187390 = CARTESIAN_POINT('',(6.28318530718,-0.23036635388)); -#187391 = CARTESIAN_POINT('',(6.28318530718,-0.248008407599)); -#187392 = CARTESIAN_POINT('',(6.28318530718,-0.265650461318)); -#187393 = CARTESIAN_POINT('',(6.28318530718,-0.283292515037)); -#187394 = CARTESIAN_POINT('',(6.28318530718,-0.300934568756)); -#187395 = CARTESIAN_POINT('',(6.28318530718,-0.318576622475)); -#187396 = CARTESIAN_POINT('',(6.28318530718,-0.336218676194)); -#187397 = CARTESIAN_POINT('',(6.28318530718,-0.353860729913)); -#187398 = CARTESIAN_POINT('',(6.28318530718,-0.371502783632)); -#187399 = CARTESIAN_POINT('',(6.28318530718,-0.389144837351)); -#187400 = CARTESIAN_POINT('',(6.28318530718,-0.40678689107)); -#187401 = CARTESIAN_POINT('',(6.28318530718,-0.418548260216)); -#187402 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); -#187403 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187404 = ORIENTED_EDGE('',*,*,#187405,.T.); -#187405 = EDGE_CURVE('',#184063,#187406,#187408,.T.); -#187406 = VERTEX_POINT('',#187407); -#187407 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 +#189770 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#189771 = CARTESIAN_POINT('',(6.28318530718,-4.218444754374E-002)); +#189772 = CARTESIAN_POINT('',(6.28318530718,-5.394581668973E-002)); +#189773 = CARTESIAN_POINT('',(6.28318530718,-7.158787040873E-002)); +#189774 = CARTESIAN_POINT('',(6.28318530718,-8.922992412772E-002)); +#189775 = CARTESIAN_POINT('',(6.28318530718,-0.106871977847)); +#189776 = CARTESIAN_POINT('',(6.28318530718,-0.124514031566)); +#189777 = CARTESIAN_POINT('',(6.28318530718,-0.142156085285)); +#189778 = CARTESIAN_POINT('',(6.28318530718,-0.159798139004)); +#189779 = CARTESIAN_POINT('',(6.28318530718,-0.177440192723)); +#189780 = CARTESIAN_POINT('',(6.28318530718,-0.195082246442)); +#189781 = CARTESIAN_POINT('',(6.28318530718,-0.212724300161)); +#189782 = CARTESIAN_POINT('',(6.28318530718,-0.23036635388)); +#189783 = CARTESIAN_POINT('',(6.28318530718,-0.248008407599)); +#189784 = CARTESIAN_POINT('',(6.28318530718,-0.265650461318)); +#189785 = CARTESIAN_POINT('',(6.28318530718,-0.283292515037)); +#189786 = CARTESIAN_POINT('',(6.28318530718,-0.300934568756)); +#189787 = CARTESIAN_POINT('',(6.28318530718,-0.318576622475)); +#189788 = CARTESIAN_POINT('',(6.28318530718,-0.336218676194)); +#189789 = CARTESIAN_POINT('',(6.28318530718,-0.353860729913)); +#189790 = CARTESIAN_POINT('',(6.28318530718,-0.371502783632)); +#189791 = CARTESIAN_POINT('',(6.28318530718,-0.389144837351)); +#189792 = CARTESIAN_POINT('',(6.28318530718,-0.40678689107)); +#189793 = CARTESIAN_POINT('',(6.28318530718,-0.418548260216)); +#189794 = CARTESIAN_POINT('',(6.28318530718,-0.424428944789)); +#189795 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189796 = ORIENTED_EDGE('',*,*,#189797,.T.); +#189797 = EDGE_CURVE('',#186455,#189798,#189800,.T.); +#189798 = VERTEX_POINT('',#189799); +#189799 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 )); -#187408 = SURFACE_CURVE('',#187409,(#187413,#187420),.PCURVE_S1.); -#187409 = LINE('',#187410,#187411); -#187410 = CARTESIAN_POINT('',(-1.362750264943,0.397931449084, +#189800 = SURFACE_CURVE('',#189801,(#189805,#189812),.PCURVE_S1.); +#189801 = LINE('',#189802,#189803); +#189802 = CARTESIAN_POINT('',(-1.362750264943,0.397931449084, 0.962940952255)); -#187411 = VECTOR('',#187412,1.); -#187412 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); -#187413 = PCURVE('',#186744,#187414); -#187414 = DEFINITIONAL_REPRESENTATION('',(#187415),#187419); -#187415 = LINE('',#187416,#187417); -#187416 = CARTESIAN_POINT('',(0.375744122765,-0.252068550916)); -#187417 = VECTOR('',#187418,1.); -#187418 = DIRECTION('',(-4.317110322781E-017,1.)); -#187419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187420 = PCURVE('',#184326,#187421); -#187421 = DEFINITIONAL_REPRESENTATION('',(#187422),#187448); -#187422 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187423,#187424,#187425, - #187426,#187427,#187428,#187429,#187430,#187431,#187432,#187433, - #187434,#187435,#187436,#187437,#187438,#187439,#187440,#187441, - #187442,#187443,#187444,#187445,#187446,#187447),.UNSPECIFIED.,.F., +#189803 = VECTOR('',#189804,1.); +#189804 = DIRECTION('',(-1.668003342285E-016,1.,-5.939389622868E-033)); +#189805 = PCURVE('',#189136,#189806); +#189806 = DEFINITIONAL_REPRESENTATION('',(#189807),#189811); +#189807 = LINE('',#189808,#189809); +#189808 = CARTESIAN_POINT('',(0.375744122765,-0.252068550916)); +#189809 = VECTOR('',#189810,1.); +#189810 = DIRECTION('',(-4.317110322781E-017,1.)); +#189811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189812 = PCURVE('',#186718,#189813); +#189813 = DEFINITIONAL_REPRESENTATION('',(#189814),#189840); +#189814 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189815,#189816,#189817, + #189818,#189819,#189820,#189821,#189822,#189823,#189824,#189825, + #189826,#189827,#189828,#189829,#189830,#189831,#189832,#189833, + #189834,#189835,#189836,#189837,#189838,#189839),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084, -0.768714531811,-0.731636223538,-0.694557915266,-0.657479606993, -0.62040129872,-0.583322990448,-0.546244682175,-0.509166373902, @@ -232754,58 +235756,58 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.323774832539,-0.286696524266,-0.249618215993,-0.212539907721, -0.175461599448,-0.138383291175,-0.101304982903,-6.422667462989E-002 ,-2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#187423 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); -#187424 = CARTESIAN_POINT('',(2.879793265791,-0.254498045091)); -#187425 = CARTESIAN_POINT('',(2.879793265791,-0.279216917273)); -#187426 = CARTESIAN_POINT('',(2.879793265791,-0.316295225546)); -#187427 = CARTESIAN_POINT('',(2.879793265791,-0.353373533818)); -#187428 = CARTESIAN_POINT('',(2.879793265791,-0.390451842091)); -#187429 = CARTESIAN_POINT('',(2.879793265791,-0.427530150364)); -#187430 = CARTESIAN_POINT('',(2.879793265791,-0.464608458637)); -#187431 = CARTESIAN_POINT('',(2.879793265791,-0.501686766909)); -#187432 = CARTESIAN_POINT('',(2.879793265791,-0.538765075182)); -#187433 = CARTESIAN_POINT('',(2.879793265791,-0.575843383455)); -#187434 = CARTESIAN_POINT('',(2.879793265791,-0.612921691727)); -#187435 = CARTESIAN_POINT('',(2.879793265791,-0.65)); -#187436 = CARTESIAN_POINT('',(2.879793265791,-0.687078308273)); -#187437 = CARTESIAN_POINT('',(2.879793265791,-0.724156616545)); -#187438 = CARTESIAN_POINT('',(2.879793265791,-0.761234924818)); -#187439 = CARTESIAN_POINT('',(2.879793265791,-0.798313233091)); -#187440 = CARTESIAN_POINT('',(2.879793265791,-0.835391541363)); -#187441 = CARTESIAN_POINT('',(2.879793265791,-0.872469849636)); -#187442 = CARTESIAN_POINT('',(2.879793265791,-0.909548157909)); -#187443 = CARTESIAN_POINT('',(2.879793265791,-0.946626466182)); -#187444 = CARTESIAN_POINT('',(2.879793265791,-0.983704774454)); -#187445 = CARTESIAN_POINT('',(2.879793265791,-1.020783082727)); -#187446 = CARTESIAN_POINT('',(2.879793265791,-1.045501954909)); -#187447 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); -#187448 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187449 = ORIENTED_EDGE('',*,*,#187450,.T.); -#187450 = EDGE_CURVE('',#187406,#186614,#187451,.T.); -#187451 = SURFACE_CURVE('',#187452,(#187456,#187463),.PCURVE_S1.); -#187452 = LINE('',#187453,#187454); -#187453 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, +#189815 = CARTESIAN_POINT('',(2.879793265791,-0.242138609)); +#189816 = CARTESIAN_POINT('',(2.879793265791,-0.254498045091)); +#189817 = CARTESIAN_POINT('',(2.879793265791,-0.279216917273)); +#189818 = CARTESIAN_POINT('',(2.879793265791,-0.316295225546)); +#189819 = CARTESIAN_POINT('',(2.879793265791,-0.353373533818)); +#189820 = CARTESIAN_POINT('',(2.879793265791,-0.390451842091)); +#189821 = CARTESIAN_POINT('',(2.879793265791,-0.427530150364)); +#189822 = CARTESIAN_POINT('',(2.879793265791,-0.464608458637)); +#189823 = CARTESIAN_POINT('',(2.879793265791,-0.501686766909)); +#189824 = CARTESIAN_POINT('',(2.879793265791,-0.538765075182)); +#189825 = CARTESIAN_POINT('',(2.879793265791,-0.575843383455)); +#189826 = CARTESIAN_POINT('',(2.879793265791,-0.612921691727)); +#189827 = CARTESIAN_POINT('',(2.879793265791,-0.65)); +#189828 = CARTESIAN_POINT('',(2.879793265791,-0.687078308273)); +#189829 = CARTESIAN_POINT('',(2.879793265791,-0.724156616545)); +#189830 = CARTESIAN_POINT('',(2.879793265791,-0.761234924818)); +#189831 = CARTESIAN_POINT('',(2.879793265791,-0.798313233091)); +#189832 = CARTESIAN_POINT('',(2.879793265791,-0.835391541363)); +#189833 = CARTESIAN_POINT('',(2.879793265791,-0.872469849636)); +#189834 = CARTESIAN_POINT('',(2.879793265791,-0.909548157909)); +#189835 = CARTESIAN_POINT('',(2.879793265791,-0.946626466182)); +#189836 = CARTESIAN_POINT('',(2.879793265791,-0.983704774454)); +#189837 = CARTESIAN_POINT('',(2.879793265791,-1.020783082727)); +#189838 = CARTESIAN_POINT('',(2.879793265791,-1.045501954909)); +#189839 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); +#189840 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189841 = ORIENTED_EDGE('',*,*,#189842,.T.); +#189842 = EDGE_CURVE('',#189798,#189006,#189843,.T.); +#189843 = SURFACE_CURVE('',#189844,(#189848,#189855),.PCURVE_S1.); +#189844 = LINE('',#189845,#189846); +#189845 = CARTESIAN_POINT('',(-1.469096372758,0.514207498814, 0.566051874704)); -#187454 = VECTOR('',#187455,1.); -#187455 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) - ); -#187456 = PCURVE('',#186744,#187457); -#187457 = DEFINITIONAL_REPRESENTATION('',(#187458),#187462); -#187458 = LINE('',#187459,#187460); -#187459 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); -#187460 = VECTOR('',#187461,1.); -#187461 = DIRECTION('',(-0.968100345886,0.250562807086)); -#187462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187463 = PCURVE('',#184696,#187464); -#187464 = DEFINITIONAL_REPRESENTATION('',(#187465),#187491); -#187465 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187466,#187467,#187468, - #187469,#187470,#187471,#187472,#187473,#187474,#187475,#187476, - #187477,#187478,#187479,#187480,#187481,#187482,#187483,#187484, - #187485,#187486,#187487,#187488,#187489,#187490),.UNSPECIFIED.,.F., +#189846 = VECTOR('',#189847,1.); +#189847 = DIRECTION('',(-0.250562807086,0.250562807086,-0.935113126531) + ); +#189848 = PCURVE('',#189136,#189849); +#189849 = DEFINITIONAL_REPRESENTATION('',(#189850),#189854); +#189850 = LINE('',#189851,#189852); +#189851 = CARTESIAN_POINT('',(-3.514568548895E-002,-0.135792501186)); +#189852 = VECTOR('',#189853,1.); +#189853 = DIRECTION('',(-0.968100345886,0.250562807086)); +#189854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189855 = PCURVE('',#187088,#189856); +#189856 = DEFINITIONAL_REPRESENTATION('',(#189857),#189883); +#189857 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189858,#189859,#189860, + #189861,#189862,#189863,#189864,#189865,#189866,#189867,#189868, + #189869,#189870,#189871,#189872,#189873,#189874,#189875,#189876, + #189877,#189878,#189879,#189880,#189881,#189882),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.424428944789, -0.40678689107,-0.389144837351,-0.371502783632,-0.353860729913, -0.336218676194,-0.318576622475,-0.300934568756,-0.283292515037, @@ -232814,67 +235816,67 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.124514031566,-0.106871977847,-8.922992412772E-002, -7.158787040873E-002,-5.394581668973E-002,-3.630376297074E-002), .UNSPECIFIED.); -#187466 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); -#187467 = CARTESIAN_POINT('',(8.223874256483E-016,-0.418548260216)); -#187468 = CARTESIAN_POINT('',(1.072145602316E-015,-0.40678689107)); -#187469 = CARTESIAN_POINT('',(-5.451986480786E-016,-0.389144837351)); -#187470 = CARTESIAN_POINT('',(1.108648989998E-015,-0.371502783632)); -#187471 = CARTESIAN_POINT('',(5.514947865868E-016,-0.353860729913)); -#187472 = CARTESIAN_POINT('',(1.126263962155E-015,-0.336218676194)); -#187473 = CARTESIAN_POINT('',(-6.15658536707E-016,-0.318576622475)); -#187474 = CARTESIAN_POINT('',(1.336370184673E-015,-0.300934568756)); -#187475 = CARTESIAN_POINT('',(-2.889301034839E-016,-0.283292515037)); -#187476 = CARTESIAN_POINT('',(-1.806497707372E-016,-0.265650461318)); -#187477 = CARTESIAN_POINT('',(1.011529186433E-015,-0.248008407599)); -#187478 = CARTESIAN_POINT('',(5.754251235075E-016,-0.23036635388)); -#187479 = CARTESIAN_POINT('',(1.127662418038E-015,-0.212724300161)); -#187480 = CARTESIAN_POINT('',(-6.451826971595E-016,-0.195082246442)); -#187481 = CARTESIAN_POINT('',(1.4530683706E-015,-0.177440192723)); -#187482 = CARTESIAN_POINT('',(-7.261986867395E-016,-0.159798139004)); -#187483 = CARTESIAN_POINT('',(1.451726376358E-015,-0.142156085285)); -#187484 = CARTESIAN_POINT('',(-6.398147201925E-016,-0.124514031566)); -#187485 = CARTESIAN_POINT('',(1.107532504412E-015,-0.106871977847)); -#187486 = CARTESIAN_POINT('',(6.505768010463E-016,-8.922992412772E-002) - ); -#187487 = CARTESIAN_POINT('',(7.310523899038E-016,-7.158787040873E-002) - ); -#187488 = CARTESIAN_POINT('',(8.661057378391E-016,-5.394581668973E-002) - ); -#187489 = CARTESIAN_POINT('',(4.523130841065E-016,-4.218444754374E-002) - ); -#187490 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#187491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187492 = ORIENTED_EDGE('',*,*,#186730,.T.); -#187493 = ADVANCED_FACE('',(#187494,#187814),#184276,.T.); -#187494 = FACE_BOUND('',#187495,.T.); -#187495 = EDGE_LOOP('',(#187496,#187541,#187542,#187589,#187609,#187610, - #187657,#187700,#187701,#187748,#187768,#187769)); -#187496 = ORIENTED_EDGE('',*,*,#187497,.T.); -#187497 = EDGE_CURVE('',#187498,#184238,#187500,.T.); -#187498 = VERTEX_POINT('',#187499); -#187499 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#187500 = SURFACE_CURVE('',#187501,(#187505,#187512),.PCURVE_S1.); -#187501 = LINE('',#187502,#187503); -#187502 = CARTESIAN_POINT('',(-1.314453973629,-0.397931449084,1.)); -#187503 = VECTOR('',#187504,1.); -#187504 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); -#187505 = PCURVE('',#184276,#187506); -#187506 = DEFINITIONAL_REPRESENTATION('',(#187507),#187511); -#187507 = LINE('',#187508,#187509); -#187508 = CARTESIAN_POINT('',(-2.774453973629,0.252068550916)); -#187509 = VECTOR('',#187510,1.); -#187510 = DIRECTION('',(1.668003342285E-016,-1.)); -#187511 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187512 = PCURVE('',#184326,#187513); -#187513 = DEFINITIONAL_REPRESENTATION('',(#187514),#187540); -#187514 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187515,#187516,#187517, - #187518,#187519,#187520,#187521,#187522,#187523,#187524,#187525, - #187526,#187527,#187528,#187529,#187530,#187531,#187532,#187533, - #187534,#187535,#187536,#187537,#187538,#187539),.UNSPECIFIED.,.F., +#189858 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); +#189859 = CARTESIAN_POINT('',(8.223874256483E-016,-0.418548260216)); +#189860 = CARTESIAN_POINT('',(1.072145602316E-015,-0.40678689107)); +#189861 = CARTESIAN_POINT('',(-5.451986480786E-016,-0.389144837351)); +#189862 = CARTESIAN_POINT('',(1.108648989998E-015,-0.371502783632)); +#189863 = CARTESIAN_POINT('',(5.514947865868E-016,-0.353860729913)); +#189864 = CARTESIAN_POINT('',(1.126263962155E-015,-0.336218676194)); +#189865 = CARTESIAN_POINT('',(-6.15658536707E-016,-0.318576622475)); +#189866 = CARTESIAN_POINT('',(1.336370184673E-015,-0.300934568756)); +#189867 = CARTESIAN_POINT('',(-2.889301034839E-016,-0.283292515037)); +#189868 = CARTESIAN_POINT('',(-1.806497707372E-016,-0.265650461318)); +#189869 = CARTESIAN_POINT('',(1.011529186433E-015,-0.248008407599)); +#189870 = CARTESIAN_POINT('',(5.754251235075E-016,-0.23036635388)); +#189871 = CARTESIAN_POINT('',(1.127662418038E-015,-0.212724300161)); +#189872 = CARTESIAN_POINT('',(-6.451826971595E-016,-0.195082246442)); +#189873 = CARTESIAN_POINT('',(1.4530683706E-015,-0.177440192723)); +#189874 = CARTESIAN_POINT('',(-7.261986867395E-016,-0.159798139004)); +#189875 = CARTESIAN_POINT('',(1.451726376358E-015,-0.142156085285)); +#189876 = CARTESIAN_POINT('',(-6.398147201925E-016,-0.124514031566)); +#189877 = CARTESIAN_POINT('',(1.107532504412E-015,-0.106871977847)); +#189878 = CARTESIAN_POINT('',(6.505768010463E-016,-8.922992412772E-002) + ); +#189879 = CARTESIAN_POINT('',(7.310523899038E-016,-7.158787040873E-002) + ); +#189880 = CARTESIAN_POINT('',(8.661057378391E-016,-5.394581668973E-002) + ); +#189881 = CARTESIAN_POINT('',(4.523130841065E-016,-4.218444754374E-002) + ); +#189882 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#189883 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189884 = ORIENTED_EDGE('',*,*,#189122,.T.); +#189885 = ADVANCED_FACE('',(#189886,#190206),#186668,.T.); +#189886 = FACE_BOUND('',#189887,.T.); +#189887 = EDGE_LOOP('',(#189888,#189933,#189934,#189981,#190001,#190002, + #190049,#190092,#190093,#190140,#190160,#190161)); +#189888 = ORIENTED_EDGE('',*,*,#189889,.T.); +#189889 = EDGE_CURVE('',#189890,#186630,#189892,.T.); +#189890 = VERTEX_POINT('',#189891); +#189891 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#189892 = SURFACE_CURVE('',#189893,(#189897,#189904),.PCURVE_S1.); +#189893 = LINE('',#189894,#189895); +#189894 = CARTESIAN_POINT('',(-1.314453973629,-0.397931449084,1.)); +#189895 = VECTOR('',#189896,1.); +#189896 = DIRECTION('',(1.668003342285E-016,-1.,0.E+000)); +#189897 = PCURVE('',#186668,#189898); +#189898 = DEFINITIONAL_REPRESENTATION('',(#189899),#189903); +#189899 = LINE('',#189900,#189901); +#189900 = CARTESIAN_POINT('',(-2.774453973629,0.252068550916)); +#189901 = VECTOR('',#189902,1.); +#189902 = DIRECTION('',(1.668003342285E-016,-1.)); +#189903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189904 = PCURVE('',#186718,#189905); +#189905 = DEFINITIONAL_REPRESENTATION('',(#189906),#189932); +#189906 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189907,#189908,#189909, + #189910,#189911,#189912,#189913,#189914,#189915,#189916,#189917, + #189918,#189919,#189920,#189921,#189922,#189923,#189924,#189925, + #189926,#189927,#189928,#189929,#189930,#189931),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084, -0.768714531811,-0.731636223538,-0.694557915266,-0.657479606993, -0.62040129872,-0.583322990448,-0.546244682175,-0.509166373902, @@ -232882,69 +235884,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.323774832539,-0.286696524266,-0.249618215993,-0.212539907721, -0.175461599448,-0.138383291175,-0.101304982903,-6.422667462989E-002 ,-2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#187515 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); -#187516 = CARTESIAN_POINT('',(1.570796326795,-1.045501954909)); -#187517 = CARTESIAN_POINT('',(1.570796326795,-1.020783082727)); -#187518 = CARTESIAN_POINT('',(1.570796326795,-0.983704774454)); -#187519 = CARTESIAN_POINT('',(1.570796326795,-0.946626466182)); -#187520 = CARTESIAN_POINT('',(1.570796326795,-0.909548157909)); -#187521 = CARTESIAN_POINT('',(1.570796326795,-0.872469849636)); -#187522 = CARTESIAN_POINT('',(1.570796326795,-0.835391541363)); -#187523 = CARTESIAN_POINT('',(1.570796326795,-0.798313233091)); -#187524 = CARTESIAN_POINT('',(1.570796326795,-0.761234924818)); -#187525 = CARTESIAN_POINT('',(1.570796326795,-0.724156616545)); -#187526 = CARTESIAN_POINT('',(1.570796326795,-0.687078308273)); -#187527 = CARTESIAN_POINT('',(1.570796326795,-0.65)); -#187528 = CARTESIAN_POINT('',(1.570796326795,-0.612921691727)); -#187529 = CARTESIAN_POINT('',(1.570796326795,-0.575843383455)); -#187530 = CARTESIAN_POINT('',(1.570796326795,-0.538765075182)); -#187531 = CARTESIAN_POINT('',(1.570796326795,-0.501686766909)); -#187532 = CARTESIAN_POINT('',(1.570796326795,-0.464608458637)); -#187533 = CARTESIAN_POINT('',(1.570796326795,-0.427530150364)); -#187534 = CARTESIAN_POINT('',(1.570796326795,-0.390451842091)); -#187535 = CARTESIAN_POINT('',(1.570796326795,-0.353373533818)); -#187536 = CARTESIAN_POINT('',(1.570796326795,-0.316295225546)); -#187537 = CARTESIAN_POINT('',(1.570796326795,-0.279216917273)); -#187538 = CARTESIAN_POINT('',(1.570796326795,-0.254498045091)); -#187539 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); -#187540 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187541 = ORIENTED_EDGE('',*,*,#184237,.T.); -#187542 = ORIENTED_EDGE('',*,*,#187543,.T.); -#187543 = EDGE_CURVE('',#184153,#187544,#187546,.T.); -#187544 = VERTEX_POINT('',#187545); -#187545 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#187546 = SURFACE_CURVE('',#187547,(#187552,#187560),.PCURVE_S1.); -#187547 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187548,#187549,#187550, -#187551),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189907 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); +#189908 = CARTESIAN_POINT('',(1.570796326795,-1.045501954909)); +#189909 = CARTESIAN_POINT('',(1.570796326795,-1.020783082727)); +#189910 = CARTESIAN_POINT('',(1.570796326795,-0.983704774454)); +#189911 = CARTESIAN_POINT('',(1.570796326795,-0.946626466182)); +#189912 = CARTESIAN_POINT('',(1.570796326795,-0.909548157909)); +#189913 = CARTESIAN_POINT('',(1.570796326795,-0.872469849636)); +#189914 = CARTESIAN_POINT('',(1.570796326795,-0.835391541363)); +#189915 = CARTESIAN_POINT('',(1.570796326795,-0.798313233091)); +#189916 = CARTESIAN_POINT('',(1.570796326795,-0.761234924818)); +#189917 = CARTESIAN_POINT('',(1.570796326795,-0.724156616545)); +#189918 = CARTESIAN_POINT('',(1.570796326795,-0.687078308273)); +#189919 = CARTESIAN_POINT('',(1.570796326795,-0.65)); +#189920 = CARTESIAN_POINT('',(1.570796326795,-0.612921691727)); +#189921 = CARTESIAN_POINT('',(1.570796326795,-0.575843383455)); +#189922 = CARTESIAN_POINT('',(1.570796326795,-0.538765075182)); +#189923 = CARTESIAN_POINT('',(1.570796326795,-0.501686766909)); +#189924 = CARTESIAN_POINT('',(1.570796326795,-0.464608458637)); +#189925 = CARTESIAN_POINT('',(1.570796326795,-0.427530150364)); +#189926 = CARTESIAN_POINT('',(1.570796326795,-0.390451842091)); +#189927 = CARTESIAN_POINT('',(1.570796326795,-0.353373533818)); +#189928 = CARTESIAN_POINT('',(1.570796326795,-0.316295225546)); +#189929 = CARTESIAN_POINT('',(1.570796326795,-0.279216917273)); +#189930 = CARTESIAN_POINT('',(1.570796326795,-0.254498045091)); +#189931 = CARTESIAN_POINT('',(1.570796326795,-0.242138609)); +#189932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189933 = ORIENTED_EDGE('',*,*,#186629,.T.); +#189934 = ORIENTED_EDGE('',*,*,#189935,.T.); +#189935 = EDGE_CURVE('',#186545,#189936,#189938,.T.); +#189936 = VERTEX_POINT('',#189937); +#189937 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#189938 = SURFACE_CURVE('',#189939,(#189944,#189952),.PCURVE_S1.); +#189939 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189940,#189941,#189942, +#189943),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187548 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); -#187549 = CARTESIAN_POINT('',(-1.268390986358,-0.494696214234,1.)); -#187550 = CARTESIAN_POINT('',(-1.24437896527,-0.504453973629,1.)); -#187551 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); -#187552 = PCURVE('',#184276,#187553); -#187553 = DEFINITIONAL_REPRESENTATION('',(#187554),#187559); -#187554 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187555,#187556,#187557, -#187558),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#189940 = CARTESIAN_POINT('',(-1.286543600296,-0.476543600296,1.)); +#189941 = CARTESIAN_POINT('',(-1.268390986358,-0.494696214234,1.)); +#189942 = CARTESIAN_POINT('',(-1.24437896527,-0.504453973629,1.)); +#189943 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,1.)); +#189944 = PCURVE('',#186668,#189945); +#189945 = DEFINITIONAL_REPRESENTATION('',(#189946),#189951); +#189946 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#189947,#189948,#189949, +#189950),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187555 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); -#187556 = CARTESIAN_POINT('',(-2.728390986358,0.155303785766)); -#187557 = CARTESIAN_POINT('',(-2.70437896527,0.145546026371)); -#187558 = CARTESIAN_POINT('',(-2.677861391,0.145546026371)); -#187559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187560 = PCURVE('',#184191,#187561); -#187561 = DEFINITIONAL_REPRESENTATION('',(#187562),#187588); -#187562 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187563,#187564,#187565, - #187566,#187567,#187568,#187569,#187570,#187571,#187572,#187573, - #187574,#187575,#187576,#187577,#187578,#187579,#187580,#187581, - #187582,#187583,#187584,#187585,#187586,#187587),.UNSPECIFIED.,.F., +#189947 = CARTESIAN_POINT('',(-2.746543600296,0.173456399704)); +#189948 = CARTESIAN_POINT('',(-2.728390986358,0.155303785766)); +#189949 = CARTESIAN_POINT('',(-2.70437896527,0.145546026371)); +#189950 = CARTESIAN_POINT('',(-2.677861391,0.145546026371)); +#189951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189952 = PCURVE('',#186583,#189953); +#189953 = DEFINITIONAL_REPRESENTATION('',(#189954),#189980); +#189954 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189955,#189956,#189957, + #189958,#189959,#189960,#189961,#189962,#189963,#189964,#189965, + #189966,#189967,#189968,#189969,#189970,#189971,#189972,#189973, + #189974,#189975,#189976,#189977,#189978,#189979),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.388131789017E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -232953,95 +235955,95 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#187563 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#187564 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#187565 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); -#187566 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#187567 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#187568 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#187569 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#187570 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#187571 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#187572 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#187573 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#187574 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#187575 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#187576 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#187577 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#187578 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#187579 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#187580 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#187581 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#187582 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#187583 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#187584 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#187585 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#187586 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#187587 = CARTESIAN_POINT('',(0.751879414295,1.)); -#187588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187589 = ORIENTED_EDGE('',*,*,#187590,.T.); -#187590 = EDGE_CURVE('',#187544,#184541,#187591,.T.); -#187591 = SURFACE_CURVE('',#187592,(#187596,#187603),.PCURVE_S1.); -#187592 = LINE('',#187593,#187594); -#187593 = CARTESIAN_POINT('',(1.207931449084,-0.504453973629,1.)); -#187594 = VECTOR('',#187595,1.); -#187595 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187596 = PCURVE('',#184276,#187597); -#187597 = DEFINITIONAL_REPRESENTATION('',(#187598),#187602); -#187598 = LINE('',#187599,#187600); -#187599 = CARTESIAN_POINT('',(-0.252068550916,0.145546026371)); -#187600 = VECTOR('',#187601,1.); -#187601 = DIRECTION('',(1.,0.E+000)); -#187602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187603 = PCURVE('',#184624,#187604); -#187604 = DEFINITIONAL_REPRESENTATION('',(#187605),#187608); -#187605 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187606,#187607), +#189955 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#189956 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#189957 = CARTESIAN_POINT('',(3.345267504996E-002,0.99997075866)); +#189958 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#189959 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#189960 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#189961 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#189962 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#189963 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#189964 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#189965 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#189966 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#189967 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#189968 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#189969 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#189970 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#189971 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#189972 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#189973 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#189974 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#189975 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#189976 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#189977 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#189978 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#189979 = CARTESIAN_POINT('',(0.751879414295,1.)); +#189980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189981 = ORIENTED_EDGE('',*,*,#189982,.T.); +#189982 = EDGE_CURVE('',#189936,#186933,#189983,.T.); +#189983 = SURFACE_CURVE('',#189984,(#189988,#189995),.PCURVE_S1.); +#189984 = LINE('',#189985,#189986); +#189985 = CARTESIAN_POINT('',(1.207931449084,-0.504453973629,1.)); +#189986 = VECTOR('',#189987,1.); +#189987 = DIRECTION('',(1.,0.E+000,0.E+000)); +#189988 = PCURVE('',#186668,#189989); +#189989 = DEFINITIONAL_REPRESENTATION('',(#189990),#189994); +#189990 = LINE('',#189991,#189992); +#189991 = CARTESIAN_POINT('',(-0.252068550916,0.145546026371)); +#189992 = VECTOR('',#189993,1.); +#189993 = DIRECTION('',(1.,0.E+000)); +#189994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#189995 = PCURVE('',#187016,#189996); +#189996 = DEFINITIONAL_REPRESENTATION('',(#189997),#190000); +#189997 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189998,#189999), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.425792840084,9.929941915507E-003), .PIECEWISE_BEZIER_KNOTS.); -#187606 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); -#187607 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); -#187608 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#189998 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); +#189999 = CARTESIAN_POINT('',(3.14159265359,-0.242138609)); +#190000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187609 = ORIENTED_EDGE('',*,*,#184540,.T.); -#187610 = ORIENTED_EDGE('',*,*,#187611,.T.); -#187611 = EDGE_CURVE('',#184456,#187612,#187614,.T.); -#187612 = VERTEX_POINT('',#187613); -#187613 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#187614 = SURFACE_CURVE('',#187615,(#187620,#187628),.PCURVE_S1.); -#187615 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187616,#187617,#187618, -#187619),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#190001 = ORIENTED_EDGE('',*,*,#186932,.T.); +#190002 = ORIENTED_EDGE('',*,*,#190003,.T.); +#190003 = EDGE_CURVE('',#186848,#190004,#190006,.T.); +#190004 = VERTEX_POINT('',#190005); +#190005 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#190006 = SURFACE_CURVE('',#190007,(#190012,#190020),.PCURVE_S1.); +#190007 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190008,#190009,#190010, +#190011),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187616 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); -#187617 = CARTESIAN_POINT('',(1.304696214234,-0.458390986358,1.)); -#187618 = CARTESIAN_POINT('',(1.314453973629,-0.43437896527,1.)); -#187619 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); -#187620 = PCURVE('',#184276,#187621); -#187621 = DEFINITIONAL_REPRESENTATION('',(#187622),#187627); -#187622 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187623,#187624,#187625, -#187626),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#190008 = CARTESIAN_POINT('',(1.286543600296,-0.476543600296,1.)); +#190009 = CARTESIAN_POINT('',(1.304696214234,-0.458390986358,1.)); +#190010 = CARTESIAN_POINT('',(1.314453973629,-0.43437896527,1.)); +#190011 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,1.)); +#190012 = PCURVE('',#186668,#190013); +#190013 = DEFINITIONAL_REPRESENTATION('',(#190014),#190019); +#190014 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190015,#190016,#190017, +#190018),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187623 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); -#187624 = CARTESIAN_POINT('',(-0.155303785766,0.191609013642)); -#187625 = CARTESIAN_POINT('',(-0.145546026371,0.21562103473)); -#187626 = CARTESIAN_POINT('',(-0.145546026371,0.242138609)); -#187627 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187628 = PCURVE('',#184494,#187629); -#187629 = DEFINITIONAL_REPRESENTATION('',(#187630),#187656); -#187630 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187631,#187632,#187633, - #187634,#187635,#187636,#187637,#187638,#187639,#187640,#187641, - #187642,#187643,#187644,#187645,#187646,#187647,#187648,#187649, - #187650,#187651,#187652,#187653,#187654,#187655),.UNSPECIFIED.,.F., +#190015 = CARTESIAN_POINT('',(-0.173456399704,0.173456399704)); +#190016 = CARTESIAN_POINT('',(-0.155303785766,0.191609013642)); +#190017 = CARTESIAN_POINT('',(-0.145546026371,0.21562103473)); +#190018 = CARTESIAN_POINT('',(-0.145546026371,0.242138609)); +#190019 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190020 = PCURVE('',#186886,#190021); +#190021 = DEFINITIONAL_REPRESENTATION('',(#190022),#190048); +#190022 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190023,#190024,#190025, + #190026,#190027,#190028,#190029,#190030,#190031,#190032,#190033, + #190034,#190035,#190036,#190037,#190038,#190039,#190040,#190041, + #190042,#190043,#190044,#190045,#190046,#190047),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -233049,56 +236051,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#187631 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#187632 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#187633 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#187634 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#187635 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#187636 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#187637 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#187638 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#187639 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#187640 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#187641 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#187642 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#187643 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#187644 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#187645 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#187646 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#187647 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#187648 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#187649 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#187650 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#187651 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#187652 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#187653 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#187654 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#187655 = CARTESIAN_POINT('',(0.751879414295,1.)); -#187656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187657 = ORIENTED_EDGE('',*,*,#187658,.T.); -#187658 = EDGE_CURVE('',#187612,#185091,#187659,.T.); -#187659 = SURFACE_CURVE('',#187660,(#187664,#187671),.PCURVE_S1.); -#187660 = LINE('',#187661,#187662); -#187661 = CARTESIAN_POINT('',(1.314453973629,0.397931449084,1.)); -#187662 = VECTOR('',#187663,1.); -#187663 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); -#187664 = PCURVE('',#184276,#187665); -#187665 = DEFINITIONAL_REPRESENTATION('',(#187666),#187670); -#187666 = LINE('',#187667,#187668); -#187667 = CARTESIAN_POINT('',(-0.145546026371,1.047931449084)); -#187668 = VECTOR('',#187669,1.); -#187669 = DIRECTION('',(-1.668003342285E-016,1.)); -#187670 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187671 = PCURVE('',#185174,#187672); -#187672 = DEFINITIONAL_REPRESENTATION('',(#187673),#187699); -#187673 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187674,#187675,#187676, - #187677,#187678,#187679,#187680,#187681,#187682,#187683,#187684, - #187685,#187686,#187687,#187688,#187689,#187690,#187691,#187692, - #187693,#187694,#187695,#187696,#187697,#187698),.UNSPECIFIED.,.F., +#190023 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#190024 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#190025 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#190026 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#190027 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#190028 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#190029 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#190030 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#190031 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#190032 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#190033 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#190034 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#190035 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#190036 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#190037 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#190038 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#190039 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#190040 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#190041 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#190042 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#190043 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#190044 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#190045 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#190046 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#190047 = CARTESIAN_POINT('',(0.751879414295,1.)); +#190048 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190049 = ORIENTED_EDGE('',*,*,#190050,.T.); +#190050 = EDGE_CURVE('',#190004,#187483,#190051,.T.); +#190051 = SURFACE_CURVE('',#190052,(#190056,#190063),.PCURVE_S1.); +#190052 = LINE('',#190053,#190054); +#190053 = CARTESIAN_POINT('',(1.314453973629,0.397931449084,1.)); +#190054 = VECTOR('',#190055,1.); +#190055 = DIRECTION('',(-1.668003342285E-016,1.,0.E+000)); +#190056 = PCURVE('',#186668,#190057); +#190057 = DEFINITIONAL_REPRESENTATION('',(#190058),#190062); +#190058 = LINE('',#190059,#190060); +#190059 = CARTESIAN_POINT('',(-0.145546026371,1.047931449084)); +#190060 = VECTOR('',#190061,1.); +#190061 = DIRECTION('',(-1.668003342285E-016,1.)); +#190062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190063 = PCURVE('',#187566,#190064); +#190064 = DEFINITIONAL_REPRESENTATION('',(#190065),#190091); +#190065 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190066,#190067,#190068, + #190069,#190070,#190071,#190072,#190073,#190074,#190075,#190076, + #190077,#190078,#190079,#190080,#190081,#190082,#190083,#190084, + #190085,#190086,#190087,#190088,#190089,#190090),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(-0.805792840084, -0.768714531811,-0.731636223538,-0.694557915266,-0.657479606993, -0.62040129872,-0.583322990448,-0.546244682175,-0.509166373902, @@ -233106,69 +236108,69 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' -0.323774832539,-0.286696524266,-0.249618215993,-0.212539907721, -0.175461599448,-0.138383291175,-0.101304982903,-6.422667462989E-002 ,-2.714836635719E-002,9.929941915506E-003),.UNSPECIFIED.); -#187674 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); -#187675 = CARTESIAN_POINT('',(1.570796326795,0.254498045091)); -#187676 = CARTESIAN_POINT('',(1.570796326795,0.279216917273)); -#187677 = CARTESIAN_POINT('',(1.570796326795,0.316295225546)); -#187678 = CARTESIAN_POINT('',(1.570796326795,0.353373533818)); -#187679 = CARTESIAN_POINT('',(1.570796326795,0.390451842091)); -#187680 = CARTESIAN_POINT('',(1.570796326795,0.427530150364)); -#187681 = CARTESIAN_POINT('',(1.570796326795,0.464608458637)); -#187682 = CARTESIAN_POINT('',(1.570796326795,0.501686766909)); -#187683 = CARTESIAN_POINT('',(1.570796326795,0.538765075182)); -#187684 = CARTESIAN_POINT('',(1.570796326795,0.575843383455)); -#187685 = CARTESIAN_POINT('',(1.570796326795,0.612921691727)); -#187686 = CARTESIAN_POINT('',(1.570796326795,0.65)); -#187687 = CARTESIAN_POINT('',(1.570796326795,0.687078308273)); -#187688 = CARTESIAN_POINT('',(1.570796326795,0.724156616545)); -#187689 = CARTESIAN_POINT('',(1.570796326795,0.761234924818)); -#187690 = CARTESIAN_POINT('',(1.570796326795,0.798313233091)); -#187691 = CARTESIAN_POINT('',(1.570796326795,0.835391541363)); -#187692 = CARTESIAN_POINT('',(1.570796326795,0.872469849636)); -#187693 = CARTESIAN_POINT('',(1.570796326795,0.909548157909)); -#187694 = CARTESIAN_POINT('',(1.570796326795,0.946626466182)); -#187695 = CARTESIAN_POINT('',(1.570796326795,0.983704774454)); -#187696 = CARTESIAN_POINT('',(1.570796326795,1.020783082727)); -#187697 = CARTESIAN_POINT('',(1.570796326795,1.045501954909)); -#187698 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); -#187699 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187700 = ORIENTED_EDGE('',*,*,#185090,.T.); -#187701 = ORIENTED_EDGE('',*,*,#187702,.T.); -#187702 = EDGE_CURVE('',#185006,#187703,#187705,.T.); -#187703 = VERTEX_POINT('',#187704); -#187704 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#187705 = SURFACE_CURVE('',#187706,(#187711,#187719),.PCURVE_S1.); -#187706 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187707,#187708,#187709, -#187710),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#190066 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); +#190067 = CARTESIAN_POINT('',(1.570796326795,0.254498045091)); +#190068 = CARTESIAN_POINT('',(1.570796326795,0.279216917273)); +#190069 = CARTESIAN_POINT('',(1.570796326795,0.316295225546)); +#190070 = CARTESIAN_POINT('',(1.570796326795,0.353373533818)); +#190071 = CARTESIAN_POINT('',(1.570796326795,0.390451842091)); +#190072 = CARTESIAN_POINT('',(1.570796326795,0.427530150364)); +#190073 = CARTESIAN_POINT('',(1.570796326795,0.464608458637)); +#190074 = CARTESIAN_POINT('',(1.570796326795,0.501686766909)); +#190075 = CARTESIAN_POINT('',(1.570796326795,0.538765075182)); +#190076 = CARTESIAN_POINT('',(1.570796326795,0.575843383455)); +#190077 = CARTESIAN_POINT('',(1.570796326795,0.612921691727)); +#190078 = CARTESIAN_POINT('',(1.570796326795,0.65)); +#190079 = CARTESIAN_POINT('',(1.570796326795,0.687078308273)); +#190080 = CARTESIAN_POINT('',(1.570796326795,0.724156616545)); +#190081 = CARTESIAN_POINT('',(1.570796326795,0.761234924818)); +#190082 = CARTESIAN_POINT('',(1.570796326795,0.798313233091)); +#190083 = CARTESIAN_POINT('',(1.570796326795,0.835391541363)); +#190084 = CARTESIAN_POINT('',(1.570796326795,0.872469849636)); +#190085 = CARTESIAN_POINT('',(1.570796326795,0.909548157909)); +#190086 = CARTESIAN_POINT('',(1.570796326795,0.946626466182)); +#190087 = CARTESIAN_POINT('',(1.570796326795,0.983704774454)); +#190088 = CARTESIAN_POINT('',(1.570796326795,1.020783082727)); +#190089 = CARTESIAN_POINT('',(1.570796326795,1.045501954909)); +#190090 = CARTESIAN_POINT('',(1.570796326795,1.057861391)); +#190091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190092 = ORIENTED_EDGE('',*,*,#187482,.T.); +#190093 = ORIENTED_EDGE('',*,*,#190094,.T.); +#190094 = EDGE_CURVE('',#187398,#190095,#190097,.T.); +#190095 = VERTEX_POINT('',#190096); +#190096 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#190097 = SURFACE_CURVE('',#190098,(#190103,#190111),.PCURVE_S1.); +#190098 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190099,#190100,#190101, +#190102),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187707 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); -#187708 = CARTESIAN_POINT('',(1.268390986358,0.494696214234,1.)); -#187709 = CARTESIAN_POINT('',(1.24437896527,0.504453973629,1.)); -#187710 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); -#187711 = PCURVE('',#184276,#187712); -#187712 = DEFINITIONAL_REPRESENTATION('',(#187713),#187718); -#187713 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187714,#187715,#187716, -#187717),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#190099 = CARTESIAN_POINT('',(1.286543600296,0.476543600296,1.)); +#190100 = CARTESIAN_POINT('',(1.268390986358,0.494696214234,1.)); +#190101 = CARTESIAN_POINT('',(1.24437896527,0.504453973629,1.)); +#190102 = CARTESIAN_POINT('',(1.217861391,0.504453973629,1.)); +#190103 = PCURVE('',#186668,#190104); +#190104 = DEFINITIONAL_REPRESENTATION('',(#190105),#190110); +#190105 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190106,#190107,#190108, +#190109),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 3.388131789017E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187714 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); -#187715 = CARTESIAN_POINT('',(-0.191609013642,1.144696214234)); -#187716 = CARTESIAN_POINT('',(-0.21562103473,1.154453973629)); -#187717 = CARTESIAN_POINT('',(-0.242138609,1.154453973629)); -#187718 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187719 = PCURVE('',#185044,#187720); -#187720 = DEFINITIONAL_REPRESENTATION('',(#187721),#187747); -#187721 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187722,#187723,#187724, - #187725,#187726,#187727,#187728,#187729,#187730,#187731,#187732, - #187733,#187734,#187735,#187736,#187737,#187738,#187739,#187740, - #187741,#187742,#187743,#187744,#187745,#187746),.UNSPECIFIED.,.F., +#190106 = CARTESIAN_POINT('',(-0.173456399704,1.126543600296)); +#190107 = CARTESIAN_POINT('',(-0.191609013642,1.144696214234)); +#190108 = CARTESIAN_POINT('',(-0.21562103473,1.154453973629)); +#190109 = CARTESIAN_POINT('',(-0.242138609,1.154453973629)); +#190110 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190111 = PCURVE('',#187436,#190112); +#190112 = DEFINITIONAL_REPRESENTATION('',(#190113),#190139); +#190113 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190114,#190115,#190116, + #190117,#190118,#190119,#190120,#190121,#190122,#190123,#190124, + #190125,#190126,#190127,#190128,#190129,#190130,#190131,#190132, + #190133,#190134,#190135,#190136,#190137,#190138),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 3.388131789017E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -233177,93 +236179,93 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#187722 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#187723 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#187724 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#187725 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#187726 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#187727 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#187728 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#187729 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#187730 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#187731 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#187732 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#187733 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#187734 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); -#187735 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#187736 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#187737 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#187738 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#187739 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#187740 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#187741 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#187742 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#187743 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#187744 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#187745 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#187746 = CARTESIAN_POINT('',(0.751879414295,1.)); -#187747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187748 = ORIENTED_EDGE('',*,*,#187749,.T.); -#187749 = EDGE_CURVE('',#187703,#184816,#187750,.T.); -#187750 = SURFACE_CURVE('',#187751,(#187755,#187762),.PCURVE_S1.); -#187751 = LINE('',#187752,#187753); -#187752 = CARTESIAN_POINT('',(-1.207931449084,0.504453973629,1.)); -#187753 = VECTOR('',#187754,1.); -#187754 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#187755 = PCURVE('',#184276,#187756); -#187756 = DEFINITIONAL_REPRESENTATION('',(#187757),#187761); -#187757 = LINE('',#187758,#187759); -#187758 = CARTESIAN_POINT('',(-2.667931449084,1.154453973629)); -#187759 = VECTOR('',#187760,1.); -#187760 = DIRECTION('',(-1.,0.E+000)); -#187761 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187762 = PCURVE('',#184899,#187763); -#187763 = DEFINITIONAL_REPRESENTATION('',(#187764),#187767); -#187764 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187765,#187766), +#190114 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#190115 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#190116 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#190117 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#190118 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#190119 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#190120 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#190121 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#190122 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#190123 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#190124 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#190125 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#190126 = CARTESIAN_POINT('',(0.375899653916,0.998577358684)); +#190127 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#190128 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#190129 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#190130 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#190131 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#190132 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#190133 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#190134 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#190135 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#190136 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#190137 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#190138 = CARTESIAN_POINT('',(0.751879414295,1.)); +#190139 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190140 = ORIENTED_EDGE('',*,*,#190141,.T.); +#190141 = EDGE_CURVE('',#190095,#187208,#190142,.T.); +#190142 = SURFACE_CURVE('',#190143,(#190147,#190154),.PCURVE_S1.); +#190143 = LINE('',#190144,#190145); +#190144 = CARTESIAN_POINT('',(-1.207931449084,0.504453973629,1.)); +#190145 = VECTOR('',#190146,1.); +#190146 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190147 = PCURVE('',#186668,#190148); +#190148 = DEFINITIONAL_REPRESENTATION('',(#190149),#190153); +#190149 = LINE('',#190150,#190151); +#190150 = CARTESIAN_POINT('',(-2.667931449084,1.154453973629)); +#190151 = VECTOR('',#190152,1.); +#190152 = DIRECTION('',(-1.,0.E+000)); +#190153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190154 = PCURVE('',#187291,#190155); +#190155 = DEFINITIONAL_REPRESENTATION('',(#190156),#190159); +#190156 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190157,#190158), .UNSPECIFIED.,.F.,.F.,(2,2),(-2.425792840084,9.929941915506E-003), .PIECEWISE_BEZIER_KNOTS.); -#187765 = CARTESIAN_POINT('',(0.E+000,0.242138609)); -#187766 = CARTESIAN_POINT('',(0.E+000,2.677861391)); -#187767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#190157 = CARTESIAN_POINT('',(0.E+000,0.242138609)); +#190158 = CARTESIAN_POINT('',(0.E+000,2.677861391)); +#190159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187768 = ORIENTED_EDGE('',*,*,#184815,.T.); -#187769 = ORIENTED_EDGE('',*,*,#187770,.T.); -#187770 = EDGE_CURVE('',#184731,#187498,#187771,.T.); -#187771 = SURFACE_CURVE('',#187772,(#187777,#187785),.PCURVE_S1.); -#187772 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187773,#187774,#187775, -#187776),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#190160 = ORIENTED_EDGE('',*,*,#187207,.T.); +#190161 = ORIENTED_EDGE('',*,*,#190162,.T.); +#190162 = EDGE_CURVE('',#187123,#189890,#190163,.T.); +#190163 = SURFACE_CURVE('',#190164,(#190169,#190177),.PCURVE_S1.); +#190164 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190165,#190166,#190167, +#190168),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187773 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); -#187774 = CARTESIAN_POINT('',(-1.304696214234,0.458390986358,1.)); -#187775 = CARTESIAN_POINT('',(-1.314453973629,0.43437896527,1.)); -#187776 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); -#187777 = PCURVE('',#184276,#187778); -#187778 = DEFINITIONAL_REPRESENTATION('',(#187779),#187784); -#187779 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#187780,#187781,#187782, -#187783),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#190165 = CARTESIAN_POINT('',(-1.286543600296,0.476543600296,1.)); +#190166 = CARTESIAN_POINT('',(-1.304696214234,0.458390986358,1.)); +#190167 = CARTESIAN_POINT('',(-1.314453973629,0.43437896527,1.)); +#190168 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,1.)); +#190169 = PCURVE('',#186668,#190170); +#190170 = DEFINITIONAL_REPRESENTATION('',(#190171),#190176); +#190171 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#190172,#190173,#190174, +#190175),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#187780 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); -#187781 = CARTESIAN_POINT('',(-2.764696214234,1.108390986358)); -#187782 = CARTESIAN_POINT('',(-2.774453973629,1.08437896527)); -#187783 = CARTESIAN_POINT('',(-2.774453973629,1.057861391)); -#187784 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187785 = PCURVE('',#184769,#187786); -#187786 = DEFINITIONAL_REPRESENTATION('',(#187787),#187813); -#187787 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187788,#187789,#187790, - #187791,#187792,#187793,#187794,#187795,#187796,#187797,#187798, - #187799,#187800,#187801,#187802,#187803,#187804,#187805,#187806, - #187807,#187808,#187809,#187810,#187811,#187812),.UNSPECIFIED.,.F., +#190172 = CARTESIAN_POINT('',(-2.746543600296,1.126543600296)); +#190173 = CARTESIAN_POINT('',(-2.764696214234,1.108390986358)); +#190174 = CARTESIAN_POINT('',(-2.774453973629,1.08437896527)); +#190175 = CARTESIAN_POINT('',(-2.774453973629,1.057861391)); +#190176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190177 = PCURVE('',#187161,#190178); +#190178 = DEFINITIONAL_REPRESENTATION('',(#190179),#190205); +#190179 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190180,#190181,#190182, + #190183,#190184,#190185,#190186,#190187,#190188,#190189,#190190, + #190191,#190192,#190193,#190194,#190195,#190196,#190197,#190198, + #190199,#190200,#190201,#190202,#190203,#190204),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -233271,59 +236273,59 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#187788 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#187789 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); -#187790 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); -#187791 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); -#187792 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); -#187793 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); -#187794 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); -#187795 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); -#187796 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); -#187797 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); -#187798 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); -#187799 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); -#187800 = CARTESIAN_POINT('',(0.375899653916,0.998577358683)); -#187801 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); -#187802 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); -#187803 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); -#187804 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); -#187805 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); -#187806 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); -#187807 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); -#187808 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); -#187809 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); -#187810 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); -#187811 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); -#187812 = CARTESIAN_POINT('',(0.751879414295,1.)); -#187813 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187814 = FACE_BOUND('',#187815,.T.); -#187815 = EDGE_LOOP('',(#187816,#187860)); -#187816 = ORIENTED_EDGE('',*,*,#187817,.F.); -#187817 = EDGE_CURVE('',#185247,#185273,#187818,.T.); -#187818 = SURFACE_CURVE('',#187819,(#187824,#187831),.PCURVE_S1.); -#187819 = CIRCLE('',#187820,0.15); -#187820 = AXIS2_PLACEMENT_3D('',#187821,#187822,#187823); -#187821 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); -#187822 = DIRECTION('',(0.E+000,0.E+000,1.)); -#187823 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187824 = PCURVE('',#184276,#187825); -#187825 = DEFINITIONAL_REPRESENTATION('',(#187826),#187830); -#187826 = CIRCLE('',#187827,0.15); -#187827 = AXIS2_PLACEMENT_2D('',#187828,#187829); -#187828 = CARTESIAN_POINT('',(-2.404441767621,0.408994126285)); -#187829 = DIRECTION('',(1.,0.E+000)); -#187830 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187831 = PCURVE('',#185261,#187832); -#187832 = DEFINITIONAL_REPRESENTATION('',(#187833),#187859); -#187833 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#187834,#187835,#187836, - #187837,#187838,#187839,#187840,#187841,#187842,#187843,#187844, - #187845,#187846,#187847,#187848,#187849,#187850,#187851,#187852, - #187853,#187854,#187855,#187856,#187857,#187858),.UNSPECIFIED.,.F., +#190180 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#190181 = CARTESIAN_POINT('',(1.112573796452E-002,0.999999986247)); +#190182 = CARTESIAN_POINT('',(3.345267504997E-002,0.99997075866)); +#190183 = CARTESIAN_POINT('',(6.714590753944E-002,0.999858629242)); +#190184 = CARTESIAN_POINT('',(0.101018031154,0.999697714073)); +#190185 = CARTESIAN_POINT('',(0.135046437107,0.999506850153)); +#190186 = CARTESIAN_POINT('',(0.169209394064,0.999303780101)); +#190187 = CARTESIAN_POINT('',(0.203486118557,0.999104661236)); +#190188 = CARTESIAN_POINT('',(0.237856655052,0.998923660586)); +#190189 = CARTESIAN_POINT('',(0.272301764008,0.998772609746)); +#190190 = CARTESIAN_POINT('',(0.306802773621,0.998660736522)); +#190191 = CARTESIAN_POINT('',(0.341341416362,0.998594475286)); +#190192 = CARTESIAN_POINT('',(0.375899653916,0.998577358683)); +#190193 = CARTESIAN_POINT('',(0.41045949854,0.998609990188)); +#190194 = CARTESIAN_POINT('',(0.445002837244,0.998690095133)); +#190195 = CARTESIAN_POINT('',(0.479511265006,0.99881264607)); +#190196 = CARTESIAN_POINT('',(0.513965932674,0.99897005671)); +#190197 = CARTESIAN_POINT('',(0.548347414424,0.999152437553)); +#190198 = CARTESIAN_POINT('',(0.582635599926,0.999347904707)); +#190199 = CARTESIAN_POINT('',(0.616809612353,0.999542934196)); +#190200 = CARTESIAN_POINT('',(0.650847765387,0.999722746961)); +#190201 = CARTESIAN_POINT('',(0.684727524261,0.999871732687)); +#190202 = CARTESIAN_POINT('',(0.718425611961,0.999973832438)); +#190203 = CARTESIAN_POINT('',(0.740753697746,1.000000029013)); +#190204 = CARTESIAN_POINT('',(0.751879414295,1.)); +#190205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190206 = FACE_BOUND('',#190207,.T.); +#190207 = EDGE_LOOP('',(#190208,#190252)); +#190208 = ORIENTED_EDGE('',*,*,#190209,.F.); +#190209 = EDGE_CURVE('',#187639,#187665,#190210,.T.); +#190210 = SURFACE_CURVE('',#190211,(#190216,#190223),.PCURVE_S1.); +#190211 = CIRCLE('',#190212,0.15); +#190212 = AXIS2_PLACEMENT_3D('',#190213,#190214,#190215); +#190213 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,1.)); +#190214 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190215 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190216 = PCURVE('',#186668,#190217); +#190217 = DEFINITIONAL_REPRESENTATION('',(#190218),#190222); +#190218 = CIRCLE('',#190219,0.15); +#190219 = AXIS2_PLACEMENT_2D('',#190220,#190221); +#190220 = CARTESIAN_POINT('',(-2.404441767621,0.408994126285)); +#190221 = DIRECTION('',(1.,0.E+000)); +#190222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190223 = PCURVE('',#187653,#190224); +#190224 = DEFINITIONAL_REPRESENTATION('',(#190225),#190251); +#190225 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190226,#190227,#190228, + #190229,#190230,#190231,#190232,#190233,#190234,#190235,#190236, + #190237,#190238,#190239,#190240,#190241,#190242,#190243,#190244, + #190245,#190246,#190247,#190248,#190249,#190250),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 0.142799666072,0.285599332145,0.428398998217,0.571198664289, 0.713998330361,0.856797996434,0.999597662506,1.142397328578, @@ -233331,881 +236333,881 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.856395658939,1.999195325012,2.141994991084,2.284794657156, 2.427594323228,2.570393989301,2.713193655373,2.855993321445, 2.998792987518,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#187834 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#187835 = CARTESIAN_POINT('',(4.759988869075E-002,-3.050892194453E-017) - ); -#187836 = CARTESIAN_POINT('',(0.142799666072,-3.54654392076E-017)); -#187837 = CARTESIAN_POINT('',(0.285599332145,3.339639610507E-017)); -#187838 = CARTESIAN_POINT('',(0.428398998217,1.895652662308E-017)); -#187839 = CARTESIAN_POINT('',(0.571198664289,-1.395047996285E-018)); -#187840 = CARTESIAN_POINT('',(0.713998330361,-8.251227252522E-018)); -#187841 = CARTESIAN_POINT('',(0.856797996434,-3.01443641288E-017)); -#187842 = CARTESIAN_POINT('',(0.999597662506,1.887911438981E-017)); -#187843 = CARTESIAN_POINT('',(1.142397328578,4.117224760062E-018)); -#187844 = CARTESIAN_POINT('',(1.28519699465,-8.601359262379E-018)); -#187845 = CARTESIAN_POINT('',(1.427996660723,1.3111094568E-017)); -#187846 = CARTESIAN_POINT('',(1.570796326795,-6.325631352262E-018)); -#187847 = CARTESIAN_POINT('',(1.713595992867,1.219143084105E-017)); -#187848 = CARTESIAN_POINT('',(1.856395658939,-4.922704354587E-018)); -#187849 = CARTESIAN_POINT('',(1.999195325012,-9.677731144158E-018)); -#187850 = CARTESIAN_POINT('',(2.141994991084,8.758874769475E-018)); -#187851 = CARTESIAN_POINT('',(2.284794657156,2.413155025675E-017)); -#187852 = CARTESIAN_POINT('',(2.427594323228,6.152115363847E-017)); -#187853 = CARTESIAN_POINT('',(2.570393989301,-8.683341617595E-017)); -#187854 = CARTESIAN_POINT('',(2.713193655373,5.934682847198E-017)); -#187855 = CARTESIAN_POINT('',(2.855993321445,-7.676035934216E-017)); -#187856 = CARTESIAN_POINT('',(2.998792987518,5.00576553463E-017)); -#187857 = CARTESIAN_POINT('',(3.093992764899,5.983073495908E-017)); -#187858 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); -#187859 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187860 = ORIENTED_EDGE('',*,*,#185272,.F.); -#187861 = ADVANCED_FACE('',(#187862),#186187,.T.); -#187862 = FACE_BOUND('',#187863,.T.); -#187863 = EDGE_LOOP('',(#187864,#187865,#187888,#187915)); -#187864 = ORIENTED_EDGE('',*,*,#186171,.F.); -#187865 = ORIENTED_EDGE('',*,*,#187866,.T.); -#187866 = EDGE_CURVE('',#186144,#187867,#187869,.T.); -#187867 = VERTEX_POINT('',#187868); -#187868 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#187869 = SURFACE_CURVE('',#187870,(#187874,#187881),.PCURVE_S1.); -#187870 = LINE('',#187871,#187872); -#187871 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#187872 = VECTOR('',#187873,1.); -#187873 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#187874 = PCURVE('',#186187,#187875); -#187875 = DEFINITIONAL_REPRESENTATION('',(#187876),#187880); -#187876 = LINE('',#187877,#187878); -#187877 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#187878 = VECTOR('',#187879,1.); -#187879 = DIRECTION('',(0.E+000,-1.)); -#187880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187881 = PCURVE('',#186159,#187882); -#187882 = DEFINITIONAL_REPRESENTATION('',(#187883),#187887); -#187883 = LINE('',#187884,#187885); -#187884 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#187885 = VECTOR('',#187886,1.); -#187886 = DIRECTION('',(0.E+000,-1.)); -#187887 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187888 = ORIENTED_EDGE('',*,*,#187889,.T.); -#187889 = EDGE_CURVE('',#187867,#187890,#187892,.T.); -#187890 = VERTEX_POINT('',#187891); -#187891 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); -#187892 = SURFACE_CURVE('',#187893,(#187897,#187904),.PCURVE_S1.); -#187893 = LINE('',#187894,#187895); -#187894 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); -#187895 = VECTOR('',#187896,1.); -#187896 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187897 = PCURVE('',#186187,#187898); -#187898 = DEFINITIONAL_REPRESENTATION('',(#187899),#187903); -#187899 = LINE('',#187900,#187901); -#187900 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#187901 = VECTOR('',#187902,1.); -#187902 = DIRECTION('',(1.,0.E+000)); -#187903 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#190226 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190227 = CARTESIAN_POINT('',(4.759988869075E-002,-3.050892194453E-017) + ); +#190228 = CARTESIAN_POINT('',(0.142799666072,-3.54654392076E-017)); +#190229 = CARTESIAN_POINT('',(0.285599332145,3.339639610507E-017)); +#190230 = CARTESIAN_POINT('',(0.428398998217,1.895652662308E-017)); +#190231 = CARTESIAN_POINT('',(0.571198664289,-1.395047996285E-018)); +#190232 = CARTESIAN_POINT('',(0.713998330361,-8.251227252522E-018)); +#190233 = CARTESIAN_POINT('',(0.856797996434,-3.01443641288E-017)); +#190234 = CARTESIAN_POINT('',(0.999597662506,1.887911438981E-017)); +#190235 = CARTESIAN_POINT('',(1.142397328578,4.117224760062E-018)); +#190236 = CARTESIAN_POINT('',(1.28519699465,-8.601359262379E-018)); +#190237 = CARTESIAN_POINT('',(1.427996660723,1.3111094568E-017)); +#190238 = CARTESIAN_POINT('',(1.570796326795,-6.325631352262E-018)); +#190239 = CARTESIAN_POINT('',(1.713595992867,1.219143084105E-017)); +#190240 = CARTESIAN_POINT('',(1.856395658939,-4.922704354587E-018)); +#190241 = CARTESIAN_POINT('',(1.999195325012,-9.677731144158E-018)); +#190242 = CARTESIAN_POINT('',(2.141994991084,8.758874769475E-018)); +#190243 = CARTESIAN_POINT('',(2.284794657156,2.413155025675E-017)); +#190244 = CARTESIAN_POINT('',(2.427594323228,6.152115363847E-017)); +#190245 = CARTESIAN_POINT('',(2.570393989301,-8.683341617595E-017)); +#190246 = CARTESIAN_POINT('',(2.713193655373,5.934682847198E-017)); +#190247 = CARTESIAN_POINT('',(2.855993321445,-7.676035934216E-017)); +#190248 = CARTESIAN_POINT('',(2.998792987518,5.00576553463E-017)); +#190249 = CARTESIAN_POINT('',(3.093992764899,5.983073495908E-017)); +#190250 = CARTESIAN_POINT('',(3.14159265359,2.733390605559E-017)); +#190251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190252 = ORIENTED_EDGE('',*,*,#187664,.F.); +#190253 = ADVANCED_FACE('',(#190254),#188579,.T.); +#190254 = FACE_BOUND('',#190255,.T.); +#190255 = EDGE_LOOP('',(#190256,#190257,#190280,#190307)); +#190256 = ORIENTED_EDGE('',*,*,#188563,.F.); +#190257 = ORIENTED_EDGE('',*,*,#190258,.T.); +#190258 = EDGE_CURVE('',#188536,#190259,#190261,.T.); +#190259 = VERTEX_POINT('',#190260); +#190260 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#190261 = SURFACE_CURVE('',#190262,(#190266,#190273),.PCURVE_S1.); +#190262 = LINE('',#190263,#190264); +#190263 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#190264 = VECTOR('',#190265,1.); +#190265 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#190266 = PCURVE('',#188579,#190267); +#190267 = DEFINITIONAL_REPRESENTATION('',(#190268),#190272); +#190268 = LINE('',#190269,#190270); +#190269 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190270 = VECTOR('',#190271,1.); +#190271 = DIRECTION('',(0.E+000,-1.)); +#190272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190273 = PCURVE('',#188551,#190274); +#190274 = DEFINITIONAL_REPRESENTATION('',(#190275),#190279); +#190275 = LINE('',#190276,#190277); +#190276 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#190277 = VECTOR('',#190278,1.); +#190278 = DIRECTION('',(0.E+000,-1.)); +#190279 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190280 = ORIENTED_EDGE('',*,*,#190281,.T.); +#190281 = EDGE_CURVE('',#190259,#190282,#190284,.T.); +#190282 = VERTEX_POINT('',#190283); +#190283 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); +#190284 = SURFACE_CURVE('',#190285,(#190289,#190296),.PCURVE_S1.); +#190285 = LINE('',#190286,#190287); +#190286 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.75)); +#190287 = VECTOR('',#190288,1.); +#190288 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190289 = PCURVE('',#188579,#190290); +#190290 = DEFINITIONAL_REPRESENTATION('',(#190291),#190295); +#190291 = LINE('',#190292,#190293); +#190292 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190293 = VECTOR('',#190294,1.); +#190294 = DIRECTION('',(1.,0.E+000)); +#190295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190296 = PCURVE('',#190297,#190302); +#190297 = CYLINDRICAL_SURFACE('',#190298,0.2); +#190298 = AXIS2_PLACEMENT_3D('',#190299,#190300,#190301); +#190299 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#190300 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190301 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190302 = DEFINITIONAL_REPRESENTATION('',(#190303),#190306); +#190303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190304,#190305), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#190304 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#190305 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#190306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#187904 = PCURVE('',#187905,#187910); -#187905 = CYLINDRICAL_SURFACE('',#187906,0.2); -#187906 = AXIS2_PLACEMENT_3D('',#187907,#187908,#187909); -#187907 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#187908 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187909 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#187910 = DEFINITIONAL_REPRESENTATION('',(#187911),#187914); -#187911 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187912,#187913), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#187912 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#187913 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#187914 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187915 = ORIENTED_EDGE('',*,*,#187916,.F.); -#187916 = EDGE_CURVE('',#186172,#187890,#187917,.T.); -#187917 = SURFACE_CURVE('',#187918,(#187922,#187929),.PCURVE_S1.); -#187918 = LINE('',#187919,#187920); -#187919 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); -#187920 = VECTOR('',#187921,1.); -#187921 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#187922 = PCURVE('',#186187,#187923); -#187923 = DEFINITIONAL_REPRESENTATION('',(#187924),#187928); -#187924 = LINE('',#187925,#187926); -#187925 = CARTESIAN_POINT('',(0.4,0.E+000)); -#187926 = VECTOR('',#187927,1.); -#187927 = DIRECTION('',(0.E+000,-1.)); -#187928 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187929 = PCURVE('',#186215,#187930); -#187930 = DEFINITIONAL_REPRESENTATION('',(#187931),#187935); -#187931 = LINE('',#187932,#187933); -#187932 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#187933 = VECTOR('',#187934,1.); -#187934 = DIRECTION('',(0.E+000,-1.)); -#187935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187936 = ADVANCED_FACE('',(#187937),#186543,.T.); -#187937 = FACE_BOUND('',#187938,.T.); -#187938 = EDGE_LOOP('',(#187939,#187940,#187963,#187990)); -#187939 = ORIENTED_EDGE('',*,*,#186529,.T.); -#187940 = ORIENTED_EDGE('',*,*,#187941,.F.); -#187941 = EDGE_CURVE('',#187942,#186200,#187944,.T.); -#187942 = VERTEX_POINT('',#187943); -#187943 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); -#187944 = SURFACE_CURVE('',#187945,(#187949,#187956),.PCURVE_S1.); -#187945 = LINE('',#187946,#187947); -#187946 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); -#187947 = VECTOR('',#187948,1.); -#187948 = DIRECTION('',(0.E+000,1.,0.E+000)); -#187949 = PCURVE('',#186543,#187950); -#187950 = DEFINITIONAL_REPRESENTATION('',(#187951),#187955); -#187951 = LINE('',#187952,#187953); -#187952 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#187953 = VECTOR('',#187954,1.); -#187954 = DIRECTION('',(0.E+000,1.)); -#187955 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187956 = PCURVE('',#186215,#187957); -#187957 = DEFINITIONAL_REPRESENTATION('',(#187958),#187962); -#187958 = LINE('',#187959,#187960); -#187959 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#187960 = VECTOR('',#187961,1.); -#187961 = DIRECTION('',(0.E+000,1.)); -#187962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187963 = ORIENTED_EDGE('',*,*,#187964,.F.); -#187964 = EDGE_CURVE('',#187965,#187942,#187967,.T.); -#187965 = VERTEX_POINT('',#187966); -#187966 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#187967 = SURFACE_CURVE('',#187968,(#187972,#187979),.PCURVE_S1.); -#187968 = LINE('',#187969,#187970); -#187969 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#187970 = VECTOR('',#187971,1.); -#187971 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187972 = PCURVE('',#186543,#187973); -#187973 = DEFINITIONAL_REPRESENTATION('',(#187974),#187978); -#187974 = LINE('',#187975,#187976); -#187975 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#187976 = VECTOR('',#187977,1.); -#187977 = DIRECTION('',(-1.,0.E+000)); -#187978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187979 = PCURVE('',#187980,#187985); -#187980 = CYLINDRICAL_SURFACE('',#187981,5.E-002); -#187981 = AXIS2_PLACEMENT_3D('',#187982,#187983,#187984); -#187982 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#187983 = DIRECTION('',(1.,0.E+000,0.E+000)); -#187984 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#187985 = DEFINITIONAL_REPRESENTATION('',(#187986),#187989); -#187986 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#187987,#187988), +#190307 = ORIENTED_EDGE('',*,*,#190308,.F.); +#190308 = EDGE_CURVE('',#188564,#190282,#190309,.T.); +#190309 = SURFACE_CURVE('',#190310,(#190314,#190321),.PCURVE_S1.); +#190310 = LINE('',#190311,#190312); +#190311 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.75)); +#190312 = VECTOR('',#190313,1.); +#190313 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#190314 = PCURVE('',#188579,#190315); +#190315 = DEFINITIONAL_REPRESENTATION('',(#190316),#190320); +#190316 = LINE('',#190317,#190318); +#190317 = CARTESIAN_POINT('',(0.4,0.E+000)); +#190318 = VECTOR('',#190319,1.); +#190319 = DIRECTION('',(0.E+000,-1.)); +#190320 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190321 = PCURVE('',#188607,#190322); +#190322 = DEFINITIONAL_REPRESENTATION('',(#190323),#190327); +#190323 = LINE('',#190324,#190325); +#190324 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#190325 = VECTOR('',#190326,1.); +#190326 = DIRECTION('',(0.E+000,-1.)); +#190327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190328 = ADVANCED_FACE('',(#190329),#188935,.T.); +#190329 = FACE_BOUND('',#190330,.T.); +#190330 = EDGE_LOOP('',(#190331,#190332,#190355,#190382)); +#190331 = ORIENTED_EDGE('',*,*,#188921,.T.); +#190332 = ORIENTED_EDGE('',*,*,#190333,.F.); +#190333 = EDGE_CURVE('',#190334,#188592,#190336,.T.); +#190334 = VERTEX_POINT('',#190335); +#190335 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); +#190336 = SURFACE_CURVE('',#190337,(#190341,#190348),.PCURVE_S1.); +#190337 = LINE('',#190338,#190339); +#190338 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.6)); +#190339 = VECTOR('',#190340,1.); +#190340 = DIRECTION('',(0.E+000,1.,0.E+000)); +#190341 = PCURVE('',#188935,#190342); +#190342 = DEFINITIONAL_REPRESENTATION('',(#190343),#190347); +#190343 = LINE('',#190344,#190345); +#190344 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#190345 = VECTOR('',#190346,1.); +#190346 = DIRECTION('',(0.E+000,1.)); +#190347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190348 = PCURVE('',#188607,#190349); +#190349 = DEFINITIONAL_REPRESENTATION('',(#190350),#190354); +#190350 = LINE('',#190351,#190352); +#190351 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#190352 = VECTOR('',#190353,1.); +#190353 = DIRECTION('',(0.E+000,1.)); +#190354 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190355 = ORIENTED_EDGE('',*,*,#190356,.F.); +#190356 = EDGE_CURVE('',#190357,#190334,#190359,.T.); +#190357 = VERTEX_POINT('',#190358); +#190358 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#190359 = SURFACE_CURVE('',#190360,(#190364,#190371),.PCURVE_S1.); +#190360 = LINE('',#190361,#190362); +#190361 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#190362 = VECTOR('',#190363,1.); +#190363 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190364 = PCURVE('',#188935,#190365); +#190365 = DEFINITIONAL_REPRESENTATION('',(#190366),#190370); +#190366 = LINE('',#190367,#190368); +#190367 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190368 = VECTOR('',#190369,1.); +#190369 = DIRECTION('',(-1.,0.E+000)); +#190370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190371 = PCURVE('',#190372,#190377); +#190372 = CYLINDRICAL_SURFACE('',#190373,5.E-002); +#190373 = AXIS2_PLACEMENT_3D('',#190374,#190375,#190376); +#190374 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#190375 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190376 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190377 = DEFINITIONAL_REPRESENTATION('',(#190378),#190381); +#190378 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190379,#190380), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#187987 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#187988 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#187989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#187990 = ORIENTED_EDGE('',*,*,#187991,.T.); -#187991 = EDGE_CURVE('',#187965,#186121,#187992,.T.); -#187992 = SURFACE_CURVE('',#187993,(#187997,#188004),.PCURVE_S1.); -#187993 = LINE('',#187994,#187995); -#187994 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); -#187995 = VECTOR('',#187996,1.); -#187996 = DIRECTION('',(0.E+000,1.,0.E+000)); -#187997 = PCURVE('',#186543,#187998); -#187998 = DEFINITIONAL_REPRESENTATION('',(#187999),#188003); -#187999 = LINE('',#188000,#188001); -#188000 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188001 = VECTOR('',#188002,1.); -#188002 = DIRECTION('',(0.E+000,1.)); -#188003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188004 = PCURVE('',#186159,#188005); -#188005 = DEFINITIONAL_REPRESENTATION('',(#188006),#188010); -#188006 = LINE('',#188007,#188008); -#188007 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#188008 = VECTOR('',#188009,1.); -#188009 = DIRECTION('',(0.E+000,1.)); -#188010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#190379 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#190380 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#190381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190382 = ORIENTED_EDGE('',*,*,#190383,.T.); +#190383 = EDGE_CURVE('',#190357,#188513,#190384,.T.); +#190384 = SURFACE_CURVE('',#190385,(#190389,#190396),.PCURVE_S1.); +#190385 = LINE('',#190386,#190387); +#190386 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.6)); +#190387 = VECTOR('',#190388,1.); +#190388 = DIRECTION('',(0.E+000,1.,0.E+000)); +#190389 = PCURVE('',#188935,#190390); +#190390 = DEFINITIONAL_REPRESENTATION('',(#190391),#190395); +#190391 = LINE('',#190392,#190393); +#190392 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190393 = VECTOR('',#190394,1.); +#190394 = DIRECTION('',(0.E+000,1.)); +#190395 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190396 = PCURVE('',#188551,#190397); +#190397 = DEFINITIONAL_REPRESENTATION('',(#190398),#190402); +#190398 = LINE('',#190399,#190400); +#190399 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#190400 = VECTOR('',#190401,1.); +#190401 = DIRECTION('',(0.E+000,1.)); +#190402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#188011 = ADVANCED_FACE('',(#188012),#186159,.F.); -#188012 = FACE_BOUND('',#188013,.T.); -#188013 = EDGE_LOOP('',(#188014,#188015,#188016,#188017,#188044,#188072, - #188100,#188128,#188156,#188184,#188216,#188244)); -#188014 = ORIENTED_EDGE('',*,*,#187866,.F.); -#188015 = ORIENTED_EDGE('',*,*,#186143,.T.); -#188016 = ORIENTED_EDGE('',*,*,#187991,.F.); -#188017 = ORIENTED_EDGE('',*,*,#188018,.F.); -#188018 = EDGE_CURVE('',#188019,#187965,#188021,.T.); -#188019 = VERTEX_POINT('',#188020); -#188020 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#188021 = SURFACE_CURVE('',#188022,(#188027,#188038),.PCURVE_S1.); -#188022 = CIRCLE('',#188023,5.E-002); -#188023 = AXIS2_PLACEMENT_3D('',#188024,#188025,#188026); -#188024 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#188025 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188026 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188027 = PCURVE('',#186159,#188028); -#188028 = DEFINITIONAL_REPRESENTATION('',(#188029),#188037); -#188029 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#188030,#188031,#188032, - #188033,#188034,#188035,#188036),.UNSPECIFIED.,.F.,.F.) +#190403 = ADVANCED_FACE('',(#190404),#188551,.F.); +#190404 = FACE_BOUND('',#190405,.T.); +#190405 = EDGE_LOOP('',(#190406,#190407,#190408,#190409,#190436,#190464, + #190492,#190520,#190548,#190576,#190608,#190636)); +#190406 = ORIENTED_EDGE('',*,*,#190258,.F.); +#190407 = ORIENTED_EDGE('',*,*,#188535,.T.); +#190408 = ORIENTED_EDGE('',*,*,#190383,.F.); +#190409 = ORIENTED_EDGE('',*,*,#190410,.F.); +#190410 = EDGE_CURVE('',#190411,#190357,#190413,.T.); +#190411 = VERTEX_POINT('',#190412); +#190412 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#190413 = SURFACE_CURVE('',#190414,(#190419,#190430),.PCURVE_S1.); +#190414 = CIRCLE('',#190415,5.E-002); +#190415 = AXIS2_PLACEMENT_3D('',#190416,#190417,#190418); +#190416 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#190417 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190418 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190419 = PCURVE('',#188551,#190420); +#190420 = DEFINITIONAL_REPRESENTATION('',(#190421),#190429); +#190421 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190422,#190423,#190424, + #190425,#190426,#190427,#190428),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#188030 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#188031 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#188032 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#188033 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#188034 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#188035 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#188036 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#188037 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188038 = PCURVE('',#187980,#188039); -#188039 = DEFINITIONAL_REPRESENTATION('',(#188040),#188043); -#188040 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188041,#188042), +#190422 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#190423 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#190424 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#190425 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#190426 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#190427 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#190428 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#190429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190430 = PCURVE('',#190372,#190431); +#190431 = DEFINITIONAL_REPRESENTATION('',(#190432),#190435); +#190432 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190433,#190434), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#188041 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#188042 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#188043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188044 = ORIENTED_EDGE('',*,*,#188045,.F.); -#188045 = EDGE_CURVE('',#188046,#188019,#188048,.T.); -#188046 = VERTEX_POINT('',#188047); -#188047 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); -#188048 = SURFACE_CURVE('',#188049,(#188053,#188060),.PCURVE_S1.); -#188049 = LINE('',#188050,#188051); -#188050 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#188051 = VECTOR('',#188052,1.); -#188052 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#188053 = PCURVE('',#186159,#188054); -#188054 = DEFINITIONAL_REPRESENTATION('',(#188055),#188059); -#188055 = LINE('',#188056,#188057); -#188056 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#188057 = VECTOR('',#188058,1.); -#188058 = DIRECTION('',(-0.993981062721,0.109552028512)); -#188059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188060 = PCURVE('',#188061,#188066); -#188061 = PLANE('',#188062); -#188062 = AXIS2_PLACEMENT_3D('',#188063,#188064,#188065); -#188063 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#188064 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); -#188065 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#188066 = DEFINITIONAL_REPRESENTATION('',(#188067),#188071); -#188067 = LINE('',#188068,#188069); -#188068 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188069 = VECTOR('',#188070,1.); -#188070 = DIRECTION('',(1.,0.E+000)); -#188071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188072 = ORIENTED_EDGE('',*,*,#188073,.F.); -#188073 = EDGE_CURVE('',#188074,#188046,#188076,.T.); -#188074 = VERTEX_POINT('',#188075); -#188075 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); -#188076 = SURFACE_CURVE('',#188077,(#188082,#188089),.PCURVE_S1.); -#188077 = CIRCLE('',#188078,0.2); -#188078 = AXIS2_PLACEMENT_3D('',#188079,#188080,#188081); -#188079 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#188080 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188081 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188082 = PCURVE('',#186159,#188083); -#188083 = DEFINITIONAL_REPRESENTATION('',(#188084),#188088); -#188084 = CIRCLE('',#188085,0.2); -#188085 = AXIS2_PLACEMENT_2D('',#188086,#188087); -#188086 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#188087 = DIRECTION('',(-1.,0.E+000)); -#188088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188089 = PCURVE('',#188090,#188095); -#188090 = CYLINDRICAL_SURFACE('',#188091,0.2); -#188091 = AXIS2_PLACEMENT_3D('',#188092,#188093,#188094); -#188092 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#188093 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188094 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188095 = DEFINITIONAL_REPRESENTATION('',(#188096),#188099); -#188096 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188097,#188098), +#190433 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#190434 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#190435 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190436 = ORIENTED_EDGE('',*,*,#190437,.F.); +#190437 = EDGE_CURVE('',#190438,#190411,#190440,.T.); +#190438 = VERTEX_POINT('',#190439); +#190439 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); +#190440 = SURFACE_CURVE('',#190441,(#190445,#190452),.PCURVE_S1.); +#190441 = LINE('',#190442,#190443); +#190442 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#190443 = VECTOR('',#190444,1.); +#190444 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#190445 = PCURVE('',#188551,#190446); +#190446 = DEFINITIONAL_REPRESENTATION('',(#190447),#190451); +#190447 = LINE('',#190448,#190449); +#190448 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#190449 = VECTOR('',#190450,1.); +#190450 = DIRECTION('',(-0.993981062721,0.109552028512)); +#190451 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190452 = PCURVE('',#190453,#190458); +#190453 = PLANE('',#190454); +#190454 = AXIS2_PLACEMENT_3D('',#190455,#190456,#190457); +#190455 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#190456 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); +#190457 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#190458 = DEFINITIONAL_REPRESENTATION('',(#190459),#190463); +#190459 = LINE('',#190460,#190461); +#190460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190461 = VECTOR('',#190462,1.); +#190462 = DIRECTION('',(1.,0.E+000)); +#190463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190464 = ORIENTED_EDGE('',*,*,#190465,.F.); +#190465 = EDGE_CURVE('',#190466,#190438,#190468,.T.); +#190466 = VERTEX_POINT('',#190467); +#190467 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); +#190468 = SURFACE_CURVE('',#190469,(#190474,#190481),.PCURVE_S1.); +#190469 = CIRCLE('',#190470,0.2); +#190470 = AXIS2_PLACEMENT_3D('',#190471,#190472,#190473); +#190471 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#190472 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190473 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190474 = PCURVE('',#188551,#190475); +#190475 = DEFINITIONAL_REPRESENTATION('',(#190476),#190480); +#190476 = CIRCLE('',#190477,0.2); +#190477 = AXIS2_PLACEMENT_2D('',#190478,#190479); +#190478 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#190479 = DIRECTION('',(-1.,0.E+000)); +#190480 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190481 = PCURVE('',#190482,#190487); +#190482 = CYLINDRICAL_SURFACE('',#190483,0.2); +#190483 = AXIS2_PLACEMENT_3D('',#190484,#190485,#190486); +#190484 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#190485 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190486 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190487 = DEFINITIONAL_REPRESENTATION('',(#190488),#190491); +#190488 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190489,#190490), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#188097 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188098 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#188099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188100 = ORIENTED_EDGE('',*,*,#188101,.F.); -#188101 = EDGE_CURVE('',#188102,#188074,#188104,.T.); -#188102 = VERTEX_POINT('',#188103); -#188103 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188104 = SURFACE_CURVE('',#188105,(#188109,#188116),.PCURVE_S1.); -#188105 = LINE('',#188106,#188107); -#188106 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188107 = VECTOR('',#188108,1.); -#188108 = DIRECTION('',(0.E+000,1.,0.E+000)); -#188109 = PCURVE('',#186159,#188110); -#188110 = DEFINITIONAL_REPRESENTATION('',(#188111),#188115); -#188111 = LINE('',#188112,#188113); -#188112 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#188113 = VECTOR('',#188114,1.); -#188114 = DIRECTION('',(0.E+000,1.)); -#188115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188116 = PCURVE('',#188117,#188122); -#188117 = PLANE('',#188118); -#188118 = AXIS2_PLACEMENT_3D('',#188119,#188120,#188121); -#188119 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188120 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188121 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188122 = DEFINITIONAL_REPRESENTATION('',(#188123),#188127); -#188123 = LINE('',#188124,#188125); -#188124 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188125 = VECTOR('',#188126,1.); -#188126 = DIRECTION('',(0.E+000,1.)); -#188127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188128 = ORIENTED_EDGE('',*,*,#188129,.F.); -#188129 = EDGE_CURVE('',#188130,#188102,#188132,.T.); -#188130 = VERTEX_POINT('',#188131); -#188131 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#188132 = SURFACE_CURVE('',#188133,(#188137,#188144),.PCURVE_S1.); -#188133 = LINE('',#188134,#188135); -#188134 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188135 = VECTOR('',#188136,1.); -#188136 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188137 = PCURVE('',#186159,#188138); -#188138 = DEFINITIONAL_REPRESENTATION('',(#188139),#188143); -#188139 = LINE('',#188140,#188141); -#188140 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#188141 = VECTOR('',#188142,1.); -#188142 = DIRECTION('',(1.,0.E+000)); -#188143 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188144 = PCURVE('',#188145,#188150); -#188145 = PLANE('',#188146); -#188146 = AXIS2_PLACEMENT_3D('',#188147,#188148,#188149); -#188147 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188148 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188149 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188150 = DEFINITIONAL_REPRESENTATION('',(#188151),#188155); -#188151 = LINE('',#188152,#188153); -#188152 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188153 = VECTOR('',#188154,1.); -#188154 = DIRECTION('',(1.,0.E+000)); -#188155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188156 = ORIENTED_EDGE('',*,*,#188157,.F.); -#188157 = EDGE_CURVE('',#188158,#188130,#188160,.T.); -#188158 = VERTEX_POINT('',#188159); -#188159 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); -#188160 = SURFACE_CURVE('',#188161,(#188165,#188172),.PCURVE_S1.); -#188161 = LINE('',#188162,#188163); -#188162 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#188163 = VECTOR('',#188164,1.); -#188164 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188165 = PCURVE('',#186159,#188166); -#188166 = DEFINITIONAL_REPRESENTATION('',(#188167),#188171); -#188167 = LINE('',#188168,#188169); -#188168 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#188169 = VECTOR('',#188170,1.); -#188170 = DIRECTION('',(0.E+000,-1.)); -#188171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188172 = PCURVE('',#188173,#188178); -#188173 = PLANE('',#188174); -#188174 = AXIS2_PLACEMENT_3D('',#188175,#188176,#188177); -#188175 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#188176 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188177 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188178 = DEFINITIONAL_REPRESENTATION('',(#188179),#188183); -#188179 = LINE('',#188180,#188181); -#188180 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188181 = VECTOR('',#188182,1.); -#188182 = DIRECTION('',(0.E+000,-1.)); -#188183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188184 = ORIENTED_EDGE('',*,*,#188185,.F.); -#188185 = EDGE_CURVE('',#188186,#188158,#188188,.T.); -#188186 = VERTEX_POINT('',#188187); -#188187 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#188188 = SURFACE_CURVE('',#188189,(#188194,#188205),.PCURVE_S1.); -#188189 = CIRCLE('',#188190,5.E-002); -#188190 = AXIS2_PLACEMENT_3D('',#188191,#188192,#188193); -#188191 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#188192 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188193 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188194 = PCURVE('',#186159,#188195); -#188195 = DEFINITIONAL_REPRESENTATION('',(#188196),#188204); -#188196 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#188197,#188198,#188199, - #188200,#188201,#188202,#188203),.UNSPECIFIED.,.F.,.F.) +#190489 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190490 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#190491 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190492 = ORIENTED_EDGE('',*,*,#190493,.F.); +#190493 = EDGE_CURVE('',#190494,#190466,#190496,.T.); +#190494 = VERTEX_POINT('',#190495); +#190495 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190496 = SURFACE_CURVE('',#190497,(#190501,#190508),.PCURVE_S1.); +#190497 = LINE('',#190498,#190499); +#190498 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190499 = VECTOR('',#190500,1.); +#190500 = DIRECTION('',(0.E+000,1.,0.E+000)); +#190501 = PCURVE('',#188551,#190502); +#190502 = DEFINITIONAL_REPRESENTATION('',(#190503),#190507); +#190503 = LINE('',#190504,#190505); +#190504 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#190505 = VECTOR('',#190506,1.); +#190506 = DIRECTION('',(0.E+000,1.)); +#190507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190508 = PCURVE('',#190509,#190514); +#190509 = PLANE('',#190510); +#190510 = AXIS2_PLACEMENT_3D('',#190511,#190512,#190513); +#190511 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190512 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190513 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190514 = DEFINITIONAL_REPRESENTATION('',(#190515),#190519); +#190515 = LINE('',#190516,#190517); +#190516 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190517 = VECTOR('',#190518,1.); +#190518 = DIRECTION('',(0.E+000,1.)); +#190519 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190520 = ORIENTED_EDGE('',*,*,#190521,.F.); +#190521 = EDGE_CURVE('',#190522,#190494,#190524,.T.); +#190522 = VERTEX_POINT('',#190523); +#190523 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#190524 = SURFACE_CURVE('',#190525,(#190529,#190536),.PCURVE_S1.); +#190525 = LINE('',#190526,#190527); +#190526 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190527 = VECTOR('',#190528,1.); +#190528 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190529 = PCURVE('',#188551,#190530); +#190530 = DEFINITIONAL_REPRESENTATION('',(#190531),#190535); +#190531 = LINE('',#190532,#190533); +#190532 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#190533 = VECTOR('',#190534,1.); +#190534 = DIRECTION('',(1.,0.E+000)); +#190535 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190536 = PCURVE('',#190537,#190542); +#190537 = PLANE('',#190538); +#190538 = AXIS2_PLACEMENT_3D('',#190539,#190540,#190541); +#190539 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190540 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#190541 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190542 = DEFINITIONAL_REPRESENTATION('',(#190543),#190547); +#190543 = LINE('',#190544,#190545); +#190544 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190545 = VECTOR('',#190546,1.); +#190546 = DIRECTION('',(1.,0.E+000)); +#190547 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190548 = ORIENTED_EDGE('',*,*,#190549,.F.); +#190549 = EDGE_CURVE('',#190550,#190522,#190552,.T.); +#190550 = VERTEX_POINT('',#190551); +#190551 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); +#190552 = SURFACE_CURVE('',#190553,(#190557,#190564),.PCURVE_S1.); +#190553 = LINE('',#190554,#190555); +#190554 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#190555 = VECTOR('',#190556,1.); +#190556 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#190557 = PCURVE('',#188551,#190558); +#190558 = DEFINITIONAL_REPRESENTATION('',(#190559),#190563); +#190559 = LINE('',#190560,#190561); +#190560 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#190561 = VECTOR('',#190562,1.); +#190562 = DIRECTION('',(0.E+000,-1.)); +#190563 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190564 = PCURVE('',#190565,#190570); +#190565 = PLANE('',#190566); +#190566 = AXIS2_PLACEMENT_3D('',#190567,#190568,#190569); +#190567 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#190568 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190569 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190570 = DEFINITIONAL_REPRESENTATION('',(#190571),#190575); +#190571 = LINE('',#190572,#190573); +#190572 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190573 = VECTOR('',#190574,1.); +#190574 = DIRECTION('',(0.E+000,-1.)); +#190575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190576 = ORIENTED_EDGE('',*,*,#190577,.F.); +#190577 = EDGE_CURVE('',#190578,#190550,#190580,.T.); +#190578 = VERTEX_POINT('',#190579); +#190579 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#190580 = SURFACE_CURVE('',#190581,(#190586,#190597),.PCURVE_S1.); +#190581 = CIRCLE('',#190582,5.E-002); +#190582 = AXIS2_PLACEMENT_3D('',#190583,#190584,#190585); +#190583 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#190584 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190585 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190586 = PCURVE('',#188551,#190587); +#190587 = DEFINITIONAL_REPRESENTATION('',(#190588),#190596); +#190588 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190589,#190590,#190591, + #190592,#190593,#190594,#190595),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#188197 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#188198 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#188199 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#188200 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#188201 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#188202 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#188203 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#188204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188205 = PCURVE('',#188206,#188211); -#188206 = CYLINDRICAL_SURFACE('',#188207,5.E-002); -#188207 = AXIS2_PLACEMENT_3D('',#188208,#188209,#188210); -#188208 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); -#188209 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188210 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188211 = DEFINITIONAL_REPRESENTATION('',(#188212),#188215); -#188212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188213,#188214), +#190589 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#190590 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#190591 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#190592 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#190593 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#190594 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#190595 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#190596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190597 = PCURVE('',#190598,#190603); +#190598 = CYLINDRICAL_SURFACE('',#190599,5.E-002); +#190599 = AXIS2_PLACEMENT_3D('',#190600,#190601,#190602); +#190600 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.2)); +#190601 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190602 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190603 = DEFINITIONAL_REPRESENTATION('',(#190604),#190607); +#190604 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190605,#190606), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#188213 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#188214 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188216 = ORIENTED_EDGE('',*,*,#188217,.F.); -#188217 = EDGE_CURVE('',#188218,#188186,#188220,.T.); -#188218 = VERTEX_POINT('',#188219); -#188219 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); -#188220 = SURFACE_CURVE('',#188221,(#188225,#188232),.PCURVE_S1.); -#188221 = LINE('',#188222,#188223); -#188222 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#188223 = VECTOR('',#188224,1.); -#188224 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#188225 = PCURVE('',#186159,#188226); -#188226 = DEFINITIONAL_REPRESENTATION('',(#188227),#188231); -#188227 = LINE('',#188228,#188229); -#188228 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#188229 = VECTOR('',#188230,1.); -#188230 = DIRECTION('',(0.993981062721,-0.109552028512)); -#188231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188232 = PCURVE('',#188233,#188238); -#188233 = PLANE('',#188234); -#188234 = AXIS2_PLACEMENT_3D('',#188235,#188236,#188237); -#188235 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#188236 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); -#188237 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#188238 = DEFINITIONAL_REPRESENTATION('',(#188239),#188243); -#188239 = LINE('',#188240,#188241); -#188240 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188241 = VECTOR('',#188242,1.); -#188242 = DIRECTION('',(1.,0.E+000)); -#188243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188244 = ORIENTED_EDGE('',*,*,#188245,.F.); -#188245 = EDGE_CURVE('',#187867,#188218,#188246,.T.); -#188246 = SURFACE_CURVE('',#188247,(#188252,#188259),.PCURVE_S1.); -#188247 = CIRCLE('',#188248,0.2); -#188248 = AXIS2_PLACEMENT_3D('',#188249,#188250,#188251); -#188249 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); -#188250 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188251 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188252 = PCURVE('',#186159,#188253); -#188253 = DEFINITIONAL_REPRESENTATION('',(#188254),#188258); -#188254 = CIRCLE('',#188255,0.2); -#188255 = AXIS2_PLACEMENT_2D('',#188256,#188257); -#188256 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#188257 = DIRECTION('',(-1.,0.E+000)); -#188258 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188259 = PCURVE('',#187905,#188260); -#188260 = DEFINITIONAL_REPRESENTATION('',(#188261),#188264); -#188261 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188262,#188263), +#190605 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#190606 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190607 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190608 = ORIENTED_EDGE('',*,*,#190609,.F.); +#190609 = EDGE_CURVE('',#190610,#190578,#190612,.T.); +#190610 = VERTEX_POINT('',#190611); +#190611 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); +#190612 = SURFACE_CURVE('',#190613,(#190617,#190624),.PCURVE_S1.); +#190613 = LINE('',#190614,#190615); +#190614 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#190615 = VECTOR('',#190616,1.); +#190616 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#190617 = PCURVE('',#188551,#190618); +#190618 = DEFINITIONAL_REPRESENTATION('',(#190619),#190623); +#190619 = LINE('',#190620,#190621); +#190620 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#190621 = VECTOR('',#190622,1.); +#190622 = DIRECTION('',(0.993981062721,-0.109552028512)); +#190623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190624 = PCURVE('',#190625,#190630); +#190625 = PLANE('',#190626); +#190626 = AXIS2_PLACEMENT_3D('',#190627,#190628,#190629); +#190627 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#190628 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); +#190629 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#190630 = DEFINITIONAL_REPRESENTATION('',(#190631),#190635); +#190631 = LINE('',#190632,#190633); +#190632 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190633 = VECTOR('',#190634,1.); +#190634 = DIRECTION('',(1.,0.E+000)); +#190635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190636 = ORIENTED_EDGE('',*,*,#190637,.F.); +#190637 = EDGE_CURVE('',#190259,#190610,#190638,.T.); +#190638 = SURFACE_CURVE('',#190639,(#190644,#190651),.PCURVE_S1.); +#190639 = CIRCLE('',#190640,0.2); +#190640 = AXIS2_PLACEMENT_3D('',#190641,#190642,#190643); +#190641 = CARTESIAN_POINT('',(0.755,-0.655208001194,0.55)); +#190642 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190643 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190644 = PCURVE('',#188551,#190645); +#190645 = DEFINITIONAL_REPRESENTATION('',(#190646),#190650); +#190646 = CIRCLE('',#190647,0.2); +#190647 = AXIS2_PLACEMENT_2D('',#190648,#190649); +#190648 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#190649 = DIRECTION('',(-1.,0.E+000)); +#190650 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190651 = PCURVE('',#190297,#190652); +#190652 = DEFINITIONAL_REPRESENTATION('',(#190653),#190656); +#190653 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190654,#190655), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#188262 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#188263 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#188264 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188265 = ADVANCED_FACE('',(#188266),#186215,.T.); -#188266 = FACE_BOUND('',#188267,.T.); -#188267 = EDGE_LOOP('',(#188268,#188269,#188270,#188293,#188316,#188343, - #188366,#188389,#188412,#188435,#188458,#188483)); -#188268 = ORIENTED_EDGE('',*,*,#186199,.F.); -#188269 = ORIENTED_EDGE('',*,*,#187916,.T.); -#188270 = ORIENTED_EDGE('',*,*,#188271,.T.); -#188271 = EDGE_CURVE('',#187890,#188272,#188274,.T.); -#188272 = VERTEX_POINT('',#188273); -#188273 = CARTESIAN_POINT('',(1.155,-0.854004213739,0.571910405702)); -#188274 = SURFACE_CURVE('',#188275,(#188280,#188287),.PCURVE_S1.); -#188275 = CIRCLE('',#188276,0.2); -#188276 = AXIS2_PLACEMENT_3D('',#188277,#188278,#188279); -#188277 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#188278 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188279 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188280 = PCURVE('',#186215,#188281); -#188281 = DEFINITIONAL_REPRESENTATION('',(#188282),#188286); -#188282 = CIRCLE('',#188283,0.2); -#188283 = AXIS2_PLACEMENT_2D('',#188284,#188285); -#188284 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#188285 = DIRECTION('',(-1.,0.E+000)); -#188286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188287 = PCURVE('',#187905,#188288); -#188288 = DEFINITIONAL_REPRESENTATION('',(#188289),#188292); -#188289 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188290,#188291), +#190654 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#190655 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#190656 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190657 = ADVANCED_FACE('',(#190658),#188607,.T.); +#190658 = FACE_BOUND('',#190659,.T.); +#190659 = EDGE_LOOP('',(#190660,#190661,#190662,#190685,#190708,#190735, + #190758,#190781,#190804,#190827,#190850,#190875)); +#190660 = ORIENTED_EDGE('',*,*,#188591,.F.); +#190661 = ORIENTED_EDGE('',*,*,#190308,.T.); +#190662 = ORIENTED_EDGE('',*,*,#190663,.T.); +#190663 = EDGE_CURVE('',#190282,#190664,#190666,.T.); +#190664 = VERTEX_POINT('',#190665); +#190665 = CARTESIAN_POINT('',(1.155,-0.854004213739,0.571910405702)); +#190666 = SURFACE_CURVE('',#190667,(#190672,#190679),.PCURVE_S1.); +#190667 = CIRCLE('',#190668,0.2); +#190668 = AXIS2_PLACEMENT_3D('',#190669,#190670,#190671); +#190669 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#190670 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190671 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190672 = PCURVE('',#188607,#190673); +#190673 = DEFINITIONAL_REPRESENTATION('',(#190674),#190678); +#190674 = CIRCLE('',#190675,0.2); +#190675 = AXIS2_PLACEMENT_2D('',#190676,#190677); +#190676 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#190677 = DIRECTION('',(-1.,0.E+000)); +#190678 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190679 = PCURVE('',#190297,#190680); +#190680 = DEFINITIONAL_REPRESENTATION('',(#190681),#190684); +#190681 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190682,#190683), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#188290 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#188291 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#188292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188293 = ORIENTED_EDGE('',*,*,#188294,.T.); -#188294 = EDGE_CURVE('',#188272,#188295,#188297,.T.); -#188295 = VERTEX_POINT('',#188296); -#188296 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); -#188297 = SURFACE_CURVE('',#188298,(#188302,#188309),.PCURVE_S1.); -#188298 = LINE('',#188299,#188300); -#188299 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); -#188300 = VECTOR('',#188301,1.); -#188301 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#188302 = PCURVE('',#186215,#188303); -#188303 = DEFINITIONAL_REPRESENTATION('',(#188304),#188308); -#188304 = LINE('',#188305,#188306); -#188305 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#188306 = VECTOR('',#188307,1.); -#188307 = DIRECTION('',(0.993981062721,-0.109552028512)); -#188308 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188309 = PCURVE('',#188233,#188310); -#188310 = DEFINITIONAL_REPRESENTATION('',(#188311),#188315); -#188311 = LINE('',#188312,#188313); -#188312 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188313 = VECTOR('',#188314,1.); -#188314 = DIRECTION('',(1.,0.E+000)); -#188315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188316 = ORIENTED_EDGE('',*,*,#188317,.T.); -#188317 = EDGE_CURVE('',#188295,#188318,#188320,.T.); -#188318 = VERTEX_POINT('',#188319); -#188319 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.15)); -#188320 = SURFACE_CURVE('',#188321,(#188326,#188337),.PCURVE_S1.); -#188321 = CIRCLE('',#188322,5.E-002); -#188322 = AXIS2_PLACEMENT_3D('',#188323,#188324,#188325); -#188323 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); -#188324 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188325 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188326 = PCURVE('',#186215,#188327); -#188327 = DEFINITIONAL_REPRESENTATION('',(#188328),#188336); -#188328 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#188329,#188330,#188331, - #188332,#188333,#188334,#188335),.UNSPECIFIED.,.F.,.F.) +#190682 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#190683 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#190684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190685 = ORIENTED_EDGE('',*,*,#190686,.T.); +#190686 = EDGE_CURVE('',#190664,#190687,#190689,.T.); +#190687 = VERTEX_POINT('',#190688); +#190688 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); +#190689 = SURFACE_CURVE('',#190690,(#190694,#190701),.PCURVE_S1.); +#190690 = LINE('',#190691,#190692); +#190691 = CARTESIAN_POINT('',(1.155,-0.895598186972,0.194522398574)); +#190692 = VECTOR('',#190693,1.); +#190693 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#190694 = PCURVE('',#188607,#190695); +#190695 = DEFINITIONAL_REPRESENTATION('',(#190696),#190700); +#190696 = LINE('',#190697,#190698); +#190697 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#190698 = VECTOR('',#190699,1.); +#190699 = DIRECTION('',(0.993981062721,-0.109552028512)); +#190700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190701 = PCURVE('',#190625,#190702); +#190702 = DEFINITIONAL_REPRESENTATION('',(#190703),#190707); +#190703 = LINE('',#190704,#190705); +#190704 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190705 = VECTOR('',#190706,1.); +#190706 = DIRECTION('',(1.,0.E+000)); +#190707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190708 = ORIENTED_EDGE('',*,*,#190709,.T.); +#190709 = EDGE_CURVE('',#190687,#190710,#190712,.T.); +#190710 = VERTEX_POINT('',#190711); +#190711 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.15)); +#190712 = SURFACE_CURVE('',#190713,(#190718,#190729),.PCURVE_S1.); +#190713 = CIRCLE('',#190714,5.E-002); +#190714 = AXIS2_PLACEMENT_3D('',#190715,#190716,#190717); +#190715 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); +#190716 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190717 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190718 = PCURVE('',#188607,#190719); +#190719 = DEFINITIONAL_REPRESENTATION('',(#190720),#190728); +#190720 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190721,#190722,#190723, + #190724,#190725,#190726,#190727),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#188329 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#188330 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#188331 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#188332 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#188333 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#188334 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#188335 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#188336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188337 = PCURVE('',#188206,#188338); -#188338 = DEFINITIONAL_REPRESENTATION('',(#188339),#188342); -#188339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188340,#188341), +#190721 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#190722 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#190723 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#190724 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#190725 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#190726 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#190727 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#190728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190729 = PCURVE('',#190598,#190730); +#190730 = DEFINITIONAL_REPRESENTATION('',(#190731),#190734); +#190731 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190732,#190733), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#188340 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#188341 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188343 = ORIENTED_EDGE('',*,*,#188344,.T.); -#188344 = EDGE_CURVE('',#188318,#188345,#188347,.T.); -#188345 = VERTEX_POINT('',#188346); -#188346 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); -#188347 = SURFACE_CURVE('',#188348,(#188352,#188359),.PCURVE_S1.); -#188348 = LINE('',#188349,#188350); -#188349 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); -#188350 = VECTOR('',#188351,1.); -#188351 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188352 = PCURVE('',#186215,#188353); -#188353 = DEFINITIONAL_REPRESENTATION('',(#188354),#188358); -#188354 = LINE('',#188355,#188356); -#188355 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#188356 = VECTOR('',#188357,1.); -#188357 = DIRECTION('',(0.E+000,-1.)); -#188358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188359 = PCURVE('',#188173,#188360); -#188360 = DEFINITIONAL_REPRESENTATION('',(#188361),#188365); -#188361 = LINE('',#188362,#188363); -#188362 = CARTESIAN_POINT('',(0.4,0.E+000)); -#188363 = VECTOR('',#188364,1.); -#188364 = DIRECTION('',(0.E+000,-1.)); -#188365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188366 = ORIENTED_EDGE('',*,*,#188367,.T.); -#188367 = EDGE_CURVE('',#188345,#188368,#188370,.T.); -#188368 = VERTEX_POINT('',#188369); -#188369 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#188370 = SURFACE_CURVE('',#188371,(#188375,#188382),.PCURVE_S1.); -#188371 = LINE('',#188372,#188373); -#188372 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#188373 = VECTOR('',#188374,1.); -#188374 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188375 = PCURVE('',#186215,#188376); -#188376 = DEFINITIONAL_REPRESENTATION('',(#188377),#188381); -#188377 = LINE('',#188378,#188379); -#188378 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#188379 = VECTOR('',#188380,1.); -#188380 = DIRECTION('',(1.,0.E+000)); -#188381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188382 = PCURVE('',#188145,#188383); -#188383 = DEFINITIONAL_REPRESENTATION('',(#188384),#188388); -#188384 = LINE('',#188385,#188386); -#188385 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188386 = VECTOR('',#188387,1.); -#188387 = DIRECTION('',(1.,0.E+000)); -#188388 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188389 = ORIENTED_EDGE('',*,*,#188390,.T.); -#188390 = EDGE_CURVE('',#188368,#188391,#188393,.T.); -#188391 = VERTEX_POINT('',#188392); -#188392 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.E+000)); -#188393 = SURFACE_CURVE('',#188394,(#188398,#188405),.PCURVE_S1.); -#188394 = LINE('',#188395,#188396); -#188395 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); -#188396 = VECTOR('',#188397,1.); -#188397 = DIRECTION('',(0.E+000,1.,0.E+000)); -#188398 = PCURVE('',#186215,#188399); -#188399 = DEFINITIONAL_REPRESENTATION('',(#188400),#188404); -#188400 = LINE('',#188401,#188402); -#188401 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#188402 = VECTOR('',#188403,1.); -#188403 = DIRECTION('',(0.E+000,1.)); -#188404 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188405 = PCURVE('',#188117,#188406); -#188406 = DEFINITIONAL_REPRESENTATION('',(#188407),#188411); -#188407 = LINE('',#188408,#188409); -#188408 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#188409 = VECTOR('',#188410,1.); -#188410 = DIRECTION('',(0.E+000,1.)); -#188411 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188412 = ORIENTED_EDGE('',*,*,#188413,.T.); -#188413 = EDGE_CURVE('',#188391,#188414,#188416,.T.); -#188414 = VERTEX_POINT('',#188415); -#188415 = CARTESIAN_POINT('',(1.155,-0.746501027564,0.178089594298)); -#188416 = SURFACE_CURVE('',#188417,(#188422,#188429),.PCURVE_S1.); -#188417 = CIRCLE('',#188418,0.2); -#188418 = AXIS2_PLACEMENT_3D('',#188419,#188420,#188421); -#188419 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); -#188420 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188421 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188422 = PCURVE('',#186215,#188423); -#188423 = DEFINITIONAL_REPRESENTATION('',(#188424),#188428); -#188424 = CIRCLE('',#188425,0.2); -#188425 = AXIS2_PLACEMENT_2D('',#188426,#188427); -#188426 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#188427 = DIRECTION('',(-1.,0.E+000)); -#188428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188429 = PCURVE('',#188090,#188430); -#188430 = DEFINITIONAL_REPRESENTATION('',(#188431),#188434); -#188431 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188432,#188433), +#190732 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#190733 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190734 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190735 = ORIENTED_EDGE('',*,*,#190736,.T.); +#190736 = EDGE_CURVE('',#190710,#190737,#190739,.T.); +#190737 = VERTEX_POINT('',#190738); +#190738 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); +#190739 = SURFACE_CURVE('',#190740,(#190744,#190751),.PCURVE_S1.); +#190740 = LINE('',#190741,#190742); +#190741 = CARTESIAN_POINT('',(1.155,-1.17,0.15)); +#190742 = VECTOR('',#190743,1.); +#190743 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#190744 = PCURVE('',#188607,#190745); +#190745 = DEFINITIONAL_REPRESENTATION('',(#190746),#190750); +#190746 = LINE('',#190747,#190748); +#190747 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#190748 = VECTOR('',#190749,1.); +#190749 = DIRECTION('',(0.E+000,-1.)); +#190750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190751 = PCURVE('',#190565,#190752); +#190752 = DEFINITIONAL_REPRESENTATION('',(#190753),#190757); +#190753 = LINE('',#190754,#190755); +#190754 = CARTESIAN_POINT('',(0.4,0.E+000)); +#190755 = VECTOR('',#190756,1.); +#190756 = DIRECTION('',(0.E+000,-1.)); +#190757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190758 = ORIENTED_EDGE('',*,*,#190759,.T.); +#190759 = EDGE_CURVE('',#190737,#190760,#190762,.T.); +#190760 = VERTEX_POINT('',#190761); +#190761 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#190762 = SURFACE_CURVE('',#190763,(#190767,#190774),.PCURVE_S1.); +#190763 = LINE('',#190764,#190765); +#190764 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#190765 = VECTOR('',#190766,1.); +#190766 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190767 = PCURVE('',#188607,#190768); +#190768 = DEFINITIONAL_REPRESENTATION('',(#190769),#190773); +#190769 = LINE('',#190770,#190771); +#190770 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#190771 = VECTOR('',#190772,1.); +#190772 = DIRECTION('',(1.,0.E+000)); +#190773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190774 = PCURVE('',#190537,#190775); +#190775 = DEFINITIONAL_REPRESENTATION('',(#190776),#190780); +#190776 = LINE('',#190777,#190778); +#190777 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190778 = VECTOR('',#190779,1.); +#190779 = DIRECTION('',(1.,0.E+000)); +#190780 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190781 = ORIENTED_EDGE('',*,*,#190782,.T.); +#190782 = EDGE_CURVE('',#190760,#190783,#190785,.T.); +#190783 = VERTEX_POINT('',#190784); +#190784 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.E+000)); +#190785 = SURFACE_CURVE('',#190786,(#190790,#190797),.PCURVE_S1.); +#190786 = LINE('',#190787,#190788); +#190787 = CARTESIAN_POINT('',(1.155,-1.17,0.E+000)); +#190788 = VECTOR('',#190789,1.); +#190789 = DIRECTION('',(0.E+000,1.,0.E+000)); +#190790 = PCURVE('',#188607,#190791); +#190791 = DEFINITIONAL_REPRESENTATION('',(#190792),#190796); +#190792 = LINE('',#190793,#190794); +#190793 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#190794 = VECTOR('',#190795,1.); +#190795 = DIRECTION('',(0.E+000,1.)); +#190796 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190797 = PCURVE('',#190509,#190798); +#190798 = DEFINITIONAL_REPRESENTATION('',(#190799),#190803); +#190799 = LINE('',#190800,#190801); +#190800 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#190801 = VECTOR('',#190802,1.); +#190802 = DIRECTION('',(0.E+000,1.)); +#190803 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190804 = ORIENTED_EDGE('',*,*,#190805,.T.); +#190805 = EDGE_CURVE('',#190783,#190806,#190808,.T.); +#190806 = VERTEX_POINT('',#190807); +#190807 = CARTESIAN_POINT('',(1.155,-0.746501027564,0.178089594298)); +#190808 = SURFACE_CURVE('',#190809,(#190814,#190821),.PCURVE_S1.); +#190809 = CIRCLE('',#190810,0.2); +#190810 = AXIS2_PLACEMENT_3D('',#190811,#190812,#190813); +#190811 = CARTESIAN_POINT('',(1.155,-0.945297240108,0.2)); +#190812 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190813 = DIRECTION('',(0.E+000,0.E+000,1.)); +#190814 = PCURVE('',#188607,#190815); +#190815 = DEFINITIONAL_REPRESENTATION('',(#190816),#190820); +#190816 = CIRCLE('',#190817,0.2); +#190817 = AXIS2_PLACEMENT_2D('',#190818,#190819); +#190818 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#190819 = DIRECTION('',(-1.,0.E+000)); +#190820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190821 = PCURVE('',#190482,#190822); +#190822 = DEFINITIONAL_REPRESENTATION('',(#190823),#190826); +#190823 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190824,#190825), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#188432 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188433 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#188434 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188435 = ORIENTED_EDGE('',*,*,#188436,.T.); -#188436 = EDGE_CURVE('',#188414,#188437,#188439,.T.); -#188437 = VERTEX_POINT('',#188438); -#188438 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); -#188439 = SURFACE_CURVE('',#188440,(#188444,#188451),.PCURVE_S1.); -#188440 = LINE('',#188441,#188442); -#188441 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); -#188442 = VECTOR('',#188443,1.); -#188443 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#188444 = PCURVE('',#186215,#188445); -#188445 = DEFINITIONAL_REPRESENTATION('',(#188446),#188450); -#188446 = LINE('',#188447,#188448); -#188447 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#188448 = VECTOR('',#188449,1.); -#188449 = DIRECTION('',(-0.993981062721,0.109552028512)); -#188450 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188451 = PCURVE('',#188061,#188452); -#188452 = DEFINITIONAL_REPRESENTATION('',(#188453),#188457); -#188453 = LINE('',#188454,#188455); -#188454 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188455 = VECTOR('',#188456,1.); -#188456 = DIRECTION('',(1.,0.E+000)); -#188457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188458 = ORIENTED_EDGE('',*,*,#188459,.T.); -#188459 = EDGE_CURVE('',#188437,#187942,#188460,.T.); -#188460 = SURFACE_CURVE('',#188461,(#188466,#188477),.PCURVE_S1.); -#188461 = CIRCLE('',#188462,5.E-002); -#188462 = AXIS2_PLACEMENT_3D('',#188463,#188464,#188465); -#188463 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); -#188464 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188465 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188466 = PCURVE('',#186215,#188467); -#188467 = DEFINITIONAL_REPRESENTATION('',(#188468),#188476); -#188468 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#188469,#188470,#188471, - #188472,#188473,#188474,#188475),.UNSPECIFIED.,.F.,.F.) +#190824 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190825 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#190826 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190827 = ORIENTED_EDGE('',*,*,#190828,.T.); +#190828 = EDGE_CURVE('',#190806,#190829,#190831,.T.); +#190829 = VERTEX_POINT('',#190830); +#190830 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); +#190831 = SURFACE_CURVE('',#190832,(#190836,#190843),.PCURVE_S1.); +#190832 = LINE('',#190833,#190834); +#190833 = CARTESIAN_POINT('',(1.155,-0.70490705433,0.555477601426)); +#190834 = VECTOR('',#190835,1.); +#190835 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#190836 = PCURVE('',#188607,#190837); +#190837 = DEFINITIONAL_REPRESENTATION('',(#190838),#190842); +#190838 = LINE('',#190839,#190840); +#190839 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#190840 = VECTOR('',#190841,1.); +#190841 = DIRECTION('',(-0.993981062721,0.109552028512)); +#190842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190843 = PCURVE('',#190453,#190844); +#190844 = DEFINITIONAL_REPRESENTATION('',(#190845),#190849); +#190845 = LINE('',#190846,#190847); +#190846 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190847 = VECTOR('',#190848,1.); +#190848 = DIRECTION('',(1.,0.E+000)); +#190849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190850 = ORIENTED_EDGE('',*,*,#190851,.T.); +#190851 = EDGE_CURVE('',#190829,#190334,#190852,.T.); +#190852 = SURFACE_CURVE('',#190853,(#190858,#190869),.PCURVE_S1.); +#190853 = CIRCLE('',#190854,5.E-002); +#190854 = AXIS2_PLACEMENT_3D('',#190855,#190856,#190857); +#190855 = CARTESIAN_POINT('',(1.155,-0.655208001194,0.55)); +#190856 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#190857 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#190858 = PCURVE('',#188607,#190859); +#190859 = DEFINITIONAL_REPRESENTATION('',(#190860),#190868); +#190860 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190861,#190862,#190863, + #190864,#190865,#190866,#190867),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#188469 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#188470 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#188471 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#188472 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#188473 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#188474 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#188475 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#188476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188477 = PCURVE('',#187980,#188478); -#188478 = DEFINITIONAL_REPRESENTATION('',(#188479),#188482); -#188479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188480,#188481), +#190861 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#190862 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#190863 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#190864 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#190865 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#190866 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#190867 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#190868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190869 = PCURVE('',#190372,#190870); +#190870 = DEFINITIONAL_REPRESENTATION('',(#190871),#190874); +#190871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190872,#190873), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#188480 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#188481 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#188482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#190872 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#190873 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#190874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#188483 = ORIENTED_EDGE('',*,*,#187941,.T.); -#188484 = ADVANCED_FACE('',(#188485),#187980,.F.); -#188485 = FACE_BOUND('',#188486,.F.); -#188486 = EDGE_LOOP('',(#188487,#188488,#188489,#188509)); -#188487 = ORIENTED_EDGE('',*,*,#187964,.F.); -#188488 = ORIENTED_EDGE('',*,*,#188018,.F.); -#188489 = ORIENTED_EDGE('',*,*,#188490,.T.); -#188490 = EDGE_CURVE('',#188019,#188437,#188491,.T.); -#188491 = SURFACE_CURVE('',#188492,(#188496,#188502),.PCURVE_S1.); -#188492 = LINE('',#188493,#188494); -#188493 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); -#188494 = VECTOR('',#188495,1.); -#188495 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188496 = PCURVE('',#187980,#188497); -#188497 = DEFINITIONAL_REPRESENTATION('',(#188498),#188501); -#188498 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188499,#188500), +#190875 = ORIENTED_EDGE('',*,*,#190333,.T.); +#190876 = ADVANCED_FACE('',(#190877),#190372,.F.); +#190877 = FACE_BOUND('',#190878,.F.); +#190878 = EDGE_LOOP('',(#190879,#190880,#190881,#190901)); +#190879 = ORIENTED_EDGE('',*,*,#190356,.F.); +#190880 = ORIENTED_EDGE('',*,*,#190410,.F.); +#190881 = ORIENTED_EDGE('',*,*,#190882,.T.); +#190882 = EDGE_CURVE('',#190411,#190829,#190883,.T.); +#190883 = SURFACE_CURVE('',#190884,(#190888,#190894),.PCURVE_S1.); +#190884 = LINE('',#190885,#190886); +#190885 = CARTESIAN_POINT('',(0.755,-0.70490705433,0.555477601426)); +#190886 = VECTOR('',#190887,1.); +#190887 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190888 = PCURVE('',#190372,#190889); +#190889 = DEFINITIONAL_REPRESENTATION('',(#190890),#190893); +#190890 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190891,#190892), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188499 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#188500 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#188501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188502 = PCURVE('',#188061,#188503); -#188503 = DEFINITIONAL_REPRESENTATION('',(#188504),#188508); -#188504 = LINE('',#188505,#188506); -#188505 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188506 = VECTOR('',#188507,1.); -#188507 = DIRECTION('',(0.E+000,1.)); -#188508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188509 = ORIENTED_EDGE('',*,*,#188459,.T.); -#188510 = ADVANCED_FACE('',(#188511),#188061,.T.); -#188511 = FACE_BOUND('',#188512,.T.); -#188512 = EDGE_LOOP('',(#188513,#188514,#188515,#188535)); -#188513 = ORIENTED_EDGE('',*,*,#188490,.T.); -#188514 = ORIENTED_EDGE('',*,*,#188436,.F.); -#188515 = ORIENTED_EDGE('',*,*,#188516,.F.); -#188516 = EDGE_CURVE('',#188046,#188414,#188517,.T.); -#188517 = SURFACE_CURVE('',#188518,(#188522,#188529),.PCURVE_S1.); -#188518 = LINE('',#188519,#188520); -#188519 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); -#188520 = VECTOR('',#188521,1.); -#188521 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188522 = PCURVE('',#188061,#188523); -#188523 = DEFINITIONAL_REPRESENTATION('',(#188524),#188528); -#188524 = LINE('',#188525,#188526); -#188525 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#188526 = VECTOR('',#188527,1.); -#188527 = DIRECTION('',(0.E+000,1.)); -#188528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188529 = PCURVE('',#188090,#188530); -#188530 = DEFINITIONAL_REPRESENTATION('',(#188531),#188534); -#188531 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188532,#188533), +#190891 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#190892 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#190893 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190894 = PCURVE('',#190453,#190895); +#190895 = DEFINITIONAL_REPRESENTATION('',(#190896),#190900); +#190896 = LINE('',#190897,#190898); +#190897 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190898 = VECTOR('',#190899,1.); +#190899 = DIRECTION('',(0.E+000,1.)); +#190900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190901 = ORIENTED_EDGE('',*,*,#190851,.T.); +#190902 = ADVANCED_FACE('',(#190903),#190453,.T.); +#190903 = FACE_BOUND('',#190904,.T.); +#190904 = EDGE_LOOP('',(#190905,#190906,#190907,#190927)); +#190905 = ORIENTED_EDGE('',*,*,#190882,.T.); +#190906 = ORIENTED_EDGE('',*,*,#190828,.F.); +#190907 = ORIENTED_EDGE('',*,*,#190908,.F.); +#190908 = EDGE_CURVE('',#190438,#190806,#190909,.T.); +#190909 = SURFACE_CURVE('',#190910,(#190914,#190921),.PCURVE_S1.); +#190910 = LINE('',#190911,#190912); +#190911 = CARTESIAN_POINT('',(0.755,-0.746501027564,0.178089594298)); +#190912 = VECTOR('',#190913,1.); +#190913 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190914 = PCURVE('',#190453,#190915); +#190915 = DEFINITIONAL_REPRESENTATION('',(#190916),#190920); +#190916 = LINE('',#190917,#190918); +#190917 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#190918 = VECTOR('',#190919,1.); +#190919 = DIRECTION('',(0.E+000,1.)); +#190920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190921 = PCURVE('',#190482,#190922); +#190922 = DEFINITIONAL_REPRESENTATION('',(#190923),#190926); +#190923 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190924,#190925), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188532 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#188533 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#188534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188535 = ORIENTED_EDGE('',*,*,#188045,.T.); -#188536 = ADVANCED_FACE('',(#188537),#188090,.T.); -#188537 = FACE_BOUND('',#188538,.T.); -#188538 = EDGE_LOOP('',(#188539,#188540,#188541,#188584)); -#188539 = ORIENTED_EDGE('',*,*,#188516,.T.); -#188540 = ORIENTED_EDGE('',*,*,#188413,.F.); -#188541 = ORIENTED_EDGE('',*,*,#188542,.F.); -#188542 = EDGE_CURVE('',#188074,#188391,#188543,.T.); -#188543 = SURFACE_CURVE('',#188544,(#188548,#188577),.PCURVE_S1.); -#188544 = LINE('',#188545,#188546); -#188545 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); -#188546 = VECTOR('',#188547,1.); -#188547 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188548 = PCURVE('',#188090,#188549); -#188549 = DEFINITIONAL_REPRESENTATION('',(#188550),#188576); -#188550 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188551,#188552,#188553, - #188554,#188555,#188556,#188557,#188558,#188559,#188560,#188561, - #188562,#188563,#188564,#188565,#188566,#188567,#188568,#188569, - #188570,#188571,#188572,#188573,#188574,#188575),.UNSPECIFIED.,.F., +#190924 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#190925 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#190926 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190927 = ORIENTED_EDGE('',*,*,#190437,.T.); +#190928 = ADVANCED_FACE('',(#190929),#190482,.T.); +#190929 = FACE_BOUND('',#190930,.T.); +#190930 = EDGE_LOOP('',(#190931,#190932,#190933,#190976)); +#190931 = ORIENTED_EDGE('',*,*,#190908,.T.); +#190932 = ORIENTED_EDGE('',*,*,#190805,.F.); +#190933 = ORIENTED_EDGE('',*,*,#190934,.F.); +#190934 = EDGE_CURVE('',#190466,#190783,#190935,.T.); +#190935 = SURFACE_CURVE('',#190936,(#190940,#190969),.PCURVE_S1.); +#190936 = LINE('',#190937,#190938); +#190937 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.E+000)); +#190938 = VECTOR('',#190939,1.); +#190939 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190940 = PCURVE('',#190482,#190941); +#190941 = DEFINITIONAL_REPRESENTATION('',(#190942),#190968); +#190942 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190943,#190944,#190945, + #190946,#190947,#190948,#190949,#190950,#190951,#190952,#190953, + #190954,#190955,#190956,#190957,#190958,#190959,#190960,#190961, + #190962,#190963,#190964,#190965,#190966,#190967),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -234213,139 +237215,139 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#188551 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188552 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) - ); -#188553 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) - ); -#188554 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#188555 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) - ); -#188556 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) - ); -#188557 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) - ); -#188558 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); -#188559 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); -#188560 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); -#188561 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); -#188562 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); -#188563 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); -#188564 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); -#188565 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); -#188566 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); -#188567 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); -#188568 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); -#188569 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); -#188570 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); -#188571 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); -#188572 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); -#188573 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); -#188574 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); -#188575 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188576 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188577 = PCURVE('',#188117,#188578); -#188578 = DEFINITIONAL_REPRESENTATION('',(#188579),#188583); -#188579 = LINE('',#188580,#188581); -#188580 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#188581 = VECTOR('',#188582,1.); -#188582 = DIRECTION('',(-1.,0.E+000)); -#188583 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188584 = ORIENTED_EDGE('',*,*,#188073,.T.); -#188585 = ADVANCED_FACE('',(#188586),#188117,.T.); -#188586 = FACE_BOUND('',#188587,.T.); -#188587 = EDGE_LOOP('',(#188588,#188589,#188590,#188611)); -#188588 = ORIENTED_EDGE('',*,*,#188542,.T.); -#188589 = ORIENTED_EDGE('',*,*,#188390,.F.); -#188590 = ORIENTED_EDGE('',*,*,#188591,.F.); -#188591 = EDGE_CURVE('',#188102,#188368,#188592,.T.); -#188592 = SURFACE_CURVE('',#188593,(#188597,#188604),.PCURVE_S1.); -#188593 = LINE('',#188594,#188595); -#188594 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); -#188595 = VECTOR('',#188596,1.); -#188596 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188597 = PCURVE('',#188117,#188598); -#188598 = DEFINITIONAL_REPRESENTATION('',(#188599),#188603); -#188599 = LINE('',#188600,#188601); -#188600 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188601 = VECTOR('',#188602,1.); -#188602 = DIRECTION('',(-1.,0.E+000)); -#188603 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188604 = PCURVE('',#188145,#188605); -#188605 = DEFINITIONAL_REPRESENTATION('',(#188606),#188610); -#188606 = LINE('',#188607,#188608); -#188607 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188608 = VECTOR('',#188609,1.); -#188609 = DIRECTION('',(0.E+000,1.)); -#188610 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188611 = ORIENTED_EDGE('',*,*,#188101,.T.); -#188612 = ADVANCED_FACE('',(#188613),#188145,.T.); -#188613 = FACE_BOUND('',#188614,.T.); -#188614 = EDGE_LOOP('',(#188615,#188616,#188617,#188638)); -#188615 = ORIENTED_EDGE('',*,*,#188591,.T.); -#188616 = ORIENTED_EDGE('',*,*,#188367,.F.); -#188617 = ORIENTED_EDGE('',*,*,#188618,.F.); -#188618 = EDGE_CURVE('',#188130,#188345,#188619,.T.); -#188619 = SURFACE_CURVE('',#188620,(#188624,#188631),.PCURVE_S1.); -#188620 = LINE('',#188621,#188622); -#188621 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); -#188622 = VECTOR('',#188623,1.); -#188623 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188624 = PCURVE('',#188145,#188625); -#188625 = DEFINITIONAL_REPRESENTATION('',(#188626),#188630); -#188626 = LINE('',#188627,#188628); -#188627 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#188628 = VECTOR('',#188629,1.); -#188629 = DIRECTION('',(0.E+000,1.)); -#188630 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188631 = PCURVE('',#188173,#188632); -#188632 = DEFINITIONAL_REPRESENTATION('',(#188633),#188637); -#188633 = LINE('',#188634,#188635); -#188634 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188635 = VECTOR('',#188636,1.); -#188636 = DIRECTION('',(1.,0.E+000)); -#188637 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188638 = ORIENTED_EDGE('',*,*,#188129,.T.); -#188639 = ADVANCED_FACE('',(#188640),#188173,.T.); -#188640 = FACE_BOUND('',#188641,.T.); -#188641 = EDGE_LOOP('',(#188642,#188643,#188644,#188687)); -#188642 = ORIENTED_EDGE('',*,*,#188618,.T.); -#188643 = ORIENTED_EDGE('',*,*,#188344,.F.); -#188644 = ORIENTED_EDGE('',*,*,#188645,.F.); -#188645 = EDGE_CURVE('',#188158,#188318,#188646,.T.); -#188646 = SURFACE_CURVE('',#188647,(#188651,#188658),.PCURVE_S1.); -#188647 = LINE('',#188648,#188649); -#188648 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); -#188649 = VECTOR('',#188650,1.); -#188650 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188651 = PCURVE('',#188173,#188652); -#188652 = DEFINITIONAL_REPRESENTATION('',(#188653),#188657); -#188653 = LINE('',#188654,#188655); -#188654 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#188655 = VECTOR('',#188656,1.); -#188656 = DIRECTION('',(1.,0.E+000)); -#188657 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188658 = PCURVE('',#188206,#188659); -#188659 = DEFINITIONAL_REPRESENTATION('',(#188660),#188686); -#188660 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#188661,#188662,#188663, - #188664,#188665,#188666,#188667,#188668,#188669,#188670,#188671, - #188672,#188673,#188674,#188675,#188676,#188677,#188678,#188679, - #188680,#188681,#188682,#188683,#188684,#188685),.UNSPECIFIED.,.F., +#190943 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190944 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) + ); +#190945 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) + ); +#190946 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#190947 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) + ); +#190948 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) + ); +#190949 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) + ); +#190950 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); +#190951 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); +#190952 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); +#190953 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); +#190954 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); +#190955 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); +#190956 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); +#190957 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); +#190958 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); +#190959 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); +#190960 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); +#190961 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); +#190962 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); +#190963 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); +#190964 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); +#190965 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); +#190966 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); +#190967 = CARTESIAN_POINT('',(0.E+000,0.4)); +#190968 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190969 = PCURVE('',#190509,#190970); +#190970 = DEFINITIONAL_REPRESENTATION('',(#190971),#190975); +#190971 = LINE('',#190972,#190973); +#190972 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#190973 = VECTOR('',#190974,1.); +#190974 = DIRECTION('',(-1.,0.E+000)); +#190975 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190976 = ORIENTED_EDGE('',*,*,#190465,.T.); +#190977 = ADVANCED_FACE('',(#190978),#190509,.T.); +#190978 = FACE_BOUND('',#190979,.T.); +#190979 = EDGE_LOOP('',(#190980,#190981,#190982,#191003)); +#190980 = ORIENTED_EDGE('',*,*,#190934,.T.); +#190981 = ORIENTED_EDGE('',*,*,#190782,.F.); +#190982 = ORIENTED_EDGE('',*,*,#190983,.F.); +#190983 = EDGE_CURVE('',#190494,#190760,#190984,.T.); +#190984 = SURFACE_CURVE('',#190985,(#190989,#190996),.PCURVE_S1.); +#190985 = LINE('',#190986,#190987); +#190986 = CARTESIAN_POINT('',(0.755,-1.17,0.E+000)); +#190987 = VECTOR('',#190988,1.); +#190988 = DIRECTION('',(1.,0.E+000,0.E+000)); +#190989 = PCURVE('',#190509,#190990); +#190990 = DEFINITIONAL_REPRESENTATION('',(#190991),#190995); +#190991 = LINE('',#190992,#190993); +#190992 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#190993 = VECTOR('',#190994,1.); +#190994 = DIRECTION('',(-1.,0.E+000)); +#190995 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#190996 = PCURVE('',#190537,#190997); +#190997 = DEFINITIONAL_REPRESENTATION('',(#190998),#191002); +#190998 = LINE('',#190999,#191000); +#190999 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191000 = VECTOR('',#191001,1.); +#191001 = DIRECTION('',(0.E+000,1.)); +#191002 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191003 = ORIENTED_EDGE('',*,*,#190493,.T.); +#191004 = ADVANCED_FACE('',(#191005),#190537,.T.); +#191005 = FACE_BOUND('',#191006,.T.); +#191006 = EDGE_LOOP('',(#191007,#191008,#191009,#191030)); +#191007 = ORIENTED_EDGE('',*,*,#190983,.T.); +#191008 = ORIENTED_EDGE('',*,*,#190759,.F.); +#191009 = ORIENTED_EDGE('',*,*,#191010,.F.); +#191010 = EDGE_CURVE('',#190522,#190737,#191011,.T.); +#191011 = SURFACE_CURVE('',#191012,(#191016,#191023),.PCURVE_S1.); +#191012 = LINE('',#191013,#191014); +#191013 = CARTESIAN_POINT('',(0.755,-1.17,0.15)); +#191014 = VECTOR('',#191015,1.); +#191015 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191016 = PCURVE('',#190537,#191017); +#191017 = DEFINITIONAL_REPRESENTATION('',(#191018),#191022); +#191018 = LINE('',#191019,#191020); +#191019 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#191020 = VECTOR('',#191021,1.); +#191021 = DIRECTION('',(0.E+000,1.)); +#191022 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191023 = PCURVE('',#190565,#191024); +#191024 = DEFINITIONAL_REPRESENTATION('',(#191025),#191029); +#191025 = LINE('',#191026,#191027); +#191026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191027 = VECTOR('',#191028,1.); +#191028 = DIRECTION('',(1.,0.E+000)); +#191029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191030 = ORIENTED_EDGE('',*,*,#190521,.T.); +#191031 = ADVANCED_FACE('',(#191032),#190565,.T.); +#191032 = FACE_BOUND('',#191033,.T.); +#191033 = EDGE_LOOP('',(#191034,#191035,#191036,#191079)); +#191034 = ORIENTED_EDGE('',*,*,#191010,.T.); +#191035 = ORIENTED_EDGE('',*,*,#190736,.F.); +#191036 = ORIENTED_EDGE('',*,*,#191037,.F.); +#191037 = EDGE_CURVE('',#190550,#190710,#191038,.T.); +#191038 = SURFACE_CURVE('',#191039,(#191043,#191050),.PCURVE_S1.); +#191039 = LINE('',#191040,#191041); +#191040 = CARTESIAN_POINT('',(0.755,-0.945297240108,0.15)); +#191041 = VECTOR('',#191042,1.); +#191042 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191043 = PCURVE('',#190565,#191044); +#191044 = DEFINITIONAL_REPRESENTATION('',(#191045),#191049); +#191045 = LINE('',#191046,#191047); +#191046 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#191047 = VECTOR('',#191048,1.); +#191048 = DIRECTION('',(1.,0.E+000)); +#191049 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191050 = PCURVE('',#190598,#191051); +#191051 = DEFINITIONAL_REPRESENTATION('',(#191052),#191078); +#191052 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#191053,#191054,#191055, + #191056,#191057,#191058,#191059,#191060,#191061,#191062,#191063, + #191064,#191065,#191066,#191067,#191068,#191069,#191070,#191071, + #191072,#191073,#191074,#191075,#191076,#191077),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -234353,954 +237355,954 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#188661 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188662 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) - ); -#188663 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); -#188664 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#188665 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) - ); -#188666 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) - ); -#188667 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) - ); -#188668 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); -#188669 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); -#188670 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); -#188671 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); -#188672 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); -#188673 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); -#188674 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); -#188675 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); -#188676 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); -#188677 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); -#188678 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); -#188679 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#188680 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); -#188681 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); -#188682 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); -#188683 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); -#188684 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); -#188685 = CARTESIAN_POINT('',(0.E+000,0.4)); -#188686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188687 = ORIENTED_EDGE('',*,*,#188157,.T.); -#188688 = ADVANCED_FACE('',(#188689),#188206,.F.); -#188689 = FACE_BOUND('',#188690,.F.); -#188690 = EDGE_LOOP('',(#188691,#188692,#188693,#188713)); -#188691 = ORIENTED_EDGE('',*,*,#188645,.F.); -#188692 = ORIENTED_EDGE('',*,*,#188185,.F.); -#188693 = ORIENTED_EDGE('',*,*,#188694,.T.); -#188694 = EDGE_CURVE('',#188186,#188295,#188695,.T.); -#188695 = SURFACE_CURVE('',#188696,(#188700,#188706),.PCURVE_S1.); -#188696 = LINE('',#188697,#188698); -#188697 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); -#188698 = VECTOR('',#188699,1.); -#188699 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188700 = PCURVE('',#188206,#188701); -#188701 = DEFINITIONAL_REPRESENTATION('',(#188702),#188705); -#188702 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188703,#188704), +#191053 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191054 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) + ); +#191055 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); +#191056 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#191057 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) + ); +#191058 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) + ); +#191059 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) + ); +#191060 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); +#191061 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); +#191062 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); +#191063 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); +#191064 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); +#191065 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); +#191066 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); +#191067 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); +#191068 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); +#191069 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); +#191070 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); +#191071 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#191072 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); +#191073 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); +#191074 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); +#191075 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); +#191076 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); +#191077 = CARTESIAN_POINT('',(0.E+000,0.4)); +#191078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191079 = ORIENTED_EDGE('',*,*,#190549,.T.); +#191080 = ADVANCED_FACE('',(#191081),#190598,.F.); +#191081 = FACE_BOUND('',#191082,.F.); +#191082 = EDGE_LOOP('',(#191083,#191084,#191085,#191105)); +#191083 = ORIENTED_EDGE('',*,*,#191037,.F.); +#191084 = ORIENTED_EDGE('',*,*,#190577,.F.); +#191085 = ORIENTED_EDGE('',*,*,#191086,.T.); +#191086 = EDGE_CURVE('',#190578,#190687,#191087,.T.); +#191087 = SURFACE_CURVE('',#191088,(#191092,#191098),.PCURVE_S1.); +#191088 = LINE('',#191089,#191090); +#191089 = CARTESIAN_POINT('',(0.755,-0.895598186972,0.194522398574)); +#191090 = VECTOR('',#191091,1.); +#191091 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191092 = PCURVE('',#190598,#191093); +#191093 = DEFINITIONAL_REPRESENTATION('',(#191094),#191097); +#191094 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191095,#191096), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188703 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#188704 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#188705 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188706 = PCURVE('',#188233,#188707); -#188707 = DEFINITIONAL_REPRESENTATION('',(#188708),#188712); -#188708 = LINE('',#188709,#188710); -#188709 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188710 = VECTOR('',#188711,1.); -#188711 = DIRECTION('',(0.E+000,1.)); -#188712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188713 = ORIENTED_EDGE('',*,*,#188317,.T.); -#188714 = ADVANCED_FACE('',(#188715),#188233,.T.); -#188715 = FACE_BOUND('',#188716,.T.); -#188716 = EDGE_LOOP('',(#188717,#188718,#188719,#188739)); -#188717 = ORIENTED_EDGE('',*,*,#188694,.T.); -#188718 = ORIENTED_EDGE('',*,*,#188294,.F.); -#188719 = ORIENTED_EDGE('',*,*,#188720,.F.); -#188720 = EDGE_CURVE('',#188218,#188272,#188721,.T.); -#188721 = SURFACE_CURVE('',#188722,(#188726,#188733),.PCURVE_S1.); -#188722 = LINE('',#188723,#188724); -#188723 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); -#188724 = VECTOR('',#188725,1.); -#188725 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188726 = PCURVE('',#188233,#188727); -#188727 = DEFINITIONAL_REPRESENTATION('',(#188728),#188732); -#188728 = LINE('',#188729,#188730); -#188729 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#188730 = VECTOR('',#188731,1.); -#188731 = DIRECTION('',(0.E+000,1.)); -#188732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188733 = PCURVE('',#187905,#188734); -#188734 = DEFINITIONAL_REPRESENTATION('',(#188735),#188738); -#188735 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188736,#188737), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188736 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#188737 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#188738 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188739 = ORIENTED_EDGE('',*,*,#188217,.T.); -#188740 = ADVANCED_FACE('',(#188741),#187905,.T.); -#188741 = FACE_BOUND('',#188742,.T.); -#188742 = EDGE_LOOP('',(#188743,#188744,#188745,#188746)); -#188743 = ORIENTED_EDGE('',*,*,#188720,.T.); -#188744 = ORIENTED_EDGE('',*,*,#188271,.F.); -#188745 = ORIENTED_EDGE('',*,*,#187889,.F.); -#188746 = ORIENTED_EDGE('',*,*,#188245,.T.); -#188747 = ADVANCED_FACE('',(#188748),#186913,.T.); -#188748 = FACE_BOUND('',#188749,.T.); -#188749 = EDGE_LOOP('',(#188750,#188751,#188774,#188801)); -#188750 = ORIENTED_EDGE('',*,*,#186899,.T.); -#188751 = ORIENTED_EDGE('',*,*,#188752,.T.); -#188752 = EDGE_CURVE('',#185542,#188753,#188755,.T.); -#188753 = VERTEX_POINT('',#188754); -#188754 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#188755 = SURFACE_CURVE('',#188756,(#188760,#188767),.PCURVE_S1.); -#188756 = LINE('',#188757,#188758); -#188757 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#188758 = VECTOR('',#188759,1.); -#188759 = DIRECTION('',(0.E+000,1.,0.E+000)); -#188760 = PCURVE('',#186913,#188761); -#188761 = DEFINITIONAL_REPRESENTATION('',(#188762),#188766); -#188762 = LINE('',#188763,#188764); -#188763 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188764 = VECTOR('',#188765,1.); -#188765 = DIRECTION('',(0.E+000,1.)); -#188766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188767 = PCURVE('',#185557,#188768); -#188768 = DEFINITIONAL_REPRESENTATION('',(#188769),#188773); -#188769 = LINE('',#188770,#188771); -#188770 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#188771 = VECTOR('',#188772,1.); -#188772 = DIRECTION('',(0.E+000,1.)); -#188773 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188774 = ORIENTED_EDGE('',*,*,#188775,.T.); -#188775 = EDGE_CURVE('',#188753,#188776,#188778,.T.); -#188776 = VERTEX_POINT('',#188777); -#188777 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); -#188778 = SURFACE_CURVE('',#188779,(#188783,#188790),.PCURVE_S1.); -#188779 = LINE('',#188780,#188781); -#188780 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); -#188781 = VECTOR('',#188782,1.); -#188782 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188783 = PCURVE('',#186913,#188784); -#188784 = DEFINITIONAL_REPRESENTATION('',(#188785),#188789); -#188785 = LINE('',#188786,#188787); -#188786 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188787 = VECTOR('',#188788,1.); -#188788 = DIRECTION('',(-1.,0.E+000)); -#188789 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188790 = PCURVE('',#188791,#188796); -#188791 = CYLINDRICAL_SURFACE('',#188792,5.E-002); -#188792 = AXIS2_PLACEMENT_3D('',#188793,#188794,#188795); -#188793 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#188794 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188795 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188796 = DEFINITIONAL_REPRESENTATION('',(#188797),#188800); -#188797 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188798,#188799), +#191095 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#191096 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#191097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191098 = PCURVE('',#190625,#191099); +#191099 = DEFINITIONAL_REPRESENTATION('',(#191100),#191104); +#191100 = LINE('',#191101,#191102); +#191101 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191102 = VECTOR('',#191103,1.); +#191103 = DIRECTION('',(0.E+000,1.)); +#191104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191105 = ORIENTED_EDGE('',*,*,#190709,.T.); +#191106 = ADVANCED_FACE('',(#191107),#190625,.T.); +#191107 = FACE_BOUND('',#191108,.T.); +#191108 = EDGE_LOOP('',(#191109,#191110,#191111,#191131)); +#191109 = ORIENTED_EDGE('',*,*,#191086,.T.); +#191110 = ORIENTED_EDGE('',*,*,#190686,.F.); +#191111 = ORIENTED_EDGE('',*,*,#191112,.F.); +#191112 = EDGE_CURVE('',#190610,#190664,#191113,.T.); +#191113 = SURFACE_CURVE('',#191114,(#191118,#191125),.PCURVE_S1.); +#191114 = LINE('',#191115,#191116); +#191115 = CARTESIAN_POINT('',(0.755,-0.854004213739,0.571910405702)); +#191116 = VECTOR('',#191117,1.); +#191117 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191118 = PCURVE('',#190625,#191119); +#191119 = DEFINITIONAL_REPRESENTATION('',(#191120),#191124); +#191120 = LINE('',#191121,#191122); +#191121 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#191122 = VECTOR('',#191123,1.); +#191123 = DIRECTION('',(0.E+000,1.)); +#191124 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191125 = PCURVE('',#190297,#191126); +#191126 = DEFINITIONAL_REPRESENTATION('',(#191127),#191130); +#191127 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191128,#191129), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188798 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#188799 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#188800 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188801 = ORIENTED_EDGE('',*,*,#188802,.F.); -#188802 = EDGE_CURVE('',#185458,#188776,#188803,.T.); -#188803 = SURFACE_CURVE('',#188804,(#188808,#188815),.PCURVE_S1.); -#188804 = LINE('',#188805,#188806); -#188805 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); -#188806 = VECTOR('',#188807,1.); -#188807 = DIRECTION('',(0.E+000,1.,0.E+000)); -#188808 = PCURVE('',#186913,#188809); -#188809 = DEFINITIONAL_REPRESENTATION('',(#188810),#188814); -#188810 = LINE('',#188811,#188812); -#188811 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#188812 = VECTOR('',#188813,1.); -#188813 = DIRECTION('',(0.E+000,1.)); -#188814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188815 = PCURVE('',#185501,#188816); -#188816 = DEFINITIONAL_REPRESENTATION('',(#188817),#188821); -#188817 = LINE('',#188818,#188819); -#188818 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#188819 = VECTOR('',#188820,1.); -#188820 = DIRECTION('',(0.E+000,1.)); -#188821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188822 = ADVANCED_FACE('',(#188823),#185529,.T.); -#188823 = FACE_BOUND('',#188824,.T.); -#188824 = EDGE_LOOP('',(#188825,#188826,#188849,#188876)); -#188825 = ORIENTED_EDGE('',*,*,#185513,.F.); -#188826 = ORIENTED_EDGE('',*,*,#188827,.F.); -#188827 = EDGE_CURVE('',#188828,#185486,#188830,.T.); -#188828 = VERTEX_POINT('',#188829); -#188829 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); -#188830 = SURFACE_CURVE('',#188831,(#188835,#188842),.PCURVE_S1.); -#188831 = LINE('',#188832,#188833); -#188832 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); -#188833 = VECTOR('',#188834,1.); -#188834 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188835 = PCURVE('',#185529,#188836); -#188836 = DEFINITIONAL_REPRESENTATION('',(#188837),#188841); -#188837 = LINE('',#188838,#188839); -#188838 = CARTESIAN_POINT('',(0.4,0.E+000)); -#188839 = VECTOR('',#188840,1.); -#188840 = DIRECTION('',(0.E+000,-1.)); -#188841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188842 = PCURVE('',#185501,#188843); -#188843 = DEFINITIONAL_REPRESENTATION('',(#188844),#188848); -#188844 = LINE('',#188845,#188846); -#188845 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#188846 = VECTOR('',#188847,1.); -#188847 = DIRECTION('',(0.E+000,-1.)); -#188848 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188849 = ORIENTED_EDGE('',*,*,#188850,.F.); -#188850 = EDGE_CURVE('',#188851,#188828,#188853,.T.); -#188851 = VERTEX_POINT('',#188852); -#188852 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#188853 = SURFACE_CURVE('',#188854,(#188858,#188865),.PCURVE_S1.); -#188854 = LINE('',#188855,#188856); -#188855 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#188856 = VECTOR('',#188857,1.); -#188857 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188858 = PCURVE('',#185529,#188859); -#188859 = DEFINITIONAL_REPRESENTATION('',(#188860),#188864); -#188860 = LINE('',#188861,#188862); -#188861 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188862 = VECTOR('',#188863,1.); -#188863 = DIRECTION('',(1.,0.E+000)); -#188864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188865 = PCURVE('',#188866,#188871); -#188866 = CYLINDRICAL_SURFACE('',#188867,0.2); -#188867 = AXIS2_PLACEMENT_3D('',#188868,#188869,#188870); -#188868 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#188869 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188870 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188871 = DEFINITIONAL_REPRESENTATION('',(#188872),#188875); -#188872 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188873,#188874), +#191128 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#191129 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#191130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191131 = ORIENTED_EDGE('',*,*,#190609,.T.); +#191132 = ADVANCED_FACE('',(#191133),#190297,.T.); +#191133 = FACE_BOUND('',#191134,.T.); +#191134 = EDGE_LOOP('',(#191135,#191136,#191137,#191138)); +#191135 = ORIENTED_EDGE('',*,*,#191112,.T.); +#191136 = ORIENTED_EDGE('',*,*,#190663,.F.); +#191137 = ORIENTED_EDGE('',*,*,#190281,.F.); +#191138 = ORIENTED_EDGE('',*,*,#190637,.T.); +#191139 = ADVANCED_FACE('',(#191140),#189305,.T.); +#191140 = FACE_BOUND('',#191141,.T.); +#191141 = EDGE_LOOP('',(#191142,#191143,#191166,#191193)); +#191142 = ORIENTED_EDGE('',*,*,#189291,.T.); +#191143 = ORIENTED_EDGE('',*,*,#191144,.T.); +#191144 = EDGE_CURVE('',#187934,#191145,#191147,.T.); +#191145 = VERTEX_POINT('',#191146); +#191146 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#191147 = SURFACE_CURVE('',#191148,(#191152,#191159),.PCURVE_S1.); +#191148 = LINE('',#191149,#191150); +#191149 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#191150 = VECTOR('',#191151,1.); +#191151 = DIRECTION('',(0.E+000,1.,0.E+000)); +#191152 = PCURVE('',#189305,#191153); +#191153 = DEFINITIONAL_REPRESENTATION('',(#191154),#191158); +#191154 = LINE('',#191155,#191156); +#191155 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191156 = VECTOR('',#191157,1.); +#191157 = DIRECTION('',(0.E+000,1.)); +#191158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191159 = PCURVE('',#187949,#191160); +#191160 = DEFINITIONAL_REPRESENTATION('',(#191161),#191165); +#191161 = LINE('',#191162,#191163); +#191162 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#191163 = VECTOR('',#191164,1.); +#191164 = DIRECTION('',(0.E+000,1.)); +#191165 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191166 = ORIENTED_EDGE('',*,*,#191167,.T.); +#191167 = EDGE_CURVE('',#191145,#191168,#191170,.T.); +#191168 = VERTEX_POINT('',#191169); +#191169 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); +#191170 = SURFACE_CURVE('',#191171,(#191175,#191182),.PCURVE_S1.); +#191171 = LINE('',#191172,#191173); +#191172 = CARTESIAN_POINT('',(0.755,0.655208001194,0.6)); +#191173 = VECTOR('',#191174,1.); +#191174 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191175 = PCURVE('',#189305,#191176); +#191176 = DEFINITIONAL_REPRESENTATION('',(#191177),#191181); +#191177 = LINE('',#191178,#191179); +#191178 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191179 = VECTOR('',#191180,1.); +#191180 = DIRECTION('',(-1.,0.E+000)); +#191181 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191182 = PCURVE('',#191183,#191188); +#191183 = CYLINDRICAL_SURFACE('',#191184,5.E-002); +#191184 = AXIS2_PLACEMENT_3D('',#191185,#191186,#191187); +#191185 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#191186 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191187 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191188 = DEFINITIONAL_REPRESENTATION('',(#191189),#191192); +#191189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191190,#191191), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#188873 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#188874 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#188875 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#191190 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#191191 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#191192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#188876 = ORIENTED_EDGE('',*,*,#188877,.T.); -#188877 = EDGE_CURVE('',#188851,#185514,#188878,.T.); -#188878 = SURFACE_CURVE('',#188879,(#188883,#188890),.PCURVE_S1.); -#188879 = LINE('',#188880,#188881); -#188880 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); -#188881 = VECTOR('',#188882,1.); -#188882 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188883 = PCURVE('',#185529,#188884); -#188884 = DEFINITIONAL_REPRESENTATION('',(#188885),#188889); -#188885 = LINE('',#188886,#188887); -#188886 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188887 = VECTOR('',#188888,1.); -#188888 = DIRECTION('',(0.E+000,-1.)); -#188889 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#191193 = ORIENTED_EDGE('',*,*,#191194,.F.); +#191194 = EDGE_CURVE('',#187850,#191168,#191195,.T.); +#191195 = SURFACE_CURVE('',#191196,(#191200,#191207),.PCURVE_S1.); +#191196 = LINE('',#191197,#191198); +#191197 = CARTESIAN_POINT('',(1.155,0.655208001194,0.6)); +#191198 = VECTOR('',#191199,1.); +#191199 = DIRECTION('',(0.E+000,1.,0.E+000)); +#191200 = PCURVE('',#189305,#191201); +#191201 = DEFINITIONAL_REPRESENTATION('',(#191202),#191206); +#191202 = LINE('',#191203,#191204); +#191203 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#191204 = VECTOR('',#191205,1.); +#191205 = DIRECTION('',(0.E+000,1.)); +#191206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191207 = PCURVE('',#187893,#191208); +#191208 = DEFINITIONAL_REPRESENTATION('',(#191209),#191213); +#191209 = LINE('',#191210,#191211); +#191210 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#191211 = VECTOR('',#191212,1.); +#191212 = DIRECTION('',(0.E+000,1.)); +#191213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191214 = ADVANCED_FACE('',(#191215),#187921,.T.); +#191215 = FACE_BOUND('',#191216,.T.); +#191216 = EDGE_LOOP('',(#191217,#191218,#191241,#191268)); +#191217 = ORIENTED_EDGE('',*,*,#187905,.F.); +#191218 = ORIENTED_EDGE('',*,*,#191219,.F.); +#191219 = EDGE_CURVE('',#191220,#187878,#191222,.T.); +#191220 = VERTEX_POINT('',#191221); +#191221 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); +#191222 = SURFACE_CURVE('',#191223,(#191227,#191234),.PCURVE_S1.); +#191223 = LINE('',#191224,#191225); +#191224 = CARTESIAN_POINT('',(1.155,0.655208001194,0.75)); +#191225 = VECTOR('',#191226,1.); +#191226 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#191227 = PCURVE('',#187921,#191228); +#191228 = DEFINITIONAL_REPRESENTATION('',(#191229),#191233); +#191229 = LINE('',#191230,#191231); +#191230 = CARTESIAN_POINT('',(0.4,0.E+000)); +#191231 = VECTOR('',#191232,1.); +#191232 = DIRECTION('',(0.E+000,-1.)); +#191233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191234 = PCURVE('',#187893,#191235); +#191235 = DEFINITIONAL_REPRESENTATION('',(#191236),#191240); +#191236 = LINE('',#191237,#191238); +#191237 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#191238 = VECTOR('',#191239,1.); +#191239 = DIRECTION('',(0.E+000,-1.)); +#191240 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191241 = ORIENTED_EDGE('',*,*,#191242,.F.); +#191242 = EDGE_CURVE('',#191243,#191220,#191245,.T.); +#191243 = VERTEX_POINT('',#191244); +#191244 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#191245 = SURFACE_CURVE('',#191246,(#191250,#191257),.PCURVE_S1.); +#191246 = LINE('',#191247,#191248); +#191247 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#191248 = VECTOR('',#191249,1.); +#191249 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191250 = PCURVE('',#187921,#191251); +#191251 = DEFINITIONAL_REPRESENTATION('',(#191252),#191256); +#191252 = LINE('',#191253,#191254); +#191253 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191254 = VECTOR('',#191255,1.); +#191255 = DIRECTION('',(1.,0.E+000)); +#191256 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191257 = PCURVE('',#191258,#191263); +#191258 = CYLINDRICAL_SURFACE('',#191259,0.2); +#191259 = AXIS2_PLACEMENT_3D('',#191260,#191261,#191262); +#191260 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#191261 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191262 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191263 = DEFINITIONAL_REPRESENTATION('',(#191264),#191267); +#191264 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191265,#191266), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#191265 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#191266 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#191267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191268 = ORIENTED_EDGE('',*,*,#191269,.T.); +#191269 = EDGE_CURVE('',#191243,#187906,#191270,.T.); +#191270 = SURFACE_CURVE('',#191271,(#191275,#191282),.PCURVE_S1.); +#191271 = LINE('',#191272,#191273); +#191272 = CARTESIAN_POINT('',(0.755,0.655208001194,0.75)); +#191273 = VECTOR('',#191274,1.); +#191274 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#191275 = PCURVE('',#187921,#191276); +#191276 = DEFINITIONAL_REPRESENTATION('',(#191277),#191281); +#191277 = LINE('',#191278,#191279); +#191278 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191279 = VECTOR('',#191280,1.); +#191280 = DIRECTION('',(0.E+000,-1.)); +#191281 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191282 = PCURVE('',#187949,#191283); +#191283 = DEFINITIONAL_REPRESENTATION('',(#191284),#191288); +#191284 = LINE('',#191285,#191286); +#191285 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#191286 = VECTOR('',#191287,1.); +#191287 = DIRECTION('',(0.E+000,-1.)); +#191288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#188890 = PCURVE('',#185557,#188891); -#188891 = DEFINITIONAL_REPRESENTATION('',(#188892),#188896); -#188892 = LINE('',#188893,#188894); -#188893 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#188894 = VECTOR('',#188895,1.); -#188895 = DIRECTION('',(0.E+000,-1.)); -#188896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188897 = ADVANCED_FACE('',(#188898),#185557,.F.); -#188898 = FACE_BOUND('',#188899,.T.); -#188899 = EDGE_LOOP('',(#188900,#188901,#188902,#188903,#188926,#188954, - #188986,#189014,#189042,#189070,#189098,#189126)); -#188900 = ORIENTED_EDGE('',*,*,#188752,.F.); -#188901 = ORIENTED_EDGE('',*,*,#185541,.T.); -#188902 = ORIENTED_EDGE('',*,*,#188877,.F.); -#188903 = ORIENTED_EDGE('',*,*,#188904,.F.); -#188904 = EDGE_CURVE('',#188905,#188851,#188907,.T.); -#188905 = VERTEX_POINT('',#188906); -#188906 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); -#188907 = SURFACE_CURVE('',#188908,(#188913,#188920),.PCURVE_S1.); -#188908 = CIRCLE('',#188909,0.2); -#188909 = AXIS2_PLACEMENT_3D('',#188910,#188911,#188912); -#188910 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#188911 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188912 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188913 = PCURVE('',#185557,#188914); -#188914 = DEFINITIONAL_REPRESENTATION('',(#188915),#188919); -#188915 = CIRCLE('',#188916,0.2); -#188916 = AXIS2_PLACEMENT_2D('',#188917,#188918); -#188917 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188918 = DIRECTION('',(1.,0.E+000)); -#188919 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188920 = PCURVE('',#188866,#188921); -#188921 = DEFINITIONAL_REPRESENTATION('',(#188922),#188925); -#188922 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188923,#188924), +#191289 = ADVANCED_FACE('',(#191290),#187949,.F.); +#191290 = FACE_BOUND('',#191291,.T.); +#191291 = EDGE_LOOP('',(#191292,#191293,#191294,#191295,#191318,#191346, + #191378,#191406,#191434,#191462,#191490,#191518)); +#191292 = ORIENTED_EDGE('',*,*,#191144,.F.); +#191293 = ORIENTED_EDGE('',*,*,#187933,.T.); +#191294 = ORIENTED_EDGE('',*,*,#191269,.F.); +#191295 = ORIENTED_EDGE('',*,*,#191296,.F.); +#191296 = EDGE_CURVE('',#191297,#191243,#191299,.T.); +#191297 = VERTEX_POINT('',#191298); +#191298 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); +#191299 = SURFACE_CURVE('',#191300,(#191305,#191312),.PCURVE_S1.); +#191300 = CIRCLE('',#191301,0.2); +#191301 = AXIS2_PLACEMENT_3D('',#191302,#191303,#191304); +#191302 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#191303 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191304 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191305 = PCURVE('',#187949,#191306); +#191306 = DEFINITIONAL_REPRESENTATION('',(#191307),#191311); +#191307 = CIRCLE('',#191308,0.2); +#191308 = AXIS2_PLACEMENT_2D('',#191309,#191310); +#191309 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191310 = DIRECTION('',(1.,0.E+000)); +#191311 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191312 = PCURVE('',#191258,#191313); +#191313 = DEFINITIONAL_REPRESENTATION('',(#191314),#191317); +#191314 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191315,#191316), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#188923 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#188924 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#188925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188926 = ORIENTED_EDGE('',*,*,#188927,.F.); -#188927 = EDGE_CURVE('',#188928,#188905,#188930,.T.); -#188928 = VERTEX_POINT('',#188929); -#188929 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#188930 = SURFACE_CURVE('',#188931,(#188935,#188942),.PCURVE_S1.); -#188931 = LINE('',#188932,#188933); -#188932 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#188933 = VECTOR('',#188934,1.); -#188934 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#188935 = PCURVE('',#185557,#188936); -#188936 = DEFINITIONAL_REPRESENTATION('',(#188937),#188941); -#188937 = LINE('',#188938,#188939); -#188938 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#188939 = VECTOR('',#188940,1.); -#188940 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#188941 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188942 = PCURVE('',#188943,#188948); -#188943 = PLANE('',#188944); -#188944 = AXIS2_PLACEMENT_3D('',#188945,#188946,#188947); -#188945 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#188946 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#188947 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#188948 = DEFINITIONAL_REPRESENTATION('',(#188949),#188953); -#188949 = LINE('',#188950,#188951); -#188950 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#188951 = VECTOR('',#188952,1.); -#188952 = DIRECTION('',(1.,0.E+000)); -#188953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188954 = ORIENTED_EDGE('',*,*,#188955,.F.); -#188955 = EDGE_CURVE('',#188956,#188928,#188958,.T.); -#188956 = VERTEX_POINT('',#188957); -#188957 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); -#188958 = SURFACE_CURVE('',#188959,(#188964,#188975),.PCURVE_S1.); -#188959 = CIRCLE('',#188960,5.E-002); -#188960 = AXIS2_PLACEMENT_3D('',#188961,#188962,#188963); -#188961 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#188962 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#188963 = DIRECTION('',(0.E+000,0.E+000,1.)); -#188964 = PCURVE('',#185557,#188965); -#188965 = DEFINITIONAL_REPRESENTATION('',(#188966),#188974); -#188966 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#188967,#188968,#188969, - #188970,#188971,#188972,#188973),.UNSPECIFIED.,.F.,.F.) +#191315 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#191316 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#191317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191318 = ORIENTED_EDGE('',*,*,#191319,.F.); +#191319 = EDGE_CURVE('',#191320,#191297,#191322,.T.); +#191320 = VERTEX_POINT('',#191321); +#191321 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#191322 = SURFACE_CURVE('',#191323,(#191327,#191334),.PCURVE_S1.); +#191323 = LINE('',#191324,#191325); +#191324 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#191325 = VECTOR('',#191326,1.); +#191326 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#191327 = PCURVE('',#187949,#191328); +#191328 = DEFINITIONAL_REPRESENTATION('',(#191329),#191333); +#191329 = LINE('',#191330,#191331); +#191330 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#191331 = VECTOR('',#191332,1.); +#191332 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#191333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191334 = PCURVE('',#191335,#191340); +#191335 = PLANE('',#191336); +#191336 = AXIS2_PLACEMENT_3D('',#191337,#191338,#191339); +#191337 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#191338 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#191339 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#191340 = DEFINITIONAL_REPRESENTATION('',(#191341),#191345); +#191341 = LINE('',#191342,#191343); +#191342 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191343 = VECTOR('',#191344,1.); +#191344 = DIRECTION('',(1.,0.E+000)); +#191345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191346 = ORIENTED_EDGE('',*,*,#191347,.F.); +#191347 = EDGE_CURVE('',#191348,#191320,#191350,.T.); +#191348 = VERTEX_POINT('',#191349); +#191349 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); +#191350 = SURFACE_CURVE('',#191351,(#191356,#191367),.PCURVE_S1.); +#191351 = CIRCLE('',#191352,5.E-002); +#191352 = AXIS2_PLACEMENT_3D('',#191353,#191354,#191355); +#191353 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#191354 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#191355 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191356 = PCURVE('',#187949,#191357); +#191357 = DEFINITIONAL_REPRESENTATION('',(#191358),#191366); +#191358 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191359,#191360,#191361, + #191362,#191363,#191364,#191365),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#188967 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#188968 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#188969 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#188970 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#188971 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#188972 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#188973 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#188974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188975 = PCURVE('',#188976,#188981); -#188976 = CYLINDRICAL_SURFACE('',#188977,5.E-002); -#188977 = AXIS2_PLACEMENT_3D('',#188978,#188979,#188980); -#188978 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#188979 = DIRECTION('',(1.,0.E+000,0.E+000)); -#188980 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#188981 = DEFINITIONAL_REPRESENTATION('',(#188982),#188985); -#188982 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#188983,#188984), +#191359 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#191360 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#191361 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#191362 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#191363 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#191364 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#191365 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#191366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191367 = PCURVE('',#191368,#191373); +#191368 = CYLINDRICAL_SURFACE('',#191369,5.E-002); +#191369 = AXIS2_PLACEMENT_3D('',#191370,#191371,#191372); +#191370 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#191371 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191372 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191373 = DEFINITIONAL_REPRESENTATION('',(#191374),#191377); +#191374 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191375,#191376), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#188983 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#188984 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#188985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#188986 = ORIENTED_EDGE('',*,*,#188987,.F.); -#188987 = EDGE_CURVE('',#188988,#188956,#188990,.T.); -#188988 = VERTEX_POINT('',#188989); -#188989 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#188990 = SURFACE_CURVE('',#188991,(#188995,#189002),.PCURVE_S1.); -#188991 = LINE('',#188992,#188993); -#188992 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#188993 = VECTOR('',#188994,1.); -#188994 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#188995 = PCURVE('',#185557,#188996); -#188996 = DEFINITIONAL_REPRESENTATION('',(#188997),#189001); -#188997 = LINE('',#188998,#188999); -#188998 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#188999 = VECTOR('',#189000,1.); -#189000 = DIRECTION('',(0.E+000,-1.)); -#189001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189002 = PCURVE('',#189003,#189008); -#189003 = PLANE('',#189004); -#189004 = AXIS2_PLACEMENT_3D('',#189005,#189006,#189007); -#189005 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#189006 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189007 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189008 = DEFINITIONAL_REPRESENTATION('',(#189009),#189013); -#189009 = LINE('',#189010,#189011); -#189010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189011 = VECTOR('',#189012,1.); -#189012 = DIRECTION('',(0.E+000,-1.)); -#189013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189014 = ORIENTED_EDGE('',*,*,#189015,.F.); -#189015 = EDGE_CURVE('',#189016,#188988,#189018,.T.); -#189016 = VERTEX_POINT('',#189017); -#189017 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189018 = SURFACE_CURVE('',#189019,(#189023,#189030),.PCURVE_S1.); -#189019 = LINE('',#189020,#189021); -#189020 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189021 = VECTOR('',#189022,1.); -#189022 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189023 = PCURVE('',#185557,#189024); -#189024 = DEFINITIONAL_REPRESENTATION('',(#189025),#189029); -#189025 = LINE('',#189026,#189027); -#189026 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189027 = VECTOR('',#189028,1.); -#189028 = DIRECTION('',(-1.,0.E+000)); -#189029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189030 = PCURVE('',#189031,#189036); -#189031 = PLANE('',#189032); -#189032 = AXIS2_PLACEMENT_3D('',#189033,#189034,#189035); -#189033 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189034 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189035 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189036 = DEFINITIONAL_REPRESENTATION('',(#189037),#189041); -#189037 = LINE('',#189038,#189039); -#189038 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189039 = VECTOR('',#189040,1.); -#189040 = DIRECTION('',(1.,0.E+000)); -#189041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189042 = ORIENTED_EDGE('',*,*,#189043,.F.); -#189043 = EDGE_CURVE('',#189044,#189016,#189046,.T.); -#189044 = VERTEX_POINT('',#189045); -#189045 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); -#189046 = SURFACE_CURVE('',#189047,(#189051,#189058),.PCURVE_S1.); -#189047 = LINE('',#189048,#189049); -#189048 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189049 = VECTOR('',#189050,1.); -#189050 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189051 = PCURVE('',#185557,#189052); -#189052 = DEFINITIONAL_REPRESENTATION('',(#189053),#189057); -#189053 = LINE('',#189054,#189055); -#189054 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189055 = VECTOR('',#189056,1.); -#189056 = DIRECTION('',(0.E+000,1.)); -#189057 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189058 = PCURVE('',#189059,#189064); -#189059 = PLANE('',#189060); -#189060 = AXIS2_PLACEMENT_3D('',#189061,#189062,#189063); -#189061 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189062 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189063 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189064 = DEFINITIONAL_REPRESENTATION('',(#189065),#189069); -#189065 = LINE('',#189066,#189067); -#189066 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189067 = VECTOR('',#189068,1.); -#189068 = DIRECTION('',(0.E+000,1.)); -#189069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189070 = ORIENTED_EDGE('',*,*,#189071,.F.); -#189071 = EDGE_CURVE('',#189072,#189044,#189074,.T.); -#189072 = VERTEX_POINT('',#189073); -#189073 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); -#189074 = SURFACE_CURVE('',#189075,(#189080,#189087),.PCURVE_S1.); -#189075 = CIRCLE('',#189076,0.2); -#189076 = AXIS2_PLACEMENT_3D('',#189077,#189078,#189079); -#189077 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#189078 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189079 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189080 = PCURVE('',#185557,#189081); -#189081 = DEFINITIONAL_REPRESENTATION('',(#189082),#189086); -#189082 = CIRCLE('',#189083,0.2); -#189083 = AXIS2_PLACEMENT_2D('',#189084,#189085); -#189084 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#189085 = DIRECTION('',(1.,0.E+000)); -#189086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189087 = PCURVE('',#189088,#189093); -#189088 = CYLINDRICAL_SURFACE('',#189089,0.2); -#189089 = AXIS2_PLACEMENT_3D('',#189090,#189091,#189092); -#189090 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); -#189091 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189092 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189093 = DEFINITIONAL_REPRESENTATION('',(#189094),#189097); -#189094 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189095,#189096), +#191375 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#191376 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#191377 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191378 = ORIENTED_EDGE('',*,*,#191379,.F.); +#191379 = EDGE_CURVE('',#191380,#191348,#191382,.T.); +#191380 = VERTEX_POINT('',#191381); +#191381 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#191382 = SURFACE_CURVE('',#191383,(#191387,#191394),.PCURVE_S1.); +#191383 = LINE('',#191384,#191385); +#191384 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#191385 = VECTOR('',#191386,1.); +#191386 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#191387 = PCURVE('',#187949,#191388); +#191388 = DEFINITIONAL_REPRESENTATION('',(#191389),#191393); +#191389 = LINE('',#191390,#191391); +#191390 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#191391 = VECTOR('',#191392,1.); +#191392 = DIRECTION('',(0.E+000,-1.)); +#191393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191394 = PCURVE('',#191395,#191400); +#191395 = PLANE('',#191396); +#191396 = AXIS2_PLACEMENT_3D('',#191397,#191398,#191399); +#191397 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#191398 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191399 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191400 = DEFINITIONAL_REPRESENTATION('',(#191401),#191405); +#191401 = LINE('',#191402,#191403); +#191402 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191403 = VECTOR('',#191404,1.); +#191404 = DIRECTION('',(0.E+000,-1.)); +#191405 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191406 = ORIENTED_EDGE('',*,*,#191407,.F.); +#191407 = EDGE_CURVE('',#191408,#191380,#191410,.T.); +#191408 = VERTEX_POINT('',#191409); +#191409 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191410 = SURFACE_CURVE('',#191411,(#191415,#191422),.PCURVE_S1.); +#191411 = LINE('',#191412,#191413); +#191412 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191413 = VECTOR('',#191414,1.); +#191414 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191415 = PCURVE('',#187949,#191416); +#191416 = DEFINITIONAL_REPRESENTATION('',(#191417),#191421); +#191417 = LINE('',#191418,#191419); +#191418 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#191419 = VECTOR('',#191420,1.); +#191420 = DIRECTION('',(-1.,0.E+000)); +#191421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191422 = PCURVE('',#191423,#191428); +#191423 = PLANE('',#191424); +#191424 = AXIS2_PLACEMENT_3D('',#191425,#191426,#191427); +#191425 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191426 = DIRECTION('',(0.E+000,1.,0.E+000)); +#191427 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191428 = DEFINITIONAL_REPRESENTATION('',(#191429),#191433); +#191429 = LINE('',#191430,#191431); +#191430 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191431 = VECTOR('',#191432,1.); +#191432 = DIRECTION('',(1.,0.E+000)); +#191433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191434 = ORIENTED_EDGE('',*,*,#191435,.F.); +#191435 = EDGE_CURVE('',#191436,#191408,#191438,.T.); +#191436 = VERTEX_POINT('',#191437); +#191437 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); +#191438 = SURFACE_CURVE('',#191439,(#191443,#191450),.PCURVE_S1.); +#191439 = LINE('',#191440,#191441); +#191440 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191441 = VECTOR('',#191442,1.); +#191442 = DIRECTION('',(0.E+000,1.,0.E+000)); +#191443 = PCURVE('',#187949,#191444); +#191444 = DEFINITIONAL_REPRESENTATION('',(#191445),#191449); +#191445 = LINE('',#191446,#191447); +#191446 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#191447 = VECTOR('',#191448,1.); +#191448 = DIRECTION('',(0.E+000,1.)); +#191449 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191450 = PCURVE('',#191451,#191456); +#191451 = PLANE('',#191452); +#191452 = AXIS2_PLACEMENT_3D('',#191453,#191454,#191455); +#191453 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191454 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191455 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#191456 = DEFINITIONAL_REPRESENTATION('',(#191457),#191461); +#191457 = LINE('',#191458,#191459); +#191458 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191459 = VECTOR('',#191460,1.); +#191460 = DIRECTION('',(0.E+000,1.)); +#191461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191462 = ORIENTED_EDGE('',*,*,#191463,.F.); +#191463 = EDGE_CURVE('',#191464,#191436,#191466,.T.); +#191464 = VERTEX_POINT('',#191465); +#191465 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); +#191466 = SURFACE_CURVE('',#191467,(#191472,#191479),.PCURVE_S1.); +#191467 = CIRCLE('',#191468,0.2); +#191468 = AXIS2_PLACEMENT_3D('',#191469,#191470,#191471); +#191469 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#191470 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191471 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191472 = PCURVE('',#187949,#191473); +#191473 = DEFINITIONAL_REPRESENTATION('',(#191474),#191478); +#191474 = CIRCLE('',#191475,0.2); +#191475 = AXIS2_PLACEMENT_2D('',#191476,#191477); +#191476 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#191477 = DIRECTION('',(1.,0.E+000)); +#191478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191479 = PCURVE('',#191480,#191485); +#191480 = CYLINDRICAL_SURFACE('',#191481,0.2); +#191481 = AXIS2_PLACEMENT_3D('',#191482,#191483,#191484); +#191482 = CARTESIAN_POINT('',(0.755,0.945297240108,0.2)); +#191483 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191484 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191485 = DEFINITIONAL_REPRESENTATION('',(#191486),#191489); +#191486 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191487,#191488), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#189095 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#189096 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#189097 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189098 = ORIENTED_EDGE('',*,*,#189099,.F.); -#189099 = EDGE_CURVE('',#189100,#189072,#189102,.T.); -#189100 = VERTEX_POINT('',#189101); -#189101 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#189102 = SURFACE_CURVE('',#189103,(#189107,#189114),.PCURVE_S1.); -#189103 = LINE('',#189104,#189105); -#189104 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#189105 = VECTOR('',#189106,1.); -#189106 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#189107 = PCURVE('',#185557,#189108); -#189108 = DEFINITIONAL_REPRESENTATION('',(#189109),#189113); -#189109 = LINE('',#189110,#189111); -#189110 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#189111 = VECTOR('',#189112,1.); -#189112 = DIRECTION('',(0.993981062721,0.109552028512)); -#189113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189114 = PCURVE('',#189115,#189120); -#189115 = PLANE('',#189116); -#189116 = AXIS2_PLACEMENT_3D('',#189117,#189118,#189119); -#189117 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#189118 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#189119 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#189120 = DEFINITIONAL_REPRESENTATION('',(#189121),#189125); -#189121 = LINE('',#189122,#189123); -#189122 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189123 = VECTOR('',#189124,1.); -#189124 = DIRECTION('',(1.,0.E+000)); -#189125 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189126 = ORIENTED_EDGE('',*,*,#189127,.F.); -#189127 = EDGE_CURVE('',#188753,#189100,#189128,.T.); -#189128 = SURFACE_CURVE('',#189129,(#189134,#189145),.PCURVE_S1.); -#189129 = CIRCLE('',#189130,5.E-002); -#189130 = AXIS2_PLACEMENT_3D('',#189131,#189132,#189133); -#189131 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); -#189132 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189133 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189134 = PCURVE('',#185557,#189135); -#189135 = DEFINITIONAL_REPRESENTATION('',(#189136),#189144); -#189136 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#189137,#189138,#189139, - #189140,#189141,#189142,#189143),.UNSPECIFIED.,.F.,.F.) +#191487 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#191488 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#191489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191490 = ORIENTED_EDGE('',*,*,#191491,.F.); +#191491 = EDGE_CURVE('',#191492,#191464,#191494,.T.); +#191492 = VERTEX_POINT('',#191493); +#191493 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#191494 = SURFACE_CURVE('',#191495,(#191499,#191506),.PCURVE_S1.); +#191495 = LINE('',#191496,#191497); +#191496 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#191497 = VECTOR('',#191498,1.); +#191498 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#191499 = PCURVE('',#187949,#191500); +#191500 = DEFINITIONAL_REPRESENTATION('',(#191501),#191505); +#191501 = LINE('',#191502,#191503); +#191502 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#191503 = VECTOR('',#191504,1.); +#191504 = DIRECTION('',(0.993981062721,0.109552028512)); +#191505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191506 = PCURVE('',#191507,#191512); +#191507 = PLANE('',#191508); +#191508 = AXIS2_PLACEMENT_3D('',#191509,#191510,#191511); +#191509 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#191510 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#191511 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#191512 = DEFINITIONAL_REPRESENTATION('',(#191513),#191517); +#191513 = LINE('',#191514,#191515); +#191514 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191515 = VECTOR('',#191516,1.); +#191516 = DIRECTION('',(1.,0.E+000)); +#191517 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191518 = ORIENTED_EDGE('',*,*,#191519,.F.); +#191519 = EDGE_CURVE('',#191145,#191492,#191520,.T.); +#191520 = SURFACE_CURVE('',#191521,(#191526,#191537),.PCURVE_S1.); +#191521 = CIRCLE('',#191522,5.E-002); +#191522 = AXIS2_PLACEMENT_3D('',#191523,#191524,#191525); +#191523 = CARTESIAN_POINT('',(0.755,0.655208001194,0.55)); +#191524 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#191525 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191526 = PCURVE('',#187949,#191527); +#191527 = DEFINITIONAL_REPRESENTATION('',(#191528),#191536); +#191528 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191529,#191530,#191531, + #191532,#191533,#191534,#191535),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#189137 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189138 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#189139 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#189140 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#189141 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#189142 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#189143 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189145 = PCURVE('',#188791,#189146); -#189146 = DEFINITIONAL_REPRESENTATION('',(#189147),#189150); -#189147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189148,#189149), +#191529 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#191530 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#191531 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#191532 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#191533 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#191534 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#191535 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#191536 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191537 = PCURVE('',#191183,#191538); +#191538 = DEFINITIONAL_REPRESENTATION('',(#191539),#191542); +#191539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191540,#191541), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#189148 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#189149 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#189150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189151 = ADVANCED_FACE('',(#189152),#185501,.T.); -#189152 = FACE_BOUND('',#189153,.T.); -#189153 = EDGE_LOOP('',(#189154,#189155,#189156,#189183,#189206,#189229, - #189252,#189275,#189298,#189325,#189348,#189369)); -#189154 = ORIENTED_EDGE('',*,*,#185485,.F.); -#189155 = ORIENTED_EDGE('',*,*,#188802,.T.); -#189156 = ORIENTED_EDGE('',*,*,#189157,.T.); -#189157 = EDGE_CURVE('',#188776,#189158,#189160,.T.); -#189158 = VERTEX_POINT('',#189159); -#189159 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); -#189160 = SURFACE_CURVE('',#189161,(#189166,#189177),.PCURVE_S1.); -#189161 = CIRCLE('',#189162,5.E-002); -#189162 = AXIS2_PLACEMENT_3D('',#189163,#189164,#189165); -#189163 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#189164 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189165 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189166 = PCURVE('',#185501,#189167); -#189167 = DEFINITIONAL_REPRESENTATION('',(#189168),#189176); -#189168 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#189169,#189170,#189171, - #189172,#189173,#189174,#189175),.UNSPECIFIED.,.F.,.F.) +#191540 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#191541 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#191542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191543 = ADVANCED_FACE('',(#191544),#187893,.T.); +#191544 = FACE_BOUND('',#191545,.T.); +#191545 = EDGE_LOOP('',(#191546,#191547,#191548,#191575,#191598,#191621, + #191644,#191667,#191690,#191717,#191740,#191761)); +#191546 = ORIENTED_EDGE('',*,*,#187877,.F.); +#191547 = ORIENTED_EDGE('',*,*,#191194,.T.); +#191548 = ORIENTED_EDGE('',*,*,#191549,.T.); +#191549 = EDGE_CURVE('',#191168,#191550,#191552,.T.); +#191550 = VERTEX_POINT('',#191551); +#191551 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); +#191552 = SURFACE_CURVE('',#191553,(#191558,#191569),.PCURVE_S1.); +#191553 = CIRCLE('',#191554,5.E-002); +#191554 = AXIS2_PLACEMENT_3D('',#191555,#191556,#191557); +#191555 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#191556 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#191557 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191558 = PCURVE('',#187893,#191559); +#191559 = DEFINITIONAL_REPRESENTATION('',(#191560),#191568); +#191560 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191561,#191562,#191563, + #191564,#191565,#191566,#191567),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#189169 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189170 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#189171 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#189172 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#189173 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#189174 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#189175 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189177 = PCURVE('',#188791,#189178); -#189178 = DEFINITIONAL_REPRESENTATION('',(#189179),#189182); -#189179 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189180,#189181), +#191561 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#191562 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#191563 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#191564 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#191565 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#191566 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#191567 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#191568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191569 = PCURVE('',#191183,#191570); +#191570 = DEFINITIONAL_REPRESENTATION('',(#191571),#191574); +#191571 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191572,#191573), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#189180 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#189181 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#189182 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189183 = ORIENTED_EDGE('',*,*,#189184,.T.); -#189184 = EDGE_CURVE('',#189158,#189185,#189187,.T.); -#189185 = VERTEX_POINT('',#189186); -#189186 = CARTESIAN_POINT('',(1.155,0.746501027564,0.178089594298)); -#189187 = SURFACE_CURVE('',#189188,(#189192,#189199),.PCURVE_S1.); -#189188 = LINE('',#189189,#189190); -#189189 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); -#189190 = VECTOR('',#189191,1.); -#189191 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#189192 = PCURVE('',#185501,#189193); -#189193 = DEFINITIONAL_REPRESENTATION('',(#189194),#189198); -#189194 = LINE('',#189195,#189196); -#189195 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#189196 = VECTOR('',#189197,1.); -#189197 = DIRECTION('',(0.993981062721,0.109552028512)); -#189198 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189199 = PCURVE('',#189115,#189200); -#189200 = DEFINITIONAL_REPRESENTATION('',(#189201),#189205); -#189201 = LINE('',#189202,#189203); -#189202 = CARTESIAN_POINT('',(0.E+000,0.4)); -#189203 = VECTOR('',#189204,1.); -#189204 = DIRECTION('',(1.,0.E+000)); -#189205 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189206 = ORIENTED_EDGE('',*,*,#189207,.T.); -#189207 = EDGE_CURVE('',#189185,#189208,#189210,.T.); -#189208 = VERTEX_POINT('',#189209); -#189209 = CARTESIAN_POINT('',(1.155,0.945297240108,0.E+000)); -#189210 = SURFACE_CURVE('',#189211,(#189216,#189223),.PCURVE_S1.); -#189211 = CIRCLE('',#189212,0.2); -#189212 = AXIS2_PLACEMENT_3D('',#189213,#189214,#189215); -#189213 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); -#189214 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189215 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189216 = PCURVE('',#185501,#189217); -#189217 = DEFINITIONAL_REPRESENTATION('',(#189218),#189222); -#189218 = CIRCLE('',#189219,0.2); -#189219 = AXIS2_PLACEMENT_2D('',#189220,#189221); -#189220 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#189221 = DIRECTION('',(1.,0.E+000)); -#189222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189223 = PCURVE('',#189088,#189224); -#189224 = DEFINITIONAL_REPRESENTATION('',(#189225),#189228); -#189225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189226,#189227), +#191572 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#191573 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#191574 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191575 = ORIENTED_EDGE('',*,*,#191576,.T.); +#191576 = EDGE_CURVE('',#191550,#191577,#191579,.T.); +#191577 = VERTEX_POINT('',#191578); +#191578 = CARTESIAN_POINT('',(1.155,0.746501027564,0.178089594298)); +#191579 = SURFACE_CURVE('',#191580,(#191584,#191591),.PCURVE_S1.); +#191580 = LINE('',#191581,#191582); +#191581 = CARTESIAN_POINT('',(1.155,0.70490705433,0.555477601426)); +#191582 = VECTOR('',#191583,1.); +#191583 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#191584 = PCURVE('',#187893,#191585); +#191585 = DEFINITIONAL_REPRESENTATION('',(#191586),#191590); +#191586 = LINE('',#191587,#191588); +#191587 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#191588 = VECTOR('',#191589,1.); +#191589 = DIRECTION('',(0.993981062721,0.109552028512)); +#191590 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191591 = PCURVE('',#191507,#191592); +#191592 = DEFINITIONAL_REPRESENTATION('',(#191593),#191597); +#191593 = LINE('',#191594,#191595); +#191594 = CARTESIAN_POINT('',(0.E+000,0.4)); +#191595 = VECTOR('',#191596,1.); +#191596 = DIRECTION('',(1.,0.E+000)); +#191597 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191598 = ORIENTED_EDGE('',*,*,#191599,.T.); +#191599 = EDGE_CURVE('',#191577,#191600,#191602,.T.); +#191600 = VERTEX_POINT('',#191601); +#191601 = CARTESIAN_POINT('',(1.155,0.945297240108,0.E+000)); +#191602 = SURFACE_CURVE('',#191603,(#191608,#191615),.PCURVE_S1.); +#191603 = CIRCLE('',#191604,0.2); +#191604 = AXIS2_PLACEMENT_3D('',#191605,#191606,#191607); +#191605 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); +#191606 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191607 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191608 = PCURVE('',#187893,#191609); +#191609 = DEFINITIONAL_REPRESENTATION('',(#191610),#191614); +#191610 = CIRCLE('',#191611,0.2); +#191611 = AXIS2_PLACEMENT_2D('',#191612,#191613); +#191612 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#191613 = DIRECTION('',(1.,0.E+000)); +#191614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191615 = PCURVE('',#191480,#191616); +#191616 = DEFINITIONAL_REPRESENTATION('',(#191617),#191620); +#191617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191618,#191619), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#189226 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#189227 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#189228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#191618 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#191619 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#191620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191621 = ORIENTED_EDGE('',*,*,#191622,.T.); +#191622 = EDGE_CURVE('',#191600,#191623,#191625,.T.); +#191623 = VERTEX_POINT('',#191624); +#191624 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#191625 = SURFACE_CURVE('',#191626,(#191630,#191637),.PCURVE_S1.); +#191626 = LINE('',#191627,#191628); +#191627 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#191628 = VECTOR('',#191629,1.); +#191629 = DIRECTION('',(0.E+000,1.,0.E+000)); +#191630 = PCURVE('',#187893,#191631); +#191631 = DEFINITIONAL_REPRESENTATION('',(#191632),#191636); +#191632 = LINE('',#191633,#191634); +#191633 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#191634 = VECTOR('',#191635,1.); +#191635 = DIRECTION('',(0.E+000,1.)); +#191636 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191637 = PCURVE('',#191451,#191638); +#191638 = DEFINITIONAL_REPRESENTATION('',(#191639),#191643); +#191639 = LINE('',#191640,#191641); +#191640 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#191641 = VECTOR('',#191642,1.); +#191642 = DIRECTION('',(0.E+000,1.)); +#191643 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191644 = ORIENTED_EDGE('',*,*,#191645,.T.); +#191645 = EDGE_CURVE('',#191623,#191646,#191648,.T.); +#191646 = VERTEX_POINT('',#191647); +#191647 = CARTESIAN_POINT('',(1.155,1.17,0.15)); +#191648 = SURFACE_CURVE('',#191649,(#191653,#191660),.PCURVE_S1.); +#191649 = LINE('',#191650,#191651); +#191650 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); +#191651 = VECTOR('',#191652,1.); +#191652 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191653 = PCURVE('',#187893,#191654); +#191654 = DEFINITIONAL_REPRESENTATION('',(#191655),#191659); +#191655 = LINE('',#191656,#191657); +#191656 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#191657 = VECTOR('',#191658,1.); +#191658 = DIRECTION('',(-1.,0.E+000)); +#191659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191660 = PCURVE('',#191423,#191661); +#191661 = DEFINITIONAL_REPRESENTATION('',(#191662),#191666); +#191662 = LINE('',#191663,#191664); +#191663 = CARTESIAN_POINT('',(0.E+000,0.4)); +#191664 = VECTOR('',#191665,1.); +#191665 = DIRECTION('',(1.,0.E+000)); +#191666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191667 = ORIENTED_EDGE('',*,*,#191668,.T.); +#191668 = EDGE_CURVE('',#191646,#191669,#191671,.T.); +#191669 = VERTEX_POINT('',#191670); +#191670 = CARTESIAN_POINT('',(1.155,0.945297240108,0.15)); +#191671 = SURFACE_CURVE('',#191672,(#191676,#191683),.PCURVE_S1.); +#191672 = LINE('',#191673,#191674); +#191673 = CARTESIAN_POINT('',(1.155,1.17,0.15)); +#191674 = VECTOR('',#191675,1.); +#191675 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#191676 = PCURVE('',#187893,#191677); +#191677 = DEFINITIONAL_REPRESENTATION('',(#191678),#191682); +#191678 = LINE('',#191679,#191680); +#191679 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#191680 = VECTOR('',#191681,1.); +#191681 = DIRECTION('',(0.E+000,-1.)); +#191682 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191683 = PCURVE('',#191395,#191684); +#191684 = DEFINITIONAL_REPRESENTATION('',(#191685),#191689); +#191685 = LINE('',#191686,#191687); +#191686 = CARTESIAN_POINT('',(0.4,0.E+000)); +#191687 = VECTOR('',#191688,1.); +#191688 = DIRECTION('',(0.E+000,-1.)); +#191689 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191690 = ORIENTED_EDGE('',*,*,#191691,.T.); +#191691 = EDGE_CURVE('',#191669,#191692,#191694,.T.); +#191692 = VERTEX_POINT('',#191693); +#191693 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); +#191694 = SURFACE_CURVE('',#191695,(#191700,#191711),.PCURVE_S1.); +#191695 = CIRCLE('',#191696,5.E-002); +#191696 = AXIS2_PLACEMENT_3D('',#191697,#191698,#191699); +#191697 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); +#191698 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#191699 = DIRECTION('',(0.E+000,0.E+000,1.)); +#191700 = PCURVE('',#187893,#191701); +#191701 = DEFINITIONAL_REPRESENTATION('',(#191702),#191710); +#191702 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191703,#191704,#191705, + #191706,#191707,#191708,#191709),.UNSPECIFIED.,.F.,.F.) +B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, + 2.094395102393,4.188790204786,6.28318530718,8.377580409573), +.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() +RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( + '') ); +#191703 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#191704 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#191705 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#191706 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#191707 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#191708 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#191709 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#191710 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191711 = PCURVE('',#191368,#191712); +#191712 = DEFINITIONAL_REPRESENTATION('',(#191713),#191716); +#191713 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191714,#191715), + .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), + .PIECEWISE_BEZIER_KNOTS.); +#191714 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#191715 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#191716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191717 = ORIENTED_EDGE('',*,*,#191718,.T.); +#191718 = EDGE_CURVE('',#191692,#191719,#191721,.T.); +#191719 = VERTEX_POINT('',#191720); +#191720 = CARTESIAN_POINT('',(1.155,0.854004213739,0.571910405702)); +#191721 = SURFACE_CURVE('',#191722,(#191726,#191733),.PCURVE_S1.); +#191722 = LINE('',#191723,#191724); +#191723 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); +#191724 = VECTOR('',#191725,1.); +#191725 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#191726 = PCURVE('',#187893,#191727); +#191727 = DEFINITIONAL_REPRESENTATION('',(#191728),#191732); +#191728 = LINE('',#191729,#191730); +#191729 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#191730 = VECTOR('',#191731,1.); +#191731 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#191732 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191733 = PCURVE('',#191335,#191734); +#191734 = DEFINITIONAL_REPRESENTATION('',(#191735),#191739); +#191735 = LINE('',#191736,#191737); +#191736 = CARTESIAN_POINT('',(0.E+000,0.4)); +#191737 = VECTOR('',#191738,1.); +#191738 = DIRECTION('',(1.,0.E+000)); +#191739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191740 = ORIENTED_EDGE('',*,*,#191741,.T.); +#191741 = EDGE_CURVE('',#191719,#191220,#191742,.T.); +#191742 = SURFACE_CURVE('',#191743,(#191748,#191755),.PCURVE_S1.); +#191743 = CIRCLE('',#191744,0.2); +#191744 = AXIS2_PLACEMENT_3D('',#191745,#191746,#191747); +#191745 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); +#191746 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191747 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#191748 = PCURVE('',#187893,#191749); +#191749 = DEFINITIONAL_REPRESENTATION('',(#191750),#191754); +#191750 = CIRCLE('',#191751,0.2); +#191751 = AXIS2_PLACEMENT_2D('',#191752,#191753); +#191752 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191753 = DIRECTION('',(1.,0.E+000)); +#191754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#189229 = ORIENTED_EDGE('',*,*,#189230,.T.); -#189230 = EDGE_CURVE('',#189208,#189231,#189233,.T.); -#189231 = VERTEX_POINT('',#189232); -#189232 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#189233 = SURFACE_CURVE('',#189234,(#189238,#189245),.PCURVE_S1.); -#189234 = LINE('',#189235,#189236); -#189235 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#189236 = VECTOR('',#189237,1.); -#189237 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189238 = PCURVE('',#185501,#189239); -#189239 = DEFINITIONAL_REPRESENTATION('',(#189240),#189244); -#189240 = LINE('',#189241,#189242); -#189241 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189242 = VECTOR('',#189243,1.); -#189243 = DIRECTION('',(0.E+000,1.)); -#189244 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189245 = PCURVE('',#189059,#189246); -#189246 = DEFINITIONAL_REPRESENTATION('',(#189247),#189251); -#189247 = LINE('',#189248,#189249); -#189248 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#189249 = VECTOR('',#189250,1.); -#189250 = DIRECTION('',(0.E+000,1.)); -#189251 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189252 = ORIENTED_EDGE('',*,*,#189253,.T.); -#189253 = EDGE_CURVE('',#189231,#189254,#189256,.T.); -#189254 = VERTEX_POINT('',#189255); -#189255 = CARTESIAN_POINT('',(1.155,1.17,0.15)); -#189256 = SURFACE_CURVE('',#189257,(#189261,#189268),.PCURVE_S1.); -#189257 = LINE('',#189258,#189259); -#189258 = CARTESIAN_POINT('',(1.155,1.17,0.E+000)); -#189259 = VECTOR('',#189260,1.); -#189260 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189261 = PCURVE('',#185501,#189262); -#189262 = DEFINITIONAL_REPRESENTATION('',(#189263),#189267); -#189263 = LINE('',#189264,#189265); -#189264 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189265 = VECTOR('',#189266,1.); -#189266 = DIRECTION('',(-1.,0.E+000)); -#189267 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189268 = PCURVE('',#189031,#189269); -#189269 = DEFINITIONAL_REPRESENTATION('',(#189270),#189274); -#189270 = LINE('',#189271,#189272); -#189271 = CARTESIAN_POINT('',(0.E+000,0.4)); -#189272 = VECTOR('',#189273,1.); -#189273 = DIRECTION('',(1.,0.E+000)); -#189274 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189275 = ORIENTED_EDGE('',*,*,#189276,.T.); -#189276 = EDGE_CURVE('',#189254,#189277,#189279,.T.); -#189277 = VERTEX_POINT('',#189278); -#189278 = CARTESIAN_POINT('',(1.155,0.945297240108,0.15)); -#189279 = SURFACE_CURVE('',#189280,(#189284,#189291),.PCURVE_S1.); -#189280 = LINE('',#189281,#189282); -#189281 = CARTESIAN_POINT('',(1.155,1.17,0.15)); -#189282 = VECTOR('',#189283,1.); -#189283 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#189284 = PCURVE('',#185501,#189285); -#189285 = DEFINITIONAL_REPRESENTATION('',(#189286),#189290); -#189286 = LINE('',#189287,#189288); -#189287 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#189288 = VECTOR('',#189289,1.); -#189289 = DIRECTION('',(0.E+000,-1.)); -#189290 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189291 = PCURVE('',#189003,#189292); -#189292 = DEFINITIONAL_REPRESENTATION('',(#189293),#189297); -#189293 = LINE('',#189294,#189295); -#189294 = CARTESIAN_POINT('',(0.4,0.E+000)); -#189295 = VECTOR('',#189296,1.); -#189296 = DIRECTION('',(0.E+000,-1.)); -#189297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189298 = ORIENTED_EDGE('',*,*,#189299,.T.); -#189299 = EDGE_CURVE('',#189277,#189300,#189302,.T.); -#189300 = VERTEX_POINT('',#189301); -#189301 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); -#189302 = SURFACE_CURVE('',#189303,(#189308,#189319),.PCURVE_S1.); -#189303 = CIRCLE('',#189304,5.E-002); -#189304 = AXIS2_PLACEMENT_3D('',#189305,#189306,#189307); -#189305 = CARTESIAN_POINT('',(1.155,0.945297240108,0.2)); -#189306 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189307 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189308 = PCURVE('',#185501,#189309); -#189309 = DEFINITIONAL_REPRESENTATION('',(#189310),#189318); -#189310 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#189311,#189312,#189313, - #189314,#189315,#189316,#189317),.UNSPECIFIED.,.F.,.F.) -B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, - 2.094395102393,4.188790204786,6.28318530718,8.377580409573), -.UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() -RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( - '') ); -#189311 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#189312 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#189313 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#189314 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#189315 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#189316 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#189317 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#189318 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189319 = PCURVE('',#188976,#189320); -#189320 = DEFINITIONAL_REPRESENTATION('',(#189321),#189324); -#189321 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189322,#189323), - .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), - .PIECEWISE_BEZIER_KNOTS.); -#189322 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#189323 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#189324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189325 = ORIENTED_EDGE('',*,*,#189326,.T.); -#189326 = EDGE_CURVE('',#189300,#189327,#189329,.T.); -#189327 = VERTEX_POINT('',#189328); -#189328 = CARTESIAN_POINT('',(1.155,0.854004213739,0.571910405702)); -#189329 = SURFACE_CURVE('',#189330,(#189334,#189341),.PCURVE_S1.); -#189330 = LINE('',#189331,#189332); -#189331 = CARTESIAN_POINT('',(1.155,0.895598186972,0.194522398574)); -#189332 = VECTOR('',#189333,1.); -#189333 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#189334 = PCURVE('',#185501,#189335); -#189335 = DEFINITIONAL_REPRESENTATION('',(#189336),#189340); -#189336 = LINE('',#189337,#189338); -#189337 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#189338 = VECTOR('',#189339,1.); -#189339 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#189340 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189341 = PCURVE('',#188943,#189342); -#189342 = DEFINITIONAL_REPRESENTATION('',(#189343),#189347); -#189343 = LINE('',#189344,#189345); -#189344 = CARTESIAN_POINT('',(0.E+000,0.4)); -#189345 = VECTOR('',#189346,1.); -#189346 = DIRECTION('',(1.,0.E+000)); -#189347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189348 = ORIENTED_EDGE('',*,*,#189349,.T.); -#189349 = EDGE_CURVE('',#189327,#188828,#189350,.T.); -#189350 = SURFACE_CURVE('',#189351,(#189356,#189363),.PCURVE_S1.); -#189351 = CIRCLE('',#189352,0.2); -#189352 = AXIS2_PLACEMENT_3D('',#189353,#189354,#189355); -#189353 = CARTESIAN_POINT('',(1.155,0.655208001194,0.55)); -#189354 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189355 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189356 = PCURVE('',#185501,#189357); -#189357 = DEFINITIONAL_REPRESENTATION('',(#189358),#189362); -#189358 = CIRCLE('',#189359,0.2); -#189359 = AXIS2_PLACEMENT_2D('',#189360,#189361); -#189360 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189361 = DIRECTION('',(1.,0.E+000)); -#189362 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189363 = PCURVE('',#188866,#189364); -#189364 = DEFINITIONAL_REPRESENTATION('',(#189365),#189368); -#189365 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189366,#189367), +#191755 = PCURVE('',#191258,#191756); +#191756 = DEFINITIONAL_REPRESENTATION('',(#191757),#191760); +#191757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191758,#191759), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#189366 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#189367 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#189368 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189369 = ORIENTED_EDGE('',*,*,#188827,.T.); -#189370 = ADVANCED_FACE('',(#189371),#188866,.T.); -#189371 = FACE_BOUND('',#189372,.T.); -#189372 = EDGE_LOOP('',(#189373,#189374,#189375,#189395)); -#189373 = ORIENTED_EDGE('',*,*,#188850,.T.); -#189374 = ORIENTED_EDGE('',*,*,#189349,.F.); -#189375 = ORIENTED_EDGE('',*,*,#189376,.F.); -#189376 = EDGE_CURVE('',#188905,#189327,#189377,.T.); -#189377 = SURFACE_CURVE('',#189378,(#189382,#189388),.PCURVE_S1.); -#189378 = LINE('',#189379,#189380); -#189379 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); -#189380 = VECTOR('',#189381,1.); -#189381 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189382 = PCURVE('',#188866,#189383); -#189383 = DEFINITIONAL_REPRESENTATION('',(#189384),#189387); -#189384 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189385,#189386), +#191758 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#191759 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#191760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191761 = ORIENTED_EDGE('',*,*,#191219,.T.); +#191762 = ADVANCED_FACE('',(#191763),#191258,.T.); +#191763 = FACE_BOUND('',#191764,.T.); +#191764 = EDGE_LOOP('',(#191765,#191766,#191767,#191787)); +#191765 = ORIENTED_EDGE('',*,*,#191242,.T.); +#191766 = ORIENTED_EDGE('',*,*,#191741,.F.); +#191767 = ORIENTED_EDGE('',*,*,#191768,.F.); +#191768 = EDGE_CURVE('',#191297,#191719,#191769,.T.); +#191769 = SURFACE_CURVE('',#191770,(#191774,#191780),.PCURVE_S1.); +#191770 = LINE('',#191771,#191772); +#191771 = CARTESIAN_POINT('',(0.755,0.854004213739,0.571910405702)); +#191772 = VECTOR('',#191773,1.); +#191773 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191774 = PCURVE('',#191258,#191775); +#191775 = DEFINITIONAL_REPRESENTATION('',(#191776),#191779); +#191776 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191777,#191778), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#189385 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#189386 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#189387 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189388 = PCURVE('',#188943,#189389); -#189389 = DEFINITIONAL_REPRESENTATION('',(#189390),#189394); -#189390 = LINE('',#189391,#189392); -#189391 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#189392 = VECTOR('',#189393,1.); -#189393 = DIRECTION('',(0.E+000,1.)); -#189394 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189395 = ORIENTED_EDGE('',*,*,#188904,.T.); -#189396 = ADVANCED_FACE('',(#189397),#188943,.T.); -#189397 = FACE_BOUND('',#189398,.T.); -#189398 = EDGE_LOOP('',(#189399,#189400,#189401,#189421)); -#189399 = ORIENTED_EDGE('',*,*,#189376,.T.); -#189400 = ORIENTED_EDGE('',*,*,#189326,.F.); -#189401 = ORIENTED_EDGE('',*,*,#189402,.F.); -#189402 = EDGE_CURVE('',#188928,#189300,#189403,.T.); -#189403 = SURFACE_CURVE('',#189404,(#189408,#189415),.PCURVE_S1.); -#189404 = LINE('',#189405,#189406); -#189405 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); -#189406 = VECTOR('',#189407,1.); -#189407 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189408 = PCURVE('',#188943,#189409); -#189409 = DEFINITIONAL_REPRESENTATION('',(#189410),#189414); -#189410 = LINE('',#189411,#189412); -#189411 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189412 = VECTOR('',#189413,1.); -#189413 = DIRECTION('',(0.E+000,1.)); -#189414 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189415 = PCURVE('',#188976,#189416); -#189416 = DEFINITIONAL_REPRESENTATION('',(#189417),#189420); -#189417 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189418,#189419), +#191777 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#191778 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#191779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191780 = PCURVE('',#191335,#191781); +#191781 = DEFINITIONAL_REPRESENTATION('',(#191782),#191786); +#191782 = LINE('',#191783,#191784); +#191783 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#191784 = VECTOR('',#191785,1.); +#191785 = DIRECTION('',(0.E+000,1.)); +#191786 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191787 = ORIENTED_EDGE('',*,*,#191296,.T.); +#191788 = ADVANCED_FACE('',(#191789),#191335,.T.); +#191789 = FACE_BOUND('',#191790,.T.); +#191790 = EDGE_LOOP('',(#191791,#191792,#191793,#191813)); +#191791 = ORIENTED_EDGE('',*,*,#191768,.T.); +#191792 = ORIENTED_EDGE('',*,*,#191718,.F.); +#191793 = ORIENTED_EDGE('',*,*,#191794,.F.); +#191794 = EDGE_CURVE('',#191320,#191692,#191795,.T.); +#191795 = SURFACE_CURVE('',#191796,(#191800,#191807),.PCURVE_S1.); +#191796 = LINE('',#191797,#191798); +#191797 = CARTESIAN_POINT('',(0.755,0.895598186972,0.194522398574)); +#191798 = VECTOR('',#191799,1.); +#191799 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191800 = PCURVE('',#191335,#191801); +#191801 = DEFINITIONAL_REPRESENTATION('',(#191802),#191806); +#191802 = LINE('',#191803,#191804); +#191803 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191804 = VECTOR('',#191805,1.); +#191805 = DIRECTION('',(0.E+000,1.)); +#191806 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191807 = PCURVE('',#191368,#191808); +#191808 = DEFINITIONAL_REPRESENTATION('',(#191809),#191812); +#191809 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191810,#191811), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#189418 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#189419 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#189420 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189421 = ORIENTED_EDGE('',*,*,#188927,.T.); -#189422 = ADVANCED_FACE('',(#189423),#188976,.F.); -#189423 = FACE_BOUND('',#189424,.F.); -#189424 = EDGE_LOOP('',(#189425,#189426,#189427,#189470)); -#189425 = ORIENTED_EDGE('',*,*,#189402,.F.); -#189426 = ORIENTED_EDGE('',*,*,#188955,.F.); -#189427 = ORIENTED_EDGE('',*,*,#189428,.T.); -#189428 = EDGE_CURVE('',#188956,#189277,#189429,.T.); -#189429 = SURFACE_CURVE('',#189430,(#189434,#189463),.PCURVE_S1.); -#189430 = LINE('',#189431,#189432); -#189431 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); -#189432 = VECTOR('',#189433,1.); -#189433 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189434 = PCURVE('',#188976,#189435); -#189435 = DEFINITIONAL_REPRESENTATION('',(#189436),#189462); -#189436 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189437,#189438,#189439, - #189440,#189441,#189442,#189443,#189444,#189445,#189446,#189447, - #189448,#189449,#189450,#189451,#189452,#189453,#189454,#189455, - #189456,#189457,#189458,#189459,#189460,#189461),.UNSPECIFIED.,.F., +#191810 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#191811 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#191812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191813 = ORIENTED_EDGE('',*,*,#191319,.T.); +#191814 = ADVANCED_FACE('',(#191815),#191368,.F.); +#191815 = FACE_BOUND('',#191816,.F.); +#191816 = EDGE_LOOP('',(#191817,#191818,#191819,#191862)); +#191817 = ORIENTED_EDGE('',*,*,#191794,.F.); +#191818 = ORIENTED_EDGE('',*,*,#191347,.F.); +#191819 = ORIENTED_EDGE('',*,*,#191820,.T.); +#191820 = EDGE_CURVE('',#191348,#191669,#191821,.T.); +#191821 = SURFACE_CURVE('',#191822,(#191826,#191855),.PCURVE_S1.); +#191822 = LINE('',#191823,#191824); +#191823 = CARTESIAN_POINT('',(0.755,0.945297240108,0.15)); +#191824 = VECTOR('',#191825,1.); +#191825 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191826 = PCURVE('',#191368,#191827); +#191827 = DEFINITIONAL_REPRESENTATION('',(#191828),#191854); +#191828 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#191829,#191830,#191831, + #191832,#191833,#191834,#191835,#191836,#191837,#191838,#191839, + #191840,#191841,#191842,#191843,#191844,#191845,#191846,#191847, + #191848,#191849,#191850,#191851,#191852,#191853),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -235308,133 +238310,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#189437 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#189438 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#189439 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#189440 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#189441 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#189442 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#189443 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#189444 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#189445 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#189446 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#189447 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#189448 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#189449 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#189450 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#189451 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#189452 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#189453 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#189454 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#189455 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#189456 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#189457 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#189458 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#189459 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#189460 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#189461 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#189462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189463 = PCURVE('',#189003,#189464); -#189464 = DEFINITIONAL_REPRESENTATION('',(#189465),#189469); -#189465 = LINE('',#189466,#189467); -#189466 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#189467 = VECTOR('',#189468,1.); -#189468 = DIRECTION('',(1.,0.E+000)); -#189469 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189470 = ORIENTED_EDGE('',*,*,#189299,.T.); -#189471 = ADVANCED_FACE('',(#189472),#189003,.T.); -#189472 = FACE_BOUND('',#189473,.T.); -#189473 = EDGE_LOOP('',(#189474,#189475,#189476,#189497)); -#189474 = ORIENTED_EDGE('',*,*,#189428,.T.); -#189475 = ORIENTED_EDGE('',*,*,#189276,.F.); -#189476 = ORIENTED_EDGE('',*,*,#189477,.F.); -#189477 = EDGE_CURVE('',#188988,#189254,#189478,.T.); -#189478 = SURFACE_CURVE('',#189479,(#189483,#189490),.PCURVE_S1.); -#189479 = LINE('',#189480,#189481); -#189480 = CARTESIAN_POINT('',(0.755,1.17,0.15)); -#189481 = VECTOR('',#189482,1.); -#189482 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189483 = PCURVE('',#189003,#189484); -#189484 = DEFINITIONAL_REPRESENTATION('',(#189485),#189489); -#189485 = LINE('',#189486,#189487); -#189486 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189487 = VECTOR('',#189488,1.); -#189488 = DIRECTION('',(1.,0.E+000)); -#189489 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189490 = PCURVE('',#189031,#189491); -#189491 = DEFINITIONAL_REPRESENTATION('',(#189492),#189496); -#189492 = LINE('',#189493,#189494); -#189493 = CARTESIAN_POINT('',(0.15,0.E+000)); -#189494 = VECTOR('',#189495,1.); -#189495 = DIRECTION('',(0.E+000,1.)); -#189496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189497 = ORIENTED_EDGE('',*,*,#188987,.T.); -#189498 = ADVANCED_FACE('',(#189499),#189031,.T.); -#189499 = FACE_BOUND('',#189500,.T.); -#189500 = EDGE_LOOP('',(#189501,#189502,#189503,#189524)); -#189501 = ORIENTED_EDGE('',*,*,#189477,.T.); -#189502 = ORIENTED_EDGE('',*,*,#189253,.F.); -#189503 = ORIENTED_EDGE('',*,*,#189504,.F.); -#189504 = EDGE_CURVE('',#189016,#189231,#189505,.T.); -#189505 = SURFACE_CURVE('',#189506,(#189510,#189517),.PCURVE_S1.); -#189506 = LINE('',#189507,#189508); -#189507 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); -#189508 = VECTOR('',#189509,1.); -#189509 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189510 = PCURVE('',#189031,#189511); -#189511 = DEFINITIONAL_REPRESENTATION('',(#189512),#189516); -#189512 = LINE('',#189513,#189514); -#189513 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189514 = VECTOR('',#189515,1.); -#189515 = DIRECTION('',(0.E+000,1.)); -#189516 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189517 = PCURVE('',#189059,#189518); -#189518 = DEFINITIONAL_REPRESENTATION('',(#189519),#189523); -#189519 = LINE('',#189520,#189521); -#189520 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189521 = VECTOR('',#189522,1.); -#189522 = DIRECTION('',(-1.,0.E+000)); -#189523 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#191829 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#191830 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#191831 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#191832 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#191833 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#191834 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#191835 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#191836 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#191837 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#191838 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#191839 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#191840 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#191841 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#191842 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#191843 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#191844 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#191845 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#191846 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#191847 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#191848 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#191849 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#191850 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#191851 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#191852 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#191853 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#191854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191855 = PCURVE('',#191395,#191856); +#191856 = DEFINITIONAL_REPRESENTATION('',(#191857),#191861); +#191857 = LINE('',#191858,#191859); +#191858 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#191859 = VECTOR('',#191860,1.); +#191860 = DIRECTION('',(1.,0.E+000)); +#191861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#189524 = ORIENTED_EDGE('',*,*,#189015,.T.); -#189525 = ADVANCED_FACE('',(#189526),#189059,.T.); -#189526 = FACE_BOUND('',#189527,.T.); -#189527 = EDGE_LOOP('',(#189528,#189529,#189530,#189573)); -#189528 = ORIENTED_EDGE('',*,*,#189504,.T.); -#189529 = ORIENTED_EDGE('',*,*,#189230,.F.); -#189530 = ORIENTED_EDGE('',*,*,#189531,.F.); -#189531 = EDGE_CURVE('',#189044,#189208,#189532,.T.); -#189532 = SURFACE_CURVE('',#189533,(#189537,#189544),.PCURVE_S1.); -#189533 = LINE('',#189534,#189535); -#189534 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); -#189535 = VECTOR('',#189536,1.); -#189536 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189537 = PCURVE('',#189059,#189538); -#189538 = DEFINITIONAL_REPRESENTATION('',(#189539),#189543); -#189539 = LINE('',#189540,#189541); -#189540 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#189541 = VECTOR('',#189542,1.); -#189542 = DIRECTION('',(-1.,0.E+000)); -#189543 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189544 = PCURVE('',#189088,#189545); -#189545 = DEFINITIONAL_REPRESENTATION('',(#189546),#189572); -#189546 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#189547,#189548,#189549, - #189550,#189551,#189552,#189553,#189554,#189555,#189556,#189557, - #189558,#189559,#189560,#189561,#189562,#189563,#189564,#189565, - #189566,#189567,#189568,#189569,#189570,#189571),.UNSPECIFIED.,.F., +#191862 = ORIENTED_EDGE('',*,*,#191691,.T.); +#191863 = ADVANCED_FACE('',(#191864),#191395,.T.); +#191864 = FACE_BOUND('',#191865,.T.); +#191865 = EDGE_LOOP('',(#191866,#191867,#191868,#191889)); +#191866 = ORIENTED_EDGE('',*,*,#191820,.T.); +#191867 = ORIENTED_EDGE('',*,*,#191668,.F.); +#191868 = ORIENTED_EDGE('',*,*,#191869,.F.); +#191869 = EDGE_CURVE('',#191380,#191646,#191870,.T.); +#191870 = SURFACE_CURVE('',#191871,(#191875,#191882),.PCURVE_S1.); +#191871 = LINE('',#191872,#191873); +#191872 = CARTESIAN_POINT('',(0.755,1.17,0.15)); +#191873 = VECTOR('',#191874,1.); +#191874 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191875 = PCURVE('',#191395,#191876); +#191876 = DEFINITIONAL_REPRESENTATION('',(#191877),#191881); +#191877 = LINE('',#191878,#191879); +#191878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191879 = VECTOR('',#191880,1.); +#191880 = DIRECTION('',(1.,0.E+000)); +#191881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191882 = PCURVE('',#191423,#191883); +#191883 = DEFINITIONAL_REPRESENTATION('',(#191884),#191888); +#191884 = LINE('',#191885,#191886); +#191885 = CARTESIAN_POINT('',(0.15,0.E+000)); +#191886 = VECTOR('',#191887,1.); +#191887 = DIRECTION('',(0.E+000,1.)); +#191888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191889 = ORIENTED_EDGE('',*,*,#191379,.T.); +#191890 = ADVANCED_FACE('',(#191891),#191423,.T.); +#191891 = FACE_BOUND('',#191892,.T.); +#191892 = EDGE_LOOP('',(#191893,#191894,#191895,#191916)); +#191893 = ORIENTED_EDGE('',*,*,#191869,.T.); +#191894 = ORIENTED_EDGE('',*,*,#191645,.F.); +#191895 = ORIENTED_EDGE('',*,*,#191896,.F.); +#191896 = EDGE_CURVE('',#191408,#191623,#191897,.T.); +#191897 = SURFACE_CURVE('',#191898,(#191902,#191909),.PCURVE_S1.); +#191898 = LINE('',#191899,#191900); +#191899 = CARTESIAN_POINT('',(0.755,1.17,0.E+000)); +#191900 = VECTOR('',#191901,1.); +#191901 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191902 = PCURVE('',#191423,#191903); +#191903 = DEFINITIONAL_REPRESENTATION('',(#191904),#191908); +#191904 = LINE('',#191905,#191906); +#191905 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191906 = VECTOR('',#191907,1.); +#191907 = DIRECTION('',(0.E+000,1.)); +#191908 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191909 = PCURVE('',#191451,#191910); +#191910 = DEFINITIONAL_REPRESENTATION('',(#191911),#191915); +#191911 = LINE('',#191912,#191913); +#191912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#191913 = VECTOR('',#191914,1.); +#191914 = DIRECTION('',(-1.,0.E+000)); +#191915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191916 = ORIENTED_EDGE('',*,*,#191407,.T.); +#191917 = ADVANCED_FACE('',(#191918),#191451,.T.); +#191918 = FACE_BOUND('',#191919,.T.); +#191919 = EDGE_LOOP('',(#191920,#191921,#191922,#191965)); +#191920 = ORIENTED_EDGE('',*,*,#191896,.T.); +#191921 = ORIENTED_EDGE('',*,*,#191622,.F.); +#191922 = ORIENTED_EDGE('',*,*,#191923,.F.); +#191923 = EDGE_CURVE('',#191436,#191600,#191924,.T.); +#191924 = SURFACE_CURVE('',#191925,(#191929,#191936),.PCURVE_S1.); +#191925 = LINE('',#191926,#191927); +#191926 = CARTESIAN_POINT('',(0.755,0.945297240108,0.E+000)); +#191927 = VECTOR('',#191928,1.); +#191928 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191929 = PCURVE('',#191451,#191930); +#191930 = DEFINITIONAL_REPRESENTATION('',(#191931),#191935); +#191931 = LINE('',#191932,#191933); +#191932 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#191933 = VECTOR('',#191934,1.); +#191934 = DIRECTION('',(-1.,0.E+000)); +#191935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191936 = PCURVE('',#191480,#191937); +#191937 = DEFINITIONAL_REPRESENTATION('',(#191938),#191964); +#191938 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#191939,#191940,#191941, + #191942,#191943,#191944,#191945,#191946,#191947,#191948,#191949, + #191950,#191951,#191952,#191953,#191954,#191955,#191956,#191957, + #191958,#191959,#191960,#191961,#191962,#191963),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -235442,949 +238444,949 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#189547 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#189548 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#189549 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#189550 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#189551 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#189552 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#189553 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#189554 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#189555 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#189556 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#189557 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#189558 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#189559 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#189560 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#189561 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#189562 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#189563 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#189564 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#189565 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#189566 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#189567 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#189568 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#189569 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#189570 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#189571 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#189572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189573 = ORIENTED_EDGE('',*,*,#189043,.T.); -#189574 = ADVANCED_FACE('',(#189575),#189088,.T.); -#189575 = FACE_BOUND('',#189576,.T.); -#189576 = EDGE_LOOP('',(#189577,#189578,#189579,#189599)); -#189577 = ORIENTED_EDGE('',*,*,#189531,.T.); -#189578 = ORIENTED_EDGE('',*,*,#189207,.F.); -#189579 = ORIENTED_EDGE('',*,*,#189580,.F.); -#189580 = EDGE_CURVE('',#189072,#189185,#189581,.T.); -#189581 = SURFACE_CURVE('',#189582,(#189586,#189592),.PCURVE_S1.); -#189582 = LINE('',#189583,#189584); -#189583 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); -#189584 = VECTOR('',#189585,1.); -#189585 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189586 = PCURVE('',#189088,#189587); -#189587 = DEFINITIONAL_REPRESENTATION('',(#189588),#189591); -#189588 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189589,#189590), +#191939 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#191940 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#191941 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#191942 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#191943 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#191944 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#191945 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#191946 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#191947 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#191948 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#191949 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#191950 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#191951 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#191952 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#191953 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#191954 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#191955 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#191956 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#191957 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#191958 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#191959 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#191960 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#191961 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#191962 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#191963 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#191964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191965 = ORIENTED_EDGE('',*,*,#191435,.T.); +#191966 = ADVANCED_FACE('',(#191967),#191480,.T.); +#191967 = FACE_BOUND('',#191968,.T.); +#191968 = EDGE_LOOP('',(#191969,#191970,#191971,#191991)); +#191969 = ORIENTED_EDGE('',*,*,#191923,.T.); +#191970 = ORIENTED_EDGE('',*,*,#191599,.F.); +#191971 = ORIENTED_EDGE('',*,*,#191972,.F.); +#191972 = EDGE_CURVE('',#191464,#191577,#191973,.T.); +#191973 = SURFACE_CURVE('',#191974,(#191978,#191984),.PCURVE_S1.); +#191974 = LINE('',#191975,#191976); +#191975 = CARTESIAN_POINT('',(0.755,0.746501027564,0.178089594298)); +#191976 = VECTOR('',#191977,1.); +#191977 = DIRECTION('',(1.,0.E+000,0.E+000)); +#191978 = PCURVE('',#191480,#191979); +#191979 = DEFINITIONAL_REPRESENTATION('',(#191980),#191983); +#191980 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191981,#191982), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#189589 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#189590 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#189591 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189592 = PCURVE('',#189115,#189593); -#189593 = DEFINITIONAL_REPRESENTATION('',(#189594),#189598); -#189594 = LINE('',#189595,#189596); -#189595 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#189596 = VECTOR('',#189597,1.); -#189597 = DIRECTION('',(0.E+000,1.)); -#189598 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189599 = ORIENTED_EDGE('',*,*,#189071,.T.); -#189600 = ADVANCED_FACE('',(#189601),#189115,.T.); -#189601 = FACE_BOUND('',#189602,.T.); -#189602 = EDGE_LOOP('',(#189603,#189604,#189605,#189625)); -#189603 = ORIENTED_EDGE('',*,*,#189580,.T.); -#189604 = ORIENTED_EDGE('',*,*,#189184,.F.); -#189605 = ORIENTED_EDGE('',*,*,#189606,.F.); -#189606 = EDGE_CURVE('',#189100,#189158,#189607,.T.); -#189607 = SURFACE_CURVE('',#189608,(#189612,#189619),.PCURVE_S1.); -#189608 = LINE('',#189609,#189610); -#189609 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); -#189610 = VECTOR('',#189611,1.); -#189611 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189612 = PCURVE('',#189115,#189613); -#189613 = DEFINITIONAL_REPRESENTATION('',(#189614),#189618); -#189614 = LINE('',#189615,#189616); -#189615 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189616 = VECTOR('',#189617,1.); -#189617 = DIRECTION('',(0.E+000,1.)); -#189618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189619 = PCURVE('',#188791,#189620); -#189620 = DEFINITIONAL_REPRESENTATION('',(#189621),#189624); -#189621 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189622,#189623), +#191981 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#191982 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#191983 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191984 = PCURVE('',#191507,#191985); +#191985 = DEFINITIONAL_REPRESENTATION('',(#191986),#191990); +#191986 = LINE('',#191987,#191988); +#191987 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#191988 = VECTOR('',#191989,1.); +#191989 = DIRECTION('',(0.E+000,1.)); +#191990 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#191991 = ORIENTED_EDGE('',*,*,#191463,.T.); +#191992 = ADVANCED_FACE('',(#191993),#191507,.T.); +#191993 = FACE_BOUND('',#191994,.T.); +#191994 = EDGE_LOOP('',(#191995,#191996,#191997,#192017)); +#191995 = ORIENTED_EDGE('',*,*,#191972,.T.); +#191996 = ORIENTED_EDGE('',*,*,#191576,.F.); +#191997 = ORIENTED_EDGE('',*,*,#191998,.F.); +#191998 = EDGE_CURVE('',#191492,#191550,#191999,.T.); +#191999 = SURFACE_CURVE('',#192000,(#192004,#192011),.PCURVE_S1.); +#192000 = LINE('',#192001,#192002); +#192001 = CARTESIAN_POINT('',(0.755,0.70490705433,0.555477601426)); +#192002 = VECTOR('',#192003,1.); +#192003 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192004 = PCURVE('',#191507,#192005); +#192005 = DEFINITIONAL_REPRESENTATION('',(#192006),#192010); +#192006 = LINE('',#192007,#192008); +#192007 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192008 = VECTOR('',#192009,1.); +#192009 = DIRECTION('',(0.E+000,1.)); +#192010 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192011 = PCURVE('',#191183,#192012); +#192012 = DEFINITIONAL_REPRESENTATION('',(#192013),#192016); +#192013 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192014,#192015), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#189622 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#189623 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#189624 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189625 = ORIENTED_EDGE('',*,*,#189099,.T.); -#189626 = ADVANCED_FACE('',(#189627),#188791,.F.); -#189627 = FACE_BOUND('',#189628,.F.); -#189628 = EDGE_LOOP('',(#189629,#189630,#189631,#189632)); -#189629 = ORIENTED_EDGE('',*,*,#189606,.F.); -#189630 = ORIENTED_EDGE('',*,*,#189127,.F.); -#189631 = ORIENTED_EDGE('',*,*,#188775,.T.); -#189632 = ORIENTED_EDGE('',*,*,#189157,.T.); -#189633 = ADVANCED_FACE('',(#189634),#186859,.T.); -#189634 = FACE_BOUND('',#189635,.T.); -#189635 = EDGE_LOOP('',(#189636,#189637,#189660,#189687)); -#189636 = ORIENTED_EDGE('',*,*,#186845,.T.); -#189637 = ORIENTED_EDGE('',*,*,#189638,.T.); -#189638 = EDGE_CURVE('',#185756,#189639,#189641,.T.); -#189639 = VERTEX_POINT('',#189640); -#189640 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#189641 = SURFACE_CURVE('',#189642,(#189646,#189653),.PCURVE_S1.); -#189642 = LINE('',#189643,#189644); -#189643 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#189644 = VECTOR('',#189645,1.); -#189645 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189646 = PCURVE('',#186859,#189647); -#189647 = DEFINITIONAL_REPRESENTATION('',(#189648),#189652); -#189648 = LINE('',#189649,#189650); -#189649 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189650 = VECTOR('',#189651,1.); -#189651 = DIRECTION('',(0.E+000,1.)); -#189652 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189653 = PCURVE('',#185771,#189654); -#189654 = DEFINITIONAL_REPRESENTATION('',(#189655),#189659); -#189655 = LINE('',#189656,#189657); -#189656 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#189657 = VECTOR('',#189658,1.); -#189658 = DIRECTION('',(0.E+000,1.)); -#189659 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189660 = ORIENTED_EDGE('',*,*,#189661,.T.); -#189661 = EDGE_CURVE('',#189639,#189662,#189664,.T.); -#189662 = VERTEX_POINT('',#189663); -#189663 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); -#189664 = SURFACE_CURVE('',#189665,(#189669,#189676),.PCURVE_S1.); -#189665 = LINE('',#189666,#189667); -#189666 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); -#189667 = VECTOR('',#189668,1.); -#189668 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189669 = PCURVE('',#186859,#189670); -#189670 = DEFINITIONAL_REPRESENTATION('',(#189671),#189675); -#189671 = LINE('',#189672,#189673); -#189672 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189673 = VECTOR('',#189674,1.); -#189674 = DIRECTION('',(-1.,0.E+000)); -#189675 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189676 = PCURVE('',#189677,#189682); -#189677 = CYLINDRICAL_SURFACE('',#189678,5.E-002); -#189678 = AXIS2_PLACEMENT_3D('',#189679,#189680,#189681); -#189679 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#189680 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189681 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189682 = DEFINITIONAL_REPRESENTATION('',(#189683),#189686); -#189683 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189684,#189685), +#192014 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#192015 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#192016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192017 = ORIENTED_EDGE('',*,*,#191491,.T.); +#192018 = ADVANCED_FACE('',(#192019),#191183,.F.); +#192019 = FACE_BOUND('',#192020,.F.); +#192020 = EDGE_LOOP('',(#192021,#192022,#192023,#192024)); +#192021 = ORIENTED_EDGE('',*,*,#191998,.F.); +#192022 = ORIENTED_EDGE('',*,*,#191519,.F.); +#192023 = ORIENTED_EDGE('',*,*,#191167,.T.); +#192024 = ORIENTED_EDGE('',*,*,#191549,.T.); +#192025 = ADVANCED_FACE('',(#192026),#189251,.T.); +#192026 = FACE_BOUND('',#192027,.T.); +#192027 = EDGE_LOOP('',(#192028,#192029,#192052,#192079)); +#192028 = ORIENTED_EDGE('',*,*,#189237,.T.); +#192029 = ORIENTED_EDGE('',*,*,#192030,.T.); +#192030 = EDGE_CURVE('',#188148,#192031,#192033,.T.); +#192031 = VERTEX_POINT('',#192032); +#192032 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#192033 = SURFACE_CURVE('',#192034,(#192038,#192045),.PCURVE_S1.); +#192034 = LINE('',#192035,#192036); +#192035 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#192036 = VECTOR('',#192037,1.); +#192037 = DIRECTION('',(0.E+000,1.,0.E+000)); +#192038 = PCURVE('',#189251,#192039); +#192039 = DEFINITIONAL_REPRESENTATION('',(#192040),#192044); +#192040 = LINE('',#192041,#192042); +#192041 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192042 = VECTOR('',#192043,1.); +#192043 = DIRECTION('',(0.E+000,1.)); +#192044 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192045 = PCURVE('',#188163,#192046); +#192046 = DEFINITIONAL_REPRESENTATION('',(#192047),#192051); +#192047 = LINE('',#192048,#192049); +#192048 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#192049 = VECTOR('',#192050,1.); +#192050 = DIRECTION('',(0.E+000,1.)); +#192051 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192052 = ORIENTED_EDGE('',*,*,#192053,.T.); +#192053 = EDGE_CURVE('',#192031,#192054,#192056,.T.); +#192054 = VERTEX_POINT('',#192055); +#192055 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); +#192056 = SURFACE_CURVE('',#192057,(#192061,#192068),.PCURVE_S1.); +#192057 = LINE('',#192058,#192059); +#192058 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.6)); +#192059 = VECTOR('',#192060,1.); +#192060 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192061 = PCURVE('',#189251,#192062); +#192062 = DEFINITIONAL_REPRESENTATION('',(#192063),#192067); +#192063 = LINE('',#192064,#192065); +#192064 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192065 = VECTOR('',#192066,1.); +#192066 = DIRECTION('',(-1.,0.E+000)); +#192067 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192068 = PCURVE('',#192069,#192074); +#192069 = CYLINDRICAL_SURFACE('',#192070,5.E-002); +#192070 = AXIS2_PLACEMENT_3D('',#192071,#192072,#192073); +#192071 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#192072 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192073 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192074 = DEFINITIONAL_REPRESENTATION('',(#192075),#192078); +#192075 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192076,#192077), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#189684 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#189685 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#189686 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189687 = ORIENTED_EDGE('',*,*,#189688,.F.); -#189688 = EDGE_CURVE('',#185677,#189662,#189689,.T.); -#189689 = SURFACE_CURVE('',#189690,(#189694,#189701),.PCURVE_S1.); -#189690 = LINE('',#189691,#189692); -#189691 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); -#189692 = VECTOR('',#189693,1.); -#189693 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189694 = PCURVE('',#186859,#189695); -#189695 = DEFINITIONAL_REPRESENTATION('',(#189696),#189700); -#189696 = LINE('',#189697,#189698); -#189697 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#189698 = VECTOR('',#189699,1.); -#189699 = DIRECTION('',(0.E+000,1.)); -#189700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189701 = PCURVE('',#185715,#189702); -#189702 = DEFINITIONAL_REPRESENTATION('',(#189703),#189707); -#189703 = LINE('',#189704,#189705); -#189704 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#189705 = VECTOR('',#189706,1.); -#189706 = DIRECTION('',(0.E+000,1.)); -#189707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189708 = ADVANCED_FACE('',(#189709),#185771,.F.); -#189709 = FACE_BOUND('',#189710,.T.); -#189710 = EDGE_LOOP('',(#189711,#189712,#189713,#189736,#189764,#189792, - #189824,#189852,#189880,#189908,#189936,#189964)); -#189711 = ORIENTED_EDGE('',*,*,#189638,.F.); -#189712 = ORIENTED_EDGE('',*,*,#185755,.T.); -#189713 = ORIENTED_EDGE('',*,*,#189714,.F.); -#189714 = EDGE_CURVE('',#189715,#185728,#189717,.T.); -#189715 = VERTEX_POINT('',#189716); -#189716 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#189717 = SURFACE_CURVE('',#189718,(#189722,#189729),.PCURVE_S1.); -#189718 = LINE('',#189719,#189720); -#189719 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#189720 = VECTOR('',#189721,1.); -#189721 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#189722 = PCURVE('',#185771,#189723); -#189723 = DEFINITIONAL_REPRESENTATION('',(#189724),#189728); -#189724 = LINE('',#189725,#189726); -#189725 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#189726 = VECTOR('',#189727,1.); -#189727 = DIRECTION('',(0.E+000,-1.)); -#189728 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#192076 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#192077 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#192078 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192079 = ORIENTED_EDGE('',*,*,#192080,.F.); +#192080 = EDGE_CURVE('',#188069,#192054,#192081,.T.); +#192081 = SURFACE_CURVE('',#192082,(#192086,#192093),.PCURVE_S1.); +#192082 = LINE('',#192083,#192084); +#192083 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.6)); +#192084 = VECTOR('',#192085,1.); +#192085 = DIRECTION('',(0.E+000,1.,0.E+000)); +#192086 = PCURVE('',#189251,#192087); +#192087 = DEFINITIONAL_REPRESENTATION('',(#192088),#192092); +#192088 = LINE('',#192089,#192090); +#192089 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#192090 = VECTOR('',#192091,1.); +#192091 = DIRECTION('',(0.E+000,1.)); +#192092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192093 = PCURVE('',#188107,#192094); +#192094 = DEFINITIONAL_REPRESENTATION('',(#192095),#192099); +#192095 = LINE('',#192096,#192097); +#192096 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#192097 = VECTOR('',#192098,1.); +#192098 = DIRECTION('',(0.E+000,1.)); +#192099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192100 = ADVANCED_FACE('',(#192101),#188163,.F.); +#192101 = FACE_BOUND('',#192102,.T.); +#192102 = EDGE_LOOP('',(#192103,#192104,#192105,#192128,#192156,#192184, + #192216,#192244,#192272,#192300,#192328,#192356)); +#192103 = ORIENTED_EDGE('',*,*,#192030,.F.); +#192104 = ORIENTED_EDGE('',*,*,#188147,.T.); +#192105 = ORIENTED_EDGE('',*,*,#192106,.F.); +#192106 = EDGE_CURVE('',#192107,#188120,#192109,.T.); +#192107 = VERTEX_POINT('',#192108); +#192108 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#192109 = SURFACE_CURVE('',#192110,(#192114,#192121),.PCURVE_S1.); +#192110 = LINE('',#192111,#192112); +#192111 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#192112 = VECTOR('',#192113,1.); +#192113 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192114 = PCURVE('',#188163,#192115); +#192115 = DEFINITIONAL_REPRESENTATION('',(#192116),#192120); +#192116 = LINE('',#192117,#192118); +#192117 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#192118 = VECTOR('',#192119,1.); +#192119 = DIRECTION('',(0.E+000,-1.)); +#192120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#189729 = PCURVE('',#185743,#189730); -#189730 = DEFINITIONAL_REPRESENTATION('',(#189731),#189735); -#189731 = LINE('',#189732,#189733); -#189732 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189733 = VECTOR('',#189734,1.); -#189734 = DIRECTION('',(0.E+000,-1.)); -#189735 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189736 = ORIENTED_EDGE('',*,*,#189737,.F.); -#189737 = EDGE_CURVE('',#189738,#189715,#189740,.T.); -#189738 = VERTEX_POINT('',#189739); -#189739 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); -#189740 = SURFACE_CURVE('',#189741,(#189746,#189753),.PCURVE_S1.); -#189741 = CIRCLE('',#189742,0.2); -#189742 = AXIS2_PLACEMENT_3D('',#189743,#189744,#189745); -#189743 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#189744 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189745 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189746 = PCURVE('',#185771,#189747); -#189747 = DEFINITIONAL_REPRESENTATION('',(#189748),#189752); -#189748 = CIRCLE('',#189749,0.2); -#189749 = AXIS2_PLACEMENT_2D('',#189750,#189751); -#189750 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189751 = DIRECTION('',(1.,0.E+000)); -#189752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189753 = PCURVE('',#189754,#189759); -#189754 = CYLINDRICAL_SURFACE('',#189755,0.2); -#189755 = AXIS2_PLACEMENT_3D('',#189756,#189757,#189758); -#189756 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#189757 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189758 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189759 = DEFINITIONAL_REPRESENTATION('',(#189760),#189763); -#189760 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189761,#189762), +#192121 = PCURVE('',#188135,#192122); +#192122 = DEFINITIONAL_REPRESENTATION('',(#192123),#192127); +#192123 = LINE('',#192124,#192125); +#192124 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192125 = VECTOR('',#192126,1.); +#192126 = DIRECTION('',(0.E+000,-1.)); +#192127 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192128 = ORIENTED_EDGE('',*,*,#192129,.F.); +#192129 = EDGE_CURVE('',#192130,#192107,#192132,.T.); +#192130 = VERTEX_POINT('',#192131); +#192131 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); +#192132 = SURFACE_CURVE('',#192133,(#192138,#192145),.PCURVE_S1.); +#192133 = CIRCLE('',#192134,0.2); +#192134 = AXIS2_PLACEMENT_3D('',#192135,#192136,#192137); +#192135 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#192136 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192137 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192138 = PCURVE('',#188163,#192139); +#192139 = DEFINITIONAL_REPRESENTATION('',(#192140),#192144); +#192140 = CIRCLE('',#192141,0.2); +#192141 = AXIS2_PLACEMENT_2D('',#192142,#192143); +#192142 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192143 = DIRECTION('',(1.,0.E+000)); +#192144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192145 = PCURVE('',#192146,#192151); +#192146 = CYLINDRICAL_SURFACE('',#192147,0.2); +#192147 = AXIS2_PLACEMENT_3D('',#192148,#192149,#192150); +#192148 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#192149 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192150 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192151 = DEFINITIONAL_REPRESENTATION('',(#192152),#192155); +#192152 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192153,#192154), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#189761 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#189762 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#189763 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189764 = ORIENTED_EDGE('',*,*,#189765,.F.); -#189765 = EDGE_CURVE('',#189766,#189738,#189768,.T.); -#189766 = VERTEX_POINT('',#189767); -#189767 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#189768 = SURFACE_CURVE('',#189769,(#189773,#189780),.PCURVE_S1.); -#189769 = LINE('',#189770,#189771); -#189770 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#189771 = VECTOR('',#189772,1.); -#189772 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#189773 = PCURVE('',#185771,#189774); -#189774 = DEFINITIONAL_REPRESENTATION('',(#189775),#189779); -#189775 = LINE('',#189776,#189777); -#189776 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#189777 = VECTOR('',#189778,1.); -#189778 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#189779 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189780 = PCURVE('',#189781,#189786); -#189781 = PLANE('',#189782); -#189782 = AXIS2_PLACEMENT_3D('',#189783,#189784,#189785); -#189783 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#189784 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#189785 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#189786 = DEFINITIONAL_REPRESENTATION('',(#189787),#189791); -#189787 = LINE('',#189788,#189789); -#189788 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189789 = VECTOR('',#189790,1.); -#189790 = DIRECTION('',(1.,0.E+000)); -#189791 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189792 = ORIENTED_EDGE('',*,*,#189793,.F.); -#189793 = EDGE_CURVE('',#189794,#189766,#189796,.T.); -#189794 = VERTEX_POINT('',#189795); -#189795 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); -#189796 = SURFACE_CURVE('',#189797,(#189802,#189813),.PCURVE_S1.); -#189797 = CIRCLE('',#189798,5.E-002); -#189798 = AXIS2_PLACEMENT_3D('',#189799,#189800,#189801); -#189799 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#189800 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189801 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189802 = PCURVE('',#185771,#189803); -#189803 = DEFINITIONAL_REPRESENTATION('',(#189804),#189812); -#189804 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#189805,#189806,#189807, - #189808,#189809,#189810,#189811),.UNSPECIFIED.,.F.,.F.) +#192153 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#192154 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#192155 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192156 = ORIENTED_EDGE('',*,*,#192157,.F.); +#192157 = EDGE_CURVE('',#192158,#192130,#192160,.T.); +#192158 = VERTEX_POINT('',#192159); +#192159 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#192160 = SURFACE_CURVE('',#192161,(#192165,#192172),.PCURVE_S1.); +#192161 = LINE('',#192162,#192163); +#192162 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#192163 = VECTOR('',#192164,1.); +#192164 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#192165 = PCURVE('',#188163,#192166); +#192166 = DEFINITIONAL_REPRESENTATION('',(#192167),#192171); +#192167 = LINE('',#192168,#192169); +#192168 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#192169 = VECTOR('',#192170,1.); +#192170 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#192171 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192172 = PCURVE('',#192173,#192178); +#192173 = PLANE('',#192174); +#192174 = AXIS2_PLACEMENT_3D('',#192175,#192176,#192177); +#192175 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#192176 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#192177 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#192178 = DEFINITIONAL_REPRESENTATION('',(#192179),#192183); +#192179 = LINE('',#192180,#192181); +#192180 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192181 = VECTOR('',#192182,1.); +#192182 = DIRECTION('',(1.,0.E+000)); +#192183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192184 = ORIENTED_EDGE('',*,*,#192185,.F.); +#192185 = EDGE_CURVE('',#192186,#192158,#192188,.T.); +#192186 = VERTEX_POINT('',#192187); +#192187 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); +#192188 = SURFACE_CURVE('',#192189,(#192194,#192205),.PCURVE_S1.); +#192189 = CIRCLE('',#192190,5.E-002); +#192190 = AXIS2_PLACEMENT_3D('',#192191,#192192,#192193); +#192191 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#192192 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#192193 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192194 = PCURVE('',#188163,#192195); +#192195 = DEFINITIONAL_REPRESENTATION('',(#192196),#192204); +#192196 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192197,#192198,#192199, + #192200,#192201,#192202,#192203),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#189805 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#189806 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#189807 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#189808 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#189809 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#189810 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#189811 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#189812 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189813 = PCURVE('',#189814,#189819); -#189814 = CYLINDRICAL_SURFACE('',#189815,5.E-002); -#189815 = AXIS2_PLACEMENT_3D('',#189816,#189817,#189818); -#189816 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#189817 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189818 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189819 = DEFINITIONAL_REPRESENTATION('',(#189820),#189823); -#189820 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189821,#189822), +#192197 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#192198 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#192199 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#192200 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#192201 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#192202 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#192203 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#192204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192205 = PCURVE('',#192206,#192211); +#192206 = CYLINDRICAL_SURFACE('',#192207,5.E-002); +#192207 = AXIS2_PLACEMENT_3D('',#192208,#192209,#192210); +#192208 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#192209 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192210 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192211 = DEFINITIONAL_REPRESENTATION('',(#192212),#192215); +#192212 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192213,#192214), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#189821 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#189822 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#189823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189824 = ORIENTED_EDGE('',*,*,#189825,.F.); -#189825 = EDGE_CURVE('',#189826,#189794,#189828,.T.); -#189826 = VERTEX_POINT('',#189827); -#189827 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#189828 = SURFACE_CURVE('',#189829,(#189833,#189840),.PCURVE_S1.); -#189829 = LINE('',#189830,#189831); -#189830 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#189831 = VECTOR('',#189832,1.); -#189832 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#189833 = PCURVE('',#185771,#189834); -#189834 = DEFINITIONAL_REPRESENTATION('',(#189835),#189839); -#189835 = LINE('',#189836,#189837); -#189836 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#189837 = VECTOR('',#189838,1.); -#189838 = DIRECTION('',(0.E+000,-1.)); -#189839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189840 = PCURVE('',#189841,#189846); -#189841 = PLANE('',#189842); -#189842 = AXIS2_PLACEMENT_3D('',#189843,#189844,#189845); -#189843 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#189844 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189845 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189846 = DEFINITIONAL_REPRESENTATION('',(#189847),#189851); -#189847 = LINE('',#189848,#189849); -#189848 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189849 = VECTOR('',#189850,1.); -#189850 = DIRECTION('',(0.E+000,-1.)); -#189851 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189852 = ORIENTED_EDGE('',*,*,#189853,.F.); -#189853 = EDGE_CURVE('',#189854,#189826,#189856,.T.); -#189854 = VERTEX_POINT('',#189855); -#189855 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#189856 = SURFACE_CURVE('',#189857,(#189861,#189868),.PCURVE_S1.); -#189857 = LINE('',#189858,#189859); -#189858 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#189859 = VECTOR('',#189860,1.); -#189860 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189861 = PCURVE('',#185771,#189862); -#189862 = DEFINITIONAL_REPRESENTATION('',(#189863),#189867); -#189863 = LINE('',#189864,#189865); -#189864 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189865 = VECTOR('',#189866,1.); -#189866 = DIRECTION('',(-1.,0.E+000)); -#189867 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189868 = PCURVE('',#189869,#189874); -#189869 = PLANE('',#189870); -#189870 = AXIS2_PLACEMENT_3D('',#189871,#189872,#189873); -#189871 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#189872 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189873 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189874 = DEFINITIONAL_REPRESENTATION('',(#189875),#189879); -#189875 = LINE('',#189876,#189877); -#189876 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189877 = VECTOR('',#189878,1.); -#189878 = DIRECTION('',(1.,0.E+000)); -#189879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189880 = ORIENTED_EDGE('',*,*,#189881,.F.); -#189881 = EDGE_CURVE('',#189882,#189854,#189884,.T.); -#189882 = VERTEX_POINT('',#189883); -#189883 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); -#189884 = SURFACE_CURVE('',#189885,(#189889,#189896),.PCURVE_S1.); -#189885 = LINE('',#189886,#189887); -#189886 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#189887 = VECTOR('',#189888,1.); -#189888 = DIRECTION('',(0.E+000,1.,0.E+000)); -#189889 = PCURVE('',#185771,#189890); -#189890 = DEFINITIONAL_REPRESENTATION('',(#189891),#189895); -#189891 = LINE('',#189892,#189893); -#189892 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#189893 = VECTOR('',#189894,1.); -#189894 = DIRECTION('',(0.E+000,1.)); -#189895 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189896 = PCURVE('',#189897,#189902); -#189897 = PLANE('',#189898); -#189898 = AXIS2_PLACEMENT_3D('',#189899,#189900,#189901); -#189899 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#189900 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189901 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189902 = DEFINITIONAL_REPRESENTATION('',(#189903),#189907); -#189903 = LINE('',#189904,#189905); -#189904 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189905 = VECTOR('',#189906,1.); -#189906 = DIRECTION('',(0.E+000,1.)); -#189907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189908 = ORIENTED_EDGE('',*,*,#189909,.F.); -#189909 = EDGE_CURVE('',#189910,#189882,#189912,.T.); -#189910 = VERTEX_POINT('',#189911); -#189911 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); -#189912 = SURFACE_CURVE('',#189913,(#189918,#189925),.PCURVE_S1.); -#189913 = CIRCLE('',#189914,0.2); -#189914 = AXIS2_PLACEMENT_3D('',#189915,#189916,#189917); -#189915 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#189916 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189917 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189918 = PCURVE('',#185771,#189919); -#189919 = DEFINITIONAL_REPRESENTATION('',(#189920),#189924); -#189920 = CIRCLE('',#189921,0.2); -#189921 = AXIS2_PLACEMENT_2D('',#189922,#189923); -#189922 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#189923 = DIRECTION('',(1.,0.E+000)); -#189924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189925 = PCURVE('',#189926,#189931); -#189926 = CYLINDRICAL_SURFACE('',#189927,0.2); -#189927 = AXIS2_PLACEMENT_3D('',#189928,#189929,#189930); -#189928 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); -#189929 = DIRECTION('',(1.,0.E+000,0.E+000)); -#189930 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#189931 = DEFINITIONAL_REPRESENTATION('',(#189932),#189935); -#189932 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189933,#189934), +#192213 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#192214 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#192215 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192216 = ORIENTED_EDGE('',*,*,#192217,.F.); +#192217 = EDGE_CURVE('',#192218,#192186,#192220,.T.); +#192218 = VERTEX_POINT('',#192219); +#192219 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#192220 = SURFACE_CURVE('',#192221,(#192225,#192232),.PCURVE_S1.); +#192221 = LINE('',#192222,#192223); +#192222 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#192223 = VECTOR('',#192224,1.); +#192224 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192225 = PCURVE('',#188163,#192226); +#192226 = DEFINITIONAL_REPRESENTATION('',(#192227),#192231); +#192227 = LINE('',#192228,#192229); +#192228 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#192229 = VECTOR('',#192230,1.); +#192230 = DIRECTION('',(0.E+000,-1.)); +#192231 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192232 = PCURVE('',#192233,#192238); +#192233 = PLANE('',#192234); +#192234 = AXIS2_PLACEMENT_3D('',#192235,#192236,#192237); +#192235 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#192236 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192237 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192238 = DEFINITIONAL_REPRESENTATION('',(#192239),#192243); +#192239 = LINE('',#192240,#192241); +#192240 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192241 = VECTOR('',#192242,1.); +#192242 = DIRECTION('',(0.E+000,-1.)); +#192243 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192244 = ORIENTED_EDGE('',*,*,#192245,.F.); +#192245 = EDGE_CURVE('',#192246,#192218,#192248,.T.); +#192246 = VERTEX_POINT('',#192247); +#192247 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192248 = SURFACE_CURVE('',#192249,(#192253,#192260),.PCURVE_S1.); +#192249 = LINE('',#192250,#192251); +#192250 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192251 = VECTOR('',#192252,1.); +#192252 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192253 = PCURVE('',#188163,#192254); +#192254 = DEFINITIONAL_REPRESENTATION('',(#192255),#192259); +#192255 = LINE('',#192256,#192257); +#192256 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#192257 = VECTOR('',#192258,1.); +#192258 = DIRECTION('',(-1.,0.E+000)); +#192259 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192260 = PCURVE('',#192261,#192266); +#192261 = PLANE('',#192262); +#192262 = AXIS2_PLACEMENT_3D('',#192263,#192264,#192265); +#192263 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192264 = DIRECTION('',(0.E+000,1.,0.E+000)); +#192265 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192266 = DEFINITIONAL_REPRESENTATION('',(#192267),#192271); +#192267 = LINE('',#192268,#192269); +#192268 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192269 = VECTOR('',#192270,1.); +#192270 = DIRECTION('',(1.,0.E+000)); +#192271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192272 = ORIENTED_EDGE('',*,*,#192273,.F.); +#192273 = EDGE_CURVE('',#192274,#192246,#192276,.T.); +#192274 = VERTEX_POINT('',#192275); +#192275 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); +#192276 = SURFACE_CURVE('',#192277,(#192281,#192288),.PCURVE_S1.); +#192277 = LINE('',#192278,#192279); +#192278 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192279 = VECTOR('',#192280,1.); +#192280 = DIRECTION('',(0.E+000,1.,0.E+000)); +#192281 = PCURVE('',#188163,#192282); +#192282 = DEFINITIONAL_REPRESENTATION('',(#192283),#192287); +#192283 = LINE('',#192284,#192285); +#192284 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#192285 = VECTOR('',#192286,1.); +#192286 = DIRECTION('',(0.E+000,1.)); +#192287 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192288 = PCURVE('',#192289,#192294); +#192289 = PLANE('',#192290); +#192290 = AXIS2_PLACEMENT_3D('',#192291,#192292,#192293); +#192291 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192292 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192293 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#192294 = DEFINITIONAL_REPRESENTATION('',(#192295),#192299); +#192295 = LINE('',#192296,#192297); +#192296 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192297 = VECTOR('',#192298,1.); +#192298 = DIRECTION('',(0.E+000,1.)); +#192299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192300 = ORIENTED_EDGE('',*,*,#192301,.F.); +#192301 = EDGE_CURVE('',#192302,#192274,#192304,.T.); +#192302 = VERTEX_POINT('',#192303); +#192303 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); +#192304 = SURFACE_CURVE('',#192305,(#192310,#192317),.PCURVE_S1.); +#192305 = CIRCLE('',#192306,0.2); +#192306 = AXIS2_PLACEMENT_3D('',#192307,#192308,#192309); +#192307 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#192308 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192309 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192310 = PCURVE('',#188163,#192311); +#192311 = DEFINITIONAL_REPRESENTATION('',(#192312),#192316); +#192312 = CIRCLE('',#192313,0.2); +#192313 = AXIS2_PLACEMENT_2D('',#192314,#192315); +#192314 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#192315 = DIRECTION('',(1.,0.E+000)); +#192316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192317 = PCURVE('',#192318,#192323); +#192318 = CYLINDRICAL_SURFACE('',#192319,0.2); +#192319 = AXIS2_PLACEMENT_3D('',#192320,#192321,#192322); +#192320 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.2)); +#192321 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192322 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192323 = DEFINITIONAL_REPRESENTATION('',(#192324),#192327); +#192324 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192325,#192326), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#189933 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#189934 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#189935 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189936 = ORIENTED_EDGE('',*,*,#189937,.F.); -#189937 = EDGE_CURVE('',#189938,#189910,#189940,.T.); -#189938 = VERTEX_POINT('',#189939); -#189939 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#189940 = SURFACE_CURVE('',#189941,(#189945,#189952),.PCURVE_S1.); -#189941 = LINE('',#189942,#189943); -#189942 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#189943 = VECTOR('',#189944,1.); -#189944 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#189945 = PCURVE('',#185771,#189946); -#189946 = DEFINITIONAL_REPRESENTATION('',(#189947),#189951); -#189947 = LINE('',#189948,#189949); -#189948 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#189949 = VECTOR('',#189950,1.); -#189950 = DIRECTION('',(0.993981062721,0.109552028512)); -#189951 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189952 = PCURVE('',#189953,#189958); -#189953 = PLANE('',#189954); -#189954 = AXIS2_PLACEMENT_3D('',#189955,#189956,#189957); -#189955 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#189956 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#189957 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#189958 = DEFINITIONAL_REPRESENTATION('',(#189959),#189963); -#189959 = LINE('',#189960,#189961); -#189960 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#189961 = VECTOR('',#189962,1.); -#189962 = DIRECTION('',(1.,0.E+000)); -#189963 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189964 = ORIENTED_EDGE('',*,*,#189965,.F.); -#189965 = EDGE_CURVE('',#189639,#189938,#189966,.T.); -#189966 = SURFACE_CURVE('',#189967,(#189972,#189983),.PCURVE_S1.); -#189967 = CIRCLE('',#189968,5.E-002); -#189968 = AXIS2_PLACEMENT_3D('',#189969,#189970,#189971); -#189969 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); -#189970 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#189971 = DIRECTION('',(0.E+000,0.E+000,1.)); -#189972 = PCURVE('',#185771,#189973); -#189973 = DEFINITIONAL_REPRESENTATION('',(#189974),#189982); -#189974 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#189975,#189976,#189977, - #189978,#189979,#189980,#189981),.UNSPECIFIED.,.F.,.F.) +#192325 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#192326 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#192327 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192328 = ORIENTED_EDGE('',*,*,#192329,.F.); +#192329 = EDGE_CURVE('',#192330,#192302,#192332,.T.); +#192330 = VERTEX_POINT('',#192331); +#192331 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#192332 = SURFACE_CURVE('',#192333,(#192337,#192344),.PCURVE_S1.); +#192333 = LINE('',#192334,#192335); +#192334 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#192335 = VECTOR('',#192336,1.); +#192336 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#192337 = PCURVE('',#188163,#192338); +#192338 = DEFINITIONAL_REPRESENTATION('',(#192339),#192343); +#192339 = LINE('',#192340,#192341); +#192340 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#192341 = VECTOR('',#192342,1.); +#192342 = DIRECTION('',(0.993981062721,0.109552028512)); +#192343 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192344 = PCURVE('',#192345,#192350); +#192345 = PLANE('',#192346); +#192346 = AXIS2_PLACEMENT_3D('',#192347,#192348,#192349); +#192347 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#192348 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#192349 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#192350 = DEFINITIONAL_REPRESENTATION('',(#192351),#192355); +#192351 = LINE('',#192352,#192353); +#192352 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192353 = VECTOR('',#192354,1.); +#192354 = DIRECTION('',(1.,0.E+000)); +#192355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192356 = ORIENTED_EDGE('',*,*,#192357,.F.); +#192357 = EDGE_CURVE('',#192031,#192330,#192358,.T.); +#192358 = SURFACE_CURVE('',#192359,(#192364,#192375),.PCURVE_S1.); +#192359 = CIRCLE('',#192360,5.E-002); +#192360 = AXIS2_PLACEMENT_3D('',#192361,#192362,#192363); +#192361 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.55)); +#192362 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#192363 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192364 = PCURVE('',#188163,#192365); +#192365 = DEFINITIONAL_REPRESENTATION('',(#192366),#192374); +#192366 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192367,#192368,#192369, + #192370,#192371,#192372,#192373),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#189975 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189976 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#189977 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#189978 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#189979 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#189980 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#189981 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#189982 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189983 = PCURVE('',#189677,#189984); -#189984 = DEFINITIONAL_REPRESENTATION('',(#189985),#189988); -#189985 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#189986,#189987), +#192367 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#192368 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#192369 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#192370 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#192371 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#192372 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#192373 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#192374 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192375 = PCURVE('',#192069,#192376); +#192376 = DEFINITIONAL_REPRESENTATION('',(#192377),#192380); +#192377 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192378,#192379), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#189986 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#189987 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#189988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#189989 = ADVANCED_FACE('',(#189990),#185743,.T.); -#189990 = FACE_BOUND('',#189991,.T.); -#189991 = EDGE_LOOP('',(#189992,#189993,#190016,#190036)); -#189992 = ORIENTED_EDGE('',*,*,#185727,.F.); -#189993 = ORIENTED_EDGE('',*,*,#189994,.F.); -#189994 = EDGE_CURVE('',#189995,#185700,#189997,.T.); -#189995 = VERTEX_POINT('',#189996); -#189996 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); -#189997 = SURFACE_CURVE('',#189998,(#190002,#190009),.PCURVE_S1.); -#189998 = LINE('',#189999,#190000); -#189999 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); -#190000 = VECTOR('',#190001,1.); -#190001 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190002 = PCURVE('',#185743,#190003); -#190003 = DEFINITIONAL_REPRESENTATION('',(#190004),#190008); -#190004 = LINE('',#190005,#190006); -#190005 = CARTESIAN_POINT('',(0.4,0.E+000)); -#190006 = VECTOR('',#190007,1.); -#190007 = DIRECTION('',(0.E+000,-1.)); -#190008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190009 = PCURVE('',#185715,#190010); -#190010 = DEFINITIONAL_REPRESENTATION('',(#190011),#190015); -#190011 = LINE('',#190012,#190013); -#190012 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#190013 = VECTOR('',#190014,1.); -#190014 = DIRECTION('',(0.E+000,-1.)); -#190015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190016 = ORIENTED_EDGE('',*,*,#190017,.F.); -#190017 = EDGE_CURVE('',#189715,#189995,#190018,.T.); -#190018 = SURFACE_CURVE('',#190019,(#190023,#190030),.PCURVE_S1.); -#190019 = LINE('',#190020,#190021); -#190020 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); -#190021 = VECTOR('',#190022,1.); -#190022 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190023 = PCURVE('',#185743,#190024); -#190024 = DEFINITIONAL_REPRESENTATION('',(#190025),#190029); -#190025 = LINE('',#190026,#190027); -#190026 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190027 = VECTOR('',#190028,1.); -#190028 = DIRECTION('',(1.,0.E+000)); -#190029 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190030 = PCURVE('',#189754,#190031); -#190031 = DEFINITIONAL_REPRESENTATION('',(#190032),#190035); -#190032 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190033,#190034), +#192378 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#192379 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#192380 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192381 = ADVANCED_FACE('',(#192382),#188135,.T.); +#192382 = FACE_BOUND('',#192383,.T.); +#192383 = EDGE_LOOP('',(#192384,#192385,#192408,#192428)); +#192384 = ORIENTED_EDGE('',*,*,#188119,.F.); +#192385 = ORIENTED_EDGE('',*,*,#192386,.F.); +#192386 = EDGE_CURVE('',#192387,#188092,#192389,.T.); +#192387 = VERTEX_POINT('',#192388); +#192388 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); +#192389 = SURFACE_CURVE('',#192390,(#192394,#192401),.PCURVE_S1.); +#192390 = LINE('',#192391,#192392); +#192391 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.75)); +#192392 = VECTOR('',#192393,1.); +#192393 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192394 = PCURVE('',#188135,#192395); +#192395 = DEFINITIONAL_REPRESENTATION('',(#192396),#192400); +#192396 = LINE('',#192397,#192398); +#192397 = CARTESIAN_POINT('',(0.4,0.E+000)); +#192398 = VECTOR('',#192399,1.); +#192399 = DIRECTION('',(0.E+000,-1.)); +#192400 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192401 = PCURVE('',#188107,#192402); +#192402 = DEFINITIONAL_REPRESENTATION('',(#192403),#192407); +#192403 = LINE('',#192404,#192405); +#192404 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#192405 = VECTOR('',#192406,1.); +#192406 = DIRECTION('',(0.E+000,-1.)); +#192407 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192408 = ORIENTED_EDGE('',*,*,#192409,.F.); +#192409 = EDGE_CURVE('',#192107,#192387,#192410,.T.); +#192410 = SURFACE_CURVE('',#192411,(#192415,#192422),.PCURVE_S1.); +#192411 = LINE('',#192412,#192413); +#192412 = CARTESIAN_POINT('',(-1.145,0.655208001194,0.75)); +#192413 = VECTOR('',#192414,1.); +#192414 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192415 = PCURVE('',#188135,#192416); +#192416 = DEFINITIONAL_REPRESENTATION('',(#192417),#192421); +#192417 = LINE('',#192418,#192419); +#192418 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192419 = VECTOR('',#192420,1.); +#192420 = DIRECTION('',(1.,0.E+000)); +#192421 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192422 = PCURVE('',#192146,#192423); +#192423 = DEFINITIONAL_REPRESENTATION('',(#192424),#192427); +#192424 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192425,#192426), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190033 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#190034 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190035 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190036 = ORIENTED_EDGE('',*,*,#189714,.T.); -#190037 = ADVANCED_FACE('',(#190038),#185715,.T.); -#190038 = FACE_BOUND('',#190039,.T.); -#190039 = EDGE_LOOP('',(#190040,#190041,#190042,#190069,#190092,#190115, - #190138,#190161,#190184,#190211,#190234,#190255)); -#190040 = ORIENTED_EDGE('',*,*,#185699,.F.); -#190041 = ORIENTED_EDGE('',*,*,#189688,.T.); -#190042 = ORIENTED_EDGE('',*,*,#190043,.T.); -#190043 = EDGE_CURVE('',#189662,#190044,#190046,.T.); -#190044 = VERTEX_POINT('',#190045); -#190045 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); -#190046 = SURFACE_CURVE('',#190047,(#190052,#190063),.PCURVE_S1.); -#190047 = CIRCLE('',#190048,5.E-002); -#190048 = AXIS2_PLACEMENT_3D('',#190049,#190050,#190051); -#190049 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#190050 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190051 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190052 = PCURVE('',#185715,#190053); -#190053 = DEFINITIONAL_REPRESENTATION('',(#190054),#190062); -#190054 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190055,#190056,#190057, - #190058,#190059,#190060,#190061),.UNSPECIFIED.,.F.,.F.) +#192425 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#192426 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#192427 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192428 = ORIENTED_EDGE('',*,*,#192106,.T.); +#192429 = ADVANCED_FACE('',(#192430),#188107,.T.); +#192430 = FACE_BOUND('',#192431,.T.); +#192431 = EDGE_LOOP('',(#192432,#192433,#192434,#192461,#192484,#192507, + #192530,#192553,#192576,#192603,#192626,#192647)); +#192432 = ORIENTED_EDGE('',*,*,#188091,.F.); +#192433 = ORIENTED_EDGE('',*,*,#192080,.T.); +#192434 = ORIENTED_EDGE('',*,*,#192435,.T.); +#192435 = EDGE_CURVE('',#192054,#192436,#192438,.T.); +#192436 = VERTEX_POINT('',#192437); +#192437 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); +#192438 = SURFACE_CURVE('',#192439,(#192444,#192455),.PCURVE_S1.); +#192439 = CIRCLE('',#192440,5.E-002); +#192440 = AXIS2_PLACEMENT_3D('',#192441,#192442,#192443); +#192441 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#192442 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#192443 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192444 = PCURVE('',#188107,#192445); +#192445 = DEFINITIONAL_REPRESENTATION('',(#192446),#192454); +#192446 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192447,#192448,#192449, + #192450,#192451,#192452,#192453),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#190055 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#190056 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#190057 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#190058 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#190059 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#190060 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#190061 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#190062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190063 = PCURVE('',#189677,#190064); -#190064 = DEFINITIONAL_REPRESENTATION('',(#190065),#190068); -#190065 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190066,#190067), +#192447 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#192448 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#192449 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#192450 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#192451 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#192452 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#192453 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#192454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192455 = PCURVE('',#192069,#192456); +#192456 = DEFINITIONAL_REPRESENTATION('',(#192457),#192460); +#192457 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192458,#192459), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#190066 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190067 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#190068 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190069 = ORIENTED_EDGE('',*,*,#190070,.T.); -#190070 = EDGE_CURVE('',#190044,#190071,#190073,.T.); -#190071 = VERTEX_POINT('',#190072); -#190072 = CARTESIAN_POINT('',(-0.745,0.746501027564,0.178089594298)); -#190073 = SURFACE_CURVE('',#190074,(#190078,#190085),.PCURVE_S1.); -#190074 = LINE('',#190075,#190076); -#190075 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); -#190076 = VECTOR('',#190077,1.); -#190077 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#190078 = PCURVE('',#185715,#190079); -#190079 = DEFINITIONAL_REPRESENTATION('',(#190080),#190084); -#190080 = LINE('',#190081,#190082); -#190081 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#190082 = VECTOR('',#190083,1.); -#190083 = DIRECTION('',(0.993981062721,0.109552028512)); -#190084 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190085 = PCURVE('',#189953,#190086); -#190086 = DEFINITIONAL_REPRESENTATION('',(#190087),#190091); -#190087 = LINE('',#190088,#190089); -#190088 = CARTESIAN_POINT('',(0.E+000,0.4)); -#190089 = VECTOR('',#190090,1.); -#190090 = DIRECTION('',(1.,0.E+000)); -#190091 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#192458 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#192459 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#192460 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192461 = ORIENTED_EDGE('',*,*,#192462,.T.); +#192462 = EDGE_CURVE('',#192436,#192463,#192465,.T.); +#192463 = VERTEX_POINT('',#192464); +#192464 = CARTESIAN_POINT('',(-0.745,0.746501027564,0.178089594298)); +#192465 = SURFACE_CURVE('',#192466,(#192470,#192477),.PCURVE_S1.); +#192466 = LINE('',#192467,#192468); +#192467 = CARTESIAN_POINT('',(-0.745,0.70490705433,0.555477601426)); +#192468 = VECTOR('',#192469,1.); +#192469 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#192470 = PCURVE('',#188107,#192471); +#192471 = DEFINITIONAL_REPRESENTATION('',(#192472),#192476); +#192472 = LINE('',#192473,#192474); +#192473 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#192474 = VECTOR('',#192475,1.); +#192475 = DIRECTION('',(0.993981062721,0.109552028512)); +#192476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#190092 = ORIENTED_EDGE('',*,*,#190093,.T.); -#190093 = EDGE_CURVE('',#190071,#190094,#190096,.T.); -#190094 = VERTEX_POINT('',#190095); -#190095 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.E+000)); -#190096 = SURFACE_CURVE('',#190097,(#190102,#190109),.PCURVE_S1.); -#190097 = CIRCLE('',#190098,0.2); -#190098 = AXIS2_PLACEMENT_3D('',#190099,#190100,#190101); -#190099 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); -#190100 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190101 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190102 = PCURVE('',#185715,#190103); -#190103 = DEFINITIONAL_REPRESENTATION('',(#190104),#190108); -#190104 = CIRCLE('',#190105,0.2); -#190105 = AXIS2_PLACEMENT_2D('',#190106,#190107); -#190106 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#190107 = DIRECTION('',(1.,0.E+000)); -#190108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190109 = PCURVE('',#189926,#190110); -#190110 = DEFINITIONAL_REPRESENTATION('',(#190111),#190114); -#190111 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190112,#190113), +#192477 = PCURVE('',#192345,#192478); +#192478 = DEFINITIONAL_REPRESENTATION('',(#192479),#192483); +#192479 = LINE('',#192480,#192481); +#192480 = CARTESIAN_POINT('',(0.E+000,0.4)); +#192481 = VECTOR('',#192482,1.); +#192482 = DIRECTION('',(1.,0.E+000)); +#192483 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192484 = ORIENTED_EDGE('',*,*,#192485,.T.); +#192485 = EDGE_CURVE('',#192463,#192486,#192488,.T.); +#192486 = VERTEX_POINT('',#192487); +#192487 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.E+000)); +#192488 = SURFACE_CURVE('',#192489,(#192494,#192501),.PCURVE_S1.); +#192489 = CIRCLE('',#192490,0.2); +#192490 = AXIS2_PLACEMENT_3D('',#192491,#192492,#192493); +#192491 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); +#192492 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192493 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192494 = PCURVE('',#188107,#192495); +#192495 = DEFINITIONAL_REPRESENTATION('',(#192496),#192500); +#192496 = CIRCLE('',#192497,0.2); +#192497 = AXIS2_PLACEMENT_2D('',#192498,#192499); +#192498 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#192499 = DIRECTION('',(1.,0.E+000)); +#192500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192501 = PCURVE('',#192318,#192502); +#192502 = DEFINITIONAL_REPRESENTATION('',(#192503),#192506); +#192503 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192504,#192505), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#190112 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#190113 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#190114 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190115 = ORIENTED_EDGE('',*,*,#190116,.T.); -#190116 = EDGE_CURVE('',#190094,#190117,#190119,.T.); -#190117 = VERTEX_POINT('',#190118); -#190118 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#190119 = SURFACE_CURVE('',#190120,(#190124,#190131),.PCURVE_S1.); -#190120 = LINE('',#190121,#190122); -#190121 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#190122 = VECTOR('',#190123,1.); -#190123 = DIRECTION('',(0.E+000,1.,0.E+000)); -#190124 = PCURVE('',#185715,#190125); -#190125 = DEFINITIONAL_REPRESENTATION('',(#190126),#190130); -#190126 = LINE('',#190127,#190128); -#190127 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#190128 = VECTOR('',#190129,1.); -#190129 = DIRECTION('',(0.E+000,1.)); -#190130 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190131 = PCURVE('',#189897,#190132); -#190132 = DEFINITIONAL_REPRESENTATION('',(#190133),#190137); -#190133 = LINE('',#190134,#190135); -#190134 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#190135 = VECTOR('',#190136,1.); -#190136 = DIRECTION('',(0.E+000,1.)); -#190137 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190138 = ORIENTED_EDGE('',*,*,#190139,.T.); -#190139 = EDGE_CURVE('',#190117,#190140,#190142,.T.); -#190140 = VERTEX_POINT('',#190141); -#190141 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); -#190142 = SURFACE_CURVE('',#190143,(#190147,#190154),.PCURVE_S1.); -#190143 = LINE('',#190144,#190145); -#190144 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); -#190145 = VECTOR('',#190146,1.); -#190146 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190147 = PCURVE('',#185715,#190148); -#190148 = DEFINITIONAL_REPRESENTATION('',(#190149),#190153); -#190149 = LINE('',#190150,#190151); -#190150 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#190151 = VECTOR('',#190152,1.); -#190152 = DIRECTION('',(-1.,0.E+000)); -#190153 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190154 = PCURVE('',#189869,#190155); -#190155 = DEFINITIONAL_REPRESENTATION('',(#190156),#190160); -#190156 = LINE('',#190157,#190158); -#190157 = CARTESIAN_POINT('',(0.E+000,0.4)); -#190158 = VECTOR('',#190159,1.); -#190159 = DIRECTION('',(1.,0.E+000)); -#190160 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190161 = ORIENTED_EDGE('',*,*,#190162,.T.); -#190162 = EDGE_CURVE('',#190140,#190163,#190165,.T.); -#190163 = VERTEX_POINT('',#190164); -#190164 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.15)); -#190165 = SURFACE_CURVE('',#190166,(#190170,#190177),.PCURVE_S1.); -#190166 = LINE('',#190167,#190168); -#190167 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); -#190168 = VECTOR('',#190169,1.); -#190169 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190170 = PCURVE('',#185715,#190171); -#190171 = DEFINITIONAL_REPRESENTATION('',(#190172),#190176); -#190172 = LINE('',#190173,#190174); -#190173 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#190174 = VECTOR('',#190175,1.); -#190175 = DIRECTION('',(0.E+000,-1.)); -#190176 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190177 = PCURVE('',#189841,#190178); -#190178 = DEFINITIONAL_REPRESENTATION('',(#190179),#190183); -#190179 = LINE('',#190180,#190181); -#190180 = CARTESIAN_POINT('',(0.4,0.E+000)); -#190181 = VECTOR('',#190182,1.); -#190182 = DIRECTION('',(0.E+000,-1.)); -#190183 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190184 = ORIENTED_EDGE('',*,*,#190185,.T.); -#190185 = EDGE_CURVE('',#190163,#190186,#190188,.T.); -#190186 = VERTEX_POINT('',#190187); -#190187 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); -#190188 = SURFACE_CURVE('',#190189,(#190194,#190205),.PCURVE_S1.); -#190189 = CIRCLE('',#190190,5.E-002); -#190190 = AXIS2_PLACEMENT_3D('',#190191,#190192,#190193); -#190191 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); -#190192 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190193 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190194 = PCURVE('',#185715,#190195); -#190195 = DEFINITIONAL_REPRESENTATION('',(#190196),#190204); -#190196 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190197,#190198,#190199, - #190200,#190201,#190202,#190203),.UNSPECIFIED.,.F.,.F.) +#192504 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#192505 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#192506 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192507 = ORIENTED_EDGE('',*,*,#192508,.T.); +#192508 = EDGE_CURVE('',#192486,#192509,#192511,.T.); +#192509 = VERTEX_POINT('',#192510); +#192510 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#192511 = SURFACE_CURVE('',#192512,(#192516,#192523),.PCURVE_S1.); +#192512 = LINE('',#192513,#192514); +#192513 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#192514 = VECTOR('',#192515,1.); +#192515 = DIRECTION('',(0.E+000,1.,0.E+000)); +#192516 = PCURVE('',#188107,#192517); +#192517 = DEFINITIONAL_REPRESENTATION('',(#192518),#192522); +#192518 = LINE('',#192519,#192520); +#192519 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#192520 = VECTOR('',#192521,1.); +#192521 = DIRECTION('',(0.E+000,1.)); +#192522 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192523 = PCURVE('',#192289,#192524); +#192524 = DEFINITIONAL_REPRESENTATION('',(#192525),#192529); +#192525 = LINE('',#192526,#192527); +#192526 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#192527 = VECTOR('',#192528,1.); +#192528 = DIRECTION('',(0.E+000,1.)); +#192529 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192530 = ORIENTED_EDGE('',*,*,#192531,.T.); +#192531 = EDGE_CURVE('',#192509,#192532,#192534,.T.); +#192532 = VERTEX_POINT('',#192533); +#192533 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); +#192534 = SURFACE_CURVE('',#192535,(#192539,#192546),.PCURVE_S1.); +#192535 = LINE('',#192536,#192537); +#192536 = CARTESIAN_POINT('',(-0.745,1.17,0.E+000)); +#192537 = VECTOR('',#192538,1.); +#192538 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192539 = PCURVE('',#188107,#192540); +#192540 = DEFINITIONAL_REPRESENTATION('',(#192541),#192545); +#192541 = LINE('',#192542,#192543); +#192542 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#192543 = VECTOR('',#192544,1.); +#192544 = DIRECTION('',(-1.,0.E+000)); +#192545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192546 = PCURVE('',#192261,#192547); +#192547 = DEFINITIONAL_REPRESENTATION('',(#192548),#192552); +#192548 = LINE('',#192549,#192550); +#192549 = CARTESIAN_POINT('',(0.E+000,0.4)); +#192550 = VECTOR('',#192551,1.); +#192551 = DIRECTION('',(1.,0.E+000)); +#192552 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192553 = ORIENTED_EDGE('',*,*,#192554,.T.); +#192554 = EDGE_CURVE('',#192532,#192555,#192557,.T.); +#192555 = VERTEX_POINT('',#192556); +#192556 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.15)); +#192557 = SURFACE_CURVE('',#192558,(#192562,#192569),.PCURVE_S1.); +#192558 = LINE('',#192559,#192560); +#192559 = CARTESIAN_POINT('',(-0.745,1.17,0.15)); +#192560 = VECTOR('',#192561,1.); +#192561 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192562 = PCURVE('',#188107,#192563); +#192563 = DEFINITIONAL_REPRESENTATION('',(#192564),#192568); +#192564 = LINE('',#192565,#192566); +#192565 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#192566 = VECTOR('',#192567,1.); +#192567 = DIRECTION('',(0.E+000,-1.)); +#192568 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192569 = PCURVE('',#192233,#192570); +#192570 = DEFINITIONAL_REPRESENTATION('',(#192571),#192575); +#192571 = LINE('',#192572,#192573); +#192572 = CARTESIAN_POINT('',(0.4,0.E+000)); +#192573 = VECTOR('',#192574,1.); +#192574 = DIRECTION('',(0.E+000,-1.)); +#192575 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192576 = ORIENTED_EDGE('',*,*,#192577,.T.); +#192577 = EDGE_CURVE('',#192555,#192578,#192580,.T.); +#192578 = VERTEX_POINT('',#192579); +#192579 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); +#192580 = SURFACE_CURVE('',#192581,(#192586,#192597),.PCURVE_S1.); +#192581 = CIRCLE('',#192582,5.E-002); +#192582 = AXIS2_PLACEMENT_3D('',#192583,#192584,#192585); +#192583 = CARTESIAN_POINT('',(-0.745,0.945297240108,0.2)); +#192584 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#192585 = DIRECTION('',(0.E+000,0.E+000,1.)); +#192586 = PCURVE('',#188107,#192587); +#192587 = DEFINITIONAL_REPRESENTATION('',(#192588),#192596); +#192588 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192589,#192590,#192591, + #192592,#192593,#192594,#192595),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#190197 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#190198 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#190199 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#190200 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#190201 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#190202 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#190203 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#190204 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190205 = PCURVE('',#189814,#190206); -#190206 = DEFINITIONAL_REPRESENTATION('',(#190207),#190210); -#190207 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190208,#190209), +#192589 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#192590 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#192591 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#192592 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#192593 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#192594 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#192595 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#192596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192597 = PCURVE('',#192206,#192598); +#192598 = DEFINITIONAL_REPRESENTATION('',(#192599),#192602); +#192599 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192600,#192601), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#190208 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#190209 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#190210 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190211 = ORIENTED_EDGE('',*,*,#190212,.T.); -#190212 = EDGE_CURVE('',#190186,#190213,#190215,.T.); -#190213 = VERTEX_POINT('',#190214); -#190214 = CARTESIAN_POINT('',(-0.745,0.854004213739,0.571910405702)); -#190215 = SURFACE_CURVE('',#190216,(#190220,#190227),.PCURVE_S1.); -#190216 = LINE('',#190217,#190218); -#190217 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); -#190218 = VECTOR('',#190219,1.); -#190219 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#190220 = PCURVE('',#185715,#190221); -#190221 = DEFINITIONAL_REPRESENTATION('',(#190222),#190226); -#190222 = LINE('',#190223,#190224); -#190223 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#190224 = VECTOR('',#190225,1.); -#190225 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#190226 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190227 = PCURVE('',#189781,#190228); -#190228 = DEFINITIONAL_REPRESENTATION('',(#190229),#190233); -#190229 = LINE('',#190230,#190231); -#190230 = CARTESIAN_POINT('',(0.E+000,0.4)); -#190231 = VECTOR('',#190232,1.); -#190232 = DIRECTION('',(1.,0.E+000)); -#190233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190234 = ORIENTED_EDGE('',*,*,#190235,.T.); -#190235 = EDGE_CURVE('',#190213,#189995,#190236,.T.); -#190236 = SURFACE_CURVE('',#190237,(#190242,#190249),.PCURVE_S1.); -#190237 = CIRCLE('',#190238,0.2); -#190238 = AXIS2_PLACEMENT_3D('',#190239,#190240,#190241); -#190239 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); -#190240 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190241 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190242 = PCURVE('',#185715,#190243); -#190243 = DEFINITIONAL_REPRESENTATION('',(#190244),#190248); -#190244 = CIRCLE('',#190245,0.2); -#190245 = AXIS2_PLACEMENT_2D('',#190246,#190247); -#190246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190247 = DIRECTION('',(1.,0.E+000)); -#190248 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190249 = PCURVE('',#189754,#190250); -#190250 = DEFINITIONAL_REPRESENTATION('',(#190251),#190254); -#190251 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190252,#190253), +#192600 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#192601 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#192602 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192603 = ORIENTED_EDGE('',*,*,#192604,.T.); +#192604 = EDGE_CURVE('',#192578,#192605,#192607,.T.); +#192605 = VERTEX_POINT('',#192606); +#192606 = CARTESIAN_POINT('',(-0.745,0.854004213739,0.571910405702)); +#192607 = SURFACE_CURVE('',#192608,(#192612,#192619),.PCURVE_S1.); +#192608 = LINE('',#192609,#192610); +#192609 = CARTESIAN_POINT('',(-0.745,0.895598186972,0.194522398574)); +#192610 = VECTOR('',#192611,1.); +#192611 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#192612 = PCURVE('',#188107,#192613); +#192613 = DEFINITIONAL_REPRESENTATION('',(#192614),#192618); +#192614 = LINE('',#192615,#192616); +#192615 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#192616 = VECTOR('',#192617,1.); +#192617 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#192618 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192619 = PCURVE('',#192173,#192620); +#192620 = DEFINITIONAL_REPRESENTATION('',(#192621),#192625); +#192621 = LINE('',#192622,#192623); +#192622 = CARTESIAN_POINT('',(0.E+000,0.4)); +#192623 = VECTOR('',#192624,1.); +#192624 = DIRECTION('',(1.,0.E+000)); +#192625 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192626 = ORIENTED_EDGE('',*,*,#192627,.T.); +#192627 = EDGE_CURVE('',#192605,#192387,#192628,.T.); +#192628 = SURFACE_CURVE('',#192629,(#192634,#192641),.PCURVE_S1.); +#192629 = CIRCLE('',#192630,0.2); +#192630 = AXIS2_PLACEMENT_3D('',#192631,#192632,#192633); +#192631 = CARTESIAN_POINT('',(-0.745,0.655208001194,0.55)); +#192632 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192633 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192634 = PCURVE('',#188107,#192635); +#192635 = DEFINITIONAL_REPRESENTATION('',(#192636),#192640); +#192636 = CIRCLE('',#192637,0.2); +#192637 = AXIS2_PLACEMENT_2D('',#192638,#192639); +#192638 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192639 = DIRECTION('',(1.,0.E+000)); +#192640 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192641 = PCURVE('',#192146,#192642); +#192642 = DEFINITIONAL_REPRESENTATION('',(#192643),#192646); +#192643 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192644,#192645), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#190252 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#190253 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190254 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190255 = ORIENTED_EDGE('',*,*,#189994,.T.); -#190256 = ADVANCED_FACE('',(#190257),#189754,.T.); -#190257 = FACE_BOUND('',#190258,.T.); -#190258 = EDGE_LOOP('',(#190259,#190260,#190261,#190281)); -#190259 = ORIENTED_EDGE('',*,*,#190017,.T.); -#190260 = ORIENTED_EDGE('',*,*,#190235,.F.); -#190261 = ORIENTED_EDGE('',*,*,#190262,.F.); -#190262 = EDGE_CURVE('',#189738,#190213,#190263,.T.); -#190263 = SURFACE_CURVE('',#190264,(#190268,#190274),.PCURVE_S1.); -#190264 = LINE('',#190265,#190266); -#190265 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); -#190266 = VECTOR('',#190267,1.); -#190267 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190268 = PCURVE('',#189754,#190269); -#190269 = DEFINITIONAL_REPRESENTATION('',(#190270),#190273); -#190270 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190271,#190272), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190271 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#190272 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#190273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190274 = PCURVE('',#189781,#190275); -#190275 = DEFINITIONAL_REPRESENTATION('',(#190276),#190280); -#190276 = LINE('',#190277,#190278); -#190277 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#190278 = VECTOR('',#190279,1.); -#190279 = DIRECTION('',(0.E+000,1.)); -#190280 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190281 = ORIENTED_EDGE('',*,*,#189737,.T.); -#190282 = ADVANCED_FACE('',(#190283),#189781,.T.); -#190283 = FACE_BOUND('',#190284,.T.); -#190284 = EDGE_LOOP('',(#190285,#190286,#190287,#190307)); -#190285 = ORIENTED_EDGE('',*,*,#190262,.T.); -#190286 = ORIENTED_EDGE('',*,*,#190212,.F.); -#190287 = ORIENTED_EDGE('',*,*,#190288,.F.); -#190288 = EDGE_CURVE('',#189766,#190186,#190289,.T.); -#190289 = SURFACE_CURVE('',#190290,(#190294,#190301),.PCURVE_S1.); -#190290 = LINE('',#190291,#190292); -#190291 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); -#190292 = VECTOR('',#190293,1.); -#190293 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190294 = PCURVE('',#189781,#190295); -#190295 = DEFINITIONAL_REPRESENTATION('',(#190296),#190300); -#190296 = LINE('',#190297,#190298); -#190297 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190298 = VECTOR('',#190299,1.); -#190299 = DIRECTION('',(0.E+000,1.)); -#190300 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190301 = PCURVE('',#189814,#190302); -#190302 = DEFINITIONAL_REPRESENTATION('',(#190303),#190306); -#190303 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190304,#190305), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190304 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#190305 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#190306 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#192644 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#192645 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#192646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#190307 = ORIENTED_EDGE('',*,*,#189765,.T.); -#190308 = ADVANCED_FACE('',(#190309),#189814,.F.); -#190309 = FACE_BOUND('',#190310,.F.); -#190310 = EDGE_LOOP('',(#190311,#190312,#190313,#190356)); -#190311 = ORIENTED_EDGE('',*,*,#190288,.F.); -#190312 = ORIENTED_EDGE('',*,*,#189793,.F.); -#190313 = ORIENTED_EDGE('',*,*,#190314,.T.); -#190314 = EDGE_CURVE('',#189794,#190163,#190315,.T.); -#190315 = SURFACE_CURVE('',#190316,(#190320,#190349),.PCURVE_S1.); -#190316 = LINE('',#190317,#190318); -#190317 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); -#190318 = VECTOR('',#190319,1.); -#190319 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190320 = PCURVE('',#189814,#190321); -#190321 = DEFINITIONAL_REPRESENTATION('',(#190322),#190348); -#190322 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190323,#190324,#190325, - #190326,#190327,#190328,#190329,#190330,#190331,#190332,#190333, - #190334,#190335,#190336,#190337,#190338,#190339,#190340,#190341, - #190342,#190343,#190344,#190345,#190346,#190347),.UNSPECIFIED.,.F., +#192647 = ORIENTED_EDGE('',*,*,#192386,.T.); +#192648 = ADVANCED_FACE('',(#192649),#192146,.T.); +#192649 = FACE_BOUND('',#192650,.T.); +#192650 = EDGE_LOOP('',(#192651,#192652,#192653,#192673)); +#192651 = ORIENTED_EDGE('',*,*,#192409,.T.); +#192652 = ORIENTED_EDGE('',*,*,#192627,.F.); +#192653 = ORIENTED_EDGE('',*,*,#192654,.F.); +#192654 = EDGE_CURVE('',#192130,#192605,#192655,.T.); +#192655 = SURFACE_CURVE('',#192656,(#192660,#192666),.PCURVE_S1.); +#192656 = LINE('',#192657,#192658); +#192657 = CARTESIAN_POINT('',(-1.145,0.854004213739,0.571910405702)); +#192658 = VECTOR('',#192659,1.); +#192659 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192660 = PCURVE('',#192146,#192661); +#192661 = DEFINITIONAL_REPRESENTATION('',(#192662),#192665); +#192662 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192663,#192664), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#192663 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#192664 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#192665 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192666 = PCURVE('',#192173,#192667); +#192667 = DEFINITIONAL_REPRESENTATION('',(#192668),#192672); +#192668 = LINE('',#192669,#192670); +#192669 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#192670 = VECTOR('',#192671,1.); +#192671 = DIRECTION('',(0.E+000,1.)); +#192672 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192673 = ORIENTED_EDGE('',*,*,#192129,.T.); +#192674 = ADVANCED_FACE('',(#192675),#192173,.T.); +#192675 = FACE_BOUND('',#192676,.T.); +#192676 = EDGE_LOOP('',(#192677,#192678,#192679,#192699)); +#192677 = ORIENTED_EDGE('',*,*,#192654,.T.); +#192678 = ORIENTED_EDGE('',*,*,#192604,.F.); +#192679 = ORIENTED_EDGE('',*,*,#192680,.F.); +#192680 = EDGE_CURVE('',#192158,#192578,#192681,.T.); +#192681 = SURFACE_CURVE('',#192682,(#192686,#192693),.PCURVE_S1.); +#192682 = LINE('',#192683,#192684); +#192683 = CARTESIAN_POINT('',(-1.145,0.895598186972,0.194522398574)); +#192684 = VECTOR('',#192685,1.); +#192685 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192686 = PCURVE('',#192173,#192687); +#192687 = DEFINITIONAL_REPRESENTATION('',(#192688),#192692); +#192688 = LINE('',#192689,#192690); +#192689 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192690 = VECTOR('',#192691,1.); +#192691 = DIRECTION('',(0.E+000,1.)); +#192692 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192693 = PCURVE('',#192206,#192694); +#192694 = DEFINITIONAL_REPRESENTATION('',(#192695),#192698); +#192695 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192696,#192697), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#192696 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#192697 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#192698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192699 = ORIENTED_EDGE('',*,*,#192157,.T.); +#192700 = ADVANCED_FACE('',(#192701),#192206,.F.); +#192701 = FACE_BOUND('',#192702,.F.); +#192702 = EDGE_LOOP('',(#192703,#192704,#192705,#192748)); +#192703 = ORIENTED_EDGE('',*,*,#192680,.F.); +#192704 = ORIENTED_EDGE('',*,*,#192185,.F.); +#192705 = ORIENTED_EDGE('',*,*,#192706,.T.); +#192706 = EDGE_CURVE('',#192186,#192555,#192707,.T.); +#192707 = SURFACE_CURVE('',#192708,(#192712,#192741),.PCURVE_S1.); +#192708 = LINE('',#192709,#192710); +#192709 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.15)); +#192710 = VECTOR('',#192711,1.); +#192711 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192712 = PCURVE('',#192206,#192713); +#192713 = DEFINITIONAL_REPRESENTATION('',(#192714),#192740); +#192714 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#192715,#192716,#192717, + #192718,#192719,#192720,#192721,#192722,#192723,#192724,#192725, + #192726,#192727,#192728,#192729,#192730,#192731,#192732,#192733, + #192734,#192735,#192736,#192737,#192738,#192739),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -236392,133 +239394,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#190323 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#190324 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#190325 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#190326 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#190327 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#190328 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#190329 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#190330 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#190331 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#190332 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#190333 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#190334 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#190335 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#190336 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#190337 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#190338 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#190339 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#190340 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#190341 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#190342 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#190343 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#190344 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#190345 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#190346 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#190347 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#190348 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190349 = PCURVE('',#189841,#190350); -#190350 = DEFINITIONAL_REPRESENTATION('',(#190351),#190355); -#190351 = LINE('',#190352,#190353); -#190352 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#190353 = VECTOR('',#190354,1.); -#190354 = DIRECTION('',(1.,0.E+000)); -#190355 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190356 = ORIENTED_EDGE('',*,*,#190185,.T.); -#190357 = ADVANCED_FACE('',(#190358),#189841,.T.); -#190358 = FACE_BOUND('',#190359,.T.); -#190359 = EDGE_LOOP('',(#190360,#190361,#190362,#190383)); -#190360 = ORIENTED_EDGE('',*,*,#190314,.T.); -#190361 = ORIENTED_EDGE('',*,*,#190162,.F.); -#190362 = ORIENTED_EDGE('',*,*,#190363,.F.); -#190363 = EDGE_CURVE('',#189826,#190140,#190364,.T.); -#190364 = SURFACE_CURVE('',#190365,(#190369,#190376),.PCURVE_S1.); -#190365 = LINE('',#190366,#190367); -#190366 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); -#190367 = VECTOR('',#190368,1.); -#190368 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190369 = PCURVE('',#189841,#190370); -#190370 = DEFINITIONAL_REPRESENTATION('',(#190371),#190375); -#190371 = LINE('',#190372,#190373); -#190372 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190373 = VECTOR('',#190374,1.); -#190374 = DIRECTION('',(1.,0.E+000)); -#190375 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190376 = PCURVE('',#189869,#190377); -#190377 = DEFINITIONAL_REPRESENTATION('',(#190378),#190382); -#190378 = LINE('',#190379,#190380); -#190379 = CARTESIAN_POINT('',(0.15,0.E+000)); -#190380 = VECTOR('',#190381,1.); -#190381 = DIRECTION('',(0.E+000,1.)); -#190382 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190383 = ORIENTED_EDGE('',*,*,#189825,.T.); -#190384 = ADVANCED_FACE('',(#190385),#189869,.T.); -#190385 = FACE_BOUND('',#190386,.T.); -#190386 = EDGE_LOOP('',(#190387,#190388,#190389,#190410)); -#190387 = ORIENTED_EDGE('',*,*,#190363,.T.); -#190388 = ORIENTED_EDGE('',*,*,#190139,.F.); -#190389 = ORIENTED_EDGE('',*,*,#190390,.F.); -#190390 = EDGE_CURVE('',#189854,#190117,#190391,.T.); -#190391 = SURFACE_CURVE('',#190392,(#190396,#190403),.PCURVE_S1.); -#190392 = LINE('',#190393,#190394); -#190393 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); -#190394 = VECTOR('',#190395,1.); -#190395 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190396 = PCURVE('',#189869,#190397); -#190397 = DEFINITIONAL_REPRESENTATION('',(#190398),#190402); -#190398 = LINE('',#190399,#190400); -#190399 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190400 = VECTOR('',#190401,1.); -#190401 = DIRECTION('',(0.E+000,1.)); -#190402 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190403 = PCURVE('',#189897,#190404); -#190404 = DEFINITIONAL_REPRESENTATION('',(#190405),#190409); -#190405 = LINE('',#190406,#190407); -#190406 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190407 = VECTOR('',#190408,1.); -#190408 = DIRECTION('',(-1.,0.E+000)); -#190409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190410 = ORIENTED_EDGE('',*,*,#189853,.T.); -#190411 = ADVANCED_FACE('',(#190412),#189897,.T.); -#190412 = FACE_BOUND('',#190413,.T.); -#190413 = EDGE_LOOP('',(#190414,#190415,#190416,#190459)); -#190414 = ORIENTED_EDGE('',*,*,#190390,.T.); -#190415 = ORIENTED_EDGE('',*,*,#190116,.F.); -#190416 = ORIENTED_EDGE('',*,*,#190417,.F.); -#190417 = EDGE_CURVE('',#189882,#190094,#190418,.T.); -#190418 = SURFACE_CURVE('',#190419,(#190423,#190430),.PCURVE_S1.); -#190419 = LINE('',#190420,#190421); -#190420 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); -#190421 = VECTOR('',#190422,1.); -#190422 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190423 = PCURVE('',#189897,#190424); -#190424 = DEFINITIONAL_REPRESENTATION('',(#190425),#190429); -#190425 = LINE('',#190426,#190427); -#190426 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#190427 = VECTOR('',#190428,1.); -#190428 = DIRECTION('',(-1.,0.E+000)); -#190429 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#192715 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#192716 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#192717 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#192718 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#192719 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#192720 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#192721 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#192722 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#192723 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#192724 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#192725 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#192726 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#192727 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#192728 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#192729 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#192730 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#192731 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#192732 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#192733 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#192734 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#192735 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#192736 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#192737 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#192738 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#192739 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#192740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#190430 = PCURVE('',#189926,#190431); -#190431 = DEFINITIONAL_REPRESENTATION('',(#190432),#190458); -#190432 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#190433,#190434,#190435, - #190436,#190437,#190438,#190439,#190440,#190441,#190442,#190443, - #190444,#190445,#190446,#190447,#190448,#190449,#190450,#190451, - #190452,#190453,#190454,#190455,#190456,#190457),.UNSPECIFIED.,.F., +#192741 = PCURVE('',#192233,#192742); +#192742 = DEFINITIONAL_REPRESENTATION('',(#192743),#192747); +#192743 = LINE('',#192744,#192745); +#192744 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#192745 = VECTOR('',#192746,1.); +#192746 = DIRECTION('',(1.,0.E+000)); +#192747 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192748 = ORIENTED_EDGE('',*,*,#192577,.T.); +#192749 = ADVANCED_FACE('',(#192750),#192233,.T.); +#192750 = FACE_BOUND('',#192751,.T.); +#192751 = EDGE_LOOP('',(#192752,#192753,#192754,#192775)); +#192752 = ORIENTED_EDGE('',*,*,#192706,.T.); +#192753 = ORIENTED_EDGE('',*,*,#192554,.F.); +#192754 = ORIENTED_EDGE('',*,*,#192755,.F.); +#192755 = EDGE_CURVE('',#192218,#192532,#192756,.T.); +#192756 = SURFACE_CURVE('',#192757,(#192761,#192768),.PCURVE_S1.); +#192757 = LINE('',#192758,#192759); +#192758 = CARTESIAN_POINT('',(-1.145,1.17,0.15)); +#192759 = VECTOR('',#192760,1.); +#192760 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192761 = PCURVE('',#192233,#192762); +#192762 = DEFINITIONAL_REPRESENTATION('',(#192763),#192767); +#192763 = LINE('',#192764,#192765); +#192764 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192765 = VECTOR('',#192766,1.); +#192766 = DIRECTION('',(1.,0.E+000)); +#192767 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192768 = PCURVE('',#192261,#192769); +#192769 = DEFINITIONAL_REPRESENTATION('',(#192770),#192774); +#192770 = LINE('',#192771,#192772); +#192771 = CARTESIAN_POINT('',(0.15,0.E+000)); +#192772 = VECTOR('',#192773,1.); +#192773 = DIRECTION('',(0.E+000,1.)); +#192774 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192775 = ORIENTED_EDGE('',*,*,#192217,.T.); +#192776 = ADVANCED_FACE('',(#192777),#192261,.T.); +#192777 = FACE_BOUND('',#192778,.T.); +#192778 = EDGE_LOOP('',(#192779,#192780,#192781,#192802)); +#192779 = ORIENTED_EDGE('',*,*,#192755,.T.); +#192780 = ORIENTED_EDGE('',*,*,#192531,.F.); +#192781 = ORIENTED_EDGE('',*,*,#192782,.F.); +#192782 = EDGE_CURVE('',#192246,#192509,#192783,.T.); +#192783 = SURFACE_CURVE('',#192784,(#192788,#192795),.PCURVE_S1.); +#192784 = LINE('',#192785,#192786); +#192785 = CARTESIAN_POINT('',(-1.145,1.17,0.E+000)); +#192786 = VECTOR('',#192787,1.); +#192787 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192788 = PCURVE('',#192261,#192789); +#192789 = DEFINITIONAL_REPRESENTATION('',(#192790),#192794); +#192790 = LINE('',#192791,#192792); +#192791 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192792 = VECTOR('',#192793,1.); +#192793 = DIRECTION('',(0.E+000,1.)); +#192794 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192795 = PCURVE('',#192289,#192796); +#192796 = DEFINITIONAL_REPRESENTATION('',(#192797),#192801); +#192797 = LINE('',#192798,#192799); +#192798 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192799 = VECTOR('',#192800,1.); +#192800 = DIRECTION('',(-1.,0.E+000)); +#192801 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192802 = ORIENTED_EDGE('',*,*,#192245,.T.); +#192803 = ADVANCED_FACE('',(#192804),#192289,.T.); +#192804 = FACE_BOUND('',#192805,.T.); +#192805 = EDGE_LOOP('',(#192806,#192807,#192808,#192851)); +#192806 = ORIENTED_EDGE('',*,*,#192782,.T.); +#192807 = ORIENTED_EDGE('',*,*,#192508,.F.); +#192808 = ORIENTED_EDGE('',*,*,#192809,.F.); +#192809 = EDGE_CURVE('',#192274,#192486,#192810,.T.); +#192810 = SURFACE_CURVE('',#192811,(#192815,#192822),.PCURVE_S1.); +#192811 = LINE('',#192812,#192813); +#192812 = CARTESIAN_POINT('',(-1.145,0.945297240108,0.E+000)); +#192813 = VECTOR('',#192814,1.); +#192814 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192815 = PCURVE('',#192289,#192816); +#192816 = DEFINITIONAL_REPRESENTATION('',(#192817),#192821); +#192817 = LINE('',#192818,#192819); +#192818 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#192819 = VECTOR('',#192820,1.); +#192820 = DIRECTION('',(-1.,0.E+000)); +#192821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192822 = PCURVE('',#192318,#192823); +#192823 = DEFINITIONAL_REPRESENTATION('',(#192824),#192850); +#192824 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#192825,#192826,#192827, + #192828,#192829,#192830,#192831,#192832,#192833,#192834,#192835, + #192836,#192837,#192838,#192839,#192840,#192841,#192842,#192843, + #192844,#192845,#192846,#192847,#192848,#192849),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -236526,949 +239528,949 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#190433 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#190434 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#190435 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#190436 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#190437 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#190438 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#190439 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#190440 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#190441 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#190442 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#190443 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#190444 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#190445 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#190446 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#190447 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#190448 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#190449 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#190450 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#190451 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#190452 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#190453 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#190454 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#190455 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#190456 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#190457 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#190458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190459 = ORIENTED_EDGE('',*,*,#189881,.T.); -#190460 = ADVANCED_FACE('',(#190461),#189926,.T.); -#190461 = FACE_BOUND('',#190462,.T.); -#190462 = EDGE_LOOP('',(#190463,#190464,#190465,#190485)); -#190463 = ORIENTED_EDGE('',*,*,#190417,.T.); -#190464 = ORIENTED_EDGE('',*,*,#190093,.F.); -#190465 = ORIENTED_EDGE('',*,*,#190466,.F.); -#190466 = EDGE_CURVE('',#189910,#190071,#190467,.T.); -#190467 = SURFACE_CURVE('',#190468,(#190472,#190478),.PCURVE_S1.); -#190468 = LINE('',#190469,#190470); -#190469 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); -#190470 = VECTOR('',#190471,1.); -#190471 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190472 = PCURVE('',#189926,#190473); -#190473 = DEFINITIONAL_REPRESENTATION('',(#190474),#190477); -#190474 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190475,#190476), +#192825 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#192826 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#192827 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#192828 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#192829 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#192830 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#192831 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#192832 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#192833 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#192834 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#192835 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#192836 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#192837 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#192838 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#192839 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#192840 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#192841 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#192842 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#192843 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#192844 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#192845 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#192846 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#192847 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#192848 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#192849 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#192850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192851 = ORIENTED_EDGE('',*,*,#192273,.T.); +#192852 = ADVANCED_FACE('',(#192853),#192318,.T.); +#192853 = FACE_BOUND('',#192854,.T.); +#192854 = EDGE_LOOP('',(#192855,#192856,#192857,#192877)); +#192855 = ORIENTED_EDGE('',*,*,#192809,.T.); +#192856 = ORIENTED_EDGE('',*,*,#192485,.F.); +#192857 = ORIENTED_EDGE('',*,*,#192858,.F.); +#192858 = EDGE_CURVE('',#192302,#192463,#192859,.T.); +#192859 = SURFACE_CURVE('',#192860,(#192864,#192870),.PCURVE_S1.); +#192860 = LINE('',#192861,#192862); +#192861 = CARTESIAN_POINT('',(-1.145,0.746501027564,0.178089594298)); +#192862 = VECTOR('',#192863,1.); +#192863 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192864 = PCURVE('',#192318,#192865); +#192865 = DEFINITIONAL_REPRESENTATION('',(#192866),#192869); +#192866 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192867,#192868), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190475 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#190476 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#190477 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190478 = PCURVE('',#189953,#190479); -#190479 = DEFINITIONAL_REPRESENTATION('',(#190480),#190484); -#190480 = LINE('',#190481,#190482); -#190481 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#190482 = VECTOR('',#190483,1.); -#190483 = DIRECTION('',(0.E+000,1.)); -#190484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190485 = ORIENTED_EDGE('',*,*,#189909,.T.); -#190486 = ADVANCED_FACE('',(#190487),#189953,.T.); -#190487 = FACE_BOUND('',#190488,.T.); -#190488 = EDGE_LOOP('',(#190489,#190490,#190491,#190511)); -#190489 = ORIENTED_EDGE('',*,*,#190466,.T.); -#190490 = ORIENTED_EDGE('',*,*,#190070,.F.); -#190491 = ORIENTED_EDGE('',*,*,#190492,.F.); -#190492 = EDGE_CURVE('',#189938,#190044,#190493,.T.); -#190493 = SURFACE_CURVE('',#190494,(#190498,#190505),.PCURVE_S1.); -#190494 = LINE('',#190495,#190496); -#190495 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); -#190496 = VECTOR('',#190497,1.); -#190497 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190498 = PCURVE('',#189953,#190499); -#190499 = DEFINITIONAL_REPRESENTATION('',(#190500),#190504); -#190500 = LINE('',#190501,#190502); -#190501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190502 = VECTOR('',#190503,1.); -#190503 = DIRECTION('',(0.E+000,1.)); -#190504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190505 = PCURVE('',#189677,#190506); -#190506 = DEFINITIONAL_REPRESENTATION('',(#190507),#190510); -#190507 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190508,#190509), +#192867 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#192868 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#192869 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192870 = PCURVE('',#192345,#192871); +#192871 = DEFINITIONAL_REPRESENTATION('',(#192872),#192876); +#192872 = LINE('',#192873,#192874); +#192873 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#192874 = VECTOR('',#192875,1.); +#192875 = DIRECTION('',(0.E+000,1.)); +#192876 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192877 = ORIENTED_EDGE('',*,*,#192301,.T.); +#192878 = ADVANCED_FACE('',(#192879),#192345,.T.); +#192879 = FACE_BOUND('',#192880,.T.); +#192880 = EDGE_LOOP('',(#192881,#192882,#192883,#192903)); +#192881 = ORIENTED_EDGE('',*,*,#192858,.T.); +#192882 = ORIENTED_EDGE('',*,*,#192462,.F.); +#192883 = ORIENTED_EDGE('',*,*,#192884,.F.); +#192884 = EDGE_CURVE('',#192330,#192436,#192885,.T.); +#192885 = SURFACE_CURVE('',#192886,(#192890,#192897),.PCURVE_S1.); +#192886 = LINE('',#192887,#192888); +#192887 = CARTESIAN_POINT('',(-1.145,0.70490705433,0.555477601426)); +#192888 = VECTOR('',#192889,1.); +#192889 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192890 = PCURVE('',#192345,#192891); +#192891 = DEFINITIONAL_REPRESENTATION('',(#192892),#192896); +#192892 = LINE('',#192893,#192894); +#192893 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192894 = VECTOR('',#192895,1.); +#192895 = DIRECTION('',(0.E+000,1.)); +#192896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192897 = PCURVE('',#192069,#192898); +#192898 = DEFINITIONAL_REPRESENTATION('',(#192899),#192902); +#192899 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192900,#192901), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190508 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#190509 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#190510 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190511 = ORIENTED_EDGE('',*,*,#189937,.T.); -#190512 = ADVANCED_FACE('',(#190513),#189677,.F.); -#190513 = FACE_BOUND('',#190514,.F.); -#190514 = EDGE_LOOP('',(#190515,#190516,#190517,#190518)); -#190515 = ORIENTED_EDGE('',*,*,#190492,.F.); -#190516 = ORIENTED_EDGE('',*,*,#189965,.F.); -#190517 = ORIENTED_EDGE('',*,*,#189661,.T.); -#190518 = ORIENTED_EDGE('',*,*,#190043,.T.); -#190519 = ADVANCED_FACE('',(#190520),#185973,.T.); -#190520 = FACE_BOUND('',#190521,.T.); -#190521 = EDGE_LOOP('',(#190522,#190523,#190546,#190573)); -#190522 = ORIENTED_EDGE('',*,*,#185957,.F.); -#190523 = ORIENTED_EDGE('',*,*,#190524,.T.); -#190524 = EDGE_CURVE('',#185930,#190525,#190527,.T.); -#190525 = VERTEX_POINT('',#190526); -#190526 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#190527 = SURFACE_CURVE('',#190528,(#190532,#190539),.PCURVE_S1.); -#190528 = LINE('',#190529,#190530); -#190529 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#190530 = VECTOR('',#190531,1.); -#190531 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190532 = PCURVE('',#185973,#190533); -#190533 = DEFINITIONAL_REPRESENTATION('',(#190534),#190538); -#190534 = LINE('',#190535,#190536); -#190535 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190536 = VECTOR('',#190537,1.); -#190537 = DIRECTION('',(0.E+000,-1.)); -#190538 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190539 = PCURVE('',#185945,#190540); -#190540 = DEFINITIONAL_REPRESENTATION('',(#190541),#190545); -#190541 = LINE('',#190542,#190543); -#190542 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#190543 = VECTOR('',#190544,1.); -#190544 = DIRECTION('',(0.E+000,-1.)); -#190545 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190546 = ORIENTED_EDGE('',*,*,#190547,.T.); -#190547 = EDGE_CURVE('',#190525,#190548,#190550,.T.); -#190548 = VERTEX_POINT('',#190549); -#190549 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); -#190550 = SURFACE_CURVE('',#190551,(#190555,#190562),.PCURVE_S1.); -#190551 = LINE('',#190552,#190553); -#190552 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); -#190553 = VECTOR('',#190554,1.); -#190554 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190555 = PCURVE('',#185973,#190556); -#190556 = DEFINITIONAL_REPRESENTATION('',(#190557),#190561); -#190557 = LINE('',#190558,#190559); -#190558 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190559 = VECTOR('',#190560,1.); -#190560 = DIRECTION('',(1.,0.E+000)); -#190561 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190562 = PCURVE('',#190563,#190568); -#190563 = CYLINDRICAL_SURFACE('',#190564,0.2); -#190564 = AXIS2_PLACEMENT_3D('',#190565,#190566,#190567); -#190565 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#190566 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190567 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190568 = DEFINITIONAL_REPRESENTATION('',(#190569),#190572); -#190569 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190570,#190571), +#192900 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#192901 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#192902 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192903 = ORIENTED_EDGE('',*,*,#192329,.T.); +#192904 = ADVANCED_FACE('',(#192905),#192069,.F.); +#192905 = FACE_BOUND('',#192906,.F.); +#192906 = EDGE_LOOP('',(#192907,#192908,#192909,#192910)); +#192907 = ORIENTED_EDGE('',*,*,#192884,.F.); +#192908 = ORIENTED_EDGE('',*,*,#192357,.F.); +#192909 = ORIENTED_EDGE('',*,*,#192053,.T.); +#192910 = ORIENTED_EDGE('',*,*,#192435,.T.); +#192911 = ADVANCED_FACE('',(#192912),#188365,.T.); +#192912 = FACE_BOUND('',#192913,.T.); +#192913 = EDGE_LOOP('',(#192914,#192915,#192938,#192965)); +#192914 = ORIENTED_EDGE('',*,*,#188349,.F.); +#192915 = ORIENTED_EDGE('',*,*,#192916,.T.); +#192916 = EDGE_CURVE('',#188322,#192917,#192919,.T.); +#192917 = VERTEX_POINT('',#192918); +#192918 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#192919 = SURFACE_CURVE('',#192920,(#192924,#192931),.PCURVE_S1.); +#192920 = LINE('',#192921,#192922); +#192921 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#192922 = VECTOR('',#192923,1.); +#192923 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192924 = PCURVE('',#188365,#192925); +#192925 = DEFINITIONAL_REPRESENTATION('',(#192926),#192930); +#192926 = LINE('',#192927,#192928); +#192927 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192928 = VECTOR('',#192929,1.); +#192929 = DIRECTION('',(0.E+000,-1.)); +#192930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192931 = PCURVE('',#188337,#192932); +#192932 = DEFINITIONAL_REPRESENTATION('',(#192933),#192937); +#192933 = LINE('',#192934,#192935); +#192934 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#192935 = VECTOR('',#192936,1.); +#192936 = DIRECTION('',(0.E+000,-1.)); +#192937 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192938 = ORIENTED_EDGE('',*,*,#192939,.T.); +#192939 = EDGE_CURVE('',#192917,#192940,#192942,.T.); +#192940 = VERTEX_POINT('',#192941); +#192941 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); +#192942 = SURFACE_CURVE('',#192943,(#192947,#192954),.PCURVE_S1.); +#192943 = LINE('',#192944,#192945); +#192944 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.75)); +#192945 = VECTOR('',#192946,1.); +#192946 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192947 = PCURVE('',#188365,#192948); +#192948 = DEFINITIONAL_REPRESENTATION('',(#192949),#192953); +#192949 = LINE('',#192950,#192951); +#192950 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#192951 = VECTOR('',#192952,1.); +#192952 = DIRECTION('',(1.,0.E+000)); +#192953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192954 = PCURVE('',#192955,#192960); +#192955 = CYLINDRICAL_SURFACE('',#192956,0.2); +#192956 = AXIS2_PLACEMENT_3D('',#192957,#192958,#192959); +#192957 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#192958 = DIRECTION('',(1.,0.E+000,0.E+000)); +#192959 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#192960 = DEFINITIONAL_REPRESENTATION('',(#192961),#192964); +#192961 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192962,#192963), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190570 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#190571 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190572 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190573 = ORIENTED_EDGE('',*,*,#190574,.F.); -#190574 = EDGE_CURVE('',#185958,#190548,#190575,.T.); -#190575 = SURFACE_CURVE('',#190576,(#190580,#190587),.PCURVE_S1.); -#190576 = LINE('',#190577,#190578); -#190577 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); -#190578 = VECTOR('',#190579,1.); -#190579 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190580 = PCURVE('',#185973,#190581); -#190581 = DEFINITIONAL_REPRESENTATION('',(#190582),#190586); -#190582 = LINE('',#190583,#190584); -#190583 = CARTESIAN_POINT('',(0.4,0.E+000)); -#190584 = VECTOR('',#190585,1.); -#190585 = DIRECTION('',(0.E+000,-1.)); -#190586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190587 = PCURVE('',#186001,#190588); -#190588 = DEFINITIONAL_REPRESENTATION('',(#190589),#190593); -#190589 = LINE('',#190590,#190591); -#190590 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#190591 = VECTOR('',#190592,1.); -#190592 = DIRECTION('',(0.E+000,-1.)); -#190593 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190594 = ADVANCED_FACE('',(#190595),#185945,.F.); -#190595 = FACE_BOUND('',#190596,.T.); -#190596 = EDGE_LOOP('',(#190597,#190598,#190599,#190622,#190654,#190682, - #190710,#190738,#190766,#190794,#190826,#190854)); -#190597 = ORIENTED_EDGE('',*,*,#190524,.F.); -#190598 = ORIENTED_EDGE('',*,*,#185929,.T.); -#190599 = ORIENTED_EDGE('',*,*,#190600,.F.); -#190600 = EDGE_CURVE('',#190601,#185902,#190603,.T.); -#190601 = VERTEX_POINT('',#190602); -#190602 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#190603 = SURFACE_CURVE('',#190604,(#190608,#190615),.PCURVE_S1.); -#190604 = LINE('',#190605,#190606); -#190605 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#190606 = VECTOR('',#190607,1.); -#190607 = DIRECTION('',(0.E+000,1.,0.E+000)); -#190608 = PCURVE('',#185945,#190609); -#190609 = DEFINITIONAL_REPRESENTATION('',(#190610),#190614); -#190610 = LINE('',#190611,#190612); -#190611 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#190612 = VECTOR('',#190613,1.); -#190613 = DIRECTION('',(0.E+000,1.)); -#190614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190615 = PCURVE('',#186597,#190616); -#190616 = DEFINITIONAL_REPRESENTATION('',(#190617),#190621); -#190617 = LINE('',#190618,#190619); -#190618 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190619 = VECTOR('',#190620,1.); -#190620 = DIRECTION('',(0.E+000,1.)); -#190621 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190622 = ORIENTED_EDGE('',*,*,#190623,.F.); -#190623 = EDGE_CURVE('',#190624,#190601,#190626,.T.); -#190624 = VERTEX_POINT('',#190625); -#190625 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#190626 = SURFACE_CURVE('',#190627,(#190632,#190643),.PCURVE_S1.); -#190627 = CIRCLE('',#190628,5.E-002); -#190628 = AXIS2_PLACEMENT_3D('',#190629,#190630,#190631); -#190629 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#190630 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190631 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190632 = PCURVE('',#185945,#190633); -#190633 = DEFINITIONAL_REPRESENTATION('',(#190634),#190642); -#190634 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190635,#190636,#190637, - #190638,#190639,#190640,#190641),.UNSPECIFIED.,.F.,.F.) +#192962 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#192963 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#192964 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192965 = ORIENTED_EDGE('',*,*,#192966,.F.); +#192966 = EDGE_CURVE('',#188350,#192940,#192967,.T.); +#192967 = SURFACE_CURVE('',#192968,(#192972,#192979),.PCURVE_S1.); +#192968 = LINE('',#192969,#192970); +#192969 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.75)); +#192970 = VECTOR('',#192971,1.); +#192971 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#192972 = PCURVE('',#188365,#192973); +#192973 = DEFINITIONAL_REPRESENTATION('',(#192974),#192978); +#192974 = LINE('',#192975,#192976); +#192975 = CARTESIAN_POINT('',(0.4,0.E+000)); +#192976 = VECTOR('',#192977,1.); +#192977 = DIRECTION('',(0.E+000,-1.)); +#192978 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192979 = PCURVE('',#188393,#192980); +#192980 = DEFINITIONAL_REPRESENTATION('',(#192981),#192985); +#192981 = LINE('',#192982,#192983); +#192982 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#192983 = VECTOR('',#192984,1.); +#192984 = DIRECTION('',(0.E+000,-1.)); +#192985 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#192986 = ADVANCED_FACE('',(#192987),#188337,.F.); +#192987 = FACE_BOUND('',#192988,.T.); +#192988 = EDGE_LOOP('',(#192989,#192990,#192991,#193014,#193046,#193074, + #193102,#193130,#193158,#193186,#193218,#193246)); +#192989 = ORIENTED_EDGE('',*,*,#192916,.F.); +#192990 = ORIENTED_EDGE('',*,*,#188321,.T.); +#192991 = ORIENTED_EDGE('',*,*,#192992,.F.); +#192992 = EDGE_CURVE('',#192993,#188294,#192995,.T.); +#192993 = VERTEX_POINT('',#192994); +#192994 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#192995 = SURFACE_CURVE('',#192996,(#193000,#193007),.PCURVE_S1.); +#192996 = LINE('',#192997,#192998); +#192997 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#192998 = VECTOR('',#192999,1.); +#192999 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193000 = PCURVE('',#188337,#193001); +#193001 = DEFINITIONAL_REPRESENTATION('',(#193002),#193006); +#193002 = LINE('',#193003,#193004); +#193003 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#193004 = VECTOR('',#193005,1.); +#193005 = DIRECTION('',(0.E+000,1.)); +#193006 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193007 = PCURVE('',#188989,#193008); +#193008 = DEFINITIONAL_REPRESENTATION('',(#193009),#193013); +#193009 = LINE('',#193010,#193011); +#193010 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193011 = VECTOR('',#193012,1.); +#193012 = DIRECTION('',(0.E+000,1.)); +#193013 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193014 = ORIENTED_EDGE('',*,*,#193015,.F.); +#193015 = EDGE_CURVE('',#193016,#192993,#193018,.T.); +#193016 = VERTEX_POINT('',#193017); +#193017 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#193018 = SURFACE_CURVE('',#193019,(#193024,#193035),.PCURVE_S1.); +#193019 = CIRCLE('',#193020,5.E-002); +#193020 = AXIS2_PLACEMENT_3D('',#193021,#193022,#193023); +#193021 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#193022 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193023 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193024 = PCURVE('',#188337,#193025); +#193025 = DEFINITIONAL_REPRESENTATION('',(#193026),#193034); +#193026 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#193027,#193028,#193029, + #193030,#193031,#193032,#193033),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#190635 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#190636 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#190637 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#190638 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#190639 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#190640 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#190641 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#190642 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190643 = PCURVE('',#190644,#190649); -#190644 = CYLINDRICAL_SURFACE('',#190645,5.E-002); -#190645 = AXIS2_PLACEMENT_3D('',#190646,#190647,#190648); -#190646 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#190647 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190648 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190649 = DEFINITIONAL_REPRESENTATION('',(#190650),#190653); -#190650 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190651,#190652), +#193027 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193028 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#193029 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#193030 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#193031 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#193032 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#193033 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193035 = PCURVE('',#193036,#193041); +#193036 = CYLINDRICAL_SURFACE('',#193037,5.E-002); +#193037 = AXIS2_PLACEMENT_3D('',#193038,#193039,#193040); +#193038 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#193039 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193040 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193041 = DEFINITIONAL_REPRESENTATION('',(#193042),#193045); +#193042 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193043,#193044), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#190651 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#190652 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#190653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190654 = ORIENTED_EDGE('',*,*,#190655,.F.); -#190655 = EDGE_CURVE('',#190656,#190624,#190658,.T.); -#190656 = VERTEX_POINT('',#190657); -#190657 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); -#190658 = SURFACE_CURVE('',#190659,(#190663,#190670),.PCURVE_S1.); -#190659 = LINE('',#190660,#190661); -#190660 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#190661 = VECTOR('',#190662,1.); -#190662 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#190663 = PCURVE('',#185945,#190664); -#190664 = DEFINITIONAL_REPRESENTATION('',(#190665),#190669); -#190665 = LINE('',#190666,#190667); -#190666 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#190667 = VECTOR('',#190668,1.); -#190668 = DIRECTION('',(-0.993981062721,0.109552028512)); -#190669 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190670 = PCURVE('',#190671,#190676); -#190671 = PLANE('',#190672); -#190672 = AXIS2_PLACEMENT_3D('',#190673,#190674,#190675); -#190673 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#190674 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); -#190675 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#190676 = DEFINITIONAL_REPRESENTATION('',(#190677),#190681); -#190677 = LINE('',#190678,#190679); -#190678 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190679 = VECTOR('',#190680,1.); -#190680 = DIRECTION('',(1.,0.E+000)); -#190681 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190682 = ORIENTED_EDGE('',*,*,#190683,.F.); -#190683 = EDGE_CURVE('',#190684,#190656,#190686,.T.); -#190684 = VERTEX_POINT('',#190685); -#190685 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); -#190686 = SURFACE_CURVE('',#190687,(#190692,#190699),.PCURVE_S1.); -#190687 = CIRCLE('',#190688,0.2); -#190688 = AXIS2_PLACEMENT_3D('',#190689,#190690,#190691); -#190689 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#190690 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190691 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190692 = PCURVE('',#185945,#190693); -#190693 = DEFINITIONAL_REPRESENTATION('',(#190694),#190698); -#190694 = CIRCLE('',#190695,0.2); -#190695 = AXIS2_PLACEMENT_2D('',#190696,#190697); -#190696 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#190697 = DIRECTION('',(-1.,0.E+000)); -#190698 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190699 = PCURVE('',#190700,#190705); -#190700 = CYLINDRICAL_SURFACE('',#190701,0.2); -#190701 = AXIS2_PLACEMENT_3D('',#190702,#190703,#190704); -#190702 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#190703 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190704 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190705 = DEFINITIONAL_REPRESENTATION('',(#190706),#190709); -#190706 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190707,#190708), +#193043 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#193044 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#193045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193046 = ORIENTED_EDGE('',*,*,#193047,.F.); +#193047 = EDGE_CURVE('',#193048,#193016,#193050,.T.); +#193048 = VERTEX_POINT('',#193049); +#193049 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); +#193050 = SURFACE_CURVE('',#193051,(#193055,#193062),.PCURVE_S1.); +#193051 = LINE('',#193052,#193053); +#193052 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#193053 = VECTOR('',#193054,1.); +#193054 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#193055 = PCURVE('',#188337,#193056); +#193056 = DEFINITIONAL_REPRESENTATION('',(#193057),#193061); +#193057 = LINE('',#193058,#193059); +#193058 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#193059 = VECTOR('',#193060,1.); +#193060 = DIRECTION('',(-0.993981062721,0.109552028512)); +#193061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193062 = PCURVE('',#193063,#193068); +#193063 = PLANE('',#193064); +#193064 = AXIS2_PLACEMENT_3D('',#193065,#193066,#193067); +#193065 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#193066 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); +#193067 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#193068 = DEFINITIONAL_REPRESENTATION('',(#193069),#193073); +#193069 = LINE('',#193070,#193071); +#193070 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193071 = VECTOR('',#193072,1.); +#193072 = DIRECTION('',(1.,0.E+000)); +#193073 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193074 = ORIENTED_EDGE('',*,*,#193075,.F.); +#193075 = EDGE_CURVE('',#193076,#193048,#193078,.T.); +#193076 = VERTEX_POINT('',#193077); +#193077 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); +#193078 = SURFACE_CURVE('',#193079,(#193084,#193091),.PCURVE_S1.); +#193079 = CIRCLE('',#193080,0.2); +#193080 = AXIS2_PLACEMENT_3D('',#193081,#193082,#193083); +#193081 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#193082 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193083 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193084 = PCURVE('',#188337,#193085); +#193085 = DEFINITIONAL_REPRESENTATION('',(#193086),#193090); +#193086 = CIRCLE('',#193087,0.2); +#193087 = AXIS2_PLACEMENT_2D('',#193088,#193089); +#193088 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#193089 = DIRECTION('',(-1.,0.E+000)); +#193090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193091 = PCURVE('',#193092,#193097); +#193092 = CYLINDRICAL_SURFACE('',#193093,0.2); +#193093 = AXIS2_PLACEMENT_3D('',#193094,#193095,#193096); +#193094 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#193095 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193096 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193097 = DEFINITIONAL_REPRESENTATION('',(#193098),#193101); +#193098 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193099,#193100), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#190707 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190708 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#190709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190710 = ORIENTED_EDGE('',*,*,#190711,.F.); -#190711 = EDGE_CURVE('',#190712,#190684,#190714,.T.); -#190712 = VERTEX_POINT('',#190713); -#190713 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#190714 = SURFACE_CURVE('',#190715,(#190719,#190726),.PCURVE_S1.); -#190715 = LINE('',#190716,#190717); -#190716 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#190717 = VECTOR('',#190718,1.); -#190718 = DIRECTION('',(0.E+000,1.,0.E+000)); -#190719 = PCURVE('',#185945,#190720); -#190720 = DEFINITIONAL_REPRESENTATION('',(#190721),#190725); -#190721 = LINE('',#190722,#190723); -#190722 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#190723 = VECTOR('',#190724,1.); -#190724 = DIRECTION('',(0.E+000,1.)); -#190725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190726 = PCURVE('',#190727,#190732); -#190727 = PLANE('',#190728); -#190728 = AXIS2_PLACEMENT_3D('',#190729,#190730,#190731); -#190729 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#190730 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190731 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190732 = DEFINITIONAL_REPRESENTATION('',(#190733),#190737); -#190733 = LINE('',#190734,#190735); -#190734 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190735 = VECTOR('',#190736,1.); -#190736 = DIRECTION('',(0.E+000,1.)); -#190737 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190738 = ORIENTED_EDGE('',*,*,#190739,.F.); -#190739 = EDGE_CURVE('',#190740,#190712,#190742,.T.); -#190740 = VERTEX_POINT('',#190741); -#190741 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#190742 = SURFACE_CURVE('',#190743,(#190747,#190754),.PCURVE_S1.); -#190743 = LINE('',#190744,#190745); -#190744 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#190745 = VECTOR('',#190746,1.); -#190746 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190747 = PCURVE('',#185945,#190748); -#190748 = DEFINITIONAL_REPRESENTATION('',(#190749),#190753); -#190749 = LINE('',#190750,#190751); -#190750 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#190751 = VECTOR('',#190752,1.); -#190752 = DIRECTION('',(1.,0.E+000)); -#190753 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190754 = PCURVE('',#190755,#190760); -#190755 = PLANE('',#190756); -#190756 = AXIS2_PLACEMENT_3D('',#190757,#190758,#190759); -#190757 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#190758 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190759 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190760 = DEFINITIONAL_REPRESENTATION('',(#190761),#190765); -#190761 = LINE('',#190762,#190763); -#190762 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190763 = VECTOR('',#190764,1.); -#190764 = DIRECTION('',(1.,0.E+000)); -#190765 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190766 = ORIENTED_EDGE('',*,*,#190767,.F.); -#190767 = EDGE_CURVE('',#190768,#190740,#190770,.T.); -#190768 = VERTEX_POINT('',#190769); -#190769 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); -#190770 = SURFACE_CURVE('',#190771,(#190775,#190782),.PCURVE_S1.); -#190771 = LINE('',#190772,#190773); -#190772 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#190773 = VECTOR('',#190774,1.); -#190774 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#190775 = PCURVE('',#185945,#190776); -#190776 = DEFINITIONAL_REPRESENTATION('',(#190777),#190781); -#190777 = LINE('',#190778,#190779); -#190778 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#190779 = VECTOR('',#190780,1.); -#190780 = DIRECTION('',(0.E+000,-1.)); -#190781 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190782 = PCURVE('',#190783,#190788); -#190783 = PLANE('',#190784); -#190784 = AXIS2_PLACEMENT_3D('',#190785,#190786,#190787); -#190785 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#190786 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190787 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190788 = DEFINITIONAL_REPRESENTATION('',(#190789),#190793); -#190789 = LINE('',#190790,#190791); -#190790 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190791 = VECTOR('',#190792,1.); -#190792 = DIRECTION('',(0.E+000,-1.)); -#190793 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190794 = ORIENTED_EDGE('',*,*,#190795,.F.); -#190795 = EDGE_CURVE('',#190796,#190768,#190798,.T.); -#190796 = VERTEX_POINT('',#190797); -#190797 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#190798 = SURFACE_CURVE('',#190799,(#190804,#190815),.PCURVE_S1.); -#190799 = CIRCLE('',#190800,5.E-002); -#190800 = AXIS2_PLACEMENT_3D('',#190801,#190802,#190803); -#190801 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#190802 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190803 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190804 = PCURVE('',#185945,#190805); -#190805 = DEFINITIONAL_REPRESENTATION('',(#190806),#190814); -#190806 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190807,#190808,#190809, - #190810,#190811,#190812,#190813),.UNSPECIFIED.,.F.,.F.) +#193099 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193100 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#193101 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193102 = ORIENTED_EDGE('',*,*,#193103,.F.); +#193103 = EDGE_CURVE('',#193104,#193076,#193106,.T.); +#193104 = VERTEX_POINT('',#193105); +#193105 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193106 = SURFACE_CURVE('',#193107,(#193111,#193118),.PCURVE_S1.); +#193107 = LINE('',#193108,#193109); +#193108 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193109 = VECTOR('',#193110,1.); +#193110 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193111 = PCURVE('',#188337,#193112); +#193112 = DEFINITIONAL_REPRESENTATION('',(#193113),#193117); +#193113 = LINE('',#193114,#193115); +#193114 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#193115 = VECTOR('',#193116,1.); +#193116 = DIRECTION('',(0.E+000,1.)); +#193117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193118 = PCURVE('',#193119,#193124); +#193119 = PLANE('',#193120); +#193120 = AXIS2_PLACEMENT_3D('',#193121,#193122,#193123); +#193121 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193122 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193123 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193124 = DEFINITIONAL_REPRESENTATION('',(#193125),#193129); +#193125 = LINE('',#193126,#193127); +#193126 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193127 = VECTOR('',#193128,1.); +#193128 = DIRECTION('',(0.E+000,1.)); +#193129 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193130 = ORIENTED_EDGE('',*,*,#193131,.F.); +#193131 = EDGE_CURVE('',#193132,#193104,#193134,.T.); +#193132 = VERTEX_POINT('',#193133); +#193133 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#193134 = SURFACE_CURVE('',#193135,(#193139,#193146),.PCURVE_S1.); +#193135 = LINE('',#193136,#193137); +#193136 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193137 = VECTOR('',#193138,1.); +#193138 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193139 = PCURVE('',#188337,#193140); +#193140 = DEFINITIONAL_REPRESENTATION('',(#193141),#193145); +#193141 = LINE('',#193142,#193143); +#193142 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#193143 = VECTOR('',#193144,1.); +#193144 = DIRECTION('',(1.,0.E+000)); +#193145 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193146 = PCURVE('',#193147,#193152); +#193147 = PLANE('',#193148); +#193148 = AXIS2_PLACEMENT_3D('',#193149,#193150,#193151); +#193149 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193150 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#193151 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193152 = DEFINITIONAL_REPRESENTATION('',(#193153),#193157); +#193153 = LINE('',#193154,#193155); +#193154 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193155 = VECTOR('',#193156,1.); +#193156 = DIRECTION('',(1.,0.E+000)); +#193157 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193158 = ORIENTED_EDGE('',*,*,#193159,.F.); +#193159 = EDGE_CURVE('',#193160,#193132,#193162,.T.); +#193160 = VERTEX_POINT('',#193161); +#193161 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); +#193162 = SURFACE_CURVE('',#193163,(#193167,#193174),.PCURVE_S1.); +#193163 = LINE('',#193164,#193165); +#193164 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#193165 = VECTOR('',#193166,1.); +#193166 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#193167 = PCURVE('',#188337,#193168); +#193168 = DEFINITIONAL_REPRESENTATION('',(#193169),#193173); +#193169 = LINE('',#193170,#193171); +#193170 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#193171 = VECTOR('',#193172,1.); +#193172 = DIRECTION('',(0.E+000,-1.)); +#193173 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193174 = PCURVE('',#193175,#193180); +#193175 = PLANE('',#193176); +#193176 = AXIS2_PLACEMENT_3D('',#193177,#193178,#193179); +#193177 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#193178 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193179 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193180 = DEFINITIONAL_REPRESENTATION('',(#193181),#193185); +#193181 = LINE('',#193182,#193183); +#193182 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193183 = VECTOR('',#193184,1.); +#193184 = DIRECTION('',(0.E+000,-1.)); +#193185 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193186 = ORIENTED_EDGE('',*,*,#193187,.F.); +#193187 = EDGE_CURVE('',#193188,#193160,#193190,.T.); +#193188 = VERTEX_POINT('',#193189); +#193189 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#193190 = SURFACE_CURVE('',#193191,(#193196,#193207),.PCURVE_S1.); +#193191 = CIRCLE('',#193192,5.E-002); +#193192 = AXIS2_PLACEMENT_3D('',#193193,#193194,#193195); +#193193 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#193194 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193195 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193196 = PCURVE('',#188337,#193197); +#193197 = DEFINITIONAL_REPRESENTATION('',(#193198),#193206); +#193198 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#193199,#193200,#193201, + #193202,#193203,#193204,#193205),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#190807 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#190808 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#190809 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#190810 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#190811 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#190812 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#190813 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#190814 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190815 = PCURVE('',#190816,#190821); -#190816 = CYLINDRICAL_SURFACE('',#190817,5.E-002); -#190817 = AXIS2_PLACEMENT_3D('',#190818,#190819,#190820); -#190818 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); -#190819 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190820 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190821 = DEFINITIONAL_REPRESENTATION('',(#190822),#190825); -#190822 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190823,#190824), +#193199 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#193200 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#193201 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#193202 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#193203 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#193204 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#193205 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#193206 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193207 = PCURVE('',#193208,#193213); +#193208 = CYLINDRICAL_SURFACE('',#193209,5.E-002); +#193209 = AXIS2_PLACEMENT_3D('',#193210,#193211,#193212); +#193210 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.2)); +#193211 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193212 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193213 = DEFINITIONAL_REPRESENTATION('',(#193214),#193217); +#193214 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193215,#193216), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#190823 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#190824 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190825 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190826 = ORIENTED_EDGE('',*,*,#190827,.F.); -#190827 = EDGE_CURVE('',#190828,#190796,#190830,.T.); -#190828 = VERTEX_POINT('',#190829); -#190829 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); -#190830 = SURFACE_CURVE('',#190831,(#190835,#190842),.PCURVE_S1.); -#190831 = LINE('',#190832,#190833); -#190832 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#190833 = VECTOR('',#190834,1.); -#190834 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#190835 = PCURVE('',#185945,#190836); -#190836 = DEFINITIONAL_REPRESENTATION('',(#190837),#190841); -#190837 = LINE('',#190838,#190839); -#190838 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#190839 = VECTOR('',#190840,1.); -#190840 = DIRECTION('',(0.993981062721,-0.109552028512)); -#190841 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190842 = PCURVE('',#190843,#190848); -#190843 = PLANE('',#190844); -#190844 = AXIS2_PLACEMENT_3D('',#190845,#190846,#190847); -#190845 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#190846 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); -#190847 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#190848 = DEFINITIONAL_REPRESENTATION('',(#190849),#190853); -#190849 = LINE('',#190850,#190851); -#190850 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190851 = VECTOR('',#190852,1.); -#190852 = DIRECTION('',(1.,0.E+000)); -#190853 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190854 = ORIENTED_EDGE('',*,*,#190855,.F.); -#190855 = EDGE_CURVE('',#190525,#190828,#190856,.T.); -#190856 = SURFACE_CURVE('',#190857,(#190862,#190869),.PCURVE_S1.); -#190857 = CIRCLE('',#190858,0.2); -#190858 = AXIS2_PLACEMENT_3D('',#190859,#190860,#190861); -#190859 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); -#190860 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190861 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190862 = PCURVE('',#185945,#190863); -#190863 = DEFINITIONAL_REPRESENTATION('',(#190864),#190868); -#190864 = CIRCLE('',#190865,0.2); -#190865 = AXIS2_PLACEMENT_2D('',#190866,#190867); -#190866 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#190867 = DIRECTION('',(-1.,0.E+000)); -#190868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#193215 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#193216 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#190869 = PCURVE('',#190563,#190870); -#190870 = DEFINITIONAL_REPRESENTATION('',(#190871),#190874); -#190871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190872,#190873), +#193218 = ORIENTED_EDGE('',*,*,#193219,.F.); +#193219 = EDGE_CURVE('',#193220,#193188,#193222,.T.); +#193220 = VERTEX_POINT('',#193221); +#193221 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); +#193222 = SURFACE_CURVE('',#193223,(#193227,#193234),.PCURVE_S1.); +#193223 = LINE('',#193224,#193225); +#193224 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#193225 = VECTOR('',#193226,1.); +#193226 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#193227 = PCURVE('',#188337,#193228); +#193228 = DEFINITIONAL_REPRESENTATION('',(#193229),#193233); +#193229 = LINE('',#193230,#193231); +#193230 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#193231 = VECTOR('',#193232,1.); +#193232 = DIRECTION('',(0.993981062721,-0.109552028512)); +#193233 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193234 = PCURVE('',#193235,#193240); +#193235 = PLANE('',#193236); +#193236 = AXIS2_PLACEMENT_3D('',#193237,#193238,#193239); +#193237 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#193238 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); +#193239 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#193240 = DEFINITIONAL_REPRESENTATION('',(#193241),#193245); +#193241 = LINE('',#193242,#193243); +#193242 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193243 = VECTOR('',#193244,1.); +#193244 = DIRECTION('',(1.,0.E+000)); +#193245 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193246 = ORIENTED_EDGE('',*,*,#193247,.F.); +#193247 = EDGE_CURVE('',#192917,#193220,#193248,.T.); +#193248 = SURFACE_CURVE('',#193249,(#193254,#193261),.PCURVE_S1.); +#193249 = CIRCLE('',#193250,0.2); +#193250 = AXIS2_PLACEMENT_3D('',#193251,#193252,#193253); +#193251 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.55)); +#193252 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193253 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193254 = PCURVE('',#188337,#193255); +#193255 = DEFINITIONAL_REPRESENTATION('',(#193256),#193260); +#193256 = CIRCLE('',#193257,0.2); +#193257 = AXIS2_PLACEMENT_2D('',#193258,#193259); +#193258 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#193259 = DIRECTION('',(-1.,0.E+000)); +#193260 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193261 = PCURVE('',#192955,#193262); +#193262 = DEFINITIONAL_REPRESENTATION('',(#193263),#193266); +#193263 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193264,#193265), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#190872 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#190873 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#190874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#193264 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#193265 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#193266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193267 = ADVANCED_FACE('',(#193268),#188989,.T.); +#193268 = FACE_BOUND('',#193269,.T.); +#193269 = EDGE_LOOP('',(#193270,#193271,#193294,#193314)); +#193270 = ORIENTED_EDGE('',*,*,#188975,.T.); +#193271 = ORIENTED_EDGE('',*,*,#193272,.F.); +#193272 = EDGE_CURVE('',#193273,#188378,#193275,.T.); +#193273 = VERTEX_POINT('',#193274); +#193274 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); +#193275 = SURFACE_CURVE('',#193276,(#193280,#193287),.PCURVE_S1.); +#193276 = LINE('',#193277,#193278); +#193277 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); +#193278 = VECTOR('',#193279,1.); +#193279 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193280 = PCURVE('',#188989,#193281); +#193281 = DEFINITIONAL_REPRESENTATION('',(#193282),#193286); +#193282 = LINE('',#193283,#193284); +#193283 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#193284 = VECTOR('',#193285,1.); +#193285 = DIRECTION('',(0.E+000,1.)); +#193286 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193287 = PCURVE('',#188393,#193288); +#193288 = DEFINITIONAL_REPRESENTATION('',(#193289),#193293); +#193289 = LINE('',#193290,#193291); +#193290 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#193291 = VECTOR('',#193292,1.); +#193292 = DIRECTION('',(0.E+000,1.)); +#193293 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193294 = ORIENTED_EDGE('',*,*,#193295,.F.); +#193295 = EDGE_CURVE('',#192993,#193273,#193296,.T.); +#193296 = SURFACE_CURVE('',#193297,(#193301,#193308),.PCURVE_S1.); +#193297 = LINE('',#193298,#193299); +#193298 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); +#193299 = VECTOR('',#193300,1.); +#193300 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193301 = PCURVE('',#188989,#193302); +#193302 = DEFINITIONAL_REPRESENTATION('',(#193303),#193307); +#193303 = LINE('',#193304,#193305); +#193304 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193305 = VECTOR('',#193306,1.); +#193306 = DIRECTION('',(-1.,0.E+000)); +#193307 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193308 = PCURVE('',#193036,#193309); +#193309 = DEFINITIONAL_REPRESENTATION('',(#193310),#193313); +#193310 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193311,#193312), + .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); +#193311 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#193312 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#193313 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#190875 = ADVANCED_FACE('',(#190876),#186597,.T.); -#190876 = FACE_BOUND('',#190877,.T.); -#190877 = EDGE_LOOP('',(#190878,#190879,#190902,#190922)); -#190878 = ORIENTED_EDGE('',*,*,#186583,.T.); -#190879 = ORIENTED_EDGE('',*,*,#190880,.F.); -#190880 = EDGE_CURVE('',#190881,#185986,#190883,.T.); -#190881 = VERTEX_POINT('',#190882); -#190882 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); -#190883 = SURFACE_CURVE('',#190884,(#190888,#190895),.PCURVE_S1.); -#190884 = LINE('',#190885,#190886); -#190885 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.6)); -#190886 = VECTOR('',#190887,1.); -#190887 = DIRECTION('',(0.E+000,1.,0.E+000)); -#190888 = PCURVE('',#186597,#190889); -#190889 = DEFINITIONAL_REPRESENTATION('',(#190890),#190894); -#190890 = LINE('',#190891,#190892); -#190891 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#190892 = VECTOR('',#190893,1.); -#190893 = DIRECTION('',(0.E+000,1.)); -#190894 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190895 = PCURVE('',#186001,#190896); -#190896 = DEFINITIONAL_REPRESENTATION('',(#190897),#190901); -#190897 = LINE('',#190898,#190899); -#190898 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#190899 = VECTOR('',#190900,1.); -#190900 = DIRECTION('',(0.E+000,1.)); -#190901 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190902 = ORIENTED_EDGE('',*,*,#190903,.F.); -#190903 = EDGE_CURVE('',#190601,#190881,#190904,.T.); -#190904 = SURFACE_CURVE('',#190905,(#190909,#190916),.PCURVE_S1.); -#190905 = LINE('',#190906,#190907); -#190906 = CARTESIAN_POINT('',(-1.145,-0.655208001194,0.6)); -#190907 = VECTOR('',#190908,1.); -#190908 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190909 = PCURVE('',#186597,#190910); -#190910 = DEFINITIONAL_REPRESENTATION('',(#190911),#190915); -#190911 = LINE('',#190912,#190913); -#190912 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#190913 = VECTOR('',#190914,1.); -#190914 = DIRECTION('',(-1.,0.E+000)); -#190915 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190916 = PCURVE('',#190644,#190917); -#190917 = DEFINITIONAL_REPRESENTATION('',(#190918),#190921); -#190918 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190919,#190920), - .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#190919 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#190920 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190921 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190922 = ORIENTED_EDGE('',*,*,#190600,.T.); -#190923 = ADVANCED_FACE('',(#190924),#186001,.T.); -#190924 = FACE_BOUND('',#190925,.T.); -#190925 = EDGE_LOOP('',(#190926,#190927,#190928,#190951,#190974,#191001, - #191024,#191047,#191070,#191093,#191116,#191141)); -#190926 = ORIENTED_EDGE('',*,*,#185985,.F.); -#190927 = ORIENTED_EDGE('',*,*,#190574,.T.); -#190928 = ORIENTED_EDGE('',*,*,#190929,.T.); -#190929 = EDGE_CURVE('',#190548,#190930,#190932,.T.); -#190930 = VERTEX_POINT('',#190931); -#190931 = CARTESIAN_POINT('',(-0.745,-0.854004213739,0.571910405702)); -#190932 = SURFACE_CURVE('',#190933,(#190938,#190945),.PCURVE_S1.); -#190933 = CIRCLE('',#190934,0.2); -#190934 = AXIS2_PLACEMENT_3D('',#190935,#190936,#190937); -#190935 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#190936 = DIRECTION('',(1.,0.E+000,0.E+000)); -#190937 = DIRECTION('',(0.E+000,0.E+000,1.)); -#190938 = PCURVE('',#186001,#190939); -#190939 = DEFINITIONAL_REPRESENTATION('',(#190940),#190944); -#190940 = CIRCLE('',#190941,0.2); -#190941 = AXIS2_PLACEMENT_2D('',#190942,#190943); -#190942 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#190943 = DIRECTION('',(-1.,0.E+000)); -#190944 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190945 = PCURVE('',#190563,#190946); -#190946 = DEFINITIONAL_REPRESENTATION('',(#190947),#190950); -#190947 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190948,#190949), +#193314 = ORIENTED_EDGE('',*,*,#192992,.T.); +#193315 = ADVANCED_FACE('',(#193316),#188393,.T.); +#193316 = FACE_BOUND('',#193317,.T.); +#193317 = EDGE_LOOP('',(#193318,#193319,#193320,#193343,#193366,#193393, + #193416,#193439,#193462,#193485,#193508,#193533)); +#193318 = ORIENTED_EDGE('',*,*,#188377,.F.); +#193319 = ORIENTED_EDGE('',*,*,#192966,.T.); +#193320 = ORIENTED_EDGE('',*,*,#193321,.T.); +#193321 = EDGE_CURVE('',#192940,#193322,#193324,.T.); +#193322 = VERTEX_POINT('',#193323); +#193323 = CARTESIAN_POINT('',(-0.745,-0.854004213739,0.571910405702)); +#193324 = SURFACE_CURVE('',#193325,(#193330,#193337),.PCURVE_S1.); +#193325 = CIRCLE('',#193326,0.2); +#193326 = AXIS2_PLACEMENT_3D('',#193327,#193328,#193329); +#193327 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#193328 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193329 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193330 = PCURVE('',#188393,#193331); +#193331 = DEFINITIONAL_REPRESENTATION('',(#193332),#193336); +#193332 = CIRCLE('',#193333,0.2); +#193333 = AXIS2_PLACEMENT_2D('',#193334,#193335); +#193334 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#193335 = DIRECTION('',(-1.,0.E+000)); +#193336 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193337 = PCURVE('',#192955,#193338); +#193338 = DEFINITIONAL_REPRESENTATION('',(#193339),#193342); +#193339 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193340,#193341), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#190948 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#190949 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#190950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190951 = ORIENTED_EDGE('',*,*,#190952,.T.); -#190952 = EDGE_CURVE('',#190930,#190953,#190955,.T.); -#190953 = VERTEX_POINT('',#190954); -#190954 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); -#190955 = SURFACE_CURVE('',#190956,(#190960,#190967),.PCURVE_S1.); -#190956 = LINE('',#190957,#190958); -#190957 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); -#190958 = VECTOR('',#190959,1.); -#190959 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#190960 = PCURVE('',#186001,#190961); -#190961 = DEFINITIONAL_REPRESENTATION('',(#190962),#190966); -#190962 = LINE('',#190963,#190964); -#190963 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#190964 = VECTOR('',#190965,1.); -#190965 = DIRECTION('',(0.993981062721,-0.109552028512)); -#190966 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190967 = PCURVE('',#190843,#190968); -#190968 = DEFINITIONAL_REPRESENTATION('',(#190969),#190973); -#190969 = LINE('',#190970,#190971); -#190970 = CARTESIAN_POINT('',(0.E+000,0.4)); -#190971 = VECTOR('',#190972,1.); -#190972 = DIRECTION('',(1.,0.E+000)); -#190973 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190974 = ORIENTED_EDGE('',*,*,#190975,.T.); -#190975 = EDGE_CURVE('',#190953,#190976,#190978,.T.); -#190976 = VERTEX_POINT('',#190977); -#190977 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.15)); -#190978 = SURFACE_CURVE('',#190979,(#190984,#190995),.PCURVE_S1.); -#190979 = CIRCLE('',#190980,5.E-002); -#190980 = AXIS2_PLACEMENT_3D('',#190981,#190982,#190983); -#190981 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); -#190982 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#190983 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#190984 = PCURVE('',#186001,#190985); -#190985 = DEFINITIONAL_REPRESENTATION('',(#190986),#190994); -#190986 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#190987,#190988,#190989, - #190990,#190991,#190992,#190993),.UNSPECIFIED.,.F.,.F.) +#193340 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#193341 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#193342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193343 = ORIENTED_EDGE('',*,*,#193344,.T.); +#193344 = EDGE_CURVE('',#193322,#193345,#193347,.T.); +#193345 = VERTEX_POINT('',#193346); +#193346 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); +#193347 = SURFACE_CURVE('',#193348,(#193352,#193359),.PCURVE_S1.); +#193348 = LINE('',#193349,#193350); +#193349 = CARTESIAN_POINT('',(-0.745,-0.895598186972,0.194522398574)); +#193350 = VECTOR('',#193351,1.); +#193351 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#193352 = PCURVE('',#188393,#193353); +#193353 = DEFINITIONAL_REPRESENTATION('',(#193354),#193358); +#193354 = LINE('',#193355,#193356); +#193355 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#193356 = VECTOR('',#193357,1.); +#193357 = DIRECTION('',(0.993981062721,-0.109552028512)); +#193358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193359 = PCURVE('',#193235,#193360); +#193360 = DEFINITIONAL_REPRESENTATION('',(#193361),#193365); +#193361 = LINE('',#193362,#193363); +#193362 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193363 = VECTOR('',#193364,1.); +#193364 = DIRECTION('',(1.,0.E+000)); +#193365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193366 = ORIENTED_EDGE('',*,*,#193367,.T.); +#193367 = EDGE_CURVE('',#193345,#193368,#193370,.T.); +#193368 = VERTEX_POINT('',#193369); +#193369 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.15)); +#193370 = SURFACE_CURVE('',#193371,(#193376,#193387),.PCURVE_S1.); +#193371 = CIRCLE('',#193372,5.E-002); +#193372 = AXIS2_PLACEMENT_3D('',#193373,#193374,#193375); +#193373 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); +#193374 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193375 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193376 = PCURVE('',#188393,#193377); +#193377 = DEFINITIONAL_REPRESENTATION('',(#193378),#193386); +#193378 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#193379,#193380,#193381, + #193382,#193383,#193384,#193385),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#190987 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#190988 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#190989 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#190990 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#190991 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#190992 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#190993 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#190994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#190995 = PCURVE('',#190816,#190996); -#190996 = DEFINITIONAL_REPRESENTATION('',(#190997),#191000); -#190997 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#190998,#190999), +#193379 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#193380 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#193381 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#193382 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#193383 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#193384 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#193385 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#193386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193387 = PCURVE('',#193208,#193388); +#193388 = DEFINITIONAL_REPRESENTATION('',(#193389),#193392); +#193389 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193390,#193391), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#190998 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#190999 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191000 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191001 = ORIENTED_EDGE('',*,*,#191002,.T.); -#191002 = EDGE_CURVE('',#190976,#191003,#191005,.T.); -#191003 = VERTEX_POINT('',#191004); -#191004 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); -#191005 = SURFACE_CURVE('',#191006,(#191010,#191017),.PCURVE_S1.); -#191006 = LINE('',#191007,#191008); -#191007 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); -#191008 = VECTOR('',#191009,1.); -#191009 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191010 = PCURVE('',#186001,#191011); -#191011 = DEFINITIONAL_REPRESENTATION('',(#191012),#191016); -#191012 = LINE('',#191013,#191014); -#191013 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#191014 = VECTOR('',#191015,1.); -#191015 = DIRECTION('',(0.E+000,-1.)); -#191016 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191017 = PCURVE('',#190783,#191018); -#191018 = DEFINITIONAL_REPRESENTATION('',(#191019),#191023); -#191019 = LINE('',#191020,#191021); -#191020 = CARTESIAN_POINT('',(0.4,0.E+000)); -#191021 = VECTOR('',#191022,1.); -#191022 = DIRECTION('',(0.E+000,-1.)); -#191023 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191024 = ORIENTED_EDGE('',*,*,#191025,.T.); -#191025 = EDGE_CURVE('',#191003,#191026,#191028,.T.); -#191026 = VERTEX_POINT('',#191027); -#191027 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#191028 = SURFACE_CURVE('',#191029,(#191033,#191040),.PCURVE_S1.); -#191029 = LINE('',#191030,#191031); -#191030 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#191031 = VECTOR('',#191032,1.); -#191032 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191033 = PCURVE('',#186001,#191034); -#191034 = DEFINITIONAL_REPRESENTATION('',(#191035),#191039); -#191035 = LINE('',#191036,#191037); -#191036 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191037 = VECTOR('',#191038,1.); -#191038 = DIRECTION('',(1.,0.E+000)); -#191039 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191040 = PCURVE('',#190755,#191041); -#191041 = DEFINITIONAL_REPRESENTATION('',(#191042),#191046); -#191042 = LINE('',#191043,#191044); -#191043 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191044 = VECTOR('',#191045,1.); -#191045 = DIRECTION('',(1.,0.E+000)); -#191046 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191047 = ORIENTED_EDGE('',*,*,#191048,.T.); -#191048 = EDGE_CURVE('',#191026,#191049,#191051,.T.); -#191049 = VERTEX_POINT('',#191050); -#191050 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.E+000)); -#191051 = SURFACE_CURVE('',#191052,(#191056,#191063),.PCURVE_S1.); -#191052 = LINE('',#191053,#191054); -#191053 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); -#191054 = VECTOR('',#191055,1.); -#191055 = DIRECTION('',(0.E+000,1.,0.E+000)); -#191056 = PCURVE('',#186001,#191057); -#191057 = DEFINITIONAL_REPRESENTATION('',(#191058),#191062); -#191058 = LINE('',#191059,#191060); -#191059 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191060 = VECTOR('',#191061,1.); -#191061 = DIRECTION('',(0.E+000,1.)); -#191062 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191063 = PCURVE('',#190727,#191064); -#191064 = DEFINITIONAL_REPRESENTATION('',(#191065),#191069); -#191065 = LINE('',#191066,#191067); -#191066 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#191067 = VECTOR('',#191068,1.); -#191068 = DIRECTION('',(0.E+000,1.)); -#191069 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191070 = ORIENTED_EDGE('',*,*,#191071,.T.); -#191071 = EDGE_CURVE('',#191049,#191072,#191074,.T.); -#191072 = VERTEX_POINT('',#191073); -#191073 = CARTESIAN_POINT('',(-0.745,-0.746501027564,0.178089594298)); -#191074 = SURFACE_CURVE('',#191075,(#191080,#191087),.PCURVE_S1.); -#191075 = CIRCLE('',#191076,0.2); -#191076 = AXIS2_PLACEMENT_3D('',#191077,#191078,#191079); -#191077 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); -#191078 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191079 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191080 = PCURVE('',#186001,#191081); -#191081 = DEFINITIONAL_REPRESENTATION('',(#191082),#191086); -#191082 = CIRCLE('',#191083,0.2); -#191083 = AXIS2_PLACEMENT_2D('',#191084,#191085); -#191084 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#191085 = DIRECTION('',(-1.,0.E+000)); -#191086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191087 = PCURVE('',#190700,#191088); -#191088 = DEFINITIONAL_REPRESENTATION('',(#191089),#191092); -#191089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191090,#191091), +#193390 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#193391 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193392 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193393 = ORIENTED_EDGE('',*,*,#193394,.T.); +#193394 = EDGE_CURVE('',#193368,#193395,#193397,.T.); +#193395 = VERTEX_POINT('',#193396); +#193396 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); +#193397 = SURFACE_CURVE('',#193398,(#193402,#193409),.PCURVE_S1.); +#193398 = LINE('',#193399,#193400); +#193399 = CARTESIAN_POINT('',(-0.745,-1.17,0.15)); +#193400 = VECTOR('',#193401,1.); +#193401 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#193402 = PCURVE('',#188393,#193403); +#193403 = DEFINITIONAL_REPRESENTATION('',(#193404),#193408); +#193404 = LINE('',#193405,#193406); +#193405 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#193406 = VECTOR('',#193407,1.); +#193407 = DIRECTION('',(0.E+000,-1.)); +#193408 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193409 = PCURVE('',#193175,#193410); +#193410 = DEFINITIONAL_REPRESENTATION('',(#193411),#193415); +#193411 = LINE('',#193412,#193413); +#193412 = CARTESIAN_POINT('',(0.4,0.E+000)); +#193413 = VECTOR('',#193414,1.); +#193414 = DIRECTION('',(0.E+000,-1.)); +#193415 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193416 = ORIENTED_EDGE('',*,*,#193417,.T.); +#193417 = EDGE_CURVE('',#193395,#193418,#193420,.T.); +#193418 = VERTEX_POINT('',#193419); +#193419 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#193420 = SURFACE_CURVE('',#193421,(#193425,#193432),.PCURVE_S1.); +#193421 = LINE('',#193422,#193423); +#193422 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#193423 = VECTOR('',#193424,1.); +#193424 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193425 = PCURVE('',#188393,#193426); +#193426 = DEFINITIONAL_REPRESENTATION('',(#193427),#193431); +#193427 = LINE('',#193428,#193429); +#193428 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#193429 = VECTOR('',#193430,1.); +#193430 = DIRECTION('',(1.,0.E+000)); +#193431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193432 = PCURVE('',#193147,#193433); +#193433 = DEFINITIONAL_REPRESENTATION('',(#193434),#193438); +#193434 = LINE('',#193435,#193436); +#193435 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193436 = VECTOR('',#193437,1.); +#193437 = DIRECTION('',(1.,0.E+000)); +#193438 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193439 = ORIENTED_EDGE('',*,*,#193440,.T.); +#193440 = EDGE_CURVE('',#193418,#193441,#193443,.T.); +#193441 = VERTEX_POINT('',#193442); +#193442 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.E+000)); +#193443 = SURFACE_CURVE('',#193444,(#193448,#193455),.PCURVE_S1.); +#193444 = LINE('',#193445,#193446); +#193445 = CARTESIAN_POINT('',(-0.745,-1.17,0.E+000)); +#193446 = VECTOR('',#193447,1.); +#193447 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193448 = PCURVE('',#188393,#193449); +#193449 = DEFINITIONAL_REPRESENTATION('',(#193450),#193454); +#193450 = LINE('',#193451,#193452); +#193451 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#193452 = VECTOR('',#193453,1.); +#193453 = DIRECTION('',(0.E+000,1.)); +#193454 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193455 = PCURVE('',#193119,#193456); +#193456 = DEFINITIONAL_REPRESENTATION('',(#193457),#193461); +#193457 = LINE('',#193458,#193459); +#193458 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#193459 = VECTOR('',#193460,1.); +#193460 = DIRECTION('',(0.E+000,1.)); +#193461 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193462 = ORIENTED_EDGE('',*,*,#193463,.T.); +#193463 = EDGE_CURVE('',#193441,#193464,#193466,.T.); +#193464 = VERTEX_POINT('',#193465); +#193465 = CARTESIAN_POINT('',(-0.745,-0.746501027564,0.178089594298)); +#193466 = SURFACE_CURVE('',#193467,(#193472,#193479),.PCURVE_S1.); +#193467 = CIRCLE('',#193468,0.2); +#193468 = AXIS2_PLACEMENT_3D('',#193469,#193470,#193471); +#193469 = CARTESIAN_POINT('',(-0.745,-0.945297240108,0.2)); +#193470 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193471 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193472 = PCURVE('',#188393,#193473); +#193473 = DEFINITIONAL_REPRESENTATION('',(#193474),#193478); +#193474 = CIRCLE('',#193475,0.2); +#193475 = AXIS2_PLACEMENT_2D('',#193476,#193477); +#193476 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#193477 = DIRECTION('',(-1.,0.E+000)); +#193478 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193479 = PCURVE('',#193092,#193480); +#193480 = DEFINITIONAL_REPRESENTATION('',(#193481),#193484); +#193481 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193482,#193483), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#191090 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191091 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#191092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191093 = ORIENTED_EDGE('',*,*,#191094,.T.); -#191094 = EDGE_CURVE('',#191072,#191095,#191097,.T.); -#191095 = VERTEX_POINT('',#191096); -#191096 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); -#191097 = SURFACE_CURVE('',#191098,(#191102,#191109),.PCURVE_S1.); -#191098 = LINE('',#191099,#191100); -#191099 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); -#191100 = VECTOR('',#191101,1.); -#191101 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#191102 = PCURVE('',#186001,#191103); -#191103 = DEFINITIONAL_REPRESENTATION('',(#191104),#191108); -#191104 = LINE('',#191105,#191106); -#191105 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#191106 = VECTOR('',#191107,1.); -#191107 = DIRECTION('',(-0.993981062721,0.109552028512)); -#191108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191109 = PCURVE('',#190671,#191110); -#191110 = DEFINITIONAL_REPRESENTATION('',(#191111),#191115); -#191111 = LINE('',#191112,#191113); -#191112 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191113 = VECTOR('',#191114,1.); -#191114 = DIRECTION('',(1.,0.E+000)); -#191115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191116 = ORIENTED_EDGE('',*,*,#191117,.T.); -#191117 = EDGE_CURVE('',#191095,#190881,#191118,.T.); -#191118 = SURFACE_CURVE('',#191119,(#191124,#191135),.PCURVE_S1.); -#191119 = CIRCLE('',#191120,5.E-002); -#191120 = AXIS2_PLACEMENT_3D('',#191121,#191122,#191123); -#191121 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); -#191122 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191123 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191124 = PCURVE('',#186001,#191125); -#191125 = DEFINITIONAL_REPRESENTATION('',(#191126),#191134); -#191126 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191127,#191128,#191129, - #191130,#191131,#191132,#191133),.UNSPECIFIED.,.F.,.F.) +#193482 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193483 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#193484 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193485 = ORIENTED_EDGE('',*,*,#193486,.T.); +#193486 = EDGE_CURVE('',#193464,#193487,#193489,.T.); +#193487 = VERTEX_POINT('',#193488); +#193488 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); +#193489 = SURFACE_CURVE('',#193490,(#193494,#193501),.PCURVE_S1.); +#193490 = LINE('',#193491,#193492); +#193491 = CARTESIAN_POINT('',(-0.745,-0.70490705433,0.555477601426)); +#193492 = VECTOR('',#193493,1.); +#193493 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#193494 = PCURVE('',#188393,#193495); +#193495 = DEFINITIONAL_REPRESENTATION('',(#193496),#193500); +#193496 = LINE('',#193497,#193498); +#193497 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#193498 = VECTOR('',#193499,1.); +#193499 = DIRECTION('',(-0.993981062721,0.109552028512)); +#193500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193501 = PCURVE('',#193063,#193502); +#193502 = DEFINITIONAL_REPRESENTATION('',(#193503),#193507); +#193503 = LINE('',#193504,#193505); +#193504 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193505 = VECTOR('',#193506,1.); +#193506 = DIRECTION('',(1.,0.E+000)); +#193507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193508 = ORIENTED_EDGE('',*,*,#193509,.T.); +#193509 = EDGE_CURVE('',#193487,#193273,#193510,.T.); +#193510 = SURFACE_CURVE('',#193511,(#193516,#193527),.PCURVE_S1.); +#193511 = CIRCLE('',#193512,5.E-002); +#193512 = AXIS2_PLACEMENT_3D('',#193513,#193514,#193515); +#193513 = CARTESIAN_POINT('',(-0.745,-0.655208001194,0.55)); +#193514 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193515 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193516 = PCURVE('',#188393,#193517); +#193517 = DEFINITIONAL_REPRESENTATION('',(#193518),#193526); +#193518 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#193519,#193520,#193521, + #193522,#193523,#193524,#193525),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#191127 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191128 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#191129 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#191130 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#191131 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#191132 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#191133 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191134 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191135 = PCURVE('',#190644,#191136); -#191136 = DEFINITIONAL_REPRESENTATION('',(#191137),#191140); -#191137 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191138,#191139), +#193519 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193520 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#193521 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#193522 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#193523 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#193524 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#193525 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193526 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193527 = PCURVE('',#193036,#193528); +#193528 = DEFINITIONAL_REPRESENTATION('',(#193529),#193532); +#193529 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193530,#193531), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#191138 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#191139 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#191140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191141 = ORIENTED_EDGE('',*,*,#190880,.T.); -#191142 = ADVANCED_FACE('',(#191143),#190644,.F.); -#191143 = FACE_BOUND('',#191144,.F.); -#191144 = EDGE_LOOP('',(#191145,#191146,#191147,#191167)); -#191145 = ORIENTED_EDGE('',*,*,#190903,.F.); -#191146 = ORIENTED_EDGE('',*,*,#190623,.F.); -#191147 = ORIENTED_EDGE('',*,*,#191148,.T.); -#191148 = EDGE_CURVE('',#190624,#191095,#191149,.T.); -#191149 = SURFACE_CURVE('',#191150,(#191154,#191160),.PCURVE_S1.); -#191150 = LINE('',#191151,#191152); -#191151 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); -#191152 = VECTOR('',#191153,1.); -#191153 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191154 = PCURVE('',#190644,#191155); -#191155 = DEFINITIONAL_REPRESENTATION('',(#191156),#191159); -#191156 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191157,#191158), +#193530 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#193531 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#193532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193533 = ORIENTED_EDGE('',*,*,#193272,.T.); +#193534 = ADVANCED_FACE('',(#193535),#193036,.F.); +#193535 = FACE_BOUND('',#193536,.F.); +#193536 = EDGE_LOOP('',(#193537,#193538,#193539,#193559)); +#193537 = ORIENTED_EDGE('',*,*,#193295,.F.); +#193538 = ORIENTED_EDGE('',*,*,#193015,.F.); +#193539 = ORIENTED_EDGE('',*,*,#193540,.T.); +#193540 = EDGE_CURVE('',#193016,#193487,#193541,.T.); +#193541 = SURFACE_CURVE('',#193542,(#193546,#193552),.PCURVE_S1.); +#193542 = LINE('',#193543,#193544); +#193543 = CARTESIAN_POINT('',(-1.145,-0.70490705433,0.555477601426)); +#193544 = VECTOR('',#193545,1.); +#193545 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193546 = PCURVE('',#193036,#193547); +#193547 = DEFINITIONAL_REPRESENTATION('',(#193548),#193551); +#193548 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193549,#193550), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#191157 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#191158 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#191159 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191160 = PCURVE('',#190671,#191161); -#191161 = DEFINITIONAL_REPRESENTATION('',(#191162),#191166); -#191162 = LINE('',#191163,#191164); -#191163 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191164 = VECTOR('',#191165,1.); -#191165 = DIRECTION('',(0.E+000,1.)); -#191166 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191167 = ORIENTED_EDGE('',*,*,#191117,.T.); -#191168 = ADVANCED_FACE('',(#191169),#190671,.T.); -#191169 = FACE_BOUND('',#191170,.T.); -#191170 = EDGE_LOOP('',(#191171,#191172,#191173,#191193)); -#191171 = ORIENTED_EDGE('',*,*,#191148,.T.); -#191172 = ORIENTED_EDGE('',*,*,#191094,.F.); -#191173 = ORIENTED_EDGE('',*,*,#191174,.F.); -#191174 = EDGE_CURVE('',#190656,#191072,#191175,.T.); -#191175 = SURFACE_CURVE('',#191176,(#191180,#191187),.PCURVE_S1.); -#191176 = LINE('',#191177,#191178); -#191177 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); -#191178 = VECTOR('',#191179,1.); -#191179 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191180 = PCURVE('',#190671,#191181); -#191181 = DEFINITIONAL_REPRESENTATION('',(#191182),#191186); -#191182 = LINE('',#191183,#191184); -#191183 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#191184 = VECTOR('',#191185,1.); -#191185 = DIRECTION('',(0.E+000,1.)); -#191186 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191187 = PCURVE('',#190700,#191188); -#191188 = DEFINITIONAL_REPRESENTATION('',(#191189),#191192); -#191189 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191190,#191191), +#193549 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#193550 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#193551 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193552 = PCURVE('',#193063,#193553); +#193553 = DEFINITIONAL_REPRESENTATION('',(#193554),#193558); +#193554 = LINE('',#193555,#193556); +#193555 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193556 = VECTOR('',#193557,1.); +#193557 = DIRECTION('',(0.E+000,1.)); +#193558 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193559 = ORIENTED_EDGE('',*,*,#193509,.T.); +#193560 = ADVANCED_FACE('',(#193561),#193063,.T.); +#193561 = FACE_BOUND('',#193562,.T.); +#193562 = EDGE_LOOP('',(#193563,#193564,#193565,#193585)); +#193563 = ORIENTED_EDGE('',*,*,#193540,.T.); +#193564 = ORIENTED_EDGE('',*,*,#193486,.F.); +#193565 = ORIENTED_EDGE('',*,*,#193566,.F.); +#193566 = EDGE_CURVE('',#193048,#193464,#193567,.T.); +#193567 = SURFACE_CURVE('',#193568,(#193572,#193579),.PCURVE_S1.); +#193568 = LINE('',#193569,#193570); +#193569 = CARTESIAN_POINT('',(-1.145,-0.746501027564,0.178089594298)); +#193570 = VECTOR('',#193571,1.); +#193571 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193572 = PCURVE('',#193063,#193573); +#193573 = DEFINITIONAL_REPRESENTATION('',(#193574),#193578); +#193574 = LINE('',#193575,#193576); +#193575 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#193576 = VECTOR('',#193577,1.); +#193577 = DIRECTION('',(0.E+000,1.)); +#193578 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193579 = PCURVE('',#193092,#193580); +#193580 = DEFINITIONAL_REPRESENTATION('',(#193581),#193584); +#193581 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193582,#193583), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#191190 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#191191 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#191192 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191193 = ORIENTED_EDGE('',*,*,#190655,.T.); -#191194 = ADVANCED_FACE('',(#191195),#190700,.T.); -#191195 = FACE_BOUND('',#191196,.T.); -#191196 = EDGE_LOOP('',(#191197,#191198,#191199,#191242)); -#191197 = ORIENTED_EDGE('',*,*,#191174,.T.); -#191198 = ORIENTED_EDGE('',*,*,#191071,.F.); -#191199 = ORIENTED_EDGE('',*,*,#191200,.F.); -#191200 = EDGE_CURVE('',#190684,#191049,#191201,.T.); -#191201 = SURFACE_CURVE('',#191202,(#191206,#191235),.PCURVE_S1.); -#191202 = LINE('',#191203,#191204); -#191203 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); -#191204 = VECTOR('',#191205,1.); -#191205 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191206 = PCURVE('',#190700,#191207); -#191207 = DEFINITIONAL_REPRESENTATION('',(#191208),#191234); -#191208 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#191209,#191210,#191211, - #191212,#191213,#191214,#191215,#191216,#191217,#191218,#191219, - #191220,#191221,#191222,#191223,#191224,#191225,#191226,#191227, - #191228,#191229,#191230,#191231,#191232,#191233),.UNSPECIFIED.,.F., +#193582 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#193583 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#193584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193585 = ORIENTED_EDGE('',*,*,#193047,.T.); +#193586 = ADVANCED_FACE('',(#193587),#193092,.T.); +#193587 = FACE_BOUND('',#193588,.T.); +#193588 = EDGE_LOOP('',(#193589,#193590,#193591,#193634)); +#193589 = ORIENTED_EDGE('',*,*,#193566,.T.); +#193590 = ORIENTED_EDGE('',*,*,#193463,.F.); +#193591 = ORIENTED_EDGE('',*,*,#193592,.F.); +#193592 = EDGE_CURVE('',#193076,#193441,#193593,.T.); +#193593 = SURFACE_CURVE('',#193594,(#193598,#193627),.PCURVE_S1.); +#193594 = LINE('',#193595,#193596); +#193595 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.E+000)); +#193596 = VECTOR('',#193597,1.); +#193597 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193598 = PCURVE('',#193092,#193599); +#193599 = DEFINITIONAL_REPRESENTATION('',(#193600),#193626); +#193600 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193601,#193602,#193603, + #193604,#193605,#193606,#193607,#193608,#193609,#193610,#193611, + #193612,#193613,#193614,#193615,#193616,#193617,#193618,#193619, + #193620,#193621,#193622,#193623,#193624,#193625),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -237476,139 +240478,139 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#191209 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191210 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) - ); -#191211 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) - ); -#191212 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#191213 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) - ); -#191214 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) - ); -#191215 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) - ); -#191216 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); -#191217 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); -#191218 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); -#191219 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); -#191220 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); -#191221 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); -#191222 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); -#191223 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); -#191224 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); -#191225 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); -#191226 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); -#191227 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); -#191228 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); -#191229 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); -#191230 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); -#191231 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); -#191232 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); -#191233 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191235 = PCURVE('',#190727,#191236); -#191236 = DEFINITIONAL_REPRESENTATION('',(#191237),#191241); -#191237 = LINE('',#191238,#191239); -#191238 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#191239 = VECTOR('',#191240,1.); -#191240 = DIRECTION('',(-1.,0.E+000)); -#191241 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191242 = ORIENTED_EDGE('',*,*,#190683,.T.); -#191243 = ADVANCED_FACE('',(#191244),#190727,.T.); -#191244 = FACE_BOUND('',#191245,.T.); -#191245 = EDGE_LOOP('',(#191246,#191247,#191248,#191269)); -#191246 = ORIENTED_EDGE('',*,*,#191200,.T.); -#191247 = ORIENTED_EDGE('',*,*,#191048,.F.); -#191248 = ORIENTED_EDGE('',*,*,#191249,.F.); -#191249 = EDGE_CURVE('',#190712,#191026,#191250,.T.); -#191250 = SURFACE_CURVE('',#191251,(#191255,#191262),.PCURVE_S1.); -#191251 = LINE('',#191252,#191253); -#191252 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); -#191253 = VECTOR('',#191254,1.); -#191254 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191255 = PCURVE('',#190727,#191256); -#191256 = DEFINITIONAL_REPRESENTATION('',(#191257),#191261); -#191257 = LINE('',#191258,#191259); -#191258 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191259 = VECTOR('',#191260,1.); -#191260 = DIRECTION('',(-1.,0.E+000)); -#191261 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191262 = PCURVE('',#190755,#191263); -#191263 = DEFINITIONAL_REPRESENTATION('',(#191264),#191268); -#191264 = LINE('',#191265,#191266); -#191265 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191266 = VECTOR('',#191267,1.); -#191267 = DIRECTION('',(0.E+000,1.)); -#191268 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191269 = ORIENTED_EDGE('',*,*,#190711,.T.); -#191270 = ADVANCED_FACE('',(#191271),#190755,.T.); -#191271 = FACE_BOUND('',#191272,.T.); -#191272 = EDGE_LOOP('',(#191273,#191274,#191275,#191296)); -#191273 = ORIENTED_EDGE('',*,*,#191249,.T.); -#191274 = ORIENTED_EDGE('',*,*,#191025,.F.); -#191275 = ORIENTED_EDGE('',*,*,#191276,.F.); -#191276 = EDGE_CURVE('',#190740,#191003,#191277,.T.); -#191277 = SURFACE_CURVE('',#191278,(#191282,#191289),.PCURVE_S1.); -#191278 = LINE('',#191279,#191280); -#191279 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); -#191280 = VECTOR('',#191281,1.); -#191281 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191282 = PCURVE('',#190755,#191283); -#191283 = DEFINITIONAL_REPRESENTATION('',(#191284),#191288); -#191284 = LINE('',#191285,#191286); -#191285 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#191286 = VECTOR('',#191287,1.); -#191287 = DIRECTION('',(0.E+000,1.)); -#191288 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#193601 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193602 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) + ); +#193603 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) + ); +#193604 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#193605 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) + ); +#193606 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) + ); +#193607 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) + ); +#193608 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); +#193609 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); +#193610 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); +#193611 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); +#193612 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); +#193613 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); +#193614 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); +#193615 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); +#193616 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); +#193617 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); +#193618 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); +#193619 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); +#193620 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); +#193621 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); +#193622 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); +#193623 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); +#193624 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); +#193625 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193626 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193627 = PCURVE('',#193119,#193628); +#193628 = DEFINITIONAL_REPRESENTATION('',(#193629),#193633); +#193629 = LINE('',#193630,#193631); +#193630 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#193631 = VECTOR('',#193632,1.); +#193632 = DIRECTION('',(-1.,0.E+000)); +#193633 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193634 = ORIENTED_EDGE('',*,*,#193075,.T.); +#193635 = ADVANCED_FACE('',(#193636),#193119,.T.); +#193636 = FACE_BOUND('',#193637,.T.); +#193637 = EDGE_LOOP('',(#193638,#193639,#193640,#193661)); +#193638 = ORIENTED_EDGE('',*,*,#193592,.T.); +#193639 = ORIENTED_EDGE('',*,*,#193440,.F.); +#193640 = ORIENTED_EDGE('',*,*,#193641,.F.); +#193641 = EDGE_CURVE('',#193104,#193418,#193642,.T.); +#193642 = SURFACE_CURVE('',#193643,(#193647,#193654),.PCURVE_S1.); +#193643 = LINE('',#193644,#193645); +#193644 = CARTESIAN_POINT('',(-1.145,-1.17,0.E+000)); +#193645 = VECTOR('',#193646,1.); +#193646 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193647 = PCURVE('',#193119,#193648); +#193648 = DEFINITIONAL_REPRESENTATION('',(#193649),#193653); +#193649 = LINE('',#193650,#193651); +#193650 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193651 = VECTOR('',#193652,1.); +#193652 = DIRECTION('',(-1.,0.E+000)); +#193653 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193654 = PCURVE('',#193147,#193655); +#193655 = DEFINITIONAL_REPRESENTATION('',(#193656),#193660); +#193656 = LINE('',#193657,#193658); +#193657 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193658 = VECTOR('',#193659,1.); +#193659 = DIRECTION('',(0.E+000,1.)); +#193660 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193661 = ORIENTED_EDGE('',*,*,#193103,.T.); +#193662 = ADVANCED_FACE('',(#193663),#193147,.T.); +#193663 = FACE_BOUND('',#193664,.T.); +#193664 = EDGE_LOOP('',(#193665,#193666,#193667,#193688)); +#193665 = ORIENTED_EDGE('',*,*,#193641,.T.); +#193666 = ORIENTED_EDGE('',*,*,#193417,.F.); +#193667 = ORIENTED_EDGE('',*,*,#193668,.F.); +#193668 = EDGE_CURVE('',#193132,#193395,#193669,.T.); +#193669 = SURFACE_CURVE('',#193670,(#193674,#193681),.PCURVE_S1.); +#193670 = LINE('',#193671,#193672); +#193671 = CARTESIAN_POINT('',(-1.145,-1.17,0.15)); +#193672 = VECTOR('',#193673,1.); +#193673 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193674 = PCURVE('',#193147,#193675); +#193675 = DEFINITIONAL_REPRESENTATION('',(#193676),#193680); +#193676 = LINE('',#193677,#193678); +#193677 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#193678 = VECTOR('',#193679,1.); +#193679 = DIRECTION('',(0.E+000,1.)); +#193680 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193681 = PCURVE('',#193175,#193682); +#193682 = DEFINITIONAL_REPRESENTATION('',(#193683),#193687); +#193683 = LINE('',#193684,#193685); +#193684 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193685 = VECTOR('',#193686,1.); +#193686 = DIRECTION('',(1.,0.E+000)); +#193687 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193688 = ORIENTED_EDGE('',*,*,#193131,.T.); +#193689 = ADVANCED_FACE('',(#193690),#193175,.T.); +#193690 = FACE_BOUND('',#193691,.T.); +#193691 = EDGE_LOOP('',(#193692,#193693,#193694,#193737)); +#193692 = ORIENTED_EDGE('',*,*,#193668,.T.); +#193693 = ORIENTED_EDGE('',*,*,#193394,.F.); +#193694 = ORIENTED_EDGE('',*,*,#193695,.F.); +#193695 = EDGE_CURVE('',#193160,#193368,#193696,.T.); +#193696 = SURFACE_CURVE('',#193697,(#193701,#193708),.PCURVE_S1.); +#193697 = LINE('',#193698,#193699); +#193698 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); +#193699 = VECTOR('',#193700,1.); +#193700 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193701 = PCURVE('',#193175,#193702); +#193702 = DEFINITIONAL_REPRESENTATION('',(#193703),#193707); +#193703 = LINE('',#193704,#193705); +#193704 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#193705 = VECTOR('',#193706,1.); +#193706 = DIRECTION('',(1.,0.E+000)); +#193707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#191289 = PCURVE('',#190783,#191290); -#191290 = DEFINITIONAL_REPRESENTATION('',(#191291),#191295); -#191291 = LINE('',#191292,#191293); -#191292 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191293 = VECTOR('',#191294,1.); -#191294 = DIRECTION('',(1.,0.E+000)); -#191295 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191296 = ORIENTED_EDGE('',*,*,#190739,.T.); -#191297 = ADVANCED_FACE('',(#191298),#190783,.T.); -#191298 = FACE_BOUND('',#191299,.T.); -#191299 = EDGE_LOOP('',(#191300,#191301,#191302,#191345)); -#191300 = ORIENTED_EDGE('',*,*,#191276,.T.); -#191301 = ORIENTED_EDGE('',*,*,#191002,.F.); -#191302 = ORIENTED_EDGE('',*,*,#191303,.F.); -#191303 = EDGE_CURVE('',#190768,#190976,#191304,.T.); -#191304 = SURFACE_CURVE('',#191305,(#191309,#191316),.PCURVE_S1.); -#191305 = LINE('',#191306,#191307); -#191306 = CARTESIAN_POINT('',(-1.145,-0.945297240108,0.15)); -#191307 = VECTOR('',#191308,1.); -#191308 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191309 = PCURVE('',#190783,#191310); -#191310 = DEFINITIONAL_REPRESENTATION('',(#191311),#191315); -#191311 = LINE('',#191312,#191313); -#191312 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#191313 = VECTOR('',#191314,1.); -#191314 = DIRECTION('',(1.,0.E+000)); -#191315 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191316 = PCURVE('',#190816,#191317); -#191317 = DEFINITIONAL_REPRESENTATION('',(#191318),#191344); -#191318 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#191319,#191320,#191321, - #191322,#191323,#191324,#191325,#191326,#191327,#191328,#191329, - #191330,#191331,#191332,#191333,#191334,#191335,#191336,#191337, - #191338,#191339,#191340,#191341,#191342,#191343),.UNSPECIFIED.,.F., +#193708 = PCURVE('',#193208,#193709); +#193709 = DEFINITIONAL_REPRESENTATION('',(#193710),#193736); +#193710 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193711,#193712,#193713, + #193714,#193715,#193716,#193717,#193718,#193719,#193720,#193721, + #193722,#193723,#193724,#193725,#193726,#193727,#193728,#193729, + #193730,#193731,#193732,#193733,#193734,#193735),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -237616,947 +240618,947 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#191319 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191320 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) - ); -#191321 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); -#191322 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#191323 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) - ); -#191324 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) - ); -#191325 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) - ); -#191326 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); -#191327 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); -#191328 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); -#191329 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); -#191330 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); -#191331 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); -#191332 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); -#191333 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); -#191334 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); -#191335 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); -#191336 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); -#191337 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#191338 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); -#191339 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); -#191340 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); -#191341 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); -#191342 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); -#191343 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191345 = ORIENTED_EDGE('',*,*,#190767,.T.); -#191346 = ADVANCED_FACE('',(#191347),#190816,.F.); -#191347 = FACE_BOUND('',#191348,.F.); -#191348 = EDGE_LOOP('',(#191349,#191350,#191351,#191371)); -#191349 = ORIENTED_EDGE('',*,*,#191303,.F.); -#191350 = ORIENTED_EDGE('',*,*,#190795,.F.); -#191351 = ORIENTED_EDGE('',*,*,#191352,.T.); -#191352 = EDGE_CURVE('',#190796,#190953,#191353,.T.); -#191353 = SURFACE_CURVE('',#191354,(#191358,#191364),.PCURVE_S1.); -#191354 = LINE('',#191355,#191356); -#191355 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); -#191356 = VECTOR('',#191357,1.); -#191357 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191358 = PCURVE('',#190816,#191359); -#191359 = DEFINITIONAL_REPRESENTATION('',(#191360),#191363); -#191360 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191361,#191362), +#193711 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193712 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) + ); +#193713 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); +#193714 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#193715 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) + ); +#193716 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) + ); +#193717 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) + ); +#193718 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); +#193719 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); +#193720 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); +#193721 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); +#193722 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); +#193723 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); +#193724 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); +#193725 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); +#193726 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); +#193727 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); +#193728 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); +#193729 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#193730 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); +#193731 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); +#193732 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); +#193733 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); +#193734 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); +#193735 = CARTESIAN_POINT('',(0.E+000,0.4)); +#193736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193737 = ORIENTED_EDGE('',*,*,#193159,.T.); +#193738 = ADVANCED_FACE('',(#193739),#193208,.F.); +#193739 = FACE_BOUND('',#193740,.F.); +#193740 = EDGE_LOOP('',(#193741,#193742,#193743,#193763)); +#193741 = ORIENTED_EDGE('',*,*,#193695,.F.); +#193742 = ORIENTED_EDGE('',*,*,#193187,.F.); +#193743 = ORIENTED_EDGE('',*,*,#193744,.T.); +#193744 = EDGE_CURVE('',#193188,#193345,#193745,.T.); +#193745 = SURFACE_CURVE('',#193746,(#193750,#193756),.PCURVE_S1.); +#193746 = LINE('',#193747,#193748); +#193747 = CARTESIAN_POINT('',(-1.145,-0.895598186972,0.194522398574)); +#193748 = VECTOR('',#193749,1.); +#193749 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193750 = PCURVE('',#193208,#193751); +#193751 = DEFINITIONAL_REPRESENTATION('',(#193752),#193755); +#193752 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193753,#193754), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#191361 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#191362 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#191363 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191364 = PCURVE('',#190843,#191365); -#191365 = DEFINITIONAL_REPRESENTATION('',(#191366),#191370); -#191366 = LINE('',#191367,#191368); -#191367 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191368 = VECTOR('',#191369,1.); -#191369 = DIRECTION('',(0.E+000,1.)); -#191370 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191371 = ORIENTED_EDGE('',*,*,#190975,.T.); -#191372 = ADVANCED_FACE('',(#191373),#190843,.T.); -#191373 = FACE_BOUND('',#191374,.T.); -#191374 = EDGE_LOOP('',(#191375,#191376,#191377,#191397)); -#191375 = ORIENTED_EDGE('',*,*,#191352,.T.); -#191376 = ORIENTED_EDGE('',*,*,#190952,.F.); -#191377 = ORIENTED_EDGE('',*,*,#191378,.F.); -#191378 = EDGE_CURVE('',#190828,#190930,#191379,.T.); -#191379 = SURFACE_CURVE('',#191380,(#191384,#191391),.PCURVE_S1.); -#191380 = LINE('',#191381,#191382); -#191381 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); -#191382 = VECTOR('',#191383,1.); -#191383 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191384 = PCURVE('',#190843,#191385); -#191385 = DEFINITIONAL_REPRESENTATION('',(#191386),#191390); -#191386 = LINE('',#191387,#191388); -#191387 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#191388 = VECTOR('',#191389,1.); -#191389 = DIRECTION('',(0.E+000,1.)); -#191390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191391 = PCURVE('',#190563,#191392); -#191392 = DEFINITIONAL_REPRESENTATION('',(#191393),#191396); -#191393 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191394,#191395), +#193753 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#193754 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#193755 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193756 = PCURVE('',#193235,#193757); +#193757 = DEFINITIONAL_REPRESENTATION('',(#193758),#193762); +#193758 = LINE('',#193759,#193760); +#193759 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193760 = VECTOR('',#193761,1.); +#193761 = DIRECTION('',(0.E+000,1.)); +#193762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193763 = ORIENTED_EDGE('',*,*,#193367,.T.); +#193764 = ADVANCED_FACE('',(#193765),#193235,.T.); +#193765 = FACE_BOUND('',#193766,.T.); +#193766 = EDGE_LOOP('',(#193767,#193768,#193769,#193789)); +#193767 = ORIENTED_EDGE('',*,*,#193744,.T.); +#193768 = ORIENTED_EDGE('',*,*,#193344,.F.); +#193769 = ORIENTED_EDGE('',*,*,#193770,.F.); +#193770 = EDGE_CURVE('',#193220,#193322,#193771,.T.); +#193771 = SURFACE_CURVE('',#193772,(#193776,#193783),.PCURVE_S1.); +#193772 = LINE('',#193773,#193774); +#193773 = CARTESIAN_POINT('',(-1.145,-0.854004213739,0.571910405702)); +#193774 = VECTOR('',#193775,1.); +#193775 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193776 = PCURVE('',#193235,#193777); +#193777 = DEFINITIONAL_REPRESENTATION('',(#193778),#193782); +#193778 = LINE('',#193779,#193780); +#193779 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#193780 = VECTOR('',#193781,1.); +#193781 = DIRECTION('',(0.E+000,1.)); +#193782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193783 = PCURVE('',#192955,#193784); +#193784 = DEFINITIONAL_REPRESENTATION('',(#193785),#193788); +#193785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193786,#193787), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#191394 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#191395 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#191396 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191397 = ORIENTED_EDGE('',*,*,#190827,.T.); -#191398 = ADVANCED_FACE('',(#191399),#190563,.T.); -#191399 = FACE_BOUND('',#191400,.T.); -#191400 = EDGE_LOOP('',(#191401,#191402,#191403,#191404)); -#191401 = ORIENTED_EDGE('',*,*,#191378,.T.); -#191402 = ORIENTED_EDGE('',*,*,#190929,.F.); -#191403 = ORIENTED_EDGE('',*,*,#190547,.F.); -#191404 = ORIENTED_EDGE('',*,*,#190855,.T.); -#191405 = ADVANCED_FACE('',(#191406),#186080,.T.); -#191406 = FACE_BOUND('',#191407,.T.); -#191407 = EDGE_LOOP('',(#191408,#191409,#191432,#191459)); -#191408 = ORIENTED_EDGE('',*,*,#186064,.F.); -#191409 = ORIENTED_EDGE('',*,*,#191410,.T.); -#191410 = EDGE_CURVE('',#186037,#191411,#191413,.T.); -#191411 = VERTEX_POINT('',#191412); -#191412 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); -#191413 = SURFACE_CURVE('',#191414,(#191418,#191425),.PCURVE_S1.); -#191414 = LINE('',#191415,#191416); -#191415 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); -#191416 = VECTOR('',#191417,1.); -#191417 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191418 = PCURVE('',#186080,#191419); -#191419 = DEFINITIONAL_REPRESENTATION('',(#191420),#191424); -#191420 = LINE('',#191421,#191422); -#191421 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191422 = VECTOR('',#191423,1.); -#191423 = DIRECTION('',(0.E+000,-1.)); -#191424 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191425 = PCURVE('',#186052,#191426); -#191426 = DEFINITIONAL_REPRESENTATION('',(#191427),#191431); -#191427 = LINE('',#191428,#191429); -#191428 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#191429 = VECTOR('',#191430,1.); -#191430 = DIRECTION('',(0.E+000,-1.)); -#191431 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191432 = ORIENTED_EDGE('',*,*,#191433,.T.); -#191433 = EDGE_CURVE('',#191411,#191434,#191436,.T.); -#191434 = VERTEX_POINT('',#191435); -#191435 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.75)); -#191436 = SURFACE_CURVE('',#191437,(#191441,#191448),.PCURVE_S1.); -#191437 = LINE('',#191438,#191439); -#191438 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); -#191439 = VECTOR('',#191440,1.); -#191440 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191441 = PCURVE('',#186080,#191442); -#191442 = DEFINITIONAL_REPRESENTATION('',(#191443),#191447); -#191443 = LINE('',#191444,#191445); -#191444 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191445 = VECTOR('',#191446,1.); -#191446 = DIRECTION('',(1.,0.E+000)); -#191447 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191448 = PCURVE('',#191449,#191454); -#191449 = CYLINDRICAL_SURFACE('',#191450,0.2); -#191450 = AXIS2_PLACEMENT_3D('',#191451,#191452,#191453); -#191451 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); -#191452 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191453 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191454 = DEFINITIONAL_REPRESENTATION('',(#191455),#191458); -#191455 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191456,#191457), +#193786 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#193787 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#193788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193789 = ORIENTED_EDGE('',*,*,#193219,.T.); +#193790 = ADVANCED_FACE('',(#193791),#192955,.T.); +#193791 = FACE_BOUND('',#193792,.T.); +#193792 = EDGE_LOOP('',(#193793,#193794,#193795,#193796)); +#193793 = ORIENTED_EDGE('',*,*,#193770,.T.); +#193794 = ORIENTED_EDGE('',*,*,#193321,.F.); +#193795 = ORIENTED_EDGE('',*,*,#192939,.F.); +#193796 = ORIENTED_EDGE('',*,*,#193247,.T.); +#193797 = ADVANCED_FACE('',(#193798),#188472,.T.); +#193798 = FACE_BOUND('',#193799,.T.); +#193799 = EDGE_LOOP('',(#193800,#193801,#193824,#193851)); +#193800 = ORIENTED_EDGE('',*,*,#188456,.F.); +#193801 = ORIENTED_EDGE('',*,*,#193802,.T.); +#193802 = EDGE_CURVE('',#188429,#193803,#193805,.T.); +#193803 = VERTEX_POINT('',#193804); +#193804 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); +#193805 = SURFACE_CURVE('',#193806,(#193810,#193817),.PCURVE_S1.); +#193806 = LINE('',#193807,#193808); +#193807 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); +#193808 = VECTOR('',#193809,1.); +#193809 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#193810 = PCURVE('',#188472,#193811); +#193811 = DEFINITIONAL_REPRESENTATION('',(#193812),#193816); +#193812 = LINE('',#193813,#193814); +#193813 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193814 = VECTOR('',#193815,1.); +#193815 = DIRECTION('',(0.E+000,-1.)); +#193816 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193817 = PCURVE('',#188444,#193818); +#193818 = DEFINITIONAL_REPRESENTATION('',(#193819),#193823); +#193819 = LINE('',#193820,#193821); +#193820 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#193821 = VECTOR('',#193822,1.); +#193822 = DIRECTION('',(0.E+000,-1.)); +#193823 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193824 = ORIENTED_EDGE('',*,*,#193825,.T.); +#193825 = EDGE_CURVE('',#193803,#193826,#193828,.T.); +#193826 = VERTEX_POINT('',#193827); +#193827 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.75)); +#193828 = SURFACE_CURVE('',#193829,(#193833,#193840),.PCURVE_S1.); +#193829 = LINE('',#193830,#193831); +#193830 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.75)); +#193831 = VECTOR('',#193832,1.); +#193832 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193833 = PCURVE('',#188472,#193834); +#193834 = DEFINITIONAL_REPRESENTATION('',(#193835),#193839); +#193835 = LINE('',#193836,#193837); +#193836 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193837 = VECTOR('',#193838,1.); +#193838 = DIRECTION('',(1.,0.E+000)); +#193839 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193840 = PCURVE('',#193841,#193846); +#193841 = CYLINDRICAL_SURFACE('',#193842,0.2); +#193842 = AXIS2_PLACEMENT_3D('',#193843,#193844,#193845); +#193843 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); +#193844 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193845 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193846 = DEFINITIONAL_REPRESENTATION('',(#193847),#193850); +#193847 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193848,#193849), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#191456 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#191457 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#191458 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191459 = ORIENTED_EDGE('',*,*,#191460,.F.); -#191460 = EDGE_CURVE('',#186065,#191434,#191461,.T.); -#191461 = SURFACE_CURVE('',#191462,(#191466,#191473),.PCURVE_S1.); -#191462 = LINE('',#191463,#191464); -#191463 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.75)); -#191464 = VECTOR('',#191465,1.); -#191465 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191466 = PCURVE('',#186080,#191467); -#191467 = DEFINITIONAL_REPRESENTATION('',(#191468),#191472); -#191468 = LINE('',#191469,#191470); -#191469 = CARTESIAN_POINT('',(0.4,0.E+000)); -#191470 = VECTOR('',#191471,1.); -#191471 = DIRECTION('',(0.E+000,-1.)); -#191472 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191473 = PCURVE('',#186108,#191474); -#191474 = DEFINITIONAL_REPRESENTATION('',(#191475),#191479); -#191475 = LINE('',#191476,#191477); -#191476 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); -#191477 = VECTOR('',#191478,1.); -#191478 = DIRECTION('',(0.E+000,-1.)); -#191479 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191480 = ADVANCED_FACE('',(#191481),#186052,.F.); -#191481 = FACE_BOUND('',#191482,.T.); -#191482 = EDGE_LOOP('',(#191483,#191484,#191485,#191508,#191540,#191568, - #191596,#191624,#191652,#191680,#191712,#191740)); -#191483 = ORIENTED_EDGE('',*,*,#191410,.F.); -#191484 = ORIENTED_EDGE('',*,*,#186036,.T.); -#191485 = ORIENTED_EDGE('',*,*,#191486,.F.); -#191486 = EDGE_CURVE('',#191487,#186014,#191489,.T.); -#191487 = VERTEX_POINT('',#191488); -#191488 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); -#191489 = SURFACE_CURVE('',#191490,(#191494,#191501),.PCURVE_S1.); -#191490 = LINE('',#191491,#191492); -#191491 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); -#191492 = VECTOR('',#191493,1.); -#191493 = DIRECTION('',(0.E+000,1.,0.E+000)); -#191494 = PCURVE('',#186052,#191495); -#191495 = DEFINITIONAL_REPRESENTATION('',(#191496),#191500); -#191496 = LINE('',#191497,#191498); -#191497 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#191498 = VECTOR('',#191499,1.); -#191499 = DIRECTION('',(0.E+000,1.)); -#191500 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191501 = PCURVE('',#186570,#191502); -#191502 = DEFINITIONAL_REPRESENTATION('',(#191503),#191507); -#191503 = LINE('',#191504,#191505); -#191504 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191505 = VECTOR('',#191506,1.); -#191506 = DIRECTION('',(0.E+000,1.)); -#191507 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191508 = ORIENTED_EDGE('',*,*,#191509,.F.); -#191509 = EDGE_CURVE('',#191510,#191487,#191512,.T.); -#191510 = VERTEX_POINT('',#191511); -#191511 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); -#191512 = SURFACE_CURVE('',#191513,(#191518,#191529),.PCURVE_S1.); -#191513 = CIRCLE('',#191514,5.E-002); -#191514 = AXIS2_PLACEMENT_3D('',#191515,#191516,#191517); -#191515 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); -#191516 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191517 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191518 = PCURVE('',#186052,#191519); -#191519 = DEFINITIONAL_REPRESENTATION('',(#191520),#191528); -#191520 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191521,#191522,#191523, - #191524,#191525,#191526,#191527),.UNSPECIFIED.,.F.,.F.) +#193848 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#193849 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#193850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193851 = ORIENTED_EDGE('',*,*,#193852,.F.); +#193852 = EDGE_CURVE('',#188457,#193826,#193853,.T.); +#193853 = SURFACE_CURVE('',#193854,(#193858,#193865),.PCURVE_S1.); +#193854 = LINE('',#193855,#193856); +#193855 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.75)); +#193856 = VECTOR('',#193857,1.); +#193857 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#193858 = PCURVE('',#188472,#193859); +#193859 = DEFINITIONAL_REPRESENTATION('',(#193860),#193864); +#193860 = LINE('',#193861,#193862); +#193861 = CARTESIAN_POINT('',(0.4,0.E+000)); +#193862 = VECTOR('',#193863,1.); +#193863 = DIRECTION('',(0.E+000,-1.)); +#193864 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193865 = PCURVE('',#188500,#193866); +#193866 = DEFINITIONAL_REPRESENTATION('',(#193867),#193871); +#193867 = LINE('',#193868,#193869); +#193868 = CARTESIAN_POINT('',(-0.2,1.33226762955E-015)); +#193869 = VECTOR('',#193870,1.); +#193870 = DIRECTION('',(0.E+000,-1.)); +#193871 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193872 = ADVANCED_FACE('',(#193873),#188444,.F.); +#193873 = FACE_BOUND('',#193874,.T.); +#193874 = EDGE_LOOP('',(#193875,#193876,#193877,#193900,#193932,#193960, + #193988,#194016,#194044,#194072,#194104,#194132)); +#193875 = ORIENTED_EDGE('',*,*,#193802,.F.); +#193876 = ORIENTED_EDGE('',*,*,#188428,.T.); +#193877 = ORIENTED_EDGE('',*,*,#193878,.F.); +#193878 = EDGE_CURVE('',#193879,#188406,#193881,.T.); +#193879 = VERTEX_POINT('',#193880); +#193880 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); +#193881 = SURFACE_CURVE('',#193882,(#193886,#193893),.PCURVE_S1.); +#193882 = LINE('',#193883,#193884); +#193883 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); +#193884 = VECTOR('',#193885,1.); +#193885 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193886 = PCURVE('',#188444,#193887); +#193887 = DEFINITIONAL_REPRESENTATION('',(#193888),#193892); +#193888 = LINE('',#193889,#193890); +#193889 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#193890 = VECTOR('',#193891,1.); +#193891 = DIRECTION('',(0.E+000,1.)); +#193892 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193893 = PCURVE('',#188962,#193894); +#193894 = DEFINITIONAL_REPRESENTATION('',(#193895),#193899); +#193895 = LINE('',#193896,#193897); +#193896 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193897 = VECTOR('',#193898,1.); +#193898 = DIRECTION('',(0.E+000,1.)); +#193899 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193900 = ORIENTED_EDGE('',*,*,#193901,.F.); +#193901 = EDGE_CURVE('',#193902,#193879,#193904,.T.); +#193902 = VERTEX_POINT('',#193903); +#193903 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); +#193904 = SURFACE_CURVE('',#193905,(#193910,#193921),.PCURVE_S1.); +#193905 = CIRCLE('',#193906,5.E-002); +#193906 = AXIS2_PLACEMENT_3D('',#193907,#193908,#193909); +#193907 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); +#193908 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#193909 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193910 = PCURVE('',#188444,#193911); +#193911 = DEFINITIONAL_REPRESENTATION('',(#193912),#193920); +#193912 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#193913,#193914,#193915, + #193916,#193917,#193918,#193919),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#191521 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191522 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#191523 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#191524 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#191525 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#191526 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#191527 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191529 = PCURVE('',#191530,#191535); -#191530 = CYLINDRICAL_SURFACE('',#191531,5.E-002); -#191531 = AXIS2_PLACEMENT_3D('',#191532,#191533,#191534); -#191532 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); -#191533 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191534 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191535 = DEFINITIONAL_REPRESENTATION('',(#191536),#191539); -#191536 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191537,#191538), +#193913 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193914 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#193915 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#193916 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#193917 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#193918 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#193919 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#193920 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193921 = PCURVE('',#193922,#193927); +#193922 = CYLINDRICAL_SURFACE('',#193923,5.E-002); +#193923 = AXIS2_PLACEMENT_3D('',#193924,#193925,#193926); +#193924 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); +#193925 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193926 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193927 = DEFINITIONAL_REPRESENTATION('',(#193928),#193931); +#193928 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193929,#193930), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#191537 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#191538 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#191539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191540 = ORIENTED_EDGE('',*,*,#191541,.F.); -#191541 = EDGE_CURVE('',#191542,#191510,#191544,.T.); -#191542 = VERTEX_POINT('',#191543); -#191543 = CARTESIAN_POINT('',(-0.2,-0.746501027564,0.178089594298)); -#191544 = SURFACE_CURVE('',#191545,(#191549,#191556),.PCURVE_S1.); -#191545 = LINE('',#191546,#191547); -#191546 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); -#191547 = VECTOR('',#191548,1.); -#191548 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#191549 = PCURVE('',#186052,#191550); -#191550 = DEFINITIONAL_REPRESENTATION('',(#191551),#191555); -#191551 = LINE('',#191552,#191553); -#191552 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#191553 = VECTOR('',#191554,1.); -#191554 = DIRECTION('',(-0.993981062721,0.109552028512)); -#191555 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191556 = PCURVE('',#191557,#191562); -#191557 = PLANE('',#191558); -#191558 = AXIS2_PLACEMENT_3D('',#191559,#191560,#191561); -#191559 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); -#191560 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); -#191561 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#191562 = DEFINITIONAL_REPRESENTATION('',(#191563),#191567); -#191563 = LINE('',#191564,#191565); -#191564 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191565 = VECTOR('',#191566,1.); -#191566 = DIRECTION('',(1.,0.E+000)); -#191567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191568 = ORIENTED_EDGE('',*,*,#191569,.F.); -#191569 = EDGE_CURVE('',#191570,#191542,#191572,.T.); -#191570 = VERTEX_POINT('',#191571); -#191571 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.E+000)); -#191572 = SURFACE_CURVE('',#191573,(#191578,#191585),.PCURVE_S1.); -#191573 = CIRCLE('',#191574,0.2); -#191574 = AXIS2_PLACEMENT_3D('',#191575,#191576,#191577); -#191575 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); -#191576 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191577 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191578 = PCURVE('',#186052,#191579); -#191579 = DEFINITIONAL_REPRESENTATION('',(#191580),#191584); -#191580 = CIRCLE('',#191581,0.2); -#191581 = AXIS2_PLACEMENT_2D('',#191582,#191583); -#191582 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#191583 = DIRECTION('',(-1.,0.E+000)); -#191584 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191585 = PCURVE('',#191586,#191591); -#191586 = CYLINDRICAL_SURFACE('',#191587,0.2); -#191587 = AXIS2_PLACEMENT_3D('',#191588,#191589,#191590); -#191588 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); -#191589 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191590 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191591 = DEFINITIONAL_REPRESENTATION('',(#191592),#191595); -#191592 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191593,#191594), +#193929 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#193930 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#193931 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193932 = ORIENTED_EDGE('',*,*,#193933,.F.); +#193933 = EDGE_CURVE('',#193934,#193902,#193936,.T.); +#193934 = VERTEX_POINT('',#193935); +#193935 = CARTESIAN_POINT('',(-0.2,-0.746501027564,0.178089594298)); +#193936 = SURFACE_CURVE('',#193937,(#193941,#193948),.PCURVE_S1.); +#193937 = LINE('',#193938,#193939); +#193938 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); +#193939 = VECTOR('',#193940,1.); +#193940 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#193941 = PCURVE('',#188444,#193942); +#193942 = DEFINITIONAL_REPRESENTATION('',(#193943),#193947); +#193943 = LINE('',#193944,#193945); +#193944 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#193945 = VECTOR('',#193946,1.); +#193946 = DIRECTION('',(-0.993981062721,0.109552028512)); +#193947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193948 = PCURVE('',#193949,#193954); +#193949 = PLANE('',#193950); +#193950 = AXIS2_PLACEMENT_3D('',#193951,#193952,#193953); +#193951 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); +#193952 = DIRECTION('',(0.E+000,0.993981062721,-0.109552028512)); +#193953 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#193954 = DEFINITIONAL_REPRESENTATION('',(#193955),#193959); +#193955 = LINE('',#193956,#193957); +#193956 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193957 = VECTOR('',#193958,1.); +#193958 = DIRECTION('',(1.,0.E+000)); +#193959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193960 = ORIENTED_EDGE('',*,*,#193961,.F.); +#193961 = EDGE_CURVE('',#193962,#193934,#193964,.T.); +#193962 = VERTEX_POINT('',#193963); +#193963 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.E+000)); +#193964 = SURFACE_CURVE('',#193965,(#193970,#193977),.PCURVE_S1.); +#193965 = CIRCLE('',#193966,0.2); +#193966 = AXIS2_PLACEMENT_3D('',#193967,#193968,#193969); +#193967 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); +#193968 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193969 = DIRECTION('',(0.E+000,0.E+000,1.)); +#193970 = PCURVE('',#188444,#193971); +#193971 = DEFINITIONAL_REPRESENTATION('',(#193972),#193976); +#193972 = CIRCLE('',#193973,0.2); +#193973 = AXIS2_PLACEMENT_2D('',#193974,#193975); +#193974 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#193975 = DIRECTION('',(-1.,0.E+000)); +#193976 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193977 = PCURVE('',#193978,#193983); +#193978 = CYLINDRICAL_SURFACE('',#193979,0.2); +#193979 = AXIS2_PLACEMENT_3D('',#193980,#193981,#193982); +#193980 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); +#193981 = DIRECTION('',(1.,0.E+000,0.E+000)); +#193982 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#193983 = DEFINITIONAL_REPRESENTATION('',(#193984),#193987); +#193984 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193985,#193986), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#191593 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191594 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#191595 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191596 = ORIENTED_EDGE('',*,*,#191597,.F.); -#191597 = EDGE_CURVE('',#191598,#191570,#191600,.T.); -#191598 = VERTEX_POINT('',#191599); -#191599 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#191600 = SURFACE_CURVE('',#191601,(#191605,#191612),.PCURVE_S1.); -#191601 = LINE('',#191602,#191603); -#191602 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#191603 = VECTOR('',#191604,1.); -#191604 = DIRECTION('',(0.E+000,1.,0.E+000)); -#191605 = PCURVE('',#186052,#191606); -#191606 = DEFINITIONAL_REPRESENTATION('',(#191607),#191611); -#191607 = LINE('',#191608,#191609); -#191608 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191609 = VECTOR('',#191610,1.); -#191610 = DIRECTION('',(0.E+000,1.)); -#191611 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191612 = PCURVE('',#191613,#191618); -#191613 = PLANE('',#191614); -#191614 = AXIS2_PLACEMENT_3D('',#191615,#191616,#191617); -#191615 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#191616 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191617 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191618 = DEFINITIONAL_REPRESENTATION('',(#191619),#191623); -#191619 = LINE('',#191620,#191621); -#191620 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191621 = VECTOR('',#191622,1.); -#191622 = DIRECTION('',(0.E+000,1.)); -#191623 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191624 = ORIENTED_EDGE('',*,*,#191625,.F.); -#191625 = EDGE_CURVE('',#191626,#191598,#191628,.T.); -#191626 = VERTEX_POINT('',#191627); -#191627 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); -#191628 = SURFACE_CURVE('',#191629,(#191633,#191640),.PCURVE_S1.); -#191629 = LINE('',#191630,#191631); -#191630 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#191631 = VECTOR('',#191632,1.); -#191632 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191633 = PCURVE('',#186052,#191634); -#191634 = DEFINITIONAL_REPRESENTATION('',(#191635),#191639); -#191635 = LINE('',#191636,#191637); -#191636 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191637 = VECTOR('',#191638,1.); -#191638 = DIRECTION('',(1.,0.E+000)); -#191639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191640 = PCURVE('',#191641,#191646); -#191641 = PLANE('',#191642); -#191642 = AXIS2_PLACEMENT_3D('',#191643,#191644,#191645); -#191643 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#191644 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191645 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191646 = DEFINITIONAL_REPRESENTATION('',(#191647),#191651); -#191647 = LINE('',#191648,#191649); -#191648 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191649 = VECTOR('',#191650,1.); -#191650 = DIRECTION('',(1.,0.E+000)); -#191651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191652 = ORIENTED_EDGE('',*,*,#191653,.F.); -#191653 = EDGE_CURVE('',#191654,#191626,#191656,.T.); -#191654 = VERTEX_POINT('',#191655); -#191655 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.15)); -#191656 = SURFACE_CURVE('',#191657,(#191661,#191668),.PCURVE_S1.); -#191657 = LINE('',#191658,#191659); -#191658 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); -#191659 = VECTOR('',#191660,1.); -#191660 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191661 = PCURVE('',#186052,#191662); -#191662 = DEFINITIONAL_REPRESENTATION('',(#191663),#191667); -#191663 = LINE('',#191664,#191665); -#191664 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#191665 = VECTOR('',#191666,1.); -#191666 = DIRECTION('',(0.E+000,-1.)); -#191667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191668 = PCURVE('',#191669,#191674); -#191669 = PLANE('',#191670); -#191670 = AXIS2_PLACEMENT_3D('',#191671,#191672,#191673); -#191671 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); -#191672 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191673 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191674 = DEFINITIONAL_REPRESENTATION('',(#191675),#191679); -#191675 = LINE('',#191676,#191677); -#191676 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191677 = VECTOR('',#191678,1.); -#191678 = DIRECTION('',(0.E+000,-1.)); -#191679 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191680 = ORIENTED_EDGE('',*,*,#191681,.F.); -#191681 = EDGE_CURVE('',#191682,#191654,#191684,.T.); -#191682 = VERTEX_POINT('',#191683); -#191683 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); -#191684 = SURFACE_CURVE('',#191685,(#191690,#191701),.PCURVE_S1.); -#191685 = CIRCLE('',#191686,5.E-002); -#191686 = AXIS2_PLACEMENT_3D('',#191687,#191688,#191689); -#191687 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); -#191688 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191689 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191690 = PCURVE('',#186052,#191691); -#191691 = DEFINITIONAL_REPRESENTATION('',(#191692),#191700); -#191692 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191693,#191694,#191695, - #191696,#191697,#191698,#191699),.UNSPECIFIED.,.F.,.F.) +#193985 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#193986 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#193987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#193988 = ORIENTED_EDGE('',*,*,#193989,.F.); +#193989 = EDGE_CURVE('',#193990,#193962,#193992,.T.); +#193990 = VERTEX_POINT('',#193991); +#193991 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#193992 = SURFACE_CURVE('',#193993,(#193997,#194004),.PCURVE_S1.); +#193993 = LINE('',#193994,#193995); +#193994 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#193995 = VECTOR('',#193996,1.); +#193996 = DIRECTION('',(0.E+000,1.,0.E+000)); +#193997 = PCURVE('',#188444,#193998); +#193998 = DEFINITIONAL_REPRESENTATION('',(#193999),#194003); +#193999 = LINE('',#194000,#194001); +#194000 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#194001 = VECTOR('',#194002,1.); +#194002 = DIRECTION('',(0.E+000,1.)); +#194003 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194004 = PCURVE('',#194005,#194010); +#194005 = PLANE('',#194006); +#194006 = AXIS2_PLACEMENT_3D('',#194007,#194008,#194009); +#194007 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#194008 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194009 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194010 = DEFINITIONAL_REPRESENTATION('',(#194011),#194015); +#194011 = LINE('',#194012,#194013); +#194012 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194013 = VECTOR('',#194014,1.); +#194014 = DIRECTION('',(0.E+000,1.)); +#194015 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194016 = ORIENTED_EDGE('',*,*,#194017,.F.); +#194017 = EDGE_CURVE('',#194018,#193990,#194020,.T.); +#194018 = VERTEX_POINT('',#194019); +#194019 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); +#194020 = SURFACE_CURVE('',#194021,(#194025,#194032),.PCURVE_S1.); +#194021 = LINE('',#194022,#194023); +#194022 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#194023 = VECTOR('',#194024,1.); +#194024 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194025 = PCURVE('',#188444,#194026); +#194026 = DEFINITIONAL_REPRESENTATION('',(#194027),#194031); +#194027 = LINE('',#194028,#194029); +#194028 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#194029 = VECTOR('',#194030,1.); +#194030 = DIRECTION('',(1.,0.E+000)); +#194031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194032 = PCURVE('',#194033,#194038); +#194033 = PLANE('',#194034); +#194034 = AXIS2_PLACEMENT_3D('',#194035,#194036,#194037); +#194035 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#194036 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194037 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194038 = DEFINITIONAL_REPRESENTATION('',(#194039),#194043); +#194039 = LINE('',#194040,#194041); +#194040 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194041 = VECTOR('',#194042,1.); +#194042 = DIRECTION('',(1.,0.E+000)); +#194043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194044 = ORIENTED_EDGE('',*,*,#194045,.F.); +#194045 = EDGE_CURVE('',#194046,#194018,#194048,.T.); +#194046 = VERTEX_POINT('',#194047); +#194047 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.15)); +#194048 = SURFACE_CURVE('',#194049,(#194053,#194060),.PCURVE_S1.); +#194049 = LINE('',#194050,#194051); +#194050 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); +#194051 = VECTOR('',#194052,1.); +#194052 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194053 = PCURVE('',#188444,#194054); +#194054 = DEFINITIONAL_REPRESENTATION('',(#194055),#194059); +#194055 = LINE('',#194056,#194057); +#194056 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#194057 = VECTOR('',#194058,1.); +#194058 = DIRECTION('',(0.E+000,-1.)); +#194059 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194060 = PCURVE('',#194061,#194066); +#194061 = PLANE('',#194062); +#194062 = AXIS2_PLACEMENT_3D('',#194063,#194064,#194065); +#194063 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); +#194064 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194065 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194066 = DEFINITIONAL_REPRESENTATION('',(#194067),#194071); +#194067 = LINE('',#194068,#194069); +#194068 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194069 = VECTOR('',#194070,1.); +#194070 = DIRECTION('',(0.E+000,-1.)); +#194071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194072 = ORIENTED_EDGE('',*,*,#194073,.F.); +#194073 = EDGE_CURVE('',#194074,#194046,#194076,.T.); +#194074 = VERTEX_POINT('',#194075); +#194075 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); +#194076 = SURFACE_CURVE('',#194077,(#194082,#194093),.PCURVE_S1.); +#194077 = CIRCLE('',#194078,5.E-002); +#194078 = AXIS2_PLACEMENT_3D('',#194079,#194080,#194081); +#194079 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); +#194080 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194081 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194082 = PCURVE('',#188444,#194083); +#194083 = DEFINITIONAL_REPRESENTATION('',(#194084),#194092); +#194084 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#194085,#194086,#194087, + #194088,#194089,#194090,#194091),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#191693 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#191694 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#191695 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#191696 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#191697 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#191698 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#191699 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#191700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191701 = PCURVE('',#191702,#191707); -#191702 = CYLINDRICAL_SURFACE('',#191703,5.E-002); -#191703 = AXIS2_PLACEMENT_3D('',#191704,#191705,#191706); -#191704 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); -#191705 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191706 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191707 = DEFINITIONAL_REPRESENTATION('',(#191708),#191711); -#191708 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191709,#191710), +#194085 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#194086 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#194087 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#194088 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#194089 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#194090 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#194091 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#194092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194093 = PCURVE('',#194094,#194099); +#194094 = CYLINDRICAL_SURFACE('',#194095,5.E-002); +#194095 = AXIS2_PLACEMENT_3D('',#194096,#194097,#194098); +#194096 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.2)); +#194097 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194098 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194099 = DEFINITIONAL_REPRESENTATION('',(#194100),#194103); +#194100 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194101,#194102), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#191709 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#191710 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191711 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191712 = ORIENTED_EDGE('',*,*,#191713,.F.); -#191713 = EDGE_CURVE('',#191714,#191682,#191716,.T.); -#191714 = VERTEX_POINT('',#191715); -#191715 = CARTESIAN_POINT('',(-0.2,-0.854004213739,0.571910405702)); -#191716 = SURFACE_CURVE('',#191717,(#191721,#191728),.PCURVE_S1.); -#191717 = LINE('',#191718,#191719); -#191718 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); -#191719 = VECTOR('',#191720,1.); -#191720 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#191721 = PCURVE('',#186052,#191722); -#191722 = DEFINITIONAL_REPRESENTATION('',(#191723),#191727); -#191723 = LINE('',#191724,#191725); -#191724 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#191725 = VECTOR('',#191726,1.); -#191726 = DIRECTION('',(0.993981062721,-0.109552028512)); -#191727 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191728 = PCURVE('',#191729,#191734); -#191729 = PLANE('',#191730); -#191730 = AXIS2_PLACEMENT_3D('',#191731,#191732,#191733); -#191731 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); -#191732 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); -#191733 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#191734 = DEFINITIONAL_REPRESENTATION('',(#191735),#191739); -#191735 = LINE('',#191736,#191737); -#191736 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#191737 = VECTOR('',#191738,1.); -#191738 = DIRECTION('',(1.,0.E+000)); -#191739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191740 = ORIENTED_EDGE('',*,*,#191741,.F.); -#191741 = EDGE_CURVE('',#191411,#191714,#191742,.T.); -#191742 = SURFACE_CURVE('',#191743,(#191748,#191755),.PCURVE_S1.); -#191743 = CIRCLE('',#191744,0.2); -#191744 = AXIS2_PLACEMENT_3D('',#191745,#191746,#191747); -#191745 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); -#191746 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191747 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191748 = PCURVE('',#186052,#191749); -#191749 = DEFINITIONAL_REPRESENTATION('',(#191750),#191754); -#191750 = CIRCLE('',#191751,0.2); -#191751 = AXIS2_PLACEMENT_2D('',#191752,#191753); -#191752 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#191753 = DIRECTION('',(-1.,0.E+000)); -#191754 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191755 = PCURVE('',#191449,#191756); -#191756 = DEFINITIONAL_REPRESENTATION('',(#191757),#191760); -#191757 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191758,#191759), +#194101 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#194102 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194103 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194104 = ORIENTED_EDGE('',*,*,#194105,.F.); +#194105 = EDGE_CURVE('',#194106,#194074,#194108,.T.); +#194106 = VERTEX_POINT('',#194107); +#194107 = CARTESIAN_POINT('',(-0.2,-0.854004213739,0.571910405702)); +#194108 = SURFACE_CURVE('',#194109,(#194113,#194120),.PCURVE_S1.); +#194109 = LINE('',#194110,#194111); +#194110 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); +#194111 = VECTOR('',#194112,1.); +#194112 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#194113 = PCURVE('',#188444,#194114); +#194114 = DEFINITIONAL_REPRESENTATION('',(#194115),#194119); +#194115 = LINE('',#194116,#194117); +#194116 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#194117 = VECTOR('',#194118,1.); +#194118 = DIRECTION('',(0.993981062721,-0.109552028512)); +#194119 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194120 = PCURVE('',#194121,#194126); +#194121 = PLANE('',#194122); +#194122 = AXIS2_PLACEMENT_3D('',#194123,#194124,#194125); +#194123 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); +#194124 = DIRECTION('',(0.E+000,-0.993981062721,0.109552028512)); +#194125 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#194126 = DEFINITIONAL_REPRESENTATION('',(#194127),#194131); +#194127 = LINE('',#194128,#194129); +#194128 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194129 = VECTOR('',#194130,1.); +#194130 = DIRECTION('',(1.,0.E+000)); +#194131 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194132 = ORIENTED_EDGE('',*,*,#194133,.F.); +#194133 = EDGE_CURVE('',#193803,#194106,#194134,.T.); +#194134 = SURFACE_CURVE('',#194135,(#194140,#194147),.PCURVE_S1.); +#194135 = CIRCLE('',#194136,0.2); +#194136 = AXIS2_PLACEMENT_3D('',#194137,#194138,#194139); +#194137 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.55)); +#194138 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194139 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194140 = PCURVE('',#188444,#194141); +#194141 = DEFINITIONAL_REPRESENTATION('',(#194142),#194146); +#194142 = CIRCLE('',#194143,0.2); +#194143 = AXIS2_PLACEMENT_2D('',#194144,#194145); +#194144 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#194145 = DIRECTION('',(-1.,0.E+000)); +#194146 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194147 = PCURVE('',#193841,#194148); +#194148 = DEFINITIONAL_REPRESENTATION('',(#194149),#194152); +#194149 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194150,#194151), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#191758 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#191759 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#191760 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191761 = ADVANCED_FACE('',(#191762),#186108,.T.); -#191762 = FACE_BOUND('',#191763,.T.); -#191763 = EDGE_LOOP('',(#191764,#191765,#191766,#191789,#191812,#191839, - #191862,#191885,#191908,#191931,#191954,#191981)); -#191764 = ORIENTED_EDGE('',*,*,#186092,.F.); -#191765 = ORIENTED_EDGE('',*,*,#191460,.T.); -#191766 = ORIENTED_EDGE('',*,*,#191767,.T.); -#191767 = EDGE_CURVE('',#191434,#191768,#191770,.T.); -#191768 = VERTEX_POINT('',#191769); -#191769 = CARTESIAN_POINT('',(0.2,-0.854004213739,0.571910405702)); -#191770 = SURFACE_CURVE('',#191771,(#191776,#191783),.PCURVE_S1.); -#191771 = CIRCLE('',#191772,0.2); -#191772 = AXIS2_PLACEMENT_3D('',#191773,#191774,#191775); -#191773 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); -#191774 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191775 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191776 = PCURVE('',#186108,#191777); -#191777 = DEFINITIONAL_REPRESENTATION('',(#191778),#191782); -#191778 = CIRCLE('',#191779,0.2); -#191779 = AXIS2_PLACEMENT_2D('',#191780,#191781); -#191780 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); -#191781 = DIRECTION('',(-1.,0.E+000)); -#191782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191783 = PCURVE('',#191449,#191784); -#191784 = DEFINITIONAL_REPRESENTATION('',(#191785),#191788); -#191785 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191786,#191787), +#194150 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#194151 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#194152 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194153 = ADVANCED_FACE('',(#194154),#188500,.T.); +#194154 = FACE_BOUND('',#194155,.T.); +#194155 = EDGE_LOOP('',(#194156,#194157,#194158,#194181,#194204,#194231, + #194254,#194277,#194300,#194323,#194346,#194373)); +#194156 = ORIENTED_EDGE('',*,*,#188484,.F.); +#194157 = ORIENTED_EDGE('',*,*,#193852,.T.); +#194158 = ORIENTED_EDGE('',*,*,#194159,.T.); +#194159 = EDGE_CURVE('',#193826,#194160,#194162,.T.); +#194160 = VERTEX_POINT('',#194161); +#194161 = CARTESIAN_POINT('',(0.2,-0.854004213739,0.571910405702)); +#194162 = SURFACE_CURVE('',#194163,(#194168,#194175),.PCURVE_S1.); +#194163 = CIRCLE('',#194164,0.2); +#194164 = AXIS2_PLACEMENT_3D('',#194165,#194166,#194167); +#194165 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); +#194166 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194167 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194168 = PCURVE('',#188500,#194169); +#194169 = DEFINITIONAL_REPRESENTATION('',(#194170),#194174); +#194170 = CIRCLE('',#194171,0.2); +#194171 = AXIS2_PLACEMENT_2D('',#194172,#194173); +#194172 = CARTESIAN_POINT('',(-1.110223024625E-016,0.E+000)); +#194173 = DIRECTION('',(-1.,0.E+000)); +#194174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194175 = PCURVE('',#193841,#194176); +#194176 = DEFINITIONAL_REPRESENTATION('',(#194177),#194180); +#194177 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194178,#194179), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#191786 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#191787 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#191788 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191789 = ORIENTED_EDGE('',*,*,#191790,.T.); -#191790 = EDGE_CURVE('',#191768,#191791,#191793,.T.); -#191791 = VERTEX_POINT('',#191792); -#191792 = CARTESIAN_POINT('',(0.2,-0.895598186972,0.194522398574)); -#191793 = SURFACE_CURVE('',#191794,(#191798,#191805),.PCURVE_S1.); -#191794 = LINE('',#191795,#191796); -#191795 = CARTESIAN_POINT('',(0.2,-0.895598186972,0.194522398574)); -#191796 = VECTOR('',#191797,1.); -#191797 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); -#191798 = PCURVE('',#186108,#191799); -#191799 = DEFINITIONAL_REPRESENTATION('',(#191800),#191804); -#191800 = LINE('',#191801,#191802); -#191801 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); -#191802 = VECTOR('',#191803,1.); -#191803 = DIRECTION('',(0.993981062721,-0.109552028512)); -#191804 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191805 = PCURVE('',#191729,#191806); -#191806 = DEFINITIONAL_REPRESENTATION('',(#191807),#191811); -#191807 = LINE('',#191808,#191809); -#191808 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191809 = VECTOR('',#191810,1.); -#191810 = DIRECTION('',(1.,0.E+000)); -#191811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191812 = ORIENTED_EDGE('',*,*,#191813,.T.); -#191813 = EDGE_CURVE('',#191791,#191814,#191816,.T.); -#191814 = VERTEX_POINT('',#191815); -#191815 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.15)); -#191816 = SURFACE_CURVE('',#191817,(#191822,#191833),.PCURVE_S1.); -#191817 = CIRCLE('',#191818,5.E-002); -#191818 = AXIS2_PLACEMENT_3D('',#191819,#191820,#191821); -#191819 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.2)); -#191820 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191821 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191822 = PCURVE('',#186108,#191823); -#191823 = DEFINITIONAL_REPRESENTATION('',(#191824),#191832); -#191824 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191825,#191826,#191827, - #191828,#191829,#191830,#191831),.UNSPECIFIED.,.F.,.F.) +#194178 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#194179 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#194180 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194181 = ORIENTED_EDGE('',*,*,#194182,.T.); +#194182 = EDGE_CURVE('',#194160,#194183,#194185,.T.); +#194183 = VERTEX_POINT('',#194184); +#194184 = CARTESIAN_POINT('',(0.2,-0.895598186972,0.194522398574)); +#194185 = SURFACE_CURVE('',#194186,(#194190,#194197),.PCURVE_S1.); +#194186 = LINE('',#194187,#194188); +#194187 = CARTESIAN_POINT('',(0.2,-0.895598186972,0.194522398574)); +#194188 = VECTOR('',#194189,1.); +#194189 = DIRECTION('',(0.E+000,-0.109552028512,-0.993981062721)); +#194190 = PCURVE('',#188500,#194191); +#194191 = DEFINITIONAL_REPRESENTATION('',(#194192),#194196); +#194192 = LINE('',#194193,#194194); +#194193 = CARTESIAN_POINT('',(0.355477601426,-0.240390185778)); +#194194 = VECTOR('',#194195,1.); +#194195 = DIRECTION('',(0.993981062721,-0.109552028512)); +#194196 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194197 = PCURVE('',#194121,#194198); +#194198 = DEFINITIONAL_REPRESENTATION('',(#194199),#194203); +#194199 = LINE('',#194200,#194201); +#194200 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194201 = VECTOR('',#194202,1.); +#194202 = DIRECTION('',(1.,0.E+000)); +#194203 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194204 = ORIENTED_EDGE('',*,*,#194205,.T.); +#194205 = EDGE_CURVE('',#194183,#194206,#194208,.T.); +#194206 = VERTEX_POINT('',#194207); +#194207 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.15)); +#194208 = SURFACE_CURVE('',#194209,(#194214,#194225),.PCURVE_S1.); +#194209 = CIRCLE('',#194210,5.E-002); +#194210 = AXIS2_PLACEMENT_3D('',#194211,#194212,#194213); +#194211 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.2)); +#194212 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194213 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194214 = PCURVE('',#188500,#194215); +#194215 = DEFINITIONAL_REPRESENTATION('',(#194216),#194224); +#194216 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#194217,#194218,#194219, + #194220,#194221,#194222,#194223),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#191825 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#191826 = CARTESIAN_POINT('',(0.4,-0.376691779292)); -#191827 = CARTESIAN_POINT('',(0.325,-0.333390509103)); -#191828 = CARTESIAN_POINT('',(0.25,-0.290089238914)); -#191829 = CARTESIAN_POINT('',(0.325,-0.246787968724)); -#191830 = CARTESIAN_POINT('',(0.4,-0.203486698535)); -#191831 = CARTESIAN_POINT('',(0.4,-0.290089238914)); -#191832 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191833 = PCURVE('',#191702,#191834); -#191834 = DEFINITIONAL_REPRESENTATION('',(#191835),#191838); -#191835 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191836,#191837), +#194217 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#194218 = CARTESIAN_POINT('',(0.4,-0.376691779292)); +#194219 = CARTESIAN_POINT('',(0.325,-0.333390509103)); +#194220 = CARTESIAN_POINT('',(0.25,-0.290089238914)); +#194221 = CARTESIAN_POINT('',(0.325,-0.246787968724)); +#194222 = CARTESIAN_POINT('',(0.4,-0.203486698535)); +#194223 = CARTESIAN_POINT('',(0.4,-0.290089238914)); +#194224 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194225 = PCURVE('',#194094,#194226); +#194226 = DEFINITIONAL_REPRESENTATION('',(#194227),#194230); +#194227 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194228,#194229), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#191836 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#191837 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191838 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191839 = ORIENTED_EDGE('',*,*,#191840,.T.); -#191840 = EDGE_CURVE('',#191814,#191841,#191843,.T.); -#191841 = VERTEX_POINT('',#191842); -#191842 = CARTESIAN_POINT('',(0.2,-1.17,0.15)); -#191843 = SURFACE_CURVE('',#191844,(#191848,#191855),.PCURVE_S1.); -#191844 = LINE('',#191845,#191846); -#191845 = CARTESIAN_POINT('',(0.2,-1.17,0.15)); -#191846 = VECTOR('',#191847,1.); -#191847 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#191848 = PCURVE('',#186108,#191849); -#191849 = DEFINITIONAL_REPRESENTATION('',(#191850),#191854); -#191850 = LINE('',#191851,#191852); -#191851 = CARTESIAN_POINT('',(0.4,-0.514791998806)); -#191852 = VECTOR('',#191853,1.); -#191853 = DIRECTION('',(0.E+000,-1.)); -#191854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191855 = PCURVE('',#191669,#191856); -#191856 = DEFINITIONAL_REPRESENTATION('',(#191857),#191861); -#191857 = LINE('',#191858,#191859); -#191858 = CARTESIAN_POINT('',(0.4,0.E+000)); -#191859 = VECTOR('',#191860,1.); -#191860 = DIRECTION('',(0.E+000,-1.)); -#191861 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191862 = ORIENTED_EDGE('',*,*,#191863,.T.); -#191863 = EDGE_CURVE('',#191841,#191864,#191866,.T.); -#191864 = VERTEX_POINT('',#191865); -#191865 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); -#191866 = SURFACE_CURVE('',#191867,(#191871,#191878),.PCURVE_S1.); -#191867 = LINE('',#191868,#191869); -#191868 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); -#191869 = VECTOR('',#191870,1.); -#191870 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191871 = PCURVE('',#186108,#191872); -#191872 = DEFINITIONAL_REPRESENTATION('',(#191873),#191877); -#191873 = LINE('',#191874,#191875); -#191874 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191875 = VECTOR('',#191876,1.); -#191876 = DIRECTION('',(1.,0.E+000)); -#191877 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191878 = PCURVE('',#191641,#191879); -#191879 = DEFINITIONAL_REPRESENTATION('',(#191880),#191884); -#191880 = LINE('',#191881,#191882); -#191881 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191882 = VECTOR('',#191883,1.); -#191883 = DIRECTION('',(1.,0.E+000)); -#191884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191885 = ORIENTED_EDGE('',*,*,#191886,.T.); -#191886 = EDGE_CURVE('',#191864,#191887,#191889,.T.); -#191887 = VERTEX_POINT('',#191888); -#191888 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.E+000)); -#191889 = SURFACE_CURVE('',#191890,(#191894,#191901),.PCURVE_S1.); -#191890 = LINE('',#191891,#191892); -#191891 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); -#191892 = VECTOR('',#191893,1.); -#191893 = DIRECTION('',(0.E+000,1.,0.E+000)); -#191894 = PCURVE('',#186108,#191895); -#191895 = DEFINITIONAL_REPRESENTATION('',(#191896),#191900); -#191896 = LINE('',#191897,#191898); -#191897 = CARTESIAN_POINT('',(0.55,-0.514791998806)); -#191898 = VECTOR('',#191899,1.); -#191899 = DIRECTION('',(0.E+000,1.)); -#191900 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191901 = PCURVE('',#191613,#191902); -#191902 = DEFINITIONAL_REPRESENTATION('',(#191903),#191907); -#191903 = LINE('',#191904,#191905); -#191904 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#191905 = VECTOR('',#191906,1.); -#191906 = DIRECTION('',(0.E+000,1.)); -#191907 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191908 = ORIENTED_EDGE('',*,*,#191909,.T.); -#191909 = EDGE_CURVE('',#191887,#191910,#191912,.T.); -#191910 = VERTEX_POINT('',#191911); -#191911 = CARTESIAN_POINT('',(0.2,-0.746501027564,0.178089594298)); -#191912 = SURFACE_CURVE('',#191913,(#191918,#191925),.PCURVE_S1.); -#191913 = CIRCLE('',#191914,0.2); -#191914 = AXIS2_PLACEMENT_3D('',#191915,#191916,#191917); -#191915 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.2)); -#191916 = DIRECTION('',(1.,0.E+000,0.E+000)); -#191917 = DIRECTION('',(0.E+000,0.E+000,1.)); -#191918 = PCURVE('',#186108,#191919); -#191919 = DEFINITIONAL_REPRESENTATION('',(#191920),#191924); -#191920 = CIRCLE('',#191921,0.2); -#191921 = AXIS2_PLACEMENT_2D('',#191922,#191923); -#191922 = CARTESIAN_POINT('',(0.35,-0.290089238914)); -#191923 = DIRECTION('',(-1.,0.E+000)); -#191924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191925 = PCURVE('',#191586,#191926); -#191926 = DEFINITIONAL_REPRESENTATION('',(#191927),#191930); -#191927 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191928,#191929), +#194228 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#194229 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194230 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194231 = ORIENTED_EDGE('',*,*,#194232,.T.); +#194232 = EDGE_CURVE('',#194206,#194233,#194235,.T.); +#194233 = VERTEX_POINT('',#194234); +#194234 = CARTESIAN_POINT('',(0.2,-1.17,0.15)); +#194235 = SURFACE_CURVE('',#194236,(#194240,#194247),.PCURVE_S1.); +#194236 = LINE('',#194237,#194238); +#194237 = CARTESIAN_POINT('',(0.2,-1.17,0.15)); +#194238 = VECTOR('',#194239,1.); +#194239 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194240 = PCURVE('',#188500,#194241); +#194241 = DEFINITIONAL_REPRESENTATION('',(#194242),#194246); +#194242 = LINE('',#194243,#194244); +#194243 = CARTESIAN_POINT('',(0.4,-0.514791998806)); +#194244 = VECTOR('',#194245,1.); +#194245 = DIRECTION('',(0.E+000,-1.)); +#194246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194247 = PCURVE('',#194061,#194248); +#194248 = DEFINITIONAL_REPRESENTATION('',(#194249),#194253); +#194249 = LINE('',#194250,#194251); +#194250 = CARTESIAN_POINT('',(0.4,0.E+000)); +#194251 = VECTOR('',#194252,1.); +#194252 = DIRECTION('',(0.E+000,-1.)); +#194253 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194254 = ORIENTED_EDGE('',*,*,#194255,.T.); +#194255 = EDGE_CURVE('',#194233,#194256,#194258,.T.); +#194256 = VERTEX_POINT('',#194257); +#194257 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); +#194258 = SURFACE_CURVE('',#194259,(#194263,#194270),.PCURVE_S1.); +#194259 = LINE('',#194260,#194261); +#194260 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); +#194261 = VECTOR('',#194262,1.); +#194262 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194263 = PCURVE('',#188500,#194264); +#194264 = DEFINITIONAL_REPRESENTATION('',(#194265),#194269); +#194265 = LINE('',#194266,#194267); +#194266 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#194267 = VECTOR('',#194268,1.); +#194268 = DIRECTION('',(1.,0.E+000)); +#194269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194270 = PCURVE('',#194033,#194271); +#194271 = DEFINITIONAL_REPRESENTATION('',(#194272),#194276); +#194272 = LINE('',#194273,#194274); +#194273 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194274 = VECTOR('',#194275,1.); +#194275 = DIRECTION('',(1.,0.E+000)); +#194276 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194277 = ORIENTED_EDGE('',*,*,#194278,.T.); +#194278 = EDGE_CURVE('',#194256,#194279,#194281,.T.); +#194279 = VERTEX_POINT('',#194280); +#194280 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.E+000)); +#194281 = SURFACE_CURVE('',#194282,(#194286,#194293),.PCURVE_S1.); +#194282 = LINE('',#194283,#194284); +#194283 = CARTESIAN_POINT('',(0.2,-1.17,0.E+000)); +#194284 = VECTOR('',#194285,1.); +#194285 = DIRECTION('',(0.E+000,1.,0.E+000)); +#194286 = PCURVE('',#188500,#194287); +#194287 = DEFINITIONAL_REPRESENTATION('',(#194288),#194292); +#194288 = LINE('',#194289,#194290); +#194289 = CARTESIAN_POINT('',(0.55,-0.514791998806)); +#194290 = VECTOR('',#194291,1.); +#194291 = DIRECTION('',(0.E+000,1.)); +#194292 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194293 = PCURVE('',#194005,#194294); +#194294 = DEFINITIONAL_REPRESENTATION('',(#194295),#194299); +#194295 = LINE('',#194296,#194297); +#194296 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#194297 = VECTOR('',#194298,1.); +#194298 = DIRECTION('',(0.E+000,1.)); +#194299 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194300 = ORIENTED_EDGE('',*,*,#194301,.T.); +#194301 = EDGE_CURVE('',#194279,#194302,#194304,.T.); +#194302 = VERTEX_POINT('',#194303); +#194303 = CARTESIAN_POINT('',(0.2,-0.746501027564,0.178089594298)); +#194304 = SURFACE_CURVE('',#194305,(#194310,#194317),.PCURVE_S1.); +#194305 = CIRCLE('',#194306,0.2); +#194306 = AXIS2_PLACEMENT_3D('',#194307,#194308,#194309); +#194307 = CARTESIAN_POINT('',(0.2,-0.945297240108,0.2)); +#194308 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194309 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194310 = PCURVE('',#188500,#194311); +#194311 = DEFINITIONAL_REPRESENTATION('',(#194312),#194316); +#194312 = CIRCLE('',#194313,0.2); +#194313 = AXIS2_PLACEMENT_2D('',#194314,#194315); +#194314 = CARTESIAN_POINT('',(0.35,-0.290089238914)); +#194315 = DIRECTION('',(-1.,0.E+000)); +#194316 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194317 = PCURVE('',#193978,#194318); +#194318 = DEFINITIONAL_REPRESENTATION('',(#194319),#194322); +#194319 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194320,#194321), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#191928 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191929 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#191930 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191931 = ORIENTED_EDGE('',*,*,#191932,.T.); -#191932 = EDGE_CURVE('',#191910,#191933,#191935,.T.); -#191933 = VERTEX_POINT('',#191934); -#191934 = CARTESIAN_POINT('',(0.2,-0.70490705433,0.555477601426)); -#191935 = SURFACE_CURVE('',#191936,(#191940,#191947),.PCURVE_S1.); -#191936 = LINE('',#191937,#191938); -#191937 = CARTESIAN_POINT('',(0.2,-0.70490705433,0.555477601426)); -#191938 = VECTOR('',#191939,1.); -#191939 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); -#191940 = PCURVE('',#186108,#191941); -#191941 = DEFINITIONAL_REPRESENTATION('',(#191942),#191946); -#191942 = LINE('',#191943,#191944); -#191943 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) - ); -#191944 = VECTOR('',#191945,1.); -#191945 = DIRECTION('',(-0.993981062721,0.109552028512)); -#191946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191947 = PCURVE('',#191557,#191948); -#191948 = DEFINITIONAL_REPRESENTATION('',(#191949),#191953); -#191949 = LINE('',#191950,#191951); -#191950 = CARTESIAN_POINT('',(0.E+000,0.4)); -#191951 = VECTOR('',#191952,1.); -#191952 = DIRECTION('',(1.,0.E+000)); -#191953 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191954 = ORIENTED_EDGE('',*,*,#191955,.T.); -#191955 = EDGE_CURVE('',#191933,#191956,#191958,.T.); -#191956 = VERTEX_POINT('',#191957); -#191957 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.6)); -#191958 = SURFACE_CURVE('',#191959,(#191964,#191975),.PCURVE_S1.); -#191959 = CIRCLE('',#191960,5.E-002); -#191960 = AXIS2_PLACEMENT_3D('',#191961,#191962,#191963); -#191961 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); -#191962 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#191963 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#191964 = PCURVE('',#186108,#191965); -#191965 = DEFINITIONAL_REPRESENTATION('',(#191966),#191974); -#191966 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#191967,#191968,#191969, - #191970,#191971,#191972,#191973),.UNSPECIFIED.,.F.,.F.) +#194320 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194321 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#194322 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194323 = ORIENTED_EDGE('',*,*,#194324,.T.); +#194324 = EDGE_CURVE('',#194302,#194325,#194327,.T.); +#194325 = VERTEX_POINT('',#194326); +#194326 = CARTESIAN_POINT('',(0.2,-0.70490705433,0.555477601426)); +#194327 = SURFACE_CURVE('',#194328,(#194332,#194339),.PCURVE_S1.); +#194328 = LINE('',#194329,#194330); +#194329 = CARTESIAN_POINT('',(0.2,-0.70490705433,0.555477601426)); +#194330 = VECTOR('',#194331,1.); +#194331 = DIRECTION('',(0.E+000,0.109552028512,0.993981062721)); +#194332 = PCURVE('',#188500,#194333); +#194333 = DEFINITIONAL_REPRESENTATION('',(#194334),#194338); +#194334 = LINE('',#194335,#194336); +#194335 = CARTESIAN_POINT('',(-5.477601425623E-003,-4.969905313607E-002) + ); +#194336 = VECTOR('',#194337,1.); +#194337 = DIRECTION('',(-0.993981062721,0.109552028512)); +#194338 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194339 = PCURVE('',#193949,#194340); +#194340 = DEFINITIONAL_REPRESENTATION('',(#194341),#194345); +#194341 = LINE('',#194342,#194343); +#194342 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194343 = VECTOR('',#194344,1.); +#194344 = DIRECTION('',(1.,0.E+000)); +#194345 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194346 = ORIENTED_EDGE('',*,*,#194347,.T.); +#194347 = EDGE_CURVE('',#194325,#194348,#194350,.T.); +#194348 = VERTEX_POINT('',#194349); +#194349 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.6)); +#194350 = SURFACE_CURVE('',#194351,(#194356,#194367),.PCURVE_S1.); +#194351 = CIRCLE('',#194352,5.E-002); +#194352 = AXIS2_PLACEMENT_3D('',#194353,#194354,#194355); +#194353 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.55)); +#194354 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194355 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194356 = PCURVE('',#188500,#194357); +#194357 = DEFINITIONAL_REPRESENTATION('',(#194358),#194366); +#194358 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#194359,#194360,#194361, + #194362,#194363,#194364,#194365),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#191967 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191968 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); -#191969 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); -#191970 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); -#191971 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); -#191972 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); -#191973 = CARTESIAN_POINT('',(5.E-002,0.E+000)); -#191974 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191975 = PCURVE('',#191530,#191976); -#191976 = DEFINITIONAL_REPRESENTATION('',(#191977),#191980); -#191977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#191978,#191979), +#194359 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#194360 = CARTESIAN_POINT('',(5.E-002,-8.660254037844E-002)); +#194361 = CARTESIAN_POINT('',(-2.5E-002,-4.330127018922E-002)); +#194362 = CARTESIAN_POINT('',(-0.1,-3.445052403073E-017)); +#194363 = CARTESIAN_POINT('',(-2.5E-002,4.330127018922E-002)); +#194364 = CARTESIAN_POINT('',(5.E-002,8.660254037844E-002)); +#194365 = CARTESIAN_POINT('',(5.E-002,0.E+000)); +#194366 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194367 = PCURVE('',#193922,#194368); +#194368 = DEFINITIONAL_REPRESENTATION('',(#194369),#194372); +#194369 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194370,#194371), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#191978 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#191979 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#191980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191981 = ORIENTED_EDGE('',*,*,#191982,.T.); -#191982 = EDGE_CURVE('',#191956,#186093,#191983,.T.); -#191983 = SURFACE_CURVE('',#191984,(#191988,#191995),.PCURVE_S1.); -#191984 = LINE('',#191985,#191986); -#191985 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.6)); -#191986 = VECTOR('',#191987,1.); -#191987 = DIRECTION('',(0.E+000,1.,0.E+000)); -#191988 = PCURVE('',#186108,#191989); -#191989 = DEFINITIONAL_REPRESENTATION('',(#191990),#191994); -#191990 = LINE('',#191991,#191992); -#191991 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); -#191992 = VECTOR('',#191993,1.); -#191993 = DIRECTION('',(0.E+000,1.)); -#191994 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#191995 = PCURVE('',#186570,#191996); -#191996 = DEFINITIONAL_REPRESENTATION('',(#191997),#192001); -#191997 = LINE('',#191998,#191999); -#191998 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#191999 = VECTOR('',#192000,1.); -#192000 = DIRECTION('',(0.E+000,1.)); -#192001 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192002 = ADVANCED_FACE('',(#192003),#191530,.F.); -#192003 = FACE_BOUND('',#192004,.F.); -#192004 = EDGE_LOOP('',(#192005,#192025,#192026,#192046)); -#192005 = ORIENTED_EDGE('',*,*,#192006,.F.); -#192006 = EDGE_CURVE('',#191487,#191956,#192007,.T.); -#192007 = SURFACE_CURVE('',#192008,(#192012,#192018),.PCURVE_S1.); -#192008 = LINE('',#192009,#192010); -#192009 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); -#192010 = VECTOR('',#192011,1.); -#192011 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192012 = PCURVE('',#191530,#192013); -#192013 = DEFINITIONAL_REPRESENTATION('',(#192014),#192017); -#192014 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192015,#192016), +#194370 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#194371 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#194372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194373 = ORIENTED_EDGE('',*,*,#194374,.T.); +#194374 = EDGE_CURVE('',#194348,#188485,#194375,.T.); +#194375 = SURFACE_CURVE('',#194376,(#194380,#194387),.PCURVE_S1.); +#194376 = LINE('',#194377,#194378); +#194377 = CARTESIAN_POINT('',(0.2,-0.655208001194,0.6)); +#194378 = VECTOR('',#194379,1.); +#194379 = DIRECTION('',(0.E+000,1.,0.E+000)); +#194380 = PCURVE('',#188500,#194381); +#194381 = DEFINITIONAL_REPRESENTATION('',(#194382),#194386); +#194382 = LINE('',#194383,#194384); +#194383 = CARTESIAN_POINT('',(-5.E-002,3.330669073875E-016)); +#194384 = VECTOR('',#194385,1.); +#194385 = DIRECTION('',(0.E+000,1.)); +#194386 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194387 = PCURVE('',#188962,#194388); +#194388 = DEFINITIONAL_REPRESENTATION('',(#194389),#194393); +#194389 = LINE('',#194390,#194391); +#194390 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#194391 = VECTOR('',#194392,1.); +#194392 = DIRECTION('',(0.E+000,1.)); +#194393 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194394 = ADVANCED_FACE('',(#194395),#193922,.F.); +#194395 = FACE_BOUND('',#194396,.F.); +#194396 = EDGE_LOOP('',(#194397,#194417,#194418,#194438)); +#194397 = ORIENTED_EDGE('',*,*,#194398,.F.); +#194398 = EDGE_CURVE('',#193879,#194348,#194399,.T.); +#194399 = SURFACE_CURVE('',#194400,(#194404,#194410),.PCURVE_S1.); +#194400 = LINE('',#194401,#194402); +#194401 = CARTESIAN_POINT('',(-0.2,-0.655208001194,0.6)); +#194402 = VECTOR('',#194403,1.); +#194403 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194404 = PCURVE('',#193922,#194405); +#194405 = DEFINITIONAL_REPRESENTATION('',(#194406),#194409); +#194406 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194407,#194408), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192015 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#192016 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#192017 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192018 = PCURVE('',#186570,#192019); -#192019 = DEFINITIONAL_REPRESENTATION('',(#192020),#192024); -#192020 = LINE('',#192021,#192022); -#192021 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192022 = VECTOR('',#192023,1.); -#192023 = DIRECTION('',(-1.,0.E+000)); -#192024 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192025 = ORIENTED_EDGE('',*,*,#191509,.F.); -#192026 = ORIENTED_EDGE('',*,*,#192027,.T.); -#192027 = EDGE_CURVE('',#191510,#191933,#192028,.T.); -#192028 = SURFACE_CURVE('',#192029,(#192033,#192039),.PCURVE_S1.); -#192029 = LINE('',#192030,#192031); -#192030 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); -#192031 = VECTOR('',#192032,1.); -#192032 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192033 = PCURVE('',#191530,#192034); -#192034 = DEFINITIONAL_REPRESENTATION('',(#192035),#192038); -#192035 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192036,#192037), +#194407 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#194408 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#194409 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194410 = PCURVE('',#188962,#194411); +#194411 = DEFINITIONAL_REPRESENTATION('',(#194412),#194416); +#194412 = LINE('',#194413,#194414); +#194413 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194414 = VECTOR('',#194415,1.); +#194415 = DIRECTION('',(-1.,0.E+000)); +#194416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194417 = ORIENTED_EDGE('',*,*,#193901,.F.); +#194418 = ORIENTED_EDGE('',*,*,#194419,.T.); +#194419 = EDGE_CURVE('',#193902,#194325,#194420,.T.); +#194420 = SURFACE_CURVE('',#194421,(#194425,#194431),.PCURVE_S1.); +#194421 = LINE('',#194422,#194423); +#194422 = CARTESIAN_POINT('',(-0.2,-0.70490705433,0.555477601426)); +#194423 = VECTOR('',#194424,1.); +#194424 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194425 = PCURVE('',#193922,#194426); +#194426 = DEFINITIONAL_REPRESENTATION('',(#194427),#194430); +#194427 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194428,#194429), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192036 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#192037 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#192038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192039 = PCURVE('',#191557,#192040); -#192040 = DEFINITIONAL_REPRESENTATION('',(#192041),#192045); -#192041 = LINE('',#192042,#192043); -#192042 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192043 = VECTOR('',#192044,1.); -#192044 = DIRECTION('',(0.E+000,1.)); -#192045 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192046 = ORIENTED_EDGE('',*,*,#191955,.T.); -#192047 = ADVANCED_FACE('',(#192048),#191557,.T.); -#192048 = FACE_BOUND('',#192049,.T.); -#192049 = EDGE_LOOP('',(#192050,#192051,#192052,#192072)); -#192050 = ORIENTED_EDGE('',*,*,#192027,.T.); -#192051 = ORIENTED_EDGE('',*,*,#191932,.F.); -#192052 = ORIENTED_EDGE('',*,*,#192053,.F.); -#192053 = EDGE_CURVE('',#191542,#191910,#192054,.T.); -#192054 = SURFACE_CURVE('',#192055,(#192059,#192066),.PCURVE_S1.); -#192055 = LINE('',#192056,#192057); -#192056 = CARTESIAN_POINT('',(-0.2,-0.746501027564,0.178089594298)); -#192057 = VECTOR('',#192058,1.); -#192058 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192059 = PCURVE('',#191557,#192060); -#192060 = DEFINITIONAL_REPRESENTATION('',(#192061),#192065); -#192061 = LINE('',#192062,#192063); -#192062 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#192063 = VECTOR('',#192064,1.); -#192064 = DIRECTION('',(0.E+000,1.)); -#192065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192066 = PCURVE('',#191586,#192067); -#192067 = DEFINITIONAL_REPRESENTATION('',(#192068),#192071); -#192068 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192069,#192070), +#194428 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#194429 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#194430 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194431 = PCURVE('',#193949,#194432); +#194432 = DEFINITIONAL_REPRESENTATION('',(#194433),#194437); +#194433 = LINE('',#194434,#194435); +#194434 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194435 = VECTOR('',#194436,1.); +#194436 = DIRECTION('',(0.E+000,1.)); +#194437 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194438 = ORIENTED_EDGE('',*,*,#194347,.T.); +#194439 = ADVANCED_FACE('',(#194440),#193949,.T.); +#194440 = FACE_BOUND('',#194441,.T.); +#194441 = EDGE_LOOP('',(#194442,#194443,#194444,#194464)); +#194442 = ORIENTED_EDGE('',*,*,#194419,.T.); +#194443 = ORIENTED_EDGE('',*,*,#194324,.F.); +#194444 = ORIENTED_EDGE('',*,*,#194445,.F.); +#194445 = EDGE_CURVE('',#193934,#194302,#194446,.T.); +#194446 = SURFACE_CURVE('',#194447,(#194451,#194458),.PCURVE_S1.); +#194447 = LINE('',#194448,#194449); +#194448 = CARTESIAN_POINT('',(-0.2,-0.746501027564,0.178089594298)); +#194449 = VECTOR('',#194450,1.); +#194450 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194451 = PCURVE('',#193949,#194452); +#194452 = DEFINITIONAL_REPRESENTATION('',(#194453),#194457); +#194453 = LINE('',#194454,#194455); +#194454 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#194455 = VECTOR('',#194456,1.); +#194456 = DIRECTION('',(0.E+000,1.)); +#194457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194458 = PCURVE('',#193978,#194459); +#194459 = DEFINITIONAL_REPRESENTATION('',(#194460),#194463); +#194460 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194461,#194462), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192069 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#192070 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#192071 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192072 = ORIENTED_EDGE('',*,*,#191541,.T.); -#192073 = ADVANCED_FACE('',(#192074),#191586,.T.); -#192074 = FACE_BOUND('',#192075,.T.); -#192075 = EDGE_LOOP('',(#192076,#192077,#192078,#192121)); -#192076 = ORIENTED_EDGE('',*,*,#192053,.T.); -#192077 = ORIENTED_EDGE('',*,*,#191909,.F.); -#192078 = ORIENTED_EDGE('',*,*,#192079,.F.); -#192079 = EDGE_CURVE('',#191570,#191887,#192080,.T.); -#192080 = SURFACE_CURVE('',#192081,(#192085,#192114),.PCURVE_S1.); -#192081 = LINE('',#192082,#192083); -#192082 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.E+000)); -#192083 = VECTOR('',#192084,1.); -#192084 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192085 = PCURVE('',#191586,#192086); -#192086 = DEFINITIONAL_REPRESENTATION('',(#192087),#192113); -#192087 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#192088,#192089,#192090, - #192091,#192092,#192093,#192094,#192095,#192096,#192097,#192098, - #192099,#192100,#192101,#192102,#192103,#192104,#192105,#192106, - #192107,#192108,#192109,#192110,#192111,#192112),.UNSPECIFIED.,.F., +#194461 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#194462 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#194463 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194464 = ORIENTED_EDGE('',*,*,#193933,.T.); +#194465 = ADVANCED_FACE('',(#194466),#193978,.T.); +#194466 = FACE_BOUND('',#194467,.T.); +#194467 = EDGE_LOOP('',(#194468,#194469,#194470,#194513)); +#194468 = ORIENTED_EDGE('',*,*,#194445,.T.); +#194469 = ORIENTED_EDGE('',*,*,#194301,.F.); +#194470 = ORIENTED_EDGE('',*,*,#194471,.F.); +#194471 = EDGE_CURVE('',#193962,#194279,#194472,.T.); +#194472 = SURFACE_CURVE('',#194473,(#194477,#194506),.PCURVE_S1.); +#194473 = LINE('',#194474,#194475); +#194474 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.E+000)); +#194475 = VECTOR('',#194476,1.); +#194476 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194477 = PCURVE('',#193978,#194478); +#194478 = DEFINITIONAL_REPRESENTATION('',(#194479),#194505); +#194479 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194480,#194481,#194482, + #194483,#194484,#194485,#194486,#194487,#194488,#194489,#194490, + #194491,#194492,#194493,#194494,#194495,#194496,#194497,#194498, + #194499,#194500,#194501,#194502,#194503,#194504),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -238564,139 +241566,139 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#192088 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192089 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) - ); -#192090 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) - ); -#192091 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#192092 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) - ); -#192093 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) - ); -#192094 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) - ); -#192095 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); -#192096 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); -#192097 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); -#192098 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); -#192099 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); -#192100 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); -#192101 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); -#192102 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); -#192103 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); -#192104 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); -#192105 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); -#192106 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); -#192107 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); -#192108 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); -#192109 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); -#192110 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); -#192111 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); -#192112 = CARTESIAN_POINT('',(0.E+000,0.4)); -#192113 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192114 = PCURVE('',#191613,#192115); -#192115 = DEFINITIONAL_REPRESENTATION('',(#192116),#192120); -#192116 = LINE('',#192117,#192118); -#192117 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#192118 = VECTOR('',#192119,1.); -#192119 = DIRECTION('',(-1.,0.E+000)); -#192120 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192121 = ORIENTED_EDGE('',*,*,#191569,.T.); -#192122 = ADVANCED_FACE('',(#192123),#191613,.T.); -#192123 = FACE_BOUND('',#192124,.T.); -#192124 = EDGE_LOOP('',(#192125,#192126,#192127,#192148)); -#192125 = ORIENTED_EDGE('',*,*,#192079,.T.); -#192126 = ORIENTED_EDGE('',*,*,#191886,.F.); -#192127 = ORIENTED_EDGE('',*,*,#192128,.F.); -#192128 = EDGE_CURVE('',#191598,#191864,#192129,.T.); -#192129 = SURFACE_CURVE('',#192130,(#192134,#192141),.PCURVE_S1.); -#192130 = LINE('',#192131,#192132); -#192131 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); -#192132 = VECTOR('',#192133,1.); -#192133 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192134 = PCURVE('',#191613,#192135); -#192135 = DEFINITIONAL_REPRESENTATION('',(#192136),#192140); -#192136 = LINE('',#192137,#192138); -#192137 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192138 = VECTOR('',#192139,1.); -#192139 = DIRECTION('',(-1.,0.E+000)); -#192140 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192141 = PCURVE('',#191641,#192142); -#192142 = DEFINITIONAL_REPRESENTATION('',(#192143),#192147); -#192143 = LINE('',#192144,#192145); -#192144 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192145 = VECTOR('',#192146,1.); -#192146 = DIRECTION('',(0.E+000,1.)); -#192147 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192148 = ORIENTED_EDGE('',*,*,#191597,.T.); -#192149 = ADVANCED_FACE('',(#192150),#191641,.T.); -#192150 = FACE_BOUND('',#192151,.T.); -#192151 = EDGE_LOOP('',(#192152,#192153,#192154,#192175)); -#192152 = ORIENTED_EDGE('',*,*,#192128,.T.); -#192153 = ORIENTED_EDGE('',*,*,#191863,.F.); -#192154 = ORIENTED_EDGE('',*,*,#192155,.F.); -#192155 = EDGE_CURVE('',#191626,#191841,#192156,.T.); -#192156 = SURFACE_CURVE('',#192157,(#192161,#192168),.PCURVE_S1.); -#192157 = LINE('',#192158,#192159); -#192158 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); -#192159 = VECTOR('',#192160,1.); -#192160 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192161 = PCURVE('',#191641,#192162); -#192162 = DEFINITIONAL_REPRESENTATION('',(#192163),#192167); -#192163 = LINE('',#192164,#192165); -#192164 = CARTESIAN_POINT('',(-0.15,0.E+000)); -#192165 = VECTOR('',#192166,1.); -#192166 = DIRECTION('',(0.E+000,1.)); -#192167 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192168 = PCURVE('',#191669,#192169); -#192169 = DEFINITIONAL_REPRESENTATION('',(#192170),#192174); -#192170 = LINE('',#192171,#192172); -#192171 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192172 = VECTOR('',#192173,1.); -#192173 = DIRECTION('',(1.,0.E+000)); -#192174 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192175 = ORIENTED_EDGE('',*,*,#191625,.T.); -#192176 = ADVANCED_FACE('',(#192177),#191669,.T.); -#192177 = FACE_BOUND('',#192178,.T.); -#192178 = EDGE_LOOP('',(#192179,#192180,#192181,#192224)); -#192179 = ORIENTED_EDGE('',*,*,#192155,.T.); -#192180 = ORIENTED_EDGE('',*,*,#191840,.F.); -#192181 = ORIENTED_EDGE('',*,*,#192182,.F.); -#192182 = EDGE_CURVE('',#191654,#191814,#192183,.T.); -#192183 = SURFACE_CURVE('',#192184,(#192188,#192195),.PCURVE_S1.); -#192184 = LINE('',#192185,#192186); -#192185 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.15)); -#192186 = VECTOR('',#192187,1.); -#192187 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192188 = PCURVE('',#191669,#192189); -#192189 = DEFINITIONAL_REPRESENTATION('',(#192190),#192194); -#192190 = LINE('',#192191,#192192); -#192191 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); -#192192 = VECTOR('',#192193,1.); -#192193 = DIRECTION('',(1.,0.E+000)); -#192194 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192195 = PCURVE('',#191702,#192196); -#192196 = DEFINITIONAL_REPRESENTATION('',(#192197),#192223); -#192197 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#192198,#192199,#192200, - #192201,#192202,#192203,#192204,#192205,#192206,#192207,#192208, - #192209,#192210,#192211,#192212,#192213,#192214,#192215,#192216, - #192217,#192218,#192219,#192220,#192221,#192222),.UNSPECIFIED.,.F., +#194480 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194481 = CARTESIAN_POINT('',(-3.552713678801E-015,6.060606060606E-003) + ); +#194482 = CARTESIAN_POINT('',(-8.881784197001E-015,1.818181818182E-002) + ); +#194483 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#194484 = CARTESIAN_POINT('',(-7.105427357601E-015,5.454545454545E-002) + ); +#194485 = CARTESIAN_POINT('',(-7.993605777301E-015,7.272727272727E-002) + ); +#194486 = CARTESIAN_POINT('',(-6.217248937901E-015,9.090909090909E-002) + ); +#194487 = CARTESIAN_POINT('',(-7.993605777301E-015,0.109090909091)); +#194488 = CARTESIAN_POINT('',(-7.105427357601E-015,0.127272727273)); +#194489 = CARTESIAN_POINT('',(-6.217248937901E-015,0.145454545455)); +#194490 = CARTESIAN_POINT('',(-7.105427357601E-015,0.163636363636)); +#194491 = CARTESIAN_POINT('',(-7.105427357601E-015,0.181818181818)); +#194492 = CARTESIAN_POINT('',(-7.105427357601E-015,0.2)); +#194493 = CARTESIAN_POINT('',(-6.217248937901E-015,0.218181818182)); +#194494 = CARTESIAN_POINT('',(-7.105427357601E-015,0.236363636364)); +#194495 = CARTESIAN_POINT('',(-6.217248937901E-015,0.254545454545)); +#194496 = CARTESIAN_POINT('',(-6.217248937901E-015,0.272727272727)); +#194497 = CARTESIAN_POINT('',(-6.217248937901E-015,0.290909090909)); +#194498 = CARTESIAN_POINT('',(-6.217248937901E-015,0.309090909091)); +#194499 = CARTESIAN_POINT('',(-6.217248937901E-015,0.327272727273)); +#194500 = CARTESIAN_POINT('',(-6.217248937901E-015,0.345454545455)); +#194501 = CARTESIAN_POINT('',(-7.105427357601E-015,0.363636363636)); +#194502 = CARTESIAN_POINT('',(-7.105427357601E-015,0.381818181818)); +#194503 = CARTESIAN_POINT('',(-4.440892098501E-015,0.393939393939)); +#194504 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194505 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194506 = PCURVE('',#194005,#194507); +#194507 = DEFINITIONAL_REPRESENTATION('',(#194508),#194512); +#194508 = LINE('',#194509,#194510); +#194509 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#194510 = VECTOR('',#194511,1.); +#194511 = DIRECTION('',(-1.,0.E+000)); +#194512 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194513 = ORIENTED_EDGE('',*,*,#193961,.T.); +#194514 = ADVANCED_FACE('',(#194515),#194005,.T.); +#194515 = FACE_BOUND('',#194516,.T.); +#194516 = EDGE_LOOP('',(#194517,#194518,#194519,#194540)); +#194517 = ORIENTED_EDGE('',*,*,#194471,.T.); +#194518 = ORIENTED_EDGE('',*,*,#194278,.F.); +#194519 = ORIENTED_EDGE('',*,*,#194520,.F.); +#194520 = EDGE_CURVE('',#193990,#194256,#194521,.T.); +#194521 = SURFACE_CURVE('',#194522,(#194526,#194533),.PCURVE_S1.); +#194522 = LINE('',#194523,#194524); +#194523 = CARTESIAN_POINT('',(-0.2,-1.17,0.E+000)); +#194524 = VECTOR('',#194525,1.); +#194525 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194526 = PCURVE('',#194005,#194527); +#194527 = DEFINITIONAL_REPRESENTATION('',(#194528),#194532); +#194528 = LINE('',#194529,#194530); +#194529 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194530 = VECTOR('',#194531,1.); +#194531 = DIRECTION('',(-1.,0.E+000)); +#194532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194533 = PCURVE('',#194033,#194534); +#194534 = DEFINITIONAL_REPRESENTATION('',(#194535),#194539); +#194535 = LINE('',#194536,#194537); +#194536 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194537 = VECTOR('',#194538,1.); +#194538 = DIRECTION('',(0.E+000,1.)); +#194539 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194540 = ORIENTED_EDGE('',*,*,#193989,.T.); +#194541 = ADVANCED_FACE('',(#194542),#194033,.T.); +#194542 = FACE_BOUND('',#194543,.T.); +#194543 = EDGE_LOOP('',(#194544,#194545,#194546,#194567)); +#194544 = ORIENTED_EDGE('',*,*,#194520,.T.); +#194545 = ORIENTED_EDGE('',*,*,#194255,.F.); +#194546 = ORIENTED_EDGE('',*,*,#194547,.F.); +#194547 = EDGE_CURVE('',#194018,#194233,#194548,.T.); +#194548 = SURFACE_CURVE('',#194549,(#194553,#194560),.PCURVE_S1.); +#194549 = LINE('',#194550,#194551); +#194550 = CARTESIAN_POINT('',(-0.2,-1.17,0.15)); +#194551 = VECTOR('',#194552,1.); +#194552 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194553 = PCURVE('',#194033,#194554); +#194554 = DEFINITIONAL_REPRESENTATION('',(#194555),#194559); +#194555 = LINE('',#194556,#194557); +#194556 = CARTESIAN_POINT('',(-0.15,0.E+000)); +#194557 = VECTOR('',#194558,1.); +#194558 = DIRECTION('',(0.E+000,1.)); +#194559 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194560 = PCURVE('',#194061,#194561); +#194561 = DEFINITIONAL_REPRESENTATION('',(#194562),#194566); +#194562 = LINE('',#194563,#194564); +#194563 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194564 = VECTOR('',#194565,1.); +#194565 = DIRECTION('',(1.,0.E+000)); +#194566 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194567 = ORIENTED_EDGE('',*,*,#194017,.T.); +#194568 = ADVANCED_FACE('',(#194569),#194061,.T.); +#194569 = FACE_BOUND('',#194570,.T.); +#194570 = EDGE_LOOP('',(#194571,#194572,#194573,#194616)); +#194571 = ORIENTED_EDGE('',*,*,#194547,.T.); +#194572 = ORIENTED_EDGE('',*,*,#194232,.F.); +#194573 = ORIENTED_EDGE('',*,*,#194574,.F.); +#194574 = EDGE_CURVE('',#194046,#194206,#194575,.T.); +#194575 = SURFACE_CURVE('',#194576,(#194580,#194587),.PCURVE_S1.); +#194576 = LINE('',#194577,#194578); +#194577 = CARTESIAN_POINT('',(-0.2,-0.945297240108,0.15)); +#194578 = VECTOR('',#194579,1.); +#194579 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194580 = PCURVE('',#194061,#194581); +#194581 = DEFINITIONAL_REPRESENTATION('',(#194582),#194586); +#194582 = LINE('',#194583,#194584); +#194583 = CARTESIAN_POINT('',(0.E+000,0.224702759892)); +#194584 = VECTOR('',#194585,1.); +#194585 = DIRECTION('',(1.,0.E+000)); +#194586 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194587 = PCURVE('',#194094,#194588); +#194588 = DEFINITIONAL_REPRESENTATION('',(#194589),#194615); +#194589 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194590,#194591,#194592, + #194593,#194594,#194595,#194596,#194597,#194598,#194599,#194600, + #194601,#194602,#194603,#194604,#194605,#194606,#194607,#194608, + #194609,#194610,#194611,#194612,#194613,#194614),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -238704,930 +241706,930 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#192198 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192199 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) - ); -#192200 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); -#192201 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) - ); -#192202 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) - ); -#192203 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) - ); -#192204 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) - ); -#192205 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); -#192206 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); -#192207 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); -#192208 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); -#192209 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); -#192210 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); -#192211 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); -#192212 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); -#192213 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); -#192214 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); -#192215 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); -#192216 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); -#192217 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); -#192218 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); -#192219 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); -#192220 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); -#192221 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); -#192222 = CARTESIAN_POINT('',(0.E+000,0.4)); -#192223 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192224 = ORIENTED_EDGE('',*,*,#191653,.T.); -#192225 = ADVANCED_FACE('',(#192226),#191702,.F.); -#192226 = FACE_BOUND('',#192227,.F.); -#192227 = EDGE_LOOP('',(#192228,#192229,#192230,#192250)); -#192228 = ORIENTED_EDGE('',*,*,#192182,.F.); -#192229 = ORIENTED_EDGE('',*,*,#191681,.F.); -#192230 = ORIENTED_EDGE('',*,*,#192231,.T.); -#192231 = EDGE_CURVE('',#191682,#191791,#192232,.T.); -#192232 = SURFACE_CURVE('',#192233,(#192237,#192243),.PCURVE_S1.); -#192233 = LINE('',#192234,#192235); -#192234 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); -#192235 = VECTOR('',#192236,1.); -#192236 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192237 = PCURVE('',#191702,#192238); -#192238 = DEFINITIONAL_REPRESENTATION('',(#192239),#192242); -#192239 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192240,#192241), +#194590 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194591 = CARTESIAN_POINT('',(-5.329070518201E-015,6.060606060606E-003) + ); +#194592 = CARTESIAN_POINT('',(-1.15463194561E-014,1.818181818182E-002)); +#194593 = CARTESIAN_POINT('',(-6.217248937901E-015,3.636363636364E-002) + ); +#194594 = CARTESIAN_POINT('',(-9.769962616701E-015,5.454545454545E-002) + ); +#194595 = CARTESIAN_POINT('',(-8.881784197001E-015,7.272727272727E-002) + ); +#194596 = CARTESIAN_POINT('',(-8.881784197001E-015,9.090909090909E-002) + ); +#194597 = CARTESIAN_POINT('',(-8.881784197001E-015,0.109090909091)); +#194598 = CARTESIAN_POINT('',(-9.769962616701E-015,0.127272727273)); +#194599 = CARTESIAN_POINT('',(-7.993605777301E-015,0.145454545455)); +#194600 = CARTESIAN_POINT('',(-9.769962616701E-015,0.163636363636)); +#194601 = CARTESIAN_POINT('',(-7.993605777301E-015,0.181818181818)); +#194602 = CARTESIAN_POINT('',(-7.993605777301E-015,0.2)); +#194603 = CARTESIAN_POINT('',(-8.881784197001E-015,0.218181818182)); +#194604 = CARTESIAN_POINT('',(-7.993605777301E-015,0.236363636364)); +#194605 = CARTESIAN_POINT('',(-8.881784197001E-015,0.254545454545)); +#194606 = CARTESIAN_POINT('',(-8.881784197001E-015,0.272727272727)); +#194607 = CARTESIAN_POINT('',(-8.881784197001E-015,0.290909090909)); +#194608 = CARTESIAN_POINT('',(-8.881784197001E-015,0.309090909091)); +#194609 = CARTESIAN_POINT('',(-8.881784197001E-015,0.327272727273)); +#194610 = CARTESIAN_POINT('',(-8.881784197001E-015,0.345454545455)); +#194611 = CARTESIAN_POINT('',(-8.881784197001E-015,0.363636363636)); +#194612 = CARTESIAN_POINT('',(-1.06581410364E-014,0.381818181818)); +#194613 = CARTESIAN_POINT('',(-5.329070518201E-015,0.393939393939)); +#194614 = CARTESIAN_POINT('',(0.E+000,0.4)); +#194615 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194616 = ORIENTED_EDGE('',*,*,#194045,.T.); +#194617 = ADVANCED_FACE('',(#194618),#194094,.F.); +#194618 = FACE_BOUND('',#194619,.F.); +#194619 = EDGE_LOOP('',(#194620,#194621,#194622,#194642)); +#194620 = ORIENTED_EDGE('',*,*,#194574,.F.); +#194621 = ORIENTED_EDGE('',*,*,#194073,.F.); +#194622 = ORIENTED_EDGE('',*,*,#194623,.T.); +#194623 = EDGE_CURVE('',#194074,#194183,#194624,.T.); +#194624 = SURFACE_CURVE('',#194625,(#194629,#194635),.PCURVE_S1.); +#194625 = LINE('',#194626,#194627); +#194626 = CARTESIAN_POINT('',(-0.2,-0.895598186972,0.194522398574)); +#194627 = VECTOR('',#194628,1.); +#194628 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194629 = PCURVE('',#194094,#194630); +#194630 = DEFINITIONAL_REPRESENTATION('',(#194631),#194634); +#194631 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194632,#194633), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192240 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); -#192241 = CARTESIAN_POINT('',(1.461023972143,0.4)); -#192242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192243 = PCURVE('',#191729,#192244); -#192244 = DEFINITIONAL_REPRESENTATION('',(#192245),#192249); -#192245 = LINE('',#192246,#192247); -#192246 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192247 = VECTOR('',#192248,1.); -#192248 = DIRECTION('',(0.E+000,1.)); -#192249 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192250 = ORIENTED_EDGE('',*,*,#191813,.T.); -#192251 = ADVANCED_FACE('',(#192252),#191729,.T.); -#192252 = FACE_BOUND('',#192253,.T.); -#192253 = EDGE_LOOP('',(#192254,#192255,#192256,#192276)); -#192254 = ORIENTED_EDGE('',*,*,#192231,.T.); -#192255 = ORIENTED_EDGE('',*,*,#191790,.F.); -#192256 = ORIENTED_EDGE('',*,*,#192257,.F.); -#192257 = EDGE_CURVE('',#191714,#191768,#192258,.T.); -#192258 = SURFACE_CURVE('',#192259,(#192263,#192270),.PCURVE_S1.); -#192259 = LINE('',#192260,#192261); -#192260 = CARTESIAN_POINT('',(-0.2,-0.854004213739,0.571910405702)); -#192261 = VECTOR('',#192262,1.); -#192262 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192263 = PCURVE('',#191729,#192264); -#192264 = DEFINITIONAL_REPRESENTATION('',(#192265),#192269); -#192265 = LINE('',#192266,#192267); -#192266 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); -#192267 = VECTOR('',#192268,1.); -#192268 = DIRECTION('',(0.E+000,1.)); -#192269 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192270 = PCURVE('',#191449,#192271); -#192271 = DEFINITIONAL_REPRESENTATION('',(#192272),#192275); -#192272 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192273,#192274), +#194632 = CARTESIAN_POINT('',(1.461023972143,0.E+000)); +#194633 = CARTESIAN_POINT('',(1.461023972143,0.4)); +#194634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194635 = PCURVE('',#194121,#194636); +#194636 = DEFINITIONAL_REPRESENTATION('',(#194637),#194641); +#194637 = LINE('',#194638,#194639); +#194638 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194639 = VECTOR('',#194640,1.); +#194640 = DIRECTION('',(0.E+000,1.)); +#194641 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194642 = ORIENTED_EDGE('',*,*,#194205,.T.); +#194643 = ADVANCED_FACE('',(#194644),#194121,.T.); +#194644 = FACE_BOUND('',#194645,.T.); +#194645 = EDGE_LOOP('',(#194646,#194647,#194648,#194668)); +#194646 = ORIENTED_EDGE('',*,*,#194623,.T.); +#194647 = ORIENTED_EDGE('',*,*,#194182,.F.); +#194648 = ORIENTED_EDGE('',*,*,#194649,.F.); +#194649 = EDGE_CURVE('',#194106,#194160,#194650,.T.); +#194650 = SURFACE_CURVE('',#194651,(#194655,#194662),.PCURVE_S1.); +#194651 = LINE('',#194652,#194653); +#194652 = CARTESIAN_POINT('',(-0.2,-0.854004213739,0.571910405702)); +#194653 = VECTOR('',#194654,1.); +#194654 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194655 = PCURVE('',#194121,#194656); +#194656 = DEFINITIONAL_REPRESENTATION('',(#194657),#194661); +#194657 = LINE('',#194658,#194659); +#194658 = CARTESIAN_POINT('',(-0.379673236525,0.E+000)); +#194659 = VECTOR('',#194660,1.); +#194660 = DIRECTION('',(0.E+000,1.)); +#194661 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194662 = PCURVE('',#193841,#194663); +#194663 = DEFINITIONAL_REPRESENTATION('',(#194664),#194667); +#194664 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194665,#194666), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192273 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); -#192274 = CARTESIAN_POINT('',(4.602616625733,0.4)); -#192275 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192276 = ORIENTED_EDGE('',*,*,#191713,.T.); -#192277 = ADVANCED_FACE('',(#192278),#191449,.T.); -#192278 = FACE_BOUND('',#192279,.T.); -#192279 = EDGE_LOOP('',(#192280,#192281,#192282,#192283)); -#192280 = ORIENTED_EDGE('',*,*,#192257,.T.); -#192281 = ORIENTED_EDGE('',*,*,#191767,.F.); -#192282 = ORIENTED_EDGE('',*,*,#191433,.F.); -#192283 = ORIENTED_EDGE('',*,*,#191741,.T.); -#192284 = ADVANCED_FACE('',(#192285),#186570,.T.); -#192285 = FACE_BOUND('',#192286,.T.); -#192286 = EDGE_LOOP('',(#192287,#192288,#192289,#192290)); -#192287 = ORIENTED_EDGE('',*,*,#191486,.T.); -#192288 = ORIENTED_EDGE('',*,*,#186556,.T.); -#192289 = ORIENTED_EDGE('',*,*,#191982,.F.); -#192290 = ORIENTED_EDGE('',*,*,#192006,.F.); -#192291 = ADVANCED_FACE('',(#192292),#185636,.T.); -#192292 = FACE_BOUND('',#192293,.T.); -#192293 = EDGE_LOOP('',(#192294,#192295,#192318,#192345)); -#192294 = ORIENTED_EDGE('',*,*,#185620,.F.); -#192295 = ORIENTED_EDGE('',*,*,#192296,.F.); -#192296 = EDGE_CURVE('',#192297,#185593,#192299,.T.); -#192297 = VERTEX_POINT('',#192298); -#192298 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); -#192299 = SURFACE_CURVE('',#192300,(#192304,#192311),.PCURVE_S1.); -#192300 = LINE('',#192301,#192302); -#192301 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); -#192302 = VECTOR('',#192303,1.); -#192303 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#192304 = PCURVE('',#185636,#192305); -#192305 = DEFINITIONAL_REPRESENTATION('',(#192306),#192310); -#192306 = LINE('',#192307,#192308); -#192307 = CARTESIAN_POINT('',(0.4,0.E+000)); -#192308 = VECTOR('',#192309,1.); -#192309 = DIRECTION('',(0.E+000,-1.)); -#192310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192311 = PCURVE('',#185608,#192312); -#192312 = DEFINITIONAL_REPRESENTATION('',(#192313),#192317); -#192313 = LINE('',#192314,#192315); -#192314 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#192315 = VECTOR('',#192316,1.); -#192316 = DIRECTION('',(0.E+000,-1.)); -#192317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192318 = ORIENTED_EDGE('',*,*,#192319,.F.); -#192319 = EDGE_CURVE('',#192320,#192297,#192322,.T.); -#192320 = VERTEX_POINT('',#192321); -#192321 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#192322 = SURFACE_CURVE('',#192323,(#192327,#192334),.PCURVE_S1.); -#192323 = LINE('',#192324,#192325); -#192324 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#192325 = VECTOR('',#192326,1.); -#192326 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192327 = PCURVE('',#185636,#192328); -#192328 = DEFINITIONAL_REPRESENTATION('',(#192329),#192333); -#192329 = LINE('',#192330,#192331); -#192330 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192331 = VECTOR('',#192332,1.); -#192332 = DIRECTION('',(1.,0.E+000)); -#192333 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192334 = PCURVE('',#192335,#192340); -#192335 = CYLINDRICAL_SURFACE('',#192336,0.2); -#192336 = AXIS2_PLACEMENT_3D('',#192337,#192338,#192339); -#192337 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#192338 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192339 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192340 = DEFINITIONAL_REPRESENTATION('',(#192341),#192344); -#192341 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192342,#192343), +#194665 = CARTESIAN_POINT('',(4.602616625733,0.E+000)); +#194666 = CARTESIAN_POINT('',(4.602616625733,0.4)); +#194667 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194668 = ORIENTED_EDGE('',*,*,#194105,.T.); +#194669 = ADVANCED_FACE('',(#194670),#193841,.T.); +#194670 = FACE_BOUND('',#194671,.T.); +#194671 = EDGE_LOOP('',(#194672,#194673,#194674,#194675)); +#194672 = ORIENTED_EDGE('',*,*,#194649,.T.); +#194673 = ORIENTED_EDGE('',*,*,#194159,.F.); +#194674 = ORIENTED_EDGE('',*,*,#193825,.F.); +#194675 = ORIENTED_EDGE('',*,*,#194133,.T.); +#194676 = ADVANCED_FACE('',(#194677),#188962,.T.); +#194677 = FACE_BOUND('',#194678,.T.); +#194678 = EDGE_LOOP('',(#194679,#194680,#194681,#194682)); +#194679 = ORIENTED_EDGE('',*,*,#193878,.T.); +#194680 = ORIENTED_EDGE('',*,*,#188948,.T.); +#194681 = ORIENTED_EDGE('',*,*,#194374,.F.); +#194682 = ORIENTED_EDGE('',*,*,#194398,.F.); +#194683 = ADVANCED_FACE('',(#194684),#188028,.T.); +#194684 = FACE_BOUND('',#194685,.T.); +#194685 = EDGE_LOOP('',(#194686,#194687,#194710,#194737)); +#194686 = ORIENTED_EDGE('',*,*,#188012,.F.); +#194687 = ORIENTED_EDGE('',*,*,#194688,.F.); +#194688 = EDGE_CURVE('',#194689,#187985,#194691,.T.); +#194689 = VERTEX_POINT('',#194690); +#194690 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); +#194691 = SURFACE_CURVE('',#194692,(#194696,#194703),.PCURVE_S1.); +#194692 = LINE('',#194693,#194694); +#194693 = CARTESIAN_POINT('',(0.2,0.655208001194,0.75)); +#194694 = VECTOR('',#194695,1.); +#194695 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194696 = PCURVE('',#188028,#194697); +#194697 = DEFINITIONAL_REPRESENTATION('',(#194698),#194702); +#194698 = LINE('',#194699,#194700); +#194699 = CARTESIAN_POINT('',(0.4,0.E+000)); +#194700 = VECTOR('',#194701,1.); +#194701 = DIRECTION('',(0.E+000,-1.)); +#194702 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194703 = PCURVE('',#188000,#194704); +#194704 = DEFINITIONAL_REPRESENTATION('',(#194705),#194709); +#194705 = LINE('',#194706,#194707); +#194706 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#194707 = VECTOR('',#194708,1.); +#194708 = DIRECTION('',(0.E+000,-1.)); +#194709 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194710 = ORIENTED_EDGE('',*,*,#194711,.F.); +#194711 = EDGE_CURVE('',#194712,#194689,#194714,.T.); +#194712 = VERTEX_POINT('',#194713); +#194713 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#194714 = SURFACE_CURVE('',#194715,(#194719,#194726),.PCURVE_S1.); +#194715 = LINE('',#194716,#194717); +#194716 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#194717 = VECTOR('',#194718,1.); +#194718 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194719 = PCURVE('',#188028,#194720); +#194720 = DEFINITIONAL_REPRESENTATION('',(#194721),#194725); +#194721 = LINE('',#194722,#194723); +#194722 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194723 = VECTOR('',#194724,1.); +#194724 = DIRECTION('',(1.,0.E+000)); +#194725 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194726 = PCURVE('',#194727,#194732); +#194727 = CYLINDRICAL_SURFACE('',#194728,0.2); +#194728 = AXIS2_PLACEMENT_3D('',#194729,#194730,#194731); +#194729 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#194730 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194731 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194732 = DEFINITIONAL_REPRESENTATION('',(#194733),#194736); +#194733 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194734,#194735), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192342 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#192343 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#192344 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192345 = ORIENTED_EDGE('',*,*,#192346,.T.); -#192346 = EDGE_CURVE('',#192320,#185621,#192347,.T.); -#192347 = SURFACE_CURVE('',#192348,(#192352,#192359),.PCURVE_S1.); -#192348 = LINE('',#192349,#192350); -#192349 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); -#192350 = VECTOR('',#192351,1.); -#192351 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#192352 = PCURVE('',#185636,#192353); -#192353 = DEFINITIONAL_REPRESENTATION('',(#192354),#192358); -#192354 = LINE('',#192355,#192356); -#192355 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192356 = VECTOR('',#192357,1.); -#192357 = DIRECTION('',(0.E+000,-1.)); -#192358 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192359 = PCURVE('',#185664,#192360); -#192360 = DEFINITIONAL_REPRESENTATION('',(#192361),#192365); -#192361 = LINE('',#192362,#192363); -#192362 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); -#192363 = VECTOR('',#192364,1.); -#192364 = DIRECTION('',(0.E+000,-1.)); -#192365 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192366 = ADVANCED_FACE('',(#192367),#185664,.F.); -#192367 = FACE_BOUND('',#192368,.T.); -#192368 = EDGE_LOOP('',(#192369,#192392,#192393,#192394,#192417,#192445, - #192477,#192505,#192533,#192561,#192589,#192617)); -#192369 = ORIENTED_EDGE('',*,*,#192370,.F.); -#192370 = EDGE_CURVE('',#185649,#192371,#192373,.T.); -#192371 = VERTEX_POINT('',#192372); -#192372 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#192373 = SURFACE_CURVE('',#192374,(#192378,#192385),.PCURVE_S1.); -#192374 = LINE('',#192375,#192376); -#192375 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#192376 = VECTOR('',#192377,1.); -#192377 = DIRECTION('',(0.E+000,1.,0.E+000)); -#192378 = PCURVE('',#185664,#192379); -#192379 = DEFINITIONAL_REPRESENTATION('',(#192380),#192384); -#192380 = LINE('',#192381,#192382); -#192381 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#192382 = VECTOR('',#192383,1.); -#192383 = DIRECTION('',(0.E+000,1.)); -#192384 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192385 = PCURVE('',#186886,#192386); -#192386 = DEFINITIONAL_REPRESENTATION('',(#192387),#192391); -#192387 = LINE('',#192388,#192389); -#192388 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192389 = VECTOR('',#192390,1.); -#192390 = DIRECTION('',(0.E+000,1.)); -#192391 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192392 = ORIENTED_EDGE('',*,*,#185648,.T.); -#192393 = ORIENTED_EDGE('',*,*,#192346,.F.); -#192394 = ORIENTED_EDGE('',*,*,#192395,.F.); -#192395 = EDGE_CURVE('',#192396,#192320,#192398,.T.); -#192396 = VERTEX_POINT('',#192397); -#192397 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); -#192398 = SURFACE_CURVE('',#192399,(#192404,#192411),.PCURVE_S1.); -#192399 = CIRCLE('',#192400,0.2); -#192400 = AXIS2_PLACEMENT_3D('',#192401,#192402,#192403); -#192401 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#192402 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192403 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192404 = PCURVE('',#185664,#192405); -#192405 = DEFINITIONAL_REPRESENTATION('',(#192406),#192410); -#192406 = CIRCLE('',#192407,0.2); -#192407 = AXIS2_PLACEMENT_2D('',#192408,#192409); -#192408 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192409 = DIRECTION('',(1.,0.E+000)); -#192410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192411 = PCURVE('',#192335,#192412); -#192412 = DEFINITIONAL_REPRESENTATION('',(#192413),#192416); -#192413 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192414,#192415), +#194734 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#194735 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#194736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194737 = ORIENTED_EDGE('',*,*,#194738,.T.); +#194738 = EDGE_CURVE('',#194712,#188013,#194739,.T.); +#194739 = SURFACE_CURVE('',#194740,(#194744,#194751),.PCURVE_S1.); +#194740 = LINE('',#194741,#194742); +#194741 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.75)); +#194742 = VECTOR('',#194743,1.); +#194743 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194744 = PCURVE('',#188028,#194745); +#194745 = DEFINITIONAL_REPRESENTATION('',(#194746),#194750); +#194746 = LINE('',#194747,#194748); +#194747 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194748 = VECTOR('',#194749,1.); +#194749 = DIRECTION('',(0.E+000,-1.)); +#194750 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194751 = PCURVE('',#188056,#194752); +#194752 = DEFINITIONAL_REPRESENTATION('',(#194753),#194757); +#194753 = LINE('',#194754,#194755); +#194754 = CARTESIAN_POINT('',(-0.2,-1.33226762955E-015)); +#194755 = VECTOR('',#194756,1.); +#194756 = DIRECTION('',(0.E+000,-1.)); +#194757 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194758 = ADVANCED_FACE('',(#194759),#188056,.F.); +#194759 = FACE_BOUND('',#194760,.T.); +#194760 = EDGE_LOOP('',(#194761,#194784,#194785,#194786,#194809,#194837, + #194869,#194897,#194925,#194953,#194981,#195009)); +#194761 = ORIENTED_EDGE('',*,*,#194762,.F.); +#194762 = EDGE_CURVE('',#188041,#194763,#194765,.T.); +#194763 = VERTEX_POINT('',#194764); +#194764 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#194765 = SURFACE_CURVE('',#194766,(#194770,#194777),.PCURVE_S1.); +#194766 = LINE('',#194767,#194768); +#194767 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#194768 = VECTOR('',#194769,1.); +#194769 = DIRECTION('',(0.E+000,1.,0.E+000)); +#194770 = PCURVE('',#188056,#194771); +#194771 = DEFINITIONAL_REPRESENTATION('',(#194772),#194776); +#194772 = LINE('',#194773,#194774); +#194773 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#194774 = VECTOR('',#194775,1.); +#194775 = DIRECTION('',(0.E+000,1.)); +#194776 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194777 = PCURVE('',#189278,#194778); +#194778 = DEFINITIONAL_REPRESENTATION('',(#194779),#194783); +#194779 = LINE('',#194780,#194781); +#194780 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194781 = VECTOR('',#194782,1.); +#194782 = DIRECTION('',(0.E+000,1.)); +#194783 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194784 = ORIENTED_EDGE('',*,*,#188040,.T.); +#194785 = ORIENTED_EDGE('',*,*,#194738,.F.); +#194786 = ORIENTED_EDGE('',*,*,#194787,.F.); +#194787 = EDGE_CURVE('',#194788,#194712,#194790,.T.); +#194788 = VERTEX_POINT('',#194789); +#194789 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); +#194790 = SURFACE_CURVE('',#194791,(#194796,#194803),.PCURVE_S1.); +#194791 = CIRCLE('',#194792,0.2); +#194792 = AXIS2_PLACEMENT_3D('',#194793,#194794,#194795); +#194793 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#194794 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194795 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194796 = PCURVE('',#188056,#194797); +#194797 = DEFINITIONAL_REPRESENTATION('',(#194798),#194802); +#194798 = CIRCLE('',#194799,0.2); +#194799 = AXIS2_PLACEMENT_2D('',#194800,#194801); +#194800 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194801 = DIRECTION('',(1.,0.E+000)); +#194802 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194803 = PCURVE('',#194727,#194804); +#194804 = DEFINITIONAL_REPRESENTATION('',(#194805),#194808); +#194805 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194806,#194807), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#192414 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#192415 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#192416 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192417 = ORIENTED_EDGE('',*,*,#192418,.F.); -#192418 = EDGE_CURVE('',#192419,#192396,#192421,.T.); -#192419 = VERTEX_POINT('',#192420); -#192420 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#192421 = SURFACE_CURVE('',#192422,(#192426,#192433),.PCURVE_S1.); -#192422 = LINE('',#192423,#192424); -#192423 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#192424 = VECTOR('',#192425,1.); -#192425 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#192426 = PCURVE('',#185664,#192427); -#192427 = DEFINITIONAL_REPRESENTATION('',(#192428),#192432); -#192428 = LINE('',#192429,#192430); -#192429 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#192430 = VECTOR('',#192431,1.); -#192431 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#192432 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192433 = PCURVE('',#192434,#192439); -#192434 = PLANE('',#192435); -#192435 = AXIS2_PLACEMENT_3D('',#192436,#192437,#192438); -#192436 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#192437 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); -#192438 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#192439 = DEFINITIONAL_REPRESENTATION('',(#192440),#192444); -#192440 = LINE('',#192441,#192442); -#192441 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192442 = VECTOR('',#192443,1.); -#192443 = DIRECTION('',(1.,0.E+000)); -#192444 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192445 = ORIENTED_EDGE('',*,*,#192446,.F.); -#192446 = EDGE_CURVE('',#192447,#192419,#192449,.T.); -#192447 = VERTEX_POINT('',#192448); -#192448 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); -#192449 = SURFACE_CURVE('',#192450,(#192455,#192466),.PCURVE_S1.); -#192450 = CIRCLE('',#192451,5.E-002); -#192451 = AXIS2_PLACEMENT_3D('',#192452,#192453,#192454); -#192452 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#192453 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#192454 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192455 = PCURVE('',#185664,#192456); -#192456 = DEFINITIONAL_REPRESENTATION('',(#192457),#192465); -#192457 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192458,#192459,#192460, - #192461,#192462,#192463,#192464),.UNSPECIFIED.,.F.,.F.) +#194806 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#194807 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#194808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194809 = ORIENTED_EDGE('',*,*,#194810,.F.); +#194810 = EDGE_CURVE('',#194811,#194788,#194813,.T.); +#194811 = VERTEX_POINT('',#194812); +#194812 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#194813 = SURFACE_CURVE('',#194814,(#194818,#194825),.PCURVE_S1.); +#194814 = LINE('',#194815,#194816); +#194815 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#194816 = VECTOR('',#194817,1.); +#194817 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#194818 = PCURVE('',#188056,#194819); +#194819 = DEFINITIONAL_REPRESENTATION('',(#194820),#194824); +#194820 = LINE('',#194821,#194822); +#194821 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#194822 = VECTOR('',#194823,1.); +#194823 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#194824 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194825 = PCURVE('',#194826,#194831); +#194826 = PLANE('',#194827); +#194827 = AXIS2_PLACEMENT_3D('',#194828,#194829,#194830); +#194828 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#194829 = DIRECTION('',(0.E+000,0.993981062721,0.109552028512)); +#194830 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#194831 = DEFINITIONAL_REPRESENTATION('',(#194832),#194836); +#194832 = LINE('',#194833,#194834); +#194833 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194834 = VECTOR('',#194835,1.); +#194835 = DIRECTION('',(1.,0.E+000)); +#194836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194837 = ORIENTED_EDGE('',*,*,#194838,.F.); +#194838 = EDGE_CURVE('',#194839,#194811,#194841,.T.); +#194839 = VERTEX_POINT('',#194840); +#194840 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); +#194841 = SURFACE_CURVE('',#194842,(#194847,#194858),.PCURVE_S1.); +#194842 = CIRCLE('',#194843,5.E-002); +#194843 = AXIS2_PLACEMENT_3D('',#194844,#194845,#194846); +#194844 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#194845 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194846 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194847 = PCURVE('',#188056,#194848); +#194848 = DEFINITIONAL_REPRESENTATION('',(#194849),#194857); +#194849 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#194850,#194851,#194852, + #194853,#194854,#194855,#194856),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#192458 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#192459 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#192460 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#192461 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#192462 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#192463 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#192464 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#192465 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192466 = PCURVE('',#192467,#192472); -#192467 = CYLINDRICAL_SURFACE('',#192468,5.E-002); -#192468 = AXIS2_PLACEMENT_3D('',#192469,#192470,#192471); -#192469 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#192470 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192471 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192472 = DEFINITIONAL_REPRESENTATION('',(#192473),#192476); -#192473 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192474,#192475), +#194850 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#194851 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#194852 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#194853 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#194854 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#194855 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#194856 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#194857 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194858 = PCURVE('',#194859,#194864); +#194859 = CYLINDRICAL_SURFACE('',#194860,5.E-002); +#194860 = AXIS2_PLACEMENT_3D('',#194861,#194862,#194863); +#194861 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#194862 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194863 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194864 = DEFINITIONAL_REPRESENTATION('',(#194865),#194868); +#194865 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194866,#194867), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#192474 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#192475 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#192476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192477 = ORIENTED_EDGE('',*,*,#192478,.F.); -#192478 = EDGE_CURVE('',#192479,#192447,#192481,.T.); -#192479 = VERTEX_POINT('',#192480); -#192480 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#192481 = SURFACE_CURVE('',#192482,(#192486,#192493),.PCURVE_S1.); -#192482 = LINE('',#192483,#192484); -#192483 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#192484 = VECTOR('',#192485,1.); -#192485 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#192486 = PCURVE('',#185664,#192487); -#192487 = DEFINITIONAL_REPRESENTATION('',(#192488),#192492); -#192488 = LINE('',#192489,#192490); -#192489 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#192490 = VECTOR('',#192491,1.); -#192491 = DIRECTION('',(0.E+000,-1.)); -#192492 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192493 = PCURVE('',#192494,#192499); -#192494 = PLANE('',#192495); -#192495 = AXIS2_PLACEMENT_3D('',#192496,#192497,#192498); -#192496 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#192497 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192498 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192499 = DEFINITIONAL_REPRESENTATION('',(#192500),#192504); -#192500 = LINE('',#192501,#192502); -#192501 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192502 = VECTOR('',#192503,1.); -#192503 = DIRECTION('',(0.E+000,-1.)); -#192504 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192505 = ORIENTED_EDGE('',*,*,#192506,.F.); -#192506 = EDGE_CURVE('',#192507,#192479,#192509,.T.); -#192507 = VERTEX_POINT('',#192508); -#192508 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#192509 = SURFACE_CURVE('',#192510,(#192514,#192521),.PCURVE_S1.); -#192510 = LINE('',#192511,#192512); -#192511 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#192512 = VECTOR('',#192513,1.); -#192513 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192514 = PCURVE('',#185664,#192515); -#192515 = DEFINITIONAL_REPRESENTATION('',(#192516),#192520); -#192516 = LINE('',#192517,#192518); -#192517 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#192518 = VECTOR('',#192519,1.); -#192519 = DIRECTION('',(-1.,0.E+000)); -#192520 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192521 = PCURVE('',#192522,#192527); -#192522 = PLANE('',#192523); -#192523 = AXIS2_PLACEMENT_3D('',#192524,#192525,#192526); -#192524 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#192525 = DIRECTION('',(0.E+000,1.,0.E+000)); -#192526 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192527 = DEFINITIONAL_REPRESENTATION('',(#192528),#192532); -#192528 = LINE('',#192529,#192530); -#192529 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192530 = VECTOR('',#192531,1.); -#192531 = DIRECTION('',(1.,0.E+000)); -#192532 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192533 = ORIENTED_EDGE('',*,*,#192534,.F.); -#192534 = EDGE_CURVE('',#192535,#192507,#192537,.T.); -#192535 = VERTEX_POINT('',#192536); -#192536 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); -#192537 = SURFACE_CURVE('',#192538,(#192542,#192549),.PCURVE_S1.); -#192538 = LINE('',#192539,#192540); -#192539 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#192540 = VECTOR('',#192541,1.); -#192541 = DIRECTION('',(0.E+000,1.,0.E+000)); -#192542 = PCURVE('',#185664,#192543); -#192543 = DEFINITIONAL_REPRESENTATION('',(#192544),#192548); -#192544 = LINE('',#192545,#192546); -#192545 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#192546 = VECTOR('',#192547,1.); -#192547 = DIRECTION('',(0.E+000,1.)); -#192548 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192549 = PCURVE('',#192550,#192555); -#192550 = PLANE('',#192551); -#192551 = AXIS2_PLACEMENT_3D('',#192552,#192553,#192554); -#192552 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#192553 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192554 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#192555 = DEFINITIONAL_REPRESENTATION('',(#192556),#192560); -#192556 = LINE('',#192557,#192558); -#192557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192558 = VECTOR('',#192559,1.); -#192559 = DIRECTION('',(0.E+000,1.)); -#192560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192561 = ORIENTED_EDGE('',*,*,#192562,.F.); -#192562 = EDGE_CURVE('',#192563,#192535,#192565,.T.); -#192563 = VERTEX_POINT('',#192564); -#192564 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); -#192565 = SURFACE_CURVE('',#192566,(#192571,#192578),.PCURVE_S1.); -#192566 = CIRCLE('',#192567,0.2); -#192567 = AXIS2_PLACEMENT_3D('',#192568,#192569,#192570); -#192568 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#192569 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192570 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192571 = PCURVE('',#185664,#192572); -#192572 = DEFINITIONAL_REPRESENTATION('',(#192573),#192577); -#192573 = CIRCLE('',#192574,0.2); -#192574 = AXIS2_PLACEMENT_2D('',#192575,#192576); -#192575 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#192576 = DIRECTION('',(1.,0.E+000)); -#192577 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192578 = PCURVE('',#192579,#192584); -#192579 = CYLINDRICAL_SURFACE('',#192580,0.2); -#192580 = AXIS2_PLACEMENT_3D('',#192581,#192582,#192583); -#192581 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); -#192582 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192583 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192584 = DEFINITIONAL_REPRESENTATION('',(#192585),#192588); -#192585 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192586,#192587), +#194866 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#194867 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#194868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194869 = ORIENTED_EDGE('',*,*,#194870,.F.); +#194870 = EDGE_CURVE('',#194871,#194839,#194873,.T.); +#194871 = VERTEX_POINT('',#194872); +#194872 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#194873 = SURFACE_CURVE('',#194874,(#194878,#194885),.PCURVE_S1.); +#194874 = LINE('',#194875,#194876); +#194875 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#194876 = VECTOR('',#194877,1.); +#194877 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#194878 = PCURVE('',#188056,#194879); +#194879 = DEFINITIONAL_REPRESENTATION('',(#194880),#194884); +#194880 = LINE('',#194881,#194882); +#194881 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#194882 = VECTOR('',#194883,1.); +#194883 = DIRECTION('',(0.E+000,-1.)); +#194884 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194885 = PCURVE('',#194886,#194891); +#194886 = PLANE('',#194887); +#194887 = AXIS2_PLACEMENT_3D('',#194888,#194889,#194890); +#194888 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#194889 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194890 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194891 = DEFINITIONAL_REPRESENTATION('',(#194892),#194896); +#194892 = LINE('',#194893,#194894); +#194893 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194894 = VECTOR('',#194895,1.); +#194895 = DIRECTION('',(0.E+000,-1.)); +#194896 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194897 = ORIENTED_EDGE('',*,*,#194898,.F.); +#194898 = EDGE_CURVE('',#194899,#194871,#194901,.T.); +#194899 = VERTEX_POINT('',#194900); +#194900 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#194901 = SURFACE_CURVE('',#194902,(#194906,#194913),.PCURVE_S1.); +#194902 = LINE('',#194903,#194904); +#194903 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#194904 = VECTOR('',#194905,1.); +#194905 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194906 = PCURVE('',#188056,#194907); +#194907 = DEFINITIONAL_REPRESENTATION('',(#194908),#194912); +#194908 = LINE('',#194909,#194910); +#194909 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#194910 = VECTOR('',#194911,1.); +#194911 = DIRECTION('',(-1.,0.E+000)); +#194912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194913 = PCURVE('',#194914,#194919); +#194914 = PLANE('',#194915); +#194915 = AXIS2_PLACEMENT_3D('',#194916,#194917,#194918); +#194916 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#194917 = DIRECTION('',(0.E+000,1.,0.E+000)); +#194918 = DIRECTION('',(0.E+000,0.E+000,1.)); +#194919 = DEFINITIONAL_REPRESENTATION('',(#194920),#194924); +#194920 = LINE('',#194921,#194922); +#194921 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194922 = VECTOR('',#194923,1.); +#194923 = DIRECTION('',(1.,0.E+000)); +#194924 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194925 = ORIENTED_EDGE('',*,*,#194926,.F.); +#194926 = EDGE_CURVE('',#194927,#194899,#194929,.T.); +#194927 = VERTEX_POINT('',#194928); +#194928 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); +#194929 = SURFACE_CURVE('',#194930,(#194934,#194941),.PCURVE_S1.); +#194930 = LINE('',#194931,#194932); +#194931 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#194932 = VECTOR('',#194933,1.); +#194933 = DIRECTION('',(0.E+000,1.,0.E+000)); +#194934 = PCURVE('',#188056,#194935); +#194935 = DEFINITIONAL_REPRESENTATION('',(#194936),#194940); +#194936 = LINE('',#194937,#194938); +#194937 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#194938 = VECTOR('',#194939,1.); +#194939 = DIRECTION('',(0.E+000,1.)); +#194940 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194941 = PCURVE('',#194942,#194947); +#194942 = PLANE('',#194943); +#194943 = AXIS2_PLACEMENT_3D('',#194944,#194945,#194946); +#194944 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#194945 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194946 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#194947 = DEFINITIONAL_REPRESENTATION('',(#194948),#194952); +#194948 = LINE('',#194949,#194950); +#194949 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#194950 = VECTOR('',#194951,1.); +#194951 = DIRECTION('',(0.E+000,1.)); +#194952 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194953 = ORIENTED_EDGE('',*,*,#194954,.F.); +#194954 = EDGE_CURVE('',#194955,#194927,#194957,.T.); +#194955 = VERTEX_POINT('',#194956); +#194956 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); +#194957 = SURFACE_CURVE('',#194958,(#194963,#194970),.PCURVE_S1.); +#194958 = CIRCLE('',#194959,0.2); +#194959 = AXIS2_PLACEMENT_3D('',#194960,#194961,#194962); +#194960 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#194961 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194962 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194963 = PCURVE('',#188056,#194964); +#194964 = DEFINITIONAL_REPRESENTATION('',(#194965),#194969); +#194965 = CIRCLE('',#194966,0.2); +#194966 = AXIS2_PLACEMENT_2D('',#194967,#194968); +#194967 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#194968 = DIRECTION('',(1.,0.E+000)); +#194969 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194970 = PCURVE('',#194971,#194976); +#194971 = CYLINDRICAL_SURFACE('',#194972,0.2); +#194972 = AXIS2_PLACEMENT_3D('',#194973,#194974,#194975); +#194973 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.2)); +#194974 = DIRECTION('',(1.,0.E+000,0.E+000)); +#194975 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#194976 = DEFINITIONAL_REPRESENTATION('',(#194977),#194980); +#194977 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194978,#194979), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#192586 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#192587 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#192588 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192589 = ORIENTED_EDGE('',*,*,#192590,.F.); -#192590 = EDGE_CURVE('',#192591,#192563,#192593,.T.); -#192591 = VERTEX_POINT('',#192592); -#192592 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#192593 = SURFACE_CURVE('',#192594,(#192598,#192605),.PCURVE_S1.); -#192594 = LINE('',#192595,#192596); -#192595 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#192596 = VECTOR('',#192597,1.); -#192597 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#192598 = PCURVE('',#185664,#192599); -#192599 = DEFINITIONAL_REPRESENTATION('',(#192600),#192604); -#192600 = LINE('',#192601,#192602); -#192601 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#192602 = VECTOR('',#192603,1.); -#192603 = DIRECTION('',(0.993981062721,0.109552028512)); -#192604 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192605 = PCURVE('',#192606,#192611); -#192606 = PLANE('',#192607); -#192607 = AXIS2_PLACEMENT_3D('',#192608,#192609,#192610); -#192608 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#192609 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); -#192610 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#192611 = DEFINITIONAL_REPRESENTATION('',(#192612),#192616); -#192612 = LINE('',#192613,#192614); -#192613 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192614 = VECTOR('',#192615,1.); -#192615 = DIRECTION('',(1.,0.E+000)); -#192616 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192617 = ORIENTED_EDGE('',*,*,#192618,.F.); -#192618 = EDGE_CURVE('',#192371,#192591,#192619,.T.); -#192619 = SURFACE_CURVE('',#192620,(#192625,#192636),.PCURVE_S1.); -#192620 = CIRCLE('',#192621,5.E-002); -#192621 = AXIS2_PLACEMENT_3D('',#192622,#192623,#192624); -#192622 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#192623 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#192624 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192625 = PCURVE('',#185664,#192626); -#192626 = DEFINITIONAL_REPRESENTATION('',(#192627),#192635); -#192627 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192628,#192629,#192630, - #192631,#192632,#192633,#192634),.UNSPECIFIED.,.F.,.F.) +#194978 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#194979 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#194980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194981 = ORIENTED_EDGE('',*,*,#194982,.F.); +#194982 = EDGE_CURVE('',#194983,#194955,#194985,.T.); +#194983 = VERTEX_POINT('',#194984); +#194984 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#194985 = SURFACE_CURVE('',#194986,(#194990,#194997),.PCURVE_S1.); +#194986 = LINE('',#194987,#194988); +#194987 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#194988 = VECTOR('',#194989,1.); +#194989 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#194990 = PCURVE('',#188056,#194991); +#194991 = DEFINITIONAL_REPRESENTATION('',(#194992),#194996); +#194992 = LINE('',#194993,#194994); +#194993 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#194994 = VECTOR('',#194995,1.); +#194995 = DIRECTION('',(0.993981062721,0.109552028512)); +#194996 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#194997 = PCURVE('',#194998,#195003); +#194998 = PLANE('',#194999); +#194999 = AXIS2_PLACEMENT_3D('',#195000,#195001,#195002); +#195000 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#195001 = DIRECTION('',(0.E+000,-0.993981062721,-0.109552028512)); +#195002 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#195003 = DEFINITIONAL_REPRESENTATION('',(#195004),#195008); +#195004 = LINE('',#195005,#195006); +#195005 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195006 = VECTOR('',#195007,1.); +#195007 = DIRECTION('',(1.,0.E+000)); +#195008 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195009 = ORIENTED_EDGE('',*,*,#195010,.F.); +#195010 = EDGE_CURVE('',#194763,#194983,#195011,.T.); +#195011 = SURFACE_CURVE('',#195012,(#195017,#195028),.PCURVE_S1.); +#195012 = CIRCLE('',#195013,5.E-002); +#195013 = AXIS2_PLACEMENT_3D('',#195014,#195015,#195016); +#195014 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#195015 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#195016 = DIRECTION('',(0.E+000,0.E+000,1.)); +#195017 = PCURVE('',#188056,#195018); +#195018 = DEFINITIONAL_REPRESENTATION('',(#195019),#195027); +#195019 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#195020,#195021,#195022, + #195023,#195024,#195025,#195026),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#192628 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#192629 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#192630 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#192631 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#192632 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#192633 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#192634 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#192635 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192636 = PCURVE('',#192637,#192642); -#192637 = CYLINDRICAL_SURFACE('',#192638,5.E-002); -#192638 = AXIS2_PLACEMENT_3D('',#192639,#192640,#192641); -#192639 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); -#192640 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192641 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192642 = DEFINITIONAL_REPRESENTATION('',(#192643),#192646); -#192643 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192644,#192645), +#195020 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#195021 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#195022 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#195023 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#195024 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#195025 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#195026 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#195027 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195028 = PCURVE('',#195029,#195034); +#195029 = CYLINDRICAL_SURFACE('',#195030,5.E-002); +#195030 = AXIS2_PLACEMENT_3D('',#195031,#195032,#195033); +#195031 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.55)); +#195032 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195033 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#195034 = DEFINITIONAL_REPRESENTATION('',(#195035),#195038); +#195035 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195036,#195037), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#192644 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#192645 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#192646 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192647 = ADVANCED_FACE('',(#192648),#185608,.T.); -#192648 = FACE_BOUND('',#192649,.T.); -#192649 = EDGE_LOOP('',(#192650,#192651,#192674,#192701,#192724,#192747, - #192770,#192793,#192816,#192843,#192866,#192887)); -#192650 = ORIENTED_EDGE('',*,*,#185592,.F.); -#192651 = ORIENTED_EDGE('',*,*,#192652,.T.); -#192652 = EDGE_CURVE('',#185570,#192653,#192655,.T.); -#192653 = VERTEX_POINT('',#192654); -#192654 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); -#192655 = SURFACE_CURVE('',#192656,(#192660,#192667),.PCURVE_S1.); -#192656 = LINE('',#192657,#192658); -#192657 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); -#192658 = VECTOR('',#192659,1.); -#192659 = DIRECTION('',(0.E+000,1.,0.E+000)); -#192660 = PCURVE('',#185608,#192661); -#192661 = DEFINITIONAL_REPRESENTATION('',(#192662),#192666); -#192662 = LINE('',#192663,#192664); -#192663 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); -#192664 = VECTOR('',#192665,1.); -#192665 = DIRECTION('',(0.E+000,1.)); -#192666 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192667 = PCURVE('',#186886,#192668); -#192668 = DEFINITIONAL_REPRESENTATION('',(#192669),#192673); -#192669 = LINE('',#192670,#192671); -#192670 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#192671 = VECTOR('',#192672,1.); -#192672 = DIRECTION('',(0.E+000,1.)); -#192673 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192674 = ORIENTED_EDGE('',*,*,#192675,.T.); -#192675 = EDGE_CURVE('',#192653,#192676,#192678,.T.); -#192676 = VERTEX_POINT('',#192677); -#192677 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); -#192678 = SURFACE_CURVE('',#192679,(#192684,#192695),.PCURVE_S1.); -#192679 = CIRCLE('',#192680,5.E-002); -#192680 = AXIS2_PLACEMENT_3D('',#192681,#192682,#192683); -#192681 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); -#192682 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#192683 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192684 = PCURVE('',#185608,#192685); -#192685 = DEFINITIONAL_REPRESENTATION('',(#192686),#192694); -#192686 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192687,#192688,#192689, - #192690,#192691,#192692,#192693),.UNSPECIFIED.,.F.,.F.) +#195036 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#195037 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#195038 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195039 = ADVANCED_FACE('',(#195040),#188000,.T.); +#195040 = FACE_BOUND('',#195041,.T.); +#195041 = EDGE_LOOP('',(#195042,#195043,#195066,#195093,#195116,#195139, + #195162,#195185,#195208,#195235,#195258,#195279)); +#195042 = ORIENTED_EDGE('',*,*,#187984,.F.); +#195043 = ORIENTED_EDGE('',*,*,#195044,.T.); +#195044 = EDGE_CURVE('',#187962,#195045,#195047,.T.); +#195045 = VERTEX_POINT('',#195046); +#195046 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); +#195047 = SURFACE_CURVE('',#195048,(#195052,#195059),.PCURVE_S1.); +#195048 = LINE('',#195049,#195050); +#195049 = CARTESIAN_POINT('',(0.2,0.655208001194,0.6)); +#195050 = VECTOR('',#195051,1.); +#195051 = DIRECTION('',(0.E+000,1.,0.E+000)); +#195052 = PCURVE('',#188000,#195053); +#195053 = DEFINITIONAL_REPRESENTATION('',(#195054),#195058); +#195054 = LINE('',#195055,#195056); +#195055 = CARTESIAN_POINT('',(-5.E-002,-3.330669073875E-016)); +#195056 = VECTOR('',#195057,1.); +#195057 = DIRECTION('',(0.E+000,1.)); +#195058 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195059 = PCURVE('',#189278,#195060); +#195060 = DEFINITIONAL_REPRESENTATION('',(#195061),#195065); +#195061 = LINE('',#195062,#195063); +#195062 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#195063 = VECTOR('',#195064,1.); +#195064 = DIRECTION('',(0.E+000,1.)); +#195065 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195066 = ORIENTED_EDGE('',*,*,#195067,.T.); +#195067 = EDGE_CURVE('',#195045,#195068,#195070,.T.); +#195068 = VERTEX_POINT('',#195069); +#195069 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); +#195070 = SURFACE_CURVE('',#195071,(#195076,#195087),.PCURVE_S1.); +#195071 = CIRCLE('',#195072,5.E-002); +#195072 = AXIS2_PLACEMENT_3D('',#195073,#195074,#195075); +#195073 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); +#195074 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#195075 = DIRECTION('',(0.E+000,0.E+000,1.)); +#195076 = PCURVE('',#188000,#195077); +#195077 = DEFINITIONAL_REPRESENTATION('',(#195078),#195086); +#195078 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#195079,#195080,#195081, + #195082,#195083,#195084,#195085),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#192687 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#192688 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); -#192689 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); -#192690 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); -#192691 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); -#192692 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); -#192693 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); -#192694 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192695 = PCURVE('',#192637,#192696); -#192696 = DEFINITIONAL_REPRESENTATION('',(#192697),#192700); -#192697 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192698,#192699), +#195079 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#195080 = CARTESIAN_POINT('',(-5.E-002,8.660254037844E-002)); +#195081 = CARTESIAN_POINT('',(2.5E-002,4.330127018922E-002)); +#195082 = CARTESIAN_POINT('',(1.E-001,3.445052403073E-017)); +#195083 = CARTESIAN_POINT('',(2.5E-002,-4.330127018922E-002)); +#195084 = CARTESIAN_POINT('',(-5.E-002,-8.660254037844E-002)); +#195085 = CARTESIAN_POINT('',(-5.E-002,0.E+000)); +#195086 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195087 = PCURVE('',#195029,#195088); +#195088 = DEFINITIONAL_REPRESENTATION('',(#195089),#195092); +#195089 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195090,#195091), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.461023972143), .PIECEWISE_BEZIER_KNOTS.); -#192698 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#192699 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#192700 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192701 = ORIENTED_EDGE('',*,*,#192702,.T.); -#192702 = EDGE_CURVE('',#192676,#192703,#192705,.T.); -#192703 = VERTEX_POINT('',#192704); -#192704 = CARTESIAN_POINT('',(0.2,0.746501027564,0.178089594298)); -#192705 = SURFACE_CURVE('',#192706,(#192710,#192717),.PCURVE_S1.); -#192706 = LINE('',#192707,#192708); -#192707 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); -#192708 = VECTOR('',#192709,1.); -#192709 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); -#192710 = PCURVE('',#185608,#192711); -#192711 = DEFINITIONAL_REPRESENTATION('',(#192712),#192716); -#192712 = LINE('',#192713,#192714); -#192713 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) - ); -#192714 = VECTOR('',#192715,1.); -#192715 = DIRECTION('',(0.993981062721,0.109552028512)); -#192716 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192717 = PCURVE('',#192606,#192718); -#192718 = DEFINITIONAL_REPRESENTATION('',(#192719),#192723); -#192719 = LINE('',#192720,#192721); -#192720 = CARTESIAN_POINT('',(0.E+000,0.4)); -#192721 = VECTOR('',#192722,1.); -#192722 = DIRECTION('',(1.,0.E+000)); -#192723 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192724 = ORIENTED_EDGE('',*,*,#192725,.T.); -#192725 = EDGE_CURVE('',#192703,#192726,#192728,.T.); -#192726 = VERTEX_POINT('',#192727); -#192727 = CARTESIAN_POINT('',(0.2,0.945297240108,0.E+000)); -#192728 = SURFACE_CURVE('',#192729,(#192734,#192741),.PCURVE_S1.); -#192729 = CIRCLE('',#192730,0.2); -#192730 = AXIS2_PLACEMENT_3D('',#192731,#192732,#192733); -#192731 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); -#192732 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192733 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192734 = PCURVE('',#185608,#192735); -#192735 = DEFINITIONAL_REPRESENTATION('',(#192736),#192740); -#192736 = CIRCLE('',#192737,0.2); -#192737 = AXIS2_PLACEMENT_2D('',#192738,#192739); -#192738 = CARTESIAN_POINT('',(0.35,0.290089238914)); -#192739 = DIRECTION('',(1.,0.E+000)); -#192740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192741 = PCURVE('',#192579,#192742); -#192742 = DEFINITIONAL_REPRESENTATION('',(#192743),#192746); -#192743 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192744,#192745), +#195090 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#195091 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#195092 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195093 = ORIENTED_EDGE('',*,*,#195094,.T.); +#195094 = EDGE_CURVE('',#195068,#195095,#195097,.T.); +#195095 = VERTEX_POINT('',#195096); +#195096 = CARTESIAN_POINT('',(0.2,0.746501027564,0.178089594298)); +#195097 = SURFACE_CURVE('',#195098,(#195102,#195109),.PCURVE_S1.); +#195098 = LINE('',#195099,#195100); +#195099 = CARTESIAN_POINT('',(0.2,0.70490705433,0.555477601426)); +#195100 = VECTOR('',#195101,1.); +#195101 = DIRECTION('',(0.E+000,0.109552028512,-0.993981062721)); +#195102 = PCURVE('',#188000,#195103); +#195103 = DEFINITIONAL_REPRESENTATION('',(#195104),#195108); +#195104 = LINE('',#195105,#195106); +#195105 = CARTESIAN_POINT('',(-5.477601425623E-003,4.969905313607E-002) + ); +#195106 = VECTOR('',#195107,1.); +#195107 = DIRECTION('',(0.993981062721,0.109552028512)); +#195108 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195109 = PCURVE('',#194998,#195110); +#195110 = DEFINITIONAL_REPRESENTATION('',(#195111),#195115); +#195111 = LINE('',#195112,#195113); +#195112 = CARTESIAN_POINT('',(0.E+000,0.4)); +#195113 = VECTOR('',#195114,1.); +#195114 = DIRECTION('',(1.,0.E+000)); +#195115 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195116 = ORIENTED_EDGE('',*,*,#195117,.T.); +#195117 = EDGE_CURVE('',#195095,#195118,#195120,.T.); +#195118 = VERTEX_POINT('',#195119); +#195119 = CARTESIAN_POINT('',(0.2,0.945297240108,0.E+000)); +#195120 = SURFACE_CURVE('',#195121,(#195126,#195133),.PCURVE_S1.); +#195121 = CIRCLE('',#195122,0.2); +#195122 = AXIS2_PLACEMENT_3D('',#195123,#195124,#195125); +#195123 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); +#195124 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195125 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#195126 = PCURVE('',#188000,#195127); +#195127 = DEFINITIONAL_REPRESENTATION('',(#195128),#195132); +#195128 = CIRCLE('',#195129,0.2); +#195129 = AXIS2_PLACEMENT_2D('',#195130,#195131); +#195130 = CARTESIAN_POINT('',(0.35,0.290089238914)); +#195131 = DIRECTION('',(1.,0.E+000)); +#195132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195133 = PCURVE('',#194971,#195134); +#195134 = DEFINITIONAL_REPRESENTATION('',(#195135),#195138); +#195135 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195136,#195137), .UNSPECIFIED.,.F.,.F.,(2,2),(4.822161335036,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#192744 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#192745 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#192746 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192747 = ORIENTED_EDGE('',*,*,#192748,.T.); -#192748 = EDGE_CURVE('',#192726,#192749,#192751,.T.); -#192749 = VERTEX_POINT('',#192750); -#192750 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#192751 = SURFACE_CURVE('',#192752,(#192756,#192763),.PCURVE_S1.); -#192752 = LINE('',#192753,#192754); -#192753 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#192754 = VECTOR('',#192755,1.); -#192755 = DIRECTION('',(0.E+000,1.,0.E+000)); -#192756 = PCURVE('',#185608,#192757); -#192757 = DEFINITIONAL_REPRESENTATION('',(#192758),#192762); -#192758 = LINE('',#192759,#192760); -#192759 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#192760 = VECTOR('',#192761,1.); -#192761 = DIRECTION('',(0.E+000,1.)); -#192762 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192763 = PCURVE('',#192550,#192764); -#192764 = DEFINITIONAL_REPRESENTATION('',(#192765),#192769); -#192765 = LINE('',#192766,#192767); -#192766 = CARTESIAN_POINT('',(-0.4,0.E+000)); -#192767 = VECTOR('',#192768,1.); -#192768 = DIRECTION('',(0.E+000,1.)); -#192769 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192770 = ORIENTED_EDGE('',*,*,#192771,.T.); -#192771 = EDGE_CURVE('',#192749,#192772,#192774,.T.); -#192772 = VERTEX_POINT('',#192773); -#192773 = CARTESIAN_POINT('',(0.2,1.17,0.15)); -#192774 = SURFACE_CURVE('',#192775,(#192779,#192786),.PCURVE_S1.); -#192775 = LINE('',#192776,#192777); -#192776 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); -#192777 = VECTOR('',#192778,1.); -#192778 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192779 = PCURVE('',#185608,#192780); -#192780 = DEFINITIONAL_REPRESENTATION('',(#192781),#192785); -#192781 = LINE('',#192782,#192783); -#192782 = CARTESIAN_POINT('',(0.55,0.514791998806)); -#192783 = VECTOR('',#192784,1.); -#192784 = DIRECTION('',(-1.,0.E+000)); -#192785 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192786 = PCURVE('',#192522,#192787); -#192787 = DEFINITIONAL_REPRESENTATION('',(#192788),#192792); -#192788 = LINE('',#192789,#192790); -#192789 = CARTESIAN_POINT('',(0.E+000,0.4)); -#192790 = VECTOR('',#192791,1.); -#192791 = DIRECTION('',(1.,0.E+000)); -#192792 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192793 = ORIENTED_EDGE('',*,*,#192794,.T.); -#192794 = EDGE_CURVE('',#192772,#192795,#192797,.T.); -#192795 = VERTEX_POINT('',#192796); -#192796 = CARTESIAN_POINT('',(0.2,0.945297240108,0.15)); -#192797 = SURFACE_CURVE('',#192798,(#192802,#192809),.PCURVE_S1.); -#192798 = LINE('',#192799,#192800); -#192799 = CARTESIAN_POINT('',(0.2,1.17,0.15)); -#192800 = VECTOR('',#192801,1.); -#192801 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#192802 = PCURVE('',#185608,#192803); -#192803 = DEFINITIONAL_REPRESENTATION('',(#192804),#192808); -#192804 = LINE('',#192805,#192806); -#192805 = CARTESIAN_POINT('',(0.4,0.514791998806)); -#192806 = VECTOR('',#192807,1.); -#192807 = DIRECTION('',(0.E+000,-1.)); -#192808 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192809 = PCURVE('',#192494,#192810); -#192810 = DEFINITIONAL_REPRESENTATION('',(#192811),#192815); -#192811 = LINE('',#192812,#192813); -#192812 = CARTESIAN_POINT('',(0.4,0.E+000)); -#192813 = VECTOR('',#192814,1.); -#192814 = DIRECTION('',(0.E+000,-1.)); -#192815 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192816 = ORIENTED_EDGE('',*,*,#192817,.T.); -#192817 = EDGE_CURVE('',#192795,#192818,#192820,.T.); -#192818 = VERTEX_POINT('',#192819); -#192819 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); -#192820 = SURFACE_CURVE('',#192821,(#192826,#192837),.PCURVE_S1.); -#192821 = CIRCLE('',#192822,5.E-002); -#192822 = AXIS2_PLACEMENT_3D('',#192823,#192824,#192825); -#192823 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); -#192824 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#192825 = DIRECTION('',(0.E+000,0.E+000,1.)); -#192826 = PCURVE('',#185608,#192827); -#192827 = DEFINITIONAL_REPRESENTATION('',(#192828),#192836); -#192828 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#192829,#192830,#192831, - #192832,#192833,#192834,#192835),.UNSPECIFIED.,.F.,.F.) +#195136 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#195137 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#195138 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195139 = ORIENTED_EDGE('',*,*,#195140,.T.); +#195140 = EDGE_CURVE('',#195118,#195141,#195143,.T.); +#195141 = VERTEX_POINT('',#195142); +#195142 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#195143 = SURFACE_CURVE('',#195144,(#195148,#195155),.PCURVE_S1.); +#195144 = LINE('',#195145,#195146); +#195145 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#195146 = VECTOR('',#195147,1.); +#195147 = DIRECTION('',(0.E+000,1.,0.E+000)); +#195148 = PCURVE('',#188000,#195149); +#195149 = DEFINITIONAL_REPRESENTATION('',(#195150),#195154); +#195150 = LINE('',#195151,#195152); +#195151 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#195152 = VECTOR('',#195153,1.); +#195153 = DIRECTION('',(0.E+000,1.)); +#195154 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195155 = PCURVE('',#194942,#195156); +#195156 = DEFINITIONAL_REPRESENTATION('',(#195157),#195161); +#195157 = LINE('',#195158,#195159); +#195158 = CARTESIAN_POINT('',(-0.4,0.E+000)); +#195159 = VECTOR('',#195160,1.); +#195160 = DIRECTION('',(0.E+000,1.)); +#195161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195162 = ORIENTED_EDGE('',*,*,#195163,.T.); +#195163 = EDGE_CURVE('',#195141,#195164,#195166,.T.); +#195164 = VERTEX_POINT('',#195165); +#195165 = CARTESIAN_POINT('',(0.2,1.17,0.15)); +#195166 = SURFACE_CURVE('',#195167,(#195171,#195178),.PCURVE_S1.); +#195167 = LINE('',#195168,#195169); +#195168 = CARTESIAN_POINT('',(0.2,1.17,0.E+000)); +#195169 = VECTOR('',#195170,1.); +#195170 = DIRECTION('',(0.E+000,0.E+000,1.)); +#195171 = PCURVE('',#188000,#195172); +#195172 = DEFINITIONAL_REPRESENTATION('',(#195173),#195177); +#195173 = LINE('',#195174,#195175); +#195174 = CARTESIAN_POINT('',(0.55,0.514791998806)); +#195175 = VECTOR('',#195176,1.); +#195176 = DIRECTION('',(-1.,0.E+000)); +#195177 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195178 = PCURVE('',#194914,#195179); +#195179 = DEFINITIONAL_REPRESENTATION('',(#195180),#195184); +#195180 = LINE('',#195181,#195182); +#195181 = CARTESIAN_POINT('',(0.E+000,0.4)); +#195182 = VECTOR('',#195183,1.); +#195183 = DIRECTION('',(1.,0.E+000)); +#195184 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195185 = ORIENTED_EDGE('',*,*,#195186,.T.); +#195186 = EDGE_CURVE('',#195164,#195187,#195189,.T.); +#195187 = VERTEX_POINT('',#195188); +#195188 = CARTESIAN_POINT('',(0.2,0.945297240108,0.15)); +#195189 = SURFACE_CURVE('',#195190,(#195194,#195201),.PCURVE_S1.); +#195190 = LINE('',#195191,#195192); +#195191 = CARTESIAN_POINT('',(0.2,1.17,0.15)); +#195192 = VECTOR('',#195193,1.); +#195193 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#195194 = PCURVE('',#188000,#195195); +#195195 = DEFINITIONAL_REPRESENTATION('',(#195196),#195200); +#195196 = LINE('',#195197,#195198); +#195197 = CARTESIAN_POINT('',(0.4,0.514791998806)); +#195198 = VECTOR('',#195199,1.); +#195199 = DIRECTION('',(0.E+000,-1.)); +#195200 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195201 = PCURVE('',#194886,#195202); +#195202 = DEFINITIONAL_REPRESENTATION('',(#195203),#195207); +#195203 = LINE('',#195204,#195205); +#195204 = CARTESIAN_POINT('',(0.4,0.E+000)); +#195205 = VECTOR('',#195206,1.); +#195206 = DIRECTION('',(0.E+000,-1.)); +#195207 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195208 = ORIENTED_EDGE('',*,*,#195209,.T.); +#195209 = EDGE_CURVE('',#195187,#195210,#195212,.T.); +#195210 = VERTEX_POINT('',#195211); +#195211 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); +#195212 = SURFACE_CURVE('',#195213,(#195218,#195229),.PCURVE_S1.); +#195213 = CIRCLE('',#195214,5.E-002); +#195214 = AXIS2_PLACEMENT_3D('',#195215,#195216,#195217); +#195215 = CARTESIAN_POINT('',(0.2,0.945297240108,0.2)); +#195216 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#195217 = DIRECTION('',(0.E+000,0.E+000,1.)); +#195218 = PCURVE('',#188000,#195219); +#195219 = DEFINITIONAL_REPRESENTATION('',(#195220),#195228); +#195220 = ( BOUNDED_CURVE() B_SPLINE_CURVE(2,(#195221,#195222,#195223, + #195224,#195225,#195226,#195227),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((1,2,2,2,2,1),(-2.094395102393,0.E+000, 2.094395102393,4.188790204786,6.28318530718,8.377580409573), .UNSPECIFIED.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1.,0.5,1.,0.5,1.,0.5,1.)) REPRESENTATION_ITEM( '') ); -#192829 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#192830 = CARTESIAN_POINT('',(0.3,0.376691779292)); -#192831 = CARTESIAN_POINT('',(0.375,0.333390509103)); -#192832 = CARTESIAN_POINT('',(0.45,0.290089238914)); -#192833 = CARTESIAN_POINT('',(0.375,0.246787968724)); -#192834 = CARTESIAN_POINT('',(0.3,0.203486698535)); -#192835 = CARTESIAN_POINT('',(0.3,0.290089238914)); -#192836 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192837 = PCURVE('',#192467,#192838); -#192838 = DEFINITIONAL_REPRESENTATION('',(#192839),#192842); -#192839 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192840,#192841), +#195221 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#195222 = CARTESIAN_POINT('',(0.3,0.376691779292)); +#195223 = CARTESIAN_POINT('',(0.375,0.333390509103)); +#195224 = CARTESIAN_POINT('',(0.45,0.290089238914)); +#195225 = CARTESIAN_POINT('',(0.375,0.246787968724)); +#195226 = CARTESIAN_POINT('',(0.3,0.203486698535)); +#195227 = CARTESIAN_POINT('',(0.3,0.290089238914)); +#195228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195229 = PCURVE('',#194859,#195230); +#195230 = DEFINITIONAL_REPRESENTATION('',(#195231),#195234); +#195231 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195232,#195233), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.602616625733), .PIECEWISE_BEZIER_KNOTS.); -#192840 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#192841 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#192842 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192843 = ORIENTED_EDGE('',*,*,#192844,.T.); -#192844 = EDGE_CURVE('',#192818,#192845,#192847,.T.); -#192845 = VERTEX_POINT('',#192846); -#192846 = CARTESIAN_POINT('',(0.2,0.854004213739,0.571910405702)); -#192847 = SURFACE_CURVE('',#192848,(#192852,#192859),.PCURVE_S1.); -#192848 = LINE('',#192849,#192850); -#192849 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); -#192850 = VECTOR('',#192851,1.); -#192851 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); -#192852 = PCURVE('',#185608,#192853); -#192853 = DEFINITIONAL_REPRESENTATION('',(#192854),#192858); -#192854 = LINE('',#192855,#192856); -#192855 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); -#192856 = VECTOR('',#192857,1.); -#192857 = DIRECTION('',(-0.993981062721,-0.109552028512)); -#192858 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192859 = PCURVE('',#192434,#192860); -#192860 = DEFINITIONAL_REPRESENTATION('',(#192861),#192865); -#192861 = LINE('',#192862,#192863); -#192862 = CARTESIAN_POINT('',(0.E+000,0.4)); -#192863 = VECTOR('',#192864,1.); -#192864 = DIRECTION('',(1.,0.E+000)); -#192865 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192866 = ORIENTED_EDGE('',*,*,#192867,.T.); -#192867 = EDGE_CURVE('',#192845,#192297,#192868,.T.); -#192868 = SURFACE_CURVE('',#192869,(#192874,#192881),.PCURVE_S1.); -#192869 = CIRCLE('',#192870,0.2); -#192870 = AXIS2_PLACEMENT_3D('',#192871,#192872,#192873); -#192871 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); -#192872 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192873 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#192874 = PCURVE('',#185608,#192875); -#192875 = DEFINITIONAL_REPRESENTATION('',(#192876),#192880); -#192876 = CIRCLE('',#192877,0.2); -#192877 = AXIS2_PLACEMENT_2D('',#192878,#192879); -#192878 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192879 = DIRECTION('',(1.,0.E+000)); -#192880 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192881 = PCURVE('',#192335,#192882); -#192882 = DEFINITIONAL_REPRESENTATION('',(#192883),#192886); -#192883 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192884,#192885), +#195232 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#195233 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#195234 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195235 = ORIENTED_EDGE('',*,*,#195236,.T.); +#195236 = EDGE_CURVE('',#195210,#195237,#195239,.T.); +#195237 = VERTEX_POINT('',#195238); +#195238 = CARTESIAN_POINT('',(0.2,0.854004213739,0.571910405702)); +#195239 = SURFACE_CURVE('',#195240,(#195244,#195251),.PCURVE_S1.); +#195240 = LINE('',#195241,#195242); +#195241 = CARTESIAN_POINT('',(0.2,0.895598186972,0.194522398574)); +#195242 = VECTOR('',#195243,1.); +#195243 = DIRECTION('',(0.E+000,-0.109552028512,0.993981062721)); +#195244 = PCURVE('',#188000,#195245); +#195245 = DEFINITIONAL_REPRESENTATION('',(#195246),#195250); +#195246 = LINE('',#195247,#195248); +#195247 = CARTESIAN_POINT('',(0.355477601426,0.240390185778)); +#195248 = VECTOR('',#195249,1.); +#195249 = DIRECTION('',(-0.993981062721,-0.109552028512)); +#195250 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195251 = PCURVE('',#194826,#195252); +#195252 = DEFINITIONAL_REPRESENTATION('',(#195253),#195257); +#195253 = LINE('',#195254,#195255); +#195254 = CARTESIAN_POINT('',(0.E+000,0.4)); +#195255 = VECTOR('',#195256,1.); +#195256 = DIRECTION('',(1.,0.E+000)); +#195257 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195258 = ORIENTED_EDGE('',*,*,#195259,.T.); +#195259 = EDGE_CURVE('',#195237,#194689,#195260,.T.); +#195260 = SURFACE_CURVE('',#195261,(#195266,#195273),.PCURVE_S1.); +#195261 = CIRCLE('',#195262,0.2); +#195262 = AXIS2_PLACEMENT_3D('',#195263,#195264,#195265); +#195263 = CARTESIAN_POINT('',(0.2,0.655208001194,0.55)); +#195264 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195265 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#195266 = PCURVE('',#188000,#195267); +#195267 = DEFINITIONAL_REPRESENTATION('',(#195268),#195272); +#195268 = CIRCLE('',#195269,0.2); +#195269 = AXIS2_PLACEMENT_2D('',#195270,#195271); +#195270 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195271 = DIRECTION('',(1.,0.E+000)); +#195272 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195273 = PCURVE('',#194727,#195274); +#195274 = DEFINITIONAL_REPRESENTATION('',(#195275),#195278); +#195275 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195276,#195277), .UNSPECIFIED.,.F.,.F.,(2,2),(1.680568681447,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#192884 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#192885 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#192886 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192887 = ORIENTED_EDGE('',*,*,#192296,.T.); -#192888 = ADVANCED_FACE('',(#192889),#192335,.T.); -#192889 = FACE_BOUND('',#192890,.T.); -#192890 = EDGE_LOOP('',(#192891,#192892,#192893,#192913)); -#192891 = ORIENTED_EDGE('',*,*,#192319,.T.); -#192892 = ORIENTED_EDGE('',*,*,#192867,.F.); -#192893 = ORIENTED_EDGE('',*,*,#192894,.F.); -#192894 = EDGE_CURVE('',#192396,#192845,#192895,.T.); -#192895 = SURFACE_CURVE('',#192896,(#192900,#192906),.PCURVE_S1.); -#192896 = LINE('',#192897,#192898); -#192897 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); -#192898 = VECTOR('',#192899,1.); -#192899 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192900 = PCURVE('',#192335,#192901); -#192901 = DEFINITIONAL_REPRESENTATION('',(#192902),#192905); -#192902 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192903,#192904), +#195276 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#195277 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#195278 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195279 = ORIENTED_EDGE('',*,*,#194688,.T.); +#195280 = ADVANCED_FACE('',(#195281),#194727,.T.); +#195281 = FACE_BOUND('',#195282,.T.); +#195282 = EDGE_LOOP('',(#195283,#195284,#195285,#195305)); +#195283 = ORIENTED_EDGE('',*,*,#194711,.T.); +#195284 = ORIENTED_EDGE('',*,*,#195259,.F.); +#195285 = ORIENTED_EDGE('',*,*,#195286,.F.); +#195286 = EDGE_CURVE('',#194788,#195237,#195287,.T.); +#195287 = SURFACE_CURVE('',#195288,(#195292,#195298),.PCURVE_S1.); +#195288 = LINE('',#195289,#195290); +#195289 = CARTESIAN_POINT('',(-0.2,0.854004213739,0.571910405702)); +#195290 = VECTOR('',#195291,1.); +#195291 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195292 = PCURVE('',#194727,#195293); +#195293 = DEFINITIONAL_REPRESENTATION('',(#195294),#195297); +#195294 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195295,#195296), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192903 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#192904 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#192905 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192906 = PCURVE('',#192434,#192907); -#192907 = DEFINITIONAL_REPRESENTATION('',(#192908),#192912); -#192908 = LINE('',#192909,#192910); -#192909 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#192910 = VECTOR('',#192911,1.); -#192911 = DIRECTION('',(0.E+000,1.)); -#192912 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192913 = ORIENTED_EDGE('',*,*,#192395,.T.); -#192914 = ADVANCED_FACE('',(#192915),#192434,.T.); -#192915 = FACE_BOUND('',#192916,.T.); -#192916 = EDGE_LOOP('',(#192917,#192918,#192919,#192939)); -#192917 = ORIENTED_EDGE('',*,*,#192894,.T.); -#192918 = ORIENTED_EDGE('',*,*,#192844,.F.); -#192919 = ORIENTED_EDGE('',*,*,#192920,.F.); -#192920 = EDGE_CURVE('',#192419,#192818,#192921,.T.); -#192921 = SURFACE_CURVE('',#192922,(#192926,#192933),.PCURVE_S1.); -#192922 = LINE('',#192923,#192924); -#192923 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); -#192924 = VECTOR('',#192925,1.); -#192925 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192926 = PCURVE('',#192434,#192927); -#192927 = DEFINITIONAL_REPRESENTATION('',(#192928),#192932); -#192928 = LINE('',#192929,#192930); -#192929 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#192930 = VECTOR('',#192931,1.); -#192931 = DIRECTION('',(0.E+000,1.)); -#192932 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192933 = PCURVE('',#192467,#192934); -#192934 = DEFINITIONAL_REPRESENTATION('',(#192935),#192938); -#192935 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#192936,#192937), +#195295 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#195296 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#195297 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195298 = PCURVE('',#194826,#195299); +#195299 = DEFINITIONAL_REPRESENTATION('',(#195300),#195304); +#195300 = LINE('',#195301,#195302); +#195301 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#195302 = VECTOR('',#195303,1.); +#195303 = DIRECTION('',(0.E+000,1.)); +#195304 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195305 = ORIENTED_EDGE('',*,*,#194787,.T.); +#195306 = ADVANCED_FACE('',(#195307),#194826,.T.); +#195307 = FACE_BOUND('',#195308,.T.); +#195308 = EDGE_LOOP('',(#195309,#195310,#195311,#195331)); +#195309 = ORIENTED_EDGE('',*,*,#195286,.T.); +#195310 = ORIENTED_EDGE('',*,*,#195236,.F.); +#195311 = ORIENTED_EDGE('',*,*,#195312,.F.); +#195312 = EDGE_CURVE('',#194811,#195210,#195313,.T.); +#195313 = SURFACE_CURVE('',#195314,(#195318,#195325),.PCURVE_S1.); +#195314 = LINE('',#195315,#195316); +#195315 = CARTESIAN_POINT('',(-0.2,0.895598186972,0.194522398574)); +#195316 = VECTOR('',#195317,1.); +#195317 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195318 = PCURVE('',#194826,#195319); +#195319 = DEFINITIONAL_REPRESENTATION('',(#195320),#195324); +#195320 = LINE('',#195321,#195322); +#195321 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195322 = VECTOR('',#195323,1.); +#195323 = DIRECTION('',(0.E+000,1.)); +#195324 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195325 = PCURVE('',#194859,#195326); +#195326 = DEFINITIONAL_REPRESENTATION('',(#195327),#195330); +#195327 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195328,#195329), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#192936 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#192937 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#192938 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192939 = ORIENTED_EDGE('',*,*,#192418,.T.); -#192940 = ADVANCED_FACE('',(#192941),#192467,.F.); -#192941 = FACE_BOUND('',#192942,.F.); -#192942 = EDGE_LOOP('',(#192943,#192944,#192945,#192988)); -#192943 = ORIENTED_EDGE('',*,*,#192920,.F.); -#192944 = ORIENTED_EDGE('',*,*,#192446,.F.); -#192945 = ORIENTED_EDGE('',*,*,#192946,.T.); -#192946 = EDGE_CURVE('',#192447,#192795,#192947,.T.); -#192947 = SURFACE_CURVE('',#192948,(#192952,#192981),.PCURVE_S1.); -#192948 = LINE('',#192949,#192950); -#192949 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); -#192950 = VECTOR('',#192951,1.); -#192951 = DIRECTION('',(1.,0.E+000,0.E+000)); -#192952 = PCURVE('',#192467,#192953); -#192953 = DEFINITIONAL_REPRESENTATION('',(#192954),#192980); -#192954 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#192955,#192956,#192957, - #192958,#192959,#192960,#192961,#192962,#192963,#192964,#192965, - #192966,#192967,#192968,#192969,#192970,#192971,#192972,#192973, - #192974,#192975,#192976,#192977,#192978,#192979),.UNSPECIFIED.,.F., +#195328 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#195329 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#195330 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195331 = ORIENTED_EDGE('',*,*,#194810,.T.); +#195332 = ADVANCED_FACE('',(#195333),#194859,.F.); +#195333 = FACE_BOUND('',#195334,.F.); +#195334 = EDGE_LOOP('',(#195335,#195336,#195337,#195380)); +#195335 = ORIENTED_EDGE('',*,*,#195312,.F.); +#195336 = ORIENTED_EDGE('',*,*,#194838,.F.); +#195337 = ORIENTED_EDGE('',*,*,#195338,.T.); +#195338 = EDGE_CURVE('',#194839,#195187,#195339,.T.); +#195339 = SURFACE_CURVE('',#195340,(#195344,#195373),.PCURVE_S1.); +#195340 = LINE('',#195341,#195342); +#195341 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.15)); +#195342 = VECTOR('',#195343,1.); +#195343 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195344 = PCURVE('',#194859,#195345); +#195345 = DEFINITIONAL_REPRESENTATION('',(#195346),#195372); +#195346 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195347,#195348,#195349, + #195350,#195351,#195352,#195353,#195354,#195355,#195356,#195357, + #195358,#195359,#195360,#195361,#195362,#195363,#195364,#195365, + #195366,#195367,#195368,#195369,#195370,#195371),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -239635,133 +242637,133 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#192955 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#192956 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#192957 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#192958 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#192959 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#192960 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#192961 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#192962 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#192963 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#192964 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#192965 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#192966 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#192967 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#192968 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#192969 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#192970 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#192971 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#192972 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#192973 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#192974 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#192975 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#192976 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#192977 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#192978 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#192979 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#192980 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192981 = PCURVE('',#192494,#192982); -#192982 = DEFINITIONAL_REPRESENTATION('',(#192983),#192987); -#192983 = LINE('',#192984,#192985); -#192984 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#192985 = VECTOR('',#192986,1.); -#192986 = DIRECTION('',(1.,0.E+000)); -#192987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#192988 = ORIENTED_EDGE('',*,*,#192817,.T.); -#192989 = ADVANCED_FACE('',(#192990),#192494,.T.); -#192990 = FACE_BOUND('',#192991,.T.); -#192991 = EDGE_LOOP('',(#192992,#192993,#192994,#193015)); -#192992 = ORIENTED_EDGE('',*,*,#192946,.T.); -#192993 = ORIENTED_EDGE('',*,*,#192794,.F.); -#192994 = ORIENTED_EDGE('',*,*,#192995,.F.); -#192995 = EDGE_CURVE('',#192479,#192772,#192996,.T.); -#192996 = SURFACE_CURVE('',#192997,(#193001,#193008),.PCURVE_S1.); -#192997 = LINE('',#192998,#192999); -#192998 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); -#192999 = VECTOR('',#193000,1.); -#193000 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193001 = PCURVE('',#192494,#193002); -#193002 = DEFINITIONAL_REPRESENTATION('',(#193003),#193007); -#193003 = LINE('',#193004,#193005); -#193004 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#193005 = VECTOR('',#193006,1.); -#193006 = DIRECTION('',(1.,0.E+000)); -#193007 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193008 = PCURVE('',#192522,#193009); -#193009 = DEFINITIONAL_REPRESENTATION('',(#193010),#193014); -#193010 = LINE('',#193011,#193012); -#193011 = CARTESIAN_POINT('',(0.15,0.E+000)); -#193012 = VECTOR('',#193013,1.); -#193013 = DIRECTION('',(0.E+000,1.)); -#193014 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193015 = ORIENTED_EDGE('',*,*,#192478,.T.); -#193016 = ADVANCED_FACE('',(#193017),#192522,.T.); -#193017 = FACE_BOUND('',#193018,.T.); -#193018 = EDGE_LOOP('',(#193019,#193020,#193021,#193042)); -#193019 = ORIENTED_EDGE('',*,*,#192995,.T.); -#193020 = ORIENTED_EDGE('',*,*,#192771,.F.); -#193021 = ORIENTED_EDGE('',*,*,#193022,.F.); -#193022 = EDGE_CURVE('',#192507,#192749,#193023,.T.); -#193023 = SURFACE_CURVE('',#193024,(#193028,#193035),.PCURVE_S1.); -#193024 = LINE('',#193025,#193026); -#193025 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); -#193026 = VECTOR('',#193027,1.); -#193027 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193028 = PCURVE('',#192522,#193029); -#193029 = DEFINITIONAL_REPRESENTATION('',(#193030),#193034); -#193030 = LINE('',#193031,#193032); -#193031 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#193032 = VECTOR('',#193033,1.); -#193033 = DIRECTION('',(0.E+000,1.)); -#193034 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193035 = PCURVE('',#192550,#193036); -#193036 = DEFINITIONAL_REPRESENTATION('',(#193037),#193041); -#193037 = LINE('',#193038,#193039); -#193038 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#193039 = VECTOR('',#193040,1.); -#193040 = DIRECTION('',(-1.,0.E+000)); -#193041 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193042 = ORIENTED_EDGE('',*,*,#192506,.T.); -#193043 = ADVANCED_FACE('',(#193044),#192550,.T.); -#193044 = FACE_BOUND('',#193045,.T.); -#193045 = EDGE_LOOP('',(#193046,#193047,#193048,#193091)); -#193046 = ORIENTED_EDGE('',*,*,#193022,.T.); -#193047 = ORIENTED_EDGE('',*,*,#192748,.F.); -#193048 = ORIENTED_EDGE('',*,*,#193049,.F.); -#193049 = EDGE_CURVE('',#192535,#192726,#193050,.T.); -#193050 = SURFACE_CURVE('',#193051,(#193055,#193062),.PCURVE_S1.); -#193051 = LINE('',#193052,#193053); -#193052 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); -#193053 = VECTOR('',#193054,1.); -#193054 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193055 = PCURVE('',#192550,#193056); -#193056 = DEFINITIONAL_REPRESENTATION('',(#193057),#193061); -#193057 = LINE('',#193058,#193059); -#193058 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); -#193059 = VECTOR('',#193060,1.); -#193060 = DIRECTION('',(-1.,0.E+000)); -#193061 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193062 = PCURVE('',#192579,#193063); -#193063 = DEFINITIONAL_REPRESENTATION('',(#193064),#193090); -#193064 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193065,#193066,#193067, - #193068,#193069,#193070,#193071,#193072,#193073,#193074,#193075, - #193076,#193077,#193078,#193079,#193080,#193081,#193082,#193083, - #193084,#193085,#193086,#193087,#193088,#193089),.UNSPECIFIED.,.F., +#195347 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#195348 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#195349 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#195350 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#195351 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#195352 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#195353 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#195354 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#195355 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#195356 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#195357 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#195358 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#195359 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#195360 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#195361 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#195362 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#195363 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#195364 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#195365 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#195366 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#195367 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#195368 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#195369 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#195370 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#195371 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#195372 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195373 = PCURVE('',#194886,#195374); +#195374 = DEFINITIONAL_REPRESENTATION('',(#195375),#195379); +#195375 = LINE('',#195376,#195377); +#195376 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#195377 = VECTOR('',#195378,1.); +#195378 = DIRECTION('',(1.,0.E+000)); +#195379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195380 = ORIENTED_EDGE('',*,*,#195209,.T.); +#195381 = ADVANCED_FACE('',(#195382),#194886,.T.); +#195382 = FACE_BOUND('',#195383,.T.); +#195383 = EDGE_LOOP('',(#195384,#195385,#195386,#195407)); +#195384 = ORIENTED_EDGE('',*,*,#195338,.T.); +#195385 = ORIENTED_EDGE('',*,*,#195186,.F.); +#195386 = ORIENTED_EDGE('',*,*,#195387,.F.); +#195387 = EDGE_CURVE('',#194871,#195164,#195388,.T.); +#195388 = SURFACE_CURVE('',#195389,(#195393,#195400),.PCURVE_S1.); +#195389 = LINE('',#195390,#195391); +#195390 = CARTESIAN_POINT('',(-0.2,1.17,0.15)); +#195391 = VECTOR('',#195392,1.); +#195392 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195393 = PCURVE('',#194886,#195394); +#195394 = DEFINITIONAL_REPRESENTATION('',(#195395),#195399); +#195395 = LINE('',#195396,#195397); +#195396 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195397 = VECTOR('',#195398,1.); +#195398 = DIRECTION('',(1.,0.E+000)); +#195399 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195400 = PCURVE('',#194914,#195401); +#195401 = DEFINITIONAL_REPRESENTATION('',(#195402),#195406); +#195402 = LINE('',#195403,#195404); +#195403 = CARTESIAN_POINT('',(0.15,0.E+000)); +#195404 = VECTOR('',#195405,1.); +#195405 = DIRECTION('',(0.E+000,1.)); +#195406 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195407 = ORIENTED_EDGE('',*,*,#194870,.T.); +#195408 = ADVANCED_FACE('',(#195409),#194914,.T.); +#195409 = FACE_BOUND('',#195410,.T.); +#195410 = EDGE_LOOP('',(#195411,#195412,#195413,#195434)); +#195411 = ORIENTED_EDGE('',*,*,#195387,.T.); +#195412 = ORIENTED_EDGE('',*,*,#195163,.F.); +#195413 = ORIENTED_EDGE('',*,*,#195414,.F.); +#195414 = EDGE_CURVE('',#194899,#195141,#195415,.T.); +#195415 = SURFACE_CURVE('',#195416,(#195420,#195427),.PCURVE_S1.); +#195416 = LINE('',#195417,#195418); +#195417 = CARTESIAN_POINT('',(-0.2,1.17,0.E+000)); +#195418 = VECTOR('',#195419,1.); +#195419 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195420 = PCURVE('',#194914,#195421); +#195421 = DEFINITIONAL_REPRESENTATION('',(#195422),#195426); +#195422 = LINE('',#195423,#195424); +#195423 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195424 = VECTOR('',#195425,1.); +#195425 = DIRECTION('',(0.E+000,1.)); +#195426 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195427 = PCURVE('',#194942,#195428); +#195428 = DEFINITIONAL_REPRESENTATION('',(#195429),#195433); +#195429 = LINE('',#195430,#195431); +#195430 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195431 = VECTOR('',#195432,1.); +#195432 = DIRECTION('',(-1.,0.E+000)); +#195433 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195434 = ORIENTED_EDGE('',*,*,#194898,.T.); +#195435 = ADVANCED_FACE('',(#195436),#194942,.T.); +#195436 = FACE_BOUND('',#195437,.T.); +#195437 = EDGE_LOOP('',(#195438,#195439,#195440,#195483)); +#195438 = ORIENTED_EDGE('',*,*,#195414,.T.); +#195439 = ORIENTED_EDGE('',*,*,#195140,.F.); +#195440 = ORIENTED_EDGE('',*,*,#195441,.F.); +#195441 = EDGE_CURVE('',#194927,#195118,#195442,.T.); +#195442 = SURFACE_CURVE('',#195443,(#195447,#195454),.PCURVE_S1.); +#195443 = LINE('',#195444,#195445); +#195444 = CARTESIAN_POINT('',(-0.2,0.945297240108,0.E+000)); +#195445 = VECTOR('',#195446,1.); +#195446 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195447 = PCURVE('',#194942,#195448); +#195448 = DEFINITIONAL_REPRESENTATION('',(#195449),#195453); +#195449 = LINE('',#195450,#195451); +#195450 = CARTESIAN_POINT('',(0.E+000,-0.224702759892)); +#195451 = VECTOR('',#195452,1.); +#195452 = DIRECTION('',(-1.,0.E+000)); +#195453 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195454 = PCURVE('',#194971,#195455); +#195455 = DEFINITIONAL_REPRESENTATION('',(#195456),#195482); +#195456 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195457,#195458,#195459, + #195460,#195461,#195462,#195463,#195464,#195465,#195466,#195467, + #195468,#195469,#195470,#195471,#195472,#195473,#195474,#195475, + #195476,#195477,#195478,#195479,#195480,#195481),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 1.818181818182E-002,3.636363636364E-002,5.454545454545E-002, 7.272727272727E-002,9.090909090909E-002,0.109090909091, @@ -239769,161 +242771,161 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.218181818182,0.236363636364,0.254545454545,0.272727272727, 0.290909090909,0.309090909091,0.327272727273,0.345454545455, 0.363636363636,0.381818181818,0.4),.QUASI_UNIFORM_KNOTS.); -#193065 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); -#193066 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); -#193067 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); -#193068 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); -#193069 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); -#193070 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); -#193071 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); -#193072 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); -#193073 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); -#193074 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); -#193075 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); -#193076 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); -#193077 = CARTESIAN_POINT('',(6.28318530718,0.2)); -#193078 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); -#193079 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); -#193080 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); -#193081 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); -#193082 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); -#193083 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); -#193084 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); -#193085 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); -#193086 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); -#193087 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); -#193088 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); -#193089 = CARTESIAN_POINT('',(6.28318530718,0.4)); -#193090 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193091 = ORIENTED_EDGE('',*,*,#192534,.T.); -#193092 = ADVANCED_FACE('',(#193093),#192579,.T.); -#193093 = FACE_BOUND('',#193094,.T.); -#193094 = EDGE_LOOP('',(#193095,#193096,#193097,#193117)); -#193095 = ORIENTED_EDGE('',*,*,#193049,.T.); -#193096 = ORIENTED_EDGE('',*,*,#192725,.F.); -#193097 = ORIENTED_EDGE('',*,*,#193098,.F.); -#193098 = EDGE_CURVE('',#192563,#192703,#193099,.T.); -#193099 = SURFACE_CURVE('',#193100,(#193104,#193110),.PCURVE_S1.); -#193100 = LINE('',#193101,#193102); -#193101 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); -#193102 = VECTOR('',#193103,1.); -#193103 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193104 = PCURVE('',#192579,#193105); -#193105 = DEFINITIONAL_REPRESENTATION('',(#193106),#193109); -#193106 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193107,#193108), +#195457 = CARTESIAN_POINT('',(6.28318530718,0.E+000)); +#195458 = CARTESIAN_POINT('',(6.28318530718,6.060606060606E-003)); +#195459 = CARTESIAN_POINT('',(6.28318530718,1.818181818182E-002)); +#195460 = CARTESIAN_POINT('',(6.28318530718,3.636363636364E-002)); +#195461 = CARTESIAN_POINT('',(6.28318530718,5.454545454545E-002)); +#195462 = CARTESIAN_POINT('',(6.28318530718,7.272727272727E-002)); +#195463 = CARTESIAN_POINT('',(6.28318530718,9.090909090909E-002)); +#195464 = CARTESIAN_POINT('',(6.28318530718,0.109090909091)); +#195465 = CARTESIAN_POINT('',(6.28318530718,0.127272727273)); +#195466 = CARTESIAN_POINT('',(6.28318530718,0.145454545455)); +#195467 = CARTESIAN_POINT('',(6.28318530718,0.163636363636)); +#195468 = CARTESIAN_POINT('',(6.28318530718,0.181818181818)); +#195469 = CARTESIAN_POINT('',(6.28318530718,0.2)); +#195470 = CARTESIAN_POINT('',(6.28318530718,0.218181818182)); +#195471 = CARTESIAN_POINT('',(6.28318530718,0.236363636364)); +#195472 = CARTESIAN_POINT('',(6.28318530718,0.254545454545)); +#195473 = CARTESIAN_POINT('',(6.28318530718,0.272727272727)); +#195474 = CARTESIAN_POINT('',(6.28318530718,0.290909090909)); +#195475 = CARTESIAN_POINT('',(6.28318530718,0.309090909091)); +#195476 = CARTESIAN_POINT('',(6.28318530718,0.327272727273)); +#195477 = CARTESIAN_POINT('',(6.28318530718,0.345454545455)); +#195478 = CARTESIAN_POINT('',(6.28318530718,0.363636363636)); +#195479 = CARTESIAN_POINT('',(6.28318530718,0.381818181818)); +#195480 = CARTESIAN_POINT('',(6.28318530718,0.393939393939)); +#195481 = CARTESIAN_POINT('',(6.28318530718,0.4)); +#195482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195483 = ORIENTED_EDGE('',*,*,#194926,.T.); +#195484 = ADVANCED_FACE('',(#195485),#194971,.T.); +#195485 = FACE_BOUND('',#195486,.T.); +#195486 = EDGE_LOOP('',(#195487,#195488,#195489,#195509)); +#195487 = ORIENTED_EDGE('',*,*,#195441,.T.); +#195488 = ORIENTED_EDGE('',*,*,#195117,.F.); +#195489 = ORIENTED_EDGE('',*,*,#195490,.F.); +#195490 = EDGE_CURVE('',#194955,#195095,#195491,.T.); +#195491 = SURFACE_CURVE('',#195492,(#195496,#195502),.PCURVE_S1.); +#195492 = LINE('',#195493,#195494); +#195493 = CARTESIAN_POINT('',(-0.2,0.746501027564,0.178089594298)); +#195494 = VECTOR('',#195495,1.); +#195495 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195496 = PCURVE('',#194971,#195497); +#195497 = DEFINITIONAL_REPRESENTATION('',(#195498),#195501); +#195498 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195499,#195500), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#193107 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); -#193108 = CARTESIAN_POINT('',(4.822161335036,0.4)); -#193109 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193110 = PCURVE('',#192606,#193111); -#193111 = DEFINITIONAL_REPRESENTATION('',(#193112),#193116); -#193112 = LINE('',#193113,#193114); -#193113 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); -#193114 = VECTOR('',#193115,1.); -#193115 = DIRECTION('',(0.E+000,1.)); -#193116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193117 = ORIENTED_EDGE('',*,*,#192562,.T.); -#193118 = ADVANCED_FACE('',(#193119),#192606,.T.); -#193119 = FACE_BOUND('',#193120,.T.); -#193120 = EDGE_LOOP('',(#193121,#193122,#193123,#193143)); -#193121 = ORIENTED_EDGE('',*,*,#193098,.T.); -#193122 = ORIENTED_EDGE('',*,*,#192702,.F.); -#193123 = ORIENTED_EDGE('',*,*,#193124,.F.); -#193124 = EDGE_CURVE('',#192591,#192676,#193125,.T.); -#193125 = SURFACE_CURVE('',#193126,(#193130,#193137),.PCURVE_S1.); -#193126 = LINE('',#193127,#193128); -#193127 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); -#193128 = VECTOR('',#193129,1.); -#193129 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193130 = PCURVE('',#192606,#193131); -#193131 = DEFINITIONAL_REPRESENTATION('',(#193132),#193136); -#193132 = LINE('',#193133,#193134); -#193133 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#193134 = VECTOR('',#193135,1.); -#193135 = DIRECTION('',(0.E+000,1.)); -#193136 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193137 = PCURVE('',#192637,#193138); -#193138 = DEFINITIONAL_REPRESENTATION('',(#193139),#193142); -#193139 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193140,#193141), +#195499 = CARTESIAN_POINT('',(4.822161335036,0.E+000)); +#195500 = CARTESIAN_POINT('',(4.822161335036,0.4)); +#195501 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195502 = PCURVE('',#194998,#195503); +#195503 = DEFINITIONAL_REPRESENTATION('',(#195504),#195508); +#195504 = LINE('',#195505,#195506); +#195505 = CARTESIAN_POINT('',(0.379673236525,0.E+000)); +#195506 = VECTOR('',#195507,1.); +#195507 = DIRECTION('',(0.E+000,1.)); +#195508 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195509 = ORIENTED_EDGE('',*,*,#194954,.T.); +#195510 = ADVANCED_FACE('',(#195511),#194998,.T.); +#195511 = FACE_BOUND('',#195512,.T.); +#195512 = EDGE_LOOP('',(#195513,#195514,#195515,#195535)); +#195513 = ORIENTED_EDGE('',*,*,#195490,.T.); +#195514 = ORIENTED_EDGE('',*,*,#195094,.F.); +#195515 = ORIENTED_EDGE('',*,*,#195516,.F.); +#195516 = EDGE_CURVE('',#194983,#195068,#195517,.T.); +#195517 = SURFACE_CURVE('',#195518,(#195522,#195529),.PCURVE_S1.); +#195518 = LINE('',#195519,#195520); +#195519 = CARTESIAN_POINT('',(-0.2,0.70490705433,0.555477601426)); +#195520 = VECTOR('',#195521,1.); +#195521 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195522 = PCURVE('',#194998,#195523); +#195523 = DEFINITIONAL_REPRESENTATION('',(#195524),#195528); +#195524 = LINE('',#195525,#195526); +#195525 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195526 = VECTOR('',#195527,1.); +#195527 = DIRECTION('',(0.E+000,1.)); +#195528 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195529 = PCURVE('',#195029,#195530); +#195530 = DEFINITIONAL_REPRESENTATION('',(#195531),#195534); +#195531 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195532,#195533), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#193140 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); -#193141 = CARTESIAN_POINT('',(1.680568681447,0.4)); -#193142 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193143 = ORIENTED_EDGE('',*,*,#192590,.T.); -#193144 = ADVANCED_FACE('',(#193145),#192637,.F.); -#193145 = FACE_BOUND('',#193146,.F.); -#193146 = EDGE_LOOP('',(#193147,#193148,#193149,#193169)); -#193147 = ORIENTED_EDGE('',*,*,#193124,.F.); -#193148 = ORIENTED_EDGE('',*,*,#192618,.F.); -#193149 = ORIENTED_EDGE('',*,*,#193150,.T.); -#193150 = EDGE_CURVE('',#192371,#192653,#193151,.T.); -#193151 = SURFACE_CURVE('',#193152,(#193156,#193162),.PCURVE_S1.); -#193152 = LINE('',#193153,#193154); -#193153 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); -#193154 = VECTOR('',#193155,1.); -#193155 = DIRECTION('',(1.,0.E+000,0.E+000)); -#193156 = PCURVE('',#192637,#193157); -#193157 = DEFINITIONAL_REPRESENTATION('',(#193158),#193161); -#193158 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#193159,#193160), +#195532 = CARTESIAN_POINT('',(1.680568681447,0.E+000)); +#195533 = CARTESIAN_POINT('',(1.680568681447,0.4)); +#195534 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195535 = ORIENTED_EDGE('',*,*,#194982,.T.); +#195536 = ADVANCED_FACE('',(#195537),#195029,.F.); +#195537 = FACE_BOUND('',#195538,.F.); +#195538 = EDGE_LOOP('',(#195539,#195540,#195541,#195561)); +#195539 = ORIENTED_EDGE('',*,*,#195516,.F.); +#195540 = ORIENTED_EDGE('',*,*,#195010,.F.); +#195541 = ORIENTED_EDGE('',*,*,#195542,.T.); +#195542 = EDGE_CURVE('',#194763,#195045,#195543,.T.); +#195543 = SURFACE_CURVE('',#195544,(#195548,#195554),.PCURVE_S1.); +#195544 = LINE('',#195545,#195546); +#195545 = CARTESIAN_POINT('',(-0.2,0.655208001194,0.6)); +#195546 = VECTOR('',#195547,1.); +#195547 = DIRECTION('',(1.,0.E+000,0.E+000)); +#195548 = PCURVE('',#195029,#195549); +#195549 = DEFINITIONAL_REPRESENTATION('',(#195550),#195553); +#195550 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#195551,#195552), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,0.4),.PIECEWISE_BEZIER_KNOTS.); -#193159 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); -#193160 = CARTESIAN_POINT('',(3.14159265359,0.4)); -#193161 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193162 = PCURVE('',#186886,#193163); -#193163 = DEFINITIONAL_REPRESENTATION('',(#193164),#193168); -#193164 = LINE('',#193165,#193166); -#193165 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#193166 = VECTOR('',#193167,1.); -#193167 = DIRECTION('',(-1.,0.E+000)); -#193168 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193169 = ORIENTED_EDGE('',*,*,#192675,.T.); -#193170 = ADVANCED_FACE('',(#193171),#186886,.T.); -#193171 = FACE_BOUND('',#193172,.T.); -#193172 = EDGE_LOOP('',(#193173,#193174,#193175,#193176)); -#193173 = ORIENTED_EDGE('',*,*,#192652,.F.); -#193174 = ORIENTED_EDGE('',*,*,#186872,.T.); -#193175 = ORIENTED_EDGE('',*,*,#192370,.T.); -#193176 = ORIENTED_EDGE('',*,*,#193150,.T.); -#193177 = ADVANCED_FACE('',(#193178),#184118,.T.); -#193178 = FACE_BOUND('',#193179,.T.); -#193179 = EDGE_LOOP('',(#193180,#193181,#193247,#193248,#193249)); -#193180 = ORIENTED_EDGE('',*,*,#185856,.F.); -#193181 = ORIENTED_EDGE('',*,*,#193182,.T.); -#193182 = EDGE_CURVE('',#185835,#184061,#193183,.T.); -#193183 = SURFACE_CURVE('',#193184,(#193189,#193218),.PCURVE_S1.); -#193184 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193185,#193186,#193187, -#193188),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195551 = CARTESIAN_POINT('',(3.14159265359,0.E+000)); +#195552 = CARTESIAN_POINT('',(3.14159265359,0.4)); +#195553 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195554 = PCURVE('',#189278,#195555); +#195555 = DEFINITIONAL_REPRESENTATION('',(#195556),#195560); +#195556 = LINE('',#195557,#195558); +#195557 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#195558 = VECTOR('',#195559,1.); +#195559 = DIRECTION('',(-1.,0.E+000)); +#195560 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195561 = ORIENTED_EDGE('',*,*,#195067,.T.); +#195562 = ADVANCED_FACE('',(#195563),#189278,.T.); +#195563 = FACE_BOUND('',#195564,.T.); +#195564 = EDGE_LOOP('',(#195565,#195566,#195567,#195568)); +#195565 = ORIENTED_EDGE('',*,*,#195044,.F.); +#195566 = ORIENTED_EDGE('',*,*,#189264,.T.); +#195567 = ORIENTED_EDGE('',*,*,#194762,.T.); +#195568 = ORIENTED_EDGE('',*,*,#195542,.T.); +#195569 = ADVANCED_FACE('',(#195570),#186510,.T.); +#195570 = FACE_BOUND('',#195571,.T.); +#195571 = EDGE_LOOP('',(#195572,#195573,#195639,#195640,#195641)); +#195572 = ORIENTED_EDGE('',*,*,#188248,.F.); +#195573 = ORIENTED_EDGE('',*,*,#195574,.T.); +#195574 = EDGE_CURVE('',#188227,#186453,#195575,.T.); +#195575 = SURFACE_CURVE('',#195576,(#195581,#195610),.PCURVE_S1.); +#195576 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195577,#195578,#195579, +#195580),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193185 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, +#195577 = CARTESIAN_POINT('',(-1.217861391,-0.552750264943, 0.962940952255)); -#193186 = CARTESIAN_POINT('',(-1.25680534294,-0.551917855478, +#195578 = CARTESIAN_POINT('',(-1.25680534294,-0.551917855478, 0.966047546673)); -#193187 = CARTESIAN_POINT('',(-1.292375921036,-0.53683376285,0.967717466 +#195579 = CARTESIAN_POINT('',(-1.292375921036,-0.53683376285,0.967717466 )); -#193188 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, +#195580 = CARTESIAN_POINT('',(-1.319604841943,-0.509604841943, 0.967717466)); -#193189 = PCURVE('',#184118,#193190); -#193190 = DEFINITIONAL_REPRESENTATION('',(#193191),#193217); -#193191 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193192,#193193,#193194, - #193195,#193196,#193197,#193198,#193199,#193200,#193201,#193202, - #193203,#193204,#193205,#193206,#193207,#193208,#193209,#193210, - #193211,#193212,#193213,#193214,#193215,#193216),.UNSPECIFIED.,.F., +#195581 = PCURVE('',#186510,#195582); +#195582 = DEFINITIONAL_REPRESENTATION('',(#195583),#195609); +#195583 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195584,#195585,#195586, + #195587,#195588,#195589,#195590,#195591,#195592,#195593,#195594, + #195595,#195596,#195597,#195598,#195599,#195600,#195601,#195602, + #195603,#195604,#195605,#195606,#195607,#195608),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -239931,40 +242933,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193192 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); -#193193 = CARTESIAN_POINT('',(4.790552085824,-0.424140987131)); -#193194 = CARTESIAN_POINT('',(4.812874135705,-0.423573537911)); -#193195 = CARTESIAN_POINT('',(4.846552114392,-0.422749662917)); -#193196 = CARTESIAN_POINT('',(4.880407630888,-0.421955010917)); -#193197 = CARTESIAN_POINT('',(4.914422492066,-0.421191423422)); -#193198 = CARTESIAN_POINT('',(4.948578027862,-0.420460671856)); -#193199 = CARTESIAN_POINT('',(4.98285506838,-0.419764438636)); -#193200 = CARTESIAN_POINT('',(5.017234026195,-0.419104307248)); -#193201 = CARTESIAN_POINT('',(5.051694955172,-0.418481750684)); -#193202 = CARTESIAN_POINT('',(5.086217619636,-0.41789812127)); -#193203 = CARTESIAN_POINT('',(5.120781564146,-0.417354641276)); -#193204 = CARTESIAN_POINT('',(5.155366185737,-0.416852394634)); -#193205 = CARTESIAN_POINT('',(5.189950807328,-0.416392319824)); -#193206 = CARTESIAN_POINT('',(5.224514751839,-0.415975204048)); -#193207 = CARTESIAN_POINT('',(5.259037416303,-0.415601678753)); -#193208 = CARTESIAN_POINT('',(5.293498345279,-0.41527221657)); -#193209 = CARTESIAN_POINT('',(5.327877303094,-0.414987129667)); -#193210 = CARTESIAN_POINT('',(5.362154343612,-0.414746569643)); -#193211 = CARTESIAN_POINT('',(5.396309879408,-0.414550528448)); -#193212 = CARTESIAN_POINT('',(5.430324740587,-0.414398842232)); -#193213 = CARTESIAN_POINT('',(5.464180257082,-0.414291190685)); -#193214 = CARTESIAN_POINT('',(5.49785823577,-0.414227119403)); -#193215 = CARTESIAN_POINT('',(5.52018028565,-0.414213027833)); -#193216 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); -#193217 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193218 = PCURVE('',#184191,#193219); -#193219 = DEFINITIONAL_REPRESENTATION('',(#193220),#193246); -#193220 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193221,#193222,#193223, - #193224,#193225,#193226,#193227,#193228,#193229,#193230,#193231, - #193232,#193233,#193234,#193235,#193236,#193237,#193238,#193239, - #193240,#193241,#193242,#193243,#193244,#193245),.UNSPECIFIED.,.F., +#195584 = CARTESIAN_POINT('',(4.77942647859,-0.424428944789)); +#195585 = CARTESIAN_POINT('',(4.790552085824,-0.424140987131)); +#195586 = CARTESIAN_POINT('',(4.812874135705,-0.423573537911)); +#195587 = CARTESIAN_POINT('',(4.846552114392,-0.422749662917)); +#195588 = CARTESIAN_POINT('',(4.880407630888,-0.421955010917)); +#195589 = CARTESIAN_POINT('',(4.914422492066,-0.421191423422)); +#195590 = CARTESIAN_POINT('',(4.948578027862,-0.420460671856)); +#195591 = CARTESIAN_POINT('',(4.98285506838,-0.419764438636)); +#195592 = CARTESIAN_POINT('',(5.017234026195,-0.419104307248)); +#195593 = CARTESIAN_POINT('',(5.051694955172,-0.418481750684)); +#195594 = CARTESIAN_POINT('',(5.086217619636,-0.41789812127)); +#195595 = CARTESIAN_POINT('',(5.120781564146,-0.417354641276)); +#195596 = CARTESIAN_POINT('',(5.155366185737,-0.416852394634)); +#195597 = CARTESIAN_POINT('',(5.189950807328,-0.416392319824)); +#195598 = CARTESIAN_POINT('',(5.224514751839,-0.415975204048)); +#195599 = CARTESIAN_POINT('',(5.259037416303,-0.415601678753)); +#195600 = CARTESIAN_POINT('',(5.293498345279,-0.41527221657)); +#195601 = CARTESIAN_POINT('',(5.327877303094,-0.414987129667)); +#195602 = CARTESIAN_POINT('',(5.362154343612,-0.414746569643)); +#195603 = CARTESIAN_POINT('',(5.396309879408,-0.414550528448)); +#195604 = CARTESIAN_POINT('',(5.430324740587,-0.414398842232)); +#195605 = CARTESIAN_POINT('',(5.464180257082,-0.414291190685)); +#195606 = CARTESIAN_POINT('',(5.49785823577,-0.414227119403)); +#195607 = CARTESIAN_POINT('',(5.52018028565,-0.414213027833)); +#195608 = CARTESIAN_POINT('',(5.531305892885,-0.41421303912)); +#195609 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195610 = PCURVE('',#186583,#195611); +#195611 = DEFINITIONAL_REPRESENTATION('',(#195612),#195638); +#195612 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195613,#195614,#195615, + #195616,#195617,#195618,#195619,#195620,#195621,#195622,#195623, + #195624,#195625,#195626,#195627,#195628,#195629,#195630,#195631, + #195632,#195633,#195634,#195635,#195636,#195637),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -239972,56 +242974,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193221 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#193222 = CARTESIAN_POINT('',(0.740753686901,5.702886578311E-008)); -#193223 = CARTESIAN_POINT('',(0.718425946423,-7.920748674994E-006)); -#193224 = CARTESIAN_POINT('',(0.684729502771,-3.211524038325E-005)); -#193225 = CARTESIAN_POINT('',(0.650851510181,-9.135957813192E-005)); -#193226 = CARTESIAN_POINT('',(0.616817843149,-8.643182884289E-005)); -#193227 = CARTESIAN_POINT('',(0.582648204501,-8.687405903415E-005)); -#193228 = CARTESIAN_POINT('',(0.548364026633,-8.593542635494E-005)); -#193229 = CARTESIAN_POINT('',(0.513985713405,-8.542361824737E-005)); -#193230 = CARTESIAN_POINT('',(0.479533105651,-8.48530842991E-005)); -#193231 = CARTESIAN_POINT('',(0.445025477762,-8.435280861152E-005)); -#193232 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); -#193233 = CARTESIAN_POINT('',(0.375920232966,-8.346461194622E-005)); -#193234 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); -#193235 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); -#193236 = CARTESIAN_POINT('',(0.272313393703,-8.242390084137E-005)); -#193237 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#193238 = CARTESIAN_POINT('',(0.203491552027,-8.179989506531E-005)); -#193239 = CARTESIAN_POINT('',(0.169212469737,-8.226451401246E-005)); -#193240 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); -#193241 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); -#193242 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095812E-005) - ); -#193243 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467631E-005) - ); -#193244 = CARTESIAN_POINT('',(1.112575605159E-002,2.97280413299E-006)); -#193245 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#193246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193247 = ORIENTED_EDGE('',*,*,#184060,.T.); -#193248 = ORIENTED_EDGE('',*,*,#187362,.F.); -#193249 = ORIENTED_EDGE('',*,*,#193250,.F.); -#193250 = EDGE_CURVE('',#185857,#186686,#193251,.T.); -#193251 = SURFACE_CURVE('',#193252,(#193257,#193286),.PCURVE_S1.); -#193252 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193253,#193254,#193255, -#193256),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195613 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#195614 = CARTESIAN_POINT('',(0.740753686901,5.702886578311E-008)); +#195615 = CARTESIAN_POINT('',(0.718425946423,-7.920748674994E-006)); +#195616 = CARTESIAN_POINT('',(0.684729502771,-3.211524038325E-005)); +#195617 = CARTESIAN_POINT('',(0.650851510181,-9.135957813192E-005)); +#195618 = CARTESIAN_POINT('',(0.616817843149,-8.643182884289E-005)); +#195619 = CARTESIAN_POINT('',(0.582648204501,-8.687405903415E-005)); +#195620 = CARTESIAN_POINT('',(0.548364026633,-8.593542635494E-005)); +#195621 = CARTESIAN_POINT('',(0.513985713405,-8.542361824737E-005)); +#195622 = CARTESIAN_POINT('',(0.479533105651,-8.48530842991E-005)); +#195623 = CARTESIAN_POINT('',(0.445025477762,-8.435280861152E-005)); +#195624 = CARTESIAN_POINT('',(0.410481676253,-8.388702468128E-005)); +#195625 = CARTESIAN_POINT('',(0.375920232966,-8.346461194622E-005)); +#195626 = CARTESIAN_POINT('',(0.341359494752,-8.308081521482E-005)); +#195627 = CARTESIAN_POINT('',(0.306817755739,-8.2740983334E-005)); +#195628 = CARTESIAN_POINT('',(0.272313393703,-8.242390084137E-005)); +#195629 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#195630 = CARTESIAN_POINT('',(0.203491552027,-8.179989506531E-005)); +#195631 = CARTESIAN_POINT('',(0.169212469737,-8.226451401246E-005)); +#195632 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); +#195633 = CARTESIAN_POINT('',(0.101018376289,-8.868396576111E-005)); +#195634 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095812E-005) + ); +#195635 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467631E-005) + ); +#195636 = CARTESIAN_POINT('',(1.112575605159E-002,2.97280413299E-006)); +#195637 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#195638 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195639 = ORIENTED_EDGE('',*,*,#186452,.T.); +#195640 = ORIENTED_EDGE('',*,*,#189754,.F.); +#195641 = ORIENTED_EDGE('',*,*,#195642,.F.); +#195642 = EDGE_CURVE('',#188249,#189078,#195643,.T.); +#195643 = SURFACE_CURVE('',#195644,(#195649,#195678),.PCURVE_S1.); +#195644 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195645,#195646,#195647, +#195648),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#193253 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); -#193254 = CARTESIAN_POINT('',(-1.401121542172,-0.65,0.6)); -#193255 = CARTESIAN_POINT('',(-1.46,-0.591121542172,0.6)); -#193256 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); -#193257 = PCURVE('',#184118,#193258); -#193258 = DEFINITIONAL_REPRESENTATION('',(#193259),#193285); -#193259 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193260,#193261,#193262, - #193263,#193264,#193265,#193266,#193267,#193268,#193269,#193270, - #193271,#193272,#193273,#193274,#193275,#193276,#193277,#193278, - #193279,#193280,#193281,#193282,#193283,#193284),.UNSPECIFIED.,.F., +#195645 = CARTESIAN_POINT('',(-1.315111126057,-0.65,0.6)); +#195646 = CARTESIAN_POINT('',(-1.401121542172,-0.65,0.6)); +#195647 = CARTESIAN_POINT('',(-1.46,-0.591121542172,0.6)); +#195648 = CARTESIAN_POINT('',(-1.46,-0.505111126057,0.6)); +#195649 = PCURVE('',#186510,#195650); +#195650 = DEFINITIONAL_REPRESENTATION('',(#195651),#195677); +#195651 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195652,#195653,#195654, + #195655,#195656,#195657,#195658,#195659,#195660,#195661,#195662, + #195663,#195664,#195665,#195666,#195667,#195668,#195669,#195670, + #195671,#195672,#195673,#195674,#195675,#195676),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240029,40 +243031,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193260 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); -#193261 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); -#193262 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); -#193263 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); -#193264 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); -#193265 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); -#193266 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); -#193267 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); -#193268 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); -#193269 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); -#193270 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); -#193271 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); -#193272 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); -#193273 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); -#193274 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); -#193275 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); -#193276 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); -#193277 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); -#193278 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); -#193279 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); -#193280 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); -#193281 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); -#193282 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); -#193283 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); -#193284 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); -#193285 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193286 = PCURVE('',#183425,#193287); -#193287 = DEFINITIONAL_REPRESENTATION('',(#193288),#193314); -#193288 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193289,#193290,#193291, - #193292,#193293,#193294,#193295,#193296,#193297,#193298,#193299, - #193300,#193301,#193302,#193303,#193304,#193305,#193306,#193307, - #193308,#193309,#193310,#193311,#193312,#193313),.UNSPECIFIED.,.F., +#195652 = CARTESIAN_POINT('',(4.77942647859,-3.630376297074E-002)); +#195653 = CARTESIAN_POINT('',(4.800122554352,-3.55002654583E-002)); +#195654 = CARTESIAN_POINT('',(4.842026813946,-3.392679389428E-002)); +#195655 = CARTESIAN_POINT('',(4.906331430682,-3.169156326634E-002)); +#195656 = CARTESIAN_POINT('',(4.972002237726,-2.960568355689E-002)); +#195657 = CARTESIAN_POINT('',(5.038935988639,-2.769364143908E-002)); +#195658 = CARTESIAN_POINT('',(5.107015701598,-2.597924597428E-002)); +#195659 = CARTESIAN_POINT('',(5.176109321395,-2.448502077123E-002)); +#195660 = CARTESIAN_POINT('',(5.246071272743,-2.323151325725E-002)); +#195661 = CARTESIAN_POINT('',(5.316743777694,-2.223663371573E-002)); +#195662 = CARTESIAN_POINT('',(5.387958755834,-2.151504028974E-002)); +#195663 = CARTESIAN_POINT('',(5.459540038821,-2.107761309379E-002)); +#195664 = CARTESIAN_POINT('',(5.531305892885,-2.093105015407E-002)); +#195665 = CARTESIAN_POINT('',(5.603071746948,-2.107761309379E-002)); +#195666 = CARTESIAN_POINT('',(5.674653029936,-2.151504028974E-002)); +#195667 = CARTESIAN_POINT('',(5.745868008076,-2.223663371573E-002)); +#195668 = CARTESIAN_POINT('',(5.816540513026,-2.323151325725E-002)); +#195669 = CARTESIAN_POINT('',(5.886502464374,-2.448502077123E-002)); +#195670 = CARTESIAN_POINT('',(5.955596084171,-2.597924597428E-002)); +#195671 = CARTESIAN_POINT('',(6.02367579713,-2.769364143908E-002)); +#195672 = CARTESIAN_POINT('',(6.090609548043,-2.960568355689E-002)); +#195673 = CARTESIAN_POINT('',(6.156280355087,-3.169156326634E-002)); +#195674 = CARTESIAN_POINT('',(6.220584971823,-3.392679389428E-002)); +#195675 = CARTESIAN_POINT('',(6.262489231417,-3.55002654583E-002)); +#195676 = CARTESIAN_POINT('',(6.28318530718,-3.630376297074E-002)); +#195677 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195678 = PCURVE('',#185817,#195679); +#195679 = DEFINITIONAL_REPRESENTATION('',(#195680),#195706); +#195680 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195681,#195682,#195683, + #195684,#195685,#195686,#195687,#195688,#195689,#195690,#195691, + #195692,#195693,#195694,#195695,#195696,#195697,#195698,#195699, + #195700,#195701,#195702,#195703,#195704,#195705),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240070,60 +243072,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193289 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#193290 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); -#193291 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); -#193292 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); -#193293 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); -#193294 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); -#193295 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); -#193296 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); -#193297 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); -#193298 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); -#193299 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); -#193300 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); -#193301 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); -#193302 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); -#193303 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); -#193304 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); -#193305 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); -#193306 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); -#193307 = CARTESIAN_POINT('',(3.469181876598,0.299752403237)); -#193308 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); -#193309 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); -#193310 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); -#193311 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); -#193312 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); -#193313 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#193314 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193315 = ADVANCED_FACE('',(#193316),#183425,.T.); -#193316 = FACE_BOUND('',#193317,.T.); -#193317 = EDGE_LOOP('',(#193318,#193319,#193320,#193386,#193387)); -#193318 = ORIENTED_EDGE('',*,*,#186685,.F.); -#193319 = ORIENTED_EDGE('',*,*,#183386,.T.); -#193320 = ORIENTED_EDGE('',*,*,#193321,.T.); -#193321 = EDGE_CURVE('',#183302,#186421,#193322,.T.); -#193322 = SURFACE_CURVE('',#193323,(#193328,#193357),.PCURVE_S1.); -#193323 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193324,#193325,#193326, -#193327),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195681 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#195682 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); +#195683 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); +#195684 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); +#195685 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); +#195686 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); +#195687 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); +#195688 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); +#195689 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); +#195690 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); +#195691 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); +#195692 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); +#195693 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); +#195694 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); +#195695 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); +#195696 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); +#195697 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); +#195698 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); +#195699 = CARTESIAN_POINT('',(3.469181876598,0.299752403237)); +#195700 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); +#195701 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); +#195702 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); +#195703 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); +#195704 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); +#195705 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#195706 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195707 = ADVANCED_FACE('',(#195708),#185817,.T.); +#195708 = FACE_BOUND('',#195709,.T.); +#195709 = EDGE_LOOP('',(#195710,#195711,#195712,#195778,#195779)); +#195710 = ORIENTED_EDGE('',*,*,#189077,.F.); +#195711 = ORIENTED_EDGE('',*,*,#185778,.T.); +#195712 = ORIENTED_EDGE('',*,*,#195713,.T.); +#195713 = EDGE_CURVE('',#185694,#188813,#195714,.T.); +#195714 = SURFACE_CURVE('',#195715,(#195720,#195749),.PCURVE_S1.); +#195715 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195716,#195717,#195718, +#195719),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( -8.881784197001E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193324 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); -#193325 = CARTESIAN_POINT('',(-1.265581001793,-0.510038843607, +#195716 = CARTESIAN_POINT('',(-1.2928099227,-0.4828099227,0.132282534)); +#195717 = CARTESIAN_POINT('',(-1.265581001793,-0.510038843607, 0.132282534)); -#193326 = CARTESIAN_POINT('',(-1.230010423697,-0.525122936235, +#195718 = CARTESIAN_POINT('',(-1.230010423697,-0.525122936235, 0.133952453327)); -#193327 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, +#195719 = CARTESIAN_POINT('',(-1.191066471757,-0.5259553457, 0.137059047745)); -#193328 = PCURVE('',#183425,#193329); -#193329 = DEFINITIONAL_REPRESENTATION('',(#193330),#193356); -#193330 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193331,#193332,#193333, - #193334,#193335,#193336,#193337,#193338,#193339,#193340,#193341, - #193342,#193343,#193344,#193345,#193346,#193347,#193348,#193349, - #193350,#193351,#193352,#193353,#193354,#193355),.UNSPECIFIED.,.F., +#195720 = PCURVE('',#185817,#195721); +#195721 = DEFINITIONAL_REPRESENTATION('',(#195722),#195748); +#195722 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195723,#195724,#195725, + #195726,#195727,#195728,#195729,#195730,#195731,#195732,#195733, + #195734,#195735,#195736,#195737,#195738,#195739,#195740,#195741, + #195742,#195743,#195744,#195745,#195746,#195747),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240132,40 +243134,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#193331 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); -#193332 = CARTESIAN_POINT('',(3.90459767512,-0.195420311637)); -#193333 = CARTESIAN_POINT('',(3.926919725,-0.195434403207)); -#193334 = CARTESIAN_POINT('',(3.960597703687,-0.195498474489)); -#193335 = CARTESIAN_POINT('',(3.994453220183,-0.195606126036)); -#193336 = CARTESIAN_POINT('',(4.028468081361,-0.195757812252)); -#193337 = CARTESIAN_POINT('',(4.062623617158,-0.195953853447)); -#193338 = CARTESIAN_POINT('',(4.096900657675,-0.196194413471)); -#193339 = CARTESIAN_POINT('',(4.13127961549,-0.196479500374)); -#193340 = CARTESIAN_POINT('',(4.165740544467,-0.196808962557)); -#193341 = CARTESIAN_POINT('',(4.200263208931,-0.197182487852)); -#193342 = CARTESIAN_POINT('',(4.234827153442,-0.197599603628)); -#193343 = CARTESIAN_POINT('',(4.269411775032,-0.198059678438)); -#193344 = CARTESIAN_POINT('',(4.303996396623,-0.19856192508)); -#193345 = CARTESIAN_POINT('',(4.338560341134,-0.199105405074)); -#193346 = CARTESIAN_POINT('',(4.373083005598,-0.199689034488)); -#193347 = CARTESIAN_POINT('',(4.407543934574,-0.200311591052)); -#193348 = CARTESIAN_POINT('',(4.44192289239,-0.20097172244)); -#193349 = CARTESIAN_POINT('',(4.476199932907,-0.20166795566)); -#193350 = CARTESIAN_POINT('',(4.510355468703,-0.202398707226)); -#193351 = CARTESIAN_POINT('',(4.544370329882,-0.203162294721)); -#193352 = CARTESIAN_POINT('',(4.578225846377,-0.203956946721)); -#193353 = CARTESIAN_POINT('',(4.611903825065,-0.204780821715)); -#193354 = CARTESIAN_POINT('',(4.634225874945,-0.205348270935)); -#193355 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); -#193356 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193357 = PCURVE('',#183340,#193358); -#193358 = DEFINITIONAL_REPRESENTATION('',(#193359),#193385); -#193359 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193360,#193361,#193362, - #193363,#193364,#193365,#193366,#193367,#193368,#193369,#193370, - #193371,#193372,#193373,#193374,#193375,#193376,#193377,#193378, - #193379,#193380,#193381,#193382,#193383,#193384),.UNSPECIFIED.,.F., +#195723 = CARTESIAN_POINT('',(3.893472067885,-0.195420322924)); +#195724 = CARTESIAN_POINT('',(3.90459767512,-0.195420311637)); +#195725 = CARTESIAN_POINT('',(3.926919725,-0.195434403207)); +#195726 = CARTESIAN_POINT('',(3.960597703687,-0.195498474489)); +#195727 = CARTESIAN_POINT('',(3.994453220183,-0.195606126036)); +#195728 = CARTESIAN_POINT('',(4.028468081361,-0.195757812252)); +#195729 = CARTESIAN_POINT('',(4.062623617158,-0.195953853447)); +#195730 = CARTESIAN_POINT('',(4.096900657675,-0.196194413471)); +#195731 = CARTESIAN_POINT('',(4.13127961549,-0.196479500374)); +#195732 = CARTESIAN_POINT('',(4.165740544467,-0.196808962557)); +#195733 = CARTESIAN_POINT('',(4.200263208931,-0.197182487852)); +#195734 = CARTESIAN_POINT('',(4.234827153442,-0.197599603628)); +#195735 = CARTESIAN_POINT('',(4.269411775032,-0.198059678438)); +#195736 = CARTESIAN_POINT('',(4.303996396623,-0.19856192508)); +#195737 = CARTESIAN_POINT('',(4.338560341134,-0.199105405074)); +#195738 = CARTESIAN_POINT('',(4.373083005598,-0.199689034488)); +#195739 = CARTESIAN_POINT('',(4.407543934574,-0.200311591052)); +#195740 = CARTESIAN_POINT('',(4.44192289239,-0.20097172244)); +#195741 = CARTESIAN_POINT('',(4.476199932907,-0.20166795566)); +#195742 = CARTESIAN_POINT('',(4.510355468703,-0.202398707226)); +#195743 = CARTESIAN_POINT('',(4.544370329882,-0.203162294721)); +#195744 = CARTESIAN_POINT('',(4.578225846377,-0.203956946721)); +#195745 = CARTESIAN_POINT('',(4.611903825065,-0.204780821715)); +#195746 = CARTESIAN_POINT('',(4.634225874945,-0.205348270935)); +#195747 = CARTESIAN_POINT('',(4.64535148218,-0.205636228593)); +#195748 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195749 = PCURVE('',#185732,#195750); +#195750 = DEFINITIONAL_REPRESENTATION('',(#195751),#195777); +#195751 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195752,#195753,#195754, + #195755,#195756,#195757,#195758,#195759,#195760,#195761,#195762, + #195763,#195764,#195765,#195766,#195767,#195768,#195769,#195770, + #195771,#195772,#195773,#195774,#195775,#195776),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( -8.881784197001E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240174,62 +243176,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .UNSPECIFIED.); -#193360 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#193361 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#193362 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#193363 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#193364 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#193365 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#193366 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#193367 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#193368 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#193369 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#193370 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#193371 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#193372 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#193373 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#193374 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#193375 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#193376 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); -#193377 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); -#193378 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); -#193379 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); -#193380 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); -#193381 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); -#193382 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); -#193383 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); -#193384 = CARTESIAN_POINT('',(0.751879414295,1.)); -#193385 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193386 = ORIENTED_EDGE('',*,*,#186420,.F.); -#193387 = ORIENTED_EDGE('',*,*,#193250,.T.); -#193388 = ADVANCED_FACE('',(#193389),#184696,.T.); -#193389 = FACE_BOUND('',#193390,.T.); -#193390 = EDGE_LOOP('',(#193391,#193392,#193458,#193459,#193460)); -#193391 = ORIENTED_EDGE('',*,*,#187450,.F.); -#193392 = ORIENTED_EDGE('',*,*,#193393,.T.); -#193393 = EDGE_CURVE('',#187406,#184639,#193394,.T.); -#193394 = SURFACE_CURVE('',#193395,(#193400,#193429),.PCURVE_S1.); -#193395 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193396,#193397,#193398, -#193399),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195752 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#195753 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#195754 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#195755 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#195756 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#195757 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#195758 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#195759 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#195760 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#195761 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#195762 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#195763 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#195764 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#195765 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#195766 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#195767 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#195768 = CARTESIAN_POINT('',(0.513985713405,1.000085423618)); +#195769 = CARTESIAN_POINT('',(0.548364026633,1.000085935426)); +#195770 = CARTESIAN_POINT('',(0.582648204501,1.000086874059)); +#195771 = CARTESIAN_POINT('',(0.616817843149,1.000086431829)); +#195772 = CARTESIAN_POINT('',(0.650851510181,1.000091359578)); +#195773 = CARTESIAN_POINT('',(0.684729502771,1.00003211524)); +#195774 = CARTESIAN_POINT('',(0.718425946423,1.000007920749)); +#195775 = CARTESIAN_POINT('',(0.740753686901,0.999999942971)); +#195776 = CARTESIAN_POINT('',(0.751879414295,1.)); +#195777 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195778 = ORIENTED_EDGE('',*,*,#188812,.F.); +#195779 = ORIENTED_EDGE('',*,*,#195642,.T.); +#195780 = ADVANCED_FACE('',(#195781),#187088,.T.); +#195781 = FACE_BOUND('',#195782,.T.); +#195782 = EDGE_LOOP('',(#195783,#195784,#195850,#195851,#195852)); +#195783 = ORIENTED_EDGE('',*,*,#189842,.F.); +#195784 = ORIENTED_EDGE('',*,*,#195785,.T.); +#195785 = EDGE_CURVE('',#189798,#187031,#195786,.T.); +#195786 = SURFACE_CURVE('',#195787,(#195792,#195821),.PCURVE_S1.); +#195787 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195788,#195789,#195790, +#195791),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193396 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 +#195788 = CARTESIAN_POINT('',(-1.362750264943,0.407861391,0.962940952255 )); -#193397 = CARTESIAN_POINT('',(-1.361917855478,0.44680534294, +#195789 = CARTESIAN_POINT('',(-1.361917855478,0.44680534294, 0.966047546673)); -#193398 = CARTESIAN_POINT('',(-1.34683376285,0.482375921036,0.967717466) +#195790 = CARTESIAN_POINT('',(-1.34683376285,0.482375921036,0.967717466) ); -#193399 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 +#195791 = CARTESIAN_POINT('',(-1.319604841943,0.509604841943,0.967717466 )); -#193400 = PCURVE('',#184696,#193401); -#193401 = DEFINITIONAL_REPRESENTATION('',(#193402),#193428); -#193402 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193403,#193404,#193405, - #193406,#193407,#193408,#193409,#193410,#193411,#193412,#193413, - #193414,#193415,#193416,#193417,#193418,#193419,#193420,#193421, - #193422,#193423,#193424,#193425,#193426,#193427),.UNSPECIFIED.,.F., +#195792 = PCURVE('',#187088,#195793); +#195793 = DEFINITIONAL_REPRESENTATION('',(#195794),#195820); +#195794 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195795,#195796,#195797, + #195798,#195799,#195800,#195801,#195802,#195803,#195804,#195805, + #195806,#195807,#195808,#195809,#195810,#195811,#195812,#195813, + #195814,#195815,#195816,#195817,#195818,#195819),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240237,40 +243239,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193403 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); -#193404 = CARTESIAN_POINT('',(1.112560723485E-002,-0.424140987131)); -#193405 = CARTESIAN_POINT('',(3.344765711494E-002,-0.423573537911)); -#193406 = CARTESIAN_POINT('',(6.712563580239E-002,-0.422749662917)); -#193407 = CARTESIAN_POINT('',(0.100981152298,-0.421955010917)); -#193408 = CARTESIAN_POINT('',(0.134996013476,-0.421191423422)); -#193409 = CARTESIAN_POINT('',(0.169151549273,-0.420460671856)); -#193410 = CARTESIAN_POINT('',(0.20342858979,-0.419764438636)); -#193411 = CARTESIAN_POINT('',(0.237807547605,-0.419104307248)); -#193412 = CARTESIAN_POINT('',(0.272268476582,-0.418481750684)); -#193413 = CARTESIAN_POINT('',(0.306791141046,-0.41789812127)); -#193414 = CARTESIAN_POINT('',(0.341355085557,-0.417354641276)); -#193415 = CARTESIAN_POINT('',(0.375939707147,-0.416852394634)); -#193416 = CARTESIAN_POINT('',(0.410524328738,-0.416392319824)); -#193417 = CARTESIAN_POINT('',(0.445088273249,-0.415975204048)); -#193418 = CARTESIAN_POINT('',(0.479610937713,-0.415601678753)); -#193419 = CARTESIAN_POINT('',(0.51407186669,-0.41527221657)); -#193420 = CARTESIAN_POINT('',(0.548450824505,-0.414987129667)); -#193421 = CARTESIAN_POINT('',(0.582727865022,-0.414746569643)); -#193422 = CARTESIAN_POINT('',(0.616883400819,-0.414550528448)); -#193423 = CARTESIAN_POINT('',(0.650898261997,-0.414398842232)); -#193424 = CARTESIAN_POINT('',(0.684753778493,-0.414291190685)); -#193425 = CARTESIAN_POINT('',(0.71843175718,-0.414227119403)); -#193426 = CARTESIAN_POINT('',(0.74075380706,-0.414213027833)); -#193427 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); -#193428 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193429 = PCURVE('',#184769,#193430); -#193430 = DEFINITIONAL_REPRESENTATION('',(#193431),#193457); -#193431 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193432,#193433,#193434, - #193435,#193436,#193437,#193438,#193439,#193440,#193441,#193442, - #193443,#193444,#193445,#193446,#193447,#193448,#193449,#193450, - #193451,#193452,#193453,#193454,#193455,#193456),.UNSPECIFIED.,.F., +#195795 = CARTESIAN_POINT('',(0.E+000,-0.424428944789)); +#195796 = CARTESIAN_POINT('',(1.112560723485E-002,-0.424140987131)); +#195797 = CARTESIAN_POINT('',(3.344765711494E-002,-0.423573537911)); +#195798 = CARTESIAN_POINT('',(6.712563580239E-002,-0.422749662917)); +#195799 = CARTESIAN_POINT('',(0.100981152298,-0.421955010917)); +#195800 = CARTESIAN_POINT('',(0.134996013476,-0.421191423422)); +#195801 = CARTESIAN_POINT('',(0.169151549273,-0.420460671856)); +#195802 = CARTESIAN_POINT('',(0.20342858979,-0.419764438636)); +#195803 = CARTESIAN_POINT('',(0.237807547605,-0.419104307248)); +#195804 = CARTESIAN_POINT('',(0.272268476582,-0.418481750684)); +#195805 = CARTESIAN_POINT('',(0.306791141046,-0.41789812127)); +#195806 = CARTESIAN_POINT('',(0.341355085557,-0.417354641276)); +#195807 = CARTESIAN_POINT('',(0.375939707147,-0.416852394634)); +#195808 = CARTESIAN_POINT('',(0.410524328738,-0.416392319824)); +#195809 = CARTESIAN_POINT('',(0.445088273249,-0.415975204048)); +#195810 = CARTESIAN_POINT('',(0.479610937713,-0.415601678753)); +#195811 = CARTESIAN_POINT('',(0.51407186669,-0.41527221657)); +#195812 = CARTESIAN_POINT('',(0.548450824505,-0.414987129667)); +#195813 = CARTESIAN_POINT('',(0.582727865022,-0.414746569643)); +#195814 = CARTESIAN_POINT('',(0.616883400819,-0.414550528448)); +#195815 = CARTESIAN_POINT('',(0.650898261997,-0.414398842232)); +#195816 = CARTESIAN_POINT('',(0.684753778493,-0.414291190685)); +#195817 = CARTESIAN_POINT('',(0.71843175718,-0.414227119403)); +#195818 = CARTESIAN_POINT('',(0.74075380706,-0.414213027833)); +#195819 = CARTESIAN_POINT('',(0.751879414295,-0.41421303912)); +#195820 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195821 = PCURVE('',#187161,#195822); +#195822 = DEFINITIONAL_REPRESENTATION('',(#195823),#195849); +#195823 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195824,#195825,#195826, + #195827,#195828,#195829,#195830,#195831,#195832,#195833,#195834, + #195835,#195836,#195837,#195838,#195839,#195840,#195841,#195842, + #195843,#195844,#195845,#195846,#195847,#195848),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240278,56 +243280,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193432 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#193433 = CARTESIAN_POINT('',(0.740753686904,5.712075643651E-008)); -#193434 = CARTESIAN_POINT('',(0.718425946425,-7.920681090372E-006)); -#193435 = CARTESIAN_POINT('',(0.684729502759,-3.211561473994E-005)); -#193436 = CARTESIAN_POINT('',(0.650851510226,-9.135814826272E-005)); -#193437 = CARTESIAN_POINT('',(0.616817843137,-8.643221197519E-005)); -#193438 = CARTESIAN_POINT('',(0.582648204505,-8.687395637416E-005)); -#193439 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); -#193440 = CARTESIAN_POINT('',(0.513985713406,-8.542361087673E-005)); -#193441 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); -#193442 = CARTESIAN_POINT('',(0.445025477762,-8.435280808235E-005)); -#193443 = CARTESIAN_POINT('',(0.410481676253,-8.388702482308E-005)); -#193444 = CARTESIAN_POINT('',(0.375920232966,-8.346461190823E-005)); -#193445 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); -#193446 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); -#193447 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); -#193448 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); -#193449 = CARTESIAN_POINT('',(0.203491552027,-8.179989506535E-005)); -#193450 = CARTESIAN_POINT('',(0.169212469737,-8.226451401251E-005)); -#193451 = CARTESIAN_POINT('',(0.135047837564,-7.965797689881E-005)); -#193452 = CARTESIAN_POINT('',(0.101018376289,-8.868396576202E-005)); -#193453 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095473E-005) - ); -#193454 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467085E-005) - ); -#193455 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135975E-006)); -#193456 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#193457 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193458 = ORIENTED_EDGE('',*,*,#184638,.T.); -#193459 = ORIENTED_EDGE('',*,*,#185340,.F.); -#193460 = ORIENTED_EDGE('',*,*,#193461,.F.); -#193461 = EDGE_CURVE('',#186614,#185341,#193462,.T.); -#193462 = SURFACE_CURVE('',#193463,(#193468,#193497),.PCURVE_S1.); -#193463 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193464,#193465,#193466, -#193467),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195824 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#195825 = CARTESIAN_POINT('',(0.740753686904,5.712075643651E-008)); +#195826 = CARTESIAN_POINT('',(0.718425946425,-7.920681090372E-006)); +#195827 = CARTESIAN_POINT('',(0.684729502759,-3.211561473994E-005)); +#195828 = CARTESIAN_POINT('',(0.650851510226,-9.135814826272E-005)); +#195829 = CARTESIAN_POINT('',(0.616817843137,-8.643221197519E-005)); +#195830 = CARTESIAN_POINT('',(0.582648204505,-8.687395637416E-005)); +#195831 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); +#195832 = CARTESIAN_POINT('',(0.513985713406,-8.542361087673E-005)); +#195833 = CARTESIAN_POINT('',(0.479533105651,-8.485308627405E-005)); +#195834 = CARTESIAN_POINT('',(0.445025477762,-8.435280808235E-005)); +#195835 = CARTESIAN_POINT('',(0.410481676253,-8.388702482308E-005)); +#195836 = CARTESIAN_POINT('',(0.375920232966,-8.346461190823E-005)); +#195837 = CARTESIAN_POINT('',(0.341359494752,-8.3080815225E-005)); +#195838 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); +#195839 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); +#195840 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); +#195841 = CARTESIAN_POINT('',(0.203491552027,-8.179989506535E-005)); +#195842 = CARTESIAN_POINT('',(0.169212469737,-8.226451401251E-005)); +#195843 = CARTESIAN_POINT('',(0.135047837564,-7.965797689881E-005)); +#195844 = CARTESIAN_POINT('',(0.101018376289,-8.868396576202E-005)); +#195845 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095473E-005) + ); +#195846 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467085E-005) + ); +#195847 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804135975E-006)); +#195848 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#195849 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195850 = ORIENTED_EDGE('',*,*,#187030,.T.); +#195851 = ORIENTED_EDGE('',*,*,#187732,.F.); +#195852 = ORIENTED_EDGE('',*,*,#195853,.F.); +#195853 = EDGE_CURVE('',#189006,#187733,#195854,.T.); +#195854 = SURFACE_CURVE('',#195855,(#195860,#195889),.PCURVE_S1.); +#195855 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195856,#195857,#195858, +#195859),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#193464 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); -#193465 = CARTESIAN_POINT('',(-1.46,0.591121542172,0.6)); -#193466 = CARTESIAN_POINT('',(-1.401121542172,0.65,0.6)); -#193467 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); -#193468 = PCURVE('',#184696,#193469); -#193469 = DEFINITIONAL_REPRESENTATION('',(#193470),#193496); -#193470 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193471,#193472,#193473, - #193474,#193475,#193476,#193477,#193478,#193479,#193480,#193481, - #193482,#193483,#193484,#193485,#193486,#193487,#193488,#193489, - #193490,#193491,#193492,#193493,#193494,#193495),.UNSPECIFIED.,.F., +#195856 = CARTESIAN_POINT('',(-1.46,0.505111126057,0.6)); +#195857 = CARTESIAN_POINT('',(-1.46,0.591121542172,0.6)); +#195858 = CARTESIAN_POINT('',(-1.401121542172,0.65,0.6)); +#195859 = CARTESIAN_POINT('',(-1.315111126057,0.65,0.6)); +#195860 = PCURVE('',#187088,#195861); +#195861 = DEFINITIONAL_REPRESENTATION('',(#195862),#195888); +#195862 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195863,#195864,#195865, + #195866,#195867,#195868,#195869,#195870,#195871,#195872,#195873, + #195874,#195875,#195876,#195877,#195878,#195879,#195880,#195881, + #195882,#195883,#195884,#195885,#195886,#195887),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240335,41 +243337,41 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193471 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#193472 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#193473 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) - ); -#193474 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#193475 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#193476 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#193477 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#193478 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#193479 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#193480 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#193481 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#193482 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#193483 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#193484 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#193485 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#193486 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#193487 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#193488 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#193489 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#193490 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#193491 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#193492 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#193493 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#193494 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#193495 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#193496 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193497 = PCURVE('',#183975,#193498); -#193498 = DEFINITIONAL_REPRESENTATION('',(#193499),#193525); -#193499 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193500,#193501,#193502, - #193503,#193504,#193505,#193506,#193507,#193508,#193509,#193510, - #193511,#193512,#193513,#193514,#193515,#193516,#193517,#193518, - #193519,#193520,#193521,#193522,#193523,#193524),.UNSPECIFIED.,.F., +#195863 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#195864 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#195865 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) + ); +#195866 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#195867 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#195868 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#195869 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#195870 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#195871 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#195872 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#195873 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#195874 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#195875 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#195876 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#195877 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#195878 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#195879 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#195880 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#195881 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#195882 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#195883 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#195884 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#195885 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#195886 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#195887 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#195888 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195889 = PCURVE('',#186367,#195890); +#195890 = DEFINITIONAL_REPRESENTATION('',(#195891),#195917); +#195891 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195892,#195893,#195894, + #195895,#195896,#195897,#195898,#195899,#195900,#195901,#195902, + #195903,#195904,#195905,#195906,#195907,#195908,#195909,#195910, + #195911,#195912,#195913,#195914,#195915,#195916),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240377,60 +243379,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193500 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); -#193501 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); -#193502 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); -#193503 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); -#193504 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); -#193505 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); -#193506 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); -#193507 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); -#193508 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); -#193509 = CARTESIAN_POINT('',(2.604275354486,-2.223663371573E-002)); -#193510 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); -#193511 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); -#193512 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); -#193513 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); -#193514 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); -#193515 = CARTESIAN_POINT('',(2.175151124104,-2.223663371573E-002)); -#193516 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); -#193517 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); -#193518 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); -#193519 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); -#193520 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); -#193521 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); -#193522 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); -#193523 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); -#193524 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); -#193525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193526 = ADVANCED_FACE('',(#193527),#183975,.T.); -#193527 = FACE_BOUND('',#193528,.T.); -#193528 = EDGE_LOOP('',(#193529,#193530,#193531,#193597,#193598)); -#193529 = ORIENTED_EDGE('',*,*,#186824,.F.); -#193530 = ORIENTED_EDGE('',*,*,#183936,.T.); -#193531 = ORIENTED_EDGE('',*,*,#193532,.T.); -#193532 = EDGE_CURVE('',#183852,#186616,#193533,.T.); -#193533 = SURFACE_CURVE('',#193534,(#193539,#193568),.PCURVE_S1.); -#193534 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193535,#193536,#193537, -#193538),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195892 = CARTESIAN_POINT('',(3.14159265359,-3.630376297074E-002)); +#195893 = CARTESIAN_POINT('',(3.120896577828,-3.55002654583E-002)); +#195894 = CARTESIAN_POINT('',(3.078992318233,-3.392679389428E-002)); +#195895 = CARTESIAN_POINT('',(3.014687701497,-3.169156326634E-002)); +#195896 = CARTESIAN_POINT('',(2.949016894454,-2.960568355689E-002)); +#195897 = CARTESIAN_POINT('',(2.88208314354,-2.769364143908E-002)); +#195898 = CARTESIAN_POINT('',(2.814003430581,-2.597924597428E-002)); +#195899 = CARTESIAN_POINT('',(2.744909810785,-2.448502077123E-002)); +#195900 = CARTESIAN_POINT('',(2.674947859436,-2.323151325725E-002)); +#195901 = CARTESIAN_POINT('',(2.604275354486,-2.223663371573E-002)); +#195902 = CARTESIAN_POINT('',(2.533060376346,-2.151504028974E-002)); +#195903 = CARTESIAN_POINT('',(2.461479093359,-2.107761309379E-002)); +#195904 = CARTESIAN_POINT('',(2.389713239295,-2.093105015407E-002)); +#195905 = CARTESIAN_POINT('',(2.317947385231,-2.107761309379E-002)); +#195906 = CARTESIAN_POINT('',(2.246366102244,-2.151504028974E-002)); +#195907 = CARTESIAN_POINT('',(2.175151124104,-2.223663371573E-002)); +#195908 = CARTESIAN_POINT('',(2.104478619153,-2.323151325725E-002)); +#195909 = CARTESIAN_POINT('',(2.034516667805,-2.448502077123E-002)); +#195910 = CARTESIAN_POINT('',(1.965423048009,-2.597924597428E-002)); +#195911 = CARTESIAN_POINT('',(1.89734333505,-2.769364143908E-002)); +#195912 = CARTESIAN_POINT('',(1.830409584136,-2.960568355689E-002)); +#195913 = CARTESIAN_POINT('',(1.764738777092,-3.169156326634E-002)); +#195914 = CARTESIAN_POINT('',(1.700434160356,-3.392679389428E-002)); +#195915 = CARTESIAN_POINT('',(1.658529900762,-3.55002654583E-002)); +#195916 = CARTESIAN_POINT('',(1.637833825,-3.630376297074E-002)); +#195917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195918 = ADVANCED_FACE('',(#195919),#186367,.T.); +#195919 = FACE_BOUND('',#195920,.T.); +#195920 = EDGE_LOOP('',(#195921,#195922,#195923,#195989,#195990)); +#195921 = ORIENTED_EDGE('',*,*,#189216,.F.); +#195922 = ORIENTED_EDGE('',*,*,#186328,.T.); +#195923 = ORIENTED_EDGE('',*,*,#195924,.T.); +#195924 = EDGE_CURVE('',#186244,#189008,#195925,.T.); +#195925 = SURFACE_CURVE('',#195926,(#195931,#195960),.PCURVE_S1.); +#195926 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195927,#195928,#195929, +#195930),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 1.807003620809E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193535 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); -#193536 = CARTESIAN_POINT('',(-1.320038843607,0.455581001793,0.132282534 +#195927 = CARTESIAN_POINT('',(-1.2928099227,0.4828099227,0.132282534)); +#195928 = CARTESIAN_POINT('',(-1.320038843607,0.455581001793,0.132282534 )); -#193537 = CARTESIAN_POINT('',(-1.335122936235,0.420010423697, +#195929 = CARTESIAN_POINT('',(-1.335122936235,0.420010423697, 0.133952453327)); -#193538 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, +#195930 = CARTESIAN_POINT('',(-1.3359553457,0.381066471757, 0.137059047745)); -#193539 = PCURVE('',#183975,#193540); -#193540 = DEFINITIONAL_REPRESENTATION('',(#193541),#193567); -#193541 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193542,#193543,#193544, - #193545,#193546,#193547,#193548,#193549,#193550,#193551,#193552, - #193553,#193554,#193555,#193556,#193557,#193558,#193559,#193560, - #193561,#193562,#193563,#193564,#193565,#193566),.UNSPECIFIED.,.F., +#195931 = PCURVE('',#186367,#195932); +#195932 = DEFINITIONAL_REPRESENTATION('',(#195933),#195959); +#195933 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195934,#195935,#195936, + #195937,#195938,#195939,#195940,#195941,#195942,#195943,#195944, + #195945,#195946,#195947,#195948,#195949,#195950,#195951,#195952, + #195953,#195954,#195955,#195956,#195957,#195958),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240439,40 +243441,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#193542 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); -#193543 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); -#193544 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); -#193545 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); -#193546 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); -#193547 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); -#193548 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); -#193549 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); -#193550 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); -#193551 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); -#193552 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); -#193553 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); -#193554 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); -#193555 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); -#193556 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); -#193557 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); -#193558 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); -#193559 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); -#193560 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); -#193561 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); -#193562 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); -#193563 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); -#193564 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); -#193565 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); -#193566 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); -#193567 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193568 = PCURVE('',#183890,#193569); -#193569 = DEFINITIONAL_REPRESENTATION('',(#193570),#193596); -#193570 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193571,#193572,#193573, - #193574,#193575,#193576,#193577,#193578,#193579,#193580,#193581, - #193582,#193583,#193584,#193585,#193586,#193587,#193588,#193589, - #193590,#193591,#193592,#193593,#193594,#193595),.UNSPECIFIED.,.F., +#195934 = CARTESIAN_POINT('',(2.389713239295,-0.521151972135)); +#195935 = CARTESIAN_POINT('',(2.40083884653,-0.521151960849)); +#195936 = CARTESIAN_POINT('',(2.42316089641,-0.521166052418)); +#195937 = CARTESIAN_POINT('',(2.456838875097,-0.521230123701)); +#195938 = CARTESIAN_POINT('',(2.490694391593,-0.521337775248)); +#195939 = CARTESIAN_POINT('',(2.524709252771,-0.521489461464)); +#195940 = CARTESIAN_POINT('',(2.558864788568,-0.521685502659)); +#195941 = CARTESIAN_POINT('',(2.593141829085,-0.521926062682)); +#195942 = CARTESIAN_POINT('',(2.6275207869,-0.522211149586)); +#195943 = CARTESIAN_POINT('',(2.661981715877,-0.522540611768)); +#195944 = CARTESIAN_POINT('',(2.696504380341,-0.522914137063)); +#195945 = CARTESIAN_POINT('',(2.731068324852,-0.523331252839)); +#195946 = CARTESIAN_POINT('',(2.765652946442,-0.523791327649)); +#195947 = CARTESIAN_POINT('',(2.800237568033,-0.524293574292)); +#195948 = CARTESIAN_POINT('',(2.834801512544,-0.524837054286)); +#195949 = CARTESIAN_POINT('',(2.869324177008,-0.5254206837)); +#195950 = CARTESIAN_POINT('',(2.903785105985,-0.526043240264)); +#195951 = CARTESIAN_POINT('',(2.9381640638,-0.526703371651)); +#195952 = CARTESIAN_POINT('',(2.972441104317,-0.527399604872)); +#195953 = CARTESIAN_POINT('',(3.006596640113,-0.528130356438)); +#195954 = CARTESIAN_POINT('',(3.040611501292,-0.528893943933)); +#195955 = CARTESIAN_POINT('',(3.074467017787,-0.529688595932)); +#195956 = CARTESIAN_POINT('',(3.108144996475,-0.530512470926)); +#195957 = CARTESIAN_POINT('',(3.130467046355,-0.531079920146)); +#195958 = CARTESIAN_POINT('',(3.14159265359,-0.531367877804)); +#195959 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195960 = PCURVE('',#186282,#195961); +#195961 = DEFINITIONAL_REPRESENTATION('',(#195962),#195988); +#195962 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#195963,#195964,#195965, + #195966,#195967,#195968,#195969,#195970,#195971,#195972,#195973, + #195974,#195975,#195976,#195977,#195978,#195979,#195980,#195981, + #195982,#195983,#195984,#195985,#195986,#195987),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 1.807003620809E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240481,62 +243483,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#193571 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#193572 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#193573 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#193574 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#193575 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#193576 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#193577 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#193578 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#193579 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#193580 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#193581 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#193582 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#193583 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#193584 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#193585 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); -#193586 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); -#193587 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); -#193588 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); -#193589 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); -#193590 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); -#193591 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); -#193592 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); -#193593 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); -#193594 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); -#193595 = CARTESIAN_POINT('',(0.751879414295,1.)); -#193596 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193597 = ORIENTED_EDGE('',*,*,#186613,.F.); -#193598 = ORIENTED_EDGE('',*,*,#193461,.T.); -#193599 = ADVANCED_FACE('',(#193600),#184421,.T.); -#193600 = FACE_BOUND('',#193601,.T.); -#193601 = EDGE_LOOP('',(#193602,#193603,#193669,#193670,#193671)); -#193602 = ORIENTED_EDGE('',*,*,#187338,.F.); -#193603 = ORIENTED_EDGE('',*,*,#193604,.T.); -#193604 = EDGE_CURVE('',#187294,#184364,#193605,.T.); -#193605 = SURFACE_CURVE('',#193606,(#193611,#193640),.PCURVE_S1.); -#193606 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193607,#193608,#193609, -#193610),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#195963 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#195964 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#195965 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#195966 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#195967 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#195968 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#195969 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#195970 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#195971 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#195972 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#195973 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#195974 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#195975 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#195976 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#195977 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); +#195978 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); +#195979 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); +#195980 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); +#195981 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); +#195982 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); +#195983 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); +#195984 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); +#195985 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); +#195986 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); +#195987 = CARTESIAN_POINT('',(0.751879414295,1.)); +#195988 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#195989 = ORIENTED_EDGE('',*,*,#189005,.F.); +#195990 = ORIENTED_EDGE('',*,*,#195853,.T.); +#195991 = ADVANCED_FACE('',(#195992),#186813,.T.); +#195992 = FACE_BOUND('',#195993,.T.); +#195993 = EDGE_LOOP('',(#195994,#195995,#196061,#196062,#196063)); +#195994 = ORIENTED_EDGE('',*,*,#189730,.F.); +#195995 = ORIENTED_EDGE('',*,*,#195996,.T.); +#195996 = EDGE_CURVE('',#189686,#186756,#195997,.T.); +#195997 = SURFACE_CURVE('',#195998,(#196003,#196032),.PCURVE_S1.); +#195998 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#195999,#196000,#196001, +#196002),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193607 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 +#195999 = CARTESIAN_POINT('',(1.362750264943,-0.407861391,0.962940952255 )); -#193608 = CARTESIAN_POINT('',(1.361917855478,-0.44680534294, +#196000 = CARTESIAN_POINT('',(1.361917855478,-0.44680534294, 0.966047546673)); -#193609 = CARTESIAN_POINT('',(1.34683376285,-0.482375921036,0.967717466) +#196001 = CARTESIAN_POINT('',(1.34683376285,-0.482375921036,0.967717466) ); -#193610 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 +#196002 = CARTESIAN_POINT('',(1.319604841943,-0.509604841943,0.967717466 )); -#193611 = PCURVE('',#184421,#193612); -#193612 = DEFINITIONAL_REPRESENTATION('',(#193613),#193639); -#193613 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193614,#193615,#193616, - #193617,#193618,#193619,#193620,#193621,#193622,#193623,#193624, - #193625,#193626,#193627,#193628,#193629,#193630,#193631,#193632, - #193633,#193634,#193635,#193636,#193637,#193638),.UNSPECIFIED.,.F., +#196003 = PCURVE('',#186813,#196004); +#196004 = DEFINITIONAL_REPRESENTATION('',(#196005),#196031); +#196005 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196006,#196007,#196008, + #196009,#196010,#196011,#196012,#196013,#196014,#196015,#196016, + #196017,#196018,#196019,#196020,#196021,#196022,#196023,#196024, + #196025,#196026,#196027,#196028,#196029,#196030),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240544,40 +243546,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193614 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); -#193615 = CARTESIAN_POINT('',(3.152718260825,-9.840933791906E-002)); -#193616 = CARTESIAN_POINT('',(3.175040310705,-9.78418886995E-002)); -#193617 = CARTESIAN_POINT('',(3.208718289392,-9.701801370533E-002)); -#193618 = CARTESIAN_POINT('',(3.242573805888,-9.622336170581E-002)); -#193619 = CARTESIAN_POINT('',(3.276588667066,-9.545977421098E-002)); -#193620 = CARTESIAN_POINT('',(3.310744202863,-9.472902264469E-002)); -#193621 = CARTESIAN_POINT('',(3.34502124338,-9.403278942409E-002)); -#193622 = CARTESIAN_POINT('',(3.379400201195,-9.337265803686E-002)); -#193623 = CARTESIAN_POINT('',(3.413861130172,-9.275010147284E-002)); -#193624 = CARTESIAN_POINT('',(3.448383794636,-9.216647205879E-002)); -#193625 = CARTESIAN_POINT('',(3.482947739147,-9.162299206488E-002)); -#193626 = CARTESIAN_POINT('',(3.517532360737,-9.112074542238E-002)); -#193627 = CARTESIAN_POINT('',(3.552116982328,-9.066067061216E-002)); -#193628 = CARTESIAN_POINT('',(3.586680926839,-9.024355483614E-002)); -#193629 = CARTESIAN_POINT('',(3.621203591303,-8.987002954109E-002)); -#193630 = CARTESIAN_POINT('',(3.65566452028,-8.954056735899E-002)); -#193631 = CARTESIAN_POINT('',(3.690043478095,-8.92554804551E-002)); -#193632 = CARTESIAN_POINT('',(3.724320518612,-8.901492043166E-002)); -#193633 = CARTESIAN_POINT('',(3.758476054408,-8.881887923673E-002)); -#193634 = CARTESIAN_POINT('',(3.792490915587,-8.866719302101E-002)); -#193635 = CARTESIAN_POINT('',(3.826346432082,-8.855954147362E-002)); -#193636 = CARTESIAN_POINT('',(3.86002441077,-8.849547019148E-002)); -#193637 = CARTESIAN_POINT('',(3.88234646065,-8.848137862171E-002)); -#193638 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); -#193639 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193640 = PCURVE('',#184494,#193641); -#193641 = DEFINITIONAL_REPRESENTATION('',(#193642),#193668); -#193642 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193643,#193644,#193645, - #193646,#193647,#193648,#193649,#193650,#193651,#193652,#193653, - #193654,#193655,#193656,#193657,#193658,#193659,#193660,#193661, - #193662,#193663,#193664,#193665,#193666,#193667),.UNSPECIFIED.,.F., +#196006 = CARTESIAN_POINT('',(3.14159265359,-9.869729557715E-002)); +#196007 = CARTESIAN_POINT('',(3.152718260825,-9.840933791906E-002)); +#196008 = CARTESIAN_POINT('',(3.175040310705,-9.78418886995E-002)); +#196009 = CARTESIAN_POINT('',(3.208718289392,-9.701801370533E-002)); +#196010 = CARTESIAN_POINT('',(3.242573805888,-9.622336170581E-002)); +#196011 = CARTESIAN_POINT('',(3.276588667066,-9.545977421098E-002)); +#196012 = CARTESIAN_POINT('',(3.310744202863,-9.472902264469E-002)); +#196013 = CARTESIAN_POINT('',(3.34502124338,-9.403278942409E-002)); +#196014 = CARTESIAN_POINT('',(3.379400201195,-9.337265803686E-002)); +#196015 = CARTESIAN_POINT('',(3.413861130172,-9.275010147284E-002)); +#196016 = CARTESIAN_POINT('',(3.448383794636,-9.216647205879E-002)); +#196017 = CARTESIAN_POINT('',(3.482947739147,-9.162299206488E-002)); +#196018 = CARTESIAN_POINT('',(3.517532360737,-9.112074542238E-002)); +#196019 = CARTESIAN_POINT('',(3.552116982328,-9.066067061216E-002)); +#196020 = CARTESIAN_POINT('',(3.586680926839,-9.024355483614E-002)); +#196021 = CARTESIAN_POINT('',(3.621203591303,-8.987002954109E-002)); +#196022 = CARTESIAN_POINT('',(3.65566452028,-8.954056735899E-002)); +#196023 = CARTESIAN_POINT('',(3.690043478095,-8.92554804551E-002)); +#196024 = CARTESIAN_POINT('',(3.724320518612,-8.901492043166E-002)); +#196025 = CARTESIAN_POINT('',(3.758476054408,-8.881887923673E-002)); +#196026 = CARTESIAN_POINT('',(3.792490915587,-8.866719302101E-002)); +#196027 = CARTESIAN_POINT('',(3.826346432082,-8.855954147362E-002)); +#196028 = CARTESIAN_POINT('',(3.86002441077,-8.849547019148E-002)); +#196029 = CARTESIAN_POINT('',(3.88234646065,-8.848137862171E-002)); +#196030 = CARTESIAN_POINT('',(3.893472067885,-8.84813899082E-002)); +#196031 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196032 = PCURVE('',#186886,#196033); +#196033 = DEFINITIONAL_REPRESENTATION('',(#196034),#196060); +#196034 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196035,#196036,#196037, + #196038,#196039,#196040,#196041,#196042,#196043,#196044,#196045, + #196046,#196047,#196048,#196049,#196050,#196051,#196052,#196053, + #196054,#196055,#196056,#196057,#196058,#196059),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240585,56 +243587,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193643 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#193644 = CARTESIAN_POINT('',(0.740753686904,5.712075427117E-008)); -#193645 = CARTESIAN_POINT('',(0.718425946425,-7.920681094289E-006)); -#193646 = CARTESIAN_POINT('',(0.684729502759,-3.211561474216E-005)); -#193647 = CARTESIAN_POINT('',(0.650851510226,-9.135814826314E-005)); -#193648 = CARTESIAN_POINT('',(0.616817843137,-8.643221197507E-005)); -#193649 = CARTESIAN_POINT('',(0.582648204505,-8.687395637419E-005)); -#193650 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); -#193651 = CARTESIAN_POINT('',(0.513985713406,-8.542361087672E-005)); -#193652 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); -#193653 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); -#193654 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); -#193655 = CARTESIAN_POINT('',(0.375920232966,-8.346461190825E-005)); -#193656 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); -#193657 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); -#193658 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); -#193659 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); -#193660 = CARTESIAN_POINT('',(0.203491552027,-8.179989506537E-005)); -#193661 = CARTESIAN_POINT('',(0.169212469737,-8.226451401244E-005)); -#193662 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); -#193663 = CARTESIAN_POINT('',(0.101018376289,-8.868396576113E-005)); -#193664 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095804E-005) - ); -#193665 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467402E-005) - ); -#193666 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134499E-006)); -#193667 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); -#193668 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193669 = ORIENTED_EDGE('',*,*,#184363,.T.); -#193670 = ORIENTED_EDGE('',*,*,#185807,.F.); -#193671 = ORIENTED_EDGE('',*,*,#193672,.F.); -#193672 = EDGE_CURVE('',#186252,#185808,#193673,.T.); -#193673 = SURFACE_CURVE('',#193674,(#193679,#193708),.PCURVE_S1.); -#193674 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193675,#193676,#193677, -#193678),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#196035 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196036 = CARTESIAN_POINT('',(0.740753686904,5.712075427117E-008)); +#196037 = CARTESIAN_POINT('',(0.718425946425,-7.920681094289E-006)); +#196038 = CARTESIAN_POINT('',(0.684729502759,-3.211561474216E-005)); +#196039 = CARTESIAN_POINT('',(0.650851510226,-9.135814826314E-005)); +#196040 = CARTESIAN_POINT('',(0.616817843137,-8.643221197507E-005)); +#196041 = CARTESIAN_POINT('',(0.582648204505,-8.687395637419E-005)); +#196042 = CARTESIAN_POINT('',(0.548364026632,-8.59354538626E-005)); +#196043 = CARTESIAN_POINT('',(0.513985713406,-8.542361087672E-005)); +#196044 = CARTESIAN_POINT('',(0.479533105651,-8.485308627406E-005)); +#196045 = CARTESIAN_POINT('',(0.445025477762,-8.435280808234E-005)); +#196046 = CARTESIAN_POINT('',(0.410481676253,-8.388702482307E-005)); +#196047 = CARTESIAN_POINT('',(0.375920232966,-8.346461190825E-005)); +#196048 = CARTESIAN_POINT('',(0.341359494752,-8.308081522499E-005)); +#196049 = CARTESIAN_POINT('',(0.306817755739,-8.274098333127E-005)); +#196050 = CARTESIAN_POINT('',(0.272313393703,-8.24239008421E-005)); +#196051 = CARTESIAN_POINT('',(0.237865006819,-8.220472162591E-005)); +#196052 = CARTESIAN_POINT('',(0.203491552027,-8.179989506537E-005)); +#196053 = CARTESIAN_POINT('',(0.169212469737,-8.226451401244E-005)); +#196054 = CARTESIAN_POINT('',(0.135047837564,-7.965797689905E-005)); +#196055 = CARTESIAN_POINT('',(0.101018376289,-8.868396576113E-005)); +#196056 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095804E-005) + ); +#196057 = CARTESIAN_POINT('',(3.345266820762E-002,-1.037052467402E-005) + ); +#196058 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134499E-006)); +#196059 = CARTESIAN_POINT('',(-8.881784197001E-016,0.E+000)); +#196060 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196061 = ORIENTED_EDGE('',*,*,#186755,.T.); +#196062 = ORIENTED_EDGE('',*,*,#188199,.F.); +#196063 = ORIENTED_EDGE('',*,*,#196064,.F.); +#196064 = EDGE_CURVE('',#188644,#188200,#196065,.T.); +#196065 = SURFACE_CURVE('',#196066,(#196071,#196100),.PCURVE_S1.); +#196066 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#196067,#196068,#196069, +#196070),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#193675 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); -#193676 = CARTESIAN_POINT('',(1.46,-0.591121542172,0.6)); -#193677 = CARTESIAN_POINT('',(1.401121542172,-0.65,0.6)); -#193678 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); -#193679 = PCURVE('',#184421,#193680); -#193680 = DEFINITIONAL_REPRESENTATION('',(#193681),#193707); -#193681 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193682,#193683,#193684, - #193685,#193686,#193687,#193688,#193689,#193690,#193691,#193692, - #193693,#193694,#193695,#193696,#193697,#193698,#193699,#193700, - #193701,#193702,#193703,#193704,#193705,#193706),.UNSPECIFIED.,.F., +#196067 = CARTESIAN_POINT('',(1.46,-0.505111126057,0.6)); +#196068 = CARTESIAN_POINT('',(1.46,-0.591121542172,0.6)); +#196069 = CARTESIAN_POINT('',(1.401121542172,-0.65,0.6)); +#196070 = CARTESIAN_POINT('',(1.315111126057,-0.65,0.6)); +#196071 = PCURVE('',#186813,#196072); +#196072 = DEFINITIONAL_REPRESENTATION('',(#196073),#196099); +#196073 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196074,#196075,#196076, + #196077,#196078,#196079,#196080,#196081,#196082,#196083,#196084, + #196085,#196086,#196087,#196088,#196089,#196090,#196091,#196092, + #196093,#196094,#196095,#196096,#196097,#196098),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240642,40 +243644,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193682 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); -#193683 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); -#193684 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); -#193685 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); -#193686 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); -#193687 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); -#193688 = CARTESIAN_POINT('',(3.469181876599,0.299752403237)); -#193689 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); -#193690 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); -#193691 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); -#193692 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); -#193693 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); -#193694 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); -#193695 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); -#193696 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); -#193697 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); -#193698 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); -#193699 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); -#193700 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); -#193701 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); -#193702 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); -#193703 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); -#193704 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); -#193705 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); -#193706 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); -#193707 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193708 = PCURVE('',#183150,#193709); -#193709 = DEFINITIONAL_REPRESENTATION('',(#193710),#193736); -#193710 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193711,#193712,#193713, - #193714,#193715,#193716,#193717,#193718,#193719,#193720,#193721, - #193722,#193723,#193724,#193725,#193726,#193727,#193728,#193729, - #193730,#193731,#193732,#193733,#193734,#193735),.UNSPECIFIED.,.F., +#196074 = CARTESIAN_POINT('',(3.14159265359,0.289427886241)); +#196075 = CARTESIAN_POINT('',(3.162288729352,0.290231383753)); +#196076 = CARTESIAN_POINT('',(3.204192988946,0.291804855317)); +#196077 = CARTESIAN_POINT('',(3.268497605682,0.294040085945)); +#196078 = CARTESIAN_POINT('',(3.334168412726,0.296125965655)); +#196079 = CARTESIAN_POINT('',(3.401102163639,0.298038007772)); +#196080 = CARTESIAN_POINT('',(3.469181876599,0.299752403237)); +#196081 = CARTESIAN_POINT('',(3.538275496395,0.30124662844)); +#196082 = CARTESIAN_POINT('',(3.608237447743,0.302500135954)); +#196083 = CARTESIAN_POINT('',(3.678909952694,0.303495015496)); +#196084 = CARTESIAN_POINT('',(3.750124930834,0.304216608922)); +#196085 = CARTESIAN_POINT('',(3.821706213821,0.304654036118)); +#196086 = CARTESIAN_POINT('',(3.893472067885,0.304800599057)); +#196087 = CARTESIAN_POINT('',(3.965237921948,0.304654036118)); +#196088 = CARTESIAN_POINT('',(4.036819204936,0.304216608922)); +#196089 = CARTESIAN_POINT('',(4.108034183076,0.303495015496)); +#196090 = CARTESIAN_POINT('',(4.178706688026,0.302500135954)); +#196091 = CARTESIAN_POINT('',(4.248668639375,0.30124662844)); +#196092 = CARTESIAN_POINT('',(4.317762259171,0.299752403237)); +#196093 = CARTESIAN_POINT('',(4.38584197213,0.298038007772)); +#196094 = CARTESIAN_POINT('',(4.452775723043,0.296125965655)); +#196095 = CARTESIAN_POINT('',(4.518446530087,0.294040085945)); +#196096 = CARTESIAN_POINT('',(4.582751146823,0.291804855317)); +#196097 = CARTESIAN_POINT('',(4.624655406418,0.290231383753)); +#196098 = CARTESIAN_POINT('',(4.64535148218,0.289427886241)); +#196099 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196100 = PCURVE('',#185542,#196101); +#196101 = DEFINITIONAL_REPRESENTATION('',(#196102),#196128); +#196102 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196103,#196104,#196105, + #196106,#196107,#196108,#196109,#196110,#196111,#196112,#196113, + #196114,#196115,#196116,#196117,#196118,#196119,#196120,#196121, + #196122,#196123,#196124,#196125,#196126,#196127),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937046,6.009774611072,6.078127285099, @@ -240683,60 +243685,60 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193711 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); -#193712 = CARTESIAN_POINT('',(6.262489231417,0.696143131232)); -#193713 = CARTESIAN_POINT('',(6.220584971823,0.697716602796)); -#193714 = CARTESIAN_POINT('',(6.156280355087,0.699951833424)); -#193715 = CARTESIAN_POINT('',(6.090609548043,0.702037713133)); -#193716 = CARTESIAN_POINT('',(6.02367579713,0.703949755251)); -#193717 = CARTESIAN_POINT('',(5.955596084171,0.705664150716)); -#193718 = CARTESIAN_POINT('',(5.886502464374,0.707158375919)); -#193719 = CARTESIAN_POINT('',(5.816540513026,0.708411883433)); -#193720 = CARTESIAN_POINT('',(5.745868008076,0.709406762975)); -#193721 = CARTESIAN_POINT('',(5.674653029936,0.710128356401)); -#193722 = CARTESIAN_POINT('',(5.603071746948,0.710565783597)); -#193723 = CARTESIAN_POINT('',(5.531305892885,0.710712346536)); -#193724 = CARTESIAN_POINT('',(5.459540038821,0.710565783597)); -#193725 = CARTESIAN_POINT('',(5.387958755834,0.710128356401)); -#193726 = CARTESIAN_POINT('',(5.316743777694,0.709406762975)); -#193727 = CARTESIAN_POINT('',(5.246071272743,0.708411883433)); -#193728 = CARTESIAN_POINT('',(5.176109321395,0.707158375919)); -#193729 = CARTESIAN_POINT('',(5.107015701598,0.705664150716)); -#193730 = CARTESIAN_POINT('',(5.038935988639,0.703949755251)); -#193731 = CARTESIAN_POINT('',(4.972002237726,0.702037713133)); -#193732 = CARTESIAN_POINT('',(4.906331430682,0.699951833424)); -#193733 = CARTESIAN_POINT('',(4.842026813946,0.697716602796)); -#193734 = CARTESIAN_POINT('',(4.800122554352,0.696143131232)); -#193735 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); -#193736 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193737 = ADVANCED_FACE('',(#193738),#183150,.T.); -#193738 = FACE_BOUND('',#193739,.T.); -#193739 = EDGE_LOOP('',(#193740,#193741,#193742,#193808,#193809)); -#193740 = ORIENTED_EDGE('',*,*,#186485,.F.); -#193741 = ORIENTED_EDGE('',*,*,#183111,.T.); -#193742 = ORIENTED_EDGE('',*,*,#193743,.T.); -#193743 = EDGE_CURVE('',#183027,#186254,#193744,.T.); -#193744 = SURFACE_CURVE('',#193745,(#193750,#193779),.PCURVE_S1.); -#193745 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193746,#193747,#193748, -#193749),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#196103 = CARTESIAN_POINT('',(6.28318530718,0.69533963372)); +#196104 = CARTESIAN_POINT('',(6.262489231417,0.696143131232)); +#196105 = CARTESIAN_POINT('',(6.220584971823,0.697716602796)); +#196106 = CARTESIAN_POINT('',(6.156280355087,0.699951833424)); +#196107 = CARTESIAN_POINT('',(6.090609548043,0.702037713133)); +#196108 = CARTESIAN_POINT('',(6.02367579713,0.703949755251)); +#196109 = CARTESIAN_POINT('',(5.955596084171,0.705664150716)); +#196110 = CARTESIAN_POINT('',(5.886502464374,0.707158375919)); +#196111 = CARTESIAN_POINT('',(5.816540513026,0.708411883433)); +#196112 = CARTESIAN_POINT('',(5.745868008076,0.709406762975)); +#196113 = CARTESIAN_POINT('',(5.674653029936,0.710128356401)); +#196114 = CARTESIAN_POINT('',(5.603071746948,0.710565783597)); +#196115 = CARTESIAN_POINT('',(5.531305892885,0.710712346536)); +#196116 = CARTESIAN_POINT('',(5.459540038821,0.710565783597)); +#196117 = CARTESIAN_POINT('',(5.387958755834,0.710128356401)); +#196118 = CARTESIAN_POINT('',(5.316743777694,0.709406762975)); +#196119 = CARTESIAN_POINT('',(5.246071272743,0.708411883433)); +#196120 = CARTESIAN_POINT('',(5.176109321395,0.707158375919)); +#196121 = CARTESIAN_POINT('',(5.107015701598,0.705664150716)); +#196122 = CARTESIAN_POINT('',(5.038935988639,0.703949755251)); +#196123 = CARTESIAN_POINT('',(4.972002237726,0.702037713133)); +#196124 = CARTESIAN_POINT('',(4.906331430682,0.699951833424)); +#196125 = CARTESIAN_POINT('',(4.842026813946,0.697716602796)); +#196126 = CARTESIAN_POINT('',(4.800122554352,0.696143131232)); +#196127 = CARTESIAN_POINT('',(4.77942647859,0.69533963372)); +#196128 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196129 = ADVANCED_FACE('',(#196130),#185542,.T.); +#196130 = FACE_BOUND('',#196131,.T.); +#196131 = EDGE_LOOP('',(#196132,#196133,#196134,#196200,#196201)); +#196132 = ORIENTED_EDGE('',*,*,#188877,.F.); +#196133 = ORIENTED_EDGE('',*,*,#185503,.T.); +#196134 = ORIENTED_EDGE('',*,*,#196135,.T.); +#196135 = EDGE_CURVE('',#185419,#188646,#196136,.T.); +#196136 = SURFACE_CURVE('',#196137,(#196142,#196171),.PCURVE_S1.); +#196137 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#196138,#196139,#196140, +#196141),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.421010862428E-016,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193746 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); -#193747 = CARTESIAN_POINT('',(1.320038843607,-0.455581001793,0.132282534 +#196138 = CARTESIAN_POINT('',(1.2928099227,-0.4828099227,0.132282534)); +#196139 = CARTESIAN_POINT('',(1.320038843607,-0.455581001793,0.132282534 )); -#193748 = CARTESIAN_POINT('',(1.335122936235,-0.420010423697, +#196140 = CARTESIAN_POINT('',(1.335122936235,-0.420010423697, 0.133952453327)); -#193749 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, +#196141 = CARTESIAN_POINT('',(1.3359553457,-0.381066471757, 0.137059047745)); -#193750 = PCURVE('',#183150,#193751); -#193751 = DEFINITIONAL_REPRESENTATION('',(#193752),#193778); -#193752 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193753,#193754,#193755, - #193756,#193757,#193758,#193759,#193760,#193761,#193762,#193763, - #193764,#193765,#193766,#193767,#193768,#193769,#193770,#193771, - #193772,#193773,#193774,#193775,#193776,#193777),.UNSPECIFIED.,.F., +#196142 = PCURVE('',#185542,#196143); +#196143 = DEFINITIONAL_REPRESENTATION('',(#196144),#196170); +#196144 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196145,#196146,#196147, + #196148,#196149,#196150,#196151,#196152,#196153,#196154,#196155, + #196156,#196157,#196158,#196159,#196160,#196161,#196162,#196163, + #196164,#196165,#196166,#196167,#196168,#196169),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 5.421010862428E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240745,40 +243747,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#193753 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); -#193754 = CARTESIAN_POINT('',(5.542431500119,0.210491435842)); -#193755 = CARTESIAN_POINT('',(5.56475355,0.210477344272)); -#193756 = CARTESIAN_POINT('',(5.598431528687,0.21041327299)); -#193757 = CARTESIAN_POINT('',(5.632287045183,0.210305621442)); -#193758 = CARTESIAN_POINT('',(5.666301906361,0.210153935227)); -#193759 = CARTESIAN_POINT('',(5.700457442157,0.209957894032)); -#193760 = CARTESIAN_POINT('',(5.734734482675,0.209717334008)); -#193761 = CARTESIAN_POINT('',(5.76911344049,0.209432247104)); -#193762 = CARTESIAN_POINT('',(5.803574369467,0.209102784922)); -#193763 = CARTESIAN_POINT('',(5.838097033931,0.208729259627)); -#193764 = CARTESIAN_POINT('',(5.872660978441,0.208312143851)); -#193765 = CARTESIAN_POINT('',(5.907245600032,0.207852069041)); -#193766 = CARTESIAN_POINT('',(5.941830221623,0.207349822399)); -#193767 = CARTESIAN_POINT('',(5.976394166134,0.206806342405)); -#193768 = CARTESIAN_POINT('',(6.010916830598,0.206222712991)); -#193769 = CARTESIAN_POINT('',(6.045377759574,0.205600156427)); -#193770 = CARTESIAN_POINT('',(6.079756717389,0.204940025039)); -#193771 = CARTESIAN_POINT('',(6.114033757907,0.204243791819)); -#193772 = CARTESIAN_POINT('',(6.148189293703,0.203513040252)); -#193773 = CARTESIAN_POINT('',(6.182204154882,0.202749452758)); -#193774 = CARTESIAN_POINT('',(6.216059671377,0.201954800758)); -#193775 = CARTESIAN_POINT('',(6.249737650065,0.201130925764)); -#193776 = CARTESIAN_POINT('',(6.272059699945,0.200563476544)); -#193777 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); -#193778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193779 = PCURVE('',#183065,#193780); -#193780 = DEFINITIONAL_REPRESENTATION('',(#193781),#193807); -#193781 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193782,#193783,#193784, - #193785,#193786,#193787,#193788,#193789,#193790,#193791,#193792, - #193793,#193794,#193795,#193796,#193797,#193798,#193799,#193800, - #193801,#193802,#193803,#193804,#193805,#193806),.UNSPECIFIED.,.F., +#196145 = CARTESIAN_POINT('',(5.531305892885,0.210491424555)); +#196146 = CARTESIAN_POINT('',(5.542431500119,0.210491435842)); +#196147 = CARTESIAN_POINT('',(5.56475355,0.210477344272)); +#196148 = CARTESIAN_POINT('',(5.598431528687,0.21041327299)); +#196149 = CARTESIAN_POINT('',(5.632287045183,0.210305621442)); +#196150 = CARTESIAN_POINT('',(5.666301906361,0.210153935227)); +#196151 = CARTESIAN_POINT('',(5.700457442157,0.209957894032)); +#196152 = CARTESIAN_POINT('',(5.734734482675,0.209717334008)); +#196153 = CARTESIAN_POINT('',(5.76911344049,0.209432247104)); +#196154 = CARTESIAN_POINT('',(5.803574369467,0.209102784922)); +#196155 = CARTESIAN_POINT('',(5.838097033931,0.208729259627)); +#196156 = CARTESIAN_POINT('',(5.872660978441,0.208312143851)); +#196157 = CARTESIAN_POINT('',(5.907245600032,0.207852069041)); +#196158 = CARTESIAN_POINT('',(5.941830221623,0.207349822399)); +#196159 = CARTESIAN_POINT('',(5.976394166134,0.206806342405)); +#196160 = CARTESIAN_POINT('',(6.010916830598,0.206222712991)); +#196161 = CARTESIAN_POINT('',(6.045377759574,0.205600156427)); +#196162 = CARTESIAN_POINT('',(6.079756717389,0.204940025039)); +#196163 = CARTESIAN_POINT('',(6.114033757907,0.204243791819)); +#196164 = CARTESIAN_POINT('',(6.148189293703,0.203513040252)); +#196165 = CARTESIAN_POINT('',(6.182204154882,0.202749452758)); +#196166 = CARTESIAN_POINT('',(6.216059671377,0.201954800758)); +#196167 = CARTESIAN_POINT('',(6.249737650065,0.201130925764)); +#196168 = CARTESIAN_POINT('',(6.272059699945,0.200563476544)); +#196169 = CARTESIAN_POINT('',(6.28318530718,0.200275518886)); +#196170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196171 = PCURVE('',#185457,#196172); +#196172 = DEFINITIONAL_REPRESENTATION('',(#196173),#196199); +#196173 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196174,#196175,#196176, + #196177,#196178,#196179,#196180,#196181,#196182,#196183,#196184, + #196185,#196186,#196187,#196188,#196189,#196190,#196191,#196192, + #196193,#196194,#196195,#196196,#196197,#196198),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),( 5.421010862428E-016,3.417633701341E-002,6.835267402682E-002, 0.10252901104,0.136705348054,0.170881685067,0.20505802208, @@ -240787,62 +243789,62 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.512645055201,0.546821392215,0.580997729228,0.615174066241, 0.649350403255,0.683526740268,0.717703077282,0.751879414295), .QUASI_UNIFORM_KNOTS.); -#193782 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); -#193783 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#193784 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#193785 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); -#193786 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#193787 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#193788 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#193789 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#193790 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#193791 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#193792 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#193793 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#193794 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#193795 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#193796 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); -#193797 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); -#193798 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); -#193799 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); -#193800 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); -#193801 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); -#193802 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); -#193803 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); -#193804 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); -#193805 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); -#193806 = CARTESIAN_POINT('',(0.751879414295,1.)); -#193807 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193808 = ORIENTED_EDGE('',*,*,#186251,.F.); -#193809 = ORIENTED_EDGE('',*,*,#193672,.T.); -#193810 = ADVANCED_FACE('',(#193811),#184971,.T.); -#193811 = FACE_BOUND('',#193812,.T.); -#193812 = EDGE_LOOP('',(#193813,#193814,#193880,#193881,#193882)); -#193813 = ORIENTED_EDGE('',*,*,#185412,.F.); -#193814 = ORIENTED_EDGE('',*,*,#193815,.T.); -#193815 = EDGE_CURVE('',#185391,#184914,#193816,.T.); -#193816 = SURFACE_CURVE('',#193817,(#193822,#193851),.PCURVE_S1.); -#193817 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193818,#193819,#193820, -#193821),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#196174 = CARTESIAN_POINT('',(-8.881784197001E-016,1.)); +#196175 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#196176 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#196177 = CARTESIAN_POINT('',(6.714594636694E-002,1.000054464841)); +#196178 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#196179 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#196180 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#196181 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#196182 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#196183 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#196184 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#196185 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#196186 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#196187 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#196188 = CARTESIAN_POINT('',(0.445025477762,1.000084352808)); +#196189 = CARTESIAN_POINT('',(0.479533105651,1.000084853086)); +#196190 = CARTESIAN_POINT('',(0.513985713406,1.000085423611)); +#196191 = CARTESIAN_POINT('',(0.548364026632,1.000085935454)); +#196192 = CARTESIAN_POINT('',(0.582648204505,1.000086873956)); +#196193 = CARTESIAN_POINT('',(0.616817843137,1.000086432212)); +#196194 = CARTESIAN_POINT('',(0.650851510226,1.000091358148)); +#196195 = CARTESIAN_POINT('',(0.684729502759,1.000032115615)); +#196196 = CARTESIAN_POINT('',(0.718425946425,1.000007920681)); +#196197 = CARTESIAN_POINT('',(0.740753686904,0.999999942879)); +#196198 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196199 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196200 = ORIENTED_EDGE('',*,*,#188643,.F.); +#196201 = ORIENTED_EDGE('',*,*,#196064,.T.); +#196202 = ADVANCED_FACE('',(#196203),#187363,.T.); +#196203 = FACE_BOUND('',#196204,.T.); +#196204 = EDGE_LOOP('',(#196205,#196206,#196272,#196273,#196274)); +#196205 = ORIENTED_EDGE('',*,*,#187804,.F.); +#196206 = ORIENTED_EDGE('',*,*,#196207,.T.); +#196207 = EDGE_CURVE('',#187783,#187306,#196208,.T.); +#196208 = SURFACE_CURVE('',#196209,(#196214,#196243),.PCURVE_S1.); +#196209 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#196210,#196211,#196212, +#196213),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,6.28318530718),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193818 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) +#196210 = CARTESIAN_POINT('',(1.217861391,0.552750264943,0.962940952255) ); -#193819 = CARTESIAN_POINT('',(1.25680534294,0.551917855478, +#196211 = CARTESIAN_POINT('',(1.25680534294,0.551917855478, 0.966047546673)); -#193820 = CARTESIAN_POINT('',(1.292375921036,0.53683376285,0.967717466) +#196212 = CARTESIAN_POINT('',(1.292375921036,0.53683376285,0.967717466) ); -#193821 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) +#196213 = CARTESIAN_POINT('',(1.319604841943,0.509604841943,0.967717466) ); -#193822 = PCURVE('',#184971,#193823); -#193823 = DEFINITIONAL_REPRESENTATION('',(#193824),#193850); -#193824 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193825,#193826,#193827, - #193828,#193829,#193830,#193831,#193832,#193833,#193834,#193835, - #193836,#193837,#193838,#193839,#193840,#193841,#193842,#193843, - #193844,#193845,#193846,#193847,#193848,#193849),.UNSPECIFIED.,.F., +#196214 = PCURVE('',#187363,#196215); +#196215 = DEFINITIONAL_REPRESENTATION('',(#196216),#196242); +#196216 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196217,#196218,#196219, + #196220,#196221,#196222,#196223,#196224,#196225,#196226,#196227, + #196228,#196229,#196230,#196231,#196232,#196233,#196234,#196235, + #196236,#196237,#196238,#196239,#196240,#196241),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240850,40 +243852,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193825 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); -#193826 = CARTESIAN_POINT('',(1.648959432235,0.30750240956)); -#193827 = CARTESIAN_POINT('',(1.671281482115,0.308069858779)); -#193828 = CARTESIAN_POINT('',(1.704959460802,0.308893733774)); -#193829 = CARTESIAN_POINT('',(1.738814977298,0.309688385773)); -#193830 = CARTESIAN_POINT('',(1.772829838476,0.310451973268)); -#193831 = CARTESIAN_POINT('',(1.806985374273,0.311182724834)); -#193832 = CARTESIAN_POINT('',(1.84126241479,0.311878958055)); -#193833 = CARTESIAN_POINT('',(1.875641372605,0.312539089442)); -#193834 = CARTESIAN_POINT('',(1.910102301582,0.313161646006)); -#193835 = CARTESIAN_POINT('',(1.944624966046,0.31374527542)); -#193836 = CARTESIAN_POINT('',(1.979188910557,0.314288755414)); -#193837 = CARTESIAN_POINT('',(2.013773532147,0.314791002057)); -#193838 = CARTESIAN_POINT('',(2.048358153738,0.315251076867)); -#193839 = CARTESIAN_POINT('',(2.082922098249,0.315668192643)); -#193840 = CARTESIAN_POINT('',(2.117444762713,0.316041717938)); -#193841 = CARTESIAN_POINT('',(2.15190569169,0.31637118012)); -#193842 = CARTESIAN_POINT('',(2.186284649505,0.316656267024)); -#193843 = CARTESIAN_POINT('',(2.220561690022,0.316896827047)); -#193844 = CARTESIAN_POINT('',(2.254717225818,0.317092868242)); -#193845 = CARTESIAN_POINT('',(2.288732086997,0.317244554458)); -#193846 = CARTESIAN_POINT('',(2.322587603492,0.317352206005)); -#193847 = CARTESIAN_POINT('',(2.35626558218,0.317416277287)); -#193848 = CARTESIAN_POINT('',(2.37858763206,0.317430368857)); -#193849 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); -#193850 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193851 = PCURVE('',#185044,#193852); -#193852 = DEFINITIONAL_REPRESENTATION('',(#193853),#193879); -#193853 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193854,#193855,#193856, - #193857,#193858,#193859,#193860,#193861,#193862,#193863,#193864, - #193865,#193866,#193867,#193868,#193869,#193870,#193871,#193872, - #193873,#193874,#193875,#193876,#193877,#193878),.UNSPECIFIED.,.F., +#196217 = CARTESIAN_POINT('',(1.637833825,0.307214451902)); +#196218 = CARTESIAN_POINT('',(1.648959432235,0.30750240956)); +#196219 = CARTESIAN_POINT('',(1.671281482115,0.308069858779)); +#196220 = CARTESIAN_POINT('',(1.704959460802,0.308893733774)); +#196221 = CARTESIAN_POINT('',(1.738814977298,0.309688385773)); +#196222 = CARTESIAN_POINT('',(1.772829838476,0.310451973268)); +#196223 = CARTESIAN_POINT('',(1.806985374273,0.311182724834)); +#196224 = CARTESIAN_POINT('',(1.84126241479,0.311878958055)); +#196225 = CARTESIAN_POINT('',(1.875641372605,0.312539089442)); +#196226 = CARTESIAN_POINT('',(1.910102301582,0.313161646006)); +#196227 = CARTESIAN_POINT('',(1.944624966046,0.31374527542)); +#196228 = CARTESIAN_POINT('',(1.979188910557,0.314288755414)); +#196229 = CARTESIAN_POINT('',(2.013773532147,0.314791002057)); +#196230 = CARTESIAN_POINT('',(2.048358153738,0.315251076867)); +#196231 = CARTESIAN_POINT('',(2.082922098249,0.315668192643)); +#196232 = CARTESIAN_POINT('',(2.117444762713,0.316041717938)); +#196233 = CARTESIAN_POINT('',(2.15190569169,0.31637118012)); +#196234 = CARTESIAN_POINT('',(2.186284649505,0.316656267024)); +#196235 = CARTESIAN_POINT('',(2.220561690022,0.316896827047)); +#196236 = CARTESIAN_POINT('',(2.254717225818,0.317092868242)); +#196237 = CARTESIAN_POINT('',(2.288732086997,0.317244554458)); +#196238 = CARTESIAN_POINT('',(2.322587603492,0.317352206005)); +#196239 = CARTESIAN_POINT('',(2.35626558218,0.317416277287)); +#196240 = CARTESIAN_POINT('',(2.37858763206,0.317430368857)); +#196241 = CARTESIAN_POINT('',(2.389713239295,0.317430357571)); +#196242 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196243 = PCURVE('',#187436,#196244); +#196244 = DEFINITIONAL_REPRESENTATION('',(#196245),#196271); +#196245 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196246,#196247,#196248, + #196249,#196250,#196251,#196252,#196253,#196254,#196255,#196256, + #196257,#196258,#196259,#196260,#196261,#196262,#196263,#196264, + #196265,#196266,#196267,#196268,#196269,#196270),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.565482229898,5.599658566911,5.633834903925,5.668011240938, 5.702187577952,5.736363914965,5.770540251978,5.804716588992, @@ -240891,55 +243893,55 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.975598274059,6.009774611072,6.043950948086,6.078127285099, 6.112303622113,6.146479959126,6.180656296139,6.214832633153, 6.249008970166,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#193854 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#193855 = CARTESIAN_POINT('',(0.740753686901,5.702835799539E-008)); -#193856 = CARTESIAN_POINT('',(0.718425946423,-7.920749048097E-006)); -#193857 = CARTESIAN_POINT('',(0.684729502771,-3.211523831336E-005)); -#193858 = CARTESIAN_POINT('',(0.650851510181,-9.135958603284E-005)); -#193859 = CARTESIAN_POINT('',(0.616817843149,-8.643182672584E-005)); -#193860 = CARTESIAN_POINT('',(0.582648204501,-8.687405960141E-005)); -#193861 = CARTESIAN_POINT('',(0.548364026633,-8.593542620295E-005)); -#193862 = CARTESIAN_POINT('',(0.513985713405,-8.54236182881E-005)); -#193863 = CARTESIAN_POINT('',(0.479533105651,-8.485308428819E-005)); -#193864 = CARTESIAN_POINT('',(0.445025477762,-8.435280861445E-005)); -#193865 = CARTESIAN_POINT('',(0.410481676253,-8.388702468049E-005)); -#193866 = CARTESIAN_POINT('',(0.375920232966,-8.346461194645E-005)); -#193867 = CARTESIAN_POINT('',(0.341359494752,-8.308081521476E-005)); -#193868 = CARTESIAN_POINT('',(0.306817755739,-8.274098333401E-005)); -#193869 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); -#193870 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); -#193871 = CARTESIAN_POINT('',(0.203491552027,-8.17998950653E-005)); -#193872 = CARTESIAN_POINT('',(0.169212469737,-8.226451401252E-005)); -#193873 = CARTESIAN_POINT('',(0.135047837564,-7.965797689883E-005)); -#193874 = CARTESIAN_POINT('',(0.101018376289,-8.868396576193E-005)); -#193875 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095504E-005) - ); -#193876 = CARTESIAN_POINT('',(3.345266820762E-002,-1.03705246737E-005)); -#193877 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134137E-006)); -#193878 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); -#193879 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193880 = ORIENTED_EDGE('',*,*,#184913,.T.); -#193881 = ORIENTED_EDGE('',*,*,#187250,.F.); -#193882 = ORIENTED_EDGE('',*,*,#193883,.F.); -#193883 = EDGE_CURVE('',#185413,#186347,#193884,.T.); -#193884 = SURFACE_CURVE('',#193885,(#193890,#193919),.PCURVE_S1.); -#193885 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193886,#193887,#193888, -#193889),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( +#196246 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196247 = CARTESIAN_POINT('',(0.740753686901,5.702835799539E-008)); +#196248 = CARTESIAN_POINT('',(0.718425946423,-7.920749048097E-006)); +#196249 = CARTESIAN_POINT('',(0.684729502771,-3.211523831336E-005)); +#196250 = CARTESIAN_POINT('',(0.650851510181,-9.135958603284E-005)); +#196251 = CARTESIAN_POINT('',(0.616817843149,-8.643182672584E-005)); +#196252 = CARTESIAN_POINT('',(0.582648204501,-8.687405960141E-005)); +#196253 = CARTESIAN_POINT('',(0.548364026633,-8.593542620295E-005)); +#196254 = CARTESIAN_POINT('',(0.513985713405,-8.54236182881E-005)); +#196255 = CARTESIAN_POINT('',(0.479533105651,-8.485308428819E-005)); +#196256 = CARTESIAN_POINT('',(0.445025477762,-8.435280861445E-005)); +#196257 = CARTESIAN_POINT('',(0.410481676253,-8.388702468049E-005)); +#196258 = CARTESIAN_POINT('',(0.375920232966,-8.346461194645E-005)); +#196259 = CARTESIAN_POINT('',(0.341359494752,-8.308081521476E-005)); +#196260 = CARTESIAN_POINT('',(0.306817755739,-8.274098333401E-005)); +#196261 = CARTESIAN_POINT('',(0.272313393703,-8.242390084136E-005)); +#196262 = CARTESIAN_POINT('',(0.237865006819,-8.220472162611E-005)); +#196263 = CARTESIAN_POINT('',(0.203491552027,-8.17998950653E-005)); +#196264 = CARTESIAN_POINT('',(0.169212469737,-8.226451401252E-005)); +#196265 = CARTESIAN_POINT('',(0.135047837564,-7.965797689883E-005)); +#196266 = CARTESIAN_POINT('',(0.101018376289,-8.868396576193E-005)); +#196267 = CARTESIAN_POINT('',(6.714594636694E-002,-5.446484095504E-005) + ); +#196268 = CARTESIAN_POINT('',(3.345266820762E-002,-1.03705246737E-005)); +#196269 = CARTESIAN_POINT('',(1.112575605159E-002,2.972804134137E-006)); +#196270 = CARTESIAN_POINT('',(3.388131789017E-016,0.E+000)); +#196271 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196272 = ORIENTED_EDGE('',*,*,#187305,.T.); +#196273 = ORIENTED_EDGE('',*,*,#189642,.F.); +#196274 = ORIENTED_EDGE('',*,*,#196275,.F.); +#196275 = EDGE_CURVE('',#187805,#188739,#196276,.T.); +#196276 = SURFACE_CURVE('',#196277,(#196282,#196311),.PCURVE_S1.); +#196277 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#196278,#196279,#196280, +#196281),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),( 5.531305892885,7.035064721475),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.820270997176,0.820270997176,1.)) REPRESENTATION_ITEM('') ); -#193886 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); -#193887 = CARTESIAN_POINT('',(1.401121542172,0.65,0.6)); -#193888 = CARTESIAN_POINT('',(1.46,0.591121542172,0.6)); -#193889 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); -#193890 = PCURVE('',#184971,#193891); -#193891 = DEFINITIONAL_REPRESENTATION('',(#193892),#193918); -#193892 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193893,#193894,#193895, - #193896,#193897,#193898,#193899,#193900,#193901,#193902,#193903, - #193904,#193905,#193906,#193907,#193908,#193909,#193910,#193911, - #193912,#193913,#193914,#193915,#193916,#193917),.UNSPECIFIED.,.F., +#196278 = CARTESIAN_POINT('',(1.315111126057,0.65,0.6)); +#196279 = CARTESIAN_POINT('',(1.401121542172,0.65,0.6)); +#196280 = CARTESIAN_POINT('',(1.46,0.591121542172,0.6)); +#196281 = CARTESIAN_POINT('',(1.46,0.505111126057,0.6)); +#196282 = PCURVE('',#187363,#196283); +#196283 = DEFINITIONAL_REPRESENTATION('',(#196284),#196310); +#196284 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196285,#196286,#196287, + #196288,#196289,#196290,#196291,#196292,#196293,#196294,#196295, + #196296,#196297,#196298,#196299,#196300,#196301,#196302,#196303, + #196304,#196305,#196306,#196307,#196308,#196309),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937045,6.009774611072,6.078127285099, @@ -240947,40 +243949,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193893 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); -#193894 = CARTESIAN_POINT('',(1.658529900762,0.696143131232)); -#193895 = CARTESIAN_POINT('',(1.700434160356,0.697716602796)); -#193896 = CARTESIAN_POINT('',(1.764738777092,0.699951833424)); -#193897 = CARTESIAN_POINT('',(1.830409584136,0.702037713133)); -#193898 = CARTESIAN_POINT('',(1.89734333505,0.703949755251)); -#193899 = CARTESIAN_POINT('',(1.965423048009,0.705664150716)); -#193900 = CARTESIAN_POINT('',(2.034516667805,0.707158375919)); -#193901 = CARTESIAN_POINT('',(2.104478619153,0.708411883433)); -#193902 = CARTESIAN_POINT('',(2.175151124104,0.709406762975)); -#193903 = CARTESIAN_POINT('',(2.246366102244,0.710128356401)); -#193904 = CARTESIAN_POINT('',(2.317947385231,0.710565783597)); -#193905 = CARTESIAN_POINT('',(2.389713239295,0.710712346536)); -#193906 = CARTESIAN_POINT('',(2.461479093359,0.710565783597)); -#193907 = CARTESIAN_POINT('',(2.533060376346,0.710128356401)); -#193908 = CARTESIAN_POINT('',(2.604275354486,0.709406762975)); -#193909 = CARTESIAN_POINT('',(2.674947859436,0.708411883433)); -#193910 = CARTESIAN_POINT('',(2.744909810785,0.707158375919)); -#193911 = CARTESIAN_POINT('',(2.814003430581,0.705664150716)); -#193912 = CARTESIAN_POINT('',(2.88208314354,0.703949755251)); -#193913 = CARTESIAN_POINT('',(2.949016894454,0.702037713133)); -#193914 = CARTESIAN_POINT('',(3.014687701497,0.699951833424)); -#193915 = CARTESIAN_POINT('',(3.078992318233,0.697716602796)); -#193916 = CARTESIAN_POINT('',(3.120896577828,0.696143131232)); -#193917 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); -#193918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193919 = PCURVE('',#183700,#193920); -#193920 = DEFINITIONAL_REPRESENTATION('',(#193921),#193947); -#193921 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193922,#193923,#193924, - #193925,#193926,#193927,#193928,#193929,#193930,#193931,#193932, - #193933,#193934,#193935,#193936,#193937,#193938,#193939,#193940, - #193941,#193942,#193943,#193944,#193945,#193946),.UNSPECIFIED.,.F., +#196285 = CARTESIAN_POINT('',(1.637833825,0.69533963372)); +#196286 = CARTESIAN_POINT('',(1.658529900762,0.696143131232)); +#196287 = CARTESIAN_POINT('',(1.700434160356,0.697716602796)); +#196288 = CARTESIAN_POINT('',(1.764738777092,0.699951833424)); +#196289 = CARTESIAN_POINT('',(1.830409584136,0.702037713133)); +#196290 = CARTESIAN_POINT('',(1.89734333505,0.703949755251)); +#196291 = CARTESIAN_POINT('',(1.965423048009,0.705664150716)); +#196292 = CARTESIAN_POINT('',(2.034516667805,0.707158375919)); +#196293 = CARTESIAN_POINT('',(2.104478619153,0.708411883433)); +#196294 = CARTESIAN_POINT('',(2.175151124104,0.709406762975)); +#196295 = CARTESIAN_POINT('',(2.246366102244,0.710128356401)); +#196296 = CARTESIAN_POINT('',(2.317947385231,0.710565783597)); +#196297 = CARTESIAN_POINT('',(2.389713239295,0.710712346536)); +#196298 = CARTESIAN_POINT('',(2.461479093359,0.710565783597)); +#196299 = CARTESIAN_POINT('',(2.533060376346,0.710128356401)); +#196300 = CARTESIAN_POINT('',(2.604275354486,0.709406762975)); +#196301 = CARTESIAN_POINT('',(2.674947859436,0.708411883433)); +#196302 = CARTESIAN_POINT('',(2.744909810785,0.707158375919)); +#196303 = CARTESIAN_POINT('',(2.814003430581,0.705664150716)); +#196304 = CARTESIAN_POINT('',(2.88208314354,0.703949755251)); +#196305 = CARTESIAN_POINT('',(2.949016894454,0.702037713133)); +#196306 = CARTESIAN_POINT('',(3.014687701497,0.699951833424)); +#196307 = CARTESIAN_POINT('',(3.078992318233,0.697716602796)); +#196308 = CARTESIAN_POINT('',(3.120896577828,0.696143131232)); +#196309 = CARTESIAN_POINT('',(3.14159265359,0.69533963372)); +#196310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196311 = PCURVE('',#186092,#196312); +#196312 = DEFINITIONAL_REPRESENTATION('',(#196313),#196339); +#196313 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196314,#196315,#196316, + #196317,#196318,#196319,#196320,#196321,#196322,#196323,#196324, + #196325,#196326,#196327,#196328,#196329,#196330,#196331,#196332, + #196333,#196334,#196335,#196336,#196337,#196338),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(5.531305892885, 5.599658566911,5.668011240938,5.736363914965,5.804716588992, 5.873069263019,5.941421937045,6.009774611072,6.078127285099, @@ -240988,61 +243990,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 6.419890655233,6.48824332926,6.556596003287,6.624948677314, 6.69330135134,6.761654025367,6.830006699394,6.898359373421, 6.966712047448,7.035064721475),.QUASI_UNIFORM_KNOTS.); -#193922 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); -#193923 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); -#193924 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); -#193925 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); -#193926 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); -#193927 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); -#193928 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); -#193929 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); -#193930 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); -#193931 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); -#193932 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); -#193933 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); -#193934 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); -#193935 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); -#193936 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); -#193937 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); -#193938 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); -#193939 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); -#193940 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); -#193941 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); -#193942 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); -#193943 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); -#193944 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) - ); -#193945 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); -#193946 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); -#193947 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193948 = ADVANCED_FACE('',(#193949),#183700,.T.); -#193949 = FACE_BOUND('',#193950,.T.); -#193950 = EDGE_LOOP('',(#193951,#193952,#193953,#194019,#194020)); -#193951 = ORIENTED_EDGE('',*,*,#186346,.F.); -#193952 = ORIENTED_EDGE('',*,*,#183661,.T.); -#193953 = ORIENTED_EDGE('',*,*,#193954,.T.); -#193954 = EDGE_CURVE('',#183577,#186760,#193955,.T.); -#193955 = SURFACE_CURVE('',#193956,(#193961,#193990),.PCURVE_S1.); -#193956 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#193957,#193958,#193959, -#193960),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 +#196314 = CARTESIAN_POINT('',(1.50375882859,-3.630376297074E-002)); +#196315 = CARTESIAN_POINT('',(1.483062752828,-3.55002654583E-002)); +#196316 = CARTESIAN_POINT('',(1.441158493233,-3.392679389428E-002)); +#196317 = CARTESIAN_POINT('',(1.376853876498,-3.169156326634E-002)); +#196318 = CARTESIAN_POINT('',(1.311183069454,-2.960568355689E-002)); +#196319 = CARTESIAN_POINT('',(1.24424931854,-2.769364143908E-002)); +#196320 = CARTESIAN_POINT('',(1.176169605581,-2.597924597428E-002)); +#196321 = CARTESIAN_POINT('',(1.107075985785,-2.448502077123E-002)); +#196322 = CARTESIAN_POINT('',(1.037114034436,-2.323151325725E-002)); +#196323 = CARTESIAN_POINT('',(0.966441529486,-2.223663371573E-002)); +#196324 = CARTESIAN_POINT('',(0.895226551346,-2.151504028974E-002)); +#196325 = CARTESIAN_POINT('',(0.823645268359,-2.107761309379E-002)); +#196326 = CARTESIAN_POINT('',(0.751879414295,-2.093105015407E-002)); +#196327 = CARTESIAN_POINT('',(0.680113560231,-2.107761309379E-002)); +#196328 = CARTESIAN_POINT('',(0.608532277244,-2.151504028974E-002)); +#196329 = CARTESIAN_POINT('',(0.537317299104,-2.223663371573E-002)); +#196330 = CARTESIAN_POINT('',(0.466644794154,-2.323151325725E-002)); +#196331 = CARTESIAN_POINT('',(0.396682842805,-2.448502077123E-002)); +#196332 = CARTESIAN_POINT('',(0.327589223009,-2.597924597428E-002)); +#196333 = CARTESIAN_POINT('',(0.25950951005,-2.769364143908E-002)); +#196334 = CARTESIAN_POINT('',(0.192575759136,-2.960568355689E-002)); +#196335 = CARTESIAN_POINT('',(0.126904952092,-3.169156326634E-002)); +#196336 = CARTESIAN_POINT('',(6.260033535652E-002,-3.392679389428E-002) + ); +#196337 = CARTESIAN_POINT('',(2.069607576218E-002,-3.55002654583E-002)); +#196338 = CARTESIAN_POINT('',(0.E+000,-3.630376297074E-002)); +#196339 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196340 = ADVANCED_FACE('',(#196341),#186092,.T.); +#196341 = FACE_BOUND('',#196342,.T.); +#196342 = EDGE_LOOP('',(#196343,#196344,#196345,#196411,#196412)); +#196343 = ORIENTED_EDGE('',*,*,#188738,.F.); +#196344 = ORIENTED_EDGE('',*,*,#186053,.T.); +#196345 = ORIENTED_EDGE('',*,*,#196346,.T.); +#196346 = EDGE_CURVE('',#185969,#189152,#196347,.T.); +#196347 = SURFACE_CURVE('',#196348,(#196353,#196382),.PCURVE_S1.); +#196348 = ( BOUNDED_CURVE() B_SPLINE_CURVE(3,(#196349,#196350,#196351, +#196352),.UNSPECIFIED.,.F.,.F.) B_SPLINE_CURVE_WITH_KNOTS((4,4),(0.E+000 ,0.751879414295),.PIECEWISE_BEZIER_KNOTS.) CURVE() GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.953442014805,0.953442014805,1.)) REPRESENTATION_ITEM('') ); -#193957 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); -#193958 = CARTESIAN_POINT('',(1.265581001793,0.510038843607,0.132282534) +#196349 = CARTESIAN_POINT('',(1.2928099227,0.4828099227,0.132282534)); +#196350 = CARTESIAN_POINT('',(1.265581001793,0.510038843607,0.132282534) ); -#193959 = CARTESIAN_POINT('',(1.230010423697,0.525122936235, +#196351 = CARTESIAN_POINT('',(1.230010423697,0.525122936235, 0.133952453327)); -#193960 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 +#196352 = CARTESIAN_POINT('',(1.191066471757,0.5259553457,0.137059047745 )); -#193961 = PCURVE('',#183700,#193962); -#193962 = DEFINITIONAL_REPRESENTATION('',(#193963),#193989); -#193963 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193964,#193965,#193966, - #193967,#193968,#193969,#193970,#193971,#193972,#193973,#193974, - #193975,#193976,#193977,#193978,#193979,#193980,#193981,#193982, - #193983,#193984,#193985,#193986,#193987,#193988),.UNSPECIFIED.,.F., +#196353 = PCURVE('',#186092,#196354); +#196354 = DEFINITIONAL_REPRESENTATION('',(#196355),#196381); +#196355 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196356,#196357,#196358, + #196359,#196360,#196361,#196362,#196363,#196364,#196365,#196366, + #196367,#196368,#196369,#196370,#196371,#196372,#196373,#196374, + #196375,#196376,#196377,#196378,#196379,#196380),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -241050,40 +244052,40 @@ GEOMETRIC_REPRESENTATION_ITEM() RATIONAL_B_SPLINE_CURVE((1., 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#193964 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); -#193965 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); -#193966 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); -#193967 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); -#193968 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); -#193969 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); -#193970 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); -#193971 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); -#193972 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); -#193973 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); -#193974 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); -#193975 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); -#193976 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); -#193977 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); -#193978 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); -#193979 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); -#193980 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); -#193981 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); -#193982 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); -#193983 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); -#193984 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); -#193985 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); -#193986 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); -#193987 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); -#193988 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); -#193989 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#193990 = PCURVE('',#183615,#193991); -#193991 = DEFINITIONAL_REPRESENTATION('',(#193992),#194018); -#193992 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#193993,#193994,#193995, - #193996,#193997,#193998,#193999,#194000,#194001,#194002,#194003, - #194004,#194005,#194006,#194007,#194008,#194009,#194010,#194011, - #194012,#194013,#194014,#194015,#194016,#194017),.UNSPECIFIED.,.F., +#196356 = CARTESIAN_POINT('',(0.751879414295,-0.521151972135)); +#196357 = CARTESIAN_POINT('',(0.76300502153,-0.521151960849)); +#196358 = CARTESIAN_POINT('',(0.78532707141,-0.521166052418)); +#196359 = CARTESIAN_POINT('',(0.819005050097,-0.521230123701)); +#196360 = CARTESIAN_POINT('',(0.852860566593,-0.521337775248)); +#196361 = CARTESIAN_POINT('',(0.886875427771,-0.521489461464)); +#196362 = CARTESIAN_POINT('',(0.921030963568,-0.521685502659)); +#196363 = CARTESIAN_POINT('',(0.955308004085,-0.521926062682)); +#196364 = CARTESIAN_POINT('',(0.9896869619,-0.522211149586)); +#196365 = CARTESIAN_POINT('',(1.024147890877,-0.522540611768)); +#196366 = CARTESIAN_POINT('',(1.058670555341,-0.522914137063)); +#196367 = CARTESIAN_POINT('',(1.093234499852,-0.523331252839)); +#196368 = CARTESIAN_POINT('',(1.127819121442,-0.523791327649)); +#196369 = CARTESIAN_POINT('',(1.162403743033,-0.524293574292)); +#196370 = CARTESIAN_POINT('',(1.196967687544,-0.524837054286)); +#196371 = CARTESIAN_POINT('',(1.231490352008,-0.5254206837)); +#196372 = CARTESIAN_POINT('',(1.265951280985,-0.526043240264)); +#196373 = CARTESIAN_POINT('',(1.3003302388,-0.526703371651)); +#196374 = CARTESIAN_POINT('',(1.334607279317,-0.527399604872)); +#196375 = CARTESIAN_POINT('',(1.368762815114,-0.528130356438)); +#196376 = CARTESIAN_POINT('',(1.402777676292,-0.528893943933)); +#196377 = CARTESIAN_POINT('',(1.436633192788,-0.529688595932)); +#196378 = CARTESIAN_POINT('',(1.470311171475,-0.530512470926)); +#196379 = CARTESIAN_POINT('',(1.492633221355,-0.531079920146)); +#196380 = CARTESIAN_POINT('',(1.50375882859,-0.531367877804)); +#196381 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196382 = PCURVE('',#186007,#196383); +#196383 = DEFINITIONAL_REPRESENTATION('',(#196384),#196410); +#196384 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196385,#196386,#196387, + #196388,#196389,#196390,#196391,#196392,#196393,#196394,#196395, + #196396,#196397,#196398,#196399,#196400,#196401,#196402,#196403, + #196404,#196405,#196406,#196407,#196408,#196409),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 3.417633701341E-002,6.835267402682E-002,0.10252901104,0.136705348054 ,0.170881685067,0.20505802208,0.239234359094,0.273410696107, @@ -241091,56 +244093,56 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.444292381174,0.478468718188,0.512645055201,0.546821392215, 0.580997729228,0.615174066241,0.649350403255,0.683526740268, 0.717703077282,0.751879414295),.QUASI_UNIFORM_KNOTS.); -#193993 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); -#193994 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); -#193995 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); -#193996 = CARTESIAN_POINT('',(6.714594636695E-002,1.000054464841)); -#193997 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); -#193998 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); -#193999 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); -#194000 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); -#194001 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); -#194002 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); -#194003 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); -#194004 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); -#194005 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); -#194006 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); -#194007 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); -#194008 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); -#194009 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); -#194010 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); -#194011 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); -#194012 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); -#194013 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); -#194014 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); -#194015 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); -#194016 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); -#194017 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194018 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194019 = ORIENTED_EDGE('',*,*,#186759,.F.); -#194020 = ORIENTED_EDGE('',*,*,#193883,.T.); -#194021 = ADVANCED_FACE('',(#194022),#185261,.F.); -#194022 = FACE_BOUND('',#194023,.F.); -#194023 = EDGE_LOOP('',(#194024,#194025,#194026,#194027)); -#194024 = ORIENTED_EDGE('',*,*,#185318,.T.); -#194025 = ORIENTED_EDGE('',*,*,#187817,.F.); -#194026 = ORIENTED_EDGE('',*,*,#185246,.F.); -#194027 = ORIENTED_EDGE('',*,*,#194028,.T.); -#194028 = EDGE_CURVE('',#185191,#185189,#194029,.T.); -#194029 = SURFACE_CURVE('',#194030,(#194035,#194064),.PCURVE_S1.); -#194030 = CIRCLE('',#194031,0.108045018441); -#194031 = AXIS2_PLACEMENT_3D('',#194032,#194033,#194034); -#194032 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); -#194033 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194034 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194035 = PCURVE('',#185261,#194036); -#194036 = DEFINITIONAL_REPRESENTATION('',(#194037),#194063); -#194037 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194038,#194039,#194040, - #194041,#194042,#194043,#194044,#194045,#194046,#194047,#194048, - #194049,#194050,#194051,#194052,#194053,#194054,#194055,#194056, - #194057,#194058,#194059,#194060,#194061,#194062),.UNSPECIFIED.,.F., +#196385 = CARTESIAN_POINT('',(3.388131789017E-016,1.)); +#196386 = CARTESIAN_POINT('',(1.112575605159E-002,0.999997027196)); +#196387 = CARTESIAN_POINT('',(3.345266820762E-002,1.000010370525)); +#196388 = CARTESIAN_POINT('',(6.714594636695E-002,1.000054464841)); +#196389 = CARTESIAN_POINT('',(0.101018376289,1.000088683966)); +#196390 = CARTESIAN_POINT('',(0.135047837564,1.000079657977)); +#196391 = CARTESIAN_POINT('',(0.169212469737,1.000082264514)); +#196392 = CARTESIAN_POINT('',(0.203491552027,1.000081799895)); +#196393 = CARTESIAN_POINT('',(0.237865006819,1.000082204722)); +#196394 = CARTESIAN_POINT('',(0.272313393703,1.000082423901)); +#196395 = CARTESIAN_POINT('',(0.306817755739,1.000082740983)); +#196396 = CARTESIAN_POINT('',(0.341359494752,1.000083080815)); +#196397 = CARTESIAN_POINT('',(0.375920232966,1.000083464612)); +#196398 = CARTESIAN_POINT('',(0.410481676253,1.000083887025)); +#196399 = CARTESIAN_POINT('',(0.445025477762,1.000084352809)); +#196400 = CARTESIAN_POINT('',(0.479533105651,1.000084853084)); +#196401 = CARTESIAN_POINT('',(0.513985713406,1.000085423618)); +#196402 = CARTESIAN_POINT('',(0.548364026632,1.000085935426)); +#196403 = CARTESIAN_POINT('',(0.582648204505,1.000086874059)); +#196404 = CARTESIAN_POINT('',(0.616817843137,1.000086431829)); +#196405 = CARTESIAN_POINT('',(0.650851510226,1.000091359578)); +#196406 = CARTESIAN_POINT('',(0.684729502759,1.00003211524)); +#196407 = CARTESIAN_POINT('',(0.718425946425,1.000007920749)); +#196408 = CARTESIAN_POINT('',(0.740753686904,0.999999942971)); +#196409 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196410 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196411 = ORIENTED_EDGE('',*,*,#189151,.F.); +#196412 = ORIENTED_EDGE('',*,*,#196275,.T.); +#196413 = ADVANCED_FACE('',(#196414),#187653,.F.); +#196414 = FACE_BOUND('',#196415,.F.); +#196415 = EDGE_LOOP('',(#196416,#196417,#196418,#196419)); +#196416 = ORIENTED_EDGE('',*,*,#187710,.T.); +#196417 = ORIENTED_EDGE('',*,*,#190209,.F.); +#196418 = ORIENTED_EDGE('',*,*,#187638,.F.); +#196419 = ORIENTED_EDGE('',*,*,#196420,.T.); +#196420 = EDGE_CURVE('',#187583,#187581,#196421,.T.); +#196421 = SURFACE_CURVE('',#196422,(#196427,#196456),.PCURVE_S1.); +#196422 = CIRCLE('',#196423,0.108045018441); +#196423 = AXIS2_PLACEMENT_3D('',#196424,#196425,#196426); +#196424 = CARTESIAN_POINT('',(-0.944441767621,-0.241005873715,0.95)); +#196425 = DIRECTION('',(0.E+000,0.E+000,1.)); +#196426 = DIRECTION('',(1.,0.E+000,0.E+000)); +#196427 = PCURVE('',#187653,#196428); +#196428 = DEFINITIONAL_REPRESENTATION('',(#196429),#196455); +#196429 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196430,#196431,#196432, + #196433,#196434,#196435,#196436,#196437,#196438,#196439,#196440, + #196441,#196442,#196443,#196444,#196445,#196446,#196447,#196448, + #196449,#196450,#196451,#196452,#196453,#196454),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 0.142799666072,0.285599332145,0.428398998217,0.571198664289, 0.713998330361,0.856797996434,0.999597662506,1.142397328578, @@ -241148,67 +244150,67 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 1.856395658939,1.999195325012,2.141994991084,2.284794657156, 2.427594323228,2.570393989301,2.713193655373,2.855993321445, 2.998792987518,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#194038 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); -#194039 = CARTESIAN_POINT('',(4.759988869075E-002,-5.E-002)); -#194040 = CARTESIAN_POINT('',(0.142799666072,-5.E-002)); -#194041 = CARTESIAN_POINT('',(0.285599332145,-5.E-002)); -#194042 = CARTESIAN_POINT('',(0.428398998217,-5.E-002)); -#194043 = CARTESIAN_POINT('',(0.571198664289,-5.E-002)); -#194044 = CARTESIAN_POINT('',(0.713998330361,-5.E-002)); -#194045 = CARTESIAN_POINT('',(0.856797996434,-5.E-002)); -#194046 = CARTESIAN_POINT('',(0.999597662506,-5.E-002)); -#194047 = CARTESIAN_POINT('',(1.142397328578,-5.E-002)); -#194048 = CARTESIAN_POINT('',(1.28519699465,-5.E-002)); -#194049 = CARTESIAN_POINT('',(1.427996660723,-5.E-002)); -#194050 = CARTESIAN_POINT('',(1.570796326795,-5.E-002)); -#194051 = CARTESIAN_POINT('',(1.713595992867,-5.E-002)); -#194052 = CARTESIAN_POINT('',(1.856395658939,-5.E-002)); -#194053 = CARTESIAN_POINT('',(1.999195325012,-5.E-002)); -#194054 = CARTESIAN_POINT('',(2.141994991084,-5.E-002)); -#194055 = CARTESIAN_POINT('',(2.284794657156,-5.E-002)); -#194056 = CARTESIAN_POINT('',(2.427594323228,-5.E-002)); -#194057 = CARTESIAN_POINT('',(2.570393989301,-5.E-002)); -#194058 = CARTESIAN_POINT('',(2.713193655373,-5.E-002)); -#194059 = CARTESIAN_POINT('',(2.855993321445,-5.E-002)); -#194060 = CARTESIAN_POINT('',(2.998792987518,-5.E-002)); -#194061 = CARTESIAN_POINT('',(3.093992764899,-5.E-002)); -#194062 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); -#194063 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194064 = PCURVE('',#185234,#194065); -#194065 = DEFINITIONAL_REPRESENTATION('',(#194066),#194070); -#194066 = CIRCLE('',#194067,0.108045018441); -#194067 = AXIS2_PLACEMENT_2D('',#194068,#194069); -#194068 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194069 = DIRECTION('',(1.,0.E+000)); -#194070 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194071 = ADVANCED_FACE('',(#194072),#185234,.T.); -#194072 = FACE_BOUND('',#194073,.T.); -#194073 = EDGE_LOOP('',(#194074,#194075)); -#194074 = ORIENTED_EDGE('',*,*,#194028,.T.); -#194075 = ORIENTED_EDGE('',*,*,#185188,.T.); -#194076 = ADVANCED_FACE('',(#194077),#185044,.T.); -#194077 = FACE_BOUND('',#194078,.T.); -#194078 = EDGE_LOOP('',(#194079,#194080,#194081,#194124)); -#194079 = ORIENTED_EDGE('',*,*,#185005,.F.); -#194080 = ORIENTED_EDGE('',*,*,#193815,.F.); -#194081 = ORIENTED_EDGE('',*,*,#194082,.F.); -#194082 = EDGE_CURVE('',#187703,#185391,#194083,.T.); -#194083 = SURFACE_CURVE('',#194084,(#194089,#194118),.PCURVE_S1.); -#194084 = CIRCLE('',#194085,5.E-002); -#194085 = AXIS2_PLACEMENT_3D('',#194086,#194087,#194088); -#194086 = CARTESIAN_POINT('',(1.217861391,0.504453973629,0.95)); -#194087 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194088 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194089 = PCURVE('',#185044,#194090); -#194090 = DEFINITIONAL_REPRESENTATION('',(#194091),#194117); -#194091 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194092,#194093,#194094, - #194095,#194096,#194097,#194098,#194099,#194100,#194101,#194102, - #194103,#194104,#194105,#194106,#194107,#194108,#194109,#194110, - #194111,#194112,#194113,#194114,#194115,#194116),.UNSPECIFIED.,.F., +#196430 = CARTESIAN_POINT('',(0.E+000,-5.E-002)); +#196431 = CARTESIAN_POINT('',(4.759988869075E-002,-5.E-002)); +#196432 = CARTESIAN_POINT('',(0.142799666072,-5.E-002)); +#196433 = CARTESIAN_POINT('',(0.285599332145,-5.E-002)); +#196434 = CARTESIAN_POINT('',(0.428398998217,-5.E-002)); +#196435 = CARTESIAN_POINT('',(0.571198664289,-5.E-002)); +#196436 = CARTESIAN_POINT('',(0.713998330361,-5.E-002)); +#196437 = CARTESIAN_POINT('',(0.856797996434,-5.E-002)); +#196438 = CARTESIAN_POINT('',(0.999597662506,-5.E-002)); +#196439 = CARTESIAN_POINT('',(1.142397328578,-5.E-002)); +#196440 = CARTESIAN_POINT('',(1.28519699465,-5.E-002)); +#196441 = CARTESIAN_POINT('',(1.427996660723,-5.E-002)); +#196442 = CARTESIAN_POINT('',(1.570796326795,-5.E-002)); +#196443 = CARTESIAN_POINT('',(1.713595992867,-5.E-002)); +#196444 = CARTESIAN_POINT('',(1.856395658939,-5.E-002)); +#196445 = CARTESIAN_POINT('',(1.999195325012,-5.E-002)); +#196446 = CARTESIAN_POINT('',(2.141994991084,-5.E-002)); +#196447 = CARTESIAN_POINT('',(2.284794657156,-5.E-002)); +#196448 = CARTESIAN_POINT('',(2.427594323228,-5.E-002)); +#196449 = CARTESIAN_POINT('',(2.570393989301,-5.E-002)); +#196450 = CARTESIAN_POINT('',(2.713193655373,-5.E-002)); +#196451 = CARTESIAN_POINT('',(2.855993321445,-5.E-002)); +#196452 = CARTESIAN_POINT('',(2.998792987518,-5.E-002)); +#196453 = CARTESIAN_POINT('',(3.093992764899,-5.E-002)); +#196454 = CARTESIAN_POINT('',(3.14159265359,-5.E-002)); +#196455 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196456 = PCURVE('',#187626,#196457); +#196457 = DEFINITIONAL_REPRESENTATION('',(#196458),#196462); +#196458 = CIRCLE('',#196459,0.108045018441); +#196459 = AXIS2_PLACEMENT_2D('',#196460,#196461); +#196460 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#196461 = DIRECTION('',(1.,0.E+000)); +#196462 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196463 = ADVANCED_FACE('',(#196464),#187626,.T.); +#196464 = FACE_BOUND('',#196465,.T.); +#196465 = EDGE_LOOP('',(#196466,#196467)); +#196466 = ORIENTED_EDGE('',*,*,#196420,.T.); +#196467 = ORIENTED_EDGE('',*,*,#187580,.T.); +#196468 = ADVANCED_FACE('',(#196469),#187436,.T.); +#196469 = FACE_BOUND('',#196470,.T.); +#196470 = EDGE_LOOP('',(#196471,#196472,#196473,#196516)); +#196471 = ORIENTED_EDGE('',*,*,#187397,.F.); +#196472 = ORIENTED_EDGE('',*,*,#196207,.F.); +#196473 = ORIENTED_EDGE('',*,*,#196474,.F.); +#196474 = EDGE_CURVE('',#190095,#187783,#196475,.T.); +#196475 = SURFACE_CURVE('',#196476,(#196481,#196510),.PCURVE_S1.); +#196476 = CIRCLE('',#196477,5.E-002); +#196477 = AXIS2_PLACEMENT_3D('',#196478,#196479,#196480); +#196478 = CARTESIAN_POINT('',(1.217861391,0.504453973629,0.95)); +#196479 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#196480 = DIRECTION('',(0.E+000,0.E+000,1.)); +#196481 = PCURVE('',#187436,#196482); +#196482 = DEFINITIONAL_REPRESENTATION('',(#196483),#196509); +#196483 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196484,#196485,#196486, + #196487,#196488,#196489,#196490,#196491,#196492,#196493,#196494, + #196495,#196496,#196497,#196498,#196499,#196500,#196501,#196502, + #196503,#196504,#196505,#196506,#196507,#196508),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(0.E+000, 5.949986086344E-002,0.118999721727,0.17849958259,0.237999443454, 0.297499304317,0.356999165181,0.416499026044,0.475998886908, @@ -241216,81 +244218,81 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 0.773498191225,0.832998052088,0.892497912952,0.951997773815, 1.011497634679,1.070997495542,1.130497356405,1.189997217269, 1.249497078132,1.308996938996),.QUASI_UNIFORM_KNOTS.); -#194092 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194093 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#194094 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#194095 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#194096 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#194097 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#194098 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#194099 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#194100 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#194101 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#194102 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#194103 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#194104 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#194105 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#194106 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#194107 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#194108 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#194109 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#194110 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#194111 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#194112 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#194113 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#194114 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#194115 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#194116 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194117 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194118 = PCURVE('',#184899,#194119); -#194119 = DEFINITIONAL_REPRESENTATION('',(#194120),#194123); -#194120 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194121,#194122), +#196484 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196485 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#196486 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#196487 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#196488 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#196489 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#196490 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#196491 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#196492 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#196493 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#196494 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#196495 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#196496 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#196497 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#196498 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#196499 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#196500 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#196501 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#196502 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#196503 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#196504 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#196505 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#196506 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#196507 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#196508 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196509 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196510 = PCURVE('',#187291,#196511); +#196511 = DEFINITIONAL_REPRESENTATION('',(#196512),#196515); +#196512 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196513,#196514), .UNSPECIFIED.,.F.,.F.,(2,2),(0.E+000,1.308996938996), .PIECEWISE_BEZIER_KNOTS.); -#194121 = CARTESIAN_POINT('',(0.E+000,0.242138609)); -#194122 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); -#194123 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194124 = ORIENTED_EDGE('',*,*,#187702,.F.); -#194125 = ADVANCED_FACE('',(#194126),#184899,.T.); -#194126 = FACE_BOUND('',#194127,.T.); -#194127 = EDGE_LOOP('',(#194128,#194129,#194130,#194131)); -#194128 = ORIENTED_EDGE('',*,*,#194082,.T.); -#194129 = ORIENTED_EDGE('',*,*,#185390,.F.); -#194130 = ORIENTED_EDGE('',*,*,#184862,.F.); -#194131 = ORIENTED_EDGE('',*,*,#187749,.F.); -#194132 = ADVANCED_FACE('',(#194133),#185174,.T.); -#194133 = FACE_BOUND('',#194134,.T.); -#194134 = EDGE_LOOP('',(#194135,#194136,#194137,#194180)); -#194135 = ORIENTED_EDGE('',*,*,#185137,.T.); -#194136 = ORIENTED_EDGE('',*,*,#187658,.F.); -#194137 = ORIENTED_EDGE('',*,*,#194138,.F.); -#194138 = EDGE_CURVE('',#187294,#187612,#194139,.T.); -#194139 = SURFACE_CURVE('',#194140,(#194145,#194151),.PCURVE_S1.); -#194140 = CIRCLE('',#194141,5.E-002); -#194141 = AXIS2_PLACEMENT_3D('',#194142,#194143,#194144); -#194142 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,0.95)); -#194143 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194144 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#194145 = PCURVE('',#185174,#194146); -#194146 = DEFINITIONAL_REPRESENTATION('',(#194147),#194150); -#194147 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194148,#194149), +#196513 = CARTESIAN_POINT('',(0.E+000,0.242138609)); +#196514 = CARTESIAN_POINT('',(1.308996938996,0.242138609)); +#196515 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196516 = ORIENTED_EDGE('',*,*,#190094,.F.); +#196517 = ADVANCED_FACE('',(#196518),#187291,.T.); +#196518 = FACE_BOUND('',#196519,.T.); +#196519 = EDGE_LOOP('',(#196520,#196521,#196522,#196523)); +#196520 = ORIENTED_EDGE('',*,*,#196474,.T.); +#196521 = ORIENTED_EDGE('',*,*,#187782,.F.); +#196522 = ORIENTED_EDGE('',*,*,#187254,.F.); +#196523 = ORIENTED_EDGE('',*,*,#190141,.F.); +#196524 = ADVANCED_FACE('',(#196525),#187566,.T.); +#196525 = FACE_BOUND('',#196526,.T.); +#196526 = EDGE_LOOP('',(#196527,#196528,#196529,#196572)); +#196527 = ORIENTED_EDGE('',*,*,#187529,.T.); +#196528 = ORIENTED_EDGE('',*,*,#190050,.F.); +#196529 = ORIENTED_EDGE('',*,*,#196530,.F.); +#196530 = EDGE_CURVE('',#189686,#190004,#196531,.T.); +#196531 = SURFACE_CURVE('',#196532,(#196537,#196543),.PCURVE_S1.); +#196532 = CIRCLE('',#196533,5.E-002); +#196533 = AXIS2_PLACEMENT_3D('',#196534,#196535,#196536); +#196534 = CARTESIAN_POINT('',(1.314453973629,-0.407861391,0.95)); +#196535 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#196536 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#196537 = PCURVE('',#187566,#196538); +#196538 = DEFINITIONAL_REPRESENTATION('',(#196539),#196542); +#196539 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196540,#196541), .UNSPECIFIED.,.F.,.F.,(2,2),(1.832595714594,3.14159265359), .PIECEWISE_BEZIER_KNOTS.); -#194148 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); -#194149 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); -#194150 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#196540 = CARTESIAN_POINT('',(2.879793265791,0.242138609)); +#196541 = CARTESIAN_POINT('',(1.570796326795,0.242138609)); +#196542 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#194151 = PCURVE('',#184494,#194152); -#194152 = DEFINITIONAL_REPRESENTATION('',(#194153),#194179); -#194153 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194154,#194155,#194156, - #194157,#194158,#194159,#194160,#194161,#194162,#194163,#194164, - #194165,#194166,#194167,#194168,#194169,#194170,#194171,#194172, - #194173,#194174,#194175,#194176,#194177,#194178),.UNSPECIFIED.,.F., +#196543 = PCURVE('',#186886,#196544); +#196544 = DEFINITIONAL_REPRESENTATION('',(#196545),#196571); +#196545 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196546,#196547,#196548, + #196549,#196550,#196551,#196552,#196553,#196554,#196555,#196556, + #196557,#196558,#196559,#196560,#196561,#196562,#196563,#196564, + #196565,#196566,#196567,#196568,#196569,#196570),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(1.832595714594, 1.892095575457,1.951595436321,2.011095297184,2.070595158048, 2.130095018911,2.189594879775,2.249094740638,2.308594601502, @@ -241298,54 +244300,54 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 2.606093905819,2.665593766682,2.725093627546,2.784593488409, 2.844093349273,2.903593210136,2.963093070999,3.022592931863, 3.082092792726,3.14159265359),.QUASI_UNIFORM_KNOTS.); -#194154 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194155 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#194156 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#194157 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#194158 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#194159 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#194160 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#194161 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#194162 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#194163 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#194164 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#194165 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#194166 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#194167 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#194168 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#194169 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#194170 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#194171 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#194172 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#194173 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#194174 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#194175 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#194176 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#194177 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#194178 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194179 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194180 = ORIENTED_EDGE('',*,*,#187293,.F.); -#194181 = ADVANCED_FACE('',(#194182),#184769,.T.); -#194182 = FACE_BOUND('',#194183,.T.); -#194183 = EDGE_LOOP('',(#194184,#194185,#194186,#194229)); -#194184 = ORIENTED_EDGE('',*,*,#184730,.F.); -#194185 = ORIENTED_EDGE('',*,*,#193393,.F.); -#194186 = ORIENTED_EDGE('',*,*,#194187,.F.); -#194187 = EDGE_CURVE('',#187498,#187406,#194188,.T.); -#194188 = SURFACE_CURVE('',#194189,(#194194,#194223),.PCURVE_S1.); -#194189 = CIRCLE('',#194190,5.E-002); -#194190 = AXIS2_PLACEMENT_3D('',#194191,#194192,#194193); -#194191 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,0.95)); -#194192 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194193 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#194194 = PCURVE('',#184769,#194195); -#194195 = DEFINITIONAL_REPRESENTATION('',(#194196),#194222); -#194196 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194197,#194198,#194199, - #194200,#194201,#194202,#194203,#194204,#194205,#194206,#194207, - #194208,#194209,#194210,#194211,#194212,#194213,#194214,#194215, - #194216,#194217,#194218,#194219,#194220,#194221),.UNSPECIFIED.,.F., +#196546 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196547 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#196548 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#196549 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#196550 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#196551 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#196552 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#196553 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#196554 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#196555 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#196556 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#196557 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#196558 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#196559 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#196560 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#196561 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#196562 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#196563 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#196564 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#196565 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#196566 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#196567 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#196568 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#196569 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#196570 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196571 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196572 = ORIENTED_EDGE('',*,*,#189685,.F.); +#196573 = ADVANCED_FACE('',(#196574),#187161,.T.); +#196574 = FACE_BOUND('',#196575,.T.); +#196575 = EDGE_LOOP('',(#196576,#196577,#196578,#196621)); +#196576 = ORIENTED_EDGE('',*,*,#187122,.F.); +#196577 = ORIENTED_EDGE('',*,*,#195785,.F.); +#196578 = ORIENTED_EDGE('',*,*,#196579,.F.); +#196579 = EDGE_CURVE('',#189890,#189798,#196580,.T.); +#196580 = SURFACE_CURVE('',#196581,(#196586,#196615),.PCURVE_S1.); +#196581 = CIRCLE('',#196582,5.E-002); +#196582 = AXIS2_PLACEMENT_3D('',#196583,#196584,#196585); +#196583 = CARTESIAN_POINT('',(-1.314453973629,0.407861391,0.95)); +#196584 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#196585 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#196586 = PCURVE('',#187161,#196587); +#196587 = DEFINITIONAL_REPRESENTATION('',(#196588),#196614); +#196588 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196589,#196590,#196591, + #196592,#196593,#196594,#196595,#196596,#196597,#196598,#196599, + #196600,#196601,#196602,#196603,#196604,#196605,#196606,#196607, + #196608,#196609,#196610,#196611,#196612,#196613),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(3.14159265359, 3.201092514453,3.260592375317,3.32009223618,3.379592097044, 3.439091957907,3.49859181877,3.558091679634,3.617591540497, @@ -241353,88 +244355,88 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 3.915090844815,3.974590705678,4.034090566541,4.093590427405, 4.153090288268,4.212590149132,4.272090009995,4.331589870859, 4.391089731722,4.450589592586),.QUASI_UNIFORM_KNOTS.); -#194197 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194198 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#194199 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#194200 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#194201 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#194202 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#194203 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#194204 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#194205 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#194206 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#194207 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#194208 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#194209 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#194210 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#194211 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#194212 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#194213 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#194214 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#194215 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#194216 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#194217 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#194218 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#194219 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#194220 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#194221 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194222 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194223 = PCURVE('',#184326,#194224); -#194224 = DEFINITIONAL_REPRESENTATION('',(#194225),#194228); -#194225 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194226,#194227), +#196589 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196590 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#196591 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#196592 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#196593 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#196594 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#196595 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#196596 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#196597 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#196598 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#196599 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#196600 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#196601 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#196602 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#196603 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#196604 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#196605 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#196606 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#196607 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#196608 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#196609 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#196610 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#196611 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#196612 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#196613 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196614 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196615 = PCURVE('',#186718,#196616); +#196616 = DEFINITIONAL_REPRESENTATION('',(#196617),#196620); +#196617 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196618,#196619), .UNSPECIFIED.,.F.,.F.,(2,2),(3.14159265359,4.450589592586), .PIECEWISE_BEZIER_KNOTS.); -#194226 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); -#194227 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); -#194228 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194229 = ORIENTED_EDGE('',*,*,#187770,.F.); -#194230 = ADVANCED_FACE('',(#194231),#184494,.T.); -#194231 = FACE_BOUND('',#194232,.T.); -#194232 = EDGE_LOOP('',(#194233,#194234,#194235,#194236)); -#194233 = ORIENTED_EDGE('',*,*,#184455,.F.); -#194234 = ORIENTED_EDGE('',*,*,#193604,.F.); -#194235 = ORIENTED_EDGE('',*,*,#194138,.T.); -#194236 = ORIENTED_EDGE('',*,*,#187611,.F.); -#194237 = ADVANCED_FACE('',(#194238),#184326,.T.); -#194238 = FACE_BOUND('',#194239,.T.); -#194239 = EDGE_LOOP('',(#194240,#194241,#194242,#194243)); -#194240 = ORIENTED_EDGE('',*,*,#194187,.T.); -#194241 = ORIENTED_EDGE('',*,*,#187405,.F.); -#194242 = ORIENTED_EDGE('',*,*,#184289,.F.); -#194243 = ORIENTED_EDGE('',*,*,#187497,.F.); -#194244 = ADVANCED_FACE('',(#194245),#184624,.T.); -#194245 = FACE_BOUND('',#194246,.T.); -#194246 = EDGE_LOOP('',(#194247,#194248,#194249,#194292)); -#194247 = ORIENTED_EDGE('',*,*,#184587,.T.); -#194248 = ORIENTED_EDGE('',*,*,#187590,.F.); -#194249 = ORIENTED_EDGE('',*,*,#194250,.F.); -#194250 = EDGE_CURVE('',#185835,#187544,#194251,.T.); -#194251 = SURFACE_CURVE('',#194252,(#194257,#194263),.PCURVE_S1.); -#194252 = CIRCLE('',#194253,5.E-002); -#194253 = AXIS2_PLACEMENT_3D('',#194254,#194255,#194256); -#194254 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,0.95)); -#194255 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194256 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194257 = PCURVE('',#184624,#194258); -#194258 = DEFINITIONAL_REPRESENTATION('',(#194259),#194262); -#194259 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194260,#194261), +#196618 = CARTESIAN_POINT('',(1.570796326795,-1.057861391)); +#196619 = CARTESIAN_POINT('',(2.879793265791,-1.057861391)); +#196620 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196621 = ORIENTED_EDGE('',*,*,#190162,.F.); +#196622 = ADVANCED_FACE('',(#196623),#186886,.T.); +#196623 = FACE_BOUND('',#196624,.T.); +#196624 = EDGE_LOOP('',(#196625,#196626,#196627,#196628)); +#196625 = ORIENTED_EDGE('',*,*,#186847,.F.); +#196626 = ORIENTED_EDGE('',*,*,#195996,.F.); +#196627 = ORIENTED_EDGE('',*,*,#196530,.T.); +#196628 = ORIENTED_EDGE('',*,*,#190003,.F.); +#196629 = ADVANCED_FACE('',(#196630),#186718,.T.); +#196630 = FACE_BOUND('',#196631,.T.); +#196631 = EDGE_LOOP('',(#196632,#196633,#196634,#196635)); +#196632 = ORIENTED_EDGE('',*,*,#196579,.T.); +#196633 = ORIENTED_EDGE('',*,*,#189797,.F.); +#196634 = ORIENTED_EDGE('',*,*,#186681,.F.); +#196635 = ORIENTED_EDGE('',*,*,#189889,.F.); +#196636 = ADVANCED_FACE('',(#196637),#187016,.T.); +#196637 = FACE_BOUND('',#196638,.T.); +#196638 = EDGE_LOOP('',(#196639,#196640,#196641,#196684)); +#196639 = ORIENTED_EDGE('',*,*,#186979,.T.); +#196640 = ORIENTED_EDGE('',*,*,#189982,.F.); +#196641 = ORIENTED_EDGE('',*,*,#196642,.F.); +#196642 = EDGE_CURVE('',#188227,#189936,#196643,.T.); +#196643 = SURFACE_CURVE('',#196644,(#196649,#196655),.PCURVE_S1.); +#196644 = CIRCLE('',#196645,5.E-002); +#196645 = AXIS2_PLACEMENT_3D('',#196646,#196647,#196648); +#196646 = CARTESIAN_POINT('',(-1.217861391,-0.504453973629,0.95)); +#196647 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#196648 = DIRECTION('',(0.E+000,0.E+000,1.)); +#196649 = PCURVE('',#187016,#196650); +#196650 = DEFINITIONAL_REPRESENTATION('',(#196651),#196654); +#196651 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196652,#196653), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#194260 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); -#194261 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); -#194262 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +#196652 = CARTESIAN_POINT('',(4.450589592586,-2.677861391)); +#196653 = CARTESIAN_POINT('',(3.14159265359,-2.677861391)); +#196654 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' ) ); -#194263 = PCURVE('',#184191,#194264); -#194264 = DEFINITIONAL_REPRESENTATION('',(#194265),#194291); -#194265 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194266,#194267,#194268, - #194269,#194270,#194271,#194272,#194273,#194274,#194275,#194276, - #194277,#194278,#194279,#194280,#194281,#194282,#194283,#194284, - #194285,#194286,#194287,#194288,#194289,#194290),.UNSPECIFIED.,.F., +#196655 = PCURVE('',#186583,#196656); +#196656 = DEFINITIONAL_REPRESENTATION('',(#196657),#196683); +#196657 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196658,#196659,#196660, + #196661,#196662,#196663,#196664,#196665,#196666,#196667,#196668, + #196669,#196670,#196671,#196672,#196673,#196674,#196675,#196676, + #196677,#196678,#196679,#196680,#196681,#196682),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -241442,61 +244444,61 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#194266 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194267 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); -#194268 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); -#194269 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); -#194270 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); -#194271 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); -#194272 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); -#194273 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); -#194274 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); -#194275 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); -#194276 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); -#194277 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); -#194278 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); -#194279 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); -#194280 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); -#194281 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); -#194282 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); -#194283 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); -#194284 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); -#194285 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); -#194286 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); -#194287 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); -#194288 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); -#194289 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); -#194290 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194291 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194292 = ORIENTED_EDGE('',*,*,#185834,.F.); -#194293 = ADVANCED_FACE('',(#194294),#184191,.T.); -#194294 = FACE_BOUND('',#194295,.T.); -#194295 = EDGE_LOOP('',(#194296,#194297,#194298,#194299)); -#194296 = ORIENTED_EDGE('',*,*,#184152,.F.); -#194297 = ORIENTED_EDGE('',*,*,#193182,.F.); -#194298 = ORIENTED_EDGE('',*,*,#194250,.T.); -#194299 = ORIENTED_EDGE('',*,*,#187543,.F.); -#194300 = ADVANCED_FACE('',(#194301),#183890,.T.); -#194301 = FACE_BOUND('',#194302,.T.); -#194302 = EDGE_LOOP('',(#194303,#194304,#194305,#194348)); -#194303 = ORIENTED_EDGE('',*,*,#183851,.F.); -#194304 = ORIENTED_EDGE('',*,*,#187133,.F.); -#194305 = ORIENTED_EDGE('',*,*,#194306,.F.); -#194306 = EDGE_CURVE('',#186616,#187089,#194307,.T.); -#194307 = SURFACE_CURVE('',#194308,(#194313,#194342),.PCURVE_S1.); -#194308 = CIRCLE('',#194309,5.E-002); -#194309 = AXIS2_PLACEMENT_3D('',#194310,#194311,#194312); -#194310 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,0.15)); -#194311 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194312 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#194313 = PCURVE('',#183890,#194314); -#194314 = DEFINITIONAL_REPRESENTATION('',(#194315),#194341); -#194315 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194316,#194317,#194318, - #194319,#194320,#194321,#194322,#194323,#194324,#194325,#194326, - #194327,#194328,#194329,#194330,#194331,#194332,#194333,#194334, - #194335,#194336,#194337,#194338,#194339,#194340),.UNSPECIFIED.,.F., +#196658 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196659 = CARTESIAN_POINT('',(0.751879422945,1.515321402759E-002)); +#196660 = CARTESIAN_POINT('',(0.751879407428,4.551530551223E-002)); +#196661 = CARTESIAN_POINT('',(0.751879204681,9.115656938682E-002)); +#196662 = CARTESIAN_POINT('',(0.751878702828,0.136819171746)); +#196663 = CARTESIAN_POINT('',(0.751877917392,0.182454060255)); +#196664 = CARTESIAN_POINT('',(0.751876926669,0.228028368465)); +#196665 = CARTESIAN_POINT('',(0.751875856201,0.273525359883)); +#196666 = CARTESIAN_POINT('',(0.751874846411,0.318940837163)); +#196667 = CARTESIAN_POINT('',(0.751874028385,0.364280526289)); +#196668 = CARTESIAN_POINT('',(0.751873504227,0.409557497693)); +#196669 = CARTESIAN_POINT('',(0.751873334395,0.454789977664)); +#196670 = CARTESIAN_POINT('',(0.751873531749,0.499999441206)); +#196671 = CARTESIAN_POINT('',(0.751874062123,0.545208929561)); +#196672 = CARTESIAN_POINT('',(0.751874850815,0.590441482182)); +#196673 = CARTESIAN_POINT('',(0.75187579418,0.635718568665)); +#196674 = CARTESIAN_POINT('',(0.75187677523,0.681058406204)); +#196675 = CARTESIAN_POINT('',(0.751877681633,0.726474052505)); +#196676 = CARTESIAN_POINT('',(0.751878423943,0.771971217636)); +#196677 = CARTESIAN_POINT('',(0.751878950957,0.817545686379)); +#196678 = CARTESIAN_POINT('',(0.751879258973,0.863180704561)); +#196679 = CARTESIAN_POINT('',(0.751879389382,0.908843392737)); +#196680 = CARTESIAN_POINT('',(0.751879417419,0.954484692963)); +#196681 = CARTESIAN_POINT('',(0.751879411776,0.984846787708)); +#196682 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196683 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196684 = ORIENTED_EDGE('',*,*,#188226,.F.); +#196685 = ADVANCED_FACE('',(#196686),#186583,.T.); +#196686 = FACE_BOUND('',#196687,.T.); +#196687 = EDGE_LOOP('',(#196688,#196689,#196690,#196691)); +#196688 = ORIENTED_EDGE('',*,*,#186544,.F.); +#196689 = ORIENTED_EDGE('',*,*,#195574,.F.); +#196690 = ORIENTED_EDGE('',*,*,#196642,.T.); +#196691 = ORIENTED_EDGE('',*,*,#189935,.F.); +#196692 = ADVANCED_FACE('',(#196693),#186282,.T.); +#196693 = FACE_BOUND('',#196694,.T.); +#196694 = EDGE_LOOP('',(#196695,#196696,#196697,#196740)); +#196695 = ORIENTED_EDGE('',*,*,#186243,.F.); +#196696 = ORIENTED_EDGE('',*,*,#189525,.F.); +#196697 = ORIENTED_EDGE('',*,*,#196698,.F.); +#196698 = EDGE_CURVE('',#189008,#189481,#196699,.T.); +#196699 = SURFACE_CURVE('',#196700,(#196705,#196734),.PCURVE_S1.); +#196700 = CIRCLE('',#196701,5.E-002); +#196701 = AXIS2_PLACEMENT_3D('',#196702,#196703,#196704); +#196702 = CARTESIAN_POINT('',(-1.287659054385,0.381066471757,0.15)); +#196703 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#196704 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#196705 = PCURVE('',#186282,#196706); +#196706 = DEFINITIONAL_REPRESENTATION('',(#196707),#196733); +#196707 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196708,#196709,#196710, + #196711,#196712,#196713,#196714,#196715,#196716,#196717,#196718, + #196719,#196720,#196721,#196722,#196723,#196724,#196725,#196726, + #196727,#196728,#196729,#196730,#196731,#196732),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -241504,64 +244506,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#194316 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194317 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#194318 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#194319 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#194320 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#194321 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#194322 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#194323 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#194324 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#194325 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#194326 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#194327 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#194328 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#194329 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#194330 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#194331 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#194332 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#194333 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#194334 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#194335 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#194336 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#194337 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); -#194338 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#194339 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#194340 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194341 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194342 = PCURVE('',#183496,#194343); -#194343 = DEFINITIONAL_REPRESENTATION('',(#194344),#194347); -#194344 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194345,#194346), +#196708 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196709 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#196710 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#196711 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#196712 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#196713 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#196714 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#196715 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#196716 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#196717 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#196718 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#196719 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#196720 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#196721 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#196722 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#196723 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#196724 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#196725 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#196726 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#196727 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#196728 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#196729 = CARTESIAN_POINT('',(0.751879389382,9.115660726252E-002)); +#196730 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#196731 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#196732 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196733 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196734 = PCURVE('',#185888,#196735); +#196735 = DEFINITIONAL_REPRESENTATION('',(#196736),#196739); +#196736 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196737,#196738), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#194345 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); -#194346 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); -#194347 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194348 = ORIENTED_EDGE('',*,*,#193532,.F.); -#194349 = ADVANCED_FACE('',(#194350),#184046,.T.); -#194350 = FACE_BOUND('',#194351,.T.); -#194351 = EDGE_LOOP('',(#194352,#194353,#194354,#194420)); -#194352 = ORIENTED_EDGE('',*,*,#184009,.T.); -#194353 = ORIENTED_EDGE('',*,*,#186804,.F.); -#194354 = ORIENTED_EDGE('',*,*,#194355,.F.); -#194355 = EDGE_CURVE('',#187180,#186760,#194356,.T.); -#194356 = SURFACE_CURVE('',#194357,(#194362,#194391),.PCURVE_S1.); -#194357 = CIRCLE('',#194358,5.E-002); -#194358 = AXIS2_PLACEMENT_3D('',#194359,#194360,#194361); -#194359 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,0.15)); -#194360 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); -#194361 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); -#194362 = PCURVE('',#184046,#194363); -#194363 = DEFINITIONAL_REPRESENTATION('',(#194364),#194390); -#194364 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194365,#194366,#194367, - #194368,#194369,#194370,#194371,#194372,#194373,#194374,#194375, - #194376,#194377,#194378,#194379,#194380,#194381,#194382,#194383, - #194384,#194385,#194386,#194387,#194388,#194389),.UNSPECIFIED.,.F., +#196737 = CARTESIAN_POINT('',(6.02138591938,-0.268933528243)); +#196738 = CARTESIAN_POINT('',(4.712388980385,-0.268933528243)); +#196739 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196740 = ORIENTED_EDGE('',*,*,#195924,.F.); +#196741 = ADVANCED_FACE('',(#196742),#186438,.T.); +#196742 = FACE_BOUND('',#196743,.T.); +#196743 = EDGE_LOOP('',(#196744,#196745,#196746,#196812)); +#196744 = ORIENTED_EDGE('',*,*,#186401,.T.); +#196745 = ORIENTED_EDGE('',*,*,#189196,.F.); +#196746 = ORIENTED_EDGE('',*,*,#196747,.F.); +#196747 = EDGE_CURVE('',#189572,#189152,#196748,.T.); +#196748 = SURFACE_CURVE('',#196749,(#196754,#196783),.PCURVE_S1.); +#196749 = CIRCLE('',#196750,5.E-002); +#196750 = AXIS2_PLACEMENT_3D('',#196751,#196752,#196753); +#196751 = CARTESIAN_POINT('',(1.191066471757,0.477659054385,0.15)); +#196752 = DIRECTION('',(1.,-4.489794735692E-015,0.E+000)); +#196753 = DIRECTION('',(4.489794735692E-015,1.,0.E+000)); +#196754 = PCURVE('',#186438,#196755); +#196755 = DEFINITIONAL_REPRESENTATION('',(#196756),#196782); +#196756 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196757,#196758,#196759, + #196760,#196761,#196762,#196763,#196764,#196765,#196766,#196767, + #196768,#196769,#196770,#196771,#196772,#196773,#196774,#196775, + #196776,#196777,#196778,#196779,#196780,#196781),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -241569,40 +244571,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#194365 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); -#194366 = CARTESIAN_POINT('',(1.983328695448E-002,2.651066471757)); -#194367 = CARTESIAN_POINT('',(5.949986086344E-002,2.651066471757)); -#194368 = CARTESIAN_POINT('',(0.118999721727,2.651066471757)); -#194369 = CARTESIAN_POINT('',(0.17849958259,2.651066471757)); -#194370 = CARTESIAN_POINT('',(0.237999443454,2.651066471757)); -#194371 = CARTESIAN_POINT('',(0.297499304317,2.651066471757)); -#194372 = CARTESIAN_POINT('',(0.356999165181,2.651066471757)); -#194373 = CARTESIAN_POINT('',(0.416499026044,2.651066471757)); -#194374 = CARTESIAN_POINT('',(0.475998886908,2.651066471757)); -#194375 = CARTESIAN_POINT('',(0.535498747771,2.651066471757)); -#194376 = CARTESIAN_POINT('',(0.594998608634,2.651066471757)); -#194377 = CARTESIAN_POINT('',(0.654498469498,2.651066471757)); -#194378 = CARTESIAN_POINT('',(0.713998330361,2.651066471757)); -#194379 = CARTESIAN_POINT('',(0.773498191225,2.651066471757)); -#194380 = CARTESIAN_POINT('',(0.832998052088,2.651066471757)); -#194381 = CARTESIAN_POINT('',(0.892497912952,2.651066471757)); -#194382 = CARTESIAN_POINT('',(0.951997773815,2.651066471757)); -#194383 = CARTESIAN_POINT('',(1.011497634679,2.651066471757)); -#194384 = CARTESIAN_POINT('',(1.070997495542,2.651066471757)); -#194385 = CARTESIAN_POINT('',(1.130497356405,2.651066471757)); -#194386 = CARTESIAN_POINT('',(1.189997217269,2.651066471757)); -#194387 = CARTESIAN_POINT('',(1.249497078132,2.651066471757)); -#194388 = CARTESIAN_POINT('',(1.289163652041,2.651066471757)); -#194389 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); -#194390 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194391 = PCURVE('',#183615,#194392); -#194392 = DEFINITIONAL_REPRESENTATION('',(#194393),#194419); -#194393 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194394,#194395,#194396, - #194397,#194398,#194399,#194400,#194401,#194402,#194403,#194404, - #194405,#194406,#194407,#194408,#194409,#194410,#194411,#194412, - #194413,#194414,#194415,#194416,#194417,#194418),.UNSPECIFIED.,.F., +#196757 = CARTESIAN_POINT('',(0.E+000,2.651066471757)); +#196758 = CARTESIAN_POINT('',(1.983328695448E-002,2.651066471757)); +#196759 = CARTESIAN_POINT('',(5.949986086344E-002,2.651066471757)); +#196760 = CARTESIAN_POINT('',(0.118999721727,2.651066471757)); +#196761 = CARTESIAN_POINT('',(0.17849958259,2.651066471757)); +#196762 = CARTESIAN_POINT('',(0.237999443454,2.651066471757)); +#196763 = CARTESIAN_POINT('',(0.297499304317,2.651066471757)); +#196764 = CARTESIAN_POINT('',(0.356999165181,2.651066471757)); +#196765 = CARTESIAN_POINT('',(0.416499026044,2.651066471757)); +#196766 = CARTESIAN_POINT('',(0.475998886908,2.651066471757)); +#196767 = CARTESIAN_POINT('',(0.535498747771,2.651066471757)); +#196768 = CARTESIAN_POINT('',(0.594998608634,2.651066471757)); +#196769 = CARTESIAN_POINT('',(0.654498469498,2.651066471757)); +#196770 = CARTESIAN_POINT('',(0.713998330361,2.651066471757)); +#196771 = CARTESIAN_POINT('',(0.773498191225,2.651066471757)); +#196772 = CARTESIAN_POINT('',(0.832998052088,2.651066471757)); +#196773 = CARTESIAN_POINT('',(0.892497912952,2.651066471757)); +#196774 = CARTESIAN_POINT('',(0.951997773815,2.651066471757)); +#196775 = CARTESIAN_POINT('',(1.011497634679,2.651066471757)); +#196776 = CARTESIAN_POINT('',(1.070997495542,2.651066471757)); +#196777 = CARTESIAN_POINT('',(1.130497356405,2.651066471757)); +#196778 = CARTESIAN_POINT('',(1.189997217269,2.651066471757)); +#196779 = CARTESIAN_POINT('',(1.249497078132,2.651066471757)); +#196780 = CARTESIAN_POINT('',(1.289163652041,2.651066471757)); +#196781 = CARTESIAN_POINT('',(1.308996938996,2.651066471757)); +#196782 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196783 = PCURVE('',#186007,#196784); +#196784 = DEFINITIONAL_REPRESENTATION('',(#196785),#196811); +#196785 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196786,#196787,#196788, + #196789,#196790,#196791,#196792,#196793,#196794,#196795,#196796, + #196797,#196798,#196799,#196800,#196801,#196802,#196803,#196804, + #196805,#196806,#196807,#196808,#196809,#196810),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -241610,68 +244612,68 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#194394 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194395 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#194396 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#194397 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#194398 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#194399 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#194400 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#194401 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#194402 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#194403 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#194404 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#194405 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#194406 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#194407 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#194408 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#194409 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#194410 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#194411 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#194412 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#194413 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#194414 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#194415 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#194416 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#194417 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#194418 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194419 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194420 = ORIENTED_EDGE('',*,*,#187179,.F.); -#194421 = ADVANCED_FACE('',(#194422),#183496,.T.); -#194422 = FACE_BOUND('',#194423,.T.); -#194423 = EDGE_LOOP('',(#194424,#194425,#194426,#194427)); -#194424 = ORIENTED_EDGE('',*,*,#194306,.T.); -#194425 = ORIENTED_EDGE('',*,*,#187088,.F.); -#194426 = ORIENTED_EDGE('',*,*,#183459,.F.); -#194427 = ORIENTED_EDGE('',*,*,#186642,.F.); -#194428 = ADVANCED_FACE('',(#194429),#183615,.T.); -#194429 = FACE_BOUND('',#194430,.T.); -#194430 = EDGE_LOOP('',(#194431,#194432,#194433,#194434)); -#194431 = ORIENTED_EDGE('',*,*,#183576,.F.); -#194432 = ORIENTED_EDGE('',*,*,#187201,.F.); -#194433 = ORIENTED_EDGE('',*,*,#194355,.T.); -#194434 = ORIENTED_EDGE('',*,*,#193954,.F.); -#194435 = ADVANCED_FACE('',(#194436),#183340,.T.); -#194436 = FACE_BOUND('',#194437,.T.); -#194437 = EDGE_LOOP('',(#194438,#194439,#194440,#194483)); -#194438 = ORIENTED_EDGE('',*,*,#183301,.F.); -#194439 = ORIENTED_EDGE('',*,*,#187042,.F.); -#194440 = ORIENTED_EDGE('',*,*,#194441,.F.); -#194441 = EDGE_CURVE('',#186421,#187021,#194442,.T.); -#194442 = SURFACE_CURVE('',#194443,(#194448,#194477),.PCURVE_S1.); -#194443 = CIRCLE('',#194444,5.E-002); -#194444 = AXIS2_PLACEMENT_3D('',#194445,#194446,#194447); -#194445 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,0.15)); -#194446 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194447 = DIRECTION('',(0.E+000,0.E+000,-1.)); -#194448 = PCURVE('',#183340,#194449); -#194449 = DEFINITIONAL_REPRESENTATION('',(#194450),#194476); -#194450 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194451,#194452,#194453, - #194454,#194455,#194456,#194457,#194458,#194459,#194460,#194461, - #194462,#194463,#194464,#194465,#194466,#194467,#194468,#194469, - #194470,#194471,#194472,#194473,#194474,#194475),.UNSPECIFIED.,.F., +#196786 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196787 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#196788 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#196789 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#196790 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#196791 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#196792 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#196793 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#196794 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#196795 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#196796 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#196797 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#196798 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#196799 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#196800 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#196801 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#196802 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#196803 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#196804 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#196805 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#196806 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#196807 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#196808 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#196809 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#196810 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196811 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196812 = ORIENTED_EDGE('',*,*,#189571,.F.); +#196813 = ADVANCED_FACE('',(#196814),#185888,.T.); +#196814 = FACE_BOUND('',#196815,.T.); +#196815 = EDGE_LOOP('',(#196816,#196817,#196818,#196819)); +#196816 = ORIENTED_EDGE('',*,*,#196698,.T.); +#196817 = ORIENTED_EDGE('',*,*,#189480,.F.); +#196818 = ORIENTED_EDGE('',*,*,#185851,.F.); +#196819 = ORIENTED_EDGE('',*,*,#189034,.F.); +#196820 = ADVANCED_FACE('',(#196821),#186007,.T.); +#196821 = FACE_BOUND('',#196822,.T.); +#196822 = EDGE_LOOP('',(#196823,#196824,#196825,#196826)); +#196823 = ORIENTED_EDGE('',*,*,#185968,.F.); +#196824 = ORIENTED_EDGE('',*,*,#189593,.F.); +#196825 = ORIENTED_EDGE('',*,*,#196747,.T.); +#196826 = ORIENTED_EDGE('',*,*,#196346,.F.); +#196827 = ADVANCED_FACE('',(#196828),#185732,.T.); +#196828 = FACE_BOUND('',#196829,.T.); +#196829 = EDGE_LOOP('',(#196830,#196831,#196832,#196875)); +#196830 = ORIENTED_EDGE('',*,*,#185693,.F.); +#196831 = ORIENTED_EDGE('',*,*,#189434,.F.); +#196832 = ORIENTED_EDGE('',*,*,#196833,.F.); +#196833 = EDGE_CURVE('',#188813,#189413,#196834,.T.); +#196834 = SURFACE_CURVE('',#196835,(#196840,#196869),.PCURVE_S1.); +#196835 = CIRCLE('',#196836,5.E-002); +#196836 = AXIS2_PLACEMENT_3D('',#196837,#196838,#196839); +#196837 = CARTESIAN_POINT('',(-1.191066471757,-0.477659054385,0.15)); +#196838 = DIRECTION('',(1.,0.E+000,0.E+000)); +#196839 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#196840 = PCURVE('',#185732,#196841); +#196841 = DEFINITIONAL_REPRESENTATION('',(#196842),#196868); +#196842 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196843,#196844,#196845, + #196846,#196847,#196848,#196849,#196850,#196851,#196852,#196853, + #196854,#196855,#196856,#196857,#196858,#196859,#196860,#196861, + #196862,#196863,#196864,#196865,#196866,#196867),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.974188368184, 5.033688229047,5.093188089911,5.152687950774,5.212187811638, 5.271687672501,5.331187533364,5.390687394228,5.450187255091, @@ -241679,64 +244681,64 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.747686559409,5.807186420272,5.866686281135,5.926186141999, 5.985686002862,6.045185863726,6.104685724589,6.164185585453, 6.223685446316,6.28318530718),.QUASI_UNIFORM_KNOTS.); -#194451 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194452 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#194453 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#194454 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#194455 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#194456 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#194457 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#194458 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#194459 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#194460 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#194461 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#194462 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#194463 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#194464 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#194465 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#194466 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#194467 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#194468 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#194469 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#194470 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#194471 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#194472 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); -#194473 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); -#194474 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); -#194475 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194476 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194477 = PCURVE('',#183221,#194478); -#194478 = DEFINITIONAL_REPRESENTATION('',(#194479),#194482); -#194479 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#194480,#194481), +#196843 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196844 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#196845 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#196846 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#196847 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#196848 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#196849 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#196850 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#196851 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#196852 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#196853 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#196854 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#196855 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#196856 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#196857 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#196858 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#196859 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#196860 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#196861 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#196862 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#196863 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#196864 = CARTESIAN_POINT('',(0.751879389382,9.115660726251E-002)); +#196865 = CARTESIAN_POINT('',(0.751879417419,4.551530703748E-002)); +#196866 = CARTESIAN_POINT('',(0.751879411776,1.515321229167E-002)); +#196867 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196868 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196869 = PCURVE('',#185613,#196870); +#196870 = DEFINITIONAL_REPRESENTATION('',(#196871),#196874); +#196871 = B_SPLINE_CURVE_WITH_KNOTS('',1,(#196872,#196873), .UNSPECIFIED.,.F.,.F.,(2,2),(4.974188368184,6.28318530718), .PIECEWISE_BEZIER_KNOTS.); -#194480 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); -#194481 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); -#194482 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194483 = ORIENTED_EDGE('',*,*,#193321,.F.); -#194484 = ADVANCED_FACE('',(#194485),#183771,.T.); -#194485 = FACE_BOUND('',#194486,.T.); -#194486 = EDGE_LOOP('',(#194487,#194488,#194489,#194555)); -#194487 = ORIENTED_EDGE('',*,*,#183734,.T.); -#194488 = ORIENTED_EDGE('',*,*,#186303,.F.); -#194489 = ORIENTED_EDGE('',*,*,#194490,.F.); -#194490 = EDGE_CURVE('',#186930,#186254,#194491,.T.); -#194491 = SURFACE_CURVE('',#194492,(#194497,#194526),.PCURVE_S1.); -#194492 = CIRCLE('',#194493,5.E-002); -#194493 = AXIS2_PLACEMENT_3D('',#194494,#194495,#194496); -#194494 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,0.15)); -#194495 = DIRECTION('',(-1.122448683923E-015,-1.,0.E+000)); -#194496 = DIRECTION('',(1.,-1.122448683923E-015,0.E+000)); -#194497 = PCURVE('',#183771,#194498); -#194498 = DEFINITIONAL_REPRESENTATION('',(#194499),#194525); -#194499 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194500,#194501,#194502, - #194503,#194504,#194505,#194506,#194507,#194508,#194509,#194510, - #194511,#194512,#194513,#194514,#194515,#194516,#194517,#194518, - #194519,#194520,#194521,#194522,#194523,#194524),.UNSPECIFIED.,.F., +#196872 = CARTESIAN_POINT('',(4.450589592586,-0.268933528243)); +#196873 = CARTESIAN_POINT('',(3.14159265359,-0.268933528243)); +#196874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196875 = ORIENTED_EDGE('',*,*,#195713,.F.); +#196876 = ADVANCED_FACE('',(#196877),#186163,.T.); +#196877 = FACE_BOUND('',#196878,.T.); +#196878 = EDGE_LOOP('',(#196879,#196880,#196881,#196947)); +#196879 = ORIENTED_EDGE('',*,*,#186126,.T.); +#196880 = ORIENTED_EDGE('',*,*,#188695,.F.); +#196881 = ORIENTED_EDGE('',*,*,#196882,.F.); +#196882 = EDGE_CURVE('',#189322,#188646,#196883,.T.); +#196883 = SURFACE_CURVE('',#196884,(#196889,#196918),.PCURVE_S1.); +#196884 = CIRCLE('',#196885,5.E-002); +#196885 = AXIS2_PLACEMENT_3D('',#196886,#196887,#196888); +#196886 = CARTESIAN_POINT('',(1.287659054385,-0.381066471757,0.15)); +#196887 = DIRECTION('',(-1.122448683923E-015,-1.,0.E+000)); +#196888 = DIRECTION('',(1.,-1.122448683923E-015,0.E+000)); +#196889 = PCURVE('',#186163,#196890); +#196890 = DEFINITIONAL_REPRESENTATION('',(#196891),#196917); +#196891 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196892,#196893,#196894, + #196895,#196896,#196897,#196898,#196899,#196900,#196901,#196902, + #196903,#196904,#196905,#196906,#196907,#196908,#196909,#196910, + #196911,#196912,#196913,#196914,#196915,#196916),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -241744,40 +244746,40 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#194500 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); -#194501 = CARTESIAN_POINT('',(4.732222267339,1.031066471757)); -#194502 = CARTESIAN_POINT('',(4.771888841248,1.031066471757)); -#194503 = CARTESIAN_POINT('',(4.831388702112,1.031066471757)); -#194504 = CARTESIAN_POINT('',(4.890888562975,1.031066471757)); -#194505 = CARTESIAN_POINT('',(4.950388423838,1.031066471757)); -#194506 = CARTESIAN_POINT('',(5.009888284702,1.031066471757)); -#194507 = CARTESIAN_POINT('',(5.069388145565,1.031066471757)); -#194508 = CARTESIAN_POINT('',(5.128888006429,1.031066471757)); -#194509 = CARTESIAN_POINT('',(5.188387867292,1.031066471757)); -#194510 = CARTESIAN_POINT('',(5.247887728156,1.031066471757)); -#194511 = CARTESIAN_POINT('',(5.307387589019,1.031066471757)); -#194512 = CARTESIAN_POINT('',(5.366887449883,1.031066471757)); -#194513 = CARTESIAN_POINT('',(5.426387310746,1.031066471757)); -#194514 = CARTESIAN_POINT('',(5.485887171609,1.031066471757)); -#194515 = CARTESIAN_POINT('',(5.545387032473,1.031066471757)); -#194516 = CARTESIAN_POINT('',(5.604886893336,1.031066471757)); -#194517 = CARTESIAN_POINT('',(5.6643867542,1.031066471757)); -#194518 = CARTESIAN_POINT('',(5.723886615063,1.031066471757)); -#194519 = CARTESIAN_POINT('',(5.783386475927,1.031066471757)); -#194520 = CARTESIAN_POINT('',(5.84288633679,1.031066471757)); -#194521 = CARTESIAN_POINT('',(5.902386197654,1.031066471757)); -#194522 = CARTESIAN_POINT('',(5.961886058517,1.031066471757)); -#194523 = CARTESIAN_POINT('',(6.001552632426,1.031066471757)); -#194524 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); -#194525 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194526 = PCURVE('',#183065,#194527); -#194527 = DEFINITIONAL_REPRESENTATION('',(#194528),#194554); -#194528 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#194529,#194530,#194531, - #194532,#194533,#194534,#194535,#194536,#194537,#194538,#194539, - #194540,#194541,#194542,#194543,#194544,#194545,#194546,#194547, - #194548,#194549,#194550,#194551,#194552,#194553),.UNSPECIFIED.,.F., +#196892 = CARTESIAN_POINT('',(4.712388980385,1.031066471757)); +#196893 = CARTESIAN_POINT('',(4.732222267339,1.031066471757)); +#196894 = CARTESIAN_POINT('',(4.771888841248,1.031066471757)); +#196895 = CARTESIAN_POINT('',(4.831388702112,1.031066471757)); +#196896 = CARTESIAN_POINT('',(4.890888562975,1.031066471757)); +#196897 = CARTESIAN_POINT('',(4.950388423838,1.031066471757)); +#196898 = CARTESIAN_POINT('',(5.009888284702,1.031066471757)); +#196899 = CARTESIAN_POINT('',(5.069388145565,1.031066471757)); +#196900 = CARTESIAN_POINT('',(5.128888006429,1.031066471757)); +#196901 = CARTESIAN_POINT('',(5.188387867292,1.031066471757)); +#196902 = CARTESIAN_POINT('',(5.247887728156,1.031066471757)); +#196903 = CARTESIAN_POINT('',(5.307387589019,1.031066471757)); +#196904 = CARTESIAN_POINT('',(5.366887449883,1.031066471757)); +#196905 = CARTESIAN_POINT('',(5.426387310746,1.031066471757)); +#196906 = CARTESIAN_POINT('',(5.485887171609,1.031066471757)); +#196907 = CARTESIAN_POINT('',(5.545387032473,1.031066471757)); +#196908 = CARTESIAN_POINT('',(5.604886893336,1.031066471757)); +#196909 = CARTESIAN_POINT('',(5.6643867542,1.031066471757)); +#196910 = CARTESIAN_POINT('',(5.723886615063,1.031066471757)); +#196911 = CARTESIAN_POINT('',(5.783386475927,1.031066471757)); +#196912 = CARTESIAN_POINT('',(5.84288633679,1.031066471757)); +#196913 = CARTESIAN_POINT('',(5.902386197654,1.031066471757)); +#196914 = CARTESIAN_POINT('',(5.961886058517,1.031066471757)); +#196915 = CARTESIAN_POINT('',(6.001552632426,1.031066471757)); +#196916 = CARTESIAN_POINT('',(6.02138591938,1.031066471757)); +#196917 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196918 = PCURVE('',#185457,#196919); +#196919 = DEFINITIONAL_REPRESENTATION('',(#196920),#196946); +#196920 = B_SPLINE_CURVE_WITH_KNOTS('',3,(#196921,#196922,#196923, + #196924,#196925,#196926,#196927,#196928,#196929,#196930,#196931, + #196932,#196933,#196934,#196935,#196936,#196937,#196938,#196939, + #196940,#196941,#196942,#196943,#196944,#196945),.UNSPECIFIED.,.F., .F.,(4,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,4),(4.712388980385, 4.771888841248,4.831388702112,4.890888562975,4.950388423838, 5.009888284702,5.069388145565,5.128888006429,5.188387867292, @@ -241785,15215 +244787,15215 @@ PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' 5.485887171609,5.545387032473,5.604886893336,5.6643867542, 5.723886615063,5.783386475927,5.84288633679,5.902386197654, 5.961886058517,6.02138591938),.QUASI_UNIFORM_KNOTS.); -#194529 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); -#194530 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); -#194531 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); -#194532 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); -#194533 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); -#194534 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); -#194535 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); -#194536 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); -#194537 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); -#194538 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); -#194539 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); -#194540 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); -#194541 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); -#194542 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); -#194543 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); -#194544 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); -#194545 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); -#194546 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); -#194547 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); -#194548 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); -#194549 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); -#194550 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); -#194551 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); -#194552 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); -#194553 = CARTESIAN_POINT('',(0.751879414295,1.)); -#194554 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194555 = ORIENTED_EDGE('',*,*,#186929,.F.); -#194556 = ADVANCED_FACE('',(#194557),#183221,.T.); -#194557 = FACE_BOUND('',#194558,.T.); -#194558 = EDGE_LOOP('',(#194559,#194560,#194561,#194562)); -#194559 = ORIENTED_EDGE('',*,*,#194441,.T.); -#194560 = ORIENTED_EDGE('',*,*,#187020,.F.); -#194561 = ORIENTED_EDGE('',*,*,#183184,.F.); -#194562 = ORIENTED_EDGE('',*,*,#186465,.F.); -#194563 = ADVANCED_FACE('',(#194564),#183065,.T.); -#194564 = FACE_BOUND('',#194565,.T.); -#194565 = EDGE_LOOP('',(#194566,#194567,#194568,#194569)); -#194566 = ORIENTED_EDGE('',*,*,#183026,.F.); -#194567 = ORIENTED_EDGE('',*,*,#186974,.F.); -#194568 = ORIENTED_EDGE('',*,*,#194490,.T.); -#194569 = ORIENTED_EDGE('',*,*,#193743,.F.); -#194570 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#194574)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#194571,#194572,#194573)) +#196921 = CARTESIAN_POINT('',(0.751879414295,0.E+000)); +#196922 = CARTESIAN_POINT('',(0.751879411776,1.515321229168E-002)); +#196923 = CARTESIAN_POINT('',(0.751879417419,4.551530703749E-002)); +#196924 = CARTESIAN_POINT('',(0.751879389382,9.115660726253E-002)); +#196925 = CARTESIAN_POINT('',(0.751879258973,0.136819295439)); +#196926 = CARTESIAN_POINT('',(0.751878950957,0.182454313621)); +#196927 = CARTESIAN_POINT('',(0.751878423943,0.228028782364)); +#196928 = CARTESIAN_POINT('',(0.751877681633,0.273525947495)); +#196929 = CARTESIAN_POINT('',(0.75187677523,0.318941593796)); +#196930 = CARTESIAN_POINT('',(0.75187579418,0.364281431335)); +#196931 = CARTESIAN_POINT('',(0.751874850815,0.409558517818)); +#196932 = CARTESIAN_POINT('',(0.751874062123,0.454791070439)); +#196933 = CARTESIAN_POINT('',(0.751873531749,0.500000558794)); +#196934 = CARTESIAN_POINT('',(0.751873334395,0.545210022336)); +#196935 = CARTESIAN_POINT('',(0.751873504227,0.590442502307)); +#196936 = CARTESIAN_POINT('',(0.751874028385,0.635719473711)); +#196937 = CARTESIAN_POINT('',(0.751874846411,0.681059162837)); +#196938 = CARTESIAN_POINT('',(0.751875856201,0.726474640117)); +#196939 = CARTESIAN_POINT('',(0.751876926669,0.771971631535)); +#196940 = CARTESIAN_POINT('',(0.751877917392,0.817545939745)); +#196941 = CARTESIAN_POINT('',(0.751878702828,0.863180828254)); +#196942 = CARTESIAN_POINT('',(0.751879204681,0.908843430613)); +#196943 = CARTESIAN_POINT('',(0.751879407428,0.954484694488)); +#196944 = CARTESIAN_POINT('',(0.751879422945,0.984846785972)); +#196945 = CARTESIAN_POINT('',(0.751879414295,1.)); +#196946 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#196947 = ORIENTED_EDGE('',*,*,#189321,.F.); +#196948 = ADVANCED_FACE('',(#196949),#185613,.T.); +#196949 = FACE_BOUND('',#196950,.T.); +#196950 = EDGE_LOOP('',(#196951,#196952,#196953,#196954)); +#196951 = ORIENTED_EDGE('',*,*,#196833,.T.); +#196952 = ORIENTED_EDGE('',*,*,#189412,.F.); +#196953 = ORIENTED_EDGE('',*,*,#185576,.F.); +#196954 = ORIENTED_EDGE('',*,*,#188857,.F.); +#196955 = ADVANCED_FACE('',(#196956),#185457,.T.); +#196956 = FACE_BOUND('',#196957,.T.); +#196957 = EDGE_LOOP('',(#196958,#196959,#196960,#196961)); +#196958 = ORIENTED_EDGE('',*,*,#185418,.F.); +#196959 = ORIENTED_EDGE('',*,*,#189366,.F.); +#196960 = ORIENTED_EDGE('',*,*,#196882,.T.); +#196961 = ORIENTED_EDGE('',*,*,#196135,.F.); +#196962 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#196966)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#196963,#196964,#196965)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#194571 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#194572 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#194573 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#194574 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#194571, +#196963 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#196964 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#196965 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#196966 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#196963, 'distance_accuracy_value','confusion accuracy'); -#194575 = SHAPE_DEFINITION_REPRESENTATION(#194576,#182948); -#194576 = PRODUCT_DEFINITION_SHAPE('','',#194577); -#194577 = PRODUCT_DEFINITION('design','',#194578,#194581); -#194578 = PRODUCT_DEFINITION_FORMATION('','',#194579); -#194579 = PRODUCT('User_Library-sot236','User_Library-sot236','',( - #194580)); -#194580 = PRODUCT_CONTEXT('',#2,'mechanical'); -#194581 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#194582 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#194583,#194585); -#194583 = ( REPRESENTATION_RELATIONSHIP('','',#182948,#182938) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#194584) +#196967 = SHAPE_DEFINITION_REPRESENTATION(#196968,#185340); +#196968 = PRODUCT_DEFINITION_SHAPE('','',#196969); +#196969 = PRODUCT_DEFINITION('design','',#196970,#196973); +#196970 = PRODUCT_DEFINITION_FORMATION('','',#196971); +#196971 = PRODUCT('User_Library-sot236','User_Library-sot236','',( + #196972)); +#196972 = PRODUCT_CONTEXT('',#2,'mechanical'); +#196973 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#196974 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#196975,#196977); +#196975 = ( REPRESENTATION_RELATIONSHIP('','',#185340,#185330) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#196976) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#194584 = ITEM_DEFINED_TRANSFORMATION('','',#11,#182939); -#194585 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #194586); -#194586 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('325','=>[0:1:1:118]','', - #182933,#194577,$); -#194587 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#194579)); -#194588 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#194589,#194591); -#194589 = ( REPRESENTATION_RELATIONSHIP('','',#182938,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#194590) +#196976 = ITEM_DEFINED_TRANSFORMATION('','',#11,#185331); +#196977 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #196978); +#196978 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('426','=>[0:1:1:118]','', + #185325,#196969,$); +#196979 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#196971)); +#196980 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#196981,#196983); +#196981 = ( REPRESENTATION_RELATIONSHIP('','',#185330,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#196982) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#194590 = ITEM_DEFINED_TRANSFORMATION('','',#11,#315); -#194591 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #194592); -#194592 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('326','=>[0:1:1:117]','',#5, - #182933,$); -#194593 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#182935)); -#194594 = SHAPE_DEFINITION_REPRESENTATION(#194595,#194601); -#194595 = PRODUCT_DEFINITION_SHAPE('','',#194596); -#194596 = PRODUCT_DEFINITION('design','',#194597,#194600); -#194597 = PRODUCT_DEFINITION_FORMATION('','',#194598); -#194598 = PRODUCT('Q2','Q2','',(#194599)); -#194599 = PRODUCT_CONTEXT('',#2,'mechanical'); -#194600 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#194601 = SHAPE_REPRESENTATION('',(#11,#194602),#194606); -#194602 = AXIS2_PLACEMENT_3D('',#194603,#194604,#194605); -#194603 = CARTESIAN_POINT('',(11.176,8.382,-2.27838)); -#194604 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); -#194605 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194606 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#194610)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#194607,#194608,#194609)) +#196982 = ITEM_DEFINED_TRANSFORMATION('','',#11,#315); +#196983 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #196984); +#196984 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('427','=>[0:1:1:117]','',#5, + #185325,$); +#196985 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#185327)); +#196986 = SHAPE_DEFINITION_REPRESENTATION(#196987,#196993); +#196987 = PRODUCT_DEFINITION_SHAPE('','',#196988); +#196988 = PRODUCT_DEFINITION('design','',#196989,#196992); +#196989 = PRODUCT_DEFINITION_FORMATION('','',#196990); +#196990 = PRODUCT('Q2','Q2','',(#196991)); +#196991 = PRODUCT_CONTEXT('',#2,'mechanical'); +#196992 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#196993 = SHAPE_REPRESENTATION('',(#11,#196994),#196998); +#196994 = AXIS2_PLACEMENT_3D('',#196995,#196996,#196997); +#196995 = CARTESIAN_POINT('',(11.176,8.382,-1.6891)); +#196996 = DIRECTION('',(0.E+000,-1.224606353822E-016,-1.)); +#196997 = DIRECTION('',(1.,0.E+000,0.E+000)); +#196998 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#197002)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#196999,#197000,#197001)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#194607 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#194608 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#194609 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#194610 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#194607, +#196999 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#197000 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#197001 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#197002 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(5.E-005),#196999, 'distance_accuracy_value','confusion accuracy'); -#194611 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#194612,#194614); -#194612 = ( REPRESENTATION_RELATIONSHIP('','',#182948,#194601) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#194613) +#197003 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#197004,#197006); +#197004 = ( REPRESENTATION_RELATIONSHIP('','',#185340,#196993) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#197005) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#194613 = ITEM_DEFINED_TRANSFORMATION('','',#11,#194602); -#194614 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #194615); -#194615 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('327','=>[0:1:1:118]','', - #194596,#194577,$); -#194616 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#194617,#194619); -#194617 = ( REPRESENTATION_RELATIONSHIP('','',#194601,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#194618) +#197005 = ITEM_DEFINED_TRANSFORMATION('','',#11,#196994); +#197006 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #197007); +#197007 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('428','=>[0:1:1:118]','', + #196988,#196969,$); +#197008 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#197009,#197011); +#197009 = ( REPRESENTATION_RELATIONSHIP('','',#196993,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#197010) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#194618 = ITEM_DEFINED_TRANSFORMATION('','',#11,#319); -#194619 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #194620); -#194620 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('328','=>[0:1:1:119]','',#5, - #194596,$); -#194621 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#194598)); -#194622 = SHAPE_DEFINITION_REPRESENTATION(#194623,#194629); -#194623 = PRODUCT_DEFINITION_SHAPE('','',#194624); -#194624 = PRODUCT_DEFINITION('design','',#194625,#194628); -#194625 = PRODUCT_DEFINITION_FORMATION('','',#194626); -#194626 = PRODUCT('CONN7','CONN7','',(#194627)); -#194627 = PRODUCT_CONTEXT('',#2,'mechanical'); -#194628 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#194629 = SHAPE_REPRESENTATION('',(#11,#194630),#194634); -#194630 = AXIS2_PLACEMENT_3D('',#194631,#194632,#194633); -#194631 = CARTESIAN_POINT('',(10.541,2.65799824,-5.17837928)); -#194632 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194633 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194634 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#194638)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#194635,#194636,#194637)) +#197010 = ITEM_DEFINED_TRANSFORMATION('','',#11,#319); +#197011 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #197012); +#197012 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('429','=>[0:1:1:119]','',#5, + #196988,$); +#197013 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#196990)); +#197014 = SHAPE_DEFINITION_REPRESENTATION(#197015,#197021); +#197015 = PRODUCT_DEFINITION_SHAPE('','',#197016); +#197016 = PRODUCT_DEFINITION('design','',#197017,#197020); +#197017 = PRODUCT_DEFINITION_FORMATION('','',#197018); +#197018 = PRODUCT('CONN7','CONN7','',(#197019)); +#197019 = PRODUCT_CONTEXT('',#2,'mechanical'); +#197020 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#197021 = SHAPE_REPRESENTATION('',(#11,#197022),#197026); +#197022 = AXIS2_PLACEMENT_3D('',#197023,#197024,#197025); +#197023 = CARTESIAN_POINT('',(10.541,2.65799824,-4.58909928)); +#197024 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197025 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197026 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#197030)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#197027,#197028,#197029)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#194635 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#194636 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#194637 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#194638 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#194635, +#197027 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#197028 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#197029 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#197030 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#197027, 'distance_accuracy_value','confusion accuracy'); -#194639 = SHAPE_DEFINITION_REPRESENTATION(#194640,#194646); -#194640 = PRODUCT_DEFINITION_SHAPE('','',#194641); -#194641 = PRODUCT_DEFINITION('design','',#194642,#194645); -#194642 = PRODUCT_DEFINITION_FORMATION('','',#194643); -#194643 = PRODUCT('622893472','622893472','',(#194644)); -#194644 = PRODUCT_CONTEXT('',#2,'mechanical'); -#194645 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#194646 = SHAPE_REPRESENTATION('',(#11,#194647),#194651); -#194647 = AXIS2_PLACEMENT_3D('',#194648,#194649,#194650); -#194648 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); -#194649 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194650 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194651 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#194655)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#194652,#194653,#194654)) +#197031 = SHAPE_DEFINITION_REPRESENTATION(#197032,#197038); +#197032 = PRODUCT_DEFINITION_SHAPE('','',#197033); +#197033 = PRODUCT_DEFINITION('design','',#197034,#197037); +#197034 = PRODUCT_DEFINITION_FORMATION('','',#197035); +#197035 = PRODUCT('549179680','549179680','',(#197036)); +#197036 = PRODUCT_CONTEXT('',#2,'mechanical'); +#197037 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#197038 = SHAPE_REPRESENTATION('',(#11,#197039),#197043); +#197039 = AXIS2_PLACEMENT_3D('',#197040,#197041,#197042); +#197040 = CARTESIAN_POINT('',(0.E+000,0.E+000,0.E+000)); +#197041 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197042 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197043 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#197047)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#197044,#197045,#197046)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#194652 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#194653 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#194654 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#194655 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#194652, +#197044 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#197045 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#197046 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#197047 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#197044, 'distance_accuracy_value','confusion accuracy'); -#194656 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#194657),#194987); -#194657 = MANIFOLD_SOLID_BREP('',#194658); -#194658 = CLOSED_SHELL('',(#194659,#194779,#194855,#194926,#194973, - #194980)); -#194659 = ADVANCED_FACE('',(#194660),#194674,.T.); -#194660 = FACE_BOUND('',#194661,.T.); -#194661 = EDGE_LOOP('',(#194662,#194697,#194725,#194753)); -#194662 = ORIENTED_EDGE('',*,*,#194663,.T.); -#194663 = EDGE_CURVE('',#194664,#194666,#194668,.T.); -#194664 = VERTEX_POINT('',#194665); -#194665 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); -#194666 = VERTEX_POINT('',#194667); -#194667 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,2.9)); -#194668 = SURFACE_CURVE('',#194669,(#194673,#194685),.PCURVE_S1.); -#194669 = LINE('',#194670,#194671); -#194670 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); -#194671 = VECTOR('',#194672,1.); -#194672 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194673 = PCURVE('',#194674,#194679); -#194674 = PLANE('',#194675); -#194675 = AXIS2_PLACEMENT_3D('',#194676,#194677,#194678); -#194676 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); -#194677 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194678 = DIRECTION('',(0.E+000,1.,0.E+000)); -#194679 = DEFINITIONAL_REPRESENTATION('',(#194680),#194684); -#194680 = LINE('',#194681,#194682); -#194681 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194682 = VECTOR('',#194683,1.); -#194683 = DIRECTION('',(0.E+000,-1.)); -#194684 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194685 = PCURVE('',#194686,#194691); -#194686 = PLANE('',#194687); -#194687 = AXIS2_PLACEMENT_3D('',#194688,#194689,#194690); -#194688 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); -#194689 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194690 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194691 = DEFINITIONAL_REPRESENTATION('',(#194692),#194696); -#194692 = LINE('',#194693,#194694); -#194693 = CARTESIAN_POINT('',(7.99999924,0.E+000)); -#194694 = VECTOR('',#194695,1.); -#194695 = DIRECTION('',(0.E+000,-1.)); -#194696 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194697 = ORIENTED_EDGE('',*,*,#194698,.T.); -#194698 = EDGE_CURVE('',#194666,#194699,#194701,.T.); -#194699 = VERTEX_POINT('',#194700); -#194700 = CARTESIAN_POINT('',(-3.99999962,2.15000078,2.9)); -#194701 = SURFACE_CURVE('',#194702,(#194706,#194713),.PCURVE_S1.); -#194702 = LINE('',#194703,#194704); -#194703 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,2.9)); -#194704 = VECTOR('',#194705,1.); -#194705 = DIRECTION('',(0.E+000,1.,0.E+000)); -#194706 = PCURVE('',#194674,#194707); -#194707 = DEFINITIONAL_REPRESENTATION('',(#194708),#194712); -#194708 = LINE('',#194709,#194710); -#194709 = CARTESIAN_POINT('',(0.E+000,-2.9)); -#194710 = VECTOR('',#194711,1.); -#194711 = DIRECTION('',(1.,0.E+000)); -#194712 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194713 = PCURVE('',#194714,#194719); -#194714 = PLANE('',#194715); -#194715 = AXIS2_PLACEMENT_3D('',#194716,#194717,#194718); -#194716 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,2.9)); -#194717 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194718 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194719 = DEFINITIONAL_REPRESENTATION('',(#194720),#194724); -#194720 = LINE('',#194721,#194722); -#194721 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194722 = VECTOR('',#194723,1.); -#194723 = DIRECTION('',(0.E+000,1.)); -#194724 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194725 = ORIENTED_EDGE('',*,*,#194726,.F.); -#194726 = EDGE_CURVE('',#194727,#194699,#194729,.T.); -#194727 = VERTEX_POINT('',#194728); -#194728 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); -#194729 = SURFACE_CURVE('',#194730,(#194734,#194741),.PCURVE_S1.); -#194730 = LINE('',#194731,#194732); -#194731 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); -#194732 = VECTOR('',#194733,1.); -#194733 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194734 = PCURVE('',#194674,#194735); -#194735 = DEFINITIONAL_REPRESENTATION('',(#194736),#194740); -#194736 = LINE('',#194737,#194738); -#194737 = CARTESIAN_POINT('',(4.29999902,0.E+000)); -#194738 = VECTOR('',#194739,1.); -#194739 = DIRECTION('',(0.E+000,-1.)); -#194740 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194741 = PCURVE('',#194742,#194747); -#194742 = PLANE('',#194743); -#194743 = AXIS2_PLACEMENT_3D('',#194744,#194745,#194746); -#194744 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); -#194745 = DIRECTION('',(0.E+000,1.,0.E+000)); -#194746 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194747 = DEFINITIONAL_REPRESENTATION('',(#194748),#194752); -#194748 = LINE('',#194749,#194750); -#194749 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194750 = VECTOR('',#194751,1.); -#194751 = DIRECTION('',(0.E+000,-1.)); -#194752 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194753 = ORIENTED_EDGE('',*,*,#194754,.F.); -#194754 = EDGE_CURVE('',#194664,#194727,#194755,.T.); -#194755 = SURFACE_CURVE('',#194756,(#194760,#194767),.PCURVE_S1.); -#194756 = LINE('',#194757,#194758); -#194757 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); -#194758 = VECTOR('',#194759,1.); -#194759 = DIRECTION('',(0.E+000,1.,0.E+000)); -#194760 = PCURVE('',#194674,#194761); -#194761 = DEFINITIONAL_REPRESENTATION('',(#194762),#194766); -#194762 = LINE('',#194763,#194764); -#194763 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194764 = VECTOR('',#194765,1.); -#194765 = DIRECTION('',(1.,0.E+000)); -#194766 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194767 = PCURVE('',#194768,#194773); -#194768 = PLANE('',#194769); -#194769 = AXIS2_PLACEMENT_3D('',#194770,#194771,#194772); -#194770 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); -#194771 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194772 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194773 = DEFINITIONAL_REPRESENTATION('',(#194774),#194778); -#194774 = LINE('',#194775,#194776); -#194775 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194776 = VECTOR('',#194777,1.); -#194777 = DIRECTION('',(0.E+000,1.)); -#194778 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194779 = ADVANCED_FACE('',(#194780),#194742,.T.); -#194780 = FACE_BOUND('',#194781,.T.); -#194781 = EDGE_LOOP('',(#194782,#194783,#194806,#194834)); -#194782 = ORIENTED_EDGE('',*,*,#194726,.T.); -#194783 = ORIENTED_EDGE('',*,*,#194784,.T.); -#194784 = EDGE_CURVE('',#194699,#194785,#194787,.T.); -#194785 = VERTEX_POINT('',#194786); -#194786 = CARTESIAN_POINT('',(3.99999962,2.15000078,2.9)); -#194787 = SURFACE_CURVE('',#194788,(#194792,#194799),.PCURVE_S1.); -#194788 = LINE('',#194789,#194790); -#194789 = CARTESIAN_POINT('',(-3.99999962,2.15000078,2.9)); -#194790 = VECTOR('',#194791,1.); -#194791 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194792 = PCURVE('',#194742,#194793); -#194793 = DEFINITIONAL_REPRESENTATION('',(#194794),#194798); -#194794 = LINE('',#194795,#194796); -#194795 = CARTESIAN_POINT('',(0.E+000,-2.9)); -#194796 = VECTOR('',#194797,1.); -#194797 = DIRECTION('',(1.,0.E+000)); -#194798 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194799 = PCURVE('',#194714,#194800); -#194800 = DEFINITIONAL_REPRESENTATION('',(#194801),#194805); -#194801 = LINE('',#194802,#194803); -#194802 = CARTESIAN_POINT('',(0.E+000,4.29999902)); -#194803 = VECTOR('',#194804,1.); -#194804 = DIRECTION('',(1.,0.E+000)); -#194805 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194806 = ORIENTED_EDGE('',*,*,#194807,.F.); -#194807 = EDGE_CURVE('',#194808,#194785,#194810,.T.); -#194808 = VERTEX_POINT('',#194809); -#194809 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); -#194810 = SURFACE_CURVE('',#194811,(#194815,#194822),.PCURVE_S1.); -#194811 = LINE('',#194812,#194813); -#194812 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); -#194813 = VECTOR('',#194814,1.); -#194814 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194815 = PCURVE('',#194742,#194816); -#194816 = DEFINITIONAL_REPRESENTATION('',(#194817),#194821); -#194817 = LINE('',#194818,#194819); -#194818 = CARTESIAN_POINT('',(7.99999924,0.E+000)); -#194819 = VECTOR('',#194820,1.); -#194820 = DIRECTION('',(0.E+000,-1.)); -#194821 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194822 = PCURVE('',#194823,#194828); -#194823 = PLANE('',#194824); -#194824 = AXIS2_PLACEMENT_3D('',#194825,#194826,#194827); -#194825 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); -#194826 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194827 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194828 = DEFINITIONAL_REPRESENTATION('',(#194829),#194833); -#194829 = LINE('',#194830,#194831); -#194830 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194831 = VECTOR('',#194832,1.); -#194832 = DIRECTION('',(0.E+000,-1.)); -#194833 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194834 = ORIENTED_EDGE('',*,*,#194835,.F.); -#194835 = EDGE_CURVE('',#194727,#194808,#194836,.T.); -#194836 = SURFACE_CURVE('',#194837,(#194841,#194848),.PCURVE_S1.); -#194837 = LINE('',#194838,#194839); -#194838 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); -#194839 = VECTOR('',#194840,1.); -#194840 = DIRECTION('',(1.,0.E+000,0.E+000)); -#194841 = PCURVE('',#194742,#194842); -#194842 = DEFINITIONAL_REPRESENTATION('',(#194843),#194847); -#194843 = LINE('',#194844,#194845); -#194844 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194845 = VECTOR('',#194846,1.); -#194846 = DIRECTION('',(1.,0.E+000)); -#194847 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194848 = PCURVE('',#194768,#194849); -#194849 = DEFINITIONAL_REPRESENTATION('',(#194850),#194854); -#194850 = LINE('',#194851,#194852); -#194851 = CARTESIAN_POINT('',(0.E+000,4.29999902)); -#194852 = VECTOR('',#194853,1.); -#194853 = DIRECTION('',(1.,0.E+000)); -#194854 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194855 = ADVANCED_FACE('',(#194856),#194823,.T.); -#194856 = FACE_BOUND('',#194857,.T.); -#194857 = EDGE_LOOP('',(#194858,#194859,#194882,#194905)); -#194858 = ORIENTED_EDGE('',*,*,#194807,.T.); -#194859 = ORIENTED_EDGE('',*,*,#194860,.T.); -#194860 = EDGE_CURVE('',#194785,#194861,#194863,.T.); -#194861 = VERTEX_POINT('',#194862); -#194862 = CARTESIAN_POINT('',(3.99999962,-2.14999824,2.9)); -#194863 = SURFACE_CURVE('',#194864,(#194868,#194875),.PCURVE_S1.); -#194864 = LINE('',#194865,#194866); -#194865 = CARTESIAN_POINT('',(3.99999962,2.15000078,2.9)); -#194866 = VECTOR('',#194867,1.); -#194867 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194868 = PCURVE('',#194823,#194869); -#194869 = DEFINITIONAL_REPRESENTATION('',(#194870),#194874); -#194870 = LINE('',#194871,#194872); -#194871 = CARTESIAN_POINT('',(0.E+000,-2.9)); -#194872 = VECTOR('',#194873,1.); -#194873 = DIRECTION('',(1.,0.E+000)); -#194874 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194875 = PCURVE('',#194714,#194876); -#194876 = DEFINITIONAL_REPRESENTATION('',(#194877),#194881); -#194877 = LINE('',#194878,#194879); -#194878 = CARTESIAN_POINT('',(7.99999924,4.29999902)); -#194879 = VECTOR('',#194880,1.); -#194880 = DIRECTION('',(0.E+000,-1.)); -#194881 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194882 = ORIENTED_EDGE('',*,*,#194883,.F.); -#194883 = EDGE_CURVE('',#194884,#194861,#194886,.T.); -#194884 = VERTEX_POINT('',#194885); -#194885 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); -#194886 = SURFACE_CURVE('',#194887,(#194891,#194898),.PCURVE_S1.); -#194887 = LINE('',#194888,#194889); -#194888 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); -#194889 = VECTOR('',#194890,1.); -#194890 = DIRECTION('',(0.E+000,0.E+000,1.)); -#194891 = PCURVE('',#194823,#194892); -#194892 = DEFINITIONAL_REPRESENTATION('',(#194893),#194897); -#194893 = LINE('',#194894,#194895); -#194894 = CARTESIAN_POINT('',(4.29999902,0.E+000)); -#194895 = VECTOR('',#194896,1.); -#194896 = DIRECTION('',(0.E+000,-1.)); -#194897 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194898 = PCURVE('',#194686,#194899); -#194899 = DEFINITIONAL_REPRESENTATION('',(#194900),#194904); -#194900 = LINE('',#194901,#194902); -#194901 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194902 = VECTOR('',#194903,1.); -#194903 = DIRECTION('',(0.E+000,-1.)); -#194904 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194905 = ORIENTED_EDGE('',*,*,#194906,.F.); -#194906 = EDGE_CURVE('',#194808,#194884,#194907,.T.); -#194907 = SURFACE_CURVE('',#194908,(#194912,#194919),.PCURVE_S1.); -#194908 = LINE('',#194909,#194910); -#194909 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); -#194910 = VECTOR('',#194911,1.); -#194911 = DIRECTION('',(0.E+000,-1.,0.E+000)); -#194912 = PCURVE('',#194823,#194913); -#194913 = DEFINITIONAL_REPRESENTATION('',(#194914),#194918); -#194914 = LINE('',#194915,#194916); -#194915 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194916 = VECTOR('',#194917,1.); -#194917 = DIRECTION('',(1.,0.E+000)); -#194918 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194919 = PCURVE('',#194768,#194920); -#194920 = DEFINITIONAL_REPRESENTATION('',(#194921),#194925); -#194921 = LINE('',#194922,#194923); -#194922 = CARTESIAN_POINT('',(7.99999924,4.29999902)); -#194923 = VECTOR('',#194924,1.); -#194924 = DIRECTION('',(0.E+000,-1.)); -#194925 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194926 = ADVANCED_FACE('',(#194927),#194686,.T.); -#194927 = FACE_BOUND('',#194928,.T.); -#194928 = EDGE_LOOP('',(#194929,#194930,#194951,#194952)); -#194929 = ORIENTED_EDGE('',*,*,#194883,.T.); -#194930 = ORIENTED_EDGE('',*,*,#194931,.T.); -#194931 = EDGE_CURVE('',#194861,#194666,#194932,.T.); -#194932 = SURFACE_CURVE('',#194933,(#194937,#194944),.PCURVE_S1.); -#194933 = LINE('',#194934,#194935); -#194934 = CARTESIAN_POINT('',(3.99999962,-2.14999824,2.9)); -#194935 = VECTOR('',#194936,1.); -#194936 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194937 = PCURVE('',#194686,#194938); -#194938 = DEFINITIONAL_REPRESENTATION('',(#194939),#194943); -#194939 = LINE('',#194940,#194941); -#194940 = CARTESIAN_POINT('',(0.E+000,-2.9)); -#194941 = VECTOR('',#194942,1.); -#194942 = DIRECTION('',(1.,0.E+000)); -#194943 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194944 = PCURVE('',#194714,#194945); -#194945 = DEFINITIONAL_REPRESENTATION('',(#194946),#194950); -#194946 = LINE('',#194947,#194948); -#194947 = CARTESIAN_POINT('',(7.99999924,0.E+000)); -#194948 = VECTOR('',#194949,1.); -#194949 = DIRECTION('',(-1.,0.E+000)); -#194950 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194951 = ORIENTED_EDGE('',*,*,#194663,.F.); -#194952 = ORIENTED_EDGE('',*,*,#194953,.F.); -#194953 = EDGE_CURVE('',#194884,#194664,#194954,.T.); -#194954 = SURFACE_CURVE('',#194955,(#194959,#194966),.PCURVE_S1.); -#194955 = LINE('',#194956,#194957); -#194956 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); -#194957 = VECTOR('',#194958,1.); -#194958 = DIRECTION('',(-1.,0.E+000,0.E+000)); -#194959 = PCURVE('',#194686,#194960); -#194960 = DEFINITIONAL_REPRESENTATION('',(#194961),#194965); -#194961 = LINE('',#194962,#194963); -#194962 = CARTESIAN_POINT('',(0.E+000,0.E+000)); -#194963 = VECTOR('',#194964,1.); -#194964 = DIRECTION('',(1.,0.E+000)); -#194965 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194966 = PCURVE('',#194768,#194967); -#194967 = DEFINITIONAL_REPRESENTATION('',(#194968),#194972); -#194968 = LINE('',#194969,#194970); -#194969 = CARTESIAN_POINT('',(7.99999924,0.E+000)); -#194970 = VECTOR('',#194971,1.); -#194971 = DIRECTION('',(-1.,0.E+000)); -#194972 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) -PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' - ) ); -#194973 = ADVANCED_FACE('',(#194974),#194768,.F.); -#194974 = FACE_BOUND('',#194975,.T.); -#194975 = EDGE_LOOP('',(#194976,#194977,#194978,#194979)); -#194976 = ORIENTED_EDGE('',*,*,#194754,.T.); -#194977 = ORIENTED_EDGE('',*,*,#194835,.T.); -#194978 = ORIENTED_EDGE('',*,*,#194906,.T.); -#194979 = ORIENTED_EDGE('',*,*,#194953,.T.); -#194980 = ADVANCED_FACE('',(#194981),#194714,.T.); -#194981 = FACE_BOUND('',#194982,.F.); -#194982 = EDGE_LOOP('',(#194983,#194984,#194985,#194986)); -#194983 = ORIENTED_EDGE('',*,*,#194698,.T.); -#194984 = ORIENTED_EDGE('',*,*,#194784,.T.); -#194985 = ORIENTED_EDGE('',*,*,#194860,.T.); -#194986 = ORIENTED_EDGE('',*,*,#194931,.T.); -#194987 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) -GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#194991)) -GLOBAL_UNIT_ASSIGNED_CONTEXT((#194988,#194989,#194990)) +#197048 = ADVANCED_BREP_SHAPE_REPRESENTATION('',(#11,#197049),#197379); +#197049 = MANIFOLD_SOLID_BREP('',#197050); +#197050 = CLOSED_SHELL('',(#197051,#197171,#197247,#197318,#197365, + #197372)); +#197051 = ADVANCED_FACE('',(#197052),#197066,.F.); +#197052 = FACE_BOUND('',#197053,.F.); +#197053 = EDGE_LOOP('',(#197054,#197089,#197117,#197145)); +#197054 = ORIENTED_EDGE('',*,*,#197055,.T.); +#197055 = EDGE_CURVE('',#197056,#197058,#197060,.T.); +#197056 = VERTEX_POINT('',#197057); +#197057 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); +#197058 = VERTEX_POINT('',#197059); +#197059 = CARTESIAN_POINT('',(3.99999962,-2.14999824,2.9)); +#197060 = SURFACE_CURVE('',#197061,(#197065,#197077),.PCURVE_S1.); +#197061 = LINE('',#197062,#197063); +#197062 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); +#197063 = VECTOR('',#197064,1.); +#197064 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197065 = PCURVE('',#197066,#197071); +#197066 = PLANE('',#197067); +#197067 = AXIS2_PLACEMENT_3D('',#197068,#197069,#197070); +#197068 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); +#197069 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197070 = DIRECTION('',(0.E+000,1.,0.E+000)); +#197071 = DEFINITIONAL_REPRESENTATION('',(#197072),#197076); +#197072 = LINE('',#197073,#197074); +#197073 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197074 = VECTOR('',#197075,1.); +#197075 = DIRECTION('',(0.E+000,-1.)); +#197076 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197077 = PCURVE('',#197078,#197083); +#197078 = PLANE('',#197079); +#197079 = AXIS2_PLACEMENT_3D('',#197080,#197081,#197082); +#197080 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); +#197081 = DIRECTION('',(0.E+000,1.,0.E+000)); +#197082 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197083 = DEFINITIONAL_REPRESENTATION('',(#197084),#197088); +#197084 = LINE('',#197085,#197086); +#197085 = CARTESIAN_POINT('',(7.99999924,0.E+000)); +#197086 = VECTOR('',#197087,1.); +#197087 = DIRECTION('',(0.E+000,-1.)); +#197088 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197089 = ORIENTED_EDGE('',*,*,#197090,.T.); +#197090 = EDGE_CURVE('',#197058,#197091,#197093,.T.); +#197091 = VERTEX_POINT('',#197092); +#197092 = CARTESIAN_POINT('',(3.99999962,2.15000078,2.9)); +#197093 = SURFACE_CURVE('',#197094,(#197098,#197105),.PCURVE_S1.); +#197094 = LINE('',#197095,#197096); +#197095 = CARTESIAN_POINT('',(3.99999962,-2.14999824,2.9)); +#197096 = VECTOR('',#197097,1.); +#197097 = DIRECTION('',(0.E+000,1.,0.E+000)); +#197098 = PCURVE('',#197066,#197099); +#197099 = DEFINITIONAL_REPRESENTATION('',(#197100),#197104); +#197100 = LINE('',#197101,#197102); +#197101 = CARTESIAN_POINT('',(0.E+000,-2.9)); +#197102 = VECTOR('',#197103,1.); +#197103 = DIRECTION('',(1.,0.E+000)); +#197104 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197105 = PCURVE('',#197106,#197111); +#197106 = PLANE('',#197107); +#197107 = AXIS2_PLACEMENT_3D('',#197108,#197109,#197110); +#197108 = CARTESIAN_POINT('',(3.99999962,-2.14999824,2.9)); +#197109 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#197110 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197111 = DEFINITIONAL_REPRESENTATION('',(#197112),#197116); +#197112 = LINE('',#197113,#197114); +#197113 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197114 = VECTOR('',#197115,1.); +#197115 = DIRECTION('',(0.E+000,1.)); +#197116 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197117 = ORIENTED_EDGE('',*,*,#197118,.F.); +#197118 = EDGE_CURVE('',#197119,#197091,#197121,.T.); +#197119 = VERTEX_POINT('',#197120); +#197120 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); +#197121 = SURFACE_CURVE('',#197122,(#197126,#197133),.PCURVE_S1.); +#197122 = LINE('',#197123,#197124); +#197123 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); +#197124 = VECTOR('',#197125,1.); +#197125 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197126 = PCURVE('',#197066,#197127); +#197127 = DEFINITIONAL_REPRESENTATION('',(#197128),#197132); +#197128 = LINE('',#197129,#197130); +#197129 = CARTESIAN_POINT('',(4.29999902,0.E+000)); +#197130 = VECTOR('',#197131,1.); +#197131 = DIRECTION('',(0.E+000,-1.)); +#197132 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197133 = PCURVE('',#197134,#197139); +#197134 = PLANE('',#197135); +#197135 = AXIS2_PLACEMENT_3D('',#197136,#197137,#197138); +#197136 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); +#197137 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#197138 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197139 = DEFINITIONAL_REPRESENTATION('',(#197140),#197144); +#197140 = LINE('',#197141,#197142); +#197141 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197142 = VECTOR('',#197143,1.); +#197143 = DIRECTION('',(0.E+000,-1.)); +#197144 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197145 = ORIENTED_EDGE('',*,*,#197146,.F.); +#197146 = EDGE_CURVE('',#197056,#197119,#197147,.T.); +#197147 = SURFACE_CURVE('',#197148,(#197152,#197159),.PCURVE_S1.); +#197148 = LINE('',#197149,#197150); +#197149 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); +#197150 = VECTOR('',#197151,1.); +#197151 = DIRECTION('',(0.E+000,1.,0.E+000)); +#197152 = PCURVE('',#197066,#197153); +#197153 = DEFINITIONAL_REPRESENTATION('',(#197154),#197158); +#197154 = LINE('',#197155,#197156); +#197155 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197156 = VECTOR('',#197157,1.); +#197157 = DIRECTION('',(1.,0.E+000)); +#197158 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197159 = PCURVE('',#197160,#197165); +#197160 = PLANE('',#197161); +#197161 = AXIS2_PLACEMENT_3D('',#197162,#197163,#197164); +#197162 = CARTESIAN_POINT('',(3.99999962,-2.14999824,0.E+000)); +#197163 = DIRECTION('',(0.E+000,0.E+000,-1.)); +#197164 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197165 = DEFINITIONAL_REPRESENTATION('',(#197166),#197170); +#197166 = LINE('',#197167,#197168); +#197167 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197168 = VECTOR('',#197169,1.); +#197169 = DIRECTION('',(0.E+000,1.)); +#197170 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197171 = ADVANCED_FACE('',(#197172),#197134,.F.); +#197172 = FACE_BOUND('',#197173,.F.); +#197173 = EDGE_LOOP('',(#197174,#197175,#197198,#197226)); +#197174 = ORIENTED_EDGE('',*,*,#197118,.T.); +#197175 = ORIENTED_EDGE('',*,*,#197176,.T.); +#197176 = EDGE_CURVE('',#197091,#197177,#197179,.T.); +#197177 = VERTEX_POINT('',#197178); +#197178 = CARTESIAN_POINT('',(-3.99999962,2.15000078,2.9)); +#197179 = SURFACE_CURVE('',#197180,(#197184,#197191),.PCURVE_S1.); +#197180 = LINE('',#197181,#197182); +#197181 = CARTESIAN_POINT('',(3.99999962,2.15000078,2.9)); +#197182 = VECTOR('',#197183,1.); +#197183 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197184 = PCURVE('',#197134,#197185); +#197185 = DEFINITIONAL_REPRESENTATION('',(#197186),#197190); +#197186 = LINE('',#197187,#197188); +#197187 = CARTESIAN_POINT('',(0.E+000,-2.9)); +#197188 = VECTOR('',#197189,1.); +#197189 = DIRECTION('',(1.,0.E+000)); +#197190 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197191 = PCURVE('',#197106,#197192); +#197192 = DEFINITIONAL_REPRESENTATION('',(#197193),#197197); +#197193 = LINE('',#197194,#197195); +#197194 = CARTESIAN_POINT('',(0.E+000,4.29999902)); +#197195 = VECTOR('',#197196,1.); +#197196 = DIRECTION('',(1.,0.E+000)); +#197197 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197198 = ORIENTED_EDGE('',*,*,#197199,.F.); +#197199 = EDGE_CURVE('',#197200,#197177,#197202,.T.); +#197200 = VERTEX_POINT('',#197201); +#197201 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); +#197202 = SURFACE_CURVE('',#197203,(#197207,#197214),.PCURVE_S1.); +#197203 = LINE('',#197204,#197205); +#197204 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); +#197205 = VECTOR('',#197206,1.); +#197206 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197207 = PCURVE('',#197134,#197208); +#197208 = DEFINITIONAL_REPRESENTATION('',(#197209),#197213); +#197209 = LINE('',#197210,#197211); +#197210 = CARTESIAN_POINT('',(7.99999924,0.E+000)); +#197211 = VECTOR('',#197212,1.); +#197212 = DIRECTION('',(0.E+000,-1.)); +#197213 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197214 = PCURVE('',#197215,#197220); +#197215 = PLANE('',#197216); +#197216 = AXIS2_PLACEMENT_3D('',#197217,#197218,#197219); +#197217 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); +#197218 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197219 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#197220 = DEFINITIONAL_REPRESENTATION('',(#197221),#197225); +#197221 = LINE('',#197222,#197223); +#197222 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197223 = VECTOR('',#197224,1.); +#197224 = DIRECTION('',(0.E+000,-1.)); +#197225 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197226 = ORIENTED_EDGE('',*,*,#197227,.F.); +#197227 = EDGE_CURVE('',#197119,#197200,#197228,.T.); +#197228 = SURFACE_CURVE('',#197229,(#197233,#197240),.PCURVE_S1.); +#197229 = LINE('',#197230,#197231); +#197230 = CARTESIAN_POINT('',(3.99999962,2.15000078,0.E+000)); +#197231 = VECTOR('',#197232,1.); +#197232 = DIRECTION('',(-1.,0.E+000,0.E+000)); +#197233 = PCURVE('',#197134,#197234); +#197234 = DEFINITIONAL_REPRESENTATION('',(#197235),#197239); +#197235 = LINE('',#197236,#197237); +#197236 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197237 = VECTOR('',#197238,1.); +#197238 = DIRECTION('',(1.,0.E+000)); +#197239 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197240 = PCURVE('',#197160,#197241); +#197241 = DEFINITIONAL_REPRESENTATION('',(#197242),#197246); +#197242 = LINE('',#197243,#197244); +#197243 = CARTESIAN_POINT('',(0.E+000,4.29999902)); +#197244 = VECTOR('',#197245,1.); +#197245 = DIRECTION('',(1.,0.E+000)); +#197246 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197247 = ADVANCED_FACE('',(#197248),#197215,.F.); +#197248 = FACE_BOUND('',#197249,.F.); +#197249 = EDGE_LOOP('',(#197250,#197251,#197274,#197297)); +#197250 = ORIENTED_EDGE('',*,*,#197199,.T.); +#197251 = ORIENTED_EDGE('',*,*,#197252,.T.); +#197252 = EDGE_CURVE('',#197177,#197253,#197255,.T.); +#197253 = VERTEX_POINT('',#197254); +#197254 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,2.9)); +#197255 = SURFACE_CURVE('',#197256,(#197260,#197267),.PCURVE_S1.); +#197256 = LINE('',#197257,#197258); +#197257 = CARTESIAN_POINT('',(-3.99999962,2.15000078,2.9)); +#197258 = VECTOR('',#197259,1.); +#197259 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#197260 = PCURVE('',#197215,#197261); +#197261 = DEFINITIONAL_REPRESENTATION('',(#197262),#197266); +#197262 = LINE('',#197263,#197264); +#197263 = CARTESIAN_POINT('',(0.E+000,-2.9)); +#197264 = VECTOR('',#197265,1.); +#197265 = DIRECTION('',(1.,0.E+000)); +#197266 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197267 = PCURVE('',#197106,#197268); +#197268 = DEFINITIONAL_REPRESENTATION('',(#197269),#197273); +#197269 = LINE('',#197270,#197271); +#197270 = CARTESIAN_POINT('',(7.99999924,4.29999902)); +#197271 = VECTOR('',#197272,1.); +#197272 = DIRECTION('',(0.E+000,-1.)); +#197273 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197274 = ORIENTED_EDGE('',*,*,#197275,.F.); +#197275 = EDGE_CURVE('',#197276,#197253,#197278,.T.); +#197276 = VERTEX_POINT('',#197277); +#197277 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); +#197278 = SURFACE_CURVE('',#197279,(#197283,#197290),.PCURVE_S1.); +#197279 = LINE('',#197280,#197281); +#197280 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); +#197281 = VECTOR('',#197282,1.); +#197282 = DIRECTION('',(0.E+000,0.E+000,1.)); +#197283 = PCURVE('',#197215,#197284); +#197284 = DEFINITIONAL_REPRESENTATION('',(#197285),#197289); +#197285 = LINE('',#197286,#197287); +#197286 = CARTESIAN_POINT('',(4.29999902,0.E+000)); +#197287 = VECTOR('',#197288,1.); +#197288 = DIRECTION('',(0.E+000,-1.)); +#197289 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197290 = PCURVE('',#197078,#197291); +#197291 = DEFINITIONAL_REPRESENTATION('',(#197292),#197296); +#197292 = LINE('',#197293,#197294); +#197293 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197294 = VECTOR('',#197295,1.); +#197295 = DIRECTION('',(0.E+000,-1.)); +#197296 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197297 = ORIENTED_EDGE('',*,*,#197298,.F.); +#197298 = EDGE_CURVE('',#197200,#197276,#197299,.T.); +#197299 = SURFACE_CURVE('',#197300,(#197304,#197311),.PCURVE_S1.); +#197300 = LINE('',#197301,#197302); +#197301 = CARTESIAN_POINT('',(-3.99999962,2.15000078,0.E+000)); +#197302 = VECTOR('',#197303,1.); +#197303 = DIRECTION('',(0.E+000,-1.,0.E+000)); +#197304 = PCURVE('',#197215,#197305); +#197305 = DEFINITIONAL_REPRESENTATION('',(#197306),#197310); +#197306 = LINE('',#197307,#197308); +#197307 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197308 = VECTOR('',#197309,1.); +#197309 = DIRECTION('',(1.,0.E+000)); +#197310 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197311 = PCURVE('',#197160,#197312); +#197312 = DEFINITIONAL_REPRESENTATION('',(#197313),#197317); +#197313 = LINE('',#197314,#197315); +#197314 = CARTESIAN_POINT('',(7.99999924,4.29999902)); +#197315 = VECTOR('',#197316,1.); +#197316 = DIRECTION('',(0.E+000,-1.)); +#197317 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197318 = ADVANCED_FACE('',(#197319),#197078,.F.); +#197319 = FACE_BOUND('',#197320,.F.); +#197320 = EDGE_LOOP('',(#197321,#197322,#197343,#197344)); +#197321 = ORIENTED_EDGE('',*,*,#197275,.T.); +#197322 = ORIENTED_EDGE('',*,*,#197323,.T.); +#197323 = EDGE_CURVE('',#197253,#197058,#197324,.T.); +#197324 = SURFACE_CURVE('',#197325,(#197329,#197336),.PCURVE_S1.); +#197325 = LINE('',#197326,#197327); +#197326 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,2.9)); +#197327 = VECTOR('',#197328,1.); +#197328 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197329 = PCURVE('',#197078,#197330); +#197330 = DEFINITIONAL_REPRESENTATION('',(#197331),#197335); +#197331 = LINE('',#197332,#197333); +#197332 = CARTESIAN_POINT('',(0.E+000,-2.9)); +#197333 = VECTOR('',#197334,1.); +#197334 = DIRECTION('',(1.,0.E+000)); +#197335 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197336 = PCURVE('',#197106,#197337); +#197337 = DEFINITIONAL_REPRESENTATION('',(#197338),#197342); +#197338 = LINE('',#197339,#197340); +#197339 = CARTESIAN_POINT('',(7.99999924,0.E+000)); +#197340 = VECTOR('',#197341,1.); +#197341 = DIRECTION('',(-1.,0.E+000)); +#197342 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197343 = ORIENTED_EDGE('',*,*,#197055,.F.); +#197344 = ORIENTED_EDGE('',*,*,#197345,.F.); +#197345 = EDGE_CURVE('',#197276,#197056,#197346,.T.); +#197346 = SURFACE_CURVE('',#197347,(#197351,#197358),.PCURVE_S1.); +#197347 = LINE('',#197348,#197349); +#197348 = CARTESIAN_POINT('',(-3.99999962,-2.14999824,0.E+000)); +#197349 = VECTOR('',#197350,1.); +#197350 = DIRECTION('',(1.,0.E+000,0.E+000)); +#197351 = PCURVE('',#197078,#197352); +#197352 = DEFINITIONAL_REPRESENTATION('',(#197353),#197357); +#197353 = LINE('',#197354,#197355); +#197354 = CARTESIAN_POINT('',(0.E+000,0.E+000)); +#197355 = VECTOR('',#197356,1.); +#197356 = DIRECTION('',(1.,0.E+000)); +#197357 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197358 = PCURVE('',#197160,#197359); +#197359 = DEFINITIONAL_REPRESENTATION('',(#197360),#197364); +#197360 = LINE('',#197361,#197362); +#197361 = CARTESIAN_POINT('',(7.99999924,0.E+000)); +#197362 = VECTOR('',#197363,1.); +#197363 = DIRECTION('',(-1.,0.E+000)); +#197364 = ( GEOMETRIC_REPRESENTATION_CONTEXT(2) +PARAMETRIC_REPRESENTATION_CONTEXT() REPRESENTATION_CONTEXT('2D SPACE','' + ) ); +#197365 = ADVANCED_FACE('',(#197366),#197160,.T.); +#197366 = FACE_BOUND('',#197367,.F.); +#197367 = EDGE_LOOP('',(#197368,#197369,#197370,#197371)); +#197368 = ORIENTED_EDGE('',*,*,#197146,.T.); +#197369 = ORIENTED_EDGE('',*,*,#197227,.T.); +#197370 = ORIENTED_EDGE('',*,*,#197298,.T.); +#197371 = ORIENTED_EDGE('',*,*,#197345,.T.); +#197372 = ADVANCED_FACE('',(#197373),#197106,.F.); +#197373 = FACE_BOUND('',#197374,.T.); +#197374 = EDGE_LOOP('',(#197375,#197376,#197377,#197378)); +#197375 = ORIENTED_EDGE('',*,*,#197090,.T.); +#197376 = ORIENTED_EDGE('',*,*,#197176,.T.); +#197377 = ORIENTED_EDGE('',*,*,#197252,.T.); +#197378 = ORIENTED_EDGE('',*,*,#197323,.T.); +#197379 = ( GEOMETRIC_REPRESENTATION_CONTEXT(3) +GLOBAL_UNCERTAINTY_ASSIGNED_CONTEXT((#197383)) +GLOBAL_UNIT_ASSIGNED_CONTEXT((#197380,#197381,#197382)) REPRESENTATION_CONTEXT('Context #1', '3D Context with UNIT and UNCERTAINTY') ); -#194988 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); -#194989 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); -#194990 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); -#194991 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#194988, +#197380 = ( LENGTH_UNIT() NAMED_UNIT(*) SI_UNIT(.MILLI.,.METRE.) ); +#197381 = ( NAMED_UNIT(*) PLANE_ANGLE_UNIT() SI_UNIT($,.RADIAN.) ); +#197382 = ( NAMED_UNIT(*) SI_UNIT($,.STERADIAN.) SOLID_ANGLE_UNIT() ); +#197383 = UNCERTAINTY_MEASURE_WITH_UNIT(LENGTH_MEASURE(1.E-007),#197380, 'distance_accuracy_value','confusion accuracy'); -#194992 = SHAPE_DEFINITION_REPRESENTATION(#194993,#194656); -#194993 = PRODUCT_DEFINITION_SHAPE('','',#194994); -#194994 = PRODUCT_DEFINITION('design','',#194995,#194998); -#194995 = PRODUCT_DEFINITION_FORMATION('','',#194996); -#194996 = PRODUCT('Extruded','Extruded','',(#194997)); -#194997 = PRODUCT_CONTEXT('',#2,'mechanical'); -#194998 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); -#194999 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#195000,#195002); -#195000 = ( REPRESENTATION_RELATIONSHIP('','',#194656,#194646) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#195001) +#197384 = SHAPE_DEFINITION_REPRESENTATION(#197385,#197048); +#197385 = PRODUCT_DEFINITION_SHAPE('','',#197386); +#197386 = PRODUCT_DEFINITION('design','',#197387,#197390); +#197387 = PRODUCT_DEFINITION_FORMATION('','',#197388); +#197388 = PRODUCT('Extruded','Extruded','',(#197389)); +#197389 = PRODUCT_CONTEXT('',#2,'mechanical'); +#197390 = PRODUCT_DEFINITION_CONTEXT('part definition',#2,'design'); +#197391 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#197392,#197394); +#197392 = ( REPRESENTATION_RELATIONSHIP('','',#197048,#197038) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#197393) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#195001 = ITEM_DEFINED_TRANSFORMATION('','',#11,#194647); -#195002 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #195003); -#195003 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('329','=>[0:1:1:2]','',#194641, - #194994,$); -#195004 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#194996)); -#195005 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#195006,#195008); -#195006 = ( REPRESENTATION_RELATIONSHIP('','',#194646,#194629) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#195007) +#197393 = ITEM_DEFINED_TRANSFORMATION('','',#11,#197039); +#197394 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #197395); +#197395 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('430','=>[0:1:1:2]','',#197033, + #197386,$); +#197396 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#197388)); +#197397 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#197398,#197400); +#197398 = ( REPRESENTATION_RELATIONSHIP('','',#197038,#197021) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#197399) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#195007 = ITEM_DEFINED_TRANSFORMATION('','',#11,#194630); -#195008 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #195009); -#195009 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('330','=>[0:1:1:121]','', - #194624,#194641,$); -#195010 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#194643)); -#195011 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#195012,#195014); -#195012 = ( REPRESENTATION_RELATIONSHIP('','',#194629,#10) -REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#195013) +#197399 = ITEM_DEFINED_TRANSFORMATION('','',#11,#197022); +#197400 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #197401); +#197401 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('431','=>[0:1:1:121]','', + #197016,#197033,$); +#197402 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#197035)); +#197403 = CONTEXT_DEPENDENT_SHAPE_REPRESENTATION(#197404,#197406); +#197404 = ( REPRESENTATION_RELATIONSHIP('','',#197021,#10) +REPRESENTATION_RELATIONSHIP_WITH_TRANSFORMATION(#197405) SHAPE_REPRESENTATION_RELATIONSHIP() ); -#195013 = ITEM_DEFINED_TRANSFORMATION('','',#11,#323); -#195014 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', - #195015); -#195015 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('331','=>[0:1:1:120]','',#5, - #194624,$); -#195016 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#194626)); -#195017 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #195018,#195026,#195034,#195041,#195048,#195055,#195062,#195069, - #195076,#195084,#195091,#195098,#195105,#195112,#195119,#195126, - #195133,#195140,#195147,#195154,#195161,#195168,#195175,#195182, - #195189,#195196,#195203,#195210,#195217,#195224,#195231,#195238, - #195245,#195252,#195259,#195266,#195273,#195280,#195287,#195294, - #195301,#195308,#195315,#195322,#195329,#195336,#195343,#195350, - #195357,#195364,#195371,#195378,#195385,#195392,#195399,#195406, - #195413,#195420,#195427,#195434,#195441,#195448,#195455,#195462, - #195469,#195476,#195483,#195490,#195497,#195504,#195511,#195518, - #195525,#195532,#195539,#195546,#195553,#195560,#195567,#195574, - #195581,#195588,#195595,#195602,#195609,#195616,#195623,#195630, - #195637,#195644,#195651,#195658,#195665,#195672,#195679,#195686, - #195693,#195700,#195707,#195714,#195721,#195728,#195735,#195742, - #195749,#195756,#195763,#195770,#195777,#195784,#195791,#195798, - #195805,#195812,#195819,#195826,#195833,#195840,#195847,#195854, - #195861,#195868,#195875,#195882,#195889,#195896,#195903,#195910, - #195917,#195924,#195931,#195938,#195945,#195952,#195959,#195966, - #195973,#195980,#195987,#195994,#196001,#196008,#196015,#196022, - #196029,#196036,#196043,#196050,#196057,#196064,#196071,#196078, - #196085,#196092,#196099,#196106,#196113,#196120,#196127,#196134, - #196141,#196148,#196155,#196162,#196169,#196176,#196183,#196190, - #196197,#196204,#196211,#196218,#196225,#196232,#196239,#196246, - #196253,#196260,#196267,#196274,#196281,#196288,#196295,#196302, - #196309,#196316,#196323,#196330,#196337,#196344,#196351,#196358, - #196365,#196372,#196379,#196386,#196393,#196400,#196407,#196414, - #196421,#196428,#196435,#196442,#196449,#196456,#196463,#196470, - #196477,#196484,#196491,#196498,#196505,#196512,#196519,#196526, - #196533,#196540,#196547,#196554,#196561,#196568,#196575,#196582, - #196589,#196596,#196603,#196610,#196617,#196624,#196631,#196638, - #196645,#196652,#196659,#196666,#196673,#196680,#196687,#196694, - #196701,#196708,#196715,#196722,#196729,#196736,#196743,#196750, - #196757,#196764,#196771,#196778,#196785,#196792,#196799,#196806, - #196813,#196820,#196827,#196834,#196841,#196848,#196855,#196862, - #196869,#196876,#196883,#196890,#196897,#196904,#196911,#196918, - #196925,#196932,#196939,#196946,#196953,#196960,#196967,#196974, - #196981,#196988,#196995,#197002,#197009,#197016,#197023,#197030, - #197037,#197044,#197051,#197058,#197065,#197072,#197079,#197086, - #197093,#197100,#197107,#197114,#197121,#197128,#197135,#197142, - #197149,#197156,#197163,#197170,#197177,#197184,#197191,#197198, - #197205,#197212,#197219,#197226,#197233,#197240,#197247,#197254, - #197261,#197268,#197275,#197282,#197289,#197296,#197303,#197310, - #197317,#197324,#197331,#197338,#197345,#197352,#197359,#197366, - #197373,#197380,#197387,#197394,#197401,#197408,#197415,#197422, - #197429,#197436,#197443,#197450,#197457,#197464,#197471,#197478, - #197485,#197492,#197499,#197506,#197513,#197520,#197527,#197534, - #197541,#197548,#197555,#197562,#197569,#197576,#197583,#197590, - #197597,#197604,#197611,#197618,#197625,#197632,#197639,#197646, - #197653,#197660,#197667,#197674,#197681,#197688,#197695,#197702, - #197709,#197716,#197723,#197730,#197737,#197744,#197751,#197758, - #197765,#197772,#197779,#197786,#197793,#197800,#197807,#197814, - #197821,#197828,#197835,#197842,#197849,#197856,#197863,#197870, - #197877,#197884,#197891,#197898,#197905,#197912,#197919,#197926, - #197933,#197940,#197947,#197954,#197961,#197968,#197975,#197982, - #197989,#197996,#198003,#198010,#198017,#198024,#198031,#198038, - #198045,#198052,#198059,#198066,#198073,#198080,#198087,#198094, - #198101,#198108,#198115,#198122,#198129,#198136,#198143,#198150, - #198157,#198164,#198171,#198178,#198185,#198192,#198199,#198206, - #198213,#198220,#198227,#198234,#198241,#198248,#198255,#198262, - #198269,#198276,#198283,#198290,#198297,#198304,#198311,#198318, - #198325,#198332,#198339,#198346,#198353,#198360,#198367,#198374, - #198381,#198388,#198395,#198402,#198409,#198416,#198423,#198430, - #198437,#198444,#198451,#198458,#198465,#198472,#198479,#198486, - #198493,#198500,#198507,#198514,#198521,#198528,#198535,#198542, - #198549,#198556,#198563,#198570,#198577,#198584,#198591,#198598, - #198605,#198612,#198619,#198626,#198633,#198640,#198647,#198654, - #198661,#198668,#198675,#198682,#198689,#198696,#198703,#198710, - #198717,#198724,#198731,#198738,#198745,#198752,#198759,#198766, - #198773,#198780,#198787,#198794,#198801,#198808,#198815,#198822, - #198829,#198836,#198843,#198850,#198857,#198864,#198871,#198878, - #198885,#198892,#198899,#198906,#198913,#198920,#198927,#198934, - #198941,#198948,#198955,#198962,#198969,#198976,#198983,#198990, - #198997,#199004,#199011,#199018,#199025,#199032,#199039,#199046, - #199053,#199060,#199067,#199074,#199081,#199088,#199095,#199102, - #199109,#199116,#199123,#199130,#199137,#199144,#199151,#199158, - #199165,#199172,#199179,#199186,#199193,#199200,#199207,#199214, - #199221,#199228,#199235,#199242,#199249,#199256,#199263,#199270, - #199277,#199284,#199291,#199298,#199305,#199312,#199319,#199326, - #199333,#199340,#199347,#199354,#199361,#199368,#199375,#199382, - #199389,#199396,#199403,#199410,#199417,#199424,#199431,#199438, - #199445,#199452,#199459,#199466,#199473,#199480,#199487,#199494, - #199501,#199508,#199515,#199522,#199529,#199536,#199543,#199550, - #199557,#199564,#199571,#199578,#199585,#199592,#199599,#199606, - #199613,#199620,#199627,#199634,#199641,#199648,#199655,#199662, - #199669,#199676,#199683,#199690,#199697,#199704,#199711,#199718, - #199725,#199732,#199739,#199746,#199753,#199760,#199767,#199774, - #199781,#199788,#199795,#199802,#199809,#199816,#199823,#199830, - #199837,#199844,#199851,#199858,#199865,#199872,#199879,#199886, - #199893,#199900,#199907,#199914,#199921,#199928,#199935,#199942, - #199949,#199956,#199963,#199970,#199977,#199984,#199991,#199998, - #200005,#200012,#200019,#200026,#200033,#200040,#200047,#200054, - #200061,#200068,#200075,#200082,#200089,#200096,#200103,#200110, - #200117,#200124,#200131,#200138,#200145,#200152,#200159,#200166, - #200173,#200180,#200187,#200194,#200201,#200208,#200215,#200222, - #200229,#200236,#200243,#200250,#200257,#200264,#200271,#200278, - #200285,#200292,#200299,#200306,#200313,#200320,#200327,#200334, - #200341,#200348,#200355,#200362,#200369,#200376,#200383,#200390, - #200397,#200404,#200411,#200418,#200425,#200432,#200439,#200446, - #200453,#200460,#200467,#200474,#200481,#200488,#200495,#200502, - #200509,#200516,#200523,#200530,#200537,#200544,#200551,#200558, - #200565,#200572,#200579,#200586,#200593,#200600,#200607,#200614, - #200621,#200628,#200635,#200642,#200649,#200656,#200663,#200670, - #200677,#200684,#200691,#200698,#200705,#200712,#200719,#200726, - #200733,#200740,#200747,#200754,#200761,#200768,#200775,#200782, - #200789,#200796,#200803,#200810,#200817,#200824,#200831,#200838, - #200845,#200852,#200859,#200866,#200873,#200880,#200887,#200894, - #200901,#200908,#200915,#200922,#200929,#200936,#200943,#200950, - #200957,#200964,#200971,#200978,#200985,#200992),#151200); -#195018 = STYLED_ITEM('color',(#195019),#86328); -#195019 = PRESENTATION_STYLE_ASSIGNMENT((#195020)); -#195020 = SURFACE_STYLE_USAGE(.BOTH.,#195021); -#195021 = SURFACE_SIDE_STYLE('',(#195022)); -#195022 = SURFACE_STYLE_FILL_AREA(#195023); -#195023 = FILL_AREA_STYLE('',(#195024)); -#195024 = FILL_AREA_STYLE_COLOUR('',#195025); -#195025 = COLOUR_RGB('',0.250980407,0.250980407,0.250980407); -#195026 = OVER_RIDING_STYLED_ITEM('overriding color',(#195027),#86330, - #195018); -#195027 = PRESENTATION_STYLE_ASSIGNMENT((#195028)); -#195028 = SURFACE_STYLE_USAGE(.BOTH.,#195029); -#195029 = SURFACE_SIDE_STYLE('',(#195030)); -#195030 = SURFACE_STYLE_FILL_AREA(#195031); -#195031 = FILL_AREA_STYLE('',(#195032)); -#195032 = FILL_AREA_STYLE_COLOUR('',#195033); -#195033 = COLOUR_RGB('',0.137254908681,0.137254908681,0.137254908681); -#195034 = OVER_RIDING_STYLED_ITEM('overriding color',(#195035),#86445, - #195018); -#195035 = PRESENTATION_STYLE_ASSIGNMENT((#195036)); -#195036 = SURFACE_STYLE_USAGE(.BOTH.,#195037); -#195037 = SURFACE_SIDE_STYLE('',(#195038)); -#195038 = SURFACE_STYLE_FILL_AREA(#195039); -#195039 = FILL_AREA_STYLE('',(#195040)); -#195040 = FILL_AREA_STYLE_COLOUR('',#195033); -#195041 = OVER_RIDING_STYLED_ITEM('overriding color',(#195042),#88389, - #195018); -#195042 = PRESENTATION_STYLE_ASSIGNMENT((#195043)); -#195043 = SURFACE_STYLE_USAGE(.BOTH.,#195044); -#195044 = SURFACE_SIDE_STYLE('',(#195045)); -#195045 = SURFACE_STYLE_FILL_AREA(#195046); -#195046 = FILL_AREA_STYLE('',(#195047)); -#195047 = FILL_AREA_STYLE_COLOUR('',#195033); -#195048 = OVER_RIDING_STYLED_ITEM('overriding color',(#195049),#90328, - #195018); -#195049 = PRESENTATION_STYLE_ASSIGNMENT((#195050)); -#195050 = SURFACE_STYLE_USAGE(.BOTH.,#195051); -#195051 = SURFACE_SIDE_STYLE('',(#195052)); -#195052 = SURFACE_STYLE_FILL_AREA(#195053); -#195053 = FILL_AREA_STYLE('',(#195054)); -#195054 = FILL_AREA_STYLE_COLOUR('',#195033); -#195055 = OVER_RIDING_STYLED_ITEM('overriding color',(#195056),#92257, - #195018); -#195056 = PRESENTATION_STYLE_ASSIGNMENT((#195057)); -#195057 = SURFACE_STYLE_USAGE(.BOTH.,#195058); -#195058 = SURFACE_SIDE_STYLE('',(#195059)); -#195059 = SURFACE_STYLE_FILL_AREA(#195060); -#195060 = FILL_AREA_STYLE('',(#195061)); -#195061 = FILL_AREA_STYLE_COLOUR('',#195033); -#195062 = OVER_RIDING_STYLED_ITEM('overriding color',(#195063),#94186, - #195018); -#195063 = PRESENTATION_STYLE_ASSIGNMENT((#195064)); -#195064 = SURFACE_STYLE_USAGE(.BOTH.,#195065); -#195065 = SURFACE_SIDE_STYLE('',(#195066)); -#195066 = SURFACE_STYLE_FILL_AREA(#195067); -#195067 = FILL_AREA_STYLE('',(#195068)); -#195068 = FILL_AREA_STYLE_COLOUR('',#195033); -#195069 = OVER_RIDING_STYLED_ITEM('overriding color',(#195070),#94309, - #195018); -#195070 = PRESENTATION_STYLE_ASSIGNMENT((#195071)); -#195071 = SURFACE_STYLE_USAGE(.BOTH.,#195072); -#195072 = SURFACE_SIDE_STYLE('',(#195073)); -#195073 = SURFACE_STYLE_FILL_AREA(#195074); -#195074 = FILL_AREA_STYLE('',(#195075)); -#195075 = FILL_AREA_STYLE_COLOUR('',#195033); -#195076 = OVER_RIDING_STYLED_ITEM('overriding color',(#195077),#94400, - #195018); -#195077 = PRESENTATION_STYLE_ASSIGNMENT((#195078)); -#195078 = SURFACE_STYLE_USAGE(.BOTH.,#195079); -#195079 = SURFACE_SIDE_STYLE('',(#195080)); -#195080 = SURFACE_STYLE_FILL_AREA(#195081); -#195081 = FILL_AREA_STYLE('',(#195082)); -#195082 = FILL_AREA_STYLE_COLOUR('',#195083); -#195083 = DRAUGHTING_PRE_DEFINED_COLOUR('white'); -#195084 = OVER_RIDING_STYLED_ITEM('overriding color',(#195085),#94509, - #195018); -#195085 = PRESENTATION_STYLE_ASSIGNMENT((#195086)); -#195086 = SURFACE_STYLE_USAGE(.BOTH.,#195087); -#195087 = SURFACE_SIDE_STYLE('',(#195088)); -#195088 = SURFACE_STYLE_FILL_AREA(#195089); -#195089 = FILL_AREA_STYLE('',(#195090)); -#195090 = FILL_AREA_STYLE_COLOUR('',#195083); -#195091 = OVER_RIDING_STYLED_ITEM('overriding color',(#195092),#94613, - #195018); -#195092 = PRESENTATION_STYLE_ASSIGNMENT((#195093)); -#195093 = SURFACE_STYLE_USAGE(.BOTH.,#195094); -#195094 = SURFACE_SIDE_STYLE('',(#195095)); -#195095 = SURFACE_STYLE_FILL_AREA(#195096); -#195096 = FILL_AREA_STYLE('',(#195097)); -#195097 = FILL_AREA_STYLE_COLOUR('',#195083); -#195098 = OVER_RIDING_STYLED_ITEM('overriding color',(#195099),#94692, - #195018); -#195099 = PRESENTATION_STYLE_ASSIGNMENT((#195100)); -#195100 = SURFACE_STYLE_USAGE(.BOTH.,#195101); -#195101 = SURFACE_SIDE_STYLE('',(#195102)); -#195102 = SURFACE_STYLE_FILL_AREA(#195103); -#195103 = FILL_AREA_STYLE('',(#195104)); -#195104 = FILL_AREA_STYLE_COLOUR('',#195083); -#195105 = OVER_RIDING_STYLED_ITEM('overriding color',(#195106),#94771, - #195018); -#195106 = PRESENTATION_STYLE_ASSIGNMENT((#195107)); -#195107 = SURFACE_STYLE_USAGE(.BOTH.,#195108); -#195108 = SURFACE_SIDE_STYLE('',(#195109)); -#195109 = SURFACE_STYLE_FILL_AREA(#195110); -#195110 = FILL_AREA_STYLE('',(#195111)); -#195111 = FILL_AREA_STYLE_COLOUR('',#195083); -#195112 = OVER_RIDING_STYLED_ITEM('overriding color',(#195113),#94846, - #195018); -#195113 = PRESENTATION_STYLE_ASSIGNMENT((#195114)); -#195114 = SURFACE_STYLE_USAGE(.BOTH.,#195115); -#195115 = SURFACE_SIDE_STYLE('',(#195116)); -#195116 = SURFACE_STYLE_FILL_AREA(#195117); -#195117 = FILL_AREA_STYLE('',(#195118)); -#195118 = FILL_AREA_STYLE_COLOUR('',#195083); -#195119 = OVER_RIDING_STYLED_ITEM('overriding color',(#195120),#94921, - #195018); -#195120 = PRESENTATION_STYLE_ASSIGNMENT((#195121)); -#195121 = SURFACE_STYLE_USAGE(.BOTH.,#195122); -#195122 = SURFACE_SIDE_STYLE('',(#195123)); -#195123 = SURFACE_STYLE_FILL_AREA(#195124); -#195124 = FILL_AREA_STYLE('',(#195125)); -#195125 = FILL_AREA_STYLE_COLOUR('',#195083); -#195126 = OVER_RIDING_STYLED_ITEM('overriding color',(#195127),#94995, - #195018); -#195127 = PRESENTATION_STYLE_ASSIGNMENT((#195128)); -#195128 = SURFACE_STYLE_USAGE(.BOTH.,#195129); -#195129 = SURFACE_SIDE_STYLE('',(#195130)); -#195130 = SURFACE_STYLE_FILL_AREA(#195131); -#195131 = FILL_AREA_STYLE('',(#195132)); -#195132 = FILL_AREA_STYLE_COLOUR('',#195083); -#195133 = OVER_RIDING_STYLED_ITEM('overriding color',(#195134),#95069, - #195018); -#195134 = PRESENTATION_STYLE_ASSIGNMENT((#195135)); -#195135 = SURFACE_STYLE_USAGE(.BOTH.,#195136); -#195136 = SURFACE_SIDE_STYLE('',(#195137)); -#195137 = SURFACE_STYLE_FILL_AREA(#195138); -#195138 = FILL_AREA_STYLE('',(#195139)); -#195139 = FILL_AREA_STYLE_COLOUR('',#195083); -#195140 = OVER_RIDING_STYLED_ITEM('overriding color',(#195141),#95144, - #195018); -#195141 = PRESENTATION_STYLE_ASSIGNMENT((#195142)); -#195142 = SURFACE_STYLE_USAGE(.BOTH.,#195143); -#195143 = SURFACE_SIDE_STYLE('',(#195144)); -#195144 = SURFACE_STYLE_FILL_AREA(#195145); -#195145 = FILL_AREA_STYLE('',(#195146)); -#195146 = FILL_AREA_STYLE_COLOUR('',#195083); -#195147 = OVER_RIDING_STYLED_ITEM('overriding color',(#195148),#95171, - #195018); -#195148 = PRESENTATION_STYLE_ASSIGNMENT((#195149)); -#195149 = SURFACE_STYLE_USAGE(.BOTH.,#195150); -#195150 = SURFACE_SIDE_STYLE('',(#195151)); -#195151 = SURFACE_STYLE_FILL_AREA(#195152); -#195152 = FILL_AREA_STYLE('',(#195153)); -#195153 = FILL_AREA_STYLE_COLOUR('',#195083); -#195154 = OVER_RIDING_STYLED_ITEM('overriding color',(#195155),#95226, - #195018); -#195155 = PRESENTATION_STYLE_ASSIGNMENT((#195156)); -#195156 = SURFACE_STYLE_USAGE(.BOTH.,#195157); -#195157 = SURFACE_SIDE_STYLE('',(#195158)); -#195158 = SURFACE_STYLE_FILL_AREA(#195159); -#195159 = FILL_AREA_STYLE('',(#195160)); -#195160 = FILL_AREA_STYLE_COLOUR('',#195083); -#195161 = OVER_RIDING_STYLED_ITEM('overriding color',(#195162),#95233, - #195018); -#195162 = PRESENTATION_STYLE_ASSIGNMENT((#195163)); -#195163 = SURFACE_STYLE_USAGE(.BOTH.,#195164); -#195164 = SURFACE_SIDE_STYLE('',(#195165)); -#195165 = SURFACE_STYLE_FILL_AREA(#195166); -#195166 = FILL_AREA_STYLE('',(#195167)); -#195167 = FILL_AREA_STYLE_COLOUR('',#195083); -#195168 = OVER_RIDING_STYLED_ITEM('overriding color',(#195169),#95240, - #195018); -#195169 = PRESENTATION_STYLE_ASSIGNMENT((#195170)); -#195170 = SURFACE_STYLE_USAGE(.BOTH.,#195171); -#195171 = SURFACE_SIDE_STYLE('',(#195172)); -#195172 = SURFACE_STYLE_FILL_AREA(#195173); -#195173 = FILL_AREA_STYLE('',(#195174)); -#195174 = FILL_AREA_STYLE_COLOUR('',#195083); -#195175 = OVER_RIDING_STYLED_ITEM('overriding color',(#195176),#95349, - #195018); -#195176 = PRESENTATION_STYLE_ASSIGNMENT((#195177)); -#195177 = SURFACE_STYLE_USAGE(.BOTH.,#195178); -#195178 = SURFACE_SIDE_STYLE('',(#195179)); -#195179 = SURFACE_STYLE_FILL_AREA(#195180); -#195180 = FILL_AREA_STYLE('',(#195181)); -#195181 = FILL_AREA_STYLE_COLOUR('',#195083); -#195182 = OVER_RIDING_STYLED_ITEM('overriding color',(#195183),#95453, - #195018); -#195183 = PRESENTATION_STYLE_ASSIGNMENT((#195184)); -#195184 = SURFACE_STYLE_USAGE(.BOTH.,#195185); -#195185 = SURFACE_SIDE_STYLE('',(#195186)); -#195186 = SURFACE_STYLE_FILL_AREA(#195187); -#195187 = FILL_AREA_STYLE('',(#195188)); -#195188 = FILL_AREA_STYLE_COLOUR('',#195083); -#195189 = OVER_RIDING_STYLED_ITEM('overriding color',(#195190),#95532, - #195018); -#195190 = PRESENTATION_STYLE_ASSIGNMENT((#195191)); -#195191 = SURFACE_STYLE_USAGE(.BOTH.,#195192); -#195192 = SURFACE_SIDE_STYLE('',(#195193)); -#195193 = SURFACE_STYLE_FILL_AREA(#195194); -#195194 = FILL_AREA_STYLE('',(#195195)); -#195195 = FILL_AREA_STYLE_COLOUR('',#195083); -#195196 = OVER_RIDING_STYLED_ITEM('overriding color',(#195197),#95611, - #195018); -#195197 = PRESENTATION_STYLE_ASSIGNMENT((#195198)); -#195198 = SURFACE_STYLE_USAGE(.BOTH.,#195199); -#195199 = SURFACE_SIDE_STYLE('',(#195200)); -#195200 = SURFACE_STYLE_FILL_AREA(#195201); -#195201 = FILL_AREA_STYLE('',(#195202)); -#195202 = FILL_AREA_STYLE_COLOUR('',#195083); -#195203 = OVER_RIDING_STYLED_ITEM('overriding color',(#195204),#95686, - #195018); -#195204 = PRESENTATION_STYLE_ASSIGNMENT((#195205)); -#195205 = SURFACE_STYLE_USAGE(.BOTH.,#195206); -#195206 = SURFACE_SIDE_STYLE('',(#195207)); -#195207 = SURFACE_STYLE_FILL_AREA(#195208); -#195208 = FILL_AREA_STYLE('',(#195209)); -#195209 = FILL_AREA_STYLE_COLOUR('',#195083); -#195210 = OVER_RIDING_STYLED_ITEM('overriding color',(#195211),#95761, - #195018); -#195211 = PRESENTATION_STYLE_ASSIGNMENT((#195212)); -#195212 = SURFACE_STYLE_USAGE(.BOTH.,#195213); -#195213 = SURFACE_SIDE_STYLE('',(#195214)); -#195214 = SURFACE_STYLE_FILL_AREA(#195215); -#195215 = FILL_AREA_STYLE('',(#195216)); -#195216 = FILL_AREA_STYLE_COLOUR('',#195083); -#195217 = OVER_RIDING_STYLED_ITEM('overriding color',(#195218),#95835, - #195018); -#195218 = PRESENTATION_STYLE_ASSIGNMENT((#195219)); -#195219 = SURFACE_STYLE_USAGE(.BOTH.,#195220); -#195220 = SURFACE_SIDE_STYLE('',(#195221)); -#195221 = SURFACE_STYLE_FILL_AREA(#195222); -#195222 = FILL_AREA_STYLE('',(#195223)); -#195223 = FILL_AREA_STYLE_COLOUR('',#195083); -#195224 = OVER_RIDING_STYLED_ITEM('overriding color',(#195225),#95909, - #195018); -#195225 = PRESENTATION_STYLE_ASSIGNMENT((#195226)); -#195226 = SURFACE_STYLE_USAGE(.BOTH.,#195227); -#195227 = SURFACE_SIDE_STYLE('',(#195228)); -#195228 = SURFACE_STYLE_FILL_AREA(#195229); -#195229 = FILL_AREA_STYLE('',(#195230)); -#195230 = FILL_AREA_STYLE_COLOUR('',#195083); -#195231 = OVER_RIDING_STYLED_ITEM('overriding color',(#195232),#95956, - #195018); -#195232 = PRESENTATION_STYLE_ASSIGNMENT((#195233)); -#195233 = SURFACE_STYLE_USAGE(.BOTH.,#195234); -#195234 = SURFACE_SIDE_STYLE('',(#195235)); -#195235 = SURFACE_STYLE_FILL_AREA(#195236); -#195236 = FILL_AREA_STYLE('',(#195237)); -#195237 = FILL_AREA_STYLE_COLOUR('',#195083); -#195238 = OVER_RIDING_STYLED_ITEM('overriding color',(#195239),#96011, - #195018); -#195239 = PRESENTATION_STYLE_ASSIGNMENT((#195240)); -#195240 = SURFACE_STYLE_USAGE(.BOTH.,#195241); -#195241 = SURFACE_SIDE_STYLE('',(#195242)); -#195242 = SURFACE_STYLE_FILL_AREA(#195243); -#195243 = FILL_AREA_STYLE('',(#195244)); -#195244 = FILL_AREA_STYLE_COLOUR('',#195083); -#195245 = OVER_RIDING_STYLED_ITEM('overriding color',(#195246),#96038, - #195018); -#195246 = PRESENTATION_STYLE_ASSIGNMENT((#195247)); -#195247 = SURFACE_STYLE_USAGE(.BOTH.,#195248); -#195248 = SURFACE_SIDE_STYLE('',(#195249)); -#195249 = SURFACE_STYLE_FILL_AREA(#195250); -#195250 = FILL_AREA_STYLE('',(#195251)); -#195251 = FILL_AREA_STYLE_COLOUR('',#195083); -#195252 = OVER_RIDING_STYLED_ITEM('overriding color',(#195253),#96073, - #195018); -#195253 = PRESENTATION_STYLE_ASSIGNMENT((#195254)); -#195254 = SURFACE_STYLE_USAGE(.BOTH.,#195255); -#195255 = SURFACE_SIDE_STYLE('',(#195256)); -#195256 = SURFACE_STYLE_FILL_AREA(#195257); -#195257 = FILL_AREA_STYLE('',(#195258)); -#195258 = FILL_AREA_STYLE_COLOUR('',#195083); -#195259 = OVER_RIDING_STYLED_ITEM('overriding color',(#195260),#96080, - #195018); -#195260 = PRESENTATION_STYLE_ASSIGNMENT((#195261)); -#195261 = SURFACE_STYLE_USAGE(.BOTH.,#195262); -#195262 = SURFACE_SIDE_STYLE('',(#195263)); -#195263 = SURFACE_STYLE_FILL_AREA(#195264); -#195264 = FILL_AREA_STYLE('',(#195265)); -#195265 = FILL_AREA_STYLE_COLOUR('',#195083); -#195266 = OVER_RIDING_STYLED_ITEM('overriding color',(#195267),#96189, - #195018); -#195267 = PRESENTATION_STYLE_ASSIGNMENT((#195268)); -#195268 = SURFACE_STYLE_USAGE(.BOTH.,#195269); -#195269 = SURFACE_SIDE_STYLE('',(#195270)); -#195270 = SURFACE_STYLE_FILL_AREA(#195271); -#195271 = FILL_AREA_STYLE('',(#195272)); -#195272 = FILL_AREA_STYLE_COLOUR('',#195083); -#195273 = OVER_RIDING_STYLED_ITEM('overriding color',(#195274),#96293, - #195018); -#195274 = PRESENTATION_STYLE_ASSIGNMENT((#195275)); -#195275 = SURFACE_STYLE_USAGE(.BOTH.,#195276); -#195276 = SURFACE_SIDE_STYLE('',(#195277)); -#195277 = SURFACE_STYLE_FILL_AREA(#195278); -#195278 = FILL_AREA_STYLE('',(#195279)); -#195279 = FILL_AREA_STYLE_COLOUR('',#195083); -#195280 = OVER_RIDING_STYLED_ITEM('overriding color',(#195281),#96372, - #195018); -#195281 = PRESENTATION_STYLE_ASSIGNMENT((#195282)); -#195282 = SURFACE_STYLE_USAGE(.BOTH.,#195283); -#195283 = SURFACE_SIDE_STYLE('',(#195284)); -#195284 = SURFACE_STYLE_FILL_AREA(#195285); -#195285 = FILL_AREA_STYLE('',(#195286)); -#195286 = FILL_AREA_STYLE_COLOUR('',#195083); -#195287 = OVER_RIDING_STYLED_ITEM('overriding color',(#195288),#96451, - #195018); -#195288 = PRESENTATION_STYLE_ASSIGNMENT((#195289)); -#195289 = SURFACE_STYLE_USAGE(.BOTH.,#195290); -#195290 = SURFACE_SIDE_STYLE('',(#195291)); -#195291 = SURFACE_STYLE_FILL_AREA(#195292); -#195292 = FILL_AREA_STYLE('',(#195293)); -#195293 = FILL_AREA_STYLE_COLOUR('',#195083); -#195294 = OVER_RIDING_STYLED_ITEM('overriding color',(#195295),#96526, - #195018); -#195295 = PRESENTATION_STYLE_ASSIGNMENT((#195296)); -#195296 = SURFACE_STYLE_USAGE(.BOTH.,#195297); -#195297 = SURFACE_SIDE_STYLE('',(#195298)); -#195298 = SURFACE_STYLE_FILL_AREA(#195299); -#195299 = FILL_AREA_STYLE('',(#195300)); -#195300 = FILL_AREA_STYLE_COLOUR('',#195083); -#195301 = OVER_RIDING_STYLED_ITEM('overriding color',(#195302),#96601, - #195018); -#195302 = PRESENTATION_STYLE_ASSIGNMENT((#195303)); -#195303 = SURFACE_STYLE_USAGE(.BOTH.,#195304); -#195304 = SURFACE_SIDE_STYLE('',(#195305)); -#195305 = SURFACE_STYLE_FILL_AREA(#195306); -#195306 = FILL_AREA_STYLE('',(#195307)); -#195307 = FILL_AREA_STYLE_COLOUR('',#195083); -#195308 = OVER_RIDING_STYLED_ITEM('overriding color',(#195309),#96675, - #195018); -#195309 = PRESENTATION_STYLE_ASSIGNMENT((#195310)); -#195310 = SURFACE_STYLE_USAGE(.BOTH.,#195311); -#195311 = SURFACE_SIDE_STYLE('',(#195312)); -#195312 = SURFACE_STYLE_FILL_AREA(#195313); -#195313 = FILL_AREA_STYLE('',(#195314)); -#195314 = FILL_AREA_STYLE_COLOUR('',#195083); -#195315 = OVER_RIDING_STYLED_ITEM('overriding color',(#195316),#96749, - #195018); -#195316 = PRESENTATION_STYLE_ASSIGNMENT((#195317)); -#195317 = SURFACE_STYLE_USAGE(.BOTH.,#195318); -#195318 = SURFACE_SIDE_STYLE('',(#195319)); -#195319 = SURFACE_STYLE_FILL_AREA(#195320); -#195320 = FILL_AREA_STYLE('',(#195321)); -#195321 = FILL_AREA_STYLE_COLOUR('',#195083); -#195322 = OVER_RIDING_STYLED_ITEM('overriding color',(#195323),#96824, - #195018); -#195323 = PRESENTATION_STYLE_ASSIGNMENT((#195324)); -#195324 = SURFACE_STYLE_USAGE(.BOTH.,#195325); -#195325 = SURFACE_SIDE_STYLE('',(#195326)); -#195326 = SURFACE_STYLE_FILL_AREA(#195327); -#195327 = FILL_AREA_STYLE('',(#195328)); -#195328 = FILL_AREA_STYLE_COLOUR('',#195083); -#195329 = OVER_RIDING_STYLED_ITEM('overriding color',(#195330),#96851, - #195018); -#195330 = PRESENTATION_STYLE_ASSIGNMENT((#195331)); -#195331 = SURFACE_STYLE_USAGE(.BOTH.,#195332); -#195332 = SURFACE_SIDE_STYLE('',(#195333)); -#195333 = SURFACE_STYLE_FILL_AREA(#195334); -#195334 = FILL_AREA_STYLE('',(#195335)); -#195335 = FILL_AREA_STYLE_COLOUR('',#195083); -#195336 = OVER_RIDING_STYLED_ITEM('overriding color',(#195337),#96906, - #195018); -#195337 = PRESENTATION_STYLE_ASSIGNMENT((#195338)); -#195338 = SURFACE_STYLE_USAGE(.BOTH.,#195339); -#195339 = SURFACE_SIDE_STYLE('',(#195340)); -#195340 = SURFACE_STYLE_FILL_AREA(#195341); -#195341 = FILL_AREA_STYLE('',(#195342)); -#195342 = FILL_AREA_STYLE_COLOUR('',#195083); -#195343 = OVER_RIDING_STYLED_ITEM('overriding color',(#195344),#96913, - #195018); -#195344 = PRESENTATION_STYLE_ASSIGNMENT((#195345)); -#195345 = SURFACE_STYLE_USAGE(.BOTH.,#195346); -#195346 = SURFACE_SIDE_STYLE('',(#195347)); -#195347 = SURFACE_STYLE_FILL_AREA(#195348); -#195348 = FILL_AREA_STYLE('',(#195349)); -#195349 = FILL_AREA_STYLE_COLOUR('',#195083); -#195350 = OVER_RIDING_STYLED_ITEM('overriding color',(#195351),#96920, - #195018); -#195351 = PRESENTATION_STYLE_ASSIGNMENT((#195352)); -#195352 = SURFACE_STYLE_USAGE(.BOTH.,#195353); -#195353 = SURFACE_SIDE_STYLE('',(#195354)); -#195354 = SURFACE_STYLE_FILL_AREA(#195355); -#195355 = FILL_AREA_STYLE('',(#195356)); -#195356 = FILL_AREA_STYLE_COLOUR('',#195083); -#195357 = OVER_RIDING_STYLED_ITEM('overriding color',(#195358),#97029, - #195018); -#195358 = PRESENTATION_STYLE_ASSIGNMENT((#195359)); -#195359 = SURFACE_STYLE_USAGE(.BOTH.,#195360); -#195360 = SURFACE_SIDE_STYLE('',(#195361)); -#195361 = SURFACE_STYLE_FILL_AREA(#195362); -#195362 = FILL_AREA_STYLE('',(#195363)); -#195363 = FILL_AREA_STYLE_COLOUR('',#195083); -#195364 = OVER_RIDING_STYLED_ITEM('overriding color',(#195365),#97133, - #195018); -#195365 = PRESENTATION_STYLE_ASSIGNMENT((#195366)); -#195366 = SURFACE_STYLE_USAGE(.BOTH.,#195367); -#195367 = SURFACE_SIDE_STYLE('',(#195368)); -#195368 = SURFACE_STYLE_FILL_AREA(#195369); -#195369 = FILL_AREA_STYLE('',(#195370)); -#195370 = FILL_AREA_STYLE_COLOUR('',#195083); -#195371 = OVER_RIDING_STYLED_ITEM('overriding color',(#195372),#97212, - #195018); -#195372 = PRESENTATION_STYLE_ASSIGNMENT((#195373)); -#195373 = SURFACE_STYLE_USAGE(.BOTH.,#195374); -#195374 = SURFACE_SIDE_STYLE('',(#195375)); -#195375 = SURFACE_STYLE_FILL_AREA(#195376); -#195376 = FILL_AREA_STYLE('',(#195377)); -#195377 = FILL_AREA_STYLE_COLOUR('',#195083); -#195378 = OVER_RIDING_STYLED_ITEM('overriding color',(#195379),#97291, - #195018); -#195379 = PRESENTATION_STYLE_ASSIGNMENT((#195380)); -#195380 = SURFACE_STYLE_USAGE(.BOTH.,#195381); -#195381 = SURFACE_SIDE_STYLE('',(#195382)); -#195382 = SURFACE_STYLE_FILL_AREA(#195383); -#195383 = FILL_AREA_STYLE('',(#195384)); -#195384 = FILL_AREA_STYLE_COLOUR('',#195083); -#195385 = OVER_RIDING_STYLED_ITEM('overriding color',(#195386),#97366, - #195018); -#195386 = PRESENTATION_STYLE_ASSIGNMENT((#195387)); -#195387 = SURFACE_STYLE_USAGE(.BOTH.,#195388); -#195388 = SURFACE_SIDE_STYLE('',(#195389)); -#195389 = SURFACE_STYLE_FILL_AREA(#195390); -#195390 = FILL_AREA_STYLE('',(#195391)); -#195391 = FILL_AREA_STYLE_COLOUR('',#195083); -#195392 = OVER_RIDING_STYLED_ITEM('overriding color',(#195393),#97441, - #195018); -#195393 = PRESENTATION_STYLE_ASSIGNMENT((#195394)); -#195394 = SURFACE_STYLE_USAGE(.BOTH.,#195395); -#195395 = SURFACE_SIDE_STYLE('',(#195396)); -#195396 = SURFACE_STYLE_FILL_AREA(#195397); -#195397 = FILL_AREA_STYLE('',(#195398)); -#195398 = FILL_AREA_STYLE_COLOUR('',#195083); -#195399 = OVER_RIDING_STYLED_ITEM('overriding color',(#195400),#97515, - #195018); -#195400 = PRESENTATION_STYLE_ASSIGNMENT((#195401)); -#195401 = SURFACE_STYLE_USAGE(.BOTH.,#195402); -#195402 = SURFACE_SIDE_STYLE('',(#195403)); -#195403 = SURFACE_STYLE_FILL_AREA(#195404); -#195404 = FILL_AREA_STYLE('',(#195405)); -#195405 = FILL_AREA_STYLE_COLOUR('',#195083); -#195406 = OVER_RIDING_STYLED_ITEM('overriding color',(#195407),#97589, - #195018); -#195407 = PRESENTATION_STYLE_ASSIGNMENT((#195408)); -#195408 = SURFACE_STYLE_USAGE(.BOTH.,#195409); -#195409 = SURFACE_SIDE_STYLE('',(#195410)); -#195410 = SURFACE_STYLE_FILL_AREA(#195411); -#195411 = FILL_AREA_STYLE('',(#195412)); -#195412 = FILL_AREA_STYLE_COLOUR('',#195083); -#195413 = OVER_RIDING_STYLED_ITEM('overriding color',(#195414),#97664, - #195018); -#195414 = PRESENTATION_STYLE_ASSIGNMENT((#195415)); -#195415 = SURFACE_STYLE_USAGE(.BOTH.,#195416); -#195416 = SURFACE_SIDE_STYLE('',(#195417)); -#195417 = SURFACE_STYLE_FILL_AREA(#195418); -#195418 = FILL_AREA_STYLE('',(#195419)); -#195419 = FILL_AREA_STYLE_COLOUR('',#195083); -#195420 = OVER_RIDING_STYLED_ITEM('overriding color',(#195421),#97691, - #195018); -#195421 = PRESENTATION_STYLE_ASSIGNMENT((#195422)); -#195422 = SURFACE_STYLE_USAGE(.BOTH.,#195423); -#195423 = SURFACE_SIDE_STYLE('',(#195424)); -#195424 = SURFACE_STYLE_FILL_AREA(#195425); -#195425 = FILL_AREA_STYLE('',(#195426)); -#195426 = FILL_AREA_STYLE_COLOUR('',#195083); -#195427 = OVER_RIDING_STYLED_ITEM('overriding color',(#195428),#97746, - #195018); -#195428 = PRESENTATION_STYLE_ASSIGNMENT((#195429)); -#195429 = SURFACE_STYLE_USAGE(.BOTH.,#195430); -#195430 = SURFACE_SIDE_STYLE('',(#195431)); -#195431 = SURFACE_STYLE_FILL_AREA(#195432); -#195432 = FILL_AREA_STYLE('',(#195433)); -#195433 = FILL_AREA_STYLE_COLOUR('',#195083); -#195434 = OVER_RIDING_STYLED_ITEM('overriding color',(#195435),#97753, - #195018); -#195435 = PRESENTATION_STYLE_ASSIGNMENT((#195436)); -#195436 = SURFACE_STYLE_USAGE(.BOTH.,#195437); -#195437 = SURFACE_SIDE_STYLE('',(#195438)); -#195438 = SURFACE_STYLE_FILL_AREA(#195439); -#195439 = FILL_AREA_STYLE('',(#195440)); -#195440 = FILL_AREA_STYLE_COLOUR('',#195083); -#195441 = OVER_RIDING_STYLED_ITEM('overriding color',(#195442),#97760, - #195018); -#195442 = PRESENTATION_STYLE_ASSIGNMENT((#195443)); -#195443 = SURFACE_STYLE_USAGE(.BOTH.,#195444); -#195444 = SURFACE_SIDE_STYLE('',(#195445)); -#195445 = SURFACE_STYLE_FILL_AREA(#195446); -#195446 = FILL_AREA_STYLE('',(#195447)); -#195447 = FILL_AREA_STYLE_COLOUR('',#195083); -#195448 = OVER_RIDING_STYLED_ITEM('overriding color',(#195449),#97869, - #195018); -#195449 = PRESENTATION_STYLE_ASSIGNMENT((#195450)); -#195450 = SURFACE_STYLE_USAGE(.BOTH.,#195451); -#195451 = SURFACE_SIDE_STYLE('',(#195452)); -#195452 = SURFACE_STYLE_FILL_AREA(#195453); -#195453 = FILL_AREA_STYLE('',(#195454)); -#195454 = FILL_AREA_STYLE_COLOUR('',#195083); -#195455 = OVER_RIDING_STYLED_ITEM('overriding color',(#195456),#97973, - #195018); -#195456 = PRESENTATION_STYLE_ASSIGNMENT((#195457)); -#195457 = SURFACE_STYLE_USAGE(.BOTH.,#195458); -#195458 = SURFACE_SIDE_STYLE('',(#195459)); -#195459 = SURFACE_STYLE_FILL_AREA(#195460); -#195460 = FILL_AREA_STYLE('',(#195461)); -#195461 = FILL_AREA_STYLE_COLOUR('',#195083); -#195462 = OVER_RIDING_STYLED_ITEM('overriding color',(#195463),#98052, - #195018); -#195463 = PRESENTATION_STYLE_ASSIGNMENT((#195464)); -#195464 = SURFACE_STYLE_USAGE(.BOTH.,#195465); -#195465 = SURFACE_SIDE_STYLE('',(#195466)); -#195466 = SURFACE_STYLE_FILL_AREA(#195467); -#195467 = FILL_AREA_STYLE('',(#195468)); -#195468 = FILL_AREA_STYLE_COLOUR('',#195083); -#195469 = OVER_RIDING_STYLED_ITEM('overriding color',(#195470),#98131, - #195018); -#195470 = PRESENTATION_STYLE_ASSIGNMENT((#195471)); -#195471 = SURFACE_STYLE_USAGE(.BOTH.,#195472); -#195472 = SURFACE_SIDE_STYLE('',(#195473)); -#195473 = SURFACE_STYLE_FILL_AREA(#195474); -#195474 = FILL_AREA_STYLE('',(#195475)); -#195475 = FILL_AREA_STYLE_COLOUR('',#195083); -#195476 = OVER_RIDING_STYLED_ITEM('overriding color',(#195477),#98206, - #195018); -#195477 = PRESENTATION_STYLE_ASSIGNMENT((#195478)); -#195478 = SURFACE_STYLE_USAGE(.BOTH.,#195479); -#195479 = SURFACE_SIDE_STYLE('',(#195480)); -#195480 = SURFACE_STYLE_FILL_AREA(#195481); -#195481 = FILL_AREA_STYLE('',(#195482)); -#195482 = FILL_AREA_STYLE_COLOUR('',#195083); -#195483 = OVER_RIDING_STYLED_ITEM('overriding color',(#195484),#98281, - #195018); -#195484 = PRESENTATION_STYLE_ASSIGNMENT((#195485)); -#195485 = SURFACE_STYLE_USAGE(.BOTH.,#195486); -#195486 = SURFACE_SIDE_STYLE('',(#195487)); -#195487 = SURFACE_STYLE_FILL_AREA(#195488); -#195488 = FILL_AREA_STYLE('',(#195489)); -#195489 = FILL_AREA_STYLE_COLOUR('',#195083); -#195490 = OVER_RIDING_STYLED_ITEM('overriding color',(#195491),#98355, - #195018); -#195491 = PRESENTATION_STYLE_ASSIGNMENT((#195492)); -#195492 = SURFACE_STYLE_USAGE(.BOTH.,#195493); -#195493 = SURFACE_SIDE_STYLE('',(#195494)); -#195494 = SURFACE_STYLE_FILL_AREA(#195495); -#195495 = FILL_AREA_STYLE('',(#195496)); -#195496 = FILL_AREA_STYLE_COLOUR('',#195083); -#195497 = OVER_RIDING_STYLED_ITEM('overriding color',(#195498),#98429, - #195018); -#195498 = PRESENTATION_STYLE_ASSIGNMENT((#195499)); -#195499 = SURFACE_STYLE_USAGE(.BOTH.,#195500); -#195500 = SURFACE_SIDE_STYLE('',(#195501)); -#195501 = SURFACE_STYLE_FILL_AREA(#195502); -#195502 = FILL_AREA_STYLE('',(#195503)); -#195503 = FILL_AREA_STYLE_COLOUR('',#195083); -#195504 = OVER_RIDING_STYLED_ITEM('overriding color',(#195505),#98504, - #195018); -#195505 = PRESENTATION_STYLE_ASSIGNMENT((#195506)); -#195506 = SURFACE_STYLE_USAGE(.BOTH.,#195507); -#195507 = SURFACE_SIDE_STYLE('',(#195508)); -#195508 = SURFACE_STYLE_FILL_AREA(#195509); -#195509 = FILL_AREA_STYLE('',(#195510)); -#195510 = FILL_AREA_STYLE_COLOUR('',#195083); -#195511 = OVER_RIDING_STYLED_ITEM('overriding color',(#195512),#98531, - #195018); -#195512 = PRESENTATION_STYLE_ASSIGNMENT((#195513)); -#195513 = SURFACE_STYLE_USAGE(.BOTH.,#195514); -#195514 = SURFACE_SIDE_STYLE('',(#195515)); -#195515 = SURFACE_STYLE_FILL_AREA(#195516); -#195516 = FILL_AREA_STYLE('',(#195517)); -#195517 = FILL_AREA_STYLE_COLOUR('',#195083); -#195518 = OVER_RIDING_STYLED_ITEM('overriding color',(#195519),#98586, - #195018); -#195519 = PRESENTATION_STYLE_ASSIGNMENT((#195520)); -#195520 = SURFACE_STYLE_USAGE(.BOTH.,#195521); -#195521 = SURFACE_SIDE_STYLE('',(#195522)); -#195522 = SURFACE_STYLE_FILL_AREA(#195523); -#195523 = FILL_AREA_STYLE('',(#195524)); -#195524 = FILL_AREA_STYLE_COLOUR('',#195083); -#195525 = OVER_RIDING_STYLED_ITEM('overriding color',(#195526),#98593, - #195018); -#195526 = PRESENTATION_STYLE_ASSIGNMENT((#195527)); -#195527 = SURFACE_STYLE_USAGE(.BOTH.,#195528); -#195528 = SURFACE_SIDE_STYLE('',(#195529)); -#195529 = SURFACE_STYLE_FILL_AREA(#195530); -#195530 = FILL_AREA_STYLE('',(#195531)); -#195531 = FILL_AREA_STYLE_COLOUR('',#195083); -#195532 = OVER_RIDING_STYLED_ITEM('overriding color',(#195533),#98600, - #195018); -#195533 = PRESENTATION_STYLE_ASSIGNMENT((#195534)); -#195534 = SURFACE_STYLE_USAGE(.BOTH.,#195535); -#195535 = SURFACE_SIDE_STYLE('',(#195536)); -#195536 = SURFACE_STYLE_FILL_AREA(#195537); -#195537 = FILL_AREA_STYLE('',(#195538)); -#195538 = FILL_AREA_STYLE_COLOUR('',#195083); -#195539 = OVER_RIDING_STYLED_ITEM('overriding color',(#195540),#98709, - #195018); -#195540 = PRESENTATION_STYLE_ASSIGNMENT((#195541)); -#195541 = SURFACE_STYLE_USAGE(.BOTH.,#195542); -#195542 = SURFACE_SIDE_STYLE('',(#195543)); -#195543 = SURFACE_STYLE_FILL_AREA(#195544); -#195544 = FILL_AREA_STYLE('',(#195545)); -#195545 = FILL_AREA_STYLE_COLOUR('',#195083); -#195546 = OVER_RIDING_STYLED_ITEM('overriding color',(#195547),#98813, - #195018); -#195547 = PRESENTATION_STYLE_ASSIGNMENT((#195548)); -#195548 = SURFACE_STYLE_USAGE(.BOTH.,#195549); -#195549 = SURFACE_SIDE_STYLE('',(#195550)); -#195550 = SURFACE_STYLE_FILL_AREA(#195551); -#195551 = FILL_AREA_STYLE('',(#195552)); -#195552 = FILL_AREA_STYLE_COLOUR('',#195083); -#195553 = OVER_RIDING_STYLED_ITEM('overriding color',(#195554),#98892, - #195018); -#195554 = PRESENTATION_STYLE_ASSIGNMENT((#195555)); -#195555 = SURFACE_STYLE_USAGE(.BOTH.,#195556); -#195556 = SURFACE_SIDE_STYLE('',(#195557)); -#195557 = SURFACE_STYLE_FILL_AREA(#195558); -#195558 = FILL_AREA_STYLE('',(#195559)); -#195559 = FILL_AREA_STYLE_COLOUR('',#195083); -#195560 = OVER_RIDING_STYLED_ITEM('overriding color',(#195561),#98971, - #195018); -#195561 = PRESENTATION_STYLE_ASSIGNMENT((#195562)); -#195562 = SURFACE_STYLE_USAGE(.BOTH.,#195563); -#195563 = SURFACE_SIDE_STYLE('',(#195564)); -#195564 = SURFACE_STYLE_FILL_AREA(#195565); -#195565 = FILL_AREA_STYLE('',(#195566)); -#195566 = FILL_AREA_STYLE_COLOUR('',#195083); -#195567 = OVER_RIDING_STYLED_ITEM('overriding color',(#195568),#99046, - #195018); -#195568 = PRESENTATION_STYLE_ASSIGNMENT((#195569)); -#195569 = SURFACE_STYLE_USAGE(.BOTH.,#195570); -#195570 = SURFACE_SIDE_STYLE('',(#195571)); -#195571 = SURFACE_STYLE_FILL_AREA(#195572); -#195572 = FILL_AREA_STYLE('',(#195573)); -#195573 = FILL_AREA_STYLE_COLOUR('',#195083); -#195574 = OVER_RIDING_STYLED_ITEM('overriding color',(#195575),#99121, - #195018); -#195575 = PRESENTATION_STYLE_ASSIGNMENT((#195576)); -#195576 = SURFACE_STYLE_USAGE(.BOTH.,#195577); -#195577 = SURFACE_SIDE_STYLE('',(#195578)); -#195578 = SURFACE_STYLE_FILL_AREA(#195579); -#195579 = FILL_AREA_STYLE('',(#195580)); -#195580 = FILL_AREA_STYLE_COLOUR('',#195083); -#195581 = OVER_RIDING_STYLED_ITEM('overriding color',(#195582),#99195, - #195018); -#195582 = PRESENTATION_STYLE_ASSIGNMENT((#195583)); -#195583 = SURFACE_STYLE_USAGE(.BOTH.,#195584); -#195584 = SURFACE_SIDE_STYLE('',(#195585)); -#195585 = SURFACE_STYLE_FILL_AREA(#195586); -#195586 = FILL_AREA_STYLE('',(#195587)); -#195587 = FILL_AREA_STYLE_COLOUR('',#195083); -#195588 = OVER_RIDING_STYLED_ITEM('overriding color',(#195589),#99269, - #195018); -#195589 = PRESENTATION_STYLE_ASSIGNMENT((#195590)); -#195590 = SURFACE_STYLE_USAGE(.BOTH.,#195591); -#195591 = SURFACE_SIDE_STYLE('',(#195592)); -#195592 = SURFACE_STYLE_FILL_AREA(#195593); -#195593 = FILL_AREA_STYLE('',(#195594)); -#195594 = FILL_AREA_STYLE_COLOUR('',#195083); -#195595 = OVER_RIDING_STYLED_ITEM('overriding color',(#195596),#99344, - #195018); -#195596 = PRESENTATION_STYLE_ASSIGNMENT((#195597)); -#195597 = SURFACE_STYLE_USAGE(.BOTH.,#195598); -#195598 = SURFACE_SIDE_STYLE('',(#195599)); -#195599 = SURFACE_STYLE_FILL_AREA(#195600); -#195600 = FILL_AREA_STYLE('',(#195601)); -#195601 = FILL_AREA_STYLE_COLOUR('',#195083); -#195602 = OVER_RIDING_STYLED_ITEM('overriding color',(#195603),#99371, - #195018); -#195603 = PRESENTATION_STYLE_ASSIGNMENT((#195604)); -#195604 = SURFACE_STYLE_USAGE(.BOTH.,#195605); -#195605 = SURFACE_SIDE_STYLE('',(#195606)); -#195606 = SURFACE_STYLE_FILL_AREA(#195607); -#195607 = FILL_AREA_STYLE('',(#195608)); -#195608 = FILL_AREA_STYLE_COLOUR('',#195083); -#195609 = OVER_RIDING_STYLED_ITEM('overriding color',(#195610),#99426, - #195018); -#195610 = PRESENTATION_STYLE_ASSIGNMENT((#195611)); -#195611 = SURFACE_STYLE_USAGE(.BOTH.,#195612); -#195612 = SURFACE_SIDE_STYLE('',(#195613)); -#195613 = SURFACE_STYLE_FILL_AREA(#195614); -#195614 = FILL_AREA_STYLE('',(#195615)); -#195615 = FILL_AREA_STYLE_COLOUR('',#195083); -#195616 = OVER_RIDING_STYLED_ITEM('overriding color',(#195617),#99433, - #195018); -#195617 = PRESENTATION_STYLE_ASSIGNMENT((#195618)); -#195618 = SURFACE_STYLE_USAGE(.BOTH.,#195619); -#195619 = SURFACE_SIDE_STYLE('',(#195620)); -#195620 = SURFACE_STYLE_FILL_AREA(#195621); -#195621 = FILL_AREA_STYLE('',(#195622)); -#195622 = FILL_AREA_STYLE_COLOUR('',#195083); -#195623 = OVER_RIDING_STYLED_ITEM('overriding color',(#195624),#99440, - #195018); -#195624 = PRESENTATION_STYLE_ASSIGNMENT((#195625)); -#195625 = SURFACE_STYLE_USAGE(.BOTH.,#195626); -#195626 = SURFACE_SIDE_STYLE('',(#195627)); -#195627 = SURFACE_STYLE_FILL_AREA(#195628); -#195628 = FILL_AREA_STYLE('',(#195629)); -#195629 = FILL_AREA_STYLE_COLOUR('',#195083); -#195630 = OVER_RIDING_STYLED_ITEM('overriding color',(#195631),#99549, - #195018); -#195631 = PRESENTATION_STYLE_ASSIGNMENT((#195632)); -#195632 = SURFACE_STYLE_USAGE(.BOTH.,#195633); -#195633 = SURFACE_SIDE_STYLE('',(#195634)); -#195634 = SURFACE_STYLE_FILL_AREA(#195635); -#195635 = FILL_AREA_STYLE('',(#195636)); -#195636 = FILL_AREA_STYLE_COLOUR('',#195083); -#195637 = OVER_RIDING_STYLED_ITEM('overriding color',(#195638),#99653, - #195018); -#195638 = PRESENTATION_STYLE_ASSIGNMENT((#195639)); -#195639 = SURFACE_STYLE_USAGE(.BOTH.,#195640); -#195640 = SURFACE_SIDE_STYLE('',(#195641)); -#195641 = SURFACE_STYLE_FILL_AREA(#195642); -#195642 = FILL_AREA_STYLE('',(#195643)); -#195643 = FILL_AREA_STYLE_COLOUR('',#195083); -#195644 = OVER_RIDING_STYLED_ITEM('overriding color',(#195645),#99732, - #195018); -#195645 = PRESENTATION_STYLE_ASSIGNMENT((#195646)); -#195646 = SURFACE_STYLE_USAGE(.BOTH.,#195647); -#195647 = SURFACE_SIDE_STYLE('',(#195648)); -#195648 = SURFACE_STYLE_FILL_AREA(#195649); -#195649 = FILL_AREA_STYLE('',(#195650)); -#195650 = FILL_AREA_STYLE_COLOUR('',#195083); -#195651 = OVER_RIDING_STYLED_ITEM('overriding color',(#195652),#99811, - #195018); -#195652 = PRESENTATION_STYLE_ASSIGNMENT((#195653)); -#195653 = SURFACE_STYLE_USAGE(.BOTH.,#195654); -#195654 = SURFACE_SIDE_STYLE('',(#195655)); -#195655 = SURFACE_STYLE_FILL_AREA(#195656); -#195656 = FILL_AREA_STYLE('',(#195657)); -#195657 = FILL_AREA_STYLE_COLOUR('',#195083); -#195658 = OVER_RIDING_STYLED_ITEM('overriding color',(#195659),#99886, - #195018); -#195659 = PRESENTATION_STYLE_ASSIGNMENT((#195660)); -#195660 = SURFACE_STYLE_USAGE(.BOTH.,#195661); -#195661 = SURFACE_SIDE_STYLE('',(#195662)); -#195662 = SURFACE_STYLE_FILL_AREA(#195663); -#195663 = FILL_AREA_STYLE('',(#195664)); -#195664 = FILL_AREA_STYLE_COLOUR('',#195083); -#195665 = OVER_RIDING_STYLED_ITEM('overriding color',(#195666),#99961, - #195018); -#195666 = PRESENTATION_STYLE_ASSIGNMENT((#195667)); -#195667 = SURFACE_STYLE_USAGE(.BOTH.,#195668); -#195668 = SURFACE_SIDE_STYLE('',(#195669)); -#195669 = SURFACE_STYLE_FILL_AREA(#195670); -#195670 = FILL_AREA_STYLE('',(#195671)); -#195671 = FILL_AREA_STYLE_COLOUR('',#195083); -#195672 = OVER_RIDING_STYLED_ITEM('overriding color',(#195673),#100035, - #195018); -#195673 = PRESENTATION_STYLE_ASSIGNMENT((#195674)); -#195674 = SURFACE_STYLE_USAGE(.BOTH.,#195675); -#195675 = SURFACE_SIDE_STYLE('',(#195676)); -#195676 = SURFACE_STYLE_FILL_AREA(#195677); -#195677 = FILL_AREA_STYLE('',(#195678)); -#195678 = FILL_AREA_STYLE_COLOUR('',#195083); -#195679 = OVER_RIDING_STYLED_ITEM('overriding color',(#195680),#100109, - #195018); -#195680 = PRESENTATION_STYLE_ASSIGNMENT((#195681)); -#195681 = SURFACE_STYLE_USAGE(.BOTH.,#195682); -#195682 = SURFACE_SIDE_STYLE('',(#195683)); -#195683 = SURFACE_STYLE_FILL_AREA(#195684); -#195684 = FILL_AREA_STYLE('',(#195685)); -#195685 = FILL_AREA_STYLE_COLOUR('',#195083); -#195686 = OVER_RIDING_STYLED_ITEM('overriding color',(#195687),#100184, - #195018); -#195687 = PRESENTATION_STYLE_ASSIGNMENT((#195688)); -#195688 = SURFACE_STYLE_USAGE(.BOTH.,#195689); -#195689 = SURFACE_SIDE_STYLE('',(#195690)); -#195690 = SURFACE_STYLE_FILL_AREA(#195691); -#195691 = FILL_AREA_STYLE('',(#195692)); -#195692 = FILL_AREA_STYLE_COLOUR('',#195083); -#195693 = OVER_RIDING_STYLED_ITEM('overriding color',(#195694),#100211, - #195018); -#195694 = PRESENTATION_STYLE_ASSIGNMENT((#195695)); -#195695 = SURFACE_STYLE_USAGE(.BOTH.,#195696); -#195696 = SURFACE_SIDE_STYLE('',(#195697)); -#195697 = SURFACE_STYLE_FILL_AREA(#195698); -#195698 = FILL_AREA_STYLE('',(#195699)); -#195699 = FILL_AREA_STYLE_COLOUR('',#195083); -#195700 = OVER_RIDING_STYLED_ITEM('overriding color',(#195701),#100266, - #195018); -#195701 = PRESENTATION_STYLE_ASSIGNMENT((#195702)); -#195702 = SURFACE_STYLE_USAGE(.BOTH.,#195703); -#195703 = SURFACE_SIDE_STYLE('',(#195704)); -#195704 = SURFACE_STYLE_FILL_AREA(#195705); -#195705 = FILL_AREA_STYLE('',(#195706)); -#195706 = FILL_AREA_STYLE_COLOUR('',#195083); -#195707 = OVER_RIDING_STYLED_ITEM('overriding color',(#195708),#100273, - #195018); -#195708 = PRESENTATION_STYLE_ASSIGNMENT((#195709)); -#195709 = SURFACE_STYLE_USAGE(.BOTH.,#195710); -#195710 = SURFACE_SIDE_STYLE('',(#195711)); -#195711 = SURFACE_STYLE_FILL_AREA(#195712); -#195712 = FILL_AREA_STYLE('',(#195713)); -#195713 = FILL_AREA_STYLE_COLOUR('',#195083); -#195714 = OVER_RIDING_STYLED_ITEM('overriding color',(#195715),#100280, - #195018); -#195715 = PRESENTATION_STYLE_ASSIGNMENT((#195716)); -#195716 = SURFACE_STYLE_USAGE(.BOTH.,#195717); -#195717 = SURFACE_SIDE_STYLE('',(#195718)); -#195718 = SURFACE_STYLE_FILL_AREA(#195719); -#195719 = FILL_AREA_STYLE('',(#195720)); -#195720 = FILL_AREA_STYLE_COLOUR('',#195083); -#195721 = OVER_RIDING_STYLED_ITEM('overriding color',(#195722),#100389, - #195018); -#195722 = PRESENTATION_STYLE_ASSIGNMENT((#195723)); -#195723 = SURFACE_STYLE_USAGE(.BOTH.,#195724); -#195724 = SURFACE_SIDE_STYLE('',(#195725)); -#195725 = SURFACE_STYLE_FILL_AREA(#195726); -#195726 = FILL_AREA_STYLE('',(#195727)); -#195727 = FILL_AREA_STYLE_COLOUR('',#195083); -#195728 = OVER_RIDING_STYLED_ITEM('overriding color',(#195729),#100493, - #195018); -#195729 = PRESENTATION_STYLE_ASSIGNMENT((#195730)); -#195730 = SURFACE_STYLE_USAGE(.BOTH.,#195731); -#195731 = SURFACE_SIDE_STYLE('',(#195732)); -#195732 = SURFACE_STYLE_FILL_AREA(#195733); -#195733 = FILL_AREA_STYLE('',(#195734)); -#195734 = FILL_AREA_STYLE_COLOUR('',#195083); -#195735 = OVER_RIDING_STYLED_ITEM('overriding color',(#195736),#100572, - #195018); -#195736 = PRESENTATION_STYLE_ASSIGNMENT((#195737)); -#195737 = SURFACE_STYLE_USAGE(.BOTH.,#195738); -#195738 = SURFACE_SIDE_STYLE('',(#195739)); -#195739 = SURFACE_STYLE_FILL_AREA(#195740); -#195740 = FILL_AREA_STYLE('',(#195741)); -#195741 = FILL_AREA_STYLE_COLOUR('',#195083); -#195742 = OVER_RIDING_STYLED_ITEM('overriding color',(#195743),#100651, - #195018); -#195743 = PRESENTATION_STYLE_ASSIGNMENT((#195744)); -#195744 = SURFACE_STYLE_USAGE(.BOTH.,#195745); -#195745 = SURFACE_SIDE_STYLE('',(#195746)); -#195746 = SURFACE_STYLE_FILL_AREA(#195747); -#195747 = FILL_AREA_STYLE('',(#195748)); -#195748 = FILL_AREA_STYLE_COLOUR('',#195083); -#195749 = OVER_RIDING_STYLED_ITEM('overriding color',(#195750),#100726, - #195018); -#195750 = PRESENTATION_STYLE_ASSIGNMENT((#195751)); -#195751 = SURFACE_STYLE_USAGE(.BOTH.,#195752); -#195752 = SURFACE_SIDE_STYLE('',(#195753)); -#195753 = SURFACE_STYLE_FILL_AREA(#195754); -#195754 = FILL_AREA_STYLE('',(#195755)); -#195755 = FILL_AREA_STYLE_COLOUR('',#195083); -#195756 = OVER_RIDING_STYLED_ITEM('overriding color',(#195757),#100801, - #195018); -#195757 = PRESENTATION_STYLE_ASSIGNMENT((#195758)); -#195758 = SURFACE_STYLE_USAGE(.BOTH.,#195759); -#195759 = SURFACE_SIDE_STYLE('',(#195760)); -#195760 = SURFACE_STYLE_FILL_AREA(#195761); -#195761 = FILL_AREA_STYLE('',(#195762)); -#195762 = FILL_AREA_STYLE_COLOUR('',#195083); -#195763 = OVER_RIDING_STYLED_ITEM('overriding color',(#195764),#100875, - #195018); -#195764 = PRESENTATION_STYLE_ASSIGNMENT((#195765)); -#195765 = SURFACE_STYLE_USAGE(.BOTH.,#195766); -#195766 = SURFACE_SIDE_STYLE('',(#195767)); -#195767 = SURFACE_STYLE_FILL_AREA(#195768); -#195768 = FILL_AREA_STYLE('',(#195769)); -#195769 = FILL_AREA_STYLE_COLOUR('',#195083); -#195770 = OVER_RIDING_STYLED_ITEM('overriding color',(#195771),#100949, - #195018); -#195771 = PRESENTATION_STYLE_ASSIGNMENT((#195772)); -#195772 = SURFACE_STYLE_USAGE(.BOTH.,#195773); -#195773 = SURFACE_SIDE_STYLE('',(#195774)); -#195774 = SURFACE_STYLE_FILL_AREA(#195775); -#195775 = FILL_AREA_STYLE('',(#195776)); -#195776 = FILL_AREA_STYLE_COLOUR('',#195083); -#195777 = OVER_RIDING_STYLED_ITEM('overriding color',(#195778),#101024, - #195018); -#195778 = PRESENTATION_STYLE_ASSIGNMENT((#195779)); -#195779 = SURFACE_STYLE_USAGE(.BOTH.,#195780); -#195780 = SURFACE_SIDE_STYLE('',(#195781)); -#195781 = SURFACE_STYLE_FILL_AREA(#195782); -#195782 = FILL_AREA_STYLE('',(#195783)); -#195783 = FILL_AREA_STYLE_COLOUR('',#195083); -#195784 = OVER_RIDING_STYLED_ITEM('overriding color',(#195785),#101051, - #195018); -#195785 = PRESENTATION_STYLE_ASSIGNMENT((#195786)); -#195786 = SURFACE_STYLE_USAGE(.BOTH.,#195787); -#195787 = SURFACE_SIDE_STYLE('',(#195788)); -#195788 = SURFACE_STYLE_FILL_AREA(#195789); -#195789 = FILL_AREA_STYLE('',(#195790)); -#195790 = FILL_AREA_STYLE_COLOUR('',#195083); -#195791 = OVER_RIDING_STYLED_ITEM('overriding color',(#195792),#101106, - #195018); -#195792 = PRESENTATION_STYLE_ASSIGNMENT((#195793)); -#195793 = SURFACE_STYLE_USAGE(.BOTH.,#195794); -#195794 = SURFACE_SIDE_STYLE('',(#195795)); -#195795 = SURFACE_STYLE_FILL_AREA(#195796); -#195796 = FILL_AREA_STYLE('',(#195797)); -#195797 = FILL_AREA_STYLE_COLOUR('',#195083); -#195798 = OVER_RIDING_STYLED_ITEM('overriding color',(#195799),#101113, - #195018); -#195799 = PRESENTATION_STYLE_ASSIGNMENT((#195800)); -#195800 = SURFACE_STYLE_USAGE(.BOTH.,#195801); -#195801 = SURFACE_SIDE_STYLE('',(#195802)); -#195802 = SURFACE_STYLE_FILL_AREA(#195803); -#195803 = FILL_AREA_STYLE('',(#195804)); -#195804 = FILL_AREA_STYLE_COLOUR('',#195083); -#195805 = OVER_RIDING_STYLED_ITEM('overriding color',(#195806),#101120, - #195018); -#195806 = PRESENTATION_STYLE_ASSIGNMENT((#195807)); -#195807 = SURFACE_STYLE_USAGE(.BOTH.,#195808); -#195808 = SURFACE_SIDE_STYLE('',(#195809)); -#195809 = SURFACE_STYLE_FILL_AREA(#195810); -#195810 = FILL_AREA_STYLE('',(#195811)); -#195811 = FILL_AREA_STYLE_COLOUR('',#195083); -#195812 = OVER_RIDING_STYLED_ITEM('overriding color',(#195813),#101229, - #195018); -#195813 = PRESENTATION_STYLE_ASSIGNMENT((#195814)); -#195814 = SURFACE_STYLE_USAGE(.BOTH.,#195815); -#195815 = SURFACE_SIDE_STYLE('',(#195816)); -#195816 = SURFACE_STYLE_FILL_AREA(#195817); -#195817 = FILL_AREA_STYLE('',(#195818)); -#195818 = FILL_AREA_STYLE_COLOUR('',#195083); -#195819 = OVER_RIDING_STYLED_ITEM('overriding color',(#195820),#101333, - #195018); -#195820 = PRESENTATION_STYLE_ASSIGNMENT((#195821)); -#195821 = SURFACE_STYLE_USAGE(.BOTH.,#195822); -#195822 = SURFACE_SIDE_STYLE('',(#195823)); -#195823 = SURFACE_STYLE_FILL_AREA(#195824); -#195824 = FILL_AREA_STYLE('',(#195825)); -#195825 = FILL_AREA_STYLE_COLOUR('',#195083); -#195826 = OVER_RIDING_STYLED_ITEM('overriding color',(#195827),#101412, - #195018); -#195827 = PRESENTATION_STYLE_ASSIGNMENT((#195828)); -#195828 = SURFACE_STYLE_USAGE(.BOTH.,#195829); -#195829 = SURFACE_SIDE_STYLE('',(#195830)); -#195830 = SURFACE_STYLE_FILL_AREA(#195831); -#195831 = FILL_AREA_STYLE('',(#195832)); -#195832 = FILL_AREA_STYLE_COLOUR('',#195083); -#195833 = OVER_RIDING_STYLED_ITEM('overriding color',(#195834),#101491, - #195018); -#195834 = PRESENTATION_STYLE_ASSIGNMENT((#195835)); -#195835 = SURFACE_STYLE_USAGE(.BOTH.,#195836); -#195836 = SURFACE_SIDE_STYLE('',(#195837)); -#195837 = SURFACE_STYLE_FILL_AREA(#195838); -#195838 = FILL_AREA_STYLE('',(#195839)); -#195839 = FILL_AREA_STYLE_COLOUR('',#195083); -#195840 = OVER_RIDING_STYLED_ITEM('overriding color',(#195841),#101566, - #195018); -#195841 = PRESENTATION_STYLE_ASSIGNMENT((#195842)); -#195842 = SURFACE_STYLE_USAGE(.BOTH.,#195843); -#195843 = SURFACE_SIDE_STYLE('',(#195844)); -#195844 = SURFACE_STYLE_FILL_AREA(#195845); -#195845 = FILL_AREA_STYLE('',(#195846)); -#195846 = FILL_AREA_STYLE_COLOUR('',#195083); -#195847 = OVER_RIDING_STYLED_ITEM('overriding color',(#195848),#101641, - #195018); -#195848 = PRESENTATION_STYLE_ASSIGNMENT((#195849)); -#195849 = SURFACE_STYLE_USAGE(.BOTH.,#195850); -#195850 = SURFACE_SIDE_STYLE('',(#195851)); -#195851 = SURFACE_STYLE_FILL_AREA(#195852); -#195852 = FILL_AREA_STYLE('',(#195853)); -#195853 = FILL_AREA_STYLE_COLOUR('',#195083); -#195854 = OVER_RIDING_STYLED_ITEM('overriding color',(#195855),#101715, - #195018); -#195855 = PRESENTATION_STYLE_ASSIGNMENT((#195856)); -#195856 = SURFACE_STYLE_USAGE(.BOTH.,#195857); -#195857 = SURFACE_SIDE_STYLE('',(#195858)); -#195858 = SURFACE_STYLE_FILL_AREA(#195859); -#195859 = FILL_AREA_STYLE('',(#195860)); -#195860 = FILL_AREA_STYLE_COLOUR('',#195083); -#195861 = OVER_RIDING_STYLED_ITEM('overriding color',(#195862),#101789, - #195018); -#195862 = PRESENTATION_STYLE_ASSIGNMENT((#195863)); -#195863 = SURFACE_STYLE_USAGE(.BOTH.,#195864); -#195864 = SURFACE_SIDE_STYLE('',(#195865)); -#195865 = SURFACE_STYLE_FILL_AREA(#195866); -#195866 = FILL_AREA_STYLE('',(#195867)); -#195867 = FILL_AREA_STYLE_COLOUR('',#195083); -#195868 = OVER_RIDING_STYLED_ITEM('overriding color',(#195869),#101864, - #195018); -#195869 = PRESENTATION_STYLE_ASSIGNMENT((#195870)); -#195870 = SURFACE_STYLE_USAGE(.BOTH.,#195871); -#195871 = SURFACE_SIDE_STYLE('',(#195872)); -#195872 = SURFACE_STYLE_FILL_AREA(#195873); -#195873 = FILL_AREA_STYLE('',(#195874)); -#195874 = FILL_AREA_STYLE_COLOUR('',#195083); -#195875 = OVER_RIDING_STYLED_ITEM('overriding color',(#195876),#101891, - #195018); -#195876 = PRESENTATION_STYLE_ASSIGNMENT((#195877)); -#195877 = SURFACE_STYLE_USAGE(.BOTH.,#195878); -#195878 = SURFACE_SIDE_STYLE('',(#195879)); -#195879 = SURFACE_STYLE_FILL_AREA(#195880); -#195880 = FILL_AREA_STYLE('',(#195881)); -#195881 = FILL_AREA_STYLE_COLOUR('',#195083); -#195882 = OVER_RIDING_STYLED_ITEM('overriding color',(#195883),#101946, - #195018); -#195883 = PRESENTATION_STYLE_ASSIGNMENT((#195884)); -#195884 = SURFACE_STYLE_USAGE(.BOTH.,#195885); -#195885 = SURFACE_SIDE_STYLE('',(#195886)); -#195886 = SURFACE_STYLE_FILL_AREA(#195887); -#195887 = FILL_AREA_STYLE('',(#195888)); -#195888 = FILL_AREA_STYLE_COLOUR('',#195083); -#195889 = OVER_RIDING_STYLED_ITEM('overriding color',(#195890),#101953, - #195018); -#195890 = PRESENTATION_STYLE_ASSIGNMENT((#195891)); -#195891 = SURFACE_STYLE_USAGE(.BOTH.,#195892); -#195892 = SURFACE_SIDE_STYLE('',(#195893)); -#195893 = SURFACE_STYLE_FILL_AREA(#195894); -#195894 = FILL_AREA_STYLE('',(#195895)); -#195895 = FILL_AREA_STYLE_COLOUR('',#195083); -#195896 = OVER_RIDING_STYLED_ITEM('overriding color',(#195897),#101960, - #195018); -#195897 = PRESENTATION_STYLE_ASSIGNMENT((#195898)); -#195898 = SURFACE_STYLE_USAGE(.BOTH.,#195899); -#195899 = SURFACE_SIDE_STYLE('',(#195900)); -#195900 = SURFACE_STYLE_FILL_AREA(#195901); -#195901 = FILL_AREA_STYLE('',(#195902)); -#195902 = FILL_AREA_STYLE_COLOUR('',#195083); -#195903 = OVER_RIDING_STYLED_ITEM('overriding color',(#195904),#102069, - #195018); -#195904 = PRESENTATION_STYLE_ASSIGNMENT((#195905)); -#195905 = SURFACE_STYLE_USAGE(.BOTH.,#195906); -#195906 = SURFACE_SIDE_STYLE('',(#195907)); -#195907 = SURFACE_STYLE_FILL_AREA(#195908); -#195908 = FILL_AREA_STYLE('',(#195909)); -#195909 = FILL_AREA_STYLE_COLOUR('',#195083); -#195910 = OVER_RIDING_STYLED_ITEM('overriding color',(#195911),#102173, - #195018); -#195911 = PRESENTATION_STYLE_ASSIGNMENT((#195912)); -#195912 = SURFACE_STYLE_USAGE(.BOTH.,#195913); -#195913 = SURFACE_SIDE_STYLE('',(#195914)); -#195914 = SURFACE_STYLE_FILL_AREA(#195915); -#195915 = FILL_AREA_STYLE('',(#195916)); -#195916 = FILL_AREA_STYLE_COLOUR('',#195083); -#195917 = OVER_RIDING_STYLED_ITEM('overriding color',(#195918),#102252, - #195018); -#195918 = PRESENTATION_STYLE_ASSIGNMENT((#195919)); -#195919 = SURFACE_STYLE_USAGE(.BOTH.,#195920); -#195920 = SURFACE_SIDE_STYLE('',(#195921)); -#195921 = SURFACE_STYLE_FILL_AREA(#195922); -#195922 = FILL_AREA_STYLE('',(#195923)); -#195923 = FILL_AREA_STYLE_COLOUR('',#195083); -#195924 = OVER_RIDING_STYLED_ITEM('overriding color',(#195925),#102331, - #195018); -#195925 = PRESENTATION_STYLE_ASSIGNMENT((#195926)); -#195926 = SURFACE_STYLE_USAGE(.BOTH.,#195927); -#195927 = SURFACE_SIDE_STYLE('',(#195928)); -#195928 = SURFACE_STYLE_FILL_AREA(#195929); -#195929 = FILL_AREA_STYLE('',(#195930)); -#195930 = FILL_AREA_STYLE_COLOUR('',#195083); -#195931 = OVER_RIDING_STYLED_ITEM('overriding color',(#195932),#102406, - #195018); -#195932 = PRESENTATION_STYLE_ASSIGNMENT((#195933)); -#195933 = SURFACE_STYLE_USAGE(.BOTH.,#195934); -#195934 = SURFACE_SIDE_STYLE('',(#195935)); -#195935 = SURFACE_STYLE_FILL_AREA(#195936); -#195936 = FILL_AREA_STYLE('',(#195937)); -#195937 = FILL_AREA_STYLE_COLOUR('',#195083); -#195938 = OVER_RIDING_STYLED_ITEM('overriding color',(#195939),#102481, - #195018); -#195939 = PRESENTATION_STYLE_ASSIGNMENT((#195940)); -#195940 = SURFACE_STYLE_USAGE(.BOTH.,#195941); -#195941 = SURFACE_SIDE_STYLE('',(#195942)); -#195942 = SURFACE_STYLE_FILL_AREA(#195943); -#195943 = FILL_AREA_STYLE('',(#195944)); -#195944 = FILL_AREA_STYLE_COLOUR('',#195083); -#195945 = OVER_RIDING_STYLED_ITEM('overriding color',(#195946),#102555, - #195018); -#195946 = PRESENTATION_STYLE_ASSIGNMENT((#195947)); -#195947 = SURFACE_STYLE_USAGE(.BOTH.,#195948); -#195948 = SURFACE_SIDE_STYLE('',(#195949)); -#195949 = SURFACE_STYLE_FILL_AREA(#195950); -#195950 = FILL_AREA_STYLE('',(#195951)); -#195951 = FILL_AREA_STYLE_COLOUR('',#195083); -#195952 = OVER_RIDING_STYLED_ITEM('overriding color',(#195953),#102629, - #195018); -#195953 = PRESENTATION_STYLE_ASSIGNMENT((#195954)); -#195954 = SURFACE_STYLE_USAGE(.BOTH.,#195955); -#195955 = SURFACE_SIDE_STYLE('',(#195956)); -#195956 = SURFACE_STYLE_FILL_AREA(#195957); -#195957 = FILL_AREA_STYLE('',(#195958)); -#195958 = FILL_AREA_STYLE_COLOUR('',#195083); -#195959 = OVER_RIDING_STYLED_ITEM('overriding color',(#195960),#102704, - #195018); -#195960 = PRESENTATION_STYLE_ASSIGNMENT((#195961)); -#195961 = SURFACE_STYLE_USAGE(.BOTH.,#195962); -#195962 = SURFACE_SIDE_STYLE('',(#195963)); -#195963 = SURFACE_STYLE_FILL_AREA(#195964); -#195964 = FILL_AREA_STYLE('',(#195965)); -#195965 = FILL_AREA_STYLE_COLOUR('',#195083); -#195966 = OVER_RIDING_STYLED_ITEM('overriding color',(#195967),#102731, - #195018); -#195967 = PRESENTATION_STYLE_ASSIGNMENT((#195968)); -#195968 = SURFACE_STYLE_USAGE(.BOTH.,#195969); -#195969 = SURFACE_SIDE_STYLE('',(#195970)); -#195970 = SURFACE_STYLE_FILL_AREA(#195971); -#195971 = FILL_AREA_STYLE('',(#195972)); -#195972 = FILL_AREA_STYLE_COLOUR('',#195083); -#195973 = OVER_RIDING_STYLED_ITEM('overriding color',(#195974),#102786, - #195018); -#195974 = PRESENTATION_STYLE_ASSIGNMENT((#195975)); -#195975 = SURFACE_STYLE_USAGE(.BOTH.,#195976); -#195976 = SURFACE_SIDE_STYLE('',(#195977)); -#195977 = SURFACE_STYLE_FILL_AREA(#195978); -#195978 = FILL_AREA_STYLE('',(#195979)); -#195979 = FILL_AREA_STYLE_COLOUR('',#195083); -#195980 = OVER_RIDING_STYLED_ITEM('overriding color',(#195981),#102793, - #195018); -#195981 = PRESENTATION_STYLE_ASSIGNMENT((#195982)); -#195982 = SURFACE_STYLE_USAGE(.BOTH.,#195983); -#195983 = SURFACE_SIDE_STYLE('',(#195984)); -#195984 = SURFACE_STYLE_FILL_AREA(#195985); -#195985 = FILL_AREA_STYLE('',(#195986)); -#195986 = FILL_AREA_STYLE_COLOUR('',#195083); -#195987 = OVER_RIDING_STYLED_ITEM('overriding color',(#195988),#102800, - #195018); -#195988 = PRESENTATION_STYLE_ASSIGNMENT((#195989)); -#195989 = SURFACE_STYLE_USAGE(.BOTH.,#195990); -#195990 = SURFACE_SIDE_STYLE('',(#195991)); -#195991 = SURFACE_STYLE_FILL_AREA(#195992); -#195992 = FILL_AREA_STYLE('',(#195993)); -#195993 = FILL_AREA_STYLE_COLOUR('',#195083); -#195994 = OVER_RIDING_STYLED_ITEM('overriding color',(#195995),#102909, - #195018); -#195995 = PRESENTATION_STYLE_ASSIGNMENT((#195996)); -#195996 = SURFACE_STYLE_USAGE(.BOTH.,#195997); -#195997 = SURFACE_SIDE_STYLE('',(#195998)); -#195998 = SURFACE_STYLE_FILL_AREA(#195999); -#195999 = FILL_AREA_STYLE('',(#196000)); -#196000 = FILL_AREA_STYLE_COLOUR('',#195083); -#196001 = OVER_RIDING_STYLED_ITEM('overriding color',(#196002),#103013, - #195018); -#196002 = PRESENTATION_STYLE_ASSIGNMENT((#196003)); -#196003 = SURFACE_STYLE_USAGE(.BOTH.,#196004); -#196004 = SURFACE_SIDE_STYLE('',(#196005)); -#196005 = SURFACE_STYLE_FILL_AREA(#196006); -#196006 = FILL_AREA_STYLE('',(#196007)); -#196007 = FILL_AREA_STYLE_COLOUR('',#195083); -#196008 = OVER_RIDING_STYLED_ITEM('overriding color',(#196009),#103092, - #195018); -#196009 = PRESENTATION_STYLE_ASSIGNMENT((#196010)); -#196010 = SURFACE_STYLE_USAGE(.BOTH.,#196011); -#196011 = SURFACE_SIDE_STYLE('',(#196012)); -#196012 = SURFACE_STYLE_FILL_AREA(#196013); -#196013 = FILL_AREA_STYLE('',(#196014)); -#196014 = FILL_AREA_STYLE_COLOUR('',#195083); -#196015 = OVER_RIDING_STYLED_ITEM('overriding color',(#196016),#103171, - #195018); -#196016 = PRESENTATION_STYLE_ASSIGNMENT((#196017)); -#196017 = SURFACE_STYLE_USAGE(.BOTH.,#196018); -#196018 = SURFACE_SIDE_STYLE('',(#196019)); -#196019 = SURFACE_STYLE_FILL_AREA(#196020); -#196020 = FILL_AREA_STYLE('',(#196021)); -#196021 = FILL_AREA_STYLE_COLOUR('',#195083); -#196022 = OVER_RIDING_STYLED_ITEM('overriding color',(#196023),#103246, - #195018); -#196023 = PRESENTATION_STYLE_ASSIGNMENT((#196024)); -#196024 = SURFACE_STYLE_USAGE(.BOTH.,#196025); -#196025 = SURFACE_SIDE_STYLE('',(#196026)); -#196026 = SURFACE_STYLE_FILL_AREA(#196027); -#196027 = FILL_AREA_STYLE('',(#196028)); -#196028 = FILL_AREA_STYLE_COLOUR('',#195083); -#196029 = OVER_RIDING_STYLED_ITEM('overriding color',(#196030),#103321, - #195018); -#196030 = PRESENTATION_STYLE_ASSIGNMENT((#196031)); -#196031 = SURFACE_STYLE_USAGE(.BOTH.,#196032); -#196032 = SURFACE_SIDE_STYLE('',(#196033)); -#196033 = SURFACE_STYLE_FILL_AREA(#196034); -#196034 = FILL_AREA_STYLE('',(#196035)); -#196035 = FILL_AREA_STYLE_COLOUR('',#195083); -#196036 = OVER_RIDING_STYLED_ITEM('overriding color',(#196037),#103395, - #195018); -#196037 = PRESENTATION_STYLE_ASSIGNMENT((#196038)); -#196038 = SURFACE_STYLE_USAGE(.BOTH.,#196039); -#196039 = SURFACE_SIDE_STYLE('',(#196040)); -#196040 = SURFACE_STYLE_FILL_AREA(#196041); -#196041 = FILL_AREA_STYLE('',(#196042)); -#196042 = FILL_AREA_STYLE_COLOUR('',#195083); -#196043 = OVER_RIDING_STYLED_ITEM('overriding color',(#196044),#103469, - #195018); -#196044 = PRESENTATION_STYLE_ASSIGNMENT((#196045)); -#196045 = SURFACE_STYLE_USAGE(.BOTH.,#196046); -#196046 = SURFACE_SIDE_STYLE('',(#196047)); -#196047 = SURFACE_STYLE_FILL_AREA(#196048); -#196048 = FILL_AREA_STYLE('',(#196049)); -#196049 = FILL_AREA_STYLE_COLOUR('',#195083); -#196050 = OVER_RIDING_STYLED_ITEM('overriding color',(#196051),#103544, - #195018); -#196051 = PRESENTATION_STYLE_ASSIGNMENT((#196052)); -#196052 = SURFACE_STYLE_USAGE(.BOTH.,#196053); -#196053 = SURFACE_SIDE_STYLE('',(#196054)); -#196054 = SURFACE_STYLE_FILL_AREA(#196055); -#196055 = FILL_AREA_STYLE('',(#196056)); -#196056 = FILL_AREA_STYLE_COLOUR('',#195083); -#196057 = OVER_RIDING_STYLED_ITEM('overriding color',(#196058),#103571, - #195018); -#196058 = PRESENTATION_STYLE_ASSIGNMENT((#196059)); -#196059 = SURFACE_STYLE_USAGE(.BOTH.,#196060); -#196060 = SURFACE_SIDE_STYLE('',(#196061)); -#196061 = SURFACE_STYLE_FILL_AREA(#196062); -#196062 = FILL_AREA_STYLE('',(#196063)); -#196063 = FILL_AREA_STYLE_COLOUR('',#195083); -#196064 = OVER_RIDING_STYLED_ITEM('overriding color',(#196065),#103626, - #195018); -#196065 = PRESENTATION_STYLE_ASSIGNMENT((#196066)); -#196066 = SURFACE_STYLE_USAGE(.BOTH.,#196067); -#196067 = SURFACE_SIDE_STYLE('',(#196068)); -#196068 = SURFACE_STYLE_FILL_AREA(#196069); -#196069 = FILL_AREA_STYLE('',(#196070)); -#196070 = FILL_AREA_STYLE_COLOUR('',#195083); -#196071 = OVER_RIDING_STYLED_ITEM('overriding color',(#196072),#103633, - #195018); -#196072 = PRESENTATION_STYLE_ASSIGNMENT((#196073)); -#196073 = SURFACE_STYLE_USAGE(.BOTH.,#196074); -#196074 = SURFACE_SIDE_STYLE('',(#196075)); -#196075 = SURFACE_STYLE_FILL_AREA(#196076); -#196076 = FILL_AREA_STYLE('',(#196077)); -#196077 = FILL_AREA_STYLE_COLOUR('',#195083); -#196078 = OVER_RIDING_STYLED_ITEM('overriding color',(#196079),#103640, - #195018); -#196079 = PRESENTATION_STYLE_ASSIGNMENT((#196080)); -#196080 = SURFACE_STYLE_USAGE(.BOTH.,#196081); -#196081 = SURFACE_SIDE_STYLE('',(#196082)); -#196082 = SURFACE_STYLE_FILL_AREA(#196083); -#196083 = FILL_AREA_STYLE('',(#196084)); -#196084 = FILL_AREA_STYLE_COLOUR('',#195083); -#196085 = OVER_RIDING_STYLED_ITEM('overriding color',(#196086),#103749, - #195018); -#196086 = PRESENTATION_STYLE_ASSIGNMENT((#196087)); -#196087 = SURFACE_STYLE_USAGE(.BOTH.,#196088); -#196088 = SURFACE_SIDE_STYLE('',(#196089)); -#196089 = SURFACE_STYLE_FILL_AREA(#196090); -#196090 = FILL_AREA_STYLE('',(#196091)); -#196091 = FILL_AREA_STYLE_COLOUR('',#195083); -#196092 = OVER_RIDING_STYLED_ITEM('overriding color',(#196093),#103853, - #195018); -#196093 = PRESENTATION_STYLE_ASSIGNMENT((#196094)); -#196094 = SURFACE_STYLE_USAGE(.BOTH.,#196095); -#196095 = SURFACE_SIDE_STYLE('',(#196096)); -#196096 = SURFACE_STYLE_FILL_AREA(#196097); -#196097 = FILL_AREA_STYLE('',(#196098)); -#196098 = FILL_AREA_STYLE_COLOUR('',#195083); -#196099 = OVER_RIDING_STYLED_ITEM('overriding color',(#196100),#103932, - #195018); -#196100 = PRESENTATION_STYLE_ASSIGNMENT((#196101)); -#196101 = SURFACE_STYLE_USAGE(.BOTH.,#196102); -#196102 = SURFACE_SIDE_STYLE('',(#196103)); -#196103 = SURFACE_STYLE_FILL_AREA(#196104); -#196104 = FILL_AREA_STYLE('',(#196105)); -#196105 = FILL_AREA_STYLE_COLOUR('',#195083); -#196106 = OVER_RIDING_STYLED_ITEM('overriding color',(#196107),#104011, - #195018); -#196107 = PRESENTATION_STYLE_ASSIGNMENT((#196108)); -#196108 = SURFACE_STYLE_USAGE(.BOTH.,#196109); -#196109 = SURFACE_SIDE_STYLE('',(#196110)); -#196110 = SURFACE_STYLE_FILL_AREA(#196111); -#196111 = FILL_AREA_STYLE('',(#196112)); -#196112 = FILL_AREA_STYLE_COLOUR('',#195083); -#196113 = OVER_RIDING_STYLED_ITEM('overriding color',(#196114),#104086, - #195018); -#196114 = PRESENTATION_STYLE_ASSIGNMENT((#196115)); -#196115 = SURFACE_STYLE_USAGE(.BOTH.,#196116); -#196116 = SURFACE_SIDE_STYLE('',(#196117)); -#196117 = SURFACE_STYLE_FILL_AREA(#196118); -#196118 = FILL_AREA_STYLE('',(#196119)); -#196119 = FILL_AREA_STYLE_COLOUR('',#195083); -#196120 = OVER_RIDING_STYLED_ITEM('overriding color',(#196121),#104161, - #195018); -#196121 = PRESENTATION_STYLE_ASSIGNMENT((#196122)); -#196122 = SURFACE_STYLE_USAGE(.BOTH.,#196123); -#196123 = SURFACE_SIDE_STYLE('',(#196124)); -#196124 = SURFACE_STYLE_FILL_AREA(#196125); -#196125 = FILL_AREA_STYLE('',(#196126)); -#196126 = FILL_AREA_STYLE_COLOUR('',#195083); -#196127 = OVER_RIDING_STYLED_ITEM('overriding color',(#196128),#104235, - #195018); -#196128 = PRESENTATION_STYLE_ASSIGNMENT((#196129)); -#196129 = SURFACE_STYLE_USAGE(.BOTH.,#196130); -#196130 = SURFACE_SIDE_STYLE('',(#196131)); -#196131 = SURFACE_STYLE_FILL_AREA(#196132); -#196132 = FILL_AREA_STYLE('',(#196133)); -#196133 = FILL_AREA_STYLE_COLOUR('',#195083); -#196134 = OVER_RIDING_STYLED_ITEM('overriding color',(#196135),#104309, - #195018); -#196135 = PRESENTATION_STYLE_ASSIGNMENT((#196136)); -#196136 = SURFACE_STYLE_USAGE(.BOTH.,#196137); -#196137 = SURFACE_SIDE_STYLE('',(#196138)); -#196138 = SURFACE_STYLE_FILL_AREA(#196139); -#196139 = FILL_AREA_STYLE('',(#196140)); -#196140 = FILL_AREA_STYLE_COLOUR('',#195083); -#196141 = OVER_RIDING_STYLED_ITEM('overriding color',(#196142),#104384, - #195018); -#196142 = PRESENTATION_STYLE_ASSIGNMENT((#196143)); -#196143 = SURFACE_STYLE_USAGE(.BOTH.,#196144); -#196144 = SURFACE_SIDE_STYLE('',(#196145)); -#196145 = SURFACE_STYLE_FILL_AREA(#196146); -#196146 = FILL_AREA_STYLE('',(#196147)); -#196147 = FILL_AREA_STYLE_COLOUR('',#195083); -#196148 = OVER_RIDING_STYLED_ITEM('overriding color',(#196149),#104411, - #195018); -#196149 = PRESENTATION_STYLE_ASSIGNMENT((#196150)); -#196150 = SURFACE_STYLE_USAGE(.BOTH.,#196151); -#196151 = SURFACE_SIDE_STYLE('',(#196152)); -#196152 = SURFACE_STYLE_FILL_AREA(#196153); -#196153 = FILL_AREA_STYLE('',(#196154)); -#196154 = FILL_AREA_STYLE_COLOUR('',#195083); -#196155 = OVER_RIDING_STYLED_ITEM('overriding color',(#196156),#104466, - #195018); -#196156 = PRESENTATION_STYLE_ASSIGNMENT((#196157)); -#196157 = SURFACE_STYLE_USAGE(.BOTH.,#196158); -#196158 = SURFACE_SIDE_STYLE('',(#196159)); -#196159 = SURFACE_STYLE_FILL_AREA(#196160); -#196160 = FILL_AREA_STYLE('',(#196161)); -#196161 = FILL_AREA_STYLE_COLOUR('',#195083); -#196162 = OVER_RIDING_STYLED_ITEM('overriding color',(#196163),#104473, - #195018); -#196163 = PRESENTATION_STYLE_ASSIGNMENT((#196164)); -#196164 = SURFACE_STYLE_USAGE(.BOTH.,#196165); -#196165 = SURFACE_SIDE_STYLE('',(#196166)); -#196166 = SURFACE_STYLE_FILL_AREA(#196167); -#196167 = FILL_AREA_STYLE('',(#196168)); -#196168 = FILL_AREA_STYLE_COLOUR('',#195083); -#196169 = OVER_RIDING_STYLED_ITEM('overriding color',(#196170),#104480, - #195018); -#196170 = PRESENTATION_STYLE_ASSIGNMENT((#196171)); -#196171 = SURFACE_STYLE_USAGE(.BOTH.,#196172); -#196172 = SURFACE_SIDE_STYLE('',(#196173)); -#196173 = SURFACE_STYLE_FILL_AREA(#196174); -#196174 = FILL_AREA_STYLE('',(#196175)); -#196175 = FILL_AREA_STYLE_COLOUR('',#195083); -#196176 = OVER_RIDING_STYLED_ITEM('overriding color',(#196177),#104589, - #195018); -#196177 = PRESENTATION_STYLE_ASSIGNMENT((#196178)); -#196178 = SURFACE_STYLE_USAGE(.BOTH.,#196179); -#196179 = SURFACE_SIDE_STYLE('',(#196180)); -#196180 = SURFACE_STYLE_FILL_AREA(#196181); -#196181 = FILL_AREA_STYLE('',(#196182)); -#196182 = FILL_AREA_STYLE_COLOUR('',#195083); -#196183 = OVER_RIDING_STYLED_ITEM('overriding color',(#196184),#104693, - #195018); -#196184 = PRESENTATION_STYLE_ASSIGNMENT((#196185)); -#196185 = SURFACE_STYLE_USAGE(.BOTH.,#196186); -#196186 = SURFACE_SIDE_STYLE('',(#196187)); -#196187 = SURFACE_STYLE_FILL_AREA(#196188); -#196188 = FILL_AREA_STYLE('',(#196189)); -#196189 = FILL_AREA_STYLE_COLOUR('',#195083); -#196190 = OVER_RIDING_STYLED_ITEM('overriding color',(#196191),#104772, - #195018); -#196191 = PRESENTATION_STYLE_ASSIGNMENT((#196192)); -#196192 = SURFACE_STYLE_USAGE(.BOTH.,#196193); -#196193 = SURFACE_SIDE_STYLE('',(#196194)); -#196194 = SURFACE_STYLE_FILL_AREA(#196195); -#196195 = FILL_AREA_STYLE('',(#196196)); -#196196 = FILL_AREA_STYLE_COLOUR('',#195083); -#196197 = OVER_RIDING_STYLED_ITEM('overriding color',(#196198),#104851, - #195018); -#196198 = PRESENTATION_STYLE_ASSIGNMENT((#196199)); -#196199 = SURFACE_STYLE_USAGE(.BOTH.,#196200); -#196200 = SURFACE_SIDE_STYLE('',(#196201)); -#196201 = SURFACE_STYLE_FILL_AREA(#196202); -#196202 = FILL_AREA_STYLE('',(#196203)); -#196203 = FILL_AREA_STYLE_COLOUR('',#195083); -#196204 = OVER_RIDING_STYLED_ITEM('overriding color',(#196205),#104926, - #195018); -#196205 = PRESENTATION_STYLE_ASSIGNMENT((#196206)); -#196206 = SURFACE_STYLE_USAGE(.BOTH.,#196207); -#196207 = SURFACE_SIDE_STYLE('',(#196208)); -#196208 = SURFACE_STYLE_FILL_AREA(#196209); -#196209 = FILL_AREA_STYLE('',(#196210)); -#196210 = FILL_AREA_STYLE_COLOUR('',#195083); -#196211 = OVER_RIDING_STYLED_ITEM('overriding color',(#196212),#105001, - #195018); -#196212 = PRESENTATION_STYLE_ASSIGNMENT((#196213)); -#196213 = SURFACE_STYLE_USAGE(.BOTH.,#196214); -#196214 = SURFACE_SIDE_STYLE('',(#196215)); -#196215 = SURFACE_STYLE_FILL_AREA(#196216); -#196216 = FILL_AREA_STYLE('',(#196217)); -#196217 = FILL_AREA_STYLE_COLOUR('',#195083); -#196218 = OVER_RIDING_STYLED_ITEM('overriding color',(#196219),#105075, - #195018); -#196219 = PRESENTATION_STYLE_ASSIGNMENT((#196220)); -#196220 = SURFACE_STYLE_USAGE(.BOTH.,#196221); -#196221 = SURFACE_SIDE_STYLE('',(#196222)); -#196222 = SURFACE_STYLE_FILL_AREA(#196223); -#196223 = FILL_AREA_STYLE('',(#196224)); -#196224 = FILL_AREA_STYLE_COLOUR('',#195083); -#196225 = OVER_RIDING_STYLED_ITEM('overriding color',(#196226),#105149, - #195018); -#196226 = PRESENTATION_STYLE_ASSIGNMENT((#196227)); -#196227 = SURFACE_STYLE_USAGE(.BOTH.,#196228); -#196228 = SURFACE_SIDE_STYLE('',(#196229)); -#196229 = SURFACE_STYLE_FILL_AREA(#196230); -#196230 = FILL_AREA_STYLE('',(#196231)); -#196231 = FILL_AREA_STYLE_COLOUR('',#195083); -#196232 = OVER_RIDING_STYLED_ITEM('overriding color',(#196233),#105224, - #195018); -#196233 = PRESENTATION_STYLE_ASSIGNMENT((#196234)); -#196234 = SURFACE_STYLE_USAGE(.BOTH.,#196235); -#196235 = SURFACE_SIDE_STYLE('',(#196236)); -#196236 = SURFACE_STYLE_FILL_AREA(#196237); -#196237 = FILL_AREA_STYLE('',(#196238)); -#196238 = FILL_AREA_STYLE_COLOUR('',#195083); -#196239 = OVER_RIDING_STYLED_ITEM('overriding color',(#196240),#105251, - #195018); -#196240 = PRESENTATION_STYLE_ASSIGNMENT((#196241)); -#196241 = SURFACE_STYLE_USAGE(.BOTH.,#196242); -#196242 = SURFACE_SIDE_STYLE('',(#196243)); -#196243 = SURFACE_STYLE_FILL_AREA(#196244); -#196244 = FILL_AREA_STYLE('',(#196245)); -#196245 = FILL_AREA_STYLE_COLOUR('',#195083); -#196246 = OVER_RIDING_STYLED_ITEM('overriding color',(#196247),#105306, - #195018); -#196247 = PRESENTATION_STYLE_ASSIGNMENT((#196248)); -#196248 = SURFACE_STYLE_USAGE(.BOTH.,#196249); -#196249 = SURFACE_SIDE_STYLE('',(#196250)); -#196250 = SURFACE_STYLE_FILL_AREA(#196251); -#196251 = FILL_AREA_STYLE('',(#196252)); -#196252 = FILL_AREA_STYLE_COLOUR('',#195083); -#196253 = OVER_RIDING_STYLED_ITEM('overriding color',(#196254),#105313, - #195018); -#196254 = PRESENTATION_STYLE_ASSIGNMENT((#196255)); -#196255 = SURFACE_STYLE_USAGE(.BOTH.,#196256); -#196256 = SURFACE_SIDE_STYLE('',(#196257)); -#196257 = SURFACE_STYLE_FILL_AREA(#196258); -#196258 = FILL_AREA_STYLE('',(#196259)); -#196259 = FILL_AREA_STYLE_COLOUR('',#195083); -#196260 = OVER_RIDING_STYLED_ITEM('overriding color',(#196261),#105320, - #195018); -#196261 = PRESENTATION_STYLE_ASSIGNMENT((#196262)); -#196262 = SURFACE_STYLE_USAGE(.BOTH.,#196263); -#196263 = SURFACE_SIDE_STYLE('',(#196264)); -#196264 = SURFACE_STYLE_FILL_AREA(#196265); -#196265 = FILL_AREA_STYLE('',(#196266)); -#196266 = FILL_AREA_STYLE_COLOUR('',#195083); -#196267 = OVER_RIDING_STYLED_ITEM('overriding color',(#196268),#105429, - #195018); -#196268 = PRESENTATION_STYLE_ASSIGNMENT((#196269)); -#196269 = SURFACE_STYLE_USAGE(.BOTH.,#196270); -#196270 = SURFACE_SIDE_STYLE('',(#196271)); -#196271 = SURFACE_STYLE_FILL_AREA(#196272); -#196272 = FILL_AREA_STYLE('',(#196273)); -#196273 = FILL_AREA_STYLE_COLOUR('',#195083); -#196274 = OVER_RIDING_STYLED_ITEM('overriding color',(#196275),#105533, - #195018); -#196275 = PRESENTATION_STYLE_ASSIGNMENT((#196276)); -#196276 = SURFACE_STYLE_USAGE(.BOTH.,#196277); -#196277 = SURFACE_SIDE_STYLE('',(#196278)); -#196278 = SURFACE_STYLE_FILL_AREA(#196279); -#196279 = FILL_AREA_STYLE('',(#196280)); -#196280 = FILL_AREA_STYLE_COLOUR('',#195083); -#196281 = OVER_RIDING_STYLED_ITEM('overriding color',(#196282),#105612, - #195018); -#196282 = PRESENTATION_STYLE_ASSIGNMENT((#196283)); -#196283 = SURFACE_STYLE_USAGE(.BOTH.,#196284); -#196284 = SURFACE_SIDE_STYLE('',(#196285)); -#196285 = SURFACE_STYLE_FILL_AREA(#196286); -#196286 = FILL_AREA_STYLE('',(#196287)); -#196287 = FILL_AREA_STYLE_COLOUR('',#195083); -#196288 = OVER_RIDING_STYLED_ITEM('overriding color',(#196289),#105691, - #195018); -#196289 = PRESENTATION_STYLE_ASSIGNMENT((#196290)); -#196290 = SURFACE_STYLE_USAGE(.BOTH.,#196291); -#196291 = SURFACE_SIDE_STYLE('',(#196292)); -#196292 = SURFACE_STYLE_FILL_AREA(#196293); -#196293 = FILL_AREA_STYLE('',(#196294)); -#196294 = FILL_AREA_STYLE_COLOUR('',#195083); -#196295 = OVER_RIDING_STYLED_ITEM('overriding color',(#196296),#105766, - #195018); -#196296 = PRESENTATION_STYLE_ASSIGNMENT((#196297)); -#196297 = SURFACE_STYLE_USAGE(.BOTH.,#196298); -#196298 = SURFACE_SIDE_STYLE('',(#196299)); -#196299 = SURFACE_STYLE_FILL_AREA(#196300); -#196300 = FILL_AREA_STYLE('',(#196301)); -#196301 = FILL_AREA_STYLE_COLOUR('',#195083); -#196302 = OVER_RIDING_STYLED_ITEM('overriding color',(#196303),#105841, - #195018); -#196303 = PRESENTATION_STYLE_ASSIGNMENT((#196304)); -#196304 = SURFACE_STYLE_USAGE(.BOTH.,#196305); -#196305 = SURFACE_SIDE_STYLE('',(#196306)); -#196306 = SURFACE_STYLE_FILL_AREA(#196307); -#196307 = FILL_AREA_STYLE('',(#196308)); -#196308 = FILL_AREA_STYLE_COLOUR('',#195083); -#196309 = OVER_RIDING_STYLED_ITEM('overriding color',(#196310),#105915, - #195018); -#196310 = PRESENTATION_STYLE_ASSIGNMENT((#196311)); -#196311 = SURFACE_STYLE_USAGE(.BOTH.,#196312); -#196312 = SURFACE_SIDE_STYLE('',(#196313)); -#196313 = SURFACE_STYLE_FILL_AREA(#196314); -#196314 = FILL_AREA_STYLE('',(#196315)); -#196315 = FILL_AREA_STYLE_COLOUR('',#195083); -#196316 = OVER_RIDING_STYLED_ITEM('overriding color',(#196317),#105989, - #195018); -#196317 = PRESENTATION_STYLE_ASSIGNMENT((#196318)); -#196318 = SURFACE_STYLE_USAGE(.BOTH.,#196319); -#196319 = SURFACE_SIDE_STYLE('',(#196320)); -#196320 = SURFACE_STYLE_FILL_AREA(#196321); -#196321 = FILL_AREA_STYLE('',(#196322)); -#196322 = FILL_AREA_STYLE_COLOUR('',#195083); -#196323 = OVER_RIDING_STYLED_ITEM('overriding color',(#196324),#106064, - #195018); -#196324 = PRESENTATION_STYLE_ASSIGNMENT((#196325)); -#196325 = SURFACE_STYLE_USAGE(.BOTH.,#196326); -#196326 = SURFACE_SIDE_STYLE('',(#196327)); -#196327 = SURFACE_STYLE_FILL_AREA(#196328); -#196328 = FILL_AREA_STYLE('',(#196329)); -#196329 = FILL_AREA_STYLE_COLOUR('',#195083); -#196330 = OVER_RIDING_STYLED_ITEM('overriding color',(#196331),#106091, - #195018); -#196331 = PRESENTATION_STYLE_ASSIGNMENT((#196332)); -#196332 = SURFACE_STYLE_USAGE(.BOTH.,#196333); -#196333 = SURFACE_SIDE_STYLE('',(#196334)); -#196334 = SURFACE_STYLE_FILL_AREA(#196335); -#196335 = FILL_AREA_STYLE('',(#196336)); -#196336 = FILL_AREA_STYLE_COLOUR('',#195083); -#196337 = OVER_RIDING_STYLED_ITEM('overriding color',(#196338),#106146, - #195018); -#196338 = PRESENTATION_STYLE_ASSIGNMENT((#196339)); -#196339 = SURFACE_STYLE_USAGE(.BOTH.,#196340); -#196340 = SURFACE_SIDE_STYLE('',(#196341)); -#196341 = SURFACE_STYLE_FILL_AREA(#196342); -#196342 = FILL_AREA_STYLE('',(#196343)); -#196343 = FILL_AREA_STYLE_COLOUR('',#195083); -#196344 = OVER_RIDING_STYLED_ITEM('overriding color',(#196345),#106153, - #195018); -#196345 = PRESENTATION_STYLE_ASSIGNMENT((#196346)); -#196346 = SURFACE_STYLE_USAGE(.BOTH.,#196347); -#196347 = SURFACE_SIDE_STYLE('',(#196348)); -#196348 = SURFACE_STYLE_FILL_AREA(#196349); -#196349 = FILL_AREA_STYLE('',(#196350)); -#196350 = FILL_AREA_STYLE_COLOUR('',#195083); -#196351 = OVER_RIDING_STYLED_ITEM('overriding color',(#196352),#106160, - #195018); -#196352 = PRESENTATION_STYLE_ASSIGNMENT((#196353)); -#196353 = SURFACE_STYLE_USAGE(.BOTH.,#196354); -#196354 = SURFACE_SIDE_STYLE('',(#196355)); -#196355 = SURFACE_STYLE_FILL_AREA(#196356); -#196356 = FILL_AREA_STYLE('',(#196357)); -#196357 = FILL_AREA_STYLE_COLOUR('',#195083); -#196358 = OVER_RIDING_STYLED_ITEM('overriding color',(#196359),#106269, - #195018); -#196359 = PRESENTATION_STYLE_ASSIGNMENT((#196360)); -#196360 = SURFACE_STYLE_USAGE(.BOTH.,#196361); -#196361 = SURFACE_SIDE_STYLE('',(#196362)); -#196362 = SURFACE_STYLE_FILL_AREA(#196363); -#196363 = FILL_AREA_STYLE('',(#196364)); -#196364 = FILL_AREA_STYLE_COLOUR('',#195083); -#196365 = OVER_RIDING_STYLED_ITEM('overriding color',(#196366),#106373, - #195018); -#196366 = PRESENTATION_STYLE_ASSIGNMENT((#196367)); -#196367 = SURFACE_STYLE_USAGE(.BOTH.,#196368); -#196368 = SURFACE_SIDE_STYLE('',(#196369)); -#196369 = SURFACE_STYLE_FILL_AREA(#196370); -#196370 = FILL_AREA_STYLE('',(#196371)); -#196371 = FILL_AREA_STYLE_COLOUR('',#195083); -#196372 = OVER_RIDING_STYLED_ITEM('overriding color',(#196373),#106452, - #195018); -#196373 = PRESENTATION_STYLE_ASSIGNMENT((#196374)); -#196374 = SURFACE_STYLE_USAGE(.BOTH.,#196375); -#196375 = SURFACE_SIDE_STYLE('',(#196376)); -#196376 = SURFACE_STYLE_FILL_AREA(#196377); -#196377 = FILL_AREA_STYLE('',(#196378)); -#196378 = FILL_AREA_STYLE_COLOUR('',#195083); -#196379 = OVER_RIDING_STYLED_ITEM('overriding color',(#196380),#106531, - #195018); -#196380 = PRESENTATION_STYLE_ASSIGNMENT((#196381)); -#196381 = SURFACE_STYLE_USAGE(.BOTH.,#196382); -#196382 = SURFACE_SIDE_STYLE('',(#196383)); -#196383 = SURFACE_STYLE_FILL_AREA(#196384); -#196384 = FILL_AREA_STYLE('',(#196385)); -#196385 = FILL_AREA_STYLE_COLOUR('',#195083); -#196386 = OVER_RIDING_STYLED_ITEM('overriding color',(#196387),#106606, - #195018); -#196387 = PRESENTATION_STYLE_ASSIGNMENT((#196388)); -#196388 = SURFACE_STYLE_USAGE(.BOTH.,#196389); -#196389 = SURFACE_SIDE_STYLE('',(#196390)); -#196390 = SURFACE_STYLE_FILL_AREA(#196391); -#196391 = FILL_AREA_STYLE('',(#196392)); -#196392 = FILL_AREA_STYLE_COLOUR('',#195083); -#196393 = OVER_RIDING_STYLED_ITEM('overriding color',(#196394),#106681, - #195018); -#196394 = PRESENTATION_STYLE_ASSIGNMENT((#196395)); -#196395 = SURFACE_STYLE_USAGE(.BOTH.,#196396); -#196396 = SURFACE_SIDE_STYLE('',(#196397)); -#196397 = SURFACE_STYLE_FILL_AREA(#196398); -#196398 = FILL_AREA_STYLE('',(#196399)); -#196399 = FILL_AREA_STYLE_COLOUR('',#195083); -#196400 = OVER_RIDING_STYLED_ITEM('overriding color',(#196401),#106755, - #195018); -#196401 = PRESENTATION_STYLE_ASSIGNMENT((#196402)); -#196402 = SURFACE_STYLE_USAGE(.BOTH.,#196403); -#196403 = SURFACE_SIDE_STYLE('',(#196404)); -#196404 = SURFACE_STYLE_FILL_AREA(#196405); -#196405 = FILL_AREA_STYLE('',(#196406)); -#196406 = FILL_AREA_STYLE_COLOUR('',#195083); -#196407 = OVER_RIDING_STYLED_ITEM('overriding color',(#196408),#106829, - #195018); -#196408 = PRESENTATION_STYLE_ASSIGNMENT((#196409)); -#196409 = SURFACE_STYLE_USAGE(.BOTH.,#196410); -#196410 = SURFACE_SIDE_STYLE('',(#196411)); -#196411 = SURFACE_STYLE_FILL_AREA(#196412); -#196412 = FILL_AREA_STYLE('',(#196413)); -#196413 = FILL_AREA_STYLE_COLOUR('',#195083); -#196414 = OVER_RIDING_STYLED_ITEM('overriding color',(#196415),#106904, - #195018); -#196415 = PRESENTATION_STYLE_ASSIGNMENT((#196416)); -#196416 = SURFACE_STYLE_USAGE(.BOTH.,#196417); -#196417 = SURFACE_SIDE_STYLE('',(#196418)); -#196418 = SURFACE_STYLE_FILL_AREA(#196419); -#196419 = FILL_AREA_STYLE('',(#196420)); -#196420 = FILL_AREA_STYLE_COLOUR('',#195083); -#196421 = OVER_RIDING_STYLED_ITEM('overriding color',(#196422),#106931, - #195018); -#196422 = PRESENTATION_STYLE_ASSIGNMENT((#196423)); -#196423 = SURFACE_STYLE_USAGE(.BOTH.,#196424); -#196424 = SURFACE_SIDE_STYLE('',(#196425)); -#196425 = SURFACE_STYLE_FILL_AREA(#196426); -#196426 = FILL_AREA_STYLE('',(#196427)); -#196427 = FILL_AREA_STYLE_COLOUR('',#195083); -#196428 = OVER_RIDING_STYLED_ITEM('overriding color',(#196429),#106986, - #195018); -#196429 = PRESENTATION_STYLE_ASSIGNMENT((#196430)); -#196430 = SURFACE_STYLE_USAGE(.BOTH.,#196431); -#196431 = SURFACE_SIDE_STYLE('',(#196432)); -#196432 = SURFACE_STYLE_FILL_AREA(#196433); -#196433 = FILL_AREA_STYLE('',(#196434)); -#196434 = FILL_AREA_STYLE_COLOUR('',#195083); -#196435 = OVER_RIDING_STYLED_ITEM('overriding color',(#196436),#106993, - #195018); -#196436 = PRESENTATION_STYLE_ASSIGNMENT((#196437)); -#196437 = SURFACE_STYLE_USAGE(.BOTH.,#196438); -#196438 = SURFACE_SIDE_STYLE('',(#196439)); -#196439 = SURFACE_STYLE_FILL_AREA(#196440); -#196440 = FILL_AREA_STYLE('',(#196441)); -#196441 = FILL_AREA_STYLE_COLOUR('',#195083); -#196442 = OVER_RIDING_STYLED_ITEM('overriding color',(#196443),#107000, - #195018); -#196443 = PRESENTATION_STYLE_ASSIGNMENT((#196444)); -#196444 = SURFACE_STYLE_USAGE(.BOTH.,#196445); -#196445 = SURFACE_SIDE_STYLE('',(#196446)); -#196446 = SURFACE_STYLE_FILL_AREA(#196447); -#196447 = FILL_AREA_STYLE('',(#196448)); -#196448 = FILL_AREA_STYLE_COLOUR('',#195083); -#196449 = OVER_RIDING_STYLED_ITEM('overriding color',(#196450),#107109, - #195018); -#196450 = PRESENTATION_STYLE_ASSIGNMENT((#196451)); -#196451 = SURFACE_STYLE_USAGE(.BOTH.,#196452); -#196452 = SURFACE_SIDE_STYLE('',(#196453)); -#196453 = SURFACE_STYLE_FILL_AREA(#196454); -#196454 = FILL_AREA_STYLE('',(#196455)); -#196455 = FILL_AREA_STYLE_COLOUR('',#195083); -#196456 = OVER_RIDING_STYLED_ITEM('overriding color',(#196457),#107213, - #195018); -#196457 = PRESENTATION_STYLE_ASSIGNMENT((#196458)); -#196458 = SURFACE_STYLE_USAGE(.BOTH.,#196459); -#196459 = SURFACE_SIDE_STYLE('',(#196460)); -#196460 = SURFACE_STYLE_FILL_AREA(#196461); -#196461 = FILL_AREA_STYLE('',(#196462)); -#196462 = FILL_AREA_STYLE_COLOUR('',#195083); -#196463 = OVER_RIDING_STYLED_ITEM('overriding color',(#196464),#107292, - #195018); -#196464 = PRESENTATION_STYLE_ASSIGNMENT((#196465)); -#196465 = SURFACE_STYLE_USAGE(.BOTH.,#196466); -#196466 = SURFACE_SIDE_STYLE('',(#196467)); -#196467 = SURFACE_STYLE_FILL_AREA(#196468); -#196468 = FILL_AREA_STYLE('',(#196469)); -#196469 = FILL_AREA_STYLE_COLOUR('',#195083); -#196470 = OVER_RIDING_STYLED_ITEM('overriding color',(#196471),#107371, - #195018); -#196471 = PRESENTATION_STYLE_ASSIGNMENT((#196472)); -#196472 = SURFACE_STYLE_USAGE(.BOTH.,#196473); -#196473 = SURFACE_SIDE_STYLE('',(#196474)); -#196474 = SURFACE_STYLE_FILL_AREA(#196475); -#196475 = FILL_AREA_STYLE('',(#196476)); -#196476 = FILL_AREA_STYLE_COLOUR('',#195083); -#196477 = OVER_RIDING_STYLED_ITEM('overriding color',(#196478),#107446, - #195018); -#196478 = PRESENTATION_STYLE_ASSIGNMENT((#196479)); -#196479 = SURFACE_STYLE_USAGE(.BOTH.,#196480); -#196480 = SURFACE_SIDE_STYLE('',(#196481)); -#196481 = SURFACE_STYLE_FILL_AREA(#196482); -#196482 = FILL_AREA_STYLE('',(#196483)); -#196483 = FILL_AREA_STYLE_COLOUR('',#195083); -#196484 = OVER_RIDING_STYLED_ITEM('overriding color',(#196485),#107521, - #195018); -#196485 = PRESENTATION_STYLE_ASSIGNMENT((#196486)); -#196486 = SURFACE_STYLE_USAGE(.BOTH.,#196487); -#196487 = SURFACE_SIDE_STYLE('',(#196488)); -#196488 = SURFACE_STYLE_FILL_AREA(#196489); -#196489 = FILL_AREA_STYLE('',(#196490)); -#196490 = FILL_AREA_STYLE_COLOUR('',#195083); -#196491 = OVER_RIDING_STYLED_ITEM('overriding color',(#196492),#107595, - #195018); -#196492 = PRESENTATION_STYLE_ASSIGNMENT((#196493)); -#196493 = SURFACE_STYLE_USAGE(.BOTH.,#196494); -#196494 = SURFACE_SIDE_STYLE('',(#196495)); -#196495 = SURFACE_STYLE_FILL_AREA(#196496); -#196496 = FILL_AREA_STYLE('',(#196497)); -#196497 = FILL_AREA_STYLE_COLOUR('',#195083); -#196498 = OVER_RIDING_STYLED_ITEM('overriding color',(#196499),#107669, - #195018); -#196499 = PRESENTATION_STYLE_ASSIGNMENT((#196500)); -#196500 = SURFACE_STYLE_USAGE(.BOTH.,#196501); -#196501 = SURFACE_SIDE_STYLE('',(#196502)); -#196502 = SURFACE_STYLE_FILL_AREA(#196503); -#196503 = FILL_AREA_STYLE('',(#196504)); -#196504 = FILL_AREA_STYLE_COLOUR('',#195083); -#196505 = OVER_RIDING_STYLED_ITEM('overriding color',(#196506),#107744, - #195018); -#196506 = PRESENTATION_STYLE_ASSIGNMENT((#196507)); -#196507 = SURFACE_STYLE_USAGE(.BOTH.,#196508); -#196508 = SURFACE_SIDE_STYLE('',(#196509)); -#196509 = SURFACE_STYLE_FILL_AREA(#196510); -#196510 = FILL_AREA_STYLE('',(#196511)); -#196511 = FILL_AREA_STYLE_COLOUR('',#195083); -#196512 = OVER_RIDING_STYLED_ITEM('overriding color',(#196513),#107771, - #195018); -#196513 = PRESENTATION_STYLE_ASSIGNMENT((#196514)); -#196514 = SURFACE_STYLE_USAGE(.BOTH.,#196515); -#196515 = SURFACE_SIDE_STYLE('',(#196516)); -#196516 = SURFACE_STYLE_FILL_AREA(#196517); -#196517 = FILL_AREA_STYLE('',(#196518)); -#196518 = FILL_AREA_STYLE_COLOUR('',#195083); -#196519 = OVER_RIDING_STYLED_ITEM('overriding color',(#196520),#107826, - #195018); -#196520 = PRESENTATION_STYLE_ASSIGNMENT((#196521)); -#196521 = SURFACE_STYLE_USAGE(.BOTH.,#196522); -#196522 = SURFACE_SIDE_STYLE('',(#196523)); -#196523 = SURFACE_STYLE_FILL_AREA(#196524); -#196524 = FILL_AREA_STYLE('',(#196525)); -#196525 = FILL_AREA_STYLE_COLOUR('',#195083); -#196526 = OVER_RIDING_STYLED_ITEM('overriding color',(#196527),#107833, - #195018); -#196527 = PRESENTATION_STYLE_ASSIGNMENT((#196528)); -#196528 = SURFACE_STYLE_USAGE(.BOTH.,#196529); -#196529 = SURFACE_SIDE_STYLE('',(#196530)); -#196530 = SURFACE_STYLE_FILL_AREA(#196531); -#196531 = FILL_AREA_STYLE('',(#196532)); -#196532 = FILL_AREA_STYLE_COLOUR('',#195083); -#196533 = OVER_RIDING_STYLED_ITEM('overriding color',(#196534),#107840, - #195018); -#196534 = PRESENTATION_STYLE_ASSIGNMENT((#196535)); -#196535 = SURFACE_STYLE_USAGE(.BOTH.,#196536); -#196536 = SURFACE_SIDE_STYLE('',(#196537)); -#196537 = SURFACE_STYLE_FILL_AREA(#196538); -#196538 = FILL_AREA_STYLE('',(#196539)); -#196539 = FILL_AREA_STYLE_COLOUR('',#195083); -#196540 = OVER_RIDING_STYLED_ITEM('overriding color',(#196541),#107949, - #195018); -#196541 = PRESENTATION_STYLE_ASSIGNMENT((#196542)); -#196542 = SURFACE_STYLE_USAGE(.BOTH.,#196543); -#196543 = SURFACE_SIDE_STYLE('',(#196544)); -#196544 = SURFACE_STYLE_FILL_AREA(#196545); -#196545 = FILL_AREA_STYLE('',(#196546)); -#196546 = FILL_AREA_STYLE_COLOUR('',#195083); -#196547 = OVER_RIDING_STYLED_ITEM('overriding color',(#196548),#108053, - #195018); -#196548 = PRESENTATION_STYLE_ASSIGNMENT((#196549)); -#196549 = SURFACE_STYLE_USAGE(.BOTH.,#196550); -#196550 = SURFACE_SIDE_STYLE('',(#196551)); -#196551 = SURFACE_STYLE_FILL_AREA(#196552); -#196552 = FILL_AREA_STYLE('',(#196553)); -#196553 = FILL_AREA_STYLE_COLOUR('',#195083); -#196554 = OVER_RIDING_STYLED_ITEM('overriding color',(#196555),#108132, - #195018); -#196555 = PRESENTATION_STYLE_ASSIGNMENT((#196556)); -#196556 = SURFACE_STYLE_USAGE(.BOTH.,#196557); -#196557 = SURFACE_SIDE_STYLE('',(#196558)); -#196558 = SURFACE_STYLE_FILL_AREA(#196559); -#196559 = FILL_AREA_STYLE('',(#196560)); -#196560 = FILL_AREA_STYLE_COLOUR('',#195083); -#196561 = OVER_RIDING_STYLED_ITEM('overriding color',(#196562),#108211, - #195018); -#196562 = PRESENTATION_STYLE_ASSIGNMENT((#196563)); -#196563 = SURFACE_STYLE_USAGE(.BOTH.,#196564); -#196564 = SURFACE_SIDE_STYLE('',(#196565)); -#196565 = SURFACE_STYLE_FILL_AREA(#196566); -#196566 = FILL_AREA_STYLE('',(#196567)); -#196567 = FILL_AREA_STYLE_COLOUR('',#195083); -#196568 = OVER_RIDING_STYLED_ITEM('overriding color',(#196569),#108286, - #195018); -#196569 = PRESENTATION_STYLE_ASSIGNMENT((#196570)); -#196570 = SURFACE_STYLE_USAGE(.BOTH.,#196571); -#196571 = SURFACE_SIDE_STYLE('',(#196572)); -#196572 = SURFACE_STYLE_FILL_AREA(#196573); -#196573 = FILL_AREA_STYLE('',(#196574)); -#196574 = FILL_AREA_STYLE_COLOUR('',#195083); -#196575 = OVER_RIDING_STYLED_ITEM('overriding color',(#196576),#108361, - #195018); -#196576 = PRESENTATION_STYLE_ASSIGNMENT((#196577)); -#196577 = SURFACE_STYLE_USAGE(.BOTH.,#196578); -#196578 = SURFACE_SIDE_STYLE('',(#196579)); -#196579 = SURFACE_STYLE_FILL_AREA(#196580); -#196580 = FILL_AREA_STYLE('',(#196581)); -#196581 = FILL_AREA_STYLE_COLOUR('',#195083); -#196582 = OVER_RIDING_STYLED_ITEM('overriding color',(#196583),#108458, - #195018); -#196583 = PRESENTATION_STYLE_ASSIGNMENT((#196584)); -#196584 = SURFACE_STYLE_USAGE(.BOTH.,#196585); -#196585 = SURFACE_SIDE_STYLE('',(#196586)); -#196586 = SURFACE_STYLE_FILL_AREA(#196587); -#196587 = FILL_AREA_STYLE('',(#196588)); -#196588 = FILL_AREA_STYLE_COLOUR('',#195083); -#196589 = OVER_RIDING_STYLED_ITEM('overriding color',(#196590),#108555, - #195018); -#196590 = PRESENTATION_STYLE_ASSIGNMENT((#196591)); -#196591 = SURFACE_STYLE_USAGE(.BOTH.,#196592); -#196592 = SURFACE_SIDE_STYLE('',(#196593)); -#196593 = SURFACE_STYLE_FILL_AREA(#196594); -#196594 = FILL_AREA_STYLE('',(#196595)); -#196595 = FILL_AREA_STYLE_COLOUR('',#195083); -#196596 = OVER_RIDING_STYLED_ITEM('overriding color',(#196597),#108602, - #195018); -#196597 = PRESENTATION_STYLE_ASSIGNMENT((#196598)); -#196598 = SURFACE_STYLE_USAGE(.BOTH.,#196599); -#196599 = SURFACE_SIDE_STYLE('',(#196600)); -#196600 = SURFACE_STYLE_FILL_AREA(#196601); -#196601 = FILL_AREA_STYLE('',(#196602)); -#196602 = FILL_AREA_STYLE_COLOUR('',#195083); -#196603 = OVER_RIDING_STYLED_ITEM('overriding color',(#196604),#108657, - #195018); -#196604 = PRESENTATION_STYLE_ASSIGNMENT((#196605)); -#196605 = SURFACE_STYLE_USAGE(.BOTH.,#196606); -#196606 = SURFACE_SIDE_STYLE('',(#196607)); -#196607 = SURFACE_STYLE_FILL_AREA(#196608); -#196608 = FILL_AREA_STYLE('',(#196609)); -#196609 = FILL_AREA_STYLE_COLOUR('',#195083); -#196610 = OVER_RIDING_STYLED_ITEM('overriding color',(#196611),#108684, - #195018); -#196611 = PRESENTATION_STYLE_ASSIGNMENT((#196612)); -#196612 = SURFACE_STYLE_USAGE(.BOTH.,#196613); -#196613 = SURFACE_SIDE_STYLE('',(#196614)); -#196614 = SURFACE_STYLE_FILL_AREA(#196615); -#196615 = FILL_AREA_STYLE('',(#196616)); -#196616 = FILL_AREA_STYLE_COLOUR('',#195083); -#196617 = OVER_RIDING_STYLED_ITEM('overriding color',(#196618),#108719, - #195018); -#196618 = PRESENTATION_STYLE_ASSIGNMENT((#196619)); -#196619 = SURFACE_STYLE_USAGE(.BOTH.,#196620); -#196620 = SURFACE_SIDE_STYLE('',(#196621)); -#196621 = SURFACE_STYLE_FILL_AREA(#196622); -#196622 = FILL_AREA_STYLE('',(#196623)); -#196623 = FILL_AREA_STYLE_COLOUR('',#195083); -#196624 = OVER_RIDING_STYLED_ITEM('overriding color',(#196625),#108726, - #195018); -#196625 = PRESENTATION_STYLE_ASSIGNMENT((#196626)); -#196626 = SURFACE_STYLE_USAGE(.BOTH.,#196627); -#196627 = SURFACE_SIDE_STYLE('',(#196628)); -#196628 = SURFACE_STYLE_FILL_AREA(#196629); -#196629 = FILL_AREA_STYLE('',(#196630)); -#196630 = FILL_AREA_STYLE_COLOUR('',#195083); -#196631 = OVER_RIDING_STYLED_ITEM('overriding color',(#196632),#108835, - #195018); -#196632 = PRESENTATION_STYLE_ASSIGNMENT((#196633)); -#196633 = SURFACE_STYLE_USAGE(.BOTH.,#196634); -#196634 = SURFACE_SIDE_STYLE('',(#196635)); -#196635 = SURFACE_STYLE_FILL_AREA(#196636); -#196636 = FILL_AREA_STYLE('',(#196637)); -#196637 = FILL_AREA_STYLE_COLOUR('',#195083); -#196638 = OVER_RIDING_STYLED_ITEM('overriding color',(#196639),#108939, - #195018); -#196639 = PRESENTATION_STYLE_ASSIGNMENT((#196640)); -#196640 = SURFACE_STYLE_USAGE(.BOTH.,#196641); -#196641 = SURFACE_SIDE_STYLE('',(#196642)); -#196642 = SURFACE_STYLE_FILL_AREA(#196643); -#196643 = FILL_AREA_STYLE('',(#196644)); -#196644 = FILL_AREA_STYLE_COLOUR('',#195083); -#196645 = OVER_RIDING_STYLED_ITEM('overriding color',(#196646),#109018, - #195018); -#196646 = PRESENTATION_STYLE_ASSIGNMENT((#196647)); -#196647 = SURFACE_STYLE_USAGE(.BOTH.,#196648); -#196648 = SURFACE_SIDE_STYLE('',(#196649)); -#196649 = SURFACE_STYLE_FILL_AREA(#196650); -#196650 = FILL_AREA_STYLE('',(#196651)); -#196651 = FILL_AREA_STYLE_COLOUR('',#195083); -#196652 = OVER_RIDING_STYLED_ITEM('overriding color',(#196653),#109097, - #195018); -#196653 = PRESENTATION_STYLE_ASSIGNMENT((#196654)); -#196654 = SURFACE_STYLE_USAGE(.BOTH.,#196655); -#196655 = SURFACE_SIDE_STYLE('',(#196656)); -#196656 = SURFACE_STYLE_FILL_AREA(#196657); -#196657 = FILL_AREA_STYLE('',(#196658)); -#196658 = FILL_AREA_STYLE_COLOUR('',#195083); -#196659 = OVER_RIDING_STYLED_ITEM('overriding color',(#196660),#109172, - #195018); -#196660 = PRESENTATION_STYLE_ASSIGNMENT((#196661)); -#196661 = SURFACE_STYLE_USAGE(.BOTH.,#196662); -#196662 = SURFACE_SIDE_STYLE('',(#196663)); -#196663 = SURFACE_STYLE_FILL_AREA(#196664); -#196664 = FILL_AREA_STYLE('',(#196665)); -#196665 = FILL_AREA_STYLE_COLOUR('',#195083); -#196666 = OVER_RIDING_STYLED_ITEM('overriding color',(#196667),#109247, - #195018); -#196667 = PRESENTATION_STYLE_ASSIGNMENT((#196668)); -#196668 = SURFACE_STYLE_USAGE(.BOTH.,#196669); -#196669 = SURFACE_SIDE_STYLE('',(#196670)); -#196670 = SURFACE_STYLE_FILL_AREA(#196671); -#196671 = FILL_AREA_STYLE('',(#196672)); -#196672 = FILL_AREA_STYLE_COLOUR('',#195083); -#196673 = OVER_RIDING_STYLED_ITEM('overriding color',(#196674),#109344, - #195018); -#196674 = PRESENTATION_STYLE_ASSIGNMENT((#196675)); -#196675 = SURFACE_STYLE_USAGE(.BOTH.,#196676); -#196676 = SURFACE_SIDE_STYLE('',(#196677)); -#196677 = SURFACE_STYLE_FILL_AREA(#196678); -#196678 = FILL_AREA_STYLE('',(#196679)); -#196679 = FILL_AREA_STYLE_COLOUR('',#195083); -#196680 = OVER_RIDING_STYLED_ITEM('overriding color',(#196681),#109441, - #195018); -#196681 = PRESENTATION_STYLE_ASSIGNMENT((#196682)); -#196682 = SURFACE_STYLE_USAGE(.BOTH.,#196683); -#196683 = SURFACE_SIDE_STYLE('',(#196684)); -#196684 = SURFACE_STYLE_FILL_AREA(#196685); -#196685 = FILL_AREA_STYLE('',(#196686)); -#196686 = FILL_AREA_STYLE_COLOUR('',#195083); -#196687 = OVER_RIDING_STYLED_ITEM('overriding color',(#196688),#109516, - #195018); -#196688 = PRESENTATION_STYLE_ASSIGNMENT((#196689)); -#196689 = SURFACE_STYLE_USAGE(.BOTH.,#196690); -#196690 = SURFACE_SIDE_STYLE('',(#196691)); -#196691 = SURFACE_STYLE_FILL_AREA(#196692); -#196692 = FILL_AREA_STYLE('',(#196693)); -#196693 = FILL_AREA_STYLE_COLOUR('',#195083); -#196694 = OVER_RIDING_STYLED_ITEM('overriding color',(#196695),#109543, - #195018); -#196695 = PRESENTATION_STYLE_ASSIGNMENT((#196696)); -#196696 = SURFACE_STYLE_USAGE(.BOTH.,#196697); -#196697 = SURFACE_SIDE_STYLE('',(#196698)); -#196698 = SURFACE_STYLE_FILL_AREA(#196699); -#196699 = FILL_AREA_STYLE('',(#196700)); -#196700 = FILL_AREA_STYLE_COLOUR('',#195083); -#196701 = OVER_RIDING_STYLED_ITEM('overriding color',(#196702),#109598, - #195018); -#196702 = PRESENTATION_STYLE_ASSIGNMENT((#196703)); -#196703 = SURFACE_STYLE_USAGE(.BOTH.,#196704); -#196704 = SURFACE_SIDE_STYLE('',(#196705)); -#196705 = SURFACE_STYLE_FILL_AREA(#196706); -#196706 = FILL_AREA_STYLE('',(#196707)); -#196707 = FILL_AREA_STYLE_COLOUR('',#195083); -#196708 = OVER_RIDING_STYLED_ITEM('overriding color',(#196709),#109605, - #195018); -#196709 = PRESENTATION_STYLE_ASSIGNMENT((#196710)); -#196710 = SURFACE_STYLE_USAGE(.BOTH.,#196711); -#196711 = SURFACE_SIDE_STYLE('',(#196712)); -#196712 = SURFACE_STYLE_FILL_AREA(#196713); -#196713 = FILL_AREA_STYLE('',(#196714)); -#196714 = FILL_AREA_STYLE_COLOUR('',#195083); -#196715 = OVER_RIDING_STYLED_ITEM('overriding color',(#196716),#109612, - #195018); -#196716 = PRESENTATION_STYLE_ASSIGNMENT((#196717)); -#196717 = SURFACE_STYLE_USAGE(.BOTH.,#196718); -#196718 = SURFACE_SIDE_STYLE('',(#196719)); -#196719 = SURFACE_STYLE_FILL_AREA(#196720); -#196720 = FILL_AREA_STYLE('',(#196721)); -#196721 = FILL_AREA_STYLE_COLOUR('',#195083); -#196722 = OVER_RIDING_STYLED_ITEM('overriding color',(#196723),#109721, - #195018); -#196723 = PRESENTATION_STYLE_ASSIGNMENT((#196724)); -#196724 = SURFACE_STYLE_USAGE(.BOTH.,#196725); -#196725 = SURFACE_SIDE_STYLE('',(#196726)); -#196726 = SURFACE_STYLE_FILL_AREA(#196727); -#196727 = FILL_AREA_STYLE('',(#196728)); -#196728 = FILL_AREA_STYLE_COLOUR('',#195083); -#196729 = OVER_RIDING_STYLED_ITEM('overriding color',(#196730),#109825, - #195018); -#196730 = PRESENTATION_STYLE_ASSIGNMENT((#196731)); -#196731 = SURFACE_STYLE_USAGE(.BOTH.,#196732); -#196732 = SURFACE_SIDE_STYLE('',(#196733)); -#196733 = SURFACE_STYLE_FILL_AREA(#196734); -#196734 = FILL_AREA_STYLE('',(#196735)); -#196735 = FILL_AREA_STYLE_COLOUR('',#195083); -#196736 = OVER_RIDING_STYLED_ITEM('overriding color',(#196737),#109904, - #195018); -#196737 = PRESENTATION_STYLE_ASSIGNMENT((#196738)); -#196738 = SURFACE_STYLE_USAGE(.BOTH.,#196739); -#196739 = SURFACE_SIDE_STYLE('',(#196740)); -#196740 = SURFACE_STYLE_FILL_AREA(#196741); -#196741 = FILL_AREA_STYLE('',(#196742)); -#196742 = FILL_AREA_STYLE_COLOUR('',#195083); -#196743 = OVER_RIDING_STYLED_ITEM('overriding color',(#196744),#109983, - #195018); -#196744 = PRESENTATION_STYLE_ASSIGNMENT((#196745)); -#196745 = SURFACE_STYLE_USAGE(.BOTH.,#196746); -#196746 = SURFACE_SIDE_STYLE('',(#196747)); -#196747 = SURFACE_STYLE_FILL_AREA(#196748); -#196748 = FILL_AREA_STYLE('',(#196749)); -#196749 = FILL_AREA_STYLE_COLOUR('',#195083); -#196750 = OVER_RIDING_STYLED_ITEM('overriding color',(#196751),#110058, - #195018); -#196751 = PRESENTATION_STYLE_ASSIGNMENT((#196752)); -#196752 = SURFACE_STYLE_USAGE(.BOTH.,#196753); -#196753 = SURFACE_SIDE_STYLE('',(#196754)); -#196754 = SURFACE_STYLE_FILL_AREA(#196755); -#196755 = FILL_AREA_STYLE('',(#196756)); -#196756 = FILL_AREA_STYLE_COLOUR('',#195083); -#196757 = OVER_RIDING_STYLED_ITEM('overriding color',(#196758),#110133, - #195018); -#196758 = PRESENTATION_STYLE_ASSIGNMENT((#196759)); -#196759 = SURFACE_STYLE_USAGE(.BOTH.,#196760); -#196760 = SURFACE_SIDE_STYLE('',(#196761)); -#196761 = SURFACE_STYLE_FILL_AREA(#196762); -#196762 = FILL_AREA_STYLE('',(#196763)); -#196763 = FILL_AREA_STYLE_COLOUR('',#195083); -#196764 = OVER_RIDING_STYLED_ITEM('overriding color',(#196765),#110230, - #195018); -#196765 = PRESENTATION_STYLE_ASSIGNMENT((#196766)); -#196766 = SURFACE_STYLE_USAGE(.BOTH.,#196767); -#196767 = SURFACE_SIDE_STYLE('',(#196768)); -#196768 = SURFACE_STYLE_FILL_AREA(#196769); -#196769 = FILL_AREA_STYLE('',(#196770)); -#196770 = FILL_AREA_STYLE_COLOUR('',#195083); -#196771 = OVER_RIDING_STYLED_ITEM('overriding color',(#196772),#110327, - #195018); -#196772 = PRESENTATION_STYLE_ASSIGNMENT((#196773)); -#196773 = SURFACE_STYLE_USAGE(.BOTH.,#196774); -#196774 = SURFACE_SIDE_STYLE('',(#196775)); -#196775 = SURFACE_STYLE_FILL_AREA(#196776); -#196776 = FILL_AREA_STYLE('',(#196777)); -#196777 = FILL_AREA_STYLE_COLOUR('',#195083); -#196778 = OVER_RIDING_STYLED_ITEM('overriding color',(#196779),#110374, - #195018); -#196779 = PRESENTATION_STYLE_ASSIGNMENT((#196780)); -#196780 = SURFACE_STYLE_USAGE(.BOTH.,#196781); -#196781 = SURFACE_SIDE_STYLE('',(#196782)); -#196782 = SURFACE_STYLE_FILL_AREA(#196783); -#196783 = FILL_AREA_STYLE('',(#196784)); -#196784 = FILL_AREA_STYLE_COLOUR('',#195083); -#196785 = OVER_RIDING_STYLED_ITEM('overriding color',(#196786),#110429, - #195018); -#196786 = PRESENTATION_STYLE_ASSIGNMENT((#196787)); -#196787 = SURFACE_STYLE_USAGE(.BOTH.,#196788); -#196788 = SURFACE_SIDE_STYLE('',(#196789)); -#196789 = SURFACE_STYLE_FILL_AREA(#196790); -#196790 = FILL_AREA_STYLE('',(#196791)); -#196791 = FILL_AREA_STYLE_COLOUR('',#195083); -#196792 = OVER_RIDING_STYLED_ITEM('overriding color',(#196793),#110456, - #195018); -#196793 = PRESENTATION_STYLE_ASSIGNMENT((#196794)); -#196794 = SURFACE_STYLE_USAGE(.BOTH.,#196795); -#196795 = SURFACE_SIDE_STYLE('',(#196796)); -#196796 = SURFACE_STYLE_FILL_AREA(#196797); -#196797 = FILL_AREA_STYLE('',(#196798)); -#196798 = FILL_AREA_STYLE_COLOUR('',#195083); -#196799 = OVER_RIDING_STYLED_ITEM('overriding color',(#196800),#110491, - #195018); -#196800 = PRESENTATION_STYLE_ASSIGNMENT((#196801)); -#196801 = SURFACE_STYLE_USAGE(.BOTH.,#196802); -#196802 = SURFACE_SIDE_STYLE('',(#196803)); -#196803 = SURFACE_STYLE_FILL_AREA(#196804); -#196804 = FILL_AREA_STYLE('',(#196805)); -#196805 = FILL_AREA_STYLE_COLOUR('',#195083); -#196806 = OVER_RIDING_STYLED_ITEM('overriding color',(#196807),#110498, - #195018); -#196807 = PRESENTATION_STYLE_ASSIGNMENT((#196808)); -#196808 = SURFACE_STYLE_USAGE(.BOTH.,#196809); -#196809 = SURFACE_SIDE_STYLE('',(#196810)); -#196810 = SURFACE_STYLE_FILL_AREA(#196811); -#196811 = FILL_AREA_STYLE('',(#196812)); -#196812 = FILL_AREA_STYLE_COLOUR('',#195083); -#196813 = OVER_RIDING_STYLED_ITEM('overriding color',(#196814),#110607, - #195018); -#196814 = PRESENTATION_STYLE_ASSIGNMENT((#196815)); -#196815 = SURFACE_STYLE_USAGE(.BOTH.,#196816); -#196816 = SURFACE_SIDE_STYLE('',(#196817)); -#196817 = SURFACE_STYLE_FILL_AREA(#196818); -#196818 = FILL_AREA_STYLE('',(#196819)); -#196819 = FILL_AREA_STYLE_COLOUR('',#195083); -#196820 = OVER_RIDING_STYLED_ITEM('overriding color',(#196821),#110711, - #195018); -#196821 = PRESENTATION_STYLE_ASSIGNMENT((#196822)); -#196822 = SURFACE_STYLE_USAGE(.BOTH.,#196823); -#196823 = SURFACE_SIDE_STYLE('',(#196824)); -#196824 = SURFACE_STYLE_FILL_AREA(#196825); -#196825 = FILL_AREA_STYLE('',(#196826)); -#196826 = FILL_AREA_STYLE_COLOUR('',#195083); -#196827 = OVER_RIDING_STYLED_ITEM('overriding color',(#196828),#110836, - #195018); -#196828 = PRESENTATION_STYLE_ASSIGNMENT((#196829)); -#196829 = SURFACE_STYLE_USAGE(.BOTH.,#196830); -#196830 = SURFACE_SIDE_STYLE('',(#196831)); -#196831 = SURFACE_STYLE_FILL_AREA(#196832); -#196832 = FILL_AREA_STYLE('',(#196833)); -#196833 = FILL_AREA_STYLE_COLOUR('',#195083); -#196834 = OVER_RIDING_STYLED_ITEM('overriding color',(#196835),#110915, - #195018); -#196835 = PRESENTATION_STYLE_ASSIGNMENT((#196836)); -#196836 = SURFACE_STYLE_USAGE(.BOTH.,#196837); -#196837 = SURFACE_SIDE_STYLE('',(#196838)); -#196838 = SURFACE_STYLE_FILL_AREA(#196839); -#196839 = FILL_AREA_STYLE('',(#196840)); -#196840 = FILL_AREA_STYLE_COLOUR('',#195083); -#196841 = OVER_RIDING_STYLED_ITEM('overriding color',(#196842),#110990, - #195018); -#196842 = PRESENTATION_STYLE_ASSIGNMENT((#196843)); -#196843 = SURFACE_STYLE_USAGE(.BOTH.,#196844); -#196844 = SURFACE_SIDE_STYLE('',(#196845)); -#196845 = SURFACE_STYLE_FILL_AREA(#196846); -#196846 = FILL_AREA_STYLE('',(#196847)); -#196847 = FILL_AREA_STYLE_COLOUR('',#195083); -#196848 = OVER_RIDING_STYLED_ITEM('overriding color',(#196849),#111065, - #195018); -#196849 = PRESENTATION_STYLE_ASSIGNMENT((#196850)); -#196850 = SURFACE_STYLE_USAGE(.BOTH.,#196851); -#196851 = SURFACE_SIDE_STYLE('',(#196852)); -#196852 = SURFACE_STYLE_FILL_AREA(#196853); -#196853 = FILL_AREA_STYLE('',(#196854)); -#196854 = FILL_AREA_STYLE_COLOUR('',#195083); -#196855 = OVER_RIDING_STYLED_ITEM('overriding color',(#196856),#111162, - #195018); -#196856 = PRESENTATION_STYLE_ASSIGNMENT((#196857)); -#196857 = SURFACE_STYLE_USAGE(.BOTH.,#196858); -#196858 = SURFACE_SIDE_STYLE('',(#196859)); -#196859 = SURFACE_STYLE_FILL_AREA(#196860); -#196860 = FILL_AREA_STYLE('',(#196861)); -#196861 = FILL_AREA_STYLE_COLOUR('',#195083); -#196862 = OVER_RIDING_STYLED_ITEM('overriding color',(#196863),#111305, - #195018); -#196863 = PRESENTATION_STYLE_ASSIGNMENT((#196864)); -#196864 = SURFACE_STYLE_USAGE(.BOTH.,#196865); -#196865 = SURFACE_SIDE_STYLE('',(#196866)); -#196866 = SURFACE_STYLE_FILL_AREA(#196867); -#196867 = FILL_AREA_STYLE('',(#196868)); -#196868 = FILL_AREA_STYLE_COLOUR('',#195083); -#196869 = OVER_RIDING_STYLED_ITEM('overriding color',(#196870),#111352, - #195018); -#196870 = PRESENTATION_STYLE_ASSIGNMENT((#196871)); -#196871 = SURFACE_STYLE_USAGE(.BOTH.,#196872); -#196872 = SURFACE_SIDE_STYLE('',(#196873)); -#196873 = SURFACE_STYLE_FILL_AREA(#196874); -#196874 = FILL_AREA_STYLE('',(#196875)); -#196875 = FILL_AREA_STYLE_COLOUR('',#195083); -#196876 = OVER_RIDING_STYLED_ITEM('overriding color',(#196877),#111407, - #195018); -#196877 = PRESENTATION_STYLE_ASSIGNMENT((#196878)); -#196878 = SURFACE_STYLE_USAGE(.BOTH.,#196879); -#196879 = SURFACE_SIDE_STYLE('',(#196880)); -#196880 = SURFACE_STYLE_FILL_AREA(#196881); -#196881 = FILL_AREA_STYLE('',(#196882)); -#196882 = FILL_AREA_STYLE_COLOUR('',#195083); -#196883 = OVER_RIDING_STYLED_ITEM('overriding color',(#196884),#111434, - #195018); -#196884 = PRESENTATION_STYLE_ASSIGNMENT((#196885)); -#196885 = SURFACE_STYLE_USAGE(.BOTH.,#196886); -#196886 = SURFACE_SIDE_STYLE('',(#196887)); -#196887 = SURFACE_STYLE_FILL_AREA(#196888); -#196888 = FILL_AREA_STYLE('',(#196889)); -#196889 = FILL_AREA_STYLE_COLOUR('',#195083); -#196890 = OVER_RIDING_STYLED_ITEM('overriding color',(#196891),#111469, - #195018); -#196891 = PRESENTATION_STYLE_ASSIGNMENT((#196892)); -#196892 = SURFACE_STYLE_USAGE(.BOTH.,#196893); -#196893 = SURFACE_SIDE_STYLE('',(#196894)); -#196894 = SURFACE_STYLE_FILL_AREA(#196895); -#196895 = FILL_AREA_STYLE('',(#196896)); -#196896 = FILL_AREA_STYLE_COLOUR('',#195083); -#196897 = OVER_RIDING_STYLED_ITEM('overriding color',(#196898),#111476, - #195018); -#196898 = PRESENTATION_STYLE_ASSIGNMENT((#196899)); -#196899 = SURFACE_STYLE_USAGE(.BOTH.,#196900); -#196900 = SURFACE_SIDE_STYLE('',(#196901)); -#196901 = SURFACE_STYLE_FILL_AREA(#196902); -#196902 = FILL_AREA_STYLE('',(#196903)); -#196903 = FILL_AREA_STYLE_COLOUR('',#195083); -#196904 = OVER_RIDING_STYLED_ITEM('overriding color',(#196905),#111585, - #195018); -#196905 = PRESENTATION_STYLE_ASSIGNMENT((#196906)); -#196906 = SURFACE_STYLE_USAGE(.BOTH.,#196907); -#196907 = SURFACE_SIDE_STYLE('',(#196908)); -#196908 = SURFACE_STYLE_FILL_AREA(#196909); -#196909 = FILL_AREA_STYLE('',(#196910)); -#196910 = FILL_AREA_STYLE_COLOUR('',#195083); -#196911 = OVER_RIDING_STYLED_ITEM('overriding color',(#196912),#111689, - #195018); -#196912 = PRESENTATION_STYLE_ASSIGNMENT((#196913)); -#196913 = SURFACE_STYLE_USAGE(.BOTH.,#196914); -#196914 = SURFACE_SIDE_STYLE('',(#196915)); -#196915 = SURFACE_STYLE_FILL_AREA(#196916); -#196916 = FILL_AREA_STYLE('',(#196917)); -#196917 = FILL_AREA_STYLE_COLOUR('',#195083); -#196918 = OVER_RIDING_STYLED_ITEM('overriding color',(#196919),#111791, - #195018); -#196919 = PRESENTATION_STYLE_ASSIGNMENT((#196920)); -#196920 = SURFACE_STYLE_USAGE(.BOTH.,#196921); -#196921 = SURFACE_SIDE_STYLE('',(#196922)); -#196922 = SURFACE_STYLE_FILL_AREA(#196923); -#196923 = FILL_AREA_STYLE('',(#196924)); -#196924 = FILL_AREA_STYLE_COLOUR('',#195083); -#196925 = OVER_RIDING_STYLED_ITEM('overriding color',(#196926),#111870, - #195018); -#196926 = PRESENTATION_STYLE_ASSIGNMENT((#196927)); -#196927 = SURFACE_STYLE_USAGE(.BOTH.,#196928); -#196928 = SURFACE_SIDE_STYLE('',(#196929)); -#196929 = SURFACE_STYLE_FILL_AREA(#196930); -#196930 = FILL_AREA_STYLE('',(#196931)); -#196931 = FILL_AREA_STYLE_COLOUR('',#195083); -#196932 = OVER_RIDING_STYLED_ITEM('overriding color',(#196933),#111945, - #195018); -#196933 = PRESENTATION_STYLE_ASSIGNMENT((#196934)); -#196934 = SURFACE_STYLE_USAGE(.BOTH.,#196935); -#196935 = SURFACE_SIDE_STYLE('',(#196936)); -#196936 = SURFACE_STYLE_FILL_AREA(#196937); -#196937 = FILL_AREA_STYLE('',(#196938)); -#196938 = FILL_AREA_STYLE_COLOUR('',#195083); -#196939 = OVER_RIDING_STYLED_ITEM('overriding color',(#196940),#112020, - #195018); -#196940 = PRESENTATION_STYLE_ASSIGNMENT((#196941)); -#196941 = SURFACE_STYLE_USAGE(.BOTH.,#196942); -#196942 = SURFACE_SIDE_STYLE('',(#196943)); -#196943 = SURFACE_STYLE_FILL_AREA(#196944); -#196944 = FILL_AREA_STYLE('',(#196945)); -#196945 = FILL_AREA_STYLE_COLOUR('',#195083); -#196946 = OVER_RIDING_STYLED_ITEM('overriding color',(#196947),#112117, - #195018); -#196947 = PRESENTATION_STYLE_ASSIGNMENT((#196948)); -#196948 = SURFACE_STYLE_USAGE(.BOTH.,#196949); -#196949 = SURFACE_SIDE_STYLE('',(#196950)); -#196950 = SURFACE_STYLE_FILL_AREA(#196951); -#196951 = FILL_AREA_STYLE('',(#196952)); -#196952 = FILL_AREA_STYLE_COLOUR('',#195083); -#196953 = OVER_RIDING_STYLED_ITEM('overriding color',(#196954),#112237, - #195018); -#196954 = PRESENTATION_STYLE_ASSIGNMENT((#196955)); -#196955 = SURFACE_STYLE_USAGE(.BOTH.,#196956); -#196956 = SURFACE_SIDE_STYLE('',(#196957)); -#196957 = SURFACE_STYLE_FILL_AREA(#196958); -#196958 = FILL_AREA_STYLE('',(#196959)); -#196959 = FILL_AREA_STYLE_COLOUR('',#195083); -#196960 = OVER_RIDING_STYLED_ITEM('overriding color',(#196961),#112284, - #195018); -#196961 = PRESENTATION_STYLE_ASSIGNMENT((#196962)); -#196962 = SURFACE_STYLE_USAGE(.BOTH.,#196963); -#196963 = SURFACE_SIDE_STYLE('',(#196964)); -#196964 = SURFACE_STYLE_FILL_AREA(#196965); -#196965 = FILL_AREA_STYLE('',(#196966)); -#196966 = FILL_AREA_STYLE_COLOUR('',#195083); -#196967 = OVER_RIDING_STYLED_ITEM('overriding color',(#196968),#112339, - #195018); -#196968 = PRESENTATION_STYLE_ASSIGNMENT((#196969)); -#196969 = SURFACE_STYLE_USAGE(.BOTH.,#196970); -#196970 = SURFACE_SIDE_STYLE('',(#196971)); -#196971 = SURFACE_STYLE_FILL_AREA(#196972); -#196972 = FILL_AREA_STYLE('',(#196973)); -#196973 = FILL_AREA_STYLE_COLOUR('',#195083); -#196974 = OVER_RIDING_STYLED_ITEM('overriding color',(#196975),#112366, - #195018); -#196975 = PRESENTATION_STYLE_ASSIGNMENT((#196976)); -#196976 = SURFACE_STYLE_USAGE(.BOTH.,#196977); -#196977 = SURFACE_SIDE_STYLE('',(#196978)); -#196978 = SURFACE_STYLE_FILL_AREA(#196979); -#196979 = FILL_AREA_STYLE('',(#196980)); -#196980 = FILL_AREA_STYLE_COLOUR('',#195083); -#196981 = OVER_RIDING_STYLED_ITEM('overriding color',(#196982),#112401, - #195018); -#196982 = PRESENTATION_STYLE_ASSIGNMENT((#196983)); -#196983 = SURFACE_STYLE_USAGE(.BOTH.,#196984); -#196984 = SURFACE_SIDE_STYLE('',(#196985)); -#196985 = SURFACE_STYLE_FILL_AREA(#196986); -#196986 = FILL_AREA_STYLE('',(#196987)); -#196987 = FILL_AREA_STYLE_COLOUR('',#195083); -#196988 = OVER_RIDING_STYLED_ITEM('overriding color',(#196989),#112408, - #195018); -#196989 = PRESENTATION_STYLE_ASSIGNMENT((#196990)); -#196990 = SURFACE_STYLE_USAGE(.BOTH.,#196991); -#196991 = SURFACE_SIDE_STYLE('',(#196992)); -#196992 = SURFACE_STYLE_FILL_AREA(#196993); -#196993 = FILL_AREA_STYLE('',(#196994)); -#196994 = FILL_AREA_STYLE_COLOUR('',#195083); -#196995 = OVER_RIDING_STYLED_ITEM('overriding color',(#196996),#112517, - #195018); -#196996 = PRESENTATION_STYLE_ASSIGNMENT((#196997)); -#196997 = SURFACE_STYLE_USAGE(.BOTH.,#196998); -#196998 = SURFACE_SIDE_STYLE('',(#196999)); -#196999 = SURFACE_STYLE_FILL_AREA(#197000); -#197000 = FILL_AREA_STYLE('',(#197001)); -#197001 = FILL_AREA_STYLE_COLOUR('',#195083); -#197002 = OVER_RIDING_STYLED_ITEM('overriding color',(#197003),#112621, - #195018); -#197003 = PRESENTATION_STYLE_ASSIGNMENT((#197004)); -#197004 = SURFACE_STYLE_USAGE(.BOTH.,#197005); -#197005 = SURFACE_SIDE_STYLE('',(#197006)); -#197006 = SURFACE_STYLE_FILL_AREA(#197007); -#197007 = FILL_AREA_STYLE('',(#197008)); -#197008 = FILL_AREA_STYLE_COLOUR('',#195083); -#197009 = OVER_RIDING_STYLED_ITEM('overriding color',(#197010),#112700, - #195018); -#197010 = PRESENTATION_STYLE_ASSIGNMENT((#197011)); -#197011 = SURFACE_STYLE_USAGE(.BOTH.,#197012); -#197012 = SURFACE_SIDE_STYLE('',(#197013)); -#197013 = SURFACE_STYLE_FILL_AREA(#197014); -#197014 = FILL_AREA_STYLE('',(#197015)); -#197015 = FILL_AREA_STYLE_COLOUR('',#195083); -#197016 = OVER_RIDING_STYLED_ITEM('overriding color',(#197017),#112779, - #195018); -#197017 = PRESENTATION_STYLE_ASSIGNMENT((#197018)); -#197018 = SURFACE_STYLE_USAGE(.BOTH.,#197019); -#197019 = SURFACE_SIDE_STYLE('',(#197020)); -#197020 = SURFACE_STYLE_FILL_AREA(#197021); -#197021 = FILL_AREA_STYLE('',(#197022)); -#197022 = FILL_AREA_STYLE_COLOUR('',#195083); -#197023 = OVER_RIDING_STYLED_ITEM('overriding color',(#197024),#112854, - #195018); -#197024 = PRESENTATION_STYLE_ASSIGNMENT((#197025)); -#197025 = SURFACE_STYLE_USAGE(.BOTH.,#197026); -#197026 = SURFACE_SIDE_STYLE('',(#197027)); -#197027 = SURFACE_STYLE_FILL_AREA(#197028); -#197028 = FILL_AREA_STYLE('',(#197029)); -#197029 = FILL_AREA_STYLE_COLOUR('',#195083); -#197030 = OVER_RIDING_STYLED_ITEM('overriding color',(#197031),#112929, - #195018); -#197031 = PRESENTATION_STYLE_ASSIGNMENT((#197032)); -#197032 = SURFACE_STYLE_USAGE(.BOTH.,#197033); -#197033 = SURFACE_SIDE_STYLE('',(#197034)); -#197034 = SURFACE_STYLE_FILL_AREA(#197035); -#197035 = FILL_AREA_STYLE('',(#197036)); -#197036 = FILL_AREA_STYLE_COLOUR('',#195083); -#197037 = OVER_RIDING_STYLED_ITEM('overriding color',(#197038),#113026, - #195018); -#197038 = PRESENTATION_STYLE_ASSIGNMENT((#197039)); -#197039 = SURFACE_STYLE_USAGE(.BOTH.,#197040); -#197040 = SURFACE_SIDE_STYLE('',(#197041)); -#197041 = SURFACE_STYLE_FILL_AREA(#197042); -#197042 = FILL_AREA_STYLE('',(#197043)); -#197043 = FILL_AREA_STYLE_COLOUR('',#195083); -#197044 = OVER_RIDING_STYLED_ITEM('overriding color',(#197045),#113123, - #195018); -#197045 = PRESENTATION_STYLE_ASSIGNMENT((#197046)); -#197046 = SURFACE_STYLE_USAGE(.BOTH.,#197047); -#197047 = SURFACE_SIDE_STYLE('',(#197048)); -#197048 = SURFACE_STYLE_FILL_AREA(#197049); -#197049 = FILL_AREA_STYLE('',(#197050)); -#197050 = FILL_AREA_STYLE_COLOUR('',#195083); -#197051 = OVER_RIDING_STYLED_ITEM('overriding color',(#197052),#113170, - #195018); -#197052 = PRESENTATION_STYLE_ASSIGNMENT((#197053)); -#197053 = SURFACE_STYLE_USAGE(.BOTH.,#197054); -#197054 = SURFACE_SIDE_STYLE('',(#197055)); -#197055 = SURFACE_STYLE_FILL_AREA(#197056); -#197056 = FILL_AREA_STYLE('',(#197057)); -#197057 = FILL_AREA_STYLE_COLOUR('',#195083); -#197058 = OVER_RIDING_STYLED_ITEM('overriding color',(#197059),#113225, - #195018); -#197059 = PRESENTATION_STYLE_ASSIGNMENT((#197060)); -#197060 = SURFACE_STYLE_USAGE(.BOTH.,#197061); -#197061 = SURFACE_SIDE_STYLE('',(#197062)); -#197062 = SURFACE_STYLE_FILL_AREA(#197063); -#197063 = FILL_AREA_STYLE('',(#197064)); -#197064 = FILL_AREA_STYLE_COLOUR('',#195083); -#197065 = OVER_RIDING_STYLED_ITEM('overriding color',(#197066),#113252, - #195018); -#197066 = PRESENTATION_STYLE_ASSIGNMENT((#197067)); -#197067 = SURFACE_STYLE_USAGE(.BOTH.,#197068); -#197068 = SURFACE_SIDE_STYLE('',(#197069)); -#197069 = SURFACE_STYLE_FILL_AREA(#197070); -#197070 = FILL_AREA_STYLE('',(#197071)); -#197071 = FILL_AREA_STYLE_COLOUR('',#195083); -#197072 = OVER_RIDING_STYLED_ITEM('overriding color',(#197073),#113287, - #195018); -#197073 = PRESENTATION_STYLE_ASSIGNMENT((#197074)); -#197074 = SURFACE_STYLE_USAGE(.BOTH.,#197075); -#197075 = SURFACE_SIDE_STYLE('',(#197076)); -#197076 = SURFACE_STYLE_FILL_AREA(#197077); -#197077 = FILL_AREA_STYLE('',(#197078)); -#197078 = FILL_AREA_STYLE_COLOUR('',#195083); -#197079 = OVER_RIDING_STYLED_ITEM('overriding color',(#197080),#113294, - #195018); -#197080 = PRESENTATION_STYLE_ASSIGNMENT((#197081)); -#197081 = SURFACE_STYLE_USAGE(.BOTH.,#197082); -#197082 = SURFACE_SIDE_STYLE('',(#197083)); -#197083 = SURFACE_STYLE_FILL_AREA(#197084); -#197084 = FILL_AREA_STYLE('',(#197085)); -#197085 = FILL_AREA_STYLE_COLOUR('',#195083); -#197086 = OVER_RIDING_STYLED_ITEM('overriding color',(#197087),#113403, - #195018); -#197087 = PRESENTATION_STYLE_ASSIGNMENT((#197088)); -#197088 = SURFACE_STYLE_USAGE(.BOTH.,#197089); -#197089 = SURFACE_SIDE_STYLE('',(#197090)); -#197090 = SURFACE_STYLE_FILL_AREA(#197091); -#197091 = FILL_AREA_STYLE('',(#197092)); -#197092 = FILL_AREA_STYLE_COLOUR('',#195083); -#197093 = OVER_RIDING_STYLED_ITEM('overriding color',(#197094),#113507, - #195018); -#197094 = PRESENTATION_STYLE_ASSIGNMENT((#197095)); -#197095 = SURFACE_STYLE_USAGE(.BOTH.,#197096); -#197096 = SURFACE_SIDE_STYLE('',(#197097)); -#197097 = SURFACE_STYLE_FILL_AREA(#197098); -#197098 = FILL_AREA_STYLE('',(#197099)); -#197099 = FILL_AREA_STYLE_COLOUR('',#195083); -#197100 = OVER_RIDING_STYLED_ITEM('overriding color',(#197101),#113609, - #195018); -#197101 = PRESENTATION_STYLE_ASSIGNMENT((#197102)); -#197102 = SURFACE_STYLE_USAGE(.BOTH.,#197103); -#197103 = SURFACE_SIDE_STYLE('',(#197104)); -#197104 = SURFACE_STYLE_FILL_AREA(#197105); -#197105 = FILL_AREA_STYLE('',(#197106)); -#197106 = FILL_AREA_STYLE_COLOUR('',#195083); -#197107 = OVER_RIDING_STYLED_ITEM('overriding color',(#197108),#113688, - #195018); -#197108 = PRESENTATION_STYLE_ASSIGNMENT((#197109)); -#197109 = SURFACE_STYLE_USAGE(.BOTH.,#197110); -#197110 = SURFACE_SIDE_STYLE('',(#197111)); -#197111 = SURFACE_STYLE_FILL_AREA(#197112); -#197112 = FILL_AREA_STYLE('',(#197113)); -#197113 = FILL_AREA_STYLE_COLOUR('',#195083); -#197114 = OVER_RIDING_STYLED_ITEM('overriding color',(#197115),#113763, - #195018); -#197115 = PRESENTATION_STYLE_ASSIGNMENT((#197116)); -#197116 = SURFACE_STYLE_USAGE(.BOTH.,#197117); -#197117 = SURFACE_SIDE_STYLE('',(#197118)); -#197118 = SURFACE_STYLE_FILL_AREA(#197119); -#197119 = FILL_AREA_STYLE('',(#197120)); -#197120 = FILL_AREA_STYLE_COLOUR('',#195083); -#197121 = OVER_RIDING_STYLED_ITEM('overriding color',(#197122),#113838, - #195018); -#197122 = PRESENTATION_STYLE_ASSIGNMENT((#197123)); -#197123 = SURFACE_STYLE_USAGE(.BOTH.,#197124); -#197124 = SURFACE_SIDE_STYLE('',(#197125)); -#197125 = SURFACE_STYLE_FILL_AREA(#197126); -#197126 = FILL_AREA_STYLE('',(#197127)); -#197127 = FILL_AREA_STYLE_COLOUR('',#195083); -#197128 = OVER_RIDING_STYLED_ITEM('overriding color',(#197129),#113935, - #195018); -#197129 = PRESENTATION_STYLE_ASSIGNMENT((#197130)); -#197130 = SURFACE_STYLE_USAGE(.BOTH.,#197131); -#197131 = SURFACE_SIDE_STYLE('',(#197132)); -#197132 = SURFACE_STYLE_FILL_AREA(#197133); -#197133 = FILL_AREA_STYLE('',(#197134)); -#197134 = FILL_AREA_STYLE_COLOUR('',#195083); -#197135 = OVER_RIDING_STYLED_ITEM('overriding color',(#197136),#114055, - #195018); -#197136 = PRESENTATION_STYLE_ASSIGNMENT((#197137)); -#197137 = SURFACE_STYLE_USAGE(.BOTH.,#197138); -#197138 = SURFACE_SIDE_STYLE('',(#197139)); -#197139 = SURFACE_STYLE_FILL_AREA(#197140); -#197140 = FILL_AREA_STYLE('',(#197141)); -#197141 = FILL_AREA_STYLE_COLOUR('',#195083); -#197142 = OVER_RIDING_STYLED_ITEM('overriding color',(#197143),#114102, - #195018); -#197143 = PRESENTATION_STYLE_ASSIGNMENT((#197144)); -#197144 = SURFACE_STYLE_USAGE(.BOTH.,#197145); -#197145 = SURFACE_SIDE_STYLE('',(#197146)); -#197146 = SURFACE_STYLE_FILL_AREA(#197147); -#197147 = FILL_AREA_STYLE('',(#197148)); -#197148 = FILL_AREA_STYLE_COLOUR('',#195083); -#197149 = OVER_RIDING_STYLED_ITEM('overriding color',(#197150),#114157, - #195018); -#197150 = PRESENTATION_STYLE_ASSIGNMENT((#197151)); -#197151 = SURFACE_STYLE_USAGE(.BOTH.,#197152); -#197152 = SURFACE_SIDE_STYLE('',(#197153)); -#197153 = SURFACE_STYLE_FILL_AREA(#197154); -#197154 = FILL_AREA_STYLE('',(#197155)); -#197155 = FILL_AREA_STYLE_COLOUR('',#195083); -#197156 = OVER_RIDING_STYLED_ITEM('overriding color',(#197157),#114184, - #195018); -#197157 = PRESENTATION_STYLE_ASSIGNMENT((#197158)); -#197158 = SURFACE_STYLE_USAGE(.BOTH.,#197159); -#197159 = SURFACE_SIDE_STYLE('',(#197160)); -#197160 = SURFACE_STYLE_FILL_AREA(#197161); -#197161 = FILL_AREA_STYLE('',(#197162)); -#197162 = FILL_AREA_STYLE_COLOUR('',#195083); -#197163 = OVER_RIDING_STYLED_ITEM('overriding color',(#197164),#114219, - #195018); -#197164 = PRESENTATION_STYLE_ASSIGNMENT((#197165)); -#197165 = SURFACE_STYLE_USAGE(.BOTH.,#197166); -#197166 = SURFACE_SIDE_STYLE('',(#197167)); -#197167 = SURFACE_STYLE_FILL_AREA(#197168); -#197168 = FILL_AREA_STYLE('',(#197169)); -#197169 = FILL_AREA_STYLE_COLOUR('',#195083); -#197170 = OVER_RIDING_STYLED_ITEM('overriding color',(#197171),#114226, - #195018); -#197171 = PRESENTATION_STYLE_ASSIGNMENT((#197172)); -#197172 = SURFACE_STYLE_USAGE(.BOTH.,#197173); -#197173 = SURFACE_SIDE_STYLE('',(#197174)); -#197174 = SURFACE_STYLE_FILL_AREA(#197175); -#197175 = FILL_AREA_STYLE('',(#197176)); -#197176 = FILL_AREA_STYLE_COLOUR('',#195083); -#197177 = OVER_RIDING_STYLED_ITEM('overriding color',(#197178),#114335, - #195018); -#197178 = PRESENTATION_STYLE_ASSIGNMENT((#197179)); -#197179 = SURFACE_STYLE_USAGE(.BOTH.,#197180); -#197180 = SURFACE_SIDE_STYLE('',(#197181)); -#197181 = SURFACE_STYLE_FILL_AREA(#197182); -#197182 = FILL_AREA_STYLE('',(#197183)); -#197183 = FILL_AREA_STYLE_COLOUR('',#195083); -#197184 = OVER_RIDING_STYLED_ITEM('overriding color',(#197185),#114439, - #195018); -#197185 = PRESENTATION_STYLE_ASSIGNMENT((#197186)); -#197186 = SURFACE_STYLE_USAGE(.BOTH.,#197187); -#197187 = SURFACE_SIDE_STYLE('',(#197188)); -#197188 = SURFACE_STYLE_FILL_AREA(#197189); -#197189 = FILL_AREA_STYLE('',(#197190)); -#197190 = FILL_AREA_STYLE_COLOUR('',#195083); -#197191 = OVER_RIDING_STYLED_ITEM('overriding color',(#197192),#114518, - #195018); -#197192 = PRESENTATION_STYLE_ASSIGNMENT((#197193)); -#197193 = SURFACE_STYLE_USAGE(.BOTH.,#197194); -#197194 = SURFACE_SIDE_STYLE('',(#197195)); -#197195 = SURFACE_STYLE_FILL_AREA(#197196); -#197196 = FILL_AREA_STYLE('',(#197197)); -#197197 = FILL_AREA_STYLE_COLOUR('',#195083); -#197198 = OVER_RIDING_STYLED_ITEM('overriding color',(#197199),#114597, - #195018); -#197199 = PRESENTATION_STYLE_ASSIGNMENT((#197200)); -#197200 = SURFACE_STYLE_USAGE(.BOTH.,#197201); -#197201 = SURFACE_SIDE_STYLE('',(#197202)); -#197202 = SURFACE_STYLE_FILL_AREA(#197203); -#197203 = FILL_AREA_STYLE('',(#197204)); -#197204 = FILL_AREA_STYLE_COLOUR('',#195083); -#197205 = OVER_RIDING_STYLED_ITEM('overriding color',(#197206),#114672, - #195018); -#197206 = PRESENTATION_STYLE_ASSIGNMENT((#197207)); -#197207 = SURFACE_STYLE_USAGE(.BOTH.,#197208); -#197208 = SURFACE_SIDE_STYLE('',(#197209)); -#197209 = SURFACE_STYLE_FILL_AREA(#197210); -#197210 = FILL_AREA_STYLE('',(#197211)); -#197211 = FILL_AREA_STYLE_COLOUR('',#195083); -#197212 = OVER_RIDING_STYLED_ITEM('overriding color',(#197213),#114747, - #195018); -#197213 = PRESENTATION_STYLE_ASSIGNMENT((#197214)); -#197214 = SURFACE_STYLE_USAGE(.BOTH.,#197215); -#197215 = SURFACE_SIDE_STYLE('',(#197216)); -#197216 = SURFACE_STYLE_FILL_AREA(#197217); -#197217 = FILL_AREA_STYLE('',(#197218)); -#197218 = FILL_AREA_STYLE_COLOUR('',#195083); -#197219 = OVER_RIDING_STYLED_ITEM('overriding color',(#197220),#114844, - #195018); -#197220 = PRESENTATION_STYLE_ASSIGNMENT((#197221)); -#197221 = SURFACE_STYLE_USAGE(.BOTH.,#197222); -#197222 = SURFACE_SIDE_STYLE('',(#197223)); -#197223 = SURFACE_STYLE_FILL_AREA(#197224); -#197224 = FILL_AREA_STYLE('',(#197225)); -#197225 = FILL_AREA_STYLE_COLOUR('',#195083); -#197226 = OVER_RIDING_STYLED_ITEM('overriding color',(#197227),#114941, - #195018); -#197227 = PRESENTATION_STYLE_ASSIGNMENT((#197228)); -#197228 = SURFACE_STYLE_USAGE(.BOTH.,#197229); -#197229 = SURFACE_SIDE_STYLE('',(#197230)); -#197230 = SURFACE_STYLE_FILL_AREA(#197231); -#197231 = FILL_AREA_STYLE('',(#197232)); -#197232 = FILL_AREA_STYLE_COLOUR('',#195083); -#197233 = OVER_RIDING_STYLED_ITEM('overriding color',(#197234),#114988, - #195018); -#197234 = PRESENTATION_STYLE_ASSIGNMENT((#197235)); -#197235 = SURFACE_STYLE_USAGE(.BOTH.,#197236); -#197236 = SURFACE_SIDE_STYLE('',(#197237)); -#197237 = SURFACE_STYLE_FILL_AREA(#197238); -#197238 = FILL_AREA_STYLE('',(#197239)); -#197239 = FILL_AREA_STYLE_COLOUR('',#195083); -#197240 = OVER_RIDING_STYLED_ITEM('overriding color',(#197241),#115043, - #195018); -#197241 = PRESENTATION_STYLE_ASSIGNMENT((#197242)); -#197242 = SURFACE_STYLE_USAGE(.BOTH.,#197243); -#197243 = SURFACE_SIDE_STYLE('',(#197244)); -#197244 = SURFACE_STYLE_FILL_AREA(#197245); -#197245 = FILL_AREA_STYLE('',(#197246)); -#197246 = FILL_AREA_STYLE_COLOUR('',#195083); -#197247 = OVER_RIDING_STYLED_ITEM('overriding color',(#197248),#115070, - #195018); -#197248 = PRESENTATION_STYLE_ASSIGNMENT((#197249)); -#197249 = SURFACE_STYLE_USAGE(.BOTH.,#197250); -#197250 = SURFACE_SIDE_STYLE('',(#197251)); -#197251 = SURFACE_STYLE_FILL_AREA(#197252); -#197252 = FILL_AREA_STYLE('',(#197253)); -#197253 = FILL_AREA_STYLE_COLOUR('',#195083); -#197254 = OVER_RIDING_STYLED_ITEM('overriding color',(#197255),#115105, - #195018); -#197255 = PRESENTATION_STYLE_ASSIGNMENT((#197256)); -#197256 = SURFACE_STYLE_USAGE(.BOTH.,#197257); -#197257 = SURFACE_SIDE_STYLE('',(#197258)); -#197258 = SURFACE_STYLE_FILL_AREA(#197259); -#197259 = FILL_AREA_STYLE('',(#197260)); -#197260 = FILL_AREA_STYLE_COLOUR('',#195083); -#197261 = OVER_RIDING_STYLED_ITEM('overriding color',(#197262),#115112, - #195018); -#197262 = PRESENTATION_STYLE_ASSIGNMENT((#197263)); -#197263 = SURFACE_STYLE_USAGE(.BOTH.,#197264); -#197264 = SURFACE_SIDE_STYLE('',(#197265)); -#197265 = SURFACE_STYLE_FILL_AREA(#197266); -#197266 = FILL_AREA_STYLE('',(#197267)); -#197267 = FILL_AREA_STYLE_COLOUR('',#195083); -#197268 = OVER_RIDING_STYLED_ITEM('overriding color',(#197269),#115221, - #195018); -#197269 = PRESENTATION_STYLE_ASSIGNMENT((#197270)); -#197270 = SURFACE_STYLE_USAGE(.BOTH.,#197271); -#197271 = SURFACE_SIDE_STYLE('',(#197272)); -#197272 = SURFACE_STYLE_FILL_AREA(#197273); -#197273 = FILL_AREA_STYLE('',(#197274)); -#197274 = FILL_AREA_STYLE_COLOUR('',#195083); -#197275 = OVER_RIDING_STYLED_ITEM('overriding color',(#197276),#115325, - #195018); -#197276 = PRESENTATION_STYLE_ASSIGNMENT((#197277)); -#197277 = SURFACE_STYLE_USAGE(.BOTH.,#197278); -#197278 = SURFACE_SIDE_STYLE('',(#197279)); -#197279 = SURFACE_STYLE_FILL_AREA(#197280); -#197280 = FILL_AREA_STYLE('',(#197281)); -#197281 = FILL_AREA_STYLE_COLOUR('',#195083); -#197282 = OVER_RIDING_STYLED_ITEM('overriding color',(#197283),#115404, - #195018); -#197283 = PRESENTATION_STYLE_ASSIGNMENT((#197284)); -#197284 = SURFACE_STYLE_USAGE(.BOTH.,#197285); -#197285 = SURFACE_SIDE_STYLE('',(#197286)); -#197286 = SURFACE_STYLE_FILL_AREA(#197287); -#197287 = FILL_AREA_STYLE('',(#197288)); -#197288 = FILL_AREA_STYLE_COLOUR('',#195083); -#197289 = OVER_RIDING_STYLED_ITEM('overriding color',(#197290),#115483, - #195018); -#197290 = PRESENTATION_STYLE_ASSIGNMENT((#197291)); -#197291 = SURFACE_STYLE_USAGE(.BOTH.,#197292); -#197292 = SURFACE_SIDE_STYLE('',(#197293)); -#197293 = SURFACE_STYLE_FILL_AREA(#197294); -#197294 = FILL_AREA_STYLE('',(#197295)); -#197295 = FILL_AREA_STYLE_COLOUR('',#195083); -#197296 = OVER_RIDING_STYLED_ITEM('overriding color',(#197297),#115558, - #195018); -#197297 = PRESENTATION_STYLE_ASSIGNMENT((#197298)); -#197298 = SURFACE_STYLE_USAGE(.BOTH.,#197299); -#197299 = SURFACE_SIDE_STYLE('',(#197300)); -#197300 = SURFACE_STYLE_FILL_AREA(#197301); -#197301 = FILL_AREA_STYLE('',(#197302)); -#197302 = FILL_AREA_STYLE_COLOUR('',#195083); -#197303 = OVER_RIDING_STYLED_ITEM('overriding color',(#197304),#115633, - #195018); -#197304 = PRESENTATION_STYLE_ASSIGNMENT((#197305)); -#197305 = SURFACE_STYLE_USAGE(.BOTH.,#197306); -#197306 = SURFACE_SIDE_STYLE('',(#197307)); -#197307 = SURFACE_STYLE_FILL_AREA(#197308); -#197308 = FILL_AREA_STYLE('',(#197309)); -#197309 = FILL_AREA_STYLE_COLOUR('',#195083); -#197310 = OVER_RIDING_STYLED_ITEM('overriding color',(#197311),#115730, - #195018); -#197311 = PRESENTATION_STYLE_ASSIGNMENT((#197312)); -#197312 = SURFACE_STYLE_USAGE(.BOTH.,#197313); -#197313 = SURFACE_SIDE_STYLE('',(#197314)); -#197314 = SURFACE_STYLE_FILL_AREA(#197315); -#197315 = FILL_AREA_STYLE('',(#197316)); -#197316 = FILL_AREA_STYLE_COLOUR('',#195083); -#197317 = OVER_RIDING_STYLED_ITEM('overriding color',(#197318),#115827, - #195018); -#197318 = PRESENTATION_STYLE_ASSIGNMENT((#197319)); -#197319 = SURFACE_STYLE_USAGE(.BOTH.,#197320); -#197320 = SURFACE_SIDE_STYLE('',(#197321)); -#197321 = SURFACE_STYLE_FILL_AREA(#197322); -#197322 = FILL_AREA_STYLE('',(#197323)); -#197323 = FILL_AREA_STYLE_COLOUR('',#195083); -#197324 = OVER_RIDING_STYLED_ITEM('overriding color',(#197325),#115874, - #195018); -#197325 = PRESENTATION_STYLE_ASSIGNMENT((#197326)); -#197326 = SURFACE_STYLE_USAGE(.BOTH.,#197327); -#197327 = SURFACE_SIDE_STYLE('',(#197328)); -#197328 = SURFACE_STYLE_FILL_AREA(#197329); -#197329 = FILL_AREA_STYLE('',(#197330)); -#197330 = FILL_AREA_STYLE_COLOUR('',#195083); -#197331 = OVER_RIDING_STYLED_ITEM('overriding color',(#197332),#115929, - #195018); -#197332 = PRESENTATION_STYLE_ASSIGNMENT((#197333)); -#197333 = SURFACE_STYLE_USAGE(.BOTH.,#197334); -#197334 = SURFACE_SIDE_STYLE('',(#197335)); -#197335 = SURFACE_STYLE_FILL_AREA(#197336); -#197336 = FILL_AREA_STYLE('',(#197337)); -#197337 = FILL_AREA_STYLE_COLOUR('',#195083); -#197338 = OVER_RIDING_STYLED_ITEM('overriding color',(#197339),#115956, - #195018); -#197339 = PRESENTATION_STYLE_ASSIGNMENT((#197340)); -#197340 = SURFACE_STYLE_USAGE(.BOTH.,#197341); -#197341 = SURFACE_SIDE_STYLE('',(#197342)); -#197342 = SURFACE_STYLE_FILL_AREA(#197343); -#197343 = FILL_AREA_STYLE('',(#197344)); -#197344 = FILL_AREA_STYLE_COLOUR('',#195083); -#197345 = OVER_RIDING_STYLED_ITEM('overriding color',(#197346),#115991, - #195018); -#197346 = PRESENTATION_STYLE_ASSIGNMENT((#197347)); -#197347 = SURFACE_STYLE_USAGE(.BOTH.,#197348); -#197348 = SURFACE_SIDE_STYLE('',(#197349)); -#197349 = SURFACE_STYLE_FILL_AREA(#197350); -#197350 = FILL_AREA_STYLE('',(#197351)); -#197351 = FILL_AREA_STYLE_COLOUR('',#195083); -#197352 = OVER_RIDING_STYLED_ITEM('overriding color',(#197353),#115998, - #195018); -#197353 = PRESENTATION_STYLE_ASSIGNMENT((#197354)); -#197354 = SURFACE_STYLE_USAGE(.BOTH.,#197355); -#197355 = SURFACE_SIDE_STYLE('',(#197356)); -#197356 = SURFACE_STYLE_FILL_AREA(#197357); -#197357 = FILL_AREA_STYLE('',(#197358)); -#197358 = FILL_AREA_STYLE_COLOUR('',#195083); -#197359 = OVER_RIDING_STYLED_ITEM('overriding color',(#197360),#116107, - #195018); -#197360 = PRESENTATION_STYLE_ASSIGNMENT((#197361)); -#197361 = SURFACE_STYLE_USAGE(.BOTH.,#197362); -#197362 = SURFACE_SIDE_STYLE('',(#197363)); -#197363 = SURFACE_STYLE_FILL_AREA(#197364); -#197364 = FILL_AREA_STYLE('',(#197365)); -#197365 = FILL_AREA_STYLE_COLOUR('',#195083); -#197366 = OVER_RIDING_STYLED_ITEM('overriding color',(#197367),#116211, - #195018); -#197367 = PRESENTATION_STYLE_ASSIGNMENT((#197368)); -#197368 = SURFACE_STYLE_USAGE(.BOTH.,#197369); -#197369 = SURFACE_SIDE_STYLE('',(#197370)); -#197370 = SURFACE_STYLE_FILL_AREA(#197371); -#197371 = FILL_AREA_STYLE('',(#197372)); -#197372 = FILL_AREA_STYLE_COLOUR('',#195083); -#197373 = OVER_RIDING_STYLED_ITEM('overriding color',(#197374),#116290, - #195018); -#197374 = PRESENTATION_STYLE_ASSIGNMENT((#197375)); -#197375 = SURFACE_STYLE_USAGE(.BOTH.,#197376); -#197376 = SURFACE_SIDE_STYLE('',(#197377)); -#197377 = SURFACE_STYLE_FILL_AREA(#197378); -#197378 = FILL_AREA_STYLE('',(#197379)); -#197379 = FILL_AREA_STYLE_COLOUR('',#195083); -#197380 = OVER_RIDING_STYLED_ITEM('overriding color',(#197381),#116369, - #195018); -#197381 = PRESENTATION_STYLE_ASSIGNMENT((#197382)); -#197382 = SURFACE_STYLE_USAGE(.BOTH.,#197383); -#197383 = SURFACE_SIDE_STYLE('',(#197384)); -#197384 = SURFACE_STYLE_FILL_AREA(#197385); -#197385 = FILL_AREA_STYLE('',(#197386)); -#197386 = FILL_AREA_STYLE_COLOUR('',#195083); -#197387 = OVER_RIDING_STYLED_ITEM('overriding color',(#197388),#116444, - #195018); -#197388 = PRESENTATION_STYLE_ASSIGNMENT((#197389)); -#197389 = SURFACE_STYLE_USAGE(.BOTH.,#197390); -#197390 = SURFACE_SIDE_STYLE('',(#197391)); -#197391 = SURFACE_STYLE_FILL_AREA(#197392); -#197392 = FILL_AREA_STYLE('',(#197393)); -#197393 = FILL_AREA_STYLE_COLOUR('',#195083); -#197394 = OVER_RIDING_STYLED_ITEM('overriding color',(#197395),#116519, - #195018); -#197395 = PRESENTATION_STYLE_ASSIGNMENT((#197396)); -#197396 = SURFACE_STYLE_USAGE(.BOTH.,#197397); -#197397 = SURFACE_SIDE_STYLE('',(#197398)); -#197398 = SURFACE_STYLE_FILL_AREA(#197399); -#197399 = FILL_AREA_STYLE('',(#197400)); -#197400 = FILL_AREA_STYLE_COLOUR('',#195083); -#197401 = OVER_RIDING_STYLED_ITEM('overriding color',(#197402),#116616, - #195018); -#197402 = PRESENTATION_STYLE_ASSIGNMENT((#197403)); -#197403 = SURFACE_STYLE_USAGE(.BOTH.,#197404); -#197404 = SURFACE_SIDE_STYLE('',(#197405)); -#197405 = SURFACE_STYLE_FILL_AREA(#197406); -#197406 = FILL_AREA_STYLE('',(#197407)); -#197407 = FILL_AREA_STYLE_COLOUR('',#195083); -#197408 = OVER_RIDING_STYLED_ITEM('overriding color',(#197409),#116713, - #195018); -#197409 = PRESENTATION_STYLE_ASSIGNMENT((#197410)); -#197410 = SURFACE_STYLE_USAGE(.BOTH.,#197411); -#197411 = SURFACE_SIDE_STYLE('',(#197412)); -#197412 = SURFACE_STYLE_FILL_AREA(#197413); -#197413 = FILL_AREA_STYLE('',(#197414)); -#197414 = FILL_AREA_STYLE_COLOUR('',#195083); -#197415 = OVER_RIDING_STYLED_ITEM('overriding color',(#197416),#116760, - #195018); -#197416 = PRESENTATION_STYLE_ASSIGNMENT((#197417)); -#197417 = SURFACE_STYLE_USAGE(.BOTH.,#197418); -#197418 = SURFACE_SIDE_STYLE('',(#197419)); -#197419 = SURFACE_STYLE_FILL_AREA(#197420); -#197420 = FILL_AREA_STYLE('',(#197421)); -#197421 = FILL_AREA_STYLE_COLOUR('',#195083); -#197422 = OVER_RIDING_STYLED_ITEM('overriding color',(#197423),#116815, - #195018); -#197423 = PRESENTATION_STYLE_ASSIGNMENT((#197424)); -#197424 = SURFACE_STYLE_USAGE(.BOTH.,#197425); -#197425 = SURFACE_SIDE_STYLE('',(#197426)); -#197426 = SURFACE_STYLE_FILL_AREA(#197427); -#197427 = FILL_AREA_STYLE('',(#197428)); -#197428 = FILL_AREA_STYLE_COLOUR('',#195083); -#197429 = OVER_RIDING_STYLED_ITEM('overriding color',(#197430),#116842, - #195018); -#197430 = PRESENTATION_STYLE_ASSIGNMENT((#197431)); -#197431 = SURFACE_STYLE_USAGE(.BOTH.,#197432); -#197432 = SURFACE_SIDE_STYLE('',(#197433)); -#197433 = SURFACE_STYLE_FILL_AREA(#197434); -#197434 = FILL_AREA_STYLE('',(#197435)); -#197435 = FILL_AREA_STYLE_COLOUR('',#195083); -#197436 = OVER_RIDING_STYLED_ITEM('overriding color',(#197437),#116877, - #195018); -#197437 = PRESENTATION_STYLE_ASSIGNMENT((#197438)); -#197438 = SURFACE_STYLE_USAGE(.BOTH.,#197439); -#197439 = SURFACE_SIDE_STYLE('',(#197440)); -#197440 = SURFACE_STYLE_FILL_AREA(#197441); -#197441 = FILL_AREA_STYLE('',(#197442)); -#197442 = FILL_AREA_STYLE_COLOUR('',#195083); -#197443 = OVER_RIDING_STYLED_ITEM('overriding color',(#197444),#116884, - #195018); -#197444 = PRESENTATION_STYLE_ASSIGNMENT((#197445)); -#197445 = SURFACE_STYLE_USAGE(.BOTH.,#197446); -#197446 = SURFACE_SIDE_STYLE('',(#197447)); -#197447 = SURFACE_STYLE_FILL_AREA(#197448); -#197448 = FILL_AREA_STYLE('',(#197449)); -#197449 = FILL_AREA_STYLE_COLOUR('',#195083); -#197450 = OVER_RIDING_STYLED_ITEM('overriding color',(#197451),#116993, - #195018); -#197451 = PRESENTATION_STYLE_ASSIGNMENT((#197452)); -#197452 = SURFACE_STYLE_USAGE(.BOTH.,#197453); -#197453 = SURFACE_SIDE_STYLE('',(#197454)); -#197454 = SURFACE_STYLE_FILL_AREA(#197455); -#197455 = FILL_AREA_STYLE('',(#197456)); -#197456 = FILL_AREA_STYLE_COLOUR('',#195083); -#197457 = OVER_RIDING_STYLED_ITEM('overriding color',(#197458),#117097, - #195018); -#197458 = PRESENTATION_STYLE_ASSIGNMENT((#197459)); -#197459 = SURFACE_STYLE_USAGE(.BOTH.,#197460); -#197460 = SURFACE_SIDE_STYLE('',(#197461)); -#197461 = SURFACE_STYLE_FILL_AREA(#197462); -#197462 = FILL_AREA_STYLE('',(#197463)); -#197463 = FILL_AREA_STYLE_COLOUR('',#195083); -#197464 = OVER_RIDING_STYLED_ITEM('overriding color',(#197465),#117176, - #195018); -#197465 = PRESENTATION_STYLE_ASSIGNMENT((#197466)); -#197466 = SURFACE_STYLE_USAGE(.BOTH.,#197467); -#197467 = SURFACE_SIDE_STYLE('',(#197468)); -#197468 = SURFACE_STYLE_FILL_AREA(#197469); -#197469 = FILL_AREA_STYLE('',(#197470)); -#197470 = FILL_AREA_STYLE_COLOUR('',#195083); -#197471 = OVER_RIDING_STYLED_ITEM('overriding color',(#197472),#117255, - #195018); -#197472 = PRESENTATION_STYLE_ASSIGNMENT((#197473)); -#197473 = SURFACE_STYLE_USAGE(.BOTH.,#197474); -#197474 = SURFACE_SIDE_STYLE('',(#197475)); -#197475 = SURFACE_STYLE_FILL_AREA(#197476); -#197476 = FILL_AREA_STYLE('',(#197477)); -#197477 = FILL_AREA_STYLE_COLOUR('',#195083); -#197478 = OVER_RIDING_STYLED_ITEM('overriding color',(#197479),#117330, - #195018); -#197479 = PRESENTATION_STYLE_ASSIGNMENT((#197480)); -#197480 = SURFACE_STYLE_USAGE(.BOTH.,#197481); -#197481 = SURFACE_SIDE_STYLE('',(#197482)); -#197482 = SURFACE_STYLE_FILL_AREA(#197483); -#197483 = FILL_AREA_STYLE('',(#197484)); -#197484 = FILL_AREA_STYLE_COLOUR('',#195083); -#197485 = OVER_RIDING_STYLED_ITEM('overriding color',(#197486),#117405, - #195018); -#197486 = PRESENTATION_STYLE_ASSIGNMENT((#197487)); -#197487 = SURFACE_STYLE_USAGE(.BOTH.,#197488); -#197488 = SURFACE_SIDE_STYLE('',(#197489)); -#197489 = SURFACE_STYLE_FILL_AREA(#197490); -#197490 = FILL_AREA_STYLE('',(#197491)); -#197491 = FILL_AREA_STYLE_COLOUR('',#195083); -#197492 = OVER_RIDING_STYLED_ITEM('overriding color',(#197493),#117502, - #195018); -#197493 = PRESENTATION_STYLE_ASSIGNMENT((#197494)); -#197494 = SURFACE_STYLE_USAGE(.BOTH.,#197495); -#197495 = SURFACE_SIDE_STYLE('',(#197496)); -#197496 = SURFACE_STYLE_FILL_AREA(#197497); -#197497 = FILL_AREA_STYLE('',(#197498)); -#197498 = FILL_AREA_STYLE_COLOUR('',#195083); -#197499 = OVER_RIDING_STYLED_ITEM('overriding color',(#197500),#117599, - #195018); -#197500 = PRESENTATION_STYLE_ASSIGNMENT((#197501)); -#197501 = SURFACE_STYLE_USAGE(.BOTH.,#197502); -#197502 = SURFACE_SIDE_STYLE('',(#197503)); -#197503 = SURFACE_STYLE_FILL_AREA(#197504); -#197504 = FILL_AREA_STYLE('',(#197505)); -#197505 = FILL_AREA_STYLE_COLOUR('',#195083); -#197506 = OVER_RIDING_STYLED_ITEM('overriding color',(#197507),#117646, - #195018); -#197507 = PRESENTATION_STYLE_ASSIGNMENT((#197508)); -#197508 = SURFACE_STYLE_USAGE(.BOTH.,#197509); -#197509 = SURFACE_SIDE_STYLE('',(#197510)); -#197510 = SURFACE_STYLE_FILL_AREA(#197511); -#197511 = FILL_AREA_STYLE('',(#197512)); -#197512 = FILL_AREA_STYLE_COLOUR('',#195083); -#197513 = OVER_RIDING_STYLED_ITEM('overriding color',(#197514),#117701, - #195018); -#197514 = PRESENTATION_STYLE_ASSIGNMENT((#197515)); -#197515 = SURFACE_STYLE_USAGE(.BOTH.,#197516); -#197516 = SURFACE_SIDE_STYLE('',(#197517)); -#197517 = SURFACE_STYLE_FILL_AREA(#197518); -#197518 = FILL_AREA_STYLE('',(#197519)); -#197519 = FILL_AREA_STYLE_COLOUR('',#195083); -#197520 = OVER_RIDING_STYLED_ITEM('overriding color',(#197521),#117728, - #195018); -#197521 = PRESENTATION_STYLE_ASSIGNMENT((#197522)); -#197522 = SURFACE_STYLE_USAGE(.BOTH.,#197523); -#197523 = SURFACE_SIDE_STYLE('',(#197524)); -#197524 = SURFACE_STYLE_FILL_AREA(#197525); -#197525 = FILL_AREA_STYLE('',(#197526)); -#197526 = FILL_AREA_STYLE_COLOUR('',#195083); -#197527 = OVER_RIDING_STYLED_ITEM('overriding color',(#197528),#117763, - #195018); -#197528 = PRESENTATION_STYLE_ASSIGNMENT((#197529)); -#197529 = SURFACE_STYLE_USAGE(.BOTH.,#197530); -#197530 = SURFACE_SIDE_STYLE('',(#197531)); -#197531 = SURFACE_STYLE_FILL_AREA(#197532); -#197532 = FILL_AREA_STYLE('',(#197533)); -#197533 = FILL_AREA_STYLE_COLOUR('',#195083); -#197534 = OVER_RIDING_STYLED_ITEM('overriding color',(#197535),#117770, - #195018); -#197535 = PRESENTATION_STYLE_ASSIGNMENT((#197536)); -#197536 = SURFACE_STYLE_USAGE(.BOTH.,#197537); -#197537 = SURFACE_SIDE_STYLE('',(#197538)); -#197538 = SURFACE_STYLE_FILL_AREA(#197539); -#197539 = FILL_AREA_STYLE('',(#197540)); -#197540 = FILL_AREA_STYLE_COLOUR('',#195083); -#197541 = OVER_RIDING_STYLED_ITEM('overriding color',(#197542),#117879, - #195018); -#197542 = PRESENTATION_STYLE_ASSIGNMENT((#197543)); -#197543 = SURFACE_STYLE_USAGE(.BOTH.,#197544); -#197544 = SURFACE_SIDE_STYLE('',(#197545)); -#197545 = SURFACE_STYLE_FILL_AREA(#197546); -#197546 = FILL_AREA_STYLE('',(#197547)); -#197547 = FILL_AREA_STYLE_COLOUR('',#195083); -#197548 = OVER_RIDING_STYLED_ITEM('overriding color',(#197549),#117983, - #195018); -#197549 = PRESENTATION_STYLE_ASSIGNMENT((#197550)); -#197550 = SURFACE_STYLE_USAGE(.BOTH.,#197551); -#197551 = SURFACE_SIDE_STYLE('',(#197552)); -#197552 = SURFACE_STYLE_FILL_AREA(#197553); -#197553 = FILL_AREA_STYLE('',(#197554)); -#197554 = FILL_AREA_STYLE_COLOUR('',#195083); -#197555 = OVER_RIDING_STYLED_ITEM('overriding color',(#197556),#118062, - #195018); -#197556 = PRESENTATION_STYLE_ASSIGNMENT((#197557)); -#197557 = SURFACE_STYLE_USAGE(.BOTH.,#197558); -#197558 = SURFACE_SIDE_STYLE('',(#197559)); -#197559 = SURFACE_STYLE_FILL_AREA(#197560); -#197560 = FILL_AREA_STYLE('',(#197561)); -#197561 = FILL_AREA_STYLE_COLOUR('',#195083); -#197562 = OVER_RIDING_STYLED_ITEM('overriding color',(#197563),#118141, - #195018); -#197563 = PRESENTATION_STYLE_ASSIGNMENT((#197564)); -#197564 = SURFACE_STYLE_USAGE(.BOTH.,#197565); -#197565 = SURFACE_SIDE_STYLE('',(#197566)); -#197566 = SURFACE_STYLE_FILL_AREA(#197567); -#197567 = FILL_AREA_STYLE('',(#197568)); -#197568 = FILL_AREA_STYLE_COLOUR('',#195083); -#197569 = OVER_RIDING_STYLED_ITEM('overriding color',(#197570),#118216, - #195018); -#197570 = PRESENTATION_STYLE_ASSIGNMENT((#197571)); -#197571 = SURFACE_STYLE_USAGE(.BOTH.,#197572); -#197572 = SURFACE_SIDE_STYLE('',(#197573)); -#197573 = SURFACE_STYLE_FILL_AREA(#197574); -#197574 = FILL_AREA_STYLE('',(#197575)); -#197575 = FILL_AREA_STYLE_COLOUR('',#195083); -#197576 = OVER_RIDING_STYLED_ITEM('overriding color',(#197577),#118291, - #195018); -#197577 = PRESENTATION_STYLE_ASSIGNMENT((#197578)); -#197578 = SURFACE_STYLE_USAGE(.BOTH.,#197579); -#197579 = SURFACE_SIDE_STYLE('',(#197580)); -#197580 = SURFACE_STYLE_FILL_AREA(#197581); -#197581 = FILL_AREA_STYLE('',(#197582)); -#197582 = FILL_AREA_STYLE_COLOUR('',#195083); -#197583 = OVER_RIDING_STYLED_ITEM('overriding color',(#197584),#118388, - #195018); -#197584 = PRESENTATION_STYLE_ASSIGNMENT((#197585)); -#197585 = SURFACE_STYLE_USAGE(.BOTH.,#197586); -#197586 = SURFACE_SIDE_STYLE('',(#197587)); -#197587 = SURFACE_STYLE_FILL_AREA(#197588); -#197588 = FILL_AREA_STYLE('',(#197589)); -#197589 = FILL_AREA_STYLE_COLOUR('',#195083); -#197590 = OVER_RIDING_STYLED_ITEM('overriding color',(#197591),#118485, - #195018); -#197591 = PRESENTATION_STYLE_ASSIGNMENT((#197592)); -#197592 = SURFACE_STYLE_USAGE(.BOTH.,#197593); -#197593 = SURFACE_SIDE_STYLE('',(#197594)); -#197594 = SURFACE_STYLE_FILL_AREA(#197595); -#197595 = FILL_AREA_STYLE('',(#197596)); -#197596 = FILL_AREA_STYLE_COLOUR('',#195083); -#197597 = OVER_RIDING_STYLED_ITEM('overriding color',(#197598),#118532, - #195018); -#197598 = PRESENTATION_STYLE_ASSIGNMENT((#197599)); -#197599 = SURFACE_STYLE_USAGE(.BOTH.,#197600); -#197600 = SURFACE_SIDE_STYLE('',(#197601)); -#197601 = SURFACE_STYLE_FILL_AREA(#197602); -#197602 = FILL_AREA_STYLE('',(#197603)); -#197603 = FILL_AREA_STYLE_COLOUR('',#195083); -#197604 = OVER_RIDING_STYLED_ITEM('overriding color',(#197605),#118587, - #195018); -#197605 = PRESENTATION_STYLE_ASSIGNMENT((#197606)); -#197606 = SURFACE_STYLE_USAGE(.BOTH.,#197607); -#197607 = SURFACE_SIDE_STYLE('',(#197608)); -#197608 = SURFACE_STYLE_FILL_AREA(#197609); -#197609 = FILL_AREA_STYLE('',(#197610)); -#197610 = FILL_AREA_STYLE_COLOUR('',#195083); -#197611 = OVER_RIDING_STYLED_ITEM('overriding color',(#197612),#118614, - #195018); -#197612 = PRESENTATION_STYLE_ASSIGNMENT((#197613)); -#197613 = SURFACE_STYLE_USAGE(.BOTH.,#197614); -#197614 = SURFACE_SIDE_STYLE('',(#197615)); -#197615 = SURFACE_STYLE_FILL_AREA(#197616); -#197616 = FILL_AREA_STYLE('',(#197617)); -#197617 = FILL_AREA_STYLE_COLOUR('',#195083); -#197618 = OVER_RIDING_STYLED_ITEM('overriding color',(#197619),#118649, - #195018); -#197619 = PRESENTATION_STYLE_ASSIGNMENT((#197620)); -#197620 = SURFACE_STYLE_USAGE(.BOTH.,#197621); -#197621 = SURFACE_SIDE_STYLE('',(#197622)); -#197622 = SURFACE_STYLE_FILL_AREA(#197623); -#197623 = FILL_AREA_STYLE('',(#197624)); -#197624 = FILL_AREA_STYLE_COLOUR('',#195083); -#197625 = OVER_RIDING_STYLED_ITEM('overriding color',(#197626),#118656, - #195018); -#197626 = PRESENTATION_STYLE_ASSIGNMENT((#197627)); -#197627 = SURFACE_STYLE_USAGE(.BOTH.,#197628); -#197628 = SURFACE_SIDE_STYLE('',(#197629)); -#197629 = SURFACE_STYLE_FILL_AREA(#197630); -#197630 = FILL_AREA_STYLE('',(#197631)); -#197631 = FILL_AREA_STYLE_COLOUR('',#195083); -#197632 = OVER_RIDING_STYLED_ITEM('overriding color',(#197633),#118765, - #195018); -#197633 = PRESENTATION_STYLE_ASSIGNMENT((#197634)); -#197634 = SURFACE_STYLE_USAGE(.BOTH.,#197635); -#197635 = SURFACE_SIDE_STYLE('',(#197636)); -#197636 = SURFACE_STYLE_FILL_AREA(#197637); -#197637 = FILL_AREA_STYLE('',(#197638)); -#197638 = FILL_AREA_STYLE_COLOUR('',#195083); -#197639 = OVER_RIDING_STYLED_ITEM('overriding color',(#197640),#118869, - #195018); -#197640 = PRESENTATION_STYLE_ASSIGNMENT((#197641)); -#197641 = SURFACE_STYLE_USAGE(.BOTH.,#197642); -#197642 = SURFACE_SIDE_STYLE('',(#197643)); -#197643 = SURFACE_STYLE_FILL_AREA(#197644); -#197644 = FILL_AREA_STYLE('',(#197645)); -#197645 = FILL_AREA_STYLE_COLOUR('',#195083); -#197646 = OVER_RIDING_STYLED_ITEM('overriding color',(#197647),#118948, - #195018); -#197647 = PRESENTATION_STYLE_ASSIGNMENT((#197648)); -#197648 = SURFACE_STYLE_USAGE(.BOTH.,#197649); -#197649 = SURFACE_SIDE_STYLE('',(#197650)); -#197650 = SURFACE_STYLE_FILL_AREA(#197651); -#197651 = FILL_AREA_STYLE('',(#197652)); -#197652 = FILL_AREA_STYLE_COLOUR('',#195083); -#197653 = OVER_RIDING_STYLED_ITEM('overriding color',(#197654),#119027, - #195018); -#197654 = PRESENTATION_STYLE_ASSIGNMENT((#197655)); -#197655 = SURFACE_STYLE_USAGE(.BOTH.,#197656); -#197656 = SURFACE_SIDE_STYLE('',(#197657)); -#197657 = SURFACE_STYLE_FILL_AREA(#197658); -#197658 = FILL_AREA_STYLE('',(#197659)); -#197659 = FILL_AREA_STYLE_COLOUR('',#195083); -#197660 = OVER_RIDING_STYLED_ITEM('overriding color',(#197661),#119102, - #195018); -#197661 = PRESENTATION_STYLE_ASSIGNMENT((#197662)); -#197662 = SURFACE_STYLE_USAGE(.BOTH.,#197663); -#197663 = SURFACE_SIDE_STYLE('',(#197664)); -#197664 = SURFACE_STYLE_FILL_AREA(#197665); -#197665 = FILL_AREA_STYLE('',(#197666)); -#197666 = FILL_AREA_STYLE_COLOUR('',#195083); -#197667 = OVER_RIDING_STYLED_ITEM('overriding color',(#197668),#119177, - #195018); -#197668 = PRESENTATION_STYLE_ASSIGNMENT((#197669)); -#197669 = SURFACE_STYLE_USAGE(.BOTH.,#197670); -#197670 = SURFACE_SIDE_STYLE('',(#197671)); -#197671 = SURFACE_STYLE_FILL_AREA(#197672); -#197672 = FILL_AREA_STYLE('',(#197673)); -#197673 = FILL_AREA_STYLE_COLOUR('',#195083); -#197674 = OVER_RIDING_STYLED_ITEM('overriding color',(#197675),#119274, - #195018); -#197675 = PRESENTATION_STYLE_ASSIGNMENT((#197676)); +#197405 = ITEM_DEFINED_TRANSFORMATION('','',#11,#323); +#197406 = PRODUCT_DEFINITION_SHAPE('Placement','Placement of an item', + #197407); +#197407 = NEXT_ASSEMBLY_USAGE_OCCURRENCE('432','=>[0:1:1:120]','',#5, + #197016,$); +#197408 = PRODUCT_RELATED_PRODUCT_CATEGORY('part',$,(#197018)); +#197409 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #197410,#197418,#197426,#197433,#197441,#197448,#197455,#197462, + #197469,#197476,#197483,#197490,#197497,#197504,#197511,#197518, + #197525,#197532,#197539,#197546,#197553,#197560,#197567,#197574, + #197581,#197588,#197595,#197602,#197609,#197616,#197623,#197631, + #197638,#197645,#197652,#197659,#197666),#9847); +#197410 = STYLED_ITEM('color',(#197411),#7465); +#197411 = PRESENTATION_STYLE_ASSIGNMENT((#197412)); +#197412 = SURFACE_STYLE_USAGE(.BOTH.,#197413); +#197413 = SURFACE_SIDE_STYLE('',(#197414)); +#197414 = SURFACE_STYLE_FILL_AREA(#197415); +#197415 = FILL_AREA_STYLE('',(#197416)); +#197416 = FILL_AREA_STYLE_COLOUR('',#197417); +#197417 = COLOUR_RGB('',0.796078443527,0.823529422283,0.937254905701); +#197418 = OVER_RIDING_STYLED_ITEM('overriding color',(#197419),#7467, + #197410); +#197419 = PRESENTATION_STYLE_ASSIGNMENT((#197420)); +#197420 = SURFACE_STYLE_USAGE(.BOTH.,#197421); +#197421 = SURFACE_SIDE_STYLE('',(#197422)); +#197422 = SURFACE_STYLE_FILL_AREA(#197423); +#197423 = FILL_AREA_STYLE('',(#197424)); +#197424 = FILL_AREA_STYLE_COLOUR('',#197425); +#197425 = COLOUR_RGB('',0.752941191196,0.752941191196,0.752941191196); +#197426 = OVER_RIDING_STYLED_ITEM('overriding color',(#197427),#7587, + #197410); +#197427 = PRESENTATION_STYLE_ASSIGNMENT((#197428)); +#197428 = SURFACE_STYLE_USAGE(.BOTH.,#197429); +#197429 = SURFACE_SIDE_STYLE('',(#197430)); +#197430 = SURFACE_STYLE_FILL_AREA(#197431); +#197431 = FILL_AREA_STYLE('',(#197432)); +#197432 = FILL_AREA_STYLE_COLOUR('',#197425); +#197433 = OVER_RIDING_STYLED_ITEM('overriding color',(#197434),#7697, + #197410); +#197434 = PRESENTATION_STYLE_ASSIGNMENT((#197435)); +#197435 = SURFACE_STYLE_USAGE(.BOTH.,#197436); +#197436 = SURFACE_SIDE_STYLE('',(#197437)); +#197437 = SURFACE_STYLE_FILL_AREA(#197438); +#197438 = FILL_AREA_STYLE('',(#197439)); +#197439 = FILL_AREA_STYLE_COLOUR('',#197440); +#197440 = COLOUR_RGB('',0.501960813999,0.501960813999,0.501960813999); +#197441 = OVER_RIDING_STYLED_ITEM('overriding color',(#197442),#7873, + #197410); +#197442 = PRESENTATION_STYLE_ASSIGNMENT((#197443)); +#197443 = SURFACE_STYLE_USAGE(.BOTH.,#197444); +#197444 = SURFACE_SIDE_STYLE('',(#197445)); +#197445 = SURFACE_STYLE_FILL_AREA(#197446); +#197446 = FILL_AREA_STYLE('',(#197447)); +#197447 = FILL_AREA_STYLE_COLOUR('',#197440); +#197448 = OVER_RIDING_STYLED_ITEM('overriding color',(#197449),#8039, + #197410); +#197449 = PRESENTATION_STYLE_ASSIGNMENT((#197450)); +#197450 = SURFACE_STYLE_USAGE(.BOTH.,#197451); +#197451 = SURFACE_SIDE_STYLE('',(#197452)); +#197452 = SURFACE_STYLE_FILL_AREA(#197453); +#197453 = FILL_AREA_STYLE('',(#197454)); +#197454 = FILL_AREA_STYLE_COLOUR('',#197440); +#197455 = OVER_RIDING_STYLED_ITEM('overriding color',(#197456),#8096, + #197410); +#197456 = PRESENTATION_STYLE_ASSIGNMENT((#197457)); +#197457 = SURFACE_STYLE_USAGE(.BOTH.,#197458); +#197458 = SURFACE_SIDE_STYLE('',(#197459)); +#197459 = SURFACE_STYLE_FILL_AREA(#197460); +#197460 = FILL_AREA_STYLE('',(#197461)); +#197461 = FILL_AREA_STYLE_COLOUR('',#197425); +#197462 = OVER_RIDING_STYLED_ITEM('overriding color',(#197463),#8172, + #197410); +#197463 = PRESENTATION_STYLE_ASSIGNMENT((#197464)); +#197464 = SURFACE_STYLE_USAGE(.BOTH.,#197465); +#197465 = SURFACE_SIDE_STYLE('',(#197466)); +#197466 = SURFACE_STYLE_FILL_AREA(#197467); +#197467 = FILL_AREA_STYLE('',(#197468)); +#197468 = FILL_AREA_STYLE_COLOUR('',#197425); +#197469 = OVER_RIDING_STYLED_ITEM('overriding color',(#197470),#8243, + #197410); +#197470 = PRESENTATION_STYLE_ASSIGNMENT((#197471)); +#197471 = SURFACE_STYLE_USAGE(.BOTH.,#197472); +#197472 = SURFACE_SIDE_STYLE('',(#197473)); +#197473 = SURFACE_STYLE_FILL_AREA(#197474); +#197474 = FILL_AREA_STYLE('',(#197475)); +#197475 = FILL_AREA_STYLE_COLOUR('',#197425); +#197476 = OVER_RIDING_STYLED_ITEM('overriding color',(#197477),#8426, + #197410); +#197477 = PRESENTATION_STYLE_ASSIGNMENT((#197478)); +#197478 = SURFACE_STYLE_USAGE(.BOTH.,#197479); +#197479 = SURFACE_SIDE_STYLE('',(#197480)); +#197480 = SURFACE_STYLE_FILL_AREA(#197481); +#197481 = FILL_AREA_STYLE('',(#197482)); +#197482 = FILL_AREA_STYLE_COLOUR('',#197425); +#197483 = OVER_RIDING_STYLED_ITEM('overriding color',(#197484),#8541, + #197410); +#197484 = PRESENTATION_STYLE_ASSIGNMENT((#197485)); +#197485 = SURFACE_STYLE_USAGE(.BOTH.,#197486); +#197486 = SURFACE_SIDE_STYLE('',(#197487)); +#197487 = SURFACE_STYLE_FILL_AREA(#197488); +#197488 = FILL_AREA_STYLE('',(#197489)); +#197489 = FILL_AREA_STYLE_COLOUR('',#197425); +#197490 = OVER_RIDING_STYLED_ITEM('overriding color',(#197491),#8568, + #197410); +#197491 = PRESENTATION_STYLE_ASSIGNMENT((#197492)); +#197492 = SURFACE_STYLE_USAGE(.BOTH.,#197493); +#197493 = SURFACE_SIDE_STYLE('',(#197494)); +#197494 = SURFACE_STYLE_FILL_AREA(#197495); +#197495 = FILL_AREA_STYLE('',(#197496)); +#197496 = FILL_AREA_STYLE_COLOUR('',#197425); +#197497 = OVER_RIDING_STYLED_ITEM('overriding color',(#197498),#8595, + #197410); +#197498 = PRESENTATION_STYLE_ASSIGNMENT((#197499)); +#197499 = SURFACE_STYLE_USAGE(.BOTH.,#197500); +#197500 = SURFACE_SIDE_STYLE('',(#197501)); +#197501 = SURFACE_STYLE_FILL_AREA(#197502); +#197502 = FILL_AREA_STYLE('',(#197503)); +#197503 = FILL_AREA_STYLE_COLOUR('',#197425); +#197504 = OVER_RIDING_STYLED_ITEM('overriding color',(#197505),#8700, + #197410); +#197505 = PRESENTATION_STYLE_ASSIGNMENT((#197506)); +#197506 = SURFACE_STYLE_USAGE(.BOTH.,#197507); +#197507 = SURFACE_SIDE_STYLE('',(#197508)); +#197508 = SURFACE_STYLE_FILL_AREA(#197509); +#197509 = FILL_AREA_STYLE('',(#197510)); +#197510 = FILL_AREA_STYLE_COLOUR('',#197425); +#197511 = OVER_RIDING_STYLED_ITEM('overriding color',(#197512),#8771, + #197410); +#197512 = PRESENTATION_STYLE_ASSIGNMENT((#197513)); +#197513 = SURFACE_STYLE_USAGE(.BOTH.,#197514); +#197514 = SURFACE_SIDE_STYLE('',(#197515)); +#197515 = SURFACE_STYLE_FILL_AREA(#197516); +#197516 = FILL_AREA_STYLE('',(#197517)); +#197517 = FILL_AREA_STYLE_COLOUR('',#197425); +#197518 = OVER_RIDING_STYLED_ITEM('overriding color',(#197519),#8820, + #197410); +#197519 = PRESENTATION_STYLE_ASSIGNMENT((#197520)); +#197520 = SURFACE_STYLE_USAGE(.BOTH.,#197521); +#197521 = SURFACE_SIDE_STYLE('',(#197522)); +#197522 = SURFACE_STYLE_FILL_AREA(#197523); +#197523 = FILL_AREA_STYLE('',(#197524)); +#197524 = FILL_AREA_STYLE_COLOUR('',#197425); +#197525 = OVER_RIDING_STYLED_ITEM('overriding color',(#197526),#8891, + #197410); +#197526 = PRESENTATION_STYLE_ASSIGNMENT((#197527)); +#197527 = SURFACE_STYLE_USAGE(.BOTH.,#197528); +#197528 = SURFACE_SIDE_STYLE('',(#197529)); +#197529 = SURFACE_STYLE_FILL_AREA(#197530); +#197530 = FILL_AREA_STYLE('',(#197531)); +#197531 = FILL_AREA_STYLE_COLOUR('',#197425); +#197532 = OVER_RIDING_STYLED_ITEM('overriding color',(#197533),#8965, + #197410); +#197533 = PRESENTATION_STYLE_ASSIGNMENT((#197534)); +#197534 = SURFACE_STYLE_USAGE(.BOTH.,#197535); +#197535 = SURFACE_SIDE_STYLE('',(#197536)); +#197536 = SURFACE_STYLE_FILL_AREA(#197537); +#197537 = FILL_AREA_STYLE('',(#197538)); +#197538 = FILL_AREA_STYLE_COLOUR('',#197425); +#197539 = OVER_RIDING_STYLED_ITEM('overriding color',(#197540),#8976, + #197410); +#197540 = PRESENTATION_STYLE_ASSIGNMENT((#197541)); +#197541 = SURFACE_STYLE_USAGE(.BOTH.,#197542); +#197542 = SURFACE_SIDE_STYLE('',(#197543)); +#197543 = SURFACE_STYLE_FILL_AREA(#197544); +#197544 = FILL_AREA_STYLE('',(#197545)); +#197545 = FILL_AREA_STYLE_COLOUR('',#197425); +#197546 = OVER_RIDING_STYLED_ITEM('overriding color',(#197547),#8987, + #197410); +#197547 = PRESENTATION_STYLE_ASSIGNMENT((#197548)); +#197548 = SURFACE_STYLE_USAGE(.BOTH.,#197549); +#197549 = SURFACE_SIDE_STYLE('',(#197550)); +#197550 = SURFACE_STYLE_FILL_AREA(#197551); +#197551 = FILL_AREA_STYLE('',(#197552)); +#197552 = FILL_AREA_STYLE_COLOUR('',#197425); +#197553 = OVER_RIDING_STYLED_ITEM('overriding color',(#197554),#9058, + #197410); +#197554 = PRESENTATION_STYLE_ASSIGNMENT((#197555)); +#197555 = SURFACE_STYLE_USAGE(.BOTH.,#197556); +#197556 = SURFACE_SIDE_STYLE('',(#197557)); +#197557 = SURFACE_STYLE_FILL_AREA(#197558); +#197558 = FILL_AREA_STYLE('',(#197559)); +#197559 = FILL_AREA_STYLE_COLOUR('',#197425); +#197560 = OVER_RIDING_STYLED_ITEM('overriding color',(#197561),#9129, + #197410); +#197561 = PRESENTATION_STYLE_ASSIGNMENT((#197562)); +#197562 = SURFACE_STYLE_USAGE(.BOTH.,#197563); +#197563 = SURFACE_SIDE_STYLE('',(#197564)); +#197564 = SURFACE_STYLE_FILL_AREA(#197565); +#197565 = FILL_AREA_STYLE('',(#197566)); +#197566 = FILL_AREA_STYLE_COLOUR('',#197425); +#197567 = OVER_RIDING_STYLED_ITEM('overriding color',(#197568),#9156, + #197410); +#197568 = PRESENTATION_STYLE_ASSIGNMENT((#197569)); +#197569 = SURFACE_STYLE_USAGE(.BOTH.,#197570); +#197570 = SURFACE_SIDE_STYLE('',(#197571)); +#197571 = SURFACE_STYLE_FILL_AREA(#197572); +#197572 = FILL_AREA_STYLE('',(#197573)); +#197573 = FILL_AREA_STYLE_COLOUR('',#197425); +#197574 = OVER_RIDING_STYLED_ITEM('overriding color',(#197575),#9183, + #197410); +#197575 = PRESENTATION_STYLE_ASSIGNMENT((#197576)); +#197576 = SURFACE_STYLE_USAGE(.BOTH.,#197577); +#197577 = SURFACE_SIDE_STYLE('',(#197578)); +#197578 = SURFACE_STYLE_FILL_AREA(#197579); +#197579 = FILL_AREA_STYLE('',(#197580)); +#197580 = FILL_AREA_STYLE_COLOUR('',#197425); +#197581 = OVER_RIDING_STYLED_ITEM('overriding color',(#197582),#9254, + #197410); +#197582 = PRESENTATION_STYLE_ASSIGNMENT((#197583)); +#197583 = SURFACE_STYLE_USAGE(.BOTH.,#197584); +#197584 = SURFACE_SIDE_STYLE('',(#197585)); +#197585 = SURFACE_STYLE_FILL_AREA(#197586); +#197586 = FILL_AREA_STYLE('',(#197587)); +#197587 = FILL_AREA_STYLE_COLOUR('',#197425); +#197588 = OVER_RIDING_STYLED_ITEM('overriding color',(#197589),#9332, + #197410); +#197589 = PRESENTATION_STYLE_ASSIGNMENT((#197590)); +#197590 = SURFACE_STYLE_USAGE(.BOTH.,#197591); +#197591 = SURFACE_SIDE_STYLE('',(#197592)); +#197592 = SURFACE_STYLE_FILL_AREA(#197593); +#197593 = FILL_AREA_STYLE('',(#197594)); +#197594 = FILL_AREA_STYLE_COLOUR('',#197425); +#197595 = OVER_RIDING_STYLED_ITEM('overriding color',(#197596),#9408, + #197410); +#197596 = PRESENTATION_STYLE_ASSIGNMENT((#197597)); +#197597 = SURFACE_STYLE_USAGE(.BOTH.,#197598); +#197598 = SURFACE_SIDE_STYLE('',(#197599)); +#197599 = SURFACE_STYLE_FILL_AREA(#197600); +#197600 = FILL_AREA_STYLE('',(#197601)); +#197601 = FILL_AREA_STYLE_COLOUR('',#197425); +#197602 = OVER_RIDING_STYLED_ITEM('overriding color',(#197603),#9479, + #197410); +#197603 = PRESENTATION_STYLE_ASSIGNMENT((#197604)); +#197604 = SURFACE_STYLE_USAGE(.BOTH.,#197605); +#197605 = SURFACE_SIDE_STYLE('',(#197606)); +#197606 = SURFACE_STYLE_FILL_AREA(#197607); +#197607 = FILL_AREA_STYLE('',(#197608)); +#197608 = FILL_AREA_STYLE_COLOUR('',#197425); +#197609 = OVER_RIDING_STYLED_ITEM('overriding color',(#197610),#9553, + #197410); +#197610 = PRESENTATION_STYLE_ASSIGNMENT((#197611)); +#197611 = SURFACE_STYLE_USAGE(.BOTH.,#197612); +#197612 = SURFACE_SIDE_STYLE('',(#197613)); +#197613 = SURFACE_STYLE_FILL_AREA(#197614); +#197614 = FILL_AREA_STYLE('',(#197615)); +#197615 = FILL_AREA_STYLE_COLOUR('',#197425); +#197616 = OVER_RIDING_STYLED_ITEM('overriding color',(#197617),#9564, + #197410); +#197617 = PRESENTATION_STYLE_ASSIGNMENT((#197618)); +#197618 = SURFACE_STYLE_USAGE(.BOTH.,#197619); +#197619 = SURFACE_SIDE_STYLE('',(#197620)); +#197620 = SURFACE_STYLE_FILL_AREA(#197621); +#197621 = FILL_AREA_STYLE('',(#197622)); +#197622 = FILL_AREA_STYLE_COLOUR('',#197425); +#197623 = OVER_RIDING_STYLED_ITEM('overriding color',(#197624),#9575, + #197410); +#197624 = PRESENTATION_STYLE_ASSIGNMENT((#197625)); +#197625 = SURFACE_STYLE_USAGE(.BOTH.,#197626); +#197626 = SURFACE_SIDE_STYLE('',(#197627)); +#197627 = SURFACE_STYLE_FILL_AREA(#197628); +#197628 = FILL_AREA_STYLE('',(#197629)); +#197629 = FILL_AREA_STYLE_COLOUR('',#197630); +#197630 = COLOUR_RGB('',0.117647059262,0.117647059262,0.117647059262); +#197631 = OVER_RIDING_STYLED_ITEM('overriding color',(#197632),#9607, + #197410); +#197632 = PRESENTATION_STYLE_ASSIGNMENT((#197633)); +#197633 = SURFACE_STYLE_USAGE(.BOTH.,#197634); +#197634 = SURFACE_SIDE_STYLE('',(#197635)); +#197635 = SURFACE_STYLE_FILL_AREA(#197636); +#197636 = FILL_AREA_STYLE('',(#197637)); +#197637 = FILL_AREA_STYLE_COLOUR('',#197630); +#197638 = OVER_RIDING_STYLED_ITEM('overriding color',(#197639),#9639, + #197410); +#197639 = PRESENTATION_STYLE_ASSIGNMENT((#197640)); +#197640 = SURFACE_STYLE_USAGE(.BOTH.,#197641); +#197641 = SURFACE_SIDE_STYLE('',(#197642)); +#197642 = SURFACE_STYLE_FILL_AREA(#197643); +#197643 = FILL_AREA_STYLE('',(#197644)); +#197644 = FILL_AREA_STYLE_COLOUR('',#197630); +#197645 = OVER_RIDING_STYLED_ITEM('overriding color',(#197646),#9715, + #197410); +#197646 = PRESENTATION_STYLE_ASSIGNMENT((#197647)); +#197647 = SURFACE_STYLE_USAGE(.BOTH.,#197648); +#197648 = SURFACE_SIDE_STYLE('',(#197649)); +#197649 = SURFACE_STYLE_FILL_AREA(#197650); +#197650 = FILL_AREA_STYLE('',(#197651)); +#197651 = FILL_AREA_STYLE_COLOUR('',#197630); +#197652 = OVER_RIDING_STYLED_ITEM('overriding color',(#197653),#9764, + #197410); +#197653 = PRESENTATION_STYLE_ASSIGNMENT((#197654)); +#197654 = SURFACE_STYLE_USAGE(.BOTH.,#197655); +#197655 = SURFACE_SIDE_STYLE('',(#197656)); +#197656 = SURFACE_STYLE_FILL_AREA(#197657); +#197657 = FILL_AREA_STYLE('',(#197658)); +#197658 = FILL_AREA_STYLE_COLOUR('',#197630); +#197659 = OVER_RIDING_STYLED_ITEM('overriding color',(#197660),#9813, + #197410); +#197660 = PRESENTATION_STYLE_ASSIGNMENT((#197661)); +#197661 = SURFACE_STYLE_USAGE(.BOTH.,#197662); +#197662 = SURFACE_SIDE_STYLE('',(#197663)); +#197663 = SURFACE_STYLE_FILL_AREA(#197664); +#197664 = FILL_AREA_STYLE('',(#197665)); +#197665 = FILL_AREA_STYLE_COLOUR('',#197630); +#197666 = OVER_RIDING_STYLED_ITEM('overriding color',(#197667),#9840, + #197410); +#197667 = PRESENTATION_STYLE_ASSIGNMENT((#197668)); +#197668 = SURFACE_STYLE_USAGE(.BOTH.,#197669); +#197669 = SURFACE_SIDE_STYLE('',(#197670)); +#197670 = SURFACE_STYLE_FILL_AREA(#197671); +#197671 = FILL_AREA_STYLE('',(#197672)); +#197672 = FILL_AREA_STYLE_COLOUR('',#197630); +#197673 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #197674),#13837); +#197674 = STYLED_ITEM('color',(#197675),#13507); +#197675 = PRESENTATION_STYLE_ASSIGNMENT((#197676,#197682)); #197676 = SURFACE_STYLE_USAGE(.BOTH.,#197677); #197677 = SURFACE_SIDE_STYLE('',(#197678)); #197678 = SURFACE_STYLE_FILL_AREA(#197679); #197679 = FILL_AREA_STYLE('',(#197680)); -#197680 = FILL_AREA_STYLE_COLOUR('',#195083); -#197681 = OVER_RIDING_STYLED_ITEM('overriding color',(#197682),#119371, - #195018); -#197682 = PRESENTATION_STYLE_ASSIGNMENT((#197683)); -#197683 = SURFACE_STYLE_USAGE(.BOTH.,#197684); -#197684 = SURFACE_SIDE_STYLE('',(#197685)); -#197685 = SURFACE_STYLE_FILL_AREA(#197686); -#197686 = FILL_AREA_STYLE('',(#197687)); -#197687 = FILL_AREA_STYLE_COLOUR('',#195083); -#197688 = OVER_RIDING_STYLED_ITEM('overriding color',(#197689),#119418, - #195018); -#197689 = PRESENTATION_STYLE_ASSIGNMENT((#197690)); -#197690 = SURFACE_STYLE_USAGE(.BOTH.,#197691); -#197691 = SURFACE_SIDE_STYLE('',(#197692)); -#197692 = SURFACE_STYLE_FILL_AREA(#197693); -#197693 = FILL_AREA_STYLE('',(#197694)); -#197694 = FILL_AREA_STYLE_COLOUR('',#195083); -#197695 = OVER_RIDING_STYLED_ITEM('overriding color',(#197696),#119473, - #195018); -#197696 = PRESENTATION_STYLE_ASSIGNMENT((#197697)); -#197697 = SURFACE_STYLE_USAGE(.BOTH.,#197698); -#197698 = SURFACE_SIDE_STYLE('',(#197699)); -#197699 = SURFACE_STYLE_FILL_AREA(#197700); -#197700 = FILL_AREA_STYLE('',(#197701)); -#197701 = FILL_AREA_STYLE_COLOUR('',#195083); -#197702 = OVER_RIDING_STYLED_ITEM('overriding color',(#197703),#119500, - #195018); -#197703 = PRESENTATION_STYLE_ASSIGNMENT((#197704)); -#197704 = SURFACE_STYLE_USAGE(.BOTH.,#197705); -#197705 = SURFACE_SIDE_STYLE('',(#197706)); -#197706 = SURFACE_STYLE_FILL_AREA(#197707); -#197707 = FILL_AREA_STYLE('',(#197708)); -#197708 = FILL_AREA_STYLE_COLOUR('',#195083); -#197709 = OVER_RIDING_STYLED_ITEM('overriding color',(#197710),#119535, - #195018); -#197710 = PRESENTATION_STYLE_ASSIGNMENT((#197711)); -#197711 = SURFACE_STYLE_USAGE(.BOTH.,#197712); -#197712 = SURFACE_SIDE_STYLE('',(#197713)); -#197713 = SURFACE_STYLE_FILL_AREA(#197714); -#197714 = FILL_AREA_STYLE('',(#197715)); -#197715 = FILL_AREA_STYLE_COLOUR('',#195083); -#197716 = OVER_RIDING_STYLED_ITEM('overriding color',(#197717),#119542, - #195018); -#197717 = PRESENTATION_STYLE_ASSIGNMENT((#197718)); -#197718 = SURFACE_STYLE_USAGE(.BOTH.,#197719); -#197719 = SURFACE_SIDE_STYLE('',(#197720)); -#197720 = SURFACE_STYLE_FILL_AREA(#197721); -#197721 = FILL_AREA_STYLE('',(#197722)); -#197722 = FILL_AREA_STYLE_COLOUR('',#195083); -#197723 = OVER_RIDING_STYLED_ITEM('overriding color',(#197724),#119651, - #195018); -#197724 = PRESENTATION_STYLE_ASSIGNMENT((#197725)); -#197725 = SURFACE_STYLE_USAGE(.BOTH.,#197726); -#197726 = SURFACE_SIDE_STYLE('',(#197727)); -#197727 = SURFACE_STYLE_FILL_AREA(#197728); -#197728 = FILL_AREA_STYLE('',(#197729)); -#197729 = FILL_AREA_STYLE_COLOUR('',#195083); -#197730 = OVER_RIDING_STYLED_ITEM('overriding color',(#197731),#119755, - #195018); -#197731 = PRESENTATION_STYLE_ASSIGNMENT((#197732)); -#197732 = SURFACE_STYLE_USAGE(.BOTH.,#197733); -#197733 = SURFACE_SIDE_STYLE('',(#197734)); -#197734 = SURFACE_STYLE_FILL_AREA(#197735); -#197735 = FILL_AREA_STYLE('',(#197736)); -#197736 = FILL_AREA_STYLE_COLOUR('',#195083); -#197737 = OVER_RIDING_STYLED_ITEM('overriding color',(#197738),#119834, - #195018); -#197738 = PRESENTATION_STYLE_ASSIGNMENT((#197739)); -#197739 = SURFACE_STYLE_USAGE(.BOTH.,#197740); -#197740 = SURFACE_SIDE_STYLE('',(#197741)); -#197741 = SURFACE_STYLE_FILL_AREA(#197742); -#197742 = FILL_AREA_STYLE('',(#197743)); -#197743 = FILL_AREA_STYLE_COLOUR('',#195083); -#197744 = OVER_RIDING_STYLED_ITEM('overriding color',(#197745),#119913, - #195018); -#197745 = PRESENTATION_STYLE_ASSIGNMENT((#197746)); -#197746 = SURFACE_STYLE_USAGE(.BOTH.,#197747); -#197747 = SURFACE_SIDE_STYLE('',(#197748)); -#197748 = SURFACE_STYLE_FILL_AREA(#197749); -#197749 = FILL_AREA_STYLE('',(#197750)); -#197750 = FILL_AREA_STYLE_COLOUR('',#195083); -#197751 = OVER_RIDING_STYLED_ITEM('overriding color',(#197752),#119988, - #195018); -#197752 = PRESENTATION_STYLE_ASSIGNMENT((#197753)); -#197753 = SURFACE_STYLE_USAGE(.BOTH.,#197754); -#197754 = SURFACE_SIDE_STYLE('',(#197755)); -#197755 = SURFACE_STYLE_FILL_AREA(#197756); -#197756 = FILL_AREA_STYLE('',(#197757)); -#197757 = FILL_AREA_STYLE_COLOUR('',#195083); -#197758 = OVER_RIDING_STYLED_ITEM('overriding color',(#197759),#120063, - #195018); -#197759 = PRESENTATION_STYLE_ASSIGNMENT((#197760)); -#197760 = SURFACE_STYLE_USAGE(.BOTH.,#197761); -#197761 = SURFACE_SIDE_STYLE('',(#197762)); -#197762 = SURFACE_STYLE_FILL_AREA(#197763); -#197763 = FILL_AREA_STYLE('',(#197764)); -#197764 = FILL_AREA_STYLE_COLOUR('',#195083); -#197765 = OVER_RIDING_STYLED_ITEM('overriding color',(#197766),#120160, - #195018); -#197766 = PRESENTATION_STYLE_ASSIGNMENT((#197767)); -#197767 = SURFACE_STYLE_USAGE(.BOTH.,#197768); -#197768 = SURFACE_SIDE_STYLE('',(#197769)); -#197769 = SURFACE_STYLE_FILL_AREA(#197770); -#197770 = FILL_AREA_STYLE('',(#197771)); -#197771 = FILL_AREA_STYLE_COLOUR('',#195083); -#197772 = OVER_RIDING_STYLED_ITEM('overriding color',(#197773),#120257, - #195018); -#197773 = PRESENTATION_STYLE_ASSIGNMENT((#197774)); -#197774 = SURFACE_STYLE_USAGE(.BOTH.,#197775); -#197775 = SURFACE_SIDE_STYLE('',(#197776)); -#197776 = SURFACE_STYLE_FILL_AREA(#197777); -#197777 = FILL_AREA_STYLE('',(#197778)); -#197778 = FILL_AREA_STYLE_COLOUR('',#195083); -#197779 = OVER_RIDING_STYLED_ITEM('overriding color',(#197780),#120304, - #195018); -#197780 = PRESENTATION_STYLE_ASSIGNMENT((#197781)); -#197781 = SURFACE_STYLE_USAGE(.BOTH.,#197782); -#197782 = SURFACE_SIDE_STYLE('',(#197783)); -#197783 = SURFACE_STYLE_FILL_AREA(#197784); -#197784 = FILL_AREA_STYLE('',(#197785)); -#197785 = FILL_AREA_STYLE_COLOUR('',#195083); -#197786 = OVER_RIDING_STYLED_ITEM('overriding color',(#197787),#120359, - #195018); -#197787 = PRESENTATION_STYLE_ASSIGNMENT((#197788)); -#197788 = SURFACE_STYLE_USAGE(.BOTH.,#197789); -#197789 = SURFACE_SIDE_STYLE('',(#197790)); -#197790 = SURFACE_STYLE_FILL_AREA(#197791); -#197791 = FILL_AREA_STYLE('',(#197792)); -#197792 = FILL_AREA_STYLE_COLOUR('',#195083); -#197793 = OVER_RIDING_STYLED_ITEM('overriding color',(#197794),#120386, - #195018); -#197794 = PRESENTATION_STYLE_ASSIGNMENT((#197795)); -#197795 = SURFACE_STYLE_USAGE(.BOTH.,#197796); -#197796 = SURFACE_SIDE_STYLE('',(#197797)); -#197797 = SURFACE_STYLE_FILL_AREA(#197798); -#197798 = FILL_AREA_STYLE('',(#197799)); -#197799 = FILL_AREA_STYLE_COLOUR('',#195083); -#197800 = OVER_RIDING_STYLED_ITEM('overriding color',(#197801),#120421, - #195018); -#197801 = PRESENTATION_STYLE_ASSIGNMENT((#197802)); -#197802 = SURFACE_STYLE_USAGE(.BOTH.,#197803); -#197803 = SURFACE_SIDE_STYLE('',(#197804)); -#197804 = SURFACE_STYLE_FILL_AREA(#197805); -#197805 = FILL_AREA_STYLE('',(#197806)); -#197806 = FILL_AREA_STYLE_COLOUR('',#195083); -#197807 = OVER_RIDING_STYLED_ITEM('overriding color',(#197808),#120428, - #195018); -#197808 = PRESENTATION_STYLE_ASSIGNMENT((#197809)); -#197809 = SURFACE_STYLE_USAGE(.BOTH.,#197810); -#197810 = SURFACE_SIDE_STYLE('',(#197811)); -#197811 = SURFACE_STYLE_FILL_AREA(#197812); -#197812 = FILL_AREA_STYLE('',(#197813)); -#197813 = FILL_AREA_STYLE_COLOUR('',#195083); -#197814 = OVER_RIDING_STYLED_ITEM('overriding color',(#197815),#120537, - #195018); -#197815 = PRESENTATION_STYLE_ASSIGNMENT((#197816)); -#197816 = SURFACE_STYLE_USAGE(.BOTH.,#197817); -#197817 = SURFACE_SIDE_STYLE('',(#197818)); -#197818 = SURFACE_STYLE_FILL_AREA(#197819); -#197819 = FILL_AREA_STYLE('',(#197820)); -#197820 = FILL_AREA_STYLE_COLOUR('',#195083); -#197821 = OVER_RIDING_STYLED_ITEM('overriding color',(#197822),#120641, - #195018); -#197822 = PRESENTATION_STYLE_ASSIGNMENT((#197823)); -#197823 = SURFACE_STYLE_USAGE(.BOTH.,#197824); -#197824 = SURFACE_SIDE_STYLE('',(#197825)); -#197825 = SURFACE_STYLE_FILL_AREA(#197826); -#197826 = FILL_AREA_STYLE('',(#197827)); -#197827 = FILL_AREA_STYLE_COLOUR('',#195083); -#197828 = OVER_RIDING_STYLED_ITEM('overriding color',(#197829),#120720, - #195018); -#197829 = PRESENTATION_STYLE_ASSIGNMENT((#197830)); -#197830 = SURFACE_STYLE_USAGE(.BOTH.,#197831); -#197831 = SURFACE_SIDE_STYLE('',(#197832)); -#197832 = SURFACE_STYLE_FILL_AREA(#197833); -#197833 = FILL_AREA_STYLE('',(#197834)); -#197834 = FILL_AREA_STYLE_COLOUR('',#195083); -#197835 = OVER_RIDING_STYLED_ITEM('overriding color',(#197836),#120799, - #195018); -#197836 = PRESENTATION_STYLE_ASSIGNMENT((#197837)); -#197837 = SURFACE_STYLE_USAGE(.BOTH.,#197838); -#197838 = SURFACE_SIDE_STYLE('',(#197839)); -#197839 = SURFACE_STYLE_FILL_AREA(#197840); -#197840 = FILL_AREA_STYLE('',(#197841)); -#197841 = FILL_AREA_STYLE_COLOUR('',#195083); -#197842 = OVER_RIDING_STYLED_ITEM('overriding color',(#197843),#120874, - #195018); -#197843 = PRESENTATION_STYLE_ASSIGNMENT((#197844)); -#197844 = SURFACE_STYLE_USAGE(.BOTH.,#197845); -#197845 = SURFACE_SIDE_STYLE('',(#197846)); -#197846 = SURFACE_STYLE_FILL_AREA(#197847); -#197847 = FILL_AREA_STYLE('',(#197848)); -#197848 = FILL_AREA_STYLE_COLOUR('',#195083); -#197849 = OVER_RIDING_STYLED_ITEM('overriding color',(#197850),#120949, - #195018); -#197850 = PRESENTATION_STYLE_ASSIGNMENT((#197851)); -#197851 = SURFACE_STYLE_USAGE(.BOTH.,#197852); -#197852 = SURFACE_SIDE_STYLE('',(#197853)); -#197853 = SURFACE_STYLE_FILL_AREA(#197854); -#197854 = FILL_AREA_STYLE('',(#197855)); -#197855 = FILL_AREA_STYLE_COLOUR('',#195083); -#197856 = OVER_RIDING_STYLED_ITEM('overriding color',(#197857),#121046, - #195018); -#197857 = PRESENTATION_STYLE_ASSIGNMENT((#197858)); -#197858 = SURFACE_STYLE_USAGE(.BOTH.,#197859); -#197859 = SURFACE_SIDE_STYLE('',(#197860)); -#197860 = SURFACE_STYLE_FILL_AREA(#197861); -#197861 = FILL_AREA_STYLE('',(#197862)); -#197862 = FILL_AREA_STYLE_COLOUR('',#195083); -#197863 = OVER_RIDING_STYLED_ITEM('overriding color',(#197864),#121143, - #195018); -#197864 = PRESENTATION_STYLE_ASSIGNMENT((#197865)); -#197865 = SURFACE_STYLE_USAGE(.BOTH.,#197866); -#197866 = SURFACE_SIDE_STYLE('',(#197867)); -#197867 = SURFACE_STYLE_FILL_AREA(#197868); -#197868 = FILL_AREA_STYLE('',(#197869)); -#197869 = FILL_AREA_STYLE_COLOUR('',#195083); -#197870 = OVER_RIDING_STYLED_ITEM('overriding color',(#197871),#121190, - #195018); -#197871 = PRESENTATION_STYLE_ASSIGNMENT((#197872)); -#197872 = SURFACE_STYLE_USAGE(.BOTH.,#197873); -#197873 = SURFACE_SIDE_STYLE('',(#197874)); -#197874 = SURFACE_STYLE_FILL_AREA(#197875); -#197875 = FILL_AREA_STYLE('',(#197876)); -#197876 = FILL_AREA_STYLE_COLOUR('',#195083); -#197877 = OVER_RIDING_STYLED_ITEM('overriding color',(#197878),#121245, - #195018); -#197878 = PRESENTATION_STYLE_ASSIGNMENT((#197879)); -#197879 = SURFACE_STYLE_USAGE(.BOTH.,#197880); -#197880 = SURFACE_SIDE_STYLE('',(#197881)); -#197881 = SURFACE_STYLE_FILL_AREA(#197882); -#197882 = FILL_AREA_STYLE('',(#197883)); -#197883 = FILL_AREA_STYLE_COLOUR('',#195083); -#197884 = OVER_RIDING_STYLED_ITEM('overriding color',(#197885),#121272, - #195018); -#197885 = PRESENTATION_STYLE_ASSIGNMENT((#197886)); -#197886 = SURFACE_STYLE_USAGE(.BOTH.,#197887); -#197887 = SURFACE_SIDE_STYLE('',(#197888)); -#197888 = SURFACE_STYLE_FILL_AREA(#197889); -#197889 = FILL_AREA_STYLE('',(#197890)); -#197890 = FILL_AREA_STYLE_COLOUR('',#195083); -#197891 = OVER_RIDING_STYLED_ITEM('overriding color',(#197892),#121307, - #195018); -#197892 = PRESENTATION_STYLE_ASSIGNMENT((#197893)); -#197893 = SURFACE_STYLE_USAGE(.BOTH.,#197894); -#197894 = SURFACE_SIDE_STYLE('',(#197895)); -#197895 = SURFACE_STYLE_FILL_AREA(#197896); -#197896 = FILL_AREA_STYLE('',(#197897)); -#197897 = FILL_AREA_STYLE_COLOUR('',#195083); -#197898 = OVER_RIDING_STYLED_ITEM('overriding color',(#197899),#121314, - #195018); -#197899 = PRESENTATION_STYLE_ASSIGNMENT((#197900)); -#197900 = SURFACE_STYLE_USAGE(.BOTH.,#197901); -#197901 = SURFACE_SIDE_STYLE('',(#197902)); -#197902 = SURFACE_STYLE_FILL_AREA(#197903); -#197903 = FILL_AREA_STYLE('',(#197904)); -#197904 = FILL_AREA_STYLE_COLOUR('',#195083); -#197905 = OVER_RIDING_STYLED_ITEM('overriding color',(#197906),#121423, - #195018); -#197906 = PRESENTATION_STYLE_ASSIGNMENT((#197907)); -#197907 = SURFACE_STYLE_USAGE(.BOTH.,#197908); -#197908 = SURFACE_SIDE_STYLE('',(#197909)); -#197909 = SURFACE_STYLE_FILL_AREA(#197910); -#197910 = FILL_AREA_STYLE('',(#197911)); -#197911 = FILL_AREA_STYLE_COLOUR('',#195083); -#197912 = OVER_RIDING_STYLED_ITEM('overriding color',(#197913),#121527, - #195018); -#197913 = PRESENTATION_STYLE_ASSIGNMENT((#197914)); -#197914 = SURFACE_STYLE_USAGE(.BOTH.,#197915); -#197915 = SURFACE_SIDE_STYLE('',(#197916)); -#197916 = SURFACE_STYLE_FILL_AREA(#197917); -#197917 = FILL_AREA_STYLE('',(#197918)); -#197918 = FILL_AREA_STYLE_COLOUR('',#195083); -#197919 = OVER_RIDING_STYLED_ITEM('overriding color',(#197920),#121606, - #195018); -#197920 = PRESENTATION_STYLE_ASSIGNMENT((#197921)); -#197921 = SURFACE_STYLE_USAGE(.BOTH.,#197922); -#197922 = SURFACE_SIDE_STYLE('',(#197923)); -#197923 = SURFACE_STYLE_FILL_AREA(#197924); -#197924 = FILL_AREA_STYLE('',(#197925)); -#197925 = FILL_AREA_STYLE_COLOUR('',#195083); -#197926 = OVER_RIDING_STYLED_ITEM('overriding color',(#197927),#121685, - #195018); -#197927 = PRESENTATION_STYLE_ASSIGNMENT((#197928)); -#197928 = SURFACE_STYLE_USAGE(.BOTH.,#197929); -#197929 = SURFACE_SIDE_STYLE('',(#197930)); -#197930 = SURFACE_STYLE_FILL_AREA(#197931); -#197931 = FILL_AREA_STYLE('',(#197932)); -#197932 = FILL_AREA_STYLE_COLOUR('',#195083); -#197933 = OVER_RIDING_STYLED_ITEM('overriding color',(#197934),#121760, - #195018); -#197934 = PRESENTATION_STYLE_ASSIGNMENT((#197935)); -#197935 = SURFACE_STYLE_USAGE(.BOTH.,#197936); -#197936 = SURFACE_SIDE_STYLE('',(#197937)); -#197937 = SURFACE_STYLE_FILL_AREA(#197938); -#197938 = FILL_AREA_STYLE('',(#197939)); -#197939 = FILL_AREA_STYLE_COLOUR('',#195083); -#197940 = OVER_RIDING_STYLED_ITEM('overriding color',(#197941),#121835, - #195018); -#197941 = PRESENTATION_STYLE_ASSIGNMENT((#197942)); -#197942 = SURFACE_STYLE_USAGE(.BOTH.,#197943); -#197943 = SURFACE_SIDE_STYLE('',(#197944)); -#197944 = SURFACE_STYLE_FILL_AREA(#197945); -#197945 = FILL_AREA_STYLE('',(#197946)); -#197946 = FILL_AREA_STYLE_COLOUR('',#195083); -#197947 = OVER_RIDING_STYLED_ITEM('overriding color',(#197948),#121932, - #195018); -#197948 = PRESENTATION_STYLE_ASSIGNMENT((#197949)); -#197949 = SURFACE_STYLE_USAGE(.BOTH.,#197950); -#197950 = SURFACE_SIDE_STYLE('',(#197951)); -#197951 = SURFACE_STYLE_FILL_AREA(#197952); -#197952 = FILL_AREA_STYLE('',(#197953)); -#197953 = FILL_AREA_STYLE_COLOUR('',#195083); -#197954 = OVER_RIDING_STYLED_ITEM('overriding color',(#197955),#122029, - #195018); -#197955 = PRESENTATION_STYLE_ASSIGNMENT((#197956)); -#197956 = SURFACE_STYLE_USAGE(.BOTH.,#197957); -#197957 = SURFACE_SIDE_STYLE('',(#197958)); -#197958 = SURFACE_STYLE_FILL_AREA(#197959); -#197959 = FILL_AREA_STYLE('',(#197960)); -#197960 = FILL_AREA_STYLE_COLOUR('',#195083); -#197961 = OVER_RIDING_STYLED_ITEM('overriding color',(#197962),#122076, - #195018); -#197962 = PRESENTATION_STYLE_ASSIGNMENT((#197963)); -#197963 = SURFACE_STYLE_USAGE(.BOTH.,#197964); -#197964 = SURFACE_SIDE_STYLE('',(#197965)); -#197965 = SURFACE_STYLE_FILL_AREA(#197966); -#197966 = FILL_AREA_STYLE('',(#197967)); -#197967 = FILL_AREA_STYLE_COLOUR('',#195083); -#197968 = OVER_RIDING_STYLED_ITEM('overriding color',(#197969),#122131, - #195018); -#197969 = PRESENTATION_STYLE_ASSIGNMENT((#197970)); -#197970 = SURFACE_STYLE_USAGE(.BOTH.,#197971); -#197971 = SURFACE_SIDE_STYLE('',(#197972)); -#197972 = SURFACE_STYLE_FILL_AREA(#197973); -#197973 = FILL_AREA_STYLE('',(#197974)); -#197974 = FILL_AREA_STYLE_COLOUR('',#195083); -#197975 = OVER_RIDING_STYLED_ITEM('overriding color',(#197976),#122158, - #195018); -#197976 = PRESENTATION_STYLE_ASSIGNMENT((#197977)); -#197977 = SURFACE_STYLE_USAGE(.BOTH.,#197978); -#197978 = SURFACE_SIDE_STYLE('',(#197979)); -#197979 = SURFACE_STYLE_FILL_AREA(#197980); -#197980 = FILL_AREA_STYLE('',(#197981)); -#197981 = FILL_AREA_STYLE_COLOUR('',#195083); -#197982 = OVER_RIDING_STYLED_ITEM('overriding color',(#197983),#122193, - #195018); -#197983 = PRESENTATION_STYLE_ASSIGNMENT((#197984)); -#197984 = SURFACE_STYLE_USAGE(.BOTH.,#197985); -#197985 = SURFACE_SIDE_STYLE('',(#197986)); -#197986 = SURFACE_STYLE_FILL_AREA(#197987); -#197987 = FILL_AREA_STYLE('',(#197988)); -#197988 = FILL_AREA_STYLE_COLOUR('',#195083); -#197989 = OVER_RIDING_STYLED_ITEM('overriding color',(#197990),#122200, - #195018); -#197990 = PRESENTATION_STYLE_ASSIGNMENT((#197991)); -#197991 = SURFACE_STYLE_USAGE(.BOTH.,#197992); -#197992 = SURFACE_SIDE_STYLE('',(#197993)); -#197993 = SURFACE_STYLE_FILL_AREA(#197994); -#197994 = FILL_AREA_STYLE('',(#197995)); -#197995 = FILL_AREA_STYLE_COLOUR('',#195083); -#197996 = OVER_RIDING_STYLED_ITEM('overriding color',(#197997),#122309, - #195018); -#197997 = PRESENTATION_STYLE_ASSIGNMENT((#197998)); -#197998 = SURFACE_STYLE_USAGE(.BOTH.,#197999); -#197999 = SURFACE_SIDE_STYLE('',(#198000)); -#198000 = SURFACE_STYLE_FILL_AREA(#198001); -#198001 = FILL_AREA_STYLE('',(#198002)); -#198002 = FILL_AREA_STYLE_COLOUR('',#195083); -#198003 = OVER_RIDING_STYLED_ITEM('overriding color',(#198004),#122413, - #195018); -#198004 = PRESENTATION_STYLE_ASSIGNMENT((#198005)); -#198005 = SURFACE_STYLE_USAGE(.BOTH.,#198006); -#198006 = SURFACE_SIDE_STYLE('',(#198007)); -#198007 = SURFACE_STYLE_FILL_AREA(#198008); -#198008 = FILL_AREA_STYLE('',(#198009)); -#198009 = FILL_AREA_STYLE_COLOUR('',#195083); -#198010 = OVER_RIDING_STYLED_ITEM('overriding color',(#198011),#122492, - #195018); -#198011 = PRESENTATION_STYLE_ASSIGNMENT((#198012)); -#198012 = SURFACE_STYLE_USAGE(.BOTH.,#198013); -#198013 = SURFACE_SIDE_STYLE('',(#198014)); -#198014 = SURFACE_STYLE_FILL_AREA(#198015); -#198015 = FILL_AREA_STYLE('',(#198016)); -#198016 = FILL_AREA_STYLE_COLOUR('',#195083); -#198017 = OVER_RIDING_STYLED_ITEM('overriding color',(#198018),#122571, - #195018); -#198018 = PRESENTATION_STYLE_ASSIGNMENT((#198019)); -#198019 = SURFACE_STYLE_USAGE(.BOTH.,#198020); -#198020 = SURFACE_SIDE_STYLE('',(#198021)); -#198021 = SURFACE_STYLE_FILL_AREA(#198022); -#198022 = FILL_AREA_STYLE('',(#198023)); -#198023 = FILL_AREA_STYLE_COLOUR('',#195083); -#198024 = OVER_RIDING_STYLED_ITEM('overriding color',(#198025),#122646, - #195018); -#198025 = PRESENTATION_STYLE_ASSIGNMENT((#198026)); -#198026 = SURFACE_STYLE_USAGE(.BOTH.,#198027); -#198027 = SURFACE_SIDE_STYLE('',(#198028)); -#198028 = SURFACE_STYLE_FILL_AREA(#198029); -#198029 = FILL_AREA_STYLE('',(#198030)); -#198030 = FILL_AREA_STYLE_COLOUR('',#195083); -#198031 = OVER_RIDING_STYLED_ITEM('overriding color',(#198032),#122721, - #195018); -#198032 = PRESENTATION_STYLE_ASSIGNMENT((#198033)); -#198033 = SURFACE_STYLE_USAGE(.BOTH.,#198034); -#198034 = SURFACE_SIDE_STYLE('',(#198035)); -#198035 = SURFACE_STYLE_FILL_AREA(#198036); -#198036 = FILL_AREA_STYLE('',(#198037)); -#198037 = FILL_AREA_STYLE_COLOUR('',#195083); -#198038 = OVER_RIDING_STYLED_ITEM('overriding color',(#198039),#122795, - #195018); -#198039 = PRESENTATION_STYLE_ASSIGNMENT((#198040)); -#198040 = SURFACE_STYLE_USAGE(.BOTH.,#198041); -#198041 = SURFACE_SIDE_STYLE('',(#198042)); -#198042 = SURFACE_STYLE_FILL_AREA(#198043); -#198043 = FILL_AREA_STYLE('',(#198044)); -#198044 = FILL_AREA_STYLE_COLOUR('',#195083); -#198045 = OVER_RIDING_STYLED_ITEM('overriding color',(#198046),#122869, - #195018); -#198046 = PRESENTATION_STYLE_ASSIGNMENT((#198047)); -#198047 = SURFACE_STYLE_USAGE(.BOTH.,#198048); -#198048 = SURFACE_SIDE_STYLE('',(#198049)); -#198049 = SURFACE_STYLE_FILL_AREA(#198050); -#198050 = FILL_AREA_STYLE('',(#198051)); -#198051 = FILL_AREA_STYLE_COLOUR('',#195083); -#198052 = OVER_RIDING_STYLED_ITEM('overriding color',(#198053),#122916, - #195018); -#198053 = PRESENTATION_STYLE_ASSIGNMENT((#198054)); -#198054 = SURFACE_STYLE_USAGE(.BOTH.,#198055); -#198055 = SURFACE_SIDE_STYLE('',(#198056)); -#198056 = SURFACE_STYLE_FILL_AREA(#198057); -#198057 = FILL_AREA_STYLE('',(#198058)); -#198058 = FILL_AREA_STYLE_COLOUR('',#195083); -#198059 = OVER_RIDING_STYLED_ITEM('overriding color',(#198060),#122971, - #195018); -#198060 = PRESENTATION_STYLE_ASSIGNMENT((#198061)); -#198061 = SURFACE_STYLE_USAGE(.BOTH.,#198062); -#198062 = SURFACE_SIDE_STYLE('',(#198063)); -#198063 = SURFACE_STYLE_FILL_AREA(#198064); -#198064 = FILL_AREA_STYLE('',(#198065)); -#198065 = FILL_AREA_STYLE_COLOUR('',#195083); -#198066 = OVER_RIDING_STYLED_ITEM('overriding color',(#198067),#122998, - #195018); -#198067 = PRESENTATION_STYLE_ASSIGNMENT((#198068)); -#198068 = SURFACE_STYLE_USAGE(.BOTH.,#198069); -#198069 = SURFACE_SIDE_STYLE('',(#198070)); -#198070 = SURFACE_STYLE_FILL_AREA(#198071); -#198071 = FILL_AREA_STYLE('',(#198072)); -#198072 = FILL_AREA_STYLE_COLOUR('',#195083); -#198073 = OVER_RIDING_STYLED_ITEM('overriding color',(#198074),#123033, - #195018); -#198074 = PRESENTATION_STYLE_ASSIGNMENT((#198075)); -#198075 = SURFACE_STYLE_USAGE(.BOTH.,#198076); -#198076 = SURFACE_SIDE_STYLE('',(#198077)); -#198077 = SURFACE_STYLE_FILL_AREA(#198078); -#198078 = FILL_AREA_STYLE('',(#198079)); -#198079 = FILL_AREA_STYLE_COLOUR('',#195083); -#198080 = OVER_RIDING_STYLED_ITEM('overriding color',(#198081),#123040, - #195018); -#198081 = PRESENTATION_STYLE_ASSIGNMENT((#198082)); -#198082 = SURFACE_STYLE_USAGE(.BOTH.,#198083); -#198083 = SURFACE_SIDE_STYLE('',(#198084)); -#198084 = SURFACE_STYLE_FILL_AREA(#198085); -#198085 = FILL_AREA_STYLE('',(#198086)); -#198086 = FILL_AREA_STYLE_COLOUR('',#195083); -#198087 = OVER_RIDING_STYLED_ITEM('overriding color',(#198088),#123149, - #195018); -#198088 = PRESENTATION_STYLE_ASSIGNMENT((#198089)); -#198089 = SURFACE_STYLE_USAGE(.BOTH.,#198090); -#198090 = SURFACE_SIDE_STYLE('',(#198091)); -#198091 = SURFACE_STYLE_FILL_AREA(#198092); -#198092 = FILL_AREA_STYLE('',(#198093)); -#198093 = FILL_AREA_STYLE_COLOUR('',#195083); -#198094 = OVER_RIDING_STYLED_ITEM('overriding color',(#198095),#123253, - #195018); -#198095 = PRESENTATION_STYLE_ASSIGNMENT((#198096)); -#198096 = SURFACE_STYLE_USAGE(.BOTH.,#198097); -#198097 = SURFACE_SIDE_STYLE('',(#198098)); -#198098 = SURFACE_STYLE_FILL_AREA(#198099); -#198099 = FILL_AREA_STYLE('',(#198100)); -#198100 = FILL_AREA_STYLE_COLOUR('',#195083); -#198101 = OVER_RIDING_STYLED_ITEM('overriding color',(#198102),#123332, - #195018); -#198102 = PRESENTATION_STYLE_ASSIGNMENT((#198103)); -#198103 = SURFACE_STYLE_USAGE(.BOTH.,#198104); -#198104 = SURFACE_SIDE_STYLE('',(#198105)); -#198105 = SURFACE_STYLE_FILL_AREA(#198106); -#198106 = FILL_AREA_STYLE('',(#198107)); -#198107 = FILL_AREA_STYLE_COLOUR('',#195083); -#198108 = OVER_RIDING_STYLED_ITEM('overriding color',(#198109),#123411, - #195018); -#198109 = PRESENTATION_STYLE_ASSIGNMENT((#198110)); -#198110 = SURFACE_STYLE_USAGE(.BOTH.,#198111); -#198111 = SURFACE_SIDE_STYLE('',(#198112)); -#198112 = SURFACE_STYLE_FILL_AREA(#198113); -#198113 = FILL_AREA_STYLE('',(#198114)); -#198114 = FILL_AREA_STYLE_COLOUR('',#195083); -#198115 = OVER_RIDING_STYLED_ITEM('overriding color',(#198116),#123486, - #195018); -#198116 = PRESENTATION_STYLE_ASSIGNMENT((#198117)); -#198117 = SURFACE_STYLE_USAGE(.BOTH.,#198118); -#198118 = SURFACE_SIDE_STYLE('',(#198119)); -#198119 = SURFACE_STYLE_FILL_AREA(#198120); -#198120 = FILL_AREA_STYLE('',(#198121)); -#198121 = FILL_AREA_STYLE_COLOUR('',#195083); -#198122 = OVER_RIDING_STYLED_ITEM('overriding color',(#198123),#123561, - #195018); -#198123 = PRESENTATION_STYLE_ASSIGNMENT((#198124)); -#198124 = SURFACE_STYLE_USAGE(.BOTH.,#198125); -#198125 = SURFACE_SIDE_STYLE('',(#198126)); -#198126 = SURFACE_STYLE_FILL_AREA(#198127); -#198127 = FILL_AREA_STYLE('',(#198128)); -#198128 = FILL_AREA_STYLE_COLOUR('',#195083); -#198129 = OVER_RIDING_STYLED_ITEM('overriding color',(#198130),#123635, - #195018); -#198130 = PRESENTATION_STYLE_ASSIGNMENT((#198131)); -#198131 = SURFACE_STYLE_USAGE(.BOTH.,#198132); -#198132 = SURFACE_SIDE_STYLE('',(#198133)); -#198133 = SURFACE_STYLE_FILL_AREA(#198134); -#198134 = FILL_AREA_STYLE('',(#198135)); -#198135 = FILL_AREA_STYLE_COLOUR('',#195083); -#198136 = OVER_RIDING_STYLED_ITEM('overriding color',(#198137),#123709, - #195018); -#198137 = PRESENTATION_STYLE_ASSIGNMENT((#198138)); -#198138 = SURFACE_STYLE_USAGE(.BOTH.,#198139); -#198139 = SURFACE_SIDE_STYLE('',(#198140)); -#198140 = SURFACE_STYLE_FILL_AREA(#198141); -#198141 = FILL_AREA_STYLE('',(#198142)); -#198142 = FILL_AREA_STYLE_COLOUR('',#195083); -#198143 = OVER_RIDING_STYLED_ITEM('overriding color',(#198144),#123784, - #195018); -#198144 = PRESENTATION_STYLE_ASSIGNMENT((#198145)); -#198145 = SURFACE_STYLE_USAGE(.BOTH.,#198146); -#198146 = SURFACE_SIDE_STYLE('',(#198147)); -#198147 = SURFACE_STYLE_FILL_AREA(#198148); -#198148 = FILL_AREA_STYLE('',(#198149)); -#198149 = FILL_AREA_STYLE_COLOUR('',#195083); -#198150 = OVER_RIDING_STYLED_ITEM('overriding color',(#198151),#123811, - #195018); -#198151 = PRESENTATION_STYLE_ASSIGNMENT((#198152)); -#198152 = SURFACE_STYLE_USAGE(.BOTH.,#198153); -#198153 = SURFACE_SIDE_STYLE('',(#198154)); -#198154 = SURFACE_STYLE_FILL_AREA(#198155); -#198155 = FILL_AREA_STYLE('',(#198156)); -#198156 = FILL_AREA_STYLE_COLOUR('',#195083); -#198157 = OVER_RIDING_STYLED_ITEM('overriding color',(#198158),#123866, - #195018); -#198158 = PRESENTATION_STYLE_ASSIGNMENT((#198159)); -#198159 = SURFACE_STYLE_USAGE(.BOTH.,#198160); -#198160 = SURFACE_SIDE_STYLE('',(#198161)); -#198161 = SURFACE_STYLE_FILL_AREA(#198162); -#198162 = FILL_AREA_STYLE('',(#198163)); -#198163 = FILL_AREA_STYLE_COLOUR('',#195083); -#198164 = OVER_RIDING_STYLED_ITEM('overriding color',(#198165),#123873, - #195018); -#198165 = PRESENTATION_STYLE_ASSIGNMENT((#198166)); -#198166 = SURFACE_STYLE_USAGE(.BOTH.,#198167); -#198167 = SURFACE_SIDE_STYLE('',(#198168)); -#198168 = SURFACE_STYLE_FILL_AREA(#198169); -#198169 = FILL_AREA_STYLE('',(#198170)); -#198170 = FILL_AREA_STYLE_COLOUR('',#195083); -#198171 = OVER_RIDING_STYLED_ITEM('overriding color',(#198172),#123880, - #195018); -#198172 = PRESENTATION_STYLE_ASSIGNMENT((#198173)); -#198173 = SURFACE_STYLE_USAGE(.BOTH.,#198174); -#198174 = SURFACE_SIDE_STYLE('',(#198175)); -#198175 = SURFACE_STYLE_FILL_AREA(#198176); -#198176 = FILL_AREA_STYLE('',(#198177)); -#198177 = FILL_AREA_STYLE_COLOUR('',#195083); -#198178 = OVER_RIDING_STYLED_ITEM('overriding color',(#198179),#123989, - #195018); -#198179 = PRESENTATION_STYLE_ASSIGNMENT((#198180)); -#198180 = SURFACE_STYLE_USAGE(.BOTH.,#198181); -#198181 = SURFACE_SIDE_STYLE('',(#198182)); -#198182 = SURFACE_STYLE_FILL_AREA(#198183); -#198183 = FILL_AREA_STYLE('',(#198184)); -#198184 = FILL_AREA_STYLE_COLOUR('',#195083); -#198185 = OVER_RIDING_STYLED_ITEM('overriding color',(#198186),#124093, - #195018); -#198186 = PRESENTATION_STYLE_ASSIGNMENT((#198187)); -#198187 = SURFACE_STYLE_USAGE(.BOTH.,#198188); -#198188 = SURFACE_SIDE_STYLE('',(#198189)); -#198189 = SURFACE_STYLE_FILL_AREA(#198190); -#198190 = FILL_AREA_STYLE('',(#198191)); -#198191 = FILL_AREA_STYLE_COLOUR('',#195083); -#198192 = OVER_RIDING_STYLED_ITEM('overriding color',(#198193),#124172, - #195018); -#198193 = PRESENTATION_STYLE_ASSIGNMENT((#198194)); -#198194 = SURFACE_STYLE_USAGE(.BOTH.,#198195); -#198195 = SURFACE_SIDE_STYLE('',(#198196)); -#198196 = SURFACE_STYLE_FILL_AREA(#198197); -#198197 = FILL_AREA_STYLE('',(#198198)); -#198198 = FILL_AREA_STYLE_COLOUR('',#195083); -#198199 = OVER_RIDING_STYLED_ITEM('overriding color',(#198200),#124251, - #195018); -#198200 = PRESENTATION_STYLE_ASSIGNMENT((#198201)); -#198201 = SURFACE_STYLE_USAGE(.BOTH.,#198202); -#198202 = SURFACE_SIDE_STYLE('',(#198203)); -#198203 = SURFACE_STYLE_FILL_AREA(#198204); -#198204 = FILL_AREA_STYLE('',(#198205)); -#198205 = FILL_AREA_STYLE_COLOUR('',#195083); -#198206 = OVER_RIDING_STYLED_ITEM('overriding color',(#198207),#124326, - #195018); -#198207 = PRESENTATION_STYLE_ASSIGNMENT((#198208)); -#198208 = SURFACE_STYLE_USAGE(.BOTH.,#198209); -#198209 = SURFACE_SIDE_STYLE('',(#198210)); -#198210 = SURFACE_STYLE_FILL_AREA(#198211); -#198211 = FILL_AREA_STYLE('',(#198212)); -#198212 = FILL_AREA_STYLE_COLOUR('',#195083); -#198213 = OVER_RIDING_STYLED_ITEM('overriding color',(#198214),#124401, - #195018); -#198214 = PRESENTATION_STYLE_ASSIGNMENT((#198215)); -#198215 = SURFACE_STYLE_USAGE(.BOTH.,#198216); -#198216 = SURFACE_SIDE_STYLE('',(#198217)); -#198217 = SURFACE_STYLE_FILL_AREA(#198218); -#198218 = FILL_AREA_STYLE('',(#198219)); -#198219 = FILL_AREA_STYLE_COLOUR('',#195083); -#198220 = OVER_RIDING_STYLED_ITEM('overriding color',(#198221),#124475, - #195018); -#198221 = PRESENTATION_STYLE_ASSIGNMENT((#198222)); -#198222 = SURFACE_STYLE_USAGE(.BOTH.,#198223); -#198223 = SURFACE_SIDE_STYLE('',(#198224)); -#198224 = SURFACE_STYLE_FILL_AREA(#198225); -#198225 = FILL_AREA_STYLE('',(#198226)); -#198226 = FILL_AREA_STYLE_COLOUR('',#195083); -#198227 = OVER_RIDING_STYLED_ITEM('overriding color',(#198228),#124549, - #195018); -#198228 = PRESENTATION_STYLE_ASSIGNMENT((#198229)); -#198229 = SURFACE_STYLE_USAGE(.BOTH.,#198230); -#198230 = SURFACE_SIDE_STYLE('',(#198231)); -#198231 = SURFACE_STYLE_FILL_AREA(#198232); -#198232 = FILL_AREA_STYLE('',(#198233)); -#198233 = FILL_AREA_STYLE_COLOUR('',#195083); -#198234 = OVER_RIDING_STYLED_ITEM('overriding color',(#198235),#124596, - #195018); -#198235 = PRESENTATION_STYLE_ASSIGNMENT((#198236)); -#198236 = SURFACE_STYLE_USAGE(.BOTH.,#198237); -#198237 = SURFACE_SIDE_STYLE('',(#198238)); -#198238 = SURFACE_STYLE_FILL_AREA(#198239); -#198239 = FILL_AREA_STYLE('',(#198240)); -#198240 = FILL_AREA_STYLE_COLOUR('',#195083); -#198241 = OVER_RIDING_STYLED_ITEM('overriding color',(#198242),#124651, - #195018); -#198242 = PRESENTATION_STYLE_ASSIGNMENT((#198243)); -#198243 = SURFACE_STYLE_USAGE(.BOTH.,#198244); -#198244 = SURFACE_SIDE_STYLE('',(#198245)); -#198245 = SURFACE_STYLE_FILL_AREA(#198246); -#198246 = FILL_AREA_STYLE('',(#198247)); -#198247 = FILL_AREA_STYLE_COLOUR('',#195083); -#198248 = OVER_RIDING_STYLED_ITEM('overriding color',(#198249),#124678, - #195018); -#198249 = PRESENTATION_STYLE_ASSIGNMENT((#198250)); -#198250 = SURFACE_STYLE_USAGE(.BOTH.,#198251); -#198251 = SURFACE_SIDE_STYLE('',(#198252)); -#198252 = SURFACE_STYLE_FILL_AREA(#198253); -#198253 = FILL_AREA_STYLE('',(#198254)); -#198254 = FILL_AREA_STYLE_COLOUR('',#195083); -#198255 = OVER_RIDING_STYLED_ITEM('overriding color',(#198256),#124713, - #195018); -#198256 = PRESENTATION_STYLE_ASSIGNMENT((#198257)); -#198257 = SURFACE_STYLE_USAGE(.BOTH.,#198258); -#198258 = SURFACE_SIDE_STYLE('',(#198259)); -#198259 = SURFACE_STYLE_FILL_AREA(#198260); -#198260 = FILL_AREA_STYLE('',(#198261)); -#198261 = FILL_AREA_STYLE_COLOUR('',#195083); -#198262 = OVER_RIDING_STYLED_ITEM('overriding color',(#198263),#124720, - #195018); -#198263 = PRESENTATION_STYLE_ASSIGNMENT((#198264)); -#198264 = SURFACE_STYLE_USAGE(.BOTH.,#198265); -#198265 = SURFACE_SIDE_STYLE('',(#198266)); -#198266 = SURFACE_STYLE_FILL_AREA(#198267); -#198267 = FILL_AREA_STYLE('',(#198268)); -#198268 = FILL_AREA_STYLE_COLOUR('',#195083); -#198269 = OVER_RIDING_STYLED_ITEM('overriding color',(#198270),#124829, - #195018); -#198270 = PRESENTATION_STYLE_ASSIGNMENT((#198271)); -#198271 = SURFACE_STYLE_USAGE(.BOTH.,#198272); -#198272 = SURFACE_SIDE_STYLE('',(#198273)); -#198273 = SURFACE_STYLE_FILL_AREA(#198274); -#198274 = FILL_AREA_STYLE('',(#198275)); -#198275 = FILL_AREA_STYLE_COLOUR('',#195083); -#198276 = OVER_RIDING_STYLED_ITEM('overriding color',(#198277),#124933, - #195018); -#198277 = PRESENTATION_STYLE_ASSIGNMENT((#198278)); -#198278 = SURFACE_STYLE_USAGE(.BOTH.,#198279); -#198279 = SURFACE_SIDE_STYLE('',(#198280)); -#198280 = SURFACE_STYLE_FILL_AREA(#198281); -#198281 = FILL_AREA_STYLE('',(#198282)); -#198282 = FILL_AREA_STYLE_COLOUR('',#195083); -#198283 = OVER_RIDING_STYLED_ITEM('overriding color',(#198284),#125012, - #195018); -#198284 = PRESENTATION_STYLE_ASSIGNMENT((#198285)); -#198285 = SURFACE_STYLE_USAGE(.BOTH.,#198286); -#198286 = SURFACE_SIDE_STYLE('',(#198287)); -#198287 = SURFACE_STYLE_FILL_AREA(#198288); -#198288 = FILL_AREA_STYLE('',(#198289)); -#198289 = FILL_AREA_STYLE_COLOUR('',#195083); -#198290 = OVER_RIDING_STYLED_ITEM('overriding color',(#198291),#125091, - #195018); -#198291 = PRESENTATION_STYLE_ASSIGNMENT((#198292)); -#198292 = SURFACE_STYLE_USAGE(.BOTH.,#198293); -#198293 = SURFACE_SIDE_STYLE('',(#198294)); -#198294 = SURFACE_STYLE_FILL_AREA(#198295); -#198295 = FILL_AREA_STYLE('',(#198296)); -#198296 = FILL_AREA_STYLE_COLOUR('',#195083); -#198297 = OVER_RIDING_STYLED_ITEM('overriding color',(#198298),#125166, - #195018); -#198298 = PRESENTATION_STYLE_ASSIGNMENT((#198299)); -#198299 = SURFACE_STYLE_USAGE(.BOTH.,#198300); -#198300 = SURFACE_SIDE_STYLE('',(#198301)); -#198301 = SURFACE_STYLE_FILL_AREA(#198302); -#198302 = FILL_AREA_STYLE('',(#198303)); -#198303 = FILL_AREA_STYLE_COLOUR('',#195083); -#198304 = OVER_RIDING_STYLED_ITEM('overriding color',(#198305),#125241, - #195018); -#198305 = PRESENTATION_STYLE_ASSIGNMENT((#198306)); -#198306 = SURFACE_STYLE_USAGE(.BOTH.,#198307); -#198307 = SURFACE_SIDE_STYLE('',(#198308)); -#198308 = SURFACE_STYLE_FILL_AREA(#198309); -#198309 = FILL_AREA_STYLE('',(#198310)); -#198310 = FILL_AREA_STYLE_COLOUR('',#195083); -#198311 = OVER_RIDING_STYLED_ITEM('overriding color',(#198312),#125315, - #195018); -#198312 = PRESENTATION_STYLE_ASSIGNMENT((#198313)); -#198313 = SURFACE_STYLE_USAGE(.BOTH.,#198314); -#198314 = SURFACE_SIDE_STYLE('',(#198315)); -#198315 = SURFACE_STYLE_FILL_AREA(#198316); -#198316 = FILL_AREA_STYLE('',(#198317)); -#198317 = FILL_AREA_STYLE_COLOUR('',#195083); -#198318 = OVER_RIDING_STYLED_ITEM('overriding color',(#198319),#125389, - #195018); -#198319 = PRESENTATION_STYLE_ASSIGNMENT((#198320)); -#198320 = SURFACE_STYLE_USAGE(.BOTH.,#198321); -#198321 = SURFACE_SIDE_STYLE('',(#198322)); -#198322 = SURFACE_STYLE_FILL_AREA(#198323); -#198323 = FILL_AREA_STYLE('',(#198324)); -#198324 = FILL_AREA_STYLE_COLOUR('',#195083); -#198325 = OVER_RIDING_STYLED_ITEM('overriding color',(#198326),#125436, - #195018); -#198326 = PRESENTATION_STYLE_ASSIGNMENT((#198327)); -#198327 = SURFACE_STYLE_USAGE(.BOTH.,#198328); -#198328 = SURFACE_SIDE_STYLE('',(#198329)); -#198329 = SURFACE_STYLE_FILL_AREA(#198330); -#198330 = FILL_AREA_STYLE('',(#198331)); -#198331 = FILL_AREA_STYLE_COLOUR('',#195083); -#198332 = OVER_RIDING_STYLED_ITEM('overriding color',(#198333),#125491, - #195018); -#198333 = PRESENTATION_STYLE_ASSIGNMENT((#198334)); -#198334 = SURFACE_STYLE_USAGE(.BOTH.,#198335); -#198335 = SURFACE_SIDE_STYLE('',(#198336)); -#198336 = SURFACE_STYLE_FILL_AREA(#198337); -#198337 = FILL_AREA_STYLE('',(#198338)); -#198338 = FILL_AREA_STYLE_COLOUR('',#195083); -#198339 = OVER_RIDING_STYLED_ITEM('overriding color',(#198340),#125518, - #195018); -#198340 = PRESENTATION_STYLE_ASSIGNMENT((#198341)); -#198341 = SURFACE_STYLE_USAGE(.BOTH.,#198342); -#198342 = SURFACE_SIDE_STYLE('',(#198343)); -#198343 = SURFACE_STYLE_FILL_AREA(#198344); -#198344 = FILL_AREA_STYLE('',(#198345)); -#198345 = FILL_AREA_STYLE_COLOUR('',#195083); -#198346 = OVER_RIDING_STYLED_ITEM('overriding color',(#198347),#125553, - #195018); -#198347 = PRESENTATION_STYLE_ASSIGNMENT((#198348)); -#198348 = SURFACE_STYLE_USAGE(.BOTH.,#198349); -#198349 = SURFACE_SIDE_STYLE('',(#198350)); -#198350 = SURFACE_STYLE_FILL_AREA(#198351); -#198351 = FILL_AREA_STYLE('',(#198352)); -#198352 = FILL_AREA_STYLE_COLOUR('',#195083); -#198353 = OVER_RIDING_STYLED_ITEM('overriding color',(#198354),#125560, - #195018); +#197680 = FILL_AREA_STYLE_COLOUR('',#197681); +#197681 = COLOUR_RGB('',0.96862745285,0.800000011921,0.435294121504); +#197682 = CURVE_STYLE('',#197683,POSITIVE_LENGTH_MEASURE(0.1),#197681); +#197683 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#197684 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #197685,#197693,#197701,#197708,#197715,#197722,#197729,#197736, + #197743,#197750,#197757,#197764,#197771,#197778,#197785,#197792, + #197799,#197806,#197813,#197820,#197827,#197834,#197841,#197848, + #197855,#197862,#197869,#197876,#197883,#197890,#197897,#197904, + #197911,#197918,#197925,#197932,#197939,#197946,#197953,#197960, + #197967,#197974,#197981,#197988,#197995,#198002,#198009,#198016, + #198023,#198030,#198037,#198044,#198051,#198058,#198065,#198072, + #198079,#198086,#198093,#198100,#198107,#198114,#198121,#198128, + #198135,#198142,#198149,#198156,#198163,#198170,#198177,#198184, + #198191,#198198,#198205,#198212,#198219,#198226,#198233,#198240, + #198247,#198254,#198261,#198268,#198275,#198282,#198289,#198296, + #198303,#198310,#198317,#198324,#198331,#198338,#198345),#168390); +#197685 = STYLED_ITEM('color',(#197686),#161100); +#197686 = PRESENTATION_STYLE_ASSIGNMENT((#197687)); +#197687 = SURFACE_STYLE_USAGE(.BOTH.,#197688); +#197688 = SURFACE_SIDE_STYLE('',(#197689)); +#197689 = SURFACE_STYLE_FILL_AREA(#197690); +#197690 = FILL_AREA_STYLE('',(#197691)); +#197691 = FILL_AREA_STYLE_COLOUR('',#197692); +#197692 = COLOUR_RGB('',0.780392169952,0.780392169952,0.86274510622); +#197693 = OVER_RIDING_STYLED_ITEM('overriding color',(#197694),#161102, + #197685); +#197694 = PRESENTATION_STYLE_ASSIGNMENT((#197695)); +#197695 = SURFACE_STYLE_USAGE(.BOTH.,#197696); +#197696 = SURFACE_SIDE_STYLE('',(#197697)); +#197697 = SURFACE_STYLE_FILL_AREA(#197698); +#197698 = FILL_AREA_STYLE('',(#197699)); +#197699 = FILL_AREA_STYLE_COLOUR('',#197700); +#197700 = COLOUR_RGB('',0.784313738346,0.784313738346,0.86274510622); +#197701 = OVER_RIDING_STYLED_ITEM('overriding color',(#197702),#161220, + #197685); +#197702 = PRESENTATION_STYLE_ASSIGNMENT((#197703)); +#197703 = SURFACE_STYLE_USAGE(.BOTH.,#197704); +#197704 = SURFACE_SIDE_STYLE('',(#197705)); +#197705 = SURFACE_STYLE_FILL_AREA(#197706); +#197706 = FILL_AREA_STYLE('',(#197707)); +#197707 = FILL_AREA_STYLE_COLOUR('',#197700); +#197708 = OVER_RIDING_STYLED_ITEM('overriding color',(#197709),#161303, + #197685); +#197709 = PRESENTATION_STYLE_ASSIGNMENT((#197710)); +#197710 = SURFACE_STYLE_USAGE(.BOTH.,#197711); +#197711 = SURFACE_SIDE_STYLE('',(#197712)); +#197712 = SURFACE_STYLE_FILL_AREA(#197713); +#197713 = FILL_AREA_STYLE('',(#197714)); +#197714 = FILL_AREA_STYLE_COLOUR('',#197700); +#197715 = OVER_RIDING_STYLED_ITEM('overriding color',(#197716),#161379, + #197685); +#197716 = PRESENTATION_STYLE_ASSIGNMENT((#197717)); +#197717 = SURFACE_STYLE_USAGE(.BOTH.,#197718); +#197718 = SURFACE_SIDE_STYLE('',(#197719)); +#197719 = SURFACE_STYLE_FILL_AREA(#197720); +#197720 = FILL_AREA_STYLE('',(#197721)); +#197721 = FILL_AREA_STYLE_COLOUR('',#197700); +#197722 = OVER_RIDING_STYLED_ITEM('overriding color',(#197723),#161455, + #197685); +#197723 = PRESENTATION_STYLE_ASSIGNMENT((#197724)); +#197724 = SURFACE_STYLE_USAGE(.BOTH.,#197725); +#197725 = SURFACE_SIDE_STYLE('',(#197726)); +#197726 = SURFACE_STYLE_FILL_AREA(#197727); +#197727 = FILL_AREA_STYLE('',(#197728)); +#197728 = FILL_AREA_STYLE_COLOUR('',#197700); +#197729 = OVER_RIDING_STYLED_ITEM('overriding color',(#197730),#161530, + #197685); +#197730 = PRESENTATION_STYLE_ASSIGNMENT((#197731)); +#197731 = SURFACE_STYLE_USAGE(.BOTH.,#197732); +#197732 = SURFACE_SIDE_STYLE('',(#197733)); +#197733 = SURFACE_STYLE_FILL_AREA(#197734); +#197734 = FILL_AREA_STYLE('',(#197735)); +#197735 = FILL_AREA_STYLE_COLOUR('',#197700); +#197736 = OVER_RIDING_STYLED_ITEM('overriding color',(#197737),#161605, + #197685); +#197737 = PRESENTATION_STYLE_ASSIGNMENT((#197738)); +#197738 = SURFACE_STYLE_USAGE(.BOTH.,#197739); +#197739 = SURFACE_SIDE_STYLE('',(#197740)); +#197740 = SURFACE_STYLE_FILL_AREA(#197741); +#197741 = FILL_AREA_STYLE('',(#197742)); +#197742 = FILL_AREA_STYLE_COLOUR('',#197700); +#197743 = OVER_RIDING_STYLED_ITEM('overriding color',(#197744),#161680, + #197685); +#197744 = PRESENTATION_STYLE_ASSIGNMENT((#197745)); +#197745 = SURFACE_STYLE_USAGE(.BOTH.,#197746); +#197746 = SURFACE_SIDE_STYLE('',(#197747)); +#197747 = SURFACE_STYLE_FILL_AREA(#197748); +#197748 = FILL_AREA_STYLE('',(#197749)); +#197749 = FILL_AREA_STYLE_COLOUR('',#197700); +#197750 = OVER_RIDING_STYLED_ITEM('overriding color',(#197751),#161763, + #197685); +#197751 = PRESENTATION_STYLE_ASSIGNMENT((#197752)); +#197752 = SURFACE_STYLE_USAGE(.BOTH.,#197753); +#197753 = SURFACE_SIDE_STYLE('',(#197754)); +#197754 = SURFACE_STYLE_FILL_AREA(#197755); +#197755 = FILL_AREA_STYLE('',(#197756)); +#197756 = FILL_AREA_STYLE_COLOUR('',#197700); +#197757 = OVER_RIDING_STYLED_ITEM('overriding color',(#197758),#161881, + #197685); +#197758 = PRESENTATION_STYLE_ASSIGNMENT((#197759)); +#197759 = SURFACE_STYLE_USAGE(.BOTH.,#197760); +#197760 = SURFACE_SIDE_STYLE('',(#197761)); +#197761 = SURFACE_STYLE_FILL_AREA(#197762); +#197762 = FILL_AREA_STYLE('',(#197763)); +#197763 = FILL_AREA_STYLE_COLOUR('',#197700); +#197764 = OVER_RIDING_STYLED_ITEM('overriding color',(#197765),#161964, + #197685); +#197765 = PRESENTATION_STYLE_ASSIGNMENT((#197766)); +#197766 = SURFACE_STYLE_USAGE(.BOTH.,#197767); +#197767 = SURFACE_SIDE_STYLE('',(#197768)); +#197768 = SURFACE_STYLE_FILL_AREA(#197769); +#197769 = FILL_AREA_STYLE('',(#197770)); +#197770 = FILL_AREA_STYLE_COLOUR('',#197700); +#197771 = OVER_RIDING_STYLED_ITEM('overriding color',(#197772),#162040, + #197685); +#197772 = PRESENTATION_STYLE_ASSIGNMENT((#197773)); +#197773 = SURFACE_STYLE_USAGE(.BOTH.,#197774); +#197774 = SURFACE_SIDE_STYLE('',(#197775)); +#197775 = SURFACE_STYLE_FILL_AREA(#197776); +#197776 = FILL_AREA_STYLE('',(#197777)); +#197777 = FILL_AREA_STYLE_COLOUR('',#197700); +#197778 = OVER_RIDING_STYLED_ITEM('overriding color',(#197779),#162116, + #197685); +#197779 = PRESENTATION_STYLE_ASSIGNMENT((#197780)); +#197780 = SURFACE_STYLE_USAGE(.BOTH.,#197781); +#197781 = SURFACE_SIDE_STYLE('',(#197782)); +#197782 = SURFACE_STYLE_FILL_AREA(#197783); +#197783 = FILL_AREA_STYLE('',(#197784)); +#197784 = FILL_AREA_STYLE_COLOUR('',#197700); +#197785 = OVER_RIDING_STYLED_ITEM('overriding color',(#197786),#162191, + #197685); +#197786 = PRESENTATION_STYLE_ASSIGNMENT((#197787)); +#197787 = SURFACE_STYLE_USAGE(.BOTH.,#197788); +#197788 = SURFACE_SIDE_STYLE('',(#197789)); +#197789 = SURFACE_STYLE_FILL_AREA(#197790); +#197790 = FILL_AREA_STYLE('',(#197791)); +#197791 = FILL_AREA_STYLE_COLOUR('',#197700); +#197792 = OVER_RIDING_STYLED_ITEM('overriding color',(#197793),#162266, + #197685); +#197793 = PRESENTATION_STYLE_ASSIGNMENT((#197794)); +#197794 = SURFACE_STYLE_USAGE(.BOTH.,#197795); +#197795 = SURFACE_SIDE_STYLE('',(#197796)); +#197796 = SURFACE_STYLE_FILL_AREA(#197797); +#197797 = FILL_AREA_STYLE('',(#197798)); +#197798 = FILL_AREA_STYLE_COLOUR('',#197700); +#197799 = OVER_RIDING_STYLED_ITEM('overriding color',(#197800),#162341, + #197685); +#197800 = PRESENTATION_STYLE_ASSIGNMENT((#197801)); +#197801 = SURFACE_STYLE_USAGE(.BOTH.,#197802); +#197802 = SURFACE_SIDE_STYLE('',(#197803)); +#197803 = SURFACE_STYLE_FILL_AREA(#197804); +#197804 = FILL_AREA_STYLE('',(#197805)); +#197805 = FILL_AREA_STYLE_COLOUR('',#197700); +#197806 = OVER_RIDING_STYLED_ITEM('overriding color',(#197807),#162419, + #197685); +#197807 = PRESENTATION_STYLE_ASSIGNMENT((#197808)); +#197808 = SURFACE_STYLE_USAGE(.BOTH.,#197809); +#197809 = SURFACE_SIDE_STYLE('',(#197810)); +#197810 = SURFACE_STYLE_FILL_AREA(#197811); +#197811 = FILL_AREA_STYLE('',(#197812)); +#197812 = FILL_AREA_STYLE_COLOUR('',#197700); +#197813 = OVER_RIDING_STYLED_ITEM('overriding color',(#197814),#162537, + #197685); +#197814 = PRESENTATION_STYLE_ASSIGNMENT((#197815)); +#197815 = SURFACE_STYLE_USAGE(.BOTH.,#197816); +#197816 = SURFACE_SIDE_STYLE('',(#197817)); +#197817 = SURFACE_STYLE_FILL_AREA(#197818); +#197818 = FILL_AREA_STYLE('',(#197819)); +#197819 = FILL_AREA_STYLE_COLOUR('',#197700); +#197820 = OVER_RIDING_STYLED_ITEM('overriding color',(#197821),#162620, + #197685); +#197821 = PRESENTATION_STYLE_ASSIGNMENT((#197822)); +#197822 = SURFACE_STYLE_USAGE(.BOTH.,#197823); +#197823 = SURFACE_SIDE_STYLE('',(#197824)); +#197824 = SURFACE_STYLE_FILL_AREA(#197825); +#197825 = FILL_AREA_STYLE('',(#197826)); +#197826 = FILL_AREA_STYLE_COLOUR('',#197700); +#197827 = OVER_RIDING_STYLED_ITEM('overriding color',(#197828),#162696, + #197685); +#197828 = PRESENTATION_STYLE_ASSIGNMENT((#197829)); +#197829 = SURFACE_STYLE_USAGE(.BOTH.,#197830); +#197830 = SURFACE_SIDE_STYLE('',(#197831)); +#197831 = SURFACE_STYLE_FILL_AREA(#197832); +#197832 = FILL_AREA_STYLE('',(#197833)); +#197833 = FILL_AREA_STYLE_COLOUR('',#197700); +#197834 = OVER_RIDING_STYLED_ITEM('overriding color',(#197835),#162772, + #197685); +#197835 = PRESENTATION_STYLE_ASSIGNMENT((#197836)); +#197836 = SURFACE_STYLE_USAGE(.BOTH.,#197837); +#197837 = SURFACE_SIDE_STYLE('',(#197838)); +#197838 = SURFACE_STYLE_FILL_AREA(#197839); +#197839 = FILL_AREA_STYLE('',(#197840)); +#197840 = FILL_AREA_STYLE_COLOUR('',#197700); +#197841 = OVER_RIDING_STYLED_ITEM('overriding color',(#197842),#162847, + #197685); +#197842 = PRESENTATION_STYLE_ASSIGNMENT((#197843)); +#197843 = SURFACE_STYLE_USAGE(.BOTH.,#197844); +#197844 = SURFACE_SIDE_STYLE('',(#197845)); +#197845 = SURFACE_STYLE_FILL_AREA(#197846); +#197846 = FILL_AREA_STYLE('',(#197847)); +#197847 = FILL_AREA_STYLE_COLOUR('',#197700); +#197848 = OVER_RIDING_STYLED_ITEM('overriding color',(#197849),#162922, + #197685); +#197849 = PRESENTATION_STYLE_ASSIGNMENT((#197850)); +#197850 = SURFACE_STYLE_USAGE(.BOTH.,#197851); +#197851 = SURFACE_SIDE_STYLE('',(#197852)); +#197852 = SURFACE_STYLE_FILL_AREA(#197853); +#197853 = FILL_AREA_STYLE('',(#197854)); +#197854 = FILL_AREA_STYLE_COLOUR('',#197700); +#197855 = OVER_RIDING_STYLED_ITEM('overriding color',(#197856),#162997, + #197685); +#197856 = PRESENTATION_STYLE_ASSIGNMENT((#197857)); +#197857 = SURFACE_STYLE_USAGE(.BOTH.,#197858); +#197858 = SURFACE_SIDE_STYLE('',(#197859)); +#197859 = SURFACE_STYLE_FILL_AREA(#197860); +#197860 = FILL_AREA_STYLE('',(#197861)); +#197861 = FILL_AREA_STYLE_COLOUR('',#197700); +#197862 = OVER_RIDING_STYLED_ITEM('overriding color',(#197863),#163075, + #197685); +#197863 = PRESENTATION_STYLE_ASSIGNMENT((#197864)); +#197864 = SURFACE_STYLE_USAGE(.BOTH.,#197865); +#197865 = SURFACE_SIDE_STYLE('',(#197866)); +#197866 = SURFACE_STYLE_FILL_AREA(#197867); +#197867 = FILL_AREA_STYLE('',(#197868)); +#197868 = FILL_AREA_STYLE_COLOUR('',#197700); +#197869 = OVER_RIDING_STYLED_ITEM('overriding color',(#197870),#163188, + #197685); +#197870 = PRESENTATION_STYLE_ASSIGNMENT((#197871)); +#197871 = SURFACE_STYLE_USAGE(.BOTH.,#197872); +#197872 = SURFACE_SIDE_STYLE('',(#197873)); +#197873 = SURFACE_STYLE_FILL_AREA(#197874); +#197874 = FILL_AREA_STYLE('',(#197875)); +#197875 = FILL_AREA_STYLE_COLOUR('',#197700); +#197876 = OVER_RIDING_STYLED_ITEM('overriding color',(#197877),#163271, + #197685); +#197877 = PRESENTATION_STYLE_ASSIGNMENT((#197878)); +#197878 = SURFACE_STYLE_USAGE(.BOTH.,#197879); +#197879 = SURFACE_SIDE_STYLE('',(#197880)); +#197880 = SURFACE_STYLE_FILL_AREA(#197881); +#197881 = FILL_AREA_STYLE('',(#197882)); +#197882 = FILL_AREA_STYLE_COLOUR('',#197700); +#197883 = OVER_RIDING_STYLED_ITEM('overriding color',(#197884),#163347, + #197685); +#197884 = PRESENTATION_STYLE_ASSIGNMENT((#197885)); +#197885 = SURFACE_STYLE_USAGE(.BOTH.,#197886); +#197886 = SURFACE_SIDE_STYLE('',(#197887)); +#197887 = SURFACE_STYLE_FILL_AREA(#197888); +#197888 = FILL_AREA_STYLE('',(#197889)); +#197889 = FILL_AREA_STYLE_COLOUR('',#197700); +#197890 = OVER_RIDING_STYLED_ITEM('overriding color',(#197891),#163423, + #197685); +#197891 = PRESENTATION_STYLE_ASSIGNMENT((#197892)); +#197892 = SURFACE_STYLE_USAGE(.BOTH.,#197893); +#197893 = SURFACE_SIDE_STYLE('',(#197894)); +#197894 = SURFACE_STYLE_FILL_AREA(#197895); +#197895 = FILL_AREA_STYLE('',(#197896)); +#197896 = FILL_AREA_STYLE_COLOUR('',#197700); +#197897 = OVER_RIDING_STYLED_ITEM('overriding color',(#197898),#163498, + #197685); +#197898 = PRESENTATION_STYLE_ASSIGNMENT((#197899)); +#197899 = SURFACE_STYLE_USAGE(.BOTH.,#197900); +#197900 = SURFACE_SIDE_STYLE('',(#197901)); +#197901 = SURFACE_STYLE_FILL_AREA(#197902); +#197902 = FILL_AREA_STYLE('',(#197903)); +#197903 = FILL_AREA_STYLE_COLOUR('',#197700); +#197904 = OVER_RIDING_STYLED_ITEM('overriding color',(#197905),#163573, + #197685); +#197905 = PRESENTATION_STYLE_ASSIGNMENT((#197906)); +#197906 = SURFACE_STYLE_USAGE(.BOTH.,#197907); +#197907 = SURFACE_SIDE_STYLE('',(#197908)); +#197908 = SURFACE_STYLE_FILL_AREA(#197909); +#197909 = FILL_AREA_STYLE('',(#197910)); +#197910 = FILL_AREA_STYLE_COLOUR('',#197700); +#197911 = OVER_RIDING_STYLED_ITEM('overriding color',(#197912),#163648, + #197685); +#197912 = PRESENTATION_STYLE_ASSIGNMENT((#197913)); +#197913 = SURFACE_STYLE_USAGE(.BOTH.,#197914); +#197914 = SURFACE_SIDE_STYLE('',(#197915)); +#197915 = SURFACE_STYLE_FILL_AREA(#197916); +#197916 = FILL_AREA_STYLE('',(#197917)); +#197917 = FILL_AREA_STYLE_COLOUR('',#197700); +#197918 = OVER_RIDING_STYLED_ITEM('overriding color',(#197919),#163726, + #197685); +#197919 = PRESENTATION_STYLE_ASSIGNMENT((#197920)); +#197920 = SURFACE_STYLE_USAGE(.BOTH.,#197921); +#197921 = SURFACE_SIDE_STYLE('',(#197922)); +#197922 = SURFACE_STYLE_FILL_AREA(#197923); +#197923 = FILL_AREA_STYLE('',(#197924)); +#197924 = FILL_AREA_STYLE_COLOUR('',#197700); +#197925 = OVER_RIDING_STYLED_ITEM('overriding color',(#197926),#163844, + #197685); +#197926 = PRESENTATION_STYLE_ASSIGNMENT((#197927)); +#197927 = SURFACE_STYLE_USAGE(.BOTH.,#197928); +#197928 = SURFACE_SIDE_STYLE('',(#197929)); +#197929 = SURFACE_STYLE_FILL_AREA(#197930); +#197930 = FILL_AREA_STYLE('',(#197931)); +#197931 = FILL_AREA_STYLE_COLOUR('',#197700); +#197932 = OVER_RIDING_STYLED_ITEM('overriding color',(#197933),#163927, + #197685); +#197933 = PRESENTATION_STYLE_ASSIGNMENT((#197934)); +#197934 = SURFACE_STYLE_USAGE(.BOTH.,#197935); +#197935 = SURFACE_SIDE_STYLE('',(#197936)); +#197936 = SURFACE_STYLE_FILL_AREA(#197937); +#197937 = FILL_AREA_STYLE('',(#197938)); +#197938 = FILL_AREA_STYLE_COLOUR('',#197700); +#197939 = OVER_RIDING_STYLED_ITEM('overriding color',(#197940),#164003, + #197685); +#197940 = PRESENTATION_STYLE_ASSIGNMENT((#197941)); +#197941 = SURFACE_STYLE_USAGE(.BOTH.,#197942); +#197942 = SURFACE_SIDE_STYLE('',(#197943)); +#197943 = SURFACE_STYLE_FILL_AREA(#197944); +#197944 = FILL_AREA_STYLE('',(#197945)); +#197945 = FILL_AREA_STYLE_COLOUR('',#197700); +#197946 = OVER_RIDING_STYLED_ITEM('overriding color',(#197947),#164079, + #197685); +#197947 = PRESENTATION_STYLE_ASSIGNMENT((#197948)); +#197948 = SURFACE_STYLE_USAGE(.BOTH.,#197949); +#197949 = SURFACE_SIDE_STYLE('',(#197950)); +#197950 = SURFACE_STYLE_FILL_AREA(#197951); +#197951 = FILL_AREA_STYLE('',(#197952)); +#197952 = FILL_AREA_STYLE_COLOUR('',#197700); +#197953 = OVER_RIDING_STYLED_ITEM('overriding color',(#197954),#164154, + #197685); +#197954 = PRESENTATION_STYLE_ASSIGNMENT((#197955)); +#197955 = SURFACE_STYLE_USAGE(.BOTH.,#197956); +#197956 = SURFACE_SIDE_STYLE('',(#197957)); +#197957 = SURFACE_STYLE_FILL_AREA(#197958); +#197958 = FILL_AREA_STYLE('',(#197959)); +#197959 = FILL_AREA_STYLE_COLOUR('',#197700); +#197960 = OVER_RIDING_STYLED_ITEM('overriding color',(#197961),#164229, + #197685); +#197961 = PRESENTATION_STYLE_ASSIGNMENT((#197962)); +#197962 = SURFACE_STYLE_USAGE(.BOTH.,#197963); +#197963 = SURFACE_SIDE_STYLE('',(#197964)); +#197964 = SURFACE_STYLE_FILL_AREA(#197965); +#197965 = FILL_AREA_STYLE('',(#197966)); +#197966 = FILL_AREA_STYLE_COLOUR('',#197700); +#197967 = OVER_RIDING_STYLED_ITEM('overriding color',(#197968),#164304, + #197685); +#197968 = PRESENTATION_STYLE_ASSIGNMENT((#197969)); +#197969 = SURFACE_STYLE_USAGE(.BOTH.,#197970); +#197970 = SURFACE_SIDE_STYLE('',(#197971)); +#197971 = SURFACE_STYLE_FILL_AREA(#197972); +#197972 = FILL_AREA_STYLE('',(#197973)); +#197973 = FILL_AREA_STYLE_COLOUR('',#197700); +#197974 = OVER_RIDING_STYLED_ITEM('overriding color',(#197975),#164382, + #197685); +#197975 = PRESENTATION_STYLE_ASSIGNMENT((#197976)); +#197976 = SURFACE_STYLE_USAGE(.BOTH.,#197977); +#197977 = SURFACE_SIDE_STYLE('',(#197978)); +#197978 = SURFACE_STYLE_FILL_AREA(#197979); +#197979 = FILL_AREA_STYLE('',(#197980)); +#197980 = FILL_AREA_STYLE_COLOUR('',#197700); +#197981 = OVER_RIDING_STYLED_ITEM('overriding color',(#197982),#164500, + #197685); +#197982 = PRESENTATION_STYLE_ASSIGNMENT((#197983)); +#197983 = SURFACE_STYLE_USAGE(.BOTH.,#197984); +#197984 = SURFACE_SIDE_STYLE('',(#197985)); +#197985 = SURFACE_STYLE_FILL_AREA(#197986); +#197986 = FILL_AREA_STYLE('',(#197987)); +#197987 = FILL_AREA_STYLE_COLOUR('',#197700); +#197988 = OVER_RIDING_STYLED_ITEM('overriding color',(#197989),#164583, + #197685); +#197989 = PRESENTATION_STYLE_ASSIGNMENT((#197990)); +#197990 = SURFACE_STYLE_USAGE(.BOTH.,#197991); +#197991 = SURFACE_SIDE_STYLE('',(#197992)); +#197992 = SURFACE_STYLE_FILL_AREA(#197993); +#197993 = FILL_AREA_STYLE('',(#197994)); +#197994 = FILL_AREA_STYLE_COLOUR('',#197700); +#197995 = OVER_RIDING_STYLED_ITEM('overriding color',(#197996),#164659, + #197685); +#197996 = PRESENTATION_STYLE_ASSIGNMENT((#197997)); +#197997 = SURFACE_STYLE_USAGE(.BOTH.,#197998); +#197998 = SURFACE_SIDE_STYLE('',(#197999)); +#197999 = SURFACE_STYLE_FILL_AREA(#198000); +#198000 = FILL_AREA_STYLE('',(#198001)); +#198001 = FILL_AREA_STYLE_COLOUR('',#197700); +#198002 = OVER_RIDING_STYLED_ITEM('overriding color',(#198003),#164735, + #197685); +#198003 = PRESENTATION_STYLE_ASSIGNMENT((#198004)); +#198004 = SURFACE_STYLE_USAGE(.BOTH.,#198005); +#198005 = SURFACE_SIDE_STYLE('',(#198006)); +#198006 = SURFACE_STYLE_FILL_AREA(#198007); +#198007 = FILL_AREA_STYLE('',(#198008)); +#198008 = FILL_AREA_STYLE_COLOUR('',#197700); +#198009 = OVER_RIDING_STYLED_ITEM('overriding color',(#198010),#164810, + #197685); +#198010 = PRESENTATION_STYLE_ASSIGNMENT((#198011)); +#198011 = SURFACE_STYLE_USAGE(.BOTH.,#198012); +#198012 = SURFACE_SIDE_STYLE('',(#198013)); +#198013 = SURFACE_STYLE_FILL_AREA(#198014); +#198014 = FILL_AREA_STYLE('',(#198015)); +#198015 = FILL_AREA_STYLE_COLOUR('',#197700); +#198016 = OVER_RIDING_STYLED_ITEM('overriding color',(#198017),#164885, + #197685); +#198017 = PRESENTATION_STYLE_ASSIGNMENT((#198018)); +#198018 = SURFACE_STYLE_USAGE(.BOTH.,#198019); +#198019 = SURFACE_SIDE_STYLE('',(#198020)); +#198020 = SURFACE_STYLE_FILL_AREA(#198021); +#198021 = FILL_AREA_STYLE('',(#198022)); +#198022 = FILL_AREA_STYLE_COLOUR('',#197700); +#198023 = OVER_RIDING_STYLED_ITEM('overriding color',(#198024),#164960, + #197685); +#198024 = PRESENTATION_STYLE_ASSIGNMENT((#198025)); +#198025 = SURFACE_STYLE_USAGE(.BOTH.,#198026); +#198026 = SURFACE_SIDE_STYLE('',(#198027)); +#198027 = SURFACE_STYLE_FILL_AREA(#198028); +#198028 = FILL_AREA_STYLE('',(#198029)); +#198029 = FILL_AREA_STYLE_COLOUR('',#197700); +#198030 = OVER_RIDING_STYLED_ITEM('overriding color',(#198031),#165038, + #197685); +#198031 = PRESENTATION_STYLE_ASSIGNMENT((#198032)); +#198032 = SURFACE_STYLE_USAGE(.BOTH.,#198033); +#198033 = SURFACE_SIDE_STYLE('',(#198034)); +#198034 = SURFACE_STYLE_FILL_AREA(#198035); +#198035 = FILL_AREA_STYLE('',(#198036)); +#198036 = FILL_AREA_STYLE_COLOUR('',#197700); +#198037 = OVER_RIDING_STYLED_ITEM('overriding color',(#198038),#165156, + #197685); +#198038 = PRESENTATION_STYLE_ASSIGNMENT((#198039)); +#198039 = SURFACE_STYLE_USAGE(.BOTH.,#198040); +#198040 = SURFACE_SIDE_STYLE('',(#198041)); +#198041 = SURFACE_STYLE_FILL_AREA(#198042); +#198042 = FILL_AREA_STYLE('',(#198043)); +#198043 = FILL_AREA_STYLE_COLOUR('',#197700); +#198044 = OVER_RIDING_STYLED_ITEM('overriding color',(#198045),#165239, + #197685); +#198045 = PRESENTATION_STYLE_ASSIGNMENT((#198046)); +#198046 = SURFACE_STYLE_USAGE(.BOTH.,#198047); +#198047 = SURFACE_SIDE_STYLE('',(#198048)); +#198048 = SURFACE_STYLE_FILL_AREA(#198049); +#198049 = FILL_AREA_STYLE('',(#198050)); +#198050 = FILL_AREA_STYLE_COLOUR('',#197700); +#198051 = OVER_RIDING_STYLED_ITEM('overriding color',(#198052),#165315, + #197685); +#198052 = PRESENTATION_STYLE_ASSIGNMENT((#198053)); +#198053 = SURFACE_STYLE_USAGE(.BOTH.,#198054); +#198054 = SURFACE_SIDE_STYLE('',(#198055)); +#198055 = SURFACE_STYLE_FILL_AREA(#198056); +#198056 = FILL_AREA_STYLE('',(#198057)); +#198057 = FILL_AREA_STYLE_COLOUR('',#197700); +#198058 = OVER_RIDING_STYLED_ITEM('overriding color',(#198059),#165391, + #197685); +#198059 = PRESENTATION_STYLE_ASSIGNMENT((#198060)); +#198060 = SURFACE_STYLE_USAGE(.BOTH.,#198061); +#198061 = SURFACE_SIDE_STYLE('',(#198062)); +#198062 = SURFACE_STYLE_FILL_AREA(#198063); +#198063 = FILL_AREA_STYLE('',(#198064)); +#198064 = FILL_AREA_STYLE_COLOUR('',#197700); +#198065 = OVER_RIDING_STYLED_ITEM('overriding color',(#198066),#165466, + #197685); +#198066 = PRESENTATION_STYLE_ASSIGNMENT((#198067)); +#198067 = SURFACE_STYLE_USAGE(.BOTH.,#198068); +#198068 = SURFACE_SIDE_STYLE('',(#198069)); +#198069 = SURFACE_STYLE_FILL_AREA(#198070); +#198070 = FILL_AREA_STYLE('',(#198071)); +#198071 = FILL_AREA_STYLE_COLOUR('',#197700); +#198072 = OVER_RIDING_STYLED_ITEM('overriding color',(#198073),#165541, + #197685); +#198073 = PRESENTATION_STYLE_ASSIGNMENT((#198074)); +#198074 = SURFACE_STYLE_USAGE(.BOTH.,#198075); +#198075 = SURFACE_SIDE_STYLE('',(#198076)); +#198076 = SURFACE_STYLE_FILL_AREA(#198077); +#198077 = FILL_AREA_STYLE('',(#198078)); +#198078 = FILL_AREA_STYLE_COLOUR('',#197700); +#198079 = OVER_RIDING_STYLED_ITEM('overriding color',(#198080),#165616, + #197685); +#198080 = PRESENTATION_STYLE_ASSIGNMENT((#198081)); +#198081 = SURFACE_STYLE_USAGE(.BOTH.,#198082); +#198082 = SURFACE_SIDE_STYLE('',(#198083)); +#198083 = SURFACE_STYLE_FILL_AREA(#198084); +#198084 = FILL_AREA_STYLE('',(#198085)); +#198085 = FILL_AREA_STYLE_COLOUR('',#197700); +#198086 = OVER_RIDING_STYLED_ITEM('overriding color',(#198087),#165694, + #197685); +#198087 = PRESENTATION_STYLE_ASSIGNMENT((#198088)); +#198088 = SURFACE_STYLE_USAGE(.BOTH.,#198089); +#198089 = SURFACE_SIDE_STYLE('',(#198090)); +#198090 = SURFACE_STYLE_FILL_AREA(#198091); +#198091 = FILL_AREA_STYLE('',(#198092)); +#198092 = FILL_AREA_STYLE_COLOUR('',#197700); +#198093 = OVER_RIDING_STYLED_ITEM('overriding color',(#198094),#165807, + #197685); +#198094 = PRESENTATION_STYLE_ASSIGNMENT((#198095)); +#198095 = SURFACE_STYLE_USAGE(.BOTH.,#198096); +#198096 = SURFACE_SIDE_STYLE('',(#198097)); +#198097 = SURFACE_STYLE_FILL_AREA(#198098); +#198098 = FILL_AREA_STYLE('',(#198099)); +#198099 = FILL_AREA_STYLE_COLOUR('',#197700); +#198100 = OVER_RIDING_STYLED_ITEM('overriding color',(#198101),#165890, + #197685); +#198101 = PRESENTATION_STYLE_ASSIGNMENT((#198102)); +#198102 = SURFACE_STYLE_USAGE(.BOTH.,#198103); +#198103 = SURFACE_SIDE_STYLE('',(#198104)); +#198104 = SURFACE_STYLE_FILL_AREA(#198105); +#198105 = FILL_AREA_STYLE('',(#198106)); +#198106 = FILL_AREA_STYLE_COLOUR('',#197700); +#198107 = OVER_RIDING_STYLED_ITEM('overriding color',(#198108),#165966, + #197685); +#198108 = PRESENTATION_STYLE_ASSIGNMENT((#198109)); +#198109 = SURFACE_STYLE_USAGE(.BOTH.,#198110); +#198110 = SURFACE_SIDE_STYLE('',(#198111)); +#198111 = SURFACE_STYLE_FILL_AREA(#198112); +#198112 = FILL_AREA_STYLE('',(#198113)); +#198113 = FILL_AREA_STYLE_COLOUR('',#197700); +#198114 = OVER_RIDING_STYLED_ITEM('overriding color',(#198115),#166042, + #197685); +#198115 = PRESENTATION_STYLE_ASSIGNMENT((#198116)); +#198116 = SURFACE_STYLE_USAGE(.BOTH.,#198117); +#198117 = SURFACE_SIDE_STYLE('',(#198118)); +#198118 = SURFACE_STYLE_FILL_AREA(#198119); +#198119 = FILL_AREA_STYLE('',(#198120)); +#198120 = FILL_AREA_STYLE_COLOUR('',#197700); +#198121 = OVER_RIDING_STYLED_ITEM('overriding color',(#198122),#166117, + #197685); +#198122 = PRESENTATION_STYLE_ASSIGNMENT((#198123)); +#198123 = SURFACE_STYLE_USAGE(.BOTH.,#198124); +#198124 = SURFACE_SIDE_STYLE('',(#198125)); +#198125 = SURFACE_STYLE_FILL_AREA(#198126); +#198126 = FILL_AREA_STYLE('',(#198127)); +#198127 = FILL_AREA_STYLE_COLOUR('',#197700); +#198128 = OVER_RIDING_STYLED_ITEM('overriding color',(#198129),#166192, + #197685); +#198129 = PRESENTATION_STYLE_ASSIGNMENT((#198130)); +#198130 = SURFACE_STYLE_USAGE(.BOTH.,#198131); +#198131 = SURFACE_SIDE_STYLE('',(#198132)); +#198132 = SURFACE_STYLE_FILL_AREA(#198133); +#198133 = FILL_AREA_STYLE('',(#198134)); +#198134 = FILL_AREA_STYLE_COLOUR('',#197700); +#198135 = OVER_RIDING_STYLED_ITEM('overriding color',(#198136),#166267, + #197685); +#198136 = PRESENTATION_STYLE_ASSIGNMENT((#198137)); +#198137 = SURFACE_STYLE_USAGE(.BOTH.,#198138); +#198138 = SURFACE_SIDE_STYLE('',(#198139)); +#198139 = SURFACE_STYLE_FILL_AREA(#198140); +#198140 = FILL_AREA_STYLE('',(#198141)); +#198141 = FILL_AREA_STYLE_COLOUR('',#197700); +#198142 = OVER_RIDING_STYLED_ITEM('overriding color',(#198143),#166345, + #197685); +#198143 = PRESENTATION_STYLE_ASSIGNMENT((#198144)); +#198144 = SURFACE_STYLE_USAGE(.BOTH.,#198145); +#198145 = SURFACE_SIDE_STYLE('',(#198146)); +#198146 = SURFACE_STYLE_FILL_AREA(#198147); +#198147 = FILL_AREA_STYLE('',(#198148)); +#198148 = FILL_AREA_STYLE_COLOUR('',#197700); +#198149 = OVER_RIDING_STYLED_ITEM('overriding color',(#198150),#166830, + #197685); +#198150 = PRESENTATION_STYLE_ASSIGNMENT((#198151)); +#198151 = SURFACE_STYLE_USAGE(.BOTH.,#198152); +#198152 = SURFACE_SIDE_STYLE('',(#198153)); +#198153 = SURFACE_STYLE_FILL_AREA(#198154); +#198154 = FILL_AREA_STYLE('',(#198155)); +#198155 = FILL_AREA_STYLE_COLOUR('',#197700); +#198156 = OVER_RIDING_STYLED_ITEM('overriding color',(#198157),#166918, + #197685); +#198157 = PRESENTATION_STYLE_ASSIGNMENT((#198158)); +#198158 = SURFACE_STYLE_USAGE(.BOTH.,#198159); +#198159 = SURFACE_SIDE_STYLE('',(#198160)); +#198160 = SURFACE_STYLE_FILL_AREA(#198161); +#198161 = FILL_AREA_STYLE('',(#198162)); +#198162 = FILL_AREA_STYLE_COLOUR('',#197700); +#198163 = OVER_RIDING_STYLED_ITEM('overriding color',(#198164),#166966, + #197685); +#198164 = PRESENTATION_STYLE_ASSIGNMENT((#198165)); +#198165 = SURFACE_STYLE_USAGE(.BOTH.,#198166); +#198166 = SURFACE_SIDE_STYLE('',(#198167)); +#198167 = SURFACE_STYLE_FILL_AREA(#198168); +#198168 = FILL_AREA_STYLE('',(#198169)); +#198169 = FILL_AREA_STYLE_COLOUR('',#197700); +#198170 = OVER_RIDING_STYLED_ITEM('overriding color',(#198171),#167023, + #197685); +#198171 = PRESENTATION_STYLE_ASSIGNMENT((#198172)); +#198172 = SURFACE_STYLE_USAGE(.BOTH.,#198173); +#198173 = SURFACE_SIDE_STYLE('',(#198174)); +#198174 = SURFACE_STYLE_FILL_AREA(#198175); +#198175 = FILL_AREA_STYLE('',(#198176)); +#198176 = FILL_AREA_STYLE_COLOUR('',#197700); +#198177 = OVER_RIDING_STYLED_ITEM('overriding color',(#198178),#167072, + #197685); +#198178 = PRESENTATION_STYLE_ASSIGNMENT((#198179)); +#198179 = SURFACE_STYLE_USAGE(.BOTH.,#198180); +#198180 = SURFACE_SIDE_STYLE('',(#198181)); +#198181 = SURFACE_STYLE_FILL_AREA(#198182); +#198182 = FILL_AREA_STYLE('',(#198183)); +#198183 = FILL_AREA_STYLE_COLOUR('',#197700); +#198184 = OVER_RIDING_STYLED_ITEM('overriding color',(#198185),#167133, + #197685); +#198185 = PRESENTATION_STYLE_ASSIGNMENT((#198186)); +#198186 = SURFACE_STYLE_USAGE(.BOTH.,#198187); +#198187 = SURFACE_SIDE_STYLE('',(#198188)); +#198188 = SURFACE_STYLE_FILL_AREA(#198189); +#198189 = FILL_AREA_STYLE('',(#198190)); +#198190 = FILL_AREA_STYLE_COLOUR('',#197700); +#198191 = OVER_RIDING_STYLED_ITEM('overriding color',(#198192),#167181, + #197685); +#198192 = PRESENTATION_STYLE_ASSIGNMENT((#198193)); +#198193 = SURFACE_STYLE_USAGE(.BOTH.,#198194); +#198194 = SURFACE_SIDE_STYLE('',(#198195)); +#198195 = SURFACE_STYLE_FILL_AREA(#198196); +#198196 = FILL_AREA_STYLE('',(#198197)); +#198197 = FILL_AREA_STYLE_COLOUR('',#197700); +#198198 = OVER_RIDING_STYLED_ITEM('overriding color',(#198199),#167238, + #197685); +#198199 = PRESENTATION_STYLE_ASSIGNMENT((#198200)); +#198200 = SURFACE_STYLE_USAGE(.BOTH.,#198201); +#198201 = SURFACE_SIDE_STYLE('',(#198202)); +#198202 = SURFACE_STYLE_FILL_AREA(#198203); +#198203 = FILL_AREA_STYLE('',(#198204)); +#198204 = FILL_AREA_STYLE_COLOUR('',#197700); +#198205 = OVER_RIDING_STYLED_ITEM('overriding color',(#198206),#167287, + #197685); +#198206 = PRESENTATION_STYLE_ASSIGNMENT((#198207)); +#198207 = SURFACE_STYLE_USAGE(.BOTH.,#198208); +#198208 = SURFACE_SIDE_STYLE('',(#198209)); +#198209 = SURFACE_STYLE_FILL_AREA(#198210); +#198210 = FILL_AREA_STYLE('',(#198211)); +#198211 = FILL_AREA_STYLE_COLOUR('',#197700); +#198212 = OVER_RIDING_STYLED_ITEM('overriding color',(#198213),#167348, + #197685); +#198213 = PRESENTATION_STYLE_ASSIGNMENT((#198214)); +#198214 = SURFACE_STYLE_USAGE(.BOTH.,#198215); +#198215 = SURFACE_SIDE_STYLE('',(#198216)); +#198216 = SURFACE_STYLE_FILL_AREA(#198217); +#198217 = FILL_AREA_STYLE('',(#198218)); +#198218 = FILL_AREA_STYLE_COLOUR('',#197700); +#198219 = OVER_RIDING_STYLED_ITEM('overriding color',(#198220),#167396, + #197685); +#198220 = PRESENTATION_STYLE_ASSIGNMENT((#198221)); +#198221 = SURFACE_STYLE_USAGE(.BOTH.,#198222); +#198222 = SURFACE_SIDE_STYLE('',(#198223)); +#198223 = SURFACE_STYLE_FILL_AREA(#198224); +#198224 = FILL_AREA_STYLE('',(#198225)); +#198225 = FILL_AREA_STYLE_COLOUR('',#197700); +#198226 = OVER_RIDING_STYLED_ITEM('overriding color',(#198227),#167465, + #197685); +#198227 = PRESENTATION_STYLE_ASSIGNMENT((#198228)); +#198228 = SURFACE_STYLE_USAGE(.BOTH.,#198229); +#198229 = SURFACE_SIDE_STYLE('',(#198230)); +#198230 = SURFACE_STYLE_FILL_AREA(#198231); +#198231 = FILL_AREA_STYLE('',(#198232)); +#198232 = FILL_AREA_STYLE_COLOUR('',#197700); +#198233 = OVER_RIDING_STYLED_ITEM('overriding color',(#198234),#167513, + #197685); +#198234 = PRESENTATION_STYLE_ASSIGNMENT((#198235)); +#198235 = SURFACE_STYLE_USAGE(.BOTH.,#198236); +#198236 = SURFACE_SIDE_STYLE('',(#198237)); +#198237 = SURFACE_STYLE_FILL_AREA(#198238); +#198238 = FILL_AREA_STYLE('',(#198239)); +#198239 = FILL_AREA_STYLE_COLOUR('',#197700); +#198240 = OVER_RIDING_STYLED_ITEM('overriding color',(#198241),#167570, + #197685); +#198241 = PRESENTATION_STYLE_ASSIGNMENT((#198242)); +#198242 = SURFACE_STYLE_USAGE(.BOTH.,#198243); +#198243 = SURFACE_SIDE_STYLE('',(#198244)); +#198244 = SURFACE_STYLE_FILL_AREA(#198245); +#198245 = FILL_AREA_STYLE('',(#198246)); +#198246 = FILL_AREA_STYLE_COLOUR('',#197700); +#198247 = OVER_RIDING_STYLED_ITEM('overriding color',(#198248),#167619, + #197685); +#198248 = PRESENTATION_STYLE_ASSIGNMENT((#198249)); +#198249 = SURFACE_STYLE_USAGE(.BOTH.,#198250); +#198250 = SURFACE_SIDE_STYLE('',(#198251)); +#198251 = SURFACE_STYLE_FILL_AREA(#198252); +#198252 = FILL_AREA_STYLE('',(#198253)); +#198253 = FILL_AREA_STYLE_COLOUR('',#197700); +#198254 = OVER_RIDING_STYLED_ITEM('overriding color',(#198255),#167680, + #197685); +#198255 = PRESENTATION_STYLE_ASSIGNMENT((#198256)); +#198256 = SURFACE_STYLE_USAGE(.BOTH.,#198257); +#198257 = SURFACE_SIDE_STYLE('',(#198258)); +#198258 = SURFACE_STYLE_FILL_AREA(#198259); +#198259 = FILL_AREA_STYLE('',(#198260)); +#198260 = FILL_AREA_STYLE_COLOUR('',#197700); +#198261 = OVER_RIDING_STYLED_ITEM('overriding color',(#198262),#167728, + #197685); +#198262 = PRESENTATION_STYLE_ASSIGNMENT((#198263)); +#198263 = SURFACE_STYLE_USAGE(.BOTH.,#198264); +#198264 = SURFACE_SIDE_STYLE('',(#198265)); +#198265 = SURFACE_STYLE_FILL_AREA(#198266); +#198266 = FILL_AREA_STYLE('',(#198267)); +#198267 = FILL_AREA_STYLE_COLOUR('',#197700); +#198268 = OVER_RIDING_STYLED_ITEM('overriding color',(#198269),#167785, + #197685); +#198269 = PRESENTATION_STYLE_ASSIGNMENT((#198270)); +#198270 = SURFACE_STYLE_USAGE(.BOTH.,#198271); +#198271 = SURFACE_SIDE_STYLE('',(#198272)); +#198272 = SURFACE_STYLE_FILL_AREA(#198273); +#198273 = FILL_AREA_STYLE('',(#198274)); +#198274 = FILL_AREA_STYLE_COLOUR('',#197700); +#198275 = OVER_RIDING_STYLED_ITEM('overriding color',(#198276),#167834, + #197685); +#198276 = PRESENTATION_STYLE_ASSIGNMENT((#198277)); +#198277 = SURFACE_STYLE_USAGE(.BOTH.,#198278); +#198278 = SURFACE_SIDE_STYLE('',(#198279)); +#198279 = SURFACE_STYLE_FILL_AREA(#198280); +#198280 = FILL_AREA_STYLE('',(#198281)); +#198281 = FILL_AREA_STYLE_COLOUR('',#197700); +#198282 = OVER_RIDING_STYLED_ITEM('overriding color',(#198283),#167895, + #197685); +#198283 = PRESENTATION_STYLE_ASSIGNMENT((#198284)); +#198284 = SURFACE_STYLE_USAGE(.BOTH.,#198285); +#198285 = SURFACE_SIDE_STYLE('',(#198286)); +#198286 = SURFACE_STYLE_FILL_AREA(#198287); +#198287 = FILL_AREA_STYLE('',(#198288)); +#198288 = FILL_AREA_STYLE_COLOUR('',#197700); +#198289 = OVER_RIDING_STYLED_ITEM('overriding color',(#198290),#167943, + #197685); +#198290 = PRESENTATION_STYLE_ASSIGNMENT((#198291)); +#198291 = SURFACE_STYLE_USAGE(.BOTH.,#198292); +#198292 = SURFACE_SIDE_STYLE('',(#198293)); +#198293 = SURFACE_STYLE_FILL_AREA(#198294); +#198294 = FILL_AREA_STYLE('',(#198295)); +#198295 = FILL_AREA_STYLE_COLOUR('',#197700); +#198296 = OVER_RIDING_STYLED_ITEM('overriding color',(#198297),#168000, + #197685); +#198297 = PRESENTATION_STYLE_ASSIGNMENT((#198298)); +#198298 = SURFACE_STYLE_USAGE(.BOTH.,#198299); +#198299 = SURFACE_SIDE_STYLE('',(#198300)); +#198300 = SURFACE_STYLE_FILL_AREA(#198301); +#198301 = FILL_AREA_STYLE('',(#198302)); +#198302 = FILL_AREA_STYLE_COLOUR('',#197700); +#198303 = OVER_RIDING_STYLED_ITEM('overriding color',(#198304),#168049, + #197685); +#198304 = PRESENTATION_STYLE_ASSIGNMENT((#198305)); +#198305 = SURFACE_STYLE_USAGE(.BOTH.,#198306); +#198306 = SURFACE_SIDE_STYLE('',(#198307)); +#198307 = SURFACE_STYLE_FILL_AREA(#198308); +#198308 = FILL_AREA_STYLE('',(#198309)); +#198309 = FILL_AREA_STYLE_COLOUR('',#197700); +#198310 = OVER_RIDING_STYLED_ITEM('overriding color',(#198311),#168110, + #197685); +#198311 = PRESENTATION_STYLE_ASSIGNMENT((#198312)); +#198312 = SURFACE_STYLE_USAGE(.BOTH.,#198313); +#198313 = SURFACE_SIDE_STYLE('',(#198314)); +#198314 = SURFACE_STYLE_FILL_AREA(#198315); +#198315 = FILL_AREA_STYLE('',(#198316)); +#198316 = FILL_AREA_STYLE_COLOUR('',#197700); +#198317 = OVER_RIDING_STYLED_ITEM('overriding color',(#198318),#168158, + #197685); +#198318 = PRESENTATION_STYLE_ASSIGNMENT((#198319)); +#198319 = SURFACE_STYLE_USAGE(.BOTH.,#198320); +#198320 = SURFACE_SIDE_STYLE('',(#198321)); +#198321 = SURFACE_STYLE_FILL_AREA(#198322); +#198322 = FILL_AREA_STYLE('',(#198323)); +#198323 = FILL_AREA_STYLE_COLOUR('',#197700); +#198324 = OVER_RIDING_STYLED_ITEM('overriding color',(#198325),#168227, + #197685); +#198325 = PRESENTATION_STYLE_ASSIGNMENT((#198326)); +#198326 = SURFACE_STYLE_USAGE(.BOTH.,#198327); +#198327 = SURFACE_SIDE_STYLE('',(#198328)); +#198328 = SURFACE_STYLE_FILL_AREA(#198329); +#198329 = FILL_AREA_STYLE('',(#198330)); +#198330 = FILL_AREA_STYLE_COLOUR('',#197700); +#198331 = OVER_RIDING_STYLED_ITEM('overriding color',(#198332),#168275, + #197685); +#198332 = PRESENTATION_STYLE_ASSIGNMENT((#198333)); +#198333 = SURFACE_STYLE_USAGE(.BOTH.,#198334); +#198334 = SURFACE_SIDE_STYLE('',(#198335)); +#198335 = SURFACE_STYLE_FILL_AREA(#198336); +#198336 = FILL_AREA_STYLE('',(#198337)); +#198337 = FILL_AREA_STYLE_COLOUR('',#197700); +#198338 = OVER_RIDING_STYLED_ITEM('overriding color',(#198339),#168332, + #197685); +#198339 = PRESENTATION_STYLE_ASSIGNMENT((#198340)); +#198340 = SURFACE_STYLE_USAGE(.BOTH.,#198341); +#198341 = SURFACE_SIDE_STYLE('',(#198342)); +#198342 = SURFACE_STYLE_FILL_AREA(#198343); +#198343 = FILL_AREA_STYLE('',(#198344)); +#198344 = FILL_AREA_STYLE_COLOUR('',#197700); +#198345 = OVER_RIDING_STYLED_ITEM('overriding color',(#198346),#168359, + #197685); +#198346 = PRESENTATION_STYLE_ASSIGNMENT((#198347)); +#198347 = SURFACE_STYLE_USAGE(.BOTH.,#198348); +#198348 = SURFACE_SIDE_STYLE('',(#198349)); +#198349 = SURFACE_STYLE_FILL_AREA(#198350); +#198350 = FILL_AREA_STYLE('',(#198351)); +#198351 = FILL_AREA_STYLE_COLOUR('',#197700); +#198352 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #198353,#198361,#198369,#198376,#198383,#198390,#198397,#198404, + #198411,#198419,#198426,#198433,#198440,#198447,#198454,#198461, + #198468,#198475,#198482,#198489,#198496,#198503,#198510,#198517, + #198524,#198531,#198538,#198545,#198552,#198559,#198566,#198573, + #198580,#198587,#198594,#198601,#198608,#198615,#198622,#198629, + #198636,#198643,#198650,#198657,#198664,#198671,#198678,#198685, + #198692,#198699,#198706,#198713,#198720,#198727,#198734,#198741, + #198748,#198755,#198762,#198769,#198776,#198783,#198790,#198797, + #198804,#198811,#198818,#198825,#198832,#198839,#198846,#198853, + #198860,#198867,#198874,#198881,#198888,#198895,#198902,#198909, + #198916,#198923,#198930,#198937,#198944,#198951,#198958,#198965, + #198972,#198979,#198986,#198993,#199000,#199007,#199014,#199021, + #199028,#199035,#199042,#199049,#199056,#199063,#199070,#199077, + #199084,#199091,#199098,#199105,#199112,#199119,#199126,#199133, + #199140,#199147,#199154,#199161,#199168,#199175,#199182,#199189, + #199196,#199203,#199210,#199217,#199224,#199231,#199238,#199245, + #199252,#199259,#199266,#199273,#199280,#199287,#199294,#199301, + #199308,#199315,#199322,#199329,#199336,#199343,#199350,#199357, + #199364,#199371,#199378,#199385,#199392,#199399,#199406,#199413, + #199420,#199427,#199434,#199441,#199448,#199455,#199462,#199469, + #199476,#199483,#199490,#199497,#199504,#199511,#199518,#199525, + #199532,#199539,#199546,#199553,#199560,#199567,#199574,#199581, + #199588,#199595,#199602,#199609,#199616,#199623,#199630,#199637, + #199644,#199651,#199658,#199665,#199672,#199679,#199686,#199693, + #199700,#199707,#199714,#199721,#199728,#199735,#199742,#199749, + #199756,#199763,#199770,#199777,#199784,#199791,#199798,#199805, + #199812,#199819,#199826,#199833,#199840,#199847,#199854,#199861, + #199868,#199875,#199882,#199889,#199896,#199903,#199910,#199917, + #199924,#199931,#199938,#199945,#199952,#199959,#199966,#199973, + #199980,#199987,#199994,#200001,#200008,#200015,#200022,#200029, + #200036,#200043,#200050,#200057,#200064,#200071,#200078,#200085, + #200092,#200099,#200106,#200113,#200120,#200127,#200134,#200141, + #200148,#200155,#200162,#200169,#200176,#200183,#200190,#200197, + #200204,#200211,#200218,#200225,#200232,#200239,#200246,#200253, + #200260,#200267,#200274,#200281,#200288,#200295,#200302,#200309, + #200316,#200323,#200330,#200337,#200344,#200351,#200358,#200365, + #200372,#200379,#200386,#200393,#200400,#200407,#200414,#200421, + #200428,#200435,#200442,#200449,#200456,#200463,#200470,#200477, + #200484,#200491,#200498,#200505,#200512,#200519,#200526,#200533, + #200540,#200547,#200554,#200561,#200568,#200575,#200582,#200589, + #200596,#200603,#200610,#200617,#200624,#200631,#200638,#200645, + #200652,#200659,#200666,#200673,#200680,#200687,#200694,#200701, + #200708,#200715,#200722,#200729,#200736,#200743,#200750,#200757, + #200764,#200771,#200778,#200785,#200792,#200799,#200806,#200813, + #200820,#200827,#200834,#200841,#200848,#200855,#200862,#200869, + #200876,#200883,#200890,#200897,#200904,#200911,#200918,#200925, + #200932,#200939,#200946,#200953,#200960,#200967,#200974,#200981, + #200988,#200995,#201002,#201009,#201016,#201023,#201030,#201037, + #201044,#201051,#201058,#201065,#201072,#201079,#201086,#201093, + #201100,#201107,#201114,#201121,#201128,#201135,#201142,#201149, + #201156,#201163,#201170,#201177,#201184,#201191,#201198,#201205, + #201212,#201219,#201226,#201233,#201240,#201247,#201254,#201261, + #201268,#201275,#201282,#201289,#201296,#201303,#201310,#201317, + #201324,#201331,#201338,#201345,#201352,#201359,#201366,#201373, + #201380,#201387,#201394,#201401,#201408,#201415,#201422,#201429, + #201436,#201443,#201450,#201457,#201464,#201471,#201478,#201485, + #201492,#201499,#201506,#201513,#201520,#201527,#201534,#201541, + #201548,#201555,#201562,#201569,#201576,#201583,#201590,#201597, + #201604,#201611,#201618,#201625,#201632,#201639,#201646,#201653, + #201660,#201667,#201674,#201681,#201688,#201695,#201702,#201709, + #201716,#201723,#201730,#201737,#201744,#201751,#201758,#201765, + #201772,#201779,#201786,#201793,#201800,#201807,#201814,#201821, + #201828,#201835,#201842,#201849,#201856,#201863,#201870,#201877, + #201884,#201891,#201898,#201905,#201912,#201919,#201926,#201933, + #201940,#201947,#201954,#201961,#201968,#201975,#201982,#201989, + #201996,#202003,#202010,#202017,#202024,#202031,#202038,#202045, + #202052,#202059,#202066,#202073,#202080,#202087,#202094,#202101, + #202108,#202115,#202122,#202129,#202136,#202143,#202150,#202157, + #202164,#202171,#202178,#202185,#202192,#202199,#202206,#202213, + #202220,#202227,#202234,#202241,#202248,#202255,#202262,#202269, + #202276,#202283,#202290,#202297,#202304,#202311,#202318,#202325, + #202332,#202339,#202346,#202353,#202360,#202367,#202374,#202381, + #202388,#202395,#202402,#202409,#202416,#202423,#202430,#202437, + #202444,#202451,#202458,#202465,#202472,#202479,#202486,#202493, + #202500,#202507,#202514,#202521,#202528,#202535,#202542,#202549, + #202556,#202563,#202570,#202577,#202584,#202591,#202598,#202605, + #202612,#202619,#202626,#202633,#202640,#202647,#202654,#202661, + #202668,#202675,#202682,#202689,#202696,#202703,#202710,#202717, + #202724,#202731,#202738,#202745,#202752,#202759,#202766,#202773, + #202780,#202787,#202794,#202801,#202808,#202815,#202822,#202829, + #202836,#202843,#202850,#202857,#202864,#202871,#202878,#202885, + #202892,#202899,#202906,#202913,#202920,#202927,#202934,#202941, + #202948,#202955,#202962,#202969,#202976,#202983,#202990,#202997, + #203004,#203011,#203018,#203025,#203032,#203039,#203046,#203053, + #203060,#203067,#203074,#203081,#203088,#203095,#203102,#203109, + #203116,#203123,#203130,#203137,#203144,#203151,#203158,#203165, + #203172,#203179,#203186,#203193,#203200,#203207,#203214,#203221, + #203228,#203235,#203242,#203249,#203256,#203263,#203270,#203277, + #203284,#203291,#203298,#203305,#203312,#203319,#203326,#203333, + #203340,#203347,#203354,#203361,#203368,#203375,#203382,#203389, + #203396,#203403,#203410,#203417,#203424,#203431,#203438,#203445, + #203452,#203459,#203466,#203473,#203480,#203487,#203494,#203501, + #203508,#203515,#203522,#203529,#203536,#203543,#203550,#203557, + #203564,#203571,#203578,#203585,#203592,#203599,#203606,#203613, + #203620,#203627,#203634,#203641,#203648,#203655,#203662,#203669, + #203676,#203683,#203690,#203697,#203704,#203711,#203718,#203725, + #203732,#203739,#203746,#203753,#203760,#203767,#203774,#203781, + #203788,#203795,#203802,#203809,#203816,#203823,#203830,#203837, + #203844,#203851,#203858,#203865,#203872,#203879,#203886,#203893, + #203900,#203907,#203914,#203921,#203928,#203935,#203942,#203949, + #203956,#203963,#203970,#203977,#203984,#203991,#203998,#204005, + #204012,#204019,#204026,#204033,#204040,#204047,#204054,#204061, + #204068,#204075,#204082,#204089,#204096,#204103,#204110,#204117, + #204124,#204131,#204138,#204145,#204152,#204159,#204166,#204173, + #204180,#204187,#204194,#204201,#204208,#204215,#204222,#204229, + #204236,#204243,#204250,#204257,#204264,#204271,#204278,#204285, + #204292,#204299,#204306,#204313,#204320,#204327),#153592); +#198353 = STYLED_ITEM('color',(#198354),#88720); #198354 = PRESENTATION_STYLE_ASSIGNMENT((#198355)); #198355 = SURFACE_STYLE_USAGE(.BOTH.,#198356); #198356 = SURFACE_SIDE_STYLE('',(#198357)); #198357 = SURFACE_STYLE_FILL_AREA(#198358); #198358 = FILL_AREA_STYLE('',(#198359)); -#198359 = FILL_AREA_STYLE_COLOUR('',#195083); -#198360 = OVER_RIDING_STYLED_ITEM('overriding color',(#198361),#125669, - #195018); -#198361 = PRESENTATION_STYLE_ASSIGNMENT((#198362)); -#198362 = SURFACE_STYLE_USAGE(.BOTH.,#198363); -#198363 = SURFACE_SIDE_STYLE('',(#198364)); -#198364 = SURFACE_STYLE_FILL_AREA(#198365); -#198365 = FILL_AREA_STYLE('',(#198366)); -#198366 = FILL_AREA_STYLE_COLOUR('',#195083); -#198367 = OVER_RIDING_STYLED_ITEM('overriding color',(#198368),#125773, - #195018); -#198368 = PRESENTATION_STYLE_ASSIGNMENT((#198369)); -#198369 = SURFACE_STYLE_USAGE(.BOTH.,#198370); -#198370 = SURFACE_SIDE_STYLE('',(#198371)); -#198371 = SURFACE_STYLE_FILL_AREA(#198372); -#198372 = FILL_AREA_STYLE('',(#198373)); -#198373 = FILL_AREA_STYLE_COLOUR('',#195083); -#198374 = OVER_RIDING_STYLED_ITEM('overriding color',(#198375),#125852, - #195018); -#198375 = PRESENTATION_STYLE_ASSIGNMENT((#198376)); -#198376 = SURFACE_STYLE_USAGE(.BOTH.,#198377); -#198377 = SURFACE_SIDE_STYLE('',(#198378)); -#198378 = SURFACE_STYLE_FILL_AREA(#198379); -#198379 = FILL_AREA_STYLE('',(#198380)); -#198380 = FILL_AREA_STYLE_COLOUR('',#195083); -#198381 = OVER_RIDING_STYLED_ITEM('overriding color',(#198382),#125931, - #195018); -#198382 = PRESENTATION_STYLE_ASSIGNMENT((#198383)); -#198383 = SURFACE_STYLE_USAGE(.BOTH.,#198384); -#198384 = SURFACE_SIDE_STYLE('',(#198385)); -#198385 = SURFACE_STYLE_FILL_AREA(#198386); -#198386 = FILL_AREA_STYLE('',(#198387)); -#198387 = FILL_AREA_STYLE_COLOUR('',#195083); -#198388 = OVER_RIDING_STYLED_ITEM('overriding color',(#198389),#126006, - #195018); -#198389 = PRESENTATION_STYLE_ASSIGNMENT((#198390)); -#198390 = SURFACE_STYLE_USAGE(.BOTH.,#198391); -#198391 = SURFACE_SIDE_STYLE('',(#198392)); -#198392 = SURFACE_STYLE_FILL_AREA(#198393); -#198393 = FILL_AREA_STYLE('',(#198394)); -#198394 = FILL_AREA_STYLE_COLOUR('',#195083); -#198395 = OVER_RIDING_STYLED_ITEM('overriding color',(#198396),#126081, - #195018); -#198396 = PRESENTATION_STYLE_ASSIGNMENT((#198397)); -#198397 = SURFACE_STYLE_USAGE(.BOTH.,#198398); -#198398 = SURFACE_SIDE_STYLE('',(#198399)); -#198399 = SURFACE_STYLE_FILL_AREA(#198400); -#198400 = FILL_AREA_STYLE('',(#198401)); -#198401 = FILL_AREA_STYLE_COLOUR('',#195083); -#198402 = OVER_RIDING_STYLED_ITEM('overriding color',(#198403),#126155, - #195018); -#198403 = PRESENTATION_STYLE_ASSIGNMENT((#198404)); -#198404 = SURFACE_STYLE_USAGE(.BOTH.,#198405); -#198405 = SURFACE_SIDE_STYLE('',(#198406)); -#198406 = SURFACE_STYLE_FILL_AREA(#198407); -#198407 = FILL_AREA_STYLE('',(#198408)); -#198408 = FILL_AREA_STYLE_COLOUR('',#195083); -#198409 = OVER_RIDING_STYLED_ITEM('overriding color',(#198410),#126229, - #195018); -#198410 = PRESENTATION_STYLE_ASSIGNMENT((#198411)); -#198411 = SURFACE_STYLE_USAGE(.BOTH.,#198412); -#198412 = SURFACE_SIDE_STYLE('',(#198413)); -#198413 = SURFACE_STYLE_FILL_AREA(#198414); -#198414 = FILL_AREA_STYLE('',(#198415)); -#198415 = FILL_AREA_STYLE_COLOUR('',#195083); -#198416 = OVER_RIDING_STYLED_ITEM('overriding color',(#198417),#126276, - #195018); -#198417 = PRESENTATION_STYLE_ASSIGNMENT((#198418)); -#198418 = SURFACE_STYLE_USAGE(.BOTH.,#198419); -#198419 = SURFACE_SIDE_STYLE('',(#198420)); -#198420 = SURFACE_STYLE_FILL_AREA(#198421); -#198421 = FILL_AREA_STYLE('',(#198422)); -#198422 = FILL_AREA_STYLE_COLOUR('',#195083); -#198423 = OVER_RIDING_STYLED_ITEM('overriding color',(#198424),#126331, - #195018); -#198424 = PRESENTATION_STYLE_ASSIGNMENT((#198425)); -#198425 = SURFACE_STYLE_USAGE(.BOTH.,#198426); -#198426 = SURFACE_SIDE_STYLE('',(#198427)); -#198427 = SURFACE_STYLE_FILL_AREA(#198428); -#198428 = FILL_AREA_STYLE('',(#198429)); -#198429 = FILL_AREA_STYLE_COLOUR('',#195083); -#198430 = OVER_RIDING_STYLED_ITEM('overriding color',(#198431),#126358, - #195018); -#198431 = PRESENTATION_STYLE_ASSIGNMENT((#198432)); -#198432 = SURFACE_STYLE_USAGE(.BOTH.,#198433); -#198433 = SURFACE_SIDE_STYLE('',(#198434)); -#198434 = SURFACE_STYLE_FILL_AREA(#198435); -#198435 = FILL_AREA_STYLE('',(#198436)); -#198436 = FILL_AREA_STYLE_COLOUR('',#195083); -#198437 = OVER_RIDING_STYLED_ITEM('overriding color',(#198438),#126393, - #195018); -#198438 = PRESENTATION_STYLE_ASSIGNMENT((#198439)); -#198439 = SURFACE_STYLE_USAGE(.BOTH.,#198440); -#198440 = SURFACE_SIDE_STYLE('',(#198441)); -#198441 = SURFACE_STYLE_FILL_AREA(#198442); -#198442 = FILL_AREA_STYLE('',(#198443)); -#198443 = FILL_AREA_STYLE_COLOUR('',#195083); -#198444 = OVER_RIDING_STYLED_ITEM('overriding color',(#198445),#126400, - #195018); -#198445 = PRESENTATION_STYLE_ASSIGNMENT((#198446)); -#198446 = SURFACE_STYLE_USAGE(.BOTH.,#198447); -#198447 = SURFACE_SIDE_STYLE('',(#198448)); -#198448 = SURFACE_STYLE_FILL_AREA(#198449); -#198449 = FILL_AREA_STYLE('',(#198450)); -#198450 = FILL_AREA_STYLE_COLOUR('',#195083); -#198451 = OVER_RIDING_STYLED_ITEM('overriding color',(#198452),#126509, - #195018); -#198452 = PRESENTATION_STYLE_ASSIGNMENT((#198453)); -#198453 = SURFACE_STYLE_USAGE(.BOTH.,#198454); -#198454 = SURFACE_SIDE_STYLE('',(#198455)); -#198455 = SURFACE_STYLE_FILL_AREA(#198456); -#198456 = FILL_AREA_STYLE('',(#198457)); -#198457 = FILL_AREA_STYLE_COLOUR('',#195083); -#198458 = OVER_RIDING_STYLED_ITEM('overriding color',(#198459),#126613, - #195018); -#198459 = PRESENTATION_STYLE_ASSIGNMENT((#198460)); -#198460 = SURFACE_STYLE_USAGE(.BOTH.,#198461); -#198461 = SURFACE_SIDE_STYLE('',(#198462)); -#198462 = SURFACE_STYLE_FILL_AREA(#198463); -#198463 = FILL_AREA_STYLE('',(#198464)); -#198464 = FILL_AREA_STYLE_COLOUR('',#195083); -#198465 = OVER_RIDING_STYLED_ITEM('overriding color',(#198466),#126692, - #195018); -#198466 = PRESENTATION_STYLE_ASSIGNMENT((#198467)); -#198467 = SURFACE_STYLE_USAGE(.BOTH.,#198468); -#198468 = SURFACE_SIDE_STYLE('',(#198469)); -#198469 = SURFACE_STYLE_FILL_AREA(#198470); -#198470 = FILL_AREA_STYLE('',(#198471)); -#198471 = FILL_AREA_STYLE_COLOUR('',#195083); -#198472 = OVER_RIDING_STYLED_ITEM('overriding color',(#198473),#126771, - #195018); -#198473 = PRESENTATION_STYLE_ASSIGNMENT((#198474)); -#198474 = SURFACE_STYLE_USAGE(.BOTH.,#198475); -#198475 = SURFACE_SIDE_STYLE('',(#198476)); -#198476 = SURFACE_STYLE_FILL_AREA(#198477); -#198477 = FILL_AREA_STYLE('',(#198478)); -#198478 = FILL_AREA_STYLE_COLOUR('',#195083); -#198479 = OVER_RIDING_STYLED_ITEM('overriding color',(#198480),#126846, - #195018); -#198480 = PRESENTATION_STYLE_ASSIGNMENT((#198481)); -#198481 = SURFACE_STYLE_USAGE(.BOTH.,#198482); -#198482 = SURFACE_SIDE_STYLE('',(#198483)); -#198483 = SURFACE_STYLE_FILL_AREA(#198484); -#198484 = FILL_AREA_STYLE('',(#198485)); -#198485 = FILL_AREA_STYLE_COLOUR('',#195083); -#198486 = OVER_RIDING_STYLED_ITEM('overriding color',(#198487),#126921, - #195018); -#198487 = PRESENTATION_STYLE_ASSIGNMENT((#198488)); -#198488 = SURFACE_STYLE_USAGE(.BOTH.,#198489); -#198489 = SURFACE_SIDE_STYLE('',(#198490)); -#198490 = SURFACE_STYLE_FILL_AREA(#198491); -#198491 = FILL_AREA_STYLE('',(#198492)); -#198492 = FILL_AREA_STYLE_COLOUR('',#195083); -#198493 = OVER_RIDING_STYLED_ITEM('overriding color',(#198494),#126995, - #195018); -#198494 = PRESENTATION_STYLE_ASSIGNMENT((#198495)); -#198495 = SURFACE_STYLE_USAGE(.BOTH.,#198496); -#198496 = SURFACE_SIDE_STYLE('',(#198497)); -#198497 = SURFACE_STYLE_FILL_AREA(#198498); -#198498 = FILL_AREA_STYLE('',(#198499)); -#198499 = FILL_AREA_STYLE_COLOUR('',#195083); -#198500 = OVER_RIDING_STYLED_ITEM('overriding color',(#198501),#127069, - #195018); -#198501 = PRESENTATION_STYLE_ASSIGNMENT((#198502)); -#198502 = SURFACE_STYLE_USAGE(.BOTH.,#198503); -#198503 = SURFACE_SIDE_STYLE('',(#198504)); -#198504 = SURFACE_STYLE_FILL_AREA(#198505); -#198505 = FILL_AREA_STYLE('',(#198506)); -#198506 = FILL_AREA_STYLE_COLOUR('',#195083); -#198507 = OVER_RIDING_STYLED_ITEM('overriding color',(#198508),#127116, - #195018); -#198508 = PRESENTATION_STYLE_ASSIGNMENT((#198509)); -#198509 = SURFACE_STYLE_USAGE(.BOTH.,#198510); -#198510 = SURFACE_SIDE_STYLE('',(#198511)); -#198511 = SURFACE_STYLE_FILL_AREA(#198512); -#198512 = FILL_AREA_STYLE('',(#198513)); -#198513 = FILL_AREA_STYLE_COLOUR('',#195083); -#198514 = OVER_RIDING_STYLED_ITEM('overriding color',(#198515),#127171, - #195018); -#198515 = PRESENTATION_STYLE_ASSIGNMENT((#198516)); -#198516 = SURFACE_STYLE_USAGE(.BOTH.,#198517); -#198517 = SURFACE_SIDE_STYLE('',(#198518)); -#198518 = SURFACE_STYLE_FILL_AREA(#198519); -#198519 = FILL_AREA_STYLE('',(#198520)); -#198520 = FILL_AREA_STYLE_COLOUR('',#195083); -#198521 = OVER_RIDING_STYLED_ITEM('overriding color',(#198522),#127198, - #195018); -#198522 = PRESENTATION_STYLE_ASSIGNMENT((#198523)); -#198523 = SURFACE_STYLE_USAGE(.BOTH.,#198524); -#198524 = SURFACE_SIDE_STYLE('',(#198525)); -#198525 = SURFACE_STYLE_FILL_AREA(#198526); -#198526 = FILL_AREA_STYLE('',(#198527)); -#198527 = FILL_AREA_STYLE_COLOUR('',#195083); -#198528 = OVER_RIDING_STYLED_ITEM('overriding color',(#198529),#127233, - #195018); -#198529 = PRESENTATION_STYLE_ASSIGNMENT((#198530)); -#198530 = SURFACE_STYLE_USAGE(.BOTH.,#198531); -#198531 = SURFACE_SIDE_STYLE('',(#198532)); -#198532 = SURFACE_STYLE_FILL_AREA(#198533); -#198533 = FILL_AREA_STYLE('',(#198534)); -#198534 = FILL_AREA_STYLE_COLOUR('',#195083); -#198535 = OVER_RIDING_STYLED_ITEM('overriding color',(#198536),#127240, - #195018); -#198536 = PRESENTATION_STYLE_ASSIGNMENT((#198537)); -#198537 = SURFACE_STYLE_USAGE(.BOTH.,#198538); -#198538 = SURFACE_SIDE_STYLE('',(#198539)); -#198539 = SURFACE_STYLE_FILL_AREA(#198540); -#198540 = FILL_AREA_STYLE('',(#198541)); -#198541 = FILL_AREA_STYLE_COLOUR('',#195083); -#198542 = OVER_RIDING_STYLED_ITEM('overriding color',(#198543),#127349, - #195018); -#198543 = PRESENTATION_STYLE_ASSIGNMENT((#198544)); -#198544 = SURFACE_STYLE_USAGE(.BOTH.,#198545); -#198545 = SURFACE_SIDE_STYLE('',(#198546)); -#198546 = SURFACE_STYLE_FILL_AREA(#198547); -#198547 = FILL_AREA_STYLE('',(#198548)); -#198548 = FILL_AREA_STYLE_COLOUR('',#195083); -#198549 = OVER_RIDING_STYLED_ITEM('overriding color',(#198550),#127453, - #195018); -#198550 = PRESENTATION_STYLE_ASSIGNMENT((#198551)); -#198551 = SURFACE_STYLE_USAGE(.BOTH.,#198552); -#198552 = SURFACE_SIDE_STYLE('',(#198553)); -#198553 = SURFACE_STYLE_FILL_AREA(#198554); -#198554 = FILL_AREA_STYLE('',(#198555)); -#198555 = FILL_AREA_STYLE_COLOUR('',#195083); -#198556 = OVER_RIDING_STYLED_ITEM('overriding color',(#198557),#127532, - #195018); -#198557 = PRESENTATION_STYLE_ASSIGNMENT((#198558)); -#198558 = SURFACE_STYLE_USAGE(.BOTH.,#198559); -#198559 = SURFACE_SIDE_STYLE('',(#198560)); -#198560 = SURFACE_STYLE_FILL_AREA(#198561); -#198561 = FILL_AREA_STYLE('',(#198562)); -#198562 = FILL_AREA_STYLE_COLOUR('',#195083); -#198563 = OVER_RIDING_STYLED_ITEM('overriding color',(#198564),#127611, - #195018); -#198564 = PRESENTATION_STYLE_ASSIGNMENT((#198565)); -#198565 = SURFACE_STYLE_USAGE(.BOTH.,#198566); -#198566 = SURFACE_SIDE_STYLE('',(#198567)); -#198567 = SURFACE_STYLE_FILL_AREA(#198568); -#198568 = FILL_AREA_STYLE('',(#198569)); -#198569 = FILL_AREA_STYLE_COLOUR('',#195083); -#198570 = OVER_RIDING_STYLED_ITEM('overriding color',(#198571),#127686, - #195018); -#198571 = PRESENTATION_STYLE_ASSIGNMENT((#198572)); -#198572 = SURFACE_STYLE_USAGE(.BOTH.,#198573); -#198573 = SURFACE_SIDE_STYLE('',(#198574)); -#198574 = SURFACE_STYLE_FILL_AREA(#198575); -#198575 = FILL_AREA_STYLE('',(#198576)); -#198576 = FILL_AREA_STYLE_COLOUR('',#195083); -#198577 = OVER_RIDING_STYLED_ITEM('overriding color',(#198578),#127761, - #195018); -#198578 = PRESENTATION_STYLE_ASSIGNMENT((#198579)); -#198579 = SURFACE_STYLE_USAGE(.BOTH.,#198580); -#198580 = SURFACE_SIDE_STYLE('',(#198581)); -#198581 = SURFACE_STYLE_FILL_AREA(#198582); -#198582 = FILL_AREA_STYLE('',(#198583)); -#198583 = FILL_AREA_STYLE_COLOUR('',#195083); -#198584 = OVER_RIDING_STYLED_ITEM('overriding color',(#198585),#127835, - #195018); -#198585 = PRESENTATION_STYLE_ASSIGNMENT((#198586)); -#198586 = SURFACE_STYLE_USAGE(.BOTH.,#198587); -#198587 = SURFACE_SIDE_STYLE('',(#198588)); -#198588 = SURFACE_STYLE_FILL_AREA(#198589); -#198589 = FILL_AREA_STYLE('',(#198590)); -#198590 = FILL_AREA_STYLE_COLOUR('',#195083); -#198591 = OVER_RIDING_STYLED_ITEM('overriding color',(#198592),#127909, - #195018); -#198592 = PRESENTATION_STYLE_ASSIGNMENT((#198593)); -#198593 = SURFACE_STYLE_USAGE(.BOTH.,#198594); -#198594 = SURFACE_SIDE_STYLE('',(#198595)); -#198595 = SURFACE_STYLE_FILL_AREA(#198596); -#198596 = FILL_AREA_STYLE('',(#198597)); -#198597 = FILL_AREA_STYLE_COLOUR('',#195083); -#198598 = OVER_RIDING_STYLED_ITEM('overriding color',(#198599),#127956, - #195018); -#198599 = PRESENTATION_STYLE_ASSIGNMENT((#198600)); -#198600 = SURFACE_STYLE_USAGE(.BOTH.,#198601); -#198601 = SURFACE_SIDE_STYLE('',(#198602)); -#198602 = SURFACE_STYLE_FILL_AREA(#198603); -#198603 = FILL_AREA_STYLE('',(#198604)); -#198604 = FILL_AREA_STYLE_COLOUR('',#195083); -#198605 = OVER_RIDING_STYLED_ITEM('overriding color',(#198606),#128011, - #195018); -#198606 = PRESENTATION_STYLE_ASSIGNMENT((#198607)); -#198607 = SURFACE_STYLE_USAGE(.BOTH.,#198608); -#198608 = SURFACE_SIDE_STYLE('',(#198609)); -#198609 = SURFACE_STYLE_FILL_AREA(#198610); -#198610 = FILL_AREA_STYLE('',(#198611)); -#198611 = FILL_AREA_STYLE_COLOUR('',#195083); -#198612 = OVER_RIDING_STYLED_ITEM('overriding color',(#198613),#128038, - #195018); -#198613 = PRESENTATION_STYLE_ASSIGNMENT((#198614)); -#198614 = SURFACE_STYLE_USAGE(.BOTH.,#198615); -#198615 = SURFACE_SIDE_STYLE('',(#198616)); -#198616 = SURFACE_STYLE_FILL_AREA(#198617); -#198617 = FILL_AREA_STYLE('',(#198618)); -#198618 = FILL_AREA_STYLE_COLOUR('',#195083); -#198619 = OVER_RIDING_STYLED_ITEM('overriding color',(#198620),#128073, - #195018); -#198620 = PRESENTATION_STYLE_ASSIGNMENT((#198621)); -#198621 = SURFACE_STYLE_USAGE(.BOTH.,#198622); -#198622 = SURFACE_SIDE_STYLE('',(#198623)); -#198623 = SURFACE_STYLE_FILL_AREA(#198624); -#198624 = FILL_AREA_STYLE('',(#198625)); -#198625 = FILL_AREA_STYLE_COLOUR('',#195083); -#198626 = OVER_RIDING_STYLED_ITEM('overriding color',(#198627),#128080, - #195018); -#198627 = PRESENTATION_STYLE_ASSIGNMENT((#198628)); -#198628 = SURFACE_STYLE_USAGE(.BOTH.,#198629); -#198629 = SURFACE_SIDE_STYLE('',(#198630)); -#198630 = SURFACE_STYLE_FILL_AREA(#198631); -#198631 = FILL_AREA_STYLE('',(#198632)); -#198632 = FILL_AREA_STYLE_COLOUR('',#195083); -#198633 = OVER_RIDING_STYLED_ITEM('overriding color',(#198634),#128189, - #195018); -#198634 = PRESENTATION_STYLE_ASSIGNMENT((#198635)); -#198635 = SURFACE_STYLE_USAGE(.BOTH.,#198636); -#198636 = SURFACE_SIDE_STYLE('',(#198637)); -#198637 = SURFACE_STYLE_FILL_AREA(#198638); -#198638 = FILL_AREA_STYLE('',(#198639)); -#198639 = FILL_AREA_STYLE_COLOUR('',#195083); -#198640 = OVER_RIDING_STYLED_ITEM('overriding color',(#198641),#128293, - #195018); -#198641 = PRESENTATION_STYLE_ASSIGNMENT((#198642)); -#198642 = SURFACE_STYLE_USAGE(.BOTH.,#198643); -#198643 = SURFACE_SIDE_STYLE('',(#198644)); -#198644 = SURFACE_STYLE_FILL_AREA(#198645); -#198645 = FILL_AREA_STYLE('',(#198646)); -#198646 = FILL_AREA_STYLE_COLOUR('',#195083); -#198647 = OVER_RIDING_STYLED_ITEM('overriding color',(#198648),#128372, - #195018); -#198648 = PRESENTATION_STYLE_ASSIGNMENT((#198649)); -#198649 = SURFACE_STYLE_USAGE(.BOTH.,#198650); -#198650 = SURFACE_SIDE_STYLE('',(#198651)); -#198651 = SURFACE_STYLE_FILL_AREA(#198652); -#198652 = FILL_AREA_STYLE('',(#198653)); -#198653 = FILL_AREA_STYLE_COLOUR('',#195083); -#198654 = OVER_RIDING_STYLED_ITEM('overriding color',(#198655),#128451, - #195018); -#198655 = PRESENTATION_STYLE_ASSIGNMENT((#198656)); -#198656 = SURFACE_STYLE_USAGE(.BOTH.,#198657); -#198657 = SURFACE_SIDE_STYLE('',(#198658)); -#198658 = SURFACE_STYLE_FILL_AREA(#198659); -#198659 = FILL_AREA_STYLE('',(#198660)); -#198660 = FILL_AREA_STYLE_COLOUR('',#195083); -#198661 = OVER_RIDING_STYLED_ITEM('overriding color',(#198662),#128526, - #195018); -#198662 = PRESENTATION_STYLE_ASSIGNMENT((#198663)); -#198663 = SURFACE_STYLE_USAGE(.BOTH.,#198664); -#198664 = SURFACE_SIDE_STYLE('',(#198665)); -#198665 = SURFACE_STYLE_FILL_AREA(#198666); -#198666 = FILL_AREA_STYLE('',(#198667)); -#198667 = FILL_AREA_STYLE_COLOUR('',#195083); -#198668 = OVER_RIDING_STYLED_ITEM('overriding color',(#198669),#128601, - #195018); -#198669 = PRESENTATION_STYLE_ASSIGNMENT((#198670)); -#198670 = SURFACE_STYLE_USAGE(.BOTH.,#198671); -#198671 = SURFACE_SIDE_STYLE('',(#198672)); -#198672 = SURFACE_STYLE_FILL_AREA(#198673); -#198673 = FILL_AREA_STYLE('',(#198674)); -#198674 = FILL_AREA_STYLE_COLOUR('',#195083); -#198675 = OVER_RIDING_STYLED_ITEM('overriding color',(#198676),#128675, - #195018); -#198676 = PRESENTATION_STYLE_ASSIGNMENT((#198677)); -#198677 = SURFACE_STYLE_USAGE(.BOTH.,#198678); -#198678 = SURFACE_SIDE_STYLE('',(#198679)); -#198679 = SURFACE_STYLE_FILL_AREA(#198680); -#198680 = FILL_AREA_STYLE('',(#198681)); -#198681 = FILL_AREA_STYLE_COLOUR('',#195083); -#198682 = OVER_RIDING_STYLED_ITEM('overriding color',(#198683),#128749, - #195018); -#198683 = PRESENTATION_STYLE_ASSIGNMENT((#198684)); -#198684 = SURFACE_STYLE_USAGE(.BOTH.,#198685); -#198685 = SURFACE_SIDE_STYLE('',(#198686)); -#198686 = SURFACE_STYLE_FILL_AREA(#198687); -#198687 = FILL_AREA_STYLE('',(#198688)); -#198688 = FILL_AREA_STYLE_COLOUR('',#195083); -#198689 = OVER_RIDING_STYLED_ITEM('overriding color',(#198690),#128796, - #195018); -#198690 = PRESENTATION_STYLE_ASSIGNMENT((#198691)); -#198691 = SURFACE_STYLE_USAGE(.BOTH.,#198692); -#198692 = SURFACE_SIDE_STYLE('',(#198693)); -#198693 = SURFACE_STYLE_FILL_AREA(#198694); -#198694 = FILL_AREA_STYLE('',(#198695)); -#198695 = FILL_AREA_STYLE_COLOUR('',#195083); -#198696 = OVER_RIDING_STYLED_ITEM('overriding color',(#198697),#128851, - #195018); -#198697 = PRESENTATION_STYLE_ASSIGNMENT((#198698)); -#198698 = SURFACE_STYLE_USAGE(.BOTH.,#198699); -#198699 = SURFACE_SIDE_STYLE('',(#198700)); -#198700 = SURFACE_STYLE_FILL_AREA(#198701); -#198701 = FILL_AREA_STYLE('',(#198702)); -#198702 = FILL_AREA_STYLE_COLOUR('',#195083); -#198703 = OVER_RIDING_STYLED_ITEM('overriding color',(#198704),#128878, - #195018); -#198704 = PRESENTATION_STYLE_ASSIGNMENT((#198705)); -#198705 = SURFACE_STYLE_USAGE(.BOTH.,#198706); -#198706 = SURFACE_SIDE_STYLE('',(#198707)); -#198707 = SURFACE_STYLE_FILL_AREA(#198708); -#198708 = FILL_AREA_STYLE('',(#198709)); -#198709 = FILL_AREA_STYLE_COLOUR('',#195083); -#198710 = OVER_RIDING_STYLED_ITEM('overriding color',(#198711),#128913, - #195018); -#198711 = PRESENTATION_STYLE_ASSIGNMENT((#198712)); -#198712 = SURFACE_STYLE_USAGE(.BOTH.,#198713); -#198713 = SURFACE_SIDE_STYLE('',(#198714)); -#198714 = SURFACE_STYLE_FILL_AREA(#198715); -#198715 = FILL_AREA_STYLE('',(#198716)); -#198716 = FILL_AREA_STYLE_COLOUR('',#195083); -#198717 = OVER_RIDING_STYLED_ITEM('overriding color',(#198718),#128920, - #195018); -#198718 = PRESENTATION_STYLE_ASSIGNMENT((#198719)); -#198719 = SURFACE_STYLE_USAGE(.BOTH.,#198720); -#198720 = SURFACE_SIDE_STYLE('',(#198721)); -#198721 = SURFACE_STYLE_FILL_AREA(#198722); -#198722 = FILL_AREA_STYLE('',(#198723)); -#198723 = FILL_AREA_STYLE_COLOUR('',#195083); -#198724 = OVER_RIDING_STYLED_ITEM('overriding color',(#198725),#129029, - #195018); -#198725 = PRESENTATION_STYLE_ASSIGNMENT((#198726)); -#198726 = SURFACE_STYLE_USAGE(.BOTH.,#198727); -#198727 = SURFACE_SIDE_STYLE('',(#198728)); -#198728 = SURFACE_STYLE_FILL_AREA(#198729); -#198729 = FILL_AREA_STYLE('',(#198730)); -#198730 = FILL_AREA_STYLE_COLOUR('',#195083); -#198731 = OVER_RIDING_STYLED_ITEM('overriding color',(#198732),#129133, - #195018); -#198732 = PRESENTATION_STYLE_ASSIGNMENT((#198733)); -#198733 = SURFACE_STYLE_USAGE(.BOTH.,#198734); -#198734 = SURFACE_SIDE_STYLE('',(#198735)); -#198735 = SURFACE_STYLE_FILL_AREA(#198736); -#198736 = FILL_AREA_STYLE('',(#198737)); -#198737 = FILL_AREA_STYLE_COLOUR('',#195083); -#198738 = OVER_RIDING_STYLED_ITEM('overriding color',(#198739),#129212, - #195018); -#198739 = PRESENTATION_STYLE_ASSIGNMENT((#198740)); -#198740 = SURFACE_STYLE_USAGE(.BOTH.,#198741); -#198741 = SURFACE_SIDE_STYLE('',(#198742)); -#198742 = SURFACE_STYLE_FILL_AREA(#198743); -#198743 = FILL_AREA_STYLE('',(#198744)); -#198744 = FILL_AREA_STYLE_COLOUR('',#195083); -#198745 = OVER_RIDING_STYLED_ITEM('overriding color',(#198746),#129291, - #195018); -#198746 = PRESENTATION_STYLE_ASSIGNMENT((#198747)); -#198747 = SURFACE_STYLE_USAGE(.BOTH.,#198748); -#198748 = SURFACE_SIDE_STYLE('',(#198749)); -#198749 = SURFACE_STYLE_FILL_AREA(#198750); -#198750 = FILL_AREA_STYLE('',(#198751)); -#198751 = FILL_AREA_STYLE_COLOUR('',#195083); -#198752 = OVER_RIDING_STYLED_ITEM('overriding color',(#198753),#129366, - #195018); -#198753 = PRESENTATION_STYLE_ASSIGNMENT((#198754)); -#198754 = SURFACE_STYLE_USAGE(.BOTH.,#198755); -#198755 = SURFACE_SIDE_STYLE('',(#198756)); -#198756 = SURFACE_STYLE_FILL_AREA(#198757); -#198757 = FILL_AREA_STYLE('',(#198758)); -#198758 = FILL_AREA_STYLE_COLOUR('',#195083); -#198759 = OVER_RIDING_STYLED_ITEM('overriding color',(#198760),#129441, - #195018); -#198760 = PRESENTATION_STYLE_ASSIGNMENT((#198761)); -#198761 = SURFACE_STYLE_USAGE(.BOTH.,#198762); -#198762 = SURFACE_SIDE_STYLE('',(#198763)); -#198763 = SURFACE_STYLE_FILL_AREA(#198764); -#198764 = FILL_AREA_STYLE('',(#198765)); -#198765 = FILL_AREA_STYLE_COLOUR('',#195083); -#198766 = OVER_RIDING_STYLED_ITEM('overriding color',(#198767),#129515, - #195018); -#198767 = PRESENTATION_STYLE_ASSIGNMENT((#198768)); -#198768 = SURFACE_STYLE_USAGE(.BOTH.,#198769); -#198769 = SURFACE_SIDE_STYLE('',(#198770)); -#198770 = SURFACE_STYLE_FILL_AREA(#198771); -#198771 = FILL_AREA_STYLE('',(#198772)); -#198772 = FILL_AREA_STYLE_COLOUR('',#195083); -#198773 = OVER_RIDING_STYLED_ITEM('overriding color',(#198774),#129589, - #195018); -#198774 = PRESENTATION_STYLE_ASSIGNMENT((#198775)); -#198775 = SURFACE_STYLE_USAGE(.BOTH.,#198776); -#198776 = SURFACE_SIDE_STYLE('',(#198777)); -#198777 = SURFACE_STYLE_FILL_AREA(#198778); -#198778 = FILL_AREA_STYLE('',(#198779)); -#198779 = FILL_AREA_STYLE_COLOUR('',#195083); -#198780 = OVER_RIDING_STYLED_ITEM('overriding color',(#198781),#129636, - #195018); -#198781 = PRESENTATION_STYLE_ASSIGNMENT((#198782)); -#198782 = SURFACE_STYLE_USAGE(.BOTH.,#198783); -#198783 = SURFACE_SIDE_STYLE('',(#198784)); -#198784 = SURFACE_STYLE_FILL_AREA(#198785); -#198785 = FILL_AREA_STYLE('',(#198786)); -#198786 = FILL_AREA_STYLE_COLOUR('',#195083); -#198787 = OVER_RIDING_STYLED_ITEM('overriding color',(#198788),#129691, - #195018); -#198788 = PRESENTATION_STYLE_ASSIGNMENT((#198789)); -#198789 = SURFACE_STYLE_USAGE(.BOTH.,#198790); -#198790 = SURFACE_SIDE_STYLE('',(#198791)); -#198791 = SURFACE_STYLE_FILL_AREA(#198792); -#198792 = FILL_AREA_STYLE('',(#198793)); -#198793 = FILL_AREA_STYLE_COLOUR('',#195083); -#198794 = OVER_RIDING_STYLED_ITEM('overriding color',(#198795),#129718, - #195018); -#198795 = PRESENTATION_STYLE_ASSIGNMENT((#198796)); -#198796 = SURFACE_STYLE_USAGE(.BOTH.,#198797); -#198797 = SURFACE_SIDE_STYLE('',(#198798)); -#198798 = SURFACE_STYLE_FILL_AREA(#198799); -#198799 = FILL_AREA_STYLE('',(#198800)); -#198800 = FILL_AREA_STYLE_COLOUR('',#195083); -#198801 = OVER_RIDING_STYLED_ITEM('overriding color',(#198802),#129753, - #195018); -#198802 = PRESENTATION_STYLE_ASSIGNMENT((#198803)); -#198803 = SURFACE_STYLE_USAGE(.BOTH.,#198804); -#198804 = SURFACE_SIDE_STYLE('',(#198805)); -#198805 = SURFACE_STYLE_FILL_AREA(#198806); -#198806 = FILL_AREA_STYLE('',(#198807)); -#198807 = FILL_AREA_STYLE_COLOUR('',#195083); -#198808 = OVER_RIDING_STYLED_ITEM('overriding color',(#198809),#129760, - #195018); -#198809 = PRESENTATION_STYLE_ASSIGNMENT((#198810)); -#198810 = SURFACE_STYLE_USAGE(.BOTH.,#198811); -#198811 = SURFACE_SIDE_STYLE('',(#198812)); -#198812 = SURFACE_STYLE_FILL_AREA(#198813); -#198813 = FILL_AREA_STYLE('',(#198814)); -#198814 = FILL_AREA_STYLE_COLOUR('',#195083); -#198815 = OVER_RIDING_STYLED_ITEM('overriding color',(#198816),#129869, - #195018); -#198816 = PRESENTATION_STYLE_ASSIGNMENT((#198817)); -#198817 = SURFACE_STYLE_USAGE(.BOTH.,#198818); -#198818 = SURFACE_SIDE_STYLE('',(#198819)); -#198819 = SURFACE_STYLE_FILL_AREA(#198820); -#198820 = FILL_AREA_STYLE('',(#198821)); -#198821 = FILL_AREA_STYLE_COLOUR('',#195083); -#198822 = OVER_RIDING_STYLED_ITEM('overriding color',(#198823),#129973, - #195018); -#198823 = PRESENTATION_STYLE_ASSIGNMENT((#198824)); -#198824 = SURFACE_STYLE_USAGE(.BOTH.,#198825); -#198825 = SURFACE_SIDE_STYLE('',(#198826)); -#198826 = SURFACE_STYLE_FILL_AREA(#198827); -#198827 = FILL_AREA_STYLE('',(#198828)); -#198828 = FILL_AREA_STYLE_COLOUR('',#195083); -#198829 = OVER_RIDING_STYLED_ITEM('overriding color',(#198830),#130052, - #195018); -#198830 = PRESENTATION_STYLE_ASSIGNMENT((#198831)); -#198831 = SURFACE_STYLE_USAGE(.BOTH.,#198832); -#198832 = SURFACE_SIDE_STYLE('',(#198833)); -#198833 = SURFACE_STYLE_FILL_AREA(#198834); -#198834 = FILL_AREA_STYLE('',(#198835)); -#198835 = FILL_AREA_STYLE_COLOUR('',#195083); -#198836 = OVER_RIDING_STYLED_ITEM('overriding color',(#198837),#130131, - #195018); -#198837 = PRESENTATION_STYLE_ASSIGNMENT((#198838)); -#198838 = SURFACE_STYLE_USAGE(.BOTH.,#198839); -#198839 = SURFACE_SIDE_STYLE('',(#198840)); -#198840 = SURFACE_STYLE_FILL_AREA(#198841); -#198841 = FILL_AREA_STYLE('',(#198842)); -#198842 = FILL_AREA_STYLE_COLOUR('',#195083); -#198843 = OVER_RIDING_STYLED_ITEM('overriding color',(#198844),#130206, - #195018); -#198844 = PRESENTATION_STYLE_ASSIGNMENT((#198845)); -#198845 = SURFACE_STYLE_USAGE(.BOTH.,#198846); -#198846 = SURFACE_SIDE_STYLE('',(#198847)); -#198847 = SURFACE_STYLE_FILL_AREA(#198848); -#198848 = FILL_AREA_STYLE('',(#198849)); -#198849 = FILL_AREA_STYLE_COLOUR('',#195083); -#198850 = OVER_RIDING_STYLED_ITEM('overriding color',(#198851),#130281, - #195018); -#198851 = PRESENTATION_STYLE_ASSIGNMENT((#198852)); -#198852 = SURFACE_STYLE_USAGE(.BOTH.,#198853); -#198853 = SURFACE_SIDE_STYLE('',(#198854)); -#198854 = SURFACE_STYLE_FILL_AREA(#198855); -#198855 = FILL_AREA_STYLE('',(#198856)); -#198856 = FILL_AREA_STYLE_COLOUR('',#195083); -#198857 = OVER_RIDING_STYLED_ITEM('overriding color',(#198858),#130355, - #195018); -#198858 = PRESENTATION_STYLE_ASSIGNMENT((#198859)); -#198859 = SURFACE_STYLE_USAGE(.BOTH.,#198860); -#198860 = SURFACE_SIDE_STYLE('',(#198861)); -#198861 = SURFACE_STYLE_FILL_AREA(#198862); -#198862 = FILL_AREA_STYLE('',(#198863)); -#198863 = FILL_AREA_STYLE_COLOUR('',#195083); -#198864 = OVER_RIDING_STYLED_ITEM('overriding color',(#198865),#130429, - #195018); -#198865 = PRESENTATION_STYLE_ASSIGNMENT((#198866)); -#198866 = SURFACE_STYLE_USAGE(.BOTH.,#198867); -#198867 = SURFACE_SIDE_STYLE('',(#198868)); -#198868 = SURFACE_STYLE_FILL_AREA(#198869); -#198869 = FILL_AREA_STYLE('',(#198870)); -#198870 = FILL_AREA_STYLE_COLOUR('',#195083); -#198871 = OVER_RIDING_STYLED_ITEM('overriding color',(#198872),#130476, - #195018); -#198872 = PRESENTATION_STYLE_ASSIGNMENT((#198873)); -#198873 = SURFACE_STYLE_USAGE(.BOTH.,#198874); -#198874 = SURFACE_SIDE_STYLE('',(#198875)); -#198875 = SURFACE_STYLE_FILL_AREA(#198876); -#198876 = FILL_AREA_STYLE('',(#198877)); -#198877 = FILL_AREA_STYLE_COLOUR('',#195083); -#198878 = OVER_RIDING_STYLED_ITEM('overriding color',(#198879),#130531, - #195018); -#198879 = PRESENTATION_STYLE_ASSIGNMENT((#198880)); -#198880 = SURFACE_STYLE_USAGE(.BOTH.,#198881); -#198881 = SURFACE_SIDE_STYLE('',(#198882)); -#198882 = SURFACE_STYLE_FILL_AREA(#198883); -#198883 = FILL_AREA_STYLE('',(#198884)); -#198884 = FILL_AREA_STYLE_COLOUR('',#195083); -#198885 = OVER_RIDING_STYLED_ITEM('overriding color',(#198886),#130558, - #195018); -#198886 = PRESENTATION_STYLE_ASSIGNMENT((#198887)); -#198887 = SURFACE_STYLE_USAGE(.BOTH.,#198888); -#198888 = SURFACE_SIDE_STYLE('',(#198889)); -#198889 = SURFACE_STYLE_FILL_AREA(#198890); -#198890 = FILL_AREA_STYLE('',(#198891)); -#198891 = FILL_AREA_STYLE_COLOUR('',#195083); -#198892 = OVER_RIDING_STYLED_ITEM('overriding color',(#198893),#130593, - #195018); -#198893 = PRESENTATION_STYLE_ASSIGNMENT((#198894)); -#198894 = SURFACE_STYLE_USAGE(.BOTH.,#198895); -#198895 = SURFACE_SIDE_STYLE('',(#198896)); -#198896 = SURFACE_STYLE_FILL_AREA(#198897); -#198897 = FILL_AREA_STYLE('',(#198898)); -#198898 = FILL_AREA_STYLE_COLOUR('',#195083); -#198899 = OVER_RIDING_STYLED_ITEM('overriding color',(#198900),#130600, - #195018); -#198900 = PRESENTATION_STYLE_ASSIGNMENT((#198901)); -#198901 = SURFACE_STYLE_USAGE(.BOTH.,#198902); -#198902 = SURFACE_SIDE_STYLE('',(#198903)); -#198903 = SURFACE_STYLE_FILL_AREA(#198904); -#198904 = FILL_AREA_STYLE('',(#198905)); -#198905 = FILL_AREA_STYLE_COLOUR('',#195083); -#198906 = OVER_RIDING_STYLED_ITEM('overriding color',(#198907),#130709, - #195018); -#198907 = PRESENTATION_STYLE_ASSIGNMENT((#198908)); -#198908 = SURFACE_STYLE_USAGE(.BOTH.,#198909); -#198909 = SURFACE_SIDE_STYLE('',(#198910)); -#198910 = SURFACE_STYLE_FILL_AREA(#198911); -#198911 = FILL_AREA_STYLE('',(#198912)); -#198912 = FILL_AREA_STYLE_COLOUR('',#195083); -#198913 = OVER_RIDING_STYLED_ITEM('overriding color',(#198914),#130813, - #195018); -#198914 = PRESENTATION_STYLE_ASSIGNMENT((#198915)); -#198915 = SURFACE_STYLE_USAGE(.BOTH.,#198916); -#198916 = SURFACE_SIDE_STYLE('',(#198917)); -#198917 = SURFACE_STYLE_FILL_AREA(#198918); -#198918 = FILL_AREA_STYLE('',(#198919)); -#198919 = FILL_AREA_STYLE_COLOUR('',#195083); -#198920 = OVER_RIDING_STYLED_ITEM('overriding color',(#198921),#130892, - #195018); -#198921 = PRESENTATION_STYLE_ASSIGNMENT((#198922)); -#198922 = SURFACE_STYLE_USAGE(.BOTH.,#198923); -#198923 = SURFACE_SIDE_STYLE('',(#198924)); -#198924 = SURFACE_STYLE_FILL_AREA(#198925); -#198925 = FILL_AREA_STYLE('',(#198926)); -#198926 = FILL_AREA_STYLE_COLOUR('',#195083); -#198927 = OVER_RIDING_STYLED_ITEM('overriding color',(#198928),#131017, - #195018); -#198928 = PRESENTATION_STYLE_ASSIGNMENT((#198929)); -#198929 = SURFACE_STYLE_USAGE(.BOTH.,#198930); -#198930 = SURFACE_SIDE_STYLE('',(#198931)); -#198931 = SURFACE_STYLE_FILL_AREA(#198932); -#198932 = FILL_AREA_STYLE('',(#198933)); -#198933 = FILL_AREA_STYLE_COLOUR('',#195083); -#198934 = OVER_RIDING_STYLED_ITEM('overriding color',(#198935),#131092, - #195018); -#198935 = PRESENTATION_STYLE_ASSIGNMENT((#198936)); -#198936 = SURFACE_STYLE_USAGE(.BOTH.,#198937); -#198937 = SURFACE_SIDE_STYLE('',(#198938)); -#198938 = SURFACE_STYLE_FILL_AREA(#198939); -#198939 = FILL_AREA_STYLE('',(#198940)); -#198940 = FILL_AREA_STYLE_COLOUR('',#195083); -#198941 = OVER_RIDING_STYLED_ITEM('overriding color',(#198942),#131167, - #195018); -#198942 = PRESENTATION_STYLE_ASSIGNMENT((#198943)); -#198943 = SURFACE_STYLE_USAGE(.BOTH.,#198944); -#198944 = SURFACE_SIDE_STYLE('',(#198945)); -#198945 = SURFACE_STYLE_FILL_AREA(#198946); -#198946 = FILL_AREA_STYLE('',(#198947)); -#198947 = FILL_AREA_STYLE_COLOUR('',#195083); -#198948 = OVER_RIDING_STYLED_ITEM('overriding color',(#198949),#131287, - #195018); -#198949 = PRESENTATION_STYLE_ASSIGNMENT((#198950)); -#198950 = SURFACE_STYLE_USAGE(.BOTH.,#198951); -#198951 = SURFACE_SIDE_STYLE('',(#198952)); -#198952 = SURFACE_STYLE_FILL_AREA(#198953); -#198953 = FILL_AREA_STYLE('',(#198954)); -#198954 = FILL_AREA_STYLE_COLOUR('',#195083); -#198955 = OVER_RIDING_STYLED_ITEM('overriding color',(#198956),#131361, - #195018); -#198956 = PRESENTATION_STYLE_ASSIGNMENT((#198957)); -#198957 = SURFACE_STYLE_USAGE(.BOTH.,#198958); -#198958 = SURFACE_SIDE_STYLE('',(#198959)); -#198959 = SURFACE_STYLE_FILL_AREA(#198960); -#198960 = FILL_AREA_STYLE('',(#198961)); -#198961 = FILL_AREA_STYLE_COLOUR('',#195083); -#198962 = OVER_RIDING_STYLED_ITEM('overriding color',(#198963),#131408, - #195018); -#198963 = PRESENTATION_STYLE_ASSIGNMENT((#198964)); -#198964 = SURFACE_STYLE_USAGE(.BOTH.,#198965); -#198965 = SURFACE_SIDE_STYLE('',(#198966)); -#198966 = SURFACE_STYLE_FILL_AREA(#198967); -#198967 = FILL_AREA_STYLE('',(#198968)); -#198968 = FILL_AREA_STYLE_COLOUR('',#195083); -#198969 = OVER_RIDING_STYLED_ITEM('overriding color',(#198970),#131463, - #195018); -#198970 = PRESENTATION_STYLE_ASSIGNMENT((#198971)); -#198971 = SURFACE_STYLE_USAGE(.BOTH.,#198972); -#198972 = SURFACE_SIDE_STYLE('',(#198973)); -#198973 = SURFACE_STYLE_FILL_AREA(#198974); -#198974 = FILL_AREA_STYLE('',(#198975)); -#198975 = FILL_AREA_STYLE_COLOUR('',#195083); -#198976 = OVER_RIDING_STYLED_ITEM('overriding color',(#198977),#131490, - #195018); -#198977 = PRESENTATION_STYLE_ASSIGNMENT((#198978)); -#198978 = SURFACE_STYLE_USAGE(.BOTH.,#198979); -#198979 = SURFACE_SIDE_STYLE('',(#198980)); -#198980 = SURFACE_STYLE_FILL_AREA(#198981); -#198981 = FILL_AREA_STYLE('',(#198982)); -#198982 = FILL_AREA_STYLE_COLOUR('',#195083); -#198983 = OVER_RIDING_STYLED_ITEM('overriding color',(#198984),#131525, - #195018); -#198984 = PRESENTATION_STYLE_ASSIGNMENT((#198985)); -#198985 = SURFACE_STYLE_USAGE(.BOTH.,#198986); -#198986 = SURFACE_SIDE_STYLE('',(#198987)); -#198987 = SURFACE_STYLE_FILL_AREA(#198988); -#198988 = FILL_AREA_STYLE('',(#198989)); -#198989 = FILL_AREA_STYLE_COLOUR('',#195083); -#198990 = OVER_RIDING_STYLED_ITEM('overriding color',(#198991),#131532, - #195018); -#198991 = PRESENTATION_STYLE_ASSIGNMENT((#198992)); -#198992 = SURFACE_STYLE_USAGE(.BOTH.,#198993); -#198993 = SURFACE_SIDE_STYLE('',(#198994)); -#198994 = SURFACE_STYLE_FILL_AREA(#198995); -#198995 = FILL_AREA_STYLE('',(#198996)); -#198996 = FILL_AREA_STYLE_COLOUR('',#195083); -#198997 = OVER_RIDING_STYLED_ITEM('overriding color',(#198998),#131641, - #195018); -#198998 = PRESENTATION_STYLE_ASSIGNMENT((#198999)); -#198999 = SURFACE_STYLE_USAGE(.BOTH.,#199000); -#199000 = SURFACE_SIDE_STYLE('',(#199001)); -#199001 = SURFACE_STYLE_FILL_AREA(#199002); -#199002 = FILL_AREA_STYLE('',(#199003)); -#199003 = FILL_AREA_STYLE_COLOUR('',#195083); -#199004 = OVER_RIDING_STYLED_ITEM('overriding color',(#199005),#131745, - #195018); -#199005 = PRESENTATION_STYLE_ASSIGNMENT((#199006)); -#199006 = SURFACE_STYLE_USAGE(.BOTH.,#199007); -#199007 = SURFACE_SIDE_STYLE('',(#199008)); -#199008 = SURFACE_STYLE_FILL_AREA(#199009); -#199009 = FILL_AREA_STYLE('',(#199010)); -#199010 = FILL_AREA_STYLE_COLOUR('',#195083); -#199011 = OVER_RIDING_STYLED_ITEM('overriding color',(#199012),#131824, - #195018); -#199012 = PRESENTATION_STYLE_ASSIGNMENT((#199013)); -#199013 = SURFACE_STYLE_USAGE(.BOTH.,#199014); -#199014 = SURFACE_SIDE_STYLE('',(#199015)); -#199015 = SURFACE_STYLE_FILL_AREA(#199016); -#199016 = FILL_AREA_STYLE('',(#199017)); -#199017 = FILL_AREA_STYLE_COLOUR('',#195083); -#199018 = OVER_RIDING_STYLED_ITEM('overriding color',(#199019),#131949, - #195018); -#199019 = PRESENTATION_STYLE_ASSIGNMENT((#199020)); -#199020 = SURFACE_STYLE_USAGE(.BOTH.,#199021); -#199021 = SURFACE_SIDE_STYLE('',(#199022)); -#199022 = SURFACE_STYLE_FILL_AREA(#199023); -#199023 = FILL_AREA_STYLE('',(#199024)); -#199024 = FILL_AREA_STYLE_COLOUR('',#195083); -#199025 = OVER_RIDING_STYLED_ITEM('overriding color',(#199026),#132024, - #195018); -#199026 = PRESENTATION_STYLE_ASSIGNMENT((#199027)); -#199027 = SURFACE_STYLE_USAGE(.BOTH.,#199028); -#199028 = SURFACE_SIDE_STYLE('',(#199029)); -#199029 = SURFACE_STYLE_FILL_AREA(#199030); -#199030 = FILL_AREA_STYLE('',(#199031)); -#199031 = FILL_AREA_STYLE_COLOUR('',#195083); -#199032 = OVER_RIDING_STYLED_ITEM('overriding color',(#199033),#132099, - #195018); -#199033 = PRESENTATION_STYLE_ASSIGNMENT((#199034)); -#199034 = SURFACE_STYLE_USAGE(.BOTH.,#199035); -#199035 = SURFACE_SIDE_STYLE('',(#199036)); -#199036 = SURFACE_STYLE_FILL_AREA(#199037); -#199037 = FILL_AREA_STYLE('',(#199038)); -#199038 = FILL_AREA_STYLE_COLOUR('',#195083); -#199039 = OVER_RIDING_STYLED_ITEM('overriding color',(#199040),#132219, - #195018); -#199040 = PRESENTATION_STYLE_ASSIGNMENT((#199041)); -#199041 = SURFACE_STYLE_USAGE(.BOTH.,#199042); -#199042 = SURFACE_SIDE_STYLE('',(#199043)); -#199043 = SURFACE_STYLE_FILL_AREA(#199044); -#199044 = FILL_AREA_STYLE('',(#199045)); -#199045 = FILL_AREA_STYLE_COLOUR('',#195083); -#199046 = OVER_RIDING_STYLED_ITEM('overriding color',(#199047),#132293, - #195018); -#199047 = PRESENTATION_STYLE_ASSIGNMENT((#199048)); -#199048 = SURFACE_STYLE_USAGE(.BOTH.,#199049); -#199049 = SURFACE_SIDE_STYLE('',(#199050)); -#199050 = SURFACE_STYLE_FILL_AREA(#199051); -#199051 = FILL_AREA_STYLE('',(#199052)); -#199052 = FILL_AREA_STYLE_COLOUR('',#195083); -#199053 = OVER_RIDING_STYLED_ITEM('overriding color',(#199054),#132340, - #195018); -#199054 = PRESENTATION_STYLE_ASSIGNMENT((#199055)); -#199055 = SURFACE_STYLE_USAGE(.BOTH.,#199056); -#199056 = SURFACE_SIDE_STYLE('',(#199057)); -#199057 = SURFACE_STYLE_FILL_AREA(#199058); -#199058 = FILL_AREA_STYLE('',(#199059)); -#199059 = FILL_AREA_STYLE_COLOUR('',#195083); -#199060 = OVER_RIDING_STYLED_ITEM('overriding color',(#199061),#132395, - #195018); -#199061 = PRESENTATION_STYLE_ASSIGNMENT((#199062)); -#199062 = SURFACE_STYLE_USAGE(.BOTH.,#199063); -#199063 = SURFACE_SIDE_STYLE('',(#199064)); -#199064 = SURFACE_STYLE_FILL_AREA(#199065); -#199065 = FILL_AREA_STYLE('',(#199066)); -#199066 = FILL_AREA_STYLE_COLOUR('',#195083); -#199067 = OVER_RIDING_STYLED_ITEM('overriding color',(#199068),#132422, - #195018); -#199068 = PRESENTATION_STYLE_ASSIGNMENT((#199069)); -#199069 = SURFACE_STYLE_USAGE(.BOTH.,#199070); -#199070 = SURFACE_SIDE_STYLE('',(#199071)); -#199071 = SURFACE_STYLE_FILL_AREA(#199072); -#199072 = FILL_AREA_STYLE('',(#199073)); -#199073 = FILL_AREA_STYLE_COLOUR('',#195083); -#199074 = OVER_RIDING_STYLED_ITEM('overriding color',(#199075),#132457, - #195018); -#199075 = PRESENTATION_STYLE_ASSIGNMENT((#199076)); -#199076 = SURFACE_STYLE_USAGE(.BOTH.,#199077); -#199077 = SURFACE_SIDE_STYLE('',(#199078)); -#199078 = SURFACE_STYLE_FILL_AREA(#199079); -#199079 = FILL_AREA_STYLE('',(#199080)); -#199080 = FILL_AREA_STYLE_COLOUR('',#195083); -#199081 = OVER_RIDING_STYLED_ITEM('overriding color',(#199082),#132464, - #195018); -#199082 = PRESENTATION_STYLE_ASSIGNMENT((#199083)); -#199083 = SURFACE_STYLE_USAGE(.BOTH.,#199084); -#199084 = SURFACE_SIDE_STYLE('',(#199085)); -#199085 = SURFACE_STYLE_FILL_AREA(#199086); -#199086 = FILL_AREA_STYLE('',(#199087)); -#199087 = FILL_AREA_STYLE_COLOUR('',#195083); -#199088 = OVER_RIDING_STYLED_ITEM('overriding color',(#199089),#132573, - #195018); -#199089 = PRESENTATION_STYLE_ASSIGNMENT((#199090)); -#199090 = SURFACE_STYLE_USAGE(.BOTH.,#199091); -#199091 = SURFACE_SIDE_STYLE('',(#199092)); -#199092 = SURFACE_STYLE_FILL_AREA(#199093); -#199093 = FILL_AREA_STYLE('',(#199094)); -#199094 = FILL_AREA_STYLE_COLOUR('',#195083); -#199095 = OVER_RIDING_STYLED_ITEM('overriding color',(#199096),#132677, - #195018); -#199096 = PRESENTATION_STYLE_ASSIGNMENT((#199097)); -#199097 = SURFACE_STYLE_USAGE(.BOTH.,#199098); -#199098 = SURFACE_SIDE_STYLE('',(#199099)); -#199099 = SURFACE_STYLE_FILL_AREA(#199100); -#199100 = FILL_AREA_STYLE('',(#199101)); -#199101 = FILL_AREA_STYLE_COLOUR('',#195083); -#199102 = OVER_RIDING_STYLED_ITEM('overriding color',(#199103),#132756, - #195018); -#199103 = PRESENTATION_STYLE_ASSIGNMENT((#199104)); -#199104 = SURFACE_STYLE_USAGE(.BOTH.,#199105); -#199105 = SURFACE_SIDE_STYLE('',(#199106)); -#199106 = SURFACE_STYLE_FILL_AREA(#199107); -#199107 = FILL_AREA_STYLE('',(#199108)); -#199108 = FILL_AREA_STYLE_COLOUR('',#195083); -#199109 = OVER_RIDING_STYLED_ITEM('overriding color',(#199110),#132881, - #195018); -#199110 = PRESENTATION_STYLE_ASSIGNMENT((#199111)); -#199111 = SURFACE_STYLE_USAGE(.BOTH.,#199112); -#199112 = SURFACE_SIDE_STYLE('',(#199113)); -#199113 = SURFACE_STYLE_FILL_AREA(#199114); -#199114 = FILL_AREA_STYLE('',(#199115)); -#199115 = FILL_AREA_STYLE_COLOUR('',#195083); -#199116 = OVER_RIDING_STYLED_ITEM('overriding color',(#199117),#132956, - #195018); -#199117 = PRESENTATION_STYLE_ASSIGNMENT((#199118)); -#199118 = SURFACE_STYLE_USAGE(.BOTH.,#199119); -#199119 = SURFACE_SIDE_STYLE('',(#199120)); -#199120 = SURFACE_STYLE_FILL_AREA(#199121); -#199121 = FILL_AREA_STYLE('',(#199122)); -#199122 = FILL_AREA_STYLE_COLOUR('',#195083); -#199123 = OVER_RIDING_STYLED_ITEM('overriding color',(#199124),#133031, - #195018); -#199124 = PRESENTATION_STYLE_ASSIGNMENT((#199125)); -#199125 = SURFACE_STYLE_USAGE(.BOTH.,#199126); -#199126 = SURFACE_SIDE_STYLE('',(#199127)); -#199127 = SURFACE_STYLE_FILL_AREA(#199128); -#199128 = FILL_AREA_STYLE('',(#199129)); -#199129 = FILL_AREA_STYLE_COLOUR('',#195083); -#199130 = OVER_RIDING_STYLED_ITEM('overriding color',(#199131),#133151, - #195018); -#199131 = PRESENTATION_STYLE_ASSIGNMENT((#199132)); -#199132 = SURFACE_STYLE_USAGE(.BOTH.,#199133); -#199133 = SURFACE_SIDE_STYLE('',(#199134)); -#199134 = SURFACE_STYLE_FILL_AREA(#199135); -#199135 = FILL_AREA_STYLE('',(#199136)); -#199136 = FILL_AREA_STYLE_COLOUR('',#195083); -#199137 = OVER_RIDING_STYLED_ITEM('overriding color',(#199138),#133225, - #195018); -#199138 = PRESENTATION_STYLE_ASSIGNMENT((#199139)); -#199139 = SURFACE_STYLE_USAGE(.BOTH.,#199140); -#199140 = SURFACE_SIDE_STYLE('',(#199141)); -#199141 = SURFACE_STYLE_FILL_AREA(#199142); -#199142 = FILL_AREA_STYLE('',(#199143)); -#199143 = FILL_AREA_STYLE_COLOUR('',#195083); -#199144 = OVER_RIDING_STYLED_ITEM('overriding color',(#199145),#133272, - #195018); -#199145 = PRESENTATION_STYLE_ASSIGNMENT((#199146)); -#199146 = SURFACE_STYLE_USAGE(.BOTH.,#199147); -#199147 = SURFACE_SIDE_STYLE('',(#199148)); -#199148 = SURFACE_STYLE_FILL_AREA(#199149); -#199149 = FILL_AREA_STYLE('',(#199150)); -#199150 = FILL_AREA_STYLE_COLOUR('',#195083); -#199151 = OVER_RIDING_STYLED_ITEM('overriding color',(#199152),#133327, - #195018); -#199152 = PRESENTATION_STYLE_ASSIGNMENT((#199153)); -#199153 = SURFACE_STYLE_USAGE(.BOTH.,#199154); -#199154 = SURFACE_SIDE_STYLE('',(#199155)); -#199155 = SURFACE_STYLE_FILL_AREA(#199156); -#199156 = FILL_AREA_STYLE('',(#199157)); -#199157 = FILL_AREA_STYLE_COLOUR('',#195083); -#199158 = OVER_RIDING_STYLED_ITEM('overriding color',(#199159),#133354, - #195018); -#199159 = PRESENTATION_STYLE_ASSIGNMENT((#199160)); -#199160 = SURFACE_STYLE_USAGE(.BOTH.,#199161); -#199161 = SURFACE_SIDE_STYLE('',(#199162)); -#199162 = SURFACE_STYLE_FILL_AREA(#199163); -#199163 = FILL_AREA_STYLE('',(#199164)); -#199164 = FILL_AREA_STYLE_COLOUR('',#195083); -#199165 = OVER_RIDING_STYLED_ITEM('overriding color',(#199166),#133389, - #195018); -#199166 = PRESENTATION_STYLE_ASSIGNMENT((#199167)); -#199167 = SURFACE_STYLE_USAGE(.BOTH.,#199168); -#199168 = SURFACE_SIDE_STYLE('',(#199169)); -#199169 = SURFACE_STYLE_FILL_AREA(#199170); -#199170 = FILL_AREA_STYLE('',(#199171)); -#199171 = FILL_AREA_STYLE_COLOUR('',#195083); -#199172 = OVER_RIDING_STYLED_ITEM('overriding color',(#199173),#133396, - #195018); -#199173 = PRESENTATION_STYLE_ASSIGNMENT((#199174)); -#199174 = SURFACE_STYLE_USAGE(.BOTH.,#199175); -#199175 = SURFACE_SIDE_STYLE('',(#199176)); -#199176 = SURFACE_STYLE_FILL_AREA(#199177); -#199177 = FILL_AREA_STYLE('',(#199178)); -#199178 = FILL_AREA_STYLE_COLOUR('',#195083); -#199179 = OVER_RIDING_STYLED_ITEM('overriding color',(#199180),#133505, - #195018); -#199180 = PRESENTATION_STYLE_ASSIGNMENT((#199181)); -#199181 = SURFACE_STYLE_USAGE(.BOTH.,#199182); -#199182 = SURFACE_SIDE_STYLE('',(#199183)); -#199183 = SURFACE_STYLE_FILL_AREA(#199184); -#199184 = FILL_AREA_STYLE('',(#199185)); -#199185 = FILL_AREA_STYLE_COLOUR('',#195083); -#199186 = OVER_RIDING_STYLED_ITEM('overriding color',(#199187),#133609, - #195018); -#199187 = PRESENTATION_STYLE_ASSIGNMENT((#199188)); -#199188 = SURFACE_STYLE_USAGE(.BOTH.,#199189); -#199189 = SURFACE_SIDE_STYLE('',(#199190)); -#199190 = SURFACE_STYLE_FILL_AREA(#199191); -#199191 = FILL_AREA_STYLE('',(#199192)); -#199192 = FILL_AREA_STYLE_COLOUR('',#195083); -#199193 = OVER_RIDING_STYLED_ITEM('overriding color',(#199194),#133688, - #195018); -#199194 = PRESENTATION_STYLE_ASSIGNMENT((#199195)); -#199195 = SURFACE_STYLE_USAGE(.BOTH.,#199196); -#199196 = SURFACE_SIDE_STYLE('',(#199197)); -#199197 = SURFACE_STYLE_FILL_AREA(#199198); -#199198 = FILL_AREA_STYLE('',(#199199)); -#199199 = FILL_AREA_STYLE_COLOUR('',#195083); -#199200 = OVER_RIDING_STYLED_ITEM('overriding color',(#199201),#133813, - #195018); -#199201 = PRESENTATION_STYLE_ASSIGNMENT((#199202)); -#199202 = SURFACE_STYLE_USAGE(.BOTH.,#199203); -#199203 = SURFACE_SIDE_STYLE('',(#199204)); -#199204 = SURFACE_STYLE_FILL_AREA(#199205); -#199205 = FILL_AREA_STYLE('',(#199206)); -#199206 = FILL_AREA_STYLE_COLOUR('',#195083); -#199207 = OVER_RIDING_STYLED_ITEM('overriding color',(#199208),#133888, - #195018); -#199208 = PRESENTATION_STYLE_ASSIGNMENT((#199209)); -#199209 = SURFACE_STYLE_USAGE(.BOTH.,#199210); -#199210 = SURFACE_SIDE_STYLE('',(#199211)); -#199211 = SURFACE_STYLE_FILL_AREA(#199212); -#199212 = FILL_AREA_STYLE('',(#199213)); -#199213 = FILL_AREA_STYLE_COLOUR('',#195083); -#199214 = OVER_RIDING_STYLED_ITEM('overriding color',(#199215),#133963, - #195018); -#199215 = PRESENTATION_STYLE_ASSIGNMENT((#199216)); -#199216 = SURFACE_STYLE_USAGE(.BOTH.,#199217); -#199217 = SURFACE_SIDE_STYLE('',(#199218)); -#199218 = SURFACE_STYLE_FILL_AREA(#199219); -#199219 = FILL_AREA_STYLE('',(#199220)); -#199220 = FILL_AREA_STYLE_COLOUR('',#195083); -#199221 = OVER_RIDING_STYLED_ITEM('overriding color',(#199222),#134083, - #195018); -#199222 = PRESENTATION_STYLE_ASSIGNMENT((#199223)); -#199223 = SURFACE_STYLE_USAGE(.BOTH.,#199224); -#199224 = SURFACE_SIDE_STYLE('',(#199225)); -#199225 = SURFACE_STYLE_FILL_AREA(#199226); -#199226 = FILL_AREA_STYLE('',(#199227)); -#199227 = FILL_AREA_STYLE_COLOUR('',#195083); -#199228 = OVER_RIDING_STYLED_ITEM('overriding color',(#199229),#134157, - #195018); -#199229 = PRESENTATION_STYLE_ASSIGNMENT((#199230)); -#199230 = SURFACE_STYLE_USAGE(.BOTH.,#199231); -#199231 = SURFACE_SIDE_STYLE('',(#199232)); -#199232 = SURFACE_STYLE_FILL_AREA(#199233); -#199233 = FILL_AREA_STYLE('',(#199234)); -#199234 = FILL_AREA_STYLE_COLOUR('',#195083); -#199235 = OVER_RIDING_STYLED_ITEM('overriding color',(#199236),#134204, - #195018); -#199236 = PRESENTATION_STYLE_ASSIGNMENT((#199237)); -#199237 = SURFACE_STYLE_USAGE(.BOTH.,#199238); -#199238 = SURFACE_SIDE_STYLE('',(#199239)); -#199239 = SURFACE_STYLE_FILL_AREA(#199240); -#199240 = FILL_AREA_STYLE('',(#199241)); -#199241 = FILL_AREA_STYLE_COLOUR('',#195083); -#199242 = OVER_RIDING_STYLED_ITEM('overriding color',(#199243),#134259, - #195018); -#199243 = PRESENTATION_STYLE_ASSIGNMENT((#199244)); -#199244 = SURFACE_STYLE_USAGE(.BOTH.,#199245); -#199245 = SURFACE_SIDE_STYLE('',(#199246)); -#199246 = SURFACE_STYLE_FILL_AREA(#199247); -#199247 = FILL_AREA_STYLE('',(#199248)); -#199248 = FILL_AREA_STYLE_COLOUR('',#195083); -#199249 = OVER_RIDING_STYLED_ITEM('overriding color',(#199250),#134286, - #195018); -#199250 = PRESENTATION_STYLE_ASSIGNMENT((#199251)); -#199251 = SURFACE_STYLE_USAGE(.BOTH.,#199252); -#199252 = SURFACE_SIDE_STYLE('',(#199253)); -#199253 = SURFACE_STYLE_FILL_AREA(#199254); -#199254 = FILL_AREA_STYLE('',(#199255)); -#199255 = FILL_AREA_STYLE_COLOUR('',#195083); -#199256 = OVER_RIDING_STYLED_ITEM('overriding color',(#199257),#134321, - #195018); -#199257 = PRESENTATION_STYLE_ASSIGNMENT((#199258)); -#199258 = SURFACE_STYLE_USAGE(.BOTH.,#199259); -#199259 = SURFACE_SIDE_STYLE('',(#199260)); -#199260 = SURFACE_STYLE_FILL_AREA(#199261); -#199261 = FILL_AREA_STYLE('',(#199262)); -#199262 = FILL_AREA_STYLE_COLOUR('',#195083); -#199263 = OVER_RIDING_STYLED_ITEM('overriding color',(#199264),#134328, - #195018); -#199264 = PRESENTATION_STYLE_ASSIGNMENT((#199265)); -#199265 = SURFACE_STYLE_USAGE(.BOTH.,#199266); -#199266 = SURFACE_SIDE_STYLE('',(#199267)); -#199267 = SURFACE_STYLE_FILL_AREA(#199268); -#199268 = FILL_AREA_STYLE('',(#199269)); -#199269 = FILL_AREA_STYLE_COLOUR('',#195083); -#199270 = OVER_RIDING_STYLED_ITEM('overriding color',(#199271),#134437, - #195018); -#199271 = PRESENTATION_STYLE_ASSIGNMENT((#199272)); -#199272 = SURFACE_STYLE_USAGE(.BOTH.,#199273); -#199273 = SURFACE_SIDE_STYLE('',(#199274)); -#199274 = SURFACE_STYLE_FILL_AREA(#199275); -#199275 = FILL_AREA_STYLE('',(#199276)); -#199276 = FILL_AREA_STYLE_COLOUR('',#195083); -#199277 = OVER_RIDING_STYLED_ITEM('overriding color',(#199278),#134541, - #195018); -#199278 = PRESENTATION_STYLE_ASSIGNMENT((#199279)); -#199279 = SURFACE_STYLE_USAGE(.BOTH.,#199280); -#199280 = SURFACE_SIDE_STYLE('',(#199281)); -#199281 = SURFACE_STYLE_FILL_AREA(#199282); -#199282 = FILL_AREA_STYLE('',(#199283)); -#199283 = FILL_AREA_STYLE_COLOUR('',#195083); -#199284 = OVER_RIDING_STYLED_ITEM('overriding color',(#199285),#134620, - #195018); -#199285 = PRESENTATION_STYLE_ASSIGNMENT((#199286)); -#199286 = SURFACE_STYLE_USAGE(.BOTH.,#199287); -#199287 = SURFACE_SIDE_STYLE('',(#199288)); -#199288 = SURFACE_STYLE_FILL_AREA(#199289); -#199289 = FILL_AREA_STYLE('',(#199290)); -#199290 = FILL_AREA_STYLE_COLOUR('',#195083); -#199291 = OVER_RIDING_STYLED_ITEM('overriding color',(#199292),#134745, - #195018); -#199292 = PRESENTATION_STYLE_ASSIGNMENT((#199293)); -#199293 = SURFACE_STYLE_USAGE(.BOTH.,#199294); -#199294 = SURFACE_SIDE_STYLE('',(#199295)); -#199295 = SURFACE_STYLE_FILL_AREA(#199296); -#199296 = FILL_AREA_STYLE('',(#199297)); -#199297 = FILL_AREA_STYLE_COLOUR('',#195083); -#199298 = OVER_RIDING_STYLED_ITEM('overriding color',(#199299),#134820, - #195018); -#199299 = PRESENTATION_STYLE_ASSIGNMENT((#199300)); -#199300 = SURFACE_STYLE_USAGE(.BOTH.,#199301); -#199301 = SURFACE_SIDE_STYLE('',(#199302)); -#199302 = SURFACE_STYLE_FILL_AREA(#199303); -#199303 = FILL_AREA_STYLE('',(#199304)); -#199304 = FILL_AREA_STYLE_COLOUR('',#195083); -#199305 = OVER_RIDING_STYLED_ITEM('overriding color',(#199306),#134895, - #195018); -#199306 = PRESENTATION_STYLE_ASSIGNMENT((#199307)); -#199307 = SURFACE_STYLE_USAGE(.BOTH.,#199308); -#199308 = SURFACE_SIDE_STYLE('',(#199309)); -#199309 = SURFACE_STYLE_FILL_AREA(#199310); -#199310 = FILL_AREA_STYLE('',(#199311)); -#199311 = FILL_AREA_STYLE_COLOUR('',#195083); -#199312 = OVER_RIDING_STYLED_ITEM('overriding color',(#199313),#134969, - #195018); -#199313 = PRESENTATION_STYLE_ASSIGNMENT((#199314)); -#199314 = SURFACE_STYLE_USAGE(.BOTH.,#199315); -#199315 = SURFACE_SIDE_STYLE('',(#199316)); -#199316 = SURFACE_STYLE_FILL_AREA(#199317); -#199317 = FILL_AREA_STYLE('',(#199318)); -#199318 = FILL_AREA_STYLE_COLOUR('',#195083); -#199319 = OVER_RIDING_STYLED_ITEM('overriding color',(#199320),#135043, - #195018); -#199320 = PRESENTATION_STYLE_ASSIGNMENT((#199321)); -#199321 = SURFACE_STYLE_USAGE(.BOTH.,#199322); -#199322 = SURFACE_SIDE_STYLE('',(#199323)); -#199323 = SURFACE_STYLE_FILL_AREA(#199324); -#199324 = FILL_AREA_STYLE('',(#199325)); -#199325 = FILL_AREA_STYLE_COLOUR('',#195083); -#199326 = OVER_RIDING_STYLED_ITEM('overriding color',(#199327),#135090, - #195018); -#199327 = PRESENTATION_STYLE_ASSIGNMENT((#199328)); -#199328 = SURFACE_STYLE_USAGE(.BOTH.,#199329); -#199329 = SURFACE_SIDE_STYLE('',(#199330)); -#199330 = SURFACE_STYLE_FILL_AREA(#199331); -#199331 = FILL_AREA_STYLE('',(#199332)); -#199332 = FILL_AREA_STYLE_COLOUR('',#195083); -#199333 = OVER_RIDING_STYLED_ITEM('overriding color',(#199334),#135145, - #195018); -#199334 = PRESENTATION_STYLE_ASSIGNMENT((#199335)); -#199335 = SURFACE_STYLE_USAGE(.BOTH.,#199336); -#199336 = SURFACE_SIDE_STYLE('',(#199337)); -#199337 = SURFACE_STYLE_FILL_AREA(#199338); -#199338 = FILL_AREA_STYLE('',(#199339)); -#199339 = FILL_AREA_STYLE_COLOUR('',#195083); -#199340 = OVER_RIDING_STYLED_ITEM('overriding color',(#199341),#135172, - #195018); -#199341 = PRESENTATION_STYLE_ASSIGNMENT((#199342)); -#199342 = SURFACE_STYLE_USAGE(.BOTH.,#199343); -#199343 = SURFACE_SIDE_STYLE('',(#199344)); -#199344 = SURFACE_STYLE_FILL_AREA(#199345); -#199345 = FILL_AREA_STYLE('',(#199346)); -#199346 = FILL_AREA_STYLE_COLOUR('',#195083); -#199347 = OVER_RIDING_STYLED_ITEM('overriding color',(#199348),#135207, - #195018); -#199348 = PRESENTATION_STYLE_ASSIGNMENT((#199349)); -#199349 = SURFACE_STYLE_USAGE(.BOTH.,#199350); -#199350 = SURFACE_SIDE_STYLE('',(#199351)); -#199351 = SURFACE_STYLE_FILL_AREA(#199352); -#199352 = FILL_AREA_STYLE('',(#199353)); -#199353 = FILL_AREA_STYLE_COLOUR('',#195083); -#199354 = OVER_RIDING_STYLED_ITEM('overriding color',(#199355),#135214, - #195018); -#199355 = PRESENTATION_STYLE_ASSIGNMENT((#199356)); -#199356 = SURFACE_STYLE_USAGE(.BOTH.,#199357); -#199357 = SURFACE_SIDE_STYLE('',(#199358)); -#199358 = SURFACE_STYLE_FILL_AREA(#199359); -#199359 = FILL_AREA_STYLE('',(#199360)); -#199360 = FILL_AREA_STYLE_COLOUR('',#195083); -#199361 = OVER_RIDING_STYLED_ITEM('overriding color',(#199362),#135323, - #195018); -#199362 = PRESENTATION_STYLE_ASSIGNMENT((#199363)); -#199363 = SURFACE_STYLE_USAGE(.BOTH.,#199364); -#199364 = SURFACE_SIDE_STYLE('',(#199365)); -#199365 = SURFACE_STYLE_FILL_AREA(#199366); -#199366 = FILL_AREA_STYLE('',(#199367)); -#199367 = FILL_AREA_STYLE_COLOUR('',#195083); -#199368 = OVER_RIDING_STYLED_ITEM('overriding color',(#199369),#135427, - #195018); -#199369 = PRESENTATION_STYLE_ASSIGNMENT((#199370)); -#199370 = SURFACE_STYLE_USAGE(.BOTH.,#199371); -#199371 = SURFACE_SIDE_STYLE('',(#199372)); -#199372 = SURFACE_STYLE_FILL_AREA(#199373); -#199373 = FILL_AREA_STYLE('',(#199374)); -#199374 = FILL_AREA_STYLE_COLOUR('',#195083); -#199375 = OVER_RIDING_STYLED_ITEM('overriding color',(#199376),#135506, - #195018); -#199376 = PRESENTATION_STYLE_ASSIGNMENT((#199377)); -#199377 = SURFACE_STYLE_USAGE(.BOTH.,#199378); -#199378 = SURFACE_SIDE_STYLE('',(#199379)); -#199379 = SURFACE_STYLE_FILL_AREA(#199380); -#199380 = FILL_AREA_STYLE('',(#199381)); -#199381 = FILL_AREA_STYLE_COLOUR('',#195083); -#199382 = OVER_RIDING_STYLED_ITEM('overriding color',(#199383),#135631, - #195018); -#199383 = PRESENTATION_STYLE_ASSIGNMENT((#199384)); -#199384 = SURFACE_STYLE_USAGE(.BOTH.,#199385); -#199385 = SURFACE_SIDE_STYLE('',(#199386)); -#199386 = SURFACE_STYLE_FILL_AREA(#199387); -#199387 = FILL_AREA_STYLE('',(#199388)); -#199388 = FILL_AREA_STYLE_COLOUR('',#195083); -#199389 = OVER_RIDING_STYLED_ITEM('overriding color',(#199390),#135706, - #195018); -#199390 = PRESENTATION_STYLE_ASSIGNMENT((#199391)); -#199391 = SURFACE_STYLE_USAGE(.BOTH.,#199392); -#199392 = SURFACE_SIDE_STYLE('',(#199393)); -#199393 = SURFACE_STYLE_FILL_AREA(#199394); -#199394 = FILL_AREA_STYLE('',(#199395)); -#199395 = FILL_AREA_STYLE_COLOUR('',#195083); -#199396 = OVER_RIDING_STYLED_ITEM('overriding color',(#199397),#135781, - #195018); -#199397 = PRESENTATION_STYLE_ASSIGNMENT((#199398)); -#199398 = SURFACE_STYLE_USAGE(.BOTH.,#199399); -#199399 = SURFACE_SIDE_STYLE('',(#199400)); -#199400 = SURFACE_STYLE_FILL_AREA(#199401); -#199401 = FILL_AREA_STYLE('',(#199402)); -#199402 = FILL_AREA_STYLE_COLOUR('',#195083); -#199403 = OVER_RIDING_STYLED_ITEM('overriding color',(#199404),#135855, - #195018); -#199404 = PRESENTATION_STYLE_ASSIGNMENT((#199405)); -#199405 = SURFACE_STYLE_USAGE(.BOTH.,#199406); -#199406 = SURFACE_SIDE_STYLE('',(#199407)); -#199407 = SURFACE_STYLE_FILL_AREA(#199408); -#199408 = FILL_AREA_STYLE('',(#199409)); -#199409 = FILL_AREA_STYLE_COLOUR('',#195083); -#199410 = OVER_RIDING_STYLED_ITEM('overriding color',(#199411),#135929, - #195018); -#199411 = PRESENTATION_STYLE_ASSIGNMENT((#199412)); -#199412 = SURFACE_STYLE_USAGE(.BOTH.,#199413); -#199413 = SURFACE_SIDE_STYLE('',(#199414)); -#199414 = SURFACE_STYLE_FILL_AREA(#199415); -#199415 = FILL_AREA_STYLE('',(#199416)); -#199416 = FILL_AREA_STYLE_COLOUR('',#195083); -#199417 = OVER_RIDING_STYLED_ITEM('overriding color',(#199418),#135976, - #195018); -#199418 = PRESENTATION_STYLE_ASSIGNMENT((#199419)); -#199419 = SURFACE_STYLE_USAGE(.BOTH.,#199420); -#199420 = SURFACE_SIDE_STYLE('',(#199421)); -#199421 = SURFACE_STYLE_FILL_AREA(#199422); -#199422 = FILL_AREA_STYLE('',(#199423)); -#199423 = FILL_AREA_STYLE_COLOUR('',#195083); -#199424 = OVER_RIDING_STYLED_ITEM('overriding color',(#199425),#136031, - #195018); -#199425 = PRESENTATION_STYLE_ASSIGNMENT((#199426)); -#199426 = SURFACE_STYLE_USAGE(.BOTH.,#199427); -#199427 = SURFACE_SIDE_STYLE('',(#199428)); -#199428 = SURFACE_STYLE_FILL_AREA(#199429); -#199429 = FILL_AREA_STYLE('',(#199430)); -#199430 = FILL_AREA_STYLE_COLOUR('',#195083); -#199431 = OVER_RIDING_STYLED_ITEM('overriding color',(#199432),#136058, - #195018); -#199432 = PRESENTATION_STYLE_ASSIGNMENT((#199433)); -#199433 = SURFACE_STYLE_USAGE(.BOTH.,#199434); -#199434 = SURFACE_SIDE_STYLE('',(#199435)); -#199435 = SURFACE_STYLE_FILL_AREA(#199436); -#199436 = FILL_AREA_STYLE('',(#199437)); -#199437 = FILL_AREA_STYLE_COLOUR('',#195083); -#199438 = OVER_RIDING_STYLED_ITEM('overriding color',(#199439),#136093, - #195018); -#199439 = PRESENTATION_STYLE_ASSIGNMENT((#199440)); -#199440 = SURFACE_STYLE_USAGE(.BOTH.,#199441); -#199441 = SURFACE_SIDE_STYLE('',(#199442)); -#199442 = SURFACE_STYLE_FILL_AREA(#199443); -#199443 = FILL_AREA_STYLE('',(#199444)); -#199444 = FILL_AREA_STYLE_COLOUR('',#195083); -#199445 = OVER_RIDING_STYLED_ITEM('overriding color',(#199446),#136100, - #195018); -#199446 = PRESENTATION_STYLE_ASSIGNMENT((#199447)); -#199447 = SURFACE_STYLE_USAGE(.BOTH.,#199448); -#199448 = SURFACE_SIDE_STYLE('',(#199449)); -#199449 = SURFACE_STYLE_FILL_AREA(#199450); -#199450 = FILL_AREA_STYLE('',(#199451)); -#199451 = FILL_AREA_STYLE_COLOUR('',#195083); -#199452 = OVER_RIDING_STYLED_ITEM('overriding color',(#199453),#136209, - #195018); -#199453 = PRESENTATION_STYLE_ASSIGNMENT((#199454)); -#199454 = SURFACE_STYLE_USAGE(.BOTH.,#199455); -#199455 = SURFACE_SIDE_STYLE('',(#199456)); -#199456 = SURFACE_STYLE_FILL_AREA(#199457); -#199457 = FILL_AREA_STYLE('',(#199458)); -#199458 = FILL_AREA_STYLE_COLOUR('',#195083); -#199459 = OVER_RIDING_STYLED_ITEM('overriding color',(#199460),#136313, - #195018); -#199460 = PRESENTATION_STYLE_ASSIGNMENT((#199461)); -#199461 = SURFACE_STYLE_USAGE(.BOTH.,#199462); -#199462 = SURFACE_SIDE_STYLE('',(#199463)); -#199463 = SURFACE_STYLE_FILL_AREA(#199464); -#199464 = FILL_AREA_STYLE('',(#199465)); -#199465 = FILL_AREA_STYLE_COLOUR('',#195083); -#199466 = OVER_RIDING_STYLED_ITEM('overriding color',(#199467),#136392, - #195018); -#199467 = PRESENTATION_STYLE_ASSIGNMENT((#199468)); -#199468 = SURFACE_STYLE_USAGE(.BOTH.,#199469); -#199469 = SURFACE_SIDE_STYLE('',(#199470)); -#199470 = SURFACE_STYLE_FILL_AREA(#199471); -#199471 = FILL_AREA_STYLE('',(#199472)); -#199472 = FILL_AREA_STYLE_COLOUR('',#195083); -#199473 = OVER_RIDING_STYLED_ITEM('overriding color',(#199474),#136471, - #195018); -#199474 = PRESENTATION_STYLE_ASSIGNMENT((#199475)); -#199475 = SURFACE_STYLE_USAGE(.BOTH.,#199476); -#199476 = SURFACE_SIDE_STYLE('',(#199477)); -#199477 = SURFACE_STYLE_FILL_AREA(#199478); -#199478 = FILL_AREA_STYLE('',(#199479)); -#199479 = FILL_AREA_STYLE_COLOUR('',#195083); -#199480 = OVER_RIDING_STYLED_ITEM('overriding color',(#199481),#136546, - #195018); -#199481 = PRESENTATION_STYLE_ASSIGNMENT((#199482)); -#199482 = SURFACE_STYLE_USAGE(.BOTH.,#199483); -#199483 = SURFACE_SIDE_STYLE('',(#199484)); -#199484 = SURFACE_STYLE_FILL_AREA(#199485); -#199485 = FILL_AREA_STYLE('',(#199486)); -#199486 = FILL_AREA_STYLE_COLOUR('',#195083); -#199487 = OVER_RIDING_STYLED_ITEM('overriding color',(#199488),#136621, - #195018); -#199488 = PRESENTATION_STYLE_ASSIGNMENT((#199489)); -#199489 = SURFACE_STYLE_USAGE(.BOTH.,#199490); -#199490 = SURFACE_SIDE_STYLE('',(#199491)); -#199491 = SURFACE_STYLE_FILL_AREA(#199492); -#199492 = FILL_AREA_STYLE('',(#199493)); -#199493 = FILL_AREA_STYLE_COLOUR('',#195083); -#199494 = OVER_RIDING_STYLED_ITEM('overriding color',(#199495),#136695, - #195018); -#199495 = PRESENTATION_STYLE_ASSIGNMENT((#199496)); -#199496 = SURFACE_STYLE_USAGE(.BOTH.,#199497); -#199497 = SURFACE_SIDE_STYLE('',(#199498)); -#199498 = SURFACE_STYLE_FILL_AREA(#199499); -#199499 = FILL_AREA_STYLE('',(#199500)); -#199500 = FILL_AREA_STYLE_COLOUR('',#195083); -#199501 = OVER_RIDING_STYLED_ITEM('overriding color',(#199502),#136769, - #195018); -#199502 = PRESENTATION_STYLE_ASSIGNMENT((#199503)); -#199503 = SURFACE_STYLE_USAGE(.BOTH.,#199504); -#199504 = SURFACE_SIDE_STYLE('',(#199505)); -#199505 = SURFACE_STYLE_FILL_AREA(#199506); -#199506 = FILL_AREA_STYLE('',(#199507)); -#199507 = FILL_AREA_STYLE_COLOUR('',#195083); -#199508 = OVER_RIDING_STYLED_ITEM('overriding color',(#199509),#136844, - #195018); -#199509 = PRESENTATION_STYLE_ASSIGNMENT((#199510)); -#199510 = SURFACE_STYLE_USAGE(.BOTH.,#199511); -#199511 = SURFACE_SIDE_STYLE('',(#199512)); -#199512 = SURFACE_STYLE_FILL_AREA(#199513); -#199513 = FILL_AREA_STYLE('',(#199514)); -#199514 = FILL_AREA_STYLE_COLOUR('',#195083); -#199515 = OVER_RIDING_STYLED_ITEM('overriding color',(#199516),#136871, - #195018); -#199516 = PRESENTATION_STYLE_ASSIGNMENT((#199517)); -#199517 = SURFACE_STYLE_USAGE(.BOTH.,#199518); -#199518 = SURFACE_SIDE_STYLE('',(#199519)); -#199519 = SURFACE_STYLE_FILL_AREA(#199520); -#199520 = FILL_AREA_STYLE('',(#199521)); -#199521 = FILL_AREA_STYLE_COLOUR('',#195083); -#199522 = OVER_RIDING_STYLED_ITEM('overriding color',(#199523),#136926, - #195018); -#199523 = PRESENTATION_STYLE_ASSIGNMENT((#199524)); -#199524 = SURFACE_STYLE_USAGE(.BOTH.,#199525); -#199525 = SURFACE_SIDE_STYLE('',(#199526)); -#199526 = SURFACE_STYLE_FILL_AREA(#199527); -#199527 = FILL_AREA_STYLE('',(#199528)); -#199528 = FILL_AREA_STYLE_COLOUR('',#195083); -#199529 = OVER_RIDING_STYLED_ITEM('overriding color',(#199530),#136933, - #195018); -#199530 = PRESENTATION_STYLE_ASSIGNMENT((#199531)); -#199531 = SURFACE_STYLE_USAGE(.BOTH.,#199532); -#199532 = SURFACE_SIDE_STYLE('',(#199533)); -#199533 = SURFACE_STYLE_FILL_AREA(#199534); -#199534 = FILL_AREA_STYLE('',(#199535)); -#199535 = FILL_AREA_STYLE_COLOUR('',#195083); -#199536 = OVER_RIDING_STYLED_ITEM('overriding color',(#199537),#136940, - #195018); -#199537 = PRESENTATION_STYLE_ASSIGNMENT((#199538)); -#199538 = SURFACE_STYLE_USAGE(.BOTH.,#199539); -#199539 = SURFACE_SIDE_STYLE('',(#199540)); -#199540 = SURFACE_STYLE_FILL_AREA(#199541); -#199541 = FILL_AREA_STYLE('',(#199542)); -#199542 = FILL_AREA_STYLE_COLOUR('',#195083); -#199543 = OVER_RIDING_STYLED_ITEM('overriding color',(#199544),#137049, - #195018); -#199544 = PRESENTATION_STYLE_ASSIGNMENT((#199545)); -#199545 = SURFACE_STYLE_USAGE(.BOTH.,#199546); -#199546 = SURFACE_SIDE_STYLE('',(#199547)); -#199547 = SURFACE_STYLE_FILL_AREA(#199548); -#199548 = FILL_AREA_STYLE('',(#199549)); -#199549 = FILL_AREA_STYLE_COLOUR('',#195083); -#199550 = OVER_RIDING_STYLED_ITEM('overriding color',(#199551),#137153, - #195018); -#199551 = PRESENTATION_STYLE_ASSIGNMENT((#199552)); -#199552 = SURFACE_STYLE_USAGE(.BOTH.,#199553); -#199553 = SURFACE_SIDE_STYLE('',(#199554)); -#199554 = SURFACE_STYLE_FILL_AREA(#199555); -#199555 = FILL_AREA_STYLE('',(#199556)); -#199556 = FILL_AREA_STYLE_COLOUR('',#195083); -#199557 = OVER_RIDING_STYLED_ITEM('overriding color',(#199558),#137278, - #195018); -#199558 = PRESENTATION_STYLE_ASSIGNMENT((#199559)); -#199559 = SURFACE_STYLE_USAGE(.BOTH.,#199560); -#199560 = SURFACE_SIDE_STYLE('',(#199561)); -#199561 = SURFACE_STYLE_FILL_AREA(#199562); -#199562 = FILL_AREA_STYLE('',(#199563)); -#199563 = FILL_AREA_STYLE_COLOUR('',#195083); -#199564 = OVER_RIDING_STYLED_ITEM('overriding color',(#199565),#137357, - #195018); -#199565 = PRESENTATION_STYLE_ASSIGNMENT((#199566)); -#199566 = SURFACE_STYLE_USAGE(.BOTH.,#199567); -#199567 = SURFACE_SIDE_STYLE('',(#199568)); -#199568 = SURFACE_STYLE_FILL_AREA(#199569); -#199569 = FILL_AREA_STYLE('',(#199570)); -#199570 = FILL_AREA_STYLE_COLOUR('',#195083); -#199571 = OVER_RIDING_STYLED_ITEM('overriding color',(#199572),#137432, - #195018); -#199572 = PRESENTATION_STYLE_ASSIGNMENT((#199573)); -#199573 = SURFACE_STYLE_USAGE(.BOTH.,#199574); -#199574 = SURFACE_SIDE_STYLE('',(#199575)); -#199575 = SURFACE_STYLE_FILL_AREA(#199576); -#199576 = FILL_AREA_STYLE('',(#199577)); -#199577 = FILL_AREA_STYLE_COLOUR('',#195083); -#199578 = OVER_RIDING_STYLED_ITEM('overriding color',(#199579),#137507, - #195018); -#199579 = PRESENTATION_STYLE_ASSIGNMENT((#199580)); -#199580 = SURFACE_STYLE_USAGE(.BOTH.,#199581); -#199581 = SURFACE_SIDE_STYLE('',(#199582)); -#199582 = SURFACE_STYLE_FILL_AREA(#199583); -#199583 = FILL_AREA_STYLE('',(#199584)); -#199584 = FILL_AREA_STYLE_COLOUR('',#195083); -#199585 = OVER_RIDING_STYLED_ITEM('overriding color',(#199586),#137581, - #195018); -#199586 = PRESENTATION_STYLE_ASSIGNMENT((#199587)); -#199587 = SURFACE_STYLE_USAGE(.BOTH.,#199588); -#199588 = SURFACE_SIDE_STYLE('',(#199589)); -#199589 = SURFACE_STYLE_FILL_AREA(#199590); -#199590 = FILL_AREA_STYLE('',(#199591)); -#199591 = FILL_AREA_STYLE_COLOUR('',#195083); -#199592 = OVER_RIDING_STYLED_ITEM('overriding color',(#199593),#137701, - #195018); -#199593 = PRESENTATION_STYLE_ASSIGNMENT((#199594)); -#199594 = SURFACE_STYLE_USAGE(.BOTH.,#199595); -#199595 = SURFACE_SIDE_STYLE('',(#199596)); -#199596 = SURFACE_STYLE_FILL_AREA(#199597); -#199597 = FILL_AREA_STYLE('',(#199598)); -#199598 = FILL_AREA_STYLE_COLOUR('',#195083); -#199599 = OVER_RIDING_STYLED_ITEM('overriding color',(#199600),#137748, - #195018); -#199600 = PRESENTATION_STYLE_ASSIGNMENT((#199601)); -#199601 = SURFACE_STYLE_USAGE(.BOTH.,#199602); -#199602 = SURFACE_SIDE_STYLE('',(#199603)); -#199603 = SURFACE_STYLE_FILL_AREA(#199604); -#199604 = FILL_AREA_STYLE('',(#199605)); -#199605 = FILL_AREA_STYLE_COLOUR('',#195083); -#199606 = OVER_RIDING_STYLED_ITEM('overriding color',(#199607),#137803, - #195018); -#199607 = PRESENTATION_STYLE_ASSIGNMENT((#199608)); -#199608 = SURFACE_STYLE_USAGE(.BOTH.,#199609); -#199609 = SURFACE_SIDE_STYLE('',(#199610)); -#199610 = SURFACE_STYLE_FILL_AREA(#199611); -#199611 = FILL_AREA_STYLE('',(#199612)); -#199612 = FILL_AREA_STYLE_COLOUR('',#195083); -#199613 = OVER_RIDING_STYLED_ITEM('overriding color',(#199614),#137830, - #195018); -#199614 = PRESENTATION_STYLE_ASSIGNMENT((#199615)); -#199615 = SURFACE_STYLE_USAGE(.BOTH.,#199616); -#199616 = SURFACE_SIDE_STYLE('',(#199617)); -#199617 = SURFACE_STYLE_FILL_AREA(#199618); -#199618 = FILL_AREA_STYLE('',(#199619)); -#199619 = FILL_AREA_STYLE_COLOUR('',#195083); -#199620 = OVER_RIDING_STYLED_ITEM('overriding color',(#199621),#137865, - #195018); -#199621 = PRESENTATION_STYLE_ASSIGNMENT((#199622)); -#199622 = SURFACE_STYLE_USAGE(.BOTH.,#199623); -#199623 = SURFACE_SIDE_STYLE('',(#199624)); -#199624 = SURFACE_STYLE_FILL_AREA(#199625); -#199625 = FILL_AREA_STYLE('',(#199626)); -#199626 = FILL_AREA_STYLE_COLOUR('',#195083); -#199627 = OVER_RIDING_STYLED_ITEM('overriding color',(#199628),#137872, - #195018); -#199628 = PRESENTATION_STYLE_ASSIGNMENT((#199629)); -#199629 = SURFACE_STYLE_USAGE(.BOTH.,#199630); -#199630 = SURFACE_SIDE_STYLE('',(#199631)); -#199631 = SURFACE_STYLE_FILL_AREA(#199632); -#199632 = FILL_AREA_STYLE('',(#199633)); -#199633 = FILL_AREA_STYLE_COLOUR('',#195083); -#199634 = OVER_RIDING_STYLED_ITEM('overriding color',(#199635),#137981, - #195018); -#199635 = PRESENTATION_STYLE_ASSIGNMENT((#199636)); -#199636 = SURFACE_STYLE_USAGE(.BOTH.,#199637); -#199637 = SURFACE_SIDE_STYLE('',(#199638)); -#199638 = SURFACE_STYLE_FILL_AREA(#199639); -#199639 = FILL_AREA_STYLE('',(#199640)); -#199640 = FILL_AREA_STYLE_COLOUR('',#195083); -#199641 = OVER_RIDING_STYLED_ITEM('overriding color',(#199642),#138085, - #195018); -#199642 = PRESENTATION_STYLE_ASSIGNMENT((#199643)); -#199643 = SURFACE_STYLE_USAGE(.BOTH.,#199644); -#199644 = SURFACE_SIDE_STYLE('',(#199645)); -#199645 = SURFACE_STYLE_FILL_AREA(#199646); -#199646 = FILL_AREA_STYLE('',(#199647)); -#199647 = FILL_AREA_STYLE_COLOUR('',#195083); -#199648 = OVER_RIDING_STYLED_ITEM('overriding color',(#199649),#138164, - #195018); -#199649 = PRESENTATION_STYLE_ASSIGNMENT((#199650)); -#199650 = SURFACE_STYLE_USAGE(.BOTH.,#199651); -#199651 = SURFACE_SIDE_STYLE('',(#199652)); -#199652 = SURFACE_STYLE_FILL_AREA(#199653); -#199653 = FILL_AREA_STYLE('',(#199654)); -#199654 = FILL_AREA_STYLE_COLOUR('',#195083); -#199655 = OVER_RIDING_STYLED_ITEM('overriding color',(#199656),#138243, - #195018); -#199656 = PRESENTATION_STYLE_ASSIGNMENT((#199657)); -#199657 = SURFACE_STYLE_USAGE(.BOTH.,#199658); -#199658 = SURFACE_SIDE_STYLE('',(#199659)); -#199659 = SURFACE_STYLE_FILL_AREA(#199660); -#199660 = FILL_AREA_STYLE('',(#199661)); -#199661 = FILL_AREA_STYLE_COLOUR('',#195083); -#199662 = OVER_RIDING_STYLED_ITEM('overriding color',(#199663),#138318, - #195018); -#199663 = PRESENTATION_STYLE_ASSIGNMENT((#199664)); -#199664 = SURFACE_STYLE_USAGE(.BOTH.,#199665); -#199665 = SURFACE_SIDE_STYLE('',(#199666)); -#199666 = SURFACE_STYLE_FILL_AREA(#199667); -#199667 = FILL_AREA_STYLE('',(#199668)); -#199668 = FILL_AREA_STYLE_COLOUR('',#195083); -#199669 = OVER_RIDING_STYLED_ITEM('overriding color',(#199670),#138393, - #195018); -#199670 = PRESENTATION_STYLE_ASSIGNMENT((#199671)); -#199671 = SURFACE_STYLE_USAGE(.BOTH.,#199672); -#199672 = SURFACE_SIDE_STYLE('',(#199673)); -#199673 = SURFACE_STYLE_FILL_AREA(#199674); -#199674 = FILL_AREA_STYLE('',(#199675)); -#199675 = FILL_AREA_STYLE_COLOUR('',#195083); -#199676 = OVER_RIDING_STYLED_ITEM('overriding color',(#199677),#138467, - #195018); -#199677 = PRESENTATION_STYLE_ASSIGNMENT((#199678)); -#199678 = SURFACE_STYLE_USAGE(.BOTH.,#199679); -#199679 = SURFACE_SIDE_STYLE('',(#199680)); -#199680 = SURFACE_STYLE_FILL_AREA(#199681); -#199681 = FILL_AREA_STYLE('',(#199682)); -#199682 = FILL_AREA_STYLE_COLOUR('',#195083); -#199683 = OVER_RIDING_STYLED_ITEM('overriding color',(#199684),#138541, - #195018); -#199684 = PRESENTATION_STYLE_ASSIGNMENT((#199685)); -#199685 = SURFACE_STYLE_USAGE(.BOTH.,#199686); -#199686 = SURFACE_SIDE_STYLE('',(#199687)); -#199687 = SURFACE_STYLE_FILL_AREA(#199688); -#199688 = FILL_AREA_STYLE('',(#199689)); -#199689 = FILL_AREA_STYLE_COLOUR('',#195083); -#199690 = OVER_RIDING_STYLED_ITEM('overriding color',(#199691),#138616, - #195018); -#199691 = PRESENTATION_STYLE_ASSIGNMENT((#199692)); -#199692 = SURFACE_STYLE_USAGE(.BOTH.,#199693); -#199693 = SURFACE_SIDE_STYLE('',(#199694)); -#199694 = SURFACE_STYLE_FILL_AREA(#199695); -#199695 = FILL_AREA_STYLE('',(#199696)); -#199696 = FILL_AREA_STYLE_COLOUR('',#195083); -#199697 = OVER_RIDING_STYLED_ITEM('overriding color',(#199698),#138643, - #195018); -#199698 = PRESENTATION_STYLE_ASSIGNMENT((#199699)); -#199699 = SURFACE_STYLE_USAGE(.BOTH.,#199700); -#199700 = SURFACE_SIDE_STYLE('',(#199701)); -#199701 = SURFACE_STYLE_FILL_AREA(#199702); -#199702 = FILL_AREA_STYLE('',(#199703)); -#199703 = FILL_AREA_STYLE_COLOUR('',#195083); -#199704 = OVER_RIDING_STYLED_ITEM('overriding color',(#199705),#138698, - #195018); -#199705 = PRESENTATION_STYLE_ASSIGNMENT((#199706)); -#199706 = SURFACE_STYLE_USAGE(.BOTH.,#199707); -#199707 = SURFACE_SIDE_STYLE('',(#199708)); -#199708 = SURFACE_STYLE_FILL_AREA(#199709); -#199709 = FILL_AREA_STYLE('',(#199710)); -#199710 = FILL_AREA_STYLE_COLOUR('',#195083); -#199711 = OVER_RIDING_STYLED_ITEM('overriding color',(#199712),#138705, - #195018); -#199712 = PRESENTATION_STYLE_ASSIGNMENT((#199713)); -#199713 = SURFACE_STYLE_USAGE(.BOTH.,#199714); -#199714 = SURFACE_SIDE_STYLE('',(#199715)); -#199715 = SURFACE_STYLE_FILL_AREA(#199716); -#199716 = FILL_AREA_STYLE('',(#199717)); -#199717 = FILL_AREA_STYLE_COLOUR('',#195083); -#199718 = OVER_RIDING_STYLED_ITEM('overriding color',(#199719),#138712, - #195018); -#199719 = PRESENTATION_STYLE_ASSIGNMENT((#199720)); -#199720 = SURFACE_STYLE_USAGE(.BOTH.,#199721); -#199721 = SURFACE_SIDE_STYLE('',(#199722)); -#199722 = SURFACE_STYLE_FILL_AREA(#199723); -#199723 = FILL_AREA_STYLE('',(#199724)); -#199724 = FILL_AREA_STYLE_COLOUR('',#195083); -#199725 = OVER_RIDING_STYLED_ITEM('overriding color',(#199726),#138821, - #195018); -#199726 = PRESENTATION_STYLE_ASSIGNMENT((#199727)); -#199727 = SURFACE_STYLE_USAGE(.BOTH.,#199728); -#199728 = SURFACE_SIDE_STYLE('',(#199729)); -#199729 = SURFACE_STYLE_FILL_AREA(#199730); -#199730 = FILL_AREA_STYLE('',(#199731)); -#199731 = FILL_AREA_STYLE_COLOUR('',#195083); -#199732 = OVER_RIDING_STYLED_ITEM('overriding color',(#199733),#138925, - #195018); -#199733 = PRESENTATION_STYLE_ASSIGNMENT((#199734)); -#199734 = SURFACE_STYLE_USAGE(.BOTH.,#199735); -#199735 = SURFACE_SIDE_STYLE('',(#199736)); -#199736 = SURFACE_STYLE_FILL_AREA(#199737); -#199737 = FILL_AREA_STYLE('',(#199738)); -#199738 = FILL_AREA_STYLE_COLOUR('',#195083); -#199739 = OVER_RIDING_STYLED_ITEM('overriding color',(#199740),#139004, - #195018); -#199740 = PRESENTATION_STYLE_ASSIGNMENT((#199741)); -#199741 = SURFACE_STYLE_USAGE(.BOTH.,#199742); -#199742 = SURFACE_SIDE_STYLE('',(#199743)); -#199743 = SURFACE_STYLE_FILL_AREA(#199744); -#199744 = FILL_AREA_STYLE('',(#199745)); -#199745 = FILL_AREA_STYLE_COLOUR('',#195083); -#199746 = OVER_RIDING_STYLED_ITEM('overriding color',(#199747),#139129, - #195018); -#199747 = PRESENTATION_STYLE_ASSIGNMENT((#199748)); -#199748 = SURFACE_STYLE_USAGE(.BOTH.,#199749); -#199749 = SURFACE_SIDE_STYLE('',(#199750)); -#199750 = SURFACE_STYLE_FILL_AREA(#199751); -#199751 = FILL_AREA_STYLE('',(#199752)); -#199752 = FILL_AREA_STYLE_COLOUR('',#195083); -#199753 = OVER_RIDING_STYLED_ITEM('overriding color',(#199754),#139204, - #195018); -#199754 = PRESENTATION_STYLE_ASSIGNMENT((#199755)); -#199755 = SURFACE_STYLE_USAGE(.BOTH.,#199756); -#199756 = SURFACE_SIDE_STYLE('',(#199757)); -#199757 = SURFACE_STYLE_FILL_AREA(#199758); -#199758 = FILL_AREA_STYLE('',(#199759)); -#199759 = FILL_AREA_STYLE_COLOUR('',#195083); -#199760 = OVER_RIDING_STYLED_ITEM('overriding color',(#199761),#139279, - #195018); -#199761 = PRESENTATION_STYLE_ASSIGNMENT((#199762)); -#199762 = SURFACE_STYLE_USAGE(.BOTH.,#199763); -#199763 = SURFACE_SIDE_STYLE('',(#199764)); -#199764 = SURFACE_STYLE_FILL_AREA(#199765); -#199765 = FILL_AREA_STYLE('',(#199766)); -#199766 = FILL_AREA_STYLE_COLOUR('',#195083); -#199767 = OVER_RIDING_STYLED_ITEM('overriding color',(#199768),#139353, - #195018); -#199768 = PRESENTATION_STYLE_ASSIGNMENT((#199769)); -#199769 = SURFACE_STYLE_USAGE(.BOTH.,#199770); -#199770 = SURFACE_SIDE_STYLE('',(#199771)); -#199771 = SURFACE_STYLE_FILL_AREA(#199772); -#199772 = FILL_AREA_STYLE('',(#199773)); -#199773 = FILL_AREA_STYLE_COLOUR('',#195083); -#199774 = OVER_RIDING_STYLED_ITEM('overriding color',(#199775),#139473, - #195018); -#199775 = PRESENTATION_STYLE_ASSIGNMENT((#199776)); -#199776 = SURFACE_STYLE_USAGE(.BOTH.,#199777); -#199777 = SURFACE_SIDE_STYLE('',(#199778)); -#199778 = SURFACE_STYLE_FILL_AREA(#199779); -#199779 = FILL_AREA_STYLE('',(#199780)); -#199780 = FILL_AREA_STYLE_COLOUR('',#195083); -#199781 = OVER_RIDING_STYLED_ITEM('overriding color',(#199782),#139548, - #195018); -#199782 = PRESENTATION_STYLE_ASSIGNMENT((#199783)); -#199783 = SURFACE_STYLE_USAGE(.BOTH.,#199784); -#199784 = SURFACE_SIDE_STYLE('',(#199785)); -#199785 = SURFACE_STYLE_FILL_AREA(#199786); -#199786 = FILL_AREA_STYLE('',(#199787)); -#199787 = FILL_AREA_STYLE_COLOUR('',#195083); -#199788 = OVER_RIDING_STYLED_ITEM('overriding color',(#199789),#139575, - #195018); -#199789 = PRESENTATION_STYLE_ASSIGNMENT((#199790)); -#199790 = SURFACE_STYLE_USAGE(.BOTH.,#199791); -#199791 = SURFACE_SIDE_STYLE('',(#199792)); -#199792 = SURFACE_STYLE_FILL_AREA(#199793); -#199793 = FILL_AREA_STYLE('',(#199794)); -#199794 = FILL_AREA_STYLE_COLOUR('',#195083); -#199795 = OVER_RIDING_STYLED_ITEM('overriding color',(#199796),#139630, - #195018); -#199796 = PRESENTATION_STYLE_ASSIGNMENT((#199797)); -#199797 = SURFACE_STYLE_USAGE(.BOTH.,#199798); -#199798 = SURFACE_SIDE_STYLE('',(#199799)); -#199799 = SURFACE_STYLE_FILL_AREA(#199800); -#199800 = FILL_AREA_STYLE('',(#199801)); -#199801 = FILL_AREA_STYLE_COLOUR('',#195083); -#199802 = OVER_RIDING_STYLED_ITEM('overriding color',(#199803),#139637, - #195018); -#199803 = PRESENTATION_STYLE_ASSIGNMENT((#199804)); -#199804 = SURFACE_STYLE_USAGE(.BOTH.,#199805); -#199805 = SURFACE_SIDE_STYLE('',(#199806)); -#199806 = SURFACE_STYLE_FILL_AREA(#199807); -#199807 = FILL_AREA_STYLE('',(#199808)); -#199808 = FILL_AREA_STYLE_COLOUR('',#195083); -#199809 = OVER_RIDING_STYLED_ITEM('overriding color',(#199810),#139644, - #195018); -#199810 = PRESENTATION_STYLE_ASSIGNMENT((#199811)); -#199811 = SURFACE_STYLE_USAGE(.BOTH.,#199812); -#199812 = SURFACE_SIDE_STYLE('',(#199813)); -#199813 = SURFACE_STYLE_FILL_AREA(#199814); -#199814 = FILL_AREA_STYLE('',(#199815)); -#199815 = FILL_AREA_STYLE_COLOUR('',#195083); -#199816 = OVER_RIDING_STYLED_ITEM('overriding color',(#199817),#139753, - #195018); -#199817 = PRESENTATION_STYLE_ASSIGNMENT((#199818)); -#199818 = SURFACE_STYLE_USAGE(.BOTH.,#199819); -#199819 = SURFACE_SIDE_STYLE('',(#199820)); -#199820 = SURFACE_STYLE_FILL_AREA(#199821); -#199821 = FILL_AREA_STYLE('',(#199822)); -#199822 = FILL_AREA_STYLE_COLOUR('',#195083); -#199823 = OVER_RIDING_STYLED_ITEM('overriding color',(#199824),#139857, - #195018); -#199824 = PRESENTATION_STYLE_ASSIGNMENT((#199825)); -#199825 = SURFACE_STYLE_USAGE(.BOTH.,#199826); -#199826 = SURFACE_SIDE_STYLE('',(#199827)); -#199827 = SURFACE_STYLE_FILL_AREA(#199828); -#199828 = FILL_AREA_STYLE('',(#199829)); -#199829 = FILL_AREA_STYLE_COLOUR('',#195083); -#199830 = OVER_RIDING_STYLED_ITEM('overriding color',(#199831),#139936, - #195018); -#199831 = PRESENTATION_STYLE_ASSIGNMENT((#199832)); -#199832 = SURFACE_STYLE_USAGE(.BOTH.,#199833); -#199833 = SURFACE_SIDE_STYLE('',(#199834)); -#199834 = SURFACE_STYLE_FILL_AREA(#199835); -#199835 = FILL_AREA_STYLE('',(#199836)); -#199836 = FILL_AREA_STYLE_COLOUR('',#195083); -#199837 = OVER_RIDING_STYLED_ITEM('overriding color',(#199838),#140061, - #195018); -#199838 = PRESENTATION_STYLE_ASSIGNMENT((#199839)); -#199839 = SURFACE_STYLE_USAGE(.BOTH.,#199840); -#199840 = SURFACE_SIDE_STYLE('',(#199841)); -#199841 = SURFACE_STYLE_FILL_AREA(#199842); -#199842 = FILL_AREA_STYLE('',(#199843)); -#199843 = FILL_AREA_STYLE_COLOUR('',#195083); -#199844 = OVER_RIDING_STYLED_ITEM('overriding color',(#199845),#140136, - #195018); -#199845 = PRESENTATION_STYLE_ASSIGNMENT((#199846)); -#199846 = SURFACE_STYLE_USAGE(.BOTH.,#199847); -#199847 = SURFACE_SIDE_STYLE('',(#199848)); -#199848 = SURFACE_STYLE_FILL_AREA(#199849); -#199849 = FILL_AREA_STYLE('',(#199850)); -#199850 = FILL_AREA_STYLE_COLOUR('',#195083); -#199851 = OVER_RIDING_STYLED_ITEM('overriding color',(#199852),#140211, - #195018); -#199852 = PRESENTATION_STYLE_ASSIGNMENT((#199853)); -#199853 = SURFACE_STYLE_USAGE(.BOTH.,#199854); -#199854 = SURFACE_SIDE_STYLE('',(#199855)); -#199855 = SURFACE_STYLE_FILL_AREA(#199856); -#199856 = FILL_AREA_STYLE('',(#199857)); -#199857 = FILL_AREA_STYLE_COLOUR('',#195083); -#199858 = OVER_RIDING_STYLED_ITEM('overriding color',(#199859),#140285, - #195018); -#199859 = PRESENTATION_STYLE_ASSIGNMENT((#199860)); -#199860 = SURFACE_STYLE_USAGE(.BOTH.,#199861); -#199861 = SURFACE_SIDE_STYLE('',(#199862)); -#199862 = SURFACE_STYLE_FILL_AREA(#199863); -#199863 = FILL_AREA_STYLE('',(#199864)); -#199864 = FILL_AREA_STYLE_COLOUR('',#195083); -#199865 = OVER_RIDING_STYLED_ITEM('overriding color',(#199866),#140405, - #195018); -#199866 = PRESENTATION_STYLE_ASSIGNMENT((#199867)); -#199867 = SURFACE_STYLE_USAGE(.BOTH.,#199868); -#199868 = SURFACE_SIDE_STYLE('',(#199869)); -#199869 = SURFACE_STYLE_FILL_AREA(#199870); -#199870 = FILL_AREA_STYLE('',(#199871)); -#199871 = FILL_AREA_STYLE_COLOUR('',#195083); -#199872 = OVER_RIDING_STYLED_ITEM('overriding color',(#199873),#140480, - #195018); -#199873 = PRESENTATION_STYLE_ASSIGNMENT((#199874)); -#199874 = SURFACE_STYLE_USAGE(.BOTH.,#199875); -#199875 = SURFACE_SIDE_STYLE('',(#199876)); -#199876 = SURFACE_STYLE_FILL_AREA(#199877); -#199877 = FILL_AREA_STYLE('',(#199878)); -#199878 = FILL_AREA_STYLE_COLOUR('',#195083); -#199879 = OVER_RIDING_STYLED_ITEM('overriding color',(#199880),#140507, - #195018); -#199880 = PRESENTATION_STYLE_ASSIGNMENT((#199881)); -#199881 = SURFACE_STYLE_USAGE(.BOTH.,#199882); -#199882 = SURFACE_SIDE_STYLE('',(#199883)); -#199883 = SURFACE_STYLE_FILL_AREA(#199884); -#199884 = FILL_AREA_STYLE('',(#199885)); -#199885 = FILL_AREA_STYLE_COLOUR('',#195083); -#199886 = OVER_RIDING_STYLED_ITEM('overriding color',(#199887),#140562, - #195018); -#199887 = PRESENTATION_STYLE_ASSIGNMENT((#199888)); -#199888 = SURFACE_STYLE_USAGE(.BOTH.,#199889); -#199889 = SURFACE_SIDE_STYLE('',(#199890)); -#199890 = SURFACE_STYLE_FILL_AREA(#199891); -#199891 = FILL_AREA_STYLE('',(#199892)); -#199892 = FILL_AREA_STYLE_COLOUR('',#195083); -#199893 = OVER_RIDING_STYLED_ITEM('overriding color',(#199894),#140569, - #195018); -#199894 = PRESENTATION_STYLE_ASSIGNMENT((#199895)); -#199895 = SURFACE_STYLE_USAGE(.BOTH.,#199896); -#199896 = SURFACE_SIDE_STYLE('',(#199897)); -#199897 = SURFACE_STYLE_FILL_AREA(#199898); -#199898 = FILL_AREA_STYLE('',(#199899)); -#199899 = FILL_AREA_STYLE_COLOUR('',#195083); -#199900 = OVER_RIDING_STYLED_ITEM('overriding color',(#199901),#140576, - #195018); -#199901 = PRESENTATION_STYLE_ASSIGNMENT((#199902)); -#199902 = SURFACE_STYLE_USAGE(.BOTH.,#199903); -#199903 = SURFACE_SIDE_STYLE('',(#199904)); -#199904 = SURFACE_STYLE_FILL_AREA(#199905); -#199905 = FILL_AREA_STYLE('',(#199906)); -#199906 = FILL_AREA_STYLE_COLOUR('',#195083); -#199907 = OVER_RIDING_STYLED_ITEM('overriding color',(#199908),#140685, - #195018); -#199908 = PRESENTATION_STYLE_ASSIGNMENT((#199909)); -#199909 = SURFACE_STYLE_USAGE(.BOTH.,#199910); -#199910 = SURFACE_SIDE_STYLE('',(#199911)); -#199911 = SURFACE_STYLE_FILL_AREA(#199912); -#199912 = FILL_AREA_STYLE('',(#199913)); -#199913 = FILL_AREA_STYLE_COLOUR('',#195083); -#199914 = OVER_RIDING_STYLED_ITEM('overriding color',(#199915),#140789, - #195018); -#199915 = PRESENTATION_STYLE_ASSIGNMENT((#199916)); -#199916 = SURFACE_STYLE_USAGE(.BOTH.,#199917); -#199917 = SURFACE_SIDE_STYLE('',(#199918)); -#199918 = SURFACE_STYLE_FILL_AREA(#199919); -#199919 = FILL_AREA_STYLE('',(#199920)); -#199920 = FILL_AREA_STYLE_COLOUR('',#195083); -#199921 = OVER_RIDING_STYLED_ITEM('overriding color',(#199922),#140868, - #195018); -#199922 = PRESENTATION_STYLE_ASSIGNMENT((#199923)); -#199923 = SURFACE_STYLE_USAGE(.BOTH.,#199924); -#199924 = SURFACE_SIDE_STYLE('',(#199925)); -#199925 = SURFACE_STYLE_FILL_AREA(#199926); -#199926 = FILL_AREA_STYLE('',(#199927)); -#199927 = FILL_AREA_STYLE_COLOUR('',#195083); -#199928 = OVER_RIDING_STYLED_ITEM('overriding color',(#199929),#140993, - #195018); -#199929 = PRESENTATION_STYLE_ASSIGNMENT((#199930)); -#199930 = SURFACE_STYLE_USAGE(.BOTH.,#199931); -#199931 = SURFACE_SIDE_STYLE('',(#199932)); -#199932 = SURFACE_STYLE_FILL_AREA(#199933); -#199933 = FILL_AREA_STYLE('',(#199934)); -#199934 = FILL_AREA_STYLE_COLOUR('',#195083); -#199935 = OVER_RIDING_STYLED_ITEM('overriding color',(#199936),#141068, - #195018); -#199936 = PRESENTATION_STYLE_ASSIGNMENT((#199937)); -#199937 = SURFACE_STYLE_USAGE(.BOTH.,#199938); -#199938 = SURFACE_SIDE_STYLE('',(#199939)); -#199939 = SURFACE_STYLE_FILL_AREA(#199940); -#199940 = FILL_AREA_STYLE('',(#199941)); -#199941 = FILL_AREA_STYLE_COLOUR('',#195083); -#199942 = OVER_RIDING_STYLED_ITEM('overriding color',(#199943),#141143, - #195018); -#199943 = PRESENTATION_STYLE_ASSIGNMENT((#199944)); -#199944 = SURFACE_STYLE_USAGE(.BOTH.,#199945); -#199945 = SURFACE_SIDE_STYLE('',(#199946)); -#199946 = SURFACE_STYLE_FILL_AREA(#199947); -#199947 = FILL_AREA_STYLE('',(#199948)); -#199948 = FILL_AREA_STYLE_COLOUR('',#195083); -#199949 = OVER_RIDING_STYLED_ITEM('overriding color',(#199950),#141217, - #195018); -#199950 = PRESENTATION_STYLE_ASSIGNMENT((#199951)); -#199951 = SURFACE_STYLE_USAGE(.BOTH.,#199952); -#199952 = SURFACE_SIDE_STYLE('',(#199953)); -#199953 = SURFACE_STYLE_FILL_AREA(#199954); -#199954 = FILL_AREA_STYLE('',(#199955)); -#199955 = FILL_AREA_STYLE_COLOUR('',#195083); -#199956 = OVER_RIDING_STYLED_ITEM('overriding color',(#199957),#141337, - #195018); -#199957 = PRESENTATION_STYLE_ASSIGNMENT((#199958)); -#199958 = SURFACE_STYLE_USAGE(.BOTH.,#199959); -#199959 = SURFACE_SIDE_STYLE('',(#199960)); -#199960 = SURFACE_STYLE_FILL_AREA(#199961); -#199961 = FILL_AREA_STYLE('',(#199962)); -#199962 = FILL_AREA_STYLE_COLOUR('',#195083); -#199963 = OVER_RIDING_STYLED_ITEM('overriding color',(#199964),#141412, - #195018); -#199964 = PRESENTATION_STYLE_ASSIGNMENT((#199965)); -#199965 = SURFACE_STYLE_USAGE(.BOTH.,#199966); -#199966 = SURFACE_SIDE_STYLE('',(#199967)); -#199967 = SURFACE_STYLE_FILL_AREA(#199968); -#199968 = FILL_AREA_STYLE('',(#199969)); -#199969 = FILL_AREA_STYLE_COLOUR('',#195083); -#199970 = OVER_RIDING_STYLED_ITEM('overriding color',(#199971),#141439, - #195018); -#199971 = PRESENTATION_STYLE_ASSIGNMENT((#199972)); -#199972 = SURFACE_STYLE_USAGE(.BOTH.,#199973); -#199973 = SURFACE_SIDE_STYLE('',(#199974)); -#199974 = SURFACE_STYLE_FILL_AREA(#199975); -#199975 = FILL_AREA_STYLE('',(#199976)); -#199976 = FILL_AREA_STYLE_COLOUR('',#195083); -#199977 = OVER_RIDING_STYLED_ITEM('overriding color',(#199978),#141494, - #195018); -#199978 = PRESENTATION_STYLE_ASSIGNMENT((#199979)); -#199979 = SURFACE_STYLE_USAGE(.BOTH.,#199980); -#199980 = SURFACE_SIDE_STYLE('',(#199981)); -#199981 = SURFACE_STYLE_FILL_AREA(#199982); -#199982 = FILL_AREA_STYLE('',(#199983)); -#199983 = FILL_AREA_STYLE_COLOUR('',#195083); -#199984 = OVER_RIDING_STYLED_ITEM('overriding color',(#199985),#141501, - #195018); -#199985 = PRESENTATION_STYLE_ASSIGNMENT((#199986)); -#199986 = SURFACE_STYLE_USAGE(.BOTH.,#199987); -#199987 = SURFACE_SIDE_STYLE('',(#199988)); -#199988 = SURFACE_STYLE_FILL_AREA(#199989); -#199989 = FILL_AREA_STYLE('',(#199990)); -#199990 = FILL_AREA_STYLE_COLOUR('',#195083); -#199991 = OVER_RIDING_STYLED_ITEM('overriding color',(#199992),#141508, - #195018); -#199992 = PRESENTATION_STYLE_ASSIGNMENT((#199993)); -#199993 = SURFACE_STYLE_USAGE(.BOTH.,#199994); -#199994 = SURFACE_SIDE_STYLE('',(#199995)); -#199995 = SURFACE_STYLE_FILL_AREA(#199996); -#199996 = FILL_AREA_STYLE('',(#199997)); -#199997 = FILL_AREA_STYLE_COLOUR('',#195083); -#199998 = OVER_RIDING_STYLED_ITEM('overriding color',(#199999),#141617, - #195018); -#199999 = PRESENTATION_STYLE_ASSIGNMENT((#200000)); -#200000 = SURFACE_STYLE_USAGE(.BOTH.,#200001); -#200001 = SURFACE_SIDE_STYLE('',(#200002)); -#200002 = SURFACE_STYLE_FILL_AREA(#200003); -#200003 = FILL_AREA_STYLE('',(#200004)); -#200004 = FILL_AREA_STYLE_COLOUR('',#195083); -#200005 = OVER_RIDING_STYLED_ITEM('overriding color',(#200006),#141721, - #195018); -#200006 = PRESENTATION_STYLE_ASSIGNMENT((#200007)); -#200007 = SURFACE_STYLE_USAGE(.BOTH.,#200008); -#200008 = SURFACE_SIDE_STYLE('',(#200009)); -#200009 = SURFACE_STYLE_FILL_AREA(#200010); -#200010 = FILL_AREA_STYLE('',(#200011)); -#200011 = FILL_AREA_STYLE_COLOUR('',#195083); -#200012 = OVER_RIDING_STYLED_ITEM('overriding color',(#200013),#141800, - #195018); -#200013 = PRESENTATION_STYLE_ASSIGNMENT((#200014)); -#200014 = SURFACE_STYLE_USAGE(.BOTH.,#200015); -#200015 = SURFACE_SIDE_STYLE('',(#200016)); -#200016 = SURFACE_STYLE_FILL_AREA(#200017); -#200017 = FILL_AREA_STYLE('',(#200018)); -#200018 = FILL_AREA_STYLE_COLOUR('',#195083); -#200019 = OVER_RIDING_STYLED_ITEM('overriding color',(#200020),#141925, - #195018); -#200020 = PRESENTATION_STYLE_ASSIGNMENT((#200021)); -#200021 = SURFACE_STYLE_USAGE(.BOTH.,#200022); -#200022 = SURFACE_SIDE_STYLE('',(#200023)); -#200023 = SURFACE_STYLE_FILL_AREA(#200024); -#200024 = FILL_AREA_STYLE('',(#200025)); -#200025 = FILL_AREA_STYLE_COLOUR('',#195083); -#200026 = OVER_RIDING_STYLED_ITEM('overriding color',(#200027),#142000, - #195018); -#200027 = PRESENTATION_STYLE_ASSIGNMENT((#200028)); -#200028 = SURFACE_STYLE_USAGE(.BOTH.,#200029); -#200029 = SURFACE_SIDE_STYLE('',(#200030)); -#200030 = SURFACE_STYLE_FILL_AREA(#200031); -#200031 = FILL_AREA_STYLE('',(#200032)); -#200032 = FILL_AREA_STYLE_COLOUR('',#195083); -#200033 = OVER_RIDING_STYLED_ITEM('overriding color',(#200034),#142075, - #195018); -#200034 = PRESENTATION_STYLE_ASSIGNMENT((#200035)); -#200035 = SURFACE_STYLE_USAGE(.BOTH.,#200036); -#200036 = SURFACE_SIDE_STYLE('',(#200037)); -#200037 = SURFACE_STYLE_FILL_AREA(#200038); -#200038 = FILL_AREA_STYLE('',(#200039)); -#200039 = FILL_AREA_STYLE_COLOUR('',#195083); -#200040 = OVER_RIDING_STYLED_ITEM('overriding color',(#200041),#142149, - #195018); -#200041 = PRESENTATION_STYLE_ASSIGNMENT((#200042)); -#200042 = SURFACE_STYLE_USAGE(.BOTH.,#200043); -#200043 = SURFACE_SIDE_STYLE('',(#200044)); -#200044 = SURFACE_STYLE_FILL_AREA(#200045); -#200045 = FILL_AREA_STYLE('',(#200046)); -#200046 = FILL_AREA_STYLE_COLOUR('',#195083); -#200047 = OVER_RIDING_STYLED_ITEM('overriding color',(#200048),#142269, - #195018); -#200048 = PRESENTATION_STYLE_ASSIGNMENT((#200049)); -#200049 = SURFACE_STYLE_USAGE(.BOTH.,#200050); -#200050 = SURFACE_SIDE_STYLE('',(#200051)); -#200051 = SURFACE_STYLE_FILL_AREA(#200052); -#200052 = FILL_AREA_STYLE('',(#200053)); -#200053 = FILL_AREA_STYLE_COLOUR('',#195083); -#200054 = OVER_RIDING_STYLED_ITEM('overriding color',(#200055),#142344, - #195018); -#200055 = PRESENTATION_STYLE_ASSIGNMENT((#200056)); -#200056 = SURFACE_STYLE_USAGE(.BOTH.,#200057); -#200057 = SURFACE_SIDE_STYLE('',(#200058)); -#200058 = SURFACE_STYLE_FILL_AREA(#200059); -#200059 = FILL_AREA_STYLE('',(#200060)); -#200060 = FILL_AREA_STYLE_COLOUR('',#195083); -#200061 = OVER_RIDING_STYLED_ITEM('overriding color',(#200062),#142371, - #195018); -#200062 = PRESENTATION_STYLE_ASSIGNMENT((#200063)); -#200063 = SURFACE_STYLE_USAGE(.BOTH.,#200064); -#200064 = SURFACE_SIDE_STYLE('',(#200065)); -#200065 = SURFACE_STYLE_FILL_AREA(#200066); -#200066 = FILL_AREA_STYLE('',(#200067)); -#200067 = FILL_AREA_STYLE_COLOUR('',#195083); -#200068 = OVER_RIDING_STYLED_ITEM('overriding color',(#200069),#142426, - #195018); -#200069 = PRESENTATION_STYLE_ASSIGNMENT((#200070)); -#200070 = SURFACE_STYLE_USAGE(.BOTH.,#200071); -#200071 = SURFACE_SIDE_STYLE('',(#200072)); -#200072 = SURFACE_STYLE_FILL_AREA(#200073); -#200073 = FILL_AREA_STYLE('',(#200074)); -#200074 = FILL_AREA_STYLE_COLOUR('',#195083); -#200075 = OVER_RIDING_STYLED_ITEM('overriding color',(#200076),#142433, - #195018); -#200076 = PRESENTATION_STYLE_ASSIGNMENT((#200077)); -#200077 = SURFACE_STYLE_USAGE(.BOTH.,#200078); -#200078 = SURFACE_SIDE_STYLE('',(#200079)); -#200079 = SURFACE_STYLE_FILL_AREA(#200080); -#200080 = FILL_AREA_STYLE('',(#200081)); -#200081 = FILL_AREA_STYLE_COLOUR('',#195083); -#200082 = OVER_RIDING_STYLED_ITEM('overriding color',(#200083),#142440, - #195018); -#200083 = PRESENTATION_STYLE_ASSIGNMENT((#200084)); -#200084 = SURFACE_STYLE_USAGE(.BOTH.,#200085); -#200085 = SURFACE_SIDE_STYLE('',(#200086)); -#200086 = SURFACE_STYLE_FILL_AREA(#200087); -#200087 = FILL_AREA_STYLE('',(#200088)); -#200088 = FILL_AREA_STYLE_COLOUR('',#195083); -#200089 = OVER_RIDING_STYLED_ITEM('overriding color',(#200090),#142549, - #195018); -#200090 = PRESENTATION_STYLE_ASSIGNMENT((#200091)); -#200091 = SURFACE_STYLE_USAGE(.BOTH.,#200092); -#200092 = SURFACE_SIDE_STYLE('',(#200093)); -#200093 = SURFACE_STYLE_FILL_AREA(#200094); -#200094 = FILL_AREA_STYLE('',(#200095)); -#200095 = FILL_AREA_STYLE_COLOUR('',#195083); -#200096 = OVER_RIDING_STYLED_ITEM('overriding color',(#200097),#142653, - #195018); -#200097 = PRESENTATION_STYLE_ASSIGNMENT((#200098)); -#200098 = SURFACE_STYLE_USAGE(.BOTH.,#200099); -#200099 = SURFACE_SIDE_STYLE('',(#200100)); -#200100 = SURFACE_STYLE_FILL_AREA(#200101); -#200101 = FILL_AREA_STYLE('',(#200102)); -#200102 = FILL_AREA_STYLE_COLOUR('',#195083); -#200103 = OVER_RIDING_STYLED_ITEM('overriding color',(#200104),#142732, - #195018); -#200104 = PRESENTATION_STYLE_ASSIGNMENT((#200105)); -#200105 = SURFACE_STYLE_USAGE(.BOTH.,#200106); -#200106 = SURFACE_SIDE_STYLE('',(#200107)); -#200107 = SURFACE_STYLE_FILL_AREA(#200108); -#200108 = FILL_AREA_STYLE('',(#200109)); -#200109 = FILL_AREA_STYLE_COLOUR('',#195083); -#200110 = OVER_RIDING_STYLED_ITEM('overriding color',(#200111),#142857, - #195018); -#200111 = PRESENTATION_STYLE_ASSIGNMENT((#200112)); -#200112 = SURFACE_STYLE_USAGE(.BOTH.,#200113); -#200113 = SURFACE_SIDE_STYLE('',(#200114)); -#200114 = SURFACE_STYLE_FILL_AREA(#200115); -#200115 = FILL_AREA_STYLE('',(#200116)); -#200116 = FILL_AREA_STYLE_COLOUR('',#195083); -#200117 = OVER_RIDING_STYLED_ITEM('overriding color',(#200118),#142932, - #195018); -#200118 = PRESENTATION_STYLE_ASSIGNMENT((#200119)); -#200119 = SURFACE_STYLE_USAGE(.BOTH.,#200120); -#200120 = SURFACE_SIDE_STYLE('',(#200121)); -#200121 = SURFACE_STYLE_FILL_AREA(#200122); -#200122 = FILL_AREA_STYLE('',(#200123)); -#200123 = FILL_AREA_STYLE_COLOUR('',#195083); -#200124 = OVER_RIDING_STYLED_ITEM('overriding color',(#200125),#143007, - #195018); -#200125 = PRESENTATION_STYLE_ASSIGNMENT((#200126)); -#200126 = SURFACE_STYLE_USAGE(.BOTH.,#200127); -#200127 = SURFACE_SIDE_STYLE('',(#200128)); -#200128 = SURFACE_STYLE_FILL_AREA(#200129); -#200129 = FILL_AREA_STYLE('',(#200130)); -#200130 = FILL_AREA_STYLE_COLOUR('',#195083); -#200131 = OVER_RIDING_STYLED_ITEM('overriding color',(#200132),#143081, - #195018); -#200132 = PRESENTATION_STYLE_ASSIGNMENT((#200133)); -#200133 = SURFACE_STYLE_USAGE(.BOTH.,#200134); -#200134 = SURFACE_SIDE_STYLE('',(#200135)); -#200135 = SURFACE_STYLE_FILL_AREA(#200136); -#200136 = FILL_AREA_STYLE('',(#200137)); -#200137 = FILL_AREA_STYLE_COLOUR('',#195083); -#200138 = OVER_RIDING_STYLED_ITEM('overriding color',(#200139),#143201, - #195018); -#200139 = PRESENTATION_STYLE_ASSIGNMENT((#200140)); -#200140 = SURFACE_STYLE_USAGE(.BOTH.,#200141); -#200141 = SURFACE_SIDE_STYLE('',(#200142)); -#200142 = SURFACE_STYLE_FILL_AREA(#200143); -#200143 = FILL_AREA_STYLE('',(#200144)); -#200144 = FILL_AREA_STYLE_COLOUR('',#195083); -#200145 = OVER_RIDING_STYLED_ITEM('overriding color',(#200146),#143276, - #195018); -#200146 = PRESENTATION_STYLE_ASSIGNMENT((#200147)); -#200147 = SURFACE_STYLE_USAGE(.BOTH.,#200148); -#200148 = SURFACE_SIDE_STYLE('',(#200149)); -#200149 = SURFACE_STYLE_FILL_AREA(#200150); -#200150 = FILL_AREA_STYLE('',(#200151)); -#200151 = FILL_AREA_STYLE_COLOUR('',#195083); -#200152 = OVER_RIDING_STYLED_ITEM('overriding color',(#200153),#143303, - #195018); -#200153 = PRESENTATION_STYLE_ASSIGNMENT((#200154)); -#200154 = SURFACE_STYLE_USAGE(.BOTH.,#200155); -#200155 = SURFACE_SIDE_STYLE('',(#200156)); -#200156 = SURFACE_STYLE_FILL_AREA(#200157); -#200157 = FILL_AREA_STYLE('',(#200158)); -#200158 = FILL_AREA_STYLE_COLOUR('',#195083); -#200159 = OVER_RIDING_STYLED_ITEM('overriding color',(#200160),#143358, - #195018); -#200160 = PRESENTATION_STYLE_ASSIGNMENT((#200161)); -#200161 = SURFACE_STYLE_USAGE(.BOTH.,#200162); -#200162 = SURFACE_SIDE_STYLE('',(#200163)); -#200163 = SURFACE_STYLE_FILL_AREA(#200164); -#200164 = FILL_AREA_STYLE('',(#200165)); -#200165 = FILL_AREA_STYLE_COLOUR('',#195083); -#200166 = OVER_RIDING_STYLED_ITEM('overriding color',(#200167),#143365, - #195018); -#200167 = PRESENTATION_STYLE_ASSIGNMENT((#200168)); -#200168 = SURFACE_STYLE_USAGE(.BOTH.,#200169); -#200169 = SURFACE_SIDE_STYLE('',(#200170)); -#200170 = SURFACE_STYLE_FILL_AREA(#200171); -#200171 = FILL_AREA_STYLE('',(#200172)); -#200172 = FILL_AREA_STYLE_COLOUR('',#195083); -#200173 = OVER_RIDING_STYLED_ITEM('overriding color',(#200174),#143372, - #195018); -#200174 = PRESENTATION_STYLE_ASSIGNMENT((#200175)); -#200175 = SURFACE_STYLE_USAGE(.BOTH.,#200176); -#200176 = SURFACE_SIDE_STYLE('',(#200177)); -#200177 = SURFACE_STYLE_FILL_AREA(#200178); -#200178 = FILL_AREA_STYLE('',(#200179)); -#200179 = FILL_AREA_STYLE_COLOUR('',#195083); -#200180 = OVER_RIDING_STYLED_ITEM('overriding color',(#200181),#143481, - #195018); -#200181 = PRESENTATION_STYLE_ASSIGNMENT((#200182)); -#200182 = SURFACE_STYLE_USAGE(.BOTH.,#200183); -#200183 = SURFACE_SIDE_STYLE('',(#200184)); -#200184 = SURFACE_STYLE_FILL_AREA(#200185); -#200185 = FILL_AREA_STYLE('',(#200186)); -#200186 = FILL_AREA_STYLE_COLOUR('',#195083); -#200187 = OVER_RIDING_STYLED_ITEM('overriding color',(#200188),#143585, - #195018); -#200188 = PRESENTATION_STYLE_ASSIGNMENT((#200189)); -#200189 = SURFACE_STYLE_USAGE(.BOTH.,#200190); -#200190 = SURFACE_SIDE_STYLE('',(#200191)); -#200191 = SURFACE_STYLE_FILL_AREA(#200192); -#200192 = FILL_AREA_STYLE('',(#200193)); -#200193 = FILL_AREA_STYLE_COLOUR('',#195083); -#200194 = OVER_RIDING_STYLED_ITEM('overriding color',(#200195),#143664, - #195018); -#200195 = PRESENTATION_STYLE_ASSIGNMENT((#200196)); -#200196 = SURFACE_STYLE_USAGE(.BOTH.,#200197); -#200197 = SURFACE_SIDE_STYLE('',(#200198)); -#200198 = SURFACE_STYLE_FILL_AREA(#200199); -#200199 = FILL_AREA_STYLE('',(#200200)); -#200200 = FILL_AREA_STYLE_COLOUR('',#195083); -#200201 = OVER_RIDING_STYLED_ITEM('overriding color',(#200202),#143789, - #195018); -#200202 = PRESENTATION_STYLE_ASSIGNMENT((#200203)); -#200203 = SURFACE_STYLE_USAGE(.BOTH.,#200204); -#200204 = SURFACE_SIDE_STYLE('',(#200205)); -#200205 = SURFACE_STYLE_FILL_AREA(#200206); -#200206 = FILL_AREA_STYLE('',(#200207)); -#200207 = FILL_AREA_STYLE_COLOUR('',#195083); -#200208 = OVER_RIDING_STYLED_ITEM('overriding color',(#200209),#143864, - #195018); -#200209 = PRESENTATION_STYLE_ASSIGNMENT((#200210)); -#200210 = SURFACE_STYLE_USAGE(.BOTH.,#200211); -#200211 = SURFACE_SIDE_STYLE('',(#200212)); -#200212 = SURFACE_STYLE_FILL_AREA(#200213); -#200213 = FILL_AREA_STYLE('',(#200214)); -#200214 = FILL_AREA_STYLE_COLOUR('',#195083); -#200215 = OVER_RIDING_STYLED_ITEM('overriding color',(#200216),#143939, - #195018); -#200216 = PRESENTATION_STYLE_ASSIGNMENT((#200217)); -#200217 = SURFACE_STYLE_USAGE(.BOTH.,#200218); -#200218 = SURFACE_SIDE_STYLE('',(#200219)); -#200219 = SURFACE_STYLE_FILL_AREA(#200220); -#200220 = FILL_AREA_STYLE('',(#200221)); -#200221 = FILL_AREA_STYLE_COLOUR('',#195083); -#200222 = OVER_RIDING_STYLED_ITEM('overriding color',(#200223),#144013, - #195018); -#200223 = PRESENTATION_STYLE_ASSIGNMENT((#200224)); -#200224 = SURFACE_STYLE_USAGE(.BOTH.,#200225); -#200225 = SURFACE_SIDE_STYLE('',(#200226)); -#200226 = SURFACE_STYLE_FILL_AREA(#200227); -#200227 = FILL_AREA_STYLE('',(#200228)); -#200228 = FILL_AREA_STYLE_COLOUR('',#195083); -#200229 = OVER_RIDING_STYLED_ITEM('overriding color',(#200230),#144133, - #195018); -#200230 = PRESENTATION_STYLE_ASSIGNMENT((#200231)); -#200231 = SURFACE_STYLE_USAGE(.BOTH.,#200232); -#200232 = SURFACE_SIDE_STYLE('',(#200233)); -#200233 = SURFACE_STYLE_FILL_AREA(#200234); -#200234 = FILL_AREA_STYLE('',(#200235)); -#200235 = FILL_AREA_STYLE_COLOUR('',#195083); -#200236 = OVER_RIDING_STYLED_ITEM('overriding color',(#200237),#144208, - #195018); -#200237 = PRESENTATION_STYLE_ASSIGNMENT((#200238)); -#200238 = SURFACE_STYLE_USAGE(.BOTH.,#200239); -#200239 = SURFACE_SIDE_STYLE('',(#200240)); -#200240 = SURFACE_STYLE_FILL_AREA(#200241); -#200241 = FILL_AREA_STYLE('',(#200242)); -#200242 = FILL_AREA_STYLE_COLOUR('',#195083); -#200243 = OVER_RIDING_STYLED_ITEM('overriding color',(#200244),#144235, - #195018); -#200244 = PRESENTATION_STYLE_ASSIGNMENT((#200245)); -#200245 = SURFACE_STYLE_USAGE(.BOTH.,#200246); -#200246 = SURFACE_SIDE_STYLE('',(#200247)); -#200247 = SURFACE_STYLE_FILL_AREA(#200248); -#200248 = FILL_AREA_STYLE('',(#200249)); -#200249 = FILL_AREA_STYLE_COLOUR('',#195083); -#200250 = OVER_RIDING_STYLED_ITEM('overriding color',(#200251),#144290, - #195018); -#200251 = PRESENTATION_STYLE_ASSIGNMENT((#200252)); -#200252 = SURFACE_STYLE_USAGE(.BOTH.,#200253); -#200253 = SURFACE_SIDE_STYLE('',(#200254)); -#200254 = SURFACE_STYLE_FILL_AREA(#200255); -#200255 = FILL_AREA_STYLE('',(#200256)); -#200256 = FILL_AREA_STYLE_COLOUR('',#195083); -#200257 = OVER_RIDING_STYLED_ITEM('overriding color',(#200258),#144297, - #195018); -#200258 = PRESENTATION_STYLE_ASSIGNMENT((#200259)); -#200259 = SURFACE_STYLE_USAGE(.BOTH.,#200260); -#200260 = SURFACE_SIDE_STYLE('',(#200261)); -#200261 = SURFACE_STYLE_FILL_AREA(#200262); -#200262 = FILL_AREA_STYLE('',(#200263)); -#200263 = FILL_AREA_STYLE_COLOUR('',#195083); -#200264 = OVER_RIDING_STYLED_ITEM('overriding color',(#200265),#144304, - #195018); -#200265 = PRESENTATION_STYLE_ASSIGNMENT((#200266)); -#200266 = SURFACE_STYLE_USAGE(.BOTH.,#200267); -#200267 = SURFACE_SIDE_STYLE('',(#200268)); -#200268 = SURFACE_STYLE_FILL_AREA(#200269); -#200269 = FILL_AREA_STYLE('',(#200270)); -#200270 = FILL_AREA_STYLE_COLOUR('',#195083); -#200271 = OVER_RIDING_STYLED_ITEM('overriding color',(#200272),#144413, - #195018); -#200272 = PRESENTATION_STYLE_ASSIGNMENT((#200273)); -#200273 = SURFACE_STYLE_USAGE(.BOTH.,#200274); -#200274 = SURFACE_SIDE_STYLE('',(#200275)); -#200275 = SURFACE_STYLE_FILL_AREA(#200276); -#200276 = FILL_AREA_STYLE('',(#200277)); -#200277 = FILL_AREA_STYLE_COLOUR('',#195083); -#200278 = OVER_RIDING_STYLED_ITEM('overriding color',(#200279),#144517, - #195018); -#200279 = PRESENTATION_STYLE_ASSIGNMENT((#200280)); -#200280 = SURFACE_STYLE_USAGE(.BOTH.,#200281); -#200281 = SURFACE_SIDE_STYLE('',(#200282)); -#200282 = SURFACE_STYLE_FILL_AREA(#200283); -#200283 = FILL_AREA_STYLE('',(#200284)); -#200284 = FILL_AREA_STYLE_COLOUR('',#195083); -#200285 = OVER_RIDING_STYLED_ITEM('overriding color',(#200286),#144642, - #195018); -#200286 = PRESENTATION_STYLE_ASSIGNMENT((#200287)); -#200287 = SURFACE_STYLE_USAGE(.BOTH.,#200288); -#200288 = SURFACE_SIDE_STYLE('',(#200289)); -#200289 = SURFACE_STYLE_FILL_AREA(#200290); -#200290 = FILL_AREA_STYLE('',(#200291)); -#200291 = FILL_AREA_STYLE_COLOUR('',#195083); -#200292 = OVER_RIDING_STYLED_ITEM('overriding color',(#200293),#144721, - #195018); -#200293 = PRESENTATION_STYLE_ASSIGNMENT((#200294)); -#200294 = SURFACE_STYLE_USAGE(.BOTH.,#200295); -#200295 = SURFACE_SIDE_STYLE('',(#200296)); -#200296 = SURFACE_STYLE_FILL_AREA(#200297); -#200297 = FILL_AREA_STYLE('',(#200298)); -#200298 = FILL_AREA_STYLE_COLOUR('',#195083); -#200299 = OVER_RIDING_STYLED_ITEM('overriding color',(#200300),#144796, - #195018); -#200300 = PRESENTATION_STYLE_ASSIGNMENT((#200301)); -#200301 = SURFACE_STYLE_USAGE(.BOTH.,#200302); -#200302 = SURFACE_SIDE_STYLE('',(#200303)); -#200303 = SURFACE_STYLE_FILL_AREA(#200304); -#200304 = FILL_AREA_STYLE('',(#200305)); -#200305 = FILL_AREA_STYLE_COLOUR('',#195083); -#200306 = OVER_RIDING_STYLED_ITEM('overriding color',(#200307),#144871, - #195018); -#200307 = PRESENTATION_STYLE_ASSIGNMENT((#200308)); -#200308 = SURFACE_STYLE_USAGE(.BOTH.,#200309); -#200309 = SURFACE_SIDE_STYLE('',(#200310)); -#200310 = SURFACE_STYLE_FILL_AREA(#200311); -#200311 = FILL_AREA_STYLE('',(#200312)); -#200312 = FILL_AREA_STYLE_COLOUR('',#195083); -#200313 = OVER_RIDING_STYLED_ITEM('overriding color',(#200314),#144991, - #195018); -#200314 = PRESENTATION_STYLE_ASSIGNMENT((#200315)); -#200315 = SURFACE_STYLE_USAGE(.BOTH.,#200316); -#200316 = SURFACE_SIDE_STYLE('',(#200317)); -#200317 = SURFACE_STYLE_FILL_AREA(#200318); -#200318 = FILL_AREA_STYLE('',(#200319)); -#200319 = FILL_AREA_STYLE_COLOUR('',#195083); -#200320 = OVER_RIDING_STYLED_ITEM('overriding color',(#200321),#145065, - #195018); -#200321 = PRESENTATION_STYLE_ASSIGNMENT((#200322)); -#200322 = SURFACE_STYLE_USAGE(.BOTH.,#200323); -#200323 = SURFACE_SIDE_STYLE('',(#200324)); -#200324 = SURFACE_STYLE_FILL_AREA(#200325); -#200325 = FILL_AREA_STYLE('',(#200326)); -#200326 = FILL_AREA_STYLE_COLOUR('',#195083); -#200327 = OVER_RIDING_STYLED_ITEM('overriding color',(#200328),#145140, - #195018); -#200328 = PRESENTATION_STYLE_ASSIGNMENT((#200329)); -#200329 = SURFACE_STYLE_USAGE(.BOTH.,#200330); -#200330 = SURFACE_SIDE_STYLE('',(#200331)); -#200331 = SURFACE_STYLE_FILL_AREA(#200332); -#200332 = FILL_AREA_STYLE('',(#200333)); -#200333 = FILL_AREA_STYLE_COLOUR('',#195083); -#200334 = OVER_RIDING_STYLED_ITEM('overriding color',(#200335),#145167, - #195018); -#200335 = PRESENTATION_STYLE_ASSIGNMENT((#200336)); -#200336 = SURFACE_STYLE_USAGE(.BOTH.,#200337); -#200337 = SURFACE_SIDE_STYLE('',(#200338)); -#200338 = SURFACE_STYLE_FILL_AREA(#200339); -#200339 = FILL_AREA_STYLE('',(#200340)); -#200340 = FILL_AREA_STYLE_COLOUR('',#195083); -#200341 = OVER_RIDING_STYLED_ITEM('overriding color',(#200342),#145222, - #195018); -#200342 = PRESENTATION_STYLE_ASSIGNMENT((#200343)); -#200343 = SURFACE_STYLE_USAGE(.BOTH.,#200344); -#200344 = SURFACE_SIDE_STYLE('',(#200345)); -#200345 = SURFACE_STYLE_FILL_AREA(#200346); -#200346 = FILL_AREA_STYLE('',(#200347)); -#200347 = FILL_AREA_STYLE_COLOUR('',#195083); -#200348 = OVER_RIDING_STYLED_ITEM('overriding color',(#200349),#145229, - #195018); -#200349 = PRESENTATION_STYLE_ASSIGNMENT((#200350)); -#200350 = SURFACE_STYLE_USAGE(.BOTH.,#200351); -#200351 = SURFACE_SIDE_STYLE('',(#200352)); -#200352 = SURFACE_STYLE_FILL_AREA(#200353); -#200353 = FILL_AREA_STYLE('',(#200354)); -#200354 = FILL_AREA_STYLE_COLOUR('',#195083); -#200355 = OVER_RIDING_STYLED_ITEM('overriding color',(#200356),#145236, - #195018); -#200356 = PRESENTATION_STYLE_ASSIGNMENT((#200357)); -#200357 = SURFACE_STYLE_USAGE(.BOTH.,#200358); -#200358 = SURFACE_SIDE_STYLE('',(#200359)); -#200359 = SURFACE_STYLE_FILL_AREA(#200360); -#200360 = FILL_AREA_STYLE('',(#200361)); -#200361 = FILL_AREA_STYLE_COLOUR('',#195083); -#200362 = OVER_RIDING_STYLED_ITEM('overriding color',(#200363),#145345, - #195018); -#200363 = PRESENTATION_STYLE_ASSIGNMENT((#200364)); -#200364 = SURFACE_STYLE_USAGE(.BOTH.,#200365); -#200365 = SURFACE_SIDE_STYLE('',(#200366)); -#200366 = SURFACE_STYLE_FILL_AREA(#200367); -#200367 = FILL_AREA_STYLE('',(#200368)); -#200368 = FILL_AREA_STYLE_COLOUR('',#195083); -#200369 = OVER_RIDING_STYLED_ITEM('overriding color',(#200370),#145449, - #195018); -#200370 = PRESENTATION_STYLE_ASSIGNMENT((#200371)); -#200371 = SURFACE_STYLE_USAGE(.BOTH.,#200372); -#200372 = SURFACE_SIDE_STYLE('',(#200373)); -#200373 = SURFACE_STYLE_FILL_AREA(#200374); -#200374 = FILL_AREA_STYLE('',(#200375)); -#200375 = FILL_AREA_STYLE_COLOUR('',#195083); -#200376 = OVER_RIDING_STYLED_ITEM('overriding color',(#200377),#145574, - #195018); -#200377 = PRESENTATION_STYLE_ASSIGNMENT((#200378)); -#200378 = SURFACE_STYLE_USAGE(.BOTH.,#200379); -#200379 = SURFACE_SIDE_STYLE('',(#200380)); -#200380 = SURFACE_STYLE_FILL_AREA(#200381); -#200381 = FILL_AREA_STYLE('',(#200382)); -#200382 = FILL_AREA_STYLE_COLOUR('',#195083); -#200383 = OVER_RIDING_STYLED_ITEM('overriding color',(#200384),#145653, - #195018); -#200384 = PRESENTATION_STYLE_ASSIGNMENT((#200385)); -#200385 = SURFACE_STYLE_USAGE(.BOTH.,#200386); -#200386 = SURFACE_SIDE_STYLE('',(#200387)); -#200387 = SURFACE_STYLE_FILL_AREA(#200388); -#200388 = FILL_AREA_STYLE('',(#200389)); -#200389 = FILL_AREA_STYLE_COLOUR('',#195083); -#200390 = OVER_RIDING_STYLED_ITEM('overriding color',(#200391),#145728, - #195018); -#200391 = PRESENTATION_STYLE_ASSIGNMENT((#200392)); -#200392 = SURFACE_STYLE_USAGE(.BOTH.,#200393); -#200393 = SURFACE_SIDE_STYLE('',(#200394)); -#200394 = SURFACE_STYLE_FILL_AREA(#200395); -#200395 = FILL_AREA_STYLE('',(#200396)); -#200396 = FILL_AREA_STYLE_COLOUR('',#195083); -#200397 = OVER_RIDING_STYLED_ITEM('overriding color',(#200398),#145803, - #195018); -#200398 = PRESENTATION_STYLE_ASSIGNMENT((#200399)); -#200399 = SURFACE_STYLE_USAGE(.BOTH.,#200400); -#200400 = SURFACE_SIDE_STYLE('',(#200401)); -#200401 = SURFACE_STYLE_FILL_AREA(#200402); -#200402 = FILL_AREA_STYLE('',(#200403)); -#200403 = FILL_AREA_STYLE_COLOUR('',#195083); -#200404 = OVER_RIDING_STYLED_ITEM('overriding color',(#200405),#145877, - #195018); -#200405 = PRESENTATION_STYLE_ASSIGNMENT((#200406)); -#200406 = SURFACE_STYLE_USAGE(.BOTH.,#200407); -#200407 = SURFACE_SIDE_STYLE('',(#200408)); -#200408 = SURFACE_STYLE_FILL_AREA(#200409); -#200409 = FILL_AREA_STYLE('',(#200410)); -#200410 = FILL_AREA_STYLE_COLOUR('',#195083); -#200411 = OVER_RIDING_STYLED_ITEM('overriding color',(#200412),#145951, - #195018); -#200412 = PRESENTATION_STYLE_ASSIGNMENT((#200413)); -#200413 = SURFACE_STYLE_USAGE(.BOTH.,#200414); -#200414 = SURFACE_SIDE_STYLE('',(#200415)); -#200415 = SURFACE_STYLE_FILL_AREA(#200416); -#200416 = FILL_AREA_STYLE('',(#200417)); -#200417 = FILL_AREA_STYLE_COLOUR('',#195083); -#200418 = OVER_RIDING_STYLED_ITEM('overriding color',(#200419),#146026, - #195018); -#200419 = PRESENTATION_STYLE_ASSIGNMENT((#200420)); -#200420 = SURFACE_STYLE_USAGE(.BOTH.,#200421); -#200421 = SURFACE_SIDE_STYLE('',(#200422)); -#200422 = SURFACE_STYLE_FILL_AREA(#200423); -#200423 = FILL_AREA_STYLE('',(#200424)); -#200424 = FILL_AREA_STYLE_COLOUR('',#195083); -#200425 = OVER_RIDING_STYLED_ITEM('overriding color',(#200426),#146053, - #195018); -#200426 = PRESENTATION_STYLE_ASSIGNMENT((#200427)); -#200427 = SURFACE_STYLE_USAGE(.BOTH.,#200428); -#200428 = SURFACE_SIDE_STYLE('',(#200429)); -#200429 = SURFACE_STYLE_FILL_AREA(#200430); -#200430 = FILL_AREA_STYLE('',(#200431)); -#200431 = FILL_AREA_STYLE_COLOUR('',#195083); -#200432 = OVER_RIDING_STYLED_ITEM('overriding color',(#200433),#146108, - #195018); -#200433 = PRESENTATION_STYLE_ASSIGNMENT((#200434)); -#200434 = SURFACE_STYLE_USAGE(.BOTH.,#200435); -#200435 = SURFACE_SIDE_STYLE('',(#200436)); -#200436 = SURFACE_STYLE_FILL_AREA(#200437); -#200437 = FILL_AREA_STYLE('',(#200438)); -#200438 = FILL_AREA_STYLE_COLOUR('',#195083); -#200439 = OVER_RIDING_STYLED_ITEM('overriding color',(#200440),#146115, - #195018); -#200440 = PRESENTATION_STYLE_ASSIGNMENT((#200441)); -#200441 = SURFACE_STYLE_USAGE(.BOTH.,#200442); -#200442 = SURFACE_SIDE_STYLE('',(#200443)); -#200443 = SURFACE_STYLE_FILL_AREA(#200444); -#200444 = FILL_AREA_STYLE('',(#200445)); -#200445 = FILL_AREA_STYLE_COLOUR('',#195083); -#200446 = OVER_RIDING_STYLED_ITEM('overriding color',(#200447),#146122, - #195018); -#200447 = PRESENTATION_STYLE_ASSIGNMENT((#200448)); -#200448 = SURFACE_STYLE_USAGE(.BOTH.,#200449); -#200449 = SURFACE_SIDE_STYLE('',(#200450)); -#200450 = SURFACE_STYLE_FILL_AREA(#200451); -#200451 = FILL_AREA_STYLE('',(#200452)); -#200452 = FILL_AREA_STYLE_COLOUR('',#195083); -#200453 = OVER_RIDING_STYLED_ITEM('overriding color',(#200454),#146231, - #195018); -#200454 = PRESENTATION_STYLE_ASSIGNMENT((#200455)); -#200455 = SURFACE_STYLE_USAGE(.BOTH.,#200456); -#200456 = SURFACE_SIDE_STYLE('',(#200457)); -#200457 = SURFACE_STYLE_FILL_AREA(#200458); -#200458 = FILL_AREA_STYLE('',(#200459)); -#200459 = FILL_AREA_STYLE_COLOUR('',#195083); -#200460 = OVER_RIDING_STYLED_ITEM('overriding color',(#200461),#146335, - #195018); -#200461 = PRESENTATION_STYLE_ASSIGNMENT((#200462)); -#200462 = SURFACE_STYLE_USAGE(.BOTH.,#200463); -#200463 = SURFACE_SIDE_STYLE('',(#200464)); -#200464 = SURFACE_STYLE_FILL_AREA(#200465); -#200465 = FILL_AREA_STYLE('',(#200466)); -#200466 = FILL_AREA_STYLE_COLOUR('',#195083); -#200467 = OVER_RIDING_STYLED_ITEM('overriding color',(#200468),#146460, - #195018); -#200468 = PRESENTATION_STYLE_ASSIGNMENT((#200469)); -#200469 = SURFACE_STYLE_USAGE(.BOTH.,#200470); -#200470 = SURFACE_SIDE_STYLE('',(#200471)); -#200471 = SURFACE_STYLE_FILL_AREA(#200472); -#200472 = FILL_AREA_STYLE('',(#200473)); -#200473 = FILL_AREA_STYLE_COLOUR('',#195083); -#200474 = OVER_RIDING_STYLED_ITEM('overriding color',(#200475),#146539, - #195018); -#200475 = PRESENTATION_STYLE_ASSIGNMENT((#200476)); -#200476 = SURFACE_STYLE_USAGE(.BOTH.,#200477); -#200477 = SURFACE_SIDE_STYLE('',(#200478)); -#200478 = SURFACE_STYLE_FILL_AREA(#200479); -#200479 = FILL_AREA_STYLE('',(#200480)); -#200480 = FILL_AREA_STYLE_COLOUR('',#195083); -#200481 = OVER_RIDING_STYLED_ITEM('overriding color',(#200482),#146614, - #195018); -#200482 = PRESENTATION_STYLE_ASSIGNMENT((#200483)); -#200483 = SURFACE_STYLE_USAGE(.BOTH.,#200484); -#200484 = SURFACE_SIDE_STYLE('',(#200485)); -#200485 = SURFACE_STYLE_FILL_AREA(#200486); -#200486 = FILL_AREA_STYLE('',(#200487)); -#200487 = FILL_AREA_STYLE_COLOUR('',#195083); -#200488 = OVER_RIDING_STYLED_ITEM('overriding color',(#200489),#146689, - #195018); -#200489 = PRESENTATION_STYLE_ASSIGNMENT((#200490)); -#200490 = SURFACE_STYLE_USAGE(.BOTH.,#200491); -#200491 = SURFACE_SIDE_STYLE('',(#200492)); -#200492 = SURFACE_STYLE_FILL_AREA(#200493); -#200493 = FILL_AREA_STYLE('',(#200494)); -#200494 = FILL_AREA_STYLE_COLOUR('',#195083); -#200495 = OVER_RIDING_STYLED_ITEM('overriding color',(#200496),#146763, - #195018); -#200496 = PRESENTATION_STYLE_ASSIGNMENT((#200497)); -#200497 = SURFACE_STYLE_USAGE(.BOTH.,#200498); -#200498 = SURFACE_SIDE_STYLE('',(#200499)); -#200499 = SURFACE_STYLE_FILL_AREA(#200500); -#200500 = FILL_AREA_STYLE('',(#200501)); -#200501 = FILL_AREA_STYLE_COLOUR('',#195083); -#200502 = OVER_RIDING_STYLED_ITEM('overriding color',(#200503),#146837, - #195018); -#200503 = PRESENTATION_STYLE_ASSIGNMENT((#200504)); -#200504 = SURFACE_STYLE_USAGE(.BOTH.,#200505); -#200505 = SURFACE_SIDE_STYLE('',(#200506)); -#200506 = SURFACE_STYLE_FILL_AREA(#200507); -#200507 = FILL_AREA_STYLE('',(#200508)); -#200508 = FILL_AREA_STYLE_COLOUR('',#195083); -#200509 = OVER_RIDING_STYLED_ITEM('overriding color',(#200510),#146912, - #195018); -#200510 = PRESENTATION_STYLE_ASSIGNMENT((#200511)); -#200511 = SURFACE_STYLE_USAGE(.BOTH.,#200512); -#200512 = SURFACE_SIDE_STYLE('',(#200513)); -#200513 = SURFACE_STYLE_FILL_AREA(#200514); -#200514 = FILL_AREA_STYLE('',(#200515)); -#200515 = FILL_AREA_STYLE_COLOUR('',#195083); -#200516 = OVER_RIDING_STYLED_ITEM('overriding color',(#200517),#146939, - #195018); -#200517 = PRESENTATION_STYLE_ASSIGNMENT((#200518)); -#200518 = SURFACE_STYLE_USAGE(.BOTH.,#200519); -#200519 = SURFACE_SIDE_STYLE('',(#200520)); -#200520 = SURFACE_STYLE_FILL_AREA(#200521); -#200521 = FILL_AREA_STYLE('',(#200522)); -#200522 = FILL_AREA_STYLE_COLOUR('',#195083); -#200523 = OVER_RIDING_STYLED_ITEM('overriding color',(#200524),#146994, - #195018); -#200524 = PRESENTATION_STYLE_ASSIGNMENT((#200525)); -#200525 = SURFACE_STYLE_USAGE(.BOTH.,#200526); -#200526 = SURFACE_SIDE_STYLE('',(#200527)); -#200527 = SURFACE_STYLE_FILL_AREA(#200528); -#200528 = FILL_AREA_STYLE('',(#200529)); -#200529 = FILL_AREA_STYLE_COLOUR('',#195083); -#200530 = OVER_RIDING_STYLED_ITEM('overriding color',(#200531),#147001, - #195018); -#200531 = PRESENTATION_STYLE_ASSIGNMENT((#200532)); -#200532 = SURFACE_STYLE_USAGE(.BOTH.,#200533); -#200533 = SURFACE_SIDE_STYLE('',(#200534)); -#200534 = SURFACE_STYLE_FILL_AREA(#200535); -#200535 = FILL_AREA_STYLE('',(#200536)); -#200536 = FILL_AREA_STYLE_COLOUR('',#195083); -#200537 = OVER_RIDING_STYLED_ITEM('overriding color',(#200538),#147008, - #195018); -#200538 = PRESENTATION_STYLE_ASSIGNMENT((#200539)); -#200539 = SURFACE_STYLE_USAGE(.BOTH.,#200540); -#200540 = SURFACE_SIDE_STYLE('',(#200541)); -#200541 = SURFACE_STYLE_FILL_AREA(#200542); -#200542 = FILL_AREA_STYLE('',(#200543)); -#200543 = FILL_AREA_STYLE_COLOUR('',#195083); -#200544 = OVER_RIDING_STYLED_ITEM('overriding color',(#200545),#147117, - #195018); -#200545 = PRESENTATION_STYLE_ASSIGNMENT((#200546)); -#200546 = SURFACE_STYLE_USAGE(.BOTH.,#200547); -#200547 = SURFACE_SIDE_STYLE('',(#200548)); -#200548 = SURFACE_STYLE_FILL_AREA(#200549); -#200549 = FILL_AREA_STYLE('',(#200550)); -#200550 = FILL_AREA_STYLE_COLOUR('',#195083); -#200551 = OVER_RIDING_STYLED_ITEM('overriding color',(#200552),#147221, - #195018); -#200552 = PRESENTATION_STYLE_ASSIGNMENT((#200553)); -#200553 = SURFACE_STYLE_USAGE(.BOTH.,#200554); -#200554 = SURFACE_SIDE_STYLE('',(#200555)); -#200555 = SURFACE_STYLE_FILL_AREA(#200556); -#200556 = FILL_AREA_STYLE('',(#200557)); -#200557 = FILL_AREA_STYLE_COLOUR('',#195083); -#200558 = OVER_RIDING_STYLED_ITEM('overriding color',(#200559),#147346, - #195018); -#200559 = PRESENTATION_STYLE_ASSIGNMENT((#200560)); -#200560 = SURFACE_STYLE_USAGE(.BOTH.,#200561); -#200561 = SURFACE_SIDE_STYLE('',(#200562)); -#200562 = SURFACE_STYLE_FILL_AREA(#200563); -#200563 = FILL_AREA_STYLE('',(#200564)); -#200564 = FILL_AREA_STYLE_COLOUR('',#195083); -#200565 = OVER_RIDING_STYLED_ITEM('overriding color',(#200566),#147425, - #195018); -#200566 = PRESENTATION_STYLE_ASSIGNMENT((#200567)); -#200567 = SURFACE_STYLE_USAGE(.BOTH.,#200568); -#200568 = SURFACE_SIDE_STYLE('',(#200569)); -#200569 = SURFACE_STYLE_FILL_AREA(#200570); -#200570 = FILL_AREA_STYLE('',(#200571)); -#200571 = FILL_AREA_STYLE_COLOUR('',#195083); -#200572 = OVER_RIDING_STYLED_ITEM('overriding color',(#200573),#147500, - #195018); -#200573 = PRESENTATION_STYLE_ASSIGNMENT((#200574)); -#200574 = SURFACE_STYLE_USAGE(.BOTH.,#200575); -#200575 = SURFACE_SIDE_STYLE('',(#200576)); -#200576 = SURFACE_STYLE_FILL_AREA(#200577); -#200577 = FILL_AREA_STYLE('',(#200578)); -#200578 = FILL_AREA_STYLE_COLOUR('',#195083); -#200579 = OVER_RIDING_STYLED_ITEM('overriding color',(#200580),#147575, - #195018); -#200580 = PRESENTATION_STYLE_ASSIGNMENT((#200581)); -#200581 = SURFACE_STYLE_USAGE(.BOTH.,#200582); -#200582 = SURFACE_SIDE_STYLE('',(#200583)); -#200583 = SURFACE_STYLE_FILL_AREA(#200584); -#200584 = FILL_AREA_STYLE('',(#200585)); -#200585 = FILL_AREA_STYLE_COLOUR('',#195083); -#200586 = OVER_RIDING_STYLED_ITEM('overriding color',(#200587),#147649, - #195018); -#200587 = PRESENTATION_STYLE_ASSIGNMENT((#200588)); -#200588 = SURFACE_STYLE_USAGE(.BOTH.,#200589); -#200589 = SURFACE_SIDE_STYLE('',(#200590)); -#200590 = SURFACE_STYLE_FILL_AREA(#200591); -#200591 = FILL_AREA_STYLE('',(#200592)); -#200592 = FILL_AREA_STYLE_COLOUR('',#195083); -#200593 = OVER_RIDING_STYLED_ITEM('overriding color',(#200594),#147723, - #195018); -#200594 = PRESENTATION_STYLE_ASSIGNMENT((#200595)); -#200595 = SURFACE_STYLE_USAGE(.BOTH.,#200596); -#200596 = SURFACE_SIDE_STYLE('',(#200597)); -#200597 = SURFACE_STYLE_FILL_AREA(#200598); -#200598 = FILL_AREA_STYLE('',(#200599)); -#200599 = FILL_AREA_STYLE_COLOUR('',#195083); -#200600 = OVER_RIDING_STYLED_ITEM('overriding color',(#200601),#147798, - #195018); -#200601 = PRESENTATION_STYLE_ASSIGNMENT((#200602)); -#200602 = SURFACE_STYLE_USAGE(.BOTH.,#200603); -#200603 = SURFACE_SIDE_STYLE('',(#200604)); -#200604 = SURFACE_STYLE_FILL_AREA(#200605); -#200605 = FILL_AREA_STYLE('',(#200606)); -#200606 = FILL_AREA_STYLE_COLOUR('',#195083); -#200607 = OVER_RIDING_STYLED_ITEM('overriding color',(#200608),#147825, - #195018); -#200608 = PRESENTATION_STYLE_ASSIGNMENT((#200609)); -#200609 = SURFACE_STYLE_USAGE(.BOTH.,#200610); -#200610 = SURFACE_SIDE_STYLE('',(#200611)); -#200611 = SURFACE_STYLE_FILL_AREA(#200612); -#200612 = FILL_AREA_STYLE('',(#200613)); -#200613 = FILL_AREA_STYLE_COLOUR('',#195083); -#200614 = OVER_RIDING_STYLED_ITEM('overriding color',(#200615),#147880, - #195018); -#200615 = PRESENTATION_STYLE_ASSIGNMENT((#200616)); -#200616 = SURFACE_STYLE_USAGE(.BOTH.,#200617); -#200617 = SURFACE_SIDE_STYLE('',(#200618)); -#200618 = SURFACE_STYLE_FILL_AREA(#200619); -#200619 = FILL_AREA_STYLE('',(#200620)); -#200620 = FILL_AREA_STYLE_COLOUR('',#195083); -#200621 = OVER_RIDING_STYLED_ITEM('overriding color',(#200622),#147887, - #195018); -#200622 = PRESENTATION_STYLE_ASSIGNMENT((#200623)); -#200623 = SURFACE_STYLE_USAGE(.BOTH.,#200624); -#200624 = SURFACE_SIDE_STYLE('',(#200625)); -#200625 = SURFACE_STYLE_FILL_AREA(#200626); -#200626 = FILL_AREA_STYLE('',(#200627)); -#200627 = FILL_AREA_STYLE_COLOUR('',#195083); -#200628 = OVER_RIDING_STYLED_ITEM('overriding color',(#200629),#147894, - #195018); -#200629 = PRESENTATION_STYLE_ASSIGNMENT((#200630)); -#200630 = SURFACE_STYLE_USAGE(.BOTH.,#200631); -#200631 = SURFACE_SIDE_STYLE('',(#200632)); -#200632 = SURFACE_STYLE_FILL_AREA(#200633); -#200633 = FILL_AREA_STYLE('',(#200634)); -#200634 = FILL_AREA_STYLE_COLOUR('',#195083); -#200635 = OVER_RIDING_STYLED_ITEM('overriding color',(#200636),#148003, - #195018); -#200636 = PRESENTATION_STYLE_ASSIGNMENT((#200637)); -#200637 = SURFACE_STYLE_USAGE(.BOTH.,#200638); -#200638 = SURFACE_SIDE_STYLE('',(#200639)); -#200639 = SURFACE_STYLE_FILL_AREA(#200640); -#200640 = FILL_AREA_STYLE('',(#200641)); -#200641 = FILL_AREA_STYLE_COLOUR('',#195083); -#200642 = OVER_RIDING_STYLED_ITEM('overriding color',(#200643),#148107, - #195018); -#200643 = PRESENTATION_STYLE_ASSIGNMENT((#200644)); -#200644 = SURFACE_STYLE_USAGE(.BOTH.,#200645); -#200645 = SURFACE_SIDE_STYLE('',(#200646)); -#200646 = SURFACE_STYLE_FILL_AREA(#200647); -#200647 = FILL_AREA_STYLE('',(#200648)); -#200648 = FILL_AREA_STYLE_COLOUR('',#195083); -#200649 = OVER_RIDING_STYLED_ITEM('overriding color',(#200650),#148232, - #195018); -#200650 = PRESENTATION_STYLE_ASSIGNMENT((#200651)); -#200651 = SURFACE_STYLE_USAGE(.BOTH.,#200652); -#200652 = SURFACE_SIDE_STYLE('',(#200653)); -#200653 = SURFACE_STYLE_FILL_AREA(#200654); -#200654 = FILL_AREA_STYLE('',(#200655)); -#200655 = FILL_AREA_STYLE_COLOUR('',#195083); -#200656 = OVER_RIDING_STYLED_ITEM('overriding color',(#200657),#148311, - #195018); -#200657 = PRESENTATION_STYLE_ASSIGNMENT((#200658)); -#200658 = SURFACE_STYLE_USAGE(.BOTH.,#200659); -#200659 = SURFACE_SIDE_STYLE('',(#200660)); -#200660 = SURFACE_STYLE_FILL_AREA(#200661); -#200661 = FILL_AREA_STYLE('',(#200662)); -#200662 = FILL_AREA_STYLE_COLOUR('',#195083); -#200663 = OVER_RIDING_STYLED_ITEM('overriding color',(#200664),#148386, - #195018); -#200664 = PRESENTATION_STYLE_ASSIGNMENT((#200665)); -#200665 = SURFACE_STYLE_USAGE(.BOTH.,#200666); -#200666 = SURFACE_SIDE_STYLE('',(#200667)); -#200667 = SURFACE_STYLE_FILL_AREA(#200668); -#200668 = FILL_AREA_STYLE('',(#200669)); -#200669 = FILL_AREA_STYLE_COLOUR('',#195083); -#200670 = OVER_RIDING_STYLED_ITEM('overriding color',(#200671),#148461, - #195018); -#200671 = PRESENTATION_STYLE_ASSIGNMENT((#200672)); -#200672 = SURFACE_STYLE_USAGE(.BOTH.,#200673); -#200673 = SURFACE_SIDE_STYLE('',(#200674)); -#200674 = SURFACE_STYLE_FILL_AREA(#200675); -#200675 = FILL_AREA_STYLE('',(#200676)); -#200676 = FILL_AREA_STYLE_COLOUR('',#195083); -#200677 = OVER_RIDING_STYLED_ITEM('overriding color',(#200678),#148535, - #195018); -#200678 = PRESENTATION_STYLE_ASSIGNMENT((#200679)); -#200679 = SURFACE_STYLE_USAGE(.BOTH.,#200680); -#200680 = SURFACE_SIDE_STYLE('',(#200681)); -#200681 = SURFACE_STYLE_FILL_AREA(#200682); -#200682 = FILL_AREA_STYLE('',(#200683)); -#200683 = FILL_AREA_STYLE_COLOUR('',#195083); -#200684 = OVER_RIDING_STYLED_ITEM('overriding color',(#200685),#148609, - #195018); -#200685 = PRESENTATION_STYLE_ASSIGNMENT((#200686)); -#200686 = SURFACE_STYLE_USAGE(.BOTH.,#200687); -#200687 = SURFACE_SIDE_STYLE('',(#200688)); -#200688 = SURFACE_STYLE_FILL_AREA(#200689); -#200689 = FILL_AREA_STYLE('',(#200690)); -#200690 = FILL_AREA_STYLE_COLOUR('',#195083); -#200691 = OVER_RIDING_STYLED_ITEM('overriding color',(#200692),#148684, - #195018); -#200692 = PRESENTATION_STYLE_ASSIGNMENT((#200693)); -#200693 = SURFACE_STYLE_USAGE(.BOTH.,#200694); -#200694 = SURFACE_SIDE_STYLE('',(#200695)); -#200695 = SURFACE_STYLE_FILL_AREA(#200696); -#200696 = FILL_AREA_STYLE('',(#200697)); -#200697 = FILL_AREA_STYLE_COLOUR('',#195083); -#200698 = OVER_RIDING_STYLED_ITEM('overriding color',(#200699),#148711, - #195018); -#200699 = PRESENTATION_STYLE_ASSIGNMENT((#200700)); -#200700 = SURFACE_STYLE_USAGE(.BOTH.,#200701); -#200701 = SURFACE_SIDE_STYLE('',(#200702)); -#200702 = SURFACE_STYLE_FILL_AREA(#200703); -#200703 = FILL_AREA_STYLE('',(#200704)); -#200704 = FILL_AREA_STYLE_COLOUR('',#195083); -#200705 = OVER_RIDING_STYLED_ITEM('overriding color',(#200706),#148766, - #195018); -#200706 = PRESENTATION_STYLE_ASSIGNMENT((#200707)); -#200707 = SURFACE_STYLE_USAGE(.BOTH.,#200708); -#200708 = SURFACE_SIDE_STYLE('',(#200709)); -#200709 = SURFACE_STYLE_FILL_AREA(#200710); -#200710 = FILL_AREA_STYLE('',(#200711)); -#200711 = FILL_AREA_STYLE_COLOUR('',#195083); -#200712 = OVER_RIDING_STYLED_ITEM('overriding color',(#200713),#148773, - #195018); -#200713 = PRESENTATION_STYLE_ASSIGNMENT((#200714)); -#200714 = SURFACE_STYLE_USAGE(.BOTH.,#200715); -#200715 = SURFACE_SIDE_STYLE('',(#200716)); -#200716 = SURFACE_STYLE_FILL_AREA(#200717); -#200717 = FILL_AREA_STYLE('',(#200718)); -#200718 = FILL_AREA_STYLE_COLOUR('',#195083); -#200719 = OVER_RIDING_STYLED_ITEM('overriding color',(#200720),#148780, - #195018); -#200720 = PRESENTATION_STYLE_ASSIGNMENT((#200721)); -#200721 = SURFACE_STYLE_USAGE(.BOTH.,#200722); -#200722 = SURFACE_SIDE_STYLE('',(#200723)); -#200723 = SURFACE_STYLE_FILL_AREA(#200724); -#200724 = FILL_AREA_STYLE('',(#200725)); -#200725 = FILL_AREA_STYLE_COLOUR('',#195083); -#200726 = OVER_RIDING_STYLED_ITEM('overriding color',(#200727),#148889, - #195018); -#200727 = PRESENTATION_STYLE_ASSIGNMENT((#200728)); -#200728 = SURFACE_STYLE_USAGE(.BOTH.,#200729); -#200729 = SURFACE_SIDE_STYLE('',(#200730)); -#200730 = SURFACE_STYLE_FILL_AREA(#200731); -#200731 = FILL_AREA_STYLE('',(#200732)); -#200732 = FILL_AREA_STYLE_COLOUR('',#195083); -#200733 = OVER_RIDING_STYLED_ITEM('overriding color',(#200734),#148993, - #195018); -#200734 = PRESENTATION_STYLE_ASSIGNMENT((#200735)); -#200735 = SURFACE_STYLE_USAGE(.BOTH.,#200736); -#200736 = SURFACE_SIDE_STYLE('',(#200737)); -#200737 = SURFACE_STYLE_FILL_AREA(#200738); -#200738 = FILL_AREA_STYLE('',(#200739)); -#200739 = FILL_AREA_STYLE_COLOUR('',#195083); -#200740 = OVER_RIDING_STYLED_ITEM('overriding color',(#200741),#149118, - #195018); -#200741 = PRESENTATION_STYLE_ASSIGNMENT((#200742)); -#200742 = SURFACE_STYLE_USAGE(.BOTH.,#200743); -#200743 = SURFACE_SIDE_STYLE('',(#200744)); -#200744 = SURFACE_STYLE_FILL_AREA(#200745); -#200745 = FILL_AREA_STYLE('',(#200746)); -#200746 = FILL_AREA_STYLE_COLOUR('',#195083); -#200747 = OVER_RIDING_STYLED_ITEM('overriding color',(#200748),#149243, - #195018); -#200748 = PRESENTATION_STYLE_ASSIGNMENT((#200749)); -#200749 = SURFACE_STYLE_USAGE(.BOTH.,#200750); -#200750 = SURFACE_SIDE_STYLE('',(#200751)); -#200751 = SURFACE_STYLE_FILL_AREA(#200752); -#200752 = FILL_AREA_STYLE('',(#200753)); -#200753 = FILL_AREA_STYLE_COLOUR('',#195083); -#200754 = OVER_RIDING_STYLED_ITEM('overriding color',(#200755),#149318, - #195018); -#200755 = PRESENTATION_STYLE_ASSIGNMENT((#200756)); -#200756 = SURFACE_STYLE_USAGE(.BOTH.,#200757); -#200757 = SURFACE_SIDE_STYLE('',(#200758)); -#200758 = SURFACE_STYLE_FILL_AREA(#200759); -#200759 = FILL_AREA_STYLE('',(#200760)); -#200760 = FILL_AREA_STYLE_COLOUR('',#195083); -#200761 = OVER_RIDING_STYLED_ITEM('overriding color',(#200762),#149393, - #195018); -#200762 = PRESENTATION_STYLE_ASSIGNMENT((#200763)); -#200763 = SURFACE_STYLE_USAGE(.BOTH.,#200764); -#200764 = SURFACE_SIDE_STYLE('',(#200765)); -#200765 = SURFACE_STYLE_FILL_AREA(#200766); -#200766 = FILL_AREA_STYLE('',(#200767)); -#200767 = FILL_AREA_STYLE_COLOUR('',#195083); -#200768 = OVER_RIDING_STYLED_ITEM('overriding color',(#200769),#149513, - #195018); -#200769 = PRESENTATION_STYLE_ASSIGNMENT((#200770)); -#200770 = SURFACE_STYLE_USAGE(.BOTH.,#200771); -#200771 = SURFACE_SIDE_STYLE('',(#200772)); -#200772 = SURFACE_STYLE_FILL_AREA(#200773); -#200773 = FILL_AREA_STYLE('',(#200774)); -#200774 = FILL_AREA_STYLE_COLOUR('',#195083); -#200775 = OVER_RIDING_STYLED_ITEM('overriding color',(#200776),#149633, - #195018); -#200776 = PRESENTATION_STYLE_ASSIGNMENT((#200777)); -#200777 = SURFACE_STYLE_USAGE(.BOTH.,#200778); -#200778 = SURFACE_SIDE_STYLE('',(#200779)); -#200779 = SURFACE_STYLE_FILL_AREA(#200780); -#200780 = FILL_AREA_STYLE('',(#200781)); -#200781 = FILL_AREA_STYLE_COLOUR('',#195083); -#200782 = OVER_RIDING_STYLED_ITEM('overriding color',(#200783),#149708, - #195018); -#200783 = PRESENTATION_STYLE_ASSIGNMENT((#200784)); -#200784 = SURFACE_STYLE_USAGE(.BOTH.,#200785); -#200785 = SURFACE_SIDE_STYLE('',(#200786)); -#200786 = SURFACE_STYLE_FILL_AREA(#200787); -#200787 = FILL_AREA_STYLE('',(#200788)); -#200788 = FILL_AREA_STYLE_COLOUR('',#195083); -#200789 = OVER_RIDING_STYLED_ITEM('overriding color',(#200790),#149735, - #195018); -#200790 = PRESENTATION_STYLE_ASSIGNMENT((#200791)); -#200791 = SURFACE_STYLE_USAGE(.BOTH.,#200792); -#200792 = SURFACE_SIDE_STYLE('',(#200793)); -#200793 = SURFACE_STYLE_FILL_AREA(#200794); -#200794 = FILL_AREA_STYLE('',(#200795)); -#200795 = FILL_AREA_STYLE_COLOUR('',#195083); -#200796 = OVER_RIDING_STYLED_ITEM('overriding color',(#200797),#149790, - #195018); -#200797 = PRESENTATION_STYLE_ASSIGNMENT((#200798)); -#200798 = SURFACE_STYLE_USAGE(.BOTH.,#200799); -#200799 = SURFACE_SIDE_STYLE('',(#200800)); -#200800 = SURFACE_STYLE_FILL_AREA(#200801); -#200801 = FILL_AREA_STYLE('',(#200802)); -#200802 = FILL_AREA_STYLE_COLOUR('',#195083); -#200803 = OVER_RIDING_STYLED_ITEM('overriding color',(#200804),#149797, - #195018); -#200804 = PRESENTATION_STYLE_ASSIGNMENT((#200805)); -#200805 = SURFACE_STYLE_USAGE(.BOTH.,#200806); -#200806 = SURFACE_SIDE_STYLE('',(#200807)); -#200807 = SURFACE_STYLE_FILL_AREA(#200808); -#200808 = FILL_AREA_STYLE('',(#200809)); -#200809 = FILL_AREA_STYLE_COLOUR('',#195083); -#200810 = OVER_RIDING_STYLED_ITEM('overriding color',(#200811),#149804, - #195018); -#200811 = PRESENTATION_STYLE_ASSIGNMENT((#200812)); -#200812 = SURFACE_STYLE_USAGE(.BOTH.,#200813); -#200813 = SURFACE_SIDE_STYLE('',(#200814)); -#200814 = SURFACE_STYLE_FILL_AREA(#200815); -#200815 = FILL_AREA_STYLE('',(#200816)); -#200816 = FILL_AREA_STYLE_COLOUR('',#195083); -#200817 = OVER_RIDING_STYLED_ITEM('overriding color',(#200818),#149913, - #195018); -#200818 = PRESENTATION_STYLE_ASSIGNMENT((#200819)); -#200819 = SURFACE_STYLE_USAGE(.BOTH.,#200820); -#200820 = SURFACE_SIDE_STYLE('',(#200821)); -#200821 = SURFACE_STYLE_FILL_AREA(#200822); -#200822 = FILL_AREA_STYLE('',(#200823)); -#200823 = FILL_AREA_STYLE_COLOUR('',#195083); -#200824 = OVER_RIDING_STYLED_ITEM('overriding color',(#200825),#150017, - #195018); -#200825 = PRESENTATION_STYLE_ASSIGNMENT((#200826)); -#200826 = SURFACE_STYLE_USAGE(.BOTH.,#200827); -#200827 = SURFACE_SIDE_STYLE('',(#200828)); -#200828 = SURFACE_STYLE_FILL_AREA(#200829); -#200829 = FILL_AREA_STYLE('',(#200830)); -#200830 = FILL_AREA_STYLE_COLOUR('',#195083); -#200831 = OVER_RIDING_STYLED_ITEM('overriding color',(#200832),#150142, - #195018); -#200832 = PRESENTATION_STYLE_ASSIGNMENT((#200833)); -#200833 = SURFACE_STYLE_USAGE(.BOTH.,#200834); -#200834 = SURFACE_SIDE_STYLE('',(#200835)); -#200835 = SURFACE_STYLE_FILL_AREA(#200836); -#200836 = FILL_AREA_STYLE('',(#200837)); -#200837 = FILL_AREA_STYLE_COLOUR('',#195083); -#200838 = OVER_RIDING_STYLED_ITEM('overriding color',(#200839),#150267, - #195018); -#200839 = PRESENTATION_STYLE_ASSIGNMENT((#200840)); -#200840 = SURFACE_STYLE_USAGE(.BOTH.,#200841); -#200841 = SURFACE_SIDE_STYLE('',(#200842)); -#200842 = SURFACE_STYLE_FILL_AREA(#200843); -#200843 = FILL_AREA_STYLE('',(#200844)); -#200844 = FILL_AREA_STYLE_COLOUR('',#195083); -#200845 = OVER_RIDING_STYLED_ITEM('overriding color',(#200846),#150342, - #195018); -#200846 = PRESENTATION_STYLE_ASSIGNMENT((#200847)); -#200847 = SURFACE_STYLE_USAGE(.BOTH.,#200848); -#200848 = SURFACE_SIDE_STYLE('',(#200849)); -#200849 = SURFACE_STYLE_FILL_AREA(#200850); -#200850 = FILL_AREA_STYLE('',(#200851)); -#200851 = FILL_AREA_STYLE_COLOUR('',#195083); -#200852 = OVER_RIDING_STYLED_ITEM('overriding color',(#200853),#150417, - #195018); -#200853 = PRESENTATION_STYLE_ASSIGNMENT((#200854)); -#200854 = SURFACE_STYLE_USAGE(.BOTH.,#200855); -#200855 = SURFACE_SIDE_STYLE('',(#200856)); -#200856 = SURFACE_STYLE_FILL_AREA(#200857); -#200857 = FILL_AREA_STYLE('',(#200858)); -#200858 = FILL_AREA_STYLE_COLOUR('',#195083); -#200859 = OVER_RIDING_STYLED_ITEM('overriding color',(#200860),#150537, - #195018); -#200860 = PRESENTATION_STYLE_ASSIGNMENT((#200861)); -#200861 = SURFACE_STYLE_USAGE(.BOTH.,#200862); -#200862 = SURFACE_SIDE_STYLE('',(#200863)); -#200863 = SURFACE_STYLE_FILL_AREA(#200864); -#200864 = FILL_AREA_STYLE('',(#200865)); -#200865 = FILL_AREA_STYLE_COLOUR('',#195083); -#200866 = OVER_RIDING_STYLED_ITEM('overriding color',(#200867),#150657, - #195018); -#200867 = PRESENTATION_STYLE_ASSIGNMENT((#200868)); -#200868 = SURFACE_STYLE_USAGE(.BOTH.,#200869); -#200869 = SURFACE_SIDE_STYLE('',(#200870)); -#200870 = SURFACE_STYLE_FILL_AREA(#200871); -#200871 = FILL_AREA_STYLE('',(#200872)); -#200872 = FILL_AREA_STYLE_COLOUR('',#195083); -#200873 = OVER_RIDING_STYLED_ITEM('overriding color',(#200874),#150732, - #195018); -#200874 = PRESENTATION_STYLE_ASSIGNMENT((#200875)); -#200875 = SURFACE_STYLE_USAGE(.BOTH.,#200876); -#200876 = SURFACE_SIDE_STYLE('',(#200877)); -#200877 = SURFACE_STYLE_FILL_AREA(#200878); -#200878 = FILL_AREA_STYLE('',(#200879)); -#200879 = FILL_AREA_STYLE_COLOUR('',#195083); -#200880 = OVER_RIDING_STYLED_ITEM('overriding color',(#200881),#150759, - #195018); -#200881 = PRESENTATION_STYLE_ASSIGNMENT((#200882)); -#200882 = SURFACE_STYLE_USAGE(.BOTH.,#200883); -#200883 = SURFACE_SIDE_STYLE('',(#200884)); -#200884 = SURFACE_STYLE_FILL_AREA(#200885); -#200885 = FILL_AREA_STYLE('',(#200886)); -#200886 = FILL_AREA_STYLE_COLOUR('',#195083); -#200887 = OVER_RIDING_STYLED_ITEM('overriding color',(#200888),#150814, - #195018); -#200888 = PRESENTATION_STYLE_ASSIGNMENT((#200889)); -#200889 = SURFACE_STYLE_USAGE(.BOTH.,#200890); -#200890 = SURFACE_SIDE_STYLE('',(#200891)); -#200891 = SURFACE_STYLE_FILL_AREA(#200892); -#200892 = FILL_AREA_STYLE('',(#200893)); -#200893 = FILL_AREA_STYLE_COLOUR('',#195083); -#200894 = OVER_RIDING_STYLED_ITEM('overriding color',(#200895),#150821, - #195018); -#200895 = PRESENTATION_STYLE_ASSIGNMENT((#200896)); -#200896 = SURFACE_STYLE_USAGE(.BOTH.,#200897); -#200897 = SURFACE_SIDE_STYLE('',(#200898)); -#200898 = SURFACE_STYLE_FILL_AREA(#200899); -#200899 = FILL_AREA_STYLE('',(#200900)); -#200900 = FILL_AREA_STYLE_COLOUR('',#195083); -#200901 = OVER_RIDING_STYLED_ITEM('overriding color',(#200902),#150828, - #195018); -#200902 = PRESENTATION_STYLE_ASSIGNMENT((#200903)); -#200903 = SURFACE_STYLE_USAGE(.BOTH.,#200904); -#200904 = SURFACE_SIDE_STYLE('',(#200905)); -#200905 = SURFACE_STYLE_FILL_AREA(#200906); -#200906 = FILL_AREA_STYLE('',(#200907)); -#200907 = FILL_AREA_STYLE_COLOUR('',#195033); -#200908 = OVER_RIDING_STYLED_ITEM('overriding color',(#200909),#150860, - #195018); -#200909 = PRESENTATION_STYLE_ASSIGNMENT((#200910)); -#200910 = SURFACE_STYLE_USAGE(.BOTH.,#200911); -#200911 = SURFACE_SIDE_STYLE('',(#200912)); -#200912 = SURFACE_STYLE_FILL_AREA(#200913); -#200913 = FILL_AREA_STYLE('',(#200914)); -#200914 = FILL_AREA_STYLE_COLOUR('',#195033); -#200915 = OVER_RIDING_STYLED_ITEM('overriding color',(#200916),#150906, - #195018); -#200916 = PRESENTATION_STYLE_ASSIGNMENT((#200917)); -#200917 = SURFACE_STYLE_USAGE(.BOTH.,#200918); -#200918 = SURFACE_SIDE_STYLE('',(#200919)); -#200919 = SURFACE_STYLE_FILL_AREA(#200920); -#200920 = FILL_AREA_STYLE('',(#200921)); -#200921 = FILL_AREA_STYLE_COLOUR('',#195033); -#200922 = OVER_RIDING_STYLED_ITEM('overriding color',(#200923),#150938, - #195018); -#200923 = PRESENTATION_STYLE_ASSIGNMENT((#200924)); -#200924 = SURFACE_STYLE_USAGE(.BOTH.,#200925); -#200925 = SURFACE_SIDE_STYLE('',(#200926)); -#200926 = SURFACE_STYLE_FILL_AREA(#200927); -#200927 = FILL_AREA_STYLE('',(#200928)); -#200928 = FILL_AREA_STYLE_COLOUR('',#195033); -#200929 = OVER_RIDING_STYLED_ITEM('overriding color',(#200930),#150965, - #195018); -#200930 = PRESENTATION_STYLE_ASSIGNMENT((#200931)); -#200931 = SURFACE_STYLE_USAGE(.BOTH.,#200932); -#200932 = SURFACE_SIDE_STYLE('',(#200933)); -#200933 = SURFACE_STYLE_FILL_AREA(#200934); -#200934 = FILL_AREA_STYLE('',(#200935)); -#200935 = FILL_AREA_STYLE_COLOUR('',#195033); -#200936 = OVER_RIDING_STYLED_ITEM('overriding color',(#200937),#150997, - #195018); -#200937 = PRESENTATION_STYLE_ASSIGNMENT((#200938)); -#200938 = SURFACE_STYLE_USAGE(.BOTH.,#200939); -#200939 = SURFACE_SIDE_STYLE('',(#200940)); -#200940 = SURFACE_STYLE_FILL_AREA(#200941); -#200941 = FILL_AREA_STYLE('',(#200942)); -#200942 = FILL_AREA_STYLE_COLOUR('',#195033); -#200943 = OVER_RIDING_STYLED_ITEM('overriding color',(#200944),#151024, - #195018); -#200944 = PRESENTATION_STYLE_ASSIGNMENT((#200945)); -#200945 = SURFACE_STYLE_USAGE(.BOTH.,#200946); -#200946 = SURFACE_SIDE_STYLE('',(#200947)); -#200947 = SURFACE_STYLE_FILL_AREA(#200948); -#200948 = FILL_AREA_STYLE('',(#200949)); -#200949 = FILL_AREA_STYLE_COLOUR('',#195033); -#200950 = OVER_RIDING_STYLED_ITEM('overriding color',(#200951),#151050, - #195018); -#200951 = PRESENTATION_STYLE_ASSIGNMENT((#200952)); -#200952 = SURFACE_STYLE_USAGE(.BOTH.,#200953); -#200953 = SURFACE_SIDE_STYLE('',(#200954)); -#200954 = SURFACE_STYLE_FILL_AREA(#200955); -#200955 = FILL_AREA_STYLE('',(#200956)); -#200956 = FILL_AREA_STYLE_COLOUR('',#195033); -#200957 = OVER_RIDING_STYLED_ITEM('overriding color',(#200958),#151076, - #195018); -#200958 = PRESENTATION_STYLE_ASSIGNMENT((#200959)); -#200959 = SURFACE_STYLE_USAGE(.BOTH.,#200960); -#200960 = SURFACE_SIDE_STYLE('',(#200961)); -#200961 = SURFACE_STYLE_FILL_AREA(#200962); -#200962 = FILL_AREA_STYLE('',(#200963)); -#200963 = FILL_AREA_STYLE_COLOUR('',#195033); -#200964 = OVER_RIDING_STYLED_ITEM('overriding color',(#200965),#151108, - #195018); -#200965 = PRESENTATION_STYLE_ASSIGNMENT((#200966)); -#200966 = SURFACE_STYLE_USAGE(.BOTH.,#200967); -#200967 = SURFACE_SIDE_STYLE('',(#200968)); -#200968 = SURFACE_STYLE_FILL_AREA(#200969); -#200969 = FILL_AREA_STYLE('',(#200970)); -#200970 = FILL_AREA_STYLE_COLOUR('',#195033); -#200971 = OVER_RIDING_STYLED_ITEM('overriding color',(#200972),#151135, - #195018); -#200972 = PRESENTATION_STYLE_ASSIGNMENT((#200973)); -#200973 = SURFACE_STYLE_USAGE(.BOTH.,#200974); -#200974 = SURFACE_SIDE_STYLE('',(#200975)); -#200975 = SURFACE_STYLE_FILL_AREA(#200976); -#200976 = FILL_AREA_STYLE('',(#200977)); -#200977 = FILL_AREA_STYLE_COLOUR('',#195033); -#200978 = OVER_RIDING_STYLED_ITEM('overriding color',(#200979),#151161, - #195018); -#200979 = PRESENTATION_STYLE_ASSIGNMENT((#200980)); -#200980 = SURFACE_STYLE_USAGE(.BOTH.,#200981); -#200981 = SURFACE_SIDE_STYLE('',(#200982)); -#200982 = SURFACE_STYLE_FILL_AREA(#200983); -#200983 = FILL_AREA_STYLE('',(#200984)); -#200984 = FILL_AREA_STYLE_COLOUR('',#195033); -#200985 = OVER_RIDING_STYLED_ITEM('overriding color',(#200986),#151168, - #195018); -#200986 = PRESENTATION_STYLE_ASSIGNMENT((#200987)); -#200987 = SURFACE_STYLE_USAGE(.BOTH.,#200988); -#200988 = SURFACE_SIDE_STYLE('',(#200989)); -#200989 = SURFACE_STYLE_FILL_AREA(#200990); -#200990 = FILL_AREA_STYLE('',(#200991)); -#200991 = FILL_AREA_STYLE_COLOUR('',#195033); -#200992 = OVER_RIDING_STYLED_ITEM('overriding color',(#200993),#151195, - #195018); -#200993 = PRESENTATION_STYLE_ASSIGNMENT((#200994)); -#200994 = SURFACE_STYLE_USAGE(.BOTH.,#200995); -#200995 = SURFACE_SIDE_STYLE('',(#200996)); -#200996 = SURFACE_STYLE_FILL_AREA(#200997); -#200997 = FILL_AREA_STYLE('',(#200998)); -#200998 = FILL_AREA_STYLE_COLOUR('',#195033); -#200999 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201000),#5025); -#201000 = STYLED_ITEM('color',(#201001),#4695); -#201001 = PRESENTATION_STYLE_ASSIGNMENT((#201002,#201008)); -#201002 = SURFACE_STYLE_USAGE(.BOTH.,#201003); -#201003 = SURFACE_SIDE_STYLE('',(#201004)); -#201004 = SURFACE_STYLE_FILL_AREA(#201005); -#201005 = FILL_AREA_STYLE('',(#201006)); -#201006 = FILL_AREA_STYLE_COLOUR('',#201007); -#201007 = COLOUR_RGB('',0.219607844949,0.219607844949,0.219607844949); -#201008 = CURVE_STYLE('',#201009,POSITIVE_LENGTH_MEASURE(0.1),#201007); -#201009 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#201010 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201011),#182733); -#201011 = STYLED_ITEM('color',(#201012),#182403); -#201012 = PRESENTATION_STYLE_ASSIGNMENT((#201013,#201018)); -#201013 = SURFACE_STYLE_USAGE(.BOTH.,#201014); -#201014 = SURFACE_SIDE_STYLE('',(#201015)); -#201015 = SURFACE_STYLE_FILL_AREA(#201016); -#201016 = FILL_AREA_STYLE('',(#201017)); -#201017 = FILL_AREA_STYLE_COLOUR('',#201007); -#201018 = CURVE_STYLE('',#201019,POSITIVE_LENGTH_MEASURE(0.1),#201007); -#201019 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#201020 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201021,#201029,#201037,#201044,#201051,#201058,#201065,#201072, - #201079,#201086,#201093,#201100,#201107,#201114),#75004); -#201021 = STYLED_ITEM('color',(#201022),#71155); -#201022 = PRESENTATION_STYLE_ASSIGNMENT((#201023)); -#201023 = SURFACE_STYLE_USAGE(.BOTH.,#201024); -#201024 = SURFACE_SIDE_STYLE('',(#201025)); -#201025 = SURFACE_STYLE_FILL_AREA(#201026); -#201026 = FILL_AREA_STYLE('',(#201027)); -#201027 = FILL_AREA_STYLE_COLOUR('',#201028); -#201028 = COLOUR_RGB('',0.752941191196,0.752941191196,0.752941191196); -#201029 = OVER_RIDING_STYLED_ITEM('overriding color',(#201030),#71992, - #201021); -#201030 = PRESENTATION_STYLE_ASSIGNMENT((#201031)); -#201031 = SURFACE_STYLE_USAGE(.BOTH.,#201032); -#201032 = SURFACE_SIDE_STYLE('',(#201033)); -#201033 = SURFACE_STYLE_FILL_AREA(#201034); -#201034 = FILL_AREA_STYLE('',(#201035)); -#201035 = FILL_AREA_STYLE_COLOUR('',#201036); -#201036 = COLOUR_RGB('',0.501960813999,0.501960813999,0.501960813999); -#201037 = OVER_RIDING_STYLED_ITEM('overriding color',(#201038),#72969, - #201021); +#198359 = FILL_AREA_STYLE_COLOUR('',#198360); +#198360 = COLOUR_RGB('',0.250980407,0.250980407,0.250980407); +#198361 = OVER_RIDING_STYLED_ITEM('overriding color',(#198362),#88722, + #198353); +#198362 = PRESENTATION_STYLE_ASSIGNMENT((#198363)); +#198363 = SURFACE_STYLE_USAGE(.BOTH.,#198364); +#198364 = SURFACE_SIDE_STYLE('',(#198365)); +#198365 = SURFACE_STYLE_FILL_AREA(#198366); +#198366 = FILL_AREA_STYLE('',(#198367)); +#198367 = FILL_AREA_STYLE_COLOUR('',#198368); +#198368 = COLOUR_RGB('',0.137254908681,0.137254908681,0.137254908681); +#198369 = OVER_RIDING_STYLED_ITEM('overriding color',(#198370),#88837, + #198353); +#198370 = PRESENTATION_STYLE_ASSIGNMENT((#198371)); +#198371 = SURFACE_STYLE_USAGE(.BOTH.,#198372); +#198372 = SURFACE_SIDE_STYLE('',(#198373)); +#198373 = SURFACE_STYLE_FILL_AREA(#198374); +#198374 = FILL_AREA_STYLE('',(#198375)); +#198375 = FILL_AREA_STYLE_COLOUR('',#198368); +#198376 = OVER_RIDING_STYLED_ITEM('overriding color',(#198377),#90781, + #198353); +#198377 = PRESENTATION_STYLE_ASSIGNMENT((#198378)); +#198378 = SURFACE_STYLE_USAGE(.BOTH.,#198379); +#198379 = SURFACE_SIDE_STYLE('',(#198380)); +#198380 = SURFACE_STYLE_FILL_AREA(#198381); +#198381 = FILL_AREA_STYLE('',(#198382)); +#198382 = FILL_AREA_STYLE_COLOUR('',#198368); +#198383 = OVER_RIDING_STYLED_ITEM('overriding color',(#198384),#92720, + #198353); +#198384 = PRESENTATION_STYLE_ASSIGNMENT((#198385)); +#198385 = SURFACE_STYLE_USAGE(.BOTH.,#198386); +#198386 = SURFACE_SIDE_STYLE('',(#198387)); +#198387 = SURFACE_STYLE_FILL_AREA(#198388); +#198388 = FILL_AREA_STYLE('',(#198389)); +#198389 = FILL_AREA_STYLE_COLOUR('',#198368); +#198390 = OVER_RIDING_STYLED_ITEM('overriding color',(#198391),#94649, + #198353); +#198391 = PRESENTATION_STYLE_ASSIGNMENT((#198392)); +#198392 = SURFACE_STYLE_USAGE(.BOTH.,#198393); +#198393 = SURFACE_SIDE_STYLE('',(#198394)); +#198394 = SURFACE_STYLE_FILL_AREA(#198395); +#198395 = FILL_AREA_STYLE('',(#198396)); +#198396 = FILL_AREA_STYLE_COLOUR('',#198368); +#198397 = OVER_RIDING_STYLED_ITEM('overriding color',(#198398),#96578, + #198353); +#198398 = PRESENTATION_STYLE_ASSIGNMENT((#198399)); +#198399 = SURFACE_STYLE_USAGE(.BOTH.,#198400); +#198400 = SURFACE_SIDE_STYLE('',(#198401)); +#198401 = SURFACE_STYLE_FILL_AREA(#198402); +#198402 = FILL_AREA_STYLE('',(#198403)); +#198403 = FILL_AREA_STYLE_COLOUR('',#198368); +#198404 = OVER_RIDING_STYLED_ITEM('overriding color',(#198405),#96701, + #198353); +#198405 = PRESENTATION_STYLE_ASSIGNMENT((#198406)); +#198406 = SURFACE_STYLE_USAGE(.BOTH.,#198407); +#198407 = SURFACE_SIDE_STYLE('',(#198408)); +#198408 = SURFACE_STYLE_FILL_AREA(#198409); +#198409 = FILL_AREA_STYLE('',(#198410)); +#198410 = FILL_AREA_STYLE_COLOUR('',#198368); +#198411 = OVER_RIDING_STYLED_ITEM('overriding color',(#198412),#96792, + #198353); +#198412 = PRESENTATION_STYLE_ASSIGNMENT((#198413)); +#198413 = SURFACE_STYLE_USAGE(.BOTH.,#198414); +#198414 = SURFACE_SIDE_STYLE('',(#198415)); +#198415 = SURFACE_STYLE_FILL_AREA(#198416); +#198416 = FILL_AREA_STYLE('',(#198417)); +#198417 = FILL_AREA_STYLE_COLOUR('',#198418); +#198418 = DRAUGHTING_PRE_DEFINED_COLOUR('white'); +#198419 = OVER_RIDING_STYLED_ITEM('overriding color',(#198420),#96901, + #198353); +#198420 = PRESENTATION_STYLE_ASSIGNMENT((#198421)); +#198421 = SURFACE_STYLE_USAGE(.BOTH.,#198422); +#198422 = SURFACE_SIDE_STYLE('',(#198423)); +#198423 = SURFACE_STYLE_FILL_AREA(#198424); +#198424 = FILL_AREA_STYLE('',(#198425)); +#198425 = FILL_AREA_STYLE_COLOUR('',#198418); +#198426 = OVER_RIDING_STYLED_ITEM('overriding color',(#198427),#97005, + #198353); +#198427 = PRESENTATION_STYLE_ASSIGNMENT((#198428)); +#198428 = SURFACE_STYLE_USAGE(.BOTH.,#198429); +#198429 = SURFACE_SIDE_STYLE('',(#198430)); +#198430 = SURFACE_STYLE_FILL_AREA(#198431); +#198431 = FILL_AREA_STYLE('',(#198432)); +#198432 = FILL_AREA_STYLE_COLOUR('',#198418); +#198433 = OVER_RIDING_STYLED_ITEM('overriding color',(#198434),#97084, + #198353); +#198434 = PRESENTATION_STYLE_ASSIGNMENT((#198435)); +#198435 = SURFACE_STYLE_USAGE(.BOTH.,#198436); +#198436 = SURFACE_SIDE_STYLE('',(#198437)); +#198437 = SURFACE_STYLE_FILL_AREA(#198438); +#198438 = FILL_AREA_STYLE('',(#198439)); +#198439 = FILL_AREA_STYLE_COLOUR('',#198418); +#198440 = OVER_RIDING_STYLED_ITEM('overriding color',(#198441),#97163, + #198353); +#198441 = PRESENTATION_STYLE_ASSIGNMENT((#198442)); +#198442 = SURFACE_STYLE_USAGE(.BOTH.,#198443); +#198443 = SURFACE_SIDE_STYLE('',(#198444)); +#198444 = SURFACE_STYLE_FILL_AREA(#198445); +#198445 = FILL_AREA_STYLE('',(#198446)); +#198446 = FILL_AREA_STYLE_COLOUR('',#198418); +#198447 = OVER_RIDING_STYLED_ITEM('overriding color',(#198448),#97238, + #198353); +#198448 = PRESENTATION_STYLE_ASSIGNMENT((#198449)); +#198449 = SURFACE_STYLE_USAGE(.BOTH.,#198450); +#198450 = SURFACE_SIDE_STYLE('',(#198451)); +#198451 = SURFACE_STYLE_FILL_AREA(#198452); +#198452 = FILL_AREA_STYLE('',(#198453)); +#198453 = FILL_AREA_STYLE_COLOUR('',#198418); +#198454 = OVER_RIDING_STYLED_ITEM('overriding color',(#198455),#97313, + #198353); +#198455 = PRESENTATION_STYLE_ASSIGNMENT((#198456)); +#198456 = SURFACE_STYLE_USAGE(.BOTH.,#198457); +#198457 = SURFACE_SIDE_STYLE('',(#198458)); +#198458 = SURFACE_STYLE_FILL_AREA(#198459); +#198459 = FILL_AREA_STYLE('',(#198460)); +#198460 = FILL_AREA_STYLE_COLOUR('',#198418); +#198461 = OVER_RIDING_STYLED_ITEM('overriding color',(#198462),#97387, + #198353); +#198462 = PRESENTATION_STYLE_ASSIGNMENT((#198463)); +#198463 = SURFACE_STYLE_USAGE(.BOTH.,#198464); +#198464 = SURFACE_SIDE_STYLE('',(#198465)); +#198465 = SURFACE_STYLE_FILL_AREA(#198466); +#198466 = FILL_AREA_STYLE('',(#198467)); +#198467 = FILL_AREA_STYLE_COLOUR('',#198418); +#198468 = OVER_RIDING_STYLED_ITEM('overriding color',(#198469),#97461, + #198353); +#198469 = PRESENTATION_STYLE_ASSIGNMENT((#198470)); +#198470 = SURFACE_STYLE_USAGE(.BOTH.,#198471); +#198471 = SURFACE_SIDE_STYLE('',(#198472)); +#198472 = SURFACE_STYLE_FILL_AREA(#198473); +#198473 = FILL_AREA_STYLE('',(#198474)); +#198474 = FILL_AREA_STYLE_COLOUR('',#198418); +#198475 = OVER_RIDING_STYLED_ITEM('overriding color',(#198476),#97536, + #198353); +#198476 = PRESENTATION_STYLE_ASSIGNMENT((#198477)); +#198477 = SURFACE_STYLE_USAGE(.BOTH.,#198478); +#198478 = SURFACE_SIDE_STYLE('',(#198479)); +#198479 = SURFACE_STYLE_FILL_AREA(#198480); +#198480 = FILL_AREA_STYLE('',(#198481)); +#198481 = FILL_AREA_STYLE_COLOUR('',#198418); +#198482 = OVER_RIDING_STYLED_ITEM('overriding color',(#198483),#97563, + #198353); +#198483 = PRESENTATION_STYLE_ASSIGNMENT((#198484)); +#198484 = SURFACE_STYLE_USAGE(.BOTH.,#198485); +#198485 = SURFACE_SIDE_STYLE('',(#198486)); +#198486 = SURFACE_STYLE_FILL_AREA(#198487); +#198487 = FILL_AREA_STYLE('',(#198488)); +#198488 = FILL_AREA_STYLE_COLOUR('',#198418); +#198489 = OVER_RIDING_STYLED_ITEM('overriding color',(#198490),#97618, + #198353); +#198490 = PRESENTATION_STYLE_ASSIGNMENT((#198491)); +#198491 = SURFACE_STYLE_USAGE(.BOTH.,#198492); +#198492 = SURFACE_SIDE_STYLE('',(#198493)); +#198493 = SURFACE_STYLE_FILL_AREA(#198494); +#198494 = FILL_AREA_STYLE('',(#198495)); +#198495 = FILL_AREA_STYLE_COLOUR('',#198418); +#198496 = OVER_RIDING_STYLED_ITEM('overriding color',(#198497),#97625, + #198353); +#198497 = PRESENTATION_STYLE_ASSIGNMENT((#198498)); +#198498 = SURFACE_STYLE_USAGE(.BOTH.,#198499); +#198499 = SURFACE_SIDE_STYLE('',(#198500)); +#198500 = SURFACE_STYLE_FILL_AREA(#198501); +#198501 = FILL_AREA_STYLE('',(#198502)); +#198502 = FILL_AREA_STYLE_COLOUR('',#198418); +#198503 = OVER_RIDING_STYLED_ITEM('overriding color',(#198504),#97632, + #198353); +#198504 = PRESENTATION_STYLE_ASSIGNMENT((#198505)); +#198505 = SURFACE_STYLE_USAGE(.BOTH.,#198506); +#198506 = SURFACE_SIDE_STYLE('',(#198507)); +#198507 = SURFACE_STYLE_FILL_AREA(#198508); +#198508 = FILL_AREA_STYLE('',(#198509)); +#198509 = FILL_AREA_STYLE_COLOUR('',#198418); +#198510 = OVER_RIDING_STYLED_ITEM('overriding color',(#198511),#97741, + #198353); +#198511 = PRESENTATION_STYLE_ASSIGNMENT((#198512)); +#198512 = SURFACE_STYLE_USAGE(.BOTH.,#198513); +#198513 = SURFACE_SIDE_STYLE('',(#198514)); +#198514 = SURFACE_STYLE_FILL_AREA(#198515); +#198515 = FILL_AREA_STYLE('',(#198516)); +#198516 = FILL_AREA_STYLE_COLOUR('',#198418); +#198517 = OVER_RIDING_STYLED_ITEM('overriding color',(#198518),#97845, + #198353); +#198518 = PRESENTATION_STYLE_ASSIGNMENT((#198519)); +#198519 = SURFACE_STYLE_USAGE(.BOTH.,#198520); +#198520 = SURFACE_SIDE_STYLE('',(#198521)); +#198521 = SURFACE_STYLE_FILL_AREA(#198522); +#198522 = FILL_AREA_STYLE('',(#198523)); +#198523 = FILL_AREA_STYLE_COLOUR('',#198418); +#198524 = OVER_RIDING_STYLED_ITEM('overriding color',(#198525),#97924, + #198353); +#198525 = PRESENTATION_STYLE_ASSIGNMENT((#198526)); +#198526 = SURFACE_STYLE_USAGE(.BOTH.,#198527); +#198527 = SURFACE_SIDE_STYLE('',(#198528)); +#198528 = SURFACE_STYLE_FILL_AREA(#198529); +#198529 = FILL_AREA_STYLE('',(#198530)); +#198530 = FILL_AREA_STYLE_COLOUR('',#198418); +#198531 = OVER_RIDING_STYLED_ITEM('overriding color',(#198532),#98003, + #198353); +#198532 = PRESENTATION_STYLE_ASSIGNMENT((#198533)); +#198533 = SURFACE_STYLE_USAGE(.BOTH.,#198534); +#198534 = SURFACE_SIDE_STYLE('',(#198535)); +#198535 = SURFACE_STYLE_FILL_AREA(#198536); +#198536 = FILL_AREA_STYLE('',(#198537)); +#198537 = FILL_AREA_STYLE_COLOUR('',#198418); +#198538 = OVER_RIDING_STYLED_ITEM('overriding color',(#198539),#98078, + #198353); +#198539 = PRESENTATION_STYLE_ASSIGNMENT((#198540)); +#198540 = SURFACE_STYLE_USAGE(.BOTH.,#198541); +#198541 = SURFACE_SIDE_STYLE('',(#198542)); +#198542 = SURFACE_STYLE_FILL_AREA(#198543); +#198543 = FILL_AREA_STYLE('',(#198544)); +#198544 = FILL_AREA_STYLE_COLOUR('',#198418); +#198545 = OVER_RIDING_STYLED_ITEM('overriding color',(#198546),#98153, + #198353); +#198546 = PRESENTATION_STYLE_ASSIGNMENT((#198547)); +#198547 = SURFACE_STYLE_USAGE(.BOTH.,#198548); +#198548 = SURFACE_SIDE_STYLE('',(#198549)); +#198549 = SURFACE_STYLE_FILL_AREA(#198550); +#198550 = FILL_AREA_STYLE('',(#198551)); +#198551 = FILL_AREA_STYLE_COLOUR('',#198418); +#198552 = OVER_RIDING_STYLED_ITEM('overriding color',(#198553),#98227, + #198353); +#198553 = PRESENTATION_STYLE_ASSIGNMENT((#198554)); +#198554 = SURFACE_STYLE_USAGE(.BOTH.,#198555); +#198555 = SURFACE_SIDE_STYLE('',(#198556)); +#198556 = SURFACE_STYLE_FILL_AREA(#198557); +#198557 = FILL_AREA_STYLE('',(#198558)); +#198558 = FILL_AREA_STYLE_COLOUR('',#198418); +#198559 = OVER_RIDING_STYLED_ITEM('overriding color',(#198560),#98301, + #198353); +#198560 = PRESENTATION_STYLE_ASSIGNMENT((#198561)); +#198561 = SURFACE_STYLE_USAGE(.BOTH.,#198562); +#198562 = SURFACE_SIDE_STYLE('',(#198563)); +#198563 = SURFACE_STYLE_FILL_AREA(#198564); +#198564 = FILL_AREA_STYLE('',(#198565)); +#198565 = FILL_AREA_STYLE_COLOUR('',#198418); +#198566 = OVER_RIDING_STYLED_ITEM('overriding color',(#198567),#98348, + #198353); +#198567 = PRESENTATION_STYLE_ASSIGNMENT((#198568)); +#198568 = SURFACE_STYLE_USAGE(.BOTH.,#198569); +#198569 = SURFACE_SIDE_STYLE('',(#198570)); +#198570 = SURFACE_STYLE_FILL_AREA(#198571); +#198571 = FILL_AREA_STYLE('',(#198572)); +#198572 = FILL_AREA_STYLE_COLOUR('',#198418); +#198573 = OVER_RIDING_STYLED_ITEM('overriding color',(#198574),#98403, + #198353); +#198574 = PRESENTATION_STYLE_ASSIGNMENT((#198575)); +#198575 = SURFACE_STYLE_USAGE(.BOTH.,#198576); +#198576 = SURFACE_SIDE_STYLE('',(#198577)); +#198577 = SURFACE_STYLE_FILL_AREA(#198578); +#198578 = FILL_AREA_STYLE('',(#198579)); +#198579 = FILL_AREA_STYLE_COLOUR('',#198418); +#198580 = OVER_RIDING_STYLED_ITEM('overriding color',(#198581),#98430, + #198353); +#198581 = PRESENTATION_STYLE_ASSIGNMENT((#198582)); +#198582 = SURFACE_STYLE_USAGE(.BOTH.,#198583); +#198583 = SURFACE_SIDE_STYLE('',(#198584)); +#198584 = SURFACE_STYLE_FILL_AREA(#198585); +#198585 = FILL_AREA_STYLE('',(#198586)); +#198586 = FILL_AREA_STYLE_COLOUR('',#198418); +#198587 = OVER_RIDING_STYLED_ITEM('overriding color',(#198588),#98465, + #198353); +#198588 = PRESENTATION_STYLE_ASSIGNMENT((#198589)); +#198589 = SURFACE_STYLE_USAGE(.BOTH.,#198590); +#198590 = SURFACE_SIDE_STYLE('',(#198591)); +#198591 = SURFACE_STYLE_FILL_AREA(#198592); +#198592 = FILL_AREA_STYLE('',(#198593)); +#198593 = FILL_AREA_STYLE_COLOUR('',#198418); +#198594 = OVER_RIDING_STYLED_ITEM('overriding color',(#198595),#98472, + #198353); +#198595 = PRESENTATION_STYLE_ASSIGNMENT((#198596)); +#198596 = SURFACE_STYLE_USAGE(.BOTH.,#198597); +#198597 = SURFACE_SIDE_STYLE('',(#198598)); +#198598 = SURFACE_STYLE_FILL_AREA(#198599); +#198599 = FILL_AREA_STYLE('',(#198600)); +#198600 = FILL_AREA_STYLE_COLOUR('',#198418); +#198601 = OVER_RIDING_STYLED_ITEM('overriding color',(#198602),#98581, + #198353); +#198602 = PRESENTATION_STYLE_ASSIGNMENT((#198603)); +#198603 = SURFACE_STYLE_USAGE(.BOTH.,#198604); +#198604 = SURFACE_SIDE_STYLE('',(#198605)); +#198605 = SURFACE_STYLE_FILL_AREA(#198606); +#198606 = FILL_AREA_STYLE('',(#198607)); +#198607 = FILL_AREA_STYLE_COLOUR('',#198418); +#198608 = OVER_RIDING_STYLED_ITEM('overriding color',(#198609),#98685, + #198353); +#198609 = PRESENTATION_STYLE_ASSIGNMENT((#198610)); +#198610 = SURFACE_STYLE_USAGE(.BOTH.,#198611); +#198611 = SURFACE_SIDE_STYLE('',(#198612)); +#198612 = SURFACE_STYLE_FILL_AREA(#198613); +#198613 = FILL_AREA_STYLE('',(#198614)); +#198614 = FILL_AREA_STYLE_COLOUR('',#198418); +#198615 = OVER_RIDING_STYLED_ITEM('overriding color',(#198616),#98764, + #198353); +#198616 = PRESENTATION_STYLE_ASSIGNMENT((#198617)); +#198617 = SURFACE_STYLE_USAGE(.BOTH.,#198618); +#198618 = SURFACE_SIDE_STYLE('',(#198619)); +#198619 = SURFACE_STYLE_FILL_AREA(#198620); +#198620 = FILL_AREA_STYLE('',(#198621)); +#198621 = FILL_AREA_STYLE_COLOUR('',#198418); +#198622 = OVER_RIDING_STYLED_ITEM('overriding color',(#198623),#98843, + #198353); +#198623 = PRESENTATION_STYLE_ASSIGNMENT((#198624)); +#198624 = SURFACE_STYLE_USAGE(.BOTH.,#198625); +#198625 = SURFACE_SIDE_STYLE('',(#198626)); +#198626 = SURFACE_STYLE_FILL_AREA(#198627); +#198627 = FILL_AREA_STYLE('',(#198628)); +#198628 = FILL_AREA_STYLE_COLOUR('',#198418); +#198629 = OVER_RIDING_STYLED_ITEM('overriding color',(#198630),#98918, + #198353); +#198630 = PRESENTATION_STYLE_ASSIGNMENT((#198631)); +#198631 = SURFACE_STYLE_USAGE(.BOTH.,#198632); +#198632 = SURFACE_SIDE_STYLE('',(#198633)); +#198633 = SURFACE_STYLE_FILL_AREA(#198634); +#198634 = FILL_AREA_STYLE('',(#198635)); +#198635 = FILL_AREA_STYLE_COLOUR('',#198418); +#198636 = OVER_RIDING_STYLED_ITEM('overriding color',(#198637),#98993, + #198353); +#198637 = PRESENTATION_STYLE_ASSIGNMENT((#198638)); +#198638 = SURFACE_STYLE_USAGE(.BOTH.,#198639); +#198639 = SURFACE_SIDE_STYLE('',(#198640)); +#198640 = SURFACE_STYLE_FILL_AREA(#198641); +#198641 = FILL_AREA_STYLE('',(#198642)); +#198642 = FILL_AREA_STYLE_COLOUR('',#198418); +#198643 = OVER_RIDING_STYLED_ITEM('overriding color',(#198644),#99067, + #198353); +#198644 = PRESENTATION_STYLE_ASSIGNMENT((#198645)); +#198645 = SURFACE_STYLE_USAGE(.BOTH.,#198646); +#198646 = SURFACE_SIDE_STYLE('',(#198647)); +#198647 = SURFACE_STYLE_FILL_AREA(#198648); +#198648 = FILL_AREA_STYLE('',(#198649)); +#198649 = FILL_AREA_STYLE_COLOUR('',#198418); +#198650 = OVER_RIDING_STYLED_ITEM('overriding color',(#198651),#99141, + #198353); +#198651 = PRESENTATION_STYLE_ASSIGNMENT((#198652)); +#198652 = SURFACE_STYLE_USAGE(.BOTH.,#198653); +#198653 = SURFACE_SIDE_STYLE('',(#198654)); +#198654 = SURFACE_STYLE_FILL_AREA(#198655); +#198655 = FILL_AREA_STYLE('',(#198656)); +#198656 = FILL_AREA_STYLE_COLOUR('',#198418); +#198657 = OVER_RIDING_STYLED_ITEM('overriding color',(#198658),#99216, + #198353); +#198658 = PRESENTATION_STYLE_ASSIGNMENT((#198659)); +#198659 = SURFACE_STYLE_USAGE(.BOTH.,#198660); +#198660 = SURFACE_SIDE_STYLE('',(#198661)); +#198661 = SURFACE_STYLE_FILL_AREA(#198662); +#198662 = FILL_AREA_STYLE('',(#198663)); +#198663 = FILL_AREA_STYLE_COLOUR('',#198418); +#198664 = OVER_RIDING_STYLED_ITEM('overriding color',(#198665),#99243, + #198353); +#198665 = PRESENTATION_STYLE_ASSIGNMENT((#198666)); +#198666 = SURFACE_STYLE_USAGE(.BOTH.,#198667); +#198667 = SURFACE_SIDE_STYLE('',(#198668)); +#198668 = SURFACE_STYLE_FILL_AREA(#198669); +#198669 = FILL_AREA_STYLE('',(#198670)); +#198670 = FILL_AREA_STYLE_COLOUR('',#198418); +#198671 = OVER_RIDING_STYLED_ITEM('overriding color',(#198672),#99298, + #198353); +#198672 = PRESENTATION_STYLE_ASSIGNMENT((#198673)); +#198673 = SURFACE_STYLE_USAGE(.BOTH.,#198674); +#198674 = SURFACE_SIDE_STYLE('',(#198675)); +#198675 = SURFACE_STYLE_FILL_AREA(#198676); +#198676 = FILL_AREA_STYLE('',(#198677)); +#198677 = FILL_AREA_STYLE_COLOUR('',#198418); +#198678 = OVER_RIDING_STYLED_ITEM('overriding color',(#198679),#99305, + #198353); +#198679 = PRESENTATION_STYLE_ASSIGNMENT((#198680)); +#198680 = SURFACE_STYLE_USAGE(.BOTH.,#198681); +#198681 = SURFACE_SIDE_STYLE('',(#198682)); +#198682 = SURFACE_STYLE_FILL_AREA(#198683); +#198683 = FILL_AREA_STYLE('',(#198684)); +#198684 = FILL_AREA_STYLE_COLOUR('',#198418); +#198685 = OVER_RIDING_STYLED_ITEM('overriding color',(#198686),#99312, + #198353); +#198686 = PRESENTATION_STYLE_ASSIGNMENT((#198687)); +#198687 = SURFACE_STYLE_USAGE(.BOTH.,#198688); +#198688 = SURFACE_SIDE_STYLE('',(#198689)); +#198689 = SURFACE_STYLE_FILL_AREA(#198690); +#198690 = FILL_AREA_STYLE('',(#198691)); +#198691 = FILL_AREA_STYLE_COLOUR('',#198418); +#198692 = OVER_RIDING_STYLED_ITEM('overriding color',(#198693),#99421, + #198353); +#198693 = PRESENTATION_STYLE_ASSIGNMENT((#198694)); +#198694 = SURFACE_STYLE_USAGE(.BOTH.,#198695); +#198695 = SURFACE_SIDE_STYLE('',(#198696)); +#198696 = SURFACE_STYLE_FILL_AREA(#198697); +#198697 = FILL_AREA_STYLE('',(#198698)); +#198698 = FILL_AREA_STYLE_COLOUR('',#198418); +#198699 = OVER_RIDING_STYLED_ITEM('overriding color',(#198700),#99525, + #198353); +#198700 = PRESENTATION_STYLE_ASSIGNMENT((#198701)); +#198701 = SURFACE_STYLE_USAGE(.BOTH.,#198702); +#198702 = SURFACE_SIDE_STYLE('',(#198703)); +#198703 = SURFACE_STYLE_FILL_AREA(#198704); +#198704 = FILL_AREA_STYLE('',(#198705)); +#198705 = FILL_AREA_STYLE_COLOUR('',#198418); +#198706 = OVER_RIDING_STYLED_ITEM('overriding color',(#198707),#99604, + #198353); +#198707 = PRESENTATION_STYLE_ASSIGNMENT((#198708)); +#198708 = SURFACE_STYLE_USAGE(.BOTH.,#198709); +#198709 = SURFACE_SIDE_STYLE('',(#198710)); +#198710 = SURFACE_STYLE_FILL_AREA(#198711); +#198711 = FILL_AREA_STYLE('',(#198712)); +#198712 = FILL_AREA_STYLE_COLOUR('',#198418); +#198713 = OVER_RIDING_STYLED_ITEM('overriding color',(#198714),#99683, + #198353); +#198714 = PRESENTATION_STYLE_ASSIGNMENT((#198715)); +#198715 = SURFACE_STYLE_USAGE(.BOTH.,#198716); +#198716 = SURFACE_SIDE_STYLE('',(#198717)); +#198717 = SURFACE_STYLE_FILL_AREA(#198718); +#198718 = FILL_AREA_STYLE('',(#198719)); +#198719 = FILL_AREA_STYLE_COLOUR('',#198418); +#198720 = OVER_RIDING_STYLED_ITEM('overriding color',(#198721),#99758, + #198353); +#198721 = PRESENTATION_STYLE_ASSIGNMENT((#198722)); +#198722 = SURFACE_STYLE_USAGE(.BOTH.,#198723); +#198723 = SURFACE_SIDE_STYLE('',(#198724)); +#198724 = SURFACE_STYLE_FILL_AREA(#198725); +#198725 = FILL_AREA_STYLE('',(#198726)); +#198726 = FILL_AREA_STYLE_COLOUR('',#198418); +#198727 = OVER_RIDING_STYLED_ITEM('overriding color',(#198728),#99833, + #198353); +#198728 = PRESENTATION_STYLE_ASSIGNMENT((#198729)); +#198729 = SURFACE_STYLE_USAGE(.BOTH.,#198730); +#198730 = SURFACE_SIDE_STYLE('',(#198731)); +#198731 = SURFACE_STYLE_FILL_AREA(#198732); +#198732 = FILL_AREA_STYLE('',(#198733)); +#198733 = FILL_AREA_STYLE_COLOUR('',#198418); +#198734 = OVER_RIDING_STYLED_ITEM('overriding color',(#198735),#99907, + #198353); +#198735 = PRESENTATION_STYLE_ASSIGNMENT((#198736)); +#198736 = SURFACE_STYLE_USAGE(.BOTH.,#198737); +#198737 = SURFACE_SIDE_STYLE('',(#198738)); +#198738 = SURFACE_STYLE_FILL_AREA(#198739); +#198739 = FILL_AREA_STYLE('',(#198740)); +#198740 = FILL_AREA_STYLE_COLOUR('',#198418); +#198741 = OVER_RIDING_STYLED_ITEM('overriding color',(#198742),#99981, + #198353); +#198742 = PRESENTATION_STYLE_ASSIGNMENT((#198743)); +#198743 = SURFACE_STYLE_USAGE(.BOTH.,#198744); +#198744 = SURFACE_SIDE_STYLE('',(#198745)); +#198745 = SURFACE_STYLE_FILL_AREA(#198746); +#198746 = FILL_AREA_STYLE('',(#198747)); +#198747 = FILL_AREA_STYLE_COLOUR('',#198418); +#198748 = OVER_RIDING_STYLED_ITEM('overriding color',(#198749),#100056, + #198353); +#198749 = PRESENTATION_STYLE_ASSIGNMENT((#198750)); +#198750 = SURFACE_STYLE_USAGE(.BOTH.,#198751); +#198751 = SURFACE_SIDE_STYLE('',(#198752)); +#198752 = SURFACE_STYLE_FILL_AREA(#198753); +#198753 = FILL_AREA_STYLE('',(#198754)); +#198754 = FILL_AREA_STYLE_COLOUR('',#198418); +#198755 = OVER_RIDING_STYLED_ITEM('overriding color',(#198756),#100083, + #198353); +#198756 = PRESENTATION_STYLE_ASSIGNMENT((#198757)); +#198757 = SURFACE_STYLE_USAGE(.BOTH.,#198758); +#198758 = SURFACE_SIDE_STYLE('',(#198759)); +#198759 = SURFACE_STYLE_FILL_AREA(#198760); +#198760 = FILL_AREA_STYLE('',(#198761)); +#198761 = FILL_AREA_STYLE_COLOUR('',#198418); +#198762 = OVER_RIDING_STYLED_ITEM('overriding color',(#198763),#100138, + #198353); +#198763 = PRESENTATION_STYLE_ASSIGNMENT((#198764)); +#198764 = SURFACE_STYLE_USAGE(.BOTH.,#198765); +#198765 = SURFACE_SIDE_STYLE('',(#198766)); +#198766 = SURFACE_STYLE_FILL_AREA(#198767); +#198767 = FILL_AREA_STYLE('',(#198768)); +#198768 = FILL_AREA_STYLE_COLOUR('',#198418); +#198769 = OVER_RIDING_STYLED_ITEM('overriding color',(#198770),#100145, + #198353); +#198770 = PRESENTATION_STYLE_ASSIGNMENT((#198771)); +#198771 = SURFACE_STYLE_USAGE(.BOTH.,#198772); +#198772 = SURFACE_SIDE_STYLE('',(#198773)); +#198773 = SURFACE_STYLE_FILL_AREA(#198774); +#198774 = FILL_AREA_STYLE('',(#198775)); +#198775 = FILL_AREA_STYLE_COLOUR('',#198418); +#198776 = OVER_RIDING_STYLED_ITEM('overriding color',(#198777),#100152, + #198353); +#198777 = PRESENTATION_STYLE_ASSIGNMENT((#198778)); +#198778 = SURFACE_STYLE_USAGE(.BOTH.,#198779); +#198779 = SURFACE_SIDE_STYLE('',(#198780)); +#198780 = SURFACE_STYLE_FILL_AREA(#198781); +#198781 = FILL_AREA_STYLE('',(#198782)); +#198782 = FILL_AREA_STYLE_COLOUR('',#198418); +#198783 = OVER_RIDING_STYLED_ITEM('overriding color',(#198784),#100261, + #198353); +#198784 = PRESENTATION_STYLE_ASSIGNMENT((#198785)); +#198785 = SURFACE_STYLE_USAGE(.BOTH.,#198786); +#198786 = SURFACE_SIDE_STYLE('',(#198787)); +#198787 = SURFACE_STYLE_FILL_AREA(#198788); +#198788 = FILL_AREA_STYLE('',(#198789)); +#198789 = FILL_AREA_STYLE_COLOUR('',#198418); +#198790 = OVER_RIDING_STYLED_ITEM('overriding color',(#198791),#100365, + #198353); +#198791 = PRESENTATION_STYLE_ASSIGNMENT((#198792)); +#198792 = SURFACE_STYLE_USAGE(.BOTH.,#198793); +#198793 = SURFACE_SIDE_STYLE('',(#198794)); +#198794 = SURFACE_STYLE_FILL_AREA(#198795); +#198795 = FILL_AREA_STYLE('',(#198796)); +#198796 = FILL_AREA_STYLE_COLOUR('',#198418); +#198797 = OVER_RIDING_STYLED_ITEM('overriding color',(#198798),#100444, + #198353); +#198798 = PRESENTATION_STYLE_ASSIGNMENT((#198799)); +#198799 = SURFACE_STYLE_USAGE(.BOTH.,#198800); +#198800 = SURFACE_SIDE_STYLE('',(#198801)); +#198801 = SURFACE_STYLE_FILL_AREA(#198802); +#198802 = FILL_AREA_STYLE('',(#198803)); +#198803 = FILL_AREA_STYLE_COLOUR('',#198418); +#198804 = OVER_RIDING_STYLED_ITEM('overriding color',(#198805),#100523, + #198353); +#198805 = PRESENTATION_STYLE_ASSIGNMENT((#198806)); +#198806 = SURFACE_STYLE_USAGE(.BOTH.,#198807); +#198807 = SURFACE_SIDE_STYLE('',(#198808)); +#198808 = SURFACE_STYLE_FILL_AREA(#198809); +#198809 = FILL_AREA_STYLE('',(#198810)); +#198810 = FILL_AREA_STYLE_COLOUR('',#198418); +#198811 = OVER_RIDING_STYLED_ITEM('overriding color',(#198812),#100598, + #198353); +#198812 = PRESENTATION_STYLE_ASSIGNMENT((#198813)); +#198813 = SURFACE_STYLE_USAGE(.BOTH.,#198814); +#198814 = SURFACE_SIDE_STYLE('',(#198815)); +#198815 = SURFACE_STYLE_FILL_AREA(#198816); +#198816 = FILL_AREA_STYLE('',(#198817)); +#198817 = FILL_AREA_STYLE_COLOUR('',#198418); +#198818 = OVER_RIDING_STYLED_ITEM('overriding color',(#198819),#100673, + #198353); +#198819 = PRESENTATION_STYLE_ASSIGNMENT((#198820)); +#198820 = SURFACE_STYLE_USAGE(.BOTH.,#198821); +#198821 = SURFACE_SIDE_STYLE('',(#198822)); +#198822 = SURFACE_STYLE_FILL_AREA(#198823); +#198823 = FILL_AREA_STYLE('',(#198824)); +#198824 = FILL_AREA_STYLE_COLOUR('',#198418); +#198825 = OVER_RIDING_STYLED_ITEM('overriding color',(#198826),#100747, + #198353); +#198826 = PRESENTATION_STYLE_ASSIGNMENT((#198827)); +#198827 = SURFACE_STYLE_USAGE(.BOTH.,#198828); +#198828 = SURFACE_SIDE_STYLE('',(#198829)); +#198829 = SURFACE_STYLE_FILL_AREA(#198830); +#198830 = FILL_AREA_STYLE('',(#198831)); +#198831 = FILL_AREA_STYLE_COLOUR('',#198418); +#198832 = OVER_RIDING_STYLED_ITEM('overriding color',(#198833),#100821, + #198353); +#198833 = PRESENTATION_STYLE_ASSIGNMENT((#198834)); +#198834 = SURFACE_STYLE_USAGE(.BOTH.,#198835); +#198835 = SURFACE_SIDE_STYLE('',(#198836)); +#198836 = SURFACE_STYLE_FILL_AREA(#198837); +#198837 = FILL_AREA_STYLE('',(#198838)); +#198838 = FILL_AREA_STYLE_COLOUR('',#198418); +#198839 = OVER_RIDING_STYLED_ITEM('overriding color',(#198840),#100896, + #198353); +#198840 = PRESENTATION_STYLE_ASSIGNMENT((#198841)); +#198841 = SURFACE_STYLE_USAGE(.BOTH.,#198842); +#198842 = SURFACE_SIDE_STYLE('',(#198843)); +#198843 = SURFACE_STYLE_FILL_AREA(#198844); +#198844 = FILL_AREA_STYLE('',(#198845)); +#198845 = FILL_AREA_STYLE_COLOUR('',#198418); +#198846 = OVER_RIDING_STYLED_ITEM('overriding color',(#198847),#100923, + #198353); +#198847 = PRESENTATION_STYLE_ASSIGNMENT((#198848)); +#198848 = SURFACE_STYLE_USAGE(.BOTH.,#198849); +#198849 = SURFACE_SIDE_STYLE('',(#198850)); +#198850 = SURFACE_STYLE_FILL_AREA(#198851); +#198851 = FILL_AREA_STYLE('',(#198852)); +#198852 = FILL_AREA_STYLE_COLOUR('',#198418); +#198853 = OVER_RIDING_STYLED_ITEM('overriding color',(#198854),#100978, + #198353); +#198854 = PRESENTATION_STYLE_ASSIGNMENT((#198855)); +#198855 = SURFACE_STYLE_USAGE(.BOTH.,#198856); +#198856 = SURFACE_SIDE_STYLE('',(#198857)); +#198857 = SURFACE_STYLE_FILL_AREA(#198858); +#198858 = FILL_AREA_STYLE('',(#198859)); +#198859 = FILL_AREA_STYLE_COLOUR('',#198418); +#198860 = OVER_RIDING_STYLED_ITEM('overriding color',(#198861),#100985, + #198353); +#198861 = PRESENTATION_STYLE_ASSIGNMENT((#198862)); +#198862 = SURFACE_STYLE_USAGE(.BOTH.,#198863); +#198863 = SURFACE_SIDE_STYLE('',(#198864)); +#198864 = SURFACE_STYLE_FILL_AREA(#198865); +#198865 = FILL_AREA_STYLE('',(#198866)); +#198866 = FILL_AREA_STYLE_COLOUR('',#198418); +#198867 = OVER_RIDING_STYLED_ITEM('overriding color',(#198868),#100992, + #198353); +#198868 = PRESENTATION_STYLE_ASSIGNMENT((#198869)); +#198869 = SURFACE_STYLE_USAGE(.BOTH.,#198870); +#198870 = SURFACE_SIDE_STYLE('',(#198871)); +#198871 = SURFACE_STYLE_FILL_AREA(#198872); +#198872 = FILL_AREA_STYLE('',(#198873)); +#198873 = FILL_AREA_STYLE_COLOUR('',#198418); +#198874 = OVER_RIDING_STYLED_ITEM('overriding color',(#198875),#101101, + #198353); +#198875 = PRESENTATION_STYLE_ASSIGNMENT((#198876)); +#198876 = SURFACE_STYLE_USAGE(.BOTH.,#198877); +#198877 = SURFACE_SIDE_STYLE('',(#198878)); +#198878 = SURFACE_STYLE_FILL_AREA(#198879); +#198879 = FILL_AREA_STYLE('',(#198880)); +#198880 = FILL_AREA_STYLE_COLOUR('',#198418); +#198881 = OVER_RIDING_STYLED_ITEM('overriding color',(#198882),#101205, + #198353); +#198882 = PRESENTATION_STYLE_ASSIGNMENT((#198883)); +#198883 = SURFACE_STYLE_USAGE(.BOTH.,#198884); +#198884 = SURFACE_SIDE_STYLE('',(#198885)); +#198885 = SURFACE_STYLE_FILL_AREA(#198886); +#198886 = FILL_AREA_STYLE('',(#198887)); +#198887 = FILL_AREA_STYLE_COLOUR('',#198418); +#198888 = OVER_RIDING_STYLED_ITEM('overriding color',(#198889),#101284, + #198353); +#198889 = PRESENTATION_STYLE_ASSIGNMENT((#198890)); +#198890 = SURFACE_STYLE_USAGE(.BOTH.,#198891); +#198891 = SURFACE_SIDE_STYLE('',(#198892)); +#198892 = SURFACE_STYLE_FILL_AREA(#198893); +#198893 = FILL_AREA_STYLE('',(#198894)); +#198894 = FILL_AREA_STYLE_COLOUR('',#198418); +#198895 = OVER_RIDING_STYLED_ITEM('overriding color',(#198896),#101363, + #198353); +#198896 = PRESENTATION_STYLE_ASSIGNMENT((#198897)); +#198897 = SURFACE_STYLE_USAGE(.BOTH.,#198898); +#198898 = SURFACE_SIDE_STYLE('',(#198899)); +#198899 = SURFACE_STYLE_FILL_AREA(#198900); +#198900 = FILL_AREA_STYLE('',(#198901)); +#198901 = FILL_AREA_STYLE_COLOUR('',#198418); +#198902 = OVER_RIDING_STYLED_ITEM('overriding color',(#198903),#101438, + #198353); +#198903 = PRESENTATION_STYLE_ASSIGNMENT((#198904)); +#198904 = SURFACE_STYLE_USAGE(.BOTH.,#198905); +#198905 = SURFACE_SIDE_STYLE('',(#198906)); +#198906 = SURFACE_STYLE_FILL_AREA(#198907); +#198907 = FILL_AREA_STYLE('',(#198908)); +#198908 = FILL_AREA_STYLE_COLOUR('',#198418); +#198909 = OVER_RIDING_STYLED_ITEM('overriding color',(#198910),#101513, + #198353); +#198910 = PRESENTATION_STYLE_ASSIGNMENT((#198911)); +#198911 = SURFACE_STYLE_USAGE(.BOTH.,#198912); +#198912 = SURFACE_SIDE_STYLE('',(#198913)); +#198913 = SURFACE_STYLE_FILL_AREA(#198914); +#198914 = FILL_AREA_STYLE('',(#198915)); +#198915 = FILL_AREA_STYLE_COLOUR('',#198418); +#198916 = OVER_RIDING_STYLED_ITEM('overriding color',(#198917),#101587, + #198353); +#198917 = PRESENTATION_STYLE_ASSIGNMENT((#198918)); +#198918 = SURFACE_STYLE_USAGE(.BOTH.,#198919); +#198919 = SURFACE_SIDE_STYLE('',(#198920)); +#198920 = SURFACE_STYLE_FILL_AREA(#198921); +#198921 = FILL_AREA_STYLE('',(#198922)); +#198922 = FILL_AREA_STYLE_COLOUR('',#198418); +#198923 = OVER_RIDING_STYLED_ITEM('overriding color',(#198924),#101661, + #198353); +#198924 = PRESENTATION_STYLE_ASSIGNMENT((#198925)); +#198925 = SURFACE_STYLE_USAGE(.BOTH.,#198926); +#198926 = SURFACE_SIDE_STYLE('',(#198927)); +#198927 = SURFACE_STYLE_FILL_AREA(#198928); +#198928 = FILL_AREA_STYLE('',(#198929)); +#198929 = FILL_AREA_STYLE_COLOUR('',#198418); +#198930 = OVER_RIDING_STYLED_ITEM('overriding color',(#198931),#101736, + #198353); +#198931 = PRESENTATION_STYLE_ASSIGNMENT((#198932)); +#198932 = SURFACE_STYLE_USAGE(.BOTH.,#198933); +#198933 = SURFACE_SIDE_STYLE('',(#198934)); +#198934 = SURFACE_STYLE_FILL_AREA(#198935); +#198935 = FILL_AREA_STYLE('',(#198936)); +#198936 = FILL_AREA_STYLE_COLOUR('',#198418); +#198937 = OVER_RIDING_STYLED_ITEM('overriding color',(#198938),#101763, + #198353); +#198938 = PRESENTATION_STYLE_ASSIGNMENT((#198939)); +#198939 = SURFACE_STYLE_USAGE(.BOTH.,#198940); +#198940 = SURFACE_SIDE_STYLE('',(#198941)); +#198941 = SURFACE_STYLE_FILL_AREA(#198942); +#198942 = FILL_AREA_STYLE('',(#198943)); +#198943 = FILL_AREA_STYLE_COLOUR('',#198418); +#198944 = OVER_RIDING_STYLED_ITEM('overriding color',(#198945),#101818, + #198353); +#198945 = PRESENTATION_STYLE_ASSIGNMENT((#198946)); +#198946 = SURFACE_STYLE_USAGE(.BOTH.,#198947); +#198947 = SURFACE_SIDE_STYLE('',(#198948)); +#198948 = SURFACE_STYLE_FILL_AREA(#198949); +#198949 = FILL_AREA_STYLE('',(#198950)); +#198950 = FILL_AREA_STYLE_COLOUR('',#198418); +#198951 = OVER_RIDING_STYLED_ITEM('overriding color',(#198952),#101825, + #198353); +#198952 = PRESENTATION_STYLE_ASSIGNMENT((#198953)); +#198953 = SURFACE_STYLE_USAGE(.BOTH.,#198954); +#198954 = SURFACE_SIDE_STYLE('',(#198955)); +#198955 = SURFACE_STYLE_FILL_AREA(#198956); +#198956 = FILL_AREA_STYLE('',(#198957)); +#198957 = FILL_AREA_STYLE_COLOUR('',#198418); +#198958 = OVER_RIDING_STYLED_ITEM('overriding color',(#198959),#101832, + #198353); +#198959 = PRESENTATION_STYLE_ASSIGNMENT((#198960)); +#198960 = SURFACE_STYLE_USAGE(.BOTH.,#198961); +#198961 = SURFACE_SIDE_STYLE('',(#198962)); +#198962 = SURFACE_STYLE_FILL_AREA(#198963); +#198963 = FILL_AREA_STYLE('',(#198964)); +#198964 = FILL_AREA_STYLE_COLOUR('',#198418); +#198965 = OVER_RIDING_STYLED_ITEM('overriding color',(#198966),#101941, + #198353); +#198966 = PRESENTATION_STYLE_ASSIGNMENT((#198967)); +#198967 = SURFACE_STYLE_USAGE(.BOTH.,#198968); +#198968 = SURFACE_SIDE_STYLE('',(#198969)); +#198969 = SURFACE_STYLE_FILL_AREA(#198970); +#198970 = FILL_AREA_STYLE('',(#198971)); +#198971 = FILL_AREA_STYLE_COLOUR('',#198418); +#198972 = OVER_RIDING_STYLED_ITEM('overriding color',(#198973),#102045, + #198353); +#198973 = PRESENTATION_STYLE_ASSIGNMENT((#198974)); +#198974 = SURFACE_STYLE_USAGE(.BOTH.,#198975); +#198975 = SURFACE_SIDE_STYLE('',(#198976)); +#198976 = SURFACE_STYLE_FILL_AREA(#198977); +#198977 = FILL_AREA_STYLE('',(#198978)); +#198978 = FILL_AREA_STYLE_COLOUR('',#198418); +#198979 = OVER_RIDING_STYLED_ITEM('overriding color',(#198980),#102124, + #198353); +#198980 = PRESENTATION_STYLE_ASSIGNMENT((#198981)); +#198981 = SURFACE_STYLE_USAGE(.BOTH.,#198982); +#198982 = SURFACE_SIDE_STYLE('',(#198983)); +#198983 = SURFACE_STYLE_FILL_AREA(#198984); +#198984 = FILL_AREA_STYLE('',(#198985)); +#198985 = FILL_AREA_STYLE_COLOUR('',#198418); +#198986 = OVER_RIDING_STYLED_ITEM('overriding color',(#198987),#102203, + #198353); +#198987 = PRESENTATION_STYLE_ASSIGNMENT((#198988)); +#198988 = SURFACE_STYLE_USAGE(.BOTH.,#198989); +#198989 = SURFACE_SIDE_STYLE('',(#198990)); +#198990 = SURFACE_STYLE_FILL_AREA(#198991); +#198991 = FILL_AREA_STYLE('',(#198992)); +#198992 = FILL_AREA_STYLE_COLOUR('',#198418); +#198993 = OVER_RIDING_STYLED_ITEM('overriding color',(#198994),#102278, + #198353); +#198994 = PRESENTATION_STYLE_ASSIGNMENT((#198995)); +#198995 = SURFACE_STYLE_USAGE(.BOTH.,#198996); +#198996 = SURFACE_SIDE_STYLE('',(#198997)); +#198997 = SURFACE_STYLE_FILL_AREA(#198998); +#198998 = FILL_AREA_STYLE('',(#198999)); +#198999 = FILL_AREA_STYLE_COLOUR('',#198418); +#199000 = OVER_RIDING_STYLED_ITEM('overriding color',(#199001),#102353, + #198353); +#199001 = PRESENTATION_STYLE_ASSIGNMENT((#199002)); +#199002 = SURFACE_STYLE_USAGE(.BOTH.,#199003); +#199003 = SURFACE_SIDE_STYLE('',(#199004)); +#199004 = SURFACE_STYLE_FILL_AREA(#199005); +#199005 = FILL_AREA_STYLE('',(#199006)); +#199006 = FILL_AREA_STYLE_COLOUR('',#198418); +#199007 = OVER_RIDING_STYLED_ITEM('overriding color',(#199008),#102427, + #198353); +#199008 = PRESENTATION_STYLE_ASSIGNMENT((#199009)); +#199009 = SURFACE_STYLE_USAGE(.BOTH.,#199010); +#199010 = SURFACE_SIDE_STYLE('',(#199011)); +#199011 = SURFACE_STYLE_FILL_AREA(#199012); +#199012 = FILL_AREA_STYLE('',(#199013)); +#199013 = FILL_AREA_STYLE_COLOUR('',#198418); +#199014 = OVER_RIDING_STYLED_ITEM('overriding color',(#199015),#102501, + #198353); +#199015 = PRESENTATION_STYLE_ASSIGNMENT((#199016)); +#199016 = SURFACE_STYLE_USAGE(.BOTH.,#199017); +#199017 = SURFACE_SIDE_STYLE('',(#199018)); +#199018 = SURFACE_STYLE_FILL_AREA(#199019); +#199019 = FILL_AREA_STYLE('',(#199020)); +#199020 = FILL_AREA_STYLE_COLOUR('',#198418); +#199021 = OVER_RIDING_STYLED_ITEM('overriding color',(#199022),#102576, + #198353); +#199022 = PRESENTATION_STYLE_ASSIGNMENT((#199023)); +#199023 = SURFACE_STYLE_USAGE(.BOTH.,#199024); +#199024 = SURFACE_SIDE_STYLE('',(#199025)); +#199025 = SURFACE_STYLE_FILL_AREA(#199026); +#199026 = FILL_AREA_STYLE('',(#199027)); +#199027 = FILL_AREA_STYLE_COLOUR('',#198418); +#199028 = OVER_RIDING_STYLED_ITEM('overriding color',(#199029),#102603, + #198353); +#199029 = PRESENTATION_STYLE_ASSIGNMENT((#199030)); +#199030 = SURFACE_STYLE_USAGE(.BOTH.,#199031); +#199031 = SURFACE_SIDE_STYLE('',(#199032)); +#199032 = SURFACE_STYLE_FILL_AREA(#199033); +#199033 = FILL_AREA_STYLE('',(#199034)); +#199034 = FILL_AREA_STYLE_COLOUR('',#198418); +#199035 = OVER_RIDING_STYLED_ITEM('overriding color',(#199036),#102658, + #198353); +#199036 = PRESENTATION_STYLE_ASSIGNMENT((#199037)); +#199037 = SURFACE_STYLE_USAGE(.BOTH.,#199038); +#199038 = SURFACE_SIDE_STYLE('',(#199039)); +#199039 = SURFACE_STYLE_FILL_AREA(#199040); +#199040 = FILL_AREA_STYLE('',(#199041)); +#199041 = FILL_AREA_STYLE_COLOUR('',#198418); +#199042 = OVER_RIDING_STYLED_ITEM('overriding color',(#199043),#102665, + #198353); +#199043 = PRESENTATION_STYLE_ASSIGNMENT((#199044)); +#199044 = SURFACE_STYLE_USAGE(.BOTH.,#199045); +#199045 = SURFACE_SIDE_STYLE('',(#199046)); +#199046 = SURFACE_STYLE_FILL_AREA(#199047); +#199047 = FILL_AREA_STYLE('',(#199048)); +#199048 = FILL_AREA_STYLE_COLOUR('',#198418); +#199049 = OVER_RIDING_STYLED_ITEM('overriding color',(#199050),#102672, + #198353); +#199050 = PRESENTATION_STYLE_ASSIGNMENT((#199051)); +#199051 = SURFACE_STYLE_USAGE(.BOTH.,#199052); +#199052 = SURFACE_SIDE_STYLE('',(#199053)); +#199053 = SURFACE_STYLE_FILL_AREA(#199054); +#199054 = FILL_AREA_STYLE('',(#199055)); +#199055 = FILL_AREA_STYLE_COLOUR('',#198418); +#199056 = OVER_RIDING_STYLED_ITEM('overriding color',(#199057),#102781, + #198353); +#199057 = PRESENTATION_STYLE_ASSIGNMENT((#199058)); +#199058 = SURFACE_STYLE_USAGE(.BOTH.,#199059); +#199059 = SURFACE_SIDE_STYLE('',(#199060)); +#199060 = SURFACE_STYLE_FILL_AREA(#199061); +#199061 = FILL_AREA_STYLE('',(#199062)); +#199062 = FILL_AREA_STYLE_COLOUR('',#198418); +#199063 = OVER_RIDING_STYLED_ITEM('overriding color',(#199064),#102885, + #198353); +#199064 = PRESENTATION_STYLE_ASSIGNMENT((#199065)); +#199065 = SURFACE_STYLE_USAGE(.BOTH.,#199066); +#199066 = SURFACE_SIDE_STYLE('',(#199067)); +#199067 = SURFACE_STYLE_FILL_AREA(#199068); +#199068 = FILL_AREA_STYLE('',(#199069)); +#199069 = FILL_AREA_STYLE_COLOUR('',#198418); +#199070 = OVER_RIDING_STYLED_ITEM('overriding color',(#199071),#102964, + #198353); +#199071 = PRESENTATION_STYLE_ASSIGNMENT((#199072)); +#199072 = SURFACE_STYLE_USAGE(.BOTH.,#199073); +#199073 = SURFACE_SIDE_STYLE('',(#199074)); +#199074 = SURFACE_STYLE_FILL_AREA(#199075); +#199075 = FILL_AREA_STYLE('',(#199076)); +#199076 = FILL_AREA_STYLE_COLOUR('',#198418); +#199077 = OVER_RIDING_STYLED_ITEM('overriding color',(#199078),#103043, + #198353); +#199078 = PRESENTATION_STYLE_ASSIGNMENT((#199079)); +#199079 = SURFACE_STYLE_USAGE(.BOTH.,#199080); +#199080 = SURFACE_SIDE_STYLE('',(#199081)); +#199081 = SURFACE_STYLE_FILL_AREA(#199082); +#199082 = FILL_AREA_STYLE('',(#199083)); +#199083 = FILL_AREA_STYLE_COLOUR('',#198418); +#199084 = OVER_RIDING_STYLED_ITEM('overriding color',(#199085),#103118, + #198353); +#199085 = PRESENTATION_STYLE_ASSIGNMENT((#199086)); +#199086 = SURFACE_STYLE_USAGE(.BOTH.,#199087); +#199087 = SURFACE_SIDE_STYLE('',(#199088)); +#199088 = SURFACE_STYLE_FILL_AREA(#199089); +#199089 = FILL_AREA_STYLE('',(#199090)); +#199090 = FILL_AREA_STYLE_COLOUR('',#198418); +#199091 = OVER_RIDING_STYLED_ITEM('overriding color',(#199092),#103193, + #198353); +#199092 = PRESENTATION_STYLE_ASSIGNMENT((#199093)); +#199093 = SURFACE_STYLE_USAGE(.BOTH.,#199094); +#199094 = SURFACE_SIDE_STYLE('',(#199095)); +#199095 = SURFACE_STYLE_FILL_AREA(#199096); +#199096 = FILL_AREA_STYLE('',(#199097)); +#199097 = FILL_AREA_STYLE_COLOUR('',#198418); +#199098 = OVER_RIDING_STYLED_ITEM('overriding color',(#199099),#103267, + #198353); +#199099 = PRESENTATION_STYLE_ASSIGNMENT((#199100)); +#199100 = SURFACE_STYLE_USAGE(.BOTH.,#199101); +#199101 = SURFACE_SIDE_STYLE('',(#199102)); +#199102 = SURFACE_STYLE_FILL_AREA(#199103); +#199103 = FILL_AREA_STYLE('',(#199104)); +#199104 = FILL_AREA_STYLE_COLOUR('',#198418); +#199105 = OVER_RIDING_STYLED_ITEM('overriding color',(#199106),#103341, + #198353); +#199106 = PRESENTATION_STYLE_ASSIGNMENT((#199107)); +#199107 = SURFACE_STYLE_USAGE(.BOTH.,#199108); +#199108 = SURFACE_SIDE_STYLE('',(#199109)); +#199109 = SURFACE_STYLE_FILL_AREA(#199110); +#199110 = FILL_AREA_STYLE('',(#199111)); +#199111 = FILL_AREA_STYLE_COLOUR('',#198418); +#199112 = OVER_RIDING_STYLED_ITEM('overriding color',(#199113),#103416, + #198353); +#199113 = PRESENTATION_STYLE_ASSIGNMENT((#199114)); +#199114 = SURFACE_STYLE_USAGE(.BOTH.,#199115); +#199115 = SURFACE_SIDE_STYLE('',(#199116)); +#199116 = SURFACE_STYLE_FILL_AREA(#199117); +#199117 = FILL_AREA_STYLE('',(#199118)); +#199118 = FILL_AREA_STYLE_COLOUR('',#198418); +#199119 = OVER_RIDING_STYLED_ITEM('overriding color',(#199120),#103443, + #198353); +#199120 = PRESENTATION_STYLE_ASSIGNMENT((#199121)); +#199121 = SURFACE_STYLE_USAGE(.BOTH.,#199122); +#199122 = SURFACE_SIDE_STYLE('',(#199123)); +#199123 = SURFACE_STYLE_FILL_AREA(#199124); +#199124 = FILL_AREA_STYLE('',(#199125)); +#199125 = FILL_AREA_STYLE_COLOUR('',#198418); +#199126 = OVER_RIDING_STYLED_ITEM('overriding color',(#199127),#103498, + #198353); +#199127 = PRESENTATION_STYLE_ASSIGNMENT((#199128)); +#199128 = SURFACE_STYLE_USAGE(.BOTH.,#199129); +#199129 = SURFACE_SIDE_STYLE('',(#199130)); +#199130 = SURFACE_STYLE_FILL_AREA(#199131); +#199131 = FILL_AREA_STYLE('',(#199132)); +#199132 = FILL_AREA_STYLE_COLOUR('',#198418); +#199133 = OVER_RIDING_STYLED_ITEM('overriding color',(#199134),#103505, + #198353); +#199134 = PRESENTATION_STYLE_ASSIGNMENT((#199135)); +#199135 = SURFACE_STYLE_USAGE(.BOTH.,#199136); +#199136 = SURFACE_SIDE_STYLE('',(#199137)); +#199137 = SURFACE_STYLE_FILL_AREA(#199138); +#199138 = FILL_AREA_STYLE('',(#199139)); +#199139 = FILL_AREA_STYLE_COLOUR('',#198418); +#199140 = OVER_RIDING_STYLED_ITEM('overriding color',(#199141),#103512, + #198353); +#199141 = PRESENTATION_STYLE_ASSIGNMENT((#199142)); +#199142 = SURFACE_STYLE_USAGE(.BOTH.,#199143); +#199143 = SURFACE_SIDE_STYLE('',(#199144)); +#199144 = SURFACE_STYLE_FILL_AREA(#199145); +#199145 = FILL_AREA_STYLE('',(#199146)); +#199146 = FILL_AREA_STYLE_COLOUR('',#198418); +#199147 = OVER_RIDING_STYLED_ITEM('overriding color',(#199148),#103621, + #198353); +#199148 = PRESENTATION_STYLE_ASSIGNMENT((#199149)); +#199149 = SURFACE_STYLE_USAGE(.BOTH.,#199150); +#199150 = SURFACE_SIDE_STYLE('',(#199151)); +#199151 = SURFACE_STYLE_FILL_AREA(#199152); +#199152 = FILL_AREA_STYLE('',(#199153)); +#199153 = FILL_AREA_STYLE_COLOUR('',#198418); +#199154 = OVER_RIDING_STYLED_ITEM('overriding color',(#199155),#103725, + #198353); +#199155 = PRESENTATION_STYLE_ASSIGNMENT((#199156)); +#199156 = SURFACE_STYLE_USAGE(.BOTH.,#199157); +#199157 = SURFACE_SIDE_STYLE('',(#199158)); +#199158 = SURFACE_STYLE_FILL_AREA(#199159); +#199159 = FILL_AREA_STYLE('',(#199160)); +#199160 = FILL_AREA_STYLE_COLOUR('',#198418); +#199161 = OVER_RIDING_STYLED_ITEM('overriding color',(#199162),#103804, + #198353); +#199162 = PRESENTATION_STYLE_ASSIGNMENT((#199163)); +#199163 = SURFACE_STYLE_USAGE(.BOTH.,#199164); +#199164 = SURFACE_SIDE_STYLE('',(#199165)); +#199165 = SURFACE_STYLE_FILL_AREA(#199166); +#199166 = FILL_AREA_STYLE('',(#199167)); +#199167 = FILL_AREA_STYLE_COLOUR('',#198418); +#199168 = OVER_RIDING_STYLED_ITEM('overriding color',(#199169),#103883, + #198353); +#199169 = PRESENTATION_STYLE_ASSIGNMENT((#199170)); +#199170 = SURFACE_STYLE_USAGE(.BOTH.,#199171); +#199171 = SURFACE_SIDE_STYLE('',(#199172)); +#199172 = SURFACE_STYLE_FILL_AREA(#199173); +#199173 = FILL_AREA_STYLE('',(#199174)); +#199174 = FILL_AREA_STYLE_COLOUR('',#198418); +#199175 = OVER_RIDING_STYLED_ITEM('overriding color',(#199176),#103958, + #198353); +#199176 = PRESENTATION_STYLE_ASSIGNMENT((#199177)); +#199177 = SURFACE_STYLE_USAGE(.BOTH.,#199178); +#199178 = SURFACE_SIDE_STYLE('',(#199179)); +#199179 = SURFACE_STYLE_FILL_AREA(#199180); +#199180 = FILL_AREA_STYLE('',(#199181)); +#199181 = FILL_AREA_STYLE_COLOUR('',#198418); +#199182 = OVER_RIDING_STYLED_ITEM('overriding color',(#199183),#104033, + #198353); +#199183 = PRESENTATION_STYLE_ASSIGNMENT((#199184)); +#199184 = SURFACE_STYLE_USAGE(.BOTH.,#199185); +#199185 = SURFACE_SIDE_STYLE('',(#199186)); +#199186 = SURFACE_STYLE_FILL_AREA(#199187); +#199187 = FILL_AREA_STYLE('',(#199188)); +#199188 = FILL_AREA_STYLE_COLOUR('',#198418); +#199189 = OVER_RIDING_STYLED_ITEM('overriding color',(#199190),#104107, + #198353); +#199190 = PRESENTATION_STYLE_ASSIGNMENT((#199191)); +#199191 = SURFACE_STYLE_USAGE(.BOTH.,#199192); +#199192 = SURFACE_SIDE_STYLE('',(#199193)); +#199193 = SURFACE_STYLE_FILL_AREA(#199194); +#199194 = FILL_AREA_STYLE('',(#199195)); +#199195 = FILL_AREA_STYLE_COLOUR('',#198418); +#199196 = OVER_RIDING_STYLED_ITEM('overriding color',(#199197),#104181, + #198353); +#199197 = PRESENTATION_STYLE_ASSIGNMENT((#199198)); +#199198 = SURFACE_STYLE_USAGE(.BOTH.,#199199); +#199199 = SURFACE_SIDE_STYLE('',(#199200)); +#199200 = SURFACE_STYLE_FILL_AREA(#199201); +#199201 = FILL_AREA_STYLE('',(#199202)); +#199202 = FILL_AREA_STYLE_COLOUR('',#198418); +#199203 = OVER_RIDING_STYLED_ITEM('overriding color',(#199204),#104256, + #198353); +#199204 = PRESENTATION_STYLE_ASSIGNMENT((#199205)); +#199205 = SURFACE_STYLE_USAGE(.BOTH.,#199206); +#199206 = SURFACE_SIDE_STYLE('',(#199207)); +#199207 = SURFACE_STYLE_FILL_AREA(#199208); +#199208 = FILL_AREA_STYLE('',(#199209)); +#199209 = FILL_AREA_STYLE_COLOUR('',#198418); +#199210 = OVER_RIDING_STYLED_ITEM('overriding color',(#199211),#104283, + #198353); +#199211 = PRESENTATION_STYLE_ASSIGNMENT((#199212)); +#199212 = SURFACE_STYLE_USAGE(.BOTH.,#199213); +#199213 = SURFACE_SIDE_STYLE('',(#199214)); +#199214 = SURFACE_STYLE_FILL_AREA(#199215); +#199215 = FILL_AREA_STYLE('',(#199216)); +#199216 = FILL_AREA_STYLE_COLOUR('',#198418); +#199217 = OVER_RIDING_STYLED_ITEM('overriding color',(#199218),#104338, + #198353); +#199218 = PRESENTATION_STYLE_ASSIGNMENT((#199219)); +#199219 = SURFACE_STYLE_USAGE(.BOTH.,#199220); +#199220 = SURFACE_SIDE_STYLE('',(#199221)); +#199221 = SURFACE_STYLE_FILL_AREA(#199222); +#199222 = FILL_AREA_STYLE('',(#199223)); +#199223 = FILL_AREA_STYLE_COLOUR('',#198418); +#199224 = OVER_RIDING_STYLED_ITEM('overriding color',(#199225),#104345, + #198353); +#199225 = PRESENTATION_STYLE_ASSIGNMENT((#199226)); +#199226 = SURFACE_STYLE_USAGE(.BOTH.,#199227); +#199227 = SURFACE_SIDE_STYLE('',(#199228)); +#199228 = SURFACE_STYLE_FILL_AREA(#199229); +#199229 = FILL_AREA_STYLE('',(#199230)); +#199230 = FILL_AREA_STYLE_COLOUR('',#198418); +#199231 = OVER_RIDING_STYLED_ITEM('overriding color',(#199232),#104352, + #198353); +#199232 = PRESENTATION_STYLE_ASSIGNMENT((#199233)); +#199233 = SURFACE_STYLE_USAGE(.BOTH.,#199234); +#199234 = SURFACE_SIDE_STYLE('',(#199235)); +#199235 = SURFACE_STYLE_FILL_AREA(#199236); +#199236 = FILL_AREA_STYLE('',(#199237)); +#199237 = FILL_AREA_STYLE_COLOUR('',#198418); +#199238 = OVER_RIDING_STYLED_ITEM('overriding color',(#199239),#104461, + #198353); +#199239 = PRESENTATION_STYLE_ASSIGNMENT((#199240)); +#199240 = SURFACE_STYLE_USAGE(.BOTH.,#199241); +#199241 = SURFACE_SIDE_STYLE('',(#199242)); +#199242 = SURFACE_STYLE_FILL_AREA(#199243); +#199243 = FILL_AREA_STYLE('',(#199244)); +#199244 = FILL_AREA_STYLE_COLOUR('',#198418); +#199245 = OVER_RIDING_STYLED_ITEM('overriding color',(#199246),#104565, + #198353); +#199246 = PRESENTATION_STYLE_ASSIGNMENT((#199247)); +#199247 = SURFACE_STYLE_USAGE(.BOTH.,#199248); +#199248 = SURFACE_SIDE_STYLE('',(#199249)); +#199249 = SURFACE_STYLE_FILL_AREA(#199250); +#199250 = FILL_AREA_STYLE('',(#199251)); +#199251 = FILL_AREA_STYLE_COLOUR('',#198418); +#199252 = OVER_RIDING_STYLED_ITEM('overriding color',(#199253),#104644, + #198353); +#199253 = PRESENTATION_STYLE_ASSIGNMENT((#199254)); +#199254 = SURFACE_STYLE_USAGE(.BOTH.,#199255); +#199255 = SURFACE_SIDE_STYLE('',(#199256)); +#199256 = SURFACE_STYLE_FILL_AREA(#199257); +#199257 = FILL_AREA_STYLE('',(#199258)); +#199258 = FILL_AREA_STYLE_COLOUR('',#198418); +#199259 = OVER_RIDING_STYLED_ITEM('overriding color',(#199260),#104723, + #198353); +#199260 = PRESENTATION_STYLE_ASSIGNMENT((#199261)); +#199261 = SURFACE_STYLE_USAGE(.BOTH.,#199262); +#199262 = SURFACE_SIDE_STYLE('',(#199263)); +#199263 = SURFACE_STYLE_FILL_AREA(#199264); +#199264 = FILL_AREA_STYLE('',(#199265)); +#199265 = FILL_AREA_STYLE_COLOUR('',#198418); +#199266 = OVER_RIDING_STYLED_ITEM('overriding color',(#199267),#104798, + #198353); +#199267 = PRESENTATION_STYLE_ASSIGNMENT((#199268)); +#199268 = SURFACE_STYLE_USAGE(.BOTH.,#199269); +#199269 = SURFACE_SIDE_STYLE('',(#199270)); +#199270 = SURFACE_STYLE_FILL_AREA(#199271); +#199271 = FILL_AREA_STYLE('',(#199272)); +#199272 = FILL_AREA_STYLE_COLOUR('',#198418); +#199273 = OVER_RIDING_STYLED_ITEM('overriding color',(#199274),#104873, + #198353); +#199274 = PRESENTATION_STYLE_ASSIGNMENT((#199275)); +#199275 = SURFACE_STYLE_USAGE(.BOTH.,#199276); +#199276 = SURFACE_SIDE_STYLE('',(#199277)); +#199277 = SURFACE_STYLE_FILL_AREA(#199278); +#199278 = FILL_AREA_STYLE('',(#199279)); +#199279 = FILL_AREA_STYLE_COLOUR('',#198418); +#199280 = OVER_RIDING_STYLED_ITEM('overriding color',(#199281),#104947, + #198353); +#199281 = PRESENTATION_STYLE_ASSIGNMENT((#199282)); +#199282 = SURFACE_STYLE_USAGE(.BOTH.,#199283); +#199283 = SURFACE_SIDE_STYLE('',(#199284)); +#199284 = SURFACE_STYLE_FILL_AREA(#199285); +#199285 = FILL_AREA_STYLE('',(#199286)); +#199286 = FILL_AREA_STYLE_COLOUR('',#198418); +#199287 = OVER_RIDING_STYLED_ITEM('overriding color',(#199288),#105021, + #198353); +#199288 = PRESENTATION_STYLE_ASSIGNMENT((#199289)); +#199289 = SURFACE_STYLE_USAGE(.BOTH.,#199290); +#199290 = SURFACE_SIDE_STYLE('',(#199291)); +#199291 = SURFACE_STYLE_FILL_AREA(#199292); +#199292 = FILL_AREA_STYLE('',(#199293)); +#199293 = FILL_AREA_STYLE_COLOUR('',#198418); +#199294 = OVER_RIDING_STYLED_ITEM('overriding color',(#199295),#105096, + #198353); +#199295 = PRESENTATION_STYLE_ASSIGNMENT((#199296)); +#199296 = SURFACE_STYLE_USAGE(.BOTH.,#199297); +#199297 = SURFACE_SIDE_STYLE('',(#199298)); +#199298 = SURFACE_STYLE_FILL_AREA(#199299); +#199299 = FILL_AREA_STYLE('',(#199300)); +#199300 = FILL_AREA_STYLE_COLOUR('',#198418); +#199301 = OVER_RIDING_STYLED_ITEM('overriding color',(#199302),#105123, + #198353); +#199302 = PRESENTATION_STYLE_ASSIGNMENT((#199303)); +#199303 = SURFACE_STYLE_USAGE(.BOTH.,#199304); +#199304 = SURFACE_SIDE_STYLE('',(#199305)); +#199305 = SURFACE_STYLE_FILL_AREA(#199306); +#199306 = FILL_AREA_STYLE('',(#199307)); +#199307 = FILL_AREA_STYLE_COLOUR('',#198418); +#199308 = OVER_RIDING_STYLED_ITEM('overriding color',(#199309),#105178, + #198353); +#199309 = PRESENTATION_STYLE_ASSIGNMENT((#199310)); +#199310 = SURFACE_STYLE_USAGE(.BOTH.,#199311); +#199311 = SURFACE_SIDE_STYLE('',(#199312)); +#199312 = SURFACE_STYLE_FILL_AREA(#199313); +#199313 = FILL_AREA_STYLE('',(#199314)); +#199314 = FILL_AREA_STYLE_COLOUR('',#198418); +#199315 = OVER_RIDING_STYLED_ITEM('overriding color',(#199316),#105185, + #198353); +#199316 = PRESENTATION_STYLE_ASSIGNMENT((#199317)); +#199317 = SURFACE_STYLE_USAGE(.BOTH.,#199318); +#199318 = SURFACE_SIDE_STYLE('',(#199319)); +#199319 = SURFACE_STYLE_FILL_AREA(#199320); +#199320 = FILL_AREA_STYLE('',(#199321)); +#199321 = FILL_AREA_STYLE_COLOUR('',#198418); +#199322 = OVER_RIDING_STYLED_ITEM('overriding color',(#199323),#105192, + #198353); +#199323 = PRESENTATION_STYLE_ASSIGNMENT((#199324)); +#199324 = SURFACE_STYLE_USAGE(.BOTH.,#199325); +#199325 = SURFACE_SIDE_STYLE('',(#199326)); +#199326 = SURFACE_STYLE_FILL_AREA(#199327); +#199327 = FILL_AREA_STYLE('',(#199328)); +#199328 = FILL_AREA_STYLE_COLOUR('',#198418); +#199329 = OVER_RIDING_STYLED_ITEM('overriding color',(#199330),#105301, + #198353); +#199330 = PRESENTATION_STYLE_ASSIGNMENT((#199331)); +#199331 = SURFACE_STYLE_USAGE(.BOTH.,#199332); +#199332 = SURFACE_SIDE_STYLE('',(#199333)); +#199333 = SURFACE_STYLE_FILL_AREA(#199334); +#199334 = FILL_AREA_STYLE('',(#199335)); +#199335 = FILL_AREA_STYLE_COLOUR('',#198418); +#199336 = OVER_RIDING_STYLED_ITEM('overriding color',(#199337),#105405, + #198353); +#199337 = PRESENTATION_STYLE_ASSIGNMENT((#199338)); +#199338 = SURFACE_STYLE_USAGE(.BOTH.,#199339); +#199339 = SURFACE_SIDE_STYLE('',(#199340)); +#199340 = SURFACE_STYLE_FILL_AREA(#199341); +#199341 = FILL_AREA_STYLE('',(#199342)); +#199342 = FILL_AREA_STYLE_COLOUR('',#198418); +#199343 = OVER_RIDING_STYLED_ITEM('overriding color',(#199344),#105484, + #198353); +#199344 = PRESENTATION_STYLE_ASSIGNMENT((#199345)); +#199345 = SURFACE_STYLE_USAGE(.BOTH.,#199346); +#199346 = SURFACE_SIDE_STYLE('',(#199347)); +#199347 = SURFACE_STYLE_FILL_AREA(#199348); +#199348 = FILL_AREA_STYLE('',(#199349)); +#199349 = FILL_AREA_STYLE_COLOUR('',#198418); +#199350 = OVER_RIDING_STYLED_ITEM('overriding color',(#199351),#105563, + #198353); +#199351 = PRESENTATION_STYLE_ASSIGNMENT((#199352)); +#199352 = SURFACE_STYLE_USAGE(.BOTH.,#199353); +#199353 = SURFACE_SIDE_STYLE('',(#199354)); +#199354 = SURFACE_STYLE_FILL_AREA(#199355); +#199355 = FILL_AREA_STYLE('',(#199356)); +#199356 = FILL_AREA_STYLE_COLOUR('',#198418); +#199357 = OVER_RIDING_STYLED_ITEM('overriding color',(#199358),#105638, + #198353); +#199358 = PRESENTATION_STYLE_ASSIGNMENT((#199359)); +#199359 = SURFACE_STYLE_USAGE(.BOTH.,#199360); +#199360 = SURFACE_SIDE_STYLE('',(#199361)); +#199361 = SURFACE_STYLE_FILL_AREA(#199362); +#199362 = FILL_AREA_STYLE('',(#199363)); +#199363 = FILL_AREA_STYLE_COLOUR('',#198418); +#199364 = OVER_RIDING_STYLED_ITEM('overriding color',(#199365),#105713, + #198353); +#199365 = PRESENTATION_STYLE_ASSIGNMENT((#199366)); +#199366 = SURFACE_STYLE_USAGE(.BOTH.,#199367); +#199367 = SURFACE_SIDE_STYLE('',(#199368)); +#199368 = SURFACE_STYLE_FILL_AREA(#199369); +#199369 = FILL_AREA_STYLE('',(#199370)); +#199370 = FILL_AREA_STYLE_COLOUR('',#198418); +#199371 = OVER_RIDING_STYLED_ITEM('overriding color',(#199372),#105787, + #198353); +#199372 = PRESENTATION_STYLE_ASSIGNMENT((#199373)); +#199373 = SURFACE_STYLE_USAGE(.BOTH.,#199374); +#199374 = SURFACE_SIDE_STYLE('',(#199375)); +#199375 = SURFACE_STYLE_FILL_AREA(#199376); +#199376 = FILL_AREA_STYLE('',(#199377)); +#199377 = FILL_AREA_STYLE_COLOUR('',#198418); +#199378 = OVER_RIDING_STYLED_ITEM('overriding color',(#199379),#105861, + #198353); +#199379 = PRESENTATION_STYLE_ASSIGNMENT((#199380)); +#199380 = SURFACE_STYLE_USAGE(.BOTH.,#199381); +#199381 = SURFACE_SIDE_STYLE('',(#199382)); +#199382 = SURFACE_STYLE_FILL_AREA(#199383); +#199383 = FILL_AREA_STYLE('',(#199384)); +#199384 = FILL_AREA_STYLE_COLOUR('',#198418); +#199385 = OVER_RIDING_STYLED_ITEM('overriding color',(#199386),#105936, + #198353); +#199386 = PRESENTATION_STYLE_ASSIGNMENT((#199387)); +#199387 = SURFACE_STYLE_USAGE(.BOTH.,#199388); +#199388 = SURFACE_SIDE_STYLE('',(#199389)); +#199389 = SURFACE_STYLE_FILL_AREA(#199390); +#199390 = FILL_AREA_STYLE('',(#199391)); +#199391 = FILL_AREA_STYLE_COLOUR('',#198418); +#199392 = OVER_RIDING_STYLED_ITEM('overriding color',(#199393),#105963, + #198353); +#199393 = PRESENTATION_STYLE_ASSIGNMENT((#199394)); +#199394 = SURFACE_STYLE_USAGE(.BOTH.,#199395); +#199395 = SURFACE_SIDE_STYLE('',(#199396)); +#199396 = SURFACE_STYLE_FILL_AREA(#199397); +#199397 = FILL_AREA_STYLE('',(#199398)); +#199398 = FILL_AREA_STYLE_COLOUR('',#198418); +#199399 = OVER_RIDING_STYLED_ITEM('overriding color',(#199400),#106018, + #198353); +#199400 = PRESENTATION_STYLE_ASSIGNMENT((#199401)); +#199401 = SURFACE_STYLE_USAGE(.BOTH.,#199402); +#199402 = SURFACE_SIDE_STYLE('',(#199403)); +#199403 = SURFACE_STYLE_FILL_AREA(#199404); +#199404 = FILL_AREA_STYLE('',(#199405)); +#199405 = FILL_AREA_STYLE_COLOUR('',#198418); +#199406 = OVER_RIDING_STYLED_ITEM('overriding color',(#199407),#106025, + #198353); +#199407 = PRESENTATION_STYLE_ASSIGNMENT((#199408)); +#199408 = SURFACE_STYLE_USAGE(.BOTH.,#199409); +#199409 = SURFACE_SIDE_STYLE('',(#199410)); +#199410 = SURFACE_STYLE_FILL_AREA(#199411); +#199411 = FILL_AREA_STYLE('',(#199412)); +#199412 = FILL_AREA_STYLE_COLOUR('',#198418); +#199413 = OVER_RIDING_STYLED_ITEM('overriding color',(#199414),#106032, + #198353); +#199414 = PRESENTATION_STYLE_ASSIGNMENT((#199415)); +#199415 = SURFACE_STYLE_USAGE(.BOTH.,#199416); +#199416 = SURFACE_SIDE_STYLE('',(#199417)); +#199417 = SURFACE_STYLE_FILL_AREA(#199418); +#199418 = FILL_AREA_STYLE('',(#199419)); +#199419 = FILL_AREA_STYLE_COLOUR('',#198418); +#199420 = OVER_RIDING_STYLED_ITEM('overriding color',(#199421),#106141, + #198353); +#199421 = PRESENTATION_STYLE_ASSIGNMENT((#199422)); +#199422 = SURFACE_STYLE_USAGE(.BOTH.,#199423); +#199423 = SURFACE_SIDE_STYLE('',(#199424)); +#199424 = SURFACE_STYLE_FILL_AREA(#199425); +#199425 = FILL_AREA_STYLE('',(#199426)); +#199426 = FILL_AREA_STYLE_COLOUR('',#198418); +#199427 = OVER_RIDING_STYLED_ITEM('overriding color',(#199428),#106245, + #198353); +#199428 = PRESENTATION_STYLE_ASSIGNMENT((#199429)); +#199429 = SURFACE_STYLE_USAGE(.BOTH.,#199430); +#199430 = SURFACE_SIDE_STYLE('',(#199431)); +#199431 = SURFACE_STYLE_FILL_AREA(#199432); +#199432 = FILL_AREA_STYLE('',(#199433)); +#199433 = FILL_AREA_STYLE_COLOUR('',#198418); +#199434 = OVER_RIDING_STYLED_ITEM('overriding color',(#199435),#106324, + #198353); +#199435 = PRESENTATION_STYLE_ASSIGNMENT((#199436)); +#199436 = SURFACE_STYLE_USAGE(.BOTH.,#199437); +#199437 = SURFACE_SIDE_STYLE('',(#199438)); +#199438 = SURFACE_STYLE_FILL_AREA(#199439); +#199439 = FILL_AREA_STYLE('',(#199440)); +#199440 = FILL_AREA_STYLE_COLOUR('',#198418); +#199441 = OVER_RIDING_STYLED_ITEM('overriding color',(#199442),#106403, + #198353); +#199442 = PRESENTATION_STYLE_ASSIGNMENT((#199443)); +#199443 = SURFACE_STYLE_USAGE(.BOTH.,#199444); +#199444 = SURFACE_SIDE_STYLE('',(#199445)); +#199445 = SURFACE_STYLE_FILL_AREA(#199446); +#199446 = FILL_AREA_STYLE('',(#199447)); +#199447 = FILL_AREA_STYLE_COLOUR('',#198418); +#199448 = OVER_RIDING_STYLED_ITEM('overriding color',(#199449),#106478, + #198353); +#199449 = PRESENTATION_STYLE_ASSIGNMENT((#199450)); +#199450 = SURFACE_STYLE_USAGE(.BOTH.,#199451); +#199451 = SURFACE_SIDE_STYLE('',(#199452)); +#199452 = SURFACE_STYLE_FILL_AREA(#199453); +#199453 = FILL_AREA_STYLE('',(#199454)); +#199454 = FILL_AREA_STYLE_COLOUR('',#198418); +#199455 = OVER_RIDING_STYLED_ITEM('overriding color',(#199456),#106553, + #198353); +#199456 = PRESENTATION_STYLE_ASSIGNMENT((#199457)); +#199457 = SURFACE_STYLE_USAGE(.BOTH.,#199458); +#199458 = SURFACE_SIDE_STYLE('',(#199459)); +#199459 = SURFACE_STYLE_FILL_AREA(#199460); +#199460 = FILL_AREA_STYLE('',(#199461)); +#199461 = FILL_AREA_STYLE_COLOUR('',#198418); +#199462 = OVER_RIDING_STYLED_ITEM('overriding color',(#199463),#106627, + #198353); +#199463 = PRESENTATION_STYLE_ASSIGNMENT((#199464)); +#199464 = SURFACE_STYLE_USAGE(.BOTH.,#199465); +#199465 = SURFACE_SIDE_STYLE('',(#199466)); +#199466 = SURFACE_STYLE_FILL_AREA(#199467); +#199467 = FILL_AREA_STYLE('',(#199468)); +#199468 = FILL_AREA_STYLE_COLOUR('',#198418); +#199469 = OVER_RIDING_STYLED_ITEM('overriding color',(#199470),#106701, + #198353); +#199470 = PRESENTATION_STYLE_ASSIGNMENT((#199471)); +#199471 = SURFACE_STYLE_USAGE(.BOTH.,#199472); +#199472 = SURFACE_SIDE_STYLE('',(#199473)); +#199473 = SURFACE_STYLE_FILL_AREA(#199474); +#199474 = FILL_AREA_STYLE('',(#199475)); +#199475 = FILL_AREA_STYLE_COLOUR('',#198418); +#199476 = OVER_RIDING_STYLED_ITEM('overriding color',(#199477),#106776, + #198353); +#199477 = PRESENTATION_STYLE_ASSIGNMENT((#199478)); +#199478 = SURFACE_STYLE_USAGE(.BOTH.,#199479); +#199479 = SURFACE_SIDE_STYLE('',(#199480)); +#199480 = SURFACE_STYLE_FILL_AREA(#199481); +#199481 = FILL_AREA_STYLE('',(#199482)); +#199482 = FILL_AREA_STYLE_COLOUR('',#198418); +#199483 = OVER_RIDING_STYLED_ITEM('overriding color',(#199484),#106803, + #198353); +#199484 = PRESENTATION_STYLE_ASSIGNMENT((#199485)); +#199485 = SURFACE_STYLE_USAGE(.BOTH.,#199486); +#199486 = SURFACE_SIDE_STYLE('',(#199487)); +#199487 = SURFACE_STYLE_FILL_AREA(#199488); +#199488 = FILL_AREA_STYLE('',(#199489)); +#199489 = FILL_AREA_STYLE_COLOUR('',#198418); +#199490 = OVER_RIDING_STYLED_ITEM('overriding color',(#199491),#106858, + #198353); +#199491 = PRESENTATION_STYLE_ASSIGNMENT((#199492)); +#199492 = SURFACE_STYLE_USAGE(.BOTH.,#199493); +#199493 = SURFACE_SIDE_STYLE('',(#199494)); +#199494 = SURFACE_STYLE_FILL_AREA(#199495); +#199495 = FILL_AREA_STYLE('',(#199496)); +#199496 = FILL_AREA_STYLE_COLOUR('',#198418); +#199497 = OVER_RIDING_STYLED_ITEM('overriding color',(#199498),#106865, + #198353); +#199498 = PRESENTATION_STYLE_ASSIGNMENT((#199499)); +#199499 = SURFACE_STYLE_USAGE(.BOTH.,#199500); +#199500 = SURFACE_SIDE_STYLE('',(#199501)); +#199501 = SURFACE_STYLE_FILL_AREA(#199502); +#199502 = FILL_AREA_STYLE('',(#199503)); +#199503 = FILL_AREA_STYLE_COLOUR('',#198418); +#199504 = OVER_RIDING_STYLED_ITEM('overriding color',(#199505),#106872, + #198353); +#199505 = PRESENTATION_STYLE_ASSIGNMENT((#199506)); +#199506 = SURFACE_STYLE_USAGE(.BOTH.,#199507); +#199507 = SURFACE_SIDE_STYLE('',(#199508)); +#199508 = SURFACE_STYLE_FILL_AREA(#199509); +#199509 = FILL_AREA_STYLE('',(#199510)); +#199510 = FILL_AREA_STYLE_COLOUR('',#198418); +#199511 = OVER_RIDING_STYLED_ITEM('overriding color',(#199512),#106981, + #198353); +#199512 = PRESENTATION_STYLE_ASSIGNMENT((#199513)); +#199513 = SURFACE_STYLE_USAGE(.BOTH.,#199514); +#199514 = SURFACE_SIDE_STYLE('',(#199515)); +#199515 = SURFACE_STYLE_FILL_AREA(#199516); +#199516 = FILL_AREA_STYLE('',(#199517)); +#199517 = FILL_AREA_STYLE_COLOUR('',#198418); +#199518 = OVER_RIDING_STYLED_ITEM('overriding color',(#199519),#107085, + #198353); +#199519 = PRESENTATION_STYLE_ASSIGNMENT((#199520)); +#199520 = SURFACE_STYLE_USAGE(.BOTH.,#199521); +#199521 = SURFACE_SIDE_STYLE('',(#199522)); +#199522 = SURFACE_STYLE_FILL_AREA(#199523); +#199523 = FILL_AREA_STYLE('',(#199524)); +#199524 = FILL_AREA_STYLE_COLOUR('',#198418); +#199525 = OVER_RIDING_STYLED_ITEM('overriding color',(#199526),#107164, + #198353); +#199526 = PRESENTATION_STYLE_ASSIGNMENT((#199527)); +#199527 = SURFACE_STYLE_USAGE(.BOTH.,#199528); +#199528 = SURFACE_SIDE_STYLE('',(#199529)); +#199529 = SURFACE_STYLE_FILL_AREA(#199530); +#199530 = FILL_AREA_STYLE('',(#199531)); +#199531 = FILL_AREA_STYLE_COLOUR('',#198418); +#199532 = OVER_RIDING_STYLED_ITEM('overriding color',(#199533),#107243, + #198353); +#199533 = PRESENTATION_STYLE_ASSIGNMENT((#199534)); +#199534 = SURFACE_STYLE_USAGE(.BOTH.,#199535); +#199535 = SURFACE_SIDE_STYLE('',(#199536)); +#199536 = SURFACE_STYLE_FILL_AREA(#199537); +#199537 = FILL_AREA_STYLE('',(#199538)); +#199538 = FILL_AREA_STYLE_COLOUR('',#198418); +#199539 = OVER_RIDING_STYLED_ITEM('overriding color',(#199540),#107318, + #198353); +#199540 = PRESENTATION_STYLE_ASSIGNMENT((#199541)); +#199541 = SURFACE_STYLE_USAGE(.BOTH.,#199542); +#199542 = SURFACE_SIDE_STYLE('',(#199543)); +#199543 = SURFACE_STYLE_FILL_AREA(#199544); +#199544 = FILL_AREA_STYLE('',(#199545)); +#199545 = FILL_AREA_STYLE_COLOUR('',#198418); +#199546 = OVER_RIDING_STYLED_ITEM('overriding color',(#199547),#107393, + #198353); +#199547 = PRESENTATION_STYLE_ASSIGNMENT((#199548)); +#199548 = SURFACE_STYLE_USAGE(.BOTH.,#199549); +#199549 = SURFACE_SIDE_STYLE('',(#199550)); +#199550 = SURFACE_STYLE_FILL_AREA(#199551); +#199551 = FILL_AREA_STYLE('',(#199552)); +#199552 = FILL_AREA_STYLE_COLOUR('',#198418); +#199553 = OVER_RIDING_STYLED_ITEM('overriding color',(#199554),#107467, + #198353); +#199554 = PRESENTATION_STYLE_ASSIGNMENT((#199555)); +#199555 = SURFACE_STYLE_USAGE(.BOTH.,#199556); +#199556 = SURFACE_SIDE_STYLE('',(#199557)); +#199557 = SURFACE_STYLE_FILL_AREA(#199558); +#199558 = FILL_AREA_STYLE('',(#199559)); +#199559 = FILL_AREA_STYLE_COLOUR('',#198418); +#199560 = OVER_RIDING_STYLED_ITEM('overriding color',(#199561),#107541, + #198353); +#199561 = PRESENTATION_STYLE_ASSIGNMENT((#199562)); +#199562 = SURFACE_STYLE_USAGE(.BOTH.,#199563); +#199563 = SURFACE_SIDE_STYLE('',(#199564)); +#199564 = SURFACE_STYLE_FILL_AREA(#199565); +#199565 = FILL_AREA_STYLE('',(#199566)); +#199566 = FILL_AREA_STYLE_COLOUR('',#198418); +#199567 = OVER_RIDING_STYLED_ITEM('overriding color',(#199568),#107616, + #198353); +#199568 = PRESENTATION_STYLE_ASSIGNMENT((#199569)); +#199569 = SURFACE_STYLE_USAGE(.BOTH.,#199570); +#199570 = SURFACE_SIDE_STYLE('',(#199571)); +#199571 = SURFACE_STYLE_FILL_AREA(#199572); +#199572 = FILL_AREA_STYLE('',(#199573)); +#199573 = FILL_AREA_STYLE_COLOUR('',#198418); +#199574 = OVER_RIDING_STYLED_ITEM('overriding color',(#199575),#107643, + #198353); +#199575 = PRESENTATION_STYLE_ASSIGNMENT((#199576)); +#199576 = SURFACE_STYLE_USAGE(.BOTH.,#199577); +#199577 = SURFACE_SIDE_STYLE('',(#199578)); +#199578 = SURFACE_STYLE_FILL_AREA(#199579); +#199579 = FILL_AREA_STYLE('',(#199580)); +#199580 = FILL_AREA_STYLE_COLOUR('',#198418); +#199581 = OVER_RIDING_STYLED_ITEM('overriding color',(#199582),#107698, + #198353); +#199582 = PRESENTATION_STYLE_ASSIGNMENT((#199583)); +#199583 = SURFACE_STYLE_USAGE(.BOTH.,#199584); +#199584 = SURFACE_SIDE_STYLE('',(#199585)); +#199585 = SURFACE_STYLE_FILL_AREA(#199586); +#199586 = FILL_AREA_STYLE('',(#199587)); +#199587 = FILL_AREA_STYLE_COLOUR('',#198418); +#199588 = OVER_RIDING_STYLED_ITEM('overriding color',(#199589),#107705, + #198353); +#199589 = PRESENTATION_STYLE_ASSIGNMENT((#199590)); +#199590 = SURFACE_STYLE_USAGE(.BOTH.,#199591); +#199591 = SURFACE_SIDE_STYLE('',(#199592)); +#199592 = SURFACE_STYLE_FILL_AREA(#199593); +#199593 = FILL_AREA_STYLE('',(#199594)); +#199594 = FILL_AREA_STYLE_COLOUR('',#198418); +#199595 = OVER_RIDING_STYLED_ITEM('overriding color',(#199596),#107712, + #198353); +#199596 = PRESENTATION_STYLE_ASSIGNMENT((#199597)); +#199597 = SURFACE_STYLE_USAGE(.BOTH.,#199598); +#199598 = SURFACE_SIDE_STYLE('',(#199599)); +#199599 = SURFACE_STYLE_FILL_AREA(#199600); +#199600 = FILL_AREA_STYLE('',(#199601)); +#199601 = FILL_AREA_STYLE_COLOUR('',#198418); +#199602 = OVER_RIDING_STYLED_ITEM('overriding color',(#199603),#107821, + #198353); +#199603 = PRESENTATION_STYLE_ASSIGNMENT((#199604)); +#199604 = SURFACE_STYLE_USAGE(.BOTH.,#199605); +#199605 = SURFACE_SIDE_STYLE('',(#199606)); +#199606 = SURFACE_STYLE_FILL_AREA(#199607); +#199607 = FILL_AREA_STYLE('',(#199608)); +#199608 = FILL_AREA_STYLE_COLOUR('',#198418); +#199609 = OVER_RIDING_STYLED_ITEM('overriding color',(#199610),#107925, + #198353); +#199610 = PRESENTATION_STYLE_ASSIGNMENT((#199611)); +#199611 = SURFACE_STYLE_USAGE(.BOTH.,#199612); +#199612 = SURFACE_SIDE_STYLE('',(#199613)); +#199613 = SURFACE_STYLE_FILL_AREA(#199614); +#199614 = FILL_AREA_STYLE('',(#199615)); +#199615 = FILL_AREA_STYLE_COLOUR('',#198418); +#199616 = OVER_RIDING_STYLED_ITEM('overriding color',(#199617),#108004, + #198353); +#199617 = PRESENTATION_STYLE_ASSIGNMENT((#199618)); +#199618 = SURFACE_STYLE_USAGE(.BOTH.,#199619); +#199619 = SURFACE_SIDE_STYLE('',(#199620)); +#199620 = SURFACE_STYLE_FILL_AREA(#199621); +#199621 = FILL_AREA_STYLE('',(#199622)); +#199622 = FILL_AREA_STYLE_COLOUR('',#198418); +#199623 = OVER_RIDING_STYLED_ITEM('overriding color',(#199624),#108083, + #198353); +#199624 = PRESENTATION_STYLE_ASSIGNMENT((#199625)); +#199625 = SURFACE_STYLE_USAGE(.BOTH.,#199626); +#199626 = SURFACE_SIDE_STYLE('',(#199627)); +#199627 = SURFACE_STYLE_FILL_AREA(#199628); +#199628 = FILL_AREA_STYLE('',(#199629)); +#199629 = FILL_AREA_STYLE_COLOUR('',#198418); +#199630 = OVER_RIDING_STYLED_ITEM('overriding color',(#199631),#108158, + #198353); +#199631 = PRESENTATION_STYLE_ASSIGNMENT((#199632)); +#199632 = SURFACE_STYLE_USAGE(.BOTH.,#199633); +#199633 = SURFACE_SIDE_STYLE('',(#199634)); +#199634 = SURFACE_STYLE_FILL_AREA(#199635); +#199635 = FILL_AREA_STYLE('',(#199636)); +#199636 = FILL_AREA_STYLE_COLOUR('',#198418); +#199637 = OVER_RIDING_STYLED_ITEM('overriding color',(#199638),#108233, + #198353); +#199638 = PRESENTATION_STYLE_ASSIGNMENT((#199639)); +#199639 = SURFACE_STYLE_USAGE(.BOTH.,#199640); +#199640 = SURFACE_SIDE_STYLE('',(#199641)); +#199641 = SURFACE_STYLE_FILL_AREA(#199642); +#199642 = FILL_AREA_STYLE('',(#199643)); +#199643 = FILL_AREA_STYLE_COLOUR('',#198418); +#199644 = OVER_RIDING_STYLED_ITEM('overriding color',(#199645),#108307, + #198353); +#199645 = PRESENTATION_STYLE_ASSIGNMENT((#199646)); +#199646 = SURFACE_STYLE_USAGE(.BOTH.,#199647); +#199647 = SURFACE_SIDE_STYLE('',(#199648)); +#199648 = SURFACE_STYLE_FILL_AREA(#199649); +#199649 = FILL_AREA_STYLE('',(#199650)); +#199650 = FILL_AREA_STYLE_COLOUR('',#198418); +#199651 = OVER_RIDING_STYLED_ITEM('overriding color',(#199652),#108381, + #198353); +#199652 = PRESENTATION_STYLE_ASSIGNMENT((#199653)); +#199653 = SURFACE_STYLE_USAGE(.BOTH.,#199654); +#199654 = SURFACE_SIDE_STYLE('',(#199655)); +#199655 = SURFACE_STYLE_FILL_AREA(#199656); +#199656 = FILL_AREA_STYLE('',(#199657)); +#199657 = FILL_AREA_STYLE_COLOUR('',#198418); +#199658 = OVER_RIDING_STYLED_ITEM('overriding color',(#199659),#108456, + #198353); +#199659 = PRESENTATION_STYLE_ASSIGNMENT((#199660)); +#199660 = SURFACE_STYLE_USAGE(.BOTH.,#199661); +#199661 = SURFACE_SIDE_STYLE('',(#199662)); +#199662 = SURFACE_STYLE_FILL_AREA(#199663); +#199663 = FILL_AREA_STYLE('',(#199664)); +#199664 = FILL_AREA_STYLE_COLOUR('',#198418); +#199665 = OVER_RIDING_STYLED_ITEM('overriding color',(#199666),#108483, + #198353); +#199666 = PRESENTATION_STYLE_ASSIGNMENT((#199667)); +#199667 = SURFACE_STYLE_USAGE(.BOTH.,#199668); +#199668 = SURFACE_SIDE_STYLE('',(#199669)); +#199669 = SURFACE_STYLE_FILL_AREA(#199670); +#199670 = FILL_AREA_STYLE('',(#199671)); +#199671 = FILL_AREA_STYLE_COLOUR('',#198418); +#199672 = OVER_RIDING_STYLED_ITEM('overriding color',(#199673),#108538, + #198353); +#199673 = PRESENTATION_STYLE_ASSIGNMENT((#199674)); +#199674 = SURFACE_STYLE_USAGE(.BOTH.,#199675); +#199675 = SURFACE_SIDE_STYLE('',(#199676)); +#199676 = SURFACE_STYLE_FILL_AREA(#199677); +#199677 = FILL_AREA_STYLE('',(#199678)); +#199678 = FILL_AREA_STYLE_COLOUR('',#198418); +#199679 = OVER_RIDING_STYLED_ITEM('overriding color',(#199680),#108545, + #198353); +#199680 = PRESENTATION_STYLE_ASSIGNMENT((#199681)); +#199681 = SURFACE_STYLE_USAGE(.BOTH.,#199682); +#199682 = SURFACE_SIDE_STYLE('',(#199683)); +#199683 = SURFACE_STYLE_FILL_AREA(#199684); +#199684 = FILL_AREA_STYLE('',(#199685)); +#199685 = FILL_AREA_STYLE_COLOUR('',#198418); +#199686 = OVER_RIDING_STYLED_ITEM('overriding color',(#199687),#108552, + #198353); +#199687 = PRESENTATION_STYLE_ASSIGNMENT((#199688)); +#199688 = SURFACE_STYLE_USAGE(.BOTH.,#199689); +#199689 = SURFACE_SIDE_STYLE('',(#199690)); +#199690 = SURFACE_STYLE_FILL_AREA(#199691); +#199691 = FILL_AREA_STYLE('',(#199692)); +#199692 = FILL_AREA_STYLE_COLOUR('',#198418); +#199693 = OVER_RIDING_STYLED_ITEM('overriding color',(#199694),#108661, + #198353); +#199694 = PRESENTATION_STYLE_ASSIGNMENT((#199695)); +#199695 = SURFACE_STYLE_USAGE(.BOTH.,#199696); +#199696 = SURFACE_SIDE_STYLE('',(#199697)); +#199697 = SURFACE_STYLE_FILL_AREA(#199698); +#199698 = FILL_AREA_STYLE('',(#199699)); +#199699 = FILL_AREA_STYLE_COLOUR('',#198418); +#199700 = OVER_RIDING_STYLED_ITEM('overriding color',(#199701),#108765, + #198353); +#199701 = PRESENTATION_STYLE_ASSIGNMENT((#199702)); +#199702 = SURFACE_STYLE_USAGE(.BOTH.,#199703); +#199703 = SURFACE_SIDE_STYLE('',(#199704)); +#199704 = SURFACE_STYLE_FILL_AREA(#199705); +#199705 = FILL_AREA_STYLE('',(#199706)); +#199706 = FILL_AREA_STYLE_COLOUR('',#198418); +#199707 = OVER_RIDING_STYLED_ITEM('overriding color',(#199708),#108844, + #198353); +#199708 = PRESENTATION_STYLE_ASSIGNMENT((#199709)); +#199709 = SURFACE_STYLE_USAGE(.BOTH.,#199710); +#199710 = SURFACE_SIDE_STYLE('',(#199711)); +#199711 = SURFACE_STYLE_FILL_AREA(#199712); +#199712 = FILL_AREA_STYLE('',(#199713)); +#199713 = FILL_AREA_STYLE_COLOUR('',#198418); +#199714 = OVER_RIDING_STYLED_ITEM('overriding color',(#199715),#108923, + #198353); +#199715 = PRESENTATION_STYLE_ASSIGNMENT((#199716)); +#199716 = SURFACE_STYLE_USAGE(.BOTH.,#199717); +#199717 = SURFACE_SIDE_STYLE('',(#199718)); +#199718 = SURFACE_STYLE_FILL_AREA(#199719); +#199719 = FILL_AREA_STYLE('',(#199720)); +#199720 = FILL_AREA_STYLE_COLOUR('',#198418); +#199721 = OVER_RIDING_STYLED_ITEM('overriding color',(#199722),#108998, + #198353); +#199722 = PRESENTATION_STYLE_ASSIGNMENT((#199723)); +#199723 = SURFACE_STYLE_USAGE(.BOTH.,#199724); +#199724 = SURFACE_SIDE_STYLE('',(#199725)); +#199725 = SURFACE_STYLE_FILL_AREA(#199726); +#199726 = FILL_AREA_STYLE('',(#199727)); +#199727 = FILL_AREA_STYLE_COLOUR('',#198418); +#199728 = OVER_RIDING_STYLED_ITEM('overriding color',(#199729),#109073, + #198353); +#199729 = PRESENTATION_STYLE_ASSIGNMENT((#199730)); +#199730 = SURFACE_STYLE_USAGE(.BOTH.,#199731); +#199731 = SURFACE_SIDE_STYLE('',(#199732)); +#199732 = SURFACE_STYLE_FILL_AREA(#199733); +#199733 = FILL_AREA_STYLE('',(#199734)); +#199734 = FILL_AREA_STYLE_COLOUR('',#198418); +#199735 = OVER_RIDING_STYLED_ITEM('overriding color',(#199736),#109147, + #198353); +#199736 = PRESENTATION_STYLE_ASSIGNMENT((#199737)); +#199737 = SURFACE_STYLE_USAGE(.BOTH.,#199738); +#199738 = SURFACE_SIDE_STYLE('',(#199739)); +#199739 = SURFACE_STYLE_FILL_AREA(#199740); +#199740 = FILL_AREA_STYLE('',(#199741)); +#199741 = FILL_AREA_STYLE_COLOUR('',#198418); +#199742 = OVER_RIDING_STYLED_ITEM('overriding color',(#199743),#109221, + #198353); +#199743 = PRESENTATION_STYLE_ASSIGNMENT((#199744)); +#199744 = SURFACE_STYLE_USAGE(.BOTH.,#199745); +#199745 = SURFACE_SIDE_STYLE('',(#199746)); +#199746 = SURFACE_STYLE_FILL_AREA(#199747); +#199747 = FILL_AREA_STYLE('',(#199748)); +#199748 = FILL_AREA_STYLE_COLOUR('',#198418); +#199749 = OVER_RIDING_STYLED_ITEM('overriding color',(#199750),#109296, + #198353); +#199750 = PRESENTATION_STYLE_ASSIGNMENT((#199751)); +#199751 = SURFACE_STYLE_USAGE(.BOTH.,#199752); +#199752 = SURFACE_SIDE_STYLE('',(#199753)); +#199753 = SURFACE_STYLE_FILL_AREA(#199754); +#199754 = FILL_AREA_STYLE('',(#199755)); +#199755 = FILL_AREA_STYLE_COLOUR('',#198418); +#199756 = OVER_RIDING_STYLED_ITEM('overriding color',(#199757),#109323, + #198353); +#199757 = PRESENTATION_STYLE_ASSIGNMENT((#199758)); +#199758 = SURFACE_STYLE_USAGE(.BOTH.,#199759); +#199759 = SURFACE_SIDE_STYLE('',(#199760)); +#199760 = SURFACE_STYLE_FILL_AREA(#199761); +#199761 = FILL_AREA_STYLE('',(#199762)); +#199762 = FILL_AREA_STYLE_COLOUR('',#198418); +#199763 = OVER_RIDING_STYLED_ITEM('overriding color',(#199764),#109378, + #198353); +#199764 = PRESENTATION_STYLE_ASSIGNMENT((#199765)); +#199765 = SURFACE_STYLE_USAGE(.BOTH.,#199766); +#199766 = SURFACE_SIDE_STYLE('',(#199767)); +#199767 = SURFACE_STYLE_FILL_AREA(#199768); +#199768 = FILL_AREA_STYLE('',(#199769)); +#199769 = FILL_AREA_STYLE_COLOUR('',#198418); +#199770 = OVER_RIDING_STYLED_ITEM('overriding color',(#199771),#109385, + #198353); +#199771 = PRESENTATION_STYLE_ASSIGNMENT((#199772)); +#199772 = SURFACE_STYLE_USAGE(.BOTH.,#199773); +#199773 = SURFACE_SIDE_STYLE('',(#199774)); +#199774 = SURFACE_STYLE_FILL_AREA(#199775); +#199775 = FILL_AREA_STYLE('',(#199776)); +#199776 = FILL_AREA_STYLE_COLOUR('',#198418); +#199777 = OVER_RIDING_STYLED_ITEM('overriding color',(#199778),#109392, + #198353); +#199778 = PRESENTATION_STYLE_ASSIGNMENT((#199779)); +#199779 = SURFACE_STYLE_USAGE(.BOTH.,#199780); +#199780 = SURFACE_SIDE_STYLE('',(#199781)); +#199781 = SURFACE_STYLE_FILL_AREA(#199782); +#199782 = FILL_AREA_STYLE('',(#199783)); +#199783 = FILL_AREA_STYLE_COLOUR('',#198418); +#199784 = OVER_RIDING_STYLED_ITEM('overriding color',(#199785),#109501, + #198353); +#199785 = PRESENTATION_STYLE_ASSIGNMENT((#199786)); +#199786 = SURFACE_STYLE_USAGE(.BOTH.,#199787); +#199787 = SURFACE_SIDE_STYLE('',(#199788)); +#199788 = SURFACE_STYLE_FILL_AREA(#199789); +#199789 = FILL_AREA_STYLE('',(#199790)); +#199790 = FILL_AREA_STYLE_COLOUR('',#198418); +#199791 = OVER_RIDING_STYLED_ITEM('overriding color',(#199792),#109605, + #198353); +#199792 = PRESENTATION_STYLE_ASSIGNMENT((#199793)); +#199793 = SURFACE_STYLE_USAGE(.BOTH.,#199794); +#199794 = SURFACE_SIDE_STYLE('',(#199795)); +#199795 = SURFACE_STYLE_FILL_AREA(#199796); +#199796 = FILL_AREA_STYLE('',(#199797)); +#199797 = FILL_AREA_STYLE_COLOUR('',#198418); +#199798 = OVER_RIDING_STYLED_ITEM('overriding color',(#199799),#109684, + #198353); +#199799 = PRESENTATION_STYLE_ASSIGNMENT((#199800)); +#199800 = SURFACE_STYLE_USAGE(.BOTH.,#199801); +#199801 = SURFACE_SIDE_STYLE('',(#199802)); +#199802 = SURFACE_STYLE_FILL_AREA(#199803); +#199803 = FILL_AREA_STYLE('',(#199804)); +#199804 = FILL_AREA_STYLE_COLOUR('',#198418); +#199805 = OVER_RIDING_STYLED_ITEM('overriding color',(#199806),#109763, + #198353); +#199806 = PRESENTATION_STYLE_ASSIGNMENT((#199807)); +#199807 = SURFACE_STYLE_USAGE(.BOTH.,#199808); +#199808 = SURFACE_SIDE_STYLE('',(#199809)); +#199809 = SURFACE_STYLE_FILL_AREA(#199810); +#199810 = FILL_AREA_STYLE('',(#199811)); +#199811 = FILL_AREA_STYLE_COLOUR('',#198418); +#199812 = OVER_RIDING_STYLED_ITEM('overriding color',(#199813),#109838, + #198353); +#199813 = PRESENTATION_STYLE_ASSIGNMENT((#199814)); +#199814 = SURFACE_STYLE_USAGE(.BOTH.,#199815); +#199815 = SURFACE_SIDE_STYLE('',(#199816)); +#199816 = SURFACE_STYLE_FILL_AREA(#199817); +#199817 = FILL_AREA_STYLE('',(#199818)); +#199818 = FILL_AREA_STYLE_COLOUR('',#198418); +#199819 = OVER_RIDING_STYLED_ITEM('overriding color',(#199820),#109913, + #198353); +#199820 = PRESENTATION_STYLE_ASSIGNMENT((#199821)); +#199821 = SURFACE_STYLE_USAGE(.BOTH.,#199822); +#199822 = SURFACE_SIDE_STYLE('',(#199823)); +#199823 = SURFACE_STYLE_FILL_AREA(#199824); +#199824 = FILL_AREA_STYLE('',(#199825)); +#199825 = FILL_AREA_STYLE_COLOUR('',#198418); +#199826 = OVER_RIDING_STYLED_ITEM('overriding color',(#199827),#109987, + #198353); +#199827 = PRESENTATION_STYLE_ASSIGNMENT((#199828)); +#199828 = SURFACE_STYLE_USAGE(.BOTH.,#199829); +#199829 = SURFACE_SIDE_STYLE('',(#199830)); +#199830 = SURFACE_STYLE_FILL_AREA(#199831); +#199831 = FILL_AREA_STYLE('',(#199832)); +#199832 = FILL_AREA_STYLE_COLOUR('',#198418); +#199833 = OVER_RIDING_STYLED_ITEM('overriding color',(#199834),#110061, + #198353); +#199834 = PRESENTATION_STYLE_ASSIGNMENT((#199835)); +#199835 = SURFACE_STYLE_USAGE(.BOTH.,#199836); +#199836 = SURFACE_SIDE_STYLE('',(#199837)); +#199837 = SURFACE_STYLE_FILL_AREA(#199838); +#199838 = FILL_AREA_STYLE('',(#199839)); +#199839 = FILL_AREA_STYLE_COLOUR('',#198418); +#199840 = OVER_RIDING_STYLED_ITEM('overriding color',(#199841),#110136, + #198353); +#199841 = PRESENTATION_STYLE_ASSIGNMENT((#199842)); +#199842 = SURFACE_STYLE_USAGE(.BOTH.,#199843); +#199843 = SURFACE_SIDE_STYLE('',(#199844)); +#199844 = SURFACE_STYLE_FILL_AREA(#199845); +#199845 = FILL_AREA_STYLE('',(#199846)); +#199846 = FILL_AREA_STYLE_COLOUR('',#198418); +#199847 = OVER_RIDING_STYLED_ITEM('overriding color',(#199848),#110163, + #198353); +#199848 = PRESENTATION_STYLE_ASSIGNMENT((#199849)); +#199849 = SURFACE_STYLE_USAGE(.BOTH.,#199850); +#199850 = SURFACE_SIDE_STYLE('',(#199851)); +#199851 = SURFACE_STYLE_FILL_AREA(#199852); +#199852 = FILL_AREA_STYLE('',(#199853)); +#199853 = FILL_AREA_STYLE_COLOUR('',#198418); +#199854 = OVER_RIDING_STYLED_ITEM('overriding color',(#199855),#110218, + #198353); +#199855 = PRESENTATION_STYLE_ASSIGNMENT((#199856)); +#199856 = SURFACE_STYLE_USAGE(.BOTH.,#199857); +#199857 = SURFACE_SIDE_STYLE('',(#199858)); +#199858 = SURFACE_STYLE_FILL_AREA(#199859); +#199859 = FILL_AREA_STYLE('',(#199860)); +#199860 = FILL_AREA_STYLE_COLOUR('',#198418); +#199861 = OVER_RIDING_STYLED_ITEM('overriding color',(#199862),#110225, + #198353); +#199862 = PRESENTATION_STYLE_ASSIGNMENT((#199863)); +#199863 = SURFACE_STYLE_USAGE(.BOTH.,#199864); +#199864 = SURFACE_SIDE_STYLE('',(#199865)); +#199865 = SURFACE_STYLE_FILL_AREA(#199866); +#199866 = FILL_AREA_STYLE('',(#199867)); +#199867 = FILL_AREA_STYLE_COLOUR('',#198418); +#199868 = OVER_RIDING_STYLED_ITEM('overriding color',(#199869),#110232, + #198353); +#199869 = PRESENTATION_STYLE_ASSIGNMENT((#199870)); +#199870 = SURFACE_STYLE_USAGE(.BOTH.,#199871); +#199871 = SURFACE_SIDE_STYLE('',(#199872)); +#199872 = SURFACE_STYLE_FILL_AREA(#199873); +#199873 = FILL_AREA_STYLE('',(#199874)); +#199874 = FILL_AREA_STYLE_COLOUR('',#198418); +#199875 = OVER_RIDING_STYLED_ITEM('overriding color',(#199876),#110341, + #198353); +#199876 = PRESENTATION_STYLE_ASSIGNMENT((#199877)); +#199877 = SURFACE_STYLE_USAGE(.BOTH.,#199878); +#199878 = SURFACE_SIDE_STYLE('',(#199879)); +#199879 = SURFACE_STYLE_FILL_AREA(#199880); +#199880 = FILL_AREA_STYLE('',(#199881)); +#199881 = FILL_AREA_STYLE_COLOUR('',#198418); +#199882 = OVER_RIDING_STYLED_ITEM('overriding color',(#199883),#110445, + #198353); +#199883 = PRESENTATION_STYLE_ASSIGNMENT((#199884)); +#199884 = SURFACE_STYLE_USAGE(.BOTH.,#199885); +#199885 = SURFACE_SIDE_STYLE('',(#199886)); +#199886 = SURFACE_STYLE_FILL_AREA(#199887); +#199887 = FILL_AREA_STYLE('',(#199888)); +#199888 = FILL_AREA_STYLE_COLOUR('',#198418); +#199889 = OVER_RIDING_STYLED_ITEM('overriding color',(#199890),#110524, + #198353); +#199890 = PRESENTATION_STYLE_ASSIGNMENT((#199891)); +#199891 = SURFACE_STYLE_USAGE(.BOTH.,#199892); +#199892 = SURFACE_SIDE_STYLE('',(#199893)); +#199893 = SURFACE_STYLE_FILL_AREA(#199894); +#199894 = FILL_AREA_STYLE('',(#199895)); +#199895 = FILL_AREA_STYLE_COLOUR('',#198418); +#199896 = OVER_RIDING_STYLED_ITEM('overriding color',(#199897),#110603, + #198353); +#199897 = PRESENTATION_STYLE_ASSIGNMENT((#199898)); +#199898 = SURFACE_STYLE_USAGE(.BOTH.,#199899); +#199899 = SURFACE_SIDE_STYLE('',(#199900)); +#199900 = SURFACE_STYLE_FILL_AREA(#199901); +#199901 = FILL_AREA_STYLE('',(#199902)); +#199902 = FILL_AREA_STYLE_COLOUR('',#198418); +#199903 = OVER_RIDING_STYLED_ITEM('overriding color',(#199904),#110678, + #198353); +#199904 = PRESENTATION_STYLE_ASSIGNMENT((#199905)); +#199905 = SURFACE_STYLE_USAGE(.BOTH.,#199906); +#199906 = SURFACE_SIDE_STYLE('',(#199907)); +#199907 = SURFACE_STYLE_FILL_AREA(#199908); +#199908 = FILL_AREA_STYLE('',(#199909)); +#199909 = FILL_AREA_STYLE_COLOUR('',#198418); +#199910 = OVER_RIDING_STYLED_ITEM('overriding color',(#199911),#110753, + #198353); +#199911 = PRESENTATION_STYLE_ASSIGNMENT((#199912)); +#199912 = SURFACE_STYLE_USAGE(.BOTH.,#199913); +#199913 = SURFACE_SIDE_STYLE('',(#199914)); +#199914 = SURFACE_STYLE_FILL_AREA(#199915); +#199915 = FILL_AREA_STYLE('',(#199916)); +#199916 = FILL_AREA_STYLE_COLOUR('',#198418); +#199917 = OVER_RIDING_STYLED_ITEM('overriding color',(#199918),#110850, + #198353); +#199918 = PRESENTATION_STYLE_ASSIGNMENT((#199919)); +#199919 = SURFACE_STYLE_USAGE(.BOTH.,#199920); +#199920 = SURFACE_SIDE_STYLE('',(#199921)); +#199921 = SURFACE_STYLE_FILL_AREA(#199922); +#199922 = FILL_AREA_STYLE('',(#199923)); +#199923 = FILL_AREA_STYLE_COLOUR('',#198418); +#199924 = OVER_RIDING_STYLED_ITEM('overriding color',(#199925),#110947, + #198353); +#199925 = PRESENTATION_STYLE_ASSIGNMENT((#199926)); +#199926 = SURFACE_STYLE_USAGE(.BOTH.,#199927); +#199927 = SURFACE_SIDE_STYLE('',(#199928)); +#199928 = SURFACE_STYLE_FILL_AREA(#199929); +#199929 = FILL_AREA_STYLE('',(#199930)); +#199930 = FILL_AREA_STYLE_COLOUR('',#198418); +#199931 = OVER_RIDING_STYLED_ITEM('overriding color',(#199932),#110994, + #198353); +#199932 = PRESENTATION_STYLE_ASSIGNMENT((#199933)); +#199933 = SURFACE_STYLE_USAGE(.BOTH.,#199934); +#199934 = SURFACE_SIDE_STYLE('',(#199935)); +#199935 = SURFACE_STYLE_FILL_AREA(#199936); +#199936 = FILL_AREA_STYLE('',(#199937)); +#199937 = FILL_AREA_STYLE_COLOUR('',#198418); +#199938 = OVER_RIDING_STYLED_ITEM('overriding color',(#199939),#111049, + #198353); +#199939 = PRESENTATION_STYLE_ASSIGNMENT((#199940)); +#199940 = SURFACE_STYLE_USAGE(.BOTH.,#199941); +#199941 = SURFACE_SIDE_STYLE('',(#199942)); +#199942 = SURFACE_STYLE_FILL_AREA(#199943); +#199943 = FILL_AREA_STYLE('',(#199944)); +#199944 = FILL_AREA_STYLE_COLOUR('',#198418); +#199945 = OVER_RIDING_STYLED_ITEM('overriding color',(#199946),#111076, + #198353); +#199946 = PRESENTATION_STYLE_ASSIGNMENT((#199947)); +#199947 = SURFACE_STYLE_USAGE(.BOTH.,#199948); +#199948 = SURFACE_SIDE_STYLE('',(#199949)); +#199949 = SURFACE_STYLE_FILL_AREA(#199950); +#199950 = FILL_AREA_STYLE('',(#199951)); +#199951 = FILL_AREA_STYLE_COLOUR('',#198418); +#199952 = OVER_RIDING_STYLED_ITEM('overriding color',(#199953),#111111, + #198353); +#199953 = PRESENTATION_STYLE_ASSIGNMENT((#199954)); +#199954 = SURFACE_STYLE_USAGE(.BOTH.,#199955); +#199955 = SURFACE_SIDE_STYLE('',(#199956)); +#199956 = SURFACE_STYLE_FILL_AREA(#199957); +#199957 = FILL_AREA_STYLE('',(#199958)); +#199958 = FILL_AREA_STYLE_COLOUR('',#198418); +#199959 = OVER_RIDING_STYLED_ITEM('overriding color',(#199960),#111118, + #198353); +#199960 = PRESENTATION_STYLE_ASSIGNMENT((#199961)); +#199961 = SURFACE_STYLE_USAGE(.BOTH.,#199962); +#199962 = SURFACE_SIDE_STYLE('',(#199963)); +#199963 = SURFACE_STYLE_FILL_AREA(#199964); +#199964 = FILL_AREA_STYLE('',(#199965)); +#199965 = FILL_AREA_STYLE_COLOUR('',#198418); +#199966 = OVER_RIDING_STYLED_ITEM('overriding color',(#199967),#111227, + #198353); +#199967 = PRESENTATION_STYLE_ASSIGNMENT((#199968)); +#199968 = SURFACE_STYLE_USAGE(.BOTH.,#199969); +#199969 = SURFACE_SIDE_STYLE('',(#199970)); +#199970 = SURFACE_STYLE_FILL_AREA(#199971); +#199971 = FILL_AREA_STYLE('',(#199972)); +#199972 = FILL_AREA_STYLE_COLOUR('',#198418); +#199973 = OVER_RIDING_STYLED_ITEM('overriding color',(#199974),#111331, + #198353); +#199974 = PRESENTATION_STYLE_ASSIGNMENT((#199975)); +#199975 = SURFACE_STYLE_USAGE(.BOTH.,#199976); +#199976 = SURFACE_SIDE_STYLE('',(#199977)); +#199977 = SURFACE_STYLE_FILL_AREA(#199978); +#199978 = FILL_AREA_STYLE('',(#199979)); +#199979 = FILL_AREA_STYLE_COLOUR('',#198418); +#199980 = OVER_RIDING_STYLED_ITEM('overriding color',(#199981),#111410, + #198353); +#199981 = PRESENTATION_STYLE_ASSIGNMENT((#199982)); +#199982 = SURFACE_STYLE_USAGE(.BOTH.,#199983); +#199983 = SURFACE_SIDE_STYLE('',(#199984)); +#199984 = SURFACE_STYLE_FILL_AREA(#199985); +#199985 = FILL_AREA_STYLE('',(#199986)); +#199986 = FILL_AREA_STYLE_COLOUR('',#198418); +#199987 = OVER_RIDING_STYLED_ITEM('overriding color',(#199988),#111489, + #198353); +#199988 = PRESENTATION_STYLE_ASSIGNMENT((#199989)); +#199989 = SURFACE_STYLE_USAGE(.BOTH.,#199990); +#199990 = SURFACE_SIDE_STYLE('',(#199991)); +#199991 = SURFACE_STYLE_FILL_AREA(#199992); +#199992 = FILL_AREA_STYLE('',(#199993)); +#199993 = FILL_AREA_STYLE_COLOUR('',#198418); +#199994 = OVER_RIDING_STYLED_ITEM('overriding color',(#199995),#111564, + #198353); +#199995 = PRESENTATION_STYLE_ASSIGNMENT((#199996)); +#199996 = SURFACE_STYLE_USAGE(.BOTH.,#199997); +#199997 = SURFACE_SIDE_STYLE('',(#199998)); +#199998 = SURFACE_STYLE_FILL_AREA(#199999); +#199999 = FILL_AREA_STYLE('',(#200000)); +#200000 = FILL_AREA_STYLE_COLOUR('',#198418); +#200001 = OVER_RIDING_STYLED_ITEM('overriding color',(#200002),#111639, + #198353); +#200002 = PRESENTATION_STYLE_ASSIGNMENT((#200003)); +#200003 = SURFACE_STYLE_USAGE(.BOTH.,#200004); +#200004 = SURFACE_SIDE_STYLE('',(#200005)); +#200005 = SURFACE_STYLE_FILL_AREA(#200006); +#200006 = FILL_AREA_STYLE('',(#200007)); +#200007 = FILL_AREA_STYLE_COLOUR('',#198418); +#200008 = OVER_RIDING_STYLED_ITEM('overriding color',(#200009),#111736, + #198353); +#200009 = PRESENTATION_STYLE_ASSIGNMENT((#200010)); +#200010 = SURFACE_STYLE_USAGE(.BOTH.,#200011); +#200011 = SURFACE_SIDE_STYLE('',(#200012)); +#200012 = SURFACE_STYLE_FILL_AREA(#200013); +#200013 = FILL_AREA_STYLE('',(#200014)); +#200014 = FILL_AREA_STYLE_COLOUR('',#198418); +#200015 = OVER_RIDING_STYLED_ITEM('overriding color',(#200016),#111833, + #198353); +#200016 = PRESENTATION_STYLE_ASSIGNMENT((#200017)); +#200017 = SURFACE_STYLE_USAGE(.BOTH.,#200018); +#200018 = SURFACE_SIDE_STYLE('',(#200019)); +#200019 = SURFACE_STYLE_FILL_AREA(#200020); +#200020 = FILL_AREA_STYLE('',(#200021)); +#200021 = FILL_AREA_STYLE_COLOUR('',#198418); +#200022 = OVER_RIDING_STYLED_ITEM('overriding color',(#200023),#111908, + #198353); +#200023 = PRESENTATION_STYLE_ASSIGNMENT((#200024)); +#200024 = SURFACE_STYLE_USAGE(.BOTH.,#200025); +#200025 = SURFACE_SIDE_STYLE('',(#200026)); +#200026 = SURFACE_STYLE_FILL_AREA(#200027); +#200027 = FILL_AREA_STYLE('',(#200028)); +#200028 = FILL_AREA_STYLE_COLOUR('',#198418); +#200029 = OVER_RIDING_STYLED_ITEM('overriding color',(#200030),#111935, + #198353); +#200030 = PRESENTATION_STYLE_ASSIGNMENT((#200031)); +#200031 = SURFACE_STYLE_USAGE(.BOTH.,#200032); +#200032 = SURFACE_SIDE_STYLE('',(#200033)); +#200033 = SURFACE_STYLE_FILL_AREA(#200034); +#200034 = FILL_AREA_STYLE('',(#200035)); +#200035 = FILL_AREA_STYLE_COLOUR('',#198418); +#200036 = OVER_RIDING_STYLED_ITEM('overriding color',(#200037),#111990, + #198353); +#200037 = PRESENTATION_STYLE_ASSIGNMENT((#200038)); +#200038 = SURFACE_STYLE_USAGE(.BOTH.,#200039); +#200039 = SURFACE_SIDE_STYLE('',(#200040)); +#200040 = SURFACE_STYLE_FILL_AREA(#200041); +#200041 = FILL_AREA_STYLE('',(#200042)); +#200042 = FILL_AREA_STYLE_COLOUR('',#198418); +#200043 = OVER_RIDING_STYLED_ITEM('overriding color',(#200044),#111997, + #198353); +#200044 = PRESENTATION_STYLE_ASSIGNMENT((#200045)); +#200045 = SURFACE_STYLE_USAGE(.BOTH.,#200046); +#200046 = SURFACE_SIDE_STYLE('',(#200047)); +#200047 = SURFACE_STYLE_FILL_AREA(#200048); +#200048 = FILL_AREA_STYLE('',(#200049)); +#200049 = FILL_AREA_STYLE_COLOUR('',#198418); +#200050 = OVER_RIDING_STYLED_ITEM('overriding color',(#200051),#112004, + #198353); +#200051 = PRESENTATION_STYLE_ASSIGNMENT((#200052)); +#200052 = SURFACE_STYLE_USAGE(.BOTH.,#200053); +#200053 = SURFACE_SIDE_STYLE('',(#200054)); +#200054 = SURFACE_STYLE_FILL_AREA(#200055); +#200055 = FILL_AREA_STYLE('',(#200056)); +#200056 = FILL_AREA_STYLE_COLOUR('',#198418); +#200057 = OVER_RIDING_STYLED_ITEM('overriding color',(#200058),#112113, + #198353); +#200058 = PRESENTATION_STYLE_ASSIGNMENT((#200059)); +#200059 = SURFACE_STYLE_USAGE(.BOTH.,#200060); +#200060 = SURFACE_SIDE_STYLE('',(#200061)); +#200061 = SURFACE_STYLE_FILL_AREA(#200062); +#200062 = FILL_AREA_STYLE('',(#200063)); +#200063 = FILL_AREA_STYLE_COLOUR('',#198418); +#200064 = OVER_RIDING_STYLED_ITEM('overriding color',(#200065),#112217, + #198353); +#200065 = PRESENTATION_STYLE_ASSIGNMENT((#200066)); +#200066 = SURFACE_STYLE_USAGE(.BOTH.,#200067); +#200067 = SURFACE_SIDE_STYLE('',(#200068)); +#200068 = SURFACE_STYLE_FILL_AREA(#200069); +#200069 = FILL_AREA_STYLE('',(#200070)); +#200070 = FILL_AREA_STYLE_COLOUR('',#198418); +#200071 = OVER_RIDING_STYLED_ITEM('overriding color',(#200072),#112296, + #198353); +#200072 = PRESENTATION_STYLE_ASSIGNMENT((#200073)); +#200073 = SURFACE_STYLE_USAGE(.BOTH.,#200074); +#200074 = SURFACE_SIDE_STYLE('',(#200075)); +#200075 = SURFACE_STYLE_FILL_AREA(#200076); +#200076 = FILL_AREA_STYLE('',(#200077)); +#200077 = FILL_AREA_STYLE_COLOUR('',#198418); +#200078 = OVER_RIDING_STYLED_ITEM('overriding color',(#200079),#112375, + #198353); +#200079 = PRESENTATION_STYLE_ASSIGNMENT((#200080)); +#200080 = SURFACE_STYLE_USAGE(.BOTH.,#200081); +#200081 = SURFACE_SIDE_STYLE('',(#200082)); +#200082 = SURFACE_STYLE_FILL_AREA(#200083); +#200083 = FILL_AREA_STYLE('',(#200084)); +#200084 = FILL_AREA_STYLE_COLOUR('',#198418); +#200085 = OVER_RIDING_STYLED_ITEM('overriding color',(#200086),#112450, + #198353); +#200086 = PRESENTATION_STYLE_ASSIGNMENT((#200087)); +#200087 = SURFACE_STYLE_USAGE(.BOTH.,#200088); +#200088 = SURFACE_SIDE_STYLE('',(#200089)); +#200089 = SURFACE_STYLE_FILL_AREA(#200090); +#200090 = FILL_AREA_STYLE('',(#200091)); +#200091 = FILL_AREA_STYLE_COLOUR('',#198418); +#200092 = OVER_RIDING_STYLED_ITEM('overriding color',(#200093),#112525, + #198353); +#200093 = PRESENTATION_STYLE_ASSIGNMENT((#200094)); +#200094 = SURFACE_STYLE_USAGE(.BOTH.,#200095); +#200095 = SURFACE_SIDE_STYLE('',(#200096)); +#200096 = SURFACE_STYLE_FILL_AREA(#200097); +#200097 = FILL_AREA_STYLE('',(#200098)); +#200098 = FILL_AREA_STYLE_COLOUR('',#198418); +#200099 = OVER_RIDING_STYLED_ITEM('overriding color',(#200100),#112622, + #198353); +#200100 = PRESENTATION_STYLE_ASSIGNMENT((#200101)); +#200101 = SURFACE_STYLE_USAGE(.BOTH.,#200102); +#200102 = SURFACE_SIDE_STYLE('',(#200103)); +#200103 = SURFACE_STYLE_FILL_AREA(#200104); +#200104 = FILL_AREA_STYLE('',(#200105)); +#200105 = FILL_AREA_STYLE_COLOUR('',#198418); +#200106 = OVER_RIDING_STYLED_ITEM('overriding color',(#200107),#112719, + #198353); +#200107 = PRESENTATION_STYLE_ASSIGNMENT((#200108)); +#200108 = SURFACE_STYLE_USAGE(.BOTH.,#200109); +#200109 = SURFACE_SIDE_STYLE('',(#200110)); +#200110 = SURFACE_STYLE_FILL_AREA(#200111); +#200111 = FILL_AREA_STYLE('',(#200112)); +#200112 = FILL_AREA_STYLE_COLOUR('',#198418); +#200113 = OVER_RIDING_STYLED_ITEM('overriding color',(#200114),#112766, + #198353); +#200114 = PRESENTATION_STYLE_ASSIGNMENT((#200115)); +#200115 = SURFACE_STYLE_USAGE(.BOTH.,#200116); +#200116 = SURFACE_SIDE_STYLE('',(#200117)); +#200117 = SURFACE_STYLE_FILL_AREA(#200118); +#200118 = FILL_AREA_STYLE('',(#200119)); +#200119 = FILL_AREA_STYLE_COLOUR('',#198418); +#200120 = OVER_RIDING_STYLED_ITEM('overriding color',(#200121),#112821, + #198353); +#200121 = PRESENTATION_STYLE_ASSIGNMENT((#200122)); +#200122 = SURFACE_STYLE_USAGE(.BOTH.,#200123); +#200123 = SURFACE_SIDE_STYLE('',(#200124)); +#200124 = SURFACE_STYLE_FILL_AREA(#200125); +#200125 = FILL_AREA_STYLE('',(#200126)); +#200126 = FILL_AREA_STYLE_COLOUR('',#198418); +#200127 = OVER_RIDING_STYLED_ITEM('overriding color',(#200128),#112848, + #198353); +#200128 = PRESENTATION_STYLE_ASSIGNMENT((#200129)); +#200129 = SURFACE_STYLE_USAGE(.BOTH.,#200130); +#200130 = SURFACE_SIDE_STYLE('',(#200131)); +#200131 = SURFACE_STYLE_FILL_AREA(#200132); +#200132 = FILL_AREA_STYLE('',(#200133)); +#200133 = FILL_AREA_STYLE_COLOUR('',#198418); +#200134 = OVER_RIDING_STYLED_ITEM('overriding color',(#200135),#112883, + #198353); +#200135 = PRESENTATION_STYLE_ASSIGNMENT((#200136)); +#200136 = SURFACE_STYLE_USAGE(.BOTH.,#200137); +#200137 = SURFACE_SIDE_STYLE('',(#200138)); +#200138 = SURFACE_STYLE_FILL_AREA(#200139); +#200139 = FILL_AREA_STYLE('',(#200140)); +#200140 = FILL_AREA_STYLE_COLOUR('',#198418); +#200141 = OVER_RIDING_STYLED_ITEM('overriding color',(#200142),#112890, + #198353); +#200142 = PRESENTATION_STYLE_ASSIGNMENT((#200143)); +#200143 = SURFACE_STYLE_USAGE(.BOTH.,#200144); +#200144 = SURFACE_SIDE_STYLE('',(#200145)); +#200145 = SURFACE_STYLE_FILL_AREA(#200146); +#200146 = FILL_AREA_STYLE('',(#200147)); +#200147 = FILL_AREA_STYLE_COLOUR('',#198418); +#200148 = OVER_RIDING_STYLED_ITEM('overriding color',(#200149),#112999, + #198353); +#200149 = PRESENTATION_STYLE_ASSIGNMENT((#200150)); +#200150 = SURFACE_STYLE_USAGE(.BOTH.,#200151); +#200151 = SURFACE_SIDE_STYLE('',(#200152)); +#200152 = SURFACE_STYLE_FILL_AREA(#200153); +#200153 = FILL_AREA_STYLE('',(#200154)); +#200154 = FILL_AREA_STYLE_COLOUR('',#198418); +#200155 = OVER_RIDING_STYLED_ITEM('overriding color',(#200156),#113103, + #198353); +#200156 = PRESENTATION_STYLE_ASSIGNMENT((#200157)); +#200157 = SURFACE_STYLE_USAGE(.BOTH.,#200158); +#200158 = SURFACE_SIDE_STYLE('',(#200159)); +#200159 = SURFACE_STYLE_FILL_AREA(#200160); +#200160 = FILL_AREA_STYLE('',(#200161)); +#200161 = FILL_AREA_STYLE_COLOUR('',#198418); +#200162 = OVER_RIDING_STYLED_ITEM('overriding color',(#200163),#113228, + #198353); +#200163 = PRESENTATION_STYLE_ASSIGNMENT((#200164)); +#200164 = SURFACE_STYLE_USAGE(.BOTH.,#200165); +#200165 = SURFACE_SIDE_STYLE('',(#200166)); +#200166 = SURFACE_STYLE_FILL_AREA(#200167); +#200167 = FILL_AREA_STYLE('',(#200168)); +#200168 = FILL_AREA_STYLE_COLOUR('',#198418); +#200169 = OVER_RIDING_STYLED_ITEM('overriding color',(#200170),#113307, + #198353); +#200170 = PRESENTATION_STYLE_ASSIGNMENT((#200171)); +#200171 = SURFACE_STYLE_USAGE(.BOTH.,#200172); +#200172 = SURFACE_SIDE_STYLE('',(#200173)); +#200173 = SURFACE_STYLE_FILL_AREA(#200174); +#200174 = FILL_AREA_STYLE('',(#200175)); +#200175 = FILL_AREA_STYLE_COLOUR('',#198418); +#200176 = OVER_RIDING_STYLED_ITEM('overriding color',(#200177),#113382, + #198353); +#200177 = PRESENTATION_STYLE_ASSIGNMENT((#200178)); +#200178 = SURFACE_STYLE_USAGE(.BOTH.,#200179); +#200179 = SURFACE_SIDE_STYLE('',(#200180)); +#200180 = SURFACE_STYLE_FILL_AREA(#200181); +#200181 = FILL_AREA_STYLE('',(#200182)); +#200182 = FILL_AREA_STYLE_COLOUR('',#198418); +#200183 = OVER_RIDING_STYLED_ITEM('overriding color',(#200184),#113457, + #198353); +#200184 = PRESENTATION_STYLE_ASSIGNMENT((#200185)); +#200185 = SURFACE_STYLE_USAGE(.BOTH.,#200186); +#200186 = SURFACE_SIDE_STYLE('',(#200187)); +#200187 = SURFACE_STYLE_FILL_AREA(#200188); +#200188 = FILL_AREA_STYLE('',(#200189)); +#200189 = FILL_AREA_STYLE_COLOUR('',#198418); +#200190 = OVER_RIDING_STYLED_ITEM('overriding color',(#200191),#113554, + #198353); +#200191 = PRESENTATION_STYLE_ASSIGNMENT((#200192)); +#200192 = SURFACE_STYLE_USAGE(.BOTH.,#200193); +#200193 = SURFACE_SIDE_STYLE('',(#200194)); +#200194 = SURFACE_STYLE_FILL_AREA(#200195); +#200195 = FILL_AREA_STYLE('',(#200196)); +#200196 = FILL_AREA_STYLE_COLOUR('',#198418); +#200197 = OVER_RIDING_STYLED_ITEM('overriding color',(#200198),#113697, + #198353); +#200198 = PRESENTATION_STYLE_ASSIGNMENT((#200199)); +#200199 = SURFACE_STYLE_USAGE(.BOTH.,#200200); +#200200 = SURFACE_SIDE_STYLE('',(#200201)); +#200201 = SURFACE_STYLE_FILL_AREA(#200202); +#200202 = FILL_AREA_STYLE('',(#200203)); +#200203 = FILL_AREA_STYLE_COLOUR('',#198418); +#200204 = OVER_RIDING_STYLED_ITEM('overriding color',(#200205),#113744, + #198353); +#200205 = PRESENTATION_STYLE_ASSIGNMENT((#200206)); +#200206 = SURFACE_STYLE_USAGE(.BOTH.,#200207); +#200207 = SURFACE_SIDE_STYLE('',(#200208)); +#200208 = SURFACE_STYLE_FILL_AREA(#200209); +#200209 = FILL_AREA_STYLE('',(#200210)); +#200210 = FILL_AREA_STYLE_COLOUR('',#198418); +#200211 = OVER_RIDING_STYLED_ITEM('overriding color',(#200212),#113799, + #198353); +#200212 = PRESENTATION_STYLE_ASSIGNMENT((#200213)); +#200213 = SURFACE_STYLE_USAGE(.BOTH.,#200214); +#200214 = SURFACE_SIDE_STYLE('',(#200215)); +#200215 = SURFACE_STYLE_FILL_AREA(#200216); +#200216 = FILL_AREA_STYLE('',(#200217)); +#200217 = FILL_AREA_STYLE_COLOUR('',#198418); +#200218 = OVER_RIDING_STYLED_ITEM('overriding color',(#200219),#113826, + #198353); +#200219 = PRESENTATION_STYLE_ASSIGNMENT((#200220)); +#200220 = SURFACE_STYLE_USAGE(.BOTH.,#200221); +#200221 = SURFACE_SIDE_STYLE('',(#200222)); +#200222 = SURFACE_STYLE_FILL_AREA(#200223); +#200223 = FILL_AREA_STYLE('',(#200224)); +#200224 = FILL_AREA_STYLE_COLOUR('',#198418); +#200225 = OVER_RIDING_STYLED_ITEM('overriding color',(#200226),#113861, + #198353); +#200226 = PRESENTATION_STYLE_ASSIGNMENT((#200227)); +#200227 = SURFACE_STYLE_USAGE(.BOTH.,#200228); +#200228 = SURFACE_SIDE_STYLE('',(#200229)); +#200229 = SURFACE_STYLE_FILL_AREA(#200230); +#200230 = FILL_AREA_STYLE('',(#200231)); +#200231 = FILL_AREA_STYLE_COLOUR('',#198418); +#200232 = OVER_RIDING_STYLED_ITEM('overriding color',(#200233),#113868, + #198353); +#200233 = PRESENTATION_STYLE_ASSIGNMENT((#200234)); +#200234 = SURFACE_STYLE_USAGE(.BOTH.,#200235); +#200235 = SURFACE_SIDE_STYLE('',(#200236)); +#200236 = SURFACE_STYLE_FILL_AREA(#200237); +#200237 = FILL_AREA_STYLE('',(#200238)); +#200238 = FILL_AREA_STYLE_COLOUR('',#198418); +#200239 = OVER_RIDING_STYLED_ITEM('overriding color',(#200240),#113977, + #198353); +#200240 = PRESENTATION_STYLE_ASSIGNMENT((#200241)); +#200241 = SURFACE_STYLE_USAGE(.BOTH.,#200242); +#200242 = SURFACE_SIDE_STYLE('',(#200243)); +#200243 = SURFACE_STYLE_FILL_AREA(#200244); +#200244 = FILL_AREA_STYLE('',(#200245)); +#200245 = FILL_AREA_STYLE_COLOUR('',#198418); +#200246 = OVER_RIDING_STYLED_ITEM('overriding color',(#200247),#114081, + #198353); +#200247 = PRESENTATION_STYLE_ASSIGNMENT((#200248)); +#200248 = SURFACE_STYLE_USAGE(.BOTH.,#200249); +#200249 = SURFACE_SIDE_STYLE('',(#200250)); +#200250 = SURFACE_STYLE_FILL_AREA(#200251); +#200251 = FILL_AREA_STYLE('',(#200252)); +#200252 = FILL_AREA_STYLE_COLOUR('',#198418); +#200253 = OVER_RIDING_STYLED_ITEM('overriding color',(#200254),#114183, + #198353); +#200254 = PRESENTATION_STYLE_ASSIGNMENT((#200255)); +#200255 = SURFACE_STYLE_USAGE(.BOTH.,#200256); +#200256 = SURFACE_SIDE_STYLE('',(#200257)); +#200257 = SURFACE_STYLE_FILL_AREA(#200258); +#200258 = FILL_AREA_STYLE('',(#200259)); +#200259 = FILL_AREA_STYLE_COLOUR('',#198418); +#200260 = OVER_RIDING_STYLED_ITEM('overriding color',(#200261),#114262, + #198353); +#200261 = PRESENTATION_STYLE_ASSIGNMENT((#200262)); +#200262 = SURFACE_STYLE_USAGE(.BOTH.,#200263); +#200263 = SURFACE_SIDE_STYLE('',(#200264)); +#200264 = SURFACE_STYLE_FILL_AREA(#200265); +#200265 = FILL_AREA_STYLE('',(#200266)); +#200266 = FILL_AREA_STYLE_COLOUR('',#198418); +#200267 = OVER_RIDING_STYLED_ITEM('overriding color',(#200268),#114337, + #198353); +#200268 = PRESENTATION_STYLE_ASSIGNMENT((#200269)); +#200269 = SURFACE_STYLE_USAGE(.BOTH.,#200270); +#200270 = SURFACE_SIDE_STYLE('',(#200271)); +#200271 = SURFACE_STYLE_FILL_AREA(#200272); +#200272 = FILL_AREA_STYLE('',(#200273)); +#200273 = FILL_AREA_STYLE_COLOUR('',#198418); +#200274 = OVER_RIDING_STYLED_ITEM('overriding color',(#200275),#114412, + #198353); +#200275 = PRESENTATION_STYLE_ASSIGNMENT((#200276)); +#200276 = SURFACE_STYLE_USAGE(.BOTH.,#200277); +#200277 = SURFACE_SIDE_STYLE('',(#200278)); +#200278 = SURFACE_STYLE_FILL_AREA(#200279); +#200279 = FILL_AREA_STYLE('',(#200280)); +#200280 = FILL_AREA_STYLE_COLOUR('',#198418); +#200281 = OVER_RIDING_STYLED_ITEM('overriding color',(#200282),#114509, + #198353); +#200282 = PRESENTATION_STYLE_ASSIGNMENT((#200283)); +#200283 = SURFACE_STYLE_USAGE(.BOTH.,#200284); +#200284 = SURFACE_SIDE_STYLE('',(#200285)); +#200285 = SURFACE_STYLE_FILL_AREA(#200286); +#200286 = FILL_AREA_STYLE('',(#200287)); +#200287 = FILL_AREA_STYLE_COLOUR('',#198418); +#200288 = OVER_RIDING_STYLED_ITEM('overriding color',(#200289),#114629, + #198353); +#200289 = PRESENTATION_STYLE_ASSIGNMENT((#200290)); +#200290 = SURFACE_STYLE_USAGE(.BOTH.,#200291); +#200291 = SURFACE_SIDE_STYLE('',(#200292)); +#200292 = SURFACE_STYLE_FILL_AREA(#200293); +#200293 = FILL_AREA_STYLE('',(#200294)); +#200294 = FILL_AREA_STYLE_COLOUR('',#198418); +#200295 = OVER_RIDING_STYLED_ITEM('overriding color',(#200296),#114676, + #198353); +#200296 = PRESENTATION_STYLE_ASSIGNMENT((#200297)); +#200297 = SURFACE_STYLE_USAGE(.BOTH.,#200298); +#200298 = SURFACE_SIDE_STYLE('',(#200299)); +#200299 = SURFACE_STYLE_FILL_AREA(#200300); +#200300 = FILL_AREA_STYLE('',(#200301)); +#200301 = FILL_AREA_STYLE_COLOUR('',#198418); +#200302 = OVER_RIDING_STYLED_ITEM('overriding color',(#200303),#114731, + #198353); +#200303 = PRESENTATION_STYLE_ASSIGNMENT((#200304)); +#200304 = SURFACE_STYLE_USAGE(.BOTH.,#200305); +#200305 = SURFACE_SIDE_STYLE('',(#200306)); +#200306 = SURFACE_STYLE_FILL_AREA(#200307); +#200307 = FILL_AREA_STYLE('',(#200308)); +#200308 = FILL_AREA_STYLE_COLOUR('',#198418); +#200309 = OVER_RIDING_STYLED_ITEM('overriding color',(#200310),#114758, + #198353); +#200310 = PRESENTATION_STYLE_ASSIGNMENT((#200311)); +#200311 = SURFACE_STYLE_USAGE(.BOTH.,#200312); +#200312 = SURFACE_SIDE_STYLE('',(#200313)); +#200313 = SURFACE_STYLE_FILL_AREA(#200314); +#200314 = FILL_AREA_STYLE('',(#200315)); +#200315 = FILL_AREA_STYLE_COLOUR('',#198418); +#200316 = OVER_RIDING_STYLED_ITEM('overriding color',(#200317),#114793, + #198353); +#200317 = PRESENTATION_STYLE_ASSIGNMENT((#200318)); +#200318 = SURFACE_STYLE_USAGE(.BOTH.,#200319); +#200319 = SURFACE_SIDE_STYLE('',(#200320)); +#200320 = SURFACE_STYLE_FILL_AREA(#200321); +#200321 = FILL_AREA_STYLE('',(#200322)); +#200322 = FILL_AREA_STYLE_COLOUR('',#198418); +#200323 = OVER_RIDING_STYLED_ITEM('overriding color',(#200324),#114800, + #198353); +#200324 = PRESENTATION_STYLE_ASSIGNMENT((#200325)); +#200325 = SURFACE_STYLE_USAGE(.BOTH.,#200326); +#200326 = SURFACE_SIDE_STYLE('',(#200327)); +#200327 = SURFACE_STYLE_FILL_AREA(#200328); +#200328 = FILL_AREA_STYLE('',(#200329)); +#200329 = FILL_AREA_STYLE_COLOUR('',#198418); +#200330 = OVER_RIDING_STYLED_ITEM('overriding color',(#200331),#114909, + #198353); +#200331 = PRESENTATION_STYLE_ASSIGNMENT((#200332)); +#200332 = SURFACE_STYLE_USAGE(.BOTH.,#200333); +#200333 = SURFACE_SIDE_STYLE('',(#200334)); +#200334 = SURFACE_STYLE_FILL_AREA(#200335); +#200335 = FILL_AREA_STYLE('',(#200336)); +#200336 = FILL_AREA_STYLE_COLOUR('',#198418); +#200337 = OVER_RIDING_STYLED_ITEM('overriding color',(#200338),#115013, + #198353); +#200338 = PRESENTATION_STYLE_ASSIGNMENT((#200339)); +#200339 = SURFACE_STYLE_USAGE(.BOTH.,#200340); +#200340 = SURFACE_SIDE_STYLE('',(#200341)); +#200341 = SURFACE_STYLE_FILL_AREA(#200342); +#200342 = FILL_AREA_STYLE('',(#200343)); +#200343 = FILL_AREA_STYLE_COLOUR('',#198418); +#200344 = OVER_RIDING_STYLED_ITEM('overriding color',(#200345),#115092, + #198353); +#200345 = PRESENTATION_STYLE_ASSIGNMENT((#200346)); +#200346 = SURFACE_STYLE_USAGE(.BOTH.,#200347); +#200347 = SURFACE_SIDE_STYLE('',(#200348)); +#200348 = SURFACE_STYLE_FILL_AREA(#200349); +#200349 = FILL_AREA_STYLE('',(#200350)); +#200350 = FILL_AREA_STYLE_COLOUR('',#198418); +#200351 = OVER_RIDING_STYLED_ITEM('overriding color',(#200352),#115171, + #198353); +#200352 = PRESENTATION_STYLE_ASSIGNMENT((#200353)); +#200353 = SURFACE_STYLE_USAGE(.BOTH.,#200354); +#200354 = SURFACE_SIDE_STYLE('',(#200355)); +#200355 = SURFACE_STYLE_FILL_AREA(#200356); +#200356 = FILL_AREA_STYLE('',(#200357)); +#200357 = FILL_AREA_STYLE_COLOUR('',#198418); +#200358 = OVER_RIDING_STYLED_ITEM('overriding color',(#200359),#115246, + #198353); +#200359 = PRESENTATION_STYLE_ASSIGNMENT((#200360)); +#200360 = SURFACE_STYLE_USAGE(.BOTH.,#200361); +#200361 = SURFACE_SIDE_STYLE('',(#200362)); +#200362 = SURFACE_STYLE_FILL_AREA(#200363); +#200363 = FILL_AREA_STYLE('',(#200364)); +#200364 = FILL_AREA_STYLE_COLOUR('',#198418); +#200365 = OVER_RIDING_STYLED_ITEM('overriding color',(#200366),#115321, + #198353); +#200366 = PRESENTATION_STYLE_ASSIGNMENT((#200367)); +#200367 = SURFACE_STYLE_USAGE(.BOTH.,#200368); +#200368 = SURFACE_SIDE_STYLE('',(#200369)); +#200369 = SURFACE_STYLE_FILL_AREA(#200370); +#200370 = FILL_AREA_STYLE('',(#200371)); +#200371 = FILL_AREA_STYLE_COLOUR('',#198418); +#200372 = OVER_RIDING_STYLED_ITEM('overriding color',(#200373),#115418, + #198353); +#200373 = PRESENTATION_STYLE_ASSIGNMENT((#200374)); +#200374 = SURFACE_STYLE_USAGE(.BOTH.,#200375); +#200375 = SURFACE_SIDE_STYLE('',(#200376)); +#200376 = SURFACE_STYLE_FILL_AREA(#200377); +#200377 = FILL_AREA_STYLE('',(#200378)); +#200378 = FILL_AREA_STYLE_COLOUR('',#198418); +#200379 = OVER_RIDING_STYLED_ITEM('overriding color',(#200380),#115515, + #198353); +#200380 = PRESENTATION_STYLE_ASSIGNMENT((#200381)); +#200381 = SURFACE_STYLE_USAGE(.BOTH.,#200382); +#200382 = SURFACE_SIDE_STYLE('',(#200383)); +#200383 = SURFACE_STYLE_FILL_AREA(#200384); +#200384 = FILL_AREA_STYLE('',(#200385)); +#200385 = FILL_AREA_STYLE_COLOUR('',#198418); +#200386 = OVER_RIDING_STYLED_ITEM('overriding color',(#200387),#115562, + #198353); +#200387 = PRESENTATION_STYLE_ASSIGNMENT((#200388)); +#200388 = SURFACE_STYLE_USAGE(.BOTH.,#200389); +#200389 = SURFACE_SIDE_STYLE('',(#200390)); +#200390 = SURFACE_STYLE_FILL_AREA(#200391); +#200391 = FILL_AREA_STYLE('',(#200392)); +#200392 = FILL_AREA_STYLE_COLOUR('',#198418); +#200393 = OVER_RIDING_STYLED_ITEM('overriding color',(#200394),#115617, + #198353); +#200394 = PRESENTATION_STYLE_ASSIGNMENT((#200395)); +#200395 = SURFACE_STYLE_USAGE(.BOTH.,#200396); +#200396 = SURFACE_SIDE_STYLE('',(#200397)); +#200397 = SURFACE_STYLE_FILL_AREA(#200398); +#200398 = FILL_AREA_STYLE('',(#200399)); +#200399 = FILL_AREA_STYLE_COLOUR('',#198418); +#200400 = OVER_RIDING_STYLED_ITEM('overriding color',(#200401),#115644, + #198353); +#200401 = PRESENTATION_STYLE_ASSIGNMENT((#200402)); +#200402 = SURFACE_STYLE_USAGE(.BOTH.,#200403); +#200403 = SURFACE_SIDE_STYLE('',(#200404)); +#200404 = SURFACE_STYLE_FILL_AREA(#200405); +#200405 = FILL_AREA_STYLE('',(#200406)); +#200406 = FILL_AREA_STYLE_COLOUR('',#198418); +#200407 = OVER_RIDING_STYLED_ITEM('overriding color',(#200408),#115679, + #198353); +#200408 = PRESENTATION_STYLE_ASSIGNMENT((#200409)); +#200409 = SURFACE_STYLE_USAGE(.BOTH.,#200410); +#200410 = SURFACE_SIDE_STYLE('',(#200411)); +#200411 = SURFACE_STYLE_FILL_AREA(#200412); +#200412 = FILL_AREA_STYLE('',(#200413)); +#200413 = FILL_AREA_STYLE_COLOUR('',#198418); +#200414 = OVER_RIDING_STYLED_ITEM('overriding color',(#200415),#115686, + #198353); +#200415 = PRESENTATION_STYLE_ASSIGNMENT((#200416)); +#200416 = SURFACE_STYLE_USAGE(.BOTH.,#200417); +#200417 = SURFACE_SIDE_STYLE('',(#200418)); +#200418 = SURFACE_STYLE_FILL_AREA(#200419); +#200419 = FILL_AREA_STYLE('',(#200420)); +#200420 = FILL_AREA_STYLE_COLOUR('',#198418); +#200421 = OVER_RIDING_STYLED_ITEM('overriding color',(#200422),#115795, + #198353); +#200422 = PRESENTATION_STYLE_ASSIGNMENT((#200423)); +#200423 = SURFACE_STYLE_USAGE(.BOTH.,#200424); +#200424 = SURFACE_SIDE_STYLE('',(#200425)); +#200425 = SURFACE_STYLE_FILL_AREA(#200426); +#200426 = FILL_AREA_STYLE('',(#200427)); +#200427 = FILL_AREA_STYLE_COLOUR('',#198418); +#200428 = OVER_RIDING_STYLED_ITEM('overriding color',(#200429),#115899, + #198353); +#200429 = PRESENTATION_STYLE_ASSIGNMENT((#200430)); +#200430 = SURFACE_STYLE_USAGE(.BOTH.,#200431); +#200431 = SURFACE_SIDE_STYLE('',(#200432)); +#200432 = SURFACE_STYLE_FILL_AREA(#200433); +#200433 = FILL_AREA_STYLE('',(#200434)); +#200434 = FILL_AREA_STYLE_COLOUR('',#198418); +#200435 = OVER_RIDING_STYLED_ITEM('overriding color',(#200436),#116001, + #198353); +#200436 = PRESENTATION_STYLE_ASSIGNMENT((#200437)); +#200437 = SURFACE_STYLE_USAGE(.BOTH.,#200438); +#200438 = SURFACE_SIDE_STYLE('',(#200439)); +#200439 = SURFACE_STYLE_FILL_AREA(#200440); +#200440 = FILL_AREA_STYLE('',(#200441)); +#200441 = FILL_AREA_STYLE_COLOUR('',#198418); +#200442 = OVER_RIDING_STYLED_ITEM('overriding color',(#200443),#116080, + #198353); +#200443 = PRESENTATION_STYLE_ASSIGNMENT((#200444)); +#200444 = SURFACE_STYLE_USAGE(.BOTH.,#200445); +#200445 = SURFACE_SIDE_STYLE('',(#200446)); +#200446 = SURFACE_STYLE_FILL_AREA(#200447); +#200447 = FILL_AREA_STYLE('',(#200448)); +#200448 = FILL_AREA_STYLE_COLOUR('',#198418); +#200449 = OVER_RIDING_STYLED_ITEM('overriding color',(#200450),#116155, + #198353); +#200450 = PRESENTATION_STYLE_ASSIGNMENT((#200451)); +#200451 = SURFACE_STYLE_USAGE(.BOTH.,#200452); +#200452 = SURFACE_SIDE_STYLE('',(#200453)); +#200453 = SURFACE_STYLE_FILL_AREA(#200454); +#200454 = FILL_AREA_STYLE('',(#200455)); +#200455 = FILL_AREA_STYLE_COLOUR('',#198418); +#200456 = OVER_RIDING_STYLED_ITEM('overriding color',(#200457),#116230, + #198353); +#200457 = PRESENTATION_STYLE_ASSIGNMENT((#200458)); +#200458 = SURFACE_STYLE_USAGE(.BOTH.,#200459); +#200459 = SURFACE_SIDE_STYLE('',(#200460)); +#200460 = SURFACE_STYLE_FILL_AREA(#200461); +#200461 = FILL_AREA_STYLE('',(#200462)); +#200462 = FILL_AREA_STYLE_COLOUR('',#198418); +#200463 = OVER_RIDING_STYLED_ITEM('overriding color',(#200464),#116327, + #198353); +#200464 = PRESENTATION_STYLE_ASSIGNMENT((#200465)); +#200465 = SURFACE_STYLE_USAGE(.BOTH.,#200466); +#200466 = SURFACE_SIDE_STYLE('',(#200467)); +#200467 = SURFACE_STYLE_FILL_AREA(#200468); +#200468 = FILL_AREA_STYLE('',(#200469)); +#200469 = FILL_AREA_STYLE_COLOUR('',#198418); +#200470 = OVER_RIDING_STYLED_ITEM('overriding color',(#200471),#116447, + #198353); +#200471 = PRESENTATION_STYLE_ASSIGNMENT((#200472)); +#200472 = SURFACE_STYLE_USAGE(.BOTH.,#200473); +#200473 = SURFACE_SIDE_STYLE('',(#200474)); +#200474 = SURFACE_STYLE_FILL_AREA(#200475); +#200475 = FILL_AREA_STYLE('',(#200476)); +#200476 = FILL_AREA_STYLE_COLOUR('',#198418); +#200477 = OVER_RIDING_STYLED_ITEM('overriding color',(#200478),#116494, + #198353); +#200478 = PRESENTATION_STYLE_ASSIGNMENT((#200479)); +#200479 = SURFACE_STYLE_USAGE(.BOTH.,#200480); +#200480 = SURFACE_SIDE_STYLE('',(#200481)); +#200481 = SURFACE_STYLE_FILL_AREA(#200482); +#200482 = FILL_AREA_STYLE('',(#200483)); +#200483 = FILL_AREA_STYLE_COLOUR('',#198418); +#200484 = OVER_RIDING_STYLED_ITEM('overriding color',(#200485),#116549, + #198353); +#200485 = PRESENTATION_STYLE_ASSIGNMENT((#200486)); +#200486 = SURFACE_STYLE_USAGE(.BOTH.,#200487); +#200487 = SURFACE_SIDE_STYLE('',(#200488)); +#200488 = SURFACE_STYLE_FILL_AREA(#200489); +#200489 = FILL_AREA_STYLE('',(#200490)); +#200490 = FILL_AREA_STYLE_COLOUR('',#198418); +#200491 = OVER_RIDING_STYLED_ITEM('overriding color',(#200492),#116576, + #198353); +#200492 = PRESENTATION_STYLE_ASSIGNMENT((#200493)); +#200493 = SURFACE_STYLE_USAGE(.BOTH.,#200494); +#200494 = SURFACE_SIDE_STYLE('',(#200495)); +#200495 = SURFACE_STYLE_FILL_AREA(#200496); +#200496 = FILL_AREA_STYLE('',(#200497)); +#200497 = FILL_AREA_STYLE_COLOUR('',#198418); +#200498 = OVER_RIDING_STYLED_ITEM('overriding color',(#200499),#116611, + #198353); +#200499 = PRESENTATION_STYLE_ASSIGNMENT((#200500)); +#200500 = SURFACE_STYLE_USAGE(.BOTH.,#200501); +#200501 = SURFACE_SIDE_STYLE('',(#200502)); +#200502 = SURFACE_STYLE_FILL_AREA(#200503); +#200503 = FILL_AREA_STYLE('',(#200504)); +#200504 = FILL_AREA_STYLE_COLOUR('',#198418); +#200505 = OVER_RIDING_STYLED_ITEM('overriding color',(#200506),#116618, + #198353); +#200506 = PRESENTATION_STYLE_ASSIGNMENT((#200507)); +#200507 = SURFACE_STYLE_USAGE(.BOTH.,#200508); +#200508 = SURFACE_SIDE_STYLE('',(#200509)); +#200509 = SURFACE_STYLE_FILL_AREA(#200510); +#200510 = FILL_AREA_STYLE('',(#200511)); +#200511 = FILL_AREA_STYLE_COLOUR('',#198418); +#200512 = OVER_RIDING_STYLED_ITEM('overriding color',(#200513),#116727, + #198353); +#200513 = PRESENTATION_STYLE_ASSIGNMENT((#200514)); +#200514 = SURFACE_STYLE_USAGE(.BOTH.,#200515); +#200515 = SURFACE_SIDE_STYLE('',(#200516)); +#200516 = SURFACE_STYLE_FILL_AREA(#200517); +#200517 = FILL_AREA_STYLE('',(#200518)); +#200518 = FILL_AREA_STYLE_COLOUR('',#198418); +#200519 = OVER_RIDING_STYLED_ITEM('overriding color',(#200520),#116831, + #198353); +#200520 = PRESENTATION_STYLE_ASSIGNMENT((#200521)); +#200521 = SURFACE_STYLE_USAGE(.BOTH.,#200522); +#200522 = SURFACE_SIDE_STYLE('',(#200523)); +#200523 = SURFACE_STYLE_FILL_AREA(#200524); +#200524 = FILL_AREA_STYLE('',(#200525)); +#200525 = FILL_AREA_STYLE_COLOUR('',#198418); +#200526 = OVER_RIDING_STYLED_ITEM('overriding color',(#200527),#116910, + #198353); +#200527 = PRESENTATION_STYLE_ASSIGNMENT((#200528)); +#200528 = SURFACE_STYLE_USAGE(.BOTH.,#200529); +#200529 = SURFACE_SIDE_STYLE('',(#200530)); +#200530 = SURFACE_STYLE_FILL_AREA(#200531); +#200531 = FILL_AREA_STYLE('',(#200532)); +#200532 = FILL_AREA_STYLE_COLOUR('',#198418); +#200533 = OVER_RIDING_STYLED_ITEM('overriding color',(#200534),#116989, + #198353); +#200534 = PRESENTATION_STYLE_ASSIGNMENT((#200535)); +#200535 = SURFACE_STYLE_USAGE(.BOTH.,#200536); +#200536 = SURFACE_SIDE_STYLE('',(#200537)); +#200537 = SURFACE_STYLE_FILL_AREA(#200538); +#200538 = FILL_AREA_STYLE('',(#200539)); +#200539 = FILL_AREA_STYLE_COLOUR('',#198418); +#200540 = OVER_RIDING_STYLED_ITEM('overriding color',(#200541),#117064, + #198353); +#200541 = PRESENTATION_STYLE_ASSIGNMENT((#200542)); +#200542 = SURFACE_STYLE_USAGE(.BOTH.,#200543); +#200543 = SURFACE_SIDE_STYLE('',(#200544)); +#200544 = SURFACE_STYLE_FILL_AREA(#200545); +#200545 = FILL_AREA_STYLE('',(#200546)); +#200546 = FILL_AREA_STYLE_COLOUR('',#198418); +#200547 = OVER_RIDING_STYLED_ITEM('overriding color',(#200548),#117139, + #198353); +#200548 = PRESENTATION_STYLE_ASSIGNMENT((#200549)); +#200549 = SURFACE_STYLE_USAGE(.BOTH.,#200550); +#200550 = SURFACE_SIDE_STYLE('',(#200551)); +#200551 = SURFACE_STYLE_FILL_AREA(#200552); +#200552 = FILL_AREA_STYLE('',(#200553)); +#200553 = FILL_AREA_STYLE_COLOUR('',#198418); +#200554 = OVER_RIDING_STYLED_ITEM('overriding color',(#200555),#117236, + #198353); +#200555 = PRESENTATION_STYLE_ASSIGNMENT((#200556)); +#200556 = SURFACE_STYLE_USAGE(.BOTH.,#200557); +#200557 = SURFACE_SIDE_STYLE('',(#200558)); +#200558 = SURFACE_STYLE_FILL_AREA(#200559); +#200559 = FILL_AREA_STYLE('',(#200560)); +#200560 = FILL_AREA_STYLE_COLOUR('',#198418); +#200561 = OVER_RIDING_STYLED_ITEM('overriding color',(#200562),#117333, + #198353); +#200562 = PRESENTATION_STYLE_ASSIGNMENT((#200563)); +#200563 = SURFACE_STYLE_USAGE(.BOTH.,#200564); +#200564 = SURFACE_SIDE_STYLE('',(#200565)); +#200565 = SURFACE_STYLE_FILL_AREA(#200566); +#200566 = FILL_AREA_STYLE('',(#200567)); +#200567 = FILL_AREA_STYLE_COLOUR('',#198418); +#200568 = OVER_RIDING_STYLED_ITEM('overriding color',(#200569),#117380, + #198353); +#200569 = PRESENTATION_STYLE_ASSIGNMENT((#200570)); +#200570 = SURFACE_STYLE_USAGE(.BOTH.,#200571); +#200571 = SURFACE_SIDE_STYLE('',(#200572)); +#200572 = SURFACE_STYLE_FILL_AREA(#200573); +#200573 = FILL_AREA_STYLE('',(#200574)); +#200574 = FILL_AREA_STYLE_COLOUR('',#198418); +#200575 = OVER_RIDING_STYLED_ITEM('overriding color',(#200576),#117435, + #198353); +#200576 = PRESENTATION_STYLE_ASSIGNMENT((#200577)); +#200577 = SURFACE_STYLE_USAGE(.BOTH.,#200578); +#200578 = SURFACE_SIDE_STYLE('',(#200579)); +#200579 = SURFACE_STYLE_FILL_AREA(#200580); +#200580 = FILL_AREA_STYLE('',(#200581)); +#200581 = FILL_AREA_STYLE_COLOUR('',#198418); +#200582 = OVER_RIDING_STYLED_ITEM('overriding color',(#200583),#117462, + #198353); +#200583 = PRESENTATION_STYLE_ASSIGNMENT((#200584)); +#200584 = SURFACE_STYLE_USAGE(.BOTH.,#200585); +#200585 = SURFACE_SIDE_STYLE('',(#200586)); +#200586 = SURFACE_STYLE_FILL_AREA(#200587); +#200587 = FILL_AREA_STYLE('',(#200588)); +#200588 = FILL_AREA_STYLE_COLOUR('',#198418); +#200589 = OVER_RIDING_STYLED_ITEM('overriding color',(#200590),#117497, + #198353); +#200590 = PRESENTATION_STYLE_ASSIGNMENT((#200591)); +#200591 = SURFACE_STYLE_USAGE(.BOTH.,#200592); +#200592 = SURFACE_SIDE_STYLE('',(#200593)); +#200593 = SURFACE_STYLE_FILL_AREA(#200594); +#200594 = FILL_AREA_STYLE('',(#200595)); +#200595 = FILL_AREA_STYLE_COLOUR('',#198418); +#200596 = OVER_RIDING_STYLED_ITEM('overriding color',(#200597),#117504, + #198353); +#200597 = PRESENTATION_STYLE_ASSIGNMENT((#200598)); +#200598 = SURFACE_STYLE_USAGE(.BOTH.,#200599); +#200599 = SURFACE_SIDE_STYLE('',(#200600)); +#200600 = SURFACE_STYLE_FILL_AREA(#200601); +#200601 = FILL_AREA_STYLE('',(#200602)); +#200602 = FILL_AREA_STYLE_COLOUR('',#198418); +#200603 = OVER_RIDING_STYLED_ITEM('overriding color',(#200604),#117613, + #198353); +#200604 = PRESENTATION_STYLE_ASSIGNMENT((#200605)); +#200605 = SURFACE_STYLE_USAGE(.BOTH.,#200606); +#200606 = SURFACE_SIDE_STYLE('',(#200607)); +#200607 = SURFACE_STYLE_FILL_AREA(#200608); +#200608 = FILL_AREA_STYLE('',(#200609)); +#200609 = FILL_AREA_STYLE_COLOUR('',#198418); +#200610 = OVER_RIDING_STYLED_ITEM('overriding color',(#200611),#117717, + #198353); +#200611 = PRESENTATION_STYLE_ASSIGNMENT((#200612)); +#200612 = SURFACE_STYLE_USAGE(.BOTH.,#200613); +#200613 = SURFACE_SIDE_STYLE('',(#200614)); +#200614 = SURFACE_STYLE_FILL_AREA(#200615); +#200615 = FILL_AREA_STYLE('',(#200616)); +#200616 = FILL_AREA_STYLE_COLOUR('',#198418); +#200617 = OVER_RIDING_STYLED_ITEM('overriding color',(#200618),#117796, + #198353); +#200618 = PRESENTATION_STYLE_ASSIGNMENT((#200619)); +#200619 = SURFACE_STYLE_USAGE(.BOTH.,#200620); +#200620 = SURFACE_SIDE_STYLE('',(#200621)); +#200621 = SURFACE_STYLE_FILL_AREA(#200622); +#200622 = FILL_AREA_STYLE('',(#200623)); +#200623 = FILL_AREA_STYLE_COLOUR('',#198418); +#200624 = OVER_RIDING_STYLED_ITEM('overriding color',(#200625),#117875, + #198353); +#200625 = PRESENTATION_STYLE_ASSIGNMENT((#200626)); +#200626 = SURFACE_STYLE_USAGE(.BOTH.,#200627); +#200627 = SURFACE_SIDE_STYLE('',(#200628)); +#200628 = SURFACE_STYLE_FILL_AREA(#200629); +#200629 = FILL_AREA_STYLE('',(#200630)); +#200630 = FILL_AREA_STYLE_COLOUR('',#198418); +#200631 = OVER_RIDING_STYLED_ITEM('overriding color',(#200632),#117950, + #198353); +#200632 = PRESENTATION_STYLE_ASSIGNMENT((#200633)); +#200633 = SURFACE_STYLE_USAGE(.BOTH.,#200634); +#200634 = SURFACE_SIDE_STYLE('',(#200635)); +#200635 = SURFACE_STYLE_FILL_AREA(#200636); +#200636 = FILL_AREA_STYLE('',(#200637)); +#200637 = FILL_AREA_STYLE_COLOUR('',#198418); +#200638 = OVER_RIDING_STYLED_ITEM('overriding color',(#200639),#118025, + #198353); +#200639 = PRESENTATION_STYLE_ASSIGNMENT((#200640)); +#200640 = SURFACE_STYLE_USAGE(.BOTH.,#200641); +#200641 = SURFACE_SIDE_STYLE('',(#200642)); +#200642 = SURFACE_STYLE_FILL_AREA(#200643); +#200643 = FILL_AREA_STYLE('',(#200644)); +#200644 = FILL_AREA_STYLE_COLOUR('',#198418); +#200645 = OVER_RIDING_STYLED_ITEM('overriding color',(#200646),#118122, + #198353); +#200646 = PRESENTATION_STYLE_ASSIGNMENT((#200647)); +#200647 = SURFACE_STYLE_USAGE(.BOTH.,#200648); +#200648 = SURFACE_SIDE_STYLE('',(#200649)); +#200649 = SURFACE_STYLE_FILL_AREA(#200650); +#200650 = FILL_AREA_STYLE('',(#200651)); +#200651 = FILL_AREA_STYLE_COLOUR('',#198418); +#200652 = OVER_RIDING_STYLED_ITEM('overriding color',(#200653),#118219, + #198353); +#200653 = PRESENTATION_STYLE_ASSIGNMENT((#200654)); +#200654 = SURFACE_STYLE_USAGE(.BOTH.,#200655); +#200655 = SURFACE_SIDE_STYLE('',(#200656)); +#200656 = SURFACE_STYLE_FILL_AREA(#200657); +#200657 = FILL_AREA_STYLE('',(#200658)); +#200658 = FILL_AREA_STYLE_COLOUR('',#198418); +#200659 = OVER_RIDING_STYLED_ITEM('overriding color',(#200660),#118266, + #198353); +#200660 = PRESENTATION_STYLE_ASSIGNMENT((#200661)); +#200661 = SURFACE_STYLE_USAGE(.BOTH.,#200662); +#200662 = SURFACE_SIDE_STYLE('',(#200663)); +#200663 = SURFACE_STYLE_FILL_AREA(#200664); +#200664 = FILL_AREA_STYLE('',(#200665)); +#200665 = FILL_AREA_STYLE_COLOUR('',#198418); +#200666 = OVER_RIDING_STYLED_ITEM('overriding color',(#200667),#118321, + #198353); +#200667 = PRESENTATION_STYLE_ASSIGNMENT((#200668)); +#200668 = SURFACE_STYLE_USAGE(.BOTH.,#200669); +#200669 = SURFACE_SIDE_STYLE('',(#200670)); +#200670 = SURFACE_STYLE_FILL_AREA(#200671); +#200671 = FILL_AREA_STYLE('',(#200672)); +#200672 = FILL_AREA_STYLE_COLOUR('',#198418); +#200673 = OVER_RIDING_STYLED_ITEM('overriding color',(#200674),#118348, + #198353); +#200674 = PRESENTATION_STYLE_ASSIGNMENT((#200675)); +#200675 = SURFACE_STYLE_USAGE(.BOTH.,#200676); +#200676 = SURFACE_SIDE_STYLE('',(#200677)); +#200677 = SURFACE_STYLE_FILL_AREA(#200678); +#200678 = FILL_AREA_STYLE('',(#200679)); +#200679 = FILL_AREA_STYLE_COLOUR('',#198418); +#200680 = OVER_RIDING_STYLED_ITEM('overriding color',(#200681),#118383, + #198353); +#200681 = PRESENTATION_STYLE_ASSIGNMENT((#200682)); +#200682 = SURFACE_STYLE_USAGE(.BOTH.,#200683); +#200683 = SURFACE_SIDE_STYLE('',(#200684)); +#200684 = SURFACE_STYLE_FILL_AREA(#200685); +#200685 = FILL_AREA_STYLE('',(#200686)); +#200686 = FILL_AREA_STYLE_COLOUR('',#198418); +#200687 = OVER_RIDING_STYLED_ITEM('overriding color',(#200688),#118390, + #198353); +#200688 = PRESENTATION_STYLE_ASSIGNMENT((#200689)); +#200689 = SURFACE_STYLE_USAGE(.BOTH.,#200690); +#200690 = SURFACE_SIDE_STYLE('',(#200691)); +#200691 = SURFACE_STYLE_FILL_AREA(#200692); +#200692 = FILL_AREA_STYLE('',(#200693)); +#200693 = FILL_AREA_STYLE_COLOUR('',#198418); +#200694 = OVER_RIDING_STYLED_ITEM('overriding color',(#200695),#118499, + #198353); +#200695 = PRESENTATION_STYLE_ASSIGNMENT((#200696)); +#200696 = SURFACE_STYLE_USAGE(.BOTH.,#200697); +#200697 = SURFACE_SIDE_STYLE('',(#200698)); +#200698 = SURFACE_STYLE_FILL_AREA(#200699); +#200699 = FILL_AREA_STYLE('',(#200700)); +#200700 = FILL_AREA_STYLE_COLOUR('',#198418); +#200701 = OVER_RIDING_STYLED_ITEM('overriding color',(#200702),#118603, + #198353); +#200702 = PRESENTATION_STYLE_ASSIGNMENT((#200703)); +#200703 = SURFACE_STYLE_USAGE(.BOTH.,#200704); +#200704 = SURFACE_SIDE_STYLE('',(#200705)); +#200705 = SURFACE_STYLE_FILL_AREA(#200706); +#200706 = FILL_AREA_STYLE('',(#200707)); +#200707 = FILL_AREA_STYLE_COLOUR('',#198418); +#200708 = OVER_RIDING_STYLED_ITEM('overriding color',(#200709),#118682, + #198353); +#200709 = PRESENTATION_STYLE_ASSIGNMENT((#200710)); +#200710 = SURFACE_STYLE_USAGE(.BOTH.,#200711); +#200711 = SURFACE_SIDE_STYLE('',(#200712)); +#200712 = SURFACE_STYLE_FILL_AREA(#200713); +#200713 = FILL_AREA_STYLE('',(#200714)); +#200714 = FILL_AREA_STYLE_COLOUR('',#198418); +#200715 = OVER_RIDING_STYLED_ITEM('overriding color',(#200716),#118761, + #198353); +#200716 = PRESENTATION_STYLE_ASSIGNMENT((#200717)); +#200717 = SURFACE_STYLE_USAGE(.BOTH.,#200718); +#200718 = SURFACE_SIDE_STYLE('',(#200719)); +#200719 = SURFACE_STYLE_FILL_AREA(#200720); +#200720 = FILL_AREA_STYLE('',(#200721)); +#200721 = FILL_AREA_STYLE_COLOUR('',#198418); +#200722 = OVER_RIDING_STYLED_ITEM('overriding color',(#200723),#118836, + #198353); +#200723 = PRESENTATION_STYLE_ASSIGNMENT((#200724)); +#200724 = SURFACE_STYLE_USAGE(.BOTH.,#200725); +#200725 = SURFACE_SIDE_STYLE('',(#200726)); +#200726 = SURFACE_STYLE_FILL_AREA(#200727); +#200727 = FILL_AREA_STYLE('',(#200728)); +#200728 = FILL_AREA_STYLE_COLOUR('',#198418); +#200729 = OVER_RIDING_STYLED_ITEM('overriding color',(#200730),#118911, + #198353); +#200730 = PRESENTATION_STYLE_ASSIGNMENT((#200731)); +#200731 = SURFACE_STYLE_USAGE(.BOTH.,#200732); +#200732 = SURFACE_SIDE_STYLE('',(#200733)); +#200733 = SURFACE_STYLE_FILL_AREA(#200734); +#200734 = FILL_AREA_STYLE('',(#200735)); +#200735 = FILL_AREA_STYLE_COLOUR('',#198418); +#200736 = OVER_RIDING_STYLED_ITEM('overriding color',(#200737),#119008, + #198353); +#200737 = PRESENTATION_STYLE_ASSIGNMENT((#200738)); +#200738 = SURFACE_STYLE_USAGE(.BOTH.,#200739); +#200739 = SURFACE_SIDE_STYLE('',(#200740)); +#200740 = SURFACE_STYLE_FILL_AREA(#200741); +#200741 = FILL_AREA_STYLE('',(#200742)); +#200742 = FILL_AREA_STYLE_COLOUR('',#198418); +#200743 = OVER_RIDING_STYLED_ITEM('overriding color',(#200744),#119105, + #198353); +#200744 = PRESENTATION_STYLE_ASSIGNMENT((#200745)); +#200745 = SURFACE_STYLE_USAGE(.BOTH.,#200746); +#200746 = SURFACE_SIDE_STYLE('',(#200747)); +#200747 = SURFACE_STYLE_FILL_AREA(#200748); +#200748 = FILL_AREA_STYLE('',(#200749)); +#200749 = FILL_AREA_STYLE_COLOUR('',#198418); +#200750 = OVER_RIDING_STYLED_ITEM('overriding color',(#200751),#119152, + #198353); +#200751 = PRESENTATION_STYLE_ASSIGNMENT((#200752)); +#200752 = SURFACE_STYLE_USAGE(.BOTH.,#200753); +#200753 = SURFACE_SIDE_STYLE('',(#200754)); +#200754 = SURFACE_STYLE_FILL_AREA(#200755); +#200755 = FILL_AREA_STYLE('',(#200756)); +#200756 = FILL_AREA_STYLE_COLOUR('',#198418); +#200757 = OVER_RIDING_STYLED_ITEM('overriding color',(#200758),#119207, + #198353); +#200758 = PRESENTATION_STYLE_ASSIGNMENT((#200759)); +#200759 = SURFACE_STYLE_USAGE(.BOTH.,#200760); +#200760 = SURFACE_SIDE_STYLE('',(#200761)); +#200761 = SURFACE_STYLE_FILL_AREA(#200762); +#200762 = FILL_AREA_STYLE('',(#200763)); +#200763 = FILL_AREA_STYLE_COLOUR('',#198418); +#200764 = OVER_RIDING_STYLED_ITEM('overriding color',(#200765),#119234, + #198353); +#200765 = PRESENTATION_STYLE_ASSIGNMENT((#200766)); +#200766 = SURFACE_STYLE_USAGE(.BOTH.,#200767); +#200767 = SURFACE_SIDE_STYLE('',(#200768)); +#200768 = SURFACE_STYLE_FILL_AREA(#200769); +#200769 = FILL_AREA_STYLE('',(#200770)); +#200770 = FILL_AREA_STYLE_COLOUR('',#198418); +#200771 = OVER_RIDING_STYLED_ITEM('overriding color',(#200772),#119269, + #198353); +#200772 = PRESENTATION_STYLE_ASSIGNMENT((#200773)); +#200773 = SURFACE_STYLE_USAGE(.BOTH.,#200774); +#200774 = SURFACE_SIDE_STYLE('',(#200775)); +#200775 = SURFACE_STYLE_FILL_AREA(#200776); +#200776 = FILL_AREA_STYLE('',(#200777)); +#200777 = FILL_AREA_STYLE_COLOUR('',#198418); +#200778 = OVER_RIDING_STYLED_ITEM('overriding color',(#200779),#119276, + #198353); +#200779 = PRESENTATION_STYLE_ASSIGNMENT((#200780)); +#200780 = SURFACE_STYLE_USAGE(.BOTH.,#200781); +#200781 = SURFACE_SIDE_STYLE('',(#200782)); +#200782 = SURFACE_STYLE_FILL_AREA(#200783); +#200783 = FILL_AREA_STYLE('',(#200784)); +#200784 = FILL_AREA_STYLE_COLOUR('',#198418); +#200785 = OVER_RIDING_STYLED_ITEM('overriding color',(#200786),#119385, + #198353); +#200786 = PRESENTATION_STYLE_ASSIGNMENT((#200787)); +#200787 = SURFACE_STYLE_USAGE(.BOTH.,#200788); +#200788 = SURFACE_SIDE_STYLE('',(#200789)); +#200789 = SURFACE_STYLE_FILL_AREA(#200790); +#200790 = FILL_AREA_STYLE('',(#200791)); +#200791 = FILL_AREA_STYLE_COLOUR('',#198418); +#200792 = OVER_RIDING_STYLED_ITEM('overriding color',(#200793),#119489, + #198353); +#200793 = PRESENTATION_STYLE_ASSIGNMENT((#200794)); +#200794 = SURFACE_STYLE_USAGE(.BOTH.,#200795); +#200795 = SURFACE_SIDE_STYLE('',(#200796)); +#200796 = SURFACE_STYLE_FILL_AREA(#200797); +#200797 = FILL_AREA_STYLE('',(#200798)); +#200798 = FILL_AREA_STYLE_COLOUR('',#198418); +#200799 = OVER_RIDING_STYLED_ITEM('overriding color',(#200800),#119568, + #198353); +#200800 = PRESENTATION_STYLE_ASSIGNMENT((#200801)); +#200801 = SURFACE_STYLE_USAGE(.BOTH.,#200802); +#200802 = SURFACE_SIDE_STYLE('',(#200803)); +#200803 = SURFACE_STYLE_FILL_AREA(#200804); +#200804 = FILL_AREA_STYLE('',(#200805)); +#200805 = FILL_AREA_STYLE_COLOUR('',#198418); +#200806 = OVER_RIDING_STYLED_ITEM('overriding color',(#200807),#119647, + #198353); +#200807 = PRESENTATION_STYLE_ASSIGNMENT((#200808)); +#200808 = SURFACE_STYLE_USAGE(.BOTH.,#200809); +#200809 = SURFACE_SIDE_STYLE('',(#200810)); +#200810 = SURFACE_STYLE_FILL_AREA(#200811); +#200811 = FILL_AREA_STYLE('',(#200812)); +#200812 = FILL_AREA_STYLE_COLOUR('',#198418); +#200813 = OVER_RIDING_STYLED_ITEM('overriding color',(#200814),#119722, + #198353); +#200814 = PRESENTATION_STYLE_ASSIGNMENT((#200815)); +#200815 = SURFACE_STYLE_USAGE(.BOTH.,#200816); +#200816 = SURFACE_SIDE_STYLE('',(#200817)); +#200817 = SURFACE_STYLE_FILL_AREA(#200818); +#200818 = FILL_AREA_STYLE('',(#200819)); +#200819 = FILL_AREA_STYLE_COLOUR('',#198418); +#200820 = OVER_RIDING_STYLED_ITEM('overriding color',(#200821),#119797, + #198353); +#200821 = PRESENTATION_STYLE_ASSIGNMENT((#200822)); +#200822 = SURFACE_STYLE_USAGE(.BOTH.,#200823); +#200823 = SURFACE_SIDE_STYLE('',(#200824)); +#200824 = SURFACE_STYLE_FILL_AREA(#200825); +#200825 = FILL_AREA_STYLE('',(#200826)); +#200826 = FILL_AREA_STYLE_COLOUR('',#198418); +#200827 = OVER_RIDING_STYLED_ITEM('overriding color',(#200828),#119894, + #198353); +#200828 = PRESENTATION_STYLE_ASSIGNMENT((#200829)); +#200829 = SURFACE_STYLE_USAGE(.BOTH.,#200830); +#200830 = SURFACE_SIDE_STYLE('',(#200831)); +#200831 = SURFACE_STYLE_FILL_AREA(#200832); +#200832 = FILL_AREA_STYLE('',(#200833)); +#200833 = FILL_AREA_STYLE_COLOUR('',#198418); +#200834 = OVER_RIDING_STYLED_ITEM('overriding color',(#200835),#119991, + #198353); +#200835 = PRESENTATION_STYLE_ASSIGNMENT((#200836)); +#200836 = SURFACE_STYLE_USAGE(.BOTH.,#200837); +#200837 = SURFACE_SIDE_STYLE('',(#200838)); +#200838 = SURFACE_STYLE_FILL_AREA(#200839); +#200839 = FILL_AREA_STYLE('',(#200840)); +#200840 = FILL_AREA_STYLE_COLOUR('',#198418); +#200841 = OVER_RIDING_STYLED_ITEM('overriding color',(#200842),#120038, + #198353); +#200842 = PRESENTATION_STYLE_ASSIGNMENT((#200843)); +#200843 = SURFACE_STYLE_USAGE(.BOTH.,#200844); +#200844 = SURFACE_SIDE_STYLE('',(#200845)); +#200845 = SURFACE_STYLE_FILL_AREA(#200846); +#200846 = FILL_AREA_STYLE('',(#200847)); +#200847 = FILL_AREA_STYLE_COLOUR('',#198418); +#200848 = OVER_RIDING_STYLED_ITEM('overriding color',(#200849),#120093, + #198353); +#200849 = PRESENTATION_STYLE_ASSIGNMENT((#200850)); +#200850 = SURFACE_STYLE_USAGE(.BOTH.,#200851); +#200851 = SURFACE_SIDE_STYLE('',(#200852)); +#200852 = SURFACE_STYLE_FILL_AREA(#200853); +#200853 = FILL_AREA_STYLE('',(#200854)); +#200854 = FILL_AREA_STYLE_COLOUR('',#198418); +#200855 = OVER_RIDING_STYLED_ITEM('overriding color',(#200856),#120120, + #198353); +#200856 = PRESENTATION_STYLE_ASSIGNMENT((#200857)); +#200857 = SURFACE_STYLE_USAGE(.BOTH.,#200858); +#200858 = SURFACE_SIDE_STYLE('',(#200859)); +#200859 = SURFACE_STYLE_FILL_AREA(#200860); +#200860 = FILL_AREA_STYLE('',(#200861)); +#200861 = FILL_AREA_STYLE_COLOUR('',#198418); +#200862 = OVER_RIDING_STYLED_ITEM('overriding color',(#200863),#120155, + #198353); +#200863 = PRESENTATION_STYLE_ASSIGNMENT((#200864)); +#200864 = SURFACE_STYLE_USAGE(.BOTH.,#200865); +#200865 = SURFACE_SIDE_STYLE('',(#200866)); +#200866 = SURFACE_STYLE_FILL_AREA(#200867); +#200867 = FILL_AREA_STYLE('',(#200868)); +#200868 = FILL_AREA_STYLE_COLOUR('',#198418); +#200869 = OVER_RIDING_STYLED_ITEM('overriding color',(#200870),#120162, + #198353); +#200870 = PRESENTATION_STYLE_ASSIGNMENT((#200871)); +#200871 = SURFACE_STYLE_USAGE(.BOTH.,#200872); +#200872 = SURFACE_SIDE_STYLE('',(#200873)); +#200873 = SURFACE_STYLE_FILL_AREA(#200874); +#200874 = FILL_AREA_STYLE('',(#200875)); +#200875 = FILL_AREA_STYLE_COLOUR('',#198418); +#200876 = OVER_RIDING_STYLED_ITEM('overriding color',(#200877),#120271, + #198353); +#200877 = PRESENTATION_STYLE_ASSIGNMENT((#200878)); +#200878 = SURFACE_STYLE_USAGE(.BOTH.,#200879); +#200879 = SURFACE_SIDE_STYLE('',(#200880)); +#200880 = SURFACE_STYLE_FILL_AREA(#200881); +#200881 = FILL_AREA_STYLE('',(#200882)); +#200882 = FILL_AREA_STYLE_COLOUR('',#198418); +#200883 = OVER_RIDING_STYLED_ITEM('overriding color',(#200884),#120375, + #198353); +#200884 = PRESENTATION_STYLE_ASSIGNMENT((#200885)); +#200885 = SURFACE_STYLE_USAGE(.BOTH.,#200886); +#200886 = SURFACE_SIDE_STYLE('',(#200887)); +#200887 = SURFACE_STYLE_FILL_AREA(#200888); +#200888 = FILL_AREA_STYLE('',(#200889)); +#200889 = FILL_AREA_STYLE_COLOUR('',#198418); +#200890 = OVER_RIDING_STYLED_ITEM('overriding color',(#200891),#120454, + #198353); +#200891 = PRESENTATION_STYLE_ASSIGNMENT((#200892)); +#200892 = SURFACE_STYLE_USAGE(.BOTH.,#200893); +#200893 = SURFACE_SIDE_STYLE('',(#200894)); +#200894 = SURFACE_STYLE_FILL_AREA(#200895); +#200895 = FILL_AREA_STYLE('',(#200896)); +#200896 = FILL_AREA_STYLE_COLOUR('',#198418); +#200897 = OVER_RIDING_STYLED_ITEM('overriding color',(#200898),#120533, + #198353); +#200898 = PRESENTATION_STYLE_ASSIGNMENT((#200899)); +#200899 = SURFACE_STYLE_USAGE(.BOTH.,#200900); +#200900 = SURFACE_SIDE_STYLE('',(#200901)); +#200901 = SURFACE_STYLE_FILL_AREA(#200902); +#200902 = FILL_AREA_STYLE('',(#200903)); +#200903 = FILL_AREA_STYLE_COLOUR('',#198418); +#200904 = OVER_RIDING_STYLED_ITEM('overriding color',(#200905),#120608, + #198353); +#200905 = PRESENTATION_STYLE_ASSIGNMENT((#200906)); +#200906 = SURFACE_STYLE_USAGE(.BOTH.,#200907); +#200907 = SURFACE_SIDE_STYLE('',(#200908)); +#200908 = SURFACE_STYLE_FILL_AREA(#200909); +#200909 = FILL_AREA_STYLE('',(#200910)); +#200910 = FILL_AREA_STYLE_COLOUR('',#198418); +#200911 = OVER_RIDING_STYLED_ITEM('overriding color',(#200912),#120683, + #198353); +#200912 = PRESENTATION_STYLE_ASSIGNMENT((#200913)); +#200913 = SURFACE_STYLE_USAGE(.BOTH.,#200914); +#200914 = SURFACE_SIDE_STYLE('',(#200915)); +#200915 = SURFACE_STYLE_FILL_AREA(#200916); +#200916 = FILL_AREA_STYLE('',(#200917)); +#200917 = FILL_AREA_STYLE_COLOUR('',#198418); +#200918 = OVER_RIDING_STYLED_ITEM('overriding color',(#200919),#120780, + #198353); +#200919 = PRESENTATION_STYLE_ASSIGNMENT((#200920)); +#200920 = SURFACE_STYLE_USAGE(.BOTH.,#200921); +#200921 = SURFACE_SIDE_STYLE('',(#200922)); +#200922 = SURFACE_STYLE_FILL_AREA(#200923); +#200923 = FILL_AREA_STYLE('',(#200924)); +#200924 = FILL_AREA_STYLE_COLOUR('',#198418); +#200925 = OVER_RIDING_STYLED_ITEM('overriding color',(#200926),#120877, + #198353); +#200926 = PRESENTATION_STYLE_ASSIGNMENT((#200927)); +#200927 = SURFACE_STYLE_USAGE(.BOTH.,#200928); +#200928 = SURFACE_SIDE_STYLE('',(#200929)); +#200929 = SURFACE_STYLE_FILL_AREA(#200930); +#200930 = FILL_AREA_STYLE('',(#200931)); +#200931 = FILL_AREA_STYLE_COLOUR('',#198418); +#200932 = OVER_RIDING_STYLED_ITEM('overriding color',(#200933),#120924, + #198353); +#200933 = PRESENTATION_STYLE_ASSIGNMENT((#200934)); +#200934 = SURFACE_STYLE_USAGE(.BOTH.,#200935); +#200935 = SURFACE_SIDE_STYLE('',(#200936)); +#200936 = SURFACE_STYLE_FILL_AREA(#200937); +#200937 = FILL_AREA_STYLE('',(#200938)); +#200938 = FILL_AREA_STYLE_COLOUR('',#198418); +#200939 = OVER_RIDING_STYLED_ITEM('overriding color',(#200940),#120979, + #198353); +#200940 = PRESENTATION_STYLE_ASSIGNMENT((#200941)); +#200941 = SURFACE_STYLE_USAGE(.BOTH.,#200942); +#200942 = SURFACE_SIDE_STYLE('',(#200943)); +#200943 = SURFACE_STYLE_FILL_AREA(#200944); +#200944 = FILL_AREA_STYLE('',(#200945)); +#200945 = FILL_AREA_STYLE_COLOUR('',#198418); +#200946 = OVER_RIDING_STYLED_ITEM('overriding color',(#200947),#121006, + #198353); +#200947 = PRESENTATION_STYLE_ASSIGNMENT((#200948)); +#200948 = SURFACE_STYLE_USAGE(.BOTH.,#200949); +#200949 = SURFACE_SIDE_STYLE('',(#200950)); +#200950 = SURFACE_STYLE_FILL_AREA(#200951); +#200951 = FILL_AREA_STYLE('',(#200952)); +#200952 = FILL_AREA_STYLE_COLOUR('',#198418); +#200953 = OVER_RIDING_STYLED_ITEM('overriding color',(#200954),#121041, + #198353); +#200954 = PRESENTATION_STYLE_ASSIGNMENT((#200955)); +#200955 = SURFACE_STYLE_USAGE(.BOTH.,#200956); +#200956 = SURFACE_SIDE_STYLE('',(#200957)); +#200957 = SURFACE_STYLE_FILL_AREA(#200958); +#200958 = FILL_AREA_STYLE('',(#200959)); +#200959 = FILL_AREA_STYLE_COLOUR('',#198418); +#200960 = OVER_RIDING_STYLED_ITEM('overriding color',(#200961),#121048, + #198353); +#200961 = PRESENTATION_STYLE_ASSIGNMENT((#200962)); +#200962 = SURFACE_STYLE_USAGE(.BOTH.,#200963); +#200963 = SURFACE_SIDE_STYLE('',(#200964)); +#200964 = SURFACE_STYLE_FILL_AREA(#200965); +#200965 = FILL_AREA_STYLE('',(#200966)); +#200966 = FILL_AREA_STYLE_COLOUR('',#198418); +#200967 = OVER_RIDING_STYLED_ITEM('overriding color',(#200968),#121157, + #198353); +#200968 = PRESENTATION_STYLE_ASSIGNMENT((#200969)); +#200969 = SURFACE_STYLE_USAGE(.BOTH.,#200970); +#200970 = SURFACE_SIDE_STYLE('',(#200971)); +#200971 = SURFACE_STYLE_FILL_AREA(#200972); +#200972 = FILL_AREA_STYLE('',(#200973)); +#200973 = FILL_AREA_STYLE_COLOUR('',#198418); +#200974 = OVER_RIDING_STYLED_ITEM('overriding color',(#200975),#121261, + #198353); +#200975 = PRESENTATION_STYLE_ASSIGNMENT((#200976)); +#200976 = SURFACE_STYLE_USAGE(.BOTH.,#200977); +#200977 = SURFACE_SIDE_STYLE('',(#200978)); +#200978 = SURFACE_STYLE_FILL_AREA(#200979); +#200979 = FILL_AREA_STYLE('',(#200980)); +#200980 = FILL_AREA_STYLE_COLOUR('',#198418); +#200981 = OVER_RIDING_STYLED_ITEM('overriding color',(#200982),#121340, + #198353); +#200982 = PRESENTATION_STYLE_ASSIGNMENT((#200983)); +#200983 = SURFACE_STYLE_USAGE(.BOTH.,#200984); +#200984 = SURFACE_SIDE_STYLE('',(#200985)); +#200985 = SURFACE_STYLE_FILL_AREA(#200986); +#200986 = FILL_AREA_STYLE('',(#200987)); +#200987 = FILL_AREA_STYLE_COLOUR('',#198418); +#200988 = OVER_RIDING_STYLED_ITEM('overriding color',(#200989),#121419, + #198353); +#200989 = PRESENTATION_STYLE_ASSIGNMENT((#200990)); +#200990 = SURFACE_STYLE_USAGE(.BOTH.,#200991); +#200991 = SURFACE_SIDE_STYLE('',(#200992)); +#200992 = SURFACE_STYLE_FILL_AREA(#200993); +#200993 = FILL_AREA_STYLE('',(#200994)); +#200994 = FILL_AREA_STYLE_COLOUR('',#198418); +#200995 = OVER_RIDING_STYLED_ITEM('overriding color',(#200996),#121494, + #198353); +#200996 = PRESENTATION_STYLE_ASSIGNMENT((#200997)); +#200997 = SURFACE_STYLE_USAGE(.BOTH.,#200998); +#200998 = SURFACE_SIDE_STYLE('',(#200999)); +#200999 = SURFACE_STYLE_FILL_AREA(#201000); +#201000 = FILL_AREA_STYLE('',(#201001)); +#201001 = FILL_AREA_STYLE_COLOUR('',#198418); +#201002 = OVER_RIDING_STYLED_ITEM('overriding color',(#201003),#121569, + #198353); +#201003 = PRESENTATION_STYLE_ASSIGNMENT((#201004)); +#201004 = SURFACE_STYLE_USAGE(.BOTH.,#201005); +#201005 = SURFACE_SIDE_STYLE('',(#201006)); +#201006 = SURFACE_STYLE_FILL_AREA(#201007); +#201007 = FILL_AREA_STYLE('',(#201008)); +#201008 = FILL_AREA_STYLE_COLOUR('',#198418); +#201009 = OVER_RIDING_STYLED_ITEM('overriding color',(#201010),#121666, + #198353); +#201010 = PRESENTATION_STYLE_ASSIGNMENT((#201011)); +#201011 = SURFACE_STYLE_USAGE(.BOTH.,#201012); +#201012 = SURFACE_SIDE_STYLE('',(#201013)); +#201013 = SURFACE_STYLE_FILL_AREA(#201014); +#201014 = FILL_AREA_STYLE('',(#201015)); +#201015 = FILL_AREA_STYLE_COLOUR('',#198418); +#201016 = OVER_RIDING_STYLED_ITEM('overriding color',(#201017),#121763, + #198353); +#201017 = PRESENTATION_STYLE_ASSIGNMENT((#201018)); +#201018 = SURFACE_STYLE_USAGE(.BOTH.,#201019); +#201019 = SURFACE_SIDE_STYLE('',(#201020)); +#201020 = SURFACE_STYLE_FILL_AREA(#201021); +#201021 = FILL_AREA_STYLE('',(#201022)); +#201022 = FILL_AREA_STYLE_COLOUR('',#198418); +#201023 = OVER_RIDING_STYLED_ITEM('overriding color',(#201024),#121810, + #198353); +#201024 = PRESENTATION_STYLE_ASSIGNMENT((#201025)); +#201025 = SURFACE_STYLE_USAGE(.BOTH.,#201026); +#201026 = SURFACE_SIDE_STYLE('',(#201027)); +#201027 = SURFACE_STYLE_FILL_AREA(#201028); +#201028 = FILL_AREA_STYLE('',(#201029)); +#201029 = FILL_AREA_STYLE_COLOUR('',#198418); +#201030 = OVER_RIDING_STYLED_ITEM('overriding color',(#201031),#121865, + #198353); +#201031 = PRESENTATION_STYLE_ASSIGNMENT((#201032)); +#201032 = SURFACE_STYLE_USAGE(.BOTH.,#201033); +#201033 = SURFACE_SIDE_STYLE('',(#201034)); +#201034 = SURFACE_STYLE_FILL_AREA(#201035); +#201035 = FILL_AREA_STYLE('',(#201036)); +#201036 = FILL_AREA_STYLE_COLOUR('',#198418); +#201037 = OVER_RIDING_STYLED_ITEM('overriding color',(#201038),#121892, + #198353); #201038 = PRESENTATION_STYLE_ASSIGNMENT((#201039)); #201039 = SURFACE_STYLE_USAGE(.BOTH.,#201040); #201040 = SURFACE_SIDE_STYLE('',(#201041)); #201041 = SURFACE_STYLE_FILL_AREA(#201042); #201042 = FILL_AREA_STYLE('',(#201043)); -#201043 = FILL_AREA_STYLE_COLOUR('',#201036); -#201044 = OVER_RIDING_STYLED_ITEM('overriding color',(#201045),#73147, - #201021); +#201043 = FILL_AREA_STYLE_COLOUR('',#198418); +#201044 = OVER_RIDING_STYLED_ITEM('overriding color',(#201045),#121927, + #198353); #201045 = PRESENTATION_STYLE_ASSIGNMENT((#201046)); #201046 = SURFACE_STYLE_USAGE(.BOTH.,#201047); #201047 = SURFACE_SIDE_STYLE('',(#201048)); #201048 = SURFACE_STYLE_FILL_AREA(#201049); #201049 = FILL_AREA_STYLE('',(#201050)); -#201050 = FILL_AREA_STYLE_COLOUR('',#201036); -#201051 = OVER_RIDING_STYLED_ITEM('overriding color',(#201052),#73223, - #201021); +#201050 = FILL_AREA_STYLE_COLOUR('',#198418); +#201051 = OVER_RIDING_STYLED_ITEM('overriding color',(#201052),#121934, + #198353); #201052 = PRESENTATION_STYLE_ASSIGNMENT((#201053)); #201053 = SURFACE_STYLE_USAGE(.BOTH.,#201054); #201054 = SURFACE_SIDE_STYLE('',(#201055)); #201055 = SURFACE_STYLE_FILL_AREA(#201056); #201056 = FILL_AREA_STYLE('',(#201057)); -#201057 = FILL_AREA_STYLE_COLOUR('',#201036); -#201058 = OVER_RIDING_STYLED_ITEM('overriding color',(#201059),#73299, - #201021); +#201057 = FILL_AREA_STYLE_COLOUR('',#198418); +#201058 = OVER_RIDING_STYLED_ITEM('overriding color',(#201059),#122043, + #198353); #201059 = PRESENTATION_STYLE_ASSIGNMENT((#201060)); #201060 = SURFACE_STYLE_USAGE(.BOTH.,#201061); #201061 = SURFACE_SIDE_STYLE('',(#201062)); #201062 = SURFACE_STYLE_FILL_AREA(#201063); #201063 = FILL_AREA_STYLE('',(#201064)); -#201064 = FILL_AREA_STYLE_COLOUR('',#201036); -#201065 = OVER_RIDING_STYLED_ITEM('overriding color',(#201066),#73370, - #201021); +#201064 = FILL_AREA_STYLE_COLOUR('',#198418); +#201065 = OVER_RIDING_STYLED_ITEM('overriding color',(#201066),#122147, + #198353); #201066 = PRESENTATION_STYLE_ASSIGNMENT((#201067)); #201067 = SURFACE_STYLE_USAGE(.BOTH.,#201068); #201068 = SURFACE_SIDE_STYLE('',(#201069)); #201069 = SURFACE_STYLE_FILL_AREA(#201070); #201070 = FILL_AREA_STYLE('',(#201071)); -#201071 = FILL_AREA_STYLE_COLOUR('',#201036); -#201072 = OVER_RIDING_STYLED_ITEM('overriding color',(#201073),#74417, - #201021); +#201071 = FILL_AREA_STYLE_COLOUR('',#198418); +#201072 = OVER_RIDING_STYLED_ITEM('overriding color',(#201073),#122226, + #198353); #201073 = PRESENTATION_STYLE_ASSIGNMENT((#201074)); #201074 = SURFACE_STYLE_USAGE(.BOTH.,#201075); #201075 = SURFACE_SIDE_STYLE('',(#201076)); #201076 = SURFACE_STYLE_FILL_AREA(#201077); #201077 = FILL_AREA_STYLE('',(#201078)); -#201078 = FILL_AREA_STYLE_COLOUR('',#201036); -#201079 = OVER_RIDING_STYLED_ITEM('overriding color',(#201080),#74556, - #201021); +#201078 = FILL_AREA_STYLE_COLOUR('',#198418); +#201079 = OVER_RIDING_STYLED_ITEM('overriding color',(#201080),#122305, + #198353); #201080 = PRESENTATION_STYLE_ASSIGNMENT((#201081)); #201081 = SURFACE_STYLE_USAGE(.BOTH.,#201082); #201082 = SURFACE_SIDE_STYLE('',(#201083)); #201083 = SURFACE_STYLE_FILL_AREA(#201084); #201084 = FILL_AREA_STYLE('',(#201085)); -#201085 = FILL_AREA_STYLE_COLOUR('',#201036); -#201086 = OVER_RIDING_STYLED_ITEM('overriding color',(#201087),#74638, - #201021); +#201085 = FILL_AREA_STYLE_COLOUR('',#198418); +#201086 = OVER_RIDING_STYLED_ITEM('overriding color',(#201087),#122380, + #198353); #201087 = PRESENTATION_STYLE_ASSIGNMENT((#201088)); #201088 = SURFACE_STYLE_USAGE(.BOTH.,#201089); #201089 = SURFACE_SIDE_STYLE('',(#201090)); #201090 = SURFACE_STYLE_FILL_AREA(#201091); #201091 = FILL_AREA_STYLE('',(#201092)); -#201092 = FILL_AREA_STYLE_COLOUR('',#201036); -#201093 = OVER_RIDING_STYLED_ITEM('overriding color',(#201094),#74700, - #201021); +#201092 = FILL_AREA_STYLE_COLOUR('',#198418); +#201093 = OVER_RIDING_STYLED_ITEM('overriding color',(#201094),#122455, + #198353); #201094 = PRESENTATION_STYLE_ASSIGNMENT((#201095)); #201095 = SURFACE_STYLE_USAGE(.BOTH.,#201096); #201096 = SURFACE_SIDE_STYLE('',(#201097)); #201097 = SURFACE_STYLE_FILL_AREA(#201098); #201098 = FILL_AREA_STYLE('',(#201099)); -#201099 = FILL_AREA_STYLE_COLOUR('',#201036); -#201100 = OVER_RIDING_STYLED_ITEM('overriding color',(#201101),#74797, - #201021); +#201099 = FILL_AREA_STYLE_COLOUR('',#198418); +#201100 = OVER_RIDING_STYLED_ITEM('overriding color',(#201101),#122552, + #198353); #201101 = PRESENTATION_STYLE_ASSIGNMENT((#201102)); #201102 = SURFACE_STYLE_USAGE(.BOTH.,#201103); #201103 = SURFACE_SIDE_STYLE('',(#201104)); #201104 = SURFACE_STYLE_FILL_AREA(#201105); #201105 = FILL_AREA_STYLE('',(#201106)); -#201106 = FILL_AREA_STYLE_COLOUR('',#201036); -#201107 = OVER_RIDING_STYLED_ITEM('overriding color',(#201108),#74839, - #201021); +#201106 = FILL_AREA_STYLE_COLOUR('',#198418); +#201107 = OVER_RIDING_STYLED_ITEM('overriding color',(#201108),#122649, + #198353); #201108 = PRESENTATION_STYLE_ASSIGNMENT((#201109)); #201109 = SURFACE_STYLE_USAGE(.BOTH.,#201110); #201110 = SURFACE_SIDE_STYLE('',(#201111)); #201111 = SURFACE_STYLE_FILL_AREA(#201112); #201112 = FILL_AREA_STYLE('',(#201113)); -#201113 = FILL_AREA_STYLE_COLOUR('',#201036); -#201114 = OVER_RIDING_STYLED_ITEM('overriding color',(#201115),#74901, - #201021); +#201113 = FILL_AREA_STYLE_COLOUR('',#198418); +#201114 = OVER_RIDING_STYLED_ITEM('overriding color',(#201115),#122696, + #198353); #201115 = PRESENTATION_STYLE_ASSIGNMENT((#201116)); #201116 = SURFACE_STYLE_USAGE(.BOTH.,#201117); #201117 = SURFACE_SIDE_STYLE('',(#201118)); #201118 = SURFACE_STYLE_FILL_AREA(#201119); #201119 = FILL_AREA_STYLE('',(#201120)); -#201120 = FILL_AREA_STYLE_COLOUR('',#201036); -#201121 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201122,#201130,#201137,#201144,#201152,#201159,#201166,#201173, - #201180,#201187,#201194,#201201,#201208,#201215,#201222,#201229, - #201236,#201243,#201250,#201257,#201264,#201271,#201278,#201285, - #201292,#201299,#201306,#201313,#201320,#201327,#201334,#201341, - #201348,#201355,#201362,#201369,#201376,#201383,#201390,#201397, - #201404,#201411,#201418,#201425,#201432,#201439,#201446,#201453, - #201460,#201467,#201474,#201481,#201488,#201495,#201502,#201509, - #201516,#201523,#201530,#201537,#201544,#201551,#201558,#201565, - #201572,#201579,#201586,#201593,#201600,#201607,#201614,#201621, - #201628,#201635,#201642,#201649,#201656,#201663,#201670,#201677, - #201684,#201691,#201698,#201705,#201712,#201719,#201726,#201733, - #201740,#201747),#28455); -#201122 = STYLED_ITEM('color',(#201123),#22039); -#201123 = PRESENTATION_STYLE_ASSIGNMENT((#201124)); -#201124 = SURFACE_STYLE_USAGE(.BOTH.,#201125); -#201125 = SURFACE_SIDE_STYLE('',(#201126)); -#201126 = SURFACE_STYLE_FILL_AREA(#201127); -#201127 = FILL_AREA_STYLE('',(#201128)); -#201128 = FILL_AREA_STYLE_COLOUR('',#201129); -#201129 = COLOUR_RGB('',0.E+000,0.501960813999,0.501960813999); -#201130 = OVER_RIDING_STYLED_ITEM('overriding color',(#201131),#22041, - #201122); -#201131 = PRESENTATION_STYLE_ASSIGNMENT((#201132)); -#201132 = SURFACE_STYLE_USAGE(.BOTH.,#201133); -#201133 = SURFACE_SIDE_STYLE('',(#201134)); -#201134 = SURFACE_STYLE_FILL_AREA(#201135); -#201135 = FILL_AREA_STYLE('',(#201136)); -#201136 = FILL_AREA_STYLE_COLOUR('',#201028); -#201137 = OVER_RIDING_STYLED_ITEM('overriding color',(#201138),#22161, - #201122); -#201138 = PRESENTATION_STYLE_ASSIGNMENT((#201139)); -#201139 = SURFACE_STYLE_USAGE(.BOTH.,#201140); -#201140 = SURFACE_SIDE_STYLE('',(#201141)); -#201141 = SURFACE_STYLE_FILL_AREA(#201142); -#201142 = FILL_AREA_STYLE('',(#201143)); -#201143 = FILL_AREA_STYLE_COLOUR('',#201028); -#201144 = OVER_RIDING_STYLED_ITEM('overriding color',(#201145),#22237, - #201122); -#201145 = PRESENTATION_STYLE_ASSIGNMENT((#201146)); -#201146 = SURFACE_STYLE_USAGE(.BOTH.,#201147); -#201147 = SURFACE_SIDE_STYLE('',(#201148)); -#201148 = SURFACE_STYLE_FILL_AREA(#201149); -#201149 = FILL_AREA_STYLE('',(#201150)); -#201150 = FILL_AREA_STYLE_COLOUR('',#201151); -#201151 = COLOUR_RGB('',0.7109375,0.6015625,0.4140625); -#201152 = OVER_RIDING_STYLED_ITEM('overriding color',(#201153),#22742, - #201122); -#201153 = PRESENTATION_STYLE_ASSIGNMENT((#201154)); -#201154 = SURFACE_STYLE_USAGE(.BOTH.,#201155); -#201155 = SURFACE_SIDE_STYLE('',(#201156)); -#201156 = SURFACE_STYLE_FILL_AREA(#201157); -#201157 = FILL_AREA_STYLE('',(#201158)); -#201158 = FILL_AREA_STYLE_COLOUR('',#201028); -#201159 = OVER_RIDING_STYLED_ITEM('overriding color',(#201160),#22791, - #201122); -#201160 = PRESENTATION_STYLE_ASSIGNMENT((#201161)); -#201161 = SURFACE_STYLE_USAGE(.BOTH.,#201162); -#201162 = SURFACE_SIDE_STYLE('',(#201163)); -#201163 = SURFACE_STYLE_FILL_AREA(#201164); -#201164 = FILL_AREA_STYLE('',(#201165)); -#201165 = FILL_AREA_STYLE_COLOUR('',#201028); -#201166 = OVER_RIDING_STYLED_ITEM('overriding color',(#201167),#22818, - #201122); -#201167 = PRESENTATION_STYLE_ASSIGNMENT((#201168)); -#201168 = SURFACE_STYLE_USAGE(.BOTH.,#201169); -#201169 = SURFACE_SIDE_STYLE('',(#201170)); -#201170 = SURFACE_STYLE_FILL_AREA(#201171); -#201171 = FILL_AREA_STYLE('',(#201172)); -#201172 = FILL_AREA_STYLE_COLOUR('',#201028); -#201173 = OVER_RIDING_STYLED_ITEM('overriding color',(#201174),#22825, - #201122); -#201174 = PRESENTATION_STYLE_ASSIGNMENT((#201175)); -#201175 = SURFACE_STYLE_USAGE(.BOTH.,#201176); -#201176 = SURFACE_SIDE_STYLE('',(#201177)); -#201177 = SURFACE_STYLE_FILL_AREA(#201178); -#201178 = FILL_AREA_STYLE('',(#201179)); -#201179 = FILL_AREA_STYLE_COLOUR('',#201151); -#201180 = OVER_RIDING_STYLED_ITEM('overriding color',(#201181),#22901, - #201122); -#201181 = PRESENTATION_STYLE_ASSIGNMENT((#201182)); -#201182 = SURFACE_STYLE_USAGE(.BOTH.,#201183); -#201183 = SURFACE_SIDE_STYLE('',(#201184)); -#201184 = SURFACE_STYLE_FILL_AREA(#201185); -#201185 = FILL_AREA_STYLE('',(#201186)); -#201186 = FILL_AREA_STYLE_COLOUR('',#201028); -#201187 = OVER_RIDING_STYLED_ITEM('overriding color',(#201188),#22977, - #201122); -#201188 = PRESENTATION_STYLE_ASSIGNMENT((#201189)); -#201189 = SURFACE_STYLE_USAGE(.BOTH.,#201190); -#201190 = SURFACE_SIDE_STYLE('',(#201191)); -#201191 = SURFACE_STYLE_FILL_AREA(#201192); -#201192 = FILL_AREA_STYLE('',(#201193)); -#201193 = FILL_AREA_STYLE_COLOUR('',#201151); -#201194 = OVER_RIDING_STYLED_ITEM('overriding color',(#201195),#23133, - #201122); -#201195 = PRESENTATION_STYLE_ASSIGNMENT((#201196)); -#201196 = SURFACE_STYLE_USAGE(.BOTH.,#201197); -#201197 = SURFACE_SIDE_STYLE('',(#201198)); -#201198 = SURFACE_STYLE_FILL_AREA(#201199); -#201199 = FILL_AREA_STYLE('',(#201200)); -#201200 = FILL_AREA_STYLE_COLOUR('',#201028); -#201201 = OVER_RIDING_STYLED_ITEM('overriding color',(#201202),#23209, - #201122); -#201202 = PRESENTATION_STYLE_ASSIGNMENT((#201203)); -#201203 = SURFACE_STYLE_USAGE(.BOTH.,#201204); -#201204 = SURFACE_SIDE_STYLE('',(#201205)); -#201205 = SURFACE_STYLE_FILL_AREA(#201206); -#201206 = FILL_AREA_STYLE('',(#201207)); -#201207 = FILL_AREA_STYLE_COLOUR('',#201028); -#201208 = OVER_RIDING_STYLED_ITEM('overriding color',(#201209),#23285, - #201122); -#201209 = PRESENTATION_STYLE_ASSIGNMENT((#201210)); -#201210 = SURFACE_STYLE_USAGE(.BOTH.,#201211); -#201211 = SURFACE_SIDE_STYLE('',(#201212)); -#201212 = SURFACE_STYLE_FILL_AREA(#201213); -#201213 = FILL_AREA_STYLE('',(#201214)); -#201214 = FILL_AREA_STYLE_COLOUR('',#201151); -#201215 = OVER_RIDING_STYLED_ITEM('overriding color',(#201216),#23334, - #201122); -#201216 = PRESENTATION_STYLE_ASSIGNMENT((#201217)); -#201217 = SURFACE_STYLE_USAGE(.BOTH.,#201218); -#201218 = SURFACE_SIDE_STYLE('',(#201219)); -#201219 = SURFACE_STYLE_FILL_AREA(#201220); -#201220 = FILL_AREA_STYLE('',(#201221)); -#201221 = FILL_AREA_STYLE_COLOUR('',#201028); -#201222 = OVER_RIDING_STYLED_ITEM('overriding color',(#201223),#23383, - #201122); -#201223 = PRESENTATION_STYLE_ASSIGNMENT((#201224)); -#201224 = SURFACE_STYLE_USAGE(.BOTH.,#201225); -#201225 = SURFACE_SIDE_STYLE('',(#201226)); -#201226 = SURFACE_STYLE_FILL_AREA(#201227); -#201227 = FILL_AREA_STYLE('',(#201228)); -#201228 = FILL_AREA_STYLE_COLOUR('',#201028); -#201229 = OVER_RIDING_STYLED_ITEM('overriding color',(#201230),#23454, - #201122); -#201230 = PRESENTATION_STYLE_ASSIGNMENT((#201231)); -#201231 = SURFACE_STYLE_USAGE(.BOTH.,#201232); -#201232 = SURFACE_SIDE_STYLE('',(#201233)); -#201233 = SURFACE_STYLE_FILL_AREA(#201234); -#201234 = FILL_AREA_STYLE('',(#201235)); -#201235 = FILL_AREA_STYLE_COLOUR('',#201028); -#201236 = OVER_RIDING_STYLED_ITEM('overriding color',(#201237),#23525, - #201122); -#201237 = PRESENTATION_STYLE_ASSIGNMENT((#201238)); -#201238 = SURFACE_STYLE_USAGE(.BOTH.,#201239); -#201239 = SURFACE_SIDE_STYLE('',(#201240)); -#201240 = SURFACE_STYLE_FILL_AREA(#201241); -#201241 = FILL_AREA_STYLE('',(#201242)); -#201242 = FILL_AREA_STYLE_COLOUR('',#201028); -#201243 = OVER_RIDING_STYLED_ITEM('overriding color',(#201244),#23574, - #201122); -#201244 = PRESENTATION_STYLE_ASSIGNMENT((#201245)); -#201245 = SURFACE_STYLE_USAGE(.BOTH.,#201246); -#201246 = SURFACE_SIDE_STYLE('',(#201247)); -#201247 = SURFACE_STYLE_FILL_AREA(#201248); -#201248 = FILL_AREA_STYLE('',(#201249)); -#201249 = FILL_AREA_STYLE_COLOUR('',#201028); -#201250 = OVER_RIDING_STYLED_ITEM('overriding color',(#201251),#23601, - #201122); -#201251 = PRESENTATION_STYLE_ASSIGNMENT((#201252)); -#201252 = SURFACE_STYLE_USAGE(.BOTH.,#201253); -#201253 = SURFACE_SIDE_STYLE('',(#201254)); -#201254 = SURFACE_STYLE_FILL_AREA(#201255); -#201255 = FILL_AREA_STYLE('',(#201256)); -#201256 = FILL_AREA_STYLE_COLOUR('',#201151); -#201257 = OVER_RIDING_STYLED_ITEM('overriding color',(#201258),#23735, - #201122); -#201258 = PRESENTATION_STYLE_ASSIGNMENT((#201259)); -#201259 = SURFACE_STYLE_USAGE(.BOTH.,#201260); -#201260 = SURFACE_SIDE_STYLE('',(#201261)); -#201261 = SURFACE_STYLE_FILL_AREA(#201262); -#201262 = FILL_AREA_STYLE('',(#201263)); -#201263 = FILL_AREA_STYLE_COLOUR('',#201028); -#201264 = OVER_RIDING_STYLED_ITEM('overriding color',(#201265),#23762, - #201122); -#201265 = PRESENTATION_STYLE_ASSIGNMENT((#201266)); -#201266 = SURFACE_STYLE_USAGE(.BOTH.,#201267); -#201267 = SURFACE_SIDE_STYLE('',(#201268)); -#201268 = SURFACE_STYLE_FILL_AREA(#201269); -#201269 = FILL_AREA_STYLE('',(#201270)); -#201270 = FILL_AREA_STYLE_COLOUR('',#201028); -#201271 = OVER_RIDING_STYLED_ITEM('overriding color',(#201272),#23789, - #201122); -#201272 = PRESENTATION_STYLE_ASSIGNMENT((#201273)); -#201273 = SURFACE_STYLE_USAGE(.BOTH.,#201274); -#201274 = SURFACE_SIDE_STYLE('',(#201275)); -#201275 = SURFACE_STYLE_FILL_AREA(#201276); -#201276 = FILL_AREA_STYLE('',(#201277)); -#201277 = FILL_AREA_STYLE_COLOUR('',#201028); -#201278 = OVER_RIDING_STYLED_ITEM('overriding color',(#201279),#23816, - #201122); -#201279 = PRESENTATION_STYLE_ASSIGNMENT((#201280)); -#201280 = SURFACE_STYLE_USAGE(.BOTH.,#201281); -#201281 = SURFACE_SIDE_STYLE('',(#201282)); -#201282 = SURFACE_STYLE_FILL_AREA(#201283); -#201283 = FILL_AREA_STYLE('',(#201284)); -#201284 = FILL_AREA_STYLE_COLOUR('',#201028); -#201285 = OVER_RIDING_STYLED_ITEM('overriding color',(#201286),#23843, - #201122); -#201286 = PRESENTATION_STYLE_ASSIGNMENT((#201287)); -#201287 = SURFACE_STYLE_USAGE(.BOTH.,#201288); -#201288 = SURFACE_SIDE_STYLE('',(#201289)); -#201289 = SURFACE_STYLE_FILL_AREA(#201290); -#201290 = FILL_AREA_STYLE('',(#201291)); -#201291 = FILL_AREA_STYLE_COLOUR('',#201151); -#201292 = OVER_RIDING_STYLED_ITEM('overriding color',(#201293),#24334, - #201122); -#201293 = PRESENTATION_STYLE_ASSIGNMENT((#201294)); -#201294 = SURFACE_STYLE_USAGE(.BOTH.,#201295); -#201295 = SURFACE_SIDE_STYLE('',(#201296)); -#201296 = SURFACE_STYLE_FILL_AREA(#201297); -#201297 = FILL_AREA_STYLE('',(#201298)); -#201298 = FILL_AREA_STYLE_COLOUR('',#201028); -#201299 = OVER_RIDING_STYLED_ITEM('overriding color',(#201300),#24341, - #201122); -#201300 = PRESENTATION_STYLE_ASSIGNMENT((#201301)); -#201301 = SURFACE_STYLE_USAGE(.BOTH.,#201302); -#201302 = SURFACE_SIDE_STYLE('',(#201303)); -#201303 = SURFACE_STYLE_FILL_AREA(#201304); -#201304 = FILL_AREA_STYLE('',(#201305)); -#201305 = FILL_AREA_STYLE_COLOUR('',#201151); -#201306 = OVER_RIDING_STYLED_ITEM('overriding color',(#201307),#24412, - #201122); -#201307 = PRESENTATION_STYLE_ASSIGNMENT((#201308)); -#201308 = SURFACE_STYLE_USAGE(.BOTH.,#201309); -#201309 = SURFACE_SIDE_STYLE('',(#201310)); -#201310 = SURFACE_STYLE_FILL_AREA(#201311); -#201311 = FILL_AREA_STYLE('',(#201312)); -#201312 = FILL_AREA_STYLE_COLOUR('',#201151); -#201313 = OVER_RIDING_STYLED_ITEM('overriding color',(#201314),#24439, - #201122); -#201314 = PRESENTATION_STYLE_ASSIGNMENT((#201315)); -#201315 = SURFACE_STYLE_USAGE(.BOTH.,#201316); -#201316 = SURFACE_SIDE_STYLE('',(#201317)); -#201317 = SURFACE_STYLE_FILL_AREA(#201318); -#201318 = FILL_AREA_STYLE('',(#201319)); -#201319 = FILL_AREA_STYLE_COLOUR('',#201151); -#201320 = OVER_RIDING_STYLED_ITEM('overriding color',(#201321),#24466, - #201122); -#201321 = PRESENTATION_STYLE_ASSIGNMENT((#201322)); -#201322 = SURFACE_STYLE_USAGE(.BOTH.,#201323); -#201323 = SURFACE_SIDE_STYLE('',(#201324)); -#201324 = SURFACE_STYLE_FILL_AREA(#201325); -#201325 = FILL_AREA_STYLE('',(#201326)); -#201326 = FILL_AREA_STYLE_COLOUR('',#201028); -#201327 = OVER_RIDING_STYLED_ITEM('overriding color',(#201328),#24473, - #201122); -#201328 = PRESENTATION_STYLE_ASSIGNMENT((#201329)); -#201329 = SURFACE_STYLE_USAGE(.BOTH.,#201330); -#201330 = SURFACE_SIDE_STYLE('',(#201331)); -#201331 = SURFACE_STYLE_FILL_AREA(#201332); -#201332 = FILL_AREA_STYLE('',(#201333)); -#201333 = FILL_AREA_STYLE_COLOUR('',#201028); -#201334 = OVER_RIDING_STYLED_ITEM('overriding color',(#201335),#24480, - #201122); -#201335 = PRESENTATION_STYLE_ASSIGNMENT((#201336)); -#201336 = SURFACE_STYLE_USAGE(.BOTH.,#201337); -#201337 = SURFACE_SIDE_STYLE('',(#201338)); -#201338 = SURFACE_STYLE_FILL_AREA(#201339); -#201339 = FILL_AREA_STYLE('',(#201340)); -#201340 = FILL_AREA_STYLE_COLOUR('',#201151); -#201341 = OVER_RIDING_STYLED_ITEM('overriding color',(#201342),#24551, - #201122); -#201342 = PRESENTATION_STYLE_ASSIGNMENT((#201343)); -#201343 = SURFACE_STYLE_USAGE(.BOTH.,#201344); -#201344 = SURFACE_SIDE_STYLE('',(#201345)); -#201345 = SURFACE_STYLE_FILL_AREA(#201346); -#201346 = FILL_AREA_STYLE('',(#201347)); -#201347 = FILL_AREA_STYLE_COLOUR('',#201151); -#201348 = OVER_RIDING_STYLED_ITEM('overriding color',(#201349),#24578, - #201122); -#201349 = PRESENTATION_STYLE_ASSIGNMENT((#201350)); -#201350 = SURFACE_STYLE_USAGE(.BOTH.,#201351); -#201351 = SURFACE_SIDE_STYLE('',(#201352)); -#201352 = SURFACE_STYLE_FILL_AREA(#201353); -#201353 = FILL_AREA_STYLE('',(#201354)); -#201354 = FILL_AREA_STYLE_COLOUR('',#201151); -#201355 = OVER_RIDING_STYLED_ITEM('overriding color',(#201356),#24605, - #201122); -#201356 = PRESENTATION_STYLE_ASSIGNMENT((#201357)); -#201357 = SURFACE_STYLE_USAGE(.BOTH.,#201358); -#201358 = SURFACE_SIDE_STYLE('',(#201359)); -#201359 = SURFACE_STYLE_FILL_AREA(#201360); -#201360 = FILL_AREA_STYLE('',(#201361)); -#201361 = FILL_AREA_STYLE_COLOUR('',#201028); -#201362 = OVER_RIDING_STYLED_ITEM('overriding color',(#201363),#24681, - #201122); -#201363 = PRESENTATION_STYLE_ASSIGNMENT((#201364)); -#201364 = SURFACE_STYLE_USAGE(.BOTH.,#201365); -#201365 = SURFACE_SIDE_STYLE('',(#201366)); -#201366 = SURFACE_STYLE_FILL_AREA(#201367); -#201367 = FILL_AREA_STYLE('',(#201368)); -#201368 = FILL_AREA_STYLE_COLOUR('',#201151); -#201369 = OVER_RIDING_STYLED_ITEM('overriding color',(#201370),#24688, - #201122); -#201370 = PRESENTATION_STYLE_ASSIGNMENT((#201371)); -#201371 = SURFACE_STYLE_USAGE(.BOTH.,#201372); -#201372 = SURFACE_SIDE_STYLE('',(#201373)); -#201373 = SURFACE_STYLE_FILL_AREA(#201374); -#201374 = FILL_AREA_STYLE('',(#201375)); -#201375 = FILL_AREA_STYLE_COLOUR('',#201028); -#201376 = OVER_RIDING_STYLED_ITEM('overriding color',(#201377),#24764, - #201122); -#201377 = PRESENTATION_STYLE_ASSIGNMENT((#201378)); -#201378 = SURFACE_STYLE_USAGE(.BOTH.,#201379); -#201379 = SURFACE_SIDE_STYLE('',(#201380)); -#201380 = SURFACE_STYLE_FILL_AREA(#201381); -#201381 = FILL_AREA_STYLE('',(#201382)); -#201382 = FILL_AREA_STYLE_COLOUR('',#201151); -#201383 = OVER_RIDING_STYLED_ITEM('overriding color',(#201384),#25059, - #201122); -#201384 = PRESENTATION_STYLE_ASSIGNMENT((#201385)); -#201385 = SURFACE_STYLE_USAGE(.BOTH.,#201386); -#201386 = SURFACE_SIDE_STYLE('',(#201387)); -#201387 = SURFACE_STYLE_FILL_AREA(#201388); -#201388 = FILL_AREA_STYLE('',(#201389)); -#201389 = FILL_AREA_STYLE_COLOUR('',#201151); -#201390 = OVER_RIDING_STYLED_ITEM('overriding color',(#201391),#25655, - #201122); -#201391 = PRESENTATION_STYLE_ASSIGNMENT((#201392)); -#201392 = SURFACE_STYLE_USAGE(.BOTH.,#201393); -#201393 = SURFACE_SIDE_STYLE('',(#201394)); -#201394 = SURFACE_STYLE_FILL_AREA(#201395); -#201395 = FILL_AREA_STYLE('',(#201396)); -#201396 = FILL_AREA_STYLE_COLOUR('',#201151); -#201397 = OVER_RIDING_STYLED_ITEM('overriding color',(#201398),#25704, - #201122); -#201398 = PRESENTATION_STYLE_ASSIGNMENT((#201399)); -#201399 = SURFACE_STYLE_USAGE(.BOTH.,#201400); -#201400 = SURFACE_SIDE_STYLE('',(#201401)); -#201401 = SURFACE_STYLE_FILL_AREA(#201402); -#201402 = FILL_AREA_STYLE('',(#201403)); -#201403 = FILL_AREA_STYLE_COLOUR('',#201028); -#201404 = OVER_RIDING_STYLED_ITEM('overriding color',(#201405),#25830, - #201122); -#201405 = PRESENTATION_STYLE_ASSIGNMENT((#201406)); -#201406 = SURFACE_STYLE_USAGE(.BOTH.,#201407); -#201407 = SURFACE_SIDE_STYLE('',(#201408)); -#201408 = SURFACE_STYLE_FILL_AREA(#201409); -#201409 = FILL_AREA_STYLE('',(#201410)); -#201410 = FILL_AREA_STYLE_COLOUR('',#201028); -#201411 = OVER_RIDING_STYLED_ITEM('overriding color',(#201412),#25946, - #201122); -#201412 = PRESENTATION_STYLE_ASSIGNMENT((#201413)); -#201413 = SURFACE_STYLE_USAGE(.BOTH.,#201414); -#201414 = SURFACE_SIDE_STYLE('',(#201415)); -#201415 = SURFACE_STYLE_FILL_AREA(#201416); -#201416 = FILL_AREA_STYLE('',(#201417)); -#201417 = FILL_AREA_STYLE_COLOUR('',#201151); -#201418 = OVER_RIDING_STYLED_ITEM('overriding color',(#201419),#26102, - #201122); -#201419 = PRESENTATION_STYLE_ASSIGNMENT((#201420)); -#201420 = SURFACE_STYLE_USAGE(.BOTH.,#201421); -#201421 = SURFACE_SIDE_STYLE('',(#201422)); -#201422 = SURFACE_STYLE_FILL_AREA(#201423); -#201423 = FILL_AREA_STYLE('',(#201424)); -#201424 = FILL_AREA_STYLE_COLOUR('',#201028); -#201425 = OVER_RIDING_STYLED_ITEM('overriding color',(#201426),#26129, - #201122); -#201426 = PRESENTATION_STYLE_ASSIGNMENT((#201427)); -#201427 = SURFACE_STYLE_USAGE(.BOTH.,#201428); -#201428 = SURFACE_SIDE_STYLE('',(#201429)); -#201429 = SURFACE_STYLE_FILL_AREA(#201430); -#201430 = FILL_AREA_STYLE('',(#201431)); -#201431 = FILL_AREA_STYLE_COLOUR('',#201151); -#201432 = OVER_RIDING_STYLED_ITEM('overriding color',(#201433),#26353, - #201122); -#201433 = PRESENTATION_STYLE_ASSIGNMENT((#201434)); -#201434 = SURFACE_STYLE_USAGE(.BOTH.,#201435); -#201435 = SURFACE_SIDE_STYLE('',(#201436)); -#201436 = SURFACE_STYLE_FILL_AREA(#201437); -#201437 = FILL_AREA_STYLE('',(#201438)); -#201438 = FILL_AREA_STYLE_COLOUR('',#201151); -#201439 = OVER_RIDING_STYLED_ITEM('overriding color',(#201440),#26360, - #201122); -#201440 = PRESENTATION_STYLE_ASSIGNMENT((#201441)); -#201441 = SURFACE_STYLE_USAGE(.BOTH.,#201442); -#201442 = SURFACE_SIDE_STYLE('',(#201443)); -#201443 = SURFACE_STYLE_FILL_AREA(#201444); -#201444 = FILL_AREA_STYLE('',(#201445)); -#201445 = FILL_AREA_STYLE_COLOUR('',#201151); -#201446 = OVER_RIDING_STYLED_ITEM('overriding color',(#201447),#26387, - #201122); -#201447 = PRESENTATION_STYLE_ASSIGNMENT((#201448)); -#201448 = SURFACE_STYLE_USAGE(.BOTH.,#201449); -#201449 = SURFACE_SIDE_STYLE('',(#201450)); -#201450 = SURFACE_STYLE_FILL_AREA(#201451); -#201451 = FILL_AREA_STYLE('',(#201452)); -#201452 = FILL_AREA_STYLE_COLOUR('',#201028); -#201453 = OVER_RIDING_STYLED_ITEM('overriding color',(#201454),#26414, - #201122); -#201454 = PRESENTATION_STYLE_ASSIGNMENT((#201455)); -#201455 = SURFACE_STYLE_USAGE(.BOTH.,#201456); -#201456 = SURFACE_SIDE_STYLE('',(#201457)); -#201457 = SURFACE_STYLE_FILL_AREA(#201458); -#201458 = FILL_AREA_STYLE('',(#201459)); -#201459 = FILL_AREA_STYLE_COLOUR('',#201028); -#201460 = OVER_RIDING_STYLED_ITEM('overriding color',(#201461),#26421, - #201122); -#201461 = PRESENTATION_STYLE_ASSIGNMENT((#201462)); -#201462 = SURFACE_STYLE_USAGE(.BOTH.,#201463); -#201463 = SURFACE_SIDE_STYLE('',(#201464)); -#201464 = SURFACE_STYLE_FILL_AREA(#201465); -#201465 = FILL_AREA_STYLE('',(#201466)); -#201466 = FILL_AREA_STYLE_COLOUR('',#201028); -#201467 = OVER_RIDING_STYLED_ITEM('overriding color',(#201468),#26428, - #201122); -#201468 = PRESENTATION_STYLE_ASSIGNMENT((#201469)); -#201469 = SURFACE_STYLE_USAGE(.BOTH.,#201470); -#201470 = SURFACE_SIDE_STYLE('',(#201471)); -#201471 = SURFACE_STYLE_FILL_AREA(#201472); -#201472 = FILL_AREA_STYLE('',(#201473)); -#201473 = FILL_AREA_STYLE_COLOUR('',#201151); -#201474 = OVER_RIDING_STYLED_ITEM('overriding color',(#201475),#26499, - #201122); -#201475 = PRESENTATION_STYLE_ASSIGNMENT((#201476)); -#201476 = SURFACE_STYLE_USAGE(.BOTH.,#201477); -#201477 = SURFACE_SIDE_STYLE('',(#201478)); -#201478 = SURFACE_STYLE_FILL_AREA(#201479); -#201479 = FILL_AREA_STYLE('',(#201480)); -#201480 = FILL_AREA_STYLE_COLOUR('',#201151); -#201481 = OVER_RIDING_STYLED_ITEM('overriding color',(#201482),#26548, - #201122); -#201482 = PRESENTATION_STYLE_ASSIGNMENT((#201483)); -#201483 = SURFACE_STYLE_USAGE(.BOTH.,#201484); -#201484 = SURFACE_SIDE_STYLE('',(#201485)); -#201485 = SURFACE_STYLE_FILL_AREA(#201486); -#201486 = FILL_AREA_STYLE('',(#201487)); -#201487 = FILL_AREA_STYLE_COLOUR('',#201151); -#201488 = OVER_RIDING_STYLED_ITEM('overriding color',(#201489),#26575, - #201122); -#201489 = PRESENTATION_STYLE_ASSIGNMENT((#201490)); -#201490 = SURFACE_STYLE_USAGE(.BOTH.,#201491); -#201491 = SURFACE_SIDE_STYLE('',(#201492)); -#201492 = SURFACE_STYLE_FILL_AREA(#201493); -#201493 = FILL_AREA_STYLE('',(#201494)); -#201494 = FILL_AREA_STYLE_COLOUR('',#201151); -#201495 = OVER_RIDING_STYLED_ITEM('overriding color',(#201496),#26962, - #201122); -#201496 = PRESENTATION_STYLE_ASSIGNMENT((#201497)); -#201497 = SURFACE_STYLE_USAGE(.BOTH.,#201498); -#201498 = SURFACE_SIDE_STYLE('',(#201499)); -#201499 = SURFACE_STYLE_FILL_AREA(#201500); -#201500 = FILL_AREA_STYLE('',(#201501)); -#201501 = FILL_AREA_STYLE_COLOUR('',#201151); -#201502 = OVER_RIDING_STYLED_ITEM('overriding color',(#201503),#27009, - #201122); -#201503 = PRESENTATION_STYLE_ASSIGNMENT((#201504)); -#201504 = SURFACE_STYLE_USAGE(.BOTH.,#201505); -#201505 = SURFACE_SIDE_STYLE('',(#201506)); -#201506 = SURFACE_STYLE_FILL_AREA(#201507); -#201507 = FILL_AREA_STYLE('',(#201508)); -#201508 = FILL_AREA_STYLE_COLOUR('',#201151); -#201509 = OVER_RIDING_STYLED_ITEM('overriding color',(#201510),#27036, - #201122); -#201510 = PRESENTATION_STYLE_ASSIGNMENT((#201511)); -#201511 = SURFACE_STYLE_USAGE(.BOTH.,#201512); -#201512 = SURFACE_SIDE_STYLE('',(#201513)); -#201513 = SURFACE_STYLE_FILL_AREA(#201514); -#201514 = FILL_AREA_STYLE('',(#201515)); -#201515 = FILL_AREA_STYLE_COLOUR('',#201151); -#201516 = OVER_RIDING_STYLED_ITEM('overriding color',(#201517),#27043, - #201122); -#201517 = PRESENTATION_STYLE_ASSIGNMENT((#201518)); -#201518 = SURFACE_STYLE_USAGE(.BOTH.,#201519); -#201519 = SURFACE_SIDE_STYLE('',(#201520)); -#201520 = SURFACE_STYLE_FILL_AREA(#201521); -#201521 = FILL_AREA_STYLE('',(#201522)); -#201522 = FILL_AREA_STYLE_COLOUR('',#201151); -#201523 = OVER_RIDING_STYLED_ITEM('overriding color',(#201524),#27050, - #201122); -#201524 = PRESENTATION_STYLE_ASSIGNMENT((#201525)); -#201525 = SURFACE_STYLE_USAGE(.BOTH.,#201526); -#201526 = SURFACE_SIDE_STYLE('',(#201527)); -#201527 = SURFACE_STYLE_FILL_AREA(#201528); -#201528 = FILL_AREA_STYLE('',(#201529)); -#201529 = FILL_AREA_STYLE_COLOUR('',#201028); -#201530 = OVER_RIDING_STYLED_ITEM('overriding color',(#201531),#27155, - #201122); -#201531 = PRESENTATION_STYLE_ASSIGNMENT((#201532)); -#201532 = SURFACE_STYLE_USAGE(.BOTH.,#201533); -#201533 = SURFACE_SIDE_STYLE('',(#201534)); -#201534 = SURFACE_STYLE_FILL_AREA(#201535); -#201535 = FILL_AREA_STYLE('',(#201536)); -#201536 = FILL_AREA_STYLE_COLOUR('',#201028); -#201537 = OVER_RIDING_STYLED_ITEM('overriding color',(#201538),#27260, - #201122); -#201538 = PRESENTATION_STYLE_ASSIGNMENT((#201539)); -#201539 = SURFACE_STYLE_USAGE(.BOTH.,#201540); -#201540 = SURFACE_SIDE_STYLE('',(#201541)); -#201541 = SURFACE_STYLE_FILL_AREA(#201542); -#201542 = FILL_AREA_STYLE('',(#201543)); -#201543 = FILL_AREA_STYLE_COLOUR('',#201151); -#201544 = OVER_RIDING_STYLED_ITEM('overriding color',(#201545),#27287, - #201122); -#201545 = PRESENTATION_STYLE_ASSIGNMENT((#201546)); -#201546 = SURFACE_STYLE_USAGE(.BOTH.,#201547); -#201547 = SURFACE_SIDE_STYLE('',(#201548)); -#201548 = SURFACE_STYLE_FILL_AREA(#201549); -#201549 = FILL_AREA_STYLE('',(#201550)); -#201550 = FILL_AREA_STYLE_COLOUR('',#201028); -#201551 = OVER_RIDING_STYLED_ITEM('overriding color',(#201552),#27392, - #201122); -#201552 = PRESENTATION_STYLE_ASSIGNMENT((#201553)); -#201553 = SURFACE_STYLE_USAGE(.BOTH.,#201554); -#201554 = SURFACE_SIDE_STYLE('',(#201555)); -#201555 = SURFACE_STYLE_FILL_AREA(#201556); -#201556 = FILL_AREA_STYLE('',(#201557)); -#201557 = FILL_AREA_STYLE_COLOUR('',#201028); -#201558 = OVER_RIDING_STYLED_ITEM('overriding color',(#201559),#27487, - #201122); -#201559 = PRESENTATION_STYLE_ASSIGNMENT((#201560)); -#201560 = SURFACE_STYLE_USAGE(.BOTH.,#201561); -#201561 = SURFACE_SIDE_STYLE('',(#201562)); -#201562 = SURFACE_STYLE_FILL_AREA(#201563); -#201563 = FILL_AREA_STYLE('',(#201564)); -#201564 = FILL_AREA_STYLE_COLOUR('',#201028); -#201565 = OVER_RIDING_STYLED_ITEM('overriding color',(#201566),#27592, - #201122); -#201566 = PRESENTATION_STYLE_ASSIGNMENT((#201567)); -#201567 = SURFACE_STYLE_USAGE(.BOTH.,#201568); -#201568 = SURFACE_SIDE_STYLE('',(#201569)); -#201569 = SURFACE_STYLE_FILL_AREA(#201570); -#201570 = FILL_AREA_STYLE('',(#201571)); -#201571 = FILL_AREA_STYLE_COLOUR('',#201028); -#201572 = OVER_RIDING_STYLED_ITEM('overriding color',(#201573),#27619, - #201122); -#201573 = PRESENTATION_STYLE_ASSIGNMENT((#201574)); -#201574 = SURFACE_STYLE_USAGE(.BOTH.,#201575); -#201575 = SURFACE_SIDE_STYLE('',(#201576)); -#201576 = SURFACE_STYLE_FILL_AREA(#201577); -#201577 = FILL_AREA_STYLE('',(#201578)); -#201578 = FILL_AREA_STYLE_COLOUR('',#201028); -#201579 = OVER_RIDING_STYLED_ITEM('overriding color',(#201580),#27714, - #201122); -#201580 = PRESENTATION_STYLE_ASSIGNMENT((#201581)); -#201581 = SURFACE_STYLE_USAGE(.BOTH.,#201582); -#201582 = SURFACE_SIDE_STYLE('',(#201583)); -#201583 = SURFACE_STYLE_FILL_AREA(#201584); -#201584 = FILL_AREA_STYLE('',(#201585)); -#201585 = FILL_AREA_STYLE_COLOUR('',#201028); -#201586 = OVER_RIDING_STYLED_ITEM('overriding color',(#201587),#27741, - #201122); -#201587 = PRESENTATION_STYLE_ASSIGNMENT((#201588)); -#201588 = SURFACE_STYLE_USAGE(.BOTH.,#201589); -#201589 = SURFACE_SIDE_STYLE('',(#201590)); -#201590 = SURFACE_STYLE_FILL_AREA(#201591); -#201591 = FILL_AREA_STYLE('',(#201592)); -#201592 = FILL_AREA_STYLE_COLOUR('',#201028); -#201593 = OVER_RIDING_STYLED_ITEM('overriding color',(#201594),#27836, - #201122); -#201594 = PRESENTATION_STYLE_ASSIGNMENT((#201595)); -#201595 = SURFACE_STYLE_USAGE(.BOTH.,#201596); -#201596 = SURFACE_SIDE_STYLE('',(#201597)); -#201597 = SURFACE_STYLE_FILL_AREA(#201598); -#201598 = FILL_AREA_STYLE('',(#201599)); -#201599 = FILL_AREA_STYLE_COLOUR('',#201028); -#201600 = OVER_RIDING_STYLED_ITEM('overriding color',(#201601),#27863, - #201122); -#201601 = PRESENTATION_STYLE_ASSIGNMENT((#201602)); -#201602 = SURFACE_STYLE_USAGE(.BOTH.,#201603); -#201603 = SURFACE_SIDE_STYLE('',(#201604)); -#201604 = SURFACE_STYLE_FILL_AREA(#201605); -#201605 = FILL_AREA_STYLE('',(#201606)); -#201606 = FILL_AREA_STYLE_COLOUR('',#201028); -#201607 = OVER_RIDING_STYLED_ITEM('overriding color',(#201608),#27958, - #201122); -#201608 = PRESENTATION_STYLE_ASSIGNMENT((#201609)); -#201609 = SURFACE_STYLE_USAGE(.BOTH.,#201610); -#201610 = SURFACE_SIDE_STYLE('',(#201611)); -#201611 = SURFACE_STYLE_FILL_AREA(#201612); -#201612 = FILL_AREA_STYLE('',(#201613)); -#201613 = FILL_AREA_STYLE_COLOUR('',#201028); -#201614 = OVER_RIDING_STYLED_ITEM('overriding color',(#201615),#27985, - #201122); -#201615 = PRESENTATION_STYLE_ASSIGNMENT((#201616)); -#201616 = SURFACE_STYLE_USAGE(.BOTH.,#201617); -#201617 = SURFACE_SIDE_STYLE('',(#201618)); -#201618 = SURFACE_STYLE_FILL_AREA(#201619); -#201619 = FILL_AREA_STYLE('',(#201620)); -#201620 = FILL_AREA_STYLE_COLOUR('',#201151); -#201621 = OVER_RIDING_STYLED_ITEM('overriding color',(#201622),#28012, - #201122); -#201622 = PRESENTATION_STYLE_ASSIGNMENT((#201623)); -#201623 = SURFACE_STYLE_USAGE(.BOTH.,#201624); -#201624 = SURFACE_SIDE_STYLE('',(#201625)); -#201625 = SURFACE_STYLE_FILL_AREA(#201626); -#201626 = FILL_AREA_STYLE('',(#201627)); -#201627 = FILL_AREA_STYLE_COLOUR('',#201151); -#201628 = OVER_RIDING_STYLED_ITEM('overriding color',(#201629),#28019, - #201122); -#201629 = PRESENTATION_STYLE_ASSIGNMENT((#201630)); -#201630 = SURFACE_STYLE_USAGE(.BOTH.,#201631); -#201631 = SURFACE_SIDE_STYLE('',(#201632)); -#201632 = SURFACE_STYLE_FILL_AREA(#201633); -#201633 = FILL_AREA_STYLE('',(#201634)); -#201634 = FILL_AREA_STYLE_COLOUR('',#201151); -#201635 = OVER_RIDING_STYLED_ITEM('overriding color',(#201636),#28114, - #201122); -#201636 = PRESENTATION_STYLE_ASSIGNMENT((#201637)); -#201637 = SURFACE_STYLE_USAGE(.BOTH.,#201638); -#201638 = SURFACE_SIDE_STYLE('',(#201639)); -#201639 = SURFACE_STYLE_FILL_AREA(#201640); -#201640 = FILL_AREA_STYLE('',(#201641)); -#201641 = FILL_AREA_STYLE_COLOUR('',#201151); -#201642 = OVER_RIDING_STYLED_ITEM('overriding color',(#201643),#28123, - #201122); -#201643 = PRESENTATION_STYLE_ASSIGNMENT((#201644)); -#201644 = SURFACE_STYLE_USAGE(.BOTH.,#201645); -#201645 = SURFACE_SIDE_STYLE('',(#201646)); -#201646 = SURFACE_STYLE_FILL_AREA(#201647); -#201647 = FILL_AREA_STYLE('',(#201648)); -#201648 = FILL_AREA_STYLE_COLOUR('',#201151); -#201649 = OVER_RIDING_STYLED_ITEM('overriding color',(#201650),#28150, - #201122); -#201650 = PRESENTATION_STYLE_ASSIGNMENT((#201651)); -#201651 = SURFACE_STYLE_USAGE(.BOTH.,#201652); -#201652 = SURFACE_SIDE_STYLE('',(#201653)); -#201653 = SURFACE_STYLE_FILL_AREA(#201654); -#201654 = FILL_AREA_STYLE('',(#201655)); -#201655 = FILL_AREA_STYLE_COLOUR('',#201151); -#201656 = OVER_RIDING_STYLED_ITEM('overriding color',(#201657),#28177, - #201122); -#201657 = PRESENTATION_STYLE_ASSIGNMENT((#201658)); -#201658 = SURFACE_STYLE_USAGE(.BOTH.,#201659); -#201659 = SURFACE_SIDE_STYLE('',(#201660)); -#201660 = SURFACE_STYLE_FILL_AREA(#201661); -#201661 = FILL_AREA_STYLE('',(#201662)); -#201662 = FILL_AREA_STYLE_COLOUR('',#201151); -#201663 = OVER_RIDING_STYLED_ITEM('overriding color',(#201664),#28204, - #201122); -#201664 = PRESENTATION_STYLE_ASSIGNMENT((#201665)); -#201665 = SURFACE_STYLE_USAGE(.BOTH.,#201666); -#201666 = SURFACE_SIDE_STYLE('',(#201667)); -#201667 = SURFACE_STYLE_FILL_AREA(#201668); -#201668 = FILL_AREA_STYLE('',(#201669)); -#201669 = FILL_AREA_STYLE_COLOUR('',#201151); -#201670 = OVER_RIDING_STYLED_ITEM('overriding color',(#201671),#28211, - #201122); -#201671 = PRESENTATION_STYLE_ASSIGNMENT((#201672)); -#201672 = SURFACE_STYLE_USAGE(.BOTH.,#201673); -#201673 = SURFACE_SIDE_STYLE('',(#201674)); -#201674 = SURFACE_STYLE_FILL_AREA(#201675); -#201675 = FILL_AREA_STYLE('',(#201676)); -#201676 = FILL_AREA_STYLE_COLOUR('',#201028); -#201677 = OVER_RIDING_STYLED_ITEM('overriding color',(#201678),#28238, - #201122); -#201678 = PRESENTATION_STYLE_ASSIGNMENT((#201679)); -#201679 = SURFACE_STYLE_USAGE(.BOTH.,#201680); -#201680 = SURFACE_SIDE_STYLE('',(#201681)); -#201681 = SURFACE_STYLE_FILL_AREA(#201682); -#201682 = FILL_AREA_STYLE('',(#201683)); -#201683 = FILL_AREA_STYLE_COLOUR('',#201028); -#201684 = OVER_RIDING_STYLED_ITEM('overriding color',(#201685),#28265, - #201122); -#201685 = PRESENTATION_STYLE_ASSIGNMENT((#201686)); -#201686 = SURFACE_STYLE_USAGE(.BOTH.,#201687); -#201687 = SURFACE_SIDE_STYLE('',(#201688)); -#201688 = SURFACE_STYLE_FILL_AREA(#201689); -#201689 = FILL_AREA_STYLE('',(#201690)); -#201690 = FILL_AREA_STYLE_COLOUR('',#201028); -#201691 = OVER_RIDING_STYLED_ITEM('overriding color',(#201692),#28292, - #201122); -#201692 = PRESENTATION_STYLE_ASSIGNMENT((#201693)); -#201693 = SURFACE_STYLE_USAGE(.BOTH.,#201694); -#201694 = SURFACE_SIDE_STYLE('',(#201695)); -#201695 = SURFACE_STYLE_FILL_AREA(#201696); -#201696 = FILL_AREA_STYLE('',(#201697)); -#201697 = FILL_AREA_STYLE_COLOUR('',#201028); -#201698 = OVER_RIDING_STYLED_ITEM('overriding color',(#201699),#28319, - #201122); -#201699 = PRESENTATION_STYLE_ASSIGNMENT((#201700)); -#201700 = SURFACE_STYLE_USAGE(.BOTH.,#201701); -#201701 = SURFACE_SIDE_STYLE('',(#201702)); -#201702 = SURFACE_STYLE_FILL_AREA(#201703); -#201703 = FILL_AREA_STYLE('',(#201704)); -#201704 = FILL_AREA_STYLE_COLOUR('',#201028); -#201705 = OVER_RIDING_STYLED_ITEM('overriding color',(#201706),#28346, - #201122); -#201706 = PRESENTATION_STYLE_ASSIGNMENT((#201707)); -#201707 = SURFACE_STYLE_USAGE(.BOTH.,#201708); -#201708 = SURFACE_SIDE_STYLE('',(#201709)); -#201709 = SURFACE_STYLE_FILL_AREA(#201710); -#201710 = FILL_AREA_STYLE('',(#201711)); -#201711 = FILL_AREA_STYLE_COLOUR('',#201028); -#201712 = OVER_RIDING_STYLED_ITEM('overriding color',(#201713),#28353, - #201122); -#201713 = PRESENTATION_STYLE_ASSIGNMENT((#201714)); -#201714 = SURFACE_STYLE_USAGE(.BOTH.,#201715); -#201715 = SURFACE_SIDE_STYLE('',(#201716)); -#201716 = SURFACE_STYLE_FILL_AREA(#201717); -#201717 = FILL_AREA_STYLE('',(#201718)); -#201718 = FILL_AREA_STYLE_COLOUR('',#201028); -#201719 = OVER_RIDING_STYLED_ITEM('overriding color',(#201720),#28380, - #201122); -#201720 = PRESENTATION_STYLE_ASSIGNMENT((#201721)); -#201721 = SURFACE_STYLE_USAGE(.BOTH.,#201722); -#201722 = SURFACE_SIDE_STYLE('',(#201723)); -#201723 = SURFACE_STYLE_FILL_AREA(#201724); -#201724 = FILL_AREA_STYLE('',(#201725)); -#201725 = FILL_AREA_STYLE_COLOUR('',#201028); -#201726 = OVER_RIDING_STYLED_ITEM('overriding color',(#201727),#28387, - #201122); -#201727 = PRESENTATION_STYLE_ASSIGNMENT((#201728)); -#201728 = SURFACE_STYLE_USAGE(.BOTH.,#201729); -#201729 = SURFACE_SIDE_STYLE('',(#201730)); -#201730 = SURFACE_STYLE_FILL_AREA(#201731); -#201731 = FILL_AREA_STYLE('',(#201732)); -#201732 = FILL_AREA_STYLE_COLOUR('',#201028); -#201733 = OVER_RIDING_STYLED_ITEM('overriding color',(#201734),#28414, - #201122); -#201734 = PRESENTATION_STYLE_ASSIGNMENT((#201735)); -#201735 = SURFACE_STYLE_USAGE(.BOTH.,#201736); -#201736 = SURFACE_SIDE_STYLE('',(#201737)); -#201737 = SURFACE_STYLE_FILL_AREA(#201738); -#201738 = FILL_AREA_STYLE('',(#201739)); -#201739 = FILL_AREA_STYLE_COLOUR('',#201028); -#201740 = OVER_RIDING_STYLED_ITEM('overriding color',(#201741),#28421, - #201122); -#201741 = PRESENTATION_STYLE_ASSIGNMENT((#201742)); -#201742 = SURFACE_STYLE_USAGE(.BOTH.,#201743); -#201743 = SURFACE_SIDE_STYLE('',(#201744)); -#201744 = SURFACE_STYLE_FILL_AREA(#201745); -#201745 = FILL_AREA_STYLE('',(#201746)); -#201746 = FILL_AREA_STYLE_COLOUR('',#201028); -#201747 = OVER_RIDING_STYLED_ITEM('overriding color',(#201748),#28448, - #201122); -#201748 = PRESENTATION_STYLE_ASSIGNMENT((#201749)); -#201749 = SURFACE_STYLE_USAGE(.BOTH.,#201750); -#201750 = SURFACE_SIDE_STYLE('',(#201751)); -#201751 = SURFACE_STYLE_FILL_AREA(#201752); -#201752 = FILL_AREA_STYLE('',(#201753)); -#201753 = FILL_AREA_STYLE_COLOUR('',#201028); -#201754 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201755),#11445); -#201755 = STYLED_ITEM('color',(#201756),#11115); -#201756 = PRESENTATION_STYLE_ASSIGNMENT((#201757,#201763)); -#201757 = SURFACE_STYLE_USAGE(.BOTH.,#201758); -#201758 = SURFACE_SIDE_STYLE('',(#201759)); -#201759 = SURFACE_STYLE_FILL_AREA(#201760); -#201760 = FILL_AREA_STYLE('',(#201761)); -#201761 = FILL_AREA_STYLE_COLOUR('',#201762); -#201762 = COLOUR_RGB('',0.96862745285,0.800000011921,0.435294121504); -#201763 = CURVE_STYLE('',#201764,POSITIVE_LENGTH_MEASURE(0.1),#201762); -#201764 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#201765 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #201766,#201774,#201782,#201789,#201796,#201803,#201810,#201817, - #201824,#201831,#201838,#201845,#201852,#201859,#201866,#201873, - #201880,#201887,#201894,#201901,#201908,#201915,#201922,#201929, - #201936,#201943,#201950,#201957,#201964,#201971,#201978,#201985, - #201992,#201999,#202006,#202013,#202020,#202027,#202034,#202041, - #202048,#202055,#202062,#202069,#202076,#202083,#202090,#202097, - #202104,#202111,#202118,#202125,#202132,#202139,#202146,#202153, - #202160,#202167,#202174,#202181,#202188,#202195,#202202,#202209, - #202216,#202223,#202230,#202237,#202244,#202251,#202258,#202265, - #202272,#202279,#202286,#202293,#202300,#202307,#202314,#202321, - #202328,#202335,#202342,#202349,#202356,#202363,#202370,#202377, - #202384,#202391,#202398,#202405,#202412,#202419,#202426,#202433, - #202440,#202447,#202454,#202461,#202468,#202475,#202482,#202489, - #202496,#202503,#202510,#202517,#202524,#202531,#202538,#202545, - #202552,#202559,#202566,#202573,#202580,#202587,#202594,#202601, - #202608,#202615,#202622,#202629,#202636,#202643,#202650,#202657, - #202664,#202671,#202678,#202685,#202692,#202699,#202706,#202713, - #202720,#202727,#202734,#202741,#202748,#202755,#202762,#202769, - #202776,#202783,#202790,#202797,#202804,#202811),#182344); -#201766 = STYLED_ITEM('color',(#201767),#168637); -#201767 = PRESENTATION_STYLE_ASSIGNMENT((#201768)); -#201768 = SURFACE_STYLE_USAGE(.BOTH.,#201769); -#201769 = SURFACE_SIDE_STYLE('',(#201770)); -#201770 = SURFACE_STYLE_FILL_AREA(#201771); -#201771 = FILL_AREA_STYLE('',(#201772)); -#201772 = FILL_AREA_STYLE_COLOUR('',#201773); -#201773 = COLOUR_RGB('',0.796078443527,0.823529422283,0.937254905701); -#201774 = OVER_RIDING_STYLED_ITEM('overriding color',(#201775),#168639, - #201766); -#201775 = PRESENTATION_STYLE_ASSIGNMENT((#201776)); -#201776 = SURFACE_STYLE_USAGE(.BOTH.,#201777); -#201777 = SURFACE_SIDE_STYLE('',(#201778)); -#201778 = SURFACE_STYLE_FILL_AREA(#201779); -#201779 = FILL_AREA_STYLE('',(#201780)); -#201780 = FILL_AREA_STYLE_COLOUR('',#201781); -#201781 = COLOUR_RGB('',0.117647059262,0.117647059262,0.117647059262); -#201782 = OVER_RIDING_STYLED_ITEM('overriding color',(#201783),#168942, - #201766); -#201783 = PRESENTATION_STYLE_ASSIGNMENT((#201784)); -#201784 = SURFACE_STYLE_USAGE(.BOTH.,#201785); -#201785 = SURFACE_SIDE_STYLE('',(#201786)); -#201786 = SURFACE_STYLE_FILL_AREA(#201787); -#201787 = FILL_AREA_STYLE('',(#201788)); -#201788 = FILL_AREA_STYLE_COLOUR('',#201781); -#201789 = OVER_RIDING_STYLED_ITEM('overriding color',(#201790),#169217, - #201766); -#201790 = PRESENTATION_STYLE_ASSIGNMENT((#201791)); -#201791 = SURFACE_STYLE_USAGE(.BOTH.,#201792); -#201792 = SURFACE_SIDE_STYLE('',(#201793)); -#201793 = SURFACE_STYLE_FILL_AREA(#201794); -#201794 = FILL_AREA_STYLE('',(#201795)); -#201795 = FILL_AREA_STYLE_COLOUR('',#201781); -#201796 = OVER_RIDING_STYLED_ITEM('overriding color',(#201797),#169492, - #201766); -#201797 = PRESENTATION_STYLE_ASSIGNMENT((#201798)); -#201798 = SURFACE_STYLE_USAGE(.BOTH.,#201799); -#201799 = SURFACE_SIDE_STYLE('',(#201800)); -#201800 = SURFACE_STYLE_FILL_AREA(#201801); -#201801 = FILL_AREA_STYLE('',(#201802)); -#201802 = FILL_AREA_STYLE_COLOUR('',#201781); -#201803 = OVER_RIDING_STYLED_ITEM('overriding color',(#201804),#169767, - #201766); -#201804 = PRESENTATION_STYLE_ASSIGNMENT((#201805)); -#201805 = SURFACE_STYLE_USAGE(.BOTH.,#201806); -#201806 = SURFACE_SIDE_STYLE('',(#201807)); -#201807 = SURFACE_STYLE_FILL_AREA(#201808); -#201808 = FILL_AREA_STYLE('',(#201809)); -#201809 = FILL_AREA_STYLE_COLOUR('',#201781); -#201810 = OVER_RIDING_STYLED_ITEM('overriding color',(#201811),#170047, - #201766); -#201811 = PRESENTATION_STYLE_ASSIGNMENT((#201812)); -#201812 = SURFACE_STYLE_USAGE(.BOTH.,#201813); -#201813 = SURFACE_SIDE_STYLE('',(#201814)); -#201814 = SURFACE_STYLE_FILL_AREA(#201815); -#201815 = FILL_AREA_STYLE('',(#201816)); -#201816 = FILL_AREA_STYLE_COLOUR('',#201781); -#201817 = OVER_RIDING_STYLED_ITEM('overriding color',(#201818),#170322, - #201766); -#201818 = PRESENTATION_STYLE_ASSIGNMENT((#201819)); -#201819 = SURFACE_STYLE_USAGE(.BOTH.,#201820); -#201820 = SURFACE_SIDE_STYLE('',(#201821)); -#201821 = SURFACE_STYLE_FILL_AREA(#201822); -#201822 = FILL_AREA_STYLE('',(#201823)); -#201823 = FILL_AREA_STYLE_COLOUR('',#201781); -#201824 = OVER_RIDING_STYLED_ITEM('overriding color',(#201825),#170597, - #201766); -#201825 = PRESENTATION_STYLE_ASSIGNMENT((#201826)); -#201826 = SURFACE_STYLE_USAGE(.BOTH.,#201827); -#201827 = SURFACE_SIDE_STYLE('',(#201828)); -#201828 = SURFACE_STYLE_FILL_AREA(#201829); -#201829 = FILL_AREA_STYLE('',(#201830)); -#201830 = FILL_AREA_STYLE_COLOUR('',#201781); -#201831 = OVER_RIDING_STYLED_ITEM('overriding color',(#201832),#170872, - #201766); -#201832 = PRESENTATION_STYLE_ASSIGNMENT((#201833)); -#201833 = SURFACE_STYLE_USAGE(.BOTH.,#201834); -#201834 = SURFACE_SIDE_STYLE('',(#201835)); -#201835 = SURFACE_STYLE_FILL_AREA(#201836); -#201836 = FILL_AREA_STYLE('',(#201837)); -#201837 = FILL_AREA_STYLE_COLOUR('',#201781); -#201838 = OVER_RIDING_STYLED_ITEM('overriding color',(#201839),#171024, - #201766); -#201839 = PRESENTATION_STYLE_ASSIGNMENT((#201840)); -#201840 = SURFACE_STYLE_USAGE(.BOTH.,#201841); -#201841 = SURFACE_SIDE_STYLE('',(#201842)); -#201842 = SURFACE_STYLE_FILL_AREA(#201843); -#201843 = FILL_AREA_STYLE('',(#201844)); -#201844 = FILL_AREA_STYLE_COLOUR('',#201781); -#201845 = OVER_RIDING_STYLED_ITEM('overriding color',(#201846),#171598, - #201766); -#201846 = PRESENTATION_STYLE_ASSIGNMENT((#201847)); -#201847 = SURFACE_STYLE_USAGE(.BOTH.,#201848); -#201848 = SURFACE_SIDE_STYLE('',(#201849)); -#201849 = SURFACE_STYLE_FILL_AREA(#201850); -#201850 = FILL_AREA_STYLE('',(#201851)); -#201851 = FILL_AREA_STYLE_COLOUR('',#201781); -#201852 = OVER_RIDING_STYLED_ITEM('overriding color',(#201853),#171767, - #201766); -#201853 = PRESENTATION_STYLE_ASSIGNMENT((#201854)); -#201854 = SURFACE_STYLE_USAGE(.BOTH.,#201855); -#201855 = SURFACE_SIDE_STYLE('',(#201856)); -#201856 = SURFACE_STYLE_FILL_AREA(#201857); -#201857 = FILL_AREA_STYLE('',(#201858)); -#201858 = FILL_AREA_STYLE_COLOUR('',#201781); -#201859 = OVER_RIDING_STYLED_ITEM('overriding color',(#201860),#172117, - #201766); -#201860 = PRESENTATION_STYLE_ASSIGNMENT((#201861)); -#201861 = SURFACE_STYLE_USAGE(.BOTH.,#201862); -#201862 = SURFACE_SIDE_STYLE('',(#201863)); -#201863 = SURFACE_STYLE_FILL_AREA(#201864); -#201864 = FILL_AREA_STYLE('',(#201865)); -#201865 = FILL_AREA_STYLE_COLOUR('',#201781); -#201866 = OVER_RIDING_STYLED_ITEM('overriding color',(#201867),#172286, - #201766); -#201867 = PRESENTATION_STYLE_ASSIGNMENT((#201868)); -#201868 = SURFACE_STYLE_USAGE(.BOTH.,#201869); -#201869 = SURFACE_SIDE_STYLE('',(#201870)); -#201870 = SURFACE_STYLE_FILL_AREA(#201871); -#201871 = FILL_AREA_STYLE('',(#201872)); -#201872 = FILL_AREA_STYLE_COLOUR('',#201781); -#201873 = OVER_RIDING_STYLED_ITEM('overriding color',(#201874),#172506, - #201766); -#201874 = PRESENTATION_STYLE_ASSIGNMENT((#201875)); -#201875 = SURFACE_STYLE_USAGE(.BOTH.,#201876); -#201876 = SURFACE_SIDE_STYLE('',(#201877)); -#201877 = SURFACE_STYLE_FILL_AREA(#201878); -#201878 = FILL_AREA_STYLE('',(#201879)); -#201879 = FILL_AREA_STYLE_COLOUR('',#201781); -#201880 = OVER_RIDING_STYLED_ITEM('overriding color',(#201881),#172827, - #201766); -#201881 = PRESENTATION_STYLE_ASSIGNMENT((#201882)); -#201882 = SURFACE_STYLE_USAGE(.BOTH.,#201883); -#201883 = SURFACE_SIDE_STYLE('',(#201884)); -#201884 = SURFACE_STYLE_FILL_AREA(#201885); -#201885 = FILL_AREA_STYLE('',(#201886)); -#201886 = FILL_AREA_STYLE_COLOUR('',#201781); -#201887 = OVER_RIDING_STYLED_ITEM('overriding color',(#201888),#172962, - #201766); -#201888 = PRESENTATION_STYLE_ASSIGNMENT((#201889)); -#201889 = SURFACE_STYLE_USAGE(.BOTH.,#201890); -#201890 = SURFACE_SIDE_STYLE('',(#201891)); -#201891 = SURFACE_STYLE_FILL_AREA(#201892); -#201892 = FILL_AREA_STYLE('',(#201893)); -#201893 = FILL_AREA_STYLE_COLOUR('',#201781); -#201894 = OVER_RIDING_STYLED_ITEM('overriding color',(#201895),#173097, - #201766); -#201895 = PRESENTATION_STYLE_ASSIGNMENT((#201896)); -#201896 = SURFACE_STYLE_USAGE(.BOTH.,#201897); -#201897 = SURFACE_SIDE_STYLE('',(#201898)); -#201898 = SURFACE_STYLE_FILL_AREA(#201899); -#201899 = FILL_AREA_STYLE('',(#201900)); -#201900 = FILL_AREA_STYLE_COLOUR('',#201781); -#201901 = OVER_RIDING_STYLED_ITEM('overriding color',(#201902),#173541, - #201766); -#201902 = PRESENTATION_STYLE_ASSIGNMENT((#201903)); -#201903 = SURFACE_STYLE_USAGE(.BOTH.,#201904); -#201904 = SURFACE_SIDE_STYLE('',(#201905)); -#201905 = SURFACE_STYLE_FILL_AREA(#201906); -#201906 = FILL_AREA_STYLE('',(#201907)); -#201907 = FILL_AREA_STYLE_COLOUR('',#201781); -#201908 = OVER_RIDING_STYLED_ITEM('overriding color',(#201909),#173909, - #201766); -#201909 = PRESENTATION_STYLE_ASSIGNMENT((#201910)); -#201910 = SURFACE_STYLE_USAGE(.BOTH.,#201911); -#201911 = SURFACE_SIDE_STYLE('',(#201912)); -#201912 = SURFACE_STYLE_FILL_AREA(#201913); -#201913 = FILL_AREA_STYLE('',(#201914)); -#201914 = FILL_AREA_STYLE_COLOUR('',#201028); -#201915 = OVER_RIDING_STYLED_ITEM('overriding color',(#201916),#173984, - #201766); -#201916 = PRESENTATION_STYLE_ASSIGNMENT((#201917)); -#201917 = SURFACE_STYLE_USAGE(.BOTH.,#201918); -#201918 = SURFACE_SIDE_STYLE('',(#201919)); -#201919 = SURFACE_STYLE_FILL_AREA(#201920); -#201920 = FILL_AREA_STYLE('',(#201921)); -#201921 = FILL_AREA_STYLE_COLOUR('',#201028); -#201922 = OVER_RIDING_STYLED_ITEM('overriding color',(#201923),#174059, - #201766); -#201923 = PRESENTATION_STYLE_ASSIGNMENT((#201924)); -#201924 = SURFACE_STYLE_USAGE(.BOTH.,#201925); -#201925 = SURFACE_SIDE_STYLE('',(#201926)); -#201926 = SURFACE_STYLE_FILL_AREA(#201927); -#201927 = FILL_AREA_STYLE('',(#201928)); -#201928 = FILL_AREA_STYLE_COLOUR('',#201028); -#201929 = OVER_RIDING_STYLED_ITEM('overriding color',(#201930),#174313, - #201766); -#201930 = PRESENTATION_STYLE_ASSIGNMENT((#201931)); -#201931 = SURFACE_STYLE_USAGE(.BOTH.,#201932); -#201932 = SURFACE_SIDE_STYLE('',(#201933)); -#201933 = SURFACE_STYLE_FILL_AREA(#201934); -#201934 = FILL_AREA_STYLE('',(#201935)); -#201935 = FILL_AREA_STYLE_COLOUR('',#201028); -#201936 = OVER_RIDING_STYLED_ITEM('overriding color',(#201937),#174532, - #201766); -#201937 = PRESENTATION_STYLE_ASSIGNMENT((#201938)); -#201938 = SURFACE_STYLE_USAGE(.BOTH.,#201939); -#201939 = SURFACE_SIDE_STYLE('',(#201940)); -#201940 = SURFACE_STYLE_FILL_AREA(#201941); -#201941 = FILL_AREA_STYLE('',(#201942)); -#201942 = FILL_AREA_STYLE_COLOUR('',#201028); -#201943 = OVER_RIDING_STYLED_ITEM('overriding color',(#201944),#174558, - #201766); -#201944 = PRESENTATION_STYLE_ASSIGNMENT((#201945)); -#201945 = SURFACE_STYLE_USAGE(.BOTH.,#201946); -#201946 = SURFACE_SIDE_STYLE('',(#201947)); -#201947 = SURFACE_STYLE_FILL_AREA(#201948); -#201948 = FILL_AREA_STYLE('',(#201949)); -#201949 = FILL_AREA_STYLE_COLOUR('',#201028); -#201950 = OVER_RIDING_STYLED_ITEM('overriding color',(#201951),#174584, - #201766); -#201951 = PRESENTATION_STYLE_ASSIGNMENT((#201952)); -#201952 = SURFACE_STYLE_USAGE(.BOTH.,#201953); -#201953 = SURFACE_SIDE_STYLE('',(#201954)); -#201954 = SURFACE_STYLE_FILL_AREA(#201955); -#201955 = FILL_AREA_STYLE('',(#201956)); -#201956 = FILL_AREA_STYLE_COLOUR('',#201028); -#201957 = OVER_RIDING_STYLED_ITEM('overriding color',(#201958),#174633, - #201766); -#201958 = PRESENTATION_STYLE_ASSIGNMENT((#201959)); -#201959 = SURFACE_STYLE_USAGE(.BOTH.,#201960); -#201960 = SURFACE_SIDE_STYLE('',(#201961)); -#201961 = SURFACE_STYLE_FILL_AREA(#201962); -#201962 = FILL_AREA_STYLE('',(#201963)); -#201963 = FILL_AREA_STYLE_COLOUR('',#201028); -#201964 = OVER_RIDING_STYLED_ITEM('overriding color',(#201965),#174660, - #201766); -#201965 = PRESENTATION_STYLE_ASSIGNMENT((#201966)); -#201966 = SURFACE_STYLE_USAGE(.BOTH.,#201967); -#201967 = SURFACE_SIDE_STYLE('',(#201968)); -#201968 = SURFACE_STYLE_FILL_AREA(#201969); -#201969 = FILL_AREA_STYLE('',(#201970)); -#201970 = FILL_AREA_STYLE_COLOUR('',#201028); -#201971 = OVER_RIDING_STYLED_ITEM('overriding color',(#201972),#174687, - #201766); -#201972 = PRESENTATION_STYLE_ASSIGNMENT((#201973)); -#201973 = SURFACE_STYLE_USAGE(.BOTH.,#201974); -#201974 = SURFACE_SIDE_STYLE('',(#201975)); -#201975 = SURFACE_STYLE_FILL_AREA(#201976); -#201976 = FILL_AREA_STYLE('',(#201977)); -#201977 = FILL_AREA_STYLE_COLOUR('',#201028); -#201978 = OVER_RIDING_STYLED_ITEM('overriding color',(#201979),#174736, - #201766); -#201979 = PRESENTATION_STYLE_ASSIGNMENT((#201980)); -#201980 = SURFACE_STYLE_USAGE(.BOTH.,#201981); -#201981 = SURFACE_SIDE_STYLE('',(#201982)); -#201982 = SURFACE_STYLE_FILL_AREA(#201983); -#201983 = FILL_AREA_STYLE('',(#201984)); -#201984 = FILL_AREA_STYLE_COLOUR('',#201028); -#201985 = OVER_RIDING_STYLED_ITEM('overriding color',(#201986),#174762, - #201766); -#201986 = PRESENTATION_STYLE_ASSIGNMENT((#201987)); -#201987 = SURFACE_STYLE_USAGE(.BOTH.,#201988); -#201988 = SURFACE_SIDE_STYLE('',(#201989)); -#201989 = SURFACE_STYLE_FILL_AREA(#201990); -#201990 = FILL_AREA_STYLE('',(#201991)); -#201991 = FILL_AREA_STYLE_COLOUR('',#201028); -#201992 = OVER_RIDING_STYLED_ITEM('overriding color',(#201993),#174788, - #201766); -#201993 = PRESENTATION_STYLE_ASSIGNMENT((#201994)); -#201994 = SURFACE_STYLE_USAGE(.BOTH.,#201995); -#201995 = SURFACE_SIDE_STYLE('',(#201996)); -#201996 = SURFACE_STYLE_FILL_AREA(#201997); -#201997 = FILL_AREA_STYLE('',(#201998)); -#201998 = FILL_AREA_STYLE_COLOUR('',#201028); -#201999 = OVER_RIDING_STYLED_ITEM('overriding color',(#202000),#174795, - #201766); -#202000 = PRESENTATION_STYLE_ASSIGNMENT((#202001)); -#202001 = SURFACE_STYLE_USAGE(.BOTH.,#202002); -#202002 = SURFACE_SIDE_STYLE('',(#202003)); -#202003 = SURFACE_STYLE_FILL_AREA(#202004); -#202004 = FILL_AREA_STYLE('',(#202005)); -#202005 = FILL_AREA_STYLE_COLOUR('',#201028); -#202006 = OVER_RIDING_STYLED_ITEM('overriding color',(#202007),#174870, - #201766); -#202007 = PRESENTATION_STYLE_ASSIGNMENT((#202008)); -#202008 = SURFACE_STYLE_USAGE(.BOTH.,#202009); -#202009 = SURFACE_SIDE_STYLE('',(#202010)); -#202010 = SURFACE_STYLE_FILL_AREA(#202011); -#202011 = FILL_AREA_STYLE('',(#202012)); -#202012 = FILL_AREA_STYLE_COLOUR('',#201028); -#202013 = OVER_RIDING_STYLED_ITEM('overriding color',(#202014),#174945, - #201766); -#202014 = PRESENTATION_STYLE_ASSIGNMENT((#202015)); -#202015 = SURFACE_STYLE_USAGE(.BOTH.,#202016); -#202016 = SURFACE_SIDE_STYLE('',(#202017)); -#202017 = SURFACE_STYLE_FILL_AREA(#202018); -#202018 = FILL_AREA_STYLE('',(#202019)); -#202019 = FILL_AREA_STYLE_COLOUR('',#201028); -#202020 = OVER_RIDING_STYLED_ITEM('overriding color',(#202021),#175199, - #201766); -#202021 = PRESENTATION_STYLE_ASSIGNMENT((#202022)); -#202022 = SURFACE_STYLE_USAGE(.BOTH.,#202023); -#202023 = SURFACE_SIDE_STYLE('',(#202024)); -#202024 = SURFACE_STYLE_FILL_AREA(#202025); -#202025 = FILL_AREA_STYLE('',(#202026)); -#202026 = FILL_AREA_STYLE_COLOUR('',#201028); -#202027 = OVER_RIDING_STYLED_ITEM('overriding color',(#202028),#175418, - #201766); -#202028 = PRESENTATION_STYLE_ASSIGNMENT((#202029)); -#202029 = SURFACE_STYLE_USAGE(.BOTH.,#202030); -#202030 = SURFACE_SIDE_STYLE('',(#202031)); -#202031 = SURFACE_STYLE_FILL_AREA(#202032); -#202032 = FILL_AREA_STYLE('',(#202033)); -#202033 = FILL_AREA_STYLE_COLOUR('',#201028); -#202034 = OVER_RIDING_STYLED_ITEM('overriding color',(#202035),#175444, - #201766); -#202035 = PRESENTATION_STYLE_ASSIGNMENT((#202036)); -#202036 = SURFACE_STYLE_USAGE(.BOTH.,#202037); -#202037 = SURFACE_SIDE_STYLE('',(#202038)); -#202038 = SURFACE_STYLE_FILL_AREA(#202039); -#202039 = FILL_AREA_STYLE('',(#202040)); -#202040 = FILL_AREA_STYLE_COLOUR('',#201028); -#202041 = OVER_RIDING_STYLED_ITEM('overriding color',(#202042),#175470, - #201766); -#202042 = PRESENTATION_STYLE_ASSIGNMENT((#202043)); -#202043 = SURFACE_STYLE_USAGE(.BOTH.,#202044); -#202044 = SURFACE_SIDE_STYLE('',(#202045)); -#202045 = SURFACE_STYLE_FILL_AREA(#202046); -#202046 = FILL_AREA_STYLE('',(#202047)); -#202047 = FILL_AREA_STYLE_COLOUR('',#201028); -#202048 = OVER_RIDING_STYLED_ITEM('overriding color',(#202049),#175519, - #201766); -#202049 = PRESENTATION_STYLE_ASSIGNMENT((#202050)); -#202050 = SURFACE_STYLE_USAGE(.BOTH.,#202051); -#202051 = SURFACE_SIDE_STYLE('',(#202052)); -#202052 = SURFACE_STYLE_FILL_AREA(#202053); -#202053 = FILL_AREA_STYLE('',(#202054)); -#202054 = FILL_AREA_STYLE_COLOUR('',#201028); -#202055 = OVER_RIDING_STYLED_ITEM('overriding color',(#202056),#175546, - #201766); -#202056 = PRESENTATION_STYLE_ASSIGNMENT((#202057)); -#202057 = SURFACE_STYLE_USAGE(.BOTH.,#202058); -#202058 = SURFACE_SIDE_STYLE('',(#202059)); -#202059 = SURFACE_STYLE_FILL_AREA(#202060); -#202060 = FILL_AREA_STYLE('',(#202061)); -#202061 = FILL_AREA_STYLE_COLOUR('',#201028); -#202062 = OVER_RIDING_STYLED_ITEM('overriding color',(#202063),#175573, - #201766); -#202063 = PRESENTATION_STYLE_ASSIGNMENT((#202064)); -#202064 = SURFACE_STYLE_USAGE(.BOTH.,#202065); -#202065 = SURFACE_SIDE_STYLE('',(#202066)); -#202066 = SURFACE_STYLE_FILL_AREA(#202067); -#202067 = FILL_AREA_STYLE('',(#202068)); -#202068 = FILL_AREA_STYLE_COLOUR('',#201028); -#202069 = OVER_RIDING_STYLED_ITEM('overriding color',(#202070),#175622, - #201766); -#202070 = PRESENTATION_STYLE_ASSIGNMENT((#202071)); -#202071 = SURFACE_STYLE_USAGE(.BOTH.,#202072); -#202072 = SURFACE_SIDE_STYLE('',(#202073)); -#202073 = SURFACE_STYLE_FILL_AREA(#202074); -#202074 = FILL_AREA_STYLE('',(#202075)); -#202075 = FILL_AREA_STYLE_COLOUR('',#201028); -#202076 = OVER_RIDING_STYLED_ITEM('overriding color',(#202077),#175648, - #201766); -#202077 = PRESENTATION_STYLE_ASSIGNMENT((#202078)); -#202078 = SURFACE_STYLE_USAGE(.BOTH.,#202079); -#202079 = SURFACE_SIDE_STYLE('',(#202080)); -#202080 = SURFACE_STYLE_FILL_AREA(#202081); -#202081 = FILL_AREA_STYLE('',(#202082)); -#202082 = FILL_AREA_STYLE_COLOUR('',#201028); -#202083 = OVER_RIDING_STYLED_ITEM('overriding color',(#202084),#175674, - #201766); -#202084 = PRESENTATION_STYLE_ASSIGNMENT((#202085)); -#202085 = SURFACE_STYLE_USAGE(.BOTH.,#202086); -#202086 = SURFACE_SIDE_STYLE('',(#202087)); -#202087 = SURFACE_STYLE_FILL_AREA(#202088); -#202088 = FILL_AREA_STYLE('',(#202089)); -#202089 = FILL_AREA_STYLE_COLOUR('',#201028); -#202090 = OVER_RIDING_STYLED_ITEM('overriding color',(#202091),#175681, - #201766); -#202091 = PRESENTATION_STYLE_ASSIGNMENT((#202092)); -#202092 = SURFACE_STYLE_USAGE(.BOTH.,#202093); -#202093 = SURFACE_SIDE_STYLE('',(#202094)); -#202094 = SURFACE_STYLE_FILL_AREA(#202095); -#202095 = FILL_AREA_STYLE('',(#202096)); -#202096 = FILL_AREA_STYLE_COLOUR('',#201781); -#202097 = OVER_RIDING_STYLED_ITEM('overriding color',(#202098),#175819, - #201766); -#202098 = PRESENTATION_STYLE_ASSIGNMENT((#202099)); -#202099 = SURFACE_STYLE_USAGE(.BOTH.,#202100); -#202100 = SURFACE_SIDE_STYLE('',(#202101)); -#202101 = SURFACE_STYLE_FILL_AREA(#202102); -#202102 = FILL_AREA_STYLE('',(#202103)); -#202103 = FILL_AREA_STYLE_COLOUR('',#201781); -#202104 = OVER_RIDING_STYLED_ITEM('overriding color',(#202105),#175892, - #201766); -#202105 = PRESENTATION_STYLE_ASSIGNMENT((#202106)); -#202106 = SURFACE_STYLE_USAGE(.BOTH.,#202107); -#202107 = SURFACE_SIDE_STYLE('',(#202108)); -#202108 = SURFACE_STYLE_FILL_AREA(#202109); -#202109 = FILL_AREA_STYLE('',(#202110)); -#202110 = FILL_AREA_STYLE_COLOUR('',#201781); -#202111 = OVER_RIDING_STYLED_ITEM('overriding color',(#202112),#176030, - #201766); -#202112 = PRESENTATION_STYLE_ASSIGNMENT((#202113)); -#202113 = SURFACE_STYLE_USAGE(.BOTH.,#202114); -#202114 = SURFACE_SIDE_STYLE('',(#202115)); -#202115 = SURFACE_STYLE_FILL_AREA(#202116); -#202116 = FILL_AREA_STYLE('',(#202117)); -#202117 = FILL_AREA_STYLE_COLOUR('',#201781); -#202118 = OVER_RIDING_STYLED_ITEM('overriding color',(#202119),#176103, - #201766); -#202119 = PRESENTATION_STYLE_ASSIGNMENT((#202120)); -#202120 = SURFACE_STYLE_USAGE(.BOTH.,#202121); -#202121 = SURFACE_SIDE_STYLE('',(#202122)); -#202122 = SURFACE_STYLE_FILL_AREA(#202123); -#202123 = FILL_AREA_STYLE('',(#202124)); -#202124 = FILL_AREA_STYLE_COLOUR('',#201781); -#202125 = OVER_RIDING_STYLED_ITEM('overriding color',(#202126),#176241, - #201766); -#202126 = PRESENTATION_STYLE_ASSIGNMENT((#202127)); -#202127 = SURFACE_STYLE_USAGE(.BOTH.,#202128); -#202128 = SURFACE_SIDE_STYLE('',(#202129)); -#202129 = SURFACE_STYLE_FILL_AREA(#202130); -#202130 = FILL_AREA_STYLE('',(#202131)); -#202131 = FILL_AREA_STYLE_COLOUR('',#201781); -#202132 = OVER_RIDING_STYLED_ITEM('overriding color',(#202133),#176314, - #201766); -#202133 = PRESENTATION_STYLE_ASSIGNMENT((#202134)); -#202134 = SURFACE_STYLE_USAGE(.BOTH.,#202135); -#202135 = SURFACE_SIDE_STYLE('',(#202136)); -#202136 = SURFACE_STYLE_FILL_AREA(#202137); -#202137 = FILL_AREA_STYLE('',(#202138)); -#202138 = FILL_AREA_STYLE_COLOUR('',#201781); -#202139 = OVER_RIDING_STYLED_ITEM('overriding color',(#202140),#176452, - #201766); -#202140 = PRESENTATION_STYLE_ASSIGNMENT((#202141)); -#202141 = SURFACE_STYLE_USAGE(.BOTH.,#202142); -#202142 = SURFACE_SIDE_STYLE('',(#202143)); -#202143 = SURFACE_STYLE_FILL_AREA(#202144); -#202144 = FILL_AREA_STYLE('',(#202145)); -#202145 = FILL_AREA_STYLE_COLOUR('',#201781); -#202146 = OVER_RIDING_STYLED_ITEM('overriding color',(#202147),#176525, - #201766); -#202147 = PRESENTATION_STYLE_ASSIGNMENT((#202148)); -#202148 = SURFACE_STYLE_USAGE(.BOTH.,#202149); -#202149 = SURFACE_SIDE_STYLE('',(#202150)); -#202150 = SURFACE_STYLE_FILL_AREA(#202151); -#202151 = FILL_AREA_STYLE('',(#202152)); -#202152 = FILL_AREA_STYLE_COLOUR('',#201781); -#202153 = OVER_RIDING_STYLED_ITEM('overriding color',(#202154),#176575, - #201766); -#202154 = PRESENTATION_STYLE_ASSIGNMENT((#202155)); -#202155 = SURFACE_STYLE_USAGE(.BOTH.,#202156); -#202156 = SURFACE_SIDE_STYLE('',(#202157)); -#202157 = SURFACE_STYLE_FILL_AREA(#202158); -#202158 = FILL_AREA_STYLE('',(#202159)); -#202159 = FILL_AREA_STYLE_COLOUR('',#195025); -#202160 = OVER_RIDING_STYLED_ITEM('overriding color',(#202161),#176580, - #201766); -#202161 = PRESENTATION_STYLE_ASSIGNMENT((#202162)); -#202162 = SURFACE_STYLE_USAGE(.BOTH.,#202163); -#202163 = SURFACE_SIDE_STYLE('',(#202164)); -#202164 = SURFACE_STYLE_FILL_AREA(#202165); -#202165 = FILL_AREA_STYLE('',(#202166)); -#202166 = FILL_AREA_STYLE_COLOUR('',#201781); -#202167 = OVER_RIDING_STYLED_ITEM('overriding color',(#202168),#176629, - #201766); -#202168 = PRESENTATION_STYLE_ASSIGNMENT((#202169)); -#202169 = SURFACE_STYLE_USAGE(.BOTH.,#202170); -#202170 = SURFACE_SIDE_STYLE('',(#202171)); -#202171 = SURFACE_STYLE_FILL_AREA(#202172); -#202172 = FILL_AREA_STYLE('',(#202173)); -#202173 = FILL_AREA_STYLE_COLOUR('',#201781); -#202174 = OVER_RIDING_STYLED_ITEM('overriding color',(#202175),#176636, - #201766); -#202175 = PRESENTATION_STYLE_ASSIGNMENT((#202176)); -#202176 = SURFACE_STYLE_USAGE(.BOTH.,#202177); -#202177 = SURFACE_SIDE_STYLE('',(#202178)); -#202178 = SURFACE_STYLE_FILL_AREA(#202179); -#202179 = FILL_AREA_STYLE('',(#202180)); -#202180 = FILL_AREA_STYLE_COLOUR('',#201781); -#202181 = OVER_RIDING_STYLED_ITEM('overriding color',(#202182),#176685, - #201766); -#202182 = PRESENTATION_STYLE_ASSIGNMENT((#202183)); -#202183 = SURFACE_STYLE_USAGE(.BOTH.,#202184); -#202184 = SURFACE_SIDE_STYLE('',(#202185)); -#202185 = SURFACE_STYLE_FILL_AREA(#202186); -#202186 = FILL_AREA_STYLE('',(#202187)); -#202187 = FILL_AREA_STYLE_COLOUR('',#201781); -#202188 = OVER_RIDING_STYLED_ITEM('overriding color',(#202189),#176734, - #201766); -#202189 = PRESENTATION_STYLE_ASSIGNMENT((#202190)); -#202190 = SURFACE_STYLE_USAGE(.BOTH.,#202191); -#202191 = SURFACE_SIDE_STYLE('',(#202192)); -#202192 = SURFACE_STYLE_FILL_AREA(#202193); -#202193 = FILL_AREA_STYLE('',(#202194)); -#202194 = FILL_AREA_STYLE_COLOUR('',#201781); -#202195 = OVER_RIDING_STYLED_ITEM('overriding color',(#202196),#176741, - #201766); -#202196 = PRESENTATION_STYLE_ASSIGNMENT((#202197)); -#202197 = SURFACE_STYLE_USAGE(.BOTH.,#202198); -#202198 = SURFACE_SIDE_STYLE('',(#202199)); -#202199 = SURFACE_STYLE_FILL_AREA(#202200); -#202200 = FILL_AREA_STYLE('',(#202201)); -#202201 = FILL_AREA_STYLE_COLOUR('',#201781); -#202202 = OVER_RIDING_STYLED_ITEM('overriding color',(#202203),#176748, - #201766); -#202203 = PRESENTATION_STYLE_ASSIGNMENT((#202204)); -#202204 = SURFACE_STYLE_USAGE(.BOTH.,#202205); -#202205 = SURFACE_SIDE_STYLE('',(#202206)); -#202206 = SURFACE_STYLE_FILL_AREA(#202207); -#202207 = FILL_AREA_STYLE('',(#202208)); -#202208 = FILL_AREA_STYLE_COLOUR('',#201781); -#202209 = OVER_RIDING_STYLED_ITEM('overriding color',(#202210),#176797, - #201766); -#202210 = PRESENTATION_STYLE_ASSIGNMENT((#202211)); -#202211 = SURFACE_STYLE_USAGE(.BOTH.,#202212); -#202212 = SURFACE_SIDE_STYLE('',(#202213)); -#202213 = SURFACE_STYLE_FILL_AREA(#202214); -#202214 = FILL_AREA_STYLE('',(#202215)); -#202215 = FILL_AREA_STYLE_COLOUR('',#201781); -#202216 = OVER_RIDING_STYLED_ITEM('overriding color',(#202217),#176804, - #201766); -#202217 = PRESENTATION_STYLE_ASSIGNMENT((#202218)); -#202218 = SURFACE_STYLE_USAGE(.BOTH.,#202219); -#202219 = SURFACE_SIDE_STYLE('',(#202220)); -#202220 = SURFACE_STYLE_FILL_AREA(#202221); -#202221 = FILL_AREA_STYLE('',(#202222)); -#202222 = FILL_AREA_STYLE_COLOUR('',#201781); -#202223 = OVER_RIDING_STYLED_ITEM('overriding color',(#202224),#176853, - #201766); -#202224 = PRESENTATION_STYLE_ASSIGNMENT((#202225)); -#202225 = SURFACE_STYLE_USAGE(.BOTH.,#202226); -#202226 = SURFACE_SIDE_STYLE('',(#202227)); -#202227 = SURFACE_STYLE_FILL_AREA(#202228); -#202228 = FILL_AREA_STYLE('',(#202229)); -#202229 = FILL_AREA_STYLE_COLOUR('',#201781); -#202230 = OVER_RIDING_STYLED_ITEM('overriding color',(#202231),#176902, - #201766); -#202231 = PRESENTATION_STYLE_ASSIGNMENT((#202232)); -#202232 = SURFACE_STYLE_USAGE(.BOTH.,#202233); -#202233 = SURFACE_SIDE_STYLE('',(#202234)); -#202234 = SURFACE_STYLE_FILL_AREA(#202235); -#202235 = FILL_AREA_STYLE('',(#202236)); -#202236 = FILL_AREA_STYLE_COLOUR('',#201781); -#202237 = OVER_RIDING_STYLED_ITEM('overriding color',(#202238),#176909, - #201766); -#202238 = PRESENTATION_STYLE_ASSIGNMENT((#202239)); -#202239 = SURFACE_STYLE_USAGE(.BOTH.,#202240); -#202240 = SURFACE_SIDE_STYLE('',(#202241)); -#202241 = SURFACE_STYLE_FILL_AREA(#202242); -#202242 = FILL_AREA_STYLE('',(#202243)); -#202243 = FILL_AREA_STYLE_COLOUR('',#201781); -#202244 = OVER_RIDING_STYLED_ITEM('overriding color',(#202245),#176916, - #201766); -#202245 = PRESENTATION_STYLE_ASSIGNMENT((#202246)); -#202246 = SURFACE_STYLE_USAGE(.BOTH.,#202247); -#202247 = SURFACE_SIDE_STYLE('',(#202248)); -#202248 = SURFACE_STYLE_FILL_AREA(#202249); -#202249 = FILL_AREA_STYLE('',(#202250)); -#202250 = FILL_AREA_STYLE_COLOUR('',#201781); -#202251 = OVER_RIDING_STYLED_ITEM('overriding color',(#202252),#176965, - #201766); -#202252 = PRESENTATION_STYLE_ASSIGNMENT((#202253)); -#202253 = SURFACE_STYLE_USAGE(.BOTH.,#202254); -#202254 = SURFACE_SIDE_STYLE('',(#202255)); -#202255 = SURFACE_STYLE_FILL_AREA(#202256); -#202256 = FILL_AREA_STYLE('',(#202257)); -#202257 = FILL_AREA_STYLE_COLOUR('',#201781); -#202258 = OVER_RIDING_STYLED_ITEM('overriding color',(#202259),#177014, - #201766); -#202259 = PRESENTATION_STYLE_ASSIGNMENT((#202260)); -#202260 = SURFACE_STYLE_USAGE(.BOTH.,#202261); -#202261 = SURFACE_SIDE_STYLE('',(#202262)); -#202262 = SURFACE_STYLE_FILL_AREA(#202263); -#202263 = FILL_AREA_STYLE('',(#202264)); -#202264 = FILL_AREA_STYLE_COLOUR('',#201781); -#202265 = OVER_RIDING_STYLED_ITEM('overriding color',(#202266),#177021, - #201766); -#202266 = PRESENTATION_STYLE_ASSIGNMENT((#202267)); -#202267 = SURFACE_STYLE_USAGE(.BOTH.,#202268); -#202268 = SURFACE_SIDE_STYLE('',(#202269)); -#202269 = SURFACE_STYLE_FILL_AREA(#202270); -#202270 = FILL_AREA_STYLE('',(#202271)); -#202271 = FILL_AREA_STYLE_COLOUR('',#201781); -#202272 = OVER_RIDING_STYLED_ITEM('overriding color',(#202273),#177028, - #201766); -#202273 = PRESENTATION_STYLE_ASSIGNMENT((#202274)); -#202274 = SURFACE_STYLE_USAGE(.BOTH.,#202275); -#202275 = SURFACE_SIDE_STYLE('',(#202276)); -#202276 = SURFACE_STYLE_FILL_AREA(#202277); -#202277 = FILL_AREA_STYLE('',(#202278)); -#202278 = FILL_AREA_STYLE_COLOUR('',#201028); -#202279 = OVER_RIDING_STYLED_ITEM('overriding color',(#202280),#177103, - #201766); -#202280 = PRESENTATION_STYLE_ASSIGNMENT((#202281)); -#202281 = SURFACE_STYLE_USAGE(.BOTH.,#202282); -#202282 = SURFACE_SIDE_STYLE('',(#202283)); -#202283 = SURFACE_STYLE_FILL_AREA(#202284); -#202284 = FILL_AREA_STYLE('',(#202285)); -#202285 = FILL_AREA_STYLE_COLOUR('',#201028); -#202286 = OVER_RIDING_STYLED_ITEM('overriding color',(#202287),#177384, - #201766); -#202287 = PRESENTATION_STYLE_ASSIGNMENT((#202288)); -#202288 = SURFACE_STYLE_USAGE(.BOTH.,#202289); -#202289 = SURFACE_SIDE_STYLE('',(#202290)); -#202290 = SURFACE_STYLE_FILL_AREA(#202291); -#202291 = FILL_AREA_STYLE('',(#202292)); -#202292 = FILL_AREA_STYLE_COLOUR('',#201028); -#202293 = OVER_RIDING_STYLED_ITEM('overriding color',(#202294),#177432, - #201766); -#202294 = PRESENTATION_STYLE_ASSIGNMENT((#202295)); -#202295 = SURFACE_STYLE_USAGE(.BOTH.,#202296); -#202296 = SURFACE_SIDE_STYLE('',(#202297)); -#202297 = SURFACE_STYLE_FILL_AREA(#202298); -#202298 = FILL_AREA_STYLE('',(#202299)); -#202299 = FILL_AREA_STYLE_COLOUR('',#201028); -#202300 = OVER_RIDING_STYLED_ITEM('overriding color',(#202301),#177651, - #201766); -#202301 = PRESENTATION_STYLE_ASSIGNMENT((#202302)); -#202302 = SURFACE_STYLE_USAGE(.BOTH.,#202303); -#202303 = SURFACE_SIDE_STYLE('',(#202304)); -#202304 = SURFACE_STYLE_FILL_AREA(#202305); -#202305 = FILL_AREA_STYLE('',(#202306)); -#202306 = FILL_AREA_STYLE_COLOUR('',#201028); -#202307 = OVER_RIDING_STYLED_ITEM('overriding color',(#202308),#177677, - #201766); -#202308 = PRESENTATION_STYLE_ASSIGNMENT((#202309)); -#202309 = SURFACE_STYLE_USAGE(.BOTH.,#202310); -#202310 = SURFACE_SIDE_STYLE('',(#202311)); -#202311 = SURFACE_STYLE_FILL_AREA(#202312); -#202312 = FILL_AREA_STYLE('',(#202313)); -#202313 = FILL_AREA_STYLE_COLOUR('',#201028); -#202314 = OVER_RIDING_STYLED_ITEM('overriding color',(#202315),#177703, - #201766); -#202315 = PRESENTATION_STYLE_ASSIGNMENT((#202316)); -#202316 = SURFACE_STYLE_USAGE(.BOTH.,#202317); -#202317 = SURFACE_SIDE_STYLE('',(#202318)); -#202318 = SURFACE_STYLE_FILL_AREA(#202319); -#202319 = FILL_AREA_STYLE('',(#202320)); -#202320 = FILL_AREA_STYLE_COLOUR('',#201028); -#202321 = OVER_RIDING_STYLED_ITEM('overriding color',(#202322),#177752, - #201766); -#202322 = PRESENTATION_STYLE_ASSIGNMENT((#202323)); -#202323 = SURFACE_STYLE_USAGE(.BOTH.,#202324); -#202324 = SURFACE_SIDE_STYLE('',(#202325)); -#202325 = SURFACE_STYLE_FILL_AREA(#202326); -#202326 = FILL_AREA_STYLE('',(#202327)); -#202327 = FILL_AREA_STYLE_COLOUR('',#201028); -#202328 = OVER_RIDING_STYLED_ITEM('overriding color',(#202329),#177779, - #201766); -#202329 = PRESENTATION_STYLE_ASSIGNMENT((#202330)); -#202330 = SURFACE_STYLE_USAGE(.BOTH.,#202331); -#202331 = SURFACE_SIDE_STYLE('',(#202332)); -#202332 = SURFACE_STYLE_FILL_AREA(#202333); -#202333 = FILL_AREA_STYLE('',(#202334)); -#202334 = FILL_AREA_STYLE_COLOUR('',#201028); -#202335 = OVER_RIDING_STYLED_ITEM('overriding color',(#202336),#177806, - #201766); -#202336 = PRESENTATION_STYLE_ASSIGNMENT((#202337)); -#202337 = SURFACE_STYLE_USAGE(.BOTH.,#202338); -#202338 = SURFACE_SIDE_STYLE('',(#202339)); -#202339 = SURFACE_STYLE_FILL_AREA(#202340); -#202340 = FILL_AREA_STYLE('',(#202341)); -#202341 = FILL_AREA_STYLE_COLOUR('',#201028); -#202342 = OVER_RIDING_STYLED_ITEM('overriding color',(#202343),#177855, - #201766); -#202343 = PRESENTATION_STYLE_ASSIGNMENT((#202344)); -#202344 = SURFACE_STYLE_USAGE(.BOTH.,#202345); -#202345 = SURFACE_SIDE_STYLE('',(#202346)); -#202346 = SURFACE_STYLE_FILL_AREA(#202347); -#202347 = FILL_AREA_STYLE('',(#202348)); -#202348 = FILL_AREA_STYLE_COLOUR('',#201028); -#202349 = OVER_RIDING_STYLED_ITEM('overriding color',(#202350),#177881, - #201766); -#202350 = PRESENTATION_STYLE_ASSIGNMENT((#202351)); -#202351 = SURFACE_STYLE_USAGE(.BOTH.,#202352); -#202352 = SURFACE_SIDE_STYLE('',(#202353)); -#202353 = SURFACE_STYLE_FILL_AREA(#202354); -#202354 = FILL_AREA_STYLE('',(#202355)); -#202355 = FILL_AREA_STYLE_COLOUR('',#201028); -#202356 = OVER_RIDING_STYLED_ITEM('overriding color',(#202357),#177907, - #201766); -#202357 = PRESENTATION_STYLE_ASSIGNMENT((#202358)); -#202358 = SURFACE_STYLE_USAGE(.BOTH.,#202359); -#202359 = SURFACE_SIDE_STYLE('',(#202360)); -#202360 = SURFACE_STYLE_FILL_AREA(#202361); -#202361 = FILL_AREA_STYLE('',(#202362)); -#202362 = FILL_AREA_STYLE_COLOUR('',#201028); -#202363 = OVER_RIDING_STYLED_ITEM('overriding color',(#202364),#177914, - #201766); -#202364 = PRESENTATION_STYLE_ASSIGNMENT((#202365)); -#202365 = SURFACE_STYLE_USAGE(.BOTH.,#202366); -#202366 = SURFACE_SIDE_STYLE('',(#202367)); -#202367 = SURFACE_STYLE_FILL_AREA(#202368); -#202368 = FILL_AREA_STYLE('',(#202369)); -#202369 = FILL_AREA_STYLE_COLOUR('',#201028); -#202370 = OVER_RIDING_STYLED_ITEM('overriding color',(#202371),#177989, - #201766); -#202371 = PRESENTATION_STYLE_ASSIGNMENT((#202372)); -#202372 = SURFACE_STYLE_USAGE(.BOTH.,#202373); -#202373 = SURFACE_SIDE_STYLE('',(#202374)); -#202374 = SURFACE_STYLE_FILL_AREA(#202375); -#202375 = FILL_AREA_STYLE('',(#202376)); -#202376 = FILL_AREA_STYLE_COLOUR('',#201028); -#202377 = OVER_RIDING_STYLED_ITEM('overriding color',(#202378),#178270, - #201766); -#202378 = PRESENTATION_STYLE_ASSIGNMENT((#202379)); -#202379 = SURFACE_STYLE_USAGE(.BOTH.,#202380); -#202380 = SURFACE_SIDE_STYLE('',(#202381)); -#202381 = SURFACE_STYLE_FILL_AREA(#202382); -#202382 = FILL_AREA_STYLE('',(#202383)); -#202383 = FILL_AREA_STYLE_COLOUR('',#201028); -#202384 = OVER_RIDING_STYLED_ITEM('overriding color',(#202385),#178318, - #201766); -#202385 = PRESENTATION_STYLE_ASSIGNMENT((#202386)); -#202386 = SURFACE_STYLE_USAGE(.BOTH.,#202387); -#202387 = SURFACE_SIDE_STYLE('',(#202388)); -#202388 = SURFACE_STYLE_FILL_AREA(#202389); -#202389 = FILL_AREA_STYLE('',(#202390)); -#202390 = FILL_AREA_STYLE_COLOUR('',#201028); -#202391 = OVER_RIDING_STYLED_ITEM('overriding color',(#202392),#178537, - #201766); -#202392 = PRESENTATION_STYLE_ASSIGNMENT((#202393)); -#202393 = SURFACE_STYLE_USAGE(.BOTH.,#202394); -#202394 = SURFACE_SIDE_STYLE('',(#202395)); -#202395 = SURFACE_STYLE_FILL_AREA(#202396); -#202396 = FILL_AREA_STYLE('',(#202397)); -#202397 = FILL_AREA_STYLE_COLOUR('',#201028); -#202398 = OVER_RIDING_STYLED_ITEM('overriding color',(#202399),#178563, - #201766); -#202399 = PRESENTATION_STYLE_ASSIGNMENT((#202400)); -#202400 = SURFACE_STYLE_USAGE(.BOTH.,#202401); -#202401 = SURFACE_SIDE_STYLE('',(#202402)); -#202402 = SURFACE_STYLE_FILL_AREA(#202403); -#202403 = FILL_AREA_STYLE('',(#202404)); -#202404 = FILL_AREA_STYLE_COLOUR('',#201028); -#202405 = OVER_RIDING_STYLED_ITEM('overriding color',(#202406),#178589, - #201766); -#202406 = PRESENTATION_STYLE_ASSIGNMENT((#202407)); -#202407 = SURFACE_STYLE_USAGE(.BOTH.,#202408); -#202408 = SURFACE_SIDE_STYLE('',(#202409)); -#202409 = SURFACE_STYLE_FILL_AREA(#202410); -#202410 = FILL_AREA_STYLE('',(#202411)); -#202411 = FILL_AREA_STYLE_COLOUR('',#201028); -#202412 = OVER_RIDING_STYLED_ITEM('overriding color',(#202413),#178638, - #201766); -#202413 = PRESENTATION_STYLE_ASSIGNMENT((#202414)); -#202414 = SURFACE_STYLE_USAGE(.BOTH.,#202415); -#202415 = SURFACE_SIDE_STYLE('',(#202416)); -#202416 = SURFACE_STYLE_FILL_AREA(#202417); -#202417 = FILL_AREA_STYLE('',(#202418)); -#202418 = FILL_AREA_STYLE_COLOUR('',#201028); -#202419 = OVER_RIDING_STYLED_ITEM('overriding color',(#202420),#178665, - #201766); -#202420 = PRESENTATION_STYLE_ASSIGNMENT((#202421)); -#202421 = SURFACE_STYLE_USAGE(.BOTH.,#202422); -#202422 = SURFACE_SIDE_STYLE('',(#202423)); -#202423 = SURFACE_STYLE_FILL_AREA(#202424); -#202424 = FILL_AREA_STYLE('',(#202425)); -#202425 = FILL_AREA_STYLE_COLOUR('',#201028); -#202426 = OVER_RIDING_STYLED_ITEM('overriding color',(#202427),#178692, - #201766); -#202427 = PRESENTATION_STYLE_ASSIGNMENT((#202428)); -#202428 = SURFACE_STYLE_USAGE(.BOTH.,#202429); -#202429 = SURFACE_SIDE_STYLE('',(#202430)); -#202430 = SURFACE_STYLE_FILL_AREA(#202431); -#202431 = FILL_AREA_STYLE('',(#202432)); -#202432 = FILL_AREA_STYLE_COLOUR('',#201028); -#202433 = OVER_RIDING_STYLED_ITEM('overriding color',(#202434),#178741, - #201766); -#202434 = PRESENTATION_STYLE_ASSIGNMENT((#202435)); -#202435 = SURFACE_STYLE_USAGE(.BOTH.,#202436); -#202436 = SURFACE_SIDE_STYLE('',(#202437)); -#202437 = SURFACE_STYLE_FILL_AREA(#202438); -#202438 = FILL_AREA_STYLE('',(#202439)); -#202439 = FILL_AREA_STYLE_COLOUR('',#201028); -#202440 = OVER_RIDING_STYLED_ITEM('overriding color',(#202441),#178767, - #201766); -#202441 = PRESENTATION_STYLE_ASSIGNMENT((#202442)); -#202442 = SURFACE_STYLE_USAGE(.BOTH.,#202443); -#202443 = SURFACE_SIDE_STYLE('',(#202444)); -#202444 = SURFACE_STYLE_FILL_AREA(#202445); -#202445 = FILL_AREA_STYLE('',(#202446)); -#202446 = FILL_AREA_STYLE_COLOUR('',#201028); -#202447 = OVER_RIDING_STYLED_ITEM('overriding color',(#202448),#178793, - #201766); -#202448 = PRESENTATION_STYLE_ASSIGNMENT((#202449)); -#202449 = SURFACE_STYLE_USAGE(.BOTH.,#202450); -#202450 = SURFACE_SIDE_STYLE('',(#202451)); -#202451 = SURFACE_STYLE_FILL_AREA(#202452); -#202452 = FILL_AREA_STYLE('',(#202453)); -#202453 = FILL_AREA_STYLE_COLOUR('',#201028); -#202454 = OVER_RIDING_STYLED_ITEM('overriding color',(#202455),#178800, - #201766); -#202455 = PRESENTATION_STYLE_ASSIGNMENT((#202456)); -#202456 = SURFACE_STYLE_USAGE(.BOTH.,#202457); -#202457 = SURFACE_SIDE_STYLE('',(#202458)); -#202458 = SURFACE_STYLE_FILL_AREA(#202459); -#202459 = FILL_AREA_STYLE('',(#202460)); -#202460 = FILL_AREA_STYLE_COLOUR('',#201028); -#202461 = OVER_RIDING_STYLED_ITEM('overriding color',(#202462),#178875, - #201766); -#202462 = PRESENTATION_STYLE_ASSIGNMENT((#202463)); -#202463 = SURFACE_STYLE_USAGE(.BOTH.,#202464); -#202464 = SURFACE_SIDE_STYLE('',(#202465)); -#202465 = SURFACE_STYLE_FILL_AREA(#202466); -#202466 = FILL_AREA_STYLE('',(#202467)); -#202467 = FILL_AREA_STYLE_COLOUR('',#201028); -#202468 = OVER_RIDING_STYLED_ITEM('overriding color',(#202469),#179156, - #201766); -#202469 = PRESENTATION_STYLE_ASSIGNMENT((#202470)); -#202470 = SURFACE_STYLE_USAGE(.BOTH.,#202471); -#202471 = SURFACE_SIDE_STYLE('',(#202472)); -#202472 = SURFACE_STYLE_FILL_AREA(#202473); -#202473 = FILL_AREA_STYLE('',(#202474)); -#202474 = FILL_AREA_STYLE_COLOUR('',#201028); -#202475 = OVER_RIDING_STYLED_ITEM('overriding color',(#202476),#179204, - #201766); -#202476 = PRESENTATION_STYLE_ASSIGNMENT((#202477)); -#202477 = SURFACE_STYLE_USAGE(.BOTH.,#202478); -#202478 = SURFACE_SIDE_STYLE('',(#202479)); -#202479 = SURFACE_STYLE_FILL_AREA(#202480); -#202480 = FILL_AREA_STYLE('',(#202481)); -#202481 = FILL_AREA_STYLE_COLOUR('',#201028); -#202482 = OVER_RIDING_STYLED_ITEM('overriding color',(#202483),#179423, - #201766); -#202483 = PRESENTATION_STYLE_ASSIGNMENT((#202484)); -#202484 = SURFACE_STYLE_USAGE(.BOTH.,#202485); -#202485 = SURFACE_SIDE_STYLE('',(#202486)); -#202486 = SURFACE_STYLE_FILL_AREA(#202487); -#202487 = FILL_AREA_STYLE('',(#202488)); -#202488 = FILL_AREA_STYLE_COLOUR('',#201028); -#202489 = OVER_RIDING_STYLED_ITEM('overriding color',(#202490),#179449, - #201766); -#202490 = PRESENTATION_STYLE_ASSIGNMENT((#202491)); -#202491 = SURFACE_STYLE_USAGE(.BOTH.,#202492); -#202492 = SURFACE_SIDE_STYLE('',(#202493)); -#202493 = SURFACE_STYLE_FILL_AREA(#202494); -#202494 = FILL_AREA_STYLE('',(#202495)); -#202495 = FILL_AREA_STYLE_COLOUR('',#201028); -#202496 = OVER_RIDING_STYLED_ITEM('overriding color',(#202497),#179475, - #201766); -#202497 = PRESENTATION_STYLE_ASSIGNMENT((#202498)); -#202498 = SURFACE_STYLE_USAGE(.BOTH.,#202499); -#202499 = SURFACE_SIDE_STYLE('',(#202500)); -#202500 = SURFACE_STYLE_FILL_AREA(#202501); -#202501 = FILL_AREA_STYLE('',(#202502)); -#202502 = FILL_AREA_STYLE_COLOUR('',#201028); -#202503 = OVER_RIDING_STYLED_ITEM('overriding color',(#202504),#179524, - #201766); -#202504 = PRESENTATION_STYLE_ASSIGNMENT((#202505)); -#202505 = SURFACE_STYLE_USAGE(.BOTH.,#202506); -#202506 = SURFACE_SIDE_STYLE('',(#202507)); -#202507 = SURFACE_STYLE_FILL_AREA(#202508); -#202508 = FILL_AREA_STYLE('',(#202509)); -#202509 = FILL_AREA_STYLE_COLOUR('',#201028); -#202510 = OVER_RIDING_STYLED_ITEM('overriding color',(#202511),#179551, - #201766); -#202511 = PRESENTATION_STYLE_ASSIGNMENT((#202512)); -#202512 = SURFACE_STYLE_USAGE(.BOTH.,#202513); -#202513 = SURFACE_SIDE_STYLE('',(#202514)); -#202514 = SURFACE_STYLE_FILL_AREA(#202515); -#202515 = FILL_AREA_STYLE('',(#202516)); -#202516 = FILL_AREA_STYLE_COLOUR('',#201028); -#202517 = OVER_RIDING_STYLED_ITEM('overriding color',(#202518),#179578, - #201766); -#202518 = PRESENTATION_STYLE_ASSIGNMENT((#202519)); -#202519 = SURFACE_STYLE_USAGE(.BOTH.,#202520); -#202520 = SURFACE_SIDE_STYLE('',(#202521)); -#202521 = SURFACE_STYLE_FILL_AREA(#202522); -#202522 = FILL_AREA_STYLE('',(#202523)); -#202523 = FILL_AREA_STYLE_COLOUR('',#201028); -#202524 = OVER_RIDING_STYLED_ITEM('overriding color',(#202525),#179627, - #201766); -#202525 = PRESENTATION_STYLE_ASSIGNMENT((#202526)); -#202526 = SURFACE_STYLE_USAGE(.BOTH.,#202527); -#202527 = SURFACE_SIDE_STYLE('',(#202528)); -#202528 = SURFACE_STYLE_FILL_AREA(#202529); -#202529 = FILL_AREA_STYLE('',(#202530)); -#202530 = FILL_AREA_STYLE_COLOUR('',#201028); -#202531 = OVER_RIDING_STYLED_ITEM('overriding color',(#202532),#179653, - #201766); -#202532 = PRESENTATION_STYLE_ASSIGNMENT((#202533)); -#202533 = SURFACE_STYLE_USAGE(.BOTH.,#202534); -#202534 = SURFACE_SIDE_STYLE('',(#202535)); -#202535 = SURFACE_STYLE_FILL_AREA(#202536); -#202536 = FILL_AREA_STYLE('',(#202537)); -#202537 = FILL_AREA_STYLE_COLOUR('',#201028); -#202538 = OVER_RIDING_STYLED_ITEM('overriding color',(#202539),#179679, - #201766); -#202539 = PRESENTATION_STYLE_ASSIGNMENT((#202540)); -#202540 = SURFACE_STYLE_USAGE(.BOTH.,#202541); -#202541 = SURFACE_SIDE_STYLE('',(#202542)); -#202542 = SURFACE_STYLE_FILL_AREA(#202543); -#202543 = FILL_AREA_STYLE('',(#202544)); -#202544 = FILL_AREA_STYLE_COLOUR('',#201028); -#202545 = OVER_RIDING_STYLED_ITEM('overriding color',(#202546),#179686, - #201766); -#202546 = PRESENTATION_STYLE_ASSIGNMENT((#202547)); -#202547 = SURFACE_STYLE_USAGE(.BOTH.,#202548); -#202548 = SURFACE_SIDE_STYLE('',(#202549)); -#202549 = SURFACE_STYLE_FILL_AREA(#202550); -#202550 = FILL_AREA_STYLE('',(#202551)); -#202551 = FILL_AREA_STYLE_COLOUR('',#201028); -#202552 = OVER_RIDING_STYLED_ITEM('overriding color',(#202553),#179761, - #201766); -#202553 = PRESENTATION_STYLE_ASSIGNMENT((#202554)); -#202554 = SURFACE_STYLE_USAGE(.BOTH.,#202555); -#202555 = SURFACE_SIDE_STYLE('',(#202556)); -#202556 = SURFACE_STYLE_FILL_AREA(#202557); -#202557 = FILL_AREA_STYLE('',(#202558)); -#202558 = FILL_AREA_STYLE_COLOUR('',#201028); -#202559 = OVER_RIDING_STYLED_ITEM('overriding color',(#202560),#180042, - #201766); -#202560 = PRESENTATION_STYLE_ASSIGNMENT((#202561)); -#202561 = SURFACE_STYLE_USAGE(.BOTH.,#202562); -#202562 = SURFACE_SIDE_STYLE('',(#202563)); -#202563 = SURFACE_STYLE_FILL_AREA(#202564); -#202564 = FILL_AREA_STYLE('',(#202565)); -#202565 = FILL_AREA_STYLE_COLOUR('',#201028); -#202566 = OVER_RIDING_STYLED_ITEM('overriding color',(#202567),#180090, - #201766); -#202567 = PRESENTATION_STYLE_ASSIGNMENT((#202568)); -#202568 = SURFACE_STYLE_USAGE(.BOTH.,#202569); -#202569 = SURFACE_SIDE_STYLE('',(#202570)); -#202570 = SURFACE_STYLE_FILL_AREA(#202571); -#202571 = FILL_AREA_STYLE('',(#202572)); -#202572 = FILL_AREA_STYLE_COLOUR('',#201028); -#202573 = OVER_RIDING_STYLED_ITEM('overriding color',(#202574),#180309, - #201766); -#202574 = PRESENTATION_STYLE_ASSIGNMENT((#202575)); -#202575 = SURFACE_STYLE_USAGE(.BOTH.,#202576); -#202576 = SURFACE_SIDE_STYLE('',(#202577)); -#202577 = SURFACE_STYLE_FILL_AREA(#202578); -#202578 = FILL_AREA_STYLE('',(#202579)); -#202579 = FILL_AREA_STYLE_COLOUR('',#201028); -#202580 = OVER_RIDING_STYLED_ITEM('overriding color',(#202581),#180335, - #201766); -#202581 = PRESENTATION_STYLE_ASSIGNMENT((#202582)); -#202582 = SURFACE_STYLE_USAGE(.BOTH.,#202583); -#202583 = SURFACE_SIDE_STYLE('',(#202584)); -#202584 = SURFACE_STYLE_FILL_AREA(#202585); -#202585 = FILL_AREA_STYLE('',(#202586)); -#202586 = FILL_AREA_STYLE_COLOUR('',#201028); -#202587 = OVER_RIDING_STYLED_ITEM('overriding color',(#202588),#180361, - #201766); -#202588 = PRESENTATION_STYLE_ASSIGNMENT((#202589)); -#202589 = SURFACE_STYLE_USAGE(.BOTH.,#202590); -#202590 = SURFACE_SIDE_STYLE('',(#202591)); -#202591 = SURFACE_STYLE_FILL_AREA(#202592); -#202592 = FILL_AREA_STYLE('',(#202593)); -#202593 = FILL_AREA_STYLE_COLOUR('',#201028); -#202594 = OVER_RIDING_STYLED_ITEM('overriding color',(#202595),#180410, - #201766); -#202595 = PRESENTATION_STYLE_ASSIGNMENT((#202596)); -#202596 = SURFACE_STYLE_USAGE(.BOTH.,#202597); -#202597 = SURFACE_SIDE_STYLE('',(#202598)); -#202598 = SURFACE_STYLE_FILL_AREA(#202599); -#202599 = FILL_AREA_STYLE('',(#202600)); -#202600 = FILL_AREA_STYLE_COLOUR('',#201028); -#202601 = OVER_RIDING_STYLED_ITEM('overriding color',(#202602),#180437, - #201766); -#202602 = PRESENTATION_STYLE_ASSIGNMENT((#202603)); -#202603 = SURFACE_STYLE_USAGE(.BOTH.,#202604); -#202604 = SURFACE_SIDE_STYLE('',(#202605)); -#202605 = SURFACE_STYLE_FILL_AREA(#202606); -#202606 = FILL_AREA_STYLE('',(#202607)); -#202607 = FILL_AREA_STYLE_COLOUR('',#201028); -#202608 = OVER_RIDING_STYLED_ITEM('overriding color',(#202609),#180464, - #201766); -#202609 = PRESENTATION_STYLE_ASSIGNMENT((#202610)); -#202610 = SURFACE_STYLE_USAGE(.BOTH.,#202611); -#202611 = SURFACE_SIDE_STYLE('',(#202612)); -#202612 = SURFACE_STYLE_FILL_AREA(#202613); -#202613 = FILL_AREA_STYLE('',(#202614)); -#202614 = FILL_AREA_STYLE_COLOUR('',#201028); -#202615 = OVER_RIDING_STYLED_ITEM('overriding color',(#202616),#180513, - #201766); -#202616 = PRESENTATION_STYLE_ASSIGNMENT((#202617)); -#202617 = SURFACE_STYLE_USAGE(.BOTH.,#202618); -#202618 = SURFACE_SIDE_STYLE('',(#202619)); -#202619 = SURFACE_STYLE_FILL_AREA(#202620); -#202620 = FILL_AREA_STYLE('',(#202621)); -#202621 = FILL_AREA_STYLE_COLOUR('',#201028); -#202622 = OVER_RIDING_STYLED_ITEM('overriding color',(#202623),#180539, - #201766); -#202623 = PRESENTATION_STYLE_ASSIGNMENT((#202624)); -#202624 = SURFACE_STYLE_USAGE(.BOTH.,#202625); -#202625 = SURFACE_SIDE_STYLE('',(#202626)); -#202626 = SURFACE_STYLE_FILL_AREA(#202627); -#202627 = FILL_AREA_STYLE('',(#202628)); -#202628 = FILL_AREA_STYLE_COLOUR('',#201028); -#202629 = OVER_RIDING_STYLED_ITEM('overriding color',(#202630),#180565, - #201766); -#202630 = PRESENTATION_STYLE_ASSIGNMENT((#202631)); -#202631 = SURFACE_STYLE_USAGE(.BOTH.,#202632); -#202632 = SURFACE_SIDE_STYLE('',(#202633)); -#202633 = SURFACE_STYLE_FILL_AREA(#202634); -#202634 = FILL_AREA_STYLE('',(#202635)); -#202635 = FILL_AREA_STYLE_COLOUR('',#201028); -#202636 = OVER_RIDING_STYLED_ITEM('overriding color',(#202637),#180572, - #201766); -#202637 = PRESENTATION_STYLE_ASSIGNMENT((#202638)); -#202638 = SURFACE_STYLE_USAGE(.BOTH.,#202639); -#202639 = SURFACE_SIDE_STYLE('',(#202640)); -#202640 = SURFACE_STYLE_FILL_AREA(#202641); -#202641 = FILL_AREA_STYLE('',(#202642)); -#202642 = FILL_AREA_STYLE_COLOUR('',#201028); -#202643 = OVER_RIDING_STYLED_ITEM('overriding color',(#202644),#180647, - #201766); -#202644 = PRESENTATION_STYLE_ASSIGNMENT((#202645)); -#202645 = SURFACE_STYLE_USAGE(.BOTH.,#202646); -#202646 = SURFACE_SIDE_STYLE('',(#202647)); -#202647 = SURFACE_STYLE_FILL_AREA(#202648); -#202648 = FILL_AREA_STYLE('',(#202649)); -#202649 = FILL_AREA_STYLE_COLOUR('',#201028); -#202650 = OVER_RIDING_STYLED_ITEM('overriding color',(#202651),#180928, - #201766); -#202651 = PRESENTATION_STYLE_ASSIGNMENT((#202652)); -#202652 = SURFACE_STYLE_USAGE(.BOTH.,#202653); -#202653 = SURFACE_SIDE_STYLE('',(#202654)); -#202654 = SURFACE_STYLE_FILL_AREA(#202655); -#202655 = FILL_AREA_STYLE('',(#202656)); -#202656 = FILL_AREA_STYLE_COLOUR('',#201028); -#202657 = OVER_RIDING_STYLED_ITEM('overriding color',(#202658),#180976, - #201766); -#202658 = PRESENTATION_STYLE_ASSIGNMENT((#202659)); -#202659 = SURFACE_STYLE_USAGE(.BOTH.,#202660); -#202660 = SURFACE_SIDE_STYLE('',(#202661)); -#202661 = SURFACE_STYLE_FILL_AREA(#202662); -#202662 = FILL_AREA_STYLE('',(#202663)); -#202663 = FILL_AREA_STYLE_COLOUR('',#201028); -#202664 = OVER_RIDING_STYLED_ITEM('overriding color',(#202665),#181195, - #201766); -#202665 = PRESENTATION_STYLE_ASSIGNMENT((#202666)); -#202666 = SURFACE_STYLE_USAGE(.BOTH.,#202667); -#202667 = SURFACE_SIDE_STYLE('',(#202668)); -#202668 = SURFACE_STYLE_FILL_AREA(#202669); -#202669 = FILL_AREA_STYLE('',(#202670)); -#202670 = FILL_AREA_STYLE_COLOUR('',#201028); -#202671 = OVER_RIDING_STYLED_ITEM('overriding color',(#202672),#181221, - #201766); -#202672 = PRESENTATION_STYLE_ASSIGNMENT((#202673)); -#202673 = SURFACE_STYLE_USAGE(.BOTH.,#202674); -#202674 = SURFACE_SIDE_STYLE('',(#202675)); -#202675 = SURFACE_STYLE_FILL_AREA(#202676); -#202676 = FILL_AREA_STYLE('',(#202677)); -#202677 = FILL_AREA_STYLE_COLOUR('',#201028); -#202678 = OVER_RIDING_STYLED_ITEM('overriding color',(#202679),#181247, - #201766); -#202679 = PRESENTATION_STYLE_ASSIGNMENT((#202680)); -#202680 = SURFACE_STYLE_USAGE(.BOTH.,#202681); -#202681 = SURFACE_SIDE_STYLE('',(#202682)); -#202682 = SURFACE_STYLE_FILL_AREA(#202683); -#202683 = FILL_AREA_STYLE('',(#202684)); -#202684 = FILL_AREA_STYLE_COLOUR('',#201028); -#202685 = OVER_RIDING_STYLED_ITEM('overriding color',(#202686),#181296, - #201766); -#202686 = PRESENTATION_STYLE_ASSIGNMENT((#202687)); -#202687 = SURFACE_STYLE_USAGE(.BOTH.,#202688); -#202688 = SURFACE_SIDE_STYLE('',(#202689)); -#202689 = SURFACE_STYLE_FILL_AREA(#202690); -#202690 = FILL_AREA_STYLE('',(#202691)); -#202691 = FILL_AREA_STYLE_COLOUR('',#201028); -#202692 = OVER_RIDING_STYLED_ITEM('overriding color',(#202693),#181323, - #201766); -#202693 = PRESENTATION_STYLE_ASSIGNMENT((#202694)); -#202694 = SURFACE_STYLE_USAGE(.BOTH.,#202695); -#202695 = SURFACE_SIDE_STYLE('',(#202696)); -#202696 = SURFACE_STYLE_FILL_AREA(#202697); -#202697 = FILL_AREA_STYLE('',(#202698)); -#202698 = FILL_AREA_STYLE_COLOUR('',#201028); -#202699 = OVER_RIDING_STYLED_ITEM('overriding color',(#202700),#181350, - #201766); -#202700 = PRESENTATION_STYLE_ASSIGNMENT((#202701)); -#202701 = SURFACE_STYLE_USAGE(.BOTH.,#202702); -#202702 = SURFACE_SIDE_STYLE('',(#202703)); -#202703 = SURFACE_STYLE_FILL_AREA(#202704); -#202704 = FILL_AREA_STYLE('',(#202705)); -#202705 = FILL_AREA_STYLE_COLOUR('',#201028); -#202706 = OVER_RIDING_STYLED_ITEM('overriding color',(#202707),#181399, - #201766); -#202707 = PRESENTATION_STYLE_ASSIGNMENT((#202708)); -#202708 = SURFACE_STYLE_USAGE(.BOTH.,#202709); -#202709 = SURFACE_SIDE_STYLE('',(#202710)); -#202710 = SURFACE_STYLE_FILL_AREA(#202711); -#202711 = FILL_AREA_STYLE('',(#202712)); -#202712 = FILL_AREA_STYLE_COLOUR('',#201028); -#202713 = OVER_RIDING_STYLED_ITEM('overriding color',(#202714),#181425, - #201766); -#202714 = PRESENTATION_STYLE_ASSIGNMENT((#202715)); -#202715 = SURFACE_STYLE_USAGE(.BOTH.,#202716); -#202716 = SURFACE_SIDE_STYLE('',(#202717)); -#202717 = SURFACE_STYLE_FILL_AREA(#202718); -#202718 = FILL_AREA_STYLE('',(#202719)); -#202719 = FILL_AREA_STYLE_COLOUR('',#201028); -#202720 = OVER_RIDING_STYLED_ITEM('overriding color',(#202721),#181451, - #201766); -#202721 = PRESENTATION_STYLE_ASSIGNMENT((#202722)); -#202722 = SURFACE_STYLE_USAGE(.BOTH.,#202723); -#202723 = SURFACE_SIDE_STYLE('',(#202724)); -#202724 = SURFACE_STYLE_FILL_AREA(#202725); -#202725 = FILL_AREA_STYLE('',(#202726)); -#202726 = FILL_AREA_STYLE_COLOUR('',#201028); -#202727 = OVER_RIDING_STYLED_ITEM('overriding color',(#202728),#181458, - #201766); -#202728 = PRESENTATION_STYLE_ASSIGNMENT((#202729)); -#202729 = SURFACE_STYLE_USAGE(.BOTH.,#202730); -#202730 = SURFACE_SIDE_STYLE('',(#202731)); -#202731 = SURFACE_STYLE_FILL_AREA(#202732); -#202732 = FILL_AREA_STYLE('',(#202733)); -#202733 = FILL_AREA_STYLE_COLOUR('',#201028); -#202734 = OVER_RIDING_STYLED_ITEM('overriding color',(#202735),#181533, - #201766); -#202735 = PRESENTATION_STYLE_ASSIGNMENT((#202736)); -#202736 = SURFACE_STYLE_USAGE(.BOTH.,#202737); -#202737 = SURFACE_SIDE_STYLE('',(#202738)); -#202738 = SURFACE_STYLE_FILL_AREA(#202739); -#202739 = FILL_AREA_STYLE('',(#202740)); -#202740 = FILL_AREA_STYLE_COLOUR('',#201028); -#202741 = OVER_RIDING_STYLED_ITEM('overriding color',(#202742),#181814, - #201766); -#202742 = PRESENTATION_STYLE_ASSIGNMENT((#202743)); -#202743 = SURFACE_STYLE_USAGE(.BOTH.,#202744); -#202744 = SURFACE_SIDE_STYLE('',(#202745)); -#202745 = SURFACE_STYLE_FILL_AREA(#202746); -#202746 = FILL_AREA_STYLE('',(#202747)); -#202747 = FILL_AREA_STYLE_COLOUR('',#201028); -#202748 = OVER_RIDING_STYLED_ITEM('overriding color',(#202749),#181862, - #201766); -#202749 = PRESENTATION_STYLE_ASSIGNMENT((#202750)); -#202750 = SURFACE_STYLE_USAGE(.BOTH.,#202751); -#202751 = SURFACE_SIDE_STYLE('',(#202752)); -#202752 = SURFACE_STYLE_FILL_AREA(#202753); -#202753 = FILL_AREA_STYLE('',(#202754)); -#202754 = FILL_AREA_STYLE_COLOUR('',#201028); -#202755 = OVER_RIDING_STYLED_ITEM('overriding color',(#202756),#182081, - #201766); -#202756 = PRESENTATION_STYLE_ASSIGNMENT((#202757)); -#202757 = SURFACE_STYLE_USAGE(.BOTH.,#202758); -#202758 = SURFACE_SIDE_STYLE('',(#202759)); -#202759 = SURFACE_STYLE_FILL_AREA(#202760); -#202760 = FILL_AREA_STYLE('',(#202761)); -#202761 = FILL_AREA_STYLE_COLOUR('',#201028); -#202762 = OVER_RIDING_STYLED_ITEM('overriding color',(#202763),#182107, - #201766); -#202763 = PRESENTATION_STYLE_ASSIGNMENT((#202764)); -#202764 = SURFACE_STYLE_USAGE(.BOTH.,#202765); -#202765 = SURFACE_SIDE_STYLE('',(#202766)); -#202766 = SURFACE_STYLE_FILL_AREA(#202767); -#202767 = FILL_AREA_STYLE('',(#202768)); -#202768 = FILL_AREA_STYLE_COLOUR('',#201028); -#202769 = OVER_RIDING_STYLED_ITEM('overriding color',(#202770),#182133, - #201766); -#202770 = PRESENTATION_STYLE_ASSIGNMENT((#202771)); -#202771 = SURFACE_STYLE_USAGE(.BOTH.,#202772); -#202772 = SURFACE_SIDE_STYLE('',(#202773)); -#202773 = SURFACE_STYLE_FILL_AREA(#202774); -#202774 = FILL_AREA_STYLE('',(#202775)); -#202775 = FILL_AREA_STYLE_COLOUR('',#201028); -#202776 = OVER_RIDING_STYLED_ITEM('overriding color',(#202777),#182182, - #201766); -#202777 = PRESENTATION_STYLE_ASSIGNMENT((#202778)); -#202778 = SURFACE_STYLE_USAGE(.BOTH.,#202779); -#202779 = SURFACE_SIDE_STYLE('',(#202780)); -#202780 = SURFACE_STYLE_FILL_AREA(#202781); -#202781 = FILL_AREA_STYLE('',(#202782)); -#202782 = FILL_AREA_STYLE_COLOUR('',#201028); -#202783 = OVER_RIDING_STYLED_ITEM('overriding color',(#202784),#182209, - #201766); -#202784 = PRESENTATION_STYLE_ASSIGNMENT((#202785)); -#202785 = SURFACE_STYLE_USAGE(.BOTH.,#202786); -#202786 = SURFACE_SIDE_STYLE('',(#202787)); -#202787 = SURFACE_STYLE_FILL_AREA(#202788); -#202788 = FILL_AREA_STYLE('',(#202789)); -#202789 = FILL_AREA_STYLE_COLOUR('',#201028); -#202790 = OVER_RIDING_STYLED_ITEM('overriding color',(#202791),#182236, - #201766); -#202791 = PRESENTATION_STYLE_ASSIGNMENT((#202792)); -#202792 = SURFACE_STYLE_USAGE(.BOTH.,#202793); -#202793 = SURFACE_SIDE_STYLE('',(#202794)); -#202794 = SURFACE_STYLE_FILL_AREA(#202795); -#202795 = FILL_AREA_STYLE('',(#202796)); -#202796 = FILL_AREA_STYLE_COLOUR('',#201028); -#202797 = OVER_RIDING_STYLED_ITEM('overriding color',(#202798),#182285, - #201766); -#202798 = PRESENTATION_STYLE_ASSIGNMENT((#202799)); -#202799 = SURFACE_STYLE_USAGE(.BOTH.,#202800); -#202800 = SURFACE_SIDE_STYLE('',(#202801)); -#202801 = SURFACE_STYLE_FILL_AREA(#202802); -#202802 = FILL_AREA_STYLE('',(#202803)); -#202803 = FILL_AREA_STYLE_COLOUR('',#201028); -#202804 = OVER_RIDING_STYLED_ITEM('overriding color',(#202805),#182311, - #201766); -#202805 = PRESENTATION_STYLE_ASSIGNMENT((#202806)); -#202806 = SURFACE_STYLE_USAGE(.BOTH.,#202807); -#202807 = SURFACE_SIDE_STYLE('',(#202808)); -#202808 = SURFACE_STYLE_FILL_AREA(#202809); -#202809 = FILL_AREA_STYLE('',(#202810)); -#202810 = FILL_AREA_STYLE_COLOUR('',#201028); -#202811 = OVER_RIDING_STYLED_ITEM('overriding color',(#202812),#182337, - #201766); -#202812 = PRESENTATION_STYLE_ASSIGNMENT((#202813)); -#202813 = SURFACE_STYLE_USAGE(.BOTH.,#202814); -#202814 = SURFACE_SIDE_STYLE('',(#202815)); -#202815 = SURFACE_STYLE_FILL_AREA(#202816); -#202816 = FILL_AREA_STYLE('',(#202817)); -#202817 = FILL_AREA_STYLE_COLOUR('',#201028); -#202818 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #202819),#11822); -#202819 = STYLED_ITEM('color',(#202820),#11492); -#202820 = PRESENTATION_STYLE_ASSIGNMENT((#202821,#202827)); -#202821 = SURFACE_STYLE_USAGE(.BOTH.,#202822); -#202822 = SURFACE_SIDE_STYLE('',(#202823)); -#202823 = SURFACE_STYLE_FILL_AREA(#202824); -#202824 = FILL_AREA_STYLE('',(#202825)); -#202825 = FILL_AREA_STYLE_COLOUR('',#202826); -#202826 = COLOUR_RGB('',0.113725490868,0.113725490868,0.113725490868); -#202827 = CURVE_STYLE('',#202828,POSITIVE_LENGTH_MEASURE(0.1),#202826); -#202828 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#202829 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #202830,#202838,#202845,#202852,#202859,#202866,#202873,#202880, - #202887,#202894,#202901),#167923); -#202830 = STYLED_ITEM('color',(#202831),#167281); -#202831 = PRESENTATION_STYLE_ASSIGNMENT((#202832)); -#202832 = SURFACE_STYLE_USAGE(.BOTH.,#202833); -#202833 = SURFACE_SIDE_STYLE('',(#202834)); -#202834 = SURFACE_STYLE_FILL_AREA(#202835); -#202835 = FILL_AREA_STYLE('',(#202836)); -#202836 = FILL_AREA_STYLE_COLOUR('',#202837); -#202837 = COLOUR_RGB('',0.705882370472,0.705882370472,0.705882370472); -#202838 = OVER_RIDING_STYLED_ITEM('overriding color',(#202839),#167283, - #202830); -#202839 = PRESENTATION_STYLE_ASSIGNMENT((#202840)); -#202840 = SURFACE_STYLE_USAGE(.BOTH.,#202841); -#202841 = SURFACE_SIDE_STYLE('',(#202842)); -#202842 = SURFACE_STYLE_FILL_AREA(#202843); -#202843 = FILL_AREA_STYLE('',(#202844)); -#202844 = FILL_AREA_STYLE_COLOUR('',#202837); -#202845 = OVER_RIDING_STYLED_ITEM('overriding color',(#202846),#167403, - #202830); -#202846 = PRESENTATION_STYLE_ASSIGNMENT((#202847)); -#202847 = SURFACE_STYLE_USAGE(.BOTH.,#202848); -#202848 = SURFACE_SIDE_STYLE('',(#202849)); -#202849 = SURFACE_STYLE_FILL_AREA(#202850); -#202850 = FILL_AREA_STYLE('',(#202851)); -#202851 = FILL_AREA_STYLE_COLOUR('',#202837); -#202852 = OVER_RIDING_STYLED_ITEM('overriding color',(#202853),#167479, - #202830); -#202853 = PRESENTATION_STYLE_ASSIGNMENT((#202854)); -#202854 = SURFACE_STYLE_USAGE(.BOTH.,#202855); -#202855 = SURFACE_SIDE_STYLE('',(#202856)); -#202856 = SURFACE_STYLE_FILL_AREA(#202857); -#202857 = FILL_AREA_STYLE('',(#202858)); -#202858 = FILL_AREA_STYLE_COLOUR('',#202837); -#202859 = OVER_RIDING_STYLED_ITEM('overriding color',(#202860),#167555, - #202830); -#202860 = PRESENTATION_STYLE_ASSIGNMENT((#202861)); -#202861 = SURFACE_STYLE_USAGE(.BOTH.,#202862); -#202862 = SURFACE_SIDE_STYLE('',(#202863)); -#202863 = SURFACE_STYLE_FILL_AREA(#202864); -#202864 = FILL_AREA_STYLE('',(#202865)); -#202865 = FILL_AREA_STYLE_COLOUR('',#202837); -#202866 = OVER_RIDING_STYLED_ITEM('overriding color',(#202867),#167631, - #202830); -#202867 = PRESENTATION_STYLE_ASSIGNMENT((#202868)); -#202868 = SURFACE_STYLE_USAGE(.BOTH.,#202869); -#202869 = SURFACE_SIDE_STYLE('',(#202870)); -#202870 = SURFACE_STYLE_FILL_AREA(#202871); -#202871 = FILL_AREA_STYLE('',(#202872)); -#202872 = FILL_AREA_STYLE_COLOUR('',#202837); -#202873 = OVER_RIDING_STYLED_ITEM('overriding color',(#202874),#167707, - #202830); -#202874 = PRESENTATION_STYLE_ASSIGNMENT((#202875)); -#202875 = SURFACE_STYLE_USAGE(.BOTH.,#202876); -#202876 = SURFACE_SIDE_STYLE('',(#202877)); -#202877 = SURFACE_STYLE_FILL_AREA(#202878); -#202878 = FILL_AREA_STYLE('',(#202879)); -#202879 = FILL_AREA_STYLE_COLOUR('',#202837); -#202880 = OVER_RIDING_STYLED_ITEM('overriding color',(#202881),#167787, - #202830); -#202881 = PRESENTATION_STYLE_ASSIGNMENT((#202882)); -#202882 = SURFACE_STYLE_USAGE(.BOTH.,#202883); -#202883 = SURFACE_SIDE_STYLE('',(#202884)); -#202884 = SURFACE_STYLE_FILL_AREA(#202885); -#202885 = FILL_AREA_STYLE('',(#202886)); -#202886 = FILL_AREA_STYLE_COLOUR('',#202837); -#202887 = OVER_RIDING_STYLED_ITEM('overriding color',(#202888),#167836, - #202830); -#202888 = PRESENTATION_STYLE_ASSIGNMENT((#202889)); -#202889 = SURFACE_STYLE_USAGE(.BOTH.,#202890); -#202890 = SURFACE_SIDE_STYLE('',(#202891)); -#202891 = SURFACE_STYLE_FILL_AREA(#202892); -#202892 = FILL_AREA_STYLE('',(#202893)); -#202893 = FILL_AREA_STYLE_COLOUR('',#202837); -#202894 = OVER_RIDING_STYLED_ITEM('overriding color',(#202895),#167889, - #202830); -#202895 = PRESENTATION_STYLE_ASSIGNMENT((#202896)); -#202896 = SURFACE_STYLE_USAGE(.BOTH.,#202897); -#202897 = SURFACE_SIDE_STYLE('',(#202898)); -#202898 = SURFACE_STYLE_FILL_AREA(#202899); -#202899 = FILL_AREA_STYLE('',(#202900)); -#202900 = FILL_AREA_STYLE_COLOUR('',#202837); -#202901 = OVER_RIDING_STYLED_ITEM('overriding color',(#202902),#167916, - #202830); -#202902 = PRESENTATION_STYLE_ASSIGNMENT((#202903)); -#202903 = SURFACE_STYLE_USAGE(.BOTH.,#202904); -#202904 = SURFACE_SIDE_STYLE('',(#202905)); -#202905 = SURFACE_STYLE_FILL_AREA(#202906); -#202906 = FILL_AREA_STYLE('',(#202907)); -#202907 = FILL_AREA_STYLE_COLOUR('',#202837); -#202908 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #202909),#166973); -#202909 = STYLED_ITEM('color',(#202910),#166643); -#202910 = PRESENTATION_STYLE_ASSIGNMENT((#202911,#202917)); -#202911 = SURFACE_STYLE_USAGE(.BOTH.,#202912); -#202912 = SURFACE_SIDE_STYLE('',(#202913)); -#202913 = SURFACE_STYLE_FILL_AREA(#202914); -#202914 = FILL_AREA_STYLE('',(#202915)); -#202915 = FILL_AREA_STYLE_COLOUR('',#202916); -#202916 = COLOUR_RGB('',0.86274510622,0.850980401039,0.780392169952); -#202917 = CURVE_STYLE('',#202918,POSITIVE_LENGTH_MEASURE(0.1),#202916); -#202918 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#202919 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #202920,#202927,#202934,#202941,#202948,#202955,#202962,#202969, - #202976,#202983,#202990),#168584); -#202920 = STYLED_ITEM('color',(#202921),#167942); +#201120 = FILL_AREA_STYLE_COLOUR('',#198418); +#201121 = OVER_RIDING_STYLED_ITEM('overriding color',(#201122),#122751, + #198353); +#201122 = PRESENTATION_STYLE_ASSIGNMENT((#201123)); +#201123 = SURFACE_STYLE_USAGE(.BOTH.,#201124); +#201124 = SURFACE_SIDE_STYLE('',(#201125)); +#201125 = SURFACE_STYLE_FILL_AREA(#201126); +#201126 = FILL_AREA_STYLE('',(#201127)); +#201127 = FILL_AREA_STYLE_COLOUR('',#198418); +#201128 = OVER_RIDING_STYLED_ITEM('overriding color',(#201129),#122778, + #198353); +#201129 = PRESENTATION_STYLE_ASSIGNMENT((#201130)); +#201130 = SURFACE_STYLE_USAGE(.BOTH.,#201131); +#201131 = SURFACE_SIDE_STYLE('',(#201132)); +#201132 = SURFACE_STYLE_FILL_AREA(#201133); +#201133 = FILL_AREA_STYLE('',(#201134)); +#201134 = FILL_AREA_STYLE_COLOUR('',#198418); +#201135 = OVER_RIDING_STYLED_ITEM('overriding color',(#201136),#122813, + #198353); +#201136 = PRESENTATION_STYLE_ASSIGNMENT((#201137)); +#201137 = SURFACE_STYLE_USAGE(.BOTH.,#201138); +#201138 = SURFACE_SIDE_STYLE('',(#201139)); +#201139 = SURFACE_STYLE_FILL_AREA(#201140); +#201140 = FILL_AREA_STYLE('',(#201141)); +#201141 = FILL_AREA_STYLE_COLOUR('',#198418); +#201142 = OVER_RIDING_STYLED_ITEM('overriding color',(#201143),#122820, + #198353); +#201143 = PRESENTATION_STYLE_ASSIGNMENT((#201144)); +#201144 = SURFACE_STYLE_USAGE(.BOTH.,#201145); +#201145 = SURFACE_SIDE_STYLE('',(#201146)); +#201146 = SURFACE_STYLE_FILL_AREA(#201147); +#201147 = FILL_AREA_STYLE('',(#201148)); +#201148 = FILL_AREA_STYLE_COLOUR('',#198418); +#201149 = OVER_RIDING_STYLED_ITEM('overriding color',(#201150),#122929, + #198353); +#201150 = PRESENTATION_STYLE_ASSIGNMENT((#201151)); +#201151 = SURFACE_STYLE_USAGE(.BOTH.,#201152); +#201152 = SURFACE_SIDE_STYLE('',(#201153)); +#201153 = SURFACE_STYLE_FILL_AREA(#201154); +#201154 = FILL_AREA_STYLE('',(#201155)); +#201155 = FILL_AREA_STYLE_COLOUR('',#198418); +#201156 = OVER_RIDING_STYLED_ITEM('overriding color',(#201157),#123033, + #198353); +#201157 = PRESENTATION_STYLE_ASSIGNMENT((#201158)); +#201158 = SURFACE_STYLE_USAGE(.BOTH.,#201159); +#201159 = SURFACE_SIDE_STYLE('',(#201160)); +#201160 = SURFACE_STYLE_FILL_AREA(#201161); +#201161 = FILL_AREA_STYLE('',(#201162)); +#201162 = FILL_AREA_STYLE_COLOUR('',#198418); +#201163 = OVER_RIDING_STYLED_ITEM('overriding color',(#201164),#123112, + #198353); +#201164 = PRESENTATION_STYLE_ASSIGNMENT((#201165)); +#201165 = SURFACE_STYLE_USAGE(.BOTH.,#201166); +#201166 = SURFACE_SIDE_STYLE('',(#201167)); +#201167 = SURFACE_STYLE_FILL_AREA(#201168); +#201168 = FILL_AREA_STYLE('',(#201169)); +#201169 = FILL_AREA_STYLE_COLOUR('',#198418); +#201170 = OVER_RIDING_STYLED_ITEM('overriding color',(#201171),#123191, + #198353); +#201171 = PRESENTATION_STYLE_ASSIGNMENT((#201172)); +#201172 = SURFACE_STYLE_USAGE(.BOTH.,#201173); +#201173 = SURFACE_SIDE_STYLE('',(#201174)); +#201174 = SURFACE_STYLE_FILL_AREA(#201175); +#201175 = FILL_AREA_STYLE('',(#201176)); +#201176 = FILL_AREA_STYLE_COLOUR('',#198418); +#201177 = OVER_RIDING_STYLED_ITEM('overriding color',(#201178),#123266, + #198353); +#201178 = PRESENTATION_STYLE_ASSIGNMENT((#201179)); +#201179 = SURFACE_STYLE_USAGE(.BOTH.,#201180); +#201180 = SURFACE_SIDE_STYLE('',(#201181)); +#201181 = SURFACE_STYLE_FILL_AREA(#201182); +#201182 = FILL_AREA_STYLE('',(#201183)); +#201183 = FILL_AREA_STYLE_COLOUR('',#198418); +#201184 = OVER_RIDING_STYLED_ITEM('overriding color',(#201185),#123341, + #198353); +#201185 = PRESENTATION_STYLE_ASSIGNMENT((#201186)); +#201186 = SURFACE_STYLE_USAGE(.BOTH.,#201187); +#201187 = SURFACE_SIDE_STYLE('',(#201188)); +#201188 = SURFACE_STYLE_FILL_AREA(#201189); +#201189 = FILL_AREA_STYLE('',(#201190)); +#201190 = FILL_AREA_STYLE_COLOUR('',#198418); +#201191 = OVER_RIDING_STYLED_ITEM('overriding color',(#201192),#123438, + #198353); +#201192 = PRESENTATION_STYLE_ASSIGNMENT((#201193)); +#201193 = SURFACE_STYLE_USAGE(.BOTH.,#201194); +#201194 = SURFACE_SIDE_STYLE('',(#201195)); +#201195 = SURFACE_STYLE_FILL_AREA(#201196); +#201196 = FILL_AREA_STYLE('',(#201197)); +#201197 = FILL_AREA_STYLE_COLOUR('',#198418); +#201198 = OVER_RIDING_STYLED_ITEM('overriding color',(#201199),#123535, + #198353); +#201199 = PRESENTATION_STYLE_ASSIGNMENT((#201200)); +#201200 = SURFACE_STYLE_USAGE(.BOTH.,#201201); +#201201 = SURFACE_SIDE_STYLE('',(#201202)); +#201202 = SURFACE_STYLE_FILL_AREA(#201203); +#201203 = FILL_AREA_STYLE('',(#201204)); +#201204 = FILL_AREA_STYLE_COLOUR('',#198418); +#201205 = OVER_RIDING_STYLED_ITEM('overriding color',(#201206),#123582, + #198353); +#201206 = PRESENTATION_STYLE_ASSIGNMENT((#201207)); +#201207 = SURFACE_STYLE_USAGE(.BOTH.,#201208); +#201208 = SURFACE_SIDE_STYLE('',(#201209)); +#201209 = SURFACE_STYLE_FILL_AREA(#201210); +#201210 = FILL_AREA_STYLE('',(#201211)); +#201211 = FILL_AREA_STYLE_COLOUR('',#198418); +#201212 = OVER_RIDING_STYLED_ITEM('overriding color',(#201213),#123637, + #198353); +#201213 = PRESENTATION_STYLE_ASSIGNMENT((#201214)); +#201214 = SURFACE_STYLE_USAGE(.BOTH.,#201215); +#201215 = SURFACE_SIDE_STYLE('',(#201216)); +#201216 = SURFACE_STYLE_FILL_AREA(#201217); +#201217 = FILL_AREA_STYLE('',(#201218)); +#201218 = FILL_AREA_STYLE_COLOUR('',#198418); +#201219 = OVER_RIDING_STYLED_ITEM('overriding color',(#201220),#123664, + #198353); +#201220 = PRESENTATION_STYLE_ASSIGNMENT((#201221)); +#201221 = SURFACE_STYLE_USAGE(.BOTH.,#201222); +#201222 = SURFACE_SIDE_STYLE('',(#201223)); +#201223 = SURFACE_STYLE_FILL_AREA(#201224); +#201224 = FILL_AREA_STYLE('',(#201225)); +#201225 = FILL_AREA_STYLE_COLOUR('',#198418); +#201226 = OVER_RIDING_STYLED_ITEM('overriding color',(#201227),#123699, + #198353); +#201227 = PRESENTATION_STYLE_ASSIGNMENT((#201228)); +#201228 = SURFACE_STYLE_USAGE(.BOTH.,#201229); +#201229 = SURFACE_SIDE_STYLE('',(#201230)); +#201230 = SURFACE_STYLE_FILL_AREA(#201231); +#201231 = FILL_AREA_STYLE('',(#201232)); +#201232 = FILL_AREA_STYLE_COLOUR('',#198418); +#201233 = OVER_RIDING_STYLED_ITEM('overriding color',(#201234),#123706, + #198353); +#201234 = PRESENTATION_STYLE_ASSIGNMENT((#201235)); +#201235 = SURFACE_STYLE_USAGE(.BOTH.,#201236); +#201236 = SURFACE_SIDE_STYLE('',(#201237)); +#201237 = SURFACE_STYLE_FILL_AREA(#201238); +#201238 = FILL_AREA_STYLE('',(#201239)); +#201239 = FILL_AREA_STYLE_COLOUR('',#198418); +#201240 = OVER_RIDING_STYLED_ITEM('overriding color',(#201241),#123815, + #198353); +#201241 = PRESENTATION_STYLE_ASSIGNMENT((#201242)); +#201242 = SURFACE_STYLE_USAGE(.BOTH.,#201243); +#201243 = SURFACE_SIDE_STYLE('',(#201244)); +#201244 = SURFACE_STYLE_FILL_AREA(#201245); +#201245 = FILL_AREA_STYLE('',(#201246)); +#201246 = FILL_AREA_STYLE_COLOUR('',#198418); +#201247 = OVER_RIDING_STYLED_ITEM('overriding color',(#201248),#123919, + #198353); +#201248 = PRESENTATION_STYLE_ASSIGNMENT((#201249)); +#201249 = SURFACE_STYLE_USAGE(.BOTH.,#201250); +#201250 = SURFACE_SIDE_STYLE('',(#201251)); +#201251 = SURFACE_STYLE_FILL_AREA(#201252); +#201252 = FILL_AREA_STYLE('',(#201253)); +#201253 = FILL_AREA_STYLE_COLOUR('',#198418); +#201254 = OVER_RIDING_STYLED_ITEM('overriding color',(#201255),#123998, + #198353); +#201255 = PRESENTATION_STYLE_ASSIGNMENT((#201256)); +#201256 = SURFACE_STYLE_USAGE(.BOTH.,#201257); +#201257 = SURFACE_SIDE_STYLE('',(#201258)); +#201258 = SURFACE_STYLE_FILL_AREA(#201259); +#201259 = FILL_AREA_STYLE('',(#201260)); +#201260 = FILL_AREA_STYLE_COLOUR('',#198418); +#201261 = OVER_RIDING_STYLED_ITEM('overriding color',(#201262),#124077, + #198353); +#201262 = PRESENTATION_STYLE_ASSIGNMENT((#201263)); +#201263 = SURFACE_STYLE_USAGE(.BOTH.,#201264); +#201264 = SURFACE_SIDE_STYLE('',(#201265)); +#201265 = SURFACE_STYLE_FILL_AREA(#201266); +#201266 = FILL_AREA_STYLE('',(#201267)); +#201267 = FILL_AREA_STYLE_COLOUR('',#198418); +#201268 = OVER_RIDING_STYLED_ITEM('overriding color',(#201269),#124152, + #198353); +#201269 = PRESENTATION_STYLE_ASSIGNMENT((#201270)); +#201270 = SURFACE_STYLE_USAGE(.BOTH.,#201271); +#201271 = SURFACE_SIDE_STYLE('',(#201272)); +#201272 = SURFACE_STYLE_FILL_AREA(#201273); +#201273 = FILL_AREA_STYLE('',(#201274)); +#201274 = FILL_AREA_STYLE_COLOUR('',#198418); +#201275 = OVER_RIDING_STYLED_ITEM('overriding color',(#201276),#124227, + #198353); +#201276 = PRESENTATION_STYLE_ASSIGNMENT((#201277)); +#201277 = SURFACE_STYLE_USAGE(.BOTH.,#201278); +#201278 = SURFACE_SIDE_STYLE('',(#201279)); +#201279 = SURFACE_STYLE_FILL_AREA(#201280); +#201280 = FILL_AREA_STYLE('',(#201281)); +#201281 = FILL_AREA_STYLE_COLOUR('',#198418); +#201282 = OVER_RIDING_STYLED_ITEM('overriding color',(#201283),#124324, + #198353); +#201283 = PRESENTATION_STYLE_ASSIGNMENT((#201284)); +#201284 = SURFACE_STYLE_USAGE(.BOTH.,#201285); +#201285 = SURFACE_SIDE_STYLE('',(#201286)); +#201286 = SURFACE_STYLE_FILL_AREA(#201287); +#201287 = FILL_AREA_STYLE('',(#201288)); +#201288 = FILL_AREA_STYLE_COLOUR('',#198418); +#201289 = OVER_RIDING_STYLED_ITEM('overriding color',(#201290),#124421, + #198353); +#201290 = PRESENTATION_STYLE_ASSIGNMENT((#201291)); +#201291 = SURFACE_STYLE_USAGE(.BOTH.,#201292); +#201292 = SURFACE_SIDE_STYLE('',(#201293)); +#201293 = SURFACE_STYLE_FILL_AREA(#201294); +#201294 = FILL_AREA_STYLE('',(#201295)); +#201295 = FILL_AREA_STYLE_COLOUR('',#198418); +#201296 = OVER_RIDING_STYLED_ITEM('overriding color',(#201297),#124468, + #198353); +#201297 = PRESENTATION_STYLE_ASSIGNMENT((#201298)); +#201298 = SURFACE_STYLE_USAGE(.BOTH.,#201299); +#201299 = SURFACE_SIDE_STYLE('',(#201300)); +#201300 = SURFACE_STYLE_FILL_AREA(#201301); +#201301 = FILL_AREA_STYLE('',(#201302)); +#201302 = FILL_AREA_STYLE_COLOUR('',#198418); +#201303 = OVER_RIDING_STYLED_ITEM('overriding color',(#201304),#124523, + #198353); +#201304 = PRESENTATION_STYLE_ASSIGNMENT((#201305)); +#201305 = SURFACE_STYLE_USAGE(.BOTH.,#201306); +#201306 = SURFACE_SIDE_STYLE('',(#201307)); +#201307 = SURFACE_STYLE_FILL_AREA(#201308); +#201308 = FILL_AREA_STYLE('',(#201309)); +#201309 = FILL_AREA_STYLE_COLOUR('',#198418); +#201310 = OVER_RIDING_STYLED_ITEM('overriding color',(#201311),#124550, + #198353); +#201311 = PRESENTATION_STYLE_ASSIGNMENT((#201312)); +#201312 = SURFACE_STYLE_USAGE(.BOTH.,#201313); +#201313 = SURFACE_SIDE_STYLE('',(#201314)); +#201314 = SURFACE_STYLE_FILL_AREA(#201315); +#201315 = FILL_AREA_STYLE('',(#201316)); +#201316 = FILL_AREA_STYLE_COLOUR('',#198418); +#201317 = OVER_RIDING_STYLED_ITEM('overriding color',(#201318),#124585, + #198353); +#201318 = PRESENTATION_STYLE_ASSIGNMENT((#201319)); +#201319 = SURFACE_STYLE_USAGE(.BOTH.,#201320); +#201320 = SURFACE_SIDE_STYLE('',(#201321)); +#201321 = SURFACE_STYLE_FILL_AREA(#201322); +#201322 = FILL_AREA_STYLE('',(#201323)); +#201323 = FILL_AREA_STYLE_COLOUR('',#198418); +#201324 = OVER_RIDING_STYLED_ITEM('overriding color',(#201325),#124592, + #198353); +#201325 = PRESENTATION_STYLE_ASSIGNMENT((#201326)); +#201326 = SURFACE_STYLE_USAGE(.BOTH.,#201327); +#201327 = SURFACE_SIDE_STYLE('',(#201328)); +#201328 = SURFACE_STYLE_FILL_AREA(#201329); +#201329 = FILL_AREA_STYLE('',(#201330)); +#201330 = FILL_AREA_STYLE_COLOUR('',#198418); +#201331 = OVER_RIDING_STYLED_ITEM('overriding color',(#201332),#124701, + #198353); +#201332 = PRESENTATION_STYLE_ASSIGNMENT((#201333)); +#201333 = SURFACE_STYLE_USAGE(.BOTH.,#201334); +#201334 = SURFACE_SIDE_STYLE('',(#201335)); +#201335 = SURFACE_STYLE_FILL_AREA(#201336); +#201336 = FILL_AREA_STYLE('',(#201337)); +#201337 = FILL_AREA_STYLE_COLOUR('',#198418); +#201338 = OVER_RIDING_STYLED_ITEM('overriding color',(#201339),#124805, + #198353); +#201339 = PRESENTATION_STYLE_ASSIGNMENT((#201340)); +#201340 = SURFACE_STYLE_USAGE(.BOTH.,#201341); +#201341 = SURFACE_SIDE_STYLE('',(#201342)); +#201342 = SURFACE_STYLE_FILL_AREA(#201343); +#201343 = FILL_AREA_STYLE('',(#201344)); +#201344 = FILL_AREA_STYLE_COLOUR('',#198418); +#201345 = OVER_RIDING_STYLED_ITEM('overriding color',(#201346),#124884, + #198353); +#201346 = PRESENTATION_STYLE_ASSIGNMENT((#201347)); +#201347 = SURFACE_STYLE_USAGE(.BOTH.,#201348); +#201348 = SURFACE_SIDE_STYLE('',(#201349)); +#201349 = SURFACE_STYLE_FILL_AREA(#201350); +#201350 = FILL_AREA_STYLE('',(#201351)); +#201351 = FILL_AREA_STYLE_COLOUR('',#198418); +#201352 = OVER_RIDING_STYLED_ITEM('overriding color',(#201353),#124963, + #198353); +#201353 = PRESENTATION_STYLE_ASSIGNMENT((#201354)); +#201354 = SURFACE_STYLE_USAGE(.BOTH.,#201355); +#201355 = SURFACE_SIDE_STYLE('',(#201356)); +#201356 = SURFACE_STYLE_FILL_AREA(#201357); +#201357 = FILL_AREA_STYLE('',(#201358)); +#201358 = FILL_AREA_STYLE_COLOUR('',#198418); +#201359 = OVER_RIDING_STYLED_ITEM('overriding color',(#201360),#125038, + #198353); +#201360 = PRESENTATION_STYLE_ASSIGNMENT((#201361)); +#201361 = SURFACE_STYLE_USAGE(.BOTH.,#201362); +#201362 = SURFACE_SIDE_STYLE('',(#201363)); +#201363 = SURFACE_STYLE_FILL_AREA(#201364); +#201364 = FILL_AREA_STYLE('',(#201365)); +#201365 = FILL_AREA_STYLE_COLOUR('',#198418); +#201366 = OVER_RIDING_STYLED_ITEM('overriding color',(#201367),#125113, + #198353); +#201367 = PRESENTATION_STYLE_ASSIGNMENT((#201368)); +#201368 = SURFACE_STYLE_USAGE(.BOTH.,#201369); +#201369 = SURFACE_SIDE_STYLE('',(#201370)); +#201370 = SURFACE_STYLE_FILL_AREA(#201371); +#201371 = FILL_AREA_STYLE('',(#201372)); +#201372 = FILL_AREA_STYLE_COLOUR('',#198418); +#201373 = OVER_RIDING_STYLED_ITEM('overriding color',(#201374),#125187, + #198353); +#201374 = PRESENTATION_STYLE_ASSIGNMENT((#201375)); +#201375 = SURFACE_STYLE_USAGE(.BOTH.,#201376); +#201376 = SURFACE_SIDE_STYLE('',(#201377)); +#201377 = SURFACE_STYLE_FILL_AREA(#201378); +#201378 = FILL_AREA_STYLE('',(#201379)); +#201379 = FILL_AREA_STYLE_COLOUR('',#198418); +#201380 = OVER_RIDING_STYLED_ITEM('overriding color',(#201381),#125261, + #198353); +#201381 = PRESENTATION_STYLE_ASSIGNMENT((#201382)); +#201382 = SURFACE_STYLE_USAGE(.BOTH.,#201383); +#201383 = SURFACE_SIDE_STYLE('',(#201384)); +#201384 = SURFACE_STYLE_FILL_AREA(#201385); +#201385 = FILL_AREA_STYLE('',(#201386)); +#201386 = FILL_AREA_STYLE_COLOUR('',#198418); +#201387 = OVER_RIDING_STYLED_ITEM('overriding color',(#201388),#125308, + #198353); +#201388 = PRESENTATION_STYLE_ASSIGNMENT((#201389)); +#201389 = SURFACE_STYLE_USAGE(.BOTH.,#201390); +#201390 = SURFACE_SIDE_STYLE('',(#201391)); +#201391 = SURFACE_STYLE_FILL_AREA(#201392); +#201392 = FILL_AREA_STYLE('',(#201393)); +#201393 = FILL_AREA_STYLE_COLOUR('',#198418); +#201394 = OVER_RIDING_STYLED_ITEM('overriding color',(#201395),#125363, + #198353); +#201395 = PRESENTATION_STYLE_ASSIGNMENT((#201396)); +#201396 = SURFACE_STYLE_USAGE(.BOTH.,#201397); +#201397 = SURFACE_SIDE_STYLE('',(#201398)); +#201398 = SURFACE_STYLE_FILL_AREA(#201399); +#201399 = FILL_AREA_STYLE('',(#201400)); +#201400 = FILL_AREA_STYLE_COLOUR('',#198418); +#201401 = OVER_RIDING_STYLED_ITEM('overriding color',(#201402),#125390, + #198353); +#201402 = PRESENTATION_STYLE_ASSIGNMENT((#201403)); +#201403 = SURFACE_STYLE_USAGE(.BOTH.,#201404); +#201404 = SURFACE_SIDE_STYLE('',(#201405)); +#201405 = SURFACE_STYLE_FILL_AREA(#201406); +#201406 = FILL_AREA_STYLE('',(#201407)); +#201407 = FILL_AREA_STYLE_COLOUR('',#198418); +#201408 = OVER_RIDING_STYLED_ITEM('overriding color',(#201409),#125425, + #198353); +#201409 = PRESENTATION_STYLE_ASSIGNMENT((#201410)); +#201410 = SURFACE_STYLE_USAGE(.BOTH.,#201411); +#201411 = SURFACE_SIDE_STYLE('',(#201412)); +#201412 = SURFACE_STYLE_FILL_AREA(#201413); +#201413 = FILL_AREA_STYLE('',(#201414)); +#201414 = FILL_AREA_STYLE_COLOUR('',#198418); +#201415 = OVER_RIDING_STYLED_ITEM('overriding color',(#201416),#125432, + #198353); +#201416 = PRESENTATION_STYLE_ASSIGNMENT((#201417)); +#201417 = SURFACE_STYLE_USAGE(.BOTH.,#201418); +#201418 = SURFACE_SIDE_STYLE('',(#201419)); +#201419 = SURFACE_STYLE_FILL_AREA(#201420); +#201420 = FILL_AREA_STYLE('',(#201421)); +#201421 = FILL_AREA_STYLE_COLOUR('',#198418); +#201422 = OVER_RIDING_STYLED_ITEM('overriding color',(#201423),#125541, + #198353); +#201423 = PRESENTATION_STYLE_ASSIGNMENT((#201424)); +#201424 = SURFACE_STYLE_USAGE(.BOTH.,#201425); +#201425 = SURFACE_SIDE_STYLE('',(#201426)); +#201426 = SURFACE_STYLE_FILL_AREA(#201427); +#201427 = FILL_AREA_STYLE('',(#201428)); +#201428 = FILL_AREA_STYLE_COLOUR('',#198418); +#201429 = OVER_RIDING_STYLED_ITEM('overriding color',(#201430),#125645, + #198353); +#201430 = PRESENTATION_STYLE_ASSIGNMENT((#201431)); +#201431 = SURFACE_STYLE_USAGE(.BOTH.,#201432); +#201432 = SURFACE_SIDE_STYLE('',(#201433)); +#201433 = SURFACE_STYLE_FILL_AREA(#201434); +#201434 = FILL_AREA_STYLE('',(#201435)); +#201435 = FILL_AREA_STYLE_COLOUR('',#198418); +#201436 = OVER_RIDING_STYLED_ITEM('overriding color',(#201437),#125724, + #198353); +#201437 = PRESENTATION_STYLE_ASSIGNMENT((#201438)); +#201438 = SURFACE_STYLE_USAGE(.BOTH.,#201439); +#201439 = SURFACE_SIDE_STYLE('',(#201440)); +#201440 = SURFACE_STYLE_FILL_AREA(#201441); +#201441 = FILL_AREA_STYLE('',(#201442)); +#201442 = FILL_AREA_STYLE_COLOUR('',#198418); +#201443 = OVER_RIDING_STYLED_ITEM('overriding color',(#201444),#125803, + #198353); +#201444 = PRESENTATION_STYLE_ASSIGNMENT((#201445)); +#201445 = SURFACE_STYLE_USAGE(.BOTH.,#201446); +#201446 = SURFACE_SIDE_STYLE('',(#201447)); +#201447 = SURFACE_STYLE_FILL_AREA(#201448); +#201448 = FILL_AREA_STYLE('',(#201449)); +#201449 = FILL_AREA_STYLE_COLOUR('',#198418); +#201450 = OVER_RIDING_STYLED_ITEM('overriding color',(#201451),#125878, + #198353); +#201451 = PRESENTATION_STYLE_ASSIGNMENT((#201452)); +#201452 = SURFACE_STYLE_USAGE(.BOTH.,#201453); +#201453 = SURFACE_SIDE_STYLE('',(#201454)); +#201454 = SURFACE_STYLE_FILL_AREA(#201455); +#201455 = FILL_AREA_STYLE('',(#201456)); +#201456 = FILL_AREA_STYLE_COLOUR('',#198418); +#201457 = OVER_RIDING_STYLED_ITEM('overriding color',(#201458),#125953, + #198353); +#201458 = PRESENTATION_STYLE_ASSIGNMENT((#201459)); +#201459 = SURFACE_STYLE_USAGE(.BOTH.,#201460); +#201460 = SURFACE_SIDE_STYLE('',(#201461)); +#201461 = SURFACE_STYLE_FILL_AREA(#201462); +#201462 = FILL_AREA_STYLE('',(#201463)); +#201463 = FILL_AREA_STYLE_COLOUR('',#198418); +#201464 = OVER_RIDING_STYLED_ITEM('overriding color',(#201465),#126027, + #198353); +#201465 = PRESENTATION_STYLE_ASSIGNMENT((#201466)); +#201466 = SURFACE_STYLE_USAGE(.BOTH.,#201467); +#201467 = SURFACE_SIDE_STYLE('',(#201468)); +#201468 = SURFACE_STYLE_FILL_AREA(#201469); +#201469 = FILL_AREA_STYLE('',(#201470)); +#201470 = FILL_AREA_STYLE_COLOUR('',#198418); +#201471 = OVER_RIDING_STYLED_ITEM('overriding color',(#201472),#126101, + #198353); +#201472 = PRESENTATION_STYLE_ASSIGNMENT((#201473)); +#201473 = SURFACE_STYLE_USAGE(.BOTH.,#201474); +#201474 = SURFACE_SIDE_STYLE('',(#201475)); +#201475 = SURFACE_STYLE_FILL_AREA(#201476); +#201476 = FILL_AREA_STYLE('',(#201477)); +#201477 = FILL_AREA_STYLE_COLOUR('',#198418); +#201478 = OVER_RIDING_STYLED_ITEM('overriding color',(#201479),#126176, + #198353); +#201479 = PRESENTATION_STYLE_ASSIGNMENT((#201480)); +#201480 = SURFACE_STYLE_USAGE(.BOTH.,#201481); +#201481 = SURFACE_SIDE_STYLE('',(#201482)); +#201482 = SURFACE_STYLE_FILL_AREA(#201483); +#201483 = FILL_AREA_STYLE('',(#201484)); +#201484 = FILL_AREA_STYLE_COLOUR('',#198418); +#201485 = OVER_RIDING_STYLED_ITEM('overriding color',(#201486),#126203, + #198353); +#201486 = PRESENTATION_STYLE_ASSIGNMENT((#201487)); +#201487 = SURFACE_STYLE_USAGE(.BOTH.,#201488); +#201488 = SURFACE_SIDE_STYLE('',(#201489)); +#201489 = SURFACE_STYLE_FILL_AREA(#201490); +#201490 = FILL_AREA_STYLE('',(#201491)); +#201491 = FILL_AREA_STYLE_COLOUR('',#198418); +#201492 = OVER_RIDING_STYLED_ITEM('overriding color',(#201493),#126258, + #198353); +#201493 = PRESENTATION_STYLE_ASSIGNMENT((#201494)); +#201494 = SURFACE_STYLE_USAGE(.BOTH.,#201495); +#201495 = SURFACE_SIDE_STYLE('',(#201496)); +#201496 = SURFACE_STYLE_FILL_AREA(#201497); +#201497 = FILL_AREA_STYLE('',(#201498)); +#201498 = FILL_AREA_STYLE_COLOUR('',#198418); +#201499 = OVER_RIDING_STYLED_ITEM('overriding color',(#201500),#126265, + #198353); +#201500 = PRESENTATION_STYLE_ASSIGNMENT((#201501)); +#201501 = SURFACE_STYLE_USAGE(.BOTH.,#201502); +#201502 = SURFACE_SIDE_STYLE('',(#201503)); +#201503 = SURFACE_STYLE_FILL_AREA(#201504); +#201504 = FILL_AREA_STYLE('',(#201505)); +#201505 = FILL_AREA_STYLE_COLOUR('',#198418); +#201506 = OVER_RIDING_STYLED_ITEM('overriding color',(#201507),#126272, + #198353); +#201507 = PRESENTATION_STYLE_ASSIGNMENT((#201508)); +#201508 = SURFACE_STYLE_USAGE(.BOTH.,#201509); +#201509 = SURFACE_SIDE_STYLE('',(#201510)); +#201510 = SURFACE_STYLE_FILL_AREA(#201511); +#201511 = FILL_AREA_STYLE('',(#201512)); +#201512 = FILL_AREA_STYLE_COLOUR('',#198418); +#201513 = OVER_RIDING_STYLED_ITEM('overriding color',(#201514),#126381, + #198353); +#201514 = PRESENTATION_STYLE_ASSIGNMENT((#201515)); +#201515 = SURFACE_STYLE_USAGE(.BOTH.,#201516); +#201516 = SURFACE_SIDE_STYLE('',(#201517)); +#201517 = SURFACE_STYLE_FILL_AREA(#201518); +#201518 = FILL_AREA_STYLE('',(#201519)); +#201519 = FILL_AREA_STYLE_COLOUR('',#198418); +#201520 = OVER_RIDING_STYLED_ITEM('overriding color',(#201521),#126485, + #198353); +#201521 = PRESENTATION_STYLE_ASSIGNMENT((#201522)); +#201522 = SURFACE_STYLE_USAGE(.BOTH.,#201523); +#201523 = SURFACE_SIDE_STYLE('',(#201524)); +#201524 = SURFACE_STYLE_FILL_AREA(#201525); +#201525 = FILL_AREA_STYLE('',(#201526)); +#201526 = FILL_AREA_STYLE_COLOUR('',#198418); +#201527 = OVER_RIDING_STYLED_ITEM('overriding color',(#201528),#126564, + #198353); +#201528 = PRESENTATION_STYLE_ASSIGNMENT((#201529)); +#201529 = SURFACE_STYLE_USAGE(.BOTH.,#201530); +#201530 = SURFACE_SIDE_STYLE('',(#201531)); +#201531 = SURFACE_STYLE_FILL_AREA(#201532); +#201532 = FILL_AREA_STYLE('',(#201533)); +#201533 = FILL_AREA_STYLE_COLOUR('',#198418); +#201534 = OVER_RIDING_STYLED_ITEM('overriding color',(#201535),#126643, + #198353); +#201535 = PRESENTATION_STYLE_ASSIGNMENT((#201536)); +#201536 = SURFACE_STYLE_USAGE(.BOTH.,#201537); +#201537 = SURFACE_SIDE_STYLE('',(#201538)); +#201538 = SURFACE_STYLE_FILL_AREA(#201539); +#201539 = FILL_AREA_STYLE('',(#201540)); +#201540 = FILL_AREA_STYLE_COLOUR('',#198418); +#201541 = OVER_RIDING_STYLED_ITEM('overriding color',(#201542),#126718, + #198353); +#201542 = PRESENTATION_STYLE_ASSIGNMENT((#201543)); +#201543 = SURFACE_STYLE_USAGE(.BOTH.,#201544); +#201544 = SURFACE_SIDE_STYLE('',(#201545)); +#201545 = SURFACE_STYLE_FILL_AREA(#201546); +#201546 = FILL_AREA_STYLE('',(#201547)); +#201547 = FILL_AREA_STYLE_COLOUR('',#198418); +#201548 = OVER_RIDING_STYLED_ITEM('overriding color',(#201549),#126793, + #198353); +#201549 = PRESENTATION_STYLE_ASSIGNMENT((#201550)); +#201550 = SURFACE_STYLE_USAGE(.BOTH.,#201551); +#201551 = SURFACE_SIDE_STYLE('',(#201552)); +#201552 = SURFACE_STYLE_FILL_AREA(#201553); +#201553 = FILL_AREA_STYLE('',(#201554)); +#201554 = FILL_AREA_STYLE_COLOUR('',#198418); +#201555 = OVER_RIDING_STYLED_ITEM('overriding color',(#201556),#126867, + #198353); +#201556 = PRESENTATION_STYLE_ASSIGNMENT((#201557)); +#201557 = SURFACE_STYLE_USAGE(.BOTH.,#201558); +#201558 = SURFACE_SIDE_STYLE('',(#201559)); +#201559 = SURFACE_STYLE_FILL_AREA(#201560); +#201560 = FILL_AREA_STYLE('',(#201561)); +#201561 = FILL_AREA_STYLE_COLOUR('',#198418); +#201562 = OVER_RIDING_STYLED_ITEM('overriding color',(#201563),#126941, + #198353); +#201563 = PRESENTATION_STYLE_ASSIGNMENT((#201564)); +#201564 = SURFACE_STYLE_USAGE(.BOTH.,#201565); +#201565 = SURFACE_SIDE_STYLE('',(#201566)); +#201566 = SURFACE_STYLE_FILL_AREA(#201567); +#201567 = FILL_AREA_STYLE('',(#201568)); +#201568 = FILL_AREA_STYLE_COLOUR('',#198418); +#201569 = OVER_RIDING_STYLED_ITEM('overriding color',(#201570),#126988, + #198353); +#201570 = PRESENTATION_STYLE_ASSIGNMENT((#201571)); +#201571 = SURFACE_STYLE_USAGE(.BOTH.,#201572); +#201572 = SURFACE_SIDE_STYLE('',(#201573)); +#201573 = SURFACE_STYLE_FILL_AREA(#201574); +#201574 = FILL_AREA_STYLE('',(#201575)); +#201575 = FILL_AREA_STYLE_COLOUR('',#198418); +#201576 = OVER_RIDING_STYLED_ITEM('overriding color',(#201577),#127043, + #198353); +#201577 = PRESENTATION_STYLE_ASSIGNMENT((#201578)); +#201578 = SURFACE_STYLE_USAGE(.BOTH.,#201579); +#201579 = SURFACE_SIDE_STYLE('',(#201580)); +#201580 = SURFACE_STYLE_FILL_AREA(#201581); +#201581 = FILL_AREA_STYLE('',(#201582)); +#201582 = FILL_AREA_STYLE_COLOUR('',#198418); +#201583 = OVER_RIDING_STYLED_ITEM('overriding color',(#201584),#127070, + #198353); +#201584 = PRESENTATION_STYLE_ASSIGNMENT((#201585)); +#201585 = SURFACE_STYLE_USAGE(.BOTH.,#201586); +#201586 = SURFACE_SIDE_STYLE('',(#201587)); +#201587 = SURFACE_STYLE_FILL_AREA(#201588); +#201588 = FILL_AREA_STYLE('',(#201589)); +#201589 = FILL_AREA_STYLE_COLOUR('',#198418); +#201590 = OVER_RIDING_STYLED_ITEM('overriding color',(#201591),#127105, + #198353); +#201591 = PRESENTATION_STYLE_ASSIGNMENT((#201592)); +#201592 = SURFACE_STYLE_USAGE(.BOTH.,#201593); +#201593 = SURFACE_SIDE_STYLE('',(#201594)); +#201594 = SURFACE_STYLE_FILL_AREA(#201595); +#201595 = FILL_AREA_STYLE('',(#201596)); +#201596 = FILL_AREA_STYLE_COLOUR('',#198418); +#201597 = OVER_RIDING_STYLED_ITEM('overriding color',(#201598),#127112, + #198353); +#201598 = PRESENTATION_STYLE_ASSIGNMENT((#201599)); +#201599 = SURFACE_STYLE_USAGE(.BOTH.,#201600); +#201600 = SURFACE_SIDE_STYLE('',(#201601)); +#201601 = SURFACE_STYLE_FILL_AREA(#201602); +#201602 = FILL_AREA_STYLE('',(#201603)); +#201603 = FILL_AREA_STYLE_COLOUR('',#198418); +#201604 = OVER_RIDING_STYLED_ITEM('overriding color',(#201605),#127221, + #198353); +#201605 = PRESENTATION_STYLE_ASSIGNMENT((#201606)); +#201606 = SURFACE_STYLE_USAGE(.BOTH.,#201607); +#201607 = SURFACE_SIDE_STYLE('',(#201608)); +#201608 = SURFACE_STYLE_FILL_AREA(#201609); +#201609 = FILL_AREA_STYLE('',(#201610)); +#201610 = FILL_AREA_STYLE_COLOUR('',#198418); +#201611 = OVER_RIDING_STYLED_ITEM('overriding color',(#201612),#127325, + #198353); +#201612 = PRESENTATION_STYLE_ASSIGNMENT((#201613)); +#201613 = SURFACE_STYLE_USAGE(.BOTH.,#201614); +#201614 = SURFACE_SIDE_STYLE('',(#201615)); +#201615 = SURFACE_STYLE_FILL_AREA(#201616); +#201616 = FILL_AREA_STYLE('',(#201617)); +#201617 = FILL_AREA_STYLE_COLOUR('',#198418); +#201618 = OVER_RIDING_STYLED_ITEM('overriding color',(#201619),#127404, + #198353); +#201619 = PRESENTATION_STYLE_ASSIGNMENT((#201620)); +#201620 = SURFACE_STYLE_USAGE(.BOTH.,#201621); +#201621 = SURFACE_SIDE_STYLE('',(#201622)); +#201622 = SURFACE_STYLE_FILL_AREA(#201623); +#201623 = FILL_AREA_STYLE('',(#201624)); +#201624 = FILL_AREA_STYLE_COLOUR('',#198418); +#201625 = OVER_RIDING_STYLED_ITEM('overriding color',(#201626),#127483, + #198353); +#201626 = PRESENTATION_STYLE_ASSIGNMENT((#201627)); +#201627 = SURFACE_STYLE_USAGE(.BOTH.,#201628); +#201628 = SURFACE_SIDE_STYLE('',(#201629)); +#201629 = SURFACE_STYLE_FILL_AREA(#201630); +#201630 = FILL_AREA_STYLE('',(#201631)); +#201631 = FILL_AREA_STYLE_COLOUR('',#198418); +#201632 = OVER_RIDING_STYLED_ITEM('overriding color',(#201633),#127558, + #198353); +#201633 = PRESENTATION_STYLE_ASSIGNMENT((#201634)); +#201634 = SURFACE_STYLE_USAGE(.BOTH.,#201635); +#201635 = SURFACE_SIDE_STYLE('',(#201636)); +#201636 = SURFACE_STYLE_FILL_AREA(#201637); +#201637 = FILL_AREA_STYLE('',(#201638)); +#201638 = FILL_AREA_STYLE_COLOUR('',#198418); +#201639 = OVER_RIDING_STYLED_ITEM('overriding color',(#201640),#127633, + #198353); +#201640 = PRESENTATION_STYLE_ASSIGNMENT((#201641)); +#201641 = SURFACE_STYLE_USAGE(.BOTH.,#201642); +#201642 = SURFACE_SIDE_STYLE('',(#201643)); +#201643 = SURFACE_STYLE_FILL_AREA(#201644); +#201644 = FILL_AREA_STYLE('',(#201645)); +#201645 = FILL_AREA_STYLE_COLOUR('',#198418); +#201646 = OVER_RIDING_STYLED_ITEM('overriding color',(#201647),#127707, + #198353); +#201647 = PRESENTATION_STYLE_ASSIGNMENT((#201648)); +#201648 = SURFACE_STYLE_USAGE(.BOTH.,#201649); +#201649 = SURFACE_SIDE_STYLE('',(#201650)); +#201650 = SURFACE_STYLE_FILL_AREA(#201651); +#201651 = FILL_AREA_STYLE('',(#201652)); +#201652 = FILL_AREA_STYLE_COLOUR('',#198418); +#201653 = OVER_RIDING_STYLED_ITEM('overriding color',(#201654),#127781, + #198353); +#201654 = PRESENTATION_STYLE_ASSIGNMENT((#201655)); +#201655 = SURFACE_STYLE_USAGE(.BOTH.,#201656); +#201656 = SURFACE_SIDE_STYLE('',(#201657)); +#201657 = SURFACE_STYLE_FILL_AREA(#201658); +#201658 = FILL_AREA_STYLE('',(#201659)); +#201659 = FILL_AREA_STYLE_COLOUR('',#198418); +#201660 = OVER_RIDING_STYLED_ITEM('overriding color',(#201661),#127828, + #198353); +#201661 = PRESENTATION_STYLE_ASSIGNMENT((#201662)); +#201662 = SURFACE_STYLE_USAGE(.BOTH.,#201663); +#201663 = SURFACE_SIDE_STYLE('',(#201664)); +#201664 = SURFACE_STYLE_FILL_AREA(#201665); +#201665 = FILL_AREA_STYLE('',(#201666)); +#201666 = FILL_AREA_STYLE_COLOUR('',#198418); +#201667 = OVER_RIDING_STYLED_ITEM('overriding color',(#201668),#127883, + #198353); +#201668 = PRESENTATION_STYLE_ASSIGNMENT((#201669)); +#201669 = SURFACE_STYLE_USAGE(.BOTH.,#201670); +#201670 = SURFACE_SIDE_STYLE('',(#201671)); +#201671 = SURFACE_STYLE_FILL_AREA(#201672); +#201672 = FILL_AREA_STYLE('',(#201673)); +#201673 = FILL_AREA_STYLE_COLOUR('',#198418); +#201674 = OVER_RIDING_STYLED_ITEM('overriding color',(#201675),#127910, + #198353); +#201675 = PRESENTATION_STYLE_ASSIGNMENT((#201676)); +#201676 = SURFACE_STYLE_USAGE(.BOTH.,#201677); +#201677 = SURFACE_SIDE_STYLE('',(#201678)); +#201678 = SURFACE_STYLE_FILL_AREA(#201679); +#201679 = FILL_AREA_STYLE('',(#201680)); +#201680 = FILL_AREA_STYLE_COLOUR('',#198418); +#201681 = OVER_RIDING_STYLED_ITEM('overriding color',(#201682),#127945, + #198353); +#201682 = PRESENTATION_STYLE_ASSIGNMENT((#201683)); +#201683 = SURFACE_STYLE_USAGE(.BOTH.,#201684); +#201684 = SURFACE_SIDE_STYLE('',(#201685)); +#201685 = SURFACE_STYLE_FILL_AREA(#201686); +#201686 = FILL_AREA_STYLE('',(#201687)); +#201687 = FILL_AREA_STYLE_COLOUR('',#198418); +#201688 = OVER_RIDING_STYLED_ITEM('overriding color',(#201689),#127952, + #198353); +#201689 = PRESENTATION_STYLE_ASSIGNMENT((#201690)); +#201690 = SURFACE_STYLE_USAGE(.BOTH.,#201691); +#201691 = SURFACE_SIDE_STYLE('',(#201692)); +#201692 = SURFACE_STYLE_FILL_AREA(#201693); +#201693 = FILL_AREA_STYLE('',(#201694)); +#201694 = FILL_AREA_STYLE_COLOUR('',#198418); +#201695 = OVER_RIDING_STYLED_ITEM('overriding color',(#201696),#128061, + #198353); +#201696 = PRESENTATION_STYLE_ASSIGNMENT((#201697)); +#201697 = SURFACE_STYLE_USAGE(.BOTH.,#201698); +#201698 = SURFACE_SIDE_STYLE('',(#201699)); +#201699 = SURFACE_STYLE_FILL_AREA(#201700); +#201700 = FILL_AREA_STYLE('',(#201701)); +#201701 = FILL_AREA_STYLE_COLOUR('',#198418); +#201702 = OVER_RIDING_STYLED_ITEM('overriding color',(#201703),#128165, + #198353); +#201703 = PRESENTATION_STYLE_ASSIGNMENT((#201704)); +#201704 = SURFACE_STYLE_USAGE(.BOTH.,#201705); +#201705 = SURFACE_SIDE_STYLE('',(#201706)); +#201706 = SURFACE_STYLE_FILL_AREA(#201707); +#201707 = FILL_AREA_STYLE('',(#201708)); +#201708 = FILL_AREA_STYLE_COLOUR('',#198418); +#201709 = OVER_RIDING_STYLED_ITEM('overriding color',(#201710),#128244, + #198353); +#201710 = PRESENTATION_STYLE_ASSIGNMENT((#201711)); +#201711 = SURFACE_STYLE_USAGE(.BOTH.,#201712); +#201712 = SURFACE_SIDE_STYLE('',(#201713)); +#201713 = SURFACE_STYLE_FILL_AREA(#201714); +#201714 = FILL_AREA_STYLE('',(#201715)); +#201715 = FILL_AREA_STYLE_COLOUR('',#198418); +#201716 = OVER_RIDING_STYLED_ITEM('overriding color',(#201717),#128323, + #198353); +#201717 = PRESENTATION_STYLE_ASSIGNMENT((#201718)); +#201718 = SURFACE_STYLE_USAGE(.BOTH.,#201719); +#201719 = SURFACE_SIDE_STYLE('',(#201720)); +#201720 = SURFACE_STYLE_FILL_AREA(#201721); +#201721 = FILL_AREA_STYLE('',(#201722)); +#201722 = FILL_AREA_STYLE_COLOUR('',#198418); +#201723 = OVER_RIDING_STYLED_ITEM('overriding color',(#201724),#128398, + #198353); +#201724 = PRESENTATION_STYLE_ASSIGNMENT((#201725)); +#201725 = SURFACE_STYLE_USAGE(.BOTH.,#201726); +#201726 = SURFACE_SIDE_STYLE('',(#201727)); +#201727 = SURFACE_STYLE_FILL_AREA(#201728); +#201728 = FILL_AREA_STYLE('',(#201729)); +#201729 = FILL_AREA_STYLE_COLOUR('',#198418); +#201730 = OVER_RIDING_STYLED_ITEM('overriding color',(#201731),#128473, + #198353); +#201731 = PRESENTATION_STYLE_ASSIGNMENT((#201732)); +#201732 = SURFACE_STYLE_USAGE(.BOTH.,#201733); +#201733 = SURFACE_SIDE_STYLE('',(#201734)); +#201734 = SURFACE_STYLE_FILL_AREA(#201735); +#201735 = FILL_AREA_STYLE('',(#201736)); +#201736 = FILL_AREA_STYLE_COLOUR('',#198418); +#201737 = OVER_RIDING_STYLED_ITEM('overriding color',(#201738),#128547, + #198353); +#201738 = PRESENTATION_STYLE_ASSIGNMENT((#201739)); +#201739 = SURFACE_STYLE_USAGE(.BOTH.,#201740); +#201740 = SURFACE_SIDE_STYLE('',(#201741)); +#201741 = SURFACE_STYLE_FILL_AREA(#201742); +#201742 = FILL_AREA_STYLE('',(#201743)); +#201743 = FILL_AREA_STYLE_COLOUR('',#198418); +#201744 = OVER_RIDING_STYLED_ITEM('overriding color',(#201745),#128621, + #198353); +#201745 = PRESENTATION_STYLE_ASSIGNMENT((#201746)); +#201746 = SURFACE_STYLE_USAGE(.BOTH.,#201747); +#201747 = SURFACE_SIDE_STYLE('',(#201748)); +#201748 = SURFACE_STYLE_FILL_AREA(#201749); +#201749 = FILL_AREA_STYLE('',(#201750)); +#201750 = FILL_AREA_STYLE_COLOUR('',#198418); +#201751 = OVER_RIDING_STYLED_ITEM('overriding color',(#201752),#128668, + #198353); +#201752 = PRESENTATION_STYLE_ASSIGNMENT((#201753)); +#201753 = SURFACE_STYLE_USAGE(.BOTH.,#201754); +#201754 = SURFACE_SIDE_STYLE('',(#201755)); +#201755 = SURFACE_STYLE_FILL_AREA(#201756); +#201756 = FILL_AREA_STYLE('',(#201757)); +#201757 = FILL_AREA_STYLE_COLOUR('',#198418); +#201758 = OVER_RIDING_STYLED_ITEM('overriding color',(#201759),#128723, + #198353); +#201759 = PRESENTATION_STYLE_ASSIGNMENT((#201760)); +#201760 = SURFACE_STYLE_USAGE(.BOTH.,#201761); +#201761 = SURFACE_SIDE_STYLE('',(#201762)); +#201762 = SURFACE_STYLE_FILL_AREA(#201763); +#201763 = FILL_AREA_STYLE('',(#201764)); +#201764 = FILL_AREA_STYLE_COLOUR('',#198418); +#201765 = OVER_RIDING_STYLED_ITEM('overriding color',(#201766),#128750, + #198353); +#201766 = PRESENTATION_STYLE_ASSIGNMENT((#201767)); +#201767 = SURFACE_STYLE_USAGE(.BOTH.,#201768); +#201768 = SURFACE_SIDE_STYLE('',(#201769)); +#201769 = SURFACE_STYLE_FILL_AREA(#201770); +#201770 = FILL_AREA_STYLE('',(#201771)); +#201771 = FILL_AREA_STYLE_COLOUR('',#198418); +#201772 = OVER_RIDING_STYLED_ITEM('overriding color',(#201773),#128785, + #198353); +#201773 = PRESENTATION_STYLE_ASSIGNMENT((#201774)); +#201774 = SURFACE_STYLE_USAGE(.BOTH.,#201775); +#201775 = SURFACE_SIDE_STYLE('',(#201776)); +#201776 = SURFACE_STYLE_FILL_AREA(#201777); +#201777 = FILL_AREA_STYLE('',(#201778)); +#201778 = FILL_AREA_STYLE_COLOUR('',#198418); +#201779 = OVER_RIDING_STYLED_ITEM('overriding color',(#201780),#128792, + #198353); +#201780 = PRESENTATION_STYLE_ASSIGNMENT((#201781)); +#201781 = SURFACE_STYLE_USAGE(.BOTH.,#201782); +#201782 = SURFACE_SIDE_STYLE('',(#201783)); +#201783 = SURFACE_STYLE_FILL_AREA(#201784); +#201784 = FILL_AREA_STYLE('',(#201785)); +#201785 = FILL_AREA_STYLE_COLOUR('',#198418); +#201786 = OVER_RIDING_STYLED_ITEM('overriding color',(#201787),#128901, + #198353); +#201787 = PRESENTATION_STYLE_ASSIGNMENT((#201788)); +#201788 = SURFACE_STYLE_USAGE(.BOTH.,#201789); +#201789 = SURFACE_SIDE_STYLE('',(#201790)); +#201790 = SURFACE_STYLE_FILL_AREA(#201791); +#201791 = FILL_AREA_STYLE('',(#201792)); +#201792 = FILL_AREA_STYLE_COLOUR('',#198418); +#201793 = OVER_RIDING_STYLED_ITEM('overriding color',(#201794),#129005, + #198353); +#201794 = PRESENTATION_STYLE_ASSIGNMENT((#201795)); +#201795 = SURFACE_STYLE_USAGE(.BOTH.,#201796); +#201796 = SURFACE_SIDE_STYLE('',(#201797)); +#201797 = SURFACE_STYLE_FILL_AREA(#201798); +#201798 = FILL_AREA_STYLE('',(#201799)); +#201799 = FILL_AREA_STYLE_COLOUR('',#198418); +#201800 = OVER_RIDING_STYLED_ITEM('overriding color',(#201801),#129084, + #198353); +#201801 = PRESENTATION_STYLE_ASSIGNMENT((#201802)); +#201802 = SURFACE_STYLE_USAGE(.BOTH.,#201803); +#201803 = SURFACE_SIDE_STYLE('',(#201804)); +#201804 = SURFACE_STYLE_FILL_AREA(#201805); +#201805 = FILL_AREA_STYLE('',(#201806)); +#201806 = FILL_AREA_STYLE_COLOUR('',#198418); +#201807 = OVER_RIDING_STYLED_ITEM('overriding color',(#201808),#129163, + #198353); +#201808 = PRESENTATION_STYLE_ASSIGNMENT((#201809)); +#201809 = SURFACE_STYLE_USAGE(.BOTH.,#201810); +#201810 = SURFACE_SIDE_STYLE('',(#201811)); +#201811 = SURFACE_STYLE_FILL_AREA(#201812); +#201812 = FILL_AREA_STYLE('',(#201813)); +#201813 = FILL_AREA_STYLE_COLOUR('',#198418); +#201814 = OVER_RIDING_STYLED_ITEM('overriding color',(#201815),#129238, + #198353); +#201815 = PRESENTATION_STYLE_ASSIGNMENT((#201816)); +#201816 = SURFACE_STYLE_USAGE(.BOTH.,#201817); +#201817 = SURFACE_SIDE_STYLE('',(#201818)); +#201818 = SURFACE_STYLE_FILL_AREA(#201819); +#201819 = FILL_AREA_STYLE('',(#201820)); +#201820 = FILL_AREA_STYLE_COLOUR('',#198418); +#201821 = OVER_RIDING_STYLED_ITEM('overriding color',(#201822),#129313, + #198353); +#201822 = PRESENTATION_STYLE_ASSIGNMENT((#201823)); +#201823 = SURFACE_STYLE_USAGE(.BOTH.,#201824); +#201824 = SURFACE_SIDE_STYLE('',(#201825)); +#201825 = SURFACE_STYLE_FILL_AREA(#201826); +#201826 = FILL_AREA_STYLE('',(#201827)); +#201827 = FILL_AREA_STYLE_COLOUR('',#198418); +#201828 = OVER_RIDING_STYLED_ITEM('overriding color',(#201829),#129387, + #198353); +#201829 = PRESENTATION_STYLE_ASSIGNMENT((#201830)); +#201830 = SURFACE_STYLE_USAGE(.BOTH.,#201831); +#201831 = SURFACE_SIDE_STYLE('',(#201832)); +#201832 = SURFACE_STYLE_FILL_AREA(#201833); +#201833 = FILL_AREA_STYLE('',(#201834)); +#201834 = FILL_AREA_STYLE_COLOUR('',#198418); +#201835 = OVER_RIDING_STYLED_ITEM('overriding color',(#201836),#129461, + #198353); +#201836 = PRESENTATION_STYLE_ASSIGNMENT((#201837)); +#201837 = SURFACE_STYLE_USAGE(.BOTH.,#201838); +#201838 = SURFACE_SIDE_STYLE('',(#201839)); +#201839 = SURFACE_STYLE_FILL_AREA(#201840); +#201840 = FILL_AREA_STYLE('',(#201841)); +#201841 = FILL_AREA_STYLE_COLOUR('',#198418); +#201842 = OVER_RIDING_STYLED_ITEM('overriding color',(#201843),#129508, + #198353); +#201843 = PRESENTATION_STYLE_ASSIGNMENT((#201844)); +#201844 = SURFACE_STYLE_USAGE(.BOTH.,#201845); +#201845 = SURFACE_SIDE_STYLE('',(#201846)); +#201846 = SURFACE_STYLE_FILL_AREA(#201847); +#201847 = FILL_AREA_STYLE('',(#201848)); +#201848 = FILL_AREA_STYLE_COLOUR('',#198418); +#201849 = OVER_RIDING_STYLED_ITEM('overriding color',(#201850),#129563, + #198353); +#201850 = PRESENTATION_STYLE_ASSIGNMENT((#201851)); +#201851 = SURFACE_STYLE_USAGE(.BOTH.,#201852); +#201852 = SURFACE_SIDE_STYLE('',(#201853)); +#201853 = SURFACE_STYLE_FILL_AREA(#201854); +#201854 = FILL_AREA_STYLE('',(#201855)); +#201855 = FILL_AREA_STYLE_COLOUR('',#198418); +#201856 = OVER_RIDING_STYLED_ITEM('overriding color',(#201857),#129590, + #198353); +#201857 = PRESENTATION_STYLE_ASSIGNMENT((#201858)); +#201858 = SURFACE_STYLE_USAGE(.BOTH.,#201859); +#201859 = SURFACE_SIDE_STYLE('',(#201860)); +#201860 = SURFACE_STYLE_FILL_AREA(#201861); +#201861 = FILL_AREA_STYLE('',(#201862)); +#201862 = FILL_AREA_STYLE_COLOUR('',#198418); +#201863 = OVER_RIDING_STYLED_ITEM('overriding color',(#201864),#129625, + #198353); +#201864 = PRESENTATION_STYLE_ASSIGNMENT((#201865)); +#201865 = SURFACE_STYLE_USAGE(.BOTH.,#201866); +#201866 = SURFACE_SIDE_STYLE('',(#201867)); +#201867 = SURFACE_STYLE_FILL_AREA(#201868); +#201868 = FILL_AREA_STYLE('',(#201869)); +#201869 = FILL_AREA_STYLE_COLOUR('',#198418); +#201870 = OVER_RIDING_STYLED_ITEM('overriding color',(#201871),#129632, + #198353); +#201871 = PRESENTATION_STYLE_ASSIGNMENT((#201872)); +#201872 = SURFACE_STYLE_USAGE(.BOTH.,#201873); +#201873 = SURFACE_SIDE_STYLE('',(#201874)); +#201874 = SURFACE_STYLE_FILL_AREA(#201875); +#201875 = FILL_AREA_STYLE('',(#201876)); +#201876 = FILL_AREA_STYLE_COLOUR('',#198418); +#201877 = OVER_RIDING_STYLED_ITEM('overriding color',(#201878),#129741, + #198353); +#201878 = PRESENTATION_STYLE_ASSIGNMENT((#201879)); +#201879 = SURFACE_STYLE_USAGE(.BOTH.,#201880); +#201880 = SURFACE_SIDE_STYLE('',(#201881)); +#201881 = SURFACE_STYLE_FILL_AREA(#201882); +#201882 = FILL_AREA_STYLE('',(#201883)); +#201883 = FILL_AREA_STYLE_COLOUR('',#198418); +#201884 = OVER_RIDING_STYLED_ITEM('overriding color',(#201885),#129845, + #198353); +#201885 = PRESENTATION_STYLE_ASSIGNMENT((#201886)); +#201886 = SURFACE_STYLE_USAGE(.BOTH.,#201887); +#201887 = SURFACE_SIDE_STYLE('',(#201888)); +#201888 = SURFACE_STYLE_FILL_AREA(#201889); +#201889 = FILL_AREA_STYLE('',(#201890)); +#201890 = FILL_AREA_STYLE_COLOUR('',#198418); +#201891 = OVER_RIDING_STYLED_ITEM('overriding color',(#201892),#129924, + #198353); +#201892 = PRESENTATION_STYLE_ASSIGNMENT((#201893)); +#201893 = SURFACE_STYLE_USAGE(.BOTH.,#201894); +#201894 = SURFACE_SIDE_STYLE('',(#201895)); +#201895 = SURFACE_STYLE_FILL_AREA(#201896); +#201896 = FILL_AREA_STYLE('',(#201897)); +#201897 = FILL_AREA_STYLE_COLOUR('',#198418); +#201898 = OVER_RIDING_STYLED_ITEM('overriding color',(#201899),#130003, + #198353); +#201899 = PRESENTATION_STYLE_ASSIGNMENT((#201900)); +#201900 = SURFACE_STYLE_USAGE(.BOTH.,#201901); +#201901 = SURFACE_SIDE_STYLE('',(#201902)); +#201902 = SURFACE_STYLE_FILL_AREA(#201903); +#201903 = FILL_AREA_STYLE('',(#201904)); +#201904 = FILL_AREA_STYLE_COLOUR('',#198418); +#201905 = OVER_RIDING_STYLED_ITEM('overriding color',(#201906),#130078, + #198353); +#201906 = PRESENTATION_STYLE_ASSIGNMENT((#201907)); +#201907 = SURFACE_STYLE_USAGE(.BOTH.,#201908); +#201908 = SURFACE_SIDE_STYLE('',(#201909)); +#201909 = SURFACE_STYLE_FILL_AREA(#201910); +#201910 = FILL_AREA_STYLE('',(#201911)); +#201911 = FILL_AREA_STYLE_COLOUR('',#198418); +#201912 = OVER_RIDING_STYLED_ITEM('overriding color',(#201913),#130153, + #198353); +#201913 = PRESENTATION_STYLE_ASSIGNMENT((#201914)); +#201914 = SURFACE_STYLE_USAGE(.BOTH.,#201915); +#201915 = SURFACE_SIDE_STYLE('',(#201916)); +#201916 = SURFACE_STYLE_FILL_AREA(#201917); +#201917 = FILL_AREA_STYLE('',(#201918)); +#201918 = FILL_AREA_STYLE_COLOUR('',#198418); +#201919 = OVER_RIDING_STYLED_ITEM('overriding color',(#201920),#130227, + #198353); +#201920 = PRESENTATION_STYLE_ASSIGNMENT((#201921)); +#201921 = SURFACE_STYLE_USAGE(.BOTH.,#201922); +#201922 = SURFACE_SIDE_STYLE('',(#201923)); +#201923 = SURFACE_STYLE_FILL_AREA(#201924); +#201924 = FILL_AREA_STYLE('',(#201925)); +#201925 = FILL_AREA_STYLE_COLOUR('',#198418); +#201926 = OVER_RIDING_STYLED_ITEM('overriding color',(#201927),#130301, + #198353); +#201927 = PRESENTATION_STYLE_ASSIGNMENT((#201928)); +#201928 = SURFACE_STYLE_USAGE(.BOTH.,#201929); +#201929 = SURFACE_SIDE_STYLE('',(#201930)); +#201930 = SURFACE_STYLE_FILL_AREA(#201931); +#201931 = FILL_AREA_STYLE('',(#201932)); +#201932 = FILL_AREA_STYLE_COLOUR('',#198418); +#201933 = OVER_RIDING_STYLED_ITEM('overriding color',(#201934),#130348, + #198353); +#201934 = PRESENTATION_STYLE_ASSIGNMENT((#201935)); +#201935 = SURFACE_STYLE_USAGE(.BOTH.,#201936); +#201936 = SURFACE_SIDE_STYLE('',(#201937)); +#201937 = SURFACE_STYLE_FILL_AREA(#201938); +#201938 = FILL_AREA_STYLE('',(#201939)); +#201939 = FILL_AREA_STYLE_COLOUR('',#198418); +#201940 = OVER_RIDING_STYLED_ITEM('overriding color',(#201941),#130403, + #198353); +#201941 = PRESENTATION_STYLE_ASSIGNMENT((#201942)); +#201942 = SURFACE_STYLE_USAGE(.BOTH.,#201943); +#201943 = SURFACE_SIDE_STYLE('',(#201944)); +#201944 = SURFACE_STYLE_FILL_AREA(#201945); +#201945 = FILL_AREA_STYLE('',(#201946)); +#201946 = FILL_AREA_STYLE_COLOUR('',#198418); +#201947 = OVER_RIDING_STYLED_ITEM('overriding color',(#201948),#130430, + #198353); +#201948 = PRESENTATION_STYLE_ASSIGNMENT((#201949)); +#201949 = SURFACE_STYLE_USAGE(.BOTH.,#201950); +#201950 = SURFACE_SIDE_STYLE('',(#201951)); +#201951 = SURFACE_STYLE_FILL_AREA(#201952); +#201952 = FILL_AREA_STYLE('',(#201953)); +#201953 = FILL_AREA_STYLE_COLOUR('',#198418); +#201954 = OVER_RIDING_STYLED_ITEM('overriding color',(#201955),#130465, + #198353); +#201955 = PRESENTATION_STYLE_ASSIGNMENT((#201956)); +#201956 = SURFACE_STYLE_USAGE(.BOTH.,#201957); +#201957 = SURFACE_SIDE_STYLE('',(#201958)); +#201958 = SURFACE_STYLE_FILL_AREA(#201959); +#201959 = FILL_AREA_STYLE('',(#201960)); +#201960 = FILL_AREA_STYLE_COLOUR('',#198418); +#201961 = OVER_RIDING_STYLED_ITEM('overriding color',(#201962),#130472, + #198353); +#201962 = PRESENTATION_STYLE_ASSIGNMENT((#201963)); +#201963 = SURFACE_STYLE_USAGE(.BOTH.,#201964); +#201964 = SURFACE_SIDE_STYLE('',(#201965)); +#201965 = SURFACE_STYLE_FILL_AREA(#201966); +#201966 = FILL_AREA_STYLE('',(#201967)); +#201967 = FILL_AREA_STYLE_COLOUR('',#198418); +#201968 = OVER_RIDING_STYLED_ITEM('overriding color',(#201969),#130581, + #198353); +#201969 = PRESENTATION_STYLE_ASSIGNMENT((#201970)); +#201970 = SURFACE_STYLE_USAGE(.BOTH.,#201971); +#201971 = SURFACE_SIDE_STYLE('',(#201972)); +#201972 = SURFACE_STYLE_FILL_AREA(#201973); +#201973 = FILL_AREA_STYLE('',(#201974)); +#201974 = FILL_AREA_STYLE_COLOUR('',#198418); +#201975 = OVER_RIDING_STYLED_ITEM('overriding color',(#201976),#130685, + #198353); +#201976 = PRESENTATION_STYLE_ASSIGNMENT((#201977)); +#201977 = SURFACE_STYLE_USAGE(.BOTH.,#201978); +#201978 = SURFACE_SIDE_STYLE('',(#201979)); +#201979 = SURFACE_STYLE_FILL_AREA(#201980); +#201980 = FILL_AREA_STYLE('',(#201981)); +#201981 = FILL_AREA_STYLE_COLOUR('',#198418); +#201982 = OVER_RIDING_STYLED_ITEM('overriding color',(#201983),#130764, + #198353); +#201983 = PRESENTATION_STYLE_ASSIGNMENT((#201984)); +#201984 = SURFACE_STYLE_USAGE(.BOTH.,#201985); +#201985 = SURFACE_SIDE_STYLE('',(#201986)); +#201986 = SURFACE_STYLE_FILL_AREA(#201987); +#201987 = FILL_AREA_STYLE('',(#201988)); +#201988 = FILL_AREA_STYLE_COLOUR('',#198418); +#201989 = OVER_RIDING_STYLED_ITEM('overriding color',(#201990),#130843, + #198353); +#201990 = PRESENTATION_STYLE_ASSIGNMENT((#201991)); +#201991 = SURFACE_STYLE_USAGE(.BOTH.,#201992); +#201992 = SURFACE_SIDE_STYLE('',(#201993)); +#201993 = SURFACE_STYLE_FILL_AREA(#201994); +#201994 = FILL_AREA_STYLE('',(#201995)); +#201995 = FILL_AREA_STYLE_COLOUR('',#198418); +#201996 = OVER_RIDING_STYLED_ITEM('overriding color',(#201997),#130918, + #198353); +#201997 = PRESENTATION_STYLE_ASSIGNMENT((#201998)); +#201998 = SURFACE_STYLE_USAGE(.BOTH.,#201999); +#201999 = SURFACE_SIDE_STYLE('',(#202000)); +#202000 = SURFACE_STYLE_FILL_AREA(#202001); +#202001 = FILL_AREA_STYLE('',(#202002)); +#202002 = FILL_AREA_STYLE_COLOUR('',#198418); +#202003 = OVER_RIDING_STYLED_ITEM('overriding color',(#202004),#130993, + #198353); +#202004 = PRESENTATION_STYLE_ASSIGNMENT((#202005)); +#202005 = SURFACE_STYLE_USAGE(.BOTH.,#202006); +#202006 = SURFACE_SIDE_STYLE('',(#202007)); +#202007 = SURFACE_STYLE_FILL_AREA(#202008); +#202008 = FILL_AREA_STYLE('',(#202009)); +#202009 = FILL_AREA_STYLE_COLOUR('',#198418); +#202010 = OVER_RIDING_STYLED_ITEM('overriding color',(#202011),#131067, + #198353); +#202011 = PRESENTATION_STYLE_ASSIGNMENT((#202012)); +#202012 = SURFACE_STYLE_USAGE(.BOTH.,#202013); +#202013 = SURFACE_SIDE_STYLE('',(#202014)); +#202014 = SURFACE_STYLE_FILL_AREA(#202015); +#202015 = FILL_AREA_STYLE('',(#202016)); +#202016 = FILL_AREA_STYLE_COLOUR('',#198418); +#202017 = OVER_RIDING_STYLED_ITEM('overriding color',(#202018),#131141, + #198353); +#202018 = PRESENTATION_STYLE_ASSIGNMENT((#202019)); +#202019 = SURFACE_STYLE_USAGE(.BOTH.,#202020); +#202020 = SURFACE_SIDE_STYLE('',(#202021)); +#202021 = SURFACE_STYLE_FILL_AREA(#202022); +#202022 = FILL_AREA_STYLE('',(#202023)); +#202023 = FILL_AREA_STYLE_COLOUR('',#198418); +#202024 = OVER_RIDING_STYLED_ITEM('overriding color',(#202025),#131188, + #198353); +#202025 = PRESENTATION_STYLE_ASSIGNMENT((#202026)); +#202026 = SURFACE_STYLE_USAGE(.BOTH.,#202027); +#202027 = SURFACE_SIDE_STYLE('',(#202028)); +#202028 = SURFACE_STYLE_FILL_AREA(#202029); +#202029 = FILL_AREA_STYLE('',(#202030)); +#202030 = FILL_AREA_STYLE_COLOUR('',#198418); +#202031 = OVER_RIDING_STYLED_ITEM('overriding color',(#202032),#131243, + #198353); +#202032 = PRESENTATION_STYLE_ASSIGNMENT((#202033)); +#202033 = SURFACE_STYLE_USAGE(.BOTH.,#202034); +#202034 = SURFACE_SIDE_STYLE('',(#202035)); +#202035 = SURFACE_STYLE_FILL_AREA(#202036); +#202036 = FILL_AREA_STYLE('',(#202037)); +#202037 = FILL_AREA_STYLE_COLOUR('',#198418); +#202038 = OVER_RIDING_STYLED_ITEM('overriding color',(#202039),#131270, + #198353); +#202039 = PRESENTATION_STYLE_ASSIGNMENT((#202040)); +#202040 = SURFACE_STYLE_USAGE(.BOTH.,#202041); +#202041 = SURFACE_SIDE_STYLE('',(#202042)); +#202042 = SURFACE_STYLE_FILL_AREA(#202043); +#202043 = FILL_AREA_STYLE('',(#202044)); +#202044 = FILL_AREA_STYLE_COLOUR('',#198418); +#202045 = OVER_RIDING_STYLED_ITEM('overriding color',(#202046),#131305, + #198353); +#202046 = PRESENTATION_STYLE_ASSIGNMENT((#202047)); +#202047 = SURFACE_STYLE_USAGE(.BOTH.,#202048); +#202048 = SURFACE_SIDE_STYLE('',(#202049)); +#202049 = SURFACE_STYLE_FILL_AREA(#202050); +#202050 = FILL_AREA_STYLE('',(#202051)); +#202051 = FILL_AREA_STYLE_COLOUR('',#198418); +#202052 = OVER_RIDING_STYLED_ITEM('overriding color',(#202053),#131312, + #198353); +#202053 = PRESENTATION_STYLE_ASSIGNMENT((#202054)); +#202054 = SURFACE_STYLE_USAGE(.BOTH.,#202055); +#202055 = SURFACE_SIDE_STYLE('',(#202056)); +#202056 = SURFACE_STYLE_FILL_AREA(#202057); +#202057 = FILL_AREA_STYLE('',(#202058)); +#202058 = FILL_AREA_STYLE_COLOUR('',#198418); +#202059 = OVER_RIDING_STYLED_ITEM('overriding color',(#202060),#131421, + #198353); +#202060 = PRESENTATION_STYLE_ASSIGNMENT((#202061)); +#202061 = SURFACE_STYLE_USAGE(.BOTH.,#202062); +#202062 = SURFACE_SIDE_STYLE('',(#202063)); +#202063 = SURFACE_STYLE_FILL_AREA(#202064); +#202064 = FILL_AREA_STYLE('',(#202065)); +#202065 = FILL_AREA_STYLE_COLOUR('',#198418); +#202066 = OVER_RIDING_STYLED_ITEM('overriding color',(#202067),#131525, + #198353); +#202067 = PRESENTATION_STYLE_ASSIGNMENT((#202068)); +#202068 = SURFACE_STYLE_USAGE(.BOTH.,#202069); +#202069 = SURFACE_SIDE_STYLE('',(#202070)); +#202070 = SURFACE_STYLE_FILL_AREA(#202071); +#202071 = FILL_AREA_STYLE('',(#202072)); +#202072 = FILL_AREA_STYLE_COLOUR('',#198418); +#202073 = OVER_RIDING_STYLED_ITEM('overriding color',(#202074),#131604, + #198353); +#202074 = PRESENTATION_STYLE_ASSIGNMENT((#202075)); +#202075 = SURFACE_STYLE_USAGE(.BOTH.,#202076); +#202076 = SURFACE_SIDE_STYLE('',(#202077)); +#202077 = SURFACE_STYLE_FILL_AREA(#202078); +#202078 = FILL_AREA_STYLE('',(#202079)); +#202079 = FILL_AREA_STYLE_COLOUR('',#198418); +#202080 = OVER_RIDING_STYLED_ITEM('overriding color',(#202081),#131683, + #198353); +#202081 = PRESENTATION_STYLE_ASSIGNMENT((#202082)); +#202082 = SURFACE_STYLE_USAGE(.BOTH.,#202083); +#202083 = SURFACE_SIDE_STYLE('',(#202084)); +#202084 = SURFACE_STYLE_FILL_AREA(#202085); +#202085 = FILL_AREA_STYLE('',(#202086)); +#202086 = FILL_AREA_STYLE_COLOUR('',#198418); +#202087 = OVER_RIDING_STYLED_ITEM('overriding color',(#202088),#131758, + #198353); +#202088 = PRESENTATION_STYLE_ASSIGNMENT((#202089)); +#202089 = SURFACE_STYLE_USAGE(.BOTH.,#202090); +#202090 = SURFACE_SIDE_STYLE('',(#202091)); +#202091 = SURFACE_STYLE_FILL_AREA(#202092); +#202092 = FILL_AREA_STYLE('',(#202093)); +#202093 = FILL_AREA_STYLE_COLOUR('',#198418); +#202094 = OVER_RIDING_STYLED_ITEM('overriding color',(#202095),#131833, + #198353); +#202095 = PRESENTATION_STYLE_ASSIGNMENT((#202096)); +#202096 = SURFACE_STYLE_USAGE(.BOTH.,#202097); +#202097 = SURFACE_SIDE_STYLE('',(#202098)); +#202098 = SURFACE_STYLE_FILL_AREA(#202099); +#202099 = FILL_AREA_STYLE('',(#202100)); +#202100 = FILL_AREA_STYLE_COLOUR('',#198418); +#202101 = OVER_RIDING_STYLED_ITEM('overriding color',(#202102),#131907, + #198353); +#202102 = PRESENTATION_STYLE_ASSIGNMENT((#202103)); +#202103 = SURFACE_STYLE_USAGE(.BOTH.,#202104); +#202104 = SURFACE_SIDE_STYLE('',(#202105)); +#202105 = SURFACE_STYLE_FILL_AREA(#202106); +#202106 = FILL_AREA_STYLE('',(#202107)); +#202107 = FILL_AREA_STYLE_COLOUR('',#198418); +#202108 = OVER_RIDING_STYLED_ITEM('overriding color',(#202109),#131981, + #198353); +#202109 = PRESENTATION_STYLE_ASSIGNMENT((#202110)); +#202110 = SURFACE_STYLE_USAGE(.BOTH.,#202111); +#202111 = SURFACE_SIDE_STYLE('',(#202112)); +#202112 = SURFACE_STYLE_FILL_AREA(#202113); +#202113 = FILL_AREA_STYLE('',(#202114)); +#202114 = FILL_AREA_STYLE_COLOUR('',#198418); +#202115 = OVER_RIDING_STYLED_ITEM('overriding color',(#202116),#132028, + #198353); +#202116 = PRESENTATION_STYLE_ASSIGNMENT((#202117)); +#202117 = SURFACE_STYLE_USAGE(.BOTH.,#202118); +#202118 = SURFACE_SIDE_STYLE('',(#202119)); +#202119 = SURFACE_STYLE_FILL_AREA(#202120); +#202120 = FILL_AREA_STYLE('',(#202121)); +#202121 = FILL_AREA_STYLE_COLOUR('',#198418); +#202122 = OVER_RIDING_STYLED_ITEM('overriding color',(#202123),#132083, + #198353); +#202123 = PRESENTATION_STYLE_ASSIGNMENT((#202124)); +#202124 = SURFACE_STYLE_USAGE(.BOTH.,#202125); +#202125 = SURFACE_SIDE_STYLE('',(#202126)); +#202126 = SURFACE_STYLE_FILL_AREA(#202127); +#202127 = FILL_AREA_STYLE('',(#202128)); +#202128 = FILL_AREA_STYLE_COLOUR('',#198418); +#202129 = OVER_RIDING_STYLED_ITEM('overriding color',(#202130),#132110, + #198353); +#202130 = PRESENTATION_STYLE_ASSIGNMENT((#202131)); +#202131 = SURFACE_STYLE_USAGE(.BOTH.,#202132); +#202132 = SURFACE_SIDE_STYLE('',(#202133)); +#202133 = SURFACE_STYLE_FILL_AREA(#202134); +#202134 = FILL_AREA_STYLE('',(#202135)); +#202135 = FILL_AREA_STYLE_COLOUR('',#198418); +#202136 = OVER_RIDING_STYLED_ITEM('overriding color',(#202137),#132145, + #198353); +#202137 = PRESENTATION_STYLE_ASSIGNMENT((#202138)); +#202138 = SURFACE_STYLE_USAGE(.BOTH.,#202139); +#202139 = SURFACE_SIDE_STYLE('',(#202140)); +#202140 = SURFACE_STYLE_FILL_AREA(#202141); +#202141 = FILL_AREA_STYLE('',(#202142)); +#202142 = FILL_AREA_STYLE_COLOUR('',#198418); +#202143 = OVER_RIDING_STYLED_ITEM('overriding color',(#202144),#132152, + #198353); +#202144 = PRESENTATION_STYLE_ASSIGNMENT((#202145)); +#202145 = SURFACE_STYLE_USAGE(.BOTH.,#202146); +#202146 = SURFACE_SIDE_STYLE('',(#202147)); +#202147 = SURFACE_STYLE_FILL_AREA(#202148); +#202148 = FILL_AREA_STYLE('',(#202149)); +#202149 = FILL_AREA_STYLE_COLOUR('',#198418); +#202150 = OVER_RIDING_STYLED_ITEM('overriding color',(#202151),#132261, + #198353); +#202151 = PRESENTATION_STYLE_ASSIGNMENT((#202152)); +#202152 = SURFACE_STYLE_USAGE(.BOTH.,#202153); +#202153 = SURFACE_SIDE_STYLE('',(#202154)); +#202154 = SURFACE_STYLE_FILL_AREA(#202155); +#202155 = FILL_AREA_STYLE('',(#202156)); +#202156 = FILL_AREA_STYLE_COLOUR('',#198418); +#202157 = OVER_RIDING_STYLED_ITEM('overriding color',(#202158),#132365, + #198353); +#202158 = PRESENTATION_STYLE_ASSIGNMENT((#202159)); +#202159 = SURFACE_STYLE_USAGE(.BOTH.,#202160); +#202160 = SURFACE_SIDE_STYLE('',(#202161)); +#202161 = SURFACE_STYLE_FILL_AREA(#202162); +#202162 = FILL_AREA_STYLE('',(#202163)); +#202163 = FILL_AREA_STYLE_COLOUR('',#198418); +#202164 = OVER_RIDING_STYLED_ITEM('overriding color',(#202165),#132444, + #198353); +#202165 = PRESENTATION_STYLE_ASSIGNMENT((#202166)); +#202166 = SURFACE_STYLE_USAGE(.BOTH.,#202167); +#202167 = SURFACE_SIDE_STYLE('',(#202168)); +#202168 = SURFACE_STYLE_FILL_AREA(#202169); +#202169 = FILL_AREA_STYLE('',(#202170)); +#202170 = FILL_AREA_STYLE_COLOUR('',#198418); +#202171 = OVER_RIDING_STYLED_ITEM('overriding color',(#202172),#132523, + #198353); +#202172 = PRESENTATION_STYLE_ASSIGNMENT((#202173)); +#202173 = SURFACE_STYLE_USAGE(.BOTH.,#202174); +#202174 = SURFACE_SIDE_STYLE('',(#202175)); +#202175 = SURFACE_STYLE_FILL_AREA(#202176); +#202176 = FILL_AREA_STYLE('',(#202177)); +#202177 = FILL_AREA_STYLE_COLOUR('',#198418); +#202178 = OVER_RIDING_STYLED_ITEM('overriding color',(#202179),#132598, + #198353); +#202179 = PRESENTATION_STYLE_ASSIGNMENT((#202180)); +#202180 = SURFACE_STYLE_USAGE(.BOTH.,#202181); +#202181 = SURFACE_SIDE_STYLE('',(#202182)); +#202182 = SURFACE_STYLE_FILL_AREA(#202183); +#202183 = FILL_AREA_STYLE('',(#202184)); +#202184 = FILL_AREA_STYLE_COLOUR('',#198418); +#202185 = OVER_RIDING_STYLED_ITEM('overriding color',(#202186),#132673, + #198353); +#202186 = PRESENTATION_STYLE_ASSIGNMENT((#202187)); +#202187 = SURFACE_STYLE_USAGE(.BOTH.,#202188); +#202188 = SURFACE_SIDE_STYLE('',(#202189)); +#202189 = SURFACE_STYLE_FILL_AREA(#202190); +#202190 = FILL_AREA_STYLE('',(#202191)); +#202191 = FILL_AREA_STYLE_COLOUR('',#198418); +#202192 = OVER_RIDING_STYLED_ITEM('overriding color',(#202193),#132747, + #198353); +#202193 = PRESENTATION_STYLE_ASSIGNMENT((#202194)); +#202194 = SURFACE_STYLE_USAGE(.BOTH.,#202195); +#202195 = SURFACE_SIDE_STYLE('',(#202196)); +#202196 = SURFACE_STYLE_FILL_AREA(#202197); +#202197 = FILL_AREA_STYLE('',(#202198)); +#202198 = FILL_AREA_STYLE_COLOUR('',#198418); +#202199 = OVER_RIDING_STYLED_ITEM('overriding color',(#202200),#132821, + #198353); +#202200 = PRESENTATION_STYLE_ASSIGNMENT((#202201)); +#202201 = SURFACE_STYLE_USAGE(.BOTH.,#202202); +#202202 = SURFACE_SIDE_STYLE('',(#202203)); +#202203 = SURFACE_STYLE_FILL_AREA(#202204); +#202204 = FILL_AREA_STYLE('',(#202205)); +#202205 = FILL_AREA_STYLE_COLOUR('',#198418); +#202206 = OVER_RIDING_STYLED_ITEM('overriding color',(#202207),#132868, + #198353); +#202207 = PRESENTATION_STYLE_ASSIGNMENT((#202208)); +#202208 = SURFACE_STYLE_USAGE(.BOTH.,#202209); +#202209 = SURFACE_SIDE_STYLE('',(#202210)); +#202210 = SURFACE_STYLE_FILL_AREA(#202211); +#202211 = FILL_AREA_STYLE('',(#202212)); +#202212 = FILL_AREA_STYLE_COLOUR('',#198418); +#202213 = OVER_RIDING_STYLED_ITEM('overriding color',(#202214),#132923, + #198353); +#202214 = PRESENTATION_STYLE_ASSIGNMENT((#202215)); +#202215 = SURFACE_STYLE_USAGE(.BOTH.,#202216); +#202216 = SURFACE_SIDE_STYLE('',(#202217)); +#202217 = SURFACE_STYLE_FILL_AREA(#202218); +#202218 = FILL_AREA_STYLE('',(#202219)); +#202219 = FILL_AREA_STYLE_COLOUR('',#198418); +#202220 = OVER_RIDING_STYLED_ITEM('overriding color',(#202221),#132950, + #198353); +#202221 = PRESENTATION_STYLE_ASSIGNMENT((#202222)); +#202222 = SURFACE_STYLE_USAGE(.BOTH.,#202223); +#202223 = SURFACE_SIDE_STYLE('',(#202224)); +#202224 = SURFACE_STYLE_FILL_AREA(#202225); +#202225 = FILL_AREA_STYLE('',(#202226)); +#202226 = FILL_AREA_STYLE_COLOUR('',#198418); +#202227 = OVER_RIDING_STYLED_ITEM('overriding color',(#202228),#132985, + #198353); +#202228 = PRESENTATION_STYLE_ASSIGNMENT((#202229)); +#202229 = SURFACE_STYLE_USAGE(.BOTH.,#202230); +#202230 = SURFACE_SIDE_STYLE('',(#202231)); +#202231 = SURFACE_STYLE_FILL_AREA(#202232); +#202232 = FILL_AREA_STYLE('',(#202233)); +#202233 = FILL_AREA_STYLE_COLOUR('',#198418); +#202234 = OVER_RIDING_STYLED_ITEM('overriding color',(#202235),#132992, + #198353); +#202235 = PRESENTATION_STYLE_ASSIGNMENT((#202236)); +#202236 = SURFACE_STYLE_USAGE(.BOTH.,#202237); +#202237 = SURFACE_SIDE_STYLE('',(#202238)); +#202238 = SURFACE_STYLE_FILL_AREA(#202239); +#202239 = FILL_AREA_STYLE('',(#202240)); +#202240 = FILL_AREA_STYLE_COLOUR('',#198418); +#202241 = OVER_RIDING_STYLED_ITEM('overriding color',(#202242),#133101, + #198353); +#202242 = PRESENTATION_STYLE_ASSIGNMENT((#202243)); +#202243 = SURFACE_STYLE_USAGE(.BOTH.,#202244); +#202244 = SURFACE_SIDE_STYLE('',(#202245)); +#202245 = SURFACE_STYLE_FILL_AREA(#202246); +#202246 = FILL_AREA_STYLE('',(#202247)); +#202247 = FILL_AREA_STYLE_COLOUR('',#198418); +#202248 = OVER_RIDING_STYLED_ITEM('overriding color',(#202249),#133205, + #198353); +#202249 = PRESENTATION_STYLE_ASSIGNMENT((#202250)); +#202250 = SURFACE_STYLE_USAGE(.BOTH.,#202251); +#202251 = SURFACE_SIDE_STYLE('',(#202252)); +#202252 = SURFACE_STYLE_FILL_AREA(#202253); +#202253 = FILL_AREA_STYLE('',(#202254)); +#202254 = FILL_AREA_STYLE_COLOUR('',#198418); +#202255 = OVER_RIDING_STYLED_ITEM('overriding color',(#202256),#133284, + #198353); +#202256 = PRESENTATION_STYLE_ASSIGNMENT((#202257)); +#202257 = SURFACE_STYLE_USAGE(.BOTH.,#202258); +#202258 = SURFACE_SIDE_STYLE('',(#202259)); +#202259 = SURFACE_STYLE_FILL_AREA(#202260); +#202260 = FILL_AREA_STYLE('',(#202261)); +#202261 = FILL_AREA_STYLE_COLOUR('',#198418); +#202262 = OVER_RIDING_STYLED_ITEM('overriding color',(#202263),#133409, + #198353); +#202263 = PRESENTATION_STYLE_ASSIGNMENT((#202264)); +#202264 = SURFACE_STYLE_USAGE(.BOTH.,#202265); +#202265 = SURFACE_SIDE_STYLE('',(#202266)); +#202266 = SURFACE_STYLE_FILL_AREA(#202267); +#202267 = FILL_AREA_STYLE('',(#202268)); +#202268 = FILL_AREA_STYLE_COLOUR('',#198418); +#202269 = OVER_RIDING_STYLED_ITEM('overriding color',(#202270),#133484, + #198353); +#202270 = PRESENTATION_STYLE_ASSIGNMENT((#202271)); +#202271 = SURFACE_STYLE_USAGE(.BOTH.,#202272); +#202272 = SURFACE_SIDE_STYLE('',(#202273)); +#202273 = SURFACE_STYLE_FILL_AREA(#202274); +#202274 = FILL_AREA_STYLE('',(#202275)); +#202275 = FILL_AREA_STYLE_COLOUR('',#198418); +#202276 = OVER_RIDING_STYLED_ITEM('overriding color',(#202277),#133559, + #198353); +#202277 = PRESENTATION_STYLE_ASSIGNMENT((#202278)); +#202278 = SURFACE_STYLE_USAGE(.BOTH.,#202279); +#202279 = SURFACE_SIDE_STYLE('',(#202280)); +#202280 = SURFACE_STYLE_FILL_AREA(#202281); +#202281 = FILL_AREA_STYLE('',(#202282)); +#202282 = FILL_AREA_STYLE_COLOUR('',#198418); +#202283 = OVER_RIDING_STYLED_ITEM('overriding color',(#202284),#133679, + #198353); +#202284 = PRESENTATION_STYLE_ASSIGNMENT((#202285)); +#202285 = SURFACE_STYLE_USAGE(.BOTH.,#202286); +#202286 = SURFACE_SIDE_STYLE('',(#202287)); +#202287 = SURFACE_STYLE_FILL_AREA(#202288); +#202288 = FILL_AREA_STYLE('',(#202289)); +#202289 = FILL_AREA_STYLE_COLOUR('',#198418); +#202290 = OVER_RIDING_STYLED_ITEM('overriding color',(#202291),#133753, + #198353); +#202291 = PRESENTATION_STYLE_ASSIGNMENT((#202292)); +#202292 = SURFACE_STYLE_USAGE(.BOTH.,#202293); +#202293 = SURFACE_SIDE_STYLE('',(#202294)); +#202294 = SURFACE_STYLE_FILL_AREA(#202295); +#202295 = FILL_AREA_STYLE('',(#202296)); +#202296 = FILL_AREA_STYLE_COLOUR('',#198418); +#202297 = OVER_RIDING_STYLED_ITEM('overriding color',(#202298),#133800, + #198353); +#202298 = PRESENTATION_STYLE_ASSIGNMENT((#202299)); +#202299 = SURFACE_STYLE_USAGE(.BOTH.,#202300); +#202300 = SURFACE_SIDE_STYLE('',(#202301)); +#202301 = SURFACE_STYLE_FILL_AREA(#202302); +#202302 = FILL_AREA_STYLE('',(#202303)); +#202303 = FILL_AREA_STYLE_COLOUR('',#198418); +#202304 = OVER_RIDING_STYLED_ITEM('overriding color',(#202305),#133855, + #198353); +#202305 = PRESENTATION_STYLE_ASSIGNMENT((#202306)); +#202306 = SURFACE_STYLE_USAGE(.BOTH.,#202307); +#202307 = SURFACE_SIDE_STYLE('',(#202308)); +#202308 = SURFACE_STYLE_FILL_AREA(#202309); +#202309 = FILL_AREA_STYLE('',(#202310)); +#202310 = FILL_AREA_STYLE_COLOUR('',#198418); +#202311 = OVER_RIDING_STYLED_ITEM('overriding color',(#202312),#133882, + #198353); +#202312 = PRESENTATION_STYLE_ASSIGNMENT((#202313)); +#202313 = SURFACE_STYLE_USAGE(.BOTH.,#202314); +#202314 = SURFACE_SIDE_STYLE('',(#202315)); +#202315 = SURFACE_STYLE_FILL_AREA(#202316); +#202316 = FILL_AREA_STYLE('',(#202317)); +#202317 = FILL_AREA_STYLE_COLOUR('',#198418); +#202318 = OVER_RIDING_STYLED_ITEM('overriding color',(#202319),#133917, + #198353); +#202319 = PRESENTATION_STYLE_ASSIGNMENT((#202320)); +#202320 = SURFACE_STYLE_USAGE(.BOTH.,#202321); +#202321 = SURFACE_SIDE_STYLE('',(#202322)); +#202322 = SURFACE_STYLE_FILL_AREA(#202323); +#202323 = FILL_AREA_STYLE('',(#202324)); +#202324 = FILL_AREA_STYLE_COLOUR('',#198418); +#202325 = OVER_RIDING_STYLED_ITEM('overriding color',(#202326),#133924, + #198353); +#202326 = PRESENTATION_STYLE_ASSIGNMENT((#202327)); +#202327 = SURFACE_STYLE_USAGE(.BOTH.,#202328); +#202328 = SURFACE_SIDE_STYLE('',(#202329)); +#202329 = SURFACE_STYLE_FILL_AREA(#202330); +#202330 = FILL_AREA_STYLE('',(#202331)); +#202331 = FILL_AREA_STYLE_COLOUR('',#198418); +#202332 = OVER_RIDING_STYLED_ITEM('overriding color',(#202333),#134033, + #198353); +#202333 = PRESENTATION_STYLE_ASSIGNMENT((#202334)); +#202334 = SURFACE_STYLE_USAGE(.BOTH.,#202335); +#202335 = SURFACE_SIDE_STYLE('',(#202336)); +#202336 = SURFACE_STYLE_FILL_AREA(#202337); +#202337 = FILL_AREA_STYLE('',(#202338)); +#202338 = FILL_AREA_STYLE_COLOUR('',#198418); +#202339 = OVER_RIDING_STYLED_ITEM('overriding color',(#202340),#134137, + #198353); +#202340 = PRESENTATION_STYLE_ASSIGNMENT((#202341)); +#202341 = SURFACE_STYLE_USAGE(.BOTH.,#202342); +#202342 = SURFACE_SIDE_STYLE('',(#202343)); +#202343 = SURFACE_STYLE_FILL_AREA(#202344); +#202344 = FILL_AREA_STYLE('',(#202345)); +#202345 = FILL_AREA_STYLE_COLOUR('',#198418); +#202346 = OVER_RIDING_STYLED_ITEM('overriding color',(#202347),#134216, + #198353); +#202347 = PRESENTATION_STYLE_ASSIGNMENT((#202348)); +#202348 = SURFACE_STYLE_USAGE(.BOTH.,#202349); +#202349 = SURFACE_SIDE_STYLE('',(#202350)); +#202350 = SURFACE_STYLE_FILL_AREA(#202351); +#202351 = FILL_AREA_STYLE('',(#202352)); +#202352 = FILL_AREA_STYLE_COLOUR('',#198418); +#202353 = OVER_RIDING_STYLED_ITEM('overriding color',(#202354),#134341, + #198353); +#202354 = PRESENTATION_STYLE_ASSIGNMENT((#202355)); +#202355 = SURFACE_STYLE_USAGE(.BOTH.,#202356); +#202356 = SURFACE_SIDE_STYLE('',(#202357)); +#202357 = SURFACE_STYLE_FILL_AREA(#202358); +#202358 = FILL_AREA_STYLE('',(#202359)); +#202359 = FILL_AREA_STYLE_COLOUR('',#198418); +#202360 = OVER_RIDING_STYLED_ITEM('overriding color',(#202361),#134416, + #198353); +#202361 = PRESENTATION_STYLE_ASSIGNMENT((#202362)); +#202362 = SURFACE_STYLE_USAGE(.BOTH.,#202363); +#202363 = SURFACE_SIDE_STYLE('',(#202364)); +#202364 = SURFACE_STYLE_FILL_AREA(#202365); +#202365 = FILL_AREA_STYLE('',(#202366)); +#202366 = FILL_AREA_STYLE_COLOUR('',#198418); +#202367 = OVER_RIDING_STYLED_ITEM('overriding color',(#202368),#134491, + #198353); +#202368 = PRESENTATION_STYLE_ASSIGNMENT((#202369)); +#202369 = SURFACE_STYLE_USAGE(.BOTH.,#202370); +#202370 = SURFACE_SIDE_STYLE('',(#202371)); +#202371 = SURFACE_STYLE_FILL_AREA(#202372); +#202372 = FILL_AREA_STYLE('',(#202373)); +#202373 = FILL_AREA_STYLE_COLOUR('',#198418); +#202374 = OVER_RIDING_STYLED_ITEM('overriding color',(#202375),#134611, + #198353); +#202375 = PRESENTATION_STYLE_ASSIGNMENT((#202376)); +#202376 = SURFACE_STYLE_USAGE(.BOTH.,#202377); +#202377 = SURFACE_SIDE_STYLE('',(#202378)); +#202378 = SURFACE_STYLE_FILL_AREA(#202379); +#202379 = FILL_AREA_STYLE('',(#202380)); +#202380 = FILL_AREA_STYLE_COLOUR('',#198418); +#202381 = OVER_RIDING_STYLED_ITEM('overriding color',(#202382),#134685, + #198353); +#202382 = PRESENTATION_STYLE_ASSIGNMENT((#202383)); +#202383 = SURFACE_STYLE_USAGE(.BOTH.,#202384); +#202384 = SURFACE_SIDE_STYLE('',(#202385)); +#202385 = SURFACE_STYLE_FILL_AREA(#202386); +#202386 = FILL_AREA_STYLE('',(#202387)); +#202387 = FILL_AREA_STYLE_COLOUR('',#198418); +#202388 = OVER_RIDING_STYLED_ITEM('overriding color',(#202389),#134732, + #198353); +#202389 = PRESENTATION_STYLE_ASSIGNMENT((#202390)); +#202390 = SURFACE_STYLE_USAGE(.BOTH.,#202391); +#202391 = SURFACE_SIDE_STYLE('',(#202392)); +#202392 = SURFACE_STYLE_FILL_AREA(#202393); +#202393 = FILL_AREA_STYLE('',(#202394)); +#202394 = FILL_AREA_STYLE_COLOUR('',#198418); +#202395 = OVER_RIDING_STYLED_ITEM('overriding color',(#202396),#134787, + #198353); +#202396 = PRESENTATION_STYLE_ASSIGNMENT((#202397)); +#202397 = SURFACE_STYLE_USAGE(.BOTH.,#202398); +#202398 = SURFACE_SIDE_STYLE('',(#202399)); +#202399 = SURFACE_STYLE_FILL_AREA(#202400); +#202400 = FILL_AREA_STYLE('',(#202401)); +#202401 = FILL_AREA_STYLE_COLOUR('',#198418); +#202402 = OVER_RIDING_STYLED_ITEM('overriding color',(#202403),#134814, + #198353); +#202403 = PRESENTATION_STYLE_ASSIGNMENT((#202404)); +#202404 = SURFACE_STYLE_USAGE(.BOTH.,#202405); +#202405 = SURFACE_SIDE_STYLE('',(#202406)); +#202406 = SURFACE_STYLE_FILL_AREA(#202407); +#202407 = FILL_AREA_STYLE('',(#202408)); +#202408 = FILL_AREA_STYLE_COLOUR('',#198418); +#202409 = OVER_RIDING_STYLED_ITEM('overriding color',(#202410),#134849, + #198353); +#202410 = PRESENTATION_STYLE_ASSIGNMENT((#202411)); +#202411 = SURFACE_STYLE_USAGE(.BOTH.,#202412); +#202412 = SURFACE_SIDE_STYLE('',(#202413)); +#202413 = SURFACE_STYLE_FILL_AREA(#202414); +#202414 = FILL_AREA_STYLE('',(#202415)); +#202415 = FILL_AREA_STYLE_COLOUR('',#198418); +#202416 = OVER_RIDING_STYLED_ITEM('overriding color',(#202417),#134856, + #198353); +#202417 = PRESENTATION_STYLE_ASSIGNMENT((#202418)); +#202418 = SURFACE_STYLE_USAGE(.BOTH.,#202419); +#202419 = SURFACE_SIDE_STYLE('',(#202420)); +#202420 = SURFACE_STYLE_FILL_AREA(#202421); +#202421 = FILL_AREA_STYLE('',(#202422)); +#202422 = FILL_AREA_STYLE_COLOUR('',#198418); +#202423 = OVER_RIDING_STYLED_ITEM('overriding color',(#202424),#134965, + #198353); +#202424 = PRESENTATION_STYLE_ASSIGNMENT((#202425)); +#202425 = SURFACE_STYLE_USAGE(.BOTH.,#202426); +#202426 = SURFACE_SIDE_STYLE('',(#202427)); +#202427 = SURFACE_STYLE_FILL_AREA(#202428); +#202428 = FILL_AREA_STYLE('',(#202429)); +#202429 = FILL_AREA_STYLE_COLOUR('',#198418); +#202430 = OVER_RIDING_STYLED_ITEM('overriding color',(#202431),#135069, + #198353); +#202431 = PRESENTATION_STYLE_ASSIGNMENT((#202432)); +#202432 = SURFACE_STYLE_USAGE(.BOTH.,#202433); +#202433 = SURFACE_SIDE_STYLE('',(#202434)); +#202434 = SURFACE_STYLE_FILL_AREA(#202435); +#202435 = FILL_AREA_STYLE('',(#202436)); +#202436 = FILL_AREA_STYLE_COLOUR('',#198418); +#202437 = OVER_RIDING_STYLED_ITEM('overriding color',(#202438),#135148, + #198353); +#202438 = PRESENTATION_STYLE_ASSIGNMENT((#202439)); +#202439 = SURFACE_STYLE_USAGE(.BOTH.,#202440); +#202440 = SURFACE_SIDE_STYLE('',(#202441)); +#202441 = SURFACE_STYLE_FILL_AREA(#202442); +#202442 = FILL_AREA_STYLE('',(#202443)); +#202443 = FILL_AREA_STYLE_COLOUR('',#198418); +#202444 = OVER_RIDING_STYLED_ITEM('overriding color',(#202445),#135273, + #198353); +#202445 = PRESENTATION_STYLE_ASSIGNMENT((#202446)); +#202446 = SURFACE_STYLE_USAGE(.BOTH.,#202447); +#202447 = SURFACE_SIDE_STYLE('',(#202448)); +#202448 = SURFACE_STYLE_FILL_AREA(#202449); +#202449 = FILL_AREA_STYLE('',(#202450)); +#202450 = FILL_AREA_STYLE_COLOUR('',#198418); +#202451 = OVER_RIDING_STYLED_ITEM('overriding color',(#202452),#135348, + #198353); +#202452 = PRESENTATION_STYLE_ASSIGNMENT((#202453)); +#202453 = SURFACE_STYLE_USAGE(.BOTH.,#202454); +#202454 = SURFACE_SIDE_STYLE('',(#202455)); +#202455 = SURFACE_STYLE_FILL_AREA(#202456); +#202456 = FILL_AREA_STYLE('',(#202457)); +#202457 = FILL_AREA_STYLE_COLOUR('',#198418); +#202458 = OVER_RIDING_STYLED_ITEM('overriding color',(#202459),#135423, + #198353); +#202459 = PRESENTATION_STYLE_ASSIGNMENT((#202460)); +#202460 = SURFACE_STYLE_USAGE(.BOTH.,#202461); +#202461 = SURFACE_SIDE_STYLE('',(#202462)); +#202462 = SURFACE_STYLE_FILL_AREA(#202463); +#202463 = FILL_AREA_STYLE('',(#202464)); +#202464 = FILL_AREA_STYLE_COLOUR('',#198418); +#202465 = OVER_RIDING_STYLED_ITEM('overriding color',(#202466),#135543, + #198353); +#202466 = PRESENTATION_STYLE_ASSIGNMENT((#202467)); +#202467 = SURFACE_STYLE_USAGE(.BOTH.,#202468); +#202468 = SURFACE_SIDE_STYLE('',(#202469)); +#202469 = SURFACE_STYLE_FILL_AREA(#202470); +#202470 = FILL_AREA_STYLE('',(#202471)); +#202471 = FILL_AREA_STYLE_COLOUR('',#198418); +#202472 = OVER_RIDING_STYLED_ITEM('overriding color',(#202473),#135617, + #198353); +#202473 = PRESENTATION_STYLE_ASSIGNMENT((#202474)); +#202474 = SURFACE_STYLE_USAGE(.BOTH.,#202475); +#202475 = SURFACE_SIDE_STYLE('',(#202476)); +#202476 = SURFACE_STYLE_FILL_AREA(#202477); +#202477 = FILL_AREA_STYLE('',(#202478)); +#202478 = FILL_AREA_STYLE_COLOUR('',#198418); +#202479 = OVER_RIDING_STYLED_ITEM('overriding color',(#202480),#135664, + #198353); +#202480 = PRESENTATION_STYLE_ASSIGNMENT((#202481)); +#202481 = SURFACE_STYLE_USAGE(.BOTH.,#202482); +#202482 = SURFACE_SIDE_STYLE('',(#202483)); +#202483 = SURFACE_STYLE_FILL_AREA(#202484); +#202484 = FILL_AREA_STYLE('',(#202485)); +#202485 = FILL_AREA_STYLE_COLOUR('',#198418); +#202486 = OVER_RIDING_STYLED_ITEM('overriding color',(#202487),#135719, + #198353); +#202487 = PRESENTATION_STYLE_ASSIGNMENT((#202488)); +#202488 = SURFACE_STYLE_USAGE(.BOTH.,#202489); +#202489 = SURFACE_SIDE_STYLE('',(#202490)); +#202490 = SURFACE_STYLE_FILL_AREA(#202491); +#202491 = FILL_AREA_STYLE('',(#202492)); +#202492 = FILL_AREA_STYLE_COLOUR('',#198418); +#202493 = OVER_RIDING_STYLED_ITEM('overriding color',(#202494),#135746, + #198353); +#202494 = PRESENTATION_STYLE_ASSIGNMENT((#202495)); +#202495 = SURFACE_STYLE_USAGE(.BOTH.,#202496); +#202496 = SURFACE_SIDE_STYLE('',(#202497)); +#202497 = SURFACE_STYLE_FILL_AREA(#202498); +#202498 = FILL_AREA_STYLE('',(#202499)); +#202499 = FILL_AREA_STYLE_COLOUR('',#198418); +#202500 = OVER_RIDING_STYLED_ITEM('overriding color',(#202501),#135781, + #198353); +#202501 = PRESENTATION_STYLE_ASSIGNMENT((#202502)); +#202502 = SURFACE_STYLE_USAGE(.BOTH.,#202503); +#202503 = SURFACE_SIDE_STYLE('',(#202504)); +#202504 = SURFACE_STYLE_FILL_AREA(#202505); +#202505 = FILL_AREA_STYLE('',(#202506)); +#202506 = FILL_AREA_STYLE_COLOUR('',#198418); +#202507 = OVER_RIDING_STYLED_ITEM('overriding color',(#202508),#135788, + #198353); +#202508 = PRESENTATION_STYLE_ASSIGNMENT((#202509)); +#202509 = SURFACE_STYLE_USAGE(.BOTH.,#202510); +#202510 = SURFACE_SIDE_STYLE('',(#202511)); +#202511 = SURFACE_STYLE_FILL_AREA(#202512); +#202512 = FILL_AREA_STYLE('',(#202513)); +#202513 = FILL_AREA_STYLE_COLOUR('',#198418); +#202514 = OVER_RIDING_STYLED_ITEM('overriding color',(#202515),#135897, + #198353); +#202515 = PRESENTATION_STYLE_ASSIGNMENT((#202516)); +#202516 = SURFACE_STYLE_USAGE(.BOTH.,#202517); +#202517 = SURFACE_SIDE_STYLE('',(#202518)); +#202518 = SURFACE_STYLE_FILL_AREA(#202519); +#202519 = FILL_AREA_STYLE('',(#202520)); +#202520 = FILL_AREA_STYLE_COLOUR('',#198418); +#202521 = OVER_RIDING_STYLED_ITEM('overriding color',(#202522),#136001, + #198353); +#202522 = PRESENTATION_STYLE_ASSIGNMENT((#202523)); +#202523 = SURFACE_STYLE_USAGE(.BOTH.,#202524); +#202524 = SURFACE_SIDE_STYLE('',(#202525)); +#202525 = SURFACE_STYLE_FILL_AREA(#202526); +#202526 = FILL_AREA_STYLE('',(#202527)); +#202527 = FILL_AREA_STYLE_COLOUR('',#198418); +#202528 = OVER_RIDING_STYLED_ITEM('overriding color',(#202529),#136080, + #198353); +#202529 = PRESENTATION_STYLE_ASSIGNMENT((#202530)); +#202530 = SURFACE_STYLE_USAGE(.BOTH.,#202531); +#202531 = SURFACE_SIDE_STYLE('',(#202532)); +#202532 = SURFACE_STYLE_FILL_AREA(#202533); +#202533 = FILL_AREA_STYLE('',(#202534)); +#202534 = FILL_AREA_STYLE_COLOUR('',#198418); +#202535 = OVER_RIDING_STYLED_ITEM('overriding color',(#202536),#136205, + #198353); +#202536 = PRESENTATION_STYLE_ASSIGNMENT((#202537)); +#202537 = SURFACE_STYLE_USAGE(.BOTH.,#202538); +#202538 = SURFACE_SIDE_STYLE('',(#202539)); +#202539 = SURFACE_STYLE_FILL_AREA(#202540); +#202540 = FILL_AREA_STYLE('',(#202541)); +#202541 = FILL_AREA_STYLE_COLOUR('',#198418); +#202542 = OVER_RIDING_STYLED_ITEM('overriding color',(#202543),#136280, + #198353); +#202543 = PRESENTATION_STYLE_ASSIGNMENT((#202544)); +#202544 = SURFACE_STYLE_USAGE(.BOTH.,#202545); +#202545 = SURFACE_SIDE_STYLE('',(#202546)); +#202546 = SURFACE_STYLE_FILL_AREA(#202547); +#202547 = FILL_AREA_STYLE('',(#202548)); +#202548 = FILL_AREA_STYLE_COLOUR('',#198418); +#202549 = OVER_RIDING_STYLED_ITEM('overriding color',(#202550),#136355, + #198353); +#202550 = PRESENTATION_STYLE_ASSIGNMENT((#202551)); +#202551 = SURFACE_STYLE_USAGE(.BOTH.,#202552); +#202552 = SURFACE_SIDE_STYLE('',(#202553)); +#202553 = SURFACE_STYLE_FILL_AREA(#202554); +#202554 = FILL_AREA_STYLE('',(#202555)); +#202555 = FILL_AREA_STYLE_COLOUR('',#198418); +#202556 = OVER_RIDING_STYLED_ITEM('overriding color',(#202557),#136475, + #198353); +#202557 = PRESENTATION_STYLE_ASSIGNMENT((#202558)); +#202558 = SURFACE_STYLE_USAGE(.BOTH.,#202559); +#202559 = SURFACE_SIDE_STYLE('',(#202560)); +#202560 = SURFACE_STYLE_FILL_AREA(#202561); +#202561 = FILL_AREA_STYLE('',(#202562)); +#202562 = FILL_AREA_STYLE_COLOUR('',#198418); +#202563 = OVER_RIDING_STYLED_ITEM('overriding color',(#202564),#136549, + #198353); +#202564 = PRESENTATION_STYLE_ASSIGNMENT((#202565)); +#202565 = SURFACE_STYLE_USAGE(.BOTH.,#202566); +#202566 = SURFACE_SIDE_STYLE('',(#202567)); +#202567 = SURFACE_STYLE_FILL_AREA(#202568); +#202568 = FILL_AREA_STYLE('',(#202569)); +#202569 = FILL_AREA_STYLE_COLOUR('',#198418); +#202570 = OVER_RIDING_STYLED_ITEM('overriding color',(#202571),#136596, + #198353); +#202571 = PRESENTATION_STYLE_ASSIGNMENT((#202572)); +#202572 = SURFACE_STYLE_USAGE(.BOTH.,#202573); +#202573 = SURFACE_SIDE_STYLE('',(#202574)); +#202574 = SURFACE_STYLE_FILL_AREA(#202575); +#202575 = FILL_AREA_STYLE('',(#202576)); +#202576 = FILL_AREA_STYLE_COLOUR('',#198418); +#202577 = OVER_RIDING_STYLED_ITEM('overriding color',(#202578),#136651, + #198353); +#202578 = PRESENTATION_STYLE_ASSIGNMENT((#202579)); +#202579 = SURFACE_STYLE_USAGE(.BOTH.,#202580); +#202580 = SURFACE_SIDE_STYLE('',(#202581)); +#202581 = SURFACE_STYLE_FILL_AREA(#202582); +#202582 = FILL_AREA_STYLE('',(#202583)); +#202583 = FILL_AREA_STYLE_COLOUR('',#198418); +#202584 = OVER_RIDING_STYLED_ITEM('overriding color',(#202585),#136678, + #198353); +#202585 = PRESENTATION_STYLE_ASSIGNMENT((#202586)); +#202586 = SURFACE_STYLE_USAGE(.BOTH.,#202587); +#202587 = SURFACE_SIDE_STYLE('',(#202588)); +#202588 = SURFACE_STYLE_FILL_AREA(#202589); +#202589 = FILL_AREA_STYLE('',(#202590)); +#202590 = FILL_AREA_STYLE_COLOUR('',#198418); +#202591 = OVER_RIDING_STYLED_ITEM('overriding color',(#202592),#136713, + #198353); +#202592 = PRESENTATION_STYLE_ASSIGNMENT((#202593)); +#202593 = SURFACE_STYLE_USAGE(.BOTH.,#202594); +#202594 = SURFACE_SIDE_STYLE('',(#202595)); +#202595 = SURFACE_STYLE_FILL_AREA(#202596); +#202596 = FILL_AREA_STYLE('',(#202597)); +#202597 = FILL_AREA_STYLE_COLOUR('',#198418); +#202598 = OVER_RIDING_STYLED_ITEM('overriding color',(#202599),#136720, + #198353); +#202599 = PRESENTATION_STYLE_ASSIGNMENT((#202600)); +#202600 = SURFACE_STYLE_USAGE(.BOTH.,#202601); +#202601 = SURFACE_SIDE_STYLE('',(#202602)); +#202602 = SURFACE_STYLE_FILL_AREA(#202603); +#202603 = FILL_AREA_STYLE('',(#202604)); +#202604 = FILL_AREA_STYLE_COLOUR('',#198418); +#202605 = OVER_RIDING_STYLED_ITEM('overriding color',(#202606),#136829, + #198353); +#202606 = PRESENTATION_STYLE_ASSIGNMENT((#202607)); +#202607 = SURFACE_STYLE_USAGE(.BOTH.,#202608); +#202608 = SURFACE_SIDE_STYLE('',(#202609)); +#202609 = SURFACE_STYLE_FILL_AREA(#202610); +#202610 = FILL_AREA_STYLE('',(#202611)); +#202611 = FILL_AREA_STYLE_COLOUR('',#198418); +#202612 = OVER_RIDING_STYLED_ITEM('overriding color',(#202613),#136933, + #198353); +#202613 = PRESENTATION_STYLE_ASSIGNMENT((#202614)); +#202614 = SURFACE_STYLE_USAGE(.BOTH.,#202615); +#202615 = SURFACE_SIDE_STYLE('',(#202616)); +#202616 = SURFACE_STYLE_FILL_AREA(#202617); +#202617 = FILL_AREA_STYLE('',(#202618)); +#202618 = FILL_AREA_STYLE_COLOUR('',#198418); +#202619 = OVER_RIDING_STYLED_ITEM('overriding color',(#202620),#137012, + #198353); +#202620 = PRESENTATION_STYLE_ASSIGNMENT((#202621)); +#202621 = SURFACE_STYLE_USAGE(.BOTH.,#202622); +#202622 = SURFACE_SIDE_STYLE('',(#202623)); +#202623 = SURFACE_STYLE_FILL_AREA(#202624); +#202624 = FILL_AREA_STYLE('',(#202625)); +#202625 = FILL_AREA_STYLE_COLOUR('',#198418); +#202626 = OVER_RIDING_STYLED_ITEM('overriding color',(#202627),#137137, + #198353); +#202627 = PRESENTATION_STYLE_ASSIGNMENT((#202628)); +#202628 = SURFACE_STYLE_USAGE(.BOTH.,#202629); +#202629 = SURFACE_SIDE_STYLE('',(#202630)); +#202630 = SURFACE_STYLE_FILL_AREA(#202631); +#202631 = FILL_AREA_STYLE('',(#202632)); +#202632 = FILL_AREA_STYLE_COLOUR('',#198418); +#202633 = OVER_RIDING_STYLED_ITEM('overriding color',(#202634),#137212, + #198353); +#202634 = PRESENTATION_STYLE_ASSIGNMENT((#202635)); +#202635 = SURFACE_STYLE_USAGE(.BOTH.,#202636); +#202636 = SURFACE_SIDE_STYLE('',(#202637)); +#202637 = SURFACE_STYLE_FILL_AREA(#202638); +#202638 = FILL_AREA_STYLE('',(#202639)); +#202639 = FILL_AREA_STYLE_COLOUR('',#198418); +#202640 = OVER_RIDING_STYLED_ITEM('overriding color',(#202641),#137287, + #198353); +#202641 = PRESENTATION_STYLE_ASSIGNMENT((#202642)); +#202642 = SURFACE_STYLE_USAGE(.BOTH.,#202643); +#202643 = SURFACE_SIDE_STYLE('',(#202644)); +#202644 = SURFACE_STYLE_FILL_AREA(#202645); +#202645 = FILL_AREA_STYLE('',(#202646)); +#202646 = FILL_AREA_STYLE_COLOUR('',#198418); +#202647 = OVER_RIDING_STYLED_ITEM('overriding color',(#202648),#137361, + #198353); +#202648 = PRESENTATION_STYLE_ASSIGNMENT((#202649)); +#202649 = SURFACE_STYLE_USAGE(.BOTH.,#202650); +#202650 = SURFACE_SIDE_STYLE('',(#202651)); +#202651 = SURFACE_STYLE_FILL_AREA(#202652); +#202652 = FILL_AREA_STYLE('',(#202653)); +#202653 = FILL_AREA_STYLE_COLOUR('',#198418); +#202654 = OVER_RIDING_STYLED_ITEM('overriding color',(#202655),#137435, + #198353); +#202655 = PRESENTATION_STYLE_ASSIGNMENT((#202656)); +#202656 = SURFACE_STYLE_USAGE(.BOTH.,#202657); +#202657 = SURFACE_SIDE_STYLE('',(#202658)); +#202658 = SURFACE_STYLE_FILL_AREA(#202659); +#202659 = FILL_AREA_STYLE('',(#202660)); +#202660 = FILL_AREA_STYLE_COLOUR('',#198418); +#202661 = OVER_RIDING_STYLED_ITEM('overriding color',(#202662),#137482, + #198353); +#202662 = PRESENTATION_STYLE_ASSIGNMENT((#202663)); +#202663 = SURFACE_STYLE_USAGE(.BOTH.,#202664); +#202664 = SURFACE_SIDE_STYLE('',(#202665)); +#202665 = SURFACE_STYLE_FILL_AREA(#202666); +#202666 = FILL_AREA_STYLE('',(#202667)); +#202667 = FILL_AREA_STYLE_COLOUR('',#198418); +#202668 = OVER_RIDING_STYLED_ITEM('overriding color',(#202669),#137537, + #198353); +#202669 = PRESENTATION_STYLE_ASSIGNMENT((#202670)); +#202670 = SURFACE_STYLE_USAGE(.BOTH.,#202671); +#202671 = SURFACE_SIDE_STYLE('',(#202672)); +#202672 = SURFACE_STYLE_FILL_AREA(#202673); +#202673 = FILL_AREA_STYLE('',(#202674)); +#202674 = FILL_AREA_STYLE_COLOUR('',#198418); +#202675 = OVER_RIDING_STYLED_ITEM('overriding color',(#202676),#137564, + #198353); +#202676 = PRESENTATION_STYLE_ASSIGNMENT((#202677)); +#202677 = SURFACE_STYLE_USAGE(.BOTH.,#202678); +#202678 = SURFACE_SIDE_STYLE('',(#202679)); +#202679 = SURFACE_STYLE_FILL_AREA(#202680); +#202680 = FILL_AREA_STYLE('',(#202681)); +#202681 = FILL_AREA_STYLE_COLOUR('',#198418); +#202682 = OVER_RIDING_STYLED_ITEM('overriding color',(#202683),#137599, + #198353); +#202683 = PRESENTATION_STYLE_ASSIGNMENT((#202684)); +#202684 = SURFACE_STYLE_USAGE(.BOTH.,#202685); +#202685 = SURFACE_SIDE_STYLE('',(#202686)); +#202686 = SURFACE_STYLE_FILL_AREA(#202687); +#202687 = FILL_AREA_STYLE('',(#202688)); +#202688 = FILL_AREA_STYLE_COLOUR('',#198418); +#202689 = OVER_RIDING_STYLED_ITEM('overriding color',(#202690),#137606, + #198353); +#202690 = PRESENTATION_STYLE_ASSIGNMENT((#202691)); +#202691 = SURFACE_STYLE_USAGE(.BOTH.,#202692); +#202692 = SURFACE_SIDE_STYLE('',(#202693)); +#202693 = SURFACE_STYLE_FILL_AREA(#202694); +#202694 = FILL_AREA_STYLE('',(#202695)); +#202695 = FILL_AREA_STYLE_COLOUR('',#198418); +#202696 = OVER_RIDING_STYLED_ITEM('overriding color',(#202697),#137715, + #198353); +#202697 = PRESENTATION_STYLE_ASSIGNMENT((#202698)); +#202698 = SURFACE_STYLE_USAGE(.BOTH.,#202699); +#202699 = SURFACE_SIDE_STYLE('',(#202700)); +#202700 = SURFACE_STYLE_FILL_AREA(#202701); +#202701 = FILL_AREA_STYLE('',(#202702)); +#202702 = FILL_AREA_STYLE_COLOUR('',#198418); +#202703 = OVER_RIDING_STYLED_ITEM('overriding color',(#202704),#137819, + #198353); +#202704 = PRESENTATION_STYLE_ASSIGNMENT((#202705)); +#202705 = SURFACE_STYLE_USAGE(.BOTH.,#202706); +#202706 = SURFACE_SIDE_STYLE('',(#202707)); +#202707 = SURFACE_STYLE_FILL_AREA(#202708); +#202708 = FILL_AREA_STYLE('',(#202709)); +#202709 = FILL_AREA_STYLE_COLOUR('',#198418); +#202710 = OVER_RIDING_STYLED_ITEM('overriding color',(#202711),#137898, + #198353); +#202711 = PRESENTATION_STYLE_ASSIGNMENT((#202712)); +#202712 = SURFACE_STYLE_USAGE(.BOTH.,#202713); +#202713 = SURFACE_SIDE_STYLE('',(#202714)); +#202714 = SURFACE_STYLE_FILL_AREA(#202715); +#202715 = FILL_AREA_STYLE('',(#202716)); +#202716 = FILL_AREA_STYLE_COLOUR('',#198418); +#202717 = OVER_RIDING_STYLED_ITEM('overriding color',(#202718),#138023, + #198353); +#202718 = PRESENTATION_STYLE_ASSIGNMENT((#202719)); +#202719 = SURFACE_STYLE_USAGE(.BOTH.,#202720); +#202720 = SURFACE_SIDE_STYLE('',(#202721)); +#202721 = SURFACE_STYLE_FILL_AREA(#202722); +#202722 = FILL_AREA_STYLE('',(#202723)); +#202723 = FILL_AREA_STYLE_COLOUR('',#198418); +#202724 = OVER_RIDING_STYLED_ITEM('overriding color',(#202725),#138098, + #198353); +#202725 = PRESENTATION_STYLE_ASSIGNMENT((#202726)); +#202726 = SURFACE_STYLE_USAGE(.BOTH.,#202727); +#202727 = SURFACE_SIDE_STYLE('',(#202728)); +#202728 = SURFACE_STYLE_FILL_AREA(#202729); +#202729 = FILL_AREA_STYLE('',(#202730)); +#202730 = FILL_AREA_STYLE_COLOUR('',#198418); +#202731 = OVER_RIDING_STYLED_ITEM('overriding color',(#202732),#138173, + #198353); +#202732 = PRESENTATION_STYLE_ASSIGNMENT((#202733)); +#202733 = SURFACE_STYLE_USAGE(.BOTH.,#202734); +#202734 = SURFACE_SIDE_STYLE('',(#202735)); +#202735 = SURFACE_STYLE_FILL_AREA(#202736); +#202736 = FILL_AREA_STYLE('',(#202737)); +#202737 = FILL_AREA_STYLE_COLOUR('',#198418); +#202738 = OVER_RIDING_STYLED_ITEM('overriding color',(#202739),#138247, + #198353); +#202739 = PRESENTATION_STYLE_ASSIGNMENT((#202740)); +#202740 = SURFACE_STYLE_USAGE(.BOTH.,#202741); +#202741 = SURFACE_SIDE_STYLE('',(#202742)); +#202742 = SURFACE_STYLE_FILL_AREA(#202743); +#202743 = FILL_AREA_STYLE('',(#202744)); +#202744 = FILL_AREA_STYLE_COLOUR('',#198418); +#202745 = OVER_RIDING_STYLED_ITEM('overriding color',(#202746),#138321, + #198353); +#202746 = PRESENTATION_STYLE_ASSIGNMENT((#202747)); +#202747 = SURFACE_STYLE_USAGE(.BOTH.,#202748); +#202748 = SURFACE_SIDE_STYLE('',(#202749)); +#202749 = SURFACE_STYLE_FILL_AREA(#202750); +#202750 = FILL_AREA_STYLE('',(#202751)); +#202751 = FILL_AREA_STYLE_COLOUR('',#198418); +#202752 = OVER_RIDING_STYLED_ITEM('overriding color',(#202753),#138368, + #198353); +#202753 = PRESENTATION_STYLE_ASSIGNMENT((#202754)); +#202754 = SURFACE_STYLE_USAGE(.BOTH.,#202755); +#202755 = SURFACE_SIDE_STYLE('',(#202756)); +#202756 = SURFACE_STYLE_FILL_AREA(#202757); +#202757 = FILL_AREA_STYLE('',(#202758)); +#202758 = FILL_AREA_STYLE_COLOUR('',#198418); +#202759 = OVER_RIDING_STYLED_ITEM('overriding color',(#202760),#138423, + #198353); +#202760 = PRESENTATION_STYLE_ASSIGNMENT((#202761)); +#202761 = SURFACE_STYLE_USAGE(.BOTH.,#202762); +#202762 = SURFACE_SIDE_STYLE('',(#202763)); +#202763 = SURFACE_STYLE_FILL_AREA(#202764); +#202764 = FILL_AREA_STYLE('',(#202765)); +#202765 = FILL_AREA_STYLE_COLOUR('',#198418); +#202766 = OVER_RIDING_STYLED_ITEM('overriding color',(#202767),#138450, + #198353); +#202767 = PRESENTATION_STYLE_ASSIGNMENT((#202768)); +#202768 = SURFACE_STYLE_USAGE(.BOTH.,#202769); +#202769 = SURFACE_SIDE_STYLE('',(#202770)); +#202770 = SURFACE_STYLE_FILL_AREA(#202771); +#202771 = FILL_AREA_STYLE('',(#202772)); +#202772 = FILL_AREA_STYLE_COLOUR('',#198418); +#202773 = OVER_RIDING_STYLED_ITEM('overriding color',(#202774),#138485, + #198353); +#202774 = PRESENTATION_STYLE_ASSIGNMENT((#202775)); +#202775 = SURFACE_STYLE_USAGE(.BOTH.,#202776); +#202776 = SURFACE_SIDE_STYLE('',(#202777)); +#202777 = SURFACE_STYLE_FILL_AREA(#202778); +#202778 = FILL_AREA_STYLE('',(#202779)); +#202779 = FILL_AREA_STYLE_COLOUR('',#198418); +#202780 = OVER_RIDING_STYLED_ITEM('overriding color',(#202781),#138492, + #198353); +#202781 = PRESENTATION_STYLE_ASSIGNMENT((#202782)); +#202782 = SURFACE_STYLE_USAGE(.BOTH.,#202783); +#202783 = SURFACE_SIDE_STYLE('',(#202784)); +#202784 = SURFACE_STYLE_FILL_AREA(#202785); +#202785 = FILL_AREA_STYLE('',(#202786)); +#202786 = FILL_AREA_STYLE_COLOUR('',#198418); +#202787 = OVER_RIDING_STYLED_ITEM('overriding color',(#202788),#138601, + #198353); +#202788 = PRESENTATION_STYLE_ASSIGNMENT((#202789)); +#202789 = SURFACE_STYLE_USAGE(.BOTH.,#202790); +#202790 = SURFACE_SIDE_STYLE('',(#202791)); +#202791 = SURFACE_STYLE_FILL_AREA(#202792); +#202792 = FILL_AREA_STYLE('',(#202793)); +#202793 = FILL_AREA_STYLE_COLOUR('',#198418); +#202794 = OVER_RIDING_STYLED_ITEM('overriding color',(#202795),#138705, + #198353); +#202795 = PRESENTATION_STYLE_ASSIGNMENT((#202796)); +#202796 = SURFACE_STYLE_USAGE(.BOTH.,#202797); +#202797 = SURFACE_SIDE_STYLE('',(#202798)); +#202798 = SURFACE_STYLE_FILL_AREA(#202799); +#202799 = FILL_AREA_STYLE('',(#202800)); +#202800 = FILL_AREA_STYLE_COLOUR('',#198418); +#202801 = OVER_RIDING_STYLED_ITEM('overriding color',(#202802),#138784, + #198353); +#202802 = PRESENTATION_STYLE_ASSIGNMENT((#202803)); +#202803 = SURFACE_STYLE_USAGE(.BOTH.,#202804); +#202804 = SURFACE_SIDE_STYLE('',(#202805)); +#202805 = SURFACE_STYLE_FILL_AREA(#202806); +#202806 = FILL_AREA_STYLE('',(#202807)); +#202807 = FILL_AREA_STYLE_COLOUR('',#198418); +#202808 = OVER_RIDING_STYLED_ITEM('overriding color',(#202809),#138863, + #198353); +#202809 = PRESENTATION_STYLE_ASSIGNMENT((#202810)); +#202810 = SURFACE_STYLE_USAGE(.BOTH.,#202811); +#202811 = SURFACE_SIDE_STYLE('',(#202812)); +#202812 = SURFACE_STYLE_FILL_AREA(#202813); +#202813 = FILL_AREA_STYLE('',(#202814)); +#202814 = FILL_AREA_STYLE_COLOUR('',#198418); +#202815 = OVER_RIDING_STYLED_ITEM('overriding color',(#202816),#138938, + #198353); +#202816 = PRESENTATION_STYLE_ASSIGNMENT((#202817)); +#202817 = SURFACE_STYLE_USAGE(.BOTH.,#202818); +#202818 = SURFACE_SIDE_STYLE('',(#202819)); +#202819 = SURFACE_STYLE_FILL_AREA(#202820); +#202820 = FILL_AREA_STYLE('',(#202821)); +#202821 = FILL_AREA_STYLE_COLOUR('',#198418); +#202822 = OVER_RIDING_STYLED_ITEM('overriding color',(#202823),#139013, + #198353); +#202823 = PRESENTATION_STYLE_ASSIGNMENT((#202824)); +#202824 = SURFACE_STYLE_USAGE(.BOTH.,#202825); +#202825 = SURFACE_SIDE_STYLE('',(#202826)); +#202826 = SURFACE_STYLE_FILL_AREA(#202827); +#202827 = FILL_AREA_STYLE('',(#202828)); +#202828 = FILL_AREA_STYLE_COLOUR('',#198418); +#202829 = OVER_RIDING_STYLED_ITEM('overriding color',(#202830),#139087, + #198353); +#202830 = PRESENTATION_STYLE_ASSIGNMENT((#202831)); +#202831 = SURFACE_STYLE_USAGE(.BOTH.,#202832); +#202832 = SURFACE_SIDE_STYLE('',(#202833)); +#202833 = SURFACE_STYLE_FILL_AREA(#202834); +#202834 = FILL_AREA_STYLE('',(#202835)); +#202835 = FILL_AREA_STYLE_COLOUR('',#198418); +#202836 = OVER_RIDING_STYLED_ITEM('overriding color',(#202837),#139161, + #198353); +#202837 = PRESENTATION_STYLE_ASSIGNMENT((#202838)); +#202838 = SURFACE_STYLE_USAGE(.BOTH.,#202839); +#202839 = SURFACE_SIDE_STYLE('',(#202840)); +#202840 = SURFACE_STYLE_FILL_AREA(#202841); +#202841 = FILL_AREA_STYLE('',(#202842)); +#202842 = FILL_AREA_STYLE_COLOUR('',#198418); +#202843 = OVER_RIDING_STYLED_ITEM('overriding color',(#202844),#139236, + #198353); +#202844 = PRESENTATION_STYLE_ASSIGNMENT((#202845)); +#202845 = SURFACE_STYLE_USAGE(.BOTH.,#202846); +#202846 = SURFACE_SIDE_STYLE('',(#202847)); +#202847 = SURFACE_STYLE_FILL_AREA(#202848); +#202848 = FILL_AREA_STYLE('',(#202849)); +#202849 = FILL_AREA_STYLE_COLOUR('',#198418); +#202850 = OVER_RIDING_STYLED_ITEM('overriding color',(#202851),#139263, + #198353); +#202851 = PRESENTATION_STYLE_ASSIGNMENT((#202852)); +#202852 = SURFACE_STYLE_USAGE(.BOTH.,#202853); +#202853 = SURFACE_SIDE_STYLE('',(#202854)); +#202854 = SURFACE_STYLE_FILL_AREA(#202855); +#202855 = FILL_AREA_STYLE('',(#202856)); +#202856 = FILL_AREA_STYLE_COLOUR('',#198418); +#202857 = OVER_RIDING_STYLED_ITEM('overriding color',(#202858),#139318, + #198353); +#202858 = PRESENTATION_STYLE_ASSIGNMENT((#202859)); +#202859 = SURFACE_STYLE_USAGE(.BOTH.,#202860); +#202860 = SURFACE_SIDE_STYLE('',(#202861)); +#202861 = SURFACE_STYLE_FILL_AREA(#202862); +#202862 = FILL_AREA_STYLE('',(#202863)); +#202863 = FILL_AREA_STYLE_COLOUR('',#198418); +#202864 = OVER_RIDING_STYLED_ITEM('overriding color',(#202865),#139325, + #198353); +#202865 = PRESENTATION_STYLE_ASSIGNMENT((#202866)); +#202866 = SURFACE_STYLE_USAGE(.BOTH.,#202867); +#202867 = SURFACE_SIDE_STYLE('',(#202868)); +#202868 = SURFACE_STYLE_FILL_AREA(#202869); +#202869 = FILL_AREA_STYLE('',(#202870)); +#202870 = FILL_AREA_STYLE_COLOUR('',#198418); +#202871 = OVER_RIDING_STYLED_ITEM('overriding color',(#202872),#139332, + #198353); +#202872 = PRESENTATION_STYLE_ASSIGNMENT((#202873)); +#202873 = SURFACE_STYLE_USAGE(.BOTH.,#202874); +#202874 = SURFACE_SIDE_STYLE('',(#202875)); +#202875 = SURFACE_STYLE_FILL_AREA(#202876); +#202876 = FILL_AREA_STYLE('',(#202877)); +#202877 = FILL_AREA_STYLE_COLOUR('',#198418); +#202878 = OVER_RIDING_STYLED_ITEM('overriding color',(#202879),#139441, + #198353); +#202879 = PRESENTATION_STYLE_ASSIGNMENT((#202880)); +#202880 = SURFACE_STYLE_USAGE(.BOTH.,#202881); +#202881 = SURFACE_SIDE_STYLE('',(#202882)); +#202882 = SURFACE_STYLE_FILL_AREA(#202883); +#202883 = FILL_AREA_STYLE('',(#202884)); +#202884 = FILL_AREA_STYLE_COLOUR('',#198418); +#202885 = OVER_RIDING_STYLED_ITEM('overriding color',(#202886),#139545, + #198353); +#202886 = PRESENTATION_STYLE_ASSIGNMENT((#202887)); +#202887 = SURFACE_STYLE_USAGE(.BOTH.,#202888); +#202888 = SURFACE_SIDE_STYLE('',(#202889)); +#202889 = SURFACE_STYLE_FILL_AREA(#202890); +#202890 = FILL_AREA_STYLE('',(#202891)); +#202891 = FILL_AREA_STYLE_COLOUR('',#198418); +#202892 = OVER_RIDING_STYLED_ITEM('overriding color',(#202893),#139670, + #198353); +#202893 = PRESENTATION_STYLE_ASSIGNMENT((#202894)); +#202894 = SURFACE_STYLE_USAGE(.BOTH.,#202895); +#202895 = SURFACE_SIDE_STYLE('',(#202896)); +#202896 = SURFACE_STYLE_FILL_AREA(#202897); +#202897 = FILL_AREA_STYLE('',(#202898)); +#202898 = FILL_AREA_STYLE_COLOUR('',#198418); +#202899 = OVER_RIDING_STYLED_ITEM('overriding color',(#202900),#139749, + #198353); +#202900 = PRESENTATION_STYLE_ASSIGNMENT((#202901)); +#202901 = SURFACE_STYLE_USAGE(.BOTH.,#202902); +#202902 = SURFACE_SIDE_STYLE('',(#202903)); +#202903 = SURFACE_STYLE_FILL_AREA(#202904); +#202904 = FILL_AREA_STYLE('',(#202905)); +#202905 = FILL_AREA_STYLE_COLOUR('',#198418); +#202906 = OVER_RIDING_STYLED_ITEM('overriding color',(#202907),#139824, + #198353); +#202907 = PRESENTATION_STYLE_ASSIGNMENT((#202908)); +#202908 = SURFACE_STYLE_USAGE(.BOTH.,#202909); +#202909 = SURFACE_SIDE_STYLE('',(#202910)); +#202910 = SURFACE_STYLE_FILL_AREA(#202911); +#202911 = FILL_AREA_STYLE('',(#202912)); +#202912 = FILL_AREA_STYLE_COLOUR('',#198418); +#202913 = OVER_RIDING_STYLED_ITEM('overriding color',(#202914),#139899, + #198353); +#202914 = PRESENTATION_STYLE_ASSIGNMENT((#202915)); +#202915 = SURFACE_STYLE_USAGE(.BOTH.,#202916); +#202916 = SURFACE_SIDE_STYLE('',(#202917)); +#202917 = SURFACE_STYLE_FILL_AREA(#202918); +#202918 = FILL_AREA_STYLE('',(#202919)); +#202919 = FILL_AREA_STYLE_COLOUR('',#198418); +#202920 = OVER_RIDING_STYLED_ITEM('overriding color',(#202921),#139973, + #198353); #202921 = PRESENTATION_STYLE_ASSIGNMENT((#202922)); #202922 = SURFACE_STYLE_USAGE(.BOTH.,#202923); #202923 = SURFACE_SIDE_STYLE('',(#202924)); #202924 = SURFACE_STYLE_FILL_AREA(#202925); #202925 = FILL_AREA_STYLE('',(#202926)); -#202926 = FILL_AREA_STYLE_COLOUR('',#202826); -#202927 = OVER_RIDING_STYLED_ITEM('overriding color',(#202928),#167944, - #202920); +#202926 = FILL_AREA_STYLE_COLOUR('',#198418); +#202927 = OVER_RIDING_STYLED_ITEM('overriding color',(#202928),#140093, + #198353); #202928 = PRESENTATION_STYLE_ASSIGNMENT((#202929)); #202929 = SURFACE_STYLE_USAGE(.BOTH.,#202930); #202930 = SURFACE_SIDE_STYLE('',(#202931)); #202931 = SURFACE_STYLE_FILL_AREA(#202932); #202932 = FILL_AREA_STYLE('',(#202933)); -#202933 = FILL_AREA_STYLE_COLOUR('',#201781); -#202934 = OVER_RIDING_STYLED_ITEM('overriding color',(#202935),#168064, - #202920); +#202933 = FILL_AREA_STYLE_COLOUR('',#198418); +#202934 = OVER_RIDING_STYLED_ITEM('overriding color',(#202935),#140140, + #198353); #202935 = PRESENTATION_STYLE_ASSIGNMENT((#202936)); #202936 = SURFACE_STYLE_USAGE(.BOTH.,#202937); #202937 = SURFACE_SIDE_STYLE('',(#202938)); #202938 = SURFACE_STYLE_FILL_AREA(#202939); #202939 = FILL_AREA_STYLE('',(#202940)); -#202940 = FILL_AREA_STYLE_COLOUR('',#201781); -#202941 = OVER_RIDING_STYLED_ITEM('overriding color',(#202942),#168140, - #202920); +#202940 = FILL_AREA_STYLE_COLOUR('',#198418); +#202941 = OVER_RIDING_STYLED_ITEM('overriding color',(#202942),#140195, + #198353); #202942 = PRESENTATION_STYLE_ASSIGNMENT((#202943)); #202943 = SURFACE_STYLE_USAGE(.BOTH.,#202944); #202944 = SURFACE_SIDE_STYLE('',(#202945)); #202945 = SURFACE_STYLE_FILL_AREA(#202946); #202946 = FILL_AREA_STYLE('',(#202947)); -#202947 = FILL_AREA_STYLE_COLOUR('',#201781); -#202948 = OVER_RIDING_STYLED_ITEM('overriding color',(#202949),#168245, - #202920); +#202947 = FILL_AREA_STYLE_COLOUR('',#198418); +#202948 = OVER_RIDING_STYLED_ITEM('overriding color',(#202949),#140222, + #198353); #202949 = PRESENTATION_STYLE_ASSIGNMENT((#202950)); #202950 = SURFACE_STYLE_USAGE(.BOTH.,#202951); #202951 = SURFACE_SIDE_STYLE('',(#202952)); #202952 = SURFACE_STYLE_FILL_AREA(#202953); #202953 = FILL_AREA_STYLE('',(#202954)); -#202954 = FILL_AREA_STYLE_COLOUR('',#201781); -#202955 = OVER_RIDING_STYLED_ITEM('overriding color',(#202956),#168292, - #202920); +#202954 = FILL_AREA_STYLE_COLOUR('',#198418); +#202955 = OVER_RIDING_STYLED_ITEM('overriding color',(#202956),#140257, + #198353); #202956 = PRESENTATION_STYLE_ASSIGNMENT((#202957)); #202957 = SURFACE_STYLE_USAGE(.BOTH.,#202958); #202958 = SURFACE_SIDE_STYLE('',(#202959)); #202959 = SURFACE_STYLE_FILL_AREA(#202960); #202960 = FILL_AREA_STYLE('',(#202961)); -#202961 = FILL_AREA_STYLE_COLOUR('',#201781); -#202962 = OVER_RIDING_STYLED_ITEM('overriding color',(#202963),#168368, - #202920); +#202961 = FILL_AREA_STYLE_COLOUR('',#198418); +#202962 = OVER_RIDING_STYLED_ITEM('overriding color',(#202963),#140264, + #198353); #202963 = PRESENTATION_STYLE_ASSIGNMENT((#202964)); #202964 = SURFACE_STYLE_USAGE(.BOTH.,#202965); #202965 = SURFACE_SIDE_STYLE('',(#202966)); #202966 = SURFACE_STYLE_FILL_AREA(#202967); #202967 = FILL_AREA_STYLE('',(#202968)); -#202968 = FILL_AREA_STYLE_COLOUR('',#201781); -#202969 = OVER_RIDING_STYLED_ITEM('overriding color',(#202970),#168448, - #202920); +#202968 = FILL_AREA_STYLE_COLOUR('',#198418); +#202969 = OVER_RIDING_STYLED_ITEM('overriding color',(#202970),#140373, + #198353); #202970 = PRESENTATION_STYLE_ASSIGNMENT((#202971)); #202971 = SURFACE_STYLE_USAGE(.BOTH.,#202972); #202972 = SURFACE_SIDE_STYLE('',(#202973)); #202973 = SURFACE_STYLE_FILL_AREA(#202974); #202974 = FILL_AREA_STYLE('',(#202975)); -#202975 = FILL_AREA_STYLE_COLOUR('',#201781); -#202976 = OVER_RIDING_STYLED_ITEM('overriding color',(#202977),#168497, - #202920); +#202975 = FILL_AREA_STYLE_COLOUR('',#198418); +#202976 = OVER_RIDING_STYLED_ITEM('overriding color',(#202977),#140477, + #198353); #202977 = PRESENTATION_STYLE_ASSIGNMENT((#202978)); #202978 = SURFACE_STYLE_USAGE(.BOTH.,#202979); #202979 = SURFACE_SIDE_STYLE('',(#202980)); #202980 = SURFACE_STYLE_FILL_AREA(#202981); #202981 = FILL_AREA_STYLE('',(#202982)); -#202982 = FILL_AREA_STYLE_COLOUR('',#201781); -#202983 = OVER_RIDING_STYLED_ITEM('overriding color',(#202984),#168550, - #202920); +#202982 = FILL_AREA_STYLE_COLOUR('',#198418); +#202983 = OVER_RIDING_STYLED_ITEM('overriding color',(#202984),#140556, + #198353); #202984 = PRESENTATION_STYLE_ASSIGNMENT((#202985)); #202985 = SURFACE_STYLE_USAGE(.BOTH.,#202986); #202986 = SURFACE_SIDE_STYLE('',(#202987)); #202987 = SURFACE_STYLE_FILL_AREA(#202988); #202988 = FILL_AREA_STYLE('',(#202989)); -#202989 = FILL_AREA_STYLE_COLOUR('',#201781); -#202990 = OVER_RIDING_STYLED_ITEM('overriding color',(#202991),#168577, - #202920); +#202989 = FILL_AREA_STYLE_COLOUR('',#198418); +#202990 = OVER_RIDING_STYLED_ITEM('overriding color',(#202991),#140635, + #198353); #202991 = PRESENTATION_STYLE_ASSIGNMENT((#202992)); #202992 = SURFACE_STYLE_USAGE(.BOTH.,#202993); #202993 = SURFACE_SIDE_STYLE('',(#202994)); #202994 = SURFACE_STYLE_FILL_AREA(#202995); #202995 = FILL_AREA_STYLE('',(#202996)); -#202996 = FILL_AREA_STYLE_COLOUR('',#201781); -#202997 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #202998,#203005,#203013,#203020,#203027,#203034,#203041,#203048, - #203055,#203062,#203069,#203076,#203083,#203090,#203097,#203104, - #203111,#203118,#203125,#203132,#203139,#203146,#203153,#203160, - #203167,#203174,#203181,#203188,#203195,#203202,#203209,#203216, - #203223,#203230,#203237,#203244,#203251,#203258,#203265,#203272, - #203279,#203286,#203293,#203300,#203307,#203314,#203321,#203328, - #203335,#203342,#203349,#203356,#203363,#203370,#203377,#203384, - #203391,#203398,#203405,#203412,#203419,#203426,#203433,#203440, - #203447,#203454,#203461,#203468,#203475,#203482,#203489,#203496, - #203503,#203510,#203517,#203524,#203531,#203538,#203545,#203552, - #203559,#203566,#203573,#203580,#203587,#203594,#203601,#203608, - #203615,#203622,#203629),#37339); -#202998 = STYLED_ITEM('color',(#202999),#28833); -#202999 = PRESENTATION_STYLE_ASSIGNMENT((#203000)); -#203000 = SURFACE_STYLE_USAGE(.BOTH.,#203001); -#203001 = SURFACE_SIDE_STYLE('',(#203002)); -#203002 = SURFACE_STYLE_FILL_AREA(#203003); -#203003 = FILL_AREA_STYLE('',(#203004)); -#203004 = FILL_AREA_STYLE_COLOUR('',#201028); -#203005 = OVER_RIDING_STYLED_ITEM('overriding color',(#203006),#28835, - #202998); -#203006 = PRESENTATION_STYLE_ASSIGNMENT((#203007)); -#203007 = SURFACE_STYLE_USAGE(.BOTH.,#203008); -#203008 = SURFACE_SIDE_STYLE('',(#203009)); -#203009 = SURFACE_STYLE_FILL_AREA(#203010); -#203010 = FILL_AREA_STYLE('',(#203011)); -#203011 = FILL_AREA_STYLE_COLOUR('',#203012); -#203012 = COLOUR_RGB('',0.909803926945,0.443137258291, - 3.137255087495E-002); -#203013 = OVER_RIDING_STYLED_ITEM('overriding color',(#203014),#31047, - #202998); -#203014 = PRESENTATION_STYLE_ASSIGNMENT((#203015)); -#203015 = SURFACE_STYLE_USAGE(.BOTH.,#203016); -#203016 = SURFACE_SIDE_STYLE('',(#203017)); -#203017 = SURFACE_STYLE_FILL_AREA(#203018); -#203018 = FILL_AREA_STYLE('',(#203019)); -#203019 = FILL_AREA_STYLE_COLOUR('',#195083); -#203020 = OVER_RIDING_STYLED_ITEM('overriding color',(#203021),#31151, - #202998); -#203021 = PRESENTATION_STYLE_ASSIGNMENT((#203022)); -#203022 = SURFACE_STYLE_USAGE(.BOTH.,#203023); -#203023 = SURFACE_SIDE_STYLE('',(#203024)); -#203024 = SURFACE_STYLE_FILL_AREA(#203025); -#203025 = FILL_AREA_STYLE('',(#203026)); -#203026 = FILL_AREA_STYLE_COLOUR('',#195083); -#203027 = OVER_RIDING_STYLED_ITEM('overriding color',(#203028),#31255, - #202998); -#203028 = PRESENTATION_STYLE_ASSIGNMENT((#203029)); -#203029 = SURFACE_STYLE_USAGE(.BOTH.,#203030); -#203030 = SURFACE_SIDE_STYLE('',(#203031)); -#203031 = SURFACE_STYLE_FILL_AREA(#203032); -#203032 = FILL_AREA_STYLE('',(#203033)); -#203033 = FILL_AREA_STYLE_COLOUR('',#195083); -#203034 = OVER_RIDING_STYLED_ITEM('overriding color',(#203035),#31372, - #202998); -#203035 = PRESENTATION_STYLE_ASSIGNMENT((#203036)); -#203036 = SURFACE_STYLE_USAGE(.BOTH.,#203037); -#203037 = SURFACE_SIDE_STYLE('',(#203038)); -#203038 = SURFACE_STYLE_FILL_AREA(#203039); -#203039 = FILL_AREA_STYLE('',(#203040)); -#203040 = FILL_AREA_STYLE_COLOUR('',#195083); -#203041 = OVER_RIDING_STYLED_ITEM('overriding color',(#203042),#31484, - #202998); -#203042 = PRESENTATION_STYLE_ASSIGNMENT((#203043)); -#203043 = SURFACE_STYLE_USAGE(.BOTH.,#203044); -#203044 = SURFACE_SIDE_STYLE('',(#203045)); -#203045 = SURFACE_STYLE_FILL_AREA(#203046); -#203046 = FILL_AREA_STYLE('',(#203047)); -#203047 = FILL_AREA_STYLE_COLOUR('',#195083); -#203048 = OVER_RIDING_STYLED_ITEM('overriding color',(#203049),#31563, - #202998); -#203049 = PRESENTATION_STYLE_ASSIGNMENT((#203050)); -#203050 = SURFACE_STYLE_USAGE(.BOTH.,#203051); -#203051 = SURFACE_SIDE_STYLE('',(#203052)); -#203052 = SURFACE_STYLE_FILL_AREA(#203053); -#203053 = FILL_AREA_STYLE('',(#203054)); -#203054 = FILL_AREA_STYLE_COLOUR('',#195083); -#203055 = OVER_RIDING_STYLED_ITEM('overriding color',(#203056),#31637, - #202998); -#203056 = PRESENTATION_STYLE_ASSIGNMENT((#203057)); -#203057 = SURFACE_STYLE_USAGE(.BOTH.,#203058); -#203058 = SURFACE_SIDE_STYLE('',(#203059)); -#203059 = SURFACE_STYLE_FILL_AREA(#203060); -#203060 = FILL_AREA_STYLE('',(#203061)); -#203061 = FILL_AREA_STYLE_COLOUR('',#195083); -#203062 = OVER_RIDING_STYLED_ITEM('overriding color',(#203063),#31692, - #202998); -#203063 = PRESENTATION_STYLE_ASSIGNMENT((#203064)); -#203064 = SURFACE_STYLE_USAGE(.BOTH.,#203065); -#203065 = SURFACE_SIDE_STYLE('',(#203066)); -#203066 = SURFACE_STYLE_FILL_AREA(#203067); -#203067 = FILL_AREA_STYLE('',(#203068)); -#203068 = FILL_AREA_STYLE_COLOUR('',#195083); -#203069 = OVER_RIDING_STYLED_ITEM('overriding color',(#203070),#31742, - #202998); -#203070 = PRESENTATION_STYLE_ASSIGNMENT((#203071)); -#203071 = SURFACE_STYLE_USAGE(.BOTH.,#203072); -#203072 = SURFACE_SIDE_STYLE('',(#203073)); -#203073 = SURFACE_STYLE_FILL_AREA(#203074); -#203074 = FILL_AREA_STYLE('',(#203075)); -#203075 = FILL_AREA_STYLE_COLOUR('',#195083); -#203076 = OVER_RIDING_STYLED_ITEM('overriding color',(#203077),#31825, - #202998); -#203077 = PRESENTATION_STYLE_ASSIGNMENT((#203078)); -#203078 = SURFACE_STYLE_USAGE(.BOTH.,#203079); -#203079 = SURFACE_SIDE_STYLE('',(#203080)); -#203080 = SURFACE_STYLE_FILL_AREA(#203081); -#203081 = FILL_AREA_STYLE('',(#203082)); -#203082 = FILL_AREA_STYLE_COLOUR('',#195083); -#203083 = OVER_RIDING_STYLED_ITEM('overriding color',(#203084),#31903, - #202998); -#203084 = PRESENTATION_STYLE_ASSIGNMENT((#203085)); -#203085 = SURFACE_STYLE_USAGE(.BOTH.,#203086); -#203086 = SURFACE_SIDE_STYLE('',(#203087)); -#203087 = SURFACE_STYLE_FILL_AREA(#203088); -#203088 = FILL_AREA_STYLE('',(#203089)); -#203089 = FILL_AREA_STYLE_COLOUR('',#195083); -#203090 = OVER_RIDING_STYLED_ITEM('overriding color',(#203091),#32002, - #202998); -#203091 = PRESENTATION_STYLE_ASSIGNMENT((#203092)); -#203092 = SURFACE_STYLE_USAGE(.BOTH.,#203093); -#203093 = SURFACE_SIDE_STYLE('',(#203094)); -#203094 = SURFACE_STYLE_FILL_AREA(#203095); -#203095 = FILL_AREA_STYLE('',(#203096)); -#203096 = FILL_AREA_STYLE_COLOUR('',#195083); -#203097 = OVER_RIDING_STYLED_ITEM('overriding color',(#203098),#32101, - #202998); -#203098 = PRESENTATION_STYLE_ASSIGNMENT((#203099)); -#203099 = SURFACE_STYLE_USAGE(.BOTH.,#203100); -#203100 = SURFACE_SIDE_STYLE('',(#203101)); -#203101 = SURFACE_STYLE_FILL_AREA(#203102); -#203102 = FILL_AREA_STYLE('',(#203103)); -#203103 = FILL_AREA_STYLE_COLOUR('',#195083); -#203104 = OVER_RIDING_STYLED_ITEM('overriding color',(#203105),#32132, - #202998); -#203105 = PRESENTATION_STYLE_ASSIGNMENT((#203106)); -#203106 = SURFACE_STYLE_USAGE(.BOTH.,#203107); -#203107 = SURFACE_SIDE_STYLE('',(#203108)); -#203108 = SURFACE_STYLE_FILL_AREA(#203109); -#203109 = FILL_AREA_STYLE('',(#203110)); -#203110 = FILL_AREA_STYLE_COLOUR('',#195083); -#203111 = OVER_RIDING_STYLED_ITEM('overriding color',(#203112),#32163, - #202998); -#203112 = PRESENTATION_STYLE_ASSIGNMENT((#203113)); -#203113 = SURFACE_STYLE_USAGE(.BOTH.,#203114); -#203114 = SURFACE_SIDE_STYLE('',(#203115)); -#203115 = SURFACE_STYLE_FILL_AREA(#203116); -#203116 = FILL_AREA_STYLE('',(#203117)); -#203117 = FILL_AREA_STYLE_COLOUR('',#195083); -#203118 = OVER_RIDING_STYLED_ITEM('overriding color',(#203119),#32219, - #202998); -#203119 = PRESENTATION_STYLE_ASSIGNMENT((#203120)); -#203120 = SURFACE_STYLE_USAGE(.BOTH.,#203121); -#203121 = SURFACE_SIDE_STYLE('',(#203122)); -#203122 = SURFACE_STYLE_FILL_AREA(#203123); -#203123 = FILL_AREA_STYLE('',(#203124)); -#203124 = FILL_AREA_STYLE_COLOUR('',#195083); -#203125 = OVER_RIDING_STYLED_ITEM('overriding color',(#203126),#32270, - #202998); -#203126 = PRESENTATION_STYLE_ASSIGNMENT((#203127)); -#203127 = SURFACE_STYLE_USAGE(.BOTH.,#203128); -#203128 = SURFACE_SIDE_STYLE('',(#203129)); -#203129 = SURFACE_STYLE_FILL_AREA(#203130); -#203130 = FILL_AREA_STYLE('',(#203131)); -#203131 = FILL_AREA_STYLE_COLOUR('',#195083); -#203132 = OVER_RIDING_STYLED_ITEM('overriding color',(#203133),#32366, - #202998); -#203133 = PRESENTATION_STYLE_ASSIGNMENT((#203134)); -#203134 = SURFACE_STYLE_USAGE(.BOTH.,#203135); -#203135 = SURFACE_SIDE_STYLE('',(#203136)); -#203136 = SURFACE_STYLE_FILL_AREA(#203137); -#203137 = FILL_AREA_STYLE('',(#203138)); -#203138 = FILL_AREA_STYLE_COLOUR('',#203012); -#203139 = OVER_RIDING_STYLED_ITEM('overriding color',(#203140),#32411, - #202998); -#203140 = PRESENTATION_STYLE_ASSIGNMENT((#203141)); -#203141 = SURFACE_STYLE_USAGE(.BOTH.,#203142); -#203142 = SURFACE_SIDE_STYLE('',(#203143)); -#203143 = SURFACE_STYLE_FILL_AREA(#203144); -#203144 = FILL_AREA_STYLE('',(#203145)); -#203145 = FILL_AREA_STYLE_COLOUR('',#195083); -#203146 = OVER_RIDING_STYLED_ITEM('overriding color',(#203147),#32507, - #202998); -#203147 = PRESENTATION_STYLE_ASSIGNMENT((#203148)); -#203148 = SURFACE_STYLE_USAGE(.BOTH.,#203149); -#203149 = SURFACE_SIDE_STYLE('',(#203150)); -#203150 = SURFACE_STYLE_FILL_AREA(#203151); -#203151 = FILL_AREA_STYLE('',(#203152)); -#203152 = FILL_AREA_STYLE_COLOUR('',#203012); -#203153 = OVER_RIDING_STYLED_ITEM('overriding color',(#203154),#32552, - #202998); -#203154 = PRESENTATION_STYLE_ASSIGNMENT((#203155)); -#203155 = SURFACE_STYLE_USAGE(.BOTH.,#203156); -#203156 = SURFACE_SIDE_STYLE('',(#203157)); -#203157 = SURFACE_STYLE_FILL_AREA(#203158); -#203158 = FILL_AREA_STYLE('',(#203159)); -#203159 = FILL_AREA_STYLE_COLOUR('',#203012); -#203160 = OVER_RIDING_STYLED_ITEM('overriding color',(#203161),#32597, - #202998); -#203161 = PRESENTATION_STYLE_ASSIGNMENT((#203162)); -#203162 = SURFACE_STYLE_USAGE(.BOTH.,#203163); -#203163 = SURFACE_SIDE_STYLE('',(#203164)); -#203164 = SURFACE_STYLE_FILL_AREA(#203165); -#203165 = FILL_AREA_STYLE('',(#203166)); -#203166 = FILL_AREA_STYLE_COLOUR('',#195083); -#203167 = OVER_RIDING_STYLED_ITEM('overriding color',(#203168),#32642, - #202998); -#203168 = PRESENTATION_STYLE_ASSIGNMENT((#203169)); -#203169 = SURFACE_STYLE_USAGE(.BOTH.,#203170); -#203170 = SURFACE_SIDE_STYLE('',(#203171)); -#203171 = SURFACE_STYLE_FILL_AREA(#203172); -#203172 = FILL_AREA_STYLE('',(#203173)); -#203173 = FILL_AREA_STYLE_COLOUR('',#195083); -#203174 = OVER_RIDING_STYLED_ITEM('overriding color',(#203175),#32713, - #202998); -#203175 = PRESENTATION_STYLE_ASSIGNMENT((#203176)); -#203176 = SURFACE_STYLE_USAGE(.BOTH.,#203177); -#203177 = SURFACE_SIDE_STYLE('',(#203178)); -#203178 = SURFACE_STYLE_FILL_AREA(#203179); -#203179 = FILL_AREA_STYLE('',(#203180)); -#203180 = FILL_AREA_STYLE_COLOUR('',#195083); -#203181 = OVER_RIDING_STYLED_ITEM('overriding color',(#203182),#32784, - #202998); -#203182 = PRESENTATION_STYLE_ASSIGNMENT((#203183)); -#203183 = SURFACE_STYLE_USAGE(.BOTH.,#203184); -#203184 = SURFACE_SIDE_STYLE('',(#203185)); -#203185 = SURFACE_STYLE_FILL_AREA(#203186); -#203186 = FILL_AREA_STYLE('',(#203187)); -#203187 = FILL_AREA_STYLE_COLOUR('',#195083); -#203188 = OVER_RIDING_STYLED_ITEM('overriding color',(#203189),#32833, - #202998); -#203189 = PRESENTATION_STYLE_ASSIGNMENT((#203190)); -#203190 = SURFACE_STYLE_USAGE(.BOTH.,#203191); -#203191 = SURFACE_SIDE_STYLE('',(#203192)); -#203192 = SURFACE_STYLE_FILL_AREA(#203193); -#203193 = FILL_AREA_STYLE('',(#203194)); -#203194 = FILL_AREA_STYLE_COLOUR('',#203012); -#203195 = OVER_RIDING_STYLED_ITEM('overriding color',(#203196),#32840, - #202998); -#203196 = PRESENTATION_STYLE_ASSIGNMENT((#203197)); -#203197 = SURFACE_STYLE_USAGE(.BOTH.,#203198); -#203198 = SURFACE_SIDE_STYLE('',(#203199)); -#203199 = SURFACE_STYLE_FILL_AREA(#203200); -#203200 = FILL_AREA_STYLE('',(#203201)); -#203201 = FILL_AREA_STYLE_COLOUR('',#195083); -#203202 = OVER_RIDING_STYLED_ITEM('overriding color',(#203203),#32885, - #202998); -#203203 = PRESENTATION_STYLE_ASSIGNMENT((#203204)); -#203204 = SURFACE_STYLE_USAGE(.BOTH.,#203205); -#203205 = SURFACE_SIDE_STYLE('',(#203206)); -#203206 = SURFACE_STYLE_FILL_AREA(#203207); -#203207 = FILL_AREA_STYLE('',(#203208)); -#203208 = FILL_AREA_STYLE_COLOUR('',#203012); -#203209 = OVER_RIDING_STYLED_ITEM('overriding color',(#203210),#32892, - #202998); -#203210 = PRESENTATION_STYLE_ASSIGNMENT((#203211)); -#203211 = SURFACE_STYLE_USAGE(.BOTH.,#203212); -#203212 = SURFACE_SIDE_STYLE('',(#203213)); -#203213 = SURFACE_STYLE_FILL_AREA(#203214); -#203214 = FILL_AREA_STYLE('',(#203215)); -#203215 = FILL_AREA_STYLE_COLOUR('',#195083); -#203216 = OVER_RIDING_STYLED_ITEM('overriding color',(#203217),#32918, - #202998); -#203217 = PRESENTATION_STYLE_ASSIGNMENT((#203218)); -#203218 = SURFACE_STYLE_USAGE(.BOTH.,#203219); -#203219 = SURFACE_SIDE_STYLE('',(#203220)); -#203220 = SURFACE_STYLE_FILL_AREA(#203221); -#203221 = FILL_AREA_STYLE('',(#203222)); -#203222 = FILL_AREA_STYLE_COLOUR('',#195083); -#203223 = OVER_RIDING_STYLED_ITEM('overriding color',(#203224),#32963, - #202998); -#203224 = PRESENTATION_STYLE_ASSIGNMENT((#203225)); -#203225 = SURFACE_STYLE_USAGE(.BOTH.,#203226); -#203226 = SURFACE_SIDE_STYLE('',(#203227)); -#203227 = SURFACE_STYLE_FILL_AREA(#203228); -#203228 = FILL_AREA_STYLE('',(#203229)); -#203229 = FILL_AREA_STYLE_COLOUR('',#195083); -#203230 = OVER_RIDING_STYLED_ITEM('overriding color',(#203231),#32969, - #202998); -#203231 = PRESENTATION_STYLE_ASSIGNMENT((#203232)); -#203232 = SURFACE_STYLE_USAGE(.BOTH.,#203233); -#203233 = SURFACE_SIDE_STYLE('',(#203234)); -#203234 = SURFACE_STYLE_FILL_AREA(#203235); -#203235 = FILL_AREA_STYLE('',(#203236)); -#203236 = FILL_AREA_STYLE_COLOUR('',#195083); -#203237 = OVER_RIDING_STYLED_ITEM('overriding color',(#203238),#33017, - #202998); -#203238 = PRESENTATION_STYLE_ASSIGNMENT((#203239)); -#203239 = SURFACE_STYLE_USAGE(.BOTH.,#203240); -#203240 = SURFACE_SIDE_STYLE('',(#203241)); -#203241 = SURFACE_STYLE_FILL_AREA(#203242); -#203242 = FILL_AREA_STYLE('',(#203243)); -#203243 = FILL_AREA_STYLE_COLOUR('',#195083); -#203244 = OVER_RIDING_STYLED_ITEM('overriding color',(#203245),#33065, - #202998); -#203245 = PRESENTATION_STYLE_ASSIGNMENT((#203246)); -#203246 = SURFACE_STYLE_USAGE(.BOTH.,#203247); -#203247 = SURFACE_SIDE_STYLE('',(#203248)); -#203248 = SURFACE_STYLE_FILL_AREA(#203249); -#203249 = FILL_AREA_STYLE('',(#203250)); -#203250 = FILL_AREA_STYLE_COLOUR('',#195083); -#203251 = OVER_RIDING_STYLED_ITEM('overriding color',(#203252),#33071, - #202998); -#203252 = PRESENTATION_STYLE_ASSIGNMENT((#203253)); -#203253 = SURFACE_STYLE_USAGE(.BOTH.,#203254); -#203254 = SURFACE_SIDE_STYLE('',(#203255)); -#203255 = SURFACE_STYLE_FILL_AREA(#203256); -#203256 = FILL_AREA_STYLE('',(#203257)); -#203257 = FILL_AREA_STYLE_COLOUR('',#203012); -#203258 = OVER_RIDING_STYLED_ITEM('overriding color',(#203259),#33078, - #202998); -#203259 = PRESENTATION_STYLE_ASSIGNMENT((#203260)); -#203260 = SURFACE_STYLE_USAGE(.BOTH.,#203261); -#203261 = SURFACE_SIDE_STYLE('',(#203262)); -#203262 = SURFACE_STYLE_FILL_AREA(#203263); -#203263 = FILL_AREA_STYLE('',(#203264)); -#203264 = FILL_AREA_STYLE_COLOUR('',#195083); -#203265 = OVER_RIDING_STYLED_ITEM('overriding color',(#203266),#33127, - #202998); -#203266 = PRESENTATION_STYLE_ASSIGNMENT((#203267)); -#203267 = SURFACE_STYLE_USAGE(.BOTH.,#203268); -#203268 = SURFACE_SIDE_STYLE('',(#203269)); -#203269 = SURFACE_STYLE_FILL_AREA(#203270); -#203270 = FILL_AREA_STYLE('',(#203271)); -#203271 = FILL_AREA_STYLE_COLOUR('',#195083); -#203272 = OVER_RIDING_STYLED_ITEM('overriding color',(#203273),#33153, - #202998); -#203273 = PRESENTATION_STYLE_ASSIGNMENT((#203274)); -#203274 = SURFACE_STYLE_USAGE(.BOTH.,#203275); -#203275 = SURFACE_SIDE_STYLE('',(#203276)); -#203276 = SURFACE_STYLE_FILL_AREA(#203277); -#203277 = FILL_AREA_STYLE('',(#203278)); -#203278 = FILL_AREA_STYLE_COLOUR('',#203012); -#203279 = OVER_RIDING_STYLED_ITEM('overriding color',(#203280),#33160, - #202998); -#203280 = PRESENTATION_STYLE_ASSIGNMENT((#203281)); -#203281 = SURFACE_STYLE_USAGE(.BOTH.,#203282); -#203282 = SURFACE_SIDE_STYLE('',(#203283)); -#203283 = SURFACE_STYLE_FILL_AREA(#203284); -#203284 = FILL_AREA_STYLE('',(#203285)); -#203285 = FILL_AREA_STYLE_COLOUR('',#195083); -#203286 = OVER_RIDING_STYLED_ITEM('overriding color',(#203287),#33185, - #202998); -#203287 = PRESENTATION_STYLE_ASSIGNMENT((#203288)); -#203288 = SURFACE_STYLE_USAGE(.BOTH.,#203289); -#203289 = SURFACE_SIDE_STYLE('',(#203290)); -#203290 = SURFACE_STYLE_FILL_AREA(#203291); -#203291 = FILL_AREA_STYLE('',(#203292)); -#203292 = FILL_AREA_STYLE_COLOUR('',#195083); -#203293 = OVER_RIDING_STYLED_ITEM('overriding color',(#203294),#33210, - #202998); -#203294 = PRESENTATION_STYLE_ASSIGNMENT((#203295)); -#203295 = SURFACE_STYLE_USAGE(.BOTH.,#203296); -#203296 = SURFACE_SIDE_STYLE('',(#203297)); -#203297 = SURFACE_STYLE_FILL_AREA(#203298); -#203298 = FILL_AREA_STYLE('',(#203299)); -#203299 = FILL_AREA_STYLE_COLOUR('',#195083); -#203300 = OVER_RIDING_STYLED_ITEM('overriding color',(#203301),#33217, - #202998); -#203301 = PRESENTATION_STYLE_ASSIGNMENT((#203302)); -#203302 = SURFACE_STYLE_USAGE(.BOTH.,#203303); -#203303 = SURFACE_SIDE_STYLE('',(#203304)); -#203304 = SURFACE_STYLE_FILL_AREA(#203305); -#203305 = FILL_AREA_STYLE('',(#203306)); -#203306 = FILL_AREA_STYLE_COLOUR('',#195083); -#203307 = OVER_RIDING_STYLED_ITEM('overriding color',(#203308),#34309, - #202998); -#203308 = PRESENTATION_STYLE_ASSIGNMENT((#203309)); -#203309 = SURFACE_STYLE_USAGE(.BOTH.,#203310); -#203310 = SURFACE_SIDE_STYLE('',(#203311)); -#203311 = SURFACE_STYLE_FILL_AREA(#203312); -#203312 = FILL_AREA_STYLE('',(#203313)); -#203313 = FILL_AREA_STYLE_COLOUR('',#195083); -#203314 = OVER_RIDING_STYLED_ITEM('overriding color',(#203315),#34352, - #202998); -#203315 = PRESENTATION_STYLE_ASSIGNMENT((#203316)); -#203316 = SURFACE_STYLE_USAGE(.BOTH.,#203317); -#203317 = SURFACE_SIDE_STYLE('',(#203318)); -#203318 = SURFACE_STYLE_FILL_AREA(#203319); -#203319 = FILL_AREA_STYLE('',(#203320)); -#203320 = FILL_AREA_STYLE_COLOUR('',#195083); -#203321 = OVER_RIDING_STYLED_ITEM('overriding color',(#203322),#34377, - #202998); -#203322 = PRESENTATION_STYLE_ASSIGNMENT((#203323)); -#203323 = SURFACE_STYLE_USAGE(.BOTH.,#203324); -#203324 = SURFACE_SIDE_STYLE('',(#203325)); -#203325 = SURFACE_STYLE_FILL_AREA(#203326); -#203326 = FILL_AREA_STYLE('',(#203327)); -#203327 = FILL_AREA_STYLE_COLOUR('',#195083); -#203328 = OVER_RIDING_STYLED_ITEM('overriding color',(#203329),#34402, - #202998); -#203329 = PRESENTATION_STYLE_ASSIGNMENT((#203330)); -#203330 = SURFACE_STYLE_USAGE(.BOTH.,#203331); -#203331 = SURFACE_SIDE_STYLE('',(#203332)); -#203332 = SURFACE_STYLE_FILL_AREA(#203333); -#203333 = FILL_AREA_STYLE('',(#203334)); -#203334 = FILL_AREA_STYLE_COLOUR('',#195083); -#203335 = OVER_RIDING_STYLED_ITEM('overriding color',(#203336),#34427, - #202998); -#203336 = PRESENTATION_STYLE_ASSIGNMENT((#203337)); -#203337 = SURFACE_STYLE_USAGE(.BOTH.,#203338); -#203338 = SURFACE_SIDE_STYLE('',(#203339)); -#203339 = SURFACE_STYLE_FILL_AREA(#203340); -#203340 = FILL_AREA_STYLE('',(#203341)); -#203341 = FILL_AREA_STYLE_COLOUR('',#195083); -#203342 = OVER_RIDING_STYLED_ITEM('overriding color',(#203343),#34452, - #202998); -#203343 = PRESENTATION_STYLE_ASSIGNMENT((#203344)); -#203344 = SURFACE_STYLE_USAGE(.BOTH.,#203345); -#203345 = SURFACE_SIDE_STYLE('',(#203346)); -#203346 = SURFACE_STYLE_FILL_AREA(#203347); -#203347 = FILL_AREA_STYLE('',(#203348)); -#203348 = FILL_AREA_STYLE_COLOUR('',#195083); -#203349 = OVER_RIDING_STYLED_ITEM('overriding color',(#203350),#34477, - #202998); -#203350 = PRESENTATION_STYLE_ASSIGNMENT((#203351)); -#203351 = SURFACE_STYLE_USAGE(.BOTH.,#203352); -#203352 = SURFACE_SIDE_STYLE('',(#203353)); -#203353 = SURFACE_STYLE_FILL_AREA(#203354); -#203354 = FILL_AREA_STYLE('',(#203355)); -#203355 = FILL_AREA_STYLE_COLOUR('',#195083); -#203356 = OVER_RIDING_STYLED_ITEM('overriding color',(#203357),#34502, - #202998); -#203357 = PRESENTATION_STYLE_ASSIGNMENT((#203358)); -#203358 = SURFACE_STYLE_USAGE(.BOTH.,#203359); -#203359 = SURFACE_SIDE_STYLE('',(#203360)); -#203360 = SURFACE_STYLE_FILL_AREA(#203361); -#203361 = FILL_AREA_STYLE('',(#203362)); -#203362 = FILL_AREA_STYLE_COLOUR('',#195083); -#203363 = OVER_RIDING_STYLED_ITEM('overriding color',(#203364),#34509, - #202998); -#203364 = PRESENTATION_STYLE_ASSIGNMENT((#203365)); -#203365 = SURFACE_STYLE_USAGE(.BOTH.,#203366); -#203366 = SURFACE_SIDE_STYLE('',(#203367)); -#203367 = SURFACE_STYLE_FILL_AREA(#203368); -#203368 = FILL_AREA_STYLE('',(#203369)); -#203369 = FILL_AREA_STYLE_COLOUR('',#195083); -#203370 = OVER_RIDING_STYLED_ITEM('overriding color',(#203371),#34605, - #202998); -#203371 = PRESENTATION_STYLE_ASSIGNMENT((#203372)); -#203372 = SURFACE_STYLE_USAGE(.BOTH.,#203373); -#203373 = SURFACE_SIDE_STYLE('',(#203374)); -#203374 = SURFACE_STYLE_FILL_AREA(#203375); -#203375 = FILL_AREA_STYLE('',(#203376)); -#203376 = FILL_AREA_STYLE_COLOUR('',#195083); -#203377 = OVER_RIDING_STYLED_ITEM('overriding color',(#203378),#34676, - #202998); -#203378 = PRESENTATION_STYLE_ASSIGNMENT((#203379)); -#203379 = SURFACE_STYLE_USAGE(.BOTH.,#203380); -#203380 = SURFACE_SIDE_STYLE('',(#203381)); -#203381 = SURFACE_STYLE_FILL_AREA(#203382); -#203382 = FILL_AREA_STYLE('',(#203383)); -#203383 = FILL_AREA_STYLE_COLOUR('',#195083); -#203384 = OVER_RIDING_STYLED_ITEM('overriding color',(#203385),#34747, - #202998); -#203385 = PRESENTATION_STYLE_ASSIGNMENT((#203386)); -#203386 = SURFACE_STYLE_USAGE(.BOTH.,#203387); -#203387 = SURFACE_SIDE_STYLE('',(#203388)); -#203388 = SURFACE_STYLE_FILL_AREA(#203389); -#203389 = FILL_AREA_STYLE('',(#203390)); -#203390 = FILL_AREA_STYLE_COLOUR('',#195083); -#203391 = OVER_RIDING_STYLED_ITEM('overriding color',(#203392),#34798, - #202998); -#203392 = PRESENTATION_STYLE_ASSIGNMENT((#203393)); -#203393 = SURFACE_STYLE_USAGE(.BOTH.,#203394); -#203394 = SURFACE_SIDE_STYLE('',(#203395)); -#203395 = SURFACE_STYLE_FILL_AREA(#203396); -#203396 = FILL_AREA_STYLE('',(#203397)); -#203397 = FILL_AREA_STYLE_COLOUR('',#195083); -#203398 = OVER_RIDING_STYLED_ITEM('overriding color',(#203399),#34902, - #202998); -#203399 = PRESENTATION_STYLE_ASSIGNMENT((#203400)); -#203400 = SURFACE_STYLE_USAGE(.BOTH.,#203401); -#203401 = SURFACE_SIDE_STYLE('',(#203402)); -#203402 = SURFACE_STYLE_FILL_AREA(#203403); -#203403 = FILL_AREA_STYLE('',(#203404)); -#203404 = FILL_AREA_STYLE_COLOUR('',#195083); -#203405 = OVER_RIDING_STYLED_ITEM('overriding color',(#203406),#34973, - #202998); -#203406 = PRESENTATION_STYLE_ASSIGNMENT((#203407)); -#203407 = SURFACE_STYLE_USAGE(.BOTH.,#203408); -#203408 = SURFACE_SIDE_STYLE('',(#203409)); -#203409 = SURFACE_STYLE_FILL_AREA(#203410); -#203410 = FILL_AREA_STYLE('',(#203411)); -#203411 = FILL_AREA_STYLE_COLOUR('',#195083); -#203412 = OVER_RIDING_STYLED_ITEM('overriding color',(#203413),#35052, - #202998); -#203413 = PRESENTATION_STYLE_ASSIGNMENT((#203414)); -#203414 = SURFACE_STYLE_USAGE(.BOTH.,#203415); -#203415 = SURFACE_SIDE_STYLE('',(#203416)); -#203416 = SURFACE_STYLE_FILL_AREA(#203417); -#203417 = FILL_AREA_STYLE('',(#203418)); -#203418 = FILL_AREA_STYLE_COLOUR('',#195083); -#203419 = OVER_RIDING_STYLED_ITEM('overriding color',(#203420),#35111, - #202998); -#203420 = PRESENTATION_STYLE_ASSIGNMENT((#203421)); -#203421 = SURFACE_STYLE_USAGE(.BOTH.,#203422); -#203422 = SURFACE_SIDE_STYLE('',(#203423)); -#203423 = SURFACE_STYLE_FILL_AREA(#203424); -#203424 = FILL_AREA_STYLE('',(#203425)); -#203425 = FILL_AREA_STYLE_COLOUR('',#203012); -#203426 = OVER_RIDING_STYLED_ITEM('overriding color',(#203427),#35118, - #202998); -#203427 = PRESENTATION_STYLE_ASSIGNMENT((#203428)); -#203428 = SURFACE_STYLE_USAGE(.BOTH.,#203429); -#203429 = SURFACE_SIDE_STYLE('',(#203430)); -#203430 = SURFACE_STYLE_FILL_AREA(#203431); -#203431 = FILL_AREA_STYLE('',(#203432)); -#203432 = FILL_AREA_STYLE_COLOUR('',#203012); -#203433 = OVER_RIDING_STYLED_ITEM('overriding color',(#203434),#35125, - #202998); -#203434 = PRESENTATION_STYLE_ASSIGNMENT((#203435)); -#203435 = SURFACE_STYLE_USAGE(.BOTH.,#203436); -#203436 = SURFACE_SIDE_STYLE('',(#203437)); -#203437 = SURFACE_STYLE_FILL_AREA(#203438); -#203438 = FILL_AREA_STYLE('',(#203439)); -#203439 = FILL_AREA_STYLE_COLOUR('',#195083); -#203440 = OVER_RIDING_STYLED_ITEM('overriding color',(#203441),#35824, - #202998); -#203441 = PRESENTATION_STYLE_ASSIGNMENT((#203442)); -#203442 = SURFACE_STYLE_USAGE(.BOTH.,#203443); -#203443 = SURFACE_SIDE_STYLE('',(#203444)); -#203444 = SURFACE_STYLE_FILL_AREA(#203445); -#203445 = FILL_AREA_STYLE('',(#203446)); -#203446 = FILL_AREA_STYLE_COLOUR('',#195083); -#203447 = OVER_RIDING_STYLED_ITEM('overriding color',(#203448),#35867, - #202998); -#203448 = PRESENTATION_STYLE_ASSIGNMENT((#203449)); -#203449 = SURFACE_STYLE_USAGE(.BOTH.,#203450); -#203450 = SURFACE_SIDE_STYLE('',(#203451)); -#203451 = SURFACE_STYLE_FILL_AREA(#203452); -#203452 = FILL_AREA_STYLE('',(#203453)); -#203453 = FILL_AREA_STYLE_COLOUR('',#195083); -#203454 = OVER_RIDING_STYLED_ITEM('overriding color',(#203455),#35892, - #202998); -#203455 = PRESENTATION_STYLE_ASSIGNMENT((#203456)); -#203456 = SURFACE_STYLE_USAGE(.BOTH.,#203457); -#203457 = SURFACE_SIDE_STYLE('',(#203458)); -#203458 = SURFACE_STYLE_FILL_AREA(#203459); -#203459 = FILL_AREA_STYLE('',(#203460)); -#203460 = FILL_AREA_STYLE_COLOUR('',#195083); -#203461 = OVER_RIDING_STYLED_ITEM('overriding color',(#203462),#35917, - #202998); -#203462 = PRESENTATION_STYLE_ASSIGNMENT((#203463)); -#203463 = SURFACE_STYLE_USAGE(.BOTH.,#203464); -#203464 = SURFACE_SIDE_STYLE('',(#203465)); -#203465 = SURFACE_STYLE_FILL_AREA(#203466); -#203466 = FILL_AREA_STYLE('',(#203467)); -#203467 = FILL_AREA_STYLE_COLOUR('',#195083); -#203468 = OVER_RIDING_STYLED_ITEM('overriding color',(#203469),#35942, - #202998); -#203469 = PRESENTATION_STYLE_ASSIGNMENT((#203470)); -#203470 = SURFACE_STYLE_USAGE(.BOTH.,#203471); -#203471 = SURFACE_SIDE_STYLE('',(#203472)); -#203472 = SURFACE_STYLE_FILL_AREA(#203473); -#203473 = FILL_AREA_STYLE('',(#203474)); -#203474 = FILL_AREA_STYLE_COLOUR('',#195083); -#203475 = OVER_RIDING_STYLED_ITEM('overriding color',(#203476),#35949, - #202998); -#203476 = PRESENTATION_STYLE_ASSIGNMENT((#203477)); -#203477 = SURFACE_STYLE_USAGE(.BOTH.,#203478); -#203478 = SURFACE_SIDE_STYLE('',(#203479)); -#203479 = SURFACE_STYLE_FILL_AREA(#203480); -#203480 = FILL_AREA_STYLE('',(#203481)); -#203481 = FILL_AREA_STYLE_COLOUR('',#195083); -#203482 = OVER_RIDING_STYLED_ITEM('overriding color',(#203483),#36037, - #202998); -#203483 = PRESENTATION_STYLE_ASSIGNMENT((#203484)); -#203484 = SURFACE_STYLE_USAGE(.BOTH.,#203485); -#203485 = SURFACE_SIDE_STYLE('',(#203486)); -#203486 = SURFACE_STYLE_FILL_AREA(#203487); -#203487 = FILL_AREA_STYLE('',(#203488)); -#203488 = FILL_AREA_STYLE_COLOUR('',#195083); -#203489 = OVER_RIDING_STYLED_ITEM('overriding color',(#203490),#36116, - #202998); -#203490 = PRESENTATION_STYLE_ASSIGNMENT((#203491)); -#203491 = SURFACE_STYLE_USAGE(.BOTH.,#203492); -#203492 = SURFACE_SIDE_STYLE('',(#203493)); -#203493 = SURFACE_STYLE_FILL_AREA(#203494); -#203494 = FILL_AREA_STYLE('',(#203495)); -#203495 = FILL_AREA_STYLE_COLOUR('',#195083); -#203496 = OVER_RIDING_STYLED_ITEM('overriding color',(#203497),#36195, - #202998); -#203497 = PRESENTATION_STYLE_ASSIGNMENT((#203498)); -#203498 = SURFACE_STYLE_USAGE(.BOTH.,#203499); -#203499 = SURFACE_SIDE_STYLE('',(#203500)); -#203500 = SURFACE_STYLE_FILL_AREA(#203501); -#203501 = FILL_AREA_STYLE('',(#203502)); -#203502 = FILL_AREA_STYLE_COLOUR('',#195083); -#203503 = OVER_RIDING_STYLED_ITEM('overriding color',(#203504),#36274, - #202998); -#203504 = PRESENTATION_STYLE_ASSIGNMENT((#203505)); -#203505 = SURFACE_STYLE_USAGE(.BOTH.,#203506); -#203506 = SURFACE_SIDE_STYLE('',(#203507)); -#203507 = SURFACE_STYLE_FILL_AREA(#203508); -#203508 = FILL_AREA_STYLE('',(#203509)); -#203509 = FILL_AREA_STYLE_COLOUR('',#195083); -#203510 = OVER_RIDING_STYLED_ITEM('overriding color',(#203511),#36317, - #202998); -#203511 = PRESENTATION_STYLE_ASSIGNMENT((#203512)); -#203512 = SURFACE_STYLE_USAGE(.BOTH.,#203513); -#203513 = SURFACE_SIDE_STYLE('',(#203514)); -#203514 = SURFACE_STYLE_FILL_AREA(#203515); -#203515 = FILL_AREA_STYLE('',(#203516)); -#203516 = FILL_AREA_STYLE_COLOUR('',#203012); -#203517 = OVER_RIDING_STYLED_ITEM('overriding color',(#203518),#36325, - #202998); -#203518 = PRESENTATION_STYLE_ASSIGNMENT((#203519)); -#203519 = SURFACE_STYLE_USAGE(.BOTH.,#203520); -#203520 = SURFACE_SIDE_STYLE('',(#203521)); -#203521 = SURFACE_STYLE_FILL_AREA(#203522); -#203522 = FILL_AREA_STYLE('',(#203523)); -#203523 = FILL_AREA_STYLE_COLOUR('',#195083); -#203524 = OVER_RIDING_STYLED_ITEM('overriding color',(#203525),#36430, - #202998); -#203525 = PRESENTATION_STYLE_ASSIGNMENT((#203526)); -#203526 = SURFACE_STYLE_USAGE(.BOTH.,#203527); -#203527 = SURFACE_SIDE_STYLE('',(#203528)); -#203528 = SURFACE_STYLE_FILL_AREA(#203529); -#203529 = FILL_AREA_STYLE('',(#203530)); -#203530 = FILL_AREA_STYLE_COLOUR('',#195083); -#203531 = OVER_RIDING_STYLED_ITEM('overriding color',(#203532),#36493, - #202998); -#203532 = PRESENTATION_STYLE_ASSIGNMENT((#203533)); -#203533 = SURFACE_STYLE_USAGE(.BOTH.,#203534); -#203534 = SURFACE_SIDE_STYLE('',(#203535)); -#203535 = SURFACE_STYLE_FILL_AREA(#203536); -#203536 = FILL_AREA_STYLE('',(#203537)); -#203537 = FILL_AREA_STYLE_COLOUR('',#195083); -#203538 = OVER_RIDING_STYLED_ITEM('overriding color',(#203539),#36556, - #202998); -#203539 = PRESENTATION_STYLE_ASSIGNMENT((#203540)); -#203540 = SURFACE_STYLE_USAGE(.BOTH.,#203541); -#203541 = SURFACE_SIDE_STYLE('',(#203542)); -#203542 = SURFACE_STYLE_FILL_AREA(#203543); -#203543 = FILL_AREA_STYLE('',(#203544)); -#203544 = FILL_AREA_STYLE_COLOUR('',#195083); -#203545 = OVER_RIDING_STYLED_ITEM('overriding color',(#203546),#36635, - #202998); -#203546 = PRESENTATION_STYLE_ASSIGNMENT((#203547)); -#203547 = SURFACE_STYLE_USAGE(.BOTH.,#203548); -#203548 = SURFACE_SIDE_STYLE('',(#203549)); -#203549 = SURFACE_STYLE_FILL_AREA(#203550); -#203550 = FILL_AREA_STYLE('',(#203551)); -#203551 = FILL_AREA_STYLE_COLOUR('',#195083); -#203552 = OVER_RIDING_STYLED_ITEM('overriding color',(#203553),#36699, - #202998); -#203553 = PRESENTATION_STYLE_ASSIGNMENT((#203554)); -#203554 = SURFACE_STYLE_USAGE(.BOTH.,#203555); -#203555 = SURFACE_SIDE_STYLE('',(#203556)); -#203556 = SURFACE_STYLE_FILL_AREA(#203557); -#203557 = FILL_AREA_STYLE('',(#203558)); -#203558 = FILL_AREA_STYLE_COLOUR('',#195083); -#203559 = OVER_RIDING_STYLED_ITEM('overriding color',(#203560),#36748, - #202998); -#203560 = PRESENTATION_STYLE_ASSIGNMENT((#203561)); -#203561 = SURFACE_STYLE_USAGE(.BOTH.,#203562); -#203562 = SURFACE_SIDE_STYLE('',(#203563)); -#203563 = SURFACE_STYLE_FILL_AREA(#203564); -#203564 = FILL_AREA_STYLE('',(#203565)); -#203565 = FILL_AREA_STYLE_COLOUR('',#195083); -#203566 = OVER_RIDING_STYLED_ITEM('overriding color',(#203567),#36797, - #202998); -#203567 = PRESENTATION_STYLE_ASSIGNMENT((#203568)); -#203568 = SURFACE_STYLE_USAGE(.BOTH.,#203569); -#203569 = SURFACE_SIDE_STYLE('',(#203570)); -#203570 = SURFACE_STYLE_FILL_AREA(#203571); -#203571 = FILL_AREA_STYLE('',(#203572)); -#203572 = FILL_AREA_STYLE_COLOUR('',#195083); -#203573 = OVER_RIDING_STYLED_ITEM('overriding color',(#203574),#36846, - #202998); -#203574 = PRESENTATION_STYLE_ASSIGNMENT((#203575)); -#203575 = SURFACE_STYLE_USAGE(.BOTH.,#203576); -#203576 = SURFACE_SIDE_STYLE('',(#203577)); -#203577 = SURFACE_STYLE_FILL_AREA(#203578); -#203578 = FILL_AREA_STYLE('',(#203579)); -#203579 = FILL_AREA_STYLE_COLOUR('',#195083); -#203580 = OVER_RIDING_STYLED_ITEM('overriding color',(#203581),#36895, - #202998); -#203581 = PRESENTATION_STYLE_ASSIGNMENT((#203582)); -#203582 = SURFACE_STYLE_USAGE(.BOTH.,#203583); -#203583 = SURFACE_SIDE_STYLE('',(#203584)); -#203584 = SURFACE_STYLE_FILL_AREA(#203585); -#203585 = FILL_AREA_STYLE('',(#203586)); -#203586 = FILL_AREA_STYLE_COLOUR('',#195083); -#203587 = OVER_RIDING_STYLED_ITEM('overriding color',(#203588),#36944, - #202998); -#203588 = PRESENTATION_STYLE_ASSIGNMENT((#203589)); -#203589 = SURFACE_STYLE_USAGE(.BOTH.,#203590); -#203590 = SURFACE_SIDE_STYLE('',(#203591)); -#203591 = SURFACE_STYLE_FILL_AREA(#203592); -#203592 = FILL_AREA_STYLE('',(#203593)); -#203593 = FILL_AREA_STYLE_COLOUR('',#195083); -#203594 = OVER_RIDING_STYLED_ITEM('overriding color',(#203595),#36992, - #202998); -#203595 = PRESENTATION_STYLE_ASSIGNMENT((#203596)); -#203596 = SURFACE_STYLE_USAGE(.BOTH.,#203597); -#203597 = SURFACE_SIDE_STYLE('',(#203598)); -#203598 = SURFACE_STYLE_FILL_AREA(#203599); -#203599 = FILL_AREA_STYLE('',(#203600)); -#203600 = FILL_AREA_STYLE_COLOUR('',#195083); -#203601 = OVER_RIDING_STYLED_ITEM('overriding color',(#203602),#37055, - #202998); -#203602 = PRESENTATION_STYLE_ASSIGNMENT((#203603)); -#203603 = SURFACE_STYLE_USAGE(.BOTH.,#203604); -#203604 = SURFACE_SIDE_STYLE('',(#203605)); -#203605 = SURFACE_STYLE_FILL_AREA(#203606); -#203606 = FILL_AREA_STYLE('',(#203607)); -#203607 = FILL_AREA_STYLE_COLOUR('',#195083); -#203608 = OVER_RIDING_STYLED_ITEM('overriding color',(#203609),#37134, - #202998); -#203609 = PRESENTATION_STYLE_ASSIGNMENT((#203610)); -#203610 = SURFACE_STYLE_USAGE(.BOTH.,#203611); -#203611 = SURFACE_SIDE_STYLE('',(#203612)); -#203612 = SURFACE_STYLE_FILL_AREA(#203613); -#203613 = FILL_AREA_STYLE('',(#203614)); -#203614 = FILL_AREA_STYLE_COLOUR('',#195083); -#203615 = OVER_RIDING_STYLED_ITEM('overriding color',(#203616),#37213, - #202998); -#203616 = PRESENTATION_STYLE_ASSIGNMENT((#203617)); -#203617 = SURFACE_STYLE_USAGE(.BOTH.,#203618); -#203618 = SURFACE_SIDE_STYLE('',(#203619)); -#203619 = SURFACE_STYLE_FILL_AREA(#203620); -#203620 = FILL_AREA_STYLE('',(#203621)); -#203621 = FILL_AREA_STYLE_COLOUR('',#195083); -#203622 = OVER_RIDING_STYLED_ITEM('overriding color',(#203623),#37293, - #202998); -#203623 = PRESENTATION_STYLE_ASSIGNMENT((#203624)); -#203624 = SURFACE_STYLE_USAGE(.BOTH.,#203625); -#203625 = SURFACE_SIDE_STYLE('',(#203626)); -#203626 = SURFACE_STYLE_FILL_AREA(#203627); -#203627 = FILL_AREA_STYLE('',(#203628)); -#203628 = FILL_AREA_STYLE_COLOUR('',#195083); -#203629 = OVER_RIDING_STYLED_ITEM('overriding color',(#203630),#37320, - #202998); -#203630 = PRESENTATION_STYLE_ASSIGNMENT((#203631)); -#203631 = SURFACE_STYLE_USAGE(.BOTH.,#203632); -#203632 = SURFACE_SIDE_STYLE('',(#203633)); -#203633 = SURFACE_STYLE_FILL_AREA(#203634); -#203634 = FILL_AREA_STYLE('',(#203635)); -#203635 = FILL_AREA_STYLE_COLOUR('',#195083); -#203636 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #203637,#203644,#203651,#203658,#203665,#203672,#203679,#203686, - #203693),#156644); -#203637 = STYLED_ITEM('color',(#203638),#151242); -#203638 = PRESENTATION_STYLE_ASSIGNMENT((#203639)); -#203639 = SURFACE_STYLE_USAGE(.BOTH.,#203640); -#203640 = SURFACE_SIDE_STYLE('',(#203641)); -#203641 = SURFACE_STYLE_FILL_AREA(#203642); -#203642 = FILL_AREA_STYLE('',(#203643)); -#203643 = FILL_AREA_STYLE_COLOUR('',#201028); -#203644 = OVER_RIDING_STYLED_ITEM('overriding color',(#203645),#151244, - #203637); -#203645 = PRESENTATION_STYLE_ASSIGNMENT((#203646)); -#203646 = SURFACE_STYLE_USAGE(.BOTH.,#203647); -#203647 = SURFACE_SIDE_STYLE('',(#203648)); -#203648 = SURFACE_STYLE_FILL_AREA(#203649); -#203649 = FILL_AREA_STYLE('',(#203650)); -#203650 = FILL_AREA_STYLE_COLOUR('',#195025); -#203651 = OVER_RIDING_STYLED_ITEM('overriding color',(#203652),#151685, - #203637); -#203652 = PRESENTATION_STYLE_ASSIGNMENT((#203653)); -#203653 = SURFACE_STYLE_USAGE(.BOTH.,#203654); -#203654 = SURFACE_SIDE_STYLE('',(#203655)); -#203655 = SURFACE_STYLE_FILL_AREA(#203656); -#203656 = FILL_AREA_STYLE('',(#203657)); -#203657 = FILL_AREA_STYLE_COLOUR('',#195025); -#203658 = OVER_RIDING_STYLED_ITEM('overriding color',(#203659),#152004, - #203637); -#203659 = PRESENTATION_STYLE_ASSIGNMENT((#203660)); -#203660 = SURFACE_STYLE_USAGE(.BOTH.,#203661); -#203661 = SURFACE_SIDE_STYLE('',(#203662)); -#203662 = SURFACE_STYLE_FILL_AREA(#203663); -#203663 = FILL_AREA_STYLE('',(#203664)); -#203664 = FILL_AREA_STYLE_COLOUR('',#195025); -#203665 = OVER_RIDING_STYLED_ITEM('overriding color',(#203666),#152161, - #203637); -#203666 = PRESENTATION_STYLE_ASSIGNMENT((#203667)); -#203667 = SURFACE_STYLE_USAGE(.BOTH.,#203668); -#203668 = SURFACE_SIDE_STYLE('',(#203669)); -#203669 = SURFACE_STYLE_FILL_AREA(#203670); -#203670 = FILL_AREA_STYLE('',(#203671)); -#203671 = FILL_AREA_STYLE_COLOUR('',#201036); -#203672 = OVER_RIDING_STYLED_ITEM('overriding color',(#203673),#152232, - #203637); -#203673 = PRESENTATION_STYLE_ASSIGNMENT((#203674)); -#203674 = SURFACE_STYLE_USAGE(.BOTH.,#203675); -#203675 = SURFACE_SIDE_STYLE('',(#203676)); -#203676 = SURFACE_STYLE_FILL_AREA(#203677); -#203677 = FILL_AREA_STYLE('',(#203678)); -#203678 = FILL_AREA_STYLE_COLOUR('',#195025); -#203679 = OVER_RIDING_STYLED_ITEM('overriding color',(#203680),#152333, - #203637); -#203680 = PRESENTATION_STYLE_ASSIGNMENT((#203681)); -#203681 = SURFACE_STYLE_USAGE(.BOTH.,#203682); -#203682 = SURFACE_SIDE_STYLE('',(#203683)); -#203683 = SURFACE_STYLE_FILL_AREA(#203684); -#203684 = FILL_AREA_STYLE('',(#203685)); -#203685 = FILL_AREA_STYLE_COLOUR('',#195025); -#203686 = OVER_RIDING_STYLED_ITEM('overriding color',(#203687),#152380, - #203637); -#203687 = PRESENTATION_STYLE_ASSIGNMENT((#203688)); -#203688 = SURFACE_STYLE_USAGE(.BOTH.,#203689); -#203689 = SURFACE_SIDE_STYLE('',(#203690)); -#203690 = SURFACE_STYLE_FILL_AREA(#203691); -#203691 = FILL_AREA_STYLE('',(#203692)); -#203692 = FILL_AREA_STYLE_COLOUR('',#201036); -#203693 = OVER_RIDING_STYLED_ITEM('overriding color',(#203694),#152389, - #203637); -#203694 = PRESENTATION_STYLE_ASSIGNMENT((#203695)); -#203695 = SURFACE_STYLE_USAGE(.BOTH.,#203696); -#203696 = SURFACE_SIDE_STYLE('',(#203697)); -#203697 = SURFACE_STYLE_FILL_AREA(#203698); -#203698 = FILL_AREA_STYLE('',(#203699)); -#203699 = FILL_AREA_STYLE_COLOUR('',#201036); -#203700 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #203701,#203708,#203715,#203722,#203729,#203736,#203743,#203750, - #203757,#203764,#203771,#203778,#203785,#203792,#203799,#203806, - #203813,#203820,#203827,#203834,#203841,#203848,#203855,#203862, - #203869,#203876,#203883,#203890,#203897,#203904,#203911,#203918, - #203925,#203932,#203939,#203946,#203953,#203960,#203967,#203974, - #203981,#203988,#203995,#204002,#204009,#204016,#204023,#204030, - #204037,#204044,#204051,#204058,#204065,#204072,#204079,#204086, - #204093,#204100,#204107,#204114,#204121,#204128,#204135,#204142, - #204149,#204156,#204163,#204170,#204177,#204184,#204191,#204198, - #204205,#204212,#204219,#204226,#204233,#204240,#204247,#204254, - #204261,#204268,#204275,#204282,#204289,#204296,#204303,#204310, - #204317,#204324,#204331,#204338,#204345,#204352,#204359,#204366, - #204373,#204380,#204387,#204394,#204401,#204408,#204415,#204422, - #204429,#204436,#204443,#204450),#85891); -#203701 = STYLED_ITEM('color',(#203702),#75544); -#203702 = PRESENTATION_STYLE_ASSIGNMENT((#203703)); -#203703 = SURFACE_STYLE_USAGE(.BOTH.,#203704); -#203704 = SURFACE_SIDE_STYLE('',(#203705)); -#203705 = SURFACE_STYLE_FILL_AREA(#203706); -#203706 = FILL_AREA_STYLE('',(#203707)); -#203707 = FILL_AREA_STYLE_COLOUR('',#201773); -#203708 = OVER_RIDING_STYLED_ITEM('overriding color',(#203709),#75546, - #203701); -#203709 = PRESENTATION_STYLE_ASSIGNMENT((#203710)); -#203710 = SURFACE_STYLE_USAGE(.BOTH.,#203711); -#203711 = SURFACE_SIDE_STYLE('',(#203712)); -#203712 = SURFACE_STYLE_FILL_AREA(#203713); -#203713 = FILL_AREA_STYLE('',(#203714)); -#203714 = FILL_AREA_STYLE_COLOUR('',#201781); -#203715 = OVER_RIDING_STYLED_ITEM('overriding color',(#203716),#75826, - #203701); -#203716 = PRESENTATION_STYLE_ASSIGNMENT((#203717)); -#203717 = SURFACE_STYLE_USAGE(.BOTH.,#203718); -#203718 = SURFACE_SIDE_STYLE('',(#203719)); -#203719 = SURFACE_STYLE_FILL_AREA(#203720); -#203720 = FILL_AREA_STYLE('',(#203721)); -#203721 = FILL_AREA_STYLE_COLOUR('',#201781); -#203722 = OVER_RIDING_STYLED_ITEM('overriding color',(#203723),#76101, - #203701); -#203723 = PRESENTATION_STYLE_ASSIGNMENT((#203724)); -#203724 = SURFACE_STYLE_USAGE(.BOTH.,#203725); -#203725 = SURFACE_SIDE_STYLE('',(#203726)); -#203726 = SURFACE_STYLE_FILL_AREA(#203727); -#203727 = FILL_AREA_STYLE('',(#203728)); -#203728 = FILL_AREA_STYLE_COLOUR('',#201781); -#203729 = OVER_RIDING_STYLED_ITEM('overriding color',(#203730),#76376, - #203701); -#203730 = PRESENTATION_STYLE_ASSIGNMENT((#203731)); -#203731 = SURFACE_STYLE_USAGE(.BOTH.,#203732); -#203732 = SURFACE_SIDE_STYLE('',(#203733)); -#203733 = SURFACE_STYLE_FILL_AREA(#203734); -#203734 = FILL_AREA_STYLE('',(#203735)); -#203735 = FILL_AREA_STYLE_COLOUR('',#201781); -#203736 = OVER_RIDING_STYLED_ITEM('overriding color',(#203737),#76651, - #203701); -#203737 = PRESENTATION_STYLE_ASSIGNMENT((#203738)); -#203738 = SURFACE_STYLE_USAGE(.BOTH.,#203739); -#203739 = SURFACE_SIDE_STYLE('',(#203740)); -#203740 = SURFACE_STYLE_FILL_AREA(#203741); -#203741 = FILL_AREA_STYLE('',(#203742)); -#203742 = FILL_AREA_STYLE_COLOUR('',#201781); -#203743 = OVER_RIDING_STYLED_ITEM('overriding color',(#203744),#76954, - #203701); -#203744 = PRESENTATION_STYLE_ASSIGNMENT((#203745)); -#203745 = SURFACE_STYLE_USAGE(.BOTH.,#203746); -#203746 = SURFACE_SIDE_STYLE('',(#203747)); -#203747 = SURFACE_STYLE_FILL_AREA(#203748); -#203748 = FILL_AREA_STYLE('',(#203749)); -#203749 = FILL_AREA_STYLE_COLOUR('',#201781); -#203750 = OVER_RIDING_STYLED_ITEM('overriding color',(#203751),#77229, - #203701); -#203751 = PRESENTATION_STYLE_ASSIGNMENT((#203752)); -#203752 = SURFACE_STYLE_USAGE(.BOTH.,#203753); -#203753 = SURFACE_SIDE_STYLE('',(#203754)); -#203754 = SURFACE_STYLE_FILL_AREA(#203755); -#203755 = FILL_AREA_STYLE('',(#203756)); -#203756 = FILL_AREA_STYLE_COLOUR('',#201781); -#203757 = OVER_RIDING_STYLED_ITEM('overriding color',(#203758),#77504, - #203701); -#203758 = PRESENTATION_STYLE_ASSIGNMENT((#203759)); -#203759 = SURFACE_STYLE_USAGE(.BOTH.,#203760); -#203760 = SURFACE_SIDE_STYLE('',(#203761)); -#203761 = SURFACE_STYLE_FILL_AREA(#203762); -#203762 = FILL_AREA_STYLE('',(#203763)); -#203763 = FILL_AREA_STYLE_COLOUR('',#201781); -#203764 = OVER_RIDING_STYLED_ITEM('overriding color',(#203765),#77779, - #203701); -#203765 = PRESENTATION_STYLE_ASSIGNMENT((#203766)); -#203766 = SURFACE_STYLE_USAGE(.BOTH.,#203767); -#203767 = SURFACE_SIDE_STYLE('',(#203768)); -#203768 = SURFACE_STYLE_FILL_AREA(#203769); -#203769 = FILL_AREA_STYLE('',(#203770)); -#203770 = FILL_AREA_STYLE_COLOUR('',#201781); -#203771 = OVER_RIDING_STYLED_ITEM('overriding color',(#203772),#78116, - #203701); -#203772 = PRESENTATION_STYLE_ASSIGNMENT((#203773)); -#203773 = SURFACE_STYLE_USAGE(.BOTH.,#203774); -#203774 = SURFACE_SIDE_STYLE('',(#203775)); -#203775 = SURFACE_STYLE_FILL_AREA(#203776); -#203776 = FILL_AREA_STYLE('',(#203777)); -#203777 = FILL_AREA_STYLE_COLOUR('',#201781); -#203778 = OVER_RIDING_STYLED_ITEM('overriding color',(#203779),#78583, - #203701); -#203779 = PRESENTATION_STYLE_ASSIGNMENT((#203780)); -#203780 = SURFACE_STYLE_USAGE(.BOTH.,#203781); -#203781 = SURFACE_SIDE_STYLE('',(#203782)); -#203782 = SURFACE_STYLE_FILL_AREA(#203783); -#203783 = FILL_AREA_STYLE('',(#203784)); -#203784 = FILL_AREA_STYLE_COLOUR('',#201781); -#203785 = OVER_RIDING_STYLED_ITEM('overriding color',(#203786),#78752, - #203701); -#203786 = PRESENTATION_STYLE_ASSIGNMENT((#203787)); -#203787 = SURFACE_STYLE_USAGE(.BOTH.,#203788); -#203788 = SURFACE_SIDE_STYLE('',(#203789)); -#203789 = SURFACE_STYLE_FILL_AREA(#203790); -#203790 = FILL_AREA_STYLE('',(#203791)); -#203791 = FILL_AREA_STYLE_COLOUR('',#201781); -#203792 = OVER_RIDING_STYLED_ITEM('overriding color',(#203793),#78918, - #203701); -#203793 = PRESENTATION_STYLE_ASSIGNMENT((#203794)); -#203794 = SURFACE_STYLE_USAGE(.BOTH.,#203795); -#203795 = SURFACE_SIDE_STYLE('',(#203796)); -#203796 = SURFACE_STYLE_FILL_AREA(#203797); -#203797 = FILL_AREA_STYLE('',(#203798)); -#203798 = FILL_AREA_STYLE_COLOUR('',#201781); -#203799 = OVER_RIDING_STYLED_ITEM('overriding color',(#203800),#79064, - #203701); -#203800 = PRESENTATION_STYLE_ASSIGNMENT((#203801)); -#203801 = SURFACE_STYLE_USAGE(.BOTH.,#203802); -#203802 = SURFACE_SIDE_STYLE('',(#203803)); -#203803 = SURFACE_STYLE_FILL_AREA(#203804); -#203804 = FILL_AREA_STYLE('',(#203805)); -#203805 = FILL_AREA_STYLE_COLOUR('',#201781); -#203806 = OVER_RIDING_STYLED_ITEM('overriding color',(#203807),#79234, - #203701); -#203807 = PRESENTATION_STYLE_ASSIGNMENT((#203808)); -#203808 = SURFACE_STYLE_USAGE(.BOTH.,#203809); -#203809 = SURFACE_SIDE_STYLE('',(#203810)); -#203810 = SURFACE_STYLE_FILL_AREA(#203811); -#203811 = FILL_AREA_STYLE('',(#203812)); -#203812 = FILL_AREA_STYLE_COLOUR('',#201781); -#203813 = OVER_RIDING_STYLED_ITEM('overriding color',(#203814),#79555, - #203701); -#203814 = PRESENTATION_STYLE_ASSIGNMENT((#203815)); -#203815 = SURFACE_STYLE_USAGE(.BOTH.,#203816); -#203816 = SURFACE_SIDE_STYLE('',(#203817)); -#203817 = SURFACE_STYLE_FILL_AREA(#203818); -#203818 = FILL_AREA_STYLE('',(#203819)); -#203819 = FILL_AREA_STYLE_COLOUR('',#201781); -#203820 = OVER_RIDING_STYLED_ITEM('overriding color',(#203821),#79667, - #203701); -#203821 = PRESENTATION_STYLE_ASSIGNMENT((#203822)); -#203822 = SURFACE_STYLE_USAGE(.BOTH.,#203823); -#203823 = SURFACE_SIDE_STYLE('',(#203824)); -#203824 = SURFACE_STYLE_FILL_AREA(#203825); -#203825 = FILL_AREA_STYLE('',(#203826)); -#203826 = FILL_AREA_STYLE_COLOUR('',#201781); -#203827 = OVER_RIDING_STYLED_ITEM('overriding color',(#203828),#79802, - #203701); -#203828 = PRESENTATION_STYLE_ASSIGNMENT((#203829)); -#203829 = SURFACE_STYLE_USAGE(.BOTH.,#203830); -#203830 = SURFACE_SIDE_STYLE('',(#203831)); -#203831 = SURFACE_STYLE_FILL_AREA(#203832); -#203832 = FILL_AREA_STYLE('',(#203833)); -#203833 = FILL_AREA_STYLE_COLOUR('',#201781); -#203834 = OVER_RIDING_STYLED_ITEM('overriding color',(#203835),#80123, - #203701); -#203835 = PRESENTATION_STYLE_ASSIGNMENT((#203836)); -#203836 = SURFACE_STYLE_USAGE(.BOTH.,#203837); -#203837 = SURFACE_SIDE_STYLE('',(#203838)); -#203838 = SURFACE_STYLE_FILL_AREA(#203839); -#203839 = FILL_AREA_STYLE('',(#203840)); -#203840 = FILL_AREA_STYLE_COLOUR('',#201028); -#203841 = OVER_RIDING_STYLED_ITEM('overriding color',(#203842),#80198, - #203701); -#203842 = PRESENTATION_STYLE_ASSIGNMENT((#203843)); -#203843 = SURFACE_STYLE_USAGE(.BOTH.,#203844); -#203844 = SURFACE_SIDE_STYLE('',(#203845)); -#203845 = SURFACE_STYLE_FILL_AREA(#203846); -#203846 = FILL_AREA_STYLE('',(#203847)); -#203847 = FILL_AREA_STYLE_COLOUR('',#201028); -#203848 = OVER_RIDING_STYLED_ITEM('overriding color',(#203849),#80273, - #203701); -#203849 = PRESENTATION_STYLE_ASSIGNMENT((#203850)); -#203850 = SURFACE_STYLE_USAGE(.BOTH.,#203851); -#203851 = SURFACE_SIDE_STYLE('',(#203852)); -#203852 = SURFACE_STYLE_FILL_AREA(#203853); -#203853 = FILL_AREA_STYLE('',(#203854)); -#203854 = FILL_AREA_STYLE_COLOUR('',#201028); -#203855 = OVER_RIDING_STYLED_ITEM('overriding color',(#203856),#80527, - #203701); -#203856 = PRESENTATION_STYLE_ASSIGNMENT((#203857)); -#203857 = SURFACE_STYLE_USAGE(.BOTH.,#203858); -#203858 = SURFACE_SIDE_STYLE('',(#203859)); -#203859 = SURFACE_STYLE_FILL_AREA(#203860); -#203860 = FILL_AREA_STYLE('',(#203861)); -#203861 = FILL_AREA_STYLE_COLOUR('',#201028); -#203862 = OVER_RIDING_STYLED_ITEM('overriding color',(#203863),#80746, - #203701); -#203863 = PRESENTATION_STYLE_ASSIGNMENT((#203864)); -#203864 = SURFACE_STYLE_USAGE(.BOTH.,#203865); -#203865 = SURFACE_SIDE_STYLE('',(#203866)); -#203866 = SURFACE_STYLE_FILL_AREA(#203867); -#203867 = FILL_AREA_STYLE('',(#203868)); -#203868 = FILL_AREA_STYLE_COLOUR('',#201028); -#203869 = OVER_RIDING_STYLED_ITEM('overriding color',(#203870),#80772, - #203701); -#203870 = PRESENTATION_STYLE_ASSIGNMENT((#203871)); -#203871 = SURFACE_STYLE_USAGE(.BOTH.,#203872); -#203872 = SURFACE_SIDE_STYLE('',(#203873)); -#203873 = SURFACE_STYLE_FILL_AREA(#203874); -#203874 = FILL_AREA_STYLE('',(#203875)); -#203875 = FILL_AREA_STYLE_COLOUR('',#201028); -#203876 = OVER_RIDING_STYLED_ITEM('overriding color',(#203877),#80798, - #203701); -#203877 = PRESENTATION_STYLE_ASSIGNMENT((#203878)); -#203878 = SURFACE_STYLE_USAGE(.BOTH.,#203879); -#203879 = SURFACE_SIDE_STYLE('',(#203880)); -#203880 = SURFACE_STYLE_FILL_AREA(#203881); -#203881 = FILL_AREA_STYLE('',(#203882)); -#203882 = FILL_AREA_STYLE_COLOUR('',#201028); -#203883 = OVER_RIDING_STYLED_ITEM('overriding color',(#203884),#80847, - #203701); -#203884 = PRESENTATION_STYLE_ASSIGNMENT((#203885)); -#203885 = SURFACE_STYLE_USAGE(.BOTH.,#203886); -#203886 = SURFACE_SIDE_STYLE('',(#203887)); -#203887 = SURFACE_STYLE_FILL_AREA(#203888); -#203888 = FILL_AREA_STYLE('',(#203889)); -#203889 = FILL_AREA_STYLE_COLOUR('',#201028); -#203890 = OVER_RIDING_STYLED_ITEM('overriding color',(#203891),#80874, - #203701); -#203891 = PRESENTATION_STYLE_ASSIGNMENT((#203892)); -#203892 = SURFACE_STYLE_USAGE(.BOTH.,#203893); -#203893 = SURFACE_SIDE_STYLE('',(#203894)); -#203894 = SURFACE_STYLE_FILL_AREA(#203895); -#203895 = FILL_AREA_STYLE('',(#203896)); -#203896 = FILL_AREA_STYLE_COLOUR('',#201028); -#203897 = OVER_RIDING_STYLED_ITEM('overriding color',(#203898),#80901, - #203701); -#203898 = PRESENTATION_STYLE_ASSIGNMENT((#203899)); -#203899 = SURFACE_STYLE_USAGE(.BOTH.,#203900); -#203900 = SURFACE_SIDE_STYLE('',(#203901)); -#203901 = SURFACE_STYLE_FILL_AREA(#203902); -#203902 = FILL_AREA_STYLE('',(#203903)); -#203903 = FILL_AREA_STYLE_COLOUR('',#201028); -#203904 = OVER_RIDING_STYLED_ITEM('overriding color',(#203905),#80950, - #203701); -#203905 = PRESENTATION_STYLE_ASSIGNMENT((#203906)); -#203906 = SURFACE_STYLE_USAGE(.BOTH.,#203907); -#203907 = SURFACE_SIDE_STYLE('',(#203908)); -#203908 = SURFACE_STYLE_FILL_AREA(#203909); -#203909 = FILL_AREA_STYLE('',(#203910)); -#203910 = FILL_AREA_STYLE_COLOUR('',#201028); -#203911 = OVER_RIDING_STYLED_ITEM('overriding color',(#203912),#80976, - #203701); -#203912 = PRESENTATION_STYLE_ASSIGNMENT((#203913)); -#203913 = SURFACE_STYLE_USAGE(.BOTH.,#203914); -#203914 = SURFACE_SIDE_STYLE('',(#203915)); -#203915 = SURFACE_STYLE_FILL_AREA(#203916); -#203916 = FILL_AREA_STYLE('',(#203917)); -#203917 = FILL_AREA_STYLE_COLOUR('',#201028); -#203918 = OVER_RIDING_STYLED_ITEM('overriding color',(#203919),#81002, - #203701); -#203919 = PRESENTATION_STYLE_ASSIGNMENT((#203920)); -#203920 = SURFACE_STYLE_USAGE(.BOTH.,#203921); -#203921 = SURFACE_SIDE_STYLE('',(#203922)); -#203922 = SURFACE_STYLE_FILL_AREA(#203923); -#203923 = FILL_AREA_STYLE('',(#203924)); -#203924 = FILL_AREA_STYLE_COLOUR('',#201028); -#203925 = OVER_RIDING_STYLED_ITEM('overriding color',(#203926),#81009, - #203701); -#203926 = PRESENTATION_STYLE_ASSIGNMENT((#203927)); -#203927 = SURFACE_STYLE_USAGE(.BOTH.,#203928); -#203928 = SURFACE_SIDE_STYLE('',(#203929)); -#203929 = SURFACE_STYLE_FILL_AREA(#203930); -#203930 = FILL_AREA_STYLE('',(#203931)); -#203931 = FILL_AREA_STYLE_COLOUR('',#201028); -#203932 = OVER_RIDING_STYLED_ITEM('overriding color',(#203933),#81084, - #203701); -#203933 = PRESENTATION_STYLE_ASSIGNMENT((#203934)); -#203934 = SURFACE_STYLE_USAGE(.BOTH.,#203935); -#203935 = SURFACE_SIDE_STYLE('',(#203936)); -#203936 = SURFACE_STYLE_FILL_AREA(#203937); -#203937 = FILL_AREA_STYLE('',(#203938)); -#203938 = FILL_AREA_STYLE_COLOUR('',#201028); -#203939 = OVER_RIDING_STYLED_ITEM('overriding color',(#203940),#81159, - #203701); -#203940 = PRESENTATION_STYLE_ASSIGNMENT((#203941)); -#203941 = SURFACE_STYLE_USAGE(.BOTH.,#203942); -#203942 = SURFACE_SIDE_STYLE('',(#203943)); -#203943 = SURFACE_STYLE_FILL_AREA(#203944); -#203944 = FILL_AREA_STYLE('',(#203945)); -#203945 = FILL_AREA_STYLE_COLOUR('',#201028); -#203946 = OVER_RIDING_STYLED_ITEM('overriding color',(#203947),#81413, - #203701); -#203947 = PRESENTATION_STYLE_ASSIGNMENT((#203948)); -#203948 = SURFACE_STYLE_USAGE(.BOTH.,#203949); -#203949 = SURFACE_SIDE_STYLE('',(#203950)); -#203950 = SURFACE_STYLE_FILL_AREA(#203951); -#203951 = FILL_AREA_STYLE('',(#203952)); -#203952 = FILL_AREA_STYLE_COLOUR('',#201028); -#203953 = OVER_RIDING_STYLED_ITEM('overriding color',(#203954),#81632, - #203701); -#203954 = PRESENTATION_STYLE_ASSIGNMENT((#203955)); -#203955 = SURFACE_STYLE_USAGE(.BOTH.,#203956); -#203956 = SURFACE_SIDE_STYLE('',(#203957)); -#203957 = SURFACE_STYLE_FILL_AREA(#203958); -#203958 = FILL_AREA_STYLE('',(#203959)); -#203959 = FILL_AREA_STYLE_COLOUR('',#201028); -#203960 = OVER_RIDING_STYLED_ITEM('overriding color',(#203961),#81658, - #203701); -#203961 = PRESENTATION_STYLE_ASSIGNMENT((#203962)); -#203962 = SURFACE_STYLE_USAGE(.BOTH.,#203963); -#203963 = SURFACE_SIDE_STYLE('',(#203964)); -#203964 = SURFACE_STYLE_FILL_AREA(#203965); -#203965 = FILL_AREA_STYLE('',(#203966)); -#203966 = FILL_AREA_STYLE_COLOUR('',#201028); -#203967 = OVER_RIDING_STYLED_ITEM('overriding color',(#203968),#81684, - #203701); -#203968 = PRESENTATION_STYLE_ASSIGNMENT((#203969)); -#203969 = SURFACE_STYLE_USAGE(.BOTH.,#203970); -#203970 = SURFACE_SIDE_STYLE('',(#203971)); -#203971 = SURFACE_STYLE_FILL_AREA(#203972); -#203972 = FILL_AREA_STYLE('',(#203973)); -#203973 = FILL_AREA_STYLE_COLOUR('',#201028); -#203974 = OVER_RIDING_STYLED_ITEM('overriding color',(#203975),#81733, - #203701); -#203975 = PRESENTATION_STYLE_ASSIGNMENT((#203976)); -#203976 = SURFACE_STYLE_USAGE(.BOTH.,#203977); -#203977 = SURFACE_SIDE_STYLE('',(#203978)); -#203978 = SURFACE_STYLE_FILL_AREA(#203979); -#203979 = FILL_AREA_STYLE('',(#203980)); -#203980 = FILL_AREA_STYLE_COLOUR('',#201028); -#203981 = OVER_RIDING_STYLED_ITEM('overriding color',(#203982),#81760, - #203701); -#203982 = PRESENTATION_STYLE_ASSIGNMENT((#203983)); -#203983 = SURFACE_STYLE_USAGE(.BOTH.,#203984); -#203984 = SURFACE_SIDE_STYLE('',(#203985)); -#203985 = SURFACE_STYLE_FILL_AREA(#203986); -#203986 = FILL_AREA_STYLE('',(#203987)); -#203987 = FILL_AREA_STYLE_COLOUR('',#201028); -#203988 = OVER_RIDING_STYLED_ITEM('overriding color',(#203989),#81787, - #203701); -#203989 = PRESENTATION_STYLE_ASSIGNMENT((#203990)); -#203990 = SURFACE_STYLE_USAGE(.BOTH.,#203991); -#203991 = SURFACE_SIDE_STYLE('',(#203992)); -#203992 = SURFACE_STYLE_FILL_AREA(#203993); -#203993 = FILL_AREA_STYLE('',(#203994)); -#203994 = FILL_AREA_STYLE_COLOUR('',#201028); -#203995 = OVER_RIDING_STYLED_ITEM('overriding color',(#203996),#81836, - #203701); -#203996 = PRESENTATION_STYLE_ASSIGNMENT((#203997)); -#203997 = SURFACE_STYLE_USAGE(.BOTH.,#203998); -#203998 = SURFACE_SIDE_STYLE('',(#203999)); -#203999 = SURFACE_STYLE_FILL_AREA(#204000); -#204000 = FILL_AREA_STYLE('',(#204001)); -#204001 = FILL_AREA_STYLE_COLOUR('',#201028); -#204002 = OVER_RIDING_STYLED_ITEM('overriding color',(#204003),#81862, - #203701); -#204003 = PRESENTATION_STYLE_ASSIGNMENT((#204004)); -#204004 = SURFACE_STYLE_USAGE(.BOTH.,#204005); -#204005 = SURFACE_SIDE_STYLE('',(#204006)); -#204006 = SURFACE_STYLE_FILL_AREA(#204007); -#204007 = FILL_AREA_STYLE('',(#204008)); -#204008 = FILL_AREA_STYLE_COLOUR('',#201028); -#204009 = OVER_RIDING_STYLED_ITEM('overriding color',(#204010),#81888, - #203701); -#204010 = PRESENTATION_STYLE_ASSIGNMENT((#204011)); -#204011 = SURFACE_STYLE_USAGE(.BOTH.,#204012); -#204012 = SURFACE_SIDE_STYLE('',(#204013)); -#204013 = SURFACE_STYLE_FILL_AREA(#204014); -#204014 = FILL_AREA_STYLE('',(#204015)); -#204015 = FILL_AREA_STYLE_COLOUR('',#201028); -#204016 = OVER_RIDING_STYLED_ITEM('overriding color',(#204017),#81895, - #203701); -#204017 = PRESENTATION_STYLE_ASSIGNMENT((#204018)); -#204018 = SURFACE_STYLE_USAGE(.BOTH.,#204019); -#204019 = SURFACE_SIDE_STYLE('',(#204020)); -#204020 = SURFACE_STYLE_FILL_AREA(#204021); -#204021 = FILL_AREA_STYLE('',(#204022)); -#204022 = FILL_AREA_STYLE_COLOUR('',#201028); -#204023 = OVER_RIDING_STYLED_ITEM('overriding color',(#204024),#81970, - #203701); -#204024 = PRESENTATION_STYLE_ASSIGNMENT((#204025)); -#204025 = SURFACE_STYLE_USAGE(.BOTH.,#204026); -#204026 = SURFACE_SIDE_STYLE('',(#204027)); -#204027 = SURFACE_STYLE_FILL_AREA(#204028); -#204028 = FILL_AREA_STYLE('',(#204029)); -#204029 = FILL_AREA_STYLE_COLOUR('',#201028); -#204030 = OVER_RIDING_STYLED_ITEM('overriding color',(#204031),#82251, - #203701); -#204031 = PRESENTATION_STYLE_ASSIGNMENT((#204032)); -#204032 = SURFACE_STYLE_USAGE(.BOTH.,#204033); -#204033 = SURFACE_SIDE_STYLE('',(#204034)); -#204034 = SURFACE_STYLE_FILL_AREA(#204035); -#204035 = FILL_AREA_STYLE('',(#204036)); -#204036 = FILL_AREA_STYLE_COLOUR('',#201028); -#204037 = OVER_RIDING_STYLED_ITEM('overriding color',(#204038),#82299, - #203701); -#204038 = PRESENTATION_STYLE_ASSIGNMENT((#204039)); -#204039 = SURFACE_STYLE_USAGE(.BOTH.,#204040); -#204040 = SURFACE_SIDE_STYLE('',(#204041)); -#204041 = SURFACE_STYLE_FILL_AREA(#204042); -#204042 = FILL_AREA_STYLE('',(#204043)); -#204043 = FILL_AREA_STYLE_COLOUR('',#201028); -#204044 = OVER_RIDING_STYLED_ITEM('overriding color',(#204045),#82518, - #203701); -#204045 = PRESENTATION_STYLE_ASSIGNMENT((#204046)); -#204046 = SURFACE_STYLE_USAGE(.BOTH.,#204047); -#204047 = SURFACE_SIDE_STYLE('',(#204048)); -#204048 = SURFACE_STYLE_FILL_AREA(#204049); -#204049 = FILL_AREA_STYLE('',(#204050)); -#204050 = FILL_AREA_STYLE_COLOUR('',#201028); -#204051 = OVER_RIDING_STYLED_ITEM('overriding color',(#204052),#82544, - #203701); -#204052 = PRESENTATION_STYLE_ASSIGNMENT((#204053)); -#204053 = SURFACE_STYLE_USAGE(.BOTH.,#204054); -#204054 = SURFACE_SIDE_STYLE('',(#204055)); -#204055 = SURFACE_STYLE_FILL_AREA(#204056); -#204056 = FILL_AREA_STYLE('',(#204057)); -#204057 = FILL_AREA_STYLE_COLOUR('',#201028); -#204058 = OVER_RIDING_STYLED_ITEM('overriding color',(#204059),#82570, - #203701); -#204059 = PRESENTATION_STYLE_ASSIGNMENT((#204060)); -#204060 = SURFACE_STYLE_USAGE(.BOTH.,#204061); -#204061 = SURFACE_SIDE_STYLE('',(#204062)); -#204062 = SURFACE_STYLE_FILL_AREA(#204063); -#204063 = FILL_AREA_STYLE('',(#204064)); -#204064 = FILL_AREA_STYLE_COLOUR('',#201028); -#204065 = OVER_RIDING_STYLED_ITEM('overriding color',(#204066),#82619, - #203701); -#204066 = PRESENTATION_STYLE_ASSIGNMENT((#204067)); -#204067 = SURFACE_STYLE_USAGE(.BOTH.,#204068); -#204068 = SURFACE_SIDE_STYLE('',(#204069)); -#204069 = SURFACE_STYLE_FILL_AREA(#204070); -#204070 = FILL_AREA_STYLE('',(#204071)); -#204071 = FILL_AREA_STYLE_COLOUR('',#201028); -#204072 = OVER_RIDING_STYLED_ITEM('overriding color',(#204073),#82646, - #203701); -#204073 = PRESENTATION_STYLE_ASSIGNMENT((#204074)); -#204074 = SURFACE_STYLE_USAGE(.BOTH.,#204075); -#204075 = SURFACE_SIDE_STYLE('',(#204076)); -#204076 = SURFACE_STYLE_FILL_AREA(#204077); -#204077 = FILL_AREA_STYLE('',(#204078)); -#204078 = FILL_AREA_STYLE_COLOUR('',#201028); -#204079 = OVER_RIDING_STYLED_ITEM('overriding color',(#204080),#82673, - #203701); -#204080 = PRESENTATION_STYLE_ASSIGNMENT((#204081)); -#204081 = SURFACE_STYLE_USAGE(.BOTH.,#204082); -#204082 = SURFACE_SIDE_STYLE('',(#204083)); -#204083 = SURFACE_STYLE_FILL_AREA(#204084); -#204084 = FILL_AREA_STYLE('',(#204085)); -#204085 = FILL_AREA_STYLE_COLOUR('',#201028); -#204086 = OVER_RIDING_STYLED_ITEM('overriding color',(#204087),#82722, - #203701); -#204087 = PRESENTATION_STYLE_ASSIGNMENT((#204088)); -#204088 = SURFACE_STYLE_USAGE(.BOTH.,#204089); -#204089 = SURFACE_SIDE_STYLE('',(#204090)); -#204090 = SURFACE_STYLE_FILL_AREA(#204091); -#204091 = FILL_AREA_STYLE('',(#204092)); -#204092 = FILL_AREA_STYLE_COLOUR('',#201028); -#204093 = OVER_RIDING_STYLED_ITEM('overriding color',(#204094),#82748, - #203701); -#204094 = PRESENTATION_STYLE_ASSIGNMENT((#204095)); -#204095 = SURFACE_STYLE_USAGE(.BOTH.,#204096); -#204096 = SURFACE_SIDE_STYLE('',(#204097)); -#204097 = SURFACE_STYLE_FILL_AREA(#204098); -#204098 = FILL_AREA_STYLE('',(#204099)); -#204099 = FILL_AREA_STYLE_COLOUR('',#201028); -#204100 = OVER_RIDING_STYLED_ITEM('overriding color',(#204101),#82774, - #203701); -#204101 = PRESENTATION_STYLE_ASSIGNMENT((#204102)); -#204102 = SURFACE_STYLE_USAGE(.BOTH.,#204103); -#204103 = SURFACE_SIDE_STYLE('',(#204104)); -#204104 = SURFACE_STYLE_FILL_AREA(#204105); -#204105 = FILL_AREA_STYLE('',(#204106)); -#204106 = FILL_AREA_STYLE_COLOUR('',#201028); -#204107 = OVER_RIDING_STYLED_ITEM('overriding color',(#204108),#82781, - #203701); -#204108 = PRESENTATION_STYLE_ASSIGNMENT((#204109)); -#204109 = SURFACE_STYLE_USAGE(.BOTH.,#204110); -#204110 = SURFACE_SIDE_STYLE('',(#204111)); -#204111 = SURFACE_STYLE_FILL_AREA(#204112); -#204112 = FILL_AREA_STYLE('',(#204113)); -#204113 = FILL_AREA_STYLE_COLOUR('',#201028); -#204114 = OVER_RIDING_STYLED_ITEM('overriding color',(#204115),#82856, - #203701); -#204115 = PRESENTATION_STYLE_ASSIGNMENT((#204116)); -#204116 = SURFACE_STYLE_USAGE(.BOTH.,#204117); -#204117 = SURFACE_SIDE_STYLE('',(#204118)); -#204118 = SURFACE_STYLE_FILL_AREA(#204119); -#204119 = FILL_AREA_STYLE('',(#204120)); -#204120 = FILL_AREA_STYLE_COLOUR('',#201028); -#204121 = OVER_RIDING_STYLED_ITEM('overriding color',(#204122),#83137, - #203701); -#204122 = PRESENTATION_STYLE_ASSIGNMENT((#204123)); -#204123 = SURFACE_STYLE_USAGE(.BOTH.,#204124); -#204124 = SURFACE_SIDE_STYLE('',(#204125)); -#204125 = SURFACE_STYLE_FILL_AREA(#204126); -#204126 = FILL_AREA_STYLE('',(#204127)); -#204127 = FILL_AREA_STYLE_COLOUR('',#201028); -#204128 = OVER_RIDING_STYLED_ITEM('overriding color',(#204129),#83185, - #203701); -#204129 = PRESENTATION_STYLE_ASSIGNMENT((#204130)); -#204130 = SURFACE_STYLE_USAGE(.BOTH.,#204131); -#204131 = SURFACE_SIDE_STYLE('',(#204132)); -#204132 = SURFACE_STYLE_FILL_AREA(#204133); -#204133 = FILL_AREA_STYLE('',(#204134)); -#204134 = FILL_AREA_STYLE_COLOUR('',#201028); -#204135 = OVER_RIDING_STYLED_ITEM('overriding color',(#204136),#83404, - #203701); -#204136 = PRESENTATION_STYLE_ASSIGNMENT((#204137)); -#204137 = SURFACE_STYLE_USAGE(.BOTH.,#204138); -#204138 = SURFACE_SIDE_STYLE('',(#204139)); -#204139 = SURFACE_STYLE_FILL_AREA(#204140); -#204140 = FILL_AREA_STYLE('',(#204141)); -#204141 = FILL_AREA_STYLE_COLOUR('',#201028); -#204142 = OVER_RIDING_STYLED_ITEM('overriding color',(#204143),#83430, - #203701); -#204143 = PRESENTATION_STYLE_ASSIGNMENT((#204144)); -#204144 = SURFACE_STYLE_USAGE(.BOTH.,#204145); -#204145 = SURFACE_SIDE_STYLE('',(#204146)); -#204146 = SURFACE_STYLE_FILL_AREA(#204147); -#204147 = FILL_AREA_STYLE('',(#204148)); -#204148 = FILL_AREA_STYLE_COLOUR('',#201028); -#204149 = OVER_RIDING_STYLED_ITEM('overriding color',(#204150),#83456, - #203701); -#204150 = PRESENTATION_STYLE_ASSIGNMENT((#204151)); -#204151 = SURFACE_STYLE_USAGE(.BOTH.,#204152); -#204152 = SURFACE_SIDE_STYLE('',(#204153)); -#204153 = SURFACE_STYLE_FILL_AREA(#204154); -#204154 = FILL_AREA_STYLE('',(#204155)); -#204155 = FILL_AREA_STYLE_COLOUR('',#201028); -#204156 = OVER_RIDING_STYLED_ITEM('overriding color',(#204157),#83505, - #203701); -#204157 = PRESENTATION_STYLE_ASSIGNMENT((#204158)); -#204158 = SURFACE_STYLE_USAGE(.BOTH.,#204159); -#204159 = SURFACE_SIDE_STYLE('',(#204160)); -#204160 = SURFACE_STYLE_FILL_AREA(#204161); -#204161 = FILL_AREA_STYLE('',(#204162)); -#204162 = FILL_AREA_STYLE_COLOUR('',#201028); -#204163 = OVER_RIDING_STYLED_ITEM('overriding color',(#204164),#83532, - #203701); -#204164 = PRESENTATION_STYLE_ASSIGNMENT((#204165)); -#204165 = SURFACE_STYLE_USAGE(.BOTH.,#204166); -#204166 = SURFACE_SIDE_STYLE('',(#204167)); -#204167 = SURFACE_STYLE_FILL_AREA(#204168); -#204168 = FILL_AREA_STYLE('',(#204169)); -#204169 = FILL_AREA_STYLE_COLOUR('',#201028); -#204170 = OVER_RIDING_STYLED_ITEM('overriding color',(#204171),#83559, - #203701); -#204171 = PRESENTATION_STYLE_ASSIGNMENT((#204172)); -#204172 = SURFACE_STYLE_USAGE(.BOTH.,#204173); -#204173 = SURFACE_SIDE_STYLE('',(#204174)); -#204174 = SURFACE_STYLE_FILL_AREA(#204175); -#204175 = FILL_AREA_STYLE('',(#204176)); -#204176 = FILL_AREA_STYLE_COLOUR('',#201028); -#204177 = OVER_RIDING_STYLED_ITEM('overriding color',(#204178),#83608, - #203701); -#204178 = PRESENTATION_STYLE_ASSIGNMENT((#204179)); -#204179 = SURFACE_STYLE_USAGE(.BOTH.,#204180); -#204180 = SURFACE_SIDE_STYLE('',(#204181)); -#204181 = SURFACE_STYLE_FILL_AREA(#204182); -#204182 = FILL_AREA_STYLE('',(#204183)); -#204183 = FILL_AREA_STYLE_COLOUR('',#201028); -#204184 = OVER_RIDING_STYLED_ITEM('overriding color',(#204185),#83634, - #203701); -#204185 = PRESENTATION_STYLE_ASSIGNMENT((#204186)); -#204186 = SURFACE_STYLE_USAGE(.BOTH.,#204187); -#204187 = SURFACE_SIDE_STYLE('',(#204188)); -#204188 = SURFACE_STYLE_FILL_AREA(#204189); -#204189 = FILL_AREA_STYLE('',(#204190)); -#204190 = FILL_AREA_STYLE_COLOUR('',#201028); -#204191 = OVER_RIDING_STYLED_ITEM('overriding color',(#204192),#83660, - #203701); -#204192 = PRESENTATION_STYLE_ASSIGNMENT((#204193)); -#204193 = SURFACE_STYLE_USAGE(.BOTH.,#204194); -#204194 = SURFACE_SIDE_STYLE('',(#204195)); -#204195 = SURFACE_STYLE_FILL_AREA(#204196); -#204196 = FILL_AREA_STYLE('',(#204197)); -#204197 = FILL_AREA_STYLE_COLOUR('',#201028); -#204198 = OVER_RIDING_STYLED_ITEM('overriding color',(#204199),#83667, - #203701); -#204199 = PRESENTATION_STYLE_ASSIGNMENT((#204200)); -#204200 = SURFACE_STYLE_USAGE(.BOTH.,#204201); -#204201 = SURFACE_SIDE_STYLE('',(#204202)); -#204202 = SURFACE_STYLE_FILL_AREA(#204203); -#204203 = FILL_AREA_STYLE('',(#204204)); -#204204 = FILL_AREA_STYLE_COLOUR('',#201028); -#204205 = OVER_RIDING_STYLED_ITEM('overriding color',(#204206),#83742, - #203701); -#204206 = PRESENTATION_STYLE_ASSIGNMENT((#204207)); -#204207 = SURFACE_STYLE_USAGE(.BOTH.,#204208); -#204208 = SURFACE_SIDE_STYLE('',(#204209)); -#204209 = SURFACE_STYLE_FILL_AREA(#204210); -#204210 = FILL_AREA_STYLE('',(#204211)); -#204211 = FILL_AREA_STYLE_COLOUR('',#201028); -#204212 = OVER_RIDING_STYLED_ITEM('overriding color',(#204213),#84023, - #203701); -#204213 = PRESENTATION_STYLE_ASSIGNMENT((#204214)); -#204214 = SURFACE_STYLE_USAGE(.BOTH.,#204215); -#204215 = SURFACE_SIDE_STYLE('',(#204216)); -#204216 = SURFACE_STYLE_FILL_AREA(#204217); -#204217 = FILL_AREA_STYLE('',(#204218)); -#204218 = FILL_AREA_STYLE_COLOUR('',#201028); -#204219 = OVER_RIDING_STYLED_ITEM('overriding color',(#204220),#84264, - #203701); -#204220 = PRESENTATION_STYLE_ASSIGNMENT((#204221)); -#204221 = SURFACE_STYLE_USAGE(.BOTH.,#204222); -#204222 = SURFACE_SIDE_STYLE('',(#204223)); -#204223 = SURFACE_STYLE_FILL_AREA(#204224); -#204224 = FILL_AREA_STYLE('',(#204225)); -#204225 = FILL_AREA_STYLE_COLOUR('',#201028); -#204226 = OVER_RIDING_STYLED_ITEM('overriding color',(#204227),#84311, - #203701); -#204227 = PRESENTATION_STYLE_ASSIGNMENT((#204228)); -#204228 = SURFACE_STYLE_USAGE(.BOTH.,#204229); -#204229 = SURFACE_SIDE_STYLE('',(#204230)); -#204230 = SURFACE_STYLE_FILL_AREA(#204231); -#204231 = FILL_AREA_STYLE('',(#204232)); -#204232 = FILL_AREA_STYLE_COLOUR('',#201028); -#204233 = OVER_RIDING_STYLED_ITEM('overriding color',(#204234),#84360, - #203701); -#204234 = PRESENTATION_STYLE_ASSIGNMENT((#204235)); -#204235 = SURFACE_STYLE_USAGE(.BOTH.,#204236); -#204236 = SURFACE_SIDE_STYLE('',(#204237)); -#204237 = SURFACE_STYLE_FILL_AREA(#204238); -#204238 = FILL_AREA_STYLE('',(#204239)); -#204239 = FILL_AREA_STYLE_COLOUR('',#201028); -#204240 = OVER_RIDING_STYLED_ITEM('overriding color',(#204241),#84386, - #203701); -#204241 = PRESENTATION_STYLE_ASSIGNMENT((#204242)); -#204242 = SURFACE_STYLE_USAGE(.BOTH.,#204243); -#204243 = SURFACE_SIDE_STYLE('',(#204244)); -#204244 = SURFACE_STYLE_FILL_AREA(#204245); -#204245 = FILL_AREA_STYLE('',(#204246)); -#204246 = FILL_AREA_STYLE_COLOUR('',#201028); -#204247 = OVER_RIDING_STYLED_ITEM('overriding color',(#204248),#84412, - #203701); -#204248 = PRESENTATION_STYLE_ASSIGNMENT((#204249)); -#204249 = SURFACE_STYLE_USAGE(.BOTH.,#204250); -#204250 = SURFACE_SIDE_STYLE('',(#204251)); -#204251 = SURFACE_STYLE_FILL_AREA(#204252); -#204252 = FILL_AREA_STYLE('',(#204253)); -#204253 = FILL_AREA_STYLE_COLOUR('',#201028); -#204254 = OVER_RIDING_STYLED_ITEM('overriding color',(#204255),#84438, - #203701); -#204255 = PRESENTATION_STYLE_ASSIGNMENT((#204256)); -#204256 = SURFACE_STYLE_USAGE(.BOTH.,#204257); -#204257 = SURFACE_SIDE_STYLE('',(#204258)); -#204258 = SURFACE_STYLE_FILL_AREA(#204259); -#204259 = FILL_AREA_STYLE('',(#204260)); -#204260 = FILL_AREA_STYLE_COLOUR('',#201028); -#204261 = OVER_RIDING_STYLED_ITEM('overriding color',(#204262),#84445, - #203701); -#204262 = PRESENTATION_STYLE_ASSIGNMENT((#204263)); -#204263 = SURFACE_STYLE_USAGE(.BOTH.,#204264); -#204264 = SURFACE_SIDE_STYLE('',(#204265)); -#204265 = SURFACE_STYLE_FILL_AREA(#204266); -#204266 = FILL_AREA_STYLE('',(#204267)); -#204267 = FILL_AREA_STYLE_COLOUR('',#201028); -#204268 = OVER_RIDING_STYLED_ITEM('overriding color',(#204269),#84471, - #203701); -#204269 = PRESENTATION_STYLE_ASSIGNMENT((#204270)); -#204270 = SURFACE_STYLE_USAGE(.BOTH.,#204271); -#204271 = SURFACE_SIDE_STYLE('',(#204272)); -#204272 = SURFACE_STYLE_FILL_AREA(#204273); -#204273 = FILL_AREA_STYLE('',(#204274)); -#204274 = FILL_AREA_STYLE_COLOUR('',#201028); -#204275 = OVER_RIDING_STYLED_ITEM('overriding color',(#204276),#84497, - #203701); -#204276 = PRESENTATION_STYLE_ASSIGNMENT((#204277)); -#204277 = SURFACE_STYLE_USAGE(.BOTH.,#204278); -#204278 = SURFACE_SIDE_STYLE('',(#204279)); -#204279 = SURFACE_STYLE_FILL_AREA(#204280); -#204280 = FILL_AREA_STYLE('',(#204281)); -#204281 = FILL_AREA_STYLE_COLOUR('',#201028); -#204282 = OVER_RIDING_STYLED_ITEM('overriding color',(#204283),#84546, - #203701); -#204283 = PRESENTATION_STYLE_ASSIGNMENT((#204284)); -#204284 = SURFACE_STYLE_USAGE(.BOTH.,#204285); -#204285 = SURFACE_SIDE_STYLE('',(#204286)); -#204286 = SURFACE_STYLE_FILL_AREA(#204287); -#204287 = FILL_AREA_STYLE('',(#204288)); -#204288 = FILL_AREA_STYLE_COLOUR('',#201028); -#204289 = OVER_RIDING_STYLED_ITEM('overriding color',(#204290),#84553, - #203701); -#204290 = PRESENTATION_STYLE_ASSIGNMENT((#204291)); -#204291 = SURFACE_STYLE_USAGE(.BOTH.,#204292); -#204292 = SURFACE_SIDE_STYLE('',(#204293)); -#204293 = SURFACE_STYLE_FILL_AREA(#204294); -#204294 = FILL_AREA_STYLE('',(#204295)); -#204295 = FILL_AREA_STYLE_COLOUR('',#201781); -#204296 = OVER_RIDING_STYLED_ITEM('overriding color',(#204297),#84691, - #203701); -#204297 = PRESENTATION_STYLE_ASSIGNMENT((#204298)); -#204298 = SURFACE_STYLE_USAGE(.BOTH.,#204299); -#204299 = SURFACE_SIDE_STYLE('',(#204300)); -#204300 = SURFACE_STYLE_FILL_AREA(#204301); -#204301 = FILL_AREA_STYLE('',(#204302)); -#204302 = FILL_AREA_STYLE_COLOUR('',#201781); -#204303 = OVER_RIDING_STYLED_ITEM('overriding color',(#204304),#84764, - #203701); -#204304 = PRESENTATION_STYLE_ASSIGNMENT((#204305)); -#204305 = SURFACE_STYLE_USAGE(.BOTH.,#204306); -#204306 = SURFACE_SIDE_STYLE('',(#204307)); -#204307 = SURFACE_STYLE_FILL_AREA(#204308); -#204308 = FILL_AREA_STYLE('',(#204309)); -#204309 = FILL_AREA_STYLE_COLOUR('',#201781); -#204310 = OVER_RIDING_STYLED_ITEM('overriding color',(#204311),#84902, - #203701); -#204311 = PRESENTATION_STYLE_ASSIGNMENT((#204312)); -#204312 = SURFACE_STYLE_USAGE(.BOTH.,#204313); -#204313 = SURFACE_SIDE_STYLE('',(#204314)); -#204314 = SURFACE_STYLE_FILL_AREA(#204315); -#204315 = FILL_AREA_STYLE('',(#204316)); -#204316 = FILL_AREA_STYLE_COLOUR('',#201781); -#204317 = OVER_RIDING_STYLED_ITEM('overriding color',(#204318),#84975, - #203701); -#204318 = PRESENTATION_STYLE_ASSIGNMENT((#204319)); -#204319 = SURFACE_STYLE_USAGE(.BOTH.,#204320); -#204320 = SURFACE_SIDE_STYLE('',(#204321)); -#204321 = SURFACE_STYLE_FILL_AREA(#204322); -#204322 = FILL_AREA_STYLE('',(#204323)); -#204323 = FILL_AREA_STYLE_COLOUR('',#201781); -#204324 = OVER_RIDING_STYLED_ITEM('overriding color',(#204325),#85113, - #203701); -#204325 = PRESENTATION_STYLE_ASSIGNMENT((#204326)); -#204326 = SURFACE_STYLE_USAGE(.BOTH.,#204327); -#204327 = SURFACE_SIDE_STYLE('',(#204328)); -#204328 = SURFACE_STYLE_FILL_AREA(#204329); -#204329 = FILL_AREA_STYLE('',(#204330)); -#204330 = FILL_AREA_STYLE_COLOUR('',#201781); -#204331 = OVER_RIDING_STYLED_ITEM('overriding color',(#204332),#85186, - #203701); -#204332 = PRESENTATION_STYLE_ASSIGNMENT((#204333)); -#204333 = SURFACE_STYLE_USAGE(.BOTH.,#204334); -#204334 = SURFACE_SIDE_STYLE('',(#204335)); -#204335 = SURFACE_STYLE_FILL_AREA(#204336); -#204336 = FILL_AREA_STYLE('',(#204337)); -#204337 = FILL_AREA_STYLE_COLOUR('',#201781); -#204338 = OVER_RIDING_STYLED_ITEM('overriding color',(#204339),#85324, - #203701); -#204339 = PRESENTATION_STYLE_ASSIGNMENT((#204340)); -#204340 = SURFACE_STYLE_USAGE(.BOTH.,#204341); -#204341 = SURFACE_SIDE_STYLE('',(#204342)); -#204342 = SURFACE_STYLE_FILL_AREA(#204343); -#204343 = FILL_AREA_STYLE('',(#204344)); -#204344 = FILL_AREA_STYLE_COLOUR('',#201781); -#204345 = OVER_RIDING_STYLED_ITEM('overriding color',(#204346),#85397, - #203701); -#204346 = PRESENTATION_STYLE_ASSIGNMENT((#204347)); -#204347 = SURFACE_STYLE_USAGE(.BOTH.,#204348); -#204348 = SURFACE_SIDE_STYLE('',(#204349)); -#204349 = SURFACE_STYLE_FILL_AREA(#204350); -#204350 = FILL_AREA_STYLE('',(#204351)); -#204351 = FILL_AREA_STYLE_COLOUR('',#201781); -#204352 = OVER_RIDING_STYLED_ITEM('overriding color',(#204353),#85446, - #203701); -#204353 = PRESENTATION_STYLE_ASSIGNMENT((#204354)); -#204354 = SURFACE_STYLE_USAGE(.BOTH.,#204355); -#204355 = SURFACE_SIDE_STYLE('',(#204356)); -#204356 = SURFACE_STYLE_FILL_AREA(#204357); -#204357 = FILL_AREA_STYLE('',(#204358)); -#204358 = FILL_AREA_STYLE_COLOUR('',#201781); -#204359 = OVER_RIDING_STYLED_ITEM('overriding color',(#204360),#85453, - #203701); -#204360 = PRESENTATION_STYLE_ASSIGNMENT((#204361)); -#204361 = SURFACE_STYLE_USAGE(.BOTH.,#204362); -#204362 = SURFACE_SIDE_STYLE('',(#204363)); -#204363 = SURFACE_STYLE_FILL_AREA(#204364); -#204364 = FILL_AREA_STYLE('',(#204365)); -#204365 = FILL_AREA_STYLE_COLOUR('',#201781); -#204366 = OVER_RIDING_STYLED_ITEM('overriding color',(#204367),#85502, - #203701); -#204367 = PRESENTATION_STYLE_ASSIGNMENT((#204368)); -#204368 = SURFACE_STYLE_USAGE(.BOTH.,#204369); -#204369 = SURFACE_SIDE_STYLE('',(#204370)); -#204370 = SURFACE_STYLE_FILL_AREA(#204371); -#204371 = FILL_AREA_STYLE('',(#204372)); -#204372 = FILL_AREA_STYLE_COLOUR('',#201781); -#204373 = OVER_RIDING_STYLED_ITEM('overriding color',(#204374),#85551, - #203701); -#204374 = PRESENTATION_STYLE_ASSIGNMENT((#204375)); -#204375 = SURFACE_STYLE_USAGE(.BOTH.,#204376); -#204376 = SURFACE_SIDE_STYLE('',(#204377)); -#204377 = SURFACE_STYLE_FILL_AREA(#204378); -#204378 = FILL_AREA_STYLE('',(#204379)); -#204379 = FILL_AREA_STYLE_COLOUR('',#201781); -#204380 = OVER_RIDING_STYLED_ITEM('overriding color',(#204381),#85558, - #203701); -#204381 = PRESENTATION_STYLE_ASSIGNMENT((#204382)); -#204382 = SURFACE_STYLE_USAGE(.BOTH.,#204383); -#204383 = SURFACE_SIDE_STYLE('',(#204384)); -#204384 = SURFACE_STYLE_FILL_AREA(#204385); -#204385 = FILL_AREA_STYLE('',(#204386)); -#204386 = FILL_AREA_STYLE_COLOUR('',#201781); -#204387 = OVER_RIDING_STYLED_ITEM('overriding color',(#204388),#85565, - #203701); -#204388 = PRESENTATION_STYLE_ASSIGNMENT((#204389)); -#204389 = SURFACE_STYLE_USAGE(.BOTH.,#204390); -#204390 = SURFACE_SIDE_STYLE('',(#204391)); -#204391 = SURFACE_STYLE_FILL_AREA(#204392); -#204392 = FILL_AREA_STYLE('',(#204393)); -#204393 = FILL_AREA_STYLE_COLOUR('',#201781); -#204394 = OVER_RIDING_STYLED_ITEM('overriding color',(#204395),#85614, - #203701); -#204395 = PRESENTATION_STYLE_ASSIGNMENT((#204396)); -#204396 = SURFACE_STYLE_USAGE(.BOTH.,#204397); -#204397 = SURFACE_SIDE_STYLE('',(#204398)); -#204398 = SURFACE_STYLE_FILL_AREA(#204399); -#204399 = FILL_AREA_STYLE('',(#204400)); -#204400 = FILL_AREA_STYLE_COLOUR('',#201781); -#204401 = OVER_RIDING_STYLED_ITEM('overriding color',(#204402),#85621, - #203701); -#204402 = PRESENTATION_STYLE_ASSIGNMENT((#204403)); -#204403 = SURFACE_STYLE_USAGE(.BOTH.,#204404); -#204404 = SURFACE_SIDE_STYLE('',(#204405)); -#204405 = SURFACE_STYLE_FILL_AREA(#204406); -#204406 = FILL_AREA_STYLE('',(#204407)); -#204407 = FILL_AREA_STYLE_COLOUR('',#201781); -#204408 = OVER_RIDING_STYLED_ITEM('overriding color',(#204409),#85670, - #203701); -#204409 = PRESENTATION_STYLE_ASSIGNMENT((#204410)); -#204410 = SURFACE_STYLE_USAGE(.BOTH.,#204411); -#204411 = SURFACE_SIDE_STYLE('',(#204412)); -#204412 = SURFACE_STYLE_FILL_AREA(#204413); -#204413 = FILL_AREA_STYLE('',(#204414)); -#204414 = FILL_AREA_STYLE_COLOUR('',#201781); -#204415 = OVER_RIDING_STYLED_ITEM('overriding color',(#204416),#85742, - #203701); -#204416 = PRESENTATION_STYLE_ASSIGNMENT((#204417)); -#204417 = SURFACE_STYLE_USAGE(.BOTH.,#204418); -#204418 = SURFACE_SIDE_STYLE('',(#204419)); -#204419 = SURFACE_STYLE_FILL_AREA(#204420); -#204420 = FILL_AREA_STYLE('',(#204421)); -#204421 = FILL_AREA_STYLE_COLOUR('',#201781); -#204422 = OVER_RIDING_STYLED_ITEM('overriding color',(#204423),#85749, - #203701); -#204423 = PRESENTATION_STYLE_ASSIGNMENT((#204424)); -#204424 = SURFACE_STYLE_USAGE(.BOTH.,#204425); -#204425 = SURFACE_SIDE_STYLE('',(#204426)); -#204426 = SURFACE_STYLE_FILL_AREA(#204427); -#204427 = FILL_AREA_STYLE('',(#204428)); -#204428 = FILL_AREA_STYLE_COLOUR('',#201781); -#204429 = OVER_RIDING_STYLED_ITEM('overriding color',(#204430),#85756, - #203701); -#204430 = PRESENTATION_STYLE_ASSIGNMENT((#204431)); -#204431 = SURFACE_STYLE_USAGE(.BOTH.,#204432); -#204432 = SURFACE_SIDE_STYLE('',(#204433)); -#204433 = SURFACE_STYLE_FILL_AREA(#204434); -#204434 = FILL_AREA_STYLE('',(#204435)); -#204435 = FILL_AREA_STYLE_COLOUR('',#201781); -#204436 = OVER_RIDING_STYLED_ITEM('overriding color',(#204437),#85805, - #203701); -#204437 = PRESENTATION_STYLE_ASSIGNMENT((#204438)); -#204438 = SURFACE_STYLE_USAGE(.BOTH.,#204439); -#204439 = SURFACE_SIDE_STYLE('',(#204440)); -#204440 = SURFACE_STYLE_FILL_AREA(#204441); -#204441 = FILL_AREA_STYLE('',(#204442)); -#204442 = FILL_AREA_STYLE_COLOUR('',#201781); -#204443 = OVER_RIDING_STYLED_ITEM('overriding color',(#204444),#85877, - #203701); -#204444 = PRESENTATION_STYLE_ASSIGNMENT((#204445)); -#204445 = SURFACE_STYLE_USAGE(.BOTH.,#204446); -#204446 = SURFACE_SIDE_STYLE('',(#204447)); -#204447 = SURFACE_STYLE_FILL_AREA(#204448); -#204448 = FILL_AREA_STYLE('',(#204449)); -#204449 = FILL_AREA_STYLE_COLOUR('',#201781); -#204450 = OVER_RIDING_STYLED_ITEM('overriding color',(#204451),#85884, - #203701); -#204451 = PRESENTATION_STYLE_ASSIGNMENT((#204452)); -#204452 = SURFACE_STYLE_USAGE(.BOTH.,#204453); -#204453 = SURFACE_SIDE_STYLE('',(#204454)); -#204454 = SURFACE_STYLE_FILL_AREA(#204455); -#204455 = FILL_AREA_STYLE('',(#204456)); -#204456 = FILL_AREA_STYLE_COLOUR('',#201781); -#204457 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #204458,#204466,#204474,#204481,#204488,#204495,#204502,#204509, - #204516,#204523,#204530,#204537,#204544,#204551,#204558,#204565, - #204572,#204579,#204586,#204593,#204600,#204607,#204614,#204621, - #204628,#204635,#204642,#204649,#204656,#204663,#204670,#204677, - #204684,#204691,#204698,#204705,#204712,#204719,#204726,#204733, - #204740,#204747,#204754,#204761,#204768,#204775,#204782,#204789, - #204796,#204803,#204810,#204817,#204824,#204831,#204838,#204845, - #204852,#204859,#204866,#204873,#204880,#204887,#204894,#204901, - #204908,#204915,#204922,#204929,#204936,#204943,#204950,#204957, - #204964,#204971,#204978,#204985,#204992,#204999,#205006,#205013, - #205020,#205027,#205034,#205041,#205048,#205055,#205062,#205069, - #205076,#205083,#205090,#205097,#205104,#205111,#205118),#165998); -#204458 = STYLED_ITEM('color',(#204459),#158708); -#204459 = PRESENTATION_STYLE_ASSIGNMENT((#204460)); -#204460 = SURFACE_STYLE_USAGE(.BOTH.,#204461); -#204461 = SURFACE_SIDE_STYLE('',(#204462)); -#204462 = SURFACE_STYLE_FILL_AREA(#204463); -#204463 = FILL_AREA_STYLE('',(#204464)); -#204464 = FILL_AREA_STYLE_COLOUR('',#204465); -#204465 = COLOUR_RGB('',0.780392169952,0.780392169952,0.86274510622); -#204466 = OVER_RIDING_STYLED_ITEM('overriding color',(#204467),#158710, - #204458); -#204467 = PRESENTATION_STYLE_ASSIGNMENT((#204468)); -#204468 = SURFACE_STYLE_USAGE(.BOTH.,#204469); -#204469 = SURFACE_SIDE_STYLE('',(#204470)); -#204470 = SURFACE_STYLE_FILL_AREA(#204471); -#204471 = FILL_AREA_STYLE('',(#204472)); -#204472 = FILL_AREA_STYLE_COLOUR('',#204473); -#204473 = COLOUR_RGB('',0.784313738346,0.784313738346,0.86274510622); -#204474 = OVER_RIDING_STYLED_ITEM('overriding color',(#204475),#158828, - #204458); +#202996 = FILL_AREA_STYLE_COLOUR('',#198418); +#202997 = OVER_RIDING_STYLED_ITEM('overriding color',(#202998),#140710, + #198353); +#202998 = PRESENTATION_STYLE_ASSIGNMENT((#202999)); +#202999 = SURFACE_STYLE_USAGE(.BOTH.,#203000); +#203000 = SURFACE_SIDE_STYLE('',(#203001)); +#203001 = SURFACE_STYLE_FILL_AREA(#203002); +#203002 = FILL_AREA_STYLE('',(#203003)); +#203003 = FILL_AREA_STYLE_COLOUR('',#198418); +#203004 = OVER_RIDING_STYLED_ITEM('overriding color',(#203005),#140785, + #198353); +#203005 = PRESENTATION_STYLE_ASSIGNMENT((#203006)); +#203006 = SURFACE_STYLE_USAGE(.BOTH.,#203007); +#203007 = SURFACE_SIDE_STYLE('',(#203008)); +#203008 = SURFACE_STYLE_FILL_AREA(#203009); +#203009 = FILL_AREA_STYLE('',(#203010)); +#203010 = FILL_AREA_STYLE_COLOUR('',#198418); +#203011 = OVER_RIDING_STYLED_ITEM('overriding color',(#203012),#140859, + #198353); +#203012 = PRESENTATION_STYLE_ASSIGNMENT((#203013)); +#203013 = SURFACE_STYLE_USAGE(.BOTH.,#203014); +#203014 = SURFACE_SIDE_STYLE('',(#203015)); +#203015 = SURFACE_STYLE_FILL_AREA(#203016); +#203016 = FILL_AREA_STYLE('',(#203017)); +#203017 = FILL_AREA_STYLE_COLOUR('',#198418); +#203018 = OVER_RIDING_STYLED_ITEM('overriding color',(#203019),#140933, + #198353); +#203019 = PRESENTATION_STYLE_ASSIGNMENT((#203020)); +#203020 = SURFACE_STYLE_USAGE(.BOTH.,#203021); +#203021 = SURFACE_SIDE_STYLE('',(#203022)); +#203022 = SURFACE_STYLE_FILL_AREA(#203023); +#203023 = FILL_AREA_STYLE('',(#203024)); +#203024 = FILL_AREA_STYLE_COLOUR('',#198418); +#203025 = OVER_RIDING_STYLED_ITEM('overriding color',(#203026),#141008, + #198353); +#203026 = PRESENTATION_STYLE_ASSIGNMENT((#203027)); +#203027 = SURFACE_STYLE_USAGE(.BOTH.,#203028); +#203028 = SURFACE_SIDE_STYLE('',(#203029)); +#203029 = SURFACE_STYLE_FILL_AREA(#203030); +#203030 = FILL_AREA_STYLE('',(#203031)); +#203031 = FILL_AREA_STYLE_COLOUR('',#198418); +#203032 = OVER_RIDING_STYLED_ITEM('overriding color',(#203033),#141035, + #198353); +#203033 = PRESENTATION_STYLE_ASSIGNMENT((#203034)); +#203034 = SURFACE_STYLE_USAGE(.BOTH.,#203035); +#203035 = SURFACE_SIDE_STYLE('',(#203036)); +#203036 = SURFACE_STYLE_FILL_AREA(#203037); +#203037 = FILL_AREA_STYLE('',(#203038)); +#203038 = FILL_AREA_STYLE_COLOUR('',#198418); +#203039 = OVER_RIDING_STYLED_ITEM('overriding color',(#203040),#141090, + #198353); +#203040 = PRESENTATION_STYLE_ASSIGNMENT((#203041)); +#203041 = SURFACE_STYLE_USAGE(.BOTH.,#203042); +#203042 = SURFACE_SIDE_STYLE('',(#203043)); +#203043 = SURFACE_STYLE_FILL_AREA(#203044); +#203044 = FILL_AREA_STYLE('',(#203045)); +#203045 = FILL_AREA_STYLE_COLOUR('',#198418); +#203046 = OVER_RIDING_STYLED_ITEM('overriding color',(#203047),#141097, + #198353); +#203047 = PRESENTATION_STYLE_ASSIGNMENT((#203048)); +#203048 = SURFACE_STYLE_USAGE(.BOTH.,#203049); +#203049 = SURFACE_SIDE_STYLE('',(#203050)); +#203050 = SURFACE_STYLE_FILL_AREA(#203051); +#203051 = FILL_AREA_STYLE('',(#203052)); +#203052 = FILL_AREA_STYLE_COLOUR('',#198418); +#203053 = OVER_RIDING_STYLED_ITEM('overriding color',(#203054),#141104, + #198353); +#203054 = PRESENTATION_STYLE_ASSIGNMENT((#203055)); +#203055 = SURFACE_STYLE_USAGE(.BOTH.,#203056); +#203056 = SURFACE_SIDE_STYLE('',(#203057)); +#203057 = SURFACE_STYLE_FILL_AREA(#203058); +#203058 = FILL_AREA_STYLE('',(#203059)); +#203059 = FILL_AREA_STYLE_COLOUR('',#198418); +#203060 = OVER_RIDING_STYLED_ITEM('overriding color',(#203061),#141213, + #198353); +#203061 = PRESENTATION_STYLE_ASSIGNMENT((#203062)); +#203062 = SURFACE_STYLE_USAGE(.BOTH.,#203063); +#203063 = SURFACE_SIDE_STYLE('',(#203064)); +#203064 = SURFACE_STYLE_FILL_AREA(#203065); +#203065 = FILL_AREA_STYLE('',(#203066)); +#203066 = FILL_AREA_STYLE_COLOUR('',#198418); +#203067 = OVER_RIDING_STYLED_ITEM('overriding color',(#203068),#141317, + #198353); +#203068 = PRESENTATION_STYLE_ASSIGNMENT((#203069)); +#203069 = SURFACE_STYLE_USAGE(.BOTH.,#203070); +#203070 = SURFACE_SIDE_STYLE('',(#203071)); +#203071 = SURFACE_STYLE_FILL_AREA(#203072); +#203072 = FILL_AREA_STYLE('',(#203073)); +#203073 = FILL_AREA_STYLE_COLOUR('',#198418); +#203074 = OVER_RIDING_STYLED_ITEM('overriding color',(#203075),#141396, + #198353); +#203075 = PRESENTATION_STYLE_ASSIGNMENT((#203076)); +#203076 = SURFACE_STYLE_USAGE(.BOTH.,#203077); +#203077 = SURFACE_SIDE_STYLE('',(#203078)); +#203078 = SURFACE_STYLE_FILL_AREA(#203079); +#203079 = FILL_AREA_STYLE('',(#203080)); +#203080 = FILL_AREA_STYLE_COLOUR('',#198418); +#203081 = OVER_RIDING_STYLED_ITEM('overriding color',(#203082),#141521, + #198353); +#203082 = PRESENTATION_STYLE_ASSIGNMENT((#203083)); +#203083 = SURFACE_STYLE_USAGE(.BOTH.,#203084); +#203084 = SURFACE_SIDE_STYLE('',(#203085)); +#203085 = SURFACE_STYLE_FILL_AREA(#203086); +#203086 = FILL_AREA_STYLE('',(#203087)); +#203087 = FILL_AREA_STYLE_COLOUR('',#198418); +#203088 = OVER_RIDING_STYLED_ITEM('overriding color',(#203089),#141596, + #198353); +#203089 = PRESENTATION_STYLE_ASSIGNMENT((#203090)); +#203090 = SURFACE_STYLE_USAGE(.BOTH.,#203091); +#203091 = SURFACE_SIDE_STYLE('',(#203092)); +#203092 = SURFACE_STYLE_FILL_AREA(#203093); +#203093 = FILL_AREA_STYLE('',(#203094)); +#203094 = FILL_AREA_STYLE_COLOUR('',#198418); +#203095 = OVER_RIDING_STYLED_ITEM('overriding color',(#203096),#141671, + #198353); +#203096 = PRESENTATION_STYLE_ASSIGNMENT((#203097)); +#203097 = SURFACE_STYLE_USAGE(.BOTH.,#203098); +#203098 = SURFACE_SIDE_STYLE('',(#203099)); +#203099 = SURFACE_STYLE_FILL_AREA(#203100); +#203100 = FILL_AREA_STYLE('',(#203101)); +#203101 = FILL_AREA_STYLE_COLOUR('',#198418); +#203102 = OVER_RIDING_STYLED_ITEM('overriding color',(#203103),#141745, + #198353); +#203103 = PRESENTATION_STYLE_ASSIGNMENT((#203104)); +#203104 = SURFACE_STYLE_USAGE(.BOTH.,#203105); +#203105 = SURFACE_SIDE_STYLE('',(#203106)); +#203106 = SURFACE_STYLE_FILL_AREA(#203107); +#203107 = FILL_AREA_STYLE('',(#203108)); +#203108 = FILL_AREA_STYLE_COLOUR('',#198418); +#203109 = OVER_RIDING_STYLED_ITEM('overriding color',(#203110),#141865, + #198353); +#203110 = PRESENTATION_STYLE_ASSIGNMENT((#203111)); +#203111 = SURFACE_STYLE_USAGE(.BOTH.,#203112); +#203112 = SURFACE_SIDE_STYLE('',(#203113)); +#203113 = SURFACE_STYLE_FILL_AREA(#203114); +#203114 = FILL_AREA_STYLE('',(#203115)); +#203115 = FILL_AREA_STYLE_COLOUR('',#198418); +#203116 = OVER_RIDING_STYLED_ITEM('overriding color',(#203117),#141940, + #198353); +#203117 = PRESENTATION_STYLE_ASSIGNMENT((#203118)); +#203118 = SURFACE_STYLE_USAGE(.BOTH.,#203119); +#203119 = SURFACE_SIDE_STYLE('',(#203120)); +#203120 = SURFACE_STYLE_FILL_AREA(#203121); +#203121 = FILL_AREA_STYLE('',(#203122)); +#203122 = FILL_AREA_STYLE_COLOUR('',#198418); +#203123 = OVER_RIDING_STYLED_ITEM('overriding color',(#203124),#141967, + #198353); +#203124 = PRESENTATION_STYLE_ASSIGNMENT((#203125)); +#203125 = SURFACE_STYLE_USAGE(.BOTH.,#203126); +#203126 = SURFACE_SIDE_STYLE('',(#203127)); +#203127 = SURFACE_STYLE_FILL_AREA(#203128); +#203128 = FILL_AREA_STYLE('',(#203129)); +#203129 = FILL_AREA_STYLE_COLOUR('',#198418); +#203130 = OVER_RIDING_STYLED_ITEM('overriding color',(#203131),#142022, + #198353); +#203131 = PRESENTATION_STYLE_ASSIGNMENT((#203132)); +#203132 = SURFACE_STYLE_USAGE(.BOTH.,#203133); +#203133 = SURFACE_SIDE_STYLE('',(#203134)); +#203134 = SURFACE_STYLE_FILL_AREA(#203135); +#203135 = FILL_AREA_STYLE('',(#203136)); +#203136 = FILL_AREA_STYLE_COLOUR('',#198418); +#203137 = OVER_RIDING_STYLED_ITEM('overriding color',(#203138),#142029, + #198353); +#203138 = PRESENTATION_STYLE_ASSIGNMENT((#203139)); +#203139 = SURFACE_STYLE_USAGE(.BOTH.,#203140); +#203140 = SURFACE_SIDE_STYLE('',(#203141)); +#203141 = SURFACE_STYLE_FILL_AREA(#203142); +#203142 = FILL_AREA_STYLE('',(#203143)); +#203143 = FILL_AREA_STYLE_COLOUR('',#198418); +#203144 = OVER_RIDING_STYLED_ITEM('overriding color',(#203145),#142036, + #198353); +#203145 = PRESENTATION_STYLE_ASSIGNMENT((#203146)); +#203146 = SURFACE_STYLE_USAGE(.BOTH.,#203147); +#203147 = SURFACE_SIDE_STYLE('',(#203148)); +#203148 = SURFACE_STYLE_FILL_AREA(#203149); +#203149 = FILL_AREA_STYLE('',(#203150)); +#203150 = FILL_AREA_STYLE_COLOUR('',#198418); +#203151 = OVER_RIDING_STYLED_ITEM('overriding color',(#203152),#142145, + #198353); +#203152 = PRESENTATION_STYLE_ASSIGNMENT((#203153)); +#203153 = SURFACE_STYLE_USAGE(.BOTH.,#203154); +#203154 = SURFACE_SIDE_STYLE('',(#203155)); +#203155 = SURFACE_STYLE_FILL_AREA(#203156); +#203156 = FILL_AREA_STYLE('',(#203157)); +#203157 = FILL_AREA_STYLE_COLOUR('',#198418); +#203158 = OVER_RIDING_STYLED_ITEM('overriding color',(#203159),#142249, + #198353); +#203159 = PRESENTATION_STYLE_ASSIGNMENT((#203160)); +#203160 = SURFACE_STYLE_USAGE(.BOTH.,#203161); +#203161 = SURFACE_SIDE_STYLE('',(#203162)); +#203162 = SURFACE_STYLE_FILL_AREA(#203163); +#203163 = FILL_AREA_STYLE('',(#203164)); +#203164 = FILL_AREA_STYLE_COLOUR('',#198418); +#203165 = OVER_RIDING_STYLED_ITEM('overriding color',(#203166),#142328, + #198353); +#203166 = PRESENTATION_STYLE_ASSIGNMENT((#203167)); +#203167 = SURFACE_STYLE_USAGE(.BOTH.,#203168); +#203168 = SURFACE_SIDE_STYLE('',(#203169)); +#203169 = SURFACE_STYLE_FILL_AREA(#203170); +#203170 = FILL_AREA_STYLE('',(#203171)); +#203171 = FILL_AREA_STYLE_COLOUR('',#198418); +#203172 = OVER_RIDING_STYLED_ITEM('overriding color',(#203173),#142453, + #198353); +#203173 = PRESENTATION_STYLE_ASSIGNMENT((#203174)); +#203174 = SURFACE_STYLE_USAGE(.BOTH.,#203175); +#203175 = SURFACE_SIDE_STYLE('',(#203176)); +#203176 = SURFACE_STYLE_FILL_AREA(#203177); +#203177 = FILL_AREA_STYLE('',(#203178)); +#203178 = FILL_AREA_STYLE_COLOUR('',#198418); +#203179 = OVER_RIDING_STYLED_ITEM('overriding color',(#203180),#142528, + #198353); +#203180 = PRESENTATION_STYLE_ASSIGNMENT((#203181)); +#203181 = SURFACE_STYLE_USAGE(.BOTH.,#203182); +#203182 = SURFACE_SIDE_STYLE('',(#203183)); +#203183 = SURFACE_STYLE_FILL_AREA(#203184); +#203184 = FILL_AREA_STYLE('',(#203185)); +#203185 = FILL_AREA_STYLE_COLOUR('',#198418); +#203186 = OVER_RIDING_STYLED_ITEM('overriding color',(#203187),#142603, + #198353); +#203187 = PRESENTATION_STYLE_ASSIGNMENT((#203188)); +#203188 = SURFACE_STYLE_USAGE(.BOTH.,#203189); +#203189 = SURFACE_SIDE_STYLE('',(#203190)); +#203190 = SURFACE_STYLE_FILL_AREA(#203191); +#203191 = FILL_AREA_STYLE('',(#203192)); +#203192 = FILL_AREA_STYLE_COLOUR('',#198418); +#203193 = OVER_RIDING_STYLED_ITEM('overriding color',(#203194),#142677, + #198353); +#203194 = PRESENTATION_STYLE_ASSIGNMENT((#203195)); +#203195 = SURFACE_STYLE_USAGE(.BOTH.,#203196); +#203196 = SURFACE_SIDE_STYLE('',(#203197)); +#203197 = SURFACE_STYLE_FILL_AREA(#203198); +#203198 = FILL_AREA_STYLE('',(#203199)); +#203199 = FILL_AREA_STYLE_COLOUR('',#198418); +#203200 = OVER_RIDING_STYLED_ITEM('overriding color',(#203201),#142797, + #198353); +#203201 = PRESENTATION_STYLE_ASSIGNMENT((#203202)); +#203202 = SURFACE_STYLE_USAGE(.BOTH.,#203203); +#203203 = SURFACE_SIDE_STYLE('',(#203204)); +#203204 = SURFACE_STYLE_FILL_AREA(#203205); +#203205 = FILL_AREA_STYLE('',(#203206)); +#203206 = FILL_AREA_STYLE_COLOUR('',#198418); +#203207 = OVER_RIDING_STYLED_ITEM('overriding color',(#203208),#142872, + #198353); +#203208 = PRESENTATION_STYLE_ASSIGNMENT((#203209)); +#203209 = SURFACE_STYLE_USAGE(.BOTH.,#203210); +#203210 = SURFACE_SIDE_STYLE('',(#203211)); +#203211 = SURFACE_STYLE_FILL_AREA(#203212); +#203212 = FILL_AREA_STYLE('',(#203213)); +#203213 = FILL_AREA_STYLE_COLOUR('',#198418); +#203214 = OVER_RIDING_STYLED_ITEM('overriding color',(#203215),#142899, + #198353); +#203215 = PRESENTATION_STYLE_ASSIGNMENT((#203216)); +#203216 = SURFACE_STYLE_USAGE(.BOTH.,#203217); +#203217 = SURFACE_SIDE_STYLE('',(#203218)); +#203218 = SURFACE_STYLE_FILL_AREA(#203219); +#203219 = FILL_AREA_STYLE('',(#203220)); +#203220 = FILL_AREA_STYLE_COLOUR('',#198418); +#203221 = OVER_RIDING_STYLED_ITEM('overriding color',(#203222),#142954, + #198353); +#203222 = PRESENTATION_STYLE_ASSIGNMENT((#203223)); +#203223 = SURFACE_STYLE_USAGE(.BOTH.,#203224); +#203224 = SURFACE_SIDE_STYLE('',(#203225)); +#203225 = SURFACE_STYLE_FILL_AREA(#203226); +#203226 = FILL_AREA_STYLE('',(#203227)); +#203227 = FILL_AREA_STYLE_COLOUR('',#198418); +#203228 = OVER_RIDING_STYLED_ITEM('overriding color',(#203229),#142961, + #198353); +#203229 = PRESENTATION_STYLE_ASSIGNMENT((#203230)); +#203230 = SURFACE_STYLE_USAGE(.BOTH.,#203231); +#203231 = SURFACE_SIDE_STYLE('',(#203232)); +#203232 = SURFACE_STYLE_FILL_AREA(#203233); +#203233 = FILL_AREA_STYLE('',(#203234)); +#203234 = FILL_AREA_STYLE_COLOUR('',#198418); +#203235 = OVER_RIDING_STYLED_ITEM('overriding color',(#203236),#142968, + #198353); +#203236 = PRESENTATION_STYLE_ASSIGNMENT((#203237)); +#203237 = SURFACE_STYLE_USAGE(.BOTH.,#203238); +#203238 = SURFACE_SIDE_STYLE('',(#203239)); +#203239 = SURFACE_STYLE_FILL_AREA(#203240); +#203240 = FILL_AREA_STYLE('',(#203241)); +#203241 = FILL_AREA_STYLE_COLOUR('',#198418); +#203242 = OVER_RIDING_STYLED_ITEM('overriding color',(#203243),#143077, + #198353); +#203243 = PRESENTATION_STYLE_ASSIGNMENT((#203244)); +#203244 = SURFACE_STYLE_USAGE(.BOTH.,#203245); +#203245 = SURFACE_SIDE_STYLE('',(#203246)); +#203246 = SURFACE_STYLE_FILL_AREA(#203247); +#203247 = FILL_AREA_STYLE('',(#203248)); +#203248 = FILL_AREA_STYLE_COLOUR('',#198418); +#203249 = OVER_RIDING_STYLED_ITEM('overriding color',(#203250),#143181, + #198353); +#203250 = PRESENTATION_STYLE_ASSIGNMENT((#203251)); +#203251 = SURFACE_STYLE_USAGE(.BOTH.,#203252); +#203252 = SURFACE_SIDE_STYLE('',(#203253)); +#203253 = SURFACE_STYLE_FILL_AREA(#203254); +#203254 = FILL_AREA_STYLE('',(#203255)); +#203255 = FILL_AREA_STYLE_COLOUR('',#198418); +#203256 = OVER_RIDING_STYLED_ITEM('overriding color',(#203257),#143260, + #198353); +#203257 = PRESENTATION_STYLE_ASSIGNMENT((#203258)); +#203258 = SURFACE_STYLE_USAGE(.BOTH.,#203259); +#203259 = SURFACE_SIDE_STYLE('',(#203260)); +#203260 = SURFACE_STYLE_FILL_AREA(#203261); +#203261 = FILL_AREA_STYLE('',(#203262)); +#203262 = FILL_AREA_STYLE_COLOUR('',#198418); +#203263 = OVER_RIDING_STYLED_ITEM('overriding color',(#203264),#143385, + #198353); +#203264 = PRESENTATION_STYLE_ASSIGNMENT((#203265)); +#203265 = SURFACE_STYLE_USAGE(.BOTH.,#203266); +#203266 = SURFACE_SIDE_STYLE('',(#203267)); +#203267 = SURFACE_STYLE_FILL_AREA(#203268); +#203268 = FILL_AREA_STYLE('',(#203269)); +#203269 = FILL_AREA_STYLE_COLOUR('',#198418); +#203270 = OVER_RIDING_STYLED_ITEM('overriding color',(#203271),#143460, + #198353); +#203271 = PRESENTATION_STYLE_ASSIGNMENT((#203272)); +#203272 = SURFACE_STYLE_USAGE(.BOTH.,#203273); +#203273 = SURFACE_SIDE_STYLE('',(#203274)); +#203274 = SURFACE_STYLE_FILL_AREA(#203275); +#203275 = FILL_AREA_STYLE('',(#203276)); +#203276 = FILL_AREA_STYLE_COLOUR('',#198418); +#203277 = OVER_RIDING_STYLED_ITEM('overriding color',(#203278),#143535, + #198353); +#203278 = PRESENTATION_STYLE_ASSIGNMENT((#203279)); +#203279 = SURFACE_STYLE_USAGE(.BOTH.,#203280); +#203280 = SURFACE_SIDE_STYLE('',(#203281)); +#203281 = SURFACE_STYLE_FILL_AREA(#203282); +#203282 = FILL_AREA_STYLE('',(#203283)); +#203283 = FILL_AREA_STYLE_COLOUR('',#198418); +#203284 = OVER_RIDING_STYLED_ITEM('overriding color',(#203285),#143609, + #198353); +#203285 = PRESENTATION_STYLE_ASSIGNMENT((#203286)); +#203286 = SURFACE_STYLE_USAGE(.BOTH.,#203287); +#203287 = SURFACE_SIDE_STYLE('',(#203288)); +#203288 = SURFACE_STYLE_FILL_AREA(#203289); +#203289 = FILL_AREA_STYLE('',(#203290)); +#203290 = FILL_AREA_STYLE_COLOUR('',#198418); +#203291 = OVER_RIDING_STYLED_ITEM('overriding color',(#203292),#143729, + #198353); +#203292 = PRESENTATION_STYLE_ASSIGNMENT((#203293)); +#203293 = SURFACE_STYLE_USAGE(.BOTH.,#203294); +#203294 = SURFACE_SIDE_STYLE('',(#203295)); +#203295 = SURFACE_STYLE_FILL_AREA(#203296); +#203296 = FILL_AREA_STYLE('',(#203297)); +#203297 = FILL_AREA_STYLE_COLOUR('',#198418); +#203298 = OVER_RIDING_STYLED_ITEM('overriding color',(#203299),#143804, + #198353); +#203299 = PRESENTATION_STYLE_ASSIGNMENT((#203300)); +#203300 = SURFACE_STYLE_USAGE(.BOTH.,#203301); +#203301 = SURFACE_SIDE_STYLE('',(#203302)); +#203302 = SURFACE_STYLE_FILL_AREA(#203303); +#203303 = FILL_AREA_STYLE('',(#203304)); +#203304 = FILL_AREA_STYLE_COLOUR('',#198418); +#203305 = OVER_RIDING_STYLED_ITEM('overriding color',(#203306),#143831, + #198353); +#203306 = PRESENTATION_STYLE_ASSIGNMENT((#203307)); +#203307 = SURFACE_STYLE_USAGE(.BOTH.,#203308); +#203308 = SURFACE_SIDE_STYLE('',(#203309)); +#203309 = SURFACE_STYLE_FILL_AREA(#203310); +#203310 = FILL_AREA_STYLE('',(#203311)); +#203311 = FILL_AREA_STYLE_COLOUR('',#198418); +#203312 = OVER_RIDING_STYLED_ITEM('overriding color',(#203313),#143886, + #198353); +#203313 = PRESENTATION_STYLE_ASSIGNMENT((#203314)); +#203314 = SURFACE_STYLE_USAGE(.BOTH.,#203315); +#203315 = SURFACE_SIDE_STYLE('',(#203316)); +#203316 = SURFACE_STYLE_FILL_AREA(#203317); +#203317 = FILL_AREA_STYLE('',(#203318)); +#203318 = FILL_AREA_STYLE_COLOUR('',#198418); +#203319 = OVER_RIDING_STYLED_ITEM('overriding color',(#203320),#143893, + #198353); +#203320 = PRESENTATION_STYLE_ASSIGNMENT((#203321)); +#203321 = SURFACE_STYLE_USAGE(.BOTH.,#203322); +#203322 = SURFACE_SIDE_STYLE('',(#203323)); +#203323 = SURFACE_STYLE_FILL_AREA(#203324); +#203324 = FILL_AREA_STYLE('',(#203325)); +#203325 = FILL_AREA_STYLE_COLOUR('',#198418); +#203326 = OVER_RIDING_STYLED_ITEM('overriding color',(#203327),#143900, + #198353); +#203327 = PRESENTATION_STYLE_ASSIGNMENT((#203328)); +#203328 = SURFACE_STYLE_USAGE(.BOTH.,#203329); +#203329 = SURFACE_SIDE_STYLE('',(#203330)); +#203330 = SURFACE_STYLE_FILL_AREA(#203331); +#203331 = FILL_AREA_STYLE('',(#203332)); +#203332 = FILL_AREA_STYLE_COLOUR('',#198418); +#203333 = OVER_RIDING_STYLED_ITEM('overriding color',(#203334),#144009, + #198353); +#203334 = PRESENTATION_STYLE_ASSIGNMENT((#203335)); +#203335 = SURFACE_STYLE_USAGE(.BOTH.,#203336); +#203336 = SURFACE_SIDE_STYLE('',(#203337)); +#203337 = SURFACE_STYLE_FILL_AREA(#203338); +#203338 = FILL_AREA_STYLE('',(#203339)); +#203339 = FILL_AREA_STYLE_COLOUR('',#198418); +#203340 = OVER_RIDING_STYLED_ITEM('overriding color',(#203341),#144113, + #198353); +#203341 = PRESENTATION_STYLE_ASSIGNMENT((#203342)); +#203342 = SURFACE_STYLE_USAGE(.BOTH.,#203343); +#203343 = SURFACE_SIDE_STYLE('',(#203344)); +#203344 = SURFACE_STYLE_FILL_AREA(#203345); +#203345 = FILL_AREA_STYLE('',(#203346)); +#203346 = FILL_AREA_STYLE_COLOUR('',#198418); +#203347 = OVER_RIDING_STYLED_ITEM('overriding color',(#203348),#144192, + #198353); +#203348 = PRESENTATION_STYLE_ASSIGNMENT((#203349)); +#203349 = SURFACE_STYLE_USAGE(.BOTH.,#203350); +#203350 = SURFACE_SIDE_STYLE('',(#203351)); +#203351 = SURFACE_STYLE_FILL_AREA(#203352); +#203352 = FILL_AREA_STYLE('',(#203353)); +#203353 = FILL_AREA_STYLE_COLOUR('',#198418); +#203354 = OVER_RIDING_STYLED_ITEM('overriding color',(#203355),#144317, + #198353); +#203355 = PRESENTATION_STYLE_ASSIGNMENT((#203356)); +#203356 = SURFACE_STYLE_USAGE(.BOTH.,#203357); +#203357 = SURFACE_SIDE_STYLE('',(#203358)); +#203358 = SURFACE_STYLE_FILL_AREA(#203359); +#203359 = FILL_AREA_STYLE('',(#203360)); +#203360 = FILL_AREA_STYLE_COLOUR('',#198418); +#203361 = OVER_RIDING_STYLED_ITEM('overriding color',(#203362),#144392, + #198353); +#203362 = PRESENTATION_STYLE_ASSIGNMENT((#203363)); +#203363 = SURFACE_STYLE_USAGE(.BOTH.,#203364); +#203364 = SURFACE_SIDE_STYLE('',(#203365)); +#203365 = SURFACE_STYLE_FILL_AREA(#203366); +#203366 = FILL_AREA_STYLE('',(#203367)); +#203367 = FILL_AREA_STYLE_COLOUR('',#198418); +#203368 = OVER_RIDING_STYLED_ITEM('overriding color',(#203369),#144467, + #198353); +#203369 = PRESENTATION_STYLE_ASSIGNMENT((#203370)); +#203370 = SURFACE_STYLE_USAGE(.BOTH.,#203371); +#203371 = SURFACE_SIDE_STYLE('',(#203372)); +#203372 = SURFACE_STYLE_FILL_AREA(#203373); +#203373 = FILL_AREA_STYLE('',(#203374)); +#203374 = FILL_AREA_STYLE_COLOUR('',#198418); +#203375 = OVER_RIDING_STYLED_ITEM('overriding color',(#203376),#144541, + #198353); +#203376 = PRESENTATION_STYLE_ASSIGNMENT((#203377)); +#203377 = SURFACE_STYLE_USAGE(.BOTH.,#203378); +#203378 = SURFACE_SIDE_STYLE('',(#203379)); +#203379 = SURFACE_STYLE_FILL_AREA(#203380); +#203380 = FILL_AREA_STYLE('',(#203381)); +#203381 = FILL_AREA_STYLE_COLOUR('',#198418); +#203382 = OVER_RIDING_STYLED_ITEM('overriding color',(#203383),#144661, + #198353); +#203383 = PRESENTATION_STYLE_ASSIGNMENT((#203384)); +#203384 = SURFACE_STYLE_USAGE(.BOTH.,#203385); +#203385 = SURFACE_SIDE_STYLE('',(#203386)); +#203386 = SURFACE_STYLE_FILL_AREA(#203387); +#203387 = FILL_AREA_STYLE('',(#203388)); +#203388 = FILL_AREA_STYLE_COLOUR('',#198418); +#203389 = OVER_RIDING_STYLED_ITEM('overriding color',(#203390),#144736, + #198353); +#203390 = PRESENTATION_STYLE_ASSIGNMENT((#203391)); +#203391 = SURFACE_STYLE_USAGE(.BOTH.,#203392); +#203392 = SURFACE_SIDE_STYLE('',(#203393)); +#203393 = SURFACE_STYLE_FILL_AREA(#203394); +#203394 = FILL_AREA_STYLE('',(#203395)); +#203395 = FILL_AREA_STYLE_COLOUR('',#198418); +#203396 = OVER_RIDING_STYLED_ITEM('overriding color',(#203397),#144763, + #198353); +#203397 = PRESENTATION_STYLE_ASSIGNMENT((#203398)); +#203398 = SURFACE_STYLE_USAGE(.BOTH.,#203399); +#203399 = SURFACE_SIDE_STYLE('',(#203400)); +#203400 = SURFACE_STYLE_FILL_AREA(#203401); +#203401 = FILL_AREA_STYLE('',(#203402)); +#203402 = FILL_AREA_STYLE_COLOUR('',#198418); +#203403 = OVER_RIDING_STYLED_ITEM('overriding color',(#203404),#144818, + #198353); +#203404 = PRESENTATION_STYLE_ASSIGNMENT((#203405)); +#203405 = SURFACE_STYLE_USAGE(.BOTH.,#203406); +#203406 = SURFACE_SIDE_STYLE('',(#203407)); +#203407 = SURFACE_STYLE_FILL_AREA(#203408); +#203408 = FILL_AREA_STYLE('',(#203409)); +#203409 = FILL_AREA_STYLE_COLOUR('',#198418); +#203410 = OVER_RIDING_STYLED_ITEM('overriding color',(#203411),#144825, + #198353); +#203411 = PRESENTATION_STYLE_ASSIGNMENT((#203412)); +#203412 = SURFACE_STYLE_USAGE(.BOTH.,#203413); +#203413 = SURFACE_SIDE_STYLE('',(#203414)); +#203414 = SURFACE_STYLE_FILL_AREA(#203415); +#203415 = FILL_AREA_STYLE('',(#203416)); +#203416 = FILL_AREA_STYLE_COLOUR('',#198418); +#203417 = OVER_RIDING_STYLED_ITEM('overriding color',(#203418),#144832, + #198353); +#203418 = PRESENTATION_STYLE_ASSIGNMENT((#203419)); +#203419 = SURFACE_STYLE_USAGE(.BOTH.,#203420); +#203420 = SURFACE_SIDE_STYLE('',(#203421)); +#203421 = SURFACE_STYLE_FILL_AREA(#203422); +#203422 = FILL_AREA_STYLE('',(#203423)); +#203423 = FILL_AREA_STYLE_COLOUR('',#198418); +#203424 = OVER_RIDING_STYLED_ITEM('overriding color',(#203425),#144941, + #198353); +#203425 = PRESENTATION_STYLE_ASSIGNMENT((#203426)); +#203426 = SURFACE_STYLE_USAGE(.BOTH.,#203427); +#203427 = SURFACE_SIDE_STYLE('',(#203428)); +#203428 = SURFACE_STYLE_FILL_AREA(#203429); +#203429 = FILL_AREA_STYLE('',(#203430)); +#203430 = FILL_AREA_STYLE_COLOUR('',#198418); +#203431 = OVER_RIDING_STYLED_ITEM('overriding color',(#203432),#145045, + #198353); +#203432 = PRESENTATION_STYLE_ASSIGNMENT((#203433)); +#203433 = SURFACE_STYLE_USAGE(.BOTH.,#203434); +#203434 = SURFACE_SIDE_STYLE('',(#203435)); +#203435 = SURFACE_STYLE_FILL_AREA(#203436); +#203436 = FILL_AREA_STYLE('',(#203437)); +#203437 = FILL_AREA_STYLE_COLOUR('',#198418); +#203438 = OVER_RIDING_STYLED_ITEM('overriding color',(#203439),#145124, + #198353); +#203439 = PRESENTATION_STYLE_ASSIGNMENT((#203440)); +#203440 = SURFACE_STYLE_USAGE(.BOTH.,#203441); +#203441 = SURFACE_SIDE_STYLE('',(#203442)); +#203442 = SURFACE_STYLE_FILL_AREA(#203443); +#203443 = FILL_AREA_STYLE('',(#203444)); +#203444 = FILL_AREA_STYLE_COLOUR('',#198418); +#203445 = OVER_RIDING_STYLED_ITEM('overriding color',(#203446),#145249, + #198353); +#203446 = PRESENTATION_STYLE_ASSIGNMENT((#203447)); +#203447 = SURFACE_STYLE_USAGE(.BOTH.,#203448); +#203448 = SURFACE_SIDE_STYLE('',(#203449)); +#203449 = SURFACE_STYLE_FILL_AREA(#203450); +#203450 = FILL_AREA_STYLE('',(#203451)); +#203451 = FILL_AREA_STYLE_COLOUR('',#198418); +#203452 = OVER_RIDING_STYLED_ITEM('overriding color',(#203453),#145324, + #198353); +#203453 = PRESENTATION_STYLE_ASSIGNMENT((#203454)); +#203454 = SURFACE_STYLE_USAGE(.BOTH.,#203455); +#203455 = SURFACE_SIDE_STYLE('',(#203456)); +#203456 = SURFACE_STYLE_FILL_AREA(#203457); +#203457 = FILL_AREA_STYLE('',(#203458)); +#203458 = FILL_AREA_STYLE_COLOUR('',#198418); +#203459 = OVER_RIDING_STYLED_ITEM('overriding color',(#203460),#145399, + #198353); +#203460 = PRESENTATION_STYLE_ASSIGNMENT((#203461)); +#203461 = SURFACE_STYLE_USAGE(.BOTH.,#203462); +#203462 = SURFACE_SIDE_STYLE('',(#203463)); +#203463 = SURFACE_STYLE_FILL_AREA(#203464); +#203464 = FILL_AREA_STYLE('',(#203465)); +#203465 = FILL_AREA_STYLE_COLOUR('',#198418); +#203466 = OVER_RIDING_STYLED_ITEM('overriding color',(#203467),#145473, + #198353); +#203467 = PRESENTATION_STYLE_ASSIGNMENT((#203468)); +#203468 = SURFACE_STYLE_USAGE(.BOTH.,#203469); +#203469 = SURFACE_SIDE_STYLE('',(#203470)); +#203470 = SURFACE_STYLE_FILL_AREA(#203471); +#203471 = FILL_AREA_STYLE('',(#203472)); +#203472 = FILL_AREA_STYLE_COLOUR('',#198418); +#203473 = OVER_RIDING_STYLED_ITEM('overriding color',(#203474),#145593, + #198353); +#203474 = PRESENTATION_STYLE_ASSIGNMENT((#203475)); +#203475 = SURFACE_STYLE_USAGE(.BOTH.,#203476); +#203476 = SURFACE_SIDE_STYLE('',(#203477)); +#203477 = SURFACE_STYLE_FILL_AREA(#203478); +#203478 = FILL_AREA_STYLE('',(#203479)); +#203479 = FILL_AREA_STYLE_COLOUR('',#198418); +#203480 = OVER_RIDING_STYLED_ITEM('overriding color',(#203481),#145668, + #198353); +#203481 = PRESENTATION_STYLE_ASSIGNMENT((#203482)); +#203482 = SURFACE_STYLE_USAGE(.BOTH.,#203483); +#203483 = SURFACE_SIDE_STYLE('',(#203484)); +#203484 = SURFACE_STYLE_FILL_AREA(#203485); +#203485 = FILL_AREA_STYLE('',(#203486)); +#203486 = FILL_AREA_STYLE_COLOUR('',#198418); +#203487 = OVER_RIDING_STYLED_ITEM('overriding color',(#203488),#145695, + #198353); +#203488 = PRESENTATION_STYLE_ASSIGNMENT((#203489)); +#203489 = SURFACE_STYLE_USAGE(.BOTH.,#203490); +#203490 = SURFACE_SIDE_STYLE('',(#203491)); +#203491 = SURFACE_STYLE_FILL_AREA(#203492); +#203492 = FILL_AREA_STYLE('',(#203493)); +#203493 = FILL_AREA_STYLE_COLOUR('',#198418); +#203494 = OVER_RIDING_STYLED_ITEM('overriding color',(#203495),#145750, + #198353); +#203495 = PRESENTATION_STYLE_ASSIGNMENT((#203496)); +#203496 = SURFACE_STYLE_USAGE(.BOTH.,#203497); +#203497 = SURFACE_SIDE_STYLE('',(#203498)); +#203498 = SURFACE_STYLE_FILL_AREA(#203499); +#203499 = FILL_AREA_STYLE('',(#203500)); +#203500 = FILL_AREA_STYLE_COLOUR('',#198418); +#203501 = OVER_RIDING_STYLED_ITEM('overriding color',(#203502),#145757, + #198353); +#203502 = PRESENTATION_STYLE_ASSIGNMENT((#203503)); +#203503 = SURFACE_STYLE_USAGE(.BOTH.,#203504); +#203504 = SURFACE_SIDE_STYLE('',(#203505)); +#203505 = SURFACE_STYLE_FILL_AREA(#203506); +#203506 = FILL_AREA_STYLE('',(#203507)); +#203507 = FILL_AREA_STYLE_COLOUR('',#198418); +#203508 = OVER_RIDING_STYLED_ITEM('overriding color',(#203509),#145764, + #198353); +#203509 = PRESENTATION_STYLE_ASSIGNMENT((#203510)); +#203510 = SURFACE_STYLE_USAGE(.BOTH.,#203511); +#203511 = SURFACE_SIDE_STYLE('',(#203512)); +#203512 = SURFACE_STYLE_FILL_AREA(#203513); +#203513 = FILL_AREA_STYLE('',(#203514)); +#203514 = FILL_AREA_STYLE_COLOUR('',#198418); +#203515 = OVER_RIDING_STYLED_ITEM('overriding color',(#203516),#145873, + #198353); +#203516 = PRESENTATION_STYLE_ASSIGNMENT((#203517)); +#203517 = SURFACE_STYLE_USAGE(.BOTH.,#203518); +#203518 = SURFACE_SIDE_STYLE('',(#203519)); +#203519 = SURFACE_STYLE_FILL_AREA(#203520); +#203520 = FILL_AREA_STYLE('',(#203521)); +#203521 = FILL_AREA_STYLE_COLOUR('',#198418); +#203522 = OVER_RIDING_STYLED_ITEM('overriding color',(#203523),#145977, + #198353); +#203523 = PRESENTATION_STYLE_ASSIGNMENT((#203524)); +#203524 = SURFACE_STYLE_USAGE(.BOTH.,#203525); +#203525 = SURFACE_SIDE_STYLE('',(#203526)); +#203526 = SURFACE_STYLE_FILL_AREA(#203527); +#203527 = FILL_AREA_STYLE('',(#203528)); +#203528 = FILL_AREA_STYLE_COLOUR('',#198418); +#203529 = OVER_RIDING_STYLED_ITEM('overriding color',(#203530),#146056, + #198353); +#203530 = PRESENTATION_STYLE_ASSIGNMENT((#203531)); +#203531 = SURFACE_STYLE_USAGE(.BOTH.,#203532); +#203532 = SURFACE_SIDE_STYLE('',(#203533)); +#203533 = SURFACE_STYLE_FILL_AREA(#203534); +#203534 = FILL_AREA_STYLE('',(#203535)); +#203535 = FILL_AREA_STYLE_COLOUR('',#198418); +#203536 = OVER_RIDING_STYLED_ITEM('overriding color',(#203537),#146181, + #198353); +#203537 = PRESENTATION_STYLE_ASSIGNMENT((#203538)); +#203538 = SURFACE_STYLE_USAGE(.BOTH.,#203539); +#203539 = SURFACE_SIDE_STYLE('',(#203540)); +#203540 = SURFACE_STYLE_FILL_AREA(#203541); +#203541 = FILL_AREA_STYLE('',(#203542)); +#203542 = FILL_AREA_STYLE_COLOUR('',#198418); +#203543 = OVER_RIDING_STYLED_ITEM('overriding color',(#203544),#146256, + #198353); +#203544 = PRESENTATION_STYLE_ASSIGNMENT((#203545)); +#203545 = SURFACE_STYLE_USAGE(.BOTH.,#203546); +#203546 = SURFACE_SIDE_STYLE('',(#203547)); +#203547 = SURFACE_STYLE_FILL_AREA(#203548); +#203548 = FILL_AREA_STYLE('',(#203549)); +#203549 = FILL_AREA_STYLE_COLOUR('',#198418); +#203550 = OVER_RIDING_STYLED_ITEM('overriding color',(#203551),#146331, + #198353); +#203551 = PRESENTATION_STYLE_ASSIGNMENT((#203552)); +#203552 = SURFACE_STYLE_USAGE(.BOTH.,#203553); +#203553 = SURFACE_SIDE_STYLE('',(#203554)); +#203554 = SURFACE_STYLE_FILL_AREA(#203555); +#203555 = FILL_AREA_STYLE('',(#203556)); +#203556 = FILL_AREA_STYLE_COLOUR('',#198418); +#203557 = OVER_RIDING_STYLED_ITEM('overriding color',(#203558),#146405, + #198353); +#203558 = PRESENTATION_STYLE_ASSIGNMENT((#203559)); +#203559 = SURFACE_STYLE_USAGE(.BOTH.,#203560); +#203560 = SURFACE_SIDE_STYLE('',(#203561)); +#203561 = SURFACE_STYLE_FILL_AREA(#203562); +#203562 = FILL_AREA_STYLE('',(#203563)); +#203563 = FILL_AREA_STYLE_COLOUR('',#198418); +#203564 = OVER_RIDING_STYLED_ITEM('overriding color',(#203565),#146525, + #198353); +#203565 = PRESENTATION_STYLE_ASSIGNMENT((#203566)); +#203566 = SURFACE_STYLE_USAGE(.BOTH.,#203567); +#203567 = SURFACE_SIDE_STYLE('',(#203568)); +#203568 = SURFACE_STYLE_FILL_AREA(#203569); +#203569 = FILL_AREA_STYLE('',(#203570)); +#203570 = FILL_AREA_STYLE_COLOUR('',#198418); +#203571 = OVER_RIDING_STYLED_ITEM('overriding color',(#203572),#146600, + #198353); +#203572 = PRESENTATION_STYLE_ASSIGNMENT((#203573)); +#203573 = SURFACE_STYLE_USAGE(.BOTH.,#203574); +#203574 = SURFACE_SIDE_STYLE('',(#203575)); +#203575 = SURFACE_STYLE_FILL_AREA(#203576); +#203576 = FILL_AREA_STYLE('',(#203577)); +#203577 = FILL_AREA_STYLE_COLOUR('',#198418); +#203578 = OVER_RIDING_STYLED_ITEM('overriding color',(#203579),#146627, + #198353); +#203579 = PRESENTATION_STYLE_ASSIGNMENT((#203580)); +#203580 = SURFACE_STYLE_USAGE(.BOTH.,#203581); +#203581 = SURFACE_SIDE_STYLE('',(#203582)); +#203582 = SURFACE_STYLE_FILL_AREA(#203583); +#203583 = FILL_AREA_STYLE('',(#203584)); +#203584 = FILL_AREA_STYLE_COLOUR('',#198418); +#203585 = OVER_RIDING_STYLED_ITEM('overriding color',(#203586),#146682, + #198353); +#203586 = PRESENTATION_STYLE_ASSIGNMENT((#203587)); +#203587 = SURFACE_STYLE_USAGE(.BOTH.,#203588); +#203588 = SURFACE_SIDE_STYLE('',(#203589)); +#203589 = SURFACE_STYLE_FILL_AREA(#203590); +#203590 = FILL_AREA_STYLE('',(#203591)); +#203591 = FILL_AREA_STYLE_COLOUR('',#198418); +#203592 = OVER_RIDING_STYLED_ITEM('overriding color',(#203593),#146689, + #198353); +#203593 = PRESENTATION_STYLE_ASSIGNMENT((#203594)); +#203594 = SURFACE_STYLE_USAGE(.BOTH.,#203595); +#203595 = SURFACE_SIDE_STYLE('',(#203596)); +#203596 = SURFACE_STYLE_FILL_AREA(#203597); +#203597 = FILL_AREA_STYLE('',(#203598)); +#203598 = FILL_AREA_STYLE_COLOUR('',#198418); +#203599 = OVER_RIDING_STYLED_ITEM('overriding color',(#203600),#146696, + #198353); +#203600 = PRESENTATION_STYLE_ASSIGNMENT((#203601)); +#203601 = SURFACE_STYLE_USAGE(.BOTH.,#203602); +#203602 = SURFACE_SIDE_STYLE('',(#203603)); +#203603 = SURFACE_STYLE_FILL_AREA(#203604); +#203604 = FILL_AREA_STYLE('',(#203605)); +#203605 = FILL_AREA_STYLE_COLOUR('',#198418); +#203606 = OVER_RIDING_STYLED_ITEM('overriding color',(#203607),#146805, + #198353); +#203607 = PRESENTATION_STYLE_ASSIGNMENT((#203608)); +#203608 = SURFACE_STYLE_USAGE(.BOTH.,#203609); +#203609 = SURFACE_SIDE_STYLE('',(#203610)); +#203610 = SURFACE_STYLE_FILL_AREA(#203611); +#203611 = FILL_AREA_STYLE('',(#203612)); +#203612 = FILL_AREA_STYLE_COLOUR('',#198418); +#203613 = OVER_RIDING_STYLED_ITEM('overriding color',(#203614),#146909, + #198353); +#203614 = PRESENTATION_STYLE_ASSIGNMENT((#203615)); +#203615 = SURFACE_STYLE_USAGE(.BOTH.,#203616); +#203616 = SURFACE_SIDE_STYLE('',(#203617)); +#203617 = SURFACE_STYLE_FILL_AREA(#203618); +#203618 = FILL_AREA_STYLE('',(#203619)); +#203619 = FILL_AREA_STYLE_COLOUR('',#198418); +#203620 = OVER_RIDING_STYLED_ITEM('overriding color',(#203621),#147034, + #198353); +#203621 = PRESENTATION_STYLE_ASSIGNMENT((#203622)); +#203622 = SURFACE_STYLE_USAGE(.BOTH.,#203623); +#203623 = SURFACE_SIDE_STYLE('',(#203624)); +#203624 = SURFACE_STYLE_FILL_AREA(#203625); +#203625 = FILL_AREA_STYLE('',(#203626)); +#203626 = FILL_AREA_STYLE_COLOUR('',#198418); +#203627 = OVER_RIDING_STYLED_ITEM('overriding color',(#203628),#147113, + #198353); +#203628 = PRESENTATION_STYLE_ASSIGNMENT((#203629)); +#203629 = SURFACE_STYLE_USAGE(.BOTH.,#203630); +#203630 = SURFACE_SIDE_STYLE('',(#203631)); +#203631 = SURFACE_STYLE_FILL_AREA(#203632); +#203632 = FILL_AREA_STYLE('',(#203633)); +#203633 = FILL_AREA_STYLE_COLOUR('',#198418); +#203634 = OVER_RIDING_STYLED_ITEM('overriding color',(#203635),#147188, + #198353); +#203635 = PRESENTATION_STYLE_ASSIGNMENT((#203636)); +#203636 = SURFACE_STYLE_USAGE(.BOTH.,#203637); +#203637 = SURFACE_SIDE_STYLE('',(#203638)); +#203638 = SURFACE_STYLE_FILL_AREA(#203639); +#203639 = FILL_AREA_STYLE('',(#203640)); +#203640 = FILL_AREA_STYLE_COLOUR('',#198418); +#203641 = OVER_RIDING_STYLED_ITEM('overriding color',(#203642),#147263, + #198353); +#203642 = PRESENTATION_STYLE_ASSIGNMENT((#203643)); +#203643 = SURFACE_STYLE_USAGE(.BOTH.,#203644); +#203644 = SURFACE_SIDE_STYLE('',(#203645)); +#203645 = SURFACE_STYLE_FILL_AREA(#203646); +#203646 = FILL_AREA_STYLE('',(#203647)); +#203647 = FILL_AREA_STYLE_COLOUR('',#198418); +#203648 = OVER_RIDING_STYLED_ITEM('overriding color',(#203649),#147383, + #198353); +#203649 = PRESENTATION_STYLE_ASSIGNMENT((#203650)); +#203650 = SURFACE_STYLE_USAGE(.BOTH.,#203651); +#203651 = SURFACE_SIDE_STYLE('',(#203652)); +#203652 = SURFACE_STYLE_FILL_AREA(#203653); +#203653 = FILL_AREA_STYLE('',(#203654)); +#203654 = FILL_AREA_STYLE_COLOUR('',#198418); +#203655 = OVER_RIDING_STYLED_ITEM('overriding color',(#203656),#147457, + #198353); +#203656 = PRESENTATION_STYLE_ASSIGNMENT((#203657)); +#203657 = SURFACE_STYLE_USAGE(.BOTH.,#203658); +#203658 = SURFACE_SIDE_STYLE('',(#203659)); +#203659 = SURFACE_STYLE_FILL_AREA(#203660); +#203660 = FILL_AREA_STYLE('',(#203661)); +#203661 = FILL_AREA_STYLE_COLOUR('',#198418); +#203662 = OVER_RIDING_STYLED_ITEM('overriding color',(#203663),#147532, + #198353); +#203663 = PRESENTATION_STYLE_ASSIGNMENT((#203664)); +#203664 = SURFACE_STYLE_USAGE(.BOTH.,#203665); +#203665 = SURFACE_SIDE_STYLE('',(#203666)); +#203666 = SURFACE_STYLE_FILL_AREA(#203667); +#203667 = FILL_AREA_STYLE('',(#203668)); +#203668 = FILL_AREA_STYLE_COLOUR('',#198418); +#203669 = OVER_RIDING_STYLED_ITEM('overriding color',(#203670),#147559, + #198353); +#203670 = PRESENTATION_STYLE_ASSIGNMENT((#203671)); +#203671 = SURFACE_STYLE_USAGE(.BOTH.,#203672); +#203672 = SURFACE_SIDE_STYLE('',(#203673)); +#203673 = SURFACE_STYLE_FILL_AREA(#203674); +#203674 = FILL_AREA_STYLE('',(#203675)); +#203675 = FILL_AREA_STYLE_COLOUR('',#198418); +#203676 = OVER_RIDING_STYLED_ITEM('overriding color',(#203677),#147614, + #198353); +#203677 = PRESENTATION_STYLE_ASSIGNMENT((#203678)); +#203678 = SURFACE_STYLE_USAGE(.BOTH.,#203679); +#203679 = SURFACE_SIDE_STYLE('',(#203680)); +#203680 = SURFACE_STYLE_FILL_AREA(#203681); +#203681 = FILL_AREA_STYLE('',(#203682)); +#203682 = FILL_AREA_STYLE_COLOUR('',#198418); +#203683 = OVER_RIDING_STYLED_ITEM('overriding color',(#203684),#147621, + #198353); +#203684 = PRESENTATION_STYLE_ASSIGNMENT((#203685)); +#203685 = SURFACE_STYLE_USAGE(.BOTH.,#203686); +#203686 = SURFACE_SIDE_STYLE('',(#203687)); +#203687 = SURFACE_STYLE_FILL_AREA(#203688); +#203688 = FILL_AREA_STYLE('',(#203689)); +#203689 = FILL_AREA_STYLE_COLOUR('',#198418); +#203690 = OVER_RIDING_STYLED_ITEM('overriding color',(#203691),#147628, + #198353); +#203691 = PRESENTATION_STYLE_ASSIGNMENT((#203692)); +#203692 = SURFACE_STYLE_USAGE(.BOTH.,#203693); +#203693 = SURFACE_SIDE_STYLE('',(#203694)); +#203694 = SURFACE_STYLE_FILL_AREA(#203695); +#203695 = FILL_AREA_STYLE('',(#203696)); +#203696 = FILL_AREA_STYLE_COLOUR('',#198418); +#203697 = OVER_RIDING_STYLED_ITEM('overriding color',(#203698),#147737, + #198353); +#203698 = PRESENTATION_STYLE_ASSIGNMENT((#203699)); +#203699 = SURFACE_STYLE_USAGE(.BOTH.,#203700); +#203700 = SURFACE_SIDE_STYLE('',(#203701)); +#203701 = SURFACE_STYLE_FILL_AREA(#203702); +#203702 = FILL_AREA_STYLE('',(#203703)); +#203703 = FILL_AREA_STYLE_COLOUR('',#198418); +#203704 = OVER_RIDING_STYLED_ITEM('overriding color',(#203705),#147841, + #198353); +#203705 = PRESENTATION_STYLE_ASSIGNMENT((#203706)); +#203706 = SURFACE_STYLE_USAGE(.BOTH.,#203707); +#203707 = SURFACE_SIDE_STYLE('',(#203708)); +#203708 = SURFACE_STYLE_FILL_AREA(#203709); +#203709 = FILL_AREA_STYLE('',(#203710)); +#203710 = FILL_AREA_STYLE_COLOUR('',#198418); +#203711 = OVER_RIDING_STYLED_ITEM('overriding color',(#203712),#147966, + #198353); +#203712 = PRESENTATION_STYLE_ASSIGNMENT((#203713)); +#203713 = SURFACE_STYLE_USAGE(.BOTH.,#203714); +#203714 = SURFACE_SIDE_STYLE('',(#203715)); +#203715 = SURFACE_STYLE_FILL_AREA(#203716); +#203716 = FILL_AREA_STYLE('',(#203717)); +#203717 = FILL_AREA_STYLE_COLOUR('',#198418); +#203718 = OVER_RIDING_STYLED_ITEM('overriding color',(#203719),#148045, + #198353); +#203719 = PRESENTATION_STYLE_ASSIGNMENT((#203720)); +#203720 = SURFACE_STYLE_USAGE(.BOTH.,#203721); +#203721 = SURFACE_SIDE_STYLE('',(#203722)); +#203722 = SURFACE_STYLE_FILL_AREA(#203723); +#203723 = FILL_AREA_STYLE('',(#203724)); +#203724 = FILL_AREA_STYLE_COLOUR('',#198418); +#203725 = OVER_RIDING_STYLED_ITEM('overriding color',(#203726),#148120, + #198353); +#203726 = PRESENTATION_STYLE_ASSIGNMENT((#203727)); +#203727 = SURFACE_STYLE_USAGE(.BOTH.,#203728); +#203728 = SURFACE_SIDE_STYLE('',(#203729)); +#203729 = SURFACE_STYLE_FILL_AREA(#203730); +#203730 = FILL_AREA_STYLE('',(#203731)); +#203731 = FILL_AREA_STYLE_COLOUR('',#198418); +#203732 = OVER_RIDING_STYLED_ITEM('overriding color',(#203733),#148195, + #198353); +#203733 = PRESENTATION_STYLE_ASSIGNMENT((#203734)); +#203734 = SURFACE_STYLE_USAGE(.BOTH.,#203735); +#203735 = SURFACE_SIDE_STYLE('',(#203736)); +#203736 = SURFACE_STYLE_FILL_AREA(#203737); +#203737 = FILL_AREA_STYLE('',(#203738)); +#203738 = FILL_AREA_STYLE_COLOUR('',#198418); +#203739 = OVER_RIDING_STYLED_ITEM('overriding color',(#203740),#148269, + #198353); +#203740 = PRESENTATION_STYLE_ASSIGNMENT((#203741)); +#203741 = SURFACE_STYLE_USAGE(.BOTH.,#203742); +#203742 = SURFACE_SIDE_STYLE('',(#203743)); +#203743 = SURFACE_STYLE_FILL_AREA(#203744); +#203744 = FILL_AREA_STYLE('',(#203745)); +#203745 = FILL_AREA_STYLE_COLOUR('',#198418); +#203746 = OVER_RIDING_STYLED_ITEM('overriding color',(#203747),#148343, + #198353); +#203747 = PRESENTATION_STYLE_ASSIGNMENT((#203748)); +#203748 = SURFACE_STYLE_USAGE(.BOTH.,#203749); +#203749 = SURFACE_SIDE_STYLE('',(#203750)); +#203750 = SURFACE_STYLE_FILL_AREA(#203751); +#203751 = FILL_AREA_STYLE('',(#203752)); +#203752 = FILL_AREA_STYLE_COLOUR('',#198418); +#203753 = OVER_RIDING_STYLED_ITEM('overriding color',(#203754),#148418, + #198353); +#203754 = PRESENTATION_STYLE_ASSIGNMENT((#203755)); +#203755 = SURFACE_STYLE_USAGE(.BOTH.,#203756); +#203756 = SURFACE_SIDE_STYLE('',(#203757)); +#203757 = SURFACE_STYLE_FILL_AREA(#203758); +#203758 = FILL_AREA_STYLE('',(#203759)); +#203759 = FILL_AREA_STYLE_COLOUR('',#198418); +#203760 = OVER_RIDING_STYLED_ITEM('overriding color',(#203761),#148445, + #198353); +#203761 = PRESENTATION_STYLE_ASSIGNMENT((#203762)); +#203762 = SURFACE_STYLE_USAGE(.BOTH.,#203763); +#203763 = SURFACE_SIDE_STYLE('',(#203764)); +#203764 = SURFACE_STYLE_FILL_AREA(#203765); +#203765 = FILL_AREA_STYLE('',(#203766)); +#203766 = FILL_AREA_STYLE_COLOUR('',#198418); +#203767 = OVER_RIDING_STYLED_ITEM('overriding color',(#203768),#148500, + #198353); +#203768 = PRESENTATION_STYLE_ASSIGNMENT((#203769)); +#203769 = SURFACE_STYLE_USAGE(.BOTH.,#203770); +#203770 = SURFACE_SIDE_STYLE('',(#203771)); +#203771 = SURFACE_STYLE_FILL_AREA(#203772); +#203772 = FILL_AREA_STYLE('',(#203773)); +#203773 = FILL_AREA_STYLE_COLOUR('',#198418); +#203774 = OVER_RIDING_STYLED_ITEM('overriding color',(#203775),#148507, + #198353); +#203775 = PRESENTATION_STYLE_ASSIGNMENT((#203776)); +#203776 = SURFACE_STYLE_USAGE(.BOTH.,#203777); +#203777 = SURFACE_SIDE_STYLE('',(#203778)); +#203778 = SURFACE_STYLE_FILL_AREA(#203779); +#203779 = FILL_AREA_STYLE('',(#203780)); +#203780 = FILL_AREA_STYLE_COLOUR('',#198418); +#203781 = OVER_RIDING_STYLED_ITEM('overriding color',(#203782),#148514, + #198353); +#203782 = PRESENTATION_STYLE_ASSIGNMENT((#203783)); +#203783 = SURFACE_STYLE_USAGE(.BOTH.,#203784); +#203784 = SURFACE_SIDE_STYLE('',(#203785)); +#203785 = SURFACE_STYLE_FILL_AREA(#203786); +#203786 = FILL_AREA_STYLE('',(#203787)); +#203787 = FILL_AREA_STYLE_COLOUR('',#198418); +#203788 = OVER_RIDING_STYLED_ITEM('overriding color',(#203789),#148623, + #198353); +#203789 = PRESENTATION_STYLE_ASSIGNMENT((#203790)); +#203790 = SURFACE_STYLE_USAGE(.BOTH.,#203791); +#203791 = SURFACE_SIDE_STYLE('',(#203792)); +#203792 = SURFACE_STYLE_FILL_AREA(#203793); +#203793 = FILL_AREA_STYLE('',(#203794)); +#203794 = FILL_AREA_STYLE_COLOUR('',#198418); +#203795 = OVER_RIDING_STYLED_ITEM('overriding color',(#203796),#148727, + #198353); +#203796 = PRESENTATION_STYLE_ASSIGNMENT((#203797)); +#203797 = SURFACE_STYLE_USAGE(.BOTH.,#203798); +#203798 = SURFACE_SIDE_STYLE('',(#203799)); +#203799 = SURFACE_STYLE_FILL_AREA(#203800); +#203800 = FILL_AREA_STYLE('',(#203801)); +#203801 = FILL_AREA_STYLE_COLOUR('',#198418); +#203802 = OVER_RIDING_STYLED_ITEM('overriding color',(#203803),#148852, + #198353); +#203803 = PRESENTATION_STYLE_ASSIGNMENT((#203804)); +#203804 = SURFACE_STYLE_USAGE(.BOTH.,#203805); +#203805 = SURFACE_SIDE_STYLE('',(#203806)); +#203806 = SURFACE_STYLE_FILL_AREA(#203807); +#203807 = FILL_AREA_STYLE('',(#203808)); +#203808 = FILL_AREA_STYLE_COLOUR('',#198418); +#203809 = OVER_RIDING_STYLED_ITEM('overriding color',(#203810),#148931, + #198353); +#203810 = PRESENTATION_STYLE_ASSIGNMENT((#203811)); +#203811 = SURFACE_STYLE_USAGE(.BOTH.,#203812); +#203812 = SURFACE_SIDE_STYLE('',(#203813)); +#203813 = SURFACE_STYLE_FILL_AREA(#203814); +#203814 = FILL_AREA_STYLE('',(#203815)); +#203815 = FILL_AREA_STYLE_COLOUR('',#198418); +#203816 = OVER_RIDING_STYLED_ITEM('overriding color',(#203817),#149006, + #198353); +#203817 = PRESENTATION_STYLE_ASSIGNMENT((#203818)); +#203818 = SURFACE_STYLE_USAGE(.BOTH.,#203819); +#203819 = SURFACE_SIDE_STYLE('',(#203820)); +#203820 = SURFACE_STYLE_FILL_AREA(#203821); +#203821 = FILL_AREA_STYLE('',(#203822)); +#203822 = FILL_AREA_STYLE_COLOUR('',#198418); +#203823 = OVER_RIDING_STYLED_ITEM('overriding color',(#203824),#149081, + #198353); +#203824 = PRESENTATION_STYLE_ASSIGNMENT((#203825)); +#203825 = SURFACE_STYLE_USAGE(.BOTH.,#203826); +#203826 = SURFACE_SIDE_STYLE('',(#203827)); +#203827 = SURFACE_STYLE_FILL_AREA(#203828); +#203828 = FILL_AREA_STYLE('',(#203829)); +#203829 = FILL_AREA_STYLE_COLOUR('',#198418); +#203830 = OVER_RIDING_STYLED_ITEM('overriding color',(#203831),#149155, + #198353); +#203831 = PRESENTATION_STYLE_ASSIGNMENT((#203832)); +#203832 = SURFACE_STYLE_USAGE(.BOTH.,#203833); +#203833 = SURFACE_SIDE_STYLE('',(#203834)); +#203834 = SURFACE_STYLE_FILL_AREA(#203835); +#203835 = FILL_AREA_STYLE('',(#203836)); +#203836 = FILL_AREA_STYLE_COLOUR('',#198418); +#203837 = OVER_RIDING_STYLED_ITEM('overriding color',(#203838),#149229, + #198353); +#203838 = PRESENTATION_STYLE_ASSIGNMENT((#203839)); +#203839 = SURFACE_STYLE_USAGE(.BOTH.,#203840); +#203840 = SURFACE_SIDE_STYLE('',(#203841)); +#203841 = SURFACE_STYLE_FILL_AREA(#203842); +#203842 = FILL_AREA_STYLE('',(#203843)); +#203843 = FILL_AREA_STYLE_COLOUR('',#198418); +#203844 = OVER_RIDING_STYLED_ITEM('overriding color',(#203845),#149304, + #198353); +#203845 = PRESENTATION_STYLE_ASSIGNMENT((#203846)); +#203846 = SURFACE_STYLE_USAGE(.BOTH.,#203847); +#203847 = SURFACE_SIDE_STYLE('',(#203848)); +#203848 = SURFACE_STYLE_FILL_AREA(#203849); +#203849 = FILL_AREA_STYLE('',(#203850)); +#203850 = FILL_AREA_STYLE_COLOUR('',#198418); +#203851 = OVER_RIDING_STYLED_ITEM('overriding color',(#203852),#149331, + #198353); +#203852 = PRESENTATION_STYLE_ASSIGNMENT((#203853)); +#203853 = SURFACE_STYLE_USAGE(.BOTH.,#203854); +#203854 = SURFACE_SIDE_STYLE('',(#203855)); +#203855 = SURFACE_STYLE_FILL_AREA(#203856); +#203856 = FILL_AREA_STYLE('',(#203857)); +#203857 = FILL_AREA_STYLE_COLOUR('',#198418); +#203858 = OVER_RIDING_STYLED_ITEM('overriding color',(#203859),#149386, + #198353); +#203859 = PRESENTATION_STYLE_ASSIGNMENT((#203860)); +#203860 = SURFACE_STYLE_USAGE(.BOTH.,#203861); +#203861 = SURFACE_SIDE_STYLE('',(#203862)); +#203862 = SURFACE_STYLE_FILL_AREA(#203863); +#203863 = FILL_AREA_STYLE('',(#203864)); +#203864 = FILL_AREA_STYLE_COLOUR('',#198418); +#203865 = OVER_RIDING_STYLED_ITEM('overriding color',(#203866),#149393, + #198353); +#203866 = PRESENTATION_STYLE_ASSIGNMENT((#203867)); +#203867 = SURFACE_STYLE_USAGE(.BOTH.,#203868); +#203868 = SURFACE_SIDE_STYLE('',(#203869)); +#203869 = SURFACE_STYLE_FILL_AREA(#203870); +#203870 = FILL_AREA_STYLE('',(#203871)); +#203871 = FILL_AREA_STYLE_COLOUR('',#198418); +#203872 = OVER_RIDING_STYLED_ITEM('overriding color',(#203873),#149400, + #198353); +#203873 = PRESENTATION_STYLE_ASSIGNMENT((#203874)); +#203874 = SURFACE_STYLE_USAGE(.BOTH.,#203875); +#203875 = SURFACE_SIDE_STYLE('',(#203876)); +#203876 = SURFACE_STYLE_FILL_AREA(#203877); +#203877 = FILL_AREA_STYLE('',(#203878)); +#203878 = FILL_AREA_STYLE_COLOUR('',#198418); +#203879 = OVER_RIDING_STYLED_ITEM('overriding color',(#203880),#149509, + #198353); +#203880 = PRESENTATION_STYLE_ASSIGNMENT((#203881)); +#203881 = SURFACE_STYLE_USAGE(.BOTH.,#203882); +#203882 = SURFACE_SIDE_STYLE('',(#203883)); +#203883 = SURFACE_STYLE_FILL_AREA(#203884); +#203884 = FILL_AREA_STYLE('',(#203885)); +#203885 = FILL_AREA_STYLE_COLOUR('',#198418); +#203886 = OVER_RIDING_STYLED_ITEM('overriding color',(#203887),#149613, + #198353); +#203887 = PRESENTATION_STYLE_ASSIGNMENT((#203888)); +#203888 = SURFACE_STYLE_USAGE(.BOTH.,#203889); +#203889 = SURFACE_SIDE_STYLE('',(#203890)); +#203890 = SURFACE_STYLE_FILL_AREA(#203891); +#203891 = FILL_AREA_STYLE('',(#203892)); +#203892 = FILL_AREA_STYLE_COLOUR('',#198418); +#203893 = OVER_RIDING_STYLED_ITEM('overriding color',(#203894),#149738, + #198353); +#203894 = PRESENTATION_STYLE_ASSIGNMENT((#203895)); +#203895 = SURFACE_STYLE_USAGE(.BOTH.,#203896); +#203896 = SURFACE_SIDE_STYLE('',(#203897)); +#203897 = SURFACE_STYLE_FILL_AREA(#203898); +#203898 = FILL_AREA_STYLE('',(#203899)); +#203899 = FILL_AREA_STYLE_COLOUR('',#198418); +#203900 = OVER_RIDING_STYLED_ITEM('overriding color',(#203901),#149817, + #198353); +#203901 = PRESENTATION_STYLE_ASSIGNMENT((#203902)); +#203902 = SURFACE_STYLE_USAGE(.BOTH.,#203903); +#203903 = SURFACE_SIDE_STYLE('',(#203904)); +#203904 = SURFACE_STYLE_FILL_AREA(#203905); +#203905 = FILL_AREA_STYLE('',(#203906)); +#203906 = FILL_AREA_STYLE_COLOUR('',#198418); +#203907 = OVER_RIDING_STYLED_ITEM('overriding color',(#203908),#149892, + #198353); +#203908 = PRESENTATION_STYLE_ASSIGNMENT((#203909)); +#203909 = SURFACE_STYLE_USAGE(.BOTH.,#203910); +#203910 = SURFACE_SIDE_STYLE('',(#203911)); +#203911 = SURFACE_STYLE_FILL_AREA(#203912); +#203912 = FILL_AREA_STYLE('',(#203913)); +#203913 = FILL_AREA_STYLE_COLOUR('',#198418); +#203914 = OVER_RIDING_STYLED_ITEM('overriding color',(#203915),#149967, + #198353); +#203915 = PRESENTATION_STYLE_ASSIGNMENT((#203916)); +#203916 = SURFACE_STYLE_USAGE(.BOTH.,#203917); +#203917 = SURFACE_SIDE_STYLE('',(#203918)); +#203918 = SURFACE_STYLE_FILL_AREA(#203919); +#203919 = FILL_AREA_STYLE('',(#203920)); +#203920 = FILL_AREA_STYLE_COLOUR('',#198418); +#203921 = OVER_RIDING_STYLED_ITEM('overriding color',(#203922),#150041, + #198353); +#203922 = PRESENTATION_STYLE_ASSIGNMENT((#203923)); +#203923 = SURFACE_STYLE_USAGE(.BOTH.,#203924); +#203924 = SURFACE_SIDE_STYLE('',(#203925)); +#203925 = SURFACE_STYLE_FILL_AREA(#203926); +#203926 = FILL_AREA_STYLE('',(#203927)); +#203927 = FILL_AREA_STYLE_COLOUR('',#198418); +#203928 = OVER_RIDING_STYLED_ITEM('overriding color',(#203929),#150115, + #198353); +#203929 = PRESENTATION_STYLE_ASSIGNMENT((#203930)); +#203930 = SURFACE_STYLE_USAGE(.BOTH.,#203931); +#203931 = SURFACE_SIDE_STYLE('',(#203932)); +#203932 = SURFACE_STYLE_FILL_AREA(#203933); +#203933 = FILL_AREA_STYLE('',(#203934)); +#203934 = FILL_AREA_STYLE_COLOUR('',#198418); +#203935 = OVER_RIDING_STYLED_ITEM('overriding color',(#203936),#150190, + #198353); +#203936 = PRESENTATION_STYLE_ASSIGNMENT((#203937)); +#203937 = SURFACE_STYLE_USAGE(.BOTH.,#203938); +#203938 = SURFACE_SIDE_STYLE('',(#203939)); +#203939 = SURFACE_STYLE_FILL_AREA(#203940); +#203940 = FILL_AREA_STYLE('',(#203941)); +#203941 = FILL_AREA_STYLE_COLOUR('',#198418); +#203942 = OVER_RIDING_STYLED_ITEM('overriding color',(#203943),#150217, + #198353); +#203943 = PRESENTATION_STYLE_ASSIGNMENT((#203944)); +#203944 = SURFACE_STYLE_USAGE(.BOTH.,#203945); +#203945 = SURFACE_SIDE_STYLE('',(#203946)); +#203946 = SURFACE_STYLE_FILL_AREA(#203947); +#203947 = FILL_AREA_STYLE('',(#203948)); +#203948 = FILL_AREA_STYLE_COLOUR('',#198418); +#203949 = OVER_RIDING_STYLED_ITEM('overriding color',(#203950),#150272, + #198353); +#203950 = PRESENTATION_STYLE_ASSIGNMENT((#203951)); +#203951 = SURFACE_STYLE_USAGE(.BOTH.,#203952); +#203952 = SURFACE_SIDE_STYLE('',(#203953)); +#203953 = SURFACE_STYLE_FILL_AREA(#203954); +#203954 = FILL_AREA_STYLE('',(#203955)); +#203955 = FILL_AREA_STYLE_COLOUR('',#198418); +#203956 = OVER_RIDING_STYLED_ITEM('overriding color',(#203957),#150279, + #198353); +#203957 = PRESENTATION_STYLE_ASSIGNMENT((#203958)); +#203958 = SURFACE_STYLE_USAGE(.BOTH.,#203959); +#203959 = SURFACE_SIDE_STYLE('',(#203960)); +#203960 = SURFACE_STYLE_FILL_AREA(#203961); +#203961 = FILL_AREA_STYLE('',(#203962)); +#203962 = FILL_AREA_STYLE_COLOUR('',#198418); +#203963 = OVER_RIDING_STYLED_ITEM('overriding color',(#203964),#150286, + #198353); +#203964 = PRESENTATION_STYLE_ASSIGNMENT((#203965)); +#203965 = SURFACE_STYLE_USAGE(.BOTH.,#203966); +#203966 = SURFACE_SIDE_STYLE('',(#203967)); +#203967 = SURFACE_STYLE_FILL_AREA(#203968); +#203968 = FILL_AREA_STYLE('',(#203969)); +#203969 = FILL_AREA_STYLE_COLOUR('',#198418); +#203970 = OVER_RIDING_STYLED_ITEM('overriding color',(#203971),#150395, + #198353); +#203971 = PRESENTATION_STYLE_ASSIGNMENT((#203972)); +#203972 = SURFACE_STYLE_USAGE(.BOTH.,#203973); +#203973 = SURFACE_SIDE_STYLE('',(#203974)); +#203974 = SURFACE_STYLE_FILL_AREA(#203975); +#203975 = FILL_AREA_STYLE('',(#203976)); +#203976 = FILL_AREA_STYLE_COLOUR('',#198418); +#203977 = OVER_RIDING_STYLED_ITEM('overriding color',(#203978),#150499, + #198353); +#203978 = PRESENTATION_STYLE_ASSIGNMENT((#203979)); +#203979 = SURFACE_STYLE_USAGE(.BOTH.,#203980); +#203980 = SURFACE_SIDE_STYLE('',(#203981)); +#203981 = SURFACE_STYLE_FILL_AREA(#203982); +#203982 = FILL_AREA_STYLE('',(#203983)); +#203983 = FILL_AREA_STYLE_COLOUR('',#198418); +#203984 = OVER_RIDING_STYLED_ITEM('overriding color',(#203985),#150624, + #198353); +#203985 = PRESENTATION_STYLE_ASSIGNMENT((#203986)); +#203986 = SURFACE_STYLE_USAGE(.BOTH.,#203987); +#203987 = SURFACE_SIDE_STYLE('',(#203988)); +#203988 = SURFACE_STYLE_FILL_AREA(#203989); +#203989 = FILL_AREA_STYLE('',(#203990)); +#203990 = FILL_AREA_STYLE_COLOUR('',#198418); +#203991 = OVER_RIDING_STYLED_ITEM('overriding color',(#203992),#150703, + #198353); +#203992 = PRESENTATION_STYLE_ASSIGNMENT((#203993)); +#203993 = SURFACE_STYLE_USAGE(.BOTH.,#203994); +#203994 = SURFACE_SIDE_STYLE('',(#203995)); +#203995 = SURFACE_STYLE_FILL_AREA(#203996); +#203996 = FILL_AREA_STYLE('',(#203997)); +#203997 = FILL_AREA_STYLE_COLOUR('',#198418); +#203998 = OVER_RIDING_STYLED_ITEM('overriding color',(#203999),#150778, + #198353); +#203999 = PRESENTATION_STYLE_ASSIGNMENT((#204000)); +#204000 = SURFACE_STYLE_USAGE(.BOTH.,#204001); +#204001 = SURFACE_SIDE_STYLE('',(#204002)); +#204002 = SURFACE_STYLE_FILL_AREA(#204003); +#204003 = FILL_AREA_STYLE('',(#204004)); +#204004 = FILL_AREA_STYLE_COLOUR('',#198418); +#204005 = OVER_RIDING_STYLED_ITEM('overriding color',(#204006),#150853, + #198353); +#204006 = PRESENTATION_STYLE_ASSIGNMENT((#204007)); +#204007 = SURFACE_STYLE_USAGE(.BOTH.,#204008); +#204008 = SURFACE_SIDE_STYLE('',(#204009)); +#204009 = SURFACE_STYLE_FILL_AREA(#204010); +#204010 = FILL_AREA_STYLE('',(#204011)); +#204011 = FILL_AREA_STYLE_COLOUR('',#198418); +#204012 = OVER_RIDING_STYLED_ITEM('overriding color',(#204013),#150927, + #198353); +#204013 = PRESENTATION_STYLE_ASSIGNMENT((#204014)); +#204014 = SURFACE_STYLE_USAGE(.BOTH.,#204015); +#204015 = SURFACE_SIDE_STYLE('',(#204016)); +#204016 = SURFACE_STYLE_FILL_AREA(#204017); +#204017 = FILL_AREA_STYLE('',(#204018)); +#204018 = FILL_AREA_STYLE_COLOUR('',#198418); +#204019 = OVER_RIDING_STYLED_ITEM('overriding color',(#204020),#151001, + #198353); +#204020 = PRESENTATION_STYLE_ASSIGNMENT((#204021)); +#204021 = SURFACE_STYLE_USAGE(.BOTH.,#204022); +#204022 = SURFACE_SIDE_STYLE('',(#204023)); +#204023 = SURFACE_STYLE_FILL_AREA(#204024); +#204024 = FILL_AREA_STYLE('',(#204025)); +#204025 = FILL_AREA_STYLE_COLOUR('',#198418); +#204026 = OVER_RIDING_STYLED_ITEM('overriding color',(#204027),#151076, + #198353); +#204027 = PRESENTATION_STYLE_ASSIGNMENT((#204028)); +#204028 = SURFACE_STYLE_USAGE(.BOTH.,#204029); +#204029 = SURFACE_SIDE_STYLE('',(#204030)); +#204030 = SURFACE_STYLE_FILL_AREA(#204031); +#204031 = FILL_AREA_STYLE('',(#204032)); +#204032 = FILL_AREA_STYLE_COLOUR('',#198418); +#204033 = OVER_RIDING_STYLED_ITEM('overriding color',(#204034),#151103, + #198353); +#204034 = PRESENTATION_STYLE_ASSIGNMENT((#204035)); +#204035 = SURFACE_STYLE_USAGE(.BOTH.,#204036); +#204036 = SURFACE_SIDE_STYLE('',(#204037)); +#204037 = SURFACE_STYLE_FILL_AREA(#204038); +#204038 = FILL_AREA_STYLE('',(#204039)); +#204039 = FILL_AREA_STYLE_COLOUR('',#198418); +#204040 = OVER_RIDING_STYLED_ITEM('overriding color',(#204041),#151158, + #198353); +#204041 = PRESENTATION_STYLE_ASSIGNMENT((#204042)); +#204042 = SURFACE_STYLE_USAGE(.BOTH.,#204043); +#204043 = SURFACE_SIDE_STYLE('',(#204044)); +#204044 = SURFACE_STYLE_FILL_AREA(#204045); +#204045 = FILL_AREA_STYLE('',(#204046)); +#204046 = FILL_AREA_STYLE_COLOUR('',#198418); +#204047 = OVER_RIDING_STYLED_ITEM('overriding color',(#204048),#151165, + #198353); +#204048 = PRESENTATION_STYLE_ASSIGNMENT((#204049)); +#204049 = SURFACE_STYLE_USAGE(.BOTH.,#204050); +#204050 = SURFACE_SIDE_STYLE('',(#204051)); +#204051 = SURFACE_STYLE_FILL_AREA(#204052); +#204052 = FILL_AREA_STYLE('',(#204053)); +#204053 = FILL_AREA_STYLE_COLOUR('',#198418); +#204054 = OVER_RIDING_STYLED_ITEM('overriding color',(#204055),#151172, + #198353); +#204055 = PRESENTATION_STYLE_ASSIGNMENT((#204056)); +#204056 = SURFACE_STYLE_USAGE(.BOTH.,#204057); +#204057 = SURFACE_SIDE_STYLE('',(#204058)); +#204058 = SURFACE_STYLE_FILL_AREA(#204059); +#204059 = FILL_AREA_STYLE('',(#204060)); +#204060 = FILL_AREA_STYLE_COLOUR('',#198418); +#204061 = OVER_RIDING_STYLED_ITEM('overriding color',(#204062),#151281, + #198353); +#204062 = PRESENTATION_STYLE_ASSIGNMENT((#204063)); +#204063 = SURFACE_STYLE_USAGE(.BOTH.,#204064); +#204064 = SURFACE_SIDE_STYLE('',(#204065)); +#204065 = SURFACE_STYLE_FILL_AREA(#204066); +#204066 = FILL_AREA_STYLE('',(#204067)); +#204067 = FILL_AREA_STYLE_COLOUR('',#198418); +#204068 = OVER_RIDING_STYLED_ITEM('overriding color',(#204069),#151385, + #198353); +#204069 = PRESENTATION_STYLE_ASSIGNMENT((#204070)); +#204070 = SURFACE_STYLE_USAGE(.BOTH.,#204071); +#204071 = SURFACE_SIDE_STYLE('',(#204072)); +#204072 = SURFACE_STYLE_FILL_AREA(#204073); +#204073 = FILL_AREA_STYLE('',(#204074)); +#204074 = FILL_AREA_STYLE_COLOUR('',#198418); +#204075 = OVER_RIDING_STYLED_ITEM('overriding color',(#204076),#151510, + #198353); +#204076 = PRESENTATION_STYLE_ASSIGNMENT((#204077)); +#204077 = SURFACE_STYLE_USAGE(.BOTH.,#204078); +#204078 = SURFACE_SIDE_STYLE('',(#204079)); +#204079 = SURFACE_STYLE_FILL_AREA(#204080); +#204080 = FILL_AREA_STYLE('',(#204081)); +#204081 = FILL_AREA_STYLE_COLOUR('',#198418); +#204082 = OVER_RIDING_STYLED_ITEM('overriding color',(#204083),#151635, + #198353); +#204083 = PRESENTATION_STYLE_ASSIGNMENT((#204084)); +#204084 = SURFACE_STYLE_USAGE(.BOTH.,#204085); +#204085 = SURFACE_SIDE_STYLE('',(#204086)); +#204086 = SURFACE_STYLE_FILL_AREA(#204087); +#204087 = FILL_AREA_STYLE('',(#204088)); +#204088 = FILL_AREA_STYLE_COLOUR('',#198418); +#204089 = OVER_RIDING_STYLED_ITEM('overriding color',(#204090),#151710, + #198353); +#204090 = PRESENTATION_STYLE_ASSIGNMENT((#204091)); +#204091 = SURFACE_STYLE_USAGE(.BOTH.,#204092); +#204092 = SURFACE_SIDE_STYLE('',(#204093)); +#204093 = SURFACE_STYLE_FILL_AREA(#204094); +#204094 = FILL_AREA_STYLE('',(#204095)); +#204095 = FILL_AREA_STYLE_COLOUR('',#198418); +#204096 = OVER_RIDING_STYLED_ITEM('overriding color',(#204097),#151785, + #198353); +#204097 = PRESENTATION_STYLE_ASSIGNMENT((#204098)); +#204098 = SURFACE_STYLE_USAGE(.BOTH.,#204099); +#204099 = SURFACE_SIDE_STYLE('',(#204100)); +#204100 = SURFACE_STYLE_FILL_AREA(#204101); +#204101 = FILL_AREA_STYLE('',(#204102)); +#204102 = FILL_AREA_STYLE_COLOUR('',#198418); +#204103 = OVER_RIDING_STYLED_ITEM('overriding color',(#204104),#151905, + #198353); +#204104 = PRESENTATION_STYLE_ASSIGNMENT((#204105)); +#204105 = SURFACE_STYLE_USAGE(.BOTH.,#204106); +#204106 = SURFACE_SIDE_STYLE('',(#204107)); +#204107 = SURFACE_STYLE_FILL_AREA(#204108); +#204108 = FILL_AREA_STYLE('',(#204109)); +#204109 = FILL_AREA_STYLE_COLOUR('',#198418); +#204110 = OVER_RIDING_STYLED_ITEM('overriding color',(#204111),#152025, + #198353); +#204111 = PRESENTATION_STYLE_ASSIGNMENT((#204112)); +#204112 = SURFACE_STYLE_USAGE(.BOTH.,#204113); +#204113 = SURFACE_SIDE_STYLE('',(#204114)); +#204114 = SURFACE_STYLE_FILL_AREA(#204115); +#204115 = FILL_AREA_STYLE('',(#204116)); +#204116 = FILL_AREA_STYLE_COLOUR('',#198418); +#204117 = OVER_RIDING_STYLED_ITEM('overriding color',(#204118),#152100, + #198353); +#204118 = PRESENTATION_STYLE_ASSIGNMENT((#204119)); +#204119 = SURFACE_STYLE_USAGE(.BOTH.,#204120); +#204120 = SURFACE_SIDE_STYLE('',(#204121)); +#204121 = SURFACE_STYLE_FILL_AREA(#204122); +#204122 = FILL_AREA_STYLE('',(#204123)); +#204123 = FILL_AREA_STYLE_COLOUR('',#198418); +#204124 = OVER_RIDING_STYLED_ITEM('overriding color',(#204125),#152127, + #198353); +#204125 = PRESENTATION_STYLE_ASSIGNMENT((#204126)); +#204126 = SURFACE_STYLE_USAGE(.BOTH.,#204127); +#204127 = SURFACE_SIDE_STYLE('',(#204128)); +#204128 = SURFACE_STYLE_FILL_AREA(#204129); +#204129 = FILL_AREA_STYLE('',(#204130)); +#204130 = FILL_AREA_STYLE_COLOUR('',#198418); +#204131 = OVER_RIDING_STYLED_ITEM('overriding color',(#204132),#152182, + #198353); +#204132 = PRESENTATION_STYLE_ASSIGNMENT((#204133)); +#204133 = SURFACE_STYLE_USAGE(.BOTH.,#204134); +#204134 = SURFACE_SIDE_STYLE('',(#204135)); +#204135 = SURFACE_STYLE_FILL_AREA(#204136); +#204136 = FILL_AREA_STYLE('',(#204137)); +#204137 = FILL_AREA_STYLE_COLOUR('',#198418); +#204138 = OVER_RIDING_STYLED_ITEM('overriding color',(#204139),#152189, + #198353); +#204139 = PRESENTATION_STYLE_ASSIGNMENT((#204140)); +#204140 = SURFACE_STYLE_USAGE(.BOTH.,#204141); +#204141 = SURFACE_SIDE_STYLE('',(#204142)); +#204142 = SURFACE_STYLE_FILL_AREA(#204143); +#204143 = FILL_AREA_STYLE('',(#204144)); +#204144 = FILL_AREA_STYLE_COLOUR('',#198418); +#204145 = OVER_RIDING_STYLED_ITEM('overriding color',(#204146),#152196, + #198353); +#204146 = PRESENTATION_STYLE_ASSIGNMENT((#204147)); +#204147 = SURFACE_STYLE_USAGE(.BOTH.,#204148); +#204148 = SURFACE_SIDE_STYLE('',(#204149)); +#204149 = SURFACE_STYLE_FILL_AREA(#204150); +#204150 = FILL_AREA_STYLE('',(#204151)); +#204151 = FILL_AREA_STYLE_COLOUR('',#198418); +#204152 = OVER_RIDING_STYLED_ITEM('overriding color',(#204153),#152305, + #198353); +#204153 = PRESENTATION_STYLE_ASSIGNMENT((#204154)); +#204154 = SURFACE_STYLE_USAGE(.BOTH.,#204155); +#204155 = SURFACE_SIDE_STYLE('',(#204156)); +#204156 = SURFACE_STYLE_FILL_AREA(#204157); +#204157 = FILL_AREA_STYLE('',(#204158)); +#204158 = FILL_AREA_STYLE_COLOUR('',#198418); +#204159 = OVER_RIDING_STYLED_ITEM('overriding color',(#204160),#152409, + #198353); +#204160 = PRESENTATION_STYLE_ASSIGNMENT((#204161)); +#204161 = SURFACE_STYLE_USAGE(.BOTH.,#204162); +#204162 = SURFACE_SIDE_STYLE('',(#204163)); +#204163 = SURFACE_STYLE_FILL_AREA(#204164); +#204164 = FILL_AREA_STYLE('',(#204165)); +#204165 = FILL_AREA_STYLE_COLOUR('',#198418); +#204166 = OVER_RIDING_STYLED_ITEM('overriding color',(#204167),#152534, + #198353); +#204167 = PRESENTATION_STYLE_ASSIGNMENT((#204168)); +#204168 = SURFACE_STYLE_USAGE(.BOTH.,#204169); +#204169 = SURFACE_SIDE_STYLE('',(#204170)); +#204170 = SURFACE_STYLE_FILL_AREA(#204171); +#204171 = FILL_AREA_STYLE('',(#204172)); +#204172 = FILL_AREA_STYLE_COLOUR('',#198418); +#204173 = OVER_RIDING_STYLED_ITEM('overriding color',(#204174),#152659, + #198353); +#204174 = PRESENTATION_STYLE_ASSIGNMENT((#204175)); +#204175 = SURFACE_STYLE_USAGE(.BOTH.,#204176); +#204176 = SURFACE_SIDE_STYLE('',(#204177)); +#204177 = SURFACE_STYLE_FILL_AREA(#204178); +#204178 = FILL_AREA_STYLE('',(#204179)); +#204179 = FILL_AREA_STYLE_COLOUR('',#198418); +#204180 = OVER_RIDING_STYLED_ITEM('overriding color',(#204181),#152734, + #198353); +#204181 = PRESENTATION_STYLE_ASSIGNMENT((#204182)); +#204182 = SURFACE_STYLE_USAGE(.BOTH.,#204183); +#204183 = SURFACE_SIDE_STYLE('',(#204184)); +#204184 = SURFACE_STYLE_FILL_AREA(#204185); +#204185 = FILL_AREA_STYLE('',(#204186)); +#204186 = FILL_AREA_STYLE_COLOUR('',#198418); +#204187 = OVER_RIDING_STYLED_ITEM('overriding color',(#204188),#152809, + #198353); +#204188 = PRESENTATION_STYLE_ASSIGNMENT((#204189)); +#204189 = SURFACE_STYLE_USAGE(.BOTH.,#204190); +#204190 = SURFACE_SIDE_STYLE('',(#204191)); +#204191 = SURFACE_STYLE_FILL_AREA(#204192); +#204192 = FILL_AREA_STYLE('',(#204193)); +#204193 = FILL_AREA_STYLE_COLOUR('',#198418); +#204194 = OVER_RIDING_STYLED_ITEM('overriding color',(#204195),#152929, + #198353); +#204195 = PRESENTATION_STYLE_ASSIGNMENT((#204196)); +#204196 = SURFACE_STYLE_USAGE(.BOTH.,#204197); +#204197 = SURFACE_SIDE_STYLE('',(#204198)); +#204198 = SURFACE_STYLE_FILL_AREA(#204199); +#204199 = FILL_AREA_STYLE('',(#204200)); +#204200 = FILL_AREA_STYLE_COLOUR('',#198418); +#204201 = OVER_RIDING_STYLED_ITEM('overriding color',(#204202),#153049, + #198353); +#204202 = PRESENTATION_STYLE_ASSIGNMENT((#204203)); +#204203 = SURFACE_STYLE_USAGE(.BOTH.,#204204); +#204204 = SURFACE_SIDE_STYLE('',(#204205)); +#204205 = SURFACE_STYLE_FILL_AREA(#204206); +#204206 = FILL_AREA_STYLE('',(#204207)); +#204207 = FILL_AREA_STYLE_COLOUR('',#198418); +#204208 = OVER_RIDING_STYLED_ITEM('overriding color',(#204209),#153124, + #198353); +#204209 = PRESENTATION_STYLE_ASSIGNMENT((#204210)); +#204210 = SURFACE_STYLE_USAGE(.BOTH.,#204211); +#204211 = SURFACE_SIDE_STYLE('',(#204212)); +#204212 = SURFACE_STYLE_FILL_AREA(#204213); +#204213 = FILL_AREA_STYLE('',(#204214)); +#204214 = FILL_AREA_STYLE_COLOUR('',#198418); +#204215 = OVER_RIDING_STYLED_ITEM('overriding color',(#204216),#153151, + #198353); +#204216 = PRESENTATION_STYLE_ASSIGNMENT((#204217)); +#204217 = SURFACE_STYLE_USAGE(.BOTH.,#204218); +#204218 = SURFACE_SIDE_STYLE('',(#204219)); +#204219 = SURFACE_STYLE_FILL_AREA(#204220); +#204220 = FILL_AREA_STYLE('',(#204221)); +#204221 = FILL_AREA_STYLE_COLOUR('',#198418); +#204222 = OVER_RIDING_STYLED_ITEM('overriding color',(#204223),#153206, + #198353); +#204223 = PRESENTATION_STYLE_ASSIGNMENT((#204224)); +#204224 = SURFACE_STYLE_USAGE(.BOTH.,#204225); +#204225 = SURFACE_SIDE_STYLE('',(#204226)); +#204226 = SURFACE_STYLE_FILL_AREA(#204227); +#204227 = FILL_AREA_STYLE('',(#204228)); +#204228 = FILL_AREA_STYLE_COLOUR('',#198418); +#204229 = OVER_RIDING_STYLED_ITEM('overriding color',(#204230),#153213, + #198353); +#204230 = PRESENTATION_STYLE_ASSIGNMENT((#204231)); +#204231 = SURFACE_STYLE_USAGE(.BOTH.,#204232); +#204232 = SURFACE_SIDE_STYLE('',(#204233)); +#204233 = SURFACE_STYLE_FILL_AREA(#204234); +#204234 = FILL_AREA_STYLE('',(#204235)); +#204235 = FILL_AREA_STYLE_COLOUR('',#198418); +#204236 = OVER_RIDING_STYLED_ITEM('overriding color',(#204237),#153220, + #198353); +#204237 = PRESENTATION_STYLE_ASSIGNMENT((#204238)); +#204238 = SURFACE_STYLE_USAGE(.BOTH.,#204239); +#204239 = SURFACE_SIDE_STYLE('',(#204240)); +#204240 = SURFACE_STYLE_FILL_AREA(#204241); +#204241 = FILL_AREA_STYLE('',(#204242)); +#204242 = FILL_AREA_STYLE_COLOUR('',#198368); +#204243 = OVER_RIDING_STYLED_ITEM('overriding color',(#204244),#153252, + #198353); +#204244 = PRESENTATION_STYLE_ASSIGNMENT((#204245)); +#204245 = SURFACE_STYLE_USAGE(.BOTH.,#204246); +#204246 = SURFACE_SIDE_STYLE('',(#204247)); +#204247 = SURFACE_STYLE_FILL_AREA(#204248); +#204248 = FILL_AREA_STYLE('',(#204249)); +#204249 = FILL_AREA_STYLE_COLOUR('',#198368); +#204250 = OVER_RIDING_STYLED_ITEM('overriding color',(#204251),#153298, + #198353); +#204251 = PRESENTATION_STYLE_ASSIGNMENT((#204252)); +#204252 = SURFACE_STYLE_USAGE(.BOTH.,#204253); +#204253 = SURFACE_SIDE_STYLE('',(#204254)); +#204254 = SURFACE_STYLE_FILL_AREA(#204255); +#204255 = FILL_AREA_STYLE('',(#204256)); +#204256 = FILL_AREA_STYLE_COLOUR('',#198368); +#204257 = OVER_RIDING_STYLED_ITEM('overriding color',(#204258),#153330, + #198353); +#204258 = PRESENTATION_STYLE_ASSIGNMENT((#204259)); +#204259 = SURFACE_STYLE_USAGE(.BOTH.,#204260); +#204260 = SURFACE_SIDE_STYLE('',(#204261)); +#204261 = SURFACE_STYLE_FILL_AREA(#204262); +#204262 = FILL_AREA_STYLE('',(#204263)); +#204263 = FILL_AREA_STYLE_COLOUR('',#198368); +#204264 = OVER_RIDING_STYLED_ITEM('overriding color',(#204265),#153357, + #198353); +#204265 = PRESENTATION_STYLE_ASSIGNMENT((#204266)); +#204266 = SURFACE_STYLE_USAGE(.BOTH.,#204267); +#204267 = SURFACE_SIDE_STYLE('',(#204268)); +#204268 = SURFACE_STYLE_FILL_AREA(#204269); +#204269 = FILL_AREA_STYLE('',(#204270)); +#204270 = FILL_AREA_STYLE_COLOUR('',#198368); +#204271 = OVER_RIDING_STYLED_ITEM('overriding color',(#204272),#153389, + #198353); +#204272 = PRESENTATION_STYLE_ASSIGNMENT((#204273)); +#204273 = SURFACE_STYLE_USAGE(.BOTH.,#204274); +#204274 = SURFACE_SIDE_STYLE('',(#204275)); +#204275 = SURFACE_STYLE_FILL_AREA(#204276); +#204276 = FILL_AREA_STYLE('',(#204277)); +#204277 = FILL_AREA_STYLE_COLOUR('',#198368); +#204278 = OVER_RIDING_STYLED_ITEM('overriding color',(#204279),#153416, + #198353); +#204279 = PRESENTATION_STYLE_ASSIGNMENT((#204280)); +#204280 = SURFACE_STYLE_USAGE(.BOTH.,#204281); +#204281 = SURFACE_SIDE_STYLE('',(#204282)); +#204282 = SURFACE_STYLE_FILL_AREA(#204283); +#204283 = FILL_AREA_STYLE('',(#204284)); +#204284 = FILL_AREA_STYLE_COLOUR('',#198368); +#204285 = OVER_RIDING_STYLED_ITEM('overriding color',(#204286),#153442, + #198353); +#204286 = PRESENTATION_STYLE_ASSIGNMENT((#204287)); +#204287 = SURFACE_STYLE_USAGE(.BOTH.,#204288); +#204288 = SURFACE_SIDE_STYLE('',(#204289)); +#204289 = SURFACE_STYLE_FILL_AREA(#204290); +#204290 = FILL_AREA_STYLE('',(#204291)); +#204291 = FILL_AREA_STYLE_COLOUR('',#198368); +#204292 = OVER_RIDING_STYLED_ITEM('overriding color',(#204293),#153468, + #198353); +#204293 = PRESENTATION_STYLE_ASSIGNMENT((#204294)); +#204294 = SURFACE_STYLE_USAGE(.BOTH.,#204295); +#204295 = SURFACE_SIDE_STYLE('',(#204296)); +#204296 = SURFACE_STYLE_FILL_AREA(#204297); +#204297 = FILL_AREA_STYLE('',(#204298)); +#204298 = FILL_AREA_STYLE_COLOUR('',#198368); +#204299 = OVER_RIDING_STYLED_ITEM('overriding color',(#204300),#153500, + #198353); +#204300 = PRESENTATION_STYLE_ASSIGNMENT((#204301)); +#204301 = SURFACE_STYLE_USAGE(.BOTH.,#204302); +#204302 = SURFACE_SIDE_STYLE('',(#204303)); +#204303 = SURFACE_STYLE_FILL_AREA(#204304); +#204304 = FILL_AREA_STYLE('',(#204305)); +#204305 = FILL_AREA_STYLE_COLOUR('',#198368); +#204306 = OVER_RIDING_STYLED_ITEM('overriding color',(#204307),#153527, + #198353); +#204307 = PRESENTATION_STYLE_ASSIGNMENT((#204308)); +#204308 = SURFACE_STYLE_USAGE(.BOTH.,#204309); +#204309 = SURFACE_SIDE_STYLE('',(#204310)); +#204310 = SURFACE_STYLE_FILL_AREA(#204311); +#204311 = FILL_AREA_STYLE('',(#204312)); +#204312 = FILL_AREA_STYLE_COLOUR('',#198368); +#204313 = OVER_RIDING_STYLED_ITEM('overriding color',(#204314),#153553, + #198353); +#204314 = PRESENTATION_STYLE_ASSIGNMENT((#204315)); +#204315 = SURFACE_STYLE_USAGE(.BOTH.,#204316); +#204316 = SURFACE_SIDE_STYLE('',(#204317)); +#204317 = SURFACE_STYLE_FILL_AREA(#204318); +#204318 = FILL_AREA_STYLE('',(#204319)); +#204319 = FILL_AREA_STYLE_COLOUR('',#198368); +#204320 = OVER_RIDING_STYLED_ITEM('overriding color',(#204321),#153560, + #198353); +#204321 = PRESENTATION_STYLE_ASSIGNMENT((#204322)); +#204322 = SURFACE_STYLE_USAGE(.BOTH.,#204323); +#204323 = SURFACE_SIDE_STYLE('',(#204324)); +#204324 = SURFACE_STYLE_FILL_AREA(#204325); +#204325 = FILL_AREA_STYLE('',(#204326)); +#204326 = FILL_AREA_STYLE_COLOUR('',#198368); +#204327 = OVER_RIDING_STYLED_ITEM('overriding color',(#204328),#153587, + #198353); +#204328 = PRESENTATION_STYLE_ASSIGNMENT((#204329)); +#204329 = SURFACE_STYLE_USAGE(.BOTH.,#204330); +#204330 = SURFACE_SIDE_STYLE('',(#204331)); +#204331 = SURFACE_STYLE_FILL_AREA(#204332); +#204332 = FILL_AREA_STYLE('',(#204333)); +#204333 = FILL_AREA_STYLE_COLOUR('',#198368); +#204334 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #204335,#204342,#204349,#204356,#204363,#204370,#204377,#204384, + #204391,#204398,#204405,#204412,#204419,#204426),#77396); +#204335 = STYLED_ITEM('color',(#204336),#73547); +#204336 = PRESENTATION_STYLE_ASSIGNMENT((#204337)); +#204337 = SURFACE_STYLE_USAGE(.BOTH.,#204338); +#204338 = SURFACE_SIDE_STYLE('',(#204339)); +#204339 = SURFACE_STYLE_FILL_AREA(#204340); +#204340 = FILL_AREA_STYLE('',(#204341)); +#204341 = FILL_AREA_STYLE_COLOUR('',#197425); +#204342 = OVER_RIDING_STYLED_ITEM('overriding color',(#204343),#74384, + #204335); +#204343 = PRESENTATION_STYLE_ASSIGNMENT((#204344)); +#204344 = SURFACE_STYLE_USAGE(.BOTH.,#204345); +#204345 = SURFACE_SIDE_STYLE('',(#204346)); +#204346 = SURFACE_STYLE_FILL_AREA(#204347); +#204347 = FILL_AREA_STYLE('',(#204348)); +#204348 = FILL_AREA_STYLE_COLOUR('',#197440); +#204349 = OVER_RIDING_STYLED_ITEM('overriding color',(#204350),#75361, + #204335); +#204350 = PRESENTATION_STYLE_ASSIGNMENT((#204351)); +#204351 = SURFACE_STYLE_USAGE(.BOTH.,#204352); +#204352 = SURFACE_SIDE_STYLE('',(#204353)); +#204353 = SURFACE_STYLE_FILL_AREA(#204354); +#204354 = FILL_AREA_STYLE('',(#204355)); +#204355 = FILL_AREA_STYLE_COLOUR('',#197440); +#204356 = OVER_RIDING_STYLED_ITEM('overriding color',(#204357),#75539, + #204335); +#204357 = PRESENTATION_STYLE_ASSIGNMENT((#204358)); +#204358 = SURFACE_STYLE_USAGE(.BOTH.,#204359); +#204359 = SURFACE_SIDE_STYLE('',(#204360)); +#204360 = SURFACE_STYLE_FILL_AREA(#204361); +#204361 = FILL_AREA_STYLE('',(#204362)); +#204362 = FILL_AREA_STYLE_COLOUR('',#197440); +#204363 = OVER_RIDING_STYLED_ITEM('overriding color',(#204364),#75615, + #204335); +#204364 = PRESENTATION_STYLE_ASSIGNMENT((#204365)); +#204365 = SURFACE_STYLE_USAGE(.BOTH.,#204366); +#204366 = SURFACE_SIDE_STYLE('',(#204367)); +#204367 = SURFACE_STYLE_FILL_AREA(#204368); +#204368 = FILL_AREA_STYLE('',(#204369)); +#204369 = FILL_AREA_STYLE_COLOUR('',#197440); +#204370 = OVER_RIDING_STYLED_ITEM('overriding color',(#204371),#75691, + #204335); +#204371 = PRESENTATION_STYLE_ASSIGNMENT((#204372)); +#204372 = SURFACE_STYLE_USAGE(.BOTH.,#204373); +#204373 = SURFACE_SIDE_STYLE('',(#204374)); +#204374 = SURFACE_STYLE_FILL_AREA(#204375); +#204375 = FILL_AREA_STYLE('',(#204376)); +#204376 = FILL_AREA_STYLE_COLOUR('',#197440); +#204377 = OVER_RIDING_STYLED_ITEM('overriding color',(#204378),#75762, + #204335); +#204378 = PRESENTATION_STYLE_ASSIGNMENT((#204379)); +#204379 = SURFACE_STYLE_USAGE(.BOTH.,#204380); +#204380 = SURFACE_SIDE_STYLE('',(#204381)); +#204381 = SURFACE_STYLE_FILL_AREA(#204382); +#204382 = FILL_AREA_STYLE('',(#204383)); +#204383 = FILL_AREA_STYLE_COLOUR('',#197440); +#204384 = OVER_RIDING_STYLED_ITEM('overriding color',(#204385),#76809, + #204335); +#204385 = PRESENTATION_STYLE_ASSIGNMENT((#204386)); +#204386 = SURFACE_STYLE_USAGE(.BOTH.,#204387); +#204387 = SURFACE_SIDE_STYLE('',(#204388)); +#204388 = SURFACE_STYLE_FILL_AREA(#204389); +#204389 = FILL_AREA_STYLE('',(#204390)); +#204390 = FILL_AREA_STYLE_COLOUR('',#197440); +#204391 = OVER_RIDING_STYLED_ITEM('overriding color',(#204392),#76948, + #204335); +#204392 = PRESENTATION_STYLE_ASSIGNMENT((#204393)); +#204393 = SURFACE_STYLE_USAGE(.BOTH.,#204394); +#204394 = SURFACE_SIDE_STYLE('',(#204395)); +#204395 = SURFACE_STYLE_FILL_AREA(#204396); +#204396 = FILL_AREA_STYLE('',(#204397)); +#204397 = FILL_AREA_STYLE_COLOUR('',#197440); +#204398 = OVER_RIDING_STYLED_ITEM('overriding color',(#204399),#77030, + #204335); +#204399 = PRESENTATION_STYLE_ASSIGNMENT((#204400)); +#204400 = SURFACE_STYLE_USAGE(.BOTH.,#204401); +#204401 = SURFACE_SIDE_STYLE('',(#204402)); +#204402 = SURFACE_STYLE_FILL_AREA(#204403); +#204403 = FILL_AREA_STYLE('',(#204404)); +#204404 = FILL_AREA_STYLE_COLOUR('',#197440); +#204405 = OVER_RIDING_STYLED_ITEM('overriding color',(#204406),#77092, + #204335); +#204406 = PRESENTATION_STYLE_ASSIGNMENT((#204407)); +#204407 = SURFACE_STYLE_USAGE(.BOTH.,#204408); +#204408 = SURFACE_SIDE_STYLE('',(#204409)); +#204409 = SURFACE_STYLE_FILL_AREA(#204410); +#204410 = FILL_AREA_STYLE('',(#204411)); +#204411 = FILL_AREA_STYLE_COLOUR('',#197440); +#204412 = OVER_RIDING_STYLED_ITEM('overriding color',(#204413),#77189, + #204335); +#204413 = PRESENTATION_STYLE_ASSIGNMENT((#204414)); +#204414 = SURFACE_STYLE_USAGE(.BOTH.,#204415); +#204415 = SURFACE_SIDE_STYLE('',(#204416)); +#204416 = SURFACE_STYLE_FILL_AREA(#204417); +#204417 = FILL_AREA_STYLE('',(#204418)); +#204418 = FILL_AREA_STYLE_COLOUR('',#197440); +#204419 = OVER_RIDING_STYLED_ITEM('overriding color',(#204420),#77231, + #204335); +#204420 = PRESENTATION_STYLE_ASSIGNMENT((#204421)); +#204421 = SURFACE_STYLE_USAGE(.BOTH.,#204422); +#204422 = SURFACE_SIDE_STYLE('',(#204423)); +#204423 = SURFACE_STYLE_FILL_AREA(#204424); +#204424 = FILL_AREA_STYLE('',(#204425)); +#204425 = FILL_AREA_STYLE_COLOUR('',#197440); +#204426 = OVER_RIDING_STYLED_ITEM('overriding color',(#204427),#77293, + #204335); +#204427 = PRESENTATION_STYLE_ASSIGNMENT((#204428)); +#204428 = SURFACE_STYLE_USAGE(.BOTH.,#204429); +#204429 = SURFACE_SIDE_STYLE('',(#204430)); +#204430 = SURFACE_STYLE_FILL_AREA(#204431); +#204431 = FILL_AREA_STYLE('',(#204432)); +#204432 = FILL_AREA_STYLE_COLOUR('',#197440); +#204433 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #204434),#7417); +#204434 = STYLED_ITEM('color',(#204435),#7087); +#204435 = PRESENTATION_STYLE_ASSIGNMENT((#204436,#204442)); +#204436 = SURFACE_STYLE_USAGE(.BOTH.,#204437); +#204437 = SURFACE_SIDE_STYLE('',(#204438)); +#204438 = SURFACE_STYLE_FILL_AREA(#204439); +#204439 = FILL_AREA_STYLE('',(#204440)); +#204440 = FILL_AREA_STYLE_COLOUR('',#204441); +#204441 = COLOUR_RGB('',0.219607844949,0.219607844949,0.219607844949); +#204442 = CURVE_STYLE('',#204443,POSITIVE_LENGTH_MEASURE(0.1),#204441); +#204443 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#204444 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #204445,#204452,#204460,#204467,#204474,#204481,#204488,#204495, + #204502,#204509,#204516,#204523,#204530,#204537,#204544,#204551, + #204558,#204565,#204572,#204579,#204586,#204593,#204600,#204607, + #204614,#204621,#204628,#204635,#204642,#204649,#204656,#204663, + #204670,#204677,#204684,#204691,#204698,#204705,#204712,#204719, + #204726,#204733,#204740,#204747,#204754,#204761,#204768,#204775, + #204782,#204789,#204796,#204803,#204810,#204817,#204824),#13408); +#204445 = STYLED_ITEM('color',(#204446),#9917); +#204446 = PRESENTATION_STYLE_ASSIGNMENT((#204447)); +#204447 = SURFACE_STYLE_USAGE(.BOTH.,#204448); +#204448 = SURFACE_SIDE_STYLE('',(#204449)); +#204449 = SURFACE_STYLE_FILL_AREA(#204450); +#204450 = FILL_AREA_STYLE('',(#204451)); +#204451 = FILL_AREA_STYLE_COLOUR('',#197417); +#204452 = OVER_RIDING_STYLED_ITEM('overriding color',(#204453),#9919, + #204445); +#204453 = PRESENTATION_STYLE_ASSIGNMENT((#204454)); +#204454 = SURFACE_STYLE_USAGE(.BOTH.,#204455); +#204455 = SURFACE_SIDE_STYLE('',(#204456)); +#204456 = SURFACE_STYLE_FILL_AREA(#204457); +#204457 = FILL_AREA_STYLE('',(#204458)); +#204458 = FILL_AREA_STYLE_COLOUR('',#204459); +#204459 = COLOUR_RGB('',1.,1.,0.752941191196); +#204460 = OVER_RIDING_STYLED_ITEM('overriding color',(#204461),#10151, + #204445); +#204461 = PRESENTATION_STYLE_ASSIGNMENT((#204462)); +#204462 = SURFACE_STYLE_USAGE(.BOTH.,#204463); +#204463 = SURFACE_SIDE_STYLE('',(#204464)); +#204464 = SURFACE_STYLE_FILL_AREA(#204465); +#204465 = FILL_AREA_STYLE('',(#204466)); +#204466 = FILL_AREA_STYLE_COLOUR('',#204459); +#204467 = OVER_RIDING_STYLED_ITEM('overriding color',(#204468),#10229, + #204445); +#204468 = PRESENTATION_STYLE_ASSIGNMENT((#204469)); +#204469 = SURFACE_STYLE_USAGE(.BOTH.,#204470); +#204470 = SURFACE_SIDE_STYLE('',(#204471)); +#204471 = SURFACE_STYLE_FILL_AREA(#204472); +#204472 = FILL_AREA_STYLE('',(#204473)); +#204473 = FILL_AREA_STYLE_COLOUR('',#204459); +#204474 = OVER_RIDING_STYLED_ITEM('overriding color',(#204475),#10278, + #204445); #204475 = PRESENTATION_STYLE_ASSIGNMENT((#204476)); #204476 = SURFACE_STYLE_USAGE(.BOTH.,#204477); #204477 = SURFACE_SIDE_STYLE('',(#204478)); #204478 = SURFACE_STYLE_FILL_AREA(#204479); #204479 = FILL_AREA_STYLE('',(#204480)); -#204480 = FILL_AREA_STYLE_COLOUR('',#204473); -#204481 = OVER_RIDING_STYLED_ITEM('overriding color',(#204482),#158911, - #204458); +#204480 = FILL_AREA_STYLE_COLOUR('',#204459); +#204481 = OVER_RIDING_STYLED_ITEM('overriding color',(#204482),#10327, + #204445); #204482 = PRESENTATION_STYLE_ASSIGNMENT((#204483)); #204483 = SURFACE_STYLE_USAGE(.BOTH.,#204484); #204484 = SURFACE_SIDE_STYLE('',(#204485)); #204485 = SURFACE_STYLE_FILL_AREA(#204486); #204486 = FILL_AREA_STYLE('',(#204487)); -#204487 = FILL_AREA_STYLE_COLOUR('',#204473); -#204488 = OVER_RIDING_STYLED_ITEM('overriding color',(#204489),#158987, - #204458); +#204487 = FILL_AREA_STYLE_COLOUR('',#204459); +#204488 = OVER_RIDING_STYLED_ITEM('overriding color',(#204489),#10375, + #204445); #204489 = PRESENTATION_STYLE_ASSIGNMENT((#204490)); #204490 = SURFACE_STYLE_USAGE(.BOTH.,#204491); #204491 = SURFACE_SIDE_STYLE('',(#204492)); #204492 = SURFACE_STYLE_FILL_AREA(#204493); #204493 = FILL_AREA_STYLE('',(#204494)); -#204494 = FILL_AREA_STYLE_COLOUR('',#204473); -#204495 = OVER_RIDING_STYLED_ITEM('overriding color',(#204496),#159063, - #204458); +#204494 = FILL_AREA_STYLE_COLOUR('',#204459); +#204495 = OVER_RIDING_STYLED_ITEM('overriding color',(#204496),#10427, + #204445); #204496 = PRESENTATION_STYLE_ASSIGNMENT((#204497)); #204497 = SURFACE_STYLE_USAGE(.BOTH.,#204498); #204498 = SURFACE_SIDE_STYLE('',(#204499)); #204499 = SURFACE_STYLE_FILL_AREA(#204500); #204500 = FILL_AREA_STYLE('',(#204501)); -#204501 = FILL_AREA_STYLE_COLOUR('',#204473); -#204502 = OVER_RIDING_STYLED_ITEM('overriding color',(#204503),#159138, - #204458); +#204501 = FILL_AREA_STYLE_COLOUR('',#204459); +#204502 = OVER_RIDING_STYLED_ITEM('overriding color',(#204503),#10476, + #204445); #204503 = PRESENTATION_STYLE_ASSIGNMENT((#204504)); #204504 = SURFACE_STYLE_USAGE(.BOTH.,#204505); #204505 = SURFACE_SIDE_STYLE('',(#204506)); #204506 = SURFACE_STYLE_FILL_AREA(#204507); #204507 = FILL_AREA_STYLE('',(#204508)); -#204508 = FILL_AREA_STYLE_COLOUR('',#204473); -#204509 = OVER_RIDING_STYLED_ITEM('overriding color',(#204510),#159213, - #204458); +#204508 = FILL_AREA_STYLE_COLOUR('',#204459); +#204509 = OVER_RIDING_STYLED_ITEM('overriding color',(#204510),#10525, + #204445); #204510 = PRESENTATION_STYLE_ASSIGNMENT((#204511)); #204511 = SURFACE_STYLE_USAGE(.BOTH.,#204512); #204512 = SURFACE_SIDE_STYLE('',(#204513)); #204513 = SURFACE_STYLE_FILL_AREA(#204514); #204514 = FILL_AREA_STYLE('',(#204515)); -#204515 = FILL_AREA_STYLE_COLOUR('',#204473); -#204516 = OVER_RIDING_STYLED_ITEM('overriding color',(#204517),#159288, - #204458); +#204515 = FILL_AREA_STYLE_COLOUR('',#204459); +#204516 = OVER_RIDING_STYLED_ITEM('overriding color',(#204517),#10552, + #204445); #204517 = PRESENTATION_STYLE_ASSIGNMENT((#204518)); #204518 = SURFACE_STYLE_USAGE(.BOTH.,#204519); #204519 = SURFACE_SIDE_STYLE('',(#204520)); #204520 = SURFACE_STYLE_FILL_AREA(#204521); #204521 = FILL_AREA_STYLE('',(#204522)); -#204522 = FILL_AREA_STYLE_COLOUR('',#204473); -#204523 = OVER_RIDING_STYLED_ITEM('overriding color',(#204524),#159371, - #204458); +#204522 = FILL_AREA_STYLE_COLOUR('',#204459); +#204523 = STYLED_ITEM('color',(#204524),#10563); #204524 = PRESENTATION_STYLE_ASSIGNMENT((#204525)); #204525 = SURFACE_STYLE_USAGE(.BOTH.,#204526); #204526 = SURFACE_SIDE_STYLE('',(#204527)); #204527 = SURFACE_STYLE_FILL_AREA(#204528); #204528 = FILL_AREA_STYLE('',(#204529)); -#204529 = FILL_AREA_STYLE_COLOUR('',#204473); -#204530 = OVER_RIDING_STYLED_ITEM('overriding color',(#204531),#159489, - #204458); +#204529 = FILL_AREA_STYLE_COLOUR('',#197417); +#204530 = OVER_RIDING_STYLED_ITEM('overriding color',(#204531),#10565, + #204523); #204531 = PRESENTATION_STYLE_ASSIGNMENT((#204532)); #204532 = SURFACE_STYLE_USAGE(.BOTH.,#204533); #204533 = SURFACE_SIDE_STYLE('',(#204534)); #204534 = SURFACE_STYLE_FILL_AREA(#204535); #204535 = FILL_AREA_STYLE('',(#204536)); -#204536 = FILL_AREA_STYLE_COLOUR('',#204473); -#204537 = OVER_RIDING_STYLED_ITEM('overriding color',(#204538),#159572, - #204458); +#204536 = FILL_AREA_STYLE_COLOUR('',#198418); +#204537 = OVER_RIDING_STYLED_ITEM('overriding color',(#204538),#10685, + #204523); #204538 = PRESENTATION_STYLE_ASSIGNMENT((#204539)); #204539 = SURFACE_STYLE_USAGE(.BOTH.,#204540); #204540 = SURFACE_SIDE_STYLE('',(#204541)); #204541 = SURFACE_STYLE_FILL_AREA(#204542); #204542 = FILL_AREA_STYLE('',(#204543)); -#204543 = FILL_AREA_STYLE_COLOUR('',#204473); -#204544 = OVER_RIDING_STYLED_ITEM('overriding color',(#204545),#159648, - #204458); +#204543 = FILL_AREA_STYLE_COLOUR('',#198418); +#204544 = OVER_RIDING_STYLED_ITEM('overriding color',(#204545),#10761, + #204523); #204545 = PRESENTATION_STYLE_ASSIGNMENT((#204546)); #204546 = SURFACE_STYLE_USAGE(.BOTH.,#204547); #204547 = SURFACE_SIDE_STYLE('',(#204548)); #204548 = SURFACE_STYLE_FILL_AREA(#204549); #204549 = FILL_AREA_STYLE('',(#204550)); -#204550 = FILL_AREA_STYLE_COLOUR('',#204473); -#204551 = OVER_RIDING_STYLED_ITEM('overriding color',(#204552),#159724, - #204458); +#204550 = FILL_AREA_STYLE_COLOUR('',#198418); +#204551 = OVER_RIDING_STYLED_ITEM('overriding color',(#204552),#10810, + #204523); #204552 = PRESENTATION_STYLE_ASSIGNMENT((#204553)); #204553 = SURFACE_STYLE_USAGE(.BOTH.,#204554); #204554 = SURFACE_SIDE_STYLE('',(#204555)); #204555 = SURFACE_STYLE_FILL_AREA(#204556); #204556 = FILL_AREA_STYLE('',(#204557)); -#204557 = FILL_AREA_STYLE_COLOUR('',#204473); -#204558 = OVER_RIDING_STYLED_ITEM('overriding color',(#204559),#159799, - #204458); +#204557 = FILL_AREA_STYLE_COLOUR('',#198418); +#204558 = OVER_RIDING_STYLED_ITEM('overriding color',(#204559),#10859, + #204523); #204559 = PRESENTATION_STYLE_ASSIGNMENT((#204560)); #204560 = SURFACE_STYLE_USAGE(.BOTH.,#204561); #204561 = SURFACE_SIDE_STYLE('',(#204562)); #204562 = SURFACE_STYLE_FILL_AREA(#204563); #204563 = FILL_AREA_STYLE('',(#204564)); -#204564 = FILL_AREA_STYLE_COLOUR('',#204473); -#204565 = OVER_RIDING_STYLED_ITEM('overriding color',(#204566),#159874, - #204458); +#204564 = FILL_AREA_STYLE_COLOUR('',#198418); +#204565 = OVER_RIDING_STYLED_ITEM('overriding color',(#204566),#10886, + #204523); #204566 = PRESENTATION_STYLE_ASSIGNMENT((#204567)); #204567 = SURFACE_STYLE_USAGE(.BOTH.,#204568); #204568 = SURFACE_SIDE_STYLE('',(#204569)); #204569 = SURFACE_STYLE_FILL_AREA(#204570); #204570 = FILL_AREA_STYLE('',(#204571)); -#204571 = FILL_AREA_STYLE_COLOUR('',#204473); -#204572 = OVER_RIDING_STYLED_ITEM('overriding color',(#204573),#159949, - #204458); +#204571 = FILL_AREA_STYLE_COLOUR('',#198418); +#204572 = STYLED_ITEM('color',(#204573),#10893); #204573 = PRESENTATION_STYLE_ASSIGNMENT((#204574)); #204574 = SURFACE_STYLE_USAGE(.BOTH.,#204575); #204575 = SURFACE_SIDE_STYLE('',(#204576)); #204576 = SURFACE_STYLE_FILL_AREA(#204577); #204577 = FILL_AREA_STYLE('',(#204578)); -#204578 = FILL_AREA_STYLE_COLOUR('',#204473); -#204579 = OVER_RIDING_STYLED_ITEM('overriding color',(#204580),#160027, - #204458); +#204578 = FILL_AREA_STYLE_COLOUR('',#197417); +#204579 = OVER_RIDING_STYLED_ITEM('overriding color',(#204580),#10895, + #204572); #204580 = PRESENTATION_STYLE_ASSIGNMENT((#204581)); #204581 = SURFACE_STYLE_USAGE(.BOTH.,#204582); #204582 = SURFACE_SIDE_STYLE('',(#204583)); #204583 = SURFACE_STYLE_FILL_AREA(#204584); #204584 = FILL_AREA_STYLE('',(#204585)); -#204585 = FILL_AREA_STYLE_COLOUR('',#204473); -#204586 = OVER_RIDING_STYLED_ITEM('overriding color',(#204587),#160145, - #204458); +#204585 = FILL_AREA_STYLE_COLOUR('',#197440); +#204586 = OVER_RIDING_STYLED_ITEM('overriding color',(#204587),#11015, + #204572); #204587 = PRESENTATION_STYLE_ASSIGNMENT((#204588)); #204588 = SURFACE_STYLE_USAGE(.BOTH.,#204589); #204589 = SURFACE_SIDE_STYLE('',(#204590)); #204590 = SURFACE_STYLE_FILL_AREA(#204591); #204591 = FILL_AREA_STYLE('',(#204592)); -#204592 = FILL_AREA_STYLE_COLOUR('',#204473); -#204593 = OVER_RIDING_STYLED_ITEM('overriding color',(#204594),#160228, - #204458); +#204592 = FILL_AREA_STYLE_COLOUR('',#197440); +#204593 = OVER_RIDING_STYLED_ITEM('overriding color',(#204594),#11091, + #204572); #204594 = PRESENTATION_STYLE_ASSIGNMENT((#204595)); #204595 = SURFACE_STYLE_USAGE(.BOTH.,#204596); #204596 = SURFACE_SIDE_STYLE('',(#204597)); #204597 = SURFACE_STYLE_FILL_AREA(#204598); #204598 = FILL_AREA_STYLE('',(#204599)); -#204599 = FILL_AREA_STYLE_COLOUR('',#204473); -#204600 = OVER_RIDING_STYLED_ITEM('overriding color',(#204601),#160304, - #204458); +#204599 = FILL_AREA_STYLE_COLOUR('',#197440); +#204600 = OVER_RIDING_STYLED_ITEM('overriding color',(#204601),#11140, + #204572); #204601 = PRESENTATION_STYLE_ASSIGNMENT((#204602)); #204602 = SURFACE_STYLE_USAGE(.BOTH.,#204603); #204603 = SURFACE_SIDE_STYLE('',(#204604)); #204604 = SURFACE_STYLE_FILL_AREA(#204605); #204605 = FILL_AREA_STYLE('',(#204606)); -#204606 = FILL_AREA_STYLE_COLOUR('',#204473); -#204607 = OVER_RIDING_STYLED_ITEM('overriding color',(#204608),#160380, - #204458); +#204606 = FILL_AREA_STYLE_COLOUR('',#197440); +#204607 = OVER_RIDING_STYLED_ITEM('overriding color',(#204608),#11189, + #204572); #204608 = PRESENTATION_STYLE_ASSIGNMENT((#204609)); #204609 = SURFACE_STYLE_USAGE(.BOTH.,#204610); #204610 = SURFACE_SIDE_STYLE('',(#204611)); #204611 = SURFACE_STYLE_FILL_AREA(#204612); #204612 = FILL_AREA_STYLE('',(#204613)); -#204613 = FILL_AREA_STYLE_COLOUR('',#204473); -#204614 = OVER_RIDING_STYLED_ITEM('overriding color',(#204615),#160455, - #204458); +#204613 = FILL_AREA_STYLE_COLOUR('',#197440); +#204614 = OVER_RIDING_STYLED_ITEM('overriding color',(#204615),#11216, + #204572); #204615 = PRESENTATION_STYLE_ASSIGNMENT((#204616)); #204616 = SURFACE_STYLE_USAGE(.BOTH.,#204617); #204617 = SURFACE_SIDE_STYLE('',(#204618)); #204618 = SURFACE_STYLE_FILL_AREA(#204619); #204619 = FILL_AREA_STYLE('',(#204620)); -#204620 = FILL_AREA_STYLE_COLOUR('',#204473); -#204621 = OVER_RIDING_STYLED_ITEM('overriding color',(#204622),#160530, - #204458); +#204620 = FILL_AREA_STYLE_COLOUR('',#197440); +#204621 = STYLED_ITEM('color',(#204622),#11223); #204622 = PRESENTATION_STYLE_ASSIGNMENT((#204623)); #204623 = SURFACE_STYLE_USAGE(.BOTH.,#204624); #204624 = SURFACE_SIDE_STYLE('',(#204625)); #204625 = SURFACE_STYLE_FILL_AREA(#204626); #204626 = FILL_AREA_STYLE('',(#204627)); -#204627 = FILL_AREA_STYLE_COLOUR('',#204473); -#204628 = OVER_RIDING_STYLED_ITEM('overriding color',(#204629),#160605, - #204458); +#204627 = FILL_AREA_STYLE_COLOUR('',#197417); +#204628 = OVER_RIDING_STYLED_ITEM('overriding color',(#204629),#11225, + #204621); #204629 = PRESENTATION_STYLE_ASSIGNMENT((#204630)); #204630 = SURFACE_STYLE_USAGE(.BOTH.,#204631); #204631 = SURFACE_SIDE_STYLE('',(#204632)); #204632 = SURFACE_STYLE_FILL_AREA(#204633); #204633 = FILL_AREA_STYLE('',(#204634)); -#204634 = FILL_AREA_STYLE_COLOUR('',#204473); -#204635 = OVER_RIDING_STYLED_ITEM('overriding color',(#204636),#160683, - #204458); +#204634 = FILL_AREA_STYLE_COLOUR('',#197425); +#204635 = OVER_RIDING_STYLED_ITEM('overriding color',(#204636),#11443, + #204621); #204636 = PRESENTATION_STYLE_ASSIGNMENT((#204637)); #204637 = SURFACE_STYLE_USAGE(.BOTH.,#204638); #204638 = SURFACE_SIDE_STYLE('',(#204639)); #204639 = SURFACE_STYLE_FILL_AREA(#204640); #204640 = FILL_AREA_STYLE('',(#204641)); -#204641 = FILL_AREA_STYLE_COLOUR('',#204473); -#204642 = OVER_RIDING_STYLED_ITEM('overriding color',(#204643),#160796, - #204458); +#204641 = FILL_AREA_STYLE_COLOUR('',#197425); +#204642 = OVER_RIDING_STYLED_ITEM('overriding color',(#204643),#11519, + #204621); #204643 = PRESENTATION_STYLE_ASSIGNMENT((#204644)); #204644 = SURFACE_STYLE_USAGE(.BOTH.,#204645); #204645 = SURFACE_SIDE_STYLE('',(#204646)); #204646 = SURFACE_STYLE_FILL_AREA(#204647); #204647 = FILL_AREA_STYLE('',(#204648)); -#204648 = FILL_AREA_STYLE_COLOUR('',#204473); -#204649 = OVER_RIDING_STYLED_ITEM('overriding color',(#204650),#160879, - #204458); +#204648 = FILL_AREA_STYLE_COLOUR('',#197425); +#204649 = OVER_RIDING_STYLED_ITEM('overriding color',(#204650),#11629, + #204621); #204650 = PRESENTATION_STYLE_ASSIGNMENT((#204651)); #204651 = SURFACE_STYLE_USAGE(.BOTH.,#204652); #204652 = SURFACE_SIDE_STYLE('',(#204653)); #204653 = SURFACE_STYLE_FILL_AREA(#204654); #204654 = FILL_AREA_STYLE('',(#204655)); -#204655 = FILL_AREA_STYLE_COLOUR('',#204473); -#204656 = OVER_RIDING_STYLED_ITEM('overriding color',(#204657),#160955, - #204458); +#204655 = FILL_AREA_STYLE_COLOUR('',#197425); +#204656 = OVER_RIDING_STYLED_ITEM('overriding color',(#204657),#11700, + #204621); #204657 = PRESENTATION_STYLE_ASSIGNMENT((#204658)); #204658 = SURFACE_STYLE_USAGE(.BOTH.,#204659); #204659 = SURFACE_SIDE_STYLE('',(#204660)); #204660 = SURFACE_STYLE_FILL_AREA(#204661); #204661 = FILL_AREA_STYLE('',(#204662)); -#204662 = FILL_AREA_STYLE_COLOUR('',#204473); -#204663 = OVER_RIDING_STYLED_ITEM('overriding color',(#204664),#161031, - #204458); +#204662 = FILL_AREA_STYLE_COLOUR('',#197425); +#204663 = OVER_RIDING_STYLED_ITEM('overriding color',(#204664),#11749, + #204621); #204664 = PRESENTATION_STYLE_ASSIGNMENT((#204665)); #204665 = SURFACE_STYLE_USAGE(.BOTH.,#204666); #204666 = SURFACE_SIDE_STYLE('',(#204667)); #204667 = SURFACE_STYLE_FILL_AREA(#204668); #204668 = FILL_AREA_STYLE('',(#204669)); -#204669 = FILL_AREA_STYLE_COLOUR('',#204473); -#204670 = OVER_RIDING_STYLED_ITEM('overriding color',(#204671),#161106, - #204458); +#204669 = FILL_AREA_STYLE_COLOUR('',#197425); +#204670 = OVER_RIDING_STYLED_ITEM('overriding color',(#204671),#11827, + #204621); #204671 = PRESENTATION_STYLE_ASSIGNMENT((#204672)); #204672 = SURFACE_STYLE_USAGE(.BOTH.,#204673); #204673 = SURFACE_SIDE_STYLE('',(#204674)); #204674 = SURFACE_STYLE_FILL_AREA(#204675); #204675 = FILL_AREA_STYLE('',(#204676)); -#204676 = FILL_AREA_STYLE_COLOUR('',#204473); -#204677 = OVER_RIDING_STYLED_ITEM('overriding color',(#204678),#161181, - #204458); +#204676 = FILL_AREA_STYLE_COLOUR('',#197425); +#204677 = OVER_RIDING_STYLED_ITEM('overriding color',(#204678),#11986, + #204621); #204678 = PRESENTATION_STYLE_ASSIGNMENT((#204679)); #204679 = SURFACE_STYLE_USAGE(.BOTH.,#204680); #204680 = SURFACE_SIDE_STYLE('',(#204681)); #204681 = SURFACE_STYLE_FILL_AREA(#204682); #204682 = FILL_AREA_STYLE('',(#204683)); -#204683 = FILL_AREA_STYLE_COLOUR('',#204473); -#204684 = OVER_RIDING_STYLED_ITEM('overriding color',(#204685),#161256, - #204458); +#204683 = FILL_AREA_STYLE_COLOUR('',#197425); +#204684 = OVER_RIDING_STYLED_ITEM('overriding color',(#204685),#12061, + #204621); #204685 = PRESENTATION_STYLE_ASSIGNMENT((#204686)); #204686 = SURFACE_STYLE_USAGE(.BOTH.,#204687); #204687 = SURFACE_SIDE_STYLE('',(#204688)); #204688 = SURFACE_STYLE_FILL_AREA(#204689); #204689 = FILL_AREA_STYLE('',(#204690)); -#204690 = FILL_AREA_STYLE_COLOUR('',#204473); -#204691 = OVER_RIDING_STYLED_ITEM('overriding color',(#204692),#161334, - #204458); +#204690 = FILL_AREA_STYLE_COLOUR('',#197425); +#204691 = OVER_RIDING_STYLED_ITEM('overriding color',(#204692),#12114, + #204621); #204692 = PRESENTATION_STYLE_ASSIGNMENT((#204693)); #204693 = SURFACE_STYLE_USAGE(.BOTH.,#204694); #204694 = SURFACE_SIDE_STYLE('',(#204695)); #204695 = SURFACE_STYLE_FILL_AREA(#204696); #204696 = FILL_AREA_STYLE('',(#204697)); -#204697 = FILL_AREA_STYLE_COLOUR('',#204473); -#204698 = OVER_RIDING_STYLED_ITEM('overriding color',(#204699),#161452, - #204458); +#204697 = FILL_AREA_STYLE_COLOUR('',#197425); +#204698 = OVER_RIDING_STYLED_ITEM('overriding color',(#204699),#12163, + #204621); #204699 = PRESENTATION_STYLE_ASSIGNMENT((#204700)); #204700 = SURFACE_STYLE_USAGE(.BOTH.,#204701); #204701 = SURFACE_SIDE_STYLE('',(#204702)); #204702 = SURFACE_STYLE_FILL_AREA(#204703); #204703 = FILL_AREA_STYLE('',(#204704)); -#204704 = FILL_AREA_STYLE_COLOUR('',#204473); -#204705 = OVER_RIDING_STYLED_ITEM('overriding color',(#204706),#161535, - #204458); +#204704 = FILL_AREA_STYLE_COLOUR('',#197425); +#204705 = OVER_RIDING_STYLED_ITEM('overriding color',(#204706),#12216, + #204621); #204706 = PRESENTATION_STYLE_ASSIGNMENT((#204707)); #204707 = SURFACE_STYLE_USAGE(.BOTH.,#204708); #204708 = SURFACE_SIDE_STYLE('',(#204709)); #204709 = SURFACE_STYLE_FILL_AREA(#204710); #204710 = FILL_AREA_STYLE('',(#204711)); -#204711 = FILL_AREA_STYLE_COLOUR('',#204473); -#204712 = OVER_RIDING_STYLED_ITEM('overriding color',(#204713),#161611, - #204458); +#204711 = FILL_AREA_STYLE_COLOUR('',#197425); +#204712 = OVER_RIDING_STYLED_ITEM('overriding color',(#204713),#12264, + #204621); #204713 = PRESENTATION_STYLE_ASSIGNMENT((#204714)); #204714 = SURFACE_STYLE_USAGE(.BOTH.,#204715); #204715 = SURFACE_SIDE_STYLE('',(#204716)); #204716 = SURFACE_STYLE_FILL_AREA(#204717); #204717 = FILL_AREA_STYLE('',(#204718)); -#204718 = FILL_AREA_STYLE_COLOUR('',#204473); -#204719 = OVER_RIDING_STYLED_ITEM('overriding color',(#204720),#161687, - #204458); +#204718 = FILL_AREA_STYLE_COLOUR('',#197425); +#204719 = OVER_RIDING_STYLED_ITEM('overriding color',(#204720),#12295, + #204621); #204720 = PRESENTATION_STYLE_ASSIGNMENT((#204721)); #204721 = SURFACE_STYLE_USAGE(.BOTH.,#204722); #204722 = SURFACE_SIDE_STYLE('',(#204723)); #204723 = SURFACE_STYLE_FILL_AREA(#204724); #204724 = FILL_AREA_STYLE('',(#204725)); -#204725 = FILL_AREA_STYLE_COLOUR('',#204473); -#204726 = OVER_RIDING_STYLED_ITEM('overriding color',(#204727),#161762, - #204458); +#204725 = FILL_AREA_STYLE_COLOUR('',#197425); +#204726 = STYLED_ITEM('color',(#204727),#12304); #204727 = PRESENTATION_STYLE_ASSIGNMENT((#204728)); #204728 = SURFACE_STYLE_USAGE(.BOTH.,#204729); #204729 = SURFACE_SIDE_STYLE('',(#204730)); #204730 = SURFACE_STYLE_FILL_AREA(#204731); #204731 = FILL_AREA_STYLE('',(#204732)); -#204732 = FILL_AREA_STYLE_COLOUR('',#204473); -#204733 = OVER_RIDING_STYLED_ITEM('overriding color',(#204734),#161837, - #204458); +#204732 = FILL_AREA_STYLE_COLOUR('',#197417); +#204733 = OVER_RIDING_STYLED_ITEM('overriding color',(#204734),#12306, + #204726); #204734 = PRESENTATION_STYLE_ASSIGNMENT((#204735)); #204735 = SURFACE_STYLE_USAGE(.BOTH.,#204736); #204736 = SURFACE_SIDE_STYLE('',(#204737)); #204737 = SURFACE_STYLE_FILL_AREA(#204738); #204738 = FILL_AREA_STYLE('',(#204739)); -#204739 = FILL_AREA_STYLE_COLOUR('',#204473); -#204740 = OVER_RIDING_STYLED_ITEM('overriding color',(#204741),#161912, - #204458); +#204739 = FILL_AREA_STYLE_COLOUR('',#197425); +#204740 = OVER_RIDING_STYLED_ITEM('overriding color',(#204741),#12524, + #204726); #204741 = PRESENTATION_STYLE_ASSIGNMENT((#204742)); #204742 = SURFACE_STYLE_USAGE(.BOTH.,#204743); #204743 = SURFACE_SIDE_STYLE('',(#204744)); #204744 = SURFACE_STYLE_FILL_AREA(#204745); #204745 = FILL_AREA_STYLE('',(#204746)); -#204746 = FILL_AREA_STYLE_COLOUR('',#204473); -#204747 = OVER_RIDING_STYLED_ITEM('overriding color',(#204748),#161990, - #204458); +#204746 = FILL_AREA_STYLE_COLOUR('',#197425); +#204747 = OVER_RIDING_STYLED_ITEM('overriding color',(#204748),#12600, + #204726); #204748 = PRESENTATION_STYLE_ASSIGNMENT((#204749)); #204749 = SURFACE_STYLE_USAGE(.BOTH.,#204750); #204750 = SURFACE_SIDE_STYLE('',(#204751)); #204751 = SURFACE_STYLE_FILL_AREA(#204752); #204752 = FILL_AREA_STYLE('',(#204753)); -#204753 = FILL_AREA_STYLE_COLOUR('',#204473); -#204754 = OVER_RIDING_STYLED_ITEM('overriding color',(#204755),#162108, - #204458); +#204753 = FILL_AREA_STYLE_COLOUR('',#197425); +#204754 = OVER_RIDING_STYLED_ITEM('overriding color',(#204755),#12710, + #204726); #204755 = PRESENTATION_STYLE_ASSIGNMENT((#204756)); #204756 = SURFACE_STYLE_USAGE(.BOTH.,#204757); #204757 = SURFACE_SIDE_STYLE('',(#204758)); #204758 = SURFACE_STYLE_FILL_AREA(#204759); #204759 = FILL_AREA_STYLE('',(#204760)); -#204760 = FILL_AREA_STYLE_COLOUR('',#204473); -#204761 = OVER_RIDING_STYLED_ITEM('overriding color',(#204762),#162191, - #204458); +#204760 = FILL_AREA_STYLE_COLOUR('',#197425); +#204761 = OVER_RIDING_STYLED_ITEM('overriding color',(#204762),#12781, + #204726); #204762 = PRESENTATION_STYLE_ASSIGNMENT((#204763)); #204763 = SURFACE_STYLE_USAGE(.BOTH.,#204764); #204764 = SURFACE_SIDE_STYLE('',(#204765)); #204765 = SURFACE_STYLE_FILL_AREA(#204766); #204766 = FILL_AREA_STYLE('',(#204767)); -#204767 = FILL_AREA_STYLE_COLOUR('',#204473); -#204768 = OVER_RIDING_STYLED_ITEM('overriding color',(#204769),#162267, - #204458); +#204767 = FILL_AREA_STYLE_COLOUR('',#197425); +#204768 = OVER_RIDING_STYLED_ITEM('overriding color',(#204769),#12830, + #204726); #204769 = PRESENTATION_STYLE_ASSIGNMENT((#204770)); #204770 = SURFACE_STYLE_USAGE(.BOTH.,#204771); #204771 = SURFACE_SIDE_STYLE('',(#204772)); #204772 = SURFACE_STYLE_FILL_AREA(#204773); #204773 = FILL_AREA_STYLE('',(#204774)); -#204774 = FILL_AREA_STYLE_COLOUR('',#204473); -#204775 = OVER_RIDING_STYLED_ITEM('overriding color',(#204776),#162343, - #204458); +#204774 = FILL_AREA_STYLE_COLOUR('',#197425); +#204775 = OVER_RIDING_STYLED_ITEM('overriding color',(#204776),#12908, + #204726); #204776 = PRESENTATION_STYLE_ASSIGNMENT((#204777)); #204777 = SURFACE_STYLE_USAGE(.BOTH.,#204778); #204778 = SURFACE_SIDE_STYLE('',(#204779)); #204779 = SURFACE_STYLE_FILL_AREA(#204780); #204780 = FILL_AREA_STYLE('',(#204781)); -#204781 = FILL_AREA_STYLE_COLOUR('',#204473); -#204782 = OVER_RIDING_STYLED_ITEM('overriding color',(#204783),#162418, - #204458); +#204781 = FILL_AREA_STYLE_COLOUR('',#197425); +#204782 = OVER_RIDING_STYLED_ITEM('overriding color',(#204783),#13067, + #204726); #204783 = PRESENTATION_STYLE_ASSIGNMENT((#204784)); #204784 = SURFACE_STYLE_USAGE(.BOTH.,#204785); #204785 = SURFACE_SIDE_STYLE('',(#204786)); #204786 = SURFACE_STYLE_FILL_AREA(#204787); #204787 = FILL_AREA_STYLE('',(#204788)); -#204788 = FILL_AREA_STYLE_COLOUR('',#204473); -#204789 = OVER_RIDING_STYLED_ITEM('overriding color',(#204790),#162493, - #204458); +#204788 = FILL_AREA_STYLE_COLOUR('',#197425); +#204789 = OVER_RIDING_STYLED_ITEM('overriding color',(#204790),#13142, + #204726); #204790 = PRESENTATION_STYLE_ASSIGNMENT((#204791)); #204791 = SURFACE_STYLE_USAGE(.BOTH.,#204792); #204792 = SURFACE_SIDE_STYLE('',(#204793)); #204793 = SURFACE_STYLE_FILL_AREA(#204794); #204794 = FILL_AREA_STYLE('',(#204795)); -#204795 = FILL_AREA_STYLE_COLOUR('',#204473); -#204796 = OVER_RIDING_STYLED_ITEM('overriding color',(#204797),#162568, - #204458); +#204795 = FILL_AREA_STYLE_COLOUR('',#197425); +#204796 = OVER_RIDING_STYLED_ITEM('overriding color',(#204797),#13195, + #204726); #204797 = PRESENTATION_STYLE_ASSIGNMENT((#204798)); #204798 = SURFACE_STYLE_USAGE(.BOTH.,#204799); #204799 = SURFACE_SIDE_STYLE('',(#204800)); #204800 = SURFACE_STYLE_FILL_AREA(#204801); #204801 = FILL_AREA_STYLE('',(#204802)); -#204802 = FILL_AREA_STYLE_COLOUR('',#204473); -#204803 = OVER_RIDING_STYLED_ITEM('overriding color',(#204804),#162646, - #204458); +#204802 = FILL_AREA_STYLE_COLOUR('',#197425); +#204803 = OVER_RIDING_STYLED_ITEM('overriding color',(#204804),#13244, + #204726); #204804 = PRESENTATION_STYLE_ASSIGNMENT((#204805)); #204805 = SURFACE_STYLE_USAGE(.BOTH.,#204806); #204806 = SURFACE_SIDE_STYLE('',(#204807)); #204807 = SURFACE_STYLE_FILL_AREA(#204808); #204808 = FILL_AREA_STYLE('',(#204809)); -#204809 = FILL_AREA_STYLE_COLOUR('',#204473); -#204810 = OVER_RIDING_STYLED_ITEM('overriding color',(#204811),#162764, - #204458); +#204809 = FILL_AREA_STYLE_COLOUR('',#197425); +#204810 = OVER_RIDING_STYLED_ITEM('overriding color',(#204811),#13297, + #204726); #204811 = PRESENTATION_STYLE_ASSIGNMENT((#204812)); #204812 = SURFACE_STYLE_USAGE(.BOTH.,#204813); #204813 = SURFACE_SIDE_STYLE('',(#204814)); #204814 = SURFACE_STYLE_FILL_AREA(#204815); #204815 = FILL_AREA_STYLE('',(#204816)); -#204816 = FILL_AREA_STYLE_COLOUR('',#204473); -#204817 = OVER_RIDING_STYLED_ITEM('overriding color',(#204818),#162847, - #204458); +#204816 = FILL_AREA_STYLE_COLOUR('',#197425); +#204817 = OVER_RIDING_STYLED_ITEM('overriding color',(#204818),#13345, + #204726); #204818 = PRESENTATION_STYLE_ASSIGNMENT((#204819)); #204819 = SURFACE_STYLE_USAGE(.BOTH.,#204820); #204820 = SURFACE_SIDE_STYLE('',(#204821)); #204821 = SURFACE_STYLE_FILL_AREA(#204822); #204822 = FILL_AREA_STYLE('',(#204823)); -#204823 = FILL_AREA_STYLE_COLOUR('',#204473); -#204824 = OVER_RIDING_STYLED_ITEM('overriding color',(#204825),#162923, - #204458); +#204823 = FILL_AREA_STYLE_COLOUR('',#197425); +#204824 = OVER_RIDING_STYLED_ITEM('overriding color',(#204825),#13399, + #204726); #204825 = PRESENTATION_STYLE_ASSIGNMENT((#204826)); #204826 = SURFACE_STYLE_USAGE(.BOTH.,#204827); #204827 = SURFACE_SIDE_STYLE('',(#204828)); #204828 = SURFACE_STYLE_FILL_AREA(#204829); #204829 = FILL_AREA_STYLE('',(#204830)); -#204830 = FILL_AREA_STYLE_COLOUR('',#204473); -#204831 = OVER_RIDING_STYLED_ITEM('overriding color',(#204832),#162999, - #204458); -#204832 = PRESENTATION_STYLE_ASSIGNMENT((#204833)); -#204833 = SURFACE_STYLE_USAGE(.BOTH.,#204834); -#204834 = SURFACE_SIDE_STYLE('',(#204835)); -#204835 = SURFACE_STYLE_FILL_AREA(#204836); -#204836 = FILL_AREA_STYLE('',(#204837)); -#204837 = FILL_AREA_STYLE_COLOUR('',#204473); -#204838 = OVER_RIDING_STYLED_ITEM('overriding color',(#204839),#163074, - #204458); -#204839 = PRESENTATION_STYLE_ASSIGNMENT((#204840)); -#204840 = SURFACE_STYLE_USAGE(.BOTH.,#204841); -#204841 = SURFACE_SIDE_STYLE('',(#204842)); -#204842 = SURFACE_STYLE_FILL_AREA(#204843); -#204843 = FILL_AREA_STYLE('',(#204844)); -#204844 = FILL_AREA_STYLE_COLOUR('',#204473); -#204845 = OVER_RIDING_STYLED_ITEM('overriding color',(#204846),#163149, - #204458); -#204846 = PRESENTATION_STYLE_ASSIGNMENT((#204847)); -#204847 = SURFACE_STYLE_USAGE(.BOTH.,#204848); -#204848 = SURFACE_SIDE_STYLE('',(#204849)); -#204849 = SURFACE_STYLE_FILL_AREA(#204850); -#204850 = FILL_AREA_STYLE('',(#204851)); -#204851 = FILL_AREA_STYLE_COLOUR('',#204473); -#204852 = OVER_RIDING_STYLED_ITEM('overriding color',(#204853),#163224, - #204458); -#204853 = PRESENTATION_STYLE_ASSIGNMENT((#204854)); -#204854 = SURFACE_STYLE_USAGE(.BOTH.,#204855); -#204855 = SURFACE_SIDE_STYLE('',(#204856)); -#204856 = SURFACE_STYLE_FILL_AREA(#204857); -#204857 = FILL_AREA_STYLE('',(#204858)); -#204858 = FILL_AREA_STYLE_COLOUR('',#204473); -#204859 = OVER_RIDING_STYLED_ITEM('overriding color',(#204860),#163302, - #204458); -#204860 = PRESENTATION_STYLE_ASSIGNMENT((#204861)); -#204861 = SURFACE_STYLE_USAGE(.BOTH.,#204862); -#204862 = SURFACE_SIDE_STYLE('',(#204863)); -#204863 = SURFACE_STYLE_FILL_AREA(#204864); -#204864 = FILL_AREA_STYLE('',(#204865)); -#204865 = FILL_AREA_STYLE_COLOUR('',#204473); -#204866 = OVER_RIDING_STYLED_ITEM('overriding color',(#204867),#163415, - #204458); -#204867 = PRESENTATION_STYLE_ASSIGNMENT((#204868)); -#204868 = SURFACE_STYLE_USAGE(.BOTH.,#204869); -#204869 = SURFACE_SIDE_STYLE('',(#204870)); -#204870 = SURFACE_STYLE_FILL_AREA(#204871); -#204871 = FILL_AREA_STYLE('',(#204872)); -#204872 = FILL_AREA_STYLE_COLOUR('',#204473); -#204873 = OVER_RIDING_STYLED_ITEM('overriding color',(#204874),#163498, - #204458); -#204874 = PRESENTATION_STYLE_ASSIGNMENT((#204875)); -#204875 = SURFACE_STYLE_USAGE(.BOTH.,#204876); -#204876 = SURFACE_SIDE_STYLE('',(#204877)); -#204877 = SURFACE_STYLE_FILL_AREA(#204878); -#204878 = FILL_AREA_STYLE('',(#204879)); -#204879 = FILL_AREA_STYLE_COLOUR('',#204473); -#204880 = OVER_RIDING_STYLED_ITEM('overriding color',(#204881),#163574, - #204458); -#204881 = PRESENTATION_STYLE_ASSIGNMENT((#204882)); -#204882 = SURFACE_STYLE_USAGE(.BOTH.,#204883); -#204883 = SURFACE_SIDE_STYLE('',(#204884)); -#204884 = SURFACE_STYLE_FILL_AREA(#204885); -#204885 = FILL_AREA_STYLE('',(#204886)); -#204886 = FILL_AREA_STYLE_COLOUR('',#204473); -#204887 = OVER_RIDING_STYLED_ITEM('overriding color',(#204888),#163650, - #204458); -#204888 = PRESENTATION_STYLE_ASSIGNMENT((#204889)); -#204889 = SURFACE_STYLE_USAGE(.BOTH.,#204890); -#204890 = SURFACE_SIDE_STYLE('',(#204891)); -#204891 = SURFACE_STYLE_FILL_AREA(#204892); -#204892 = FILL_AREA_STYLE('',(#204893)); -#204893 = FILL_AREA_STYLE_COLOUR('',#204473); -#204894 = OVER_RIDING_STYLED_ITEM('overriding color',(#204895),#163725, - #204458); -#204895 = PRESENTATION_STYLE_ASSIGNMENT((#204896)); -#204896 = SURFACE_STYLE_USAGE(.BOTH.,#204897); -#204897 = SURFACE_SIDE_STYLE('',(#204898)); -#204898 = SURFACE_STYLE_FILL_AREA(#204899); -#204899 = FILL_AREA_STYLE('',(#204900)); -#204900 = FILL_AREA_STYLE_COLOUR('',#204473); -#204901 = OVER_RIDING_STYLED_ITEM('overriding color',(#204902),#163800, - #204458); -#204902 = PRESENTATION_STYLE_ASSIGNMENT((#204903)); -#204903 = SURFACE_STYLE_USAGE(.BOTH.,#204904); -#204904 = SURFACE_SIDE_STYLE('',(#204905)); -#204905 = SURFACE_STYLE_FILL_AREA(#204906); -#204906 = FILL_AREA_STYLE('',(#204907)); -#204907 = FILL_AREA_STYLE_COLOUR('',#204473); -#204908 = OVER_RIDING_STYLED_ITEM('overriding color',(#204909),#163875, - #204458); -#204909 = PRESENTATION_STYLE_ASSIGNMENT((#204910)); -#204910 = SURFACE_STYLE_USAGE(.BOTH.,#204911); -#204911 = SURFACE_SIDE_STYLE('',(#204912)); -#204912 = SURFACE_STYLE_FILL_AREA(#204913); -#204913 = FILL_AREA_STYLE('',(#204914)); -#204914 = FILL_AREA_STYLE_COLOUR('',#204473); -#204915 = OVER_RIDING_STYLED_ITEM('overriding color',(#204916),#163953, - #204458); -#204916 = PRESENTATION_STYLE_ASSIGNMENT((#204917)); -#204917 = SURFACE_STYLE_USAGE(.BOTH.,#204918); -#204918 = SURFACE_SIDE_STYLE('',(#204919)); -#204919 = SURFACE_STYLE_FILL_AREA(#204920); -#204920 = FILL_AREA_STYLE('',(#204921)); -#204921 = FILL_AREA_STYLE_COLOUR('',#204473); -#204922 = OVER_RIDING_STYLED_ITEM('overriding color',(#204923),#164438, - #204458); -#204923 = PRESENTATION_STYLE_ASSIGNMENT((#204924)); -#204924 = SURFACE_STYLE_USAGE(.BOTH.,#204925); -#204925 = SURFACE_SIDE_STYLE('',(#204926)); -#204926 = SURFACE_STYLE_FILL_AREA(#204927); -#204927 = FILL_AREA_STYLE('',(#204928)); -#204928 = FILL_AREA_STYLE_COLOUR('',#204473); -#204929 = OVER_RIDING_STYLED_ITEM('overriding color',(#204930),#164526, - #204458); -#204930 = PRESENTATION_STYLE_ASSIGNMENT((#204931)); -#204931 = SURFACE_STYLE_USAGE(.BOTH.,#204932); -#204932 = SURFACE_SIDE_STYLE('',(#204933)); -#204933 = SURFACE_STYLE_FILL_AREA(#204934); -#204934 = FILL_AREA_STYLE('',(#204935)); -#204935 = FILL_AREA_STYLE_COLOUR('',#204473); -#204936 = OVER_RIDING_STYLED_ITEM('overriding color',(#204937),#164574, - #204458); -#204937 = PRESENTATION_STYLE_ASSIGNMENT((#204938)); -#204938 = SURFACE_STYLE_USAGE(.BOTH.,#204939); -#204939 = SURFACE_SIDE_STYLE('',(#204940)); -#204940 = SURFACE_STYLE_FILL_AREA(#204941); -#204941 = FILL_AREA_STYLE('',(#204942)); -#204942 = FILL_AREA_STYLE_COLOUR('',#204473); -#204943 = OVER_RIDING_STYLED_ITEM('overriding color',(#204944),#164631, - #204458); -#204944 = PRESENTATION_STYLE_ASSIGNMENT((#204945)); -#204945 = SURFACE_STYLE_USAGE(.BOTH.,#204946); -#204946 = SURFACE_SIDE_STYLE('',(#204947)); -#204947 = SURFACE_STYLE_FILL_AREA(#204948); -#204948 = FILL_AREA_STYLE('',(#204949)); -#204949 = FILL_AREA_STYLE_COLOUR('',#204473); -#204950 = OVER_RIDING_STYLED_ITEM('overriding color',(#204951),#164680, - #204458); -#204951 = PRESENTATION_STYLE_ASSIGNMENT((#204952)); -#204952 = SURFACE_STYLE_USAGE(.BOTH.,#204953); -#204953 = SURFACE_SIDE_STYLE('',(#204954)); -#204954 = SURFACE_STYLE_FILL_AREA(#204955); -#204955 = FILL_AREA_STYLE('',(#204956)); -#204956 = FILL_AREA_STYLE_COLOUR('',#204473); -#204957 = OVER_RIDING_STYLED_ITEM('overriding color',(#204958),#164741, - #204458); -#204958 = PRESENTATION_STYLE_ASSIGNMENT((#204959)); -#204959 = SURFACE_STYLE_USAGE(.BOTH.,#204960); -#204960 = SURFACE_SIDE_STYLE('',(#204961)); -#204961 = SURFACE_STYLE_FILL_AREA(#204962); -#204962 = FILL_AREA_STYLE('',(#204963)); -#204963 = FILL_AREA_STYLE_COLOUR('',#204473); -#204964 = OVER_RIDING_STYLED_ITEM('overriding color',(#204965),#164789, - #204458); -#204965 = PRESENTATION_STYLE_ASSIGNMENT((#204966)); -#204966 = SURFACE_STYLE_USAGE(.BOTH.,#204967); -#204967 = SURFACE_SIDE_STYLE('',(#204968)); -#204968 = SURFACE_STYLE_FILL_AREA(#204969); -#204969 = FILL_AREA_STYLE('',(#204970)); -#204970 = FILL_AREA_STYLE_COLOUR('',#204473); -#204971 = OVER_RIDING_STYLED_ITEM('overriding color',(#204972),#164846, - #204458); -#204972 = PRESENTATION_STYLE_ASSIGNMENT((#204973)); -#204973 = SURFACE_STYLE_USAGE(.BOTH.,#204974); -#204974 = SURFACE_SIDE_STYLE('',(#204975)); -#204975 = SURFACE_STYLE_FILL_AREA(#204976); -#204976 = FILL_AREA_STYLE('',(#204977)); -#204977 = FILL_AREA_STYLE_COLOUR('',#204473); -#204978 = OVER_RIDING_STYLED_ITEM('overriding color',(#204979),#164895, - #204458); -#204979 = PRESENTATION_STYLE_ASSIGNMENT((#204980)); -#204980 = SURFACE_STYLE_USAGE(.BOTH.,#204981); -#204981 = SURFACE_SIDE_STYLE('',(#204982)); -#204982 = SURFACE_STYLE_FILL_AREA(#204983); -#204983 = FILL_AREA_STYLE('',(#204984)); -#204984 = FILL_AREA_STYLE_COLOUR('',#204473); -#204985 = OVER_RIDING_STYLED_ITEM('overriding color',(#204986),#164956, - #204458); -#204986 = PRESENTATION_STYLE_ASSIGNMENT((#204987)); -#204987 = SURFACE_STYLE_USAGE(.BOTH.,#204988); -#204988 = SURFACE_SIDE_STYLE('',(#204989)); -#204989 = SURFACE_STYLE_FILL_AREA(#204990); -#204990 = FILL_AREA_STYLE('',(#204991)); -#204991 = FILL_AREA_STYLE_COLOUR('',#204473); -#204992 = OVER_RIDING_STYLED_ITEM('overriding color',(#204993),#165004, - #204458); -#204993 = PRESENTATION_STYLE_ASSIGNMENT((#204994)); -#204994 = SURFACE_STYLE_USAGE(.BOTH.,#204995); -#204995 = SURFACE_SIDE_STYLE('',(#204996)); -#204996 = SURFACE_STYLE_FILL_AREA(#204997); -#204997 = FILL_AREA_STYLE('',(#204998)); -#204998 = FILL_AREA_STYLE_COLOUR('',#204473); -#204999 = OVER_RIDING_STYLED_ITEM('overriding color',(#205000),#165073, - #204458); -#205000 = PRESENTATION_STYLE_ASSIGNMENT((#205001)); -#205001 = SURFACE_STYLE_USAGE(.BOTH.,#205002); -#205002 = SURFACE_SIDE_STYLE('',(#205003)); -#205003 = SURFACE_STYLE_FILL_AREA(#205004); -#205004 = FILL_AREA_STYLE('',(#205005)); -#205005 = FILL_AREA_STYLE_COLOUR('',#204473); -#205006 = OVER_RIDING_STYLED_ITEM('overriding color',(#205007),#165121, - #204458); -#205007 = PRESENTATION_STYLE_ASSIGNMENT((#205008)); -#205008 = SURFACE_STYLE_USAGE(.BOTH.,#205009); -#205009 = SURFACE_SIDE_STYLE('',(#205010)); -#205010 = SURFACE_STYLE_FILL_AREA(#205011); -#205011 = FILL_AREA_STYLE('',(#205012)); -#205012 = FILL_AREA_STYLE_COLOUR('',#204473); -#205013 = OVER_RIDING_STYLED_ITEM('overriding color',(#205014),#165178, - #204458); -#205014 = PRESENTATION_STYLE_ASSIGNMENT((#205015)); -#205015 = SURFACE_STYLE_USAGE(.BOTH.,#205016); -#205016 = SURFACE_SIDE_STYLE('',(#205017)); -#205017 = SURFACE_STYLE_FILL_AREA(#205018); -#205018 = FILL_AREA_STYLE('',(#205019)); -#205019 = FILL_AREA_STYLE_COLOUR('',#204473); -#205020 = OVER_RIDING_STYLED_ITEM('overriding color',(#205021),#165227, - #204458); -#205021 = PRESENTATION_STYLE_ASSIGNMENT((#205022)); -#205022 = SURFACE_STYLE_USAGE(.BOTH.,#205023); -#205023 = SURFACE_SIDE_STYLE('',(#205024)); -#205024 = SURFACE_STYLE_FILL_AREA(#205025); -#205025 = FILL_AREA_STYLE('',(#205026)); -#205026 = FILL_AREA_STYLE_COLOUR('',#204473); -#205027 = OVER_RIDING_STYLED_ITEM('overriding color',(#205028),#165288, - #204458); -#205028 = PRESENTATION_STYLE_ASSIGNMENT((#205029)); -#205029 = SURFACE_STYLE_USAGE(.BOTH.,#205030); -#205030 = SURFACE_SIDE_STYLE('',(#205031)); -#205031 = SURFACE_STYLE_FILL_AREA(#205032); -#205032 = FILL_AREA_STYLE('',(#205033)); -#205033 = FILL_AREA_STYLE_COLOUR('',#204473); -#205034 = OVER_RIDING_STYLED_ITEM('overriding color',(#205035),#165336, - #204458); -#205035 = PRESENTATION_STYLE_ASSIGNMENT((#205036)); -#205036 = SURFACE_STYLE_USAGE(.BOTH.,#205037); -#205037 = SURFACE_SIDE_STYLE('',(#205038)); -#205038 = SURFACE_STYLE_FILL_AREA(#205039); -#205039 = FILL_AREA_STYLE('',(#205040)); -#205040 = FILL_AREA_STYLE_COLOUR('',#204473); -#205041 = OVER_RIDING_STYLED_ITEM('overriding color',(#205042),#165393, - #204458); -#205042 = PRESENTATION_STYLE_ASSIGNMENT((#205043)); -#205043 = SURFACE_STYLE_USAGE(.BOTH.,#205044); -#205044 = SURFACE_SIDE_STYLE('',(#205045)); -#205045 = SURFACE_STYLE_FILL_AREA(#205046); -#205046 = FILL_AREA_STYLE('',(#205047)); -#205047 = FILL_AREA_STYLE_COLOUR('',#204473); -#205048 = OVER_RIDING_STYLED_ITEM('overriding color',(#205049),#165442, - #204458); -#205049 = PRESENTATION_STYLE_ASSIGNMENT((#205050)); -#205050 = SURFACE_STYLE_USAGE(.BOTH.,#205051); -#205051 = SURFACE_SIDE_STYLE('',(#205052)); -#205052 = SURFACE_STYLE_FILL_AREA(#205053); -#205053 = FILL_AREA_STYLE('',(#205054)); -#205054 = FILL_AREA_STYLE_COLOUR('',#204473); -#205055 = OVER_RIDING_STYLED_ITEM('overriding color',(#205056),#165503, - #204458); -#205056 = PRESENTATION_STYLE_ASSIGNMENT((#205057)); -#205057 = SURFACE_STYLE_USAGE(.BOTH.,#205058); -#205058 = SURFACE_SIDE_STYLE('',(#205059)); -#205059 = SURFACE_STYLE_FILL_AREA(#205060); -#205060 = FILL_AREA_STYLE('',(#205061)); -#205061 = FILL_AREA_STYLE_COLOUR('',#204473); -#205062 = OVER_RIDING_STYLED_ITEM('overriding color',(#205063),#165551, - #204458); -#205063 = PRESENTATION_STYLE_ASSIGNMENT((#205064)); -#205064 = SURFACE_STYLE_USAGE(.BOTH.,#205065); -#205065 = SURFACE_SIDE_STYLE('',(#205066)); -#205066 = SURFACE_STYLE_FILL_AREA(#205067); -#205067 = FILL_AREA_STYLE('',(#205068)); -#205068 = FILL_AREA_STYLE_COLOUR('',#204473); -#205069 = OVER_RIDING_STYLED_ITEM('overriding color',(#205070),#165608, - #204458); -#205070 = PRESENTATION_STYLE_ASSIGNMENT((#205071)); -#205071 = SURFACE_STYLE_USAGE(.BOTH.,#205072); -#205072 = SURFACE_SIDE_STYLE('',(#205073)); -#205073 = SURFACE_STYLE_FILL_AREA(#205074); -#205074 = FILL_AREA_STYLE('',(#205075)); -#205075 = FILL_AREA_STYLE_COLOUR('',#204473); -#205076 = OVER_RIDING_STYLED_ITEM('overriding color',(#205077),#165657, - #204458); -#205077 = PRESENTATION_STYLE_ASSIGNMENT((#205078)); -#205078 = SURFACE_STYLE_USAGE(.BOTH.,#205079); -#205079 = SURFACE_SIDE_STYLE('',(#205080)); -#205080 = SURFACE_STYLE_FILL_AREA(#205081); -#205081 = FILL_AREA_STYLE('',(#205082)); -#205082 = FILL_AREA_STYLE_COLOUR('',#204473); -#205083 = OVER_RIDING_STYLED_ITEM('overriding color',(#205084),#165718, - #204458); -#205084 = PRESENTATION_STYLE_ASSIGNMENT((#205085)); -#205085 = SURFACE_STYLE_USAGE(.BOTH.,#205086); -#205086 = SURFACE_SIDE_STYLE('',(#205087)); -#205087 = SURFACE_STYLE_FILL_AREA(#205088); -#205088 = FILL_AREA_STYLE('',(#205089)); -#205089 = FILL_AREA_STYLE_COLOUR('',#204473); -#205090 = OVER_RIDING_STYLED_ITEM('overriding color',(#205091),#165766, - #204458); -#205091 = PRESENTATION_STYLE_ASSIGNMENT((#205092)); -#205092 = SURFACE_STYLE_USAGE(.BOTH.,#205093); -#205093 = SURFACE_SIDE_STYLE('',(#205094)); -#205094 = SURFACE_STYLE_FILL_AREA(#205095); -#205095 = FILL_AREA_STYLE('',(#205096)); -#205096 = FILL_AREA_STYLE_COLOUR('',#204473); -#205097 = OVER_RIDING_STYLED_ITEM('overriding color',(#205098),#165835, - #204458); -#205098 = PRESENTATION_STYLE_ASSIGNMENT((#205099)); -#205099 = SURFACE_STYLE_USAGE(.BOTH.,#205100); -#205100 = SURFACE_SIDE_STYLE('',(#205101)); -#205101 = SURFACE_STYLE_FILL_AREA(#205102); -#205102 = FILL_AREA_STYLE('',(#205103)); -#205103 = FILL_AREA_STYLE_COLOUR('',#204473); -#205104 = OVER_RIDING_STYLED_ITEM('overriding color',(#205105),#165883, - #204458); -#205105 = PRESENTATION_STYLE_ASSIGNMENT((#205106)); -#205106 = SURFACE_STYLE_USAGE(.BOTH.,#205107); -#205107 = SURFACE_SIDE_STYLE('',(#205108)); -#205108 = SURFACE_STYLE_FILL_AREA(#205109); -#205109 = FILL_AREA_STYLE('',(#205110)); -#205110 = FILL_AREA_STYLE_COLOUR('',#204473); -#205111 = OVER_RIDING_STYLED_ITEM('overriding color',(#205112),#165940, - #204458); -#205112 = PRESENTATION_STYLE_ASSIGNMENT((#205113)); -#205113 = SURFACE_STYLE_USAGE(.BOTH.,#205114); -#205114 = SURFACE_SIDE_STYLE('',(#205115)); -#205115 = SURFACE_STYLE_FILL_AREA(#205116); -#205116 = FILL_AREA_STYLE('',(#205117)); -#205117 = FILL_AREA_STYLE_COLOUR('',#204473); -#205118 = OVER_RIDING_STYLED_ITEM('overriding color',(#205119),#165967, - #204458); -#205119 = PRESENTATION_STYLE_ASSIGNMENT((#205120)); -#205120 = SURFACE_STYLE_USAGE(.BOTH.,#205121); -#205121 = SURFACE_SIDE_STYLE('',(#205122)); -#205122 = SURFACE_STYLE_FILL_AREA(#205123); -#205123 = FILL_AREA_STYLE('',(#205124)); -#205124 = FILL_AREA_STYLE_COLOUR('',#204473); -#205125 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205126),#194987); -#205126 = STYLED_ITEM('color',(#205127),#194657); -#205127 = PRESENTATION_STYLE_ASSIGNMENT((#205128,#205134)); +#204830 = FILL_AREA_STYLE_COLOUR('',#197425); +#204831 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #204832,#204839,#204846,#204853,#204860,#204867,#204874,#204881, + #204888,#204895,#204902,#204909,#204916,#204923,#204930,#204937, + #204944,#204951,#204958,#204965,#204972,#204979,#204986,#204993, + #205000,#205007,#205014,#205021,#205028,#205035,#205042,#205049, + #205056,#205063,#205070,#205077,#205084,#205091,#205098,#205105, + #205112,#205119,#205126,#205133,#205140,#205147,#205154,#205161, + #205168,#205175,#205182,#205189,#205196,#205203,#205210,#205217, + #205224,#205231,#205238,#205245,#205252,#205259,#205266,#205273, + #205280,#205287,#205294,#205301,#205308,#205315,#205322,#205329, + #205336,#205343,#205350,#205357,#205364,#205371,#205378,#205385, + #205392,#205399,#205406,#205413,#205420,#205427,#205434,#205441, + #205448,#205455,#205462,#205469,#205476,#205483,#205490,#205497, + #205504,#205511,#205518,#205525,#205532,#205539,#205546,#205553, + #205560,#205567,#205574,#205581,#205588,#205595,#205602,#205609, + #205616,#205623,#205630,#205637,#205644,#205651,#205658,#205665, + #205672,#205679,#205686,#205693,#205700,#205707,#205714,#205721, + #205728,#205735,#205742,#205749,#205756,#205763,#205770,#205777, + #205784,#205791,#205798,#205805,#205812,#205819,#205826,#205833, + #205840,#205847,#205854,#205861,#205868,#205875),#184736); +#204832 = STYLED_ITEM('color',(#204833),#171029); +#204833 = PRESENTATION_STYLE_ASSIGNMENT((#204834)); +#204834 = SURFACE_STYLE_USAGE(.BOTH.,#204835); +#204835 = SURFACE_SIDE_STYLE('',(#204836)); +#204836 = SURFACE_STYLE_FILL_AREA(#204837); +#204837 = FILL_AREA_STYLE('',(#204838)); +#204838 = FILL_AREA_STYLE_COLOUR('',#197417); +#204839 = OVER_RIDING_STYLED_ITEM('overriding color',(#204840),#171031, + #204832); +#204840 = PRESENTATION_STYLE_ASSIGNMENT((#204841)); +#204841 = SURFACE_STYLE_USAGE(.BOTH.,#204842); +#204842 = SURFACE_SIDE_STYLE('',(#204843)); +#204843 = SURFACE_STYLE_FILL_AREA(#204844); +#204844 = FILL_AREA_STYLE('',(#204845)); +#204845 = FILL_AREA_STYLE_COLOUR('',#197630); +#204846 = OVER_RIDING_STYLED_ITEM('overriding color',(#204847),#171334, + #204832); +#204847 = PRESENTATION_STYLE_ASSIGNMENT((#204848)); +#204848 = SURFACE_STYLE_USAGE(.BOTH.,#204849); +#204849 = SURFACE_SIDE_STYLE('',(#204850)); +#204850 = SURFACE_STYLE_FILL_AREA(#204851); +#204851 = FILL_AREA_STYLE('',(#204852)); +#204852 = FILL_AREA_STYLE_COLOUR('',#197630); +#204853 = OVER_RIDING_STYLED_ITEM('overriding color',(#204854),#171609, + #204832); +#204854 = PRESENTATION_STYLE_ASSIGNMENT((#204855)); +#204855 = SURFACE_STYLE_USAGE(.BOTH.,#204856); +#204856 = SURFACE_SIDE_STYLE('',(#204857)); +#204857 = SURFACE_STYLE_FILL_AREA(#204858); +#204858 = FILL_AREA_STYLE('',(#204859)); +#204859 = FILL_AREA_STYLE_COLOUR('',#197630); +#204860 = OVER_RIDING_STYLED_ITEM('overriding color',(#204861),#171884, + #204832); +#204861 = PRESENTATION_STYLE_ASSIGNMENT((#204862)); +#204862 = SURFACE_STYLE_USAGE(.BOTH.,#204863); +#204863 = SURFACE_SIDE_STYLE('',(#204864)); +#204864 = SURFACE_STYLE_FILL_AREA(#204865); +#204865 = FILL_AREA_STYLE('',(#204866)); +#204866 = FILL_AREA_STYLE_COLOUR('',#197630); +#204867 = OVER_RIDING_STYLED_ITEM('overriding color',(#204868),#172159, + #204832); +#204868 = PRESENTATION_STYLE_ASSIGNMENT((#204869)); +#204869 = SURFACE_STYLE_USAGE(.BOTH.,#204870); +#204870 = SURFACE_SIDE_STYLE('',(#204871)); +#204871 = SURFACE_STYLE_FILL_AREA(#204872); +#204872 = FILL_AREA_STYLE('',(#204873)); +#204873 = FILL_AREA_STYLE_COLOUR('',#197630); +#204874 = OVER_RIDING_STYLED_ITEM('overriding color',(#204875),#172439, + #204832); +#204875 = PRESENTATION_STYLE_ASSIGNMENT((#204876)); +#204876 = SURFACE_STYLE_USAGE(.BOTH.,#204877); +#204877 = SURFACE_SIDE_STYLE('',(#204878)); +#204878 = SURFACE_STYLE_FILL_AREA(#204879); +#204879 = FILL_AREA_STYLE('',(#204880)); +#204880 = FILL_AREA_STYLE_COLOUR('',#197630); +#204881 = OVER_RIDING_STYLED_ITEM('overriding color',(#204882),#172714, + #204832); +#204882 = PRESENTATION_STYLE_ASSIGNMENT((#204883)); +#204883 = SURFACE_STYLE_USAGE(.BOTH.,#204884); +#204884 = SURFACE_SIDE_STYLE('',(#204885)); +#204885 = SURFACE_STYLE_FILL_AREA(#204886); +#204886 = FILL_AREA_STYLE('',(#204887)); +#204887 = FILL_AREA_STYLE_COLOUR('',#197630); +#204888 = OVER_RIDING_STYLED_ITEM('overriding color',(#204889),#172989, + #204832); +#204889 = PRESENTATION_STYLE_ASSIGNMENT((#204890)); +#204890 = SURFACE_STYLE_USAGE(.BOTH.,#204891); +#204891 = SURFACE_SIDE_STYLE('',(#204892)); +#204892 = SURFACE_STYLE_FILL_AREA(#204893); +#204893 = FILL_AREA_STYLE('',(#204894)); +#204894 = FILL_AREA_STYLE_COLOUR('',#197630); +#204895 = OVER_RIDING_STYLED_ITEM('overriding color',(#204896),#173264, + #204832); +#204896 = PRESENTATION_STYLE_ASSIGNMENT((#204897)); +#204897 = SURFACE_STYLE_USAGE(.BOTH.,#204898); +#204898 = SURFACE_SIDE_STYLE('',(#204899)); +#204899 = SURFACE_STYLE_FILL_AREA(#204900); +#204900 = FILL_AREA_STYLE('',(#204901)); +#204901 = FILL_AREA_STYLE_COLOUR('',#197630); +#204902 = OVER_RIDING_STYLED_ITEM('overriding color',(#204903),#173416, + #204832); +#204903 = PRESENTATION_STYLE_ASSIGNMENT((#204904)); +#204904 = SURFACE_STYLE_USAGE(.BOTH.,#204905); +#204905 = SURFACE_SIDE_STYLE('',(#204906)); +#204906 = SURFACE_STYLE_FILL_AREA(#204907); +#204907 = FILL_AREA_STYLE('',(#204908)); +#204908 = FILL_AREA_STYLE_COLOUR('',#197630); +#204909 = OVER_RIDING_STYLED_ITEM('overriding color',(#204910),#173990, + #204832); +#204910 = PRESENTATION_STYLE_ASSIGNMENT((#204911)); +#204911 = SURFACE_STYLE_USAGE(.BOTH.,#204912); +#204912 = SURFACE_SIDE_STYLE('',(#204913)); +#204913 = SURFACE_STYLE_FILL_AREA(#204914); +#204914 = FILL_AREA_STYLE('',(#204915)); +#204915 = FILL_AREA_STYLE_COLOUR('',#197630); +#204916 = OVER_RIDING_STYLED_ITEM('overriding color',(#204917),#174159, + #204832); +#204917 = PRESENTATION_STYLE_ASSIGNMENT((#204918)); +#204918 = SURFACE_STYLE_USAGE(.BOTH.,#204919); +#204919 = SURFACE_SIDE_STYLE('',(#204920)); +#204920 = SURFACE_STYLE_FILL_AREA(#204921); +#204921 = FILL_AREA_STYLE('',(#204922)); +#204922 = FILL_AREA_STYLE_COLOUR('',#197630); +#204923 = OVER_RIDING_STYLED_ITEM('overriding color',(#204924),#174509, + #204832); +#204924 = PRESENTATION_STYLE_ASSIGNMENT((#204925)); +#204925 = SURFACE_STYLE_USAGE(.BOTH.,#204926); +#204926 = SURFACE_SIDE_STYLE('',(#204927)); +#204927 = SURFACE_STYLE_FILL_AREA(#204928); +#204928 = FILL_AREA_STYLE('',(#204929)); +#204929 = FILL_AREA_STYLE_COLOUR('',#197630); +#204930 = OVER_RIDING_STYLED_ITEM('overriding color',(#204931),#174678, + #204832); +#204931 = PRESENTATION_STYLE_ASSIGNMENT((#204932)); +#204932 = SURFACE_STYLE_USAGE(.BOTH.,#204933); +#204933 = SURFACE_SIDE_STYLE('',(#204934)); +#204934 = SURFACE_STYLE_FILL_AREA(#204935); +#204935 = FILL_AREA_STYLE('',(#204936)); +#204936 = FILL_AREA_STYLE_COLOUR('',#197630); +#204937 = OVER_RIDING_STYLED_ITEM('overriding color',(#204938),#174898, + #204832); +#204938 = PRESENTATION_STYLE_ASSIGNMENT((#204939)); +#204939 = SURFACE_STYLE_USAGE(.BOTH.,#204940); +#204940 = SURFACE_SIDE_STYLE('',(#204941)); +#204941 = SURFACE_STYLE_FILL_AREA(#204942); +#204942 = FILL_AREA_STYLE('',(#204943)); +#204943 = FILL_AREA_STYLE_COLOUR('',#197630); +#204944 = OVER_RIDING_STYLED_ITEM('overriding color',(#204945),#175219, + #204832); +#204945 = PRESENTATION_STYLE_ASSIGNMENT((#204946)); +#204946 = SURFACE_STYLE_USAGE(.BOTH.,#204947); +#204947 = SURFACE_SIDE_STYLE('',(#204948)); +#204948 = SURFACE_STYLE_FILL_AREA(#204949); +#204949 = FILL_AREA_STYLE('',(#204950)); +#204950 = FILL_AREA_STYLE_COLOUR('',#197630); +#204951 = OVER_RIDING_STYLED_ITEM('overriding color',(#204952),#175354, + #204832); +#204952 = PRESENTATION_STYLE_ASSIGNMENT((#204953)); +#204953 = SURFACE_STYLE_USAGE(.BOTH.,#204954); +#204954 = SURFACE_SIDE_STYLE('',(#204955)); +#204955 = SURFACE_STYLE_FILL_AREA(#204956); +#204956 = FILL_AREA_STYLE('',(#204957)); +#204957 = FILL_AREA_STYLE_COLOUR('',#197630); +#204958 = OVER_RIDING_STYLED_ITEM('overriding color',(#204959),#175489, + #204832); +#204959 = PRESENTATION_STYLE_ASSIGNMENT((#204960)); +#204960 = SURFACE_STYLE_USAGE(.BOTH.,#204961); +#204961 = SURFACE_SIDE_STYLE('',(#204962)); +#204962 = SURFACE_STYLE_FILL_AREA(#204963); +#204963 = FILL_AREA_STYLE('',(#204964)); +#204964 = FILL_AREA_STYLE_COLOUR('',#197630); +#204965 = OVER_RIDING_STYLED_ITEM('overriding color',(#204966),#175933, + #204832); +#204966 = PRESENTATION_STYLE_ASSIGNMENT((#204967)); +#204967 = SURFACE_STYLE_USAGE(.BOTH.,#204968); +#204968 = SURFACE_SIDE_STYLE('',(#204969)); +#204969 = SURFACE_STYLE_FILL_AREA(#204970); +#204970 = FILL_AREA_STYLE('',(#204971)); +#204971 = FILL_AREA_STYLE_COLOUR('',#197630); +#204972 = OVER_RIDING_STYLED_ITEM('overriding color',(#204973),#176301, + #204832); +#204973 = PRESENTATION_STYLE_ASSIGNMENT((#204974)); +#204974 = SURFACE_STYLE_USAGE(.BOTH.,#204975); +#204975 = SURFACE_SIDE_STYLE('',(#204976)); +#204976 = SURFACE_STYLE_FILL_AREA(#204977); +#204977 = FILL_AREA_STYLE('',(#204978)); +#204978 = FILL_AREA_STYLE_COLOUR('',#197425); +#204979 = OVER_RIDING_STYLED_ITEM('overriding color',(#204980),#176376, + #204832); +#204980 = PRESENTATION_STYLE_ASSIGNMENT((#204981)); +#204981 = SURFACE_STYLE_USAGE(.BOTH.,#204982); +#204982 = SURFACE_SIDE_STYLE('',(#204983)); +#204983 = SURFACE_STYLE_FILL_AREA(#204984); +#204984 = FILL_AREA_STYLE('',(#204985)); +#204985 = FILL_AREA_STYLE_COLOUR('',#197425); +#204986 = OVER_RIDING_STYLED_ITEM('overriding color',(#204987),#176451, + #204832); +#204987 = PRESENTATION_STYLE_ASSIGNMENT((#204988)); +#204988 = SURFACE_STYLE_USAGE(.BOTH.,#204989); +#204989 = SURFACE_SIDE_STYLE('',(#204990)); +#204990 = SURFACE_STYLE_FILL_AREA(#204991); +#204991 = FILL_AREA_STYLE('',(#204992)); +#204992 = FILL_AREA_STYLE_COLOUR('',#197425); +#204993 = OVER_RIDING_STYLED_ITEM('overriding color',(#204994),#176705, + #204832); +#204994 = PRESENTATION_STYLE_ASSIGNMENT((#204995)); +#204995 = SURFACE_STYLE_USAGE(.BOTH.,#204996); +#204996 = SURFACE_SIDE_STYLE('',(#204997)); +#204997 = SURFACE_STYLE_FILL_AREA(#204998); +#204998 = FILL_AREA_STYLE('',(#204999)); +#204999 = FILL_AREA_STYLE_COLOUR('',#197425); +#205000 = OVER_RIDING_STYLED_ITEM('overriding color',(#205001),#176924, + #204832); +#205001 = PRESENTATION_STYLE_ASSIGNMENT((#205002)); +#205002 = SURFACE_STYLE_USAGE(.BOTH.,#205003); +#205003 = SURFACE_SIDE_STYLE('',(#205004)); +#205004 = SURFACE_STYLE_FILL_AREA(#205005); +#205005 = FILL_AREA_STYLE('',(#205006)); +#205006 = FILL_AREA_STYLE_COLOUR('',#197425); +#205007 = OVER_RIDING_STYLED_ITEM('overriding color',(#205008),#176950, + #204832); +#205008 = PRESENTATION_STYLE_ASSIGNMENT((#205009)); +#205009 = SURFACE_STYLE_USAGE(.BOTH.,#205010); +#205010 = SURFACE_SIDE_STYLE('',(#205011)); +#205011 = SURFACE_STYLE_FILL_AREA(#205012); +#205012 = FILL_AREA_STYLE('',(#205013)); +#205013 = FILL_AREA_STYLE_COLOUR('',#197425); +#205014 = OVER_RIDING_STYLED_ITEM('overriding color',(#205015),#176976, + #204832); +#205015 = PRESENTATION_STYLE_ASSIGNMENT((#205016)); +#205016 = SURFACE_STYLE_USAGE(.BOTH.,#205017); +#205017 = SURFACE_SIDE_STYLE('',(#205018)); +#205018 = SURFACE_STYLE_FILL_AREA(#205019); +#205019 = FILL_AREA_STYLE('',(#205020)); +#205020 = FILL_AREA_STYLE_COLOUR('',#197425); +#205021 = OVER_RIDING_STYLED_ITEM('overriding color',(#205022),#177025, + #204832); +#205022 = PRESENTATION_STYLE_ASSIGNMENT((#205023)); +#205023 = SURFACE_STYLE_USAGE(.BOTH.,#205024); +#205024 = SURFACE_SIDE_STYLE('',(#205025)); +#205025 = SURFACE_STYLE_FILL_AREA(#205026); +#205026 = FILL_AREA_STYLE('',(#205027)); +#205027 = FILL_AREA_STYLE_COLOUR('',#197425); +#205028 = OVER_RIDING_STYLED_ITEM('overriding color',(#205029),#177052, + #204832); +#205029 = PRESENTATION_STYLE_ASSIGNMENT((#205030)); +#205030 = SURFACE_STYLE_USAGE(.BOTH.,#205031); +#205031 = SURFACE_SIDE_STYLE('',(#205032)); +#205032 = SURFACE_STYLE_FILL_AREA(#205033); +#205033 = FILL_AREA_STYLE('',(#205034)); +#205034 = FILL_AREA_STYLE_COLOUR('',#197425); +#205035 = OVER_RIDING_STYLED_ITEM('overriding color',(#205036),#177079, + #204832); +#205036 = PRESENTATION_STYLE_ASSIGNMENT((#205037)); +#205037 = SURFACE_STYLE_USAGE(.BOTH.,#205038); +#205038 = SURFACE_SIDE_STYLE('',(#205039)); +#205039 = SURFACE_STYLE_FILL_AREA(#205040); +#205040 = FILL_AREA_STYLE('',(#205041)); +#205041 = FILL_AREA_STYLE_COLOUR('',#197425); +#205042 = OVER_RIDING_STYLED_ITEM('overriding color',(#205043),#177128, + #204832); +#205043 = PRESENTATION_STYLE_ASSIGNMENT((#205044)); +#205044 = SURFACE_STYLE_USAGE(.BOTH.,#205045); +#205045 = SURFACE_SIDE_STYLE('',(#205046)); +#205046 = SURFACE_STYLE_FILL_AREA(#205047); +#205047 = FILL_AREA_STYLE('',(#205048)); +#205048 = FILL_AREA_STYLE_COLOUR('',#197425); +#205049 = OVER_RIDING_STYLED_ITEM('overriding color',(#205050),#177154, + #204832); +#205050 = PRESENTATION_STYLE_ASSIGNMENT((#205051)); +#205051 = SURFACE_STYLE_USAGE(.BOTH.,#205052); +#205052 = SURFACE_SIDE_STYLE('',(#205053)); +#205053 = SURFACE_STYLE_FILL_AREA(#205054); +#205054 = FILL_AREA_STYLE('',(#205055)); +#205055 = FILL_AREA_STYLE_COLOUR('',#197425); +#205056 = OVER_RIDING_STYLED_ITEM('overriding color',(#205057),#177180, + #204832); +#205057 = PRESENTATION_STYLE_ASSIGNMENT((#205058)); +#205058 = SURFACE_STYLE_USAGE(.BOTH.,#205059); +#205059 = SURFACE_SIDE_STYLE('',(#205060)); +#205060 = SURFACE_STYLE_FILL_AREA(#205061); +#205061 = FILL_AREA_STYLE('',(#205062)); +#205062 = FILL_AREA_STYLE_COLOUR('',#197425); +#205063 = OVER_RIDING_STYLED_ITEM('overriding color',(#205064),#177187, + #204832); +#205064 = PRESENTATION_STYLE_ASSIGNMENT((#205065)); +#205065 = SURFACE_STYLE_USAGE(.BOTH.,#205066); +#205066 = SURFACE_SIDE_STYLE('',(#205067)); +#205067 = SURFACE_STYLE_FILL_AREA(#205068); +#205068 = FILL_AREA_STYLE('',(#205069)); +#205069 = FILL_AREA_STYLE_COLOUR('',#197425); +#205070 = OVER_RIDING_STYLED_ITEM('overriding color',(#205071),#177262, + #204832); +#205071 = PRESENTATION_STYLE_ASSIGNMENT((#205072)); +#205072 = SURFACE_STYLE_USAGE(.BOTH.,#205073); +#205073 = SURFACE_SIDE_STYLE('',(#205074)); +#205074 = SURFACE_STYLE_FILL_AREA(#205075); +#205075 = FILL_AREA_STYLE('',(#205076)); +#205076 = FILL_AREA_STYLE_COLOUR('',#197425); +#205077 = OVER_RIDING_STYLED_ITEM('overriding color',(#205078),#177337, + #204832); +#205078 = PRESENTATION_STYLE_ASSIGNMENT((#205079)); +#205079 = SURFACE_STYLE_USAGE(.BOTH.,#205080); +#205080 = SURFACE_SIDE_STYLE('',(#205081)); +#205081 = SURFACE_STYLE_FILL_AREA(#205082); +#205082 = FILL_AREA_STYLE('',(#205083)); +#205083 = FILL_AREA_STYLE_COLOUR('',#197425); +#205084 = OVER_RIDING_STYLED_ITEM('overriding color',(#205085),#177591, + #204832); +#205085 = PRESENTATION_STYLE_ASSIGNMENT((#205086)); +#205086 = SURFACE_STYLE_USAGE(.BOTH.,#205087); +#205087 = SURFACE_SIDE_STYLE('',(#205088)); +#205088 = SURFACE_STYLE_FILL_AREA(#205089); +#205089 = FILL_AREA_STYLE('',(#205090)); +#205090 = FILL_AREA_STYLE_COLOUR('',#197425); +#205091 = OVER_RIDING_STYLED_ITEM('overriding color',(#205092),#177810, + #204832); +#205092 = PRESENTATION_STYLE_ASSIGNMENT((#205093)); +#205093 = SURFACE_STYLE_USAGE(.BOTH.,#205094); +#205094 = SURFACE_SIDE_STYLE('',(#205095)); +#205095 = SURFACE_STYLE_FILL_AREA(#205096); +#205096 = FILL_AREA_STYLE('',(#205097)); +#205097 = FILL_AREA_STYLE_COLOUR('',#197425); +#205098 = OVER_RIDING_STYLED_ITEM('overriding color',(#205099),#177836, + #204832); +#205099 = PRESENTATION_STYLE_ASSIGNMENT((#205100)); +#205100 = SURFACE_STYLE_USAGE(.BOTH.,#205101); +#205101 = SURFACE_SIDE_STYLE('',(#205102)); +#205102 = SURFACE_STYLE_FILL_AREA(#205103); +#205103 = FILL_AREA_STYLE('',(#205104)); +#205104 = FILL_AREA_STYLE_COLOUR('',#197425); +#205105 = OVER_RIDING_STYLED_ITEM('overriding color',(#205106),#177862, + #204832); +#205106 = PRESENTATION_STYLE_ASSIGNMENT((#205107)); +#205107 = SURFACE_STYLE_USAGE(.BOTH.,#205108); +#205108 = SURFACE_SIDE_STYLE('',(#205109)); +#205109 = SURFACE_STYLE_FILL_AREA(#205110); +#205110 = FILL_AREA_STYLE('',(#205111)); +#205111 = FILL_AREA_STYLE_COLOUR('',#197425); +#205112 = OVER_RIDING_STYLED_ITEM('overriding color',(#205113),#177911, + #204832); +#205113 = PRESENTATION_STYLE_ASSIGNMENT((#205114)); +#205114 = SURFACE_STYLE_USAGE(.BOTH.,#205115); +#205115 = SURFACE_SIDE_STYLE('',(#205116)); +#205116 = SURFACE_STYLE_FILL_AREA(#205117); +#205117 = FILL_AREA_STYLE('',(#205118)); +#205118 = FILL_AREA_STYLE_COLOUR('',#197425); +#205119 = OVER_RIDING_STYLED_ITEM('overriding color',(#205120),#177938, + #204832); +#205120 = PRESENTATION_STYLE_ASSIGNMENT((#205121)); +#205121 = SURFACE_STYLE_USAGE(.BOTH.,#205122); +#205122 = SURFACE_SIDE_STYLE('',(#205123)); +#205123 = SURFACE_STYLE_FILL_AREA(#205124); +#205124 = FILL_AREA_STYLE('',(#205125)); +#205125 = FILL_AREA_STYLE_COLOUR('',#197425); +#205126 = OVER_RIDING_STYLED_ITEM('overriding color',(#205127),#177965, + #204832); +#205127 = PRESENTATION_STYLE_ASSIGNMENT((#205128)); #205128 = SURFACE_STYLE_USAGE(.BOTH.,#205129); #205129 = SURFACE_SIDE_STYLE('',(#205130)); #205130 = SURFACE_STYLE_FILL_AREA(#205131); #205131 = FILL_AREA_STYLE('',(#205132)); -#205132 = FILL_AREA_STYLE_COLOUR('',#205133); -#205133 = COLOUR_RGB('',0.713725507259,0.603921592236,0.415686279535); -#205134 = CURVE_STYLE('',#205135,POSITIVE_LENGTH_MEASURE(0.1),#205133); -#205135 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#205136 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205137,#205145,#205153,#205160,#205167,#205174,#205181,#205188, - #205195,#205202,#205209),#17215); -#205137 = STYLED_ITEM('color',(#205138),#16381); -#205138 = PRESENTATION_STYLE_ASSIGNMENT((#205139)); -#205139 = SURFACE_STYLE_USAGE(.BOTH.,#205140); -#205140 = SURFACE_SIDE_STYLE('',(#205141)); -#205141 = SURFACE_STYLE_FILL_AREA(#205142); -#205142 = FILL_AREA_STYLE('',(#205143)); -#205143 = FILL_AREA_STYLE_COLOUR('',#205144); -#205144 = COLOUR_RGB('',0.188235297799,0.188235297799,0.188235297799); -#205145 = OVER_RIDING_STYLED_ITEM('overriding color',(#205146),#16383, - #205137); -#205146 = PRESENTATION_STYLE_ASSIGNMENT((#205147)); -#205147 = SURFACE_STYLE_USAGE(.BOTH.,#205148); -#205148 = SURFACE_SIDE_STYLE('',(#205149)); -#205149 = SURFACE_STYLE_FILL_AREA(#205150); -#205150 = FILL_AREA_STYLE('',(#205151)); -#205151 = FILL_AREA_STYLE_COLOUR('',#205152); -#205152 = COLOUR_RGB('',0.192156866193,0.192156866193,0.192156866193); -#205153 = OVER_RIDING_STYLED_ITEM('overriding color',(#205154),#16677, - #205137); -#205154 = PRESENTATION_STYLE_ASSIGNMENT((#205155)); -#205155 = SURFACE_STYLE_USAGE(.BOTH.,#205156); -#205156 = SURFACE_SIDE_STYLE('',(#205157)); -#205157 = SURFACE_STYLE_FILL_AREA(#205158); -#205158 = FILL_AREA_STYLE('',(#205159)); -#205159 = FILL_AREA_STYLE_COLOUR('',#205152); -#205160 = OVER_RIDING_STYLED_ITEM('overriding color',(#205161),#16797, - #205137); -#205161 = PRESENTATION_STYLE_ASSIGNMENT((#205162)); -#205162 = SURFACE_STYLE_USAGE(.BOTH.,#205163); -#205163 = SURFACE_SIDE_STYLE('',(#205164)); -#205164 = SURFACE_STYLE_FILL_AREA(#205165); -#205165 = FILL_AREA_STYLE('',(#205166)); -#205166 = FILL_AREA_STYLE_COLOUR('',#205152); -#205167 = OVER_RIDING_STYLED_ITEM('overriding color',(#205168),#16845, - #205137); -#205168 = PRESENTATION_STYLE_ASSIGNMENT((#205169)); -#205169 = SURFACE_STYLE_USAGE(.BOTH.,#205170); -#205170 = SURFACE_SIDE_STYLE('',(#205171)); -#205171 = SURFACE_STYLE_FILL_AREA(#205172); -#205172 = FILL_AREA_STYLE('',(#205173)); -#205173 = FILL_AREA_STYLE_COLOUR('',#205152); -#205174 = OVER_RIDING_STYLED_ITEM('overriding color',(#205175),#16893, - #205137); -#205175 = PRESENTATION_STYLE_ASSIGNMENT((#205176)); -#205176 = SURFACE_STYLE_USAGE(.BOTH.,#205177); -#205177 = SURFACE_SIDE_STYLE('',(#205178)); -#205178 = SURFACE_STYLE_FILL_AREA(#205179); -#205179 = FILL_AREA_STYLE('',(#205180)); -#205180 = FILL_AREA_STYLE_COLOUR('',#205152); -#205181 = OVER_RIDING_STYLED_ITEM('overriding color',(#205182),#16941, - #205137); -#205182 = PRESENTATION_STYLE_ASSIGNMENT((#205183)); -#205183 = SURFACE_STYLE_USAGE(.BOTH.,#205184); -#205184 = SURFACE_SIDE_STYLE('',(#205185)); -#205185 = SURFACE_STYLE_FILL_AREA(#205186); -#205186 = FILL_AREA_STYLE('',(#205187)); -#205187 = FILL_AREA_STYLE_COLOUR('',#205152); -#205188 = OVER_RIDING_STYLED_ITEM('overriding color',(#205189),#17035, - #205137); -#205189 = PRESENTATION_STYLE_ASSIGNMENT((#205190)); -#205190 = SURFACE_STYLE_USAGE(.BOTH.,#205191); -#205191 = SURFACE_SIDE_STYLE('',(#205192)); -#205192 = SURFACE_STYLE_FILL_AREA(#205193); -#205193 = FILL_AREA_STYLE('',(#205194)); -#205194 = FILL_AREA_STYLE_COLOUR('',#205152); -#205195 = OVER_RIDING_STYLED_ITEM('overriding color',(#205196),#17083, - #205137); -#205196 = PRESENTATION_STYLE_ASSIGNMENT((#205197)); -#205197 = SURFACE_STYLE_USAGE(.BOTH.,#205198); -#205198 = SURFACE_SIDE_STYLE('',(#205199)); -#205199 = SURFACE_STYLE_FILL_AREA(#205200); -#205200 = FILL_AREA_STYLE('',(#205201)); -#205201 = FILL_AREA_STYLE_COLOUR('',#205152); -#205202 = OVER_RIDING_STYLED_ITEM('overriding color',(#205203),#17177, - #205137); -#205203 = PRESENTATION_STYLE_ASSIGNMENT((#205204)); -#205204 = SURFACE_STYLE_USAGE(.BOTH.,#205205); -#205205 = SURFACE_SIDE_STYLE('',(#205206)); -#205206 = SURFACE_STYLE_FILL_AREA(#205207); -#205207 = FILL_AREA_STYLE('',(#205208)); -#205208 = FILL_AREA_STYLE_COLOUR('',#205152); -#205209 = OVER_RIDING_STYLED_ITEM('overriding color',(#205210),#17204, - #205137); -#205210 = PRESENTATION_STYLE_ASSIGNMENT((#205211)); -#205211 = SURFACE_STYLE_USAGE(.BOTH.,#205212); -#205212 = SURFACE_SIDE_STYLE('',(#205213)); -#205213 = SURFACE_STYLE_FILL_AREA(#205214); -#205214 = FILL_AREA_STYLE('',(#205215)); -#205215 = FILL_AREA_STYLE_COLOUR('',#205152); -#205216 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205217,#205224,#205232,#205239,#205246,#205253,#205260,#205267, - #205274,#205281,#205288,#205295,#205302,#205309,#205316,#205323, - #205330,#205337,#205344,#205351,#205358,#205365,#205372,#205379, - #205386,#205393,#205400,#205407,#205414,#205421,#205428,#205435, - #205442,#205449,#205456,#205463,#205470,#205477,#205484,#205491, - #205498,#205505,#205512,#205519,#205526,#205533,#205540,#205547, - #205554,#205561,#205568,#205575,#205582,#205589,#205596),#11016); -#205217 = STYLED_ITEM('color',(#205218),#7525); +#205132 = FILL_AREA_STYLE_COLOUR('',#197425); +#205133 = OVER_RIDING_STYLED_ITEM('overriding color',(#205134),#178014, + #204832); +#205134 = PRESENTATION_STYLE_ASSIGNMENT((#205135)); +#205135 = SURFACE_STYLE_USAGE(.BOTH.,#205136); +#205136 = SURFACE_SIDE_STYLE('',(#205137)); +#205137 = SURFACE_STYLE_FILL_AREA(#205138); +#205138 = FILL_AREA_STYLE('',(#205139)); +#205139 = FILL_AREA_STYLE_COLOUR('',#197425); +#205140 = OVER_RIDING_STYLED_ITEM('overriding color',(#205141),#178040, + #204832); +#205141 = PRESENTATION_STYLE_ASSIGNMENT((#205142)); +#205142 = SURFACE_STYLE_USAGE(.BOTH.,#205143); +#205143 = SURFACE_SIDE_STYLE('',(#205144)); +#205144 = SURFACE_STYLE_FILL_AREA(#205145); +#205145 = FILL_AREA_STYLE('',(#205146)); +#205146 = FILL_AREA_STYLE_COLOUR('',#197425); +#205147 = OVER_RIDING_STYLED_ITEM('overriding color',(#205148),#178066, + #204832); +#205148 = PRESENTATION_STYLE_ASSIGNMENT((#205149)); +#205149 = SURFACE_STYLE_USAGE(.BOTH.,#205150); +#205150 = SURFACE_SIDE_STYLE('',(#205151)); +#205151 = SURFACE_STYLE_FILL_AREA(#205152); +#205152 = FILL_AREA_STYLE('',(#205153)); +#205153 = FILL_AREA_STYLE_COLOUR('',#197425); +#205154 = OVER_RIDING_STYLED_ITEM('overriding color',(#205155),#178073, + #204832); +#205155 = PRESENTATION_STYLE_ASSIGNMENT((#205156)); +#205156 = SURFACE_STYLE_USAGE(.BOTH.,#205157); +#205157 = SURFACE_SIDE_STYLE('',(#205158)); +#205158 = SURFACE_STYLE_FILL_AREA(#205159); +#205159 = FILL_AREA_STYLE('',(#205160)); +#205160 = FILL_AREA_STYLE_COLOUR('',#197630); +#205161 = OVER_RIDING_STYLED_ITEM('overriding color',(#205162),#178211, + #204832); +#205162 = PRESENTATION_STYLE_ASSIGNMENT((#205163)); +#205163 = SURFACE_STYLE_USAGE(.BOTH.,#205164); +#205164 = SURFACE_SIDE_STYLE('',(#205165)); +#205165 = SURFACE_STYLE_FILL_AREA(#205166); +#205166 = FILL_AREA_STYLE('',(#205167)); +#205167 = FILL_AREA_STYLE_COLOUR('',#197630); +#205168 = OVER_RIDING_STYLED_ITEM('overriding color',(#205169),#178284, + #204832); +#205169 = PRESENTATION_STYLE_ASSIGNMENT((#205170)); +#205170 = SURFACE_STYLE_USAGE(.BOTH.,#205171); +#205171 = SURFACE_SIDE_STYLE('',(#205172)); +#205172 = SURFACE_STYLE_FILL_AREA(#205173); +#205173 = FILL_AREA_STYLE('',(#205174)); +#205174 = FILL_AREA_STYLE_COLOUR('',#197630); +#205175 = OVER_RIDING_STYLED_ITEM('overriding color',(#205176),#178422, + #204832); +#205176 = PRESENTATION_STYLE_ASSIGNMENT((#205177)); +#205177 = SURFACE_STYLE_USAGE(.BOTH.,#205178); +#205178 = SURFACE_SIDE_STYLE('',(#205179)); +#205179 = SURFACE_STYLE_FILL_AREA(#205180); +#205180 = FILL_AREA_STYLE('',(#205181)); +#205181 = FILL_AREA_STYLE_COLOUR('',#197630); +#205182 = OVER_RIDING_STYLED_ITEM('overriding color',(#205183),#178495, + #204832); +#205183 = PRESENTATION_STYLE_ASSIGNMENT((#205184)); +#205184 = SURFACE_STYLE_USAGE(.BOTH.,#205185); +#205185 = SURFACE_SIDE_STYLE('',(#205186)); +#205186 = SURFACE_STYLE_FILL_AREA(#205187); +#205187 = FILL_AREA_STYLE('',(#205188)); +#205188 = FILL_AREA_STYLE_COLOUR('',#197630); +#205189 = OVER_RIDING_STYLED_ITEM('overriding color',(#205190),#178633, + #204832); +#205190 = PRESENTATION_STYLE_ASSIGNMENT((#205191)); +#205191 = SURFACE_STYLE_USAGE(.BOTH.,#205192); +#205192 = SURFACE_SIDE_STYLE('',(#205193)); +#205193 = SURFACE_STYLE_FILL_AREA(#205194); +#205194 = FILL_AREA_STYLE('',(#205195)); +#205195 = FILL_AREA_STYLE_COLOUR('',#197630); +#205196 = OVER_RIDING_STYLED_ITEM('overriding color',(#205197),#178706, + #204832); +#205197 = PRESENTATION_STYLE_ASSIGNMENT((#205198)); +#205198 = SURFACE_STYLE_USAGE(.BOTH.,#205199); +#205199 = SURFACE_SIDE_STYLE('',(#205200)); +#205200 = SURFACE_STYLE_FILL_AREA(#205201); +#205201 = FILL_AREA_STYLE('',(#205202)); +#205202 = FILL_AREA_STYLE_COLOUR('',#197630); +#205203 = OVER_RIDING_STYLED_ITEM('overriding color',(#205204),#178844, + #204832); +#205204 = PRESENTATION_STYLE_ASSIGNMENT((#205205)); +#205205 = SURFACE_STYLE_USAGE(.BOTH.,#205206); +#205206 = SURFACE_SIDE_STYLE('',(#205207)); +#205207 = SURFACE_STYLE_FILL_AREA(#205208); +#205208 = FILL_AREA_STYLE('',(#205209)); +#205209 = FILL_AREA_STYLE_COLOUR('',#197630); +#205210 = OVER_RIDING_STYLED_ITEM('overriding color',(#205211),#178917, + #204832); +#205211 = PRESENTATION_STYLE_ASSIGNMENT((#205212)); +#205212 = SURFACE_STYLE_USAGE(.BOTH.,#205213); +#205213 = SURFACE_SIDE_STYLE('',(#205214)); +#205214 = SURFACE_STYLE_FILL_AREA(#205215); +#205215 = FILL_AREA_STYLE('',(#205216)); +#205216 = FILL_AREA_STYLE_COLOUR('',#197630); +#205217 = OVER_RIDING_STYLED_ITEM('overriding color',(#205218),#178967, + #204832); #205218 = PRESENTATION_STYLE_ASSIGNMENT((#205219)); #205219 = SURFACE_STYLE_USAGE(.BOTH.,#205220); #205220 = SURFACE_SIDE_STYLE('',(#205221)); #205221 = SURFACE_STYLE_FILL_AREA(#205222); #205222 = FILL_AREA_STYLE('',(#205223)); -#205223 = FILL_AREA_STYLE_COLOUR('',#201773); -#205224 = OVER_RIDING_STYLED_ITEM('overriding color',(#205225),#7527, - #205217); +#205223 = FILL_AREA_STYLE_COLOUR('',#198360); +#205224 = OVER_RIDING_STYLED_ITEM('overriding color',(#205225),#178972, + #204832); #205225 = PRESENTATION_STYLE_ASSIGNMENT((#205226)); #205226 = SURFACE_STYLE_USAGE(.BOTH.,#205227); #205227 = SURFACE_SIDE_STYLE('',(#205228)); #205228 = SURFACE_STYLE_FILL_AREA(#205229); #205229 = FILL_AREA_STYLE('',(#205230)); -#205230 = FILL_AREA_STYLE_COLOUR('',#205231); -#205231 = COLOUR_RGB('',1.,1.,0.752941191196); -#205232 = OVER_RIDING_STYLED_ITEM('overriding color',(#205233),#7759, - #205217); -#205233 = PRESENTATION_STYLE_ASSIGNMENT((#205234)); -#205234 = SURFACE_STYLE_USAGE(.BOTH.,#205235); -#205235 = SURFACE_SIDE_STYLE('',(#205236)); -#205236 = SURFACE_STYLE_FILL_AREA(#205237); -#205237 = FILL_AREA_STYLE('',(#205238)); -#205238 = FILL_AREA_STYLE_COLOUR('',#205231); -#205239 = OVER_RIDING_STYLED_ITEM('overriding color',(#205240),#7837, - #205217); -#205240 = PRESENTATION_STYLE_ASSIGNMENT((#205241)); -#205241 = SURFACE_STYLE_USAGE(.BOTH.,#205242); -#205242 = SURFACE_SIDE_STYLE('',(#205243)); -#205243 = SURFACE_STYLE_FILL_AREA(#205244); -#205244 = FILL_AREA_STYLE('',(#205245)); -#205245 = FILL_AREA_STYLE_COLOUR('',#205231); -#205246 = OVER_RIDING_STYLED_ITEM('overriding color',(#205247),#7886, - #205217); -#205247 = PRESENTATION_STYLE_ASSIGNMENT((#205248)); -#205248 = SURFACE_STYLE_USAGE(.BOTH.,#205249); -#205249 = SURFACE_SIDE_STYLE('',(#205250)); -#205250 = SURFACE_STYLE_FILL_AREA(#205251); -#205251 = FILL_AREA_STYLE('',(#205252)); -#205252 = FILL_AREA_STYLE_COLOUR('',#205231); -#205253 = OVER_RIDING_STYLED_ITEM('overriding color',(#205254),#7935, - #205217); -#205254 = PRESENTATION_STYLE_ASSIGNMENT((#205255)); -#205255 = SURFACE_STYLE_USAGE(.BOTH.,#205256); -#205256 = SURFACE_SIDE_STYLE('',(#205257)); -#205257 = SURFACE_STYLE_FILL_AREA(#205258); -#205258 = FILL_AREA_STYLE('',(#205259)); -#205259 = FILL_AREA_STYLE_COLOUR('',#205231); -#205260 = OVER_RIDING_STYLED_ITEM('overriding color',(#205261),#7983, - #205217); -#205261 = PRESENTATION_STYLE_ASSIGNMENT((#205262)); -#205262 = SURFACE_STYLE_USAGE(.BOTH.,#205263); -#205263 = SURFACE_SIDE_STYLE('',(#205264)); -#205264 = SURFACE_STYLE_FILL_AREA(#205265); -#205265 = FILL_AREA_STYLE('',(#205266)); -#205266 = FILL_AREA_STYLE_COLOUR('',#205231); -#205267 = OVER_RIDING_STYLED_ITEM('overriding color',(#205268),#8035, - #205217); -#205268 = PRESENTATION_STYLE_ASSIGNMENT((#205269)); -#205269 = SURFACE_STYLE_USAGE(.BOTH.,#205270); -#205270 = SURFACE_SIDE_STYLE('',(#205271)); -#205271 = SURFACE_STYLE_FILL_AREA(#205272); -#205272 = FILL_AREA_STYLE('',(#205273)); -#205273 = FILL_AREA_STYLE_COLOUR('',#205231); -#205274 = OVER_RIDING_STYLED_ITEM('overriding color',(#205275),#8084, - #205217); -#205275 = PRESENTATION_STYLE_ASSIGNMENT((#205276)); -#205276 = SURFACE_STYLE_USAGE(.BOTH.,#205277); -#205277 = SURFACE_SIDE_STYLE('',(#205278)); -#205278 = SURFACE_STYLE_FILL_AREA(#205279); -#205279 = FILL_AREA_STYLE('',(#205280)); -#205280 = FILL_AREA_STYLE_COLOUR('',#205231); -#205281 = OVER_RIDING_STYLED_ITEM('overriding color',(#205282),#8133, - #205217); -#205282 = PRESENTATION_STYLE_ASSIGNMENT((#205283)); -#205283 = SURFACE_STYLE_USAGE(.BOTH.,#205284); -#205284 = SURFACE_SIDE_STYLE('',(#205285)); -#205285 = SURFACE_STYLE_FILL_AREA(#205286); -#205286 = FILL_AREA_STYLE('',(#205287)); -#205287 = FILL_AREA_STYLE_COLOUR('',#205231); -#205288 = OVER_RIDING_STYLED_ITEM('overriding color',(#205289),#8160, - #205217); -#205289 = PRESENTATION_STYLE_ASSIGNMENT((#205290)); -#205290 = SURFACE_STYLE_USAGE(.BOTH.,#205291); -#205291 = SURFACE_SIDE_STYLE('',(#205292)); -#205292 = SURFACE_STYLE_FILL_AREA(#205293); -#205293 = FILL_AREA_STYLE('',(#205294)); -#205294 = FILL_AREA_STYLE_COLOUR('',#205231); -#205295 = STYLED_ITEM('color',(#205296),#8171); -#205296 = PRESENTATION_STYLE_ASSIGNMENT((#205297)); -#205297 = SURFACE_STYLE_USAGE(.BOTH.,#205298); -#205298 = SURFACE_SIDE_STYLE('',(#205299)); -#205299 = SURFACE_STYLE_FILL_AREA(#205300); -#205300 = FILL_AREA_STYLE('',(#205301)); -#205301 = FILL_AREA_STYLE_COLOUR('',#201773); -#205302 = OVER_RIDING_STYLED_ITEM('overriding color',(#205303),#8173, - #205295); -#205303 = PRESENTATION_STYLE_ASSIGNMENT((#205304)); -#205304 = SURFACE_STYLE_USAGE(.BOTH.,#205305); -#205305 = SURFACE_SIDE_STYLE('',(#205306)); -#205306 = SURFACE_STYLE_FILL_AREA(#205307); -#205307 = FILL_AREA_STYLE('',(#205308)); -#205308 = FILL_AREA_STYLE_COLOUR('',#195083); -#205309 = OVER_RIDING_STYLED_ITEM('overriding color',(#205310),#8293, - #205295); -#205310 = PRESENTATION_STYLE_ASSIGNMENT((#205311)); -#205311 = SURFACE_STYLE_USAGE(.BOTH.,#205312); -#205312 = SURFACE_SIDE_STYLE('',(#205313)); -#205313 = SURFACE_STYLE_FILL_AREA(#205314); -#205314 = FILL_AREA_STYLE('',(#205315)); -#205315 = FILL_AREA_STYLE_COLOUR('',#195083); -#205316 = OVER_RIDING_STYLED_ITEM('overriding color',(#205317),#8369, - #205295); -#205317 = PRESENTATION_STYLE_ASSIGNMENT((#205318)); -#205318 = SURFACE_STYLE_USAGE(.BOTH.,#205319); -#205319 = SURFACE_SIDE_STYLE('',(#205320)); -#205320 = SURFACE_STYLE_FILL_AREA(#205321); -#205321 = FILL_AREA_STYLE('',(#205322)); -#205322 = FILL_AREA_STYLE_COLOUR('',#195083); -#205323 = OVER_RIDING_STYLED_ITEM('overriding color',(#205324),#8418, - #205295); -#205324 = PRESENTATION_STYLE_ASSIGNMENT((#205325)); -#205325 = SURFACE_STYLE_USAGE(.BOTH.,#205326); -#205326 = SURFACE_SIDE_STYLE('',(#205327)); -#205327 = SURFACE_STYLE_FILL_AREA(#205328); -#205328 = FILL_AREA_STYLE('',(#205329)); -#205329 = FILL_AREA_STYLE_COLOUR('',#195083); -#205330 = OVER_RIDING_STYLED_ITEM('overriding color',(#205331),#8467, - #205295); -#205331 = PRESENTATION_STYLE_ASSIGNMENT((#205332)); -#205332 = SURFACE_STYLE_USAGE(.BOTH.,#205333); -#205333 = SURFACE_SIDE_STYLE('',(#205334)); -#205334 = SURFACE_STYLE_FILL_AREA(#205335); -#205335 = FILL_AREA_STYLE('',(#205336)); -#205336 = FILL_AREA_STYLE_COLOUR('',#195083); -#205337 = OVER_RIDING_STYLED_ITEM('overriding color',(#205338),#8494, - #205295); -#205338 = PRESENTATION_STYLE_ASSIGNMENT((#205339)); -#205339 = SURFACE_STYLE_USAGE(.BOTH.,#205340); -#205340 = SURFACE_SIDE_STYLE('',(#205341)); -#205341 = SURFACE_STYLE_FILL_AREA(#205342); -#205342 = FILL_AREA_STYLE('',(#205343)); -#205343 = FILL_AREA_STYLE_COLOUR('',#195083); -#205344 = STYLED_ITEM('color',(#205345),#8501); -#205345 = PRESENTATION_STYLE_ASSIGNMENT((#205346)); -#205346 = SURFACE_STYLE_USAGE(.BOTH.,#205347); -#205347 = SURFACE_SIDE_STYLE('',(#205348)); -#205348 = SURFACE_STYLE_FILL_AREA(#205349); -#205349 = FILL_AREA_STYLE('',(#205350)); -#205350 = FILL_AREA_STYLE_COLOUR('',#201773); -#205351 = OVER_RIDING_STYLED_ITEM('overriding color',(#205352),#8503, - #205344); -#205352 = PRESENTATION_STYLE_ASSIGNMENT((#205353)); -#205353 = SURFACE_STYLE_USAGE(.BOTH.,#205354); -#205354 = SURFACE_SIDE_STYLE('',(#205355)); -#205355 = SURFACE_STYLE_FILL_AREA(#205356); -#205356 = FILL_AREA_STYLE('',(#205357)); -#205357 = FILL_AREA_STYLE_COLOUR('',#201036); -#205358 = OVER_RIDING_STYLED_ITEM('overriding color',(#205359),#8623, - #205344); -#205359 = PRESENTATION_STYLE_ASSIGNMENT((#205360)); -#205360 = SURFACE_STYLE_USAGE(.BOTH.,#205361); -#205361 = SURFACE_SIDE_STYLE('',(#205362)); -#205362 = SURFACE_STYLE_FILL_AREA(#205363); -#205363 = FILL_AREA_STYLE('',(#205364)); -#205364 = FILL_AREA_STYLE_COLOUR('',#201036); -#205365 = OVER_RIDING_STYLED_ITEM('overriding color',(#205366),#8699, - #205344); -#205366 = PRESENTATION_STYLE_ASSIGNMENT((#205367)); -#205367 = SURFACE_STYLE_USAGE(.BOTH.,#205368); -#205368 = SURFACE_SIDE_STYLE('',(#205369)); -#205369 = SURFACE_STYLE_FILL_AREA(#205370); -#205370 = FILL_AREA_STYLE('',(#205371)); -#205371 = FILL_AREA_STYLE_COLOUR('',#201036); -#205372 = OVER_RIDING_STYLED_ITEM('overriding color',(#205373),#8748, - #205344); -#205373 = PRESENTATION_STYLE_ASSIGNMENT((#205374)); -#205374 = SURFACE_STYLE_USAGE(.BOTH.,#205375); -#205375 = SURFACE_SIDE_STYLE('',(#205376)); -#205376 = SURFACE_STYLE_FILL_AREA(#205377); -#205377 = FILL_AREA_STYLE('',(#205378)); -#205378 = FILL_AREA_STYLE_COLOUR('',#201036); -#205379 = OVER_RIDING_STYLED_ITEM('overriding color',(#205380),#8797, - #205344); -#205380 = PRESENTATION_STYLE_ASSIGNMENT((#205381)); -#205381 = SURFACE_STYLE_USAGE(.BOTH.,#205382); -#205382 = SURFACE_SIDE_STYLE('',(#205383)); -#205383 = SURFACE_STYLE_FILL_AREA(#205384); -#205384 = FILL_AREA_STYLE('',(#205385)); -#205385 = FILL_AREA_STYLE_COLOUR('',#201036); -#205386 = OVER_RIDING_STYLED_ITEM('overriding color',(#205387),#8824, - #205344); -#205387 = PRESENTATION_STYLE_ASSIGNMENT((#205388)); -#205388 = SURFACE_STYLE_USAGE(.BOTH.,#205389); -#205389 = SURFACE_SIDE_STYLE('',(#205390)); -#205390 = SURFACE_STYLE_FILL_AREA(#205391); -#205391 = FILL_AREA_STYLE('',(#205392)); -#205392 = FILL_AREA_STYLE_COLOUR('',#201036); -#205393 = STYLED_ITEM('color',(#205394),#8831); -#205394 = PRESENTATION_STYLE_ASSIGNMENT((#205395)); -#205395 = SURFACE_STYLE_USAGE(.BOTH.,#205396); -#205396 = SURFACE_SIDE_STYLE('',(#205397)); -#205397 = SURFACE_STYLE_FILL_AREA(#205398); -#205398 = FILL_AREA_STYLE('',(#205399)); -#205399 = FILL_AREA_STYLE_COLOUR('',#201773); -#205400 = OVER_RIDING_STYLED_ITEM('overriding color',(#205401),#8833, - #205393); -#205401 = PRESENTATION_STYLE_ASSIGNMENT((#205402)); -#205402 = SURFACE_STYLE_USAGE(.BOTH.,#205403); -#205403 = SURFACE_SIDE_STYLE('',(#205404)); -#205404 = SURFACE_STYLE_FILL_AREA(#205405); -#205405 = FILL_AREA_STYLE('',(#205406)); -#205406 = FILL_AREA_STYLE_COLOUR('',#201028); -#205407 = OVER_RIDING_STYLED_ITEM('overriding color',(#205408),#9051, - #205393); -#205408 = PRESENTATION_STYLE_ASSIGNMENT((#205409)); -#205409 = SURFACE_STYLE_USAGE(.BOTH.,#205410); -#205410 = SURFACE_SIDE_STYLE('',(#205411)); -#205411 = SURFACE_STYLE_FILL_AREA(#205412); -#205412 = FILL_AREA_STYLE('',(#205413)); -#205413 = FILL_AREA_STYLE_COLOUR('',#201028); -#205414 = OVER_RIDING_STYLED_ITEM('overriding color',(#205415),#9127, - #205393); -#205415 = PRESENTATION_STYLE_ASSIGNMENT((#205416)); -#205416 = SURFACE_STYLE_USAGE(.BOTH.,#205417); -#205417 = SURFACE_SIDE_STYLE('',(#205418)); -#205418 = SURFACE_STYLE_FILL_AREA(#205419); -#205419 = FILL_AREA_STYLE('',(#205420)); -#205420 = FILL_AREA_STYLE_COLOUR('',#201028); -#205421 = OVER_RIDING_STYLED_ITEM('overriding color',(#205422),#9237, - #205393); -#205422 = PRESENTATION_STYLE_ASSIGNMENT((#205423)); -#205423 = SURFACE_STYLE_USAGE(.BOTH.,#205424); -#205424 = SURFACE_SIDE_STYLE('',(#205425)); -#205425 = SURFACE_STYLE_FILL_AREA(#205426); -#205426 = FILL_AREA_STYLE('',(#205427)); -#205427 = FILL_AREA_STYLE_COLOUR('',#201028); -#205428 = OVER_RIDING_STYLED_ITEM('overriding color',(#205429),#9308, - #205393); -#205429 = PRESENTATION_STYLE_ASSIGNMENT((#205430)); -#205430 = SURFACE_STYLE_USAGE(.BOTH.,#205431); -#205431 = SURFACE_SIDE_STYLE('',(#205432)); -#205432 = SURFACE_STYLE_FILL_AREA(#205433); -#205433 = FILL_AREA_STYLE('',(#205434)); -#205434 = FILL_AREA_STYLE_COLOUR('',#201028); -#205435 = OVER_RIDING_STYLED_ITEM('overriding color',(#205436),#9357, - #205393); -#205436 = PRESENTATION_STYLE_ASSIGNMENT((#205437)); -#205437 = SURFACE_STYLE_USAGE(.BOTH.,#205438); -#205438 = SURFACE_SIDE_STYLE('',(#205439)); -#205439 = SURFACE_STYLE_FILL_AREA(#205440); -#205440 = FILL_AREA_STYLE('',(#205441)); -#205441 = FILL_AREA_STYLE_COLOUR('',#201028); -#205442 = OVER_RIDING_STYLED_ITEM('overriding color',(#205443),#9435, - #205393); -#205443 = PRESENTATION_STYLE_ASSIGNMENT((#205444)); -#205444 = SURFACE_STYLE_USAGE(.BOTH.,#205445); -#205445 = SURFACE_SIDE_STYLE('',(#205446)); -#205446 = SURFACE_STYLE_FILL_AREA(#205447); -#205447 = FILL_AREA_STYLE('',(#205448)); -#205448 = FILL_AREA_STYLE_COLOUR('',#201028); -#205449 = OVER_RIDING_STYLED_ITEM('overriding color',(#205450),#9594, - #205393); -#205450 = PRESENTATION_STYLE_ASSIGNMENT((#205451)); -#205451 = SURFACE_STYLE_USAGE(.BOTH.,#205452); -#205452 = SURFACE_SIDE_STYLE('',(#205453)); -#205453 = SURFACE_STYLE_FILL_AREA(#205454); -#205454 = FILL_AREA_STYLE('',(#205455)); -#205455 = FILL_AREA_STYLE_COLOUR('',#201028); -#205456 = OVER_RIDING_STYLED_ITEM('overriding color',(#205457),#9669, - #205393); -#205457 = PRESENTATION_STYLE_ASSIGNMENT((#205458)); -#205458 = SURFACE_STYLE_USAGE(.BOTH.,#205459); -#205459 = SURFACE_SIDE_STYLE('',(#205460)); -#205460 = SURFACE_STYLE_FILL_AREA(#205461); -#205461 = FILL_AREA_STYLE('',(#205462)); -#205462 = FILL_AREA_STYLE_COLOUR('',#201028); -#205463 = OVER_RIDING_STYLED_ITEM('overriding color',(#205464),#9722, - #205393); -#205464 = PRESENTATION_STYLE_ASSIGNMENT((#205465)); -#205465 = SURFACE_STYLE_USAGE(.BOTH.,#205466); -#205466 = SURFACE_SIDE_STYLE('',(#205467)); -#205467 = SURFACE_STYLE_FILL_AREA(#205468); -#205468 = FILL_AREA_STYLE('',(#205469)); -#205469 = FILL_AREA_STYLE_COLOUR('',#201028); -#205470 = OVER_RIDING_STYLED_ITEM('overriding color',(#205471),#9771, - #205393); -#205471 = PRESENTATION_STYLE_ASSIGNMENT((#205472)); -#205472 = SURFACE_STYLE_USAGE(.BOTH.,#205473); -#205473 = SURFACE_SIDE_STYLE('',(#205474)); -#205474 = SURFACE_STYLE_FILL_AREA(#205475); -#205475 = FILL_AREA_STYLE('',(#205476)); -#205476 = FILL_AREA_STYLE_COLOUR('',#201028); -#205477 = OVER_RIDING_STYLED_ITEM('overriding color',(#205478),#9824, - #205393); -#205478 = PRESENTATION_STYLE_ASSIGNMENT((#205479)); -#205479 = SURFACE_STYLE_USAGE(.BOTH.,#205480); -#205480 = SURFACE_SIDE_STYLE('',(#205481)); -#205481 = SURFACE_STYLE_FILL_AREA(#205482); -#205482 = FILL_AREA_STYLE('',(#205483)); -#205483 = FILL_AREA_STYLE_COLOUR('',#201028); -#205484 = OVER_RIDING_STYLED_ITEM('overriding color',(#205485),#9872, - #205393); -#205485 = PRESENTATION_STYLE_ASSIGNMENT((#205486)); -#205486 = SURFACE_STYLE_USAGE(.BOTH.,#205487); -#205487 = SURFACE_SIDE_STYLE('',(#205488)); -#205488 = SURFACE_STYLE_FILL_AREA(#205489); -#205489 = FILL_AREA_STYLE('',(#205490)); -#205490 = FILL_AREA_STYLE_COLOUR('',#201028); -#205491 = OVER_RIDING_STYLED_ITEM('overriding color',(#205492),#9903, - #205393); -#205492 = PRESENTATION_STYLE_ASSIGNMENT((#205493)); -#205493 = SURFACE_STYLE_USAGE(.BOTH.,#205494); -#205494 = SURFACE_SIDE_STYLE('',(#205495)); -#205495 = SURFACE_STYLE_FILL_AREA(#205496); -#205496 = FILL_AREA_STYLE('',(#205497)); -#205497 = FILL_AREA_STYLE_COLOUR('',#201028); -#205498 = STYLED_ITEM('color',(#205499),#9912); -#205499 = PRESENTATION_STYLE_ASSIGNMENT((#205500)); -#205500 = SURFACE_STYLE_USAGE(.BOTH.,#205501); -#205501 = SURFACE_SIDE_STYLE('',(#205502)); -#205502 = SURFACE_STYLE_FILL_AREA(#205503); -#205503 = FILL_AREA_STYLE('',(#205504)); -#205504 = FILL_AREA_STYLE_COLOUR('',#201773); -#205505 = OVER_RIDING_STYLED_ITEM('overriding color',(#205506),#9914, - #205498); -#205506 = PRESENTATION_STYLE_ASSIGNMENT((#205507)); -#205507 = SURFACE_STYLE_USAGE(.BOTH.,#205508); -#205508 = SURFACE_SIDE_STYLE('',(#205509)); -#205509 = SURFACE_STYLE_FILL_AREA(#205510); -#205510 = FILL_AREA_STYLE('',(#205511)); -#205511 = FILL_AREA_STYLE_COLOUR('',#201028); -#205512 = OVER_RIDING_STYLED_ITEM('overriding color',(#205513),#10132, - #205498); -#205513 = PRESENTATION_STYLE_ASSIGNMENT((#205514)); -#205514 = SURFACE_STYLE_USAGE(.BOTH.,#205515); -#205515 = SURFACE_SIDE_STYLE('',(#205516)); -#205516 = SURFACE_STYLE_FILL_AREA(#205517); -#205517 = FILL_AREA_STYLE('',(#205518)); -#205518 = FILL_AREA_STYLE_COLOUR('',#201028); -#205519 = OVER_RIDING_STYLED_ITEM('overriding color',(#205520),#10208, - #205498); -#205520 = PRESENTATION_STYLE_ASSIGNMENT((#205521)); -#205521 = SURFACE_STYLE_USAGE(.BOTH.,#205522); -#205522 = SURFACE_SIDE_STYLE('',(#205523)); -#205523 = SURFACE_STYLE_FILL_AREA(#205524); -#205524 = FILL_AREA_STYLE('',(#205525)); -#205525 = FILL_AREA_STYLE_COLOUR('',#201028); -#205526 = OVER_RIDING_STYLED_ITEM('overriding color',(#205527),#10318, - #205498); -#205527 = PRESENTATION_STYLE_ASSIGNMENT((#205528)); -#205528 = SURFACE_STYLE_USAGE(.BOTH.,#205529); -#205529 = SURFACE_SIDE_STYLE('',(#205530)); -#205530 = SURFACE_STYLE_FILL_AREA(#205531); -#205531 = FILL_AREA_STYLE('',(#205532)); -#205532 = FILL_AREA_STYLE_COLOUR('',#201028); -#205533 = OVER_RIDING_STYLED_ITEM('overriding color',(#205534),#10389, - #205498); -#205534 = PRESENTATION_STYLE_ASSIGNMENT((#205535)); -#205535 = SURFACE_STYLE_USAGE(.BOTH.,#205536); -#205536 = SURFACE_SIDE_STYLE('',(#205537)); -#205537 = SURFACE_STYLE_FILL_AREA(#205538); -#205538 = FILL_AREA_STYLE('',(#205539)); -#205539 = FILL_AREA_STYLE_COLOUR('',#201028); -#205540 = OVER_RIDING_STYLED_ITEM('overriding color',(#205541),#10438, - #205498); -#205541 = PRESENTATION_STYLE_ASSIGNMENT((#205542)); -#205542 = SURFACE_STYLE_USAGE(.BOTH.,#205543); -#205543 = SURFACE_SIDE_STYLE('',(#205544)); -#205544 = SURFACE_STYLE_FILL_AREA(#205545); -#205545 = FILL_AREA_STYLE('',(#205546)); -#205546 = FILL_AREA_STYLE_COLOUR('',#201028); -#205547 = OVER_RIDING_STYLED_ITEM('overriding color',(#205548),#10516, - #205498); -#205548 = PRESENTATION_STYLE_ASSIGNMENT((#205549)); -#205549 = SURFACE_STYLE_USAGE(.BOTH.,#205550); -#205550 = SURFACE_SIDE_STYLE('',(#205551)); -#205551 = SURFACE_STYLE_FILL_AREA(#205552); -#205552 = FILL_AREA_STYLE('',(#205553)); -#205553 = FILL_AREA_STYLE_COLOUR('',#201028); -#205554 = OVER_RIDING_STYLED_ITEM('overriding color',(#205555),#10675, - #205498); -#205555 = PRESENTATION_STYLE_ASSIGNMENT((#205556)); -#205556 = SURFACE_STYLE_USAGE(.BOTH.,#205557); -#205557 = SURFACE_SIDE_STYLE('',(#205558)); -#205558 = SURFACE_STYLE_FILL_AREA(#205559); -#205559 = FILL_AREA_STYLE('',(#205560)); -#205560 = FILL_AREA_STYLE_COLOUR('',#201028); -#205561 = OVER_RIDING_STYLED_ITEM('overriding color',(#205562),#10750, - #205498); -#205562 = PRESENTATION_STYLE_ASSIGNMENT((#205563)); -#205563 = SURFACE_STYLE_USAGE(.BOTH.,#205564); -#205564 = SURFACE_SIDE_STYLE('',(#205565)); -#205565 = SURFACE_STYLE_FILL_AREA(#205566); -#205566 = FILL_AREA_STYLE('',(#205567)); -#205567 = FILL_AREA_STYLE_COLOUR('',#201028); -#205568 = OVER_RIDING_STYLED_ITEM('overriding color',(#205569),#10803, - #205498); -#205569 = PRESENTATION_STYLE_ASSIGNMENT((#205570)); -#205570 = SURFACE_STYLE_USAGE(.BOTH.,#205571); -#205571 = SURFACE_SIDE_STYLE('',(#205572)); -#205572 = SURFACE_STYLE_FILL_AREA(#205573); -#205573 = FILL_AREA_STYLE('',(#205574)); -#205574 = FILL_AREA_STYLE_COLOUR('',#201028); -#205575 = OVER_RIDING_STYLED_ITEM('overriding color',(#205576),#10852, - #205498); -#205576 = PRESENTATION_STYLE_ASSIGNMENT((#205577)); -#205577 = SURFACE_STYLE_USAGE(.BOTH.,#205578); -#205578 = SURFACE_SIDE_STYLE('',(#205579)); -#205579 = SURFACE_STYLE_FILL_AREA(#205580); -#205580 = FILL_AREA_STYLE('',(#205581)); -#205581 = FILL_AREA_STYLE_COLOUR('',#201028); -#205582 = OVER_RIDING_STYLED_ITEM('overriding color',(#205583),#10905, - #205498); -#205583 = PRESENTATION_STYLE_ASSIGNMENT((#205584)); -#205584 = SURFACE_STYLE_USAGE(.BOTH.,#205585); -#205585 = SURFACE_SIDE_STYLE('',(#205586)); -#205586 = SURFACE_STYLE_FILL_AREA(#205587); -#205587 = FILL_AREA_STYLE('',(#205588)); -#205588 = FILL_AREA_STYLE_COLOUR('',#201028); -#205589 = OVER_RIDING_STYLED_ITEM('overriding color',(#205590),#10953, - #205498); -#205590 = PRESENTATION_STYLE_ASSIGNMENT((#205591)); -#205591 = SURFACE_STYLE_USAGE(.BOTH.,#205592); -#205592 = SURFACE_SIDE_STYLE('',(#205593)); -#205593 = SURFACE_STYLE_FILL_AREA(#205594); -#205594 = FILL_AREA_STYLE('',(#205595)); -#205595 = FILL_AREA_STYLE_COLOUR('',#201028); -#205596 = OVER_RIDING_STYLED_ITEM('overriding color',(#205597),#11007, - #205498); -#205597 = PRESENTATION_STYLE_ASSIGNMENT((#205598)); -#205598 = SURFACE_STYLE_USAGE(.BOTH.,#205599); -#205599 = SURFACE_SIDE_STYLE('',(#205600)); -#205600 = SURFACE_STYLE_FILL_AREA(#205601); -#205601 = FILL_AREA_STYLE('',(#205602)); -#205602 = FILL_AREA_STYLE_COLOUR('',#201028); -#205603 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205604),#86280); -#205604 = STYLED_ITEM('color',(#205605),#85950); -#205605 = PRESENTATION_STYLE_ASSIGNMENT((#205606,#205611)); -#205606 = SURFACE_STYLE_USAGE(.BOTH.,#205607); -#205607 = SURFACE_SIDE_STYLE('',(#205608)); -#205608 = SURFACE_STYLE_FILL_AREA(#205609); -#205609 = FILL_AREA_STYLE('',(#205610)); -#205610 = FILL_AREA_STYLE_COLOUR('',#201036); -#205611 = CURVE_STYLE('',#205612,POSITIVE_LENGTH_MEASURE(0.1),#201036); -#205612 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#205613 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205614,#205621,#205628,#205635,#205642,#205649,#205656,#205663, - #205670,#205677,#205684,#205691,#205698,#205705,#205712,#205719, - #205726,#205733,#205740,#205747,#205754,#205761,#205768,#205775, - #205782,#205789,#205796,#205803,#205810,#205817,#205824,#205831, - #205838,#205845,#205852,#205859,#205866),#7455); -#205614 = STYLED_ITEM('color',(#205615),#5073); -#205615 = PRESENTATION_STYLE_ASSIGNMENT((#205616)); -#205616 = SURFACE_STYLE_USAGE(.BOTH.,#205617); -#205617 = SURFACE_SIDE_STYLE('',(#205618)); -#205618 = SURFACE_STYLE_FILL_AREA(#205619); -#205619 = FILL_AREA_STYLE('',(#205620)); -#205620 = FILL_AREA_STYLE_COLOUR('',#201773); -#205621 = OVER_RIDING_STYLED_ITEM('overriding color',(#205622),#5075, - #205614); -#205622 = PRESENTATION_STYLE_ASSIGNMENT((#205623)); -#205623 = SURFACE_STYLE_USAGE(.BOTH.,#205624); -#205624 = SURFACE_SIDE_STYLE('',(#205625)); -#205625 = SURFACE_STYLE_FILL_AREA(#205626); -#205626 = FILL_AREA_STYLE('',(#205627)); -#205627 = FILL_AREA_STYLE_COLOUR('',#201028); -#205628 = OVER_RIDING_STYLED_ITEM('overriding color',(#205629),#5195, - #205614); -#205629 = PRESENTATION_STYLE_ASSIGNMENT((#205630)); -#205630 = SURFACE_STYLE_USAGE(.BOTH.,#205631); -#205631 = SURFACE_SIDE_STYLE('',(#205632)); -#205632 = SURFACE_STYLE_FILL_AREA(#205633); -#205633 = FILL_AREA_STYLE('',(#205634)); -#205634 = FILL_AREA_STYLE_COLOUR('',#201028); -#205635 = OVER_RIDING_STYLED_ITEM('overriding color',(#205636),#5305, - #205614); -#205636 = PRESENTATION_STYLE_ASSIGNMENT((#205637)); -#205637 = SURFACE_STYLE_USAGE(.BOTH.,#205638); -#205638 = SURFACE_SIDE_STYLE('',(#205639)); -#205639 = SURFACE_STYLE_FILL_AREA(#205640); -#205640 = FILL_AREA_STYLE('',(#205641)); -#205641 = FILL_AREA_STYLE_COLOUR('',#201036); -#205642 = OVER_RIDING_STYLED_ITEM('overriding color',(#205643),#5481, - #205614); -#205643 = PRESENTATION_STYLE_ASSIGNMENT((#205644)); -#205644 = SURFACE_STYLE_USAGE(.BOTH.,#205645); -#205645 = SURFACE_SIDE_STYLE('',(#205646)); -#205646 = SURFACE_STYLE_FILL_AREA(#205647); -#205647 = FILL_AREA_STYLE('',(#205648)); -#205648 = FILL_AREA_STYLE_COLOUR('',#201036); -#205649 = OVER_RIDING_STYLED_ITEM('overriding color',(#205650),#5647, - #205614); -#205650 = PRESENTATION_STYLE_ASSIGNMENT((#205651)); -#205651 = SURFACE_STYLE_USAGE(.BOTH.,#205652); -#205652 = SURFACE_SIDE_STYLE('',(#205653)); -#205653 = SURFACE_STYLE_FILL_AREA(#205654); -#205654 = FILL_AREA_STYLE('',(#205655)); -#205655 = FILL_AREA_STYLE_COLOUR('',#201036); -#205656 = OVER_RIDING_STYLED_ITEM('overriding color',(#205657),#5704, - #205614); -#205657 = PRESENTATION_STYLE_ASSIGNMENT((#205658)); -#205658 = SURFACE_STYLE_USAGE(.BOTH.,#205659); -#205659 = SURFACE_SIDE_STYLE('',(#205660)); -#205660 = SURFACE_STYLE_FILL_AREA(#205661); -#205661 = FILL_AREA_STYLE('',(#205662)); -#205662 = FILL_AREA_STYLE_COLOUR('',#201028); -#205663 = OVER_RIDING_STYLED_ITEM('overriding color',(#205664),#5780, - #205614); -#205664 = PRESENTATION_STYLE_ASSIGNMENT((#205665)); -#205665 = SURFACE_STYLE_USAGE(.BOTH.,#205666); -#205666 = SURFACE_SIDE_STYLE('',(#205667)); -#205667 = SURFACE_STYLE_FILL_AREA(#205668); -#205668 = FILL_AREA_STYLE('',(#205669)); -#205669 = FILL_AREA_STYLE_COLOUR('',#201028); -#205670 = OVER_RIDING_STYLED_ITEM('overriding color',(#205671),#5851, - #205614); -#205671 = PRESENTATION_STYLE_ASSIGNMENT((#205672)); -#205672 = SURFACE_STYLE_USAGE(.BOTH.,#205673); -#205673 = SURFACE_SIDE_STYLE('',(#205674)); -#205674 = SURFACE_STYLE_FILL_AREA(#205675); -#205675 = FILL_AREA_STYLE('',(#205676)); -#205676 = FILL_AREA_STYLE_COLOUR('',#201028); -#205677 = OVER_RIDING_STYLED_ITEM('overriding color',(#205678),#6034, - #205614); -#205678 = PRESENTATION_STYLE_ASSIGNMENT((#205679)); -#205679 = SURFACE_STYLE_USAGE(.BOTH.,#205680); -#205680 = SURFACE_SIDE_STYLE('',(#205681)); -#205681 = SURFACE_STYLE_FILL_AREA(#205682); -#205682 = FILL_AREA_STYLE('',(#205683)); -#205683 = FILL_AREA_STYLE_COLOUR('',#201028); -#205684 = OVER_RIDING_STYLED_ITEM('overriding color',(#205685),#6149, - #205614); -#205685 = PRESENTATION_STYLE_ASSIGNMENT((#205686)); -#205686 = SURFACE_STYLE_USAGE(.BOTH.,#205687); -#205687 = SURFACE_SIDE_STYLE('',(#205688)); -#205688 = SURFACE_STYLE_FILL_AREA(#205689); -#205689 = FILL_AREA_STYLE('',(#205690)); -#205690 = FILL_AREA_STYLE_COLOUR('',#201028); -#205691 = OVER_RIDING_STYLED_ITEM('overriding color',(#205692),#6176, - #205614); -#205692 = PRESENTATION_STYLE_ASSIGNMENT((#205693)); -#205693 = SURFACE_STYLE_USAGE(.BOTH.,#205694); -#205694 = SURFACE_SIDE_STYLE('',(#205695)); -#205695 = SURFACE_STYLE_FILL_AREA(#205696); -#205696 = FILL_AREA_STYLE('',(#205697)); -#205697 = FILL_AREA_STYLE_COLOUR('',#201028); -#205698 = OVER_RIDING_STYLED_ITEM('overriding color',(#205699),#6203, - #205614); -#205699 = PRESENTATION_STYLE_ASSIGNMENT((#205700)); -#205700 = SURFACE_STYLE_USAGE(.BOTH.,#205701); -#205701 = SURFACE_SIDE_STYLE('',(#205702)); -#205702 = SURFACE_STYLE_FILL_AREA(#205703); -#205703 = FILL_AREA_STYLE('',(#205704)); -#205704 = FILL_AREA_STYLE_COLOUR('',#201028); -#205705 = OVER_RIDING_STYLED_ITEM('overriding color',(#205706),#6308, - #205614); -#205706 = PRESENTATION_STYLE_ASSIGNMENT((#205707)); -#205707 = SURFACE_STYLE_USAGE(.BOTH.,#205708); -#205708 = SURFACE_SIDE_STYLE('',(#205709)); -#205709 = SURFACE_STYLE_FILL_AREA(#205710); -#205710 = FILL_AREA_STYLE('',(#205711)); -#205711 = FILL_AREA_STYLE_COLOUR('',#201028); -#205712 = OVER_RIDING_STYLED_ITEM('overriding color',(#205713),#6379, - #205614); -#205713 = PRESENTATION_STYLE_ASSIGNMENT((#205714)); -#205714 = SURFACE_STYLE_USAGE(.BOTH.,#205715); -#205715 = SURFACE_SIDE_STYLE('',(#205716)); -#205716 = SURFACE_STYLE_FILL_AREA(#205717); -#205717 = FILL_AREA_STYLE('',(#205718)); -#205718 = FILL_AREA_STYLE_COLOUR('',#201028); -#205719 = OVER_RIDING_STYLED_ITEM('overriding color',(#205720),#6428, - #205614); -#205720 = PRESENTATION_STYLE_ASSIGNMENT((#205721)); -#205721 = SURFACE_STYLE_USAGE(.BOTH.,#205722); -#205722 = SURFACE_SIDE_STYLE('',(#205723)); -#205723 = SURFACE_STYLE_FILL_AREA(#205724); -#205724 = FILL_AREA_STYLE('',(#205725)); -#205725 = FILL_AREA_STYLE_COLOUR('',#201028); -#205726 = OVER_RIDING_STYLED_ITEM('overriding color',(#205727),#6499, - #205614); -#205727 = PRESENTATION_STYLE_ASSIGNMENT((#205728)); -#205728 = SURFACE_STYLE_USAGE(.BOTH.,#205729); -#205729 = SURFACE_SIDE_STYLE('',(#205730)); -#205730 = SURFACE_STYLE_FILL_AREA(#205731); -#205731 = FILL_AREA_STYLE('',(#205732)); -#205732 = FILL_AREA_STYLE_COLOUR('',#201028); -#205733 = OVER_RIDING_STYLED_ITEM('overriding color',(#205734),#6573, - #205614); -#205734 = PRESENTATION_STYLE_ASSIGNMENT((#205735)); -#205735 = SURFACE_STYLE_USAGE(.BOTH.,#205736); -#205736 = SURFACE_SIDE_STYLE('',(#205737)); -#205737 = SURFACE_STYLE_FILL_AREA(#205738); -#205738 = FILL_AREA_STYLE('',(#205739)); -#205739 = FILL_AREA_STYLE_COLOUR('',#201028); -#205740 = OVER_RIDING_STYLED_ITEM('overriding color',(#205741),#6584, - #205614); -#205741 = PRESENTATION_STYLE_ASSIGNMENT((#205742)); -#205742 = SURFACE_STYLE_USAGE(.BOTH.,#205743); -#205743 = SURFACE_SIDE_STYLE('',(#205744)); -#205744 = SURFACE_STYLE_FILL_AREA(#205745); -#205745 = FILL_AREA_STYLE('',(#205746)); -#205746 = FILL_AREA_STYLE_COLOUR('',#201028); -#205747 = OVER_RIDING_STYLED_ITEM('overriding color',(#205748),#6595, - #205614); -#205748 = PRESENTATION_STYLE_ASSIGNMENT((#205749)); -#205749 = SURFACE_STYLE_USAGE(.BOTH.,#205750); -#205750 = SURFACE_SIDE_STYLE('',(#205751)); -#205751 = SURFACE_STYLE_FILL_AREA(#205752); -#205752 = FILL_AREA_STYLE('',(#205753)); -#205753 = FILL_AREA_STYLE_COLOUR('',#201028); -#205754 = OVER_RIDING_STYLED_ITEM('overriding color',(#205755),#6666, - #205614); -#205755 = PRESENTATION_STYLE_ASSIGNMENT((#205756)); -#205756 = SURFACE_STYLE_USAGE(.BOTH.,#205757); -#205757 = SURFACE_SIDE_STYLE('',(#205758)); -#205758 = SURFACE_STYLE_FILL_AREA(#205759); -#205759 = FILL_AREA_STYLE('',(#205760)); -#205760 = FILL_AREA_STYLE_COLOUR('',#201028); -#205761 = OVER_RIDING_STYLED_ITEM('overriding color',(#205762),#6737, - #205614); -#205762 = PRESENTATION_STYLE_ASSIGNMENT((#205763)); -#205763 = SURFACE_STYLE_USAGE(.BOTH.,#205764); -#205764 = SURFACE_SIDE_STYLE('',(#205765)); -#205765 = SURFACE_STYLE_FILL_AREA(#205766); -#205766 = FILL_AREA_STYLE('',(#205767)); -#205767 = FILL_AREA_STYLE_COLOUR('',#201028); -#205768 = OVER_RIDING_STYLED_ITEM('overriding color',(#205769),#6764, - #205614); -#205769 = PRESENTATION_STYLE_ASSIGNMENT((#205770)); -#205770 = SURFACE_STYLE_USAGE(.BOTH.,#205771); -#205771 = SURFACE_SIDE_STYLE('',(#205772)); -#205772 = SURFACE_STYLE_FILL_AREA(#205773); -#205773 = FILL_AREA_STYLE('',(#205774)); -#205774 = FILL_AREA_STYLE_COLOUR('',#201028); -#205775 = OVER_RIDING_STYLED_ITEM('overriding color',(#205776),#6791, - #205614); -#205776 = PRESENTATION_STYLE_ASSIGNMENT((#205777)); -#205777 = SURFACE_STYLE_USAGE(.BOTH.,#205778); -#205778 = SURFACE_SIDE_STYLE('',(#205779)); -#205779 = SURFACE_STYLE_FILL_AREA(#205780); -#205780 = FILL_AREA_STYLE('',(#205781)); -#205781 = FILL_AREA_STYLE_COLOUR('',#201028); -#205782 = OVER_RIDING_STYLED_ITEM('overriding color',(#205783),#6862, - #205614); -#205783 = PRESENTATION_STYLE_ASSIGNMENT((#205784)); -#205784 = SURFACE_STYLE_USAGE(.BOTH.,#205785); -#205785 = SURFACE_SIDE_STYLE('',(#205786)); -#205786 = SURFACE_STYLE_FILL_AREA(#205787); -#205787 = FILL_AREA_STYLE('',(#205788)); -#205788 = FILL_AREA_STYLE_COLOUR('',#201028); -#205789 = OVER_RIDING_STYLED_ITEM('overriding color',(#205790),#6940, - #205614); -#205790 = PRESENTATION_STYLE_ASSIGNMENT((#205791)); -#205791 = SURFACE_STYLE_USAGE(.BOTH.,#205792); -#205792 = SURFACE_SIDE_STYLE('',(#205793)); -#205793 = SURFACE_STYLE_FILL_AREA(#205794); -#205794 = FILL_AREA_STYLE('',(#205795)); -#205795 = FILL_AREA_STYLE_COLOUR('',#201028); -#205796 = OVER_RIDING_STYLED_ITEM('overriding color',(#205797),#7016, - #205614); -#205797 = PRESENTATION_STYLE_ASSIGNMENT((#205798)); -#205798 = SURFACE_STYLE_USAGE(.BOTH.,#205799); -#205799 = SURFACE_SIDE_STYLE('',(#205800)); -#205800 = SURFACE_STYLE_FILL_AREA(#205801); -#205801 = FILL_AREA_STYLE('',(#205802)); -#205802 = FILL_AREA_STYLE_COLOUR('',#201028); -#205803 = OVER_RIDING_STYLED_ITEM('overriding color',(#205804),#7087, - #205614); -#205804 = PRESENTATION_STYLE_ASSIGNMENT((#205805)); -#205805 = SURFACE_STYLE_USAGE(.BOTH.,#205806); -#205806 = SURFACE_SIDE_STYLE('',(#205807)); -#205807 = SURFACE_STYLE_FILL_AREA(#205808); -#205808 = FILL_AREA_STYLE('',(#205809)); -#205809 = FILL_AREA_STYLE_COLOUR('',#201028); -#205810 = OVER_RIDING_STYLED_ITEM('overriding color',(#205811),#7161, - #205614); -#205811 = PRESENTATION_STYLE_ASSIGNMENT((#205812)); -#205812 = SURFACE_STYLE_USAGE(.BOTH.,#205813); -#205813 = SURFACE_SIDE_STYLE('',(#205814)); -#205814 = SURFACE_STYLE_FILL_AREA(#205815); -#205815 = FILL_AREA_STYLE('',(#205816)); -#205816 = FILL_AREA_STYLE_COLOUR('',#201028); -#205817 = OVER_RIDING_STYLED_ITEM('overriding color',(#205818),#7172, - #205614); -#205818 = PRESENTATION_STYLE_ASSIGNMENT((#205819)); -#205819 = SURFACE_STYLE_USAGE(.BOTH.,#205820); -#205820 = SURFACE_SIDE_STYLE('',(#205821)); -#205821 = SURFACE_STYLE_FILL_AREA(#205822); -#205822 = FILL_AREA_STYLE('',(#205823)); -#205823 = FILL_AREA_STYLE_COLOUR('',#201028); -#205824 = OVER_RIDING_STYLED_ITEM('overriding color',(#205825),#7183, - #205614); -#205825 = PRESENTATION_STYLE_ASSIGNMENT((#205826)); -#205826 = SURFACE_STYLE_USAGE(.BOTH.,#205827); -#205827 = SURFACE_SIDE_STYLE('',(#205828)); -#205828 = SURFACE_STYLE_FILL_AREA(#205829); -#205829 = FILL_AREA_STYLE('',(#205830)); -#205830 = FILL_AREA_STYLE_COLOUR('',#201781); -#205831 = OVER_RIDING_STYLED_ITEM('overriding color',(#205832),#7215, - #205614); -#205832 = PRESENTATION_STYLE_ASSIGNMENT((#205833)); -#205833 = SURFACE_STYLE_USAGE(.BOTH.,#205834); -#205834 = SURFACE_SIDE_STYLE('',(#205835)); -#205835 = SURFACE_STYLE_FILL_AREA(#205836); -#205836 = FILL_AREA_STYLE('',(#205837)); -#205837 = FILL_AREA_STYLE_COLOUR('',#201781); -#205838 = OVER_RIDING_STYLED_ITEM('overriding color',(#205839),#7247, - #205614); -#205839 = PRESENTATION_STYLE_ASSIGNMENT((#205840)); -#205840 = SURFACE_STYLE_USAGE(.BOTH.,#205841); -#205841 = SURFACE_SIDE_STYLE('',(#205842)); -#205842 = SURFACE_STYLE_FILL_AREA(#205843); -#205843 = FILL_AREA_STYLE('',(#205844)); -#205844 = FILL_AREA_STYLE_COLOUR('',#201781); -#205845 = OVER_RIDING_STYLED_ITEM('overriding color',(#205846),#7323, - #205614); -#205846 = PRESENTATION_STYLE_ASSIGNMENT((#205847)); -#205847 = SURFACE_STYLE_USAGE(.BOTH.,#205848); -#205848 = SURFACE_SIDE_STYLE('',(#205849)); -#205849 = SURFACE_STYLE_FILL_AREA(#205850); -#205850 = FILL_AREA_STYLE('',(#205851)); -#205851 = FILL_AREA_STYLE_COLOUR('',#201781); -#205852 = OVER_RIDING_STYLED_ITEM('overriding color',(#205853),#7372, - #205614); -#205853 = PRESENTATION_STYLE_ASSIGNMENT((#205854)); -#205854 = SURFACE_STYLE_USAGE(.BOTH.,#205855); -#205855 = SURFACE_SIDE_STYLE('',(#205856)); -#205856 = SURFACE_STYLE_FILL_AREA(#205857); -#205857 = FILL_AREA_STYLE('',(#205858)); -#205858 = FILL_AREA_STYLE_COLOUR('',#201781); -#205859 = OVER_RIDING_STYLED_ITEM('overriding color',(#205860),#7421, - #205614); -#205860 = PRESENTATION_STYLE_ASSIGNMENT((#205861)); -#205861 = SURFACE_STYLE_USAGE(.BOTH.,#205862); -#205862 = SURFACE_SIDE_STYLE('',(#205863)); -#205863 = SURFACE_STYLE_FILL_AREA(#205864); -#205864 = FILL_AREA_STYLE('',(#205865)); -#205865 = FILL_AREA_STYLE_COLOUR('',#201781); -#205866 = OVER_RIDING_STYLED_ITEM('overriding color',(#205867),#7448, - #205614); -#205867 = PRESENTATION_STYLE_ASSIGNMENT((#205868)); -#205868 = SURFACE_STYLE_USAGE(.BOTH.,#205869); -#205869 = SURFACE_SIDE_STYLE('',(#205870)); -#205870 = SURFACE_STYLE_FILL_AREA(#205871); -#205871 = FILL_AREA_STYLE('',(#205872)); -#205872 = FILL_AREA_STYLE_COLOUR('',#201781); -#205873 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #205874,#205881,#205888,#205895,#205902,#205909,#205916,#205923, - #205930,#205937,#205944,#205951,#205958,#205965,#205972,#205979, - #205986,#205993,#206000,#206007,#206014,#206021,#206028,#206035, - #206042,#206049,#206056,#206063,#206070,#206077,#206084,#206091, - #206098,#206105,#206112,#206119,#206126,#206133,#206140,#206147, - #206154,#206161,#206168,#206175,#206182,#206189,#206196,#206203, - #206210,#206217,#206224,#206231,#206238,#206245,#206252,#206259, - #206266,#206273,#206280,#206287,#206294,#206301,#206308,#206315, - #206322,#206329,#206336,#206343,#206350,#206357,#206364,#206371, - #206378,#206385,#206392,#206399,#206406,#206413,#206420,#206427, - #206434,#206441,#206448,#206455,#206462,#206469,#206476,#206483, - #206490,#206497,#206504,#206511,#206518,#206525,#206532,#206539, - #206546,#206553,#206560,#206567,#206574,#206581,#206588,#206595, - #206602,#206609,#206616,#206623,#206630,#206637,#206644,#206651, - #206658,#206665,#206672,#206679,#206686,#206693,#206700,#206707, - #206714,#206721,#206728,#206735),#194570); -#205874 = STYLED_ITEM('color',(#205875),#182949); -#205875 = PRESENTATION_STYLE_ASSIGNMENT((#205876)); -#205876 = SURFACE_STYLE_USAGE(.BOTH.,#205877); -#205877 = SURFACE_SIDE_STYLE('',(#205878)); -#205878 = SURFACE_STYLE_FILL_AREA(#205879); -#205879 = FILL_AREA_STYLE('',(#205880)); -#205880 = FILL_AREA_STYLE_COLOUR('',#201773); -#205881 = OVER_RIDING_STYLED_ITEM('overriding color',(#205882),#182951, - #205874); -#205882 = PRESENTATION_STYLE_ASSIGNMENT((#205883)); -#205883 = SURFACE_STYLE_USAGE(.BOTH.,#205884); -#205884 = SURFACE_SIDE_STYLE('',(#205885)); -#205885 = SURFACE_STYLE_FILL_AREA(#205886); -#205886 = FILL_AREA_STYLE('',(#205887)); -#205887 = FILL_AREA_STYLE_COLOUR('',#201781); -#205888 = OVER_RIDING_STYLED_ITEM('overriding color',(#205889),#183231, - #205874); -#205889 = PRESENTATION_STYLE_ASSIGNMENT((#205890)); -#205890 = SURFACE_STYLE_USAGE(.BOTH.,#205891); -#205891 = SURFACE_SIDE_STYLE('',(#205892)); -#205892 = SURFACE_STYLE_FILL_AREA(#205893); -#205893 = FILL_AREA_STYLE('',(#205894)); -#205894 = FILL_AREA_STYLE_COLOUR('',#201781); -#205895 = OVER_RIDING_STYLED_ITEM('overriding color',(#205896),#183506, - #205874); -#205896 = PRESENTATION_STYLE_ASSIGNMENT((#205897)); -#205897 = SURFACE_STYLE_USAGE(.BOTH.,#205898); -#205898 = SURFACE_SIDE_STYLE('',(#205899)); -#205899 = SURFACE_STYLE_FILL_AREA(#205900); -#205900 = FILL_AREA_STYLE('',(#205901)); -#205901 = FILL_AREA_STYLE_COLOUR('',#201781); -#205902 = OVER_RIDING_STYLED_ITEM('overriding color',(#205903),#183781, - #205874); -#205903 = PRESENTATION_STYLE_ASSIGNMENT((#205904)); -#205904 = SURFACE_STYLE_USAGE(.BOTH.,#205905); -#205905 = SURFACE_SIDE_STYLE('',(#205906)); -#205906 = SURFACE_STYLE_FILL_AREA(#205907); -#205907 = FILL_AREA_STYLE('',(#205908)); -#205908 = FILL_AREA_STYLE_COLOUR('',#201781); -#205909 = OVER_RIDING_STYLED_ITEM('overriding color',(#205910),#184056, - #205874); +#205230 = FILL_AREA_STYLE_COLOUR('',#197630); +#205231 = OVER_RIDING_STYLED_ITEM('overriding color',(#205232),#179021, + #204832); +#205232 = PRESENTATION_STYLE_ASSIGNMENT((#205233)); +#205233 = SURFACE_STYLE_USAGE(.BOTH.,#205234); +#205234 = SURFACE_SIDE_STYLE('',(#205235)); +#205235 = SURFACE_STYLE_FILL_AREA(#205236); +#205236 = FILL_AREA_STYLE('',(#205237)); +#205237 = FILL_AREA_STYLE_COLOUR('',#197630); +#205238 = OVER_RIDING_STYLED_ITEM('overriding color',(#205239),#179028, + #204832); +#205239 = PRESENTATION_STYLE_ASSIGNMENT((#205240)); +#205240 = SURFACE_STYLE_USAGE(.BOTH.,#205241); +#205241 = SURFACE_SIDE_STYLE('',(#205242)); +#205242 = SURFACE_STYLE_FILL_AREA(#205243); +#205243 = FILL_AREA_STYLE('',(#205244)); +#205244 = FILL_AREA_STYLE_COLOUR('',#197630); +#205245 = OVER_RIDING_STYLED_ITEM('overriding color',(#205246),#179077, + #204832); +#205246 = PRESENTATION_STYLE_ASSIGNMENT((#205247)); +#205247 = SURFACE_STYLE_USAGE(.BOTH.,#205248); +#205248 = SURFACE_SIDE_STYLE('',(#205249)); +#205249 = SURFACE_STYLE_FILL_AREA(#205250); +#205250 = FILL_AREA_STYLE('',(#205251)); +#205251 = FILL_AREA_STYLE_COLOUR('',#197630); +#205252 = OVER_RIDING_STYLED_ITEM('overriding color',(#205253),#179126, + #204832); +#205253 = PRESENTATION_STYLE_ASSIGNMENT((#205254)); +#205254 = SURFACE_STYLE_USAGE(.BOTH.,#205255); +#205255 = SURFACE_SIDE_STYLE('',(#205256)); +#205256 = SURFACE_STYLE_FILL_AREA(#205257); +#205257 = FILL_AREA_STYLE('',(#205258)); +#205258 = FILL_AREA_STYLE_COLOUR('',#197630); +#205259 = OVER_RIDING_STYLED_ITEM('overriding color',(#205260),#179133, + #204832); +#205260 = PRESENTATION_STYLE_ASSIGNMENT((#205261)); +#205261 = SURFACE_STYLE_USAGE(.BOTH.,#205262); +#205262 = SURFACE_SIDE_STYLE('',(#205263)); +#205263 = SURFACE_STYLE_FILL_AREA(#205264); +#205264 = FILL_AREA_STYLE('',(#205265)); +#205265 = FILL_AREA_STYLE_COLOUR('',#197630); +#205266 = OVER_RIDING_STYLED_ITEM('overriding color',(#205267),#179140, + #204832); +#205267 = PRESENTATION_STYLE_ASSIGNMENT((#205268)); +#205268 = SURFACE_STYLE_USAGE(.BOTH.,#205269); +#205269 = SURFACE_SIDE_STYLE('',(#205270)); +#205270 = SURFACE_STYLE_FILL_AREA(#205271); +#205271 = FILL_AREA_STYLE('',(#205272)); +#205272 = FILL_AREA_STYLE_COLOUR('',#197630); +#205273 = OVER_RIDING_STYLED_ITEM('overriding color',(#205274),#179189, + #204832); +#205274 = PRESENTATION_STYLE_ASSIGNMENT((#205275)); +#205275 = SURFACE_STYLE_USAGE(.BOTH.,#205276); +#205276 = SURFACE_SIDE_STYLE('',(#205277)); +#205277 = SURFACE_STYLE_FILL_AREA(#205278); +#205278 = FILL_AREA_STYLE('',(#205279)); +#205279 = FILL_AREA_STYLE_COLOUR('',#197630); +#205280 = OVER_RIDING_STYLED_ITEM('overriding color',(#205281),#179196, + #204832); +#205281 = PRESENTATION_STYLE_ASSIGNMENT((#205282)); +#205282 = SURFACE_STYLE_USAGE(.BOTH.,#205283); +#205283 = SURFACE_SIDE_STYLE('',(#205284)); +#205284 = SURFACE_STYLE_FILL_AREA(#205285); +#205285 = FILL_AREA_STYLE('',(#205286)); +#205286 = FILL_AREA_STYLE_COLOUR('',#197630); +#205287 = OVER_RIDING_STYLED_ITEM('overriding color',(#205288),#179245, + #204832); +#205288 = PRESENTATION_STYLE_ASSIGNMENT((#205289)); +#205289 = SURFACE_STYLE_USAGE(.BOTH.,#205290); +#205290 = SURFACE_SIDE_STYLE('',(#205291)); +#205291 = SURFACE_STYLE_FILL_AREA(#205292); +#205292 = FILL_AREA_STYLE('',(#205293)); +#205293 = FILL_AREA_STYLE_COLOUR('',#197630); +#205294 = OVER_RIDING_STYLED_ITEM('overriding color',(#205295),#179294, + #204832); +#205295 = PRESENTATION_STYLE_ASSIGNMENT((#205296)); +#205296 = SURFACE_STYLE_USAGE(.BOTH.,#205297); +#205297 = SURFACE_SIDE_STYLE('',(#205298)); +#205298 = SURFACE_STYLE_FILL_AREA(#205299); +#205299 = FILL_AREA_STYLE('',(#205300)); +#205300 = FILL_AREA_STYLE_COLOUR('',#197630); +#205301 = OVER_RIDING_STYLED_ITEM('overriding color',(#205302),#179301, + #204832); +#205302 = PRESENTATION_STYLE_ASSIGNMENT((#205303)); +#205303 = SURFACE_STYLE_USAGE(.BOTH.,#205304); +#205304 = SURFACE_SIDE_STYLE('',(#205305)); +#205305 = SURFACE_STYLE_FILL_AREA(#205306); +#205306 = FILL_AREA_STYLE('',(#205307)); +#205307 = FILL_AREA_STYLE_COLOUR('',#197630); +#205308 = OVER_RIDING_STYLED_ITEM('overriding color',(#205309),#179308, + #204832); +#205309 = PRESENTATION_STYLE_ASSIGNMENT((#205310)); +#205310 = SURFACE_STYLE_USAGE(.BOTH.,#205311); +#205311 = SURFACE_SIDE_STYLE('',(#205312)); +#205312 = SURFACE_STYLE_FILL_AREA(#205313); +#205313 = FILL_AREA_STYLE('',(#205314)); +#205314 = FILL_AREA_STYLE_COLOUR('',#197630); +#205315 = OVER_RIDING_STYLED_ITEM('overriding color',(#205316),#179357, + #204832); +#205316 = PRESENTATION_STYLE_ASSIGNMENT((#205317)); +#205317 = SURFACE_STYLE_USAGE(.BOTH.,#205318); +#205318 = SURFACE_SIDE_STYLE('',(#205319)); +#205319 = SURFACE_STYLE_FILL_AREA(#205320); +#205320 = FILL_AREA_STYLE('',(#205321)); +#205321 = FILL_AREA_STYLE_COLOUR('',#197630); +#205322 = OVER_RIDING_STYLED_ITEM('overriding color',(#205323),#179406, + #204832); +#205323 = PRESENTATION_STYLE_ASSIGNMENT((#205324)); +#205324 = SURFACE_STYLE_USAGE(.BOTH.,#205325); +#205325 = SURFACE_SIDE_STYLE('',(#205326)); +#205326 = SURFACE_STYLE_FILL_AREA(#205327); +#205327 = FILL_AREA_STYLE('',(#205328)); +#205328 = FILL_AREA_STYLE_COLOUR('',#197630); +#205329 = OVER_RIDING_STYLED_ITEM('overriding color',(#205330),#179413, + #204832); +#205330 = PRESENTATION_STYLE_ASSIGNMENT((#205331)); +#205331 = SURFACE_STYLE_USAGE(.BOTH.,#205332); +#205332 = SURFACE_SIDE_STYLE('',(#205333)); +#205333 = SURFACE_STYLE_FILL_AREA(#205334); +#205334 = FILL_AREA_STYLE('',(#205335)); +#205335 = FILL_AREA_STYLE_COLOUR('',#197630); +#205336 = OVER_RIDING_STYLED_ITEM('overriding color',(#205337),#179420, + #204832); +#205337 = PRESENTATION_STYLE_ASSIGNMENT((#205338)); +#205338 = SURFACE_STYLE_USAGE(.BOTH.,#205339); +#205339 = SURFACE_SIDE_STYLE('',(#205340)); +#205340 = SURFACE_STYLE_FILL_AREA(#205341); +#205341 = FILL_AREA_STYLE('',(#205342)); +#205342 = FILL_AREA_STYLE_COLOUR('',#197425); +#205343 = OVER_RIDING_STYLED_ITEM('overriding color',(#205344),#179495, + #204832); +#205344 = PRESENTATION_STYLE_ASSIGNMENT((#205345)); +#205345 = SURFACE_STYLE_USAGE(.BOTH.,#205346); +#205346 = SURFACE_SIDE_STYLE('',(#205347)); +#205347 = SURFACE_STYLE_FILL_AREA(#205348); +#205348 = FILL_AREA_STYLE('',(#205349)); +#205349 = FILL_AREA_STYLE_COLOUR('',#197425); +#205350 = OVER_RIDING_STYLED_ITEM('overriding color',(#205351),#179776, + #204832); +#205351 = PRESENTATION_STYLE_ASSIGNMENT((#205352)); +#205352 = SURFACE_STYLE_USAGE(.BOTH.,#205353); +#205353 = SURFACE_SIDE_STYLE('',(#205354)); +#205354 = SURFACE_STYLE_FILL_AREA(#205355); +#205355 = FILL_AREA_STYLE('',(#205356)); +#205356 = FILL_AREA_STYLE_COLOUR('',#197425); +#205357 = OVER_RIDING_STYLED_ITEM('overriding color',(#205358),#179824, + #204832); +#205358 = PRESENTATION_STYLE_ASSIGNMENT((#205359)); +#205359 = SURFACE_STYLE_USAGE(.BOTH.,#205360); +#205360 = SURFACE_SIDE_STYLE('',(#205361)); +#205361 = SURFACE_STYLE_FILL_AREA(#205362); +#205362 = FILL_AREA_STYLE('',(#205363)); +#205363 = FILL_AREA_STYLE_COLOUR('',#197425); +#205364 = OVER_RIDING_STYLED_ITEM('overriding color',(#205365),#180043, + #204832); +#205365 = PRESENTATION_STYLE_ASSIGNMENT((#205366)); +#205366 = SURFACE_STYLE_USAGE(.BOTH.,#205367); +#205367 = SURFACE_SIDE_STYLE('',(#205368)); +#205368 = SURFACE_STYLE_FILL_AREA(#205369); +#205369 = FILL_AREA_STYLE('',(#205370)); +#205370 = FILL_AREA_STYLE_COLOUR('',#197425); +#205371 = OVER_RIDING_STYLED_ITEM('overriding color',(#205372),#180069, + #204832); +#205372 = PRESENTATION_STYLE_ASSIGNMENT((#205373)); +#205373 = SURFACE_STYLE_USAGE(.BOTH.,#205374); +#205374 = SURFACE_SIDE_STYLE('',(#205375)); +#205375 = SURFACE_STYLE_FILL_AREA(#205376); +#205376 = FILL_AREA_STYLE('',(#205377)); +#205377 = FILL_AREA_STYLE_COLOUR('',#197425); +#205378 = OVER_RIDING_STYLED_ITEM('overriding color',(#205379),#180095, + #204832); +#205379 = PRESENTATION_STYLE_ASSIGNMENT((#205380)); +#205380 = SURFACE_STYLE_USAGE(.BOTH.,#205381); +#205381 = SURFACE_SIDE_STYLE('',(#205382)); +#205382 = SURFACE_STYLE_FILL_AREA(#205383); +#205383 = FILL_AREA_STYLE('',(#205384)); +#205384 = FILL_AREA_STYLE_COLOUR('',#197425); +#205385 = OVER_RIDING_STYLED_ITEM('overriding color',(#205386),#180144, + #204832); +#205386 = PRESENTATION_STYLE_ASSIGNMENT((#205387)); +#205387 = SURFACE_STYLE_USAGE(.BOTH.,#205388); +#205388 = SURFACE_SIDE_STYLE('',(#205389)); +#205389 = SURFACE_STYLE_FILL_AREA(#205390); +#205390 = FILL_AREA_STYLE('',(#205391)); +#205391 = FILL_AREA_STYLE_COLOUR('',#197425); +#205392 = OVER_RIDING_STYLED_ITEM('overriding color',(#205393),#180171, + #204832); +#205393 = PRESENTATION_STYLE_ASSIGNMENT((#205394)); +#205394 = SURFACE_STYLE_USAGE(.BOTH.,#205395); +#205395 = SURFACE_SIDE_STYLE('',(#205396)); +#205396 = SURFACE_STYLE_FILL_AREA(#205397); +#205397 = FILL_AREA_STYLE('',(#205398)); +#205398 = FILL_AREA_STYLE_COLOUR('',#197425); +#205399 = OVER_RIDING_STYLED_ITEM('overriding color',(#205400),#180198, + #204832); +#205400 = PRESENTATION_STYLE_ASSIGNMENT((#205401)); +#205401 = SURFACE_STYLE_USAGE(.BOTH.,#205402); +#205402 = SURFACE_SIDE_STYLE('',(#205403)); +#205403 = SURFACE_STYLE_FILL_AREA(#205404); +#205404 = FILL_AREA_STYLE('',(#205405)); +#205405 = FILL_AREA_STYLE_COLOUR('',#197425); +#205406 = OVER_RIDING_STYLED_ITEM('overriding color',(#205407),#180247, + #204832); +#205407 = PRESENTATION_STYLE_ASSIGNMENT((#205408)); +#205408 = SURFACE_STYLE_USAGE(.BOTH.,#205409); +#205409 = SURFACE_SIDE_STYLE('',(#205410)); +#205410 = SURFACE_STYLE_FILL_AREA(#205411); +#205411 = FILL_AREA_STYLE('',(#205412)); +#205412 = FILL_AREA_STYLE_COLOUR('',#197425); +#205413 = OVER_RIDING_STYLED_ITEM('overriding color',(#205414),#180273, + #204832); +#205414 = PRESENTATION_STYLE_ASSIGNMENT((#205415)); +#205415 = SURFACE_STYLE_USAGE(.BOTH.,#205416); +#205416 = SURFACE_SIDE_STYLE('',(#205417)); +#205417 = SURFACE_STYLE_FILL_AREA(#205418); +#205418 = FILL_AREA_STYLE('',(#205419)); +#205419 = FILL_AREA_STYLE_COLOUR('',#197425); +#205420 = OVER_RIDING_STYLED_ITEM('overriding color',(#205421),#180299, + #204832); +#205421 = PRESENTATION_STYLE_ASSIGNMENT((#205422)); +#205422 = SURFACE_STYLE_USAGE(.BOTH.,#205423); +#205423 = SURFACE_SIDE_STYLE('',(#205424)); +#205424 = SURFACE_STYLE_FILL_AREA(#205425); +#205425 = FILL_AREA_STYLE('',(#205426)); +#205426 = FILL_AREA_STYLE_COLOUR('',#197425); +#205427 = OVER_RIDING_STYLED_ITEM('overriding color',(#205428),#180306, + #204832); +#205428 = PRESENTATION_STYLE_ASSIGNMENT((#205429)); +#205429 = SURFACE_STYLE_USAGE(.BOTH.,#205430); +#205430 = SURFACE_SIDE_STYLE('',(#205431)); +#205431 = SURFACE_STYLE_FILL_AREA(#205432); +#205432 = FILL_AREA_STYLE('',(#205433)); +#205433 = FILL_AREA_STYLE_COLOUR('',#197425); +#205434 = OVER_RIDING_STYLED_ITEM('overriding color',(#205435),#180381, + #204832); +#205435 = PRESENTATION_STYLE_ASSIGNMENT((#205436)); +#205436 = SURFACE_STYLE_USAGE(.BOTH.,#205437); +#205437 = SURFACE_SIDE_STYLE('',(#205438)); +#205438 = SURFACE_STYLE_FILL_AREA(#205439); +#205439 = FILL_AREA_STYLE('',(#205440)); +#205440 = FILL_AREA_STYLE_COLOUR('',#197425); +#205441 = OVER_RIDING_STYLED_ITEM('overriding color',(#205442),#180662, + #204832); +#205442 = PRESENTATION_STYLE_ASSIGNMENT((#205443)); +#205443 = SURFACE_STYLE_USAGE(.BOTH.,#205444); +#205444 = SURFACE_SIDE_STYLE('',(#205445)); +#205445 = SURFACE_STYLE_FILL_AREA(#205446); +#205446 = FILL_AREA_STYLE('',(#205447)); +#205447 = FILL_AREA_STYLE_COLOUR('',#197425); +#205448 = OVER_RIDING_STYLED_ITEM('overriding color',(#205449),#180710, + #204832); +#205449 = PRESENTATION_STYLE_ASSIGNMENT((#205450)); +#205450 = SURFACE_STYLE_USAGE(.BOTH.,#205451); +#205451 = SURFACE_SIDE_STYLE('',(#205452)); +#205452 = SURFACE_STYLE_FILL_AREA(#205453); +#205453 = FILL_AREA_STYLE('',(#205454)); +#205454 = FILL_AREA_STYLE_COLOUR('',#197425); +#205455 = OVER_RIDING_STYLED_ITEM('overriding color',(#205456),#180929, + #204832); +#205456 = PRESENTATION_STYLE_ASSIGNMENT((#205457)); +#205457 = SURFACE_STYLE_USAGE(.BOTH.,#205458); +#205458 = SURFACE_SIDE_STYLE('',(#205459)); +#205459 = SURFACE_STYLE_FILL_AREA(#205460); +#205460 = FILL_AREA_STYLE('',(#205461)); +#205461 = FILL_AREA_STYLE_COLOUR('',#197425); +#205462 = OVER_RIDING_STYLED_ITEM('overriding color',(#205463),#180955, + #204832); +#205463 = PRESENTATION_STYLE_ASSIGNMENT((#205464)); +#205464 = SURFACE_STYLE_USAGE(.BOTH.,#205465); +#205465 = SURFACE_SIDE_STYLE('',(#205466)); +#205466 = SURFACE_STYLE_FILL_AREA(#205467); +#205467 = FILL_AREA_STYLE('',(#205468)); +#205468 = FILL_AREA_STYLE_COLOUR('',#197425); +#205469 = OVER_RIDING_STYLED_ITEM('overriding color',(#205470),#180981, + #204832); +#205470 = PRESENTATION_STYLE_ASSIGNMENT((#205471)); +#205471 = SURFACE_STYLE_USAGE(.BOTH.,#205472); +#205472 = SURFACE_SIDE_STYLE('',(#205473)); +#205473 = SURFACE_STYLE_FILL_AREA(#205474); +#205474 = FILL_AREA_STYLE('',(#205475)); +#205475 = FILL_AREA_STYLE_COLOUR('',#197425); +#205476 = OVER_RIDING_STYLED_ITEM('overriding color',(#205477),#181030, + #204832); +#205477 = PRESENTATION_STYLE_ASSIGNMENT((#205478)); +#205478 = SURFACE_STYLE_USAGE(.BOTH.,#205479); +#205479 = SURFACE_SIDE_STYLE('',(#205480)); +#205480 = SURFACE_STYLE_FILL_AREA(#205481); +#205481 = FILL_AREA_STYLE('',(#205482)); +#205482 = FILL_AREA_STYLE_COLOUR('',#197425); +#205483 = OVER_RIDING_STYLED_ITEM('overriding color',(#205484),#181057, + #204832); +#205484 = PRESENTATION_STYLE_ASSIGNMENT((#205485)); +#205485 = SURFACE_STYLE_USAGE(.BOTH.,#205486); +#205486 = SURFACE_SIDE_STYLE('',(#205487)); +#205487 = SURFACE_STYLE_FILL_AREA(#205488); +#205488 = FILL_AREA_STYLE('',(#205489)); +#205489 = FILL_AREA_STYLE_COLOUR('',#197425); +#205490 = OVER_RIDING_STYLED_ITEM('overriding color',(#205491),#181084, + #204832); +#205491 = PRESENTATION_STYLE_ASSIGNMENT((#205492)); +#205492 = SURFACE_STYLE_USAGE(.BOTH.,#205493); +#205493 = SURFACE_SIDE_STYLE('',(#205494)); +#205494 = SURFACE_STYLE_FILL_AREA(#205495); +#205495 = FILL_AREA_STYLE('',(#205496)); +#205496 = FILL_AREA_STYLE_COLOUR('',#197425); +#205497 = OVER_RIDING_STYLED_ITEM('overriding color',(#205498),#181133, + #204832); +#205498 = PRESENTATION_STYLE_ASSIGNMENT((#205499)); +#205499 = SURFACE_STYLE_USAGE(.BOTH.,#205500); +#205500 = SURFACE_SIDE_STYLE('',(#205501)); +#205501 = SURFACE_STYLE_FILL_AREA(#205502); +#205502 = FILL_AREA_STYLE('',(#205503)); +#205503 = FILL_AREA_STYLE_COLOUR('',#197425); +#205504 = OVER_RIDING_STYLED_ITEM('overriding color',(#205505),#181159, + #204832); +#205505 = PRESENTATION_STYLE_ASSIGNMENT((#205506)); +#205506 = SURFACE_STYLE_USAGE(.BOTH.,#205507); +#205507 = SURFACE_SIDE_STYLE('',(#205508)); +#205508 = SURFACE_STYLE_FILL_AREA(#205509); +#205509 = FILL_AREA_STYLE('',(#205510)); +#205510 = FILL_AREA_STYLE_COLOUR('',#197425); +#205511 = OVER_RIDING_STYLED_ITEM('overriding color',(#205512),#181185, + #204832); +#205512 = PRESENTATION_STYLE_ASSIGNMENT((#205513)); +#205513 = SURFACE_STYLE_USAGE(.BOTH.,#205514); +#205514 = SURFACE_SIDE_STYLE('',(#205515)); +#205515 = SURFACE_STYLE_FILL_AREA(#205516); +#205516 = FILL_AREA_STYLE('',(#205517)); +#205517 = FILL_AREA_STYLE_COLOUR('',#197425); +#205518 = OVER_RIDING_STYLED_ITEM('overriding color',(#205519),#181192, + #204832); +#205519 = PRESENTATION_STYLE_ASSIGNMENT((#205520)); +#205520 = SURFACE_STYLE_USAGE(.BOTH.,#205521); +#205521 = SURFACE_SIDE_STYLE('',(#205522)); +#205522 = SURFACE_STYLE_FILL_AREA(#205523); +#205523 = FILL_AREA_STYLE('',(#205524)); +#205524 = FILL_AREA_STYLE_COLOUR('',#197425); +#205525 = OVER_RIDING_STYLED_ITEM('overriding color',(#205526),#181267, + #204832); +#205526 = PRESENTATION_STYLE_ASSIGNMENT((#205527)); +#205527 = SURFACE_STYLE_USAGE(.BOTH.,#205528); +#205528 = SURFACE_SIDE_STYLE('',(#205529)); +#205529 = SURFACE_STYLE_FILL_AREA(#205530); +#205530 = FILL_AREA_STYLE('',(#205531)); +#205531 = FILL_AREA_STYLE_COLOUR('',#197425); +#205532 = OVER_RIDING_STYLED_ITEM('overriding color',(#205533),#181548, + #204832); +#205533 = PRESENTATION_STYLE_ASSIGNMENT((#205534)); +#205534 = SURFACE_STYLE_USAGE(.BOTH.,#205535); +#205535 = SURFACE_SIDE_STYLE('',(#205536)); +#205536 = SURFACE_STYLE_FILL_AREA(#205537); +#205537 = FILL_AREA_STYLE('',(#205538)); +#205538 = FILL_AREA_STYLE_COLOUR('',#197425); +#205539 = OVER_RIDING_STYLED_ITEM('overriding color',(#205540),#181596, + #204832); +#205540 = PRESENTATION_STYLE_ASSIGNMENT((#205541)); +#205541 = SURFACE_STYLE_USAGE(.BOTH.,#205542); +#205542 = SURFACE_SIDE_STYLE('',(#205543)); +#205543 = SURFACE_STYLE_FILL_AREA(#205544); +#205544 = FILL_AREA_STYLE('',(#205545)); +#205545 = FILL_AREA_STYLE_COLOUR('',#197425); +#205546 = OVER_RIDING_STYLED_ITEM('overriding color',(#205547),#181815, + #204832); +#205547 = PRESENTATION_STYLE_ASSIGNMENT((#205548)); +#205548 = SURFACE_STYLE_USAGE(.BOTH.,#205549); +#205549 = SURFACE_SIDE_STYLE('',(#205550)); +#205550 = SURFACE_STYLE_FILL_AREA(#205551); +#205551 = FILL_AREA_STYLE('',(#205552)); +#205552 = FILL_AREA_STYLE_COLOUR('',#197425); +#205553 = OVER_RIDING_STYLED_ITEM('overriding color',(#205554),#181841, + #204832); +#205554 = PRESENTATION_STYLE_ASSIGNMENT((#205555)); +#205555 = SURFACE_STYLE_USAGE(.BOTH.,#205556); +#205556 = SURFACE_SIDE_STYLE('',(#205557)); +#205557 = SURFACE_STYLE_FILL_AREA(#205558); +#205558 = FILL_AREA_STYLE('',(#205559)); +#205559 = FILL_AREA_STYLE_COLOUR('',#197425); +#205560 = OVER_RIDING_STYLED_ITEM('overriding color',(#205561),#181867, + #204832); +#205561 = PRESENTATION_STYLE_ASSIGNMENT((#205562)); +#205562 = SURFACE_STYLE_USAGE(.BOTH.,#205563); +#205563 = SURFACE_SIDE_STYLE('',(#205564)); +#205564 = SURFACE_STYLE_FILL_AREA(#205565); +#205565 = FILL_AREA_STYLE('',(#205566)); +#205566 = FILL_AREA_STYLE_COLOUR('',#197425); +#205567 = OVER_RIDING_STYLED_ITEM('overriding color',(#205568),#181916, + #204832); +#205568 = PRESENTATION_STYLE_ASSIGNMENT((#205569)); +#205569 = SURFACE_STYLE_USAGE(.BOTH.,#205570); +#205570 = SURFACE_SIDE_STYLE('',(#205571)); +#205571 = SURFACE_STYLE_FILL_AREA(#205572); +#205572 = FILL_AREA_STYLE('',(#205573)); +#205573 = FILL_AREA_STYLE_COLOUR('',#197425); +#205574 = OVER_RIDING_STYLED_ITEM('overriding color',(#205575),#181943, + #204832); +#205575 = PRESENTATION_STYLE_ASSIGNMENT((#205576)); +#205576 = SURFACE_STYLE_USAGE(.BOTH.,#205577); +#205577 = SURFACE_SIDE_STYLE('',(#205578)); +#205578 = SURFACE_STYLE_FILL_AREA(#205579); +#205579 = FILL_AREA_STYLE('',(#205580)); +#205580 = FILL_AREA_STYLE_COLOUR('',#197425); +#205581 = OVER_RIDING_STYLED_ITEM('overriding color',(#205582),#181970, + #204832); +#205582 = PRESENTATION_STYLE_ASSIGNMENT((#205583)); +#205583 = SURFACE_STYLE_USAGE(.BOTH.,#205584); +#205584 = SURFACE_SIDE_STYLE('',(#205585)); +#205585 = SURFACE_STYLE_FILL_AREA(#205586); +#205586 = FILL_AREA_STYLE('',(#205587)); +#205587 = FILL_AREA_STYLE_COLOUR('',#197425); +#205588 = OVER_RIDING_STYLED_ITEM('overriding color',(#205589),#182019, + #204832); +#205589 = PRESENTATION_STYLE_ASSIGNMENT((#205590)); +#205590 = SURFACE_STYLE_USAGE(.BOTH.,#205591); +#205591 = SURFACE_SIDE_STYLE('',(#205592)); +#205592 = SURFACE_STYLE_FILL_AREA(#205593); +#205593 = FILL_AREA_STYLE('',(#205594)); +#205594 = FILL_AREA_STYLE_COLOUR('',#197425); +#205595 = OVER_RIDING_STYLED_ITEM('overriding color',(#205596),#182045, + #204832); +#205596 = PRESENTATION_STYLE_ASSIGNMENT((#205597)); +#205597 = SURFACE_STYLE_USAGE(.BOTH.,#205598); +#205598 = SURFACE_SIDE_STYLE('',(#205599)); +#205599 = SURFACE_STYLE_FILL_AREA(#205600); +#205600 = FILL_AREA_STYLE('',(#205601)); +#205601 = FILL_AREA_STYLE_COLOUR('',#197425); +#205602 = OVER_RIDING_STYLED_ITEM('overriding color',(#205603),#182071, + #204832); +#205603 = PRESENTATION_STYLE_ASSIGNMENT((#205604)); +#205604 = SURFACE_STYLE_USAGE(.BOTH.,#205605); +#205605 = SURFACE_SIDE_STYLE('',(#205606)); +#205606 = SURFACE_STYLE_FILL_AREA(#205607); +#205607 = FILL_AREA_STYLE('',(#205608)); +#205608 = FILL_AREA_STYLE_COLOUR('',#197425); +#205609 = OVER_RIDING_STYLED_ITEM('overriding color',(#205610),#182078, + #204832); +#205610 = PRESENTATION_STYLE_ASSIGNMENT((#205611)); +#205611 = SURFACE_STYLE_USAGE(.BOTH.,#205612); +#205612 = SURFACE_SIDE_STYLE('',(#205613)); +#205613 = SURFACE_STYLE_FILL_AREA(#205614); +#205614 = FILL_AREA_STYLE('',(#205615)); +#205615 = FILL_AREA_STYLE_COLOUR('',#197425); +#205616 = OVER_RIDING_STYLED_ITEM('overriding color',(#205617),#182153, + #204832); +#205617 = PRESENTATION_STYLE_ASSIGNMENT((#205618)); +#205618 = SURFACE_STYLE_USAGE(.BOTH.,#205619); +#205619 = SURFACE_SIDE_STYLE('',(#205620)); +#205620 = SURFACE_STYLE_FILL_AREA(#205621); +#205621 = FILL_AREA_STYLE('',(#205622)); +#205622 = FILL_AREA_STYLE_COLOUR('',#197425); +#205623 = OVER_RIDING_STYLED_ITEM('overriding color',(#205624),#182434, + #204832); +#205624 = PRESENTATION_STYLE_ASSIGNMENT((#205625)); +#205625 = SURFACE_STYLE_USAGE(.BOTH.,#205626); +#205626 = SURFACE_SIDE_STYLE('',(#205627)); +#205627 = SURFACE_STYLE_FILL_AREA(#205628); +#205628 = FILL_AREA_STYLE('',(#205629)); +#205629 = FILL_AREA_STYLE_COLOUR('',#197425); +#205630 = OVER_RIDING_STYLED_ITEM('overriding color',(#205631),#182482, + #204832); +#205631 = PRESENTATION_STYLE_ASSIGNMENT((#205632)); +#205632 = SURFACE_STYLE_USAGE(.BOTH.,#205633); +#205633 = SURFACE_SIDE_STYLE('',(#205634)); +#205634 = SURFACE_STYLE_FILL_AREA(#205635); +#205635 = FILL_AREA_STYLE('',(#205636)); +#205636 = FILL_AREA_STYLE_COLOUR('',#197425); +#205637 = OVER_RIDING_STYLED_ITEM('overriding color',(#205638),#182701, + #204832); +#205638 = PRESENTATION_STYLE_ASSIGNMENT((#205639)); +#205639 = SURFACE_STYLE_USAGE(.BOTH.,#205640); +#205640 = SURFACE_SIDE_STYLE('',(#205641)); +#205641 = SURFACE_STYLE_FILL_AREA(#205642); +#205642 = FILL_AREA_STYLE('',(#205643)); +#205643 = FILL_AREA_STYLE_COLOUR('',#197425); +#205644 = OVER_RIDING_STYLED_ITEM('overriding color',(#205645),#182727, + #204832); +#205645 = PRESENTATION_STYLE_ASSIGNMENT((#205646)); +#205646 = SURFACE_STYLE_USAGE(.BOTH.,#205647); +#205647 = SURFACE_SIDE_STYLE('',(#205648)); +#205648 = SURFACE_STYLE_FILL_AREA(#205649); +#205649 = FILL_AREA_STYLE('',(#205650)); +#205650 = FILL_AREA_STYLE_COLOUR('',#197425); +#205651 = OVER_RIDING_STYLED_ITEM('overriding color',(#205652),#182753, + #204832); +#205652 = PRESENTATION_STYLE_ASSIGNMENT((#205653)); +#205653 = SURFACE_STYLE_USAGE(.BOTH.,#205654); +#205654 = SURFACE_SIDE_STYLE('',(#205655)); +#205655 = SURFACE_STYLE_FILL_AREA(#205656); +#205656 = FILL_AREA_STYLE('',(#205657)); +#205657 = FILL_AREA_STYLE_COLOUR('',#197425); +#205658 = OVER_RIDING_STYLED_ITEM('overriding color',(#205659),#182802, + #204832); +#205659 = PRESENTATION_STYLE_ASSIGNMENT((#205660)); +#205660 = SURFACE_STYLE_USAGE(.BOTH.,#205661); +#205661 = SURFACE_SIDE_STYLE('',(#205662)); +#205662 = SURFACE_STYLE_FILL_AREA(#205663); +#205663 = FILL_AREA_STYLE('',(#205664)); +#205664 = FILL_AREA_STYLE_COLOUR('',#197425); +#205665 = OVER_RIDING_STYLED_ITEM('overriding color',(#205666),#182829, + #204832); +#205666 = PRESENTATION_STYLE_ASSIGNMENT((#205667)); +#205667 = SURFACE_STYLE_USAGE(.BOTH.,#205668); +#205668 = SURFACE_SIDE_STYLE('',(#205669)); +#205669 = SURFACE_STYLE_FILL_AREA(#205670); +#205670 = FILL_AREA_STYLE('',(#205671)); +#205671 = FILL_AREA_STYLE_COLOUR('',#197425); +#205672 = OVER_RIDING_STYLED_ITEM('overriding color',(#205673),#182856, + #204832); +#205673 = PRESENTATION_STYLE_ASSIGNMENT((#205674)); +#205674 = SURFACE_STYLE_USAGE(.BOTH.,#205675); +#205675 = SURFACE_SIDE_STYLE('',(#205676)); +#205676 = SURFACE_STYLE_FILL_AREA(#205677); +#205677 = FILL_AREA_STYLE('',(#205678)); +#205678 = FILL_AREA_STYLE_COLOUR('',#197425); +#205679 = OVER_RIDING_STYLED_ITEM('overriding color',(#205680),#182905, + #204832); +#205680 = PRESENTATION_STYLE_ASSIGNMENT((#205681)); +#205681 = SURFACE_STYLE_USAGE(.BOTH.,#205682); +#205682 = SURFACE_SIDE_STYLE('',(#205683)); +#205683 = SURFACE_STYLE_FILL_AREA(#205684); +#205684 = FILL_AREA_STYLE('',(#205685)); +#205685 = FILL_AREA_STYLE_COLOUR('',#197425); +#205686 = OVER_RIDING_STYLED_ITEM('overriding color',(#205687),#182931, + #204832); +#205687 = PRESENTATION_STYLE_ASSIGNMENT((#205688)); +#205688 = SURFACE_STYLE_USAGE(.BOTH.,#205689); +#205689 = SURFACE_SIDE_STYLE('',(#205690)); +#205690 = SURFACE_STYLE_FILL_AREA(#205691); +#205691 = FILL_AREA_STYLE('',(#205692)); +#205692 = FILL_AREA_STYLE_COLOUR('',#197425); +#205693 = OVER_RIDING_STYLED_ITEM('overriding color',(#205694),#182957, + #204832); +#205694 = PRESENTATION_STYLE_ASSIGNMENT((#205695)); +#205695 = SURFACE_STYLE_USAGE(.BOTH.,#205696); +#205696 = SURFACE_SIDE_STYLE('',(#205697)); +#205697 = SURFACE_STYLE_FILL_AREA(#205698); +#205698 = FILL_AREA_STYLE('',(#205699)); +#205699 = FILL_AREA_STYLE_COLOUR('',#197425); +#205700 = OVER_RIDING_STYLED_ITEM('overriding color',(#205701),#182964, + #204832); +#205701 = PRESENTATION_STYLE_ASSIGNMENT((#205702)); +#205702 = SURFACE_STYLE_USAGE(.BOTH.,#205703); +#205703 = SURFACE_SIDE_STYLE('',(#205704)); +#205704 = SURFACE_STYLE_FILL_AREA(#205705); +#205705 = FILL_AREA_STYLE('',(#205706)); +#205706 = FILL_AREA_STYLE_COLOUR('',#197425); +#205707 = OVER_RIDING_STYLED_ITEM('overriding color',(#205708),#183039, + #204832); +#205708 = PRESENTATION_STYLE_ASSIGNMENT((#205709)); +#205709 = SURFACE_STYLE_USAGE(.BOTH.,#205710); +#205710 = SURFACE_SIDE_STYLE('',(#205711)); +#205711 = SURFACE_STYLE_FILL_AREA(#205712); +#205712 = FILL_AREA_STYLE('',(#205713)); +#205713 = FILL_AREA_STYLE_COLOUR('',#197425); +#205714 = OVER_RIDING_STYLED_ITEM('overriding color',(#205715),#183320, + #204832); +#205715 = PRESENTATION_STYLE_ASSIGNMENT((#205716)); +#205716 = SURFACE_STYLE_USAGE(.BOTH.,#205717); +#205717 = SURFACE_SIDE_STYLE('',(#205718)); +#205718 = SURFACE_STYLE_FILL_AREA(#205719); +#205719 = FILL_AREA_STYLE('',(#205720)); +#205720 = FILL_AREA_STYLE_COLOUR('',#197425); +#205721 = OVER_RIDING_STYLED_ITEM('overriding color',(#205722),#183368, + #204832); +#205722 = PRESENTATION_STYLE_ASSIGNMENT((#205723)); +#205723 = SURFACE_STYLE_USAGE(.BOTH.,#205724); +#205724 = SURFACE_SIDE_STYLE('',(#205725)); +#205725 = SURFACE_STYLE_FILL_AREA(#205726); +#205726 = FILL_AREA_STYLE('',(#205727)); +#205727 = FILL_AREA_STYLE_COLOUR('',#197425); +#205728 = OVER_RIDING_STYLED_ITEM('overriding color',(#205729),#183587, + #204832); +#205729 = PRESENTATION_STYLE_ASSIGNMENT((#205730)); +#205730 = SURFACE_STYLE_USAGE(.BOTH.,#205731); +#205731 = SURFACE_SIDE_STYLE('',(#205732)); +#205732 = SURFACE_STYLE_FILL_AREA(#205733); +#205733 = FILL_AREA_STYLE('',(#205734)); +#205734 = FILL_AREA_STYLE_COLOUR('',#197425); +#205735 = OVER_RIDING_STYLED_ITEM('overriding color',(#205736),#183613, + #204832); +#205736 = PRESENTATION_STYLE_ASSIGNMENT((#205737)); +#205737 = SURFACE_STYLE_USAGE(.BOTH.,#205738); +#205738 = SURFACE_SIDE_STYLE('',(#205739)); +#205739 = SURFACE_STYLE_FILL_AREA(#205740); +#205740 = FILL_AREA_STYLE('',(#205741)); +#205741 = FILL_AREA_STYLE_COLOUR('',#197425); +#205742 = OVER_RIDING_STYLED_ITEM('overriding color',(#205743),#183639, + #204832); +#205743 = PRESENTATION_STYLE_ASSIGNMENT((#205744)); +#205744 = SURFACE_STYLE_USAGE(.BOTH.,#205745); +#205745 = SURFACE_SIDE_STYLE('',(#205746)); +#205746 = SURFACE_STYLE_FILL_AREA(#205747); +#205747 = FILL_AREA_STYLE('',(#205748)); +#205748 = FILL_AREA_STYLE_COLOUR('',#197425); +#205749 = OVER_RIDING_STYLED_ITEM('overriding color',(#205750),#183688, + #204832); +#205750 = PRESENTATION_STYLE_ASSIGNMENT((#205751)); +#205751 = SURFACE_STYLE_USAGE(.BOTH.,#205752); +#205752 = SURFACE_SIDE_STYLE('',(#205753)); +#205753 = SURFACE_STYLE_FILL_AREA(#205754); +#205754 = FILL_AREA_STYLE('',(#205755)); +#205755 = FILL_AREA_STYLE_COLOUR('',#197425); +#205756 = OVER_RIDING_STYLED_ITEM('overriding color',(#205757),#183715, + #204832); +#205757 = PRESENTATION_STYLE_ASSIGNMENT((#205758)); +#205758 = SURFACE_STYLE_USAGE(.BOTH.,#205759); +#205759 = SURFACE_SIDE_STYLE('',(#205760)); +#205760 = SURFACE_STYLE_FILL_AREA(#205761); +#205761 = FILL_AREA_STYLE('',(#205762)); +#205762 = FILL_AREA_STYLE_COLOUR('',#197425); +#205763 = OVER_RIDING_STYLED_ITEM('overriding color',(#205764),#183742, + #204832); +#205764 = PRESENTATION_STYLE_ASSIGNMENT((#205765)); +#205765 = SURFACE_STYLE_USAGE(.BOTH.,#205766); +#205766 = SURFACE_SIDE_STYLE('',(#205767)); +#205767 = SURFACE_STYLE_FILL_AREA(#205768); +#205768 = FILL_AREA_STYLE('',(#205769)); +#205769 = FILL_AREA_STYLE_COLOUR('',#197425); +#205770 = OVER_RIDING_STYLED_ITEM('overriding color',(#205771),#183791, + #204832); +#205771 = PRESENTATION_STYLE_ASSIGNMENT((#205772)); +#205772 = SURFACE_STYLE_USAGE(.BOTH.,#205773); +#205773 = SURFACE_SIDE_STYLE('',(#205774)); +#205774 = SURFACE_STYLE_FILL_AREA(#205775); +#205775 = FILL_AREA_STYLE('',(#205776)); +#205776 = FILL_AREA_STYLE_COLOUR('',#197425); +#205777 = OVER_RIDING_STYLED_ITEM('overriding color',(#205778),#183817, + #204832); +#205778 = PRESENTATION_STYLE_ASSIGNMENT((#205779)); +#205779 = SURFACE_STYLE_USAGE(.BOTH.,#205780); +#205780 = SURFACE_SIDE_STYLE('',(#205781)); +#205781 = SURFACE_STYLE_FILL_AREA(#205782); +#205782 = FILL_AREA_STYLE('',(#205783)); +#205783 = FILL_AREA_STYLE_COLOUR('',#197425); +#205784 = OVER_RIDING_STYLED_ITEM('overriding color',(#205785),#183843, + #204832); +#205785 = PRESENTATION_STYLE_ASSIGNMENT((#205786)); +#205786 = SURFACE_STYLE_USAGE(.BOTH.,#205787); +#205787 = SURFACE_SIDE_STYLE('',(#205788)); +#205788 = SURFACE_STYLE_FILL_AREA(#205789); +#205789 = FILL_AREA_STYLE('',(#205790)); +#205790 = FILL_AREA_STYLE_COLOUR('',#197425); +#205791 = OVER_RIDING_STYLED_ITEM('overriding color',(#205792),#183850, + #204832); +#205792 = PRESENTATION_STYLE_ASSIGNMENT((#205793)); +#205793 = SURFACE_STYLE_USAGE(.BOTH.,#205794); +#205794 = SURFACE_SIDE_STYLE('',(#205795)); +#205795 = SURFACE_STYLE_FILL_AREA(#205796); +#205796 = FILL_AREA_STYLE('',(#205797)); +#205797 = FILL_AREA_STYLE_COLOUR('',#197425); +#205798 = OVER_RIDING_STYLED_ITEM('overriding color',(#205799),#183925, + #204832); +#205799 = PRESENTATION_STYLE_ASSIGNMENT((#205800)); +#205800 = SURFACE_STYLE_USAGE(.BOTH.,#205801); +#205801 = SURFACE_SIDE_STYLE('',(#205802)); +#205802 = SURFACE_STYLE_FILL_AREA(#205803); +#205803 = FILL_AREA_STYLE('',(#205804)); +#205804 = FILL_AREA_STYLE_COLOUR('',#197425); +#205805 = OVER_RIDING_STYLED_ITEM('overriding color',(#205806),#184206, + #204832); +#205806 = PRESENTATION_STYLE_ASSIGNMENT((#205807)); +#205807 = SURFACE_STYLE_USAGE(.BOTH.,#205808); +#205808 = SURFACE_SIDE_STYLE('',(#205809)); +#205809 = SURFACE_STYLE_FILL_AREA(#205810); +#205810 = FILL_AREA_STYLE('',(#205811)); +#205811 = FILL_AREA_STYLE_COLOUR('',#197425); +#205812 = OVER_RIDING_STYLED_ITEM('overriding color',(#205813),#184254, + #204832); +#205813 = PRESENTATION_STYLE_ASSIGNMENT((#205814)); +#205814 = SURFACE_STYLE_USAGE(.BOTH.,#205815); +#205815 = SURFACE_SIDE_STYLE('',(#205816)); +#205816 = SURFACE_STYLE_FILL_AREA(#205817); +#205817 = FILL_AREA_STYLE('',(#205818)); +#205818 = FILL_AREA_STYLE_COLOUR('',#197425); +#205819 = OVER_RIDING_STYLED_ITEM('overriding color',(#205820),#184473, + #204832); +#205820 = PRESENTATION_STYLE_ASSIGNMENT((#205821)); +#205821 = SURFACE_STYLE_USAGE(.BOTH.,#205822); +#205822 = SURFACE_SIDE_STYLE('',(#205823)); +#205823 = SURFACE_STYLE_FILL_AREA(#205824); +#205824 = FILL_AREA_STYLE('',(#205825)); +#205825 = FILL_AREA_STYLE_COLOUR('',#197425); +#205826 = OVER_RIDING_STYLED_ITEM('overriding color',(#205827),#184499, + #204832); +#205827 = PRESENTATION_STYLE_ASSIGNMENT((#205828)); +#205828 = SURFACE_STYLE_USAGE(.BOTH.,#205829); +#205829 = SURFACE_SIDE_STYLE('',(#205830)); +#205830 = SURFACE_STYLE_FILL_AREA(#205831); +#205831 = FILL_AREA_STYLE('',(#205832)); +#205832 = FILL_AREA_STYLE_COLOUR('',#197425); +#205833 = OVER_RIDING_STYLED_ITEM('overriding color',(#205834),#184525, + #204832); +#205834 = PRESENTATION_STYLE_ASSIGNMENT((#205835)); +#205835 = SURFACE_STYLE_USAGE(.BOTH.,#205836); +#205836 = SURFACE_SIDE_STYLE('',(#205837)); +#205837 = SURFACE_STYLE_FILL_AREA(#205838); +#205838 = FILL_AREA_STYLE('',(#205839)); +#205839 = FILL_AREA_STYLE_COLOUR('',#197425); +#205840 = OVER_RIDING_STYLED_ITEM('overriding color',(#205841),#184574, + #204832); +#205841 = PRESENTATION_STYLE_ASSIGNMENT((#205842)); +#205842 = SURFACE_STYLE_USAGE(.BOTH.,#205843); +#205843 = SURFACE_SIDE_STYLE('',(#205844)); +#205844 = SURFACE_STYLE_FILL_AREA(#205845); +#205845 = FILL_AREA_STYLE('',(#205846)); +#205846 = FILL_AREA_STYLE_COLOUR('',#197425); +#205847 = OVER_RIDING_STYLED_ITEM('overriding color',(#205848),#184601, + #204832); +#205848 = PRESENTATION_STYLE_ASSIGNMENT((#205849)); +#205849 = SURFACE_STYLE_USAGE(.BOTH.,#205850); +#205850 = SURFACE_SIDE_STYLE('',(#205851)); +#205851 = SURFACE_STYLE_FILL_AREA(#205852); +#205852 = FILL_AREA_STYLE('',(#205853)); +#205853 = FILL_AREA_STYLE_COLOUR('',#197425); +#205854 = OVER_RIDING_STYLED_ITEM('overriding color',(#205855),#184628, + #204832); +#205855 = PRESENTATION_STYLE_ASSIGNMENT((#205856)); +#205856 = SURFACE_STYLE_USAGE(.BOTH.,#205857); +#205857 = SURFACE_SIDE_STYLE('',(#205858)); +#205858 = SURFACE_STYLE_FILL_AREA(#205859); +#205859 = FILL_AREA_STYLE('',(#205860)); +#205860 = FILL_AREA_STYLE_COLOUR('',#197425); +#205861 = OVER_RIDING_STYLED_ITEM('overriding color',(#205862),#184677, + #204832); +#205862 = PRESENTATION_STYLE_ASSIGNMENT((#205863)); +#205863 = SURFACE_STYLE_USAGE(.BOTH.,#205864); +#205864 = SURFACE_SIDE_STYLE('',(#205865)); +#205865 = SURFACE_STYLE_FILL_AREA(#205866); +#205866 = FILL_AREA_STYLE('',(#205867)); +#205867 = FILL_AREA_STYLE_COLOUR('',#197425); +#205868 = OVER_RIDING_STYLED_ITEM('overriding color',(#205869),#184703, + #204832); +#205869 = PRESENTATION_STYLE_ASSIGNMENT((#205870)); +#205870 = SURFACE_STYLE_USAGE(.BOTH.,#205871); +#205871 = SURFACE_SIDE_STYLE('',(#205872)); +#205872 = SURFACE_STYLE_FILL_AREA(#205873); +#205873 = FILL_AREA_STYLE('',(#205874)); +#205874 = FILL_AREA_STYLE_COLOUR('',#197425); +#205875 = OVER_RIDING_STYLED_ITEM('overriding color',(#205876),#184729, + #204832); +#205876 = PRESENTATION_STYLE_ASSIGNMENT((#205877)); +#205877 = SURFACE_STYLE_USAGE(.BOTH.,#205878); +#205878 = SURFACE_SIDE_STYLE('',(#205879)); +#205879 = SURFACE_STYLE_FILL_AREA(#205880); +#205880 = FILL_AREA_STYLE('',(#205881)); +#205881 = FILL_AREA_STYLE_COLOUR('',#197425); +#205882 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #205883),#169365); +#205883 = STYLED_ITEM('color',(#205884),#169035); +#205884 = PRESENTATION_STYLE_ASSIGNMENT((#205885,#205891)); +#205885 = SURFACE_STYLE_USAGE(.BOTH.,#205886); +#205886 = SURFACE_SIDE_STYLE('',(#205887)); +#205887 = SURFACE_STYLE_FILL_AREA(#205888); +#205888 = FILL_AREA_STYLE('',(#205889)); +#205889 = FILL_AREA_STYLE_COLOUR('',#205890); +#205890 = COLOUR_RGB('',0.86274510622,0.850980401039,0.780392169952); +#205891 = CURVE_STYLE('',#205892,POSITIVE_LENGTH_MEASURE(0.1),#205890); +#205892 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#205893 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #205894,#205901,#205909,#205916,#205923,#205930,#205937,#205944, + #205951,#205958,#205965,#205972,#205979,#205986,#205993,#206000, + #206007,#206014,#206021,#206028,#206035,#206042,#206049,#206056, + #206063,#206070,#206077,#206084,#206091,#206098,#206105,#206112, + #206119,#206126,#206133,#206140,#206147,#206154,#206161,#206168, + #206175,#206182,#206189,#206196,#206203,#206210,#206217,#206224, + #206231,#206238,#206245,#206252,#206259,#206266,#206273,#206280, + #206287,#206294,#206301,#206308,#206315,#206322,#206329,#206336, + #206343,#206350,#206357,#206364,#206371,#206378,#206385,#206392, + #206399,#206406,#206413,#206420,#206427,#206434,#206441,#206448, + #206455,#206462,#206469,#206476,#206483,#206490,#206497,#206504, + #206511,#206518,#206525),#39731); +#205894 = STYLED_ITEM('color',(#205895),#31225); +#205895 = PRESENTATION_STYLE_ASSIGNMENT((#205896)); +#205896 = SURFACE_STYLE_USAGE(.BOTH.,#205897); +#205897 = SURFACE_SIDE_STYLE('',(#205898)); +#205898 = SURFACE_STYLE_FILL_AREA(#205899); +#205899 = FILL_AREA_STYLE('',(#205900)); +#205900 = FILL_AREA_STYLE_COLOUR('',#197425); +#205901 = OVER_RIDING_STYLED_ITEM('overriding color',(#205902),#31227, + #205894); +#205902 = PRESENTATION_STYLE_ASSIGNMENT((#205903)); +#205903 = SURFACE_STYLE_USAGE(.BOTH.,#205904); +#205904 = SURFACE_SIDE_STYLE('',(#205905)); +#205905 = SURFACE_STYLE_FILL_AREA(#205906); +#205906 = FILL_AREA_STYLE('',(#205907)); +#205907 = FILL_AREA_STYLE_COLOUR('',#205908); +#205908 = COLOUR_RGB('',0.909803926945,0.443137258291, + 3.137255087495E-002); +#205909 = OVER_RIDING_STYLED_ITEM('overriding color',(#205910),#33439, + #205894); #205910 = PRESENTATION_STYLE_ASSIGNMENT((#205911)); #205911 = SURFACE_STYLE_USAGE(.BOTH.,#205912); #205912 = SURFACE_SIDE_STYLE('',(#205913)); #205913 = SURFACE_STYLE_FILL_AREA(#205914); #205914 = FILL_AREA_STYLE('',(#205915)); -#205915 = FILL_AREA_STYLE_COLOUR('',#201781); -#205916 = OVER_RIDING_STYLED_ITEM('overriding color',(#205917),#184359, - #205874); +#205915 = FILL_AREA_STYLE_COLOUR('',#198418); +#205916 = OVER_RIDING_STYLED_ITEM('overriding color',(#205917),#33543, + #205894); #205917 = PRESENTATION_STYLE_ASSIGNMENT((#205918)); #205918 = SURFACE_STYLE_USAGE(.BOTH.,#205919); #205919 = SURFACE_SIDE_STYLE('',(#205920)); #205920 = SURFACE_STYLE_FILL_AREA(#205921); #205921 = FILL_AREA_STYLE('',(#205922)); -#205922 = FILL_AREA_STYLE_COLOUR('',#201781); -#205923 = OVER_RIDING_STYLED_ITEM('overriding color',(#205924),#184634, - #205874); +#205922 = FILL_AREA_STYLE_COLOUR('',#198418); +#205923 = OVER_RIDING_STYLED_ITEM('overriding color',(#205924),#33647, + #205894); #205924 = PRESENTATION_STYLE_ASSIGNMENT((#205925)); #205925 = SURFACE_STYLE_USAGE(.BOTH.,#205926); #205926 = SURFACE_SIDE_STYLE('',(#205927)); #205927 = SURFACE_STYLE_FILL_AREA(#205928); #205928 = FILL_AREA_STYLE('',(#205929)); -#205929 = FILL_AREA_STYLE_COLOUR('',#201781); -#205930 = OVER_RIDING_STYLED_ITEM('overriding color',(#205931),#184909, - #205874); +#205929 = FILL_AREA_STYLE_COLOUR('',#198418); +#205930 = OVER_RIDING_STYLED_ITEM('overriding color',(#205931),#33764, + #205894); #205931 = PRESENTATION_STYLE_ASSIGNMENT((#205932)); #205932 = SURFACE_STYLE_USAGE(.BOTH.,#205933); #205933 = SURFACE_SIDE_STYLE('',(#205934)); #205934 = SURFACE_STYLE_FILL_AREA(#205935); #205935 = FILL_AREA_STYLE('',(#205936)); -#205936 = FILL_AREA_STYLE_COLOUR('',#201781); -#205937 = OVER_RIDING_STYLED_ITEM('overriding color',(#205938),#185184, - #205874); +#205936 = FILL_AREA_STYLE_COLOUR('',#198418); +#205937 = OVER_RIDING_STYLED_ITEM('overriding color',(#205938),#33876, + #205894); #205938 = PRESENTATION_STYLE_ASSIGNMENT((#205939)); #205939 = SURFACE_STYLE_USAGE(.BOTH.,#205940); #205940 = SURFACE_SIDE_STYLE('',(#205941)); #205941 = SURFACE_STYLE_FILL_AREA(#205942); #205942 = FILL_AREA_STYLE('',(#205943)); -#205943 = FILL_AREA_STYLE_COLOUR('',#201781); -#205944 = OVER_RIDING_STYLED_ITEM('overriding color',(#205945),#185336, - #205874); +#205943 = FILL_AREA_STYLE_COLOUR('',#198418); +#205944 = OVER_RIDING_STYLED_ITEM('overriding color',(#205945),#33955, + #205894); #205945 = PRESENTATION_STYLE_ASSIGNMENT((#205946)); #205946 = SURFACE_STYLE_USAGE(.BOTH.,#205947); #205947 = SURFACE_SIDE_STYLE('',(#205948)); #205948 = SURFACE_STYLE_FILL_AREA(#205949); #205949 = FILL_AREA_STYLE('',(#205950)); -#205950 = FILL_AREA_STYLE_COLOUR('',#201781); -#205951 = OVER_RIDING_STYLED_ITEM('overriding color',(#205952),#185803, - #205874); +#205950 = FILL_AREA_STYLE_COLOUR('',#198418); +#205951 = OVER_RIDING_STYLED_ITEM('overriding color',(#205952),#34029, + #205894); #205952 = PRESENTATION_STYLE_ASSIGNMENT((#205953)); #205953 = SURFACE_STYLE_USAGE(.BOTH.,#205954); #205954 = SURFACE_SIDE_STYLE('',(#205955)); #205955 = SURFACE_STYLE_FILL_AREA(#205956); #205956 = FILL_AREA_STYLE('',(#205957)); -#205957 = FILL_AREA_STYLE_COLOUR('',#201781); -#205958 = OVER_RIDING_STYLED_ITEM('overriding color',(#205959),#186247, - #205874); +#205957 = FILL_AREA_STYLE_COLOUR('',#198418); +#205958 = OVER_RIDING_STYLED_ITEM('overriding color',(#205959),#34084, + #205894); #205959 = PRESENTATION_STYLE_ASSIGNMENT((#205960)); #205960 = SURFACE_STYLE_USAGE(.BOTH.,#205961); #205961 = SURFACE_SIDE_STYLE('',(#205962)); #205962 = SURFACE_STYLE_FILL_AREA(#205963); #205963 = FILL_AREA_STYLE('',(#205964)); -#205964 = FILL_AREA_STYLE_COLOUR('',#201781); -#205965 = OVER_RIDING_STYLED_ITEM('overriding color',(#205966),#186416, - #205874); +#205964 = FILL_AREA_STYLE_COLOUR('',#198418); +#205965 = OVER_RIDING_STYLED_ITEM('overriding color',(#205966),#34134, + #205894); #205966 = PRESENTATION_STYLE_ASSIGNMENT((#205967)); #205967 = SURFACE_STYLE_USAGE(.BOTH.,#205968); #205968 = SURFACE_SIDE_STYLE('',(#205969)); #205969 = SURFACE_STYLE_FILL_AREA(#205970); #205970 = FILL_AREA_STYLE('',(#205971)); -#205971 = FILL_AREA_STYLE_COLOUR('',#201781); -#205972 = OVER_RIDING_STYLED_ITEM('overriding color',(#205973),#186609, - #205874); +#205971 = FILL_AREA_STYLE_COLOUR('',#198418); +#205972 = OVER_RIDING_STYLED_ITEM('overriding color',(#205973),#34217, + #205894); #205973 = PRESENTATION_STYLE_ASSIGNMENT((#205974)); #205974 = SURFACE_STYLE_USAGE(.BOTH.,#205975); #205975 = SURFACE_SIDE_STYLE('',(#205976)); #205976 = SURFACE_STYLE_FILL_AREA(#205977); #205977 = FILL_AREA_STYLE('',(#205978)); -#205978 = FILL_AREA_STYLE_COLOUR('',#201781); -#205979 = OVER_RIDING_STYLED_ITEM('overriding color',(#205980),#186755, - #205874); +#205978 = FILL_AREA_STYLE_COLOUR('',#198418); +#205979 = OVER_RIDING_STYLED_ITEM('overriding color',(#205980),#34295, + #205894); #205980 = PRESENTATION_STYLE_ASSIGNMENT((#205981)); #205981 = SURFACE_STYLE_USAGE(.BOTH.,#205982); #205982 = SURFACE_SIDE_STYLE('',(#205983)); #205983 = SURFACE_STYLE_FILL_AREA(#205984); #205984 = FILL_AREA_STYLE('',(#205985)); -#205985 = FILL_AREA_STYLE_COLOUR('',#201781); -#205986 = OVER_RIDING_STYLED_ITEM('overriding color',(#205987),#186925, - #205874); +#205985 = FILL_AREA_STYLE_COLOUR('',#198418); +#205986 = OVER_RIDING_STYLED_ITEM('overriding color',(#205987),#34394, + #205894); #205987 = PRESENTATION_STYLE_ASSIGNMENT((#205988)); #205988 = SURFACE_STYLE_USAGE(.BOTH.,#205989); #205989 = SURFACE_SIDE_STYLE('',(#205990)); #205990 = SURFACE_STYLE_FILL_AREA(#205991); #205991 = FILL_AREA_STYLE('',(#205992)); -#205992 = FILL_AREA_STYLE_COLOUR('',#201781); -#205993 = OVER_RIDING_STYLED_ITEM('overriding color',(#205994),#187246, - #205874); +#205992 = FILL_AREA_STYLE_COLOUR('',#198418); +#205993 = OVER_RIDING_STYLED_ITEM('overriding color',(#205994),#34493, + #205894); #205994 = PRESENTATION_STYLE_ASSIGNMENT((#205995)); #205995 = SURFACE_STYLE_USAGE(.BOTH.,#205996); #205996 = SURFACE_SIDE_STYLE('',(#205997)); #205997 = SURFACE_STYLE_FILL_AREA(#205998); #205998 = FILL_AREA_STYLE('',(#205999)); -#205999 = FILL_AREA_STYLE_COLOUR('',#201781); -#206000 = OVER_RIDING_STYLED_ITEM('overriding color',(#206001),#187358, - #205874); +#205999 = FILL_AREA_STYLE_COLOUR('',#198418); +#206000 = OVER_RIDING_STYLED_ITEM('overriding color',(#206001),#34524, + #205894); #206001 = PRESENTATION_STYLE_ASSIGNMENT((#206002)); #206002 = SURFACE_STYLE_USAGE(.BOTH.,#206003); #206003 = SURFACE_SIDE_STYLE('',(#206004)); #206004 = SURFACE_STYLE_FILL_AREA(#206005); #206005 = FILL_AREA_STYLE('',(#206006)); -#206006 = FILL_AREA_STYLE_COLOUR('',#201781); -#206007 = OVER_RIDING_STYLED_ITEM('overriding color',(#206008),#187493, - #205874); +#206006 = FILL_AREA_STYLE_COLOUR('',#198418); +#206007 = OVER_RIDING_STYLED_ITEM('overriding color',(#206008),#34555, + #205894); #206008 = PRESENTATION_STYLE_ASSIGNMENT((#206009)); #206009 = SURFACE_STYLE_USAGE(.BOTH.,#206010); #206010 = SURFACE_SIDE_STYLE('',(#206011)); #206011 = SURFACE_STYLE_FILL_AREA(#206012); #206012 = FILL_AREA_STYLE('',(#206013)); -#206013 = FILL_AREA_STYLE_COLOUR('',#201781); -#206014 = OVER_RIDING_STYLED_ITEM('overriding color',(#206015),#187861, - #205874); +#206013 = FILL_AREA_STYLE_COLOUR('',#198418); +#206014 = OVER_RIDING_STYLED_ITEM('overriding color',(#206015),#34611, + #205894); #206015 = PRESENTATION_STYLE_ASSIGNMENT((#206016)); #206016 = SURFACE_STYLE_USAGE(.BOTH.,#206017); #206017 = SURFACE_SIDE_STYLE('',(#206018)); #206018 = SURFACE_STYLE_FILL_AREA(#206019); #206019 = FILL_AREA_STYLE('',(#206020)); -#206020 = FILL_AREA_STYLE_COLOUR('',#201028); -#206021 = OVER_RIDING_STYLED_ITEM('overriding color',(#206022),#187936, - #205874); +#206020 = FILL_AREA_STYLE_COLOUR('',#198418); +#206021 = OVER_RIDING_STYLED_ITEM('overriding color',(#206022),#34662, + #205894); #206022 = PRESENTATION_STYLE_ASSIGNMENT((#206023)); #206023 = SURFACE_STYLE_USAGE(.BOTH.,#206024); #206024 = SURFACE_SIDE_STYLE('',(#206025)); #206025 = SURFACE_STYLE_FILL_AREA(#206026); #206026 = FILL_AREA_STYLE('',(#206027)); -#206027 = FILL_AREA_STYLE_COLOUR('',#201028); -#206028 = OVER_RIDING_STYLED_ITEM('overriding color',(#206029),#188011, - #205874); +#206027 = FILL_AREA_STYLE_COLOUR('',#198418); +#206028 = OVER_RIDING_STYLED_ITEM('overriding color',(#206029),#34758, + #205894); #206029 = PRESENTATION_STYLE_ASSIGNMENT((#206030)); #206030 = SURFACE_STYLE_USAGE(.BOTH.,#206031); #206031 = SURFACE_SIDE_STYLE('',(#206032)); #206032 = SURFACE_STYLE_FILL_AREA(#206033); #206033 = FILL_AREA_STYLE('',(#206034)); -#206034 = FILL_AREA_STYLE_COLOUR('',#201028); -#206035 = OVER_RIDING_STYLED_ITEM('overriding color',(#206036),#188265, - #205874); +#206034 = FILL_AREA_STYLE_COLOUR('',#205908); +#206035 = OVER_RIDING_STYLED_ITEM('overriding color',(#206036),#34803, + #205894); #206036 = PRESENTATION_STYLE_ASSIGNMENT((#206037)); #206037 = SURFACE_STYLE_USAGE(.BOTH.,#206038); #206038 = SURFACE_SIDE_STYLE('',(#206039)); #206039 = SURFACE_STYLE_FILL_AREA(#206040); #206040 = FILL_AREA_STYLE('',(#206041)); -#206041 = FILL_AREA_STYLE_COLOUR('',#201028); -#206042 = OVER_RIDING_STYLED_ITEM('overriding color',(#206043),#188484, - #205874); +#206041 = FILL_AREA_STYLE_COLOUR('',#198418); +#206042 = OVER_RIDING_STYLED_ITEM('overriding color',(#206043),#34899, + #205894); #206043 = PRESENTATION_STYLE_ASSIGNMENT((#206044)); #206044 = SURFACE_STYLE_USAGE(.BOTH.,#206045); #206045 = SURFACE_SIDE_STYLE('',(#206046)); #206046 = SURFACE_STYLE_FILL_AREA(#206047); #206047 = FILL_AREA_STYLE('',(#206048)); -#206048 = FILL_AREA_STYLE_COLOUR('',#201028); -#206049 = OVER_RIDING_STYLED_ITEM('overriding color',(#206050),#188510, - #205874); +#206048 = FILL_AREA_STYLE_COLOUR('',#205908); +#206049 = OVER_RIDING_STYLED_ITEM('overriding color',(#206050),#34944, + #205894); #206050 = PRESENTATION_STYLE_ASSIGNMENT((#206051)); #206051 = SURFACE_STYLE_USAGE(.BOTH.,#206052); #206052 = SURFACE_SIDE_STYLE('',(#206053)); #206053 = SURFACE_STYLE_FILL_AREA(#206054); #206054 = FILL_AREA_STYLE('',(#206055)); -#206055 = FILL_AREA_STYLE_COLOUR('',#201028); -#206056 = OVER_RIDING_STYLED_ITEM('overriding color',(#206057),#188536, - #205874); +#206055 = FILL_AREA_STYLE_COLOUR('',#205908); +#206056 = OVER_RIDING_STYLED_ITEM('overriding color',(#206057),#34989, + #205894); #206057 = PRESENTATION_STYLE_ASSIGNMENT((#206058)); #206058 = SURFACE_STYLE_USAGE(.BOTH.,#206059); #206059 = SURFACE_SIDE_STYLE('',(#206060)); #206060 = SURFACE_STYLE_FILL_AREA(#206061); #206061 = FILL_AREA_STYLE('',(#206062)); -#206062 = FILL_AREA_STYLE_COLOUR('',#201028); -#206063 = OVER_RIDING_STYLED_ITEM('overriding color',(#206064),#188585, - #205874); +#206062 = FILL_AREA_STYLE_COLOUR('',#198418); +#206063 = OVER_RIDING_STYLED_ITEM('overriding color',(#206064),#35034, + #205894); #206064 = PRESENTATION_STYLE_ASSIGNMENT((#206065)); #206065 = SURFACE_STYLE_USAGE(.BOTH.,#206066); #206066 = SURFACE_SIDE_STYLE('',(#206067)); #206067 = SURFACE_STYLE_FILL_AREA(#206068); #206068 = FILL_AREA_STYLE('',(#206069)); -#206069 = FILL_AREA_STYLE_COLOUR('',#201028); -#206070 = OVER_RIDING_STYLED_ITEM('overriding color',(#206071),#188612, - #205874); +#206069 = FILL_AREA_STYLE_COLOUR('',#198418); +#206070 = OVER_RIDING_STYLED_ITEM('overriding color',(#206071),#35105, + #205894); #206071 = PRESENTATION_STYLE_ASSIGNMENT((#206072)); #206072 = SURFACE_STYLE_USAGE(.BOTH.,#206073); #206073 = SURFACE_SIDE_STYLE('',(#206074)); #206074 = SURFACE_STYLE_FILL_AREA(#206075); #206075 = FILL_AREA_STYLE('',(#206076)); -#206076 = FILL_AREA_STYLE_COLOUR('',#201028); -#206077 = OVER_RIDING_STYLED_ITEM('overriding color',(#206078),#188639, - #205874); +#206076 = FILL_AREA_STYLE_COLOUR('',#198418); +#206077 = OVER_RIDING_STYLED_ITEM('overriding color',(#206078),#35176, + #205894); #206078 = PRESENTATION_STYLE_ASSIGNMENT((#206079)); #206079 = SURFACE_STYLE_USAGE(.BOTH.,#206080); #206080 = SURFACE_SIDE_STYLE('',(#206081)); #206081 = SURFACE_STYLE_FILL_AREA(#206082); #206082 = FILL_AREA_STYLE('',(#206083)); -#206083 = FILL_AREA_STYLE_COLOUR('',#201028); -#206084 = OVER_RIDING_STYLED_ITEM('overriding color',(#206085),#188688, - #205874); +#206083 = FILL_AREA_STYLE_COLOUR('',#198418); +#206084 = OVER_RIDING_STYLED_ITEM('overriding color',(#206085),#35225, + #205894); #206085 = PRESENTATION_STYLE_ASSIGNMENT((#206086)); #206086 = SURFACE_STYLE_USAGE(.BOTH.,#206087); #206087 = SURFACE_SIDE_STYLE('',(#206088)); #206088 = SURFACE_STYLE_FILL_AREA(#206089); #206089 = FILL_AREA_STYLE('',(#206090)); -#206090 = FILL_AREA_STYLE_COLOUR('',#201028); -#206091 = OVER_RIDING_STYLED_ITEM('overriding color',(#206092),#188714, - #205874); +#206090 = FILL_AREA_STYLE_COLOUR('',#205908); +#206091 = OVER_RIDING_STYLED_ITEM('overriding color',(#206092),#35232, + #205894); #206092 = PRESENTATION_STYLE_ASSIGNMENT((#206093)); #206093 = SURFACE_STYLE_USAGE(.BOTH.,#206094); #206094 = SURFACE_SIDE_STYLE('',(#206095)); #206095 = SURFACE_STYLE_FILL_AREA(#206096); #206096 = FILL_AREA_STYLE('',(#206097)); -#206097 = FILL_AREA_STYLE_COLOUR('',#201028); -#206098 = OVER_RIDING_STYLED_ITEM('overriding color',(#206099),#188740, - #205874); +#206097 = FILL_AREA_STYLE_COLOUR('',#198418); +#206098 = OVER_RIDING_STYLED_ITEM('overriding color',(#206099),#35277, + #205894); #206099 = PRESENTATION_STYLE_ASSIGNMENT((#206100)); #206100 = SURFACE_STYLE_USAGE(.BOTH.,#206101); #206101 = SURFACE_SIDE_STYLE('',(#206102)); #206102 = SURFACE_STYLE_FILL_AREA(#206103); #206103 = FILL_AREA_STYLE('',(#206104)); -#206104 = FILL_AREA_STYLE_COLOUR('',#201028); -#206105 = OVER_RIDING_STYLED_ITEM('overriding color',(#206106),#188747, - #205874); +#206104 = FILL_AREA_STYLE_COLOUR('',#205908); +#206105 = OVER_RIDING_STYLED_ITEM('overriding color',(#206106),#35284, + #205894); #206106 = PRESENTATION_STYLE_ASSIGNMENT((#206107)); #206107 = SURFACE_STYLE_USAGE(.BOTH.,#206108); #206108 = SURFACE_SIDE_STYLE('',(#206109)); #206109 = SURFACE_STYLE_FILL_AREA(#206110); #206110 = FILL_AREA_STYLE('',(#206111)); -#206111 = FILL_AREA_STYLE_COLOUR('',#201028); -#206112 = OVER_RIDING_STYLED_ITEM('overriding color',(#206113),#188822, - #205874); +#206111 = FILL_AREA_STYLE_COLOUR('',#198418); +#206112 = OVER_RIDING_STYLED_ITEM('overriding color',(#206113),#35310, + #205894); #206113 = PRESENTATION_STYLE_ASSIGNMENT((#206114)); #206114 = SURFACE_STYLE_USAGE(.BOTH.,#206115); #206115 = SURFACE_SIDE_STYLE('',(#206116)); #206116 = SURFACE_STYLE_FILL_AREA(#206117); #206117 = FILL_AREA_STYLE('',(#206118)); -#206118 = FILL_AREA_STYLE_COLOUR('',#201028); -#206119 = OVER_RIDING_STYLED_ITEM('overriding color',(#206120),#188897, - #205874); +#206118 = FILL_AREA_STYLE_COLOUR('',#198418); +#206119 = OVER_RIDING_STYLED_ITEM('overriding color',(#206120),#35355, + #205894); #206120 = PRESENTATION_STYLE_ASSIGNMENT((#206121)); #206121 = SURFACE_STYLE_USAGE(.BOTH.,#206122); #206122 = SURFACE_SIDE_STYLE('',(#206123)); #206123 = SURFACE_STYLE_FILL_AREA(#206124); #206124 = FILL_AREA_STYLE('',(#206125)); -#206125 = FILL_AREA_STYLE_COLOUR('',#201028); -#206126 = OVER_RIDING_STYLED_ITEM('overriding color',(#206127),#189151, - #205874); +#206125 = FILL_AREA_STYLE_COLOUR('',#198418); +#206126 = OVER_RIDING_STYLED_ITEM('overriding color',(#206127),#35361, + #205894); #206127 = PRESENTATION_STYLE_ASSIGNMENT((#206128)); #206128 = SURFACE_STYLE_USAGE(.BOTH.,#206129); #206129 = SURFACE_SIDE_STYLE('',(#206130)); #206130 = SURFACE_STYLE_FILL_AREA(#206131); #206131 = FILL_AREA_STYLE('',(#206132)); -#206132 = FILL_AREA_STYLE_COLOUR('',#201028); -#206133 = OVER_RIDING_STYLED_ITEM('overriding color',(#206134),#189370, - #205874); +#206132 = FILL_AREA_STYLE_COLOUR('',#198418); +#206133 = OVER_RIDING_STYLED_ITEM('overriding color',(#206134),#35409, + #205894); #206134 = PRESENTATION_STYLE_ASSIGNMENT((#206135)); #206135 = SURFACE_STYLE_USAGE(.BOTH.,#206136); #206136 = SURFACE_SIDE_STYLE('',(#206137)); #206137 = SURFACE_STYLE_FILL_AREA(#206138); #206138 = FILL_AREA_STYLE('',(#206139)); -#206139 = FILL_AREA_STYLE_COLOUR('',#201028); -#206140 = OVER_RIDING_STYLED_ITEM('overriding color',(#206141),#189396, - #205874); +#206139 = FILL_AREA_STYLE_COLOUR('',#198418); +#206140 = OVER_RIDING_STYLED_ITEM('overriding color',(#206141),#35457, + #205894); #206141 = PRESENTATION_STYLE_ASSIGNMENT((#206142)); #206142 = SURFACE_STYLE_USAGE(.BOTH.,#206143); #206143 = SURFACE_SIDE_STYLE('',(#206144)); #206144 = SURFACE_STYLE_FILL_AREA(#206145); #206145 = FILL_AREA_STYLE('',(#206146)); -#206146 = FILL_AREA_STYLE_COLOUR('',#201028); -#206147 = OVER_RIDING_STYLED_ITEM('overriding color',(#206148),#189422, - #205874); +#206146 = FILL_AREA_STYLE_COLOUR('',#198418); +#206147 = OVER_RIDING_STYLED_ITEM('overriding color',(#206148),#35463, + #205894); #206148 = PRESENTATION_STYLE_ASSIGNMENT((#206149)); #206149 = SURFACE_STYLE_USAGE(.BOTH.,#206150); #206150 = SURFACE_SIDE_STYLE('',(#206151)); #206151 = SURFACE_STYLE_FILL_AREA(#206152); #206152 = FILL_AREA_STYLE('',(#206153)); -#206153 = FILL_AREA_STYLE_COLOUR('',#201028); -#206154 = OVER_RIDING_STYLED_ITEM('overriding color',(#206155),#189471, - #205874); +#206153 = FILL_AREA_STYLE_COLOUR('',#205908); +#206154 = OVER_RIDING_STYLED_ITEM('overriding color',(#206155),#35470, + #205894); #206155 = PRESENTATION_STYLE_ASSIGNMENT((#206156)); #206156 = SURFACE_STYLE_USAGE(.BOTH.,#206157); #206157 = SURFACE_SIDE_STYLE('',(#206158)); #206158 = SURFACE_STYLE_FILL_AREA(#206159); #206159 = FILL_AREA_STYLE('',(#206160)); -#206160 = FILL_AREA_STYLE_COLOUR('',#201028); -#206161 = OVER_RIDING_STYLED_ITEM('overriding color',(#206162),#189498, - #205874); +#206160 = FILL_AREA_STYLE_COLOUR('',#198418); +#206161 = OVER_RIDING_STYLED_ITEM('overriding color',(#206162),#35519, + #205894); #206162 = PRESENTATION_STYLE_ASSIGNMENT((#206163)); #206163 = SURFACE_STYLE_USAGE(.BOTH.,#206164); #206164 = SURFACE_SIDE_STYLE('',(#206165)); #206165 = SURFACE_STYLE_FILL_AREA(#206166); #206166 = FILL_AREA_STYLE('',(#206167)); -#206167 = FILL_AREA_STYLE_COLOUR('',#201028); -#206168 = OVER_RIDING_STYLED_ITEM('overriding color',(#206169),#189525, - #205874); +#206167 = FILL_AREA_STYLE_COLOUR('',#198418); +#206168 = OVER_RIDING_STYLED_ITEM('overriding color',(#206169),#35545, + #205894); #206169 = PRESENTATION_STYLE_ASSIGNMENT((#206170)); #206170 = SURFACE_STYLE_USAGE(.BOTH.,#206171); #206171 = SURFACE_SIDE_STYLE('',(#206172)); #206172 = SURFACE_STYLE_FILL_AREA(#206173); #206173 = FILL_AREA_STYLE('',(#206174)); -#206174 = FILL_AREA_STYLE_COLOUR('',#201028); -#206175 = OVER_RIDING_STYLED_ITEM('overriding color',(#206176),#189574, - #205874); +#206174 = FILL_AREA_STYLE_COLOUR('',#205908); +#206175 = OVER_RIDING_STYLED_ITEM('overriding color',(#206176),#35552, + #205894); #206176 = PRESENTATION_STYLE_ASSIGNMENT((#206177)); #206177 = SURFACE_STYLE_USAGE(.BOTH.,#206178); #206178 = SURFACE_SIDE_STYLE('',(#206179)); #206179 = SURFACE_STYLE_FILL_AREA(#206180); #206180 = FILL_AREA_STYLE('',(#206181)); -#206181 = FILL_AREA_STYLE_COLOUR('',#201028); -#206182 = OVER_RIDING_STYLED_ITEM('overriding color',(#206183),#189600, - #205874); +#206181 = FILL_AREA_STYLE_COLOUR('',#198418); +#206182 = OVER_RIDING_STYLED_ITEM('overriding color',(#206183),#35577, + #205894); #206183 = PRESENTATION_STYLE_ASSIGNMENT((#206184)); #206184 = SURFACE_STYLE_USAGE(.BOTH.,#206185); #206185 = SURFACE_SIDE_STYLE('',(#206186)); #206186 = SURFACE_STYLE_FILL_AREA(#206187); #206187 = FILL_AREA_STYLE('',(#206188)); -#206188 = FILL_AREA_STYLE_COLOUR('',#201028); -#206189 = OVER_RIDING_STYLED_ITEM('overriding color',(#206190),#189626, - #205874); +#206188 = FILL_AREA_STYLE_COLOUR('',#198418); +#206189 = OVER_RIDING_STYLED_ITEM('overriding color',(#206190),#35602, + #205894); #206190 = PRESENTATION_STYLE_ASSIGNMENT((#206191)); #206191 = SURFACE_STYLE_USAGE(.BOTH.,#206192); #206192 = SURFACE_SIDE_STYLE('',(#206193)); #206193 = SURFACE_STYLE_FILL_AREA(#206194); #206194 = FILL_AREA_STYLE('',(#206195)); -#206195 = FILL_AREA_STYLE_COLOUR('',#201028); -#206196 = OVER_RIDING_STYLED_ITEM('overriding color',(#206197),#189633, - #205874); +#206195 = FILL_AREA_STYLE_COLOUR('',#198418); +#206196 = OVER_RIDING_STYLED_ITEM('overriding color',(#206197),#35609, + #205894); #206197 = PRESENTATION_STYLE_ASSIGNMENT((#206198)); #206198 = SURFACE_STYLE_USAGE(.BOTH.,#206199); #206199 = SURFACE_SIDE_STYLE('',(#206200)); #206200 = SURFACE_STYLE_FILL_AREA(#206201); #206201 = FILL_AREA_STYLE('',(#206202)); -#206202 = FILL_AREA_STYLE_COLOUR('',#201028); -#206203 = OVER_RIDING_STYLED_ITEM('overriding color',(#206204),#189708, - #205874); +#206202 = FILL_AREA_STYLE_COLOUR('',#198418); +#206203 = OVER_RIDING_STYLED_ITEM('overriding color',(#206204),#36701, + #205894); #206204 = PRESENTATION_STYLE_ASSIGNMENT((#206205)); #206205 = SURFACE_STYLE_USAGE(.BOTH.,#206206); #206206 = SURFACE_SIDE_STYLE('',(#206207)); #206207 = SURFACE_STYLE_FILL_AREA(#206208); #206208 = FILL_AREA_STYLE('',(#206209)); -#206209 = FILL_AREA_STYLE_COLOUR('',#201028); -#206210 = OVER_RIDING_STYLED_ITEM('overriding color',(#206211),#189989, - #205874); +#206209 = FILL_AREA_STYLE_COLOUR('',#198418); +#206210 = OVER_RIDING_STYLED_ITEM('overriding color',(#206211),#36744, + #205894); #206211 = PRESENTATION_STYLE_ASSIGNMENT((#206212)); #206212 = SURFACE_STYLE_USAGE(.BOTH.,#206213); #206213 = SURFACE_SIDE_STYLE('',(#206214)); #206214 = SURFACE_STYLE_FILL_AREA(#206215); #206215 = FILL_AREA_STYLE('',(#206216)); -#206216 = FILL_AREA_STYLE_COLOUR('',#201028); -#206217 = OVER_RIDING_STYLED_ITEM('overriding color',(#206218),#190037, - #205874); +#206216 = FILL_AREA_STYLE_COLOUR('',#198418); +#206217 = OVER_RIDING_STYLED_ITEM('overriding color',(#206218),#36769, + #205894); #206218 = PRESENTATION_STYLE_ASSIGNMENT((#206219)); #206219 = SURFACE_STYLE_USAGE(.BOTH.,#206220); #206220 = SURFACE_SIDE_STYLE('',(#206221)); #206221 = SURFACE_STYLE_FILL_AREA(#206222); #206222 = FILL_AREA_STYLE('',(#206223)); -#206223 = FILL_AREA_STYLE_COLOUR('',#201028); -#206224 = OVER_RIDING_STYLED_ITEM('overriding color',(#206225),#190256, - #205874); +#206223 = FILL_AREA_STYLE_COLOUR('',#198418); +#206224 = OVER_RIDING_STYLED_ITEM('overriding color',(#206225),#36794, + #205894); #206225 = PRESENTATION_STYLE_ASSIGNMENT((#206226)); #206226 = SURFACE_STYLE_USAGE(.BOTH.,#206227); #206227 = SURFACE_SIDE_STYLE('',(#206228)); #206228 = SURFACE_STYLE_FILL_AREA(#206229); #206229 = FILL_AREA_STYLE('',(#206230)); -#206230 = FILL_AREA_STYLE_COLOUR('',#201028); -#206231 = OVER_RIDING_STYLED_ITEM('overriding color',(#206232),#190282, - #205874); +#206230 = FILL_AREA_STYLE_COLOUR('',#198418); +#206231 = OVER_RIDING_STYLED_ITEM('overriding color',(#206232),#36819, + #205894); #206232 = PRESENTATION_STYLE_ASSIGNMENT((#206233)); #206233 = SURFACE_STYLE_USAGE(.BOTH.,#206234); #206234 = SURFACE_SIDE_STYLE('',(#206235)); #206235 = SURFACE_STYLE_FILL_AREA(#206236); #206236 = FILL_AREA_STYLE('',(#206237)); -#206237 = FILL_AREA_STYLE_COLOUR('',#201028); -#206238 = OVER_RIDING_STYLED_ITEM('overriding color',(#206239),#190308, - #205874); +#206237 = FILL_AREA_STYLE_COLOUR('',#198418); +#206238 = OVER_RIDING_STYLED_ITEM('overriding color',(#206239),#36844, + #205894); #206239 = PRESENTATION_STYLE_ASSIGNMENT((#206240)); #206240 = SURFACE_STYLE_USAGE(.BOTH.,#206241); #206241 = SURFACE_SIDE_STYLE('',(#206242)); #206242 = SURFACE_STYLE_FILL_AREA(#206243); #206243 = FILL_AREA_STYLE('',(#206244)); -#206244 = FILL_AREA_STYLE_COLOUR('',#201028); -#206245 = OVER_RIDING_STYLED_ITEM('overriding color',(#206246),#190357, - #205874); +#206244 = FILL_AREA_STYLE_COLOUR('',#198418); +#206245 = OVER_RIDING_STYLED_ITEM('overriding color',(#206246),#36869, + #205894); #206246 = PRESENTATION_STYLE_ASSIGNMENT((#206247)); #206247 = SURFACE_STYLE_USAGE(.BOTH.,#206248); #206248 = SURFACE_SIDE_STYLE('',(#206249)); #206249 = SURFACE_STYLE_FILL_AREA(#206250); #206250 = FILL_AREA_STYLE('',(#206251)); -#206251 = FILL_AREA_STYLE_COLOUR('',#201028); -#206252 = OVER_RIDING_STYLED_ITEM('overriding color',(#206253),#190384, - #205874); +#206251 = FILL_AREA_STYLE_COLOUR('',#198418); +#206252 = OVER_RIDING_STYLED_ITEM('overriding color',(#206253),#36894, + #205894); #206253 = PRESENTATION_STYLE_ASSIGNMENT((#206254)); #206254 = SURFACE_STYLE_USAGE(.BOTH.,#206255); #206255 = SURFACE_SIDE_STYLE('',(#206256)); #206256 = SURFACE_STYLE_FILL_AREA(#206257); #206257 = FILL_AREA_STYLE('',(#206258)); -#206258 = FILL_AREA_STYLE_COLOUR('',#201028); -#206259 = OVER_RIDING_STYLED_ITEM('overriding color',(#206260),#190411, - #205874); +#206258 = FILL_AREA_STYLE_COLOUR('',#198418); +#206259 = OVER_RIDING_STYLED_ITEM('overriding color',(#206260),#36901, + #205894); #206260 = PRESENTATION_STYLE_ASSIGNMENT((#206261)); #206261 = SURFACE_STYLE_USAGE(.BOTH.,#206262); #206262 = SURFACE_SIDE_STYLE('',(#206263)); #206263 = SURFACE_STYLE_FILL_AREA(#206264); #206264 = FILL_AREA_STYLE('',(#206265)); -#206265 = FILL_AREA_STYLE_COLOUR('',#201028); -#206266 = OVER_RIDING_STYLED_ITEM('overriding color',(#206267),#190460, - #205874); +#206265 = FILL_AREA_STYLE_COLOUR('',#198418); +#206266 = OVER_RIDING_STYLED_ITEM('overriding color',(#206267),#36997, + #205894); #206267 = PRESENTATION_STYLE_ASSIGNMENT((#206268)); #206268 = SURFACE_STYLE_USAGE(.BOTH.,#206269); #206269 = SURFACE_SIDE_STYLE('',(#206270)); #206270 = SURFACE_STYLE_FILL_AREA(#206271); #206271 = FILL_AREA_STYLE('',(#206272)); -#206272 = FILL_AREA_STYLE_COLOUR('',#201028); -#206273 = OVER_RIDING_STYLED_ITEM('overriding color',(#206274),#190486, - #205874); +#206272 = FILL_AREA_STYLE_COLOUR('',#198418); +#206273 = OVER_RIDING_STYLED_ITEM('overriding color',(#206274),#37068, + #205894); #206274 = PRESENTATION_STYLE_ASSIGNMENT((#206275)); #206275 = SURFACE_STYLE_USAGE(.BOTH.,#206276); #206276 = SURFACE_SIDE_STYLE('',(#206277)); #206277 = SURFACE_STYLE_FILL_AREA(#206278); #206278 = FILL_AREA_STYLE('',(#206279)); -#206279 = FILL_AREA_STYLE_COLOUR('',#201028); -#206280 = OVER_RIDING_STYLED_ITEM('overriding color',(#206281),#190512, - #205874); +#206279 = FILL_AREA_STYLE_COLOUR('',#198418); +#206280 = OVER_RIDING_STYLED_ITEM('overriding color',(#206281),#37139, + #205894); #206281 = PRESENTATION_STYLE_ASSIGNMENT((#206282)); #206282 = SURFACE_STYLE_USAGE(.BOTH.,#206283); #206283 = SURFACE_SIDE_STYLE('',(#206284)); #206284 = SURFACE_STYLE_FILL_AREA(#206285); #206285 = FILL_AREA_STYLE('',(#206286)); -#206286 = FILL_AREA_STYLE_COLOUR('',#201028); -#206287 = OVER_RIDING_STYLED_ITEM('overriding color',(#206288),#190519, - #205874); +#206286 = FILL_AREA_STYLE_COLOUR('',#198418); +#206287 = OVER_RIDING_STYLED_ITEM('overriding color',(#206288),#37190, + #205894); #206288 = PRESENTATION_STYLE_ASSIGNMENT((#206289)); #206289 = SURFACE_STYLE_USAGE(.BOTH.,#206290); #206290 = SURFACE_SIDE_STYLE('',(#206291)); #206291 = SURFACE_STYLE_FILL_AREA(#206292); #206292 = FILL_AREA_STYLE('',(#206293)); -#206293 = FILL_AREA_STYLE_COLOUR('',#201028); -#206294 = OVER_RIDING_STYLED_ITEM('overriding color',(#206295),#190594, - #205874); +#206293 = FILL_AREA_STYLE_COLOUR('',#198418); +#206294 = OVER_RIDING_STYLED_ITEM('overriding color',(#206295),#37294, + #205894); #206295 = PRESENTATION_STYLE_ASSIGNMENT((#206296)); #206296 = SURFACE_STYLE_USAGE(.BOTH.,#206297); #206297 = SURFACE_SIDE_STYLE('',(#206298)); #206298 = SURFACE_STYLE_FILL_AREA(#206299); #206299 = FILL_AREA_STYLE('',(#206300)); -#206300 = FILL_AREA_STYLE_COLOUR('',#201028); -#206301 = OVER_RIDING_STYLED_ITEM('overriding color',(#206302),#190875, - #205874); +#206300 = FILL_AREA_STYLE_COLOUR('',#198418); +#206301 = OVER_RIDING_STYLED_ITEM('overriding color',(#206302),#37365, + #205894); #206302 = PRESENTATION_STYLE_ASSIGNMENT((#206303)); #206303 = SURFACE_STYLE_USAGE(.BOTH.,#206304); #206304 = SURFACE_SIDE_STYLE('',(#206305)); #206305 = SURFACE_STYLE_FILL_AREA(#206306); #206306 = FILL_AREA_STYLE('',(#206307)); -#206307 = FILL_AREA_STYLE_COLOUR('',#201028); -#206308 = OVER_RIDING_STYLED_ITEM('overriding color',(#206309),#190923, - #205874); +#206307 = FILL_AREA_STYLE_COLOUR('',#198418); +#206308 = OVER_RIDING_STYLED_ITEM('overriding color',(#206309),#37444, + #205894); #206309 = PRESENTATION_STYLE_ASSIGNMENT((#206310)); #206310 = SURFACE_STYLE_USAGE(.BOTH.,#206311); #206311 = SURFACE_SIDE_STYLE('',(#206312)); #206312 = SURFACE_STYLE_FILL_AREA(#206313); #206313 = FILL_AREA_STYLE('',(#206314)); -#206314 = FILL_AREA_STYLE_COLOUR('',#201028); -#206315 = OVER_RIDING_STYLED_ITEM('overriding color',(#206316),#191142, - #205874); +#206314 = FILL_AREA_STYLE_COLOUR('',#198418); +#206315 = OVER_RIDING_STYLED_ITEM('overriding color',(#206316),#37503, + #205894); #206316 = PRESENTATION_STYLE_ASSIGNMENT((#206317)); #206317 = SURFACE_STYLE_USAGE(.BOTH.,#206318); #206318 = SURFACE_SIDE_STYLE('',(#206319)); #206319 = SURFACE_STYLE_FILL_AREA(#206320); #206320 = FILL_AREA_STYLE('',(#206321)); -#206321 = FILL_AREA_STYLE_COLOUR('',#201028); -#206322 = OVER_RIDING_STYLED_ITEM('overriding color',(#206323),#191168, - #205874); +#206321 = FILL_AREA_STYLE_COLOUR('',#205908); +#206322 = OVER_RIDING_STYLED_ITEM('overriding color',(#206323),#37510, + #205894); #206323 = PRESENTATION_STYLE_ASSIGNMENT((#206324)); #206324 = SURFACE_STYLE_USAGE(.BOTH.,#206325); #206325 = SURFACE_SIDE_STYLE('',(#206326)); #206326 = SURFACE_STYLE_FILL_AREA(#206327); #206327 = FILL_AREA_STYLE('',(#206328)); -#206328 = FILL_AREA_STYLE_COLOUR('',#201028); -#206329 = OVER_RIDING_STYLED_ITEM('overriding color',(#206330),#191194, - #205874); +#206328 = FILL_AREA_STYLE_COLOUR('',#205908); +#206329 = OVER_RIDING_STYLED_ITEM('overriding color',(#206330),#37517, + #205894); #206330 = PRESENTATION_STYLE_ASSIGNMENT((#206331)); #206331 = SURFACE_STYLE_USAGE(.BOTH.,#206332); #206332 = SURFACE_SIDE_STYLE('',(#206333)); #206333 = SURFACE_STYLE_FILL_AREA(#206334); #206334 = FILL_AREA_STYLE('',(#206335)); -#206335 = FILL_AREA_STYLE_COLOUR('',#201028); -#206336 = OVER_RIDING_STYLED_ITEM('overriding color',(#206337),#191243, - #205874); +#206335 = FILL_AREA_STYLE_COLOUR('',#198418); +#206336 = OVER_RIDING_STYLED_ITEM('overriding color',(#206337),#38216, + #205894); #206337 = PRESENTATION_STYLE_ASSIGNMENT((#206338)); #206338 = SURFACE_STYLE_USAGE(.BOTH.,#206339); #206339 = SURFACE_SIDE_STYLE('',(#206340)); #206340 = SURFACE_STYLE_FILL_AREA(#206341); #206341 = FILL_AREA_STYLE('',(#206342)); -#206342 = FILL_AREA_STYLE_COLOUR('',#201028); -#206343 = OVER_RIDING_STYLED_ITEM('overriding color',(#206344),#191270, - #205874); +#206342 = FILL_AREA_STYLE_COLOUR('',#198418); +#206343 = OVER_RIDING_STYLED_ITEM('overriding color',(#206344),#38259, + #205894); #206344 = PRESENTATION_STYLE_ASSIGNMENT((#206345)); #206345 = SURFACE_STYLE_USAGE(.BOTH.,#206346); #206346 = SURFACE_SIDE_STYLE('',(#206347)); #206347 = SURFACE_STYLE_FILL_AREA(#206348); #206348 = FILL_AREA_STYLE('',(#206349)); -#206349 = FILL_AREA_STYLE_COLOUR('',#201028); -#206350 = OVER_RIDING_STYLED_ITEM('overriding color',(#206351),#191297, - #205874); +#206349 = FILL_AREA_STYLE_COLOUR('',#198418); +#206350 = OVER_RIDING_STYLED_ITEM('overriding color',(#206351),#38284, + #205894); #206351 = PRESENTATION_STYLE_ASSIGNMENT((#206352)); #206352 = SURFACE_STYLE_USAGE(.BOTH.,#206353); #206353 = SURFACE_SIDE_STYLE('',(#206354)); #206354 = SURFACE_STYLE_FILL_AREA(#206355); #206355 = FILL_AREA_STYLE('',(#206356)); -#206356 = FILL_AREA_STYLE_COLOUR('',#201028); -#206357 = OVER_RIDING_STYLED_ITEM('overriding color',(#206358),#191346, - #205874); +#206356 = FILL_AREA_STYLE_COLOUR('',#198418); +#206357 = OVER_RIDING_STYLED_ITEM('overriding color',(#206358),#38309, + #205894); #206358 = PRESENTATION_STYLE_ASSIGNMENT((#206359)); #206359 = SURFACE_STYLE_USAGE(.BOTH.,#206360); #206360 = SURFACE_SIDE_STYLE('',(#206361)); #206361 = SURFACE_STYLE_FILL_AREA(#206362); #206362 = FILL_AREA_STYLE('',(#206363)); -#206363 = FILL_AREA_STYLE_COLOUR('',#201028); -#206364 = OVER_RIDING_STYLED_ITEM('overriding color',(#206365),#191372, - #205874); +#206363 = FILL_AREA_STYLE_COLOUR('',#198418); +#206364 = OVER_RIDING_STYLED_ITEM('overriding color',(#206365),#38334, + #205894); #206365 = PRESENTATION_STYLE_ASSIGNMENT((#206366)); #206366 = SURFACE_STYLE_USAGE(.BOTH.,#206367); #206367 = SURFACE_SIDE_STYLE('',(#206368)); #206368 = SURFACE_STYLE_FILL_AREA(#206369); #206369 = FILL_AREA_STYLE('',(#206370)); -#206370 = FILL_AREA_STYLE_COLOUR('',#201028); -#206371 = OVER_RIDING_STYLED_ITEM('overriding color',(#206372),#191398, - #205874); +#206370 = FILL_AREA_STYLE_COLOUR('',#198418); +#206371 = OVER_RIDING_STYLED_ITEM('overriding color',(#206372),#38341, + #205894); #206372 = PRESENTATION_STYLE_ASSIGNMENT((#206373)); #206373 = SURFACE_STYLE_USAGE(.BOTH.,#206374); #206374 = SURFACE_SIDE_STYLE('',(#206375)); #206375 = SURFACE_STYLE_FILL_AREA(#206376); #206376 = FILL_AREA_STYLE('',(#206377)); -#206377 = FILL_AREA_STYLE_COLOUR('',#201028); -#206378 = OVER_RIDING_STYLED_ITEM('overriding color',(#206379),#191405, - #205874); +#206377 = FILL_AREA_STYLE_COLOUR('',#198418); +#206378 = OVER_RIDING_STYLED_ITEM('overriding color',(#206379),#38429, + #205894); #206379 = PRESENTATION_STYLE_ASSIGNMENT((#206380)); #206380 = SURFACE_STYLE_USAGE(.BOTH.,#206381); #206381 = SURFACE_SIDE_STYLE('',(#206382)); #206382 = SURFACE_STYLE_FILL_AREA(#206383); #206383 = FILL_AREA_STYLE('',(#206384)); -#206384 = FILL_AREA_STYLE_COLOUR('',#201028); -#206385 = OVER_RIDING_STYLED_ITEM('overriding color',(#206386),#191480, - #205874); +#206384 = FILL_AREA_STYLE_COLOUR('',#198418); +#206385 = OVER_RIDING_STYLED_ITEM('overriding color',(#206386),#38508, + #205894); #206386 = PRESENTATION_STYLE_ASSIGNMENT((#206387)); #206387 = SURFACE_STYLE_USAGE(.BOTH.,#206388); #206388 = SURFACE_SIDE_STYLE('',(#206389)); #206389 = SURFACE_STYLE_FILL_AREA(#206390); #206390 = FILL_AREA_STYLE('',(#206391)); -#206391 = FILL_AREA_STYLE_COLOUR('',#201028); -#206392 = OVER_RIDING_STYLED_ITEM('overriding color',(#206393),#191761, - #205874); +#206391 = FILL_AREA_STYLE_COLOUR('',#198418); +#206392 = OVER_RIDING_STYLED_ITEM('overriding color',(#206393),#38587, + #205894); #206393 = PRESENTATION_STYLE_ASSIGNMENT((#206394)); #206394 = SURFACE_STYLE_USAGE(.BOTH.,#206395); #206395 = SURFACE_SIDE_STYLE('',(#206396)); #206396 = SURFACE_STYLE_FILL_AREA(#206397); #206397 = FILL_AREA_STYLE('',(#206398)); -#206398 = FILL_AREA_STYLE_COLOUR('',#201028); -#206399 = OVER_RIDING_STYLED_ITEM('overriding color',(#206400),#192002, - #205874); +#206398 = FILL_AREA_STYLE_COLOUR('',#198418); +#206399 = OVER_RIDING_STYLED_ITEM('overriding color',(#206400),#38666, + #205894); #206400 = PRESENTATION_STYLE_ASSIGNMENT((#206401)); #206401 = SURFACE_STYLE_USAGE(.BOTH.,#206402); #206402 = SURFACE_SIDE_STYLE('',(#206403)); #206403 = SURFACE_STYLE_FILL_AREA(#206404); #206404 = FILL_AREA_STYLE('',(#206405)); -#206405 = FILL_AREA_STYLE_COLOUR('',#201028); -#206406 = OVER_RIDING_STYLED_ITEM('overriding color',(#206407),#192047, - #205874); +#206405 = FILL_AREA_STYLE_COLOUR('',#198418); +#206406 = OVER_RIDING_STYLED_ITEM('overriding color',(#206407),#38709, + #205894); #206407 = PRESENTATION_STYLE_ASSIGNMENT((#206408)); #206408 = SURFACE_STYLE_USAGE(.BOTH.,#206409); #206409 = SURFACE_SIDE_STYLE('',(#206410)); #206410 = SURFACE_STYLE_FILL_AREA(#206411); #206411 = FILL_AREA_STYLE('',(#206412)); -#206412 = FILL_AREA_STYLE_COLOUR('',#201028); -#206413 = OVER_RIDING_STYLED_ITEM('overriding color',(#206414),#192073, - #205874); +#206412 = FILL_AREA_STYLE_COLOUR('',#205908); +#206413 = OVER_RIDING_STYLED_ITEM('overriding color',(#206414),#38717, + #205894); #206414 = PRESENTATION_STYLE_ASSIGNMENT((#206415)); #206415 = SURFACE_STYLE_USAGE(.BOTH.,#206416); #206416 = SURFACE_SIDE_STYLE('',(#206417)); #206417 = SURFACE_STYLE_FILL_AREA(#206418); #206418 = FILL_AREA_STYLE('',(#206419)); -#206419 = FILL_AREA_STYLE_COLOUR('',#201028); -#206420 = OVER_RIDING_STYLED_ITEM('overriding color',(#206421),#192122, - #205874); +#206419 = FILL_AREA_STYLE_COLOUR('',#198418); +#206420 = OVER_RIDING_STYLED_ITEM('overriding color',(#206421),#38822, + #205894); #206421 = PRESENTATION_STYLE_ASSIGNMENT((#206422)); #206422 = SURFACE_STYLE_USAGE(.BOTH.,#206423); #206423 = SURFACE_SIDE_STYLE('',(#206424)); #206424 = SURFACE_STYLE_FILL_AREA(#206425); #206425 = FILL_AREA_STYLE('',(#206426)); -#206426 = FILL_AREA_STYLE_COLOUR('',#201028); -#206427 = OVER_RIDING_STYLED_ITEM('overriding color',(#206428),#192149, - #205874); +#206426 = FILL_AREA_STYLE_COLOUR('',#198418); +#206427 = OVER_RIDING_STYLED_ITEM('overriding color',(#206428),#38885, + #205894); #206428 = PRESENTATION_STYLE_ASSIGNMENT((#206429)); #206429 = SURFACE_STYLE_USAGE(.BOTH.,#206430); #206430 = SURFACE_SIDE_STYLE('',(#206431)); #206431 = SURFACE_STYLE_FILL_AREA(#206432); #206432 = FILL_AREA_STYLE('',(#206433)); -#206433 = FILL_AREA_STYLE_COLOUR('',#201028); -#206434 = OVER_RIDING_STYLED_ITEM('overriding color',(#206435),#192176, - #205874); +#206433 = FILL_AREA_STYLE_COLOUR('',#198418); +#206434 = OVER_RIDING_STYLED_ITEM('overriding color',(#206435),#38948, + #205894); #206435 = PRESENTATION_STYLE_ASSIGNMENT((#206436)); #206436 = SURFACE_STYLE_USAGE(.BOTH.,#206437); #206437 = SURFACE_SIDE_STYLE('',(#206438)); #206438 = SURFACE_STYLE_FILL_AREA(#206439); #206439 = FILL_AREA_STYLE('',(#206440)); -#206440 = FILL_AREA_STYLE_COLOUR('',#201028); -#206441 = OVER_RIDING_STYLED_ITEM('overriding color',(#206442),#192225, - #205874); +#206440 = FILL_AREA_STYLE_COLOUR('',#198418); +#206441 = OVER_RIDING_STYLED_ITEM('overriding color',(#206442),#39027, + #205894); #206442 = PRESENTATION_STYLE_ASSIGNMENT((#206443)); #206443 = SURFACE_STYLE_USAGE(.BOTH.,#206444); #206444 = SURFACE_SIDE_STYLE('',(#206445)); #206445 = SURFACE_STYLE_FILL_AREA(#206446); #206446 = FILL_AREA_STYLE('',(#206447)); -#206447 = FILL_AREA_STYLE_COLOUR('',#201028); -#206448 = OVER_RIDING_STYLED_ITEM('overriding color',(#206449),#192251, - #205874); +#206447 = FILL_AREA_STYLE_COLOUR('',#198418); +#206448 = OVER_RIDING_STYLED_ITEM('overriding color',(#206449),#39091, + #205894); #206449 = PRESENTATION_STYLE_ASSIGNMENT((#206450)); #206450 = SURFACE_STYLE_USAGE(.BOTH.,#206451); #206451 = SURFACE_SIDE_STYLE('',(#206452)); #206452 = SURFACE_STYLE_FILL_AREA(#206453); #206453 = FILL_AREA_STYLE('',(#206454)); -#206454 = FILL_AREA_STYLE_COLOUR('',#201028); -#206455 = OVER_RIDING_STYLED_ITEM('overriding color',(#206456),#192277, - #205874); +#206454 = FILL_AREA_STYLE_COLOUR('',#198418); +#206455 = OVER_RIDING_STYLED_ITEM('overriding color',(#206456),#39140, + #205894); #206456 = PRESENTATION_STYLE_ASSIGNMENT((#206457)); #206457 = SURFACE_STYLE_USAGE(.BOTH.,#206458); #206458 = SURFACE_SIDE_STYLE('',(#206459)); #206459 = SURFACE_STYLE_FILL_AREA(#206460); #206460 = FILL_AREA_STYLE('',(#206461)); -#206461 = FILL_AREA_STYLE_COLOUR('',#201028); -#206462 = OVER_RIDING_STYLED_ITEM('overriding color',(#206463),#192284, - #205874); +#206461 = FILL_AREA_STYLE_COLOUR('',#198418); +#206462 = OVER_RIDING_STYLED_ITEM('overriding color',(#206463),#39189, + #205894); #206463 = PRESENTATION_STYLE_ASSIGNMENT((#206464)); #206464 = SURFACE_STYLE_USAGE(.BOTH.,#206465); #206465 = SURFACE_SIDE_STYLE('',(#206466)); #206466 = SURFACE_STYLE_FILL_AREA(#206467); #206467 = FILL_AREA_STYLE('',(#206468)); -#206468 = FILL_AREA_STYLE_COLOUR('',#201028); -#206469 = OVER_RIDING_STYLED_ITEM('overriding color',(#206470),#192291, - #205874); +#206468 = FILL_AREA_STYLE_COLOUR('',#198418); +#206469 = OVER_RIDING_STYLED_ITEM('overriding color',(#206470),#39238, + #205894); #206470 = PRESENTATION_STYLE_ASSIGNMENT((#206471)); #206471 = SURFACE_STYLE_USAGE(.BOTH.,#206472); #206472 = SURFACE_SIDE_STYLE('',(#206473)); #206473 = SURFACE_STYLE_FILL_AREA(#206474); #206474 = FILL_AREA_STYLE('',(#206475)); -#206475 = FILL_AREA_STYLE_COLOUR('',#201028); -#206476 = OVER_RIDING_STYLED_ITEM('overriding color',(#206477),#192366, - #205874); +#206475 = FILL_AREA_STYLE_COLOUR('',#198418); +#206476 = OVER_RIDING_STYLED_ITEM('overriding color',(#206477),#39287, + #205894); #206477 = PRESENTATION_STYLE_ASSIGNMENT((#206478)); #206478 = SURFACE_STYLE_USAGE(.BOTH.,#206479); #206479 = SURFACE_SIDE_STYLE('',(#206480)); #206480 = SURFACE_STYLE_FILL_AREA(#206481); #206481 = FILL_AREA_STYLE('',(#206482)); -#206482 = FILL_AREA_STYLE_COLOUR('',#201028); -#206483 = OVER_RIDING_STYLED_ITEM('overriding color',(#206484),#192647, - #205874); +#206482 = FILL_AREA_STYLE_COLOUR('',#198418); +#206483 = OVER_RIDING_STYLED_ITEM('overriding color',(#206484),#39336, + #205894); #206484 = PRESENTATION_STYLE_ASSIGNMENT((#206485)); #206485 = SURFACE_STYLE_USAGE(.BOTH.,#206486); #206486 = SURFACE_SIDE_STYLE('',(#206487)); #206487 = SURFACE_STYLE_FILL_AREA(#206488); #206488 = FILL_AREA_STYLE('',(#206489)); -#206489 = FILL_AREA_STYLE_COLOUR('',#201028); -#206490 = OVER_RIDING_STYLED_ITEM('overriding color',(#206491),#192888, - #205874); +#206489 = FILL_AREA_STYLE_COLOUR('',#198418); +#206490 = OVER_RIDING_STYLED_ITEM('overriding color',(#206491),#39384, + #205894); #206491 = PRESENTATION_STYLE_ASSIGNMENT((#206492)); #206492 = SURFACE_STYLE_USAGE(.BOTH.,#206493); #206493 = SURFACE_SIDE_STYLE('',(#206494)); #206494 = SURFACE_STYLE_FILL_AREA(#206495); #206495 = FILL_AREA_STYLE('',(#206496)); -#206496 = FILL_AREA_STYLE_COLOUR('',#201028); -#206497 = OVER_RIDING_STYLED_ITEM('overriding color',(#206498),#192914, - #205874); +#206496 = FILL_AREA_STYLE_COLOUR('',#198418); +#206497 = OVER_RIDING_STYLED_ITEM('overriding color',(#206498),#39447, + #205894); #206498 = PRESENTATION_STYLE_ASSIGNMENT((#206499)); #206499 = SURFACE_STYLE_USAGE(.BOTH.,#206500); #206500 = SURFACE_SIDE_STYLE('',(#206501)); #206501 = SURFACE_STYLE_FILL_AREA(#206502); #206502 = FILL_AREA_STYLE('',(#206503)); -#206503 = FILL_AREA_STYLE_COLOUR('',#201028); -#206504 = OVER_RIDING_STYLED_ITEM('overriding color',(#206505),#192940, - #205874); +#206503 = FILL_AREA_STYLE_COLOUR('',#198418); +#206504 = OVER_RIDING_STYLED_ITEM('overriding color',(#206505),#39526, + #205894); #206505 = PRESENTATION_STYLE_ASSIGNMENT((#206506)); #206506 = SURFACE_STYLE_USAGE(.BOTH.,#206507); #206507 = SURFACE_SIDE_STYLE('',(#206508)); #206508 = SURFACE_STYLE_FILL_AREA(#206509); #206509 = FILL_AREA_STYLE('',(#206510)); -#206510 = FILL_AREA_STYLE_COLOUR('',#201028); -#206511 = OVER_RIDING_STYLED_ITEM('overriding color',(#206512),#192989, - #205874); +#206510 = FILL_AREA_STYLE_COLOUR('',#198418); +#206511 = OVER_RIDING_STYLED_ITEM('overriding color',(#206512),#39605, + #205894); #206512 = PRESENTATION_STYLE_ASSIGNMENT((#206513)); #206513 = SURFACE_STYLE_USAGE(.BOTH.,#206514); #206514 = SURFACE_SIDE_STYLE('',(#206515)); #206515 = SURFACE_STYLE_FILL_AREA(#206516); #206516 = FILL_AREA_STYLE('',(#206517)); -#206517 = FILL_AREA_STYLE_COLOUR('',#201028); -#206518 = OVER_RIDING_STYLED_ITEM('overriding color',(#206519),#193016, - #205874); +#206517 = FILL_AREA_STYLE_COLOUR('',#198418); +#206518 = OVER_RIDING_STYLED_ITEM('overriding color',(#206519),#39685, + #205894); #206519 = PRESENTATION_STYLE_ASSIGNMENT((#206520)); #206520 = SURFACE_STYLE_USAGE(.BOTH.,#206521); #206521 = SURFACE_SIDE_STYLE('',(#206522)); #206522 = SURFACE_STYLE_FILL_AREA(#206523); #206523 = FILL_AREA_STYLE('',(#206524)); -#206524 = FILL_AREA_STYLE_COLOUR('',#201028); -#206525 = OVER_RIDING_STYLED_ITEM('overriding color',(#206526),#193043, - #205874); +#206524 = FILL_AREA_STYLE_COLOUR('',#198418); +#206525 = OVER_RIDING_STYLED_ITEM('overriding color',(#206526),#39712, + #205894); #206526 = PRESENTATION_STYLE_ASSIGNMENT((#206527)); #206527 = SURFACE_STYLE_USAGE(.BOTH.,#206528); #206528 = SURFACE_SIDE_STYLE('',(#206529)); #206529 = SURFACE_STYLE_FILL_AREA(#206530); #206530 = FILL_AREA_STYLE('',(#206531)); -#206531 = FILL_AREA_STYLE_COLOUR('',#201028); -#206532 = OVER_RIDING_STYLED_ITEM('overriding color',(#206533),#193092, - #205874); -#206533 = PRESENTATION_STYLE_ASSIGNMENT((#206534)); -#206534 = SURFACE_STYLE_USAGE(.BOTH.,#206535); -#206535 = SURFACE_SIDE_STYLE('',(#206536)); -#206536 = SURFACE_STYLE_FILL_AREA(#206537); -#206537 = FILL_AREA_STYLE('',(#206538)); -#206538 = FILL_AREA_STYLE_COLOUR('',#201028); -#206539 = OVER_RIDING_STYLED_ITEM('overriding color',(#206540),#193118, - #205874); -#206540 = PRESENTATION_STYLE_ASSIGNMENT((#206541)); -#206541 = SURFACE_STYLE_USAGE(.BOTH.,#206542); -#206542 = SURFACE_SIDE_STYLE('',(#206543)); -#206543 = SURFACE_STYLE_FILL_AREA(#206544); -#206544 = FILL_AREA_STYLE('',(#206545)); -#206545 = FILL_AREA_STYLE_COLOUR('',#201028); -#206546 = OVER_RIDING_STYLED_ITEM('overriding color',(#206547),#193144, - #205874); -#206547 = PRESENTATION_STYLE_ASSIGNMENT((#206548)); -#206548 = SURFACE_STYLE_USAGE(.BOTH.,#206549); -#206549 = SURFACE_SIDE_STYLE('',(#206550)); -#206550 = SURFACE_STYLE_FILL_AREA(#206551); -#206551 = FILL_AREA_STYLE('',(#206552)); -#206552 = FILL_AREA_STYLE_COLOUR('',#201028); -#206553 = OVER_RIDING_STYLED_ITEM('overriding color',(#206554),#193170, - #205874); -#206554 = PRESENTATION_STYLE_ASSIGNMENT((#206555)); -#206555 = SURFACE_STYLE_USAGE(.BOTH.,#206556); -#206556 = SURFACE_SIDE_STYLE('',(#206557)); -#206557 = SURFACE_STYLE_FILL_AREA(#206558); -#206558 = FILL_AREA_STYLE('',(#206559)); -#206559 = FILL_AREA_STYLE_COLOUR('',#201028); -#206560 = OVER_RIDING_STYLED_ITEM('overriding color',(#206561),#193177, - #205874); -#206561 = PRESENTATION_STYLE_ASSIGNMENT((#206562)); -#206562 = SURFACE_STYLE_USAGE(.BOTH.,#206563); -#206563 = SURFACE_SIDE_STYLE('',(#206564)); -#206564 = SURFACE_STYLE_FILL_AREA(#206565); -#206565 = FILL_AREA_STYLE('',(#206566)); -#206566 = FILL_AREA_STYLE_COLOUR('',#201781); -#206567 = OVER_RIDING_STYLED_ITEM('overriding color',(#206568),#193315, - #205874); -#206568 = PRESENTATION_STYLE_ASSIGNMENT((#206569)); -#206569 = SURFACE_STYLE_USAGE(.BOTH.,#206570); -#206570 = SURFACE_SIDE_STYLE('',(#206571)); -#206571 = SURFACE_STYLE_FILL_AREA(#206572); -#206572 = FILL_AREA_STYLE('',(#206573)); -#206573 = FILL_AREA_STYLE_COLOUR('',#201781); -#206574 = OVER_RIDING_STYLED_ITEM('overriding color',(#206575),#193388, - #205874); -#206575 = PRESENTATION_STYLE_ASSIGNMENT((#206576)); -#206576 = SURFACE_STYLE_USAGE(.BOTH.,#206577); -#206577 = SURFACE_SIDE_STYLE('',(#206578)); -#206578 = SURFACE_STYLE_FILL_AREA(#206579); -#206579 = FILL_AREA_STYLE('',(#206580)); -#206580 = FILL_AREA_STYLE_COLOUR('',#201781); -#206581 = OVER_RIDING_STYLED_ITEM('overriding color',(#206582),#193526, - #205874); -#206582 = PRESENTATION_STYLE_ASSIGNMENT((#206583)); -#206583 = SURFACE_STYLE_USAGE(.BOTH.,#206584); -#206584 = SURFACE_SIDE_STYLE('',(#206585)); -#206585 = SURFACE_STYLE_FILL_AREA(#206586); -#206586 = FILL_AREA_STYLE('',(#206587)); -#206587 = FILL_AREA_STYLE_COLOUR('',#201781); -#206588 = OVER_RIDING_STYLED_ITEM('overriding color',(#206589),#193599, - #205874); -#206589 = PRESENTATION_STYLE_ASSIGNMENT((#206590)); -#206590 = SURFACE_STYLE_USAGE(.BOTH.,#206591); -#206591 = SURFACE_SIDE_STYLE('',(#206592)); -#206592 = SURFACE_STYLE_FILL_AREA(#206593); -#206593 = FILL_AREA_STYLE('',(#206594)); -#206594 = FILL_AREA_STYLE_COLOUR('',#201781); -#206595 = OVER_RIDING_STYLED_ITEM('overriding color',(#206596),#193737, - #205874); -#206596 = PRESENTATION_STYLE_ASSIGNMENT((#206597)); -#206597 = SURFACE_STYLE_USAGE(.BOTH.,#206598); -#206598 = SURFACE_SIDE_STYLE('',(#206599)); -#206599 = SURFACE_STYLE_FILL_AREA(#206600); -#206600 = FILL_AREA_STYLE('',(#206601)); -#206601 = FILL_AREA_STYLE_COLOUR('',#201781); -#206602 = OVER_RIDING_STYLED_ITEM('overriding color',(#206603),#193810, - #205874); -#206603 = PRESENTATION_STYLE_ASSIGNMENT((#206604)); -#206604 = SURFACE_STYLE_USAGE(.BOTH.,#206605); -#206605 = SURFACE_SIDE_STYLE('',(#206606)); -#206606 = SURFACE_STYLE_FILL_AREA(#206607); -#206607 = FILL_AREA_STYLE('',(#206608)); -#206608 = FILL_AREA_STYLE_COLOUR('',#201781); -#206609 = OVER_RIDING_STYLED_ITEM('overriding color',(#206610),#193948, - #205874); -#206610 = PRESENTATION_STYLE_ASSIGNMENT((#206611)); -#206611 = SURFACE_STYLE_USAGE(.BOTH.,#206612); -#206612 = SURFACE_SIDE_STYLE('',(#206613)); -#206613 = SURFACE_STYLE_FILL_AREA(#206614); -#206614 = FILL_AREA_STYLE('',(#206615)); -#206615 = FILL_AREA_STYLE_COLOUR('',#201781); -#206616 = OVER_RIDING_STYLED_ITEM('overriding color',(#206617),#194021, - #205874); -#206617 = PRESENTATION_STYLE_ASSIGNMENT((#206618)); -#206618 = SURFACE_STYLE_USAGE(.BOTH.,#206619); -#206619 = SURFACE_SIDE_STYLE('',(#206620)); -#206620 = SURFACE_STYLE_FILL_AREA(#206621); -#206621 = FILL_AREA_STYLE('',(#206622)); -#206622 = FILL_AREA_STYLE_COLOUR('',#201781); -#206623 = OVER_RIDING_STYLED_ITEM('overriding color',(#206624),#194071, - #205874); -#206624 = PRESENTATION_STYLE_ASSIGNMENT((#206625)); -#206625 = SURFACE_STYLE_USAGE(.BOTH.,#206626); -#206626 = SURFACE_SIDE_STYLE('',(#206627)); -#206627 = SURFACE_STYLE_FILL_AREA(#206628); -#206628 = FILL_AREA_STYLE('',(#206629)); -#206629 = FILL_AREA_STYLE_COLOUR('',#195025); -#206630 = OVER_RIDING_STYLED_ITEM('overriding color',(#206631),#194076, - #205874); -#206631 = PRESENTATION_STYLE_ASSIGNMENT((#206632)); -#206632 = SURFACE_STYLE_USAGE(.BOTH.,#206633); -#206633 = SURFACE_SIDE_STYLE('',(#206634)); -#206634 = SURFACE_STYLE_FILL_AREA(#206635); -#206635 = FILL_AREA_STYLE('',(#206636)); -#206636 = FILL_AREA_STYLE_COLOUR('',#201781); -#206637 = OVER_RIDING_STYLED_ITEM('overriding color',(#206638),#194125, - #205874); -#206638 = PRESENTATION_STYLE_ASSIGNMENT((#206639)); -#206639 = SURFACE_STYLE_USAGE(.BOTH.,#206640); -#206640 = SURFACE_SIDE_STYLE('',(#206641)); -#206641 = SURFACE_STYLE_FILL_AREA(#206642); -#206642 = FILL_AREA_STYLE('',(#206643)); -#206643 = FILL_AREA_STYLE_COLOUR('',#201781); -#206644 = OVER_RIDING_STYLED_ITEM('overriding color',(#206645),#194132, - #205874); -#206645 = PRESENTATION_STYLE_ASSIGNMENT((#206646)); -#206646 = SURFACE_STYLE_USAGE(.BOTH.,#206647); -#206647 = SURFACE_SIDE_STYLE('',(#206648)); -#206648 = SURFACE_STYLE_FILL_AREA(#206649); -#206649 = FILL_AREA_STYLE('',(#206650)); -#206650 = FILL_AREA_STYLE_COLOUR('',#201781); -#206651 = OVER_RIDING_STYLED_ITEM('overriding color',(#206652),#194181, - #205874); -#206652 = PRESENTATION_STYLE_ASSIGNMENT((#206653)); -#206653 = SURFACE_STYLE_USAGE(.BOTH.,#206654); -#206654 = SURFACE_SIDE_STYLE('',(#206655)); -#206655 = SURFACE_STYLE_FILL_AREA(#206656); -#206656 = FILL_AREA_STYLE('',(#206657)); -#206657 = FILL_AREA_STYLE_COLOUR('',#201781); -#206658 = OVER_RIDING_STYLED_ITEM('overriding color',(#206659),#194230, - #205874); -#206659 = PRESENTATION_STYLE_ASSIGNMENT((#206660)); -#206660 = SURFACE_STYLE_USAGE(.BOTH.,#206661); -#206661 = SURFACE_SIDE_STYLE('',(#206662)); -#206662 = SURFACE_STYLE_FILL_AREA(#206663); -#206663 = FILL_AREA_STYLE('',(#206664)); -#206664 = FILL_AREA_STYLE_COLOUR('',#201781); -#206665 = OVER_RIDING_STYLED_ITEM('overriding color',(#206666),#194237, - #205874); -#206666 = PRESENTATION_STYLE_ASSIGNMENT((#206667)); -#206667 = SURFACE_STYLE_USAGE(.BOTH.,#206668); -#206668 = SURFACE_SIDE_STYLE('',(#206669)); -#206669 = SURFACE_STYLE_FILL_AREA(#206670); -#206670 = FILL_AREA_STYLE('',(#206671)); -#206671 = FILL_AREA_STYLE_COLOUR('',#201781); -#206672 = OVER_RIDING_STYLED_ITEM('overriding color',(#206673),#194244, - #205874); -#206673 = PRESENTATION_STYLE_ASSIGNMENT((#206674)); -#206674 = SURFACE_STYLE_USAGE(.BOTH.,#206675); -#206675 = SURFACE_SIDE_STYLE('',(#206676)); -#206676 = SURFACE_STYLE_FILL_AREA(#206677); -#206677 = FILL_AREA_STYLE('',(#206678)); -#206678 = FILL_AREA_STYLE_COLOUR('',#201781); -#206679 = OVER_RIDING_STYLED_ITEM('overriding color',(#206680),#194293, - #205874); -#206680 = PRESENTATION_STYLE_ASSIGNMENT((#206681)); -#206681 = SURFACE_STYLE_USAGE(.BOTH.,#206682); -#206682 = SURFACE_SIDE_STYLE('',(#206683)); -#206683 = SURFACE_STYLE_FILL_AREA(#206684); -#206684 = FILL_AREA_STYLE('',(#206685)); -#206685 = FILL_AREA_STYLE_COLOUR('',#201781); -#206686 = OVER_RIDING_STYLED_ITEM('overriding color',(#206687),#194300, - #205874); -#206687 = PRESENTATION_STYLE_ASSIGNMENT((#206688)); -#206688 = SURFACE_STYLE_USAGE(.BOTH.,#206689); -#206689 = SURFACE_SIDE_STYLE('',(#206690)); -#206690 = SURFACE_STYLE_FILL_AREA(#206691); -#206691 = FILL_AREA_STYLE('',(#206692)); -#206692 = FILL_AREA_STYLE_COLOUR('',#201781); -#206693 = OVER_RIDING_STYLED_ITEM('overriding color',(#206694),#194349, - #205874); -#206694 = PRESENTATION_STYLE_ASSIGNMENT((#206695)); -#206695 = SURFACE_STYLE_USAGE(.BOTH.,#206696); -#206696 = SURFACE_SIDE_STYLE('',(#206697)); -#206697 = SURFACE_STYLE_FILL_AREA(#206698); -#206698 = FILL_AREA_STYLE('',(#206699)); -#206699 = FILL_AREA_STYLE_COLOUR('',#201781); -#206700 = OVER_RIDING_STYLED_ITEM('overriding color',(#206701),#194421, - #205874); -#206701 = PRESENTATION_STYLE_ASSIGNMENT((#206702)); -#206702 = SURFACE_STYLE_USAGE(.BOTH.,#206703); -#206703 = SURFACE_SIDE_STYLE('',(#206704)); -#206704 = SURFACE_STYLE_FILL_AREA(#206705); -#206705 = FILL_AREA_STYLE('',(#206706)); -#206706 = FILL_AREA_STYLE_COLOUR('',#201781); -#206707 = OVER_RIDING_STYLED_ITEM('overriding color',(#206708),#194428, - #205874); -#206708 = PRESENTATION_STYLE_ASSIGNMENT((#206709)); -#206709 = SURFACE_STYLE_USAGE(.BOTH.,#206710); -#206710 = SURFACE_SIDE_STYLE('',(#206711)); -#206711 = SURFACE_STYLE_FILL_AREA(#206712); -#206712 = FILL_AREA_STYLE('',(#206713)); -#206713 = FILL_AREA_STYLE_COLOUR('',#201781); -#206714 = OVER_RIDING_STYLED_ITEM('overriding color',(#206715),#194435, - #205874); -#206715 = PRESENTATION_STYLE_ASSIGNMENT((#206716)); -#206716 = SURFACE_STYLE_USAGE(.BOTH.,#206717); -#206717 = SURFACE_SIDE_STYLE('',(#206718)); -#206718 = SURFACE_STYLE_FILL_AREA(#206719); -#206719 = FILL_AREA_STYLE('',(#206720)); -#206720 = FILL_AREA_STYLE_COLOUR('',#201781); -#206721 = OVER_RIDING_STYLED_ITEM('overriding color',(#206722),#194484, - #205874); -#206722 = PRESENTATION_STYLE_ASSIGNMENT((#206723)); -#206723 = SURFACE_STYLE_USAGE(.BOTH.,#206724); -#206724 = SURFACE_SIDE_STYLE('',(#206725)); -#206725 = SURFACE_STYLE_FILL_AREA(#206726); -#206726 = FILL_AREA_STYLE('',(#206727)); -#206727 = FILL_AREA_STYLE_COLOUR('',#201781); -#206728 = OVER_RIDING_STYLED_ITEM('overriding color',(#206729),#194556, - #205874); -#206729 = PRESENTATION_STYLE_ASSIGNMENT((#206730)); -#206730 = SURFACE_STYLE_USAGE(.BOTH.,#206731); -#206731 = SURFACE_SIDE_STYLE('',(#206732)); -#206732 = SURFACE_STYLE_FILL_AREA(#206733); -#206733 = FILL_AREA_STYLE('',(#206734)); -#206734 = FILL_AREA_STYLE_COLOUR('',#201781); -#206735 = OVER_RIDING_STYLED_ITEM('overriding color',(#206736),#194563, - #205874); -#206736 = PRESENTATION_STYLE_ASSIGNMENT((#206737)); -#206737 = SURFACE_STYLE_USAGE(.BOTH.,#206738); -#206738 = SURFACE_SIDE_STYLE('',(#206739)); -#206739 = SURFACE_STYLE_FILL_AREA(#206740); -#206740 = FILL_AREA_STYLE('',(#206741)); -#206741 = FILL_AREA_STYLE_COLOUR('',#201781); -#206742 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #206743,#206751,#206759,#206766,#206773,#206780,#206787,#206794, - #206801,#206808,#206815,#206822,#206829,#206836,#206843,#206850, - #206857,#206864,#206871,#206879,#206886,#206893,#206900,#206907, - #206914,#206921,#206928,#206935,#206942,#206949,#206956,#206963, - #206970,#206977,#206984,#206991,#206998,#207005,#207012),#21885); -#206743 = STYLED_ITEM('color',(#206744),#17667); -#206744 = PRESENTATION_STYLE_ASSIGNMENT((#206745)); -#206745 = SURFACE_STYLE_USAGE(.BOTH.,#206746); -#206746 = SURFACE_SIDE_STYLE('',(#206747)); -#206747 = SURFACE_STYLE_FILL_AREA(#206748); -#206748 = FILL_AREA_STYLE('',(#206749)); -#206749 = FILL_AREA_STYLE_COLOUR('',#206750); -#206750 = COLOUR_RGB('',0.949019670486,0.925490260124,0.607843160629); -#206751 = OVER_RIDING_STYLED_ITEM('overriding color',(#206752),#18875, - #206743); -#206752 = PRESENTATION_STYLE_ASSIGNMENT((#206753)); -#206753 = SURFACE_STYLE_USAGE(.BOTH.,#206754); -#206754 = SURFACE_SIDE_STYLE('',(#206755)); -#206755 = SURFACE_STYLE_FILL_AREA(#206756); -#206756 = FILL_AREA_STYLE('',(#206757)); -#206757 = FILL_AREA_STYLE_COLOUR('',#206758); -#206758 = COLOUR_RGB('',0.600000023842,0.600000023842,0.600000023842); -#206759 = OVER_RIDING_STYLED_ITEM('overriding color',(#206760),#18951, - #206743); -#206760 = PRESENTATION_STYLE_ASSIGNMENT((#206761)); -#206761 = SURFACE_STYLE_USAGE(.BOTH.,#206762); -#206762 = SURFACE_SIDE_STYLE('',(#206763)); -#206763 = SURFACE_STYLE_FILL_AREA(#206764); -#206764 = FILL_AREA_STYLE('',(#206765)); -#206765 = FILL_AREA_STYLE_COLOUR('',#206758); -#206766 = OVER_RIDING_STYLED_ITEM('overriding color',(#206767),#19051, - #206743); -#206767 = PRESENTATION_STYLE_ASSIGNMENT((#206768)); -#206768 = SURFACE_STYLE_USAGE(.BOTH.,#206769); -#206769 = SURFACE_SIDE_STYLE('',(#206770)); -#206770 = SURFACE_STYLE_FILL_AREA(#206771); -#206771 = FILL_AREA_STYLE('',(#206772)); -#206772 = FILL_AREA_STYLE_COLOUR('',#206758); -#206773 = OVER_RIDING_STYLED_ITEM('overriding color',(#206774),#19129, - #206743); -#206774 = PRESENTATION_STYLE_ASSIGNMENT((#206775)); -#206775 = SURFACE_STYLE_USAGE(.BOTH.,#206776); -#206776 = SURFACE_SIDE_STYLE('',(#206777)); -#206777 = SURFACE_STYLE_FILL_AREA(#206778); -#206778 = FILL_AREA_STYLE('',(#206779)); -#206779 = FILL_AREA_STYLE_COLOUR('',#206758); -#206780 = OVER_RIDING_STYLED_ITEM('overriding color',(#206781),#19205, - #206743); -#206781 = PRESENTATION_STYLE_ASSIGNMENT((#206782)); -#206782 = SURFACE_STYLE_USAGE(.BOTH.,#206783); -#206783 = SURFACE_SIDE_STYLE('',(#206784)); -#206784 = SURFACE_STYLE_FILL_AREA(#206785); -#206785 = FILL_AREA_STYLE('',(#206786)); -#206786 = FILL_AREA_STYLE_COLOUR('',#206758); -#206787 = OVER_RIDING_STYLED_ITEM('overriding color',(#206788),#19347, - #206743); -#206788 = PRESENTATION_STYLE_ASSIGNMENT((#206789)); -#206789 = SURFACE_STYLE_USAGE(.BOTH.,#206790); -#206790 = SURFACE_SIDE_STYLE('',(#206791)); -#206791 = SURFACE_STYLE_FILL_AREA(#206792); -#206792 = FILL_AREA_STYLE('',(#206793)); -#206793 = FILL_AREA_STYLE_COLOUR('',#206758); -#206794 = OVER_RIDING_STYLED_ITEM('overriding color',(#206795),#19494, - #206743); -#206795 = PRESENTATION_STYLE_ASSIGNMENT((#206796)); -#206796 = SURFACE_STYLE_USAGE(.BOTH.,#206797); -#206797 = SURFACE_SIDE_STYLE('',(#206798)); -#206798 = SURFACE_STYLE_FILL_AREA(#206799); -#206799 = FILL_AREA_STYLE('',(#206800)); -#206800 = FILL_AREA_STYLE_COLOUR('',#206758); -#206801 = OVER_RIDING_STYLED_ITEM('overriding color',(#206802),#19610, - #206743); -#206802 = PRESENTATION_STYLE_ASSIGNMENT((#206803)); -#206803 = SURFACE_STYLE_USAGE(.BOTH.,#206804); -#206804 = SURFACE_SIDE_STYLE('',(#206805)); -#206805 = SURFACE_STYLE_FILL_AREA(#206806); -#206806 = FILL_AREA_STYLE('',(#206807)); -#206807 = FILL_AREA_STYLE_COLOUR('',#206758); -#206808 = OVER_RIDING_STYLED_ITEM('overriding color',(#206809),#19709, - #206743); -#206809 = PRESENTATION_STYLE_ASSIGNMENT((#206810)); -#206810 = SURFACE_STYLE_USAGE(.BOTH.,#206811); -#206811 = SURFACE_SIDE_STYLE('',(#206812)); -#206812 = SURFACE_STYLE_FILL_AREA(#206813); -#206813 = FILL_AREA_STYLE('',(#206814)); -#206814 = FILL_AREA_STYLE_COLOUR('',#206758); -#206815 = OVER_RIDING_STYLED_ITEM('overriding color',(#206816),#19808, - #206743); -#206816 = PRESENTATION_STYLE_ASSIGNMENT((#206817)); -#206817 = SURFACE_STYLE_USAGE(.BOTH.,#206818); -#206818 = SURFACE_SIDE_STYLE('',(#206819)); -#206819 = SURFACE_STYLE_FILL_AREA(#206820); -#206820 = FILL_AREA_STYLE('',(#206821)); -#206821 = FILL_AREA_STYLE_COLOUR('',#206758); -#206822 = OVER_RIDING_STYLED_ITEM('overriding color',(#206823),#19907, - #206743); -#206823 = PRESENTATION_STYLE_ASSIGNMENT((#206824)); -#206824 = SURFACE_STYLE_USAGE(.BOTH.,#206825); -#206825 = SURFACE_SIDE_STYLE('',(#206826)); -#206826 = SURFACE_STYLE_FILL_AREA(#206827); -#206827 = FILL_AREA_STYLE('',(#206828)); -#206828 = FILL_AREA_STYLE_COLOUR('',#206758); -#206829 = OVER_RIDING_STYLED_ITEM('overriding color',(#206830),#20006, - #206743); -#206830 = PRESENTATION_STYLE_ASSIGNMENT((#206831)); -#206831 = SURFACE_STYLE_USAGE(.BOTH.,#206832); -#206832 = SURFACE_SIDE_STYLE('',(#206833)); -#206833 = SURFACE_STYLE_FILL_AREA(#206834); -#206834 = FILL_AREA_STYLE('',(#206835)); -#206835 = FILL_AREA_STYLE_COLOUR('',#206758); -#206836 = OVER_RIDING_STYLED_ITEM('overriding color',(#206837),#20106, - #206743); -#206837 = PRESENTATION_STYLE_ASSIGNMENT((#206838)); -#206838 = SURFACE_STYLE_USAGE(.BOTH.,#206839); -#206839 = SURFACE_SIDE_STYLE('',(#206840)); -#206840 = SURFACE_STYLE_FILL_AREA(#206841); -#206841 = FILL_AREA_STYLE('',(#206842)); -#206842 = FILL_AREA_STYLE_COLOUR('',#206758); -#206843 = OVER_RIDING_STYLED_ITEM('overriding color',(#206844),#20202, - #206743); -#206844 = PRESENTATION_STYLE_ASSIGNMENT((#206845)); -#206845 = SURFACE_STYLE_USAGE(.BOTH.,#206846); -#206846 = SURFACE_SIDE_STYLE('',(#206847)); -#206847 = SURFACE_STYLE_FILL_AREA(#206848); -#206848 = FILL_AREA_STYLE('',(#206849)); -#206849 = FILL_AREA_STYLE_COLOUR('',#206758); -#206850 = OVER_RIDING_STYLED_ITEM('overriding color',(#206851),#20340, - #206743); -#206851 = PRESENTATION_STYLE_ASSIGNMENT((#206852)); -#206852 = SURFACE_STYLE_USAGE(.BOTH.,#206853); -#206853 = SURFACE_SIDE_STYLE('',(#206854)); -#206854 = SURFACE_STYLE_FILL_AREA(#206855); -#206855 = FILL_AREA_STYLE('',(#206856)); -#206856 = FILL_AREA_STYLE_COLOUR('',#206758); -#206857 = OVER_RIDING_STYLED_ITEM('overriding color',(#206858),#20389, - #206743); -#206858 = PRESENTATION_STYLE_ASSIGNMENT((#206859)); -#206859 = SURFACE_STYLE_USAGE(.BOTH.,#206860); -#206860 = SURFACE_SIDE_STYLE('',(#206861)); -#206861 = SURFACE_STYLE_FILL_AREA(#206862); -#206862 = FILL_AREA_STYLE('',(#206863)); -#206863 = FILL_AREA_STYLE_COLOUR('',#206758); -#206864 = OVER_RIDING_STYLED_ITEM('overriding color',(#206865),#20438, - #206743); -#206865 = PRESENTATION_STYLE_ASSIGNMENT((#206866)); -#206866 = SURFACE_STYLE_USAGE(.BOTH.,#206867); -#206867 = SURFACE_SIDE_STYLE('',(#206868)); -#206868 = SURFACE_STYLE_FILL_AREA(#206869); -#206869 = FILL_AREA_STYLE('',(#206870)); -#206870 = FILL_AREA_STYLE_COLOUR('',#206758); -#206871 = OVER_RIDING_STYLED_ITEM('overriding color',(#206872),#20543, - #206743); -#206872 = PRESENTATION_STYLE_ASSIGNMENT((#206873)); -#206873 = SURFACE_STYLE_USAGE(.BOTH.,#206874); -#206874 = SURFACE_SIDE_STYLE('',(#206875)); -#206875 = SURFACE_STYLE_FILL_AREA(#206876); -#206876 = FILL_AREA_STYLE('',(#206877)); -#206877 = FILL_AREA_STYLE_COLOUR('',#206878); -#206878 = COLOUR_RGB('',0.949019670486,0.733333349228,0.156862750649); -#206879 = OVER_RIDING_STYLED_ITEM('overriding color',(#206880),#20643, - #206743); -#206880 = PRESENTATION_STYLE_ASSIGNMENT((#206881)); -#206881 = SURFACE_STYLE_USAGE(.BOTH.,#206882); -#206882 = SURFACE_SIDE_STYLE('',(#206883)); -#206883 = SURFACE_STYLE_FILL_AREA(#206884); -#206884 = FILL_AREA_STYLE('',(#206885)); -#206885 = FILL_AREA_STYLE_COLOUR('',#206878); -#206886 = OVER_RIDING_STYLED_ITEM('overriding color',(#206887),#20690, - #206743); -#206887 = PRESENTATION_STYLE_ASSIGNMENT((#206888)); -#206888 = SURFACE_STYLE_USAGE(.BOTH.,#206889); -#206889 = SURFACE_SIDE_STYLE('',(#206890)); -#206890 = SURFACE_STYLE_FILL_AREA(#206891); -#206891 = FILL_AREA_STYLE('',(#206892)); -#206892 = FILL_AREA_STYLE_COLOUR('',#206758); -#206893 = OVER_RIDING_STYLED_ITEM('overriding color',(#206894),#20699, - #206743); -#206894 = PRESENTATION_STYLE_ASSIGNMENT((#206895)); -#206895 = SURFACE_STYLE_USAGE(.BOTH.,#206896); -#206896 = SURFACE_SIDE_STYLE('',(#206897)); -#206897 = SURFACE_STYLE_FILL_AREA(#206898); -#206898 = FILL_AREA_STYLE('',(#206899)); -#206899 = FILL_AREA_STYLE_COLOUR('',#206878); -#206900 = OVER_RIDING_STYLED_ITEM('overriding color',(#206901),#20726, - #206743); -#206901 = PRESENTATION_STYLE_ASSIGNMENT((#206902)); -#206902 = SURFACE_STYLE_USAGE(.BOTH.,#206903); -#206903 = SURFACE_SIDE_STYLE('',(#206904)); -#206904 = SURFACE_STYLE_FILL_AREA(#206905); -#206905 = FILL_AREA_STYLE('',(#206906)); -#206906 = FILL_AREA_STYLE_COLOUR('',#206758); -#206907 = OVER_RIDING_STYLED_ITEM('overriding color',(#206908),#20855, - #206743); -#206908 = PRESENTATION_STYLE_ASSIGNMENT((#206909)); -#206909 = SURFACE_STYLE_USAGE(.BOTH.,#206910); -#206910 = SURFACE_SIDE_STYLE('',(#206911)); -#206911 = SURFACE_STYLE_FILL_AREA(#206912); -#206912 = FILL_AREA_STYLE('',(#206913)); -#206913 = FILL_AREA_STYLE_COLOUR('',#206758); -#206914 = OVER_RIDING_STYLED_ITEM('overriding color',(#206915),#20946, - #206743); -#206915 = PRESENTATION_STYLE_ASSIGNMENT((#206916)); -#206916 = SURFACE_STYLE_USAGE(.BOTH.,#206917); -#206917 = SURFACE_SIDE_STYLE('',(#206918)); -#206918 = SURFACE_STYLE_FILL_AREA(#206919); -#206919 = FILL_AREA_STYLE('',(#206920)); -#206920 = FILL_AREA_STYLE_COLOUR('',#206758); -#206921 = OVER_RIDING_STYLED_ITEM('overriding color',(#206922),#20953, - #206743); +#206531 = FILL_AREA_STYLE_COLOUR('',#198418); +#206532 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206533,#206541,#206549,#206556,#206563,#206570,#206577,#206584, + #206591,#206598,#206605,#206612,#206619,#206626,#206633,#206640, + #206647,#206654,#206661,#206669,#206676,#206683,#206690,#206697, + #206704,#206711,#206718,#206725,#206732,#206739,#206746,#206753, + #206760,#206767,#206774,#206781,#206788,#206795,#206802),#24277); +#206533 = STYLED_ITEM('color',(#206534),#20059); +#206534 = PRESENTATION_STYLE_ASSIGNMENT((#206535)); +#206535 = SURFACE_STYLE_USAGE(.BOTH.,#206536); +#206536 = SURFACE_SIDE_STYLE('',(#206537)); +#206537 = SURFACE_STYLE_FILL_AREA(#206538); +#206538 = FILL_AREA_STYLE('',(#206539)); +#206539 = FILL_AREA_STYLE_COLOUR('',#206540); +#206540 = COLOUR_RGB('',0.949019670486,0.925490260124,0.607843160629); +#206541 = OVER_RIDING_STYLED_ITEM('overriding color',(#206542),#21267, + #206533); +#206542 = PRESENTATION_STYLE_ASSIGNMENT((#206543)); +#206543 = SURFACE_STYLE_USAGE(.BOTH.,#206544); +#206544 = SURFACE_SIDE_STYLE('',(#206545)); +#206545 = SURFACE_STYLE_FILL_AREA(#206546); +#206546 = FILL_AREA_STYLE('',(#206547)); +#206547 = FILL_AREA_STYLE_COLOUR('',#206548); +#206548 = COLOUR_RGB('',0.600000023842,0.600000023842,0.600000023842); +#206549 = OVER_RIDING_STYLED_ITEM('overriding color',(#206550),#21343, + #206533); +#206550 = PRESENTATION_STYLE_ASSIGNMENT((#206551)); +#206551 = SURFACE_STYLE_USAGE(.BOTH.,#206552); +#206552 = SURFACE_SIDE_STYLE('',(#206553)); +#206553 = SURFACE_STYLE_FILL_AREA(#206554); +#206554 = FILL_AREA_STYLE('',(#206555)); +#206555 = FILL_AREA_STYLE_COLOUR('',#206548); +#206556 = OVER_RIDING_STYLED_ITEM('overriding color',(#206557),#21443, + #206533); +#206557 = PRESENTATION_STYLE_ASSIGNMENT((#206558)); +#206558 = SURFACE_STYLE_USAGE(.BOTH.,#206559); +#206559 = SURFACE_SIDE_STYLE('',(#206560)); +#206560 = SURFACE_STYLE_FILL_AREA(#206561); +#206561 = FILL_AREA_STYLE('',(#206562)); +#206562 = FILL_AREA_STYLE_COLOUR('',#206548); +#206563 = OVER_RIDING_STYLED_ITEM('overriding color',(#206564),#21521, + #206533); +#206564 = PRESENTATION_STYLE_ASSIGNMENT((#206565)); +#206565 = SURFACE_STYLE_USAGE(.BOTH.,#206566); +#206566 = SURFACE_SIDE_STYLE('',(#206567)); +#206567 = SURFACE_STYLE_FILL_AREA(#206568); +#206568 = FILL_AREA_STYLE('',(#206569)); +#206569 = FILL_AREA_STYLE_COLOUR('',#206548); +#206570 = OVER_RIDING_STYLED_ITEM('overriding color',(#206571),#21597, + #206533); +#206571 = PRESENTATION_STYLE_ASSIGNMENT((#206572)); +#206572 = SURFACE_STYLE_USAGE(.BOTH.,#206573); +#206573 = SURFACE_SIDE_STYLE('',(#206574)); +#206574 = SURFACE_STYLE_FILL_AREA(#206575); +#206575 = FILL_AREA_STYLE('',(#206576)); +#206576 = FILL_AREA_STYLE_COLOUR('',#206548); +#206577 = OVER_RIDING_STYLED_ITEM('overriding color',(#206578),#21739, + #206533); +#206578 = PRESENTATION_STYLE_ASSIGNMENT((#206579)); +#206579 = SURFACE_STYLE_USAGE(.BOTH.,#206580); +#206580 = SURFACE_SIDE_STYLE('',(#206581)); +#206581 = SURFACE_STYLE_FILL_AREA(#206582); +#206582 = FILL_AREA_STYLE('',(#206583)); +#206583 = FILL_AREA_STYLE_COLOUR('',#206548); +#206584 = OVER_RIDING_STYLED_ITEM('overriding color',(#206585),#21886, + #206533); +#206585 = PRESENTATION_STYLE_ASSIGNMENT((#206586)); +#206586 = SURFACE_STYLE_USAGE(.BOTH.,#206587); +#206587 = SURFACE_SIDE_STYLE('',(#206588)); +#206588 = SURFACE_STYLE_FILL_AREA(#206589); +#206589 = FILL_AREA_STYLE('',(#206590)); +#206590 = FILL_AREA_STYLE_COLOUR('',#206548); +#206591 = OVER_RIDING_STYLED_ITEM('overriding color',(#206592),#22002, + #206533); +#206592 = PRESENTATION_STYLE_ASSIGNMENT((#206593)); +#206593 = SURFACE_STYLE_USAGE(.BOTH.,#206594); +#206594 = SURFACE_SIDE_STYLE('',(#206595)); +#206595 = SURFACE_STYLE_FILL_AREA(#206596); +#206596 = FILL_AREA_STYLE('',(#206597)); +#206597 = FILL_AREA_STYLE_COLOUR('',#206548); +#206598 = OVER_RIDING_STYLED_ITEM('overriding color',(#206599),#22101, + #206533); +#206599 = PRESENTATION_STYLE_ASSIGNMENT((#206600)); +#206600 = SURFACE_STYLE_USAGE(.BOTH.,#206601); +#206601 = SURFACE_SIDE_STYLE('',(#206602)); +#206602 = SURFACE_STYLE_FILL_AREA(#206603); +#206603 = FILL_AREA_STYLE('',(#206604)); +#206604 = FILL_AREA_STYLE_COLOUR('',#206548); +#206605 = OVER_RIDING_STYLED_ITEM('overriding color',(#206606),#22200, + #206533); +#206606 = PRESENTATION_STYLE_ASSIGNMENT((#206607)); +#206607 = SURFACE_STYLE_USAGE(.BOTH.,#206608); +#206608 = SURFACE_SIDE_STYLE('',(#206609)); +#206609 = SURFACE_STYLE_FILL_AREA(#206610); +#206610 = FILL_AREA_STYLE('',(#206611)); +#206611 = FILL_AREA_STYLE_COLOUR('',#206548); +#206612 = OVER_RIDING_STYLED_ITEM('overriding color',(#206613),#22299, + #206533); +#206613 = PRESENTATION_STYLE_ASSIGNMENT((#206614)); +#206614 = SURFACE_STYLE_USAGE(.BOTH.,#206615); +#206615 = SURFACE_SIDE_STYLE('',(#206616)); +#206616 = SURFACE_STYLE_FILL_AREA(#206617); +#206617 = FILL_AREA_STYLE('',(#206618)); +#206618 = FILL_AREA_STYLE_COLOUR('',#206548); +#206619 = OVER_RIDING_STYLED_ITEM('overriding color',(#206620),#22398, + #206533); +#206620 = PRESENTATION_STYLE_ASSIGNMENT((#206621)); +#206621 = SURFACE_STYLE_USAGE(.BOTH.,#206622); +#206622 = SURFACE_SIDE_STYLE('',(#206623)); +#206623 = SURFACE_STYLE_FILL_AREA(#206624); +#206624 = FILL_AREA_STYLE('',(#206625)); +#206625 = FILL_AREA_STYLE_COLOUR('',#206548); +#206626 = OVER_RIDING_STYLED_ITEM('overriding color',(#206627),#22498, + #206533); +#206627 = PRESENTATION_STYLE_ASSIGNMENT((#206628)); +#206628 = SURFACE_STYLE_USAGE(.BOTH.,#206629); +#206629 = SURFACE_SIDE_STYLE('',(#206630)); +#206630 = SURFACE_STYLE_FILL_AREA(#206631); +#206631 = FILL_AREA_STYLE('',(#206632)); +#206632 = FILL_AREA_STYLE_COLOUR('',#206548); +#206633 = OVER_RIDING_STYLED_ITEM('overriding color',(#206634),#22594, + #206533); +#206634 = PRESENTATION_STYLE_ASSIGNMENT((#206635)); +#206635 = SURFACE_STYLE_USAGE(.BOTH.,#206636); +#206636 = SURFACE_SIDE_STYLE('',(#206637)); +#206637 = SURFACE_STYLE_FILL_AREA(#206638); +#206638 = FILL_AREA_STYLE('',(#206639)); +#206639 = FILL_AREA_STYLE_COLOUR('',#206548); +#206640 = OVER_RIDING_STYLED_ITEM('overriding color',(#206641),#22732, + #206533); +#206641 = PRESENTATION_STYLE_ASSIGNMENT((#206642)); +#206642 = SURFACE_STYLE_USAGE(.BOTH.,#206643); +#206643 = SURFACE_SIDE_STYLE('',(#206644)); +#206644 = SURFACE_STYLE_FILL_AREA(#206645); +#206645 = FILL_AREA_STYLE('',(#206646)); +#206646 = FILL_AREA_STYLE_COLOUR('',#206548); +#206647 = OVER_RIDING_STYLED_ITEM('overriding color',(#206648),#22781, + #206533); +#206648 = PRESENTATION_STYLE_ASSIGNMENT((#206649)); +#206649 = SURFACE_STYLE_USAGE(.BOTH.,#206650); +#206650 = SURFACE_SIDE_STYLE('',(#206651)); +#206651 = SURFACE_STYLE_FILL_AREA(#206652); +#206652 = FILL_AREA_STYLE('',(#206653)); +#206653 = FILL_AREA_STYLE_COLOUR('',#206548); +#206654 = OVER_RIDING_STYLED_ITEM('overriding color',(#206655),#22830, + #206533); +#206655 = PRESENTATION_STYLE_ASSIGNMENT((#206656)); +#206656 = SURFACE_STYLE_USAGE(.BOTH.,#206657); +#206657 = SURFACE_SIDE_STYLE('',(#206658)); +#206658 = SURFACE_STYLE_FILL_AREA(#206659); +#206659 = FILL_AREA_STYLE('',(#206660)); +#206660 = FILL_AREA_STYLE_COLOUR('',#206548); +#206661 = OVER_RIDING_STYLED_ITEM('overriding color',(#206662),#22935, + #206533); +#206662 = PRESENTATION_STYLE_ASSIGNMENT((#206663)); +#206663 = SURFACE_STYLE_USAGE(.BOTH.,#206664); +#206664 = SURFACE_SIDE_STYLE('',(#206665)); +#206665 = SURFACE_STYLE_FILL_AREA(#206666); +#206666 = FILL_AREA_STYLE('',(#206667)); +#206667 = FILL_AREA_STYLE_COLOUR('',#206668); +#206668 = COLOUR_RGB('',0.949019670486,0.733333349228,0.156862750649); +#206669 = OVER_RIDING_STYLED_ITEM('overriding color',(#206670),#23035, + #206533); +#206670 = PRESENTATION_STYLE_ASSIGNMENT((#206671)); +#206671 = SURFACE_STYLE_USAGE(.BOTH.,#206672); +#206672 = SURFACE_SIDE_STYLE('',(#206673)); +#206673 = SURFACE_STYLE_FILL_AREA(#206674); +#206674 = FILL_AREA_STYLE('',(#206675)); +#206675 = FILL_AREA_STYLE_COLOUR('',#206668); +#206676 = OVER_RIDING_STYLED_ITEM('overriding color',(#206677),#23082, + #206533); +#206677 = PRESENTATION_STYLE_ASSIGNMENT((#206678)); +#206678 = SURFACE_STYLE_USAGE(.BOTH.,#206679); +#206679 = SURFACE_SIDE_STYLE('',(#206680)); +#206680 = SURFACE_STYLE_FILL_AREA(#206681); +#206681 = FILL_AREA_STYLE('',(#206682)); +#206682 = FILL_AREA_STYLE_COLOUR('',#206548); +#206683 = OVER_RIDING_STYLED_ITEM('overriding color',(#206684),#23091, + #206533); +#206684 = PRESENTATION_STYLE_ASSIGNMENT((#206685)); +#206685 = SURFACE_STYLE_USAGE(.BOTH.,#206686); +#206686 = SURFACE_SIDE_STYLE('',(#206687)); +#206687 = SURFACE_STYLE_FILL_AREA(#206688); +#206688 = FILL_AREA_STYLE('',(#206689)); +#206689 = FILL_AREA_STYLE_COLOUR('',#206668); +#206690 = OVER_RIDING_STYLED_ITEM('overriding color',(#206691),#23118, + #206533); +#206691 = PRESENTATION_STYLE_ASSIGNMENT((#206692)); +#206692 = SURFACE_STYLE_USAGE(.BOTH.,#206693); +#206693 = SURFACE_SIDE_STYLE('',(#206694)); +#206694 = SURFACE_STYLE_FILL_AREA(#206695); +#206695 = FILL_AREA_STYLE('',(#206696)); +#206696 = FILL_AREA_STYLE_COLOUR('',#206548); +#206697 = OVER_RIDING_STYLED_ITEM('overriding color',(#206698),#23247, + #206533); +#206698 = PRESENTATION_STYLE_ASSIGNMENT((#206699)); +#206699 = SURFACE_STYLE_USAGE(.BOTH.,#206700); +#206700 = SURFACE_SIDE_STYLE('',(#206701)); +#206701 = SURFACE_STYLE_FILL_AREA(#206702); +#206702 = FILL_AREA_STYLE('',(#206703)); +#206703 = FILL_AREA_STYLE_COLOUR('',#206548); +#206704 = OVER_RIDING_STYLED_ITEM('overriding color',(#206705),#23338, + #206533); +#206705 = PRESENTATION_STYLE_ASSIGNMENT((#206706)); +#206706 = SURFACE_STYLE_USAGE(.BOTH.,#206707); +#206707 = SURFACE_SIDE_STYLE('',(#206708)); +#206708 = SURFACE_STYLE_FILL_AREA(#206709); +#206709 = FILL_AREA_STYLE('',(#206710)); +#206710 = FILL_AREA_STYLE_COLOUR('',#206548); +#206711 = OVER_RIDING_STYLED_ITEM('overriding color',(#206712),#23345, + #206533); +#206712 = PRESENTATION_STYLE_ASSIGNMENT((#206713)); +#206713 = SURFACE_STYLE_USAGE(.BOTH.,#206714); +#206714 = SURFACE_SIDE_STYLE('',(#206715)); +#206715 = SURFACE_STYLE_FILL_AREA(#206716); +#206716 = FILL_AREA_STYLE('',(#206717)); +#206717 = FILL_AREA_STYLE_COLOUR('',#206548); +#206718 = OVER_RIDING_STYLED_ITEM('overriding color',(#206719),#23436, + #206533); +#206719 = PRESENTATION_STYLE_ASSIGNMENT((#206720)); +#206720 = SURFACE_STYLE_USAGE(.BOTH.,#206721); +#206721 = SURFACE_SIDE_STYLE('',(#206722)); +#206722 = SURFACE_STYLE_FILL_AREA(#206723); +#206723 = FILL_AREA_STYLE('',(#206724)); +#206724 = FILL_AREA_STYLE_COLOUR('',#206548); +#206725 = OVER_RIDING_STYLED_ITEM('overriding color',(#206726),#23449, + #206533); +#206726 = PRESENTATION_STYLE_ASSIGNMENT((#206727)); +#206727 = SURFACE_STYLE_USAGE(.BOTH.,#206728); +#206728 = SURFACE_SIDE_STYLE('',(#206729)); +#206729 = SURFACE_STYLE_FILL_AREA(#206730); +#206730 = FILL_AREA_STYLE('',(#206731)); +#206731 = FILL_AREA_STYLE_COLOUR('',#206548); +#206732 = OVER_RIDING_STYLED_ITEM('overriding color',(#206733),#23498, + #206533); +#206733 = PRESENTATION_STYLE_ASSIGNMENT((#206734)); +#206734 = SURFACE_STYLE_USAGE(.BOTH.,#206735); +#206735 = SURFACE_SIDE_STYLE('',(#206736)); +#206736 = SURFACE_STYLE_FILL_AREA(#206737); +#206737 = FILL_AREA_STYLE('',(#206738)); +#206738 = FILL_AREA_STYLE_COLOUR('',#206548); +#206739 = OVER_RIDING_STYLED_ITEM('overriding color',(#206740),#23591, + #206533); +#206740 = PRESENTATION_STYLE_ASSIGNMENT((#206741)); +#206741 = SURFACE_STYLE_USAGE(.BOTH.,#206742); +#206742 = SURFACE_SIDE_STYLE('',(#206743)); +#206743 = SURFACE_STYLE_FILL_AREA(#206744); +#206744 = FILL_AREA_STYLE('',(#206745)); +#206745 = FILL_AREA_STYLE_COLOUR('',#206548); +#206746 = OVER_RIDING_STYLED_ITEM('overriding color',(#206747),#23915, + #206533); +#206747 = PRESENTATION_STYLE_ASSIGNMENT((#206748)); +#206748 = SURFACE_STYLE_USAGE(.BOTH.,#206749); +#206749 = SURFACE_SIDE_STYLE('',(#206750)); +#206750 = SURFACE_STYLE_FILL_AREA(#206751); +#206751 = FILL_AREA_STYLE('',(#206752)); +#206752 = FILL_AREA_STYLE_COLOUR('',#206548); +#206753 = OVER_RIDING_STYLED_ITEM('overriding color',(#206754),#23942, + #206533); +#206754 = PRESENTATION_STYLE_ASSIGNMENT((#206755)); +#206755 = SURFACE_STYLE_USAGE(.BOTH.,#206756); +#206756 = SURFACE_SIDE_STYLE('',(#206757)); +#206757 = SURFACE_STYLE_FILL_AREA(#206758); +#206758 = FILL_AREA_STYLE('',(#206759)); +#206759 = FILL_AREA_STYLE_COLOUR('',#206548); +#206760 = OVER_RIDING_STYLED_ITEM('overriding color',(#206761),#23949, + #206533); +#206761 = PRESENTATION_STYLE_ASSIGNMENT((#206762)); +#206762 = SURFACE_STYLE_USAGE(.BOTH.,#206763); +#206763 = SURFACE_SIDE_STYLE('',(#206764)); +#206764 = SURFACE_STYLE_FILL_AREA(#206765); +#206765 = FILL_AREA_STYLE('',(#206766)); +#206766 = FILL_AREA_STYLE_COLOUR('',#206668); +#206767 = OVER_RIDING_STYLED_ITEM('overriding color',(#206768),#24050, + #206533); +#206768 = PRESENTATION_STYLE_ASSIGNMENT((#206769)); +#206769 = SURFACE_STYLE_USAGE(.BOTH.,#206770); +#206770 = SURFACE_SIDE_STYLE('',(#206771)); +#206771 = SURFACE_STYLE_FILL_AREA(#206772); +#206772 = FILL_AREA_STYLE('',(#206773)); +#206773 = FILL_AREA_STYLE_COLOUR('',#206668); +#206774 = OVER_RIDING_STYLED_ITEM('overriding color',(#206775),#24159, + #206533); +#206775 = PRESENTATION_STYLE_ASSIGNMENT((#206776)); +#206776 = SURFACE_STYLE_USAGE(.BOTH.,#206777); +#206777 = SURFACE_SIDE_STYLE('',(#206778)); +#206778 = SURFACE_STYLE_FILL_AREA(#206779); +#206779 = FILL_AREA_STYLE('',(#206780)); +#206780 = FILL_AREA_STYLE_COLOUR('',#206668); +#206781 = OVER_RIDING_STYLED_ITEM('overriding color',(#206782),#24207, + #206533); +#206782 = PRESENTATION_STYLE_ASSIGNMENT((#206783)); +#206783 = SURFACE_STYLE_USAGE(.BOTH.,#206784); +#206784 = SURFACE_SIDE_STYLE('',(#206785)); +#206785 = SURFACE_STYLE_FILL_AREA(#206786); +#206786 = FILL_AREA_STYLE('',(#206787)); +#206787 = FILL_AREA_STYLE_COLOUR('',#206668); +#206788 = OVER_RIDING_STYLED_ITEM('overriding color',(#206789),#24256, + #206533); +#206789 = PRESENTATION_STYLE_ASSIGNMENT((#206790)); +#206790 = SURFACE_STYLE_USAGE(.BOTH.,#206791); +#206791 = SURFACE_SIDE_STYLE('',(#206792)); +#206792 = SURFACE_STYLE_FILL_AREA(#206793); +#206793 = FILL_AREA_STYLE('',(#206794)); +#206794 = FILL_AREA_STYLE_COLOUR('',#206668); +#206795 = OVER_RIDING_STYLED_ITEM('overriding color',(#206796),#24263, + #206533); +#206796 = PRESENTATION_STYLE_ASSIGNMENT((#206797)); +#206797 = SURFACE_STYLE_USAGE(.BOTH.,#206798); +#206798 = SURFACE_SIDE_STYLE('',(#206799)); +#206799 = SURFACE_STYLE_FILL_AREA(#206800); +#206800 = FILL_AREA_STYLE('',(#206801)); +#206801 = FILL_AREA_STYLE_COLOUR('',#206548); +#206802 = OVER_RIDING_STYLED_ITEM('overriding color',(#206803),#24270, + #206533); +#206803 = PRESENTATION_STYLE_ASSIGNMENT((#206804)); +#206804 = SURFACE_STYLE_USAGE(.BOTH.,#206805); +#206805 = SURFACE_SIDE_STYLE('',(#206806)); +#206806 = SURFACE_STYLE_FILL_AREA(#206807); +#206807 = FILL_AREA_STYLE('',(#206808)); +#206808 = FILL_AREA_STYLE_COLOUR('',#206668); +#206809 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206810),#169511); +#206810 = STYLED_ITEM('color',(#206811),#169407); +#206811 = PRESENTATION_STYLE_ASSIGNMENT((#206812,#206818)); +#206812 = SURFACE_STYLE_USAGE(.BOTH.,#206813); +#206813 = SURFACE_SIDE_STYLE('',(#206814)); +#206814 = SURFACE_STYLE_FILL_AREA(#206815); +#206815 = FILL_AREA_STYLE('',(#206816)); +#206816 = FILL_AREA_STYLE_COLOUR('',#206817); +#206817 = COLOUR_RGB('',3.137255087495E-002,5.098039284348E-002, + 7.843137718737E-003); +#206818 = CURVE_STYLE('',#206819,POSITIVE_LENGTH_MEASURE(0.1),#206817); +#206819 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#206820 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206821),#168993); +#206821 = STYLED_ITEM('color',(#206822),#168663); +#206822 = PRESENTATION_STYLE_ASSIGNMENT((#206823,#206829)); +#206823 = SURFACE_STYLE_USAGE(.BOTH.,#206824); +#206824 = SURFACE_SIDE_STYLE('',(#206825)); +#206825 = SURFACE_STYLE_FILL_AREA(#206826); +#206826 = FILL_AREA_STYLE('',(#206827)); +#206827 = FILL_AREA_STYLE_COLOUR('',#206828); +#206828 = COLOUR_RGB('',0.E+000,0.501960813999,0.E+000); +#206829 = CURVE_STYLE('',#206830,POSITIVE_LENGTH_MEASURE(0.1),#206828); +#206830 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#206831 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206832,#206840,#206847,#206854,#206861,#206868,#206875,#206882, + #206889,#206896,#206903),#170315); +#206832 = STYLED_ITEM('color',(#206833),#169673); +#206833 = PRESENTATION_STYLE_ASSIGNMENT((#206834)); +#206834 = SURFACE_STYLE_USAGE(.BOTH.,#206835); +#206835 = SURFACE_SIDE_STYLE('',(#206836)); +#206836 = SURFACE_STYLE_FILL_AREA(#206837); +#206837 = FILL_AREA_STYLE('',(#206838)); +#206838 = FILL_AREA_STYLE_COLOUR('',#206839); +#206839 = COLOUR_RGB('',0.705882370472,0.705882370472,0.705882370472); +#206840 = OVER_RIDING_STYLED_ITEM('overriding color',(#206841),#169675, + #206832); +#206841 = PRESENTATION_STYLE_ASSIGNMENT((#206842)); +#206842 = SURFACE_STYLE_USAGE(.BOTH.,#206843); +#206843 = SURFACE_SIDE_STYLE('',(#206844)); +#206844 = SURFACE_STYLE_FILL_AREA(#206845); +#206845 = FILL_AREA_STYLE('',(#206846)); +#206846 = FILL_AREA_STYLE_COLOUR('',#206839); +#206847 = OVER_RIDING_STYLED_ITEM('overriding color',(#206848),#169795, + #206832); +#206848 = PRESENTATION_STYLE_ASSIGNMENT((#206849)); +#206849 = SURFACE_STYLE_USAGE(.BOTH.,#206850); +#206850 = SURFACE_SIDE_STYLE('',(#206851)); +#206851 = SURFACE_STYLE_FILL_AREA(#206852); +#206852 = FILL_AREA_STYLE('',(#206853)); +#206853 = FILL_AREA_STYLE_COLOUR('',#206839); +#206854 = OVER_RIDING_STYLED_ITEM('overriding color',(#206855),#169871, + #206832); +#206855 = PRESENTATION_STYLE_ASSIGNMENT((#206856)); +#206856 = SURFACE_STYLE_USAGE(.BOTH.,#206857); +#206857 = SURFACE_SIDE_STYLE('',(#206858)); +#206858 = SURFACE_STYLE_FILL_AREA(#206859); +#206859 = FILL_AREA_STYLE('',(#206860)); +#206860 = FILL_AREA_STYLE_COLOUR('',#206839); +#206861 = OVER_RIDING_STYLED_ITEM('overriding color',(#206862),#169947, + #206832); +#206862 = PRESENTATION_STYLE_ASSIGNMENT((#206863)); +#206863 = SURFACE_STYLE_USAGE(.BOTH.,#206864); +#206864 = SURFACE_SIDE_STYLE('',(#206865)); +#206865 = SURFACE_STYLE_FILL_AREA(#206866); +#206866 = FILL_AREA_STYLE('',(#206867)); +#206867 = FILL_AREA_STYLE_COLOUR('',#206839); +#206868 = OVER_RIDING_STYLED_ITEM('overriding color',(#206869),#170023, + #206832); +#206869 = PRESENTATION_STYLE_ASSIGNMENT((#206870)); +#206870 = SURFACE_STYLE_USAGE(.BOTH.,#206871); +#206871 = SURFACE_SIDE_STYLE('',(#206872)); +#206872 = SURFACE_STYLE_FILL_AREA(#206873); +#206873 = FILL_AREA_STYLE('',(#206874)); +#206874 = FILL_AREA_STYLE_COLOUR('',#206839); +#206875 = OVER_RIDING_STYLED_ITEM('overriding color',(#206876),#170099, + #206832); +#206876 = PRESENTATION_STYLE_ASSIGNMENT((#206877)); +#206877 = SURFACE_STYLE_USAGE(.BOTH.,#206878); +#206878 = SURFACE_SIDE_STYLE('',(#206879)); +#206879 = SURFACE_STYLE_FILL_AREA(#206880); +#206880 = FILL_AREA_STYLE('',(#206881)); +#206881 = FILL_AREA_STYLE_COLOUR('',#206839); +#206882 = OVER_RIDING_STYLED_ITEM('overriding color',(#206883),#170179, + #206832); +#206883 = PRESENTATION_STYLE_ASSIGNMENT((#206884)); +#206884 = SURFACE_STYLE_USAGE(.BOTH.,#206885); +#206885 = SURFACE_SIDE_STYLE('',(#206886)); +#206886 = SURFACE_STYLE_FILL_AREA(#206887); +#206887 = FILL_AREA_STYLE('',(#206888)); +#206888 = FILL_AREA_STYLE_COLOUR('',#206839); +#206889 = OVER_RIDING_STYLED_ITEM('overriding color',(#206890),#170228, + #206832); +#206890 = PRESENTATION_STYLE_ASSIGNMENT((#206891)); +#206891 = SURFACE_STYLE_USAGE(.BOTH.,#206892); +#206892 = SURFACE_SIDE_STYLE('',(#206893)); +#206893 = SURFACE_STYLE_FILL_AREA(#206894); +#206894 = FILL_AREA_STYLE('',(#206895)); +#206895 = FILL_AREA_STYLE_COLOUR('',#206839); +#206896 = OVER_RIDING_STYLED_ITEM('overriding color',(#206897),#170281, + #206832); +#206897 = PRESENTATION_STYLE_ASSIGNMENT((#206898)); +#206898 = SURFACE_STYLE_USAGE(.BOTH.,#206899); +#206899 = SURFACE_SIDE_STYLE('',(#206900)); +#206900 = SURFACE_STYLE_FILL_AREA(#206901); +#206901 = FILL_AREA_STYLE('',(#206902)); +#206902 = FILL_AREA_STYLE_COLOUR('',#206839); +#206903 = OVER_RIDING_STYLED_ITEM('overriding color',(#206904),#170308, + #206832); +#206904 = PRESENTATION_STYLE_ASSIGNMENT((#206905)); +#206905 = SURFACE_STYLE_USAGE(.BOTH.,#206906); +#206906 = SURFACE_SIDE_STYLE('',(#206907)); +#206907 = SURFACE_STYLE_FILL_AREA(#206908); +#206908 = FILL_AREA_STYLE('',(#206909)); +#206909 = FILL_AREA_STYLE_COLOUR('',#206839); +#206910 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206911),#20006); +#206911 = STYLED_ITEM('color',(#206912),#19676); +#206912 = PRESENTATION_STYLE_ASSIGNMENT((#206913,#206918)); +#206913 = SURFACE_STYLE_USAGE(.BOTH.,#206914); +#206914 = SURFACE_SIDE_STYLE('',(#206915)); +#206915 = SURFACE_STYLE_FILL_AREA(#206916); +#206916 = FILL_AREA_STYLE('',(#206917)); +#206917 = FILL_AREA_STYLE_COLOUR('',#197440); +#206918 = CURVE_STYLE('',#206919,POSITIVE_LENGTH_MEASURE(0.1),#197440); +#206919 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#206920 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #206921,#206929,#206936,#206943,#206950,#206957,#206964,#206971, + #206978,#206985,#206992,#206999,#207006,#207013,#207020,#207027, + #207034,#207041,#207048,#207055,#207062,#207069,#207076,#207083, + #207090,#207097,#207104,#207111,#207118,#207125,#207132,#207139, + #207146,#207153,#207160,#207167,#207174,#207181,#207188,#207195, + #207202,#207209,#207216,#207223,#207230,#207237,#207244,#207251, + #207258,#207265,#207272,#207279,#207286,#207293,#207300),#18754); +#206921 = STYLED_ITEM('color',(#206922),#14288); #206922 = PRESENTATION_STYLE_ASSIGNMENT((#206923)); #206923 = SURFACE_STYLE_USAGE(.BOTH.,#206924); #206924 = SURFACE_SIDE_STYLE('',(#206925)); #206925 = SURFACE_STYLE_FILL_AREA(#206926); #206926 = FILL_AREA_STYLE('',(#206927)); -#206927 = FILL_AREA_STYLE_COLOUR('',#206758); -#206928 = OVER_RIDING_STYLED_ITEM('overriding color',(#206929),#21044, - #206743); -#206929 = PRESENTATION_STYLE_ASSIGNMENT((#206930)); -#206930 = SURFACE_STYLE_USAGE(.BOTH.,#206931); -#206931 = SURFACE_SIDE_STYLE('',(#206932)); -#206932 = SURFACE_STYLE_FILL_AREA(#206933); -#206933 = FILL_AREA_STYLE('',(#206934)); -#206934 = FILL_AREA_STYLE_COLOUR('',#206758); -#206935 = OVER_RIDING_STYLED_ITEM('overriding color',(#206936),#21057, - #206743); -#206936 = PRESENTATION_STYLE_ASSIGNMENT((#206937)); -#206937 = SURFACE_STYLE_USAGE(.BOTH.,#206938); -#206938 = SURFACE_SIDE_STYLE('',(#206939)); -#206939 = SURFACE_STYLE_FILL_AREA(#206940); -#206940 = FILL_AREA_STYLE('',(#206941)); -#206941 = FILL_AREA_STYLE_COLOUR('',#206758); -#206942 = OVER_RIDING_STYLED_ITEM('overriding color',(#206943),#21106, - #206743); -#206943 = PRESENTATION_STYLE_ASSIGNMENT((#206944)); -#206944 = SURFACE_STYLE_USAGE(.BOTH.,#206945); -#206945 = SURFACE_SIDE_STYLE('',(#206946)); -#206946 = SURFACE_STYLE_FILL_AREA(#206947); -#206947 = FILL_AREA_STYLE('',(#206948)); -#206948 = FILL_AREA_STYLE_COLOUR('',#206758); -#206949 = OVER_RIDING_STYLED_ITEM('overriding color',(#206950),#21199, - #206743); -#206950 = PRESENTATION_STYLE_ASSIGNMENT((#206951)); -#206951 = SURFACE_STYLE_USAGE(.BOTH.,#206952); -#206952 = SURFACE_SIDE_STYLE('',(#206953)); -#206953 = SURFACE_STYLE_FILL_AREA(#206954); -#206954 = FILL_AREA_STYLE('',(#206955)); -#206955 = FILL_AREA_STYLE_COLOUR('',#206758); -#206956 = OVER_RIDING_STYLED_ITEM('overriding color',(#206957),#21523, - #206743); -#206957 = PRESENTATION_STYLE_ASSIGNMENT((#206958)); -#206958 = SURFACE_STYLE_USAGE(.BOTH.,#206959); -#206959 = SURFACE_SIDE_STYLE('',(#206960)); -#206960 = SURFACE_STYLE_FILL_AREA(#206961); -#206961 = FILL_AREA_STYLE('',(#206962)); -#206962 = FILL_AREA_STYLE_COLOUR('',#206758); -#206963 = OVER_RIDING_STYLED_ITEM('overriding color',(#206964),#21550, - #206743); -#206964 = PRESENTATION_STYLE_ASSIGNMENT((#206965)); -#206965 = SURFACE_STYLE_USAGE(.BOTH.,#206966); -#206966 = SURFACE_SIDE_STYLE('',(#206967)); -#206967 = SURFACE_STYLE_FILL_AREA(#206968); -#206968 = FILL_AREA_STYLE('',(#206969)); -#206969 = FILL_AREA_STYLE_COLOUR('',#206758); -#206970 = OVER_RIDING_STYLED_ITEM('overriding color',(#206971),#21557, - #206743); -#206971 = PRESENTATION_STYLE_ASSIGNMENT((#206972)); -#206972 = SURFACE_STYLE_USAGE(.BOTH.,#206973); -#206973 = SURFACE_SIDE_STYLE('',(#206974)); -#206974 = SURFACE_STYLE_FILL_AREA(#206975); -#206975 = FILL_AREA_STYLE('',(#206976)); -#206976 = FILL_AREA_STYLE_COLOUR('',#206878); -#206977 = OVER_RIDING_STYLED_ITEM('overriding color',(#206978),#21658, - #206743); -#206978 = PRESENTATION_STYLE_ASSIGNMENT((#206979)); -#206979 = SURFACE_STYLE_USAGE(.BOTH.,#206980); -#206980 = SURFACE_SIDE_STYLE('',(#206981)); -#206981 = SURFACE_STYLE_FILL_AREA(#206982); -#206982 = FILL_AREA_STYLE('',(#206983)); -#206983 = FILL_AREA_STYLE_COLOUR('',#206878); -#206984 = OVER_RIDING_STYLED_ITEM('overriding color',(#206985),#21767, - #206743); -#206985 = PRESENTATION_STYLE_ASSIGNMENT((#206986)); -#206986 = SURFACE_STYLE_USAGE(.BOTH.,#206987); -#206987 = SURFACE_SIDE_STYLE('',(#206988)); -#206988 = SURFACE_STYLE_FILL_AREA(#206989); -#206989 = FILL_AREA_STYLE('',(#206990)); -#206990 = FILL_AREA_STYLE_COLOUR('',#206878); -#206991 = OVER_RIDING_STYLED_ITEM('overriding color',(#206992),#21815, - #206743); -#206992 = PRESENTATION_STYLE_ASSIGNMENT((#206993)); -#206993 = SURFACE_STYLE_USAGE(.BOTH.,#206994); -#206994 = SURFACE_SIDE_STYLE('',(#206995)); -#206995 = SURFACE_STYLE_FILL_AREA(#206996); -#206996 = FILL_AREA_STYLE('',(#206997)); -#206997 = FILL_AREA_STYLE_COLOUR('',#206878); -#206998 = OVER_RIDING_STYLED_ITEM('overriding color',(#206999),#21864, - #206743); -#206999 = PRESENTATION_STYLE_ASSIGNMENT((#207000)); -#207000 = SURFACE_STYLE_USAGE(.BOTH.,#207001); -#207001 = SURFACE_SIDE_STYLE('',(#207002)); -#207002 = SURFACE_STYLE_FILL_AREA(#207003); -#207003 = FILL_AREA_STYLE('',(#207004)); -#207004 = FILL_AREA_STYLE_COLOUR('',#206878); -#207005 = OVER_RIDING_STYLED_ITEM('overriding color',(#207006),#21871, - #206743); -#207006 = PRESENTATION_STYLE_ASSIGNMENT((#207007)); -#207007 = SURFACE_STYLE_USAGE(.BOTH.,#207008); -#207008 = SURFACE_SIDE_STYLE('',(#207009)); -#207009 = SURFACE_STYLE_FILL_AREA(#207010); -#207010 = FILL_AREA_STYLE('',(#207011)); -#207011 = FILL_AREA_STYLE_COLOUR('',#206758); -#207012 = OVER_RIDING_STYLED_ITEM('overriding color',(#207013),#21878, - #206743); -#207013 = PRESENTATION_STYLE_ASSIGNMENT((#207014)); -#207014 = SURFACE_STYLE_USAGE(.BOTH.,#207015); -#207015 = SURFACE_SIDE_STYLE('',(#207016)); -#207016 = SURFACE_STYLE_FILL_AREA(#207017); -#207017 = FILL_AREA_STYLE('',(#207018)); -#207018 = FILL_AREA_STYLE_COLOUR('',#206878); -#207019 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207020,#207027,#207035,#207042,#207049,#207056,#207063,#207070, - #207077,#207084,#207091,#207098,#207105,#207112,#207119,#207126, - #207133,#207140,#207147,#207154,#207161,#207168,#207175,#207182, - #207189,#207196),#158689); -#207020 = STYLED_ITEM('color',(#207021),#156707); +#206927 = FILL_AREA_STYLE_COLOUR('',#206928); +#206928 = COLOUR_RGB('',0.803921580315,0.803921580315,0.803921580315); +#206929 = OVER_RIDING_STYLED_ITEM('overriding color',(#206930),#14290, + #206921); +#206930 = PRESENTATION_STYLE_ASSIGNMENT((#206931)); +#206931 = SURFACE_STYLE_USAGE(.BOTH.,#206932); +#206932 = SURFACE_SIDE_STYLE('',(#206933)); +#206933 = SURFACE_STYLE_FILL_AREA(#206934); +#206934 = FILL_AREA_STYLE('',(#206935)); +#206935 = FILL_AREA_STYLE_COLOUR('',#206928); +#206936 = OVER_RIDING_STYLED_ITEM('overriding color',(#206937),#14405, + #206921); +#206937 = PRESENTATION_STYLE_ASSIGNMENT((#206938)); +#206938 = SURFACE_STYLE_USAGE(.BOTH.,#206939); +#206939 = SURFACE_SIDE_STYLE('',(#206940)); +#206940 = SURFACE_STYLE_FILL_AREA(#206941); +#206941 = FILL_AREA_STYLE('',(#206942)); +#206942 = FILL_AREA_STYLE_COLOUR('',#206928); +#206943 = OVER_RIDING_STYLED_ITEM('overriding color',(#206944),#14521, + #206921); +#206944 = PRESENTATION_STYLE_ASSIGNMENT((#206945)); +#206945 = SURFACE_STYLE_USAGE(.BOTH.,#206946); +#206946 = SURFACE_SIDE_STYLE('',(#206947)); +#206947 = SURFACE_STYLE_FILL_AREA(#206948); +#206948 = FILL_AREA_STYLE('',(#206949)); +#206949 = FILL_AREA_STYLE_COLOUR('',#206928); +#206950 = OVER_RIDING_STYLED_ITEM('overriding color',(#206951),#14679, + #206921); +#206951 = PRESENTATION_STYLE_ASSIGNMENT((#206952)); +#206952 = SURFACE_STYLE_USAGE(.BOTH.,#206953); +#206953 = SURFACE_SIDE_STYLE('',(#206954)); +#206954 = SURFACE_STYLE_FILL_AREA(#206955); +#206955 = FILL_AREA_STYLE('',(#206956)); +#206956 = FILL_AREA_STYLE_COLOUR('',#206928); +#206957 = OVER_RIDING_STYLED_ITEM('overriding color',(#206958),#14794, + #206921); +#206958 = PRESENTATION_STYLE_ASSIGNMENT((#206959)); +#206959 = SURFACE_STYLE_USAGE(.BOTH.,#206960); +#206960 = SURFACE_SIDE_STYLE('',(#206961)); +#206961 = SURFACE_STYLE_FILL_AREA(#206962); +#206962 = FILL_AREA_STYLE('',(#206963)); +#206963 = FILL_AREA_STYLE_COLOUR('',#206928); +#206964 = OVER_RIDING_STYLED_ITEM('overriding color',(#206965),#14891, + #206921); +#206965 = PRESENTATION_STYLE_ASSIGNMENT((#206966)); +#206966 = SURFACE_STYLE_USAGE(.BOTH.,#206967); +#206967 = SURFACE_SIDE_STYLE('',(#206968)); +#206968 = SURFACE_STYLE_FILL_AREA(#206969); +#206969 = FILL_AREA_STYLE('',(#206970)); +#206970 = FILL_AREA_STYLE_COLOUR('',#206928); +#206971 = OVER_RIDING_STYLED_ITEM('overriding color',(#206972),#14983, + #206921); +#206972 = PRESENTATION_STYLE_ASSIGNMENT((#206973)); +#206973 = SURFACE_STYLE_USAGE(.BOTH.,#206974); +#206974 = SURFACE_SIDE_STYLE('',(#206975)); +#206975 = SURFACE_STYLE_FILL_AREA(#206976); +#206976 = FILL_AREA_STYLE('',(#206977)); +#206977 = FILL_AREA_STYLE_COLOUR('',#206928); +#206978 = OVER_RIDING_STYLED_ITEM('overriding color',(#206979),#15080, + #206921); +#206979 = PRESENTATION_STYLE_ASSIGNMENT((#206980)); +#206980 = SURFACE_STYLE_USAGE(.BOTH.,#206981); +#206981 = SURFACE_SIDE_STYLE('',(#206982)); +#206982 = SURFACE_STYLE_FILL_AREA(#206983); +#206983 = FILL_AREA_STYLE('',(#206984)); +#206984 = FILL_AREA_STYLE_COLOUR('',#206928); +#206985 = OVER_RIDING_STYLED_ITEM('overriding color',(#206986),#15172, + #206921); +#206986 = PRESENTATION_STYLE_ASSIGNMENT((#206987)); +#206987 = SURFACE_STYLE_USAGE(.BOTH.,#206988); +#206988 = SURFACE_SIDE_STYLE('',(#206989)); +#206989 = SURFACE_STYLE_FILL_AREA(#206990); +#206990 = FILL_AREA_STYLE('',(#206991)); +#206991 = FILL_AREA_STYLE_COLOUR('',#206928); +#206992 = OVER_RIDING_STYLED_ITEM('overriding color',(#206993),#15269, + #206921); +#206993 = PRESENTATION_STYLE_ASSIGNMENT((#206994)); +#206994 = SURFACE_STYLE_USAGE(.BOTH.,#206995); +#206995 = SURFACE_SIDE_STYLE('',(#206996)); +#206996 = SURFACE_STYLE_FILL_AREA(#206997); +#206997 = FILL_AREA_STYLE('',(#206998)); +#206998 = FILL_AREA_STYLE_COLOUR('',#206928); +#206999 = OVER_RIDING_STYLED_ITEM('overriding color',(#207000),#15300, + #206921); +#207000 = PRESENTATION_STYLE_ASSIGNMENT((#207001)); +#207001 = SURFACE_STYLE_USAGE(.BOTH.,#207002); +#207002 = SURFACE_SIDE_STYLE('',(#207003)); +#207003 = SURFACE_STYLE_FILL_AREA(#207004); +#207004 = FILL_AREA_STYLE('',(#207005)); +#207005 = FILL_AREA_STYLE_COLOUR('',#206928); +#207006 = OVER_RIDING_STYLED_ITEM('overriding color',(#207007),#15408, + #206921); +#207007 = PRESENTATION_STYLE_ASSIGNMENT((#207008)); +#207008 = SURFACE_STYLE_USAGE(.BOTH.,#207009); +#207009 = SURFACE_SIDE_STYLE('',(#207010)); +#207010 = SURFACE_STYLE_FILL_AREA(#207011); +#207011 = FILL_AREA_STYLE('',(#207012)); +#207012 = FILL_AREA_STYLE_COLOUR('',#206928); +#207013 = OVER_RIDING_STYLED_ITEM('overriding color',(#207014),#15460, + #206921); +#207014 = PRESENTATION_STYLE_ASSIGNMENT((#207015)); +#207015 = SURFACE_STYLE_USAGE(.BOTH.,#207016); +#207016 = SURFACE_SIDE_STYLE('',(#207017)); +#207017 = SURFACE_STYLE_FILL_AREA(#207018); +#207018 = FILL_AREA_STYLE('',(#207019)); +#207019 = FILL_AREA_STYLE_COLOUR('',#206928); +#207020 = OVER_RIDING_STYLED_ITEM('overriding color',(#207021),#15547, + #206921); #207021 = PRESENTATION_STYLE_ASSIGNMENT((#207022)); #207022 = SURFACE_STYLE_USAGE(.BOTH.,#207023); #207023 = SURFACE_SIDE_STYLE('',(#207024)); #207024 = SURFACE_STYLE_FILL_AREA(#207025); #207025 = FILL_AREA_STYLE('',(#207026)); -#207026 = FILL_AREA_STYLE_COLOUR('',#205152); -#207027 = OVER_RIDING_STYLED_ITEM('overriding color',(#207028),#156709, - #207020); +#207026 = FILL_AREA_STYLE_COLOUR('',#206928); +#207027 = OVER_RIDING_STYLED_ITEM('overriding color',(#207028),#15599, + #206921); #207028 = PRESENTATION_STYLE_ASSIGNMENT((#207029)); #207029 = SURFACE_STYLE_USAGE(.BOTH.,#207030); #207030 = SURFACE_SIDE_STYLE('',(#207031)); #207031 = SURFACE_STYLE_FILL_AREA(#207032); #207032 = FILL_AREA_STYLE('',(#207033)); -#207033 = FILL_AREA_STYLE_COLOUR('',#207034); -#207034 = COLOUR_RGB('',0.196078434587,0.196078434587,0.196078434587); -#207035 = OVER_RIDING_STYLED_ITEM('overriding color',(#207036),#157001, - #207020); -#207036 = PRESENTATION_STYLE_ASSIGNMENT((#207037)); -#207037 = SURFACE_STYLE_USAGE(.BOTH.,#207038); -#207038 = SURFACE_SIDE_STYLE('',(#207039)); -#207039 = SURFACE_STYLE_FILL_AREA(#207040); -#207040 = FILL_AREA_STYLE('',(#207041)); -#207041 = FILL_AREA_STYLE_COLOUR('',#207034); -#207042 = OVER_RIDING_STYLED_ITEM('overriding color',(#207043),#157092, - #207020); -#207043 = PRESENTATION_STYLE_ASSIGNMENT((#207044)); -#207044 = SURFACE_STYLE_USAGE(.BOTH.,#207045); -#207045 = SURFACE_SIDE_STYLE('',(#207046)); -#207046 = SURFACE_STYLE_FILL_AREA(#207047); -#207047 = FILL_AREA_STYLE('',(#207048)); -#207048 = FILL_AREA_STYLE_COLOUR('',#207034); -#207049 = OVER_RIDING_STYLED_ITEM('overriding color',(#207050),#157146, - #207020); -#207050 = PRESENTATION_STYLE_ASSIGNMENT((#207051)); -#207051 = SURFACE_STYLE_USAGE(.BOTH.,#207052); -#207052 = SURFACE_SIDE_STYLE('',(#207053)); -#207053 = SURFACE_STYLE_FILL_AREA(#207054); -#207054 = FILL_AREA_STYLE('',(#207055)); -#207055 = FILL_AREA_STYLE_COLOUR('',#207034); -#207056 = OVER_RIDING_STYLED_ITEM('overriding color',(#207057),#157262, - #207020); -#207057 = PRESENTATION_STYLE_ASSIGNMENT((#207058)); -#207058 = SURFACE_STYLE_USAGE(.BOTH.,#207059); -#207059 = SURFACE_SIDE_STYLE('',(#207060)); -#207060 = SURFACE_STYLE_FILL_AREA(#207061); -#207061 = FILL_AREA_STYLE('',(#207062)); -#207062 = FILL_AREA_STYLE_COLOUR('',#207034); -#207063 = OVER_RIDING_STYLED_ITEM('overriding color',(#207064),#157442, - #207020); -#207064 = PRESENTATION_STYLE_ASSIGNMENT((#207065)); -#207065 = SURFACE_STYLE_USAGE(.BOTH.,#207066); -#207066 = SURFACE_SIDE_STYLE('',(#207067)); -#207067 = SURFACE_STYLE_FILL_AREA(#207068); -#207068 = FILL_AREA_STYLE('',(#207069)); -#207069 = FILL_AREA_STYLE_COLOUR('',#207034); -#207070 = OVER_RIDING_STYLED_ITEM('overriding color',(#207071),#157535, - #207020); -#207071 = PRESENTATION_STYLE_ASSIGNMENT((#207072)); -#207072 = SURFACE_STYLE_USAGE(.BOTH.,#207073); -#207073 = SURFACE_SIDE_STYLE('',(#207074)); -#207074 = SURFACE_STYLE_FILL_AREA(#207075); -#207075 = FILL_AREA_STYLE('',(#207076)); -#207076 = FILL_AREA_STYLE_COLOUR('',#207034); -#207077 = OVER_RIDING_STYLED_ITEM('overriding color',(#207078),#157633, - #207020); -#207078 = PRESENTATION_STYLE_ASSIGNMENT((#207079)); -#207079 = SURFACE_STYLE_USAGE(.BOTH.,#207080); -#207080 = SURFACE_SIDE_STYLE('',(#207081)); -#207081 = SURFACE_STYLE_FILL_AREA(#207082); -#207082 = FILL_AREA_STYLE('',(#207083)); -#207083 = FILL_AREA_STYLE_COLOUR('',#207034); -#207084 = OVER_RIDING_STYLED_ITEM('overriding color',(#207085),#157659, - #207020); -#207085 = PRESENTATION_STYLE_ASSIGNMENT((#207086)); -#207086 = SURFACE_STYLE_USAGE(.BOTH.,#207087); -#207087 = SURFACE_SIDE_STYLE('',(#207088)); -#207088 = SURFACE_STYLE_FILL_AREA(#207089); -#207089 = FILL_AREA_STYLE('',(#207090)); -#207090 = FILL_AREA_STYLE_COLOUR('',#207034); -#207091 = OVER_RIDING_STYLED_ITEM('overriding color',(#207092),#157735, - #207020); -#207092 = PRESENTATION_STYLE_ASSIGNMENT((#207093)); -#207093 = SURFACE_STYLE_USAGE(.BOTH.,#207094); -#207094 = SURFACE_SIDE_STYLE('',(#207095)); -#207095 = SURFACE_STYLE_FILL_AREA(#207096); -#207096 = FILL_AREA_STYLE('',(#207097)); -#207097 = FILL_AREA_STYLE_COLOUR('',#207034); -#207098 = OVER_RIDING_STYLED_ITEM('overriding color',(#207099),#157790, - #207020); -#207099 = PRESENTATION_STYLE_ASSIGNMENT((#207100)); -#207100 = SURFACE_STYLE_USAGE(.BOTH.,#207101); -#207101 = SURFACE_SIDE_STYLE('',(#207102)); -#207102 = SURFACE_STYLE_FILL_AREA(#207103); -#207103 = FILL_AREA_STYLE('',(#207104)); -#207104 = FILL_AREA_STYLE_COLOUR('',#207034); -#207105 = OVER_RIDING_STYLED_ITEM('overriding color',(#207106),#157844, - #207020); -#207106 = PRESENTATION_STYLE_ASSIGNMENT((#207107)); -#207107 = SURFACE_STYLE_USAGE(.BOTH.,#207108); -#207108 = SURFACE_SIDE_STYLE('',(#207109)); -#207109 = SURFACE_STYLE_FILL_AREA(#207110); -#207110 = FILL_AREA_STYLE('',(#207111)); -#207111 = FILL_AREA_STYLE_COLOUR('',#207034); -#207112 = OVER_RIDING_STYLED_ITEM('overriding color',(#207113),#157877, - #207020); -#207113 = PRESENTATION_STYLE_ASSIGNMENT((#207114)); -#207114 = SURFACE_STYLE_USAGE(.BOTH.,#207115); -#207115 = SURFACE_SIDE_STYLE('',(#207116)); -#207116 = SURFACE_STYLE_FILL_AREA(#207117); -#207117 = FILL_AREA_STYLE('',(#207118)); -#207118 = FILL_AREA_STYLE_COLOUR('',#207034); -#207119 = OVER_RIDING_STYLED_ITEM('overriding color',(#207120),#157953, - #207020); -#207120 = PRESENTATION_STYLE_ASSIGNMENT((#207121)); -#207121 = SURFACE_STYLE_USAGE(.BOTH.,#207122); -#207122 = SURFACE_SIDE_STYLE('',(#207123)); -#207123 = SURFACE_STYLE_FILL_AREA(#207124); -#207124 = FILL_AREA_STYLE('',(#207125)); -#207125 = FILL_AREA_STYLE_COLOUR('',#207034); -#207126 = OVER_RIDING_STYLED_ITEM('overriding color',(#207127),#158007, - #207020); -#207127 = PRESENTATION_STYLE_ASSIGNMENT((#207128)); -#207128 = SURFACE_STYLE_USAGE(.BOTH.,#207129); -#207129 = SURFACE_SIDE_STYLE('',(#207130)); -#207130 = SURFACE_STYLE_FILL_AREA(#207131); -#207131 = FILL_AREA_STYLE('',(#207132)); -#207132 = FILL_AREA_STYLE_COLOUR('',#207034); -#207133 = OVER_RIDING_STYLED_ITEM('overriding color',(#207134),#158061, - #207020); -#207134 = PRESENTATION_STYLE_ASSIGNMENT((#207135)); -#207135 = SURFACE_STYLE_USAGE(.BOTH.,#207136); -#207136 = SURFACE_SIDE_STYLE('',(#207137)); -#207137 = SURFACE_STYLE_FILL_AREA(#207138); -#207138 = FILL_AREA_STYLE('',(#207139)); -#207139 = FILL_AREA_STYLE_COLOUR('',#207034); -#207140 = OVER_RIDING_STYLED_ITEM('overriding color',(#207141),#158093, - #207020); -#207141 = PRESENTATION_STYLE_ASSIGNMENT((#207142)); -#207142 = SURFACE_STYLE_USAGE(.BOTH.,#207143); -#207143 = SURFACE_SIDE_STYLE('',(#207144)); -#207144 = SURFACE_STYLE_FILL_AREA(#207145); -#207145 = FILL_AREA_STYLE('',(#207146)); -#207146 = FILL_AREA_STYLE_COLOUR('',#207034); -#207147 = OVER_RIDING_STYLED_ITEM('overriding color',(#207148),#158168, - #207020); -#207148 = PRESENTATION_STYLE_ASSIGNMENT((#207149)); -#207149 = SURFACE_STYLE_USAGE(.BOTH.,#207150); -#207150 = SURFACE_SIDE_STYLE('',(#207151)); -#207151 = SURFACE_STYLE_FILL_AREA(#207152); -#207152 = FILL_AREA_STYLE('',(#207153)); -#207153 = FILL_AREA_STYLE_COLOUR('',#207034); -#207154 = OVER_RIDING_STYLED_ITEM('overriding color',(#207155),#158221, - #207020); -#207155 = PRESENTATION_STYLE_ASSIGNMENT((#207156)); -#207156 = SURFACE_STYLE_USAGE(.BOTH.,#207157); -#207157 = SURFACE_SIDE_STYLE('',(#207158)); -#207158 = SURFACE_STYLE_FILL_AREA(#207159); -#207159 = FILL_AREA_STYLE('',(#207160)); -#207160 = FILL_AREA_STYLE_COLOUR('',#207034); -#207161 = OVER_RIDING_STYLED_ITEM('overriding color',(#207162),#158274, - #207020); -#207162 = PRESENTATION_STYLE_ASSIGNMENT((#207163)); -#207163 = SURFACE_STYLE_USAGE(.BOTH.,#207164); -#207164 = SURFACE_SIDE_STYLE('',(#207165)); -#207165 = SURFACE_STYLE_FILL_AREA(#207166); -#207166 = FILL_AREA_STYLE('',(#207167)); -#207167 = FILL_AREA_STYLE_COLOUR('',#207034); -#207168 = OVER_RIDING_STYLED_ITEM('overriding color',(#207169),#158305, - #207020); -#207169 = PRESENTATION_STYLE_ASSIGNMENT((#207170)); -#207170 = SURFACE_STYLE_USAGE(.BOTH.,#207171); -#207171 = SURFACE_SIDE_STYLE('',(#207172)); -#207172 = SURFACE_STYLE_FILL_AREA(#207173); -#207173 = FILL_AREA_STYLE('',(#207174)); -#207174 = FILL_AREA_STYLE_COLOUR('',#207034); -#207175 = OVER_RIDING_STYLED_ITEM('overriding color',(#207176),#158470, - #207020); -#207176 = PRESENTATION_STYLE_ASSIGNMENT((#207177)); -#207177 = SURFACE_STYLE_USAGE(.BOTH.,#207178); -#207178 = SURFACE_SIDE_STYLE('',(#207179)); -#207179 = SURFACE_STYLE_FILL_AREA(#207180); -#207180 = FILL_AREA_STYLE('',(#207181)); -#207181 = FILL_AREA_STYLE_COLOUR('',#207034); -#207182 = OVER_RIDING_STYLED_ITEM('overriding color',(#207183),#158563, - #207020); -#207183 = PRESENTATION_STYLE_ASSIGNMENT((#207184)); -#207184 = SURFACE_STYLE_USAGE(.BOTH.,#207185); -#207185 = SURFACE_SIDE_STYLE('',(#207186)); -#207186 = SURFACE_STYLE_FILL_AREA(#207187); -#207187 = FILL_AREA_STYLE('',(#207188)); -#207188 = FILL_AREA_STYLE_COLOUR('',#207034); -#207189 = OVER_RIDING_STYLED_ITEM('overriding color',(#207190),#158656, - #207020); -#207190 = PRESENTATION_STYLE_ASSIGNMENT((#207191)); -#207191 = SURFACE_STYLE_USAGE(.BOTH.,#207192); -#207192 = SURFACE_SIDE_STYLE('',(#207193)); -#207193 = SURFACE_STYLE_FILL_AREA(#207194); -#207194 = FILL_AREA_STYLE('',(#207195)); -#207195 = FILL_AREA_STYLE_COLOUR('',#207034); -#207196 = OVER_RIDING_STYLED_ITEM('overriding color',(#207197),#158682, - #207020); -#207197 = PRESENTATION_STYLE_ASSIGNMENT((#207198)); -#207198 = SURFACE_STYLE_USAGE(.BOTH.,#207199); -#207199 = SURFACE_SIDE_STYLE('',(#207200)); -#207200 = SURFACE_STYLE_FILL_AREA(#207201); -#207201 = FILL_AREA_STYLE('',(#207202)); -#207202 = FILL_AREA_STYLE_COLOUR('',#207034); -#207203 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207204),#167119); -#207204 = STYLED_ITEM('color',(#207205),#167015); -#207205 = PRESENTATION_STYLE_ASSIGNMENT((#207206,#207212)); -#207206 = SURFACE_STYLE_USAGE(.BOTH.,#207207); -#207207 = SURFACE_SIDE_STYLE('',(#207208)); -#207208 = SURFACE_STYLE_FILL_AREA(#207209); -#207209 = FILL_AREA_STYLE('',(#207210)); -#207210 = FILL_AREA_STYLE_COLOUR('',#207211); -#207211 = COLOUR_RGB('',3.137255087495E-002,5.098039284348E-002, - 7.843137718737E-003); -#207212 = CURVE_STYLE('',#207213,POSITIVE_LENGTH_MEASURE(0.1),#207211); -#207213 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#207214 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207215),#17614); -#207215 = STYLED_ITEM('color',(#207216),#17284); -#207216 = PRESENTATION_STYLE_ASSIGNMENT((#207217,#207222)); -#207217 = SURFACE_STYLE_USAGE(.BOTH.,#207218); -#207218 = SURFACE_SIDE_STYLE('',(#207219)); -#207219 = SURFACE_STYLE_FILL_AREA(#207220); -#207220 = FILL_AREA_STYLE('',(#207221)); -#207221 = FILL_AREA_STYLE_COLOUR('',#201036); -#207222 = CURVE_STYLE('',#207223,POSITIVE_LENGTH_MEASURE(0.1),#201036); -#207223 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#207224 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207225,#207233,#207240,#207247,#207254,#207261,#207268,#207275, - #207282,#207289,#207296,#207303,#207310,#207317,#207324,#207331, - #207338,#207345,#207352,#207359,#207366,#207373,#207380,#207387, - #207394,#207401,#207408,#207415,#207422,#207429,#207436,#207443, - #207450,#207457,#207464,#207471,#207478,#207485,#207492,#207499, - #207506,#207513,#207520,#207527,#207534,#207541,#207548,#207555, - #207562,#207569,#207576,#207583,#207590,#207597,#207604),#16362); -#207225 = STYLED_ITEM('color',(#207226),#11896); -#207226 = PRESENTATION_STYLE_ASSIGNMENT((#207227)); -#207227 = SURFACE_STYLE_USAGE(.BOTH.,#207228); -#207228 = SURFACE_SIDE_STYLE('',(#207229)); -#207229 = SURFACE_STYLE_FILL_AREA(#207230); -#207230 = FILL_AREA_STYLE('',(#207231)); -#207231 = FILL_AREA_STYLE_COLOUR('',#207232); -#207232 = COLOUR_RGB('',0.803921580315,0.803921580315,0.803921580315); -#207233 = OVER_RIDING_STYLED_ITEM('overriding color',(#207234),#11898, - #207225); -#207234 = PRESENTATION_STYLE_ASSIGNMENT((#207235)); -#207235 = SURFACE_STYLE_USAGE(.BOTH.,#207236); -#207236 = SURFACE_SIDE_STYLE('',(#207237)); -#207237 = SURFACE_STYLE_FILL_AREA(#207238); -#207238 = FILL_AREA_STYLE('',(#207239)); -#207239 = FILL_AREA_STYLE_COLOUR('',#207232); -#207240 = OVER_RIDING_STYLED_ITEM('overriding color',(#207241),#12013, - #207225); -#207241 = PRESENTATION_STYLE_ASSIGNMENT((#207242)); -#207242 = SURFACE_STYLE_USAGE(.BOTH.,#207243); -#207243 = SURFACE_SIDE_STYLE('',(#207244)); -#207244 = SURFACE_STYLE_FILL_AREA(#207245); -#207245 = FILL_AREA_STYLE('',(#207246)); -#207246 = FILL_AREA_STYLE_COLOUR('',#207232); -#207247 = OVER_RIDING_STYLED_ITEM('overriding color',(#207248),#12129, - #207225); -#207248 = PRESENTATION_STYLE_ASSIGNMENT((#207249)); -#207249 = SURFACE_STYLE_USAGE(.BOTH.,#207250); -#207250 = SURFACE_SIDE_STYLE('',(#207251)); -#207251 = SURFACE_STYLE_FILL_AREA(#207252); -#207252 = FILL_AREA_STYLE('',(#207253)); -#207253 = FILL_AREA_STYLE_COLOUR('',#207232); -#207254 = OVER_RIDING_STYLED_ITEM('overriding color',(#207255),#12287, - #207225); -#207255 = PRESENTATION_STYLE_ASSIGNMENT((#207256)); -#207256 = SURFACE_STYLE_USAGE(.BOTH.,#207257); -#207257 = SURFACE_SIDE_STYLE('',(#207258)); -#207258 = SURFACE_STYLE_FILL_AREA(#207259); -#207259 = FILL_AREA_STYLE('',(#207260)); -#207260 = FILL_AREA_STYLE_COLOUR('',#207232); -#207261 = OVER_RIDING_STYLED_ITEM('overriding color',(#207262),#12402, - #207225); -#207262 = PRESENTATION_STYLE_ASSIGNMENT((#207263)); -#207263 = SURFACE_STYLE_USAGE(.BOTH.,#207264); -#207264 = SURFACE_SIDE_STYLE('',(#207265)); -#207265 = SURFACE_STYLE_FILL_AREA(#207266); -#207266 = FILL_AREA_STYLE('',(#207267)); -#207267 = FILL_AREA_STYLE_COLOUR('',#207232); -#207268 = OVER_RIDING_STYLED_ITEM('overriding color',(#207269),#12499, - #207225); -#207269 = PRESENTATION_STYLE_ASSIGNMENT((#207270)); -#207270 = SURFACE_STYLE_USAGE(.BOTH.,#207271); -#207271 = SURFACE_SIDE_STYLE('',(#207272)); -#207272 = SURFACE_STYLE_FILL_AREA(#207273); -#207273 = FILL_AREA_STYLE('',(#207274)); -#207274 = FILL_AREA_STYLE_COLOUR('',#207232); -#207275 = OVER_RIDING_STYLED_ITEM('overriding color',(#207276),#12591, - #207225); -#207276 = PRESENTATION_STYLE_ASSIGNMENT((#207277)); -#207277 = SURFACE_STYLE_USAGE(.BOTH.,#207278); -#207278 = SURFACE_SIDE_STYLE('',(#207279)); -#207279 = SURFACE_STYLE_FILL_AREA(#207280); -#207280 = FILL_AREA_STYLE('',(#207281)); -#207281 = FILL_AREA_STYLE_COLOUR('',#207232); -#207282 = OVER_RIDING_STYLED_ITEM('overriding color',(#207283),#12688, - #207225); -#207283 = PRESENTATION_STYLE_ASSIGNMENT((#207284)); -#207284 = SURFACE_STYLE_USAGE(.BOTH.,#207285); -#207285 = SURFACE_SIDE_STYLE('',(#207286)); -#207286 = SURFACE_STYLE_FILL_AREA(#207287); -#207287 = FILL_AREA_STYLE('',(#207288)); -#207288 = FILL_AREA_STYLE_COLOUR('',#207232); -#207289 = OVER_RIDING_STYLED_ITEM('overriding color',(#207290),#12780, - #207225); -#207290 = PRESENTATION_STYLE_ASSIGNMENT((#207291)); -#207291 = SURFACE_STYLE_USAGE(.BOTH.,#207292); -#207292 = SURFACE_SIDE_STYLE('',(#207293)); -#207293 = SURFACE_STYLE_FILL_AREA(#207294); -#207294 = FILL_AREA_STYLE('',(#207295)); -#207295 = FILL_AREA_STYLE_COLOUR('',#207232); -#207296 = OVER_RIDING_STYLED_ITEM('overriding color',(#207297),#12877, - #207225); -#207297 = PRESENTATION_STYLE_ASSIGNMENT((#207298)); -#207298 = SURFACE_STYLE_USAGE(.BOTH.,#207299); -#207299 = SURFACE_SIDE_STYLE('',(#207300)); -#207300 = SURFACE_STYLE_FILL_AREA(#207301); -#207301 = FILL_AREA_STYLE('',(#207302)); -#207302 = FILL_AREA_STYLE_COLOUR('',#207232); -#207303 = OVER_RIDING_STYLED_ITEM('overriding color',(#207304),#12908, - #207225); -#207304 = PRESENTATION_STYLE_ASSIGNMENT((#207305)); -#207305 = SURFACE_STYLE_USAGE(.BOTH.,#207306); -#207306 = SURFACE_SIDE_STYLE('',(#207307)); -#207307 = SURFACE_STYLE_FILL_AREA(#207308); -#207308 = FILL_AREA_STYLE('',(#207309)); -#207309 = FILL_AREA_STYLE_COLOUR('',#207232); -#207310 = OVER_RIDING_STYLED_ITEM('overriding color',(#207311),#13016, - #207225); -#207311 = PRESENTATION_STYLE_ASSIGNMENT((#207312)); -#207312 = SURFACE_STYLE_USAGE(.BOTH.,#207313); -#207313 = SURFACE_SIDE_STYLE('',(#207314)); -#207314 = SURFACE_STYLE_FILL_AREA(#207315); -#207315 = FILL_AREA_STYLE('',(#207316)); -#207316 = FILL_AREA_STYLE_COLOUR('',#207232); -#207317 = OVER_RIDING_STYLED_ITEM('overriding color',(#207318),#13068, - #207225); -#207318 = PRESENTATION_STYLE_ASSIGNMENT((#207319)); -#207319 = SURFACE_STYLE_USAGE(.BOTH.,#207320); -#207320 = SURFACE_SIDE_STYLE('',(#207321)); -#207321 = SURFACE_STYLE_FILL_AREA(#207322); -#207322 = FILL_AREA_STYLE('',(#207323)); -#207323 = FILL_AREA_STYLE_COLOUR('',#207232); -#207324 = OVER_RIDING_STYLED_ITEM('overriding color',(#207325),#13155, - #207225); -#207325 = PRESENTATION_STYLE_ASSIGNMENT((#207326)); -#207326 = SURFACE_STYLE_USAGE(.BOTH.,#207327); -#207327 = SURFACE_SIDE_STYLE('',(#207328)); -#207328 = SURFACE_STYLE_FILL_AREA(#207329); -#207329 = FILL_AREA_STYLE('',(#207330)); -#207330 = FILL_AREA_STYLE_COLOUR('',#207232); -#207331 = OVER_RIDING_STYLED_ITEM('overriding color',(#207332),#13207, - #207225); -#207332 = PRESENTATION_STYLE_ASSIGNMENT((#207333)); -#207333 = SURFACE_STYLE_USAGE(.BOTH.,#207334); -#207334 = SURFACE_SIDE_STYLE('',(#207335)); -#207335 = SURFACE_STYLE_FILL_AREA(#207336); -#207336 = FILL_AREA_STYLE('',(#207337)); -#207337 = FILL_AREA_STYLE_COLOUR('',#207232); -#207338 = OVER_RIDING_STYLED_ITEM('overriding color',(#207339),#13317, - #207225); -#207339 = PRESENTATION_STYLE_ASSIGNMENT((#207340)); -#207340 = SURFACE_STYLE_USAGE(.BOTH.,#207341); -#207341 = SURFACE_SIDE_STYLE('',(#207342)); -#207342 = SURFACE_STYLE_FILL_AREA(#207343); -#207343 = FILL_AREA_STYLE('',(#207344)); -#207344 = FILL_AREA_STYLE_COLOUR('',#207232); -#207345 = OVER_RIDING_STYLED_ITEM('overriding color',(#207346),#13369, - #207225); -#207346 = PRESENTATION_STYLE_ASSIGNMENT((#207347)); -#207347 = SURFACE_STYLE_USAGE(.BOTH.,#207348); -#207348 = SURFACE_SIDE_STYLE('',(#207349)); -#207349 = SURFACE_STYLE_FILL_AREA(#207350); -#207350 = FILL_AREA_STYLE('',(#207351)); -#207351 = FILL_AREA_STYLE_COLOUR('',#207232); -#207352 = OVER_RIDING_STYLED_ITEM('overriding color',(#207353),#13456, - #207225); -#207353 = PRESENTATION_STYLE_ASSIGNMENT((#207354)); -#207354 = SURFACE_STYLE_USAGE(.BOTH.,#207355); -#207355 = SURFACE_SIDE_STYLE('',(#207356)); -#207356 = SURFACE_STYLE_FILL_AREA(#207357); -#207357 = FILL_AREA_STYLE('',(#207358)); -#207358 = FILL_AREA_STYLE_COLOUR('',#207232); -#207359 = OVER_RIDING_STYLED_ITEM('overriding color',(#207360),#13487, - #207225); -#207360 = PRESENTATION_STYLE_ASSIGNMENT((#207361)); -#207361 = SURFACE_STYLE_USAGE(.BOTH.,#207362); -#207362 = SURFACE_SIDE_STYLE('',(#207363)); -#207363 = SURFACE_STYLE_FILL_AREA(#207364); -#207364 = FILL_AREA_STYLE('',(#207365)); -#207365 = FILL_AREA_STYLE_COLOUR('',#207232); -#207366 = OVER_RIDING_STYLED_ITEM('overriding color',(#207367),#13603, - #207225); -#207367 = PRESENTATION_STYLE_ASSIGNMENT((#207368)); -#207368 = SURFACE_STYLE_USAGE(.BOTH.,#207369); -#207369 = SURFACE_SIDE_STYLE('',(#207370)); -#207370 = SURFACE_STYLE_FILL_AREA(#207371); -#207371 = FILL_AREA_STYLE('',(#207372)); -#207372 = FILL_AREA_STYLE_COLOUR('',#207232); -#207373 = OVER_RIDING_STYLED_ITEM('overriding color',(#207374),#13742, - #207225); -#207374 = PRESENTATION_STYLE_ASSIGNMENT((#207375)); -#207375 = SURFACE_STYLE_USAGE(.BOTH.,#207376); -#207376 = SURFACE_SIDE_STYLE('',(#207377)); -#207377 = SURFACE_STYLE_FILL_AREA(#207378); -#207378 = FILL_AREA_STYLE('',(#207379)); -#207379 = FILL_AREA_STYLE_COLOUR('',#207232); -#207380 = OVER_RIDING_STYLED_ITEM('overriding color',(#207381),#13812, - #207225); -#207381 = PRESENTATION_STYLE_ASSIGNMENT((#207382)); -#207382 = SURFACE_STYLE_USAGE(.BOTH.,#207383); -#207383 = SURFACE_SIDE_STYLE('',(#207384)); -#207384 = SURFACE_STYLE_FILL_AREA(#207385); -#207385 = FILL_AREA_STYLE('',(#207386)); -#207386 = FILL_AREA_STYLE_COLOUR('',#207232); -#207387 = OVER_RIDING_STYLED_ITEM('overriding color',(#207388),#13907, - #207225); -#207388 = PRESENTATION_STYLE_ASSIGNMENT((#207389)); +#207033 = FILL_AREA_STYLE_COLOUR('',#206928); +#207034 = OVER_RIDING_STYLED_ITEM('overriding color',(#207035),#15709, + #206921); +#207035 = PRESENTATION_STYLE_ASSIGNMENT((#207036)); +#207036 = SURFACE_STYLE_USAGE(.BOTH.,#207037); +#207037 = SURFACE_SIDE_STYLE('',(#207038)); +#207038 = SURFACE_STYLE_FILL_AREA(#207039); +#207039 = FILL_AREA_STYLE('',(#207040)); +#207040 = FILL_AREA_STYLE_COLOUR('',#206928); +#207041 = OVER_RIDING_STYLED_ITEM('overriding color',(#207042),#15761, + #206921); +#207042 = PRESENTATION_STYLE_ASSIGNMENT((#207043)); +#207043 = SURFACE_STYLE_USAGE(.BOTH.,#207044); +#207044 = SURFACE_SIDE_STYLE('',(#207045)); +#207045 = SURFACE_STYLE_FILL_AREA(#207046); +#207046 = FILL_AREA_STYLE('',(#207047)); +#207047 = FILL_AREA_STYLE_COLOUR('',#206928); +#207048 = OVER_RIDING_STYLED_ITEM('overriding color',(#207049),#15848, + #206921); +#207049 = PRESENTATION_STYLE_ASSIGNMENT((#207050)); +#207050 = SURFACE_STYLE_USAGE(.BOTH.,#207051); +#207051 = SURFACE_SIDE_STYLE('',(#207052)); +#207052 = SURFACE_STYLE_FILL_AREA(#207053); +#207053 = FILL_AREA_STYLE('',(#207054)); +#207054 = FILL_AREA_STYLE_COLOUR('',#206928); +#207055 = OVER_RIDING_STYLED_ITEM('overriding color',(#207056),#15879, + #206921); +#207056 = PRESENTATION_STYLE_ASSIGNMENT((#207057)); +#207057 = SURFACE_STYLE_USAGE(.BOTH.,#207058); +#207058 = SURFACE_SIDE_STYLE('',(#207059)); +#207059 = SURFACE_STYLE_FILL_AREA(#207060); +#207060 = FILL_AREA_STYLE('',(#207061)); +#207061 = FILL_AREA_STYLE_COLOUR('',#206928); +#207062 = OVER_RIDING_STYLED_ITEM('overriding color',(#207063),#15995, + #206921); +#207063 = PRESENTATION_STYLE_ASSIGNMENT((#207064)); +#207064 = SURFACE_STYLE_USAGE(.BOTH.,#207065); +#207065 = SURFACE_SIDE_STYLE('',(#207066)); +#207066 = SURFACE_STYLE_FILL_AREA(#207067); +#207067 = FILL_AREA_STYLE('',(#207068)); +#207068 = FILL_AREA_STYLE_COLOUR('',#206928); +#207069 = OVER_RIDING_STYLED_ITEM('overriding color',(#207070),#16134, + #206921); +#207070 = PRESENTATION_STYLE_ASSIGNMENT((#207071)); +#207071 = SURFACE_STYLE_USAGE(.BOTH.,#207072); +#207072 = SURFACE_SIDE_STYLE('',(#207073)); +#207073 = SURFACE_STYLE_FILL_AREA(#207074); +#207074 = FILL_AREA_STYLE('',(#207075)); +#207075 = FILL_AREA_STYLE_COLOUR('',#206928); +#207076 = OVER_RIDING_STYLED_ITEM('overriding color',(#207077),#16204, + #206921); +#207077 = PRESENTATION_STYLE_ASSIGNMENT((#207078)); +#207078 = SURFACE_STYLE_USAGE(.BOTH.,#207079); +#207079 = SURFACE_SIDE_STYLE('',(#207080)); +#207080 = SURFACE_STYLE_FILL_AREA(#207081); +#207081 = FILL_AREA_STYLE('',(#207082)); +#207082 = FILL_AREA_STYLE_COLOUR('',#206928); +#207083 = OVER_RIDING_STYLED_ITEM('overriding color',(#207084),#16299, + #206921); +#207084 = PRESENTATION_STYLE_ASSIGNMENT((#207085)); +#207085 = SURFACE_STYLE_USAGE(.BOTH.,#207086); +#207086 = SURFACE_SIDE_STYLE('',(#207087)); +#207087 = SURFACE_STYLE_FILL_AREA(#207088); +#207088 = FILL_AREA_STYLE('',(#207089)); +#207089 = FILL_AREA_STYLE_COLOUR('',#206928); +#207090 = OVER_RIDING_STYLED_ITEM('overriding color',(#207091),#16369, + #206921); +#207091 = PRESENTATION_STYLE_ASSIGNMENT((#207092)); +#207092 = SURFACE_STYLE_USAGE(.BOTH.,#207093); +#207093 = SURFACE_SIDE_STYLE('',(#207094)); +#207094 = SURFACE_STYLE_FILL_AREA(#207095); +#207095 = FILL_AREA_STYLE('',(#207096)); +#207096 = FILL_AREA_STYLE_COLOUR('',#206928); +#207097 = OVER_RIDING_STYLED_ITEM('overriding color',(#207098),#16464, + #206921); +#207098 = PRESENTATION_STYLE_ASSIGNMENT((#207099)); +#207099 = SURFACE_STYLE_USAGE(.BOTH.,#207100); +#207100 = SURFACE_SIDE_STYLE('',(#207101)); +#207101 = SURFACE_STYLE_FILL_AREA(#207102); +#207102 = FILL_AREA_STYLE('',(#207103)); +#207103 = FILL_AREA_STYLE_COLOUR('',#206928); +#207104 = OVER_RIDING_STYLED_ITEM('overriding color',(#207105),#16534, + #206921); +#207105 = PRESENTATION_STYLE_ASSIGNMENT((#207106)); +#207106 = SURFACE_STYLE_USAGE(.BOTH.,#207107); +#207107 = SURFACE_SIDE_STYLE('',(#207108)); +#207108 = SURFACE_STYLE_FILL_AREA(#207109); +#207109 = FILL_AREA_STYLE('',(#207110)); +#207110 = FILL_AREA_STYLE_COLOUR('',#206928); +#207111 = OVER_RIDING_STYLED_ITEM('overriding color',(#207112),#16629, + #206921); +#207112 = PRESENTATION_STYLE_ASSIGNMENT((#207113)); +#207113 = SURFACE_STYLE_USAGE(.BOTH.,#207114); +#207114 = SURFACE_SIDE_STYLE('',(#207115)); +#207115 = SURFACE_STYLE_FILL_AREA(#207116); +#207116 = FILL_AREA_STYLE('',(#207117)); +#207117 = FILL_AREA_STYLE_COLOUR('',#206928); +#207118 = OVER_RIDING_STYLED_ITEM('overriding color',(#207119),#16655, + #206921); +#207119 = PRESENTATION_STYLE_ASSIGNMENT((#207120)); +#207120 = SURFACE_STYLE_USAGE(.BOTH.,#207121); +#207121 = SURFACE_SIDE_STYLE('',(#207122)); +#207122 = SURFACE_STYLE_FILL_AREA(#207123); +#207123 = FILL_AREA_STYLE('',(#207124)); +#207124 = FILL_AREA_STYLE_COLOUR('',#206928); +#207125 = OVER_RIDING_STYLED_ITEM('overriding color',(#207126),#16813, + #206921); +#207126 = PRESENTATION_STYLE_ASSIGNMENT((#207127)); +#207127 = SURFACE_STYLE_USAGE(.BOTH.,#207128); +#207128 = SURFACE_SIDE_STYLE('',(#207129)); +#207129 = SURFACE_STYLE_FILL_AREA(#207130); +#207130 = FILL_AREA_STYLE('',(#207131)); +#207131 = FILL_AREA_STYLE_COLOUR('',#206928); +#207132 = OVER_RIDING_STYLED_ITEM('overriding color',(#207133),#16905, + #206921); +#207133 = PRESENTATION_STYLE_ASSIGNMENT((#207134)); +#207134 = SURFACE_STYLE_USAGE(.BOTH.,#207135); +#207135 = SURFACE_SIDE_STYLE('',(#207136)); +#207136 = SURFACE_STYLE_FILL_AREA(#207137); +#207137 = FILL_AREA_STYLE('',(#207138)); +#207138 = FILL_AREA_STYLE_COLOUR('',#206928); +#207139 = OVER_RIDING_STYLED_ITEM('overriding color',(#207140),#17002, + #206921); +#207140 = PRESENTATION_STYLE_ASSIGNMENT((#207141)); +#207141 = SURFACE_STYLE_USAGE(.BOTH.,#207142); +#207142 = SURFACE_SIDE_STYLE('',(#207143)); +#207143 = SURFACE_STYLE_FILL_AREA(#207144); +#207144 = FILL_AREA_STYLE('',(#207145)); +#207145 = FILL_AREA_STYLE_COLOUR('',#206928); +#207146 = OVER_RIDING_STYLED_ITEM('overriding color',(#207147),#17094, + #206921); +#207147 = PRESENTATION_STYLE_ASSIGNMENT((#207148)); +#207148 = SURFACE_STYLE_USAGE(.BOTH.,#207149); +#207149 = SURFACE_SIDE_STYLE('',(#207150)); +#207150 = SURFACE_STYLE_FILL_AREA(#207151); +#207151 = FILL_AREA_STYLE('',(#207152)); +#207152 = FILL_AREA_STYLE_COLOUR('',#206928); +#207153 = OVER_RIDING_STYLED_ITEM('overriding color',(#207154),#17191, + #206921); +#207154 = PRESENTATION_STYLE_ASSIGNMENT((#207155)); +#207155 = SURFACE_STYLE_USAGE(.BOTH.,#207156); +#207156 = SURFACE_SIDE_STYLE('',(#207157)); +#207157 = SURFACE_STYLE_FILL_AREA(#207158); +#207158 = FILL_AREA_STYLE('',(#207159)); +#207159 = FILL_AREA_STYLE_COLOUR('',#206928); +#207160 = OVER_RIDING_STYLED_ITEM('overriding color',(#207161),#17283, + #206921); +#207161 = PRESENTATION_STYLE_ASSIGNMENT((#207162)); +#207162 = SURFACE_STYLE_USAGE(.BOTH.,#207163); +#207163 = SURFACE_SIDE_STYLE('',(#207164)); +#207164 = SURFACE_STYLE_FILL_AREA(#207165); +#207165 = FILL_AREA_STYLE('',(#207166)); +#207166 = FILL_AREA_STYLE_COLOUR('',#206928); +#207167 = OVER_RIDING_STYLED_ITEM('overriding color',(#207168),#17380, + #206921); +#207168 = PRESENTATION_STYLE_ASSIGNMENT((#207169)); +#207169 = SURFACE_STYLE_USAGE(.BOTH.,#207170); +#207170 = SURFACE_SIDE_STYLE('',(#207171)); +#207171 = SURFACE_STYLE_FILL_AREA(#207172); +#207172 = FILL_AREA_STYLE('',(#207173)); +#207173 = FILL_AREA_STYLE_COLOUR('',#206928); +#207174 = OVER_RIDING_STYLED_ITEM('overriding color',(#207175),#17411, + #206921); +#207175 = PRESENTATION_STYLE_ASSIGNMENT((#207176)); +#207176 = SURFACE_STYLE_USAGE(.BOTH.,#207177); +#207177 = SURFACE_SIDE_STYLE('',(#207178)); +#207178 = SURFACE_STYLE_FILL_AREA(#207179); +#207179 = FILL_AREA_STYLE('',(#207180)); +#207180 = FILL_AREA_STYLE_COLOUR('',#206928); +#207181 = OVER_RIDING_STYLED_ITEM('overriding color',(#207182),#17446, + #206921); +#207182 = PRESENTATION_STYLE_ASSIGNMENT((#207183)); +#207183 = SURFACE_STYLE_USAGE(.BOTH.,#207184); +#207184 = SURFACE_SIDE_STYLE('',(#207185)); +#207185 = SURFACE_STYLE_FILL_AREA(#207186); +#207186 = FILL_AREA_STYLE('',(#207187)); +#207187 = FILL_AREA_STYLE_COLOUR('',#206928); +#207188 = OVER_RIDING_STYLED_ITEM('overriding color',(#207189),#17554, + #206921); +#207189 = PRESENTATION_STYLE_ASSIGNMENT((#207190)); +#207190 = SURFACE_STYLE_USAGE(.BOTH.,#207191); +#207191 = SURFACE_SIDE_STYLE('',(#207192)); +#207192 = SURFACE_STYLE_FILL_AREA(#207193); +#207193 = FILL_AREA_STYLE('',(#207194)); +#207194 = FILL_AREA_STYLE_COLOUR('',#206928); +#207195 = OVER_RIDING_STYLED_ITEM('overriding color',(#207196),#17606, + #206921); +#207196 = PRESENTATION_STYLE_ASSIGNMENT((#207197)); +#207197 = SURFACE_STYLE_USAGE(.BOTH.,#207198); +#207198 = SURFACE_SIDE_STYLE('',(#207199)); +#207199 = SURFACE_STYLE_FILL_AREA(#207200); +#207200 = FILL_AREA_STYLE('',(#207201)); +#207201 = FILL_AREA_STYLE_COLOUR('',#206928); +#207202 = OVER_RIDING_STYLED_ITEM('overriding color',(#207203),#17693, + #206921); +#207203 = PRESENTATION_STYLE_ASSIGNMENT((#207204)); +#207204 = SURFACE_STYLE_USAGE(.BOTH.,#207205); +#207205 = SURFACE_SIDE_STYLE('',(#207206)); +#207206 = SURFACE_STYLE_FILL_AREA(#207207); +#207207 = FILL_AREA_STYLE('',(#207208)); +#207208 = FILL_AREA_STYLE_COLOUR('',#206928); +#207209 = OVER_RIDING_STYLED_ITEM('overriding color',(#207210),#17745, + #206921); +#207210 = PRESENTATION_STYLE_ASSIGNMENT((#207211)); +#207211 = SURFACE_STYLE_USAGE(.BOTH.,#207212); +#207212 = SURFACE_SIDE_STYLE('',(#207213)); +#207213 = SURFACE_STYLE_FILL_AREA(#207214); +#207214 = FILL_AREA_STYLE('',(#207215)); +#207215 = FILL_AREA_STYLE_COLOUR('',#206928); +#207216 = OVER_RIDING_STYLED_ITEM('overriding color',(#207217),#17855, + #206921); +#207217 = PRESENTATION_STYLE_ASSIGNMENT((#207218)); +#207218 = SURFACE_STYLE_USAGE(.BOTH.,#207219); +#207219 = SURFACE_SIDE_STYLE('',(#207220)); +#207220 = SURFACE_STYLE_FILL_AREA(#207221); +#207221 = FILL_AREA_STYLE('',(#207222)); +#207222 = FILL_AREA_STYLE_COLOUR('',#206928); +#207223 = OVER_RIDING_STYLED_ITEM('overriding color',(#207224),#17907, + #206921); +#207224 = PRESENTATION_STYLE_ASSIGNMENT((#207225)); +#207225 = SURFACE_STYLE_USAGE(.BOTH.,#207226); +#207226 = SURFACE_SIDE_STYLE('',(#207227)); +#207227 = SURFACE_STYLE_FILL_AREA(#207228); +#207228 = FILL_AREA_STYLE('',(#207229)); +#207229 = FILL_AREA_STYLE_COLOUR('',#206928); +#207230 = OVER_RIDING_STYLED_ITEM('overriding color',(#207231),#18017, + #206921); +#207231 = PRESENTATION_STYLE_ASSIGNMENT((#207232)); +#207232 = SURFACE_STYLE_USAGE(.BOTH.,#207233); +#207233 = SURFACE_SIDE_STYLE('',(#207234)); +#207234 = SURFACE_STYLE_FILL_AREA(#207235); +#207235 = FILL_AREA_STYLE('',(#207236)); +#207236 = FILL_AREA_STYLE_COLOUR('',#206928); +#207237 = OVER_RIDING_STYLED_ITEM('overriding color',(#207238),#18048, + #206921); +#207238 = PRESENTATION_STYLE_ASSIGNMENT((#207239)); +#207239 = SURFACE_STYLE_USAGE(.BOTH.,#207240); +#207240 = SURFACE_SIDE_STYLE('',(#207241)); +#207241 = SURFACE_STYLE_FILL_AREA(#207242); +#207242 = FILL_AREA_STYLE('',(#207243)); +#207243 = FILL_AREA_STYLE_COLOUR('',#206928); +#207244 = OVER_RIDING_STYLED_ITEM('overriding color',(#207245),#18079, + #206921); +#207245 = PRESENTATION_STYLE_ASSIGNMENT((#207246)); +#207246 = SURFACE_STYLE_USAGE(.BOTH.,#207247); +#207247 = SURFACE_SIDE_STYLE('',(#207248)); +#207248 = SURFACE_STYLE_FILL_AREA(#207249); +#207249 = FILL_AREA_STYLE('',(#207250)); +#207250 = FILL_AREA_STYLE_COLOUR('',#206928); +#207251 = OVER_RIDING_STYLED_ITEM('overriding color',(#207252),#18218, + #206921); +#207252 = PRESENTATION_STYLE_ASSIGNMENT((#207253)); +#207253 = SURFACE_STYLE_USAGE(.BOTH.,#207254); +#207254 = SURFACE_SIDE_STYLE('',(#207255)); +#207255 = SURFACE_STYLE_FILL_AREA(#207256); +#207256 = FILL_AREA_STYLE('',(#207257)); +#207257 = FILL_AREA_STYLE_COLOUR('',#206928); +#207258 = OVER_RIDING_STYLED_ITEM('overriding color',(#207259),#18288, + #206921); +#207259 = PRESENTATION_STYLE_ASSIGNMENT((#207260)); +#207260 = SURFACE_STYLE_USAGE(.BOTH.,#207261); +#207261 = SURFACE_SIDE_STYLE('',(#207262)); +#207262 = SURFACE_STYLE_FILL_AREA(#207263); +#207263 = FILL_AREA_STYLE('',(#207264)); +#207264 = FILL_AREA_STYLE_COLOUR('',#206928); +#207265 = OVER_RIDING_STYLED_ITEM('overriding color',(#207266),#18383, + #206921); +#207266 = PRESENTATION_STYLE_ASSIGNMENT((#207267)); +#207267 = SURFACE_STYLE_USAGE(.BOTH.,#207268); +#207268 = SURFACE_SIDE_STYLE('',(#207269)); +#207269 = SURFACE_STYLE_FILL_AREA(#207270); +#207270 = FILL_AREA_STYLE('',(#207271)); +#207271 = FILL_AREA_STYLE_COLOUR('',#206928); +#207272 = OVER_RIDING_STYLED_ITEM('overriding color',(#207273),#18453, + #206921); +#207273 = PRESENTATION_STYLE_ASSIGNMENT((#207274)); +#207274 = SURFACE_STYLE_USAGE(.BOTH.,#207275); +#207275 = SURFACE_SIDE_STYLE('',(#207276)); +#207276 = SURFACE_STYLE_FILL_AREA(#207277); +#207277 = FILL_AREA_STYLE('',(#207278)); +#207278 = FILL_AREA_STYLE_COLOUR('',#206928); +#207279 = OVER_RIDING_STYLED_ITEM('overriding color',(#207280),#18548, + #206921); +#207280 = PRESENTATION_STYLE_ASSIGNMENT((#207281)); +#207281 = SURFACE_STYLE_USAGE(.BOTH.,#207282); +#207282 = SURFACE_SIDE_STYLE('',(#207283)); +#207283 = SURFACE_STYLE_FILL_AREA(#207284); +#207284 = FILL_AREA_STYLE('',(#207285)); +#207285 = FILL_AREA_STYLE_COLOUR('',#206928); +#207286 = OVER_RIDING_STYLED_ITEM('overriding color',(#207287),#18618, + #206921); +#207287 = PRESENTATION_STYLE_ASSIGNMENT((#207288)); +#207288 = SURFACE_STYLE_USAGE(.BOTH.,#207289); +#207289 = SURFACE_SIDE_STYLE('',(#207290)); +#207290 = SURFACE_STYLE_FILL_AREA(#207291); +#207291 = FILL_AREA_STYLE('',(#207292)); +#207292 = FILL_AREA_STYLE_COLOUR('',#206928); +#207293 = OVER_RIDING_STYLED_ITEM('overriding color',(#207294),#18713, + #206921); +#207294 = PRESENTATION_STYLE_ASSIGNMENT((#207295)); +#207295 = SURFACE_STYLE_USAGE(.BOTH.,#207296); +#207296 = SURFACE_SIDE_STYLE('',(#207297)); +#207297 = SURFACE_STYLE_FILL_AREA(#207298); +#207298 = FILL_AREA_STYLE('',(#207299)); +#207299 = FILL_AREA_STYLE_COLOUR('',#206928); +#207300 = OVER_RIDING_STYLED_ITEM('overriding color',(#207301),#18739, + #206921); +#207301 = PRESENTATION_STYLE_ASSIGNMENT((#207302)); +#207302 = SURFACE_STYLE_USAGE(.BOTH.,#207303); +#207303 = SURFACE_SIDE_STYLE('',(#207304)); +#207304 = SURFACE_STYLE_FILL_AREA(#207305); +#207305 = FILL_AREA_STYLE('',(#207306)); +#207306 = FILL_AREA_STYLE_COLOUR('',#206928); +#207307 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #207308,#207316,#207323,#207330,#207337,#207344,#207351,#207358, + #207365,#207372,#207379),#170976); +#207308 = STYLED_ITEM('color',(#207309),#170334); +#207309 = PRESENTATION_STYLE_ASSIGNMENT((#207310)); +#207310 = SURFACE_STYLE_USAGE(.BOTH.,#207311); +#207311 = SURFACE_SIDE_STYLE('',(#207312)); +#207312 = SURFACE_STYLE_FILL_AREA(#207313); +#207313 = FILL_AREA_STYLE('',(#207314)); +#207314 = FILL_AREA_STYLE_COLOUR('',#207315); +#207315 = COLOUR_RGB('',0.113725490868,0.113725490868,0.113725490868); +#207316 = OVER_RIDING_STYLED_ITEM('overriding color',(#207317),#170336, + #207308); +#207317 = PRESENTATION_STYLE_ASSIGNMENT((#207318)); +#207318 = SURFACE_STYLE_USAGE(.BOTH.,#207319); +#207319 = SURFACE_SIDE_STYLE('',(#207320)); +#207320 = SURFACE_STYLE_FILL_AREA(#207321); +#207321 = FILL_AREA_STYLE('',(#207322)); +#207322 = FILL_AREA_STYLE_COLOUR('',#197630); +#207323 = OVER_RIDING_STYLED_ITEM('overriding color',(#207324),#170456, + #207308); +#207324 = PRESENTATION_STYLE_ASSIGNMENT((#207325)); +#207325 = SURFACE_STYLE_USAGE(.BOTH.,#207326); +#207326 = SURFACE_SIDE_STYLE('',(#207327)); +#207327 = SURFACE_STYLE_FILL_AREA(#207328); +#207328 = FILL_AREA_STYLE('',(#207329)); +#207329 = FILL_AREA_STYLE_COLOUR('',#197630); +#207330 = OVER_RIDING_STYLED_ITEM('overriding color',(#207331),#170532, + #207308); +#207331 = PRESENTATION_STYLE_ASSIGNMENT((#207332)); +#207332 = SURFACE_STYLE_USAGE(.BOTH.,#207333); +#207333 = SURFACE_SIDE_STYLE('',(#207334)); +#207334 = SURFACE_STYLE_FILL_AREA(#207335); +#207335 = FILL_AREA_STYLE('',(#207336)); +#207336 = FILL_AREA_STYLE_COLOUR('',#197630); +#207337 = OVER_RIDING_STYLED_ITEM('overriding color',(#207338),#170637, + #207308); +#207338 = PRESENTATION_STYLE_ASSIGNMENT((#207339)); +#207339 = SURFACE_STYLE_USAGE(.BOTH.,#207340); +#207340 = SURFACE_SIDE_STYLE('',(#207341)); +#207341 = SURFACE_STYLE_FILL_AREA(#207342); +#207342 = FILL_AREA_STYLE('',(#207343)); +#207343 = FILL_AREA_STYLE_COLOUR('',#197630); +#207344 = OVER_RIDING_STYLED_ITEM('overriding color',(#207345),#170684, + #207308); +#207345 = PRESENTATION_STYLE_ASSIGNMENT((#207346)); +#207346 = SURFACE_STYLE_USAGE(.BOTH.,#207347); +#207347 = SURFACE_SIDE_STYLE('',(#207348)); +#207348 = SURFACE_STYLE_FILL_AREA(#207349); +#207349 = FILL_AREA_STYLE('',(#207350)); +#207350 = FILL_AREA_STYLE_COLOUR('',#197630); +#207351 = OVER_RIDING_STYLED_ITEM('overriding color',(#207352),#170760, + #207308); +#207352 = PRESENTATION_STYLE_ASSIGNMENT((#207353)); +#207353 = SURFACE_STYLE_USAGE(.BOTH.,#207354); +#207354 = SURFACE_SIDE_STYLE('',(#207355)); +#207355 = SURFACE_STYLE_FILL_AREA(#207356); +#207356 = FILL_AREA_STYLE('',(#207357)); +#207357 = FILL_AREA_STYLE_COLOUR('',#197630); +#207358 = OVER_RIDING_STYLED_ITEM('overriding color',(#207359),#170840, + #207308); +#207359 = PRESENTATION_STYLE_ASSIGNMENT((#207360)); +#207360 = SURFACE_STYLE_USAGE(.BOTH.,#207361); +#207361 = SURFACE_SIDE_STYLE('',(#207362)); +#207362 = SURFACE_STYLE_FILL_AREA(#207363); +#207363 = FILL_AREA_STYLE('',(#207364)); +#207364 = FILL_AREA_STYLE_COLOUR('',#197630); +#207365 = OVER_RIDING_STYLED_ITEM('overriding color',(#207366),#170889, + #207308); +#207366 = PRESENTATION_STYLE_ASSIGNMENT((#207367)); +#207367 = SURFACE_STYLE_USAGE(.BOTH.,#207368); +#207368 = SURFACE_SIDE_STYLE('',(#207369)); +#207369 = SURFACE_STYLE_FILL_AREA(#207370); +#207370 = FILL_AREA_STYLE('',(#207371)); +#207371 = FILL_AREA_STYLE_COLOUR('',#197630); +#207372 = OVER_RIDING_STYLED_ITEM('overriding color',(#207373),#170942, + #207308); +#207373 = PRESENTATION_STYLE_ASSIGNMENT((#207374)); +#207374 = SURFACE_STYLE_USAGE(.BOTH.,#207375); +#207375 = SURFACE_SIDE_STYLE('',(#207376)); +#207376 = SURFACE_STYLE_FILL_AREA(#207377); +#207377 = FILL_AREA_STYLE('',(#207378)); +#207378 = FILL_AREA_STYLE_COLOUR('',#197630); +#207379 = OVER_RIDING_STYLED_ITEM('overriding color',(#207380),#170969, + #207308); +#207380 = PRESENTATION_STYLE_ASSIGNMENT((#207381)); +#207381 = SURFACE_STYLE_USAGE(.BOTH.,#207382); +#207382 = SURFACE_SIDE_STYLE('',(#207383)); +#207383 = SURFACE_STYLE_FILL_AREA(#207384); +#207384 = FILL_AREA_STYLE('',(#207385)); +#207385 = FILL_AREA_STYLE_COLOUR('',#197630); +#207386 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #207387),#185125); +#207387 = STYLED_ITEM('color',(#207388),#184795); +#207388 = PRESENTATION_STYLE_ASSIGNMENT((#207389,#207394)); #207389 = SURFACE_STYLE_USAGE(.BOTH.,#207390); #207390 = SURFACE_SIDE_STYLE('',(#207391)); #207391 = SURFACE_STYLE_FILL_AREA(#207392); #207392 = FILL_AREA_STYLE('',(#207393)); -#207393 = FILL_AREA_STYLE_COLOUR('',#207232); -#207394 = OVER_RIDING_STYLED_ITEM('overriding color',(#207395),#13977, - #207225); -#207395 = PRESENTATION_STYLE_ASSIGNMENT((#207396)); -#207396 = SURFACE_STYLE_USAGE(.BOTH.,#207397); -#207397 = SURFACE_SIDE_STYLE('',(#207398)); -#207398 = SURFACE_STYLE_FILL_AREA(#207399); -#207399 = FILL_AREA_STYLE('',(#207400)); -#207400 = FILL_AREA_STYLE_COLOUR('',#207232); -#207401 = OVER_RIDING_STYLED_ITEM('overriding color',(#207402),#14072, - #207225); -#207402 = PRESENTATION_STYLE_ASSIGNMENT((#207403)); -#207403 = SURFACE_STYLE_USAGE(.BOTH.,#207404); -#207404 = SURFACE_SIDE_STYLE('',(#207405)); -#207405 = SURFACE_STYLE_FILL_AREA(#207406); -#207406 = FILL_AREA_STYLE('',(#207407)); -#207407 = FILL_AREA_STYLE_COLOUR('',#207232); -#207408 = OVER_RIDING_STYLED_ITEM('overriding color',(#207409),#14142, - #207225); -#207409 = PRESENTATION_STYLE_ASSIGNMENT((#207410)); -#207410 = SURFACE_STYLE_USAGE(.BOTH.,#207411); -#207411 = SURFACE_SIDE_STYLE('',(#207412)); -#207412 = SURFACE_STYLE_FILL_AREA(#207413); -#207413 = FILL_AREA_STYLE('',(#207414)); -#207414 = FILL_AREA_STYLE_COLOUR('',#207232); -#207415 = OVER_RIDING_STYLED_ITEM('overriding color',(#207416),#14237, - #207225); -#207416 = PRESENTATION_STYLE_ASSIGNMENT((#207417)); -#207417 = SURFACE_STYLE_USAGE(.BOTH.,#207418); -#207418 = SURFACE_SIDE_STYLE('',(#207419)); -#207419 = SURFACE_STYLE_FILL_AREA(#207420); -#207420 = FILL_AREA_STYLE('',(#207421)); -#207421 = FILL_AREA_STYLE_COLOUR('',#207232); -#207422 = OVER_RIDING_STYLED_ITEM('overriding color',(#207423),#14263, - #207225); -#207423 = PRESENTATION_STYLE_ASSIGNMENT((#207424)); -#207424 = SURFACE_STYLE_USAGE(.BOTH.,#207425); -#207425 = SURFACE_SIDE_STYLE('',(#207426)); -#207426 = SURFACE_STYLE_FILL_AREA(#207427); -#207427 = FILL_AREA_STYLE('',(#207428)); -#207428 = FILL_AREA_STYLE_COLOUR('',#207232); -#207429 = OVER_RIDING_STYLED_ITEM('overriding color',(#207430),#14421, - #207225); -#207430 = PRESENTATION_STYLE_ASSIGNMENT((#207431)); -#207431 = SURFACE_STYLE_USAGE(.BOTH.,#207432); -#207432 = SURFACE_SIDE_STYLE('',(#207433)); -#207433 = SURFACE_STYLE_FILL_AREA(#207434); -#207434 = FILL_AREA_STYLE('',(#207435)); -#207435 = FILL_AREA_STYLE_COLOUR('',#207232); -#207436 = OVER_RIDING_STYLED_ITEM('overriding color',(#207437),#14513, - #207225); -#207437 = PRESENTATION_STYLE_ASSIGNMENT((#207438)); -#207438 = SURFACE_STYLE_USAGE(.BOTH.,#207439); -#207439 = SURFACE_SIDE_STYLE('',(#207440)); -#207440 = SURFACE_STYLE_FILL_AREA(#207441); -#207441 = FILL_AREA_STYLE('',(#207442)); -#207442 = FILL_AREA_STYLE_COLOUR('',#207232); -#207443 = OVER_RIDING_STYLED_ITEM('overriding color',(#207444),#14610, - #207225); -#207444 = PRESENTATION_STYLE_ASSIGNMENT((#207445)); -#207445 = SURFACE_STYLE_USAGE(.BOTH.,#207446); -#207446 = SURFACE_SIDE_STYLE('',(#207447)); -#207447 = SURFACE_STYLE_FILL_AREA(#207448); -#207448 = FILL_AREA_STYLE('',(#207449)); -#207449 = FILL_AREA_STYLE_COLOUR('',#207232); -#207450 = OVER_RIDING_STYLED_ITEM('overriding color',(#207451),#14702, - #207225); -#207451 = PRESENTATION_STYLE_ASSIGNMENT((#207452)); -#207452 = SURFACE_STYLE_USAGE(.BOTH.,#207453); -#207453 = SURFACE_SIDE_STYLE('',(#207454)); -#207454 = SURFACE_STYLE_FILL_AREA(#207455); -#207455 = FILL_AREA_STYLE('',(#207456)); -#207456 = FILL_AREA_STYLE_COLOUR('',#207232); -#207457 = OVER_RIDING_STYLED_ITEM('overriding color',(#207458),#14799, - #207225); -#207458 = PRESENTATION_STYLE_ASSIGNMENT((#207459)); -#207459 = SURFACE_STYLE_USAGE(.BOTH.,#207460); -#207460 = SURFACE_SIDE_STYLE('',(#207461)); -#207461 = SURFACE_STYLE_FILL_AREA(#207462); -#207462 = FILL_AREA_STYLE('',(#207463)); -#207463 = FILL_AREA_STYLE_COLOUR('',#207232); -#207464 = OVER_RIDING_STYLED_ITEM('overriding color',(#207465),#14891, - #207225); -#207465 = PRESENTATION_STYLE_ASSIGNMENT((#207466)); -#207466 = SURFACE_STYLE_USAGE(.BOTH.,#207467); -#207467 = SURFACE_SIDE_STYLE('',(#207468)); -#207468 = SURFACE_STYLE_FILL_AREA(#207469); -#207469 = FILL_AREA_STYLE('',(#207470)); -#207470 = FILL_AREA_STYLE_COLOUR('',#207232); -#207471 = OVER_RIDING_STYLED_ITEM('overriding color',(#207472),#14988, - #207225); -#207472 = PRESENTATION_STYLE_ASSIGNMENT((#207473)); -#207473 = SURFACE_STYLE_USAGE(.BOTH.,#207474); -#207474 = SURFACE_SIDE_STYLE('',(#207475)); -#207475 = SURFACE_STYLE_FILL_AREA(#207476); -#207476 = FILL_AREA_STYLE('',(#207477)); -#207477 = FILL_AREA_STYLE_COLOUR('',#207232); -#207478 = OVER_RIDING_STYLED_ITEM('overriding color',(#207479),#15019, - #207225); -#207479 = PRESENTATION_STYLE_ASSIGNMENT((#207480)); -#207480 = SURFACE_STYLE_USAGE(.BOTH.,#207481); -#207481 = SURFACE_SIDE_STYLE('',(#207482)); -#207482 = SURFACE_STYLE_FILL_AREA(#207483); -#207483 = FILL_AREA_STYLE('',(#207484)); -#207484 = FILL_AREA_STYLE_COLOUR('',#207232); -#207485 = OVER_RIDING_STYLED_ITEM('overriding color',(#207486),#15054, - #207225); -#207486 = PRESENTATION_STYLE_ASSIGNMENT((#207487)); -#207487 = SURFACE_STYLE_USAGE(.BOTH.,#207488); -#207488 = SURFACE_SIDE_STYLE('',(#207489)); -#207489 = SURFACE_STYLE_FILL_AREA(#207490); -#207490 = FILL_AREA_STYLE('',(#207491)); -#207491 = FILL_AREA_STYLE_COLOUR('',#207232); -#207492 = OVER_RIDING_STYLED_ITEM('overriding color',(#207493),#15162, - #207225); -#207493 = PRESENTATION_STYLE_ASSIGNMENT((#207494)); -#207494 = SURFACE_STYLE_USAGE(.BOTH.,#207495); -#207495 = SURFACE_SIDE_STYLE('',(#207496)); -#207496 = SURFACE_STYLE_FILL_AREA(#207497); -#207497 = FILL_AREA_STYLE('',(#207498)); -#207498 = FILL_AREA_STYLE_COLOUR('',#207232); -#207499 = OVER_RIDING_STYLED_ITEM('overriding color',(#207500),#15214, - #207225); -#207500 = PRESENTATION_STYLE_ASSIGNMENT((#207501)); -#207501 = SURFACE_STYLE_USAGE(.BOTH.,#207502); -#207502 = SURFACE_SIDE_STYLE('',(#207503)); -#207503 = SURFACE_STYLE_FILL_AREA(#207504); -#207504 = FILL_AREA_STYLE('',(#207505)); -#207505 = FILL_AREA_STYLE_COLOUR('',#207232); -#207506 = OVER_RIDING_STYLED_ITEM('overriding color',(#207507),#15301, - #207225); -#207507 = PRESENTATION_STYLE_ASSIGNMENT((#207508)); -#207508 = SURFACE_STYLE_USAGE(.BOTH.,#207509); -#207509 = SURFACE_SIDE_STYLE('',(#207510)); -#207510 = SURFACE_STYLE_FILL_AREA(#207511); -#207511 = FILL_AREA_STYLE('',(#207512)); -#207512 = FILL_AREA_STYLE_COLOUR('',#207232); -#207513 = OVER_RIDING_STYLED_ITEM('overriding color',(#207514),#15353, - #207225); -#207514 = PRESENTATION_STYLE_ASSIGNMENT((#207515)); -#207515 = SURFACE_STYLE_USAGE(.BOTH.,#207516); -#207516 = SURFACE_SIDE_STYLE('',(#207517)); -#207517 = SURFACE_STYLE_FILL_AREA(#207518); -#207518 = FILL_AREA_STYLE('',(#207519)); -#207519 = FILL_AREA_STYLE_COLOUR('',#207232); -#207520 = OVER_RIDING_STYLED_ITEM('overriding color',(#207521),#15463, - #207225); -#207521 = PRESENTATION_STYLE_ASSIGNMENT((#207522)); -#207522 = SURFACE_STYLE_USAGE(.BOTH.,#207523); -#207523 = SURFACE_SIDE_STYLE('',(#207524)); -#207524 = SURFACE_STYLE_FILL_AREA(#207525); -#207525 = FILL_AREA_STYLE('',(#207526)); -#207526 = FILL_AREA_STYLE_COLOUR('',#207232); -#207527 = OVER_RIDING_STYLED_ITEM('overriding color',(#207528),#15515, - #207225); -#207528 = PRESENTATION_STYLE_ASSIGNMENT((#207529)); -#207529 = SURFACE_STYLE_USAGE(.BOTH.,#207530); -#207530 = SURFACE_SIDE_STYLE('',(#207531)); -#207531 = SURFACE_STYLE_FILL_AREA(#207532); -#207532 = FILL_AREA_STYLE('',(#207533)); -#207533 = FILL_AREA_STYLE_COLOUR('',#207232); -#207534 = OVER_RIDING_STYLED_ITEM('overriding color',(#207535),#15625, - #207225); -#207535 = PRESENTATION_STYLE_ASSIGNMENT((#207536)); -#207536 = SURFACE_STYLE_USAGE(.BOTH.,#207537); -#207537 = SURFACE_SIDE_STYLE('',(#207538)); -#207538 = SURFACE_STYLE_FILL_AREA(#207539); -#207539 = FILL_AREA_STYLE('',(#207540)); -#207540 = FILL_AREA_STYLE_COLOUR('',#207232); -#207541 = OVER_RIDING_STYLED_ITEM('overriding color',(#207542),#15656, - #207225); -#207542 = PRESENTATION_STYLE_ASSIGNMENT((#207543)); -#207543 = SURFACE_STYLE_USAGE(.BOTH.,#207544); -#207544 = SURFACE_SIDE_STYLE('',(#207545)); -#207545 = SURFACE_STYLE_FILL_AREA(#207546); -#207546 = FILL_AREA_STYLE('',(#207547)); -#207547 = FILL_AREA_STYLE_COLOUR('',#207232); -#207548 = OVER_RIDING_STYLED_ITEM('overriding color',(#207549),#15687, - #207225); -#207549 = PRESENTATION_STYLE_ASSIGNMENT((#207550)); -#207550 = SURFACE_STYLE_USAGE(.BOTH.,#207551); -#207551 = SURFACE_SIDE_STYLE('',(#207552)); -#207552 = SURFACE_STYLE_FILL_AREA(#207553); -#207553 = FILL_AREA_STYLE('',(#207554)); -#207554 = FILL_AREA_STYLE_COLOUR('',#207232); -#207555 = OVER_RIDING_STYLED_ITEM('overriding color',(#207556),#15826, - #207225); -#207556 = PRESENTATION_STYLE_ASSIGNMENT((#207557)); -#207557 = SURFACE_STYLE_USAGE(.BOTH.,#207558); -#207558 = SURFACE_SIDE_STYLE('',(#207559)); -#207559 = SURFACE_STYLE_FILL_AREA(#207560); -#207560 = FILL_AREA_STYLE('',(#207561)); -#207561 = FILL_AREA_STYLE_COLOUR('',#207232); -#207562 = OVER_RIDING_STYLED_ITEM('overriding color',(#207563),#15896, - #207225); -#207563 = PRESENTATION_STYLE_ASSIGNMENT((#207564)); -#207564 = SURFACE_STYLE_USAGE(.BOTH.,#207565); -#207565 = SURFACE_SIDE_STYLE('',(#207566)); -#207566 = SURFACE_STYLE_FILL_AREA(#207567); -#207567 = FILL_AREA_STYLE('',(#207568)); -#207568 = FILL_AREA_STYLE_COLOUR('',#207232); -#207569 = OVER_RIDING_STYLED_ITEM('overriding color',(#207570),#15991, - #207225); -#207570 = PRESENTATION_STYLE_ASSIGNMENT((#207571)); -#207571 = SURFACE_STYLE_USAGE(.BOTH.,#207572); -#207572 = SURFACE_SIDE_STYLE('',(#207573)); -#207573 = SURFACE_STYLE_FILL_AREA(#207574); -#207574 = FILL_AREA_STYLE('',(#207575)); -#207575 = FILL_AREA_STYLE_COLOUR('',#207232); -#207576 = OVER_RIDING_STYLED_ITEM('overriding color',(#207577),#16061, - #207225); -#207577 = PRESENTATION_STYLE_ASSIGNMENT((#207578)); -#207578 = SURFACE_STYLE_USAGE(.BOTH.,#207579); -#207579 = SURFACE_SIDE_STYLE('',(#207580)); -#207580 = SURFACE_STYLE_FILL_AREA(#207581); -#207581 = FILL_AREA_STYLE('',(#207582)); -#207582 = FILL_AREA_STYLE_COLOUR('',#207232); -#207583 = OVER_RIDING_STYLED_ITEM('overriding color',(#207584),#16156, - #207225); -#207584 = PRESENTATION_STYLE_ASSIGNMENT((#207585)); -#207585 = SURFACE_STYLE_USAGE(.BOTH.,#207586); -#207586 = SURFACE_SIDE_STYLE('',(#207587)); -#207587 = SURFACE_STYLE_FILL_AREA(#207588); -#207588 = FILL_AREA_STYLE('',(#207589)); -#207589 = FILL_AREA_STYLE_COLOUR('',#207232); -#207590 = OVER_RIDING_STYLED_ITEM('overriding color',(#207591),#16226, - #207225); -#207591 = PRESENTATION_STYLE_ASSIGNMENT((#207592)); -#207592 = SURFACE_STYLE_USAGE(.BOTH.,#207593); -#207593 = SURFACE_SIDE_STYLE('',(#207594)); -#207594 = SURFACE_STYLE_FILL_AREA(#207595); -#207595 = FILL_AREA_STYLE('',(#207596)); -#207596 = FILL_AREA_STYLE_COLOUR('',#207232); -#207597 = OVER_RIDING_STYLED_ITEM('overriding color',(#207598),#16321, - #207225); -#207598 = PRESENTATION_STYLE_ASSIGNMENT((#207599)); -#207599 = SURFACE_STYLE_USAGE(.BOTH.,#207600); -#207600 = SURFACE_SIDE_STYLE('',(#207601)); -#207601 = SURFACE_STYLE_FILL_AREA(#207602); -#207602 = FILL_AREA_STYLE('',(#207603)); -#207603 = FILL_AREA_STYLE_COLOUR('',#207232); -#207604 = OVER_RIDING_STYLED_ITEM('overriding color',(#207605),#16347, - #207225); -#207605 = PRESENTATION_STYLE_ASSIGNMENT((#207606)); -#207606 = SURFACE_STYLE_USAGE(.BOTH.,#207607); -#207607 = SURFACE_SIDE_STYLE('',(#207608)); -#207608 = SURFACE_STYLE_FILL_AREA(#207609); -#207609 = FILL_AREA_STYLE('',(#207610)); -#207610 = FILL_AREA_STYLE_COLOUR('',#207232); -#207611 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207612),#166601); -#207612 = STYLED_ITEM('color',(#207613),#166271); -#207613 = PRESENTATION_STYLE_ASSIGNMENT((#207614,#207620)); -#207614 = SURFACE_STYLE_USAGE(.BOTH.,#207615); -#207615 = SURFACE_SIDE_STYLE('',(#207616)); -#207616 = SURFACE_STYLE_FILL_AREA(#207617); -#207617 = FILL_AREA_STYLE('',(#207618)); -#207618 = FILL_AREA_STYLE_COLOUR('',#207619); -#207619 = COLOUR_RGB('',0.E+000,0.501960813999,0.E+000); -#207620 = CURVE_STYLE('',#207621,POSITIVE_LENGTH_MEASURE(0.1),#207619); -#207621 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); -#207622 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( - #207623),#4642); -#207623 = STYLED_ITEM('color',(#207624),#334); -#207624 = PRESENTATION_STYLE_ASSIGNMENT((#207625,#207630)); -#207625 = SURFACE_STYLE_USAGE(.BOTH.,#207626); -#207626 = SURFACE_SIDE_STYLE('',(#207627)); -#207627 = SURFACE_STYLE_FILL_AREA(#207628); -#207628 = FILL_AREA_STYLE('',(#207629)); -#207629 = FILL_AREA_STYLE_COLOUR('',#207619); -#207630 = CURVE_STYLE('',#207631,POSITIVE_LENGTH_MEASURE(0.1),#207619); -#207631 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#207393 = FILL_AREA_STYLE_COLOUR('',#204441); +#207394 = CURVE_STYLE('',#207395,POSITIVE_LENGTH_MEASURE(0.1),#204441); +#207395 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#207396 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #207397,#207404,#207411,#207418,#207425,#207432,#207439,#207446, + #207453,#207460,#207467,#207474,#207481,#207488,#207495,#207502, + #207509,#207516,#207523,#207530,#207537,#207544,#207551,#207558, + #207565,#207572,#207579,#207586,#207593,#207600,#207607,#207614, + #207621,#207628,#207635,#207642,#207649,#207656,#207663,#207670, + #207677,#207684,#207691,#207698,#207705,#207712,#207719,#207726, + #207733,#207740,#207747,#207754,#207761,#207768,#207775,#207782, + #207789,#207796,#207803,#207810,#207817,#207824,#207831,#207838, + #207845,#207852,#207859,#207866,#207873,#207880,#207887,#207894, + #207901,#207908,#207915,#207922,#207929,#207936,#207943,#207950, + #207957,#207964,#207971,#207978,#207985,#207992,#207999,#208006, + #208013,#208020,#208027,#208034,#208041,#208048,#208055,#208062, + #208069,#208076,#208083,#208090,#208097,#208104,#208111,#208118, + #208125,#208132,#208139,#208146,#208153,#208160,#208167,#208174, + #208181,#208188,#208195,#208202,#208209,#208216,#208223,#208230, + #208237,#208244,#208251,#208258),#196962); +#207397 = STYLED_ITEM('color',(#207398),#185341); +#207398 = PRESENTATION_STYLE_ASSIGNMENT((#207399)); +#207399 = SURFACE_STYLE_USAGE(.BOTH.,#207400); +#207400 = SURFACE_SIDE_STYLE('',(#207401)); +#207401 = SURFACE_STYLE_FILL_AREA(#207402); +#207402 = FILL_AREA_STYLE('',(#207403)); +#207403 = FILL_AREA_STYLE_COLOUR('',#197417); +#207404 = OVER_RIDING_STYLED_ITEM('overriding color',(#207405),#185343, + #207397); +#207405 = PRESENTATION_STYLE_ASSIGNMENT((#207406)); +#207406 = SURFACE_STYLE_USAGE(.BOTH.,#207407); +#207407 = SURFACE_SIDE_STYLE('',(#207408)); +#207408 = SURFACE_STYLE_FILL_AREA(#207409); +#207409 = FILL_AREA_STYLE('',(#207410)); +#207410 = FILL_AREA_STYLE_COLOUR('',#197630); +#207411 = OVER_RIDING_STYLED_ITEM('overriding color',(#207412),#185623, + #207397); +#207412 = PRESENTATION_STYLE_ASSIGNMENT((#207413)); +#207413 = SURFACE_STYLE_USAGE(.BOTH.,#207414); +#207414 = SURFACE_SIDE_STYLE('',(#207415)); +#207415 = SURFACE_STYLE_FILL_AREA(#207416); +#207416 = FILL_AREA_STYLE('',(#207417)); +#207417 = FILL_AREA_STYLE_COLOUR('',#197630); +#207418 = OVER_RIDING_STYLED_ITEM('overriding color',(#207419),#185898, + #207397); +#207419 = PRESENTATION_STYLE_ASSIGNMENT((#207420)); +#207420 = SURFACE_STYLE_USAGE(.BOTH.,#207421); +#207421 = SURFACE_SIDE_STYLE('',(#207422)); +#207422 = SURFACE_STYLE_FILL_AREA(#207423); +#207423 = FILL_AREA_STYLE('',(#207424)); +#207424 = FILL_AREA_STYLE_COLOUR('',#197630); +#207425 = OVER_RIDING_STYLED_ITEM('overriding color',(#207426),#186173, + #207397); +#207426 = PRESENTATION_STYLE_ASSIGNMENT((#207427)); +#207427 = SURFACE_STYLE_USAGE(.BOTH.,#207428); +#207428 = SURFACE_SIDE_STYLE('',(#207429)); +#207429 = SURFACE_STYLE_FILL_AREA(#207430); +#207430 = FILL_AREA_STYLE('',(#207431)); +#207431 = FILL_AREA_STYLE_COLOUR('',#197630); +#207432 = OVER_RIDING_STYLED_ITEM('overriding color',(#207433),#186448, + #207397); +#207433 = PRESENTATION_STYLE_ASSIGNMENT((#207434)); +#207434 = SURFACE_STYLE_USAGE(.BOTH.,#207435); +#207435 = SURFACE_SIDE_STYLE('',(#207436)); +#207436 = SURFACE_STYLE_FILL_AREA(#207437); +#207437 = FILL_AREA_STYLE('',(#207438)); +#207438 = FILL_AREA_STYLE_COLOUR('',#197630); +#207439 = OVER_RIDING_STYLED_ITEM('overriding color',(#207440),#186751, + #207397); +#207440 = PRESENTATION_STYLE_ASSIGNMENT((#207441)); +#207441 = SURFACE_STYLE_USAGE(.BOTH.,#207442); +#207442 = SURFACE_SIDE_STYLE('',(#207443)); +#207443 = SURFACE_STYLE_FILL_AREA(#207444); +#207444 = FILL_AREA_STYLE('',(#207445)); +#207445 = FILL_AREA_STYLE_COLOUR('',#197630); +#207446 = OVER_RIDING_STYLED_ITEM('overriding color',(#207447),#187026, + #207397); +#207447 = PRESENTATION_STYLE_ASSIGNMENT((#207448)); +#207448 = SURFACE_STYLE_USAGE(.BOTH.,#207449); +#207449 = SURFACE_SIDE_STYLE('',(#207450)); +#207450 = SURFACE_STYLE_FILL_AREA(#207451); +#207451 = FILL_AREA_STYLE('',(#207452)); +#207452 = FILL_AREA_STYLE_COLOUR('',#197630); +#207453 = OVER_RIDING_STYLED_ITEM('overriding color',(#207454),#187301, + #207397); +#207454 = PRESENTATION_STYLE_ASSIGNMENT((#207455)); +#207455 = SURFACE_STYLE_USAGE(.BOTH.,#207456); +#207456 = SURFACE_SIDE_STYLE('',(#207457)); +#207457 = SURFACE_STYLE_FILL_AREA(#207458); +#207458 = FILL_AREA_STYLE('',(#207459)); +#207459 = FILL_AREA_STYLE_COLOUR('',#197630); +#207460 = OVER_RIDING_STYLED_ITEM('overriding color',(#207461),#187576, + #207397); +#207461 = PRESENTATION_STYLE_ASSIGNMENT((#207462)); +#207462 = SURFACE_STYLE_USAGE(.BOTH.,#207463); +#207463 = SURFACE_SIDE_STYLE('',(#207464)); +#207464 = SURFACE_STYLE_FILL_AREA(#207465); +#207465 = FILL_AREA_STYLE('',(#207466)); +#207466 = FILL_AREA_STYLE_COLOUR('',#197630); +#207467 = OVER_RIDING_STYLED_ITEM('overriding color',(#207468),#187728, + #207397); +#207468 = PRESENTATION_STYLE_ASSIGNMENT((#207469)); +#207469 = SURFACE_STYLE_USAGE(.BOTH.,#207470); +#207470 = SURFACE_SIDE_STYLE('',(#207471)); +#207471 = SURFACE_STYLE_FILL_AREA(#207472); +#207472 = FILL_AREA_STYLE('',(#207473)); +#207473 = FILL_AREA_STYLE_COLOUR('',#197630); +#207474 = OVER_RIDING_STYLED_ITEM('overriding color',(#207475),#188195, + #207397); +#207475 = PRESENTATION_STYLE_ASSIGNMENT((#207476)); +#207476 = SURFACE_STYLE_USAGE(.BOTH.,#207477); +#207477 = SURFACE_SIDE_STYLE('',(#207478)); +#207478 = SURFACE_STYLE_FILL_AREA(#207479); +#207479 = FILL_AREA_STYLE('',(#207480)); +#207480 = FILL_AREA_STYLE_COLOUR('',#197630); +#207481 = OVER_RIDING_STYLED_ITEM('overriding color',(#207482),#188639, + #207397); +#207482 = PRESENTATION_STYLE_ASSIGNMENT((#207483)); +#207483 = SURFACE_STYLE_USAGE(.BOTH.,#207484); +#207484 = SURFACE_SIDE_STYLE('',(#207485)); +#207485 = SURFACE_STYLE_FILL_AREA(#207486); +#207486 = FILL_AREA_STYLE('',(#207487)); +#207487 = FILL_AREA_STYLE_COLOUR('',#197630); +#207488 = OVER_RIDING_STYLED_ITEM('overriding color',(#207489),#188808, + #207397); +#207489 = PRESENTATION_STYLE_ASSIGNMENT((#207490)); +#207490 = SURFACE_STYLE_USAGE(.BOTH.,#207491); +#207491 = SURFACE_SIDE_STYLE('',(#207492)); +#207492 = SURFACE_STYLE_FILL_AREA(#207493); +#207493 = FILL_AREA_STYLE('',(#207494)); +#207494 = FILL_AREA_STYLE_COLOUR('',#197630); +#207495 = OVER_RIDING_STYLED_ITEM('overriding color',(#207496),#189001, + #207397); +#207496 = PRESENTATION_STYLE_ASSIGNMENT((#207497)); +#207497 = SURFACE_STYLE_USAGE(.BOTH.,#207498); +#207498 = SURFACE_SIDE_STYLE('',(#207499)); +#207499 = SURFACE_STYLE_FILL_AREA(#207500); +#207500 = FILL_AREA_STYLE('',(#207501)); +#207501 = FILL_AREA_STYLE_COLOUR('',#197630); +#207502 = OVER_RIDING_STYLED_ITEM('overriding color',(#207503),#189147, + #207397); +#207503 = PRESENTATION_STYLE_ASSIGNMENT((#207504)); +#207504 = SURFACE_STYLE_USAGE(.BOTH.,#207505); +#207505 = SURFACE_SIDE_STYLE('',(#207506)); +#207506 = SURFACE_STYLE_FILL_AREA(#207507); +#207507 = FILL_AREA_STYLE('',(#207508)); +#207508 = FILL_AREA_STYLE_COLOUR('',#197630); +#207509 = OVER_RIDING_STYLED_ITEM('overriding color',(#207510),#189317, + #207397); +#207510 = PRESENTATION_STYLE_ASSIGNMENT((#207511)); +#207511 = SURFACE_STYLE_USAGE(.BOTH.,#207512); +#207512 = SURFACE_SIDE_STYLE('',(#207513)); +#207513 = SURFACE_STYLE_FILL_AREA(#207514); +#207514 = FILL_AREA_STYLE('',(#207515)); +#207515 = FILL_AREA_STYLE_COLOUR('',#197630); +#207516 = OVER_RIDING_STYLED_ITEM('overriding color',(#207517),#189638, + #207397); +#207517 = PRESENTATION_STYLE_ASSIGNMENT((#207518)); +#207518 = SURFACE_STYLE_USAGE(.BOTH.,#207519); +#207519 = SURFACE_SIDE_STYLE('',(#207520)); +#207520 = SURFACE_STYLE_FILL_AREA(#207521); +#207521 = FILL_AREA_STYLE('',(#207522)); +#207522 = FILL_AREA_STYLE_COLOUR('',#197630); +#207523 = OVER_RIDING_STYLED_ITEM('overriding color',(#207524),#189750, + #207397); +#207524 = PRESENTATION_STYLE_ASSIGNMENT((#207525)); +#207525 = SURFACE_STYLE_USAGE(.BOTH.,#207526); +#207526 = SURFACE_SIDE_STYLE('',(#207527)); +#207527 = SURFACE_STYLE_FILL_AREA(#207528); +#207528 = FILL_AREA_STYLE('',(#207529)); +#207529 = FILL_AREA_STYLE_COLOUR('',#197630); +#207530 = OVER_RIDING_STYLED_ITEM('overriding color',(#207531),#189885, + #207397); +#207531 = PRESENTATION_STYLE_ASSIGNMENT((#207532)); +#207532 = SURFACE_STYLE_USAGE(.BOTH.,#207533); +#207533 = SURFACE_SIDE_STYLE('',(#207534)); +#207534 = SURFACE_STYLE_FILL_AREA(#207535); +#207535 = FILL_AREA_STYLE('',(#207536)); +#207536 = FILL_AREA_STYLE_COLOUR('',#197630); +#207537 = OVER_RIDING_STYLED_ITEM('overriding color',(#207538),#190253, + #207397); +#207538 = PRESENTATION_STYLE_ASSIGNMENT((#207539)); +#207539 = SURFACE_STYLE_USAGE(.BOTH.,#207540); +#207540 = SURFACE_SIDE_STYLE('',(#207541)); +#207541 = SURFACE_STYLE_FILL_AREA(#207542); +#207542 = FILL_AREA_STYLE('',(#207543)); +#207543 = FILL_AREA_STYLE_COLOUR('',#197425); +#207544 = OVER_RIDING_STYLED_ITEM('overriding color',(#207545),#190328, + #207397); +#207545 = PRESENTATION_STYLE_ASSIGNMENT((#207546)); +#207546 = SURFACE_STYLE_USAGE(.BOTH.,#207547); +#207547 = SURFACE_SIDE_STYLE('',(#207548)); +#207548 = SURFACE_STYLE_FILL_AREA(#207549); +#207549 = FILL_AREA_STYLE('',(#207550)); +#207550 = FILL_AREA_STYLE_COLOUR('',#197425); +#207551 = OVER_RIDING_STYLED_ITEM('overriding color',(#207552),#190403, + #207397); +#207552 = PRESENTATION_STYLE_ASSIGNMENT((#207553)); +#207553 = SURFACE_STYLE_USAGE(.BOTH.,#207554); +#207554 = SURFACE_SIDE_STYLE('',(#207555)); +#207555 = SURFACE_STYLE_FILL_AREA(#207556); +#207556 = FILL_AREA_STYLE('',(#207557)); +#207557 = FILL_AREA_STYLE_COLOUR('',#197425); +#207558 = OVER_RIDING_STYLED_ITEM('overriding color',(#207559),#190657, + #207397); +#207559 = PRESENTATION_STYLE_ASSIGNMENT((#207560)); +#207560 = SURFACE_STYLE_USAGE(.BOTH.,#207561); +#207561 = SURFACE_SIDE_STYLE('',(#207562)); +#207562 = SURFACE_STYLE_FILL_AREA(#207563); +#207563 = FILL_AREA_STYLE('',(#207564)); +#207564 = FILL_AREA_STYLE_COLOUR('',#197425); +#207565 = OVER_RIDING_STYLED_ITEM('overriding color',(#207566),#190876, + #207397); +#207566 = PRESENTATION_STYLE_ASSIGNMENT((#207567)); +#207567 = SURFACE_STYLE_USAGE(.BOTH.,#207568); +#207568 = SURFACE_SIDE_STYLE('',(#207569)); +#207569 = SURFACE_STYLE_FILL_AREA(#207570); +#207570 = FILL_AREA_STYLE('',(#207571)); +#207571 = FILL_AREA_STYLE_COLOUR('',#197425); +#207572 = OVER_RIDING_STYLED_ITEM('overriding color',(#207573),#190902, + #207397); +#207573 = PRESENTATION_STYLE_ASSIGNMENT((#207574)); +#207574 = SURFACE_STYLE_USAGE(.BOTH.,#207575); +#207575 = SURFACE_SIDE_STYLE('',(#207576)); +#207576 = SURFACE_STYLE_FILL_AREA(#207577); +#207577 = FILL_AREA_STYLE('',(#207578)); +#207578 = FILL_AREA_STYLE_COLOUR('',#197425); +#207579 = OVER_RIDING_STYLED_ITEM('overriding color',(#207580),#190928, + #207397); +#207580 = PRESENTATION_STYLE_ASSIGNMENT((#207581)); +#207581 = SURFACE_STYLE_USAGE(.BOTH.,#207582); +#207582 = SURFACE_SIDE_STYLE('',(#207583)); +#207583 = SURFACE_STYLE_FILL_AREA(#207584); +#207584 = FILL_AREA_STYLE('',(#207585)); +#207585 = FILL_AREA_STYLE_COLOUR('',#197425); +#207586 = OVER_RIDING_STYLED_ITEM('overriding color',(#207587),#190977, + #207397); +#207587 = PRESENTATION_STYLE_ASSIGNMENT((#207588)); +#207588 = SURFACE_STYLE_USAGE(.BOTH.,#207589); +#207589 = SURFACE_SIDE_STYLE('',(#207590)); +#207590 = SURFACE_STYLE_FILL_AREA(#207591); +#207591 = FILL_AREA_STYLE('',(#207592)); +#207592 = FILL_AREA_STYLE_COLOUR('',#197425); +#207593 = OVER_RIDING_STYLED_ITEM('overriding color',(#207594),#191004, + #207397); +#207594 = PRESENTATION_STYLE_ASSIGNMENT((#207595)); +#207595 = SURFACE_STYLE_USAGE(.BOTH.,#207596); +#207596 = SURFACE_SIDE_STYLE('',(#207597)); +#207597 = SURFACE_STYLE_FILL_AREA(#207598); +#207598 = FILL_AREA_STYLE('',(#207599)); +#207599 = FILL_AREA_STYLE_COLOUR('',#197425); +#207600 = OVER_RIDING_STYLED_ITEM('overriding color',(#207601),#191031, + #207397); +#207601 = PRESENTATION_STYLE_ASSIGNMENT((#207602)); +#207602 = SURFACE_STYLE_USAGE(.BOTH.,#207603); +#207603 = SURFACE_SIDE_STYLE('',(#207604)); +#207604 = SURFACE_STYLE_FILL_AREA(#207605); +#207605 = FILL_AREA_STYLE('',(#207606)); +#207606 = FILL_AREA_STYLE_COLOUR('',#197425); +#207607 = OVER_RIDING_STYLED_ITEM('overriding color',(#207608),#191080, + #207397); +#207608 = PRESENTATION_STYLE_ASSIGNMENT((#207609)); +#207609 = SURFACE_STYLE_USAGE(.BOTH.,#207610); +#207610 = SURFACE_SIDE_STYLE('',(#207611)); +#207611 = SURFACE_STYLE_FILL_AREA(#207612); +#207612 = FILL_AREA_STYLE('',(#207613)); +#207613 = FILL_AREA_STYLE_COLOUR('',#197425); +#207614 = OVER_RIDING_STYLED_ITEM('overriding color',(#207615),#191106, + #207397); +#207615 = PRESENTATION_STYLE_ASSIGNMENT((#207616)); +#207616 = SURFACE_STYLE_USAGE(.BOTH.,#207617); +#207617 = SURFACE_SIDE_STYLE('',(#207618)); +#207618 = SURFACE_STYLE_FILL_AREA(#207619); +#207619 = FILL_AREA_STYLE('',(#207620)); +#207620 = FILL_AREA_STYLE_COLOUR('',#197425); +#207621 = OVER_RIDING_STYLED_ITEM('overriding color',(#207622),#191132, + #207397); +#207622 = PRESENTATION_STYLE_ASSIGNMENT((#207623)); +#207623 = SURFACE_STYLE_USAGE(.BOTH.,#207624); +#207624 = SURFACE_SIDE_STYLE('',(#207625)); +#207625 = SURFACE_STYLE_FILL_AREA(#207626); +#207626 = FILL_AREA_STYLE('',(#207627)); +#207627 = FILL_AREA_STYLE_COLOUR('',#197425); +#207628 = OVER_RIDING_STYLED_ITEM('overriding color',(#207629),#191139, + #207397); +#207629 = PRESENTATION_STYLE_ASSIGNMENT((#207630)); +#207630 = SURFACE_STYLE_USAGE(.BOTH.,#207631); +#207631 = SURFACE_SIDE_STYLE('',(#207632)); +#207632 = SURFACE_STYLE_FILL_AREA(#207633); +#207633 = FILL_AREA_STYLE('',(#207634)); +#207634 = FILL_AREA_STYLE_COLOUR('',#197425); +#207635 = OVER_RIDING_STYLED_ITEM('overriding color',(#207636),#191214, + #207397); +#207636 = PRESENTATION_STYLE_ASSIGNMENT((#207637)); +#207637 = SURFACE_STYLE_USAGE(.BOTH.,#207638); +#207638 = SURFACE_SIDE_STYLE('',(#207639)); +#207639 = SURFACE_STYLE_FILL_AREA(#207640); +#207640 = FILL_AREA_STYLE('',(#207641)); +#207641 = FILL_AREA_STYLE_COLOUR('',#197425); +#207642 = OVER_RIDING_STYLED_ITEM('overriding color',(#207643),#191289, + #207397); +#207643 = PRESENTATION_STYLE_ASSIGNMENT((#207644)); +#207644 = SURFACE_STYLE_USAGE(.BOTH.,#207645); +#207645 = SURFACE_SIDE_STYLE('',(#207646)); +#207646 = SURFACE_STYLE_FILL_AREA(#207647); +#207647 = FILL_AREA_STYLE('',(#207648)); +#207648 = FILL_AREA_STYLE_COLOUR('',#197425); +#207649 = OVER_RIDING_STYLED_ITEM('overriding color',(#207650),#191543, + #207397); +#207650 = PRESENTATION_STYLE_ASSIGNMENT((#207651)); +#207651 = SURFACE_STYLE_USAGE(.BOTH.,#207652); +#207652 = SURFACE_SIDE_STYLE('',(#207653)); +#207653 = SURFACE_STYLE_FILL_AREA(#207654); +#207654 = FILL_AREA_STYLE('',(#207655)); +#207655 = FILL_AREA_STYLE_COLOUR('',#197425); +#207656 = OVER_RIDING_STYLED_ITEM('overriding color',(#207657),#191762, + #207397); +#207657 = PRESENTATION_STYLE_ASSIGNMENT((#207658)); +#207658 = SURFACE_STYLE_USAGE(.BOTH.,#207659); +#207659 = SURFACE_SIDE_STYLE('',(#207660)); +#207660 = SURFACE_STYLE_FILL_AREA(#207661); +#207661 = FILL_AREA_STYLE('',(#207662)); +#207662 = FILL_AREA_STYLE_COLOUR('',#197425); +#207663 = OVER_RIDING_STYLED_ITEM('overriding color',(#207664),#191788, + #207397); +#207664 = PRESENTATION_STYLE_ASSIGNMENT((#207665)); +#207665 = SURFACE_STYLE_USAGE(.BOTH.,#207666); +#207666 = SURFACE_SIDE_STYLE('',(#207667)); +#207667 = SURFACE_STYLE_FILL_AREA(#207668); +#207668 = FILL_AREA_STYLE('',(#207669)); +#207669 = FILL_AREA_STYLE_COLOUR('',#197425); +#207670 = OVER_RIDING_STYLED_ITEM('overriding color',(#207671),#191814, + #207397); +#207671 = PRESENTATION_STYLE_ASSIGNMENT((#207672)); +#207672 = SURFACE_STYLE_USAGE(.BOTH.,#207673); +#207673 = SURFACE_SIDE_STYLE('',(#207674)); +#207674 = SURFACE_STYLE_FILL_AREA(#207675); +#207675 = FILL_AREA_STYLE('',(#207676)); +#207676 = FILL_AREA_STYLE_COLOUR('',#197425); +#207677 = OVER_RIDING_STYLED_ITEM('overriding color',(#207678),#191863, + #207397); +#207678 = PRESENTATION_STYLE_ASSIGNMENT((#207679)); +#207679 = SURFACE_STYLE_USAGE(.BOTH.,#207680); +#207680 = SURFACE_SIDE_STYLE('',(#207681)); +#207681 = SURFACE_STYLE_FILL_AREA(#207682); +#207682 = FILL_AREA_STYLE('',(#207683)); +#207683 = FILL_AREA_STYLE_COLOUR('',#197425); +#207684 = OVER_RIDING_STYLED_ITEM('overriding color',(#207685),#191890, + #207397); +#207685 = PRESENTATION_STYLE_ASSIGNMENT((#207686)); +#207686 = SURFACE_STYLE_USAGE(.BOTH.,#207687); +#207687 = SURFACE_SIDE_STYLE('',(#207688)); +#207688 = SURFACE_STYLE_FILL_AREA(#207689); +#207689 = FILL_AREA_STYLE('',(#207690)); +#207690 = FILL_AREA_STYLE_COLOUR('',#197425); +#207691 = OVER_RIDING_STYLED_ITEM('overriding color',(#207692),#191917, + #207397); +#207692 = PRESENTATION_STYLE_ASSIGNMENT((#207693)); +#207693 = SURFACE_STYLE_USAGE(.BOTH.,#207694); +#207694 = SURFACE_SIDE_STYLE('',(#207695)); +#207695 = SURFACE_STYLE_FILL_AREA(#207696); +#207696 = FILL_AREA_STYLE('',(#207697)); +#207697 = FILL_AREA_STYLE_COLOUR('',#197425); +#207698 = OVER_RIDING_STYLED_ITEM('overriding color',(#207699),#191966, + #207397); +#207699 = PRESENTATION_STYLE_ASSIGNMENT((#207700)); +#207700 = SURFACE_STYLE_USAGE(.BOTH.,#207701); +#207701 = SURFACE_SIDE_STYLE('',(#207702)); +#207702 = SURFACE_STYLE_FILL_AREA(#207703); +#207703 = FILL_AREA_STYLE('',(#207704)); +#207704 = FILL_AREA_STYLE_COLOUR('',#197425); +#207705 = OVER_RIDING_STYLED_ITEM('overriding color',(#207706),#191992, + #207397); +#207706 = PRESENTATION_STYLE_ASSIGNMENT((#207707)); +#207707 = SURFACE_STYLE_USAGE(.BOTH.,#207708); +#207708 = SURFACE_SIDE_STYLE('',(#207709)); +#207709 = SURFACE_STYLE_FILL_AREA(#207710); +#207710 = FILL_AREA_STYLE('',(#207711)); +#207711 = FILL_AREA_STYLE_COLOUR('',#197425); +#207712 = OVER_RIDING_STYLED_ITEM('overriding color',(#207713),#192018, + #207397); +#207713 = PRESENTATION_STYLE_ASSIGNMENT((#207714)); +#207714 = SURFACE_STYLE_USAGE(.BOTH.,#207715); +#207715 = SURFACE_SIDE_STYLE('',(#207716)); +#207716 = SURFACE_STYLE_FILL_AREA(#207717); +#207717 = FILL_AREA_STYLE('',(#207718)); +#207718 = FILL_AREA_STYLE_COLOUR('',#197425); +#207719 = OVER_RIDING_STYLED_ITEM('overriding color',(#207720),#192025, + #207397); +#207720 = PRESENTATION_STYLE_ASSIGNMENT((#207721)); +#207721 = SURFACE_STYLE_USAGE(.BOTH.,#207722); +#207722 = SURFACE_SIDE_STYLE('',(#207723)); +#207723 = SURFACE_STYLE_FILL_AREA(#207724); +#207724 = FILL_AREA_STYLE('',(#207725)); +#207725 = FILL_AREA_STYLE_COLOUR('',#197425); +#207726 = OVER_RIDING_STYLED_ITEM('overriding color',(#207727),#192100, + #207397); +#207727 = PRESENTATION_STYLE_ASSIGNMENT((#207728)); +#207728 = SURFACE_STYLE_USAGE(.BOTH.,#207729); +#207729 = SURFACE_SIDE_STYLE('',(#207730)); +#207730 = SURFACE_STYLE_FILL_AREA(#207731); +#207731 = FILL_AREA_STYLE('',(#207732)); +#207732 = FILL_AREA_STYLE_COLOUR('',#197425); +#207733 = OVER_RIDING_STYLED_ITEM('overriding color',(#207734),#192381, + #207397); +#207734 = PRESENTATION_STYLE_ASSIGNMENT((#207735)); +#207735 = SURFACE_STYLE_USAGE(.BOTH.,#207736); +#207736 = SURFACE_SIDE_STYLE('',(#207737)); +#207737 = SURFACE_STYLE_FILL_AREA(#207738); +#207738 = FILL_AREA_STYLE('',(#207739)); +#207739 = FILL_AREA_STYLE_COLOUR('',#197425); +#207740 = OVER_RIDING_STYLED_ITEM('overriding color',(#207741),#192429, + #207397); +#207741 = PRESENTATION_STYLE_ASSIGNMENT((#207742)); +#207742 = SURFACE_STYLE_USAGE(.BOTH.,#207743); +#207743 = SURFACE_SIDE_STYLE('',(#207744)); +#207744 = SURFACE_STYLE_FILL_AREA(#207745); +#207745 = FILL_AREA_STYLE('',(#207746)); +#207746 = FILL_AREA_STYLE_COLOUR('',#197425); +#207747 = OVER_RIDING_STYLED_ITEM('overriding color',(#207748),#192648, + #207397); +#207748 = PRESENTATION_STYLE_ASSIGNMENT((#207749)); +#207749 = SURFACE_STYLE_USAGE(.BOTH.,#207750); +#207750 = SURFACE_SIDE_STYLE('',(#207751)); +#207751 = SURFACE_STYLE_FILL_AREA(#207752); +#207752 = FILL_AREA_STYLE('',(#207753)); +#207753 = FILL_AREA_STYLE_COLOUR('',#197425); +#207754 = OVER_RIDING_STYLED_ITEM('overriding color',(#207755),#192674, + #207397); +#207755 = PRESENTATION_STYLE_ASSIGNMENT((#207756)); +#207756 = SURFACE_STYLE_USAGE(.BOTH.,#207757); +#207757 = SURFACE_SIDE_STYLE('',(#207758)); +#207758 = SURFACE_STYLE_FILL_AREA(#207759); +#207759 = FILL_AREA_STYLE('',(#207760)); +#207760 = FILL_AREA_STYLE_COLOUR('',#197425); +#207761 = OVER_RIDING_STYLED_ITEM('overriding color',(#207762),#192700, + #207397); +#207762 = PRESENTATION_STYLE_ASSIGNMENT((#207763)); +#207763 = SURFACE_STYLE_USAGE(.BOTH.,#207764); +#207764 = SURFACE_SIDE_STYLE('',(#207765)); +#207765 = SURFACE_STYLE_FILL_AREA(#207766); +#207766 = FILL_AREA_STYLE('',(#207767)); +#207767 = FILL_AREA_STYLE_COLOUR('',#197425); +#207768 = OVER_RIDING_STYLED_ITEM('overriding color',(#207769),#192749, + #207397); +#207769 = PRESENTATION_STYLE_ASSIGNMENT((#207770)); +#207770 = SURFACE_STYLE_USAGE(.BOTH.,#207771); +#207771 = SURFACE_SIDE_STYLE('',(#207772)); +#207772 = SURFACE_STYLE_FILL_AREA(#207773); +#207773 = FILL_AREA_STYLE('',(#207774)); +#207774 = FILL_AREA_STYLE_COLOUR('',#197425); +#207775 = OVER_RIDING_STYLED_ITEM('overriding color',(#207776),#192776, + #207397); +#207776 = PRESENTATION_STYLE_ASSIGNMENT((#207777)); +#207777 = SURFACE_STYLE_USAGE(.BOTH.,#207778); +#207778 = SURFACE_SIDE_STYLE('',(#207779)); +#207779 = SURFACE_STYLE_FILL_AREA(#207780); +#207780 = FILL_AREA_STYLE('',(#207781)); +#207781 = FILL_AREA_STYLE_COLOUR('',#197425); +#207782 = OVER_RIDING_STYLED_ITEM('overriding color',(#207783),#192803, + #207397); +#207783 = PRESENTATION_STYLE_ASSIGNMENT((#207784)); +#207784 = SURFACE_STYLE_USAGE(.BOTH.,#207785); +#207785 = SURFACE_SIDE_STYLE('',(#207786)); +#207786 = SURFACE_STYLE_FILL_AREA(#207787); +#207787 = FILL_AREA_STYLE('',(#207788)); +#207788 = FILL_AREA_STYLE_COLOUR('',#197425); +#207789 = OVER_RIDING_STYLED_ITEM('overriding color',(#207790),#192852, + #207397); +#207790 = PRESENTATION_STYLE_ASSIGNMENT((#207791)); +#207791 = SURFACE_STYLE_USAGE(.BOTH.,#207792); +#207792 = SURFACE_SIDE_STYLE('',(#207793)); +#207793 = SURFACE_STYLE_FILL_AREA(#207794); +#207794 = FILL_AREA_STYLE('',(#207795)); +#207795 = FILL_AREA_STYLE_COLOUR('',#197425); +#207796 = OVER_RIDING_STYLED_ITEM('overriding color',(#207797),#192878, + #207397); +#207797 = PRESENTATION_STYLE_ASSIGNMENT((#207798)); +#207798 = SURFACE_STYLE_USAGE(.BOTH.,#207799); +#207799 = SURFACE_SIDE_STYLE('',(#207800)); +#207800 = SURFACE_STYLE_FILL_AREA(#207801); +#207801 = FILL_AREA_STYLE('',(#207802)); +#207802 = FILL_AREA_STYLE_COLOUR('',#197425); +#207803 = OVER_RIDING_STYLED_ITEM('overriding color',(#207804),#192904, + #207397); +#207804 = PRESENTATION_STYLE_ASSIGNMENT((#207805)); +#207805 = SURFACE_STYLE_USAGE(.BOTH.,#207806); +#207806 = SURFACE_SIDE_STYLE('',(#207807)); +#207807 = SURFACE_STYLE_FILL_AREA(#207808); +#207808 = FILL_AREA_STYLE('',(#207809)); +#207809 = FILL_AREA_STYLE_COLOUR('',#197425); +#207810 = OVER_RIDING_STYLED_ITEM('overriding color',(#207811),#192911, + #207397); +#207811 = PRESENTATION_STYLE_ASSIGNMENT((#207812)); +#207812 = SURFACE_STYLE_USAGE(.BOTH.,#207813); +#207813 = SURFACE_SIDE_STYLE('',(#207814)); +#207814 = SURFACE_STYLE_FILL_AREA(#207815); +#207815 = FILL_AREA_STYLE('',(#207816)); +#207816 = FILL_AREA_STYLE_COLOUR('',#197425); +#207817 = OVER_RIDING_STYLED_ITEM('overriding color',(#207818),#192986, + #207397); +#207818 = PRESENTATION_STYLE_ASSIGNMENT((#207819)); +#207819 = SURFACE_STYLE_USAGE(.BOTH.,#207820); +#207820 = SURFACE_SIDE_STYLE('',(#207821)); +#207821 = SURFACE_STYLE_FILL_AREA(#207822); +#207822 = FILL_AREA_STYLE('',(#207823)); +#207823 = FILL_AREA_STYLE_COLOUR('',#197425); +#207824 = OVER_RIDING_STYLED_ITEM('overriding color',(#207825),#193267, + #207397); +#207825 = PRESENTATION_STYLE_ASSIGNMENT((#207826)); +#207826 = SURFACE_STYLE_USAGE(.BOTH.,#207827); +#207827 = SURFACE_SIDE_STYLE('',(#207828)); +#207828 = SURFACE_STYLE_FILL_AREA(#207829); +#207829 = FILL_AREA_STYLE('',(#207830)); +#207830 = FILL_AREA_STYLE_COLOUR('',#197425); +#207831 = OVER_RIDING_STYLED_ITEM('overriding color',(#207832),#193315, + #207397); +#207832 = PRESENTATION_STYLE_ASSIGNMENT((#207833)); +#207833 = SURFACE_STYLE_USAGE(.BOTH.,#207834); +#207834 = SURFACE_SIDE_STYLE('',(#207835)); +#207835 = SURFACE_STYLE_FILL_AREA(#207836); +#207836 = FILL_AREA_STYLE('',(#207837)); +#207837 = FILL_AREA_STYLE_COLOUR('',#197425); +#207838 = OVER_RIDING_STYLED_ITEM('overriding color',(#207839),#193534, + #207397); +#207839 = PRESENTATION_STYLE_ASSIGNMENT((#207840)); +#207840 = SURFACE_STYLE_USAGE(.BOTH.,#207841); +#207841 = SURFACE_SIDE_STYLE('',(#207842)); +#207842 = SURFACE_STYLE_FILL_AREA(#207843); +#207843 = FILL_AREA_STYLE('',(#207844)); +#207844 = FILL_AREA_STYLE_COLOUR('',#197425); +#207845 = OVER_RIDING_STYLED_ITEM('overriding color',(#207846),#193560, + #207397); +#207846 = PRESENTATION_STYLE_ASSIGNMENT((#207847)); +#207847 = SURFACE_STYLE_USAGE(.BOTH.,#207848); +#207848 = SURFACE_SIDE_STYLE('',(#207849)); +#207849 = SURFACE_STYLE_FILL_AREA(#207850); +#207850 = FILL_AREA_STYLE('',(#207851)); +#207851 = FILL_AREA_STYLE_COLOUR('',#197425); +#207852 = OVER_RIDING_STYLED_ITEM('overriding color',(#207853),#193586, + #207397); +#207853 = PRESENTATION_STYLE_ASSIGNMENT((#207854)); +#207854 = SURFACE_STYLE_USAGE(.BOTH.,#207855); +#207855 = SURFACE_SIDE_STYLE('',(#207856)); +#207856 = SURFACE_STYLE_FILL_AREA(#207857); +#207857 = FILL_AREA_STYLE('',(#207858)); +#207858 = FILL_AREA_STYLE_COLOUR('',#197425); +#207859 = OVER_RIDING_STYLED_ITEM('overriding color',(#207860),#193635, + #207397); +#207860 = PRESENTATION_STYLE_ASSIGNMENT((#207861)); +#207861 = SURFACE_STYLE_USAGE(.BOTH.,#207862); +#207862 = SURFACE_SIDE_STYLE('',(#207863)); +#207863 = SURFACE_STYLE_FILL_AREA(#207864); +#207864 = FILL_AREA_STYLE('',(#207865)); +#207865 = FILL_AREA_STYLE_COLOUR('',#197425); +#207866 = OVER_RIDING_STYLED_ITEM('overriding color',(#207867),#193662, + #207397); +#207867 = PRESENTATION_STYLE_ASSIGNMENT((#207868)); +#207868 = SURFACE_STYLE_USAGE(.BOTH.,#207869); +#207869 = SURFACE_SIDE_STYLE('',(#207870)); +#207870 = SURFACE_STYLE_FILL_AREA(#207871); +#207871 = FILL_AREA_STYLE('',(#207872)); +#207872 = FILL_AREA_STYLE_COLOUR('',#197425); +#207873 = OVER_RIDING_STYLED_ITEM('overriding color',(#207874),#193689, + #207397); +#207874 = PRESENTATION_STYLE_ASSIGNMENT((#207875)); +#207875 = SURFACE_STYLE_USAGE(.BOTH.,#207876); +#207876 = SURFACE_SIDE_STYLE('',(#207877)); +#207877 = SURFACE_STYLE_FILL_AREA(#207878); +#207878 = FILL_AREA_STYLE('',(#207879)); +#207879 = FILL_AREA_STYLE_COLOUR('',#197425); +#207880 = OVER_RIDING_STYLED_ITEM('overriding color',(#207881),#193738, + #207397); +#207881 = PRESENTATION_STYLE_ASSIGNMENT((#207882)); +#207882 = SURFACE_STYLE_USAGE(.BOTH.,#207883); +#207883 = SURFACE_SIDE_STYLE('',(#207884)); +#207884 = SURFACE_STYLE_FILL_AREA(#207885); +#207885 = FILL_AREA_STYLE('',(#207886)); +#207886 = FILL_AREA_STYLE_COLOUR('',#197425); +#207887 = OVER_RIDING_STYLED_ITEM('overriding color',(#207888),#193764, + #207397); +#207888 = PRESENTATION_STYLE_ASSIGNMENT((#207889)); +#207889 = SURFACE_STYLE_USAGE(.BOTH.,#207890); +#207890 = SURFACE_SIDE_STYLE('',(#207891)); +#207891 = SURFACE_STYLE_FILL_AREA(#207892); +#207892 = FILL_AREA_STYLE('',(#207893)); +#207893 = FILL_AREA_STYLE_COLOUR('',#197425); +#207894 = OVER_RIDING_STYLED_ITEM('overriding color',(#207895),#193790, + #207397); +#207895 = PRESENTATION_STYLE_ASSIGNMENT((#207896)); +#207896 = SURFACE_STYLE_USAGE(.BOTH.,#207897); +#207897 = SURFACE_SIDE_STYLE('',(#207898)); +#207898 = SURFACE_STYLE_FILL_AREA(#207899); +#207899 = FILL_AREA_STYLE('',(#207900)); +#207900 = FILL_AREA_STYLE_COLOUR('',#197425); +#207901 = OVER_RIDING_STYLED_ITEM('overriding color',(#207902),#193797, + #207397); +#207902 = PRESENTATION_STYLE_ASSIGNMENT((#207903)); +#207903 = SURFACE_STYLE_USAGE(.BOTH.,#207904); +#207904 = SURFACE_SIDE_STYLE('',(#207905)); +#207905 = SURFACE_STYLE_FILL_AREA(#207906); +#207906 = FILL_AREA_STYLE('',(#207907)); +#207907 = FILL_AREA_STYLE_COLOUR('',#197425); +#207908 = OVER_RIDING_STYLED_ITEM('overriding color',(#207909),#193872, + #207397); +#207909 = PRESENTATION_STYLE_ASSIGNMENT((#207910)); +#207910 = SURFACE_STYLE_USAGE(.BOTH.,#207911); +#207911 = SURFACE_SIDE_STYLE('',(#207912)); +#207912 = SURFACE_STYLE_FILL_AREA(#207913); +#207913 = FILL_AREA_STYLE('',(#207914)); +#207914 = FILL_AREA_STYLE_COLOUR('',#197425); +#207915 = OVER_RIDING_STYLED_ITEM('overriding color',(#207916),#194153, + #207397); +#207916 = PRESENTATION_STYLE_ASSIGNMENT((#207917)); +#207917 = SURFACE_STYLE_USAGE(.BOTH.,#207918); +#207918 = SURFACE_SIDE_STYLE('',(#207919)); +#207919 = SURFACE_STYLE_FILL_AREA(#207920); +#207920 = FILL_AREA_STYLE('',(#207921)); +#207921 = FILL_AREA_STYLE_COLOUR('',#197425); +#207922 = OVER_RIDING_STYLED_ITEM('overriding color',(#207923),#194394, + #207397); +#207923 = PRESENTATION_STYLE_ASSIGNMENT((#207924)); +#207924 = SURFACE_STYLE_USAGE(.BOTH.,#207925); +#207925 = SURFACE_SIDE_STYLE('',(#207926)); +#207926 = SURFACE_STYLE_FILL_AREA(#207927); +#207927 = FILL_AREA_STYLE('',(#207928)); +#207928 = FILL_AREA_STYLE_COLOUR('',#197425); +#207929 = OVER_RIDING_STYLED_ITEM('overriding color',(#207930),#194439, + #207397); +#207930 = PRESENTATION_STYLE_ASSIGNMENT((#207931)); +#207931 = SURFACE_STYLE_USAGE(.BOTH.,#207932); +#207932 = SURFACE_SIDE_STYLE('',(#207933)); +#207933 = SURFACE_STYLE_FILL_AREA(#207934); +#207934 = FILL_AREA_STYLE('',(#207935)); +#207935 = FILL_AREA_STYLE_COLOUR('',#197425); +#207936 = OVER_RIDING_STYLED_ITEM('overriding color',(#207937),#194465, + #207397); +#207937 = PRESENTATION_STYLE_ASSIGNMENT((#207938)); +#207938 = SURFACE_STYLE_USAGE(.BOTH.,#207939); +#207939 = SURFACE_SIDE_STYLE('',(#207940)); +#207940 = SURFACE_STYLE_FILL_AREA(#207941); +#207941 = FILL_AREA_STYLE('',(#207942)); +#207942 = FILL_AREA_STYLE_COLOUR('',#197425); +#207943 = OVER_RIDING_STYLED_ITEM('overriding color',(#207944),#194514, + #207397); +#207944 = PRESENTATION_STYLE_ASSIGNMENT((#207945)); +#207945 = SURFACE_STYLE_USAGE(.BOTH.,#207946); +#207946 = SURFACE_SIDE_STYLE('',(#207947)); +#207947 = SURFACE_STYLE_FILL_AREA(#207948); +#207948 = FILL_AREA_STYLE('',(#207949)); +#207949 = FILL_AREA_STYLE_COLOUR('',#197425); +#207950 = OVER_RIDING_STYLED_ITEM('overriding color',(#207951),#194541, + #207397); +#207951 = PRESENTATION_STYLE_ASSIGNMENT((#207952)); +#207952 = SURFACE_STYLE_USAGE(.BOTH.,#207953); +#207953 = SURFACE_SIDE_STYLE('',(#207954)); +#207954 = SURFACE_STYLE_FILL_AREA(#207955); +#207955 = FILL_AREA_STYLE('',(#207956)); +#207956 = FILL_AREA_STYLE_COLOUR('',#197425); +#207957 = OVER_RIDING_STYLED_ITEM('overriding color',(#207958),#194568, + #207397); +#207958 = PRESENTATION_STYLE_ASSIGNMENT((#207959)); +#207959 = SURFACE_STYLE_USAGE(.BOTH.,#207960); +#207960 = SURFACE_SIDE_STYLE('',(#207961)); +#207961 = SURFACE_STYLE_FILL_AREA(#207962); +#207962 = FILL_AREA_STYLE('',(#207963)); +#207963 = FILL_AREA_STYLE_COLOUR('',#197425); +#207964 = OVER_RIDING_STYLED_ITEM('overriding color',(#207965),#194617, + #207397); +#207965 = PRESENTATION_STYLE_ASSIGNMENT((#207966)); +#207966 = SURFACE_STYLE_USAGE(.BOTH.,#207967); +#207967 = SURFACE_SIDE_STYLE('',(#207968)); +#207968 = SURFACE_STYLE_FILL_AREA(#207969); +#207969 = FILL_AREA_STYLE('',(#207970)); +#207970 = FILL_AREA_STYLE_COLOUR('',#197425); +#207971 = OVER_RIDING_STYLED_ITEM('overriding color',(#207972),#194643, + #207397); +#207972 = PRESENTATION_STYLE_ASSIGNMENT((#207973)); +#207973 = SURFACE_STYLE_USAGE(.BOTH.,#207974); +#207974 = SURFACE_SIDE_STYLE('',(#207975)); +#207975 = SURFACE_STYLE_FILL_AREA(#207976); +#207976 = FILL_AREA_STYLE('',(#207977)); +#207977 = FILL_AREA_STYLE_COLOUR('',#197425); +#207978 = OVER_RIDING_STYLED_ITEM('overriding color',(#207979),#194669, + #207397); +#207979 = PRESENTATION_STYLE_ASSIGNMENT((#207980)); +#207980 = SURFACE_STYLE_USAGE(.BOTH.,#207981); +#207981 = SURFACE_SIDE_STYLE('',(#207982)); +#207982 = SURFACE_STYLE_FILL_AREA(#207983); +#207983 = FILL_AREA_STYLE('',(#207984)); +#207984 = FILL_AREA_STYLE_COLOUR('',#197425); +#207985 = OVER_RIDING_STYLED_ITEM('overriding color',(#207986),#194676, + #207397); +#207986 = PRESENTATION_STYLE_ASSIGNMENT((#207987)); +#207987 = SURFACE_STYLE_USAGE(.BOTH.,#207988); +#207988 = SURFACE_SIDE_STYLE('',(#207989)); +#207989 = SURFACE_STYLE_FILL_AREA(#207990); +#207990 = FILL_AREA_STYLE('',(#207991)); +#207991 = FILL_AREA_STYLE_COLOUR('',#197425); +#207992 = OVER_RIDING_STYLED_ITEM('overriding color',(#207993),#194683, + #207397); +#207993 = PRESENTATION_STYLE_ASSIGNMENT((#207994)); +#207994 = SURFACE_STYLE_USAGE(.BOTH.,#207995); +#207995 = SURFACE_SIDE_STYLE('',(#207996)); +#207996 = SURFACE_STYLE_FILL_AREA(#207997); +#207997 = FILL_AREA_STYLE('',(#207998)); +#207998 = FILL_AREA_STYLE_COLOUR('',#197425); +#207999 = OVER_RIDING_STYLED_ITEM('overriding color',(#208000),#194758, + #207397); +#208000 = PRESENTATION_STYLE_ASSIGNMENT((#208001)); +#208001 = SURFACE_STYLE_USAGE(.BOTH.,#208002); +#208002 = SURFACE_SIDE_STYLE('',(#208003)); +#208003 = SURFACE_STYLE_FILL_AREA(#208004); +#208004 = FILL_AREA_STYLE('',(#208005)); +#208005 = FILL_AREA_STYLE_COLOUR('',#197425); +#208006 = OVER_RIDING_STYLED_ITEM('overriding color',(#208007),#195039, + #207397); +#208007 = PRESENTATION_STYLE_ASSIGNMENT((#208008)); +#208008 = SURFACE_STYLE_USAGE(.BOTH.,#208009); +#208009 = SURFACE_SIDE_STYLE('',(#208010)); +#208010 = SURFACE_STYLE_FILL_AREA(#208011); +#208011 = FILL_AREA_STYLE('',(#208012)); +#208012 = FILL_AREA_STYLE_COLOUR('',#197425); +#208013 = OVER_RIDING_STYLED_ITEM('overriding color',(#208014),#195280, + #207397); +#208014 = PRESENTATION_STYLE_ASSIGNMENT((#208015)); +#208015 = SURFACE_STYLE_USAGE(.BOTH.,#208016); +#208016 = SURFACE_SIDE_STYLE('',(#208017)); +#208017 = SURFACE_STYLE_FILL_AREA(#208018); +#208018 = FILL_AREA_STYLE('',(#208019)); +#208019 = FILL_AREA_STYLE_COLOUR('',#197425); +#208020 = OVER_RIDING_STYLED_ITEM('overriding color',(#208021),#195306, + #207397); +#208021 = PRESENTATION_STYLE_ASSIGNMENT((#208022)); +#208022 = SURFACE_STYLE_USAGE(.BOTH.,#208023); +#208023 = SURFACE_SIDE_STYLE('',(#208024)); +#208024 = SURFACE_STYLE_FILL_AREA(#208025); +#208025 = FILL_AREA_STYLE('',(#208026)); +#208026 = FILL_AREA_STYLE_COLOUR('',#197425); +#208027 = OVER_RIDING_STYLED_ITEM('overriding color',(#208028),#195332, + #207397); +#208028 = PRESENTATION_STYLE_ASSIGNMENT((#208029)); +#208029 = SURFACE_STYLE_USAGE(.BOTH.,#208030); +#208030 = SURFACE_SIDE_STYLE('',(#208031)); +#208031 = SURFACE_STYLE_FILL_AREA(#208032); +#208032 = FILL_AREA_STYLE('',(#208033)); +#208033 = FILL_AREA_STYLE_COLOUR('',#197425); +#208034 = OVER_RIDING_STYLED_ITEM('overriding color',(#208035),#195381, + #207397); +#208035 = PRESENTATION_STYLE_ASSIGNMENT((#208036)); +#208036 = SURFACE_STYLE_USAGE(.BOTH.,#208037); +#208037 = SURFACE_SIDE_STYLE('',(#208038)); +#208038 = SURFACE_STYLE_FILL_AREA(#208039); +#208039 = FILL_AREA_STYLE('',(#208040)); +#208040 = FILL_AREA_STYLE_COLOUR('',#197425); +#208041 = OVER_RIDING_STYLED_ITEM('overriding color',(#208042),#195408, + #207397); +#208042 = PRESENTATION_STYLE_ASSIGNMENT((#208043)); +#208043 = SURFACE_STYLE_USAGE(.BOTH.,#208044); +#208044 = SURFACE_SIDE_STYLE('',(#208045)); +#208045 = SURFACE_STYLE_FILL_AREA(#208046); +#208046 = FILL_AREA_STYLE('',(#208047)); +#208047 = FILL_AREA_STYLE_COLOUR('',#197425); +#208048 = OVER_RIDING_STYLED_ITEM('overriding color',(#208049),#195435, + #207397); +#208049 = PRESENTATION_STYLE_ASSIGNMENT((#208050)); +#208050 = SURFACE_STYLE_USAGE(.BOTH.,#208051); +#208051 = SURFACE_SIDE_STYLE('',(#208052)); +#208052 = SURFACE_STYLE_FILL_AREA(#208053); +#208053 = FILL_AREA_STYLE('',(#208054)); +#208054 = FILL_AREA_STYLE_COLOUR('',#197425); +#208055 = OVER_RIDING_STYLED_ITEM('overriding color',(#208056),#195484, + #207397); +#208056 = PRESENTATION_STYLE_ASSIGNMENT((#208057)); +#208057 = SURFACE_STYLE_USAGE(.BOTH.,#208058); +#208058 = SURFACE_SIDE_STYLE('',(#208059)); +#208059 = SURFACE_STYLE_FILL_AREA(#208060); +#208060 = FILL_AREA_STYLE('',(#208061)); +#208061 = FILL_AREA_STYLE_COLOUR('',#197425); +#208062 = OVER_RIDING_STYLED_ITEM('overriding color',(#208063),#195510, + #207397); +#208063 = PRESENTATION_STYLE_ASSIGNMENT((#208064)); +#208064 = SURFACE_STYLE_USAGE(.BOTH.,#208065); +#208065 = SURFACE_SIDE_STYLE('',(#208066)); +#208066 = SURFACE_STYLE_FILL_AREA(#208067); +#208067 = FILL_AREA_STYLE('',(#208068)); +#208068 = FILL_AREA_STYLE_COLOUR('',#197425); +#208069 = OVER_RIDING_STYLED_ITEM('overriding color',(#208070),#195536, + #207397); +#208070 = PRESENTATION_STYLE_ASSIGNMENT((#208071)); +#208071 = SURFACE_STYLE_USAGE(.BOTH.,#208072); +#208072 = SURFACE_SIDE_STYLE('',(#208073)); +#208073 = SURFACE_STYLE_FILL_AREA(#208074); +#208074 = FILL_AREA_STYLE('',(#208075)); +#208075 = FILL_AREA_STYLE_COLOUR('',#197425); +#208076 = OVER_RIDING_STYLED_ITEM('overriding color',(#208077),#195562, + #207397); +#208077 = PRESENTATION_STYLE_ASSIGNMENT((#208078)); +#208078 = SURFACE_STYLE_USAGE(.BOTH.,#208079); +#208079 = SURFACE_SIDE_STYLE('',(#208080)); +#208080 = SURFACE_STYLE_FILL_AREA(#208081); +#208081 = FILL_AREA_STYLE('',(#208082)); +#208082 = FILL_AREA_STYLE_COLOUR('',#197425); +#208083 = OVER_RIDING_STYLED_ITEM('overriding color',(#208084),#195569, + #207397); +#208084 = PRESENTATION_STYLE_ASSIGNMENT((#208085)); +#208085 = SURFACE_STYLE_USAGE(.BOTH.,#208086); +#208086 = SURFACE_SIDE_STYLE('',(#208087)); +#208087 = SURFACE_STYLE_FILL_AREA(#208088); +#208088 = FILL_AREA_STYLE('',(#208089)); +#208089 = FILL_AREA_STYLE_COLOUR('',#197630); +#208090 = OVER_RIDING_STYLED_ITEM('overriding color',(#208091),#195707, + #207397); +#208091 = PRESENTATION_STYLE_ASSIGNMENT((#208092)); +#208092 = SURFACE_STYLE_USAGE(.BOTH.,#208093); +#208093 = SURFACE_SIDE_STYLE('',(#208094)); +#208094 = SURFACE_STYLE_FILL_AREA(#208095); +#208095 = FILL_AREA_STYLE('',(#208096)); +#208096 = FILL_AREA_STYLE_COLOUR('',#197630); +#208097 = OVER_RIDING_STYLED_ITEM('overriding color',(#208098),#195780, + #207397); +#208098 = PRESENTATION_STYLE_ASSIGNMENT((#208099)); +#208099 = SURFACE_STYLE_USAGE(.BOTH.,#208100); +#208100 = SURFACE_SIDE_STYLE('',(#208101)); +#208101 = SURFACE_STYLE_FILL_AREA(#208102); +#208102 = FILL_AREA_STYLE('',(#208103)); +#208103 = FILL_AREA_STYLE_COLOUR('',#197630); +#208104 = OVER_RIDING_STYLED_ITEM('overriding color',(#208105),#195918, + #207397); +#208105 = PRESENTATION_STYLE_ASSIGNMENT((#208106)); +#208106 = SURFACE_STYLE_USAGE(.BOTH.,#208107); +#208107 = SURFACE_SIDE_STYLE('',(#208108)); +#208108 = SURFACE_STYLE_FILL_AREA(#208109); +#208109 = FILL_AREA_STYLE('',(#208110)); +#208110 = FILL_AREA_STYLE_COLOUR('',#197630); +#208111 = OVER_RIDING_STYLED_ITEM('overriding color',(#208112),#195991, + #207397); +#208112 = PRESENTATION_STYLE_ASSIGNMENT((#208113)); +#208113 = SURFACE_STYLE_USAGE(.BOTH.,#208114); +#208114 = SURFACE_SIDE_STYLE('',(#208115)); +#208115 = SURFACE_STYLE_FILL_AREA(#208116); +#208116 = FILL_AREA_STYLE('',(#208117)); +#208117 = FILL_AREA_STYLE_COLOUR('',#197630); +#208118 = OVER_RIDING_STYLED_ITEM('overriding color',(#208119),#196129, + #207397); +#208119 = PRESENTATION_STYLE_ASSIGNMENT((#208120)); +#208120 = SURFACE_STYLE_USAGE(.BOTH.,#208121); +#208121 = SURFACE_SIDE_STYLE('',(#208122)); +#208122 = SURFACE_STYLE_FILL_AREA(#208123); +#208123 = FILL_AREA_STYLE('',(#208124)); +#208124 = FILL_AREA_STYLE_COLOUR('',#197630); +#208125 = OVER_RIDING_STYLED_ITEM('overriding color',(#208126),#196202, + #207397); +#208126 = PRESENTATION_STYLE_ASSIGNMENT((#208127)); +#208127 = SURFACE_STYLE_USAGE(.BOTH.,#208128); +#208128 = SURFACE_SIDE_STYLE('',(#208129)); +#208129 = SURFACE_STYLE_FILL_AREA(#208130); +#208130 = FILL_AREA_STYLE('',(#208131)); +#208131 = FILL_AREA_STYLE_COLOUR('',#197630); +#208132 = OVER_RIDING_STYLED_ITEM('overriding color',(#208133),#196340, + #207397); +#208133 = PRESENTATION_STYLE_ASSIGNMENT((#208134)); +#208134 = SURFACE_STYLE_USAGE(.BOTH.,#208135); +#208135 = SURFACE_SIDE_STYLE('',(#208136)); +#208136 = SURFACE_STYLE_FILL_AREA(#208137); +#208137 = FILL_AREA_STYLE('',(#208138)); +#208138 = FILL_AREA_STYLE_COLOUR('',#197630); +#208139 = OVER_RIDING_STYLED_ITEM('overriding color',(#208140),#196413, + #207397); +#208140 = PRESENTATION_STYLE_ASSIGNMENT((#208141)); +#208141 = SURFACE_STYLE_USAGE(.BOTH.,#208142); +#208142 = SURFACE_SIDE_STYLE('',(#208143)); +#208143 = SURFACE_STYLE_FILL_AREA(#208144); +#208144 = FILL_AREA_STYLE('',(#208145)); +#208145 = FILL_AREA_STYLE_COLOUR('',#197630); +#208146 = OVER_RIDING_STYLED_ITEM('overriding color',(#208147),#196463, + #207397); +#208147 = PRESENTATION_STYLE_ASSIGNMENT((#208148)); +#208148 = SURFACE_STYLE_USAGE(.BOTH.,#208149); +#208149 = SURFACE_SIDE_STYLE('',(#208150)); +#208150 = SURFACE_STYLE_FILL_AREA(#208151); +#208151 = FILL_AREA_STYLE('',(#208152)); +#208152 = FILL_AREA_STYLE_COLOUR('',#198360); +#208153 = OVER_RIDING_STYLED_ITEM('overriding color',(#208154),#196468, + #207397); +#208154 = PRESENTATION_STYLE_ASSIGNMENT((#208155)); +#208155 = SURFACE_STYLE_USAGE(.BOTH.,#208156); +#208156 = SURFACE_SIDE_STYLE('',(#208157)); +#208157 = SURFACE_STYLE_FILL_AREA(#208158); +#208158 = FILL_AREA_STYLE('',(#208159)); +#208159 = FILL_AREA_STYLE_COLOUR('',#197630); +#208160 = OVER_RIDING_STYLED_ITEM('overriding color',(#208161),#196517, + #207397); +#208161 = PRESENTATION_STYLE_ASSIGNMENT((#208162)); +#208162 = SURFACE_STYLE_USAGE(.BOTH.,#208163); +#208163 = SURFACE_SIDE_STYLE('',(#208164)); +#208164 = SURFACE_STYLE_FILL_AREA(#208165); +#208165 = FILL_AREA_STYLE('',(#208166)); +#208166 = FILL_AREA_STYLE_COLOUR('',#197630); +#208167 = OVER_RIDING_STYLED_ITEM('overriding color',(#208168),#196524, + #207397); +#208168 = PRESENTATION_STYLE_ASSIGNMENT((#208169)); +#208169 = SURFACE_STYLE_USAGE(.BOTH.,#208170); +#208170 = SURFACE_SIDE_STYLE('',(#208171)); +#208171 = SURFACE_STYLE_FILL_AREA(#208172); +#208172 = FILL_AREA_STYLE('',(#208173)); +#208173 = FILL_AREA_STYLE_COLOUR('',#197630); +#208174 = OVER_RIDING_STYLED_ITEM('overriding color',(#208175),#196573, + #207397); +#208175 = PRESENTATION_STYLE_ASSIGNMENT((#208176)); +#208176 = SURFACE_STYLE_USAGE(.BOTH.,#208177); +#208177 = SURFACE_SIDE_STYLE('',(#208178)); +#208178 = SURFACE_STYLE_FILL_AREA(#208179); +#208179 = FILL_AREA_STYLE('',(#208180)); +#208180 = FILL_AREA_STYLE_COLOUR('',#197630); +#208181 = OVER_RIDING_STYLED_ITEM('overriding color',(#208182),#196622, + #207397); +#208182 = PRESENTATION_STYLE_ASSIGNMENT((#208183)); +#208183 = SURFACE_STYLE_USAGE(.BOTH.,#208184); +#208184 = SURFACE_SIDE_STYLE('',(#208185)); +#208185 = SURFACE_STYLE_FILL_AREA(#208186); +#208186 = FILL_AREA_STYLE('',(#208187)); +#208187 = FILL_AREA_STYLE_COLOUR('',#197630); +#208188 = OVER_RIDING_STYLED_ITEM('overriding color',(#208189),#196629, + #207397); +#208189 = PRESENTATION_STYLE_ASSIGNMENT((#208190)); +#208190 = SURFACE_STYLE_USAGE(.BOTH.,#208191); +#208191 = SURFACE_SIDE_STYLE('',(#208192)); +#208192 = SURFACE_STYLE_FILL_AREA(#208193); +#208193 = FILL_AREA_STYLE('',(#208194)); +#208194 = FILL_AREA_STYLE_COLOUR('',#197630); +#208195 = OVER_RIDING_STYLED_ITEM('overriding color',(#208196),#196636, + #207397); +#208196 = PRESENTATION_STYLE_ASSIGNMENT((#208197)); +#208197 = SURFACE_STYLE_USAGE(.BOTH.,#208198); +#208198 = SURFACE_SIDE_STYLE('',(#208199)); +#208199 = SURFACE_STYLE_FILL_AREA(#208200); +#208200 = FILL_AREA_STYLE('',(#208201)); +#208201 = FILL_AREA_STYLE_COLOUR('',#197630); +#208202 = OVER_RIDING_STYLED_ITEM('overriding color',(#208203),#196685, + #207397); +#208203 = PRESENTATION_STYLE_ASSIGNMENT((#208204)); +#208204 = SURFACE_STYLE_USAGE(.BOTH.,#208205); +#208205 = SURFACE_SIDE_STYLE('',(#208206)); +#208206 = SURFACE_STYLE_FILL_AREA(#208207); +#208207 = FILL_AREA_STYLE('',(#208208)); +#208208 = FILL_AREA_STYLE_COLOUR('',#197630); +#208209 = OVER_RIDING_STYLED_ITEM('overriding color',(#208210),#196692, + #207397); +#208210 = PRESENTATION_STYLE_ASSIGNMENT((#208211)); +#208211 = SURFACE_STYLE_USAGE(.BOTH.,#208212); +#208212 = SURFACE_SIDE_STYLE('',(#208213)); +#208213 = SURFACE_STYLE_FILL_AREA(#208214); +#208214 = FILL_AREA_STYLE('',(#208215)); +#208215 = FILL_AREA_STYLE_COLOUR('',#197630); +#208216 = OVER_RIDING_STYLED_ITEM('overriding color',(#208217),#196741, + #207397); +#208217 = PRESENTATION_STYLE_ASSIGNMENT((#208218)); +#208218 = SURFACE_STYLE_USAGE(.BOTH.,#208219); +#208219 = SURFACE_SIDE_STYLE('',(#208220)); +#208220 = SURFACE_STYLE_FILL_AREA(#208221); +#208221 = FILL_AREA_STYLE('',(#208222)); +#208222 = FILL_AREA_STYLE_COLOUR('',#197630); +#208223 = OVER_RIDING_STYLED_ITEM('overriding color',(#208224),#196813, + #207397); +#208224 = PRESENTATION_STYLE_ASSIGNMENT((#208225)); +#208225 = SURFACE_STYLE_USAGE(.BOTH.,#208226); +#208226 = SURFACE_SIDE_STYLE('',(#208227)); +#208227 = SURFACE_STYLE_FILL_AREA(#208228); +#208228 = FILL_AREA_STYLE('',(#208229)); +#208229 = FILL_AREA_STYLE_COLOUR('',#197630); +#208230 = OVER_RIDING_STYLED_ITEM('overriding color',(#208231),#196820, + #207397); +#208231 = PRESENTATION_STYLE_ASSIGNMENT((#208232)); +#208232 = SURFACE_STYLE_USAGE(.BOTH.,#208233); +#208233 = SURFACE_SIDE_STYLE('',(#208234)); +#208234 = SURFACE_STYLE_FILL_AREA(#208235); +#208235 = FILL_AREA_STYLE('',(#208236)); +#208236 = FILL_AREA_STYLE_COLOUR('',#197630); +#208237 = OVER_RIDING_STYLED_ITEM('overriding color',(#208238),#196827, + #207397); +#208238 = PRESENTATION_STYLE_ASSIGNMENT((#208239)); +#208239 = SURFACE_STYLE_USAGE(.BOTH.,#208240); +#208240 = SURFACE_SIDE_STYLE('',(#208241)); +#208241 = SURFACE_STYLE_FILL_AREA(#208242); +#208242 = FILL_AREA_STYLE('',(#208243)); +#208243 = FILL_AREA_STYLE_COLOUR('',#197630); +#208244 = OVER_RIDING_STYLED_ITEM('overriding color',(#208245),#196876, + #207397); +#208245 = PRESENTATION_STYLE_ASSIGNMENT((#208246)); +#208246 = SURFACE_STYLE_USAGE(.BOTH.,#208247); +#208247 = SURFACE_SIDE_STYLE('',(#208248)); +#208248 = SURFACE_STYLE_FILL_AREA(#208249); +#208249 = FILL_AREA_STYLE('',(#208250)); +#208250 = FILL_AREA_STYLE_COLOUR('',#197630); +#208251 = OVER_RIDING_STYLED_ITEM('overriding color',(#208252),#196948, + #207397); +#208252 = PRESENTATION_STYLE_ASSIGNMENT((#208253)); +#208253 = SURFACE_STYLE_USAGE(.BOTH.,#208254); +#208254 = SURFACE_SIDE_STYLE('',(#208255)); +#208255 = SURFACE_STYLE_FILL_AREA(#208256); +#208256 = FILL_AREA_STYLE('',(#208257)); +#208257 = FILL_AREA_STYLE_COLOUR('',#197630); +#208258 = OVER_RIDING_STYLED_ITEM('overriding color',(#208259),#196955, + #207397); +#208259 = PRESENTATION_STYLE_ASSIGNMENT((#208260)); +#208260 = SURFACE_STYLE_USAGE(.BOTH.,#208261); +#208261 = SURFACE_SIDE_STYLE('',(#208262)); +#208262 = SURFACE_STYLE_FILL_AREA(#208263); +#208263 = FILL_AREA_STYLE('',(#208264)); +#208264 = FILL_AREA_STYLE_COLOUR('',#197630); +#208265 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #208266),#7034); +#208266 = STYLED_ITEM('color',(#208267),#334); +#208267 = PRESENTATION_STYLE_ASSIGNMENT((#208268,#208273)); +#208268 = SURFACE_STYLE_USAGE(.BOTH.,#208269); +#208269 = SURFACE_SIDE_STYLE('',(#208270)); +#208270 = SURFACE_STYLE_FILL_AREA(#208271); +#208271 = FILL_AREA_STYLE('',(#208272)); +#208272 = FILL_AREA_STYLE_COLOUR('',#206828); +#208273 = CURVE_STYLE('',#208274,POSITIVE_LENGTH_MEASURE(0.1),#206828); +#208274 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#208275 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #208276,#208284,#208291,#208298,#208306,#208313,#208320,#208327, + #208334,#208341,#208348,#208355,#208362,#208369,#208376,#208383, + #208390,#208397,#208404,#208411,#208418,#208425,#208432,#208439, + #208446,#208453,#208460,#208467,#208474,#208481,#208488,#208495, + #208502,#208509,#208516,#208523,#208530,#208537,#208544,#208551, + #208558,#208565,#208572,#208579,#208586,#208593,#208600,#208607, + #208614,#208621,#208628,#208635,#208642,#208649,#208656,#208663, + #208670,#208677,#208684,#208691,#208698,#208705,#208712,#208719, + #208726,#208733,#208740,#208747,#208754,#208761,#208768,#208775, + #208782,#208789,#208796,#208803,#208810,#208817,#208824,#208831, + #208838,#208845,#208852,#208859,#208866,#208873,#208880,#208887, + #208894,#208901),#30847); +#208276 = STYLED_ITEM('color',(#208277),#24431); +#208277 = PRESENTATION_STYLE_ASSIGNMENT((#208278)); +#208278 = SURFACE_STYLE_USAGE(.BOTH.,#208279); +#208279 = SURFACE_SIDE_STYLE('',(#208280)); +#208280 = SURFACE_STYLE_FILL_AREA(#208281); +#208281 = FILL_AREA_STYLE('',(#208282)); +#208282 = FILL_AREA_STYLE_COLOUR('',#208283); +#208283 = COLOUR_RGB('',0.E+000,0.501960813999,0.501960813999); +#208284 = OVER_RIDING_STYLED_ITEM('overriding color',(#208285),#24433, + #208276); +#208285 = PRESENTATION_STYLE_ASSIGNMENT((#208286)); +#208286 = SURFACE_STYLE_USAGE(.BOTH.,#208287); +#208287 = SURFACE_SIDE_STYLE('',(#208288)); +#208288 = SURFACE_STYLE_FILL_AREA(#208289); +#208289 = FILL_AREA_STYLE('',(#208290)); +#208290 = FILL_AREA_STYLE_COLOUR('',#197425); +#208291 = OVER_RIDING_STYLED_ITEM('overriding color',(#208292),#24553, + #208276); +#208292 = PRESENTATION_STYLE_ASSIGNMENT((#208293)); +#208293 = SURFACE_STYLE_USAGE(.BOTH.,#208294); +#208294 = SURFACE_SIDE_STYLE('',(#208295)); +#208295 = SURFACE_STYLE_FILL_AREA(#208296); +#208296 = FILL_AREA_STYLE('',(#208297)); +#208297 = FILL_AREA_STYLE_COLOUR('',#197425); +#208298 = OVER_RIDING_STYLED_ITEM('overriding color',(#208299),#24629, + #208276); +#208299 = PRESENTATION_STYLE_ASSIGNMENT((#208300)); +#208300 = SURFACE_STYLE_USAGE(.BOTH.,#208301); +#208301 = SURFACE_SIDE_STYLE('',(#208302)); +#208302 = SURFACE_STYLE_FILL_AREA(#208303); +#208303 = FILL_AREA_STYLE('',(#208304)); +#208304 = FILL_AREA_STYLE_COLOUR('',#208305); +#208305 = COLOUR_RGB('',0.7109375,0.6015625,0.4140625); +#208306 = OVER_RIDING_STYLED_ITEM('overriding color',(#208307),#25134, + #208276); +#208307 = PRESENTATION_STYLE_ASSIGNMENT((#208308)); +#208308 = SURFACE_STYLE_USAGE(.BOTH.,#208309); +#208309 = SURFACE_SIDE_STYLE('',(#208310)); +#208310 = SURFACE_STYLE_FILL_AREA(#208311); +#208311 = FILL_AREA_STYLE('',(#208312)); +#208312 = FILL_AREA_STYLE_COLOUR('',#197425); +#208313 = OVER_RIDING_STYLED_ITEM('overriding color',(#208314),#25183, + #208276); +#208314 = PRESENTATION_STYLE_ASSIGNMENT((#208315)); +#208315 = SURFACE_STYLE_USAGE(.BOTH.,#208316); +#208316 = SURFACE_SIDE_STYLE('',(#208317)); +#208317 = SURFACE_STYLE_FILL_AREA(#208318); +#208318 = FILL_AREA_STYLE('',(#208319)); +#208319 = FILL_AREA_STYLE_COLOUR('',#197425); +#208320 = OVER_RIDING_STYLED_ITEM('overriding color',(#208321),#25210, + #208276); +#208321 = PRESENTATION_STYLE_ASSIGNMENT((#208322)); +#208322 = SURFACE_STYLE_USAGE(.BOTH.,#208323); +#208323 = SURFACE_SIDE_STYLE('',(#208324)); +#208324 = SURFACE_STYLE_FILL_AREA(#208325); +#208325 = FILL_AREA_STYLE('',(#208326)); +#208326 = FILL_AREA_STYLE_COLOUR('',#197425); +#208327 = OVER_RIDING_STYLED_ITEM('overriding color',(#208328),#25217, + #208276); +#208328 = PRESENTATION_STYLE_ASSIGNMENT((#208329)); +#208329 = SURFACE_STYLE_USAGE(.BOTH.,#208330); +#208330 = SURFACE_SIDE_STYLE('',(#208331)); +#208331 = SURFACE_STYLE_FILL_AREA(#208332); +#208332 = FILL_AREA_STYLE('',(#208333)); +#208333 = FILL_AREA_STYLE_COLOUR('',#208305); +#208334 = OVER_RIDING_STYLED_ITEM('overriding color',(#208335),#25293, + #208276); +#208335 = PRESENTATION_STYLE_ASSIGNMENT((#208336)); +#208336 = SURFACE_STYLE_USAGE(.BOTH.,#208337); +#208337 = SURFACE_SIDE_STYLE('',(#208338)); +#208338 = SURFACE_STYLE_FILL_AREA(#208339); +#208339 = FILL_AREA_STYLE('',(#208340)); +#208340 = FILL_AREA_STYLE_COLOUR('',#197425); +#208341 = OVER_RIDING_STYLED_ITEM('overriding color',(#208342),#25369, + #208276); +#208342 = PRESENTATION_STYLE_ASSIGNMENT((#208343)); +#208343 = SURFACE_STYLE_USAGE(.BOTH.,#208344); +#208344 = SURFACE_SIDE_STYLE('',(#208345)); +#208345 = SURFACE_STYLE_FILL_AREA(#208346); +#208346 = FILL_AREA_STYLE('',(#208347)); +#208347 = FILL_AREA_STYLE_COLOUR('',#208305); +#208348 = OVER_RIDING_STYLED_ITEM('overriding color',(#208349),#25525, + #208276); +#208349 = PRESENTATION_STYLE_ASSIGNMENT((#208350)); +#208350 = SURFACE_STYLE_USAGE(.BOTH.,#208351); +#208351 = SURFACE_SIDE_STYLE('',(#208352)); +#208352 = SURFACE_STYLE_FILL_AREA(#208353); +#208353 = FILL_AREA_STYLE('',(#208354)); +#208354 = FILL_AREA_STYLE_COLOUR('',#197425); +#208355 = OVER_RIDING_STYLED_ITEM('overriding color',(#208356),#25601, + #208276); +#208356 = PRESENTATION_STYLE_ASSIGNMENT((#208357)); +#208357 = SURFACE_STYLE_USAGE(.BOTH.,#208358); +#208358 = SURFACE_SIDE_STYLE('',(#208359)); +#208359 = SURFACE_STYLE_FILL_AREA(#208360); +#208360 = FILL_AREA_STYLE('',(#208361)); +#208361 = FILL_AREA_STYLE_COLOUR('',#197425); +#208362 = OVER_RIDING_STYLED_ITEM('overriding color',(#208363),#25677, + #208276); +#208363 = PRESENTATION_STYLE_ASSIGNMENT((#208364)); +#208364 = SURFACE_STYLE_USAGE(.BOTH.,#208365); +#208365 = SURFACE_SIDE_STYLE('',(#208366)); +#208366 = SURFACE_STYLE_FILL_AREA(#208367); +#208367 = FILL_AREA_STYLE('',(#208368)); +#208368 = FILL_AREA_STYLE_COLOUR('',#208305); +#208369 = OVER_RIDING_STYLED_ITEM('overriding color',(#208370),#25726, + #208276); +#208370 = PRESENTATION_STYLE_ASSIGNMENT((#208371)); +#208371 = SURFACE_STYLE_USAGE(.BOTH.,#208372); +#208372 = SURFACE_SIDE_STYLE('',(#208373)); +#208373 = SURFACE_STYLE_FILL_AREA(#208374); +#208374 = FILL_AREA_STYLE('',(#208375)); +#208375 = FILL_AREA_STYLE_COLOUR('',#197425); +#208376 = OVER_RIDING_STYLED_ITEM('overriding color',(#208377),#25775, + #208276); +#208377 = PRESENTATION_STYLE_ASSIGNMENT((#208378)); +#208378 = SURFACE_STYLE_USAGE(.BOTH.,#208379); +#208379 = SURFACE_SIDE_STYLE('',(#208380)); +#208380 = SURFACE_STYLE_FILL_AREA(#208381); +#208381 = FILL_AREA_STYLE('',(#208382)); +#208382 = FILL_AREA_STYLE_COLOUR('',#197425); +#208383 = OVER_RIDING_STYLED_ITEM('overriding color',(#208384),#25846, + #208276); +#208384 = PRESENTATION_STYLE_ASSIGNMENT((#208385)); +#208385 = SURFACE_STYLE_USAGE(.BOTH.,#208386); +#208386 = SURFACE_SIDE_STYLE('',(#208387)); +#208387 = SURFACE_STYLE_FILL_AREA(#208388); +#208388 = FILL_AREA_STYLE('',(#208389)); +#208389 = FILL_AREA_STYLE_COLOUR('',#197425); +#208390 = OVER_RIDING_STYLED_ITEM('overriding color',(#208391),#25917, + #208276); +#208391 = PRESENTATION_STYLE_ASSIGNMENT((#208392)); +#208392 = SURFACE_STYLE_USAGE(.BOTH.,#208393); +#208393 = SURFACE_SIDE_STYLE('',(#208394)); +#208394 = SURFACE_STYLE_FILL_AREA(#208395); +#208395 = FILL_AREA_STYLE('',(#208396)); +#208396 = FILL_AREA_STYLE_COLOUR('',#197425); +#208397 = OVER_RIDING_STYLED_ITEM('overriding color',(#208398),#25966, + #208276); +#208398 = PRESENTATION_STYLE_ASSIGNMENT((#208399)); +#208399 = SURFACE_STYLE_USAGE(.BOTH.,#208400); +#208400 = SURFACE_SIDE_STYLE('',(#208401)); +#208401 = SURFACE_STYLE_FILL_AREA(#208402); +#208402 = FILL_AREA_STYLE('',(#208403)); +#208403 = FILL_AREA_STYLE_COLOUR('',#197425); +#208404 = OVER_RIDING_STYLED_ITEM('overriding color',(#208405),#25993, + #208276); +#208405 = PRESENTATION_STYLE_ASSIGNMENT((#208406)); +#208406 = SURFACE_STYLE_USAGE(.BOTH.,#208407); +#208407 = SURFACE_SIDE_STYLE('',(#208408)); +#208408 = SURFACE_STYLE_FILL_AREA(#208409); +#208409 = FILL_AREA_STYLE('',(#208410)); +#208410 = FILL_AREA_STYLE_COLOUR('',#208305); +#208411 = OVER_RIDING_STYLED_ITEM('overriding color',(#208412),#26127, + #208276); +#208412 = PRESENTATION_STYLE_ASSIGNMENT((#208413)); +#208413 = SURFACE_STYLE_USAGE(.BOTH.,#208414); +#208414 = SURFACE_SIDE_STYLE('',(#208415)); +#208415 = SURFACE_STYLE_FILL_AREA(#208416); +#208416 = FILL_AREA_STYLE('',(#208417)); +#208417 = FILL_AREA_STYLE_COLOUR('',#197425); +#208418 = OVER_RIDING_STYLED_ITEM('overriding color',(#208419),#26154, + #208276); +#208419 = PRESENTATION_STYLE_ASSIGNMENT((#208420)); +#208420 = SURFACE_STYLE_USAGE(.BOTH.,#208421); +#208421 = SURFACE_SIDE_STYLE('',(#208422)); +#208422 = SURFACE_STYLE_FILL_AREA(#208423); +#208423 = FILL_AREA_STYLE('',(#208424)); +#208424 = FILL_AREA_STYLE_COLOUR('',#197425); +#208425 = OVER_RIDING_STYLED_ITEM('overriding color',(#208426),#26181, + #208276); +#208426 = PRESENTATION_STYLE_ASSIGNMENT((#208427)); +#208427 = SURFACE_STYLE_USAGE(.BOTH.,#208428); +#208428 = SURFACE_SIDE_STYLE('',(#208429)); +#208429 = SURFACE_STYLE_FILL_AREA(#208430); +#208430 = FILL_AREA_STYLE('',(#208431)); +#208431 = FILL_AREA_STYLE_COLOUR('',#197425); +#208432 = OVER_RIDING_STYLED_ITEM('overriding color',(#208433),#26208, + #208276); +#208433 = PRESENTATION_STYLE_ASSIGNMENT((#208434)); +#208434 = SURFACE_STYLE_USAGE(.BOTH.,#208435); +#208435 = SURFACE_SIDE_STYLE('',(#208436)); +#208436 = SURFACE_STYLE_FILL_AREA(#208437); +#208437 = FILL_AREA_STYLE('',(#208438)); +#208438 = FILL_AREA_STYLE_COLOUR('',#197425); +#208439 = OVER_RIDING_STYLED_ITEM('overriding color',(#208440),#26235, + #208276); +#208440 = PRESENTATION_STYLE_ASSIGNMENT((#208441)); +#208441 = SURFACE_STYLE_USAGE(.BOTH.,#208442); +#208442 = SURFACE_SIDE_STYLE('',(#208443)); +#208443 = SURFACE_STYLE_FILL_AREA(#208444); +#208444 = FILL_AREA_STYLE('',(#208445)); +#208445 = FILL_AREA_STYLE_COLOUR('',#208305); +#208446 = OVER_RIDING_STYLED_ITEM('overriding color',(#208447),#26726, + #208276); +#208447 = PRESENTATION_STYLE_ASSIGNMENT((#208448)); +#208448 = SURFACE_STYLE_USAGE(.BOTH.,#208449); +#208449 = SURFACE_SIDE_STYLE('',(#208450)); +#208450 = SURFACE_STYLE_FILL_AREA(#208451); +#208451 = FILL_AREA_STYLE('',(#208452)); +#208452 = FILL_AREA_STYLE_COLOUR('',#197425); +#208453 = OVER_RIDING_STYLED_ITEM('overriding color',(#208454),#26733, + #208276); +#208454 = PRESENTATION_STYLE_ASSIGNMENT((#208455)); +#208455 = SURFACE_STYLE_USAGE(.BOTH.,#208456); +#208456 = SURFACE_SIDE_STYLE('',(#208457)); +#208457 = SURFACE_STYLE_FILL_AREA(#208458); +#208458 = FILL_AREA_STYLE('',(#208459)); +#208459 = FILL_AREA_STYLE_COLOUR('',#208305); +#208460 = OVER_RIDING_STYLED_ITEM('overriding color',(#208461),#26804, + #208276); +#208461 = PRESENTATION_STYLE_ASSIGNMENT((#208462)); +#208462 = SURFACE_STYLE_USAGE(.BOTH.,#208463); +#208463 = SURFACE_SIDE_STYLE('',(#208464)); +#208464 = SURFACE_STYLE_FILL_AREA(#208465); +#208465 = FILL_AREA_STYLE('',(#208466)); +#208466 = FILL_AREA_STYLE_COLOUR('',#208305); +#208467 = OVER_RIDING_STYLED_ITEM('overriding color',(#208468),#26831, + #208276); +#208468 = PRESENTATION_STYLE_ASSIGNMENT((#208469)); +#208469 = SURFACE_STYLE_USAGE(.BOTH.,#208470); +#208470 = SURFACE_SIDE_STYLE('',(#208471)); +#208471 = SURFACE_STYLE_FILL_AREA(#208472); +#208472 = FILL_AREA_STYLE('',(#208473)); +#208473 = FILL_AREA_STYLE_COLOUR('',#208305); +#208474 = OVER_RIDING_STYLED_ITEM('overriding color',(#208475),#26858, + #208276); +#208475 = PRESENTATION_STYLE_ASSIGNMENT((#208476)); +#208476 = SURFACE_STYLE_USAGE(.BOTH.,#208477); +#208477 = SURFACE_SIDE_STYLE('',(#208478)); +#208478 = SURFACE_STYLE_FILL_AREA(#208479); +#208479 = FILL_AREA_STYLE('',(#208480)); +#208480 = FILL_AREA_STYLE_COLOUR('',#197425); +#208481 = OVER_RIDING_STYLED_ITEM('overriding color',(#208482),#26865, + #208276); +#208482 = PRESENTATION_STYLE_ASSIGNMENT((#208483)); +#208483 = SURFACE_STYLE_USAGE(.BOTH.,#208484); +#208484 = SURFACE_SIDE_STYLE('',(#208485)); +#208485 = SURFACE_STYLE_FILL_AREA(#208486); +#208486 = FILL_AREA_STYLE('',(#208487)); +#208487 = FILL_AREA_STYLE_COLOUR('',#197425); +#208488 = OVER_RIDING_STYLED_ITEM('overriding color',(#208489),#26872, + #208276); +#208489 = PRESENTATION_STYLE_ASSIGNMENT((#208490)); +#208490 = SURFACE_STYLE_USAGE(.BOTH.,#208491); +#208491 = SURFACE_SIDE_STYLE('',(#208492)); +#208492 = SURFACE_STYLE_FILL_AREA(#208493); +#208493 = FILL_AREA_STYLE('',(#208494)); +#208494 = FILL_AREA_STYLE_COLOUR('',#208305); +#208495 = OVER_RIDING_STYLED_ITEM('overriding color',(#208496),#26943, + #208276); +#208496 = PRESENTATION_STYLE_ASSIGNMENT((#208497)); +#208497 = SURFACE_STYLE_USAGE(.BOTH.,#208498); +#208498 = SURFACE_SIDE_STYLE('',(#208499)); +#208499 = SURFACE_STYLE_FILL_AREA(#208500); +#208500 = FILL_AREA_STYLE('',(#208501)); +#208501 = FILL_AREA_STYLE_COLOUR('',#208305); +#208502 = OVER_RIDING_STYLED_ITEM('overriding color',(#208503),#26970, + #208276); +#208503 = PRESENTATION_STYLE_ASSIGNMENT((#208504)); +#208504 = SURFACE_STYLE_USAGE(.BOTH.,#208505); +#208505 = SURFACE_SIDE_STYLE('',(#208506)); +#208506 = SURFACE_STYLE_FILL_AREA(#208507); +#208507 = FILL_AREA_STYLE('',(#208508)); +#208508 = FILL_AREA_STYLE_COLOUR('',#208305); +#208509 = OVER_RIDING_STYLED_ITEM('overriding color',(#208510),#26997, + #208276); +#208510 = PRESENTATION_STYLE_ASSIGNMENT((#208511)); +#208511 = SURFACE_STYLE_USAGE(.BOTH.,#208512); +#208512 = SURFACE_SIDE_STYLE('',(#208513)); +#208513 = SURFACE_STYLE_FILL_AREA(#208514); +#208514 = FILL_AREA_STYLE('',(#208515)); +#208515 = FILL_AREA_STYLE_COLOUR('',#197425); +#208516 = OVER_RIDING_STYLED_ITEM('overriding color',(#208517),#27073, + #208276); +#208517 = PRESENTATION_STYLE_ASSIGNMENT((#208518)); +#208518 = SURFACE_STYLE_USAGE(.BOTH.,#208519); +#208519 = SURFACE_SIDE_STYLE('',(#208520)); +#208520 = SURFACE_STYLE_FILL_AREA(#208521); +#208521 = FILL_AREA_STYLE('',(#208522)); +#208522 = FILL_AREA_STYLE_COLOUR('',#208305); +#208523 = OVER_RIDING_STYLED_ITEM('overriding color',(#208524),#27080, + #208276); +#208524 = PRESENTATION_STYLE_ASSIGNMENT((#208525)); +#208525 = SURFACE_STYLE_USAGE(.BOTH.,#208526); +#208526 = SURFACE_SIDE_STYLE('',(#208527)); +#208527 = SURFACE_STYLE_FILL_AREA(#208528); +#208528 = FILL_AREA_STYLE('',(#208529)); +#208529 = FILL_AREA_STYLE_COLOUR('',#197425); +#208530 = OVER_RIDING_STYLED_ITEM('overriding color',(#208531),#27156, + #208276); +#208531 = PRESENTATION_STYLE_ASSIGNMENT((#208532)); +#208532 = SURFACE_STYLE_USAGE(.BOTH.,#208533); +#208533 = SURFACE_SIDE_STYLE('',(#208534)); +#208534 = SURFACE_STYLE_FILL_AREA(#208535); +#208535 = FILL_AREA_STYLE('',(#208536)); +#208536 = FILL_AREA_STYLE_COLOUR('',#208305); +#208537 = OVER_RIDING_STYLED_ITEM('overriding color',(#208538),#27451, + #208276); +#208538 = PRESENTATION_STYLE_ASSIGNMENT((#208539)); +#208539 = SURFACE_STYLE_USAGE(.BOTH.,#208540); +#208540 = SURFACE_SIDE_STYLE('',(#208541)); +#208541 = SURFACE_STYLE_FILL_AREA(#208542); +#208542 = FILL_AREA_STYLE('',(#208543)); +#208543 = FILL_AREA_STYLE_COLOUR('',#208305); +#208544 = OVER_RIDING_STYLED_ITEM('overriding color',(#208545),#28047, + #208276); +#208545 = PRESENTATION_STYLE_ASSIGNMENT((#208546)); +#208546 = SURFACE_STYLE_USAGE(.BOTH.,#208547); +#208547 = SURFACE_SIDE_STYLE('',(#208548)); +#208548 = SURFACE_STYLE_FILL_AREA(#208549); +#208549 = FILL_AREA_STYLE('',(#208550)); +#208550 = FILL_AREA_STYLE_COLOUR('',#208305); +#208551 = OVER_RIDING_STYLED_ITEM('overriding color',(#208552),#28096, + #208276); +#208552 = PRESENTATION_STYLE_ASSIGNMENT((#208553)); +#208553 = SURFACE_STYLE_USAGE(.BOTH.,#208554); +#208554 = SURFACE_SIDE_STYLE('',(#208555)); +#208555 = SURFACE_STYLE_FILL_AREA(#208556); +#208556 = FILL_AREA_STYLE('',(#208557)); +#208557 = FILL_AREA_STYLE_COLOUR('',#197425); +#208558 = OVER_RIDING_STYLED_ITEM('overriding color',(#208559),#28222, + #208276); +#208559 = PRESENTATION_STYLE_ASSIGNMENT((#208560)); +#208560 = SURFACE_STYLE_USAGE(.BOTH.,#208561); +#208561 = SURFACE_SIDE_STYLE('',(#208562)); +#208562 = SURFACE_STYLE_FILL_AREA(#208563); +#208563 = FILL_AREA_STYLE('',(#208564)); +#208564 = FILL_AREA_STYLE_COLOUR('',#197425); +#208565 = OVER_RIDING_STYLED_ITEM('overriding color',(#208566),#28338, + #208276); +#208566 = PRESENTATION_STYLE_ASSIGNMENT((#208567)); +#208567 = SURFACE_STYLE_USAGE(.BOTH.,#208568); +#208568 = SURFACE_SIDE_STYLE('',(#208569)); +#208569 = SURFACE_STYLE_FILL_AREA(#208570); +#208570 = FILL_AREA_STYLE('',(#208571)); +#208571 = FILL_AREA_STYLE_COLOUR('',#208305); +#208572 = OVER_RIDING_STYLED_ITEM('overriding color',(#208573),#28494, + #208276); +#208573 = PRESENTATION_STYLE_ASSIGNMENT((#208574)); +#208574 = SURFACE_STYLE_USAGE(.BOTH.,#208575); +#208575 = SURFACE_SIDE_STYLE('',(#208576)); +#208576 = SURFACE_STYLE_FILL_AREA(#208577); +#208577 = FILL_AREA_STYLE('',(#208578)); +#208578 = FILL_AREA_STYLE_COLOUR('',#197425); +#208579 = OVER_RIDING_STYLED_ITEM('overriding color',(#208580),#28521, + #208276); +#208580 = PRESENTATION_STYLE_ASSIGNMENT((#208581)); +#208581 = SURFACE_STYLE_USAGE(.BOTH.,#208582); +#208582 = SURFACE_SIDE_STYLE('',(#208583)); +#208583 = SURFACE_STYLE_FILL_AREA(#208584); +#208584 = FILL_AREA_STYLE('',(#208585)); +#208585 = FILL_AREA_STYLE_COLOUR('',#208305); +#208586 = OVER_RIDING_STYLED_ITEM('overriding color',(#208587),#28745, + #208276); +#208587 = PRESENTATION_STYLE_ASSIGNMENT((#208588)); +#208588 = SURFACE_STYLE_USAGE(.BOTH.,#208589); +#208589 = SURFACE_SIDE_STYLE('',(#208590)); +#208590 = SURFACE_STYLE_FILL_AREA(#208591); +#208591 = FILL_AREA_STYLE('',(#208592)); +#208592 = FILL_AREA_STYLE_COLOUR('',#208305); +#208593 = OVER_RIDING_STYLED_ITEM('overriding color',(#208594),#28752, + #208276); +#208594 = PRESENTATION_STYLE_ASSIGNMENT((#208595)); +#208595 = SURFACE_STYLE_USAGE(.BOTH.,#208596); +#208596 = SURFACE_SIDE_STYLE('',(#208597)); +#208597 = SURFACE_STYLE_FILL_AREA(#208598); +#208598 = FILL_AREA_STYLE('',(#208599)); +#208599 = FILL_AREA_STYLE_COLOUR('',#208305); +#208600 = OVER_RIDING_STYLED_ITEM('overriding color',(#208601),#28779, + #208276); +#208601 = PRESENTATION_STYLE_ASSIGNMENT((#208602)); +#208602 = SURFACE_STYLE_USAGE(.BOTH.,#208603); +#208603 = SURFACE_SIDE_STYLE('',(#208604)); +#208604 = SURFACE_STYLE_FILL_AREA(#208605); +#208605 = FILL_AREA_STYLE('',(#208606)); +#208606 = FILL_AREA_STYLE_COLOUR('',#197425); +#208607 = OVER_RIDING_STYLED_ITEM('overriding color',(#208608),#28806, + #208276); +#208608 = PRESENTATION_STYLE_ASSIGNMENT((#208609)); +#208609 = SURFACE_STYLE_USAGE(.BOTH.,#208610); +#208610 = SURFACE_SIDE_STYLE('',(#208611)); +#208611 = SURFACE_STYLE_FILL_AREA(#208612); +#208612 = FILL_AREA_STYLE('',(#208613)); +#208613 = FILL_AREA_STYLE_COLOUR('',#197425); +#208614 = OVER_RIDING_STYLED_ITEM('overriding color',(#208615),#28813, + #208276); +#208615 = PRESENTATION_STYLE_ASSIGNMENT((#208616)); +#208616 = SURFACE_STYLE_USAGE(.BOTH.,#208617); +#208617 = SURFACE_SIDE_STYLE('',(#208618)); +#208618 = SURFACE_STYLE_FILL_AREA(#208619); +#208619 = FILL_AREA_STYLE('',(#208620)); +#208620 = FILL_AREA_STYLE_COLOUR('',#197425); +#208621 = OVER_RIDING_STYLED_ITEM('overriding color',(#208622),#28820, + #208276); +#208622 = PRESENTATION_STYLE_ASSIGNMENT((#208623)); +#208623 = SURFACE_STYLE_USAGE(.BOTH.,#208624); +#208624 = SURFACE_SIDE_STYLE('',(#208625)); +#208625 = SURFACE_STYLE_FILL_AREA(#208626); +#208626 = FILL_AREA_STYLE('',(#208627)); +#208627 = FILL_AREA_STYLE_COLOUR('',#208305); +#208628 = OVER_RIDING_STYLED_ITEM('overriding color',(#208629),#28891, + #208276); +#208629 = PRESENTATION_STYLE_ASSIGNMENT((#208630)); +#208630 = SURFACE_STYLE_USAGE(.BOTH.,#208631); +#208631 = SURFACE_SIDE_STYLE('',(#208632)); +#208632 = SURFACE_STYLE_FILL_AREA(#208633); +#208633 = FILL_AREA_STYLE('',(#208634)); +#208634 = FILL_AREA_STYLE_COLOUR('',#208305); +#208635 = OVER_RIDING_STYLED_ITEM('overriding color',(#208636),#28940, + #208276); +#208636 = PRESENTATION_STYLE_ASSIGNMENT((#208637)); +#208637 = SURFACE_STYLE_USAGE(.BOTH.,#208638); +#208638 = SURFACE_SIDE_STYLE('',(#208639)); +#208639 = SURFACE_STYLE_FILL_AREA(#208640); +#208640 = FILL_AREA_STYLE('',(#208641)); +#208641 = FILL_AREA_STYLE_COLOUR('',#208305); +#208642 = OVER_RIDING_STYLED_ITEM('overriding color',(#208643),#28967, + #208276); +#208643 = PRESENTATION_STYLE_ASSIGNMENT((#208644)); +#208644 = SURFACE_STYLE_USAGE(.BOTH.,#208645); +#208645 = SURFACE_SIDE_STYLE('',(#208646)); +#208646 = SURFACE_STYLE_FILL_AREA(#208647); +#208647 = FILL_AREA_STYLE('',(#208648)); +#208648 = FILL_AREA_STYLE_COLOUR('',#208305); +#208649 = OVER_RIDING_STYLED_ITEM('overriding color',(#208650),#29354, + #208276); +#208650 = PRESENTATION_STYLE_ASSIGNMENT((#208651)); +#208651 = SURFACE_STYLE_USAGE(.BOTH.,#208652); +#208652 = SURFACE_SIDE_STYLE('',(#208653)); +#208653 = SURFACE_STYLE_FILL_AREA(#208654); +#208654 = FILL_AREA_STYLE('',(#208655)); +#208655 = FILL_AREA_STYLE_COLOUR('',#208305); +#208656 = OVER_RIDING_STYLED_ITEM('overriding color',(#208657),#29401, + #208276); +#208657 = PRESENTATION_STYLE_ASSIGNMENT((#208658)); +#208658 = SURFACE_STYLE_USAGE(.BOTH.,#208659); +#208659 = SURFACE_SIDE_STYLE('',(#208660)); +#208660 = SURFACE_STYLE_FILL_AREA(#208661); +#208661 = FILL_AREA_STYLE('',(#208662)); +#208662 = FILL_AREA_STYLE_COLOUR('',#208305); +#208663 = OVER_RIDING_STYLED_ITEM('overriding color',(#208664),#29428, + #208276); +#208664 = PRESENTATION_STYLE_ASSIGNMENT((#208665)); +#208665 = SURFACE_STYLE_USAGE(.BOTH.,#208666); +#208666 = SURFACE_SIDE_STYLE('',(#208667)); +#208667 = SURFACE_STYLE_FILL_AREA(#208668); +#208668 = FILL_AREA_STYLE('',(#208669)); +#208669 = FILL_AREA_STYLE_COLOUR('',#208305); +#208670 = OVER_RIDING_STYLED_ITEM('overriding color',(#208671),#29435, + #208276); +#208671 = PRESENTATION_STYLE_ASSIGNMENT((#208672)); +#208672 = SURFACE_STYLE_USAGE(.BOTH.,#208673); +#208673 = SURFACE_SIDE_STYLE('',(#208674)); +#208674 = SURFACE_STYLE_FILL_AREA(#208675); +#208675 = FILL_AREA_STYLE('',(#208676)); +#208676 = FILL_AREA_STYLE_COLOUR('',#208305); +#208677 = OVER_RIDING_STYLED_ITEM('overriding color',(#208678),#29442, + #208276); +#208678 = PRESENTATION_STYLE_ASSIGNMENT((#208679)); +#208679 = SURFACE_STYLE_USAGE(.BOTH.,#208680); +#208680 = SURFACE_SIDE_STYLE('',(#208681)); +#208681 = SURFACE_STYLE_FILL_AREA(#208682); +#208682 = FILL_AREA_STYLE('',(#208683)); +#208683 = FILL_AREA_STYLE_COLOUR('',#197425); +#208684 = OVER_RIDING_STYLED_ITEM('overriding color',(#208685),#29547, + #208276); +#208685 = PRESENTATION_STYLE_ASSIGNMENT((#208686)); +#208686 = SURFACE_STYLE_USAGE(.BOTH.,#208687); +#208687 = SURFACE_SIDE_STYLE('',(#208688)); +#208688 = SURFACE_STYLE_FILL_AREA(#208689); +#208689 = FILL_AREA_STYLE('',(#208690)); +#208690 = FILL_AREA_STYLE_COLOUR('',#197425); +#208691 = OVER_RIDING_STYLED_ITEM('overriding color',(#208692),#29652, + #208276); +#208692 = PRESENTATION_STYLE_ASSIGNMENT((#208693)); +#208693 = SURFACE_STYLE_USAGE(.BOTH.,#208694); +#208694 = SURFACE_SIDE_STYLE('',(#208695)); +#208695 = SURFACE_STYLE_FILL_AREA(#208696); +#208696 = FILL_AREA_STYLE('',(#208697)); +#208697 = FILL_AREA_STYLE_COLOUR('',#208305); +#208698 = OVER_RIDING_STYLED_ITEM('overriding color',(#208699),#29679, + #208276); +#208699 = PRESENTATION_STYLE_ASSIGNMENT((#208700)); +#208700 = SURFACE_STYLE_USAGE(.BOTH.,#208701); +#208701 = SURFACE_SIDE_STYLE('',(#208702)); +#208702 = SURFACE_STYLE_FILL_AREA(#208703); +#208703 = FILL_AREA_STYLE('',(#208704)); +#208704 = FILL_AREA_STYLE_COLOUR('',#197425); +#208705 = OVER_RIDING_STYLED_ITEM('overriding color',(#208706),#29784, + #208276); +#208706 = PRESENTATION_STYLE_ASSIGNMENT((#208707)); +#208707 = SURFACE_STYLE_USAGE(.BOTH.,#208708); +#208708 = SURFACE_SIDE_STYLE('',(#208709)); +#208709 = SURFACE_STYLE_FILL_AREA(#208710); +#208710 = FILL_AREA_STYLE('',(#208711)); +#208711 = FILL_AREA_STYLE_COLOUR('',#197425); +#208712 = OVER_RIDING_STYLED_ITEM('overriding color',(#208713),#29879, + #208276); +#208713 = PRESENTATION_STYLE_ASSIGNMENT((#208714)); +#208714 = SURFACE_STYLE_USAGE(.BOTH.,#208715); +#208715 = SURFACE_SIDE_STYLE('',(#208716)); +#208716 = SURFACE_STYLE_FILL_AREA(#208717); +#208717 = FILL_AREA_STYLE('',(#208718)); +#208718 = FILL_AREA_STYLE_COLOUR('',#197425); +#208719 = OVER_RIDING_STYLED_ITEM('overriding color',(#208720),#29984, + #208276); +#208720 = PRESENTATION_STYLE_ASSIGNMENT((#208721)); +#208721 = SURFACE_STYLE_USAGE(.BOTH.,#208722); +#208722 = SURFACE_SIDE_STYLE('',(#208723)); +#208723 = SURFACE_STYLE_FILL_AREA(#208724); +#208724 = FILL_AREA_STYLE('',(#208725)); +#208725 = FILL_AREA_STYLE_COLOUR('',#197425); +#208726 = OVER_RIDING_STYLED_ITEM('overriding color',(#208727),#30011, + #208276); +#208727 = PRESENTATION_STYLE_ASSIGNMENT((#208728)); +#208728 = SURFACE_STYLE_USAGE(.BOTH.,#208729); +#208729 = SURFACE_SIDE_STYLE('',(#208730)); +#208730 = SURFACE_STYLE_FILL_AREA(#208731); +#208731 = FILL_AREA_STYLE('',(#208732)); +#208732 = FILL_AREA_STYLE_COLOUR('',#197425); +#208733 = OVER_RIDING_STYLED_ITEM('overriding color',(#208734),#30106, + #208276); +#208734 = PRESENTATION_STYLE_ASSIGNMENT((#208735)); +#208735 = SURFACE_STYLE_USAGE(.BOTH.,#208736); +#208736 = SURFACE_SIDE_STYLE('',(#208737)); +#208737 = SURFACE_STYLE_FILL_AREA(#208738); +#208738 = FILL_AREA_STYLE('',(#208739)); +#208739 = FILL_AREA_STYLE_COLOUR('',#197425); +#208740 = OVER_RIDING_STYLED_ITEM('overriding color',(#208741),#30133, + #208276); +#208741 = PRESENTATION_STYLE_ASSIGNMENT((#208742)); +#208742 = SURFACE_STYLE_USAGE(.BOTH.,#208743); +#208743 = SURFACE_SIDE_STYLE('',(#208744)); +#208744 = SURFACE_STYLE_FILL_AREA(#208745); +#208745 = FILL_AREA_STYLE('',(#208746)); +#208746 = FILL_AREA_STYLE_COLOUR('',#197425); +#208747 = OVER_RIDING_STYLED_ITEM('overriding color',(#208748),#30228, + #208276); +#208748 = PRESENTATION_STYLE_ASSIGNMENT((#208749)); +#208749 = SURFACE_STYLE_USAGE(.BOTH.,#208750); +#208750 = SURFACE_SIDE_STYLE('',(#208751)); +#208751 = SURFACE_STYLE_FILL_AREA(#208752); +#208752 = FILL_AREA_STYLE('',(#208753)); +#208753 = FILL_AREA_STYLE_COLOUR('',#197425); +#208754 = OVER_RIDING_STYLED_ITEM('overriding color',(#208755),#30255, + #208276); +#208755 = PRESENTATION_STYLE_ASSIGNMENT((#208756)); +#208756 = SURFACE_STYLE_USAGE(.BOTH.,#208757); +#208757 = SURFACE_SIDE_STYLE('',(#208758)); +#208758 = SURFACE_STYLE_FILL_AREA(#208759); +#208759 = FILL_AREA_STYLE('',(#208760)); +#208760 = FILL_AREA_STYLE_COLOUR('',#197425); +#208761 = OVER_RIDING_STYLED_ITEM('overriding color',(#208762),#30350, + #208276); +#208762 = PRESENTATION_STYLE_ASSIGNMENT((#208763)); +#208763 = SURFACE_STYLE_USAGE(.BOTH.,#208764); +#208764 = SURFACE_SIDE_STYLE('',(#208765)); +#208765 = SURFACE_STYLE_FILL_AREA(#208766); +#208766 = FILL_AREA_STYLE('',(#208767)); +#208767 = FILL_AREA_STYLE_COLOUR('',#197425); +#208768 = OVER_RIDING_STYLED_ITEM('overriding color',(#208769),#30377, + #208276); +#208769 = PRESENTATION_STYLE_ASSIGNMENT((#208770)); +#208770 = SURFACE_STYLE_USAGE(.BOTH.,#208771); +#208771 = SURFACE_SIDE_STYLE('',(#208772)); +#208772 = SURFACE_STYLE_FILL_AREA(#208773); +#208773 = FILL_AREA_STYLE('',(#208774)); +#208774 = FILL_AREA_STYLE_COLOUR('',#208305); +#208775 = OVER_RIDING_STYLED_ITEM('overriding color',(#208776),#30404, + #208276); +#208776 = PRESENTATION_STYLE_ASSIGNMENT((#208777)); +#208777 = SURFACE_STYLE_USAGE(.BOTH.,#208778); +#208778 = SURFACE_SIDE_STYLE('',(#208779)); +#208779 = SURFACE_STYLE_FILL_AREA(#208780); +#208780 = FILL_AREA_STYLE('',(#208781)); +#208781 = FILL_AREA_STYLE_COLOUR('',#208305); +#208782 = OVER_RIDING_STYLED_ITEM('overriding color',(#208783),#30411, + #208276); +#208783 = PRESENTATION_STYLE_ASSIGNMENT((#208784)); +#208784 = SURFACE_STYLE_USAGE(.BOTH.,#208785); +#208785 = SURFACE_SIDE_STYLE('',(#208786)); +#208786 = SURFACE_STYLE_FILL_AREA(#208787); +#208787 = FILL_AREA_STYLE('',(#208788)); +#208788 = FILL_AREA_STYLE_COLOUR('',#208305); +#208789 = OVER_RIDING_STYLED_ITEM('overriding color',(#208790),#30506, + #208276); +#208790 = PRESENTATION_STYLE_ASSIGNMENT((#208791)); +#208791 = SURFACE_STYLE_USAGE(.BOTH.,#208792); +#208792 = SURFACE_SIDE_STYLE('',(#208793)); +#208793 = SURFACE_STYLE_FILL_AREA(#208794); +#208794 = FILL_AREA_STYLE('',(#208795)); +#208795 = FILL_AREA_STYLE_COLOUR('',#208305); +#208796 = OVER_RIDING_STYLED_ITEM('overriding color',(#208797),#30515, + #208276); +#208797 = PRESENTATION_STYLE_ASSIGNMENT((#208798)); +#208798 = SURFACE_STYLE_USAGE(.BOTH.,#208799); +#208799 = SURFACE_SIDE_STYLE('',(#208800)); +#208800 = SURFACE_STYLE_FILL_AREA(#208801); +#208801 = FILL_AREA_STYLE('',(#208802)); +#208802 = FILL_AREA_STYLE_COLOUR('',#208305); +#208803 = OVER_RIDING_STYLED_ITEM('overriding color',(#208804),#30542, + #208276); +#208804 = PRESENTATION_STYLE_ASSIGNMENT((#208805)); +#208805 = SURFACE_STYLE_USAGE(.BOTH.,#208806); +#208806 = SURFACE_SIDE_STYLE('',(#208807)); +#208807 = SURFACE_STYLE_FILL_AREA(#208808); +#208808 = FILL_AREA_STYLE('',(#208809)); +#208809 = FILL_AREA_STYLE_COLOUR('',#208305); +#208810 = OVER_RIDING_STYLED_ITEM('overriding color',(#208811),#30569, + #208276); +#208811 = PRESENTATION_STYLE_ASSIGNMENT((#208812)); +#208812 = SURFACE_STYLE_USAGE(.BOTH.,#208813); +#208813 = SURFACE_SIDE_STYLE('',(#208814)); +#208814 = SURFACE_STYLE_FILL_AREA(#208815); +#208815 = FILL_AREA_STYLE('',(#208816)); +#208816 = FILL_AREA_STYLE_COLOUR('',#208305); +#208817 = OVER_RIDING_STYLED_ITEM('overriding color',(#208818),#30596, + #208276); +#208818 = PRESENTATION_STYLE_ASSIGNMENT((#208819)); +#208819 = SURFACE_STYLE_USAGE(.BOTH.,#208820); +#208820 = SURFACE_SIDE_STYLE('',(#208821)); +#208821 = SURFACE_STYLE_FILL_AREA(#208822); +#208822 = FILL_AREA_STYLE('',(#208823)); +#208823 = FILL_AREA_STYLE_COLOUR('',#208305); +#208824 = OVER_RIDING_STYLED_ITEM('overriding color',(#208825),#30603, + #208276); +#208825 = PRESENTATION_STYLE_ASSIGNMENT((#208826)); +#208826 = SURFACE_STYLE_USAGE(.BOTH.,#208827); +#208827 = SURFACE_SIDE_STYLE('',(#208828)); +#208828 = SURFACE_STYLE_FILL_AREA(#208829); +#208829 = FILL_AREA_STYLE('',(#208830)); +#208830 = FILL_AREA_STYLE_COLOUR('',#197425); +#208831 = OVER_RIDING_STYLED_ITEM('overriding color',(#208832),#30630, + #208276); +#208832 = PRESENTATION_STYLE_ASSIGNMENT((#208833)); +#208833 = SURFACE_STYLE_USAGE(.BOTH.,#208834); +#208834 = SURFACE_SIDE_STYLE('',(#208835)); +#208835 = SURFACE_STYLE_FILL_AREA(#208836); +#208836 = FILL_AREA_STYLE('',(#208837)); +#208837 = FILL_AREA_STYLE_COLOUR('',#197425); +#208838 = OVER_RIDING_STYLED_ITEM('overriding color',(#208839),#30657, + #208276); +#208839 = PRESENTATION_STYLE_ASSIGNMENT((#208840)); +#208840 = SURFACE_STYLE_USAGE(.BOTH.,#208841); +#208841 = SURFACE_SIDE_STYLE('',(#208842)); +#208842 = SURFACE_STYLE_FILL_AREA(#208843); +#208843 = FILL_AREA_STYLE('',(#208844)); +#208844 = FILL_AREA_STYLE_COLOUR('',#197425); +#208845 = OVER_RIDING_STYLED_ITEM('overriding color',(#208846),#30684, + #208276); +#208846 = PRESENTATION_STYLE_ASSIGNMENT((#208847)); +#208847 = SURFACE_STYLE_USAGE(.BOTH.,#208848); +#208848 = SURFACE_SIDE_STYLE('',(#208849)); +#208849 = SURFACE_STYLE_FILL_AREA(#208850); +#208850 = FILL_AREA_STYLE('',(#208851)); +#208851 = FILL_AREA_STYLE_COLOUR('',#197425); +#208852 = OVER_RIDING_STYLED_ITEM('overriding color',(#208853),#30711, + #208276); +#208853 = PRESENTATION_STYLE_ASSIGNMENT((#208854)); +#208854 = SURFACE_STYLE_USAGE(.BOTH.,#208855); +#208855 = SURFACE_SIDE_STYLE('',(#208856)); +#208856 = SURFACE_STYLE_FILL_AREA(#208857); +#208857 = FILL_AREA_STYLE('',(#208858)); +#208858 = FILL_AREA_STYLE_COLOUR('',#197425); +#208859 = OVER_RIDING_STYLED_ITEM('overriding color',(#208860),#30738, + #208276); +#208860 = PRESENTATION_STYLE_ASSIGNMENT((#208861)); +#208861 = SURFACE_STYLE_USAGE(.BOTH.,#208862); +#208862 = SURFACE_SIDE_STYLE('',(#208863)); +#208863 = SURFACE_STYLE_FILL_AREA(#208864); +#208864 = FILL_AREA_STYLE('',(#208865)); +#208865 = FILL_AREA_STYLE_COLOUR('',#197425); +#208866 = OVER_RIDING_STYLED_ITEM('overriding color',(#208867),#30745, + #208276); +#208867 = PRESENTATION_STYLE_ASSIGNMENT((#208868)); +#208868 = SURFACE_STYLE_USAGE(.BOTH.,#208869); +#208869 = SURFACE_SIDE_STYLE('',(#208870)); +#208870 = SURFACE_STYLE_FILL_AREA(#208871); +#208871 = FILL_AREA_STYLE('',(#208872)); +#208872 = FILL_AREA_STYLE_COLOUR('',#197425); +#208873 = OVER_RIDING_STYLED_ITEM('overriding color',(#208874),#30772, + #208276); +#208874 = PRESENTATION_STYLE_ASSIGNMENT((#208875)); +#208875 = SURFACE_STYLE_USAGE(.BOTH.,#208876); +#208876 = SURFACE_SIDE_STYLE('',(#208877)); +#208877 = SURFACE_STYLE_FILL_AREA(#208878); +#208878 = FILL_AREA_STYLE('',(#208879)); +#208879 = FILL_AREA_STYLE_COLOUR('',#197425); +#208880 = OVER_RIDING_STYLED_ITEM('overriding color',(#208881),#30779, + #208276); +#208881 = PRESENTATION_STYLE_ASSIGNMENT((#208882)); +#208882 = SURFACE_STYLE_USAGE(.BOTH.,#208883); +#208883 = SURFACE_SIDE_STYLE('',(#208884)); +#208884 = SURFACE_STYLE_FILL_AREA(#208885); +#208885 = FILL_AREA_STYLE('',(#208886)); +#208886 = FILL_AREA_STYLE_COLOUR('',#197425); +#208887 = OVER_RIDING_STYLED_ITEM('overriding color',(#208888),#30806, + #208276); +#208888 = PRESENTATION_STYLE_ASSIGNMENT((#208889)); +#208889 = SURFACE_STYLE_USAGE(.BOTH.,#208890); +#208890 = SURFACE_SIDE_STYLE('',(#208891)); +#208891 = SURFACE_STYLE_FILL_AREA(#208892); +#208892 = FILL_AREA_STYLE('',(#208893)); +#208893 = FILL_AREA_STYLE_COLOUR('',#197425); +#208894 = OVER_RIDING_STYLED_ITEM('overriding color',(#208895),#30813, + #208276); +#208895 = PRESENTATION_STYLE_ASSIGNMENT((#208896)); +#208896 = SURFACE_STYLE_USAGE(.BOTH.,#208897); +#208897 = SURFACE_SIDE_STYLE('',(#208898)); +#208898 = SURFACE_STYLE_FILL_AREA(#208899); +#208899 = FILL_AREA_STYLE('',(#208900)); +#208900 = FILL_AREA_STYLE_COLOUR('',#197425); +#208901 = OVER_RIDING_STYLED_ITEM('overriding color',(#208902),#30840, + #208276); +#208902 = PRESENTATION_STYLE_ASSIGNMENT((#208903)); +#208903 = SURFACE_STYLE_USAGE(.BOTH.,#208904); +#208904 = SURFACE_SIDE_STYLE('',(#208905)); +#208905 = SURFACE_STYLE_FILL_AREA(#208906); +#208906 = FILL_AREA_STYLE('',(#208907)); +#208907 = FILL_AREA_STYLE_COLOUR('',#197425); +#208908 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #208909,#208917,#208925,#208932,#208939,#208946,#208953,#208960, + #208967,#208974,#208981),#19607); +#208909 = STYLED_ITEM('color',(#208910),#18773); +#208910 = PRESENTATION_STYLE_ASSIGNMENT((#208911)); +#208911 = SURFACE_STYLE_USAGE(.BOTH.,#208912); +#208912 = SURFACE_SIDE_STYLE('',(#208913)); +#208913 = SURFACE_STYLE_FILL_AREA(#208914); +#208914 = FILL_AREA_STYLE('',(#208915)); +#208915 = FILL_AREA_STYLE_COLOUR('',#208916); +#208916 = COLOUR_RGB('',0.188235297799,0.188235297799,0.188235297799); +#208917 = OVER_RIDING_STYLED_ITEM('overriding color',(#208918),#18775, + #208909); +#208918 = PRESENTATION_STYLE_ASSIGNMENT((#208919)); +#208919 = SURFACE_STYLE_USAGE(.BOTH.,#208920); +#208920 = SURFACE_SIDE_STYLE('',(#208921)); +#208921 = SURFACE_STYLE_FILL_AREA(#208922); +#208922 = FILL_AREA_STYLE('',(#208923)); +#208923 = FILL_AREA_STYLE_COLOUR('',#208924); +#208924 = COLOUR_RGB('',0.192156866193,0.192156866193,0.192156866193); +#208925 = OVER_RIDING_STYLED_ITEM('overriding color',(#208926),#19069, + #208909); +#208926 = PRESENTATION_STYLE_ASSIGNMENT((#208927)); +#208927 = SURFACE_STYLE_USAGE(.BOTH.,#208928); +#208928 = SURFACE_SIDE_STYLE('',(#208929)); +#208929 = SURFACE_STYLE_FILL_AREA(#208930); +#208930 = FILL_AREA_STYLE('',(#208931)); +#208931 = FILL_AREA_STYLE_COLOUR('',#208924); +#208932 = OVER_RIDING_STYLED_ITEM('overriding color',(#208933),#19189, + #208909); +#208933 = PRESENTATION_STYLE_ASSIGNMENT((#208934)); +#208934 = SURFACE_STYLE_USAGE(.BOTH.,#208935); +#208935 = SURFACE_SIDE_STYLE('',(#208936)); +#208936 = SURFACE_STYLE_FILL_AREA(#208937); +#208937 = FILL_AREA_STYLE('',(#208938)); +#208938 = FILL_AREA_STYLE_COLOUR('',#208924); +#208939 = OVER_RIDING_STYLED_ITEM('overriding color',(#208940),#19237, + #208909); +#208940 = PRESENTATION_STYLE_ASSIGNMENT((#208941)); +#208941 = SURFACE_STYLE_USAGE(.BOTH.,#208942); +#208942 = SURFACE_SIDE_STYLE('',(#208943)); +#208943 = SURFACE_STYLE_FILL_AREA(#208944); +#208944 = FILL_AREA_STYLE('',(#208945)); +#208945 = FILL_AREA_STYLE_COLOUR('',#208924); +#208946 = OVER_RIDING_STYLED_ITEM('overriding color',(#208947),#19285, + #208909); +#208947 = PRESENTATION_STYLE_ASSIGNMENT((#208948)); +#208948 = SURFACE_STYLE_USAGE(.BOTH.,#208949); +#208949 = SURFACE_SIDE_STYLE('',(#208950)); +#208950 = SURFACE_STYLE_FILL_AREA(#208951); +#208951 = FILL_AREA_STYLE('',(#208952)); +#208952 = FILL_AREA_STYLE_COLOUR('',#208924); +#208953 = OVER_RIDING_STYLED_ITEM('overriding color',(#208954),#19333, + #208909); +#208954 = PRESENTATION_STYLE_ASSIGNMENT((#208955)); +#208955 = SURFACE_STYLE_USAGE(.BOTH.,#208956); +#208956 = SURFACE_SIDE_STYLE('',(#208957)); +#208957 = SURFACE_STYLE_FILL_AREA(#208958); +#208958 = FILL_AREA_STYLE('',(#208959)); +#208959 = FILL_AREA_STYLE_COLOUR('',#208924); +#208960 = OVER_RIDING_STYLED_ITEM('overriding color',(#208961),#19427, + #208909); +#208961 = PRESENTATION_STYLE_ASSIGNMENT((#208962)); +#208962 = SURFACE_STYLE_USAGE(.BOTH.,#208963); +#208963 = SURFACE_SIDE_STYLE('',(#208964)); +#208964 = SURFACE_STYLE_FILL_AREA(#208965); +#208965 = FILL_AREA_STYLE('',(#208966)); +#208966 = FILL_AREA_STYLE_COLOUR('',#208924); +#208967 = OVER_RIDING_STYLED_ITEM('overriding color',(#208968),#19475, + #208909); +#208968 = PRESENTATION_STYLE_ASSIGNMENT((#208969)); +#208969 = SURFACE_STYLE_USAGE(.BOTH.,#208970); +#208970 = SURFACE_SIDE_STYLE('',(#208971)); +#208971 = SURFACE_STYLE_FILL_AREA(#208972); +#208972 = FILL_AREA_STYLE('',(#208973)); +#208973 = FILL_AREA_STYLE_COLOUR('',#208924); +#208974 = OVER_RIDING_STYLED_ITEM('overriding color',(#208975),#19569, + #208909); +#208975 = PRESENTATION_STYLE_ASSIGNMENT((#208976)); +#208976 = SURFACE_STYLE_USAGE(.BOTH.,#208977); +#208977 = SURFACE_SIDE_STYLE('',(#208978)); +#208978 = SURFACE_STYLE_FILL_AREA(#208979); +#208979 = FILL_AREA_STYLE('',(#208980)); +#208980 = FILL_AREA_STYLE_COLOUR('',#208924); +#208981 = OVER_RIDING_STYLED_ITEM('overriding color',(#208982),#19596, + #208909); +#208982 = PRESENTATION_STYLE_ASSIGNMENT((#208983)); +#208983 = SURFACE_STYLE_USAGE(.BOTH.,#208984); +#208984 = SURFACE_SIDE_STYLE('',(#208985)); +#208985 = SURFACE_STYLE_FILL_AREA(#208986); +#208986 = FILL_AREA_STYLE('',(#208987)); +#208987 = FILL_AREA_STYLE_COLOUR('',#208924); +#208988 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #208989,#208996,#209003,#209010,#209017,#209024,#209031,#209038, + #209045,#209052,#209059,#209066,#209073,#209080,#209087,#209094, + #209101,#209108,#209115,#209122,#209129,#209136,#209143,#209150, + #209157,#209164,#209171,#209178,#209185,#209192,#209199,#209206, + #209213,#209220,#209227,#209234,#209241,#209248,#209255,#209262, + #209269,#209276,#209283,#209290,#209297,#209304,#209311,#209318, + #209325,#209332,#209339,#209346,#209353,#209360,#209367,#209374, + #209381,#209388,#209395,#209402,#209409,#209416,#209423,#209430, + #209437,#209444,#209451,#209458,#209465,#209472,#209479,#209486, + #209493,#209500,#209507,#209514,#209521,#209528,#209535,#209542, + #209549,#209556,#209563,#209570,#209577,#209584,#209591,#209598, + #209605,#209612,#209619,#209626,#209633,#209640,#209647,#209654, + #209661,#209668,#209675,#209682,#209689,#209696,#209703,#209710, + #209717,#209724,#209731,#209738),#88283); +#208989 = STYLED_ITEM('color',(#208990),#77936); +#208990 = PRESENTATION_STYLE_ASSIGNMENT((#208991)); +#208991 = SURFACE_STYLE_USAGE(.BOTH.,#208992); +#208992 = SURFACE_SIDE_STYLE('',(#208993)); +#208993 = SURFACE_STYLE_FILL_AREA(#208994); +#208994 = FILL_AREA_STYLE('',(#208995)); +#208995 = FILL_AREA_STYLE_COLOUR('',#197417); +#208996 = OVER_RIDING_STYLED_ITEM('overriding color',(#208997),#77938, + #208989); +#208997 = PRESENTATION_STYLE_ASSIGNMENT((#208998)); +#208998 = SURFACE_STYLE_USAGE(.BOTH.,#208999); +#208999 = SURFACE_SIDE_STYLE('',(#209000)); +#209000 = SURFACE_STYLE_FILL_AREA(#209001); +#209001 = FILL_AREA_STYLE('',(#209002)); +#209002 = FILL_AREA_STYLE_COLOUR('',#197630); +#209003 = OVER_RIDING_STYLED_ITEM('overriding color',(#209004),#78218, + #208989); +#209004 = PRESENTATION_STYLE_ASSIGNMENT((#209005)); +#209005 = SURFACE_STYLE_USAGE(.BOTH.,#209006); +#209006 = SURFACE_SIDE_STYLE('',(#209007)); +#209007 = SURFACE_STYLE_FILL_AREA(#209008); +#209008 = FILL_AREA_STYLE('',(#209009)); +#209009 = FILL_AREA_STYLE_COLOUR('',#197630); +#209010 = OVER_RIDING_STYLED_ITEM('overriding color',(#209011),#78493, + #208989); +#209011 = PRESENTATION_STYLE_ASSIGNMENT((#209012)); +#209012 = SURFACE_STYLE_USAGE(.BOTH.,#209013); +#209013 = SURFACE_SIDE_STYLE('',(#209014)); +#209014 = SURFACE_STYLE_FILL_AREA(#209015); +#209015 = FILL_AREA_STYLE('',(#209016)); +#209016 = FILL_AREA_STYLE_COLOUR('',#197630); +#209017 = OVER_RIDING_STYLED_ITEM('overriding color',(#209018),#78768, + #208989); +#209018 = PRESENTATION_STYLE_ASSIGNMENT((#209019)); +#209019 = SURFACE_STYLE_USAGE(.BOTH.,#209020); +#209020 = SURFACE_SIDE_STYLE('',(#209021)); +#209021 = SURFACE_STYLE_FILL_AREA(#209022); +#209022 = FILL_AREA_STYLE('',(#209023)); +#209023 = FILL_AREA_STYLE_COLOUR('',#197630); +#209024 = OVER_RIDING_STYLED_ITEM('overriding color',(#209025),#79043, + #208989); +#209025 = PRESENTATION_STYLE_ASSIGNMENT((#209026)); +#209026 = SURFACE_STYLE_USAGE(.BOTH.,#209027); +#209027 = SURFACE_SIDE_STYLE('',(#209028)); +#209028 = SURFACE_STYLE_FILL_AREA(#209029); +#209029 = FILL_AREA_STYLE('',(#209030)); +#209030 = FILL_AREA_STYLE_COLOUR('',#197630); +#209031 = OVER_RIDING_STYLED_ITEM('overriding color',(#209032),#79346, + #208989); +#209032 = PRESENTATION_STYLE_ASSIGNMENT((#209033)); +#209033 = SURFACE_STYLE_USAGE(.BOTH.,#209034); +#209034 = SURFACE_SIDE_STYLE('',(#209035)); +#209035 = SURFACE_STYLE_FILL_AREA(#209036); +#209036 = FILL_AREA_STYLE('',(#209037)); +#209037 = FILL_AREA_STYLE_COLOUR('',#197630); +#209038 = OVER_RIDING_STYLED_ITEM('overriding color',(#209039),#79621, + #208989); +#209039 = PRESENTATION_STYLE_ASSIGNMENT((#209040)); +#209040 = SURFACE_STYLE_USAGE(.BOTH.,#209041); +#209041 = SURFACE_SIDE_STYLE('',(#209042)); +#209042 = SURFACE_STYLE_FILL_AREA(#209043); +#209043 = FILL_AREA_STYLE('',(#209044)); +#209044 = FILL_AREA_STYLE_COLOUR('',#197630); +#209045 = OVER_RIDING_STYLED_ITEM('overriding color',(#209046),#79896, + #208989); +#209046 = PRESENTATION_STYLE_ASSIGNMENT((#209047)); +#209047 = SURFACE_STYLE_USAGE(.BOTH.,#209048); +#209048 = SURFACE_SIDE_STYLE('',(#209049)); +#209049 = SURFACE_STYLE_FILL_AREA(#209050); +#209050 = FILL_AREA_STYLE('',(#209051)); +#209051 = FILL_AREA_STYLE_COLOUR('',#197630); +#209052 = OVER_RIDING_STYLED_ITEM('overriding color',(#209053),#80171, + #208989); +#209053 = PRESENTATION_STYLE_ASSIGNMENT((#209054)); +#209054 = SURFACE_STYLE_USAGE(.BOTH.,#209055); +#209055 = SURFACE_SIDE_STYLE('',(#209056)); +#209056 = SURFACE_STYLE_FILL_AREA(#209057); +#209057 = FILL_AREA_STYLE('',(#209058)); +#209058 = FILL_AREA_STYLE_COLOUR('',#197630); +#209059 = OVER_RIDING_STYLED_ITEM('overriding color',(#209060),#80508, + #208989); +#209060 = PRESENTATION_STYLE_ASSIGNMENT((#209061)); +#209061 = SURFACE_STYLE_USAGE(.BOTH.,#209062); +#209062 = SURFACE_SIDE_STYLE('',(#209063)); +#209063 = SURFACE_STYLE_FILL_AREA(#209064); +#209064 = FILL_AREA_STYLE('',(#209065)); +#209065 = FILL_AREA_STYLE_COLOUR('',#197630); +#209066 = OVER_RIDING_STYLED_ITEM('overriding color',(#209067),#80975, + #208989); +#209067 = PRESENTATION_STYLE_ASSIGNMENT((#209068)); +#209068 = SURFACE_STYLE_USAGE(.BOTH.,#209069); +#209069 = SURFACE_SIDE_STYLE('',(#209070)); +#209070 = SURFACE_STYLE_FILL_AREA(#209071); +#209071 = FILL_AREA_STYLE('',(#209072)); +#209072 = FILL_AREA_STYLE_COLOUR('',#197630); +#209073 = OVER_RIDING_STYLED_ITEM('overriding color',(#209074),#81144, + #208989); +#209074 = PRESENTATION_STYLE_ASSIGNMENT((#209075)); +#209075 = SURFACE_STYLE_USAGE(.BOTH.,#209076); +#209076 = SURFACE_SIDE_STYLE('',(#209077)); +#209077 = SURFACE_STYLE_FILL_AREA(#209078); +#209078 = FILL_AREA_STYLE('',(#209079)); +#209079 = FILL_AREA_STYLE_COLOUR('',#197630); +#209080 = OVER_RIDING_STYLED_ITEM('overriding color',(#209081),#81310, + #208989); +#209081 = PRESENTATION_STYLE_ASSIGNMENT((#209082)); +#209082 = SURFACE_STYLE_USAGE(.BOTH.,#209083); +#209083 = SURFACE_SIDE_STYLE('',(#209084)); +#209084 = SURFACE_STYLE_FILL_AREA(#209085); +#209085 = FILL_AREA_STYLE('',(#209086)); +#209086 = FILL_AREA_STYLE_COLOUR('',#197630); +#209087 = OVER_RIDING_STYLED_ITEM('overriding color',(#209088),#81456, + #208989); +#209088 = PRESENTATION_STYLE_ASSIGNMENT((#209089)); +#209089 = SURFACE_STYLE_USAGE(.BOTH.,#209090); +#209090 = SURFACE_SIDE_STYLE('',(#209091)); +#209091 = SURFACE_STYLE_FILL_AREA(#209092); +#209092 = FILL_AREA_STYLE('',(#209093)); +#209093 = FILL_AREA_STYLE_COLOUR('',#197630); +#209094 = OVER_RIDING_STYLED_ITEM('overriding color',(#209095),#81626, + #208989); +#209095 = PRESENTATION_STYLE_ASSIGNMENT((#209096)); +#209096 = SURFACE_STYLE_USAGE(.BOTH.,#209097); +#209097 = SURFACE_SIDE_STYLE('',(#209098)); +#209098 = SURFACE_STYLE_FILL_AREA(#209099); +#209099 = FILL_AREA_STYLE('',(#209100)); +#209100 = FILL_AREA_STYLE_COLOUR('',#197630); +#209101 = OVER_RIDING_STYLED_ITEM('overriding color',(#209102),#81947, + #208989); +#209102 = PRESENTATION_STYLE_ASSIGNMENT((#209103)); +#209103 = SURFACE_STYLE_USAGE(.BOTH.,#209104); +#209104 = SURFACE_SIDE_STYLE('',(#209105)); +#209105 = SURFACE_STYLE_FILL_AREA(#209106); +#209106 = FILL_AREA_STYLE('',(#209107)); +#209107 = FILL_AREA_STYLE_COLOUR('',#197630); +#209108 = OVER_RIDING_STYLED_ITEM('overriding color',(#209109),#82059, + #208989); +#209109 = PRESENTATION_STYLE_ASSIGNMENT((#209110)); +#209110 = SURFACE_STYLE_USAGE(.BOTH.,#209111); +#209111 = SURFACE_SIDE_STYLE('',(#209112)); +#209112 = SURFACE_STYLE_FILL_AREA(#209113); +#209113 = FILL_AREA_STYLE('',(#209114)); +#209114 = FILL_AREA_STYLE_COLOUR('',#197630); +#209115 = OVER_RIDING_STYLED_ITEM('overriding color',(#209116),#82194, + #208989); +#209116 = PRESENTATION_STYLE_ASSIGNMENT((#209117)); +#209117 = SURFACE_STYLE_USAGE(.BOTH.,#209118); +#209118 = SURFACE_SIDE_STYLE('',(#209119)); +#209119 = SURFACE_STYLE_FILL_AREA(#209120); +#209120 = FILL_AREA_STYLE('',(#209121)); +#209121 = FILL_AREA_STYLE_COLOUR('',#197630); +#209122 = OVER_RIDING_STYLED_ITEM('overriding color',(#209123),#82515, + #208989); +#209123 = PRESENTATION_STYLE_ASSIGNMENT((#209124)); +#209124 = SURFACE_STYLE_USAGE(.BOTH.,#209125); +#209125 = SURFACE_SIDE_STYLE('',(#209126)); +#209126 = SURFACE_STYLE_FILL_AREA(#209127); +#209127 = FILL_AREA_STYLE('',(#209128)); +#209128 = FILL_AREA_STYLE_COLOUR('',#197425); +#209129 = OVER_RIDING_STYLED_ITEM('overriding color',(#209130),#82590, + #208989); +#209130 = PRESENTATION_STYLE_ASSIGNMENT((#209131)); +#209131 = SURFACE_STYLE_USAGE(.BOTH.,#209132); +#209132 = SURFACE_SIDE_STYLE('',(#209133)); +#209133 = SURFACE_STYLE_FILL_AREA(#209134); +#209134 = FILL_AREA_STYLE('',(#209135)); +#209135 = FILL_AREA_STYLE_COLOUR('',#197425); +#209136 = OVER_RIDING_STYLED_ITEM('overriding color',(#209137),#82665, + #208989); +#209137 = PRESENTATION_STYLE_ASSIGNMENT((#209138)); +#209138 = SURFACE_STYLE_USAGE(.BOTH.,#209139); +#209139 = SURFACE_SIDE_STYLE('',(#209140)); +#209140 = SURFACE_STYLE_FILL_AREA(#209141); +#209141 = FILL_AREA_STYLE('',(#209142)); +#209142 = FILL_AREA_STYLE_COLOUR('',#197425); +#209143 = OVER_RIDING_STYLED_ITEM('overriding color',(#209144),#82919, + #208989); +#209144 = PRESENTATION_STYLE_ASSIGNMENT((#209145)); +#209145 = SURFACE_STYLE_USAGE(.BOTH.,#209146); +#209146 = SURFACE_SIDE_STYLE('',(#209147)); +#209147 = SURFACE_STYLE_FILL_AREA(#209148); +#209148 = FILL_AREA_STYLE('',(#209149)); +#209149 = FILL_AREA_STYLE_COLOUR('',#197425); +#209150 = OVER_RIDING_STYLED_ITEM('overriding color',(#209151),#83138, + #208989); +#209151 = PRESENTATION_STYLE_ASSIGNMENT((#209152)); +#209152 = SURFACE_STYLE_USAGE(.BOTH.,#209153); +#209153 = SURFACE_SIDE_STYLE('',(#209154)); +#209154 = SURFACE_STYLE_FILL_AREA(#209155); +#209155 = FILL_AREA_STYLE('',(#209156)); +#209156 = FILL_AREA_STYLE_COLOUR('',#197425); +#209157 = OVER_RIDING_STYLED_ITEM('overriding color',(#209158),#83164, + #208989); +#209158 = PRESENTATION_STYLE_ASSIGNMENT((#209159)); +#209159 = SURFACE_STYLE_USAGE(.BOTH.,#209160); +#209160 = SURFACE_SIDE_STYLE('',(#209161)); +#209161 = SURFACE_STYLE_FILL_AREA(#209162); +#209162 = FILL_AREA_STYLE('',(#209163)); +#209163 = FILL_AREA_STYLE_COLOUR('',#197425); +#209164 = OVER_RIDING_STYLED_ITEM('overriding color',(#209165),#83190, + #208989); +#209165 = PRESENTATION_STYLE_ASSIGNMENT((#209166)); +#209166 = SURFACE_STYLE_USAGE(.BOTH.,#209167); +#209167 = SURFACE_SIDE_STYLE('',(#209168)); +#209168 = SURFACE_STYLE_FILL_AREA(#209169); +#209169 = FILL_AREA_STYLE('',(#209170)); +#209170 = FILL_AREA_STYLE_COLOUR('',#197425); +#209171 = OVER_RIDING_STYLED_ITEM('overriding color',(#209172),#83239, + #208989); +#209172 = PRESENTATION_STYLE_ASSIGNMENT((#209173)); +#209173 = SURFACE_STYLE_USAGE(.BOTH.,#209174); +#209174 = SURFACE_SIDE_STYLE('',(#209175)); +#209175 = SURFACE_STYLE_FILL_AREA(#209176); +#209176 = FILL_AREA_STYLE('',(#209177)); +#209177 = FILL_AREA_STYLE_COLOUR('',#197425); +#209178 = OVER_RIDING_STYLED_ITEM('overriding color',(#209179),#83266, + #208989); +#209179 = PRESENTATION_STYLE_ASSIGNMENT((#209180)); +#209180 = SURFACE_STYLE_USAGE(.BOTH.,#209181); +#209181 = SURFACE_SIDE_STYLE('',(#209182)); +#209182 = SURFACE_STYLE_FILL_AREA(#209183); +#209183 = FILL_AREA_STYLE('',(#209184)); +#209184 = FILL_AREA_STYLE_COLOUR('',#197425); +#209185 = OVER_RIDING_STYLED_ITEM('overriding color',(#209186),#83293, + #208989); +#209186 = PRESENTATION_STYLE_ASSIGNMENT((#209187)); +#209187 = SURFACE_STYLE_USAGE(.BOTH.,#209188); +#209188 = SURFACE_SIDE_STYLE('',(#209189)); +#209189 = SURFACE_STYLE_FILL_AREA(#209190); +#209190 = FILL_AREA_STYLE('',(#209191)); +#209191 = FILL_AREA_STYLE_COLOUR('',#197425); +#209192 = OVER_RIDING_STYLED_ITEM('overriding color',(#209193),#83342, + #208989); +#209193 = PRESENTATION_STYLE_ASSIGNMENT((#209194)); +#209194 = SURFACE_STYLE_USAGE(.BOTH.,#209195); +#209195 = SURFACE_SIDE_STYLE('',(#209196)); +#209196 = SURFACE_STYLE_FILL_AREA(#209197); +#209197 = FILL_AREA_STYLE('',(#209198)); +#209198 = FILL_AREA_STYLE_COLOUR('',#197425); +#209199 = OVER_RIDING_STYLED_ITEM('overriding color',(#209200),#83368, + #208989); +#209200 = PRESENTATION_STYLE_ASSIGNMENT((#209201)); +#209201 = SURFACE_STYLE_USAGE(.BOTH.,#209202); +#209202 = SURFACE_SIDE_STYLE('',(#209203)); +#209203 = SURFACE_STYLE_FILL_AREA(#209204); +#209204 = FILL_AREA_STYLE('',(#209205)); +#209205 = FILL_AREA_STYLE_COLOUR('',#197425); +#209206 = OVER_RIDING_STYLED_ITEM('overriding color',(#209207),#83394, + #208989); +#209207 = PRESENTATION_STYLE_ASSIGNMENT((#209208)); +#209208 = SURFACE_STYLE_USAGE(.BOTH.,#209209); +#209209 = SURFACE_SIDE_STYLE('',(#209210)); +#209210 = SURFACE_STYLE_FILL_AREA(#209211); +#209211 = FILL_AREA_STYLE('',(#209212)); +#209212 = FILL_AREA_STYLE_COLOUR('',#197425); +#209213 = OVER_RIDING_STYLED_ITEM('overriding color',(#209214),#83401, + #208989); +#209214 = PRESENTATION_STYLE_ASSIGNMENT((#209215)); +#209215 = SURFACE_STYLE_USAGE(.BOTH.,#209216); +#209216 = SURFACE_SIDE_STYLE('',(#209217)); +#209217 = SURFACE_STYLE_FILL_AREA(#209218); +#209218 = FILL_AREA_STYLE('',(#209219)); +#209219 = FILL_AREA_STYLE_COLOUR('',#197425); +#209220 = OVER_RIDING_STYLED_ITEM('overriding color',(#209221),#83476, + #208989); +#209221 = PRESENTATION_STYLE_ASSIGNMENT((#209222)); +#209222 = SURFACE_STYLE_USAGE(.BOTH.,#209223); +#209223 = SURFACE_SIDE_STYLE('',(#209224)); +#209224 = SURFACE_STYLE_FILL_AREA(#209225); +#209225 = FILL_AREA_STYLE('',(#209226)); +#209226 = FILL_AREA_STYLE_COLOUR('',#197425); +#209227 = OVER_RIDING_STYLED_ITEM('overriding color',(#209228),#83551, + #208989); +#209228 = PRESENTATION_STYLE_ASSIGNMENT((#209229)); +#209229 = SURFACE_STYLE_USAGE(.BOTH.,#209230); +#209230 = SURFACE_SIDE_STYLE('',(#209231)); +#209231 = SURFACE_STYLE_FILL_AREA(#209232); +#209232 = FILL_AREA_STYLE('',(#209233)); +#209233 = FILL_AREA_STYLE_COLOUR('',#197425); +#209234 = OVER_RIDING_STYLED_ITEM('overriding color',(#209235),#83805, + #208989); +#209235 = PRESENTATION_STYLE_ASSIGNMENT((#209236)); +#209236 = SURFACE_STYLE_USAGE(.BOTH.,#209237); +#209237 = SURFACE_SIDE_STYLE('',(#209238)); +#209238 = SURFACE_STYLE_FILL_AREA(#209239); +#209239 = FILL_AREA_STYLE('',(#209240)); +#209240 = FILL_AREA_STYLE_COLOUR('',#197425); +#209241 = OVER_RIDING_STYLED_ITEM('overriding color',(#209242),#84024, + #208989); +#209242 = PRESENTATION_STYLE_ASSIGNMENT((#209243)); +#209243 = SURFACE_STYLE_USAGE(.BOTH.,#209244); +#209244 = SURFACE_SIDE_STYLE('',(#209245)); +#209245 = SURFACE_STYLE_FILL_AREA(#209246); +#209246 = FILL_AREA_STYLE('',(#209247)); +#209247 = FILL_AREA_STYLE_COLOUR('',#197425); +#209248 = OVER_RIDING_STYLED_ITEM('overriding color',(#209249),#84050, + #208989); +#209249 = PRESENTATION_STYLE_ASSIGNMENT((#209250)); +#209250 = SURFACE_STYLE_USAGE(.BOTH.,#209251); +#209251 = SURFACE_SIDE_STYLE('',(#209252)); +#209252 = SURFACE_STYLE_FILL_AREA(#209253); +#209253 = FILL_AREA_STYLE('',(#209254)); +#209254 = FILL_AREA_STYLE_COLOUR('',#197425); +#209255 = OVER_RIDING_STYLED_ITEM('overriding color',(#209256),#84076, + #208989); +#209256 = PRESENTATION_STYLE_ASSIGNMENT((#209257)); +#209257 = SURFACE_STYLE_USAGE(.BOTH.,#209258); +#209258 = SURFACE_SIDE_STYLE('',(#209259)); +#209259 = SURFACE_STYLE_FILL_AREA(#209260); +#209260 = FILL_AREA_STYLE('',(#209261)); +#209261 = FILL_AREA_STYLE_COLOUR('',#197425); +#209262 = OVER_RIDING_STYLED_ITEM('overriding color',(#209263),#84125, + #208989); +#209263 = PRESENTATION_STYLE_ASSIGNMENT((#209264)); +#209264 = SURFACE_STYLE_USAGE(.BOTH.,#209265); +#209265 = SURFACE_SIDE_STYLE('',(#209266)); +#209266 = SURFACE_STYLE_FILL_AREA(#209267); +#209267 = FILL_AREA_STYLE('',(#209268)); +#209268 = FILL_AREA_STYLE_COLOUR('',#197425); +#209269 = OVER_RIDING_STYLED_ITEM('overriding color',(#209270),#84152, + #208989); +#209270 = PRESENTATION_STYLE_ASSIGNMENT((#209271)); +#209271 = SURFACE_STYLE_USAGE(.BOTH.,#209272); +#209272 = SURFACE_SIDE_STYLE('',(#209273)); +#209273 = SURFACE_STYLE_FILL_AREA(#209274); +#209274 = FILL_AREA_STYLE('',(#209275)); +#209275 = FILL_AREA_STYLE_COLOUR('',#197425); +#209276 = OVER_RIDING_STYLED_ITEM('overriding color',(#209277),#84179, + #208989); +#209277 = PRESENTATION_STYLE_ASSIGNMENT((#209278)); +#209278 = SURFACE_STYLE_USAGE(.BOTH.,#209279); +#209279 = SURFACE_SIDE_STYLE('',(#209280)); +#209280 = SURFACE_STYLE_FILL_AREA(#209281); +#209281 = FILL_AREA_STYLE('',(#209282)); +#209282 = FILL_AREA_STYLE_COLOUR('',#197425); +#209283 = OVER_RIDING_STYLED_ITEM('overriding color',(#209284),#84228, + #208989); +#209284 = PRESENTATION_STYLE_ASSIGNMENT((#209285)); +#209285 = SURFACE_STYLE_USAGE(.BOTH.,#209286); +#209286 = SURFACE_SIDE_STYLE('',(#209287)); +#209287 = SURFACE_STYLE_FILL_AREA(#209288); +#209288 = FILL_AREA_STYLE('',(#209289)); +#209289 = FILL_AREA_STYLE_COLOUR('',#197425); +#209290 = OVER_RIDING_STYLED_ITEM('overriding color',(#209291),#84254, + #208989); +#209291 = PRESENTATION_STYLE_ASSIGNMENT((#209292)); +#209292 = SURFACE_STYLE_USAGE(.BOTH.,#209293); +#209293 = SURFACE_SIDE_STYLE('',(#209294)); +#209294 = SURFACE_STYLE_FILL_AREA(#209295); +#209295 = FILL_AREA_STYLE('',(#209296)); +#209296 = FILL_AREA_STYLE_COLOUR('',#197425); +#209297 = OVER_RIDING_STYLED_ITEM('overriding color',(#209298),#84280, + #208989); +#209298 = PRESENTATION_STYLE_ASSIGNMENT((#209299)); +#209299 = SURFACE_STYLE_USAGE(.BOTH.,#209300); +#209300 = SURFACE_SIDE_STYLE('',(#209301)); +#209301 = SURFACE_STYLE_FILL_AREA(#209302); +#209302 = FILL_AREA_STYLE('',(#209303)); +#209303 = FILL_AREA_STYLE_COLOUR('',#197425); +#209304 = OVER_RIDING_STYLED_ITEM('overriding color',(#209305),#84287, + #208989); +#209305 = PRESENTATION_STYLE_ASSIGNMENT((#209306)); +#209306 = SURFACE_STYLE_USAGE(.BOTH.,#209307); +#209307 = SURFACE_SIDE_STYLE('',(#209308)); +#209308 = SURFACE_STYLE_FILL_AREA(#209309); +#209309 = FILL_AREA_STYLE('',(#209310)); +#209310 = FILL_AREA_STYLE_COLOUR('',#197425); +#209311 = OVER_RIDING_STYLED_ITEM('overriding color',(#209312),#84362, + #208989); +#209312 = PRESENTATION_STYLE_ASSIGNMENT((#209313)); +#209313 = SURFACE_STYLE_USAGE(.BOTH.,#209314); +#209314 = SURFACE_SIDE_STYLE('',(#209315)); +#209315 = SURFACE_STYLE_FILL_AREA(#209316); +#209316 = FILL_AREA_STYLE('',(#209317)); +#209317 = FILL_AREA_STYLE_COLOUR('',#197425); +#209318 = OVER_RIDING_STYLED_ITEM('overriding color',(#209319),#84643, + #208989); +#209319 = PRESENTATION_STYLE_ASSIGNMENT((#209320)); +#209320 = SURFACE_STYLE_USAGE(.BOTH.,#209321); +#209321 = SURFACE_SIDE_STYLE('',(#209322)); +#209322 = SURFACE_STYLE_FILL_AREA(#209323); +#209323 = FILL_AREA_STYLE('',(#209324)); +#209324 = FILL_AREA_STYLE_COLOUR('',#197425); +#209325 = OVER_RIDING_STYLED_ITEM('overriding color',(#209326),#84691, + #208989); +#209326 = PRESENTATION_STYLE_ASSIGNMENT((#209327)); +#209327 = SURFACE_STYLE_USAGE(.BOTH.,#209328); +#209328 = SURFACE_SIDE_STYLE('',(#209329)); +#209329 = SURFACE_STYLE_FILL_AREA(#209330); +#209330 = FILL_AREA_STYLE('',(#209331)); +#209331 = FILL_AREA_STYLE_COLOUR('',#197425); +#209332 = OVER_RIDING_STYLED_ITEM('overriding color',(#209333),#84910, + #208989); +#209333 = PRESENTATION_STYLE_ASSIGNMENT((#209334)); +#209334 = SURFACE_STYLE_USAGE(.BOTH.,#209335); +#209335 = SURFACE_SIDE_STYLE('',(#209336)); +#209336 = SURFACE_STYLE_FILL_AREA(#209337); +#209337 = FILL_AREA_STYLE('',(#209338)); +#209338 = FILL_AREA_STYLE_COLOUR('',#197425); +#209339 = OVER_RIDING_STYLED_ITEM('overriding color',(#209340),#84936, + #208989); +#209340 = PRESENTATION_STYLE_ASSIGNMENT((#209341)); +#209341 = SURFACE_STYLE_USAGE(.BOTH.,#209342); +#209342 = SURFACE_SIDE_STYLE('',(#209343)); +#209343 = SURFACE_STYLE_FILL_AREA(#209344); +#209344 = FILL_AREA_STYLE('',(#209345)); +#209345 = FILL_AREA_STYLE_COLOUR('',#197425); +#209346 = OVER_RIDING_STYLED_ITEM('overriding color',(#209347),#84962, + #208989); +#209347 = PRESENTATION_STYLE_ASSIGNMENT((#209348)); +#209348 = SURFACE_STYLE_USAGE(.BOTH.,#209349); +#209349 = SURFACE_SIDE_STYLE('',(#209350)); +#209350 = SURFACE_STYLE_FILL_AREA(#209351); +#209351 = FILL_AREA_STYLE('',(#209352)); +#209352 = FILL_AREA_STYLE_COLOUR('',#197425); +#209353 = OVER_RIDING_STYLED_ITEM('overriding color',(#209354),#85011, + #208989); +#209354 = PRESENTATION_STYLE_ASSIGNMENT((#209355)); +#209355 = SURFACE_STYLE_USAGE(.BOTH.,#209356); +#209356 = SURFACE_SIDE_STYLE('',(#209357)); +#209357 = SURFACE_STYLE_FILL_AREA(#209358); +#209358 = FILL_AREA_STYLE('',(#209359)); +#209359 = FILL_AREA_STYLE_COLOUR('',#197425); +#209360 = OVER_RIDING_STYLED_ITEM('overriding color',(#209361),#85038, + #208989); +#209361 = PRESENTATION_STYLE_ASSIGNMENT((#209362)); +#209362 = SURFACE_STYLE_USAGE(.BOTH.,#209363); +#209363 = SURFACE_SIDE_STYLE('',(#209364)); +#209364 = SURFACE_STYLE_FILL_AREA(#209365); +#209365 = FILL_AREA_STYLE('',(#209366)); +#209366 = FILL_AREA_STYLE_COLOUR('',#197425); +#209367 = OVER_RIDING_STYLED_ITEM('overriding color',(#209368),#85065, + #208989); +#209368 = PRESENTATION_STYLE_ASSIGNMENT((#209369)); +#209369 = SURFACE_STYLE_USAGE(.BOTH.,#209370); +#209370 = SURFACE_SIDE_STYLE('',(#209371)); +#209371 = SURFACE_STYLE_FILL_AREA(#209372); +#209372 = FILL_AREA_STYLE('',(#209373)); +#209373 = FILL_AREA_STYLE_COLOUR('',#197425); +#209374 = OVER_RIDING_STYLED_ITEM('overriding color',(#209375),#85114, + #208989); +#209375 = PRESENTATION_STYLE_ASSIGNMENT((#209376)); +#209376 = SURFACE_STYLE_USAGE(.BOTH.,#209377); +#209377 = SURFACE_SIDE_STYLE('',(#209378)); +#209378 = SURFACE_STYLE_FILL_AREA(#209379); +#209379 = FILL_AREA_STYLE('',(#209380)); +#209380 = FILL_AREA_STYLE_COLOUR('',#197425); +#209381 = OVER_RIDING_STYLED_ITEM('overriding color',(#209382),#85140, + #208989); +#209382 = PRESENTATION_STYLE_ASSIGNMENT((#209383)); +#209383 = SURFACE_STYLE_USAGE(.BOTH.,#209384); +#209384 = SURFACE_SIDE_STYLE('',(#209385)); +#209385 = SURFACE_STYLE_FILL_AREA(#209386); +#209386 = FILL_AREA_STYLE('',(#209387)); +#209387 = FILL_AREA_STYLE_COLOUR('',#197425); +#209388 = OVER_RIDING_STYLED_ITEM('overriding color',(#209389),#85166, + #208989); +#209389 = PRESENTATION_STYLE_ASSIGNMENT((#209390)); +#209390 = SURFACE_STYLE_USAGE(.BOTH.,#209391); +#209391 = SURFACE_SIDE_STYLE('',(#209392)); +#209392 = SURFACE_STYLE_FILL_AREA(#209393); +#209393 = FILL_AREA_STYLE('',(#209394)); +#209394 = FILL_AREA_STYLE_COLOUR('',#197425); +#209395 = OVER_RIDING_STYLED_ITEM('overriding color',(#209396),#85173, + #208989); +#209396 = PRESENTATION_STYLE_ASSIGNMENT((#209397)); +#209397 = SURFACE_STYLE_USAGE(.BOTH.,#209398); +#209398 = SURFACE_SIDE_STYLE('',(#209399)); +#209399 = SURFACE_STYLE_FILL_AREA(#209400); +#209400 = FILL_AREA_STYLE('',(#209401)); +#209401 = FILL_AREA_STYLE_COLOUR('',#197425); +#209402 = OVER_RIDING_STYLED_ITEM('overriding color',(#209403),#85248, + #208989); +#209403 = PRESENTATION_STYLE_ASSIGNMENT((#209404)); +#209404 = SURFACE_STYLE_USAGE(.BOTH.,#209405); +#209405 = SURFACE_SIDE_STYLE('',(#209406)); +#209406 = SURFACE_STYLE_FILL_AREA(#209407); +#209407 = FILL_AREA_STYLE('',(#209408)); +#209408 = FILL_AREA_STYLE_COLOUR('',#197425); +#209409 = OVER_RIDING_STYLED_ITEM('overriding color',(#209410),#85529, + #208989); +#209410 = PRESENTATION_STYLE_ASSIGNMENT((#209411)); +#209411 = SURFACE_STYLE_USAGE(.BOTH.,#209412); +#209412 = SURFACE_SIDE_STYLE('',(#209413)); +#209413 = SURFACE_STYLE_FILL_AREA(#209414); +#209414 = FILL_AREA_STYLE('',(#209415)); +#209415 = FILL_AREA_STYLE_COLOUR('',#197425); +#209416 = OVER_RIDING_STYLED_ITEM('overriding color',(#209417),#85577, + #208989); +#209417 = PRESENTATION_STYLE_ASSIGNMENT((#209418)); +#209418 = SURFACE_STYLE_USAGE(.BOTH.,#209419); +#209419 = SURFACE_SIDE_STYLE('',(#209420)); +#209420 = SURFACE_STYLE_FILL_AREA(#209421); +#209421 = FILL_AREA_STYLE('',(#209422)); +#209422 = FILL_AREA_STYLE_COLOUR('',#197425); +#209423 = OVER_RIDING_STYLED_ITEM('overriding color',(#209424),#85796, + #208989); +#209424 = PRESENTATION_STYLE_ASSIGNMENT((#209425)); +#209425 = SURFACE_STYLE_USAGE(.BOTH.,#209426); +#209426 = SURFACE_SIDE_STYLE('',(#209427)); +#209427 = SURFACE_STYLE_FILL_AREA(#209428); +#209428 = FILL_AREA_STYLE('',(#209429)); +#209429 = FILL_AREA_STYLE_COLOUR('',#197425); +#209430 = OVER_RIDING_STYLED_ITEM('overriding color',(#209431),#85822, + #208989); +#209431 = PRESENTATION_STYLE_ASSIGNMENT((#209432)); +#209432 = SURFACE_STYLE_USAGE(.BOTH.,#209433); +#209433 = SURFACE_SIDE_STYLE('',(#209434)); +#209434 = SURFACE_STYLE_FILL_AREA(#209435); +#209435 = FILL_AREA_STYLE('',(#209436)); +#209436 = FILL_AREA_STYLE_COLOUR('',#197425); +#209437 = OVER_RIDING_STYLED_ITEM('overriding color',(#209438),#85848, + #208989); +#209438 = PRESENTATION_STYLE_ASSIGNMENT((#209439)); +#209439 = SURFACE_STYLE_USAGE(.BOTH.,#209440); +#209440 = SURFACE_SIDE_STYLE('',(#209441)); +#209441 = SURFACE_STYLE_FILL_AREA(#209442); +#209442 = FILL_AREA_STYLE('',(#209443)); +#209443 = FILL_AREA_STYLE_COLOUR('',#197425); +#209444 = OVER_RIDING_STYLED_ITEM('overriding color',(#209445),#85897, + #208989); +#209445 = PRESENTATION_STYLE_ASSIGNMENT((#209446)); +#209446 = SURFACE_STYLE_USAGE(.BOTH.,#209447); +#209447 = SURFACE_SIDE_STYLE('',(#209448)); +#209448 = SURFACE_STYLE_FILL_AREA(#209449); +#209449 = FILL_AREA_STYLE('',(#209450)); +#209450 = FILL_AREA_STYLE_COLOUR('',#197425); +#209451 = OVER_RIDING_STYLED_ITEM('overriding color',(#209452),#85924, + #208989); +#209452 = PRESENTATION_STYLE_ASSIGNMENT((#209453)); +#209453 = SURFACE_STYLE_USAGE(.BOTH.,#209454); +#209454 = SURFACE_SIDE_STYLE('',(#209455)); +#209455 = SURFACE_STYLE_FILL_AREA(#209456); +#209456 = FILL_AREA_STYLE('',(#209457)); +#209457 = FILL_AREA_STYLE_COLOUR('',#197425); +#209458 = OVER_RIDING_STYLED_ITEM('overriding color',(#209459),#85951, + #208989); +#209459 = PRESENTATION_STYLE_ASSIGNMENT((#209460)); +#209460 = SURFACE_STYLE_USAGE(.BOTH.,#209461); +#209461 = SURFACE_SIDE_STYLE('',(#209462)); +#209462 = SURFACE_STYLE_FILL_AREA(#209463); +#209463 = FILL_AREA_STYLE('',(#209464)); +#209464 = FILL_AREA_STYLE_COLOUR('',#197425); +#209465 = OVER_RIDING_STYLED_ITEM('overriding color',(#209466),#86000, + #208989); +#209466 = PRESENTATION_STYLE_ASSIGNMENT((#209467)); +#209467 = SURFACE_STYLE_USAGE(.BOTH.,#209468); +#209468 = SURFACE_SIDE_STYLE('',(#209469)); +#209469 = SURFACE_STYLE_FILL_AREA(#209470); +#209470 = FILL_AREA_STYLE('',(#209471)); +#209471 = FILL_AREA_STYLE_COLOUR('',#197425); +#209472 = OVER_RIDING_STYLED_ITEM('overriding color',(#209473),#86026, + #208989); +#209473 = PRESENTATION_STYLE_ASSIGNMENT((#209474)); +#209474 = SURFACE_STYLE_USAGE(.BOTH.,#209475); +#209475 = SURFACE_SIDE_STYLE('',(#209476)); +#209476 = SURFACE_STYLE_FILL_AREA(#209477); +#209477 = FILL_AREA_STYLE('',(#209478)); +#209478 = FILL_AREA_STYLE_COLOUR('',#197425); +#209479 = OVER_RIDING_STYLED_ITEM('overriding color',(#209480),#86052, + #208989); +#209480 = PRESENTATION_STYLE_ASSIGNMENT((#209481)); +#209481 = SURFACE_STYLE_USAGE(.BOTH.,#209482); +#209482 = SURFACE_SIDE_STYLE('',(#209483)); +#209483 = SURFACE_STYLE_FILL_AREA(#209484); +#209484 = FILL_AREA_STYLE('',(#209485)); +#209485 = FILL_AREA_STYLE_COLOUR('',#197425); +#209486 = OVER_RIDING_STYLED_ITEM('overriding color',(#209487),#86059, + #208989); +#209487 = PRESENTATION_STYLE_ASSIGNMENT((#209488)); +#209488 = SURFACE_STYLE_USAGE(.BOTH.,#209489); +#209489 = SURFACE_SIDE_STYLE('',(#209490)); +#209490 = SURFACE_STYLE_FILL_AREA(#209491); +#209491 = FILL_AREA_STYLE('',(#209492)); +#209492 = FILL_AREA_STYLE_COLOUR('',#197425); +#209493 = OVER_RIDING_STYLED_ITEM('overriding color',(#209494),#86134, + #208989); +#209494 = PRESENTATION_STYLE_ASSIGNMENT((#209495)); +#209495 = SURFACE_STYLE_USAGE(.BOTH.,#209496); +#209496 = SURFACE_SIDE_STYLE('',(#209497)); +#209497 = SURFACE_STYLE_FILL_AREA(#209498); +#209498 = FILL_AREA_STYLE('',(#209499)); +#209499 = FILL_AREA_STYLE_COLOUR('',#197425); +#209500 = OVER_RIDING_STYLED_ITEM('overriding color',(#209501),#86415, + #208989); +#209501 = PRESENTATION_STYLE_ASSIGNMENT((#209502)); +#209502 = SURFACE_STYLE_USAGE(.BOTH.,#209503); +#209503 = SURFACE_SIDE_STYLE('',(#209504)); +#209504 = SURFACE_STYLE_FILL_AREA(#209505); +#209505 = FILL_AREA_STYLE('',(#209506)); +#209506 = FILL_AREA_STYLE_COLOUR('',#197425); +#209507 = OVER_RIDING_STYLED_ITEM('overriding color',(#209508),#86656, + #208989); +#209508 = PRESENTATION_STYLE_ASSIGNMENT((#209509)); +#209509 = SURFACE_STYLE_USAGE(.BOTH.,#209510); +#209510 = SURFACE_SIDE_STYLE('',(#209511)); +#209511 = SURFACE_STYLE_FILL_AREA(#209512); +#209512 = FILL_AREA_STYLE('',(#209513)); +#209513 = FILL_AREA_STYLE_COLOUR('',#197425); +#209514 = OVER_RIDING_STYLED_ITEM('overriding color',(#209515),#86703, + #208989); +#209515 = PRESENTATION_STYLE_ASSIGNMENT((#209516)); +#209516 = SURFACE_STYLE_USAGE(.BOTH.,#209517); +#209517 = SURFACE_SIDE_STYLE('',(#209518)); +#209518 = SURFACE_STYLE_FILL_AREA(#209519); +#209519 = FILL_AREA_STYLE('',(#209520)); +#209520 = FILL_AREA_STYLE_COLOUR('',#197425); +#209521 = OVER_RIDING_STYLED_ITEM('overriding color',(#209522),#86752, + #208989); +#209522 = PRESENTATION_STYLE_ASSIGNMENT((#209523)); +#209523 = SURFACE_STYLE_USAGE(.BOTH.,#209524); +#209524 = SURFACE_SIDE_STYLE('',(#209525)); +#209525 = SURFACE_STYLE_FILL_AREA(#209526); +#209526 = FILL_AREA_STYLE('',(#209527)); +#209527 = FILL_AREA_STYLE_COLOUR('',#197425); +#209528 = OVER_RIDING_STYLED_ITEM('overriding color',(#209529),#86778, + #208989); +#209529 = PRESENTATION_STYLE_ASSIGNMENT((#209530)); +#209530 = SURFACE_STYLE_USAGE(.BOTH.,#209531); +#209531 = SURFACE_SIDE_STYLE('',(#209532)); +#209532 = SURFACE_STYLE_FILL_AREA(#209533); +#209533 = FILL_AREA_STYLE('',(#209534)); +#209534 = FILL_AREA_STYLE_COLOUR('',#197425); +#209535 = OVER_RIDING_STYLED_ITEM('overriding color',(#209536),#86804, + #208989); +#209536 = PRESENTATION_STYLE_ASSIGNMENT((#209537)); +#209537 = SURFACE_STYLE_USAGE(.BOTH.,#209538); +#209538 = SURFACE_SIDE_STYLE('',(#209539)); +#209539 = SURFACE_STYLE_FILL_AREA(#209540); +#209540 = FILL_AREA_STYLE('',(#209541)); +#209541 = FILL_AREA_STYLE_COLOUR('',#197425); +#209542 = OVER_RIDING_STYLED_ITEM('overriding color',(#209543),#86830, + #208989); +#209543 = PRESENTATION_STYLE_ASSIGNMENT((#209544)); +#209544 = SURFACE_STYLE_USAGE(.BOTH.,#209545); +#209545 = SURFACE_SIDE_STYLE('',(#209546)); +#209546 = SURFACE_STYLE_FILL_AREA(#209547); +#209547 = FILL_AREA_STYLE('',(#209548)); +#209548 = FILL_AREA_STYLE_COLOUR('',#197425); +#209549 = OVER_RIDING_STYLED_ITEM('overriding color',(#209550),#86837, + #208989); +#209550 = PRESENTATION_STYLE_ASSIGNMENT((#209551)); +#209551 = SURFACE_STYLE_USAGE(.BOTH.,#209552); +#209552 = SURFACE_SIDE_STYLE('',(#209553)); +#209553 = SURFACE_STYLE_FILL_AREA(#209554); +#209554 = FILL_AREA_STYLE('',(#209555)); +#209555 = FILL_AREA_STYLE_COLOUR('',#197425); +#209556 = OVER_RIDING_STYLED_ITEM('overriding color',(#209557),#86863, + #208989); +#209557 = PRESENTATION_STYLE_ASSIGNMENT((#209558)); +#209558 = SURFACE_STYLE_USAGE(.BOTH.,#209559); +#209559 = SURFACE_SIDE_STYLE('',(#209560)); +#209560 = SURFACE_STYLE_FILL_AREA(#209561); +#209561 = FILL_AREA_STYLE('',(#209562)); +#209562 = FILL_AREA_STYLE_COLOUR('',#197425); +#209563 = OVER_RIDING_STYLED_ITEM('overriding color',(#209564),#86889, + #208989); +#209564 = PRESENTATION_STYLE_ASSIGNMENT((#209565)); +#209565 = SURFACE_STYLE_USAGE(.BOTH.,#209566); +#209566 = SURFACE_SIDE_STYLE('',(#209567)); +#209567 = SURFACE_STYLE_FILL_AREA(#209568); +#209568 = FILL_AREA_STYLE('',(#209569)); +#209569 = FILL_AREA_STYLE_COLOUR('',#197425); +#209570 = OVER_RIDING_STYLED_ITEM('overriding color',(#209571),#86938, + #208989); +#209571 = PRESENTATION_STYLE_ASSIGNMENT((#209572)); +#209572 = SURFACE_STYLE_USAGE(.BOTH.,#209573); +#209573 = SURFACE_SIDE_STYLE('',(#209574)); +#209574 = SURFACE_STYLE_FILL_AREA(#209575); +#209575 = FILL_AREA_STYLE('',(#209576)); +#209576 = FILL_AREA_STYLE_COLOUR('',#197425); +#209577 = OVER_RIDING_STYLED_ITEM('overriding color',(#209578),#86945, + #208989); +#209578 = PRESENTATION_STYLE_ASSIGNMENT((#209579)); +#209579 = SURFACE_STYLE_USAGE(.BOTH.,#209580); +#209580 = SURFACE_SIDE_STYLE('',(#209581)); +#209581 = SURFACE_STYLE_FILL_AREA(#209582); +#209582 = FILL_AREA_STYLE('',(#209583)); +#209583 = FILL_AREA_STYLE_COLOUR('',#197630); +#209584 = OVER_RIDING_STYLED_ITEM('overriding color',(#209585),#87083, + #208989); +#209585 = PRESENTATION_STYLE_ASSIGNMENT((#209586)); +#209586 = SURFACE_STYLE_USAGE(.BOTH.,#209587); +#209587 = SURFACE_SIDE_STYLE('',(#209588)); +#209588 = SURFACE_STYLE_FILL_AREA(#209589); +#209589 = FILL_AREA_STYLE('',(#209590)); +#209590 = FILL_AREA_STYLE_COLOUR('',#197630); +#209591 = OVER_RIDING_STYLED_ITEM('overriding color',(#209592),#87156, + #208989); +#209592 = PRESENTATION_STYLE_ASSIGNMENT((#209593)); +#209593 = SURFACE_STYLE_USAGE(.BOTH.,#209594); +#209594 = SURFACE_SIDE_STYLE('',(#209595)); +#209595 = SURFACE_STYLE_FILL_AREA(#209596); +#209596 = FILL_AREA_STYLE('',(#209597)); +#209597 = FILL_AREA_STYLE_COLOUR('',#197630); +#209598 = OVER_RIDING_STYLED_ITEM('overriding color',(#209599),#87294, + #208989); +#209599 = PRESENTATION_STYLE_ASSIGNMENT((#209600)); +#209600 = SURFACE_STYLE_USAGE(.BOTH.,#209601); +#209601 = SURFACE_SIDE_STYLE('',(#209602)); +#209602 = SURFACE_STYLE_FILL_AREA(#209603); +#209603 = FILL_AREA_STYLE('',(#209604)); +#209604 = FILL_AREA_STYLE_COLOUR('',#197630); +#209605 = OVER_RIDING_STYLED_ITEM('overriding color',(#209606),#87367, + #208989); +#209606 = PRESENTATION_STYLE_ASSIGNMENT((#209607)); +#209607 = SURFACE_STYLE_USAGE(.BOTH.,#209608); +#209608 = SURFACE_SIDE_STYLE('',(#209609)); +#209609 = SURFACE_STYLE_FILL_AREA(#209610); +#209610 = FILL_AREA_STYLE('',(#209611)); +#209611 = FILL_AREA_STYLE_COLOUR('',#197630); +#209612 = OVER_RIDING_STYLED_ITEM('overriding color',(#209613),#87505, + #208989); +#209613 = PRESENTATION_STYLE_ASSIGNMENT((#209614)); +#209614 = SURFACE_STYLE_USAGE(.BOTH.,#209615); +#209615 = SURFACE_SIDE_STYLE('',(#209616)); +#209616 = SURFACE_STYLE_FILL_AREA(#209617); +#209617 = FILL_AREA_STYLE('',(#209618)); +#209618 = FILL_AREA_STYLE_COLOUR('',#197630); +#209619 = OVER_RIDING_STYLED_ITEM('overriding color',(#209620),#87578, + #208989); +#209620 = PRESENTATION_STYLE_ASSIGNMENT((#209621)); +#209621 = SURFACE_STYLE_USAGE(.BOTH.,#209622); +#209622 = SURFACE_SIDE_STYLE('',(#209623)); +#209623 = SURFACE_STYLE_FILL_AREA(#209624); +#209624 = FILL_AREA_STYLE('',(#209625)); +#209625 = FILL_AREA_STYLE_COLOUR('',#197630); +#209626 = OVER_RIDING_STYLED_ITEM('overriding color',(#209627),#87716, + #208989); +#209627 = PRESENTATION_STYLE_ASSIGNMENT((#209628)); +#209628 = SURFACE_STYLE_USAGE(.BOTH.,#209629); +#209629 = SURFACE_SIDE_STYLE('',(#209630)); +#209630 = SURFACE_STYLE_FILL_AREA(#209631); +#209631 = FILL_AREA_STYLE('',(#209632)); +#209632 = FILL_AREA_STYLE_COLOUR('',#197630); +#209633 = OVER_RIDING_STYLED_ITEM('overriding color',(#209634),#87789, + #208989); +#209634 = PRESENTATION_STYLE_ASSIGNMENT((#209635)); +#209635 = SURFACE_STYLE_USAGE(.BOTH.,#209636); +#209636 = SURFACE_SIDE_STYLE('',(#209637)); +#209637 = SURFACE_STYLE_FILL_AREA(#209638); +#209638 = FILL_AREA_STYLE('',(#209639)); +#209639 = FILL_AREA_STYLE_COLOUR('',#197630); +#209640 = OVER_RIDING_STYLED_ITEM('overriding color',(#209641),#87838, + #208989); +#209641 = PRESENTATION_STYLE_ASSIGNMENT((#209642)); +#209642 = SURFACE_STYLE_USAGE(.BOTH.,#209643); +#209643 = SURFACE_SIDE_STYLE('',(#209644)); +#209644 = SURFACE_STYLE_FILL_AREA(#209645); +#209645 = FILL_AREA_STYLE('',(#209646)); +#209646 = FILL_AREA_STYLE_COLOUR('',#197630); +#209647 = OVER_RIDING_STYLED_ITEM('overriding color',(#209648),#87845, + #208989); +#209648 = PRESENTATION_STYLE_ASSIGNMENT((#209649)); +#209649 = SURFACE_STYLE_USAGE(.BOTH.,#209650); +#209650 = SURFACE_SIDE_STYLE('',(#209651)); +#209651 = SURFACE_STYLE_FILL_AREA(#209652); +#209652 = FILL_AREA_STYLE('',(#209653)); +#209653 = FILL_AREA_STYLE_COLOUR('',#197630); +#209654 = OVER_RIDING_STYLED_ITEM('overriding color',(#209655),#87894, + #208989); +#209655 = PRESENTATION_STYLE_ASSIGNMENT((#209656)); +#209656 = SURFACE_STYLE_USAGE(.BOTH.,#209657); +#209657 = SURFACE_SIDE_STYLE('',(#209658)); +#209658 = SURFACE_STYLE_FILL_AREA(#209659); +#209659 = FILL_AREA_STYLE('',(#209660)); +#209660 = FILL_AREA_STYLE_COLOUR('',#197630); +#209661 = OVER_RIDING_STYLED_ITEM('overriding color',(#209662),#87943, + #208989); +#209662 = PRESENTATION_STYLE_ASSIGNMENT((#209663)); +#209663 = SURFACE_STYLE_USAGE(.BOTH.,#209664); +#209664 = SURFACE_SIDE_STYLE('',(#209665)); +#209665 = SURFACE_STYLE_FILL_AREA(#209666); +#209666 = FILL_AREA_STYLE('',(#209667)); +#209667 = FILL_AREA_STYLE_COLOUR('',#197630); +#209668 = OVER_RIDING_STYLED_ITEM('overriding color',(#209669),#87950, + #208989); +#209669 = PRESENTATION_STYLE_ASSIGNMENT((#209670)); +#209670 = SURFACE_STYLE_USAGE(.BOTH.,#209671); +#209671 = SURFACE_SIDE_STYLE('',(#209672)); +#209672 = SURFACE_STYLE_FILL_AREA(#209673); +#209673 = FILL_AREA_STYLE('',(#209674)); +#209674 = FILL_AREA_STYLE_COLOUR('',#197630); +#209675 = OVER_RIDING_STYLED_ITEM('overriding color',(#209676),#87957, + #208989); +#209676 = PRESENTATION_STYLE_ASSIGNMENT((#209677)); +#209677 = SURFACE_STYLE_USAGE(.BOTH.,#209678); +#209678 = SURFACE_SIDE_STYLE('',(#209679)); +#209679 = SURFACE_STYLE_FILL_AREA(#209680); +#209680 = FILL_AREA_STYLE('',(#209681)); +#209681 = FILL_AREA_STYLE_COLOUR('',#197630); +#209682 = OVER_RIDING_STYLED_ITEM('overriding color',(#209683),#88006, + #208989); +#209683 = PRESENTATION_STYLE_ASSIGNMENT((#209684)); +#209684 = SURFACE_STYLE_USAGE(.BOTH.,#209685); +#209685 = SURFACE_SIDE_STYLE('',(#209686)); +#209686 = SURFACE_STYLE_FILL_AREA(#209687); +#209687 = FILL_AREA_STYLE('',(#209688)); +#209688 = FILL_AREA_STYLE_COLOUR('',#197630); +#209689 = OVER_RIDING_STYLED_ITEM('overriding color',(#209690),#88013, + #208989); +#209690 = PRESENTATION_STYLE_ASSIGNMENT((#209691)); +#209691 = SURFACE_STYLE_USAGE(.BOTH.,#209692); +#209692 = SURFACE_SIDE_STYLE('',(#209693)); +#209693 = SURFACE_STYLE_FILL_AREA(#209694); +#209694 = FILL_AREA_STYLE('',(#209695)); +#209695 = FILL_AREA_STYLE_COLOUR('',#197630); +#209696 = OVER_RIDING_STYLED_ITEM('overriding color',(#209697),#88062, + #208989); +#209697 = PRESENTATION_STYLE_ASSIGNMENT((#209698)); +#209698 = SURFACE_STYLE_USAGE(.BOTH.,#209699); +#209699 = SURFACE_SIDE_STYLE('',(#209700)); +#209700 = SURFACE_STYLE_FILL_AREA(#209701); +#209701 = FILL_AREA_STYLE('',(#209702)); +#209702 = FILL_AREA_STYLE_COLOUR('',#197630); +#209703 = OVER_RIDING_STYLED_ITEM('overriding color',(#209704),#88134, + #208989); +#209704 = PRESENTATION_STYLE_ASSIGNMENT((#209705)); +#209705 = SURFACE_STYLE_USAGE(.BOTH.,#209706); +#209706 = SURFACE_SIDE_STYLE('',(#209707)); +#209707 = SURFACE_STYLE_FILL_AREA(#209708); +#209708 = FILL_AREA_STYLE('',(#209709)); +#209709 = FILL_AREA_STYLE_COLOUR('',#197630); +#209710 = OVER_RIDING_STYLED_ITEM('overriding color',(#209711),#88141, + #208989); +#209711 = PRESENTATION_STYLE_ASSIGNMENT((#209712)); +#209712 = SURFACE_STYLE_USAGE(.BOTH.,#209713); +#209713 = SURFACE_SIDE_STYLE('',(#209714)); +#209714 = SURFACE_STYLE_FILL_AREA(#209715); +#209715 = FILL_AREA_STYLE('',(#209716)); +#209716 = FILL_AREA_STYLE_COLOUR('',#197630); +#209717 = OVER_RIDING_STYLED_ITEM('overriding color',(#209718),#88148, + #208989); +#209718 = PRESENTATION_STYLE_ASSIGNMENT((#209719)); +#209719 = SURFACE_STYLE_USAGE(.BOTH.,#209720); +#209720 = SURFACE_SIDE_STYLE('',(#209721)); +#209721 = SURFACE_STYLE_FILL_AREA(#209722); +#209722 = FILL_AREA_STYLE('',(#209723)); +#209723 = FILL_AREA_STYLE_COLOUR('',#197630); +#209724 = OVER_RIDING_STYLED_ITEM('overriding color',(#209725),#88197, + #208989); +#209725 = PRESENTATION_STYLE_ASSIGNMENT((#209726)); +#209726 = SURFACE_STYLE_USAGE(.BOTH.,#209727); +#209727 = SURFACE_SIDE_STYLE('',(#209728)); +#209728 = SURFACE_STYLE_FILL_AREA(#209729); +#209729 = FILL_AREA_STYLE('',(#209730)); +#209730 = FILL_AREA_STYLE_COLOUR('',#197630); +#209731 = OVER_RIDING_STYLED_ITEM('overriding color',(#209732),#88269, + #208989); +#209732 = PRESENTATION_STYLE_ASSIGNMENT((#209733)); +#209733 = SURFACE_STYLE_USAGE(.BOTH.,#209734); +#209734 = SURFACE_SIDE_STYLE('',(#209735)); +#209735 = SURFACE_STYLE_FILL_AREA(#209736); +#209736 = FILL_AREA_STYLE('',(#209737)); +#209737 = FILL_AREA_STYLE_COLOUR('',#197630); +#209738 = OVER_RIDING_STYLED_ITEM('overriding color',(#209739),#88276, + #208989); +#209739 = PRESENTATION_STYLE_ASSIGNMENT((#209740)); +#209740 = SURFACE_STYLE_USAGE(.BOTH.,#209741); +#209741 = SURFACE_SIDE_STYLE('',(#209742)); +#209742 = SURFACE_STYLE_FILL_AREA(#209743); +#209743 = FILL_AREA_STYLE('',(#209744)); +#209744 = FILL_AREA_STYLE_COLOUR('',#197630); +#209745 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #209746),#14214); +#209746 = STYLED_ITEM('color',(#209747),#13884); +#209747 = PRESENTATION_STYLE_ASSIGNMENT((#209748,#209753)); +#209748 = SURFACE_STYLE_USAGE(.BOTH.,#209749); +#209749 = SURFACE_SIDE_STYLE('',(#209750)); +#209750 = SURFACE_STYLE_FILL_AREA(#209751); +#209751 = FILL_AREA_STYLE('',(#209752)); +#209752 = FILL_AREA_STYLE_COLOUR('',#207315); +#209753 = CURVE_STYLE('',#209754,POSITIVE_LENGTH_MEASURE(0.1),#207315); +#209754 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#209755 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #209756),#88672); +#209756 = STYLED_ITEM('color',(#209757),#88342); +#209757 = PRESENTATION_STYLE_ASSIGNMENT((#209758,#209763)); +#209758 = SURFACE_STYLE_USAGE(.BOTH.,#209759); +#209759 = SURFACE_SIDE_STYLE('',(#209760)); +#209760 = SURFACE_STYLE_FILL_AREA(#209761); +#209761 = FILL_AREA_STYLE('',(#209762)); +#209762 = FILL_AREA_STYLE_COLOUR('',#197440); +#209763 = CURVE_STYLE('',#209764,POSITIVE_LENGTH_MEASURE(0.1),#197440); +#209764 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#209765 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #209766),#197379); +#209766 = STYLED_ITEM('color',(#209767),#197049); +#209767 = PRESENTATION_STYLE_ASSIGNMENT((#209768,#209774)); +#209768 = SURFACE_STYLE_USAGE(.BOTH.,#209769); +#209769 = SURFACE_SIDE_STYLE('',(#209770)); +#209770 = SURFACE_STYLE_FILL_AREA(#209771); +#209771 = FILL_AREA_STYLE('',(#209772)); +#209772 = FILL_AREA_STYLE_COLOUR('',#209773); +#209773 = COLOUR_RGB('',0.713725507259,0.603921592236,0.415686279535); +#209774 = CURVE_STYLE('',#209775,POSITIVE_LENGTH_MEASURE(0.1),#209773); +#209775 = DRAUGHTING_PRE_DEFINED_CURVE_FONT('continuous'); +#209776 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #209777,#209784,#209792,#209799,#209806,#209813,#209820,#209827, + #209834,#209841,#209848,#209855,#209862,#209869,#209876,#209883, + #209890,#209897,#209904,#209911,#209918,#209925,#209932,#209939, + #209946,#209953),#161081); +#209777 = STYLED_ITEM('color',(#209778),#159099); +#209778 = PRESENTATION_STYLE_ASSIGNMENT((#209779)); +#209779 = SURFACE_STYLE_USAGE(.BOTH.,#209780); +#209780 = SURFACE_SIDE_STYLE('',(#209781)); +#209781 = SURFACE_STYLE_FILL_AREA(#209782); +#209782 = FILL_AREA_STYLE('',(#209783)); +#209783 = FILL_AREA_STYLE_COLOUR('',#208924); +#209784 = OVER_RIDING_STYLED_ITEM('overriding color',(#209785),#159101, + #209777); +#209785 = PRESENTATION_STYLE_ASSIGNMENT((#209786)); +#209786 = SURFACE_STYLE_USAGE(.BOTH.,#209787); +#209787 = SURFACE_SIDE_STYLE('',(#209788)); +#209788 = SURFACE_STYLE_FILL_AREA(#209789); +#209789 = FILL_AREA_STYLE('',(#209790)); +#209790 = FILL_AREA_STYLE_COLOUR('',#209791); +#209791 = COLOUR_RGB('',0.196078434587,0.196078434587,0.196078434587); +#209792 = OVER_RIDING_STYLED_ITEM('overriding color',(#209793),#159393, + #209777); +#209793 = PRESENTATION_STYLE_ASSIGNMENT((#209794)); +#209794 = SURFACE_STYLE_USAGE(.BOTH.,#209795); +#209795 = SURFACE_SIDE_STYLE('',(#209796)); +#209796 = SURFACE_STYLE_FILL_AREA(#209797); +#209797 = FILL_AREA_STYLE('',(#209798)); +#209798 = FILL_AREA_STYLE_COLOUR('',#209791); +#209799 = OVER_RIDING_STYLED_ITEM('overriding color',(#209800),#159484, + #209777); +#209800 = PRESENTATION_STYLE_ASSIGNMENT((#209801)); +#209801 = SURFACE_STYLE_USAGE(.BOTH.,#209802); +#209802 = SURFACE_SIDE_STYLE('',(#209803)); +#209803 = SURFACE_STYLE_FILL_AREA(#209804); +#209804 = FILL_AREA_STYLE('',(#209805)); +#209805 = FILL_AREA_STYLE_COLOUR('',#209791); +#209806 = OVER_RIDING_STYLED_ITEM('overriding color',(#209807),#159538, + #209777); +#209807 = PRESENTATION_STYLE_ASSIGNMENT((#209808)); +#209808 = SURFACE_STYLE_USAGE(.BOTH.,#209809); +#209809 = SURFACE_SIDE_STYLE('',(#209810)); +#209810 = SURFACE_STYLE_FILL_AREA(#209811); +#209811 = FILL_AREA_STYLE('',(#209812)); +#209812 = FILL_AREA_STYLE_COLOUR('',#209791); +#209813 = OVER_RIDING_STYLED_ITEM('overriding color',(#209814),#159654, + #209777); +#209814 = PRESENTATION_STYLE_ASSIGNMENT((#209815)); +#209815 = SURFACE_STYLE_USAGE(.BOTH.,#209816); +#209816 = SURFACE_SIDE_STYLE('',(#209817)); +#209817 = SURFACE_STYLE_FILL_AREA(#209818); +#209818 = FILL_AREA_STYLE('',(#209819)); +#209819 = FILL_AREA_STYLE_COLOUR('',#209791); +#209820 = OVER_RIDING_STYLED_ITEM('overriding color',(#209821),#159834, + #209777); +#209821 = PRESENTATION_STYLE_ASSIGNMENT((#209822)); +#209822 = SURFACE_STYLE_USAGE(.BOTH.,#209823); +#209823 = SURFACE_SIDE_STYLE('',(#209824)); +#209824 = SURFACE_STYLE_FILL_AREA(#209825); +#209825 = FILL_AREA_STYLE('',(#209826)); +#209826 = FILL_AREA_STYLE_COLOUR('',#209791); +#209827 = OVER_RIDING_STYLED_ITEM('overriding color',(#209828),#159927, + #209777); +#209828 = PRESENTATION_STYLE_ASSIGNMENT((#209829)); +#209829 = SURFACE_STYLE_USAGE(.BOTH.,#209830); +#209830 = SURFACE_SIDE_STYLE('',(#209831)); +#209831 = SURFACE_STYLE_FILL_AREA(#209832); +#209832 = FILL_AREA_STYLE('',(#209833)); +#209833 = FILL_AREA_STYLE_COLOUR('',#209791); +#209834 = OVER_RIDING_STYLED_ITEM('overriding color',(#209835),#160025, + #209777); +#209835 = PRESENTATION_STYLE_ASSIGNMENT((#209836)); +#209836 = SURFACE_STYLE_USAGE(.BOTH.,#209837); +#209837 = SURFACE_SIDE_STYLE('',(#209838)); +#209838 = SURFACE_STYLE_FILL_AREA(#209839); +#209839 = FILL_AREA_STYLE('',(#209840)); +#209840 = FILL_AREA_STYLE_COLOUR('',#209791); +#209841 = OVER_RIDING_STYLED_ITEM('overriding color',(#209842),#160051, + #209777); +#209842 = PRESENTATION_STYLE_ASSIGNMENT((#209843)); +#209843 = SURFACE_STYLE_USAGE(.BOTH.,#209844); +#209844 = SURFACE_SIDE_STYLE('',(#209845)); +#209845 = SURFACE_STYLE_FILL_AREA(#209846); +#209846 = FILL_AREA_STYLE('',(#209847)); +#209847 = FILL_AREA_STYLE_COLOUR('',#209791); +#209848 = OVER_RIDING_STYLED_ITEM('overriding color',(#209849),#160127, + #209777); +#209849 = PRESENTATION_STYLE_ASSIGNMENT((#209850)); +#209850 = SURFACE_STYLE_USAGE(.BOTH.,#209851); +#209851 = SURFACE_SIDE_STYLE('',(#209852)); +#209852 = SURFACE_STYLE_FILL_AREA(#209853); +#209853 = FILL_AREA_STYLE('',(#209854)); +#209854 = FILL_AREA_STYLE_COLOUR('',#209791); +#209855 = OVER_RIDING_STYLED_ITEM('overriding color',(#209856),#160182, + #209777); +#209856 = PRESENTATION_STYLE_ASSIGNMENT((#209857)); +#209857 = SURFACE_STYLE_USAGE(.BOTH.,#209858); +#209858 = SURFACE_SIDE_STYLE('',(#209859)); +#209859 = SURFACE_STYLE_FILL_AREA(#209860); +#209860 = FILL_AREA_STYLE('',(#209861)); +#209861 = FILL_AREA_STYLE_COLOUR('',#209791); +#209862 = OVER_RIDING_STYLED_ITEM('overriding color',(#209863),#160236, + #209777); +#209863 = PRESENTATION_STYLE_ASSIGNMENT((#209864)); +#209864 = SURFACE_STYLE_USAGE(.BOTH.,#209865); +#209865 = SURFACE_SIDE_STYLE('',(#209866)); +#209866 = SURFACE_STYLE_FILL_AREA(#209867); +#209867 = FILL_AREA_STYLE('',(#209868)); +#209868 = FILL_AREA_STYLE_COLOUR('',#209791); +#209869 = OVER_RIDING_STYLED_ITEM('overriding color',(#209870),#160269, + #209777); +#209870 = PRESENTATION_STYLE_ASSIGNMENT((#209871)); +#209871 = SURFACE_STYLE_USAGE(.BOTH.,#209872); +#209872 = SURFACE_SIDE_STYLE('',(#209873)); +#209873 = SURFACE_STYLE_FILL_AREA(#209874); +#209874 = FILL_AREA_STYLE('',(#209875)); +#209875 = FILL_AREA_STYLE_COLOUR('',#209791); +#209876 = OVER_RIDING_STYLED_ITEM('overriding color',(#209877),#160345, + #209777); +#209877 = PRESENTATION_STYLE_ASSIGNMENT((#209878)); +#209878 = SURFACE_STYLE_USAGE(.BOTH.,#209879); +#209879 = SURFACE_SIDE_STYLE('',(#209880)); +#209880 = SURFACE_STYLE_FILL_AREA(#209881); +#209881 = FILL_AREA_STYLE('',(#209882)); +#209882 = FILL_AREA_STYLE_COLOUR('',#209791); +#209883 = OVER_RIDING_STYLED_ITEM('overriding color',(#209884),#160399, + #209777); +#209884 = PRESENTATION_STYLE_ASSIGNMENT((#209885)); +#209885 = SURFACE_STYLE_USAGE(.BOTH.,#209886); +#209886 = SURFACE_SIDE_STYLE('',(#209887)); +#209887 = SURFACE_STYLE_FILL_AREA(#209888); +#209888 = FILL_AREA_STYLE('',(#209889)); +#209889 = FILL_AREA_STYLE_COLOUR('',#209791); +#209890 = OVER_RIDING_STYLED_ITEM('overriding color',(#209891),#160453, + #209777); +#209891 = PRESENTATION_STYLE_ASSIGNMENT((#209892)); +#209892 = SURFACE_STYLE_USAGE(.BOTH.,#209893); +#209893 = SURFACE_SIDE_STYLE('',(#209894)); +#209894 = SURFACE_STYLE_FILL_AREA(#209895); +#209895 = FILL_AREA_STYLE('',(#209896)); +#209896 = FILL_AREA_STYLE_COLOUR('',#209791); +#209897 = OVER_RIDING_STYLED_ITEM('overriding color',(#209898),#160485, + #209777); +#209898 = PRESENTATION_STYLE_ASSIGNMENT((#209899)); +#209899 = SURFACE_STYLE_USAGE(.BOTH.,#209900); +#209900 = SURFACE_SIDE_STYLE('',(#209901)); +#209901 = SURFACE_STYLE_FILL_AREA(#209902); +#209902 = FILL_AREA_STYLE('',(#209903)); +#209903 = FILL_AREA_STYLE_COLOUR('',#209791); +#209904 = OVER_RIDING_STYLED_ITEM('overriding color',(#209905),#160560, + #209777); +#209905 = PRESENTATION_STYLE_ASSIGNMENT((#209906)); +#209906 = SURFACE_STYLE_USAGE(.BOTH.,#209907); +#209907 = SURFACE_SIDE_STYLE('',(#209908)); +#209908 = SURFACE_STYLE_FILL_AREA(#209909); +#209909 = FILL_AREA_STYLE('',(#209910)); +#209910 = FILL_AREA_STYLE_COLOUR('',#209791); +#209911 = OVER_RIDING_STYLED_ITEM('overriding color',(#209912),#160613, + #209777); +#209912 = PRESENTATION_STYLE_ASSIGNMENT((#209913)); +#209913 = SURFACE_STYLE_USAGE(.BOTH.,#209914); +#209914 = SURFACE_SIDE_STYLE('',(#209915)); +#209915 = SURFACE_STYLE_FILL_AREA(#209916); +#209916 = FILL_AREA_STYLE('',(#209917)); +#209917 = FILL_AREA_STYLE_COLOUR('',#209791); +#209918 = OVER_RIDING_STYLED_ITEM('overriding color',(#209919),#160666, + #209777); +#209919 = PRESENTATION_STYLE_ASSIGNMENT((#209920)); +#209920 = SURFACE_STYLE_USAGE(.BOTH.,#209921); +#209921 = SURFACE_SIDE_STYLE('',(#209922)); +#209922 = SURFACE_STYLE_FILL_AREA(#209923); +#209923 = FILL_AREA_STYLE('',(#209924)); +#209924 = FILL_AREA_STYLE_COLOUR('',#209791); +#209925 = OVER_RIDING_STYLED_ITEM('overriding color',(#209926),#160697, + #209777); +#209926 = PRESENTATION_STYLE_ASSIGNMENT((#209927)); +#209927 = SURFACE_STYLE_USAGE(.BOTH.,#209928); +#209928 = SURFACE_SIDE_STYLE('',(#209929)); +#209929 = SURFACE_STYLE_FILL_AREA(#209930); +#209930 = FILL_AREA_STYLE('',(#209931)); +#209931 = FILL_AREA_STYLE_COLOUR('',#209791); +#209932 = OVER_RIDING_STYLED_ITEM('overriding color',(#209933),#160862, + #209777); +#209933 = PRESENTATION_STYLE_ASSIGNMENT((#209934)); +#209934 = SURFACE_STYLE_USAGE(.BOTH.,#209935); +#209935 = SURFACE_SIDE_STYLE('',(#209936)); +#209936 = SURFACE_STYLE_FILL_AREA(#209937); +#209937 = FILL_AREA_STYLE('',(#209938)); +#209938 = FILL_AREA_STYLE_COLOUR('',#209791); +#209939 = OVER_RIDING_STYLED_ITEM('overriding color',(#209940),#160955, + #209777); +#209940 = PRESENTATION_STYLE_ASSIGNMENT((#209941)); +#209941 = SURFACE_STYLE_USAGE(.BOTH.,#209942); +#209942 = SURFACE_SIDE_STYLE('',(#209943)); +#209943 = SURFACE_STYLE_FILL_AREA(#209944); +#209944 = FILL_AREA_STYLE('',(#209945)); +#209945 = FILL_AREA_STYLE_COLOUR('',#209791); +#209946 = OVER_RIDING_STYLED_ITEM('overriding color',(#209947),#161048, + #209777); +#209947 = PRESENTATION_STYLE_ASSIGNMENT((#209948)); +#209948 = SURFACE_STYLE_USAGE(.BOTH.,#209949); +#209949 = SURFACE_SIDE_STYLE('',(#209950)); +#209950 = SURFACE_STYLE_FILL_AREA(#209951); +#209951 = FILL_AREA_STYLE('',(#209952)); +#209952 = FILL_AREA_STYLE_COLOUR('',#209791); +#209953 = OVER_RIDING_STYLED_ITEM('overriding color',(#209954),#161074, + #209777); +#209954 = PRESENTATION_STYLE_ASSIGNMENT((#209955)); +#209955 = SURFACE_STYLE_USAGE(.BOTH.,#209956); +#209956 = SURFACE_SIDE_STYLE('',(#209957)); +#209957 = SURFACE_STYLE_FILL_AREA(#209958); +#209958 = FILL_AREA_STYLE('',(#209959)); +#209959 = FILL_AREA_STYLE_COLOUR('',#209791); +#209960 = MECHANICAL_DESIGN_GEOMETRIC_PRESENTATION_REPRESENTATION('',( + #209961,#209968,#209975,#209982,#209989,#209996,#210003,#210010, + #210017),#159036); +#209961 = STYLED_ITEM('color',(#209962),#153634); +#209962 = PRESENTATION_STYLE_ASSIGNMENT((#209963)); +#209963 = SURFACE_STYLE_USAGE(.BOTH.,#209964); +#209964 = SURFACE_SIDE_STYLE('',(#209965)); +#209965 = SURFACE_STYLE_FILL_AREA(#209966); +#209966 = FILL_AREA_STYLE('',(#209967)); +#209967 = FILL_AREA_STYLE_COLOUR('',#197425); +#209968 = OVER_RIDING_STYLED_ITEM('overriding color',(#209969),#153636, + #209961); +#209969 = PRESENTATION_STYLE_ASSIGNMENT((#209970)); +#209970 = SURFACE_STYLE_USAGE(.BOTH.,#209971); +#209971 = SURFACE_SIDE_STYLE('',(#209972)); +#209972 = SURFACE_STYLE_FILL_AREA(#209973); +#209973 = FILL_AREA_STYLE('',(#209974)); +#209974 = FILL_AREA_STYLE_COLOUR('',#198360); +#209975 = OVER_RIDING_STYLED_ITEM('overriding color',(#209976),#154077, + #209961); +#209976 = PRESENTATION_STYLE_ASSIGNMENT((#209977)); +#209977 = SURFACE_STYLE_USAGE(.BOTH.,#209978); +#209978 = SURFACE_SIDE_STYLE('',(#209979)); +#209979 = SURFACE_STYLE_FILL_AREA(#209980); +#209980 = FILL_AREA_STYLE('',(#209981)); +#209981 = FILL_AREA_STYLE_COLOUR('',#198360); +#209982 = OVER_RIDING_STYLED_ITEM('overriding color',(#209983),#154396, + #209961); +#209983 = PRESENTATION_STYLE_ASSIGNMENT((#209984)); +#209984 = SURFACE_STYLE_USAGE(.BOTH.,#209985); +#209985 = SURFACE_SIDE_STYLE('',(#209986)); +#209986 = SURFACE_STYLE_FILL_AREA(#209987); +#209987 = FILL_AREA_STYLE('',(#209988)); +#209988 = FILL_AREA_STYLE_COLOUR('',#198360); +#209989 = OVER_RIDING_STYLED_ITEM('overriding color',(#209990),#154553, + #209961); +#209990 = PRESENTATION_STYLE_ASSIGNMENT((#209991)); +#209991 = SURFACE_STYLE_USAGE(.BOTH.,#209992); +#209992 = SURFACE_SIDE_STYLE('',(#209993)); +#209993 = SURFACE_STYLE_FILL_AREA(#209994); +#209994 = FILL_AREA_STYLE('',(#209995)); +#209995 = FILL_AREA_STYLE_COLOUR('',#197440); +#209996 = OVER_RIDING_STYLED_ITEM('overriding color',(#209997),#154624, + #209961); +#209997 = PRESENTATION_STYLE_ASSIGNMENT((#209998)); +#209998 = SURFACE_STYLE_USAGE(.BOTH.,#209999); +#209999 = SURFACE_SIDE_STYLE('',(#210000)); +#210000 = SURFACE_STYLE_FILL_AREA(#210001); +#210001 = FILL_AREA_STYLE('',(#210002)); +#210002 = FILL_AREA_STYLE_COLOUR('',#198360); +#210003 = OVER_RIDING_STYLED_ITEM('overriding color',(#210004),#154725, + #209961); +#210004 = PRESENTATION_STYLE_ASSIGNMENT((#210005)); +#210005 = SURFACE_STYLE_USAGE(.BOTH.,#210006); +#210006 = SURFACE_SIDE_STYLE('',(#210007)); +#210007 = SURFACE_STYLE_FILL_AREA(#210008); +#210008 = FILL_AREA_STYLE('',(#210009)); +#210009 = FILL_AREA_STYLE_COLOUR('',#198360); +#210010 = OVER_RIDING_STYLED_ITEM('overriding color',(#210011),#154772, + #209961); +#210011 = PRESENTATION_STYLE_ASSIGNMENT((#210012)); +#210012 = SURFACE_STYLE_USAGE(.BOTH.,#210013); +#210013 = SURFACE_SIDE_STYLE('',(#210014)); +#210014 = SURFACE_STYLE_FILL_AREA(#210015); +#210015 = FILL_AREA_STYLE('',(#210016)); +#210016 = FILL_AREA_STYLE_COLOUR('',#197440); +#210017 = OVER_RIDING_STYLED_ITEM('overriding color',(#210018),#154781, + #209961); +#210018 = PRESENTATION_STYLE_ASSIGNMENT((#210019)); +#210019 = SURFACE_STYLE_USAGE(.BOTH.,#210020); +#210020 = SURFACE_SIDE_STYLE('',(#210021)); +#210021 = SURFACE_STYLE_FILL_AREA(#210022); +#210022 = FILL_AREA_STYLE('',(#210023)); +#210023 = FILL_AREA_STYLE_COLOUR('',#197440); ENDSEC; END-ISO-10303-21; diff --git a/flight/targets/sparkybgc/fw/Makefile b/flight/targets/sparkybgc/fw/Makefile index 7a743ae8790..e2c23782747 100644 --- a/flight/targets/sparkybgc/fw/Makefile +++ b/flight/targets/sparkybgc/fw/Makefile @@ -102,7 +102,6 @@ SRC += $(FLIGHTLIB)/insgps16state.c SRC += $(FLIGHTLIB)/taskmonitor.c SRC += $(FLIGHTLIB)/sanitycheck.c SRC += $(MATHLIB)/coordinate_conversions.c -SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/misc_math.c SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/atmospheric_math.c @@ -120,6 +119,7 @@ SRC += $(PIOSCOMMON)/pios_mpxv5004.c SRC += $(PIOSCOMMON)/pios_mpxv7002.c SRC += $(PIOSCOMMON)/pios_crc.c SRC += $(PIOSCOMMON)/pios_com.c +SRC += $(PIOSCOMMON)/pios_dsm.c SRC += $(PIOSCOMMON)/pios_rcvr.c SRC += $(PIOSCOMMON)/pios_sbus.c SRC += $(PIOSCOMMON)/pios_sensors.c @@ -137,9 +137,6 @@ SRC += $(PIOSCOMMON)/pios_mutex.c SRC += $(PIOSCOMMON)/pios_thread.c SRC += $(PIOSCOMMON)/pios_queue.c -include ./UAVObjects.inc -SRC += $(UAVOBJSRC) - # List C++ source files here. # use file-extension .cpp for C++-files (not .C) CPPSRC = @@ -305,4 +302,8 @@ LDFLAGS += -Wl,--fatal-warnings #Linker scripts LDFLAGS += $(addprefix -T,$(LINKER_SCRIPTS_APP)) +include ./UAVObjects.inc + +UAVO_NAV = YES + include $(MAKE_INC_DIR)/firmware-common.mk diff --git a/flight/targets/sparkybgc/fw/UAVObjects.inc b/flight/targets/sparkybgc/fw/UAVObjects.inc index 9fc2859cc3f..b2660f84413 100644 --- a/flight/targets/sparkybgc/fw/UAVObjects.inc +++ b/flight/targets/sparkybgc/fw/UAVObjects.inc @@ -1,11 +1,11 @@ ############################################################################### # @file Makefile -# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2014 +# @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 # @addtogroup # @{ # @addtogroup # @{ -# @brief Makefile to build UAVObject code for Sparky board. +# @brief Makefile to build UAVObject code for SparkyBGC board. ############################################################################### # # This program is free software; you can redistribute it and/or modify @@ -27,96 +27,10 @@ # (all architectures) UAVOBJSRCFILENAMES = -UAVOBJSRCFILENAMES += accessorydesired -UAVOBJSRCFILENAMES += actuatorcommand -UAVOBJSRCFILENAMES += actuatordesired -UAVOBJSRCFILENAMES += actuatorsettings -UAVOBJSRCFILENAMES += attitudesettings -UAVOBJSRCFILENAMES += insstate -UAVOBJSRCFILENAMES += inssettings -UAVOBJSRCFILENAMES += attitudeactual UAVOBJSRCFILENAMES += brushlessgimbalsettings -UAVOBJSRCFILENAMES += gyros -UAVOBJSRCFILENAMES += gyrosbias -UAVOBJSRCFILENAMES += sensorsettings -UAVOBJSRCFILENAMES += accels -UAVOBJSRCFILENAMES += magnetometer -UAVOBJSRCFILENAMES += magbias -UAVOBJSRCFILENAMES += baroaltitude -UAVOBJSRCFILENAMES += baroairspeed -UAVOBJSRCFILENAMES += airspeedsettings -UAVOBJSRCFILENAMES += airspeedactual -UAVOBJSRCFILENAMES += fixedwingairspeeds -UAVOBJSRCFILENAMES += fixedwingpathfollowersettings -UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus -UAVOBJSRCFILENAMES += flightbatterysettings -UAVOBJSRCFILENAMES += firmwareiapobj -UAVOBJSRCFILENAMES += flightbatterystate -UAVOBJSRCFILENAMES += flightplancontrol -UAVOBJSRCFILENAMES += flightplansettings -UAVOBJSRCFILENAMES += flightplanstatus -UAVOBJSRCFILENAMES += flighttelemetrystats -UAVOBJSRCFILENAMES += gcstelemetrystats -UAVOBJSRCFILENAMES += gcsreceiver -UAVOBJSRCFILENAMES += gpsposition -UAVOBJSRCFILENAMES += gpssatellites -UAVOBJSRCFILENAMES += gpstime -UAVOBJSRCFILENAMES += gpsvelocity -UAVOBJSRCFILENAMES += loitercommand -UAVOBJSRCFILENAMES += vtolpathfollowersettings -UAVOBJSRCFILENAMES += vtolpathfollowerstatus -UAVOBJSRCFILENAMES += homelocation -UAVOBJSRCFILENAMES += manualcontrolcommand -UAVOBJSRCFILENAMES += manualcontrolsettings -UAVOBJSRCFILENAMES += mixersettings -UAVOBJSRCFILENAMES += mixerstatus -UAVOBJSRCFILENAMES += mwratesettings -UAVOBJSRCFILENAMES += nedaccel -UAVOBJSRCFILENAMES += nedposition -UAVOBJSRCFILENAMES += objectpersistence -UAVOBJSRCFILENAMES += overosyncstats -UAVOBJSRCFILENAMES += overosyncsettings -UAVOBJSRCFILENAMES += pathdesired -UAVOBJSRCFILENAMES += pathplannersettings -UAVOBJSRCFILENAMES += pathstatus -UAVOBJSRCFILENAMES += poilocation -UAVOBJSRCFILENAMES += positionactual -UAVOBJSRCFILENAMES += ratedesired -UAVOBJSRCFILENAMES += stateestimation -UAVOBJSRCFILENAMES += sonaraltitude -UAVOBJSRCFILENAMES += stabilizationdesired -UAVOBJSRCFILENAMES += stabilizationsettings -UAVOBJSRCFILENAMES += systemalarms -UAVOBJSRCFILENAMES += systemident -UAVOBJSRCFILENAMES += systemsettings -UAVOBJSRCFILENAMES += systemstats -UAVOBJSRCFILENAMES += tabletinfo -UAVOBJSRCFILENAMES += taskinfo -UAVOBJSRCFILENAMES += velocityactual -UAVOBJSRCFILENAMES += velocitydesired -UAVOBJSRCFILENAMES += vibrationanalysissettings -UAVOBJSRCFILENAMES += vibrationanalysisoutput -UAVOBJSRCFILENAMES += watchdogstatus -UAVOBJSRCFILENAMES += flightstatus UAVOBJSRCFILENAMES += hwsparkybgc -UAVOBJSRCFILENAMES += modulesettings -UAVOBJSRCFILENAMES += receiveractivity -UAVOBJSRCFILENAMES += cameradesired -UAVOBJSRCFILENAMES += camerastabsettings -UAVOBJSRCFILENAMES += altitudeholdsettings -UAVOBJSRCFILENAMES += altitudeholddesired -UAVOBJSRCFILENAMES += waypoint -UAVOBJSRCFILENAMES += waypointactive -UAVOBJSRCFILENAMES += ubloxinfo -UAVOBJSRCFILENAMES += txpidsettings UAVOBJSRCFILENAMES += i2cvm UAVOBJSRCFILENAMES += i2cvmuserprogram -UAVOBJSRCFILENAMES += trimangles -UAVOBJSRCFILENAMES += trimanglessettings -UAVOBJSRCFILENAMES += sessionmanaging - -UAVOBJSRC = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) -UAVOBJDEFINE = $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) diff --git a/flight/targets/sparkybgc/fw/pios_board.c b/flight/targets/sparkybgc/fw/pios_board.c index 38891c14b83..d212e771f0b 100644 --- a/flight/targets/sparkybgc/fw/pios_board.c +++ b/flight/targets/sparkybgc/fw/pios_board.c @@ -180,7 +180,7 @@ static void PIOS_Board_configure_com (const struct pios_usart_cfg *usart_port_cf #ifdef PIOS_INCLUDE_DSM static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm_cfg, const struct pios_dsm_cfg *pios_dsm_cfg, const struct pios_com_driver *pios_usart_com_driver, - ManualControlSettingsChannelGroupsOptions channelgroup,uint8_t *bind) + ManualControlSettingsChannelGroupsOptions channelgroup,HwSparkyBGCDSMxModeOptions *mode) { uintptr_t pios_usart_dsm_id; if (PIOS_USART_Init(&pios_usart_dsm_id, pios_usart_dsm_cfg)) { @@ -189,7 +189,7 @@ static void PIOS_Board_configure_dsm(const struct pios_usart_cfg *pios_usart_dsm uintptr_t pios_dsm_id; if (PIOS_DSM_Init(&pios_dsm_id, pios_dsm_cfg, pios_usart_com_driver, - pios_usart_dsm_id, *bind)) { + pios_usart_dsm_id, *mode)) { PIOS_Assert(0); } @@ -473,8 +473,8 @@ void PIOS_Board_Init(void) { #endif /* PIOS_INCLUDE_USB */ /* Configure the IO ports */ - uint8_t hw_DSMxBind; - HwSparkyBGCDSMxBindGet(&hw_DSMxBind); + HwSparkyBGCDSMxModeOptions hw_DSMxMode; + HwSparkyBGCDSMxModeGet(&hw_DSMxMode); /* UART1 Port */ uint8_t hw_flexi; @@ -515,7 +515,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_flexi_dsm_cfg, &pios_flexi_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMFLEXIPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; @@ -569,7 +569,7 @@ void PIOS_Board_Init(void) { #if defined(PIOS_INCLUDE_DSM) { PIOS_Board_configure_dsm(&pios_rcvr_dsm_cfg, &pios_rcvr_dsm_aux_cfg, &pios_usart_com_driver, - MANUALCONTROLSETTINGS_CHANNELGROUPS_DSMMAINPORT, &hw_DSMxBind); + MANUALCONTROLSETTINGS_CHANNELGROUPS_DSM, &hw_DSMxMode); } #endif /* PIOS_INCLUDE_DSM */ break; diff --git a/flight/targets/sparkybgc/fw/pios_config.h b/flight/targets/sparkybgc/fw/pios_config.h index 271580aecbd..6efbf5f821f 100644 --- a/flight/targets/sparkybgc/fw/pios_config.h +++ b/flight/targets/sparkybgc/fw/pios_config.h @@ -115,9 +115,6 @@ #define GIMBAL -// This flag is needed to get the GPS objects defined which attitude requires -#define REVOLUTION - #endif /* PIOS_CONFIG_H */ /** * @} diff --git a/flight/tests/misc_math/unittest.cpp b/flight/tests/misc_math/unittest.cpp index 6b3bfaff23a..8b5e0fa301d 100644 --- a/flight/tests/misc_math/unittest.cpp +++ b/flight/tests/misc_math/unittest.cpp @@ -237,3 +237,55 @@ TEST_F(CircularModulusDeg, SweepError) { ASSERT_NEAR(error, circular_modulus_deg(error + 1080), eps); } }; + +// Test fixture for vector2_clip() +class Vector2Clip : public MiscMath { +protected: + virtual void SetUp() { + } + + virtual void TearDown() { + } +}; + +TEST_F(Vector2Clip, TestScale) { + float eps = 0.000001f; + + // Choose a non-integer limit + for (int i=0; i<3; i++) { + // Change the limit on each interation. This tests limit < 1, limit = 1, and limit > 1. + float limit = 0.5*i; + + float test_vec_null[2] = {0, 0}; + float test_vec_within[2] = {limit/2, limit/2}; + float test_vec_edge_numerically_stable[2] = {limit, 0}; + float test_vec_edge_numerically_unstable[2] = + {(float) (sqrt(2)/2*limit), (float) (sqrt(2)/2*limit)}; + float test_vec_outside[2] = {limit, limit}; + + // Test for 0 vector + vector2_clip(test_vec_null, limit); + ASSERT_NEAR(test_vec_null[0], 0, eps); + ASSERT_NEAR(test_vec_null[1], 0, eps); + + // Test for vector within limits + vector2_clip(test_vec_within, limit); + EXPECT_EQ(test_vec_within[0], limit/2); + EXPECT_EQ(test_vec_within[1], limit/2); + + // Test for vector numerically identically at limits + vector2_clip(test_vec_edge_numerically_stable, limit); + EXPECT_EQ(test_vec_edge_numerically_stable[0], limit); + EXPECT_EQ(test_vec_edge_numerically_stable[1], 0.0f); + + // Test for vector identically at limits, but suffering from numerical imprecision + vector2_clip(test_vec_edge_numerically_unstable, limit); + ASSERT_NEAR(test_vec_edge_numerically_unstable[0], sqrt(2)/2*limit, eps); + ASSERT_NEAR(test_vec_edge_numerically_unstable[1], sqrt(2)/2*limit, eps); + + // Test for vector outside limits + vector2_clip(test_vec_outside, limit); + ASSERT_NEAR(test_vec_outside[0], sqrt(2)/2*limit, eps); + ASSERT_NEAR(test_vec_outside[1], sqrt(2)/2*limit, eps); + } +}; diff --git a/flight/tests/sin_lookup/unittest.cpp b/flight/tests/sin_lookup/unittest.cpp deleted file mode 100644 index d0e48a63878..00000000000 --- a/flight/tests/sin_lookup/unittest.cpp +++ /dev/null @@ -1,95 +0,0 @@ -/** - ****************************************************************************** - * @file unittest.cpp - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * @addtogroup UnitTests - * @{ - * @addtogroup UnitTests - * @{ - * @brief Unit test - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -/* - * NOTE: This program uses the Google Test infrastructure to drive the unit test - * - * Main site for Google Test: http://code.google.com/p/googletest/ - * Documentation and examples: http://code.google.com/p/googletest/wiki/Documentation - */ - -#include "gtest/gtest.h" - -#include /* printf */ -#include /* abort */ -#include /* memset */ -#include /* uint*_t */ - -extern "C" { - -#include "sin_lookup.h" /* API for sin_lookup functions */ - -} - -#include /* sinf/cosf/tanf */ - -// To use a test fixture, derive a class from testing::Test. -class SinLookup : public testing::Test { -protected: - virtual void SetUp() { - EXPECT_EQ(0, sin_lookup_initialize()); - } - - virtual void TearDown() { - } - - float deg2rad(float deg) - { - return (deg * M_PI / 180); - } -}; - -TEST_F(SinLookup, SinDegSweep) { - float eps = 0.02f; - - for (float x = 0; x <= 720.0; x += .001) { - ASSERT_NEAR(sinf(deg2rad(x)), sin_lookup_deg(x), eps); - } -} - -TEST_F(SinLookup, SinRadSweep) { - float eps = 0.02f; - - for (float x = 0; x <= 4 * M_PI; x += .0001) { - ASSERT_NEAR(sinf(x), sin_lookup_rad(x), eps); - } -} - -TEST_F(SinLookup, CosDegSweep) { - float eps = 0.02f; - - for (float x = 0; x <= 720.0; x += .001) { - ASSERT_NEAR(cosf(deg2rad(x)), cos_lookup_deg(x), eps); - } -} - -TEST_F(SinLookup, CosRadSweep) { - float eps = 0.02f; - - for (float x = 0; x <= 4 * M_PI; x += .0001) { - ASSERT_NEAR(cosf(x), cos_lookup_rad(x), eps); - } -} diff --git a/ground/gcs/gcs.pri b/ground/gcs/gcs.pri index 4be36524075..a4c31bfb768 100644 --- a/ground/gcs/gcs.pri +++ b/ground/gcs/gcs.pri @@ -57,8 +57,6 @@ isEmpty(GCS_BUILD_TREE) { } GCS_APP_PATH = $$GCS_BUILD_TREE/bin macx { - QMAKE_CFLAGS_X86_64 += -mmacosx-version-min=10.7 - QMAKE_CXXFLAGS_X86_64 = $$QMAKE_CFLAGS_X86_64 GCS_APP_TARGET = "Tau Labs GCS" GCS_LIBRARY_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/Plugins GCS_PLUGIN_PATH = $$GCS_LIBRARY_PATH @@ -67,6 +65,7 @@ macx { GCS_DATA_BASENAME = Resources GCS_DOC_PATH = $$GCS_DATA_PATH/doc GCS_BIN_PATH = $$GCS_APP_PATH/$${GCS_APP_TARGET}.app/Contents/MacOS + QMAKE_MACOSX_DEPLOYMENT_TARGET=10.9 copydata = 1 } else { win32 { @@ -133,3 +132,17 @@ win32 { # http://gcc.gnu.org/bugzilla/show_bug.cgi?id=52991 QMAKE_CXXFLAGS += -mno-ms-bitfields } + +unix { + GEN_GCOV { + QMAKE_CXXFLAGS += -g -Wall -fprofile-arcs -ftest-coverage -O0 + QMAKE_LFLAGS += -g -Wall -fprofile-arcs -ftest-coverage -O0 + LIBS += \ + -lgcov + unix:OBJECTS_DIR = ./Build + unix:MOC_DIR = ./Build + unix:UI_DIR = ./Build + } +} + +CONFIG += c++11 diff --git a/ground/gcs/share/taulabs/default_configurations/TauLabs_developer.xml b/ground/gcs/share/taulabs/default_configurations/TauLabs_developer.xml index 4f5ecfa0fea..9074085bbab 100644 --- a/ground/gcs/share/taulabs/default_configurations/TauLabs_developer.xml +++ b/ground/gcs/share/taulabs/default_configurations/TauLabs_developer.xml @@ -34,23 +34,6 @@ 100 - - - - false - 0.0.0 - - - Serial - 8 - 0 - 0 - Unknown - 4800 - 1 - - - diff --git a/ground/gcs/share/taulabs/default_configurations/TauLabs_netbook.xml b/ground/gcs/share/taulabs/default_configurations/TauLabs_netbook.xml index 881d8d3e1ca..6704677e967 100644 --- a/ground/gcs/share/taulabs/default_configurations/TauLabs_netbook.xml +++ b/ground/gcs/share/taulabs/default_configurations/TauLabs_netbook.xml @@ -34,23 +34,6 @@ 100 - - - - false - 0.0.0 - - - Serial - 8 - 0 - 0 - Unknown - 4800 - 1 - - - diff --git a/ground/gcs/share/taulabs/default_configurations/TauLabs_wide.xml b/ground/gcs/share/taulabs/default_configurations/TauLabs_wide.xml index 4441d338e21..ec95c569381 100644 --- a/ground/gcs/share/taulabs/default_configurations/TauLabs_wide.xml +++ b/ground/gcs/share/taulabs/default_configurations/TauLabs_wide.xml @@ -34,23 +34,6 @@ 100 - - - - false - 0.0.0 - - - Serial - 8 - 0 - 0 - Unknown - 4800 - 1 - - - diff --git a/ground/gcs/share/taulabs/pfd/default/PfdIndicators.qml b/ground/gcs/share/taulabs/pfd/default/PfdIndicators.qml index 6e84f8dd235..500029cd9ac 100644 --- a/ground/gcs/share/taulabs/pfd/default/PfdIndicators.qml +++ b/ground/gcs/share/taulabs/pfd/default/PfdIndicators.qml @@ -1,4 +1,5 @@ import QtQuick 2.0 +import "convertint8.js" as CInt8 Item { id: sceneItem @@ -14,7 +15,7 @@ Item { elementName: "gcstelemetry-"+statusName sceneSize: sceneItem.sceneSize - property string statusName : ["Disconnected","HandshakeReq","HandshakeAck","Connected"][GCSTelemetryStats.Status] + property string statusName : ["Disconnected","HandshakeReq","HandshakeAck","Connected"][CInt8.ConvertInt8(GCSTelemetryStats.Status)] // Force refresh of the arrow image when elementName changes onElementNameChanged: { generateSource() } @@ -39,14 +40,12 @@ Item { // GPS status text Text { id: gps_text - text: "GPS: " + GPSPosition.Satellites + "\nPDP: " + GPSPosition.PDOP.toFixed(2) + "\nACC: " + GPSPosition.Accuracy.toFixed(2) + text: "GPS: " + CInt8.ConvertInt8(GPSPosition.Satellites) + "\nPDP: " + GPSPosition.PDOP.toFixed(2) + "\nACC: " + GPSPosition.Accuracy.toFixed(2) color: "white" font.family: "Arial" font.pixelSize: telemetry_status.height * 0.55 - // Non-float types are not properly getting exported to QML environment, - // so we can't do this (or print the satellite count above) - //visible: GPSPosition.Satellites > 0 + visible: CInt8.ConvertInt8(GPSPosition.Satellites) property variant scaledBounds: svgRenderer.scaledElementBounds("pfd.svg", "gps-txt") x: Math.floor(scaledBounds.x * sceneItem.width) diff --git a/ground/gcs/share/taulabs/pfd/default/convertint8.js b/ground/gcs/share/taulabs/pfd/default/convertint8.js new file mode 100644 index 00000000000..9452d472241 --- /dev/null +++ b/ground/gcs/share/taulabs/pfd/default/convertint8.js @@ -0,0 +1,22 @@ +.pragma library + +// workaround for QT bug 37241 +function ConvertInt8(a) { + if (!a.hasOwnProperty("length")) { + // Doesn't seem like a string. Let's see if it's a number + // (e.g. upstream 37241 has been fixed) + + if (!isNaN(a)) { + return a; + } + + // Nope. Don't know what to do here. + return 0; + } + + if (a.length < 1) { + return 0; + } + + return a.charCodeAt(0); +} diff --git a/ground/gcs/share/taulabs/translations/translations.pro b/ground/gcs/share/taulabs/translations/translations.pro index 3864e1da494..c9c0af934fa 100644 --- a/ground/gcs/share/taulabs/translations/translations.pro +++ b/ground/gcs/share/taulabs/translations/translations.pro @@ -65,23 +65,25 @@ qmfiles.path = /share/taulabs/translations qmfiles.CONFIG += no_check_exist INSTALLS += qmfiles +QTSYSTRANS = qt qtbase qtscript qtquick1 qtmultimedia qtxmlpatterns + #========= begin block copying qt_*.qm files ========== -win32 { - defineReplace(QtQmExists) { - for(lang,$$1) { - qm_file = $$[QT_INSTALL_TRANSLATIONS]/qt_$${lang}.qm +defineReplace(QtQmExists) { + for(lang,$$1) { + for(transbase,QTSYSTRANS) { + qm_file = $$[QT_INSTALL_TRANSLATIONS]/$${transbase}_$${lang}.qm exists($$qm_file) : result += $$qm_file } - return($$result) } - QT_TRANSLATIONS = $$QtQmExists(LANGUAGES) - - copyQT_QMs.input = QT_TRANSLATIONS - copyQT_QMs.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm - isEmpty(vcproj):copyQT_QMs.variable_out = PRE_TARGETDEPS - copyQT_QMs.commands = $(COPY_FILE) ${QMAKE_FILE_IN} ${QMAKE_FILE_OUT} - copyQT_QMs.name = Copy ${QMAKE_FILE_IN} - copyQT_QMs.CONFIG += no_link - QMAKE_EXTRA_COMPILERS += copyQT_QMs + return($$result) } +QT_TRANSLATIONS = $$QtQmExists(LANGUAGES) + +copyQT_QMs.input = QT_TRANSLATIONS +copyQT_QMs.output = $$GCS_DATA_PATH/translations/${QMAKE_FILE_BASE}.qm +isEmpty(vcproj):copyQT_QMs.variable_out = PRE_TARGETDEPS +copyQT_QMs.commands = $(COPY_FILE) ${QMAKE_FILE_IN} ${QMAKE_FILE_OUT} +copyQT_QMs.name = Copy ${QMAKE_FILE_IN} +copyQT_QMs.CONFIG += no_link +QMAKE_EXTRA_COMPILERS += copyQT_QMs #========= end block copying qt_*.qm files ============ diff --git a/ground/gcs/src/app/customsplash.cpp b/ground/gcs/src/app/customsplash.cpp index 98a1ce25ab0..75edd3f122a 100644 --- a/ground/gcs/src/app/customsplash.cpp +++ b/ground/gcs/src/app/customsplash.cpp @@ -27,6 +27,7 @@ #include "customsplash.h" #include #include +#include #include #define PROGRESS_BAR_WIDTH 100 @@ -104,6 +105,8 @@ void CustomSplash::showMessage(const QString &message, int alignment, const QCol } settings.setValue(QString::number(message_number),time.elapsed()); ++message_number; + + QCoreApplication::processEvents(); } /** * @brief Closes the splashscreen diff --git a/ground/gcs/src/app/main.cpp b/ground/gcs/src/app/main.cpp index 424847582b0..45f6804d2ff 100644 --- a/ground/gcs/src/app/main.cpp +++ b/ground/gcs/src/app/main.cpp @@ -263,12 +263,17 @@ int main(int argc, char **argv) // Must be done before any QSettings class is created QSettings::setPath(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, QCoreApplication::applicationDirPath()+QLatin1String(SHARE_PATH)); - // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp - QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, - QLatin1String("TauLabs"), QLatin1String("TauLabs_config")); - overrideSettings(settings, argc, argv); - locale = settings.value("General/OverrideLanguage", locale).toString(); + // Scope this so that we are guaranteed that the QSettings file is closed immediately. This + // prevents corruption. + { + // keep this in sync with the MainWindow ctor in coreplugin/mainwindow.cpp + QSettings settings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, + QLatin1String("TauLabs"), QLatin1String("TauLabs_config")); + + overrideSettings(settings, argc, argv); + locale = settings.value("General/OverrideLanguage", locale).toString(); + } QTranslator translator; QTranslator qtTranslator; diff --git a/ground/gcs/src/libs/glc_lib/3rdparty/quazip/unzip.h b/ground/gcs/src/libs/glc_lib/3rdparty/quazip/unzip.h index c3206a05899..de5b71eb510 100644 --- a/ground/gcs/src/libs/glc_lib/3rdparty/quazip/unzip.h +++ b/ground/gcs/src/libs/glc_lib/3rdparty/quazip/unzip.h @@ -50,8 +50,12 @@ extern "C" { #endif #ifndef _ZLIB_H +#ifdef _MSC_VER +#include +#else #include "zlib.h" #endif +#endif #ifndef _ZLIBIOAPI_H #include "ioapi.h" diff --git a/ground/gcs/src/libs/glc_lib/3rdparty/quazip/zip.h b/ground/gcs/src/libs/glc_lib/3rdparty/quazip/zip.h index cd38b670fd9..f583f00387c 100644 --- a/ground/gcs/src/libs/glc_lib/3rdparty/quazip/zip.h +++ b/ground/gcs/src/libs/glc_lib/3rdparty/quazip/zip.h @@ -51,8 +51,12 @@ extern "C" { #endif #ifndef _ZLIB_H +#ifdef _MSC_VER +#include +#else #include "zlib.h" #endif +#endif #ifndef _ZLIBIOAPI_H #include "ioapi.h" diff --git a/ground/gcs/src/libs/glc_lib/glc_lib.pro b/ground/gcs/src/libs/glc_lib/glc_lib.pro index 9825ef5bbca..e63a000b5f3 100644 --- a/ground/gcs/src/libs/glc_lib/glc_lib.pro +++ b/ground/gcs/src/libs/glc_lib/glc_lib.pro @@ -504,7 +504,8 @@ INSTALLS += include_lib3ds include_glext include_quazip include_glc_maths includ INSTALLS += include_glc_scengraph include_glc_geometry include_glc_shading include_glc_viewport INSTALLS += include_glc_3dwidget include_glc_glu -INSTALLS += target +# workaround to avoid target being added a second time due to ../../taulabslibrary.pri +!contains(INSTALLS,target):INSTALLS += target INSTALLS +=include OTHER_FILES += \ diff --git a/ground/gcs/src/libs/glc_lib/shading/glc_material.cpp b/ground/gcs/src/libs/glc_lib/shading/glc_material.cpp index e1bd9075a08..48ea87adc84 100644 --- a/ground/gcs/src/libs/glc_lib/shading/glc_material.cpp +++ b/ground/gcs/src/libs/glc_lib/shading/glc_material.cpp @@ -477,25 +477,25 @@ void GLC_Material::glLoadTexture(QGLContext* pContext) void GLC_Material::glExecute() { - GLfloat pAmbientColor[4]= {ambientColor().redF(), - ambientColor().greenF(), - ambientColor().blueF(), - ambientColor().alphaF()}; - - GLfloat pDiffuseColor[4]= {diffuseColor().redF(), - diffuseColor().greenF(), - diffuseColor().blueF(), - diffuseColor().alphaF()}; - - GLfloat pSpecularColor[4]= {specularColor().redF(), - specularColor().greenF(), - specularColor().blueF(), - specularColor().alphaF()}; - - GLfloat pLightEmission[4]= {emissiveColor().redF(), - emissiveColor().greenF(), - emissiveColor().blueF(), - emissiveColor().alphaF()}; + GLfloat pAmbientColor[4]= { (GLfloat) ambientColor().redF(), + (GLfloat) ambientColor().greenF(), + (GLfloat) ambientColor().blueF(), + (GLfloat) ambientColor().alphaF()}; + + GLfloat pDiffuseColor[4]= { (GLfloat) diffuseColor().redF(), + (GLfloat) diffuseColor().greenF(), + (GLfloat) diffuseColor().blueF(), + (GLfloat) diffuseColor().alphaF()}; + + GLfloat pSpecularColor[4]= { (GLfloat) specularColor().redF(), + (GLfloat) specularColor().greenF(), + (GLfloat) specularColor().blueF(), + (GLfloat) specularColor().alphaF()}; + + GLfloat pLightEmission[4]= { (GLfloat) emissiveColor().redF(), + (GLfloat) emissiveColor().greenF(), + (GLfloat) emissiveColor().blueF(), + (GLfloat) emissiveColor().alphaF()}; const bool textureIsEnable= glIsEnabled(GL_TEXTURE_2D); if (m_pTexture != NULL) @@ -550,24 +550,24 @@ void GLC_Material::glExecute() // Execute OpenGL Material void GLC_Material::glExecute(float overwriteTransparency) { - GLfloat pAmbientColor[4]= {ambientColor().redF(), - ambientColor().greenF(), - ambientColor().blueF(), + GLfloat pAmbientColor[4]= { (GLfloat) ambientColor().redF(), + (GLfloat) ambientColor().greenF(), + (GLfloat) ambientColor().blueF(), overwriteTransparency}; - GLfloat pDiffuseColor[4]= {diffuseColor().redF(), - diffuseColor().greenF(), - diffuseColor().blueF(), + GLfloat pDiffuseColor[4]= { (GLfloat) diffuseColor().redF(), + (GLfloat) diffuseColor().greenF(), + (GLfloat) diffuseColor().blueF(), overwriteTransparency}; - GLfloat pSpecularColor[4]= {specularColor().redF(), - specularColor().greenF(), - specularColor().blueF(), + GLfloat pSpecularColor[4]= { (GLfloat) specularColor().redF(), + (GLfloat) specularColor().greenF(), + (GLfloat) specularColor().blueF(), overwriteTransparency}; - GLfloat pLightEmission[4]= {emissiveColor().redF(), - emissiveColor().greenF(), - emissiveColor().blueF(), + GLfloat pLightEmission[4]= { (GLfloat) emissiveColor().redF(), + (GLfloat) emissiveColor().greenF(), + (GLfloat) emissiveColor().blueF(), overwriteTransparency}; const bool textureIsEnable= glIsEnabled(GL_TEXTURE_2D); diff --git a/ground/gcs/src/libs/qscispinbox/QScienceSpinBox.h b/ground/gcs/src/libs/qscispinbox/QScienceSpinBox.h index d6f382265a0..2dd6ced351d 100644 --- a/ground/gcs/src/libs/qscispinbox/QScienceSpinBox.h +++ b/ground/gcs/src/libs/qscispinbox/QScienceSpinBox.h @@ -4,6 +4,12 @@ #ifndef __QScienceSpinBox_H__ #define __QScienceSpinBox_H__ +#ifdef QSCIENCESPINBOX + #define QSCIENCESPINBOX_EXPORT Q_DECL_EXPORT +#else + #define QSCIENCESPINBOX_EXPORT Q_DECL_IMPORT +#endif + #include #include #include @@ -12,7 +18,7 @@ #include -class QScienceSpinBox : public QDoubleSpinBox +class QSCIENCESPINBOX_EXPORT QScienceSpinBox : public QDoubleSpinBox { Q_OBJECT public: diff --git a/ground/gcs/src/libs/qwt/qwt.pri b/ground/gcs/src/libs/qwt/qwt.pri index 7d57a8ce75b..a13ca9afe53 100644 --- a/ground/gcs/src/libs/qwt/qwt.pri +++ b/ground/gcs/src/libs/qwt/qwt.pri @@ -1,2 +1,3 @@ LIBS *= -l$$qtLibraryName(Qwt) +DEFINES += QWT_DLL diff --git a/ground/gcs/src/libs/qwt/qwt.pro b/ground/gcs/src/libs/qwt/qwt.pro index 2dccbc83bfd..ed7d6519f50 100644 --- a/ground/gcs/src/libs/qwt/qwt.pro +++ b/ground/gcs/src/libs/qwt/qwt.pro @@ -8,8 +8,6 @@ ################################################################ include( qwtconfig.pri ) -# include(../../../taulabslibrary.pri) - TEMPLATE = subdirs CONFIG += warn_off CONFIG += ordered diff --git a/ground/gcs/src/libs/qwt/src/src.pro b/ground/gcs/src/libs/qwt/src/src.pro index ecca039bff5..3660318eee7 100644 --- a/ground/gcs/src/libs/qwt/src/src.pro +++ b/ground/gcs/src/libs/qwt/src/src.pro @@ -13,7 +13,7 @@ TEMPLATE = lib TARGET = Qwt DEFINES += QWT_LIBRARY QT += printsupport -QMAKE_CXXFLAGS += -Wno-sign-compare +!win32-msvc*:QMAKE_CXXFLAGS += -Wno-sign-compare include(../../../taulabslibrary.pri) include( ../qwtconfig.pri ) @@ -42,12 +42,6 @@ CONFIG(lib_bundle) { FRAMEWORK_HEADERS.path = Headers QMAKE_BUNDLE_DATA += FRAMEWORK_HEADERS } -else { - - headers.files = $${HEADERS} - headers.path = $${QWT_INSTALL_HEADERS} - INSTALLS += headers -} contains(QWT_CONFIG, QwtPkgConfig) { diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/accessmode.h b/ground/gcs/src/libs/tlmapcontrol/core/accessmode.h similarity index 93% rename from ground/gcs/src/libs/tlmapcontrol/src/core/accessmode.h rename to ground/gcs/src/libs/tlmapcontrol/core/accessmode.h index 08c79448bce..880ff2f7c91 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/accessmode.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/accessmode.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -33,8 +33,10 @@ #include #include #include +#include "corecommon.h" + namespace core { - class AccessMode:public QObject + class TLMAPWIDGET_EXPORT AccessMode:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.cpp b/ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.cpp index 100e94273dc..063dc0b6e6a 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.h b/ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.h rename to ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.h index 155bdca6925..5cf1a0681e1 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/alllayersoftype.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/alllayersoftype.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/cache.cpp b/ground/gcs/src/libs/tlmapcontrol/core/cache.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/cache.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/cache.cpp index d829c040b09..793052cc685 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/cache.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/cache.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/cache.h b/ground/gcs/src/libs/tlmapcontrol/core/cache.h similarity index 93% rename from ground/gcs/src/libs/tlmapcontrol/src/core/cache.h rename to ground/gcs/src/libs/tlmapcontrol/core/cache.h index 01cdb382698..d001d29fd62 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/cache.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/cache.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -30,9 +30,10 @@ #include "pureimagecache.h" #include "debugheader.h" +#include "corecommon.h" namespace core { - class Cache + class TLMAPWIDGET_EXPORT Cache { public: static Cache* Instance(); diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.cpp b/ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.cpp index 9af74e0b100..61e424e1dc1 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.h b/ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.h rename to ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.h index 41384cda077..73e1cfe1601 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/cacheitemqueue.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/cacheitemqueue.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/core/corecommon.h b/ground/gcs/src/libs/tlmapcontrol/core/corecommon.h new file mode 100644 index 00000000000..29bcc7aa049 --- /dev/null +++ b/ground/gcs/src/libs/tlmapcontrol/core/corecommon.h @@ -0,0 +1,11 @@ +#ifndef CORECOMMON +#define CORECOMMON + +#ifdef TLMAPWIDGET_LIBRARY + #define TLMAPWIDGET_EXPORT Q_DECL_EXPORT +#else + #define TLMAPWIDGET_EXPORT Q_DECL_IMPORT +#endif + +#endif // CORECOMMON + diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/debugheader.h b/ground/gcs/src/libs/tlmapcontrol/core/debugheader.h similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/core/debugheader.h rename to ground/gcs/src/libs/tlmapcontrol/core/debugheader.h diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.cpp b/ground/gcs/src/libs/tlmapcontrol/core/diagnostics.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/diagnostics.cpp index 88bdab1455f..bb772457c56 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/diagnostics.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.h b/ground/gcs/src/libs/tlmapcontrol/core/diagnostics.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.h rename to ground/gcs/src/libs/tlmapcontrol/core/diagnostics.h index afe6d73eeeb..39aacf6d338 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/diagnostics.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/diagnostics.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/geodecoderstatus.h b/ground/gcs/src/libs/tlmapcontrol/core/geodecoderstatus.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/core/geodecoderstatus.h rename to ground/gcs/src/libs/tlmapcontrol/core/geodecoderstatus.h index 1e236fbab8b..e2510f42315 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/geodecoderstatus.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/geodecoderstatus.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -32,8 +32,10 @@ #include #include #include +#include "corecommon.h" + namespace core { - class GeoCoderStatusCode:public QObject + class TLMAPWIDGET_EXPORT GeoCoderStatusCode:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.cpp b/ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.cpp similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.cpp index 6b236064d6c..2f26fddb5c3 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.h b/ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.h rename to ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.h index 81833f811cb..727020602d5 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/kibertilecache.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/kibertilecache.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.cpp b/ground/gcs/src/libs/tlmapcontrol/core/languagetype.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/languagetype.cpp index b2116b3c78b..5029c2798ba 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/languagetype.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.h b/ground/gcs/src/libs/tlmapcontrol/core/languagetype.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.h rename to ground/gcs/src/libs/tlmapcontrol/core/languagetype.h index 3ce238b4eca..384a763e1a7 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/languagetype.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/languagetype.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -32,10 +32,10 @@ #include #include #include - +#include "corecommon.h" namespace core { - class LanguageType:public QObject + class TLMAPWIDGET_EXPORT LanguageType:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/maptype.h b/ground/gcs/src/libs/tlmapcontrol/core/maptype.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/core/maptype.h rename to ground/gcs/src/libs/tlmapcontrol/core/maptype.h index 27864795502..e861935d133 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/maptype.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/maptype.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -30,9 +30,10 @@ #include #include #include +#include "corecommon.h" namespace core { - class MapType:public QObject + class TLMAPWIDGET_EXPORT MapType:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.cpp b/ground/gcs/src/libs/tlmapcontrol/core/memorycache.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/memorycache.cpp index d59b13d9b67..187424abe39 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/memorycache.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.h b/ground/gcs/src/libs/tlmapcontrol/core/memorycache.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.h rename to ground/gcs/src/libs/tlmapcontrol/core/memorycache.h index d976027e059..6f88a696d56 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/memorycache.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/memorycache.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/point.cpp b/ground/gcs/src/libs/tlmapcontrol/core/point.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/point.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/point.cpp index 38dcc606757..cf177527857 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/point.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/point.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/point.h b/ground/gcs/src/libs/tlmapcontrol/core/point.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/point.h rename to ground/gcs/src/libs/tlmapcontrol/core/point.h index 1b9814138ff..562a500eccd 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/point.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/point.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.cpp b/ground/gcs/src/libs/tlmapcontrol/core/providerstrings.cpp similarity index 97% rename from ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/providerstrings.cpp index b4f32decd5f..e38dae7356a 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/providerstrings.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.h b/ground/gcs/src/libs/tlmapcontrol/core/providerstrings.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.h rename to ground/gcs/src/libs/tlmapcontrol/core/providerstrings.h index 8413dd5b3e7..e12e8886b84 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/providerstrings.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/providerstrings.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.cpp b/ground/gcs/src/libs/tlmapcontrol/core/pureimage.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/pureimage.cpp index 5272fc55af2..c1ac04cb471 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/pureimage.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.h b/ground/gcs/src/libs/tlmapcontrol/core/pureimage.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.h rename to ground/gcs/src/libs/tlmapcontrol/core/pureimage.h index e83e5b412cf..737b1d99d72 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimage.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/pureimage.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.cpp b/ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.cpp index 8872d95b55a..62d72726d00 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.h b/ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.h similarity index 98% rename from ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.h rename to ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.h index 3e2decac61a..dc59e606672 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/pureimagecache.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/pureimagecache.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.cpp b/ground/gcs/src/libs/tlmapcontrol/core/rawtile.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/rawtile.cpp index 380660e431d..45679827aa7 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/rawtile.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.h b/ground/gcs/src/libs/tlmapcontrol/core/rawtile.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.h rename to ground/gcs/src/libs/tlmapcontrol/core/rawtile.h index 749367ba43f..15096c91664 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/rawtile.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/rawtile.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/size.cpp b/ground/gcs/src/libs/tlmapcontrol/core/size.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/size.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/size.cpp index e93e0a87675..0a3e8178bcf 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/size.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/size.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/size.h b/ground/gcs/src/libs/tlmapcontrol/core/size.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/core/size.h rename to ground/gcs/src/libs/tlmapcontrol/core/size.h index 2a5a4863165..80800f9cb77 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/size.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/size.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.cpp b/ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.cpp index 6cfae89c4d1..d50725620be 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.h b/ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.h rename to ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.h index b7dc7e81317..90abfb7ade2 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/tilecachequeue.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/tilecachequeue.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.cpp b/ground/gcs/src/libs/tlmapcontrol/core/tlmaps.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/tlmaps.cpp index 1b451faaecd..61424b4e92a 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/tlmaps.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.h b/ground/gcs/src/libs/tlmapcontrol/core/tlmaps.h similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.h rename to ground/gcs/src/libs/tlmapcontrol/core/tlmaps.h index aa8860cb094..5864093f0b8 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/tlmaps.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/tlmaps.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.cpp b/ground/gcs/src/libs/tlmapcontrol/core/urlfactory.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.cpp rename to ground/gcs/src/libs/tlmapcontrol/core/urlfactory.cpp index 402dff44288..afef33af23a 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/core/urlfactory.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -25,6 +25,8 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define _USE_MATH_DEFINES +#include #include "urlfactory.h" #include diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.h b/ground/gcs/src/libs/tlmapcontrol/core/urlfactory.h similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.h rename to ground/gcs/src/libs/tlmapcontrol/core/urlfactory.h index 16d74813061..68f75188f86 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/urlfactory.h +++ b/ground/gcs/src/libs/tlmapcontrol/core/urlfactory.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/copyrightstrings.h b/ground/gcs/src/libs/tlmapcontrol/internals/copyrightstrings.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/copyrightstrings.h rename to ground/gcs/src/libs/tlmapcontrol/internals/copyrightstrings.h index b4667f674ee..2118f9df169 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/copyrightstrings.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/copyrightstrings.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/core.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/core.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/core.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/core.cpp index f58dabedd15..df00cd8c70c 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/core.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/core.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/core.h b/ground/gcs/src/libs/tlmapcontrol/internals/core.h similarity index 98% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/core.h rename to ground/gcs/src/libs/tlmapcontrol/internals/core.h index f44004ad625..c36d06dc878 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/core.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/core.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -57,6 +57,7 @@ #include #include +#include "../core/corecommon.h" namespace mapcontrol { @@ -66,7 +67,7 @@ namespace mapcontrol namespace internals { - class Core:public QObject,public QRunnable + class TLMAPWIDGET_EXPORT Core:public QObject,public QRunnable { Q_OBJECT diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/debugheader.h b/ground/gcs/src/libs/tlmapcontrol/internals/debugheader.h similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/debugheader.h rename to ground/gcs/src/libs/tlmapcontrol/internals/debugheader.h diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/loadtask.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/loadtask.cpp index a68f7efa089..6ebfaa2b7ce 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/loadtask.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.h b/ground/gcs/src/libs/tlmapcontrol/internals/loadtask.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.h rename to ground/gcs/src/libs/tlmapcontrol/internals/loadtask.h index d768d54ddf6..0a5195d233f 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/loadtask.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/loadtask.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/MouseWheelZoomType.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/MouseWheelZoomType.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.cpp index 3d67f27ecf0..d003d24fdd4 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/MouseWheelZoomType.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.cpp @@ -5,7 +5,7 @@ * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/mousewheelzoomtype.h b/ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/mousewheelzoomtype.h rename to ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.h index d04abd9df7b..082cf7bff73 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/mousewheelzoomtype.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/mousewheelzoomtype.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.cpp index ea3eca1d6f3..d7315bb178d 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.h b/ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.h similarity index 79% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.h rename to ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.h index ace3a8c4d27..c649bc31c1f 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/pointlatlng.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/pointlatlng.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -31,17 +31,15 @@ #include #include #include "sizelatlng.h" - +#include "../core/corecommon.h" + namespace internals { -struct PointLatLng +struct TLMAPWIDGET_EXPORT PointLatLng { - //friend uint qHash(PointLatLng const& point); - friend bool operator==(PointLatLng const& lhs,PointLatLng const& rhs); - friend bool operator!=(PointLatLng const& left, PointLatLng const& right); - friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); - friend PointLatLng operator-(PointLatLng pt, SizeLatLng sz); - - //TODO Sizelatlng friend PointLatLng operator+(PointLatLng pt, SizeLatLng sz); + friend bool TLMAPWIDGET_EXPORT operator==(PointLatLng const& lhs,PointLatLng const& rhs); + friend bool TLMAPWIDGET_EXPORT operator!=(PointLatLng const& left, PointLatLng const& right); + friend PointLatLng TLMAPWIDGET_EXPORT operator+(PointLatLng pt, SizeLatLng sz); + friend PointLatLng TLMAPWIDGET_EXPORT operator-(PointLatLng pt, SizeLatLng sz); private: double lat; @@ -50,7 +48,6 @@ struct PointLatLng public: PointLatLng(); - static PointLatLng Empty; PointLatLng(const double &lat,const double &lng) @@ -87,10 +84,6 @@ struct PointLatLng empty=false; } - - - - static PointLatLng Add(PointLatLng const& pt, SizeLatLng const& sz) { return PointLatLng(pt.Lat() - sz.HeightLat(), pt.Lng() + sz.WidthLng()); @@ -119,13 +112,7 @@ struct PointLatLng return QString("{Lat=%1, Lng=%2}").arg(this->lat).arg(this->lng); } -//// static PointLatLng() -//// { -//// Empty = new PointLatLng(); -//// } }; - -// } #endif // POINTLATLNG_H diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.cpp similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.cpp index 5f21b711626..cde5f8528c2 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org Copyright (C) 2013. * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -26,6 +26,8 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define _USE_MATH_DEFINES +#include #include "lks94projection.h" #include "../../../../shared/api/physical_constants.h" diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.h b/ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.h rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.h index 41e97e51a68..721a4597b3e 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/lks94projection.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/lks94projection.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.cpp index ace60772bec..c1b448f0137 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -25,6 +25,8 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define _USE_MATH_DEFINES +#include #include "mercatorprojection.h" diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.h b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.h rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.h index c5a3f895abf..d6bfb8373b9 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojection.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojection.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.cpp index 1187c88c55d..5b8f532a6bf 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -25,10 +25,10 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define _USE_MATH_DEFINES +#include #include "mercatorprojectionyandex.h" - - namespace projections { MercatorProjectionYandex::MercatorProjectionYandex():MinLatitude(-85.05112878), MaxLatitude(85.05112878),MinLongitude(-180), MaxLongitude(180), RAD_DEG(180 / M_PI),DEG_RAD(M_PI / 180),MathPiDiv4(M_PI / 4),tileSize(256, 256) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.h b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.h rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.h index 1b30ded79af..c5728e9e145 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/mercatorprojectionyandex.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/mercatorprojectionyandex.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.cpp index 6fc6b82f4ae..baba95ccaec 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.h b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.h rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.h index 33440ad97f5..ead170c03d5 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojection.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojection.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.cpp index 235670b481f..ea231d1cbb8 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.h b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.h rename to ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.h index 57a19f0ed8b..7ed26e4c7d8 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/projections/platecarreeprojectionpergo.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/projections/platecarreeprojectionpergo.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.cpp similarity index 97% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.cpp index 3ae26c28819..624accc0212 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org Copyright (C) 2013. * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.h b/ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.h rename to ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.h index af4cac9f117..23edf2ed7c9 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/pureprojection.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/pureprojection.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org Copyright (C) 2013. * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -35,6 +35,7 @@ #include "cmath" #include "rectlatlng.h" #include + using namespace core; namespace internals diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/rectangle.cpp similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/rectangle.cpp index e9ded848eb1..8205683a38f 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/rectangle.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.h b/ground/gcs/src/libs/tlmapcontrol/internals/rectangle.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.h rename to ground/gcs/src/libs/tlmapcontrol/internals/rectangle.h index 8fa09adb081..4e1010a92c2 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectangle.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/rectangle.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -27,7 +27,6 @@ */ #ifndef RECTANGLE_H #define RECTANGLE_H -//#include #include "../core/size.h" #include "math.h" using namespace core; diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.cpp similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.cpp index 473494d516a..478d9e9ad04 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.h b/ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.h similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.h rename to ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.h index caa02f649e3..0f7e022b3cf 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/rectlatlng.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/rectlatlng.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.cpp similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.cpp index d54198360d7..fe175d91d81 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.h b/ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.h rename to ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.h index 587004db490..5e51c3535f1 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/sizelatlng.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/sizelatlng.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/tile.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/tile.cpp similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/tile.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/tile.cpp index aa2ff42bdd6..c8c3a36ec42 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/tile.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/tile.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/tile.h b/ground/gcs/src/libs/tlmapcontrol/internals/tile.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/tile.h rename to ground/gcs/src/libs/tlmapcontrol/internals/tile.h index bba263899a7..51f8c202fc6 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/tile.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/tile.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.cpp b/ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.cpp similarity index 96% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.cpp rename to ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.cpp index 40d39612833..85f7780e7b2 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.cpp @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.h b/ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.h rename to ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.h index f6f6dc7db13..d3945eba91e 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/tilematrix.h +++ b/ground/gcs/src/libs/tlmapcontrol/internals/tilematrix.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/configuration.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/configuration.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/configuration.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/configuration.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/configuration.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/configuration.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/configuration.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/configuration.h index 86ad72bbaa4..976e027d4ea 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/configuration.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/configuration.h @@ -6,7 +6,7 @@ * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * @brief A class that centralizes most of the mapcontrol configurations * @see The GNU Public License (GPL) Version 3 -* @defgroup OPMapWidget +* @defgroup TLMapWidget * @{ * *****************************************************************************/ @@ -36,6 +36,8 @@ #include "../core/tlmaps.h" #include "../core/accessmode.h" #include "../core/cache.h" +#include "../core/corecommon.h" + namespace mapcontrol { @@ -44,7 +46,7 @@ namespace mapcontrol * * @class Configuration configuration.h "configuration.h" */ -class Configuration +class TLMAPWIDGET_EXPORT Configuration { public: Configuration(); diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/gpsitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/gpsitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/gpsitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/gpsitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/gpsitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/gpsitem.h similarity index 98% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/gpsitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/gpsitem.h index 22ad8e312b4..b9d097b9e04 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/gpsitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/gpsitem.h @@ -35,6 +35,7 @@ #include #include "trailitem.h" #include "traillineitem.h" +#include "../core/corecommon.h" namespace mapcontrol { @@ -45,7 +46,7 @@ namespace mapcontrol * * @class UAVItem gpsitem.h "mapwidget/gpsitem.h" */ - class GPSItem: public MapPointItem + class TLMAPWIDGET_EXPORT GPSItem: public MapPointItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/homeitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/homeitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/homeitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/homeitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/homeitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/homeitem.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/homeitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/homeitem.h index 64de8332003..cadeb6fee7d 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/homeitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/homeitem.h @@ -30,11 +30,12 @@ #include "mappointitem.h" +#include "../core/corecommon.h" namespace mapcontrol { - class HomeItem:public MapPointItem + class TLMAPWIDGET_EXPORT HomeItem:public MapPointItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) @@ -59,7 +60,6 @@ namespace mapcontrol TLMapWidget* mapwidget; QPixmap pic; core::Point localposition; - internals::PointLatLng coord; bool showsafearea; bool toggleRefresh; int safearea; diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/EasystarBlue.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/EasystarBlue.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/EasystarBlue.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/EasystarBlue.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplane.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplane.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplane.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplane.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplane.svg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplane.svg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplane.svg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplane.svg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplanepip.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplanepip.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/airplanepip.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/airplanepip.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/bigMarkerGreen.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/bigMarkerGreen.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/bigMarkerGreen.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/bigMarkerGreen.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/compass.svg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/compass.svg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/compass.svg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/compass.svg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/dragons1.jpg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/dragons1.jpg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/dragons1.jpg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/dragons1.jpg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/dragons2.jpeg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/dragons2.jpeg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/dragons2.jpeg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/dragons2.jpeg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home.svg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home.svg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home.svg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home.svg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home2.svg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home2.svg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/home2.svg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/home2.svg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/mapquad.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/mapquad.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/mapquad.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/mapquad.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/marker.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/marker.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/marker.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/marker.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker1.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker1.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker1.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker1.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker2.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker2.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker2.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker2.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker3.png b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker3.png similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/waypoint_marker3.png rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/waypoint_marker3.png diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/wind_compass.svg b/ground/gcs/src/libs/tlmapcontrol/mapwidget/images/wind_compass.svg similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/images/wind_compass.svg rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/images/wind_compass.svg diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapcircle.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapcircle.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapcircle.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapcircle.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapcircle.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapcircle.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapcircle.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapcircle.h index 3e399dece5c..ca707d382b2 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapcircle.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapcircle.h @@ -29,13 +29,14 @@ #define MAPCIRCLE_H #include "mappointitem.h" +#include "../core/corecommon.h" namespace mapcontrol { class HomeItem; -class MapCircle: public QObject, public QGraphicsEllipseItem +class TLMAPWIDGET_EXPORT MapCircle: public QObject, public QGraphicsEllipseItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapgraphicitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapgraphicitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapgraphicitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapgraphicitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapgraphicitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapgraphicitem.h similarity index 98% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapgraphicitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapgraphicitem.h index e1fcca40a6d..d2966d9262c 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapgraphicitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapgraphicitem.h @@ -38,6 +38,7 @@ #include #include #include +#include "../core/corecommon.h" namespace mapcontrol { @@ -48,7 +49,7 @@ namespace mapcontrol * * @class MapGraphicItem mapgraphicitem.h "mapgraphicitem.h" */ - class MapGraphicItem:public QObject,public QGraphicsItem + class TLMAPWIDGET_EXPORT MapGraphicItem:public QObject,public QGraphicsItem { friend class mapcontrol::TLMapWidget; Q_OBJECT diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapline.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapline.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapline.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapline.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapline.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapline.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapline.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapline.h index b38bb0fe86c..fa34a9384b3 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapline.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapline.h @@ -30,12 +30,13 @@ #include "mapgraphicitem.h" #include "mappointitem.h" +#include "../core/corecommon.h" namespace mapcontrol { class HomeItem; -class MapLine : public QObject, public QGraphicsLineItem +class TLMAPWIDGET_EXPORT MapLine : public QObject, public QGraphicsLineItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mappointitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mappointitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mappointitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mappointitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mappointitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mappointitem.h similarity index 92% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mappointitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mappointitem.h index fd9e98da5ba..0c02d7ddf09 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mappointitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mappointitem.h @@ -37,11 +37,12 @@ #include "../internals/pointlatlng.h" #include "mapgraphicitem.h" #include "physical_constants.h" +#include "../core/corecommon.h" namespace mapcontrol { -struct distBearingAltitude +struct TLMAPWIDGET_EXPORT distBearingAltitude { double distance; double bearing; @@ -53,7 +54,7 @@ struct distBearingAltitude * * @class MapPointItem mappointitem.h "mappointitem.h" */ -class MapPointItem: public QObject,public QGraphicsItem +class TLMAPWIDGET_EXPORT MapPointItem: public QObject,public QGraphicsItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapresources.qrc b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapresources.qrc similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapresources.qrc rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapresources.qrc diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.h similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.h diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.ui b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.ui similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripform.ui rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripform.ui diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripper.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripper.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripper.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripper.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripper.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripper.h similarity index 93% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripper.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripper.h index 7c397c7c248..9b89f192df3 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapripper.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/mapripper.h @@ -33,9 +33,11 @@ #include "mapripform.h" #include #include +#include "../core/corecommon.h" + namespace mapcontrol { - class MapRipper:public QThread + class TLMAPWIDGET_EXPORT MapRipper:public QThread { Q_OBJECT public: diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.cpp similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.cpp index f4457a154cd..8e2aa2ded54 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.cpp +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.cpp @@ -136,7 +136,7 @@ namespace mapcontrol } /** - * @brief OPMapWidget::WPCurveCreate Create a curve from one waypoint to another with specified radius + * @brief TLMapWidget::WPCurveCreate Create a curve from one waypoint to another with specified radius * @param start The starting waypoint * @param dest The ending waypoint * @param radius The radius to use connecting the two @@ -540,7 +540,7 @@ namespace mapcontrol ////////////////////////////////////////////// /** - * @brief OPMapWidget::SetShowCompassRose Shows the compass rose on the map. + * @brief TLMapWidget::SetShowCompassRose Shows the compass rose on the map. * @param value If true the compass rose is enabled. If false it is disabled. */ void TLMapWidget::SetShowCompassRose(const bool &value) @@ -565,7 +565,7 @@ namespace mapcontrol } /** - * @brief OPMapWidget::SetShowWindCompass Shows the compass rose on the map. + * @brief TLMapWidget::SetShowWindCompass Shows the compass rose on the map. * @param value If true the compass is enabled. If false it is disabled. */ void TLMapWidget::SetShowWindCompass(const bool &value) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.h similarity index 99% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.h index ea45d108279..bdd8cdcda68 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/tlmapwidget.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/tlmapwidget.h @@ -45,6 +45,7 @@ #include "mapcircle.h" #include "waypointcurve.h" #include "waypointitem.h" +#include "../core/corecommon.h" #include namespace mapcontrol @@ -153,7 +154,7 @@ namespace mapcontrol static QStringList UAVTrailTypes(){return UAVTrailType::TypesList();} }; - class TLMapWidget:public QGraphicsView + class TLMAPWIDGET_EXPORT TLMapWidget:public QGraphicsView { Q_OBJECT @@ -175,7 +176,6 @@ namespace mapcontrol */ TLMapWidget(QWidget *parent=0,Configuration *config=new Configuration); ~TLMapWidget(); - /** * @brief Returns true if map is showing gridlines * diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/trailitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/trailitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/trailitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/trailitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/trailitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/trailitem.h similarity index 92% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/trailitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/trailitem.h index 5ae28cd9f0a..f1bd4979428 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/trailitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/trailitem.h @@ -34,11 +34,12 @@ #include "../internals/pointlatlng.h" #include #include "mapgraphicitem.h" +#include "../core/corecommon.h" namespace mapcontrol { - class TrailItem:public QObject,public QGraphicsItem + class TLMAPWIDGET_EXPORT TrailItem:public QObject,public QGraphicsItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/traillineitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/traillineitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/traillineitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/traillineitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/traillineitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/traillineitem.h similarity index 91% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/traillineitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/traillineitem.h index 57ebeeede65..86f7218bac3 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/traillineitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/traillineitem.h @@ -34,11 +34,12 @@ #include "../internals/pointlatlng.h" #include #include "mapgraphicitem.h" +#include "../core/corecommon.h" namespace mapcontrol { - class TrailLineItem:public QObject,public QGraphicsLineItem + class TLMAPWIDGET_EXPORT TrailLineItem:public QObject,public QGraphicsLineItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/uavitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavitem.h similarity index 98% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/uavitem.h index 239efa37775..43fadc548a5 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavitem.h @@ -35,6 +35,7 @@ #include "uavtrailtype.h" #include "trailitem.h" #include "traillineitem.h" +#include "../core/corecommon.h" namespace mapcontrol { @@ -45,7 +46,7 @@ namespace mapcontrol * * @class UAVItem uavitem.h "mapwidget/uavitem.h" */ - class UAVItem: public MapPointItem + class TLMAPWIDGET_EXPORT UAVItem: public MapPointItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavmapfollowtype.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavmapfollowtype.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavmapfollowtype.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/uavmapfollowtype.h index 106b4fe35d4..7965b6a4199 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavmapfollowtype.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavmapfollowtype.h @@ -32,8 +32,10 @@ #include #include #include +#include "../core/corecommon.h" + namespace mapcontrol { - class UAVMapFollowType:public QObject + class TLMAPWIDGET_EXPORT UAVMapFollowType:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavtrailtype.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavtrailtype.h similarity index 94% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavtrailtype.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/uavtrailtype.h index 65ac89fe9b3..c3ed962bd11 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/uavtrailtype.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/uavtrailtype.h @@ -32,8 +32,10 @@ #include #include #include +#include "../core/corecommon.h" + namespace mapcontrol { - class UAVTrailType:public QObject + class TLMAPWIDGET_EXPORT UAVTrailType:public QObject { Q_OBJECT Q_ENUMS(Types) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointcurve.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointcurve.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointcurve.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointcurve.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointcurve.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointcurve.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointcurve.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointcurve.h index bee93f06ae8..222db5f7ab3 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointcurve.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointcurve.h @@ -28,6 +28,7 @@ #define WAYPOINTCURVE_H #include "waypointitem.h" +#include "../core/corecommon.h" namespace mapcontrol { @@ -37,7 +38,7 @@ namespace mapcontrol * radius and direction of curvature. It will display a red straight line if the * radius is insufficient to connect the two waypoints */ -class WayPointCurve:public QObject,public QGraphicsEllipseItem +class TLMAPWIDGET_EXPORT WayPointCurve:public QObject,public QGraphicsEllipseItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointitem.cpp b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointitem.cpp similarity index 100% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointitem.cpp rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointitem.cpp diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointitem.h b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointitem.h similarity index 95% rename from ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointitem.h rename to ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointitem.h index 30216dfc505..0cefc36ceba 100644 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/waypointitem.h +++ b/ground/gcs/src/libs/tlmapcontrol/mapwidget/waypointitem.h @@ -29,6 +29,7 @@ #define WAYPOINTITEM_H #include "mappointitem.h" +#include "../core/corecommon.h" namespace mapcontrol { @@ -38,7 +39,7 @@ class HomeItem; * * @class WayPointItem waypointitem.h "waypointitem.h" */ -class WayPointItem: public MapPointItem +class TLMAPWIDGET_EXPORT WayPointItem: public MapPointItem { Q_OBJECT Q_INTERFACES(QGraphicsItem) diff --git a/ground/gcs/src/libs/tlmapcontrol/src/common.pri b/ground/gcs/src/libs/tlmapcontrol/src/common.pri deleted file mode 100644 index be48b5c3a4a..00000000000 --- a/ground/gcs/src/libs/tlmapcontrol/src/common.pri +++ /dev/null @@ -1,11 +0,0 @@ -DESTDIR = ../build - -QT += network -QT += sql -QT += xml -CONFIG += staticlib -TEMPLATE = lib -UI_DIR = uics -MOC_DIR = mocs -OBJECTS_DIR = objs -INCLUDEPATH *=../../../../libs/ diff --git a/ground/gcs/src/libs/tlmapcontrol/src/core/core.pro b/ground/gcs/src/libs/tlmapcontrol/src/core/core.pro deleted file mode 100644 index 384e7c02d92..00000000000 --- a/ground/gcs/src/libs/tlmapcontrol/src/core/core.pro +++ /dev/null @@ -1,42 +0,0 @@ -include (../common.pri) - -QT += widgets - -SOURCES += \ - pureimagecache.cpp \ - pureimage.cpp \ - rawtile.cpp \ - memorycache.cpp \ - cache.cpp \ - languagetype.cpp \ - providerstrings.cpp \ - cacheitemqueue.cpp \ - tilecachequeue.cpp \ - alllayersoftype.cpp \ - urlfactory.cpp \ - point.cpp \ - size.cpp \ - kibertilecache.cpp \ - diagnostics.cpp \ - tlmaps.cpp -HEADERS += \ - size.h \ - maptype.h \ - pureimagecache.h \ - pureimage.h \ - rawtile.h \ - memorycache.h \ - cache.h \ - accessmode.h \ - languagetype.h \ - providerstrings.h \ - cacheitemqueue.h \ - tilecachequeue.h \ - alllayersoftype.h \ - urlfactory.h \ - geodecoderstatus.h \ - point.h \ - kibertilecache.h \ - debugheader.h \ - diagnostics.h \ - tlmaps.h diff --git a/ground/gcs/src/libs/tlmapcontrol/src/internals/internals.pro b/ground/gcs/src/libs/tlmapcontrol/src/internals/internals.pro deleted file mode 100644 index 21ce6b4b692..00000000000 --- a/ground/gcs/src/libs/tlmapcontrol/src/internals/internals.pro +++ /dev/null @@ -1,35 +0,0 @@ -include (../common.pri) -HEADERS += core.h \ - mousewheelzoomtype.h \ - rectangle.h \ - tile.h \ - tilematrix.h \ - loadtask.h \ - copyrightstrings.h \ - pureprojection.h \ - pointlatlng.h \ - rectlatlng.h \ - sizelatlng.h \ - debugheader.h -SOURCES += core.cpp \ - rectangle.cpp \ - tile.cpp \ - tilematrix.cpp \ - pureprojection.cpp \ - rectlatlng.cpp \ - sizelatlng.cpp \ - pointlatlng.cpp \ - loadtask.cpp \ - mousewheelzoomtype.cpp -HEADERS += ./projections/lks94projection.h \ - ./projections/mercatorprojection.h \ - ./projections/mercatorprojectionyandex.h \ - ./projections/platecarreeprojection.h \ - ./projections/platecarreeprojectionpergo.h -SOURCES += ./projections/lks94projection.cpp \ - ./projections/mercatorprojection.cpp \ - ./projections/mercatorprojectionyandex.cpp \ - ./projections/platecarreeprojection.cpp \ - ./projections/platecarreeprojectionpergo.cpp -LIBS += -L../build \ - -lcore diff --git a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapwidget.pro b/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapwidget.pro deleted file mode 100644 index 0cadfd4dced..00000000000 --- a/ground/gcs/src/libs/tlmapcontrol/src/mapwidget/mapwidget.pro +++ /dev/null @@ -1,61 +0,0 @@ -TEMPLATE = lib -TARGET = opmapwidget -DEFINES += OPMAPWIDGET_LIBRARY -include(../../../../taulabslibrary.pri) - -# DESTDIR = ../build -SOURCES += mapgraphicitem.cpp \ - configuration.cpp \ - mappointitem.cpp \ - waypointitem.cpp \ - uavitem.cpp \ - gpsitem.cpp \ - trailitem.cpp \ - homeitem.cpp \ - mapripform.cpp \ - mapripper.cpp \ - traillineitem.cpp \ - mapline.cpp \ - mapcircle.cpp \ - waypointcurve.cpp \ - tlmapwidget.cpp - -LIBS += -L../build \ - -lcore \ - -linternals \ - -lcore - -# order of linking matters -include(../../../utils/utils.pri) - -POST_TARGETDEPS += ../build/libcore.a -POST_TARGETDEPS += ../build/libinternals.a - -HEADERS += mapgraphicitem.h \ - configuration.h \ - mappointitem.h \ - waypointitem.h \ - uavitem.h \ - gpsitem.h \ - uavmapfollowtype.h \ - uavtrailtype.h \ - trailitem.h \ - homeitem.h \ - mapripform.h \ - mapripper.h \ - traillineitem.h \ - mapline.h \ - mapcircle.h \ - waypointcurve.h \ - tlmapwidget.h - -QT += network -QT += sql -QT += svg -QT += xml -QT += widgets - -RESOURCES += mapresources.qrc - -FORMS += \ - mapripform.ui diff --git a/ground/gcs/src/libs/tlmapcontrol/src/src.pro b/ground/gcs/src/libs/tlmapcontrol/src/src.pro deleted file mode 100644 index d9f3b26f067..00000000000 --- a/ground/gcs/src/libs/tlmapcontrol/src/src.pro +++ /dev/null @@ -1,6 +0,0 @@ -TEMPLATE = subdirs -CONFIG += ordered -SUBDIRS = core -SUBDIRS += internals -SUBDIRS += mapwidget -QT += widgets diff --git a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.h b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.h index a3f95e7fc32..b5e22d0c4ab 100644 --- a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.h +++ b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.h @@ -1,6 +1,6 @@ -#ifndef OPMAP_CONTROL_H_ -#define OPMAP_CONTROL_H_ -#include "src/mapwidget/tlmapwidget.h" +#ifndef TLMAP_CONTROL_H_ +#define TLMAP_CONTROL_H_ +#include "mapwidget/tlmapwidget.h" namespace mapcontrol { struct customData diff --git a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pri b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pri index f6ea6004b5d..37ea4e8da42 100644 --- a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pri +++ b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pri @@ -1 +1 @@ -LIBS *= -l$$qtLibraryName(opmapwidget) +LIBS *= -l$$qtLibraryName(tlmapwidget) diff --git a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pro b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pro index dee478c28b6..b758c0badaf 100644 --- a/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pro +++ b/ground/gcs/src/libs/tlmapcontrol/tlmapcontrol.pro @@ -1,4 +1,122 @@ -TEMPLATE = subdirs +TEMPLATE = lib +TARGET = tlmapwidget +DEFINES += TLMAPWIDGET_LIBRARY +include(../../taulabslibrary.pri) +SOURCES += mapwidget/mapgraphicitem.cpp \ + mapwidget/configuration.cpp \ + mapwidget/mappointitem.cpp \ + mapwidget/waypointitem.cpp \ + mapwidget/uavitem.cpp \ + mapwidget/gpsitem.cpp \ + mapwidget/trailitem.cpp \ + mapwidget/homeitem.cpp \ + mapwidget/mapripform.cpp \ + mapwidget/mapripper.cpp \ + mapwidget/traillineitem.cpp \ + mapwidget/mapline.cpp \ + mapwidget/mapcircle.cpp \ + mapwidget/waypointcurve.cpp \ + mapwidget/tlmapwidget.cpp \ + core/pureimagecache.cpp \ + core/pureimage.cpp \ + core/rawtile.cpp \ + core/memorycache.cpp \ + core/cache.cpp \ + core/languagetype.cpp \ + core/providerstrings.cpp \ + core/cacheitemqueue.cpp \ + core/tilecachequeue.cpp \ + core/alllayersoftype.cpp \ + core/urlfactory.cpp \ + core/point.cpp \ + core/size.cpp \ + core/kibertilecache.cpp \ + core/diagnostics.cpp \ + core/tlmaps.cpp \ + internals/core.cpp \ + internals/rectangle.cpp \ + internals/tile.cpp \ + internals/tilematrix.cpp \ + internals/pureprojection.cpp \ + internals/rectlatlng.cpp \ + internals/sizelatlng.cpp \ + internals/pointlatlng.cpp \ + internals/loadtask.cpp \ + internals/mousewheelzoomtype.cpp \ + internals/projections/lks94projection.cpp \ + internals/projections/mercatorprojection.cpp \ + internals/projections/mercatorprojectionyandex.cpp \ + internals/projections/platecarreeprojection.cpp \ + internals/projections/platecarreeprojectionpergo.cpp + +# order of linking matters +include(../utils/utils.pri) + +HEADERS += mapwidget/mapgraphicitem.h \ + mapwidget/configuration.h \ + mapwidget/mappointitem.h \ + mapwidget/waypointitem.h \ + mapwidget/uavitem.h \ + mapwidget/gpsitem.h \ + mapwidget/uavmapfollowtype.h \ + mapwidget/uavtrailtype.h \ + mapwidget/trailitem.h \ + mapwidget/homeitem.h \ + mapwidget/mapripform.h \ + mapwidget/mapripper.h \ + mapwidget/traillineitem.h \ + mapwidget/mapline.h \ + mapwidget/mapcircle.h \ + mapwidget/waypointcurve.h \ + mapwidget/tlmapwidget.h \ + core/size.h \ + core/maptype.h \ + core/pureimagecache.h \ + core/pureimage.h \ + core/rawtile.h \ + core/memorycache.h \ + core/cache.h \ + core/accessmode.h \ + core/languagetype.h \ + core/providerstrings.h \ + core/cacheitemqueue.h \ + core/tilecachequeue.h \ + core/alllayersoftype.h \ + core/urlfactory.h \ + core/geodecoderstatus.h \ + core/point.h \ + core/kibertilecache.h \ + core/debugheader.h \ + core/diagnostics.h \ + core/tlmaps.h \ + internals/core.h \ + internals/mousewheelzoomtype.h \ + internals/rectangle.h \ + internals/tile.h \ + internals/tilematrix.h \ + internals/loadtask.h \ + internals/copyrightstrings.h \ + internals/pureprojection.h \ + internals/pointlatlng.h \ + internals/rectlatlng.h \ + internals/sizelatlng.h \ + internals/debugheader.h \ + internals/projections/lks94projection.h \ + internals/projections/mercatorprojection.h \ + internals/projections/mercatorprojectionyandex.h \ + internals/projections/platecarreeprojection.h \ + internals/projections/platecarreeprojectionpergo.h \ + core/corecommon.h + +QT += network +QT += sql +QT += svg +QT += xml +QT += widgets + +RESOURCES += mapwidget/mapresources.qrc + +FORMS += \ + mapwidget/mapripform.ui -SUBDIRS = src \ diff --git a/ground/gcs/src/libs/utils/coordinateconversions.cpp b/ground/gcs/src/libs/utils/coordinateconversions.cpp index 828a40742f1..04d96b60850 100644 --- a/ground/gcs/src/libs/utils/coordinateconversions.cpp +++ b/ground/gcs/src/libs/utils/coordinateconversions.cpp @@ -26,14 +26,14 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - +#define _USE_MATH_DEFINES +#include #include "coordinateconversions.h" #include #include #include -#define RAD2DEG (180.0/M_PI) -#define DEG2RAD (M_PI/180.0) +#include namespace Utils { diff --git a/ground/gcs/src/libs/utils/filenamevalidatinglineedit.cpp b/ground/gcs/src/libs/utils/filenamevalidatinglineedit.cpp index 2111f0afea6..1a7409c7ea0 100644 --- a/ground/gcs/src/libs/utils/filenamevalidatinglineedit.cpp +++ b/ground/gcs/src/libs/utils/filenamevalidatinglineedit.cpp @@ -81,7 +81,7 @@ void FileNameValidatingLineEdit::setAllowDirectories(bool v) #endif static const char *notAllowedCharsSubDir = "?:&*\"|#%<> "; -static const char *notAllowedCharsNoSubDir = "?:&*\"|#%<> "SLASHES; +static const char *notAllowedCharsNoSubDir = "?:&*\"|#%<> " SLASHES; static const char *notAllowedSubStrings[] = {".."}; diff --git a/ground/gcs/src/libs/utils/utils.pro b/ground/gcs/src/libs/utils/utils.pro index 6a099a5d6ec..cc22eede9c0 100644 --- a/ground/gcs/src/libs/utils/utils.pro +++ b/ground/gcs/src/libs/utils/utils.pro @@ -1,6 +1,8 @@ TEMPLATE = lib TARGET = Utils -QMAKE_CXXFLAGS += -Wno-sign-compare + +!win32-msvc*:QMAKE_CXXFLAGS += -Wno-sign-compare +win32: QMAKE_CXXFLAGS_RELEASE -= -Zc:strictStrings QT += gui \ network \ diff --git a/ground/gcs/src/libs/utils/worldmagmodel.cpp b/ground/gcs/src/libs/utils/worldmagmodel.cpp index 78f7dc67f67..6ec7215a522 100644 --- a/ground/gcs/src/libs/utils/worldmagmodel.cpp +++ b/ground/gcs/src/libs/utils/worldmagmodel.cpp @@ -44,6 +44,8 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#define _USE_MATH_DEFINES +#include #include "worldmagmodel.h" #include diff --git a/ground/gcs/src/libs/utils/xmlconfig.cpp b/ground/gcs/src/libs/utils/xmlconfig.cpp index 0bdd7513059..06923add3f5 100644 --- a/ground/gcs/src/libs/utils/xmlconfig.cpp +++ b/ground/gcs/src/libs/utils/xmlconfig.cpp @@ -39,6 +39,7 @@ #include #include #include +#include #define NUM_PREFIX "arr_" diff --git a/ground/gcs/src/plugins/antennatrack/AntennaTrack.pluginspec b/ground/gcs/src/plugins/antennatrack/AntennaTrack.pluginspec deleted file mode 100644 index 7ba3b76a0b9..00000000000 --- a/ground/gcs/src/plugins/antennatrack/AntennaTrack.pluginspec +++ /dev/null @@ -1,11 +0,0 @@ - - Tau Labs - (C) 2012 SK - The GNU Public License (GPL) Version 3 - Plugin for antenna tracker - http://taulabs.org - - - - - diff --git a/ground/gcs/src/plugins/antennatrack/antennatrack.pro b/ground/gcs/src/plugins/antennatrack/antennatrack.pro deleted file mode 100644 index 825975ce654..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrack.pro +++ /dev/null @@ -1,26 +0,0 @@ -TEMPLATE = lib -TARGET = AntennaTrack -QT += serialport -include(../../taulabsgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(antennatrack_dependencies.pri) -include(../../libs/qwt/qwt.pri) -HEADERS += antennatrackplugin.h -HEADERS += gpsparser.h -HEADERS += telemetryparser.h -HEADERS += antennatrackgadget.h -HEADERS += antennatrackwidget.h -HEADERS += antennatrackgadgetfactory.h -HEADERS += antennatrackgadgetconfiguration.h -HEADERS += antennatrackgadgetoptionspage.h -SOURCES += antennatrackplugin.cpp -SOURCES += gpsparser.cpp -SOURCES += telemetryparser.cpp -SOURCES += antennatrackgadget.cpp -SOURCES += antennatrackgadgetfactory.cpp -SOURCES += antennatrackwidget.cpp -SOURCES += antennatrackgadgetconfiguration.cpp -SOURCES += antennatrackgadgetoptionspage.cpp -OTHER_FILES += AntennaTrack.pluginspec -FORMS += antennatrackgadgetoptionspage.ui -FORMS += antennatrackwidget.ui diff --git a/ground/gcs/src/plugins/antennatrack/antennatrack_dependencies.pri b/ground/gcs/src/plugins/antennatrack/antennatrack_dependencies.pri deleted file mode 100644 index ad54b007373..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrack_dependencies.pri +++ /dev/null @@ -1,3 +0,0 @@ -include(../../plugins/uavobjects/uavobjects.pri) -#include(../../plugins/coreplugin/coreplugin.pri) -#include(../../libs/utils/utils.pri) diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadget.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackgadget.cpp deleted file mode 100644 index 0c65cebf2bf..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadget.cpp +++ /dev/null @@ -1,157 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTracgadget.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "antennatrackgadget.h" -#include "antennatrackwidget.h" -#include "antennatrackgadgetconfiguration.h" -#include "../gpsdisplay/gpsdisplaygadgetconfiguration.h" /* For struct PortSettings declaration */ - - -AntennaTrackGadget::AntennaTrackGadget(QString classId, AntennaTrackWidget *widget, QWidget *parent) : - IUAVGadget(classId, parent), - m_widget(widget), - connected(false) -{ - connect(m_widget->connectButton, SIGNAL(clicked(bool)), this,SLOT(onConnect())); - connect(m_widget->disconnectButton, SIGNAL(clicked(bool)), this,SLOT(onDisconnect())); -} - -AntennaTrackGadget::~AntennaTrackGadget() -{ -} - -/* - This is called when a configuration is loaded, and updates the plugin's settings. - Careful: the plugin is already drawn before the loadConfiguration method is called the - first time, so you have to be careful not to assume all the plugin values are initialized - the first time you use them - */ -void AntennaTrackGadget::loadConfiguration(IUAVGadgetConfiguration* config) -{ - // Delete the (old)port, this also closes it. - if(port) { - delete port; - } - - // Delete the (old)parser, this also disconnects all signals. - if(parser) { - delete parser; - } - - AntennaTrackGadgetConfiguration *AntennaTrackConfig = qobject_cast< AntennaTrackGadgetConfiguration*>(config); - - PortSettings portsettings; - portsettings.BaudRate=AntennaTrackConfig->speed(); - portsettings.DataBits=AntennaTrackConfig->dataBits(); - portsettings.FlowControl=AntennaTrackConfig->flow(); - portsettings.Parity=AntennaTrackConfig->parity(); - portsettings.StopBits=AntennaTrackConfig->stopBits(); - portsettings.Timeout_Millisec=AntennaTrackConfig->timeOut(); - - // In case we find no port, buttons disabled - m_widget->connectButton->setEnabled(false); - m_widget->disconnectButton->setEnabled(false); - - QList ports = QSerialPortInfo::availablePorts(); - foreach( QSerialPortInfo nport, ports ) { - if (nport.portName() == AntennaTrackConfig->port()) { - qDebug() << "Using Serial port"; - //parser = new NMEAParser(); - -#ifdef Q_OS_WIN - port=new QSerialPort(nport); -#else - port=new QSerialPort(nport); -#endif - m_widget->setPort(port); - m_widget->connectButton->setEnabled(true); - m_widget->disconnectButton->setEnabled(false); - m_widget->connectButton->setHidden(false); - m_widget->disconnectButton->setHidden(false); - - connect(port, SIGNAL(readyRead()), this, SLOT(onDataAvailable())); - } - } - m_widget->dataStreamGroupBox->setHidden(false); - qDebug() << "Using Telemetry parser"; - parser = new TelemetryParser(); - - connect(parser, SIGNAL(position(double,double,double)), m_widget,SLOT(setPosition(double,double,double))); - connect(parser, SIGNAL(home(double,double,double)), m_widget,SLOT(setHomePosition(double,double,double))); - connect(parser, SIGNAL(packet(QString)), m_widget, SLOT(dumpPacket(QString))); -} - -void AntennaTrackGadget::onConnect() { - m_widget->textBrowser->append(QString("Connecting to Tracker ...\n")); - // TODO: Somehow mark that we're running, and disable connect button while so? - - if (port) { - qDebug() << "Opening: " << port->portName() << "."; - bool isOpen = port->open(QIODevice::ReadWrite); - qDebug() << "Open: " << isOpen; - if(isOpen) { - m_widget->connectButton->setEnabled(false); - m_widget->disconnectButton->setEnabled(true); - } - } else { - qDebug() << "Port undefined or invalid."; - } - -} - -void AntennaTrackGadget::onDisconnect() { - if (port) { - qDebug() << "Closing: " << port->portName() << "."; - port->close(); - m_widget->connectButton->setEnabled(true); - m_widget->disconnectButton->setEnabled(false); - } else { - qDebug() << "Port undefined or invalid."; - } -} - -void AntennaTrackGadget::onDataAvailable() { - int avail = port->bytesAvailable(); - if( avail > 0 ) { - QByteArray serialData; - serialData.resize(avail); - int bytesRead = port->read(serialData.data(), serialData.size()); - if( bytesRead > 0 ) { - processNewSerialData(serialData); - } - } -} - -void AntennaTrackGadget::processNewSerialData(QByteArray serialData) { - int dataLength = serialData.size(); - const char* data = serialData.constData(); - m_widget->textBrowser->append(QString(serialData)); - for(int pos = 0; pos < dataLength; pos++) { - //parser->processInputStream(data[pos]); - } -} diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadget.h b/ground/gcs/src/plugins/antennatrack/antennatrackgadget.h deleted file mode 100644 index 33d38f249c6..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadget.h +++ /dev/null @@ -1,73 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTrackgadget.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ANTENNATRACKGADGET_H_ -#define ANTENNATRACKGADGET_H_ - -#include -#include -#include -#include "antennatrackwidget.h" -#include "telemetryparser.h" - -class IUAVGadget; -class QWidget; -class QString; -class AntennaTrackWidget; - -using namespace Core; - -class AntennaTrackGadget : public Core::IUAVGadget -{ - Q_OBJECT -public: - AntennaTrackGadget(QString classId, AntennaTrackWidget *widget, QWidget *parent = 0); - ~AntennaTrackGadget(); - - QWidget *widget() { return m_widget; } - - // void setMode(QString mode); // Either UAVTalk or serial port - - void loadConfiguration(IUAVGadgetConfiguration* config); -public slots: - void onConnect(); - void onDisconnect(); - -private slots: - void onDataAvailable(); - -private: - QPointer m_widget; - QPointer port; - QPointer parser; - bool connected; - void processNewSerialData(QByteArray serialData); -}; - - -#endif // ANTENNATRACKGADGET_H_ diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.cpp deleted file mode 100644 index 581f5adb1b7..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.cpp +++ /dev/null @@ -1,108 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTracgadgetconfiguration.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "antennatrackgadgetconfiguration.h" -#include - -/** - * Loads a saved configuration or defaults if non exist. - * - */ -AntennaTrackGadgetConfiguration::AntennaTrackGadgetConfiguration(QString classId, QSettings* qSettings, QObject *parent) : - IUAVGadgetConfiguration(classId, parent), - m_connectionMode("Serial"), - m_defaultPort("Unknown"), - m_defaultSpeed(QSerialPort::Baud4800), - m_defaultDataBits(QSerialPort::Data8), - m_defaultFlow(QSerialPort::NoFlowControl), - m_defaultParity(QSerialPort::NoParity), - m_defaultStopBits(QSerialPort::OneStop), - m_defaultTimeOut(5000) -{ - //if a saved configuration exists load it - if(qSettings != 0) { - QSerialPort::BaudRate speed; - QSerialPort::DataBits databits; - QSerialPort::FlowControl flow; - QSerialPort::Parity parity; - QSerialPort::StopBits stopbits; - - int ispeed = qSettings->value("defaultSpeed").toInt(); - int idatabits = qSettings->value("defaultDataBits").toInt(); - int iflow = qSettings->value("defaultFlow").toInt(); - int iparity = qSettings->value("defaultParity").toInt(); - int istopbits = qSettings->value("defaultStopBits").toInt(); - QString port = qSettings->value("defaultPort").toString(); - QString conMode = qSettings->value("connectionMode").toString(); - - databits = (QSerialPort::DataBits) idatabits; - flow = (QSerialPort::FlowControl)iflow; - parity = (QSerialPort::Parity)iparity; - stopbits = (QSerialPort::StopBits)istopbits; - speed = (QSerialPort::BaudRate)ispeed; - m_defaultPort = port; - m_defaultSpeed = speed; - m_defaultDataBits = databits; - m_defaultFlow = flow; - m_defaultParity = parity; - m_defaultStopBits = stopbits; - m_connectionMode = conMode; - } -} - -/** - * Clones a configuration. - * - */ -IUAVGadgetConfiguration *AntennaTrackGadgetConfiguration::clone() -{ - AntennaTrackGadgetConfiguration *m = new AntennaTrackGadgetConfiguration(this->classId()); - - m->m_defaultSpeed = m_defaultSpeed; - m->m_defaultDataBits = m_defaultDataBits; - m->m_defaultFlow = m_defaultFlow; - m->m_defaultParity = m_defaultParity; - m->m_defaultStopBits = m_defaultStopBits; - m->m_defaultPort = m_defaultPort; - m->m_connectionMode = m_connectionMode; - return m; -} - -/** - * Saves a configuration. - * - */ -void AntennaTrackGadgetConfiguration::saveConfig(QSettings* settings) const { - settings->setValue("defaultSpeed", m_defaultSpeed); - settings->setValue("defaultDataBits", m_defaultDataBits); - settings->setValue("defaultFlow", m_defaultFlow); - settings->setValue("defaultParity", m_defaultParity); - settings->setValue("defaultStopBits", m_defaultStopBits); - settings->setValue("defaultPort", m_defaultPort); - settings->setValue("connectionMode", m_connectionMode); -} diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.h b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.h deleted file mode 100644 index 57f5b50cd2e..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetconfiguration.h +++ /dev/null @@ -1,79 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTracgadgetconfiguration.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ANTENNATRACKGADGETCONFIGURATION_H -#define ANTENNATRACKGADGETCONFIGURATION_H - -#include -#include - -using namespace Core; - -class AntennaTrackGadgetConfiguration : public IUAVGadgetConfiguration -{ - Q_OBJECT - public: - explicit AntennaTrackGadgetConfiguration(QString classId, QSettings* qSettings = 0, QObject *parent = 0); - - void setConnectionMode(QString mode) { m_connectionMode = mode; } - QString connectionMode() { return m_connectionMode; } - - //set port configuration functions - void setSpeed(QSerialPort::BaudRate speed) {m_defaultSpeed=speed;} - void setDataBits(QSerialPort::DataBits databits) {m_defaultDataBits=databits;} - void setFlow(QSerialPort::FlowControl flow) {m_defaultFlow=flow;} - void setParity(QSerialPort::Parity parity) {m_defaultParity=parity;} - void setStopBits(QSerialPort::StopBits stopbits) {m_defaultStopBits=stopbits;} - void setPort(QString port){m_defaultPort=port;} - void setTimeOut(long timeout){m_defaultTimeOut=timeout;} - - //get port configuration functions - QString port(){return m_defaultPort;} - QSerialPort::BaudRate speed() {return m_defaultSpeed;} - QSerialPort::FlowControl flow() {return m_defaultFlow;} - QSerialPort::DataBits dataBits() {return m_defaultDataBits;} - QSerialPort::StopBits stopBits() {return m_defaultStopBits;} - QSerialPort::Parity parity() {return m_defaultParity;} - long timeOut(){return m_defaultTimeOut;} - - void saveConfig(QSettings* settings) const; - IUAVGadgetConfiguration *clone(); - - private: - QString m_connectionMode; - QString m_defaultPort; - QSerialPort::BaudRate m_defaultSpeed; - QSerialPort::DataBits m_defaultDataBits; - QSerialPort::FlowControl m_defaultFlow; - QSerialPort::Parity m_defaultParity; - QSerialPort::StopBits m_defaultStopBits; - long m_defaultTimeOut; - -}; - -#endif // ANTENNATRACKGADGETCONFIGURATION_H diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.cpp deleted file mode 100644 index adf0190366c..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.cpp +++ /dev/null @@ -1,61 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTracgadgetfactory.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "antennatrackgadgetfactory.h" -#include "antennatrackwidget.h" -#include "antennatrackgadget.h" -#include "antennatrackgadgetconfiguration.h" -#include "antennatrackgadgetoptionspage.h" -#include - -AntennaTrackGadgetFactory::AntennaTrackGadgetFactory(QObject *parent) : - IUAVGadgetFactory(QString("AntennaTrackGadget"), - tr("Antenna Track Gadget"), - parent) -{ -} - -AntennaTrackGadgetFactory::~AntennaTrackGadgetFactory() -{ -} - -Core::IUAVGadget* AntennaTrackGadgetFactory::createGadget(QWidget *parent) -{ - AntennaTrackWidget* gadgetWidget = new AntennaTrackWidget(parent); - return new AntennaTrackGadget(QString("AntennaTrackGadget"), gadgetWidget, parent); -} - -IUAVGadgetConfiguration *AntennaTrackGadgetFactory::createConfiguration(QSettings* qSettings) -{ - return new AntennaTrackGadgetConfiguration(QString("AntennaTrackGadget"), qSettings); -} - -IOptionsPage *AntennaTrackGadgetFactory::createOptionsPage(IUAVGadgetConfiguration *config) -{ - return new AntennaTrackGadgetOptionsPage(qobject_cast(config)); -} - diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.h b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.h deleted file mode 100644 index 777e2e59a47..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetfactory.h +++ /dev/null @@ -1,53 +0,0 @@ -/** - ****************************************************************************** - * - * @file antennatracgadgetfactory.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ANTENNATRACKGADGETFACTORY_H_ -#define ANTENNATRACKGADGETFACTORY_H_ - -#include - -namespace Core { -class IUAVGadget; -class IUAVGadgetFactory; -} - -using namespace Core; - -class AntennaTrackGadgetFactory : public IUAVGadgetFactory -{ - Q_OBJECT -public: - AntennaTrackGadgetFactory(QObject *parent = 0); - ~AntennaTrackGadgetFactory(); - - Core::IUAVGadget *createGadget(QWidget *parent); - IUAVGadgetConfiguration *createConfiguration(QSettings* qSettings); - IOptionsPage *createOptionsPage(IUAVGadgetConfiguration *config); -}; - -#endif // ANTENNATRACKGADGETFACTORY_H_ diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.cpp deleted file mode 100644 index c10dd6355a9..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.cpp +++ /dev/null @@ -1,174 +0,0 @@ -/** - ****************************************************************************** - * - * @file AntennaTracgadgetoptionspage.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "antennatrackgadgetoptionspage.h" -#include "antennatrackgadgetconfiguration.h" -#include "ui_antennatrackgadgetoptionspage.h" - -#include -#include -#include - -AntennaTrackGadgetOptionsPage::AntennaTrackGadgetOptionsPage(AntennaTrackGadgetConfiguration *config, QObject *parent) : - IOptionsPage(parent), - m_config(config) -{ -// Taken from the uploader gadget, since we also can use a serial port for this -// Gadget - //the begining of some ugly code -} -bool sortPorts(QSerialPortInfo const& s1, QSerialPortInfo const& s2) -{ - return s1.portName() < s2.portName(); -} - - -//creates options page widget (uses the UI file) -QWidget *AntennaTrackGadgetOptionsPage::createPage(QWidget *parent) -{ - Q_UNUSED(parent); - options_page = new Ui::AntennaTrackGadgetOptionsPage(); - QWidget *optionsPageWidget = new QWidget; - options_page->setupUi(optionsPageWidget); - - // PORTS - QList ports = QSerialPortInfo::availablePorts(); - qSort(ports.begin(), ports.end(), sortPorts); - foreach( QSerialPortInfo port, ports ) { - qDebug() << "Adding port: " << port.portName() << " (" << port.portName() << ")"; - options_page->portComboBox->addItem(port.portName(), port.portName()); - } - - int portIndex = options_page->portComboBox->findData(m_config->port()); - if(portIndex!=-1){ - qDebug() << "createPage(): port is " << m_config->port(); - options_page->portComboBox->setCurrentIndex(portIndex); - } - - // BAUDRATES - options_page->portSpeedComboBox->addItem("Baud1200", QSerialPort::Baud1200); - options_page->portSpeedComboBox->addItem("Baud2400", QSerialPort::Baud2400); - options_page->portSpeedComboBox->addItem("Baud4800", QSerialPort::Baud4800); - options_page->portSpeedComboBox->addItem("Baud9600", QSerialPort::Baud9600); - options_page->portSpeedComboBox->addItem("Baud19200", QSerialPort::Baud19200); - options_page->portSpeedComboBox->addItem("Baud38400", QSerialPort::Baud38400); - options_page->portSpeedComboBox->addItem("Baud57600", QSerialPort::Baud57600); - options_page->portSpeedComboBox->addItem("Baud115200", QSerialPort::Baud115200); - options_page->portSpeedComboBox->addItem("UnknownBaud", QSerialPort::UnknownBaud); - - int portSpeedIndex = options_page->portSpeedComboBox->findData(m_config->speed()); - if(portSpeedIndex != -1){ - options_page->portSpeedComboBox->setCurrentIndex(portSpeedIndex); - } - - // FLOW CONTROL - options_page->flowControlComboBox->addItem("NoFlowControl", QSerialPort::NoFlowControl); - options_page->flowControlComboBox->addItem("HardwareControl", QSerialPort::HardwareControl); - options_page->flowControlComboBox->addItem("SoftwareControl", QSerialPort::SoftwareControl); - options_page->flowControlComboBox->addItem("UnknownFlowControl", QSerialPort::UnknownFlowControl); - - int flowControlIndex = options_page->flowControlComboBox->findData(m_config->flow()); - if(flowControlIndex != -1){ - options_page->flowControlComboBox->setCurrentIndex(flowControlIndex); - } - - // DATABITS - options_page->dataBitsComboBox->addItem("Data5", QSerialPort::Data5); - options_page->dataBitsComboBox->addItem("Data6", QSerialPort::Data6); - options_page->dataBitsComboBox->addItem("Data7", QSerialPort::Data7); - options_page->dataBitsComboBox->addItem("Data8", QSerialPort::Data8); - options_page->dataBitsComboBox->addItem("UnknownDataBits", QSerialPort::UnknownDataBits); - - int dataBitsIndex = options_page->dataBitsComboBox->findData(m_config->dataBits()); - if(dataBitsIndex != -1){ - options_page->dataBitsComboBox->setCurrentIndex(dataBitsIndex); - } - - // STOPBITS - options_page->stopBitsComboBox->addItem("OneStop", QSerialPort::OneStop); - options_page->stopBitsComboBox->addItem("OneAndHalfStop", QSerialPort::OneAndHalfStop); - options_page->stopBitsComboBox->addItem("TwoStop", QSerialPort::TwoStop); - options_page->stopBitsComboBox->addItem("UnknownStopBits", QSerialPort::UnknownStopBits); - - int stopBitsIndex = options_page->stopBitsComboBox->findData(m_config->stopBits()); - if(stopBitsIndex != -1){ - options_page->stopBitsComboBox->setCurrentIndex(stopBitsIndex); - } - - // PARITY - options_page->parityComboBox->addItem("NoParity", QSerialPort::NoParity); - options_page->parityComboBox->addItem("EvenParity", QSerialPort::EvenParity); - options_page->parityComboBox->addItem("OddParity", QSerialPort::OddParity); - options_page->parityComboBox->addItem("SpaceParity", QSerialPort::SpaceParity); - options_page->parityComboBox->addItem("MarkParity", QSerialPort::MarkParity); - options_page->parityComboBox->addItem("UnknownParity", QSerialPort::UnknownParity); - - int parityIndex = options_page->parityComboBox->findData(m_config->parity()); - if(parityIndex != -1){ - options_page->parityComboBox->setCurrentIndex(parityIndex); - } - - // TIMEOUT - options_page->timeoutSpinBox->setValue(m_config->timeOut()); - - QStringList connectionModes; - connectionModes << "Serial"; - options_page->connectionMode->addItems(connectionModes); - int conMode = options_page->connectionMode->findText(m_config->connectionMode()); - if (conMode != -1) - options_page->connectionMode->setCurrentIndex(conMode); - - - return optionsPageWidget; -} - -/** - * Called when the user presses apply or OK. - * - * Saves the current values - * - */ -void AntennaTrackGadgetOptionsPage::apply() -{ - int portIndex = options_page->portComboBox->currentIndex(); - m_config->setPort(options_page->portComboBox->itemData(portIndex).toString()); - qDebug() << "apply(): port is " << m_config->port(); - - m_config->setSpeed((QSerialPort::BaudRate)options_page->portSpeedComboBox->currentData().toInt()); - m_config->setFlow((QSerialPort::FlowControl)options_page->flowControlComboBox->currentData().toInt()); - m_config->setDataBits((QSerialPort::DataBits)options_page->dataBitsComboBox->currentData().toInt()); - m_config->setStopBits((QSerialPort::StopBits)options_page->stopBitsComboBox->currentData().toInt()); - m_config->setParity((QSerialPort::Parity)options_page->parityComboBox->currentData().toInt()); - m_config->setTimeOut( options_page->timeoutSpinBox->value()); - m_config->setConnectionMode(options_page->connectionMode->currentText()); -} - -void AntennaTrackGadgetOptionsPage::finish() -{ - delete options_page; -} diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.h b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.h deleted file mode 100644 index 1ec75ff97dc..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.h +++ /dev/null @@ -1,66 +0,0 @@ -/** - ****************************************************************************** - * - * @file antennatrackgadgetoptionspage.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ANTENNATRACKGADGETOPTIONSPAGE_H -#define ANTENNATRACKGADGETOPTIONSPAGE_H - -#include -#include "coreplugin/dialogs/ioptionspage.h" -#include "QString" -#include - -namespace Core { -class IUAVGadgetConfiguration; -} - -class AntennaTrackGadgetConfiguration; - -namespace Ui { - class AntennaTrackGadgetOptionsPage; -} - -using namespace Core; - -class AntennaTrackGadgetOptionsPage : public IOptionsPage -{ -Q_OBJECT -public: - explicit AntennaTrackGadgetOptionsPage(AntennaTrackGadgetConfiguration *config, QObject *parent = 0); - - QWidget *createPage(QWidget *parent); - void apply(); - void finish(); - -private: - Ui::AntennaTrackGadgetOptionsPage *options_page; - AntennaTrackGadgetConfiguration *m_config; - -private slots: -}; - -#endif // ANTENNATRACKGADGETOPTIONSPAGE_H diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.ui b/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.ui deleted file mode 100644 index 34f6f3bc90c..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackgadgetoptionspage.ui +++ /dev/null @@ -1,186 +0,0 @@ - - - AntennaTrackGadgetOptionsPage - - - - 0 - 0 - 587 - 359 - - - - - 0 - 0 - - - - Form - - - - 0 - - - - - - - - - - Mode: - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - Qt::Horizontal - - - - - - - 0 - - - - - 0 - - - - - Serial Connection - - - - - - - - - - - - - - - Data Bits: - - - - - - - Stop Bits: - - - - - - - Parity: - - - - - - - Timeout(ms): - - - - - - - - - - - - - - - - Port: - - - - - - - Port Speed: - - - - - - - - - - Flow Control: - - - - - - - 100000 - - - - - - - - - - - - - - - - - - connectionMode - currentIndexChanged(int) - stackedWidget - setCurrentIndex(int) - - - 77 - 16 - - - 293 - 194 - - - - - diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackplugin.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackplugin.cpp deleted file mode 100644 index 11a6b7b7df6..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackplugin.cpp +++ /dev/null @@ -1,32 +0,0 @@ -#include "antennatrackplugin.h" -#include "antennatrackgadgetfactory.h" -#include -#include -#include -#include - -AntennaTrackPlugin::AntennaTrackPlugin() { - // Do nothing - } - -AntennaTrackPlugin::~AntennaTrackPlugin() { - // Do nothing -} - -bool AntennaTrackPlugin::initialize(const QStringList& args, QString *errMsg) { - Q_UNUSED(args); - Q_UNUSED(errMsg); - - mf = new AntennaTrackGadgetFactory(this); - addAutoReleasedObject(mf); - - return true; -} - -void AntennaTrackPlugin::extensionsInitialized() { - // Do nothing -} - -void AntennaTrackPlugin::shutdown() { - // Do nothing -} diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackplugin.h b/ground/gcs/src/plugins/antennatrack/antennatrackplugin.h deleted file mode 100644 index 4e168bae6d0..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackplugin.h +++ /dev/null @@ -1,23 +0,0 @@ -#ifndef ANTENNATRACKPLUGIN_H -#define ANTENNATRACKPLUGIN_H - -#include - -class AntennaTrackGadgetFactory; - -class AntennaTrackPlugin : public ExtensionSystem::IPlugin -{ - Q_OBJECT - Q_PLUGIN_METADATA(IID "TauLabs.plugins.AntennaTrack" FILE "AntennaTrack.json") -public: - AntennaTrackPlugin(); - ~AntennaTrackPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void shutdown(); -private: - AntennaTrackGadgetFactory *mf; -}; - -#endif // ANTENNATRACKPLUGIN_H diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.cpp b/ground/gcs/src/plugins/antennatrack/antennatrackwidget.cpp deleted file mode 100644 index a2a87bf0554..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.cpp +++ /dev/null @@ -1,207 +0,0 @@ -/** - ****************************************************************************** - * - * @file Antennatrackwidget.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "antennatrackwidget.h" -#include "extensionsystem/pluginmanager.h" -#include "uavobjectmanager.h" -#include "physical_constants.h" - -#include -#include -#include - -/* - * Initialize the widget - */ -AntennaTrackWidget::AntennaTrackWidget(QWidget *parent) : QWidget(parent) -{ - setupUi(this); - - azimuth_old=0; - elevation_old=0; -} - -AntennaTrackWidget::~AntennaTrackWidget() -{ -} -void AntennaTrackWidget::setPort(QPointer portx) -{ - port=portx; -} - -void AntennaTrackWidget::dumpPacket(const QString &packet) -{ - textBrowser->append(packet); - if(textBrowser->document()->lineCount() > 200) { - QTextCursor tc = textBrowser->textCursor(); - tc.movePosition(QTextCursor::Start); - tc.movePosition(QTextCursor::Down, QTextCursor::KeepAnchor); - tc.movePosition(QTextCursor::StartOfLine, QTextCursor::KeepAnchor); - tc.removeSelectedText(); - } -} - -void AntennaTrackWidget::setPosition(double lat, double lon, double alt) -{ - //lat *= 1E-7; - //lon *= 1E-7; - double deg = floor(fabs(lat)); - double min = (fabs(lat)-deg)*60; - QString str1; - str1.sprintf("%.0f%c%.3f' ", deg,0x00b0, min); - if (lat>0) - str1.append("N"); - else - str1.append("S"); - coord_value->setText(str1); - deg = floor(fabs(lon)); - min = (fabs(lon)-deg)*60; - QString str2; - str2.sprintf("%.0f%c%.3f' ", deg,0x00b0, min); - if (lon>0) - str2.append("E"); - else - str2.append("W"); - coord_value_2->setText(str2); - QString str3; - str3.sprintf("%.2f m", alt); - coord_value_3->setText(str3); - TrackData.Latitude=lat; - TrackData.Longitude=lon; - TrackData.Altitude=alt; - calcAntennaPosition(); -} - -void AntennaTrackWidget::setHomePosition(double lat, double lon, double alt) -{ - //lat *= 1E-7; - //lon *= 1E-7; - double deg = floor(fabs(lat)); - double min = (fabs(lat)-deg)*60; - QString str1; - str1.sprintf("%.0f%c%.3f' ", deg,0x00b0, min); - if (lat>0) - str1.append("N"); - else - str1.append("S"); - speed_value->setText(str1); - deg = floor(fabs(lon)); - min = (fabs(lon)-deg)*60; - QString str2; - str2.sprintf("%.0f%c%.3f' ", deg,0x00b0, min); - if (lon>0) - str2.append("E"); - else - str2.append("W"); - bear_label->setText(str2); - QString str3; - str3.sprintf("%.2f m", alt); - bear_value->setText(str3); - TrackData.HomeLatitude=lat; - TrackData.HomeLongitude=lon; - TrackData.HomeAltitude=alt; - calcAntennaPosition(); -} - -void AntennaTrackWidget::calcAntennaPosition(void) -{ - /** http://www.movable-type.co.uk/scripts/latlong.html **/ - double lat1, lat2, lon1, lon2, a, c, d, x, y, brng; - double azimuth, elevation; - double gcsAlt=TrackData.HomeAltitude; // Home MSL altitude - double uavAlt=TrackData.Altitude; // UAV MSL altitude - double dAlt=uavAlt-gcsAlt; // Altitude difference - - // Convert to radians - lat1 = TrackData.HomeLatitude*(M_PI/180); // Home lat - lon1 = TrackData.HomeLongitude*(M_PI/180); // Home lon - lat2 = TrackData.Latitude*(M_PI/180); // UAV lat - lon2 = TrackData.Longitude*(M_PI/180); // UAV lon - - // Bearing - /** - var y = Math.sin(dLon) * Math.cos(lat2); - var x = Math.cos(lat1)*Math.sin(lat2) - - Math.sin(lat1)*Math.cos(lat2)*Math.cos(dLon); - var brng = Math.atan2(y, x).toDeg(); - **/ - y = sin(lon2-lon1) * cos(lat2); - x = cos(lat1) * sin(lat2) - sin(lat1) * cos(lat2) * cos(lon2-lon1); - brng = atan2((sin(lon2-lon1)*cos(lat2)),(cos(lat1)*sin(lat2)-sin(lat1)*cos(lat2)*cos(lon2-lon1)))*(180/M_PI); - if(brng<0) - brng+=360; - - // bearing to stepper - azimuth = brng; - - // Haversine formula for distance - /** - var R = 6371; // km - var dLat = (lat2-lat1).toRad(); - var dLon = (lon2-lon1).toRad(); - var a = Math.sin(dLat/2) * Math.sin(dLat/2) + - Math.cos(lat1.toRad()) * Math.cos(lat2.toRad()) * - Math.sin(dLon/2) * Math.sin(dLon/2); - var c = 2 * Math.atan2(Math.sqrt(a), Math.sqrt(1-a)); - var d = R * c; - **/ - a = sin((lat2-lat1)/2) * sin((lat2-lat1)/2) + - cos(lat1) * cos(lat2) * - sin((lon2-lon1)/2) * sin((lon2-lon1)/2); - c = 2 * atan2(sqrt(a), sqrt(1-a)); - d = WGS84_RADIUS_EARTH_KM * 1000 * c; - - // Elevation v depends servo direction - if(d!=0) - elevation = 90-(atan(dAlt/d)*(180/M_PI)); - else - elevation = 0; - //! TODO: sanity check - - QString str3; - str3.sprintf("%.0f deg", azimuth); - azimuth_value->setText(str3); - - str3.sprintf("%.0f deg", elevation); - elevation_value->setText(str3); - - //servo value 2000-4000 - int servo = (int)(2000.0/180*elevation+2000); - int stepper = (int)(400.0/360*(azimuth-azimuth_old)); - - // send azimuth and elevation to tracker hardware - str3.sprintf("move %d 2000 2000 2000 %d\r", stepper,servo); - if(port->isOpen()) - { - if(azimuth_old!=azimuth || elevation!=elevation_old) - port->write(str3.toLatin1()); - azimuth_old = azimuth; - elevation_old = elevation; - } - -} diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.h b/ground/gcs/src/plugins/antennatrack/antennatrackwidget.h deleted file mode 100644 index 67738cf856a..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.h +++ /dev/null @@ -1,76 +0,0 @@ -/** - ****************************************************************************** - * - * @file antennatrackwidget.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef ANTENNATRACKWIDGET_H_ -#define ANTENNATRACKWIDGET_H_ - -#include "ui_antennatrackwidget.h" -#include "antennatrackgadgetconfiguration.h" -#include "uavobject.h" -#include -#include -#include -#include -#include - -class Ui_AntennaTrackWidget; - -typedef struct struct_TrackData -{ - double Latitude; - double Longitude; - double Altitude; - double HomeLatitude; - double HomeLongitude; - double HomeAltitude; - -}TrackData_t; - -class AntennaTrackWidget : public QWidget, public Ui_AntennaTrackWidget -{ - Q_OBJECT - -public: - AntennaTrackWidget(QWidget *parent = 0); - ~AntennaTrackWidget(); - TrackData_t TrackData; - void setPort(QPointer portx); - -private slots: - void setPosition(double, double, double); - void setHomePosition(double, double, double); - void dumpPacket(const QString &packet); - -private: - void calcAntennaPosition(void); - QGraphicsSvgItem * marker; - QPointer port; - double azimuth_old; - double elevation_old; -}; -#endif /* ANTENNATRACKWIDGET_H_ */ diff --git a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.ui b/ground/gcs/src/plugins/antennatrack/antennatrackwidget.ui deleted file mode 100644 index 8ffd42f0f8e..00000000000 --- a/ground/gcs/src/plugins/antennatrack/antennatrackwidget.ui +++ /dev/null @@ -1,479 +0,0 @@ - - - AntennaTrackWidget - - - - 0 - 0 - 560 - 376 - - - - - 0 - 0 - - - - - 0 - - - 6 - - - - - - 0 - 0 - - - - Qt::Vertical - - - true - - - - - - - 0 - - - - - 0 - - - - - true - - - Coord: - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 6 - - - - - - - - 0 - - - - - HomeCoord: - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - false - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 4 - - - - - - - - Qt::Horizontal - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 4 - - - - - - - - 0 - - - - - Azimuth - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - - - Qt::Vertical - - - QSizePolicy::Preferred - - - - 20 - 6 - - - - - - - - 0 - - - - - Elevation - - - - - - - Qt::Horizontal - - - QSizePolicy::Minimum - - - - 6 - 0 - - - - - - - - Unknown - - - - - - - - - Qt::Vertical - - - QSizePolicy::Ignored - - - - 20 - 6 - - - - - - - - - - 0 - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 9 - 20 - - - - - - - - - - Connect - - - - - - - Disconnect - - - - - - - - - Qt::Horizontal - - - - 0 - 20 - - - - - - - - - - - Output - - - - 0 - - - - - - 0 - 0 - - - - - 0 - 50 - - - - Qt::ScrollBarAlwaysOn - - - QTextEdit::WidgetWidth - - - false - - - - - - - - - - - - diff --git a/ground/gcs/src/plugins/antennatrack/gpsparser.h b/ground/gcs/src/plugins/antennatrack/gpsparser.h deleted file mode 100644 index b4a8b4c0278..00000000000 --- a/ground/gcs/src/plugins/antennatrack/gpsparser.h +++ /dev/null @@ -1,60 +0,0 @@ -/** - ****************************************************************************** - * - * @file gpsparser.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef GPSPARSER_H -#define GPSPARSER_H - -#include -#include -#include - -class GPSParser: public QObject -{ - Q_OBJECT -public: - ~GPSParser(); - virtual void processInputStream(char c); - -protected: - GPSParser(QObject *parent = 0); - -signals: - void sv(int); // Satellites in view - void position(double,double,double); // Lat, Lon, Alt - void home(double,double,double); // Lat, Lon, Alt - void datetime(double,double); // Date then time - void speedheading(double,double); - void packet(QString); // Raw NMEA Packet (or just info) - void satellite(int,int,int,int,int); // Index, PRN, Elevation, Azimuth, SNR - void fixmode(QString); // Mode of fix: "Auto", "Manual". - void fixtype(QString); // Type of fix: "NoGPS", "NoFix", "Fix2D", "Fix3D". - void dop(double, double, double); // HDOP, VDOP, PDOP - void fixSVs(QList); // SV's used for fix. -}; - -#endif // GPSPARSER_H diff --git a/ground/gcs/src/plugins/antennatrack/telemetryparser.cpp b/ground/gcs/src/plugins/antennatrack/telemetryparser.cpp deleted file mode 100644 index 9c8dc0b438f..00000000000 --- a/ground/gcs/src/plugins/antennatrack/telemetryparser.cpp +++ /dev/null @@ -1,82 +0,0 @@ -/** - ****************************************************************************** - * - * @file telemetryparser.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - - -#include "telemetryparser.h" -#include -#include -#include - - -/** - * Initialize the parser - */ -TelemetryParser::TelemetryParser(QObject *parent) : GPSParser(parent) -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *objManager = pm->getObject(); - UAVDataObject *gpsObj = dynamic_cast(objManager->getObject("GPSPosition")); - if (gpsObj != NULL) { - connect(gpsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateGPS(UAVObject*))); - } else { - qDebug() << "Error: Object is unknown (GPSPosition)."; - } - - gpsObj = dynamic_cast(objManager->getObject("HomeLocation")); - if (gpsObj != NULL) { - connect(gpsObj, SIGNAL(objectUpdated(UAVObject*)), this, SLOT(updateHome(UAVObject*))); - } else { - qDebug() << "Error: Object is unknown (HomeLocation)."; - } - -} - -TelemetryParser::~TelemetryParser() -{ - -} - -void TelemetryParser::updateHome( UAVObject* object1) { - double lat = object1->getField(QString("Latitude"))->getDouble(); - double lon = object1->getField(QString("Longitude"))->getDouble(); - double alt = object1->getField(QString("Altitude"))->getDouble(); - lat *= 1E-7; - lon *= 1E-7; - emit home(lat,lon,alt); -} - - -void TelemetryParser::updateGPS( UAVObject* object1) { - double lat = object1->getField(QString("Latitude"))->getDouble(); - double lon = object1->getField(QString("Longitude"))->getDouble(); - double alt = object1->getField(QString("Altitude"))->getDouble(); - lat *= 1E-7; - lon *= 1E-7; - emit position(lat,lon,alt); -} - diff --git a/ground/gcs/src/plugins/antennatrack/telemetryparser.h b/ground/gcs/src/plugins/antennatrack/telemetryparser.h deleted file mode 100644 index 9e67a716f70..00000000000 --- a/ground/gcs/src/plugins/antennatrack/telemetryparser.h +++ /dev/null @@ -1,53 +0,0 @@ -/** - ****************************************************************************** - * - * @file telemetryparser.h - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef TELEMETRYPARSER_H -#define TELEMETRYPARSER_H - -#include -#include -#include "extensionsystem/pluginmanager.h" -#include "uavobjectmanager.h" -#include "uavobject.h" -#include "gpsparser.h" - - -class TelemetryParser: public GPSParser -{ - - Q_OBJECT - -public: - TelemetryParser(QObject *parent = 0); - ~TelemetryParser(); -public slots: - void updateGPS(UAVObject* object1); - void updateHome(UAVObject* object1); -}; - -#endif // TELEMETRYPARSER_H diff --git a/ground/gcs/src/plugins/antennatrack/AntennaTrack.json b/ground/gcs/src/plugins/boards_aeroquad/AeroQuad.json similarity index 100% rename from ground/gcs/src/plugins/antennatrack/AntennaTrack.json rename to ground/gcs/src/plugins/boards_aeroquad/AeroQuad.json diff --git a/ground/gcs/src/plugins/boards_aeroquad/AeroQuad.pluginspec b/ground/gcs/src/plugins/boards_aeroquad/AeroQuad.pluginspec new file mode 100644 index 00000000000..73b593a15ab --- /dev/null +++ b/ground/gcs/src/plugins/boards_aeroquad/AeroQuad.pluginspec @@ -0,0 +1,11 @@ + + AeroQuad + (C) 2012-2013 Tau Labs + The GNU Public License (GPL) Version 3 + Hardware definitions for AeroQuad boards + http://aeroquad.com + + + + + diff --git a/ground/gcs/src/plugins/boards_aeroquad/aeroquad.qrc b/ground/gcs/src/plugins/boards_aeroquad/aeroquad.qrc new file mode 100644 index 00000000000..b66ed4280b0 --- /dev/null +++ b/ground/gcs/src/plugins/boards_aeroquad/aeroquad.qrc @@ -0,0 +1,5 @@ + + + images/aq32.png + + diff --git a/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.cpp b/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.cpp new file mode 100644 index 00000000000..57880ea462f --- /dev/null +++ b/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.cpp @@ -0,0 +1,60 @@ +/** +****************************************************************************** +* @file aeroquadplugin.cpp +* @author Tau Labs, http://taulabs.org, Copyright (C) 2013 +* +* @addtogroup GCSPlugins GCS Plugins +* @{ +* @addtogroup Boards_AeroQuadPlugin AeroQuad boards support Plugin +* @{ +* @brief Plugin to support AeroQuad boards +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#include "aeroquadplugin.h" +#include "aq32.h" + +AeroQuadPlugin::AeroQuadPlugin() +{ + // Do nothing +} + +AeroQuadPlugin::~AeroQuadPlugin() +{ + // Do nothing +} + +bool AeroQuadPlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + return true; +} + +void AeroQuadPlugin::extensionsInitialized() +{ + /** + * Create the board objects here. + * + */ + AQ32* aq32 = new AQ32(); + addAutoReleasedObject(aq32); +} + +void AeroQuadPlugin::shutdown() +{ +} diff --git a/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.h b/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.h new file mode 100644 index 00000000000..3c5dd1d36c9 --- /dev/null +++ b/ground/gcs/src/plugins/boards_aeroquad/aeroquadplugin.h @@ -0,0 +1,48 @@ +/** +****************************************************************************** +* @file aeroquadplugin.cpp +* @author Tau Labs, http://taulabs.org, Copyright (C) 2013 +* +* @addtogroup GCSPlugins GCS Plugins +* @{ +* @addtogroup Boards_AeroQuadPlugin AeroQuad boards support Plugin +* @{ +* @brief Plugin to support AeroQuad boards +*****************************************************************************/ +/* +* This program is free software; you can redistribute it and/or modify +* it under the terms of the GNU General Public License as published by +* the Free Software Foundation; either version 3 of the License, or +* (at your option) any later version. +* +* This program is distributed in the hope that it will be useful, but +* WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY +* or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License +* for more details. +* +* You should have received a copy of the GNU General Public License along +* with this program; if not, write to the Free Software Foundation, Inc., +* 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA +*/ + +#ifndef AEROQUADPLUGIN_H +#define AEROQUADPLUGIN_H + +#include + +class AeroQuadPlugin : public ExtensionSystem::IPlugin +{ + Q_OBJECT + Q_PLUGIN_METADATA(IID "AeroQuad.plugins.AeroQuad" FILE "AeroQuad.json") + +public: + AeroQuadPlugin(); + ~AeroQuadPlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); + +}; + +#endif // AEROQUADPLUGIN_H diff --git a/ground/gcs/src/plugins/boards_openpilot/revolution.cpp b/ground/gcs/src/plugins/boards_aeroquad/aq32.cpp similarity index 61% rename from ground/gcs/src/plugins/boards_openpilot/revolution.cpp rename to ground/gcs/src/plugins/boards_aeroquad/aq32.cpp index d30a02f9671..ea9f53b3471 100644 --- a/ground/gcs/src/plugins/boards_openpilot/revolution.cpp +++ b/ground/gcs/src/plugins/boards_aeroquad/aq32.cpp @@ -1,14 +1,13 @@ /** ****************************************************************************** - * - * @file revolution.cpp + * @file aq32.cpp * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup Boards_OpenPilotPlugin OpenPilot boards support Plugin + * @addtogroup Boards_AeroQuadPlugin AeroQuad boards support Plugin * @{ - * @brief Plugin to support boards by the OP project + * @brief Plugin to support AeroQuad boards *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -26,53 +25,55 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "aq32.h" + #include #include "uavobjectutil/uavobjectutilmanager.h" #include -#include "revolution.h" -#include "hwrevolution.h" + +#include "hwaq32.h" /** - * @brief Revolution::Revolution - * This is the Revolution board definition + * @brief AQ32::AQ32 + * This is the AQ32 board definition */ -Revolution::Revolution(void) +AQ32::AQ32(void) { // Initialize our USB Structure definition here: USBInfo board; - board.vendorID = 0x20A0; - board.productID = 0x415b; + board.vendorID = 0x20a0; + board.productID = 0x4284; setUSBInfo(board); - boardType = 0x7f; + boardType = 0x94; // Define the bank of channels that are connected to a given timer - channelBanks.resize(6); + channelBanks.resize(5); channelBanks[0] = QVector () << 1 << 2; - channelBanks[1] = QVector () << 3; - channelBanks[2] = QVector () << 4; - channelBanks[3] = QVector () << 5 << 6; + channelBanks[1] = QVector () << 3 << 4; + channelBanks[2] = QVector () << 5 << 6; + channelBanks[3] = QVector () << 7 << 8 << 9 <<10; } -Revolution::~Revolution() +AQ32::~AQ32() { } -QString Revolution::shortName() +QString AQ32::shortName() { - return QString("Revolution"); + return QString("AQ32"); } -QString Revolution::boardDescription() +QString AQ32::boardDescription() { - return QString("The OpenPilot project Revolution boards"); + return QString("The AQ32 board"); } //! Return which capabilities this board has -bool Revolution::queryCapabilities(BoardCapabilities capability) +bool AQ32::queryCapabilities(BoardCapabilities capability) { switch(capability) { case BOARD_CAPABILITIES_GYROS: @@ -89,46 +90,47 @@ bool Revolution::queryCapabilities(BoardCapabilities capability) return false; } + /** - * @brief Revolution::getSupportedProtocols + * @brief AQ32::getSupportedProtocols * TODO: this is just a stub, we'll need to extend this a lot with multi protocol support * @return */ -QStringList Revolution::getSupportedProtocols() +QStringList AQ32::getSupportedProtocols() { return QStringList("uavtalk"); } -QPixmap Revolution::getBoardPicture() +QPixmap AQ32::getBoardPicture() { - return QPixmap(); + return QPixmap(":/aq32/images/aq32.png"); } -QString Revolution::getHwUAVO() +QString AQ32::getHwUAVO() { - return "HwRevolution"; + return "HwAQ32"; } -int Revolution::queryMaxGyroRate() +int AQ32::queryMaxGyroRate() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *uavoManager = pm->getObject(); - HwRevolution *hwRevolution = HwRevolution::GetInstance(uavoManager); - Q_ASSERT(hwRevolution); - if (!hwRevolution) + HwAQ32 *hwAQ32 = HwAQ32::GetInstance(uavoManager); + Q_ASSERT(hwAQ32); + if (!hwAQ32) return 0; - HwRevolution::DataFields settings = hwRevolution->getData(); + HwAQ32::DataFields settings = hwAQ32->getData(); switch(settings.GyroRange) { - case HwRevolution::GYRORANGE_250: + case HwAQ32::GYRORANGE_250: return 250; - case HwRevolution::GYRORANGE_500: + case HwAQ32::GYRORANGE_500: return 500; - case HwRevolution::GYRORANGE_1000: + case HwAQ32::GYRORANGE_1000: return 1000; - case HwRevolution::GYRORANGE_2000: + case HwAQ32::GYRORANGE_2000: return 2000; default: return 500; diff --git a/ground/gcs/src/plugins/boards_openpilot/pipxtreme.h b/ground/gcs/src/plugins/boards_aeroquad/aq32.h similarity index 65% rename from ground/gcs/src/plugins/boards_openpilot/pipxtreme.h rename to ground/gcs/src/plugins/boards_aeroquad/aq32.h index d45620ca847..a98e87a75bf 100644 --- a/ground/gcs/src/plugins/boards_openpilot/pipxtreme.h +++ b/ground/gcs/src/plugins/boards_aeroquad/aq32.h @@ -1,14 +1,13 @@ /** ****************************************************************************** - * - * @file pipxtreme.h + * @file aq32.cpp * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup Boards_OpenPilotPlugin OpenPilot boards support Plugin + * @addtogroup Boards_AeroQuadPlugin AeroQuad boards support Plugin * @{ - * @brief Plugin to support boards by the OP project + * @brief Plugin to support AeroQuad boards *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -25,18 +24,19 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef PIPXTREME_H -#define PIPXTREME_H + +#ifndef AQ32_H +#define AQ32_H #include class IBoardType; -class PipXtreme : public Core::IBoardType +class AQ32 : public Core::IBoardType { public: - PipXtreme(); - virtual ~PipXtreme(); + AQ32(); + virtual ~AQ32(); virtual QString shortName(); virtual QString boardDescription(); @@ -44,22 +44,9 @@ class PipXtreme : public Core::IBoardType virtual QStringList getSupportedProtocols(); virtual QPixmap getBoardPicture(); virtual QString getHwUAVO(); - - - /** - * Get the RFM22b device ID this modem - * @return RFM22B device ID or 0 if not supported - */ - virtual quint32 getRfmID(); - - /** - * Set the coordinator ID. If set to zero this device will - * be a coordinator. - * @return true if successful or false if not - */ - virtual bool setCoordID(quint32 id, quint32 baud_rate = 0, float rf_power = -1); + virtual int queryMaxGyroRate(); }; -#endif // PIPXTREME_H +#endif // AQ32_H diff --git a/ground/gcs/src/plugins/boards_aeroquad/boards_aeroquad.pro b/ground/gcs/src/plugins/boards_aeroquad/boards_aeroquad.pro new file mode 100644 index 00000000000..46691fd3d51 --- /dev/null +++ b/ground/gcs/src/plugins/boards_aeroquad/boards_aeroquad.pro @@ -0,0 +1,18 @@ +TEMPLATE = lib +TARGET = AeroQuad +include(../../taulabsgcsplugin.pri) +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/coreplugin/coreplugin.pri) + +OTHER_FILES += AeroQuad.json + +HEADERS += \ + aeroquadplugin.h \ + aq32.h + +SOURCES += \ + aeroquadplugin.cpp \ + aq32.cpp + +RESOURCES += \ + aeroquad.qrc diff --git a/ground/gcs/src/plugins/boards_aeroquad/images/aq32.png b/ground/gcs/src/plugins/boards_aeroquad/images/aq32.png new file mode 100644 index 00000000000..5605aef9739 Binary files /dev/null and b/ground/gcs/src/plugins/boards_aeroquad/images/aq32.png differ diff --git a/ground/gcs/src/plugins/gcscontrol/GCSControl.json b/ground/gcs/src/plugins/boards_naze/Naze.json similarity index 100% rename from ground/gcs/src/plugins/gcscontrol/GCSControl.json rename to ground/gcs/src/plugins/boards_naze/Naze.json diff --git a/ground/gcs/src/plugins/boards_naze/Naze.pluginspec b/ground/gcs/src/plugins/boards_naze/Naze.pluginspec new file mode 100644 index 00000000000..3e58355091f --- /dev/null +++ b/ground/gcs/src/plugins/boards_naze/Naze.pluginspec @@ -0,0 +1,12 @@ + + Tau Labs + (C) 2012-2015 Tau Labs + The GNU Public License (GPL) Version 3 + Hardware definitions for OpenNaze and similar boards + https://github.com/Brotronics/OpenNaze_rev4/ + + + + + + diff --git a/ground/gcs/src/plugins/boards_naze/boards_naze.pro b/ground/gcs/src/plugins/boards_naze/boards_naze.pro new file mode 100644 index 00000000000..2ed6889b5bc --- /dev/null +++ b/ground/gcs/src/plugins/boards_naze/boards_naze.pro @@ -0,0 +1,18 @@ +TEMPLATE = lib +TARGET = Naze +include(../../taulabsgcsplugin.pri) +include(../../plugins/uavobjects/uavobjects.pri) +include(../../plugins/coreplugin/coreplugin.pri) + +OTHER_FILES += Naze.pluginspec + +HEADERS += \ + nazeplugin.h \ + naze.h + +SOURCES += \ + nazeplugin.cpp \ + naze.cpp + +RESOURCES += \ + naze.qrc diff --git a/ground/gcs/src/plugins/boards_naze/images/open_naze.png b/ground/gcs/src/plugins/boards_naze/images/open_naze.png new file mode 100644 index 00000000000..fe271e73834 Binary files /dev/null and b/ground/gcs/src/plugins/boards_naze/images/open_naze.png differ diff --git a/ground/gcs/src/plugins/boards_naze/naze.cpp b/ground/gcs/src/plugins/boards_naze/naze.cpp new file mode 100644 index 00000000000..3c6e4bd7e4e --- /dev/null +++ b/ground/gcs/src/plugins/boards_naze/naze.cpp @@ -0,0 +1,131 @@ +/** + ****************************************************************************** + * + * @file open_naze.cpp + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 + * + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Boards_Naze Naze boards support Plugin + * @{ + * @brief Plugin to support Naze boards + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "naze.h" + +#include +#include "uavobjectutil/uavobjectutilmanager.h" +#include + +#include "hwnaze.h" + +/** + * @brief Naze:Naze + * This is the Naze board definition + */ +Naze::Naze(void) +{ + boardType = 0xA0; + + // Define the bank of channels that are connected to a given timer + channelBanks.resize(6); + channelBanks[0] = QVector () << 1 << 2; // T1 + channelBanks[1] = QVector () << 3 << 4 << 5 << 6; // T4 + channelBanks[2] = QVector () << 7 << 8 << 9 << 10; // T2 + channelBanks[3] = QVector () << 11 << 12 << 13 << 14; // T3 +} + +Naze::~Naze() +{ + +} + +QString Naze::shortName() +{ + return QString("naze"); +} + +QString Naze::boardDescription() +{ + return QString("Open Naze hardware by ReadError, based on Naze32 by timecop."); +} + +//! Return which capabilities this board has +bool Naze::queryCapabilities(BoardCapabilities capability) +{ + switch(capability) { + case BOARD_CAPABILITIES_GYROS: + return true; + case BOARD_CAPABILITIES_ACCELS: + return true; + case BOARD_CAPABILITIES_MAGS: + return false; + case BOARD_CAPABILITIES_BAROS: + return false; + case BOARD_CAPABILITIES_RADIO: + return false; + } + return false; +} + + +/** + * @brief Naze::getSupportedProtocols + * TODO: this is just a stub, we'll need to extend this a lot with multi protocol support + * @return + */ +QStringList Naze::getSupportedProtocols() +{ + + return QStringList("uavtalk"); +} + +QPixmap Naze::getBoardPicture() +{ + return QPixmap(":/naze/images/open_naze.png"); +} + +QString Naze::getHwUAVO() +{ + return "HwNaze"; +} + +int Naze::queryMaxGyroRate() +{ + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + UAVObjectManager *uavoManager = pm->getObject(); + HwNaze *hwNaze = HwNaze::GetInstance(uavoManager); + Q_ASSERT(hwNaze); + if (!hwNaze) + return 0; + + HwNaze::DataFields settings = hwNaze->getData(); + + switch(settings.GyroRange) { + case HwNaze::GYRORANGE_250: + return 250; + case HwNaze::GYRORANGE_500: + return 500; + case HwNaze::GYRORANGE_1000: + return 1000; + case HwNaze::GYRORANGE_2000: + return 2000; + default: + return 500; + } +} diff --git a/ground/gcs/src/plugins/boards_openpilot/revolution.h b/ground/gcs/src/plugins/boards_naze/naze.h similarity index 81% rename from ground/gcs/src/plugins/boards_openpilot/revolution.h rename to ground/gcs/src/plugins/boards_naze/naze.h index 582a2916f7f..9a2e52baa71 100644 --- a/ground/gcs/src/plugins/boards_openpilot/revolution.h +++ b/ground/gcs/src/plugins/boards_naze/naze.h @@ -1,14 +1,14 @@ /** ****************************************************************************** * - * @file revolution.h + * @file open_naze.h * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 * * @addtogroup GCSPlugins GCS Plugins * @{ - * @addtogroup Boards_OpenPilotPlugin OpenPilot boards support Plugin + * @addtogroup Boards_Naze Naze boards support Plugin * @{ - * @brief Plugin to support boards by the OP project + * @brief Plugin to support Naze boards *****************************************************************************/ /* * This program is free software; you can redistribute it and/or modify @@ -25,18 +25,18 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef REVOLUTION_H -#define REVOLUTION_H +#ifndef NAZE_H +#define NAZE_H #include class IBoardType; -class Revolution : public Core::IBoardType +class Naze : public Core::IBoardType { public: - Revolution(); - virtual ~Revolution(); + Naze(); + virtual ~Naze(); virtual QString shortName(); virtual QString boardDescription(); @@ -48,4 +48,4 @@ class Revolution : public Core::IBoardType }; -#endif // REVOLUTION_H +#endif // NAZE_H diff --git a/ground/gcs/src/plugins/boards_naze/naze.qrc b/ground/gcs/src/plugins/boards_naze/naze.qrc new file mode 100644 index 00000000000..d49af5696f6 --- /dev/null +++ b/ground/gcs/src/plugins/boards_naze/naze.qrc @@ -0,0 +1,5 @@ + + + images/open_naze.png + + diff --git a/ground/gcs/src/plugins/antennatrack/gpsparser.cpp b/ground/gcs/src/plugins/boards_naze/nazeplugin.cpp similarity index 58% rename from ground/gcs/src/plugins/antennatrack/gpsparser.cpp rename to ground/gcs/src/plugins/boards_naze/nazeplugin.cpp index 5d512f0f569..3bf3c91c380 100644 --- a/ground/gcs/src/plugins/antennatrack/gpsparser.cpp +++ b/ground/gcs/src/plugins/boards_naze/nazeplugin.cpp @@ -1,44 +1,65 @@ -/** - ****************************************************************************** - * - * @file gpsparser.cpp - * @author Sami Korhonen & the OpenPilot team Copyright (C) 2010. - * @author Tau Labs, http://taulabs.org, Copyright (C) 2012-2014. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup AntennaTrackGadgetPlugin Antenna Track Gadget Plugin - * @{ - * @brief A gadget that communicates with antenna tracker and enables basic configuration - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "gpsparser.h" - -GPSParser::GPSParser(QObject *parent) : QObject(parent) -{ - qRegisterMetaType >("QList"); -} - -GPSParser::~GPSParser() -{ - -} - -void GPSParser::processInputStream(char c) { -{ - Q_UNUSED(c)} -} +/** + ****************************************************************************** + * + * @file nazeplugin.h + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 + * + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Boards_Naze Naze boards support Plugin + * @{ + * @brief Plugin to support Naze boards + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ + +#include "nazeplugin.h" +#include "naze.h" +#include + + +NazePlugin::NazePlugin() +{ + // Do nothing +} + +NazePlugin::~NazePlugin() +{ + // Do nothing +} + +bool NazePlugin::initialize(const QStringList& args, QString *errMsg) +{ + Q_UNUSED(args); + Q_UNUSED(errMsg); + return true; +} + +void NazePlugin::extensionsInitialized() +{ + /** + * Create the board objects here. + * + */ + Naze* naze = new Naze(); + addAutoReleasedObject(naze); + +} + +void NazePlugin::shutdown() +{ +} + diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcsonctrolgadgetwidget.h b/ground/gcs/src/plugins/boards_naze/nazeplugin.h similarity index 62% rename from ground/gcs/src/plugins/gcscontrolwidget/gcsonctrolgadgetwidget.h rename to ground/gcs/src/plugins/boards_naze/nazeplugin.h index 360b59080d9..4f9708b1c33 100644 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcsonctrolgadgetwidget.h +++ b/ground/gcs/src/plugins/boards_naze/nazeplugin.h @@ -1,44 +1,48 @@ -/** - ****************************************************************************** - * - * @file emptygadgetwidget.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup EmptyGadgetPlugin Empty Gadget Plugin - * @{ - * @brief A place holder gadget plugin - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef EMPTYGADGETWIDGET_H_ -#define EMPTYGADGETWIDGET_H_ - -#include - -class EmptyGadgetWidget : public QLabel -{ - Q_OBJECT - -public: - EmptyGadgetWidget(QWidget *parent = 0); - ~EmptyGadgetWidget(); - -private: -}; - -#endif /* EMPTYGADGETWIDGET_H_ */ +/** + ****************************************************************************** + * + * @file nazeplugin.h + * @author Tau Labs, http://taulabs.org, Copyright (C) 2013-2015 + * + * @addtogroup GCSPlugins GCS Plugins + * @{ + * @addtogroup Boards_Naze Naze boards support Plugin + * @{ + * @brief Plugin to support Naze boards + *****************************************************************************/ +/* + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY + * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License + * for more details. + * + * You should have received a copy of the GNU General Public License along + * with this program; if not, write to the Free Software Foundation, Inc., + * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + */ +#ifndef NAZEPLUGIN_H +#define NAZEPLUGIN_H + +#include + +class NazePlugin : public ExtensionSystem::IPlugin +{ + Q_OBJECT + Q_PLUGIN_METADATA(IID "TauLabs.plugins.Naze" FILE "Naze.json") + +public: + NazePlugin(); + ~NazePlugin(); + + void extensionsInitialized(); + bool initialize(const QStringList & arguments, QString * errorString); + void shutdown(); + +}; + +#endif // NAZEPLUGIN_H diff --git a/ground/gcs/src/plugins/boards_openpilot/boards_openpilot.pro b/ground/gcs/src/plugins/boards_openpilot/boards_openpilot.pro index 3d050e7cacd..0f4711aefb9 100644 --- a/ground/gcs/src/plugins/boards_openpilot/boards_openpilot.pro +++ b/ground/gcs/src/plugins/boards_openpilot/boards_openpilot.pro @@ -13,17 +13,13 @@ HEADERS += \ openpilotplugin.h \ coptercontrol.h \ config_cc_hw_widget.h \ - revolution.h \ - revomini.h \ - pipxtreme.h + revomini.h SOURCES += \ openpilotplugin.cpp \ coptercontrol.cpp \ config_cc_hw_widget.cpp \ - revolution.cpp \ - revomini.cpp \ - pipxtreme.cpp + revomini.cpp RESOURCES += \ openpilot.qrc \ diff --git a/ground/gcs/src/plugins/boards_openpilot/coptercontrol.cpp b/ground/gcs/src/plugins/boards_openpilot/coptercontrol.cpp index df93029cd37..1a3559d15c8 100644 --- a/ground/gcs/src/plugins/boards_openpilot/coptercontrol.cpp +++ b/ground/gcs/src/plugins/boards_openpilot/coptercontrol.cpp @@ -143,7 +143,9 @@ bool CopterControl::setInputOnPort(enum InputType type, int port_num) settings.RcvrPort = HwCopterControl::RCVRPORT_PWM; break; case INPUT_TYPE_PPM: - settings.RcvrPort = HwCopterControl::RCVRPORT_PPM; + /* Break from the past; for new builds pick a default that will + * work with OneShot/SyncPWM. */ + settings.RcvrPort = HwCopterControl::RCVRPORT_PPMONPIN8; break; case INPUT_TYPE_SBUS: settings.MainPort = HwCopterControl::MAINPORT_SBUS; @@ -201,6 +203,7 @@ enum Core::IBoardType::InputType CopterControl::getInputOnPort(int port_num) } switch(settings.RcvrPort) { + case HwCopterControl::RCVRPORT_PPMONPIN8: case HwCopterControl::RCVRPORT_PPM: return INPUT_TYPE_PPM; case HwCopterControl::RCVRPORT_PWM: diff --git a/ground/gcs/src/plugins/boards_openpilot/images/connection-diagrams.svg b/ground/gcs/src/plugins/boards_openpilot/images/connection-diagrams.svg index 77b218c1560..23914189f98 100644 --- a/ground/gcs/src/plugins/boards_openpilot/images/connection-diagrams.svg +++ b/ground/gcs/src/plugins/boards_openpilot/images/connection-diagrams.svg @@ -14,7 +14,7 @@ height="525.51001" width="1078.6002" version="1.1" - inkscape:version="0.48.2 r9819" + inkscape:version="0.48.5 r10040" sodipodi:docname="connection-diagrams.svg"> + @@ -2719,9493 +2729,9504 @@ id="background" transform="translate(0,5.995598)"> + transform="translate(-21.636986,-37.172948)" + id="pwm"> + + + + + + + + + + + + Throttle + Roll + Pitch + Yaw + Flight Mode + + + + + + + + transform="matrix(1.0887723,0,0,1.065281,432.61098,99.35125)" + id="g8764"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - + id="path12850_1_" /> + + + + + + + + + + + + + + + + + + + + + transform="matrix(1.4970318,0,0,1,-211.28069,0.21205357)" + id="g3781"> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="path3777-3" /> + sodipodi:nodetypes="cc" + id="path3779-4" /> + + + id="path3787-5" /> + sodipodi:nodetypes="cc" + id="path3789-0" /> + + + id="path3793-1" /> + sodipodi:nodetypes="cc" + id="path3795-4" /> + + + id="path3799-5" /> + sodipodi:nodetypes="cc" + id="path3801-6" /> + + + id="path3805-2" /> + sodipodi:nodetypes="cc" + id="path3807-0" /> + + + id="path3811-3" /> + sodipodi:nodetypes="cc" + id="path3813-5" /> + + + id="path3817-6" /> + sodipodi:nodetypes="cc" + id="path3819-6" /> + + + id="path3823-6" /> + sodipodi:nodetypes="cc" + id="path3825-7" /> + + + id="path3829-6" /> + sodipodi:nodetypes="cc" + id="path3831-7" /> + + + id="path3835-7" /> + sodipodi:nodetypes="cc" + id="path3837-1" /> + + + id="path3841-9" /> + sodipodi:nodetypes="cc" + id="path3843-1" /> + + + id="path3847-6" /> + sodipodi:nodetypes="cc" + id="path3849-2" /> + + + id="path3853-7" /> + sodipodi:nodetypes="cc" + id="path3855-2" /> + + + id="path3859-7" /> + sodipodi:nodetypes="cc" + id="path3861-6" /> + + - + id="path3865-5" /> + sodipodi:nodetypes="cc" + id="path3867-1" /> + + + id="path3871-3" /> + sodipodi:nodetypes="cc" + id="path3873-9" /> + + + id="path3929-9" /> + sodipodi:nodetypes="cc" + id="path3931-5" /> + + + id="path3935-9" /> + sodipodi:nodetypes="cc" + id="path3937-2" /> + + + id="path3941-6" /> + sodipodi:nodetypes="cc" + id="path3943-5" /> + + + id="path3947-3" /> + sodipodi:nodetypes="cc" + id="path3949-2" /> + + + id="path3953-4" /> + sodipodi:nodetypes="cc" + id="path3955-4" /> + + + id="path3959-4" /> + sodipodi:nodetypes="cc" + id="path3961-2" /> + + + id="path3965-7" /> + sodipodi:nodetypes="cc" + id="path3967-9" /> + + + id="path3971-2" /> + sodipodi:nodetypes="cc" + id="path3973-3" /> + + + id="path3977-7" /> + sodipodi:nodetypes="cc" + id="path3979-3" /> + + + id="path3983-1" /> + sodipodi:nodetypes="cc" + id="path3985-5" /> + + + id="path3989-7" /> + sodipodi:nodetypes="cc" + id="path3991-8" /> + + + id="path3995-5" /> + sodipodi:nodetypes="cc" + id="path3997-8" /> + + - + id="path4001-3" /> + sodipodi:nodetypes="cc" + id="path4003-2" /> + + + id="path4007-4" /> + sodipodi:nodetypes="cc" + id="path4009-1" /> + + + id="path4013-1" /> + sodipodi:nodetypes="cc" + id="path4015-5" /> + + + id="path4019-9" /> + sodipodi:nodetypes="cc" + id="path4021-5" /> + + + id="path4027-1" /> + sodipodi:nodetypes="cc" + id="path4029-0" /> + + + id="path4033-6" /> + sodipodi:nodetypes="cc" + id="path4035-4" /> + + + id="path4039-5" /> + sodipodi:nodetypes="cc" + id="path4041-3" /> + + + id="path4045-0" /> + sodipodi:nodetypes="cc" + id="path4047-8" /> + + + id="path4051-9" /> + sodipodi:nodetypes="cc" + id="path4053-1" /> + + + id="path4057-3" /> + sodipodi:nodetypes="cc" + id="path4059-4" /> + + + id="path4063-7" /> + sodipodi:nodetypes="cc" + id="path4065-4" /> + + + id="path4069-6" /> + sodipodi:nodetypes="cc" + id="path4071-3" /> + + + id="path4075-6" /> + sodipodi:nodetypes="cc" + id="path4077-5" /> + + + id="path4081-2" /> + sodipodi:nodetypes="cc" + id="path4083-8" /> + + - + id="path4087-1" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + sodipodi:nodetypes="cc" + id="path4089-0" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + d="m 167.542,162.639 v 6.498 c 0,0.342 -0.277,0.621 -0.621,0.621 h -11.936 c -0.344,0 -0.623,-0.279 -0.623,-0.621 v -6.498 c 0,-0.344 0.279,-0.621 0.623,-0.621 h 11.936 c 0.344,0 0.621,0.277 0.621,0.621 z" + id="rect4841-7" /> + + + + + + + + + + + d="m 150.42,158.868 v 6.498 c 0,0.342 -0.277,0.621 -0.621,0.621 h -11.936 c -0.344,0 -0.623,-0.279 -0.623,-0.621 v -6.498 c 0,-0.344 0.279,-0.621 0.623,-0.621 h 11.936 c 0.344,0 0.621,0.277 0.621,0.621 z" + id="rect4841_1_" /> + + + + + + + + + + + d="m 160.505,133.086 h -6.498 c -0.342,0 -0.621,-0.277 -0.621,-0.621 v -11.936 c 0,-0.344 0.279,-0.623 0.621,-0.623 h 6.498 c 0.344,0 0.621,0.279 0.621,0.623 v 11.936 c 0,0.344 -0.277,0.621 -0.621,0.621 z" + id="rect4841_2_" /> + + + + + + + + + + + d="m 59.366,43.544 h -6.498 c -0.342,0 -0.621,-0.277 -0.621,-0.621 V 30.987 c 0,-0.344 0.279,-0.623 0.621,-0.623 h 6.498 c 0.344,0 0.621,0.279 0.621,0.623 v 11.936 c 0,0.344 -0.278,0.621 -0.621,0.621 z" + id="rect4841_3_" /> + + + + + + + + + + + d="m 54.64,77.769 h -4.459 c -0.234,0 -0.426,-0.19 -0.426,-0.426 v -8.19 c 0,-0.236 0.192,-0.428 0.426,-0.428 h 4.459 c 0.236,0 0.426,0.192 0.426,0.428 v 8.19 c 0,0.236 -0.19,0.426 -0.426,0.426 z" + id="rect4841_4_" /> + + + + + + + + + + + d="m 54.64,89.629 h -4.459 c -0.234,0 -0.426,-0.19 -0.426,-0.426 v -8.19 c 0,-0.236 0.192,-0.428 0.426,-0.428 h 4.459 c 0.236,0 0.426,0.192 0.426,0.428 v 8.19 c 0,0.236 -0.19,0.426 -0.426,0.426 z" + id="rect4841_5_" /> + + + + + + + + + + + d="m 54.64,101.489 h -4.459 c -0.234,0 -0.426,-0.19 -0.426,-0.426 v -8.19 c 0,-0.236 0.192,-0.428 0.426,-0.428 h 4.459 c 0.236,0 0.426,0.192 0.426,0.428 v 8.19 c 0,0.236 -0.19,0.426 -0.426,0.426 z" + id="rect4841_6_" /> + + + + + + + + + + + d="m 54.64,113.35 h -4.459 c -0.234,0 -0.426,-0.19 -0.426,-0.427 v -8.19 c 0,-0.236 0.192,-0.428 0.426,-0.428 h 4.459 c 0.236,0 0.426,0.192 0.426,0.428 v 8.19 c 0,0.236 -0.19,0.427 -0.426,0.427 z" + id="rect4841_7_" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + inkscape:connector-curvature="0" + id="path8668" + d="m 110.126,10.926 0.563,1.734 c 3.82,-1.425 2.62,-7.761 -2.074,-6.405 4.021,-0.446 4.084,4.377 1.511,4.671 z" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + d="m 533,1510 c 1.7,0.98 2.04,3.56 0.773,5.76 -1.267,2.2 -3.68,3.19 -5.37,2.21 l -153,-88.1 c -1.7,-0.98 -2.04,-3.56 -0.776,-5.76 1.27,-2.2 3.68,-3.19 5.38,-2.21 l 153,88.1 z" + id="path10031" /> + stroke-miterlimit="10" + d="m 533,1510 c 1.7,0.98 2.04,3.56 0.773,5.76 -1.267,2.2 -3.68,3.19 -5.37,2.21 l -153,-88.1 c -1.7,-0.98 -2.04,-3.56 -0.776,-5.76 1.27,-2.2 3.68,-3.19 5.38,-2.21 l 153,88.1 z" + id="path10035" /> + d="m 235,1510 c -1.63,0.94 -3.98,-0.082 -5.24,-2.28 -1.27,-2.2 -0.981,-4.74 0.644,-5.68 l 146,-84.4 c 1.63,-0.939 3.98,0.082 5.24,2.28 1.27,2.2 0.983,4.74 -0.644,5.68 L 235,1510 z" + id="path10039" /> + stroke-miterlimit="10" + d="m 235,1510 c -1.63,0.94 -3.98,-0.082 -5.24,-2.28 -1.27,-2.2 -0.981,-4.74 0.644,-5.68 l 146,-84.4 c 1.63,-0.939 3.98,0.082 5.24,2.28 1.27,2.2 0.983,4.74 -0.644,5.68 L 235,1510 z" + id="path10043" /> + d="m 375,1240 c -0.002,-2.06 2.06,-3.73 4.6,-3.73 2.54,0 4.6,1.67 4.6,3.73 l -0.002,185 c 0,2.06 -2.06,3.73 -4.6,3.73 -2.54,0 -4.6,-1.67 -4.6,-3.73 L 375,1240 z" + id="path10047" /> + stroke-miterlimit="10" + d="m 375,1240 c -0.002,-2.06 2.06,-3.73 4.6,-3.73 2.54,0 4.6,1.67 4.6,3.73 l -0.002,185 c 0,2.06 -2.06,3.73 -4.6,3.73 -2.54,0 -4.6,-1.67 -4.6,-3.73 L 375,1240 z" + id="path10051" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + d="m 349,1460 62.1,0 c 1.63,0 2.95,-1.32 2.95,-2.95 v -62.1 c 0,-1.63 -1.32,-2.96 -2.95,-2.96 H 349 c -1.63,0 -2.95,1.32 -2.95,2.96 v 62.1 c 0,1.63 1.32,2.95 2.95,2.95" + id="path10243" /> + d="m 372,1420 -2.78,-9.4 7.16,-3.94 2.89,11 -7.27,2.36 z m -1.79,16.9 -3.03,-12.3 1.96,-0.745 11.1,-3.97 2.99,9.89 -13,7.07 z m 12.8,13.2 c -1.15,0.022 -2.18,-0.468 -2.61,-1.87 l -4.04,-13.6 6.49,-3.55 2.8,10.6 c 0.795,1.24 1.93,0.761 3.16,0.014 l 9.6,-6.33 c 0.85,-0.699 1.4,-1.66 1.35,-3.17 l -0.592,-8.39 c -0.113,-1.18 -0.826,-1.89 -1.37,-1.78 l -15.2,8.23 -2.69,-10.2 3.7,-1.34 v -0.01 l 15.2,-5.49 c 2.26,-0.824 4.28,1.66 4.36,5.4 l 0.065,13.4 c -0.049,3.31 -1.64,5.1 -3.24,6.39 l -12.7,9.9 c -1.06,0.864 -2.79,1.74 -4.3,1.77" + id="path10247" /> + d="m 368,1440 -1.31,0.757 1.16,4.26 -2.92,1.59 -6.44,-2.74 -8.89,2.35 7.9,-5.36 3.09,-7.39 4,-1.32 1.26,4.74 1.24,-0.195 0.906,3.31 z" + id="path10251" /> + d="m 398,1400 2.56,0 c 0.279,0 0.5,-0.107 0.695,-0.296 0.1,-0.089 0.176,-0.2 0.215,-0.314 0.051,-0.119 0.084,-0.246 0.084,-0.387 v -0.914 c 0,-0.135 -0.033,-0.266 -0.084,-0.396 -0.039,-0.106 -0.115,-0.209 -0.215,-0.298 -0.195,-0.194 -0.416,-0.299 -0.695,-0.299 H 398 c -0.275,0 -0.504,0.105 -0.693,0.299 -0.104,0.089 -0.174,0.192 -0.225,0.298 -0.039,0.13 -0.078,0.261 -0.078,0.396 v 0.914 c 0,0.141 0.039,0.268 0.078,0.387 0.051,0.114 0.121,0.225 0.225,0.314 0.189,0.189 0.418,0.296 0.693,0.296 m -12.4,0 2.56,0 c 0.276,0 0.497,-0.107 0.688,-0.296 0.191,-0.187 0.309,-0.427 0.309,-0.701 v -0.914 c 0,-0.277 -0.118,-0.527 -0.309,-0.694 -0.184,-0.191 -0.41,-0.298 -0.676,-0.299 h -3.57 v 0.993 0.521 0.393 c 0,0.141 0.035,0.268 0.084,0.387 0.051,0.114 0.129,0.225 0.228,0.314 0.176,0.189 0.403,0.296 0.684,0.296 m -15,0 2.55,0 c 0.287,0 0.506,-0.107 0.701,-0.296 0.096,-0.089 0.166,-0.2 0.213,-0.314 0.053,-0.119 0.082,-0.246 0.082,-0.38 h -4.54 c 0,0.134 0.033,0.261 0.08,0.38 0.051,0.114 0.121,0.225 0.219,0.314 0.189,0.189 0.426,0.296 0.695,0.296 m -7.51,0 2.54,0 c 0.281,0 0.519,-0.107 0.715,-0.296 0.197,-0.187 0.281,-0.427 0.281,-0.701 v -0.914 c 0,-0.277 -0.084,-0.527 -0.281,-0.694 -0.196,-0.194 -0.434,-0.299 -0.715,-0.299 h -1.89 -1.64 v 0.993 0.521 0.393 c 0,0.141 0.02,0.268 0.073,0.387 0.062,0.114 0.135,0.225 0.224,0.314 0.18,0.189 0.42,0.296 0.7,0.296 m -7.52,0 2.54,0 c 0.277,0 0.522,-0.107 0.709,-0.296 0.088,-0.089 0.158,-0.2 0.215,-0.314 0.051,-0.119 0.074,-0.246 0.074,-0.387 v -0.914 c 0,-0.135 -0.023,-0.266 -0.074,-0.396 -0.057,-0.106 -0.127,-0.209 -0.215,-0.298 -0.187,-0.194 -0.432,-0.299 -0.709,-0.299 h -0.318 -2.22 c -0.281,0 -0.514,0.105 -0.713,0.299 -0.082,0.089 -0.158,0.192 -0.209,0.298 -0.057,0.13 -0.074,0.261 -0.074,0.396 v 0.914 c 0,0.141 0.017,0.268 0.074,0.387 0.051,0.114 0.127,0.225 0.209,0.314 0.199,0.189 0.432,0.296 0.713,0.296 m 42.4,1.04 c -0.278,0 -0.543,-0.05 -0.795,-0.167 -0.233,-0.088 -0.453,-0.241 -0.619,-0.419 -0.194,-0.19 -0.34,-0.406 -0.457,-0.652 -0.106,-0.255 -0.141,-0.521 -0.141,-0.794 v -0.929 c 0,-0.282 0.035,-0.548 0.141,-0.795 0.117,-0.243 0.263,-0.456 0.457,-0.642 0.166,-0.179 0.386,-0.332 0.619,-0.427 0.252,-0.115 0.517,-0.159 0.795,-0.159 h 2.69 c 0.277,0 0.543,0.044 0.791,0.159 0.236,0.095 0.459,0.248 0.637,0.427 0.189,0.186 0.334,0.399 0.445,0.642 0.096,0.247 0.147,0.513 0.147,0.795 v 0.929 c 0,0.273 -0.051,0.539 -0.147,0.794 -0.111,0.246 -0.256,0.462 -0.445,0.652 -0.178,0.178 -0.401,0.331 -0.637,0.419 -0.248,0.117 -0.514,0.167 -0.791,0.167 h -2.69 z m -27.4,0 c -0.274,0 -0.539,-0.05 -0.797,-0.167 -0.236,-0.088 -0.451,-0.241 -0.625,-0.419 -0.186,-0.19 -0.34,-0.406 -0.447,-0.652 -0.108,-0.252 -0.156,-0.509 -0.156,-0.786 v -0.929 c 0,-0.277 0.048,-0.542 0.156,-0.796 0.107,-0.243 0.261,-0.463 0.447,-0.649 0.174,-0.179 0.389,-0.332 0.625,-0.427 0.258,-0.115 0.523,-0.159 0.797,-0.159 h 4.11 v 1.04 h -4.05 c -0.269,0 -0.506,0.105 -0.695,0.299 -0.074,0.078 -0.133,0.161 -0.18,0.257 -0.058,0.097 -0.091,0.204 -0.107,0.304 h 5.63 v 1.06 c 0,0.277 -0.051,0.534 -0.145,0.786 -0.117,0.246 -0.254,0.462 -0.449,0.652 -0.182,0.178 -0.4,0.331 -0.644,0.419 -0.233,0.117 -0.5,0.167 -0.791,0.167 h -2.68 z m -15,0 c -0.291,0 -0.555,-0.05 -0.793,-0.167 -0.25,-0.088 -0.459,-0.241 -0.645,-0.419 -0.183,-0.19 -0.336,-0.406 -0.445,-0.652 -0.1,-0.255 -0.153,-0.521 -0.153,-0.794 v -0.929 c 0,-0.282 0.053,-0.548 0.153,-0.795 0.109,-0.243 0.262,-0.456 0.445,-0.642 0.186,-0.179 0.395,-0.332 0.645,-0.427 0.238,-0.115 0.502,-0.159 0.793,-0.159 h 2.01 0.664 2.8 v -1.99 h 1.11 v 1.99 h 0.928 0.36 2.32 c 0.283,0 0.543,0.044 0.783,0.159 0.252,0.095 0.463,0.248 0.654,0.427 0.192,0.186 0.334,0.399 0.436,0.642 0.099,0.247 0.158,0.513 0.158,0.795 v 0.929 c 0,0.273 -0.059,0.539 -0.158,0.794 -0.102,0.246 -0.244,0.462 -0.436,0.652 -0.191,0.178 -0.402,0.331 -0.654,0.419 -0.24,0.117 -0.5,0.167 -0.783,0.167 h -2.68 c -0.281,0 -0.545,-0.05 -0.793,-0.167 -0.244,-0.088 -0.455,-0.241 -0.642,-0.419 -0.186,-0.19 -0.338,-0.406 -0.44,-0.652 -0.107,-0.255 -0.164,-0.521 -0.164,-0.794 v -1.91 h -1.02 c 0.027,0.063 0.068,0.128 0.087,0.19 0.112,0.247 0.165,0.513 0.165,0.795 v 0.929 c 0,0.273 -0.053,0.539 -0.165,0.794 -0.091,0.246 -0.244,0.462 -0.423,0.652 -0.192,0.178 -0.407,0.331 -0.653,0.419 -0.252,0.117 -0.517,0.167 -0.797,0.167 h -2.68 z m 35.5,-4.98 1.1,0 0,5 -1.1,0 0,-5 z m -13,5 c -0.274,0 -0.539,-0.059 -0.791,-0.183 -0.229,-0.088 -0.446,-0.241 -0.625,-0.419 -0.186,-0.19 -0.336,-0.406 -0.451,-0.652 -0.096,-0.252 -0.139,-0.509 -0.139,-0.786 v -2.96 h 1.09 v 2.95 c 0,0.273 0.113,0.514 0.301,0.708 0.08,0.089 0.197,0.157 0.302,0.213 0.121,0.052 0.244,0.074 0.381,0.074 h 2.57 c 0.132,0 0.263,-0.022 0.369,-0.074 0.121,-0.056 0.244,-0.124 0.314,-0.213 0.197,-0.194 0.301,-0.435 0.301,-0.708 v -2.95 h 0.307 0.785 0.777 v -1.99 h 1.1 v 1.99 h 0.927 2.3 0.407 c 0.265,0 0.531,0.044 0.783,0.159 0.23,0.095 0.451,0.248 0.631,0.427 0.183,0.186 0.338,0.399 0.445,0.642 0.103,0.247 0.139,0.513 0.139,0.795 v 0.929 c 0,0.273 -0.036,0.539 -0.139,0.794 -0.107,0.246 -0.262,0.462 -0.445,0.652 -0.18,0.178 -0.401,0.331 -0.631,0.419 -0.252,0.117 -0.518,0.167 -0.783,0.167 h -2.71 c -0.279,0 -0.544,-0.05 -0.792,-0.167 -0.225,-0.088 -0.438,-0.241 -0.625,-0.419 -0.19,-0.19 -0.34,-0.406 -0.456,-0.652 -0.099,-0.255 -0.15,-0.521 -0.15,-0.794 v -1.91 h -0.777 v 1.91 0.01 c 0,0.277 -0.053,0.534 -0.139,0.786 -0.119,0.246 -0.262,0.462 -0.451,0.652 -0.184,0.178 -0.406,0.331 -0.643,0.419 -0.23,0.124 -0.496,0.183 -0.777,0.183 h -2.7 z m 25.6,1.43 0,-1.22 -0.49,0 0,-1.05 0.49,0 0,-2.13 c 0,-0.282 0.06,-0.548 0.154,-0.795 0.112,-0.243 0.252,-0.456 0.438,-0.642 0.195,-0.179 0.4,-0.332 0.652,-0.427 0.236,-0.115 0.502,-0.159 0.793,-0.159 h 0.791 v 1.04 h -0.777 c -0.27,0.025 -0.504,0.13 -0.664,0.32 -0.096,0.079 -0.168,0.192 -0.213,0.308 -0.049,0.104 -0.065,0.232 -0.065,0.365 v 2.12 h 1.72 v 0.224 0.83 h -1.72 v 1.22 h -1.11 z m -10.8,0.564 0,-4.96 c 0,-0.277 0.06,-0.542 0.162,-0.796 0.1,-0.243 0.24,-0.463 0.434,-0.638 0.197,-0.184 0.398,-0.332 0.66,-0.438 0.234,-0.115 0.49,-0.159 0.777,-0.159 h 0.221 v 1.04 h -0.201 c -0.262,0.025 -0.479,0.13 -0.664,0.32 -0.088,0.079 -0.157,0.192 -0.198,0.308 -0.064,0.104 -0.068,0.232 -0.068,0.365 v 4.96 h -1.12 z m -1.86,-1.1 1.1,0 0,1.1 -1.1,0 0,-1.1 z" + id="path10255" /> + d="m 544,1522.7358 c 9.4,-9.41 9.4,-24.7 -0.008,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.4,9.409 -9.4,24.7 0.008,34.1 9.41,9.41 24.7,9.41 34.1,0.01" + id="path10259" /> + d="m 522,1500 0,2.94 5.8,5.25 c 0.734,0.693 1.22,1.39 1.22,2.29 0,1.05 -0.736,1.78 -1.85,1.78 -1.18,0 -1.95,-0.924 -2.1,-2.25 l -3.38,0.462 c 0.335,3 2.77,4.79 5.67,4.79 2.73,0 5.38,-1.45 5.38,-4.56 0,-2.12 -1.24,-3.36 -2.6,-4.58 l -3.44,-3.07 h 6.07 v -3.06 h -10.8 z" + id="path10263" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + d="m 397,1264.5284 c 9.41,-9.41 9.41,-24.7 -0.008,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.41,9.41 -9.41,24.7 0.008,34.1 9.41,9.41 24.7,9.41 34.1,0.01" + id="path10347" /> + d="m 380,1240 c -2.71,0 -5.16,1.18 -5.96,3.95 l 3.28,0.861 c 0.274,-0.988 1.18,-1.85 2.52,-1.85 1.01,0 2.16,0.504 2.16,1.89 0,1.51 -1.55,1.95 -3.02,1.95 h -0.945 v 2.58 h 1.03 c 1.32,0 2.6,0.336 2.6,1.76 0,1.07 -0.902,1.64 -1.87,1.64 -1.01,0 -1.81,-0.651 -2.04,-1.66 l -3.28,0.756 c 0.712,2.5 3.06,3.78 5.54,3.78 2.62,0 5.23,-1.34 5.23,-4.2 0,-1.64 -1.05,-2.86 -2.5,-3.23 v -0.063 c 1.68,-0.399 2.86,-1.78 2.86,-3.44 0,-3.26 -2.88,-4.72 -5.6,-4.72" + id="path10351" /> + d="m 253,1525.4716 c 9.4,-9.41 9.4,-24.7 -0.008,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.4,9.409 -9.4,24.7 0.008,34.1 9.4,9.41 24.7,9.41 34.1,0.01" + id="path10355" /> + d="m 235,1500 0,10.9 -2.77,-2.14 -1.83,2.5 4.89,3.59 3.23,0 0,-14.9 -3.53,0 z" + id="path10359" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + d="m 1090,1480 c 1.8,1.8 4.71,1.8 6.5,0 1.8,-1.8 1.8,-4.71 0,-6.5 l -161,-161 c -1.8,-1.8 -4.71,-1.8 -6.5,0 -1.8,1.8 -1.8,4.71 0,6.5 l 161,161 z" + id="path5031" /> + stroke-miterlimit="10" + d="m 1090,1480 c 1.8,1.8 4.71,1.8 6.5,0 1.8,-1.8 1.8,-4.71 0,-6.5 l -161,-161 c -1.8,-1.8 -4.71,-1.8 -6.5,0 -1.8,1.8 -1.8,4.71 0,6.5 l 161,161 z" + id="path5035" /> + d="m 1100,1320 c 1.8,-1.8 1.8,-4.71 0,-6.5 -1.8,-1.8 -4.71,-1.8 -6.5,0 l -161,161 c -1.8,1.8 -1.8,4.71 0,6.5 1.8,1.8 4.71,1.8 6.5,0 l 161,-161 z" + id="path5039" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + stroke-miterlimit="10" + d="m 1100,1320 c 1.8,-1.8 1.8,-4.71 0,-6.5 -1.8,-1.8 -4.71,-1.8 -6.5,0 l -161,161 c -1.8,1.8 -1.8,4.71 0,6.5 1.8,1.8 4.71,1.8 6.5,0 l 161,-161 z" + id="path5043" /> - - - - - - - + transform="matrix(1,0,0,-1,0,2792.2535)" + id="g5053"> + style="opacity:0.5" + clip-path="url(#clipPath5049)" + id="g5055"> - - - + transform="translate(1170.2617,1551.2617)" + id="g5057"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5065)" + id="g5071"> - - - + transform="translate(977.2441,1551.2617)" + id="g5073"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5081)" + id="g5087"> - - - + transform="translate(1170.2617,1361.2432)" + id="g5089"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5097)" + id="g5103"> - - - + transform="translate(977.2441,1361.2432)" + id="g5105"> + + + + + + - - - + style="opacity:0.69999701" + clip-path="url(#clipPath5135)" + id="g5151"> + id="g5153"> + id="g5155"> + id="g5157"> - - - + id="g5159"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5167)" + id="g5183"> + id="g5185"> + id="g5187"> + id="g5189"> - - - + id="g5191"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5199)" + id="g5215"> + id="g5217"> + id="g5219"> + id="g5221"> - - - + id="g5223"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5231)" + id="g5247"> + id="g5249"> + id="g5251"> + id="g5253"> - - - + id="g5255"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5263)" + id="g5279"> + id="g5281"> + id="g5283"> + id="g5285"> - - - + id="g5287"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5295)" + id="g5311"> + id="g5313"> + id="g5315"> + id="g5317"> - - - + id="g5319"> + + + + style="opacity:0.69999701;fill:url(#linearGradient8778)" + clip-path="url(#clipPath5327)" + id="g5343"> + style="fill:url(#linearGradient8776)" + id="g5345"> + style="fill:url(#linearGradient8774)" + id="g5347"> + style="fill:url(#linearGradient8772)" + id="g5349"> - - - + style="fill:url(#linearGradient8770)" + id="g5351"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5359)" + id="g5375"> + id="g5377"> + id="g5379"> + id="g5381"> - - - + id="g5383"> + - - - - - - - - - - - - + d="m 934,1288.1 c 9.4,9.41 9.4,24.7 -0.008,34.1 -9.41,9.41 -24.7,9.41 -34.1,0 -9.4,-9.41 -9.4,-24.7 0.008,-34.1 9.41,-9.41 24.7,-9.41 34.1,-0.01" + id="path5389" /> + d="m 916,1312.7 0,-10.9 -2.77,2.14 -1.83,-2.5 4.89,-3.59 3.23,0 0,14.9 -3.53,0 z" + id="path5393" /> + d="m 1130,1288.1 c 9.4,9.41 9.4,24.7 -0.01,34.1 -9.41,9.41 -24.7,9.41 -34.1,0 -9.4,-9.41 -9.4,-24.7 0.01,-34.1 9.41,-9.41 24.7,-9.41 34.1,-0.01" + id="path5397" /> - - + d="m 1108.1,1312.7 0,-2.94 5.8,-5.25 c 0.734,-0.693 1.22,-1.39 1.22,-2.29 0,-1.05 -0.736,-1.78 -1.85,-1.78 -1.18,0 -1.95,0.924 -2.1,2.25 l -3.38,-0.462 c 0.335,-3 2.77,-4.79 5.67,-4.79 2.73,0 5.38,1.45 5.38,4.56 0,2.12 -1.24,3.36 -2.6,4.58 l -3.44,3.07 h 6.07 v 3.06 h -10.8 z" + id="path5401" /> + + + d="m 1124.6,1477.3 c 9.4,9.41 9.4,24.7 -0.01,34.1 -9.41,9.41 -24.7,9.41 -34.1,0 -9.4,-9.41 -9.4,-24.7 0.01,-34.1 9.41,-9.41 24.7,-9.41 34.1,-0.01" + id="path5413" /> + style="fill:#ffffff;fill-rule:nonzero" + inkscape:connector-curvature="0" + d="m 1107.3,1502.7 c -2.71,0 -5.16,-1.18 -5.96,-3.95 l 3.28,-0.861 c 0.274,0.987 1.18,1.85 2.52,1.85 1.01,0 2.16,-0.504 2.16,-1.89 0,-1.51 -1.55,-1.95 -3.02,-1.95 h -0.945 v -2.58 h 1.03 c 1.32,0 2.6,-0.336 2.6,-1.76 0,-1.07 -0.902,-1.64 -1.87,-1.64 -1.01,0 -1.81,0.65 -2.04,1.66 l -3.28,-0.756 c 0.712,-2.5 3.06,-3.78 5.54,-3.78 2.62,0 5.23,1.34 5.23,4.2 0,1.64 -1.05,2.86 -2.5,3.23 v 0.063 c 1.68,0.398 2.86,1.78 2.86,3.44 0,3.25 -2.88,4.72 -5.6,4.72" + id="path5417" /> + + + + d="m 1030,1420 2.56,0 c 0.281,0 0.5,0.107 0.695,0.297 0.102,0.088 0.176,0.199 0.215,0.314 0.051,0.118 0.086,0.246 0.086,0.387 v 0.914 c 0,0.135 -0.035,0.266 -0.086,0.395 -0.039,0.107 -0.113,0.209 -0.215,0.298 -0.195,0.194 -0.414,0.299 -0.695,0.299 H 1030 c -0.275,0 -0.504,-0.105 -0.691,-0.299 -0.104,-0.089 -0.176,-0.191 -0.225,-0.298 -0.041,-0.129 -0.08,-0.26 -0.08,-0.395 v -0.914 c 0,-0.141 0.039,-0.269 0.08,-0.387 0.049,-0.115 0.121,-0.226 0.225,-0.314 0.187,-0.19 0.416,-0.297 0.691,-0.297 m -12.4,0 2.56,0 c 0.278,0 0.498,0.107 0.69,0.297 0.191,0.187 0.307,0.426 0.307,0.701 v 0.914 c 0,0.277 -0.116,0.526 -0.307,0.693 -0.184,0.192 -0.41,0.299 -0.676,0.299 h -3.57 v -0.992 -0.521 -0.393 c 0,-0.141 0.035,-0.269 0.084,-0.387 0.051,-0.115 0.129,-0.226 0.228,-0.314 0.176,-0.19 0.403,-0.297 0.684,-0.297 m -15,0 2.55,0 c 0.287,0 0.508,0.107 0.703,0.297 0.094,0.088 0.164,0.199 0.211,0.314 0.053,0.118 0.082,0.246 0.082,0.379 h -4.54 c 0,-0.133 0.033,-0.261 0.082,-0.379 0.049,-0.115 0.119,-0.226 0.217,-0.314 0.189,-0.19 0.426,-0.297 0.697,-0.297 m -7.51,0 2.54,0 c 0.281,0 0.519,0.107 0.715,0.297 0.197,0.187 0.281,0.426 0.281,0.701 v 0.914 c 0,0.277 -0.084,0.526 -0.281,0.693 -0.196,0.194 -0.434,0.299 -0.715,0.299 h -1.89 -1.64 v -0.992 -0.521 -0.393 c 0,-0.141 0.02,-0.269 0.073,-0.387 0.062,-0.115 0.135,-0.226 0.226,-0.314 0.18,-0.19 0.418,-0.297 0.7,-0.297 m -7.52,0 2.54,0 c 0.277,0 0.522,0.107 0.711,0.297 0.088,0.088 0.156,0.199 0.213,0.314 0.051,0.118 0.074,0.246 0.074,0.387 v 0.914 c 0,0.135 -0.023,0.266 -0.074,0.395 -0.057,0.107 -0.125,0.209 -0.213,0.298 -0.189,0.194 -0.434,0.299 -0.711,0.299 h -0.318 -2.22 c -0.283,0 -0.516,-0.105 -0.713,-0.299 -0.082,-0.089 -0.158,-0.191 -0.211,-0.298 -0.055,-0.129 -0.074,-0.26 -0.074,-0.395 v -0.914 c 0,-0.141 0.019,-0.269 0.074,-0.387 0.053,-0.115 0.129,-0.226 0.211,-0.314 0.197,-0.19 0.43,-0.297 0.713,-0.297 m 42.4,-1.04 c -0.28,0 -0.543,0.049 -0.797,0.166 -0.231,0.088 -0.451,0.242 -0.619,0.42 -0.192,0.189 -0.338,0.406 -0.456,0.652 -0.107,0.254 -0.14,0.52 -0.14,0.793 v 0.93 c 0,0.281 0.033,0.547 0.14,0.795 0.118,0.242 0.264,0.455 0.456,0.642 0.168,0.178 0.388,0.332 0.619,0.426 0.254,0.115 0.517,0.16 0.797,0.16 h 2.69 c 0.277,0 0.543,-0.045 0.791,-0.16 0.236,-0.094 0.457,-0.248 0.637,-0.426 0.187,-0.187 0.332,-0.4 0.443,-0.642 0.098,-0.248 0.148,-0.514 0.148,-0.795 v -0.93 c 0,-0.273 -0.05,-0.539 -0.148,-0.793 -0.111,-0.246 -0.256,-0.463 -0.443,-0.652 -0.18,-0.178 -0.401,-0.332 -0.637,-0.42 -0.248,-0.117 -0.514,-0.166 -0.791,-0.166 h -2.69 z m -27.4,0 c -0.276,0 -0.541,0.049 -0.799,0.166 -0.236,0.088 -0.451,0.242 -0.623,0.42 -0.186,0.189 -0.34,0.406 -0.449,0.652 -0.108,0.252 -0.156,0.508 -0.156,0.785 v 0.93 c 0,0.277 0.048,0.541 0.156,0.795 0.109,0.244 0.263,0.463 0.449,0.65 0.172,0.178 0.387,0.332 0.623,0.426 0.258,0.115 0.523,0.16 0.799,0.16 h 4.11 v -1.04 h -4.04 c -0.271,0 -0.508,-0.105 -0.697,-0.299 -0.074,-0.078 -0.133,-0.16 -0.18,-0.257 -0.056,-0.096 -0.091,-0.203 -0.107,-0.303 h 5.63 v -1.06 c 0,-0.277 -0.053,-0.533 -0.145,-0.785 -0.117,-0.246 -0.254,-0.463 -0.451,-0.652 -0.182,-0.178 -0.4,-0.332 -0.644,-0.42 -0.233,-0.117 -0.498,-0.166 -0.791,-0.166 h -2.68 z m -15,0 c -0.289,0 -0.555,0.049 -0.791,0.166 -0.252,0.088 -0.461,0.242 -0.647,0.42 -0.183,0.189 -0.334,0.406 -0.445,0.652 -0.1,0.254 -0.153,0.52 -0.153,0.793 v 0.93 c 0,0.281 0.053,0.547 0.153,0.795 0.111,0.242 0.262,0.455 0.445,0.642 0.186,0.178 0.395,0.332 0.647,0.426 0.236,0.115 0.502,0.16 0.791,0.16 h 2.01 0.664 2.8 v 1.99 h 1.11 v -1.99 h 0.928 0.36 2.32 c 0.283,0 0.545,-0.045 0.783,-0.16 0.254,-0.094 0.463,-0.248 0.656,-0.426 0.192,-0.187 0.332,-0.4 0.434,-0.642 0.099,-0.248 0.158,-0.514 0.158,-0.795 v -0.93 c 0,-0.273 -0.059,-0.539 -0.158,-0.793 -0.102,-0.246 -0.242,-0.463 -0.434,-0.652 -0.193,-0.178 -0.402,-0.332 -0.656,-0.42 -0.238,-0.117 -0.5,-0.166 -0.783,-0.166 h -2.68 c -0.281,0 -0.545,0.049 -0.793,0.166 -0.242,0.088 -0.455,0.242 -0.64,0.42 -0.188,0.189 -0.34,0.406 -0.44,0.652 -0.109,0.254 -0.166,0.52 -0.166,0.793 v 1.91 h -1.02 c 0.025,-0.062 0.066,-0.127 0.085,-0.189 0.112,-0.248 0.165,-0.514 0.165,-0.795 v -0.93 c 0,-0.273 -0.053,-0.539 -0.165,-0.793 -0.091,-0.246 -0.244,-0.463 -0.423,-0.652 -0.192,-0.178 -0.407,-0.332 -0.653,-0.42 -0.252,-0.117 -0.515,-0.166 -0.797,-0.166 h -2.68 z m 35.5,4.98 1.1,0 0,-5 -1.1,0 0,5 z m -13,-5 c -0.272,0 -0.539,0.059 -0.791,0.182 -0.227,0.088 -0.446,0.242 -0.625,0.42 -0.186,0.189 -0.336,0.406 -0.451,0.652 -0.096,0.252 -0.139,0.508 -0.139,0.785 v 2.96 h 1.09 v -2.95 c 0,-0.273 0.111,-0.513 0.299,-0.707 0.08,-0.09 0.199,-0.158 0.304,-0.213 0.121,-0.052 0.242,-0.074 0.379,-0.074 h 2.57 c 0.132,0 0.263,0.022 0.369,0.074 0.121,0.055 0.244,0.123 0.314,0.213 0.197,0.194 0.303,0.434 0.303,0.707 v 2.95 h 0.305 0.785 0.779 v 1.99 h 1.09 v -1.99 h 0.927 2.3 0.407 c 0.265,0 0.531,-0.045 0.781,-0.16 0.23,-0.094 0.453,-0.248 0.631,-0.426 0.185,-0.187 0.338,-0.4 0.445,-0.642 0.103,-0.248 0.141,-0.514 0.141,-0.795 v -0.93 c 0,-0.273 -0.038,-0.539 -0.141,-0.793 -0.107,-0.246 -0.26,-0.463 -0.445,-0.652 -0.178,-0.178 -0.401,-0.332 -0.631,-0.42 -0.25,-0.117 -0.516,-0.166 -0.781,-0.166 h -2.71 c -0.279,0 -0.542,0.049 -0.792,0.166 -0.225,0.088 -0.438,0.242 -0.625,0.42 -0.188,0.189 -0.338,0.406 -0.454,0.652 -0.099,0.254 -0.15,0.52 -0.15,0.793 v 1.91 h -0.779 v -1.91 -0.01 c 0,-0.277 -0.053,-0.533 -0.139,-0.785 -0.117,-0.246 -0.262,-0.463 -0.449,-0.652 -0.184,-0.178 -0.406,-0.332 -0.643,-0.42 -0.23,-0.123 -0.498,-0.182 -0.779,-0.182 h -2.7 z m 25.6,-1.43 0,1.22 -0.49,0 0,1.05 0.49,0 0,2.13 c 0,0.281 0.062,0.547 0.154,0.795 0.113,0.242 0.254,0.455 0.44,0.642 0.193,0.178 0.4,0.332 0.652,0.426 0.234,0.115 0.5,0.16 0.791,0.16 h 0.791 v -1.04 h -0.777 c -0.27,-0.025 -0.504,-0.129 -0.664,-0.32 -0.096,-0.078 -0.168,-0.191 -0.211,-0.307 -0.049,-0.105 -0.065,-0.232 -0.065,-0.365 v -2.12 h 1.72 v -0.223 -0.83 h -1.72 v -1.22 h -1.11 z m -10.8,-0.563 0,4.96 c 0,0.277 0.06,0.541 0.162,0.795 0.1,0.244 0.238,0.463 0.432,0.639 0.197,0.183 0.398,0.332 0.66,0.437 0.236,0.115 0.492,0.16 0.777,0.16 h 0.221 v -1.04 h -0.201 c -0.262,-0.025 -0.477,-0.129 -0.664,-0.32 -0.088,-0.078 -0.157,-0.191 -0.198,-0.307 -0.064,-0.105 -0.068,-0.232 -0.068,-0.365 v -4.96 h -1.12 z m -1.86,1.1 1.1,0 0,-1.1 -1.1,0 0,1.1 z" + id="path7087" /> + + + + + + + + + + + - - - - + id="g5429"> - - + d="m 1640,1430 2.77,0 0,-17.2 17.2,0 0,17.2 3.07,0 -11.5,11.5 -11.5,-11.5 z" + id="path5437" /> + + + + + + + style="opacity:0.5" + clip-path="url(#clipPath5467)" + id="g5473"> - - - + transform="translate(1823.7813,1443.3135)" + id="g5475"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5483)" + id="g5489"> - - - + transform="translate(1687.2949,1579.7949)" + id="g5491"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5499)" + id="g5505"> - - - + transform="translate(1689.418,1308.9482)" + id="g5507"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5515)" + id="g5521"> - - - + transform="translate(1552.9316,1445.4316)" + id="g5523"> + + + + + + - - - + style="opacity:0.69999701" + clip-path="url(#clipPath5553)" + id="g5569"> + id="g5571"> + id="g5573"> + id="g5575"> - - - + id="g5577"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5585)" + id="g5601"> + id="g5603"> + id="g5605"> + id="g5607"> - - - + id="g5609"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5617)" + id="g5633"> + id="g5635"> + id="g5637"> + id="g5639"> - - - + id="g5641"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5649)" + id="g5665"> + id="g5667"> + id="g5669"> + id="g5671"> - - - + id="g5673"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5681)" + id="g5697"> + id="g5699"> + id="g5701"> + id="g5703"> - - - + id="g5705"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5713)" + id="g5729"> + id="g5731"> + id="g5733"> + id="g5735"> - - - + id="g5737"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5745)" + id="g5761"> + id="g5763"> + id="g5765"> + id="g5767"> - - - + id="g5769"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5777)" + id="g5793"> + id="g5795"> + id="g5797"> + id="g5799"> - - - + id="g5801"> + - - - - - - - - - - - - + + + + + d="m 1510,1400 c 9.4,-9.41 9.4,-24.7 -0.01,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.41,9.41 -9.41,24.7 0.01,34.1 9.41,9.41 24.7,9.41 34.1,0.01" + id="path5823" /> + + + + + + + + + + + + + + + + transform="matrix(1.25,0,0,-1.25,-596.76331,2570.3294)" + id="3454"> + + stroke-miterlimit="10" + d="m 2440,1270 c 3.33,-1.92 7.05,-1.7 8.32,0.508 1.27,2.2 -0.396,5.54 -3.72,7.46 l -299,173 c -3.32,1.92 -7.05,1.69 -8.32,-0.508 -1.27,-2.198 0.399,-5.54 3.72,-7.46 l 299,-173 z" + id="path4247" /> + d="m 2450,1440 c 3.33,1.92 4.99,5.26 3.72,7.46 -1.27,2.2 -4.99,2.43 -8.32,0.506 l -299,-173 c -3.32,-1.92 -4.99,-5.26 -3.72,-7.46 1.27,-2.2 5,-2.43 8.32,-0.504 l 299,173 z" + id="path4251" /> + stroke-miterlimit="10" + d="m 2450,1440 c 3.33,1.92 4.99,5.26 3.72,7.46 -1.27,2.2 -4.99,2.43 -8.32,0.506 l -299,-173 c -3.32,-1.92 -4.99,-5.26 -3.72,-7.46 1.27,-2.2 5,-2.43 8.32,-0.504 l 299,173 z" + id="path4255" /> + d="m 2300,1530 c 0,3.84 -2.06,6.96 -4.6,6.95 -2.54,10e-4 -4.6,-3.11 -4.6,-6.95 v -345 c 0,-3.84 2.06,-6.95 4.6,-6.95 2.54,0 4.6,3.12 4.6,6.96 l 0,345 z" + id="path4259" /> + stroke-miterlimit="10" + d="m 2300,1530 c 0,3.84 -2.06,6.96 -4.6,6.95 -2.54,10e-4 -4.6,-3.11 -4.6,-6.95 v -345 c 0,-3.84 2.06,-6.95 4.6,-6.95 2.54,0 4.6,3.12 4.6,6.96 l 0,345 z" + id="path4263" /> - - - - + id="g4307"> - - - - + d="m 2310,1410 2.77,0 0,-17.2 17.2,0 0,17.2 3.07,0 -11.5,11.5 -11.5,-11.5 z" + id="path4315" /> + + + style="opacity:0.5" + clip-path="url(#clipPath5841)" + id="g5847"> - - - + transform="translate(2515.9893,1514.8203)" + id="g5849"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5857)" + id="g5863"> - - - + transform="translate(2355.4863,1607.2334)" + id="g5865"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5873)" + id="g5879"> - - - + transform="translate(2516.0371,1330.8896)" + id="g5881"> + + + + style="opacity:0.5" + clip-path="url(#clipPath5889)" + id="g5895"> - - - + transform="translate(2354.9951,1235.6455)" + id="g5897"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5905)" + id="g5921"> + id="g5923"> + id="g5925"> + id="g5927"> - - - + id="g5929"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5937)" + id="g5953"> + id="g5955"> + id="g5957"> + id="g5959"> - - - + id="g5961"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath5969)" + id="g5985"> + id="g5987"> + id="g5989"> + id="g5991"> - - - + id="g5993"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6001)" + id="g6017"> + id="g6019"> + id="g6021"> + id="g6023"> - - - + id="g6025"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6033)" + id="g6049"> + id="g6051"> + id="g6053"> + id="g6055"> - - - + id="g6057"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6065)" + id="g6081"> + id="g6083"> + id="g6085"> + id="g6087"> - - - + id="g6089"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6097)" + id="g6113"> + id="g6115"> + id="g6117"> + id="g6119"> - - - + id="g6121"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6129)" + id="g6145"> + id="g6147"> + id="g6149"> + id="g6151"> - - - + id="g6153"> + - - + + + + + style="opacity:0.5" + clip-path="url(#clipPath6169)" + id="g6175"> - - - + transform="translate(2191.2754,1327.0928)" + id="g6177"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6185)" + id="g6201"> + id="g6203"> + id="g6205"> + id="g6207"> - - - + id="g6209"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6217)" + id="g6233"> + id="g6235"> + id="g6237"> + id="g6239"> - - - + id="g6241"> + - - - - - - + + + + + + + + + style="opacity:0.5" + clip-path="url(#clipPath6273)" + id="g6279"> - - - + transform="translate(2193.8848,1514.2402)" + id="g6281"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6289)" + id="g6305"> + id="g6307"> + id="g6309"> + id="g6311"> - - - + id="g6313"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath6321)" + id="g6337"> + id="g6339"> + id="g6341"> + id="g6343"> - - - + id="g6345"> + - - - - - - - - - - + + + + + + + d="m 2280,1370 -1.31,0.756 1.16,4.26 -2.92,1.59 -6.44,-2.74 -8.89,2.35 7.9,-5.35 3.1,-7.39 4,-1.32 1.26,4.74 1.24,-0.196 0.906,3.31 z" + id="path7865" /> + + + + + + + id="g4333"> + style="opacity:0.5" + clip-path="url(#clipPath4329)" + id="g4335"> - - - + transform="translate(284.2432,1018.4248)" + id="g4337"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4345)" + id="g4361"> + id="g4363"> + id="g4365"> + id="g4367"> - - - + id="g4369"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4377)" + id="g4393"> + id="g4395"> + id="g4397"> + id="g4399"> - - - + id="g4401"> + - - - - - - - + + + + + + + + + + style="opacity:0.5" + clip-path="url(#clipPath4437)" + id="g4443"> - - - + transform="translate(429.3359,762.3701)" + id="g4445"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4453)" + id="g4469"> + id="g4471"> + id="g4473"> + id="g4475"> - - - + id="g4477"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4485)" + id="g4501"> + id="g4503"> + id="g4505"> + id="g4507"> - - - + id="g4509"> + - + + + + style="opacity:0.5" + clip-path="url(#clipPath4925)" + id="g4931"> - - - + transform="translate(262.6084,1040.4229)" + id="g4933"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4941)" + id="g4957"> + id="g4959"> + id="g4961"> + id="g4963"> - - - + id="g4965"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4973)" + id="g4989"> + id="g4991"> + id="g4993"> + id="g4995"> - - - + id="g4997"> + + + + + + - - - + style="opacity:0.5" + clip-path="url(#clipPath7903)" + id="g7909"> - - - + transform="translate(406.8271,782.3682)" + id="g7911"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7919)" + id="g7935"> + id="g7937"> + id="g7939"> + id="g7941"> - - - + id="g7943"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7951)" + id="g7967"> + id="g7969"> + id="g7971"> + id="g7973"> - - - + id="g7975"> + + + + + + + - - + d="m 362,739 c 9.41,-9.41 9.41,-24.7 -0.007,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.41,9.41 -9.41,24.7 0.008,34.1 9.41,9.41 24.7,9.41 34.1,0.008" + id="path8445" /> - - - - - - - - + d="m 344,715 c -2.71,0 -4.96,1.43 -5.65,3.78 l 3.21,0.987 c 0.315,-1.03 1.24,-1.79 2.39,-1.79 1.2,0 2.23,0.736 2.23,2.16 0,1.76 -1.6,2.27 -3.04,2.27 -1.05,0 -2.58,-0.272 -3.63,-0.651 l 0.357,8.5 h 9.11 v -3.02 h -5.98 l -0.127,-2.35 c 0.442,0.105 1.05,0.146 1.49,0.146 2.98,0 5.38,-1.6 5.38,-4.72 0,-3.61 -2.81,-5.31 -5.73,-5.31" + id="path8449" /> + + + d="m 217,994 c 9.4,-9.41 9.4,-24.7 -0.008,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.4,9.41 -9.4,24.7 0.008,34.1 9.4,9.41 24.7,9.41 34.1,0.008" + id="path8453" /> + d="m 199,969 0,10.9 -2.77,-2.14 -1.83,2.5 4.89,3.59 3.23,0 0,-14.9 -3.53,0 z" + id="path8457" /> + + + + + style="opacity:0.5" + clip-path="url(#clipPath4329)" + id="g5146"> - - - + transform="translate(284.2432,1018.4248)" + id="g5148"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4345)" + id="g5154"> + id="g5156"> + id="g5158"> + id="g5160"> - - - + id="g5162"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4377)" + id="g5168"> + id="g5170"> + id="g5172"> + id="g5174"> - - - + id="g5176"> + - + + + + style="opacity:0.5" + clip-path="url(#clipPath4925)" + id="g5184"> - - - + transform="translate(262.6084,1040.4229)" + id="g5186"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4941)" + id="g5192"> + id="g5194"> + id="g5196"> + id="g5198"> - - - + id="g5200"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath4973)" + id="g5206"> + id="g5208"> + id="g5210"> + id="g5212"> - - - + id="g5214"> + + + - - - - + style="fill-rule:nonzero" + id="g5252"> + + + + + + + + + + + + + + + + d="m 2290,818 2.7,0 0,-16.7 16.7,0 0,16.7 2.99,0 -11.2,11.2 -11.2,-11.2 z" + id="path7107" /> + d="m 2470,595 c 3.95,-3.95 8.6,-5.69 10.4,-3.9 1.8,1.8 0.051,6.45 -3.9,10.4 l -355,355 c -3.95,3.95 -8.6,5.69 -10.4,3.9 -1.8,-1.8 -0.053,-6.45 3.9,-10.4 l 355,-355 z" + id="path7119" /> + stroke-miterlimit="10" + d="m 2470,595 c 3.95,-3.95 8.6,-5.69 10.4,-3.9 1.8,1.8 0.051,6.45 -3.9,10.4 l -355,355 c -3.95,3.95 -8.6,5.69 -10.4,3.9 -1.8,-1.8 -0.053,-6.45 3.9,-10.4 l 355,-355 z" + id="path7123" /> + d="m 2470,944 c 3.9,3.9 5.6,8.51 3.8,10.3 -1.8,1.8 -6.41,0.093 -10.3,-3.8 l -350,-350 c -3.9,-3.9 -5.6,-8.51 -3.8,-10.3 1.8,-1.8 6.41,-0.093 10.3,3.8 l 350,350 z" + id="path7127" /> - - - - - - - - - - - - - - - + stroke-miterlimit="10" + d="m 2470,944 c 3.9,3.9 5.6,8.51 3.8,10.3 -1.8,1.8 -6.41,0.093 -10.3,-3.8 l -350,-350 c -3.9,-3.9 -5.6,-8.51 -3.8,-10.3 1.8,-1.8 6.41,-0.093 10.3,3.8 l 350,350 z" + id="path7131" /> + + + + + style="opacity:0.5" + clip-path="url(#clipPath7159)" + id="g7165"> - - - + transform="translate(2538.3311,837.6123)" + id="g7167"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7175)" + id="g7191"> + id="g7193"> + id="g7195"> + id="g7197"> - - - + id="g7199"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7207)" + id="g7223"> + id="g7225"> + id="g7227"> + id="g7229"> - - - + id="g7231"> + + + + style="opacity:0.5" + clip-path="url(#clipPath7239)" + id="g7245"> - - - + transform="translate(2538.3311,657.5947)" + id="g7247"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7255)" + id="g7271"> + id="g7273"> + id="g7275"> + id="g7277"> - - - + id="g7279"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7287)" + id="g7303"> + id="g7305"> + id="g7307"> + id="g7309"> - - - + id="g7311"> + + + + style="opacity:0.5" + clip-path="url(#clipPath7319)" + id="g7325"> - - - + transform="translate(2538.3252,1017.5234)" + id="g7327"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7335)" + id="g7351"> + id="g7353"> + id="g7355"> + id="g7357"> - - - + id="g7359"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7367)" + id="g7383"> + id="g7385"> + id="g7387"> + id="g7389"> - - - + id="g7391"> + - - - - - - + + + + + + + + + style="opacity:0.5" + clip-path="url(#clipPath7423)" + id="g7429"> - - - + transform="translate(2056.7451,837.6123)" + id="g7431"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7439)" + id="g7455"> + id="g7457"> + id="g7459"> + id="g7461"> - - - + id="g7463"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7471)" + id="g7487"> + id="g7489"> + id="g7491"> + id="g7493"> - - - + id="g7495"> + + + + style="opacity:0.5" + clip-path="url(#clipPath7503)" + id="g7509"> - - - + transform="translate(2056.7451,657.5947)" + id="g7511"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7519)" + id="g7535"> + id="g7537"> + id="g7539"> + id="g7541"> - - - + id="g7543"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7551)" + id="g7567"> + id="g7569"> + id="g7571"> + id="g7573"> - - - + id="g7575"> + + + + style="opacity:0.5" + clip-path="url(#clipPath7583)" + id="g7589"> - - - + transform="translate(2056.7471,1017.5234)" + id="g7591"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7599)" + id="g7615"> + id="g7617"> + id="g7619"> + id="g7621"> - - - + id="g7623"> + + + + style="opacity:0.69999701" + clip-path="url(#clipPath7631)" + id="g7647"> + id="g7649"> + id="g7651"> + id="g7653"> - - - + id="g7655"> + - - - - - - - - - - + + + + + d="m 2138,613 c 9.41,-9.41 9.41,-24.7 -0.01,-34.1 -9.41,-9.41 -24.7,-9.41 -34.1,0 -9.41,9.41 -9.41,24.7 0.01,34.1 9.41,9.41 24.7,9.41 34.1,0.008" + id="path7677" /> + d="m 2120,599 -0.063,0 -3.53,-5.5 3.59,0 0,5.5 z m 3.28,-8.36 0,-2.9 -3.3,0 0,2.9 -6.99,0 0,2.96 6.05,9.01 4.22,0 0,-9.11 2.06,0 0,-2.86 -2.04,0 z" + id="path7681" /> + d="m 2270,809 62.1,0 c 1.63,0 2.95,-1.32 2.95,-2.95 v -62.1 c 0,-1.63 -1.32,-2.95 -2.95,-2.95 H 2270 c -1.63,0 -2.95,1.32 -2.95,2.95 v 62.1 c 0,1.63 1.32,2.95 2.95,2.95" + id="path7685" /> + d="m 2290,774 -2.78,-9.4 7.16,-3.94 2.89,11 -7.27,2.36 z m -1.79,16.9 -3.04,-12.3 1.96,-0.745 11.1,-3.97 2.99,9.89 -13,7.07 z m 12.8,13.2 c -1.15,0.022 -2.18,-0.468 -2.61,-1.87 l -4.04,-13.6 6.49,-3.55 2.8,10.6 c 0.793,1.24 1.93,0.761 3.16,0.014 l 9.6,-6.33 c 0.848,-0.699 1.4,-1.66 1.35,-3.17 l -0.592,-8.39 c -0.113,-1.18 -0.826,-1.89 -1.37,-1.78 l -15.2,8.23 -2.69,-10.2 3.7,-1.34 v -0.006 l 15.2,-5.49 c 2.26,-0.824 4.28,1.66 4.36,5.4 l 0.065,13.4 c -0.049,3.31 -1.64,5.1 -3.24,6.39 l -12.7,9.9 c -1.06,0.864 -2.79,1.74 -4.3,1.77" + id="path7689" /> + d="m 2290,787 -1.31,0.757 1.16,4.26 -2.92,1.59 -6.44,-2.74 -8.88,2.35 7.89,-5.36 3.1,-7.39 4,-1.32 1.26,4.74 1.24,-0.195 0.908,3.31 z" + id="path7693" /> + d="m 2320,752 2.56,0 c 0.281,0 0.5,-0.107 0.695,-0.296 0.102,-0.089 0.176,-0.2 0.215,-0.314 0.051,-0.119 0.086,-0.246 0.086,-0.387 v -0.914 c 0,-0.135 -0.035,-0.266 -0.086,-0.396 -0.039,-0.106 -0.113,-0.209 -0.215,-0.298 -0.195,-0.194 -0.414,-0.299 -0.695,-0.299 H 2320 c -0.275,0 -0.504,0.105 -0.691,0.299 -0.104,0.089 -0.176,0.192 -0.225,0.298 -0.041,0.13 -0.08,0.261 -0.08,0.396 v 0.914 c 0,0.141 0.039,0.268 0.08,0.387 0.049,0.114 0.121,0.225 0.225,0.314 0.187,0.189 0.416,0.296 0.691,0.296 m -12.4,0 2.56,0 c 0.278,0 0.498,-0.107 0.69,-0.296 0.191,-0.187 0.307,-0.427 0.307,-0.701 v -0.914 c 0,-0.277 -0.116,-0.527 -0.307,-0.694 -0.184,-0.191 -0.41,-0.298 -0.676,-0.299 h -3.57 v 0.993 0.521 0.393 c 0,0.141 0.033,0.268 0.082,0.387 0.051,0.114 0.131,0.225 0.23,0.314 0.174,0.189 0.401,0.296 0.682,0.296 m -15,0 2.55,0 c 0.287,0 0.508,-0.107 0.703,-0.296 0.096,-0.089 0.164,-0.2 0.213,-0.314 0.053,-0.119 0.082,-0.246 0.082,-0.38 h -4.54 c 0,0.134 0.035,0.261 0.082,0.38 0.049,0.114 0.121,0.225 0.217,0.314 0.191,0.189 0.428,0.296 0.697,0.296 m -7.51,0 2.54,0 c 0.281,0 0.521,-0.107 0.715,-0.296 0.197,-0.187 0.281,-0.427 0.281,-0.701 v -0.914 c 0,-0.277 -0.084,-0.527 -0.281,-0.694 -0.194,-0.194 -0.434,-0.299 -0.715,-0.299 h -1.89 -1.64 v 0.993 0.521 0.393 c 0,0.141 0.018,0.268 0.071,0.387 0.062,0.114 0.135,0.225 0.226,0.314 0.18,0.189 0.418,0.296 0.7,0.296 m -7.52,0 2.54,0 c 0.275,0 0.52,-0.107 0.709,-0.296 0.088,-0.089 0.158,-0.2 0.213,-0.314 0.053,-0.119 0.074,-0.246 0.074,-0.387 v -0.914 c 0,-0.135 -0.021,-0.266 -0.074,-0.396 -0.055,-0.106 -0.125,-0.209 -0.213,-0.298 -0.189,-0.194 -0.434,-0.299 -0.709,-0.299 h -0.318 -2.22 c -0.283,0 -0.516,0.105 -0.713,0.299 -0.082,0.089 -0.158,0.192 -0.211,0.298 -0.055,0.13 -0.072,0.261 -0.072,0.396 v 0.914 c 0,0.141 0.017,0.268 0.072,0.387 0.053,0.114 0.129,0.225 0.211,0.314 0.197,0.189 0.43,0.296 0.713,0.296 m 42.4,1.04 c -0.28,0 -0.543,-0.05 -0.797,-0.167 -0.231,-0.088 -0.451,-0.241 -0.619,-0.419 -0.192,-0.19 -0.338,-0.406 -0.456,-0.652 -0.107,-0.255 -0.14,-0.521 -0.14,-0.794 v -0.929 c 0,-0.282 0.033,-0.548 0.14,-0.795 0.118,-0.243 0.264,-0.456 0.456,-0.642 0.168,-0.179 0.388,-0.332 0.619,-0.427 0.254,-0.115 0.517,-0.159 0.797,-0.159 h 2.69 c 0.277,0 0.543,0.044 0.791,0.159 0.236,0.095 0.457,0.248 0.637,0.427 0.187,0.186 0.332,0.399 0.443,0.642 0.098,0.247 0.148,0.513 0.148,0.795 v 0.929 c 0,0.273 -0.05,0.539 -0.148,0.794 -0.111,0.246 -0.256,0.462 -0.443,0.652 -0.18,0.178 -0.401,0.331 -0.637,0.419 -0.248,0.117 -0.514,0.167 -0.791,0.167 h -2.69 z m -27.4,0 c -0.274,0 -0.539,-0.05 -0.797,-0.167 -0.238,-0.088 -0.453,-0.241 -0.625,-0.419 -0.186,-0.19 -0.34,-0.406 -0.449,-0.652 -0.108,-0.252 -0.156,-0.509 -0.156,-0.786 v -0.929 c 0,-0.277 0.048,-0.542 0.156,-0.796 0.109,-0.243 0.263,-0.463 0.449,-0.649 0.172,-0.179 0.387,-0.332 0.625,-0.427 0.258,-0.115 0.523,-0.159 0.797,-0.159 h 4.11 v 1.04 h -4.05 c -0.269,0 -0.506,0.105 -0.697,0.299 -0.072,0.078 -0.131,0.161 -0.178,0.257 -0.058,0.097 -0.093,0.204 -0.109,0.304 h 5.63 v 1.06 c 0,0.277 -0.053,0.534 -0.145,0.786 -0.117,0.246 -0.254,0.462 -0.451,0.652 -0.182,0.178 -0.398,0.331 -0.644,0.419 -0.233,0.117 -0.498,0.167 -0.789,0.167 h -2.68 z m -15,0 c -0.289,0 -0.553,-0.05 -0.791,-0.167 -0.252,-0.088 -0.461,-0.241 -0.647,-0.419 -0.183,-0.19 -0.334,-0.406 -0.445,-0.652 -0.098,-0.255 -0.151,-0.521 -0.151,-0.794 v -0.929 c 0,-0.282 0.053,-0.548 0.151,-0.795 0.111,-0.243 0.262,-0.456 0.445,-0.642 0.186,-0.179 0.395,-0.332 0.647,-0.427 0.238,-0.115 0.502,-0.159 0.791,-0.159 h 2.01 0.664 2.8 v -1.99 h 1.11 v 1.99 h 0.926 0.36 2.33 c 0.281,0 0.543,0.044 0.781,0.159 0.254,0.095 0.463,0.248 0.656,0.427 0.192,0.186 0.334,0.399 0.434,0.642 0.101,0.247 0.158,0.513 0.158,0.795 v 0.929 c 0,0.273 -0.057,0.539 -0.158,0.794 -0.1,0.246 -0.242,0.462 -0.434,0.652 -0.193,0.178 -0.402,0.331 -0.656,0.419 -0.238,0.117 -0.5,0.167 -0.781,0.167 h -2.69 c -0.281,0 -0.543,-0.05 -0.793,-0.167 -0.242,-0.088 -0.453,-0.241 -0.64,-0.419 -0.186,-0.19 -0.34,-0.406 -0.44,-0.652 -0.109,-0.255 -0.164,-0.521 -0.164,-0.794 v -1.91 h -1.02 c 0.027,0.063 0.066,0.128 0.087,0.19 0.112,0.247 0.164,0.513 0.164,0.795 v 0.929 c 0,0.273 -0.052,0.539 -0.164,0.794 -0.093,0.246 -0.244,0.462 -0.423,0.652 -0.194,0.178 -0.407,0.331 -0.655,0.419 -0.252,0.117 -0.515,0.167 -0.797,0.167 h -2.68 z m 35.5,-4.98 1.1,0 0,5 -1.1,0 0,-5 z m -13,5 c -0.272,0 -0.537,-0.059 -0.791,-0.183 -0.227,-0.088 -0.446,-0.241 -0.625,-0.419 -0.186,-0.19 -0.336,-0.406 -0.451,-0.652 -0.096,-0.252 -0.139,-0.509 -0.139,-0.786 v -2.96 h 1.09 v 2.95 c 0,0.273 0.111,0.514 0.299,0.708 0.082,0.089 0.199,0.157 0.304,0.213 0.121,0.052 0.242,0.074 0.379,0.074 h 2.57 c 0.132,0 0.265,-0.022 0.369,-0.074 0.121,-0.056 0.244,-0.124 0.314,-0.213 0.197,-0.194 0.303,-0.435 0.303,-0.708 v -2.95 h 0.306 0.784 0.779 v -1.99 h 1.1 v 1.99 h 0.925 2.3 0.407 c 0.265,0 0.531,0.044 0.781,0.159 0.23,0.095 0.453,0.248 0.631,0.427 0.185,0.186 0.338,0.399 0.445,0.642 0.103,0.247 0.141,0.513 0.141,0.795 v 0.929 c 0,0.273 -0.038,0.539 -0.141,0.794 -0.107,0.246 -0.26,0.462 -0.445,0.652 -0.178,0.178 -0.401,0.331 -0.631,0.419 -0.25,0.117 -0.516,0.167 -0.781,0.167 h -2.71 c -0.279,0 -0.542,-0.05 -0.792,-0.167 -0.223,-0.088 -0.438,-0.241 -0.625,-0.419 -0.188,-0.19 -0.338,-0.406 -0.454,-0.652 -0.099,-0.255 -0.15,-0.521 -0.15,-0.794 v -1.91 h -0.779 v 1.91 0.008 c 0,0.277 -0.051,0.534 -0.139,0.786 -0.117,0.246 -0.26,0.462 -0.449,0.652 -0.184,0.178 -0.406,0.331 -0.643,0.419 -0.23,0.124 -0.496,0.183 -0.779,0.183 h -2.7 z m 25.6,1.43 0,-1.22 -0.49,0 0,-1.05 0.49,0 0,-2.13 c 0,-0.282 0.062,-0.548 0.154,-0.795 0.113,-0.243 0.254,-0.456 0.44,-0.642 0.193,-0.179 0.4,-0.332 0.652,-0.427 0.234,-0.115 0.5,-0.159 0.791,-0.159 h 0.791 v 1.04 h -0.777 c -0.27,0.025 -0.504,0.13 -0.664,0.32 -0.096,0.079 -0.168,0.192 -0.211,0.308 -0.049,0.104 -0.065,0.232 -0.065,0.365 v 2.12 h 1.72 v 0.224 0.83 h -1.72 v 1.22 h -1.11 z m -10.8,0.564 0,-4.96 c 0,-0.277 0.06,-0.542 0.162,-0.796 0.1,-0.243 0.238,-0.463 0.432,-0.638 0.197,-0.184 0.398,-0.332 0.66,-0.438 0.236,-0.115 0.492,-0.159 0.777,-0.159 h 0.221 v 1.04 l -0.201,0.003 c -0.262,0.025 -0.477,0.13 -0.664,0.32 -0.088,0.079 -0.157,0.192 -0.198,0.308 -0.064,0.104 -0.068,0.232 -0.068,0.365 v 4.96 h -1.12 z m -1.86,-1.1 1.1,0 0,1.1 -1.1,0 0,-1.1 z" + id="path7697" /> + + + + + + + + + + + - + style="stroke-width:20.94064903;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" + stroke-miterlimit="4" + transform="matrix(0,0.53382948,1,0,-92.428952,141.22781)" + id="g9957"> + d="m 1890,1470 316,0 -311,0" + id="path8856-5-6" /> - - - - - - - + + + + Spectrum - Spectrum + Satellite - + y="1500.4048" + font-size="40px" + id="tspan4851">Satellite + + + + + - + style="stroke-width:20.94064903;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" + stroke-miterlimit="4" + transform="matrix(0,0.53382948,1,0,-92.428952,141.22781)" + id="g9957-4"> + d="m 1890,1470 316,0 -311,0" + id="path8856-5-6-5" /> - - - - - - - + + + + Futaba - Futaba + S-Bus - + y="1500.4048" + font-size="40px" + style="font-size:40px;text-align:center;text-anchor:middle;fill:#ffffff" + id="tspan4851-2">S-Bus + + - - - - - - - - - - PPM Signal - - - + style="stroke-miterlimit:4;stroke-dasharray:none" + transform="matrix(0.4,0,0,0.4,-57.128189,-153.53265)" + stroke-miterlimit="4" + id="receiver-3"> + + + + - - - - - - - - - - - - Throttle - Roll - Pitch - Yaw - Flight Mode - - - + transform="matrix(0.4,0,0,0.4,-57.650264,-154.52823)" + id="99"> + PPM Signal + - + (8) + + diff --git a/ground/gcs/src/plugins/boards_openpilot/openpilotplugin.cpp b/ground/gcs/src/plugins/boards_openpilot/openpilotplugin.cpp index 93dc65231a7..236cb8dd895 100644 --- a/ground/gcs/src/plugins/boards_openpilot/openpilotplugin.cpp +++ b/ground/gcs/src/plugins/boards_openpilot/openpilotplugin.cpp @@ -28,8 +28,6 @@ #include "openpilotplugin.h" #include "coptercontrol.h" -#include "pipxtreme.h" -#include "revolution.h" #include "revomini.h" #include @@ -60,12 +58,6 @@ void OpenPilotPlugin::extensionsInitialized() CopterControl* cc3d = new CopterControl(); addAutoReleasedObject(cc3d); - PipXtreme* pipx = new PipXtreme(); - addAutoReleasedObject(pipx); - - Revolution* revo = new Revolution(); - addAutoReleasedObject(revo); - RevoMini* rmini = new RevoMini(); addAutoReleasedObject(rmini); diff --git a/ground/gcs/src/plugins/boards_openpilot/pipxtreme.cpp b/ground/gcs/src/plugins/boards_openpilot/pipxtreme.cpp deleted file mode 100644 index b571b9dc75c..00000000000 --- a/ground/gcs/src/plugins/boards_openpilot/pipxtreme.cpp +++ /dev/null @@ -1,160 +0,0 @@ -/** - ****************************************************************************** - * - * @file pipxtreme.cpp - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Boards_OpenPilotPlugin OpenPilot boards support Plugin - * @{ - * @brief Plugin to support boards by the OP project - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "pipxtreme.h" - -#include -#include "uavobjectutil/uavobjectutilmanager.h" -#include - -#include "hwtaulink.h" -#include "rfm22bstatus.h" - -/** - * @brief PipXtreme::PipXtreme - * This is the PipXtreme radio modem definition - */ -PipXtreme::PipXtreme(void) -{ - // Initialize our USB Structure definition here: - USBInfo board; - board.vendorID = 0x20A0; - board.productID = 0x415c; - - setUSBInfo(board); - - boardType = 0x03; -} - -PipXtreme::~PipXtreme() -{ - -} - - -QString PipXtreme::shortName() -{ - return QString("PipXtreme"); -} - -QString PipXtreme::boardDescription() -{ - return QString("The OpenPilot project PipXtreme RF radio modem"); -} - -//! Return which capabilities this board has -bool PipXtreme::queryCapabilities(BoardCapabilities capability) -{ - switch(capability) { - case BOARD_CAPABILITIES_GYROS: - return false; - case BOARD_CAPABILITIES_ACCELS: - return false; - case BOARD_CAPABILITIES_MAGS: - return false; - case BOARD_CAPABILITIES_BAROS: - return false; - case BOARD_CAPABILITIES_RADIO: - return true; - } - return false; -} - -/** - * @brief PipXtreme::getSupportedProtocols - * TODO: this is just a stub, we'll need to extend this a lot with multi protocol support - * TODO: for the PipXtreme, depending on its configuration, it might offer several protocols (uavtalk and raw) - * @return - */ -QStringList PipXtreme::getSupportedProtocols() -{ - - return QStringList("uavtalk"); -} - -QPixmap PipXtreme::getBoardPicture() -{ - return QPixmap(":/images/pipx.png"); -} - -QString PipXtreme::getHwUAVO() -{ - return "PipXtreme"; -} - -/** - * Get the RFM22b device ID this modem - * @return RFM22B device ID or 0 if not supported - */ -quint32 PipXtreme::getRfmID() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - - // Modem has instance 0 - RFM22BStatus *rfm22bStatus = RFM22BStatus::GetInstance(uavoManager,0); - Q_ASSERT(rfm22bStatus); - RFM22BStatus::DataFields rfm22b = rfm22bStatus->getData(); - - return rfm22b.DeviceID; -} - -/** - * Set the coordinator ID. If set to zero this device will - * be a coordinator. - * @return true if successful or false if not - */ -bool PipXtreme::setCoordID(quint32 id, quint32 baud_rate, float rf_power) -{ - Q_UNUSED(baud_rate); - Q_UNUSED(rf_power); - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - - HwTauLink *hwTauLink = HwTauLink::GetInstance(uavoManager); - Q_ASSERT(hwTauLink); - HwTauLink::DataFields settings = hwTauLink->getData(); - - if (id == 0) { - // set as coordinator - settings.Radio = HwTauLink::RADIO_TELEM; - settings.CoordID = 0; - } else { - settings.Radio = HwTauLink::RADIO_TELEM; - settings.CoordID = id; - } - - hwTauLink->setData(settings); - - // save the settings - UAVObjectUtilManager* uavoUtilManager = pm->getObject(); - uavoUtilManager->saveObjectToFlash(hwTauLink); - - return true; -} diff --git a/ground/gcs/src/plugins/boards_taulabs/boards_taulabs.pro b/ground/gcs/src/plugins/boards_taulabs/boards_taulabs.pro index c1d565260e5..95fb9935886 100644 --- a/ground/gcs/src/plugins/boards_taulabs/boards_taulabs.pro +++ b/ground/gcs/src/plugins/boards_taulabs/boards_taulabs.pro @@ -10,7 +10,6 @@ OTHER_FILES += TauLabs.json HEADERS += \ taulabsplugin.h \ - freedom.h \ sparky.h \ sparkybgc.h \ sparkybgcconfiguration.h \ @@ -19,7 +18,6 @@ HEADERS += \ SOURCES += \ taulabsplugin.cpp \ - freedom.cpp \ sparky.cpp \ sparkybgc.cpp \ sparkybgcconfiguration.cpp \ diff --git a/ground/gcs/src/plugins/boards_taulabs/freedom.cpp b/ground/gcs/src/plugins/boards_taulabs/freedom.cpp deleted file mode 100644 index 80fbf68bafe..00000000000 --- a/ground/gcs/src/plugins/boards_taulabs/freedom.cpp +++ /dev/null @@ -1,255 +0,0 @@ -/** - ****************************************************************************** - * @file freedom.cpp - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Boards_TauLabsPlugin Tau Labs boards support Plugin - * @{ - * @brief Plugin to support boards by the Tau Labs project - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#include "freedom.h" - -#include -#include - -#include "rfm22bstatus.h" - -/** - * @brief Freedom::Freedom - * This is the Freedom board definition - */ -Freedom::Freedom(void) -{ - // Initialize our USB Structure definition here: - USBInfo board; - board.vendorID = 0x20A0; - board.productID = 0x415b; - - setUSBInfo(board); - - boardType = 0x81; - - // Define the bank of channels that are connected to a given timer - channelBanks.resize(6); - channelBanks[0] = QVector () << 1 << 2; - channelBanks[1] = QVector () << 3; - channelBanks[2] = QVector () << 4 << 5; - channelBanks[3] = QVector () << 6; - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - uavoUtilManager = pm->getObject(); -} - -Freedom::~Freedom() -{ - -} - -QString Freedom::shortName() -{ - return QString("Freedom"); -} - -QString Freedom::boardDescription() -{ - return QString("The Tau Labs project Freedom boards"); -} - -//! Return which capabilities this board has -bool Freedom::queryCapabilities(BoardCapabilities capability) -{ - switch(capability) { - case BOARD_CAPABILITIES_GYROS: - return true; - case BOARD_CAPABILITIES_ACCELS: - return true; - case BOARD_CAPABILITIES_MAGS: - return true; - case BOARD_CAPABILITIES_BAROS: - return true; - case BOARD_CAPABILITIES_RADIO: - return true; - } - return false; -} - - -/** - * @brief Freedom::getSupportedProtocols - * TODO: this is just a stub, we'll need to extend this a lot with multi protocol support - * @return - */ -QStringList Freedom::getSupportedProtocols() -{ - - return QStringList("uavtalk"); -} - -QPixmap Freedom::getBoardPicture() -{ - return QPixmap(":/taulabs/images/freedom.png"); -} - -QString Freedom::getHwUAVO() -{ - return "HwFreedom"; -} - -//! Get the settings object -HwFreedom * Freedom::getSettings() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - - HwFreedom *hwFreedom = HwFreedom::GetInstance(uavoManager); - Q_ASSERT(hwFreedom); - - return hwFreedom; -} - -int Freedom::queryMaxGyroRate() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - HwFreedom *hwFreedom = HwFreedom::GetInstance(uavoManager); - Q_ASSERT(hwFreedom); - if (!hwFreedom) - return 0; - - HwFreedom::DataFields settings = hwFreedom->getData(); - - switch(settings.GyroRange) { - case HwFreedom::GYRORANGE_250: - return 250; - case HwFreedom::GYRORANGE_500: - return 500; - case HwFreedom::GYRORANGE_1000: - return 1000; - case HwFreedom::GYRORANGE_2000: - return 2000; - default: - return 500; - } -} - -/** - * Get the RFM22b device ID this modem - * @return RFM22B device ID or 0 if not supported - */ -quint32 Freedom::getRfmID() -{ - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - - // Flight controllers are instance 1 - RFM22BStatus *rfm22bStatus = RFM22BStatus::GetInstance(uavoManager,1); - Q_ASSERT(rfm22bStatus); - RFM22BStatus::DataFields rfm22b = rfm22bStatus->getData(); - - return rfm22b.DeviceID; -} - -/** - * Set the coordinator ID. If set to zero this device will - * be a coordinator. - * @return true if successful or false if not - */ -bool Freedom::bindRadio(quint32 id, quint32 baud_rate, float rf_power, - Core::IBoardType::LinkMode linkMode, quint8 min, quint8 max) -{ - HwFreedom::DataFields settings = getSettings()->getData(); - - settings.CoordID = id; - - switch(baud_rate) { - case 9600: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_9600; - break; - case 19200: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_19200; - break; - case 32000: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_32000; - break; - case 64000: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_64000; - break; - case 100000: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_100000; - break; - case 192000: - settings.MaxRfSpeed = HwFreedom::MAXRFSPEED_192000; - break; - } - - // Round to an integer to use a switch statement - quint32 rf_power_100 = rf_power * 100; - switch(rf_power_100) { - case 0: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_0; - break; - case 125: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_125; - break; - case 160: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_16; - break; - case 316: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_316; - break; - case 630: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_63; - break; - case 1260: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_126; - break; - case 2500: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_25; - break; - case 5000: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_50; - break; - case 10000: - settings.MaxRfPower = HwFreedom::MAXRFPOWER_100; - break; - } - - switch(linkMode) { - case Core::IBoardType::LINK_TELEM: - settings.Radio = HwFreedom::RADIO_TELEM; - break; - case Core::IBoardType::LINK_TELEM_PPM: - settings.Radio = HwFreedom::RADIO_TELEMPPM; - break; - case Core::IBoardType::LINK_PPM: - settings.Radio = HwFreedom::RADIO_PPM; - break; - } - - settings.MinChannel = min; - settings.MaxChannel = max; - - getSettings()->setData(settings); - uavoUtilManager->saveObjectToFlash(getSettings()); - - return true; -} - diff --git a/ground/gcs/src/plugins/boards_taulabs/freedom.h b/ground/gcs/src/plugins/boards_taulabs/freedom.h deleted file mode 100644 index 7dc508ba16e..00000000000 --- a/ground/gcs/src/plugins/boards_taulabs/freedom.h +++ /dev/null @@ -1,71 +0,0 @@ -/** - ****************************************************************************** - * @file freedom.h - * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 - * - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup Boards_TauLabsPlugin Tau Labs boards support Plugin - * @{ - * @brief Plugin to support boards by the Tau Labs project - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#ifndef FREEDOM_H -#define FREEDOM_H - -#include "hwfreedom.h" -#include -#include - -class IBoardType; - -class Freedom : public Core::IBoardType -{ -public: - Freedom(); - virtual ~Freedom(); - - virtual QString shortName(); - virtual QString boardDescription(); - virtual bool queryCapabilities(BoardCapabilities capability); - virtual QStringList getSupportedProtocols(); - virtual QPixmap getBoardPicture(); - virtual QString getHwUAVO(); - virtual int queryMaxGyroRate(); - - HwFreedom * getSettings(); - - /** - * Get the RFM22b device ID this modem - * @return RFM22B device ID or 0 if not supported - */ - virtual quint32 getRfmID(); - - /** - * Set the coordinator ID. If set to zero this device will - * be a coordinator. - * @return true if successful or false if not - */ - virtual bool bindRadio(quint32 id, quint32 baud_rate, float rf_power, - Core::IBoardType::LinkMode linkMode, quint8 min, quint8 max); - -private: - UAVObjectUtilManager* uavoUtilManager; -}; - - -#endif // FREEDOM_H diff --git a/ground/gcs/src/plugins/boards_taulabs/images/freedom.png b/ground/gcs/src/plugins/boards_taulabs/images/freedom.png deleted file mode 100644 index f09a8594c33..00000000000 Binary files a/ground/gcs/src/plugins/boards_taulabs/images/freedom.png and /dev/null differ diff --git a/ground/gcs/src/plugins/boards_taulabs/taulabs.qrc b/ground/gcs/src/plugins/boards_taulabs/taulabs.qrc index 0e8c28dab0a..377c74fbd1a 100644 --- a/ground/gcs/src/plugins/boards_taulabs/taulabs.qrc +++ b/ground/gcs/src/plugins/boards_taulabs/taulabs.qrc @@ -1,6 +1,5 @@ - images/freedom.png images/sparky.png images/sparky-connection-diagram.svg images/sparkybgc.png diff --git a/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.cpp b/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.cpp index 52216eb0e34..f8c7354f05c 100644 --- a/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.cpp +++ b/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.cpp @@ -26,7 +26,6 @@ */ #include "taulabsplugin.h" -#include "freedom.h" #include "sparky.h" #include "sparky2.h" #include "sparkybgc.h" @@ -65,9 +64,6 @@ void TauLabsPlugin::extensionsInitialized() SparkyBGC* sparkybgc = new SparkyBGC(); addAutoReleasedObject(sparkybgc); - Freedom* freedom = new Freedom(); - addAutoReleasedObject(freedom); - TauLink* taulink = new TauLink(); addAutoReleasedObject(taulink); } diff --git a/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.h b/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.h index 8cb3aaae12b..0bac48eda4a 100644 --- a/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.h +++ b/ground/gcs/src/plugins/boards_taulabs/taulabsplugin.h @@ -1,11 +1,7 @@ /** ****************************************************************************** * @file taulabsplugin.h -<<<<<<< HEAD * @author Tau Labs, http://taulabs.org, Copyright (C) 2013 -======= - * @author Tau Labs, http://github.com/TauLabs, Copyright (C) 2013. ->>>>>>> GCS: Add board plugin for taulabs * * @addtogroup GCSPlugins GCS Plugins * @{ diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp b/ground/gcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp index c1d089390ea..ef3f42db753 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/configccpmwidget.cpp @@ -1091,11 +1091,20 @@ void ConfigCcpmWidget::SwashLvlStartButtonPressed() oldSwashLvlConfiguration.ServoChannels[1]=m_ccpm->ccpmServoXChannel->currentIndex(); oldSwashLvlConfiguration.ServoChannels[2]=m_ccpm->ccpmServoYChannel->currentIndex(); oldSwashLvlConfiguration.ServoChannels[3]=m_ccpm->ccpmServoZChannel->currentIndex(); + //if servos are used - oldSwashLvlConfiguration.Used[0]=((m_ccpm->ccpmServoWChannel->currentIndex()>0)&&(m_ccpm->ccpmServoWChannel->isEnabled())); - oldSwashLvlConfiguration.Used[1]=((m_ccpm->ccpmServoXChannel->currentIndex()>0)&&(m_ccpm->ccpmServoXChannel->isEnabled())); - oldSwashLvlConfiguration.Used[2]=((m_ccpm->ccpmServoYChannel->currentIndex()>0)&&(m_ccpm->ccpmServoYChannel->isEnabled())); - oldSwashLvlConfiguration.Used[3]=((m_ccpm->ccpmServoZChannel->currentIndex()>0)&&(m_ccpm->ccpmServoZChannel->isEnabled())); + oldSwashLvlConfiguration.Used[0]=(m_ccpm->ccpmServoWChannel->currentIndex()>0); + oldSwashLvlConfiguration.Used[1]=(m_ccpm->ccpmServoXChannel->currentIndex()>0); + oldSwashLvlConfiguration.Used[2]=(m_ccpm->ccpmServoYChannel->currentIndex()>0); + oldSwashLvlConfiguration.Used[3]=(m_ccpm->ccpmServoZChannel->currentIndex()>0); + + // all the channel spinboxes have "None" as index zero; thus, all channels will be off by 1 + for (uint8_t i = 0; i < CCPM_MAX_SWASH_SERVOS; ++i ) + { + // if a channel is selected, shift its value into the correct range [0,N-1] instead of [1,N] + if (oldSwashLvlConfiguration.ServoChannels[i] > 0) oldSwashLvlConfiguration.ServoChannels[i] --; + } + //min,neutral,max values for the servos for (i=0;igetData(); for (i=0;i 0) @@ -1457,6 +1470,10 @@ void ConfigCcpmWidget::SwashLvlSpinBoxChanged(int value) ActuatorCommand::DataFields actuatorCommandData = actuatorCommand->getData(); for (i = 0; i < CCPM_MAX_SWASH_SERVOS; i++) { + // don't do anything for unused channels (set to "None") + if (newSwashLvlConfiguration.Used[i] == 0) + continue; + value = SwashLvlSpinBoxes[i]->value(); switch (SwashLvlState) diff --git a/ground/gcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h b/ground/gcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h index f2810867016..bc732f73ede 100644 --- a/ground/gcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h +++ b/ground/gcs/src/plugins/config/cfg_vehicletypes/vehicleconfig.h @@ -27,6 +27,12 @@ #ifndef GUIVEHICLECONFIG_H #define GUIVEHICLECONFIG_H +#ifdef _MSC_VER +#define PACK( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#else +#define PACK( __Declaration__ ) __Declaration__ __attribute__((__packed__)) +#endif + #include "../uavobjectwidgetutils/configtaskwidget.h" #include "extensionsystem/pluginmanager.h" #include "uavobjectmanager.h" @@ -34,7 +40,7 @@ #include "mixersettings.h" #include "systemsettings.h" -typedef struct { +PACK(typedef struct { uint VTOLMotorN:4; uint VTOLMotorS:4; uint VTOLMotorE:4; @@ -47,9 +53,9 @@ typedef struct { quint32 padding:28; //64bits quint32 padding1; quint32 padding2; //128bits -} __attribute__((packed)) multiGUISettingsStruct; +}) multiGUISettingsStruct; -typedef struct { +PACK(typedef struct { uint SwashplateType:3; uint FirstServoIndex:2; uint CorrectionAngle:9; @@ -67,9 +73,9 @@ typedef struct { uint Tail:4; //65bits quint32 padding:31; //96bits quint32 padding1; //128bits -} __attribute__((packed)) heliGUISettingsStruct; +}) heliGUISettingsStruct; -typedef struct { +PACK(typedef struct { uint FixedWingThrottle:4; uint FixedWingRoll1:4; uint FixedWingRoll2:4; @@ -81,9 +87,9 @@ typedef struct { quint32 padding1; quint32 padding2; quint32 padding3; //128bits -} __attribute__((packed)) fixedGUISettingsStruct; +}) fixedGUISettingsStruct; -typedef struct { +PACK(typedef struct { uint GroundVehicleThrottle1:4; uint GroundVehicleThrottle2:4; uint GroundVehicleSteering1:4; @@ -92,7 +98,7 @@ typedef struct { quint32 padding1; quint32 padding2; quint32 padding3; //128bits -} __attribute__((packed)) groundGUISettingsStruct; +}) groundGUISettingsStruct; typedef union { diff --git a/ground/gcs/src/plugins/config/config.pro b/ground/gcs/src/plugins/config/config.pro index 65a0d0a55cd..7486ab9498d 100644 --- a/ground/gcs/src/plugins/config/config.pro +++ b/ground/gcs/src/plugins/config/config.pro @@ -1,8 +1,13 @@ TEMPLATE = lib TARGET = Config DEFINES += CONFIG_LIBRARY +DEFINES += QWT_DLL + QT += svg + include(config_dependencies.pri) +LIBS *= -l$$qtLibraryName(Qwt) + INCLUDEPATH *= ../../libs/eigen OTHER_FILES += Config.pluginspec \ diff --git a/ground/gcs/src/plugins/config/config_dependencies.pri b/ground/gcs/src/plugins/config/config_dependencies.pri index defbf6506f7..41f4be18122 100644 --- a/ground/gcs/src/plugins/config/config_dependencies.pri +++ b/ground/gcs/src/plugins/config/config_dependencies.pri @@ -1,4 +1,5 @@ include(../../taulabsgcsplugin.pri) +include(../../libs/qwt/qwt.pri) include(../../libs/utils/utils.pri) include(../../plugins/uavtalk/uavtalk.pri) include(../../plugins/coreplugin/coreplugin.pri) @@ -6,4 +7,3 @@ include(../../plugins/uavobjects/uavobjects.pri) include(../../plugins/uavobjectutil/uavobjectutil.pri) include(../../plugins/uavsettingsimportexport/uavsettingsimportexport.pri) include(../../plugins/uavobjectwidgetutils/uavobjectwidgetutils.pri) -include(../../libs/qwt/qwt.pri) diff --git a/ground/gcs/src/plugins/config/configautotunewidget.cpp b/ground/gcs/src/plugins/config/configautotunewidget.cpp index 40fbedc16d0..02beead48c6 100644 --- a/ground/gcs/src/plugins/config/configautotunewidget.cpp +++ b/ground/gcs/src/plugins/config/configautotunewidget.cpp @@ -19,7 +19,7 @@ #include "extensionsystem/pluginmanager.h" #include -#define FORUM_SHARING_FORUM 17 +#define FORUM_SHARING_FORUM 27 #define FORUM_SHARING_THREAD 268 ConfigAutotuneWidget::ConfigAutotuneWidget(QWidget *parent) : diff --git a/ground/gcs/src/plugins/config/configoutputwidget.cpp b/ground/gcs/src/plugins/config/configoutputwidget.cpp index a9bf69139cd..afadc65087b 100644 --- a/ground/gcs/src/plugins/config/configoutputwidget.cpp +++ b/ground/gcs/src/plugins/config/configoutputwidget.cpp @@ -340,8 +340,11 @@ void ConfigOutputWidget::startESCCalibration() QMessageBox mbox; mbox.setText(QString(tr("Starting ESC calibration.
Please remove all propellers and disconnect battery from ESCs."))); - mbox.setStandardButtons(QMessageBox::Ok); - mbox.exec(); + mbox.setStandardButtons(QMessageBox::Ok | QMessageBox::Cancel); + mbox.setDefaultButton(QMessageBox::Cancel); + QMessageBox::StandardButton butt; + + if (mbox.exec() != QMessageBox::Ok) return; // Get access to actuator command (for setting actual value) ActuatorCommand * actuatorCommand = ActuatorCommand::GetInstance(getObjectManager()); @@ -379,21 +382,24 @@ void ConfigOutputWidget::startESCCalibration() mbox.setText(QString(tr("Motors outputs were increased to maximum. " "Reconnect the battery and wait for notification from ESCs that they recognized high throttle position.
" "Immediately after that proceed to next step."))); - mbox.exec(); + if (mbox.exec() == QMessageBox::Ok) { + // Decrease output for all motors + for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) + { + // Check if the output channel was selected + if (!channelsToCalibrate[i]) + continue; - // Decrease output for all motors - for (unsigned int i = 0; i < ActuatorCommand::CHANNEL_NUMELEM; i++) - { - // Check if the output channel was selected - if (!channelsToCalibrate[i]) - continue; + actuatorCommandFields.Channel[i] = actuatorSettingsData.ChannelMin[i]; + } + actuatorCommand->setData(actuatorCommandFields); - actuatorCommandFields.Channel[i] = actuatorSettingsData.ChannelMin[i]; - } - actuatorCommand->setData(actuatorCommandFields); - mbox.setText(QString(tr("Motors outputs were decreased to minimum.
Wait for notification from ESCs that calibration is finished."))); - mbox.exec(); + mbox.setStandardButtons(QMessageBox::Ok); + mbox.setDefaultButton(QMessageBox::Ok); + mbox.setText(QString(tr("Motors outputs were decreased to minimum.
Wait for notification from ESCs that calibration is finished."))); + mbox.exec(); + } // Restore metadata actuatorCommand->setMetadata(accInitialData); diff --git a/ground/gcs/src/plugins/config/configstabilizationwidget.cpp b/ground/gcs/src/plugins/config/configstabilizationwidget.cpp index 2753dee32ad..640e74c9c22 100644 --- a/ground/gcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/gcs/src/plugins/config/configstabilizationwidget.cpp @@ -87,20 +87,28 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa connect(m_stabilization->fullStickRatePitch, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); connect(m_stabilization->fullStickRateYaw, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + m_stabilization->attitudeStickExpoPlot->init(ExpoCurve::AttitudeCurve, 0); + connect(m_stabilization->attitudeRollExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + connect(m_stabilization->attitudePitchExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + connect(m_stabilization->attitudeYawExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + connect(m_stabilization->rateRollKp_3, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + connect(m_stabilization->ratePitchKp_4, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + connect(m_stabilization->rateYawKp_3, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); + /* The init value for horizontransisition of 85% / 0.85 as used in here is copied/ the same as in the defined in /flight/Modules/Stabilization/stabilization.c * Please be aware of changes that are made there. */ m_stabilization->horizonStickExpoPlot->init(ExpoCurve::HorizonCurve, 85); connect(m_stabilization->horizonRollExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); connect(m_stabilization->horizonPitchExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); connect(m_stabilization->horizonYawExpo, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); - connect(m_stabilization->rateRollKp_3, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); - connect(m_stabilization->ratePitchKp_4, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); - connect(m_stabilization->rateYawKp_3, SIGNAL(valueChanged(double)), this, SLOT(showExpoPlot())); // set the flags for all Expo Plots, so that they get updatet after initialization update_exp.RateRoll = true; update_exp.RatePitch = true; update_exp.RateYaw = true; + update_exp.AttitudeRoll = true; + update_exp.AttitudePitch = true; + update_exp.AttitudeYaw = true; update_exp.HorizonAttitudeRoll = true; update_exp.HorizonAttitudePitch = true; update_exp.HorizonAttitudeYaw = true; @@ -274,6 +282,9 @@ void ConfigStabilizationWidget::showExpoPlot() if ( (obj == m_stabilization->horizonRollExpo) ) { update_exp.HorizonRateRoll = true; } + if ( (obj == m_stabilization->rateRollKp_3) ) { + update_exp.AttitudeRoll = true; + } } else if ( (obj == m_stabilization->horizonPitchExpo) || (obj == m_stabilization->ratePitchKp_4) ) { @@ -281,6 +292,9 @@ void ConfigStabilizationWidget::showExpoPlot() if ( (obj == m_stabilization->horizonPitchExpo) ) { update_exp.HorizonRatePitch = true; } + if ( (obj == m_stabilization->ratePitchKp_4) ) { + update_exp.AttitudePitch = true; + } } else if ( (obj == m_stabilization->horizonYawExpo) || (obj == m_stabilization->rateYawKp_3) ) { @@ -288,6 +302,9 @@ void ConfigStabilizationWidget::showExpoPlot() if ( (obj == m_stabilization->horizonYawExpo) ) { update_exp.HorizonRateYaw = true; } + if ( (obj == m_stabilization->rateYawKp_3) ) { + update_exp.AttitudeYaw = true; + } } else if ( (obj == m_stabilization->rateRollExpo) || (obj == m_stabilization->fullStickRateRoll) ) { @@ -311,6 +328,17 @@ void ConfigStabilizationWidget::showExpoPlot() update_exp.HorizonRateYaw = true; } } + else if ( (obj == m_stabilization->attitudeRollExpo) ) { + update_exp.AttitudeRoll = true; + } + + else if ( (obj == m_stabilization->attitudePitchExpo) ) { + update_exp.AttitudePitch = true; + } + + else if ( (obj == m_stabilization->attitudeYawExpo) ) { + update_exp.AttitudeYaw = true; + } } // update the Plots with latest data if the correspopnding flag is set @@ -353,4 +381,17 @@ void ConfigStabilizationWidget::showExpoPlot() m_stabilization->rateStickExpoPlot->plotDataYaw(m_stabilization->rateYawExpo->value(), m_stabilization->fullStickRateYaw->value(), ExpoCurve::Y_Left); update_exp.RateYaw = false; } + // Attitude Curves + if (update_exp.AttitudeRoll) { + m_stabilization->attitudeStickExpoPlot->plotDataRoll(m_stabilization->attitudeRollExpo->value(), m_stabilization->rateRollKp_3->value(), ExpoCurve::Y_Left); + update_exp.RateRoll = false; + } + if (update_exp.AttitudePitch) { + m_stabilization->attitudeStickExpoPlot->plotDataPitch(m_stabilization->attitudePitchExpo->value(), m_stabilization->ratePitchKp_4->value(), ExpoCurve::Y_Left); + update_exp.RatePitch = false; + } + if (update_exp.AttitudeYaw) { + m_stabilization->attitudeStickExpoPlot->plotDataYaw(m_stabilization->attitudeYawExpo->value(), m_stabilization->rateYawKp_3->value(), ExpoCurve::Y_Left); + update_exp.RateYaw = false; + } } diff --git a/ground/gcs/src/plugins/config/configstabilizationwidget.h b/ground/gcs/src/plugins/config/configstabilizationwidget.h index 99b7b62b4d2..ce9fd9a25fe 100644 --- a/ground/gcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/gcs/src/plugins/config/configstabilizationwidget.h @@ -54,6 +54,9 @@ class ConfigStabilizationWidget: public ConfigTaskWidget bool RateRoll; bool RatePitch; bool RateYaw; + bool AttitudeRoll; + bool AttitudePitch; + bool AttitudeYaw; bool HorizonAttitudeRoll; bool HorizonAttitudePitch; bool HorizonAttitudeYaw; diff --git a/ground/gcs/src/plugins/config/expocurve.cpp b/ground/gcs/src/plugins/config/expocurve.cpp index d26362b2383..19f6df1e307 100644 --- a/ground/gcs/src/plugins/config/expocurve.cpp +++ b/ground/gcs/src/plugins/config/expocurve.cpp @@ -136,7 +136,7 @@ ExpoCurve::ExpoCurve(QWidget *parent) : /** * @brief ExpoCurve::init Init labels, titels, horizin transition,... - * @param lbl_mode Chose the mode of this widget; RateCurve: for rate mode, HorizonCurve: for horizon mode + * @param lbl_mode Chose the mode of this widget; RateCurve: for rate mode, AttitudeCurve for Attitude mode, HorizonCurve: for horizon mode * @param horizon_transitions value for the horizon transition markers in the plot; 0: disabled, >0: horizon transitions in % horizon (should be the same as defined in /flight/Modules/Stabilization/stabilization.c) */ void ExpoCurve::init(label_mode lbl_mode, int h_transistion) @@ -167,6 +167,17 @@ void ExpoCurve::init(label_mode lbl_mode, int h_transistion) this->setAxisTitle(QwtPlot::yLeft, axis_title); curve_cnt = 1; + break; + case AttitudeCurve: + roll_elements.Curve.setTitle(tr("Roll angle (deg)")); + pitch_elements.Curve.setTitle(tr("Pitch angle (deg)")); + yaw_elements.Curve.setTitle(tr("Yaw angle (deg)")); + + axis_title.setText(tr("attitude angle (deg)")); + this->setAxisTitle(QwtPlot::yRight, axis_title); + this->setAxisTitle(QwtPlot::yLeft, axis_title); + curve_cnt = 1; + break; case HorizonCurve: roll_elements.Curve.setTitle(tr("Roll angle (deg)")); diff --git a/ground/gcs/src/plugins/config/expocurve.h b/ground/gcs/src/plugins/config/expocurve.h index 61eb7706459..8f79721c622 100644 --- a/ground/gcs/src/plugins/config/expocurve.h +++ b/ground/gcs/src/plugins/config/expocurve.h @@ -30,7 +30,7 @@ #include - +#define QWT_DLL #include "qwt/src/qwt.h" #include "qwt/src/qwt_plot.h" #include "qwt/src/qwt_plot_curve.h" @@ -58,7 +58,7 @@ class ExpoCurve : public QwtPlot } ExpoPlotElements_t; enum axis_mode {Y_Left, Y_Right}; - enum label_mode {RateCurve, HorizonCurve}; + enum label_mode {RateCurve, AttitudeCurve, HorizonCurve}; //! Set label for the stick channels void init(label_mode lbl_mode, int h_transistion); diff --git a/ground/gcs/src/plugins/config/inputchannelform.cpp b/ground/gcs/src/plugins/config/inputchannelform.cpp index a677a417683..0d72f93b7ff 100644 --- a/ground/gcs/src/plugins/config/inputchannelform.cpp +++ b/ground/gcs/src/plugins/config/inputchannelform.cpp @@ -129,9 +129,7 @@ void inputChannelForm::groupUpdated() count = 8; // Need to make this 6 for CC break; case ManualControlSettings::CHANNELGROUPS_PPM: - case ManualControlSettings::CHANNELGROUPS_DSMMAINPORT: - case ManualControlSettings::CHANNELGROUPS_DSMFLEXIPORT: - case ManualControlSettings::CHANNELGROUPS_DSMRCVRPORT: + case ManualControlSettings::CHANNELGROUPS_DSM: count = 12; break; case ManualControlSettings::CHANNELGROUPS_SBUS: diff --git a/ground/gcs/src/plugins/config/legacy-calibration.cpp b/ground/gcs/src/plugins/config/legacy-calibration.cpp deleted file mode 100644 index 683fecc2523..00000000000 --- a/ground/gcs/src/plugins/config/legacy-calibration.cpp +++ /dev/null @@ -1,114 +0,0 @@ -/** - ****************************************************************************** - * - * @file legacy-calibration.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup ConfigPlugin Config Plugin - * @{ - * @brief The Configuration Gadget used to update settings in the firmware - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include -#include - -/** - * The basic calibration algorithm initially used in OpenPilot. This is a basic - * 6-point calibration that doesn't attempt to account for any of the white noise - * in the sensors. - * The measurement equation is - * B_k = D^-1 * (A_k * H_k - b) - * Where B_k is the measurement of the field at time k - * D is the diagonal matrix of scale factors - * A_k is the attitude direction cosine matrix at time k - * H_k is the reference field at the kth sample - * b is the vector of scale factors. - * - * After computing the scale factor and bias, the optimized measurement is - * \tilde{B}_k = D * (B_k + b) - * - * @param bias[out] The computed bias of the sensor - * @param scale[out] The computed scale factor of the sensor - * @param samples An array of sample data points. Only the first 6 are - * used. - * @param n_samples The number of sample data points. Must be at least 6. - * @param referenceField The field being measured by the sensor. - */ -void -openpilot_bias_scale(Vector3f& bias, - Vector3f& scale, - const Vector3f samples[], - const size_t n_samples, - const Vector3f& referenceField) -{ - // TODO: Add error handling, and return error codes through the return - // value. - if (n_samples < 6) { - bias = Vector3f::Zero(); - scale = Vector3f::Zero(); - return; - } - // mag = (S*x + b)**2 - // mag = (S**2 * x**2 + 2*S*b*x + b*b) - // 0 = S**2 * (x1**2 - x2**2) + 2*S*B*(x1 - x2)) - // Fill in matrix A - - // write six difference-in-magnitude equations of the form - // Sx^2(x2^2-x1^2) + 2*Sx*bx*(x2-x1) + Sy^2(y2^2-y1^2) + - // 2*Sy*by*(y2-y1) + Sz^2(z2^2-z1^2) + 2*Sz*bz*(z2-z1) = 0 - // - // or in other words - // 2*Sx*bx*(x2-x1)/Sx^2 + Sy^2(y2^2-y1^2)/Sx^2 + - // 2*Sy*by*(y2-y1)/Sx^2 + Sz^2(z2^2-z1^2)/Sx^2 + 2*Sz*bz*(z2-z1)/Sx^2 = - // (x1^2-x2^2) - Matrix A; - Matrix f; - for (unsigned i=0; i<5; i++){ - A.row(i)[0] = 2.0 * (samples[i+1].x() - samples[i].x()); - A.row(i)[1] = samples[i+1].y()* samples[i+1].y() - samples[i].y()*samples[i].y(); - A.row(i)[2] = 2.0 * (samples[i+1].y() - samples[i].y()); - A.row(i)[3] = samples[i+1].z()*samples[i+1].z() - samples[i].z()*samples[i].z(); - A.row(i)[4] = 2.0 * (samples[i+1].z() - samples[i].z()); - f[i] = samples[i].x()*samples[i].x() - samples[i+1].x()*samples[i+1].x(); - } - Matrix c; - A.lu().solve(f, &c); - - - // use one magnitude equation and c's to find Sx - doesn't matter which - all give the same answer - float xp = samples[0].x(); - float yp = samples[0].y(); - float zp = samples[0].z(); - - float Sx = sqrt(referenceField.squaredNorm() / - (xp*xp + 2*c[0]*xp + c[0]*c[0] + c[1]*yp*yp + 2*c[2]*yp + c[2]*c[2]/c[1] + c[3]*zp*zp + 2*c[4]*zp + c[4]*c[4]/c[3])); - - scale[0] = Sx; - bias[0] = Sx*c[0]; - scale[1] = sqrt(c[1]*Sx*Sx); - bias[1] = c[2]*Sx*Sx/scale[1]; - scale[2] = sqrt(c[3]*Sx*Sx); - bias[2] = c[4]*Sx*Sx/scale[2]; - - for (int i = 0; i < 3; ++i) { - // Fixup difference between openpilot measurement model and twostep - // version - bias[i] = -bias[i] / scale[i]; - } -} - - diff --git a/ground/gcs/src/plugins/config/modules.ui b/ground/gcs/src/plugins/config/modules.ui index 52fbdf31b8e..0c3c5576c68 100644 --- a/ground/gcs/src/plugins/config/modules.ui +++ b/ground/gcs/src/plugins/config/modules.ui @@ -905,7 +905,7 @@ Geofence - + @@ -957,7 +957,7 @@ - + Qt::Vertical @@ -973,7 +973,7 @@ - + Qt::Vertical diff --git a/ground/gcs/src/plugins/config/old_calibration.h b/ground/gcs/src/plugins/config/old_calibration.h deleted file mode 100644 index 8fa40167d20..00000000000 --- a/ground/gcs/src/plugins/config/old_calibration.h +++ /dev/null @@ -1,54 +0,0 @@ -#ifndef AHRS_CALIBRATION_HPP -#define AHRS_CALIBRATION_HPP - -#include -#include -using std::size_t; -using namespace Eigen; - -void -calibration_misalignment(Vector3f& rotationVector, - const Vector3f samples0[], - const Vector3f& reference0, - const Vector3f samples1[], - const Vector3f& reference1, - size_t n_samples); - -Vector3f -twostep_bias_only(const Vector3f samples[], - size_t n_samples, - const Vector3f& referenceField, - const float noise); - -void -twostep_bias_scale(Vector3f& bias, - Vector3f& scale, - const Vector3f samples[], - const size_t n_samples, - const Vector3f& referenceField, - const float noise); - -void -twostep_bias_scale(Vector3f& bias, - Matrix3f& scale, - const Vector3f samples[], - const size_t n_samples, - const Vector3f& referenceField, - const float noise); - -void -openpilot_bias_scale(Vector3f& bias, - Vector3f& scale, - const Vector3f samples[], - const size_t n_samples, - const Vector3f& referenceField); - -void -gyroscope_calibration(Vector3f& bias, - Matrix3f& accelSensitivity, - Vector3f gyroSamples[], - Vector3f accelSamples[], - size_t n_samples); - -#endif // !defined AHRS_CALIBRATION_HPP - diff --git a/ground/gcs/src/plugins/config/outputchannelform.cpp b/ground/gcs/src/plugins/config/outputchannelform.cpp index 48ad43aa443..7a1a0b2e3ae 100755 --- a/ground/gcs/src/plugins/config/outputchannelform.cpp +++ b/ground/gcs/src/plugins/config/outputchannelform.cpp @@ -330,9 +330,6 @@ void OutputChannelForm::sendChannelTest(int value) if (!ob) return; - if (ui.actuatorMin->value() > ui.actuatorMax->value()) - value = ui.actuatorMin->value() - value + ui.actuatorMax->value(); // the channel is reversed - if (ui.actuatorLink->checkState() && parent()) { // the channel is linked to other channels QList outputChannelForms = parent()->findChildren(); diff --git a/ground/gcs/src/plugins/config/stabilization.ui b/ground/gcs/src/plugins/config/stabilization.ui index 10bf3b27699..56f11686f81 100644 --- a/ground/gcs/src/plugins/config/stabilization.ui +++ b/ground/gcs/src/plugins/config/stabilization.ui @@ -6997,8 +6997,8 @@ border-radius: 5; 0 0 - 1194 - 709 + 926 + 872 @@ -7018,1187 +7018,1133 @@ border-radius: 5; 12 - + - - - 0 + + + + 0 + 0 + - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 251 - 251 - 251 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - + + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + - 255 - 255 - 255 + 250 + 250 + 250 - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + - 251 - 251 - 251 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + - 165 - 165 - 165 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + - 255 - 255 - 255 + 243 + 243 + 243 - - - - + + - 124 - 124 - 124 + 250 + 250 + 250 - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + - 0 - 0 - 0 + 243 + 243 + 243 - - - - + + - 248 - 248 - 248 + 250 + 250 + 250 - - - - + + + + + + + + - 255 - 255 - 220 + 243 + 243 + 243 - - - - + + - 0 - 0 - 0 + 250 + 250 + 250 - - - - - - - Rate Stabilization (Inner Loop) - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - 4 - - - 12 - - - 4 - - - 12 - - - 6 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Rate Stabilization (Inner Loop) + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 + + + 12 + + + 4 + + + 12 + + + 6 + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + - 243 - 243 - 243 + 0 + 0 + 0 - - + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + - 250 - 250 - 250 + 255 + 255 + 255 - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - + + + + - 243 - 243 - 243 + 251 + 251 + 251 - - + + + + - 250 - 250 - 250 + 124 + 124 + 124 - - - - - - - - + + + + - 243 - 243 - 243 + 165 + 165 + 165 - - + + + + - 250 - 250 - 250 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - + + + + - 243 - 243 - 243 + 255 + 255 + 255 - - + + + + - 250 - 250 - 250 + 0 + 0 + 0 - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + - 243 - 243 - 243 + 0 + 0 + 0 - - + + + + - 250 - 250 - 250 + 251 + 251 + 251 - - - - - - - - + + + + - 243 - 243 - 243 + 255 + 255 + 220 - - + + + + - 250 - 250 - 250 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - + + + + + + - 243 - 243 - 243 + 0 + 0 + 0 - - + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + - 250 - 250 - 250 + 255 + 255 + 255 - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - + + + + - 243 - 243 - 243 + 251 + 251 + 251 - - + + + + - 250 - 250 - 250 + 124 + 124 + 124 - - - - - - - - + + + + - 243 - 243 - 243 + 165 + 165 + 165 - - + + + + - 250 - 250 - 250 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - Stick Scaling and Expo Rate - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - 4 - - - 4 - - - 4 - - - 4 - - - 6 - - - - - - 0 - 0 - + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + PID Coefficients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 - - - 0 - 0 - + + 4 - - - 16777215 - 16777215 - + + 4 - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - - - Qt::Horizontal + + 4 - - QSizePolicy::Preferred - - - - 632 - 27 - + + 6 - - - - - - + + - + 0 0 @@ -8206,23669 +8152,29502 @@ border-radius: 5; 0 - 215 + 0 16777215 - 550 + 16777215 + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:4 + + - - - - - - - 0 - 0 - - - - - 0 - 110 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 0 - - - 6 - - - - - - 0 - 0 - - - - - 103 - 22 - + + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RateExpo - element:Roll - haslimits:yes - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + 9 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + +You can usually go for higher values for Yaw factors. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 39 + 39 + 39 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Expo rate (%) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 69 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 497 + 20 + + + + + + + + + + + Link Roll and Pitch + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Stick Scaling and Expo Coeffcients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + 0 + 0 + + + + + 0 + 110 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + 0 - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RateExpo - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - + + 6 - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RateExpo - element:Pitch - haslimits:yes - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 150 - 16 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - Full stick rate (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:ManualRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 29 - - - - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - PID Coefficients - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - 4 - - - 4 - - - 4 - - - 4 - - - 6 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:4 - - - - - - - - - 0 - 0 - - - - - 0 - 140 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 0 - - - 9 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - -You can usually go for higher values for Yaw factors. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 69 - 0 - - - - - 16777215 - 16777215 - - - - - - - Derivative - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 150 - 16 - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 497 - 20 - - - - - - - - - - - Link Roll and Pitch - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 1 - - - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 4 - 20 - - - - - - - - 0 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - Attitude Stabilization (Outer Loop) - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - 4 - - - 12 - - - 4 - - - 12 - - - 6 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - Stick Scaling and Expo Horizon - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - - 4 - - - 4 - - - 4 - - - 4 - - - 6 - - - - - - 0 - 0 - - - - - 0 - 110 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 0 - - - 6 - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:PitchMax - haslimits:no - scale:1 - buttongroup:7,20 - - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:7,20 - - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Expo horizon (%) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:7,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:HorizonExpo - element:Pitch - haslimits:yes - scale:1 - buttongroup:7,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 150 - 16 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:HorizonExpo - element:Roll - haslimits:yes - scale:1 - buttongroup:7,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - Full stick angle (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:HorizonExpo - element:Yaw - haslimits:yes - scale:1 - buttongroup:7,20 - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 632 - 27 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:7 - - - - - - - - - - - 0 - 0 - - - - - 0 - 215 - - - - - 16777215 - 550 - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 1 - - - - - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 31 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - PID Coefficients - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - 4 - - - 4 - - - 4 - - - 4 - - - 6 - - - - - Qt::Horizontal - - - QSizePolicy::Preferred - - - - 497 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 110 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 0 - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 103 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Kp - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 3 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:Ki - haslimits:no - scale:1 - buttongroup:5,20 - - - - - - - - - 0 - 0 - - - - - 69 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 150 - 16 - - - - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:5 - - - - - - - - - - - Link Roll and Pitch - - - - - - - - - - - - - - - - - - - - - - MultiWii Rate - - - - - - This mode attempts to replicate the feel of the control loop used in MultiWii / baseflight. The units are different for the settings, but you can use the calculate button below to translate from one system to the other. To use this, you use a Stabilization# flight mode with the roll and pitch (optionally yaw) axes set to MWRate (selected in the input configuration page). - - - true - - - - - - - Qt::Vertical - - - QSizePolicy::Fixed - - - - 20 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - - - 243 - 243 - 243 - - - - - 250 - 250 - 250 - - - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - MultiWii Rate Stabilization Coefficients - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - - 12 - - - 12 - - - 12 - - - 12 - - - 6 - - - - - - 0 - 0 - - - - - 0 - 140 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - false - - - - - - - - - true - - - - 0 - - - 9 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:MWRateSettings - fieldname:PitchRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - - - Integral - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:YawRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:PitchRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - -You can usually go for higher values for Yaw factors. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:YawRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:MWRateSettings - fieldname:YawRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Proportional - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:RollRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:RollRatePID - element:Ki - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 58 - 0 - - - - - 16777215 - 16777215 - - - - - - - Derivative - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 5 - - - 0.000100000000000 - - - - objname:MWRateSettings - fieldname:PitchRatePID - element:Kp - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 6 - - - 0.000001000000000 - - - - objname:MWRateSettings - fieldname:RollRatePID - element:Kd - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - - - - - - - Link Roll and Pitch - - - - - - - Qt::Horizontal - - - - 497 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:MWRateSettings - button:default - buttongroup:4 - - - - - - - - - - - Rate gain settings (attenuate PID with stick position) - - - - - - RollPitchRate (%) - - - - - - - YawRate (%) - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1.000000000000000 - - - - objname:MWRateSettings - fieldname:RollPitchRate - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1.000000000000000 - - - - objname:MWRateSettings - fieldname:YawRate - haslimits:no - scale:1 - buttongroup:4,20 - - - - - - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - Calculate from Multi Wii / Baseflight settings - - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - 0 - 0 - - - - Expert - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 255 - 255 - 255 - - - - - - - 240 - 240 - 240 - - - - - - - - - 240 - 240 - 240 - - - - - - - 240 - 240 - 240 - - - - - - - - QFrame::NoFrame - - - QFrame::Sunken - - - 0 - - - true - - - - - 0 - 0 - 937 - 595 - - - - - 12 - - - 12 - - - 12 - - - 12 - - - - - - 0 - 0 - - - - - 0 - 0 - - - - false - - - Weak Leveling / Axis Lock - - - - 12 - - - 12 - - - 12 - - - 12 - - - - - Qt::Horizontal - - - - 632 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:10 - - - - - - - - true - - - - 12 - - - 12 - - - 12 - - - 12 - - - - - - 0 - 0 - - - - - 144 - 16 - - - - - 175 - 16777215 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Weak Leveling Kp - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 144 - 16 - - - - - 175 - 16777215 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Weak Leveling Rate - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 144 - 16 - - - - - 175 - 16777215 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 144 - 16 - - - - - 175 - 16777215 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Max Axis Lock Rate - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 90 - 11 - - - - - - - - - 0 - 0 - - - - - 5 - 22 - - - - - 175 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 2 - - - 0.010000000000000 - - - 360.000000000000000 - - - 0.010000000000000 - - - - objname:StabilizationSettings - fieldname:WeakLevelingKp - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 25 - 22 - - - - - 175 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxWeakLevelingRate - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 25 - 22 - - - - - 175 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxAxisLock - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - 0 - 0 - - - - - 25 - 22 - - - - - 175 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1.000000000000000 - - - 360.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettings - fieldname:MaxAxisLockRate - haslimits:no - scale:1 - buttongroup:10 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - Integral Limits - - - - 12 - - - 12 - - - 12 - - - 12 - - - 6 - - - - - Qt::Horizontal - - - - 632 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:13 - - - - - - - - - 0 - 100 - - - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - - - 69 - 69 - 69 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 69 - 69 - 69 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - - - 125 - 125 - 125 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 125 - 125 - 125 - - - - - - - 166 - 166 - 166 - - - - - - - 125 - 125 - 125 - - - - - - - 125 - 125 - 125 - - - - - - - 0 - 0 - 0 - - - - - - - - - - - true - - - - 12 - - - 12 - - - 12 - - - 12 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:PitchRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:RollRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:YawPI - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - - 0 - 0 - - - - - 91 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit Attitude - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:PitchPI - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 91 - 13 - - - - - - - - - 0 - 0 - - - - - 91 - 0 - - - - - 16777215 - 16777215 - - - - - - - ILimit Rate - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 2 - - - 0.100000000000000 - - - - objname:StabilizationSettings - fieldname:RollPI - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 4 - - - 1.000000000000000 - - - 0.001000000000000 - - - - objname:StabilizationSettings - fieldname:YawRatePID - element:ILimit - haslimits:no - scale:1 - buttongroup:13 - - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - Qt::Horizontal - - - - 1 - 20 - - - - - - - - - - - - - - - 0 - 0 - - - - - 0 - 60 - - - - Real Time Updates - - - - - - - 0 - 0 - - - - - 136 - 20 - - - - If you check this, the GCS will udpate the stabilization factors -automatically every 300ms, which will help for fast tuning. - - - - - - Update in real time - - - - - - - - - - Throttle PID attenuation - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 13 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RateExpo + element:Roll + haslimits:yes + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Expo rate (%) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RateExpo + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RateExpo + element:Pitch + haslimits:yes + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Full stick rate (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 1 + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Stick Scaling and Expo Curves + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 300 + 215 + + + + + 16777215 + 550 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 5 + + + + + + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Attitude Stabilization (Outer Loop) + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 - - - 75 - true - + + 12 - - false + + 4 - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + 12 + + + 6 + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + PID Coefficients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 110 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Kp + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 3 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:Ki + haslimits:no + scale:1 + buttongroup:5,20 + + + + + + + + + 0 + 0 + + + + + 69 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:5 + + + + + + + + + + + Link Roll and Pitch + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Stick Scaling and Expo Coefficients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 110 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 + + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:7,20 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:7,20 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Expo attitude (%) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:7,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:AttitudeExpo + element:Pitch + haslimits:yes + scale:1 + buttongroup:7,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:AttitudeExpo + element:Roll + haslimits:yes + scale:1 + buttongroup:7,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Full stick angle (deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:AttitudeExpo + element:Yaw + haslimits:yes + scale:1 + buttongroup:7,20 + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:7 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 1 + + + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + Stick Scaling and Expo Curves + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 300 + 215 + + + + + 16777215 + 550 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 5 + + + + + + + + + + + + + + + + + + + + + + + MultiWii Rate + + + + + + This mode attempts to replicate the feel of the control loop used in MultiWii / baseflight. The units are different for the settings, but you can use the calculate button below to translate from one system to the other. To use this, you use a Stabilization# flight mode with the roll and pitch (optionally yaw) axes set to MWRate (selected in the input configuration page). + + + true + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + MultiWii Rate Stabilization Coefficients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 12 + + + 12 + + + 12 + + + 12 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 + + + 9 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:MWRateSettings + fieldname:PitchRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + + + Integral + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:YawRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:PitchRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 85 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. +Then lower the value by 20% or so. + +You can usually go for higher values for Yaw factors. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:YawRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:MWRateSettings + fieldname:YawRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Attenuation (%) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Proportional + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 85 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRateTPA - element:Attenuation - - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:RollRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 140 + 13 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same +value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:RollRatePID + element:Ki + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 58 + 0 + + + + + 16777215 + 16777215 + + + + + + + Derivative + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 85 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + Slowly raise Kp until you start seeing clear oscillations when you fly. Then lower the value by 20% or so. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:PitchRateTPA - element:Attenuation - haslimits:no - scale:1 - - - - - - - - - 0 - 0 - - - - - 85 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - Slowly raise Kp until you start seeing clear oscillations when you fly. -Then lower the value by 20% or so. - -You can usually go for higher values for Yaw factors. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:YawRateTPA - element:Attenuation - - - - - - - - - 0 - 0 - - - - - - - Threshold (%) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 5 + + + 0.000100000000000 + + + + objname:MWRateSettings + fieldname:PitchRatePID + element:Kp + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 6 + + + 0.000001000000000 + + + + objname:MWRateSettings + fieldname:RollRatePID + element:Kd + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + + + + + + Link Roll and Pitch + + + + + + + Qt::Horizontal + + + + 497 + 20 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:MWRateSettings + button:default + buttongroup:4 + + + + + + + + + + + Rate gain settings (attenuate PID with stick position) + + + + + + RollPitchRate (%) + + + + + + + YawRate (%) + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same value as the Kp. - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 0.000100000000000 - - - - objname:StabilizationSettings - fieldname:RollRateTPA - element:Threshold - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - As a rule of thumb, you can set the Ki at roughly the same + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1.000000000000000 + + + + objname:MWRateSettings + fieldname:RollPitchRate + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + As a rule of thumb, you can set the Ki at roughly the same value as the Kp. + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1.000000000000000 + + + + objname:MWRateSettings + fieldname:YawRate + haslimits:no + scale:1 + buttongroup:4,20 + + + + + + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Calculate from Multi Wii / Baseflight settings + + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + 0 + 0 + + + + Expert + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 255 + 255 + 255 + + + + + + + 240 + 240 + 240 + + + + + + + + + 240 + 240 + 240 + + + + + + + 240 + 240 + 240 + + + + + + + + QFrame::NoFrame + + + QFrame::Sunken + + + 0 + + + true + + + + + 0 + -787 + 921 + 1393 + + + + + 12 + + + 12 + + + 12 + + + 12 + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + false + + + Weak Leveling / Axis Lock + + + + 4 - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + 12 - - 0 + + 4 - - 0.000100000000000 + + 12 - - - objname:StabilizationSettings - fieldname:PitchRateTPA - element:Threshold - + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:10 + + + + + + + + true + + + + 0 + + + 9 + + + 9 + + + 9 + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 120 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + 16777215 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Kp + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + 16777215 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Rate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 2 + + + 0.010000000000000 + + + 360.000000000000000 + + + 0.010000000000000 + + + + objname:StabilizationSettings + fieldname:WeakLevelingKp + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxWeakLevelingRate + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 6 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + Weak Leveling + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + Axis Lock + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 0.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLock + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1.000000000000000 + + + 360.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:MaxAxisLockRate + haslimits:no + scale:1 + buttongroup:10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + 16777215 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max Rate + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + 16777215 + 16777215 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Max + + + Qt::AlignCenter + + + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + Throttle PID attenuation + + + + 4 - - - - - - Qt::Horizontal + + 12 - - QSizePolicy::Fixed + + 4 - - - 10 - 10 - + + 12 - - - - - - - 0 - 0 - + + 6 + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:17 + + + + + + + + + 0 + 110 + + + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 69 + 69 + 69 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 125 + 125 + 125 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 125 + 125 + 125 + + + + + + + 125 + 125 + 125 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + true + + + + 0 + + + 9 + + + 9 + + + 9 + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRateTPA + element:Threshold + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + Attenuation (%) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + Threshold (%) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollRateTPA + element:Attenuation + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:RollRateTPA + element:Threshold + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawRateTPA + element:Threshold + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRateTPA + element:Attenuation + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:YawRateTPA + element:Attenuation + haslimits:yes + scale:1 + buttongroup:17,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + Integral Limits + + + + 4 - - - 0 - 22 - + + 12 - - - 16777215 - 22 - + + 4 - - Qt::StrongFocus + + 12 - - As a rule of thumb, you can set the Ki at roughly the same -value as the Kp. + + 6 - - + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:13 + + + + + + + + + 0 + 110 + + + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 69 + 69 + 69 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 69 + 69 + 69 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + + + 125 + 125 + 125 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 125 + 125 + 125 + + + + + + + 166 + 166 + 166 + + + + + + + 125 + 125 + 125 + + + + + + + 125 + 125 + 125 + + + + + + + 0 + 0 + 0 + + + + + + + + + + + true + + + + 0 + + + 9 + + + 9 + + + 9 + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:YawRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:YawPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + ILimit Rate + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:RollPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + 16777215 + 16777215 + + + + + + + ILimit Attitude + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 2 + + + 0.100000000000000 + + + + objname:StabilizationSettings + fieldname:PitchPI + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:PitchRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 4 + + + 1.000000000000000 + + + 0.001000000000000 + + + + objname:StabilizationSettings + fieldname:RollRatePID + element:ILimit + haslimits:no + scale:1 + buttongroup:13 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 60 + + + + Real Time Updates + + + + 4 - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + 4 - - 0 + + + + + 0 + 0 + + + + + 136 + 20 + + + + If you check this, the GCS will udpate the stabilization factors +automatically every 300ms, which will help for fast tuning. + + + + + + Update in real time + + + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Horizon + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + + 4 - - 0.000100000000000 + + 12 - - - objname:StabilizationSettings - fieldname:YawRateTPA - element:Threshold - + + 4 - - - - - - Qt::Horizontal + + 12 - - - 371 - 20 - + + 6 - - - - - - - - - Qt::Vertical - - - - 20 - 149 - - - + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Expo Coeffcients + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 80 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + + + + + + + true + + + + 0 + + + 6 + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Roll + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Expo horizon (%) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:HorizonExpo + element:Roll + haslimits:yes + scale:1 + buttongroup:15,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:HorizonExpo + element:Yaw + haslimits:yes + scale:1 + buttongroup:15,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 150 + 16 + + + + + + + + + 0 + 0 + + + + + 103 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettings + fieldname:HorizonExpo + element:Pitch + haslimits:yes + scale:1 + buttongroup:15,20 + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:15 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Preferred + + + + 632 + 27 + + + + + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + + + 243 + 243 + 243 + + + + + 250 + 250 + 250 + + + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + Expo Curves + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + 4 + + + 4 + + + 4 + + + 4 + + + 6 + + + + + + 0 + 0 + + + + + 300 + 400 + + + + + 16777215 + 550 + + + + + + + + Qt::Vertical + + + QSizePolicy::Fixed + + + + 20 + 5 + + + + + + + + + + + + + + + + Qt::Vertical + + + + 10 + 10 + + + + + @@ -32141,9 +37920,9 @@ Useful if you have accidentally changed some settings. rateRollKp_3 ratePitchKp_4 rateYawKp_3 - horizonRollExpo - horizonPitchExpo - horizonYawExpo + attitudeRollExpo + attitudePitchExpo + attitudeYawExpo cb_linkMwRollPitch pb_MWRateDefault MWRateRollKp @@ -32159,11 +37938,22 @@ Useful if you have accidentally changed some settings. MWRateYawRate calculateMW scrollArea_3 + pushButton_7 + horizonRollExpo + horizonPitchExpo + horizonYawExpo pushButton_6 WeakLevelingKp WeakLevelingRate MaAxisLock MaxAxisLockRate + pushButton_10 + TpaAttenuationRoll + TpaAttenuationPitch + TpaAttenuationYaw + TpaThresholdRoll + TpaThresholdPitch + TpaThresholdYaw pushButton_9 RateRollILimit_2 RatePitchILimit @@ -32172,12 +37962,6 @@ Useful if you have accidentally changed some settings. AttitudePitchILimit_2 AttitudeYawILimit realTimeUpdates_6 - RateRollKp_3 - RatePitchKp_2 - RateYawKp_2 - RateRollKi_3 - RatePitchKi_2 - RateYawKi_2 tabWidget diff --git a/ground/gcs/src/plugins/config/textbubbleslider.h b/ground/gcs/src/plugins/config/textbubbleslider.h index ba07c7a111a..d72ef7b165d 100644 --- a/ground/gcs/src/plugins/config/textbubbleslider.h +++ b/ground/gcs/src/plugins/config/textbubbleslider.h @@ -29,7 +29,7 @@ #define TEXTBUBBLESLIDER_H #include -#include +#include class TextBubbleSlider : public QSlider { diff --git a/ground/gcs/src/plugins/coreplugin/CREDITS.html b/ground/gcs/src/plugins/coreplugin/CREDITS.html index a6c0b854dfd..080ce52721b 100644 --- a/ground/gcs/src/plugins/coreplugin/CREDITS.html +++ b/ground/gcs/src/plugins/coreplugin/CREDITS.html @@ -1,5 +1,5 @@ -

This is a credits file of people that are or have been key contributors to Tau Labs project. +

This is a credits file of people that are or have been key contributors to the Tau Labs project. Some of this work was contributed under the OpenPilot project.

It is sorted alphabetically by name

@@ -11,7 +11,7 @@ Fredrik Arvidsson Werner Backes Jose Barros -Pete Boehl +Pete Boehl David Carlson James Cotton Steve Doll @@ -39,6 +39,7 @@ Pablo Lema David Llama Matt Lipski +Michael Lyle Les Newell Ken Northup Greg Matthews diff --git a/ground/gcs/src/plugins/coreplugin/coreplugin.pro b/ground/gcs/src/plugins/coreplugin/coreplugin.pro index ccc45a2a31c..175d77862aa 100644 --- a/ground/gcs/src/plugins/coreplugin/coreplugin.pro +++ b/ground/gcs/src/plugins/coreplugin/coreplugin.pro @@ -5,7 +5,6 @@ DEFINES += CORE_LIBRARY QT += widgets QT += xml \ network \ - script \ svg \ sql include(../../taulabsgcsplugin.pri) diff --git a/ground/gcs/src/plugins/coreplugin/gcsversioninfo.pri b/ground/gcs/src/plugins/coreplugin/gcsversioninfo.pri index 60a6b135e70..525d6f03ff6 100644 --- a/ground/gcs/src/plugins/coreplugin/gcsversioninfo.pri +++ b/ground/gcs/src/plugins/coreplugin/gcsversioninfo.pri @@ -21,6 +21,7 @@ isEmpty($$PYTHON_LOCAL) { !debug_and_release|build_pass { ROOT_DIR = $$GCS_SOURCE_TREE/../.. VERSION_INFO_HEADER = $$GCS_BUILD_TREE/gcsversioninfo.h +win32-msvc*:write_file($$VERSION_INFO_HEADER) VERSION_INFO_SCRIPT = $$ROOT_DIR/make/scripts/version-info.py VERSION_INFO_TEMPLATE = $$ROOT_DIR/make/templates/gcsversioninfotemplate.h VERSION_INFO_COMMAND = $$PYTHON_LOCAL \"$$VERSION_INFO_SCRIPT\" @@ -35,7 +36,7 @@ isEmpty($$PYTHON_LOCAL) { --outfile=\"$$VERSION_INFO_HEADER\" version_info.depends = FORCE QMAKE_EXTRA_TARGETS += version_info - + PRE_TARGETDEPS += $$VERSION_INFO_HEADER # Hook version_info target in between qmake's Makefile update and # the actual project target version_info_hook.depends = version_info diff --git a/ground/gcs/src/plugins/coreplugin/generalsettings.cpp b/ground/gcs/src/plugins/coreplugin/generalsettings.cpp index 67ceaeb6001..6ca84d391be 100644 --- a/ground/gcs/src/plugins/coreplugin/generalsettings.cpp +++ b/ground/gcs/src/plugins/coreplugin/generalsettings.cpp @@ -96,7 +96,7 @@ void GeneralSettings::fillLanguageBox() const const QString creatorTrPath = Core::ICore::instance()->resourcePath() + QLatin1String("/translations"); - const QStringList languageFiles = QDir(creatorTrPath).entryList(QStringList(QLatin1String("openpilotgcs*.qm"))); + const QStringList languageFiles = QDir(creatorTrPath).entryList(QStringList(QLatin1String("taulabs*.qm"))); Q_FOREACH(const QString &languageFile, languageFiles) { diff --git a/ground/gcs/src/plugins/coreplugin/mainwindow.cpp b/ground/gcs/src/plugins/coreplugin/mainwindow.cpp index fc5a39f10b5..5c8ee417051 100644 --- a/ground/gcs/src/plugins/coreplugin/mainwindow.cpp +++ b/ground/gcs/src/plugins/coreplugin/mainwindow.cpp @@ -103,14 +103,6 @@ MainWindow::MainWindow() : m_uniqueIDManager(new UniqueIDManager()), m_globalContext(QList() << Constants::C_GLOBAL_ID), m_additionalContexts(m_globalContext), - // keep this in sync with main() in app/main.cpp - m_settings(new QSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, - QLatin1String("TauLabs"), QLatin1String("TauLabs_config"), this)), - m_globalSettings(new QSettings(XmlConfig::XmlSettingsFormat, QSettings::SystemScope, - QLatin1String("TauLabs"), QLatin1String("TauLabs_config"), this)), - m_settingsDatabase(new SettingsDatabase(QFileInfo(m_settings->fileName()).path(), - QLatin1String("TauLabs_config"), - this)), m_dontSaveSettings(false), m_actionManager(new ActionManagerPrivate(this)), m_variableManager(new VariableManager(this)), @@ -138,6 +130,29 @@ MainWindow::MainWindow() : #endif /* Q_OS_MAC */ m_toggleFullScreenAction(0) { + // keep this in sync with main() in app/main.cpp + m_settings = new QSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, + QLatin1String("TauLabs"), QLatin1String("TauLabs_config.autosave"), this); + m_settingsDatabase = new SettingsDatabase(QFileInfo(m_settings->fileName()).path(), + QLatin1String("TauLabs_config"), + this); + + // Copy original settings file to working settings. Do this in scope so that + // we are guaranteed that the originalSettings file is closed. This prevents corruption + // since the QSettings being used are copies of the original file. + { + QSettings originalSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, + QLatin1String("TauLabs"), QLatin1String("TauLabs_config"), this); + + // There is no copy constructor for QSettings, so we have to do it manually + m_settings->clear(); + QStringList keys = originalSettings.allKeys(); + for( QStringList::iterator i = keys.begin(); i != keys.end(); i++ ) + { + m_settings->setValue( *i, originalSettings.value( *i ) ); + } + } + setWindowTitle(QLatin1String(Core::Constants::GCS_NAME)); if (!Utils::HostOsInfo::isMacHost()) QApplication::setWindowIcon(QIcon(Core::Constants::ICON_TAULABS)); @@ -235,6 +250,23 @@ MainWindow::~MainWindow() m_generalSettings = 0; delete m_workspaceSettings; m_workspaceSettings = 0; + + // Copy working settings back to original settings file. Do this in scope so that + // we are guaranteed that the originalSettings file is closed. This minimizes the risk + // of corruption since the QSettings are saved (almost) atomically. + { + QSettings originalSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, + QLatin1String("TauLabs"), QLatin1String("TauLabs_config"), this); + + // There is no copy constructor for QSettings, so we have to do it manually + originalSettings.clear(); + QStringList keys = m_settings->allKeys(); + for( QStringList::iterator i = keys.begin(); i != keys.end(); i++ ) + { + originalSettings.setValue( *i, m_settings->value( *i ) ); + } + } + delete m_settings; m_settings = 0; delete m_uniqueIDManager; @@ -1302,8 +1334,17 @@ void MainWindow::saveSettings(IConfigurablePlugin* plugin, QSettings* qs) void MainWindow::deleteSettings() { + // Clear the in-memory settings m_settings->clear(); m_settings->sync(); + + // Clear the on-disk settings + QSettings originalSettings(XmlConfig::XmlSettingsFormat, QSettings::UserScope, + QLatin1String("TauLabs"), QLatin1String("TauLabs_config"), this); + originalSettings.clear(); + originalSettings.sync(); + + // Don't save the settings when exiting m_dontSaveSettings = true; } diff --git a/ground/gcs/src/plugins/gcscontrolwidget/GCSControlWidget.json b/ground/gcs/src/plugins/gcscontrolplugin/GCSControlWidget.json similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/GCSControlWidget.json rename to ground/gcs/src/plugins/gcscontrolplugin/GCSControlWidget.json diff --git a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.cpp index 9729f605bc1..10224a5f32b 100644 --- a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.cpp +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.cpp @@ -27,6 +27,10 @@ #include "gcscontrol.h" #include #include +#include "gcscontrolgadgetfactory.h" +#if defined(USE_SDL) +#include "sdlgamepad/sdlgamepad.h" +#endif #define CHANNEL_MAX 2000 #define CHANNEL_NEUTRAL 1500 @@ -67,6 +71,18 @@ bool GCSControl::initialize(const QStringList &arguments, QString *errorString) Q_UNUSED(arguments); Q_UNUSED(errorString); +#if defined(USE_SDL) + sdlGamepad = new SDLGamepad(); + if(sdlGamepad->init()) { + sdlGamepad->start(); + qRegisterMetaType("QListInt16"); + qRegisterMetaType("ButtonNumber"); + } +#endif + + mf = new GCSControlGadgetFactory(this); + addAutoReleasedObject(mf); + // Add this plugin to plugin manager addObject(this); return true; @@ -193,7 +209,7 @@ bool GCSControl::setChannel(quint8 channel, float value) void GCSControl::objectsUpdated(UAVObject *obj) { - qDebug()<<__PRETTY_FUNCTION__<<"Object"<getName()<<"changed outside this class"; + qDebug()<< "GCSControl::objectsUpdated" <<"Object"<getName()<<"changed outside this class"; } void GCSControl::receiverActivitySlot() diff --git a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.h index b8a035b3a7e..6bfe47e3873 100644 --- a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.h +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.h @@ -35,6 +35,7 @@ #include "gcsreceiver.h" #include "extensionsystem/pluginmanager.h" #include "QTimer" +#include "gcscontrolgadgetfactory.h" class GCSCONTROLSHARED_EXPORT GCSControl : public ExtensionSystem::IPlugin { Q_OBJECT @@ -45,6 +46,10 @@ class GCSCONTROLSHARED_EXPORT GCSControl : public ExtensionSystem::IPlugin { void extensionsInitialized(); bool initialize(const QStringList & arguments, QString *errorString); void shutdown(); + +#if defined(USE_SDL) + SDLGamepad *sdlGamepad; +#endif public slots: bool beginGCSControl(); bool endGCSControl(); @@ -54,6 +59,7 @@ public slots: bool setPitch(float value); bool setYaw(float value); bool setChannel(quint8 channel, float value); + private: ManualControlSettings *manControlSettingsUAVO; GCSReceiver *m_gcsReceiver; @@ -62,6 +68,8 @@ public slots: ManualControlSettings::Metadata metaBackup; bool hasControl; QTimer receiverActivity; + + GCSControlGadgetFactory *mf; private slots: void objectsUpdated(UAVObject *); void receiverActivitySlot(); diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrol.qrc b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.qrc similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrol.qrc rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.qrc diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrol.ui b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.ui similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrol.ui rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrol.ui diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.cpp similarity index 99% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.cpp index dc6ba4cec07..dfe131a0eff 100644 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.cpp +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.cpp @@ -24,6 +24,7 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include "gcscontrol.h" #include "gcscontrolgadget.h" #include "gcscontrolgadgetwidget.h" #include "gcscontrolgadgetconfiguration.h" @@ -54,7 +55,7 @@ GCSControlGadget::GCSControlGadget(QString classId, GCSControlGadgetWidget *widg joystickTime.start(); #if defined(USE_SDL) - GCSControlWidgetPlugin *pl = dynamic_cast(plugin); + GCSControl *pl = dynamic_cast(plugin); connect(pl->sdlGamepad,SIGNAL(gamepads(quint8)),this,SLOT(gamepads(quint8))); connect(pl->sdlGamepad,SIGNAL(buttonState(ButtonNumber,bool)),this,SLOT(buttonState(ButtonNumber,bool))); connect(pl->sdlGamepad,SIGNAL(axesValues(QListInt16)),this,SLOT(axesValues(QListInt16))); diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.h similarity index 95% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.h rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.h index c1542b2c980..d58067445e7 100644 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadget.h +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadget.h @@ -30,7 +30,6 @@ #include #include "gcscontrolgadgetconfiguration.h" -#include "gcscontrolwidgetplugin.h" #include #include #include diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetconfiguration.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetconfiguration.cpp similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetconfiguration.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetconfiguration.cpp diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetconfiguration.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetconfiguration.h similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetconfiguration.h rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetconfiguration.h diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetfactory.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetfactory.cpp similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetfactory.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetfactory.cpp diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetfactory.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetfactory.h similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetfactory.h rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetfactory.h diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.cpp similarity index 96% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.cpp index 2499ffcb53d..5a42cf2050f 100644 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.cpp +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.cpp @@ -28,6 +28,7 @@ #include "gcscontrolgadgetoptionspage.h" #include "gcscontrolgadgetconfiguration.h" #include "ui_gcscontrolgadgetoptionspage.h" +#include "gcscontrol.h" #include #include @@ -40,7 +41,7 @@ GCSControlGadgetOptionsPage::GCSControlGadgetOptionsPage(GCSControlGadgetConfigu options_page = NULL; #if defined(USE_SDL) - sdlGamepad = dynamic_cast(parent)->sdlGamepad; + sdlGamepad = dynamic_cast(parent)->sdlGamepad; #endif } diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.h similarity index 95% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.h rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.h index e6cafedff82..b4b1ff7ee4a 100644 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.h +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.h @@ -29,7 +29,6 @@ #define GCSCONTROLGADGETOPTIONSPAGE_H #include "coreplugin/dialogs/ioptionspage.h" -#include "gcscontrolwidgetplugin.h" #if defined(USE_SDL) #include "sdlgamepad/sdlgamepad.h" diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.ui b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.ui similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetoptionspage.ui rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetoptionspage.ui diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetwidget.cpp b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetwidget.cpp similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetwidget.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetwidget.cpp diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetwidget.h b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetwidget.h similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/gcscontrolgadgetwidget.h rename to ground/gcs/src/plugins/gcscontrolplugin/gcscontrolgadgetwidget.h diff --git a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolplugin.pro b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolplugin.pro index 95e1bcb74ab..8d48bec0c27 100644 --- a/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolplugin.pro +++ b/ground/gcs/src/plugins/gcscontrolplugin/gcscontrolplugin.pro @@ -8,8 +8,33 @@ include(../../plugins/uavobjectutil/uavobjectutil.pri) DEFINES += GCSCONTROL_LIBRARY SOURCES += gcscontrol.cpp +SOURCES += gcscontrolgadget.cpp \ + gcscontrolgadgetconfiguration.cpp \ + gcscontrolgadgetoptionspage.cpp +SOURCES += gcscontrolgadgetwidget.cpp +SOURCES += gcscontrolgadgetfactory.cpp +SOURCES += joystickcontrol.cpp HEADERS += gcscontrol.h\ gcscontrol_global.h +HEADERS += gcscontrolgadget.h \ + gcscontrolgadgetconfiguration.h \ + gcscontrolgadgetoptionspage.h +HEADERS += joystickcontrol.h +HEADERS += gcscontrolgadgetwidget.h +HEADERS += gcscontrolgadgetfactory.h OTHER_FILES += GCSControl.pluginspec + +QT += svg +QT += network + +SDL { + DEFINES += USE_SDL + include(../../libs/sdlgamepad/sdlgamepad.pri) +} + +FORMS += gcscontrol.ui \ + gcscontrolgadgetoptionspage.ui + +RESOURCES += gcscontrol.qrc diff --git a/ground/gcs/src/plugins/gcscontrolwidget/images/joystick.svg b/ground/gcs/src/plugins/gcscontrolplugin/images/joystick.svg similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/images/joystick.svg rename to ground/gcs/src/plugins/gcscontrolplugin/images/joystick.svg diff --git a/ground/gcs/src/plugins/gcscontrolwidget/joystickcontrol.cpp b/ground/gcs/src/plugins/gcscontrolplugin/joystickcontrol.cpp similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/joystickcontrol.cpp rename to ground/gcs/src/plugins/gcscontrolplugin/joystickcontrol.cpp diff --git a/ground/gcs/src/plugins/gcscontrolwidget/joystickcontrol.h b/ground/gcs/src/plugins/gcscontrolplugin/joystickcontrol.h similarity index 100% rename from ground/gcs/src/plugins/gcscontrolwidget/joystickcontrol.h rename to ground/gcs/src/plugins/gcscontrolplugin/joystickcontrol.h diff --git a/ground/gcs/src/plugins/gcscontrolwidget/GCSControlWidget.pluginspec b/ground/gcs/src/plugins/gcscontrolwidget/GCSControlWidget.pluginspec deleted file mode 100644 index 5e297b17ca7..00000000000 --- a/ground/gcs/src/plugins/gcscontrolwidget/GCSControlWidget.pluginspec +++ /dev/null @@ -1,13 +0,0 @@ - - Tau Labs - (C) 2010-2012 OpenPilot Project - The GNU Public License (GPL) Version 3 - Allow GCS to take over from the receiver and control the UAV, either with a mouse and keyboard or an external joystick - http://taulabs.org - - - - - - - diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidget.pro b/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidget.pro deleted file mode 100644 index 9cc66eff8b4..00000000000 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidget.pro +++ /dev/null @@ -1,40 +0,0 @@ -TEMPLATE = lib -TARGET = GCSControlWidget -QT += svg -QT += network - -include(../../taulabsgcsplugin.pri) -include(../../plugins/coreplugin/coreplugin.pri) -include(../../plugins/uavobjects/uavobjects.pri) -include(../../plugins/gcscontrolplugin/gcscontrol.pri) - -SDL { - DEFINES += USE_SDL - include(../../libs/sdlgamepad/sdlgamepad.pri) -} - -HEADERS += gcscontrolgadget.h \ - gcscontrolgadgetconfiguration.h \ - gcscontrolgadgetoptionspage.h \ - gcscontrolwidgetplugin.h -HEADERS += joystickcontrol.h -HEADERS += gcscontrolgadgetwidget.h -HEADERS += gcscontrolgadgetfactory.h -HEADERS += - -SOURCES += gcscontrolgadget.cpp \ - gcscontrolgadgetconfiguration.cpp \ - gcscontrolgadgetoptionspage.cpp \ - gcscontrolwidgetplugin.cpp -SOURCES += gcscontrolgadgetwidget.cpp -SOURCES += gcscontrolgadgetfactory.cpp -SOURCES += -SOURCES += joystickcontrol.cpp - -OTHER_FILES += GCSControlWidget.pluginspec - GCSControlWidget.json - -FORMS += gcscontrol.ui \ - gcscontrolgadgetoptionspage.ui - -RESOURCES += gcscontrol.qrc diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.cpp b/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.cpp deleted file mode 100644 index 0003712ed81..00000000000 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.cpp +++ /dev/null @@ -1,78 +0,0 @@ -/** - ****************************************************************************** - * - * @file GCSControlwidgetplugin.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup GCSControlGadgetPlugin GCSControl Gadget Plugin - * @{ - * @brief A gadget to control the UAV, either from the keyboard or a joystick - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ -#include "gcscontrolwidgetplugin.h" -#include "gcscontrolgadgetfactory.h" -#include -#include -#include -#include - - -GCSControlWidgetPlugin::GCSControlWidgetPlugin() -{ - // Do nothing -} - -GCSControlWidgetPlugin::~GCSControlWidgetPlugin() -{ - // Do nothing -} - -bool GCSControlWidgetPlugin::initialize(const QStringList& args, QString *errMsg) -{ - Q_UNUSED(args); - Q_UNUSED(errMsg); - -#if defined(USE_SDL) - sdlGamepad = new SDLGamepad(); - if(sdlGamepad->init()) { - sdlGamepad->start(); - qRegisterMetaType("QListInt16"); - qRegisterMetaType("ButtonNumber"); - } -#endif - - mf = new GCSControlGadgetFactory(this); - addAutoReleasedObject(mf); - - return true; -} - -void GCSControlWidgetPlugin::extensionsInitialized() -{ - // Do nothing -} - -void GCSControlWidgetPlugin::shutdown() -{ - // Do nothing -} - -/** - * @} - * @} - */ diff --git a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.h b/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.h deleted file mode 100644 index 0e93ce2594b..00000000000 --- a/ground/gcs/src/plugins/gcscontrolwidget/gcscontrolwidgetplugin.h +++ /dev/null @@ -1,60 +0,0 @@ -/** - ****************************************************************************** - * - * @file GCSControlwidgetplugin.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. - * @addtogroup GCSPlugins GCS Plugins - * @{ - * @addtogroup GCSControlGadgetPlugin GCSControl Gadget Plugin - * @{ - * @brief A gadget to control the UAV, either from the keyboard or a joystick - *****************************************************************************/ -/* - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, but - * WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY - * or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License - * for more details. - * - * You should have received a copy of the GNU General Public License along - * with this program; if not, write to the Free Software Foundation, Inc., - * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - */ - -#ifndef GCSControlPLUGIN_H_ -#define GCSControlPLUGIN_H_ - -#include - -#if defined(USE_SDL) -#include "sdlgamepad/sdlgamepad.h" -#endif - -class GCSControlGadgetFactory; - -class GCSControlWidgetPlugin : public ExtensionSystem::IPlugin -{ - Q_OBJECT - Q_PLUGIN_METADATA(IID "TauLabs.plugins.GCSControlPlugin" FILE "GCSControlWidget.json") - -public: - GCSControlWidgetPlugin(); - ~GCSControlWidgetPlugin(); - - void extensionsInitialized(); - bool initialize(const QStringList & arguments, QString * errorString); - void shutdown(); - -#if defined(USE_SDL) - SDLGamepad *sdlGamepad; -#endif - -private: - GCSControlGadgetFactory *mf; - -}; -#endif /* GCSControlPLUGIN_H_ */ diff --git a/ground/gcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h b/ground/gcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h index 697695bc208..59b84fe2c91 100644 --- a/ground/gcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h +++ b/ground/gcs/src/plugins/hitl/aerosimrc/src/aerosimrcdatastruct.h @@ -38,9 +38,13 @@ const quint16 DBG_BUFFER_MAX_SIZE = 4096; #define OBSOLETE_MIT_CHECKBOX (1 << 1) #define OBSOLETE_MIT_SEPARATOR (1 << 7) -#define PACK_STRUCT __attribute__((packed)) +#ifdef _MSC_VER +#define PACK( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#else +#define PACK( __Declaration__ ) __Declaration__ __attribute__((__packed__)) +#endif -struct simToPlugin +PACK(struct simToPlugin { quint16 structSize; float simTimeStep; @@ -135,11 +139,11 @@ struct simToPlugin float accelZm; // ver 3.90 quint32 OSDVideoBufSize; -} PACK_STRUCT ; // normal - 592, packed - 582 OK (3.81) +}) ; // normal - 592, packed - 582 OK (3.81) // normal - ???, packed - 658 OK (3.83) // normal - ???, packed - 662 OK (3.90) -struct pluginToSim +PACK(struct pluginToSim { quint16 structSize; const char *dbgInfoText; @@ -183,24 +187,22 @@ struct pluginToSim qint16 newScreenH; qint16 newScreenX; qint16 newScreenY; -} PACK_STRUCT ; // normal 516, packed 507 OK (3.81) +}); // normal 516, packed 507 OK (3.81) // normal ???, packed 515 OK (3.83 & 3.90) -struct TPluginMenuItem +PACK(struct TPluginMenuItem { quint32 OBSOLETE_eType; char *OBSOLETE_strName; -} PACK_STRUCT ; +}); -struct pluginInit +PACK(struct pluginInit { quint32 nStructSize; char *OBSOLETE_strMenuTitle; TPluginMenuItem OBSOLETE_atMenuItem[MAX_DLL_USER_MENU_ITEMS]; const char *strPluginFolder; const char *strOutputFolder; -} PACK_STRUCT ; // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90) - -#undef PACK_STRUCT +}); // normal - 144, packed - 144 OK (3.81 & 3.83 & 3.90) #endif // AEROSIMRCDATASTRUCT_H diff --git a/ground/gcs/src/plugins/hitl/aerosimrc/src/plugin.pro b/ground/gcs/src/plugins/hitl/aerosimrc/src/plugin.pro index c8e1a1285f4..0c2dd7a883f 100644 --- a/ground/gcs/src/plugins/hitl/aerosimrc/src/plugin.pro +++ b/ground/gcs/src/plugins/hitl/aerosimrc/src/plugin.pro @@ -52,9 +52,13 @@ equals(copydata, 1) { # Qt DLLs QT_DLLS = \ Qt5Core.dll \ - Qt5Network.dll \ - libgcc_s_dw2-1.dll \ - libstdc++-6.dll + Qt5Network.dll + win32-g++ { + QT_DLLS += \ + libgcc_s_dw2-1.dll \ + libstdc++-6.dll + } + for(dll, QT_DLLS) { data_copy.commands += $(COPY_FILE) $$targetPath(\"$$[QT_INSTALL_BINS]/$$dll\") $$targetPath(\"$$SIM_DIR/$$dll\") $$addNewline() } diff --git a/ground/gcs/src/plugins/hitl/il2simulator.cpp b/ground/gcs/src/plugins/hitl/il2simulator.cpp index a330a6bf4eb..338e8efd2f0 100644 --- a/ground/gcs/src/plugins/hitl/il2simulator.cpp +++ b/ground/gcs/src/plugins/hitl/il2simulator.cpp @@ -69,7 +69,7 @@ #include "extensionsystem/pluginmanager.h" #include #include -#include +#include IL2Simulator::IL2Simulator(const SimulatorSettings& params) : Simulator(params) @@ -184,9 +184,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp) current.Y = old.Y + (current.dY*current.dT); // accelerations (filtered) - if (isnan(old.ddX) || isinf(old.ddX)) old.ddX=0; - if (isnan(old.ddY) || isinf(old.ddY)) old.ddY=0; - if (isnan(old.ddZ) || isinf(old.ddZ)) old.ddZ=0; + if (std::isnan(old.ddX) || std::isinf(old.ddX)) old.ddX=0; + if (std::isnan(old.ddY) || std::isinf(old.ddY)) old.ddY=0; + if (std::isnan(old.ddZ) || std::isinf(old.ddZ)) old.ddZ=0; #define SPEED_FILTER 10 current.ddX = ((current.dX-old.dX)/current.dT + SPEED_FILTER * (old.ddX)) / (SPEED_FILTER+1); current.ddY = ((current.dY-old.dY)/current.dT + SPEED_FILTER * (old.ddY)) / (SPEED_FILTER+1); @@ -194,9 +194,9 @@ void IL2Simulator::processUpdate(const QByteArray& inp) #define TURN_FILTER 10 // turn speeds (filtered) - if (isnan(old.dAzimuth) || isinf(old.dAzimuth)) old.dAzimuth=0; - if (isnan(old.dPitch) || isinf(old.dPitch)) old.dPitch=0; - if (isnan(old.dRoll) || isinf(old.dRoll)) old.dRoll=0; + if (std::isnan(old.dAzimuth) || std::isinf(old.dAzimuth)) old.dAzimuth=0; + if (std::isnan(old.dPitch) || std::isinf(old.dPitch)) old.dPitch=0; + if (std::isnan(old.dRoll) || std::isinf(old.dRoll)) old.dRoll=0; current.dAzimuth = (angleDifference(current.azimuth,old.azimuth)/current.dT + TURN_FILTER * (old.dAzimuth)) / (TURN_FILTER+1); current.dPitch = (angleDifference(current.pitch,old.pitch)/current.dT + TURN_FILTER * (old.dPitch)) / (TURN_FILTER+1); current.dRoll = (angleDifference(current.roll,old.roll)/current.dT + TURN_FILTER * (old.dRoll)) / (TURN_FILTER+1); diff --git a/ground/gcs/src/plugins/modelview/modelviewgadgetwidget.cpp b/ground/gcs/src/plugins/modelview/modelviewgadgetwidget.cpp index 5fa9b67e5cc..bbe0af3b29b 100644 --- a/ground/gcs/src/plugins/modelview/modelviewgadgetwidget.cpp +++ b/ground/gcs/src/plugins/modelview/modelviewgadgetwidget.cpp @@ -186,7 +186,7 @@ void ModelViewGadgetWidget::resizeGL(int width, int height) void ModelViewGadgetWidget::CreateScene() { // put a black background if the 3D model is invalid or if the background image is also invalid - if (acFilename == ":/modelview/models/warning_sign.obj" or !QFile::exists(bgFilename)) { + if (acFilename == ":/modelview/models/warning_sign.obj" || !QFile::exists(bgFilename)) { bgFilename = ":/modelview/models/black.jpg"; } @@ -250,7 +250,7 @@ void ModelViewGadgetWidget::mouseMoveEvent(QMouseEvent *e) { GLC_UserInput userInput(e->x(), e->y()); - if (not m_MoverController.hasActiveMover()) { + if (!m_MoverController.hasActiveMover()) { return; } m_MoverController.move(userInput); @@ -260,7 +260,7 @@ void ModelViewGadgetWidget::mouseMoveEvent(QMouseEvent *e) void ModelViewGadgetWidget::mouseReleaseEvent(QMouseEvent *) { - if (not m_MoverController.hasActiveMover()) { + if (!m_MoverController.hasActiveMover()) { return; } m_MoverController.setNoMover(); diff --git a/ground/gcs/src/plugins/pathplanner/algorithms/pathfillet.cpp b/ground/gcs/src/plugins/pathplanner/algorithms/pathfillet.cpp index d9fe7b28b74..c85132e3484 100644 --- a/ground/gcs/src/plugins/pathplanner/algorithms/pathfillet.cpp +++ b/ground/gcs/src/plugins/pathplanner/algorithms/pathfillet.cpp @@ -23,11 +23,14 @@ * with this program; if not, write to the Free Software Foundation, Inc., * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ - +#define _USE_MATH_DEFINES +#include #include +#include #include #include -#include + +#include #define SIGN(x) (x < 0 ? -1 : 1) @@ -398,10 +401,10 @@ void PathFillet::setNewWaypoint(int index, float *pos, float velocity, float cur // Convert from curvature representation to waypoint quint8 mode = Waypoint::MODE_VECTOR; float radius = 0; - if (curvature > 0 && !isinf(curvature)) { + if (curvature > 0 && !std::isinf(curvature)) { mode = Waypoint::MODE_CIRCLERIGHT; radius = 1.0 / curvature; - } else if (curvature < 0 && !isinf(curvature)) { + } else if (curvature < 0 && !std::isinf(curvature)) { mode = Waypoint::MODE_CIRCLELEFT; radius = -1.0 / curvature; } diff --git a/ground/gcs/src/plugins/pathplanner/flightdatamodel.cpp b/ground/gcs/src/plugins/pathplanner/flightdatamodel.cpp index 93bfee418dd..3010a795b82 100644 --- a/ground/gcs/src/plugins/pathplanner/flightdatamodel.cpp +++ b/ground/gcs/src/plugins/pathplanner/flightdatamodel.cpp @@ -470,7 +470,7 @@ void FlightDataModel::pauseValidation(bool pausing) { void FlightDataModel::fixupValidationErrors() { - struct FlightDataModel::NED prevNED = {}; + struct FlightDataModel::NED prevNED = {0.0, 0.0, 0.0}; // Skip validation when there's a download from firmware in process. if (valPaused) { return; } diff --git a/ground/gcs/src/plugins/plugins.pro b/ground/gcs/src/plugins/plugins.pro index d61d5a436da..e568af545af 100644 --- a/ground/gcs/src/plugins/plugins.pro +++ b/ground/gcs/src/plugins/plugins.pro @@ -225,20 +225,8 @@ KML { plugin_gcscontrolplugin.depends = plugin_coreplugin plugin_gcscontrolplugin.depends += plugin_uavobjects SUBDIRS += plugin_gcscontrolplugin - - plugin_gcscontrolwidget.subdir = gcscontrolwidget - plugin_gcscontrolwidget.depends = plugin_coreplugin - plugin_gcscontrolwidget.depends += plugin_uavobjects - plugin_gcscontrolwidget.depends += plugin_gcscontrolplugin - SUBDIRS += plugin_gcscontrolwidget } -# Antenna tracker -plugin_antennatrack.subdir = antennatrack -plugin_antennatrack.depends = plugin_coreplugin -plugin_antennatrack.depends += plugin_uavobjects -SUBDIRS += plugin_antennatrack - # UAV Object Utility plugin plugin_uavobjectutil.subdir = uavobjectutil plugin_uavobjectutil.depends = plugin_coreplugin @@ -330,6 +318,12 @@ plugin_boards_quantec.depends = plugin_coreplugin plugin_boards_quantec.depends = plugin_uavobjects SUBDIRS += plugin_boards_quantec +# Naze32 +plugin_boards_naze.subdir = boards_naze +plugin_boards_naze.depends = plugin_coreplugin +plugin_boards_naze.depends = plugin_uavobjects +SUBDIRS += plugin_boards_naze + # Team Black Sheep plugin_boards_tbs.subdir = boards_tbs plugin_boards_tbs.depends = plugin_coreplugin @@ -343,3 +337,9 @@ plugin_boards_stm.subdir = boards_stm plugin_boards_stm.depends = plugin_coreplugin plugin_boards_stm.depends = plugin_uavobjects SUBDIRS += plugin_boards_stm + +# AeroQuad AQ32 +plugin_boards_aeroquad.subdir = boards_aeroquad +plugin_boards_aeroquad.depends = plugin_coreplugin +plugin_boards_aeroquad.depends = plugin_uavobjects +SUBDIRS += plugin_boards_aeroquad diff --git a/ground/gcs/src/plugins/rawhid/hidapi/hidapi_linux.c b/ground/gcs/src/plugins/rawhid/hidapi/hidapi_linux.c index 4d369f64abf..e124f9285ee 100644 --- a/ground/gcs/src/plugins/rawhid/hidapi/hidapi_linux.c +++ b/ground/gcs/src/plugins/rawhid/hidapi/hidapi_linux.c @@ -867,7 +867,7 @@ static void *read_thread(void *param) } -hid_device * HID_API_EXPORT hid_open_path(const char *path) +HID_API_EXPORT hid_device * hid_open_path(const char *path) { hid_device *dev = NULL; @@ -1298,6 +1298,7 @@ int HID_API_EXPORT_CALL hid_get_indexed_string(hid_device *dev, int string_index HID_API_EXPORT const wchar_t * HID_API_CALL hid_error(hid_device *dev) { + (void) dev; return NULL; } diff --git a/ground/gcs/src/plugins/rawhid/rawhid.cpp b/ground/gcs/src/plugins/rawhid/rawhid.cpp index 2552cdbc66a..8f581b1abb5 100644 --- a/ground/gcs/src/plugins/rawhid/rawhid.cpp +++ b/ground/gcs/src/plugins/rawhid/rawhid.cpp @@ -326,11 +326,10 @@ bool RawHID::open(OpenMode mode) { QMutexLocker locker(m_mutex); - int res; hid_device *handle; // Initialize the hidapi library (safe to call multiple times) - res = hid_init(); + hid_init(); // Open the device using the VID, PID handle = hid_open(m_deviceInfo->getVendorID(), m_deviceInfo->getProductID(), NULL); diff --git a/ground/gcs/src/plugins/rawhid/rawhid.pro b/ground/gcs/src/plugins/rawhid/rawhid.pro index d3ed79a879a..8307b7418e0 100644 --- a/ground/gcs/src/plugins/rawhid/rawhid.pro +++ b/ground/gcs/src/plugins/rawhid/rawhid.pro @@ -27,6 +27,9 @@ win32 { usbmonitor_win.cpp LIBS += -lhid \ -lsetupapi + win32-msvc* { + LIBS += -lUser32 + } } macx { SOURCES += usbmonitor_mac.cpp \ diff --git a/ground/gcs/src/plugins/rawhid/usbmonitor.h b/ground/gcs/src/plugins/rawhid/usbmonitor.h index b5f4b89a099..a185b9dbeeb 100644 --- a/ground/gcs/src/plugins/rawhid/usbmonitor.h +++ b/ground/gcs/src/plugins/rawhid/usbmonitor.h @@ -62,22 +62,17 @@ extern "C" { #endif // Some functions no longer included in hidsdi.h -//HIDAPI BOOL NTAPI HidD_GetAttributes (HANDLE, PHIDD_ATTRIBUTES); +#ifndef _MSC_VER HIDAPI VOID NTAPI HidD_GetHidGuid (LPGUID); HIDAPI BOOL NTAPI HidD_GetPreparsedData(HANDLE, PHIDP_PREPARSED_DATA *); HIDAPI BOOL NTAPI HidD_FreePreparsedData(PHIDP_PREPARSED_DATA); HIDAPI BOOL NTAPI HidD_FlushQueue (HANDLE); HIDAPI BOOL NTAPI HidD_GetConfiguration (HANDLE, PHIDD_CONFIGURATION, ULONG); HIDAPI BOOL NTAPI HidD_SetConfiguration (HANDLE, PHIDD_CONFIGURATION, ULONG); -//HIDAPI BOOL NTAPI HidD_GetFeature (HANDLE, PVOID, ULONG); -//HIDAPI BOOL NTAPI HidD_SetFeature (HANDLE, PVOID, ULONG); -//HIDAPI BOOL NTAPI HidD_GetNumInputBuffers (HANDLE, PULONG); -//HIDAPI BOOL NTAPI HidD_SetNumInputBuffers (HANDLE HidDeviceObject, ULONG); HIDAPI BOOL NTAPI HidD_GetPhysicalDescriptor (HANDLE, PVOID, ULONG); -//HIDAPI BOOL NTAPI HidD_GetManufacturerString (HANDLE, PVOID, ULONG); -//HIDAPI BOOL NTAPI HidD_GetProductString ( HANDLE, PVOID, ULONG); HIDAPI BOOL NTAPI HidD_GetIndexedString ( HANDLE, ULONG, PVOID, ULONG); HIDAPI BOOL NTAPI HidD_GetSerialNumberString (HANDLE, PVOID, ULONG); +#endif #ifdef __cplusplus } diff --git a/ground/gcs/src/plugins/scope/scope.pro b/ground/gcs/src/plugins/scope/scope.pro index d3f15aa1ed1..9d5302cf2a6 100644 --- a/ground/gcs/src/plugins/scope/scope.pro +++ b/ground/gcs/src/plugins/scope/scope.pro @@ -2,6 +2,8 @@ TEMPLATE = lib QT+=widgets TARGET = ScopeGadget DEFINES += SCOPE_LIBRARY +DEFINES += QWT_DLL + include(../../taulabsgcsplugin.pri) include (scope_dependencies.pri) HEADERS += scopeplugin.h \ diff --git a/ground/gcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/gcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 4d5fe80985e..cce84b2499a 100644 --- a/ground/gcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/gcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -388,7 +388,7 @@ void VehicleConfigurationHelper::applyManualControlDefaults() channelType = ManualControlSettings::CHANNELGROUPS_SBUS; break; case Core::IBoardType::INPUT_TYPE_DSM: - channelType = ManualControlSettings::CHANNELGROUPS_DSMMAINPORT; + channelType = ManualControlSettings::CHANNELGROUPS_DSM; break; case Core::IBoardType::INPUT_TYPE_HOTTSUMD: case Core::IBoardType::INPUT_TYPE_HOTTSUMH: diff --git a/ground/gcs/src/plugins/systemhealth/html/GPS-Error.html b/ground/gcs/src/plugins/systemhealth/html/GPS-Error.html index 827887acbc5..4719c4ecf17 100644 --- a/ground/gcs/src/plugins/systemhealth/html/GPS-Error.html +++ b/ground/gcs/src/plugins/systemhealth/html/GPS-Error.html @@ -7,7 +7,7 @@

GPS: Error

- The GPS has timed out; either there is no GPS plugged in, the GPS has locked up or there is some other hardware fault. + The GPS has timed out; either there is no GPS plugged in, the GPS has locked up, there is no port assigned to GPS, or there is some other hardware fault.

\ No newline at end of file diff --git a/ground/gcs/src/plugins/systemhealth/html/SystemConfiguration-Error-DuplicatePortCfg.html b/ground/gcs/src/plugins/systemhealth/html/SystemConfiguration-Error-DuplicatePortCfg.html new file mode 100644 index 00000000000..02aee3e4481 --- /dev/null +++ b/ground/gcs/src/plugins/systemhealth/html/SystemConfiguration-Error-DuplicatePortCfg.html @@ -0,0 +1,12 @@ + + + + + + + +

System Configuration: Error

+

Error Code: Duplicate Port Configuration

+

Multiple ports share the same function. For instance, two different ports may be configured for MavLink or GPS.

+ + diff --git a/ground/gcs/src/plugins/systemhealth/systemhealth.qrc b/ground/gcs/src/plugins/systemhealth/systemhealth.qrc index 7faed43caf5..45d0778fcb1 100644 --- a/ground/gcs/src/plugins/systemhealth/systemhealth.qrc +++ b/ground/gcs/src/plugins/systemhealth/systemhealth.qrc @@ -31,6 +31,7 @@ html/Telemetry-Error.html html/SystemConfiguration-Error-AltitudeHold.html html/SystemConfiguration-Error-AutoTune.html + html/SystemConfiguration-Error-DuplicatePortCfg.html html/SystemConfiguration-Error-Multirotor.html html/SystemConfiguration-Error-PathPlanner.html html/SystemConfiguration-Error-PositionHold.html diff --git a/ground/gcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp b/ground/gcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp index 527047d5d94..699d1ffbc19 100644 --- a/ground/gcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp +++ b/ground/gcs/src/plugins/systemhealth/systemhealthgadgetwidget.cpp @@ -299,6 +299,9 @@ QString SystemHealthGadgetWidget::getAlarmDescriptionFileName(const QString item case SystemAlarms::CONFIGERROR_POSITIONHOLD: alarmDescriptionFileName = QString(":/systemhealth/html/SystemConfiguration-Error-PositionHold.html"); break; + case SystemAlarms::CONFIGERROR_DUPLICATEPORTCFG: + alarmDescriptionFileName = QString(":/systemhealth/html/SystemConfiguration-Error-DuplicatePortCfg.html"); + break; case SystemAlarms::CONFIGERROR_PATHPLANNER: alarmDescriptionFileName = QString(":/systemhealth/html/SystemConfiguration-Error-PathPlanner.html"); break; diff --git a/ground/gcs/src/plugins/uavobjectbrowser/fieldtreeitem.h b/ground/gcs/src/plugins/uavobjectbrowser/fieldtreeitem.h index 6768b4575da..1751d057833 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/fieldtreeitem.h +++ b/ground/gcs/src/plugins/uavobjectbrowser/fieldtreeitem.h @@ -90,6 +90,11 @@ Q_OBJECT } void apply() { int value = data(dataColumn).toInt(); + if (value == -1) { + qDebug() << "Warning, UAVO browser field is outside range. This should never happen!"; + Q_ASSERT(0); + return; + } QStringList options = m_field->getOptions(); m_field->setValue(options[value], m_index); setChanged(false); diff --git a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp index 40f078eba14..5e45c5c990e 100644 --- a/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp +++ b/ground/gcs/src/plugins/uavobjectbrowser/uavobjectbrowserwidget.cpp @@ -342,7 +342,12 @@ void UAVObjectBrowserWidget::sendUpdate() { this->setFocus(); ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); + + // This occurs when the selected item is not inside a UAVObject + if (objItem == NULL) { + return; + } + UAVDataObject * dataObj=qobject_cast(objItem->object()); if(dataObj && dataObj->isSettings()) objItem->setUpdatedOnly(true); @@ -362,7 +367,12 @@ void UAVObjectBrowserWidget::sendUpdate() void UAVObjectBrowserWidget::requestUpdate() { ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); + + // This occurs when the selected item is not inside a UAVObject + if (objItem == NULL) { + return; + } + UAVObject *obj = objItem->object(); Q_ASSERT(obj); obj->requestUpdate(); @@ -409,7 +419,12 @@ void UAVObjectBrowserWidget::saveObject() sendUpdate(); // Save object ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); + + // This occurs when the selected item is not inside a UAVObject + if (objItem == NULL) { + return; + } + UAVDataObject * dataObj=qobject_cast(objItem->object()); if(dataObj && dataObj->isSettings()) objItem->setUpdatedOnly(false); @@ -429,7 +444,12 @@ void UAVObjectBrowserWidget::loadObject() { // Load object ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); + + // This occurs when the selected item is not inside a UAVObject + if (objItem == NULL) { + return; + } + UAVObject *obj = objItem->object(); Q_ASSERT(obj); updateObjectPersistance(ObjectPersistence::OPERATION_LOAD, obj); @@ -447,7 +467,12 @@ void UAVObjectBrowserWidget::loadObject() void UAVObjectBrowserWidget::eraseObject() { ObjectTreeItem *objItem = findCurrentObjectTreeItem(); - Q_ASSERT(objItem); + + // This occurs when the selected item is not inside a UAVObject + if (objItem == NULL) { + return; + } + UAVObject *obj = objItem->object(); Q_ASSERT(obj); updateObjectPersistance(ObjectPersistence::OPERATION_DELETE, obj); diff --git a/ground/gcs/src/plugins/uavobjects/uavmetaobject.cpp b/ground/gcs/src/plugins/uavobjects/uavmetaobject.cpp index 2805c9a1fc1..7d4f0bb5ddb 100644 --- a/ground/gcs/src/plugins/uavobjects/uavmetaobject.cpp +++ b/ground/gcs/src/plugins/uavobjects/uavmetaobject.cpp @@ -41,10 +41,10 @@ UAVMetaObject::UAVMetaObject(quint32 objID, const QString& name, UAVObject *pare QStringList modesBitField; modesBitField << tr("FlightReadOnly") << tr("GCSReadOnly") << tr("FlightTelemetryAcked") << tr("GCSTelemetryAcked") << tr("FlightUpdatePeriodic") << tr("FlightUpdateOnChange") << tr("GCSUpdatePeriodic") << tr("GCSUpdateOnChange"); QList fields; - fields.append( new UAVObjectField(tr("Modes"), tr("boolean"), UAVObjectField::BITFIELD, modesBitField, QStringList()) ); - fields.append( new UAVObjectField(tr("Flight Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()) ); - fields.append( new UAVObjectField(tr("GCS Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()) ); - fields.append( new UAVObjectField(tr("Logging Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList()) ); + fields.append( new UAVObjectField(tr("Modes"), tr("boolean"), UAVObjectField::BITFIELD, modesBitField, QStringList(), QList() ) ); + fields.append( new UAVObjectField(tr("Flight Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList(), QList() ) ); + fields.append( new UAVObjectField(tr("GCS Telemetry Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList(), QList() ) ); + fields.append( new UAVObjectField(tr("Logging Update Period"), tr("ms"), UAVObjectField::UINT16, 1, QStringList(), QList() ) ); // Initialize parent UAVObject::initialize(0); UAVObject::initializeFields(fields, (quint8*)&parentMetadata, sizeof(Metadata)); diff --git a/ground/gcs/src/plugins/uavobjects/uavobject.cpp b/ground/gcs/src/plugins/uavobjects/uavobject.cpp index 75c0111cdf3..60737b9a8d7 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/gcs/src/plugins/uavobjects/uavobject.cpp @@ -303,151 +303,6 @@ qint32 UAVObject::unpack(const quint8* dataIn) return numBytes; } -/** - * Save the object data to the file. - * The file will be created in the current directory - * and its name will be the same as the object with - * the .uavobj extension. - * @returns True on success, false on failure - */ -bool UAVObject::save() -{ - QMutexLocker locker(mutex); - - // Open file - QFile file(name + ".uavobj"); - if (!file.open(QFile::WriteOnly)) - { - return false; - } - - // Write object - if ( !save(file) ) - { - return false; - } - - // Close file - file.close(); - return true; -} - -/** - * Save the object data to the file. - * The file is expected to be already open for writting. - * The data will be appended and the file will not be closed. - * @returns True on success, false on failure - */ -bool UAVObject::save(QFile& file) -{ - QMutexLocker locker(mutex); - quint8 buffer[numBytes]; - quint8 tmpId[4]; - - // Write the object ID - qToLittleEndian(objID, tmpId); - if ( file.write((const char*)tmpId, 4) == -1 ) - { - return false; - } - - // Write the instance ID - if (!isSingleInst) - { - qToLittleEndian(instID, tmpId); - if ( file.write((const char*)tmpId, 2) == -1 ) - { - return false; - } - } - - // Write the data - pack(buffer); - if ( file.write((const char*)buffer, numBytes) == -1 ) - { - return false; - } - - // Done - return true; -} - -/** - * Load the object data from a file. - * The file will be openned in the current directory - * and its name will be the same as the object with - * the .uavobj extension. - * @returns True on success, false on failure - */ -bool UAVObject::load() -{ - QMutexLocker locker(mutex); - - // Open file - QFile file(name + ".uavobj"); - if (!file.open(QFile::ReadOnly)) - { - return false; - } - - // Load object - if ( !load(file) ) - { - return false; - } - - // Close file - file.close(); - return true; -} - -/** - * Load the object data from file. - * The file is expected to be already open for reading. - * The data will be read and the file will not be closed. - * @returns True on success, false on failure - */ -bool UAVObject::load(QFile& file) -{ - QMutexLocker locker(mutex); - quint8 buffer[numBytes]; - quint8 tmpId[4]; - - // Read the object ID - if ( file.read((char*)tmpId, 4) != 4 ) - { - return false; - } - - // Check that the IDs match - if (qFromLittleEndian(tmpId) != objID) - { - return false; - } - - // Read the instance ID - if ( file.read((char*)tmpId, 2) != 2 ) - { - return false; - } - - // Check that the IDs match - if (qFromLittleEndian(tmpId) != instID) - { - return false; - } - - // Read and unpack the data - if ( file.read((char*)buffer, numBytes) != numBytes ) - { - return false; - } - unpack(buffer); - - // Done - return true; -} - /** * Return a string with the object information */ diff --git a/ground/gcs/src/plugins/uavobjects/uavobject.h b/ground/gcs/src/plugins/uavobjects/uavobject.h index 4a8eda6d279..366b82a117c 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobject.h +++ b/ground/gcs/src/plugins/uavobjects/uavobject.h @@ -40,6 +40,12 @@ #include #include "uavobjectfield.h" +#ifdef _MSC_VER +#define PACK( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#else +#define PACK( __Declaration__ ) __Declaration__ __attribute__((__packed__)) +#endif + #define UAVOBJ_ACCESS_SHIFT 0 #define UAVOBJ_GCS_ACCESS_SHIFT 1 #define UAVOBJ_TELEMETRY_ACKED_SHIFT 2 @@ -90,12 +96,12 @@ class UAVOBJECTS_EXPORT UAVObject: public QObject * 4-5 telemetryUpdateMode Update mode used by the telemetry module (UAVObjUpdateMode) * 6-7 gcsTelemetryUpdateMode Update mode used by the GCS (UAVObjUpdateMode) */ - typedef struct { + PACK(typedef struct { quint8 flags; /** Defines flags for update and logging modes and whether an update should be ACK'd (bits defined above) */ quint16 flightTelemetryUpdatePeriod; /** Update period used by the telemetry module (only if telemetry mode is PERIODIC) */ quint16 gcsTelemetryUpdatePeriod; /** Update period used by the GCS (only if telemetry mode is PERIODIC) */ quint16 loggingUpdatePeriod; /** Update period used by the logging module (only if logging mode is PERIODIC) */ - } __attribute__((packed)) Metadata; + }) Metadata; UAVObject(quint32 objID, bool isSingleInst, const QString& name); @@ -109,10 +115,6 @@ class UAVOBJECTS_EXPORT UAVObject: public QObject quint32 getNumBytes(); qint32 pack(quint8* dataOut); qint32 unpack(const quint8* dataIn); - bool save(); - bool save(QFile& file); - bool load(); - bool load(QFile& file); virtual void setMetadata(const Metadata& mdata) = 0; virtual Metadata getMetadata() = 0; virtual Metadata getDefaultMetadata() = 0; diff --git a/ground/gcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/gcs/src/plugins/uavobjects/uavobjectfield.cpp index 5be2cf7090b..7d1adc1135f 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/gcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -29,7 +29,7 @@ #include #include -UAVObjectField::UAVObjectField(const QString& name, const QString& units, FieldType type, quint32 numElements, const QStringList& options, const QString &limits) +UAVObjectField::UAVObjectField(const QString& name, const QString& units, FieldType type, quint32 numElements, const QStringList& options, const QList& indices, const QString &limits) { QStringList elementNames; // Set element names @@ -38,22 +38,23 @@ UAVObjectField::UAVObjectField(const QString& name, const QString& units, FieldT elementNames.append(QString("%1").arg(n)); } // Initialize - constructorInitialize(name, units, type, elementNames, options,limits); + constructorInitialize(name, units, type, elementNames, options, indices, limits); } -UAVObjectField::UAVObjectField(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QString &limits) +UAVObjectField::UAVObjectField(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QList& indices, const QString &limits) { - constructorInitialize(name, units, type, elementNames, options,limits); + constructorInitialize(name, units, type, elementNames, options, indices, limits); } -void UAVObjectField::constructorInitialize(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options,const QString &limits) +void UAVObjectField::constructorInitialize(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QList& indices, const QString &limits) { // Copy params this->name = name; this->units = units; this->type = type; this->options = options; + this->indices = indices; this->numElements = elementNames.length(); this->offset = 0; this->data = NULL; @@ -88,7 +89,8 @@ void UAVObjectField::constructorInitialize(const QString& name, const QString& u break; case BITFIELD: numBytesPerElement = sizeof(quint8); - this->options = QStringList()<options = QStringList() << tr("0") << tr("1"); + this->indices = QList() << 0 << 1; break; case STRING: numBytesPerElement = sizeof(quint8); @@ -313,6 +315,9 @@ bool UAVObjectField::isWithinLimits(QVariant var,quint32 index, int board) return true; break; case ENUM: + // OK, I think this is OK with parents. Because we'll + // consider the limit to mean "as ordered in this object". + // So no need to map to underlying types. if(!(options.indexOf(var.toString())>=options.indexOf(struc.values.at(0).toString()) && options.indexOf(var.toString())<=options.indexOf(struc.values.at(1).toString()))) return false; return true; @@ -877,12 +882,14 @@ QVariant UAVObjectField::getValue(quint32 index) { quint8 tmpenum; memcpy(&tmpenum, &data[offset + numBytesPerElement*index], numBytesPerElement); - // Q_ASSERT((tmpenum < options.length()) && (tmpenum >= 0)); // catch bad enum settings - if(tmpenum >= options.length()) { - qDebug() << "Invalid value for" << name; - return QVariant( QString("Bad Value") ); - } - return QVariant( options[tmpenum] ); + // Too slow? + for (int i = 0; i < indices.length(); i++) { + if (tmpenum == indices[i]) { + return QVariant( options[i] ); + } + } + + return QVariant( QString("Bad Value") ); break; } case BITFIELD: @@ -1007,6 +1014,9 @@ void UAVObjectField::setValue(const QVariant& value, quint32 index) { qint8 tmpenum = options.indexOf( value.toString() ); Q_ASSERT(tmpenum >= 0); // To catch any programming errors where we set invalid values + + tmpenum = indices[tmpenum]; + memcpy(&data[offset + numBytesPerElement*index], &tmpenum, numBytesPerElement); break; } diff --git a/ground/gcs/src/plugins/uavobjects/uavobjectfield.h b/ground/gcs/src/plugins/uavobjects/uavobjectfield.h index 48d92779757..c25df7ff6bb 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/gcs/src/plugins/uavobjects/uavobjectfield.h @@ -51,8 +51,8 @@ class UAVOBJECTS_EXPORT UAVObjectField: public QObject int board; } LimitStruct; - UAVObjectField(const QString& name, const QString& units, FieldType type, quint32 numElements, const QStringList& options,const QString& limits=QString()); - UAVObjectField(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options,const QString& limits=QString()); + UAVObjectField(const QString& name, const QString& units, FieldType type, quint32 numElements, const QStringList& options, const QList& indices, const QString& limits=QString()); + UAVObjectField(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QList& indices, const QString& limits=QString()); void initialize(quint8* data, quint32 dataOffset, UAVObject* obj); UAVObject* getObject(); FieldType getType(); @@ -86,6 +86,7 @@ class UAVOBJECTS_EXPORT UAVObjectField: public QObject QString units; FieldType type; QStringList elementNames; + QList indices; QStringList options; quint32 numElements; quint32 numBytesPerElement; @@ -94,7 +95,7 @@ class UAVOBJECTS_EXPORT UAVObjectField: public QObject UAVObject* obj; QMap > elementLimits; void clear(); - void constructorInitialize(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QString &limits); + void constructorInitialize(const QString& name, const QString& units, FieldType type, const QStringList& elementNames, const QStringList& options, const QList &indices, const QString &limits); void limitsInitialize(const QString &limits); diff --git a/ground/gcs/src/plugins/uavobjects/uavobjects.pro b/ground/gcs/src/plugins/uavobjects/uavobjects.pro index 230fe3720f6..059ec743b91 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobjects.pro +++ b/ground/gcs/src/plugins/uavobjects/uavobjects.pro @@ -24,247 +24,5 @@ OTHER_FILES += UAVObjects.pluginspec \ UAVObjects.json # Add in all of the synthetic/generated uavobject files -HEADERS += $$UAVOBJECT_SYNTHETICS/accels.h \ - $$UAVOBJECT_SYNTHETICS/acceldesired.h \ - $$UAVOBJECT_SYNTHETICS/accessorydesired.h \ - $$UAVOBJECT_SYNTHETICS/actuatorcommand.h \ - $$UAVOBJECT_SYNTHETICS/actuatordesired.h \ - $$UAVOBJECT_SYNTHETICS/actuatorsettings.h \ - $$UAVOBJECT_SYNTHETICS/airspeedsettings.h \ - $$UAVOBJECT_SYNTHETICS/airspeedactual.h \ - $$UAVOBJECT_SYNTHETICS/altitudeholddesired.h \ - $$UAVOBJECT_SYNTHETICS/altitudeholdsettings.h \ - $$UAVOBJECT_SYNTHETICS/altitudeholdstate.h \ - $$UAVOBJECT_SYNTHETICS/attitudeactual.h \ - $$UAVOBJECT_SYNTHETICS/attitudesettings.h \ - $$UAVOBJECT_SYNTHETICS/attitudesimulated.h \ - $$UAVOBJECT_SYNTHETICS/baroaltitude.h \ - $$UAVOBJECT_SYNTHETICS/baroairspeed.h \ - $$UAVOBJECT_SYNTHETICS/brushlessgimbalsettings.h \ - $$UAVOBJECT_SYNTHETICS/cameradesired.h \ - $$UAVOBJECT_SYNTHETICS/camerastabsettings.h \ - $$UAVOBJECT_SYNTHETICS/faultsettings.h \ - $$UAVOBJECT_SYNTHETICS/firmwareiapobj.h \ - $$UAVOBJECT_SYNTHETICS/fixedwingairspeeds.h \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettingscc.h \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.h \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.h \ - $$UAVOBJECT_SYNTHETICS/flightbatterysettings.h \ - $$UAVOBJECT_SYNTHETICS/flightbatterystate.h \ - $$UAVOBJECT_SYNTHETICS/flightplanstatus.h \ - $$UAVOBJECT_SYNTHETICS/flightplansettings.h \ - $$UAVOBJECT_SYNTHETICS/flightplancontrol.h \ - $$UAVOBJECT_SYNTHETICS/flightstatus.h \ - $$UAVOBJECT_SYNTHETICS/flightstats.h \ - $$UAVOBJECT_SYNTHETICS/flightstatssettings.h \ - $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.h \ - $$UAVOBJECT_SYNTHETICS/gcsreceiver.h \ - $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.h \ - $$UAVOBJECT_SYNTHETICS/geofencesettings.h \ - $$UAVOBJECT_SYNTHETICS/gpsposition.h \ - $$UAVOBJECT_SYNTHETICS/gpssatellites.h \ - $$UAVOBJECT_SYNTHETICS/gpstime.h \ - $$UAVOBJECT_SYNTHETICS/gpsvelocity.h \ - $$UAVOBJECT_SYNTHETICS/groundtruth.h \ - $$UAVOBJECT_SYNTHETICS/groundpathfollowersettings.h \ - $$UAVOBJECT_SYNTHETICS/gyros.h \ - $$UAVOBJECT_SYNTHETICS/gyrosbias.h \ - $$UAVOBJECT_SYNTHETICS/homelocation.h \ - $$UAVOBJECT_SYNTHETICS/hottsettings.h \ - $$UAVOBJECT_SYNTHETICS/hwcolibri.h \ - $$UAVOBJECT_SYNTHETICS/hwcoptercontrol.h \ - $$UAVOBJECT_SYNTHETICS/hwdiscoveryf4.h \ - $$UAVOBJECT_SYNTHETICS/hwfreedom.h \ - $$UAVOBJECT_SYNTHETICS/hwflyingf3.h \ - $$UAVOBJECT_SYNTHETICS/hwflyingf4.h \ - $$UAVOBJECT_SYNTHETICS/hwquanton.h \ - $$UAVOBJECT_SYNTHETICS/hwrevolution.h \ - $$UAVOBJECT_SYNTHETICS/hwrevomini.h \ - $$UAVOBJECT_SYNTHETICS/hwsparky.h \ - $$UAVOBJECT_SYNTHETICS/hwsparkybgc.h \ - $$UAVOBJECT_SYNTHETICS/hwtaulink.h \ - $$UAVOBJECT_SYNTHETICS/hwsparky2.h \ - $$UAVOBJECT_SYNTHETICS/i2cvm.h \ - $$UAVOBJECT_SYNTHETICS/i2cvmuserprogram.h \ - $$UAVOBJECT_SYNTHETICS/inssettings.h \ - $$UAVOBJECT_SYNTHETICS/insstate.h \ - $$UAVOBJECT_SYNTHETICS/loitercommand.h \ - $$UAVOBJECT_SYNTHETICS/loggingsettings.h \ - $$UAVOBJECT_SYNTHETICS/loggingstats.h \ - $$UAVOBJECT_SYNTHETICS/magbias.h \ - $$UAVOBJECT_SYNTHETICS/magnetometer.h \ - $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.h \ - $$UAVOBJECT_SYNTHETICS/manualcontrolcommand.h \ - $$UAVOBJECT_SYNTHETICS/mixersettings.h \ - $$UAVOBJECT_SYNTHETICS/mixerstatus.h \ - $$UAVOBJECT_SYNTHETICS/modulesettings.h \ - $$UAVOBJECT_SYNTHETICS/mwratesettings.h \ - $$UAVOBJECT_SYNTHETICS/nedaccel.h \ - $$UAVOBJECT_SYNTHETICS/nedposition.h \ - $$UAVOBJECT_SYNTHETICS/objectpersistence.h \ - $$UAVOBJECT_SYNTHETICS/oplinksettings.h \ - $$UAVOBJECT_SYNTHETICS/openlrs.h \ - $$UAVOBJECT_SYNTHETICS/openlrsstatus.h \ - $$UAVOBJECT_SYNTHETICS/overosyncsettings.h \ - $$UAVOBJECT_SYNTHETICS/overosyncstats.h \ - $$UAVOBJECT_SYNTHETICS/pathdesired.h \ - $$UAVOBJECT_SYNTHETICS/pathplannersettings.h \ - $$UAVOBJECT_SYNTHETICS/pathstatus.h \ - $$UAVOBJECT_SYNTHETICS/picocsettings.h \ - $$UAVOBJECT_SYNTHETICS/picocstatus.h \ - $$UAVOBJECT_SYNTHETICS/poilocation.h \ - $$UAVOBJECT_SYNTHETICS/positionactual.h \ - $$UAVOBJECT_SYNTHETICS/radiocombridgestats.h \ - $$UAVOBJECT_SYNTHETICS/ratedesired.h \ - $$UAVOBJECT_SYNTHETICS/receiveractivity.h \ - $$UAVOBJECT_SYNTHETICS/rfm22breceiver.h \ - $$UAVOBJECT_SYNTHETICS/sensorsettings.h \ - $$UAVOBJECT_SYNTHETICS/sessionmanaging.h \ - $$UAVOBJECT_SYNTHETICS/sonaraltitude.h \ - $$UAVOBJECT_SYNTHETICS/stabilizationdesired.h \ - $$UAVOBJECT_SYNTHETICS/stabilizationsettings.h \ - $$UAVOBJECT_SYNTHETICS/stateestimation.h \ - $$UAVOBJECT_SYNTHETICS/systemstats.h \ - $$UAVOBJECT_SYNTHETICS/systemident.h \ - $$UAVOBJECT_SYNTHETICS/systemalarms.h \ - $$UAVOBJECT_SYNTHETICS/systemsettings.h \ - $$UAVOBJECT_SYNTHETICS/tabletinfo.h \ - $$UAVOBJECT_SYNTHETICS/taskinfo.h \ - $$UAVOBJECT_SYNTHETICS/rfm22bstatus.h \ - $$UAVOBJECT_SYNTHETICS/trimangles.h \ - $$UAVOBJECT_SYNTHETICS/trimanglessettings.h \ - $$UAVOBJECT_SYNTHETICS/txpidsettings.h \ - $$UAVOBJECT_SYNTHETICS/ubloxinfo.h \ - $$UAVOBJECT_SYNTHETICS/velocitydesired.h \ - $$UAVOBJECT_SYNTHETICS/velocityactual.h \ - $$UAVOBJECT_SYNTHETICS/vibrationanalysisoutput.h \ - $$UAVOBJECT_SYNTHETICS/vibrationanalysissettings.h \ - $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.h \ - $$UAVOBJECT_SYNTHETICS/vtolpathfollowerstatus.h \ - $$UAVOBJECT_SYNTHETICS/watchdogstatus.h \ - $$UAVOBJECT_SYNTHETICS/waypoint.h \ - $$UAVOBJECT_SYNTHETICS/waypointactive.h \ - $$UAVOBJECT_SYNTHETICS/windvelocityactual.h - -SOURCES += $$UAVOBJECT_SYNTHETICS/accels.cpp \ - $$UAVOBJECT_SYNTHETICS/acceldesired.cpp \ - $$UAVOBJECT_SYNTHETICS/accessorydesired.cpp \ - $$UAVOBJECT_SYNTHETICS/actuatorcommand.cpp \ - $$UAVOBJECT_SYNTHETICS/actuatordesired.cpp \ - $$UAVOBJECT_SYNTHETICS/actuatorsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/airspeedsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/airspeedactual.cpp \ - $$UAVOBJECT_SYNTHETICS/altitudeholddesired.cpp \ - $$UAVOBJECT_SYNTHETICS/altitudeholdsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/altitudeholdstate.cpp \ - $$UAVOBJECT_SYNTHETICS/attitudeactual.cpp \ - $$UAVOBJECT_SYNTHETICS/attitudesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/attitudesimulated.cpp \ - $$UAVOBJECT_SYNTHETICS/baroaltitude.cpp \ - $$UAVOBJECT_SYNTHETICS/baroairspeed.cpp \ - $$UAVOBJECT_SYNTHETICS/brushlessgimbalsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/cameradesired.cpp \ - $$UAVOBJECT_SYNTHETICS/camerastabsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/faultsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/firmwareiapobj.cpp \ - $$UAVOBJECT_SYNTHETICS/fixedwingairspeeds.cpp \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettingscc.cpp \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/fixedwingpathfollowerstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/flightbatterysettings.cpp \ - $$UAVOBJECT_SYNTHETICS/flightbatterystate.cpp \ - $$UAVOBJECT_SYNTHETICS/flightplanstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/flightplansettings.cpp \ - $$UAVOBJECT_SYNTHETICS/flightplancontrol.cpp \ - $$UAVOBJECT_SYNTHETICS/flightstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/flightstats.cpp \ - $$UAVOBJECT_SYNTHETICS/flightstatssettings.cpp \ - $$UAVOBJECT_SYNTHETICS/flighttelemetrystats.cpp \ - $$UAVOBJECT_SYNTHETICS/gcsreceiver.cpp \ - $$UAVOBJECT_SYNTHETICS/gcstelemetrystats.cpp \ - $$UAVOBJECT_SYNTHETICS/geofencesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/gpsposition.cpp \ - $$UAVOBJECT_SYNTHETICS/gpssatellites.cpp \ - $$UAVOBJECT_SYNTHETICS/gpstime.cpp \ - $$UAVOBJECT_SYNTHETICS/gpsvelocity.cpp \ - $$UAVOBJECT_SYNTHETICS/groundtruth.cpp \ - $$UAVOBJECT_SYNTHETICS/groundpathfollowersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/gyros.cpp \ - $$UAVOBJECT_SYNTHETICS/gyrosbias.cpp \ - $$UAVOBJECT_SYNTHETICS/homelocation.cpp \ - $$UAVOBJECT_SYNTHETICS/hottsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/hwcolibri.cpp \ - $$UAVOBJECT_SYNTHETICS/hwcoptercontrol.cpp \ - $$UAVOBJECT_SYNTHETICS/hwdiscoveryf4.cpp \ - $$UAVOBJECT_SYNTHETICS/hwfreedom.cpp \ - $$UAVOBJECT_SYNTHETICS/hwflyingf3.cpp \ - $$UAVOBJECT_SYNTHETICS/hwflyingf4.cpp \ - $$UAVOBJECT_SYNTHETICS/hwquanton.cpp \ - $$UAVOBJECT_SYNTHETICS/hwrevolution.cpp \ - $$UAVOBJECT_SYNTHETICS/hwrevomini.cpp \ - $$UAVOBJECT_SYNTHETICS/hwsparky.cpp \ - $$UAVOBJECT_SYNTHETICS/hwsparkybgc.cpp \ - $$UAVOBJECT_SYNTHETICS/hwtaulink.cpp \ - $$UAVOBJECT_SYNTHETICS/hwsparky2.cpp \ - $$UAVOBJECT_SYNTHETICS/i2cvm.cpp \ - $$UAVOBJECT_SYNTHETICS/i2cvmuserprogram.cpp \ - $$UAVOBJECT_SYNTHETICS/inssettings.cpp \ - $$UAVOBJECT_SYNTHETICS/insstate.cpp \ - $$UAVOBJECT_SYNTHETICS/loitercommand.cpp \ - $$UAVOBJECT_SYNTHETICS/loggingsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/loggingstats.cpp \ - $$UAVOBJECT_SYNTHETICS/magbias.cpp \ - $$UAVOBJECT_SYNTHETICS/magnetometer.cpp \ - $$UAVOBJECT_SYNTHETICS/manualcontrolsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/manualcontrolcommand.cpp \ - $$UAVOBJECT_SYNTHETICS/mixersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/mixerstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/modulesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/mwratesettings.cpp \ - $$UAVOBJECT_SYNTHETICS/nedaccel.cpp \ - $$UAVOBJECT_SYNTHETICS/nedposition.cpp \ - $$UAVOBJECT_SYNTHETICS/objectpersistence.cpp \ - $$UAVOBJECT_SYNTHETICS/oplinksettings.cpp \ - $$UAVOBJECT_SYNTHETICS/openlrs.cpp \ - $$UAVOBJECT_SYNTHETICS/openlrsstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/overosyncsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/overosyncstats.cpp \ - $$UAVOBJECT_SYNTHETICS/pathdesired.cpp \ - $$UAVOBJECT_SYNTHETICS/pathplannersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/pathstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/picocsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/picocstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/poilocation.cpp \ - $$UAVOBJECT_SYNTHETICS/positionactual.cpp \ - $$UAVOBJECT_SYNTHETICS/radiocombridgestats.cpp \ - $$UAVOBJECT_SYNTHETICS/ratedesired.cpp \ - $$UAVOBJECT_SYNTHETICS/receiveractivity.cpp \ - $$UAVOBJECT_SYNTHETICS/rfm22breceiver.cpp \ - $$UAVOBJECT_SYNTHETICS/sensorsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/sessionmanaging.cpp \ - $$UAVOBJECT_SYNTHETICS/sonaraltitude.cpp \ - $$UAVOBJECT_SYNTHETICS/stabilizationdesired.cpp \ - $$UAVOBJECT_SYNTHETICS/stabilizationsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/stateestimation.cpp \ - $$UAVOBJECT_SYNTHETICS/systemalarms.cpp \ - $$UAVOBJECT_SYNTHETICS/systemident.cpp \ - $$UAVOBJECT_SYNTHETICS/systemsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/systemstats.cpp \ - $$UAVOBJECT_SYNTHETICS/tabletinfo.cpp \ - $$UAVOBJECT_SYNTHETICS/taskinfo.cpp \ - $$UAVOBJECT_SYNTHETICS/rfm22bstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/trimangles.cpp \ - $$UAVOBJECT_SYNTHETICS/trimanglessettings.cpp \ - $$UAVOBJECT_SYNTHETICS/txpidsettings.cpp \ - $$UAVOBJECT_SYNTHETICS/uavobjectsinit.cpp \ - $$UAVOBJECT_SYNTHETICS/ubloxinfo.cpp \ - $$UAVOBJECT_SYNTHETICS/velocitydesired.cpp \ - $$UAVOBJECT_SYNTHETICS/velocityactual.cpp \ - $$UAVOBJECT_SYNTHETICS/vibrationanalysisoutput.cpp \ - $$UAVOBJECT_SYNTHETICS/vibrationanalysissettings.cpp \ - $$UAVOBJECT_SYNTHETICS/vtolpathfollowersettings.cpp \ - $$UAVOBJECT_SYNTHETICS/vtolpathfollowerstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/watchdogstatus.cpp \ - $$UAVOBJECT_SYNTHETICS/waypoint.cpp \ - $$UAVOBJECT_SYNTHETICS/waypointactive.cpp\ - $$UAVOBJECT_SYNTHETICS/windvelocityactual.cpp +HEADERS += $$files($$UAVOBJECT_SYNTHETICS/*.h) +SOURCES += $$files($$UAVOBJECT_SYNTHETICS/*.cpp) diff --git a/ground/gcs/src/plugins/uavobjects/uavobjecttemplate.h b/ground/gcs/src/plugins/uavobjects/uavobjecttemplate.h index 17c87036fd0..d38465da750 100644 --- a/ground/gcs/src/plugins/uavobjects/uavobjecttemplate.h +++ b/ground/gcs/src/plugins/uavobjects/uavobjecttemplate.h @@ -36,6 +36,8 @@ #include "uavdataobject.h" #include "uavobjectmanager.h" +$(PARENT_INCLUDES) + class UAVOBJECTS_EXPORT $(NAME): public UAVDataObject { Q_OBJECT @@ -44,10 +46,17 @@ class UAVOBJECTS_EXPORT $(NAME): public UAVDataObject public: // Field structure +#ifdef _MSC_VER +#pragma pack(push, 1) +__declspec(align(4)) typedef struct { +$(DATAFIELDS) + } DataFields; +#pragma pack(pop) +#else typedef struct { $(DATAFIELDS) } __attribute__((packed)) __attribute__((aligned(4))) DataFields; - +#endif // Field information $(DATAFIELDINFO) diff --git a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp index 223c559a2ab..06e0b8f1242 100644 --- a/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp +++ b/ground/gcs/src/plugins/uavobjectutil/uavobjectutilmanager.cpp @@ -35,6 +35,7 @@ #include #include #include +#include #include #include "firmwareiapobj.h" @@ -703,7 +704,10 @@ bool UAVObjectUtilManager::descriptionToStructure(QByteArray desc, deviceDescrip struc.fwHash=desc.mid(40,20); struc.uavoHash.clear(); struc.uavoHash=desc.mid(60,20); - if (struc.gitTag.startsWith("RELEASE",Qt::CaseSensitive)) + + // The git tag format used for releases is yyyymmdd + QRegularExpression certifiedPattern("^20[0-9]{6}$"); + if (certifiedPattern.match(struc.gitTag).hasMatch()) struc.certified = true; else struc.certified = false; diff --git a/ground/gcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutilsplugin.cpp b/ground/gcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutilsplugin.cpp index b83b26390ba..d41fd244c3b 100644 --- a/ground/gcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutilsplugin.cpp +++ b/ground/gcs/src/plugins/uavobjectwidgetutils/uavobjectwidgetutilsplugin.cpp @@ -27,6 +27,7 @@ */ #include "uavobjectwidgetutilsplugin.h" +#include UAVObjectWidgetUtilsPlugin::UAVObjectWidgetUtilsPlugin() { diff --git a/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro b/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro index 3c040764bb5..99ce6483131 100644 --- a/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro +++ b/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexport.pro @@ -2,6 +2,7 @@ TEMPLATE = lib QT += xml QT += widgets +QT += xmlpatterns TARGET = UAVSettingsImportExport DEFINES += UAVSETTINGSIMPORTEXPORT_LIBRARY include(../../taulabsgcsplugin.pri) diff --git a/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp b/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp index 4425bb1dc7e..d80c32ea35f 100644 --- a/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp +++ b/ground/gcs/src/plugins/uavsettingsimportexport/uavsettingsimportexportfactory.cpp @@ -46,6 +46,7 @@ // for XML object #include +#include // for file dialog and error messages #include @@ -337,7 +338,39 @@ QString UAVSettingsImportExportFactory::createXMLDocument(const enum storedData } } - return doc.toString(4); + // This sorts the XML children's attribute by alphabetical order. This + // is particularly helpful when comparing *.uav files to each other. + QString preliminaryXMLDoc = doc.toString(4); + QString alphabetizedXMLDoc; + + QString xmlAlpheticalSorter(" \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + \ + "); + + QXmlQuery query(QXmlQuery::XSLT20); + query.setFocus(preliminaryXMLDoc); + query.setQuery(xmlAlpheticalSorter); + query.evaluateTo(&alphabetizedXMLDoc); + + return alphabetizedXMLDoc; } // Slot called by the menu manager on user action diff --git a/ground/gcs/src/plugins/uploader/bl_messages.h b/ground/gcs/src/plugins/uploader/bl_messages.h index eb4f9ae6ab5..9bf59735e26 100644 --- a/ground/gcs/src/plugins/uploader/bl_messages.h +++ b/ground/gcs/src/plugins/uploader/bl_messages.h @@ -28,6 +28,14 @@ #ifndef BL_MESSAGES_H_ #define BL_MESSAGES_H_ +#ifndef PACK +#ifdef _MSC_VER +#define PACK( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) ) +#else +#define PACK( __Declaration__ ) __Declaration__ __attribute__((__packed__)) +#endif /* _MSC_VER */ +#endif /* PACK */ + namespace tl_dfu { #define BL_INCLUDE_CAP_EXTENSIONS @@ -36,7 +44,6 @@ namespace tl_dfu { #define uint16_t quint16 #define uint32_t quint32 - /* Note: * Writes are from PC -> FC * Reads are from FC -> PC @@ -85,6 +92,10 @@ enum bl_commands { * Note: These enum values MUST NOT be changed or backward * compatibility will be broken */ + +#ifdef _MSC_VER +#pragma pack(push,1) +#endif enum dfu_partition_label { DFU_PARTITION_FW, DFU_PARTITION_DESC, @@ -93,91 +104,112 @@ enum dfu_partition_label { DFU_PARTITION_WAYPOINTS, DFU_PARTITION_LOG, DFU_PARTITION_OTA, +#ifdef _MSC_VER +} +#pragma pack(pop) +#else }__attribute__((packed)); +#endif -struct bl_messages { - uint8_t flags_command; +struct msg_capabilities_req { + uint8_t unused[4]; + uint8_t device_number; +}; - union { - struct msg_capabilities_req { - uint8_t unused[4]; - uint8_t device_number; - } cap_req; - - struct msg_capabilities_rep_all { - uint8_t unused[4]; - uint16_t number_of_devices; - uint16_t wrflags; - } cap_rep_all; - - struct msg_capabilities_rep_specific { - uint32_t fw_size; - uint8_t device_number; - uint8_t bl_version; - uint8_t desc_size; - uint8_t board_rev; - uint32_t fw_crc; - uint16_t device_id; +struct msg_capabilities_rep_all { + uint8_t unused[4]; + uint16_t number_of_devices; + uint16_t wrflags; +}; + +struct msg_capabilities_rep_specific { + uint32_t fw_size; + uint8_t device_number; + uint8_t bl_version; + uint8_t desc_size; + uint8_t board_rev; + uint32_t fw_crc; + uint16_t device_id; #if defined(BL_INCLUDE_CAP_EXTENSIONS) - /* Extensions to original protocol */ + /* Extensions to original protocol */ #define BL_CAP_EXTENSION_MAGIC 0x3456 - uint16_t cap_extension_magic; - uint32_t partition_sizes[10]; + uint16_t cap_extension_magic; + uint32_t partition_sizes[10]; #endif /* BL_INCLUDE_CAP_EXTENSIONS */ - } cap_rep_specific; - - struct msg_enter_dfu { - uint8_t unused[4]; - uint8_t device_number; - } enter_dfu; - - struct msg_jump_fw { - uint8_t unused[4]; - uint8_t unused2[2]; - uint16_t safe_word; - } jump_fw; - - struct msg_reset { - /* No subfields */ - } reset; - - struct msg_op_abort { - /* No subfields */ - } op_abort; - - struct msg_op_end { - /* No subfields */ - } op_end; - - struct msg_xfer_start { - uint32_t packets_in_transfer; - uint8_t label; - uint8_t words_in_last_packet; - uint32_t expected_crc; /* only used in writes */ - }__attribute__((packed)) xfer_start; +}; + +struct msg_enter_dfu { + uint8_t unused[4]; + uint8_t device_number; +}; + +struct msg_jump_fw { + uint8_t unused[4]; + uint8_t unused2[2]; + uint16_t safe_word; +}; + +struct msg_reset { + /* No subfields */ +}; + +struct msg_op_abort { + /* No subfields */ +}; + +struct msg_op_end { + /* No subfields */ +}; + +PACK(struct msg_xfer_start { + uint32_t packets_in_transfer; + uint8_t label; + uint8_t words_in_last_packet; + uint32_t expected_crc; /* only used in writes */ +}); #define XFER_BYTES_PER_PACKET 56 - struct msg_xfer_cont { - uint32_t current_packet_number; - uint8_t data[XFER_BYTES_PER_PACKET]; - } xfer_cont; - - struct msg_status_req { - /* No subfields */ - } status_req; - - struct msg_status_rep { - uint32_t unused; - uint8_t current_state; - } status_rep; - - struct msg_wipe_partition { - uint8_t label; - } wipe_partition; - - uint8_t pad[62]; - } __attribute__((aligned(1)))v; -} __attribute__((packed)); -} +struct msg_xfer_cont { + uint32_t current_packet_number; + uint8_t data[XFER_BYTES_PER_PACKET]; +}; + +struct msg_status_req { + /* No subfields */ +}; + +struct msg_status_rep { + uint32_t unused; + uint8_t current_state; +}; + +struct msg_wipe_partition { + uint8_t label; +}; + +PACK(union msg_contents { + struct msg_capabilities_req cap_req; + struct msg_capabilities_rep_all cap_rep_all; + struct msg_capabilities_rep_specific cap_rep_specific; + struct msg_enter_dfu enter_dfu; + struct msg_jump_fw jump_fw; + struct msg_reset reset; + struct msg_op_abort op_abort; + struct msg_op_end op_end; + struct msg_xfer_start xfer_start; + struct msg_xfer_cont xfer_cont; + struct msg_status_req status_req; + struct msg_status_rep status_rep; + struct msg_wipe_partition wipe_partition; + uint8_t pad[62]; +}); + +PACK(struct bl_messages { + uint8_t flags_command; + + union msg_contents v; +}); + +} /* namespace tl_dfu */ #endif // BL_MESSAGES_H diff --git a/ground/gcs/src/plugins/uploader/tl_dfu.cpp b/ground/gcs/src/plugins/uploader/tl_dfu.cpp index 88da360009b..64d24b9aa9f 100644 --- a/ground/gcs/src/plugins/uploader/tl_dfu.cpp +++ b/ground/gcs/src/plugins/uploader/tl_dfu.cpp @@ -637,7 +637,7 @@ quint32 DFUObject::CRCFromQBArray(QByteArray array, quint32 Size) array.append( QByteArray(pad, 255) ); } - int maxSize = (array.length() > Size) ? Size : array.length(); + int maxSize = ((quint32) array.length() > Size) ? Size : array.length(); // Large firmwares require defining super large arrays, // so better to malloc them. I did run into stack overflows here // with devices with large firmwares (1MB) (E. Lafargue), hence diff --git a/ground/gcs/src/plugins/uploader/uploadergadgetwidget.cpp b/ground/gcs/src/plugins/uploader/uploadergadgetwidget.cpp index ae6bdc1c476..716c90dd6cc 100755 --- a/ground/gcs/src/plugins/uploader/uploadergadgetwidget.cpp +++ b/ground/gcs/src/plugins/uploader/uploadergadgetwidget.cpp @@ -1171,12 +1171,21 @@ void UploaderGadgetWidget::onResetButtonClick() } timeout.stop(); } - setUploaderStatus(uploader::BOOTING); - conMngr->disconnectDevice(); - timeout.start(200); - loop.exec(); - conMngr->suspendPolling(); - bootTimeoutTimer.start(); + if(conMngr->getCurrentDevice().connection->shortName() == "USB") + { + setUploaderStatus(uploader::BOOTING); + conMngr->disconnectDevice(); + timeout.start(200); + loop.exec(); + conMngr->suspendPolling(); + bootTimeoutTimer.start(); + } + else + { + setUploaderStatus(uploader::DISCONNECTED); + conMngr->disconnectDevice(); + } + return; } @@ -1235,11 +1244,19 @@ void UploaderGadgetWidget::onHaltButtonClick() } timeout.stop(); } - conMngr->disconnectDevice(); - timeout.start(200); - loop.exec(); - conMngr->suspendPolling(); - onRescueTimer(true); + if(conMngr->getCurrentDevice().connection->shortName() == "USB") + { + conMngr->disconnectDevice(); + timeout.start(200); + loop.exec(); + conMngr->suspendPolling(); + onRescueTimer(true); + } + else + { + setUploaderStatus(uploader::DISCONNECTED); + conMngr->disconnectDevice(); + } return; } @@ -1341,10 +1358,7 @@ void UploaderGadgetWidget::setUploaderStatus(const uploader::UploaderStatus &val case uploader::CONNECTED_TO_TELEMETRY: m_widget->rescueButton->setVisible(false); m_widget->openButton->setVisible(true); - if(conMngr->getCurrentDevice().connection->shortName() == "USB") - m_widget->haltButton->setVisible(true); - else - m_widget->haltButton->setVisible(false); + m_widget->haltButton->setVisible(true); m_widget->bootButton->setVisible(false); m_widget->safeBootButton->setVisible(false); m_widget->resetButton->setVisible(true); diff --git a/ground/gcs/src/shared/qtsingleapplication/qtlocalpeer.cpp b/ground/gcs/src/shared/qtsingleapplication/qtlocalpeer.cpp index 1d9a8dd8d0f..ee6cc58436f 100644 --- a/ground/gcs/src/shared/qtsingleapplication/qtlocalpeer.cpp +++ b/ground/gcs/src/shared/qtsingleapplication/qtlocalpeer.cpp @@ -30,6 +30,7 @@ #include #include +#include #if defined(Q_OS_WIN) #include @@ -38,6 +39,8 @@ typedef BOOL(WINAPI*PProcessIdToSessionId)(DWORD,DWORD*); static PProcessIdToSessionId pProcessIdToSessionId = 0; #endif +#include + #if defined(Q_OS_UNIX) #include #include diff --git a/ground/uavobjects/uavobjects.pro b/ground/uavobjects/uavobjects.pro index 9a1402cd795..52f83e6e5e1 100644 --- a/ground/uavobjects/uavobjects.pro +++ b/ground/uavobjects/uavobjects.pro @@ -38,9 +38,7 @@ win32|unix { win32 { # Windows sometimes remembers working directory changed from Makefile, sometimes not. # That's why pushd/popd is used here - to make sure that we know current directory. - - uavobjects.commands += -$(MKDIR) $$targetPath(../../uavobject-synthetics) $$addNewline() - + uavobjects.commands += -$(MKDIR) -p $$targetPath(../../uavobject-synthetics) $$addNewline() uavobjects.commands += pushd $$targetPath(../../uavobject-synthetics) && uavobjects.commands += $$targetPath(../ground/uavobjgenerator/$${BUILD_CONFIG}/uavobjgenerator) uavobjects.commands += -gcs -flight -matlab diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp index 94951ed0fa4..9d190b52506 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.cpp @@ -97,6 +97,14 @@ bool UAVObjectGeneratorFlight::generate(UAVObjectParser* parser,QString template return true; // if we come here everything should be fine } +QString UAVObjectGeneratorFlight::form_enum_name(QString& objName, + QString &fieldName, QString &option) { + QString s = "%1_%2_%3"; + + return s.arg( objName.toUpper() ) + .arg( fieldName.toUpper() ) + .arg( option.toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")); +} /** * Generate the Flight object files @@ -114,6 +122,15 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo* info) replaceCommonTags(outInclude, info); replaceCommonTags(outCode, info); + // Replace the $(PARENT_INCLUDES) tag + QString parentIncludes; + + foreach (ObjectInfo *parent, info->parents) { + parentIncludes.append( QString("#include <%1.h>\r\n").arg(parent->namelc)); + } + + outInclude.replace(QString("$(PARENT_INCLUDES)"), parentIncludes); + // Replace the $(DATAFIELDS) tag QString type; QString fields; @@ -147,12 +164,20 @@ bool UAVObjectGeneratorFlight::process_object(ObjectInfo* info) // Go through each option QStringList options = info->fields[n]->options; for (int m = 0; m < options.length(); ++m) { - QString s = (m == (options.length()-1)) ? "%1_%2_%3=%4" : "%1_%2_%3=%4, "; + QString optionName = form_enum_name(info->name, + info->fields[n]->name, options[m]); + QString value = QString::number(m); + + if (info->fields[n]->parent) { + value = form_enum_name(info->fields[n]->parentObj->name, + info->fields[n]->parent->name, options[m]); + } + + QString s = (m == (options.length()-1)) ? "%1=%2" : "%1=%2, "; + enums.append( s - .arg( info->name.toUpper() ) - .arg( info->fields[n]->name.toUpper() ) - .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) - .arg(m) ); + .arg( optionName ) + .arg( value ) ); } enums.append( QString(" } __attribute__((packed)) %1%2Options;\r\n") diff --git a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h index db728374b56..f288b006d3c 100644 --- a/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h +++ b/ground/uavobjgenerator/generators/flight/uavobjectgeneratorflight.h @@ -40,6 +40,7 @@ class UAVObjectGeneratorFlight private: bool process_object(ObjectInfo* info); + QString form_enum_name(QString& objName, QString &fieldName, QString &option); }; diff --git a/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.cpp b/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.cpp index e063bce78c5..3c8d86bdb1e 100644 --- a/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.cpp +++ b/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.cpp @@ -71,6 +71,22 @@ bool UAVObjectGeneratorGCS::generate(UAVObjectParser* parser,QString templatepat return true; // if we come here everything should be fine } +QString UAVObjectGeneratorGCS::form_enum_name(const QString& objectName, + const QString& fieldName, const QString& option) { + QString s = "%3::%1_%2"; + + if (objectName.isEmpty()) { + s = "%1_%2"; + + return s.arg( fieldName.toUpper() ) + .arg( option.toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")); + } + + return s.arg( fieldName.toUpper() ) + .arg( option.toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "")) + .arg( objectName); +} + /** * Generate the GCS object files */ @@ -87,6 +103,15 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo* info) replaceCommonTags(outInclude, info); replaceCommonTags(outCode, info); + // Replace the $(PARENT_INCLUDES) tag + QString parentIncludes; + + foreach (ObjectInfo *parent, info->parents) { + parentIncludes.append( QString("#include <%1.h>\r\n").arg(parent->namelc)); + } + + outInclude.replace(QString("$(PARENT_INCLUDES)"), parentIncludes); + // Replace the $(DATAFIELDS) tag QString type; QString fields; @@ -254,25 +279,51 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo* info) // Only for enum types if (info->fields[n]->type == FIELDTYPE_ENUM) { - QString varOptionName = info->fields[n]->name + "EnumOptions"; - finit.append( QString(" QStringList %1;\n").arg(varOptionName) ); + // Form list of enum names + finit.append( QString(" QStringList %1EnumOptions = { ") + .arg( info->fields[n]->name) ); + QStringList options = info->fields[n]->options; for (int m = 0; m < options.length(); ++m) { - finit.append( QString(" %1.append(\"%2\");\n") - .arg(varOptionName) + finit.append( QString("%1\"%2\"") + .arg(QString(m ? ", " : "")) .arg(options[m]) ); } - finit.append( QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::ENUM, %3, %4, QString(\"%5\")));\n") + + finit.append("};\n"); +#if 0 + /* Perhaps use this type in the future, when gcs cleaned up */ + finit.append( QString(" QList<%1Options> %2EnumIndices = { ") + .arg( info->fields[n]->name ) + .arg( info->fields[n]->name ) ); +#endif + + finit.append( QString(" QList %2EnumIndices = { ") + .arg( info->fields[n]->name ) ); + + // Form list of enum values, because they may not be contiguous + for (int m = 0; m < options.length(); ++m) { + QString optionName = form_enum_name(QString(), + info->fields[n]->name, options[m]); + + QString s = (m != (options.length()-1)) ? "%1, " : "%1"; + finit.append( s.arg(optionName) ); + } + + finit.append("};\n"); + + finit.append( QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::ENUM, %3, %4, %5, QString(\"%6\")));\n") .arg(info->fields[n]->name) .arg(info->fields[n]->units) .arg(varElemName) - .arg(varOptionName) + .arg(info->fields[n]->name + "EnumOptions") + .arg(info->fields[n]->name + "EnumIndices") .arg(info->fields[n]->limitValues)); } // For all other types else { - finit.append( QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::%3, %4, QStringList(), QString(\"%5\")));\n") + finit.append( QString(" fields.append( new UAVObjectField(QString(\"%1\"), QString(\"%2\"), UAVObjectField::%3, %4, QStringList(), QList(), QString(\"%5\")));\n") .arg(info->fields[n]->name) .arg(info->fields[n]->units) .arg(fieldTypeStrCPPClass[info->fields[n]->type]) @@ -302,10 +353,18 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo* info) // Go through each option QStringList options = info->fields[n]->options; for (int m = 0; m < options.length(); ++m) { - QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; - enums.append( s.arg( info->fields[n]->name.toUpper() ) - .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) - .arg(m) ); + QString optionName = form_enum_name(QString(), + info->fields[n]->name, options[m]); + QString value = QString::number(m); + + if (info->fields[n]->parent) { + value = form_enum_name(info->fields[n]->parentObj->name, + info->fields[n]->parent->name, options[m]); + } + + QString s = (m != (options.length()-1)) ? "%1=%2, " : "%1=%2"; + enums.append( s.arg(optionName) + .arg(value)); } enums.append( QString(" } %1Options;\n") @@ -321,9 +380,8 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo* info) for (int m = 0; m < elemNames.length(); ++m) { QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; enums.append( s.arg( info->fields[n]->name.toUpper() ) - .arg( elemNames[m].toUpper() ) - .arg(m) ); - + .arg( elemNames[m].toUpper() ) + .arg(m) ); } enums.append( QString(" } %1Elem;\n") .arg( info->fields[n]->name ) ); @@ -377,6 +435,7 @@ bool UAVObjectGeneratorGCS::process_object(ObjectInfo* info) initfields.append( QString(" data.%1[%2] = %3;\n") .arg( info->fields[n]->name ) .arg( idx ) + // XXX TODO MPL .arg( info->fields[n]->options.indexOf( info->fields[n]->defaultValues[idx] ) ) ); } else if ( info->fields[n]->type == FIELDTYPE_FLOAT32 ) { diff --git a/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.h b/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.h index 207ec68cf2b..b41754143a7 100644 --- a/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.h +++ b/ground/uavobjgenerator/generators/gcs/uavobjectgeneratorgcs.h @@ -38,6 +38,8 @@ class UAVObjectGeneratorGCS private: bool process_object(ObjectInfo* info); + QString form_enum_name(const QString& objectName, + const QString& fieldName, const QString& option); QString gcsCodeTemplate,gcsIncludeTemplate; QStringList fieldTypeStrCPP,fieldTypeStrCPPClass; diff --git a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp index dc593fd5fa0..66f9fc71c2e 100644 --- a/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp +++ b/ground/uavobjgenerator/generators/java/uavobjectgeneratorjava.cpp @@ -150,55 +150,6 @@ bool UAVObjectGeneratorJava::process_object(ObjectInfo* info) } outCode.replace(QString("$(FIELDSINIT)"), finit); - // Replace the $(DATAFIELDINFO) tag - QString name; - QString enums; - for (int n = 0; n < info->fields.length(); ++n) - { - enums.append(QString(" // Field %1 information\n").arg(info->fields[n]->name)); - // Only for enum types - if (info->fields[n]->type == FIELDTYPE_ENUM) - { - enums.append(QString(" /* Enumeration options for field %1 */\n").arg(info->fields[n]->name)); - enums.append(" typedef enum { "); - // Go through each option - QStringList options = info->fields[n]->options; - for (int m = 0; m < options.length(); ++m) { - QString s = (m != (options.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; - enums.append( s.arg( info->fields[n]->name.toUpper() ) - .arg( options[m].toUpper().replace(QRegExp(ENUM_SPECIAL_CHARS), "") ) - .arg(m) ); - - } - enums.append( QString(" } %1Options;\n") - .arg( info->fields[n]->name ) ); - } - // Generate element names (only if field has more than one element) - if (info->fields[n]->numElements > 1 && !info->fields[n]->defaultElementNames) { - enums.append(QString(" /* Array element names for field %1 */\n").arg(info->fields[n]->name)); - enums.append(" typedef enum { "); - // Go through the element names - QStringList elemNames = info->fields[n]->elementNames; - for (int m = 0; m < elemNames.length(); ++m) { - QString s = (m != (elemNames.length()-1)) ? "%1_%2=%3, " : "%1_%2=%3"; - enums.append( s.arg( info->fields[n]->name.toUpper() ) - .arg( elemNames[m].toUpper() ) - .arg(m) ); - - } - enums.append( QString(" } %1Elem;\n") - .arg( info->fields[n]->name ) ); - } - // Generate array information - if (info->fields[n]->numElements > 1) { - enums.append(QString(" /* Number of elements for field %1 */\n").arg(info->fields[n]->name)); - enums.append( QString(" static const quint32 %1_NUMELEM = %2;\n") - .arg( info->fields[n]->name.toUpper() ) - .arg( info->fields[n]->numElements ) ); - } - } - outInclude.replace(QString("$(DATAFIELDINFO)"), enums); - // Replace the $(INITFIELDS) tag QString initfields; for (int n = 0; n < info->fields.length(); ++n) diff --git a/ground/uavobjgenerator/main.cpp b/ground/uavobjgenerator/main.cpp index 9c74141242a..1138543da97 100644 --- a/ground/uavobjgenerator/main.cpp +++ b/ground/uavobjgenerator/main.cpp @@ -171,9 +171,20 @@ int main(int argc, char *argv[]) return RETURN_ERR_XML; } + // resolve all references to parent objects + QString res = parser->resolveParents(); + + if (!res.isEmpty()) { + cout << "Error: " << res.toStdString() << endl; + return RETURN_ERR_XML; + } + // check for duplicate object ID's QList objIDList; int numBytesTotal=0; + + parser->calculateAllIds(); + for (int objidx = 0; objidx < parser->getNumObjects(); ++objidx) { quint32 id = parser->getObjectID(objidx); numBytesTotal+=parser->getNumBytes(objidx); diff --git a/ground/uavobjgenerator/uavobjectparser.cpp b/ground/uavobjgenerator/uavobjectparser.cpp index 68d9908b4aa..a6e783046c3 100644 --- a/ground/uavobjgenerator/uavobjectparser.cpp +++ b/ground/uavobjgenerator/uavobjectparser.cpp @@ -3,6 +3,8 @@ * * @file uavobjectparser.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @author Tau Labs, http://taulabs.org, Copyright (C) 2015 + * * @brief Parses XML files and extracts object information. * * @see The GNU Public License (GPL) Version 3 @@ -24,6 +26,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include #include "uavobjectparser.h" @@ -63,9 +66,135 @@ QList UAVObjectParser::getObjectInfo() return objInfo; } +FieldInfo* UAVObjectParser::getFieldByName(QString &name, ObjectInfo **objRet) { + if (objRet) { + *objRet = NULL; + } + + // Split name into object and field name + QStringList splitStr = name.split("."); + + if (splitStr.size() != 2) { + return NULL; + } + + QString objName = splitStr[0].trimmed(); + QString fieldName = splitStr[1].trimmed(); + + // Pull out the object + ObjectInfo *obj = getObjectByName(objName); + + if (!obj) { + return NULL; + } + + // Retrieve field info + foreach (FieldInfo *field, obj->fields) { + if (field->name == fieldName) { + // Got a match-- return it. + if (objRet) { + *objRet = obj; + } + + return field; + } + } + + // Didn't find it? Give up. (return neither obj nor field) + return NULL; +} + +int UAVObjectParser::resolveFieldParent(ObjectInfo *item, FieldInfo *field) +{ + if (field->parent) { + // We could have done this already because of how we recursively + // do stuff. + return 0; + } + + if (!field->parentName.isEmpty()) { + // There is a parent relationship we have to resolve here. + field->parent = getFieldByName(field->parentName, + &field->parentObj); + + if (!field->parent) { + return -1; + } + + // Add to object parent set, if not present. + item->parents.insert(field->parentObj); + + // Make sure any upwards dependencies are resolved before using the + // field info. This allows inheritance multiple levels deep. + resolveFieldParent(field->parentObj, field->parent); + + // If the child had no options specified, take the list from + // the parent + if (field->options.isEmpty()) { + field->options.append(field->parent->options); + } + } + + return 0; +} + +QString UAVObjectParser::resolveParents() +{ + foreach (ObjectInfo *item, objInfo) { + foreach (FieldInfo *field, item->fields) { + // Because resolveFieldParent can recurse, make sure we've not + // set a parent here already. + if (resolveFieldParent(item, field) < 0) { + return QString("Invalid parent for %1.%2") + .arg(item->name) + .arg(field->name); + } + + for (int n = 0; n < field->options.length(); n++) { + if (findOptionIndex(field, n) < 0) { + return QString("Parent of %1.%2.%3 missing") + .arg(item->name) + .arg(field->name) + .arg(field->options[n]); + } + } + } + } + + return QString(); +} + +void UAVObjectParser::calculateAllIds() +{ + foreach (ObjectInfo *item, objInfo) { + calculateID(item); + } +} + +ObjectInfo* UAVObjectParser::getObjectByName(QString& name) { + foreach (ObjectInfo *item, objInfo) { + if (item->name == name) { + return item; + } + } + + return NULL; +} + + ObjectInfo* UAVObjectParser::getObjectByIndex(int objIndex) { - return objInfo[objIndex]; + ObjectInfo *ret = objInfo[objIndex]; + + if (ret != NULL) { + if (ret->id == 0) { + // Lazily calculate IDs on first retrieval. This lets us have + // dependent objects that are fixed up after parse completes. + calculateID(ret); + } + } + + return ret; } /** @@ -73,7 +202,7 @@ ObjectInfo* UAVObjectParser::getObjectByIndex(int objIndex) */ QString UAVObjectParser::getObjectName(int objIndex) { - ObjectInfo* info = objInfo[objIndex]; + ObjectInfo* info = getObjectByIndex(objIndex); if (info == NULL) return QString(); @@ -85,7 +214,7 @@ QString UAVObjectParser::getObjectName(int objIndex) */ quint32 UAVObjectParser::getObjectID(int objIndex) { - ObjectInfo* info = objInfo[objIndex]; + ObjectInfo* info = getObjectByIndex(objIndex); if (info == NULL) return 0; return info->id; @@ -96,7 +225,9 @@ quint32 UAVObjectParser::getObjectID(int objIndex) */ int UAVObjectParser::getNumBytes(int objIndex) { - ObjectInfo* info = objInfo[objIndex]; + ObjectInfo* info = getObjectByIndex(objIndex); + if (info == NULL) + return 0; return info->numBytes; } @@ -160,7 +291,7 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) QDomNode node = docElement.firstChild(); while ( !node.isNull() ) { // Create new object entry - ObjectInfo* info = new ObjectInfo; + ObjectInfo* info = new ObjectInfo(); info->filename=filename; // Process object attributes @@ -270,12 +401,14 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) return genErrorMsg(filename, "missing or duplicate description element", node.lineNumber(), node.columnNumber()); - // Calculate ID - calculateID(info); - // Calculate size calculateSize(info); + // Check size against max allowed + if(info->numBytes > UAVO_MAX_SIZE) + return genErrorMsg(filename, QString("total object size(%1 bytes) exceeds maximum limit (%2 bytes)") + .arg(QString::number(info->numBytes), QString::number(UAVO_MAX_SIZE)), 0, 0); + // Add object objInfo.append(info); @@ -288,6 +421,30 @@ QString UAVObjectParser::parseXML(QString& xml, QString& filename) return QString(); } +int UAVObjectParser::findOptionIndex(FieldInfo *field, quint32 inputIdx) { + if (!field->parent) { + return inputIdx; + } + + // Walk up inheritance tree. + FieldInfo *root = field->parent; + + while (root->parent) { + root = root->parent; + } + + QString& optionName = field->options[inputIdx]; + + QStringList options = root->options; + for (int m = 0; m < options.length(); m++) { + if (optionName == options[m]) { + return m; + } + } + + return -1; +} + /** * Calculate the unique object ID based on the object information. * The ID will change if the object definition changes, this is intentional @@ -308,8 +465,22 @@ void UAVObjectParser::calculateID(ObjectInfo* info) hash = updateHash(info->fields[n]->type, hash); if(info->fields[n]->type == FIELDTYPE_ENUM) { QStringList options = info->fields[n]->options; - for (int m = 0; m < options.length(); m++) + int nextIdx = 0; + + for (int m = 0; m < options.length(); m++) { + int idx = findOptionIndex(info->fields[n], m); + + if (idx < 0) abort(); + + // Not contiguous options. Update with next value. + if (idx != nextIdx) { + hash = updateHash((quint32) idx, hash); + } + + nextIdx = idx+1; + hash = updateHash(options[m], hash); + } } } // Done @@ -421,7 +592,7 @@ QString UAVObjectParser::processObjectAccess(QDomNode& childNode, ObjectInfo* in QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* info) { // Create field - FieldInfo* field = new FieldInfo; + FieldInfo* field = new FieldInfo(); // Get name attribute QDomNamedNodeMap elemAttributes = childNode.attributes(); QDomNode elemAttr = elemAttributes.namedItem("name"); @@ -532,6 +703,10 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in } // Get options attribute or child elements (only if an enum type) if (field->type == FIELDTYPE_ENUM) { + elemAttr = elemAttributes.namedItem("parent"); + if (!elemAttr.isNull()) { + field->parentName = elemAttr.nodeValue().trimmed(); + } // Look for options attribute elemAttr = elemAttributes.namedItem("options"); @@ -555,7 +730,7 @@ QString UAVObjectParser::processObjectFields(QDomNode& childNode, ObjectInfo* in } } } - if (field->options.length() == 0) { + if ((field->options.isEmpty()) && (field->parentName.isEmpty())) { return QString("Object:field:options attribute/element is missing"); } } diff --git a/ground/uavobjgenerator/uavobjectparser.h b/ground/uavobjgenerator/uavobjectparser.h index e6133d5a567..674a7581058 100644 --- a/ground/uavobjgenerator/uavobjectparser.h +++ b/ground/uavobjgenerator/uavobjectparser.h @@ -30,11 +30,19 @@ #include #include #include +#include #include #include #include #include +/** + * The maximum size of UAVOs is limited by the FlashFS filesystem in the flight code + * The flash slot size is 256 bytes which is comprised of the FlashFS header (12 bytes) + * and the UAVO. This leaves a maximum of 244 bytes for the UAVO. + */ +#define UAVO_MAX_SIZE 244 + // Types typedef enum { FIELDTYPE_INT8 = 0, @@ -47,7 +55,10 @@ typedef enum { FIELDTYPE_ENUM } FieldType; -typedef struct { +typedef struct FieldInfo_s FieldInfo; +typedef struct ObjectInfo_s ObjectInfo; + +struct FieldInfo_s { QString name; QString units; FieldType type; @@ -55,10 +66,14 @@ typedef struct { int numBytes; QStringList elementNames; QStringList options; // for enums only + QString parentName; // optional, for enums only bool defaultElementNames; QStringList defaultValues; QString limitValues; -} FieldInfo; + + FieldInfo *parent; + ObjectInfo *parentObj; +}; /** * Object update mode @@ -76,8 +91,7 @@ typedef enum { ACCESS_READONLY = 1 } AccessMode; - -typedef struct { +struct ObjectInfo_s { QString name; QString namelc; /** name in lowercase */ QString filename; @@ -98,7 +112,8 @@ typedef struct { QString description; /** Description used for Doxygen **/ QString category; /** Description used for Doxygen **/ int numBytes; -} ObjectInfo; + QSet parents; +}; class UAVObjectParser { @@ -107,12 +122,18 @@ class UAVObjectParser // Functions UAVObjectParser(); QString parseXML(QString& xml, QString& filename); + QString resolveParents(); + void calculateAllIds(); int getNumObjects(); QList getObjectInfo(); QString getObjectName(int objIndex); quint32 getObjectID(int objIndex); ObjectInfo* getObjectByIndex(int objIndex); + ObjectInfo* getObjectByName(QString& name); + FieldInfo* getFieldByName(QString &name, ObjectInfo **objRet); + int findOptionIndex(FieldInfo *field, quint32 inputIdx); + int getNumBytes(int objIndex); QStringList all_units; @@ -127,7 +148,6 @@ class UAVObjectParser QString genErrorMsg(QString& fileName, QString errMsg, int errorLine, int errorCol); - QString processObjectAttributes(QDomNode& node, ObjectInfo* info); QString processObjectFields(QDomNode& childNode, ObjectInfo* info); QString processObjectAccess(QDomNode& childNode, ObjectInfo* info); @@ -138,6 +158,7 @@ class UAVObjectParser void calculateSize(ObjectInfo* info); quint32 updateHash(quint32 value, quint32 hash); quint32 updateHash(QString& value, quint32 hash); + int resolveFieldParent(ObjectInfo *item, FieldInfo *field); }; #endif // UAVOBJECTPARSER_H diff --git a/make/firmware-common.mk b/make/firmware-common.mk index 7b3847db18e..60be51a32af 100644 --- a/make/firmware-common.mk +++ b/make/firmware-common.mk @@ -1,6 +1,107 @@ +ifneq ($(NO_AUTO_UAVO),YES) + +# Common UAVOs to all targets: + +UAVOBJSRCFILENAMES += accels +UAVOBJSRCFILENAMES += firmwareiapobj +UAVOBJSRCFILENAMES += flightstatus +UAVOBJSRCFILENAMES += flighttelemetrystats +UAVOBJSRCFILENAMES += gcsreceiver +UAVOBJSRCFILENAMES += gcstelemetrystats +UAVOBJSRCFILENAMES += modulesettings +UAVOBJSRCFILENAMES += objectpersistence +UAVOBJSRCFILENAMES += receiveractivity +UAVOBJSRCFILENAMES += sessionmanaging +UAVOBJSRCFILENAMES += systemalarms +UAVOBJSRCFILENAMES += systemsettings +UAVOBJSRCFILENAMES += systemstats +UAVOBJSRCFILENAMES += taskinfo +UAVOBJSRCFILENAMES += watchdogstatus + +ifneq ($(UAVO_MINIMAL),YES) +# On all non-discovery board targets: + +UAVOBJSRCFILENAMES += accessorydesired +UAVOBJSRCFILENAMES += actuatorcommand +UAVOBJSRCFILENAMES += actuatordesired +UAVOBJSRCFILENAMES += actuatorsettings +UAVOBJSRCFILENAMES += airspeedactual +UAVOBJSRCFILENAMES += attitudeactual +UAVOBJSRCFILENAMES += attitudesettings +UAVOBJSRCFILENAMES += baroaltitude +UAVOBJSRCFILENAMES += cameradesired +UAVOBJSRCFILENAMES += camerastabsettings +UAVOBJSRCFILENAMES += fixedwingairspeeds +UAVOBJSRCFILENAMES += fixedwingpathfollowerstatus +UAVOBJSRCFILENAMES += flightbatterysettings +UAVOBJSRCFILENAMES += flightbatterystate +UAVOBJSRCFILENAMES += gpsposition +UAVOBJSRCFILENAMES += gpsvelocity +UAVOBJSRCFILENAMES += gyros +UAVOBJSRCFILENAMES += homelocation +UAVOBJSRCFILENAMES += manualcontrolcommand +UAVOBJSRCFILENAMES += manualcontrolsettings +UAVOBJSRCFILENAMES += mixersettings +UAVOBJSRCFILENAMES += mixerstatus +UAVOBJSRCFILENAMES += mwratesettings +UAVOBJSRCFILENAMES += pathdesired +UAVOBJSRCFILENAMES += pathstatus +UAVOBJSRCFILENAMES += poilocation +UAVOBJSRCFILENAMES += positionactual +UAVOBJSRCFILENAMES += ratedesired +UAVOBJSRCFILENAMES += sensorsettings +UAVOBJSRCFILENAMES += stabilizationdesired +UAVOBJSRCFILENAMES += stabilizationsettings +UAVOBJSRCFILENAMES += systemident +UAVOBJSRCFILENAMES += tabletinfo +UAVOBJSRCFILENAMES += trimangles +UAVOBJSRCFILENAMES += trimanglessettings +UAVOBJSRCFILENAMES += txpidsettings +UAVOBJSRCFILENAMES += ubloxinfo +UAVOBJSRCFILENAMES += velocityactual + +ifeq ($(UAVO_NAV),YES) +UAVOBJSRCFILENAMES += airspeedsettings +UAVOBJSRCFILENAMES += altitudeholddesired +UAVOBJSRCFILENAMES += altitudeholdsettings +UAVOBJSRCFILENAMES += baroairspeed +UAVOBJSRCFILENAMES += fixedwingpathfollowersettings +UAVOBJSRCFILENAMES += flightplancontrol +UAVOBJSRCFILENAMES += flightplansettings +UAVOBJSRCFILENAMES += flightplanstatus +UAVOBJSRCFILENAMES += gpssatellites +UAVOBJSRCFILENAMES += gpstime +UAVOBJSRCFILENAMES += gyrosbias +UAVOBJSRCFILENAMES += inssettings +UAVOBJSRCFILENAMES += insstate +UAVOBJSRCFILENAMES += loitercommand +UAVOBJSRCFILENAMES += magbias +UAVOBJSRCFILENAMES += magnetometer +UAVOBJSRCFILENAMES += nedaccel +UAVOBJSRCFILENAMES += nedposition +UAVOBJSRCFILENAMES += pathplannersettings +UAVOBJSRCFILENAMES += sonaraltitude +UAVOBJSRCFILENAMES += stateestimation +UAVOBJSRCFILENAMES += velocitydesired +UAVOBJSRCFILENAMES += vibrationanalysisoutput +UAVOBJSRCFILENAMES += vibrationanalysissettings +UAVOBJSRCFILENAMES += vtolpathfollowersettings +UAVOBJSRCFILENAMES += vtolpathfollowerstatus +UAVOBJSRCFILENAMES += waypoint +UAVOBJSRCFILENAMES += waypointactive +endif # UAVO_NAV + +endif # !UAVO_MINIMAL + +endif # !NO_AUTO_UAVO + # Define programs and commands. REMOVE = rm -f +SRC += $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),$(OPUAVSYNTHDIR)/$(UAVOBJSRCFILE).c ) + +CFLAGS += $(foreach UAVOBJSRCFILE,$(UAVOBJSRCFILENAMES),-DUAVOBJ_INIT_$(UAVOBJSRCFILE) ) + # List of all source files. ALLSRC = $(ASRC) $(SRC) $(CPPSRC) # List of all source files without directory and file-extension. @@ -15,7 +116,11 @@ DEPFILES = $(addprefix $(OUTDIR)/dep/, $(addsuffix .o.d, $(ALLSRCBASE))) # Default target. all: gccversion build -build: elf hex bin lss sym +build: elf + +ifneq ($(BUILD_FWFILES), NO) +build: hex bin lss sym +endif # Link: create ELF output file from object files. $(eval $(call LINK_TEMPLATE, $(OUTDIR)/$(TARGET).elf, $(ALLOBJ))) diff --git a/make/firmware-defs.mk b/make/firmware-defs.mk index 5c284719b14..f9a68a6c6c1 100644 --- a/make/firmware-defs.mk +++ b/make/firmware-defs.mk @@ -141,9 +141,12 @@ $(1).firmwareinfo.c: $(1) $(ROOT_DIR)/make/templates/firmwareinfotemplate.c FORC $(eval $(call COMPILE_C_TEMPLATE, $(1).firmwareinfo.c)) +# Hack to place Naze firmware info at correct location in flash TODO: fix properly +ifeq (,$(findstring naze32,$(TARGET))) $(OUTDIR)/$(notdir $(basename $(1))).tlfw : $(1) $(1).firmwareinfo.bin @echo $(MSG_TLFIRMWARE) $$(call toprel, $$@) $(V1) cat $(1) $(1).firmwareinfo.bin > $$@ +endif endef # Assemble: create object files from assembler source files. diff --git a/make/linux.mk b/make/linux.mk index 3e4643df923..91fd4b34dcc 100644 --- a/make/linux.mk +++ b/make/linux.mk @@ -9,7 +9,7 @@ # misc tools RM=rm -QT_SPEC=linux-g++ +QT_SPEC ?= linux-g++ # Check for and find Python 2 diff --git a/make/macosx.mk b/make/macosx.mk index 8584f71cdee..068e0229353 100644 --- a/make/macosx.mk +++ b/make/macosx.mk @@ -38,6 +38,6 @@ endif export PYTHON -QT_SPEC=macx-g++ +QT_SPEC ?= macx-g++ UAVOBJGENERATOR="$(BUILD_DIR)/ground/uavobjgenerator/uavobjgenerator" diff --git a/make/tools.mk b/make/tools.mk index e307a50d599..b3ad6c1b05b 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -22,13 +22,13 @@ ifdef OPENOCD_FTDI endif # Set up QT toolchain -QT_SDK_DIR := $(TOOLS_DIR)/Qt5.4.1 +QT_SDK_DIR := $(TOOLS_DIR)/Qt5.5.0 ifdef LINUX ifdef AMD64 - QT_PLUGINS_DIR = $(QT_SDK_DIR)/5.4/gcc_64/plugins + QT_PLUGINS_DIR = $(QT_SDK_DIR)/5.5/gcc_64/plugins else - QT_PLUGINS_DIR = $(QT_SDK_DIR)/5.4/gcc/plugins + QT_PLUGINS_DIR = $(QT_SDK_DIR)/5.5/gcc/plugins endif endif @@ -57,23 +57,25 @@ OPENOCD_FTDI ?= yes ifdef LINUX ifdef AMD64 # Linux 64-bit - qt_sdk_install: QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x64-5.4.1.run - QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.4/gcc_64/bin/qmake + qt_sdk_install: QT_SDK_URL := http://download.qt.io/official_releases/qt/5.5/5.5.0/qt-opensource-linux-x64-5.5.0-2.run + QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.5/gcc_64/bin/qmake else # Linux 32-bit - qt_sdk_install: QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.1/qt-opensource-linux-x86-5.4.1.run - QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.4/gcc/bin/qmake + qt_sdk_install: QT_SDK_URL := http://download.qt.io/official_releases/qt/5.5/5.5.0/qt-opensource-linux-x86-5.5.0.run + QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.5/gcc/bin/qmake endif endif ifdef MACOSX - qt_sdk_install: QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.1/qt-opensource-mac-x64-clang-5.4.1.dmg - QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.4/clang_64/bin/qmake + qt_sdk_install: QT_SDK_URL := http://download.qt.io/official_releases/qt/5.5/5.5.0/qt-opensource-mac-x64-clang-5.5.0.dmg + QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.5/clang_64/bin/qmake + + export QT_SDK_BIN_PATH := $(QT_SDK_DIR)/5.5/clang_64/bin endif ifdef WINDOWS - qt_sdk_install: QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.4/5.4.1/qt-opensource-windows-x86-mingw491_opengl-5.4.1.exe - QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.4/mingw491_32/bin/qmake + qt_sdk_install: QT_SDK_URL := http://download.qt.io/official_releases/qt/5.5/5.5.0/qt-opensource-windows-x86-mingw492-5.5.0.exe + QT_SDK_QMAKE_PATH := $(QT_SDK_DIR)/5.5/mingw492_32/bin/qmake endif qt_sdk_install: QT_SDK_FILE := $(notdir $(QT_SDK_URL)) @@ -93,18 +95,18 @@ qt_sdk_install: qt_sdk_clean ifneq (,$(filter $(UNAME), Darwin)) $(V1) hdiutil attach -quiet -private -mountpoint /tmp/qt-installer "$(DL_DIR)/$(QT_SDK_FILE)" - $(V1) /tmp/qt-installer/qt-opensource-mac-x64-clang-5.4.1.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.4.1 + $(V1) /tmp/qt-installer/qt-opensource-mac-x64-clang-5.5.0.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.5.0 $(V1) hdiutil detach -quiet /tmp/qt-installer endif - + ifneq (,$(filter $(UNAME), Linux)) #installer is an executable, make it executable and run it $(V1) chmod u+x "$(DL_DIR)/$(QT_SDK_FILE)" - $(V1) "$(DL_DIR)/$(QT_SDK_FILE)" -style cleanlooks + $(V1) "$(DL_DIR)/$(QT_SDK_FILE)" endif ifdef WINDOWS - $(V1) ./downloads/qt-opensource-windows-x86-mingw491_opengl-5.4.1.exe + $(V1) ./downloads/qt-opensource-windows-x86-mingw492-5.5.0.exe endif .PHONY: qt_sdk_clean @@ -124,18 +126,23 @@ ifdef MACOSX endif ifdef WINDOWS - arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q1-update/+download/gcc-arm-none-eabi-4_9-2015q1-20150306-win32.zip + arm_sdk_install: ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.9/4.9-2015-q1-update/+download/gcc-arm-none-eabi-4_9-2015q1-20150306-win32.zip endif arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL)) # order-only prereq on directory existance: arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR) arm_sdk_install: arm_sdk_clean +ifneq ($(OSFAMILY), windows) # download the source only if it's newer than what we already have $(V1) wget --no-check-certificate -N -P "$(DL_DIR)" "$(ARM_SDK_URL)" # binary only release so just extract it $(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)" +else + $(V1) curl -L -k -o "$(DL_DIR)/$(ARM_SDK_FILE)" "$(ARM_SDK_URL)" + $(V1) unzip -q -d $(ARM_SDK_DIR) "$(DL_DIR)/$(ARM_SDK_FILE)" +endif .PHONY: arm_sdk_clean arm_sdk_clean: @@ -512,7 +519,7 @@ ifeq ($(shell [ -d "$(QT_SDK_DIR)" ] && echo "exists"), exists) QMAKE = $(QT_SDK_QMAKE_PATH) ifdef WINDOWS # Windows needs to be told where to find Qt libraries - export PATH := $(QT_SDK_DIR)/5.4/mingw491_32/bin:$(PATH) + export PATH := $(QT_SDK_DIR)/5.5/mingw492_32/bin:$(PATH) endif else # not installed, hope it's in the path... @@ -522,6 +529,9 @@ endif ifeq ($(shell [ -d "$(ARM_SDK_DIR)" ] && echo "exists"), exists) ARM_SDK_PREFIX := $(ARM_SDK_DIR)/bin/arm-none-eabi- else + ifneq ($(MAKECMDGOALS),arm_sdk_install) + $(info **WARNING** ARM-SDK not in $(ARM_SDK_DIR) Please run 'make arm_sdk_install') + endif # not installed, hope it's in the path... ARM_SDK_PREFIX ?= arm-none-eabi- endif @@ -556,7 +566,7 @@ endif # OPENSSL download URL ifdef WINDOWS openssl_install: OPENSSL_URL := http://slproweb.com/download/Win32OpenSSL-1_0_2c.exe - + openssl_install: OPENSSL_FILE := $(notdir $(OPENSSL_URL)) OPENSSL_DIR = $(TOOLS_DIR)/win32openssl # order-only prereq on directory existance: diff --git a/make/windows.mk b/make/windows.mk index 657e81e98f9..da1470d2294 100644 --- a/make/windows.mk +++ b/make/windows.mk @@ -18,7 +18,7 @@ RM=rm PYTHON := python export PYTHON -QT_SPEC := win32-g++ +QT_SPEC ?= win32-g++ # this might need to switch on debug/release UAVOBJGENERATOR := "$(BUILD_DIR)/ground/uavobjgenerator/debug/uavobjgenerator.exe" diff --git a/package/Makefile b/package/Makefile index 28b91dde318..c341b307d6e 100644 --- a/package/Makefile +++ b/package/Makefile @@ -45,12 +45,18 @@ CLEAN_FLIGHT := YES endif # Set up targets -ALL_BOARDS := coptercontrol pipxtreme revolution revomini sparky sparky2 sparkybgc freedom quanton colibri flyingf3 flyingf4 +ALL_BOARDS := coptercontrol pipxtreme revomini sparky sparky2 sparkybgc quanton colibri flyingf3 flyingf4 aq32 naze32 ALL_BOARDS_BU := coptercontrol pipxtreme -FW_TARGETS := $(addprefix fw_, $(ALL_BOARDS)) -FW_TARGETS_TOOLS := $(addprefix fw_, $(ALL_BOARDS)) -BL_TARGETS := $(addprefix bl_, $(ALL_BOARDS)) -BU_TARGETS := $(addprefix bu_, $(ALL_BOARDS_BU)) + +FW_BOARDS := $(ALL_BOARDS) +BL_BOARDS := $(filter-out naze32, $(ALL_BOARDS)) +BU_BOARDS := $(ALL_BOARDS_BU) +EF_BOARDS := $(filter-out naze32, $(ALL_BOARDS)) + +FW_TARGETS := $(addprefix fw_, $(FW_BOARDS)) +FW_TARGETS_TOOLS := $(addprefix fw_, $(FW_BOARDS)) +BL_TARGETS := $(addprefix bl_, $(BL_BOARDS)) +BU_TARGETS := $(addprefix bu_, $(BU_BOARDS)) help: @echo diff --git a/package/Makefile.linux b/package/Makefile.linux index 20e8eb8cd01..57be26149a2 100644 --- a/package/Makefile.linux +++ b/package/Makefile.linux @@ -13,7 +13,7 @@ endef VERNUM := 0.1.0 VERSION_FULL := $(VERNUM)-$(PACKAGE_LBL) -FLIGHT_FW := coptercontrol revolution sparky sparky2 sparkybgc freedom revomini pipxtreme quanton flyingf3 +FLIGHT_FW := coptercontrol sparky sparky2 sparkybgc revomini pipxtreme quanton flyingf3 naze32 aq32 DEB_BUILD_DIR := $(ROOT_DIR)/debian @@ -40,7 +40,7 @@ ALL_DEB_FILES += $(foreach f, $(DEB_MACHINE_FILES), $(DEB_BUILD_DIR)/$(f)) DEB_PACKAGE_NAME := taulabs_$(VERSION_FULL)_$(DEB_PLATFORM) -QT_PLUGINS_USED :=imageformats platforms sqldrivers +QT_PLUGINS_USED := imageformats platforms sqldrivers xcbglintegrations standalone: gcs @echo $@ starting @@ -50,6 +50,7 @@ standalone: gcs $(V1)cp -v -R $(QT_PLUGINS_DIR)/platforms $(ROOT_DIR)/build/ground/gcs/lib/taulabs/qtplugins/ $(V1) mkdir -p "$(ROOT_DIR)/build/ground/gcs/lib/taulabs/qtplugins/sqldrivers" $(V1)cp -v -R $(QT_PLUGINS_DIR)/sqldrivers/libqsqlite.so $(ROOT_DIR)/build/ground/gcs/lib/taulabs/qtplugins/sqldrivers + $(V1)cp -v -R $(QT_PLUGINS_DIR)/xcbglintegrations $(ROOT_DIR)/build/ground/gcs/lib/taulabs/qtplugins/ $(V1) mkdir -p "$(ROOT_DIR)/build/ground/gcs/lib/taulabs/qml" $(V1)cp -v -R $(QT_PLUGINS_DIR)/../qml/QtQuick.2 $(ROOT_DIR)/build/ground/gcs/lib/taulabs/qml/ $(V1)cp -v -R $(QT_PLUGINS_DIR)/../qml/QtQuick $(ROOT_DIR)/build/ground/gcs/lib/taulabs/qml/ diff --git a/package/linux/deb_common/taulabs.udev b/package/linux/deb_common/taulabs.udev index 65f38b11428..1e89d6006cf 100644 --- a/package/linux/deb_common/taulabs.udev +++ b/package/linux/deb_common/taulabs.udev @@ -56,3 +56,10 @@ SUBSYSTEM=="usb", ATTRS{idVendor}=="0483", ATTRS{idProduct}=="df11", MODE="0664" SUBSYSTEM=="usb", ATTRS{idVendor}=="0403", ATTRS{idProduct}=="6010", MODE="0664", GROUP="plugdev" # Olimex Ltd. OpenOCD JTAG TINY SUBSYSTEM=="usb", ATTRS{idVendor}=="15ba", ATTRS{idProduct}=="0004", MODE="0664", GROUP="plugdev" + +# +# AeroQuad +# + +# AeroQuad AQ32 flight controller board +SUBSYSTEM=="usb", ATTRS{idVendor}=="20a0", ATTRS{idProduct}=="4284", MODE="0664", GROUP="plugdev" \ No newline at end of file diff --git a/package/osx/libraries b/package/osx/libraries index 4a5c6aa198b..f96b4a8ffa0 100755 --- a/package/osx/libraries +++ b/package/osx/libraries @@ -1,50 +1,31 @@ -#!/usr/bin/env bash +#!/usr/bin/env bash -e -v APP="${1?}" PLUGINS="${APP}/Contents/Plugins" -QT_DIR=$(otool -L "${APP}/Contents/MacOS/Tau Labs GCS" | sed -n -e 's/\/QtCore\.framework.*//p' | sed -n -E 's:^.::p') # Specify a list of all the qml directories that need imports QMLDIR="${APP}/Contents/Resources/welcome" # macdeployqt will copy all the Qt5 binaries to the app bundle and relink as appropriate -echo "Running \"${QT_DIR}/../bin/macdeployqt\" \"${APP}\" -verbose=2 -no-strip -always-overwrite -qmldir=\"$QMLDIR"\" -"${QT_DIR}/../bin/macdeployqt" "${APP}" -verbose=2 -no-strip -always-overwrite -qmldir="$QMLDIR" -# HACK/WORKAROUND: XXX TODO: QTBUG-42954 -# https://bugreports.qt.io/browse/QTBUG-42954 -# Fixed (supposedly) in QT 5.4.2 -# libqtquick2plugin is ending up as invalid symbolic link in macdeployqt. -# fix up manually-- just copy lib, it's small. (remove once we used fixed QT) -rm -f "${APP}/Contents/Resources/qml/QtQuick.2/libqtquick2plugin.dylib" -cp "${APP}/Contents/Plugins/quick/libqtquick2plugin.dylib" "${APP}/Contents/Resources/qml/QtQuick.2/libqtquick2plugin.dylib" +#pushd/popd: workaround QTBUG-46404 -- need to be next to macdeployqt's path -rm -f "${APP}/Contents/Resources/qml/QtQuick/XmlListModel/libqmlxmllistmodelplugin.dylib" -cp "${APP}/Contents/Plugins/quick/libqmlxmllistmodelplugin.dylib" "${APP}/Contents/Resources/qml/QtQuick/XmlListModel/libqmlxmllistmodelplugin.dylib" +pushd "${QT_SDK_BIN_PATH}" + +./macdeployqt "${APP}" -verbose=2 -no-strip -always-overwrite -qmldir="$QMLDIR" + +popd # Copy SDL files echo "Copying SDL" cp -r "/Library/Frameworks/SDL.framework" "${APP}/Contents/Frameworks/" +# these are optional echo "Changing package identification of SDL" install_name_tool -id \ @executable_path/../Frameworks/SDL.framework/SDL \ - "${APP}/Contents/Frameworks/SDL.framework/SDL" + "${APP}/Contents/Frameworks/SDL.framework/SDL" || true install_name_tool -change \ @rpath/SDL.framework/Versions/A/SDL \ "@executable_path/../Frameworks/SDL.framework/SDL" \ - "${APP}/Contents/Plugins/libsdlgamepad.1.dylib" - -# Copy OSG files -OSG_EXTRA="libosgViewer.90.dylib" -echo "Copying OSG libraries" -for f in ${OSG_EXTRA} -do - echo "Copying library ${f} - cp /usr/local/lib/{$f} "${APP}/Contents/Plugins/${f}" - echo "Changing package identification of ${f} - install_name_tool -id \ - @executable_path/../Frameworks/SDL.framework/Versions/A/SDL \ - "${APP}/Contents/Frameworks/SDL.framework/Versions/A/SDL" -done - + "${APP}/Contents/Plugins/libsdlgamepad.1.dylib" || true diff --git a/package/osx/package b/package/osx/package index 147d3cbbaef..699058a9891 100755 --- a/package/osx/package +++ b/package/osx/package @@ -29,16 +29,16 @@ mkdir "/Volumes/${VOL_NAME}/Utilities" cp -r "${APP_PATH}/${APP_NAME}" "/Volumes/${VOL_NAME}" cp "${FW_DIR}/fw_quanton-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_colibri-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" -cp "${FW_DIR}/fw_freedom-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_flyingf3-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_flyingf4-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_coptercontrol-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_revomini-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_pipxtreme-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" -cp "${FW_DIR}/fw_revolution-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_sparky-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_sparkybgc-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${FW_DIR}/fw_sparky2-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" +cp "${FW_DIR}/fw_naze32-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" +cp "${FW_DIR}/fw_aq32-${PACKAGE_LBL}.tlfw" "/Volumes/${VOL_NAME}/Firmware" cp "${BUILD_DIR}/matlab/LogConvert.m" "/Volumes/${VOL_NAME}/Utilities/LogConvert-${PACKAGE_LBL}.m" diff --git a/package/winx86/taulabs.nsi b/package/winx86/taulabs.nsi index 26a618706ec..f5fff0dff83 100644 --- a/package/winx86/taulabs.nsi +++ b/package/winx86/taulabs.nsi @@ -213,12 +213,12 @@ Section "Firmware" InSecFirmware File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_flyingf4-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_quanton-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_colibri-${PACKAGE_LBL}.tlfw" - File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_freedom-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_sparky-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_sparkybgc-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_sparky2-${PACKAGE_LBL}.tlfw" - File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_revolution-${PACKAGE_LBL}.tlfw" File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_revomini-${PACKAGE_LBL}.tlfw" + File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_naze32-${PACKAGE_LBL}.tlfw" + File "${PACKAGE_DIR}\${FIRMWARE_DIR}\fw_aq32-${PACKAGE_LBL}.tlfw" SectionEnd ; Copy utility files diff --git a/python/doiap.py b/python/doiap.py new file mode 100755 index 00000000000..6f9c5121359 --- /dev/null +++ b/python/doiap.py @@ -0,0 +1,35 @@ +#!/usr/bin/python -B + +import sys, time +from taulabs import telemetry + +def main(): + t = telemetry.get_telemetry_by_args(service_in_iter=False, iter_blocks=False) + t.start_thread() + + magic_value=1122 + + from taulabs.uavo import UAVO_FirmwareIAPObj + + t.request_object(UAVO_FirmwareIAPObj) + + time.sleep(0.9) + + for i in range(3): + print magic_value + f=UAVO_FirmwareIAPObj._make_to_send(Command=magic_value, + Description=(0,)*100, + CPUSerial=(0,)*12, + BoardRevision=0, + BoardType=0, + ArmReset=0, + crc=0) + + magic_value += 1111 + + t.send_object(f) + time.sleep(0.9) + +#------------------------------------------------------------------------------- +if __name__ == "__main__": + main() diff --git a/python/minimal_connection.py b/python/minimal_connection.py index 20a862d8598..bf19f690c58 100755 --- a/python/minimal_connection.py +++ b/python/minimal_connection.py @@ -20,20 +20,7 @@ #------------------------------------------------------------------------------- def main(): - # Setup the command line arguments. - parser = argparse.ArgumentParser(usage = USAGE, description = DESC) - - parser.add_argument("-g", "--githash", - action = "store", - dest = "githash", - help = "override githash for UAVO XML definitions") - - # Parse the command-line. - args = parser.parse_args() - - githash = args.githash - - tStream = telemetry.NetworkTelemetry(service_in_iter=False) + tStream = telemetry.get_telemetry_by_args(service_in_iter=False) tStream.start_thread() settings_objects = tStream.uavo_defs.get_settings_objects() diff --git a/python/taulabs/telemetry.py b/python/taulabs/telemetry.py index 2042f40398e..5085ef75031 100644 --- a/python/taulabs/telemetry.py +++ b/python/taulabs/telemetry.py @@ -146,6 +146,9 @@ def __iter__(self): def __make_handshake(self, handshake): return uavo.UAVO_GCSTelemetryStats._make_to_send(0, 0, 0, 0, 0, handshake) + def send_object(self, obj): + self._send(uavtalk.send_object(obj)) + def __handle_handshake(self, obj): if obj.name == "UAVO_FlightTelemetryStats": # Handle the telemetry handshaking @@ -164,7 +167,7 @@ def __handle_handshake(self, obj): print "Connected" send_obj = self.__make_handshake(CONNECTED) - self._send(uavtalk.send_object(send_obj)) + self.send_object(send_obj) def request_object(self, obj): if not self.do_handshaking: @@ -384,9 +387,9 @@ def __init__(self, port, speed=115200, *args, **kwargs): import serial - ser = serial.Serial(port, speed) + self.ser = serial.Serial(port, speed) - FDTelemetry.__init__(self, fd=ser.fileno(), *args, **kwargs) + FDTelemetry.__init__(self, fd=self.ser.fileno(), *args, **kwargs) class FileTelemetry(TelemetryBase): """ Telemetry interface to data in a file """ @@ -444,7 +447,8 @@ def _receive(self, finish_time): return buf -def get_telemetry_by_args(desc="Process telemetry"): +def get_telemetry_by_args(desc="Process telemetry", service_in_iter=True, + iter_blocks=True): """ Parses command line to decide how to get a telemetry object. """ # Setup the command line arguments. import argparse @@ -492,7 +496,8 @@ def get_telemetry_by_args(desc="Process telemetry"): from taulabs import telemetry if args.serial: - return telemetry.SerialTelemetry(args.source, speed=args.baud) + return telemetry.SerialTelemetry(args.source, speed=args.baud, + service_in_iter=service_in_iter, iter_blocks=iter_blocks) if args.baud is not None: parser.print_help() @@ -515,4 +520,5 @@ def get_telemetry_by_args(desc="Process telemetry"): parser.print_help() raise ValueError("Target doesn't exist and isn't a network address") - return telemetry.NetworkTelemetry(host=host, port=int(port), name=args.source) + return telemetry.NetworkTelemetry(host=host, port=int(port), name=args.source, + service_in_iter=service_in_iter, iter_blocks=iter_blocks) diff --git a/python/taulabs/uavo.py b/python/taulabs/uavo.py index be6f774eb46..70721e719c8 100644 --- a/python/taulabs/uavo.py +++ b/python/taulabs/uavo.py @@ -20,7 +20,7 @@ class UAVTupleClass(): """ This is the prototype for a class that contains a uav object. """ @classmethod - def _make_to_send(cls, *args): + def _make_to_send(cls, *args, **kwargs): """ Accepts all the uavo fields and creates an object. The object is dated as of the current time, and has the name and id @@ -28,7 +28,7 @@ def _make_to_send(cls, *args): """ import time - return cls(cls._name, round(time.time() * 1000), cls._id, *args) + return cls(cls._name, round(time.time() * 1000), cls._id, *args, **kwargs) def to_bytes(self): """ Serializes this object into a byte stream. """ diff --git a/shared/api/physical_constants.h b/shared/api/physical_constants.h index 561e0c8b776..90183e54719 100644 --- a/shared/api/physical_constants.h +++ b/shared/api/physical_constants.h @@ -41,6 +41,10 @@ #define RAD2DEG (180.0f / PI) #endif +#ifndef M_PI +#define M_PI PI +#endif + // Temperature and pressure conversions #define CELSIUS2KELVIN 273.15f #define INCHES_MERCURY2KPA 3.386f diff --git a/shared/uavobjectdefinition/altitudeholdsettings.xml b/shared/uavobjectdefinition/altitudeholdsettings.xml index 2a8344081e9..4b28e431596 100644 --- a/shared/uavobjectdefinition/altitudeholdsettings.xml +++ b/shared/uavobjectdefinition/altitudeholdsettings.xml @@ -7,7 +7,7 @@ - + diff --git a/shared/uavobjectdefinition/attitudesettings.xml b/shared/uavobjectdefinition/attitudesettings.xml index 23c6e79bfcf..2e16673a624 100644 --- a/shared/uavobjectdefinition/attitudesettings.xml +++ b/shared/uavobjectdefinition/attitudesettings.xml @@ -12,7 +12,6 @@ - diff --git a/shared/uavobjectdefinition/fixedwingpathfollowersettingscc.xml b/shared/uavobjectdefinition/fixedwingpathfollowersettingscc.xml deleted file mode 100644 index 735687c7368..00000000000 --- a/shared/uavobjectdefinition/fixedwingpathfollowersettingscc.xml +++ /dev/null @@ -1,48 +0,0 @@ - - - Settings for the @ref FixedWingPathFollowerModule - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/flightstatus.xml b/shared/uavobjectdefinition/flightstatus.xml index b378e638754..ae108b360c8 100644 --- a/shared/uavobjectdefinition/flightstatus.xml +++ b/shared/uavobjectdefinition/flightstatus.xml @@ -22,6 +22,7 @@ + diff --git a/shared/uavobjectdefinition/gpsposition.xml b/shared/uavobjectdefinition/gpsposition.xml index 31af1a8dacb..e85d5d0bc1b 100644 --- a/shared/uavobjectdefinition/gpsposition.xml +++ b/shared/uavobjectdefinition/gpsposition.xml @@ -8,7 +8,7 @@ - + diff --git a/shared/uavobjectdefinition/hwaq32.xml b/shared/uavobjectdefinition/hwaq32.xml new file mode 100644 index 00000000000..150f3fa8a41 --- /dev/null +++ b/shared/uavobjectdefinition/hwaq32.xml @@ -0,0 +1,114 @@ + + + Selection of optional hardware configurations. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/hwcolibri.xml b/shared/uavobjectdefinition/hwcolibri.xml index e36e25d096c..5eddbf59a4d 100644 --- a/shared/uavobjectdefinition/hwcolibri.xml +++ b/shared/uavobjectdefinition/hwcolibri.xml @@ -5,7 +5,7 @@ - + @@ -25,12 +25,12 @@ - + - + @@ -45,7 +45,7 @@ - + @@ -65,7 +65,7 @@ - + @@ -84,10 +84,10 @@ - - + + - + @@ -95,7 +95,7 @@ - + diff --git a/shared/uavobjectdefinition/hwcoptercontrol.xml b/shared/uavobjectdefinition/hwcoptercontrol.xml index 2dfccf8bbb6..a9390cf170b 100644 --- a/shared/uavobjectdefinition/hwcoptercontrol.xml +++ b/shared/uavobjectdefinition/hwcoptercontrol.xml @@ -2,14 +2,14 @@ Selection of optional hardware configurations. - - - + + + - - + + - + diff --git a/shared/uavobjectdefinition/hwdiscoveryf4.xml b/shared/uavobjectdefinition/hwdiscoveryf4.xml index d953141213b..778c1a832e8 100644 --- a/shared/uavobjectdefinition/hwdiscoveryf4.xml +++ b/shared/uavobjectdefinition/hwdiscoveryf4.xml @@ -2,10 +2,10 @@ Selection of optional hardware configurations. - + - - + + diff --git a/shared/uavobjectdefinition/hwflyingf3.xml b/shared/uavobjectdefinition/hwflyingf3.xml index 564892a3afc..2f7626ebdd5 100644 --- a/shared/uavobjectdefinition/hwflyingf3.xml +++ b/shared/uavobjectdefinition/hwflyingf3.xml @@ -3,7 +3,7 @@ Selection of optional hardware configurations. - + @@ -23,7 +23,7 @@ - + @@ -43,7 +43,7 @@ - + @@ -63,7 +63,7 @@ - + @@ -83,7 +83,7 @@ - + @@ -103,10 +103,10 @@ - - + + - + diff --git a/shared/uavobjectdefinition/hwflyingf4.xml b/shared/uavobjectdefinition/hwflyingf4.xml index af014088be9..b0ed9243900 100644 --- a/shared/uavobjectdefinition/hwflyingf4.xml +++ b/shared/uavobjectdefinition/hwflyingf4.xml @@ -4,7 +4,7 @@ - + @@ -16,7 +16,7 @@ - + @@ -35,7 +35,7 @@ - + @@ -54,24 +54,24 @@ - + - + - - + + - + @@ -79,7 +79,7 @@ - + diff --git a/shared/uavobjectdefinition/hwfreedom.xml b/shared/uavobjectdefinition/hwfreedom.xml deleted file mode 100644 index 05e56d90770..00000000000 --- a/shared/uavobjectdefinition/hwfreedom.xml +++ /dev/null @@ -1,85 +0,0 @@ - - - Selection of optional hardware configurations. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/hwnaze.xml b/shared/uavobjectdefinition/hwnaze.xml new file mode 100644 index 00000000000..a86e0b74a8b --- /dev/null +++ b/shared/uavobjectdefinition/hwnaze.xml @@ -0,0 +1,20 @@ + + + Selection of optional hardware configurations. + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/hwquanton.xml b/shared/uavobjectdefinition/hwquanton.xml index 5438dda08e4..537374c6de2 100644 --- a/shared/uavobjectdefinition/hwquanton.xml +++ b/shared/uavobjectdefinition/hwquanton.xml @@ -4,7 +4,7 @@ - + @@ -25,12 +25,12 @@ - + - + @@ -46,7 +46,7 @@ - + @@ -67,7 +67,7 @@ - + @@ -87,7 +87,7 @@ - + @@ -107,10 +107,10 @@ - - + + - + @@ -118,7 +118,7 @@ - + diff --git a/shared/uavobjectdefinition/hwrevolution.xml b/shared/uavobjectdefinition/hwrevolution.xml deleted file mode 100644 index 124f1bc5e68..00000000000 --- a/shared/uavobjectdefinition/hwrevolution.xml +++ /dev/null @@ -1,72 +0,0 @@ - - - Selection of optional hardware configurations. - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/hwrevomini.xml b/shared/uavobjectdefinition/hwrevomini.xml index 6862a432a18..94554f7709f 100644 --- a/shared/uavobjectdefinition/hwrevomini.xml +++ b/shared/uavobjectdefinition/hwrevomini.xml @@ -12,7 +12,7 @@ - + @@ -32,7 +32,7 @@ - + @@ -53,16 +53,16 @@ - - + + - + - + diff --git a/shared/uavobjectdefinition/hwshared.xml b/shared/uavobjectdefinition/hwshared.xml new file mode 100644 index 00000000000..852f5184a2b --- /dev/null +++ b/shared/uavobjectdefinition/hwshared.xml @@ -0,0 +1,43 @@ + + + Templates for common enums. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/shared/uavobjectdefinition/hwsparky.xml b/shared/uavobjectdefinition/hwsparky.xml index 4307fc0a619..f8ad6d785ca 100644 --- a/shared/uavobjectdefinition/hwsparky.xml +++ b/shared/uavobjectdefinition/hwsparky.xml @@ -2,7 +2,7 @@ Selection of optional hardware configurations. - + @@ -13,7 +13,7 @@ - + @@ -32,7 +32,7 @@ - + @@ -60,10 +60,10 @@ - - + + - + @@ -71,7 +71,7 @@ - + diff --git a/shared/uavobjectdefinition/hwsparky2.xml b/shared/uavobjectdefinition/hwsparky2.xml index cef62543c94..5b159265fa8 100644 --- a/shared/uavobjectdefinition/hwsparky2.xml +++ b/shared/uavobjectdefinition/hwsparky2.xml @@ -2,7 +2,7 @@ Selection of optional hardware configurations. - + @@ -15,7 +15,7 @@ - + @@ -34,7 +34,7 @@ - + @@ -55,35 +55,31 @@ - - + + - + - - - - - + - - + + - + - + diff --git a/shared/uavobjectdefinition/hwsparkybgc.xml b/shared/uavobjectdefinition/hwsparkybgc.xml index d062484033c..4b3218f0c89 100644 --- a/shared/uavobjectdefinition/hwsparkybgc.xml +++ b/shared/uavobjectdefinition/hwsparkybgc.xml @@ -2,7 +2,7 @@ Selection of optional hardware configurations. - + @@ -13,7 +13,7 @@ - + @@ -31,10 +31,10 @@ - - + + - + diff --git a/shared/uavobjectdefinition/hwtaulink.xml b/shared/uavobjectdefinition/hwtaulink.xml index d5a30047322..1350b198c8e 100644 --- a/shared/uavobjectdefinition/hwtaulink.xml +++ b/shared/uavobjectdefinition/hwtaulink.xml @@ -6,20 +6,21 @@ - + - + + - - - + + + - - + + diff --git a/shared/uavobjectdefinition/inssettings.xml b/shared/uavobjectdefinition/inssettings.xml index 8546dc132bd..2a55d83caba 100644 --- a/shared/uavobjectdefinition/inssettings.xml +++ b/shared/uavobjectdefinition/inssettings.xml @@ -6,7 +6,7 @@ - + diff --git a/shared/uavobjectdefinition/loitercommand.xml b/shared/uavobjectdefinition/loitercommand.xml index e65e2f32360..8d8780d1436 100644 --- a/shared/uavobjectdefinition/loitercommand.xml +++ b/shared/uavobjectdefinition/loitercommand.xml @@ -1,9 +1,9 @@ Requested movement while in loiter mode - - - + + + diff --git a/shared/uavobjectdefinition/manualcontrolsettings.xml b/shared/uavobjectdefinition/manualcontrolsettings.xml index b0c3aefafea..cc06a8af04f 100644 --- a/shared/uavobjectdefinition/manualcontrolsettings.xml +++ b/shared/uavobjectdefinition/manualcontrolsettings.xml @@ -19,9 +19,7 @@ - - - + @@ -30,7 +28,7 @@ - + @@ -124,13 +122,13 @@ - - - + + + - + diff --git a/shared/uavobjectdefinition/modulesettings.xml b/shared/uavobjectdefinition/modulesettings.xml index 0765a37ed22..fd7fc5e857b 100644 --- a/shared/uavobjectdefinition/modulesettings.xml +++ b/shared/uavobjectdefinition/modulesettings.xml @@ -92,6 +92,8 @@ + + diff --git a/shared/uavobjectdefinition/oplinksettings.xml b/shared/uavobjectdefinition/oplinksettings.xml deleted file mode 100644 index 5c8f5680710..00000000000 --- a/shared/uavobjectdefinition/oplinksettings.xml +++ /dev/null @@ -1,23 +0,0 @@ - - - OPLink configurations options. - - - - - - - - - - - - - - - - - - - - diff --git a/shared/uavobjectdefinition/receiveractivity.xml b/shared/uavobjectdefinition/receiveractivity.xml index 8173a97642f..88f202b38f0 100644 --- a/shared/uavobjectdefinition/receiveractivity.xml +++ b/shared/uavobjectdefinition/receiveractivity.xml @@ -7,9 +7,7 @@ - - - + diff --git a/shared/uavobjectdefinition/stabilizationdesired.xml b/shared/uavobjectdefinition/stabilizationdesired.xml index 00bd8958353..58f512a50d9 100644 --- a/shared/uavobjectdefinition/stabilizationdesired.xml +++ b/shared/uavobjectdefinition/stabilizationdesired.xml @@ -6,7 +6,7 @@ - + diff --git a/shared/uavobjectdefinition/stabilizationsettings.xml b/shared/uavobjectdefinition/stabilizationsettings.xml index f1e333c5b5c..966dd0efd02 100644 --- a/shared/uavobjectdefinition/stabilizationsettings.xml +++ b/shared/uavobjectdefinition/stabilizationsettings.xml @@ -7,15 +7,16 @@ + - - - + + + @@ -30,7 +31,7 @@ - + @@ -44,6 +45,8 @@ + + diff --git a/shared/uavobjectdefinition/systemalarms.xml b/shared/uavobjectdefinition/systemalarms.xml index f6d24ece97c..e59cc78f0f3 100644 --- a/shared/uavobjectdefinition/systemalarms.xml +++ b/shared/uavobjectdefinition/systemalarms.xml @@ -35,6 +35,7 @@ + diff --git a/shared/uavobjectdefinition/txpidsettings.xml b/shared/uavobjectdefinition/txpidsettings.xml index b4aeb9054ca..8521aa419f3 100644 --- a/shared/uavobjectdefinition/txpidsettings.xml +++ b/shared/uavobjectdefinition/txpidsettings.xml @@ -17,11 +17,13 @@ Roll Attitude.Kp, Pitch Attitude.Kp, Roll+Pitch Attitude.Kp, Yaw Attitude.Kp, Roll Attitude.Ki, Pitch Attitude.Ki, Roll+Pitch Attitude.Ki, Yaw Attitude.Ki, Roll Attitude.ILimit, Pitch Attitude.ILimit, Roll+Pitch Attitude.ILimit, Yaw Attitude.ILimit, - GyroTau, + GyroCutoff, Roll VbarSensitivity, Pitch VbarSensitivity, Roll+Pitch VbarSensitivity, Yaw VbarSensitivity, Roll Vbar.Kp, Pitch Vbar.Kp, Roll+Pitch Vbar.Kp, Yaw Vbar.Kp, Roll Vbar.Ki,Pitch Vbar.Ki, Roll+Pitch Vbar.Ki, Yaw Vbar.Ki, - Roll Vbar.Kd, Pitch Vbar.Kd, Roll+Pitch Vbar.Kd, Yaw Vbar.Kd" + Roll Vbar.Kd, Pitch Vbar.Kd, Roll+Pitch Vbar.Kd, Yaw Vbar.Kd, + Horizontal Pos.Kp, Horizontal Pos.Ki, Horizontal Pos.ILimit, + Horizontal Vel.Kp, Horizontal Vel.Ki, Horizontal Vel.Kd" defaultvalue="Disabled"/> diff --git a/shared/uavobjectdefinition/vtolpathfollowersettings.xml b/shared/uavobjectdefinition/vtolpathfollowersettings.xml index 0b97eeca804..5d4f8ea72fe 100644 --- a/shared/uavobjectdefinition/vtolpathfollowersettings.xml +++ b/shared/uavobjectdefinition/vtolpathfollowersettings.xml @@ -4,11 +4,11 @@ - + - + @@ -25,6 +25,16 @@ + + + + + + + + + + diff --git a/shared/uavobjectdefinition/watchdogstatus.xml b/shared/uavobjectdefinition/watchdogstatus.xml index 2c09abac837..4aae572daba 100644 --- a/shared/uavobjectdefinition/watchdogstatus.xml +++ b/shared/uavobjectdefinition/watchdogstatus.xml @@ -8,4 +8,4 @@ - \ No newline at end of file +